From d8631e66128c260e083b51a6da0786e8838c1b10 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Sat, 22 Jul 2023 14:15:29 +0200 Subject: [PATCH 01/71] scene an example scenes --- ...seratBeamFallingUnderTheEffectOfGravity.py | 76 +++++++++++++ examples/python3/PCS_Example1.py | 1 - examples/python3/__init__.py | 2 +- examples/python3/cosserat/cosseratObject.py | 58 +++++----- examples/python3/example1.py | 77 +++++++++++++ examples/python3/useful/header.py | 107 ++++++++++++++++++ 6 files changed, 288 insertions(+), 33 deletions(-) create mode 100644 examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py create mode 100644 examples/python3/example1.py create mode 100644 examples/python3/useful/header.py diff --git a/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py b/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py new file mode 100644 index 00000000..32b934ec --- /dev/null +++ b/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py @@ -0,0 +1,76 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "Yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +from useful.header import addHeader, addSolvers +from cosserat.cosseratObject import Cosserat +from dataclasses import dataclass + + +# [@info] ================ Unit: N, m, Kg, Pa ================ + +# @todo use this dataclass to create the cosserat object +@dataclass +class CableParameters: + youngModulus: float = 1.205e11 + poissonRatio: float = 0.499 + radius: float = 0.004 + density: float = 7.850e3 + maxDisplacement: float = 0.3 + + GI: float =1.5708 + GA: float =3.1416e4 + EI: float =0.7854 + EA: float =3.1416e4 + L: float = 1. # beam length in m + Rb: float = 0.02/2. # beam radius in m + +@dataclass +class CableGeometryParameters: + init_pos: list[float] # = [0., 0., 0.] + tot_length: float = 1. + nbSectionS: int = 5 + nbFramesF: int = 30 + buildCollisionModel: int = 0 + beamMass: float = 1. + + +YM = 1.0e8 +PR = 0.38 +rayleighStiffness = 1.e-3 # Nope +firstOrder = 1 +EI = 1.e2 +coeff = 1 + + + +# beam parameters +length = 1. # in m +Rb = 0.02/2. # beam radius in m + +geoParams = CableGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, + nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) +# inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, maxDisplacement=0.3, nbSections=20) +nonLinearConfig = {'init_pos': [0., 0., 0.], 'tot_length': length, 'nbSectionS': 5, + 'nbFramesF': 30, 'buildCollisionModel': 0, 'beamMass': 1.} +inertialParams = {'GI': 1.5708, 'GA': 3.1416e4, + 'EI': 0.7854, 'EA': 3.1416e4, 'L': length, 'Rb': Rb} + +isCollisionModel = 0 + +def createScene(rootNode): + addHeader(rootNode) + + node = rootNode.addChild('rootNode') + node.gravity = [0., -9.81, 0.] + node.addChild( + Cosserat(parent=node, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, + useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, + rayleighStiffness=rayleighStiffness)) \ No newline at end of file diff --git a/examples/python3/PCS_Example1.py b/examples/python3/PCS_Example1.py index 01e2070c..d8ab7dcf 100644 --- a/examples/python3/PCS_Example1.py +++ b/examples/python3/PCS_Example1.py @@ -11,7 +11,6 @@ import Sofa from cosserat.cosseratObject import Cosserat -from cosserat.nonLinearCosserat import NonLinearCosserat as nonCosserat from cosserat.usefulFunctions import buildEdges, pluginList, BuildCosseratGeometry from math import sqrt diff --git a/examples/python3/__init__.py b/examples/python3/__init__.py index f92d993f..cc00b39c 100644 --- a/examples/python3/__init__.py +++ b/examples/python3/__init__.py @@ -13,4 +13,4 @@ """ -__all__ = ["cosserat"] +__all__ = ["cosserat","useful"] diff --git a/examples/python3/cosserat/cosseratObject.py b/examples/python3/cosserat/cosseratObject.py index 734940ab..ae8ea527 100644 --- a/examples/python3/cosserat/cosseratObject.py +++ b/examples/python3/cosserat/cosseratObject.py @@ -3,33 +3,22 @@ Cosserat class in SofaPython3. """ -__authors__ = "younesssss" +__authors__ = "adagolodjo" __contact__ = "adagolodjo@protonmail.com" __version__ = "1.0.0" __copyright__ = "(c) 2021,Inria" __date__ = "October, 26 2021" -# from dataclasses import dataclass import Sofa from cosserat.usefulFunctions import buildEdges, pluginList, BuildCosseratGeometry -from splib3.numerics import Quat from cosserat.utils import addEdgeCollision, addPointsCollision cosserat_config = {'init_pos': [0., 0., 0.], 'tot_length': 6, 'nbSectionS': 6, 'nbFramesF': 12, 'buildCollisionModel': 1, 'beamMass': 0.22} -# @dataclass - - class Cosserat(Sofa.Prefab): - """ActuatedArm is a reusable sofa model of a S90 servo motor and the tripod actuation arm. - Parameters: - -parent: node where the ServoArm will be attached - - translation the position in space of the structure - - eulerRotation the orientation of the structure - - attachingTo (MechanicalObject) a rest shape force field will constraint the object - to follow arm position + """Cosserat beam prefab class. It is a prefab class that allow to create a cosserat beam in Sofa. Structure: Node : { name : 'Cosserat' @@ -76,7 +65,7 @@ def __init__(self, *args, **kwargs): self.radius = kwargs.get('radius', ) if self.parent.hasObject("EulerImplicitSolver") is False: - print('The code does not have parent EulerImplicite') + print('The code does not have parent EulerImplicit') self.solverNode = self.addSolverNode() else: self.solverNode = self.parent @@ -86,11 +75,11 @@ def __init__(self, *args, **kwargs): self.inertialParams = kwargs['inertialParams'] self.rigidBaseNode = self.addRigidBaseNode() - [positionS, curv_abs_inputS, longeurS, framesF, curv_abs_outputF, self.frames3D] = \ + [positionS, curv_abs_inputS, sectionsLength, framesF, curv_abs_outputF, self.frames3D] = \ BuildCosseratGeometry(self.cosseratGeometry) self.cosseratCoordinateNode = self.addCosseratCoordinate( - positionS, longeurS) + positionS, sectionsLength) self.cosseratFrame = self.addCosseratFrame( framesF, curv_abs_inputS, curv_abs_outputF) # print(f'=== > {curv_abs_inputS}') @@ -115,15 +104,16 @@ def addSlidingPoints(self): def addSlidingPointsWithContainer(self): slidingPoint = self.cosseratFrame.addChild('slidingPoint') - container = slidingPoint.addObject("PointSetTopologyContainer") - modifier = slidingPoint.addObject("PointSetTopologyModifier") + slidingPoint.addObject("PointSetTopologyContainer") + slidingPoint.addObject("PointSetTopologyModifier") slidingPoint.addObject('MechanicalObject', name="slidingPointMO", position=self.frames3D, showObject="1", showIndices="0") slidingPoint.addObject('IdentityMapping') return slidingPoint def addSolverNode(self): - solverNode = self.addChild('solverNode') + solverNode = self.parent + # solverNode = self.addChild('solverNode') solverNode.addObject('EulerImplicitSolver', rayleighStiffness="0.2", rayleighMass='0.1') solverNode.addObject('SparseLDLSolver', name='solver', @@ -166,24 +156,30 @@ def addCosseratCoordinate(self, bendingStates, listOfSectionsLength): rayleighStiffness=self.rayleighStiffness.value, lengthY=self.length_Y.value, lengthZ=self.length_Z.value) else: - GA = self.inertialParams['GA'] - GI = self.inertialParams['GI'] - EA = self.inertialParams['EA'] - EI = self.inertialParams['EI'] - print(f'{GA}') - cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, - length=listOfSectionsLength, radius=self.radius.value, useInertiaParams=True, - GI=GI, GA=GA, EI=EI, EA=EA, rayleighStiffness=self.rayleighStiffness.value, - lengthY=self.length_Y.value, lengthZ=self.length_Z.value) + self._extracted_from_addCosseratCoordinate_15( + cosseratCoordinateNode, listOfSectionsLength + ) return cosseratCoordinateNode + # TODO Rename this here and in `addCosseratCoordinate` + def _extracted_from_addCosseratCoordinate_15(self, cosseratCoordinateNode, listOfSectionsLength): + GA = self.inertialParams['GA'] + GI = self.inertialParams['GI'] + EA = self.inertialParams['EA'] + EI = self.inertialParams['EI'] + print(f'{GA}') + cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, + length=listOfSectionsLength, radius=self.radius.value, useInertiaParams=True, + GI=GI, GA=GA, EI=EI, EA=EA, rayleighStiffness=self.rayleighStiffness.value, + lengthY=self.length_Y.value, lengthZ=self.length_Z.value) + def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): cosseratInSofaFrameNode = self.rigidBaseNode.addChild( 'cosseratInSofaFrameNode') self.cosseratCoordinateNode.addChild(cosseratInSofaFrameNode) framesMO = cosseratInSofaFrameNode.addObject( - 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showObject=0, showObjectScale=0.1) + 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showObject=1, showObjectScale=0.1) if self.beamMass != 0.: cosseratInSofaFrameNode.addObject( 'UniformMass', totalMass=self.beamMass, showAxisSizeFactor='0') @@ -222,10 +218,10 @@ def createScene(rootNode): Cosserat(parent=solverNode, cosseratGeometry=cosserat_config, name="cosserat", radius=0.15)) # use this to add the collision if the beam will interact with another object - collisionModel = cosserat.addCollisionModel() + cosserat.addCollisionModel() # Attach a force at the beam tip, - # we can attach this force to non mechanical node thanks to the MechanicalMatrixMapper component + # we can attach this force to a non-mechanical node to control the beam in order to be able to drive it. beamFrame = cosserat.cosseratFrame beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-2, indices=12, force=[0., -100., 0., 0., 0., 0.]) diff --git a/examples/python3/example1.py b/examples/python3/example1.py new file mode 100644 index 00000000..45c3120f --- /dev/null +++ b/examples/python3/example1.py @@ -0,0 +1,77 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +import Sofa +from useful.header import addHeader, addSolvers +from cosserat.cosseratObject import Cosserat +from dataclasses import dataclass + + +# [@info] ================ Unit: N, m, Kg, Pa ================ + +@dataclass +class CableParameters: + youngModulus: float = 1.205e11 + poissonRatio: float = 0.499 + radius: float = 0.004 + density: float = 7.850e3 + maxDisplacement: float = 0.3 + + GI: float =1.5708 + GA: float =3.1416e4 + EI: float =0.7854 + EA: float =3.1416e4 + L: float = 1. # beam length in m + Rb: float = 0.02/2. # beam radius in m + + +@dataclass +class CableGeometryParameters: + init_pos: list[float] # = [0., 0., 0.] + tot_length: float = 1. + nbSectionS: int = 5 + nbFramesF: int = 30 + buildCollisionModel: int = 0 + beamMass: float = 1. + + +YM = 1.0e8 +PR = 0.38 +rayleighStiffness = 1.e-3 # Nope +firstOrder = 1 +EI = 1.e2 +coeff = 1 + + + +# beam parameters +length = 1. # in m +Rb = 0.02/2. # beam radius in m + +geoParams = CableGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, + nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) +# inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, maxDisplacement=0.3, nbSections=20) +nonLinearConfig = {'init_pos': [0., 0., 0.], 'tot_length': length, 'nbSectionS': 5, + 'nbFramesF': 30, 'buildCollisionModel': 0, 'beamMass': 1.} +inertialParams = {'GI': 1.5708, 'GA': 3.1416e4, + 'EI': 0.7854, 'EA': 3.1416e4, 'L': length, 'Rb': Rb} + +isCollisionModel = 0 + +def createScene(rootNode): + addHeader(rootNode) + + node = rootNode.addChild('rootNode') + # solverNode = addSolvers(node) + cosseratNode = node.addChild( + Cosserat(parent=node, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, + useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, + rayleighStiffness=rayleighStiffness)) \ No newline at end of file diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py new file mode 100644 index 00000000..e8844dec --- /dev/null +++ b/examples/python3/useful/header.py @@ -0,0 +1,107 @@ + +def addHeader(rootnode, multithreading=False, inverse=False, isConstrained=False): + """ + Adds to rootnode the default headers for a simulation with contact. Also adds and returns three nodes: + - Settings + - Modelling + - Simulation + + Args: + inverse: + isConstrained: + rootnode: + multithreading: + + Usage: + addHeader(rootnode) + + Returns: + the three SOFA nodes {settings, modelling, simulation} + """ + settings = rootnode.addChild('Settings') + settings.addObject('RequiredPlugin', pluginName=[ + "ArticulatedSystemPlugin", + "Cosserat", # Needed to use component RigidDistanceMapping + "Sofa.Component.AnimationLoop", # Needed to use components FreeMotionAnimationLoop + "Sofa.Component.Collision.Detection.Algorithm", + "Sofa.Component.Collision.Detection.Intersection", # Needed to use components LocalMinDistance + "Sofa.Component.Collision.Response.Contact", # Needed to use components RuleBasedContactManager + "Sofa.Component.Constraint.Lagrangian.Correction", # Needed to use components GenericConstraintCorrection + "Sofa.Component.Constraint.Lagrangian.Solver", # Needed to use components GenericConstraintSolver + "Sofa.Component.Constraint.Projective", # Needed to use components FixedConstraint + "Sofa.Component.IO.Mesh", # Needed to use components MeshOBJLoader, MeshSTLLoader + "Sofa.Component.Mass", # Needed to use components UniformMass + "Sofa.Component.Setting", # Needed to use components BackgroundSetting + "Sofa.Component.SolidMechanics.Spring", # Needed to use components RestShapeSpringsForceField + "Sofa.Component.Topology.Container.Constant", # Needed to use components MeshTopology + "Sofa.Component.Topology.Container.Dynamic", + # Needed to use components EdgeSetTopologyContainer, EdgeSetTopologyModifier, + # QuadSetTopologyContainer, QuadSetTopologyModifier + "Sofa.Component.Topology.Container.Grid", # Needed to use components RegularGridTopology + "Sofa.Component.Topology.Mapping", # Needed to use components Edge2QuadTopologicalMapping + "Sofa.Component.Visual", # Needed to use components VisualStyle + "Sofa.GL.Component.Rendering3D", # Needed to use components OglGrid, OglModel + "Sofa.GUI.Component", # Needed to use components AttachBodyButtonSetting + ]) + settings.addObject('BackgroundSetting', color=[1, 1, 1, 1]) + # settings.addObject('AttachBodyButtonSetting', stiffness=1e6) + + if isConstrained: + rootnode.addObject('VisualStyle') + rootnode.addObject('CollisionPipeline') + rootnode.addObject("DefaultVisualManagerLoop") + rootnode.addObject('RuleBasedContactManager', responseParams='mu=0.8', response='FrictionContactConstraint') + rootnode.addObject('BruteForceBroadPhase') + rootnode.addObject('BVHNarrowPhase') + rootnode.addObject('LocalMinDistance', alarmDistance=0.05, contactDistance=0.01) + rootnode.addObject('FreeMotionAnimationLoop', parallelCollisionDetectionAndFreeMotion=multithreading, parallelODESolving=multithreading) + if inverse: + settings.addObject('RequiredPlugin', name="SoftRobots.Inverse") + rootnode.addObject('QPInverseProblemSolver', name='ConstraintSolver', tolerance=1e-8, maxIterations=100, multithreading=multithreading, + epsilon=1) + else: + rootnode.addObject('GenericConstraintSolver', name='ConstraintSolver', tolerance=1e-8, maxIterations=100, multithreading=multithreading) + rootnode.dt = 0.01 + + modelling = rootnode.addChild('Modelling') + modelling.addChild('Topology') + simulation = rootnode.addChild('Simulation') + return settings, modelling, simulation + +def addSolvers(node, template='CompressedRowSparseMatrixd', rayleighMass=0., rayleighStiffness=0., firstOrder=False, + iterative=False): + """ + Adds solvers (EulerImplicitSolver, LDLSolver, GenericConstraintCorrection) to the given node. + + Args: + node: + template: for the LDLSolver + rayleighMass: + rayleighStiffness: + firstOrder: for the implicit scheme + iterative: iterative solver + + Usage: + addSolvers(node) + """ + node.addObject('RequiredPlugin', name='SofaPlugins', pluginName=['Sofa.Component.LinearSolver.Direct', + 'Sofa.Component.ODESolver.Backward']) + node.addObject('EulerImplicitSolver', firstOrder=firstOrder, rayleighStiffness=rayleighStiffness, rayleighMass=rayleighMass) + if iterative: + node.addObject('CGLinearSolver', name='Solver', template=template) + else: + node.addObject('SparseLDLSolver', name='Solver', template=template) + node.addObject('GenericConstraintCorrection', linearSolver=node.Solver.getLinkPath()) + + return node + + +# Test +def createScene(rootNode): + + addHeader(rootNode) + + node = rootNode.addChild('rootNode') + solverNode = addSolvers(node) + + From 60b41ffc2dcf9fd10c736cfd3478fb22c5607cda Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Tue, 25 Jul 2023 01:05:47 +0200 Subject: [PATCH 02/71] add some example scenes --- examples/python3/actuators/example1.py | 133 + .../python3/actuators/mesh/disqueBlender.mtl | 2 + .../python3/actuators/mesh/disqueBlender.obj | 5785 +++++++++++++++++ .../python3/actuators/mesh/disqueBlender2.mtl | 2 + .../python3/actuators/mesh/disqueBlender2.obj | 5785 +++++++++++++++++ examples/python3/cosserat/cosseratObject.py | 2 +- examples/python3/example1.py | 77 - examples/python3/useful/header.py | 7 +- examples/python3/useful/params.py | 27 + 9 files changed, 11739 insertions(+), 81 deletions(-) create mode 100644 examples/python3/actuators/example1.py create mode 100644 examples/python3/actuators/mesh/disqueBlender.mtl create mode 100644 examples/python3/actuators/mesh/disqueBlender.obj create mode 100644 examples/python3/actuators/mesh/disqueBlender2.mtl create mode 100644 examples/python3/actuators/mesh/disqueBlender2.obj delete mode 100644 examples/python3/example1.py create mode 100644 examples/python3/useful/params.py diff --git a/examples/python3/actuators/example1.py b/examples/python3/actuators/example1.py new file mode 100644 index 00000000..ae9d7751 --- /dev/null +++ b/examples/python3/actuators/example1.py @@ -0,0 +1,133 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + + +__authors__ = "Yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +from useful.header import addHeader +from useful.params import CableGeometryParameters +from cosserat.cosseratObject import Cosserat + +import os +from splib3.numerics.quat import Quat + +path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' + +# @info Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) +# et de 13 disques en iglidur. +# +# "-La colonne mesure 65.5 cm pour un diamètre de 6.2mm" +# +# -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g +# +# -Les disques sur la colonne sont espacés d'environ 4.7cm +# +# -Concernant les trous des disques, il y en a 3 sortes : +# +# les trous intérieurs sont au nombre de 3, ont un diamètre de 2mm et sont placés à environ 6mm du centre +# les trous intermédiaires sont au nombre de 3, ont un diamètre de 2.5mm et sont placés à environ 2cm du centre +# les trous extérieurs sont au nombre de 12, ont un diamètre de 1mm et sont placés à environ 2.3cm du centre +# -Enfin concernant le routage des câbles : +# +# Le manipulateur est constitué de 3 sections, chaque section est composé de 3 fils (disposés à 120° les uns des autres) +# Les câbles sont routés de manière parallèle +# La première section (celle du haut) ainsi que la deuxième (intermédiaire) sont constituées de 4 disques et la +# troisième (celle du bas) de 5 disques +# Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 +# passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. +# [@info] ================ Unit: N, cm, g, Pa ================ + + +YM = 1.0e8 +PR = 0.38 +rayleighStiffness = 1.e-3 # Nope +firstOrder = 1 +EI = 1.e2 +# coeff = 1. + +# beam parameters +length = 65.5 # in cm +Rb = 6.2e-1 / 2. # beam radius in cm + +# @todo use CableGeometryParameters & CableParameters in Cosserat class for both geometry and physics parameters +geoParams = CableGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, + nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) +# inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, +# maxDisplacement=0.3, nbSections=20) +nonLinearConfig = {'init_pos': [0., 0., 0.], 'tot_length': length, 'nbSectionS': 5, + 'nbFramesF': 30, 'buildCollisionModel': 0, 'beamMass': 1.} +inertialParams = {'GI': 1.5708, 'GA': 3.1416e4, + 'EI': 0.7854, 'EA': 3.1416e4, 'L': length, 'Rb': Rb} + +isCollisionModel = 0 + + +def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState"): + """ The intermediateRigid construction """ + if rigidCentral is None: + rigidCentral = [3, 0., 0, 0, 0, 0, 1] + q0 = Quat() + q1 = Quat() + q2 = Quat() + + interChildPos = [[0, 1.7, 1., q0[0], q0[1], q0[2], q0[3]], + [0, -1.7, 1., q1[0], q1[1], q1[2], q1[3]], + [0., 0., -2., q2[0], q2[1], q2[2], q2[3]]] + intermediateRigid = parent.addChild('intermediateRigid') + intermediateRigid.addObject('MechanicalObject', name=baseName, template='Rigid3d', + position=rigidCentral, showObject=True, showObjectScale=0.4) + intermediateRigid.addObject('RestShapeSpringsForceField', name='rigid', stiffness=1.e1, template="Rigid3d", + angularStiffness=1.e1, external_points=0, points=0) + """Create intermediate kids""" + interRigidChild = intermediateRigid.addChild('interRigidChild') + interRigidChild.addObject('MechanicalObject', name="interRigidChildMo", template='Rigid3d', + position=interChildPos, showObject=True, showObjectScale=0.4) + interRigidChild.addObject('RigidMapping', name="interRigidMap") + + + """ Add disk to the scene, actually this disk is only use for the visualisation """ + loadDisk(intermediateRigid) + + return intermediateRigid + +def loadDisk(parentNode): + #### MAPPING of the disks (here some torus) #### ########### + diskMapping = parentNode.addChild("diskMapping") + diskMapping.addObject("MeshOBJLoader", name="diskLoader", filename=f'{path}disqueBlender2.obj') + diskMapping.addObject("OglModel", name="Visual", src="@diskLoader", color="1.0 0.5 0.25 1.0") + diskMapping.addObject('RigidMapping', name="diskMap") + + +def createRigidDisk(rootNode): + diskSolverNode = rootNode.addChild('diskSolverNode') + diskSolverNode.addObject('EulerImplicitSolver', firstOrder=0, rayleighStiffness=0.01, rayleighMass=0.) + diskSolverNode.addObject('SparseLDLSolver', name='solver') + + for i in range(1, 14): + """ Create the rigid disk nodes """ + createIntermediateNode(diskSolverNode, rigidCentral=[i*(length/13.), 0., 0, 0, 0, 0, 1], baseName=f"rigidState{i}") + + # """ The intermediateRigid construction """ + # intermediateRigid = createIntermediateNode(diskSolverNode) + + +def createScene(rootNode): + addHeader(rootNode) + rootNode.gravity = [0., -9.81, 0.] + stemNode = rootNode.addChild('stemNode') + stemNode.addChild( + Cosserat(parent=stemNode, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, + useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, + rayleighStiffness=rayleighStiffness)) + + # create the rigid disk node + createRigidDisk(rootNode) + + + diff --git a/examples/python3/actuators/mesh/disqueBlender.mtl b/examples/python3/actuators/mesh/disqueBlender.mtl new file mode 100644 index 00000000..345c68b5 --- /dev/null +++ b/examples/python3/actuators/mesh/disqueBlender.mtl @@ -0,0 +1,2 @@ +# Blender 3.6.1 MTL File: 'None' +# www.blender.org diff --git a/examples/python3/actuators/mesh/disqueBlender.obj b/examples/python3/actuators/mesh/disqueBlender.obj new file mode 100644 index 00000000..8fde343f --- /dev/null +++ b/examples/python3/actuators/mesh/disqueBlender.obj @@ -0,0 +1,5785 @@ +# Blender 3.6.1 +# www.blender.org +mtllib disqueBlender.mtl +o disqueMeshLab +v 0.200000 0.310419 -2.659089 +v 0.200000 0.300000 -2.660000 +v 0.200000 0.454071 -2.805000 +v 0.200000 4.414655 -4.461996 +v 0.200000 4.494455 -4.142500 +v 0.200000 4.008525 -4.142500 +v 0.200000 5.055672 -1.745790 +v 0.200000 4.954826 -1.497823 +v 0.200000 4.745929 -1.617500 +v 0.200000 4.745929 -1.432500 +v 0.200000 0.245174 -1.497823 +v 0.200000 0.454071 -1.617500 +v 0.200000 0.454071 -1.432500 +v 0.200000 0.144328 -1.745790 +v 0.200000 0.120000 -1.962500 +v 0.200000 0.454071 -1.962500 +v 0.200000 1.437556 -4.925666 +v 0.200000 1.682845 -5.032864 +v 0.200000 1.745192 -4.688429 +v 0.200000 2.660777 -2.255317 +v 0.200000 2.719707 -2.271108 +v 0.200000 2.712500 -1.962500 +v 0.200000 2.662500 -4.491747 +v 0.200000 2.680349 -4.504245 +v 0.200000 2.712500 -4.503429 +v 0.200000 0.750488 -1.642753 +v 0.200000 0.744848 -1.621706 +v 0.200000 0.705545 -1.617500 +v 0.200000 4.457051 -1.600000 +v 0.200000 4.455152 -1.621706 +v 0.200000 4.494455 -1.617500 +v 0.200000 4.532770 -1.439581 +v 0.200000 4.535477 -1.429479 +v 0.200000 4.494455 -1.432500 +v 0.200000 2.664279 -3.276604 +v 0.200000 2.650000 -3.286602 +v 0.200000 2.712500 -3.495000 +v 0.200000 2.480293 -2.928893 +v 0.200000 2.523396 -3.135721 +v 0.200000 2.535721 -3.123396 +v 0.200000 2.634202 -3.293969 +v 0.200000 2.617365 -3.298481 +v 0.200000 2.520000 -3.495000 +v 0.200000 2.600000 -3.300000 +v 0.200000 2.582635 -3.298481 +v 0.200000 2.565798 -3.293969 +v 0.200000 2.550000 -3.286602 +v 0.200000 2.550000 -3.113397 +v 0.200000 2.565798 -3.106031 +v 0.200000 2.539223 -2.944683 +v 0.200000 2.582635 -3.101519 +v 0.200000 2.600000 -2.950000 +v 0.200000 2.600000 -3.100000 +v 0.200000 2.660777 -2.944683 +v 0.200000 2.617365 -3.101519 +v 0.200000 2.719707 -2.928893 +v 0.200000 2.634202 -3.106031 +v 0.200000 2.700000 -3.200000 +v 0.200000 2.698481 -3.217365 +v 0.200000 2.693969 -3.234202 +v 0.200000 2.686603 -3.250000 +v 0.200000 2.676605 -3.264279 +v 0.200000 2.650000 -3.113397 +v 0.200000 2.664279 -3.123396 +v 0.200000 2.676605 -3.135721 +v 0.200000 2.686603 -3.150000 +v 0.200000 2.693969 -3.165798 +v 0.200000 2.698481 -3.182635 +v 0.200000 2.535721 -3.276604 +v 0.200000 2.523396 -3.264279 +v 0.200000 2.487500 -3.495000 +v 0.200000 2.500000 -3.200000 +v 0.200000 2.501519 -3.182635 +v 0.200000 2.506031 -3.165798 +v 0.200000 2.513398 -3.150000 +v 0.200000 2.513398 -3.250000 +v 0.200000 2.506031 -3.234202 +v 0.200000 2.501519 -3.217365 +v 0.200000 4.531858 -1.450000 +v 0.200000 4.650947 -1.439581 +v 0.200000 4.651859 -1.450000 +v 0.200000 4.650947 -1.460419 +v 0.200000 4.648241 -1.470521 +v 0.200000 4.643820 -1.480000 +v 0.200000 4.637821 -1.488567 +v 0.200000 4.630426 -1.495963 +v 0.200000 4.621859 -1.501962 +v 0.200000 4.581439 -1.509089 +v 0.200000 4.571337 -1.506382 +v 0.200000 4.561859 -1.501962 +v 0.200000 4.553291 -1.495963 +v 0.200000 4.545896 -1.488567 +v 0.200000 4.539897 -1.480000 +v 0.200000 4.535477 -1.470521 +v 0.200000 4.532770 -1.460419 +v 0.200000 4.612380 -1.506382 +v 0.200000 4.602277 -1.509089 +v 0.200000 4.591859 -1.510000 +v 0.200000 4.545896 -1.411433 +v 0.200000 4.553291 -1.404037 +v 0.200000 4.494455 -1.029071 +v 0.200000 4.539897 -1.420000 +v 0.200000 4.561859 -1.398039 +v 0.200000 4.571337 -1.393618 +v 0.200000 4.581439 -1.390912 +v 0.200000 4.591859 -1.390000 +v 0.200000 4.602277 -1.390912 +v 0.200000 4.679582 -1.039443 +v 0.200000 4.637821 -1.411433 +v 0.200000 4.643820 -1.420000 +v 0.200000 4.648241 -1.429479 +v 0.200000 4.612380 -1.393618 +v 0.200000 4.621859 -1.398039 +v 0.200000 4.630426 -1.404037 +v 0.200000 0.660103 -1.480000 +v 0.200000 0.654104 -1.488567 +v 0.200000 0.562179 -1.488567 +v 0.200000 0.556180 -1.480000 +v 0.200000 0.551760 -1.470521 +v 0.200000 0.549053 -1.460419 +v 0.200000 0.548142 -1.450000 +v 0.200000 0.667230 -1.439581 +v 0.200000 0.668142 -1.450000 +v 0.200000 0.705545 -1.432500 +v 0.200000 0.667230 -1.460419 +v 0.200000 0.664523 -1.470521 +v 0.200000 0.646709 -1.495963 +v 0.200000 0.638142 -1.501962 +v 0.200000 0.628663 -1.506382 +v 0.200000 0.587620 -1.506382 +v 0.200000 0.578142 -1.501962 +v 0.200000 0.569574 -1.495963 +v 0.200000 0.618560 -1.509089 +v 0.200000 0.608142 -1.510000 +v 0.200000 0.597723 -1.509089 +v 0.200000 0.654104 -1.411433 +v 0.200000 0.660103 -1.420000 +v 0.200000 0.664523 -1.429479 +v 0.200000 0.556180 -1.420000 +v 0.200000 0.562179 -1.411433 +v 0.200000 0.520418 -1.039443 +v 0.200000 0.549053 -1.439581 +v 0.200000 0.551760 -1.429479 +v 0.200000 0.638142 -1.398039 +v 0.200000 0.646709 -1.404037 +v 0.200000 0.705545 -1.029071 +v 0.200000 0.569574 -1.404037 +v 0.200000 0.578142 -1.398039 +v 0.200000 0.587620 -1.393618 +v 0.200000 0.628663 -1.393618 +v 0.200000 0.597723 -1.390912 +v 0.200000 0.608142 -1.390000 +v 0.200000 0.618560 -1.390912 +v 0.200000 4.440304 -1.662500 +v 0.200000 4.427806 -1.680349 +v 0.200000 4.494455 -1.962500 +v 0.200000 4.449512 -1.642753 +v 0.200000 4.412399 -1.695756 +v 0.200000 4.394551 -1.708253 +v 0.200000 4.374804 -1.717462 +v 0.200000 4.353757 -1.723101 +v 0.200000 4.332051 -1.725000 +v 0.200000 4.008525 -1.962500 +v 0.200000 4.310345 -1.723101 +v 0.200000 4.289299 -1.717462 +v 0.200000 4.269551 -1.708253 +v 0.200000 4.251703 -1.695756 +v 0.200000 4.236295 -1.680349 +v 0.200000 4.223798 -1.662500 +v 0.200000 4.214590 -1.642753 +v 0.200000 4.008525 -1.617500 +v 0.200000 4.208950 -1.621706 +v 0.200000 4.207051 -1.600000 +v 0.200000 4.208950 -1.578294 +v 0.200000 4.214590 -1.557248 +v 0.200000 4.008525 -1.432500 +v 0.200000 4.223798 -1.537500 +v 0.200000 4.236295 -1.519652 +v 0.200000 4.374804 -1.482539 +v 0.200000 4.394551 -1.491747 +v 0.200000 4.412399 -1.504244 +v 0.200000 4.427806 -1.519652 +v 0.200000 4.440304 -1.537500 +v 0.200000 4.449512 -1.557248 +v 0.200000 4.455152 -1.578294 +v 0.200000 4.251703 -1.504244 +v 0.200000 4.269551 -1.491747 +v 0.200000 4.289299 -1.482539 +v 0.200000 4.310345 -1.476899 +v 0.200000 4.332051 -1.475000 +v 0.200000 4.353757 -1.476899 +v 0.200000 0.759696 -1.662500 +v 0.200000 0.985411 -1.642753 +v 0.200000 0.976202 -1.662500 +v 0.200000 1.191475 -1.962500 +v 0.200000 0.963705 -1.680349 +v 0.200000 0.948298 -1.695756 +v 0.200000 0.930449 -1.708253 +v 0.200000 0.705545 -1.962500 +v 0.200000 0.846243 -1.723101 +v 0.200000 0.825197 -1.717462 +v 0.200000 0.910702 -1.717462 +v 0.200000 0.889655 -1.723101 +v 0.200000 0.867949 -1.725000 +v 0.200000 0.805449 -1.708253 +v 0.200000 0.787601 -1.695756 +v 0.200000 0.772194 -1.680349 +v 0.200000 0.759696 -1.537500 +v 0.200000 0.772194 -1.519652 +v 0.200000 0.910702 -1.482539 +v 0.200000 0.930449 -1.491747 +v 0.200000 1.191475 -1.432500 +v 0.200000 0.985411 -1.557248 +v 0.200000 0.991050 -1.578294 +v 0.200000 1.191475 -1.617500 +v 0.200000 0.992949 -1.600000 +v 0.200000 0.991050 -1.621706 +v 0.200000 0.742949 -1.600000 +v 0.200000 0.744848 -1.578294 +v 0.200000 0.750488 -1.557248 +v 0.200000 0.948298 -1.504244 +v 0.200000 0.963705 -1.519652 +v 0.200000 0.976202 -1.537500 +v 0.200000 0.787601 -1.504244 +v 0.200000 0.805449 -1.491747 +v 0.200000 0.825197 -1.482539 +v 0.200000 0.846243 -1.476899 +v 0.200000 0.867949 -1.475000 +v 0.200000 0.889655 -1.476899 +v 0.200000 2.600000 -5.200000 +v 0.200000 2.600000 -4.960001 +v 0.200000 2.589581 -4.959089 +v 0.200000 2.537500 -4.708253 +v 0.200000 2.519652 -4.695756 +v 0.200000 2.579479 -4.843618 +v 0.200000 2.610419 -4.840911 +v 0.200000 2.620521 -4.843618 +v 0.200000 2.621706 -4.723101 +v 0.200000 2.570000 -4.848039 +v 0.200000 2.642753 -4.717462 +v 0.200000 2.630000 -4.951962 +v 0.200000 2.620521 -4.956382 +v 0.200000 2.733845 -5.196553 +v 0.200000 2.540912 -4.889581 +v 0.200000 2.543619 -4.879479 +v 0.200000 2.548038 -4.870000 +v 0.200000 2.466155 -5.196553 +v 0.200000 2.579479 -4.956382 +v 0.200000 2.570000 -4.951962 +v 0.200000 2.561433 -4.945962 +v 0.200000 2.554038 -4.938568 +v 0.200000 2.548038 -4.930000 +v 0.200000 2.554038 -4.861433 +v 0.200000 2.561433 -4.854038 +v 0.200000 2.600000 -4.840000 +v 0.200000 2.600000 -4.725000 +v 0.200000 2.589581 -4.840911 +v 0.200000 2.578294 -4.723101 +v 0.200000 2.557248 -4.717462 +v 0.200000 2.712500 -4.688429 +v 0.200000 2.695756 -4.680349 +v 0.200000 2.680349 -4.695756 +v 0.200000 2.638567 -4.854038 +v 0.200000 2.645963 -4.861433 +v 0.200000 2.651962 -4.870000 +v 0.200000 2.610419 -4.959089 +v 0.200000 2.543619 -4.920521 +v 0.200000 2.540912 -4.910419 +v 0.200000 2.540000 -4.900000 +v 0.200000 2.630000 -4.848039 +v 0.200000 2.662500 -4.708253 +v 0.200000 2.651962 -4.930000 +v 0.200000 2.645963 -4.938568 +v 0.200000 2.638567 -4.945962 +v 0.200000 2.660000 -4.900000 +v 0.200000 2.659089 -4.910419 +v 0.200000 2.656382 -4.920521 +v 0.200000 2.656382 -4.879479 +v 0.200000 2.659089 -4.889581 +v 0.200000 2.984808 -4.688429 +v 0.200000 2.717462 -4.642753 +v 0.200000 2.708253 -4.662500 +v 0.200000 2.723101 -4.578294 +v 0.200000 2.725000 -4.600000 +v 0.200000 2.723101 -4.621706 +v 0.200000 2.717462 -4.557248 +v 0.200000 2.984808 -4.503429 +v 0.200000 2.708253 -4.537500 +v 0.200000 2.695756 -4.519652 +v 0.200000 2.537500 -4.491747 +v 0.200000 2.557248 -4.482539 +v 0.200000 2.520000 -4.142500 +v 0.200000 2.578294 -4.476899 +v 0.200000 2.600000 -4.475000 +v 0.200000 2.712500 -4.142500 +v 0.200000 2.621706 -4.476899 +v 0.200000 2.642753 -4.482539 +v 0.200000 2.519652 -4.504245 +v 0.200000 2.520000 -4.503429 +v 0.200000 2.504245 -4.519652 +v 0.200000 2.487500 -4.503429 +v 0.200000 2.491747 -4.662500 +v 0.200000 2.482538 -4.642753 +v 0.200000 1.745192 -4.503429 +v 0.200000 2.482538 -4.557248 +v 0.200000 2.491747 -4.537500 +v 0.200000 2.476899 -4.621706 +v 0.200000 2.475000 -4.600000 +v 0.200000 2.476899 -4.578294 +v 0.200000 2.487500 -4.688429 +v 0.200000 2.504245 -4.680349 +v 0.200000 2.775000 -2.903109 +v 0.200000 2.984808 -3.495000 +v 0.200000 2.944683 -2.660777 +v 0.200000 2.928893 -2.719707 +v 0.200000 2.984808 -2.805000 +v 0.200000 2.903109 -2.775000 +v 0.200000 2.868116 -2.824976 +v 0.200000 2.824976 -2.868116 +v 0.200000 2.950000 -2.600000 +v 0.200000 2.984808 -2.470000 +v 0.200000 2.944683 -2.539223 +v 0.200000 2.984808 -1.962500 +v 0.200000 2.775000 -2.296891 +v 0.200000 2.824976 -2.331885 +v 0.200000 2.868116 -2.375025 +v 0.200000 2.903109 -2.425000 +v 0.200000 2.928893 -2.480293 +v 0.200000 2.600000 -2.250000 +v 0.200000 2.520000 -1.962500 +v 0.200000 2.539223 -2.255317 +v 0.200000 2.487500 -1.962500 +v 0.200000 2.487352 -2.268624 +v 0.200000 2.063020 -2.398481 +v 0.200000 2.046183 -2.393969 +v 0.200000 1.745192 -2.470000 +v 0.200000 2.156989 -2.364279 +v 0.200000 2.144664 -2.376605 +v 0.200000 2.271108 -2.480293 +v 0.200000 2.130385 -2.386603 +v 0.200000 2.114587 -2.393969 +v 0.200000 2.097750 -2.398481 +v 0.200000 2.080385 -2.400000 +v 0.200000 2.030385 -2.386603 +v 0.200000 2.016106 -2.376605 +v 0.200000 2.003780 -2.364279 +v 0.200000 1.993782 -2.350000 +v 0.200000 1.986416 -2.334202 +v 0.200000 1.981904 -2.317365 +v 0.200000 1.745192 -1.962500 +v 0.200000 1.993782 -2.250000 +v 0.200000 2.003780 -2.235721 +v 0.200000 2.144664 -2.223396 +v 0.200000 2.130385 -2.213398 +v 0.200000 2.114587 -2.206031 +v 0.200000 2.016106 -2.223396 +v 0.200000 2.030385 -2.213398 +v 0.200000 2.046183 -2.206031 +v 0.200000 1.980385 -2.300000 +v 0.200000 1.981904 -2.282635 +v 0.200000 1.986416 -2.265798 +v 0.200000 2.063020 -2.201519 +v 0.200000 2.080385 -2.200000 +v 0.200000 2.097750 -2.201519 +v 0.200000 2.156989 -2.235721 +v 0.200000 2.166987 -2.250000 +v 0.200000 2.174354 -2.265798 +v 0.200000 2.178866 -2.282635 +v 0.200000 2.166987 -2.350000 +v 0.200000 2.296891 -2.425000 +v 0.200000 2.174354 -2.334202 +v 0.200000 2.331885 -2.375025 +v 0.200000 2.178866 -2.317365 +v 0.200000 2.375025 -2.331885 +v 0.200000 2.180385 -2.300000 +v 0.200000 2.425000 -2.296891 +v 0.200000 2.480293 -2.271108 +v 0.200000 2.375025 -2.868116 +v 0.200000 2.331885 -2.824976 +v 0.200000 1.745192 -2.805000 +v 0.200000 2.296891 -2.775000 +v 0.200000 2.271108 -2.719707 +v 0.200000 2.255317 -2.660777 +v 0.200000 2.250000 -2.600000 +v 0.200000 2.255317 -2.539223 +v 0.200000 1.745192 -3.495000 +v 0.200000 2.425000 -2.903109 +v 0.200000 1.937855 -5.114272 +v 0.200000 2.199885 -5.169029 +v 0.200000 1.204590 -4.793817 +v 0.200000 1.191475 -4.688429 +v 0.200000 0.986415 -4.638711 +v 0.200000 1.191475 -4.503429 +v 0.200000 0.785345 -4.461996 +v 0.200000 0.618560 -3.690912 +v 0.200000 0.628663 -3.693619 +v 0.200000 0.705545 -3.495000 +v 0.200000 0.667230 -3.760419 +v 0.200000 0.664523 -3.770521 +v 0.200000 0.705545 -4.142500 +v 0.200000 0.587620 -3.806382 +v 0.200000 0.442840 -4.051434 +v 0.200000 0.597723 -3.809088 +v 0.200000 0.603511 -4.265543 +v 0.200000 0.608142 -3.810000 +v 0.200000 0.578142 -3.698039 +v 0.200000 0.587620 -3.693619 +v 0.200000 0.454071 -3.495000 +v 0.200000 0.597723 -3.690912 +v 0.200000 0.608142 -3.690000 +v 0.200000 0.668142 -3.750000 +v 0.200000 0.578142 -3.801962 +v 0.200000 0.569574 -3.795963 +v 0.200000 0.562179 -3.788567 +v 0.200000 0.556180 -3.780000 +v 0.200000 0.551760 -3.770521 +v 0.200000 0.549053 -3.760419 +v 0.200000 0.556180 -3.720000 +v 0.200000 0.562179 -3.711433 +v 0.200000 0.569574 -3.704037 +v 0.200000 0.638142 -3.698039 +v 0.200000 0.646709 -3.704037 +v 0.200000 0.654104 -3.711433 +v 0.200000 0.660103 -3.780000 +v 0.200000 0.654104 -3.788567 +v 0.200000 0.646709 -3.795963 +v 0.200000 0.638142 -3.801962 +v 0.200000 0.628663 -3.806382 +v 0.200000 0.618560 -3.809088 +v 0.200000 0.548142 -3.750000 +v 0.200000 0.549053 -3.739581 +v 0.200000 0.551760 -3.729479 +v 0.200000 0.660103 -3.720000 +v 0.200000 0.664523 -3.729479 +v 0.200000 0.667230 -3.739581 +v 0.200000 0.305035 -3.821939 +v 0.200000 0.191558 -3.579493 +v 0.200000 0.120000 -2.470000 +v 0.200000 0.007755 -2.800656 +v 0.200000 0.120000 -2.805000 +v 0.200000 0.042125 -3.066130 +v 0.200000 0.103610 -3.326663 +v 0.200000 0.069513 -2.002812 +v 0.200000 0.021521 -2.266165 +v 0.200000 0.000862 -2.533056 +v 0.200000 0.370982 -1.261539 +v 0.200000 1.809302 -0.123148 +v 0.200000 1.558820 -0.217576 +v 0.200000 1.745192 -0.454071 +v 0.200000 1.319375 -0.337258 +v 0.200000 1.191475 -0.454071 +v 0.200000 1.093505 -0.480926 +v 0.200000 1.191475 -1.029071 +v 0.200000 0.883605 -0.647057 +v 0.200000 0.691898 -0.833889 +v 0.200000 2.561433 -0.254037 +v 0.200000 2.570000 -0.248039 +v 0.200000 2.519851 -0.001236 +v 0.200000 2.589581 -0.359089 +v 0.200000 2.579479 -0.356382 +v 0.200000 2.520000 -0.454071 +v 0.200000 2.570000 -0.351961 +v 0.200000 2.600000 -0.240000 +v 0.200000 2.600000 -0.000000 +v 0.200000 2.589581 -0.240912 +v 0.200000 2.579479 -0.243619 +v 0.200000 2.630000 -0.351961 +v 0.200000 2.620521 -0.356382 +v 0.200000 2.712500 -0.454071 +v 0.200000 2.610419 -0.359089 +v 0.200000 2.600000 -0.360000 +v 0.200000 2.610419 -0.240912 +v 0.200000 2.620521 -0.243619 +v 0.200000 2.867335 -0.013780 +v 0.200000 2.630000 -0.248039 +v 0.200000 2.561433 -0.345963 +v 0.200000 2.554038 -0.338567 +v 0.200000 2.548038 -0.330000 +v 0.200000 2.540912 -0.289581 +v 0.200000 2.543619 -0.279479 +v 0.200000 2.659089 -0.310419 +v 0.200000 2.656382 -0.320521 +v 0.200000 2.651962 -0.330000 +v 0.200000 2.548038 -0.270000 +v 0.200000 2.554038 -0.261433 +v 0.200000 2.645963 -0.338567 +v 0.200000 2.638567 -0.345963 +v 0.200000 2.543619 -0.320521 +v 0.200000 2.540912 -0.310419 +v 0.200000 2.540000 -0.300000 +v 0.200000 2.638567 -0.254037 +v 0.200000 2.645963 -0.261433 +v 0.200000 2.651962 -0.270000 +v 0.200000 2.068165 -0.054975 +v 0.200000 2.487500 -0.454071 +v 0.200000 2.332665 -0.013780 +v 0.200000 2.656382 -0.279479 +v 0.200000 2.659089 -0.289581 +v 0.200000 2.660000 -0.300000 +v 0.200000 3.641180 -0.217576 +v 0.200000 3.390699 -0.123148 +v 0.200000 3.454808 -0.454071 +v 0.200000 3.131835 -0.054975 +v 0.200000 2.984808 -0.454071 +v 0.200000 3.880625 -0.337258 +v 0.200000 4.008525 -0.454071 +v 0.200000 4.106495 -0.480926 +v 0.200000 4.316396 -0.647057 +v 0.200000 4.008525 -1.029071 +v 0.200000 4.508102 -0.833889 +v 0.200000 4.829018 -1.261539 +v 0.200000 4.840911 -2.610419 +v 0.200000 4.840000 -2.600000 +v 0.200000 4.745929 -2.470000 +v 0.200000 4.900000 -2.660000 +v 0.200000 4.889581 -2.659089 +v 0.200000 4.745929 -2.805000 +v 0.200000 4.861433 -2.645963 +v 0.200000 4.854038 -2.638567 +v 0.200000 4.848039 -2.630000 +v 0.200000 4.843618 -2.620521 +v 0.200000 4.879479 -2.656382 +v 0.200000 4.870000 -2.651962 +v 0.200000 4.938568 -2.645963 +v 0.200000 5.157875 -3.066130 +v 0.200000 4.945962 -2.638567 +v 0.200000 5.192245 -2.800656 +v 0.200000 4.951962 -2.630000 +v 0.200000 5.199138 -2.533056 +v 0.200000 4.959089 -2.610419 +v 0.200000 4.956382 -2.620521 +v 0.200000 4.930000 -2.651962 +v 0.200000 4.920521 -2.656382 +v 0.200000 4.910419 -2.659089 +v 0.200000 4.840911 -2.589581 +v 0.200000 4.843618 -2.579479 +v 0.200000 4.848039 -2.570000 +v 0.200000 4.951962 -2.570000 +v 0.200000 4.956382 -2.579479 +v 0.200000 4.959089 -2.589581 +v 0.200000 4.960001 -2.600000 +v 0.200000 4.945962 -2.561433 +v 0.200000 5.178479 -2.266165 +v 0.200000 4.938568 -2.554038 +v 0.200000 4.854038 -2.561433 +v 0.200000 4.861433 -2.554038 +v 0.200000 4.870000 -2.548038 +v 0.200000 4.910419 -2.540912 +v 0.200000 4.920521 -2.543619 +v 0.200000 4.930000 -2.548038 +v 0.200000 4.879479 -2.543619 +v 0.200000 4.889581 -2.540912 +v 0.200000 4.900000 -2.540000 +v 0.200000 5.096390 -3.326663 +v 0.200000 5.008442 -3.579493 +v 0.200000 4.745929 -3.495000 +v 0.200000 4.757160 -4.051434 +v 0.200000 4.894965 -3.821939 +v 0.200000 4.596489 -4.265543 +v 0.200000 4.591859 -3.810000 +v 0.200000 4.581439 -3.809088 +v 0.200000 4.535477 -3.770521 +v 0.200000 4.532770 -3.760419 +v 0.200000 4.535477 -3.729479 +v 0.200000 4.494455 -3.495000 +v 0.200000 4.532770 -3.739581 +v 0.200000 4.531858 -3.750000 +v 0.200000 4.571337 -3.806382 +v 0.200000 4.561859 -3.801962 +v 0.200000 4.553291 -3.795963 +v 0.200000 4.545896 -3.788567 +v 0.200000 4.539897 -3.780000 +v 0.200000 4.539897 -3.720000 +v 0.200000 4.545896 -3.711433 +v 0.200000 4.553291 -3.704037 +v 0.200000 4.602277 -3.690912 +v 0.200000 4.591859 -3.690000 +v 0.200000 4.581439 -3.690912 +v 0.200000 4.561859 -3.698039 +v 0.200000 4.571337 -3.693619 +v 0.200000 4.612380 -3.693619 +v 0.200000 4.621859 -3.698039 +v 0.200000 4.630426 -3.704037 +v 0.200000 4.637821 -3.711433 +v 0.200000 4.643820 -3.720000 +v 0.200000 4.648241 -3.729479 +v 0.200000 4.648241 -3.770521 +v 0.200000 4.643820 -3.780000 +v 0.200000 4.637821 -3.788567 +v 0.200000 4.630426 -3.795963 +v 0.200000 4.621859 -3.801962 +v 0.200000 4.612380 -3.806382 +v 0.200000 4.602277 -3.809088 +v 0.200000 4.650947 -3.739581 +v 0.200000 4.651859 -3.750000 +v 0.200000 4.650947 -3.760419 +v 0.200000 3.995410 -4.793817 +v 0.200000 4.008525 -4.688429 +v 0.200000 3.762444 -4.925666 +v 0.200000 3.454808 -4.688429 +v 0.200000 3.000116 -5.169029 +v 0.200000 3.262145 -5.114272 +v 0.200000 3.517155 -5.032864 +v 0.200000 5.130487 -2.002812 +v 0.200000 4.745929 -1.962500 +v 0.200000 3.729479 -4.648241 +v 0.200000 3.720000 -4.643820 +v 0.200000 3.720000 -4.539897 +v 0.200000 3.729479 -4.535477 +v 0.200000 3.454808 -4.503429 +v 0.200000 3.788567 -4.545896 +v 0.200000 4.008525 -4.503429 +v 0.200000 3.780000 -4.539897 +v 0.200000 3.770521 -4.535477 +v 0.200000 3.780000 -4.643820 +v 0.200000 3.770521 -4.648241 +v 0.200000 3.739581 -4.532770 +v 0.200000 3.750000 -4.531858 +v 0.200000 3.760419 -4.532770 +v 0.200000 3.760419 -4.650947 +v 0.200000 3.750000 -4.651859 +v 0.200000 3.739581 -4.650947 +v 0.200000 3.698039 -4.621859 +v 0.200000 3.693619 -4.612380 +v 0.200000 3.795963 -4.553291 +v 0.200000 3.801962 -4.561859 +v 0.200000 3.806382 -4.571337 +v 0.200000 3.806382 -4.612380 +v 0.200000 3.801962 -4.621859 +v 0.200000 3.711433 -4.637821 +v 0.200000 3.704037 -4.630426 +v 0.200000 3.690912 -4.602277 +v 0.200000 3.690000 -4.591859 +v 0.200000 3.690912 -4.581439 +v 0.200000 3.693619 -4.571337 +v 0.200000 3.698039 -4.561859 +v 0.200000 3.704037 -4.553291 +v 0.200000 3.711433 -4.545896 +v 0.200000 3.809088 -4.581439 +v 0.200000 3.810000 -4.591859 +v 0.200000 3.809088 -4.602277 +v 0.200000 3.795963 -4.630426 +v 0.200000 3.788567 -4.637821 +v 0.200000 4.494455 -2.805000 +v 0.200000 4.008525 -3.495000 +v 0.200000 4.008525 -2.805000 +v 0.200000 3.454808 -3.495000 +v 0.200000 3.454808 -2.805000 +v 0.200000 4.494455 -2.470000 +v 0.200000 4.008525 -2.470000 +v 0.200000 3.454808 -2.470000 +v 0.200000 3.454808 -1.962500 +v 0.200000 3.729479 -0.664523 +v 0.200000 3.720000 -0.660103 +v 0.200000 3.454808 -1.029071 +v 0.200000 3.693619 -0.628663 +v 0.200000 3.690912 -0.618560 +v 0.200000 3.711433 -0.654104 +v 0.200000 3.704037 -0.646709 +v 0.200000 3.698039 -0.638142 +v 0.200000 3.690000 -0.608142 +v 0.200000 3.690912 -0.597723 +v 0.200000 3.693619 -0.587620 +v 0.200000 3.729479 -0.551760 +v 0.200000 3.720000 -0.556180 +v 0.200000 3.711433 -0.562179 +v 0.200000 3.698039 -0.578142 +v 0.200000 3.704037 -0.569574 +v 0.200000 3.801962 -0.638142 +v 0.200000 3.795963 -0.646709 +v 0.200000 3.739581 -0.549053 +v 0.200000 3.750000 -0.548142 +v 0.200000 3.760419 -0.549053 +v 0.200000 3.770521 -0.551760 +v 0.200000 3.780000 -0.556180 +v 0.200000 3.788567 -0.562179 +v 0.200000 3.795963 -0.569574 +v 0.200000 3.801962 -0.578142 +v 0.200000 3.806382 -0.587620 +v 0.200000 3.809088 -0.597723 +v 0.200000 3.810000 -0.608142 +v 0.200000 3.809088 -0.618560 +v 0.200000 3.806382 -0.628663 +v 0.200000 3.788567 -0.654104 +v 0.200000 3.780000 -0.660103 +v 0.200000 3.770521 -0.664523 +v 0.200000 3.760419 -0.667230 +v 0.200000 3.750000 -0.668142 +v 0.200000 3.739581 -0.667230 +v 0.200000 3.025646 -2.334202 +v 0.200000 3.033013 -2.350000 +v 0.200000 3.043011 -2.364279 +v 0.200000 3.119615 -2.400000 +v 0.200000 3.102251 -2.398481 +v 0.200000 3.085413 -2.393969 +v 0.200000 3.218096 -2.317365 +v 0.200000 3.213585 -2.334202 +v 0.200000 3.069615 -2.386603 +v 0.200000 3.055337 -2.376605 +v 0.200000 3.021135 -2.317365 +v 0.200000 3.019615 -2.300000 +v 0.200000 3.021135 -2.282635 +v 0.200000 3.025646 -2.265798 +v 0.200000 3.033013 -2.250000 +v 0.200000 3.043011 -2.235721 +v 0.200000 3.055337 -2.223396 +v 0.200000 3.069615 -2.213398 +v 0.200000 3.085413 -2.206031 +v 0.200000 3.102251 -2.201519 +v 0.200000 3.119615 -2.200000 +v 0.200000 3.136980 -2.201519 +v 0.200000 3.153817 -2.206031 +v 0.200000 3.169616 -2.213398 +v 0.200000 3.183894 -2.223396 +v 0.200000 3.196220 -2.235721 +v 0.200000 3.206218 -2.250000 +v 0.200000 3.206218 -2.350000 +v 0.200000 3.196220 -2.364279 +v 0.200000 3.183894 -2.376605 +v 0.200000 3.169616 -2.386603 +v 0.200000 3.153817 -2.393969 +v 0.200000 3.136980 -2.398481 +v 0.200000 3.213585 -2.265798 +v 0.200000 3.218096 -2.282635 +v 0.200000 3.219615 -2.300000 +v 0.200000 4.213585 -4.638711 +v 0.200000 3.454808 -4.142500 +v 0.200000 2.984808 -4.142500 +v 0.200000 2.984808 -1.029071 +v 0.200000 2.712500 -1.029071 +v 0.200000 2.520000 -1.029071 +v 0.200000 2.487500 -1.029071 +v 0.200000 1.745192 -1.029071 +v 0.200000 1.460419 -4.650947 +v 0.200000 1.450000 -4.651859 +v 0.200000 1.429479 -4.648241 +v 0.200000 1.420000 -4.643820 +v 0.200000 1.439581 -4.650947 +v 0.200000 1.411433 -4.637821 +v 0.200000 1.404037 -4.630426 +v 0.200000 1.398039 -4.621859 +v 0.200000 1.404037 -4.553291 +v 0.200000 1.411433 -4.545896 +v 0.200000 1.420000 -4.539897 +v 0.200000 1.429479 -4.535477 +v 0.200000 1.460419 -4.532770 +v 0.200000 1.450000 -4.531858 +v 0.200000 1.439581 -4.532770 +v 0.200000 1.470521 -4.535477 +v 0.200000 1.480000 -4.539897 +v 0.200000 1.488567 -4.545896 +v 0.200000 1.390912 -4.581439 +v 0.200000 1.393618 -4.571337 +v 0.200000 1.398039 -4.561859 +v 0.200000 1.488567 -4.637821 +v 0.200000 1.480000 -4.643820 +v 0.200000 1.470521 -4.648241 +v 0.200000 1.393618 -4.612380 +v 0.200000 1.390912 -4.602277 +v 0.200000 1.390000 -4.591859 +v 0.200000 1.495963 -4.553291 +v 0.200000 1.501962 -4.561859 +v 0.200000 1.506382 -4.571337 +v 0.200000 1.506382 -4.612380 +v 0.200000 1.501962 -4.621859 +v 0.200000 1.495963 -4.630426 +v 0.200000 1.509089 -4.581439 +v 0.200000 1.510000 -4.591859 +v 0.200000 1.509089 -4.602277 +v 0.200000 2.487500 -4.142500 +v 0.200000 1.745192 -4.142500 +v 0.200000 1.191475 -4.142500 +v 0.200000 3.454808 -1.617500 +v 0.200000 2.984808 -1.617500 +v 0.200000 2.712500 -1.617500 +v 0.200000 2.520000 -1.617500 +v 0.200000 2.487500 -1.617500 +v 0.200000 1.745192 -1.617500 +v 0.200000 3.454808 -1.432500 +v 0.200000 2.984808 -1.432500 +v 0.200000 2.712500 -1.432500 +v 0.200000 2.520000 -1.432500 +v 0.200000 2.487500 -1.432500 +v 0.200000 1.745192 -1.432500 +v 0.200000 1.439581 -0.667230 +v 0.200000 1.429479 -0.664523 +v 0.200000 1.420000 -0.660103 +v 0.200000 1.411433 -0.654104 +v 0.200000 1.404037 -0.646709 +v 0.200000 1.411433 -0.562179 +v 0.200000 1.420000 -0.556180 +v 0.200000 1.429479 -0.551760 +v 0.200000 1.390912 -0.618560 +v 0.200000 1.393618 -0.628663 +v 0.200000 1.398039 -0.638142 +v 0.200000 1.390000 -0.608142 +v 0.200000 1.390912 -0.597723 +v 0.200000 1.393618 -0.587620 +v 0.200000 1.501962 -0.638142 +v 0.200000 1.495963 -0.646709 +v 0.200000 1.488567 -0.654104 +v 0.200000 1.480000 -0.660103 +v 0.200000 1.398039 -0.578142 +v 0.200000 1.404037 -0.569574 +v 0.200000 1.470521 -0.551760 +v 0.200000 1.480000 -0.556180 +v 0.200000 1.488567 -0.562179 +v 0.200000 1.495963 -0.569574 +v 0.200000 1.470521 -0.664523 +v 0.200000 1.460419 -0.667230 +v 0.200000 1.450000 -0.668142 +v 0.200000 1.439581 -0.549053 +v 0.200000 1.450000 -0.548142 +v 0.200000 1.460419 -0.549053 +v 0.200000 1.501962 -0.578142 +v 0.200000 1.506382 -0.587620 +v 0.200000 1.509089 -0.597723 +v 0.200000 1.510000 -0.608142 +v 0.200000 1.509089 -0.618560 +v 0.200000 1.506382 -0.628663 +v 0.200000 1.191475 -3.495000 +v 0.200000 1.191475 -2.805000 +v 0.200000 0.705545 -2.805000 +v 0.200000 1.191475 -2.470000 +v 0.200000 0.705545 -2.470000 +v 0.200000 0.454071 -2.470000 +v 0.200000 0.240000 -2.600000 +v 0.200000 0.240911 -2.610419 +v 0.200000 0.243618 -2.620521 +v 0.200000 0.248039 -2.630000 +v 0.200000 0.289581 -2.659089 +v 0.200000 0.279479 -2.656382 +v 0.200000 0.270000 -2.651962 +v 0.200000 0.351961 -2.570000 +v 0.200000 0.356382 -2.579479 +v 0.200000 0.345963 -2.638567 +v 0.200000 0.351961 -2.630000 +v 0.200000 0.356382 -2.620521 +v 0.200000 0.320521 -2.656382 +v 0.200000 0.261433 -2.645963 +v 0.200000 0.254037 -2.638567 +v 0.200000 0.240911 -2.589581 +v 0.200000 0.243618 -2.579479 +v 0.200000 0.248039 -2.570000 +v 0.200000 0.359089 -2.589581 +v 0.200000 0.360000 -2.600000 +v 0.200000 0.359089 -2.610419 +v 0.200000 0.254037 -2.561433 +v 0.200000 0.261433 -2.554038 +v 0.200000 0.270000 -2.548038 +v 0.200000 0.310419 -2.540912 +v 0.200000 0.320521 -2.543619 +v 0.200000 0.330000 -2.548038 +v 0.200000 0.338567 -2.645963 +v 0.200000 0.330000 -2.651962 +v 0.200000 0.338567 -2.554038 +v 0.200000 0.345963 -2.561433 +v 0.200000 0.279479 -2.543619 +v 0.200000 0.289581 -2.540912 +v 0.200000 0.300000 -2.540000 +v 0.000000 3.454808 -2.470000 +v 0.000000 3.454808 -1.962500 +v 0.000000 4.008525 -1.962500 +v 0.000000 2.984808 -2.805000 +v 0.000000 2.984808 -2.470000 +v -0.000000 0.144328 -1.745790 +v -0.000000 0.120000 -1.962500 +v -0.000000 0.069513 -2.002812 +v -0.000000 0.245174 -1.497823 +v -0.000000 0.454071 -1.432500 +v -0.000000 0.454071 -1.617500 +v 0.000000 1.558820 -0.217576 +v 0.000000 1.809302 -0.123148 +v 0.000000 1.745192 -0.454071 +v 0.000000 2.610419 -0.240912 +v 0.000000 2.600000 -0.240000 +v 0.000000 2.600000 -0.000000 +v 0.000000 4.679582 -1.039443 +v 0.000000 4.494455 -1.029071 +v 0.000000 4.508102 -0.833889 +v 0.000000 4.954826 -1.497823 +v 0.000000 4.745929 -1.617500 +v 0.000000 4.745929 -1.432500 +v 0.000000 5.055672 -1.745790 +v 0.000000 5.130487 -2.002812 +v 0.000000 4.745929 -1.962500 +v 0.000000 5.096390 -3.326663 +v 0.000000 5.008442 -3.579493 +v 0.000000 4.745929 -3.495000 +v -0.000000 2.296891 -2.775000 +v -0.000000 2.331885 -2.824976 +v -0.000000 1.745192 -2.805000 +v 0.000000 4.449512 -1.642753 +v 0.000000 4.455152 -1.621706 +v 0.000000 4.494455 -1.617500 +v -0.000000 2.634202 -3.293969 +v -0.000000 2.650000 -3.286602 +v -0.000000 2.712500 -3.495000 +v -0.000000 2.664279 -3.276604 +v -0.000000 2.676605 -3.264279 +v -0.000000 2.523396 -3.135721 +v -0.000000 2.480293 -2.928893 +v -0.000000 2.535721 -3.123396 +v -0.000000 2.550000 -3.113397 +v -0.000000 2.565798 -3.293969 +v -0.000000 2.520000 -3.495000 +v -0.000000 2.550000 -3.286602 +v -0.000000 2.535721 -3.276604 +v -0.000000 2.582635 -3.298481 +v -0.000000 2.600000 -3.300000 +v -0.000000 2.617365 -3.298481 +v -0.000000 2.719707 -2.928893 +v -0.000000 2.650000 -3.113397 +v -0.000000 2.634202 -3.106031 +v -0.000000 2.660777 -2.944683 +v -0.000000 2.617365 -3.101519 +v -0.000000 2.600000 -2.950000 +v -0.000000 2.600000 -3.100000 +v -0.000000 2.539223 -2.944683 +v -0.000000 2.582635 -3.101519 +v -0.000000 2.565798 -3.106031 +v -0.000000 2.686603 -3.250000 +v -0.000000 2.693969 -3.234202 +v -0.000000 2.698481 -3.217365 +v -0.000000 2.700000 -3.200000 +v -0.000000 2.698481 -3.182635 +v -0.000000 2.693969 -3.165798 +v -0.000000 2.686603 -3.150000 +v -0.000000 2.676605 -3.135721 +v -0.000000 2.664279 -3.123396 +v -0.000000 2.487500 -3.495000 +v -0.000000 2.513398 -3.250000 +v -0.000000 2.523396 -3.264279 +v -0.000000 2.513398 -3.150000 +v -0.000000 2.506031 -3.165798 +v -0.000000 2.501519 -3.182635 +v -0.000000 2.500000 -3.200000 +v -0.000000 2.501519 -3.217365 +v -0.000000 2.506031 -3.234202 +v 0.000000 4.532770 -1.439581 +v 0.000000 4.531858 -1.450000 +v 0.000000 4.494455 -1.432500 +v 0.000000 4.532770 -1.460419 +v 0.000000 4.535477 -1.470521 +v 0.000000 4.539897 -1.480000 +v 0.000000 4.545896 -1.488567 +v 0.000000 4.553291 -1.495963 +v 0.000000 4.561859 -1.501962 +v 0.000000 4.571337 -1.506382 +v 0.000000 4.581439 -1.509089 +v 0.000000 4.591859 -1.510000 +v 0.000000 4.602277 -1.509089 +v 0.000000 4.612380 -1.506382 +v 0.000000 4.621859 -1.501962 +v 0.000000 4.630426 -1.495963 +v 0.000000 4.637821 -1.488567 +v 0.000000 4.643820 -1.480000 +v 0.000000 4.648241 -1.470521 +v 0.000000 4.650947 -1.460419 +v 0.000000 4.651859 -1.450000 +v 0.000000 4.643820 -1.420000 +v 0.000000 4.637821 -1.411433 +v 0.000000 4.650947 -1.439581 +v 0.000000 4.648241 -1.429479 +v 0.000000 4.630426 -1.404037 +v 0.000000 4.621859 -1.398039 +v 0.000000 4.612380 -1.393618 +v 0.000000 4.545896 -1.411433 +v 0.000000 4.539897 -1.420000 +v 0.000000 4.535477 -1.429479 +v 0.000000 4.602277 -1.390912 +v 0.000000 4.591859 -1.390000 +v 0.000000 4.581439 -1.390912 +v 0.000000 4.571337 -1.393618 +v 0.000000 4.561859 -1.398039 +v 0.000000 4.553291 -1.404037 +v -0.000000 0.705545 -1.617500 +v -0.000000 0.646709 -1.495963 +v -0.000000 0.654104 -1.488567 +v -0.000000 0.660103 -1.480000 +v -0.000000 0.664523 -1.470521 +v -0.000000 0.705545 -1.432500 +v -0.000000 0.667230 -1.460419 +v -0.000000 0.668142 -1.450000 +v -0.000000 0.549053 -1.439581 +v -0.000000 0.548142 -1.450000 +v -0.000000 0.549053 -1.460419 +v -0.000000 0.551760 -1.470521 +v -0.000000 0.556180 -1.480000 +v -0.000000 0.562179 -1.488567 +v -0.000000 0.569574 -1.495963 +v -0.000000 0.578142 -1.501962 +v -0.000000 0.587620 -1.506382 +v -0.000000 0.597723 -1.509089 +v -0.000000 0.608142 -1.510000 +v -0.000000 0.618560 -1.509089 +v -0.000000 0.628663 -1.506382 +v -0.000000 0.638142 -1.501962 +v -0.000000 0.667230 -1.439581 +v -0.000000 0.664523 -1.429479 +v -0.000000 0.660103 -1.420000 +v -0.000000 0.654104 -1.411433 +v -0.000000 0.646709 -1.404037 +v -0.000000 0.705545 -1.029071 +v -0.000000 0.562179 -1.411433 +v -0.000000 0.556180 -1.420000 +v -0.000000 0.551760 -1.429479 +v -0.000000 0.608142 -1.390000 +v -0.000000 0.597723 -1.390912 +v -0.000000 0.520418 -1.039443 +v -0.000000 0.638142 -1.398039 +v -0.000000 0.628663 -1.393618 +v -0.000000 0.618560 -1.390912 +v -0.000000 0.587620 -1.393618 +v -0.000000 0.578142 -1.398039 +v -0.000000 0.569574 -1.404037 +v 0.000000 4.440304 -1.662500 +v 0.000000 4.008525 -1.617500 +v 0.000000 4.208950 -1.621706 +v 0.000000 4.214590 -1.642753 +v 0.000000 4.223798 -1.662500 +v 0.000000 4.236295 -1.680349 +v 0.000000 4.289299 -1.717462 +v 0.000000 4.310345 -1.723101 +v 0.000000 4.427806 -1.680349 +v 0.000000 4.494455 -1.962500 +v 0.000000 4.332051 -1.725000 +v 0.000000 4.353757 -1.723101 +v 0.000000 4.374804 -1.717462 +v 0.000000 4.251703 -1.695756 +v 0.000000 4.269551 -1.708253 +v 0.000000 4.394551 -1.708253 +v 0.000000 4.412399 -1.695756 +v 0.000000 4.223798 -1.537500 +v 0.000000 4.214590 -1.557248 +v 0.000000 4.008525 -1.432500 +v 0.000000 4.440304 -1.537500 +v 0.000000 4.427806 -1.519652 +v 0.000000 4.412399 -1.504244 +v 0.000000 4.394551 -1.491747 +v 0.000000 4.374804 -1.482539 +v 0.000000 4.208950 -1.578294 +v 0.000000 4.207051 -1.600000 +v 0.000000 4.457051 -1.600000 +v 0.000000 4.455152 -1.578294 +v 0.000000 4.449512 -1.557248 +v 0.000000 4.353757 -1.476899 +v 0.000000 4.332051 -1.475000 +v 0.000000 4.310345 -1.476899 +v 0.000000 4.289299 -1.482539 +v 0.000000 4.269551 -1.491747 +v 0.000000 4.251703 -1.504244 +v 0.000000 4.236295 -1.519652 +v -0.000000 0.742949 -1.600000 +v -0.000000 0.744848 -1.621706 +v -0.000000 0.750488 -1.642753 +v -0.000000 0.759696 -1.662500 +v -0.000000 0.772194 -1.680349 +v -0.000000 0.705545 -1.962500 +v -0.000000 1.191475 -1.962500 +v -0.000000 0.963705 -1.680349 +v -0.000000 0.976202 -1.662500 +v -0.000000 0.787601 -1.695756 +v -0.000000 0.805449 -1.708253 +v -0.000000 0.825197 -1.717462 +v -0.000000 0.846243 -1.723101 +v -0.000000 0.867949 -1.725000 +v -0.000000 0.889655 -1.723101 +v -0.000000 0.910702 -1.717462 +v -0.000000 0.930449 -1.708253 +v -0.000000 0.948298 -1.695756 +v -0.000000 0.985411 -1.642753 +v -0.000000 0.991050 -1.621706 +v -0.000000 1.191475 -1.617500 +v -0.000000 0.992949 -1.600000 +v -0.000000 0.991050 -1.578294 +v -0.000000 0.759696 -1.537500 +v -0.000000 0.750488 -1.557248 +v -0.000000 0.948298 -1.504244 +v -0.000000 0.930449 -1.491747 +v -0.000000 1.191475 -1.432500 +v -0.000000 0.910702 -1.482539 +v -0.000000 0.744848 -1.578294 +v -0.000000 0.985411 -1.557248 +v -0.000000 0.976202 -1.537500 +v -0.000000 0.963705 -1.519652 +v -0.000000 0.889655 -1.476899 +v -0.000000 0.867949 -1.475000 +v -0.000000 0.846243 -1.476899 +v -0.000000 0.825197 -1.482539 +v -0.000000 0.805449 -1.491747 +v -0.000000 0.787601 -1.504244 +v -0.000000 0.772194 -1.519652 +v -0.000000 2.680349 -4.695756 +v -0.000000 2.695756 -4.680349 +v -0.000000 2.712500 -4.688429 +v -0.000000 2.554038 -4.938568 +v -0.000000 2.561433 -4.945962 +v -0.000000 2.466155 -5.196553 +v -0.000000 2.630000 -4.951962 +v -0.000000 2.638567 -4.945962 +v -0.000000 2.733845 -5.196553 +v -0.000000 2.519652 -4.695756 +v -0.000000 2.579479 -4.843618 +v -0.000000 2.570000 -4.848039 +v -0.000000 2.642753 -4.717462 +v -0.000000 2.662500 -4.708253 +v -0.000000 2.620521 -4.843618 +v -0.000000 2.537500 -4.708253 +v -0.000000 2.557248 -4.717462 +v -0.000000 2.578294 -4.723101 +v -0.000000 2.621706 -4.723101 +v -0.000000 2.610419 -4.840911 +v -0.000000 2.600000 -4.725000 +v -0.000000 2.600000 -4.840000 +v -0.000000 2.589581 -4.840911 +v -0.000000 2.561433 -4.854038 +v -0.000000 2.554038 -4.861433 +v -0.000000 2.548038 -4.870000 +v -0.000000 2.589581 -4.959089 +v -0.000000 2.600000 -5.200000 +v -0.000000 2.579479 -4.956382 +v -0.000000 2.570000 -4.951962 +v -0.000000 2.600000 -4.960001 +v -0.000000 2.610419 -4.959089 +v -0.000000 2.620521 -4.956382 +v -0.000000 2.645963 -4.938568 +v -0.000000 2.651962 -4.930000 +v -0.000000 2.656382 -4.920521 +v -0.000000 2.630000 -4.848039 +v -0.000000 2.638567 -4.854038 +v -0.000000 2.543619 -4.879479 +v -0.000000 2.540912 -4.889581 +v -0.000000 2.540000 -4.900000 +v -0.000000 2.540912 -4.910419 +v -0.000000 2.543619 -4.920521 +v -0.000000 2.548038 -4.930000 +v -0.000000 2.656382 -4.879479 +v -0.000000 2.651962 -4.870000 +v -0.000000 2.645963 -4.861433 +v -0.000000 2.659089 -4.910419 +v -0.000000 2.660000 -4.900000 +v -0.000000 2.659089 -4.889581 +v -0.000000 2.491747 -4.662500 +v -0.000000 2.504245 -4.680349 +v -0.000000 2.487500 -4.688429 +v -0.000000 2.482538 -4.642753 +v -0.000000 1.745192 -4.688429 +v -0.000000 2.476899 -4.621706 +v -0.000000 1.745192 -4.503429 +v -0.000000 2.476899 -4.578294 +v -0.000000 2.475000 -4.600000 +v -0.000000 2.487500 -4.503429 +v -0.000000 2.520000 -4.503429 +v -0.000000 2.519652 -4.504245 +v -0.000000 2.504245 -4.519652 +v -0.000000 2.491747 -4.537500 +v -0.000000 2.482538 -4.557248 +v -0.000000 2.680349 -4.504245 +v -0.000000 2.662500 -4.491747 +v -0.000000 2.712500 -4.142500 +v -0.000000 2.642753 -4.482539 +v -0.000000 2.621706 -4.476899 +v -0.000000 2.520000 -4.142500 +v -0.000000 2.600000 -4.475000 +v -0.000000 2.578294 -4.476899 +v -0.000000 2.557248 -4.482539 +v -0.000000 2.537500 -4.491747 +v -0.000000 2.712500 -4.503429 +v -0.000000 2.708253 -4.537500 +v -0.000000 2.695756 -4.519652 +v -0.000000 2.723101 -4.578294 +v -0.000000 2.717462 -4.557248 +v -0.000000 2.984808 -4.503429 +v -0.000000 2.708253 -4.662500 +v -0.000000 2.717462 -4.642753 +v -0.000000 2.984808 -4.688429 +v -0.000000 2.723101 -4.621706 +v -0.000000 2.725000 -4.600000 +v -0.000000 2.425000 -2.903109 +v -0.000000 1.745192 -3.495000 +v -0.000000 2.375025 -2.868116 +v -0.000000 2.250000 -2.600000 +v -0.000000 1.745192 -2.470000 +v -0.000000 2.255317 -2.539223 +v -0.000000 2.271108 -2.480293 +v -0.000000 2.255317 -2.660777 +v -0.000000 2.271108 -2.719707 +v 0.000000 2.487500 -1.962500 +v -0.000000 2.144664 -2.223396 +v -0.000000 2.130385 -2.213398 +v -0.000000 1.981904 -2.282635 +v -0.000000 1.980385 -2.300000 +v -0.000000 2.114587 -2.206031 +v -0.000000 2.097750 -2.201519 +v -0.000000 1.745192 -1.962500 +v -0.000000 2.080385 -2.200000 +v -0.000000 2.063020 -2.201519 +v -0.000000 2.016106 -2.223396 +v -0.000000 2.003780 -2.235721 +v -0.000000 1.981904 -2.317365 +v -0.000000 1.986416 -2.334202 +v -0.000000 1.993782 -2.350000 +v -0.000000 2.003780 -2.364279 +v -0.000000 2.016106 -2.376605 +v -0.000000 2.030385 -2.386603 +v -0.000000 2.174354 -2.265798 +v -0.000000 2.166987 -2.250000 +v -0.000000 2.156989 -2.235721 +v -0.000000 2.046183 -2.206031 +v -0.000000 2.030385 -2.213398 +v -0.000000 1.993782 -2.250000 +v -0.000000 1.986416 -2.265798 +v -0.000000 2.080385 -2.400000 +v -0.000000 2.063020 -2.398481 +v -0.000000 2.046183 -2.393969 +v -0.000000 2.097750 -2.398481 +v -0.000000 2.114587 -2.393969 +v -0.000000 2.130385 -2.386603 +v -0.000000 2.144664 -2.376605 +v -0.000000 2.156989 -2.364279 +v -0.000000 2.296891 -2.425000 +v -0.000000 2.166987 -2.350000 +v -0.000000 2.331885 -2.375025 +v -0.000000 2.174354 -2.334202 +v 0.000000 2.375025 -2.331885 +v -0.000000 2.178866 -2.317365 +v -0.000000 2.180385 -2.300000 +v 0.000000 2.487352 -2.268624 +v -0.000000 2.178866 -2.282635 +v 0.000000 2.480293 -2.271108 +v 0.000000 2.425000 -2.296891 +v 0.000000 2.520000 -1.962500 +v 0.000000 2.539223 -2.255317 +v 0.000000 2.712500 -1.962500 +v 0.000000 2.660777 -2.255317 +v 0.000000 2.600000 -2.250000 +v 0.000000 2.928893 -2.480293 +v 0.000000 2.984808 -1.962500 +v 0.000000 2.903109 -2.425000 +v 0.000000 2.868116 -2.375025 +v 0.000000 2.824976 -2.331885 +v 0.000000 2.775000 -2.296891 +v 0.000000 2.719707 -2.271108 +v -0.000000 2.824976 -2.868116 +v 0.000000 2.868116 -2.824976 +v 0.000000 2.903109 -2.775000 +v 0.000000 2.928893 -2.719707 +v 0.000000 2.944683 -2.660777 +v 0.000000 2.950000 -2.600000 +v 0.000000 2.944683 -2.539223 +v -0.000000 2.984808 -3.495000 +v -0.000000 2.775000 -2.903109 +v -0.000000 3.000116 -5.169029 +v -0.000000 3.454808 -4.688429 +v -0.000000 3.517155 -5.032864 +v -0.000000 3.262145 -5.114272 +v 0.000000 4.571337 -3.693619 +v 0.000000 4.494455 -3.495000 +v 0.000000 4.581439 -3.690912 +v 0.000000 4.591859 -3.690000 +v 0.000000 4.532770 -3.760419 +v 0.000000 4.535477 -3.770521 +v 0.000000 4.494455 -4.142500 +v 0.000000 4.630426 -3.795963 +v 0.000000 4.637821 -3.788567 +v 0.000000 4.757160 -4.051434 +v 0.000000 4.531858 -3.750000 +v -0.000000 4.414655 -4.461996 +v 0.000000 4.596489 -4.265543 +v 0.000000 4.581439 -3.809088 +v 0.000000 4.621859 -3.801962 +v 0.000000 4.561859 -3.698039 +v 0.000000 4.553291 -3.704037 +v 0.000000 4.545896 -3.711433 +v 0.000000 4.591859 -3.810000 +v 0.000000 4.602277 -3.809088 +v 0.000000 4.612380 -3.806382 +v 0.000000 4.643820 -3.780000 +v 0.000000 4.648241 -3.770521 +v 0.000000 4.650947 -3.760419 +v 0.000000 4.648241 -3.729479 +v 0.000000 4.650947 -3.739581 +v 0.000000 4.651859 -3.750000 +v 0.000000 4.643820 -3.720000 +v 0.000000 4.637821 -3.711433 +v 0.000000 4.630426 -3.704037 +v 0.000000 4.621859 -3.698039 +v 0.000000 4.612380 -3.693619 +v 0.000000 4.602277 -3.690912 +v 0.000000 4.539897 -3.720000 +v 0.000000 4.535477 -3.729479 +v 0.000000 4.532770 -3.739581 +v 0.000000 4.539897 -3.780000 +v 0.000000 4.545896 -3.788567 +v 0.000000 4.553291 -3.795963 +v 0.000000 4.561859 -3.801962 +v 0.000000 4.571337 -3.806382 +v 0.000000 4.894965 -3.821939 +v 0.000000 4.745929 -2.470000 +v 0.000000 4.861433 -2.554038 +v 0.000000 4.854038 -2.561433 +v 0.000000 4.848039 -2.570000 +v 0.000000 4.843618 -2.579479 +v 0.000000 4.840911 -2.589581 +v 0.000000 4.840000 -2.600000 +v 0.000000 4.840911 -2.610419 +v 0.000000 4.745929 -2.805000 +v 0.000000 4.843618 -2.620521 +v 0.000000 4.848039 -2.630000 +v 0.000000 4.854038 -2.638567 +v 0.000000 4.861433 -2.645963 +v 0.000000 4.870000 -2.651962 +v 0.000000 5.157875 -3.066130 +v 0.000000 4.938568 -2.645963 +v 0.000000 5.192245 -2.800656 +v 0.000000 4.945962 -2.638567 +v 0.000000 4.951962 -2.630000 +v 0.000000 4.956382 -2.620521 +v 0.000000 5.199138 -2.533056 +v 0.000000 4.959089 -2.610419 +v 0.000000 4.960001 -2.600000 +v 0.000000 4.959089 -2.589581 +v 0.000000 5.178479 -2.266165 +v 0.000000 4.938568 -2.554038 +v 0.000000 4.930000 -2.548038 +v 0.000000 4.900000 -2.540000 +v 0.000000 4.889581 -2.540912 +v 0.000000 4.879479 -2.543619 +v 0.000000 4.870000 -2.548038 +v 0.000000 4.956382 -2.579479 +v 0.000000 4.951962 -2.570000 +v 0.000000 4.945962 -2.561433 +v 0.000000 4.920521 -2.543619 +v 0.000000 4.910419 -2.540912 +v 0.000000 4.910419 -2.659089 +v 0.000000 4.920521 -2.656382 +v 0.000000 4.930000 -2.651962 +v 0.000000 4.879479 -2.656382 +v 0.000000 4.889581 -2.659089 +v 0.000000 4.900000 -2.660000 +v 0.000000 4.829018 -1.261539 +v 0.000000 4.316396 -0.647057 +v 0.000000 4.008525 -1.029071 +v 0.000000 4.106495 -0.480926 +v 0.000000 4.008525 -0.454071 +v 0.000000 3.880625 -0.337258 +v 0.000000 3.454808 -0.454071 +v 0.000000 3.641180 -0.217576 +v 0.000000 2.712500 -0.454071 +v 0.000000 2.867335 -0.013780 +v 0.000000 2.984808 -0.454071 +v 0.000000 3.131835 -0.054975 +v 0.000000 3.390699 -0.123148 +v 0.000000 2.579479 -0.243618 +v 0.000000 2.570000 -0.248039 +v 0.000000 2.519851 -0.001236 +v 0.000000 2.570000 -0.351961 +v 0.000000 2.579479 -0.356382 +v 0.000000 2.520000 -0.454071 +v 0.000000 2.589581 -0.359089 +v 0.000000 2.600000 -0.360000 +v 0.000000 2.589581 -0.240912 +v 0.000000 2.610419 -0.359089 +v 0.000000 2.620521 -0.356382 +v 0.000000 2.630000 -0.351961 +v 0.000000 2.630000 -0.248039 +v 0.000000 2.620521 -0.243618 +v 0.000000 2.561433 -0.254037 +v 0.000000 2.554038 -0.261433 +v 0.000000 2.548038 -0.270000 +v 0.000000 2.548038 -0.330000 +v 0.000000 2.554038 -0.338567 +v 0.000000 2.561433 -0.345963 +v 0.000000 2.638567 -0.345963 +v 0.000000 2.645963 -0.338567 +v 0.000000 2.651962 -0.330000 +v 0.000000 2.659089 -0.289581 +v 0.000000 2.656382 -0.279479 +v 0.000000 2.651962 -0.270000 +v 0.000000 2.645963 -0.261433 +v 0.000000 2.638567 -0.254037 +v 0.000000 2.543619 -0.279479 +v 0.000000 2.540912 -0.289581 +v 0.000000 2.540000 -0.300000 +v 0.000000 2.540912 -0.310419 +v 0.000000 2.543619 -0.320521 +v 0.000000 2.656382 -0.320521 +v 0.000000 2.659089 -0.310419 +v 0.000000 2.660000 -0.300000 +v 0.000000 2.487500 -0.454071 +v 0.000000 2.332665 -0.013780 +v 0.000000 2.068165 -0.054975 +v 0.000000 1.319375 -0.337258 +v 0.000000 1.191475 -0.454071 +v 0.000000 1.093505 -0.480926 +v 0.000000 0.883605 -0.647057 +v 0.000000 1.191475 -1.029071 +v -0.000000 0.691898 -0.833889 +v -0.000000 0.370982 -1.261539 +v -0.000000 0.454071 -1.962500 +v -0.000000 0.120000 -2.470000 +v -0.000000 0.000862 -2.533056 +v -0.000000 0.021521 -2.266165 +v -0.000000 0.442840 -4.051434 +v -0.000000 0.305035 -3.821939 +v -0.000000 0.454071 -3.495000 +v -0.000000 0.191558 -3.579493 +v -0.000000 0.103610 -3.326663 +v -0.000000 0.597723 -3.690912 +v -0.000000 0.608142 -3.690000 +v -0.000000 0.705545 -3.495000 +v -0.000000 0.618560 -3.690912 +v -0.000000 0.587620 -3.693619 +v -0.000000 0.578142 -3.698039 +v -0.000000 0.569574 -3.704037 +v -0.000000 0.654104 -3.711433 +v -0.000000 0.646709 -3.704037 +v -0.000000 0.562179 -3.711433 +v -0.000000 0.556180 -3.720000 +v -0.000000 0.551760 -3.729479 +v -0.000000 0.551760 -3.770521 +v -0.000000 0.556180 -3.780000 +v -0.000000 0.562179 -3.788567 +v -0.000000 0.569574 -3.795963 +v -0.000000 0.578142 -3.801962 +v -0.000000 0.587620 -3.806382 +v -0.000000 0.603511 -4.265543 +v -0.000000 0.597723 -3.809088 +v -0.000000 0.608142 -3.810000 +v -0.000000 0.618560 -3.809088 +v -0.000000 0.705545 -4.142500 +v -0.000000 0.628663 -3.806382 +v -0.000000 0.638142 -3.801962 +v -0.000000 0.646709 -3.795963 +v -0.000000 0.654104 -3.788567 +v -0.000000 0.660103 -3.780000 +v -0.000000 0.667230 -3.739581 +v -0.000000 0.664523 -3.729479 +v -0.000000 0.660103 -3.720000 +v -0.000000 0.638142 -3.698039 +v -0.000000 0.628663 -3.693619 +v -0.000000 0.549053 -3.739581 +v -0.000000 0.548142 -3.750000 +v -0.000000 0.549053 -3.760419 +v -0.000000 0.664523 -3.770521 +v -0.000000 0.667230 -3.760419 +v -0.000000 0.668142 -3.750000 +v -0.000000 1.191475 -4.503429 +v -0.000000 1.191475 -4.688429 +v -0.000000 0.785345 -4.461996 +v -0.000000 0.986415 -4.638711 +v -0.000000 1.437556 -4.925666 +v -0.000000 1.204590 -4.793817 +v -0.000000 2.199885 -5.169029 +v -0.000000 1.937855 -5.114272 +v -0.000000 1.682845 -5.032864 +v -0.000000 0.248039 -2.570000 +v -0.000000 0.243618 -2.579479 +v -0.000000 0.240912 -2.589581 +v -0.000000 0.240000 -2.600000 +v -0.000000 0.120000 -2.805000 +v -0.000000 0.007755 -2.800656 +v -0.000000 0.454071 -2.470000 +v -0.000000 0.360000 -2.600000 +v -0.000000 0.359089 -2.589581 +v -0.000000 0.279479 -2.543619 +v -0.000000 0.270000 -2.548038 +v -0.000000 0.240912 -2.610419 +v -0.000000 0.243618 -2.620521 +v -0.000000 0.248039 -2.630000 +v -0.000000 0.356382 -2.579479 +v -0.000000 0.351961 -2.570000 +v -0.000000 0.345963 -2.561433 +v -0.000000 0.261433 -2.554038 +v -0.000000 0.254037 -2.561433 +v -0.000000 0.320521 -2.543619 +v -0.000000 0.310419 -2.540912 +v -0.000000 0.300000 -2.540000 +v -0.000000 0.289581 -2.540912 +v -0.000000 0.351961 -2.630000 +v -0.000000 0.356382 -2.620521 +v -0.000000 0.454071 -2.805000 +v -0.000000 0.359089 -2.610419 +v -0.000000 0.338567 -2.554038 +v -0.000000 0.330000 -2.548038 +v -0.000000 0.254037 -2.638567 +v -0.000000 0.261433 -2.645963 +v -0.000000 0.270000 -2.651962 +v -0.000000 0.310419 -2.659089 +v -0.000000 0.320521 -2.656382 +v -0.000000 0.330000 -2.651962 +v -0.000000 0.279479 -2.656382 +v -0.000000 0.289581 -2.659089 +v -0.000000 0.300000 -2.660000 +v -0.000000 0.338567 -2.645963 +v -0.000000 0.345963 -2.638567 +v -0.000000 1.439581 -4.532770 +v -0.000000 1.450000 -4.531858 +v -0.000000 1.460419 -4.532770 +v -0.000000 1.470521 -4.648241 +v -0.000000 1.480000 -4.643820 +v -0.000000 1.495963 -4.553291 +v -0.000000 1.488567 -4.545896 +v -0.000000 1.429479 -4.535477 +v -0.000000 1.420000 -4.539897 +v -0.000000 1.411433 -4.545896 +v -0.000000 1.488567 -4.637821 +v -0.000000 1.495963 -4.630426 +v -0.000000 1.501962 -4.621859 +v -0.000000 1.480000 -4.539897 +v -0.000000 1.470521 -4.535477 +v -0.000000 1.404037 -4.553291 +v -0.000000 1.398039 -4.561859 +v -0.000000 1.393618 -4.571337 +v -0.000000 1.393618 -4.612380 +v -0.000000 1.398039 -4.621859 +v -0.000000 1.404037 -4.630426 +v -0.000000 1.411433 -4.637821 +v -0.000000 1.420000 -4.643820 +v -0.000000 1.429479 -4.648241 +v -0.000000 1.439581 -4.650947 +v -0.000000 1.450000 -4.651859 +v -0.000000 1.460419 -4.650947 +v -0.000000 1.506382 -4.612380 +v -0.000000 1.509089 -4.602277 +v -0.000000 1.510000 -4.591859 +v -0.000000 1.509089 -4.581439 +v -0.000000 1.506382 -4.571337 +v -0.000000 1.501962 -4.561859 +v -0.000000 1.390912 -4.581439 +v -0.000000 1.390000 -4.591859 +v -0.000000 1.390912 -4.602277 +v -0.000000 1.191475 -3.495000 +v -0.000000 1.191475 -2.805000 +v -0.000000 0.705545 -2.805000 +v -0.000000 0.042125 -3.066130 +v -0.000000 1.191475 -2.470000 +v -0.000000 0.705545 -2.470000 +v 0.000000 1.460419 -0.667230 +v 0.000000 1.745192 -1.029071 +v 0.000000 1.450000 -0.668142 +v 0.000000 1.470521 -0.664523 +v 0.000000 1.480000 -0.660103 +v 0.000000 1.488567 -0.654104 +v 0.000000 1.495963 -0.646709 +v 0.000000 1.501962 -0.638142 +v 0.000000 1.506382 -0.628663 +v 0.000000 1.495963 -0.569574 +v 0.000000 1.488567 -0.562179 +v 0.000000 1.480000 -0.556180 +v 0.000000 1.450000 -0.548142 +v 0.000000 1.439581 -0.549053 +v 0.000000 1.429479 -0.551760 +v 0.000000 1.420000 -0.556180 +v 0.000000 1.411433 -0.562179 +v 0.000000 1.404037 -0.569574 +v 0.000000 1.398039 -0.578142 +v 0.000000 1.393618 -0.587620 +v 0.000000 1.390912 -0.597723 +v 0.000000 1.398039 -0.638142 +v 0.000000 1.404037 -0.646709 +v 0.000000 1.411433 -0.654104 +v 0.000000 1.420000 -0.660103 +v 0.000000 1.429479 -0.664523 +v 0.000000 1.439581 -0.667230 +v 0.000000 1.509089 -0.618560 +v 0.000000 1.510000 -0.608142 +v 0.000000 1.509089 -0.597723 +v 0.000000 1.470521 -0.551760 +v 0.000000 1.460419 -0.549053 +v 0.000000 1.506382 -0.587620 +v 0.000000 1.501962 -0.578142 +v 0.000000 1.390000 -0.608142 +v 0.000000 1.390912 -0.618560 +v 0.000000 1.393618 -0.628663 +v -0.000000 1.191475 -4.142500 +v -0.000000 1.745192 -4.142500 +v -0.000000 2.487500 -4.142500 +v 0.000000 3.119615 -2.200000 +v 0.000000 3.102251 -2.201519 +v 0.000000 3.169616 -2.386603 +v 0.000000 3.183894 -2.376605 +v 0.000000 3.085413 -2.206031 +v 0.000000 3.069615 -2.213398 +v 0.000000 3.055337 -2.223396 +v 0.000000 3.196220 -2.364279 +v 0.000000 3.206218 -2.350000 +v 0.000000 3.213585 -2.334202 +v 0.000000 3.213585 -2.265798 +v 0.000000 3.206218 -2.250000 +v 0.000000 3.196220 -2.235721 +v 0.000000 3.183894 -2.223396 +v 0.000000 3.169616 -2.213398 +v 0.000000 3.153817 -2.206031 +v 0.000000 3.136980 -2.201519 +v 0.000000 3.043011 -2.235721 +v 0.000000 3.033013 -2.250000 +v 0.000000 3.025646 -2.265798 +v 0.000000 3.025646 -2.334202 +v 0.000000 3.033013 -2.350000 +v 0.000000 3.043011 -2.364279 +v 0.000000 3.055337 -2.376605 +v 0.000000 3.218096 -2.317365 +v 0.000000 3.219615 -2.300000 +v 0.000000 3.218096 -2.282635 +v 0.000000 3.021135 -2.282635 +v 0.000000 3.019615 -2.300000 +v 0.000000 3.021135 -2.317365 +v 0.000000 3.069615 -2.386603 +v 0.000000 3.085413 -2.393969 +v 0.000000 3.102251 -2.398481 +v 0.000000 3.119615 -2.400000 +v 0.000000 3.136980 -2.398481 +v 0.000000 3.153817 -2.393969 +v 0.000000 2.487500 -1.029071 +v 0.000000 2.520000 -1.029071 +v 0.000000 2.712500 -1.029071 +v 0.000000 2.984808 -1.029071 +v 0.000000 3.454808 -1.029071 +v -0.000000 3.739581 -4.532770 +v -0.000000 3.729479 -4.535477 +v -0.000000 3.454808 -4.503429 +v -0.000000 3.750000 -4.531858 +v -0.000000 4.008525 -4.688429 +v -0.000000 3.770521 -4.648241 +v -0.000000 3.780000 -4.643820 +v -0.000000 3.690000 -4.591859 +v -0.000000 3.690912 -4.602277 +v -0.000000 3.780000 -4.539897 +v -0.000000 3.770521 -4.535477 +v -0.000000 4.008525 -4.503429 +v -0.000000 3.760419 -4.532770 +v -0.000000 3.720000 -4.539897 +v -0.000000 3.711433 -4.545896 +v -0.000000 3.704037 -4.553291 +v -0.000000 3.698039 -4.561859 +v -0.000000 3.693619 -4.571337 +v -0.000000 3.690912 -4.581439 +v -0.000000 3.729479 -4.648241 +v -0.000000 3.739581 -4.650947 +v -0.000000 3.750000 -4.651859 +v -0.000000 3.760419 -4.650947 +v -0.000000 3.788567 -4.637821 +v -0.000000 3.795963 -4.630426 +v -0.000000 3.801962 -4.621859 +v -0.000000 3.693619 -4.612380 +v -0.000000 3.698039 -4.621859 +v -0.000000 3.704037 -4.630426 +v -0.000000 3.806382 -4.612380 +v -0.000000 3.809088 -4.602277 +v -0.000000 3.810000 -4.591859 +v -0.000000 3.809088 -4.581439 +v -0.000000 3.806382 -4.571337 +v -0.000000 3.801962 -4.561859 +v -0.000000 3.795963 -4.553291 +v -0.000000 3.788567 -4.545896 +v -0.000000 3.711433 -4.637821 +v -0.000000 3.720000 -4.643820 +v -0.000000 4.008525 -4.142500 +v 0.000000 3.454808 -2.805000 +v 0.000000 4.008525 -2.470000 +v 0.000000 3.454808 -1.617500 +v 0.000000 2.984808 -1.617500 +v 0.000000 2.712500 -1.617500 +v 0.000000 2.520000 -1.617500 +v 0.000000 2.487500 -1.617500 +v 0.000000 1.745192 -1.617500 +v 0.000000 3.454808 -1.432500 +v 0.000000 2.984808 -1.432500 +v 0.000000 2.712500 -1.432500 +v 0.000000 2.520000 -1.432500 +v 0.000000 2.487500 -1.432500 +v 0.000000 1.745192 -1.432500 +v 0.000000 3.810000 -0.608142 +v 0.000000 3.809088 -0.597723 +v 0.000000 3.729479 -0.551760 +v 0.000000 3.720000 -0.556180 +v 0.000000 3.711433 -0.562179 +v 0.000000 3.704037 -0.569574 +v 0.000000 3.760419 -0.667230 +v 0.000000 3.770521 -0.664523 +v 0.000000 3.698039 -0.578142 +v 0.000000 3.693619 -0.587620 +v 0.000000 3.690912 -0.597723 +v 0.000000 3.690000 -0.608142 +v 0.000000 3.690912 -0.618560 +v 0.000000 3.693619 -0.628663 +v 0.000000 3.698039 -0.638142 +v 0.000000 3.704037 -0.646709 +v 0.000000 3.711433 -0.654104 +v 0.000000 3.720000 -0.660103 +v 0.000000 3.780000 -0.660103 +v 0.000000 3.788567 -0.654104 +v 0.000000 3.795963 -0.646709 +v 0.000000 3.801962 -0.638142 +v 0.000000 3.806382 -0.628663 +v 0.000000 3.809088 -0.618560 +v 0.000000 3.806382 -0.587620 +v 0.000000 3.801962 -0.578142 +v 0.000000 3.795963 -0.569574 +v 0.000000 3.788567 -0.562179 +v 0.000000 3.780000 -0.556180 +v 0.000000 3.770521 -0.551760 +v 0.000000 3.760419 -0.549053 +v 0.000000 3.750000 -0.548142 +v 0.000000 3.739581 -0.549053 +v 0.000000 3.729479 -0.664523 +v 0.000000 3.739581 -0.667230 +v 0.000000 3.750000 -0.668142 +v -0.000000 4.213585 -4.638711 +v -0.000000 3.995410 -4.793817 +v -0.000000 3.762444 -4.925666 +v -0.000000 3.454808 -4.142500 +v 0.000000 4.008525 -3.495000 +v 0.000000 4.494455 -2.805000 +v 0.000000 4.494455 -2.470000 +v 0.000000 4.008525 -2.805000 +v -0.000000 3.454808 -3.495000 +v -0.000000 2.984808 -4.142500 +vn 0.7273 -0.1192 0.6759 +vn 0.7273 -0.0000 0.6864 +vn 1.0000 -0.0000 -0.0000 +vn 0.6957 0.5013 -0.5145 +vn 0.6957 0.6784 0.2360 +vn 0.6957 0.6506 0.3045 +vn 0.6957 -0.6506 0.3045 +vn 0.6957 -0.6784 0.2360 +vn 0.6957 -0.3212 -0.6425 +vn 0.6957 -0.2534 -0.6721 +vn 0.7273 -0.1191 -0.6759 +vn 0.7273 -0.2347 -0.6450 +vn 0.7273 -0.3432 -0.5944 +vn 0.7273 -0.4412 -0.5258 +vn 0.7273 0.6450 0.2347 +vn 0.7273 0.6759 0.1192 +vn 0.7273 -0.6864 -0.0000 +vn 0.7273 -0.6759 0.1192 +vn 0.7273 0.6759 -0.1192 +vn 0.7273 0.6450 -0.2348 +vn 0.7273 -0.4412 0.5258 +vn 0.7273 -0.3432 0.5944 +vn 0.7273 0.2347 0.6450 +vn 0.7273 0.5258 -0.4412 +vn 0.7273 0.4412 -0.5258 +vn 0.7273 -0.2348 0.6450 +vn 0.7273 0.1192 0.6759 +vn 0.7273 0.2348 0.6449 +vn 0.7273 0.3432 0.5944 +vn 0.7273 0.3432 -0.5944 +vn 0.7273 0.2348 0.6450 +vn 0.7273 0.3431 -0.5944 +vn 0.7273 0.2347 -0.6450 +vn 0.7273 0.2348 -0.6450 +vn 0.7273 0.1192 -0.6759 +vn 0.7273 0.1191 0.6759 +vn 0.7273 -0.0001 0.6864 +vn 0.7273 -0.0000 -0.6864 +vn 0.7273 -0.0001 -0.6864 +vn 0.7273 -0.1191 0.6759 +vn 0.7273 -0.1192 -0.6759 +vn 0.7273 -0.2347 0.6450 +vn 0.7273 -0.6759 0.1191 +vn 0.7273 -0.6450 0.2348 +vn 0.7273 -0.6450 0.2347 +vn 0.7273 -0.5944 0.3432 +vn 0.7273 -0.5258 0.4412 +vn 0.7273 -0.3431 -0.5944 +vn 0.7273 -0.2348 0.6449 +vn 0.7273 -0.5258 -0.4412 +vn 0.7273 -0.5944 -0.3431 +vn 0.7273 -0.5944 -0.3432 +vn 0.7273 -0.6450 -0.2348 +vn 0.7273 -0.6450 -0.2347 +vn 0.7273 -0.6759 -0.1192 +vn 0.7273 0.4412 0.5258 +vn 0.7273 0.5258 0.4412 +vn 0.7273 0.6864 -0.0001 +vn 0.7273 0.6759 -0.1191 +vn 0.7273 0.6450 -0.2347 +vn 0.7273 0.5944 -0.3431 +vn 0.7273 0.5944 0.3432 +vn 0.7273 0.6450 0.2348 +vn 0.7273 0.6864 -0.0000 +vn 0.7273 -0.6759 -0.1191 +vn 0.7273 0.6759 0.1191 +vn 0.7273 0.5944 -0.3432 +vn 0.7273 0.1191 -0.6759 +vn 0.6957 0.5746 0.4311 +vn 0.7273 -0.2348 -0.6449 +vn 0.6957 0.5745 0.4311 +vn 0.6957 0.5745 0.4312 +vn 0.7273 -0.2348 -0.6450 +vn 0.7273 0.5944 0.3431 +vn 0.7273 -0.5944 0.3431 +vn 0.6957 -0.5746 0.4311 +vn 0.7273 0.5258 -0.4411 +vn 0.6957 -0.5745 0.4311 +vn 0.6957 -0.5745 0.4312 +vn 0.7273 0.2348 -0.6449 +vn 0.7273 0.3431 0.5944 +vn 0.7273 -0.6449 -0.2348 +vn 0.7273 0.0001 -0.6864 +vn 0.7273 -0.3431 0.5944 +vn 0.7014 -0.0000 -0.7128 +vn 0.7273 0.4411 0.5258 +vn 0.6985 0.0460 -0.7141 +vn 0.6985 -0.0460 -0.7141 +vn 0.6985 -0.0461 -0.7141 +vn 0.7273 0.5258 0.4411 +vn 0.7014 0.0001 -0.7128 +vn 0.7273 -0.4411 0.5258 +vn 0.6985 0.0461 -0.7141 +vn 0.7273 -0.5258 0.4411 +vn 0.7273 -0.6864 -0.0001 +vn 0.7273 -0.6864 0.0001 +vn 0.7273 -0.4411 -0.5258 +vn 0.7260 0.1158 -0.6779 +vn 0.7260 0.1159 -0.6779 +vn 0.7171 0.2025 -0.6670 +vn 0.7273 0.6449 -0.2348 +vn 0.7273 0.4411 -0.5258 +vn 0.7273 -0.5258 -0.4411 +vn 0.7273 0.5943 -0.3434 +vn 0.7183 0.2628 -0.6442 +vn 0.6957 -0.1829 -0.6946 +vn 0.6957 -0.1105 -0.7098 +vn 0.6957 -0.1106 -0.7098 +vn 0.6957 -0.3211 -0.6425 +vn 0.6957 -0.3855 -0.6061 +vn 0.6957 -0.4458 -0.5633 +vn 0.6957 -0.4458 -0.5632 +vn 0.6957 -0.5013 -0.5145 +vn 0.6957 -0.5960 -0.4010 +vn 0.6957 -0.5516 -0.4602 +vn 0.6957 -0.5516 -0.4601 +vn 0.6957 -0.5959 -0.4011 +vn 0.6957 -0.5959 -0.4010 +vn 0.7273 0.6449 0.2348 +vn 0.7273 0.6864 0.0001 +vn 0.6957 -0.5960 -0.4009 +vn 0.6957 -0.6341 -0.3376 +vn 0.6957 -0.6340 -0.3376 +vn 0.6957 -0.6654 -0.2706 +vn 0.6957 -0.7162 -0.0554 +vn 0.6957 -0.7162 -0.0555 +vn 0.6957 -0.7067 -0.1288 +vn 0.6957 -0.6897 -0.2007 +vn 0.6957 -0.6991 0.1650 +vn 0.6957 -0.7124 0.0922 +vn 0.6957 -0.7181 0.0184 +vn 0.6957 -0.7181 0.0185 +vn 0.6957 -0.6158 0.3698 +vn 0.6957 -0.2184 0.6843 +vn 0.6957 -0.2877 0.6582 +vn 0.6957 -0.2876 0.6582 +vn 0.6957 -0.3538 0.6251 +vn 0.6957 -0.3538 0.6252 +vn 0.6957 -0.4162 0.5855 +vn 0.6957 -0.4742 0.5396 +vn 0.6957 -0.4742 0.5395 +vn 0.6957 -0.5271 0.4880 +vn 0.6957 -0.5272 0.4879 +vn 0.7014 -0.0293 0.7122 +vn 0.6997 0.0129 0.7144 +vn 0.7014 -0.0294 0.7122 +vn 0.6957 0.0739 0.7145 +vn 0.6957 0.0738 0.7145 +vn 0.6957 -0.1469 0.7031 +vn 0.6957 -0.1470 0.7031 +vn 0.6974 -0.0792 0.7123 +vn 0.6957 0.2877 0.6582 +vn 0.6957 0.2184 0.6843 +vn 0.6957 0.1469 0.7031 +vn 0.6957 0.1470 0.7031 +vn 0.6957 0.2876 0.6582 +vn 0.6957 0.3538 0.6251 +vn 0.6957 0.3538 0.6252 +vn 0.6957 0.4162 0.5855 +vn 0.6957 0.4162 0.5854 +vn 0.6957 0.4742 0.5395 +vn 0.6957 0.4742 0.5396 +vn 0.6957 0.5272 0.4879 +vn 0.6957 0.6158 0.3698 +vn 0.6957 0.7067 -0.1288 +vn 0.6957 0.7067 -0.1287 +vn 0.6957 0.7162 -0.0554 +vn 0.6957 0.7162 -0.0555 +vn 0.6957 0.7181 0.0184 +vn 0.6957 0.7181 0.0186 +vn 0.6957 0.7181 0.0185 +vn 0.6957 0.7124 0.0922 +vn 0.6957 0.7124 0.0923 +vn 0.6957 0.6897 -0.2007 +vn 0.6957 0.6654 -0.2706 +vn 0.6957 0.5960 -0.4010 +vn 0.6957 0.6341 -0.3376 +vn 0.6957 0.5013 -0.5144 +vn 0.6957 0.5516 -0.4601 +vn 0.7273 0.5257 0.4412 +vn 0.6957 0.5959 -0.4010 +vn 0.6957 0.5959 -0.4011 +vn 0.6957 0.5516 -0.4602 +vn 0.6957 0.3855 -0.6061 +vn 0.6957 0.3212 -0.6425 +vn 0.6957 0.1106 -0.7098 +vn 0.6957 0.1105 -0.7098 +vn 0.6957 0.1830 -0.6946 +vn 0.6957 0.1829 -0.6946 +vn 0.6957 0.2534 -0.6722 +vn 0.6957 0.2534 -0.6721 +vn 0.6957 0.6991 0.1650 +vn 0.6957 0.6785 0.2360 +vn 0.7273 -0.4412 -0.5257 +vn 0.6957 0.6340 -0.3376 +vn 0.7273 -0.6449 0.2348 +vn 0.6957 0.4458 -0.5633 +vn 0.6957 0.4458 -0.5632 +vn 0.6957 0.5014 -0.5144 +vn 0.7273 0.4412 -0.5257 +vn 0.7273 -0.4412 0.5257 +vn 0.6957 -0.5014 -0.5144 +vn 0.6957 -0.5013 -0.5144 +vn 0.6957 -0.6785 0.2360 +vn 0.6957 -0.6897 -0.2008 +vn -1.0000 -0.0000 -0.0000 +vn -0.6957 -0.6784 0.2360 +vn -0.6957 -0.6991 0.1650 +vn -0.6957 -0.6506 0.3045 +vn -0.6957 -0.2877 0.6582 +vn -0.6957 -0.2184 0.6843 +vn -0.7273 -0.1191 -0.6759 +vn -0.7273 -0.0000 -0.6864 +vn -0.6997 0.0129 0.7144 +vn -0.6957 0.5745 0.4312 +vn -0.6957 0.5272 0.4879 +vn -0.6957 0.6506 0.3045 +vn -0.6957 0.6784 0.2360 +vn -0.6957 0.6991 0.1650 +vn -0.6957 0.6897 -0.2008 +vn -0.6957 0.6654 -0.2706 +vn -0.7273 0.5944 0.3432 +vn -0.7273 0.5258 0.4412 +vn -0.7273 -0.6450 0.2347 +vn -0.7273 -0.6759 0.1191 +vn -0.7273 -0.2348 0.6450 +vn -0.7273 -0.3432 0.5944 +vn -0.7273 -0.4412 0.5258 +vn -0.7273 -0.5258 0.4412 +vn -0.7273 0.5258 -0.4412 +vn -0.7273 0.2347 0.6450 +vn -0.7273 0.4412 -0.5258 +vn -0.7273 0.2348 0.6450 +vn -0.7273 0.3432 -0.5944 +vn -0.7273 0.3432 0.5944 +vn -0.7273 0.4412 0.5258 +vn -0.7273 0.2348 0.6449 +vn -0.7273 0.1192 0.6759 +vn -0.7273 -0.0000 0.6864 +vn -0.7273 -0.1192 0.6759 +vn -0.7273 -0.2348 0.6449 +vn -0.7273 -0.3431 -0.5944 +vn -0.7273 -0.2347 -0.6450 +vn -0.7273 -0.2348 -0.6450 +vn -0.7273 -0.1192 -0.6759 +vn -0.7273 -0.1191 0.6759 +vn -0.7273 0.0001 0.6864 +vn -0.7273 0.0001 -0.6864 +vn -0.7273 0.1191 0.6759 +vn -0.7273 0.1192 -0.6759 +vn -0.7273 0.2347 -0.6450 +vn -0.7273 0.3431 -0.5944 +vn -0.7273 -0.5944 0.3432 +vn -0.7273 -0.6450 0.2348 +vn -0.7273 -0.6759 0.1192 +vn -0.7273 -0.6864 -0.0001 +vn -0.7273 -0.6759 -0.1192 +vn -0.7273 -0.2347 0.6450 +vn -0.7273 -0.6450 -0.2347 +vn -0.7273 -0.6450 -0.2348 +vn -0.7273 -0.5944 -0.3432 +vn -0.7273 -0.5944 -0.3431 +vn -0.7273 -0.5258 -0.4412 +vn -0.7273 -0.4412 -0.5258 +vn -0.7273 -0.3432 -0.5944 +vn -0.7273 0.5944 0.3431 +vn -0.7273 0.5944 -0.3431 +vn -0.7273 0.6450 -0.2348 +vn -0.7273 0.6450 -0.2347 +vn -0.7273 0.6759 -0.1191 +vn -0.7273 0.6864 -0.0000 +vn -0.7273 0.6759 0.1192 +vn -0.7273 0.6450 0.2348 +vn -0.7273 0.6450 0.2347 +vn -0.7273 0.6759 -0.1192 +vn -0.7273 -0.6864 -0.0000 +vn -0.6957 0.5746 0.4311 +vn -0.7273 -0.6759 -0.1191 +vn -0.6957 0.5745 0.4311 +vn -0.7273 0.5257 -0.4412 +vn -0.7273 0.5944 -0.3432 +vn -0.7273 -0.2348 -0.6449 +vn -0.7273 -0.0001 -0.6864 +vn -0.7273 0.1191 -0.6759 +vn -0.7273 -0.5944 0.3431 +vn -0.7273 0.6759 0.1191 +vn -0.6957 -0.5746 0.4311 +vn -0.7273 0.2348 -0.6449 +vn -0.6957 -0.5745 0.4311 +vn -0.6957 -0.5745 0.4312 +vn -0.7273 0.2348 -0.6450 +vn -0.7273 0.3431 0.5944 +vn -0.7273 -0.3431 0.5944 +vn -0.7273 0.6449 -0.2348 +vn -0.7273 0.5258 0.4411 +vn -0.6985 -0.0461 -0.7141 +vn -0.6985 0.0461 -0.7141 +vn -0.7273 0.4411 0.5258 +vn -0.7014 0.0001 -0.7128 +vn -0.7014 -0.0000 -0.7128 +vn -0.6985 -0.0460 -0.7141 +vn -0.6985 0.0460 -0.7141 +vn -0.7273 -0.5258 0.4411 +vn -0.7273 -0.4411 0.5258 +vn -0.7273 -0.4412 -0.5257 +vn -0.7273 0.6864 -0.0001 +vn -0.7273 0.4411 -0.5258 +vn -0.7273 -0.6449 -0.2348 +vn -0.7273 -0.5258 -0.4411 +vn -0.7273 -0.4411 -0.5258 +vn -0.7273 0.5258 -0.4411 +vn -0.7273 0.4412 -0.5257 +vn -0.7171 0.2025 -0.6670 +vn -0.7183 0.2628 -0.6442 +vn -0.7171 0.2025 -0.6669 +vn -0.7260 0.1158 -0.6779 +vn -0.7273 -0.6864 0.0001 +vn -0.6957 0.1105 -0.7098 +vn -0.6957 0.2534 -0.6722 +vn -0.6957 0.1830 -0.6946 +vn -0.6957 0.5960 -0.4010 +vn -0.6957 0.5013 -0.5144 +vn -0.6957 0.5516 -0.4601 +vn -0.6957 0.5516 -0.4602 +vn -0.6957 0.5959 -0.4010 +vn -0.7273 0.5257 0.4412 +vn -0.6957 0.5960 -0.4009 +vn -0.6957 0.6341 -0.3376 +vn -0.6957 0.6340 -0.3376 +vn -0.6957 0.7067 -0.1288 +vn -0.6957 0.7162 -0.0554 +vn -0.6957 0.7162 -0.0555 +vn -0.6957 0.7181 0.0185 +vn -0.6957 0.7181 0.0184 +vn -0.6957 0.7124 0.0923 +vn -0.6957 0.7124 0.0922 +vn -0.6957 0.7181 0.0186 +vn -0.6957 0.7067 -0.1287 +vn -0.6957 0.6158 0.3698 +vn -0.6957 0.5271 0.4880 +vn -0.6957 0.4742 0.5396 +vn -0.6957 0.4742 0.5395 +vn -0.6957 0.4162 0.5855 +vn -0.6957 0.3538 0.6252 +vn -0.6957 0.3538 0.6251 +vn -0.6957 0.2876 0.6582 +vn -0.6957 0.0738 0.7145 +vn -0.6957 0.0739 0.7145 +vn -0.6957 0.1470 0.7031 +vn -0.6957 0.1469 0.7031 +vn -0.6957 0.2184 0.6843 +vn -0.6957 0.2877 0.6582 +vn -0.7014 -0.0293 0.7122 +vn -0.7273 -0.0001 0.6864 +vn -0.7014 -0.0294 0.7122 +vn -0.6974 -0.0792 0.7123 +vn -0.6957 -0.2185 0.6843 +vn -0.6957 -0.1469 0.7031 +vn -0.6957 -0.1470 0.7031 +vn -0.6957 -0.2876 0.6582 +vn -0.6957 -0.3538 0.6251 +vn -0.6957 -0.3538 0.6252 +vn -0.6957 -0.4162 0.5855 +vn -0.6957 -0.4162 0.5854 +vn -0.6957 -0.4742 0.5395 +vn -0.6957 -0.4742 0.5396 +vn -0.6957 -0.5272 0.4879 +vn -0.6957 -0.6158 0.3698 +vn -0.6957 -0.7181 0.0184 +vn -0.6957 -0.7124 0.0922 +vn -0.6957 -0.5960 -0.4010 +vn -0.6957 -0.6341 -0.3376 +vn -0.6957 -0.6340 -0.3376 +vn -0.6957 -0.6654 -0.2706 +vn -0.6957 -0.6897 -0.2008 +vn -0.7273 0.6449 0.2348 +vn -0.6957 -0.5959 -0.4010 +vn -0.6957 -0.5959 -0.4011 +vn -0.6957 -0.5516 -0.4602 +vn -0.7273 0.6864 0.0001 +vn -0.6957 -0.5014 -0.5144 +vn -0.6957 -0.5013 -0.5145 +vn -0.6957 -0.4458 -0.5632 +vn -0.6957 -0.3212 -0.6425 +vn -0.6957 -0.3855 -0.6061 +vn -0.6957 -0.4458 -0.5633 +vn -0.6957 -0.1106 -0.7098 +vn -0.6957 -0.1105 -0.7098 +vn -0.6957 -0.1829 -0.6946 +vn -0.6957 -0.1830 -0.6946 +vn -0.6957 -0.2534 -0.6722 +vn -0.6957 -0.2534 -0.6721 +vn -0.6957 -0.7181 0.0185 +vn -0.6957 -0.7162 -0.0555 +vn -0.7273 -0.4412 0.5257 +vn -0.6957 -0.6785 0.2360 +vn -0.6957 -0.6897 -0.2007 +vn -0.6957 -0.7067 -0.1288 +vn -0.6957 -0.5516 -0.4601 +vn -0.6957 -0.5013 -0.5144 +vn -0.6957 0.1829 -0.6946 +vn -0.6957 0.1106 -0.7098 +vn -0.7273 -0.6449 0.2348 +vn -0.6957 0.5013 -0.5145 +vn -0.6957 0.5014 -0.5144 +vn -0.6957 0.4458 -0.5633 +vn -0.6957 0.4458 -0.5632 +vn -0.6957 0.3855 -0.6061 +vn -0.6957 0.3211 -0.6425 +vn -0.6957 0.3212 -0.6425 +vn -0.6957 0.2534 -0.6721 +vn -0.6957 0.6897 -0.2007 +vn -0.6957 0.6785 0.2360 +vn 0.6974 -0.0791 0.7123 +vn -0.6957 -0.1469 0.7032 +vn 0.6957 -0.1469 0.7032 +vn 0.6957 -0.2185 0.6843 +vn 0.6957 -0.3539 0.6251 +vn 0.6957 -0.4163 0.5854 +vn -0.6957 -0.5272 0.4880 +vn 0.6957 -0.5272 0.4880 +vn 0.6957 -0.5746 0.4312 +vn 0.6957 -0.6159 0.3698 +vn -0.6957 -0.6506 0.3046 +vn -0.6957 -0.7124 0.0923 +vn -0.6957 -0.7162 -0.0554 +vn -0.6957 -0.7067 -0.1287 +vn 0.6957 -0.6654 -0.2707 +vn -0.6957 -0.3856 -0.6061 +vn 0.6957 -0.3211 -0.6426 +vn 0.6957 -0.2534 -0.6722 +vn -0.6957 -0.1829 -0.6947 +vn 0.6957 -0.1829 -0.6947 +vn 0.7014 -0.0001 -0.7128 +vn 0.6957 0.1469 0.7032 +vn 0.6957 0.2185 0.6843 +vn -0.6957 0.1469 0.7032 +vn -0.6957 0.2185 0.6843 +vn -0.6957 0.3539 0.6251 +vn -0.6957 0.4163 0.5854 +vn 0.6957 0.5272 0.4880 +vn -0.6957 0.5272 0.4880 +vn -0.6957 0.5746 0.4312 +vn -0.6957 0.6159 0.3698 +vn 0.6957 0.6506 0.3046 +vn 0.6957 0.6897 -0.2008 +vn -0.6957 0.6654 -0.2707 +vn 0.6957 0.3856 -0.6061 +vn -0.6957 0.3211 -0.6426 +vn 0.6957 0.1829 -0.6947 +vn -0.6957 0.1829 -0.6947 +vn 0.7273 -0.0000 -0.6863 +vn -0.7273 -0.0000 -0.6863 +vn -0.7273 -0.5257 -0.4412 +vn 0.7273 -0.6863 -0.0000 +vn -0.7273 -0.6863 -0.0000 +vn 0.7273 -0.0000 0.6863 +vn -0.7273 -0.0000 0.6863 +vn 0.7273 0.6863 -0.0000 +vn -0.7273 0.6863 -0.0000 +vn 0.7273 0.5257 -0.4412 +vn 0.7183 0.2629 -0.6442 +vn 0.7171 0.2025 -0.6669 +vn -0.7183 0.2629 -0.6442 +vn -0.7170 0.2025 -0.6670 +vn 0.7170 0.2024 -0.6670 +vn -0.7171 0.2024 -0.6669 +vn -0.7260 0.1157 -0.6779 +vn -0.7272 -0.0000 -0.6864 +vn -0.7272 -0.5258 -0.4412 +vn 0.7273 -0.6863 -0.0001 +vn -0.7273 -0.6863 0.0001 +vn 0.7272 -0.5944 0.3432 +vn 0.7273 -0.5257 0.4412 +vn -0.7273 -0.5257 0.4412 +vn 0.7273 0.0001 0.6864 +vn -0.7273 0.4412 0.5257 +vn 0.7272 0.5258 -0.4412 +vn -0.7272 0.5258 -0.4412 +vn 0.7272 -0.0000 -0.6864 +vn 0.7272 -0.1192 -0.6760 +vn 0.7272 -0.1191 -0.6760 +vn -0.7272 -0.1192 -0.6760 +vn -0.7272 -0.1192 -0.6759 +vn 0.7272 -0.5258 -0.4412 +vn 0.7272 -0.5258 0.4412 +vn 0.7272 -0.1191 0.6760 +vn -0.7272 -0.1192 0.6759 +vn 0.7272 -0.1192 0.6760 +vn -0.7272 -0.1191 0.6760 +vn -0.7272 -0.1192 0.6760 +vn 0.7272 0.1192 0.6760 +vn 0.7272 0.1191 0.6760 +vn -0.7272 0.1192 0.6760 +vn 0.7272 0.1192 0.6759 +vn -0.7272 0.1191 0.6760 +vn 0.7273 0.4412 0.5257 +vn -0.7272 0.5258 0.4412 +vn 0.7273 0.6863 0.0001 +vn -0.7273 0.6863 -0.0001 +vn 0.7272 0.1192 -0.6760 +vn 0.7272 0.1192 -0.6759 +vn -0.7272 0.1191 -0.6760 +vn -0.7272 0.1192 -0.6760 +vn 0.7273 -0.5257 -0.4412 +vn 0.7272 0.4412 0.5258 +vn -0.7272 0.4412 0.5258 +vn 0.7272 0.4412 -0.5258 +vn -0.7273 -0.6759 -0.1193 +vn -0.7273 0.6759 0.1193 +vn 0.7273 0.6759 -0.1193 +vn -0.7273 -0.0001 -0.6863 +vn 0.7273 -0.0001 0.6863 +vn -0.7273 0.0001 0.6863 +vn 0.7273 0.0001 -0.6863 +vn 0.7273 -0.1193 -0.6759 +vn -0.7273 0.1193 -0.6759 +vn 0.7272 0.6864 -0.0000 +vn 0.7272 0.6864 0.0001 +vn -0.7272 0.6864 -0.0000 +vn -0.7272 0.6864 -0.0001 +vn -0.7272 -0.4412 -0.5258 +vn 0.7272 -0.6760 -0.1192 +vn 0.7272 -0.6759 -0.1192 +vn -0.7272 -0.6760 -0.1192 +vn -0.7272 -0.6760 -0.1191 +vn 0.7272 -0.6760 0.1192 +vn 0.7272 -0.6760 0.1191 +vn -0.7272 -0.6760 0.1192 +vn -0.7272 -0.6759 0.1192 +vn 0.7272 -0.4412 0.5258 +vn -0.7272 -0.4412 0.5258 +vn 0.7272 0.6760 0.1192 +vn 0.7272 0.6759 0.1192 +vn -0.7272 0.6760 0.1192 +vn -0.7272 0.6760 0.1191 +vn 0.7272 0.6760 -0.1192 +vn 0.7272 0.6760 -0.1191 +vn -0.7272 0.6760 -0.1192 +vn -0.7272 0.6759 -0.1192 +vn -0.7272 -0.3432 0.5944 +vn -0.7272 0.4412 -0.5258 +vn 0.7272 -0.4412 -0.5258 +vn -0.7272 -0.3432 -0.5944 +vn -0.7272 -0.5258 0.4412 +vn 0.7272 0.3432 0.5944 +vn 0.7272 0.5258 0.4412 +vn 0.7272 0.3432 -0.5944 +s 0 +f 1//1 2//2 3//3 +f 4//4 5//3 6//3 +f 7//5 8//6 9//3 +f 9//3 8//6 10//3 +f 11//7 12//3 13//3 +f 14//8 15//3 16//3 +f 17//9 18//10 19//3 +f 20//11 21//12 22//3 +f 23//13 24//14 25//3 +f 26//15 27//16 28//3 +f 29//17 30//18 31//3 +f 32//19 33//20 34//3 +f 35//21 36//22 37//3 +f 38//23 39//24 40//25 +f 36//22 41//26 37//3 +f 37//3 41//26 42//1 +f 37//3 42//1 43//3 +f 43//3 42//1 44//2 +f 44//2 45//27 43//3 +f 43//3 45//27 46//28 +f 43//3 46//23 47//29 +f 40//25 48//30 38//31 +f 38//28 48//32 49//33 +f 38//31 49//33 50//27 +f 50//27 49//34 51//35 +f 50//36 51//35 52//2 +f 52//37 51//35 53//38 +f 52//2 53//39 54//40 +f 54//40 53//38 55//41 +f 54//1 55//41 56//26 +f 56//42 55//41 57//12 +f 58//17 59//43 37//3 +f 37//3 59//18 60//44 +f 60//45 61//46 37//3 +f 37//3 61//46 62//47 +f 37//3 62//47 35//21 +f 57//12 63//48 56//49 +f 56//26 63//13 64//14 +f 56//42 64//14 65//50 +f 65//50 66//51 56//42 +f 56//26 66//52 67//53 +f 56//26 67//54 68//55 +f 47//29 69//56 43//3 +f 43//3 69//56 70//57 +f 43//3 70//57 71//3 +f 72//58 73//19 38//23 +f 73//59 74//60 38//31 +f 38//31 74//20 75//61 +f 38//23 75//61 39//24 +f 70//57 76//62 71//3 +f 71//3 76//62 77//15 +f 71//3 77//63 78//16 +f 32//19 34//3 79//64 +f 80//65 81//17 10//3 +f 10//3 81//17 82//18 +f 10//3 82//43 9//3 +f 9//3 82//18 83//45 +f 9//3 83//45 84//46 +f 84//46 85//47 9//3 +f 9//3 85//47 86//21 +f 9//3 86//21 87//22 +f 31//3 88//27 89//23 +f 89//28 90//29 31//3 +f 31//3 90//29 91//56 +f 31//3 91//56 92//57 +f 92//57 93//62 31//3 +f 31//3 93//62 94//63 +f 31//3 94//63 34//3 +f 34//3 94//15 95//66 +f 34//3 95//16 79//64 +f 87//22 96//26 9//3 +f 9//3 96//42 97//1 +f 9//3 97//1 31//3 +f 31//3 97//1 98//2 +f 31//3 98//2 88//27 +f 99//24 100//25 101//3 +f 99//24 101//3 102//67 +f 100//25 103//30 101//3 +f 101//3 103//30 104//33 +f 101//3 104//33 105//68 +f 106//38 107//41 108//69 +f 109//50 110//52 10//3 +f 10//3 110//52 111//53 +f 10//3 111//53 80//55 +f 107//41 112//70 108//71 +f 108//72 112//73 113//13 +f 108//71 113//13 114//14 +f 28//3 115//46 116//47 +f 117//57 118//74 12//3 +f 12//3 118//62 119//15 +f 12//3 119//15 13//3 +f 13//3 119//15 120//16 +f 13//3 120//66 121//64 +f 122//55 123//17 124//3 +f 124//3 123//17 125//18 +f 124//3 125//18 28//3 +f 28//3 125//18 126//44 +f 28//3 126//44 115//75 +f 116//47 127//21 28//3 +f 28//3 127//21 128//22 +f 28//3 128//22 129//49 +f 130//31 131//29 12//3 +f 12//3 131//29 132//56 +f 12//3 132//56 117//57 +f 129//42 133//1 28//3 +f 28//3 133//1 134//2 +f 28//3 134//2 12//3 +f 12//3 134//2 135//27 +f 12//3 135//27 130//23 +f 136//50 137//52 124//3 +f 124//3 137//52 138//54 +f 124//3 138//53 122//55 +f 139//67 140//24 141//76 +f 121//64 142//59 13//3 +f 13//3 142//19 143//20 +f 13//3 143//20 139//67 +f 144//13 145//14 146//3 +f 140//77 147//25 141//78 +f 141//78 147//25 148//30 +f 141//79 148//30 149//34 +f 144//13 146//3 150//12 +f 149//80 151//35 141//78 +f 141//76 151//35 152//38 +f 141//76 152//38 146//3 +f 146//3 152//38 153//11 +f 146//3 153//41 150//12 +f 154//75 155//47 156//3 +f 154//46 156//3 157//45 +f 155//47 158//21 156//3 +f 156//3 158//21 159//22 +f 156//3 159//22 160//42 +f 160//42 161//40 156//3 +f 156//3 161//1 162//2 +f 156//3 162//2 163//3 +f 163//3 162//2 164//27 +f 163//3 164//27 165//31 +f 165//23 166//29 163//3 +f 163//3 166//81 167//56 +f 163//3 167//56 168//57 +f 169//62 170//63 171//3 +f 171//3 170//15 172//16 +f 171//3 172//16 173//64 +f 174//19 175//60 176//3 +f 176//3 175//60 177//67 +f 176//3 177//67 178//24 +f 179//12 180//13 34//3 +f 34//3 180//13 181//14 +f 34//3 181//14 182//50 +f 182//50 183//52 34//3 +f 34//3 183//51 184//53 +f 34//3 184//54 31//3 +f 31//3 184//82 185//55 +f 31//3 185//55 29//17 +f 178//24 186//25 176//3 +f 176//3 186//25 187//30 +f 176//3 187//32 188//80 +f 188//34 189//35 176//3 +f 176//3 189//35 190//83 +f 176//3 190//38 34//3 +f 34//3 190//38 191//41 +f 34//3 191//41 179//12 +f 26//15 28//3 192//62 +f 193//45 194//46 195//3 +f 194//46 196//47 195//3 +f 195//3 196//47 197//21 +f 195//3 197//21 198//84 +f 199//3 200//36 201//23 +f 198//22 202//42 195//3 +f 195//3 202//26 203//1 +f 195//3 203//40 199//3 +f 199//3 203//1 204//2 +f 199//3 204//2 200//27 +f 201//23 205//29 199//3 +f 199//3 205//81 206//56 +f 199//3 206//56 207//57 +f 208//67 209//24 124//3 +f 210//70 211//48 212//3 +f 213//54 214//55 215//3 +f 215//3 214//55 216//17 +f 215//3 216//17 217//18 +f 27//16 218//64 28//3 +f 28//3 218//64 219//59 +f 28//3 219//59 124//3 +f 124//3 219//19 220//60 +f 124//3 220//20 208//61 +f 211//13 221//14 212//3 +f 212//3 221//14 222//50 +f 212//3 222//50 223//52 +f 209//24 224//25 124//3 +f 124//3 224//25 225//30 +f 124//3 225//30 226//33 +f 226//33 227//35 124//3 +f 124//3 227//35 228//38 +f 124//3 228//38 212//3 +f 212//3 228//39 229//41 +f 212//3 229//41 210//73 +f 230//85 231//2 232//27 +f 233//29 234//86 235//34 +f 236//41 237//12 238//1 +f 235//33 234//56 239//32 +f 238//40 237//12 240//42 +f 241//22 242//26 243//87 +f 244//19 245//60 234//56 +f 234//56 245//20 246//67 +f 230//85 232//27 247//88 +f 247//88 232//36 248//23 +f 247//88 248//31 249//29 +f 249//29 250//56 247//89 +f 247//88 250//56 251//90 +f 247//89 251//57 252//62 +f 246//67 253//24 234//56 +f 234//86 253//24 254//25 +f 234//86 254//25 239//30 +f 236//11 238//1 255//38 +f 255//38 238//1 256//2 +f 255//38 256//2 257//35 +f 257//35 256//2 258//27 +f 257//35 258//27 235//33 +f 235//33 258//36 259//23 +f 235//34 259//31 233//29 +f 260//3 261//47 262//21 +f 263//14 264//50 260//3 +f 260//3 264//50 265//52 +f 243//87 242//49 230//85 +f 230//91 242//26 266//1 +f 230//85 266//1 231//2 +f 252//74 267//15 247//88 +f 247//88 267//63 268//16 +f 247//89 268//16 269//64 +f 263//14 260//3 270//13 +f 270//48 260//3 262//21 +f 270//48 262//21 237//12 +f 237//73 262//92 271//22 +f 237//73 271//22 240//26 +f 272//46 273//47 243//93 +f 243//93 273//94 274//21 +f 243//93 274//21 241//22 +f 275//17 276//18 243//93 +f 243//87 276//18 277//44 +f 243//87 277//45 272//46 +f 265//52 278//54 260//3 +f 260//3 278//54 279//55 +f 260//3 279//55 275//17 +f 280//3 281//45 260//3 +f 260//3 281//44 282//46 +f 260//3 282//75 261//47 +f 283//55 284//17 280//3 +f 280//3 284//17 285//18 +f 280//3 285//18 281//45 +f 286//54 287//3 288//51 +f 288//51 287//3 25//3 +f 288//51 25//3 289//50 +f 289//50 25//3 24//14 +f 290//30 291//33 292//3 +f 291//33 293//68 292//3 +f 292//3 293//35 294//38 +f 292//3 294//38 295//3 +f 295//3 294//38 296//41 +f 295//3 296//41 297//12 +f 298//25 299//3 300//24 +f 300//24 299//3 301//3 +f 302//62 303//15 19//3 +f 304//3 305//20 301//3 +f 301//3 305//60 306//67 +f 301//3 306//61 300//24 +f 303//15 307//16 19//3 +f 19//3 307//66 308//64 +f 19//3 308//64 304//3 +f 304//3 308//64 309//19 +f 304//3 309//19 305//60 +f 302//74 310//3 311//57 +f 311//57 310//3 234//56 +f 68//55 58//95 56//42 +f 56//26 58//17 37//3 +f 56//42 37//3 312//22 +f 312//22 37//3 313//3 +f 314//18 315//45 316//3 +f 315//45 317//46 316//3 +f 316//3 317//46 318//47 +f 316//3 318//47 313//3 +f 313//3 318//47 319//21 +f 313//3 319//21 312//22 +f 314//18 316//3 320//96 +f 320//17 316//3 321//3 +f 320//96 321//3 322//55 +f 22//3 21//12 323//3 +f 323//3 21//73 324//13 +f 323//3 324//13 325//97 +f 325//14 326//50 323//3 +f 323//3 326//50 327//51 +f 323//3 327//52 321//3 +f 321//3 327//52 328//53 +f 321//3 328//54 322//55 +f 20//41 22//3 329//38 +f 329//38 22//3 330//3 +f 329//38 330//3 331//98 +f 331//99 330//3 332//3 +f 331//98 332//3 333//100 +f 334//27 335//31 336//3 +f 337//47 338//21 339//60 +f 339//60 338//21 340//22 +f 340//22 341//42 339//60 +f 339//60 341//42 342//1 +f 339//101 342//1 343//2 +f 335//23 344//29 336//3 +f 336//3 344//81 345//56 +f 336//3 345//56 346//57 +f 346//57 347//62 336//3 +f 336//3 347//62 348//63 +f 336//3 348//15 349//16 +f 350//3 351//67 352//24 +f 353//14 332//3 354//13 +f 354//48 332//3 355//73 +f 352//24 356//102 350//3 +f 350//3 356//25 357//30 +f 350//3 357//30 358//34 +f 359//64 360//19 350//3 +f 350//3 360//19 361//20 +f 350//3 361//60 351//67 +f 358//33 362//35 350//3 +f 350//3 362//35 363//38 +f 350//3 363//38 332//3 +f 332//3 363//38 364//11 +f 332//3 364//41 355//12 +f 353//97 365//50 332//3 +f 332//3 365//103 366//52 +f 332//3 366//52 333//100 +f 333//100 366//52 367//54 +f 333//100 367//54 368//55 +f 337//47 339//101 369//46 +f 369//46 339//20 370//104 +f 369//46 370//61 371//44 +f 371//45 370//67 372//77 +f 371//45 372//24 373//18 +f 373//18 372//24 374//25 +f 373//18 374//102 375//17 +f 375//17 374//25 376//30 +f 375//17 376//32 368//55 +f 368//55 376//30 377//105 +f 368//65 377//105 333//100 +f 378//56 379//57 380//3 +f 380//3 379//57 381//62 +f 380//3 381//62 382//15 +f 383//16 384//64 336//3 +f 343//2 334//27 339//60 +f 339//101 334//27 336//3 +f 339//20 336//3 385//19 +f 385//19 336//3 384//64 +f 78//16 72//64 71//3 +f 71//3 72//64 38//31 +f 71//3 38//23 386//3 +f 386//3 38//23 387//29 +f 302//62 19//3 310//3 +f 310//3 19//3 18//10 +f 310//3 18//10 388//106 +f 388//106 389//107 310//3 +f 310//3 389//108 247//88 +f 310//3 247//89 234//56 +f 234//56 247//88 269//64 +f 234//56 269//64 244//19 +f 17//109 19//3 390//110 +f 390//110 19//3 391//3 +f 390//110 391//3 392//111 +f 392//112 391//3 393//3 +f 392//111 393//3 394//113 +f 395//41 396//73 397//3 +f 398//43 399//44 400//3 +f 401//31 402//114 403//27 +f 403//27 402//114 404//115 +f 403//27 404//116 405//2 +f 406//30 407//34 408//3 +f 408//3 407//33 409//35 +f 408//3 409//35 397//3 +f 397//3 409//35 410//38 +f 397//3 410//38 395//41 +f 398//18 400//3 411//17 +f 401//31 412//29 402//117 +f 402//114 412//29 413//56 +f 402//114 413//86 414//57 +f 414//57 415//62 402//118 +f 402//118 415//62 416//119 +f 402//114 416//15 417//16 +f 418//67 419//24 408//3 +f 408//3 419//24 420//25 +f 408//3 420//102 406//30 +f 396//12 421//13 397//3 +f 397//3 421//13 422//14 +f 397//3 422//14 423//50 +f 399//45 424//46 400//3 +f 400//3 424//75 425//47 +f 400//3 425//47 426//21 +f 426//21 427//22 400//3 +f 400//3 427//22 428//42 +f 400//3 428//26 429//1 +f 430//64 431//19 408//3 +f 408//3 431//19 432//60 +f 408//3 432//60 418//67 +f 423//50 433//52 397//3 +f 397//3 433//51 434//53 +f 397//3 434//53 435//55 +f 417//16 430//120 402//121 +f 402//114 430//64 408//3 +f 402//114 408//3 436//122 +f 436//123 408//3 437//124 +f 438//3 439//125 440//3 +f 440//3 439//126 441//127 +f 440//3 441//127 442//128 +f 443//129 444//130 438//3 +f 438//3 444//130 445//131 +f 438//3 445//132 439//125 +f 139//67 141//79 13//3 +f 13//3 141//76 446//133 +f 13//3 446//133 11//7 +f 447//134 448//135 449//3 +f 449//3 448//136 450//137 +f 449//3 450//138 451//3 +f 451//3 450//138 452//139 +f 451//3 452//139 453//3 +f 453//3 452//139 454//140 +f 453//3 454//141 146//3 +f 146//3 454//140 455//142 +f 146//3 455//143 141//79 +f 456//25 457//30 458//144 +f 459//27 460//23 461//3 +f 461//3 460//23 462//29 +f 463//38 464//145 465//68 +f 465//35 464//145 458//146 +f 465//35 458//144 466//33 +f 466//33 458//144 457//30 +f 467//22 468//49 469//3 +f 469//3 468//26 470//1 +f 469//3 470//1 461//3 +f 461//3 470//1 471//2 +f 461//3 471//37 459//27 +f 463//38 472//11 464//145 +f 464//145 472//11 473//73 +f 464//145 473//12 474//147 +f 474//147 473//12 475//13 +f 462//29 476//56 461//3 +f 461//3 476//56 477//57 +f 461//3 477//57 478//62 +f 479//19 480//20 458//144 +f 481//18 482//44 469//3 +f 469//3 482//44 483//46 +f 480//60 484//67 458//146 +f 458//144 484//67 485//24 +f 458//146 485//24 456//25 +f 483//75 486//47 469//3 +f 469//3 486//47 487//21 +f 469//3 487//21 467//22 +f 478//62 488//119 461//3 +f 461//3 488//63 489//16 +f 461//3 489//16 490//58 +f 475//13 491//14 474//148 +f 474//147 491//14 492//103 +f 474//147 492//50 493//51 +f 447//134 449//3 494//149 +f 494//149 449//3 495//3 +f 494//150 495//3 496//151 +f 496//151 495//3 461//3 +f 496//151 461//3 458//144 +f 458//144 461//3 490//64 +f 458//144 490//64 479//19 +f 493//52 497//53 474//147 +f 474//148 497//54 498//65 +f 474//147 498//55 499//17 +f 500//152 501//153 502//3 +f 502//3 501//153 503//154 +f 502//3 503//154 504//3 +f 504//3 503//155 474//147 +f 504//3 474//148 469//3 +f 469//3 474//147 499//17 +f 469//3 499//17 481//18 +f 500//156 502//3 505//157 +f 505//158 502//3 506//3 +f 505//158 506//3 507//159 +f 507//160 506//3 508//161 +f 508//162 506//3 509//3 +f 508//161 509//3 510//163 +f 510//163 509//3 101//3 +f 510//163 101//3 108//72 +f 108//71 101//3 105//35 +f 108//69 105//35 106//38 +f 114//14 109//50 108//69 +f 108//69 109//50 10//3 +f 108//69 10//3 511//164 +f 511//164 10//3 8//6 +f 512//16 513//64 514//3 +f 515//2 516//27 517//3 +f 518//56 519//57 517//3 +f 517//3 519//57 520//62 +f 517//3 520//62 521//15 +f 516//27 522//23 517//3 +f 517//3 522//23 523//29 +f 517//3 523//29 518//86 +f 524//21 525//165 526//47 +f 526//94 525//166 527//167 +f 526//47 527//168 528//46 +f 529//169 530//18 527//167 +f 527//167 530//18 531//44 +f 527//167 531//44 528//46 +f 524//21 532//22 525//166 +f 525//166 532//84 533//26 +f 525//165 533//42 534//1 +f 513//64 535//19 514//3 +f 514//3 535//19 536//60 +f 514//3 536//60 537//67 +f 529//169 538//52 539//54 +f 539//82 540//55 529//170 +f 529//171 540//55 541//17 +f 529//169 541//17 530//18 +f 538//52 529//171 542//50 +f 542//50 529//171 543//172 +f 542//50 543//173 544//14 +f 537//61 545//24 514//3 +f 514//3 545//24 546//25 +f 514//3 546//25 547//30 +f 548//41 549//73 543//172 +f 543//173 549//73 550//13 +f 543//173 550//13 544//97 +f 547//30 551//33 514//3 +f 514//3 551//34 552//35 +f 514//3 552//35 543//172 +f 543//173 552//35 553//38 +f 543//173 553//83 548//41 +f 534//1 515//2 525//165 +f 525//165 515//2 517//3 +f 525//165 517//3 554//174 +f 554//174 517//3 555//175 +f 556//3 557//176 558//177 +f 4//178 559//179 5//3 +f 5//3 559//179 560//2 +f 5//3 560//2 561//27 +f 5//3 562//63 563//66 +f 564//20 565//3 566//19 +f 566//19 565//3 567//120 +f 561//27 568//31 5//3 +f 5//3 568//23 569//29 +f 5//3 569//29 570//56 +f 570//56 571//57 5//3 +f 5//3 571//180 572//74 +f 5//3 572//62 562//15 +f 564//20 573//61 565//3 +f 565//3 573//67 574//24 +f 565//3 574//24 575//25 +f 576//41 556//3 577//38 +f 577//38 556//3 565//3 +f 577//38 565//3 578//35 +f 575//25 579//30 565//3 +f 565//3 579//30 580//33 +f 565//3 580//34 578//35 +f 576//41 581//12 556//3 +f 556//3 581//73 582//13 +f 556//3 582//13 583//97 +f 583//14 584//50 556//3 +f 556//3 584//50 585//52 +f 556//3 585//52 586//53 +f 587//45 588//46 557//181 +f 557//181 588//46 589//47 +f 557//176 589//47 590//21 +f 590//21 591//22 557//176 +f 557//182 591//22 592//26 +f 557//176 592//42 559//183 +f 559//183 592//26 593//1 +f 559//179 593//1 560//2 +f 586//54 594//65 556//3 +f 556//3 594//55 595//17 +f 556//3 595//17 557//176 +f 557//176 595//96 596//18 +f 557//176 596//43 587//45 +f 597//184 598//3 599//185 +f 599//185 598//3 600//3 +f 275//17 243//93 260//3 +f 260//3 243//87 601//186 +f 260//3 601//187 280//3 +f 280//3 601//186 602//188 +f 280//3 602//189 600//3 +f 600//3 602//188 603//190 +f 600//3 603//191 599//185 +f 604//192 7//5 605//3 +f 605//3 7//193 9//3 +f 605//3 9//3 156//3 +f 156//3 9//3 31//3 +f 156//3 31//3 157//44 +f 157//45 31//3 30//43 +f 606//31 607//29 600//3 +f 608//30 609//33 610//3 +f 611//14 612//3 613//13 +f 613//13 612//3 614//73 +f 615//22 616//26 598//3 +f 609//33 617//35 610//3 +f 610//3 617//35 618//38 +f 610//3 618//38 612//3 +f 612//3 618//38 619//41 +f 612//3 619//41 614//12 +f 616//42 620//40 598//3 +f 598//3 620//1 621//2 +f 598//3 621//2 600//3 +f 600//3 621//2 622//27 +f 600//3 622//36 606//31 +f 600//3 623//62 624//63 +f 611//194 625//50 612//3 +f 612//3 625//50 626//51 +f 612//3 626//52 627//54 +f 628//44 629//46 598//3 +f 607//29 630//56 600//3 +f 600//3 630//86 631//57 +f 600//3 631//57 623//62 +f 632//16 633//64 610//3 +f 633//64 634//19 610//3 +f 610//3 634//19 635//60 +f 610//3 635//60 636//67 +f 636//67 637//24 610//3 +f 610//3 637//24 638//25 +f 610//3 638//25 608//32 +f 627//54 639//55 612//3 +f 612//3 639//55 640//17 +f 612//3 640//96 598//3 +f 598//3 640//17 641//18 +f 598//3 641//18 628//45 +f 629//46 642//47 598//3 +f 598//3 642//47 643//21 +f 598//3 643//21 615//84 +f 558//195 555//175 556//3 +f 556//3 555//175 517//3 +f 556//3 517//3 565//3 +f 565//3 517//3 644//3 +f 565//3 644//3 645//3 +f 645//3 644//3 646//3 +f 645//3 646//3 647//3 +f 647//3 646//3 648//3 +f 647//3 648//3 313//3 +f 521//63 512//66 517//3 +f 517//3 512//66 514//3 +f 517//3 514//3 644//3 +f 644//3 514//3 649//3 +f 644//3 649//3 646//3 +f 646//3 649//3 650//3 +f 646//3 650//3 648//3 +f 648//3 650//3 651//3 +f 543//173 604//192 514//3 +f 514//3 604//192 605//3 +f 514//3 605//3 649//3 +f 649//3 605//3 156//3 +f 649//3 156//3 650//3 +f 650//3 156//3 163//3 +f 650//3 163//3 651//3 +f 651//3 163//3 652//3 +f 653//31 654//81 655//3 +f 656//15 657//16 502//3 +f 654//29 658//56 655//3 +f 655//3 658//56 659//57 +f 655//3 659//57 660//62 +f 657//16 661//64 502//3 +f 502//3 661//64 662//59 +f 502//3 662//19 663//60 +f 664//33 502//3 665//30 +f 665//30 502//3 666//25 +f 663//20 667//67 502//3 +f 502//3 667//61 668//24 +f 502//3 668//24 666//25 +f 669//46 670//94 509//3 +f 664//33 671//35 502//3 +f 502//3 671//35 672//38 +f 502//3 672//38 506//3 +f 506//3 672//38 673//41 +f 506//3 673//41 674//73 +f 674//12 675//13 506//3 +f 506//3 675//48 676//14 +f 506//3 676//14 677//50 +f 677//50 678//52 506//3 +f 506//3 678//51 679//54 +f 506//3 679//53 680//55 +f 680//55 681//17 506//3 +f 506//3 681//17 682//43 +f 506//3 682//18 509//3 +f 509//3 682//18 683//45 +f 509//3 683//196 669//46 +f 670//47 684//21 509//3 +f 509//3 684//92 685//84 +f 509//3 685//22 686//26 +f 686//26 687//1 509//3 +f 509//3 687//1 688//2 +f 509//3 688//2 655//3 +f 655//3 688//2 689//27 +f 655//3 689//27 653//31 +f 624//63 632//16 600//3 +f 600//3 632//66 610//3 +f 600//3 610//3 280//3 +f 280//3 610//3 287//3 +f 280//3 287//3 283//65 +f 283//55 287//3 286//53 +f 690//15 321//3 691//62 +f 691//62 321//3 692//57 +f 693//2 694//27 321//3 +f 321//3 694//27 695//31 +f 651//3 696//18 697//45 +f 695//31 698//29 321//3 +f 321//3 698//29 699//56 +f 321//3 699//56 692//57 +f 690//15 700//16 321//3 +f 321//3 700//16 701//64 +f 321//3 701//64 323//3 +f 323//3 701//64 702//19 +f 323//3 702//59 703//60 +f 703//20 704//67 323//3 +f 323//3 704//61 705//24 +f 323//3 705//24 706//25 +f 706//25 707//32 323//3 +f 323//3 707//30 708//33 +f 323//3 708//34 709//35 +f 709//35 710//38 323//3 +f 323//3 710//38 711//41 +f 323//3 711//41 652//3 +f 652//3 711//41 712//12 +f 652//3 712//73 713//13 +f 713//13 714//14 652//3 +f 652//3 714//97 715//50 +f 652//3 715//50 716//52 +f 697//45 717//46 651//3 +f 651//3 717//46 718//47 +f 651//3 718//47 719//21 +f 719//21 720//84 651//3 +f 651//3 720//22 721//42 +f 651//3 721//42 722//1 +f 313//3 648//3 316//3 +f 316//3 648//3 651//3 +f 316//3 651//3 321//3 +f 321//3 651//3 722//1 +f 321//3 722//1 693//2 +f 716//52 723//54 652//3 +f 652//3 723//53 724//55 +f 652//3 724//65 651//3 +f 651//3 724//55 725//17 +f 651//3 725//96 696//18 +f 597//184 726//197 598//3 +f 598//3 726//198 4//4 +f 598//3 4//199 612//3 +f 612//3 4//199 6//3 +f 612//3 6//3 610//3 +f 610//3 6//3 727//3 +f 610//3 727//3 287//3 +f 287//3 727//3 728//3 +f 287//3 728//3 25//3 +f 25//3 728//3 295//3 +f 25//3 295//3 23//13 +f 23//13 295//3 297//73 +f 660//62 656//15 655//3 +f 655//3 656//63 502//3 +f 655//3 502//3 729//3 +f 729//3 502//3 504//3 +f 729//3 504//3 730//3 +f 730//3 504//3 469//3 +f 730//3 469//3 731//3 +f 731//3 469//3 461//3 +f 731//3 461//3 732//3 +f 732//3 461//3 495//3 +f 732//3 495//3 733//3 +f 733//3 495//3 449//3 +f 19//3 734//1 735//2 +f 736//31 737//29 391//3 +f 19//3 735//2 391//3 +f 391//3 735//2 738//27 +f 391//3 738//36 736//23 +f 737//29 739//56 391//3 +f 391//3 739//56 740//57 +f 391//3 740//57 741//62 +f 742//24 743//200 393//3 +f 393//3 743//25 744//30 +f 393//3 744//30 745//34 +f 746//41 304//3 747//38 +f 747//38 304//3 393//3 +f 747//38 393//3 748//35 +f 748//35 393//3 745//33 +f 746//41 749//12 304//3 +f 304//3 749//12 750//13 +f 304//3 750//48 751//14 +f 752//19 753//60 393//3 +f 393//3 753//60 754//67 +f 393//3 754//61 742//24 +f 755//21 756//22 19//3 +f 19//3 756//22 757//26 +f 19//3 757//26 734//40 +f 741//62 758//63 391//3 +f 391//3 758//15 759//16 +f 391//3 759//16 393//3 +f 393//3 759//16 760//64 +f 393//3 760//64 752//19 +f 751//14 761//50 304//3 +f 304//3 761//50 762//52 +f 304//3 762//52 763//54 +f 764//44 765//46 19//3 +f 19//3 765//46 766//47 +f 19//3 766//47 755//201 +f 763//54 767//55 304//3 +f 304//3 767//55 768//17 +f 304//3 768//17 19//3 +f 19//3 768//17 769//18 +f 19//3 769//18 764//44 +f 298//25 290//30 299//3 +f 299//3 290//30 292//3 +f 299//3 292//3 301//3 +f 301//3 292//3 770//3 +f 301//3 770//3 304//3 +f 304//3 770//3 771//3 +f 304//3 771//3 393//3 +f 393//3 771//3 772//3 +f 393//3 772//3 394//202 +f 394//113 772//3 400//3 +f 394//203 400//3 404//116 +f 404//116 400//3 429//1 +f 404//115 429//1 405//2 +f 168//57 169//62 163//3 +f 163//3 169//74 171//3 +f 163//3 171//3 652//3 +f 652//3 171//3 773//3 +f 652//3 773//3 323//3 +f 323//3 773//3 774//3 +f 323//3 774//3 22//3 +f 22//3 774//3 775//3 +f 22//3 775//3 330//3 +f 330//3 775//3 776//3 +f 330//3 776//3 332//3 +f 332//3 776//3 777//3 +f 332//3 777//3 350//3 +f 350//3 777//3 778//3 +f 350//3 778//3 195//3 +f 195//3 778//3 215//3 +f 195//3 215//3 193//44 +f 193//45 215//3 217//18 +f 173//64 174//19 171//3 +f 171//3 174//19 176//3 +f 171//3 176//3 773//3 +f 773//3 176//3 779//3 +f 773//3 779//3 774//3 +f 774//3 779//3 780//3 +f 774//3 780//3 775//3 +f 775//3 780//3 781//3 +f 775//3 781//3 776//3 +f 776//3 781//3 782//3 +f 776//3 782//3 777//3 +f 777//3 782//3 783//3 +f 777//3 783//3 778//3 +f 778//3 783//3 784//3 +f 778//3 784//3 215//3 +f 215//3 784//3 212//3 +f 215//3 212//3 213//53 +f 213//54 212//3 223//52 +f 453//3 785//27 786//31 +f 786//31 787//29 453//3 +f 453//3 787//29 788//56 +f 453//3 788//56 789//57 +f 790//25 791//32 451//3 +f 451//3 791//30 792//33 +f 793//16 451//3 794//63 +f 794//15 451//3 453//3 +f 794//119 453//3 795//62 +f 795//62 453//3 789//57 +f 793//66 796//64 451//3 +f 451//3 796//64 797//19 +f 451//3 797//19 798//20 +f 799//46 800//47 733//3 +f 733//3 800//47 801//21 +f 733//3 801//21 802//22 +f 798//60 803//61 451//3 +f 451//3 803//67 804//24 +f 451//3 804//24 790//25 +f 805//12 806//13 449//3 +f 449//3 806//13 807//14 +f 449//3 807//14 808//50 +f 802//22 809//26 733//3 +f 733//3 809//26 810//1 +f 733//3 810//1 453//3 +f 453//3 810//1 811//2 +f 453//3 811//2 785//27 +f 792//34 812//35 451//3 +f 451//3 812//35 813//38 +f 451//3 813//38 449//3 +f 449//3 813//38 814//41 +f 449//3 814//41 805//12 +f 808//50 815//51 449//3 +f 449//3 815//51 816//54 +f 449//3 816//54 817//55 +f 817//65 818//17 449//3 +f 449//3 818//17 819//18 +f 449//3 819//18 733//3 +f 733//3 819//18 820//44 +f 733//3 820//45 799//46 +f 563//16 567//64 5//3 +f 5//3 567//64 565//3 +f 5//3 565//3 6//3 +f 6//3 565//3 645//3 +f 6//3 645//3 727//3 +f 727//3 645//3 647//3 +f 727//3 647//3 728//3 +f 728//3 647//3 313//3 +f 728//3 313//3 295//3 +f 295//3 313//3 37//3 +f 295//3 37//3 292//3 +f 292//3 37//3 43//3 +f 292//3 43//3 770//3 +f 770//3 43//3 71//3 +f 770//3 71//3 771//3 +f 771//3 71//3 386//3 +f 771//3 386//3 772//3 +f 772//3 386//3 821//3 +f 772//3 821//3 400//3 +f 400//3 821//3 397//3 +f 400//3 397//3 411//17 +f 411//96 397//3 435//55 +f 33//60 102//67 34//3 +f 34//3 102//67 101//3 +f 34//3 101//3 176//3 +f 176//3 101//3 509//3 +f 176//3 509//3 779//3 +f 779//3 509//3 655//3 +f 779//3 655//3 780//3 +f 780//3 655//3 729//3 +f 780//3 729//3 781//3 +f 781//3 729//3 730//3 +f 781//3 730//3 782//3 +f 782//3 730//3 731//3 +f 782//3 731//3 783//3 +f 783//3 731//3 732//3 +f 783//3 732//3 784//3 +f 784//3 732//3 733//3 +f 784//3 733//3 212//3 +f 212//3 733//3 453//3 +f 212//3 453//3 124//3 +f 124//3 453//3 146//3 +f 124//3 146//3 136//50 +f 136//50 146//3 145//14 +f 387//29 378//56 386//3 +f 386//3 378//56 380//3 +f 386//3 380//3 821//3 +f 821//3 380//3 822//3 +f 821//3 822//3 397//3 +f 397//3 822//3 823//3 +f 397//3 823//3 408//3 +f 408//3 823//3 3//3 +f 382//63 383//16 380//3 +f 380//3 383//16 336//3 +f 380//3 336//3 822//3 +f 822//3 336//3 824//3 +f 822//3 824//3 823//3 +f 823//3 824//3 825//3 +f 823//3 825//3 3//3 +f 3//3 825//3 826//3 +f 207//57 192//74 199//3 +f 199//3 192//62 28//3 +f 199//3 28//3 16//3 +f 16//3 28//3 12//3 +f 16//3 12//3 14//204 +f 14//8 12//3 11//7 +f 827//64 438//3 828//16 +f 828//16 438//3 440//3 +f 828//16 440//3 829//15 +f 829//63 440//3 830//62 +f 831//27 832//31 440//3 +f 440//3 832//31 833//29 +f 834//52 835//54 826//3 +f 836//47 3//3 837//46 +f 837//46 3//3 838//45 +f 1//1 3//3 839//42 +f 437//124 408//3 442//205 +f 442//205 408//3 3//3 +f 442//128 3//3 440//3 +f 440//3 3//3 2//2 +f 440//3 2//2 831//27 +f 833//29 840//56 440//3 +f 440//3 840//56 841//57 +f 440//3 841//57 830//62 +f 827//64 842//19 438//3 +f 438//3 842//19 843//60 +f 438//3 843//60 844//67 +f 835//54 845//55 826//3 +f 826//3 845//55 846//17 +f 826//3 846//17 3//3 +f 3//3 846//17 847//18 +f 3//3 847//18 838//44 +f 844//67 848//24 438//3 +f 438//3 848//24 849//25 +f 438//3 849//25 850//32 +f 851//41 852//73 826//3 +f 826//3 852//12 853//13 +f 836//47 854//21 3//3 +f 3//3 854//92 855//22 +f 3//3 855//22 839//42 +f 853//13 856//14 826//3 +f 826//3 856//14 857//50 +f 826//3 857//50 834//51 +f 850//30 858//33 438//3 +f 438//3 858//33 859//68 +f 438//3 859//35 826//3 +f 826//3 859//68 860//38 +f 826//3 860//83 851//41 +f 349//16 359//58 336//3 +f 336//3 359//64 350//3 +f 336//3 350//3 824//3 +f 824//3 350//3 195//3 +f 824//3 195//3 825//3 +f 825//3 195//3 199//3 +f 825//3 199//3 826//3 +f 826//3 199//3 16//3 +f 826//3 16//3 438//3 +f 438//3 16//3 15//3 +f 438//3 15//3 443//129 +f 443//129 15//3 14//8 +f 861//206 862//206 863//206 +f 864//206 865//206 861//206 +f 866//207 867//206 868//208 +f 869//209 870//206 871//206 +f 872//210 873//211 874//206 +f 875//212 876//213 877//214 +f 878//215 879//206 880//216 +f 881//217 882//206 883//206 +f 884//218 885//219 886//206 +f 887//220 888//221 889//206 +f 890//222 891//223 892//206 +f 893//224 894//225 895//206 +f 896//226 897//227 898//206 +f 898//206 897//227 899//228 +f 898//206 899//228 900//229 +f 901//230 902//231 903//232 +f 903//232 902//233 904//234 +f 905//231 906//206 907//235 +f 907//235 906//206 908//236 +f 905//237 909//238 906//206 +f 906//206 909//238 910//239 +f 906//206 910//239 898//206 +f 898//206 910//239 911//240 +f 898//206 911//240 896//226 +f 912//241 913//242 914//243 +f 912//226 914//243 915//240 +f 915//240 914//244 916//245 +f 915//246 916//245 917//239 +f 917//247 916//245 918//213 +f 917//239 918//248 919//249 +f 919//249 918//213 920//250 +f 919//238 920//250 902//233 +f 902//231 920//250 921//251 +f 902//237 921//251 904//252 +f 900//229 922//253 898//206 +f 898//206 922//253 923//224 +f 898//206 923//254 924//255 +f 925//256 926//257 912//258 +f 912//226 926//257 927//259 +f 912//226 927//260 928//261 +f 928//262 929//263 912//258 +f 912//258 929//263 930//264 +f 912//226 930//264 913//265 +f 931//206 932//222 906//206 +f 906//206 932//266 933//223 +f 906//206 933//223 908//236 +f 901//230 934//267 902//231 +f 902//233 934//267 935//268 +f 902//233 935//269 936//270 +f 937//271 938//272 931//206 +f 931//206 938//272 939//273 +f 931//206 939//274 932//222 +f 940//275 941//271 942//206 +f 942//206 941//271 943//272 +f 942//206 943//272 895//206 +f 895//206 943//272 944//273 +f 895//206 944//273 945//266 +f 945//222 946//223 895//206 +f 895//206 946//223 947//236 +f 895//206 947//236 948//235 +f 948//235 949//237 895//206 +f 895//206 949//231 950//238 +f 895//206 950//238 951//239 +f 882//206 952//240 953//258 +f 953//226 954//227 882//206 +f 882//206 954//227 955//228 +f 882//206 955//228 956//229 +f 956//229 957//253 882//206 +f 882//206 957//253 958//224 +f 882//206 958//224 883//206 +f 883//206 958//224 959//255 +f 883//206 959//255 960//276 +f 961//261 962//263 878//277 +f 960//276 963//278 883//206 +f 883//206 963//257 964//260 +f 883//206 964//260 961//261 +f 962//263 965//264 878//279 +f 878//279 965//264 966//265 +f 878//215 966//265 967//244 +f 968//280 969//281 942//206 +f 942//206 969//281 970//269 +f 942//206 970//268 940//275 +f 967//282 971//245 878//215 +f 878//277 971//245 972//213 +f 878//277 972//213 879//206 +f 879//206 972//283 973//284 +f 879//206 973//284 974//251 +f 974//251 975//234 879//206 +f 879//206 975//234 976//232 +f 879//206 976//232 968//230 +f 977//206 978//228 979//229 +f 979//229 980//253 977//206 +f 977//206 980//285 981//254 +f 977//206 981//254 982//206 +f 982//206 981//224 983//225 +f 982//206 983//255 984//276 +f 985//270 986//271 870//206 +f 870//206 986//271 987//286 +f 870//206 987//286 871//206 +f 871//206 987//272 988//273 +f 871//206 988//274 989//222 +f 989//266 990//223 871//206 +f 871//206 990//223 991//236 +f 871//206 991//236 992//235 +f 992//235 993//233 871//206 +f 871//206 993//231 994//238 +f 871//206 994//238 977//206 +f 977//206 994//238 995//239 +f 977//206 995//239 996//240 +f 996//240 997//258 977//206 +f 977//206 997//241 998//227 +f 977//206 998//227 978//228 +f 984//276 999//257 982//206 +f 982//206 999//257 1000//260 +f 982//206 1000//259 1001//261 +f 1002//263 1003//264 1004//206 +f 1005//230 1006//281 870//206 +f 870//206 1006//281 1007//268 +f 870//206 1007//268 985//275 +f 1008//213 1009//250 1010//287 +f 1003//264 1011//265 1004//206 +f 1004//206 1011//265 1012//243 +f 1004//206 1012//243 1013//245 +f 1009//250 1014//288 1010//289 +f 1010//290 1014//291 1015//234 +f 1010//289 1015//234 1016//232 +f 893//224 895//206 1017//253 +f 1018//206 1019//272 1020//274 +f 1021//222 1022//223 863//206 +f 1023//233 1024//238 863//206 +f 1021//222 863//206 1020//274 +f 1025//229 1017//285 1026//206 +f 1026//206 1017//253 895//206 +f 1026//206 895//206 882//206 +f 882//206 895//206 951//239 +f 882//206 951//239 952//240 +f 1027//239 1028//240 1026//206 +f 1026//206 1028//246 1029//258 +f 1022//223 1030//236 863//206 +f 863//206 1030//236 1031//292 +f 863//206 1031//235 1023//231 +f 1029//258 1032//227 1026//206 +f 1026//206 1032//227 1033//228 +f 1026//206 1033//228 1025//229 +f 1034//281 1035//269 1036//206 +f 1037//261 1038//263 942//206 +f 1038//263 1039//264 942//206 +f 942//206 1039//264 1040//265 +f 942//206 1040//265 1041//243 +f 1035//269 1042//275 1018//206 +f 1018//206 1042//275 1043//271 +f 1018//206 1043//271 1019//272 +f 894//255 1044//276 895//206 +f 895//206 1044//276 1045//257 +f 895//206 1045//278 942//206 +f 942//206 1045//257 1046//259 +f 942//206 1046//260 1037//262 +f 1041//243 1047//245 942//206 +f 942//206 1047//245 1048//213 +f 942//206 1048//213 1036//206 +f 1048//248 1049//250 1036//206 +f 1036//206 1049//250 1050//291 +f 1036//206 1050//288 1051//252 +f 1051//234 1052//232 1036//206 +f 1036//206 1052//232 1053//230 +f 1036//206 1053//230 1034//281 +f 1054//271 1055//272 977//206 +f 977//206 1055//272 1056//274 +f 1057//266 1058//223 1059//206 +f 1060//206 1061//229 1062//253 +f 1057//222 1059//206 1056//274 +f 1058//223 1063//236 1059//206 +f 1059//206 1063//236 1064//292 +f 1059//206 1064//235 1065//231 +f 1065//231 1066//249 1059//206 +f 1059//206 1066//238 1067//239 +f 1059//206 1067//239 1060//206 +f 1060//206 1067//239 1068//240 +f 1060//206 1068//240 1069//226 +f 1069//258 1070//227 1060//206 +f 1060//206 1070//293 1071//228 +f 1060//206 1071//228 1061//229 +f 1072//224 1073//255 1074//206 +f 1074//206 1073//255 1075//276 +f 1074//206 1075//276 1076//257 +f 1077//267 1078//268 982//206 +f 1079//264 1080//265 1081//206 +f 1081//206 1080//242 1082//282 +f 982//206 1078//269 977//206 +f 977//206 1078//294 1083//275 +f 977//206 1083//270 1054//271 +f 1084//259 1085//261 1081//206 +f 1081//206 1085//261 1086//263 +f 1081//206 1086//263 1079//264 +f 1082//244 1087//245 1081//206 +f 1081//206 1087//245 1088//283 +f 1081//206 1088//213 982//206 +f 1088//213 1089//250 982//206 +f 982//206 1089//250 1090//251 +f 982//206 1090//251 1091//234 +f 1091//234 1092//232 982//206 +f 982//206 1092//232 1093//230 +f 982//206 1093//230 1077//281 +f 1094//228 1095//229 1096//206 +f 1097//295 1098//236 1099//296 +f 1100//227 1101//228 1102//297 +f 1103//236 1104//251 1105//252 +f 1106//226 1107//227 1108//244 +f 1103//298 1109//235 1104//291 +f 1104//291 1109//235 1110//233 +f 1104//251 1110//231 1111//249 +f 1106//258 1108//243 1112//246 +f 1112//240 1108//243 1113//245 +f 1112//240 1113//212 1114//239 +f 1114//239 1113//245 1115//213 +f 1114//239 1115//213 1111//238 +f 1111//238 1115//213 1116//284 +f 1111//238 1116//250 1104//251 +f 1105//234 1117//232 1103//298 +f 1103//298 1117//232 1118//230 +f 1103//236 1118//230 1119//281 +f 1120//238 1121//299 1122//233 +f 1122//237 1121//300 1099//301 +f 1122//233 1099//301 1123//235 +f 1123//235 1099//296 1098//236 +f 1120//238 1124//239 1121//300 +f 1121//300 1124//239 1125//240 +f 1121//300 1125//240 1102//302 +f 1102//302 1125//246 1126//258 +f 1102//302 1126//226 1100//227 +f 1101//228 1127//303 1102//297 +f 1102//297 1127//229 1128//253 +f 1102//302 1128//253 1129//224 +f 1107//227 1094//304 1108//244 +f 1108//243 1094//228 1096//206 +f 1108//244 1096//206 1130//265 +f 1130//265 1096//206 1131//264 +f 1119//281 1132//268 1103//236 +f 1103//298 1132//269 1133//275 +f 1103//236 1133//275 1134//271 +f 1135//272 1136//273 1099//301 +f 1099//301 1136//274 1137//266 +f 1099//296 1137//222 1097//223 +f 1138//259 1139//261 1096//206 +f 1096//206 1139//261 1140//263 +f 1096//206 1140//263 1131//264 +f 1129//254 1141//255 1102//302 +f 1102//297 1141//255 1142//276 +f 1102//297 1142//276 1096//206 +f 1096//206 1142//276 1143//257 +f 1096//206 1143//257 1138//259 +f 1144//266 1145//223 1146//206 +f 1146//206 1145//223 1103//236 +f 1146//206 1103//236 1099//296 +f 1099//301 1103//298 1134//271 +f 1099//296 1134//271 1135//272 +f 1144//222 1146//206 1147//273 +f 1147//274 1146//206 1148//206 +f 1147//274 1148//206 1149//272 +f 1150//206 1151//270 1148//206 +f 1148//206 1151//275 1152//271 +f 1148//206 1152//271 1149//286 +f 1153//206 1154//206 1155//232 +f 1155//232 1156//230 1153//206 +f 1153//206 1156//230 1157//267 +f 1153//206 1157//267 1150//206 +f 1150//206 1157//281 1158//268 +f 1150//206 1158//269 1151//275 +f 1159//305 1160//265 1161//206 +f 1160//265 1162//244 1161//206 +f 1161//206 1162//243 1163//245 +f 1161//206 1163//245 1164//206 +f 1164//206 1163//245 1165//213 +f 1165//213 1166//250 1164//206 +f 1164//206 1166//250 1167//251 +f 1164//206 1167//251 1168//234 +f 1169//206 1170//262 1171//263 +f 1172//257 1173//260 1174//206 +f 1175//253 1176//224 1177//206 +f 1177//206 1176//224 1178//255 +f 1172//257 1174//206 1179//276 +f 936//275 937//306 902//231 +f 902//233 937//271 931//206 +f 902//231 931//206 1180//235 +f 1180//235 931//206 1181//206 +f 1180//235 1181//206 1182//236 +f 1182//236 1181//206 891//223 +f 1183//271 1184//206 1185//275 +f 1185//275 1184//206 1186//268 +f 1183//271 1187//272 892//206 +f 892//206 1187//272 1188//273 +f 892//206 1188//274 890//222 +f 1189//206 1190//264 1191//265 +f 1192//275 1193//271 1184//206 +f 1191//242 1194//244 1189//206 +f 1189//206 1194//243 1195//245 +f 1189//206 1195//245 1196//206 +f 1196//206 1195//245 1197//213 +f 1196//206 1197//213 1198//250 +f 1196//206 1199//307 1200//230 +f 1193//306 1201//272 1184//206 +f 1184//206 1201//272 1202//274 +f 1184//206 1202//273 1203//222 +f 1203//222 1204//223 1184//206 +f 1184//206 1204//223 1205//236 +f 1184//206 1205//236 1206//292 +f 1207//308 1208//261 1189//206 +f 1189//206 1208//261 1209//309 +f 1189//206 1209//263 1190//310 +f 1198//250 1210//251 1196//206 +f 1196//206 1210//291 1211//234 +f 1196//206 1211//234 1199//232 +f 1200//230 1212//281 1196//206 +f 1196//206 1212//281 1213//269 +f 1196//206 1213//268 1192//275 +f 1214//239 1186//269 1215//238 +f 1215//238 1186//294 1184//206 +f 1215//238 1184//206 1216//233 +f 1216//231 1184//206 1206//235 +f 1214//239 1217//240 1186//294 +f 1186//269 1217//240 1218//258 +f 1186//269 1218//258 1219//227 +f 1219//227 1220//228 1186//269 +f 1186//269 1220//228 1221//229 +f 1186//294 1221//229 1222//281 +f 1222//281 1221//229 1223//253 +f 1222//281 1223//285 1224//230 +f 1224//311 1223//253 1225//254 +f 1224//230 1225//224 1226//232 +f 1226//312 1225//224 1227//255 +f 1226//307 1227//255 1228//276 +f 1207//259 1229//313 1230//257 +f 1230//257 1229//313 1231//314 +f 1230//257 1231//314 1228//276 +f 1228//276 1231//314 1232//234 +f 1228//276 1232//234 1226//232 +f 1207//259 1189//206 1229//313 +f 1229//313 1189//206 1233//206 +f 1229//315 1233//206 1234//316 +f 1235//206 1236//245 1233//206 +f 1233//206 1236//245 1237//213 +f 1233//206 1237//213 1234//316 +f 865//206 1238//259 1239//206 +f 1239//206 1238//260 1240//261 +f 1239//206 1240//262 1241//263 +f 1241//263 1242//264 1239//206 +f 1239//206 1242//310 1243//265 +f 1239//206 1243//242 1235//206 +f 1235//206 1243//265 1244//244 +f 1235//206 1244//243 1236//212 +f 1245//228 1246//229 864//206 +f 864//206 1246//229 1247//253 +f 864//206 1247//253 1248//224 +f 1248//224 1249//255 864//206 +f 864//206 1249//255 1250//317 +f 864//206 1250//276 865//206 +f 865//206 1250//317 1251//257 +f 865//206 1251//257 1238//259 +f 924//225 925//276 898//206 +f 898//206 925//276 912//226 +f 898//206 912//258 1252//206 +f 1252//206 912//258 1253//227 +f 1095//229 1175//285 1096//206 +f 1096//206 1175//253 1177//206 +f 1096//206 1177//206 1102//302 +f 1102//302 1177//206 1254//318 +f 1255//206 1256//319 1257//320 +f 1258//291 1259//206 1260//250 +f 1260//250 1259//206 1261//213 +f 1262//286 1263//273 1264//206 +f 1265//228 1266//229 1267//321 +f 1262//272 1264//206 1268//271 +f 1269//322 1264//206 1270//323 +f 1270//323 1264//206 1271//238 +f 1265//228 1267//321 1272//227 +f 1258//251 1273//234 1259//206 +f 1259//206 1273//234 1274//232 +f 1259//206 1274//232 1275//230 +f 1271//238 1276//239 1270//324 +f 1270//323 1276//239 1277//240 +f 1270//324 1277//240 1267//321 +f 1267//321 1277//240 1278//258 +f 1267//325 1278//226 1272//227 +f 1266//229 1279//253 1267//325 +f 1267//325 1279//253 1280//224 +f 1267//321 1280//224 1281//225 +f 1282//259 889//206 1283//278 +f 1283//257 889//206 1284//276 +f 1282//260 1285//261 889//206 +f 889//206 1285//261 1286//263 +f 889//206 1286//263 1287//264 +f 1287//310 1288//265 889//206 +f 889//206 1288//265 1289//244 +f 889//206 1289//243 1290//245 +f 1275//230 1291//281 1259//206 +f 1259//206 1291//267 1292//268 +f 1259//206 1292//268 1293//275 +f 1263//274 1294//222 1264//206 +f 1264//206 1294//266 1295//326 +f 1264//206 1295//223 1296//236 +f 1296//236 1297//235 1264//206 +f 1264//206 1297//235 1298//231 +f 1264//206 1298//233 1271//238 +f 1281//255 1284//317 1267//327 +f 1267//321 1284//276 889//206 +f 1267//321 889//206 1299//328 +f 1299//329 889//206 888//221 +f 1300//206 1301//232 1302//230 +f 1302//230 1303//267 1300//206 +f 1300//206 1303//281 1304//269 +f 1300//206 1304//269 1305//275 +f 1306//271 1307//272 1308//206 +f 1308//206 1307//286 1309//273 +f 1308//206 1309//274 1310//222 +f 1310//222 1311//223 1308//206 +f 1308//206 1311//223 1312//236 +f 1308//206 1312//298 1313//235 +f 1314//330 1315//228 1316//331 +f 1316//332 1315//228 1317//229 +f 1317//229 1318//253 1316//332 +f 1316//331 1318//253 1319//254 +f 1316//332 1319//254 1320//333 +f 1319//254 1321//255 1320//334 +f 1320//334 1321//255 1322//276 +f 1320//333 1322//276 1323//257 +f 1324//335 1325//310 1326//265 +f 1324//336 1327//213 1300//206 +f 1300//206 1327//283 1328//250 +f 1328//250 1329//291 1300//206 +f 1300//206 1329//251 1330//234 +f 1300//206 1330//234 1301//232 +f 1323//257 1331//308 1320//337 +f 1320//334 1331//259 1332//261 +f 1320//333 1332//261 1324//335 +f 1324//335 1332//261 1333//263 +f 1324//335 1333//263 1325//264 +f 1326//265 1334//244 1324//335 +f 1324//336 1334//244 1335//245 +f 1324//335 1335//245 1327//248 +f 1336//240 1337//258 1314//330 +f 1314//338 1337//226 1338//293 +f 1314//338 1338//227 1315//228 +f 1313//235 1339//231 1308//206 +f 1308//206 1339//231 1340//238 +f 1308//206 1340//238 1314//330 +f 1314//330 1340//238 1341//239 +f 1314//330 1341//239 1336//240 +f 961//261 878//215 883//206 +f 883//206 878//277 1342//339 +f 883//206 1342//339 881//217 +f 880//340 879//206 1343//341 +f 1343//342 879//206 1344//206 +f 1343//341 1344//206 1345//343 +f 1345//343 1344//206 1346//206 +f 1345//343 1346//206 1347//344 +f 1347//344 1346//206 1348//206 +f 1347//345 1348//206 1349//346 +f 1350//206 1351//347 1352//206 +f 1352//206 1351//348 1353//349 +f 1352//206 1353//350 1348//206 +f 1348//206 1353//350 1354//351 +f 1348//206 1354//351 1349//352 +f 1355//251 1356//234 1357//353 +f 1358//235 1359//231 1360//206 +f 1359//231 1361//238 1360//206 +f 1360//206 1361//238 1362//354 +f 1360//206 1362//239 1350//206 +f 877//214 876//213 1357//353 +f 1357//355 876//213 1363//250 +f 1357//353 1363//250 1355//251 +f 1362//239 1364//240 1350//206 +f 1350//206 1364//240 1365//226 +f 1350//206 1365//241 1366//227 +f 1351//348 1367//242 877//214 +f 877//214 1367//242 1368//243 +f 877//214 1368//244 875//212 +f 1356//234 1369//232 1357//353 +f 1357//355 1369//232 1370//230 +f 1357//353 1370//230 1371//281 +f 1372//222 1373//223 1360//206 +f 1360//206 1373//223 1374//236 +f 1360//206 1374//236 1358//235 +f 1366//227 1375//228 1350//206 +f 1350//206 1375//228 1376//229 +f 1350//206 1376//229 1377//285 +f 1378//278 1379//259 1351//347 +f 1351//348 1379//260 1380//261 +f 1380//262 1381//263 1351//348 +f 1351//348 1381//309 1382//264 +f 1351//347 1382//264 1367//265 +f 1371//281 1383//269 1357//355 +f 1357//355 1383//268 1384//275 +f 1357//353 1384//275 1385//271 +f 1385//306 1386//272 1360//206 +f 1360//206 1386//272 1387//273 +f 1360//206 1387//273 1372//222 +f 1377//253 1388//254 1350//206 +f 1350//206 1388//254 1389//255 +f 1350//206 1389//255 1351//347 +f 1351//348 1389//255 1390//276 +f 1351//348 1390//276 1378//257 +f 1385//271 1360//206 1357//353 +f 1357//353 1360//206 1391//206 +f 1357//353 1391//206 1392//356 +f 874//206 873//357 1391//206 +f 1391//206 873//357 1393//358 +f 1391//206 1393//359 1392//356 +f 872//360 874//206 1394//361 +f 1394//362 874//206 1395//206 +f 1394//362 1395//206 1396//363 +f 1396//364 1395//206 1397//365 +f 1397//366 1395//206 1398//206 +f 1397//365 1398//206 1399//367 +f 1399//367 1398//206 1004//206 +f 1399//367 1004//206 1010//290 +f 1010//289 1004//206 1013//245 +f 1010//287 1013//245 1008//213 +f 1016//232 1005//311 1010//287 +f 1010//287 1005//230 870//206 +f 1010//287 870//206 1400//368 +f 1400//368 870//206 869//209 +f 867//206 866//207 1401//206 +f 1402//206 1403//369 1404//370 +f 1405//371 1406//372 1407//206 +f 1407//206 1406//373 1408//374 +f 1407//206 1408//374 1409//375 +f 1410//250 1407//206 1411//213 +f 1411//213 1407//206 1412//206 +f 1411//213 1412//206 1413//245 +f 1410//250 1414//251 1407//206 +f 1407//206 1414//291 1415//234 +f 1407//206 1415//234 1416//307 +f 1412//206 1417//263 1418//264 +f 1416//232 1419//230 1407//206 +f 1407//206 1419//230 1420//281 +f 1407//206 1420//281 1421//269 +f 1422//376 1423//222 1405//377 +f 1405//377 1423//222 1424//223 +f 1405//371 1424//223 1425//298 +f 1425//236 1426//235 1405//371 +f 1405//378 1426//235 1427//233 +f 1405//371 1427//231 1428//379 +f 1428//379 1427//233 1429//238 +f 1430//239 1431//240 1432//206 +f 1432//206 1431//240 1433//226 +f 1432//206 1433//258 1434//227 +f 1434//227 1435//228 1432//206 +f 1432//206 1435//228 1436//229 +f 1432//206 1436//229 1437//285 +f 1438//257 1439//260 1412//206 +f 1412//206 1439//260 1440//262 +f 1412//206 1440//261 1417//263 +f 1418//264 1441//265 1412//206 +f 1412//206 1441//265 1442//243 +f 1412//206 1442//244 1413//245 +f 1421//269 1443//275 1407//206 +f 1407//206 1443//275 1444//271 +f 1407//206 1444//271 1405//371 +f 1405//371 1444//380 1445//272 +f 1405//371 1445//272 1422//274 +f 1437//253 1446//224 1432//206 +f 1432//206 1446//254 1447//225 +f 1432//206 1447//255 1448//276 +f 1449//206 1450//206 1451//381 +f 1451//382 1450//206 1452//383 +f 1148//206 1453//384 1450//206 +f 1450//206 1453//384 1454//385 +f 1450//206 1454//385 1452//386 +f 1099//301 1455//387 1146//206 +f 1146//206 1455//388 1456//389 +f 1146//206 1456//389 1148//206 +f 1148//206 1456//390 1457//391 +f 1148//206 1457//392 1453//384 +f 1458//281 1459//269 1402//206 +f 1402//206 1459//269 1460//275 +f 1460//275 1461//271 1402//206 +f 1402//206 1461//271 1462//206 +f 1402//206 1462//206 1403//393 +f 1403//393 1462//206 1463//394 +f 1464//206 1465//276 1466//257 +f 1402//206 1467//251 1468//234 +f 1461//271 1469//272 1462//206 +f 1462//206 1469//272 1470//274 +f 1462//206 1470//273 1471//222 +f 1466//257 1472//259 1464//206 +f 1464//206 1472//259 1473//261 +f 1464//206 1473//262 1474//263 +f 1468//252 1475//232 1402//206 +f 1402//206 1475//232 1476//230 +f 1402//206 1476//230 1458//281 +f 1477//244 1478//245 1464//206 +f 1464//206 1478//245 1479//248 +f 1464//206 1479//213 1402//206 +f 1402//206 1479//213 1480//250 +f 1402//206 1480//284 1467//251 +f 1481//253 1482//224 1483//206 +f 1483//206 1482//254 1484//255 +f 1474//263 1485//264 1464//206 +f 1464//206 1485//264 1486//265 +f 1464//206 1486//265 1477//243 +f 1471//222 1487//223 1462//206 +f 1462//206 1487//223 1488//236 +f 1462//206 1488//236 1489//235 +f 1490//240 1491//258 1483//206 +f 1483//206 1491//258 1492//227 +f 1489//235 1493//233 1462//206 +f 1462//206 1493//233 1494//238 +f 1462//206 1494//238 1483//206 +f 1483//206 1494//249 1495//239 +f 1483//206 1495//239 1490//240 +f 1492//227 1496//395 1483//206 +f 1483//206 1496//228 1497//229 +f 1483//206 1497//229 1481//253 +f 1056//273 1059//206 977//206 +f 977//206 1059//206 1401//206 +f 977//206 1401//206 871//206 +f 871//206 1401//206 866//396 +f 871//206 866//207 869//209 +f 1498//250 1449//206 1499//213 +f 1499//213 1449//206 1150//206 +f 1499//213 1150//206 1500//245 +f 1148//206 1501//226 1502//227 +f 1150//206 1503//263 1504//264 +f 1498//250 1505//251 1449//206 +f 1449//206 1505//291 1506//234 +f 1449//206 1506//234 1507//232 +f 1502//227 1508//228 1148//206 +f 1148//206 1508//395 1509//229 +f 1148//206 1509//229 1510//253 +f 1504//264 1511//242 1150//206 +f 1150//206 1511//265 1512//243 +f 1150//206 1512//243 1500//245 +f 1507//312 1513//230 1449//206 +f 1449//206 1513//230 1514//267 +f 1449//206 1514//281 1515//269 +f 1516//273 1517//222 1450//206 +f 1450//206 1517//222 1518//223 +f 1518//223 1519//236 1450//206 +f 1450//206 1519//236 1520//235 +f 1450//206 1520//235 1521//233 +f 1521//231 1522//249 1450//206 +f 1450//206 1522//238 1523//239 +f 1450//206 1523//239 1148//206 +f 1148//206 1523//239 1524//240 +f 1148//206 1524//246 1501//226 +f 1510//253 1525//254 1148//206 +f 1148//206 1525//254 1526//255 +f 1148//206 1526//225 1150//206 +f 1150//206 1526//255 1527//276 +f 1150//206 1527//276 1528//257 +f 1528//257 1529//259 1150//206 +f 1150//206 1529//259 1530//261 +f 1150//206 1530//261 1503//263 +f 1515//269 1531//275 1449//206 +f 1449//206 1531//275 1532//271 +f 1449//206 1532//306 1450//206 +f 1450//206 1532//271 1533//272 +f 1450//206 1533//272 1516//274 +f 891//223 1181//206 892//206 +f 892//206 1181//206 1534//206 +f 892//206 1534//206 1535//206 +f 1535//206 1534//206 1412//206 +f 1535//206 1412//206 1536//206 +f 1536//206 1412//206 1407//206 +f 1536//206 1407//206 1483//206 +f 1483//206 1407//206 1409//375 +f 1483//206 1409//397 1462//206 +f 1462//206 1409//397 1537//398 +f 1462//206 1537//398 1463//394 +f 1183//306 892//206 1184//206 +f 1184//206 892//206 1535//206 +f 1184//206 1535//206 1538//206 +f 1538//206 1535//206 1536//206 +f 1538//206 1536//206 1539//206 +f 1539//206 1536//206 1483//206 +f 1539//206 1483//206 1464//206 +f 1464//206 1483//206 1484//255 +f 1464//206 1484//255 1465//276 +f 1192//270 1184//206 1196//206 +f 1196//206 1184//206 1538//206 +f 1196//206 1538//206 1060//206 +f 1060//206 1538//206 1539//206 +f 1060//206 1539//206 1059//206 +f 1059//206 1539//206 1464//206 +f 1059//206 1464//206 1401//206 +f 1401//206 1464//206 1402//206 +f 1401//206 1402//206 867//206 +f 867//206 1402//206 1404//370 +f 867//206 1404//370 868//208 +f 1540//240 1541//206 1542//239 +f 1542//239 1541//206 1398//206 +f 1540//240 1543//226 1541//206 +f 1541//206 1543//226 1544//227 +f 1541//206 1544//227 1545//228 +f 1545//228 1546//229 1541//206 +f 1541//206 1546//229 1547//253 +f 1541//206 1547//253 1548//224 +f 1549//263 1550//264 874//206 +f 874//206 1550//264 1551//265 +f 874//206 1552//213 1395//206 +f 1395//206 1552//213 1553//250 +f 1395//206 1553//250 1554//291 +f 1554//251 1555//234 1395//206 +f 1395//206 1555//252 1556//232 +f 1395//206 1556//232 1557//230 +f 1557//230 1558//281 1395//206 +f 1395//206 1558//267 1559//269 +f 1395//206 1559//268 1560//275 +f 1561//222 1562//223 1398//206 +f 1398//206 1562//223 1563//236 +f 1398//206 1563//236 1564//235 +f 1564//235 1565//233 1398//206 +f 1398//206 1565//233 1566//238 +f 1398//206 1566//238 1542//239 +f 1548//224 1567//255 874//206 +f 874//206 1567//255 1568//276 +f 874//206 1568//276 1569//278 +f 1551//265 1570//243 874//206 +f 874//206 1570//243 1571//245 +f 874//206 1571//245 1552//213 +f 1569//257 1572//259 874//206 +f 874//206 1572//259 1573//262 +f 874//206 1573//262 1549//263 +f 1560//275 1574//271 1395//206 +f 1395//206 1574//271 1575//286 +f 1395//206 1575//272 1398//206 +f 1398//206 1575//272 1576//274 +f 1398//206 1576//376 1561//222 +f 1429//238 1430//239 1428//399 +f 1428//399 1430//239 1432//206 +f 1428//399 1432//206 1451//400 +f 1451//382 1432//206 1577//206 +f 1451//381 1577//206 1449//206 +f 1449//206 1577//206 1578//206 +f 1449//206 1578//206 1150//206 +f 1150//206 1578//206 1579//206 +f 1150//206 1579//206 1153//206 +f 1153//206 1579//206 1164//206 +f 1153//206 1164//206 1154//206 +f 1154//206 1164//206 1168//234 +f 1154//206 1168//234 1155//232 +f 1252//206 1161//206 898//206 +f 898//206 1161//206 1164//206 +f 898//206 1164//206 906//206 +f 906//206 1164//206 1579//206 +f 906//206 1579//206 931//206 +f 931//206 1579//206 1578//206 +f 931//206 1578//206 1181//206 +f 1181//206 1578//206 1577//206 +f 1181//206 1577//206 1534//206 +f 1534//206 1577//206 1432//206 +f 1534//206 1432//206 1412//206 +f 1412//206 1432//206 1448//276 +f 1412//206 1448//317 1438//257 +f 1239//206 1580//213 1581//250 +f 861//206 1582//293 1583//228 +f 1581//250 1584//291 1239//206 +f 1239//206 1584//251 1585//234 +f 1239//206 1585//252 1586//232 +f 1583//228 1587//229 861//206 +f 861//206 1587//229 1588//253 +f 861//206 1588//253 1589//224 +f 1590//259 1591//261 862//206 +f 862//206 1591//261 1592//263 +f 862//206 1592//263 1593//310 +f 1593//264 1594//265 862//206 +f 862//206 1594//265 1595//244 +f 862//206 1595//244 1239//206 +f 1239//206 1595//244 1596//245 +f 1239//206 1596//245 1580//213 +f 1586//232 1597//230 1239//206 +f 1239//206 1597//230 1598//267 +f 1239//206 1598//281 1599//268 +f 1600//274 1601//222 865//206 +f 865//206 1601//222 1602//223 +f 865//206 1602//223 1603//236 +f 1589//224 1604//255 861//206 +f 861//206 1604//255 1605//317 +f 861//206 1605//276 862//206 +f 862//206 1605//276 1606//257 +f 862//206 1606//257 1590//260 +f 1599//269 1607//270 1239//206 +f 1239//206 1607//275 1608//271 +f 1239//206 1608//271 865//206 +f 865//206 1608//271 1609//272 +f 865//206 1609//272 1600//274 +f 1603//236 1610//235 865//206 +f 865//206 1610//235 1611//233 +f 865//206 1611//233 1612//238 +f 1612//238 1613//239 865//206 +f 865//206 1613//239 1614//240 +f 865//206 1614//240 861//206 +f 861//206 1614//240 1615//258 +f 861//206 1615//258 1582//227 +f 1548//254 874//206 1541//206 +f 1541//206 874//206 1391//206 +f 1541//206 1391//206 1616//206 +f 1616//206 1391//206 1360//206 +f 1616//206 1360//206 1617//206 +f 1617//206 1360//206 1350//206 +f 1617//206 1350//206 1618//206 +f 1618//206 1350//206 1352//206 +f 1618//206 1352//206 1619//206 +f 1619//206 1352//206 1348//206 +f 1619//206 1348//206 1620//206 +f 1621//250 1622//251 1623//206 +f 1621//250 1623//206 1624//213 +f 1625//206 1626//226 1627//227 +f 1628//271 1629//272 1255//206 +f 1630//265 1631//244 1632//206 +f 1632//206 1631//243 1633//245 +f 1622//251 1634//234 1623//206 +f 1623//206 1634//252 1635//232 +f 1623//206 1635//232 1636//230 +f 1636//230 1637//281 1623//206 +f 1623//206 1637//281 1638//269 +f 1623//206 1638//269 1639//275 +f 1640//233 1641//249 1255//206 +f 1255//206 1641//238 1642//239 +f 1255//206 1642//239 1625//206 +f 1625//206 1642//239 1643//240 +f 1625//206 1643//246 1626//258 +f 1627//293 1644//228 1625//206 +f 1625//206 1644//228 1645//229 +f 1625//206 1645//229 1646//253 +f 1639//275 1628//271 1623//206 +f 1623//206 1628//271 1255//206 +f 1623//206 1255//206 1177//206 +f 1177//206 1255//206 1257//401 +f 1177//206 1257//320 1254//402 +f 1629//272 1647//273 1255//206 +f 1255//206 1647//273 1648//222 +f 1255//206 1648//222 1649//223 +f 1646//253 1650//254 1625//206 +f 1625//206 1650//224 1651//255 +f 1625//206 1651//255 1632//206 +f 1632//206 1651//255 1652//276 +f 1652//276 1653//257 1632//206 +f 1632//206 1653//257 1654//259 +f 1632//206 1654//259 1655//261 +f 1655//262 1656//263 1632//206 +f 1632//206 1656//263 1657//305 +f 1632//206 1657//264 1630//265 +f 1649//223 1658//298 1255//206 +f 1255//206 1658//236 1659//235 +f 1255//206 1659//235 1640//233 +f 1633//245 1624//213 1632//206 +f 1632//206 1624//213 1623//206 +f 1632//206 1623//206 1660//206 +f 1253//227 1245//228 1252//206 +f 1252//206 1245//395 864//206 +f 1252//206 864//206 1661//206 +f 1661//206 864//206 861//206 +f 1661//206 861//206 1662//206 +f 1662//206 861//206 863//206 +f 1662//206 863//206 1026//206 +f 1026//206 863//206 1024//249 +f 1026//206 1024//238 1027//239 +f 1020//273 863//206 1018//206 +f 1018//206 863//206 862//206 +f 1018//206 862//206 1663//206 +f 1663//206 862//206 1239//206 +f 1663//206 1239//206 1664//206 +f 1664//206 1239//206 1235//206 +f 1664//206 1235//206 1665//206 +f 1665//206 1235//206 1233//206 +f 1665//206 1233//206 1666//206 +f 1666//206 1233//206 1189//206 +f 1666//206 1189//206 1667//206 +f 1667//206 1189//206 1196//206 +f 1667//206 1196//206 1668//206 +f 1668//206 1196//206 1060//206 +f 1668//206 1060//206 1074//206 +f 1074//206 1060//206 1062//285 +f 1074//206 1062//253 1072//254 +f 1035//268 1018//206 1036//206 +f 1036//206 1018//206 1663//206 +f 1036//206 1663//206 1669//206 +f 1669//206 1663//206 1664//206 +f 1669//206 1664//206 1670//206 +f 1670//206 1664//206 1665//206 +f 1670//206 1665//206 1671//206 +f 1671//206 1665//206 1666//206 +f 1671//206 1666//206 1672//206 +f 1672//206 1666//206 1667//206 +f 1672//206 1667//206 1673//206 +f 1673//206 1667//206 1668//206 +f 1673//206 1668//206 1674//206 +f 1674//206 1668//206 1074//206 +f 1674//206 1074//206 1081//206 +f 1081//206 1074//206 1076//257 +f 1081//206 1076//257 1084//259 +f 1346//206 1675//276 1676//257 +f 1677//251 1678//234 1348//206 +f 1348//206 1678//234 1679//232 +f 1348//206 1679//232 1680//230 +f 1681//240 1682//226 1344//206 +f 1680//230 1683//267 1348//206 +f 1348//206 1683//281 1684//268 +f 1348//206 1684//269 1685//275 +f 1685//270 1686//271 1348//206 +f 1348//206 1686//271 1687//272 +f 1348//206 1687//272 1620//206 +f 1620//206 1687//272 1688//273 +f 1620//206 1688//274 1689//222 +f 1689//222 1690//223 1620//206 +f 1620//206 1690//223 1691//236 +f 1620//206 1691//236 1692//235 +f 1682//226 1693//227 1344//206 +f 1344//206 1693//293 1694//304 +f 1344//206 1694//228 1695//229 +f 1695//303 1696//253 1344//206 +f 1344//206 1696//253 1697//403 +f 1344//206 1697//224 1346//206 +f 1346//206 1697//254 1698//255 +f 1346//206 1698//225 1675//276 +f 1676//257 1699//260 1346//206 +f 1346//206 1699//259 1700//262 +f 1346//206 1700//261 1701//263 +f 1701//263 1702//264 1346//206 +f 1346//206 1702//264 1703//242 +f 1346//206 1703//265 1704//243 +f 1704//244 1705//245 1346//206 +f 1346//206 1705//245 1706//213 +f 1346//206 1706//213 1348//206 +f 1348//206 1706//213 1707//250 +f 1348//206 1707//250 1677//251 +f 1692//292 1708//233 1620//206 +f 1620//206 1708//233 1709//238 +f 1620//206 1709//238 1344//206 +f 1344//206 1709//238 1710//239 +f 1344//206 1710//239 1681//240 +f 1293//275 1268//380 1259//206 +f 1259//206 1268//271 1264//206 +f 1259//206 1264//206 1660//206 +f 1660//206 1264//206 1269//404 +f 1660//206 1269//405 1632//206 +f 1632//206 1269//404 1711//406 +f 1632//206 1711//407 1625//206 +f 1625//206 1711//406 1712//408 +f 1625//206 1712//408 1255//206 +f 1255//206 1712//408 1713//409 +f 1255//206 1713//410 1256//411 +f 968//230 942//206 879//206 +f 879//206 942//206 1036//206 +f 879//206 1036//206 1344//206 +f 1344//206 1036//206 1669//206 +f 1344//206 1669//206 1620//206 +f 1620//206 1669//206 1670//206 +f 1620//206 1670//206 1619//206 +f 1619//206 1670//206 1671//206 +f 1619//206 1671//206 1618//206 +f 1618//206 1671//206 1672//206 +f 1618//206 1672//206 1617//206 +f 1617//206 1672//206 1673//206 +f 1617//206 1673//206 1616//206 +f 1616//206 1673//206 1674//206 +f 1616//206 1674//206 1541//206 +f 1541//206 1674//206 1081//206 +f 1541//206 1081//206 1398//206 +f 1398//206 1081//206 982//206 +f 1398//206 982//206 1004//206 +f 1004//206 982//206 1001//262 +f 1004//206 1001//262 1002//263 +f 1314//330 887//412 1308//206 +f 1308//206 887//220 889//206 +f 1308//206 889//206 1259//206 +f 1259//206 889//206 1290//245 +f 1259//206 1290//245 1261//213 +f 1178//255 1179//276 1177//206 +f 1177//206 1179//276 1174//206 +f 1177//206 1174//206 1623//206 +f 1623//206 1174//206 1714//206 +f 1623//206 1714//206 1660//206 +f 1660//206 1714//206 1715//206 +f 1660//206 1715//206 1259//206 +f 1259//206 1715//206 1716//206 +f 1259//206 1716//206 1308//206 +f 1308//206 1716//206 1300//206 +f 1308//206 1300//206 1306//271 +f 1306//271 1300//206 1305//275 +f 885//219 1324//336 886//206 +f 886//206 1324//336 1300//206 +f 886//206 1300//206 1717//206 +f 1717//206 1300//206 1716//206 +f 1717//206 1716//206 1718//206 +f 1718//206 1716//206 1715//206 +f 1718//206 1715//206 1719//206 +f 1719//206 1715//206 1714//206 +f 1719//206 1714//206 1720//206 +f 1720//206 1714//206 1174//206 +f 1720//206 1174//206 1169//206 +f 1169//206 1174//206 1173//260 +f 1169//206 1173//259 1170//261 +f 1171//263 1159//264 1169//206 +f 1169//206 1159//264 1161//206 +f 1169//206 1161//206 1720//206 +f 1720//206 1161//206 1252//206 +f 1720//206 1252//206 1719//206 +f 1719//206 1252//206 1661//206 +f 1719//206 1661//206 1718//206 +f 1718//206 1661//206 1662//206 +f 1718//206 1662//206 1717//206 +f 1717//206 1662//206 1026//206 +f 1717//206 1026//206 886//206 +f 886//206 1026//206 882//206 +f 886//206 882//206 884//413 +f 884//218 882//206 881//217 +f 496//151 458//146 1357//355 +f 1357//353 458//146 877//214 +f 1357//353 1392//356 496//151 +f 496//414 1392//356 1393//358 +f 496//414 1393//415 494//150 +f 494//150 1393//415 873//357 +f 494//416 873//211 447//417 +f 447//417 873//211 872//210 +f 447//134 872//360 448//135 +f 448//135 872//360 1394//362 +f 448//135 1394//362 450//418 +f 450//137 1394//362 1396//363 +f 450//138 1396//363 452//419 +f 452//419 1396//363 1397//366 +f 452//139 1397//366 454//141 +f 454//141 1397//366 1399//367 +f 454//140 1399//420 455//143 +f 455//143 1399//420 1010//287 +f 455//421 1010//290 141//76 +f 141//76 1010//290 1400//368 +f 141//422 1400//368 446//423 +f 446//423 1400//368 869//209 +f 446//133 869//209 11//7 +f 11//7 869//424 866//396 +f 11//7 866//207 14//204 +f 14//204 866//396 868//208 +f 14//204 868//208 443//129 +f 443//129 868//208 1404//370 +f 443//129 1404//425 444//130 +f 444//130 1404//425 1403//393 +f 444//130 1403//393 445//132 +f 445//132 1403//393 1463//426 +f 445//132 1463//426 439//126 +f 439//126 1463//426 1537//398 +f 439//125 1537//427 441//127 +f 441//127 1537//427 1409//375 +f 441//127 1409//397 442//205 +f 442//205 1409//397 1408//374 +f 442//205 1408//374 437//428 +f 437//428 1408//374 1406//372 +f 437//124 1406//372 436//123 +f 436//123 1406//372 1405//371 +f 436//122 1405//371 402//114 +f 402//114 1405//371 1428//379 +f 402//114 1428//399 404//115 +f 404//115 1428//399 1451//381 +f 404//115 1451//381 394//113 +f 394//113 1451//381 1452//386 +f 394//202 1452//383 392//111 +f 392//111 1452//383 1454//385 +f 392//111 1454//429 390//110 +f 390//110 1454//429 1453//384 +f 390//110 1453//384 17//430 +f 17//430 1453//384 1457//391 +f 17//9 1457//392 18//431 +f 18//431 1457//392 1456//432 +f 18//431 1456//390 388//433 +f 388//433 1456//390 1455//388 +f 388//433 1455//387 389//107 +f 389//107 1455//387 1099//301 +f 389//108 1099//296 247//89 +f 247//88 1099//301 230//85 +f 230//434 1099//296 1121//300 +f 230//85 1121//299 243//93 +f 458//144 464//145 877//214 +f 877//214 464//145 474//147 +f 877//214 474//148 1351//348 +f 1351//348 474//148 503//154 +f 1351//348 503//435 1353//349 +f 1353//349 503//435 501//436 +f 1353//437 501//153 1354//438 +f 1354//438 501//153 500//152 +f 1354//351 500//156 1349//352 +f 1349//352 500//156 505//158 +f 1349//352 505//158 1347//439 +f 1347//345 505//158 507//159 +f 1347//344 507//159 1345//440 +f 1345//440 507//159 508//162 +f 1345//343 508//162 1343//342 +f 1343//342 508//162 510//163 +f 1343//341 510//441 880//216 +f 880//216 510//441 108//69 +f 880//442 108//72 878//277 +f 878//277 108//72 511//164 +f 878//443 511//164 1342//444 +f 1342//444 511//164 8//6 +f 1342//339 8//6 881//217 +f 881//217 8//445 7//193 +f 881//217 7//5 884//413 +f 884//413 7//193 604//192 +f 884//413 604//192 885//219 +f 885//219 604//192 543//172 +f 885//219 543//173 1324//336 +f 1324//336 543//173 529//171 +f 1324//336 529//171 1320//333 +f 1320//333 529//171 527//167 +f 1320//333 527//167 1316//332 +f 1316//332 527//167 525//165 +f 1316//331 525//166 1314//330 +f 1314//330 525//166 554//446 +f 1314//330 554//174 887//220 +f 887//220 554//174 555//175 +f 887//220 555//175 888//447 +f 888//447 555//175 558//177 +f 888//221 558//177 1299//329 +f 1299//329 558//177 557//176 +f 1299//328 557//176 1267//321 +f 1267//321 557//176 559//183 +f 1267//321 559//179 1270//324 +f 1270//324 559//179 4//199 +f 1270//324 4//199 1269//404 +f 1269//404 4//199 726//197 +f 1269//405 726//198 1711//406 +f 1711//406 726//198 597//184 +f 1711//406 597//448 1712//408 +f 1712//408 597//448 599//185 +f 1712//408 599//185 1713//449 +f 1713//449 599//185 603//190 +f 1713//410 603//191 1256//319 +f 1256//319 603//191 602//450 +f 1256//319 602//188 1257//451 +f 1257//451 602//188 601//187 +f 1257//451 601//186 1254//318 +f 1254//318 601//186 243//87 +f 1254//402 243//93 1102//297 +f 1102//302 243//87 1121//300 +f 329//452 1237//213 20//41 +f 20//41 1237//453 1236//245 +f 20//41 1236//245 21//12 +f 21//73 1236//245 1244//243 +f 21//70 1244//243 324//48 +f 324//13 1244//282 1243//242 +f 324//13 1243//265 325//14 +f 325//14 1243//265 1242//310 +f 325//194 1242//264 326//50 +f 326//50 1242//264 1241//454 +f 326//50 1241//263 327//52 +f 327//52 1241//263 1240//261 +f 327//51 1240//261 328//82 +f 328//54 1240//262 1238//308 +f 328//54 1238//260 322//55 +f 322//55 1238//259 1251//257 +f 322//55 1251//257 320//455 +f 320//17 1251//257 1250//456 +f 320//455 1250//276 314//18 +f 314//18 1250//456 1249//255 +f 314//18 1249//255 315//45 +f 315//44 1249//255 1248//224 +f 315//196 1248//224 317//75 +f 317//46 1248//403 1247//285 +f 317//46 1247//253 318//47 +f 318//47 1247//253 1246//303 +f 318//47 1246//229 319//21 +f 319//21 1246//229 1245//228 +f 319//21 1245//228 312//22 +f 312//22 1245//228 1253//227 +f 312//84 1253//227 56//49 +f 56//42 1253//293 912//241 +f 56//42 912//226 54//1 +f 54//1 912//258 915//240 +f 54//1 915//240 52//457 +f 52//2 915//240 917//458 +f 52//457 917//239 50//27 +f 50//27 917//458 919//238 +f 50//27 919//238 38//23 +f 38//31 919//238 902//231 +f 38//28 902//231 387//81 +f 387//29 902//237 1180//292 +f 387//29 1180//235 378//56 +f 378//56 1180//235 1182//236 +f 378//56 1182//236 379//57 +f 379//57 1182//236 891//223 +f 379//90 891//223 381//62 +f 381//62 891//223 890//222 +f 381//74 890//222 382//119 +f 382//15 890//266 1188//376 +f 382//15 1188//273 383//16 +f 383//16 1188//274 1187//272 +f 383//16 1187//272 384//459 +f 384//64 1187//272 1183//460 +f 384//459 1183//271 385//19 +f 385//19 1183//460 1185//275 +f 385//19 1185//275 339//60 +f 339//20 1185//275 1186//269 +f 339//101 1186//269 370//61 +f 370//67 1186//294 1222//267 +f 370//67 1222//281 372//24 +f 372//24 1222//281 1224//230 +f 372//461 1224//230 374//25 +f 374//25 1224//230 1226//312 +f 374//25 1226//232 376//30 +f 376//30 1226//232 1232//234 +f 376//32 1232//234 377//462 +f 377//105 1232//252 1231//314 +f 377//105 1231//314 333//463 +f 333//463 1231//464 1229//465 +f 333//466 1229//465 331//98 +f 331//98 1229//467 1234//316 +f 331//98 1234//316 329//452 +f 329//38 1234//468 1237//453 +f 255//38 1115//469 236//41 +f 236//11 1115//469 1113//245 +f 236//41 1113//245 237//73 +f 237//12 1113//245 1108//243 +f 237//73 1108//282 270//13 +f 270//48 1108//243 1130//265 +f 270//13 1130//265 263//14 +f 263//97 1130//265 1131//264 +f 263//194 1131//310 264//103 +f 264//103 1131//264 1140//470 +f 264//50 1140//309 265//52 +f 265//52 1140//263 1139//261 +f 265//51 1139//262 278//54 +f 278//82 1139//261 1138//308 +f 278//54 1138//259 279//55 +f 279//55 1138//260 1143//257 +f 279//55 1143//278 275//17 +f 275//471 1143//257 1142//456 +f 275//455 1142//472 276//18 +f 276//43 1142//276 1141//225 +f 276//18 1141//255 277//44 +f 277//45 1141//255 1129//224 +f 277//196 1129//403 272//46 +f 272//75 1129//224 1128//285 +f 272//473 1128//285 273//47 +f 273//474 1128//285 1127//475 +f 273//474 1127//303 274//21 +f 274//201 1127//229 1101//228 +f 274//21 1101//304 241//22 +f 241//22 1101//228 1100//227 +f 241//22 1100//293 242//42 +f 242//49 1100//227 1126//226 +f 242//42 1126//258 266//1 +f 266//1 1126//226 1125//240 +f 266//1 1125//246 231//2 +f 231//476 1125//240 1124//458 +f 231//457 1124//354 232//27 +f 232//36 1124//239 1120//238 +f 232//27 1120//238 248//31 +f 248//23 1120//238 1122//231 +f 248//31 1122//237 249//29 +f 249//81 1122//231 1123//235 +f 249//29 1123//235 250//56 +f 250//86 1123//235 1098//236 +f 250//56 1098//477 251//57 +f 251//180 1098//236 1097//326 +f 251//90 1097//326 252//74 +f 252//74 1097//223 1137//222 +f 252//74 1137//266 267//15 +f 267//119 1137//222 1136//376 +f 267//15 1136//274 268//16 +f 268//16 1136//273 1135//272 +f 268//16 1135//286 269//64 +f 269//58 1135//272 1134//460 +f 269//459 1134//380 244//19 +f 244//59 1134//271 1133//275 +f 244//19 1133//275 245//20 +f 245//60 1133//275 1132//269 +f 245//101 1132//294 246//67 +f 246//67 1132//269 1119//267 +f 246//67 1119//267 253//478 +f 253//478 1119//281 1118//479 +f 253//478 1118//311 254//25 +f 254//102 1118//311 1117//312 +f 254//25 1117//307 239//30 +f 239//30 1117//232 1105//234 +f 239//30 1105//252 235//33 +f 235//80 1105//234 1104//291 +f 235//33 1104//251 257//35 +f 257//68 1104//291 1116//250 +f 257//35 1116//284 255//480 +f 255//480 1116//250 1115//213 +f 294//452 1165//453 296//11 +f 296//41 1165//453 1163//212 +f 296//41 1163//245 297//12 +f 297//73 1163//245 1162//243 +f 297//70 1162//243 23//13 +f 23//13 1162//282 1160//242 +f 23//13 1160//265 24//97 +f 24//14 1160//265 1159//264 +f 24//194 1159//264 289//50 +f 289//50 1159//264 1171//454 +f 289//50 1171//263 288//52 +f 288//52 1171//263 1170//261 +f 288//51 1170//261 286//82 +f 286//54 1170//262 1173//308 +f 286//54 1173//260 283//55 +f 283//55 1173//259 1172//257 +f 283//65 1172//257 284//455 +f 284//455 1172//278 1179//456 +f 284//455 1179//456 285//43 +f 285//18 1179//456 1178//225 +f 285//18 1178//255 281//45 +f 281//44 1178//255 1176//224 +f 281//196 1176//224 282//75 +f 282//46 1176//403 1175//285 +f 282//46 1175//253 261//47 +f 261//47 1175//253 1095//303 +f 261//47 1095//229 262//201 +f 262//21 1095//475 1094//228 +f 262//92 1094//228 271//22 +f 271//22 1094//228 1107//227 +f 271//84 1107//227 240//49 +f 240//42 1107//227 1106//241 +f 240//42 1106//226 238//1 +f 238//1 1106//258 1112//240 +f 238//40 1112//240 256//457 +f 256//457 1112//246 1114//458 +f 256//457 1114//458 258//36 +f 258//27 1114//458 1111//249 +f 258//27 1111//238 259//23 +f 259//31 1111//238 1110//231 +f 259//28 1110//231 233//29 +f 233//29 1110//233 1109//292 +f 233//29 1109//235 234//56 +f 234//56 1109//235 1103//298 +f 234//56 1103//236 311//180 +f 311//57 1103//477 1145//223 +f 311//90 1145//223 302//62 +f 302//62 1145//223 1144//222 +f 302//74 1144//222 303//119 +f 303//15 1144//266 1147//376 +f 303//15 1147//273 307//16 +f 307//16 1147//274 1149//272 +f 307//16 1149//272 308//459 +f 308//459 1149//272 1152//460 +f 308//459 1152//460 309//19 +f 309//19 1152//460 1151//275 +f 309//19 1151//275 305//60 +f 305//20 1151//275 1158//269 +f 305//101 1158//269 306//61 +f 306//67 1158//294 1157//267 +f 306//67 1157//281 300//24 +f 300//24 1157//281 1156//230 +f 300//461 1156//230 298//25 +f 298//25 1156//230 1155//312 +f 298//25 1155//232 290//30 +f 290//30 1155//232 1168//234 +f 290//32 1168//234 291//34 +f 291//33 1168//234 1167//288 +f 291//33 1167//291 293//35 +f 293//35 1167//251 1166//250 +f 293//68 1166//250 294//452 +f 294//452 1166//284 1165//453 +f 747//452 1499//248 746//481 +f 746//482 1499//213 1500//483 +f 746//41 1500//484 749//12 +f 749//12 1500//483 1512//243 +f 749//12 1512//243 750//13 +f 750//13 1512//243 1511//265 +f 750//13 1511//265 751//14 +f 751//97 1511//265 1504//264 +f 751//14 1504//305 761//485 +f 761//485 1504//264 1503//263 +f 761//50 1503//309 762//52 +f 762//52 1503//263 1530//261 +f 762//51 1530//262 763//54 +f 763//82 1530//261 1529//308 +f 763//54 1529//308 767//55 +f 767//65 1529//260 1528//257 +f 767//65 1528//278 768//17 +f 768//471 1528//257 1527//456 +f 768//455 1527//472 769//18 +f 769//43 1527//276 1526//255 +f 769//18 1526//255 764//44 +f 764//45 1526//255 1525//224 +f 764//196 1525//403 765//46 +f 765//75 1525//224 1510//285 +f 765//46 1510//253 766//47 +f 766//94 1510//253 1509//229 +f 766//486 1509//475 755//21 +f 755//92 1509//303 1508//304 +f 755//21 1508//304 756//22 +f 756//22 1508//228 1502//227 +f 756//22 1502//293 757//42 +f 757//49 1502//227 1501//226 +f 757//49 1501//226 734//1 +f 734//487 1501//226 1524//488 +f 734//489 1524//490 735//2 +f 735//476 1524//491 1523//458 +f 735//457 1523//354 738//492 +f 738//493 1523//239 1522//494 +f 738//495 1522//496 736//31 +f 736//31 1522//238 1521//237 +f 736//31 1521//237 737//29 +f 737//81 1521//231 1520//235 +f 737//29 1520//235 739//56 +f 739//86 1520//235 1519//236 +f 739//497 1519//298 740//90 +f 740//90 1519//236 1518//498 +f 740//57 1518//295 741//62 +f 741//62 1518//223 1517//222 +f 741//74 1517//266 758//15 +f 758//119 1517//222 1516//376 +f 758//15 1516//274 759//16 +f 759//16 1516//273 1533//272 +f 759//16 1533//286 760//64 +f 760//499 1533//272 1532//460 +f 760//459 1532//500 752//19 +f 752//59 1532//271 1531//270 +f 752//19 1531//270 753//20 +f 753//101 1531//275 1515//269 +f 753//101 1515//294 754//67 +f 754//61 1515//269 1514//267 +f 754//67 1514//281 742//24 +f 742//77 1514//281 1513//230 +f 742//24 1513//479 743//25 +f 743//200 1513//479 1507//232 +f 743//25 1507//307 744//30 +f 744//30 1507//232 1506//234 +f 744//30 1506//234 745//33 +f 745//33 1506//234 1505//251 +f 745//33 1505//251 748//501 +f 748//502 1505//251 1498//250 +f 748//501 1498//503 747//38 +f 747//39 1498//504 1499//453 +f 228//452 1088//453 229//41 +f 229//41 1088//453 1087//245 +f 229//41 1087//245 210//12 +f 210//73 1087//245 1082//243 +f 210//70 1082//243 211//48 +f 211//13 1082//282 1080//242 +f 211//13 1080//265 221//97 +f 221//14 1080//265 1079//310 +f 221//14 1079//264 222//505 +f 222//50 1079//264 1086//454 +f 222//50 1086//263 223//52 +f 223//52 1086//309 1085//261 +f 223//51 1085//261 213//82 +f 213//54 1085//262 1084//308 +f 213//54 1084//260 214//55 +f 214//55 1084//259 1076//257 +f 214//55 1076//257 216//455 +f 216//455 1076//257 1075//456 +f 216//455 1075//456 217//18 +f 217//18 1075//456 1073//255 +f 217//18 1073//255 193//45 +f 193//44 1073//255 1072//224 +f 193//196 1072//224 194//75 +f 194//46 1072//403 1062//285 +f 194//46 1062//253 196//94 +f 196//47 1062//253 1061//303 +f 196//474 1061//229 197//21 +f 197//21 1061//475 1071//228 +f 197//21 1071//228 198//22 +f 198//22 1071//228 1070//227 +f 198//84 1070//227 202//49 +f 202//42 1070//293 1069//241 +f 202//42 1069//258 203//1 +f 203//1 1069//258 1068//240 +f 203//40 1068//240 204//457 +f 204//457 1068//246 1067//458 +f 204//457 1067//458 200//36 +f 200//27 1067//458 1066//249 +f 200//27 1066//238 201//23 +f 201//23 1066//238 1065//231 +f 201//28 1065//231 205//81 +f 205//29 1065//237 1064//292 +f 205//29 1064//235 206//56 +f 206//56 1064//235 1063//236 +f 206//56 1063//236 207//180 +f 207//57 1063//236 1058//326 +f 207//90 1058//223 192//62 +f 192//62 1058//295 1057//222 +f 192//74 1057//222 26//119 +f 26//15 1057//266 1056//376 +f 26//15 1056//273 27//16 +f 27//16 1056//274 1055//272 +f 27//16 1055//272 218//459 +f 218//459 1055//272 1054//460 +f 218//459 1054//460 219//19 +f 219//19 1054//460 1083//275 +f 219//19 1083//275 220//60 +f 220//20 1083//275 1078//269 +f 220//101 1078//269 208//61 +f 208//67 1078//294 1077//267 +f 208//67 1077//281 209//77 +f 209//24 1077//281 1093//230 +f 209//461 1093//230 224//25 +f 224//25 1093//280 1092//232 +f 224//102 1092//232 225//30 +f 225//30 1092//307 1091//234 +f 225//32 1091//234 226//80 +f 226//33 1091//252 1090//288 +f 226//33 1090//291 227//35 +f 227//35 1090//251 1089//250 +f 227//35 1089//250 228//452 +f 228//452 1089//250 1088//453 +f 410//38 1411//469 395//41 +f 395//11 1411//469 1413//245 +f 395//41 1413//245 396//73 +f 396//12 1413//245 1442//243 +f 396//73 1442//282 421//13 +f 421//48 1442//243 1441//265 +f 421//13 1441//265 422//14 +f 422//97 1441//265 1418//264 +f 422//14 1418//305 423//50 +f 423//103 1418//264 1417//454 +f 423//505 1417//454 433//51 +f 433//51 1417//263 1440//261 +f 433//51 1440//262 434//54 +f 434//82 1440//261 1439//308 +f 434//54 1439//259 435//55 +f 435//55 1439//259 1438//257 +f 435//55 1438//278 411//17 +f 411//471 1438//257 1448//456 +f 411//455 1448//256 398//18 +f 398//43 1448//276 1447//255 +f 398//18 1447//255 399//44 +f 399//45 1447//255 1446//224 +f 399//196 1446//403 424//46 +f 424//75 1446//224 1437//285 +f 424//46 1437//285 425//47 +f 425//474 1437//285 1436//475 +f 425//474 1436//303 426//21 +f 426//201 1436//229 1435//228 +f 426//21 1435//304 427//22 +f 427//22 1435//228 1434//227 +f 427//22 1434//293 428//42 +f 428//49 1434//227 1433//226 +f 428//42 1433//258 429//1 +f 429//1 1433//226 1431//240 +f 429//1 1431//246 405//2 +f 405//476 1431//240 1430//458 +f 405//457 1430//354 403//27 +f 403//36 1430//239 1429//238 +f 403//27 1429//238 401//31 +f 401//23 1429//238 1427//231 +f 401//31 1427//237 412//29 +f 412//81 1427//231 1426//235 +f 412//29 1426//235 413//506 +f 413//506 1426//235 1425//507 +f 413//506 1425//507 414//57 +f 414//90 1425//507 1424//326 +f 414//180 1424//326 415//74 +f 415//74 1424//223 1423//222 +f 415//74 1423//266 416//15 +f 416//119 1423//222 1422//376 +f 416//15 1422//274 417//16 +f 417//16 1422//273 1445//272 +f 417//16 1445//286 430//64 +f 430//499 1445//272 1444//460 +f 430//459 1444//500 431//19 +f 431//59 1444//271 1443//275 +f 431//19 1443//275 432//60 +f 432//60 1443//275 1421//269 +f 432//101 1421//294 418//67 +f 418//61 1421//269 1420//267 +f 418//67 1420//267 419//24 +f 419//461 1420//267 1419//280 +f 419//461 1419//311 420//508 +f 420//508 1419//230 1416//232 +f 420//508 1416//307 406//30 +f 406//30 1416//232 1415//234 +f 406//30 1415//252 407//33 +f 407//80 1415//234 1414//291 +f 407//33 1414//251 409//35 +f 409//68 1414//291 1410//250 +f 409//35 1410//284 410//480 +f 410//480 1410//250 1411//213 +f 190//452 1048//453 191//41 +f 191//41 1048//453 1047//245 +f 191//41 1047//245 179//12 +f 179//73 1047//245 1041//243 +f 179//70 1041//243 180//48 +f 180//13 1041//282 1040//242 +f 180//13 1040//265 181//97 +f 181//14 1040//265 1039//310 +f 181//14 1039//264 182//505 +f 182//50 1039//305 1038//263 +f 182//50 1038//263 183//52 +f 183//52 1038//263 1037//261 +f 183//51 1037//261 184//82 +f 184//54 1037//262 1046//308 +f 184//54 1046//260 185//55 +f 185//55 1046//259 1045//257 +f 185//55 1045//257 29//455 +f 29//455 1045//257 1044//456 +f 29//455 1044//456 30//18 +f 30//18 1044//456 894//255 +f 30//18 894//255 157//45 +f 157//44 894//255 893//224 +f 157//196 893//224 154//75 +f 154//46 893//403 1017//285 +f 154//46 1017//253 155//94 +f 155//47 1017//253 1025//229 +f 155//474 1025//229 158//21 +f 158//21 1025//229 1033//228 +f 158//21 1033//228 159//22 +f 159//22 1033//304 1032//227 +f 159//84 1032//227 160//49 +f 160//42 1032//293 1029//241 +f 160//42 1029//258 161//1 +f 161//1 1029//258 1028//240 +f 161//40 1028//240 162//457 +f 162//457 1028//246 1027//458 +f 162//457 1027//458 164//36 +f 164//27 1027//458 1024//249 +f 164//27 1024//238 165//23 +f 165//23 1024//238 1023//231 +f 165//28 1023//231 166//81 +f 166//29 1023//237 1031//292 +f 166//29 1031//235 167//86 +f 167//56 1031//235 1030//236 +f 167//56 1030//236 168//57 +f 168//57 1030//236 1022//326 +f 168//57 1022//223 169//62 +f 169//62 1022//295 1021//222 +f 169//74 1021//222 170//119 +f 170//15 1021//266 1020//376 +f 170//15 1020//273 172//16 +f 172//16 1020//274 1019//272 +f 172//16 1019//272 173//459 +f 173//459 1019//272 1043//460 +f 173//459 1043//460 174//19 +f 174//19 1043//460 1042//275 +f 174//19 1042//275 175//60 +f 175//20 1042//275 1035//269 +f 175//101 1035//269 177//61 +f 177//67 1035//294 1034//267 +f 177//67 1034//281 178//24 +f 178//24 1034//281 1053//230 +f 178//24 1053//230 186//200 +f 186//25 1053//280 1052//232 +f 186//102 1052//232 187//30 +f 187//30 1052//307 1051//234 +f 187//32 1051//234 188//80 +f 188//33 1051//252 1050//288 +f 188//33 1050//291 189//35 +f 189//35 1050//251 1049//250 +f 189//35 1049//250 190//452 +f 190//38 1049//250 1048//453 +f 860//452 1479//248 851//41 +f 851//11 1479//213 1478//245 +f 851//41 1478//245 852//73 +f 852//12 1478//245 1477//243 +f 852//70 1477//243 853//13 +f 853//13 1477//243 1486//265 +f 853//13 1486//242 856//14 +f 856//97 1486//265 1485//264 +f 856//14 1485//305 857//50 +f 857//505 1485//264 1474//263 +f 857//103 1474//454 834//52 +f 834//52 1474//263 1473//261 +f 834//52 1473//262 835//54 +f 835//82 1473//261 1472//308 +f 835//54 1472//259 845//55 +f 845//55 1472//308 1466//257 +f 845//65 1466//509 846//17 +f 846//471 1466//257 1465//456 +f 846//455 1465//472 847//18 +f 847//43 1465//276 1484//225 +f 847//18 1484//255 838//44 +f 838//45 1484//255 1482//224 +f 838//196 1482//403 837//46 +f 837//75 1482//224 1481//253 +f 837//46 1481//253 836//47 +f 836//94 1481//253 1497//229 +f 836//474 1497//303 854//21 +f 854//92 1497//229 1496//395 +f 854//92 1496//395 855//22 +f 855//84 1496//228 1492//227 +f 855//84 1492//293 839//42 +f 839//49 1492//227 1491//241 +f 839//42 1491//258 1//1 +f 1//1 1491//226 1490//240 +f 1//1 1490//246 2//457 +f 2//457 1490//240 1495//458 +f 2//457 1495//458 831//27 +f 831//36 1495//458 1494//238 +f 831//27 1494//238 832//31 +f 832//23 1494//238 1493//231 +f 832//28 1493//237 833//29 +f 833//81 1493//231 1489//292 +f 833//29 1489//292 840//56 +f 840//497 1489//235 1488//298 +f 840//497 1488//477 841//57 +f 841//90 1488//236 1487//326 +f 841//57 1487//295 830//62 +f 830//62 1487//223 1471//222 +f 830//62 1471//266 829//15 +f 829//119 1471//222 1470//376 +f 829//15 1470//274 828//16 +f 828//16 1470//273 1469//272 +f 828//66 1469//510 827//64 +f 827//499 1469//272 1461//460 +f 827//459 1461//500 842//19 +f 842//511 1461//271 1460//270 +f 842//19 1460//275 843//20 +f 843//60 1460//275 1459//269 +f 843//101 1459//294 844//67 +f 844//61 1459//269 1458//281 +f 844//67 1458//281 848//24 +f 848//461 1458//281 1476//311 +f 848//24 1476//280 849//25 +f 849//200 1476//230 1475//232 +f 849//25 1475//307 850//30 +f 850//32 1475//232 1468//234 +f 850//30 1468//234 858//33 +f 858//33 1468//234 1467//288 +f 858//33 1467//251 859//35 +f 859//35 1467//291 1480//250 +f 859//35 1480//284 860//38 +f 860//39 1480//250 1479//453 +f 152//452 1008//512 153//41 +f 153//11 1008//213 1013//245 +f 153//41 1013//245 150//73 +f 150//12 1013//245 1012//243 +f 150//70 1012//282 144//13 +f 144//48 1012//243 1011//242 +f 144//13 1011//242 145//14 +f 145//97 1011//265 1003//310 +f 145//14 1003//305 136//50 +f 136//505 1003//264 1002//263 +f 136//50 1002//309 137//52 +f 137//52 1002//263 1001//261 +f 137//51 1001//262 138//54 +f 138//82 1001//261 1000//308 +f 138//54 1000//308 122//55 +f 122//55 1000//260 999//257 +f 122//55 999//278 123//17 +f 123//471 999//257 984//456 +f 123//455 984//472 125//18 +f 125//43 984//276 983//255 +f 125//18 983//255 126//44 +f 126//45 983//255 981//224 +f 126//196 981//403 115//46 +f 115//75 981//224 980//285 +f 115//46 980//253 116//47 +f 116//94 980//253 979//229 +f 116//47 979//475 127//21 +f 127//201 979//229 978//228 +f 127//21 978//304 128//22 +f 128//22 978//228 998//227 +f 128//84 998//227 129//42 +f 129//42 998//227 997//241 +f 129//42 997//258 133//1 +f 133//1 997//226 996//240 +f 133//1 996//246 134//2 +f 134//513 996//240 995//458 +f 134//457 995//514 135//27 +f 135//36 995//239 994//238 +f 135//27 994//238 130//31 +f 130//23 994//238 993//231 +f 130//28 993//237 131//29 +f 131//29 993//231 992//292 +f 131//29 992//235 132//56 +f 132//86 992//235 991//236 +f 132//56 991//477 117//57 +f 117//180 991//236 990//326 +f 117//57 990//295 118//62 +f 118//62 990//223 989//222 +f 118//74 989//266 119//15 +f 119//119 989//222 988//376 +f 119//15 988//274 120//16 +f 120//16 988//273 987//272 +f 120//16 987//286 121//64 +f 121//499 987//272 986//460 +f 121//459 986//500 142//19 +f 142//59 986//271 985//275 +f 142//19 985//275 143//20 +f 143//60 985//275 1007//269 +f 143//101 1007//294 139//67 +f 139//67 1007//269 1006//267 +f 139//67 1006//281 140//24 +f 140//77 1006//281 1005//230 +f 140//461 1005//280 147//25 +f 147//200 1005//230 1016//232 +f 147//102 1016//307 148//30 +f 148//32 1016//232 1015//234 +f 148//32 1015//252 149//33 +f 149//80 1015//234 1014//288 +f 149//33 1014//251 151//35 +f 151//35 1014//291 1009//250 +f 151//35 1009//284 152//38 +f 152//515 1009//250 1008//453 +f 813//452 1552//512 814//41 +f 814//11 1552//213 1571//245 +f 814//41 1571//245 805//73 +f 805//12 1571//245 1570//243 +f 805//70 1570//282 806//13 +f 806//48 1570//243 1551//242 +f 806//13 1551//265 807//14 +f 807//97 1551//265 1550//310 +f 807//194 1550//310 808//50 +f 808//505 1550//264 1549//263 +f 808//50 1549//309 815//52 +f 815//52 1549//263 1573//261 +f 815//51 1573//262 816//54 +f 816//82 1573//261 1572//308 +f 816//54 1572//259 817//55 +f 817//55 1572//260 1569//257 +f 817//65 1569//278 818//17 +f 818//471 1569//257 1568//456 +f 818//455 1568//472 819//18 +f 819//43 1568//276 1567//255 +f 819//18 1567//255 820//44 +f 820//45 1567//255 1548//224 +f 820//196 1548//403 799//46 +f 799//75 1548//224 1547//285 +f 799//46 1547//253 800//47 +f 800//94 1547//253 1546//229 +f 800//47 1546//475 801//21 +f 801//201 1546//229 1545//395 +f 801//92 1545//304 802//22 +f 802//22 1545//228 1544//227 +f 802//84 1544//293 809//42 +f 809//49 1544//227 1543//241 +f 809//42 1543//241 810//1 +f 810//1 1543//226 1540//240 +f 810//1 1540//246 811//2 +f 811//513 1540//240 1542//458 +f 811//457 1542//514 785//27 +f 785//36 1542//239 1566//238 +f 785//27 1566//238 786//31 +f 786//28 1566//238 1565//231 +f 786//28 1565//237 787//29 +f 787//81 1565//231 1564//292 +f 787//29 1564//235 788//56 +f 788//86 1564//235 1563//236 +f 788//56 1563//477 789//57 +f 789//180 1563//236 1562//223 +f 789//57 1562//295 795//62 +f 795//62 1562//223 1561//222 +f 795//74 1561//266 794//15 +f 794//119 1561//222 1576//376 +f 794//15 1576//274 793//16 +f 793//16 1576//273 1575//272 +f 793//16 1575//286 796//64 +f 796//499 1575//272 1574//460 +f 796//459 1574//500 797//19 +f 797//59 1574//271 1560//270 +f 797//19 1560//275 798//20 +f 798//60 1560//275 1559//269 +f 798//101 1559//294 803//67 +f 803//61 1559//269 1558//267 +f 803//67 1558//281 804//24 +f 804//77 1558//281 1557//230 +f 804//24 1557//280 790//25 +f 790//102 1557//230 1556//312 +f 790//25 1556//307 791//30 +f 791//30 1556//232 1555//234 +f 791//32 1555//252 792//33 +f 792//80 1555//234 1554//288 +f 792//33 1554//251 812//35 +f 812//35 1554//291 1553//250 +f 812//35 1553//284 813//38 +f 813//515 1553//250 1552//453 +f 463//452 876//512 472//41 +f 472//516 876//213 875//212 +f 472//41 875//245 473//73 +f 473//12 875//245 1368//243 +f 473//70 1368//282 475//13 +f 475//48 1368//243 1367//265 +f 475//13 1367//265 491//14 +f 491//97 1367//265 1382//310 +f 491//194 1382//305 492//50 +f 492//505 1382//264 1381//263 +f 492//50 1381//309 493//52 +f 493//52 1381//263 1380//261 +f 493//51 1380//262 497//54 +f 497//82 1380//261 1379//308 +f 497//54 1379//259 498//55 +f 498//55 1379//260 1378//257 +f 498//55 1378//278 499//17 +f 499//471 1378//257 1390//456 +f 499//455 1390//472 481//18 +f 481//43 1390//276 1389//255 +f 481//18 1389//255 482//44 +f 482//45 1389//255 1388//224 +f 482//196 1388//403 483//46 +f 483//75 1388//224 1377//285 +f 483//46 1377//253 486//47 +f 486//94 1377//253 1376//303 +f 486//47 1376//475 487//21 +f 487//201 1376//229 1375//395 +f 487//92 1375//304 467//22 +f 467//22 1375//228 1366//227 +f 467//22 1366//293 468//42 +f 468//49 1366//227 1365//241 +f 468//42 1365//258 470//1 +f 470//1 1365//226 1364//240 +f 470//1 1364//246 471//2 +f 471//513 1364//240 1362//458 +f 471//457 1362//514 459//27 +f 459//36 1362//239 1361//238 +f 459//27 1361//238 460//28 +f 460//23 1361//238 1359//231 +f 460//28 1359//237 462//29 +f 462//81 1359//231 1358//235 +f 462//29 1358//235 476//56 +f 476//86 1358//235 1374//298 +f 476//497 1374//477 477//57 +f 477//180 1374//236 1373//223 +f 477//57 1373//295 478//62 +f 478//74 1373//223 1372//222 +f 478//74 1372//222 488//15 +f 488//119 1372//222 1387//376 +f 488//15 1387//274 489//16 +f 489//16 1387//273 1386//272 +f 489//16 1386//286 490//64 +f 490//58 1386//272 1385//460 +f 490//459 1385//380 479//19 +f 479//59 1385//271 1384//275 +f 479//19 1384//275 480//20 +f 480//60 1384//275 1383//269 +f 480//101 1383//294 484//67 +f 484//67 1383//269 1371//267 +f 484//67 1371//267 485//24 +f 485//77 1371//281 1370//230 +f 485//24 1370//280 456//25 +f 456//200 1370//230 1369//312 +f 456//102 1369//307 457//30 +f 457//30 1369//232 1356//234 +f 457//30 1356//252 466//33 +f 466//80 1356//234 1355//288 +f 466//33 1355//251 465//35 +f 465//35 1355//291 1363//250 +f 465//68 1363//517 463//38 +f 463//515 1363//250 876//453 +f 672//452 1706//512 673//41 +f 673//11 1706//213 1705//212 +f 673//41 1705//245 674//73 +f 674//12 1705//245 1704//243 +f 674//70 1704//282 675//13 +f 675//48 1704//243 1703//242 +f 675//13 1703//265 676//14 +f 676//194 1703//265 1702//310 +f 676//194 1702//310 677//50 +f 677//485 1702//264 1701//470 +f 677//50 1701//470 678//52 +f 678//52 1701//470 1700//261 +f 678//51 1700//262 679//54 +f 679//82 1700//261 1699//308 +f 679//54 1699//259 680//55 +f 680//55 1699//260 1676//257 +f 680//55 1676//278 681//17 +f 681//96 1676//257 1675//456 +f 681//455 1675//256 682//18 +f 682//43 1675//276 1698//255 +f 682//18 1698//255 683//44 +f 683//45 1698//255 1697//224 +f 683//196 1697//403 669//46 +f 669//75 1697//224 1696//285 +f 669//46 1696//253 670//47 +f 670//94 1696//253 1695//229 +f 670//47 1695//475 684//21 +f 684//92 1695//229 1694//395 +f 684//92 1694//395 685//22 +f 685//22 1694//228 1693//227 +f 685//84 1693//293 686//42 +f 686//49 1693//227 1682//241 +f 686//42 1682//241 687//1 +f 687//1 1682//226 1681//240 +f 687//1 1681//246 688//2 +f 688//513 1681//240 1710//458 +f 688//457 1710//514 689//27 +f 689//36 1710//239 1709//238 +f 689//27 1709//238 653//31 +f 653//28 1709//238 1708//231 +f 653//28 1708//231 654//29 +f 654//81 1708//231 1692//292 +f 654//29 1692//235 658//56 +f 658//497 1692//235 1691//298 +f 658//497 1691//298 659//57 +f 659//180 1691//236 1690//223 +f 659//57 1690//295 660//62 +f 660//62 1690//223 1689//222 +f 660//74 1689//266 656//15 +f 656//119 1689//222 1688//376 +f 656//15 1688//274 657//16 +f 657//16 1688//273 1687//272 +f 657//66 1687//286 661//518 +f 661//519 1687//272 1686//520 +f 661//518 1686//521 662//19 +f 662//19 1686//520 1685//270 +f 662//19 1685//270 663//20 +f 663//60 1685//275 1684//269 +f 663//101 1684//294 667//67 +f 667//61 1684//269 1683//267 +f 667//67 1683//281 668//478 +f 668//478 1683//281 1680//230 +f 668//478 1680//479 666//25 +f 666//102 1680//311 1679//312 +f 666//102 1679//312 665//30 +f 665//30 1679//232 1678//234 +f 665//32 1678//252 664//33 +f 664//80 1678//234 1677//288 +f 664//33 1677//251 671//35 +f 671//35 1677//291 1707//250 +f 671//35 1707//284 672//38 +f 672//515 1707//250 1706//453 +f 106//452 972//512 107//41 +f 107//11 972//213 971//245 +f 107//41 971//245 112//73 +f 112//12 971//245 967//243 +f 112//70 967//282 113//13 +f 113//48 967//243 966//242 +f 113//13 966//242 114//14 +f 114//97 966//265 965//522 +f 114//14 965//305 109//50 +f 109//505 965//264 962//454 +f 109//50 962//309 110//52 +f 110//52 962//263 961//261 +f 110//51 961//261 111//54 +f 111//54 961//261 964//308 +f 111//54 964//308 80//523 +f 80//524 964//259 963//525 +f 80//523 963//526 81//17 +f 81//96 963//525 960//456 +f 81//455 960//256 82//527 +f 82//528 960//276 959//529 +f 82//527 959//530 83//45 +f 83//196 959//529 958//224 +f 83//196 958//224 84//46 +f 84//75 958//224 957//285 +f 84//46 957//253 85//47 +f 85//94 957//253 956//229 +f 85//474 956//475 86//531 +f 86//531 956//229 955//228 +f 86//21 955//304 87//22 +f 87//22 955//532 954//227 +f 87//84 954//227 96//42 +f 96//42 954//227 953//241 +f 96//42 953//258 97//1 +f 97//1 953//226 952//240 +f 97//1 952//246 98//2 +f 98//513 952//240 951//458 +f 98//457 951//514 88//27 +f 88//36 951//239 950//249 +f 88//27 950//238 89//31 +f 89//23 950//238 949//231 +f 89//28 949//231 90//29 +f 90//29 949//231 948//292 +f 90//29 948//235 91//506 +f 91//86 948//235 947//236 +f 91//56 947//507 92//57 +f 92//180 947//507 946//326 +f 92//57 946//295 93//62 +f 93//62 946//223 945//222 +f 93//74 945//266 94//15 +f 94//15 945//222 944//376 +f 94//15 944//376 95//533 +f 95//534 944//274 943//535 +f 95//533 943//536 79//64 +f 79//58 943//535 941//460 +f 79//459 941//380 32//537 +f 32//538 941//271 940//539 +f 32//537 940//540 33//60 +f 33//101 940//539 970//269 +f 33//101 970//269 102//67 +f 102//67 970//269 969//267 +f 102//67 969//281 99//24 +f 99//77 969//281 968//230 +f 99//461 968//280 100//25 +f 100//200 968//230 976//232 +f 100//508 976//307 103//30 +f 103//32 976//232 975//234 +f 103//32 975//252 104//33 +f 104//80 975//234 974//288 +f 104//33 974//251 105//35 +f 105//35 974//291 973//250 +f 105//68 973//284 106//38 +f 106//515 973//250 972//453 +f 553//452 1327//248 548//41 +f 548//11 1327//213 1335//245 +f 548//41 1335//245 549//73 +f 549//12 1335//245 1334//243 +f 549//70 1334//243 550//13 +f 550//13 1334//243 1326//242 +f 550//13 1326//265 544//14 +f 544//97 1326//265 1325//264 +f 544//14 1325//305 542//485 +f 542//505 1325//264 1333//263 +f 542//485 1333//309 538//52 +f 538//51 1333//263 1332//261 +f 538//51 1332//262 539//54 +f 539//82 1332//261 1331//308 +f 539//54 1331//259 540//55 +f 540//55 1331//260 1323//257 +f 540//55 1323//278 541//17 +f 541//96 1323//257 1322//456 +f 541//455 1322//256 530//18 +f 530//43 1322//276 1321//255 +f 530//18 1321//255 531//44 +f 531//45 1321//255 1319//224 +f 531//196 1319//403 528//46 +f 528//75 1319//224 1318//285 +f 528//46 1318//253 526//486 +f 526//94 1318//253 1317//229 +f 526//486 1317//475 524//21 +f 524//92 1317//229 1315//395 +f 524//201 1315//395 532//84 +f 532//22 1315//228 1338//541 +f 532//84 1338//293 533//42 +f 533//49 1338//227 1337//241 +f 533//42 1337//258 534//1 +f 534//1 1337//226 1336//240 +f 534//1 1336//246 515//457 +f 515//457 1336//240 1341//458 +f 515//457 1341//458 516//27 +f 516//36 1341//458 1340//238 +f 516//27 1340//238 522//31 +f 522//23 1340//238 1339//231 +f 522//28 1339//237 523//29 +f 523//81 1339//231 1313//292 +f 523//29 1313//292 518//56 +f 518//86 1313//235 1312//507 +f 518//497 1312//477 519//57 +f 519//90 1312//236 1311//326 +f 519//57 1311//295 520//62 +f 520//62 1311//223 1310//222 +f 520//74 1310//266 521//15 +f 521//119 1310//222 1309//376 +f 521//15 1309//274 512//16 +f 512//16 1309//273 1307//272 +f 512//66 1307//272 513//518 +f 513//519 1307//272 1306//520 +f 513//518 1306//521 535//19 +f 535//19 1306//520 1305//270 +f 535//19 1305//275 536//20 +f 536//60 1305//275 1304//269 +f 536//101 1304//294 537//67 +f 537//61 1304//269 1303//267 +f 537//67 1303//267 545//24 +f 545//461 1303//281 1302//311 +f 545//24 1302//280 546//508 +f 546//508 1302//230 1301//232 +f 546//508 1301//542 547//30 +f 547//32 1301//542 1330//234 +f 547//30 1330//234 551//33 +f 551//33 1330//234 1329//288 +f 551//33 1329//251 552//35 +f 552//35 1329//291 1328//250 +f 552//35 1328//284 553//38 +f 553//39 1328//250 1327//453 +f 577//38 1261//469 576//41 +f 576//11 1261//469 1290//245 +f 576//41 1290//245 581//73 +f 581//12 1290//245 1289//243 +f 581//73 1289//282 582//13 +f 582//48 1289//243 1288//265 +f 582//13 1288//265 583//543 +f 583//543 1288//265 1287//522 +f 583//543 1287//522 584//50 +f 584//103 1287//522 1286//454 +f 584//505 1286//454 585//51 +f 585//51 1286//263 1285//261 +f 585//51 1285//262 586//54 +f 586//54 1285//261 1282//308 +f 586//54 1282//308 594//523 +f 594//524 1282//259 1283//525 +f 594//523 1283//526 595//17 +f 595//96 1283//525 1284//456 +f 595//455 1284//256 596//527 +f 596//528 1284//276 1281//529 +f 596//527 1281//530 587//45 +f 587//196 1281//529 1280//224 +f 587//196 1280//224 588//46 +f 588//75 1280//224 1279//285 +f 588//46 1279//285 589//47 +f 589//474 1279//285 1266//475 +f 589//474 1266//303 590//531 +f 590//531 1266//229 1265//532 +f 590//531 1265//532 591//22 +f 591//22 1265//532 1272//227 +f 591//22 1272//293 592//42 +f 592//49 1272//227 1278//226 +f 592//42 1278//258 593//1 +f 593//1 1278//226 1277//240 +f 593//1 1277//246 560//2 +f 560//476 1277//240 1276//458 +f 560//457 1276//354 561//27 +f 561//36 1276//239 1271//238 +f 561//27 1271//238 568//31 +f 568//23 1271//238 1298//231 +f 568//31 1298//237 569//29 +f 569//81 1298//231 1297//235 +f 569//29 1297//235 570//506 +f 570//506 1297//235 1296//507 +f 570//506 1296//507 571//57 +f 571//90 1296//507 1295//326 +f 571//180 1295//326 572//74 +f 572//74 1295//223 1294//222 +f 572//74 1294//266 562//15 +f 562//15 1294//222 1263//376 +f 562//15 1263//376 563//533 +f 563//534 1263//274 1262//535 +f 563//533 1262//536 567//64 +f 567//58 1262//535 1268//460 +f 567//459 1268//380 566//537 +f 566//538 1268//271 1293//539 +f 566//537 1293//540 564//60 +f 564//101 1293//539 1292//269 +f 564//101 1292//269 573//67 +f 573//61 1292//269 1291//267 +f 573//67 1291//267 574//24 +f 574//461 1291//267 1275//280 +f 574//461 1275//311 575//508 +f 575//508 1275//230 1274//542 +f 575//508 1274//542 579//30 +f 579//30 1274//542 1273//234 +f 579//30 1273//252 580//33 +f 580//80 1273//234 1258//291 +f 580//33 1258//251 578//35 +f 578//68 1258//291 1260//250 +f 578//35 1260//284 577//480 +f 577//480 1260//250 1261//213 +f 618//452 1624//248 619//481 +f 619//482 1624//213 1633//483 +f 619//41 1633//484 614//12 +f 614//12 1633//483 1631//243 +f 614//12 1631//243 613//13 +f 613//13 1631//243 1630//544 +f 613//13 1630//265 611//14 +f 611//194 1630//265 1657//264 +f 611//14 1657//305 625//485 +f 625//485 1657//264 1656//263 +f 625//485 1656//470 626//52 +f 626//52 1656//470 1655//261 +f 626//51 1655//262 627//54 +f 627//82 1655//261 1654//308 +f 627//54 1654//308 639//55 +f 639//55 1654//260 1653//257 +f 639//55 1653//278 640//17 +f 640//96 1653//257 1652//456 +f 640//455 1652//256 641//18 +f 641//43 1652//276 1651//255 +f 641//18 1651//255 628//44 +f 628//45 1651//255 1650//224 +f 628//196 1650//403 629//46 +f 629//75 1650//224 1646//285 +f 629//46 1646//253 642//486 +f 642//486 1646//253 1645//545 +f 642//486 1645//545 643//21 +f 643//92 1645//303 1644//304 +f 643//21 1644//395 615//22 +f 615//22 1644//228 1627//227 +f 615//22 1627//293 616//42 +f 616//49 1627//541 1626//226 +f 616//49 1626//226 620//1 +f 620//487 1626//226 1643//488 +f 620//489 1643//490 621//2 +f 621//476 1643//491 1642//458 +f 621//457 1642//354 622//492 +f 622//493 1642//239 1641//494 +f 622//495 1641//496 606//31 +f 606//31 1641//238 1640//237 +f 606//31 1640//237 607//546 +f 607//81 1640//231 1659//235 +f 607//29 1659//235 630//56 +f 630//497 1659//235 1658//236 +f 630//86 1658//298 631//90 +f 631//547 1658//236 1649//498 +f 631//547 1649//498 623//62 +f 623//62 1649//498 1648//222 +f 623//74 1648//266 624//15 +f 624//119 1648//222 1647//376 +f 624//15 1647//274 632//16 +f 632//16 1647//273 1629//272 +f 632//66 1629//286 633//518 +f 633//519 1629//272 1628//520 +f 633//518 1628//521 634//19 +f 634//19 1628//520 1639//270 +f 634//19 1639//270 635//20 +f 635//101 1639//275 1638//269 +f 635//101 1638//294 636//67 +f 636//61 1638//269 1637//267 +f 636//67 1637//281 637//478 +f 637//478 1637//281 1636//479 +f 637//24 1636//479 638//25 +f 638//200 1636//479 1635//232 +f 638//25 1635//312 608//30 +f 608//30 1635//232 1634//234 +f 608//548 1634//234 609//33 +f 609//33 1634//234 1622//251 +f 609//33 1622//251 617//501 +f 617//502 1622//251 1621//250 +f 617//501 1621//503 618//38 +f 618//39 1621//504 1624//453 +f 53//452 918//453 55//41 +f 55//11 918//453 916//245 +f 55//41 916//245 57//73 +f 57//12 916//245 914//243 +f 57//70 914//282 63//13 +f 63//48 914//243 913//242 +f 63//13 913//265 64//14 +f 64//97 913//265 930//264 +f 64//14 930//305 65//50 +f 65//505 930//264 929//263 +f 65//50 929//309 66//52 +f 66//52 929//263 928//261 +f 66//51 928//262 67//54 +f 67//82 928//261 927//308 +f 67//54 927//259 68//55 +f 68//55 927//260 926//257 +f 68//55 926//278 58//17 +f 58//455 926//257 925//456 +f 58//455 925//456 59//18 +f 59//43 925//276 924//225 +f 59//18 924//255 60//44 +f 60//45 924//255 923//224 +f 60//196 923//403 61//46 +f 61//75 923//224 922//253 +f 61//46 922//253 62//47 +f 62//94 922//253 900//229 +f 62//474 900//475 35//21 +f 35//201 900//229 899//395 +f 35//92 899//304 36//84 +f 36//22 899//228 897//541 +f 36//22 897//293 41//42 +f 41//49 897//227 896//241 +f 41//42 896//258 42//1 +f 42//40 896//241 911//246 +f 42//40 911//246 44//2 +f 44//457 911//240 910//458 +f 44//457 910//458 45//27 +f 45//36 910//239 909//249 +f 45//36 909//249 46//31 +f 46//23 909//238 905//231 +f 46//28 905//237 47//29 +f 47//81 905//231 907//235 +f 47//546 907//235 69//56 +f 69//86 907//292 908//298 +f 69//497 908//477 70//57 +f 70//180 908//236 933//326 +f 70//57 933//295 76//62 +f 76//62 933//223 932//222 +f 76//62 932//266 77//15 +f 77//119 932//222 939//376 +f 77//15 939//274 78//16 +f 78//16 939//273 938//272 +f 78//66 938//286 72//64 +f 72//459 938//272 937//460 +f 72//459 937//460 73//19 +f 73//59 937//271 936//275 +f 73//19 936//275 74//20 +f 74//60 936//275 935//269 +f 74//101 935//294 75//67 +f 75//61 935//269 934//267 +f 75//67 934//281 39//24 +f 39//77 934//281 901//311 +f 39//24 901//280 40//25 +f 40//200 901//230 903//232 +f 40//25 903//307 48//30 +f 48//30 903//232 904//234 +f 48//32 904//252 49//33 +f 49//80 904//234 921//288 +f 49//33 921//251 51//35 +f 51//35 921//291 920//250 +f 51//35 920//284 53//452 +f 53//452 920//250 918//453 +f 363//452 1197//512 364//41 +f 364//11 1197//213 1195//245 +f 364//41 1195//245 355//73 +f 355//12 1195//245 1194//243 +f 355//70 1194//282 354//13 +f 354//48 1194//243 1191//265 +f 354//13 1191//265 353//14 +f 353//97 1191//265 1190//310 +f 353//14 1190//305 365//50 +f 365//505 1190//264 1209//263 +f 365//50 1209//309 366//52 +f 366//52 1209//263 1208//261 +f 366//51 1208//262 367//54 +f 367//82 1208//261 1207//308 +f 367//54 1207//259 368//55 +f 368//55 1207//260 1230//257 +f 368//55 1230//278 375//17 +f 375//455 1230//257 1228//456 +f 375//455 1228//456 373//18 +f 373//43 1228//276 1227//255 +f 373//18 1227//255 371//44 +f 371//45 1227//255 1225//224 +f 371//196 1225//403 369//46 +f 369//75 1225//224 1223//285 +f 369//46 1223//253 337//47 +f 337//94 1223//253 1221//229 +f 337//47 1221//475 338//21 +f 338//201 1221//229 1220//228 +f 338//21 1220//304 340//22 +f 340//22 1220//228 1219//227 +f 340//84 1219//293 341//42 +f 341//49 1219//227 1218//241 +f 341//42 1218//258 342//1 +f 342//1 1218//226 1217//240 +f 342//1 1217//246 343//457 +f 343//457 1217//240 1214//458 +f 343//457 1214//458 334//27 +f 334//36 1214//458 1215//238 +f 334//27 1215//238 335//31 +f 335//23 1215//238 1216//231 +f 335//28 1216//237 344//29 +f 344//81 1216//231 1206//292 +f 344//29 1206//235 345//56 +f 345//86 1206//235 1205//236 +f 345//56 1205//477 346//57 +f 346//180 1205//236 1204//223 +f 346//57 1204//295 347//62 +f 347//62 1204//223 1203//222 +f 347//74 1203//266 348//15 +f 348//119 1203//222 1202//376 +f 348//15 1202//274 349//16 +f 349//16 1202//273 1201//272 +f 349//16 1201//286 359//64 +f 359//459 1201//272 1193//460 +f 359//459 1193//460 360//19 +f 360//59 1193//271 1192//275 +f 360//19 1192//275 361//20 +f 361//60 1192//275 1213//269 +f 361//101 1213//294 351//67 +f 351//61 1213//269 1212//267 +f 351//67 1212//281 352//24 +f 352//77 1212//281 1200//230 +f 352//24 1200//280 356//25 +f 356//200 1200//230 1199//232 +f 356//102 1199//307 357//30 +f 357//30 1199//232 1211//234 +f 357//30 1211//252 358//33 +f 358//80 1211//234 1210//288 +f 358//33 1210//251 362//35 +f 362//35 1210//291 1198//250 +f 362//35 1198//284 363//38 +f 363//515 1198//250 1197//453 +f 710//452 1580//512 711//41 +f 711//11 1580//213 1596//245 +f 711//41 1596//245 712//73 +f 712//12 1596//245 1595//243 +f 712//70 1595//282 713//13 +f 713//48 1595//243 1594//265 +f 713//13 1594//265 714//14 +f 714//97 1594//265 1593//310 +f 714//14 1593//305 715//50 +f 715//505 1593//264 1592//263 +f 715//50 1592//309 716//52 +f 716//52 1592//263 1591//261 +f 716//51 1591//262 723//54 +f 723//82 1591//261 1590//308 +f 723//54 1590//259 724//55 +f 724//55 1590//260 1606//257 +f 724//65 1606//278 725//17 +f 725//455 1606//257 1605//456 +f 725//455 1605//456 696//18 +f 696//43 1605//276 1604//225 +f 696//18 1604//255 697//44 +f 697//45 1604//255 1589//224 +f 697//196 1589//403 717//46 +f 717//75 1589//224 1588//285 +f 717//46 1588//253 718//47 +f 718//94 1588//253 1587//229 +f 718//47 1587//475 719//21 +f 719//201 1587//229 1583//228 +f 719//21 1583//304 720//22 +f 720//22 1583//228 1582//227 +f 720//84 1582//293 721//42 +f 721//49 1582//227 1615//241 +f 721//42 1615//258 722//1 +f 722//1 1615//226 1614//240 +f 722//1 1614//246 693//457 +f 693//457 1614//240 1613//458 +f 693//457 1613//458 694//27 +f 694//36 1613//458 1612//238 +f 694//27 1612//238 695//31 +f 695//23 1612//238 1611//231 +f 695//28 1611//237 698//29 +f 698//81 1611//231 1610//292 +f 698//29 1610//235 699//56 +f 699//86 1610//235 1603//236 +f 699//56 1603//477 692//57 +f 692//180 1603//236 1602//223 +f 692//57 1602//295 691//62 +f 691//62 1602//223 1601//222 +f 691//74 1601//266 690//15 +f 690//119 1601//222 1600//376 +f 690//15 1600//274 700//16 +f 700//16 1600//273 1609//272 +f 700//16 1609//286 701//64 +f 701//459 1609//272 1608//460 +f 701//459 1608//460 702//19 +f 702//59 1608//271 1607//275 +f 702//19 1607//275 703//20 +f 703//60 1607//275 1599//269 +f 703//101 1599//294 704//67 +f 704//61 1599//269 1598//267 +f 704//67 1598//281 705//24 +f 705//77 1598//281 1597//230 +f 705//24 1597//280 706//25 +f 706//200 1597//230 1586//232 +f 706//102 1586//307 707//30 +f 707//30 1586//232 1585//234 +f 707//30 1585//252 708//33 +f 708//80 1585//234 1584//288 +f 708//33 1584//251 709//35 +f 709//35 1584//291 1581//250 +f 709//35 1581//284 710//38 +f 710//515 1581//250 1580//453 diff --git a/examples/python3/actuators/mesh/disqueBlender2.mtl b/examples/python3/actuators/mesh/disqueBlender2.mtl new file mode 100644 index 00000000..345c68b5 --- /dev/null +++ b/examples/python3/actuators/mesh/disqueBlender2.mtl @@ -0,0 +1,2 @@ +# Blender 3.6.1 MTL File: 'None' +# www.blender.org diff --git a/examples/python3/actuators/mesh/disqueBlender2.obj b/examples/python3/actuators/mesh/disqueBlender2.obj new file mode 100644 index 00000000..03b1e2c0 --- /dev/null +++ b/examples/python3/actuators/mesh/disqueBlender2.obj @@ -0,0 +1,5785 @@ +# Blender 3.6.1 +# www.blender.org +mtllib disqueBlender2.mtl +o disqueMeshLab +v 0.200000 -2.289581 -0.059089 +v 0.200000 -2.300000 -0.060000 +v 0.200000 -2.145929 -0.205000 +v 0.200000 1.814655 -1.861996 +v 0.200000 1.894455 -1.542500 +v 0.200000 1.408525 -1.542500 +v 0.200000 2.455672 0.854210 +v 0.200000 2.354826 1.102177 +v 0.200000 2.145929 0.982500 +v 0.200000 2.145929 1.167500 +v 0.200000 -2.354826 1.102177 +v 0.200000 -2.145929 0.982500 +v 0.200000 -2.145929 1.167500 +v 0.200000 -2.455672 0.854210 +v 0.200000 -2.480000 0.637500 +v 0.200000 -2.145929 0.637500 +v 0.200000 -1.162444 -2.325666 +v 0.200000 -0.917155 -2.432864 +v 0.200000 -0.854807 -2.088429 +v 0.200000 0.060777 0.344682 +v 0.200000 0.119707 0.328892 +v 0.200000 0.112500 0.637500 +v 0.200000 0.062500 -1.891747 +v 0.200000 0.080349 -1.904245 +v 0.200000 0.112500 -1.903430 +v 0.200000 -1.849512 0.957247 +v 0.200000 -1.855152 0.978294 +v 0.200000 -1.894454 0.982500 +v 0.200000 1.857051 1.000000 +v 0.200000 1.855152 0.978294 +v 0.200000 1.894455 0.982500 +v 0.200000 1.932770 1.160419 +v 0.200000 1.935477 1.170521 +v 0.200000 1.894455 1.167500 +v 0.200000 0.064279 -0.676605 +v 0.200000 0.050000 -0.686603 +v 0.200000 0.112500 -0.895000 +v 0.200000 -0.119707 -0.328893 +v 0.200000 -0.076604 -0.535721 +v 0.200000 -0.064279 -0.523396 +v 0.200000 0.034202 -0.693969 +v 0.200000 0.017365 -0.698481 +v 0.200000 -0.080000 -0.895000 +v 0.200000 0.000000 -0.700000 +v 0.200000 -0.017365 -0.698481 +v 0.200000 -0.034202 -0.693969 +v 0.200000 -0.050000 -0.686603 +v 0.200000 -0.050000 -0.513397 +v 0.200000 -0.034202 -0.506031 +v 0.200000 -0.060777 -0.344683 +v 0.200000 -0.017365 -0.501519 +v 0.200000 0.000000 -0.350000 +v 0.200000 0.000000 -0.500000 +v 0.200000 0.060777 -0.344683 +v 0.200000 0.017365 -0.501519 +v 0.200000 0.119707 -0.328893 +v 0.200000 0.034202 -0.506031 +v 0.200000 0.100000 -0.600000 +v 0.200000 0.098481 -0.617365 +v 0.200000 0.093970 -0.634202 +v 0.200000 0.086603 -0.650000 +v 0.200000 0.076605 -0.664279 +v 0.200000 0.050000 -0.513397 +v 0.200000 0.064279 -0.523396 +v 0.200000 0.076605 -0.535721 +v 0.200000 0.086603 -0.550000 +v 0.200000 0.093970 -0.565798 +v 0.200000 0.098481 -0.582635 +v 0.200000 -0.064279 -0.676605 +v 0.200000 -0.076604 -0.664279 +v 0.200000 -0.112500 -0.895000 +v 0.200000 -0.100000 -0.600000 +v 0.200000 -0.098481 -0.582635 +v 0.200000 -0.093969 -0.565798 +v 0.200000 -0.086602 -0.550000 +v 0.200000 -0.086602 -0.650000 +v 0.200000 -0.093969 -0.634202 +v 0.200000 -0.098481 -0.617365 +v 0.200000 1.931859 1.150000 +v 0.200000 2.050947 1.160419 +v 0.200000 2.051859 1.150000 +v 0.200000 2.050947 1.139581 +v 0.200000 2.048241 1.129479 +v 0.200000 2.043820 1.120000 +v 0.200000 2.037821 1.111432 +v 0.200000 2.030426 1.104037 +v 0.200000 2.021859 1.098038 +v 0.200000 1.981440 1.090911 +v 0.200000 1.971337 1.093618 +v 0.200000 1.961859 1.098038 +v 0.200000 1.953291 1.104037 +v 0.200000 1.945896 1.111432 +v 0.200000 1.939897 1.120000 +v 0.200000 1.935477 1.129479 +v 0.200000 1.932770 1.139581 +v 0.200000 2.012380 1.093618 +v 0.200000 2.002277 1.090911 +v 0.200000 1.991859 1.090000 +v 0.200000 1.945896 1.188567 +v 0.200000 1.953291 1.195963 +v 0.200000 1.894455 1.570929 +v 0.200000 1.939897 1.180000 +v 0.200000 1.961859 1.201961 +v 0.200000 1.971337 1.206381 +v 0.200000 1.981440 1.209088 +v 0.200000 1.991859 1.210000 +v 0.200000 2.002277 1.209088 +v 0.200000 2.079582 1.560557 +v 0.200000 2.037821 1.188567 +v 0.200000 2.043820 1.180000 +v 0.200000 2.048241 1.170521 +v 0.200000 2.012380 1.206381 +v 0.200000 2.021859 1.201961 +v 0.200000 2.030426 1.195963 +v 0.200000 -1.939897 1.120000 +v 0.200000 -1.945896 1.111432 +v 0.200000 -2.037821 1.111432 +v 0.200000 -2.043820 1.120000 +v 0.200000 -2.048240 1.129479 +v 0.200000 -2.050947 1.139581 +v 0.200000 -2.051858 1.150000 +v 0.200000 -1.932770 1.160419 +v 0.200000 -1.931858 1.150000 +v 0.200000 -1.894454 1.167500 +v 0.200000 -1.932770 1.139581 +v 0.200000 -1.935477 1.129479 +v 0.200000 -1.953291 1.104037 +v 0.200000 -1.961858 1.098038 +v 0.200000 -1.971337 1.093618 +v 0.200000 -2.012379 1.093618 +v 0.200000 -2.021858 1.098038 +v 0.200000 -2.030426 1.104037 +v 0.200000 -1.981439 1.090911 +v 0.200000 -1.991858 1.090000 +v 0.200000 -2.002277 1.090911 +v 0.200000 -1.945896 1.188567 +v 0.200000 -1.939897 1.180000 +v 0.200000 -1.935477 1.170521 +v 0.200000 -2.043820 1.180000 +v 0.200000 -2.037821 1.188567 +v 0.200000 -2.079582 1.560557 +v 0.200000 -2.050947 1.160419 +v 0.200000 -2.048240 1.170521 +v 0.200000 -1.961858 1.201961 +v 0.200000 -1.953291 1.195963 +v 0.200000 -1.894454 1.570929 +v 0.200000 -2.030426 1.195963 +v 0.200000 -2.021858 1.201961 +v 0.200000 -2.012379 1.206381 +v 0.200000 -1.971337 1.206381 +v 0.200000 -2.002277 1.209088 +v 0.200000 -1.991858 1.210000 +v 0.200000 -1.981439 1.209088 +v 0.200000 1.840304 0.937500 +v 0.200000 1.827806 0.919651 +v 0.200000 1.894455 0.637500 +v 0.200000 1.849513 0.957247 +v 0.200000 1.812399 0.904244 +v 0.200000 1.794551 0.891747 +v 0.200000 1.774804 0.882538 +v 0.200000 1.753757 0.876899 +v 0.200000 1.732051 0.875000 +v 0.200000 1.408525 0.637500 +v 0.200000 1.710345 0.876899 +v 0.200000 1.689299 0.882538 +v 0.200000 1.669551 0.891747 +v 0.200000 1.651703 0.904244 +v 0.200000 1.636295 0.919651 +v 0.200000 1.623798 0.937500 +v 0.200000 1.614590 0.957247 +v 0.200000 1.408525 0.982500 +v 0.200000 1.608950 0.978294 +v 0.200000 1.607051 1.000000 +v 0.200000 1.608950 1.021706 +v 0.200000 1.614590 1.042752 +v 0.200000 1.408525 1.167500 +v 0.200000 1.623798 1.062500 +v 0.200000 1.636295 1.080348 +v 0.200000 1.774804 1.117461 +v 0.200000 1.794551 1.108253 +v 0.200000 1.812399 1.095755 +v 0.200000 1.827806 1.080348 +v 0.200000 1.840304 1.062500 +v 0.200000 1.849513 1.042752 +v 0.200000 1.855152 1.021706 +v 0.200000 1.651703 1.095755 +v 0.200000 1.669551 1.108253 +v 0.200000 1.689299 1.117461 +v 0.200000 1.710345 1.123101 +v 0.200000 1.732051 1.125000 +v 0.200000 1.753757 1.123101 +v 0.200000 -1.840304 0.937500 +v 0.200000 -1.614589 0.957247 +v 0.200000 -1.623797 0.937500 +v 0.200000 -1.408525 0.637500 +v 0.200000 -1.636295 0.919651 +v 0.200000 -1.651702 0.904244 +v 0.200000 -1.669551 0.891747 +v 0.200000 -1.894454 0.637500 +v 0.200000 -1.753757 0.876899 +v 0.200000 -1.774803 0.882538 +v 0.200000 -1.689298 0.882538 +v 0.200000 -1.710345 0.876899 +v 0.200000 -1.732051 0.875000 +v 0.200000 -1.794551 0.891747 +v 0.200000 -1.812399 0.904244 +v 0.200000 -1.827806 0.919651 +v 0.200000 -1.840304 1.062500 +v 0.200000 -1.827806 1.080348 +v 0.200000 -1.689298 1.117461 +v 0.200000 -1.669551 1.108253 +v 0.200000 -1.408525 1.167500 +v 0.200000 -1.614589 1.042752 +v 0.200000 -1.608950 1.021706 +v 0.200000 -1.408525 0.982500 +v 0.200000 -1.607051 1.000000 +v 0.200000 -1.608950 0.978294 +v 0.200000 -1.857051 1.000000 +v 0.200000 -1.855152 1.021706 +v 0.200000 -1.849512 1.042752 +v 0.200000 -1.651702 1.095755 +v 0.200000 -1.636295 1.080348 +v 0.200000 -1.623797 1.062500 +v 0.200000 -1.812399 1.095755 +v 0.200000 -1.794551 1.108253 +v 0.200000 -1.774803 1.117461 +v 0.200000 -1.753757 1.123101 +v 0.200000 -1.732051 1.125000 +v 0.200000 -1.710345 1.123101 +v 0.200000 0.000000 -2.600000 +v 0.200000 0.000000 -2.360001 +v 0.200000 -0.010419 -2.359089 +v 0.200000 -0.062500 -2.108253 +v 0.200000 -0.080348 -2.095756 +v 0.200000 -0.020521 -2.243618 +v 0.200000 0.010419 -2.240911 +v 0.200000 0.020521 -2.243618 +v 0.200000 0.021706 -2.123101 +v 0.200000 -0.030000 -2.248039 +v 0.200000 0.042753 -2.117462 +v 0.200000 0.030000 -2.351962 +v 0.200000 0.020521 -2.356382 +v 0.200000 0.133845 -2.596553 +v 0.200000 -0.059088 -2.289581 +v 0.200000 -0.056381 -2.279479 +v 0.200000 -0.051961 -2.270000 +v 0.200000 -0.133845 -2.596553 +v 0.200000 -0.020521 -2.356382 +v 0.200000 -0.030000 -2.351962 +v 0.200000 -0.038567 -2.345963 +v 0.200000 -0.045962 -2.338568 +v 0.200000 -0.051961 -2.330000 +v 0.200000 -0.045962 -2.261433 +v 0.200000 -0.038567 -2.254038 +v 0.200000 0.000000 -2.240000 +v 0.200000 0.000000 -2.125000 +v 0.200000 -0.010419 -2.240911 +v 0.200000 -0.021706 -2.123101 +v 0.200000 -0.042752 -2.117462 +v 0.200000 0.112500 -2.088429 +v 0.200000 0.095756 -2.080349 +v 0.200000 0.080349 -2.095756 +v 0.200000 0.038568 -2.254038 +v 0.200000 0.045963 -2.261433 +v 0.200000 0.051962 -2.270000 +v 0.200000 0.010419 -2.359089 +v 0.200000 -0.056381 -2.320521 +v 0.200000 -0.059088 -2.310419 +v 0.200000 -0.060000 -2.300000 +v 0.200000 0.030000 -2.248039 +v 0.200000 0.062500 -2.108253 +v 0.200000 0.051962 -2.330000 +v 0.200000 0.045963 -2.338568 +v 0.200000 0.038568 -2.345963 +v 0.200000 0.060000 -2.300000 +v 0.200000 0.059089 -2.310419 +v 0.200000 0.056382 -2.320521 +v 0.200000 0.056382 -2.279479 +v 0.200000 0.059089 -2.289581 +v 0.200000 0.384808 -2.088429 +v 0.200000 0.117462 -2.042753 +v 0.200000 0.108253 -2.062500 +v 0.200000 0.123101 -1.978294 +v 0.200000 0.125000 -2.000000 +v 0.200000 0.123101 -2.021706 +v 0.200000 0.117462 -1.957248 +v 0.200000 0.384808 -1.903430 +v 0.200000 0.108253 -1.937500 +v 0.200000 0.095756 -1.919652 +v 0.200000 -0.062500 -1.891747 +v 0.200000 -0.042752 -1.882539 +v 0.200000 -0.080000 -1.542500 +v 0.200000 -0.021706 -1.876899 +v 0.200000 0.000000 -1.875000 +v 0.200000 0.112500 -1.542500 +v 0.200000 0.021706 -1.876899 +v 0.200000 0.042753 -1.882539 +v 0.200000 -0.080348 -1.904245 +v 0.200000 -0.080000 -1.903430 +v 0.200000 -0.095755 -1.919652 +v 0.200000 -0.112500 -1.903430 +v 0.200000 -0.108253 -2.062500 +v 0.200000 -0.117461 -2.042753 +v 0.200000 -0.854807 -1.903430 +v 0.200000 -0.117461 -1.957248 +v 0.200000 -0.108253 -1.937500 +v 0.200000 -0.123101 -2.021706 +v 0.200000 -0.125000 -2.000000 +v 0.200000 -0.123101 -1.978294 +v 0.200000 -0.112500 -2.088429 +v 0.200000 -0.095755 -2.080349 +v 0.200000 0.175000 -0.303109 +v 0.200000 0.384808 -0.895000 +v 0.200000 0.344683 -0.060777 +v 0.200000 0.328893 -0.119707 +v 0.200000 0.384808 -0.205000 +v 0.200000 0.303109 -0.175000 +v 0.200000 0.268116 -0.224976 +v 0.200000 0.224976 -0.268116 +v 0.200000 0.350000 -0.000000 +v 0.200000 0.384808 0.130000 +v 0.200000 0.344683 0.060777 +v 0.200000 0.384808 0.637500 +v 0.200000 0.175000 0.303109 +v 0.200000 0.224976 0.268115 +v 0.200000 0.268116 0.224975 +v 0.200000 0.303109 0.175000 +v 0.200000 0.328893 0.119707 +v 0.200000 0.000000 0.350000 +v 0.200000 -0.080000 0.637500 +v 0.200000 -0.060777 0.344682 +v 0.200000 -0.112500 0.637500 +v 0.200000 -0.112648 0.331376 +v 0.200000 -0.536980 0.201519 +v 0.200000 -0.553817 0.206031 +v 0.200000 -0.854807 0.130000 +v 0.200000 -0.443011 0.235721 +v 0.200000 -0.455336 0.223395 +v 0.200000 -0.328892 0.119707 +v 0.200000 -0.469615 0.213397 +v 0.200000 -0.485413 0.206031 +v 0.200000 -0.502250 0.201519 +v 0.200000 -0.519615 0.200000 +v 0.200000 -0.569615 0.213397 +v 0.200000 -0.583894 0.223395 +v 0.200000 -0.596220 0.235721 +v 0.200000 -0.606218 0.250000 +v 0.200000 -0.613584 0.265798 +v 0.200000 -0.618096 0.282635 +v 0.200000 -0.854807 0.637500 +v 0.200000 -0.606218 0.350000 +v 0.200000 -0.596220 0.364279 +v 0.200000 -0.455336 0.376604 +v 0.200000 -0.469615 0.386602 +v 0.200000 -0.485413 0.393969 +v 0.200000 -0.583894 0.376604 +v 0.200000 -0.569615 0.386602 +v 0.200000 -0.553817 0.393969 +v 0.200000 -0.619615 0.300000 +v 0.200000 -0.618096 0.317364 +v 0.200000 -0.613584 0.334202 +v 0.200000 -0.536980 0.398480 +v 0.200000 -0.519615 0.400000 +v 0.200000 -0.502250 0.398480 +v 0.200000 -0.443011 0.364279 +v 0.200000 -0.433012 0.350000 +v 0.200000 -0.425646 0.334202 +v 0.200000 -0.421134 0.317364 +v 0.200000 -0.433012 0.250000 +v 0.200000 -0.303109 0.175000 +v 0.200000 -0.425646 0.265798 +v 0.200000 -0.268115 0.224975 +v 0.200000 -0.421134 0.282635 +v 0.200000 -0.224975 0.268115 +v 0.200000 -0.419615 0.300000 +v 0.200000 -0.175000 0.303109 +v 0.200000 -0.119707 0.328892 +v 0.200000 -0.224975 -0.268116 +v 0.200000 -0.268115 -0.224976 +v 0.200000 -0.854807 -0.205000 +v 0.200000 -0.303109 -0.175000 +v 0.200000 -0.328892 -0.119707 +v 0.200000 -0.344682 -0.060777 +v 0.200000 -0.350000 -0.000000 +v 0.200000 -0.344682 0.060777 +v 0.200000 -0.854807 -0.895000 +v 0.200000 -0.175000 -0.303109 +v 0.200000 -0.662145 -2.514272 +v 0.200000 -0.400115 -2.569029 +v 0.200000 -1.395410 -2.193817 +v 0.200000 -1.408525 -2.088429 +v 0.200000 -1.613585 -2.038712 +v 0.200000 -1.408525 -1.903430 +v 0.200000 -1.814655 -1.861996 +v 0.200000 -1.981439 -1.090912 +v 0.200000 -1.971337 -1.093619 +v 0.200000 -1.894454 -0.895000 +v 0.200000 -1.932770 -1.160419 +v 0.200000 -1.935477 -1.170521 +v 0.200000 -1.894454 -1.542500 +v 0.200000 -2.012379 -1.206382 +v 0.200000 -2.157160 -1.451434 +v 0.200000 -2.002277 -1.209089 +v 0.200000 -1.996489 -1.665543 +v 0.200000 -1.991858 -1.210000 +v 0.200000 -2.021858 -1.098039 +v 0.200000 -2.012379 -1.093619 +v 0.200000 -2.145929 -0.895000 +v 0.200000 -2.002277 -1.090912 +v 0.200000 -1.991858 -1.090000 +v 0.200000 -1.931858 -1.150000 +v 0.200000 -2.021858 -1.201962 +v 0.200000 -2.030426 -1.195963 +v 0.200000 -2.037821 -1.188567 +v 0.200000 -2.043820 -1.180000 +v 0.200000 -2.048240 -1.170521 +v 0.200000 -2.050947 -1.160419 +v 0.200000 -2.043820 -1.120000 +v 0.200000 -2.037821 -1.111433 +v 0.200000 -2.030426 -1.104038 +v 0.200000 -1.961858 -1.098039 +v 0.200000 -1.953291 -1.104038 +v 0.200000 -1.945896 -1.111433 +v 0.200000 -1.939897 -1.180000 +v 0.200000 -1.945896 -1.188567 +v 0.200000 -1.953291 -1.195963 +v 0.200000 -1.961858 -1.201962 +v 0.200000 -1.971337 -1.206382 +v 0.200000 -1.981439 -1.209089 +v 0.200000 -2.051858 -1.150000 +v 0.200000 -2.050947 -1.139581 +v 0.200000 -2.048240 -1.129479 +v 0.200000 -1.939897 -1.120000 +v 0.200000 -1.935477 -1.129479 +v 0.200000 -1.932770 -1.139581 +v 0.200000 -2.294965 -1.221940 +v 0.200000 -2.408442 -0.979493 +v 0.200000 -2.480000 0.130000 +v 0.200000 -2.592245 -0.200656 +v 0.200000 -2.480000 -0.205000 +v 0.200000 -2.557874 -0.466130 +v 0.200000 -2.496390 -0.726663 +v 0.200000 -2.530487 0.597188 +v 0.200000 -2.578479 0.333835 +v 0.200000 -2.599138 0.066944 +v 0.200000 -2.229018 1.338461 +v 0.200000 -0.790698 2.476852 +v 0.200000 -1.041180 2.382424 +v 0.200000 -0.854807 2.145929 +v 0.200000 -1.280625 2.262742 +v 0.200000 -1.408525 2.145929 +v 0.200000 -1.506495 2.119073 +v 0.200000 -1.408525 1.570929 +v 0.200000 -1.716395 1.952943 +v 0.200000 -1.908102 1.766111 +v 0.200000 -0.038567 2.345963 +v 0.200000 -0.030000 2.351961 +v 0.200000 -0.080149 2.598764 +v 0.200000 -0.010419 2.240911 +v 0.200000 -0.020521 2.243618 +v 0.200000 -0.080000 2.145929 +v 0.200000 -0.030000 2.248038 +v 0.200000 0.000000 2.360000 +v 0.200000 0.000000 2.600000 +v 0.200000 -0.010419 2.359088 +v 0.200000 -0.020521 2.356381 +v 0.200000 0.030000 2.248038 +v 0.200000 0.020521 2.243618 +v 0.200000 0.112500 2.145929 +v 0.200000 0.010419 2.240911 +v 0.200000 0.000000 2.240000 +v 0.200000 0.010419 2.359088 +v 0.200000 0.020521 2.356381 +v 0.200000 0.267335 2.586220 +v 0.200000 0.030000 2.351961 +v 0.200000 -0.038567 2.254037 +v 0.200000 -0.045962 2.261433 +v 0.200000 -0.051961 2.270000 +v 0.200000 -0.059088 2.310419 +v 0.200000 -0.056381 2.320521 +v 0.200000 0.059089 2.289581 +v 0.200000 0.056382 2.279479 +v 0.200000 0.051962 2.270000 +v 0.200000 -0.051961 2.330000 +v 0.200000 -0.045962 2.338567 +v 0.200000 0.045963 2.261433 +v 0.200000 0.038568 2.254037 +v 0.200000 -0.056381 2.279479 +v 0.200000 -0.059088 2.289581 +v 0.200000 -0.060000 2.300000 +v 0.200000 0.038568 2.345963 +v 0.200000 0.045963 2.338567 +v 0.200000 0.051962 2.330000 +v 0.200000 -0.531835 2.545025 +v 0.200000 -0.112500 2.145929 +v 0.200000 -0.267334 2.586220 +v 0.200000 0.056382 2.320521 +v 0.200000 0.059089 2.310419 +v 0.200000 0.060000 2.300000 +v 0.200000 1.041180 2.382424 +v 0.200000 0.790699 2.476852 +v 0.200000 0.854808 2.145929 +v 0.200000 0.531836 2.545025 +v 0.200000 0.384808 2.145929 +v 0.200000 1.280625 2.262742 +v 0.200000 1.408525 2.145929 +v 0.200000 1.506495 2.119073 +v 0.200000 1.716396 1.952943 +v 0.200000 1.408525 1.570929 +v 0.200000 1.908102 1.766111 +v 0.200000 2.229018 1.338461 +v 0.200000 2.240911 -0.010419 +v 0.200000 2.240000 -0.000000 +v 0.200000 2.145929 0.130000 +v 0.200000 2.300000 -0.060000 +v 0.200000 2.289581 -0.059089 +v 0.200000 2.145929 -0.205000 +v 0.200000 2.261433 -0.045963 +v 0.200000 2.254038 -0.038568 +v 0.200000 2.248039 -0.030000 +v 0.200000 2.243618 -0.020521 +v 0.200000 2.279479 -0.056382 +v 0.200000 2.270000 -0.051962 +v 0.200000 2.338568 -0.045963 +v 0.200000 2.557875 -0.466130 +v 0.200000 2.345963 -0.038568 +v 0.200000 2.592246 -0.200656 +v 0.200000 2.351962 -0.030000 +v 0.200000 2.599138 0.066944 +v 0.200000 2.359089 -0.010419 +v 0.200000 2.356382 -0.020521 +v 0.200000 2.330000 -0.051962 +v 0.200000 2.320521 -0.056382 +v 0.200000 2.310419 -0.059089 +v 0.200000 2.240911 0.010419 +v 0.200000 2.243618 0.020521 +v 0.200000 2.248039 0.030000 +v 0.200000 2.351962 0.030000 +v 0.200000 2.356382 0.020521 +v 0.200000 2.359089 0.010419 +v 0.200000 2.360001 -0.000000 +v 0.200000 2.345963 0.038567 +v 0.200000 2.578479 0.333835 +v 0.200000 2.338568 0.045962 +v 0.200000 2.254038 0.038567 +v 0.200000 2.261433 0.045962 +v 0.200000 2.270000 0.051961 +v 0.200000 2.310419 0.059088 +v 0.200000 2.320521 0.056381 +v 0.200000 2.330000 0.051961 +v 0.200000 2.279479 0.056381 +v 0.200000 2.289581 0.059088 +v 0.200000 2.300000 0.060000 +v 0.200000 2.496390 -0.726663 +v 0.200000 2.408442 -0.979493 +v 0.200000 2.145929 -0.895000 +v 0.200000 2.157160 -1.451434 +v 0.200000 2.294965 -1.221940 +v 0.200000 1.996490 -1.665543 +v 0.200000 1.991859 -1.210000 +v 0.200000 1.981440 -1.209089 +v 0.200000 1.935477 -1.170521 +v 0.200000 1.932770 -1.160419 +v 0.200000 1.935477 -1.129479 +v 0.200000 1.894455 -0.895000 +v 0.200000 1.932770 -1.139581 +v 0.200000 1.931859 -1.150000 +v 0.200000 1.971337 -1.206382 +v 0.200000 1.961859 -1.201962 +v 0.200000 1.953291 -1.195963 +v 0.200000 1.945896 -1.188567 +v 0.200000 1.939897 -1.180000 +v 0.200000 1.939897 -1.120000 +v 0.200000 1.945896 -1.111433 +v 0.200000 1.953291 -1.104038 +v 0.200000 2.002277 -1.090912 +v 0.200000 1.991859 -1.090000 +v 0.200000 1.981440 -1.090912 +v 0.200000 1.961859 -1.098039 +v 0.200000 1.971337 -1.093619 +v 0.200000 2.012380 -1.093619 +v 0.200000 2.021859 -1.098039 +v 0.200000 2.030426 -1.104038 +v 0.200000 2.037821 -1.111433 +v 0.200000 2.043820 -1.120000 +v 0.200000 2.048241 -1.129479 +v 0.200000 2.048241 -1.170521 +v 0.200000 2.043820 -1.180000 +v 0.200000 2.037821 -1.188567 +v 0.200000 2.030426 -1.195963 +v 0.200000 2.021859 -1.201962 +v 0.200000 2.012380 -1.206382 +v 0.200000 2.002277 -1.209089 +v 0.200000 2.050947 -1.139581 +v 0.200000 2.051859 -1.150000 +v 0.200000 2.050947 -1.160419 +v 0.200000 1.395410 -2.193817 +v 0.200000 1.408525 -2.088429 +v 0.200000 1.162444 -2.325666 +v 0.200000 0.854808 -2.088429 +v 0.200000 0.400116 -2.569029 +v 0.200000 0.662145 -2.514272 +v 0.200000 0.917156 -2.432864 +v 0.200000 2.530488 0.597188 +v 0.200000 2.145929 0.637500 +v 0.200000 1.129479 -2.048241 +v 0.200000 1.120000 -2.043820 +v 0.200000 1.120000 -1.939897 +v 0.200000 1.129479 -1.935477 +v 0.200000 0.854808 -1.903430 +v 0.200000 1.188567 -1.945896 +v 0.200000 1.408525 -1.903430 +v 0.200000 1.180000 -1.939897 +v 0.200000 1.170521 -1.935477 +v 0.200000 1.180000 -2.043820 +v 0.200000 1.170521 -2.048241 +v 0.200000 1.139581 -1.932770 +v 0.200000 1.150000 -1.931859 +v 0.200000 1.160419 -1.932770 +v 0.200000 1.160419 -2.050947 +v 0.200000 1.150000 -2.051859 +v 0.200000 1.139581 -2.050947 +v 0.200000 1.098039 -2.021859 +v 0.200000 1.093619 -2.012380 +v 0.200000 1.195963 -1.953291 +v 0.200000 1.201962 -1.961859 +v 0.200000 1.206382 -1.971337 +v 0.200000 1.206382 -2.012380 +v 0.200000 1.201962 -2.021859 +v 0.200000 1.111433 -2.037821 +v 0.200000 1.104038 -2.030426 +v 0.200000 1.090912 -2.002277 +v 0.200000 1.090000 -1.991859 +v 0.200000 1.090912 -1.981440 +v 0.200000 1.093619 -1.971337 +v 0.200000 1.098039 -1.961859 +v 0.200000 1.104038 -1.953291 +v 0.200000 1.111433 -1.945896 +v 0.200000 1.209089 -1.981440 +v 0.200000 1.210000 -1.991859 +v 0.200000 1.209089 -2.002277 +v 0.200000 1.195963 -2.030426 +v 0.200000 1.188567 -2.037821 +v 0.200000 1.894455 -0.205000 +v 0.200000 1.408525 -0.895000 +v 0.200000 1.408525 -0.205000 +v 0.200000 0.854808 -0.895000 +v 0.200000 0.854808 -0.205000 +v 0.200000 1.894455 0.130000 +v 0.200000 1.408525 0.130000 +v 0.200000 0.854808 0.130000 +v 0.200000 0.854808 0.637500 +v 0.200000 1.129479 1.935477 +v 0.200000 1.120000 1.939897 +v 0.200000 0.854808 1.570929 +v 0.200000 1.093619 1.971337 +v 0.200000 1.090912 1.981439 +v 0.200000 1.111433 1.945896 +v 0.200000 1.104038 1.953291 +v 0.200000 1.098039 1.961858 +v 0.200000 1.090000 1.991858 +v 0.200000 1.090912 2.002277 +v 0.200000 1.093619 2.012379 +v 0.200000 1.129479 2.048240 +v 0.200000 1.120000 2.043820 +v 0.200000 1.111433 2.037821 +v 0.200000 1.098039 2.021858 +v 0.200000 1.104038 2.030426 +v 0.200000 1.201962 1.961858 +v 0.200000 1.195963 1.953291 +v 0.200000 1.139581 2.050947 +v 0.200000 1.150000 2.051858 +v 0.200000 1.160419 2.050947 +v 0.200000 1.170521 2.048240 +v 0.200000 1.180000 2.043820 +v 0.200000 1.188567 2.037821 +v 0.200000 1.195963 2.030426 +v 0.200000 1.201962 2.021858 +v 0.200000 1.206382 2.012379 +v 0.200000 1.209089 2.002277 +v 0.200000 1.210000 1.991858 +v 0.200000 1.209089 1.981439 +v 0.200000 1.206382 1.971337 +v 0.200000 1.188567 1.945896 +v 0.200000 1.180000 1.939897 +v 0.200000 1.170521 1.935477 +v 0.200000 1.160419 1.932770 +v 0.200000 1.150000 1.931858 +v 0.200000 1.139581 1.932770 +v 0.200000 0.425646 0.265798 +v 0.200000 0.433013 0.250000 +v 0.200000 0.443011 0.235721 +v 0.200000 0.519615 0.200000 +v 0.200000 0.502251 0.201519 +v 0.200000 0.485414 0.206031 +v 0.200000 0.618096 0.282635 +v 0.200000 0.613585 0.265798 +v 0.200000 0.469615 0.213397 +v 0.200000 0.455337 0.223395 +v 0.200000 0.421135 0.282635 +v 0.200000 0.419616 0.300000 +v 0.200000 0.421135 0.317364 +v 0.200000 0.425646 0.334202 +v 0.200000 0.433013 0.350000 +v 0.200000 0.443011 0.364279 +v 0.200000 0.455337 0.376604 +v 0.200000 0.469615 0.386602 +v 0.200000 0.485414 0.393969 +v 0.200000 0.502251 0.398480 +v 0.200000 0.519615 0.400000 +v 0.200000 0.536980 0.398480 +v 0.200000 0.553818 0.393969 +v 0.200000 0.569616 0.386602 +v 0.200000 0.583894 0.376604 +v 0.200000 0.596220 0.364279 +v 0.200000 0.606218 0.350000 +v 0.200000 0.606218 0.250000 +v 0.200000 0.596220 0.235721 +v 0.200000 0.583894 0.223395 +v 0.200000 0.569616 0.213397 +v 0.200000 0.553818 0.206031 +v 0.200000 0.536980 0.201519 +v 0.200000 0.613585 0.334202 +v 0.200000 0.618096 0.317364 +v 0.200000 0.619615 0.300000 +v 0.200000 1.613585 -2.038712 +v 0.200000 0.854808 -1.542500 +v 0.200000 0.384808 -1.542500 +v 0.200000 0.384808 1.570929 +v 0.200000 0.112500 1.570929 +v 0.200000 -0.080000 1.570929 +v 0.200000 -0.112500 1.570929 +v 0.200000 -0.854807 1.570929 +v 0.200000 -1.139581 -2.050947 +v 0.200000 -1.150000 -2.051859 +v 0.200000 -1.170521 -2.048241 +v 0.200000 -1.180000 -2.043820 +v 0.200000 -1.160419 -2.050947 +v 0.200000 -1.188567 -2.037821 +v 0.200000 -1.195963 -2.030426 +v 0.200000 -1.201961 -2.021859 +v 0.200000 -1.195963 -1.953291 +v 0.200000 -1.188567 -1.945896 +v 0.200000 -1.180000 -1.939897 +v 0.200000 -1.170521 -1.935477 +v 0.200000 -1.139581 -1.932770 +v 0.200000 -1.150000 -1.931859 +v 0.200000 -1.160419 -1.932770 +v 0.200000 -1.129479 -1.935477 +v 0.200000 -1.120000 -1.939897 +v 0.200000 -1.111432 -1.945896 +v 0.200000 -1.209088 -1.981440 +v 0.200000 -1.206381 -1.971337 +v 0.200000 -1.201961 -1.961859 +v 0.200000 -1.111432 -2.037821 +v 0.200000 -1.120000 -2.043820 +v 0.200000 -1.129479 -2.048241 +v 0.200000 -1.206381 -2.012380 +v 0.200000 -1.209088 -2.002277 +v 0.200000 -1.210000 -1.991859 +v 0.200000 -1.104037 -1.953291 +v 0.200000 -1.098038 -1.961859 +v 0.200000 -1.093618 -1.971337 +v 0.200000 -1.093618 -2.012380 +v 0.200000 -1.098038 -2.021859 +v 0.200000 -1.104037 -2.030426 +v 0.200000 -1.090911 -1.981440 +v 0.200000 -1.090000 -1.991859 +v 0.200000 -1.090911 -2.002277 +v 0.200000 -0.112500 -1.542500 +v 0.200000 -0.854807 -1.542500 +v 0.200000 -1.408525 -1.542500 +v 0.200000 0.854808 0.982500 +v 0.200000 0.384808 0.982500 +v 0.200000 0.112500 0.982500 +v 0.200000 -0.080000 0.982500 +v 0.200000 -0.112500 0.982500 +v 0.200000 -0.854807 0.982500 +v 0.200000 0.854808 1.167500 +v 0.200000 0.384808 1.167500 +v 0.200000 0.112500 1.167500 +v 0.200000 -0.080000 1.167500 +v 0.200000 -0.112500 1.167500 +v 0.200000 -0.854807 1.167500 +v 0.200000 -1.160419 1.932770 +v 0.200000 -1.170521 1.935477 +v 0.200000 -1.180000 1.939897 +v 0.200000 -1.188567 1.945896 +v 0.200000 -1.195963 1.953291 +v 0.200000 -1.188567 2.037821 +v 0.200000 -1.180000 2.043820 +v 0.200000 -1.170521 2.048240 +v 0.200000 -1.209088 1.981439 +v 0.200000 -1.206381 1.971337 +v 0.200000 -1.201961 1.961858 +v 0.200000 -1.210000 1.991858 +v 0.200000 -1.209088 2.002277 +v 0.200000 -1.206381 2.012379 +v 0.200000 -1.098038 1.961858 +v 0.200000 -1.104037 1.953291 +v 0.200000 -1.111432 1.945896 +v 0.200000 -1.120000 1.939897 +v 0.200000 -1.201961 2.021858 +v 0.200000 -1.195963 2.030426 +v 0.200000 -1.129479 2.048240 +v 0.200000 -1.120000 2.043820 +v 0.200000 -1.111432 2.037821 +v 0.200000 -1.104037 2.030426 +v 0.200000 -1.129479 1.935477 +v 0.200000 -1.139581 1.932770 +v 0.200000 -1.150000 1.931858 +v 0.200000 -1.160419 2.050947 +v 0.200000 -1.150000 2.051858 +v 0.200000 -1.139581 2.050947 +v 0.200000 -1.098038 2.021858 +v 0.200000 -1.093618 2.012379 +v 0.200000 -1.090911 2.002277 +v 0.200000 -1.090000 1.991858 +v 0.200000 -1.090911 1.981439 +v 0.200000 -1.093618 1.971337 +v 0.200000 -1.408525 -0.895000 +v 0.200000 -1.408525 -0.205000 +v 0.200000 -1.894454 -0.205000 +v 0.200000 -1.408525 0.130000 +v 0.200000 -1.894454 0.130000 +v 0.200000 -2.145929 0.130000 +v 0.200000 -2.360000 -0.000000 +v 0.200000 -2.359088 -0.010419 +v 0.200000 -2.356381 -0.020521 +v 0.200000 -2.351961 -0.030000 +v 0.200000 -2.310419 -0.059089 +v 0.200000 -2.320521 -0.056382 +v 0.200000 -2.330000 -0.051962 +v 0.200000 -2.248038 0.030000 +v 0.200000 -2.243618 0.020521 +v 0.200000 -2.254037 -0.038568 +v 0.200000 -2.248038 -0.030000 +v 0.200000 -2.243618 -0.020521 +v 0.200000 -2.279479 -0.056382 +v 0.200000 -2.338567 -0.045963 +v 0.200000 -2.345963 -0.038568 +v 0.200000 -2.359088 0.010419 +v 0.200000 -2.356381 0.020521 +v 0.200000 -2.351961 0.030000 +v 0.200000 -2.240911 0.010419 +v 0.200000 -2.240000 -0.000000 +v 0.200000 -2.240911 -0.010419 +v 0.200000 -2.345963 0.038567 +v 0.200000 -2.338567 0.045962 +v 0.200000 -2.330000 0.051961 +v 0.200000 -2.289581 0.059088 +v 0.200000 -2.279479 0.056381 +v 0.200000 -2.270000 0.051961 +v 0.200000 -2.261433 -0.045963 +v 0.200000 -2.270000 -0.051962 +v 0.200000 -2.261433 0.045962 +v 0.200000 -2.254037 0.038567 +v 0.200000 -2.320521 0.056381 +v 0.200000 -2.310419 0.059088 +v 0.200000 -2.300000 0.060000 +v 0.000000 0.854808 0.130000 +v 0.000000 0.854808 0.637500 +v 0.000000 1.408525 0.637500 +v 0.000000 0.384808 -0.205000 +v 0.000000 0.384808 0.130000 +v -0.000000 -2.455672 0.854210 +v -0.000000 -2.480000 0.637500 +v -0.000000 -2.530487 0.597188 +v -0.000000 -2.354826 1.102177 +v -0.000000 -2.145929 1.167500 +v -0.000000 -2.145929 0.982500 +v 0.000000 -1.041180 2.382424 +v 0.000000 -0.790698 2.476852 +v 0.000000 -0.854807 2.145929 +v 0.000000 0.010419 2.359088 +v 0.000000 0.000000 2.360000 +v 0.000000 0.000000 2.600000 +v 0.000000 2.079582 1.560557 +v 0.000000 1.894455 1.570929 +v 0.000000 1.908102 1.766111 +v 0.000000 2.354826 1.102177 +v 0.000000 2.145929 0.982500 +v 0.000000 2.145929 1.167500 +v 0.000000 2.455672 0.854210 +v 0.000000 2.530488 0.597188 +v 0.000000 2.145929 0.637500 +v 0.000000 2.496390 -0.726663 +v 0.000000 2.408442 -0.979493 +v 0.000000 2.145929 -0.895000 +v -0.000000 -0.303109 -0.175000 +v -0.000000 -0.268115 -0.224976 +v -0.000000 -0.854807 -0.205000 +v 0.000000 1.849513 0.957247 +v 0.000000 1.855152 0.978294 +v 0.000000 1.894455 0.982500 +v -0.000000 0.034202 -0.693969 +v -0.000000 0.050000 -0.686603 +v -0.000000 0.112500 -0.895000 +v -0.000000 0.064279 -0.676605 +v -0.000000 0.076605 -0.664279 +v -0.000000 -0.076604 -0.535721 +v -0.000000 -0.119707 -0.328893 +v -0.000000 -0.064279 -0.523396 +v -0.000000 -0.050000 -0.513397 +v -0.000000 -0.034202 -0.693969 +v -0.000000 -0.080000 -0.895000 +v -0.000000 -0.050000 -0.686603 +v -0.000000 -0.064279 -0.676605 +v -0.000000 -0.017365 -0.698481 +v -0.000000 0.000000 -0.700000 +v -0.000000 0.017365 -0.698481 +v -0.000000 0.119707 -0.328893 +v -0.000000 0.050000 -0.513397 +v -0.000000 0.034202 -0.506031 +v -0.000000 0.060777 -0.344683 +v -0.000000 0.017365 -0.501519 +v -0.000000 0.000000 -0.350000 +v -0.000000 0.000000 -0.500000 +v -0.000000 -0.060777 -0.344683 +v -0.000000 -0.017365 -0.501519 +v -0.000000 -0.034202 -0.506031 +v -0.000000 0.086603 -0.650000 +v -0.000000 0.093970 -0.634202 +v -0.000000 0.098481 -0.617365 +v -0.000000 0.100000 -0.600000 +v -0.000000 0.098481 -0.582635 +v -0.000000 0.093970 -0.565798 +v -0.000000 0.086603 -0.550000 +v -0.000000 0.076605 -0.535721 +v -0.000000 0.064279 -0.523396 +v -0.000000 -0.112500 -0.895000 +v -0.000000 -0.086602 -0.650000 +v -0.000000 -0.076604 -0.664279 +v -0.000000 -0.086602 -0.550000 +v -0.000000 -0.093969 -0.565798 +v -0.000000 -0.098481 -0.582635 +v -0.000000 -0.100000 -0.600000 +v -0.000000 -0.098481 -0.617365 +v -0.000000 -0.093969 -0.634202 +v 0.000000 1.932770 1.160419 +v 0.000000 1.931859 1.150000 +v 0.000000 1.894455 1.167500 +v 0.000000 1.932770 1.139581 +v 0.000000 1.935477 1.129479 +v 0.000000 1.939897 1.120000 +v 0.000000 1.945896 1.111432 +v 0.000000 1.953291 1.104037 +v 0.000000 1.961859 1.098038 +v 0.000000 1.971337 1.093618 +v 0.000000 1.981440 1.090911 +v 0.000000 1.991859 1.090000 +v 0.000000 2.002277 1.090911 +v 0.000000 2.012380 1.093618 +v 0.000000 2.021859 1.098038 +v 0.000000 2.030426 1.104037 +v 0.000000 2.037821 1.111432 +v 0.000000 2.043820 1.120000 +v 0.000000 2.048241 1.129479 +v 0.000000 2.050947 1.139581 +v 0.000000 2.051859 1.150000 +v 0.000000 2.043820 1.180000 +v 0.000000 2.037821 1.188567 +v 0.000000 2.050947 1.160419 +v 0.000000 2.048241 1.170521 +v 0.000000 2.030426 1.195963 +v 0.000000 2.021859 1.201961 +v 0.000000 2.012380 1.206381 +v 0.000000 1.945896 1.188567 +v 0.000000 1.939897 1.180000 +v 0.000000 1.935477 1.170521 +v 0.000000 2.002277 1.209088 +v 0.000000 1.991859 1.210000 +v 0.000000 1.981440 1.209088 +v 0.000000 1.971337 1.206381 +v 0.000000 1.961859 1.201961 +v 0.000000 1.953291 1.195963 +v -0.000000 -1.894454 0.982500 +v -0.000000 -1.953291 1.104037 +v -0.000000 -1.945896 1.111432 +v -0.000000 -1.939897 1.120000 +v -0.000000 -1.935477 1.129479 +v -0.000000 -1.894454 1.167500 +v -0.000000 -1.932770 1.139581 +v -0.000000 -1.931858 1.150000 +v -0.000000 -2.050947 1.160419 +v -0.000000 -2.051858 1.150000 +v -0.000000 -2.050947 1.139581 +v -0.000000 -2.048240 1.129479 +v -0.000000 -2.043820 1.120000 +v -0.000000 -2.037821 1.111432 +v -0.000000 -2.030426 1.104037 +v -0.000000 -2.021858 1.098038 +v -0.000000 -2.012379 1.093618 +v -0.000000 -2.002277 1.090911 +v -0.000000 -1.991858 1.090000 +v -0.000000 -1.981439 1.090911 +v -0.000000 -1.971337 1.093618 +v -0.000000 -1.961858 1.098038 +v -0.000000 -1.932770 1.160419 +v -0.000000 -1.935477 1.170521 +v -0.000000 -1.939897 1.180000 +v -0.000000 -1.945896 1.188567 +v -0.000000 -1.953291 1.195963 +v -0.000000 -1.894454 1.570929 +v -0.000000 -2.037821 1.188567 +v -0.000000 -2.043820 1.180000 +v -0.000000 -2.048240 1.170521 +v -0.000000 -1.991858 1.210000 +v -0.000000 -2.002277 1.209088 +v -0.000000 -2.079582 1.560557 +v -0.000000 -1.961858 1.201961 +v -0.000000 -1.971337 1.206381 +v -0.000000 -1.981439 1.209088 +v -0.000000 -2.012379 1.206381 +v -0.000000 -2.021858 1.201961 +v -0.000000 -2.030426 1.195963 +v 0.000000 1.840304 0.937500 +v 0.000000 1.408525 0.982500 +v 0.000000 1.608950 0.978294 +v 0.000000 1.614590 0.957247 +v 0.000000 1.623798 0.937500 +v 0.000000 1.636295 0.919651 +v 0.000000 1.689299 0.882538 +v 0.000000 1.710345 0.876899 +v 0.000000 1.827806 0.919651 +v 0.000000 1.894455 0.637500 +v 0.000000 1.732051 0.875000 +v 0.000000 1.753757 0.876899 +v 0.000000 1.774804 0.882538 +v 0.000000 1.651703 0.904244 +v 0.000000 1.669551 0.891747 +v 0.000000 1.794551 0.891747 +v 0.000000 1.812399 0.904244 +v 0.000000 1.623798 1.062500 +v 0.000000 1.614590 1.042752 +v 0.000000 1.408525 1.167500 +v 0.000000 1.840304 1.062500 +v 0.000000 1.827806 1.080348 +v 0.000000 1.812399 1.095755 +v 0.000000 1.794551 1.108253 +v 0.000000 1.774804 1.117461 +v 0.000000 1.608950 1.021706 +v 0.000000 1.607051 1.000000 +v 0.000000 1.857051 1.000000 +v 0.000000 1.855152 1.021706 +v 0.000000 1.849513 1.042752 +v 0.000000 1.753757 1.123101 +v 0.000000 1.732051 1.125000 +v 0.000000 1.710345 1.123101 +v 0.000000 1.689299 1.117461 +v 0.000000 1.669551 1.108253 +v 0.000000 1.651703 1.095755 +v 0.000000 1.636295 1.080348 +v -0.000000 -1.857051 1.000000 +v -0.000000 -1.855152 0.978294 +v -0.000000 -1.849512 0.957247 +v -0.000000 -1.840304 0.937500 +v -0.000000 -1.827806 0.919651 +v -0.000000 -1.894454 0.637500 +v -0.000000 -1.408525 0.637500 +v -0.000000 -1.636295 0.919651 +v -0.000000 -1.623797 0.937500 +v -0.000000 -1.812399 0.904244 +v -0.000000 -1.794551 0.891747 +v -0.000000 -1.774803 0.882538 +v -0.000000 -1.753757 0.876899 +v -0.000000 -1.732051 0.875000 +v -0.000000 -1.710345 0.876899 +v -0.000000 -1.689298 0.882538 +v -0.000000 -1.669551 0.891747 +v -0.000000 -1.651702 0.904244 +v -0.000000 -1.614589 0.957247 +v -0.000000 -1.608950 0.978294 +v -0.000000 -1.408525 0.982500 +v -0.000000 -1.607051 1.000000 +v -0.000000 -1.608950 1.021706 +v -0.000000 -1.840304 1.062500 +v -0.000000 -1.849512 1.042752 +v -0.000000 -1.651702 1.095755 +v -0.000000 -1.669551 1.108253 +v -0.000000 -1.408525 1.167500 +v -0.000000 -1.689298 1.117461 +v -0.000000 -1.855152 1.021706 +v -0.000000 -1.614589 1.042752 +v -0.000000 -1.623797 1.062500 +v -0.000000 -1.636295 1.080348 +v -0.000000 -1.710345 1.123101 +v -0.000000 -1.732051 1.125000 +v -0.000000 -1.753757 1.123101 +v -0.000000 -1.774803 1.117461 +v -0.000000 -1.794551 1.108253 +v -0.000000 -1.812399 1.095755 +v -0.000000 -1.827806 1.080348 +v -0.000000 0.080349 -2.095756 +v -0.000000 0.095756 -2.080349 +v -0.000000 0.112500 -2.088429 +v -0.000000 -0.045962 -2.338568 +v -0.000000 -0.038567 -2.345963 +v -0.000000 -0.133845 -2.596553 +v -0.000000 0.030000 -2.351962 +v -0.000000 0.038568 -2.345963 +v -0.000000 0.133845 -2.596553 +v -0.000000 -0.080348 -2.095756 +v -0.000000 -0.020521 -2.243618 +v -0.000000 -0.030000 -2.248039 +v -0.000000 0.042753 -2.117462 +v -0.000000 0.062500 -2.108253 +v -0.000000 0.020521 -2.243618 +v -0.000000 -0.062500 -2.108253 +v -0.000000 -0.042752 -2.117462 +v -0.000000 -0.021706 -2.123101 +v -0.000000 0.021706 -2.123101 +v -0.000000 0.010419 -2.240911 +v -0.000000 0.000000 -2.125000 +v -0.000000 0.000000 -2.240000 +v -0.000000 -0.010419 -2.240911 +v -0.000000 -0.038567 -2.254038 +v -0.000000 -0.045962 -2.261433 +v -0.000000 -0.051961 -2.270000 +v -0.000000 -0.010419 -2.359089 +v -0.000000 0.000000 -2.600000 +v -0.000000 -0.020521 -2.356382 +v -0.000000 -0.030000 -2.351962 +v -0.000000 0.000000 -2.360001 +v -0.000000 0.010419 -2.359089 +v -0.000000 0.020521 -2.356382 +v -0.000000 0.045963 -2.338568 +v -0.000000 0.051962 -2.330000 +v -0.000000 0.056382 -2.320521 +v -0.000000 0.030000 -2.248039 +v -0.000000 0.038568 -2.254038 +v -0.000000 -0.056381 -2.279479 +v -0.000000 -0.059088 -2.289581 +v -0.000000 -0.060000 -2.300000 +v -0.000000 -0.059088 -2.310419 +v -0.000000 -0.056381 -2.320521 +v -0.000000 -0.051961 -2.330000 +v -0.000000 0.056382 -2.279479 +v -0.000000 0.051962 -2.270000 +v -0.000000 0.045963 -2.261433 +v -0.000000 0.059089 -2.310419 +v -0.000000 0.060000 -2.300000 +v -0.000000 0.059089 -2.289581 +v -0.000000 -0.108253 -2.062500 +v -0.000000 -0.095755 -2.080349 +v -0.000000 -0.112500 -2.088429 +v -0.000000 -0.117461 -2.042753 +v -0.000000 -0.854807 -2.088429 +v -0.000000 -0.123101 -2.021706 +v -0.000000 -0.854807 -1.903430 +v -0.000000 -0.123101 -1.978294 +v -0.000000 -0.125000 -2.000000 +v -0.000000 -0.112500 -1.903430 +v -0.000000 -0.080000 -1.903430 +v -0.000000 -0.080348 -1.904245 +v -0.000000 -0.095755 -1.919652 +v -0.000000 -0.108253 -1.937500 +v -0.000000 -0.117461 -1.957248 +v -0.000000 0.080349 -1.904245 +v -0.000000 0.062500 -1.891747 +v -0.000000 0.112500 -1.542500 +v -0.000000 0.042753 -1.882539 +v -0.000000 0.021706 -1.876899 +v -0.000000 -0.080000 -1.542500 +v -0.000000 0.000000 -1.875000 +v -0.000000 -0.021706 -1.876899 +v -0.000000 -0.042752 -1.882539 +v -0.000000 -0.062500 -1.891747 +v -0.000000 0.112500 -1.903430 +v -0.000000 0.108253 -1.937500 +v -0.000000 0.095756 -1.919652 +v -0.000000 0.123101 -1.978294 +v -0.000000 0.117462 -1.957248 +v -0.000000 0.384808 -1.903430 +v -0.000000 0.108253 -2.062500 +v -0.000000 0.117462 -2.042753 +v -0.000000 0.384808 -2.088429 +v -0.000000 0.123101 -2.021706 +v -0.000000 0.125000 -2.000000 +v -0.000000 -0.175000 -0.303109 +v -0.000000 -0.854807 -0.895000 +v -0.000000 -0.224975 -0.268116 +v -0.000000 -0.350000 -0.000000 +v -0.000000 -0.854807 0.130000 +v -0.000000 -0.344682 0.060777 +v -0.000000 -0.328892 0.119707 +v -0.000000 -0.344682 -0.060777 +v -0.000000 -0.328892 -0.119707 +v 0.000000 -0.112500 0.637500 +v -0.000000 -0.455336 0.376604 +v -0.000000 -0.469615 0.386602 +v -0.000000 -0.618096 0.317364 +v -0.000000 -0.619615 0.300000 +v -0.000000 -0.485413 0.393969 +v -0.000000 -0.502250 0.398480 +v -0.000000 -0.854807 0.637500 +v -0.000000 -0.519615 0.400000 +v -0.000000 -0.536980 0.398480 +v -0.000000 -0.583894 0.376604 +v -0.000000 -0.596220 0.364279 +v -0.000000 -0.618096 0.282635 +v -0.000000 -0.613584 0.265798 +v -0.000000 -0.606218 0.250000 +v -0.000000 -0.596220 0.235721 +v -0.000000 -0.583894 0.223395 +v -0.000000 -0.569615 0.213397 +v -0.000000 -0.425646 0.334202 +v -0.000000 -0.433012 0.350000 +v -0.000000 -0.443011 0.364279 +v -0.000000 -0.553817 0.393969 +v -0.000000 -0.569615 0.386602 +v -0.000000 -0.606218 0.350000 +v -0.000000 -0.613584 0.334202 +v -0.000000 -0.519615 0.200000 +v -0.000000 -0.536980 0.201519 +v -0.000000 -0.553817 0.206031 +v -0.000000 -0.502250 0.201519 +v -0.000000 -0.485413 0.206031 +v -0.000000 -0.469615 0.213397 +v -0.000000 -0.455336 0.223395 +v -0.000000 -0.443011 0.235721 +v -0.000000 -0.303109 0.175000 +v -0.000000 -0.433012 0.250000 +v -0.000000 -0.268115 0.224975 +v -0.000000 -0.425646 0.265798 +v 0.000000 -0.224975 0.268115 +v -0.000000 -0.421134 0.282635 +v -0.000000 -0.419615 0.300000 +v 0.000000 -0.112648 0.331376 +v -0.000000 -0.421134 0.317364 +v 0.000000 -0.119707 0.328892 +v 0.000000 -0.175000 0.303109 +v 0.000000 -0.080000 0.637500 +v 0.000000 -0.060777 0.344682 +v 0.000000 0.112500 0.637500 +v 0.000000 0.060777 0.344682 +v 0.000000 0.000000 0.350000 +v 0.000000 0.328893 0.119707 +v 0.000000 0.384808 0.637500 +v 0.000000 0.303109 0.175000 +v 0.000000 0.268116 0.224975 +v 0.000000 0.224976 0.268115 +v 0.000000 0.175000 0.303109 +v 0.000000 0.119707 0.328892 +v -0.000000 0.224976 -0.268116 +v 0.000000 0.268116 -0.224976 +v 0.000000 0.303109 -0.175000 +v 0.000000 0.328893 -0.119707 +v 0.000000 0.344683 -0.060777 +v 0.000000 0.350000 -0.000000 +v 0.000000 0.344683 0.060777 +v -0.000000 0.384808 -0.895000 +v -0.000000 0.175000 -0.303109 +v -0.000000 0.400116 -2.569029 +v -0.000000 0.854808 -2.088429 +v -0.000000 0.917156 -2.432864 +v -0.000000 0.662145 -2.514272 +v 0.000000 1.971337 -1.093619 +v 0.000000 1.894455 -0.895000 +v 0.000000 1.981440 -1.090912 +v 0.000000 1.991859 -1.090000 +v 0.000000 1.932770 -1.160419 +v 0.000000 1.935477 -1.170521 +v 0.000000 1.894455 -1.542500 +v 0.000000 2.030426 -1.195963 +v 0.000000 2.037821 -1.188567 +v 0.000000 2.157160 -1.451434 +v 0.000000 1.931859 -1.150000 +v -0.000000 1.814655 -1.861996 +v 0.000000 1.996490 -1.665543 +v 0.000000 1.981440 -1.209089 +v 0.000000 2.021859 -1.201962 +v 0.000000 1.961859 -1.098039 +v 0.000000 1.953291 -1.104038 +v 0.000000 1.945896 -1.111433 +v 0.000000 1.991859 -1.210000 +v 0.000000 2.002277 -1.209089 +v 0.000000 2.012380 -1.206382 +v 0.000000 2.043820 -1.180000 +v 0.000000 2.048241 -1.170521 +v 0.000000 2.050947 -1.160419 +v 0.000000 2.048241 -1.129479 +v 0.000000 2.050947 -1.139581 +v 0.000000 2.051859 -1.150000 +v 0.000000 2.043820 -1.120000 +v 0.000000 2.037821 -1.111433 +v 0.000000 2.030426 -1.104038 +v 0.000000 2.021859 -1.098039 +v 0.000000 2.012380 -1.093619 +v 0.000000 2.002277 -1.090912 +v 0.000000 1.939897 -1.120000 +v 0.000000 1.935477 -1.129479 +v 0.000000 1.932770 -1.139581 +v 0.000000 1.939897 -1.180000 +v 0.000000 1.945896 -1.188567 +v 0.000000 1.953291 -1.195963 +v 0.000000 1.961859 -1.201962 +v 0.000000 1.971337 -1.206382 +v 0.000000 2.294965 -1.221940 +v 0.000000 2.145929 0.130000 +v 0.000000 2.261433 0.045962 +v 0.000000 2.254038 0.038567 +v 0.000000 2.248039 0.030000 +v 0.000000 2.243618 0.020521 +v 0.000000 2.240911 0.010419 +v 0.000000 2.240000 -0.000000 +v 0.000000 2.240911 -0.010419 +v 0.000000 2.145929 -0.205000 +v 0.000000 2.243618 -0.020521 +v 0.000000 2.248039 -0.030000 +v 0.000000 2.254038 -0.038568 +v 0.000000 2.261433 -0.045963 +v 0.000000 2.270000 -0.051962 +v 0.000000 2.557875 -0.466130 +v 0.000000 2.338568 -0.045963 +v 0.000000 2.592246 -0.200656 +v 0.000000 2.345963 -0.038568 +v 0.000000 2.351962 -0.030000 +v 0.000000 2.356382 -0.020521 +v 0.000000 2.599138 0.066944 +v 0.000000 2.359089 -0.010419 +v 0.000000 2.360001 -0.000000 +v 0.000000 2.359089 0.010419 +v 0.000000 2.578479 0.333835 +v 0.000000 2.338568 0.045962 +v 0.000000 2.330000 0.051961 +v 0.000000 2.300000 0.060000 +v 0.000000 2.289581 0.059088 +v 0.000000 2.279479 0.056381 +v 0.000000 2.270000 0.051961 +v 0.000000 2.356382 0.020521 +v 0.000000 2.351962 0.030000 +v 0.000000 2.345963 0.038567 +v 0.000000 2.320521 0.056381 +v 0.000000 2.310419 0.059088 +v 0.000000 2.310419 -0.059089 +v 0.000000 2.320521 -0.056382 +v 0.000000 2.330000 -0.051962 +v 0.000000 2.279479 -0.056382 +v 0.000000 2.289581 -0.059089 +v 0.000000 2.300000 -0.060000 +v 0.000000 2.229018 1.338461 +v 0.000000 1.716396 1.952943 +v 0.000000 1.408525 1.570929 +v 0.000000 1.506495 2.119073 +v 0.000000 1.408525 2.145929 +v 0.000000 1.280625 2.262742 +v 0.000000 0.854808 2.145929 +v 0.000000 1.041180 2.382424 +v 0.000000 0.112500 2.145929 +v 0.000000 0.267335 2.586220 +v 0.000000 0.384808 2.145929 +v 0.000000 0.531836 2.545025 +v 0.000000 0.790699 2.476852 +v 0.000000 -0.020521 2.356381 +v 0.000000 -0.030000 2.351961 +v 0.000000 -0.080149 2.598764 +v 0.000000 -0.030000 2.248038 +v 0.000000 -0.020521 2.243618 +v 0.000000 -0.080000 2.145929 +v 0.000000 -0.010419 2.240911 +v 0.000000 0.000000 2.240000 +v 0.000000 -0.010419 2.359088 +v 0.000000 0.010419 2.240911 +v 0.000000 0.020521 2.243618 +v 0.000000 0.030000 2.248038 +v 0.000000 0.030000 2.351961 +v 0.000000 0.020521 2.356381 +v 0.000000 -0.038567 2.345963 +v 0.000000 -0.045962 2.338567 +v 0.000000 -0.051961 2.330000 +v 0.000000 -0.051961 2.270000 +v 0.000000 -0.045962 2.261433 +v 0.000000 -0.038567 2.254037 +v 0.000000 0.038568 2.254037 +v 0.000000 0.045963 2.261433 +v 0.000000 0.051962 2.270000 +v 0.000000 0.059089 2.310419 +v 0.000000 0.056382 2.320521 +v 0.000000 0.051962 2.330000 +v 0.000000 0.045963 2.338567 +v 0.000000 0.038568 2.345963 +v 0.000000 -0.056381 2.320521 +v 0.000000 -0.059088 2.310419 +v 0.000000 -0.060000 2.300000 +v 0.000000 -0.059088 2.289581 +v 0.000000 -0.056381 2.279479 +v 0.000000 0.056382 2.279479 +v 0.000000 0.059089 2.289581 +v 0.000000 0.060000 2.300000 +v 0.000000 -0.112500 2.145929 +v 0.000000 -0.267334 2.586220 +v 0.000000 -0.531835 2.545025 +v 0.000000 -1.280625 2.262742 +v 0.000000 -1.408525 2.145929 +v 0.000000 -1.506495 2.119073 +v 0.000000 -1.716395 1.952943 +v 0.000000 -1.408525 1.570929 +v -0.000000 -1.908102 1.766111 +v -0.000000 -2.229018 1.338461 +v -0.000000 -2.145929 0.637500 +v -0.000000 -2.480000 0.130000 +v -0.000000 -2.599138 0.066944 +v -0.000000 -2.578479 0.333835 +v -0.000000 -2.157160 -1.451434 +v -0.000000 -2.294965 -1.221940 +v -0.000000 -2.145929 -0.895000 +v -0.000000 -2.408442 -0.979493 +v -0.000000 -2.496389 -0.726663 +v -0.000000 -2.002277 -1.090912 +v -0.000000 -1.991858 -1.090000 +v -0.000000 -1.894454 -0.895000 +v -0.000000 -1.981439 -1.090912 +v -0.000000 -2.012379 -1.093619 +v -0.000000 -2.021858 -1.098039 +v -0.000000 -2.030426 -1.104038 +v -0.000000 -1.945896 -1.111433 +v -0.000000 -1.953291 -1.104038 +v -0.000000 -2.037821 -1.111433 +v -0.000000 -2.043820 -1.120000 +v -0.000000 -2.048240 -1.129479 +v -0.000000 -2.048240 -1.170521 +v -0.000000 -2.043820 -1.180000 +v -0.000000 -2.037821 -1.188567 +v -0.000000 -2.030426 -1.195963 +v -0.000000 -2.021858 -1.201962 +v -0.000000 -2.012379 -1.206382 +v -0.000000 -1.996489 -1.665543 +v -0.000000 -2.002277 -1.209089 +v -0.000000 -1.991858 -1.210000 +v -0.000000 -1.981439 -1.209089 +v -0.000000 -1.894454 -1.542500 +v -0.000000 -1.971337 -1.206382 +v -0.000000 -1.961858 -1.201962 +v -0.000000 -1.953291 -1.195963 +v -0.000000 -1.945896 -1.188567 +v -0.000000 -1.939897 -1.180000 +v -0.000000 -1.932770 -1.139581 +v -0.000000 -1.935477 -1.129479 +v -0.000000 -1.939897 -1.120000 +v -0.000000 -1.961858 -1.098039 +v -0.000000 -1.971337 -1.093619 +v -0.000000 -2.050947 -1.139581 +v -0.000000 -2.051858 -1.150000 +v -0.000000 -2.050947 -1.160419 +v -0.000000 -1.935477 -1.170521 +v -0.000000 -1.932770 -1.160419 +v -0.000000 -1.931858 -1.150000 +v -0.000000 -1.408525 -1.903430 +v -0.000000 -1.408525 -2.088429 +v -0.000000 -1.814655 -1.861996 +v -0.000000 -1.613585 -2.038712 +v -0.000000 -1.162444 -2.325666 +v -0.000000 -1.395410 -2.193817 +v -0.000000 -0.400115 -2.569029 +v -0.000000 -0.662145 -2.514272 +v -0.000000 -0.917155 -2.432864 +v -0.000000 -2.351961 0.030000 +v -0.000000 -2.356381 0.020521 +v -0.000000 -2.359088 0.010419 +v -0.000000 -2.360000 -0.000000 +v -0.000000 -2.480000 -0.205000 +v -0.000000 -2.592245 -0.200656 +v -0.000000 -2.145929 0.130000 +v -0.000000 -2.240000 -0.000000 +v -0.000000 -2.240911 0.010419 +v -0.000000 -2.320521 0.056381 +v -0.000000 -2.330000 0.051961 +v -0.000000 -2.359088 -0.010419 +v -0.000000 -2.356381 -0.020521 +v -0.000000 -2.351961 -0.030000 +v -0.000000 -2.243618 0.020521 +v -0.000000 -2.248038 0.030000 +v -0.000000 -2.254037 0.038567 +v -0.000000 -2.338567 0.045962 +v -0.000000 -2.345963 0.038567 +v -0.000000 -2.279479 0.056381 +v -0.000000 -2.289581 0.059088 +v -0.000000 -2.300000 0.060000 +v -0.000000 -2.310419 0.059088 +v -0.000000 -2.248038 -0.030000 +v -0.000000 -2.243618 -0.020521 +v -0.000000 -2.145929 -0.205000 +v -0.000000 -2.240911 -0.010419 +v -0.000000 -2.261433 0.045962 +v -0.000000 -2.270000 0.051961 +v -0.000000 -2.345963 -0.038568 +v -0.000000 -2.338567 -0.045963 +v -0.000000 -2.330000 -0.051962 +v -0.000000 -2.289581 -0.059089 +v -0.000000 -2.279479 -0.056382 +v -0.000000 -2.270000 -0.051962 +v -0.000000 -2.320521 -0.056382 +v -0.000000 -2.310419 -0.059089 +v -0.000000 -2.300000 -0.060000 +v -0.000000 -2.261433 -0.045963 +v -0.000000 -2.254037 -0.038568 +v -0.000000 -1.160419 -1.932770 +v -0.000000 -1.150000 -1.931859 +v -0.000000 -1.139581 -1.932770 +v -0.000000 -1.129479 -2.048241 +v -0.000000 -1.120000 -2.043820 +v -0.000000 -1.104037 -1.953291 +v -0.000000 -1.111432 -1.945896 +v -0.000000 -1.170521 -1.935477 +v -0.000000 -1.180000 -1.939897 +v -0.000000 -1.188567 -1.945896 +v -0.000000 -1.111432 -2.037821 +v -0.000000 -1.104037 -2.030426 +v -0.000000 -1.098038 -2.021859 +v -0.000000 -1.120000 -1.939897 +v -0.000000 -1.129479 -1.935477 +v -0.000000 -1.195963 -1.953291 +v -0.000000 -1.201961 -1.961859 +v -0.000000 -1.206381 -1.971337 +v -0.000000 -1.206381 -2.012380 +v -0.000000 -1.201961 -2.021859 +v -0.000000 -1.195963 -2.030426 +v -0.000000 -1.188567 -2.037821 +v -0.000000 -1.180000 -2.043820 +v -0.000000 -1.170521 -2.048241 +v -0.000000 -1.160419 -2.050947 +v -0.000000 -1.150000 -2.051859 +v -0.000000 -1.139581 -2.050947 +v -0.000000 -1.093618 -2.012380 +v -0.000000 -1.090911 -2.002277 +v -0.000000 -1.090000 -1.991859 +v -0.000000 -1.090911 -1.981440 +v -0.000000 -1.093618 -1.971337 +v -0.000000 -1.098038 -1.961859 +v -0.000000 -1.209088 -1.981440 +v -0.000000 -1.210000 -1.991859 +v -0.000000 -1.209088 -2.002277 +v -0.000000 -1.408525 -0.895000 +v -0.000000 -1.408525 -0.205000 +v -0.000000 -1.894454 -0.205000 +v -0.000000 -2.557874 -0.466130 +v -0.000000 -1.408525 0.130000 +v -0.000000 -1.894454 0.130000 +v 0.000000 -1.139581 1.932770 +v 0.000000 -0.854807 1.570929 +v 0.000000 -1.150000 1.931858 +v 0.000000 -1.129479 1.935477 +v 0.000000 -1.120000 1.939897 +v 0.000000 -1.111432 1.945896 +v 0.000000 -1.104037 1.953291 +v 0.000000 -1.098038 1.961858 +v 0.000000 -1.093618 1.971337 +v 0.000000 -1.104037 2.030426 +v 0.000000 -1.111432 2.037821 +v 0.000000 -1.120000 2.043820 +v 0.000000 -1.150000 2.051858 +v 0.000000 -1.160419 2.050947 +v 0.000000 -1.170521 2.048240 +v 0.000000 -1.180000 2.043820 +v 0.000000 -1.188567 2.037821 +v 0.000000 -1.195963 2.030426 +v 0.000000 -1.201961 2.021858 +v 0.000000 -1.206381 2.012379 +v 0.000000 -1.209088 2.002277 +v 0.000000 -1.201961 1.961858 +v 0.000000 -1.195963 1.953291 +v 0.000000 -1.188567 1.945896 +v 0.000000 -1.180000 1.939897 +v 0.000000 -1.170521 1.935477 +v 0.000000 -1.160419 1.932770 +v 0.000000 -1.090911 1.981439 +v 0.000000 -1.090000 1.991858 +v 0.000000 -1.090911 2.002277 +v 0.000000 -1.129479 2.048240 +v 0.000000 -1.139581 2.050947 +v 0.000000 -1.093618 2.012379 +v 0.000000 -1.098038 2.021858 +v 0.000000 -1.210000 1.991858 +v 0.000000 -1.209088 1.981439 +v 0.000000 -1.206381 1.971337 +v -0.000000 -1.408525 -1.542500 +v -0.000000 -0.854807 -1.542500 +v -0.000000 -0.112500 -1.542500 +v 0.000000 0.519615 0.400000 +v 0.000000 0.502251 0.398480 +v 0.000000 0.569616 0.213397 +v 0.000000 0.583894 0.223395 +v 0.000000 0.485414 0.393969 +v 0.000000 0.469615 0.386602 +v 0.000000 0.455337 0.376604 +v 0.000000 0.596220 0.235721 +v 0.000000 0.606218 0.250000 +v 0.000000 0.613585 0.265798 +v 0.000000 0.613585 0.334202 +v 0.000000 0.606218 0.350000 +v 0.000000 0.596220 0.364279 +v 0.000000 0.583894 0.376604 +v 0.000000 0.569616 0.386602 +v 0.000000 0.553818 0.393969 +v 0.000000 0.536980 0.398480 +v 0.000000 0.443011 0.364279 +v 0.000000 0.433013 0.350000 +v 0.000000 0.425646 0.334202 +v 0.000000 0.425646 0.265798 +v 0.000000 0.433013 0.250000 +v 0.000000 0.443011 0.235721 +v 0.000000 0.455337 0.223395 +v 0.000000 0.618096 0.282635 +v 0.000000 0.619615 0.300000 +v 0.000000 0.618096 0.317364 +v 0.000000 0.421135 0.317364 +v 0.000000 0.419616 0.300000 +v 0.000000 0.421135 0.282635 +v 0.000000 0.469615 0.213397 +v 0.000000 0.485414 0.206031 +v 0.000000 0.502251 0.201519 +v 0.000000 0.519615 0.200000 +v 0.000000 0.536980 0.201519 +v 0.000000 0.553818 0.206031 +v 0.000000 -0.112500 1.570929 +v 0.000000 -0.080000 1.570929 +v 0.000000 0.112500 1.570929 +v 0.000000 0.384808 1.570929 +v 0.000000 0.854808 1.570929 +v -0.000000 1.139581 -1.932770 +v -0.000000 1.129479 -1.935477 +v -0.000000 0.854808 -1.903430 +v -0.000000 1.150000 -1.931859 +v -0.000000 1.408525 -2.088429 +v -0.000000 1.170521 -2.048241 +v -0.000000 1.180000 -2.043820 +v -0.000000 1.090000 -1.991859 +v -0.000000 1.090912 -2.002277 +v -0.000000 1.180000 -1.939897 +v -0.000000 1.170521 -1.935477 +v -0.000000 1.408525 -1.903430 +v -0.000000 1.160419 -1.932770 +v -0.000000 1.120000 -1.939897 +v -0.000000 1.111433 -1.945896 +v -0.000000 1.104038 -1.953291 +v -0.000000 1.098039 -1.961859 +v -0.000000 1.093619 -1.971337 +v -0.000000 1.090912 -1.981440 +v -0.000000 1.129479 -2.048241 +v -0.000000 1.139581 -2.050947 +v -0.000000 1.150000 -2.051859 +v -0.000000 1.160419 -2.050947 +v -0.000000 1.188567 -2.037821 +v -0.000000 1.195963 -2.030426 +v -0.000000 1.201962 -2.021859 +v -0.000000 1.093619 -2.012380 +v -0.000000 1.098039 -2.021859 +v -0.000000 1.104038 -2.030426 +v -0.000000 1.206382 -2.012380 +v -0.000000 1.209089 -2.002277 +v -0.000000 1.210000 -1.991859 +v -0.000000 1.209089 -1.981440 +v -0.000000 1.206382 -1.971337 +v -0.000000 1.201962 -1.961859 +v -0.000000 1.195963 -1.953291 +v -0.000000 1.188567 -1.945896 +v -0.000000 1.111433 -2.037821 +v -0.000000 1.120000 -2.043820 +v -0.000000 1.408525 -1.542500 +v 0.000000 0.854808 -0.205000 +v 0.000000 1.408525 0.130000 +v 0.000000 0.854808 0.982500 +v 0.000000 0.384808 0.982500 +v 0.000000 0.112500 0.982500 +v 0.000000 -0.080000 0.982500 +v 0.000000 -0.112500 0.982500 +v 0.000000 -0.854807 0.982500 +v 0.000000 0.854808 1.167500 +v 0.000000 0.384808 1.167500 +v 0.000000 0.112500 1.167500 +v 0.000000 -0.080000 1.167500 +v 0.000000 -0.112500 1.167500 +v 0.000000 -0.854807 1.167500 +v 0.000000 1.210000 1.991858 +v 0.000000 1.209089 2.002277 +v 0.000000 1.129479 2.048240 +v 0.000000 1.120000 2.043820 +v 0.000000 1.111433 2.037821 +v 0.000000 1.104038 2.030426 +v 0.000000 1.160419 1.932770 +v 0.000000 1.170521 1.935477 +v 0.000000 1.098039 2.021858 +v 0.000000 1.093619 2.012379 +v 0.000000 1.090912 2.002277 +v 0.000000 1.090000 1.991858 +v 0.000000 1.090912 1.981439 +v 0.000000 1.093619 1.971337 +v 0.000000 1.098039 1.961858 +v 0.000000 1.104038 1.953291 +v 0.000000 1.111433 1.945896 +v 0.000000 1.120000 1.939897 +v 0.000000 1.180000 1.939897 +v 0.000000 1.188567 1.945896 +v 0.000000 1.195963 1.953291 +v 0.000000 1.201962 1.961858 +v 0.000000 1.206382 1.971337 +v 0.000000 1.209089 1.981439 +v 0.000000 1.206382 2.012379 +v 0.000000 1.201962 2.021858 +v 0.000000 1.195963 2.030426 +v 0.000000 1.188567 2.037821 +v 0.000000 1.180000 2.043820 +v 0.000000 1.170521 2.048240 +v 0.000000 1.160419 2.050947 +v 0.000000 1.150000 2.051858 +v 0.000000 1.139581 2.050947 +v 0.000000 1.129479 1.935477 +v 0.000000 1.139581 1.932770 +v 0.000000 1.150000 1.931858 +v -0.000000 1.613585 -2.038712 +v -0.000000 1.395410 -2.193817 +v -0.000000 1.162444 -2.325666 +v -0.000000 0.854808 -1.542500 +v 0.000000 1.408525 -0.895000 +v 0.000000 1.894455 -0.205000 +v 0.000000 1.894455 0.130000 +v 0.000000 1.408525 -0.205000 +v -0.000000 0.854808 -0.895000 +v -0.000000 0.384808 -1.542500 +vn 0.7273 -0.1192 0.6759 +vn 0.7273 -0.0000 0.6864 +vn 1.0000 -0.0000 -0.0000 +vn 0.6957 0.5013 -0.5145 +vn 0.6957 0.6784 0.2360 +vn 0.6957 0.6506 0.3045 +vn 0.6957 -0.6506 0.3045 +vn 0.6957 -0.6784 0.2360 +vn 0.6957 -0.3212 -0.6425 +vn 0.6957 -0.2534 -0.6721 +vn 0.7273 -0.1191 -0.6759 +vn 0.7273 -0.2347 -0.6450 +vn 0.7273 -0.3432 -0.5944 +vn 0.7273 -0.4412 -0.5258 +vn 0.7273 0.6450 0.2347 +vn 0.7273 0.6759 0.1192 +vn 0.7273 -0.6864 -0.0000 +vn 0.7273 -0.6759 0.1192 +vn 0.7273 0.6759 -0.1192 +vn 0.7273 0.6450 -0.2348 +vn 0.7273 -0.4412 0.5258 +vn 0.7273 -0.3432 0.5944 +vn 0.7273 0.2347 0.6450 +vn 0.7273 0.5258 -0.4412 +vn 0.7273 0.4412 -0.5258 +vn 0.7273 -0.2348 0.6450 +vn 0.7273 0.1192 0.6759 +vn 0.7273 0.2348 0.6449 +vn 0.7273 0.3432 0.5944 +vn 0.7273 0.3432 -0.5944 +vn 0.7273 0.2348 0.6450 +vn 0.7273 0.3431 -0.5944 +vn 0.7273 0.2347 -0.6450 +vn 0.7273 0.2348 -0.6450 +vn 0.7273 0.1192 -0.6759 +vn 0.7273 0.1191 0.6759 +vn 0.7273 -0.0001 0.6864 +vn 0.7273 -0.0000 -0.6864 +vn 0.7273 -0.0001 -0.6864 +vn 0.7273 -0.1191 0.6759 +vn 0.7273 -0.1192 -0.6759 +vn 0.7273 -0.2347 0.6450 +vn 0.7273 -0.6759 0.1191 +vn 0.7273 -0.6450 0.2348 +vn 0.7273 -0.6450 0.2347 +vn 0.7273 -0.5944 0.3432 +vn 0.7273 -0.5258 0.4412 +vn 0.7273 -0.3431 -0.5944 +vn 0.7273 -0.2348 0.6449 +vn 0.7273 -0.5258 -0.4412 +vn 0.7273 -0.5944 -0.3431 +vn 0.7273 -0.5944 -0.3432 +vn 0.7273 -0.6450 -0.2348 +vn 0.7273 -0.6450 -0.2347 +vn 0.7273 -0.6759 -0.1192 +vn 0.7273 0.4412 0.5258 +vn 0.7273 0.5258 0.4412 +vn 0.7273 0.6864 -0.0001 +vn 0.7273 0.6759 -0.1191 +vn 0.7273 0.6450 -0.2347 +vn 0.7273 0.5944 -0.3431 +vn 0.7273 0.5944 0.3432 +vn 0.7273 0.6450 0.2348 +vn 0.7273 0.6864 -0.0000 +vn 0.7273 -0.6759 -0.1191 +vn 0.7273 0.6759 0.1191 +vn 0.7273 0.5944 -0.3432 +vn 0.7273 0.1191 -0.6759 +vn 0.6957 0.5746 0.4311 +vn 0.7273 -0.2348 -0.6449 +vn 0.6957 0.5745 0.4311 +vn 0.6957 0.5745 0.4312 +vn 0.7273 -0.2348 -0.6450 +vn 0.7273 0.5944 0.3431 +vn 0.7273 -0.5944 0.3431 +vn 0.6957 -0.5746 0.4311 +vn 0.7273 0.5258 -0.4411 +vn 0.6957 -0.5745 0.4311 +vn 0.6957 -0.5745 0.4312 +vn 0.7273 0.2348 -0.6449 +vn 0.7273 0.3431 0.5944 +vn 0.7273 -0.6449 -0.2348 +vn 0.7273 0.0001 -0.6864 +vn 0.7273 -0.3431 0.5944 +vn 0.7014 -0.0000 -0.7128 +vn 0.7273 0.4411 0.5258 +vn 0.6985 0.0460 -0.7141 +vn 0.6985 -0.0460 -0.7141 +vn 0.6985 -0.0461 -0.7141 +vn 0.7273 0.5258 0.4411 +vn 0.7014 0.0001 -0.7128 +vn 0.7273 -0.4411 0.5258 +vn 0.6985 0.0461 -0.7141 +vn 0.7273 -0.5258 0.4411 +vn 0.7273 -0.6864 -0.0001 +vn 0.7273 -0.6864 0.0001 +vn 0.7273 -0.4411 -0.5258 +vn 0.7260 0.1158 -0.6779 +vn 0.7260 0.1159 -0.6779 +vn 0.7171 0.2025 -0.6670 +vn 0.7273 0.6449 -0.2348 +vn 0.7273 0.4411 -0.5258 +vn 0.7273 -0.5258 -0.4411 +vn 0.7273 0.5943 -0.3434 +vn 0.7183 0.2628 -0.6442 +vn 0.6957 -0.1829 -0.6946 +vn 0.6957 -0.1105 -0.7098 +vn 0.6957 -0.1106 -0.7098 +vn 0.6957 -0.3211 -0.6425 +vn 0.6957 -0.3855 -0.6061 +vn 0.6957 -0.4458 -0.5633 +vn 0.6957 -0.4458 -0.5632 +vn 0.6957 -0.5013 -0.5145 +vn 0.6957 -0.5960 -0.4010 +vn 0.6957 -0.5516 -0.4602 +vn 0.6957 -0.5516 -0.4601 +vn 0.6957 -0.5959 -0.4011 +vn 0.6957 -0.5959 -0.4010 +vn 0.7273 0.6449 0.2348 +vn 0.7273 0.6864 0.0001 +vn 0.6957 -0.5960 -0.4009 +vn 0.6957 -0.6341 -0.3376 +vn 0.6957 -0.6340 -0.3376 +vn 0.6957 -0.6654 -0.2706 +vn 0.6957 -0.7162 -0.0554 +vn 0.6957 -0.7162 -0.0555 +vn 0.6957 -0.7067 -0.1288 +vn 0.6957 -0.6897 -0.2007 +vn 0.6957 -0.6991 0.1650 +vn 0.6957 -0.7124 0.0922 +vn 0.6957 -0.7181 0.0184 +vn 0.6957 -0.7181 0.0185 +vn 0.6957 -0.6158 0.3698 +vn 0.6957 -0.2184 0.6843 +vn 0.6957 -0.2877 0.6582 +vn 0.6957 -0.2876 0.6582 +vn 0.6957 -0.3538 0.6251 +vn 0.6957 -0.3538 0.6252 +vn 0.6957 -0.4162 0.5855 +vn 0.6957 -0.4742 0.5396 +vn 0.6957 -0.4742 0.5395 +vn 0.6957 -0.5271 0.4880 +vn 0.6957 -0.5272 0.4879 +vn 0.7014 -0.0293 0.7122 +vn 0.6997 0.0129 0.7144 +vn 0.7014 -0.0294 0.7122 +vn 0.6957 0.0739 0.7145 +vn 0.6957 0.0738 0.7145 +vn 0.6957 -0.1469 0.7031 +vn 0.6957 -0.1470 0.7031 +vn 0.6974 -0.0792 0.7123 +vn 0.6957 0.2877 0.6582 +vn 0.6957 0.2184 0.6843 +vn 0.6957 0.1469 0.7031 +vn 0.6957 0.1470 0.7031 +vn 0.6957 0.2876 0.6582 +vn 0.6957 0.3538 0.6251 +vn 0.6957 0.3538 0.6252 +vn 0.6957 0.4162 0.5855 +vn 0.6957 0.4162 0.5854 +vn 0.6957 0.4742 0.5395 +vn 0.6957 0.4742 0.5396 +vn 0.6957 0.5272 0.4879 +vn 0.6957 0.6158 0.3698 +vn 0.6957 0.7067 -0.1288 +vn 0.6957 0.7067 -0.1287 +vn 0.6957 0.7162 -0.0554 +vn 0.6957 0.7162 -0.0555 +vn 0.6957 0.7181 0.0184 +vn 0.6957 0.7181 0.0186 +vn 0.6957 0.7181 0.0185 +vn 0.6957 0.7124 0.0922 +vn 0.6957 0.7124 0.0923 +vn 0.6957 0.6897 -0.2007 +vn 0.6957 0.6654 -0.2706 +vn 0.6957 0.5960 -0.4010 +vn 0.6957 0.6341 -0.3376 +vn 0.6957 0.5013 -0.5144 +vn 0.6957 0.5516 -0.4601 +vn 0.7273 0.5257 0.4412 +vn 0.6957 0.5959 -0.4010 +vn 0.6957 0.5959 -0.4011 +vn 0.6957 0.5516 -0.4602 +vn 0.6957 0.3855 -0.6061 +vn 0.6957 0.3212 -0.6425 +vn 0.6957 0.1106 -0.7098 +vn 0.6957 0.1105 -0.7098 +vn 0.6957 0.1830 -0.6946 +vn 0.6957 0.1829 -0.6946 +vn 0.6957 0.2534 -0.6722 +vn 0.6957 0.2534 -0.6721 +vn 0.6957 0.6991 0.1650 +vn 0.6957 0.6785 0.2360 +vn 0.7273 -0.4412 -0.5257 +vn 0.6957 0.6340 -0.3376 +vn 0.7273 -0.6449 0.2348 +vn 0.6957 0.4458 -0.5633 +vn 0.6957 0.4458 -0.5632 +vn 0.6957 0.5014 -0.5144 +vn 0.7273 0.4412 -0.5257 +vn 0.7273 -0.4412 0.5257 +vn 0.6957 -0.5014 -0.5144 +vn 0.6957 -0.5013 -0.5144 +vn 0.6957 -0.6785 0.2360 +vn 0.6957 -0.6897 -0.2008 +vn -1.0000 -0.0000 -0.0000 +vn -0.6957 -0.6784 0.2360 +vn -0.6957 -0.6991 0.1650 +vn -0.6957 -0.6506 0.3045 +vn -0.6957 -0.2877 0.6582 +vn -0.6957 -0.2184 0.6843 +vn -0.7273 -0.1191 -0.6759 +vn -0.7273 -0.0000 -0.6864 +vn -0.6997 0.0129 0.7144 +vn -0.6957 0.5745 0.4312 +vn -0.6957 0.5272 0.4879 +vn -0.6957 0.6506 0.3045 +vn -0.6957 0.6784 0.2360 +vn -0.6957 0.6991 0.1650 +vn -0.6957 0.6897 -0.2008 +vn -0.6957 0.6654 -0.2706 +vn -0.7273 0.5944 0.3432 +vn -0.7273 0.5258 0.4412 +vn -0.7273 -0.6450 0.2347 +vn -0.7273 -0.6759 0.1191 +vn -0.7273 -0.2348 0.6450 +vn -0.7273 -0.3432 0.5944 +vn -0.7273 -0.4412 0.5258 +vn -0.7273 -0.5258 0.4412 +vn -0.7273 0.5258 -0.4412 +vn -0.7273 0.2347 0.6450 +vn -0.7273 0.4412 -0.5258 +vn -0.7273 0.2348 0.6450 +vn -0.7273 0.3432 -0.5944 +vn -0.7273 0.3432 0.5944 +vn -0.7273 0.4412 0.5258 +vn -0.7273 0.2348 0.6449 +vn -0.7273 0.1192 0.6759 +vn -0.7273 -0.0000 0.6864 +vn -0.7273 -0.1192 0.6759 +vn -0.7273 -0.2348 0.6449 +vn -0.7273 -0.3431 -0.5944 +vn -0.7273 -0.2347 -0.6450 +vn -0.7273 -0.2348 -0.6450 +vn -0.7273 -0.1192 -0.6759 +vn -0.7273 -0.1191 0.6759 +vn -0.7273 0.0001 0.6864 +vn -0.7273 0.0001 -0.6864 +vn -0.7273 0.1191 0.6759 +vn -0.7273 0.1192 -0.6759 +vn -0.7273 0.2347 -0.6450 +vn -0.7273 0.3431 -0.5944 +vn -0.7273 -0.5944 0.3432 +vn -0.7273 -0.6450 0.2348 +vn -0.7273 -0.6759 0.1192 +vn -0.7273 -0.6864 -0.0001 +vn -0.7273 -0.6759 -0.1192 +vn -0.7273 -0.2347 0.6450 +vn -0.7273 -0.6450 -0.2347 +vn -0.7273 -0.6450 -0.2348 +vn -0.7273 -0.5944 -0.3432 +vn -0.7273 -0.5944 -0.3431 +vn -0.7273 -0.5258 -0.4412 +vn -0.7273 -0.4412 -0.5258 +vn -0.7273 -0.3432 -0.5944 +vn -0.7273 0.5944 0.3431 +vn -0.7273 0.5944 -0.3431 +vn -0.7273 0.6450 -0.2348 +vn -0.7273 0.6450 -0.2347 +vn -0.7273 0.6759 -0.1191 +vn -0.7273 0.6864 -0.0000 +vn -0.7273 0.6759 0.1192 +vn -0.7273 0.6450 0.2348 +vn -0.7273 0.6450 0.2347 +vn -0.7273 0.6759 -0.1192 +vn -0.7273 -0.6864 -0.0000 +vn -0.6957 0.5746 0.4311 +vn -0.7273 -0.6759 -0.1191 +vn -0.6957 0.5745 0.4311 +vn -0.7273 0.5257 -0.4412 +vn -0.7273 0.5944 -0.3432 +vn -0.7273 -0.2348 -0.6449 +vn -0.7273 -0.0001 -0.6864 +vn -0.7273 0.1191 -0.6759 +vn -0.7273 -0.5944 0.3431 +vn -0.7273 0.6759 0.1191 +vn -0.6957 -0.5746 0.4311 +vn -0.7273 0.2348 -0.6449 +vn -0.6957 -0.5745 0.4311 +vn -0.6957 -0.5745 0.4312 +vn -0.7273 0.2348 -0.6450 +vn -0.7273 0.3431 0.5944 +vn -0.7273 -0.3431 0.5944 +vn -0.7273 0.6449 -0.2348 +vn -0.7273 0.5258 0.4411 +vn -0.6985 -0.0461 -0.7141 +vn -0.6985 0.0461 -0.7141 +vn -0.7273 0.4411 0.5258 +vn -0.7014 0.0001 -0.7128 +vn -0.7014 -0.0000 -0.7128 +vn -0.6985 -0.0460 -0.7141 +vn -0.6985 0.0460 -0.7141 +vn -0.7273 -0.5258 0.4411 +vn -0.7273 -0.4411 0.5258 +vn -0.7273 -0.4412 -0.5257 +vn -0.7273 0.6864 -0.0001 +vn -0.7273 0.4411 -0.5258 +vn -0.7273 -0.6449 -0.2348 +vn -0.7273 -0.5258 -0.4411 +vn -0.7273 -0.4411 -0.5258 +vn -0.7273 0.5258 -0.4411 +vn -0.7273 0.4412 -0.5257 +vn -0.7171 0.2025 -0.6670 +vn -0.7183 0.2628 -0.6442 +vn -0.7171 0.2025 -0.6669 +vn -0.7260 0.1158 -0.6779 +vn -0.7273 -0.6864 0.0001 +vn -0.6957 0.1105 -0.7098 +vn -0.6957 0.2534 -0.6722 +vn -0.6957 0.1830 -0.6946 +vn -0.6957 0.5960 -0.4010 +vn -0.6957 0.5013 -0.5144 +vn -0.6957 0.5516 -0.4601 +vn -0.6957 0.5516 -0.4602 +vn -0.6957 0.5959 -0.4010 +vn -0.7273 0.5257 0.4412 +vn -0.6957 0.5960 -0.4009 +vn -0.6957 0.6341 -0.3376 +vn -0.6957 0.6340 -0.3376 +vn -0.6957 0.7067 -0.1288 +vn -0.6957 0.7162 -0.0554 +vn -0.6957 0.7162 -0.0555 +vn -0.6957 0.7181 0.0185 +vn -0.6957 0.7181 0.0184 +vn -0.6957 0.7124 0.0923 +vn -0.6957 0.7124 0.0922 +vn -0.6957 0.7181 0.0186 +vn -0.6957 0.7067 -0.1287 +vn -0.6957 0.6158 0.3698 +vn -0.6957 0.5271 0.4880 +vn -0.6957 0.4742 0.5396 +vn -0.6957 0.4742 0.5395 +vn -0.6957 0.4162 0.5855 +vn -0.6957 0.3538 0.6252 +vn -0.6957 0.3538 0.6251 +vn -0.6957 0.2876 0.6582 +vn -0.6957 0.0738 0.7145 +vn -0.6957 0.0739 0.7145 +vn -0.6957 0.1470 0.7031 +vn -0.6957 0.1469 0.7031 +vn -0.6957 0.2184 0.6843 +vn -0.6957 0.2877 0.6582 +vn -0.7014 -0.0293 0.7122 +vn -0.7273 -0.0001 0.6864 +vn -0.7014 -0.0294 0.7122 +vn -0.6974 -0.0792 0.7123 +vn -0.6957 -0.2185 0.6843 +vn -0.6957 -0.1469 0.7031 +vn -0.6957 -0.1470 0.7031 +vn -0.6957 -0.2876 0.6582 +vn -0.6957 -0.3538 0.6251 +vn -0.6957 -0.3538 0.6252 +vn -0.6957 -0.4162 0.5855 +vn -0.6957 -0.4162 0.5854 +vn -0.6957 -0.4742 0.5395 +vn -0.6957 -0.4742 0.5396 +vn -0.6957 -0.5272 0.4879 +vn -0.6957 -0.6158 0.3698 +vn -0.6957 -0.7181 0.0184 +vn -0.6957 -0.7124 0.0922 +vn -0.6957 -0.5960 -0.4010 +vn -0.6957 -0.6341 -0.3376 +vn -0.6957 -0.6340 -0.3376 +vn -0.6957 -0.6654 -0.2706 +vn -0.6957 -0.6897 -0.2008 +vn -0.7273 0.6449 0.2348 +vn -0.6957 -0.5959 -0.4010 +vn -0.6957 -0.5959 -0.4011 +vn -0.6957 -0.5516 -0.4602 +vn -0.7273 0.6864 0.0001 +vn -0.6957 -0.5014 -0.5144 +vn -0.6957 -0.5013 -0.5145 +vn -0.6957 -0.4458 -0.5632 +vn -0.6957 -0.3212 -0.6425 +vn -0.6957 -0.3855 -0.6061 +vn -0.6957 -0.4458 -0.5633 +vn -0.6957 -0.1106 -0.7098 +vn -0.6957 -0.1105 -0.7098 +vn -0.6957 -0.1829 -0.6946 +vn -0.6957 -0.1830 -0.6946 +vn -0.6957 -0.2534 -0.6722 +vn -0.6957 -0.2534 -0.6721 +vn -0.6957 -0.7181 0.0185 +vn -0.6957 -0.7162 -0.0555 +vn -0.7273 -0.4412 0.5257 +vn -0.6957 -0.6785 0.2360 +vn -0.6957 -0.6897 -0.2007 +vn -0.6957 -0.7067 -0.1288 +vn -0.6957 -0.5516 -0.4601 +vn -0.6957 -0.5013 -0.5144 +vn -0.6957 0.1829 -0.6946 +vn -0.6957 0.1106 -0.7098 +vn -0.7273 -0.6449 0.2348 +vn -0.6957 0.5013 -0.5145 +vn -0.6957 0.5014 -0.5144 +vn -0.6957 0.4458 -0.5633 +vn -0.6957 0.4458 -0.5632 +vn -0.6957 0.3855 -0.6061 +vn -0.6957 0.3211 -0.6425 +vn -0.6957 0.3212 -0.6425 +vn -0.6957 0.2534 -0.6721 +vn -0.6957 0.6897 -0.2007 +vn -0.6957 0.6785 0.2360 +vn 0.6974 -0.0791 0.7123 +vn -0.6957 -0.1469 0.7032 +vn 0.6957 -0.1469 0.7032 +vn 0.6957 -0.2185 0.6843 +vn 0.6957 -0.3539 0.6251 +vn 0.6957 -0.4163 0.5854 +vn -0.6957 -0.5272 0.4880 +vn 0.6957 -0.5272 0.4880 +vn 0.6957 -0.5746 0.4312 +vn 0.6957 -0.6159 0.3698 +vn -0.6957 -0.6506 0.3046 +vn -0.6957 -0.7124 0.0923 +vn -0.6957 -0.7162 -0.0554 +vn -0.6957 -0.7067 -0.1287 +vn 0.6957 -0.6654 -0.2707 +vn -0.6957 -0.3856 -0.6061 +vn 0.6957 -0.3211 -0.6426 +vn 0.6957 -0.2534 -0.6722 +vn -0.6957 -0.1829 -0.6947 +vn 0.6957 -0.1829 -0.6947 +vn 0.7014 -0.0001 -0.7128 +vn 0.6957 0.1469 0.7032 +vn 0.6957 0.2185 0.6843 +vn -0.6957 0.1469 0.7032 +vn -0.6957 0.2185 0.6843 +vn -0.6957 0.3539 0.6251 +vn -0.6957 0.4163 0.5854 +vn 0.6957 0.5272 0.4880 +vn -0.6957 0.5272 0.4880 +vn -0.6957 0.5746 0.4312 +vn -0.6957 0.6159 0.3698 +vn 0.6957 0.6506 0.3046 +vn 0.6957 0.6897 -0.2008 +vn -0.6957 0.6654 -0.2707 +vn 0.6957 0.3856 -0.6061 +vn -0.6957 0.3211 -0.6426 +vn 0.6957 0.1829 -0.6947 +vn -0.6957 0.1829 -0.6947 +vn 0.7273 -0.0000 -0.6863 +vn -0.7273 -0.0000 -0.6863 +vn -0.7273 -0.5257 -0.4412 +vn 0.7273 -0.6863 -0.0000 +vn -0.7273 -0.6863 -0.0000 +vn 0.7273 -0.0000 0.6863 +vn -0.7273 -0.0000 0.6863 +vn 0.7273 0.6863 -0.0000 +vn -0.7273 0.6863 -0.0000 +vn 0.7273 0.5257 -0.4412 +vn 0.7183 0.2629 -0.6442 +vn 0.7171 0.2025 -0.6669 +vn -0.7183 0.2629 -0.6442 +vn -0.7170 0.2025 -0.6670 +vn 0.7170 0.2024 -0.6670 +vn -0.7171 0.2024 -0.6669 +vn -0.7260 0.1157 -0.6779 +vn -0.7272 -0.0000 -0.6864 +vn -0.7272 -0.5258 -0.4412 +vn 0.7273 -0.6863 -0.0001 +vn -0.7273 -0.6863 0.0001 +vn 0.7272 -0.5944 0.3432 +vn 0.7273 -0.5257 0.4412 +vn -0.7273 -0.5257 0.4412 +vn 0.7273 0.0001 0.6864 +vn -0.7273 0.4412 0.5257 +vn 0.7272 0.5258 -0.4412 +vn -0.7272 0.5258 -0.4412 +vn 0.7272 -0.0000 -0.6864 +vn 0.7272 -0.1192 -0.6760 +vn 0.7272 -0.1191 -0.6760 +vn -0.7272 -0.1192 -0.6760 +vn -0.7272 -0.1192 -0.6759 +vn 0.7272 -0.5258 -0.4412 +vn 0.7272 -0.5258 0.4412 +vn 0.7272 -0.1191 0.6760 +vn -0.7272 -0.1192 0.6759 +vn 0.7272 -0.1192 0.6760 +vn -0.7272 -0.1191 0.6760 +vn -0.7272 -0.1192 0.6760 +vn 0.7272 0.1192 0.6760 +vn 0.7272 0.1191 0.6760 +vn -0.7272 0.1192 0.6760 +vn 0.7272 0.1192 0.6759 +vn -0.7272 0.1191 0.6760 +vn 0.7273 0.4412 0.5257 +vn -0.7272 0.5258 0.4412 +vn 0.7273 0.6863 0.0001 +vn -0.7273 0.6863 -0.0001 +vn 0.7272 0.1192 -0.6760 +vn 0.7272 0.1192 -0.6759 +vn -0.7272 0.1191 -0.6760 +vn -0.7272 0.1192 -0.6760 +vn 0.7273 -0.5257 -0.4412 +vn 0.7272 0.4412 0.5258 +vn -0.7272 0.4412 0.5258 +vn 0.7272 0.4412 -0.5258 +vn -0.7273 -0.6759 -0.1193 +vn -0.7273 0.6759 0.1193 +vn 0.7273 0.6759 -0.1193 +vn -0.7273 -0.0001 -0.6863 +vn 0.7273 -0.0001 0.6863 +vn -0.7273 0.0001 0.6863 +vn 0.7273 0.0001 -0.6863 +vn 0.7273 -0.1193 -0.6759 +vn -0.7273 0.1193 -0.6759 +vn 0.7272 0.6864 -0.0000 +vn 0.7272 0.6864 0.0001 +vn -0.7272 0.6864 -0.0000 +vn -0.7272 0.6864 -0.0001 +vn -0.7272 -0.4412 -0.5258 +vn 0.7272 -0.6760 -0.1192 +vn 0.7272 -0.6759 -0.1192 +vn -0.7272 -0.6760 -0.1192 +vn -0.7272 -0.6760 -0.1191 +vn 0.7272 -0.6760 0.1192 +vn 0.7272 -0.6760 0.1191 +vn -0.7272 -0.6760 0.1192 +vn -0.7272 -0.6759 0.1192 +vn 0.7272 -0.4412 0.5258 +vn -0.7272 -0.4412 0.5258 +vn 0.7272 0.6760 0.1192 +vn 0.7272 0.6759 0.1192 +vn -0.7272 0.6760 0.1192 +vn -0.7272 0.6760 0.1191 +vn 0.7272 0.6760 -0.1192 +vn 0.7272 0.6760 -0.1191 +vn -0.7272 0.6760 -0.1192 +vn -0.7272 0.6759 -0.1192 +vn -0.7272 -0.3432 0.5944 +vn -0.7272 0.4412 -0.5258 +vn 0.7272 -0.4412 -0.5258 +vn -0.7272 -0.3432 -0.5944 +vn -0.7272 -0.5258 0.4412 +vn 0.7272 0.3432 0.5944 +vn 0.7272 0.5258 0.4412 +vn 0.7272 0.3432 -0.5944 +s 0 +f 1//1 2//2 3//3 +f 4//4 5//3 6//3 +f 7//5 8//6 9//3 +f 9//3 8//6 10//3 +f 11//7 12//3 13//3 +f 14//8 15//3 16//3 +f 17//9 18//10 19//3 +f 20//11 21//12 22//3 +f 23//13 24//14 25//3 +f 26//15 27//16 28//3 +f 29//17 30//18 31//3 +f 32//19 33//20 34//3 +f 35//21 36//22 37//3 +f 38//23 39//24 40//25 +f 36//22 41//26 37//3 +f 37//3 41//26 42//1 +f 37//3 42//1 43//3 +f 43//3 42//1 44//2 +f 44//2 45//27 43//3 +f 43//3 45//27 46//28 +f 43//3 46//23 47//29 +f 40//25 48//30 38//31 +f 38//28 48//32 49//33 +f 38//31 49//33 50//27 +f 50//27 49//34 51//35 +f 50//36 51//35 52//2 +f 52//37 51//35 53//38 +f 52//2 53//39 54//40 +f 54//40 53//38 55//41 +f 54//1 55//41 56//26 +f 56//42 55//41 57//12 +f 58//17 59//43 37//3 +f 37//3 59//18 60//44 +f 60//45 61//46 37//3 +f 37//3 61//46 62//47 +f 37//3 62//47 35//21 +f 57//12 63//48 56//49 +f 56//26 63//13 64//14 +f 56//42 64//14 65//50 +f 65//50 66//51 56//42 +f 56//26 66//52 67//53 +f 56//26 67//54 68//55 +f 47//29 69//56 43//3 +f 43//3 69//56 70//57 +f 43//3 70//57 71//3 +f 72//58 73//19 38//23 +f 73//59 74//60 38//31 +f 38//31 74//20 75//61 +f 38//23 75//61 39//24 +f 70//57 76//62 71//3 +f 71//3 76//62 77//15 +f 71//3 77//63 78//16 +f 32//19 34//3 79//64 +f 80//65 81//17 10//3 +f 10//3 81//17 82//18 +f 10//3 82//43 9//3 +f 9//3 82//18 83//45 +f 9//3 83//45 84//46 +f 84//46 85//47 9//3 +f 9//3 85//47 86//21 +f 9//3 86//21 87//22 +f 31//3 88//27 89//23 +f 89//28 90//29 31//3 +f 31//3 90//29 91//56 +f 31//3 91//56 92//57 +f 92//57 93//62 31//3 +f 31//3 93//62 94//63 +f 31//3 94//63 34//3 +f 34//3 94//15 95//66 +f 34//3 95//16 79//64 +f 87//22 96//26 9//3 +f 9//3 96//42 97//1 +f 9//3 97//1 31//3 +f 31//3 97//1 98//2 +f 31//3 98//2 88//27 +f 99//24 100//25 101//3 +f 99//24 101//3 102//67 +f 100//25 103//30 101//3 +f 101//3 103//30 104//33 +f 101//3 104//33 105//68 +f 106//38 107//41 108//69 +f 109//50 110//52 10//3 +f 10//3 110//52 111//53 +f 10//3 111//53 80//55 +f 107//41 112//70 108//71 +f 108//72 112//73 113//13 +f 108//71 113//13 114//14 +f 28//3 115//46 116//47 +f 117//57 118//74 12//3 +f 12//3 118//62 119//15 +f 12//3 119//15 13//3 +f 13//3 119//15 120//16 +f 13//3 120//66 121//64 +f 122//55 123//17 124//3 +f 124//3 123//17 125//18 +f 124//3 125//18 28//3 +f 28//3 125//18 126//44 +f 28//3 126//44 115//75 +f 116//47 127//21 28//3 +f 28//3 127//21 128//22 +f 28//3 128//22 129//49 +f 130//31 131//29 12//3 +f 12//3 131//29 132//56 +f 12//3 132//56 117//57 +f 129//42 133//1 28//3 +f 28//3 133//1 134//2 +f 28//3 134//2 12//3 +f 12//3 134//2 135//27 +f 12//3 135//27 130//23 +f 136//50 137//52 124//3 +f 124//3 137//52 138//54 +f 124//3 138//53 122//55 +f 139//67 140//24 141//76 +f 121//64 142//59 13//3 +f 13//3 142//19 143//20 +f 13//3 143//20 139//67 +f 144//13 145//14 146//3 +f 140//77 147//25 141//78 +f 141//78 147//25 148//30 +f 141//79 148//30 149//34 +f 144//13 146//3 150//12 +f 149//80 151//35 141//78 +f 141//76 151//35 152//38 +f 141//76 152//38 146//3 +f 146//3 152//38 153//11 +f 146//3 153//41 150//12 +f 154//75 155//47 156//3 +f 154//46 156//3 157//45 +f 155//47 158//21 156//3 +f 156//3 158//21 159//22 +f 156//3 159//22 160//42 +f 160//42 161//40 156//3 +f 156//3 161//1 162//2 +f 156//3 162//2 163//3 +f 163//3 162//2 164//27 +f 163//3 164//27 165//31 +f 165//23 166//29 163//3 +f 163//3 166//81 167//56 +f 163//3 167//56 168//57 +f 169//62 170//63 171//3 +f 171//3 170//15 172//16 +f 171//3 172//16 173//64 +f 174//19 175//60 176//3 +f 176//3 175//60 177//67 +f 176//3 177//67 178//24 +f 179//12 180//13 34//3 +f 34//3 180//13 181//14 +f 34//3 181//14 182//50 +f 182//50 183//52 34//3 +f 34//3 183//51 184//53 +f 34//3 184//54 31//3 +f 31//3 184//82 185//55 +f 31//3 185//55 29//17 +f 178//24 186//25 176//3 +f 176//3 186//25 187//30 +f 176//3 187//32 188//80 +f 188//34 189//35 176//3 +f 176//3 189//35 190//83 +f 176//3 190//38 34//3 +f 34//3 190//38 191//41 +f 34//3 191//41 179//12 +f 26//15 28//3 192//62 +f 193//45 194//46 195//3 +f 194//46 196//47 195//3 +f 195//3 196//47 197//21 +f 195//3 197//21 198//84 +f 199//3 200//36 201//23 +f 198//22 202//42 195//3 +f 195//3 202//26 203//1 +f 195//3 203//40 199//3 +f 199//3 203//1 204//2 +f 199//3 204//2 200//27 +f 201//23 205//29 199//3 +f 199//3 205//81 206//56 +f 199//3 206//56 207//57 +f 208//67 209//24 124//3 +f 210//70 211//48 212//3 +f 213//54 214//55 215//3 +f 215//3 214//55 216//17 +f 215//3 216//17 217//18 +f 27//16 218//64 28//3 +f 28//3 218//64 219//59 +f 28//3 219//59 124//3 +f 124//3 219//19 220//60 +f 124//3 220//20 208//61 +f 211//13 221//14 212//3 +f 212//3 221//14 222//50 +f 212//3 222//50 223//52 +f 209//24 224//25 124//3 +f 124//3 224//25 225//30 +f 124//3 225//30 226//33 +f 226//33 227//35 124//3 +f 124//3 227//35 228//38 +f 124//3 228//38 212//3 +f 212//3 228//39 229//41 +f 212//3 229//41 210//73 +f 230//85 231//2 232//27 +f 233//29 234//86 235//34 +f 236//41 237//12 238//1 +f 235//33 234//56 239//32 +f 238//40 237//12 240//42 +f 241//22 242//26 243//87 +f 244//19 245//60 234//56 +f 234//56 245//20 246//67 +f 230//85 232//27 247//88 +f 247//88 232//36 248//23 +f 247//88 248//31 249//29 +f 249//29 250//56 247//89 +f 247//88 250//56 251//90 +f 247//89 251//57 252//62 +f 246//67 253//24 234//56 +f 234//86 253//24 254//25 +f 234//86 254//25 239//30 +f 236//11 238//1 255//38 +f 255//38 238//1 256//2 +f 255//38 256//2 257//35 +f 257//35 256//2 258//27 +f 257//35 258//27 235//33 +f 235//33 258//36 259//23 +f 235//34 259//31 233//29 +f 260//3 261//47 262//21 +f 263//14 264//50 260//3 +f 260//3 264//50 265//52 +f 243//87 242//49 230//85 +f 230//91 242//26 266//1 +f 230//85 266//1 231//2 +f 252//74 267//15 247//88 +f 247//88 267//63 268//16 +f 247//89 268//16 269//64 +f 263//14 260//3 270//13 +f 270//48 260//3 262//21 +f 270//48 262//21 237//12 +f 237//73 262//92 271//22 +f 237//73 271//22 240//26 +f 272//46 273//47 243//93 +f 243//93 273//94 274//21 +f 243//93 274//21 241//22 +f 275//17 276//18 243//93 +f 243//87 276//18 277//44 +f 243//87 277//45 272//46 +f 265//52 278//54 260//3 +f 260//3 278//54 279//55 +f 260//3 279//55 275//17 +f 280//3 281//45 260//3 +f 260//3 281//44 282//46 +f 260//3 282//75 261//47 +f 283//55 284//17 280//3 +f 280//3 284//17 285//18 +f 280//3 285//18 281//45 +f 286//54 287//3 288//51 +f 288//51 287//3 25//3 +f 288//51 25//3 289//50 +f 289//50 25//3 24//14 +f 290//30 291//33 292//3 +f 291//33 293//68 292//3 +f 292//3 293//35 294//38 +f 292//3 294//38 295//3 +f 295//3 294//38 296//41 +f 295//3 296//41 297//12 +f 298//25 299//3 300//24 +f 300//24 299//3 301//3 +f 302//62 303//15 19//3 +f 304//3 305//20 301//3 +f 301//3 305//60 306//67 +f 301//3 306//61 300//24 +f 303//15 307//16 19//3 +f 19//3 307//66 308//64 +f 19//3 308//64 304//3 +f 304//3 308//64 309//19 +f 304//3 309//19 305//60 +f 302//74 310//3 311//57 +f 311//57 310//3 234//56 +f 68//55 58//95 56//42 +f 56//26 58//17 37//3 +f 56//42 37//3 312//22 +f 312//22 37//3 313//3 +f 314//18 315//45 316//3 +f 315//45 317//46 316//3 +f 316//3 317//46 318//47 +f 316//3 318//47 313//3 +f 313//3 318//47 319//21 +f 313//3 319//21 312//22 +f 314//18 316//3 320//96 +f 320//17 316//3 321//3 +f 320//96 321//3 322//55 +f 22//3 21//12 323//3 +f 323//3 21//73 324//13 +f 323//3 324//13 325//97 +f 325//14 326//50 323//3 +f 323//3 326//50 327//51 +f 323//3 327//52 321//3 +f 321//3 327//52 328//53 +f 321//3 328//54 322//55 +f 20//41 22//3 329//38 +f 329//38 22//3 330//3 +f 329//38 330//3 331//98 +f 331//99 330//3 332//3 +f 331//98 332//3 333//100 +f 334//27 335//31 336//3 +f 337//47 338//21 339//60 +f 339//60 338//21 340//22 +f 340//22 341//42 339//60 +f 339//60 341//42 342//1 +f 339//101 342//1 343//2 +f 335//23 344//29 336//3 +f 336//3 344//81 345//56 +f 336//3 345//56 346//57 +f 346//57 347//62 336//3 +f 336//3 347//62 348//63 +f 336//3 348//15 349//16 +f 350//3 351//67 352//24 +f 353//14 332//3 354//13 +f 354//48 332//3 355//73 +f 352//24 356//102 350//3 +f 350//3 356//25 357//30 +f 350//3 357//30 358//34 +f 359//64 360//19 350//3 +f 350//3 360//19 361//20 +f 350//3 361//60 351//67 +f 358//33 362//35 350//3 +f 350//3 362//35 363//38 +f 350//3 363//38 332//3 +f 332//3 363//38 364//11 +f 332//3 364//41 355//12 +f 353//97 365//50 332//3 +f 332//3 365//103 366//52 +f 332//3 366//52 333//100 +f 333//100 366//52 367//54 +f 333//100 367//54 368//55 +f 337//47 339//101 369//46 +f 369//46 339//20 370//104 +f 369//46 370//61 371//44 +f 371//45 370//67 372//77 +f 371//45 372//24 373//18 +f 373//18 372//24 374//25 +f 373//18 374//102 375//17 +f 375//17 374//25 376//30 +f 375//17 376//32 368//55 +f 368//55 376//30 377//105 +f 368//65 377//105 333//100 +f 378//56 379//57 380//3 +f 380//3 379//57 381//62 +f 380//3 381//62 382//15 +f 383//16 384//64 336//3 +f 343//2 334//27 339//60 +f 339//101 334//27 336//3 +f 339//20 336//3 385//19 +f 385//19 336//3 384//64 +f 78//16 72//64 71//3 +f 71//3 72//64 38//31 +f 71//3 38//23 386//3 +f 386//3 38//23 387//29 +f 302//62 19//3 310//3 +f 310//3 19//3 18//10 +f 310//3 18//10 388//106 +f 388//106 389//107 310//3 +f 310//3 389//108 247//88 +f 310//3 247//89 234//56 +f 234//56 247//88 269//64 +f 234//56 269//64 244//19 +f 17//109 19//3 390//110 +f 390//110 19//3 391//3 +f 390//110 391//3 392//111 +f 392//112 391//3 393//3 +f 392//111 393//3 394//113 +f 395//41 396//73 397//3 +f 398//43 399//44 400//3 +f 401//31 402//114 403//27 +f 403//27 402//114 404//115 +f 403//27 404//116 405//2 +f 406//30 407//34 408//3 +f 408//3 407//33 409//35 +f 408//3 409//35 397//3 +f 397//3 409//35 410//38 +f 397//3 410//38 395//41 +f 398//18 400//3 411//17 +f 401//31 412//29 402//117 +f 402//114 412//29 413//56 +f 402//114 413//86 414//57 +f 414//57 415//62 402//118 +f 402//118 415//62 416//119 +f 402//114 416//15 417//16 +f 418//67 419//24 408//3 +f 408//3 419//24 420//25 +f 408//3 420//102 406//30 +f 396//12 421//13 397//3 +f 397//3 421//13 422//14 +f 397//3 422//14 423//50 +f 399//45 424//46 400//3 +f 400//3 424//75 425//47 +f 400//3 425//47 426//21 +f 426//21 427//22 400//3 +f 400//3 427//22 428//42 +f 400//3 428//26 429//1 +f 430//64 431//19 408//3 +f 408//3 431//19 432//60 +f 408//3 432//60 418//67 +f 423//50 433//52 397//3 +f 397//3 433//51 434//53 +f 397//3 434//53 435//55 +f 417//16 430//120 402//121 +f 402//114 430//64 408//3 +f 402//114 408//3 436//122 +f 436//123 408//3 437//124 +f 438//3 439//125 440//3 +f 440//3 439//126 441//127 +f 440//3 441//127 442//128 +f 443//129 444//130 438//3 +f 438//3 444//130 445//131 +f 438//3 445//132 439//125 +f 139//67 141//79 13//3 +f 13//3 141//76 446//133 +f 13//3 446//133 11//7 +f 447//134 448//135 449//3 +f 449//3 448//136 450//137 +f 449//3 450//138 451//3 +f 451//3 450//138 452//139 +f 451//3 452//139 453//3 +f 453//3 452//139 454//140 +f 453//3 454//141 146//3 +f 146//3 454//140 455//142 +f 146//3 455//143 141//79 +f 456//25 457//30 458//144 +f 459//27 460//23 461//3 +f 461//3 460//23 462//29 +f 463//38 464//145 465//68 +f 465//35 464//145 458//146 +f 465//35 458//144 466//33 +f 466//33 458//144 457//30 +f 467//22 468//49 469//3 +f 469//3 468//26 470//1 +f 469//3 470//1 461//3 +f 461//3 470//1 471//2 +f 461//3 471//37 459//27 +f 463//38 472//11 464//145 +f 464//145 472//11 473//73 +f 464//145 473//12 474//147 +f 474//147 473//12 475//13 +f 462//29 476//56 461//3 +f 461//3 476//56 477//57 +f 461//3 477//57 478//62 +f 479//19 480//20 458//144 +f 481//18 482//44 469//3 +f 469//3 482//44 483//46 +f 480//60 484//67 458//146 +f 458//144 484//67 485//24 +f 458//146 485//24 456//25 +f 483//75 486//47 469//3 +f 469//3 486//47 487//21 +f 469//3 487//21 467//22 +f 478//62 488//119 461//3 +f 461//3 488//63 489//16 +f 461//3 489//16 490//58 +f 475//13 491//14 474//148 +f 474//147 491//14 492//103 +f 474//147 492//50 493//51 +f 447//134 449//3 494//149 +f 494//149 449//3 495//3 +f 494//150 495//3 496//151 +f 496//151 495//3 461//3 +f 496//151 461//3 458//144 +f 458//144 461//3 490//64 +f 458//144 490//64 479//19 +f 493//52 497//53 474//147 +f 474//148 497//54 498//65 +f 474//147 498//55 499//17 +f 500//152 501//153 502//3 +f 502//3 501//153 503//154 +f 502//3 503//154 504//3 +f 504//3 503//155 474//147 +f 504//3 474//148 469//3 +f 469//3 474//147 499//17 +f 469//3 499//17 481//18 +f 500//156 502//3 505//157 +f 505//158 502//3 506//3 +f 505//158 506//3 507//159 +f 507//160 506//3 508//161 +f 508//162 506//3 509//3 +f 508//161 509//3 510//163 +f 510//163 509//3 101//3 +f 510//163 101//3 108//72 +f 108//71 101//3 105//35 +f 108//69 105//35 106//38 +f 114//14 109//50 108//69 +f 108//69 109//50 10//3 +f 108//69 10//3 511//164 +f 511//164 10//3 8//6 +f 512//16 513//64 514//3 +f 515//2 516//27 517//3 +f 518//56 519//57 517//3 +f 517//3 519//57 520//62 +f 517//3 520//62 521//15 +f 516//27 522//23 517//3 +f 517//3 522//23 523//29 +f 517//3 523//29 518//86 +f 524//21 525//165 526//47 +f 526//94 525//166 527//167 +f 526//47 527//168 528//46 +f 529//169 530//18 527//167 +f 527//167 530//18 531//44 +f 527//167 531//44 528//46 +f 524//21 532//22 525//166 +f 525//166 532//84 533//26 +f 525//165 533//42 534//1 +f 513//64 535//19 514//3 +f 514//3 535//19 536//60 +f 514//3 536//60 537//67 +f 529//169 538//52 539//54 +f 539//82 540//55 529//170 +f 529//171 540//55 541//17 +f 529//169 541//17 530//18 +f 538//52 529//171 542//50 +f 542//50 529//171 543//172 +f 542//50 543//173 544//14 +f 537//61 545//24 514//3 +f 514//3 545//24 546//25 +f 514//3 546//25 547//30 +f 548//41 549//73 543//172 +f 543//173 549//73 550//13 +f 543//173 550//13 544//97 +f 547//30 551//33 514//3 +f 514//3 551//34 552//35 +f 514//3 552//35 543//172 +f 543//173 552//35 553//38 +f 543//173 553//83 548//41 +f 534//1 515//2 525//165 +f 525//165 515//2 517//3 +f 525//165 517//3 554//174 +f 554//174 517//3 555//175 +f 556//3 557//176 558//177 +f 4//178 559//179 5//3 +f 5//3 559//179 560//2 +f 5//3 560//2 561//27 +f 5//3 562//63 563//66 +f 564//20 565//3 566//19 +f 566//19 565//3 567//120 +f 561//27 568//31 5//3 +f 5//3 568//23 569//29 +f 5//3 569//29 570//56 +f 570//56 571//57 5//3 +f 5//3 571//180 572//74 +f 5//3 572//62 562//15 +f 564//20 573//61 565//3 +f 565//3 573//67 574//24 +f 565//3 574//24 575//25 +f 576//41 556//3 577//38 +f 577//38 556//3 565//3 +f 577//38 565//3 578//35 +f 575//25 579//30 565//3 +f 565//3 579//30 580//33 +f 565//3 580//34 578//35 +f 576//41 581//12 556//3 +f 556//3 581//73 582//13 +f 556//3 582//13 583//97 +f 583//14 584//50 556//3 +f 556//3 584//50 585//52 +f 556//3 585//52 586//53 +f 587//45 588//46 557//181 +f 557//181 588//46 589//47 +f 557//176 589//47 590//21 +f 590//21 591//22 557//176 +f 557//182 591//22 592//26 +f 557//176 592//42 559//183 +f 559//183 592//26 593//1 +f 559//179 593//1 560//2 +f 586//54 594//65 556//3 +f 556//3 594//55 595//17 +f 556//3 595//17 557//176 +f 557//176 595//96 596//18 +f 557//176 596//43 587//45 +f 597//184 598//3 599//185 +f 599//185 598//3 600//3 +f 275//17 243//93 260//3 +f 260//3 243//87 601//186 +f 260//3 601//187 280//3 +f 280//3 601//186 602//188 +f 280//3 602//189 600//3 +f 600//3 602//188 603//190 +f 600//3 603//191 599//185 +f 604//192 7//5 605//3 +f 605//3 7//193 9//3 +f 605//3 9//3 156//3 +f 156//3 9//3 31//3 +f 156//3 31//3 157//44 +f 157//45 31//3 30//43 +f 606//31 607//29 600//3 +f 608//30 609//33 610//3 +f 611//14 612//3 613//13 +f 613//13 612//3 614//73 +f 615//22 616//26 598//3 +f 609//33 617//35 610//3 +f 610//3 617//35 618//38 +f 610//3 618//38 612//3 +f 612//3 618//38 619//41 +f 612//3 619//41 614//12 +f 616//42 620//40 598//3 +f 598//3 620//1 621//2 +f 598//3 621//2 600//3 +f 600//3 621//2 622//27 +f 600//3 622//36 606//31 +f 600//3 623//62 624//63 +f 611//194 625//50 612//3 +f 612//3 625//50 626//51 +f 612//3 626//52 627//54 +f 628//44 629//46 598//3 +f 607//29 630//56 600//3 +f 600//3 630//86 631//57 +f 600//3 631//57 623//62 +f 632//16 633//64 610//3 +f 633//64 634//19 610//3 +f 610//3 634//19 635//60 +f 610//3 635//60 636//67 +f 636//67 637//24 610//3 +f 610//3 637//24 638//25 +f 610//3 638//25 608//32 +f 627//54 639//55 612//3 +f 612//3 639//55 640//17 +f 612//3 640//96 598//3 +f 598//3 640//17 641//18 +f 598//3 641//18 628//45 +f 629//46 642//47 598//3 +f 598//3 642//47 643//21 +f 598//3 643//21 615//84 +f 558//195 555//175 556//3 +f 556//3 555//175 517//3 +f 556//3 517//3 565//3 +f 565//3 517//3 644//3 +f 565//3 644//3 645//3 +f 645//3 644//3 646//3 +f 645//3 646//3 647//3 +f 647//3 646//3 648//3 +f 647//3 648//3 313//3 +f 521//63 512//66 517//3 +f 517//3 512//66 514//3 +f 517//3 514//3 644//3 +f 644//3 514//3 649//3 +f 644//3 649//3 646//3 +f 646//3 649//3 650//3 +f 646//3 650//3 648//3 +f 648//3 650//3 651//3 +f 543//173 604//192 514//3 +f 514//3 604//192 605//3 +f 514//3 605//3 649//3 +f 649//3 605//3 156//3 +f 649//3 156//3 650//3 +f 650//3 156//3 163//3 +f 650//3 163//3 651//3 +f 651//3 163//3 652//3 +f 653//31 654//81 655//3 +f 656//15 657//16 502//3 +f 654//29 658//56 655//3 +f 655//3 658//56 659//57 +f 655//3 659//57 660//62 +f 657//16 661//64 502//3 +f 502//3 661//64 662//59 +f 502//3 662//19 663//60 +f 664//33 502//3 665//30 +f 665//30 502//3 666//25 +f 663//20 667//67 502//3 +f 502//3 667//61 668//24 +f 502//3 668//24 666//25 +f 669//46 670//94 509//3 +f 664//33 671//35 502//3 +f 502//3 671//35 672//38 +f 502//3 672//38 506//3 +f 506//3 672//38 673//41 +f 506//3 673//41 674//73 +f 674//12 675//13 506//3 +f 506//3 675//48 676//14 +f 506//3 676//14 677//50 +f 677//50 678//52 506//3 +f 506//3 678//51 679//54 +f 506//3 679//53 680//55 +f 680//55 681//17 506//3 +f 506//3 681//17 682//43 +f 506//3 682//18 509//3 +f 509//3 682//18 683//45 +f 509//3 683//196 669//46 +f 670//47 684//21 509//3 +f 509//3 684//92 685//84 +f 509//3 685//22 686//26 +f 686//26 687//1 509//3 +f 509//3 687//1 688//2 +f 509//3 688//2 655//3 +f 655//3 688//2 689//27 +f 655//3 689//27 653//31 +f 624//63 632//16 600//3 +f 600//3 632//66 610//3 +f 600//3 610//3 280//3 +f 280//3 610//3 287//3 +f 280//3 287//3 283//65 +f 283//55 287//3 286//53 +f 690//15 321//3 691//62 +f 691//62 321//3 692//57 +f 693//2 694//27 321//3 +f 321//3 694//27 695//31 +f 651//3 696//18 697//45 +f 695//31 698//29 321//3 +f 321//3 698//29 699//56 +f 321//3 699//56 692//57 +f 690//15 700//16 321//3 +f 321//3 700//16 701//64 +f 321//3 701//64 323//3 +f 323//3 701//64 702//19 +f 323//3 702//59 703//60 +f 703//20 704//67 323//3 +f 323//3 704//61 705//24 +f 323//3 705//24 706//25 +f 706//25 707//32 323//3 +f 323//3 707//30 708//33 +f 323//3 708//34 709//35 +f 709//35 710//38 323//3 +f 323//3 710//38 711//41 +f 323//3 711//41 652//3 +f 652//3 711//41 712//12 +f 652//3 712//73 713//13 +f 713//13 714//14 652//3 +f 652//3 714//97 715//50 +f 652//3 715//50 716//52 +f 697//45 717//46 651//3 +f 651//3 717//46 718//47 +f 651//3 718//47 719//21 +f 719//21 720//84 651//3 +f 651//3 720//22 721//42 +f 651//3 721//42 722//1 +f 313//3 648//3 316//3 +f 316//3 648//3 651//3 +f 316//3 651//3 321//3 +f 321//3 651//3 722//1 +f 321//3 722//1 693//2 +f 716//52 723//54 652//3 +f 652//3 723//53 724//55 +f 652//3 724//65 651//3 +f 651//3 724//55 725//17 +f 651//3 725//96 696//18 +f 597//184 726//197 598//3 +f 598//3 726//198 4//4 +f 598//3 4//199 612//3 +f 612//3 4//199 6//3 +f 612//3 6//3 610//3 +f 610//3 6//3 727//3 +f 610//3 727//3 287//3 +f 287//3 727//3 728//3 +f 287//3 728//3 25//3 +f 25//3 728//3 295//3 +f 25//3 295//3 23//13 +f 23//13 295//3 297//73 +f 660//62 656//15 655//3 +f 655//3 656//63 502//3 +f 655//3 502//3 729//3 +f 729//3 502//3 504//3 +f 729//3 504//3 730//3 +f 730//3 504//3 469//3 +f 730//3 469//3 731//3 +f 731//3 469//3 461//3 +f 731//3 461//3 732//3 +f 732//3 461//3 495//3 +f 732//3 495//3 733//3 +f 733//3 495//3 449//3 +f 19//3 734//1 735//2 +f 736//31 737//29 391//3 +f 19//3 735//2 391//3 +f 391//3 735//2 738//27 +f 391//3 738//36 736//23 +f 737//29 739//56 391//3 +f 391//3 739//56 740//57 +f 391//3 740//57 741//62 +f 742//24 743//200 393//3 +f 393//3 743//25 744//30 +f 393//3 744//30 745//34 +f 746//41 304//3 747//38 +f 747//38 304//3 393//3 +f 747//38 393//3 748//35 +f 748//35 393//3 745//33 +f 746//41 749//12 304//3 +f 304//3 749//12 750//13 +f 304//3 750//48 751//14 +f 752//19 753//60 393//3 +f 393//3 753//60 754//67 +f 393//3 754//61 742//24 +f 755//21 756//22 19//3 +f 19//3 756//22 757//26 +f 19//3 757//26 734//40 +f 741//62 758//63 391//3 +f 391//3 758//15 759//16 +f 391//3 759//16 393//3 +f 393//3 759//16 760//64 +f 393//3 760//64 752//19 +f 751//14 761//50 304//3 +f 304//3 761//50 762//52 +f 304//3 762//52 763//54 +f 764//44 765//46 19//3 +f 19//3 765//46 766//47 +f 19//3 766//47 755//201 +f 763//54 767//55 304//3 +f 304//3 767//55 768//17 +f 304//3 768//17 19//3 +f 19//3 768//17 769//18 +f 19//3 769//18 764//44 +f 298//25 290//30 299//3 +f 299//3 290//30 292//3 +f 299//3 292//3 301//3 +f 301//3 292//3 770//3 +f 301//3 770//3 304//3 +f 304//3 770//3 771//3 +f 304//3 771//3 393//3 +f 393//3 771//3 772//3 +f 393//3 772//3 394//202 +f 394//113 772//3 400//3 +f 394//203 400//3 404//116 +f 404//116 400//3 429//1 +f 404//115 429//1 405//2 +f 168//57 169//62 163//3 +f 163//3 169//74 171//3 +f 163//3 171//3 652//3 +f 652//3 171//3 773//3 +f 652//3 773//3 323//3 +f 323//3 773//3 774//3 +f 323//3 774//3 22//3 +f 22//3 774//3 775//3 +f 22//3 775//3 330//3 +f 330//3 775//3 776//3 +f 330//3 776//3 332//3 +f 332//3 776//3 777//3 +f 332//3 777//3 350//3 +f 350//3 777//3 778//3 +f 350//3 778//3 195//3 +f 195//3 778//3 215//3 +f 195//3 215//3 193//44 +f 193//45 215//3 217//18 +f 173//64 174//19 171//3 +f 171//3 174//19 176//3 +f 171//3 176//3 773//3 +f 773//3 176//3 779//3 +f 773//3 779//3 774//3 +f 774//3 779//3 780//3 +f 774//3 780//3 775//3 +f 775//3 780//3 781//3 +f 775//3 781//3 776//3 +f 776//3 781//3 782//3 +f 776//3 782//3 777//3 +f 777//3 782//3 783//3 +f 777//3 783//3 778//3 +f 778//3 783//3 784//3 +f 778//3 784//3 215//3 +f 215//3 784//3 212//3 +f 215//3 212//3 213//53 +f 213//54 212//3 223//52 +f 453//3 785//27 786//31 +f 786//31 787//29 453//3 +f 453//3 787//29 788//56 +f 453//3 788//56 789//57 +f 790//25 791//32 451//3 +f 451//3 791//30 792//33 +f 793//16 451//3 794//63 +f 794//15 451//3 453//3 +f 794//119 453//3 795//62 +f 795//62 453//3 789//57 +f 793//66 796//64 451//3 +f 451//3 796//64 797//19 +f 451//3 797//19 798//20 +f 799//46 800//47 733//3 +f 733//3 800//47 801//21 +f 733//3 801//21 802//22 +f 798//60 803//61 451//3 +f 451//3 803//67 804//24 +f 451//3 804//24 790//25 +f 805//12 806//13 449//3 +f 449//3 806//13 807//14 +f 449//3 807//14 808//50 +f 802//22 809//26 733//3 +f 733//3 809//26 810//1 +f 733//3 810//1 453//3 +f 453//3 810//1 811//2 +f 453//3 811//2 785//27 +f 792//34 812//35 451//3 +f 451//3 812//35 813//38 +f 451//3 813//38 449//3 +f 449//3 813//38 814//41 +f 449//3 814//41 805//12 +f 808//50 815//51 449//3 +f 449//3 815//51 816//54 +f 449//3 816//54 817//55 +f 817//65 818//17 449//3 +f 449//3 818//17 819//18 +f 449//3 819//18 733//3 +f 733//3 819//18 820//44 +f 733//3 820//45 799//46 +f 563//16 567//64 5//3 +f 5//3 567//64 565//3 +f 5//3 565//3 6//3 +f 6//3 565//3 645//3 +f 6//3 645//3 727//3 +f 727//3 645//3 647//3 +f 727//3 647//3 728//3 +f 728//3 647//3 313//3 +f 728//3 313//3 295//3 +f 295//3 313//3 37//3 +f 295//3 37//3 292//3 +f 292//3 37//3 43//3 +f 292//3 43//3 770//3 +f 770//3 43//3 71//3 +f 770//3 71//3 771//3 +f 771//3 71//3 386//3 +f 771//3 386//3 772//3 +f 772//3 386//3 821//3 +f 772//3 821//3 400//3 +f 400//3 821//3 397//3 +f 400//3 397//3 411//17 +f 411//96 397//3 435//55 +f 33//60 102//67 34//3 +f 34//3 102//67 101//3 +f 34//3 101//3 176//3 +f 176//3 101//3 509//3 +f 176//3 509//3 779//3 +f 779//3 509//3 655//3 +f 779//3 655//3 780//3 +f 780//3 655//3 729//3 +f 780//3 729//3 781//3 +f 781//3 729//3 730//3 +f 781//3 730//3 782//3 +f 782//3 730//3 731//3 +f 782//3 731//3 783//3 +f 783//3 731//3 732//3 +f 783//3 732//3 784//3 +f 784//3 732//3 733//3 +f 784//3 733//3 212//3 +f 212//3 733//3 453//3 +f 212//3 453//3 124//3 +f 124//3 453//3 146//3 +f 124//3 146//3 136//50 +f 136//50 146//3 145//14 +f 387//29 378//56 386//3 +f 386//3 378//56 380//3 +f 386//3 380//3 821//3 +f 821//3 380//3 822//3 +f 821//3 822//3 397//3 +f 397//3 822//3 823//3 +f 397//3 823//3 408//3 +f 408//3 823//3 3//3 +f 382//63 383//16 380//3 +f 380//3 383//16 336//3 +f 380//3 336//3 822//3 +f 822//3 336//3 824//3 +f 822//3 824//3 823//3 +f 823//3 824//3 825//3 +f 823//3 825//3 3//3 +f 3//3 825//3 826//3 +f 207//57 192//74 199//3 +f 199//3 192//62 28//3 +f 199//3 28//3 16//3 +f 16//3 28//3 12//3 +f 16//3 12//3 14//204 +f 14//8 12//3 11//7 +f 827//64 438//3 828//16 +f 828//16 438//3 440//3 +f 828//16 440//3 829//15 +f 829//63 440//3 830//62 +f 831//27 832//31 440//3 +f 440//3 832//31 833//29 +f 834//52 835//54 826//3 +f 836//47 3//3 837//46 +f 837//46 3//3 838//45 +f 1//1 3//3 839//42 +f 437//124 408//3 442//205 +f 442//205 408//3 3//3 +f 442//128 3//3 440//3 +f 440//3 3//3 2//2 +f 440//3 2//2 831//27 +f 833//29 840//56 440//3 +f 440//3 840//56 841//57 +f 440//3 841//57 830//62 +f 827//64 842//19 438//3 +f 438//3 842//19 843//60 +f 438//3 843//60 844//67 +f 835//54 845//55 826//3 +f 826//3 845//55 846//17 +f 826//3 846//17 3//3 +f 3//3 846//17 847//18 +f 3//3 847//18 838//44 +f 844//67 848//24 438//3 +f 438//3 848//24 849//25 +f 438//3 849//25 850//32 +f 851//41 852//73 826//3 +f 826//3 852//12 853//13 +f 836//47 854//21 3//3 +f 3//3 854//92 855//22 +f 3//3 855//22 839//42 +f 853//13 856//14 826//3 +f 826//3 856//14 857//50 +f 826//3 857//50 834//51 +f 850//30 858//33 438//3 +f 438//3 858//33 859//68 +f 438//3 859//35 826//3 +f 826//3 859//68 860//38 +f 826//3 860//83 851//41 +f 349//16 359//58 336//3 +f 336//3 359//64 350//3 +f 336//3 350//3 824//3 +f 824//3 350//3 195//3 +f 824//3 195//3 825//3 +f 825//3 195//3 199//3 +f 825//3 199//3 826//3 +f 826//3 199//3 16//3 +f 826//3 16//3 438//3 +f 438//3 16//3 15//3 +f 438//3 15//3 443//129 +f 443//129 15//3 14//8 +f 861//206 862//206 863//206 +f 864//206 865//206 861//206 +f 866//207 867//206 868//208 +f 869//209 870//206 871//206 +f 872//210 873//211 874//206 +f 875//212 876//213 877//214 +f 878//215 879//206 880//216 +f 881//217 882//206 883//206 +f 884//218 885//219 886//206 +f 887//220 888//221 889//206 +f 890//222 891//223 892//206 +f 893//224 894//225 895//206 +f 896//226 897//227 898//206 +f 898//206 897//227 899//228 +f 898//206 899//228 900//229 +f 901//230 902//231 903//232 +f 903//232 902//233 904//234 +f 905//231 906//206 907//235 +f 907//235 906//206 908//236 +f 905//237 909//238 906//206 +f 906//206 909//238 910//239 +f 906//206 910//239 898//206 +f 898//206 910//239 911//240 +f 898//206 911//240 896//226 +f 912//241 913//242 914//243 +f 912//226 914//243 915//240 +f 915//240 914//244 916//245 +f 915//246 916//245 917//239 +f 917//247 916//245 918//213 +f 917//239 918//248 919//249 +f 919//249 918//213 920//250 +f 919//238 920//250 902//233 +f 902//231 920//250 921//251 +f 902//237 921//251 904//252 +f 900//229 922//253 898//206 +f 898//206 922//253 923//224 +f 898//206 923//254 924//255 +f 925//256 926//257 912//258 +f 912//226 926//257 927//259 +f 912//226 927//260 928//261 +f 928//262 929//263 912//258 +f 912//258 929//263 930//264 +f 912//226 930//264 913//265 +f 931//206 932//222 906//206 +f 906//206 932//266 933//223 +f 906//206 933//223 908//236 +f 901//230 934//267 902//231 +f 902//233 934//267 935//268 +f 902//233 935//269 936//270 +f 937//271 938//272 931//206 +f 931//206 938//272 939//273 +f 931//206 939//274 932//222 +f 940//275 941//271 942//206 +f 942//206 941//271 943//272 +f 942//206 943//272 895//206 +f 895//206 943//272 944//273 +f 895//206 944//273 945//266 +f 945//222 946//223 895//206 +f 895//206 946//223 947//236 +f 895//206 947//236 948//235 +f 948//235 949//237 895//206 +f 895//206 949//231 950//238 +f 895//206 950//238 951//239 +f 882//206 952//240 953//258 +f 953//226 954//227 882//206 +f 882//206 954//227 955//228 +f 882//206 955//228 956//229 +f 956//229 957//253 882//206 +f 882//206 957//253 958//224 +f 882//206 958//224 883//206 +f 883//206 958//224 959//255 +f 883//206 959//255 960//276 +f 961//261 962//263 878//277 +f 960//276 963//278 883//206 +f 883//206 963//257 964//260 +f 883//206 964//260 961//261 +f 962//263 965//264 878//279 +f 878//279 965//264 966//265 +f 878//215 966//265 967//244 +f 968//280 969//281 942//206 +f 942//206 969//281 970//269 +f 942//206 970//268 940//275 +f 967//282 971//245 878//215 +f 878//277 971//245 972//213 +f 878//277 972//213 879//206 +f 879//206 972//283 973//284 +f 879//206 973//284 974//251 +f 974//251 975//234 879//206 +f 879//206 975//234 976//232 +f 879//206 976//232 968//230 +f 977//206 978//228 979//229 +f 979//229 980//253 977//206 +f 977//206 980//285 981//254 +f 977//206 981//254 982//206 +f 982//206 981//224 983//225 +f 982//206 983//255 984//276 +f 985//270 986//271 870//206 +f 870//206 986//271 987//286 +f 870//206 987//286 871//206 +f 871//206 987//272 988//273 +f 871//206 988//274 989//222 +f 989//266 990//223 871//206 +f 871//206 990//223 991//236 +f 871//206 991//236 992//235 +f 992//235 993//233 871//206 +f 871//206 993//231 994//238 +f 871//206 994//238 977//206 +f 977//206 994//238 995//239 +f 977//206 995//239 996//240 +f 996//240 997//258 977//206 +f 977//206 997//241 998//227 +f 977//206 998//227 978//228 +f 984//276 999//257 982//206 +f 982//206 999//257 1000//260 +f 982//206 1000//259 1001//261 +f 1002//263 1003//264 1004//206 +f 1005//230 1006//281 870//206 +f 870//206 1006//281 1007//268 +f 870//206 1007//268 985//275 +f 1008//213 1009//250 1010//287 +f 1003//264 1011//265 1004//206 +f 1004//206 1011//265 1012//243 +f 1004//206 1012//243 1013//245 +f 1009//250 1014//288 1010//289 +f 1010//290 1014//291 1015//234 +f 1010//289 1015//234 1016//232 +f 893//224 895//206 1017//253 +f 1018//206 1019//272 1020//274 +f 1021//222 1022//223 863//206 +f 1023//233 1024//238 863//206 +f 1021//222 863//206 1020//274 +f 1025//229 1017//285 1026//206 +f 1026//206 1017//253 895//206 +f 1026//206 895//206 882//206 +f 882//206 895//206 951//239 +f 882//206 951//239 952//240 +f 1027//239 1028//240 1026//206 +f 1026//206 1028//246 1029//258 +f 1022//223 1030//236 863//206 +f 863//206 1030//236 1031//292 +f 863//206 1031//235 1023//231 +f 1029//258 1032//227 1026//206 +f 1026//206 1032//227 1033//228 +f 1026//206 1033//228 1025//229 +f 1034//281 1035//269 1036//206 +f 1037//261 1038//263 942//206 +f 1038//263 1039//264 942//206 +f 942//206 1039//264 1040//265 +f 942//206 1040//265 1041//243 +f 1035//269 1042//275 1018//206 +f 1018//206 1042//275 1043//271 +f 1018//206 1043//271 1019//272 +f 894//255 1044//276 895//206 +f 895//206 1044//276 1045//257 +f 895//206 1045//278 942//206 +f 942//206 1045//257 1046//259 +f 942//206 1046//260 1037//262 +f 1041//243 1047//245 942//206 +f 942//206 1047//245 1048//213 +f 942//206 1048//213 1036//206 +f 1048//248 1049//250 1036//206 +f 1036//206 1049//250 1050//291 +f 1036//206 1050//288 1051//252 +f 1051//234 1052//232 1036//206 +f 1036//206 1052//232 1053//230 +f 1036//206 1053//230 1034//281 +f 1054//271 1055//272 977//206 +f 977//206 1055//272 1056//274 +f 1057//266 1058//223 1059//206 +f 1060//206 1061//229 1062//253 +f 1057//222 1059//206 1056//274 +f 1058//223 1063//236 1059//206 +f 1059//206 1063//236 1064//292 +f 1059//206 1064//235 1065//231 +f 1065//231 1066//249 1059//206 +f 1059//206 1066//238 1067//239 +f 1059//206 1067//239 1060//206 +f 1060//206 1067//239 1068//240 +f 1060//206 1068//240 1069//226 +f 1069//258 1070//227 1060//206 +f 1060//206 1070//293 1071//228 +f 1060//206 1071//228 1061//229 +f 1072//224 1073//255 1074//206 +f 1074//206 1073//255 1075//276 +f 1074//206 1075//276 1076//257 +f 1077//267 1078//268 982//206 +f 1079//264 1080//265 1081//206 +f 1081//206 1080//242 1082//282 +f 982//206 1078//269 977//206 +f 977//206 1078//294 1083//275 +f 977//206 1083//270 1054//271 +f 1084//259 1085//261 1081//206 +f 1081//206 1085//261 1086//263 +f 1081//206 1086//263 1079//264 +f 1082//244 1087//245 1081//206 +f 1081//206 1087//245 1088//283 +f 1081//206 1088//213 982//206 +f 1088//213 1089//250 982//206 +f 982//206 1089//250 1090//251 +f 982//206 1090//251 1091//234 +f 1091//234 1092//232 982//206 +f 982//206 1092//232 1093//230 +f 982//206 1093//230 1077//281 +f 1094//228 1095//229 1096//206 +f 1097//295 1098//236 1099//296 +f 1100//227 1101//228 1102//297 +f 1103//236 1104//251 1105//252 +f 1106//226 1107//227 1108//244 +f 1103//298 1109//235 1104//291 +f 1104//291 1109//235 1110//233 +f 1104//251 1110//231 1111//249 +f 1106//258 1108//243 1112//246 +f 1112//240 1108//243 1113//245 +f 1112//240 1113//212 1114//239 +f 1114//239 1113//245 1115//213 +f 1114//239 1115//213 1111//238 +f 1111//238 1115//213 1116//284 +f 1111//238 1116//250 1104//251 +f 1105//234 1117//232 1103//298 +f 1103//298 1117//232 1118//230 +f 1103//236 1118//230 1119//281 +f 1120//238 1121//299 1122//233 +f 1122//237 1121//300 1099//301 +f 1122//233 1099//301 1123//235 +f 1123//235 1099//296 1098//236 +f 1120//238 1124//239 1121//300 +f 1121//300 1124//239 1125//240 +f 1121//300 1125//240 1102//302 +f 1102//302 1125//246 1126//258 +f 1102//302 1126//226 1100//227 +f 1101//228 1127//303 1102//297 +f 1102//297 1127//229 1128//253 +f 1102//302 1128//253 1129//224 +f 1107//227 1094//304 1108//244 +f 1108//243 1094//228 1096//206 +f 1108//244 1096//206 1130//265 +f 1130//265 1096//206 1131//264 +f 1119//281 1132//268 1103//236 +f 1103//298 1132//269 1133//275 +f 1103//236 1133//275 1134//271 +f 1135//272 1136//273 1099//301 +f 1099//301 1136//274 1137//266 +f 1099//296 1137//222 1097//223 +f 1138//259 1139//261 1096//206 +f 1096//206 1139//261 1140//263 +f 1096//206 1140//263 1131//264 +f 1129//254 1141//255 1102//302 +f 1102//297 1141//255 1142//276 +f 1102//297 1142//276 1096//206 +f 1096//206 1142//276 1143//257 +f 1096//206 1143//257 1138//259 +f 1144//266 1145//223 1146//206 +f 1146//206 1145//223 1103//236 +f 1146//206 1103//236 1099//296 +f 1099//301 1103//298 1134//271 +f 1099//296 1134//271 1135//272 +f 1144//222 1146//206 1147//273 +f 1147//274 1146//206 1148//206 +f 1147//274 1148//206 1149//272 +f 1150//206 1151//270 1148//206 +f 1148//206 1151//275 1152//271 +f 1148//206 1152//271 1149//286 +f 1153//206 1154//206 1155//232 +f 1155//232 1156//230 1153//206 +f 1153//206 1156//230 1157//267 +f 1153//206 1157//267 1150//206 +f 1150//206 1157//281 1158//268 +f 1150//206 1158//269 1151//275 +f 1159//305 1160//265 1161//206 +f 1160//265 1162//244 1161//206 +f 1161//206 1162//243 1163//245 +f 1161//206 1163//245 1164//206 +f 1164//206 1163//245 1165//213 +f 1165//213 1166//250 1164//206 +f 1164//206 1166//250 1167//251 +f 1164//206 1167//251 1168//234 +f 1169//206 1170//262 1171//263 +f 1172//257 1173//260 1174//206 +f 1175//253 1176//224 1177//206 +f 1177//206 1176//224 1178//255 +f 1172//257 1174//206 1179//276 +f 936//275 937//306 902//231 +f 902//233 937//271 931//206 +f 902//231 931//206 1180//235 +f 1180//235 931//206 1181//206 +f 1180//235 1181//206 1182//236 +f 1182//236 1181//206 891//223 +f 1183//271 1184//206 1185//275 +f 1185//275 1184//206 1186//268 +f 1183//271 1187//272 892//206 +f 892//206 1187//272 1188//273 +f 892//206 1188//274 890//222 +f 1189//206 1190//264 1191//265 +f 1192//275 1193//271 1184//206 +f 1191//242 1194//244 1189//206 +f 1189//206 1194//243 1195//245 +f 1189//206 1195//245 1196//206 +f 1196//206 1195//245 1197//213 +f 1196//206 1197//213 1198//250 +f 1196//206 1199//307 1200//230 +f 1193//306 1201//272 1184//206 +f 1184//206 1201//272 1202//274 +f 1184//206 1202//273 1203//222 +f 1203//222 1204//223 1184//206 +f 1184//206 1204//223 1205//236 +f 1184//206 1205//236 1206//292 +f 1207//308 1208//261 1189//206 +f 1189//206 1208//261 1209//309 +f 1189//206 1209//263 1190//310 +f 1198//250 1210//251 1196//206 +f 1196//206 1210//291 1211//234 +f 1196//206 1211//234 1199//232 +f 1200//230 1212//281 1196//206 +f 1196//206 1212//281 1213//269 +f 1196//206 1213//268 1192//275 +f 1214//239 1186//269 1215//238 +f 1215//238 1186//294 1184//206 +f 1215//238 1184//206 1216//233 +f 1216//231 1184//206 1206//235 +f 1214//239 1217//240 1186//294 +f 1186//269 1217//240 1218//258 +f 1186//269 1218//258 1219//227 +f 1219//227 1220//228 1186//269 +f 1186//269 1220//228 1221//229 +f 1186//294 1221//229 1222//281 +f 1222//281 1221//229 1223//253 +f 1222//281 1223//285 1224//230 +f 1224//311 1223//253 1225//254 +f 1224//230 1225//224 1226//232 +f 1226//312 1225//224 1227//255 +f 1226//307 1227//255 1228//276 +f 1207//259 1229//313 1230//257 +f 1230//257 1229//313 1231//314 +f 1230//257 1231//314 1228//276 +f 1228//276 1231//314 1232//234 +f 1228//276 1232//234 1226//232 +f 1207//259 1189//206 1229//313 +f 1229//313 1189//206 1233//206 +f 1229//315 1233//206 1234//316 +f 1235//206 1236//245 1233//206 +f 1233//206 1236//245 1237//213 +f 1233//206 1237//213 1234//316 +f 865//206 1238//259 1239//206 +f 1239//206 1238//260 1240//261 +f 1239//206 1240//262 1241//263 +f 1241//263 1242//264 1239//206 +f 1239//206 1242//310 1243//265 +f 1239//206 1243//242 1235//206 +f 1235//206 1243//265 1244//244 +f 1235//206 1244//243 1236//212 +f 1245//228 1246//229 864//206 +f 864//206 1246//229 1247//253 +f 864//206 1247//253 1248//224 +f 1248//224 1249//255 864//206 +f 864//206 1249//255 1250//317 +f 864//206 1250//276 865//206 +f 865//206 1250//317 1251//257 +f 865//206 1251//257 1238//259 +f 924//225 925//276 898//206 +f 898//206 925//276 912//226 +f 898//206 912//258 1252//206 +f 1252//206 912//258 1253//227 +f 1095//229 1175//285 1096//206 +f 1096//206 1175//253 1177//206 +f 1096//206 1177//206 1102//302 +f 1102//302 1177//206 1254//318 +f 1255//206 1256//319 1257//320 +f 1258//291 1259//206 1260//250 +f 1260//250 1259//206 1261//213 +f 1262//286 1263//273 1264//206 +f 1265//228 1266//229 1267//321 +f 1262//272 1264//206 1268//271 +f 1269//322 1264//206 1270//323 +f 1270//323 1264//206 1271//238 +f 1265//228 1267//321 1272//227 +f 1258//251 1273//234 1259//206 +f 1259//206 1273//234 1274//232 +f 1259//206 1274//232 1275//230 +f 1271//238 1276//239 1270//324 +f 1270//323 1276//239 1277//240 +f 1270//324 1277//240 1267//321 +f 1267//321 1277//240 1278//258 +f 1267//325 1278//226 1272//227 +f 1266//229 1279//253 1267//325 +f 1267//325 1279//253 1280//224 +f 1267//321 1280//224 1281//225 +f 1282//259 889//206 1283//278 +f 1283//257 889//206 1284//276 +f 1282//260 1285//261 889//206 +f 889//206 1285//261 1286//263 +f 889//206 1286//263 1287//264 +f 1287//310 1288//265 889//206 +f 889//206 1288//265 1289//244 +f 889//206 1289//243 1290//245 +f 1275//230 1291//281 1259//206 +f 1259//206 1291//267 1292//268 +f 1259//206 1292//268 1293//275 +f 1263//274 1294//222 1264//206 +f 1264//206 1294//266 1295//326 +f 1264//206 1295//223 1296//236 +f 1296//236 1297//235 1264//206 +f 1264//206 1297//235 1298//231 +f 1264//206 1298//233 1271//238 +f 1281//255 1284//317 1267//327 +f 1267//321 1284//276 889//206 +f 1267//321 889//206 1299//328 +f 1299//329 889//206 888//221 +f 1300//206 1301//232 1302//230 +f 1302//230 1303//267 1300//206 +f 1300//206 1303//281 1304//269 +f 1300//206 1304//269 1305//275 +f 1306//271 1307//272 1308//206 +f 1308//206 1307//286 1309//273 +f 1308//206 1309//274 1310//222 +f 1310//222 1311//223 1308//206 +f 1308//206 1311//223 1312//236 +f 1308//206 1312//298 1313//235 +f 1314//330 1315//228 1316//331 +f 1316//332 1315//228 1317//229 +f 1317//229 1318//253 1316//332 +f 1316//331 1318//253 1319//254 +f 1316//332 1319//254 1320//333 +f 1319//254 1321//255 1320//334 +f 1320//334 1321//255 1322//276 +f 1320//333 1322//276 1323//257 +f 1324//335 1325//310 1326//265 +f 1324//336 1327//213 1300//206 +f 1300//206 1327//283 1328//250 +f 1328//250 1329//291 1300//206 +f 1300//206 1329//251 1330//234 +f 1300//206 1330//234 1301//232 +f 1323//257 1331//308 1320//337 +f 1320//334 1331//259 1332//261 +f 1320//333 1332//261 1324//335 +f 1324//335 1332//261 1333//263 +f 1324//335 1333//263 1325//264 +f 1326//265 1334//244 1324//335 +f 1324//336 1334//244 1335//245 +f 1324//335 1335//245 1327//248 +f 1336//240 1337//258 1314//330 +f 1314//338 1337//226 1338//293 +f 1314//338 1338//227 1315//228 +f 1313//235 1339//231 1308//206 +f 1308//206 1339//231 1340//238 +f 1308//206 1340//238 1314//330 +f 1314//330 1340//238 1341//239 +f 1314//330 1341//239 1336//240 +f 961//261 878//215 883//206 +f 883//206 878//277 1342//339 +f 883//206 1342//339 881//217 +f 880//340 879//206 1343//341 +f 1343//342 879//206 1344//206 +f 1343//341 1344//206 1345//343 +f 1345//343 1344//206 1346//206 +f 1345//343 1346//206 1347//344 +f 1347//344 1346//206 1348//206 +f 1347//345 1348//206 1349//346 +f 1350//206 1351//347 1352//206 +f 1352//206 1351//348 1353//349 +f 1352//206 1353//350 1348//206 +f 1348//206 1353//350 1354//351 +f 1348//206 1354//351 1349//352 +f 1355//251 1356//234 1357//353 +f 1358//235 1359//231 1360//206 +f 1359//231 1361//238 1360//206 +f 1360//206 1361//238 1362//354 +f 1360//206 1362//239 1350//206 +f 877//214 876//213 1357//353 +f 1357//355 876//213 1363//250 +f 1357//353 1363//250 1355//251 +f 1362//239 1364//240 1350//206 +f 1350//206 1364//240 1365//226 +f 1350//206 1365//241 1366//227 +f 1351//348 1367//242 877//214 +f 877//214 1367//242 1368//243 +f 877//214 1368//244 875//212 +f 1356//234 1369//232 1357//353 +f 1357//355 1369//232 1370//230 +f 1357//353 1370//230 1371//281 +f 1372//222 1373//223 1360//206 +f 1360//206 1373//223 1374//236 +f 1360//206 1374//236 1358//235 +f 1366//227 1375//228 1350//206 +f 1350//206 1375//228 1376//229 +f 1350//206 1376//229 1377//285 +f 1378//278 1379//259 1351//347 +f 1351//348 1379//260 1380//261 +f 1380//262 1381//263 1351//348 +f 1351//348 1381//309 1382//264 +f 1351//347 1382//264 1367//265 +f 1371//281 1383//269 1357//355 +f 1357//355 1383//268 1384//275 +f 1357//353 1384//275 1385//271 +f 1385//306 1386//272 1360//206 +f 1360//206 1386//272 1387//273 +f 1360//206 1387//273 1372//222 +f 1377//253 1388//254 1350//206 +f 1350//206 1388//254 1389//255 +f 1350//206 1389//255 1351//347 +f 1351//348 1389//255 1390//276 +f 1351//348 1390//276 1378//257 +f 1385//271 1360//206 1357//353 +f 1357//353 1360//206 1391//206 +f 1357//353 1391//206 1392//356 +f 874//206 873//357 1391//206 +f 1391//206 873//357 1393//358 +f 1391//206 1393//359 1392//356 +f 872//360 874//206 1394//361 +f 1394//362 874//206 1395//206 +f 1394//362 1395//206 1396//363 +f 1396//364 1395//206 1397//365 +f 1397//366 1395//206 1398//206 +f 1397//365 1398//206 1399//367 +f 1399//367 1398//206 1004//206 +f 1399//367 1004//206 1010//290 +f 1010//289 1004//206 1013//245 +f 1010//287 1013//245 1008//213 +f 1016//232 1005//311 1010//287 +f 1010//287 1005//230 870//206 +f 1010//287 870//206 1400//368 +f 1400//368 870//206 869//209 +f 867//206 866//207 1401//206 +f 1402//206 1403//369 1404//370 +f 1405//371 1406//372 1407//206 +f 1407//206 1406//373 1408//374 +f 1407//206 1408//374 1409//375 +f 1410//250 1407//206 1411//213 +f 1411//213 1407//206 1412//206 +f 1411//213 1412//206 1413//245 +f 1410//250 1414//251 1407//206 +f 1407//206 1414//291 1415//234 +f 1407//206 1415//234 1416//307 +f 1412//206 1417//263 1418//264 +f 1416//232 1419//230 1407//206 +f 1407//206 1419//230 1420//281 +f 1407//206 1420//281 1421//269 +f 1422//376 1423//222 1405//377 +f 1405//377 1423//222 1424//223 +f 1405//371 1424//223 1425//298 +f 1425//236 1426//235 1405//371 +f 1405//378 1426//235 1427//233 +f 1405//371 1427//231 1428//379 +f 1428//379 1427//233 1429//238 +f 1430//239 1431//240 1432//206 +f 1432//206 1431//240 1433//226 +f 1432//206 1433//258 1434//227 +f 1434//227 1435//228 1432//206 +f 1432//206 1435//228 1436//229 +f 1432//206 1436//229 1437//285 +f 1438//257 1439//260 1412//206 +f 1412//206 1439//260 1440//262 +f 1412//206 1440//261 1417//263 +f 1418//264 1441//265 1412//206 +f 1412//206 1441//265 1442//243 +f 1412//206 1442//244 1413//245 +f 1421//269 1443//275 1407//206 +f 1407//206 1443//275 1444//271 +f 1407//206 1444//271 1405//371 +f 1405//371 1444//380 1445//272 +f 1405//371 1445//272 1422//274 +f 1437//253 1446//224 1432//206 +f 1432//206 1446//254 1447//225 +f 1432//206 1447//255 1448//276 +f 1449//206 1450//206 1451//381 +f 1451//382 1450//206 1452//383 +f 1148//206 1453//384 1450//206 +f 1450//206 1453//384 1454//385 +f 1450//206 1454//385 1452//386 +f 1099//301 1455//387 1146//206 +f 1146//206 1455//388 1456//389 +f 1146//206 1456//389 1148//206 +f 1148//206 1456//390 1457//391 +f 1148//206 1457//392 1453//384 +f 1458//281 1459//269 1402//206 +f 1402//206 1459//269 1460//275 +f 1460//275 1461//271 1402//206 +f 1402//206 1461//271 1462//206 +f 1402//206 1462//206 1403//393 +f 1403//393 1462//206 1463//394 +f 1464//206 1465//276 1466//257 +f 1402//206 1467//251 1468//234 +f 1461//271 1469//272 1462//206 +f 1462//206 1469//272 1470//274 +f 1462//206 1470//273 1471//222 +f 1466//257 1472//259 1464//206 +f 1464//206 1472//259 1473//261 +f 1464//206 1473//262 1474//263 +f 1468//252 1475//232 1402//206 +f 1402//206 1475//232 1476//230 +f 1402//206 1476//230 1458//281 +f 1477//244 1478//245 1464//206 +f 1464//206 1478//245 1479//248 +f 1464//206 1479//213 1402//206 +f 1402//206 1479//213 1480//250 +f 1402//206 1480//284 1467//251 +f 1481//253 1482//224 1483//206 +f 1483//206 1482//254 1484//255 +f 1474//263 1485//264 1464//206 +f 1464//206 1485//264 1486//265 +f 1464//206 1486//265 1477//243 +f 1471//222 1487//223 1462//206 +f 1462//206 1487//223 1488//236 +f 1462//206 1488//236 1489//235 +f 1490//240 1491//258 1483//206 +f 1483//206 1491//258 1492//227 +f 1489//235 1493//233 1462//206 +f 1462//206 1493//233 1494//238 +f 1462//206 1494//238 1483//206 +f 1483//206 1494//249 1495//239 +f 1483//206 1495//239 1490//240 +f 1492//227 1496//395 1483//206 +f 1483//206 1496//228 1497//229 +f 1483//206 1497//229 1481//253 +f 1056//273 1059//206 977//206 +f 977//206 1059//206 1401//206 +f 977//206 1401//206 871//206 +f 871//206 1401//206 866//396 +f 871//206 866//207 869//209 +f 1498//250 1449//206 1499//213 +f 1499//213 1449//206 1150//206 +f 1499//213 1150//206 1500//245 +f 1148//206 1501//226 1502//227 +f 1150//206 1503//263 1504//264 +f 1498//250 1505//251 1449//206 +f 1449//206 1505//291 1506//234 +f 1449//206 1506//234 1507//232 +f 1502//227 1508//228 1148//206 +f 1148//206 1508//395 1509//229 +f 1148//206 1509//229 1510//253 +f 1504//264 1511//242 1150//206 +f 1150//206 1511//265 1512//243 +f 1150//206 1512//243 1500//245 +f 1507//312 1513//230 1449//206 +f 1449//206 1513//230 1514//267 +f 1449//206 1514//281 1515//269 +f 1516//273 1517//222 1450//206 +f 1450//206 1517//222 1518//223 +f 1518//223 1519//236 1450//206 +f 1450//206 1519//236 1520//235 +f 1450//206 1520//235 1521//233 +f 1521//231 1522//249 1450//206 +f 1450//206 1522//238 1523//239 +f 1450//206 1523//239 1148//206 +f 1148//206 1523//239 1524//240 +f 1148//206 1524//246 1501//226 +f 1510//253 1525//254 1148//206 +f 1148//206 1525//254 1526//255 +f 1148//206 1526//225 1150//206 +f 1150//206 1526//255 1527//276 +f 1150//206 1527//276 1528//257 +f 1528//257 1529//259 1150//206 +f 1150//206 1529//259 1530//261 +f 1150//206 1530//261 1503//263 +f 1515//269 1531//275 1449//206 +f 1449//206 1531//275 1532//271 +f 1449//206 1532//306 1450//206 +f 1450//206 1532//271 1533//272 +f 1450//206 1533//272 1516//274 +f 891//223 1181//206 892//206 +f 892//206 1181//206 1534//206 +f 892//206 1534//206 1535//206 +f 1535//206 1534//206 1412//206 +f 1535//206 1412//206 1536//206 +f 1536//206 1412//206 1407//206 +f 1536//206 1407//206 1483//206 +f 1483//206 1407//206 1409//375 +f 1483//206 1409//397 1462//206 +f 1462//206 1409//397 1537//398 +f 1462//206 1537//398 1463//394 +f 1183//306 892//206 1184//206 +f 1184//206 892//206 1535//206 +f 1184//206 1535//206 1538//206 +f 1538//206 1535//206 1536//206 +f 1538//206 1536//206 1539//206 +f 1539//206 1536//206 1483//206 +f 1539//206 1483//206 1464//206 +f 1464//206 1483//206 1484//255 +f 1464//206 1484//255 1465//276 +f 1192//270 1184//206 1196//206 +f 1196//206 1184//206 1538//206 +f 1196//206 1538//206 1060//206 +f 1060//206 1538//206 1539//206 +f 1060//206 1539//206 1059//206 +f 1059//206 1539//206 1464//206 +f 1059//206 1464//206 1401//206 +f 1401//206 1464//206 1402//206 +f 1401//206 1402//206 867//206 +f 867//206 1402//206 1404//370 +f 867//206 1404//370 868//208 +f 1540//240 1541//206 1542//239 +f 1542//239 1541//206 1398//206 +f 1540//240 1543//226 1541//206 +f 1541//206 1543//226 1544//227 +f 1541//206 1544//227 1545//228 +f 1545//228 1546//229 1541//206 +f 1541//206 1546//229 1547//253 +f 1541//206 1547//253 1548//224 +f 1549//263 1550//264 874//206 +f 874//206 1550//264 1551//265 +f 874//206 1552//213 1395//206 +f 1395//206 1552//213 1553//250 +f 1395//206 1553//250 1554//291 +f 1554//251 1555//234 1395//206 +f 1395//206 1555//252 1556//232 +f 1395//206 1556//232 1557//230 +f 1557//230 1558//281 1395//206 +f 1395//206 1558//267 1559//269 +f 1395//206 1559//268 1560//275 +f 1561//222 1562//223 1398//206 +f 1398//206 1562//223 1563//236 +f 1398//206 1563//236 1564//235 +f 1564//235 1565//233 1398//206 +f 1398//206 1565//233 1566//238 +f 1398//206 1566//238 1542//239 +f 1548//224 1567//255 874//206 +f 874//206 1567//255 1568//276 +f 874//206 1568//276 1569//278 +f 1551//265 1570//243 874//206 +f 874//206 1570//243 1571//245 +f 874//206 1571//245 1552//213 +f 1569//257 1572//259 874//206 +f 874//206 1572//259 1573//262 +f 874//206 1573//262 1549//263 +f 1560//275 1574//271 1395//206 +f 1395//206 1574//271 1575//286 +f 1395//206 1575//272 1398//206 +f 1398//206 1575//272 1576//274 +f 1398//206 1576//376 1561//222 +f 1429//238 1430//239 1428//399 +f 1428//399 1430//239 1432//206 +f 1428//399 1432//206 1451//400 +f 1451//382 1432//206 1577//206 +f 1451//381 1577//206 1449//206 +f 1449//206 1577//206 1578//206 +f 1449//206 1578//206 1150//206 +f 1150//206 1578//206 1579//206 +f 1150//206 1579//206 1153//206 +f 1153//206 1579//206 1164//206 +f 1153//206 1164//206 1154//206 +f 1154//206 1164//206 1168//234 +f 1154//206 1168//234 1155//232 +f 1252//206 1161//206 898//206 +f 898//206 1161//206 1164//206 +f 898//206 1164//206 906//206 +f 906//206 1164//206 1579//206 +f 906//206 1579//206 931//206 +f 931//206 1579//206 1578//206 +f 931//206 1578//206 1181//206 +f 1181//206 1578//206 1577//206 +f 1181//206 1577//206 1534//206 +f 1534//206 1577//206 1432//206 +f 1534//206 1432//206 1412//206 +f 1412//206 1432//206 1448//276 +f 1412//206 1448//317 1438//257 +f 1239//206 1580//213 1581//250 +f 861//206 1582//293 1583//228 +f 1581//250 1584//291 1239//206 +f 1239//206 1584//251 1585//234 +f 1239//206 1585//252 1586//232 +f 1583//228 1587//229 861//206 +f 861//206 1587//229 1588//253 +f 861//206 1588//253 1589//224 +f 1590//259 1591//261 862//206 +f 862//206 1591//261 1592//263 +f 862//206 1592//263 1593//310 +f 1593//264 1594//265 862//206 +f 862//206 1594//265 1595//244 +f 862//206 1595//244 1239//206 +f 1239//206 1595//244 1596//245 +f 1239//206 1596//245 1580//213 +f 1586//232 1597//230 1239//206 +f 1239//206 1597//230 1598//267 +f 1239//206 1598//281 1599//268 +f 1600//274 1601//222 865//206 +f 865//206 1601//222 1602//223 +f 865//206 1602//223 1603//236 +f 1589//224 1604//255 861//206 +f 861//206 1604//255 1605//317 +f 861//206 1605//276 862//206 +f 862//206 1605//276 1606//257 +f 862//206 1606//257 1590//260 +f 1599//269 1607//270 1239//206 +f 1239//206 1607//275 1608//271 +f 1239//206 1608//271 865//206 +f 865//206 1608//271 1609//272 +f 865//206 1609//272 1600//274 +f 1603//236 1610//235 865//206 +f 865//206 1610//235 1611//233 +f 865//206 1611//233 1612//238 +f 1612//238 1613//239 865//206 +f 865//206 1613//239 1614//240 +f 865//206 1614//240 861//206 +f 861//206 1614//240 1615//258 +f 861//206 1615//258 1582//227 +f 1548//254 874//206 1541//206 +f 1541//206 874//206 1391//206 +f 1541//206 1391//206 1616//206 +f 1616//206 1391//206 1360//206 +f 1616//206 1360//206 1617//206 +f 1617//206 1360//206 1350//206 +f 1617//206 1350//206 1618//206 +f 1618//206 1350//206 1352//206 +f 1618//206 1352//206 1619//206 +f 1619//206 1352//206 1348//206 +f 1619//206 1348//206 1620//206 +f 1621//250 1622//251 1623//206 +f 1621//250 1623//206 1624//213 +f 1625//206 1626//226 1627//227 +f 1628//271 1629//272 1255//206 +f 1630//265 1631//244 1632//206 +f 1632//206 1631//243 1633//245 +f 1622//251 1634//234 1623//206 +f 1623//206 1634//252 1635//232 +f 1623//206 1635//232 1636//230 +f 1636//230 1637//281 1623//206 +f 1623//206 1637//281 1638//269 +f 1623//206 1638//269 1639//275 +f 1640//233 1641//249 1255//206 +f 1255//206 1641//238 1642//239 +f 1255//206 1642//239 1625//206 +f 1625//206 1642//239 1643//240 +f 1625//206 1643//246 1626//258 +f 1627//293 1644//228 1625//206 +f 1625//206 1644//228 1645//229 +f 1625//206 1645//229 1646//253 +f 1639//275 1628//271 1623//206 +f 1623//206 1628//271 1255//206 +f 1623//206 1255//206 1177//206 +f 1177//206 1255//206 1257//401 +f 1177//206 1257//320 1254//402 +f 1629//272 1647//273 1255//206 +f 1255//206 1647//273 1648//222 +f 1255//206 1648//222 1649//223 +f 1646//253 1650//254 1625//206 +f 1625//206 1650//224 1651//255 +f 1625//206 1651//255 1632//206 +f 1632//206 1651//255 1652//276 +f 1652//276 1653//257 1632//206 +f 1632//206 1653//257 1654//259 +f 1632//206 1654//259 1655//261 +f 1655//262 1656//263 1632//206 +f 1632//206 1656//263 1657//305 +f 1632//206 1657//264 1630//265 +f 1649//223 1658//298 1255//206 +f 1255//206 1658//236 1659//235 +f 1255//206 1659//235 1640//233 +f 1633//245 1624//213 1632//206 +f 1632//206 1624//213 1623//206 +f 1632//206 1623//206 1660//206 +f 1253//227 1245//228 1252//206 +f 1252//206 1245//395 864//206 +f 1252//206 864//206 1661//206 +f 1661//206 864//206 861//206 +f 1661//206 861//206 1662//206 +f 1662//206 861//206 863//206 +f 1662//206 863//206 1026//206 +f 1026//206 863//206 1024//249 +f 1026//206 1024//238 1027//239 +f 1020//273 863//206 1018//206 +f 1018//206 863//206 862//206 +f 1018//206 862//206 1663//206 +f 1663//206 862//206 1239//206 +f 1663//206 1239//206 1664//206 +f 1664//206 1239//206 1235//206 +f 1664//206 1235//206 1665//206 +f 1665//206 1235//206 1233//206 +f 1665//206 1233//206 1666//206 +f 1666//206 1233//206 1189//206 +f 1666//206 1189//206 1667//206 +f 1667//206 1189//206 1196//206 +f 1667//206 1196//206 1668//206 +f 1668//206 1196//206 1060//206 +f 1668//206 1060//206 1074//206 +f 1074//206 1060//206 1062//285 +f 1074//206 1062//253 1072//254 +f 1035//268 1018//206 1036//206 +f 1036//206 1018//206 1663//206 +f 1036//206 1663//206 1669//206 +f 1669//206 1663//206 1664//206 +f 1669//206 1664//206 1670//206 +f 1670//206 1664//206 1665//206 +f 1670//206 1665//206 1671//206 +f 1671//206 1665//206 1666//206 +f 1671//206 1666//206 1672//206 +f 1672//206 1666//206 1667//206 +f 1672//206 1667//206 1673//206 +f 1673//206 1667//206 1668//206 +f 1673//206 1668//206 1674//206 +f 1674//206 1668//206 1074//206 +f 1674//206 1074//206 1081//206 +f 1081//206 1074//206 1076//257 +f 1081//206 1076//257 1084//259 +f 1346//206 1675//276 1676//257 +f 1677//251 1678//234 1348//206 +f 1348//206 1678//234 1679//232 +f 1348//206 1679//232 1680//230 +f 1681//240 1682//226 1344//206 +f 1680//230 1683//267 1348//206 +f 1348//206 1683//281 1684//268 +f 1348//206 1684//269 1685//275 +f 1685//270 1686//271 1348//206 +f 1348//206 1686//271 1687//272 +f 1348//206 1687//272 1620//206 +f 1620//206 1687//272 1688//273 +f 1620//206 1688//274 1689//222 +f 1689//222 1690//223 1620//206 +f 1620//206 1690//223 1691//236 +f 1620//206 1691//236 1692//235 +f 1682//226 1693//227 1344//206 +f 1344//206 1693//293 1694//304 +f 1344//206 1694//228 1695//229 +f 1695//303 1696//253 1344//206 +f 1344//206 1696//253 1697//403 +f 1344//206 1697//224 1346//206 +f 1346//206 1697//254 1698//255 +f 1346//206 1698//225 1675//276 +f 1676//257 1699//260 1346//206 +f 1346//206 1699//259 1700//262 +f 1346//206 1700//261 1701//263 +f 1701//263 1702//264 1346//206 +f 1346//206 1702//264 1703//242 +f 1346//206 1703//265 1704//243 +f 1704//244 1705//245 1346//206 +f 1346//206 1705//245 1706//213 +f 1346//206 1706//213 1348//206 +f 1348//206 1706//213 1707//250 +f 1348//206 1707//250 1677//251 +f 1692//292 1708//233 1620//206 +f 1620//206 1708//233 1709//238 +f 1620//206 1709//238 1344//206 +f 1344//206 1709//238 1710//239 +f 1344//206 1710//239 1681//240 +f 1293//275 1268//380 1259//206 +f 1259//206 1268//271 1264//206 +f 1259//206 1264//206 1660//206 +f 1660//206 1264//206 1269//404 +f 1660//206 1269//405 1632//206 +f 1632//206 1269//404 1711//406 +f 1632//206 1711//407 1625//206 +f 1625//206 1711//406 1712//408 +f 1625//206 1712//408 1255//206 +f 1255//206 1712//408 1713//409 +f 1255//206 1713//410 1256//411 +f 968//230 942//206 879//206 +f 879//206 942//206 1036//206 +f 879//206 1036//206 1344//206 +f 1344//206 1036//206 1669//206 +f 1344//206 1669//206 1620//206 +f 1620//206 1669//206 1670//206 +f 1620//206 1670//206 1619//206 +f 1619//206 1670//206 1671//206 +f 1619//206 1671//206 1618//206 +f 1618//206 1671//206 1672//206 +f 1618//206 1672//206 1617//206 +f 1617//206 1672//206 1673//206 +f 1617//206 1673//206 1616//206 +f 1616//206 1673//206 1674//206 +f 1616//206 1674//206 1541//206 +f 1541//206 1674//206 1081//206 +f 1541//206 1081//206 1398//206 +f 1398//206 1081//206 982//206 +f 1398//206 982//206 1004//206 +f 1004//206 982//206 1001//262 +f 1004//206 1001//262 1002//263 +f 1314//330 887//412 1308//206 +f 1308//206 887//220 889//206 +f 1308//206 889//206 1259//206 +f 1259//206 889//206 1290//245 +f 1259//206 1290//245 1261//213 +f 1178//255 1179//276 1177//206 +f 1177//206 1179//276 1174//206 +f 1177//206 1174//206 1623//206 +f 1623//206 1174//206 1714//206 +f 1623//206 1714//206 1660//206 +f 1660//206 1714//206 1715//206 +f 1660//206 1715//206 1259//206 +f 1259//206 1715//206 1716//206 +f 1259//206 1716//206 1308//206 +f 1308//206 1716//206 1300//206 +f 1308//206 1300//206 1306//271 +f 1306//271 1300//206 1305//275 +f 885//219 1324//336 886//206 +f 886//206 1324//336 1300//206 +f 886//206 1300//206 1717//206 +f 1717//206 1300//206 1716//206 +f 1717//206 1716//206 1718//206 +f 1718//206 1716//206 1715//206 +f 1718//206 1715//206 1719//206 +f 1719//206 1715//206 1714//206 +f 1719//206 1714//206 1720//206 +f 1720//206 1714//206 1174//206 +f 1720//206 1174//206 1169//206 +f 1169//206 1174//206 1173//260 +f 1169//206 1173//259 1170//261 +f 1171//263 1159//264 1169//206 +f 1169//206 1159//264 1161//206 +f 1169//206 1161//206 1720//206 +f 1720//206 1161//206 1252//206 +f 1720//206 1252//206 1719//206 +f 1719//206 1252//206 1661//206 +f 1719//206 1661//206 1718//206 +f 1718//206 1661//206 1662//206 +f 1718//206 1662//206 1717//206 +f 1717//206 1662//206 1026//206 +f 1717//206 1026//206 886//206 +f 886//206 1026//206 882//206 +f 886//206 882//206 884//413 +f 884//218 882//206 881//217 +f 496//151 458//146 1357//355 +f 1357//353 458//146 877//214 +f 1357//353 1392//356 496//151 +f 496//414 1392//356 1393//358 +f 496//414 1393//415 494//150 +f 494//150 1393//415 873//357 +f 494//416 873//211 447//417 +f 447//417 873//211 872//210 +f 447//134 872//360 448//135 +f 448//135 872//360 1394//362 +f 448//135 1394//362 450//418 +f 450//137 1394//362 1396//363 +f 450//138 1396//363 452//419 +f 452//419 1396//363 1397//366 +f 452//139 1397//366 454//141 +f 454//141 1397//366 1399//367 +f 454//140 1399//420 455//143 +f 455//143 1399//420 1010//287 +f 455//421 1010//290 141//76 +f 141//76 1010//290 1400//368 +f 141//422 1400//368 446//423 +f 446//423 1400//368 869//209 +f 446//133 869//209 11//7 +f 11//7 869//424 866//396 +f 11//7 866//207 14//204 +f 14//204 866//396 868//208 +f 14//204 868//208 443//129 +f 443//129 868//208 1404//370 +f 443//129 1404//425 444//130 +f 444//130 1404//425 1403//393 +f 444//130 1403//393 445//132 +f 445//132 1403//393 1463//426 +f 445//132 1463//426 439//126 +f 439//126 1463//426 1537//398 +f 439//125 1537//427 441//127 +f 441//127 1537//427 1409//375 +f 441//127 1409//397 442//205 +f 442//205 1409//397 1408//374 +f 442//205 1408//374 437//428 +f 437//428 1408//374 1406//372 +f 437//124 1406//372 436//123 +f 436//123 1406//372 1405//371 +f 436//122 1405//371 402//114 +f 402//114 1405//371 1428//379 +f 402//114 1428//399 404//115 +f 404//115 1428//399 1451//381 +f 404//115 1451//381 394//113 +f 394//113 1451//381 1452//386 +f 394//202 1452//383 392//111 +f 392//111 1452//383 1454//385 +f 392//111 1454//429 390//110 +f 390//110 1454//429 1453//384 +f 390//110 1453//384 17//430 +f 17//430 1453//384 1457//391 +f 17//9 1457//392 18//431 +f 18//431 1457//392 1456//432 +f 18//431 1456//390 388//433 +f 388//433 1456//390 1455//388 +f 388//433 1455//387 389//107 +f 389//107 1455//387 1099//301 +f 389//108 1099//296 247//89 +f 247//88 1099//301 230//85 +f 230//434 1099//296 1121//300 +f 230//85 1121//299 243//93 +f 458//144 464//145 877//214 +f 877//214 464//145 474//147 +f 877//214 474//148 1351//348 +f 1351//348 474//148 503//154 +f 1351//348 503//435 1353//349 +f 1353//349 503//435 501//436 +f 1353//437 501//153 1354//438 +f 1354//438 501//153 500//152 +f 1354//351 500//156 1349//352 +f 1349//352 500//156 505//158 +f 1349//352 505//158 1347//439 +f 1347//345 505//158 507//159 +f 1347//344 507//159 1345//440 +f 1345//440 507//159 508//162 +f 1345//343 508//162 1343//342 +f 1343//342 508//162 510//163 +f 1343//341 510//441 880//216 +f 880//216 510//441 108//69 +f 880//442 108//72 878//277 +f 878//277 108//72 511//164 +f 878//443 511//164 1342//444 +f 1342//444 511//164 8//6 +f 1342//339 8//6 881//217 +f 881//217 8//445 7//193 +f 881//217 7//5 884//413 +f 884//413 7//193 604//192 +f 884//413 604//192 885//219 +f 885//219 604//192 543//172 +f 885//219 543//173 1324//336 +f 1324//336 543//173 529//171 +f 1324//336 529//171 1320//333 +f 1320//333 529//171 527//167 +f 1320//333 527//167 1316//332 +f 1316//332 527//167 525//165 +f 1316//331 525//166 1314//330 +f 1314//330 525//166 554//446 +f 1314//330 554//174 887//220 +f 887//220 554//174 555//175 +f 887//220 555//175 888//447 +f 888//447 555//175 558//177 +f 888//221 558//177 1299//329 +f 1299//329 558//177 557//176 +f 1299//328 557//176 1267//321 +f 1267//321 557//176 559//183 +f 1267//321 559//179 1270//324 +f 1270//324 559//179 4//199 +f 1270//324 4//199 1269//404 +f 1269//404 4//199 726//197 +f 1269//405 726//198 1711//406 +f 1711//406 726//198 597//184 +f 1711//406 597//448 1712//408 +f 1712//408 597//448 599//185 +f 1712//408 599//185 1713//449 +f 1713//449 599//185 603//190 +f 1713//410 603//191 1256//319 +f 1256//319 603//191 602//450 +f 1256//319 602//188 1257//451 +f 1257//451 602//188 601//187 +f 1257//451 601//186 1254//318 +f 1254//318 601//186 243//87 +f 1254//402 243//93 1102//297 +f 1102//302 243//87 1121//300 +f 329//452 1237//213 20//41 +f 20//41 1237//453 1236//245 +f 20//41 1236//245 21//12 +f 21//73 1236//245 1244//243 +f 21//70 1244//243 324//48 +f 324//13 1244//282 1243//242 +f 324//13 1243//265 325//14 +f 325//14 1243//265 1242//310 +f 325//194 1242//264 326//50 +f 326//50 1242//264 1241//454 +f 326//50 1241//263 327//52 +f 327//52 1241//263 1240//261 +f 327//51 1240//261 328//82 +f 328//54 1240//262 1238//308 +f 328//54 1238//260 322//55 +f 322//55 1238//259 1251//257 +f 322//55 1251//257 320//455 +f 320//17 1251//257 1250//456 +f 320//455 1250//276 314//18 +f 314//18 1250//456 1249//255 +f 314//18 1249//255 315//45 +f 315//44 1249//255 1248//224 +f 315//196 1248//224 317//75 +f 317//46 1248//403 1247//285 +f 317//46 1247//253 318//47 +f 318//47 1247//253 1246//303 +f 318//47 1246//229 319//21 +f 319//21 1246//229 1245//228 +f 319//21 1245//228 312//22 +f 312//22 1245//228 1253//227 +f 312//84 1253//227 56//49 +f 56//42 1253//293 912//241 +f 56//42 912//226 54//1 +f 54//1 912//258 915//240 +f 54//1 915//240 52//457 +f 52//2 915//240 917//458 +f 52//457 917//239 50//27 +f 50//27 917//458 919//238 +f 50//27 919//238 38//23 +f 38//31 919//238 902//231 +f 38//28 902//231 387//81 +f 387//29 902//237 1180//292 +f 387//29 1180//235 378//56 +f 378//56 1180//235 1182//236 +f 378//56 1182//236 379//57 +f 379//57 1182//236 891//223 +f 379//90 891//223 381//62 +f 381//62 891//223 890//222 +f 381//74 890//222 382//119 +f 382//15 890//266 1188//376 +f 382//15 1188//273 383//16 +f 383//16 1188//274 1187//272 +f 383//16 1187//272 384//459 +f 384//64 1187//272 1183//460 +f 384//459 1183//271 385//19 +f 385//19 1183//460 1185//275 +f 385//19 1185//275 339//60 +f 339//20 1185//275 1186//269 +f 339//101 1186//269 370//61 +f 370//67 1186//294 1222//267 +f 370//67 1222//281 372//24 +f 372//24 1222//281 1224//230 +f 372//461 1224//230 374//25 +f 374//25 1224//230 1226//312 +f 374//25 1226//232 376//30 +f 376//30 1226//232 1232//234 +f 376//32 1232//234 377//462 +f 377//105 1232//252 1231//314 +f 377//105 1231//314 333//463 +f 333//463 1231//464 1229//465 +f 333//466 1229//465 331//98 +f 331//98 1229//467 1234//316 +f 331//98 1234//316 329//452 +f 329//38 1234//468 1237//453 +f 255//38 1115//469 236//41 +f 236//11 1115//469 1113//245 +f 236//41 1113//245 237//73 +f 237//12 1113//245 1108//243 +f 237//73 1108//282 270//13 +f 270//48 1108//243 1130//265 +f 270//13 1130//265 263//14 +f 263//97 1130//265 1131//264 +f 263//194 1131//310 264//103 +f 264//103 1131//264 1140//470 +f 264//50 1140//309 265//52 +f 265//52 1140//263 1139//261 +f 265//51 1139//262 278//54 +f 278//82 1139//261 1138//308 +f 278//54 1138//259 279//55 +f 279//55 1138//260 1143//257 +f 279//55 1143//278 275//17 +f 275//471 1143//257 1142//456 +f 275//455 1142//472 276//18 +f 276//43 1142//276 1141//225 +f 276//18 1141//255 277//44 +f 277//45 1141//255 1129//224 +f 277//196 1129//403 272//46 +f 272//75 1129//224 1128//285 +f 272//473 1128//285 273//47 +f 273//474 1128//285 1127//475 +f 273//474 1127//303 274//21 +f 274//201 1127//229 1101//228 +f 274//21 1101//304 241//22 +f 241//22 1101//228 1100//227 +f 241//22 1100//293 242//42 +f 242//49 1100//227 1126//226 +f 242//42 1126//258 266//1 +f 266//1 1126//226 1125//240 +f 266//1 1125//246 231//2 +f 231//476 1125//240 1124//458 +f 231//457 1124//354 232//27 +f 232//36 1124//239 1120//238 +f 232//27 1120//238 248//31 +f 248//23 1120//238 1122//231 +f 248//31 1122//237 249//29 +f 249//81 1122//231 1123//235 +f 249//29 1123//235 250//56 +f 250//86 1123//235 1098//236 +f 250//56 1098//477 251//57 +f 251//180 1098//236 1097//326 +f 251//90 1097//326 252//74 +f 252//74 1097//223 1137//222 +f 252//74 1137//266 267//15 +f 267//119 1137//222 1136//376 +f 267//15 1136//274 268//16 +f 268//16 1136//273 1135//272 +f 268//16 1135//286 269//64 +f 269//58 1135//272 1134//460 +f 269//459 1134//380 244//19 +f 244//59 1134//271 1133//275 +f 244//19 1133//275 245//20 +f 245//60 1133//275 1132//269 +f 245//101 1132//294 246//67 +f 246//67 1132//269 1119//267 +f 246//67 1119//267 253//478 +f 253//478 1119//281 1118//479 +f 253//478 1118//311 254//25 +f 254//102 1118//311 1117//312 +f 254//25 1117//307 239//30 +f 239//30 1117//232 1105//234 +f 239//30 1105//252 235//33 +f 235//80 1105//234 1104//291 +f 235//33 1104//251 257//35 +f 257//68 1104//291 1116//250 +f 257//35 1116//284 255//480 +f 255//480 1116//250 1115//213 +f 294//452 1165//453 296//11 +f 296//41 1165//453 1163//212 +f 296//41 1163//245 297//12 +f 297//73 1163//245 1162//243 +f 297//70 1162//243 23//13 +f 23//13 1162//282 1160//242 +f 23//13 1160//265 24//97 +f 24//14 1160//265 1159//264 +f 24//194 1159//264 289//50 +f 289//50 1159//264 1171//454 +f 289//50 1171//263 288//52 +f 288//52 1171//263 1170//261 +f 288//51 1170//261 286//82 +f 286//54 1170//262 1173//308 +f 286//54 1173//260 283//55 +f 283//55 1173//259 1172//257 +f 283//65 1172//257 284//455 +f 284//455 1172//278 1179//456 +f 284//455 1179//456 285//43 +f 285//18 1179//456 1178//225 +f 285//18 1178//255 281//45 +f 281//44 1178//255 1176//224 +f 281//196 1176//224 282//75 +f 282//46 1176//403 1175//285 +f 282//46 1175//253 261//47 +f 261//47 1175//253 1095//303 +f 261//47 1095//229 262//201 +f 262//21 1095//475 1094//228 +f 262//92 1094//228 271//22 +f 271//22 1094//228 1107//227 +f 271//84 1107//227 240//49 +f 240//42 1107//227 1106//241 +f 240//42 1106//226 238//1 +f 238//1 1106//258 1112//240 +f 238//40 1112//240 256//457 +f 256//457 1112//246 1114//458 +f 256//457 1114//458 258//36 +f 258//27 1114//458 1111//249 +f 258//27 1111//238 259//23 +f 259//31 1111//238 1110//231 +f 259//28 1110//231 233//29 +f 233//29 1110//233 1109//292 +f 233//29 1109//235 234//56 +f 234//56 1109//235 1103//298 +f 234//56 1103//236 311//180 +f 311//57 1103//477 1145//223 +f 311//90 1145//223 302//62 +f 302//62 1145//223 1144//222 +f 302//74 1144//222 303//119 +f 303//15 1144//266 1147//376 +f 303//15 1147//273 307//16 +f 307//16 1147//274 1149//272 +f 307//16 1149//272 308//459 +f 308//459 1149//272 1152//460 +f 308//459 1152//460 309//19 +f 309//19 1152//460 1151//275 +f 309//19 1151//275 305//60 +f 305//20 1151//275 1158//269 +f 305//101 1158//269 306//61 +f 306//67 1158//294 1157//267 +f 306//67 1157//281 300//24 +f 300//24 1157//281 1156//230 +f 300//461 1156//230 298//25 +f 298//25 1156//230 1155//312 +f 298//25 1155//232 290//30 +f 290//30 1155//232 1168//234 +f 290//32 1168//234 291//34 +f 291//33 1168//234 1167//288 +f 291//33 1167//291 293//35 +f 293//35 1167//251 1166//250 +f 293//68 1166//250 294//452 +f 294//452 1166//284 1165//453 +f 747//452 1499//248 746//481 +f 746//482 1499//213 1500//483 +f 746//41 1500//484 749//12 +f 749//12 1500//483 1512//243 +f 749//12 1512//243 750//13 +f 750//13 1512//243 1511//265 +f 750//13 1511//265 751//14 +f 751//97 1511//265 1504//264 +f 751//14 1504//305 761//485 +f 761//485 1504//264 1503//263 +f 761//50 1503//309 762//52 +f 762//52 1503//263 1530//261 +f 762//51 1530//262 763//54 +f 763//82 1530//261 1529//308 +f 763//54 1529//308 767//55 +f 767//65 1529//260 1528//257 +f 767//65 1528//278 768//17 +f 768//471 1528//257 1527//456 +f 768//455 1527//472 769//18 +f 769//43 1527//276 1526//255 +f 769//18 1526//255 764//44 +f 764//45 1526//255 1525//224 +f 764//196 1525//403 765//46 +f 765//75 1525//224 1510//285 +f 765//46 1510//253 766//47 +f 766//94 1510//253 1509//229 +f 766//486 1509//475 755//21 +f 755//92 1509//303 1508//304 +f 755//21 1508//304 756//22 +f 756//22 1508//228 1502//227 +f 756//22 1502//293 757//42 +f 757//49 1502//227 1501//226 +f 757//49 1501//226 734//1 +f 734//487 1501//226 1524//488 +f 734//489 1524//490 735//2 +f 735//476 1524//491 1523//458 +f 735//457 1523//354 738//492 +f 738//493 1523//239 1522//494 +f 738//495 1522//496 736//31 +f 736//31 1522//238 1521//237 +f 736//31 1521//237 737//29 +f 737//81 1521//231 1520//235 +f 737//29 1520//235 739//56 +f 739//86 1520//235 1519//236 +f 739//497 1519//298 740//90 +f 740//90 1519//236 1518//498 +f 740//57 1518//295 741//62 +f 741//62 1518//223 1517//222 +f 741//74 1517//266 758//15 +f 758//119 1517//222 1516//376 +f 758//15 1516//274 759//16 +f 759//16 1516//273 1533//272 +f 759//16 1533//286 760//64 +f 760//499 1533//272 1532//460 +f 760//459 1532//500 752//19 +f 752//59 1532//271 1531//270 +f 752//19 1531//270 753//20 +f 753//101 1531//275 1515//269 +f 753//101 1515//294 754//67 +f 754//61 1515//269 1514//267 +f 754//67 1514//281 742//24 +f 742//77 1514//281 1513//230 +f 742//24 1513//479 743//25 +f 743//200 1513//479 1507//232 +f 743//25 1507//307 744//30 +f 744//30 1507//232 1506//234 +f 744//30 1506//234 745//33 +f 745//33 1506//234 1505//251 +f 745//33 1505//251 748//501 +f 748//502 1505//251 1498//250 +f 748//501 1498//503 747//38 +f 747//39 1498//504 1499//453 +f 228//452 1088//453 229//41 +f 229//41 1088//453 1087//245 +f 229//41 1087//245 210//12 +f 210//73 1087//245 1082//243 +f 210//70 1082//243 211//48 +f 211//13 1082//282 1080//242 +f 211//13 1080//265 221//97 +f 221//14 1080//265 1079//310 +f 221//14 1079//264 222//505 +f 222//50 1079//264 1086//454 +f 222//50 1086//263 223//52 +f 223//52 1086//309 1085//261 +f 223//51 1085//261 213//82 +f 213//54 1085//262 1084//308 +f 213//54 1084//260 214//55 +f 214//55 1084//259 1076//257 +f 214//55 1076//257 216//455 +f 216//455 1076//257 1075//456 +f 216//455 1075//456 217//18 +f 217//18 1075//456 1073//255 +f 217//18 1073//255 193//45 +f 193//44 1073//255 1072//224 +f 193//196 1072//224 194//75 +f 194//46 1072//403 1062//285 +f 194//46 1062//253 196//94 +f 196//47 1062//253 1061//303 +f 196//474 1061//229 197//21 +f 197//21 1061//475 1071//228 +f 197//21 1071//228 198//22 +f 198//22 1071//228 1070//227 +f 198//84 1070//227 202//49 +f 202//42 1070//293 1069//241 +f 202//42 1069//258 203//1 +f 203//1 1069//258 1068//240 +f 203//40 1068//240 204//457 +f 204//457 1068//246 1067//458 +f 204//457 1067//458 200//36 +f 200//27 1067//458 1066//249 +f 200//27 1066//238 201//23 +f 201//23 1066//238 1065//231 +f 201//28 1065//231 205//81 +f 205//29 1065//237 1064//292 +f 205//29 1064//235 206//56 +f 206//56 1064//235 1063//236 +f 206//56 1063//236 207//180 +f 207//57 1063//236 1058//326 +f 207//90 1058//223 192//62 +f 192//62 1058//295 1057//222 +f 192//74 1057//222 26//119 +f 26//15 1057//266 1056//376 +f 26//15 1056//273 27//16 +f 27//16 1056//274 1055//272 +f 27//16 1055//272 218//459 +f 218//459 1055//272 1054//460 +f 218//459 1054//460 219//19 +f 219//19 1054//460 1083//275 +f 219//19 1083//275 220//60 +f 220//20 1083//275 1078//269 +f 220//101 1078//269 208//61 +f 208//67 1078//294 1077//267 +f 208//67 1077//281 209//77 +f 209//24 1077//281 1093//230 +f 209//461 1093//230 224//25 +f 224//25 1093//280 1092//232 +f 224//102 1092//232 225//30 +f 225//30 1092//307 1091//234 +f 225//32 1091//234 226//80 +f 226//33 1091//252 1090//288 +f 226//33 1090//291 227//35 +f 227//35 1090//251 1089//250 +f 227//35 1089//250 228//452 +f 228//452 1089//250 1088//453 +f 410//38 1411//469 395//41 +f 395//11 1411//469 1413//245 +f 395//41 1413//245 396//73 +f 396//12 1413//245 1442//243 +f 396//73 1442//282 421//13 +f 421//48 1442//243 1441//265 +f 421//13 1441//265 422//14 +f 422//97 1441//265 1418//264 +f 422//14 1418//305 423//50 +f 423//103 1418//264 1417//454 +f 423//505 1417//454 433//51 +f 433//51 1417//263 1440//261 +f 433//51 1440//262 434//54 +f 434//82 1440//261 1439//308 +f 434//54 1439//259 435//55 +f 435//55 1439//259 1438//257 +f 435//55 1438//278 411//17 +f 411//471 1438//257 1448//456 +f 411//455 1448//256 398//18 +f 398//43 1448//276 1447//255 +f 398//18 1447//255 399//44 +f 399//45 1447//255 1446//224 +f 399//196 1446//403 424//46 +f 424//75 1446//224 1437//285 +f 424//46 1437//285 425//47 +f 425//474 1437//285 1436//475 +f 425//474 1436//303 426//21 +f 426//201 1436//229 1435//228 +f 426//21 1435//304 427//22 +f 427//22 1435//228 1434//227 +f 427//22 1434//293 428//42 +f 428//49 1434//227 1433//226 +f 428//42 1433//258 429//1 +f 429//1 1433//226 1431//240 +f 429//1 1431//246 405//2 +f 405//476 1431//240 1430//458 +f 405//457 1430//354 403//27 +f 403//36 1430//239 1429//238 +f 403//27 1429//238 401//31 +f 401//23 1429//238 1427//231 +f 401//31 1427//237 412//29 +f 412//81 1427//231 1426//235 +f 412//29 1426//235 413//506 +f 413//506 1426//235 1425//507 +f 413//506 1425//507 414//57 +f 414//90 1425//507 1424//326 +f 414//180 1424//326 415//74 +f 415//74 1424//223 1423//222 +f 415//74 1423//266 416//15 +f 416//119 1423//222 1422//376 +f 416//15 1422//274 417//16 +f 417//16 1422//273 1445//272 +f 417//16 1445//286 430//64 +f 430//499 1445//272 1444//460 +f 430//459 1444//500 431//19 +f 431//59 1444//271 1443//275 +f 431//19 1443//275 432//60 +f 432//60 1443//275 1421//269 +f 432//101 1421//294 418//67 +f 418//61 1421//269 1420//267 +f 418//67 1420//267 419//24 +f 419//461 1420//267 1419//280 +f 419//461 1419//311 420//508 +f 420//508 1419//230 1416//232 +f 420//508 1416//307 406//30 +f 406//30 1416//232 1415//234 +f 406//30 1415//252 407//33 +f 407//80 1415//234 1414//291 +f 407//33 1414//251 409//35 +f 409//68 1414//291 1410//250 +f 409//35 1410//284 410//480 +f 410//480 1410//250 1411//213 +f 190//452 1048//453 191//41 +f 191//41 1048//453 1047//245 +f 191//41 1047//245 179//12 +f 179//73 1047//245 1041//243 +f 179//70 1041//243 180//48 +f 180//13 1041//282 1040//242 +f 180//13 1040//265 181//97 +f 181//14 1040//265 1039//310 +f 181//14 1039//264 182//505 +f 182//50 1039//305 1038//263 +f 182//50 1038//263 183//52 +f 183//52 1038//263 1037//261 +f 183//51 1037//261 184//82 +f 184//54 1037//262 1046//308 +f 184//54 1046//260 185//55 +f 185//55 1046//259 1045//257 +f 185//55 1045//257 29//455 +f 29//455 1045//257 1044//456 +f 29//455 1044//456 30//18 +f 30//18 1044//456 894//255 +f 30//18 894//255 157//45 +f 157//44 894//255 893//224 +f 157//196 893//224 154//75 +f 154//46 893//403 1017//285 +f 154//46 1017//253 155//94 +f 155//47 1017//253 1025//229 +f 155//474 1025//229 158//21 +f 158//21 1025//229 1033//228 +f 158//21 1033//228 159//22 +f 159//22 1033//304 1032//227 +f 159//84 1032//227 160//49 +f 160//42 1032//293 1029//241 +f 160//42 1029//258 161//1 +f 161//1 1029//258 1028//240 +f 161//40 1028//240 162//457 +f 162//457 1028//246 1027//458 +f 162//457 1027//458 164//36 +f 164//27 1027//458 1024//249 +f 164//27 1024//238 165//23 +f 165//23 1024//238 1023//231 +f 165//28 1023//231 166//81 +f 166//29 1023//237 1031//292 +f 166//29 1031//235 167//86 +f 167//56 1031//235 1030//236 +f 167//56 1030//236 168//57 +f 168//57 1030//236 1022//326 +f 168//57 1022//223 169//62 +f 169//62 1022//295 1021//222 +f 169//74 1021//222 170//119 +f 170//15 1021//266 1020//376 +f 170//15 1020//273 172//16 +f 172//16 1020//274 1019//272 +f 172//16 1019//272 173//459 +f 173//459 1019//272 1043//460 +f 173//459 1043//460 174//19 +f 174//19 1043//460 1042//275 +f 174//19 1042//275 175//60 +f 175//20 1042//275 1035//269 +f 175//101 1035//269 177//61 +f 177//67 1035//294 1034//267 +f 177//67 1034//281 178//24 +f 178//24 1034//281 1053//230 +f 178//24 1053//230 186//200 +f 186//25 1053//280 1052//232 +f 186//102 1052//232 187//30 +f 187//30 1052//307 1051//234 +f 187//32 1051//234 188//80 +f 188//33 1051//252 1050//288 +f 188//33 1050//291 189//35 +f 189//35 1050//251 1049//250 +f 189//35 1049//250 190//452 +f 190//38 1049//250 1048//453 +f 860//452 1479//248 851//41 +f 851//11 1479//213 1478//245 +f 851//41 1478//245 852//73 +f 852//12 1478//245 1477//243 +f 852//70 1477//243 853//13 +f 853//13 1477//243 1486//265 +f 853//13 1486//242 856//14 +f 856//97 1486//265 1485//264 +f 856//14 1485//305 857//50 +f 857//505 1485//264 1474//263 +f 857//103 1474//454 834//52 +f 834//52 1474//263 1473//261 +f 834//52 1473//262 835//54 +f 835//82 1473//261 1472//308 +f 835//54 1472//259 845//55 +f 845//55 1472//308 1466//257 +f 845//65 1466//509 846//17 +f 846//471 1466//257 1465//456 +f 846//455 1465//472 847//18 +f 847//43 1465//276 1484//225 +f 847//18 1484//255 838//44 +f 838//45 1484//255 1482//224 +f 838//196 1482//403 837//46 +f 837//75 1482//224 1481//253 +f 837//46 1481//253 836//47 +f 836//94 1481//253 1497//229 +f 836//474 1497//303 854//21 +f 854//92 1497//229 1496//395 +f 854//92 1496//395 855//22 +f 855//84 1496//228 1492//227 +f 855//84 1492//293 839//42 +f 839//49 1492//227 1491//241 +f 839//42 1491//258 1//1 +f 1//1 1491//226 1490//240 +f 1//1 1490//246 2//457 +f 2//457 1490//240 1495//458 +f 2//457 1495//458 831//27 +f 831//36 1495//458 1494//238 +f 831//27 1494//238 832//31 +f 832//23 1494//238 1493//231 +f 832//28 1493//237 833//29 +f 833//81 1493//231 1489//292 +f 833//29 1489//292 840//56 +f 840//497 1489//235 1488//298 +f 840//497 1488//477 841//57 +f 841//90 1488//236 1487//326 +f 841//57 1487//295 830//62 +f 830//62 1487//223 1471//222 +f 830//62 1471//266 829//15 +f 829//119 1471//222 1470//376 +f 829//15 1470//274 828//16 +f 828//16 1470//273 1469//272 +f 828//66 1469//510 827//64 +f 827//499 1469//272 1461//460 +f 827//459 1461//500 842//19 +f 842//511 1461//271 1460//270 +f 842//19 1460//275 843//20 +f 843//60 1460//275 1459//269 +f 843//101 1459//294 844//67 +f 844//61 1459//269 1458//281 +f 844//67 1458//281 848//24 +f 848//461 1458//281 1476//311 +f 848//24 1476//280 849//25 +f 849//200 1476//230 1475//232 +f 849//25 1475//307 850//30 +f 850//32 1475//232 1468//234 +f 850//30 1468//234 858//33 +f 858//33 1468//234 1467//288 +f 858//33 1467//251 859//35 +f 859//35 1467//291 1480//250 +f 859//35 1480//284 860//38 +f 860//39 1480//250 1479//453 +f 152//452 1008//512 153//41 +f 153//11 1008//213 1013//245 +f 153//41 1013//245 150//73 +f 150//12 1013//245 1012//243 +f 150//70 1012//282 144//13 +f 144//48 1012//243 1011//242 +f 144//13 1011//242 145//14 +f 145//97 1011//265 1003//310 +f 145//14 1003//305 136//50 +f 136//505 1003//264 1002//263 +f 136//50 1002//309 137//52 +f 137//52 1002//263 1001//261 +f 137//51 1001//262 138//54 +f 138//82 1001//261 1000//308 +f 138//54 1000//308 122//55 +f 122//55 1000//260 999//257 +f 122//55 999//278 123//17 +f 123//471 999//257 984//456 +f 123//455 984//472 125//18 +f 125//43 984//276 983//255 +f 125//18 983//255 126//44 +f 126//45 983//255 981//224 +f 126//196 981//403 115//46 +f 115//75 981//224 980//285 +f 115//46 980//253 116//47 +f 116//94 980//253 979//229 +f 116//47 979//475 127//21 +f 127//201 979//229 978//228 +f 127//21 978//304 128//22 +f 128//22 978//228 998//227 +f 128//84 998//227 129//42 +f 129//42 998//227 997//241 +f 129//42 997//258 133//1 +f 133//1 997//226 996//240 +f 133//1 996//246 134//2 +f 134//513 996//240 995//458 +f 134//457 995//514 135//27 +f 135//36 995//239 994//238 +f 135//27 994//238 130//31 +f 130//23 994//238 993//231 +f 130//28 993//237 131//29 +f 131//29 993//231 992//292 +f 131//29 992//235 132//56 +f 132//86 992//235 991//236 +f 132//56 991//477 117//57 +f 117//180 991//236 990//326 +f 117//57 990//295 118//62 +f 118//62 990//223 989//222 +f 118//74 989//266 119//15 +f 119//119 989//222 988//376 +f 119//15 988//274 120//16 +f 120//16 988//273 987//272 +f 120//16 987//286 121//64 +f 121//499 987//272 986//460 +f 121//459 986//500 142//19 +f 142//59 986//271 985//275 +f 142//19 985//275 143//20 +f 143//60 985//275 1007//269 +f 143//101 1007//294 139//67 +f 139//67 1007//269 1006//267 +f 139//67 1006//281 140//24 +f 140//77 1006//281 1005//230 +f 140//461 1005//280 147//25 +f 147//200 1005//230 1016//232 +f 147//102 1016//307 148//30 +f 148//32 1016//232 1015//234 +f 148//32 1015//252 149//33 +f 149//80 1015//234 1014//288 +f 149//33 1014//251 151//35 +f 151//35 1014//291 1009//250 +f 151//35 1009//284 152//38 +f 152//515 1009//250 1008//453 +f 813//452 1552//512 814//41 +f 814//11 1552//213 1571//245 +f 814//41 1571//245 805//73 +f 805//12 1571//245 1570//243 +f 805//70 1570//282 806//13 +f 806//48 1570//243 1551//242 +f 806//13 1551//265 807//14 +f 807//97 1551//265 1550//310 +f 807//194 1550//310 808//50 +f 808//505 1550//264 1549//263 +f 808//50 1549//309 815//52 +f 815//52 1549//263 1573//261 +f 815//51 1573//262 816//54 +f 816//82 1573//261 1572//308 +f 816//54 1572//259 817//55 +f 817//55 1572//260 1569//257 +f 817//65 1569//278 818//17 +f 818//471 1569//257 1568//456 +f 818//455 1568//472 819//18 +f 819//43 1568//276 1567//255 +f 819//18 1567//255 820//44 +f 820//45 1567//255 1548//224 +f 820//196 1548//403 799//46 +f 799//75 1548//224 1547//285 +f 799//46 1547//253 800//47 +f 800//94 1547//253 1546//229 +f 800//47 1546//475 801//21 +f 801//201 1546//229 1545//395 +f 801//92 1545//304 802//22 +f 802//22 1545//228 1544//227 +f 802//84 1544//293 809//42 +f 809//49 1544//227 1543//241 +f 809//42 1543//241 810//1 +f 810//1 1543//226 1540//240 +f 810//1 1540//246 811//2 +f 811//513 1540//240 1542//458 +f 811//457 1542//514 785//27 +f 785//36 1542//239 1566//238 +f 785//27 1566//238 786//31 +f 786//28 1566//238 1565//231 +f 786//28 1565//237 787//29 +f 787//81 1565//231 1564//292 +f 787//29 1564//235 788//56 +f 788//86 1564//235 1563//236 +f 788//56 1563//477 789//57 +f 789//180 1563//236 1562//223 +f 789//57 1562//295 795//62 +f 795//62 1562//223 1561//222 +f 795//74 1561//266 794//15 +f 794//119 1561//222 1576//376 +f 794//15 1576//274 793//16 +f 793//16 1576//273 1575//272 +f 793//16 1575//286 796//64 +f 796//499 1575//272 1574//460 +f 796//459 1574//500 797//19 +f 797//59 1574//271 1560//270 +f 797//19 1560//275 798//20 +f 798//60 1560//275 1559//269 +f 798//101 1559//294 803//67 +f 803//61 1559//269 1558//267 +f 803//67 1558//281 804//24 +f 804//77 1558//281 1557//230 +f 804//24 1557//280 790//25 +f 790//102 1557//230 1556//312 +f 790//25 1556//307 791//30 +f 791//30 1556//232 1555//234 +f 791//32 1555//252 792//33 +f 792//80 1555//234 1554//288 +f 792//33 1554//251 812//35 +f 812//35 1554//291 1553//250 +f 812//35 1553//284 813//38 +f 813//515 1553//250 1552//453 +f 463//452 876//512 472//41 +f 472//516 876//213 875//212 +f 472//41 875//245 473//73 +f 473//12 875//245 1368//243 +f 473//70 1368//282 475//13 +f 475//48 1368//243 1367//265 +f 475//13 1367//265 491//14 +f 491//97 1367//265 1382//310 +f 491//194 1382//305 492//50 +f 492//505 1382//264 1381//263 +f 492//50 1381//309 493//52 +f 493//52 1381//263 1380//261 +f 493//51 1380//262 497//54 +f 497//82 1380//261 1379//308 +f 497//54 1379//259 498//55 +f 498//55 1379//260 1378//257 +f 498//55 1378//278 499//17 +f 499//471 1378//257 1390//456 +f 499//455 1390//472 481//18 +f 481//43 1390//276 1389//255 +f 481//18 1389//255 482//44 +f 482//45 1389//255 1388//224 +f 482//196 1388//403 483//46 +f 483//75 1388//224 1377//285 +f 483//46 1377//253 486//47 +f 486//94 1377//253 1376//303 +f 486//47 1376//475 487//21 +f 487//201 1376//229 1375//395 +f 487//92 1375//304 467//22 +f 467//22 1375//228 1366//227 +f 467//22 1366//293 468//42 +f 468//49 1366//227 1365//241 +f 468//42 1365//258 470//1 +f 470//1 1365//226 1364//240 +f 470//1 1364//246 471//2 +f 471//513 1364//240 1362//458 +f 471//457 1362//514 459//27 +f 459//36 1362//239 1361//238 +f 459//27 1361//238 460//28 +f 460//23 1361//238 1359//231 +f 460//28 1359//237 462//29 +f 462//81 1359//231 1358//235 +f 462//29 1358//235 476//56 +f 476//86 1358//235 1374//298 +f 476//497 1374//477 477//57 +f 477//180 1374//236 1373//223 +f 477//57 1373//295 478//62 +f 478//74 1373//223 1372//222 +f 478//74 1372//222 488//15 +f 488//119 1372//222 1387//376 +f 488//15 1387//274 489//16 +f 489//16 1387//273 1386//272 +f 489//16 1386//286 490//64 +f 490//58 1386//272 1385//460 +f 490//459 1385//380 479//19 +f 479//59 1385//271 1384//275 +f 479//19 1384//275 480//20 +f 480//60 1384//275 1383//269 +f 480//101 1383//294 484//67 +f 484//67 1383//269 1371//267 +f 484//67 1371//267 485//24 +f 485//77 1371//281 1370//230 +f 485//24 1370//280 456//25 +f 456//200 1370//230 1369//312 +f 456//102 1369//307 457//30 +f 457//30 1369//232 1356//234 +f 457//30 1356//252 466//33 +f 466//80 1356//234 1355//288 +f 466//33 1355//251 465//35 +f 465//35 1355//291 1363//250 +f 465//68 1363//517 463//38 +f 463//515 1363//250 876//453 +f 672//452 1706//512 673//41 +f 673//11 1706//213 1705//212 +f 673//41 1705//245 674//73 +f 674//12 1705//245 1704//243 +f 674//70 1704//282 675//13 +f 675//48 1704//243 1703//242 +f 675//13 1703//265 676//14 +f 676//194 1703//265 1702//310 +f 676//194 1702//310 677//50 +f 677//485 1702//264 1701//470 +f 677//50 1701//470 678//52 +f 678//52 1701//470 1700//261 +f 678//51 1700//262 679//54 +f 679//82 1700//261 1699//308 +f 679//54 1699//259 680//55 +f 680//55 1699//260 1676//257 +f 680//55 1676//278 681//17 +f 681//96 1676//257 1675//456 +f 681//455 1675//256 682//18 +f 682//43 1675//276 1698//255 +f 682//18 1698//255 683//44 +f 683//45 1698//255 1697//224 +f 683//196 1697//403 669//46 +f 669//75 1697//224 1696//285 +f 669//46 1696//253 670//47 +f 670//94 1696//253 1695//229 +f 670//47 1695//475 684//21 +f 684//92 1695//229 1694//395 +f 684//92 1694//395 685//22 +f 685//22 1694//228 1693//227 +f 685//84 1693//293 686//42 +f 686//49 1693//227 1682//241 +f 686//42 1682//241 687//1 +f 687//1 1682//226 1681//240 +f 687//1 1681//246 688//2 +f 688//513 1681//240 1710//458 +f 688//457 1710//514 689//27 +f 689//36 1710//239 1709//238 +f 689//27 1709//238 653//31 +f 653//28 1709//238 1708//231 +f 653//28 1708//231 654//29 +f 654//81 1708//231 1692//292 +f 654//29 1692//235 658//56 +f 658//497 1692//235 1691//298 +f 658//497 1691//298 659//57 +f 659//180 1691//236 1690//223 +f 659//57 1690//295 660//62 +f 660//62 1690//223 1689//222 +f 660//74 1689//266 656//15 +f 656//119 1689//222 1688//376 +f 656//15 1688//274 657//16 +f 657//16 1688//273 1687//272 +f 657//66 1687//286 661//518 +f 661//519 1687//272 1686//520 +f 661//518 1686//521 662//19 +f 662//19 1686//520 1685//270 +f 662//19 1685//270 663//20 +f 663//60 1685//275 1684//269 +f 663//101 1684//294 667//67 +f 667//61 1684//269 1683//267 +f 667//67 1683//281 668//478 +f 668//478 1683//281 1680//230 +f 668//478 1680//479 666//25 +f 666//102 1680//311 1679//312 +f 666//102 1679//312 665//30 +f 665//30 1679//232 1678//234 +f 665//32 1678//252 664//33 +f 664//80 1678//234 1677//288 +f 664//33 1677//251 671//35 +f 671//35 1677//291 1707//250 +f 671//35 1707//284 672//38 +f 672//515 1707//250 1706//453 +f 106//452 972//512 107//41 +f 107//11 972//213 971//245 +f 107//41 971//245 112//73 +f 112//12 971//245 967//243 +f 112//70 967//282 113//13 +f 113//48 967//243 966//242 +f 113//13 966//242 114//14 +f 114//97 966//265 965//522 +f 114//14 965//305 109//50 +f 109//505 965//264 962//454 +f 109//50 962//309 110//52 +f 110//52 962//263 961//261 +f 110//51 961//261 111//54 +f 111//54 961//261 964//308 +f 111//54 964//308 80//523 +f 80//524 964//259 963//525 +f 80//523 963//526 81//17 +f 81//96 963//525 960//456 +f 81//455 960//256 82//527 +f 82//528 960//276 959//529 +f 82//527 959//530 83//45 +f 83//196 959//529 958//224 +f 83//196 958//224 84//46 +f 84//75 958//224 957//285 +f 84//46 957//253 85//47 +f 85//94 957//253 956//229 +f 85//474 956//475 86//531 +f 86//531 956//229 955//228 +f 86//21 955//304 87//22 +f 87//22 955//532 954//227 +f 87//84 954//227 96//42 +f 96//42 954//227 953//241 +f 96//42 953//258 97//1 +f 97//1 953//226 952//240 +f 97//1 952//246 98//2 +f 98//513 952//240 951//458 +f 98//457 951//514 88//27 +f 88//36 951//239 950//249 +f 88//27 950//238 89//31 +f 89//23 950//238 949//231 +f 89//28 949//231 90//29 +f 90//29 949//231 948//292 +f 90//29 948//235 91//506 +f 91//86 948//235 947//236 +f 91//56 947//507 92//57 +f 92//180 947//507 946//326 +f 92//57 946//295 93//62 +f 93//62 946//223 945//222 +f 93//74 945//266 94//15 +f 94//15 945//222 944//376 +f 94//15 944//376 95//533 +f 95//534 944//274 943//535 +f 95//533 943//536 79//64 +f 79//58 943//535 941//460 +f 79//459 941//380 32//537 +f 32//538 941//271 940//539 +f 32//537 940//540 33//60 +f 33//101 940//539 970//269 +f 33//101 970//269 102//67 +f 102//67 970//269 969//267 +f 102//67 969//281 99//24 +f 99//77 969//281 968//230 +f 99//461 968//280 100//25 +f 100//200 968//230 976//232 +f 100//508 976//307 103//30 +f 103//32 976//232 975//234 +f 103//32 975//252 104//33 +f 104//80 975//234 974//288 +f 104//33 974//251 105//35 +f 105//35 974//291 973//250 +f 105//68 973//284 106//38 +f 106//515 973//250 972//453 +f 553//452 1327//248 548//41 +f 548//11 1327//213 1335//245 +f 548//41 1335//245 549//73 +f 549//12 1335//245 1334//243 +f 549//70 1334//243 550//13 +f 550//13 1334//243 1326//242 +f 550//13 1326//265 544//14 +f 544//97 1326//265 1325//264 +f 544//14 1325//305 542//485 +f 542//505 1325//264 1333//263 +f 542//485 1333//309 538//52 +f 538//51 1333//263 1332//261 +f 538//51 1332//262 539//54 +f 539//82 1332//261 1331//308 +f 539//54 1331//259 540//55 +f 540//55 1331//260 1323//257 +f 540//55 1323//278 541//17 +f 541//96 1323//257 1322//456 +f 541//455 1322//256 530//18 +f 530//43 1322//276 1321//255 +f 530//18 1321//255 531//44 +f 531//45 1321//255 1319//224 +f 531//196 1319//403 528//46 +f 528//75 1319//224 1318//285 +f 528//46 1318//253 526//486 +f 526//94 1318//253 1317//229 +f 526//486 1317//475 524//21 +f 524//92 1317//229 1315//395 +f 524//201 1315//395 532//84 +f 532//22 1315//228 1338//541 +f 532//84 1338//293 533//42 +f 533//49 1338//227 1337//241 +f 533//42 1337//258 534//1 +f 534//1 1337//226 1336//240 +f 534//1 1336//246 515//457 +f 515//457 1336//240 1341//458 +f 515//457 1341//458 516//27 +f 516//36 1341//458 1340//238 +f 516//27 1340//238 522//31 +f 522//23 1340//238 1339//231 +f 522//28 1339//237 523//29 +f 523//81 1339//231 1313//292 +f 523//29 1313//292 518//56 +f 518//86 1313//235 1312//507 +f 518//497 1312//477 519//57 +f 519//90 1312//236 1311//326 +f 519//57 1311//295 520//62 +f 520//62 1311//223 1310//222 +f 520//74 1310//266 521//15 +f 521//119 1310//222 1309//376 +f 521//15 1309//274 512//16 +f 512//16 1309//273 1307//272 +f 512//66 1307//272 513//518 +f 513//519 1307//272 1306//520 +f 513//518 1306//521 535//19 +f 535//19 1306//520 1305//270 +f 535//19 1305//275 536//20 +f 536//60 1305//275 1304//269 +f 536//101 1304//294 537//67 +f 537//61 1304//269 1303//267 +f 537//67 1303//267 545//24 +f 545//461 1303//281 1302//311 +f 545//24 1302//280 546//508 +f 546//508 1302//230 1301//232 +f 546//508 1301//542 547//30 +f 547//32 1301//542 1330//234 +f 547//30 1330//234 551//33 +f 551//33 1330//234 1329//288 +f 551//33 1329//251 552//35 +f 552//35 1329//291 1328//250 +f 552//35 1328//284 553//38 +f 553//39 1328//250 1327//453 +f 577//38 1261//469 576//41 +f 576//11 1261//469 1290//245 +f 576//41 1290//245 581//73 +f 581//12 1290//245 1289//243 +f 581//73 1289//282 582//13 +f 582//48 1289//243 1288//265 +f 582//13 1288//265 583//543 +f 583//543 1288//265 1287//522 +f 583//543 1287//522 584//50 +f 584//103 1287//522 1286//454 +f 584//505 1286//454 585//51 +f 585//51 1286//263 1285//261 +f 585//51 1285//262 586//54 +f 586//54 1285//261 1282//308 +f 586//54 1282//308 594//523 +f 594//524 1282//259 1283//525 +f 594//523 1283//526 595//17 +f 595//96 1283//525 1284//456 +f 595//455 1284//256 596//527 +f 596//528 1284//276 1281//529 +f 596//527 1281//530 587//45 +f 587//196 1281//529 1280//224 +f 587//196 1280//224 588//46 +f 588//75 1280//224 1279//285 +f 588//46 1279//285 589//47 +f 589//474 1279//285 1266//475 +f 589//474 1266//303 590//531 +f 590//531 1266//229 1265//532 +f 590//531 1265//532 591//22 +f 591//22 1265//532 1272//227 +f 591//22 1272//293 592//42 +f 592//49 1272//227 1278//226 +f 592//42 1278//258 593//1 +f 593//1 1278//226 1277//240 +f 593//1 1277//246 560//2 +f 560//476 1277//240 1276//458 +f 560//457 1276//354 561//27 +f 561//36 1276//239 1271//238 +f 561//27 1271//238 568//31 +f 568//23 1271//238 1298//231 +f 568//31 1298//237 569//29 +f 569//81 1298//231 1297//235 +f 569//29 1297//235 570//506 +f 570//506 1297//235 1296//507 +f 570//506 1296//507 571//57 +f 571//90 1296//507 1295//326 +f 571//180 1295//326 572//74 +f 572//74 1295//223 1294//222 +f 572//74 1294//266 562//15 +f 562//15 1294//222 1263//376 +f 562//15 1263//376 563//533 +f 563//534 1263//274 1262//535 +f 563//533 1262//536 567//64 +f 567//58 1262//535 1268//460 +f 567//459 1268//380 566//537 +f 566//538 1268//271 1293//539 +f 566//537 1293//540 564//60 +f 564//101 1293//539 1292//269 +f 564//101 1292//269 573//67 +f 573//61 1292//269 1291//267 +f 573//67 1291//267 574//24 +f 574//461 1291//267 1275//280 +f 574//461 1275//311 575//508 +f 575//508 1275//230 1274//542 +f 575//508 1274//542 579//30 +f 579//30 1274//542 1273//234 +f 579//30 1273//252 580//33 +f 580//80 1273//234 1258//291 +f 580//33 1258//251 578//35 +f 578//68 1258//291 1260//250 +f 578//35 1260//284 577//480 +f 577//480 1260//250 1261//213 +f 618//452 1624//248 619//481 +f 619//482 1624//213 1633//483 +f 619//41 1633//484 614//12 +f 614//12 1633//483 1631//243 +f 614//12 1631//243 613//13 +f 613//13 1631//243 1630//544 +f 613//13 1630//265 611//14 +f 611//194 1630//265 1657//264 +f 611//14 1657//305 625//485 +f 625//485 1657//264 1656//263 +f 625//485 1656//470 626//52 +f 626//52 1656//470 1655//261 +f 626//51 1655//262 627//54 +f 627//82 1655//261 1654//308 +f 627//54 1654//308 639//55 +f 639//55 1654//260 1653//257 +f 639//55 1653//278 640//17 +f 640//96 1653//257 1652//456 +f 640//455 1652//256 641//18 +f 641//43 1652//276 1651//255 +f 641//18 1651//255 628//44 +f 628//45 1651//255 1650//224 +f 628//196 1650//403 629//46 +f 629//75 1650//224 1646//285 +f 629//46 1646//253 642//486 +f 642//486 1646//253 1645//545 +f 642//486 1645//545 643//21 +f 643//92 1645//303 1644//304 +f 643//21 1644//395 615//22 +f 615//22 1644//228 1627//227 +f 615//22 1627//293 616//42 +f 616//49 1627//541 1626//226 +f 616//49 1626//226 620//1 +f 620//487 1626//226 1643//488 +f 620//489 1643//490 621//2 +f 621//476 1643//491 1642//458 +f 621//457 1642//354 622//492 +f 622//493 1642//239 1641//494 +f 622//495 1641//496 606//31 +f 606//31 1641//238 1640//237 +f 606//31 1640//237 607//546 +f 607//81 1640//231 1659//235 +f 607//29 1659//235 630//56 +f 630//497 1659//235 1658//236 +f 630//86 1658//298 631//90 +f 631//547 1658//236 1649//498 +f 631//547 1649//498 623//62 +f 623//62 1649//498 1648//222 +f 623//74 1648//266 624//15 +f 624//119 1648//222 1647//376 +f 624//15 1647//274 632//16 +f 632//16 1647//273 1629//272 +f 632//66 1629//286 633//518 +f 633//519 1629//272 1628//520 +f 633//518 1628//521 634//19 +f 634//19 1628//520 1639//270 +f 634//19 1639//270 635//20 +f 635//101 1639//275 1638//269 +f 635//101 1638//294 636//67 +f 636//61 1638//269 1637//267 +f 636//67 1637//281 637//478 +f 637//478 1637//281 1636//479 +f 637//24 1636//479 638//25 +f 638//200 1636//479 1635//232 +f 638//25 1635//312 608//30 +f 608//30 1635//232 1634//234 +f 608//548 1634//234 609//33 +f 609//33 1634//234 1622//251 +f 609//33 1622//251 617//501 +f 617//502 1622//251 1621//250 +f 617//501 1621//503 618//38 +f 618//39 1621//504 1624//453 +f 53//452 918//453 55//41 +f 55//11 918//453 916//245 +f 55//41 916//245 57//73 +f 57//12 916//245 914//243 +f 57//70 914//282 63//13 +f 63//48 914//243 913//242 +f 63//13 913//265 64//14 +f 64//97 913//265 930//264 +f 64//14 930//305 65//50 +f 65//505 930//264 929//263 +f 65//50 929//309 66//52 +f 66//52 929//263 928//261 +f 66//51 928//262 67//54 +f 67//82 928//261 927//308 +f 67//54 927//259 68//55 +f 68//55 927//260 926//257 +f 68//55 926//278 58//17 +f 58//455 926//257 925//456 +f 58//455 925//456 59//18 +f 59//43 925//276 924//225 +f 59//18 924//255 60//44 +f 60//45 924//255 923//224 +f 60//196 923//403 61//46 +f 61//75 923//224 922//253 +f 61//46 922//253 62//47 +f 62//94 922//253 900//229 +f 62//474 900//475 35//21 +f 35//201 900//229 899//395 +f 35//92 899//304 36//84 +f 36//22 899//228 897//541 +f 36//22 897//293 41//42 +f 41//49 897//227 896//241 +f 41//42 896//258 42//1 +f 42//40 896//241 911//246 +f 42//40 911//246 44//2 +f 44//457 911//240 910//458 +f 44//457 910//458 45//27 +f 45//36 910//239 909//249 +f 45//36 909//249 46//31 +f 46//23 909//238 905//231 +f 46//28 905//237 47//29 +f 47//81 905//231 907//235 +f 47//546 907//235 69//56 +f 69//86 907//292 908//298 +f 69//497 908//477 70//57 +f 70//180 908//236 933//326 +f 70//57 933//295 76//62 +f 76//62 933//223 932//222 +f 76//62 932//266 77//15 +f 77//119 932//222 939//376 +f 77//15 939//274 78//16 +f 78//16 939//273 938//272 +f 78//66 938//286 72//64 +f 72//459 938//272 937//460 +f 72//459 937//460 73//19 +f 73//59 937//271 936//275 +f 73//19 936//275 74//20 +f 74//60 936//275 935//269 +f 74//101 935//294 75//67 +f 75//61 935//269 934//267 +f 75//67 934//281 39//24 +f 39//77 934//281 901//311 +f 39//24 901//280 40//25 +f 40//200 901//230 903//232 +f 40//25 903//307 48//30 +f 48//30 903//232 904//234 +f 48//32 904//252 49//33 +f 49//80 904//234 921//288 +f 49//33 921//251 51//35 +f 51//35 921//291 920//250 +f 51//35 920//284 53//452 +f 53//452 920//250 918//453 +f 363//452 1197//512 364//41 +f 364//11 1197//213 1195//245 +f 364//41 1195//245 355//73 +f 355//12 1195//245 1194//243 +f 355//70 1194//282 354//13 +f 354//48 1194//243 1191//265 +f 354//13 1191//265 353//14 +f 353//97 1191//265 1190//310 +f 353//14 1190//305 365//50 +f 365//505 1190//264 1209//263 +f 365//50 1209//309 366//52 +f 366//52 1209//263 1208//261 +f 366//51 1208//262 367//54 +f 367//82 1208//261 1207//308 +f 367//54 1207//259 368//55 +f 368//55 1207//260 1230//257 +f 368//55 1230//278 375//17 +f 375//455 1230//257 1228//456 +f 375//455 1228//456 373//18 +f 373//43 1228//276 1227//255 +f 373//18 1227//255 371//44 +f 371//45 1227//255 1225//224 +f 371//196 1225//403 369//46 +f 369//75 1225//224 1223//285 +f 369//46 1223//253 337//47 +f 337//94 1223//253 1221//229 +f 337//47 1221//475 338//21 +f 338//201 1221//229 1220//228 +f 338//21 1220//304 340//22 +f 340//22 1220//228 1219//227 +f 340//84 1219//293 341//42 +f 341//49 1219//227 1218//241 +f 341//42 1218//258 342//1 +f 342//1 1218//226 1217//240 +f 342//1 1217//246 343//457 +f 343//457 1217//240 1214//458 +f 343//457 1214//458 334//27 +f 334//36 1214//458 1215//238 +f 334//27 1215//238 335//31 +f 335//23 1215//238 1216//231 +f 335//28 1216//237 344//29 +f 344//81 1216//231 1206//292 +f 344//29 1206//235 345//56 +f 345//86 1206//235 1205//236 +f 345//56 1205//477 346//57 +f 346//180 1205//236 1204//223 +f 346//57 1204//295 347//62 +f 347//62 1204//223 1203//222 +f 347//74 1203//266 348//15 +f 348//119 1203//222 1202//376 +f 348//15 1202//274 349//16 +f 349//16 1202//273 1201//272 +f 349//16 1201//286 359//64 +f 359//459 1201//272 1193//460 +f 359//459 1193//460 360//19 +f 360//59 1193//271 1192//275 +f 360//19 1192//275 361//20 +f 361//60 1192//275 1213//269 +f 361//101 1213//294 351//67 +f 351//61 1213//269 1212//267 +f 351//67 1212//281 352//24 +f 352//77 1212//281 1200//230 +f 352//24 1200//280 356//25 +f 356//200 1200//230 1199//232 +f 356//102 1199//307 357//30 +f 357//30 1199//232 1211//234 +f 357//30 1211//252 358//33 +f 358//80 1211//234 1210//288 +f 358//33 1210//251 362//35 +f 362//35 1210//291 1198//250 +f 362//35 1198//284 363//38 +f 363//515 1198//250 1197//453 +f 710//452 1580//512 711//41 +f 711//11 1580//213 1596//245 +f 711//41 1596//245 712//73 +f 712//12 1596//245 1595//243 +f 712//70 1595//282 713//13 +f 713//48 1595//243 1594//265 +f 713//13 1594//265 714//14 +f 714//97 1594//265 1593//310 +f 714//14 1593//305 715//50 +f 715//505 1593//264 1592//263 +f 715//50 1592//309 716//52 +f 716//52 1592//263 1591//261 +f 716//51 1591//262 723//54 +f 723//82 1591//261 1590//308 +f 723//54 1590//259 724//55 +f 724//55 1590//260 1606//257 +f 724//65 1606//278 725//17 +f 725//455 1606//257 1605//456 +f 725//455 1605//456 696//18 +f 696//43 1605//276 1604//225 +f 696//18 1604//255 697//44 +f 697//45 1604//255 1589//224 +f 697//196 1589//403 717//46 +f 717//75 1589//224 1588//285 +f 717//46 1588//253 718//47 +f 718//94 1588//253 1587//229 +f 718//47 1587//475 719//21 +f 719//201 1587//229 1583//228 +f 719//21 1583//304 720//22 +f 720//22 1583//228 1582//227 +f 720//84 1582//293 721//42 +f 721//49 1582//227 1615//241 +f 721//42 1615//258 722//1 +f 722//1 1615//226 1614//240 +f 722//1 1614//246 693//457 +f 693//457 1614//240 1613//458 +f 693//457 1613//458 694//27 +f 694//36 1613//458 1612//238 +f 694//27 1612//238 695//31 +f 695//23 1612//238 1611//231 +f 695//28 1611//237 698//29 +f 698//81 1611//231 1610//292 +f 698//29 1610//235 699//56 +f 699//86 1610//235 1603//236 +f 699//56 1603//477 692//57 +f 692//180 1603//236 1602//223 +f 692//57 1602//295 691//62 +f 691//62 1602//223 1601//222 +f 691//74 1601//266 690//15 +f 690//119 1601//222 1600//376 +f 690//15 1600//274 700//16 +f 700//16 1600//273 1609//272 +f 700//16 1609//286 701//64 +f 701//459 1609//272 1608//460 +f 701//459 1608//460 702//19 +f 702//59 1608//271 1607//275 +f 702//19 1607//275 703//20 +f 703//60 1607//275 1599//269 +f 703//101 1599//294 704//67 +f 704//61 1599//269 1598//267 +f 704//67 1598//281 705//24 +f 705//77 1598//281 1597//230 +f 705//24 1597//280 706//25 +f 706//200 1597//230 1586//232 +f 706//102 1586//307 707//30 +f 707//30 1586//232 1585//234 +f 707//30 1585//252 708//33 +f 708//80 1585//234 1584//288 +f 708//33 1584//251 709//35 +f 709//35 1584//291 1581//250 +f 709//35 1581//284 710//38 +f 710//515 1581//250 1580//453 diff --git a/examples/python3/cosserat/cosseratObject.py b/examples/python3/cosserat/cosseratObject.py index ae8ea527..0238ed41 100644 --- a/examples/python3/cosserat/cosseratObject.py +++ b/examples/python3/cosserat/cosseratObject.py @@ -179,7 +179,7 @@ def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): 'cosseratInSofaFrameNode') self.cosseratCoordinateNode.addChild(cosseratInSofaFrameNode) framesMO = cosseratInSofaFrameNode.addObject( - 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showObject=1, showObjectScale=0.1) + 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showObject=1, showObjectScale=0.001) if self.beamMass != 0.: cosseratInSofaFrameNode.addObject( 'UniformMass', totalMass=self.beamMass, showAxisSizeFactor='0') diff --git a/examples/python3/example1.py b/examples/python3/example1.py deleted file mode 100644 index 45c3120f..00000000 --- a/examples/python3/example1.py +++ /dev/null @@ -1,77 +0,0 @@ -# -*- coding: utf-8 -*- -""" - Cosserat class in SofaPython3. -""" - -__authors__ = "yinoussa" -__contact__ = "adagolodjo@protonmail.com" -__version__ = "1.0.0" -__copyright__ = "(c) 2021,Inria" -__date__ = "July, 20 2023" - -import Sofa -from useful.header import addHeader, addSolvers -from cosserat.cosseratObject import Cosserat -from dataclasses import dataclass - - -# [@info] ================ Unit: N, m, Kg, Pa ================ - -@dataclass -class CableParameters: - youngModulus: float = 1.205e11 - poissonRatio: float = 0.499 - radius: float = 0.004 - density: float = 7.850e3 - maxDisplacement: float = 0.3 - - GI: float =1.5708 - GA: float =3.1416e4 - EI: float =0.7854 - EA: float =3.1416e4 - L: float = 1. # beam length in m - Rb: float = 0.02/2. # beam radius in m - - -@dataclass -class CableGeometryParameters: - init_pos: list[float] # = [0., 0., 0.] - tot_length: float = 1. - nbSectionS: int = 5 - nbFramesF: int = 30 - buildCollisionModel: int = 0 - beamMass: float = 1. - - -YM = 1.0e8 -PR = 0.38 -rayleighStiffness = 1.e-3 # Nope -firstOrder = 1 -EI = 1.e2 -coeff = 1 - - - -# beam parameters -length = 1. # in m -Rb = 0.02/2. # beam radius in m - -geoParams = CableGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, - nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) -# inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, maxDisplacement=0.3, nbSections=20) -nonLinearConfig = {'init_pos': [0., 0., 0.], 'tot_length': length, 'nbSectionS': 5, - 'nbFramesF': 30, 'buildCollisionModel': 0, 'beamMass': 1.} -inertialParams = {'GI': 1.5708, 'GA': 3.1416e4, - 'EI': 0.7854, 'EA': 3.1416e4, 'L': length, 'Rb': Rb} - -isCollisionModel = 0 - -def createScene(rootNode): - addHeader(rootNode) - - node = rootNode.addChild('rootNode') - # solverNode = addSolvers(node) - cosseratNode = node.addChild( - Cosserat(parent=node, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, - useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, - rayleighStiffness=rayleighStiffness)) \ No newline at end of file diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index e8844dec..aeab6697 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -20,7 +20,6 @@ def addHeader(rootnode, multithreading=False, inverse=False, isConstrained=False """ settings = rootnode.addChild('Settings') settings.addObject('RequiredPlugin', pluginName=[ - "ArticulatedSystemPlugin", "Cosserat", # Needed to use component RigidDistanceMapping "Sofa.Component.AnimationLoop", # Needed to use components FreeMotionAnimationLoop "Sofa.Component.Collision.Detection.Algorithm", @@ -34,7 +33,7 @@ def addHeader(rootnode, multithreading=False, inverse=False, isConstrained=False "Sofa.Component.Setting", # Needed to use components BackgroundSetting "Sofa.Component.SolidMechanics.Spring", # Needed to use components RestShapeSpringsForceField "Sofa.Component.Topology.Container.Constant", # Needed to use components MeshTopology - "Sofa.Component.Topology.Container.Dynamic", + "Sofa.Component.Topology.Container.Dynamic", "Sofa.Component.Playback", # Needed to use components EdgeSetTopologyContainer, EdgeSetTopologyModifier, # QuadSetTopologyContainer, QuadSetTopologyModifier "Sofa.Component.Topology.Container.Grid", # Needed to use components RegularGridTopology @@ -46,8 +45,10 @@ def addHeader(rootnode, multithreading=False, inverse=False, isConstrained=False settings.addObject('BackgroundSetting', color=[1, 1, 1, 1]) # settings.addObject('AttachBodyButtonSetting', stiffness=1e6) + rootnode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels showCollisionModels ' + 'hideBoundingCollisionModels hideForceFields ' + 'hideInteractionForceFields hideWireframe showMechanicalMappings') if isConstrained: - rootnode.addObject('VisualStyle') rootnode.addObject('CollisionPipeline') rootnode.addObject("DefaultVisualManagerLoop") rootnode.addObject('RuleBasedContactManager', responseParams='mu=0.8', response='FrictionContactConstraint') diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py new file mode 100644 index 00000000..45c95a88 --- /dev/null +++ b/examples/python3/useful/params.py @@ -0,0 +1,27 @@ +# @todo use this dataclass to create the cosserat object + +from dataclasses import dataclass +@dataclass +class CableParameters: + youngModulus: float = 1.205e11 + poissonRatio: float = 0.499 + radius: float = 0.004 + density: float = 7.850e3 + maxDisplacement: float = 0.3 + + GI: float = 1.5708 + GA: float = 3.1416e4 + EI: float = 0.7854 + EA: float = 3.1416e4 + L: float = 1. # beam length in m + Rb: float = 0.02 / 2. # beam radius in m + + +@dataclass +class CableGeometryParameters: + init_pos: list[float] # = [0., 0., 0.] + tot_length: float = 1. + nbSectionS: int = 5 + nbFramesF: int = 30 + buildCollisionModel: int = 0 + beamMass: float = 1. \ No newline at end of file From 4d9de24ba9b5509f07dc9d15bea7904ccaaf20ae Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Sun, 30 Jul 2023 01:47:37 +0200 Subject: [PATCH 03/71] Reviving the FingerActuation scene, this illustration demonstrates the application of the Cosserat model in simulating a non-extending cable. In this case, the cable is utilized to control the movement of a deformable finger. --- examples/python3/__init__.py | 2 +- examples/python3/actuators/controler.py | 57 +++++ examples/python3/actuators/example1.py | 17 +- examples/python3/actuators/fingerActuation.py | 127 ++++++++++ examples/python3/actuators/mesh/finger.stl | Bin 0 -> 15384 bytes examples/python3/actuators/mesh/finger.vtk | Bin 0 -> 21102 bytes examples/python3/cosserat/CosseratPrefab.py | 232 ++++++++++++++++++ examples/python3/cosserat/__init__.py | 2 +- examples/python3/cosserat/cosseratObject.py | 3 +- examples/python3/useful/header.py | 211 ++++++++++++---- examples/python3/useful/params.py | 45 +++- 11 files changed, 629 insertions(+), 67 deletions(-) create mode 100644 examples/python3/actuators/controler.py create mode 100644 examples/python3/actuators/fingerActuation.py create mode 100644 examples/python3/actuators/mesh/finger.stl create mode 100644 examples/python3/actuators/mesh/finger.vtk create mode 100644 examples/python3/cosserat/CosseratPrefab.py diff --git a/examples/python3/__init__.py b/examples/python3/__init__.py index cc00b39c..f079f1ef 100644 --- a/examples/python3/__init__.py +++ b/examples/python3/__init__.py @@ -13,4 +13,4 @@ """ -__all__ = ["cosserat","useful"] +__all__ = ["cosserat","useful", "actuators"] diff --git a/examples/python3/actuators/controler.py b/examples/python3/actuators/controler.py new file mode 100644 index 00000000..00bb3d50 --- /dev/null +++ b/examples/python3/actuators/controler.py @@ -0,0 +1,57 @@ +import Sofa +from splib3.numerics import Quat + + +class FingerController(Sofa.Core.Controller): + """ + Implements the AnimationManager as a PythonScriptController + """ + + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, *args, **kwargs) + self.rigidBaseMO = args[0] + self.rateAngularDeformMO = args[1] + + self.rate = 0.2 + self.angularRate = 0.02 + return + + def _extracted_from_onKeypressedEvent_10(self, qOld, posA, angularRate): + qNew = Quat.createFromEuler([0., angularRate, 0.], 'ryxz') + qNew.normalize() + qNew.rotateFromQuat(qOld) + for i in range(4): + posA[0][i+3] = qNew[i] + + def onKeypressedEvent(self, event): + key = event['key'] + if ord(key) == 19: # up + with self.rigidBaseMO.rest_position.writeable() as posA: + qOld = Quat() + for i in range(4): + qOld[i] = posA[0][i+3] + + self._extracted_from_onKeypressedEvent_10( + self, qOld, posA, self.angularRate) + + if ord(key) == 21: # down + with self.rigidBaseMO.rest_position.writeable() as posA: + qOld = Quat() + for i in range(4): + qOld[i] = posA[0][i+3] + + self._extracted_from_onKeypressedEvent_10( + qOld, posA, -self.angularRate) + + # Pull the cable base + if ord(key) == 18: # left + print("left: the cable is pulled") + with self.rigidBaseMO.rest_position.writeable() as posA: + posA[0][0] -= self.rate + print(f' The new position is : {posA[0]}') + # release the cable base + if ord(key) == 20: # right + print("left: the cable is released") + with self.rigidBaseMO.rest_position.writeable() as posA: + posA[0][0] += self.rate + print(f' The new position is : {posA[0]}') \ No newline at end of file diff --git a/examples/python3/actuators/example1.py b/examples/python3/actuators/example1.py index ae9d7751..f927677e 100644 --- a/examples/python3/actuators/example1.py +++ b/examples/python3/actuators/example1.py @@ -11,7 +11,7 @@ __date__ = "July, 20 2023" from useful.header import addHeader -from useful.params import CableGeometryParameters +from useful.params import BeamGeometryParameters from cosserat.cosseratObject import Cosserat import os @@ -19,11 +19,12 @@ path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' -# @info Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) -# et de 13 disques en iglidur. -# -# "-La colonne mesure 65.5 cm pour un diamètre de 6.2mm" -# +""" @info +Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) + et de 13 disques en iglidur. + + -La colonne mesure 65.5 cm pour un diamètre de 6.2mm + # -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g # # -Les disques sur la colonne sont espacés d'environ 4.7cm @@ -42,7 +43,7 @@ # Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 # passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. # [@info] ================ Unit: N, cm, g, Pa ================ - +""" YM = 1.0e8 PR = 0.38 @@ -56,7 +57,7 @@ Rb = 6.2e-1 / 2. # beam radius in cm # @todo use CableGeometryParameters & CableParameters in Cosserat class for both geometry and physics parameters -geoParams = CableGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) # inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, # maxDisplacement=0.3, nbSections=20) diff --git a/examples/python3/actuators/fingerActuation.py b/examples/python3/actuators/fingerActuation.py new file mode 100644 index 00000000..a976f17e --- /dev/null +++ b/examples/python3/actuators/fingerActuation.py @@ -0,0 +1,127 @@ +# -*- coding: utf-8 -*- + +"""_summary_ Basic scene using Cosserat in SofaPython3. + The Finger is modeled using FEM model while de cable is modeled using cosserat theory. + The link between these two mechanical models is performed by constraint based on Lagrangian Multiplier + +Returns: + _type_: _description_ +""" + + +__authors__ = "Younes" +__contact__ = "adagolodjo@protonmail.com, yinoussa.adagolodjo@inria.fr" +__version__ = "1.0.0" +__copyright__ = "(c) 2020,Inria" +__date__ = "july 2023" + +import Sofa +import os +from cosserat.CosseratPrefab import CosseratClasse +from useful.header import addHeader, addVisual, addSolverNode, Finger +from controler import FingerController + +path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' + + + + +femPos = [" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"] + + +def createScene(rootNode): + rootNode.addObject('BackgroundSetting', color='0 0.168627 0.211765') + addVisual(rootNode) + + addHeader(rootNode,isConstrained=False) + rootNode.addObject('FreeMotionAnimationLoop', parallelCollisionDetectionAndFreeMotion=False, + parallelODESolving=False) + rootNode.addObject('GenericConstraintSolver', name='ConstraintSolver', tolerance=1e-20, maxIterations=1000, + multithreading=False) + rootNode.findData('gravity').value = [0., 0., 0.] + + femFingerNode = rootNode.addChild('femFingerNode') + + """ Add FEM finger to the scene""" + fingerNode, femPointsNode = Finger(femFingerNode, name="Finger", rotation=[0.0, 180.0, 0.0], + translation=[-17.5, -12.5, 7.5], path=path) + """ + Add Cosserat cable to the scene + """ + beamGeometrie = {'init_pos': [0., 0., 0.], 'tot_length': 81, 'nbSectionS': 12, + 'nbFramesF': 30, 'buildCollisionModel': 0, 'beamMass': 0.} + + cableNode = addSolverNode(rootNode, name="cableSolver", isConstrained=True) + cosseratCable = cableNode.addChild( + CosseratClasse(parent=cableNode, cosseratGeometry=beamGeometrie, name="cosserat", radius=0.5, + youngModulus=5e6, poissonRatio=0.4)) + + mappedFrameNode = cosseratCable.cosseratFrame + # This creates a new node in the scene. This node is appended to the finger's node. + cable3DPosNode = mappedFrameNode.addChild('cable3DPosNode') + + # This creates a MechanicalObject, a componant holding the degree of freedom of our + # mechanical modelling. In the case of a cable it is a set of positions specifying + # the points where the cable is passing by. + cable3DPosNodeMO = cable3DPosNode.addObject('MechanicalObject', name="cablePos", position=cosseratCable.frames3D, + showObject="1", showIndices="0") + cable3DPosNode.addObject('IdentityMapping') + + """ These positions are in fact the distance between fem points and the cable points""" + distancePointsNode = cable3DPosNode.addChild('distancePoints') + femPointsNode.addChild(distancePointsNode) + mappedPoints = distancePointsNode.addObject('MechanicalObject', template='Vec3d', position=femPos, + name="distancePointsMO", showObject='1', showObjectScale='1') + # cableBaseMo = cosseratCable.rigidBaseNode.getObject('MechanicalObject') + # cosseratCoordinateMo = cosseratCable.cosseratCoordinateNode.getObject('MechanicalObject') + + """The controller of the cable is added to the scene""" + cableNode.addObject(FingerController(cosseratCable.rigidBaseNode.RigidBaseMO, + cosseratCable.cosseratCoordinateNode.cosseratCoordinateMO)) + + inputCableMO = cable3DPosNodeMO.getLinkPath() + inputFEMCableMO = femPointsNode.getLinkPath() + outputPointMO = mappedPoints.getLinkPath() + """ This constraint is used to compute the distance between the cable and the fem points""" + distancePointsNode.addObject('QPSlidingConstraint', name="QPConstraint") + distancePointsNode.addObject('DifferenceMultiMapping', name="pointsMulti", input1=inputFEMCableMO, indices="5", + input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position") + + + + return + + + + # ############### + # New adds to use the sliding Actuator + ############### + cableNode = rootNode.addChild('cableNode') + cableNode.addObject('EulerImplicitSolver', firstOrder="0", + rayleighStiffness="0.1", rayleighMass='0.1') + cableNode.addObject('SparseLUSolver', name='solver') + cableNode.addObject('GenericConstraintCorrection') + + + cosserat = cableNode.addChild(Cosserat(parent=cableNode, cosseratGeometry=beamGeometrie, radius=0.5, + useCollisionModel=True, name="cosserat", youngModulus=5e6, poissonRatio=0.4)) + + cableNode.addObject(Animation(cosserat.rigidBaseNode.RigidBaseMO, + cosserat.cosseratCoordinateNode.cosseratCoordinateMO)) + + + mappedPointsNode = slidingPoint.addChild('MappedPoints') + femPoints.addChild(mappedPointsNode) + mappedPoints = mappedPointsNode.addObject('MechanicalObject', template='Vec3d', position=FEMpos, + name="FramesMO", showObject='1', showObjectScale='1') + + inputCableMO = slidingPointMO.getLinkPath() + inputFEMCableMO = inputFEMCable.getLinkPath() + outputPointMO = mappedPoints.getLinkPath() + + mappedPointsNode.addObject('QPSlidingConstraint', name="QPConstraint") + mappedPointsNode.addObject('DifferenceMultiMapping', name="pointsMulti", input1=inputFEMCableMO, + input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position") + # Get the tree mstate links for the mapping + + return rootNode diff --git a/examples/python3/actuators/mesh/finger.stl b/examples/python3/actuators/mesh/finger.stl new file mode 100644 index 0000000000000000000000000000000000000000..c51bd9cd0130fa9d0f85e9b9ba75fd125fce7530 GIT binary patch literal 15384 zcmbtadyE}r6(6tyHie4Wq$TxH1G`H}ObRRytL)CCi6n(kW2uh-f=ekjwP7M8@(PYs zN((7LYL!>8(r(K`5mYd+u(vygstDDh2%%IA5(NHeZUQz%`NMPOn=`-P`S#9A;v{?b z+?n$`zw`PY_q%uTH!u0x6_>1-KYG>tGuK@H_2mD(PCCRa6eB8a8o#Sdk~|CY1CT$n zt(NmtpXn7N@@!M1HI!`{H*~PZh{w&AAbwfPim?0LRJHYrIl3u0@)R63q5#5diC5$a z^Hl^rI22)7V7{R$D~d9&j6=0J4vT!+I2x~};V9s{)TZH($eT>J*FzDg8pjkzZgFV+ zP3D-Uav(y-K_12&hKRbPL9}N#ioD5N%~15LN24`u9K?<|xOcUJL&uyo^7ISyMm8@v zYvAS4jnc1M>8ta$YLy00Mb{mF+yb}Ph_>u=u9T1)z_6@<>S zZ3y32UJKlHUsW7}*a5rU)cDjB+*eMid4qthB!S#bAG&XS`Ges@vWxD$I(3La*y^T` zljMxo*OtqdpOLM&^eRFuUUllAd7|TnwHOVKFRl6G7$e|SlJxd!#wj!V4WZF8M{mR{ zAN})yA=E3@Vl=$kJ+Xpn?z78iAU4jMGk^%YDcd#f&?VwPVRPb=zOOc&v7|30+3su2 z!xdIFXlXs5h5PY(4y`1Chbpfzz9}4LH6vwY2e_(G{XVc5U3nxiXGCjX4-$S{gY#bO?#up7@NihYpbd5yxSC@6W4TvS8jC z10v^KnXDcnZ-%kH;y9p%zEXW#KOVpD$Nihe7fKCuebpUVki+a_eD&-zqO<723vZKo z_mhIylEw%_hdI(XbWQ}j<_dNV5k?dtWYmHKvg|U*L&OngQM21k=be9QGpm7*BNv41 zGK@nkJ%2(obK-tIQ&*AS`Q|~2T=#I6H;;x_hdnwft24CN6ZQ~@8K>OX&z`WBS@OBs zbKM29%K!%>*b+E~zCCx0BV;YJ(JKPz)0vddb`S8-Hp)NgNILD|i-{+Sqatx#_D4;VTFZwaf9rt6Q$VXOKA{cT?l=UI_B-JuNkwSwU?uV4#yyD6jF5FCdh%)=;-0(KQ) zUgd%??sl)(6Ga$0{yYdxL`B_<=Z(VTK7<^Z|7fA1h zwcX^GWc&m1`J-0~0$QRih_JTXeUEr*#zQ-Lai|vVYt79oaj<}0&1m2YcEJaPa164o z^WM8+Qa?LiD6=T;i(TfBcV-mASXV%jP_n3Ki!n=T1G-`)V7V+scH?NxL*yywhgap$3tE!lR90rm!c>H6VZDPK zAqvIfG7i#~hez&BN&sina@U4WbCo)L*;cJA2q5 zYBkleT&Z32iqM6`(h+s}ZsqW7? z_-1OzfUtMSmEO@$-c$KvjwE5b%x6|(M4mC?wAp%Qt(Rq_j$C%d{jz3Ez22W!u=niV>v}F~eA7i&{y4%K7eCbKi5|NuI&0Je&F0&l|M)5po4YlCT!g zrf*#Wukwt&T6WR8-W-KwvCgiZCw{omk_y)MZQNL{z>y?um-)=E5Cvqu;ln zHl72X=t#Y?iB`}}M%oa1$^``XSUUoCJ=!6(f(<*{Wj=?{j5fLAI&)9Q2+NNjwWw2^ zU5o>*8Zy2A(uyNk>2-`ELmdOFFx`9Iw$HNx$nXHIh{tTfKIP|<#JyZ^p8S(5h z&kSx@zkU#iUg#bOITy9az3;ehkqgHTaHuE75$v*u`mE^Gh?+wY#-TFDq5HXu{<5lb z;E~DUEB72T{MS>SEq}e}$ZX~dpP(A#*@0JnSI#{)6Kx%}6Mffo%BRj8-v7q+#9?*= zA6rV26Zf9mdFj(fjr?lS_XgM&fVYFt~yc#?GyW1H7zHSOx86{5>lCKfX6`p8zb*yM^^6ahAvYhwa#Z?ZI zMDjGz>AR--)eApi1Z4F}^3)N}Mvgyt({YRdAA6;olBWsD*NEoI5SkO%70;UrY8>np zw6ua2N0P85cy-C%ySA|{$lcTI_SM(ZyBYzvK2?~<7}aw!@k2- zeg58&v!Ktat5C1_1d=1SGyPguRD+~(;5$gR%X|$=1kZtUQD6TCQ78hxdcp5~RAbr4 zww5pcLQgpBs|f!Ufp5vU&iH1_Ao5>OMF*#9dcubDz4lJTK2g2G{y~3J_No27`ic>( zHC-Hc)pM-r_5iR%CBhOzxdH%AsDQm0jbH(}LYBs0}!E*`E zANDZr8uKJ<{N|v zMTfJ<*`3n63M=C5a<@;(l_KQwqn4xPn1XJ2^>ZS33HPx_aLsuXv4UzkKh@OJA*sM zBX~q{XACddRW99sa?08&YbRo^Wkh=gdC$Q4;Y>4+_7(OeJU)Dn0pn)|_C3T0O_LOH zj?7o#;tuD|x99pl-jQLpJ7V1pabib$VX+Se~KtaT=vKMOe4XnM||umNV;SM?MvS6EBRe z7LGzWP>(#@eB;^W`0OKO-?#XRr1PL(f+sit1Gm z%)xfCGl;#yEuJ6HW`8QecH!!k{ie*dgU1I} z0RNp%!%@`T-i!&3gV7B_1nphhh3n~ut?fPw6+-Om@~u&9Oh{v%WlQ zNAR48op+usIQR7Owe=g)Ub7EoQP#rx5qrgBkmnMvKQg6V!efocAZOYmc&u^nzQ62p zex~boj9T`cv(R`|gb`&Y6TV-kbctx|r6bBdc}WGEU9lfsK{vemS#;LPYs*f#In}Ch zragj3Dsyn&JOcY@zmjonDnt=*ey!#8l`X{xj1P{3SBYRR+@66u zV@l*=UoWkPeXh+j?8sV1RG|p$)qDlH$139$L5Rb?we%|)=glK{U&6iAK0dIs^l@-} z4TlJRU&0;Eo$nDm!|}{H`-&UNeIql{UULa*&RXpi}kd>+BMV!n0` sj+Xh_Ik8fawGs3;H>W)v&N zah#OSRE$L`$vaa{5{*e5hf16zlNmFWm`Y40WEsq2oafhlpVyaa!OTZ&b^gY6>}z6&8e7Dvb40KtR%O5R@uE( zm6@RPQzhuCoQ}^dxxv8EkKJky{4t#6U)o)l& z>dE45kB7dv=;_0M^_2C*Ka00LF0A*ssh%v}{?3=}pUr3c+y3WP`^O8uy=~#&y!N-* ze%XAse|A0gH=p=t&0EyXMXg4-*0^( zDyZAM4KatyYhJ?#+Rw^(4=j z0nGo4=97A|c-yn*KgrX-?j3z5oa^=^PZsYywrBUpyw@au{hYsa6JPk^qWxbS^=tE9 z;}LcIZ>)QbCpA1Z=2FF0>t5rMKjU9k_rCtleqQ5Qeot4`eTU5Z-P zeOIpCi315 zYnPkG6{X+b_5R}TN0~YNDx+Q_Ui-o4IvkGczdvszdGbe$TXgx`6XWvxzVhU}i9d~c zzrgQPQL6#(?=1M#uj1M5M>TFcZcvoz{r17$Z|{j(&1wFJF}vT6>%TuAf3LdLcP^fJ zneWwQ_bcf`Ht+M6{oqD_^Yz~)zw4aHbxv9M-2R6BejMsK7V3E`p8B<8<@*XYh5BDg z>aYJUef6gE7XN0>g;_s58TwNm{C^!6)$aNGZ~v@8=;xu3|DWRe@6yNLF`sw*`+Ub< zNY3l}M{f92{Pj4S?^RRRxHvmc{k{JouK$ibpRT{;wpV{25Bke9ONO7%ggPIf&Y%7A z{h!5szIW#jpBsE7oNEE+T6?BtX&nAtmCS!(-F*J>CO&UBzb$?T(QWmT@9`$S{=C14 zE0>*ntzqSf#P0sgxt>3KU#C?GU;kb{ipSje?}w<~zd>AF_Z_=4@pqom8^2e+>{>XKeWJjh<)DX7LT;?sa)Ke$2-ocKh;ww20@uSN4^* z|M_6Tcb(Mm-7#JMCH%YPrKnNed;ZA%xrujw>c1yH4&RwZ;qS`_@q*{BeEFTR&qw*6 zo_n?CeB-F#ckh;drrn;K__lBI`*J*g#^RC9zV%)-VBh5Bjb{He@z3V%KjNk7m1lpl zGRl0d|66zb_KMFDmt9!e@tM9?qs;X&i+(xqj|pG3;)TuY3qBp?k6QTQ*e^Yu@a?v} z_vx#JPe+Y94S8waE8k1_%3dv3=70U&D6iSlYtOEEGT~>wJUV~D`U_F_s@7kB=PRod ze*E`#e)EGQzn_^8|M9WR+&2<_ez)BfSI*T&o%b$&<&m`|316CX z_+b9)nW)W@{eQ9Zua_tMpnb1Ad;Y@nQS0gJPyhCfB?(`2`Nu{> zk?>i4PWa0Fny+3y@?4Zx{O;Swe_WgJGe7&ylUIJyGwNROX8i8PaS5N*=Y-GdbHZo! zIpIrlk9Vn@@>ihbZU7@1JdO?ZJev{LaZ(mlWOkas%!vD(rNbHJ)EQIzs=S_zveE zz(05Llo>NBGoy!$$qXMcdStGsx_n_p1`Wg7D6Gr@eB-b-32W1^^6v-i{5zD@d7B5l zMOa&gm4Aoh*D9>7!`ddSd0}lER=(o+w-0NFu=2fx=ih&cfY{1a_{&P z*FVUt_`wr5AjqutXHEtNo|SpQpSVFmX2lPlxWPeYwLkMUB=D@v8UDl#4Kgc!@Wc%Z zGOPWW%i)1%Wj^tTcPyO!ncEQpKCH|yGCVQJaL&VAj|@C3^KJi8L1w)>$gHD-%sM8> ztYd@BIxfhpgNS+>eR{R?Uop(Mn=y0Z zo}gpL7a#2QAqO&X*z8X{vhD1Bui*Wu8yP?1`H=%3bYihvXK!+Oe~EQA@_K(_?2jM* zuIDz%e4ok%{MjEF4jnr>-!|K+&Hiw+1=rhHGQJf8HjokULB@_PBcPK9oBcCEwm*51 zy&t)e?N7b}p;90pa?_NK9h>XV4>~^hb3SZyf{wk3P!;qZL59O0of!L*8(-_#ksVKN zd~7E_HrLxr^6kQ0f&7I*hC}Zuu=o6+<3CSu{p3T2!yh}jtdnm+;IQM5-TBb*_5SRK zjTrplk<?@sj|_*sudqRu}HuNfAl^A z96B<-#Gu0?J3n@G`;!ORcJ@PdJoO9^77OHS8Duzg?ATln_I`oGPJP&x2io55DBEy;|~$pwl0GY^Ppw*pAGZTo3iLr}rnGSn4D{ z@xz2wK}T+r(y?PBFaASsrC}Q7^jf=-A-MhyU=Dj*PGE_@lE2{_Ka2ANq(O-yd}HwHK^oUoY67 zc=UFH=c}j-1wk(5U}Bcjz4;7&_`({SK5D~ zbbRn{FH90_A1`@>FhRgRRUp^Kpu;1R1N#&K|7}4p(z;pL6m;@o!v}x#af1CvOU9QN z=fhSK^kS`B1l!r4T&`zKu;Jr+v3b8pGBvp#_9GW@_@mz~*gjb@x!4!`SOH(>k0fsu z=oxlm(H)OY&*88~0ygXPliKJTcJ`qjYDA|u?72PY$n0%>a*$mQI=!-;cx3k%8?x=( zC3o-sQ7d=v`nXqYo)6B6&GRu*@-AVTK)uY{T>>0>N1=nTJLvf1YaJV$b>fMIb38WZ zCpWV5@0AQUUBDk3Iy^f3o|IlDnVR+q*jdq?A02=E9N$3l{-Cp>cS`B_d;bHH`8ggx ze(>aj$KN{n@JZ{)__#i5^LgN@(fWAFyn!PE{<*?QVNB5P)_P1h81&IvvEhUNSmCH} zDCpSnCk}g_&`zik(3vOvi9;VHv=(Xv^d3SJ0Uz`h!ZD$L(0gjdhL7!oB;$kLQ0Oik z4tgK0)YdHMcW50d_&l7Q8LbtFM@M!%`H;H^*x8?4J}(1-^P#JNM^570(NZVww-%p?~?*{>W8yVJhAQ%^MUUAxexMrKIsRwo)*Z* z-JyFw=8xR$iJdv*{JtOJiR~a@XAU{5`^SAz%NYSXGWA$zKjPgl>c!^slNURF#M8eT zfj8j&*vs#W{fH+IcIu^8;?Q|NHG=y;Rq_D-vvA9iem1@;4<5HdmT ztMzt)8nLw!IM1-4bN+42RDCbd0y`WPcz43Xeh5opnjAYJ|-jBU}UUC!b{M-*` zbG_7uFFj$u0^yT_?*ksY`!zr^vqBB77abm*{t!`LLCBd{t@uwB>^IL{6`cS$Ye>nf0sxrN&)FdNLpF2S5<1sfcFW}YeqW)F_LiUj&e zU*TE`oSj)8Ai%8muO+!M&=MOnnChY9tmP>Ph>dvj=h1h#wrjss(xt#~%BHj)M0fmYx#pnz=(}Wv=k3 zK&?t%6;Fw+V%@!I7aOCBj`-M&doclsgxOX^ah54p7&p3Bj%rJi4gz*A%xJ`ijq)-y{?SZ2&{5_!$ejm)hG~trKED#Gk({qB(9&qU1 zLt@=`;(*pNfjI7-e(|@*@0a^#Z_dj8_>qqq$yF)9Z4jmkoR_o1H5MKbGD3v_*GE_+ z+$Z=ht0gl>^we|U85kh0xj<}KJ3Byh~@p>B@nwyfFl?8na;<1 z9xE^d;{^Pug*j(#sR@p=QcwEc=r{L79pwUkeuIUQ9|~NJR(k53`0<{7AKW`!Mqp-V z3qBjYTP^rIf!|D_R>0>T0ghbE5O?Z)^oo2L!TJ3C;vVw_V)>qv?|^Wx0LQG27r0Z- z2uJUDgSkMNlxz#S5JBh7^S1UULe59!@m0WN)Z-!DDJ51%3dzu^LR%Xyg{ zxMJa)&|K&(z_l0X$Nd7na1#a2GC`;n;M{vSYJeLl>=e?yXTGNidj-!p`+JXvB@;`1 z@a)OnaQILUy8YnrOV>wjyy;rOGsOHM!(k&|TY-G!@*dnb^HwQr7w{uLzG=UK(wTvS z0<(^vXOg?Sl;RpleoV-|OYYI%I%0@V`_X6mN3PQXd(gLO0^CIbj(VxPO6VcLRSLZ8 z?E-eVuEH!Ky~jf74+-alz5;$e2k(ly;65Q_1m1Zg0gf8zHThf%d$KogYo34~v%%a? z5qRHlo{{d7J*V6Ye42AD>~%mOcDZneK;I7vaMc3$u|jxIfO9|T|Ng-7R#pnjgnofr zqII*dSn%8rkxV|mVOs_7F<3J3-lLi1LV@?med5PCn74*P7XglYq*t87z3MEP`$+fn zap|SOhrSX!QXrlm1Z z(HGtvJsBmy(Q|s$N^oENx0YD;!jC)S?gk0IH_l35sKw{yUhy3&*v~!X4X5XY*a-qW zdyvoP#Rlg)=f3@&^qexI`B{GWR0oc}aOU#@XCxoW;-9_>~B}g+~Qyf@6m1G4o8%;kX~}i9M(Xj&ooq z&gYO=_iw>;Ej8kNm+d4I+d^QbIWONLxTeB9fm+xfj=h+%PQqgXT(v;`#4*Qk*zXnC zmmeH=9tqrckpQumrswEE==+z1VKjwltm@Zrt;F#ye!W7|20gm}j z^KcsihYer2hlE4I7J(kZ@#7q|LKgv!x~MOGj*ZgEIYD?zz^}6~Q)nnKgK!nX?4a9^ zxos^B71jv&QO81|P@pb2@*fe>dvISXg=&HO!>^e@Jh2M|IA-W}p_kx%)XZJh3YP@@ z774`OCwQLWdFRYm4*{Kbz&j*vw*W^^{1%vXxT6BGRRZyFvxKg~Cxk`6Nud>P)kR_wKS2;-t6m|edpZ4BLcDHaeemV?<#$!4&Tud$<&js z1nIIh_FMLBy1Jz z$2;eZ*9MNW5j!Epb(Ty{_T=plOU?9jv2a#^>UNi`aAiMxI%&0g#!JfPxK3pUU6UCWr+aC8^^b~ z&|83GHWml{Lg3hgeC$EL@q;@mz?<{E*@ho6==k`K*b|=GsKNQ*III2W0kLV0chFvV zSl~Sn+gcbRFkhntxCez*!dBs+0JmJYLl`Km7T|^nZG`gz{&4hwZ(zDF=Q>ye(#Ym%zRg z1>Vdhp;mySZ=9drw5|Jp(3Vy$D4$aIKceM|Yw&-BM%w2V{`Y#&SpB_)TRpfn1Gi@2 a|MLv+H|Z8`_2AYF+?s(~GjMALa{n7&>KBUu literal 0 HcmV?d00001 diff --git a/examples/python3/cosserat/CosseratPrefab.py b/examples/python3/cosserat/CosseratPrefab.py new file mode 100644 index 00000000..e2a9e9a9 --- /dev/null +++ b/examples/python3/cosserat/CosseratPrefab.py @@ -0,0 +1,232 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "adagolodjo" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "October, 26 2021" + +import Sofa +from cosserat.usefulFunctions import buildEdges, BuildCosseratGeometry +from cosserat.utils import addEdgeCollision, addPointsCollision +from useful.header import addHeader, addVisual, addSolverNode + +cosserat_config = {'init_pos': [0., 0., 0.], 'tot_length': 6, 'nbSectionS': 6, + 'nbFramesF': 12, 'buildCollisionModel': 1, 'beamMass': 0.22} + + +class CosseratClasse(Sofa.Prefab): + + """ + import Sofa.Core + + class Foo(Sofa.Core.Prefab): + prefabParameters = [{ 'name': 'n', 'type': 'int', 'help': 'number of repetition, 'default': 1}, + {'name': 'message', 'type': 'string', 'help': 'message to display', 'default': ''}] + + myAttribute = 0 + + def __init__(self, *a, *k): + Sofa.Prefab.__init__(self, *a, **k) + + def init(self): + myAttribute += 1 + for i in range(0, self.n.value): + print(self.message.value) + + Cosserat beam prefab class. It is a prefab class that allow to create a cosserat beam in Sofa. + Structure: + Node : { + name : 'Cosserat' + Node0 MechanicalObject : // Rigid position of the base of the beam + Node1 MechanicalObject : // Vec3d, The rate angular composed of the twist and the bending along y and z + Node1 ForceField // + MechanicalObject // The child of the two precedent nodes, Rigid positions + Cosserat Mapping // it allow the transfer from the local to the global frame + } + + """ + prefabParameters = [ + {'name': 'name', 'type': 'string', 'help': 'Node name', 'default': 'Cosserat'}, + {'name': 'position', 'type': 'Rigid3d::VecCoord', 'help': 'Cosserat base position', + 'default': [[0., 0., 0., 0, 0, 0, 1.]]}, + {'name': 'translation', 'type': 'Vec3d', 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, + {'name': 'rotation', 'type': 'Vec3d', + 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, + {'name': 'youngModulus', 'type': 'double', + 'help': 'Beam Young modulus', 'default': 1.e6}, + {'name': 'poissonRatio', 'type': 'double', + 'help': 'Beam poisson ratio', 'default': 0.4}, + {'name': 'shape', 'type': 'string', 'help': 'beam section', 'default': "circular"}, + {'name': 'radius', 'type': 'double', + 'help': 'the radius in case of circular section', 'default': 0.02}, + {'name': 'length_Y', 'type': 'double', + 'help': 'the radius in case of circular section', 'default': 1.0}, + {'name': 'length_Z', 'type': 'double', + 'help': 'the radius in case of circular section', 'default': 1.0}, + {'name': 'rayleighStiffness', 'type': 'double', 'help': 'Rayleigh damping - stiffness matrix coefficient', + 'default': 0.0}, + {'name': 'attachingToLink', 'type': 'string', 'help': 'a rest shape force field will constraint the object ' + 'to follow arm position', 'default': '1'}, + {'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'}] + + def __init__(self, *args, **kwargs): + Sofa.Prefab.__init__(self, *args, **kwargs) + # self.bPhysicsParams = kwargs.get('beamPhysicsParams') + # self.bGeometryParams = kwargs.get('beamGeometryParams') + + self.cosseratGeometry = kwargs['cosseratGeometry'] + self.beamMass = self.cosseratGeometry['beamMass'] + self.parent = kwargs.get('parent') + self.useInertiaParams = False + self.radius = kwargs.get('radius') + + if self.parent.hasObject("EulerImplicitSolver") is False: + print('The code does not have parent EulerImplicit') + self.solverNode = addSolverNode(self.parent) + else: + self.solverNode = self.parent + + if 'inertialParams' in kwargs: + self.useInertiaParams = True + self.inertialParams = kwargs['inertialParams'] + + self.rigidBaseNode = self.addRigidBaseNode() + [positionS, curv_abs_inputS, sectionsLength, framesF, curv_abs_outputF, self.frames3D] = \ + BuildCosseratGeometry(self.cosseratGeometry) + + self.cosseratCoordinateNode = self.addCosseratCoordinate(positionS, sectionsLength) + self.cosseratFrame = self.addCosseratFrame(framesF, curv_abs_inputS, curv_abs_outputF) + + def init(self): + pass + + def addCollisionModel(self): + tab_edges = buildEdges(self.frames3D) + return addEdgeCollision(self.cosseratFrame, self.frames3D, tab_edges) + + def addPointCollisionModel(self, nodeName='CollisionPoints'): + tab_edges = buildEdges(self.frames3D) + return addPointsCollision(self.cosseratFrame, self.frames3D, tab_edges, nodeName) + + def addSlidingPoints(self): + slidingPoint = self.cosseratFrame.addChild('slidingPoint') + slidingPoint.addObject('MechanicalObject', name="slidingPointMO", position=self.frames3D, + showObject="0", showIndices="0") + slidingPoint.addObject('IdentityMapping') + return slidingPoint + + def addSlidingPointsWithContainer(self): + slidingPoint = self.cosseratFrame.addChild('slidingPoint') + slidingPoint.addObject("PointSetTopologyContainer") + slidingPoint.addObject("PointSetTopologyModifier") + slidingPoint.addObject('MechanicalObject', name="slidingPointMO", position=self.frames3D, + showObject="1", showIndices="0") + slidingPoint.addObject('IdentityMapping') + return slidingPoint + + def addRigidBaseNode(self): + rigidBaseNode = self.addChild('rigidBase') + + # trans = [t for t in self.translation.value] + trans = list(self.translation.value) + rot = list(self.rotation.value) + # @todo converter + positions = [list(pos) for pos in self.position.value] + + rigidBaseNode.addObject('MechanicalObject', template='Rigid3d', name="RigidBaseMO", showObjectScale=0.2, + translation=trans, position=positions, rotation=rot, + showObject=int(self.showObject.value)) + + # one can choose to set this to false and directly attach the beam base + # to a control object in order to be able to drive it. + if int(self.attachingToLink.value): + print("Adding the rest shape to the base") + rigidBaseNode.addObject('RestShapeSpringsForceField', name='spring', stiffness=1e8, angularStiffness=1.e8, + external_points=0, mstate="@RigidBaseMO", points=0, template="Rigid3d") + return rigidBaseNode + + def addCosseratCoordinate(self, bendingStates, listOfSectionsLength): + cosseratCoordinateNode = self.addChild('cosseratCoordinate') + cosseratCoordinateNode.addObject('MechanicalObject', + template='Vec3d', name='cosseratCoordinateMO', + position=bendingStates, + showIndices=0) + + if self.useInertiaParams is False: + cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, + length=listOfSectionsLength, radius=self.radius.value, + youngModulus=self.youngModulus.value, poissonRatio=self.poissonRatio.value, + rayleighStiffness=self.rayleighStiffness.value, + lengthY=self.length_Y.value, lengthZ=self.length_Z.value) + else: + self._extracted_from_addCosseratCoordinate_15( + cosseratCoordinateNode, listOfSectionsLength + ) + return cosseratCoordinateNode + + # TODO Rename this here and in `addCosseratCoordinate` + def _extracted_from_addCosseratCoordinate_15(self, cosseratCoordinateNode, listOfSectionsLength): + GA = self.inertialParams['GA'] + GI = self.inertialParams['GI'] + EA = self.inertialParams['EA'] + EI = self.inertialParams['EI'] + print(f'{GA}') + cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, + length=listOfSectionsLength, radius=self.radius.value, useInertiaParams=True, + GI=GI, GA=GA, EI=EI, EA=EA, rayleighStiffness=self.rayleighStiffness.value, + lengthY=self.length_Y.value, lengthZ=self.length_Z.value) + + def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): + + cosseratInSofaFrameNode = self.rigidBaseNode.addChild( + 'cosseratInSofaFrameNode') + self.cosseratCoordinateNode.addChild(cosseratInSofaFrameNode) + framesMO = cosseratInSofaFrameNode.addObject( + 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showObject=1, showObjectScale=0.001) + if self.beamMass != 0.: + cosseratInSofaFrameNode.addObject( + 'UniformMass', totalMass=self.beamMass, showAxisSizeFactor='0') + + cosseratInSofaFrameNode.addObject('DiscreteCosseratMapping', curv_abs_input=curv_abs_inputS, + curv_abs_output=curv_abs_outputF, name='cosseratMapping', + input1=self.cosseratCoordinateNode.cosseratCoordinateMO.getLinkPath(), + input2=self.rigidBaseNode.RigidBaseMO.getLinkPath(), + output=framesMO.getLinkPath(), debug=0, radius=self.radius.value) + return cosseratInSofaFrameNode + + +def createScene(rootNode): + addHeader(rootNode) + addVisual(rootNode) + + rootNode.findData('dt').value = 0.01 + rootNode.findData('gravity').value = [0., -9.81, 0.] + rootNode.addObject('BackgroundSetting', color='0 0.168627 0.211765') + rootNode.addObject('FreeMotionAnimationLoop') + rootNode.addObject('GenericConstraintSolver', tolerance=1e-5, maxIterations=5e2) + rootNode.addObject('Camera', position="-35 0 280", lookAt="0 0 0") + + solverNode = rootNode.addChild('solverNode') + solverNode.addObject('EulerImplicitSolver', + rayleighStiffness="0.2", rayleighMass='0.1') + solverNode.addObject('SparseLDLSolver', name='solver', + template="CompressedRowSparseMatrixd") + solverNode.addObject('GenericConstraintCorrection') + + cosserat = solverNode.addChild( + CosseratClasse(parent=solverNode, cosseratGeometry=cosserat_config, name="cosserat", radius=0.15)) + + # use this to add the collision if the beam will interact with another object + cosserat.addCollisionModel() + + # Attach a force at the beam tip, + # we can attach this force to a non-mechanical node to control the beam in order to be able to drive it. + beamFrame = cosserat.cosseratFrame + beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-2, indices=12, + force=[0., -100., 0., 0., 0., 0.]) + + return rootNode diff --git a/examples/python3/cosserat/__init__.py b/examples/python3/cosserat/__init__.py index 49259a65..2d711a6d 100644 --- a/examples/python3/cosserat/__init__.py +++ b/examples/python3/cosserat/__init__.py @@ -18,4 +18,4 @@ """ -__all__ = ["utils","cosseratObject", "nonLinearCosserat", "createFemRegularGrid"] +__all__ = ["utils","cosseratObject", "nonLinearCosserat", "createFemRegularGrid", "actuators"] diff --git a/examples/python3/cosserat/cosseratObject.py b/examples/python3/cosserat/cosseratObject.py index 0238ed41..6f353960 100644 --- a/examples/python3/cosserat/cosseratObject.py +++ b/examples/python3/cosserat/cosseratObject.py @@ -16,7 +16,6 @@ cosserat_config = {'init_pos': [0., 0., 0.], 'tot_length': 6, 'nbSectionS': 6, 'nbFramesF': 12, 'buildCollisionModel': 1, 'beamMass': 0.22} - class Cosserat(Sofa.Prefab): """Cosserat beam prefab class. It is a prefab class that allow to create a cosserat beam in Sofa. Structure: @@ -197,7 +196,7 @@ def createScene(rootNode): ['SofaEngine', 'SofaLoader', 'SofaSimpleFem', 'SofaExporter']]) rootNode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels hideCollisionModels ' - 'hideBoundingCollisionModels hireForceFields ' + 'hideBoundingCollisionModels hideForceFields ' 'hideInteractionForceFields hideWireframe showMechanicalMappings') rootNode.findData('dt').value = 0.01 rootNode.findData('gravity').value = [0., -9.81, 0.] diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index aeab6697..d0658a28 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -1,27 +1,46 @@ +"""_summary_ Basic scene using Cosserat in SofaPython3. + The Finger is modeled using FEM model while de cable is modeled using cosserat theory. + The link between these two mechanical models is performed by constraint based on Lagrangian Multiplier -def addHeader(rootnode, multithreading=False, inverse=False, isConstrained=False): +Returns: + _type_: _description_ +""" + + +__authors__ = "Younes" +__contact__ = "adagolodjo@protonmail.com, yinoussa.adagolodjo@inria.fr" +__version__ = "1.0.0" +__copyright__ = "(c) 2020,Inria" +__date__ = "july 2023" + +from stlib3.physics.deformable import ElasticMaterialObject +from stlib3.physics.constraints import FixedBox +import os + + +def addHeader(parentNode, multithreading=False, inverse=False, isConstrained=False, isContact=False): """ - Adds to rootnode the default headers for a simulation with contact. Also adds and returns three nodes: + Adds to rootNode the default headers for a simulation with contact. Also adds and returns three nodes: - Settings - Modelling - Simulation Args: + isContact: inverse: isConstrained: - rootnode: + parentNode: multithreading: Usage: - addHeader(rootnode) + addHeader(rootNode) Returns: the three SOFA nodes {settings, modelling, simulation} """ - settings = rootnode.addChild('Settings') + settings = parentNode.addChild('Settings') settings.addObject('RequiredPlugin', pluginName=[ - "Cosserat", # Needed to use component RigidDistanceMapping - "Sofa.Component.AnimationLoop", # Needed to use components FreeMotionAnimationLoop + "Cosserat", "Sofa.Component.AnimationLoop", # Needed to use components FreeMotionAnimationLoop "Sofa.Component.Collision.Detection.Algorithm", "Sofa.Component.Collision.Detection.Intersection", # Needed to use components LocalMinDistance "Sofa.Component.Collision.Response.Contact", # Needed to use components RuleBasedContactManager @@ -29,52 +48,72 @@ def addHeader(rootnode, multithreading=False, inverse=False, isConstrained=False "Sofa.Component.Constraint.Lagrangian.Solver", # Needed to use components GenericConstraintSolver "Sofa.Component.Constraint.Projective", # Needed to use components FixedConstraint "Sofa.Component.IO.Mesh", # Needed to use components MeshOBJLoader, MeshSTLLoader - "Sofa.Component.Mass", # Needed to use components UniformMass + "Sofa.Component.Mass", 'Sofa.Component.LinearSolver.Direct', "Sofa.Component.Setting", # Needed to use components BackgroundSetting "Sofa.Component.SolidMechanics.Spring", # Needed to use components RestShapeSpringsForceField "Sofa.Component.Topology.Container.Constant", # Needed to use components MeshTopology "Sofa.Component.Topology.Container.Dynamic", "Sofa.Component.Playback", - # Needed to use components EdgeSetTopologyContainer, EdgeSetTopologyModifier, - # QuadSetTopologyContainer, QuadSetTopologyModifier + "Sofa.Component.Playback", "Sofa.Component.Visual", # Needed to use components VisualStyle "Sofa.Component.Topology.Container.Grid", # Needed to use components RegularGridTopology "Sofa.Component.Topology.Mapping", # Needed to use components Edge2QuadTopologicalMapping - "Sofa.Component.Visual", # Needed to use components VisualStyle "Sofa.GL.Component.Rendering3D", # Needed to use components OglGrid, OglModel - "Sofa.GUI.Component", # Needed to use components AttachBodyButtonSetting + "Sofa.GUI.Component", "Sofa.Component.Collision.Geometry", "Sofa.Component.LinearSolver.Direct", + "Sofa.Component.Mapping.Linear", "Sofa.Component.MechanicalLoad", + "Sofa.Component.StateContainer", 'Sofa.Component.ODESolver.Backward' ]) settings.addObject('BackgroundSetting', color=[1, 1, 1, 1]) # settings.addObject('AttachBodyButtonSetting', stiffness=1e6) - rootnode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels showCollisionModels ' + parentNode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels showCollisionModels ' 'hideBoundingCollisionModels hideForceFields ' 'hideInteractionForceFields hideWireframe showMechanicalMappings') - if isConstrained: - rootnode.addObject('CollisionPipeline') - rootnode.addObject("DefaultVisualManagerLoop") - rootnode.addObject('RuleBasedContactManager', responseParams='mu=0.8', response='FrictionContactConstraint') - rootnode.addObject('BruteForceBroadPhase') - rootnode.addObject('BVHNarrowPhase') - rootnode.addObject('LocalMinDistance', alarmDistance=0.05, contactDistance=0.01) - rootnode.addObject('FreeMotionAnimationLoop', parallelCollisionDetectionAndFreeMotion=multithreading, parallelODESolving=multithreading) + if isConstrained : + parentNode.addObject('FreeMotionAnimationLoop', parallelCollisionDetectionAndFreeMotion=multithreading, + parallelODESolving=multithreading) if inverse: settings.addObject('RequiredPlugin', name="SoftRobots.Inverse") - rootnode.addObject('QPInverseProblemSolver', name='ConstraintSolver', tolerance=1e-8, maxIterations=100, multithreading=multithreading, - epsilon=1) + parentNode.addObject('QPInverseProblemSolver', name='ConstraintSolver', tolerance=1e-8, maxIterations=100, + multithreading=multithreading, epsilon=1) else: - rootnode.addObject('GenericConstraintSolver', name='ConstraintSolver', tolerance=1e-8, maxIterations=100, multithreading=multithreading) - rootnode.dt = 0.01 + parentNode.addObject('GenericConstraintSolver', name='ConstraintSolver', tolerance=1e-8, maxIterations=100, + multithreading=multithreading) - modelling = rootnode.addChild('Modelling') - modelling.addChild('Topology') - simulation = rootnode.addChild('Simulation') - return settings, modelling, simulation + if isContact: + contactHeader(parentNode) -def addSolvers(node, template='CompressedRowSparseMatrixd', rayleighMass=0., rayleighStiffness=0., firstOrder=False, - iterative=False): + +# components needed for contact modeling +def contactHeader(parentNode): + parentNode.addObject('CollisionPipeline') + parentNode.addObject("DefaultVisualManagerLoop") + parentNode.addObject('RuleBasedContactManager', responseParams='mu=0.8', response='FrictionContactConstraint') + parentNode.addObject('BruteForceBroadPhase') + parentNode.addObject('BVHNarrowPhase') + parentNode.addObject('LocalMinDistance', alarmDistance=0.05, contactDistance=0.01) + + +def addVisual(node): + """ + Adds a visual model to the given node. + + Args: + node: + Usage: + addVisual(node) + """ + node.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels hideCollisionModels ' + 'hideBoundingCollisionModels hideForceFields ' + 'hideInteractionForceFields hideWireframe showMechanicalMappings') + return node + +def addSolverNode(node, name='solverNode', template='CompressedRowSparseMatrixd', rayleighMass=0., rayleighStiffness=0., firstOrder=False, + iterative=False, isConstrained=False): """ Adds solvers (EulerImplicitSolver, LDLSolver, GenericConstraintCorrection) to the given node. Args: + name: + isConstrained: node: template: for the LDLSolver rayleighMass: @@ -83,26 +122,112 @@ def addSolvers(node, template='CompressedRowSparseMatrixd', rayleighMass=0., ray iterative: iterative solver Usage: - addSolvers(node) + addSolversNode(node) """ - node.addObject('RequiredPlugin', name='SofaPlugins', pluginName=['Sofa.Component.LinearSolver.Direct', - 'Sofa.Component.ODESolver.Backward']) - node.addObject('EulerImplicitSolver', firstOrder=firstOrder, rayleighStiffness=rayleighStiffness, rayleighMass=rayleighMass) + solverNode = node.addChild(name) + solverNode.addObject('EulerImplicitSolver', firstOrder=firstOrder, rayleighStiffness=rayleighStiffness, + rayleighMass=rayleighMass) + solverNode.addObject('GenericConstraintSolver', tolerance=1e-5, maxIterations=5e2) if iterative: - node.addObject('CGLinearSolver', name='Solver', template=template) + solverNode.addObject('CGLinearSolver', name='Solver', template=template) else: - node.addObject('SparseLDLSolver', name='Solver', template=template) - node.addObject('GenericConstraintCorrection', linearSolver=node.Solver.getLinkPath()) + solverNode.addObject('SparseLDLSolver', name='Solver', template=template) + if isConstrained: + solverNode.addObject('GenericConstraintCorrection', linearSolver=solverNode.Solver.getLinkPath()) + + return solverNode + +def addFEMObject(parentNode, path) : + fingerSolver = addSolverNode(parentNode) + + # Load a VTK tetrahedral mesh and expose the resulting topology in the scene . + loader = fingerSolver.addObject('MeshVTKLoader', name='loader', filename=f'{path}finger.vtk', + translation="-17.5 -12.5 7.5", + rotation="0 180 0") + fingerSolver.addObject('TetrahedronSetTopologyContainer', position=loader.position.getLinkPath(), + tetras=loader.tetras.getLinkPath(), name='container') + # Create a MechanicalObject component to stores the DoFs of the model + fingerSolver.addObject('MechanicalObject', template='Vec3', name='dofs') + + # Gives a mass to the model + fingerSolver.addObject('UniformMass', totalMass='0.075') + # Add a TetrahedronFEMForceField component which implement an elastic material model + # solved using the Finite Element Method on + # tetrahedrons. + fingerSolver.addObject('TetrahedronFEMForceField', template='Vec3d', name='forceField', method='large', + poissonRatio='0.45', youngModulus='500') + + fingerSolver.addObject('BoxROI', name='ROI1', box='-18 -15 -8 2 -3 8', drawBoxes='true') + fingerSolver.addObject('RestShapeSpringsForceField', + points='@ROI1.indices', stiffness='1e12') + ########################################## + # Cable points # + ########################################## + # Mapped points inside the finger volume, these points attached to the FE model + # are constrained to slide on the cable. + + FEMpos = [" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"] + femPoints = fingerSolver.addChild('femPoints') + femPoints.addObject('MechanicalObject', name="pointsInFEM", position=FEMpos, showObject="1", + showIndices="1") + femPoints.addObject('BarycentricMapping') + +def addMappedPoints(parentNode, name="pointsInFEM", position=None, showObject="1", + showIndices="1", femPos=" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"): + if position is None: + position = femPos + + femPoints = parentNode.addChild(name) + femPoints.addObject( + 'MechanicalObject', + name=f'{name}Mo', + position=position, + showObject=showObject, + showIndices=showIndices, + template='Vec3d' + ) + femPoints.addObject('BarycentricMapping') + return femPoints + +def Finger(parentNode=None, name="Finger", rotation=None, translation=None, fixingBox=None,path=None, femPos=None): + + if fixingBox is None: + fixingBox = [-18, -15, -8, 2, -3, 8] + if rotation is None: + rotation = [0., 180., 0] + if translation is None: + translation = [-17.5, -12.5, 7.5] + if path is None: + path = f'{os.path.dirname(os.path.abspath(__file__))}/' + + + # TODO : add physical properties as the finger input + finger = parentNode.addChild(name) + e_object = ElasticMaterialObject(finger, + volumeMeshFileName=f'{path}finger.vtk', + poissonRatio=0.48, + youngModulus=500, + totalMass=0.075, + surfaceColor=[0.0, 0.7, 0.7, 0.5], + surfaceMeshFileName=f'{path}finger.stl', + rotation=rotation, + translation=translation) + FixedBox(e_object, + doVisualization=True, + atPositions=fixingBox) + """Add sliding point to the scene, these points are those on which the cable slides""" + if femPos is None: + femPoints = addMappedPoints(e_object) + else: + femPoints = addMappedPoints(e_object, femPos=femPos) - return node + finger.addChild(e_object) + return finger, femPoints # Test def createScene(rootNode): - addHeader(rootNode) - - node = rootNode.addChild('rootNode') - solverNode = addSolvers(node) + addSolverNode(rootNode) diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py index 45c95a88..5841ce18 100644 --- a/examples/python3/useful/params.py +++ b/examples/python3/useful/params.py @@ -2,26 +2,47 @@ from dataclasses import dataclass @dataclass -class CableParameters: +class BeamPhysicsParameters: + """one can only use one of the following two parameters""" + """First set of parameters""" youngModulus: float = 1.205e11 poissonRatio: float = 0.499 - radius: float = 0.004 - density: float = 7.850e3 - maxDisplacement: float = 0.3 + """Second set of parameters""" + useInertia: bool = False GI: float = 1.5708 GA: float = 3.1416e4 EI: float = 0.7854 EA: float = 3.1416e4 - L: float = 1. # beam length in m - Rb: float = 0.02 / 2. # beam radius in m + """Common parameters, this parameters are used in both cases""" + beamMass: float = 1. + beamLength: float = 1. # beam length in m + beamRadius: float = 0.02 / 2. # beam radius in m @dataclass -class CableGeometryParameters: - init_pos: list[float] # = [0., 0., 0.] - tot_length: float = 1. - nbSectionS: int = 5 - nbFramesF: int = 30 +class BeamGeometryParameters: + """cosserat beam Geometry parameters""" + init_pos: list[float] # = [0., 0., 0.], The beam rigid base position + beamLength: float = 1. # beam length in m + nbSection: int = 5 # number of sections, here sections are not cross-sections but sections along the beam length + nbFrames: int = 30 buildCollisionModel: int = 0 - beamMass: float = 1. \ No newline at end of file + +@dataclass +class SimulationParameters: + """Simulation parameters""" + rayleighStiffness: float = 0.2 + rayleighMass: float = 0.1 + +@dataclass +class ContactParameters: + """Contact parameters""" + responseParams: str = 'mu=0.8' + response: str = 'FrictionContactConstraint' + alarmDistance: float = 0.05 + contactDistance: float = 0.01 + isMultithreading: bool = False + tolerance: float = 1.e-8 + maxIterations: int = 100 + epsilon: float = 1.e-6 \ No newline at end of file From 157721aed11f3058229b9247191e82d58a8f18b8 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Wed, 2 Aug 2023 03:00:24 +0200 Subject: [PATCH 04/71] Reviving the FingerActuation scene, this illustration demonstrates the application of the Cosserat model in simulating a non-extending cable. In this case, the cable is utilized to control the movement of a deformable finger. --- examples/python3/actuators/example1.py | 4 +- examples/python3/actuators/fingerActuation.py | 4 +- .../{CosseratPrefab.py => CosseratBase.py} | 159 +++++++++++++----- examples/python3/cosserat/needle/params.py | 21 ++- examples/python3/cosserat/usefulFunctions.py | 48 ++++++ examples/python3/useful/params.py | 21 ++- 6 files changed, 201 insertions(+), 56 deletions(-) rename examples/python3/cosserat/{CosseratPrefab.py => CosseratBase.py} (61%) diff --git a/examples/python3/actuators/example1.py b/examples/python3/actuators/example1.py index f927677e..b7283927 100644 --- a/examples/python3/actuators/example1.py +++ b/examples/python3/actuators/example1.py @@ -11,7 +11,7 @@ __date__ = "July, 20 2023" from useful.header import addHeader -from useful.params import BeamGeometryParameters +from useful.params import BeamPhysicsParameters, BeamGeometryParameters from cosserat.cosseratObject import Cosserat import os @@ -57,7 +57,7 @@ Rb = 6.2e-1 / 2. # beam radius in cm # @todo use CableGeometryParameters & CableParameters in Cosserat class for both geometry and physics parameters -geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], tot_length=length, +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=length, nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) # inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, # maxDisplacement=0.3, nbSections=20) diff --git a/examples/python3/actuators/fingerActuation.py b/examples/python3/actuators/fingerActuation.py index a976f17e..91b4b04c 100644 --- a/examples/python3/actuators/fingerActuation.py +++ b/examples/python3/actuators/fingerActuation.py @@ -17,7 +17,7 @@ import Sofa import os -from cosserat.CosseratPrefab import CosseratClasse +from cosserat.cosseratObject import Cosserat from useful.header import addHeader, addVisual, addSolverNode, Finger from controler import FingerController @@ -53,7 +53,7 @@ def createScene(rootNode): cableNode = addSolverNode(rootNode, name="cableSolver", isConstrained=True) cosseratCable = cableNode.addChild( - CosseratClasse(parent=cableNode, cosseratGeometry=beamGeometrie, name="cosserat", radius=0.5, + Cosserat(parent=cableNode, cosseratGeometry=beamGeometrie, name="cosserat", radius=0.5, youngModulus=5e6, poissonRatio=0.4)) mappedFrameNode = cosseratCable.cosseratFrame diff --git a/examples/python3/cosserat/CosseratPrefab.py b/examples/python3/cosserat/CosseratBase.py similarity index 61% rename from examples/python3/cosserat/CosseratPrefab.py rename to examples/python3/cosserat/CosseratBase.py index e2a9e9a9..aadc2c7a 100644 --- a/examples/python3/cosserat/CosseratPrefab.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -10,43 +10,31 @@ __date__ = "October, 26 2021" import Sofa -from cosserat.usefulFunctions import buildEdges, BuildCosseratGeometry +# from cosserat.usefulFunctions import buildEdges from cosserat.utils import addEdgeCollision, addPointsCollision from useful.header import addHeader, addVisual, addSolverNode +# from useful.params import Parameters +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters, ContactParameters cosserat_config = {'init_pos': [0., 0., 0.], 'tot_length': 6, 'nbSectionS': 6, 'nbFramesF': 12, 'buildCollisionModel': 1, 'beamMass': 0.22} -class CosseratClasse(Sofa.Prefab): +class CosseratBase(Sofa.Prefab): """ - import Sofa.Core - - class Foo(Sofa.Core.Prefab): - prefabParameters = [{ 'name': 'n', 'type': 'int', 'help': 'number of repetition, 'default': 1}, - {'name': 'message', 'type': 'string', 'help': 'message to display', 'default': ''}] - - myAttribute = 0 - - def __init__(self, *a, *k): - Sofa.Prefab.__init__(self, *a, **k) - - def init(self): - myAttribute += 1 - for i in range(0, self.n.value): - print(self.message.value) - - Cosserat beam prefab class. It is a prefab class that allow to create a cosserat beam in Sofa. + CosseratBase model prefab class. It is a prefab class that allow to create a cosserat beam/rod in Sofa. Structure: Node : { - name : 'Cosserat' + name : 'CosseratBase' Node0 MechanicalObject : // Rigid position of the base of the beam - Node1 MechanicalObject : // Vec3d, The rate angular composed of the twist and the bending along y and z - Node1 ForceField // - MechanicalObject // The child of the two precedent nodes, Rigid positions - Cosserat Mapping // it allow the transfer from the local to the global frame + Node1 MechanicalObject : // Vec3d, cosserat local parameters composed of the twist and the bending along y and z + Node1 ForceField // Base on Hook's law, it compute the force applied on the beam + (Node0-Node1)-child MechanicalObject // The child of the two precedent nodes, Rigid positions + Allow to compute the cosserat frame in the world frame (Sofa frame) + Cosserat Mapping // it allow the transfer from the local to the word frame } + params """ prefabParameters = [ @@ -73,16 +61,19 @@ def init(self): 'to follow arm position', 'default': '1'}, {'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'}] + def __init__(self, *args, **kwargs): Sofa.Prefab.__init__(self, *args, **kwargs) - # self.bPhysicsParams = kwargs.get('beamPhysicsParams') + beamPhysicsParams = BeamPhysicsParameters() + beamGeometryParams = BeamGeometryParameters(init_pos=[0., 0., 0.]) # self.bGeometryParams = kwargs.get('beamGeometryParams') + # params = Parameters() self.cosseratGeometry = kwargs['cosseratGeometry'] - self.beamMass = self.cosseratGeometry['beamMass'] + self.beamMass = beamPhysicsParams.beamMass # self.cosseratGeometry['beamMass'] self.parent = kwargs.get('parent') - self.useInertiaParams = False - self.radius = kwargs.get('radius') + self.useInertiaParams = beamPhysicsParams.useInertia # False + self.radius = beamPhysicsParams.beamRadius # kwargs.get('radius') if self.parent.hasObject("EulerImplicitSolver") is False: print('The code does not have parent EulerImplicit') @@ -95,21 +86,26 @@ def __init__(self, *args, **kwargs): self.inertialParams = kwargs['inertialParams'] self.rigidBaseNode = self.addRigidBaseNode() - [positionS, curv_abs_inputS, sectionsLength, framesF, curv_abs_outputF, self.frames3D] = \ - BuildCosseratGeometry(self.cosseratGeometry) - self.cosseratCoordinateNode = self.addCosseratCoordinate(positionS, sectionsLength) - self.cosseratFrame = self.addCosseratFrame(framesF, curv_abs_inputS, curv_abs_outputF) + cosserat_geometry = CosseratGeometry(beamGeometryParams) + self.frames3D = cosserat_geometry.cable_positionF + + # [positionS, curv_abs_inputS, sectionsLength, framesF, curv_abs_outputF, self.frames3D] = __buildCosseratGeometry(params.beamGeoParams) + + self.cosseratCoordinateNode = self.addCosseratCoordinate(cosserat_geometry.bendingState, + cosserat_geometry.sectionsLengthList) + self.cosseratFrame = self.addCosseratFrame(cosserat_geometry.framesF, cosserat_geometry.curv_abs_inputS, + cosserat_geometry.curv_abs_outputF) def init(self): pass def addCollisionModel(self): - tab_edges = buildEdges(self.frames3D) + tab_edges = generate_edge_list(self.frames3D) return addEdgeCollision(self.cosseratFrame, self.frames3D, tab_edges) def addPointCollisionModel(self, nodeName='CollisionPoints'): - tab_edges = buildEdges(self.frames3D) + tab_edges = generate_edge_list(self.frames3D) return addPointsCollision(self.cosseratFrame, self.frames3D, tab_edges, nodeName) def addSlidingPoints(self): @@ -158,7 +154,7 @@ def addCosseratCoordinate(self, bendingStates, listOfSectionsLength): if self.useInertiaParams is False: cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, - length=listOfSectionsLength, radius=self.radius.value, + length=listOfSectionsLength, radius=self.radius, youngModulus=self.youngModulus.value, poissonRatio=self.poissonRatio.value, rayleighStiffness=self.rayleighStiffness.value, lengthY=self.length_Y.value, lengthZ=self.length_Z.value) @@ -176,7 +172,7 @@ def _extracted_from_addCosseratCoordinate_15(self, cosseratCoordinateNode, listO EI = self.inertialParams['EI'] print(f'{GA}') cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, - length=listOfSectionsLength, radius=self.radius.value, useInertiaParams=True, + length=listOfSectionsLength, radius=self.radius, useInertiaParams=True, GI=GI, GA=GA, EI=EI, EA=EA, rayleighStiffness=self.rayleighStiffness.value, lengthY=self.length_Y.value, lengthZ=self.length_Z.value) @@ -195,10 +191,97 @@ def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): curv_abs_output=curv_abs_outputF, name='cosseratMapping', input1=self.cosseratCoordinateNode.cosseratCoordinateMO.getLinkPath(), input2=self.rigidBaseNode.RigidBaseMO.getLinkPath(), - output=framesMO.getLinkPath(), debug=0, radius=self.radius.value) + output=framesMO.getLinkPath(), debug=0, radius=self.radius) return cosseratInSofaFrameNode +class CosseratGeometry: + def __init__(self, beamGeoParams): + # Data validation checks for beamGeoParams + if not isinstance(beamGeoParams, BeamGeometryParameters): + raise ValueError("beamGeoParams must be an instance of BeamGeoParams.") + + self.bendingState, self.curv_abs_inputS, self.sectionsLengthList = self.__calculate_beam_parameters(beamGeoParams) + self.framesF, self.curv_abs_outputF, self.cable_positionF = self.__calculate_frame_parameters(beamGeoParams) + + def __calculate_beam_parameters(self, beamGeoParams): + # Data validation checks for beamGeoParams attributes + if not all(hasattr(beamGeoParams, attr) for attr in ['init_pos', 'beamLength', 'nbSection']): + raise ValueError("beamGeoParams must have 'init_pos', 'beamLength', and 'nbSection' attributes.") + + total_length = beamGeoParams.beamLength + nb_sections = beamGeoParams.nbSection + x, y, z = beamGeoParams.init_pos + + if not all(isinstance(val, (int, float)) for val in [x, y, z, total_length]): + raise ValueError("init_pos and beamLength in beamGeoParams must be numeric values.") + + if not isinstance(nb_sections, int) or nb_sections <= 0: + raise ValueError("nbSection in beamGeoParams must be a positive integer.") + + length_s = total_length / nb_sections + bendingState = [] + listOfSectionsLength = [] + temp = x + curv_abs_input_s = [x] + + for i in range(nb_sections): + bendingState.append([0, 0, 0]) + listOfSectionsLength.append((((i + 1) * length_s) - i * length_s)) + temp += listOfSectionsLength[i] + curv_abs_input_s.append(temp) + curv_abs_input_s[nb_sections] = total_length + x + + return bendingState, curv_abs_input_s, listOfSectionsLength + + def __calculate_frame_parameters(self, beamGeoParams): + # Data validation checks for beamGeoParams attributes + # if not all(hasattr(beamGeoParams, attr) for attr in ['init_pos', 'beamLength', 'nbFrames']): + # raise ValueError("beamGeoParams must have 'init_pos', 'beamLength', and 'nbFrames' attributes.") + + x, y, z = beamGeoParams.init_pos + total_length = beamGeoParams.beamLength + nb_frames = beamGeoParams.nbFrames + + if not all(isinstance(val, (int, float)) for val in [x, y, z, total_length]): + raise ValueError("init_pos and beamLength in beamGeoParams must be numeric values.") + + if not isinstance(nb_frames, int) or nb_frames <= 0: + raise ValueError("nbFrames in beamGeoParams must be a positive integer.") + + length_f = total_length / nb_frames + frames_f = [] + curv_abs_output_f = [] + cable_position_f = [] + + for i in range(nb_frames): + sol = i * length_f + frames_f.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + curv_abs_output_f.append(sol + x) + + frames_f.append([total_length + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([total_length + x, y, z]) + curv_abs_output_f.append(total_length + x) + + return frames_f, curv_abs_output_f, cable_position_f + +from typing import List + +def generate_edge_list(cable3DPos: List[List[float]]) -> List[int]: + """ + Generate an edge list required in the EdgeSetTopologyContainer component. + + Parameters: + cable3DPos (List[List[float]]): A list of 3D points representing the cable positions. + + Returns: + List[int]: A list of indices forming edges in the EdgeSetTopologyContainer. + """ + number_of_points = len(cable3DPos) + edge_list = [i for i in range(number_of_points - 1) for _ in range(2)] + return edge_list + def createScene(rootNode): addHeader(rootNode) addVisual(rootNode) @@ -218,7 +301,7 @@ def createScene(rootNode): solverNode.addObject('GenericConstraintCorrection') cosserat = solverNode.addChild( - CosseratClasse(parent=solverNode, cosseratGeometry=cosserat_config, name="cosserat", radius=0.15)) + CosseratBase(parent=solverNode, cosseratGeometry=cosserat_config, name="cosserat", radius=0.15)) # use this to add the collision if the beam will interact with another object cosserat.addCollisionModel() diff --git a/examples/python3/cosserat/needle/params.py b/examples/python3/cosserat/needle/params.py index 3cc30d53..422db658 100644 --- a/examples/python3/cosserat/needle/params.py +++ b/examples/python3/cosserat/needle/params.py @@ -41,21 +41,24 @@ class ContactParams: coneFactor: float = "0" +def display(): + print(f''' + # Geometry + {string.ascii_uppercase[:4]} + {string.ascii_uppercase[4:6]} + {string.ascii_uppercase[6:8]} + {string.ascii_uppercase[8:10]} + ''' + ) + + @dataclass class NeedleParameters: # Geometry: GeometryParams = GeometryParams() # Physics: PhysicsParams = PhysicsParams() # Fem: FemParams = FemParams() # contact: ContactParams = ContactParams() - def display(): - print(f''' - # Geometry - {string.ascii_uppercase[:4]} - {string.ascii_uppercase[4:6]} - {string.ascii_uppercase[6:8]} - {string.ascii_uppercase[8:10]} - ''' - ) + pass @dataclass class ConstraintsParams: diff --git a/examples/python3/cosserat/usefulFunctions.py b/examples/python3/cosserat/usefulFunctions.py index 10bb55e4..c91c3b9b 100644 --- a/examples/python3/cosserat/usefulFunctions.py +++ b/examples/python3/cosserat/usefulFunctions.py @@ -315,6 +315,54 @@ def usePlasticityWithTable(self): # ####################### # Function and class # ####################### + + +class CosseratGeometry: + def __init__(self, positionS, curv_abs_inputS, sectionLength, framesF, curv_abs_outputF, cable_positionF): + self.positionS = positionS + self.curv_abs_inputS = curv_abs_inputS + self.sectionLength = sectionLength + self.framesF = framesF + self.curv_abs_outputF = curv_abs_outputF + self.cable_positionF = cable_positionF + +def generate_cosserat_geometry(beamGeoParams): + x, y, z = beamGeoParams.init_pos + total_length = beamGeoParams.beamLength + nb_sections = beamGeoParams.nbSection + nb_frames = beamGeoParams.nbFrames + + length_s = total_length / nb_sections + + position_s = [] + sectionLengthList = [] + temp = x + curv_abs_input_s = [x] + + for i in range(nb_sections): + position_s.append([0, 0, 0]) + sectionLengthList.append((((i + 1) * length_s) - i * length_s)) + temp += sectionLengthList[i] + curv_abs_input_s.append(temp) + curv_abs_input_s[nb_sections] = total_length + x + + length_f = total_length / nb_frames + frames_f = [] + curv_abs_output_f = [] + cable_position_f = [] + + for i in range(nb_frames): + sol = i * length_f + frames_f.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + curv_abs_output_f.append(sol + x) + + frames_f.append([total_length + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([total_length + x, y, z]) + curv_abs_output_f.append(total_length + x) + + return CosseratGeometry(position_s, curv_abs_input_s, sectionLengthList, frames_f, curv_abs_output_f, cable_position_f) + def BuildCosseratGeometry(config): # Define: the number of section, the total length and the length of each beam. diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py index 5841ce18..62fab49e 100644 --- a/examples/python3/useful/params.py +++ b/examples/python3/useful/params.py @@ -1,20 +1,18 @@ # @todo use this dataclass to create the cosserat object -from dataclasses import dataclass +from dataclasses import dataclass, field @dataclass class BeamPhysicsParameters: """one can only use one of the following two parameters""" """First set of parameters""" youngModulus: float = 1.205e11 poissonRatio: float = 0.499 - """Second set of parameters""" useInertia: bool = False GI: float = 1.5708 GA: float = 3.1416e4 EI: float = 0.7854 EA: float = 3.1416e4 - """Common parameters, this parameters are used in both cases""" beamMass: float = 1. beamLength: float = 1. # beam length in m @@ -23,7 +21,8 @@ class BeamPhysicsParameters: @dataclass class BeamGeometryParameters: """cosserat beam Geometry parameters""" - init_pos: list[float] # = [0., 0., 0.], The beam rigid base position + # init_pos: str = "0. 0. 0." # list[float] # = [0., 0., 0.], The beam rigid base position + init_pos: list[float] = field(default_factory=list) beamLength: float = 1. # beam length in m nbSection: int = 5 # number of sections, here sections are not cross-sections but sections along the beam length nbFrames: int = 30 @@ -45,4 +44,16 @@ class ContactParameters: isMultithreading: bool = False tolerance: float = 1.e-8 maxIterations: int = 100 - epsilon: float = 1.e-6 \ No newline at end of file + epsilon: float = 1.e-6 + + +# @dataclass +# class Parameters: +# """Parameters for the cosserat beam""" +# beamPhysicsParams: BeamPhysicsParameters = BeamPhysicsParameters() +# simuParams: SimulationParameters = SimulationParameters() +# contactParams: ContactParameters = ContactParameters() +# beamGeoParams: BeamGeometryParameters = BeamGeometryParameters() + + + From a3366f88fc536ef0e161a61c8ad08f9eab67be5d Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Wed, 2 Aug 2023 17:09:27 +0200 Subject: [PATCH 05/71] Added a new class, CosseratBase, this class uses dataclasses to make it easier to read and use different types of parameters in the scene. --- ...seratBeamFallingUnderTheEffectOfGravity.py | 9 +- examples/python3/actuators/example1.py | 43 ++--- examples/python3/cosserat/CosseratBase.py | 173 ++++-------------- examples/python3/useful/geometry.py | 89 +++++++++ examples/python3/useful/params.py | 70 ++++--- .../python3/{cosserat => useful}/utils.py | 5 +- 6 files changed, 196 insertions(+), 193 deletions(-) create mode 100644 examples/python3/useful/geometry.py rename examples/python3/{cosserat => useful}/utils.py (96%) diff --git a/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py b/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py index 32b934ec..11c917d0 100644 --- a/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py +++ b/examples/python3/CosseratBeamFallingUnderTheEffectOfGravity.py @@ -9,9 +9,10 @@ __copyright__ = "(c) 2021,Inria" __date__ = "July, 20 2023" -from useful.header import addHeader, addSolvers +from useful.header import addHeader from cosserat.cosseratObject import Cosserat from dataclasses import dataclass +from useful.params import Parameters, BeamGeometryParameters # [@info] ================ Unit: N, m, Kg, Pa ================ @@ -42,6 +43,9 @@ class CableGeometryParameters: beamMass: float = 1. + + + YM = 1.0e8 PR = 0.38 rayleighStiffness = 1.e-3 # Nope @@ -65,6 +69,9 @@ class CableGeometryParameters: isCollisionModel = 0 +Params = Parameters(beamGeoParams=BeamGeometryParameters(init_pos=[0, 0, 0], beamLength=length, + nbSection=5, nbFrames=30, buildCollisionModel=0)) + def createScene(rootNode): addHeader(rootNode) diff --git a/examples/python3/actuators/example1.py b/examples/python3/actuators/example1.py index b7283927..1dffd2a1 100644 --- a/examples/python3/actuators/example1.py +++ b/examples/python3/actuators/example1.py @@ -11,8 +11,10 @@ __date__ = "July, 20 2023" from useful.header import addHeader -from useful.params import BeamPhysicsParameters, BeamGeometryParameters +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters from cosserat.cosseratObject import Cosserat +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase import os from splib3.numerics.quat import Quat @@ -45,30 +47,19 @@ # [@info] ================ Unit: N, cm, g, Pa ================ """ -YM = 1.0e8 -PR = 0.38 -rayleighStiffness = 1.e-3 # Nope -firstOrder = 1 -EI = 1.e2 -# coeff = 1. -# beam parameters -length = 65.5 # in cm -Rb = 6.2e-1 / 2. # beam radius in cm # @todo use CableGeometryParameters & CableParameters in Cosserat class for both geometry and physics parameters -geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=length, - nbSectionS=5, nbFramesF=30, buildCollisionModel=0, beamMass=1.) -# inertialParams = CableParameters(youngModulus=YM, poissonRatio=PR, radius=Rb, density=7.850e3, -# maxDisplacement=0.3, nbSections=20) -nonLinearConfig = {'init_pos': [0., 0., 0.], 'tot_length': length, 'nbSectionS': 5, - 'nbFramesF': 30, 'buildCollisionModel': 0, 'beamMass': 1.} -inertialParams = {'GI': 1.5708, 'GA': 3.1416e4, - 'EI': 0.7854, 'EA': 3.1416e4, 'L': length, 'Rb': Rb} +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, + nbSection=5, nbFrames=30, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus= 1.0e8, poissonRatio=0.38, beamRadius=6.2e-1/2., + beamLength=65.5) +simuParams = SimulationParameters(rayleighStiffness=1.e-3) isCollisionModel = 0 + def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState"): """ The intermediateRigid construction """ if rigidCentral is None: @@ -105,7 +96,7 @@ def loadDisk(parentNode): diskMapping.addObject('RigidMapping', name="diskMap") -def createRigidDisk(rootNode): +def createRigidDisk(rootNode, length=65.5): # @todo add a parameter for the number of disk diskSolverNode = rootNode.addChild('diskSolverNode') diskSolverNode.addObject('EulerImplicitSolver', firstOrder=0, rayleighStiffness=0.01, rayleighMass=0.) diskSolverNode.addObject('SparseLDLSolver', name='solver') @@ -116,19 +107,23 @@ def createRigidDisk(rootNode): # """ The intermediateRigid construction """ # intermediateRigid = createIntermediateNode(diskSolverNode) + return diskSolverNode + +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) def createScene(rootNode): addHeader(rootNode) rootNode.gravity = [0., -9.81, 0.] stemNode = rootNode.addChild('stemNode') - stemNode.addChild( - Cosserat(parent=stemNode, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, - useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, - rayleighStiffness=rayleighStiffness)) + + stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) + # Cosserat(parent=stemNode, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, + # useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, + # rayleighStiffness=rayleighStiffness)) # create the rigid disk node - createRigidDisk(rootNode) + # createRigidDisk(rootNode) diff --git a/examples/python3/cosserat/CosseratBase.py b/examples/python3/cosserat/CosseratBase.py index aadc2c7a..af283793 100644 --- a/examples/python3/cosserat/CosseratBase.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -10,14 +10,10 @@ __date__ = "October, 26 2021" import Sofa -# from cosserat.usefulFunctions import buildEdges -from cosserat.utils import addEdgeCollision, addPointsCollision +from useful.utils import addEdgeCollision, addPointsCollision from useful.header import addHeader, addVisual, addSolverNode -# from useful.params import Parameters -from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters, ContactParameters - -cosserat_config = {'init_pos': [0., 0., 0.], 'tot_length': 6, 'nbSectionS': 6, - 'nbFramesF': 12, 'buildCollisionModel': 1, 'beamMass': 0.22} +from useful.params import Parameters, BeamGeometryParameters +from useful.geometry import CosseratGeometry, generate_edge_list class CosseratBase(Sofa.Prefab): @@ -29,7 +25,7 @@ class CosseratBase(Sofa.Prefab): name : 'CosseratBase' Node0 MechanicalObject : // Rigid position of the base of the beam Node1 MechanicalObject : // Vec3d, cosserat local parameters composed of the twist and the bending along y and z - Node1 ForceField // Base on Hook's law, it compute the force applied on the beam + Node1 ForceField // Base on Hook's law, it computed the force applied on the beam (Node0-Node1)-child MechanicalObject // The child of the two precedent nodes, Rigid positions Allow to compute the cosserat frame in the world frame (Sofa frame) Cosserat Mapping // it allow the transfer from the local to the word frame @@ -39,37 +35,19 @@ class CosseratBase(Sofa.Prefab): """ prefabParameters = [ {'name': 'name', 'type': 'string', 'help': 'Node name', 'default': 'Cosserat'}, - {'name': 'position', 'type': 'Rigid3d::VecCoord', 'help': 'Cosserat base position', - 'default': [[0., 0., 0., 0, 0, 0, 1.]]}, {'name': 'translation', 'type': 'Vec3d', 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, - {'name': 'rotation', 'type': 'Vec3d', - 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, - {'name': 'youngModulus', 'type': 'double', - 'help': 'Beam Young modulus', 'default': 1.e6}, - {'name': 'poissonRatio', 'type': 'double', - 'help': 'Beam poisson ratio', 'default': 0.4}, - {'name': 'shape', 'type': 'string', 'help': 'beam section', 'default': "circular"}, - {'name': 'radius', 'type': 'double', - 'help': 'the radius in case of circular section', 'default': 0.02}, - {'name': 'length_Y', 'type': 'double', - 'help': 'the radius in case of circular section', 'default': 1.0}, - {'name': 'length_Z', 'type': 'double', - 'help': 'the radius in case of circular section', 'default': 1.0}, - {'name': 'rayleighStiffness', 'type': 'double', 'help': 'Rayleigh damping - stiffness matrix coefficient', - 'default': 0.0}, + {'name': 'rotation', 'type': 'Vec3d', 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, {'name': 'attachingToLink', 'type': 'string', 'help': 'a rest shape force field will constraint the object ' 'to follow arm position', 'default': '1'}, - {'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'}] - + {'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'} + ] def __init__(self, *args, **kwargs): Sofa.Prefab.__init__(self, *args, **kwargs) - beamPhysicsParams = BeamPhysicsParameters() - beamGeometryParams = BeamGeometryParameters(init_pos=[0., 0., 0.]) - # self.bGeometryParams = kwargs.get('beamGeometryParams') - # params = Parameters() + self.params = kwargs.get('params', Parameters()) # Use the Parameters class with default values + beamPhysicsParams = self.params.beamPhysicsParams + beamGeometryParams = self.params.beamGeoParams - self.cosseratGeometry = kwargs['cosseratGeometry'] self.beamMass = beamPhysicsParams.beamMass # self.cosseratGeometry['beamMass'] self.parent = kwargs.get('parent') self.useInertiaParams = beamPhysicsParams.useInertia # False @@ -85,16 +63,14 @@ def __init__(self, *args, **kwargs): self.useInertiaParams = True self.inertialParams = kwargs['inertialParams'] - self.rigidBaseNode = self.addRigidBaseNode() + self.rigidBaseNode = self._addRigidBaseNode() cosserat_geometry = CosseratGeometry(beamGeometryParams) self.frames3D = cosserat_geometry.cable_positionF - # [positionS, curv_abs_inputS, sectionsLength, framesF, curv_abs_outputF, self.frames3D] = __buildCosseratGeometry(params.beamGeoParams) - - self.cosseratCoordinateNode = self.addCosseratCoordinate(cosserat_geometry.bendingState, + self.cosseratCoordinateNode = self._addCosseratCoordinate(cosserat_geometry.bendingState, cosserat_geometry.sectionsLengthList) - self.cosseratFrame = self.addCosseratFrame(cosserat_geometry.framesF, cosserat_geometry.curv_abs_inputS, + self.cosseratFrame = self._addCosseratFrame(cosserat_geometry.framesF, cosserat_geometry.curv_abs_inputS, cosserat_geometry.curv_abs_outputF) def init(self): @@ -104,18 +80,18 @@ def addCollisionModel(self): tab_edges = generate_edge_list(self.frames3D) return addEdgeCollision(self.cosseratFrame, self.frames3D, tab_edges) - def addPointCollisionModel(self, nodeName='CollisionPoints'): + def _addPointCollisionModel(self, nodeName='CollisionPoints'): tab_edges = generate_edge_list(self.frames3D) return addPointsCollision(self.cosseratFrame, self.frames3D, tab_edges, nodeName) - def addSlidingPoints(self): + def _addSlidingPoints(self): slidingPoint = self.cosseratFrame.addChild('slidingPoint') slidingPoint.addObject('MechanicalObject', name="slidingPointMO", position=self.frames3D, showObject="0", showIndices="0") slidingPoint.addObject('IdentityMapping') return slidingPoint - def addSlidingPointsWithContainer(self): + def _addSlidingPointsWithContainer(self): slidingPoint = self.cosseratFrame.addChild('slidingPoint') slidingPoint.addObject("PointSetTopologyContainer") slidingPoint.addObject("PointSetTopologyModifier") @@ -124,14 +100,11 @@ def addSlidingPointsWithContainer(self): slidingPoint.addObject('IdentityMapping') return slidingPoint - def addRigidBaseNode(self): + def _addRigidBaseNode(self): rigidBaseNode = self.addChild('rigidBase') - - # trans = [t for t in self.translation.value] trans = list(self.translation.value) rot = list(self.rotation.value) - # @todo converter - positions = [list(pos) for pos in self.position.value] + positions = [[self.params.beamGeoParams.init_pos] + [0., 0., 0., 1.]] rigidBaseNode.addObject('MechanicalObject', template='Rigid3d', name="RigidBaseMO", showObjectScale=0.2, translation=trans, position=positions, rotation=rot, @@ -145,7 +118,7 @@ def addRigidBaseNode(self): external_points=0, mstate="@RigidBaseMO", points=0, template="Rigid3d") return rigidBaseNode - def addCosseratCoordinate(self, bendingStates, listOfSectionsLength): + def _addCosseratCoordinate(self, bendingStates, listOfSectionsLength): cosseratCoordinateNode = self.addChild('cosseratCoordinate') cosseratCoordinateNode.addObject('MechanicalObject', template='Vec3d', name='cosseratCoordinateMO', @@ -153,11 +126,16 @@ def addCosseratCoordinate(self, bendingStates, listOfSectionsLength): showIndices=0) if self.useInertiaParams is False: - cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, - length=listOfSectionsLength, radius=self.radius, - youngModulus=self.youngModulus.value, poissonRatio=self.poissonRatio.value, - rayleighStiffness=self.rayleighStiffness.value, - lengthY=self.length_Y.value, lengthZ=self.length_Z.value) + cosseratCoordinateNode.addObject('BeamHookeLawForceField', + crossSectionShape=self.params.beamPhysicsParams.beamShape, + length=listOfSectionsLength, + radius=self.radius, + youngModulus=self.params.beamPhysicsParams.youngModulus, + poissonRatio=self.params.beamPhysicsParams.poissonRatio, + rayleighStiffness=self.params.simuParams.rayleighStiffness, + lengthY=self.params.beamPhysicsParams.length_Y, + lengthZ=self.params.beamPhysicsParams.length_Z + ) else: self._extracted_from_addCosseratCoordinate_15( cosseratCoordinateNode, listOfSectionsLength @@ -176,7 +154,7 @@ def _extracted_from_addCosseratCoordinate_15(self, cosseratCoordinateNode, listO GI=GI, GA=GA, EI=EI, EA=EA, rayleighStiffness=self.rayleighStiffness.value, lengthY=self.length_Y.value, lengthZ=self.length_Z.value) - def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): + def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): cosseratInSofaFrameNode = self.rigidBaseNode.addChild( 'cosseratInSofaFrameNode') @@ -195,92 +173,8 @@ def addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): return cosseratInSofaFrameNode -class CosseratGeometry: - def __init__(self, beamGeoParams): - # Data validation checks for beamGeoParams - if not isinstance(beamGeoParams, BeamGeometryParameters): - raise ValueError("beamGeoParams must be an instance of BeamGeoParams.") - - self.bendingState, self.curv_abs_inputS, self.sectionsLengthList = self.__calculate_beam_parameters(beamGeoParams) - self.framesF, self.curv_abs_outputF, self.cable_positionF = self.__calculate_frame_parameters(beamGeoParams) - - def __calculate_beam_parameters(self, beamGeoParams): - # Data validation checks for beamGeoParams attributes - if not all(hasattr(beamGeoParams, attr) for attr in ['init_pos', 'beamLength', 'nbSection']): - raise ValueError("beamGeoParams must have 'init_pos', 'beamLength', and 'nbSection' attributes.") - - total_length = beamGeoParams.beamLength - nb_sections = beamGeoParams.nbSection - x, y, z = beamGeoParams.init_pos - - if not all(isinstance(val, (int, float)) for val in [x, y, z, total_length]): - raise ValueError("init_pos and beamLength in beamGeoParams must be numeric values.") - - if not isinstance(nb_sections, int) or nb_sections <= 0: - raise ValueError("nbSection in beamGeoParams must be a positive integer.") - - length_s = total_length / nb_sections - bendingState = [] - listOfSectionsLength = [] - temp = x - curv_abs_input_s = [x] - - for i in range(nb_sections): - bendingState.append([0, 0, 0]) - listOfSectionsLength.append((((i + 1) * length_s) - i * length_s)) - temp += listOfSectionsLength[i] - curv_abs_input_s.append(temp) - curv_abs_input_s[nb_sections] = total_length + x - - return bendingState, curv_abs_input_s, listOfSectionsLength - - def __calculate_frame_parameters(self, beamGeoParams): - # Data validation checks for beamGeoParams attributes - # if not all(hasattr(beamGeoParams, attr) for attr in ['init_pos', 'beamLength', 'nbFrames']): - # raise ValueError("beamGeoParams must have 'init_pos', 'beamLength', and 'nbFrames' attributes.") +Params = Parameters(beamGeoParams=BeamGeometryParameters(init_pos=[0, 0, 0])) - x, y, z = beamGeoParams.init_pos - total_length = beamGeoParams.beamLength - nb_frames = beamGeoParams.nbFrames - - if not all(isinstance(val, (int, float)) for val in [x, y, z, total_length]): - raise ValueError("init_pos and beamLength in beamGeoParams must be numeric values.") - - if not isinstance(nb_frames, int) or nb_frames <= 0: - raise ValueError("nbFrames in beamGeoParams must be a positive integer.") - - length_f = total_length / nb_frames - frames_f = [] - curv_abs_output_f = [] - cable_position_f = [] - - for i in range(nb_frames): - sol = i * length_f - frames_f.append([sol + x, y, z, 0, 0, 0, 1]) - cable_position_f.append([sol + x, y, z]) - curv_abs_output_f.append(sol + x) - - frames_f.append([total_length + x, y, z, 0, 0, 0, 1]) - cable_position_f.append([total_length + x, y, z]) - curv_abs_output_f.append(total_length + x) - - return frames_f, curv_abs_output_f, cable_position_f - -from typing import List - -def generate_edge_list(cable3DPos: List[List[float]]) -> List[int]: - """ - Generate an edge list required in the EdgeSetTopologyContainer component. - - Parameters: - cable3DPos (List[List[float]]): A list of 3D points representing the cable positions. - - Returns: - List[int]: A list of indices forming edges in the EdgeSetTopologyContainer. - """ - number_of_points = len(cable3DPos) - edge_list = [i for i in range(number_of_points - 1) for _ in range(2)] - return edge_list def createScene(rootNode): addHeader(rootNode) @@ -300,8 +194,9 @@ def createScene(rootNode): template="CompressedRowSparseMatrixd") solverNode.addObject('GenericConstraintCorrection') + # Create a cosserat = solverNode.addChild( - CosseratBase(parent=solverNode, cosseratGeometry=cosserat_config, name="cosserat", radius=0.15)) + CosseratBase(parent=solverNode, params=Params)) # use this to add the collision if the beam will interact with another object cosserat.addCollisionModel() @@ -309,7 +204,5 @@ def createScene(rootNode): # Attach a force at the beam tip, # we can attach this force to a non-mechanical node to control the beam in order to be able to drive it. beamFrame = cosserat.cosseratFrame - beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-2, indices=12, - force=[0., -100., 0., 0., 0., 0.]) return rootNode diff --git a/examples/python3/useful/geometry.py b/examples/python3/useful/geometry.py new file mode 100644 index 00000000..54778369 --- /dev/null +++ b/examples/python3/useful/geometry.py @@ -0,0 +1,89 @@ +# +from typing import List +from useful.params import BeamGeometryParameters + +def calculate_beam_parameters(beamGeoParams): + # Data validation checks for beamGeoParams attributes + if not all(hasattr(beamGeoParams, attr) for attr in ['init_pos', 'beamLength', 'nbSection']): + raise ValueError("beamGeoParams must have 'init_pos', 'beamLength', and 'nbSection' attributes.") + + total_length = beamGeoParams.beamLength + nb_sections = beamGeoParams.nbSection + x, y, z = beamGeoParams.init_pos + + if not all(isinstance(val, (int, float)) for val in [x, y, z, total_length]): + raise ValueError("init_pos and beamLength in beamGeoParams must be numeric values.") + + if not isinstance(nb_sections, int) or nb_sections <= 0: + raise ValueError("nbSection in beamGeoParams must be a positive integer.") + + length_s = total_length / nb_sections + bendingState = [] + listOfSectionsLength = [] + temp = x + curv_abs_input_s = [x] + + for i in range(nb_sections): + bendingState.append([0, 0, 0]) + listOfSectionsLength.append((((i + 1) * length_s) - i * length_s)) + temp += listOfSectionsLength[i] + curv_abs_input_s.append(temp) + curv_abs_input_s[nb_sections] = total_length + x + + return bendingState, curv_abs_input_s, listOfSectionsLength + + +def calculate_frame_parameters(beamGeoParams): + # Data validation checks for beamGeoParams attributes + if not all(hasattr(beamGeoParams, attr) for attr in ['init_pos', 'beamLength', 'nbFrames']): + raise ValueError("beamGeoParams must have 'init_pos', 'beamLength', and 'nbFrames' attributes.") + + x, y, z = beamGeoParams.init_pos + total_length = beamGeoParams.beamLength + nb_frames = beamGeoParams.nbFrames + + if not all(isinstance(val, (int, float)) for val in [x, y, z, total_length]): + raise ValueError("init_pos and beamLength in beamGeoParams must be numeric values.") + + if not isinstance(nb_frames, int) or nb_frames <= 0: + raise ValueError("nbFrames in beamGeoParams must be a positive integer.") + + length_f = total_length / nb_frames + frames_f = [] + curv_abs_output_f = [] + cable_position_f = [] + + for i in range(nb_frames): + sol = i * length_f + frames_f.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + curv_abs_output_f.append(sol + x) + + frames_f.append([total_length + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([total_length + x, y, z]) + curv_abs_output_f.append(total_length + x) + + return frames_f, curv_abs_output_f, cable_position_f + + +def generate_edge_list(cable3DPos: List[List[float]]) -> List[int]: + """ + Generate an edge list required in the EdgeSetTopologyContainer component. + + Parameters: + cable3DPos (List[List[float]]): A list of 3D points representing the cable positions. + + Returns: + List[int]: A list of indices forming edges in the EdgeSetTopologyContainer. + """ + number_of_points = len(cable3DPos) + return [i for i in range(number_of_points - 1) for _ in range(2)] + +class CosseratGeometry: + def __init__(self, beamGeoParams): + # Data validation checks for beamGeoParams + if not isinstance(beamGeoParams, BeamGeometryParameters): + raise ValueError("beamGeoParams must be an instance of BeamGeoParams.") + + self.bendingState, self.curv_abs_inputS, self.sectionsLengthList = calculate_beam_parameters(beamGeoParams) + self.framesF, self.curv_abs_outputF, self.cable_positionF = calculate_frame_parameters(beamGeoParams) diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py index 62fab49e..a9ac6f69 100644 --- a/examples/python3/useful/params.py +++ b/examples/python3/useful/params.py @@ -1,38 +1,59 @@ # @todo use this dataclass to create the cosserat object from dataclasses import dataclass, field +from typing import List + + +@dataclass +class BeamGeometryParameters: + """Cosserat Beam Geometry parameters""" + beamLength: float = 1.0 # beam length in m + nbSection: int = 5 # number of sections, sections along the beam length + nbFrames: int = 30 # number of frames along the beam + buildCollisionModel: int = 0 + init_pos: List[float] = field(default_factory=lambda: [0., 0., 0.]) # The beam rigid base position as a list [x, y, z] + showFramesObject: int = 1 + showRigidBaseObject: int = 1 + + @dataclass class BeamPhysicsParameters: - """one can only use one of the following two parameters""" + """Cosserat Beam Physics parameters""" """First set of parameters""" - youngModulus: float = 1.205e11 - poissonRatio: float = 0.499 + youngModulus: float = 1.205e8 + poissonRatio: float = 0.3 + """Second set of parameters""" useInertia: bool = False GI: float = 1.5708 GA: float = 3.1416e4 EI: float = 0.7854 EA: float = 3.1416e4 - """Common parameters, this parameters are used in both cases""" - beamMass: float = 1. - beamLength: float = 1. # beam length in m - beamRadius: float = 0.02 / 2. # beam radius in m -@dataclass -class BeamGeometryParameters: - """cosserat beam Geometry parameters""" - # init_pos: str = "0. 0. 0." # list[float] # = [0., 0., 0.], The beam rigid base position - init_pos: list[float] = field(default_factory=list) - beamLength: float = 1. # beam length in m - nbSection: int = 5 # number of sections, here sections are not cross-sections but sections along the beam length - nbFrames: int = 30 - buildCollisionModel: int = 0 + """Common parameters used in both cases""" + beamMass: float = 1.0 + beamRadius: float = 0.02 / 2.0 # beam radius in m + beamLength: float = 1.0 # beam length in m along the X axis + # Todo : add complex beam shape + beamShape: str = "circular" # beam shape, circular or rectangular + """"If using rectangular beam shape""" + length_Y: float = 0.1 # length of the beam in the Y direction + length_Z: float = 0.1 # length of the beam in the Z direction + @dataclass class SimulationParameters: """Simulation parameters""" rayleighStiffness: float = 0.2 rayleighMass: float = 0.1 + firstOrder: bool = False + +@dataclass +class VisualParameters: + """Visual parameters""" + showObject: int = 1 + showObjectScale: float = 1.0 + showObjectColor: List[float] = field(default_factory=lambda: [1.0, 0.0, 0.0, 1.0]) @dataclass class ContactParameters: @@ -46,14 +67,13 @@ class ContactParameters: maxIterations: int = 100 epsilon: float = 1.e-6 - -# @dataclass -# class Parameters: -# """Parameters for the cosserat beam""" -# beamPhysicsParams: BeamPhysicsParameters = BeamPhysicsParameters() -# simuParams: SimulationParameters = SimulationParameters() -# contactParams: ContactParameters = ContactParameters() -# beamGeoParams: BeamGeometryParameters = BeamGeometryParameters() - +@dataclass +class Parameters: + """Parameters for the Cosserat Beam""" + beamPhysicsParams: BeamPhysicsParameters = field(default_factory=BeamPhysicsParameters) + simuParams: SimulationParameters = field(default_factory=SimulationParameters) # SimulationParameters() + contactParams: ContactParameters = field(default_factory=ContactParameters) # ContactParameters() + beamGeoParams: BeamGeometryParameters = field(default_factory=BeamGeometryParameters) + visualParams: VisualParameters = field(default_factory=VisualParameters) diff --git a/examples/python3/cosserat/utils.py b/examples/python3/useful/utils.py similarity index 96% rename from examples/python3/cosserat/utils.py rename to examples/python3/useful/utils.py index a136fea2..9e1fc061 100644 --- a/examples/python3/cosserat/utils.py +++ b/examples/python3/useful/utils.py @@ -12,8 +12,7 @@ def addEdgeCollision(parentNode, position3D, edges): collisInstrumentCombined.addObject('IdentityMapping', name="mapping") return collisInstrumentCombined - -# @info: This function is used to build the beam collision node +"""@info: This function is used to build the beam collision node""" def addPointsCollision(parentNode, position3D, edges, nodeName): collisInstrumentCombined = parentNode.addChild(nodeName) collisInstrumentCombined.addObject('EdgeSetTopologyContainer', name="beamContainer", position=position3D, @@ -26,7 +25,7 @@ def addPointsCollision(parentNode, position3D, edges, nodeName): return collisInstrumentCombined -# @info: This function is used to build the constraint node + # """ @info: This function is used to build the constraint node""" def addConstraintPoint(parentNode, beamPath): constraintPointsNode = parentNode.addChild('constraintPoints') constraintPointsNode.addObject("PointSetTopologyContainer", name="constraintPtsContainer", listening="1") From ef81e005ea756e7d12658dadaa529f8776632567 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Thu, 3 Aug 2023 01:01:08 +0200 Subject: [PATCH 06/71] Revamped ISIR robot scene with enhanced functionality. The discs are now seamlessly attached to the central rod of the robot using the RigidMapping. The scene has been updated to utilize the newly implemented python class for cosserat beams, , which takes advantage of dataclasses for improved data handling and organization. --- examples/python3/actuators/example1.py | 60 ++++++++------------- examples/python3/cosserat/CosseratBase.py | 26 +++++---- examples/python3/cosserat/cosseratObject.py | 2 +- examples/python3/useful/params.py | 2 + 4 files changed, 42 insertions(+), 48 deletions(-) diff --git a/examples/python3/actuators/example1.py b/examples/python3/actuators/example1.py index 1dffd2a1..22ed2f97 100644 --- a/examples/python3/actuators/example1.py +++ b/examples/python3/actuators/example1.py @@ -1,18 +1,15 @@ # -*- coding: utf-8 -*- """ - Cosserat class in SofaPython3. + Scene robot ISIR. """ - - __authors__ = "Yinoussa" __contact__ = "adagolodjo@protonmail.com" __version__ = "1.0.0" __copyright__ = "(c) 2021,Inria" __date__ = "July, 20 2023" -from useful.header import addHeader +from useful.header import addHeader, addSolverNode from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters -from cosserat.cosseratObject import Cosserat from useful.params import Parameters from cosserat.CosseratBase import CosseratBase @@ -47,23 +44,19 @@ # [@info] ================ Unit: N, cm, g, Pa ================ """ - - -# @todo use CableGeometryParameters & CableParameters in Cosserat class for both geometry and physics parameters -geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, - nbSection=5, nbFrames=30, buildCollisionModel=0) -physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus= 1.0e8, poissonRatio=0.38, beamRadius=6.2e-1/2., +# @todo +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, showFramesObject=1, + nbSection=5, nbFrames=26, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus= 1.0e8, poissonRatio=0.38, beamRadius=6.2e-1/2., beamLength=65.5) simuParams = SimulationParameters(rayleighStiffness=1.e-3) - -isCollisionModel = 0 - +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) -def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState"): +def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState",rigidIndex=2): """ The intermediateRigid construction """ if rigidCentral is None: - rigidCentral = [3, 0., 0, 0, 0, 0, 1] + rigidCentral = [0, 0., 0, 0, 0, 0, 1] q0 = Quat() q1 = Quat() q2 = Quat() @@ -74,15 +67,15 @@ def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState"): intermediateRigid = parent.addChild('intermediateRigid') intermediateRigid.addObject('MechanicalObject', name=baseName, template='Rigid3d', position=rigidCentral, showObject=True, showObjectScale=0.4) - intermediateRigid.addObject('RestShapeSpringsForceField', name='rigid', stiffness=1.e1, template="Rigid3d", - angularStiffness=1.e1, external_points=0, points=0) + # @TODO add the mass of the disk + intermediateRigid.addObject('RigidMapping', name="interRigidMap", index=rigidIndex) + """Create intermediate kids""" interRigidChild = intermediateRigid.addChild('interRigidChild') interRigidChild.addObject('MechanicalObject', name="interRigidChildMo", template='Rigid3d', position=interChildPos, showObject=True, showObjectScale=0.4) interRigidChild.addObject('RigidMapping', name="interRigidMap") - """ Add disk to the scene, actually this disk is only use for the visualisation """ loadDisk(intermediateRigid) @@ -96,34 +89,27 @@ def loadDisk(parentNode): diskMapping.addObject('RigidMapping', name="diskMap") -def createRigidDisk(rootNode, length=65.5): # @todo add a parameter for the number of disk - diskSolverNode = rootNode.addChild('diskSolverNode') - diskSolverNode.addObject('EulerImplicitSolver', firstOrder=0, rayleighStiffness=0.01, rayleighMass=0.) - diskSolverNode.addObject('SparseLDLSolver', name='solver') - +def createRigidDisk(parentNode): # @todo add a parameter for the number of disk + """ Create the rigid disk nodes """ for i in range(1, 14): """ Create the rigid disk nodes """ - createIntermediateNode(diskSolverNode, rigidCentral=[i*(length/13.), 0., 0, 0, 0, 0, 1], baseName=f"rigidState{i}") - - # """ The intermediateRigid construction """ - # intermediateRigid = createIntermediateNode(diskSolverNode) - return diskSolverNode - + createIntermediateNode(parentNode, rigidCentral=[0, 0., 0, 0, 0, 0, 1], + baseName=f"rigidState{i}", rigidIndex=i*2) -Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) def createScene(rootNode): addHeader(rootNode) rootNode.gravity = [0., -9.81, 0.] - stemNode = rootNode.addChild('stemNode') - stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) - # Cosserat(parent=stemNode, cosseratGeometry=nonLinearConfig, inertialParams=inertialParams, radius=Rb, - # useCollisionModel=isCollisionModel, name="cosserat", youngModulus=YM, poissonRatio=PR, - # rayleighStiffness=rayleighStiffness)) + stemNode = addSolverNode(rootNode, name="stemNode") + cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) # create the rigid disk node - # createRigidDisk(rootNode) + createRigidDisk(cosserat.cosseratFrame) + return + + + diff --git a/examples/python3/cosserat/CosseratBase.py b/examples/python3/cosserat/CosseratBase.py index af283793..88865af9 100644 --- a/examples/python3/cosserat/CosseratBase.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -144,15 +144,19 @@ def _addCosseratCoordinate(self, bendingStates, listOfSectionsLength): # TODO Rename this here and in `addCosseratCoordinate` def _extracted_from_addCosseratCoordinate_15(self, cosseratCoordinateNode, listOfSectionsLength): - GA = self.inertialParams['GA'] - GI = self.inertialParams['GI'] - EA = self.inertialParams['EA'] - EI = self.inertialParams['EI'] - print(f'{GA}') - cosseratCoordinateNode.addObject('BeamHookeLawForceField', crossSectionShape=self.shape.value, - length=listOfSectionsLength, radius=self.radius, useInertiaParams=True, - GI=GI, GA=GA, EI=EI, EA=EA, rayleighStiffness=self.rayleighStiffness.value, - lengthY=self.length_Y.value, lengthZ=self.length_Z.value) + GA = self.params.beamPhysicsParams.GA + GI = self.params.beamPhysicsParams.GI + EA = self.params.beamPhysicsParams.EA + EI = self.params.beamPhysicsParams.EI + cosseratCoordinateNode.addObject('BeamHookeLawForceField', + crossSectionShape=self.params.beamPhysicsParams.beamShape, + length=listOfSectionsLength, + radius=self.params.beamPhysicsParams.beamRadius, + useInertiaParams=True, + GI=GI, GA=GA, EI=EI, EA=EA, + rayleighStiffness=self.rayleighStiffness.value, + lengthY=self.params.beamPhysicsParams.length_Y, + lengthZ=self.params.beamPhysicsParams.length_Z) def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): @@ -160,7 +164,9 @@ def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): 'cosseratInSofaFrameNode') self.cosseratCoordinateNode.addChild(cosseratInSofaFrameNode) framesMO = cosseratInSofaFrameNode.addObject( - 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showObject=1, showObjectScale=0.001) + 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, + showIndices=self.params.beamGeoParams.showFramesObject, + showObject=self.params.beamGeoParams.showFramesObject, showObjectScale=0.1) if self.beamMass != 0.: cosseratInSofaFrameNode.addObject( 'UniformMass', totalMass=self.beamMass, showAxisSizeFactor='0') diff --git a/examples/python3/cosserat/cosseratObject.py b/examples/python3/cosserat/cosseratObject.py index 6f353960..ec97050b 100644 --- a/examples/python3/cosserat/cosseratObject.py +++ b/examples/python3/cosserat/cosseratObject.py @@ -11,7 +11,7 @@ import Sofa from cosserat.usefulFunctions import buildEdges, pluginList, BuildCosseratGeometry -from cosserat.utils import addEdgeCollision, addPointsCollision +from useful.utils import addEdgeCollision, addPointsCollision cosserat_config = {'init_pos': [0., 0., 0.], 'tot_length': 6, 'nbSectionS': 6, 'nbFramesF': 12, 'buildCollisionModel': 1, 'beamMass': 0.22} diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py index a9ac6f69..cbc1aada 100644 --- a/examples/python3/useful/params.py +++ b/examples/python3/useful/params.py @@ -12,6 +12,8 @@ class BeamGeometryParameters: nbFrames: int = 30 # number of frames along the beam buildCollisionModel: int = 0 init_pos: List[float] = field(default_factory=lambda: [0., 0., 0.]) # The beam rigid base position as a list [x, y, z] + + """Parameters for the visualisation of the beam""" showFramesObject: int = 1 showRigidBaseObject: int = 1 From afcf84e223da9da1b3bb93b55483ced8edb78871 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Thu, 24 Aug 2023 18:25:00 +0200 Subject: [PATCH 07/71] upd --- examples/python3/actuators/cable.json | 14 +++ examples/python3/actuators/cable.py | 87 +++++++++++++++++ examples/python3/actuators/step3.py | 129 ++++++++++++++++++++++++++ 3 files changed, 230 insertions(+) create mode 100644 examples/python3/actuators/cable.json create mode 100644 examples/python3/actuators/cable.py create mode 100644 examples/python3/actuators/step3.py diff --git a/examples/python3/actuators/cable.json b/examples/python3/actuators/cable.json new file mode 100644 index 00000000..d848a9b7 --- /dev/null +++ b/examples/python3/actuators/cable.json @@ -0,0 +1,14 @@ +[[-17.5, 12.5, 2.5], + [-32.5, 12.5, 2.5], + [-47.5, 12.5, 2.5], + [-62.5, 12.5, 2.5], + [-77.5, 12.5, 2.5], + [-83.5, 12.5, 4.5], + [-85.5, 12.5, 6.5], + [-85.5, 12.5, 8.5], + [-83.5, 12.5, 10.5], + [-77.5, 12.5, 12.5], + [-62.5, 12.5, 12.5], + [-47.5, 12.5, 12.5], + [-32.5, 12.5, 12.5], + [-17.5, 12.5, 12.5]] diff --git a/examples/python3/actuators/cable.py b/examples/python3/actuators/cable.py new file mode 100644 index 00000000..7b242dd9 --- /dev/null +++ b/examples/python3/actuators/cable.py @@ -0,0 +1,87 @@ +def PullingCable(attachedTo=None, + name="Cable", + cableGeometry=[[1.0, 0.0, 0.0], [0.0, 0.0, 0.0]], + rotation=[0.0, 0.0, 0.0], + translation=[0.0, 0.0, 0.0], + uniformScale=1.0, + pullPointLocation=None, + initialValue=0.0, + valueType="displacement"): + """Adds a cable constraint. + + The constraint apply to a parent mesh. + + Args: + name (str): Name of the added cable. + + cableGeometry: (list vec3): Location of the degree of freedom of the cable. + + pullPointLocation (vec3): Position from where the cable is pulled. If not specified + the point will be considered in the structure. + + valueType (str): either "force" or "displacement". Default is displacement. + + translation (vec3): Apply a 3D translation to the object. + + rotation (vec3): Apply a 3D rotation to the object in Euler angles. + + uniformScale (vec3): Apply an uniform scaling to the object. + + + Structure: + .. sourcecode:: qml + + Node : { + name : "Cable" + MechanicalObject, + CableConstraint, + BarycentricMapping + } + + """ + # This add a new node in the scene. This node is appended to the finger's node. + cable = attachedTo.addChild(name) + + # This add a MechanicalObject, a component holding the degree of freedom of our + # mechanical modelling. In the case of a cable it is a set of positions specifying + # the points where the cable is passing by. + cable.addObject('MechanicalObject', position=cableGeometry, + rotation=rotation, translation=translation, scale=uniformScale) + + # Add a CableConstraint object with a name. + # the indices are referring to the MechanicalObject's positions. + # The last indice is where the pullPoint is connected. + if pullPointLocation is not None: + cable.addObject('CableConstraint', + indices=list(range(len(cableGeometry))), + pullPoint=pullPointLocation, + value=initialValue, + valueType=valueType, + hasPullPoint=True + ) + else: + cable.addObject('CableConstraint', + indices=list(range(len(cableGeometry))), + value=initialValue, + valueType=valueType, + hasPullPoint=False + ) + + # This add a BarycentricMapping. A BarycentricMapping is a key element as it will add a bi-directional link + # between the cable's DoFs and the parents's ones so that movements of the cable's DoFs will be mapped + # to the finger and vice-versa; + cable.addObject('BarycentricMapping', name="Mapping", mapForces=False, mapMasses=False) + + return cable + + +def createScene(node): + from stlib3.scene import MainHeader + from stlib3.physics.deformable import ElasticMaterialObject + + MainHeader(node, plugins=["SoftRobots"]) + target = ElasticMaterialObject(volumeMeshFileName="mesh/liver.msh", + totalMass=0.5, + attachedTo=node) + + PullingCable(target) diff --git a/examples/python3/actuators/step3.py b/examples/python3/actuators/step3.py new file mode 100644 index 00000000..9c862464 --- /dev/null +++ b/examples/python3/actuators/step3.py @@ -0,0 +1,129 @@ +# -*- coding: utf-8 -*- +""" + Scene robot ISIR. +""" +__authors__ = "Yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +from useful.header import addHeader, addSolverNode +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from cable import PullingCable +from splib3.loaders import loadPointListFromFile + +import os +from splib3.numerics.quat import Quat + +path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' + +""" @info +Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) + et de 13 disques en iglidur. + + -La colonne mesure 65.5 cm pour un diamètre de 6.2mm + +# -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g +# +# -Les disques sur la colonne sont espacés d'environ 4.7cm +# +# -Concernant les trous des disques, il y en a 3 sortes : +# +# les trous intérieurs sont au nombre de 3, ont un diamètre de 2mm et sont placés à environ 6mm du centre +# les trous intermédiaires sont au nombre de 3, ont un diamètre de 2.5mm et sont placés à environ 2cm du centre +# les trous extérieurs sont au nombre de 12, ont un diamètre de 1mm et sont placés à environ 2.3cm du centre +# -Enfin concernant le routage des câbles : +# +# Le manipulateur est constitué de 3 sections, chaque section est composé de 3 fils (disposés à 120° les uns des autres) +# Les câbles sont routés de manière parallèle +# La première section (celle du haut) ainsi que la deuxième (intermédiaire) sont constituées de 4 disques et la +# troisième (celle du bas) de 5 disques +# Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 +# passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. +# [@info] ================ Unit: N, cm, g, Pa ================ +""" + +# @todo +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, showFramesObject=1, + nbSection=5, nbFrames=26, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus= 1.0e8, poissonRatio=0.38, beamRadius=6.2e-1/2., + beamLength=65.5) +simuParams = SimulationParameters(rayleighStiffness=1.e-3) +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + + +def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState",rigidIndex=2): + """ The intermediateRigid construction """ + if rigidCentral is None: + rigidCentral = [0, 0., 0, 0, 0, 0, 1] + q0 = Quat() + q1 = Quat() + q2 = Quat() + + interChildPos = [[0, 1.7, 1., q0[0], q0[1], q0[2], q0[3]], + [0, -1.7, 1., q1[0], q1[1], q1[2], q1[3]], + [0., 0., -2., q2[0], q2[1], q2[2], q2[3]]] + intermediateRigid = parent.addChild('intermediateRigid') + intermediateRigid.addObject('MechanicalObject', name=baseName, template='Rigid3d', + position=rigidCentral, showObject=True, showObjectScale=0.4) + # @TODO add the mass of the disk + intermediateRigid.addObject('RigidMapping', name="interRigidMap", index=rigidIndex) + + """Create intermediate kids""" + interRigidChild = intermediateRigid.addChild('interRigidChild') + interRigidChild.addObject('MechanicalObject', name="interRigidChildMo", template='Rigid3d', + position=interChildPos, showObject=True, showObjectScale=0.4) + interRigidChild.addObject('RigidMapping', name="interRigidMap") + + """ Add disk to the scene, actually this disk is only use for the visualisation """ + loadDisk(intermediateRigid) + + return intermediateRigid + +def loadDisk(parentNode): + #### MAPPING of the disks (here some torus) #### ########### + diskMapping = parentNode.addChild("diskMapping") + diskMapping.addObject("MeshOBJLoader", name="diskLoader", filename=f'{path}disqueBlender2.obj') + diskMapping.addObject("OglModel", name="Visual", src="@diskLoader", color="1.0 0.5 0.25 1.0") + diskMapping.addObject('RigidMapping', name="diskMap") + + +def createRigidDisk(parentNode): # @todo add a parameter for the number of disk + """ Create the rigid disk nodes """ + for i in range(1, 14): + """ Create the rigid disk nodes """ + createIntermediateNode(parentNode, rigidCentral=[0, 0., 0, 0, 0, 0, 1], + baseName=f"rigidState{i}", rigidIndex=i*2) + +rotation=[0.0, 0.0, 0.0] +translation=[0.0, 0.0, 0.0] +pullPointLocation=[0.0, 0.0, 0.0] +youngModulus=18000 +valueType='position' +def createScene(rootNode): + addHeader(rootNode) + rootNode.gravity = [0., -9.81, 0.] + + stemNode = addSolverNode(rootNode, name="stemNode") + cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) + + # create the rigid disk node + createRigidDisk(cosserat.cosseratFrame) + + PullingCable(stemNode, + "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=loadPointListFromFile(os.path.join(path, "../cable.json")), + valueType=valueType) + return + + + + + + From e63e6ae6b27304d5a4e120a86aaa77e55b11760e Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo Date: Thu, 31 Aug 2023 17:19:03 +0200 Subject: [PATCH 08/71] Add mesh data to repository --- examples/python3/actuators/example1.py | 9 +- examples/python3/actuators/mesh/Tige.STL | Bin 0 -> 7284 bytes examples/python3/actuators/mesh/Trompe.STL | Bin 0 -> 2290084 bytes examples/python3/actuators/mesh/Trompe07.stl | Bin 0 -> 3079184 bytes examples/python3/actuators/mesh/disque.stl | Bin 0 -> 175684 bytes .../python3/actuators/mesh/disqueMeshLab.obj | 6968 +++++++++++++++++ .../python3/actuators/mesh/manipulateur.jpg | Bin 0 -> 2435409 bytes examples/python3/actuators/step3.py | 4 + examples/python3/cosserat/test3.py | 21 + examples/python3/useful/header.py | 2 + 10 files changed, 6999 insertions(+), 5 deletions(-) create mode 100644 examples/python3/actuators/mesh/Tige.STL create mode 100644 examples/python3/actuators/mesh/Trompe.STL create mode 100644 examples/python3/actuators/mesh/Trompe07.stl create mode 100644 examples/python3/actuators/mesh/disque.stl create mode 100644 examples/python3/actuators/mesh/disqueMeshLab.obj create mode 100644 examples/python3/actuators/mesh/manipulateur.jpg create mode 100644 examples/python3/cosserat/test3.py diff --git a/examples/python3/actuators/example1.py b/examples/python3/actuators/example1.py index 22ed2f97..b1eb6047 100644 --- a/examples/python3/actuators/example1.py +++ b/examples/python3/actuators/example1.py @@ -12,9 +12,7 @@ from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters from useful.params import Parameters from cosserat.CosseratBase import CosseratBase - import os -from splib3.numerics.quat import Quat path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' @@ -57,9 +55,10 @@ def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState",rigi """ The intermediateRigid construction """ if rigidCentral is None: rigidCentral = [0, 0., 0, 0, 0, 0, 1] - q0 = Quat() - q1 = Quat() - q2 = Quat() + q0 = [0, 0, 0, 1] + q1 = [0, 0, 0, 1] + q2 = [0, 0, 0, 1] + interChildPos = [[0, 1.7, 1., q0[0], q0[1], q0[2], q0[3]], [0, -1.7, 1., q1[0], q1[1], q1[2], q1[3]], diff --git a/examples/python3/actuators/mesh/Tige.STL b/examples/python3/actuators/mesh/Tige.STL new file mode 100644 index 0000000000000000000000000000000000000000..9361d39d41c04dd22dfda2f24c8f1744ad12619e GIT binary patch literal 7284 zcmb_gzpI@^5dBawy<%fyK>q^8!s5Mq3rQuy6ASGkDoG$9Xkn)d@ei=F^G6vJEVQul zeHNxLTG)sR5^f=if+8^~vrf-+1Z`h@4nYwxqRuRv(H|- z@bcOJ<@NS7P4C|O=KSRwpB$LkUgx(ke){_PgYRFxvYozo_(`{k`2F1L^PgAVI!veq z&|CQW5iID+tm2`p2uhVM-BD3Z5sca`CxPAn`=#D#88ym)UY+o zmKinF=l^K@HoBW2-PV97RvWeeA{iw>J)dY#JkmqTFUAJ5$GY zQmCOGw{0Cq4?eNI_|%Q2F=8mnZEDy_|J+VIHPquaYlRNjHH{HtniSRSu5r*bilgWW z20AO&f&S}RDML|iGtwW{f2~$UJ#O1N(0{QX!k8Rou@vPtHPC-;&x?B8X05Jn<6H?N z;xd+^n$7QjvHrVN&u&34GuDEE{)_$)hT(#tD7P8uruE;g+Ji+sZreH#AD=Pprb!r+ zqb!!9+@=QB@N1nVMLlj?+`6_tuY?hCEtaC(rUv!`6}AsWJ#L!@_8a?C*CC9EYjj1q zO%0r>HrtDO+%^rITb!V(A&iJ?u@vPtHQuxS`>@_PMLlkF53K*tVYG!2aT!Zd&328C ztk?Mgz07XKr(i(u8Jj1eaS}sOZZj-aZe4YZ59)Ed?Z=}w7o%1uF;Lx(a+@00>z-3X zJ#L#u-T&RDYK$0)a+?}A?d<+$cL+YH$8FQVIsVt~sj4wzD9UYWp#Q9^sG%OWO#_{V zd$DSa7>aV68f`LALp^Sr1||mYciJOHMl}XC+JvKqqv(ma=s!HC)OCy)igKHg+N7q2 zdfc|$(SLXT%n$!t+Dy$B3aQx2a(}h-V*asK;%te7A{nHDch&DNxO(MtdS_D_2i2 z@H`j&F=8mnZED=M{_8!c9=B~Bh#!4EVkpXOYS^td+das2sK;&7sL$7ZUX2)va+?}9 z;qcplGf_Qmn+Eo~Pt<7|F%;!CHEg!eeNwB(ZPUQHjr(K7P?X!$KyO@Yca(bEHVp#( z9vm?;3ZHtnfq~Ag2=z3(tpj~uXGudAd&t=6Eu*(ujc*z~Lqp?LHtNZY-Il)2Ab!bM z-p(gyrSn|x57lnr`IfU%hTd>vhN840&L~)iPEMWF>$1v>xJz8ajJyuNeXOEd5i%?z zyvjyrl+MI;S?x0{=qWoGvt27v)8YS?l}-blKI^i|jF^u#de_LY0;LtnS!v&CpXW%S zlJ`RyI*9_m+(AWYMKS|%aXL_UWEeexN=pwmTFxpn06C3O!&H=3q=n~O*l7D6L2+fPvlXyN36^o9nX54E=QVmK3_q{-weK?_YqH9W`0I{q zn31#cb7dZ_NM?9%+t=O`gsjPGpMhP>uVq$HdK~b z1xhOtcvRQ#4Ex$=?dq(Q;Zs`$%+6UUN-LtIG9xaZ=ijZe$yvmF@*mn){ zqwl6_S8V-1uRJsKFGa!041aDnfL4U~QdwozsgGIPPyV{Blu@VlY3E8&T9Ik`4-bYk A-~a#s literal 0 HcmV?d00001 diff --git a/examples/python3/actuators/mesh/Trompe.STL b/examples/python3/actuators/mesh/Trompe.STL new file mode 100644 index 0000000000000000000000000000000000000000..0299fc4431edf1b75103bbe987024518bf20130d GIT binary patch literal 2290084 zcmb@P37k*W|NoPH%w((V`;s-;@-?>3+fp$YTgX1v!7yZBKMiRt5y_UAv9$<^Xk*A0 z*~*flELlQCk%av3=N@x=9&_$*@_76|j~>%`c)gzI{XX0M+|T{o&$%!4?;G8%aLa-H zV`94({{Qg$<)er23e?$mvA2}?dWmejT&dpm=ljU=)4DviMOT^JVwwBz03Hg|Su?Ps z+W+KISDBHkr<%2Dfm@zdWwvTMb&-XLT{laW8`IuZDy3bfsyx(6)32^pB|p*sZpN4a zg+xT(^(yAFrcL6+zOhp6;n&@ISJfIKT_@>s=u^XGLW$QbS*3e@tn_aGrmOt)&}iBF z>Rh*cZey%`^wTU0@$`@aQoYAES9x@E4w)6L%NPH6O!m*&Xd$u}$S23%pX4gV*W{KH zqjWj^WC1CEYP^NWb@a0Oapf9UIacD5D!WaWU*3N~?Ha4gX3Jy$>@7=|Om&GGFZYp% z#=1N;ZH%m#sLLi%{rMeg-HOgGaq9E!s`blV-15O&ThxqC^}m}$n(wx&LbKYsuE~FH zR~5_Y^3)SM)sf$H*(5fs4-wV*ZI{UXSQcsifiA0I>1FBN1oz)f;;S^dq}h-;I!2Kk z^6mMz+;WB!*=6r6T{a2UJ8*IqDe_xtF&Ldhm0Y2+w4|QLW(*Q^^@|Ucg7LQ5PK89l zwV_g>nJosDz8%73P>go5CNnE4ByNU1BC|)>VvwM#=cY%b$}k(je*YjYyL{15j{(QY z%!&$$W}(^Taz@(-lA!D8>_?^Lb9yeAF{qH37RV;i`{!Ba6$!c;KAS_jotbSRsE}Ct zb5=RN)E0vTUAc;8lb0iHF{qGe9iCO*nrMqbg03t7dqgTtwH>dhkk~cx5g9tl7Gp+2 zh%8&BM=Eo#5NVulzS}=s1?G5AA+fn}h`iBW(GWD@L?_TPoc(J{Jz*oP)Tg~YH@VY23RTkn#ftAAXm3|?&`s6<@IB1KO;NLD0P zcFQ7>`D|;DS<$uZdWbyL#YXU$(Wrk`Y2V{Pj#ngFJ(f-8)wdmec)X(P<4?n+%P!k- zx8jZL68)^64WC!YAz%Kk=M|4J<_OaDaKjujYF=st>mpI3eh#UpY_pvNU6b(+XJ*CL z4qK5;etlf`kAKUlka(S$YA3=(wtuPBb~`#)_|e{I$EaxR!zQ6bT3 zLXw)D(bl^p==yKHOX36Bq!xwSVz4f{I4jL|+}gHXRc@nKXZxYs)y!-9xRUVMVb!f@ zBg^_ALD#-3+f~ucwsp>WU&y#!Ma)et2J0o!boe$^i<-1rmn-f6O8xfwbC#BeX56GYoYbySkx8m^9$hbwm1b5{NR;?+qw3n( zmK6!Qc+59rF!yJNe5tl4rq&L&kVNT(&1&%yO`9=D(A8+~CKdLXjo@eGoX2BjO6MtV zkB+_;E9u_UWi!UL7K5aJq`sa|bJZY;siMog=3o+3Nc6fpNPf*`yD~w7F8^y8R7hly z!Sc^pTRTY5m1FQ=xwzg&{Qk@Ud1~flw|~xt4UoE9bot`-{<6QgE}JcvGT~D zsS$K>oXi+hNK`!*E9uMH+ChRYj=vd$vtf6>0diowu9r2L1QindS`3h(*HX)ht^@N1 z$ZPp+v!r$Ym!w9lR(ibplI-sHATyCft1B-_u5Pv%oQZUC6__n&zAG;ekYlxUz3dT_ zphDtc#6XE^ZOe)TUCh>uL4`#0M+2ozFIx-}bg|dX80jhul%z6xR)2nAfNXB?AnSv~ z>*Ji&)jPHIK^NDinbn!agJn@(J>y1B9V}(f>U!TyJ6dY>dd2eo!6U#wvj$6%S2WEd zh8cqji7m?pOPNU9Y$rh%vo&MPxHV9^hU(lG&lo7VbLsN6s3G$B#&MQ*u(f4-4wiOn zQ)@ZS>8Vg07Hvj;Te323rU!Bwj4CS5=R<#UMe~=RfRIIp4Dp zRQAsKM&(_sU98D$ITaF_njBE0huC6}psVnugKAE38!im!+?$ka%p*5mh(FHcLp*^;P2cs^EKiR+=p@RN)6T`jB29-^Bi)_WY%1c*}{G z)blI!cRD6Pg~W+&Kd3EvZ0myrUCXlkpi0)U#b}W28};Ri4sM@RYQ9f>wnmrvdDqN} z3W=NZ_o&tmPmph9B!m?NtHYFkz$=$ie)cdB=Y zji6HL<{`CktR4^6x)*R{y5(jnSLY#-lK?)*5@T{#`f_K+PfPIJp)nR-fEyBYlXbalg?4i7-n|rN3@RidlA>h7CEK|u z3Az%8Mac`TZJ$_pXT{8meI)#%UQt}ZW>!>4)Tz{0qF>guKS7s&?@}R=r$t}Mp3@eC z1YI0iGb@f-x%1uS@PyPxkYh_CAy0SNxk}S!3=(t=Zr4qUT(A+GeQ)pWBg6LUac29> z7*t67+P05G^|#Fu5_H|#)>}^Gvk_FD&(&K-9M-wBCjYER6mJnNO%iP_XI*r$56u`< zNQ@iXOa2;di$Q`eu4Xev&6CH};&Pka^*naMX*G1)7jF6eW@l8)VO=(fHASwfDa$@_ zU6&63u4=!o%f&XFSL=3vW;rt4ctc*11MqOrxW;>{mSXAYrS|6`zli+x840i52t6G)+(vlSw5)(?CRZV}gjUWlSmfSk4 zP8_olRO0rWQ)R!^F4knWg9?ewGk;OzH`-#5psQJ<^D1tUjbJbC&3sWk)AB*agG7bT zFR0j}w(;Ny(&axBIomlai?sbkot$o)yHrTre)w0leXwnPkf1B(vGc0ua$5{4B zN#&nwi$Q`eu1#~ysgPLM^*1%~JzESCbnzHt#`x;uY4y(Ob?!Q-)9bAI?u0I94n3#l zKWAI#1#_HHs=l*cr4*+He*mBQF+(T>gsaa zY$rh%kJ@GouAFx+o>ytcKFF#iaVGYH%Gt`66;~}?cMe}r50$hL91o7c?Vr!6VIyq4 zONE60n3JH3?+j*NQ6bUy`Z@K{JGOa6f-e7eoV)LzREc}_QRcv*lPY&w-9MZ?W>!>4 z3@Cm|{Zhr&yCmr1yPX+hNv2b(O+}s6?yVrl$P~y4WU@ z==Q}gs{cTp)$xOe)mtrByIJ)MxuAxW(*JG}R7m*WLr;RPZ4)l4f|qS~-BTgKd-lz& zI%fP!tzV(@9eMmuRpmupF8#lUrC9Vzw@oHN*W+>5)xJklBUl%SJvaYQi;vsdL4vNo zoBpZZKk>$i(@S?Uv#7A?uIu4p8RT%;85V-B zjaM^ETz&2GC#aBkw_k`%ANqzR1_`?S+d+lIjTX-Df9B1!#2`Tz`_LQ@_7yWc{%{sa z`=Ra1HWdlT&P69ZM$;E-;D9MWYIt8lsoIMb^cO1HV$rR~%Dx)^IRdzT7{^W(G1`tNO5)kx6AelufGAyIdAm>hc7 zHXbDC@*fZWwvS`8D5iky3A43>3W=Uqi_5a!6D%W0g090e3dx6yY%!>iSW&d3od3WU zg9Kgs>K2hJ4Q+jud+U>OEleK`mJX^Qx%27r(dVnncV}$Jt24*S$`>p2H&xLE%gN@4 z^wH;+1103j8C^CAPOLSd)JY5}W5% zk~*VoF<2K}yE0Xlj!)YN)k(<N597L#n>M-`v;q*Sh`kI0<6 znQB*%c7<$5YAPg#Ua25A^4kbT|ENJ_X>#uyK4xq76%`U~&R3F}7i}>}&~;~ECF%FB zjrgfUWjTLNuc)50DvP|K%dE*iD-tU|tSq;~ZQmlZF1k22W(?+A<6K3#5UX=%O(sEw zM6-q!rE>#Y%Sq71(KKUFA(1xmDalvH7J~#`{^0Fw9 zT2^%VAE~L3X!mtF+5fpM1_`>Fw=XBF)7aJ^kL^4@R{gZBG+;YNayGB+a}*U4Y?GN4f9c6z&hnR`CP9S+f8pv+ z(DmG(rDWflcP-;Vg+#-FdE|PGo;_v^UIXA&3Vymb2`VJGqlZ61*UmhdB+ZGfmUd7X z9)3$*-L=JaF}8mU68v7opP6!vc6{H5g2L$uVj35cRp4?GWnm%s({yfc-P31y8eN8Xt z)+Um%mM-tf*Hi}I`p^=i@ADB-q?EoE_D=N($=yMhCw^T|Mp(Z;-#NUAG+Cst(2Y6O zRJuO5!L9db)+W+-p6$vV6%sXPHjt>xww9BitHJw?WynNZjCoTcteej^L5gP2_k&%F#4qaMVcbXxvoF%(9IK3A%c$ZYtyAYy_2+p^@@(j|a($#1HKw z<*wLbFe|!-EsT^Ld2B@MG|gmPgkBSuE=Ef2+`7!UVD=Ri5^ryfl>TRJ<3WNh&S^6S z*LJ$LO=L)IT`y;kNl+p2*pA;2+Iro>1prTes$mEiGoLQ593=;MKa@y3yHcMC+U4ISInteruM9lNUnNVq;m z?k=}|Z$N@B?&D|1Xwa;^WPHD++rms~x=E*k?cH+D9&P2&0oyN;sE{ars<&KfZu>cbR9XG6nlflqD+@t|#N{t*%D}6dHnUnWpq9MUF2b#=Nj)X`UaRYt5A3TY zW2fqWHwh{v{M$i-t`)^HcAlnC+lKV$`%+ z^6A>tdY7(k7i!76Q8r@2x3#4}K|QY;ovJMr);4il%UNk=757BA+_)Tn7&wH$N0`aSQ&n`a{`&dnwD{|I+SDs!WvvV3?Aw>)flURgG$fn@}# zka+DxIr%YntyBoQYFsEQ#U8WGD=H+|KC^d8(8XhnNl+o--&Z8);xXTh!QN%Rh5QmK zxn9*hZ4y*Sw0<#ze7)V)yCmqE)AC`NUfD)aA(8*aZ|aF_w)b-?BzkoHTOB%XJHH}9 zSDN3CsxF)LS*F=?DkQjXoIgPq_d+uXDkS{(pd&#S_og#raK|<7N5`5>f(i-lH0Mvy zHGkVWwWXD9MNuKa9p=p#Yc5Sv0~YJgWM8+KtQytV<*J=#sU3GmTGn~vw6CZFqCYPU z+xv>j*+Q2qt(mN9mKbj#A{)l5Z<=V=)a(;g=^CjKtcyg!uO_Neg*0upg9KfJdreXi zH*}j!g1NU?G(lZ|@jh2gz?@}QVR_+CLBF>f-3A*+?5vN|8WsC83)gCHK?xAkyGQz`mZP|B+9OztiBp->njp;^&A{r>eMM)R@*}2Rgqiz z7=HfgS5^Cqy3972Sy3VJb>|5x{Ic!cfCOFseZ_pQRG*~Q&(OKEeP&ivNYt1yQRRuW zwVVW9%+`!Sg~V@%;#F7yTMQC(vDeKQJZA7+l*bs8phAN0cK!riB|a1N*{`{24X+?Kdq1pQv-UL8R(eB*As@={jaR zsE{ahD@JwSH`@|}1YIvp@2}dONR5cyHcVZP*RBiuhO0E4Y{ZXIBUQPtX1URumy1`^ z_s($3yNZoe#qQ{TH`_slMBe!$)a44c7|geP^#Q8ZFWSZSnK7u4h(0q=?LBLYL4vN5 z69=h0$7}?Z#kq#40be~xRwTBJAF5(Mu*G0jba8CVmUBG1w;rjM&PX{nCc!Zvu`$g^ zRlcKb1WC{}w%Z8Rv7C)~BxH~}GD)uku9c{S!D`=Iw)H`U1Y?`+AVJry+(T8%k8LrS z@1XI+)u;bx7ilvF6%svr4O2@F+hUNQ%Rejj)eBJr)t_;?UiN~S6%`VB*Tt&t<84`y zpsPcU{wnV@8$spdxES^2q6f)}#HPplsx2FBF_;xyIS=<%^-tM|W&i7?GA`CLu3)`h zYT6N9<}ujpD=H+m&+Vl$gxS_03A)l%i&lqg+XyPza`jdt`f3+z^3RGy{>pvSw3)UT ztcxzbGng@`keCqHR~`S@7J~#`d@nI$aHQsb9jz*b>ha*nngkUR(RX{P`Za9F5)yQ= zN6Z*hNPIf9m&(@97J~#`oNs1~hJD7VJ8!LY-}^f3e?>K#@qt^O5&62RddhYm02LAm z16Qi*)_VuJw*YrV;64FnR#ZrodU=!T(`SR5p+7+vfAwz?R7jLfze=TVX}gny1YQ0u zr$VCJ*#&CLo^_UXkf4jbZnooSrirTc=lTu-KD{u_q-AP*=V(g|DkS(k4KoG_y0|Z| zNl+odJwg2my8QP;rb2?x2{dE0o$;0$_K2SCLwn6vnZtCMy>1e>*DqApit9D;XX%CN zr`yZj9&Outt!h7Og{60|j+v)geXL!Ne>_?BE3fa~*%$eiN_b!YyBUKDiAyEttBUX0 zh=ytAsI@b6^vG#*)UMBTnd{Mv!Q7vTTcD;LO|2blA&G0--d35vv}HwtF1E?ciVBIH zf6rGrSKDHcpv%9n*gqMn&2`R-Q|l}CB8ldI%vB4o+s2#(UHqXtPk2US(?s=kA*IbJd-%^cb+$%@|Zj6iqW%{c}3C5u|H( z=Q%2nNw2i~V&s^uWT#fX$u(Q;{70AB>n6dq-75TT)$-xg);W8Z#2aZAs1GjN`icZy z>}fNr^*=6DHDA$n?W>!hO244XTsI~`*SoJKsE)-_BUl%Sr`}0WJulmOmjqpd6BE?& zPizF0#32c)*Ldw>O=df&ka)OMf|}FZ7J~#`JRX}dIDe)dovmUj>3TUsO@a!Ep@V0u zKo?t9B$dggf*E26%zHP&sN#GYucZn zi|<4x!D~po0>$%Slb}L^*RuQxy7=kUB&d)W^uz-7dkNc~10?9meQ3FAxWaZ8PK8AH z{>|$BbhayZB54@n}#7s?vpo@Esn0>`>-1zMx`^_Y%klNUa@gA&EcNXO-Id zZ1<6opzE_8StWAyvzFd1kU6W=*<0ULNEeRGDt!vt?v0{CqF8)ZSu@;5F#3;Mvx;h< zGa+sEE)^03S7nvvKiXoDpvyn2EDvRo$G+8>40fJipRR`PQQnthX2rgej~|i5$tnBI zB$yS6{H-66H`{31pP-9(B$)&i60cqjllPvs#UMe~+*iZobV(aQWm5hy`LeWju_phl zNW8TsRLa${#b8}@-EJBxqk7l~Dr>G~k+BONBr6i}OR`AZ8CwiyMc4T*S)_e++f1bL z)00lUv$cyg`S%rxtD#vW_Z?dd)Tn%lzGj4oMekZf-b&G zm@%l3=zJhlR-ClOAVC-3QOy{*Ws)a$ zq>N|AV7(+lT4a_+2W>HUMwWL)dU>eht8SaVosnJ|tkY#P2J0G@K19xa^B`G~Xumc@ zvTm|v#dgr;-&Y)uC(nh-^xxuBjE&h2#vmaz!z6#Aru_-JxF4ZOP$98%noueiChCjYER^cou?O@7w2KS7uO zXB;Xdj_%DYWe(e7kf19je`c9_#70n=7?VkQT+lAoWVV9}iNKDGQYwqBcS+FIp+ZJE zT-`?SC^L6HYPpOd~>z?)}=;Dt5CP9S+_rUij=*o5UvifnQZFhVsB>eZ& z=T#?OFXLwhGb<`2c*Vk>plijTD>|v1OmUtr8T{3^Nl+od z-?8}GJlm#GpcgzXmm9kf5u7tw=fk>kvx} zDkS);Rx<|oYkU80Vd-3clUwip4n^c_16?+W7UhddQYWoM%_%C89d((zvY7;9uwH+H z3W@Gpipa6nwya3d#ca*2n0xay#pJCPskMVKNL=k!O#Y~oT2^#b-&9O~FJ>c#E-Wsq z4sCSDpwzJ9a(uBaa|b)K9aKn^c&5127@}!^g07-Bi%E$lHe$-jqVnRyTH#Y3iac9P zB6HdZDkPY#nH34To?Ti@4wtjVphDumwPV51qB87neb*c_G_#^YVp?cXId{u;&m9T6 z5*8Pc`5A2Oxb;qPSvn}m9rL91#bsq3U1poitf-JUwYIpF4AHbdK^NznN$f0FSX!^s zb?xp}SZ@EU%UsPSL50M=<%K1CsBN~Bpo>Q$GX_^qw`|2F_Mrz^wItHEC@$j;+xm*@ zoG$jdnH3chStmFdzGI6)f-cSlGY02RnrDhgy}T*cqe*ZklKA9wVX6PLZ6=bS>$RDM zWk*{ZQRz}4nV46%Fx!qC#Tc zl5;BU&|WU>Pte6{113R*ME_!$C{*DGHTsbL6wjG&W<`ZW%ZZoN^DAt7G?Ji;GvACsg~V>>9*q)XZJ*Cc(8ZZ= z#-KuCTFd;h=$37rlc0+;-;6moJA_j6rC61&JlGj-W)2bEVsqon9`?P5(P zL50Mi!BO(bNLvgNbmja$N}^lZh=#v*6_sCK*?QLLpPQTXO6C5kW>!>4)QjmVdtz>txw(@>2^NQK?%eSv*K9^M`km89(YWuNsCQ+A9gVIH%1Rn=W>dfjgt! zeqSBvB9Xgw+5bu^6%t?O>LQ<=)U+9c1YO0}c9xLLw)MeYyjrNUEd5pYD0|(EL50Nb zmpV(`3bxr!f-cT{GX@nBzkkzNnnu}Tkf4jlM>7VG8PR#VN`)sMk* z7~DODyPR-$50jumg1@2hC+On$swP2&1b;*0Pte8hRZW5l3I6KFpP-B1tC|EA61sdQj>&&+R~5^( zbz8Xa%63(Ba~roj^~6qf!>4a34^Af-ZjYHVG;ucn`EcK^H%Hn*@Pmqa`d4>g3r@1W00ULU4?;?RK^yA3W>!t z21@Q+HiA!B^e5=z5!EE9khoRvIVmtG!P2`V=;9I8j6sD&$2>2} z;pR&$F-XwGClQ%3sE`=jqN_}9VY|DH&n)FrO4$o$3@Rk}JWzjvF7|>+P$6;0*;jpA z6TQ!&KS39J!6c}V=-j`Pj4r>xG9D!8^6y?97ZQ5HF zT%PKdw>x*8-T6^JHP&ng6%td^#>k3^n)WB?I=3-aKKjY_t9U9TR@E9JT_@STX&^yY zy4S}_@AkHR)u@p0e^OJGf&HXPeZ6w{^r=#H`pL6{Y%7Wi2|iKF>?;y^~D1T#c59qPi~51kpKkylkf4j>Z?>EYiG1gy<%My!7$oTOUs3Fn`IGy}OE2kq z*@tFUR7f=L)=w5ITUI3KdcIsgxtr5Qe7L8t6im=ZoGo4ZO3gW`9evolB-Z}rtf;w~ zHrv7D)#cp1C4Wmj6WNC*L50NC$lkK)W!w57L6`sWiurDx)<-%od61TqC{eDDWctL` za`qKnJm#A%=SVd;6C)Qc>Uue{CP9Tn-{~!a=?hAi{E}mtY1QilI zfAlBlVy~M76%srf^e5=z>@f){Bz}5mwCsI#uI0Rh1YLY8su_a{37(_6L_l+aB=0v^ z{VLV-?!|J--rZtO*(AJQ(K(9u+cl@mnoPor?zp_HoU)g#Q#J|j+}TmQC!soJ@BBIi z;XS|9QM_lAIc4u#jueFVTti3ko{;F2y(bx_AiQVrIEr`W&MA9OB}yiA=ROoj@}8XI zDBg~wPT709PBIbDNFd4E8`V*~-IJWMx64rq!rOu0QM?_@oU*sGSqdWUQ-x(j9%mP0 zM~Tl@P>y_|%ibsC6hws)+f~MnQ7+-_bn3Xg9Z*vc11D#ZBEP-u61kl_kD7m=%ih)c z6a*C#8`g)2>a1yVmXM&U`j8Ok$K@b`Sit!&X>ySq^6hzNZ!;(QS7~xdvmtZba)uMx zW$!Hg?`{l_phDsUXTPN{8s0|)!zA4ddqifBa6X4SF}&{$oN~`ik4Tka`ro}6EV9RjTSFWPj~c9H)<-}$B#=act`sZEBeyTMTNxX#v$@X zdrkWjbY<=pB8}652x5WYc+5x$k!7oN3zuCFk*B)oGH0k6g9?e2-LgnzK3iXrpey1+ z7Abn-z7ce@qS8MuR0glsF4p9q6^UV`!eq_sh~d;9dU3A$1oMRih6489xGsGmdXDLu}dp=LX%ka)OZ z4jDBMvm~H{n6sU(&nx7RFMqcY6>nsh=x6o2SAj*@<)=4wnSE$xMTNv;m9tCIQM?a& zS&^WNJ*``i+>SKgZC8b6Ip3K&BUt*4?ds!Oy6k;p>ioNz6%`WM%Wqdl+rH@5{mST%8r%Fs5zw4T(8X-E*ZJ#Efh6YcJ#E$24#ypQIiJ<`f2DqV{W-VgBuXc2R*RRs@b3r) zT;M)}u4jjQskSHDh+EsXtIBP3zkBzWI9c&n>DKPWphCjCwlzRbQN;XUy-IV%m^N6^L3(YkVt1d^zb@Sd=n93x;O=xREA zn=0}==9LDVtf;(@al49`t6hxknyoQNv>&=%&Af&fR)Q|h1v7^CO{LSq-T4N{f$dY= z**E%HtfYHWmra67&f~E%rL%UiCX=8-qUy0&NnaK*f>TUtyHYS+WKeGl)kymuSIR+1wi|cinSB+e=(}v*7IWjyoTqcxw z&5ceXgAA5`&Z6Z37r2k0%l~Q=6%xJf4w7H9>DX@VUJMd+)m$}5Vyf5(D%V;JlKzp} z#hUzMkZ5(~CCSyz7K3%s)#KHdWOqLsL8W#6m!wAQgJeY_`lEr;rk5=Sv!aVL)NDBw z5(gs&N>poG3=(v$ygWdT)v^&(4$K=MujSV+*5scRiG3{w$k1!HnaH~6;!(nl5&RPf z&UUVx-=7&EPtDY;h-=d$f>06_60eVQ)?ja}L8t!U%OvRf{J;R&+yI1Y4-($}SI!Z@ zyXVR&d-r0cI5Lc!I#|k{)pea&JXjXxeUNodV#~6@QYO;YyF4<`#bb=yVtNhO{h zB)g00tQyT6B+YB-@|$T#ORZkcj)KYU@LJB+&bT#Dx`t}PzvWa&B=&eou7zmYO(>w# z3M7%BYuf&ot zvq+H%+g0{jUH|P}FNXJPS*PD0+jB(Kjp^>X0_(q1*Yi2QkWU^DkMMp8?YcLx z_aC4CuutWD&-vxO<9e~kUR6C_ms1cA=~p0$G3fHo>c!*R)yiDm+!$=F_Z))cb_7EN zf-8y&3HFL_}S2{J&+tD_lVtUs?t5W@9Hj9 z^*cRkY@bO`ArU=ur|KPH8*`3xrX~l}=pjBM=w-!GBe8eRH!AO9O`BPfpo_D|B$#h} z->+2nrF!nNeI`MLM9FbGRQNePd;AHyINx02-k(6yiEclrEqU}eKi|aup!WQw%idk= zDQ4otmv^bl%R0Jq_vD?gRjo?8%uh02j6iTE(sgtG9@Y9p2bWGkIPT!fITua7gWrix zqEhpH>a#VP)>ilLeFR+%vVEhzTwx>FTJN{|PCOoC%otQic>4q-_f;S{D-v|^*k#7x zw{O*--{D;4>g@Iv*P}^LA#t(5S8DqCPA;wUasCE^y-R{F_PQB^3W-4Fo$7cvVmS2& zU*-tX#o431L3@zkNG;p>t$J(kgUk{V=VK4529N1k>BeyC55CN-=(5gsm!PZC%|mM8 zSY2-lA`pxaj6sFO>=(XMy+dq$MS`y3V~(i)t3l`xP7EqXdw#Fx_1Ck6HR*ITVrE5R zS(YDE$vV!?6e;E|>!OQC3^T^ei+v>gqCP9G@p2!DXzbkO>(tA$T9cqcBKFVTvUG{2 zO~SjA*s0gMC)p``cXgy_hj&kjqjZ=QC2@;%hMPJ>N#&|I)7M?)^e$ttUjM9^$=c1m zEK^UZ(#J+n=}@+Z?0E4(vLf+C>+Uk3nk@#i zqKmz5wu1_Z*>7}{`VZS;kf7_#>8^6(3)?KAaxJo}bcoh2*5scRiMq$4!zsJOy+45@DkLJ3qGZA)+c`A}x|WviDlbh2;l(K2xUWoE ztUoX1adtk)o>Q+0eopkV3IvaE<<57P!xJXCGkoWk9ugm`%igbtlH1|9gRejm6%q#) z^_0mmn$}kLuR}08v*HoMB&d+6Q>m{+zl?PrNRB~*E*{6U*ZJ#E&fPo7JDWHy^!6-q z%50xYIPT!fY&nU9Jl$pIDqG807hUXiU3)MZ+}K|7*XRcs4-&;&L`##z)Uu+B z9T6 zVh-yyQS;<6wYc17H>(LH&Z?$A>3=t4P$7|G4SF$1(6!{&S#{zVVt51<5?u3UR&2-E z38&T2Z7JJyuX<;S1ZN3zCsBFV&+6)OWaYSnFO#6l|5!qW#F(N#t3{J+F-XwG!asegC9N+>2QfNRB~*uDVN4syuUT1doF}&hsc?W<`aB z|GNPRx^Dk`MhzQbTeVb36wGl(m45|N@LnUpqQr5UTsTq|Z)R7f;ybY8_Rvc(`l7vF>Lb<@2S zb@Pu?s`U}wi%n<#tPZc$W%jh06%`UE8lF}M=U_YnI+Ane*~Qc9ozwa}fvyxI=nF{qIEqTeZ1|6yAU5_GZG%^2-|zpnl$ zr{7c44Y{To_0;8+{jRI7t8DMJR7h}!nlVVw#o1#LR7m*Gb`o@P6}U0({Rt$o<;<}A zGdI-Vr}WvGnH3ch-fr5-=ZRhn5_J9D>MxZz*%rgwZQ7|T?I$LwYVh!;JZ*@Kb^Aol&BOj(q}!Z;$PD9CuiETDs4Jl_MTXpf}lcTd%d%2`J1-c z&a9Y8!Eev1AIgGoJ1p1^-f7Kyt9dWC*}GIo@UH25)oalBO#@xtt}!WEPKAWGYfLiX zwSxp*-rh1P2r4A_n=h{&fnZ;SeNoY1Oyggu2#2`TzfBB}PJ zibUGPrzBq)TUM-#F7Ma5Df)^EiDnHeO6LZ)7$oSbajv3Vh)s?7s6l0Ea__r>YVnn& z#U$G`efFsL+h<$v2HdW4`ilKdV)NWeQfHKHCX%45_@kAi?|K_SCC#XclJ~53u_iYk zYgQ!wI`otr%P_;TK3ErBk3R8~tj!G~7|4m^oWp%xPWFGU`~9!T^0FwP%bW{AbI=`p zne&Q7zVqefdNbPyvM#!~R&?$9Zy<@Y;m*KH((heeFK3VI4I~p(NVGX$NoroSWkrH6 z&M{qkatzM6bIU8swv&4Hu_o6WNG7O|SovXPxgD<8zdu12j~Kf4bb-t zXYQ>}%C#_zc_5jfLV~l$j6s5~rGqL+?tF-G4+|twA(3JxdReg@Cq|c-5<611$*tZa zm^+Drzn7E5X|^>;g08J2%gMJ9HiAlY!E&|R7k|EEh{8o&x#6(>UoRFw@qx{D3YLyedzX**H>&gkHKt{Nl+o-Jv}DH82|~o4$mkg zA1=bTWL{R@({7x)vKPoF$KKc9-H|r4qC#R(Oaa*wW{W|Bt`u3hfr2xUyHV6#9VUm~ z)#L0v|0hMusgO87KC7(%-j)>!y1LEHE^VI%5zHzO%!hV&m1!5?3GZQ2`r4SGtp#MTObk4XFH6GejC4(Z>(Qc5AoBAaVTR zERy!a`;LhY6-Z)Tba957F{qGOS}s(g-?kk~NYKT3Y{uYk+4<{r{#xE8f`0Cs!chpLtzqpv)I3W=zM!D`=IAOgwl@OI#L>W$qtOkIwj?Ploh zv!7xF(^ZRBhihxs_PM=OhA>_3`$7Zt+^_TgZMhENw1Y8NueX1HiWuH=)g6Vz-3F1W zUlC_V(i8+05-&~fuiBl^8M+C1EoVEJd$wG?)rh_zymoLr28|!CKK&=<*qAXm1|-II z8=*Run`LPS3A#3>8L7&5v=MA!p<6Mk`#zmJd*ogd?yV0hBqqf5RmVR@%e}rLK^ObY zY&jJY`78HP(`MRYkf1BYcz9WH_7$wxOHDhX`-e68XGLP!|9Yv6i*3Ejy6F0JXfKtm zpN+_QxVNf*O3w`L$~5=uXjLiHMo=LUeYcmYUjsz2F;43PNsO`S@xE%y#+32Qma|?G zC&$I8FBjR43?%64kfXoKI}L=F6_vc}VpaF?50Vv$7orBLKjRR?X|)?BiCNM0NXQ^{ zWD*DsIDN&H)4labwRDE=QLZ#yxkds>R7m_7HBy!P3gZ#55p?Y;Hc}P4Vk|R1QimTJ$me%zk%S2B0<-0pFg8UzkT1latSIVxGS3*!*K^+fuyRP zW~m)_N4iJ-JJlwuvb9IM<@pmPt6hn@tiAegAc;!<)sxkyA!A&EHM!nEGC_qz+4Ymv zSA#X}Ptdh^_GGp0xQ+O_#bni}{#ZAYHJ2u-0gH9H(wfPtW{L6cznd|rkQm%+l8U&Y zX@7#Qf?rKkr3wWsF{n(|>!+7;g6I%?{Mc05~uc`@cK?DN@f@9vV zaYMEB9sS$TXAC*nXj?%>P$#smt9#O85o)Lq+nP}%cDoO*4RcCjX1 zx%>CN7$mY6jZEPB)#k2L4`!?7cJYD>XyBHWgL*t@ngEYjF57kH|k#2>F`>8s0M)|7!)BVFZq>zWdI zO_!_xRZ|9yYGonlx_YUGOgWtz!MaGakFOyKUuxQILO?epkVJwmj;u*=k7({4?cZ`L zBo6GWC1a=RJ~U&Hpo_h363qSSGBsr8G~HVNc2FVF?r^wVkFfO>3A)-$3zuEDoBlh3 zx^tab!Wo{oT1`nTr(4TDG}}RiMCnB}WlL#WUy-1TdwkzZNQX+|d|kV!w#*on+T7)M zkVw0$wp2W!X|o+9=!!XBTM9pqBSS#v7D(E5p_Z&0rTcx?irG|om)nL4_*96707oNs1UR7hM2uPtk;rZ#u!;<_9NQ^CATmF9N1xr>W==$H$hO#(P@1?0LcmFyu_&f$ar-8IdP$BWzxfW6=1V@HI zatso5`DewaM=-}5rQt}7>FrGLd3OYc%4QS8cK*`GMX zLQo;$Jx4P|RwU@kaCf+b*SCEtqC$eZj+rA!f-deMW)f6Lq}ajC>s=CbafdcH#=Sqz z-U--ujJwORCjYERaNjt8g06(?W905~+g%n^Nbrd$W(+=2g-=@Xo-va==3dLa=gK%r z%=5$K#ow2>bLrh3BW25}h5yd0AQ1>28OEGyDqWx3;3{k8w2^UT^|#aBbLo;}IPTyp zkVJ)q_Z+-rLId{^ba_v;BM}J3*l@L}^yvSwn-$~DdZVeFXr=%CUiJ6dL4}0(#M0y# zPW{1GAc+KBX`XB<7wX*?!zGy2?D~=N@#`rw)Rnt`?`t`Uc~c_g>rW6PU?b>yduych zKWihH`;aM(JK9m2_qbzQm`DYbL2OVQJ=*_suJ)@ho_x(H4C6LeKg z*Gy`~*@z$7N6KAU?`EvfOv80@yg zX+!X3zJHJy|E;tB&tp6SE^r?~7uSvJ^$02?hAoVg9C>Urkpx{lDw#1jf8MDcA-Ox~ z+&SM&f(nVg&qqj+Qnr?ppsP)v2x)yCBj^SS_HJ~w@^W&%K4yg0FC!b%Y;lhtPwuEG zO&_=I4nu{+uWwe8=AUWWYzKc|`}B|kQoYAEHwI~wphBW>{!;Sip{@TO;k>y4WMG*CVKqcyx0P znH8=3&7Yu){igHLe*;P06IPw$mG?ASr_8fKGX@nB-qUZB-wo~s3M5hSp0N9$W03Hk z0h}BoklYStMHkOx&2~^B5x4Cn$-C#hf9I7K!+Rd26Wx2_tyA`%u={^z-269^Od_GTp>ae4DPa}59>=837DkQw8 zxF*MN>JPr0XHF(RMcz^9@}2>kOlZI%*o)qidmR_&g05U6&i5Y|2T9ZK7P(_f!h2G1 za*TkDpo{B9d!4@y6-e@)@9Wg%J-O8>vwbe%xPvdVB`-|P7Ep} zyeHG9h(Urb&SNu%_r!FkF7KJnPT70TaEcgINO(_&P9}nZ0>QrGZ1A2Z?6}w?W>!>4 zc+WCUj^WfFe3|1x7e`iG-M~(JdJ4jO z9=)S@&vbUm>~%9MDkQw8L#K$r=)>~#m2r3URRd;g#-KvNdscjk7$oRowq^_}B)n(S zr-(s5~N>@|r!aJkDWcdazrL4`z$D@6ev z#C+xpU3>zE8G{N5UYXLhC&wT`SBfiMK_C!Zwa+dsCWp&ybdT*klP&UWF^SBn|6SLf zOi&@golsoDsXzD%B$1$N%E_Yg;=_m$Z~=$lIo!VGg(Z9FCO5;~-3rU?pKYJdS#O$W zib%b@y55AvMPz;k#Lyw`YkAR|#iT?N?P8l;vzHYW5+$A~E;WWAhLxbJ)Ue`me6fvS z3wM?)EUnk+*0M*;tf-I}k-o6RkGJ&|3A(afDJ0nC-gt8k z5jCf%M0T{rU{-XsC|^{PI@t&+-M18xW33+~D-!!V6p^zHY%!P>U7XWqUr{0P{@udT zxx6g~3A%VBGGlP%RJv41Cg#;MgEg516%v2mE+jL~;K&ff0>PO`f-bH!GX@nBrwSI9 z9UmcvQ-AQ~yc?X&E!Qf4?jCFDy4 z`cET9z(&x;fR7muGww7$jzrvjh{sdjO>OCg~1|?VsDkOMK z){H@du8z)ANe?&IXUir*g@pfgQ4)0Vtk#S{g+z+))dDW(%ytrV@$B4;L50K<&-IhT z-BoSpzz)KoS)a949jd z3A#G>?bzDLV|av zm;_^7E!0_-{;Kc4A#D;=NL)VBNk+`K-MvGCu8Rqsq@uDBROS!wBr|^Oo1z!|vm#Nc zTPImONYnlVT`jwGl9`!71hGKyY^m7V&JvQjx0}hAxw^<_C!^gm?|L$0P$988&_yD5 zYucZv`+1ZUyQN*chsh+UkciIHRVqBGv-KzFsu$B$_QZm4v0%%oJnKB!5y zBpUwORaE{yZol~xbj{1zO-_sj;blc7UFmMJ?-%X*Z&{HzS+<+}?Cs zyUFeiHlkgXuF@mFUY$9=kCNz?y6nFOsgM{nI7&VlX zK1fz1;;VI$8slv-m=#?-Dw$)>wU&E8Ct0>ok095LNl+n?{*6wOJsh(npr?s>pCw({ zw|9~YNAH{M4i!k^>fCg(iwxZPAnTmO%2rWQ?fcZ$IbB@Ax&_W(H!J45DpP047O!(> zkGO>64!+EmllY-cX9-hidB6qkBk1ChPkWOIu7iqyca<*1^zoeQ#`Ol02`VH??C2`- zFWcS?NYKUkX2zgGV#4^Y5_QNHg9Ke%&1MYVJH)$%c(0L3P$9v)7W@gicn^Y01pfqr zV@`!c$s3jA%R9FH+ey&HPsnZzr~cr}ysAbb-LismaHegSX4Xa5f4j~=A~rg$^jN;q za-?Qmba5YX-2nHm(+(;m{P(9OK^ONxH)BvC;lDpM3A(t0x*3D}MsX)_?pb9LR7fyG ze}b-l@u5;MUVpo65>!aAr~L`KxGS_tP$9t?<4@4VYbPc_g#>55KS39-otOj_5?sOl z1YNv#ViHtHq_{UK;BwCTAVC-J_cLQ~_q}zcvd9~E_3jP{+p*Kyu4T(Dm(%^wMD6tN-?H5OAnKQqp@F zB<*0GZ-)vQ<#2UfUbf_68FO{?zl7rsz5+>9NCb9dlu}u2Ehj_Xv{-b@iyRCjYERL`({kzvf}gt?i&I=d>`XaLq=P92P1AtLk+(@%Jo} z5Ub1FSJBLh3W**sW|77VHSJH()qZV=WZh&VIIHunNG}g{)VXsNm@%l3SbQeEw9Sl` z2eCkKUXh^dzs*Dv>%%k1>CaMIA9QhTy6w34$2o7uNbMdJCW9mN(cr($5)x7~O!6n% zjwP&%E{?35kke1Wm$|1bi6_s6%JkoCF<2K}oNu~v_pcL!vtd~J5IOhFgUmz{AuTdX zql312#jNNWy(p7BvBO4Csc@$YQ`WzS9DT2nKHho<-L{)3GQ)W#vno0oXth0{F7ZRF{qH>t{7$v5_BDk%Pt?T zZuf5t7YiO4o{3warX5}GDu0$9~Y{cujn%On$_N*-6bO5 zQVH+t=$A^)R~6sW<;OpstooII@85Pf?%*qsM1{o8zvru*tI-Y(I0XCW_WFhDT5;Vb z_JXclBY`9;Bpxo6pyo8!v_C;t;*bQ@Ydi=qD=LE%6V&lf9waLgPrZ|%dR|71fUO;L zz58l{>R8M+f^BEKrG`DCKkJX)I8VKqL6=jEpcjJ*iRORIRSU1%VvwMV^UZC67lR6k z4Atg3J4f1Lkf4k6*o?thU2pnqm94w3mo=FL6%tEjwo;W-%ZjdVa?Msd|G@~lfr7K0 zBgNIl8ER%lg#>%upP-BTNSg!|5-IkM4!E4t4ia?v?@!I+$A~ryRq0i_M;Xt|iVBJ1 zpDa+zzqO4A3A)}$vp{`t*+y`r9?vmb$xc0LoC{`FR7fnSI9oNEdEb~j{pH-{jpHs| zJo1?_sE`;sc(w|3vBjV=_2_IBQ%Sp6lYa~nyF1TOflU98vh$9Ys=D6y*p(udD2R<} zR8S(epMYHVRr4O3(SXE?^CyR+A4P{ezW%TBSur&SN1{^H{woCk8jkMpmvGdY|I240iP8OT2^%!b zeUr++M5g$8TzWpb5xN~b-tidz-@St*_=({iT2pbXWop81H-^Km%6$XL>*n(g4E(;- zJ8V1XklR;y!B|r!|BzSgSdhilbNify<+}FYp^DoMD z&>>Opu8+dBZAbl!s7@UunA-QZ$3y#Gga1X80ND;YB#v)BJM1++cfL!4sU~N?7On~) zyrX)?yWzVn`&c_WCf~j!tTnpdzn+zE2OSc1kLXD-HMHgWasGkBGaYnDa7=BR;LnN# zQ|)_g5l?twOs0bl3Eq38vV#OuYxQgypV%_@T^}71yx&Y^2MMOy4cjpuvw3x9JLr($ z{dg)nNHBHg)HZR_vAGU9B)Dd(vV#Ou^*-qm*NeGtap;iXnyJbT5=^yecS2lQzDrOg zL5IZCC-sWE?*8Y@t4o5Z7kl)I_rGxEzX&VR&#O0weGp#%v6ngg%RlO}ufjq1o%%1L zx`b30>5$;xbmexCVCuEa>c`d>j5=@

j z5=`}ZkS&ks@eNns#*6&ao{$k6u)h; zY;_{&kZ3u+QGEC;bYuypMm*3c9`SLGxT8^n_~?}f*|U1($@;PJ!6nTr(w3f2dRBa_ zkDqT8Lze@L=CieI_F0j5;>AX>`-3IAZi1=rXEchPw>;4LO3$bCU-^awPQ4o%#ktj` z)PMJ^Nc`5TQT*u>bY!=KsnxzCbAk?uQ<^o3Z?`YK(zXRzf~no!*f73#R*s)>NCb@E>u#)-8#f`3adj;tTQTvd8SSNps2EvG}``A+rY z^jmZ92MMM|$q{GmjyZx({X+e?*;}Q*K0Z?AYek2|PQTWR>-NRpu41w+)kP9a@e`x6 zgAR!m4eG}xzvlK@5=`-v$U5{t)%vXXxitQE`Mg?G`Xu5b86j!?Uv-fViHBF#j~Cop zqDxWx@4pdD{c>1?cy1pMR-hepZhp8yY+LoeJS!5HZ`Ck9y8}9^bI*#YNtZT^pKk}k zpB0@;S2T=w@A1DpD-v7v*f3syEIP8!imCtZ^NK`#bi+9Hid+XDizyz7>{aq-#r^rv zy&KB4s{fbI5)wVH;B&^a~&j@;?d4J%Kxb@^1ej8 z3mflzRQasvkl@{X>L!?~`@0M}BzQNt$_^4t{deEVkl6U)VPVF)_x$TvTWw9U*YdHL z;)R?I6Jv??qVJ=CtKMzc4H8 zdhD_GSXV80IlTAJ<4p4&0sr=_o|qSUw>V@qf}^Fn38wfrT}jX(!O>FP1XJ8MD+xLz zI9jTkV2U%1l>{9U9ADKtBsTGAi-4K z_e-6%-{NrZ^`)!qZS&UR@IjlB=6qY}(dEC=Q#lhyV*cCn!p%oLXs??QlGguK5=?PM zpp-5Bw{rfR#N2ts(CLReGaY;^rg%iH?4U!U$vgLkgYUZ`(?NnMzUq}7bV!W+_M1zixu56Gp!s_T2pD%xgu51pkgJJ4i5f+)yEUUw3lo3w0oj$n%KY$=-v zIwUxoY1!%=!4&_dOW8!wA;Gyx%U0(Irnsk-vWcKWf^(CWtTxj4WaG%If4#}%6p%k_x7^RN1l6HQJcbX-dZ@1apBfGBuM9*Zg0)^WgI?W>-8VNdIz<61g+KaD~GM8Q+?SWLOL zjwjmgSGChwt*nENYw6(qGztX}1y9LiG3DAi7Sungs^gGG)!9OWI(P?;LIFg< zQ}S3$xwejjZyQy$L$|A~gN|$IsJw3mh=Ql&v6ymg9e;Z2oT@<$J6H!D*V4heV-yM? z3Z9b3V#>93eADiNsv893>{)w3)qC&NbkYtwuBC(5 zIV==F6g(x5#guF7SoPg`RRe!5bk+_!uBD^$3L78_o|4C6%C&V&=z3Pw)6ev?4mz%- zgIDw@6hIU_C6C3FYwNh{x8YUw*SpI)=(v^+UcI?c08#LiJQh=~tz+G0{i?S6;$7`1 z&~Ystl~*0Ai(tyNbzJi52~{^&tyQHRbX-dZuX0o<)I~7m+B&Xi(XDFjKW?Ns&Fke#f9j%(@Qy;%x{x(KFRTgM?|cBuM(ewB65aV;IZV@#n? z7r~Tk>v-YaKUAG@V0Y`F<61g+E&oEHE`ll7)=}*8Yv+g0IoUesxRwt7_PtQ3i(tyN zbzHgg?9LsJ9AF)ETuTRk$zCYbMKI;sI#w>erSnJkpJ5$zTuVpg_4Ml^m~w3$%aEQMI3x&D}rd(S`%WL1=`|In@w+=e4rK9rd_;nFXxwekG9&FZe_U{*1 z2OZba!K?Ah=T#j9Q?9L}*Y&SIwd#@5cF=Jx9lS?Cp->mWlxypFzHnI0_m7p{4?3=; zgZDZp6zU?Fa%~+CkDXj|!$u?RwW8x%w`0!YaP&^kmd6Hl5lp$Zj=LW()+{?^uyxRJ zEghW}eiWv+eJ0ja5HssN)rwA*5V}xk_Qkt3>&r1jh}%iHmekT6=Z356KV9y~jwYnt zM-bH3vB}VfJ5PUZXi<+Jo)X8k5Pkc`Hn$`6C;9T1dILYvCF+Ztb>kgd0fBWx^>h=Fy-1hwmEs*;-1GI zXdQH1%j5cY8P-u3!IW$3=(+8##q$>JQQD5R?hLyXj<(NNPs!u@_bAp;7r~Tk>$v`> z{fYy}wzLj9uH|w4`)li{i(tyNb?jR_s(9OJ8(Ie)*YddjEw^>lMKI;sI&QrQ=#2_to9|g!)ZJmp|LtU>v-$NzQyf! z{=houxR%HDH8a*x7r~Tk>)33&6N=j&xptMlA9P&H!^!h%C&X;?bNQt4YqG; z9dumF!^!h%C&XeHKJqjFURj}9dumF!^!h%C&VY8n=CMn@9Gs4mz&o zasBtB)=?M1lxyo)^5&++zpQz)2Hp(XEkl`*75a*vYJ9tuH|tz-g?XUk^WXj z{=Jf*lO=?f)5^a$L5WUOIXL)njNY>m|FT) zjf87S?fYQE_|9MD_ffU_S3-hLmavZ2!w;-_w)3{O9VA>!>W;PzV*kI$uePj%1f48l z9d|Z3wd&UmR@%{kglkF7U$cH(>+kX_Q|ll>Crem|?tii$YDYB**OL0JQ@wb|dlSkX zB(KpA_A2Wj;aXB_FWex8hS!ukNYKd=)}i~K>{T;$J4m>eRLzPF;@JJKEq9Qh zlO?P}_dnUIYP5rdYf1feNWFN?=(KpA_A2Wj;aXDuyX0E^+a*CKOIU~Q zf3jB(U#nL0?&$r9F~`=9Jp)L5WUOIU~Qf3jDVUMoD7(~{~pZ_8NSE_INglO?P}_dnUItb>GWN%?(RYIPqZ zK_^RChwgu}S6K%M*OFT6PtD@lTcp1$5_GbJb?E*ldzE#Na4o5O)@l(?JUH!xB(KpA_A2Wj;aXA$jBgoVIy#LYNzlm>)}i~K>{a@iSRmnAQhrC2T75rA(8&_kq5Gen zk7@@A*OICo-8wFAnm*e}(8&_kq5GenU1|pj*OK~TZtM8(KpA&n~rtglkFd-=%e&a!xvDAVDWfScmR^dUmNDBwS1C z`<|_0qvO)K4+%P1!a8*S)3ZzMAmLh4do^tt-#Rp%!;zqqC9FgDKRvtD4ic^<^~*WU zlv)RRwP_Y%13&&x}TGvlO?RT;IBalM>L5WUOIXK8-9GGe zQF+Ws!nLG+`D{@bb9U+=K_^RC$HO&UJ5MQ(IZ3#d)Ha(e3OikrI!MsT64r5n?BiFL z$DAZwOKQQvpNF?^N*yHVWC`mSE&F)y@|cr^Ye^k8@v|`Rk<>wgPL{BaKg&M;W_ip> z!nLGUefw$X@m}g6K_^RC$0jo7{GdGMB;i_8GlzT{_Fq%(09dR02MIb^!aDAd{cp{B zr7f=-sOj!$L(8(kiA zl5j1leeYNpwwRPUNYKd=)}bTFmkub6IZ3#d)bIB!3{z*P4ia>-gmv5?``>`_n3IHS zNzHv{VQ8|}%<_9qf=-sOj{9Z*`|_*On3IHSNeyrHY4~Ed)IowymavYlvj5#$9&?g# zEvYdRKMhy*N*yHVWC`n7A^Tsy@|cr^Ye}8o;7(6d^kf4(#tV51!o#i-a9VA>!YFz8Z;jm9q2MIb^!aC%rHdBs+)L5WUOIU{-)oSE8XdNV6OKR-vOG2BsQU?h-S;9Kxs8%D#LF*vlT2jwU{32Xj zlR8My$r9EfN426H2d#sIYe^k`$kH%&TIwJ{Crem|9My_)9JCG+t|fKX@}*&o3sMIO zI$6RxCrem|9My_) z9JCG+t|is($z@?!i_}4aPL{9^IjR-qI9R2hyChsoYKKFXh1XW5^F$JKvV?WWQLQM) zLF*vlT2d{aS{fdEEp?EflO?P}j%r0Y4q68Z*OD5%+0xMW-qb;YPL{9^IjYsjanL$Q zxR#WU!fN$=mjs#sU0VM9Twc1I!MsT64tR~{|`G|QXUVIa4o6EAJ&GC?@t{h=wu1& zsCl|;=S#}tK@zSd<-c&O)%Sx0oh)G;>&kfWujTO|3D=VH-(Xq?2|8KAI?k2-@6_^m zkc4YV`7c1Ng9M!{VI2cx|NFW;9wgyfQvQom>mWfVOIXLBWIXstc|1tMwWQ|Uxg@;w zviy?OI!MsT64voo+5c9R=O9VAmX!Z)-#SRp$r9FatL%RVm&b!7TuaKYEMOfZ=wu1& zSRnh~)beb*4mGiUn>%HvV?W${SM(Q9zCrenz zO|t(TRvr(Ma4o5-ev8Aq3sMIOI$6RxZjk-&^zs}e3D=U^puv)G%Yie}m=gq@EMXl- z$^Lguc|1tMwWJ1pw9YS7%i}>3t|j%$nqP)lqf!S6I$6Rxppzx6V}*yV>bjT{GU zJ4m>e)Y@mR42Seh9VF;v3G0xfT2YRJ))IowymavW+W&eArJRT(B zT2iO)^F#RQ)3gtgppzx6V+$D%zF8g*l5j1lpN{@9OuZs?kf4(#tmA&!|2`|vL6UGS zslV;GDoofRb&#NwC9Gqb?0@ac<3SRxCAHS$t3pjNeYTUJlO?RE&q=tJ z)MKkwg+7O;4ia>-gmvimF;iuJLOV#fmeliKtqKbl%GH5t^*oUToh)G;a#SnIanQzU zBwS1C@`(2zb9+0ZU+fES;9K5mHlt0@_3MhYf1S% zV6B4$oh)G;a#SnIaj;6?4-&2=bj z{FY8y6LqdK_^RC$4|2VjVX@@Nw}8O8v8Vl z`!!7+B)2lQzlr7XAPLu!di?WdasNG12MIb^!aClU{qL&sc#wo^N&R_Zv-sk1 zse=TaEMXn1^wgsrFxO8!u~GEboIP z=wu1&xKzf2jXRdcgCtx_YNM~WjT?1O9VF;v3G296_P;luF0Dx=;aXB>uhT4!zc_V} zppzx6W0vfH!^`u7BwS1C<+jaYkH=C62|8KAIykx`;aXC!^==k_`7Cvippzx6V~Om4 zBg^AK60RjR=iX*<;|A&1%OvPz3G3Kh_P^`PYf?$Lmef7JH;X-YN*yHVWC`mSiTObi zt|j%xNzLQpE~$eAoh)G;a#ZvAK@zSdb^3G7<3~MG2MIb^!aC%r)>)2&MLlOA;aXBh z?$ja{Pe~ml=wu1&kfWNfNhRT0QoU|!5xbw9I!MsT64oI{H6IU>a4o4L)@T`TJ~DNX zppzx6Lyl@SavZeRiiB%Pt?1n{ep{6~NYKd=)*(l=q8taUgM@2I?e%oa_)W{yL4r<} zunsw@73DZ+9VA>!s`o~%;;=&MAVDWfSjWrqea!AMKcRnDBwR~sts`5-i{_=z5)yQ> zgmuVKttiLA(l`o_<+P+4jg#%TD|L{dlO?P}j%r0Y4q68Z*OL1Au2%7mk*R|Ooh)G; zU&#LVzN}Z%*NTK|Nfl?biuYHg4ia>-gmuVKttiJq8xN9jEvZi*X%)AtmpVw$$r9Ef zN426H2W_lI!nLGE-_|NV@J>2sAVDWfSce?digFyZ4ic^60RjRcUs?g#o*LIf=-sOj%)E7 zMG~$h_40Fl;`m{yg9M!{VI8gH`L5WUOIXLdvj06)9uJam zEvYG6oE~3(Aa#(SlO?QUoa}!ml*fZ4TuW-y3B6=nm-bwzm` zMS@P2u#RVB{~IIcqq2KclW;AmsbhM@V|t|Z?Ih@A3G2}L`7@p^jR#4%mXzO9uU6j= z5_GbJbzGwBMP+_Mw}XUhN%=ketb+udEMXnfWd9p0=cC#|!nLGMy1Z8$J1zaDfdri_ zVI617{`XCJevpJ~N$vYluXtd+^xF&)bh3nX=>8{rRZ+KtglkEy?0#B2sekGqK_^RC z$GX$1s*Wg+2T8b=)S}N%iwkC^4ia>-gmp}k{cr#Bc#wo^N!@r|@3{Y({#zLkbh3nX zY%lxY&E@$)60RjRv&ZRi_@1eQ1f48l9dcCbEXP58KMEvVOX{RHed3G9rw$TyvV?Wa zl>KjBc|1tMwWJ!Z-#6|yFm;filO?RL5WUOIXKQ@_o$nyV>bQI3Q5T9I%qsbSv_hp0b&#NwC9LBt+5he=uNNiZT2d324~!j_r_Wsybh3nX6lMRrSk6av zA0**gQdR8-#r_wj4ia>-gmuVKttiJq>mcD;Qd=B3C~mxI>L5WUOIU{-)rxW)wDBMb z*OF@1ZBV>&dODtyppzx6L-#*DyVTc;glkD%)ND}fyhrLFK_^RC$Ca}GO)Sq3l5j1l zzsw#O$IMRWJ|yU53G0xfT2ap~bvsD7meiNW4UD~prVbKxvV?W;7l$NVOX}wr2E+wh zrVbKxvV?Wak^Qe}c|1tMwWJPeJRqJuFP&49ppzx6Lyl@SavZeRiiB%P`6#Sb&*4bW z$r9F~-^b`|gT5a(Tz6PpaCB*Y*|ntB*!i%yY`-+`OoC39unzq`M!sdS4ic^dFXa@<`lG^O+Zn4cl zse=TaEMXn`eT>dFXa@<`k~;IsZgK93se=TaEMXn`eT>dFXa@<`lGdFXa@<`l3H_N*Lch=se=TaEMXn`eT>dFXa@<`lIneH*SO!T)Iowymaq<8 zudTBU+Cjp#q>dffHTL)}b&#NwC9Fe#zpJwiQc+F9wWJ0e)HOEWKCNLPK_^RChtALI zY=d@?a4o63_Uam&oRm69(8&_kp}z*y*#_+(;aXCcbm|(XT$?&b(8&_kq4V=P+n^mJ zTubVohj)#QUrZe&=wu1&(D`|tZO{%9t|is^tgdm%kEw$Moh)G;GA~i3vklro!nLHr zgI(hl+oknaB(Kf6_sio!60Rk+|Bv#19GW^v(8&_kq4V=H>u%dY!nLHf?b-2|8KAI&^+sXB(uWK*F`8K5TSo95gv~ zkf4(#tV8GLW!Bv~NVt~N%V!-L51p1eNYKd=)}izBI@_SzLBh49-uwK}IDbm&AVDWf zSclHf>uiH|kZ>)j7rPx6cf28Wkf4(#tV8GLb+$n}NVt|%p9c?%7mZCFB(KSu zI@_QfBwS1C{s!ISg?&;72|8KAI&^+sXB)JGglkECaANoPdrTc9=wu1&(D`|tZO{%9 zt|c|*w(fD0Em8*wI$6Rx^!K|u+n^mJTubWWw`4n(rq4tYbh3nX=zX=9(8&_kq3gAE^_g~%a4o5?mUoYxo1_jBbh3nX=={8{KGO~ot|j%C=ex(Di_^Ie z2|8KAI^?KU)YWI&LBh49CSTb-zWR9TAVDWfSclHf%W=>;NVt~Njr(_xk6xWRNYKd= z)}izBGV5*~BwS1CsTGICK0{Ln2|8KAI&^+sSD)!?MZ&eDd=yrz<3SR1vV?VTwr}aM zw?miBPPTat*OI#P<+sAkvrj6|e~_S)C9H$9eI#5?=ihG*|f9VF;v3G3i&9|_lz zYJbF>@WjKZg9M!{VI7?9BjH+7t8RHc^jMHONYKd=*1_3660Rk+@Yh$v-t9~8Q=veD zPL{9^&i0XTEvd^cd?nQ0nL0?&$r9Ef-*Wo=APLu!s^0bGFu%ho<-aQubh3nXaJG+x zYe_BN`lWEq($qnMPL{9^&i0XTEvdZ@dNDk9U(d|^Ae}5>9h~hW;aXCkJ~=D&xbW0+ z2MIb^!a6wHN5ZwF+MPWstaoy+at8@IS;9KxTTY)JB;i_8&Bx6O8}EHuxq}3qEMXm- z?IYn@QpeAq74B~=ciXMi&qNY*vV?VTwvU8sNo{x0i=o4k)Iowymaq=a_K|Qcsquqe z3a8(3dU-oY(8&_k!P!0%t|irf;>%$`*FNPA5_GbJb#Q)=glkF7S@BBP{oT|-f=-sO z4$k(Ga4o4OXTKJ%3VqAlL4r<}unx}lk#H@k)>o33D=T(@`E{H z)4Nj#2|8KAIyl=$!nLGk-}Gi^Iz4reppzx6gR^}kTuW;GL+6I`&P*L7=wu1&;A|fW z*OF@X)!X5wR;hyooh)G;ob4mwT2iC?&kKtmNPoK|=wu1&kfWN<50Y>#sp=W;hVQma z9VF;v3G3i&9|_lz+U)iB!oGvkX9)>9S;9Iv+egB+q+Xi(e%R*j^qEM4PL{9^&i0XT zEvaqWeGtxjCmlaX(8&_k!P!0%t|j&6un)rPKjJv(Gm3PwgmuVK&F2S6xR%s{-XDbL zwn!Z$=wu1&;A|fW*OI!k{s&>Zs&vjkf=-sO4$k(Ga4o41`@SD04^8JjB)>o3 z3D=T3>-_h^&(J{t>D3CggM@2IJ$Krm*y*O!L4r<}unxVRlg>712MO1bdgRA}@!m

L5WU zOIU|q&q=RVs2wC+OX}k{2E+~CP8}rZWC`og>pAJw3bliTYe_v+Js@83L+T(wCrem| zUe8IdR;V2$TuW-x&I96@=F`jPi6rP`3G2|=KD}C@c93u_srBm1c63i2B(JRg zy;`AERFiNmsV$fGkH=h;I!MsT64s&D_tmQvY6l6|lIrn(|Jd#E)Iowymaq=JzOP=b zP&-JtmelSa^^b3Vl{!e!$r9F~*Z0+{6>0|w*OIz*MgQ2f#qH(yoCKXLVI6vXU%gtP zc93u_soEw3;#Nnc4ia>-gmvikef4UE+Cjp#q*inv5TCv(8&_kq1X4-s})K|frM*GUH-tpIQ6^KL4r<}unxVxuU@TCJ4m>e)R-*> z#fyGT9VF;v3G2}7`|50ic93u_sY@>&6#wu`>L5WUOIU|q-&e0zs2wC+OX|$82E|iW zqz)2vvV?W$^?mhfh1x;FwWKyXd~lrcaq1vJCrem|Uf)-*R;V2$TubVtzYUI$J(D^} z(8&_kq1X4-s}*Vo3D=Uk?3clDw_8&O2|8KAI`sO!dbL9BAmLh4+gA;V2aHS|B(JRgy;`AmkZ>)j-9`+FyX~JkNYKd=)}ga~di8qkAmLh4%_a_s{WnP+B(J}_ z>ecJDgM@2IeLj6i9Px2FMv^grEvZ|s7!uDoBXy9VlO?P}ukWi@uh$L|t|is2_mDU}qz)2vvV?W$^?l_ySfw2# zTubVpwnO6Yo2CvDbh3nX$Wg7RSFhI&60RlHWzpccY! zYS1-< z#u;(mCZ&Iu)f+M%Oe;+3WC`ow>Q54`B{j9r8F6L3)Iowymaq=4{v_dAQrG@GBA(VD zb&#NwC9H$1KS{Wj)bwjd#3qeX2MIb^!aBJ6lZ0zYt=(=!Ebf>(NYKd=*1^@EBwS1C z$+^ShGhI>#2|8KAI=K3iglkD%ebMl^?|{@nf=-sO4zB(r;aXDP>@z(6X=3UiK_^RC zhmP*jdQlRtCAGMrY{zq{g9M!{VI4ZUOY22RxR%sU%ZJ4czfT<`=wu1&;Ob8jt|hhm zN5kSeZPM=zNYKd=)}i0Wr1hdCTuW-x`NQIsJyQn>I$6RxxcZZXYe}8Aa#&pZ`qV*! zPL{9^uKpz9T2ilVIXuptl{!e!$r9GV)t@9>OKQ%M!{g|cse=TaEMXm7{Yk>Lq~=Z@ z9{;>m`mGEJI$6RxxcZZXYf0T-J3M~0cj_QPCreldSAUXlEvdJ=j)=W_qz)2vvV?VT z^(P6}lIs7^h-gmrNBCkfY*I{ND~V&mSag9M!{VI5rkNy4?HRvtMr4(*;gNYKd=*1^@EBwS0X z(*q;p;N4OO2|8KAI=K3iglkFl`+a2ma--Bif=-sO4zB(r;aXDb#!>ON#p$zz1f48l z9Xh&8>qSYpmeeMrM#bebQU?h-S;9JWbeGnPl5j1l-)#*GwgPL{9^uKpz9T2kA$8x?1aOC2QWWC`ow>Q54`CDrLqz;)lG9Iya>L5WUOIQb2f0A&m+kr7$<$6&%S;9JW|I@Qe z9dqvcWUtur=l=G+x@$?@e{`?7r_3Fc)?bmJlO?P}*K6z9rFM{TEvcuMpBhKJoH|I* z$r9F~`=6d&Y6l6|l6tWE)Y$#C)Iowymaq<8udQd7+Cjp#q@HbjYJ6g0>L5WUOIU}l z*VeO3?I7V=QY|0p8S8B@p!|N2ppzx6L)UBT*`;=na4o41j_ny6hSWiVPL{Ba_vQN- zJ-gHn60Rln!1_JoM&nZl2|8KAI&{6Z>{Zr5!nLF}o^?uG_F?KEK_^RChpyMwvrF9$ z60Rk+&UL56jXMl1zaJ#%WC`ogZ&&o}QYxxRxRz9t;itqqZ%Z8{=wu1&(BJRMw=C8{ z!nLH1I`xz|af3nS?I1xXOIU~gepk;fbvsD7mQ?%Rr^M+aQwIq;S;9K>_q%#_sU0L- zOX`-hPKnokoH|I*$r9F~zu(ofOYI=xT2jlWoDz2lgUhcK2|8KAI*yY4PtPv3gM@2I z)xLL1Jo}c^L4r<}unztGuAW_L2MO1bTCr`1rQaebvmeeH;dc_vk zqz)2vvV?W$?|1d=Qaebvmej~mz2f8Nqz)2vvV?W$?|1d=Qaebvmei*2_lo_GN*yHV zWC`og-|y<#rFM{TEvXZBJ1zFvDs_;clO?P}j%t2=Q4+2tHSXfmVy}17K1hO2maq=} z{jPk=V%tH&wWM0Vcv>8PVd@}3Crem|{(e`_NA)jwRh+p=X{Zl=OpN43G2|`@9J!Wc93u_smYu6jteeG9VF;v3G2|`@9J!W zc93u_se`{fErzX92MIb^!aC%r=GPY`;aXA$JaSrG^>jLiBS9xiScm?8S7#e^J4m>e z)P93ci?0t$9VF;v3G2|`@9J!Wc93u_ss3A>7TfKdI!MsT64s&L$LMT>c93u_DIbN^ z>UvQUbh3nX==^*d58gL??|8-uU2Q*bEvd#0_KugzwI)jY2MIb^!a8(*URR&#c93u_ zsU4J4m>eRMR~>#i?ym2MIb^!a8(*URR%K2MO1bYBRfI ztRGVc2|8KAI&^+sSD$GI3D=UkazMv;LjTl3f=-sO4xOLZ)o0p4!nLIKYt%8GJT-NY zppzx6L+9sp^_g~%a4o4ViXGyqU!)Eabh3nX=={8{KGO~ot|fK$xgBE1PTk6XyCmpj z3G2}Ld0l;`9VA>!YREyd9g|ZB2|8KAI&{6Zu0E5BY7(v`HTI7k;t#*44ia>-gmvh8 zZC!n)9VA>!s-|&=_<8?B%dZs)I$6Rx^!pfHeWo2GTubWarXAw9Z>J6tbh3nX=z48k zeWo2GTuW-5KXr(o?R{8zJ4n#U64s&XwRQEGc93u_siS*zh-0Uw4ia>-gmvh8ZC!n) z9VA>!>evY#;w!(T4ia>-gmuU|wJKeGrX3_)OX`Gq9pZOgyO&=p5_GbJb?AC+U45n< zBwR~sj~zS4i4#%>2|8KAI&{5u8V{0iEvXa7cZ^e>O&uiYWC`n#qneKgNw}8Oimy7x zD?d*iB(KSuy829Bs{#qvlA7P6Q|vC+%qSgeNzlm>)}iaQb@iEckZ>)j+Gjh( z5i3#$2|8KAI&{6Zu0GQa60Rlnahtv41|Ovk5_GbJb?AC+U45n{>p zNYKd=)*(kVzaKpb*OGc++1~N7b5jQiI$6RxbiKB&KGW?W;aXB(cjz1+-aU1Yppzx6 zL)UBT>ND*i;aXBxo!2?Ow=jK{kf4(#tV7pp>*_P@AmLh4lmFg1K6Fv)AVDWfSck6H z)?XuO2MO1b8uwP`xb-%vg9M!{VI8_&TYrtD9VA>!>X1)6$99jTV-yKGS;9K>`xyN- zl6H`AEvdotJI7`Rr4ABwvV?W$dTsqRl6H`AEvdC$=^S@ikj@!M(8&_kq3gBv*GSqy z!nLFxnbtX8dv59=K_^RChpyMwUn6M;3D=VP`+&~z;O41=1f48l9dcAF>aUTsgM@2I z-Pf{n+~&=6E=qz-tmH~QU?h-S;9JWy>=Q8l5nltfiYa= z{pjgr3G3i&-&Q>~jMpE#za5KQOX|`U4ddN=l>WW){)2R~gmrMXkA!PUO}eyU{CvCA zL4r<}unx}lk#H@k%eQJ6pWPvKkf4(#tb?)>o33D=T(<;nW7@xcd`Un>%HvV?VTwvU8sN!`(?L45Se)Iowymaq=a_K|Qc zsaFR#h|d&L2MIb^!a6wHN5ZwFdd_VS?^~EUNYKd=*1_3660Rk6=-v%wtd=@R(8&_k z!P!0%t|fKyUmM1WwW)&yoh)G;ob4mwT2kFM-Z1X?e(E4WCreldXZuLFmeiLcH;f-X zm^w(%$r9GV**+4kCAHfd8^-s}N*yHVWC`owY##~Nk~*bXqxg3F)Iowymaq=a_K|Qc zso#1via&jlK1)c@$r9GV**+4kB~|Z+MsaR+>L5WUOIQbI`$)K!)b}$Q#m-x%4ia>- zgmrMXkA!PUJ@I0r*!{tDj3PlNOIQbI`$)K!)W^>^ilIyDAVDWfSO;hONVt~NhzA&3?%4e3G3i&9|_lzYB|19eE6)?L4r<}unx}lk#H@kX5Aabf!m}G5_GbJb#S(i zglkD{y+NZ`H9MV)lAx0%tb?KDuF?dPV9WK_^RC2WR_8xR#WU!fOA0evnR< zunwJ{*Rx9<*LK_N`EcgkW9;0(wWL}e{9L&F!P381{(g{7maq<;pO?MLI!L&d)B$Hc z8)i*S9VF;v3G2}Lc|E(-?I7V=Qaem}CQQFQb&#NwC9Ff|=k@GTJ4m>e)FHE<4h^43 z9VF;v3G2}Lc|E(-4ic^<)nL7+!$}KM2MIb^!aDeCKoYJcb#C`!=($CY@_8Z&I$6Rx zbbemXE_FLdxRzAwzt@D*dZrE%bh3nX=={8%U1|pj*OFSgV@>G%Na`R#Crem|ejlS} zm)b$XwWQvB{;AM=lVi)T6$v_7!a8(*Ue7M2qMC$jNv*1WDy$lvI!MsT64s&Xwe{>$ zJ4m>e)X-C(3QHEI4ia>-gmvg_pPpT62MO1bYSZ_r@O{_g%C8j(I$6RxbiKBoU1|pj z*OL1Eny12|M^gt0I$6RxbiKBoU1|pj*OIz*!BgSlEsig52MIb^!a63({Ggs)Y6l6| zlDfTnO?Z7|>L5WUOIQbg4M@VZr0)5oCj9t(>L5WUOIU}l*OqTtY&%G}meeWZis8of zPAI=tB)@{eNw}8O-{R9@T8Gp@f=-sO4*nXDglkF7Yxqo$J4m>e)SEM&4Ws&}4ia>-gmvh8Z9Tix z4ic^<^}uD%h5ARO4ia>-gmvh8Z9Tix4ic^<^;P%h!_2m+g9M!{VIBN6APLu!I)A+v z!ar7~{euLZEMXnGUR%#DbvsD7mekvKy&%`8P8}rZWC`og_1b!NsU0L-OKRhtW`z%r zOC2QWWC`og`FTAb)eaJ_CAGtKv%;f4r_Wsybh3nX=z49PpU@5xt|hg`yR*W!H>3^{ zbh3nX=z49PZO{%9t|fKF_p`z-ZBqvcI$6Rxbhb}t8?=LjYe~)ddRA!hOgh$*ppzx6 zL)UBTY=d@?a4o5yUzinkJvMcappzx6L)UBTY=d@?a4o45N6!iqSElnT5_GbJb;wc8 z?>9lhwWN+&Z&v6!DRq#blO?Q!zXl}XT2hCd^+ITVQ0gE-Crem|uGf}tS*rB4BH>z6 zliz$kj9oW%kf4(#tV7pp>uiH|kZ>(2ABENGc#s60EMXlwKd-CLwBw)ej1LXBKG%-h zt|j$Cz44*>&*zkn=OpN43G2}Ld0l;`9VA>!YUv)Ah7*^k4ia>-gmviryq;ZZ2MO1b zdbQ`c(4jVUkf4(#tV8GLb@iEckZ>)jFR!{J+`d-nH7pcJ(8&_kq4V>)`b;}WxR%uY zFJ2tJ-7$5Lppzx6L+9sp^_g~%a4o5AHoiFg&?|M2ppzx6L+9sp^_g~%a4o49hg}qY zx;u4{ppzx6L+9sp^_g~%a4o6JmX8f@|C%~T(8&_kp`$xpeWo2GTuW;BC1b-+C!AN_ zKSND*i z;aXDN*19BY9a9GhI$6RxbiKB&K9i0D3D=SuGy9UT>5-{}1f48l9lBmySD$GI3D=T3 za@x4?-SMe|1f48l9lBmy&n~rtglkC+A9HCKcUknx^CqXAmSck6H*41a)LBh499{%d`FnoIIAVDWf zSci`8biJB(kZ>)jSC70R9I}7vAVDWfSci`8*Kity5?)Iowymaq<8udTmE(hd@?B{lTHE5bkOr4ABwvV?W$dTsqR zl6H`AEvZ|^T@hZHn$8(W(8&_kq3gBv*GSqy!nLG+-SdjjrgQ2bK_^RC2d@@N!nLG+ zc=7V^>8I%&js%@7VI6W*^XrR}a4o5?_qsgHxHff=ppzx6L)UBTuaWe%BH>z69k0DC zY|%Y+kf4(#tV7pp>#vctgM@2I`6#Sb$Acv3WC`ow{9vysqr#k-pKIY z<)weGoFAlX=?5!uMlS2MIb^!a6wHN5ZwFnm#rxoPKfYAVDWfSO;hO zNVt~NNt+A}O(&!d5_GbJb#S(iglkDHyl8NEc3SEnK_^RC2WR_8xR%t@n-2=l)uav* zbh3nXaJG+xYe{W7Z$Q}p)6_wNPL{9^&i0XTEvZSb_7CkF+)zH>B|#@kSci`8()=I^ z*OKc0d%v)M$J9ZBPL{9^9o?n*K@zSd^^ej0!bU?<2MIb^!a6wHN5ZwF?)-oK!g|wF z2MIb^!aDT(m^42~!nLHf*{@%i@LuX5K_^RC2WR_8xR%tcN&UjQ4R0*J=OpN43G3i& z9|_lzT6@p_VP5CdL4r<}unx}lk#H@kjT#RKXAeppB)>o33D=U^YS)2b!o<`; zf=-sO4$k(Ga4o5EV+V!#kERY1bh3nXaJG+xYe{YU^Wbp$oYX;rPL{9^&i0XTEvYlE z85&MlkUB`v$r9GV**+4kCAHID!^7TRqz)2vvV?VTwvU8sN%dbeBFtW#I!MsT64t@l zJ`%1awcTYS!xkT<4ia>-gmrMXkA!PUO>cZ=82(b~AVDWfSO;hONVt~Na~F>e!~T{! zNYKd=*1_3660RjR?1eF*c6{m}K_^RC2WR_8xR%tiIcJ46PDvdk=wu1&(9vC*A0**g zQcZ6;JJhyI9VF;v3G2|&U78;x;aXC!v^*!Y{52gvNYKd=*1_3660Rlnaj$bi+m})Y z2|8KAI`sRPG(SkfwWLn(aZb47+SEaUPL{9^&i0XTEvcF{&Ivo6oH|I*$r9GV**+4k zC3QjXv%|@4QwIq;S;9Iv+egB+q()wRR`|zn={%7Hoh)G;ob4mwT2g)cjS08UOC2QW zWC`owY##~NlKQ#H=y24dse=TaEMXm-?IYn@Qa%c+{rCAnI$6RxbpO+{OC58reBm!) zgJ{2^OxR%t4^CyR+A59%3=wu1&(D`{iyVMR6 zt|j&Gj7j0wmr@4_I$6RxDt--!$8uUyE!LP6e)~Likf4(#tb@M>B;i_8ul2ksRImTH z@_9Q6I$6Rxbbem;DtoO+xR%saAKn-Sw@)1;=wu1&;I9EmxR%uDQ8$L_Q&R^CI$6Rx z_-jBCt|fKrE;oilCZ-M&bh3nX=z4AWmPNnot0v)EQk!pbV~8)O4ia>-gmvh8Z9Tix z4ic^<^=9K6!^^*=4ia>-gmvh8Z9Tix4ic^rSCrenzQ8GWTXP4SR!nLFhUgM_l$hE111f48l9lBmy&n~rtglkE4 zpKw!n<%!fmf=-sO4qdOUXP4SR!nLH<-E)$R4N?aQI$6Rx^!pe+yVMR6t|fKEx0Awc z-=z)`bh3nX==U*tb}1bN60Rk6Ud`li{kr#;|E@^T$r9EfM>W5`C<)h+I_}z=!$J4m>e)X^RO5{_Ckb&#Nw zC9Ff&YwOvic93u_sq5CbHTdpl{!e!$r9GVUjveG zEvd7Qy)EqUKv=Axn=4gK_^RChpyL_Z&~!Sy+FdXr2cf*l+d>}9ivFl z$r9F~>$P>ZK|4semei=JQ^NemQwIq;S;9JWy|&IaXa@<`lA3zvl+f?u)Iowymaq<8 zudTBU+Cjp#q}JSiO1SBW)Iowymaq;vs`>RrNw}8OFEefnD_f-w5_GbJb?AC+oo&$V zAmLh4-|ui+_~e&#zDt5mmaq<8udTBU+Cjp#r1lwmYnbq1>L5WUOIU|~AEUDk+Cjp# zqeNAkPL{Ba-DNy@TX{T4!nLG^j%^S}J(xO3(8&_kafz%KJ)yi_l!R+Z zbzN3JwpfrlNYKd=)=@3{-$&*3q9j~P>i*vKWA`m@E}vhKppzx6qm}G`&y~l6BwS1C z&hP5QKb@L7NYKd=)}izBYn9iFl5j1lYp2wUcRr9hNYKd=)}iaQ|5(1hC<)h++Mr*( z*lq1w%C8j(I$6RxbpKmczP>04*OGdsTfKPQiK&AGoh)G;`hCpT2bIQyBwR~s{1Nry zE03lQ5_GbJbxfA=;2+D^7bW3ZQhS|QFLrA9m-1^xf=-sO4&DD`ud?wV3D=T(YDT>n zdZrE%bh3nX93lJP_2uy(3D=TpBG<(^;%}*g1f48l9q-EiH?BM$B;i_8Bd(|)oBuO) zkf4(#tm9eP|5}&FgCtx_YPZG>;vL)FT7ExB(8&_kv5)M36U*a460Rk+%_9wByTell z2|8KAIu^-z@PYDpkc4YV4LYe|96303kf4(#tV51!on^1G^L7%hCAF&IhVjO;QwIq; zS;9KxsOIBA60RlH_vsDeZevmh2|8KAI_ArG@Gs@@APLu!I%H_0cw(Q_L4r<}unyh- zWUsQ|Xj@zy! zwbs->#VvO%{d=K6f=-sO4&DFs>{8zk60RjR`s;S_hpkcv2|8KAI-c+HVW&&V^MfQ@ zOKSbj?cxdBrVbKxvV?U!EAxZ5mFEXZxRz9_2|LGKcS#*2=wu1&(EU%(F7>q{;aXB# zF5M}9cX;X`K_^RChn$C2>Di@rkZ>)jAG_}qr&Xs85_GbJbzC9)-`w(ekc4YVo$zYg z_{Ni|g9M!{VI3UZk#H@kBTj4^A6#QX`COC)oh)G;cgz0wZTbF#BwS0X^LlOLcHL74 z2|8KAI`sRPy~^W360Rln=}+WjAG;=#vUU4B1E(8&_kA?Kl0dUmNDBwR~s(MN6K%==OY2|8KA zI&}ZjvrFwD;aXDtw`m)nDO^+D4ia>-gmoM$``^vw@gND;l6wA}w(+g5se=TaEMXn* z%l>z9c|1tMwWPNBrfr-$A$5?TlO?P}zmL(gOMR_KxR%s{^LC1@UrZe&=wu1&_+IwE zzm~^?BwS1Cm8Lt#2UesG5_GbJb##*bZ%TPQNW!(GnmoUAT-os2@_SB#PL{9^-T(CL zQeLY93D=UkV`RJ7WXse+f=-sOj&AaOjGkR;2MO1b`okap6d!4lI!MsT64s&L$LQIm zc93u_sUP3@Q~YS%)Iowymaq=p|McuqJ4m>e)EejR5}Phg?>PxNS;9KxJhZ51m)b$X zwWM18p?w@QBXy9VlO?P}j%r0Y4q68Z*OGc>Qu|nSZt5UGCreldM|UJ#OX`*Nca10S zkvd4w$r9EfN426H2lX?tK*F`8J~?UExO7SS+$BLLOIU{-)rxW)vQ2)3KHW zoh)G;`ukm-ZP4u?;aXCAj^8yNd3ov}K_^RChwguRcBvgCTubVqF1yA<_e>om=wu1& z(C=e(wm~~cxR%thOWVgz%hP!x2|8KAI$o3g@4E7Mkc4YV{W_w39P-!HL4r<}unzq` zM$ayFJ4m>eRL3Q|#AU-$2MIb^!a6$3_c7O($ActXOUg%KwK^UoK_^RC#}_gll&CT4r4ABwvV?W${-bh3nX=>Df?m-3z$NVt|%y(2e>hrFFS zNYKd=*1^#o3D=SuvrfIZL5WUOIU}_&&&6s))_~)glkE?HnL$H)irgHppzx6L-#*DyVSoc60Rk+>4b){-AWt>ouHE?tb?OF60RlH z_40=C$H}RK1f48l9XdZR-;3(;yg9`60Rln)Qb(`u-j7y2|8KAIykx`;aXC?4sQ^ro|-yH z(8&_k!O@c*|5vD)xSqz0=O1g48#*KO>yexMO)Gh3A=Hl?eA^Vzswt8t8dTn>pl|++Y zhQuA)3^3>16Gz5}2A^Si{qOq3qt6{qVq^!oAJkj)$M!$vqcep-7 zeB1rBcvAnX%vtpLX>q~KlHO>|-f>aS2^r$fm){CE&pyeVE*rfWp1rT6o1XGUnA76K z4DoRD72(P|A2;XAdEbQ2SC{nHAAJ*UJ^mjVVw+7Cg`F;W!kh&Me;(exsiceBe;)eG z$`R=sL49>UE`Nup`mNfIap2#s$#i_*vsG+#Txo05+?^6>j!kvt`@zRe-`xG*9c(9& zzLQ(Mg9K9-Z`d*ZzxV%~*$z4+(sy#JchE`Ss%eUkRJrAJNTlz}R_`FeRQmR7b%L*Z znuF97->1rFMTbP1U0l6`1XKHWX&tAWllyC@Ln6&CuHHd{sdmq`jt|I;;_3t)5@~kv z|0bCFVs7jB^`hKgI~@{fc5(F%5=_;OZXFjlEq%sRz8`c*q}j#QJJQ^ZI%$qYHTQzb z4mu>#?8)jKbkh9Cf8RkO&1|gR!Dq!3Kb0!CgRe=N8P&(-YgkFpA(7@hSASL{m|9St zOI@9yljb1*`)5TW%`UFq!Dq!(nk!tL;AckqW?NJIjH!IB=#c1C{`P$J4iZe=@kNKY zc-P$LZd!k%kCoQRsOD!(<+EZct$O*t2|gByw4P=4?I6Jvk8qXGid&n$-`B^jd&}vN zNGq#We^w-zO6#OnCwKqjMd6ET(>)w=5L4%Mm=go4vvEu+LFX+I!RP$z@?!i;}K{#{fr=iDtrB`w0kWa(@YnC3jU6bd-@CS3RE(xX% zoA_Cn_ehT5#Q~TbrFf^T%BYwYUVVF9*c_!! z*A{gSE#IqCHNSJH+;Tc3(tR{n?;ycc-QQ)U`DZWpYuPz-D>26@FcaUI;?|)?n{~FSrv-ENK zNRDMFkcg0Tty?^b7awlCS z_=!>3L5D=TGwtfzL4qkh+sck~_e*`ObeBri$4;Ia&V1wK%yw{VzbM~wmu;B+}hhSMT6fZ7bzWFYE+qU%G^y&Nj5Pte}hP}^6wpuUVdQIuyE1wk!rq(`lWjLg7j^N|| zbo7s5>J|T~gO5w%-W^wk2|JYN%4bD_skI(o6>5r)W&U>QJhp08=yP}}#Yd{UgT(V+ ztqKblKAP#^V==X5?b`9prT1qDIwUTixGG#XGS@+Zsi(jGF}&U&N6#sta7fQ|xb*4m{{I6hL{&x*u4jTVRTXXHLb`B+TxeX8uBL!zqR;_&W*Tn7oJxEEA*aK4sj zvR@2)J9ODBcP6v#S8s=#TJ^R4d367IVaWr1Oz*wt*P-u%!I}M>sS9Vk8@}K2KM{N^ z5}UpLUf6f=>6s1^Ouabu{jkm5y)(p|SC)r4S08WAo%KHm+f|)v`oq5Ohsi^GW(Ypk zw(UL$=e={9rPy8h>e3p%9&bdX?*&$hCI4vG1_KM2olk?SDA6kmnP4!$O5 zo&R1K`rs+{-1$hA1RWAL9`kM(P_IPSO)%Ad)jQ#~3vz#nmtFWusJ*k~RPXw7nBSrF zxEz;McC^0e#n53%>966^K`({V?!8!YW+j!hV#zM5nNf({)jo@iHHBwDhux0B!0Z* z_0VHMiLQKBB$%rE)ulsX;jgcTz1!#BK@v>yovnOUeAoIu=*kWfOf@7(MbrdOIi=c-Y$&EnF(R}xr0RO`j*4v+*u{P#gT*J#+&Bmg!x$PSln=U-1oU$2Oomb3@_U%T+8RK#Uoz`EB zj8ji8rT9pdTTX|>!4pTuBlga9kYK9S9wXyxEpr54#cM8-zl;H;6kqkqXGMp^H~S2a zf0~%5zv(``c*#qO4*|}Gj1XKKssqEO{#DQ_^?@D{;u+PRa5$3JgX`UJSYc6j_~?~>*t)!jkj?XDwYuO7M25`JdzvxIwdWd|J+&)qpH z?$|x|evn{_pW2lj+;b+paYmfCN$EY{o>ocFAu+Yj8F6L3+&f5uscU~85l?H7Blv#s zJ$U2D;c@iJ+?LZJQTKaJf+-#uDz}^tiR+dRj2)Ke-g6R6)qTY2^uWkCc(>AH_5FQh z{Bom`=3h_cv!X*{-8d@#wmA1%kzk5PyULC}m!1({8&Y~EM}K`rY~1^Qc~&G=9yu}& z?OviQJNT@a;ww@~a9`{H(1>_!ztZFK{jVhGkm#}18L{KA+_NIV6kn0bj!}~a#V#jL zw4?Ao*YuCyZ(myL%15ds=#Ut6*noIzZSM1m1XKL9tL$jFe&4v;z|u2myrggZfBj0D z&$g1FL*kMDPuZEr=~(rDd{Bh3SN3IW4zXJkNRgeBS4C&biLH?q#m~oQ>V&Y%@&< z6LhgpHqpL9SJ~c1*VR6*i{#v?$8BxPF4EWAr6BSz4OB=3KSNJ~u4%7$?~XINGN_Q? zGy8Tw8l`rUQRnrYY~J8b@?=ZB?!Ni-ak<{XwFc?h-m;Utzx8GW>msqSeJ81YpKI=t zpsU=HC!|t!*VEBdNVFfKm#pOH8GvoDGZHnnE%U{yvb@aHroO5F-OivZ zQqCwLeD({o7UkQ<*>$YQAMdff2R7kv(>4w_yf$R00 z1YJK@@J>YVc8-jEfA#v`zc~&oX}`z~m%slkryg(tfx7?=wiG{USRugRP<~?f2D@1ji@sm&IXM@K{kHk@lP6$P5y6 zrTqdplAx0Io8f=oDiUeCHAQByRdl88y%b3-QdiX8i!b=|Cv8Wduq$ono=75XKasG) zxtq3^NhCpqMA{B3kp$Dz_V)?9*jjrgQX!GHb5CRj3A)nu;fW;Dc9#k(X}duE`&N-i z+utcNgRP>A*T(KS+nct(&%bXKiL{-2{<&3j@oL(wqCz5V=bp$65_AR663)c%4m7R3 zy>PD6Wg;_3(3Q4ROeDd3JMWKadznNMR7jj1nM+oG z<9an9L08(IERh*hNIbGEhwOjL^=X>~U1@vEL}pMSv8ZCSB)#GKBus*?v^{bnGpLX_ zk}{juYp8Vx3e;H~MR7mg_uE7Ld%SJySmrf6J zyicS;;-NyNWKR>PXj9NkBkc9V}&T+d8UA+fJdq7)c>GlH(W zM|YG%<6Xa%p+e%5yV}cJOvZkcW)8)rL zuO@}3wQ$Um!xidC*6-qdW!R)T^6?5?o;A9W%w4F<_UNvdA1hOaHTH?DtLsVO*^l|< zOgm$x>QVjgHbI5Nu*>msUzSFWR*|5q*O6E$QNM|U=v}|2beyTvQ~py^e*H_AAAYl{ zd@{YhgP=lUUH+PKBFU9Og0A4vr9$HMLN(==eXa}=bn(jCqsuGEt9D^iZF%O>&930G z?y*uoCh}_98N6yF-YXR=#lCV~K@xQB-Cak9PjnGf-s@XO`nT0C))d?-68WR+$moY$ z8LW%0^7CuU=JGD$(Ok8p{XDG{Osy#iXLOl!!EO~55<`d8lv=f2>w^ScoYQs&*LJH( zHD%|Go2_%sD-vxF)RZfYT(g7(UH9KpOQue85xjqF{jrX$8m3*Gm3BXRsBeaV(*#s35qxQr~(PFL)5_B~@9xIhsxYl{02Wrc_ zih3?p*i}oi%dN~S5)-=Dk~T@2w)??(MHlC^P4L>b8&gZ>ZqnC)bHOI4khpZdmP|O| zx`HI=I?}SX#Cxv@k)J=fIyr7!&33D(kl=^}6LhWot&Y50SsbmRLgJS%tIO-#V;w~K zu34nVjfZ`uVU|0k#_hHIa=le|O5TBS4uT4aQfrIJxJsI~`$2-PrcafZp?zvQGCr$u zR^3xr`AWy-f2dqhy6tSOok4}fzIIvV)UU2qk)VrxvNQNAO#U*EzuL43DkPTPu}qyA z;F?z?=;A(pcEjYTtI~O$fS1 zFHTmu*7tW1R7h+t`Haf9Cix}=UE4D+Ryj-ba}ZQW4E=7T$~VvTbTkRN_!~@nbg7W2 z^4nyUqrB_a10?9;^|v!-e3qoDMeDyJCH>V+)vcw=4ZeL?UH#1U_o#Ilo>i5e(yrl& zL)B9ib-7uOk?PbI*I!1dkmxsZh+6ZfE2HS6-PELmy57k}MRiKle}h{5U^kUzf&O>9 zA5=&L_k#po9}nuLa`$#+P$9u_vs+bY)=+h!vTpm%QqQVVf9QJ8R~V%VOn3dwiwcRu zot{+{ceq+bf-a7_-6|?1y0m;&Et=xWAVC-Bf}O!DxNSx^l{tqV1zsDQphDud2a?o* zSl8bmNzm24Vtw`CyR#gtmI{eH`May3JzW``qg}fVRtpd4`N|Qo`$2`o^#X&`6DwV_ zodjK-=MGT2Uw0Ah^Y&4NCTZpPh+b;bd|l?Ov|CkXY=2eoJKe*1`3I`LJ9L?|$0n$d z*fesGN`BWhR&2?}yL+n5>u=U7wwJ`62fC}e$6Y-qK^O01c0btOK3fN?3uA7j=OljI zJw#>b;OaTYiY~5yyH&ilIkWXw-;C3}h!1sqD)qIMz885>tzh zR8xz)UZY6R^+a-T1YbcCbn%X1XK>sHOzxxF9=(-o zPNLF7eN~+^t}DoEPFK>&erne#7t!;rLF(&Q-|??)le-huM|&3g<^AU;sLZY2bX;>P zBwiZ(xLUG*-c1O)MlBwrREF6Of(i-t&mLV8bn%X16I4h9j}-~Jc+a;pIJz9SE-#K& zh4X&k=s6V9SOR)H=Uiq9oM)Y9c!`)DkQkmTrfe` z@i)FvU+>=F7+oqPxWl}iF?&!+8T|V?zphEqCFS&WT~6#@L}HTGIx>!}C@p2PrTWUC zIi+Rk{`G!2WlMRvyvTLUOI|A_Wt(VMy+x(uK*gI8tcyfUy;2gNPt$fkNYFLmSV?J< z(M7QB04nx74~$2noeeA#tHu30X11bp=V#b-b9D_o0gzdV2{OGg8mdPb-#? zmaBA`eL|zWlTWCS_&l+MT>rr}+ey$BJXUP)uQ!Uzl#{yc?4R8#DkQ3%FD_#Xxmrbn zF1FUrph6<|#p04X-jzXuE{?jL!FvW@MR`}U2`VJ`x)My#m7&1H@=4E)j#mRJBtBSI zUvfJ~_kk*P<#Il~!*HcGZROM*`h1i>4>gym4PEaUc%n`f@7GR;+pP3k!qau^eo!IN zGD9<2)o7KYA0+5He=c5P3*3yzaBoxj@loBXd|R4GmO8p@w`$;o#*Yw>1Qik)k2R7fXSrHM zg095bjpUJSF5-X98cF``dd6|Byja_N>Sc;+CQ>26Y`Y&M=z7z8GNC|wR|ebLs)yIx zE4MOMBzo3wBr)Y&8Egq%!L8z0#SUpCr>{nio85Dc4+*ubk&G|9+Hq$fL08?YjbvUE z7eS?XqsDTvk9M)9;8u~SyQHxU9P7$pU34AF)kJ#EbP-*bHI)%5T6sS@US8;`%e)8M zt)fEW+jjBtm$))W&^35YyyPwDBB+eqwPw;+-d?H8g(nY@W%U*~)*uxUMc4I~>?_}J5ZqgU zyCU#c|8}dWkXW*1xRjduiX(#rUHsL*ok4}fPdlEMAJ4e{21$ah;GR<<@!iT{GP3+^ zM?Xl=#ZkBWF>yh58B|n%`r+w?t?S<*U%afp1F{J!BzT@iFhLjh<+TYaB)BJNFhN)F ze#lfv@SH$9qj6$yS)lZ+Zcwqe{FP6aIqEi%C3|-nAFo}7&nC%}BXs$;&QHtU60R$F zd0Kbb|Mo)v+CF$DN&3a;b0#mvcb5$>=zq5}sF1i&pt}@#+(lIH*IR1T)k=w}y(KBH zE^|HF8EkvYZ<3_(M>p#Sdq|?jcS*AEyr%685_GXoHbI5NoJ&d4sHCgsBlGbJ=`< zRxbOZrxcs3%QnHeyZc;sDf5}W1{`&pphDtG{T}kpiJM(Py2dT-A@i=dh`XBglGTT` z^3=P%WYtDp=BV4P;@YlvvX}gLPWP50ViQzI^qkyFX6|&26$!dH(sst?&ON2}bY0hq ztKRs`&}FV0o1kmUq#ly6@MZ+-B2lJd54qzbS3gM5b@kJyFdPRE3G1t zFSff3j&aR)wu&y^kL|JI{25%Zr;PYR&l1j1o1j8s^vIra=MC3PBtcj3Or%0$;Q5}? z;gTzZ1YKMOc0af##@^^9HD=#zeK3PWxwzg^um8{jtRBz^(c}Yx_;lMT&W##Ih?>gS~k)Uf^(>Q6} zbFPD+LL$$JQquZQ*I)HX(8WDR?0)bsZv5*a$IT|Fkl?qt!313#H=CeB;;E*EuGjO8)pOM4 z(z@Jg-WruTt9~xWZq?4;XQ_P4^gZKz*;%UU+q%prM{I)i{#t&H`u>I{f-|U)csOOY znsmr@zal}`<*je1teac}+rB&gbv1X%&HBL}lDPEzOz-JWR|W~Xmam?n{@CFnW>=l2 z8cx;Mfb_rt(^ROV>%L2c#Kc3>RIh3-g6SnQ%us)xxRsuh_&i~{3f#hUseM6zyV7!L1?@KWVz!xyF^jy6DRMzzpwcV;4cC z`7blnoGZ7|DiXui&s48we&6vL#a7YPYRcYyJ zx-wW7UBPpg3W--T%vSGSaE&ery0~uaesC3iba;-c{i3dyHQ59e5??+tSCxPAX04*@ zt9!4l`3z}RZm~gtCrcpts*gC-duI$BiG%BbMFR7gw;<(8x`T|}+AdF4^1e@ikxCa>%{`?`O}A#Jyc3W>}|^T@8( zG;I@nN7k@UE@{_Qf8YAVUAbjOUDtQ7tn1yBJhHaIt+a|nv*A&aY3><3-JW5w&S zb8Jo-G%WJk*gavZ$=<&Om~$Vk@Ghax)jfyUgJCa?4M5 zYZvcIcB`n6xT|^|Nj>E1ISIOo&Ces>zv?2WRQ)ZFB-PU{))d?-5}#DgE1Q0H%|zBk zSH=c;W!Ov?!S9gxy$1J}wOd7n1haz)x_IZa2`VIl`$2*(zS`LtoIgF==aBxr^eo|g zvk59BuI0!n(}%idA_=#m)_CkOgJkSwcC>UVnlZrLWN zkl-_g!316W9^NLXkcfY|t*rS)|0OnvR7mi5Y<30-x{{A9R|V=%bBq-g68s&Tok4=GeZ@XhCkMEmlc7R_ zzoN7=NYIsk?=m&@OV=+zsgU5WLG26@bXCstj#`|1q+_h8kl?Rc?F{bMcC138eD9sa z7T!bVw(^Ox`%DiD6I4jd$d@Qbhr3!uf-bh! zZWY`9Xs^z)EBR*qUP(t7X9QRHs$Xq zYmVvJP-;bjWXpOh*PO(+tr8@Ma?M1J4_%yZc0bB&?<`|p(Cw}IduQoXN|$-Zun8(8 ziWW(f&)2!GAPKs7C$clRa^8QUlRV%(wH3Z!ai!S=6%rfHb(DUey4D~Gx;Tb*1{D&^ zLLDXkb5{llx;Pi?49=g=pGlBMD)+vHxl7{buM(tbCr#TKob7atexRe&8tEePebY&j z9@k3S8l9zU5nbk$wKJ%Y7&X$HWBXm}g9Kfip>_t_J8)h{iSnKX49^nw&nBplcrm(@ zl$`A9ISIPhT04UZiT(pR$w$w+GDy(HQMWUA?h?4;>kxgL50Ni z1&_zc@empeN$NYE9$3oR8A z+$GU&6$!ey_p41%ArZXeA_=;J_ms__az*XFQ}5jH#kF75f+NfQ@!?YhcB`n6NJ+k+ z_I$Y1F}ft^;&%gf1{D&8x}H_lKXg6gMS?DVYiMUsA@NzUld5-H*LSZZ=;9eOb_Nv^ z)fOICb$@n!5+*?x&zP|@sE~N=hodTQao1-Y5_J8$GZaW1oOV=g7~(n~hjr1#vo7p@ zP$6+~|2Jyy$0?3^MS`w64_s7FA9cM(Q6a%|>g`sMpsV=#eQJ7X*Peh>NCcmGfA^sa z>hSw|-F;W)ysEHOmpSw8R#73*Z0!*>vzTkI7ZP-F=Gz%mNSs~vt-4-xk>h%hpo=r# z&Y(hKX7>Z?{_U{*i3}I_svLjsc^FL4#hGstR7fON-lGnUbFD!VbaCd} z8B|ET`NLOg>`B)eBtaKvzMVmZL~6`u>h&@s9M_x#U7Y!L1{D%5^KVnv>brLGBtci( zm|g0jF|IX8g+zg&pR0+=MQ|t2S)<0Qo%5dad;7-&<5h)NUAFr{<+ttQ)bZoPe1bLE z1QimO9vY`sPtkNRL07FQV^zU;7cur+irV*wR{Fh|qJD3y+s^${?F=d;W~dbP@Acet+B5a}soMPTLuA^HNmd z&bqyI^NdiP*XwfdH>p%eG@LU+)ytws-OeCESB82c)wFUhf}^-#+IY3<$n&>w1xZv` zJznh?plQ2RyykRq=Gz1n63NTPtB~A()_xpS*2?3JE@g5KPd; zPu?~`g#=%Ng9*C$$=fEVkl;JcV1ll*OE#*6-`hFvK2%8XJPkX81YHTEQq{C9Z5?@}y&|NYKTTi0lk1B*xdeTh^{^y$-nC2hDc$@g z1YM&B>{p-0)pZb5NCcnMG_FVv*;HQF#nY!|jLsn^%DOVBkl=}0_ADVm*XT<*|pZe#NZe#?Sjufqe6mtc0Wka#Zk8jDkQ$!l1tQMx_`k0U7QOx!E0MIYc6?s zm!3<^wh1aEWMxj7H{LZ9NzfHMcew^%Umh(L|6bc%U3ROekhsw_T84FXwTc8?%P(h_ z;j>)?XLyr3Ii%mEo6UBv0}}1u${|xPxaKYix_JHVo>L*wI8RQw=NnfB3A%z;6vt%D z!t9cAQjZVE&~6nK5@$PRm-Y|2?jzl_s=fpuDR|EykGsphAN0 zQ7t0X{08fP86P#zVtHlr?3Y)z3G*vDPcgq;^UAErCQQ2LGOhB;rnO$#Cd_+hPcbK< zdS&zeI)X6gmwJjhqs%Ltzj8zn=3GNhF()K?Wpk2Y1YyqL@f7pTomVzz43P*$MTJt$ z$vK{4b|m%6=5!qr-VlUR&EBYDQ`@yz;W2akzbTIeS`{&A0Ut1QilH z@2Du`w%CZcT92rzd#Ac}| zW#iKk{x$#bvFg&~0j-$78+dJRb+($+KBx1{Z1)K&B>w1EO?tnTj__v*GaeXIU0RHb z%rhB2!FoxYey6%@J(jK?5d>YlPId+r67PRdU2fFW*FTt`i?hcjE(|IorwVz$GV?}s z%d-__Pa}PulZsW8jZv;^PJ*s8d&|hh@bgy@^NI?IliyX4wePw5L4vNzo6E>jCqae8 zeIHkl22ZBT2!-zqBOH&K^JGfeLbj8#x(sQ-GYMgI&tEiC3Fs!N+I_0|NBoVt?-6|?13T(MoF6VG%kf3X4p?hWNC09SF9DS~ml-aIbtSPuv zB#Ql9QRYo@Ww0)~xE}2c^S4cJ6q_}uDhZG2yBhCGHbI3%?bB7|$7I(%kpx}NyJ#pp z6ZvXzHNKL}59xY2L+w^kAyN2jCAref)hZHnm7a93RIlnH?ue}{ZHsGV(8bE~TM=F6 z7}~9(LL$?=DpL3!R|W~XIMOD=AFE<{PpV2UdVfFluHYX(oK%B{>azKZX~g=VLZa}R zQ!48aO`8m_5K1LMSMa+GDkOe;>9jf*a%GU9E2i}sb!@VWpwjEEv+C)0w2L*_{h&gk z)Vi~3)#t7Z5_FYs_@ny#vWuWn`I8@2a>-BpYr~p?TSa15)^qCN$2A>H&^5otIkkF> zi{N|Qr)r*4aqG2ff1z{g{$E@Kl|K&rsG`cQ_4~n^>{d}BaWeTwmG22n2NQI?dG4&r zFx*8@Y1Z(pN|}Evts=2;>KQe1y(@$Lpey*Z0TmJ{Uz}DI_P8=g(6#XTDRuNa7cqR) z2{mY|R?Io0-rDA8AA59J*Qhe5RMYP@&1^%2!t0z0i6zZWs$K_Nts+4eTWd1BLMWAO zH>a)sV?WqK5`(55R}(t9T1A4czNL?=Gc{bqwO@{_mIw8EHqV!Mt>T@}?gteT=Gm5i zyzkP*JGh;}_U_q#Ocl(e+s^*k1QinI#9Ov16uurL=;G&SJA(=dbHXk&Jk)!KTwsgp zyG)NRU7v3`rb;HJyZiX9qO$Og0pAc;BTX-kSNt)vl_R|l|h28CUUWdO}%_8ts-%K>o!%rmG?YD#JplZ=;EBV`$2`ou8Z4L z$&IcI5_FCGb(^YMv9+UBR5EWSDJiSi++DKoiJ{{Mo z)5r8&y0UJry3x(GKG@rZ@$1zW{q>zXxaU+z%s#qKjV$PTH6TIPUz69VlPlBBE59FX z`_<4ob#2hi`oSKO_;SlSm6+GHqDatn=AQK`c7XrVw>?HirWd>crt?KgdZ|e8stNjf2)|^A&W!wFrLW1KKOwh&8C5G_(L50M>`#eY& zKO341uMkSza{ih+c1(}xs%zI&*Ji8yQDFaUf(nUDA6--HQ#EZ9yw1-a`BmN5#@k2X zAFnyD8j1EyP#K*d5S$^Cf>;SliD^wug>K|e^fIc)@6Q@F&SPVluB2V zqG#28*LB;22`VIdUOBBkeACr)5_DyYKCNc`*F~_m=C}G@Z+VZg`$2_-*(V@ktVqzs zdzYQTzrHPxxuhm6)}zbyXcJUO%<23;HTG@SU6ce}978*U3W>NS=T(szt_%`%arW35 zyi#%9PN}bt>b1?9Y=R1j+jE^#W1ex{8A#COob93T+@&jDrc)}@ZMt43;WaOmN`=I> zM^CADUe$L#yB{RzD!S*CI#eMY;kSy)?!~9oj!*RpW=+8vBof!2QGNQk?r^M&F5WTh zjB3qyt2N8p`}f+%a(|^Zy{F53S8EegNG$$zk9vKVrftGJN$jmP^Gvc=Hcxd#tU>ck ziKo1<`fK%T;jVrQ2PGX)raL#w(kBG}w<&c$QEhv3vSgs?dU`9jzik*P3s4t9);#Bm9i9FYHto7JEZhuEBfWA)_uQenEYjm+em%r~cxWh<3W+i!wyT<_^|i4x zn9f%5j$sp2NL-!ug=%@!buS@77w=!I1R#4EFZHbI5Nu1h=BeP5@$`*^55 zR&;UH?F^1$nRLwsyuX?%JP(6+fKqm z?e7^#9RFmSYWae`cbSX`g06?^Z}+}QO?OZ9TSetu(H&~?S$(hlcda53s{W}uQqy&( zW?gh~rP=+c^+FG6)L8!|H~H7@vS^_$n-j<*R#bzj{iS&w{aja>GyP@WQ@R}L{k&X1 zJ;rfo$U9(woLfD?S2D{0`SX-6o3qd(GOlm!E=LRNdVfEcEIEJGC`7O&nDOs5^wD4A%l0hT1A4c z5hZ#`?ES7*u^()EL2rNOJo$8=>{d}B@!aKPx$RX~1_`=KH0~)A7Pts1B=Q|emI(>z zh){S%k)SKM=Tu1C_g%8wULjqEHw2+n5_ECY%~<)Z;{5sf;l5I3s=jKR3x@DBsF0XE z!kdZRUDuohU2FIDm5q<3Bm7o9J8^(iIHi>_m4?giiMm|j=>gJqMLNQ76%`WBHRxxM zpsQTv0kV2jx(uJ7LV|1FYmE6Xl*)dbTrfc97t&XaEi`to;JwR0Z%J%kJV5S=cU^N5 zbOql_sF3*cwE+_IqAP<0UA&Lk{oq~g>A(8RPr3C3Ax;`V9vuS10m(R$7yt>S_Vz-J4 ziPHD?m(NSNGDy(H*I+v%>BD}~s+%6geU17_rgVq+Ll5ZkjVHRx^kKSe6I4iWh6WRKarW2*6%xU-odjK61tudDUQz5h z`!r&BH@W(ptLIcmnBBDbKGDx0LD$~-Ps{jTt_-txv{zTfvt8uCDD5I``r#EqsZ>aO zy1A>2Np@wBpewjlW}j`ZRc2pruWWV&kLWp-WbZVOLN)aLgEiUxph99m+e9h(qpKez z=;9dK8B|EjE!agqUFympK^I5b&Nz9Zvm9NkKc$%Sc)am3yF+oT{3}S8IjQF#3D!lT z{kTq>(J)AVHVePb#8SR7h-W-$|<9mo6g|o{3bpx9lYEZ`H4_tjQiLDkSC&?j%pP zbiF#0pv&wqAJGqU?vkghZP`Wo{{0J;X|H(S1!QzRr*F;x^$2tBXSf{KMRM+(>i7iN zvuSskeL-LIhbJe=ujO>T=ETy7R#73bVq-Ts+w7*TLQC?Wep(*vmX7eR2cNX&v(K*xgK3TTeb!VVLB5_6@X??%z-4Zj*J}h2F@UPFPkT83|u;+e1NYKS!zS%uD z`<{DsjrcON?ECLne}sE}yz$?fvLuC8x!NYG_|of|P$R7lL2cDp>6%auWbu02z3m&aC(cH9|Atge|^ zPOKT_yHelIESU!AvfXozsQK;lKaMWPokX|c*`&!2`a0PeBcWZVj zdXH{9YYNUF(WzOq%#R4MS9EcXnGC;G zoN?_dXOROB=@DhNAtG8uBD6h=l*{hA9;}Nl-Z4yu->OFAa>&)0x`(`TzTP#5jC#b? zb1Eb_d+ZDnbmcFTLteO;t{;A@sE`PriR?$dNjaqQ<;XsnR(XX`D%(!t^Zq$xKqJ@P zhXh^T@xxMNo{OMz@9Ain{6FntO~I`qQFd^&^t;csK3ErBXGi9e)!(>Y2dR)4`*U`g zo9xOULDwV8a>)L-T<;U9km%YbyELBT${<14qKeUy^oHyGE)^2(R%DZ08(bMA=o)-` zHaY#3i{KsZ=L+8G*?<3fHCv0U(r}-PphDu$+S#Px!F2Bv{h3IDuHaTtA#o&QcFFXC zejjYlD-v{ZL~MdR=RKHxvI#0A%;_-^?*K^9b=$G5qH?%?0cuXW@#=c3cQ%3v3<;xXM2C0z9@nLDX_Yv1j zCg|e#*ET_g#F8z;rPNe?f3%6B>v~J}m2dd#`MZ_FWMui-e)*>z&&!WzT-Us3{YDZ~ zPCsF2_M!Ji^v#DFNrCqI-|Y-4BwnoDNajv)5oQN|uigyzHkBVA)lV3jefA@+;NUs& zlDFV$zwO_)i+{ACY0sRreGURbo2J;Wp`>f%JwT zluCuf`E&6STfo(G_JeI7xyS3%*>r^84_=Q}JsQcAS9D7_()RVBLLzZ?BY9+-s~;rj z%6QDno8=5laj9I5u-~N$IZ^5LL&Kcywq6j${<0P z^LqHL;_Q1rI$mDr`VTYFCzwH^>$0XYB1O}|{h(`mQv_b&SiQX#SSQd8;L$CW{Xu4#4SW#!8*g38PZ@$%V6 zx6&#SZ)}N|KBrt6Y!zL+kJ&xvTH~7FYPJa~BshD53A+9~)Lf=Ebp5)Y3JLDYW@jY! zFCsBXx~>b&O2~>4>-|^Dm!_7G?X7j$5TWqgrSj2<5>oem?P5)a@Cx2HEXW`c^>BQCl2iMTJCS?$VMRwZTD9d1yl^xl~HKSd-mzDkLr?mXcrM zTp1+jx^{bvq}JW)Xcb+}GnA6oTj+X&2`VHyO)n|&Pq|t}g02>oN=j-67x6*!yX8NF zb$fTeQ$q4YYuD$ACFJ@K`r6oIMI!gb;*vXFySUP9f(nUh=ZnkOLg_L>;Z;lJ*BixU z%1J$!SW|EYiQ~n*d&!5cnaH~6;+@FO;3#(493$Vgyp=0R;>-3ia_X^k*Te5QuOM9< zb-PtmNG$oQgd|i-m*JtIR1$RY`r8?t4WCvlAuU(wtHzpaf(nVDx0jGHBhy{;h*r_X z8DnRpt}ZR_$LYGRzgb!q_19(IV{C#7iCm*fOP@Dgts+4e??iS6?|tP4mzE<7^z7rk z(k7^o7&ND}EZy&#yCmphYwZjwB#x~pEoHOatmkxb)a?xJN5ma(xPOsNP$6;rjc?S~ zyIpga1YO)~)?|djvz`0Xa%Y>aMHZ?@Gk@f`Q&S;f&XVHib3cOwT{r%ms#?`b_xnMg zphBX~)yZm6s}CKmB0*P|7e}kYc|ULvR7mVUKS5<~^`=euts+5J&$kAtuU~z~CZfWl zd%nUbRbaaQwx)f>`s%@VXZfyCi^nLHVYY*yLgJ;dkERYyj@kwes)KeaME zaj1H#q9&U47^zNeaedcE*SZYPs!HLLzrEQPOi&@wrRB3~(G*Raf$|F8FLIGi7q6^M zaF1y29Ua_rDkK&^*iB_w;A#~Kx;W}~tJwC#ot{+{cj$V9`$2`o&Qi~+Qh&HwMS`wE zvxce*m8aR)JQN;X&hR|>yQ`r+wTokD_k#+F+a5?#2V&D@c&N8)c2QBC6174X_xLs$ zeyccNXMC2VszvMGa?}msXHX$==Yj63?s3;_CqdW7yL+n5>s>_WxdYVh*R^uJz##R+ zN?qm*wOd7nMAvSE)xra=3=(v4ZQ2>UwmN4k>-6|?1N?h-yy6kpkP#KfbQyp1(D;Xq;R_~!E zO?73kRdjLYn|_4Cvz_zj_=sL=(|moMIo}N76+)?0NVLz}M-`gnnk6LYDzqwDbs6a* zs65%JpZYaLyExzMR#735Gh2W4%{W&E3A(s$>NGpLYAI@wR{I_1hBK^Iqn$q0q7Ij;xDjaSwXUcsIvB&HT0siqcpy*jfl zx}HdmQ_n}c{;JRO7EqCOiEDg+YYr~)%>xd zLc*MK&UeTW1YMg;KBMxjNp@sVAu;s3kt*N3ryT?p66PGuh*puHtIBVaRgUr<92rzd zaMv;W3X-6UJA&B+6%x)J%>2#Cg@sv$1-(h zK)hpgsgU4_D0T)Bj z=d)Wyg+!qTYRkNeuGvn4F0LCpg9?fA^J~lI@~#XLbn&iaXK?-un^Z?WUZJluXQ)k3 zA#u1u9m)EgYnG6p>%ykm^30`lL@2xlKe?;Dywz0ix3jNLq7)dcchC9V+q1ZGyXN+* zn%BHgDisoUkM1ak#;4m;)+hM;+5$Iv%RLpk`}LBxdrpPKqf5KV$0_Od_woBdg0A3J z@fXq$mKY|J-y7k#ioayGTSbM${*8mBa@FS?V?}~4j)g~YIS{pG`6&p0wj(8X~x z8U9$A6IQ+Zl{t;pEA!o;A-sb9K9Phu{g$r=eg+kD!tTG$AYo4QWky7+=;AwByB}0Y zG|Y0R)VN*0_q7Rg9;BCUPQ3NX=7imUY?V1@)N`2=OCt#O)|}Sux!6LxRa8irle;4_ zNYG`@MUEiYLvtFj=i-Rit)fE0oZ=dhL4q!G1}uqCcqVcb&B?u<>)*{?66T~}W_TU4 zXFFY7H+Ij>`MzFV=Hynd%>LN~6%ytQ*oanToZ*NJDkRM5&=CY@gE>#wb8$rMR#72g&N7b3AVC+etewG?V@?|P>g7ta2`VJa z$>tHQB0-lqNj-uv=h1tLIn&uIbJXotQ6XVYhmOc#dZ{tFWcd*NeE?f)XHX$w&Wex7 zAVC*fYiCd)Va}$H$RI%%$I#B;n3(gn|MlpSFlT-LW2@-mN;9nrh3{9~ZI-*Na@R^j zcm?kp;SOJ_-6h-k?V56&=vfR*W(>K$kePo{eJMB zY_-G=vY@~Icaz~2yr-$4kl?;1!315ihIEiAhg}(bM^>~*qI|wiyQ==)Svr;K<#-Rr zdOv?AK_02x+jm_mo*;{UN=Nu(#hw@F+d&r3=@Bssc0br#61Tn5LGskpbTC0z?rk09 z+#&rQ-X_??GTS@Lm=|>0IU+Veg~X_l-dOEV*K-fG_xGWzZH>;-wTK=!JA(1&ax|6yI50j z28nv!PD| zV-*tRdvA}?@VB4A1YNun*#uWkzHd57(&Ks+G214nkmx_4lYI27YYmd1i|fYDphDus z=uT2{vMYlGT?6NJl&GmLg39OzI!djP+QpiJTSemMuM(tbCszjRqKo%=lMxEv8Mrz( zs~^I1i$^XTSbDd$qD(T$R|%a zT1ABfzss~UNYKT1wKhS8MDX9$NYKT1=XM4a5~bD_lW~>OeZvw8UqKRdIlq(f3GN%k ztI3^7>{d}B!Rr)E(6!{TXvsO*b#JFag4fB;AVJqNxwFXt)ygqTsF2`wvNK4~#m~Do zL4`!{=W`Nt@%u895ei>(?tjB;!~Jp$;T7y1fkWCg|d4Dx07} zf@2s=(8bSGHbI31zugHY=;9LvHbI3%@RI{1==!Y2S#?ig<(TaiR*zRZ20ZU8mGiu# z7Uv%6my?%`S0887|8BR63JE@)ViU|*Fm1eAbtE#+CRi_t&svOE4eJhf^n(Ol%g>Kf zeHXY0Dg(NWQ;mMpF4h#>DiXzaj8)}|hi=j;x+dlstIF4M5gF=@RMX07rQw_rs$Ldd z=2K60tEiBun`eaTyx!Gw5?}l$MZNTzz8-vr$7j9I z^%PeI3A%pUK29A!?jorC@xXXhAy!{O)?|+r6%w;XjaNJ8rJE)GSdpNMcO^T6Yc0OP z81+??TUk*g`VJngMzwaWTCOO%TFf7%uC#FxT%B?AQdHs2dZn@^yB}0Y%xj*ahW+JQ zgCywU3br%Y-a)%wRQX!m%2<(ToaseXR9ro0tLWmL&$KEOULRZsI}=8!nirn+*EZLU zA-saUqDY*%f3#|MPSe2zU7T+=L50NDY-3c+byo%ny11I{3_d%=r-k^ekxft`!KW62 z3A*?Uf=y5%v3Fe)dGNC9ydn~G{ku=wB(glxOa@*V;<&f7F1q;LfZY!&B(5)bT;5(Y z-jP9qF766$XHX%*J*9&Qy0{0rO;8~bygxMwy10Y7oxy#hxUV<&tg;CzB-p}Wg07J{ zYsrJ(yyUnZR7h~7?FT|A>DTN&(5GiV(@#p<)^!6J6c78t|#uwEi>x6h@S0p zNdI11DYhb7DmT;R)7>&k^|K2c8B|Er$R90>%DOU0(A95zc8U34x+~~k4=M%j$}Y{{ z)h^a#j};XX>sDtImEg)CK^NzOok4}fLj$vU+vd75NYKTZZ!$vRnaKI`eqwfsFRbSh zYchmau;(s`Mn8JHQy$fGI+&oVPfD~5Smq*H*32cZkJZYeA9Bf&MY_y=73~ZvBqoJ& zOVXFF3=(uTi_Rk#vba_hXLZ9qxujiJJ^Q!{>{d}B@$`nAQe&`d?vkL3v&YV$LgHGE zoHBi=D}w}GT$?5%6u#!XQiIFokmWDy5&d_wghacqbI76RUDtzk(Z%azTICh&J!MJk z9Gg=H4Rd9%F1k41>lpzFhsm-m|<1=DlCRa6dt z*LCdWT}0!=-m*aH9?lxyTb_AFmxHe$ z6%v`}^_FvQy2gqGU7T-rZ&v7oo~JM79JK^Nz-oxxdMF0QxK>#ye$YqAL{B*xz8 zB{gQJn~DDQAVJqt@Ai^a8`BY?@HOX^;_BjDuvYqpc1tLNliGIOVk;FY?oSua_A_*P~KiGk;P zN{377uDRDCZ$}{9cj@At&+a)D5~D}2Q$+TDkS*s+-?;Ky8ctJpp@D4-v7TZF&R`y6uxkqe0BEy z|0n(q3Z;^ut3~N7GJA5mo$H($RI)2mh;!tv1927KVw|;pH<_v z%l*2Tk&=8t?fG!2BZCSFehUA))BgX3Qc2KNsOwo({X^HPr9y(AsqG9BbbVIrr0U() z^_i0j37$P-XON()+QQ?i?$540gs70)^Db zYQqrM89Y=-1V2qhg074EzfpTXPI1gDDkS*Kl-&;!bdC9JpX%1Hk0XN$i9tyR)aj+J zXE{mGRs8%uHNAAYeQ`qJRl9Z6IaTa}UQwL+&DI`KGmCxTXcZL_oYQvCNziq6*|+L? z(M667DkM0k?Fhkl6YAER}DWD}w}Gm$$y5 zvTkw_R31*5ttK7PF4km^E)^2LmY<`(zv0RtLD!AdbJXS1u6f0|^yMRSRrx3XVP5%T z#TiH9qr-Dl?HBQW_wUYle-nNuRV~W8%%6R94Q(|?m0#*2sFeO_wt8pJt+a~7D;Z|1 zcQ3dy*ebes$FQ#l6%tR>d_z5+G2OkyA1e}c@lIrC@V+!`{Y>?0W?e69vI#0An*TCG z&AH<0ISINlKQP1FInqT?iJvrG?OdZ>tSPuvBpPIxu2xQQWw0)~9-TZ*#s=R*~3~f13LAPuKcjtLXZ7cTo~|=bfhHQ&$G-qKmIY_ULjwXDl~YO>eI2<@&b? zDkSC(oU6KxbhU~EU0gSI1{D$m=FL?{K5}J{po_0|CL7XDkQ3O9v~C$(|_Ly zCg|d~R5n3{MB&LpWLdqNed9$J&muG#q3|`o_RDeA^57c(6(_aa3DtF*KHZOJ1Q^0A zgi@)H;HRZvf-cT!o1j91pO%6Ny0|uNf(i+KS_&rU;$IqVf(i+Kz6vJj;$KW{f(i+K zS_&rU;$MDkf(i+KS_&rU;$N_Bf(i+KS_&rU;$Pxzf(i+KS_&rU;&awEL50NGB^y=3 z@9q4R7EI8^eR6Gr3W;}RgIZ9tts{d3T?wO7)wC?>h){T)^K_LA1s;}9dT#XVDy6EC7s+~cF#P9o*T(S02L09gKiE=VQ z-&bsc3W@d=y2|!8HznX&+p>%FeZWObdnHloX4J~b6P@Mg+KK*%GTU!eNVm<~c28bx*^6H|?l>Lk)Wy_{Mzft@QDyHmZ@N|r*C=gM`<<&)(Df=1U#O6s|x~sXL zLB*84413=}5K+eE)kT*n`x%>NTv@+&PJ*97#gx4a?sFIw1tQA0yt?QzWj~`{;ce@C z=j!QaP%&jM!`@*7M3ixPb%d3knQ}#19y|QB6#;D=pj3_Fm>}A-y4h0c(nX;cT z@$SC0&s^0RR7}~+;4Vi|Q9%S{h(sXUIzDGii!#%=rUzLBeqIH zY`&dC{0u6l>}Bw5mZ+#8f-Y0`Gp-$;AA4+hKR<(tDSH__F(xW1h@i`q{fsMT_r~VT zp5$jxF=a1s!QZ||MFkObnX;d;zf=CWn7&Q? z3@WDVW$>5mQBgqzU8d}3JiWU@T&*2-{0u6l>}A;d=?4*XnX;d;GbuK%evt}(1{G8G zGPr+#R8$Z_mnr)hJ^pGEmwoQteg+j&_A>0<@q-AuOxe$9(YbwGp7BwB1{G8GGPoOm zR8$Z_mnr)hq25Vx3Dx$5-*v$Azy46;t-=H77;;89@YHrtD`Fz4}<{kvn7j3@WDV)oV_?_A`PAx=h*6 z_)nYrQl~Ag;b%}WWv^aya<`umM9^i*en#|{F{v379`iG(n6g)|If2~I2qNe*Wj|x@ z#OTzbzdqq-P%&k%UUPc7pAkgRWy*fWlXK6lpINW7pFzcxy?V`g>wZQML6<4}8SgLn zWPN;<-hKuZQ}*gL-(~n2K?Gf<>}TwGd+hopQwI7OR7}~c*L;uSX9N*+nX;d;uz$t% zXIl>QGpLxdSFid0+Rq3g=rUzLqw0v!>k^WO`x#VB*{j!l%k5_b5p3?J<&C*ZUsc&j=#uGG#yGgZFaAhF_<`_Yx|m?A4nvw}R{#<$dGjX9N*+ znX;d8@!o;4-#<6l&!A$;UcKfobbdwk7rXRevY$c4l)ZY*-|_s6Ac8Ja z_A`De^L^~OMP2<2DyHn!`@y>UlDkmq-(wX-&}GVgMq>5Madk7a@iVBHvX}Aaq2@BR z;o845f(W`y+0R&dx^P^E91Z;pDyHmZRBF>!PTk=>KjDv65J8tI`x)O~t{k`V(nEd* z6;t-=trF8&4!7}sW8!B75puX%dM&j=#uGG#xbS=ndfN_T$D z&!A$;UcKh`qkcvZL6<4}8QIP~ANSK;YyI!rshF}?ulZf7pAkgRWy*d=rW?cK#(q{~ zZTP-R#gx5z?f30L1YM@=XQX{L2xm|+WiNxD6QZJK?i(6cCbiM}FtPqpR!OPr{o28E znX*^!TfMW%MAQ}$fHweWV*ndv=i;AfDa;w1cx zw$<9ijr!sC)NnsYn6l?uJ~LW6EcE^|>SvIk;w1cxgY)9zUR+<^&mdvSp6lX+Ii=df z*Z$5RLB&b<8JlB^$Cd8;Uq6F{DSNK`C3DLQ@!nn*em_W1aT0z;#%z~k7e#mUGf0@S z=W0+duOyyK%OF9;N%$F+E6$Hy@Rj~njf5$Cu0zxAl*j)&{qKH|pyDL_jI$f>jy-(e zbACTan6l^Eks-e{8<>_sf{K&yGkVrPw07hf{Y@$fQ}$d9`W2Kbz0xvBP;nA|MtJ>s zt18@&5D8QET-^>7mQdxi3=&kFgr5;!f8MI{Gf0@S=NePEm>gW2cFjppaT0z;c>Q^+ z%FiHS%APAzl@cHb`58B&awEKO?;UyjA6A zkT7M>Wqz0JuR#)2oP?hdUVq-I3f~h$Buv?JnO{!(86>DU2|pve{=8M?XOJ*u&vju? z897xb?cPp;ij(j&!t2jlRelBuQ}$eE_Lh;0;a|A<{UAZbN%$Gz_2;ds+TpPxValGX z^5!zK^u3q=&LBa>N%$Gz_2;dsST7@rgeiNjx{sBSxzBpfo%sDALB&b<8R7Nkttvl* zgeiNjUlU48uGVSa+>xN-B>ar<`tw#*T(}=3OxbfiRH&5fY4XzF{UAZbN%$Gz_2;cB zKZArRd#)SL#>iiZ6aLO1LB&b<8R7Nkttvl*geiM2b54tYJxEY-5`IQ_{dud(&mdvS zo@;)uqVh$Kv~O!kP;nA|MtJ>stIE$HValE>Ptn5i-I8&Cj}-|jPQuR!uRm{9`57ck z*>ja%UO>Kd#RUnU4}DAn6l@3WLXZ`|5n->BtgYV_!;5#7k+mc&LCmRo@-IX zXi0h_?OsBHij(j&!s{>m?lPP~!jwJNk&M|T(+6qyL=se-gr5;!f8lqR;S3U{?79A| zolP1ZOuM&}pyDL_jP0)uiCgn|XFr34DSNJ;D|kEI{*jhJf{K&yGn&kJE^hC+?0yCb zQ}$f99m^^zN7`#G2`Wy)&j_#a@H^P>SdlPg&t*R8`Rkkn6(`|mOz_rtl@0ncXTBrJ zG9f|FQB(F@&s|QI+g?qZyCkSM2|r_ix5lIYr$2L&FlEp6Md7}(cUxKp2`Wy)RM z@r8eX<|JXtp6kmNePz()vzpkfl5F=iReP%#P3*dJp~5~&tf$6K%QZ}o^7B&e8# zW*j49&IyGvCy7*x>w@pD@l`s+3=&jKLNmI_m~&iV%t<2E;@Z-xukTqLGe}S|3C$QJ z?XO*7%t<2E;%f9{U*G-sm_dSyNod9$(*Bkd#+)QlEv`;~^z~ow6EjFqF$vA6Ank8; zVa!P))#BRS_w&E6jn@(qR7^rMW=i{8yk|D%B#~-y?c1-P-#9B~kf34`nsKkRzutv0 zCy7*x>-T&5`RcdC3=&jKLNnfy_V@I>Y|Kd_)#92rqn|&jIA)NbViKA$T*jPVpOTF^ zNu*j_Yo_({Q>(=c5>!k=Go)9WBmJQE=Oj`suIp~^=j*JE_lYE^n1p6XuQo^eLCqkM zYH`)+)X!f!GiH#WViKAmz1ke<2lYOYM5@JgWW9cV*6^4?f{ICKhV*K4q#x7_5~&u~ z;a~OjQ!bAgB&e8#W=O9#NBTj{AdzZuH67R2pVv5Mkf34`njyW~Z0QFzgG8#uRqMpQ z{;irZg9H_m&MwKV1=k!o>`-QLHyuMjgxP%#P3kY25c^n!k= zGo)8*BK@FdkVv(-cCFXP&p9e)kf34`njyVfk@SO_K_b=Sdinj{e(o7Dg9H_m&cl>Z1QnCe4C&R1q#xArAc<6qD~-Z*JV=6yNodA&X@6~IXXC-SZQA+c zPRQ<~QZ24FquTi)Q{(*=2`VO`8IMW(`|+D>JV+wd;_{!i^JkTdzcY}aViKCsRoY+o z!g!EGs>Ss~aeLpUOUxia#UwQ2ZfSq-7RG}lQZ26ZgrlAh5>!k=GnPsF+pjPlB#~-y zrDrfTg9H_m(2RX#JUFE=9wd=!aiu3fHG>2dlhBOr(*DBTW%w!k= zGp5QM;1`n1p7$i18qaREsM;x3Bv_f{ICK#s+DB|169L zNu*j_>CFO~L4t}&XvRe{9=x|O9wd=!ah-B!7r*t$c&tcJF$vA+DebRIVLV78)#B>b zva7#;Q*47IsF;LijF$HIeqlUFBGuyRwY95%aC*!jLB%9A<9KO*PZq|5BvLJ|hBsgB zn>CLaB&e8#W;`zKZ*5^bNFvqZx@+UrzQM+L-6cWABsAkOX@5W0$>tzQq*`1>^}G2l zH^&STR7^rMmPq@%r7#{Ok!o>OZPm?JsvI*&P%#P37%JnzB`ve@Ac<6q>#*kC{B6@> zUrU0DNoa=jYICF?)c%}As>L<*ux`G|i7|r&6_e16Yo+~dEzCiZNVT~Bx#Vg;a7nx` zAwk6?G(&o|Inod6JsgQti|gx)ulDVF#tafvOhPkOOZ&UFFdih4YH@8}(ABRzFlLaT zViKAmz1ke<2X#M4q*`2OSLx~pEsOI}B&e8#W=O9#TlzuGAdzZu)oRtnx0n($NKi2e z&G<#y-=lFnh|fy2xQ5=;+5db)%pgI?c_&yj~OJWn1p6D zJ?FpUK@zDJ*BkRX`VqZi1_>%Ap&18a4w6Kw#Z`CxRess%Ap&7-}{>B%^gCtTdu1z0b z;Rj8M86>Efgl0&uRwVu4oN&%bq*`2?4{hro{5ockpkfl5(M#H2$HI7!M5@L0)-`SY zsr7mkjuirlQc0v*T(?wc z=WE;NlhBMWdYv_AzoKkSDv4B!>+nVG{fL`m1_>%Ap&1L;-atFWirkFv3ib-gO z^lEdYAJhyIsTNn$uiJZfP|P4f#UwOCdbK&y59&P}iBya0Ou0|o_G;I{u_8gmBs7Dg zI})iD*J<6``z5_%1_>%Ap&8Pv&5?dk_k%>L#nq*1dtdKwF@ppZlh6$5)n-dSs2LX^_)1^=R?Hwl#UwOCdbK9f4{8R9 zREz7iDp&d!SH%nxR7^rMo|Ez5@WObIM5@JAb7os#ZqN9=B0m{fg9H_m&Efgl0&uRwVtPW{^m=xb|6i zh2OY5W{{v_5}F~sT9N!Ns@FsksTS9+cU|EtHHg!k=Go)85l729|w&SxBEv^H4 zU*Tsw5HmO9{x7XcO4_;N+4-!;NLNh**_BXUJ9wd=! zadjE@hU?l){*sv!k=Gup}TG4d;mW{^m= zxYA#^(hL$*OhPjnHCg_0xVsGdK_b=ST6*uhuG+MCtVmEX3C)-!zsKBK7!Q(2wYc_Z z@xHsEf6O33#UwN%%+JfLd)SY`BvLJ|^f&eNSdpM&5}Fa_=fiA6$RLqwaizcErx_%u zn1p6@koNauVLV78)#AE&)<5~&u~es6#5PVFAAB_ybr zgl2^HC#`CBI94Q5Ev`jV{^JgLI9?M;P%#P3xLw-cqlNJxiBya0(0ZS^8$Qgg`SPYh z5L8S;GuBA^t6F$QkwmJ+^=_|E+}l65D_l!RP%#P3xJBCEm1ku0gCtTdt`!|Var3Ii z3=&jKLNlaSnbNKi2e&3Ibc-}~QW<3SRs7T5Al|8Wz0 zwk>3kpkfl5@pox|vkT)v5~&u~wKsn3dOmeUA%g@Jlh6$5)#gY)SR~)wQY2C>uJIRs zEfgl6n3_eyKzel%o|NVT}?Z~M?aaMR_5{UAZbBs62Dw7(Y%<3SRs7S~t3 zK5%F37c)puF$v9(UTt=mZ3z28BGuxW@y2`Zz9nr6`$2+=Noa=jYO}*^L&zYJYH^*h z&%5rm$72QwDkh;BeH$-tbZcQeNFvqZs(;>6_u?}#g9H_m(2Qa7d(4Q!c#uS@#r5-~ zw_WR%F@ppZlh6$5)tZFWXW>|pNVT|D{r0A7TtA+35>!k=Gs66QSbY{UNTga^BX3^p zHqD3`B&e8#W`y<^?k+lFzqCZQSO_Zaz=MKegGT3i>j zZs3PZi5VoQn1p78-($jTL)Z@zsTS8oV;cCyzs3v_R7^rM!tXI*wjpGYNVT{wUDm+= z*sQp4tVmEX3C#$<$AsC2kU=8V;yUrDhJM_bm_dSyNoYp+JtoXHgbWg?7T0AX8v4nv z#S9WuOhPll?=fMvA!Lw9wYWBa)6n1cWy~N!#UwN%{2mi#8$t$&REujx>qfqKOUxia z#UwN%{2mj>gCtTdu1&8s^4DyR86>Efgl2^K`7qlcyD^wVs>StLoyLC8Ph$oNDkh;B zVSYZ$HiQfksTSAuV;cJxX2uK>R7^rM!u))gZ3r18QZ23p8yfrPu8$ccsF;Lig!%a} z+YmBHq*`3xHE80WIU#0{pkfl55$5N^Y(vN(k!o?>enS)g@v3+&Awk6?G$YKzvh1e7%`jzf!6c2`VO`8DV}t%r=DmAdzZubzjlMA9i-kAVI|>G$YK+zaR{2}i)`)@y(2r4F_8DV}t%r=A!5~&u~ z`%4@9n{JO8B&e8#W`yEfgl2^K`7l2bGDxIaT(ze*^7CrP3=&jKLNmhre3)$r86;9Iu4*SW@>A-@ z3=&jKLNmhrd{})JGDxIaTy>T-^yPibAVI|>G$YKaR>$JTa`ZiNy1_>%Ap&4Plc36EDGDxIaTvg{Z@NK_}86>Efgl2^K z`LOydWROU;xCUL{z&C6ZuO%d?n1p78`T4N=EM$;KwYYkm-N0WtF=mjUViKAW=I6ue zvyed|)#4iR*9Ly;A2EXj6_e16Fh4J|?wUa&)#7@kN(298m)J*a(yP zBvLJ|Gz!!4APFiap&6X*+imZ)Zp1b6cR1yRjf;Pvi=?J0GiZaGc*^sIV?~0BNoWRV`$(i(T)*z}wOiOPW{{v_5}Lu;J`$-G zSJ5NixPvCd3=&jKLNhqqM0dek;IrgqFALB%9AgR^}kQZ24B&u??H=frC}2`VO`8Jz7Sk!o>0w{4s2cy7!f zLB%9ALw@B<^MfQ(Ew1_BY;&tt#kb>=pkfl5!P!0%sTS9$aogNoePad*Dkh;Bob4l# zYH_{#-Oujr3NeEO6_d~m&i0W=wYb`p{n^cWd}g8lAVI|>G=sB!BvLJ|>sD-aCtMOU zNKi2e&ERYwiByZL%8(!3(!azE5>!k=GdSBvBGux0d)p6g+KOii$BG0Mlh6##_K`@n zxJI4#y=(q*%pgI;#OM;3?Xa;BdNTga^9bW#*_3RTfNKi2e&ERYwiByYg>5O&m^*3S$2`VO`8Jz7S zk!o=r{N7r(yiU9(lAvM|n!(vV5~&u~!qe8eNAHdqB&e8#W^lHTM5@JAxy)KuX4lvc zlAvM|njyVfnja*QYH_7e*bei9R7^rM!uy=U+X};&vwW%Ye!ut5)N5a=#no@W@_yHb zXBDoAB&e8#W`y@Sg|`)k3=*jp*ZfB1{j~dI1_>%Ap&8+QPT_5ZA%jG!#kHt!dB1U6 z%pgI%Ap&8-*zTs_!A%jG!#dXDDd;1US#|#owOhPll`+dXP z3PT2oREz8Pc6gG8#uRqmd>{riJs1_>%Ap&1X!{9t%n zVaOnnYH@9ywYP6_V9X#v#UwN%yx%vxtuSPeNVT|LT(q|@ek$u%N|ho(#UwOC-kLop zysa=~kVv(-KApd}cW1;55>!k=Gs63Q!`liaqZEl$i|d*v_x9&~cE*4E!9-9o3C#%a z_YH3=3>hR+Ev}j)_V&+Q8#72yF$v8G@AnOFD-0PVQZ25-iud+c9}+W2P%#P32=Dg| zZz~KLBvLJ|gZJFqpR(li|Mr84pkfl55#H|`-c}egNTga^{@K0!l+iJR1QnCejPQQn z@V3H`K_b=SI;izt{_cxn1_>%Ap&8Pv%?@uX3>hR+Ev{QPSM(2`7&AyvF$v8G@AnOF zD-0PVQZ23tw^sCD9uYH0P%#P32=Die^MfQ(Ev``qRrIgbju|AVn1p78_xr~AK@zDJ z*L}}a@O6t~1_>%Ap&8-*zTxfl;aHJKwYYw5S;1f5F=mjUViKAmy;^#o42e{W>zOU( z{Z04B3=&jKLNmhqeZ$-9!+wxRwYWx1FYkw}i5VoQn1p78_xpyo*M|%esTSAzE6e*f zC&z0E2`VO`8R7lD;qCPygG8#u_4(h*`=R4w1_>%Ap&8Pv6-hs+86;9IuFVz7`vZQ9 z86>Efgl2^I`-ZpIhy5UtYH=O?TRFdbr`Si4pkfl55&n8aczb=wAdzZurBRrU2T4#d z3C-Z@&pMr6aa)^Rtk>{Vi|da&UvX=m&Hi2fJ|k9`QZWh5;Ob8jsTSA$D_?QLs$Np) zKS)q93C-Z@PZFsX*Yx7q?(M!Yg9H_m&Q54>7T06`RX43c%pgI!k=Gr0PbM5@L0^s2e8RkxTyf{ICK23LQQNVT}$nf03M*Cl3am*k=#UwO?t3OGkT3og7TIinL z95mq=!|sV0B&e8#W^nZeSC%pgIO9-*@dpzgqT5sib-e&*Nc)!wYXYdyTDaHJ7$oeViKCc)t@9% zEv||0&UZt0j~OJWn1p6<^(To`i>t+c^IiY!k=Go)8b>qSYVT3j`o&U2%l ziWwxRn1p6<^(To`i|fq(uepU&Vg?B+CZQQz{YfI#;;KD)uA4qRW{{v_5}Lu)pCnQ( zu5*^W>h^juW{{v_5}Lu)pCnQ(t_o#eb!}F~3=&jKLNmDflSHb;b$#(1*S2c>?vkKl z5}Lu)pCnQ(t|R_E+qG{SGe}S|3C-Z@PZFsX*H=f)c1>o+3=&jKLNmDflSHb;_0IfP zT!($*b(aJclh6$5)zW%V5~&u~&x2oa+Xlo85>!k=Gr0PbM5@Kr^U7D;x>YfQ1QnCe z46gnpk!o?JQP>XaMX8vCW`y5k!rf&UbH4r8A?_dd+^E;SREulMc|+Xwe`Nojf4?Xd zlhBN?UOU`fh71y^7FW@fA@0ETHx;hCB&e8#W`yN0M%wcZ)kuie=6_e16 zuwFadU4{%2sTNoBGPk&ceas+1#UwN%tk({Ammz~hs>L;6$t|vOtC&H8ib-fjSg$Ru zN;62LT3oHB4tGCZ5;I6pF$v8G>$St(W!MiAsTNo7fw#Kh7sm_|R7^rM!t=Y~?ouKK zlSs9=ikpsb@3x2;B&e8#W`yT=q=k%CCf{ICKMtFWV++BtY5~&u~wDF_e zb1UMtodgw=&{_jn#2qeR7^rM z!t=Y~?lSBLiBya0r$wXO>ebg5_Jaf!lhBOt{BF3r3>hR+Ew0Tck8-od#tafvOhPll z^Sj~hGGvfQwYVCN9qFnT#|#owOhPll^Sj~hGGvfQwYa|haD=OPaLgb<#UwN%Jii<6 zE<*;1REujtxe>1V_Uj7gg9H_m(2Vf>uKdcP86;9IuCGqK)m^qRW{{v_5}Fa7-wpSp zVLwQuT3n0U4tEVU#S9WuOhPll^SfcTA!Lw9wYa{%{T4U9OgtYXsF;Ligy(nVR~F46 zk!o>0v1pk4;i#BFf{ICKhV*Lb{h}mNEv|zr4Rc%D#S9WuOhPll^Sjay>VA+&wYV1b z8tQ&|IA)NbViKAWp5G0#4dHx{NVT{|ZXDu1_$_9Tpkfl55uV=-vkf7GM5@Kr=awPv zmrLU{kpvZ!(2Vf>ZkTNd86;9It_g04yJK$5AVI|>G$TB}8)h3q28mRQt5S_2?#4Q? zk0L?EBs3$;&xhHDkU=8V;!2}19S@SAViKAW#)Dz?S;#o}w9anK$M@)UDb?ayIH9xK zz2f-)_JfI_ViKAW=I6uevyed|)#BRqq%Lk*lbAt*ib-fj_6 zZZU%d6_e16Fh3twpN0J(k!o=reB9M;%($3Af{ICKMwp)utIt9PiByYg#E@=o#j`Pk z1QnCej4(eRR-c6o5~&u~VcWaAtCq$L5>!k=Gs67*Lxu4miByZL-<>_(r7L3w2`VO` z8DV}ttUe3-K_b=SI{M_^uJKnfg9H_m(2OuYA6B1*3=*jpSC=(?+>*61g9H_m(2THN zJFHieh`}UMEv~~y_H|W1jTt1Un1p78_1a}e(%Su%umP^uV=;pS6_e16uwFZ?R|^>=QZ25Y3kJGPBVq;#Dkh;BVZC-(eHJoE zq*`1XmR{>hUlB7%P%#P32a&nRBGuxmHffOCR4-s_R7^rM!g}qn`YdFSNVT{=Yj>Ti`+CeELB%9ABaH6C>a&nRBGux$ zs`Yj5!Lc!e1QnCej4-+jtIs5(6p2)e>y^^ixuY+S86>Efgl2^G+F|us$RLqwaoyBm zkh{EY%pgI;C}faGwYd5WyVkw<``v~9oCFn<(2THNJFGqn86;9Iu8y4t zy6MYe1_>%Ap&4Plc36EDGDxIaT-y&A;4XMJW{{v_5}Fa#YlqcmA%jG!#npatKezP0 zm_dSyNoYn`uPyzcW{^m=xb`a7*ZpTy%pgI$St`vyed|)#9r5TrYRku$V!Dib-fjSg#$PMhY1uQZ24F`}TCz#>5N~R7^rM z!g}rSG*ZYQk!o?R9@^c#HZ^9Dpkfl55!P#mr;$PiiByYg?*84}yxB2>1QnCejIdri zJdG4GNTga^e_7VmoxVC|kf34`ni1A(ho_N328mRQYr>mdT>T31dPRbYNoYn`uN|I7 z3K=9)Ev_zqbatmVj2R@Tn1p78_1fWSq>w=()#7?#Kxem4kC;J%ib-fjSg#$PMhY1u zQZ23-fA8$dPKy~NsF;Ligwb7i8YyIuNVT}qC@hT!BSFO^G$V`$!k=GdSBvBGuw59&@i-{9?=?LB%9AgR^}kQZ26CPnsZOgP1{rib-e&XZuK`T3qM- zFu^_WW6U5y#UwO?vwb8|Ew1ZlPjq+h{zTz>MS_Y+Xa;BdNTga^7mdBo4cseckf34` zn!(vV5~&tf|IU-#o)u#T2`VO`8Jz7Sk!o>W(BPl${9R%O2`VO`8Jz7Sk!o?>Rr-GS z*rs^SNl-Bf&5&O?)BGTbREw+D^Y^<)--{U}sF;LiaJG*`s>LaP*#oZ8Eir=x6_d~m&i0W=wYc6nb+W5{Vay;w#UwO?vwb8|Ev|pvI@w)b zGiH#WViKCc**+4f7S}NkO?I6&W&Mi09E%pgIOB6ko(=3 zREz8O<>OuV`Z0q96_d~m&i0W=wYd8C8}9~R88b*wF$vA! zY#)hKi|hVl$GdaJ#S9WuOhPj_+eaeR;@W@T@y@>yGe}S|3C#%O!8kuiBGuwbqp&m{ zj06>v(2OuYAMP&0nDdWER=FulUearLszb(yt6bGGFBh)uB&e8#W`y~9X;qp*BGuyR zU2C=b>iC#Jf{ICK2A>8bk!o=b7`NKp)-Gm{pkfl55$5N^-DNmdBvLJ|8*6;wrjCjk zB&e8#W`z0qaCaFpNTga^$1VQCZGJRnkf34`ni1yb!`)@bAdzZu-8B45H()``AVI|> zG$YKL4t}&XhxWy4|kU#gG8#uHT>|kuI1-3g9H_m(2UTU z!rf)aAdzZuP2axOt^71*kf34`nh}0o33rzgF_=WE#Wm#Zb*|2PF@ppZlh6!44M-x@ z;+i||D>rO*%pgI$St(Wym0rYH>ZZ zalI>jQ_LVi#UwPNqs$M6yUUP4BGuwr(`$pPd_l}0LB%9ABdpgBcb6f9M5@L0+p-O= z)Dba*1QnCejIdri++BtY5~&u~ht)Q^6Mx9A`LZeq1QnCejIdr?er3@N5~&u~(VcRB%pgI< zBs3$e*Op&dG=oH{#Z~X64X#&>m_dSyNoWS21|*Scan(L&gL`Ysi-rE21QnCe4C&R< zUymS>YH`(kWxadut(ZZAib-fjSg#%KF2ngCk!o>u-*3I^^k~c=LB%9ABdpgBcb6f9 zM5@JA{o=3Osykx_2`VO`8Pcnz=LbooT3kQ07 zZ;2TssF;Li@M%C2sTSADreC@b?u{8FsF;Lig!S5Cwjt~XiByZL<+v~0vY9c11QnCe zjIdri%r=A!5~&u~wjWlz)*r_V5>!k=Go)8be{X_Bs>StkkJawG?qtsTS8;^H;eV9byIvDkh;BVZFBe%A)&0 zBGuwL^}$uH+Ju-vf{ICKMp&;MW*fq>B9UrwrBT=p&ks^D3C-Z!LihRZP`^*{9PKAk zEv`Yk9p*<2%l=(vb*06I^=e_OsF;Lig!%cf`t1KF5-qMb>K^7>KNmAdP%#P32=nt{ z^;yUuk!o?h)!{I|{fn4Ef{ICK2HzG+BGuwr`siW4QiWFweJu$pCZQQ&em<-|3;RJL z)#7^OkHdW1qhkgMDkh;BVSYZWJ_{KnQZ24`+En*z&xjc$sF;Lig!%cf`YdFSNVT}G znpfR_+B#;Cpkfl55$5N^>a&nRBGuw*b#x6s=Zcs?f{ICKMwo4n<3SRs7FWA_Yxv^J zV+IK-CZQQ&y>=WAl1R0<&MRHh-`6T;kf34`ni1A(ht+3ts0NcrwYWBSsOf(wiWwxR zn1p6bm-ZJ{pM?w(sTSACuh#UNYsL%`R7^rM!g}qn`YdFSNVT{+>{HA4Dit$GP%#P3 z2a&nRBGuw5)2fyqx-4ExNKi2e%?RtY!|Jn;K_b=S+Ix5{-}9lEL4t}&XvRa* z{=(|BkU=8V;@bXDE&pKOm_dSyNoYn`uN_vOg$xp@7T26vwfqxBF@ppZlhBN?UOTKl z3mGI*Ev{8FYxyI}#S9WuOhPlldhM|KOfpK5NVT{IJW$I&`QhxswVebNlhBN?UOTKl z3mGI*Ev_R6*77T+#S9WuOhPlldhM|KEM$;KwYUyHrIv5lKW31iViKAW)@z5=XCZ?` zs>M}fTTOpNic$KbR7^rM!g}qn`YdFSNVT}C zpIOrvSB@DZsF;LiNUxUOFG?cS;<{~B4S&flF@ppZlhBN?UOTKl3;RJL)#AE;Kn*|e zmsbkkT@qAGLNlaSOXEQjsTS9m3N`$??JGe3Fkb9&84 zwYa`Lx0$c9DEs&P`$egkgl2HIk3_1))#Tb{e%;S8g9H_m&G=sB!BvLJ|<$JgA-6qBi5>!k=GdSBvBGux0e@mP%#P3;A|g>REuj-^OpXodtwF&Dkh;Bob4l#YH@XZs-+(~ zBxaDHViKCc**+4f7S|IMiv7(UV+IK-CZQRe?IV$DaeZ=GvH!!z3=&jKLNhqqMG=sB!BvLJ|VeiR)tdG}35>!k=GZtaCk3_1))oV+!KYmusAVI|> zG=sB!BvLJ|6Lvk$v$5DW zIUr_`pkfl5!P!0%sTS8i=NJ2)Yo9IjQ6#9Cgl2HIk3_1)HSxA$|K{^Cg9H_m&eykf34`n!(vV5~&u~%bQ#Jjy+=r2`VO`8Jz7Sk!o?>b5~2h@`9K_ zf{ICK250+7q*`31|JKrPI4x$7pkfl5!P!0%sTNn|`7M0e#xa8g6_d~m&i0W=wYYY@ zxP|ZEBxaDHViKCc**+4f7T12?HTQMSju|AVn1p6%Ap&6X*Bav!xU39hV$B!|C1QnCe4C&R<{2+-`i>uq&&3yGEw(Q(e6t$U3w;y`Dkh;Bd>W8Ms>QYGfUf?a^J4}HDkh;BVSYZ`U55Q2k!o>mF7E1I zy*Xx(pkfl55$5N^-DSuik!o>m8Q;}^_;Ac1LB%9AgHHpJNVT|@ZtUt0e=}x~pkfl5 z5$5N^-DTJh5~&u~k7r-)AN?|Bkf34`n!%?5Nu*j_qn^ClPx&!skf34`ni1ybrB&&E zkVv(-23GCnhyE5bNKi2e&EV63BvLJ|TZeV?fB7|Lkf34`ni1A(hr3HT9fL`vT3r3V z>E^H495YBzF$v8G>$T-q7R?}$YH{s%Zg)THvzS4Gib-fjEopz@?lSBLiBya0^2fUS z=jO%?5>!k=Gx#(hiByYg!k=Gs1f9aCaH@gG8#ub!1Twe`ep9L4t}& zXhvAC9quke28mRQ>$pBW{PCy93=&jKLNoX@Ac<6q>#%V>e3yM=1_>%Ap&4PlcDTC? z`#~br;`(x058vmrtY67LKS;$SG=onAl1R0rBu9)6mO86>Efgl2^G+Trdp><5Wdi>qnf9{!KY zF@ppZlhBN?UOU`fh71y^7T1|;y88_qrxxxRNKi2e&EV63BvLJ|Zg+O~6Bow}5>!k= zGs1f9aCaH@gG8#ub;fbs{a>Dn86>Efgl6z*KoY4I*HdqI^M_2186>Efgl2^G+VU%l z?gxofi)&u{ZobjIF@ppZlh6!44M-x@;+pxh+%rsw86>Efgl2^G+F^booDUMI7T5eS zSNpcpV+IK-CZQQ&y|(*>K={pg=!1_>%Ap&4Plc9?Al=YvG5#Z|dUS3j_Nyq1ulViKAW z)@z5^hLAxb)#55!UiPCnW{{v_5}LuM0ZF7R-BGuwbqp%&GAEaUunsJ}BzY2xbpC`Of$2Yz34!wq_T3l;B zt>a&QJo|U~E1n>zn1p6LAnot?!g^5>sTNn4L+bjurS2^BA0()lgl4pn@!*icc#uS@ z#WnxBy8gXpF@ppZlhBN}WjuIiVLV78)#5tj`?`M0n3zF=ib-h3Jei-bRah@dBGuwr zdBf5E@I^6$1QnCejNhgG%_xiqNu*j_i>v+3Ke;((kf34`nsI`x7oA#IFG?cS;yPgd z-~5(}V+-e;1QnCejE!^mZ}M4TJV+wd;(D-eJ%7M~F@ppZlhBM^@qSSfsTS8?{(6j` zc|gn{LB%9Aqdwj*N+Q+b`uW3S{HMFe3=&jKLNiX3_9v}sj$C#JlSs9=N?(7hueLUx za}rccLNi86`@6U>9wd=!an<@uecx?X%pgIrp){BxzwYcU^sPBuej~OJW zn1p78_9v}Mj}?hji)-;7$N9@oj2R@Tn1p6LDedp`!g!EGs>StLo8$cYb@94Of{ICK z#&l_ahZok1l1R0!k=GeZ0OYHl_jB#~-yJ@N13{I3mS1_>%Ap&7Tx zdeIrDW$Q&rq*`3-9zD)4ST&|_Eg?b0Bs62Jj0ayTtQRGbYH^)3;yB-GRLmej#UwN% zv_I(w_1=d>s>Sv68OQk+C&dgBR7^rMq*t3G{a|(vhtEp1xGq{>-#6NLd*N7-pkfl5 zu~yn&|H62XM5@L0Tc7&A$G>6*2`VO`8KM12tJ3`-k!o=@T6e79&?{z;pkfl5A-&pc z=?67~M5@JgZqs9Z+cRPY2`VO`8PcoGmVQt(NTga^Wu_eC4?HSnkf34`njyW~Y-v@R zK_b=S8t`2`|Iua{ zzxm^ijTt1Un1p6Xuht~oU54=oiBya0!1YJ_AJ2^$B&e8#W=OAAB>kXfkVv(-el9-R zPaPaHNKi2e&5&NLNcus|AdzZuUHWES|ISM>g9H_m(2UUj!rf&!RwPm_uJbOd>z^te zuU90fn1p78)t`qH){BxzwYZv;t?Q2{ju|AVn1p6XuT~`epk8-Lq*`3hE~(?+o*pwu zP%#P32<=b$LCqkMYH@X+S;trYEoP9QViKAWR)02VnynWlk!o?JQCM0p8VM>Up&8Pv z70oY<2Pcf*&EK&12<<0QEv}|7?dHGjnEiXHQY5IDgl2^H7w#^@_liWS#kJ(u-Tamp zVg?B+CZQP}rTtw~7!Q(2wYX|uvb*1X_mPEukOUQz(2Nbz{(2S0gCtTduA%Sj?msvy zW{{v_5}Fa(U%0yr$BIO%#dZ2+W&Op2V+IK-CZQQ}AKE0`U4{%2sTNngZDsxHM`8vE zDkh;B)ujE+D2xY5q*`1zOx?r(by3V9LB%9AgQGhVsTNncR(tw$K8P74sF;Li93|~9 zJdG5N6^T@fYv69>{JM8z1_>%Ap&5Hg`;%W;LdIYcsTS8|Gt2qCUyT_gsF;LiaCAo^ z)#B=SNqOJ=ftW#pib-h34buLuEQ|+9q*`1fzc246_lg-LsF;Li$bIOXaCaGw6^T@f z>xh9Be4i6y1_>%Ap&6n5g}cj;K_b=S`rEn+{?2dX^@;=)lhBN3r2V~H7!Q(2wYYqv zivFM}F@ppZlhBN5(*Eie#)BkMEv~ovR`mUv#S9WuOhPll=q}t{hGRt{)#9o=rlPO6 z<<`P=mjo4)(2UUjzAijJNFvqZYBs8(|9N7}AVI|>G$XXX-3#ME5~&u~eH|!k=Gs5UD++E7CDn%mI;;M3ZMSt^m!wbiX1QnCejLW3`-BK72l1R0Efgl2^H7w#@Y28mRQYx08f{@|lx1_>%A zp&4=?n*QDdiBya0xg*Q_yZ*SPa6U*-F$v9(UTwDYgSsCiQZ25|HVD9k{`QY!1_>%Ap&8PvH3_o~;hd95 zwYWxh-@|v@5HmD7v)AJhyIsTNn8 zdS(5xlVb)6Dkh;BGA~gSW*fqOkVv(-<~+Q+FVin(kf34`ni1MxxVsD)BvLJ|Sq*mg zU%nVKNKi2e%?Q88$geDVO(cG=rl%5~&u~0sEEr=RFoPNKi2e%?Q88NIy6yoO2SX7FVCq<$d*UV+IK-CZQRj z{e`>BkU=8V;yS)c1^?g?_ZQ9w2`VO`8R7RB`ISX8NTga^hs>zx}jNKi2e&EV*c zM5@KrtxZMWw|mSWLB%9ABecJ8cNvZqiByYgTgAQny@O%~2`VO`864e_NVT{+y}Fk_ zeqhWXLB%9AgQGhVsTS8cJ@@vPb&MG#sF;LiaCAo^)#AEfzkU3K(_;n+Dkh;B9Nm#f zwYUa8zK{QU|Cm97ib-fjn4gz^Fr4$jBvLJ|{f?{T=PZwHkOUQz(2UUj!rf)aAdzZu z9Wu3&|NQQlL4t}&XhxWy53>y+gG8#ub?i@-e3vt01_>%Ap&1rZnrg9H_m z(2Ov;+pjPlB#~-yjjq10e{cPLh3hT}Dkh;B9Nm#fwYYX)S;;TCCuWeKViKCc(H)6Y zi|er=mHf+1V+IK-CZQSfE9V^fU9?EfM=27i7T38ID)~)iV+IK-CZQRj{e`>BkU=8V z;uEfgl2GbMiByZL=a34%-%~Mz1QnCe436$dq*`3fHk9`@R>lkx zR7^rM!u-7aE~?*M5~&u~6CKL?;sawFBtgX_G$XXXaCaHnAc<6qYsQb|{4rO?3=&jK zLNnx7&La6;RL4;yQZ25rlgs%TPsR)qR7^rMIJzT|YH{t^xtwplYwSNrP%#P3;OLG- zs>L<8c{zXAWif*U6_e16FuJ>_Fdih4YH_7eSQ-yTf{ICKMmX2me}jwS(_l@@4o%OG zh5Dve?fvLhGkmC{JN$oe(KCH6ckle|K~=_9>E!Nt@_wzy96#Q*ynU)c^m^_dSNF!t zRHIT2$)(Kj#o88Ml{rNoxabo|2{mC5{sPdP&`}%vj zWc9`$_Ve%DJKG>C9ekkw^pR1j)OzLszw-L5Zm{ZLfAs2M22o}CCimGBb0;orDA z3$ps=cQ&}iH)VBx&wFj{>K~kbyAlm=zS=iyp4GRP>FysNnbmpXKeUup*yy2R^Ptz4fpZ4S)C{12s?a#;z&5u zZs2bI!9OPJC*_IPOIPvd_P;mFDBOhwBHp9y_)X;J#*y&UM7%rO zF@sx0SG?ESk>E8W{!$cNyvF2@6%`WUH=v2~Yt)VzBWo3|{t4^m^+}38+o>Teb&R5);XEPT+spPF9asSF!+_0*b7~gh& z7G2YeXS=uiS_JRzmQ|eV#$0x(e(p1?=DJqhvO2$2RNkHSn(NmkbMce%1Qilbj-2Pp zpKoQ5pzE9B`R?Vq7D464vJ2b`Te7|7CzZTaIpU!Oav!|2WAy=C{O0E~sF0|1^g_4% zVk?6LT_v|Dp4&%0pY490pM5UB3;C_0LgI?ybKLl{*3l(F*Z+2ONj&CXbyFKy8T>4| z_^r(E$Myva-EkLXt@E-03*ERa*>z>|i_2Vx8s`}8g9Kemzgy^P%(dD%Klj423th7b zJImnbl4yDD0$2U)jLz=|3A!e}JKqi2-6ERrH{bPt|3clvnoZ}qQBP%c{dZn>-`;VS zvF8=azUtbn%3RkM&v9+5W}nMzWqzxukU0F`vt9eP)>e_Ai`V>o2Dkmp{;#=(Q+Bo= z+(QzzC(m`$re}0Mg9KgYEP2&ce9w6Yw zzb7<$vaj!cd{*-}hde=rMCU*H`mgt~ewiRaSINI+P$99q@8^GCYwZUKy7ukY&u^S% z5#OKE+aEJ-v>us8-kf4j_KcB&G!&?XT_U|vuK9`@AC#aBE+N!r7uw`dkMc4Zid;5PJWPM9oA9Rgx z*eg>y-g=FHtH+=DCX%?|yK8)v4ps)giFC0Q)TF(E^ci;W9;@mzI}yk+oz4~;}58k)mz&2_xsNtYU~I1woa#h{?eH{ z+jAZh5=YkS=VuMi==@fZpzH9j`uZuCTLkxm+die^HGWGui{NLSGp?^cukoMR4-$u; z*w?>R)5_p}(8Vpx?>Q9`W8S&OFWcA3AVF8jdtQC`LRYDAdp)<8tXSxtsM0~}Q-6Qn z)o<6`IOinjsyAq%D|>l6gW%^LF?5k@ux@7={9F`wS7bMce%=YtA~0|ve2Zg-uG3=(ved+1X)_0WC>L50L6)t9)FM_3so=z8gs zrLOYB7C~jnz3;ke(=r!7DZl4bNbJ$#eRo5DD}w}Ghkf&bySJ7_4Cu1Vt$i{(2ZLvQ zsvyCuGgph#~t!;_N~nC`JwebaW{OJwU2ju zed6B!Is1m6Kk^%Q_T$-{PM)AbVr7R<+`Ot*`yfHrjPjqjBZ{nyGxmAcz4mw;JtpH=WBT<+pT3+fBzF2lV{i&V&=(sl{Zz-&$$Y)R?(QHmTKl~f(UX%n~QwFy47q+%WEL>SJZsXOy!N#mb zu?6S1iVBIM`rUk&n=`s(g07N}E)^10TXpl5Dq9&O=;E2pZxzp4-St=bWy5!N26=8t zOs;yBf8)uF&S#LItKX#^eDw_$!EfI`mt5@!F3HX__b;D8g~ZnvU+vrVw7w-I=-R%Z zt6zDbMNm1rN>@K{IaM6Fg`e2Xd8p7XQl;xWu;P$4n&rq2H78>|cxbg?z( zGa9Y>)J>~9SKISV!@qO`7QC$WBj>Jh-Irx`o_MDEW_R0+=hgMivhQ7!JF>dwE9>2J zZ@p+-8Gic5I=69fro_KsAFj1e58B`+o|4h|41N|fYM-;gy|u;4;Ab(T#lh>{3EO8G zTQzXpYIj?^Y!7d&@r9c@Dy!EY^}f5K{Hq4>VYQ9!#2;Q#rA>p4u4r~va|`qPL50NB z<2SllBQiQq@OnxyWr^8jIE+VV))@}UCYm{Gf0B2>D$-3m7iJ!l_77hb9LU! zT>PZ`eo!GXcidNQ*la6<1YPHzv)&DvY7sn&OZMF8PC5V2oDUN9UfSS#)v(S7&mdhT ze-rs_=eM%@#b3EqcUs?FDkOg0Wc#X+tyuR^E_t2NmX*($Dyw-iRGOPEju+B|7%WCI`?7PMt zeM@#sRyO_8eQAklK%7jD^1>*(^D!D|Uyb3TI#iQ^W3;Wj^NecMUU#jAEc zgDvNwjq6?MoBm9zC9$U023Pq4Ypd95>H2Ni23P6`i{Sa-Ir#O9HE!S_>*!J;QSvz_ zK^J?5{IQ}!qT7$_+|v(P-zySymE7a}@yIGSWl46GdH=&z?tn7c@!_{8zg1L7^scqq zeRaHbbV<;~-Y%apeUH`dqGPkIdTahFSEEB#^ON!f6%waDxXM+XU|mH?(8VK?&tO~I z_QPt|`r|*-YDv7@W3@Yd7i+8dU80LeB)?TheD{tU@WM>J`cy8n)|J^cyZZ2x@&pwU zyY0Q!jkqSGOD5>z)hZEj3$tB)c< z7mrAOtEiAD^ZYh9dyaLzB0(3ATRwwl@QEHjy7o_IXLHy7TiiLFtouYNBzSk8&)_QP zv4v;U!kCk*rt<_95?qsBGC|if6D#;Drr&L}K`JCxZQ1Jje{jD+{NAXXKj-7@H@#g~ z?de^`JJq$zz}@|_I%5rjuGyRS^g~Y1TqP4!Nc^iuIe+JXyNnDHbd|gxR7m{PO5Vva zah#Dsf-WAz{Q2Oq;ufyhrMxfmZ|j$BDkRD*DerIG-TFO|1YHl-t>C--)B5F(&y4X| zvMyg#_P;$h#MpBxB&PcPeWP2f-+f5XHSF`s{;7EuL8ZflO8(*#v){$|N%^Bog~a+{ zd;3}cv3^w}K^Ko(K7$I0Q=h8nKm3<7#N#!N@arG5GDy(1^wjG9yQbE$ihpS#TnFP{L_||Fe?#Ga-zpOEuOsZ3!L6bz{;h)@ z33r9_7v7V7&KyzGzkWe>$5Qd>TK;dRW+MppUHJ_5^t=z^_c%{bAyIM$3A#27INYzT zW{sn$kl;S$w~9}C^2u2~8JZ`kkl+)pB@=X=we?89^qGGd=YtA~rhTgVAG>GYo_q#> z1K_U|9Np&$DkS(ukCF+x-l)2VFTHZUu^&{fZLr;KUOZ1-%q}^D1m{IcCg>{pw+t#I zN}gjOK^JGR^IOGtr10n-cF>W2>xb5{qC%p==|}n5rL*If&mck9*LT1e-d(j4OqlA!BviyHZs`&;wprT^B_Z#eB){jAFKTllh#v-<4=Tl#+6|7~P+JG+^$ zeq{Dr*h42b^9Qua>XC1r<_DSc=Wkrw!nc^3{X%!+>XyF!S+D5lF5kO_?>5o;<&Fx8 zM&r)#?KW9^PJ*s89%=6TkF+u--d612d_LRT@uwI2XYa`BO&46`>-_q(vFB7syt28a z@7Ob=^XHrdT_qn~DkSc?tEFFgft5jmE}q%^R`Cq-tX*_vug>zuOz-bx0$c9D5LZH zL4vL(*EaL(ezpiI?x|*e^by&4<|mb$LE`kEWuIDD-x7WnU57Sn?!W745yRe-@96q$ zdwXpu_Q%i4YJL~;TSbM$3A>)_8xOJeoCIC`PUkatZjU~;x&LtBpZQ*q*kx5Sf8iwS zTf*-ZT^;Uk=1*H_5p112Zfwo@{h&gEN2Fweu4nGO$PcY!t>mCW;-m-K`V%Hw=VRc; zzP{y0Q?)M|vfvtD?d^xP?tgbr|In}2y(kqDe?6;*Uv`x>UrU0nQ&)EK`~TbO2VXex zMqlZ%iMl2KT6CSCxB3CCxwZLYMTJE7vj_T1zMrmi$pl^8r#!)@F!^L4pW4h5R7gzz z@kam0qt?6u3A*?mzkJ3S=U(Q^K61Y9;U1+s_$v;%OzX-WFZLh4Z#{`bg+#5@UHv!b zSx;1vpzDNL-ThM!b~TPJ6%yaA>g9VL+kGblU3cEz!M`;7CWD|tqULw~{5w z&tT?{E)^2H|8cEvaQa{)g9KeX|M`rWQ=9m)*EiSC`ghkRzG?NWKKPi^{D>8&85x_u zY3OhJvRIWBtsD7bxmt(cNKXE_k?(u`1qMNd#HQC8`97O7I=@wq_ipU3xwM&nR*Tb| zKky%?YW@Dw#{Q<;vwzPMR7jM(A0+5{yk--B$h%es6%ssd`K`KWOas68*Ot2Nmo97I ze{7cRZH2E+@I$UX&p1|8NSt_7LqBeeb*xCx#iO3zDk>x{8`02De$C1tK^MOZ`3#=H zDis?0TV*U2z9l?2d4dXw+EW|(d9|(cL4vL_jZgA@-zqYWE)^2hPHN<*)U`7B9sR6M zW54I8+412K$?pdh64#Gu>|dC5r^!&#uzIf7vA?`0dFPR7l)ct%3jHgN)7-+>-7qn)t)c-q}`hdr6d8 z+{7QdGTYjG1_`=&9m^Bk-rbIA;J;{`9XIY@o}fbFg4PZEkSQ5mGC>#Hf1cpE{jNb1 z|I7)0=6glr_8Xe`k5^e+#cv{A6aU@BKRwhU*beF}Y3R%QtWB`pAPKs7#mHyyxL2Liz+d^*pE>6w23_C4H*93JTAp*ddYmnJ z6D{J{303^*KQz!YwdXlC{G-=4)Oz5f)%=Wm&oIs)6%zkgS=WDdK;xYdbT!;i$JgA? z`d(2X!Trl0T@rNh8j~lekSO_Bk)Vs${CozFE{|KeuPXQ|w`NB=Pf#JzTK?AWn+vU@ zOM!0d7MR1A#u=8-@3nUvHEi=Bs#YL#eKNKy1ybpSLyGUyDR5rcbWM;r$U17 zjVqa;i|<0q6I4i){0=%2bn)GE`3$~sjqju5C*=t$B>1Mek_oydEqKn&yTEEuR7mg* z^ZATtz8U3uPs_$+Z?+ok&N)4+Pq^Y9x9E@SjCS6<%q{Lx-$`E&8`)qrAG;iwWKa{<}YRY*--1UFlXdGQC zBr4Xu(5)O|Z50W+-u~+l_m6w5j5kl{=*k~3K+`9`bS_E6swDF_eb1SmF zExAQeAyH@6X!m+Q>sXPXtLIar-3#R`f@koMO2gbw?XK4|xTx1q_shdsoj+DoMs6J9 zKKLzj@ssid6%xH~8RCAqH2cPsOwh$|OrGGjGw+E-!`u%?S^GhSM6IGh?&2xkjTS|M zuCH&u#Z50`W$?I98a~=Bo|5e?&r^OssF3*Wq|vTU6YE%!pzEhaqulD%)>bVjH^Nol zo?XM&pLnagY-3h)pYmHpg~Xd}hr0%wtloeGT_qnYZtr&|k8-odX4}sF%WoAG5)H?W zbXAM3JtsjIw>FzX@zx=UB?jOevspxZPeb8T39tt)+nMSRxoI#>7g zdo=yLx+C13OU7!wxaM`P=5N`*=l6pOiE5JuxlQ$~3~ukyC--)Zzsg+PzkCK25?$8x zaZA=(86@aBVq{-e^;3(WGObE~*ZcK9vsEPK4IAKkJ!WNatLWmn$?rMO$5pMba}SQ) z@!aGIo&yrIOJC=XzT7&4B;rY9CZcFgw2= zBt}Z?=`et)i>)vaas* z)fO@1@10%QY1udKkkdN5F&}3&ufh3aMTNw|37y^U6|FW%g05Xp>f)9)u?Q;rRO#vl zb<14*q>{Ia#6ibh?Z%9=GWc0^v1iC z&upHcLZZtbo!#jTt!oJhx_CtL8B|ETFrc&Br-zk6f-ZjF@)=F99_oI(?+NYu+Prg% zJ7?@;T8}Nh!=13&S_eRd#N<9txRcGbgM7CD--^KZ1mw4h3W+0ce$`!l^((rCB@=Y< zssB7dg+!g*o^-pNZ>{7YL08FpPK88=wfDPuZ$D@32MM}()bsnXe2AbS8B|E{?`h;SNYKUi^5zLDB=}Cyk_oy>ejhRw68t-X`HYLl-scAHm3`X> zbe`n)teDk2>UrYVSr51^wX!y`we|z<^Isp;BYJV`neMWC9ygBe<{Kxv3!cqf`#(F{ z^*B0Py|c9VJ~#Q1?BDYlR7iYt#3Xm@!xquB^u2E8*etzx%)M^$i&@R~n9tz0pEBfr zH)i?H_Jey!V#|Vmx;qPTbd`Lpczkw0X@cAp@9bFd zD3UnuhY9Y1AFXpvg07OkS5!#cFnglAd-v>HnLkz}=;C*}WTMvd_q#{m%eH;cMGv^z zPg?uI@9s0RCb-{T&&~mldOm{+i5jIRxZl6r*%_qkt+w~N!Fyya?f=Wzcf9j&WXii$ z#=AFu&uSj^Ji)eoL4$v~^LN==FSLy7KvjXn(R7lvW_kZy82C->{dK)5mcu1pX@ph%Ut}V z{C-d&vCEN@-M!~o86@c9^*Eow@6YYa$Gh(Jv(M!>G*3_=@&7106L_tr{r?{tXp(ek zkfu{^RH6)jm2<2`Ng7Ut%+)Dro-`soDrveRk#N&!o>Iz1=aE!~6e2FsK&6o=B(DE= zul4NJdv(_S(ev^;zOTNY_xh~0_F8*CdwBL5He|X=bqUpq1Xal+kr@&*&zY{Sm=^LN zLDeak1%5j?C+6$vN;R^hgeCa|GbAp(f4VyHW=kg%RPjjU6TF7RD^UC%>=Vq8;I*t| zf-0W9`UEp12LE%W`muKCodYDOs`%-%s^#;cZ{f_4X#C+a^-R&wl{*qtT|ev-b-^i* z2EJu5Lt^Bho$BGf_x=Sz72i4H_Z9EB@$Mq~%_o>4!K=8*1Xb)epJ0Z>uys$V8CjwG zI3%cIzxf`_kjS}XwQ9d{OrUp3P{p41J(wYJSJeY5x5fB?2d`7}TR(fj_h5zuzt1NV zRIwL)f*BG#14t&QVlVgvGbFe=MlwNFa_=%j;)!|3>O1#^?&Gw%sEj3D*E@ES`e z6IAhuB%ff0#6A1U=%>#Qd61xL#yw^9x2J~)W+qlCqu)Bis#sETtw=n&u(Yn18}eXT zRQ=wzw7#Qzh+t;n{!)6>%%iCliShGF>Csz59;_8rJGzw8H(VGRiOhU`mXtf)s#sET zUy;~Xx|FW?N63R^QI$M)nITdCkCM9hEulRF392}6{C02_z1_5wo;&leW)wY0tQuTO z?>-pX!;zrsz1K_W3N1tXU1sK&Ev;XfY*j4DZwE6Z-tSvlFH46!NKnP2gzv!&iO%av z>*qIzJV;Q*BdYJgYZg3@=2^H;Fhhc8mdONFyzc80%#h%lT$2f^_&!^oV1@+WHR}_n z4==3;oj1W82l=kJ2|t$7vj*6I_X%c5bib~YZvA+OXmId2z2zC389C>8{m)f}{d^CW zOQK|l68efyLLU4^R{8m2I_su;Oq)KQT1+=zY-8VpWeqP@Qg8q0Xlg~`hD9ZH**8PA zVmqix?kjGOv$mJk_kTaW(6;g0K@SqTX&GH*wxyE^s`x%apJ0Z>>cM67kX9iN5>%C+ zQbsq}AKD(ww3=8(|N4kkv83c$k$9|o89nZjkO#}6szU8D`mP_wnV$ANm|422v>q_e zs#uawFhe50U1>eLOUQ!+RkK!<(x;snBA8iRr<8u+&$~_CSyFPXNc0$0Qn&fW(#Zr> z$>%uCkoa;<34P}JkOv8>`c^5S@BKVPFf*a=@w)p?t71uhJD4GnT6LVRQ!3QEB&fQv z!Et*1g&~4_nHkfI>5*maoZw!`uN5;STE1RPf8RYcqexJ-=J#TH|9?URGiS(e42l=G z`zV%_Tq_b|J}j<3X%X7Pu`H^Z-Ef?~CKV!h4T;w^_Edjf?AVUki;y5>&BGz6UcT=58&fuPqVUi;|#< z$6eopPY#q@I6y5a{*2jQ@!GOaFhhdR6ebf?@jARuFhgR>xzknKd+j?Fk_oE#easM}w$J)KNY#W()@1T!S~4*X<-stRB3RbRaj zdOJQdB$D5!&#O+nUdD3KfRB%#h&k*nAHXRP{{P)01U& z$-?hXWQGKP$L4#Gpz6W3jr5%l_6m3~LxR7e^gT#WwIS;~U9@uVfCn=q_-jz#g9KIm zFUr#!cMlDCFhhdBYV|$%zP4xntgbuPf76uv;f*!)w&phWi4OH^>U1ZY$$z+}&b!IR zd@Gwz(1YbB6U>mfd3g=Jp<}34B&cF-{aUf^?T^XUk9PR0cF=>wzHZt2r`*4)6;&6$ znXP}!4iUp1uccr7w7_hGI>T$}jdN|xH`w{@V1`8Pi)-m7LoJ<5P*w9_wyxbKL`>dX zQ(t$i&2W{68kc43yz(J}84|3mUn>$+T{b^kudf&KV1~rsYsbuCHTCe{>{D~BpMdghJ0@#Yin)~l{NF1BT@?p9s@{*8?}n|*>A5^JBWuFI7Ujdl`LaZluXaOQM7v6dc? zbu_byqzgEnU`1$v0dg|7Y2MMa!>%IrqUE+FG zTv5p)QS^zb`jcsP-K}JTD$Y%x zV1~r$zckcu{SjKPhy+#1Z=q#|1mBYA*NOyHeD|wQFhe5wjf*6xN`9wo^*x`chilny z^uv0tSKD6fZjNw#iomZGGbA3Fw_Oz(*2B=r1Xa8?;1kS{=%0PO-q>Pbz=H%;fA0z; ziH7-=^z|!-2Rv97Ra|4nZwE6ZigeD_ubmotE`tPBTw})fV1`740cYx~Pe}#ZL4vBk zw}t|Vp|k7i8P|k7SQb@W>%wmbGbBoW-CQ51L)Vr_P}TLNtMsLRhJG{33<<7N@7Ib1 zRjWGY>lao`4)iWFB$C&>e`of8Rn@2MuOO;5_(F~R)Skt26-U1B!3>FY51gfkZx4Bppo$~k_h5!Z_YW`EXMPo0 z`-}ut9QnQnGbF~>xJg%R9=g6uf~ooL*mlDUG)b8Li4=#s;+wcU42dekRCU-tIq$_{=4tN3<U`OF5D)+R;)XT)2ejStC#i(j4KjUZLZr*f88NO zH0;(%&mC+tkB#W0r+#H)UN!V<#SDpEvpVT>RA_sUpla{uo%C&wg$UNS=o#Jg+VAWb zWBdGCF+<{!^4;{NQK4(EB&gz;_C4O*)kP0_x2Ng%1*tANZ?%n+ucR_V;;jl@^lO_f z?R$`*Dtl39U9v=Iey|t!RqL$h@3uY4UiUqiA+h?_&iaxDq0vr)Dvo^LgBcP(e$-jF z%@28ypo;rP--G*%o|U@l24@}3-iO2`ujlLRL!s@#Q9>2BlV2-lNW5@WzP{kUArBH% zalH8+91UMw(^;2Mw&g6zCzv7e;_;pJiQ_}#iUd{VR(8@mzYGz~6nmhPF4x%3JC>AO zD-sn4cG6Eg9-6f*iz<##--8(vS9a;7r3TeWmZgx2NzeCw#kyPcTD*zoAJc zsN#K9pJ0Xre?yZ@P{sSIKEVtL{^}-~po;fZeS#She3l}apo;fZeS#ShT!%TCpo-VB ze1aJg{l=HpRmX?!xRaoY*Rp&MW=L?IuVjKMUd!?cW=L?IuVjKMUd!?cW=Qn9>>|Ci z%JYHmJ|w8(wJhI*84_GiBblHod1WAGNF=Y#G3n=(>YRGlnij78VWq0M>>3l_yXjr^ z`Sw@)xbg3mxF6IAic+b5VI!KW6I395MJ?Gwz9;4=ux1XVoq z_6cT4@EL?;f-0VQ`vfy2_zXfaK^4!ueS#Shdm{ zH_l{&s$B>A>kn&93haHDA;I-Dd=C;-6>Ts`r_T&|FhgSQ)Iqvpg%H6N7P(d@_o#lY zm?6PcIFkvgxJUH~W=I^mw1qxx@T@@ZlAwxvRNsRc5;s-4POoo2FW^CfDy~H2doV*{ zREMs5QissfZCtaItCX@Ad=F+wa6Qmuf-3fcPcTE`4|%WpiZ=E=hsgw0>;<1-hD7K7 zo%G21GXvX$1Xans%M6LTp6;O=ofR5a7vJAg|59g)aqrW%m!7%zUK6jBr_TQP%B~vg zw}TlH_ZI1^pPyjqWP+;g1q1ZUUx$7b&kTtdFB+=5P7K{?AVF2p`$p+rH-z4+#tez% zm72~S)K8z=%+4IHS5+sspT2BxXhtzZf-7qIeMN$*3BUK%=gtgyFhk<+t5>gvS)5!elSC#qg-QX{c4Czh z`m0(|l{|Ji2dm3{f}SVYayh&FS}{Z7+qwPppszxsgalQ^XZO>)o(vHj;pKCB>ESi3 zDtWXsL*lqnGFS3K9weyZ_V-)P42e^B^wd|633-s9DtSh+Pad1pPv3g0Eth@h*NPbu zt-JNpb5*ETB&fQ)UO)Y3`4I8a2YqzaS$2=JylWrb^x?nS`>=OOEc#Vu)C^1e?cn}u zZ^d4^%9VB`vJZWN84~;Qdg(Xs3e67^R3-1PSl_p&^wyo{9Zkzg)UMZCAOC8oNWSw2z)OgK^0d;^*xv&!SASsNLenGcE7<| zHTqKbESALXX)%d?!u^U)GVZr)60;7nRzj87eZMY5xb;gV zk+ZAo+bYRhj3qPv)T;XPH*DnLYdAFIkzjI6l-EQc^CN93IoL=*g{deQx2xdq; zC+}N&qva7qWRpHv<^(cj|a=u5O z8_VdyeGB^;ts_`2iK>fA>jv#Y9wew@ulpX%kT|zOX+8h+kOv8>IC^}KAO7D7y5YTY zt}i`$!)Immmv_ol6^Y-QaDpCohmDg7sw&hxQQwtkN4`%mL!x8jvii{pArBH%wY=;k z-EC{ggBcR@zbUIX&WDGoS~RXmQ1#{Xf9NY)*m3N)gBcQ2QYY%3ABH?gP{on&doV+y zUFmXq?{SzPDcg`#ngmsaW|Sj1pU1Z^so#6$F|*A%di+{3Lt&O?SxVR3bi@`k zwPL3K=+b(~0;^(4$+aReyiOUt@IH7*`OznpW?58mK3b{yD}=kZDKmBW^C#-vrzGsJ zj6vkVy$^}2PCijT(k!$uAwgB4y{N5}c<^Y@q}fUOQf0R@N2uQpW=I^{@+5u7BN!zq zYvPY~s$Oq!l78#Q5OK~g<#f->?9uDAIpy@%589Z0=+}xF5+^q*r_*2JIOu9cf-3g3 zZ9&|QV?JA{sy!t4Ol1q6@xV&;${`!OJErpQeyx}xQLg?<_2sqKnUazTs*=BDFyj$V zu274g4|$OI1gblaTcQ55KSVIIC+}_bM!oAz-C2^~4rWNaIAOUeb)}_~393F?@|GIX zGej`6aPu7#KF{3b#NFwr2OcUN|T`Kqqmo;ZYO~-@`$)2 zFReOP>S*fg))|$$^W4W2?g*B(`vvVhcznX8Xmsanmj zDta4n(1XMc!&a(k`{5BJsNz`gJ=~p2Y2oTq2kLbzC!5hXa{mBb^g$c@1T*C~4$zZ3 zTNO+431&!~w_$)TRu>)-mWsAH398)F7lpP5GbDc7H9(*6vpi+-e-cz}D>G1EvK)kI zOjN7?Jv2nuxZBqEq#;A}t|d0+RU;#oHbfuUGn_p_kE{JJ<4&Tu9-{xZ4J}U@;0S`M zc9>upMR9wex0`r=^S_uLS{%>E98b^ko8VoAv!B(D15R$ZZ6$b)53 z)%~7Z_3C~hf|-t0Zq-c&98IlA^n7`czNSaWgSDcHBh+s>GbBD~HAv@o40({C>V>@n z^@fW=1T*U%8L0nN#j03Ra;-?L?J!Ue+aDT1cC5%V(Cl!r$&YT}F9;nZrW@i!S zrXwOK%?yeA#>gD(g*hnYM<1V{>h*O4^|Iz5j65RT^H;J5aL-&x?4HFcv}d^e-XXf~ zHe1%#xkL1v%11NLNi2V2h(0qf)Vtg>P{n#UIDqZ{h!FqMJt<@FN2J7}0+4#XC zBlSf+8_dbSI8sk=~au; zYt)6~ZCr@RvY%9%9#kdQ>bi|9)e9B684tGBtwRvEBeF^D;%QAZ!2po-@u zR%`$IXDlTC-uWO^JU29@r(%zax2;z9D%+!L_r0gi`^;`Nw$CS+A<=W%yQ){K&^G6G zKEBO5HF9Xe7Id}ZRwJ?I;g3}1xt8{8MS?1h9-m-+$M<D*-5~)V-s*R1|A>~IOe+yE@(POodJR-QIo_P0T_2`$%l=?!Qo-1#rC^U9i7FFD1_#V@C z_12Ad*>A;7?&_^uwU(!RrCffi^$BK34EVX1oR?!#d1kh*nW$?pogXX zmXn~W%<;GAb9;vfW^Sz8U9YwY_!Au;`dZo1jAArBH% zZT+^Z-t%7CwQLdYL$xi zaP@ZFtk;j5Xh!(E%e(9G18nSmJruV?)X^uEW`@MNIk)IZeJyRJ=C2TRXRWx$@Cjx} z>5)O?!Co9Qs)zn{5hg$QXw z^zpYji9;)T=}o6%?4}HG1VPpAYkTYb{va$M1T+6$(_0T;V^x2zRwTw$@1t|h4_#+q zSyXYRnF_gflqkJjJ=S80nNhhtwyDoHEjF=Rv%JuZS~l%FHMZalqZ<9ec2)Od8^61D zo4Tt0Tjt+=kKxm{sLA$LIgb)*4U>eKT+7v_h3y(Jl^$tHQ{MX zClgfVKC?$vnGqt`4%YqU+jgo)E)EgQkoe_a+tsdAsO2Q6`u*75YUPlS2QwsUT>G8c zd_O!)^P?F>f~w?}Gee^9$vf07&%z^RO;TwRRB=0HDrEkbN^|@)czvfDQ1f*&t~eH~ zH1=SI#F`Sj)Wug?I+>tq&bhnPlJOv{h4j@k?Y64E>+PIqx_N_|TW^`E)wtT*RNJrZ zzxy7{kSH_+y6f~w?w2{R<_toeptDADi*QjvLv5ihQy!G zY*w?^V3ed{4-!;eGJmtGG$TZCKgj(&_Y!`sm?4pTG$29M@84`y!*2`CT4qR8J!z|| ze>Vu*aOqvnoEsbOQn>}TwVa!NJD4HyY2{t&{GUR7MS`k7*6&nVr-w$#)&V}~ofvQ4V&=DM?tKZ(NYId{RfMeRP6*DB}9lu3g zb53XrlAwyU^*xv&@kYNbs@bt24-!|Xms%MX>MThQJSKMOb7y2DgU0)0x zYndUz5$b!8po*i%Czv6TJlaW6#aUoHGJjHOwwyJ*`Ql&HZ(HoQGrv~MkZ^C)j=v{5 z4-!=UcGa(H_N0)9d)u^>Rpix!svvF0F=@Y6%#e8Q%!6vm86gi6R3+ESy)|2E<=*Qp zv3o0cp_Vfvl&?lH7vH0LY)xDkV>12W` z_Ov0QKdI;&z=qm;RNWP_I*;^;TaQO#_jV}ul_98dEA@m3QAeLtnq`rg*#1Y=`VH%C zrRMJu1Xb?sP;sqNF~JOp4-WpM=5B zE|Ir&NLlXpqZ02OR$FhY{DAp)pJ0Z>ck62FAGXTxRpVMo`O(MsaPMIeRr0UTm?7cb z0aM6>1XcXyo2`!dE46a(J(sd-O*u<9I>%nqJwB&_zP?)M`tB_cHPZS4`4z4Z?)SA4 zvlndXQM03#v#eo1G|<0PvE|a+5TcGgeyvCpnSHiC^~_MMSQb_8*SUrIiWw5^TArgj zHxGG`psLCCbM(#ue?`39ype8`xmR$(_(rqbEtPyrmLi{*zY8k&1k4| z?+A@V5>(atM?>9bNr+(Pm^;qVmA6?HOEUEd){4ZhpPsEZ6rUQHA1sTifBf@oy{ICH z$VhzTJKX#A^oOt8e*ZPEzMhk^F~>qAj?~e|A6Fz!-BDj3XcyXoEQ>166lAVWm!j4D-v5b)YWf1k8K_`M%t1}vsP3!SYBJdNW!(884~CHr><^!b;yGRRn3~$ z*0XL8?M0a((RWc@UH%Uct{o((`nhv0UG`ec!HAGgD$NXuSJu?kAIyVC$^b_YROK93 zPoJI_BDjZJdr1xbLrZ&KrTq={^nznT1T!RlzrBY3vs>t{3<;`|YsCzS3oB>qkK2Uq zD3YLxeQ0{g^%YyreK6bP6U>lstH%`j20((U^;4_qm*(IunX8ps?MBKfciO3X!!!2Y z9cjN-%#fJV_cZ-MnUDtwstVQ07)2wIZ=<+mK^gt&Q+7MM^?wSroEZ{3#+KDf{u` zvG9@7y3@P|1K*H&2b|X&c-`05C#q6ZD`rUW`hy`v9esR)Dqg>~Qu9{`W=Pbz>rK_W z_tHQ+W(|5lU3lmvlj*i?rds}iy&lK@XPe-rrxy!>y|>84`as&r|(s$Qwxu5zLUd_5S|q`c1Zm zrb4deYzOOpVufDnwmu+SJGeatj~$`@^S{E|#`oYhATg@jZR)0a4+Yvmf~taJZddhh z3K48!wL^W?&1-Gl*&~@IWabAmB*u;Iqc*;Rmb<jd;+dnKRxmF~e_7{Q6$1*%mu8_*SMF z@Ap&mape+tJjDMEwf~s*Ao0d9YSgaX;p_oO6wHf^*X+ zm?6Q@W4E3BO+_<`1XbU^ez6+)?<2;QA($b-x3U=zQAeLt`n*mLsa1d8Zua_rTrf%1 z%^7Lp$Hq-k@6EQc)!M(QG&B7dOj7?Td8Z**lF_DOf*BHZmrPRc46$@FLDk&plhopk zA>#cGlhhT>Mwyx{+%r)PoNMET3n!_jwa1!&_dS>)F{H;t)#?{ZClgdveP@EIQ!N$n zVCLR(6Vw?^tcu>r9whQwj#nSG33;$Ass;|fM~%A{L}ZkTwt2tSE!Epk+TVs=JbSb{ zwX1DynR-{NO`}1GI{L^R6J$utZa-Sx@n>jzF!RAbN2`B5WK}H57H<9?;X$HY&C%-4 zy6`YnI^{k&4?vf~pC-MypT$ zxFb-jTDiBWYiIX0ncer^t>zW6s`opOQ;ql9xoJvw9wfg1bi68ank6{Xe1aJgO{Pvz zmGV$4+YH$r%=~cSM73n<(Rh&fWz|HrWeYr9J6J2KxF^a~C^L51i>n5VQNKNH%Vn?o zEoX*A)pBFiFZrmIYdHz3*z3LrGbCPEHCFv}COlHsM4mmzHm8c)KU1Mh%Q+f$oPUqH zVV4~lEGfBGBvzChuWB6nt8qmYM~v@r%w=QM^g4E*(dzLr>ayc(%zcbcFhinwxiPA1 zL1@2Af-3Hbd=KvXI?NfT4qRtz#eJnuFhgSan!8o`4xxP_3949I--8(vt&7~PPSYU| z5>&C*eGk5mh;Ppcz6&W8?M0a(@z{#RYWY=d0{bfxRPkN2rdF9hsWjhD%QxFp`Q>}{ z&;7Xp4`xWXwWQ*+ZRbIPs)w&UR^Q*~qQf4JV1`7;>x%35SAs}cB$XyXRmty4>k9WY zIqcyGW=ITwwz7WW;pT@4S1S@!oin3?ZuV2-!-VrF{oQ$bbno^iQ{uIjp8l$0sO2Q6Vhy9>qw=FqD$NXu5?9pJ&yGM}8TpX}RfSq^ z93tZR>>OS7qgJNnFZIgNEo-zk@o8sYs>g4*szZ`ppl&xDTy<+D@dhs2$-|v`mk^avj8*_yE9?X#Vs_sR) z#D>roBtaGDrtiURdsWBAdh~3&ojDeKf*BIU&Tg!~xd@{qWjGlnB&d3{a%26|C+MpP z5Gs|v?T*H}NmJYJmC}uMm+$Pz;CM5oi#q!FBay_VWt-@mW@B6#c|{7*f<9l%Y6jW%ezwK%JisQ{E zm?1IxpN;h|e`20TSSs3rB&hm(BauYE%ViwPT5*N%X0R-(I15ZWGJjHOZV&b}x2zFM z8=_At%?ycAXXNPLvaSx)iUd{v@5`2YZk~OYrY+q36%Ve*z;zl(`vfy2UfbS5S1XA< zLn`(lK~-|CxOxO@SZhl!y{CQXO*+hwaI2ih-;iCcNKo~|<^j6@Iei1Y%M6L^ABN}; zXAcb!%#d*FXcnp!395?!IYKvX7CI|ph6LX_=5Ij~RPh~RKEVu$LT@m0y-R{BzM;){ zWd6vz6Y$4Un%*o=zj9yU8rs6m-y>R1;*rUD`u$hokqQx1{rl}a z-G5t%VBLpKZmrkdU{xpo&|25M9E7!yTCuD>yYh5S#l?ks+K7X-BGK`fc6xCuOD7Xl zomaG-zG!ra_~M2<{ij}HYVtzqJbhPp8*_yE9?X#FzM!ohGuqP01XZhAx7BAp6e5`U z{M$Bq|s+vw~uJiY%O^^8PV1~q(W!vaJkAys$Khs(donSN7 zTD8_c^tZ8F-@VZMV1`7qUt8%}Z9*O-s8S1B=}D)D2xf9dw9?yuwIhQi`7LLL#P{u5 z=?betD3Jve@z zys(w7c%!X5$D2YCoIbjJhOg2pK7-JTcJ*P9=+`;5}f&eR3R zEI0d)vsN|LZBGfk9flbayB}<*+rMUMza9L2?fFAb(-(GMVLV9t1T!S6SE-|a{`Bp` zdpOq)5>yqcRYatsmh%_VBN`u4``)v4=P#K}@uH4CsWdYr-mP@JK4ueYl`_B)1Xb)2 zqjdx`B>u7NB>hlN+i%GPRqQugANx0zb}OvP{>rUJD>1(f`X0=XaI4?OM}v$}D$R^r zVfSx)kZ@}N#~!J;9jp~q{3h$SgBcQ|SKO*AfAI9-apgSRdXVDoR=kzit+4xl*2=9j zDk`^PX(58Gb*puYiZ%4x!3+tva(5vQ5>&Z$kz*nPMcNcqu6)|`x2k(UfrZVlL&uz(QkMYnRVs5lmE;TDnmAG-$Ywx7*0+m?h|DLD2> zg$SxRZ>(1S3YAK`^?ju*w{ok*Y@Z=S9ew#;<`yOt^bScZN=`68ZXSk3DGbG&V&@mAirJ}y#XmINZi;6ws*NPbuZY|^3L&}dn z{`R1XTh>a=Um-Yi+)Cq8E@zrgFyj$>GHan1suc;h{<)~!O6r9Ow;sJ@+?vi3v)BDv zF+;+w4qeED?!znf(PRFwR}ENO--8(vZmsx29wew@ZG8`BNVv7>3we;BihbyNuut52 z+kd-vNw~GX|Ib=c#hGSmmH8v@n#4PB`Ic3_wbE|~Gb9RKDN0!rf6W)FxB`do!3+sr znX;wF9wewLbj2$IQqiovY<{+0U$4OI+xbnl#%0+$ue|+tTY5||LxOKYF@%&KeNt%> zR88JoQ(t#1JW>V_g5TlRK3iRvEB&Ua;p%SH_3z(=&d*uyF&Ed+msYmr&YD|8KUN$b z*5Zhk*F2c5Yqzl~w#kTHt(YNE`{G)<$xwI%399N0ucbH64H0bNyY;H;j*D$;*&}|f zm?3dnvFdvK*ic`Qpz6dQs_7H+Ktx8;7Fjfygx zI+>uV&?qrjR4ex4u*YlZ7e76kEl6U^qFVa&l4!ZKI{Nr$cT}a9)Y32HhKOz_*3tvA z?0CKK&20T+wvBmyWeYcd#e*3V`?_W8pK>kj6U?+fCR;z+;b=Ta5cM1{A+`PPo-q7)AYDMD18*Auo%|jln6;&M5eqS*|;+a3I>(2E<9weyZp2+v$ z%xSo%nx0VEjtrLM6U>nK`S)si>Q?L-A}ke+L=seSruiPskl0eSx?c4%Jf!^SBS(X6 z74`l`ubX`>ReRf2*Neu0F!G3C=3mpK+-t3hCE3Ew-y=Loy!vf*-RyjLq(TH$+|OHW zOmKD{da{V6%)*mC_7GO^OK=@PJ$|qP~U?Y5=A=H(qq<#JV;Q*eT;2E z+z!5vi0>)lTYUUlF+-x)Wf$qCRh~CvA(^1+(4{T(X@h442xds|nyl|Zf~uQjRnqnC z?YCv0V1`8Ubx{&j@msC$!3>E)_tjE{lhICsDtL!!|6xvLcks(8K3cx3*_ub1)0EN&aVVaKl(GbGrD$plqg zjln0FA;CUOCaB^$l}|83f_<1wP{ng9pJ0XrukIuhRPl)dpJ0YWp(h7YhLd?tf~xa5%5+kf|K#S95Po#GSp*jKHyp1<2Z ze?!_Qm?5$E^G^D<$3joq~{K{bTUEJ zm0ddNX(d2JSStFql)b34E?J_NsmWUvy6D$7_cSq|dh$J(A+aFUMdz)ybTV-jqS zkX7*+CZAx2M9)fHb%V2PZIcPAF74Y@e=q=q!J?KkbD6B{aqvy6qIa?fiI%&&YE`AT z>9=Hpsz=Iq)0;+taJ6El=o#Jg+V8CD@70RL=DOYV*RrBZ;inB*7FDNJ>84jN4H4I$ z+f{e3VrOUh|K{tSSK2sv4l+Yx@Q{4{>g}O-=m{QwzxiReT1)5YeAhw9T0z zar!R}^;>_0-rr7wDxM)54=F$T_*d0P6n&zq{$yI{EzK;8s=s%gfy98GMRfOPUkL1} zSr%1%kGO4s`77;UhD7rFsYy`9ccA+o%#cWaKQ#%e_y%>~gYS*vo51L6qK-a(tw?;iri4CoJv>qdID(*xTh?eD!3>EWqe|*F--J9! zP{omN>l4?C{eq*$+aTUYGN7v>m%6a!FEtpeo7hLV1I}>eRyd-=sY{` zCj3}R&l+H3zE{z&6*DBdUsp=Ee%#W@1XVXIDyhr986r5UD?eXMXWeA$&RO7lFhgSQ z)?)hF5@>mZrJ`{~f~vna5=ks+TwH(q+F#8NsyH`IJ2HRddpow&>cM67kXCkY@b^Xu z3Ei}et};8cFJW0!am$(tNk2s&|DCcV&e~pD-~WBcgJn_0@n#D*f5n5NVR*5UdizI5 zGZIOZ>`+2q@kwZ0u~t-#oO8VX=c*9FOoM~R=`GJ3O|3{YyWu!}O)BKUT2aLj>h~2h zB*uJLTz}FcClMg{$vDf~ubBdV2EMTLQ;gW=QZI7rqAxsvcfeQ`bMMYrumU5_~I$ z??Hm9Pe+&2FD&+i{V);i2b!B6TD|)&3R# zRwdrDv|pYT3bBMjClgf79y&|)7z@JHikTs^XQ_>^9!;%C zoc-i1b<19Oq(beW>ZyBXshhGxTkzVckE-D(*mM1n1&^o)i`%%+7IYrWkZAwY4E6Yd zkOv8>INnSPoCh-`ieE58-W(b7AVC$!vG2iAed+zv)rmLTa#@m3FhgR#o~~4*zp52g zA61yH-u)l8pfQR@JGT^P7e}aHD`rTr*OLjV_#SDWV1`7YcSolTC+#3XRr33(x&OHB zn#a`{FWMfZpI<9xNYr|Drh4|{(Doof)dR=ORL|`V5!_OzoHSkOckNc=SnzAb42hZN zOjlP-J7Swlf5}tc*zZ!sJ)iHv42fYwrmIw!kOwpOemPzBZD>_2DcOU>>dp_V)ba3; zHbftPPfb9`lQk%s2VwFr+T>Wy@$UuSU?D7 zNbuXaE!-kLK~>Hjt5y4rV*(z`kSO`&1~sSJki$eO_8>vkCI5R>HO%jOn6QAfgBcRn z)mWo093T3=OMiwd6B(;MDHMogRv6bNt{u#fNIs({K~?|k z*^WTgglrb!Dps?4-!&0~n6F=0G5IiIjH3P3M+3f4AN-nc zG939=PS~R^f4<9MB4v?Oni&!t(|$WhP__ExQo8o2(AhRKBsivh4-!;Oxw49$b0{=x znIXY3?R$`*s#E*Zbyj=(ES66&LxN*EnV@QNetrF8{)oW#V1@+8wC_QJs&x;XrH5}1 zc`!qQW7_v1K~?t;FV|;&H9F7^W=L>M`yM2y8eiikU9mZ?@1_hVqn#NN^Uvt2Z=EzL zP%9Et4UngvDxVu7_%_wA&nl%yPj7C@-O;6#zTrX}+xo<{I;})mox7%)QB}_?t9w_q zDqd|d+Eh$1Ln3>8S-o%sJc0yOgI+AF+kX`z=9ew4UzvQlsnvV0m(mql+L&*owe^W> z#j?J7yR25tFEcc2YqY^yk$7!YS)I4Q(#Zr>KQAe(b53nx{A_*fU%A49Ov#7J>UAlr z`g^q^@xT1C`nRv)5o`xlg|3k~f*BH>s+ZNDG_*Z!S`Z|tI`_j9^yec&1T(t_pP;{7 zU{&-^_8`%^+zI;3|AstR7F9PrRYp(S8zMNCRt+wtcOSGpT4-FkmNP@*?WU#l+?k>6 zL4v9wa>OaxBt$S%Dyx(}`C~i!Sd!mY%#f)6M@e1$7L45pleVPNB&gyZ!}nl@#JAqYF#xdbvkaD-si{l+kaU0gqIuR#eTnr;PsgbP%pq%-plDjDGt3 zqp1~%DjiSI4_*V0V6CY7d;2RA`jr#(>`5UHmPHkhM5dQqtvH|CTvSHhRed!35)z%) zmDbO14(%DZFQJO_#;+AKB;M~^S}#k7JV;Q*qn+`{{7I#`E)iE@Vt(YOf)qIi( zs*^(;P@o4C3 z6bY($mCE;EhQ!po`_y?`UJkT_1XWy%(6%{l`JojnRikUJF=gGm>0R~t_t%=3YXlro ztJl`6ZZ)qcMDT1WnV^be+9#MH!Ly}gf-25UpJ0Xr&z6!2s(7c-Czv6@^Q&ZnD&8^m z31&#}Y$=(big$i}f*BG#TS_LV;vHqJ`;p7ioVHkt(4lYY4zIfiDu4o zoff}V%#h&9X~_gtJQDc?Gb9SF4VW^Vw1Wgy$?K)AymXs-_CfoWy{aE?Q(x4zG4Hq8 z(&exC_;=z+Z2V-sdi2T#rr!)9>geMWRPm00)!M)Q{c{rQ)~8j|U!Dkfuq>*0MD;zG zAyM(uXI0DR9}0Mopo+cjdoV*{@IPm&A8U^bc#xoq~ml{PMSs4grQ8jGc zQ))(5=&Ca_B-n4ZaPwC@NKn=I!)5B3qINIg6U>m{_D?3Lx_;Ov>Vi`q4fGW=Bsh+J z4-!;ed*v2&`zxXEiOi7TeDpm?P<7XbJJoxm76#hE42f=Ue5d*k3jHdD1XcY??o>nT zfQYJ=iblzbal2I2z1Dq0?LDgQ3LCQ|(~is^dBPO+CBa`^7_pQeeSCr{_K4Nmzp{rz zzmwp-Nuy1L2&%Yctu`i@A;G(uMwsjg7+qkHWebM;!LyJm|%tk?@bzQ zDnwAlJ%-iB1T!S2-m^fR{^|{Zu}gxg0gE3}_3jK2%#iTcJ{$ST&YTW+bWKM!b89{v zH|A2eS_NbCCbr!b*X0ar+|v+FB^ehB!8L}mvgqMdLO4IhLT6<){p$GKbjNEVkCanM z#>GN#wF-~$+Ci0zjmMe!RdZ)oyWDs%<6`mP8X8$yAhMiF%A(4}#^bUJ8|E%uae?t* z#>L{n^)#}wKx8?Ultq<`jmK;CF3qh!qL%Ss#>L{n^)#}wKx8?Ultq<`jmM@^SLQb9 zSJrqi<6`mP3LIHkAhMiF%A(4}#^c^+yX5A+v9BQ7=FGTQJh%c!Ru+gXr;@U$aV)5|b zumK{=siZ8bTx>k1v>K87=CU5fgBcf#2jA$Cl?5WpsiZ8bTx>j^{NKRbQpY`MJeYB@ zc<}AbSy>>moJz`~%EiW`c=aB+r+@cZrfIwm5YtX-S1zY`)F>F+{l9& z7mEkqa+H;oL{Q~o<1wjb>)fLMtYkcxaj|&t-Ah?nNd#3cHXd7BHO>9FUwz}jjElvC zYqMl!B@tA)*mztq{EXb6H|81-W?U>DTrnmqD~X`W#l~aBXaC5(wMCxsV8+Gb!FTy* zWhD_*x!8E5oBxrs@b;UG2Qw}f5B~N&D=Ueh%EiWG@>y$gnsn%8JeYB@c<`6(Sy@R0 zRW3Fj`?o!ov*CqXjR!L>77zb@`bh*;E;b&!c6P{VI^;Iv!HkQ=gYWOp%1R=ra%EiVb|G^KI z9$aMG!HkQ=gKGq2WhD_*x!8EToz=GB=f!q=FymtJ;93V+SxE#{E;b$uM?X^V(20Xh zUoqq2s2yv!sjKS0l{q&^BB*k)@p$^xbivL}eT@e*E*6ibn>VPr^_JFN@5=dN$uQ%=jEkjQw^Fe2NFu0mvGKUN@~Jr+N{uug%(z&} zb!!V7k0gRB7aNa{*R{CltOcWt2Qw~~a^0H6#v_TK%EiXx)GaqGoj1#RFymq=*R2$7 zJdy~iTx>jUKe2j2k1y^p?O?{mQm$L^+IS=pRJquAY<^@+LGkW(n=|8LDc7ysZ9I|) zs$6V5`oHr^L5ucw>@wqGDc7w)Zak6*s$6V5{&W1cf=aJ+GkwL3i=|w*db;sQBB*k) z@wj<+iFEU4I~osWTrB0f_129?5G)Piaept&AKYHFG(V( zaumU7=eue&N$aad-1 zBoS1(*m&&j)Hgj>j#H5bGcFd7GWD)jn?}p^cGHd|f+`mqkBSF}q_e;Mm+@f6#Zs=j zLuWja2&!CcJl_BL_Vlr*oo76laj}%^?&BGcB!Vgz8;^90QRxw-XGG`cS&atVaI(!Hh=|L6wV*$Kur^)75@0 zmJ@j}<6`mXb9HmoVz;~j)AUsmL6wV*$MR!Gr0<;9*LX1FVk!5}=6R}LjaeCwB!Vgz z8;_G79GI@${b}RDjElv?Ju_q4kwj4CV&n1g^jp%WpY?_DV8+E#u6t(2cq9>2x!8D| zeERk2Y8{H^M%#lK7fZSBnHl4eL{Q~o#tvGIt{4We!_BPtzZik*6s{(VspgzmGEG ziUc!3!g$mk*dq6>oNA^WBwQ@2`SnWcp8u9#Z5a;|%mfMJ@kHq^xqp<{Z;l2eTr8@M z$ClDXUXov#8V?f81PS92%|Dq{kw=Pzi$(RnrX}?ipHInnkYFZA7>{WF$*eLSBwQ@2 zqMJ)-Rp$PT2MK0^gz<>xpUkQ^qIQsQv8W36mC&P`P0e_aU?xZyk7)kMtSX2+NVr&3 zPxULQ?;rL+#)AYiLBe=M^G{}#@gU)1QMunGn{7^lnIK_2qWLGYDjl_hgo{PxemQMC zNH7y5j7K#8WL6mu5-t|i5C883-SA#{Hp+OAU?xZyk7)kMtTG-XTr8>zHBZ!c{WF$*eLSBwQ@2mY1ERyKRjS7 zFcTzPLrRv8ZxE*8~0$5hbmhQ=NwmPLrRv8ZxE*6zrr^Sq263he%;}Ok2nN`Mv zgo{O0}$RC|Zj z*4rw_`*sq{1PS92&A;f|W#mD^#iIIdU2XltRvZT%!Ay`a9?|@ZzFkHhBwQ@22Fq*f z7oU%>8jxTnNEnZ3{zcy|BM%ZT7FDz6we_sqbLU#R z?6vWC9}>(23F8sXzv$a#j#$!{3)6&Ijwlp3jTr8^f zQ>*Eh=EUFINiY*6j7K!bqi?WLUy*RJsN9*Jndc;!2@=NRxw>--Ud^0y*0}aNwfX+n z%rVu)qWa}u+tsd={r9Xa63he%Xgo{PBspYrolZRsu63he%<1tL;c(=?sCkYpes_nFI)cQrS2MK0^gz@;7%<+#h z=bR*5EUJS)ZBZRRk3C2*6C{ksNpjBlMdqB7go{P>M!zkp*|D+$pqU>em2@=L*i_E`a znR8AOE*8}#^EazXGhz=C%mfMJ5uHK4bD2HoB;jIF{rSvhHG56$L4uheVLTp^`PVCR z&Pl?>qFVRqW>vAs8<}lRf|(#;JYJCbw|kF0=Op1`Q4OrMMSXW}>_LK=AYnXO$^4s{ zIp-wdVo?pBwna_Ok3C2*6C{ksKAC?#GUuEmTr8?PYks5VOpHB9FcTz<$7#9Ma=#j2 z&pAoBSX7PP`$p}1HufOFOpq`hLuCGq%batPaIvUHjr&#&TM>JZU?xZy4>_vk$Z;?o z9cxLrSX9rn+p7Amk3C2*6C{j>9My8vyWG(_;@3%mfMJAxE{e90!dD2^Wj%)5^Ql`9H_LK=AYnYBGe|iOnsZJPE*90Cb9bpF<6{pJ%mfMJAxE{e90$$$APEf$S74-(7-3F9G0wX_@ujRy%Ai>krvJJo=iu?Goef`svqqgq;ygSpXumxPN&b;cDt z)$0B6_e2uR1PS9IN42yZ2aN{_7mF%;=?=Acb?iZcnIK_27I;G(A%=sV*7mMo589%5^&&D1km*&Ig~$oDY(4 zv8dc{FpUQZW`czAxI^Y&m(2Mf2^WjX{Q}f@kYFZA7>`~u|9;4v50Y@PsN643jRy&4 zf`sunTh0d;WzGjlxL8zcpV+S6c~^ePYCK3V6C{ksQ!@V!X6`|faIvV|@Ai!c31)(X z@t7&|uVv zgy!~qkc5jxRjlkbHU8Gvg9I}{!gxF^^RI2@e2|2TMU~rQoBC{1>_LK=AYnWnlKFRY z<{l&o7mKPy>Fw&V7E9uDP7url3FC34%)k3H=Yu3%EUG>SwyT$)j6Fy&6C{ksDw%%| zXU+#nxL8zePTQf*I~046U?xZykAKMd;J2CcK@u(&)yuc-RF7QzYNoG9FcTz<$6T3z z>CE{c2^Wj%_hWafl|y0=63he%;~_`2961iAqwggoTr8^GXZENnGhz=C%mfMJktgSa zdot&PBwQ@2$Gd*7COjQ`kYFZA7!NtBy&<#8w1b3;MYXWTJ~jD?*nsH zGUtONTr8?R>wi=^_r)G0m}$RB!J&s5Wnww*#5uISFQhgz=E0T3U{S=3I@0i$yhY+ClZe;Mju%GeN?5$Z;?& z$3f#k!o{L;YqFYlkYFZA7>}tk|LSMX2T8bCRBjDe<3WO%AYnY@sFs%FU~aTMNVr&3 zw{QGeoqJvUJ&^=6LBe=EDf6$fd>@TGNVr&3r;I+J*8U^*Ai+$KFdlMLE0E)$@gU)1 zQMt1)(^n*z2@=NRdEOtqEL-Q5FEC@YMjVT3^5&ZQx?}CXXJwIKCP)~M#c!Wdusm}< zNW#UUnmMed9{$_X%={q1Opq`hMOqzxCY6MXMKz^#O}+h4>_LK=AYnXyl>38n95ma5 zgo{NrYi|AuGI2T8bCRL5LgLtk1s_8`GbkT4!~Wd2RdoDY(4 zv8Z1Cwz_V1e(XVlnIK_2{wwqE-pu(R2^Wj%U(>4VRoBKIB$x>j#^az|k2#n*A0**o zQSEJ4T`w9FdyrrzNEnX~Wd8NfoDY(4v8c9Gm3F)wdyrrzNEnX^az3~!b3RDI#iIK8 z_iB3T*4TptGeN?5{3P@5$+UeYm4u5$)o@QWJ)v?sGY3g96C{ksJ#s!+p@}^oB;jIF zo%lmFePUkhL4uheVLZml{QKxl`%Eec7mMn)V%7Edv9SjUW`czASSj;wVCMcH2^Wj% z-Fnq^$HlP+31)(X@!;7V2^WiMb+_vJ_ithk63he%_u(_LK=AYnYdllk{wd0s8* zD-tdiReDJ+{X%Z+L4uheVLarhmX_n7IUgk9Vo_~bR7;;;GWH*Q7tXULE}Nf#iFV+yq4ZLH})XGOpq`ha#Typb z7S+4UyX)}-Vh<9`1PS9&ORmQ}k~tqF;bKwM+i|mAKQ8tl!Ay`a9-qnldpUDHNW#UU znpNp${qBpg2MK0^gz*?B^Y8l1`5*}wi)zUA-E@teu?Goef`svyA@gr#=6sNZi$&#D zoHApV1T#UxctqD@p30mLl5nx8+zMC5g9I}{!g$;v=Yx-Co);zIVo|k9=j(BM;^)Fi zFcTz<$1<6J!{z&^Opg=^7mI54@O*uB$N2en63he%;}PATzx6G9K1jmFqH=5MnZ6>y zOpq`hcSp~Q%KeF`9VA>VDz}E8@gTuWkT4!|Wd4no@1v0i2^Wj%#)mjDMR!f|(#;Jfit0vnn06gM^DkwLh<`zOiTQL4uhe zVLXb@$<1w_IUgk9Vo`1VwyWOsM(ja?nIK_2X2|?&mN_3J;bKuuf1sOgcC7oY39My8s8mq9we9v z62{{VnSbju=Yu3%EUGfc-=fd$9ea>qCP)~M1?|3kV|3>JAPE1eL^aVX)4-(7- z3F9G0wE{T~n!Y08Vo@zx)j z#^Y(3f6X%IgCtxmsy=Od>6v@u`9Xr2AYnY@sFs%Fpy?|TE*8~*pL^-~^I{JY%mfMJ zAxE{e90!dD2^Wj1$z8p5tJbjx31)(X@facV?}^Owq9j}_s%g7=>&Cm{{VoY+f`su% z%lsQF-$$c4NW#UU%5B(3_q;3iAi+$KFdlMLOUrT4c#v?hs48{nqsx_#JxDMUB#eg~ z)zWetH0OgPTr8^Ut^4T7bK~PV31)(X@rdSM^zAb0D-tdi)tKsibk6y)2MK0^gz=ax z^KV+_{vZh#i|XHNdh6k9;_p5rm-_$)2MK0^gz?}n z4oSFJREJjd(wk0=JxDMUB#g&enSYft=Yu3%EUL>Z^wPJjkH1rsU?xZy4>_t8$Z^p0 z6$uxM%AJLo?^h(42@=L5x*ikVZHTtVLl3moo366=mt8EXW6o-;cU~IbcP7D1kT4$6 z^%%LzVmwH=SXAZTZljO8DE1)1Opq`h(e;??quEUIoZTj@(z#vUY?2@=L5dR{xa+Yot>aIvVa>D@|qJP>=3U?xZykLdTi(cK2I zNRe={sQO&qO4q0pKf^+TnIK_2qWkmF-G<16go{P>i<*r=5bq1`~QE5(jmPaq=;ll`mVM1z1Hu!fA{!;eXSn%!H{0McNW|K@e!8xS6ki=ONKjD;pW)``-E4!)AQ5Zps()7#`Re^I5uREprR5!!_CjT z*#?`Di$tug>+2%Tr2Ev6L4t}(_zX8cZ)e?o28mc(*P6SUNwZlYg9H_o@ELA?-pw|+ zc94j*b$zk3nQWU8GDuKS37_HS=iO|B%ODYJ>ssBkxm12UWRReu5%E;WOO)yqj%s86;wDU4y4*$!R4+1_>%E;WOOtcin7*%ODYJ>l*o~ZO5MQ zok)U;O85--`(3yC%w>>>wRQDAm?gCqhYS)_RKjPt`FXec%w>>>wRK&5;&oDQc*r0@ zMJ0TO`!%3jedaPq#M-)AzOs5nkU!ap1qEY1QnI=8Jz7S z5o_yebm}K&`O6`L1QnI=8Jz7S5o_zJas3AK)`E~hf{IG`49@nEh_!Y7Iqf6UVtdFS zK}98e250+7#M-)c99d`T)kyYJu3RLjsD#hpY#)hOTi4k8*P8v$gbWf?RKjQ2r<`$q zkVLGlYgo-SW?Svn*~b+LDk|YKINL`e*4DN6%n!^XdqM^YDk|YKINL`e*4A~|HLK0* zFSp5V2MH=F;WIefMHdMabMBql?I1x#C42^F`$)vvy1GnSW4bo! zn4Lj_ic0tl&JU7^wRLScu-07sdB`9^MJ0R&XZuLR+PX>%`OrLMI%T(m1QnI=8Jz7S z5o_zZt^9g(*_e<)f{IG`49@nEh_!XS{nZ9j?D>#Ef{IG`49@nEh_!XCf8rBUYIevV zK}98e250+7#M-(}Znn|fGcaV3prR5!gR^}kVr^aJ_H8mxR16s;sHlX`;A|g>SXH**+4nwyrZi`odh%BYc;T zprR5!gR^}kVr^X?%>2@neLj3AlAxjzK7+G;Bw}q{XI1;k-1AwuevqJ|5H**+4nwytLier3*S z5XKB7sHlX`;A|g>SXGyT3WrY1o}C42^F`$)vvy5e0}j`=|< zDv@N^`9b%#LU+&EsAdm2ef}(eO^vm6z4}piDLW(ice~0L1QnI=8SZ^f?rnuGgG8*Y z>;3lKrS20Ug9H_o@EPuXPHwirWsr!qbuIj(o4hzBWRReu55&}EQ_wRNqS z&`sLR2^l1)sD#gO?{ji*D|8toVr^ZOs&!;eXSnw{xwjR%3=*-nuGfZjmGQra3=&jS!e_YmIk~qLx(pJrwyt9JyUO75 zv$MyEB&eu_&v3JS?rnuGgG8*YD_=p|j;xSDf{IG`3^&{7-d1QMhLMQ1b(P-JMQ$Du zGDuKS37_HK@9W-H=rTye+PYeN*+rVZ5i&?nQ3;>n-tX()R_HQF#M-(p-qJ-j?F$(s zsHlX`aPRkZZ!2^eBw}q{Pao(aP0pT^z0XNdQ3;>n-tX()R_HQF#M-*{m*^^GZVVYD zsHlX`aPRkZZ!2^eBw}q{2eP`#d-sP75>!;eXV~`|HgIn%bQvUKZCwW^ca_hc4;dt= zsD#gO@Aq|YD|8toVr^X;_I8y@>p}(zDk|YK-1~jq+X`IEvgwJsA_jPY8bQvUKZC$s&)I(lh7BWasQ3;>n-tX() zR_HQF#M-*X{@p`rJsmPgP*Dk=;ok4--d5-`NW|K@&TG(9uIe8$NKjD;pW$Zv+}jFW z28mc(SFOH1rB=g`L4t}(_zXAO=iXlLGDyVQy2?%JDP2wr86>EvgwJsA_jPZtcNrvN zZCyKO_msX{!!?Qo6_xNA?(Hz{?e#8$M69hV@64XE_t}s^f{IG`4EKIt_x5_1K_b@H zHEn!P>DMo0kf5RxKEu7=*S)>oWsr!qbv5nKQ)ZixL4t}(_zd@cU-$NUmq8-d)^$zQ zo^rHU$RI&QC47dxsx5VIuXhVKR*4FjQ<$dI$Ng;y-6_xNA?(QzE7bOvE z>)Kt|w&VSfL4t}(_zZV<7uJiCh_!Y7wYRsNawuewprR5!gR4JD#M-(p-qKr6suF&0 zK!S=&_zd?vCaf1F5o_xzwyn23*d}CsHlX`;Ob8jv9_)aH}sJ~2SWx4Dk|YKxcZYstgUO~)IRc`GU2x} zB&eu_&*17$60x?fdHegwmUuy+Z~GDk|YKxcZYstgWl#1O4Q~o*{z-6_xNA zT>VKR*4A~?&;6u$hmb*nic0tluKpwuYwJ3ALx1U&6*5RrQ3;>H)t@9{ZC!O==`THM zg$xo@RKjO)^(To~TUY0!{pH6~Lk0;dD&aG@`jbSgtt+n#kbicE?-CMJRKjPtySuPn zltiqp>$Cv_WbfjTL4t}(_zZV<7uJiCh_!Y7^Y{QMKPqI9prR5!gR4JD#M-*ve`bJG z&I%bMsHlX`aL;4HdQlRwwys^X2gs~aA%g@JmGBu{{YfI$)^+zo1Ek9CFlHb@MJ0R& zSAUX-wRKhLG(cJ|3>hS-sD#hp>Q54}wyyK44Uom7Lk0;dD&aG@`jbSgt*g@a{blAI zA%g@JmGBu{{YfI$)^+Wq{&Ic2kU@fqO85+}{v;7=*ACpn<;q2Zic0tlcmBE2rMu_6 z;_Y@);cyrKTs_v-HSeZ&a;cp=NY-DGprR5!!>!kLqf3`TBG%UR-rly-cTLD3K}98e zhCBb<=+b47h_!XiAJ$f~J`5QosHlX`aO<_*=+b47h_!VsFWy$(+7U8HP*Dk=;nr)r z(WT2E5o_zJu&|93$lo=4e~_S}5EvgwOcWK96yu zOP4_+*4FjP$!+A+F(HEl6_xNAZoRfWt9%BDSX)=oRjuWRuR{h2Dk|YK+Cx6ww05`b{Xv3?O85--`&~D>v=PHd#M-(_^l2^6Ob;0(sHlX`aKGQRPg#5h ziCA0Ljcr@Yr2O5p+d+bgO85--`&~D>bnPG!YwN1fp|#BJA2LW#Q3;>ne!uHRmo9@u ztgUO>U9Dx}){sGhic0tl_xoKpx^x*NVr^Y}XS9~;rbl*Pk)WayKI2Av{<+bm%ODYJ z>)QWCYZ)>vWRReu5($t!H*$k)WayKEpkaaidF@K_b@H^~)!1q~Lk0;dD&aHS?|0qk(q)i{wRH`g*;aDdIgsR9OM;3@_zd?v#*Hpr28mc(*Qi46 z%E;WOOtcirgHWsr!qb@d<6PTsgXWRReu5h?0`{*Xa}ic0tl_xoKpx^#U-BG%Sb{jc`YwnE4tK}98e zhWq`ln{99zBw}q{XO`(8AHEyD+euJS37_G9ziXee_zV)UwyqsjI>z= z_zd^^T{qj{+Cd`L)^+0f9c07z;d)Mjic0tl_xoKp+u$-t#M-*17V99}?+Y0usHlX` zaKGPmvkfkTM69i=@sI7rlnEImsHlX`uvfMCeo+#!wyvudwwFKO3u8DER8+!exZm%( z*#_4R60x?fD|@t;k9vm;5>!;eXSm<*y4ePoK_b@H)um*6sdiz=AVEbXe1>}-<7OLN z28mc(SG)`J>qSXWQ3;>n=I6ux;LCmLNxzm&{CN;->ndKTo;+aRHIbYjB&eu_&v5he zZuOaK2Z>l)*ZH&R%KPVs3=&jS!e_YodAIt^Wsr!qb(OlbuFR|&GDuKS37_HS=iTZv zmq8-d)>UPF9VsXwg9H_o@ELA?-mN}!86;wDT@QAxBQ3jx3=&jS!e_YodAIt^Wsr!q zbzNDcj@&UbWRReu5kU@fqO85*nKkrtbxeOAqwyq&V zYfGKFO|y?(5>!;eXSn%!xBARwkchQ)^}NQmV`|7CK}98ehFh=gR-f63VI*R0UBl0< zEx#WP86>EvgwJs6wcYA7mq8-d*0rQ~ZQ0qSS$1EMprR5!!#$62tIu2piCA0Llcj3Q zubV;!2`Vb#Gu(P@xBARwkchQ)ope!c`ER}E+3g@fMJ0TOTd(a_pScVYv9_+8TGW=| zGeZUmDk|YK+&_n;8vfx3=*-nu9ll?%WqAx zviphz6_xNAZoRf!edaPq#M-(psa!`UO$ZqzsHlX`aO<_h{UC{0TUV!;eXSns+ZuOb%t6U^vZC%@1)Ripz&Wz+*OM;3@ z_zbsR+pRux86;wDUHg~UmA(f;1_>%E;WONNZMXW&Wsr!qb#1LuPx5aG86>EvgwJs6 zwcYA7mq8-d)-`lOJ$Z9s$RI&QC47ckukBW!xeOAqwyu>w)RWhTh71x^RKjPt_1bRr znady%YwP;Cc70iJamXM+MJ0TOTd(a_pScVYv9_*?dI?N`i_?_zbsR+x;5JWsr!qb#2^G zPwsmtWRReu5%E;WIefMSvPRkCD-u*x!e?-{k3_7k z>zfO0J0^z=5>!;eXK=QUM69jrK%s(C;z-CKK}98e250+7#M-(pI8s3JcDgFNuSif) z37^5)J`%CEu7bG=${C-A3=&jS!e?-{k3_7kYrq)=<-|HyXSag{6_xNAob4kKYwKE3 zx1h{^I%JTbq7puXvwb9DZC$JT7nC3W3>hS-sD#hpY#)hOTi4pR3rg|E*JSq<2`Vb# zGdSBvBG%S5w@4vb^kB#!K}98e250+7#M-*n^(Z9EmWB)xR8+!eaJG*`tgWlf#zOM) zj*vluic0tl&i0XrwRJVCSJ>XGg$xo@RKjO)wvR-tt?Q2G3d^MZA%g@JmGBvy?IRIu z>uOr`6si1W$RI&QC42^F`$)vvx_<0`ihMmkWRReu5%E;WIefMniYg z5!pB_WRReu5%E;WIefM$iq60|_cB;WIefMFT2`Vb#GdSBvBG%S*X8t15V0{>ilAxjzK7+G;Bw}q{ zvgj0$+;-a%$- zj*vluic0tl{u+=(tgUNk)>6}^WQ*)^A_*!g;WOO)yc=D*c94j*bya$GiD};^WRReu z5)KO!iK)LZWRReu5!;e zXSn%!H@dVD!$`#1y8ayYuK9CN$RI&QC47ckukA*cE`vm@t*cktcg=S@LIw#cD&aHS zY@Zulx(pJrwyr9j-Zh7s+?w52B&eu_&v5It-RRO~kchQ)9ew0ovujbvAVEbXe1==E z?M9a_gG8*Y>*?+9nvo@M%Wek=Dk|YKCfWHxH@b8gBw}q{bF!A0kNSrU5>!;eXYkj6 zBw}q{FMPAa{IMcrkf5RxKEtiowoh4nJ4nRZx>}E3Y9{AvncY_;sHlX`aO<_*=+gBS ziCA0LOY)wXRXb#mprR5!!>!kLqf48Si$tugYjfdcWEvgwJs6wcY5_wSz>gt?QG;%gul;A%g@JmGBvEy|x=&x(pJrwysyk zzHbWN7&1suQ3;>n)@!@brOO}@YwOyVwZgnpHDr*Wq7puXzXl``YwNl<-%9i5!Ek<% zprR5!!>!kLqf6Hg60x?fP0y~h@23tKB&eu_&v5It-RRO~kchQ)6}@1U`TEw7L4t}( z_zX8c@5ZApgG8*Y>-!;eXSns+ zZnnW?kchQ)9bUQ0)Vw8Rkf5RxKEtiocC!sGgG8*YtJR=YX41hhz9KQ!I zK_b@Hb#uN|rpc6$L4t}(_zeCUkVLGltNC3kP5Em=1_>%E;WONNZTpm^f$J+0v9_+M zpR6#$^M(u(R8+!exb@m@w!vkPh_!XayD)!0NP>z=_zX8c?^d6=jGsOmV+x-+)L*w_ zZCxu1j4|a8-<^FuCqYFee1@B!cdO4_28mc(*PcrrFs=563=&jS!e_Yoc{jRr86;wD zUF+J6HnsPM3=&jS!e_YodAIt^Wsr!qb^Z9zC^IKd(ucWnk)WayKEut=yVYkdgG8*Y zYu@US=GV$0g9H_o@ELA?-mN}!86;wDU1f`oG{3hC86>EvgwJsE^KSK-%ODYJ>ssA= zg!$|FkU@fqO85*nKkrtbxeOAqwyv>zhnr1DLIw#cD&aHS-JM%~<}ygc+PeCT8gBk- zc~AEFL4t}(_zZV<=T@KDh+!mRZCz8$aP#o8kU@fqO85-7UfZoca~ULJZCypr9&YZf za&LA!NKjD;pW)VPyVYkdgG8*Y>!WjroBuo>GDuKS37_HCYrEBFE`vm@t!w7>!_Cm6 zA%g@JmGBvEy|!C@<}ygc+PW^EIoyCQNW|K@2CpAwiro-0NKjD; zpW)VPyVYkdgG8*Y>xNmQ&2P7b3=&jS!e_Yk+HQ2|GDyVQy7~-$z>K~%WRReu5NA%?BG%S5pz}D>S5o_zJvUt4tU_i(qK}98ehFh=gevRZZNW|K@ zdd(ki-YgI@NKjD;pW)VPyI&)@3=*-nu4$vko3%5;n1KWpmGBvEy|()`lFJ|wYwJ34 z>3CD6e#js}MJ0TOTd(bYjpQ;&#M-)kUp>xz`)wG*k)WayKEqzs;`>EO#M-)kzHFRX zJTYXDprR5!!>!kLzeaNHAQ5Zpsxxt{DVY^ANKjD;pW)VPyI&)@3=*-nu6P&b?*~ax zQ3;>H*}ir&2AB;`KIX>;v9_*L3iLN$j7$DKJwHfAC42^F`$)vvx^8aQ*BlxiGDuKS z37^5)J`%CEu2Qe}Hg}E;86>EvgwNn?ABk97*X^hEGNmSj3=&jS!e?-{k3_7kYsZKl zX8Ej;L4t}(_zceWk%+Z*z4x!~=KUohg9H_o@EM%#BN1!sDz>?+Y4~l(AVEbXdEvgwJqycVT{zM69jr z%|V^bsXapm2`Vb#GdSBvBG%UR%)dLEe6vFa2`Vb#Gu-o-Fh58l*49<_%FbrO7a@ZL z6_xNAob4kKYwKDyrL)OfcyjhWCqYFed*<3$lkf5RxK7+G;Bw}q{ zrxx#OhI9`ZB&eu_&){qyiC9}#nVQ|qgh?TT1QnI=8Jz7S5o_xjJ-oZwwkTwfprR5! zgR^}kVr^Y#9qwW7+z>KIP*Dk=!P!0%v9_*$kMuGvw}%W8R8+!eaJG*`tgY*U%lepl z--iqmR8+!eaJG*`tgWlduD)jd?vO!(ic0tl&i0XrwRN2{w!bO4C1jAGq7puXvwb9D zZC$gA4>Wx~2pJ@(sD#hpY#)hOTi5#|2btb4g$xo@RKjO)wvR-tt*iIS!Dj!MkU@fq zO85-U_K}FSb^Wm6E|a@;$RI&QC47dvy9@J!Bw}q{rKSxr`>TZv5>!;eXSln&Fh58l z*4DMQ!ri9Ak#PMWK}98e250+7#M-*Hw!7O@{UBtJprR5!!#$4)^MfQ}ZC!V^xZBK~ z7&1suQ3;>H**+4nwyq_)?=~0Q5i&?nQ3;>H**+4nwyyg+3^8|94H+b;sD#hpY#)hO zTUY;)cbPZ;3FAZ(R8+!eaJG*`tgWk4=fP&q=8!>xic0tl&i0XrwRIgXG05DwC}fbJ zq7puXvwb9DZC&v$EXVvH6_xNA?)-D3OLxzCaOG1b|MD08I4aiGwdSvBrr7-C-_ySz zq@of&!_CjT(WT2E5o_z(cg{3Z{rQkVf{IG`40ryy(WT2E5o_z(koBaQ@j}QTK}98e zhMS*vqf3`TBG%S*;NGd`rbQux1QnI=8E$^wjV@gViCA0Lg2hwJkq<%!2`Vb#Gg7|> z#Aij?y3Wo$#r(4~WRReu5-w!GhFn;tbn1_>%E;WOO)yc=D*{Xrtu)-`CrWHYR7$RI&QC47ckukA*cHewiwSX$>uh$>!8M zLk0;dD&aG3wDW^*bm=lk#M-(V=YGO0oES1lP*Dk=;nr)r(WT2E5o_zpn(%~K`&P&x zK}98ehFh=gMwc#wM69hV@1;}hy+OzzK}98ehI=04Mwc#wM69jr`d_D*>A!^x5>!;e zXSnAvZggoga*>F&b=|XMs(CE$yzJwO1QnI=8E(C{8(q2#60x?fTPHqg2A>i#NKjD; zpW&XzxY4D{AQ5Zp8q|53$zM2Rkf5RxKEtiocB4y|K_b@HbyMx9%#A063=&jS!e_Yk z+HQ2|GDyVQx*pB_w0UWN*ykjusD#hpuK`KK+PW&f@w9pI(~v=eic0tl{u+=(tgUOv zEz`~UuY?Q|R8+!exb@ohDU0tb60x?f#apMFx}!n{2`Vb#Gu(P@Hy(BSgG8*YYr_>Y z%=tHm3=&jS!e_Yk+HQWrWsr!qbv^gM40A_?kU@fqO85-7UfVup@fjpyZCw{VJHvF^ zAFfd(sHlX`aO<_*Y=dhDiCA0LfSEJQwl_is2`Vb#Gu(P@H{0McNW|K@W)7TTI*$w) zB&eu_&v5It-E4!)AQ5ZpI^nz-=85Y=1_>%E;WO-2ExuorM69jr@5R&2!HOY+1QnI= z8E(C{n{9CIAQ5ZpI&}VY^UdF3yi0n zp2xV^2A4r1*47p8!gBn6kcvw9jN116o0)w-IQPFrWZT@S{(2W{>uOQEh&(wq`S)D8 zNKjD;pRv!b7u}kDKS(0h*0px*DKcni$RI&QC49z~tN*|IK@zdHu2!EHmap#(86>Ev zgwN=S^`azVZC!)UD=Z5h4jCk)7oP*Dk=G0M)* zx6EEIN+Q5up{M(YfUX(EvgwJsE^Let@i;{@7bxoX6K%RLeWRReu5EvgwL32?+4G#e!nP*SX#9|}kjy>j>FoVMf{IG`jLYr$H!1sm zkVLGltL(x;Qti5sL4t}(_>5ile(;s-`#}=1wyy5C7nc4#LIw#cD&aHiRjs}~tNgf~ zM69jr&%&q3+95P5yQ3;>1&E5|_m3==*BG%S* zZLcEIs$<9?K}98ehCBc4S>^kRM69jrrZY~JsSQI02`Vb#GwfAusl5*R3=*-nuE8&# zDnI@!WRReu5H!CbvOq}P*Dk=VXtaS?RC&+kchQ)ojI$h zeDheyAVEbXe1==EZLfp=K8i%Ft*iR)MWxGCA%g@JmGBvEy|%p$`V11Wwyw9UohHkF z3D*x2R8+!exbx3m2Ym*KSX!smE<(b zl$zB;1_>%E;WOO%=SG*VuSmq&x=Qc4Kz_R}WRReu5jIfI zEM$(w=`Kv+oB<#M-*b{!&$DP6!z!sHlX`aL;4h z=+gBSiCA0L_IoanN~=Q#2`Vb#GY;AF@44*zK@zdHuC=8ulvfUf3=&jS!e`XA=iiL% z`#}=1wyqK@E|i0XCuZ++5>!;eXSnmvjV^6pzdoYnv^IVGDuKS37^r_K96yu zOP4_+*4B0UxfjX85+Q>G6_xNA?s<$GUAhbsv9_*1KD$V^`TprR5!!;V9jy3wV}AQ5Zps(5-0>ApB*kf5RxKEqzsmfGu}&ma+N z>smIYhBO!&GDuKS37^5cI})+BuC*uElshg786>EvgwL>7wWant=)Mzkk%+Z*eRF$F z+4Eia-X%drC47dxsx7tGL7zb)*4EYO@tPu!h71x^RKjPt^UsYgT{}p`+PdbwT2ub6 z9WqEzQ3;>n&Odt{^!I}#Vr^aDy;xIL?g-af5>!;eXSm<*y4eQT4id4pu1m+%lpDr{ z3=&jS!e_Yi&y6l!28mc(*K3VxO0!Et1_>%E;WOOx7&qJCGDyVQx^CH1L+b7g<3tiv zRKjO`XwSb#v+oB<#M-)!^sOO1p9>izsHlX`aL;4h=+d==M69i=&Ue-2hu$HB1QnI= z8TIY+n8&j32T8=*y5e1!zaJz)MJ0U3_x66!J{R@vc>TPB^61e~{(2W{>*{=80crN% zQN@YJoH7#AVEbX ze1>}-<7OLNJ4nRZy2kc6Svvj@GDuKS37_H4KR3E`86;wDUBg!Alk*CW&K{SLprR5! z!#$6&*Fm2_BG%S*d$oMB`Ld8ff{IG`4Bp+5h_!VseLk<`84xl^P*Dk=;m$udx^#U- zBG%TmxOQII`BumvK}98e2Jh}j#M-)M?>b3t&Hq65{vbg`C42_&?nuPix=Ou#lH|H0 zWRReu5zXq8B)O-^nC!kH zK}98ehI^lry$-tT`7jc(wywr+pCmtZ3>hS-sD#gO=bsy0x(pJrwyyPmpCkw03>hS- zsD#gO^Yd=D!DWz$wRN3;TVBbVcWicFk)WayK7)66Bw}q{BREvgwNpJ9f??5*Wi;1 z$akNF3=&jS!e`j0oJ;I;QQr;{v9_*O3kyh*_d*5=A%g@JmGBwv{BxsAmq8-d)>XVxVY&b3Fuo!|MJ0TO zeagAiJ{N7^GDyVQy53z~NP5o+86>EvgwNpJ9f??5SG(&9$;`GPg9H_o@EN?jBN1!s znz6E=oLM^SUHQ17BrQ`3% zTs=S6G_(D!XT{aQ?fyTk!3UcwN#0#`yz=`A7s+i`Th@&zdX5l(KhAk>Bt4 zO1BU0k%!KCz}Kb!-Cw@9W6_)$R7iY2eXtyPWt>86-T0xYbJ>e3g=pTtyZLQLKd(IV-(hCa6J341 zy~$(dsSEon#0z=OmR5})_sUgcD#!;nJ?86+pQ$Xjw4JIDAI$vHlzqN~SI(;TmAU7$ z_P(yrc#El3BB|5+qe180=JV~Zdsl%%-fA) zt86cw)VV5jmv)P^-rYF0kNl_1e?0N>{yws$UQ)j^uD1-Dm(=NuaEI;oZMYM5b@TJ` z%A4;c$3mKzTeXmMc`Es=F!pgo7^CDoO8B|qPWb=MU^Z zm|s{vd+tG{cd3vFqqCeDBM#X+$s`ug%My*f=U>}{qI{v;>qlBV$KY1 z6T>Oqn_Z1Zq;TcfQ3=(t|{pyGr-c$SD4bLy!XNBhsuI6`4daLMi zPYrIh&oBOOf}ceqJP*j(4ia?n3YXq0wl+M!a-W;IPZWTSa1K$9{6KfR@3}qHE&ezS6#sMsRfZ z@Q6MlT@%+Ym-ms2CTRqf-G%$e74K)eGL93OLE^8yz2%fcS_TQaF5c2xPO73ES5%5^ z>n#tq$#(ruTSelYgT3X%$FvM?6h4HzJM7i(t}3A+Aye1Mc6r4hVG zE`RIyX2&DRQ-k0C^PSl{EUDA&xMJ=OQ*z4NzTf|OVTYNyKB@W4Ax%&r@#$ywlkz0b zA2JhkWqy`Hg+$+q-dq@nZZMjwN-SLJ#Ck{V3bC@)AL)?@PuT4%sKg6b4&H(ITA^HxMGJnyF)^!+reX( zE}jKxg4?^T@lLbpiR0-j63r+5*KA&>wVb_67q>RORa8j)`Rli)#TQxz3A)(p>5MyS z?==mUB)vGR)?TxCOj7eKNE1{@tj}*h=|*jTkf4j_W;)}((L2qcmC5=1{B^rbkIhN_ z%&iB_DOv9;*AIRJ+?9IKd6v+cJCgO`#vp$1YMb1 zUh#%5(rjk(WNXBIo#l^vl6wE%_EN0!C}p3MpzE6AU1i8-?HL(AcjK&1@?ei+W$<%J zta-nqjOndqkf5vTo;zjpXpNvUqvV~kCVS3-`YF?a-yl)@ZPKM7)>P;hC$-sLbR*pm}B(B)fPOdKS&@l+Qe$8qxw|CKq zT|3*$_IDCx@}nK3;RzG`=RW*n8yP?7Q6+;4iFaDuDShpV-<;2VNYHhAm5#FdHjSur ze>Z8;G})?0_jZ%ody~H6{cd^>QX$cxMtA9Qe?n&_=qh8+(fd$W znL9_zAVC+;f^-JwYdMlVsmN|Kre89Tnje6S{|(;57%EtU3}Dl3nt9VAwc-fPP4*S3o7po?3Z-YP02dKUP>3_MS3 z2MM~^3+W8@N!d?#o3E-QD-!rgX@UxgRafpdFFvNNXCOgWu{^s?o)fhr@$VCUG^+-@ z;rC#J7xtMlQ<9qZCF!mD>!v@<%<;)8gcmFSX(pVX)YaPMl|{L=tr|D!PxEO1L|OXt zALgS%N!{anGg+?zKE`{ArdfO^%Grdyoo= z*Z=&}bi7VGu1L_eV&9);#}4f%;n6p}{ZD4>^T#?8*>VyK${#QfK6A{zg6qf4znJJ|BGK}f-^{O7wG6g{F7{!14^km<=jFefzrNLuL=trIY))s~_3Z*P zuU&Kh%`h};scBQPg|E+fb%|-;CaKfJW!J1WufN>JyLP<2%Cxw@t*>7h`@Si7V@qGB ziA~S0w8U**34g)fjaYXaS!e3jxI-cMSzhwKVzAh zGv{WnT)X}~Q~0f<&im{;=A7nD6yk+%mY6?QB<*NDdZ~FlU$Q0K!gR~2ka$VnGqY-I z?co04KKQ%Oi{_Vk*DG5^g~a!jmzeqswLM6Ju1{9HYdV~Ei;_X*k74hcKL;f)ep0&S zR7mu0`>y$Jhn7Ktt}310HHVtqs%#Z|adY8i=Al-{vp-0@wqu#Op}V#}xCiOVd?fN{ z=TUiYzLn<9gUQj8?kg%J#@@fy?0-f(KSfQtDkO&0Tw}J?Zmsk#3A%W0 zrrSY<#NIPMFpuofGDy(H@0fJPOG7rALgyss^D}EcHBYWj>PDx2VwSzEo#(kfUuDjE zJUM>G9a?3oS50buQsxX2>wjKl&R(V+yZp}JcL~qtbOsd?h4Q^;Zr_o76J;jo;>t{GWUJ9bIXH79F{`KZ4}aDQ+god4)5v*@sPo>L)_ zd7qP@i&utp%c+p4as3AK)&lLgB0*Q?D^9aBR+xbslYLvU@%v`n{9|2lcwCXVYT$CS zYNmFSkf4iKyL8KM&bP`mnUY*5n%}k3l)oma`AKPl3W=$otT4m#YF8W*bg@U$89dki zTDi*9yd^pBxc}1x6%wrmtum7iYFkBuF7`+|W6|NArsNArzt{NlGc*0Z{QG&iOqRf(nUYi$6ENmDVyy(Dkp6zA#txxKqh^>#GgswC9u7cKTt1dG6(; zzODRvbJ>`rPWLVq5|cN6WLEa;tYnlQy~-4=m;9pQwr#7-yyD5PE;9d`qeYpg&B}5^ z{AaB{u-07sdD7a<8B|D=81kWc$Y|{#K^NQi|7$t6z0!!)ruKKoY6n|LVodiBOvky} z{vbgYdnCP8R7iB4w8nI8q8%k9=wiR6Gq?xOI&r0W>i*0wC(Rn(9 ztDw0$o~x$Q1Qilolb)HNYnJ>=>WCeC`E472>xb_za@LKqkRih zg~`f3r$VCeYZc|fD<&O-plko2O0v7uqY6Rg`;C?4=UvH~L}sUZmkNn$?^lvn>>K`a z&Owr(i~W|)phBWyqe?R4Zf!n_1YMc;2Y=hgeUs;+ax$c(wm+zlXfd#&oc7W*rR5~( z8dJKgeDRK!L50LmT`NerB2Ot9BP@d7)iT20 z{BW-Dw>ey0{OnWZ{w%E>R7ixsy5Z>bKBp4?ZpQzfK_dJ`jGP(VD!Rhox5!Dbf5KmO zaIVaKMTJE8n+-WLNYEAj0z*!MO86TJ|NB;v2!91{D&G`<9g7dT1FW=*qkYsgUTrxwH(cre%OhOwje|+3U>-4Ym6yDkQd@P*C!`s@)aw833PB@a{gnRa8jujUJf^ zy2f_;k7@UP@?#EzM6aXip}nkSNf#y*WB>m~ym}pzHoMP0hF;M<@gp5`UaLz?}Zvu?V{Mthmy& zKTmsJ(re{lvwuu-_4;AMT_$(yq@LbvyjeYWin3K5I}bKXm4`3C6qc>{CnXURSJX`8#6hTkT1dVf$M@j|J~%|}DDGl~RVOaIl~ ztXQIDblKI{tlyoqw$j-CrsS5S{`BgB#>~;~YpIZ!ReYf7`$0md+d+b^%)Lv6#PX4Y zOz)Sp3=(v4&!)GEdyspr-^jbnTmNW%#XZ>hXlK)~PR_lV&fs1n@y4Le=G30r)qn(D z&-}Zy$v0agsFc03vzhS4@oW`|RZ}{fyoI&i za(hzqSV;F36%ti1>tpJDuVs*+i^p_2gXebXX+zBZYRTvF=t&b)NUW=Hx2bSM+aDz8 z+S=}JQ}qLl;P*%S83W9QCy(`A!sC@hkplhA7vr>Jmjqoc+VwSuhHC_sQm^+mcaA)s zts-&9X}wIT30elXimvS=dYI+2G~(3aUCog0$zD6NW;Zio((xQuBpw*v-E3QQtmBF< z9@FWgg!}f+7I&Mu6O;YSVv$}Kg%psjI>h8x)!{YP(Rruxt_nCj4`LeH@JTTgn zT=b%Hb*4h1P1UaE!rspvgP`k*D{eK1M$T46>7femD9IOF-ONP@-??Mb2~`L zr{m3$dz1EMCg@_D(gc5n$zKNYSDR^q3W?2?x0}tQv|neEpo{PEOJ`i#?K1iI{N=uX zo-bQXYMi&i*LMx6CjYLm#Mfzp3W+}^R+KqstULxm*MsxUlpo$o^3oYpNG#u3Qt}Vd zGDy(X^GFf7^Pabrt)fEWgz81)mTR>P5_Iu5nCW&q->;{H!(thuY1 zG@G^9xA2Rd&1Bn*q+W2|4RT6#?Kh(*>}Vo4PfN~;4o^3cD_14;{cW$77xrlD^r?`z zrCSqe@moTtw`yLYEV;j9vL&y+f0KM=l6}x|esdWyJo)!DL4`!-c95WJb<^fj`Ef0S z3JLaGdaF*nwV4d8pS19dpPNdRYm&OnBhBRJr?uZrP$4n!!KSjYmDX1z=wh#@w~7jh z3#vDjO@p-z5_IucNM~>le%UHZj!MqGnI^c`NDQ8yC8w3t_6G^NuFiLd-13!1P$4n$ zQ@e$GURTa@9;4l_X(Hv%OI+-cbUUb!c=oa;QsQNb%X6E&jYA5COtv!sP* zHEAk8_eyFWmFcaT+%QWPJ)G>@cMmj|j=hfONF?$2qs?XeP1;eyEot~dQyDn+SX;&I zCGk~}X3~ACwg*Yj#qY6n%elR|FKjM9WWPt2=S`ZRLZaA;W|FU-)^ZYb@%&F`aNquP zT@xw3`go2j67}zDBH#U?9VI-j=rZ%0$oO-#-sO4F`(T#TTAX|?&zp2RsF0|2;&oDQ zxVBX!=xUMsI(fZ`MsSqD@xv>vu8?^P-&4+7DkMtYe3iV>MB9TT=sM$zCi2&%+DL{9 z3HExruSn3vV>(SxA(43xlAw#<80if5`@X$dQoqFU>~j)Nt;mvIyS3isKBsHygITif z4UPC$p}vxJdvXu3s(yE=yY&^npO1F$D7`;;UfJhVNc4U1PMKdo8<&uvYv*+>};C(zmy6NGMpZ#C7mLb!Uy2IYqGCp5_<+%FlmNrt@boI(BC%2JP$0YSt2UN85Ll zD^}g1><84 zRzZ|7Aa^LPBRI=*rwz+}{2J+Q}PtA5UMADE4JL>2jmia`qKnY+vSfkZ4(} zy>u+2W$?4;Vy~w&_?^M4D8FOU1Qimz5@jan`tpOD<@s~6l%t&ri9GfR+o-aQ6{5n3 ztK_#cZt%*J(`(DWf4bb)T}EChz4A3w2>wN#zO62jzqi-(F8+0$bUUb!xUxtcxqW66 zC4&TAC70HgHs2qMIO(F=^51&R{pa4)qP7g5nbhg6x}WP+{ zYs+s?^v4pIcjgKdKQ_ z-Ys5Rc6DiX99u==$x^lD;HHGmyj65@-=qodk5*&q$c*JV_f4AMJ|J;mUmbaHr?v-4 z(6y~aUCFXfb#h*Dey&|#7F?VtJXco!P)}YTsu5I3Fgx825_H`&p`N_CP|M)Wi^7zwcpm4Y73L&m7kP(t4Q?NR$t0pqaE%1EV}ZntuNKLYvihbi&rXunqv|Th z6%`VPp2#f)@48kY_-+Bd6@kC{Pj3|!5?7zT!3_GUk&;1zF8+o;ok4}fvIo933tNkl zL4vN#EvG`_xepJSJbRO#PHzayhc*?M6?88JDj+3Nu8 z-weC`xxzAO|24iBn-)DqDu0>OujR^X-%fg+(z}Ni7m@mvkW_7u)I1;48Qk_C`=26T%|BK<*g_Ju zK0ZZ0zbm2B86@apo6-ao60OVGzN(>Rkf1AbU$KAwZeB=+c05*Ju@^}!I9O2bds@3I zB0*Q??ya@LgI43A%Vpr+b$~!CVF9j8CufN8*4p3d)IfwBw4$?pv#iNY?y> zV6Ue$sF2vYqKKGA37wgstM4mCz#7Coq)QB0?6U5`StY^g?2X}htIyu9Ohwu(gadWEI$0WE`DMHj!1(|yI`r^1*b zvf!>{pYsS!6I4i)%PJz>%4$a<3A%Xxr!%OKI5U3{X|P^9&q>h5vml+pbK-#mh2{B6 zj&*)8gT#~v3d_!OjE@k*55Dn3Kv6DW>@(*zX~e3q4&po@2}X@Uxgs#}`NxtI4+ zuID7^+OnaVoI1CILQo-*tN!KE{L|!}Jn5|>LDx@t%1XaYeUyxpg3m41_d@w1*T`cK zbn%@d>8;|78)p~UZ)t)G2|mTmOwg6;Hz30rP$6;6<`#0_iCXWHNV(8&h_ItR?gJ8M z{`+dVVVyRnCP5c_I-Nm{#ufiz|}STSbM$*uQ&7t*5mN5_Fx{ zpr>5bUn8j0>f2LlHB4Omq|94IqMV)G?Q)uy!Ox;==j@)+cdK?rQOP^Ar|f+;aq*Kf zZxxAY<9kZKep&`Ui>{^}ddh605mXvi?I}l#9nV&gxN27q`C)HzRAz1mU73$vDkQo; z(nF@M)iOxX#q%b;RXmH9x3}vopE%YT#S9V){;=N?Q;xM&bgh`sP1?-S2r8ATc9WCe zIG(K{vGwDwl7Ewy!FJHat3G-a=i{Gpwjc_9KdXMes&YuGEF{%7MhiPs+SiBucEf zP!1N>-lW6NqHAvdYEq)KMo>BZ+>2ykiNwWE%Dh!1{`l-7*^*bw;Ahd5duVkjwOi{e zDiu$!A>9`rPhXK(Hl>C%7^-D(tLVynk3)sT+LP^@JTK8QNYJ(Q_L{QiJMG(tN~gzb ziaeUQ_(|#gL50M;S8K}OwY3Zqbba??OL(gCywUbvK>Cl>?Qll$JMhpsVGY^0IK3_8UbiB>1b=bOztoHgEMvbFlJIzwKuh9cg}Vm(*!u z?B3yK(~(5!Gitc`t7Y;|IKGuFO)!I>o0*_OVs-Bk=C9|qts+4ew>G_1-1aGExOsTl zvD(255=GA*Ztkseud>fc(DmWD!_9vl*NDOEN10+bB=5|-an@+_+igkBH`t}yL4`!$ z!4H_xwO-{pfF_xL2i$`dh;PxK5biAotKiPJ+FHKM( zacK28^X<3Vu}gw3wlAGQg~Wl&#+k(vwG0w;vDecX{JTs1dsY04N@;=$3I1KF%miKh z%SUN~3W=ZcY%>E2Yrn!KK^J>Hok4}fD@|T8wYLseuFfRr;<=g5ph9BP!tv(E{@UsU z5_DyL3oR8Ad`n__t4PqrcfY0yDkL($aghXFncpe9xx&9vQ?v4rx{+;^tR*|5q`0(G%hSRmX zJ1QhH|IPbfv)aq;U6LnTyLPsh?e8QtkNosjQ6cg0k8NbU`UZXybn(bfXHX$At6X!b zTV$$o?2@31M}9hk3W*0!x?Gk&tDPSt=;D!|&Y(gfPs2;)on6|oOMEenquYpFe z7iY{aFVpfK&mJU^`||Q~Whw2OfqRfH9{K6MqC(=0o#mwAC0Ygvy7>K=&fs^(fesbq z*9OOPl#saWy$W)m!m*ALy11XxTSbLLhg0nllS|7WK^Kp=bOw)xZx>dSa|#^Kkw{|D z^osJzXWIVYR?&6d;EJ+swnk8?ba_RoGca-SlhW;=LgMT{E66#`v)ak9FLW1uB%}mh6 zJMT0>g#_0?XC~<4op+j`LV~LnG81(1&O1#|A;C2WnF+dh=ba{~kl-4G%miJ$^G*{~ zNN^28W`Zu>d8Y{~B)A44GeH;cywd~~61)ayCg|dwcbcF=f+Nn%1YLQ@>@#cDzNLIq zQz5~>r;*MeLDwC%_nHPv-c~ZGkoc_BUUSK>8o|G?$iLOeZ`AZwQ6a&jhfD&LSlF2mrTcZv|l2Tpo@QrD4jut#Qa>-%=WjQRocP7 zS<1gs%3erkP$9v;2b!6ni@lI0sE`=c@@sSNO^5WiC3V-vo6Mb!UQ@P;3WDaf--M!yY+Chax=D*a`IQJ7~ z(ZrYiXYnstUHQmlbLySRzo*+lg#`ZwS7w5)xiZ<9npy@G5}y{IY}Wjv&B}b(<_RkdMpBbbZxt01g9c1C!`f;Y{b$ZF+ulf&nFD8-&LfjL^O3mbuW6>({AAvV z$MM0HPnrD7wfQJ2BrYHRw3+a=Ml4u7#T@w{XU2hhr<$A8zm~?oyvA?4%zyig3JGpu zx_3#?#a>SnR7jkidy4sIr`B>3bn#e7XK>$6uRhsaJL!0i5)%J9ZL*Oy+EK!-qAT;U z%X2Vm!V_lgTRG3ibUS$7k;r@L6#ExlwKIwYUDy9Q#Z3QABY1?LaNZ2_#P!EI+Ib$3 z_E?v1Lff3js~yKZVorUc_;Dqj z!L>``oi-1f>2v>Td(f5pc*XWUe$RB%zRv#ioWv=QPdD9m{?(pH7mxYro^wlG+4!I4 ziUam%FCpGpZ+|yu2vme}naGwe$V6SW^3EzobqR z{#SIO_}{Kc%_XG?pDr%nDye;IrA`z6v$G@GePPa9CHFR^_Mfkd5&r$9qWE`|N$u}) z6eIk54Mp*9NR-;Y$*>sV-@zk_|K?6=|Bj)AkTvW6qKtoYjwpUcQmOshbrM4Dj_`A% zisENalG@L5RE+R5@QdPSFq7KPY*vgY+*R5RYbL)S7UjV8rL8G1zp0hlUm+JG{H&*< z_?b?fE13bc7%`^LA-3zbk-FSIN0+wueG=FH+xlVz6%wDVE^SX-6Vtj{{kkGSSNEZ1 zY^$$|5V}3?oOy`-+X{J-RMO`(C}(^8^IomXTwdB<@?re%K0^sABnBT;#%_KOL=@{bO`*V9ZEOP6L3W?(em$UuOz%~yObZs3`!7lty zD1!=#G2fT9)B7SrTBI=<5_Fw6ue|-}U*iM)phBYSwPkI~X`u`fbaBs*+av#t+`6Jd z;`#+;Y=u{mp`9p7&{b?id4l8l#pBD`2maWfV+o1r%gWkgPW-Dqk* zXBMw0XZy~Ml`8eh+q=JuYwn@03;Gv1f(nU;yOy`3&I^rm5_Gi~Ti*UWwFn_WQHDz8 z3FU3W-LZ>Hiksx@MO#JUt^VchfEIr>qUhpyOlSCen{phSGWj5TXN7pVJjQs!H7s?! zBJuvjgX{$_7U{Y6gUh0;*ils6?k~#lY|wCTDZ62AyuWgvj=j$A2r49+U0=#x6aCfR zPS@~v54Im(7$Q!%_F#MP!LhRX*Msctf5+>J>oDCaDkLs`Mi!(qvNyXyO-Z$2knlJIR1`lvGX|<5^q<(#eT3nbi5*wa^?J#!OtHg?%dti z9{7Ku3=(uzUfb7>?+_xWobh>Idrwjt$iC?z&wTJEroekJ3x;B-+#h&+ih@kTQ zxwqI;CS_g!Q>#e)WB4uB_6%jPRdg--;1;{&f)K&axCb`uXEP_pu2~cN*`un22r3iz z^|PJI#V#%>-Ur=o==MY^BxZEI)$T46${<14gm-VXYYqz$RO+7D-@a96e_BQ2l1csT zW#<&h&=JK}(Utq!fC`CvTl(7>?TcjSx*|c>@eK#qg`>E zuYJVm|Dp_+RlnN+d)ZM^g(gKhV3Tg}xE z&0r5n95!Hp-M%n%WFSG;!FGWCeN%|&@q9mfb@%uv>Yp!>R`JN^`=PC(Lc%}W@?Vd; zbnyu8Go*+zY;X5J`rB_R#w}$3JfW?kLc+iCHffc(-CvX;K^L#1W3RJ2f(i-$hTSB? zVZ{i#uKey+TcvZ{CueqU_ZMZTbiL?NMB3{n-pEwXWG>*54nyxTG{eg+!ktwwi8F z7ReAa-732L(-+0I2Ne=^7H>5#zEvbcdrpF`6E4|i-r5a9-0m;R+*SK4GjpummzDIv zlQx*~9pjqc8pU2`cLWs@{pxNoTTYMZ+yq^@zm1|o;{A`-o2n&486@cXeeQZQW3@by zQf%!~Id6_EcS`KylG6R4LgKBZ>rL&>p$rmq%|2v>_OOlSq>-_UOUm6U z62E=5(F`6E%HXo-;!(n9ND*Z?avHv}&GfAuZx4<%C8C&&eg<&LFyZ4PbodV17q&)M7G)@(C*$HheM zo>L*QvF|oh`N~i~NYM58_N}JGP!N&!M)nf6ec0QZP5t-(OFx8)GVCFV+50w`b)O@{ zMHD0G8dYzTY5ir0;J41a7O8uA58G-+{2icMy#7V5RsPqqvj3d-c}II;nfr7bv>V&e z4x1S|JNsY43*moLFLmzwA9GIVWN#f8e@g8u@20MHdR!MHq($ye)^76q{36TE-Kyb3 zyW5}djC;u5`u7mXlH#Su|BW(KNN~M*B66)FK^Lz}ln}T3OJ8}B_}{Jv>Eg9vymS}f zG6r1N+1B0`_k4QQE_T(kah+;yf+#_SM1!qe?3z)by@cC&#^8?jsEb#}w~7jh z;Wc~P{4+yW!X)V8-s3a0Roqg2_w=-LX2)BNOY%fibT1*%t94KN=+4kK=d$Q3wztdj z-Jjgy#j?)5zlYs({C^oAkt4V)5(}1ew_7ibX3aRiqJ;@#_KKnB@ar(*0-tkZoq_xpB>_zSx@( zC12WW3N!KOeDcJ-X2J>aIQPFEO8Vh|$n}E?iC?b#*~}Oh)A7<1g6V7(j~Ho!3W-+7 zY&B=>3uTa?i^nma;To3l^Or~u{hTFIvwxn5iuRnui+lH)u9t?6a9kE$T*q>IBD44s$96bdY8c?(!baA9Qt5j(|@HMl1MqK-Mp%=?o|H^XH_U;>%cy`R|rtB5hY5nfP*UW$(ah>kR&yT!q z+OCV+-srM-%**rRy3$F@&1ctK8)y|X&c0}cdGYBE#q!b_Yzc|&$E-B>Z@nRqL4vO6 zv{hzp;}F4qurc;Nux@~XUFyB1Wv9;D)PAoL}3*vuIw~7jh zVq?%}kf7_mrHf7H!{QOF8J?g*f@412D)!@!HW|~QYVkgKLW(HEwv#AV>Q&QjeSDPg zL{yZZEBCR43W-ZrziP_A9LgX;7ms7>*VBuad|+|+mwglup37iBnd zZWxs@50=`WQA=X(mxbo%r8r(`K+$nd*X%Zh=I#C=;?Z@B&4{Y8^2hy)&BhnvwsWj# z2Ydz<67{<+HhWs2=Rtxlo`Zdc6jA1vWy{TJSI6Ud^>@on?Im%|HSLK=*Y1!HOu6IY zvn7eKdzPD18-!ZLWzkh^3%Vf9;6B>=wq>T)Me+X1QQ*w_7r9nZA#qiy<)+1y(B4jh zF19wCkZlze64wt}ZYJ#xWssnYYdxJ&Yt(X6>6}hF4jK+wZc4T9sCA74mzjUw9oK1s z3JIQ9aualMe@hcoNaWtzNzlbnpczq|6lK_R_UYQS%gr-YRoS`Gd_;j zbZ&w!u4zw55oKyL{M6j}Q9Ppj`*>vi_}QV7b(O`U3|;aoUbdKMYtc7IWZN{t;KnuqGfTa8PKz0U3kDkKhR^?|u_U}&3@ zpv%uNU#uVgy-T93?fj{Ey=r_^d#~@O=Ix)09O1Md{vDt~`1gKF?ce!SEMrUG56uNf z#8)Pb_I_lh4UKF6#?oR06%v!L`q=a=6T0$ZtJsp;?)t>sJP(AdS@#!Z_@p(Tt>&}b zvDeuhL4^dLnpQ&G?k`Qy%|GDy%hae5j1*s~9(w}*tu zx6ZW=v+r+>l_t#&v*(+5x!f1ht)fEWfQt{acT5eniUeI8E1D6-N%Cwh_J&Jtu3)e4 z8gFOrJ?U0aA<^yCL+$BPFYui*Wvdts6&8d*!-jmKCLDyqHma(VYhzwc2`;%w9ppXde ziIF4NkDG^;vjgT8?~^WE102D&lNfw_c{~3fF`b*B>-vw&+t2O_5meq7bEqA3$Nsd6 zMBBy{?89S@P_1Cb%icYpG^9SVs{%T=;FOJToKdr^X}r-oIsi!KfkJi^VW zakM?XZrqZC*HyBs9}E#xNOWIQ-9`=358o;hbmeXp6%rTst7?Dj6Urb#7uTU{kp4w( zU9smp2D49Dzt|l?g@k{5OtDV@BjxDQ<)5!>Pd;zbU$lxYZl`nx6%x%y*Rd>r)u=hK)Sw@3b4EQ7?^)#}*yTNQcQ&_Stw(8WD8ok4}fo(^?w zg=<33s*#|J`*Avhzh&pI*EtJ=C$t|_NaX%CISIP_OyI>v6crLP?UA* zpMhVNd(bJ3?N{f-_c{GM`^C242{W78*H37ntvagQIrg5jHTqC|! zQl!@viSa#~*lT;B=MIaC5_ECBIkWynj-W!K{^};StPN$5psU#Sa3Pw(z3=H;&at;% z7cZAfa%TODinfZx2k)F?hu-&Bt)lDcI{Eh4_d-O;H}dVN>ssnQ%2}D_&&;bZ&yKQSay5V~&lF z5}wdjQJMN&zI}dp>|(YjBG(TpB<{O2-+r>bNJcS&uJ0P>+xcf;e2ClqMH!Bq>qj@S z(_h=4QA^^?6Pwsc6Of?+E`y_%uItt`wm-HA5j@sDT&=O){b9TfcK`Jg zTyf(Kc2eos#cbDU{fpeXqC%qTEjQT5ruF)ZR?&6P12@=8jf)Tx6lJ#TX>aeU&{miA z>h>G$t*heo^GBzy_Ppio0~u6EJac77d)9wKYnRG-uXMC^_U%swi5^uu*@h?gOt(t= z!B)}r)4txe^qHZ%mUNxpr;}aXH(qXTf(nV|^1I8uuNG;QZb1@sUHnZaYmP3mJ(Sq` zR6o1Dd0*|}F-Lc{Z!eDbl2d=_WINUg?d>G4JH3$lc0;OO=nOc@#)naY-zAk?pZg3FbhUhCh<#%6j6eI~2`VIZ{C%*^oHFZA!gWKaC_{p-$G#qD z>r8$uKu{s^NAIq-@5(3sBz&t#&~;?Fezr}!C;udTt2*4@%6|8#yx~OF$%Uob+p9la zsP)&EwzYdYJeww5S29#c^c&yB&MOo8)fNf5*h1GJ{fk@%6%xzyd)ua8gjz*{u3|lx z<-5Nqv!Z2dd*Xv}Z$J6Em0deMuIC?rxjppMMd_YLj<~v43)}X`_*Z6~A8ldJUmn+Y z-*};&yEW8vx(-<1!d~^rUlCjuiIYxkX+Ins)7k;;gliQEy0~T21m}q6+|jvvPK89* zd9Cg6VexuPXON(aYduY{?E}ZRv>#j__cnJwsE|0~yOy^8MWJ;?g02IvX=MlIgNWj` zMH%klBi?Ug|JeGX?ipN%>3&clF?d=Vdsx-bx*|ar=lIqP-zx5}t8Qy$Th08deV5yV z#HSTn+1^t_ts+5Jv$-wpz%e0WWYZRQ`owtsJTBj&9@Q?cxre6L6%`V_FKS_H9Us%V z3A#8o(*(C|<)y7`sdM&czamlMMMF_1a`?-ak(JHhja^I!P%xhuC9Ty^~4V+jema<__ak6;Ubo>?^E%=XU+OQnJEMcTj<|d%8bahiUeIZFB@!jjz)&K z-Cw#@^~Ur!RX;D@!r1HVMSD)7$HsnU^(JIEtQbL8gR^fj=WGcPZ2K1-Z#NBAKB(*M z%{sT6I={uWTfAGo`;+;|u&n;~-)yd1w?F+LQFC7()8(B|tGEs5x@TB#v-X7$v3yE* zb8z`sIrjYSX2K_N+qs9vJ#d|H{h&hPvA=gWrDmb$4l72`_0pj3rs7Q@f=c&4x|?QA z_NP@Oro7q1G%6R$U_a=ZTkTx)_K^E@Yq~DzU*vjDg~VZNdYWb%{x3jej_hrg7RJiD z;eE_&GvnI7-@VxQphBYkVKt|7*A&0m}63Wd3+2(t7LC^G&DY#{`ZH zR7l*ts-+qGO}wOd=`O%!@b|T?`}a0KuD`WdUYg)?N$jg|o%wd|oqx7Umhb+e3<9Ca92j?5oJU@KEU9 z1PQvh-ZUeMlcJ1&!>Syw{M%@y=BL4QtEiChZ@*2>20nv|f5YzooI%3B(KpF(O_QAT zr&qf8N!FS5FLDGG5?7TOYL0YoGcT6m-v=p*f8(vx{tdgu2(Byto>6i6HFK{K;GRk~ad&vizG{rDp#U zcbq|mgntKYu~w0wi~UPyP$A*pOj|621YO*Z(;5Da>9Q>UPG_n8n~95MP$A*p4oyPB zq73&2|2|=HagC%~MTLZamoYOUmqCIqZrOAOM~;8fxGa|=Elp4%;oodttW_lF@^4Zv zM)>#9i{jtuEH&49x>Zz2__sqB%V7G1&nBBbjh@mYCtI7&phCjGE529;3A)(YbOsd? z{@wJ&GDy(Hb(qfJI`Qw@{-4(_3IDF||Jo|LIMTFLQQWpDQ-C>eIm;?%txWfW3W;Lh z6gez%>1g9-_LGo^$q-~FZE=0R8R8!sj9t2D-(&?NrE%1^R2R*o^p*NFdJ z7oPo(e1?NUf-|9bB66)FLDzupV@->nh6X+}@DtfL_l-2OOWvWbH#>|njd$K2Ah_K6 z3&)w21MX7StjXidi)-UrTO}=Wf3iK$^EMZcHt)46z7}Gyvpa&lCDCv2J!aH3Mb=d@ zg03rOjxs-98zR`lEoa_iuHPQ_mTM&4Dk>zFmKkko?F+3d5_En0(P&ftn0QV53@M@v z*W#O(k29Avi?P$4mY$5_*ER%n}(psUzkBFlGwQHE=A@amDK^5y%p1xd6l zIno?sL)(MfoURhhN0`aShluHy4KsKA5$|zt{cV`J_rbX4^;O&h*9q4TDkLh^9%k;U zkA2r+N>G_%hM9jXiLdCmBxlyYsAvX>TSg8uzg&mwL5CD0=o+(qnECLxB72DvR95sI zZhmL+5%!(0a_lcnl5_IuMlugL4D~_Bd z6UUgUZQ|u}Noj%#iCt%pH47&eX_cVqe$d5nlg^+*V$X`PX2XUe8Ij8%LDz3*jWZ|a z7uid+Ra71sHO{;-BX)5~xm!h|@4Rv5-(^C3JC{WlkMo)#eQKLH$hi^w>QmYKRg;ZJ5wRSZ$Hx+Blj51YUh@YpV ztJrrkkpe<+-Y9N=&P)<}U4YA=LW0{VH$m5+>pnAgT^ZVfR7h|;r87v-RinltGx6BD zf37QsMXn!INN_u)Gf2?I>)kX#g+%cBTw6tgE`DF88RB+-@+(u!n8j_wS$txzvpa$c z39iH31YLX^Lz!BBy7)vvnxH}=_~bz3 zwjc?*M&I#-sdL)D1ABXkb8Ff2s}-tp-Ktu4!N&Nx;FrFxX`7uH|9iSsR7mjYlr+JN z>9cCtM-DEYmnOJe5);bRwww1Y4)lWrU5^f`Z3q7nBB+dCU)x@L!2Yy~M6Kp^Y@5oV zb;VZE)qGAJyQV=ALRNvyPPwqIeWoCzJ>2(rT|1|LT=S`?^tz%#qQa=Uw(sLHotrrO z)jD=pomVxF&oHG4DkOGwu48{Fi0Rw}U6+-pV;{a8L=hgLm`*~Xs;&y*ghRVC`YS~Q}>`$vm%>ARL?Qjw@G@xj!=z8bL znzmB85K-~F8n$Aac-uDGQNxa@7T3AQAQcjOeyw3AZY;7VMy^#P=-O~>O}pax5J6?< zr8Vt>;jxQLa-G({sAvX>dnZZ8HK7bHi!L6OvI!F4GC0<1@2z8xYZWh-<0ef|AyMz# zy0*!{P^(DLb^PGEcI~VpgoH&Ij?R*o*R{jf?9VtS(Yd0G^Ssbr!dB765$t=etzvrz zO{;64{b+yI6^RWC>e}PV{MFHiE*|-`RZ-lwD8q5^R_B`b*RSH`ax}+Y`L9svaZX}Y zgPQj07elS$vgqRemd>C;V#q-??dTDq3=(v4G^aE8>=2(8;ji_ai< zLJIi>D4ts&@!^7T=9~V1^*jSzyh8RFk;|Y$;@K9@n#NxY3w#0~K^MOpNM}$X@omYq zW_Va@$>fXof*z4?$phDvC zznx+i92L{K3A*O=Z)lII9wOM@k~2=R)lZDu&ik_(DtB0;+f}8v%fa}M_`-X2-|=bJWt4?e6mXv+t64v)ak_*uH$fN2rV>%i$-N?MsbjxyU}sE- zw;K1ibOsd?OK)#r-)|Ax<|OFimQ80+A<^^L26jnaD1!uD+~3j}+#B*sHL%CEiT4aH zDNRrzaoP0^?7R}8{fY!#*S*=mzWYj%y(DsbJC&c?oMdN4v5QN}-6|5*x1MBwyfl=- zWzoewG@U_(MBND|+tW@BWssnY=iPJ$ug`hK%J0t71QineC1P%Zu6?u5wx?H!pR7s~ zR7mibnz;$OIz89e)_W>6mjx9P{Do^eg9Kf6-MO~cjhJD>VUgRfsF2_s7wHTVbSebu?Led3~gUDm_%%h?76@w{_mk1lUtJ0Y&q z#ESl9?e@JFDzUU_Sv%{|xaM55o{&QB@IF|YzkC_j)849L-*0k$x*w4v zsF1j!rYxxu`XO%jCo{KT{j~d6c{^$6e_2v=>&6et*{9co zkmW0sq4H**a&}2(e_BOiPK9#zh4IMHfTFFU>y1~++A0@^h^;r4wb!2=&lfy;c3C@Y zW4xV%TQG7NR7lL$wTKIFEFi zph6-zcXZ_T5)yRfo}Ze>j{!%NwFfr&FUJziU`t4p%`0n5AGHs zxTWk1huRtA_Gd34aZKq7wqP~3d3F^?8SYnf@yM6n9#lxwY*WGZI=0B{--1RNDs@Iz zu=8(=U0hP`3=;jGtza+vqDV&MGPo?dzF1npnhT1oU2PSWmseDNG zl%YbRugpkV?euYf5^66>&^6$?&bIb8v?_9lBifDaXotY2i{fWyQRnx zR7mi;T^FtaMG3k#zjU$v+mWH)zEUBD1YOO) zXk;J%W?CSF3JJb%CY?couI^7aus5DHGmt@r1mDM#&LEL;&8%&<`pkI117kBrl8-B}|Vi%X>%=#C(eo!G%eQOVU)$mXT3A##^?P|5v_&#Bu47aW~mpZ;iJavprEPgT%ozZnE1S z4{dWUi>|L{-DLZHQG}2%nF$(7O?mf6kHg|I!6oHx6^YaP-DFR178+4p7G1{|++>^g zFG6UmsEqlwk3Id-{b?16_D}V(FD@yPQEctf#Uo$3=Tt}>acLjB@QY9e3A%VDN@s99 zSI+Ng2iJLWa})`>c;`0(;!iSENbqVYH$fNgd8Y{~BzU!yo1lyL?$ZPn z61=|3P0+>XtkVP)5(kgoVOG8Ia$wYwpo{b5rZcFJn0fkkvvBk)feaFKwQs!L6cmDp z;-vIjt^Tv}D*ME7ZFISOPfNO0R7mj6X}JlycqU2{R7eziH=x5Jx3`m^EBE_SCtvlk z=~?Cm?d@%MePV8&7uUSs=3C`rQg`A=G9{oR7iaOPD5L9PUk=d3A(t}(-~AqH2A!={oA=W2Qo;|#r-XvL4^e0kL8KT zZ9x)r@jZB+kV5Vo;0<{sioH`$mhb+eOt)@>Y|F21(;o6IQ>9Dvwo~d43-p`{3FgI1 zcL6Sg1YH-cX={fbI3$okg#_1II)g;Ym4B{n{eCDT4+;rx|8xcky1p%WtiAQaTLS%{ zLW28oI)emVBli7ncAe2ZkU@n6$74E!1YLD5{@k2?RHr}&6%vn?{nQ*+5SpEm1YK)8 ze`;Q@+A*CW&5JVc_5IYm{d26;X!xnQ^P{*WT$1mH5>!a=R~Md$Tm}icxJEpo8B|E{ z-lQiqg9KgNvYyZkDkOMs(i56NBIUw9?Fr4`zDt7lCOx4UBu zbn%Gc3C*BFqWa(a+bu8Nlisg1g9Keuj=kMh`04HdL4`#6-Df3RmMLi0r)`02pMU2= z!|Lbzw^gv#nb?jzvZVseaJqYt1-l@8bLq{@q72sQ6kk_zsP{JP>)_CCj4A*P3y~;p6j1HW{cH zRD3NNe4j>M9*8{el4a55Yt1;m+o|~_Yu%w4RD3NNd;>>b9*8{el4a55Yt8uVp8L}Ji^IygpRD3NNd;>>b9*8{el4a55Yt6W7 zLFvMmp1M=}LB-dS!8dT^<$=iaE?E{`zSfLKTHR83?HhwNgNm;uBmLeC5P9Au%c9HI zno;(oCky{`{wB@Tv_X&Ot~kn)eI`WmJH5wn3o44&%0z z-X+VT%h#H*w@kxKiPeoYgNm;ugEM;M<$=iaE?E{`zSfK}mzm7r@BK|PsQ6kkID2zm z9*8{el4a55Yt6Xt-b*u2m#geD@~HS)GSagSmv z<>eyi^0j7+JFQpdljGjd3@W~s49>ljmzRs6%h#ImE39WboZAd3m`A zx_qq}7j7PsdAju_nnA_alEF8|B@WZt?f^TpxI&vDy>imxSubNT1xiJaWl-_8Wbn7|d3m`Ax_qq})rQ=a`Jm$3#V&)2uO)-Oeb39wMbPDI z%~)@TWJXMFTj(;V_*yd3^Xcaz=<>B@jO=`CX4AY!HG_(;C4=+#=jG)h=<>B@JiDt$ zX4U3*G=qw-B_lmMelCJ8Uu(vJ2e!}Lw)J<-pyF%E;B5SPdASI>e61NDywWfs|Y zZhKJiwPf%e0eN}32)cZ&8T$$fGOso`Q8TFcS~B>qgS@<41YN$?jB1M;WcGdAR5Pgf zS~B=H2HAIW5On!kGrG(^CNpfoMVdjy*OGDDhWX~1j`E~zida-;aa}4wLg>7_=gL*i zjF)qW5VJ}6T3iP|zQ`Qcx3cELrHniaTh?p>nzS_uEnK_BIxq9X1uthdBMZgYH9`*U(0g+yM;9)7eSY= zHDk~5Z40hiSVl9b_*$0h-&w2~xd^&^tr?eH*ty{9g`4x;_MqZxS+0Lmv}WWY=<>B@ zH2w9ag2Tow)C?-VmgV|4UTa1!f-YZc#zTJ_RPaUbk(xop*Rovy=5Ec%MbPDI%{YI- z9R*ca)zJ(pzLw?sH;`*aE`ly!YsM)L3@uplZ7)5aQ}MMd*S|eoGjb7h`C2pnv1n+) zh0D&?b1fBL%X0nu)-@v+L6@&JmY%X5=F1^0j7M@yXQ%$5%QeB@T;J#K1#gc#RWqpgS~9lmX>aeU&^DWqi=fNb znz8WIdIdM#f1YMg@wH_5`*>34<>eyi^0j8HJfmX4bt5j<3@W~s<(8CplaD<1;%q;1 z5p?-lGpcp@A^(E2Z`2GbzLtz0BhI%smy%zGX+Lribop8{4t?YG{L4rpP0Y?+5wtD#n+P2@A^~huj|gqX5=F1^0j9CXURGFJN|LI zW>E39WcX)hbY0~l=<;=(F>&rWEsh?l8B}~N%k|I9#2GmVx_qq}|9D~gqE0`=8B}~N z%k|I9XhtrAE?;ZL@zF1fw^hDN`$5ImvRwa^jb`K`=<>B@j6R}E;ZMVE(+n!UmgV}V zcQhjxL6@&J$yf z5p?-lGg|aLAoJD**J}n9U(0gSpWAa0bop8{l4}EZY^UOD$>4QDUf%G+6EdI9D9~1w zJf)@`QdNFyB`#mfa_5$;ZLhyr-Uq2YCqX4hXshbpa$)B6{2H1;!q?(zKDv%wd8ND? zP%}tS2@;y|c)1%hzn0#uXJ-<=7FYS_>)Mmgo0QEUK_y6N#_ad{WsYw!Q!_~TT3kB^ z)w7$b$uD@cA0(&*3C;N8j5{;immH}XBz!HdEg#gg-))q+UNnOQl^~%RBeo39l)LD& zrfx4G;cIaC#3C)=L;gC%2OpAP%LBiMKYIZ?AJNpb{iB zV_L17GH335MKehFT3mZN)U_3^k$G4&g9Mczp&8dTx;8WFtAh$$KS=mmTxVCSW8ZHj zPabLp2`WKCGu-%-QROls622DKueaB-e{>$7%^*P~NN9!|e=@2xgM_cewPs=s``k?V z&8YT+1eGA68E*W^sL~7)z82TaKF8R%%O@Ems00bkaN|!#m1dCewYVxBQ{8?sSANN= z{UAXlNN9!|e=@2xgM_ce<$sr~86>C#3C(chPezqyknpv*{4b|9g9Mczp&4%c$*79g zl|9ln9T~3^Pm62BmzC|j*OPTcf=ZCk3^)E{RA~kYUyG~rluGuRGm~vjf=ZCk3^)E{ zRA~kYUyEz&hzfS$f07ImRDy(NxbY{W%4Ot{@U^(kn^)d`^si(LlAsbKG{cQQ8C9A= z!q?)O)1aK~@z3N~LV`+=&JWK`)fk%X_swf2Crw&ZikF_8q7AfXv<{K=@&3=+N; z*Y8cs*h@Z1j_o9<1PRS><4;DFW{~i;xcqxsbbOGY5+pRkjXxPxi`+IR;cIaf?ka7E zHIw-PHG>3|AfXv<{K=>)bQvUkEv|pvRL0)#e)X#vB&Y-l&2ZySMwMoe@U^&py1cBd zJvI64LxM_>&JWK?BbKS=mmT>gzH+7A*`f`n$c@#j8Wx(pJ&7T0%wKh!q5FZnD= zf=ZCk3^)GVr%RVX!q?)eQoEwPyG{H#I4_R`l^~%RZv44Vmo9^Zuf=t7^TTZCjY$Rx zDnUXs-1w7Gr5PlAEw0ZdA8xO>@S#7?gPx!gBs9Z~Klka<^@D`3#kI0T6?^HxB!dK% zAfXv<{JBq;E`x-x#dUGNs`ke|Nd^fjK|(X!_;a5wT?PqXi>v#Z>NaYaWRRc|Bs62= zt_KSnPwTH4Bz!Hd88wc!r`Js~NKgq9n(^fUOA7ZL-A6M>_*z_}s~>AWS(NNoB&Y-l z&2VGfeS&rCiiEGl<*)Q~oRgpuBsAki8RJi9uQ~53waol`_qDo@`dVBcKEBMn_;md5 zd3hwL1PRUPEn~b#_L`G~ufx$zF4k@U^&3cwo7CVV}Iy zUDp)}DnUXsrpg%aBAkkE{;WQ@1UUUQQ0wYbLaS#C~k zkYtdc5+pQZq>S+<&EsoM622DK>hG4D+Dop^t}7B$f`n#FmN9;H_L`G~uf_GtvgPKq ztCI{8RDy(N%#~}-KX$~|oFsfLuImRaHBz!Hd*0(J)wJu6BNKgq9n(>s3zq7K}oFsfLuBq=WHNy^0 zGDuJf5}I*%ncaocv)7y?d@Zh4M=Ui1Ke#HpJxEXq5}Hv?#^1lP*PJALEv~v3zi!6P zOEO4M2@;xd&ud2(ev-ZBB;jjuH6QqzSw17lAVDQaXhy}BpEVtxz2+q0YjK@0eTkVp zJINqHB}iz-)WR0|GqTs5Bz!HdOIE*X%DC#3C(CB<8Ns8nv;aD#dSxUjOkD{*>_1$2@;wiXSD)34;Hv%I|*Nl>$v9%O{We? z1_>%bLNny7Rv_m=%^=}xacw!V(Bv;jGDuJf5}F}rwE{U0>a`jPUyJL#rHf7H!;<4J z2`WKCGvusRAm>5NAmM9q{TwYedj};MB&Y-l&5*NNft&|5gM_ce)%V85X7lkE0FV`UUQQ0wYchcTWt2UNY1q+s00bkkh5BWoCozY0|{S?>yP^vn~g6d86>C# z3C)nRT7jGgHG_n&#r5dA#b!j+C#3C)nRT7jGgHG_n&#dX7|jCrusb=h+i2`WKC zGvut6FXutcAmM9qJ!M}tGaDxvB&Y-l&5*NNzMKa&gM_cewWj%bLNny7 zmM`Z)%^=}xaXr6&iMhOYl0kw>kkAY{t1XiApk|QpwYc70_?j8eBgr5^B}iz7oYe~D zJg6BYd@ZhL$GmRJUXf&wpb{iBL(Xc2avszS622DKjy6lpq6SF@2`WKCGvut6k@KKt zknpv*{8gA<+@JxIdW;yUu}Pt19Jx@5;72`WKCGp5M+Ybc*b-T9n^uf?@;#(&JQPsnePbzPC5 z5+pQZsf@qw_2cV7622Cf|AnJwkf0JIG~-hlf34;7sOtv_UyIBC22(RgPze&6;lA@Z z^1}Ffkc6+r<$nRH86>C#3C(chZ-#sxb^RdWYjOEsoN5LMDnUXs9+L5Qb@m=4315rr zvu^(}Q*Z8&-R2~y1PRT!R>t4x?DZfCUyIBCZeROBf=ZCkjIU+<4bEN-{LBKH zL4rz<(2NB#{!YnW50db;xEk&K$V?lWJb6ZfN|4ZulVto&&0Y_Z@U^(M^!?CWa72

}sA zl0kw>kkE|7F8T8wBne-OtI=ien3v}#86>C#3C(ywzK@xdy&fdtYjOSj$lIpvx+H@H zl^~%R{pEUaS@wF6gs;W5{J{;f#{ z2`WKCGvusRAm>3n?vn7exX!+4g?zu891}@U2@;wyO~&5^+3P_Pz82T|SC*T$cgvgu zx~@o22@;wiXSD)34{AS1_*z^Ihb%Xx+RI!7nn8j}kkAZwM^Vm$dOb+O*W#)*YPqR& zj?8hO86>C#3C(chZ$kEZkc6+rb?w^a=9wzV=MoZBf`n!~CgZPi_8ue&UyG~W@D--< z<|Kmzl^~%Rm&^E@n7tk(;cIb??!D4%bLNlI| z@%NwX{Xr7G7T24Xk29AvOEO4M2@;wiXSIx+2lZNwgs;UlYw|er;@Z2i>xu-GAfXvM zWc*$9YJ5FN!q?)ezi^ycIUva(K_y6Nh8uscH;JzYN%&e^edmoc|1Ohckf0JIG-J4o zzfG^k*MlT{Ev`pKjWch|xHG%1NKgq9n(>m1zZbIi2TAx^T)&+)&YYN^WRRc|BsAkx z8GmnPuLnu^T3mZpj5QlJ+>z}E2`WKCGb+q1$Xt-U9wgywaqT*LtXViQ$sj=`NN7eI zxgLzN*MlT{Ev_aL$C#>Zk_-}5f`n$Qkn6#|+3P_Pz82TFAB{HUk4Z8}Pze&6(O$lf zS)RQfB;jjuEiE(J)Y^A@c6*SZ5+pQZ{Od;+uFhT$lJK>-ww!s7xqf?+L4rz<(2PTI zJxIdW;(D{gDARanl0kw>kkE_|<@=aNv)6+pd@ZhT?i*=lmrS+?2`WKCGe&*;N`AZS z^&kmfi|d&cBh2m-lME76f`n%9ZXXF>i|d$5Bg{`7lME76f`n%9ZXXF>i)%&S;pUeo zk_-}5f`n$sS*<|Mg9Yw$A_-rMYs~gx=EL8T3=&j=gl5QDtw7F$dL2c=*W$WmC# z3C;LO#$Ubc{Xr7G7FWTHVWxVgC# z3C)nRTE3hIwI3vWEv}X&N19`7l0kw>kkAY{tL4jiP%}vQT3mxyk2IApPcleQ2@;wi zXSIAe4{8PpUyJLCnWM~)*CrVxs00bkkh7Y9CY6M*#no@{J!aH3Nd^fjK|(X+tX3%J zLG1?#UyG~F#iPx8t&$89RDy(N$XTsW&V!mk!q?)uuhJNELX#we1eGA68NAy^!q?*R zS7CZRNPkot(WM zB;jjum3(QhDa^c>T~{Qi1PRSpBjay=_WmFVUyJL-y?ag9OOp%|RDy(NxVwFWvcFLz z;cIa%-LcoKUoUTi(*24Al^~%R?)#X@+2=(`_*z{4jZ>OIf=ZCk4EKGEe9NMr8A$kA zT>cGLnn8j}kkE{=ay@u<_Ii+nuf^5A)X!$&)ABAl%^*P~NNC1X8GmnPuLnu^T3olU z-DA$UHpw7CB}iz7yFV{?-3#QSXhg!-;_~m*(|(Yk5+pR^6uBOBcN<&=315rLzr#;6 zNKgq9nsJAWzX!9|gCu+{uCbSWZ(1&rw+U(n2`WKCGp>>EW4_5=50db;xK5n%omux} zl0kw>kkAY_{@mRLx2{O|T3kndw$ps^Op-x@N|4Zu+HyVkc=mdbgs;W*dA%K`{<0*4 z1eGA684t<$8=t)%B;jjuEgQAn9J@2gAVDQaXvQrv{<>%H50db;xNa)5%?vy~86PC5 z1PRTMvs!_i2i^9_BjIatby>8<+}tn8AVDQaXhumHf8S*950db;xZZhevst++$sj=` zNNC1#8GmE4*MlT{Ev{qV-()_mpB&psPze&6A!oG$IS=Y_mxQmywfy`|=E?s{GDuJf z5}M(@kGVrWkGkza!q?)eTym2sd0=uLBta!eXoh=U`{7pc^&kmfi|e2Yo6P82lME76 zf`n$cyM1yV)ayYKz7|(O_f6*Gbx8&ZDnUXs zK|(X`mGO6a_Ii+nuf^5t$Ia&X$CC^aRDy(NJSyXFdG>mcgs;Wb>X@zOjD1N42`WKC zGvusR;GRBn>xzW0#WjD(HZ%3y_;YYx9tkQzLNny7mM`Z)%^=}xas7J0H)i>OB!dK% zAfXv<{JBq;t{)_PEv|yOJIv8jk_-}5f`n$&mivPnv)6+pd@ZhNoxU|=o=7rCPze&6 zA!jvzJxIdW;+kJ;ml^+9l0kw>kkE{pGX9d^D3b8CxV~BQy~+Pal0kw>kkE`OGXCad zuLnu^T3iPX+-)xDmSm8i5+pQ3&T1Js59&52;cIdEt1$iSLxM_>&e_vuT00p^{DlME76f`n$c`}6K@gUcY{ zYjIU5)8BkDHpw7CB}iz7yFc&lHn$S5>$eOX1M$Fa@SomNcdV@>xTC+ zugy#{NKgq9n&IxxySojpA0&J&uFR3W&CkD{yxkBqNW6uf=uPnx3ZF zh9rXol^~%R?*6>ob=M3Mz82S%H+z^y<&xtS2`WKCGvusR;O;iKevt6BxVrz*-85^G zWRRc|Bs9a_pLcf~Tm}hWi|eI9-A%=tk_-}5f`n$ct2=kM!DW!}wYVPpdv{Z6R+2%2 zN|4YD_kE1J+u$-t_*z`Yp5NU}_$0|7K_y6NhPyxS?l!m#622DK@+sZT!R3?BB_yZ> z3C(c#=iS`~mqEhU;yUoG9%fB`l0kw>kkAbG`(1ap!DW!}wYVx)>1l@aPBKVP2@;y& ze!uIUK64o)d@ZhHPU~eROiD6HPze&6;qK47r_Wpl315rro?*Ss+82@x5>$eOX1M$F zavszS622B!&3%1Lmv@p35>$eOX1M3I-P32TA0&J&uKxGmY_40EWRRc|Bs9a_pLb86 zxeOA%7FUC_Z!za=Nis-K2@;y&?$5iY&s+uxUyG~9#(rk?rX+&|l^~%R?*6=c`pjjJ z@U^(=jp=Wyex78Ipb{iB!`+{kyY8An!q?)OS!JN}U0p4-gV;_ADnr=2r9ne&VUl^~%RyxT{@*Wzk&cQ4zb zWs*UHN|4YD-t8mdYjHiWy_apgJ((Yl1eGA68NAy^!q?&|Xw=*GxI4)pK_y6N2JiNf z@U^(AUf$bQs+?qypb{iB!(H9EyA5u?BH?Rs)oj_@j-Qpx*GGa%kkAa??IYo9aSgB8 z+vcB{WRRc|Bs7C}`$+g&T>o6%%MM;WE_;1Wf=ZCk4BqV{;cId2xTcrwcyp3Lf=ZCk z4BqV{;cId2Th`OAtDa<#pb{iBgLnH#_*z^SRq1JmtV!mxBta!eXa?{0k?^&+>R#T% zwwjS-kf0JIG=q2hNcdV@!-saaKi`>Tkf0JIG=q2hNcdV@AI$7#$M;DxNKgq9n!&q$ zBz!HdRj+roqx&WqB&Y-l&EVZW622B!gRNccno&sx2`WKCGkCX;gs;Uly=oV`>e(cN z1eGA68NAy^!q?&&a9w9xds~u0f=ZCk4BqV{;cIdAUC_x^J3SeLB&Y-l&EVZW622DK zoD(|PTgN3CB&Y-l&EVZW622B!%S=Z*YDbbmf=ZCk4BqV{;cIct7~Iib)iyb{lb{kL zG{arpCHDtO_*z^m+IF$eOX7Fww315rryw5w@3(F**uSie{5}LugeI$G>t{>WTvh8{#86>C# z3C-Z$J`%nb*T%0q*>#JO3=&j=gl6z=9|>QJYw`n~ZLi>v%0-R$YTk_-}5f`n%9 zZXXF>i>u1!ZuYG1Nd^fjK|(Wlw~vIc#kF8bcf0k{B!dK%AfXw&+egCJ;yU;K9(K?1 zNd^fjK|(Wlw~vIc#pSQUirpWi5+pRk&FAE1D|FWebzgea%zgi9{p{>(aSge8nmOUw z_}}I2jv%N63C(cxIX#uVKS;vY;#&B{G}Clsl0kw>kkAY_pOc%d(Dj3auf_GwdDG1a zS0x!Fs00bkaPv92*$Q0-315rr@q4D5_H~jB5>$eOX1MvB+-!v|gM_ceb;{$@O}Cv- zWv_8aPze&6A!oIWo2}4gknpv*`p=kd*1nWvkf0JIG{emf<7O*#86i)+sb)6AE@KAGL-B&Y-l&2aPky4eb4RYfFxEv|EiJ!&R=mSm8i5+pRk&F|}G zD|8tod@Zis%l>Ifzm{Z>pb{iB!_DvOW-D|VBz!HdRlhu9D$h$YNKgq9n&Ia6b+Z+^ z3=+N;*N)>JF{eI}WRRc|Bs9a#?>jPke~^T)#q~~`ht2f4Nd^fjK|(X!{Jw6sLe~!x zz82T6yQZ2eUq~`YPze&6A@dsMyV(j|1_@t_YyQG1=C_qe1_>%bLNna_zHYWcmqEhU z;;LO@iuwKPB!dK%AfXvhO?>4oSv22`WKCGu-^XavszS622DK zgwH0MK8=zL5>$eOX2@Bsz|B_Z`a#0i;u zC!0$qB^e~B1PRS>^ZUBl3S9;XUyJL=!zLTMD#;*0B}iz7ySj6;6}k)(z82T}RVJHN zzb6?as00bkkh5BWo2}4gknpv*=Ge)`oR)lMAVDQaXoj2L*UeVwGD!GZT<70E*;MS3 zWRRc|Bs7C}`$+g&To;#k$hkkAY_zptCU z-mNPVz82TPXHAiNMM(w;DnUXs-2A@Dd@>|_Ew0Ocm|~{=m}HQk5+pRk&F|}GuXp_* z;cIc-Svb}F-@(shKQoY^5+pRk&F|}GuXhi&o+T|UVmK_y6NhMV8l&0g>NLBiMKy0Y;<%@qeE86>C#3C)nRTA`c0-er*R zwYVNA@u+!fXR^&nPze&6;pX>sv)8)}622CfzY5dqK@wDggl6#R&o-BAHN$2u(*4KR z;(C1hR#ReV{O{@KMX3Y{&EV6YBz!HdjeWP7%2y^CB&Y-l&5);F{PUtDd@Ziu)@(C* z$0Zpgs00bk;M1QZd@Zhzs%slJK>-+Be>A3JQ}95>$eO zX1Ke3$@8Kld@Zh-r*Ah4M<*F1s00bk;M1QZd@ZikrKKNNBpD>A1PRUH)1M@KEv|;I zY%_gpCmAHD1PRUH)g1|6i|d3-wwbqfzntCXB&Y-l&EVA?315q=&f=}+#kZ0S5>$eO zX7K4x622B!pCh)KZcio|B&Y-l&EV6YBz!HdTGwnb>+er8NKgq9n!%?(N%&e^Ki#|8 zY>$!*5>$eOX7K4x622B!^_Mr9(zhiUB&Y-l&EV6YBz!Hd-@e*t1`kOxNKgq9n!%?( zN%&e^#~!xPoHR1YAVDQaXa=ADB;jjut-bhb^Wj5D1_>%bLNoaECkbDRtM#O>%$fyB z1_>%bLNoaECkbDRYwr&mOxsVA3=&j=gl6#RPZGWs*P@#?m}Ung$14(4f`n%9=}!{A z7T4@UHkhkVO)^MO2@;yYr$0&fT3l}}U2kf4PBKVP2@;y&?)D|mi<0oQxXzoi-c+5E zWRRc|Bs4?LYW{gq622DK?{n9i8LN{F5>$eOX7K4x622DK`yWX^N+zF6NKgq9n!%?( zN%&e^{pxNoTTV|hNKgq9n!&3(622DK;7J?I_>M^i2`WKCGkA4J!q?)utM*rB=GY{I z1eGA68GQPags;VQ+8bY)T~8(%B&Y-l&EV6YBz!Hdp`*SwgO(*3B&Y-l&EV6YBz!Hd zCobJ+`m9MZNKgq9n!%?(N%&e^qv~xkt-nk%NKgq9n!%?(N%&e^v-fQ>>po91NKgq9 zn!%?(N%&e^!`|L(>c5|4kf0JIG=oonlJK>-UY)eXj3`VpNKgq9n!%?(N%&e^{wl24 z^P*IOgl4$swcV#ncg=bBt99(IIGuy(2@;y&p4WDtE?ou* zUyG~c<#p}wHJR*ZY7$g}gl0S^*MsiUrOP1UYjIT=CH;6j$sj=`NN9$8UfX@TbQvUk zEv|i!*R^x{CmAHD1PRS>&uhC+mo9^Zuf>&FSl2#NkYtdc5+pRkJ+JLPUAhbsz82Sp z1$FIlWs(dMRDy(NxaYOqr%RVX!q?&&G_9_E_M^h=HYY(PNN9$8URy?$W{~i;xQ-uO z*RGwFWRRc|Bs9Z4ukAivx_*%GwYch?Th}%jm}HQk5+pRk{eIVdx|E2Bgs;U_dv6_k zT&pC51eGA68SeMH@-2&Iknpv*n$M|Y*EC2nNKgq9n&E!G>poq&evt6BxN0@8W7||t zGDuJf5}M(Dzw16-x(pJ&7T5Uowe7VBBpD>A1PRS>zu$GAE?ou*UyJL}LACARUlwQg zT@qA+gl4$!W89}pmqEhU;+jydw%xoh$sj=`NN9%p{jU3T=`u+8T3pj-)v}KqoUAJn zRDy(NxZm%(PnRx(gs;U_;@n#H{Ax)C2`WKCGu-cY-KR^JLBiMKdg<$$w%M6U1_>%b zLNhp9C<$MS>)uHjw#6i)+uXHSENVNd^fjK|(X!?|0p&OP4{y z*WzllqlO(*EjdS#pb{iB!~K5OeY$iRBz!Hdir>|+726~kB&Y-l&2Ycpb)PO>1_@t_ zYsf)0?dTCn1_>%bLNna&cja3a%^=}xajj}l(_Z~zl0kw>kkAbG`(5{W)b)deuf_FN z=bHA{uaXQBRDy(NxZm%(`x7pMgs;W*&XYB5rE~77T3G&YS~Q}BpD>A1PRS>zu$Ft8{E1g;cIbqdA*kX zyls*}f=ZCk4EKGEyW8M0NcdV@m!DMIW^PC_NKgq9n&E!G>+UwV3=+N;SI38H+cxc! z3=&j=gl4$k@4CAUE`x-x#dTSUI`-kqlME76f`n$c-|xD+4K9O(um7L2GlAD?+TVDj z(j?V&OOi&Him33{X#Ei7R7W90G)nV48PZWnDMix6O_N-+6q)KsDndocta2$85rs_s z*KpSAyPWmj=yR{n?{l8#yPvhz-fIu<-ur#EYj4+T@uo>q4U30g=WRM88 zc7>}jdp$^kN|LY{ydHeAM7G@4ZK*xS3AJ{8*gjhhiu-$fJxC=<*bH-j-aLI~`avSp z+BN*aY$^GTD!))tNXF@xx8~Y5>%3e%`o@p&C_QlgG8vc ztN*@islU``kf4$zY=*f%Z=OCg86-ljUGDA37cW=&zq;uOa_TiYgfA? zE|ur9d^GTDy)oy|wJRz-N%4k|b<~d0yK*eP%L9gj&1GzSc^LH1-)J zs3ZxSVV>7EPoJ3#5~0?vqpoTtL!0;v5>%3e%`nevo2SoA28mE>*Kyyqlv>Sw1_>%j z!e;2_)WYx4lL)nT4V~ChHn#T}B&Z|_o58C)5~0?v)6Q%un}+)g5>%3e&EVA?iBN0T zk=wH5iU)iK2`Wj#W|-%-&C_RkeH0)OYVGPeJ4-HD?K4PFNfI{0Jg;q@J~J64Lakj_ z_R5lW`+WupDoMg-nCG?4(`P1wM5wi^ck?W%a*E%#lc16$Y=(JW+dO?{GDw74yB7EZzGuu5~0?v3xCd%xvhK#2`Wj#X6U0@_&s_Oq1LXGvRcY_{d@)qDoMg- znCG?4+eoG#BtmWa@n}mKI^JiHppqnPhIwAwyp3csNQ7FuJ}T8pde8D1B&Z|_n_-^U zHg6-D3=*N%t~YLMC9UT93=&k5gv~I|Yn!)`Oa_TiYu5)~w301zdy)N_<)Xnp zg9Mc%VKelnoZ>H`^xTzeFh0CNy29EZXbzIYu5u4`pTd| zK7$06Bw;gnw~s`qwX0>!L6F$gbV<^42*CDoMg-OvL>`5~0?v-uLv8S!;a;2`Wj#X7FwwiBM}-vwD5xAB%hj z2`Wj#X7FwwiBN0T({J~dN^^V$2`Wj#X7FwwiBN0Tt6h3aqZvMf1eGLVGkCX;M5wiE z@z1^Fv6()D1eGLVGkCX;M5wjvwaLAt;{u;Sf=ZIG8NAy^BGlSdqjoPj`gxy0f=ZIG z8N9k95o+!FbVE-my2)pdppqnP2Cwc&gj&0v$>}K*e)1V4s3ZxS!MlAVLakk8oAi|7 zRs6n$1eGLVGkCX;M5wi^NO9edY@b1bN|LY{yxT`2)Y^5z&K`2bXrDoXN|LY{yxT`2 z)Y{eV!yeM|d7nXoN|LY{yxT`2)Y?`5lOD3^8=pafN|LY{yxT`2)Y>(BZx6|;>dzTS zP)QOtgLnH#gj&1ylPDoMg-@NOT8P;1xz=6c`$h0h>CB}v!} z-t8k1YVEr7sa`U7zt12+B}v!}-t8k1YV8_+d~X^3yU!p&B}v!}-t8k1YVEpXOmF$e zZ$5(rl_X&^c(;#4sI_b8H@&69UY|jNN|LY{yxT`2)Y^62rF~@Sr#^!Ol_X&^cs)oW z)Y=uU!tz}YQb`gv!`z=YXP4&MxzSUDrBD64>^WzswX6HV!SeO7?(gyYgH)1)%`o@p z^{lcPBtorSg=L8Rv3+9R`7Q}6Ny29I*VlvQ?9%juM5wi^%#b0nd#TSLK_yAp40C_p zoL!m>5~0?vKc)?lD!2O#5>%3e%`o@p&Do{NAQ5WqTDfqD)Xer7B&Z|_n_=$Ho3l%k zK_b-J_2v8_GOvQqAVDQb*bH-j-ke>U3=*N%uA3(fky_g))K z5o+zKb;A(3W{J-rK_yAp40C_poL!m>5~0?vQ|b(nrDJ^t2`Wj#X7Fu55~0?v8ea{T zx!3s&5>%3e%`nevo3l&ZjT{o8)~-vY4wg2JeFh0CNy29EZ9o#C)~@Pj507EXO|{}M5wiE%C7^ZO9`Jrf=ZIG8RmIyb9QMmNQ7Fu=1&%3e%`nev z>rYv128mE>*HLu_N^VV`L4rz>uo-+CkVL4p>*b9DWJNQdL4rz>uo-+CkVL4p>+aD5 zM0)xR5>%3e%`nev>rYwCSQQ`|ya95?RG&eDN|LY{`luFuZ-PXqwQGCH0doFI zpFx63lCT-(d2MrcY5GAT)Y|pS?*4Mjk3NG0l_X&^%=6mj?9ybA2(@;d^+|szRLdWu zNKi=SJ^H7WnxF4L4rz>uo>ogZF6>MGDw74yGHEmFGtDA37cV_*Vdo1*bEY()~`BAwsslXu=uf=ZIG8T__T5~0?v8f&`9xZ8XN z2`Wj#W|;f)=IJxj4-%o)t}}np{ix?h_ZcLpBng{gp4T={pP392q1LYRU+OH?e(jMrRwSq-37cV_*EUa|nG6!4 z)~+Wn?=0u&dk1cQkf4$zY=(JW+dO?{GDw74yI$GdNd~>)Ge}TL5;lY17D^)2+O;UB zlVrc;Ge}TL5;ns;uWg<_GyNbDYVCTpTqk*Po6jIYB}v!}{hV6(eo+#k)~;$xI!dvk ze!C(;B}v!}^Sris`poo$M5wjvqboZ~N#!$0P)QOt!#uBTo<7qV1xSQiyPi6_qZ~WV zXON(hBy0x1EtEv4wX5{%4zlZGpFx63lCT-(d2RFbndt|KP-|DAdpk(!27aGNf=ZIG z8RmIy^Yod?AQ5WqI(|S0S@@vOAVDQb*bMW$wt4!@WRM88c3sw~gG?=o<6t1DBng{g zp4T={pP392q1LXtT|3D9!9Ifol_X&^%=6mj=`)i-BGlUTz>OVb%BMbq1eGLVGx%+x zBtorSyXSO}GnGI0AweZc*bH9XkqEVR?fIaC-1LCYAVDQb*bH9XkqEVR?LDcZJoL5C zAVDQb*bMW$ws{-LtPc{Q)~>e(b(Hh#xbt9rB?N*>lCT-(d2RDHlF1+uYVG>|osQDF zv(F$wB}v!}^Sris8_8sl2(@;NJExO09OE-cP)QOt!#uBT-bOMRBtorSL+5sq0{WRa zcdR8rB}v!}ep@JsP;1xiB|1yhdwd27DoMg-nCG?4+eoG#BtorSgNJmM=Wq5IB&Z|_ zo1u?t;rm5Ngj&1Ge%M)hT;?-KP)QOt!#uBT-bOP0AQ5Wq3RhwFdXNN_Bw;gne{j{V z#`4@P*>>HATD!h$&_ouW<^CSuAEc5bYzFW4kqEVRO&ZZeKG@beZ@VHvB}v!}-t8k1 zYVDf!bQ5`Iw9ga(SZRBrAwNKi=W)OHwQEt&Cepl$&mci1N!Sct-H`~jc0Ez8iBx(gD{rhw zP)QOtgLnH#gj%~cu5T(qITWaX(og9Mc%VKaEQk3^`otHL>rWNvMrL4rz> zuo=ADMCDK0*P1eGLVGkCX;M5wiEV$X(hbq}9Gf=ZIG8NAy^BGlS-L8*pv z?OdNhf=ZIG8NAy^BGlS-d~O5j_?6EfK_yAp4BqV{5o+za>6Ql4u#w-Fkf4$zYzFW4 zkqEVR^=;ljI?eJKB&Z|_o58z%BtorSqyE)EemdwgNKi=%j!e;PpABj+FSD`Z+$bTFAa|RMrl7!9R-98eb z)~?IjHIPwreFh0CNy29E>W)OHwd=~s4P@9 zk|b;f@Ai=hwRW9dv!P6#>@!GENfI`Lcl$_$TD#hhYbbMG^%*3nBng|ryL}`=tzCP+ zX($uF@EIhiBng|ryL}`=tzBE%HIi)oof+;}OM*(0uo=ADMQAVDQb z*bLt7BN1xt`m|PKDf)@eAVDQb*bLt7BN1xt8Zo)Cys*S)kf4$zYzFTSk_feSg{!c9 z_XnvY37f(92kUP*M&7@%xm~xR)~*hfOUb6X?(gyYgH)1)%`o@p&Do{7t|bv_?fRp0 zDf#8Ii}SWC5>%3e&3GE`50VJAb`_hZ`;p@_NKi=|cD=Z!lw>cuC~vGtP)QOt!`z=YXO|{}M5wjv)7MIgYUVRYP)QOt z!`z=YXO|{}M5wiE;8Uff&8N-s`ayz9lCT-({=A-5HiJZ{wX52=QnL6)pFx63lCT+k z8<0e(wX1S=Dd|@hNTg3lm9B}v!}z70qs)Y?_C-7#|Cl|F+6l_X&^%=6mj?9%juM5wjvj=d%2 zk+XdU2`Wj#W|-%-&Do{NAQ5Wqnt4Y_`Ql`sL4rz>uo>ogZF6>MGDw74yY8%5QeHjP zXON(hBy5IxUfY~qnhX-5)~@>(myp^`eFh0CNy28B=e5n*rO6->YVG>1bqTqpo6jIY zB}v!}z70qs)Y`RpUvU{Z+h>rVk|b;f-v%TRYV8`gpty|s(r1vMk|b<~d0yL`UFxwa zKqA!IwX;)kX@9QYmyn>6By5I0s)g?tB@t@v`t`KKNlrIB}v!}^SrkH zlqJ`!4-%o)u7^sMkY^|Q3=&k5gw5dFfFwe#U2pa&AuDoy1_>%j!e*G~wawiI(+?7% z)~-$)OUM)3d-mLaklb z{->l&-QzPzP)QOt!#uBT?lzbV5~0?vmZgu8njiWM5>%3e%`nevo4XArgG8vc>+8YC z$VZEO1_>%j!e*G~wawiIlR+ZX+7+(C^1VMuB}v$fTlMpzpXEI-I{y3OGN=D|d(IhZ z?K*jQ2^n~n`+I=`B&Z|_n^9fQzm<9K50VJAcGcNYLhku?T;BOE2`Wj#W-QRxgN5>* z7bOvD?UF_%rQ%$lL4rz>uo;i&`BzLouV&T$6q zMM;EOyUI>3DRuVUkvCQ(s3ZxSVdh_l=I(lsM5whZ>&}w$^DLi1f=ZIG8Tae?cU<20 zi;@VncHQ5tq>Me^XON(hBy7fmdj6fY$6XJS2(@;Vt5H&J`)+LBSdpNTBy5JcKX0Bs zGwYm0sI_a^niA4~fzKd8B}v!}^St)hyzdt!5o+z~d}#@p+sS8;ppqnPhM9kQR+)a} zkO;MQ%~@4kPORxONKi=p>Es)~@a&i%F~h`V10Ol7!7L^H0wzJ60q@tz93lD=IZN`wS9Pl7!884A+AsLakkW zDi)PVANULsRFZ_vI7iRFnR(ZPBtorS%3e%h2;r&ni1sBtorSIcti@ zDaHMEbq)wBNy27aujgOCyyrzpgj&0%j!e;2BT2p--wAWE2Lakl%zbqtI z74`dF5>%3e&G@&Tf35SL7bOvD?W*uZAt`X3&mci1N!ScC|MaY~{U8x)?Rs}gA!+uU z&mci1N!SeYd5k^|+Ur3Qq1LXM(+kOnQvP^Of=ZIG8TzQ!R38WJIRlAMYgdbx3dy(K zdxUfG@ zBta!f*bMW$wmuHp3=*N%uF)F`%chHc1_>%j!e*HHXU;B7KS+dHyDn^BM6Sy586>DA z37eshYEATU&}NVbwRY7xP((g|)Mt>Ok|b<~KB_g*$3dGxBGlS7V&2j6uQfh{1eGLV zGtB%mXP0KINQ7FuinT2&mu&JGB&Z|_oAD3)9zBUrYuE5X#bn1jK7$06Bw;i3QEj>|8urIR|~av9apck^`4Cf=ZIG84u|BS1s>)kVL4p>&%}@OOK0u1_>%j!e-pB z=ijw?*MlTNtz9qGDI>3b|3KbYk)V%j!e*GO zJ9BnvGDw74yBc0tMlMi3g9Mc%VKZjv`PVA%dXPk@wd>9*W#rwR_veij2`Wj#W|;Zs zuLntlTDuBwEiLP&`3w?Nl7!7L^H0yJre>^2gj%~EA5~gjZs9XXP)QOt!+ahyGVgkj zM5wjv(h{X*PZ6I%f=ZIG8D{>OvrFBL91@|{uE{yaN{eFh0CNy28B`De~9O$Lcj zYuDQG$H=f-drVk|b<~nSbW&(u@^}P-|DeQ6*%^BA-EmN|LY{(0LUF0`tD8JRFZ_v&_}f<`Z#DaNQ7FuDlI7?buRT8B&Z|_ zo1yPZG%}jdp$^kN|LY{59;~1BJX;z z`akMQ@1^(H^TAMS*NT~SrRgp1?*$5wppqnPhM9ln?9z-CiBN0T+N0~qb!Ynw5>%3e z&EVA?iBN0Tr`Oh#ojdN%JKrTiB}v!}^LdQ9+hF=ZBGlS-!?b!L_xcPHRFZ_vF!Rrx zU78FMq1LV^pROmrHSifEs3ZxSp^s|0`Z#E>2T6olyLLQQPgZT4oHte^s3ZxS!K*tG zq1LW*#?_OyclrzxRFZ_vF!RrxU7E2X5o+yvrdd5{b&k&w{gj%}_&OJj;sOd9EP)QOt!^}T( zc4@|nM5wiE*mrg0r;0v<1eGLVGtB*YbGN}{kO;MQ9o?jkTyv7oAVDQb*bH9XkqEVR zRiAvi)H~B>kf4$zY=)VC=Iqk+gG8vc>x7-B$^J`y1_>%j!e&g=*Msfyt_MkkTDyME zK27H3_zV(Ml7!93(bt2YW)OHwW~>y+H!KX&mci1N!SeiDQ8ptxv1Umk_feSJ-e=!yuH9@ zkf4$zY=)VC=Iqjp6^T%5SDz)dr0nlLg9Mc%VKdD9)1Qml>p>Es)~>T&s3k3~@W)yb zRFZ_v;ME<8P;1whpVX3%3e%`o%NoL!o+A`xos+B)Ji zsj9Vinl)Up2 z5>%3e%`o%NoL!o+A`xosdT4MRDSv{`AVDQb*bMzCXZZa=5~0?vfBfqVSyJ9-kf4$z zYzD9HNQ7Fuetz!^`J}MVAVDQb*bFoO%-N+GD-xmBt|M+aQz~rt>zo9YBw;hU=wZV#n&cd z&Wpum#(}AM8JP&WeC;y!FTOPQi}%VjH9e=|Ym>3Ra!I-Iza1M- zf15$Y*Cyk+kB*V6Hc!jT$VAZPYnP$>kgHo}GpP95WDNc2SQ$NjdR|5*f-YaX481Ov z>k+mYRD5kR9yzwGj4e4MFC!B{m#Vts%p;9X`}bott4nE98t&U2{v+Kp8uY*!!(c$Zn$(2oweeC;x} z>-o3OZM%A`oa@iT*&kKL`~ac%SBD6?eC;y6*Yj_mn}a!2d~N#i)4f$O&p{OMF0(AU zeC;w!A9lEXNe&fXn~bbqs$qWxqJVdqWzpqpmtoe08DYJ<%Aw+GlhNkL8rbiGDBxXY zS#|J>onFzXk?J~aC+wM+%3^8Lx#n&doY@yE| zn3$K5iJ;5ZF2l?}J*#X665YYx5Cw`PyaVodH;aimy$E zIe$2`J~9z>`PyaZHE7O#Yz7ryyRkYJ+f^pQoGtmS&(|&^?~E+3=g#HE>JVYh=MK$} zOaxuNb{YHi{PS~=imy#S%z5ddd7g=&%hxVLAJua8anSaIimy$EJHPh(t4su4zIGXU z4`;3o>^_l-uT6%zPB^sR%|y`UYnP$-)VY4&PQ}+I!(8w9BZIrfNfC7U+GUuzu`2Hv zMa9=9!(Wk^x_Z8EZWRe0;W86+aYO=z zc|AcTCJyZ%GZTJaYqoZdh$V7-2In2;IkPiokl>yuGeH+eBqq#q{U<4=g?>)_wN}N1 zoBwWKawsL9wSV3-9NNQ?Fzdj7W?|ayKO^~Tts>z@!GDUw3@(csXu+1kza>OUPY z>)C%A!6n56m6+h?C5M_7b4%VTRyX6f(i+@*FM~K zMHfdTWaQ}4&GpMQ$5h`!Q~PXptPPANsKkUj4*qY#9|wJ&nS&8wTjke*QGDA?&Fn*M zGX0=J!jD3fq0yM2iz5;;Y^(hCYL?~K^IvaOOdR@jCuHPnmEW#R21g_&{M0?`!{h zt4R30_Wy1bT^y0PRc5*7jNUBEAE}eA%5hx0?Z(8R^WZom9;-txjz~i4g=DkctHi^du8SRHb4L@bfx zxSU)ww|z^@obWB=k}_xHCtRNbp>yKVb<1@wj)*0++x*MPHTyxo*3ACHug$;Ks+e%+ z?PjFi(%pam+^Rz^j)?W5zhTB}I7z4qa@E4nx$u046JYPx=RPpR?d z0$JIn)CK#S_maoHaP`QxU1UPrh4$|;v3THhYQyOdS!GJO8`QL?X4`sl{pqUpq?{UTyC?v9aFI9c^I65Y_t{*Aq9C^20?o*A2 zN|!rbUE+)zWo(VR60JJw?vc{7{e4#XtiT9acgIXy?^xbnp80HAf;fBViE?hYRaW`O ziZU{-hpTu0aGY$Iu{=SPKJf(k>lW zjc-(~Rj$5m!!EUUq^ske_y4h{JhWhvB^ut=OR`$JdQ!nY^2B&o$HckK*Qn>7=xB-0 zUs|o&-PXz0n|@uXro7<(9ur5rzgnF%?JDb<@Z)NAW^Gqb+WLn2;9FP6gnwheY*+rt zep9RAh2)`wbL^60;`JlS$)!VQxQx8F3=QGm!83JCaJl};{{Nl9bQ1oV{rnju=;}MJ zgj5=r+S;j*@Xze$&!FO;x;HK^DegHH66SgO>H5k3{23(Z@=wR-Cphl@9Yy2fdWu^` zg@k|mFn2+1=)nE7aun*VyGQ-nK%u?d|HgRaD+t`l=ez!@0Pmn4m)9sqrgS z@yk*fBGR;jjnyW&xaG$gR7jLQZMFLN zs#FFEx-!owuG>dHTdsb7%`KPPLfk4UBsz@ERnv>4MwbL#e{FP0JT9-Oc@0t-Tozs2 zD&v0qx@xtmccq)1?T4*aQ}?<3%A6NBtFBcqNz4xtbglnxwW_)zHP5-+D~haESu+op z!R3-@ed8)srMaWyevqJR);q7MQH4`P%i~^CLpNSwdswZ-N_FQVSJ&O}y88C+ixWLB zQREeM?KbDSB|BGjJl-vr`^vagR7li#db#S-G1V#(ba9^_XRz%T4SiLuo_n}{u!kg0 zowGvCU*PCCg9Kfdtb0Y3d@)7v8oBJ2{xY%SL_4A*_Vt&e?sIjVv9Il5>6h(3PiXYi zVChre)%?sMCa93;esHjSeQfHJ2@-T={w#wEiNZ2O{@9-C2MM~$3>hN3m!^pC&l@0T zOr2oIXM4#3a{fwJ@7~`}HdJ?Y+;b`$XyjvTS>c$gQQ`9r*ykxki6CR z?`(-AF8^+jlBfG<@_Ns zuY%j+Zk{wmYHfGRy|3U1Y25wx#PNfBfIp@Ukt(-4ntO~mg9?e23x`O}?9|pyf-bf; z&Y1G+Kp91S#3^-#$kMTnj$1{7 zt{PtrmburZ2=;?*pWAJa>?@WcxU5U24wg2J|4u(h)Hr*vyj3lg!G6%i7REiNLSpiU zL9)3_DuV=FnR{Mk>}plIaTmL8uimm+Jz1`+tJuy~PNF4X} z2kQJjsjY+rU9ZpmP*r-wZIyA)Ppb2g8u6Z+AMf=4NWJ~D+rlp!|BY(?guAB`6I4iS z?fQ{gd3qXONt39 zB$lk`E;}zhT&w6h@17p=(M2`KND)+;m+L7vZFX(vk}|i7MD?~kq}AM1&$%qR zIEHZs6%wOIc9)+=q%ug*#n~KZG}`uwnqPZ`ozEl3exZh~dfC>GUizi#v)R=#vAD`! zHF4qd*7eQi?^Tn#U0rS2PW9YdFDCX3Ki#!M?apz^2`_F}MQ?QVGdJy0v(9sLoWW%= zev^sI8I_uY^iB=7t`nj6e+4b<&s{d8>6bY)w`#iF)ofwh4=N<))!(g_j&pQOaD8wcys>_}y8N_P6Rn~`Vr-4=s`Y27 zHAsT41;1`rTR%w=R7SnML)CiMxwxdbA5=)JnEI6(vpkhSg04$1*{Md&OA#E!bwzip z^Dg^4>w`p{mv*WCRa5JOYmlzYTOzl1Zk1K8`burPC$;TTA@SRhU#rzaQuBiZU44$* zscv{Il|h9>(?`Ei6=$Y0NYKT(8Lx9HBp&SYts4JGDuV=F+{eTjukZdsJ^aOUb{;hC zzFob))zw8y>`)I}oSNsA%6zF#yWNe+))rr=O*350C1uVa(R%8C)#fFs(d9ma`x4IP zID-m_dTaly_CA){+DXvGy>^_zne*`Oo$82@e`nT`__F^lRrc~!t2k@v`hD{*Rp8_l z!S%s)@Y{dCRKssdjV=`unb$c9x_D%W$BGJx-uri`XC6*%S0w1le8f5U=r%QXo!iT7 zd~cg7U(k&Yx1P9FR7eb{{<-?9erj|{(8Z%&oU!2O&()P@x>mjQ+BQ|StE;)Bn4m)9 z{D-!w<7cM!q9o|zh{PG3YX^S#T($e)@61{fFZcaiU3g@wRos^7;)ukpI{CW|YS;@) z?B1tr!R@NxQEu^?_lCg@_HVxsHIU#WfrU8}Zi+N|!sY>{nM-(tJe&{N#sV}c5a%+Ju1 zplj9G-Kx@_)Km9VNbs5cxK-B``B^P}!nOD2EkCOISG)Su|2tBu^?1_uDJJOp=cxT^ z{XY&za9JeYKJbH@za`ZV5_J92`bYKX*2fdAqC(=%Hs7n3FQ+m{&{cEhcWUcnDI)i~ zpViwX-1hU4uFpT()pt%kpza-<+ODXOxS{Q@YHW)Xan1Mp)ep7Z*~Ind{iJ^R-0ht+ zzs+&c_VTi?p4$UFci@2PcBz|pnKP)6c57f+y2YtKdZSD4%ZL% zki_FP52(qfrjAi0=;DaPt)fDr;PVI6^4!$^iUeI8w>X1q@X5aWRhOsS+B|CLK6S|r zsq;iCBzSfnXYeU#J{`}erelH%2|kmanV@U&tP;{;!F`E2NQK0;_YAu?kwJp4%>AH3 z;-|LyH%4YnO=OUui(?qC4~`XExaG*=Qt;{2C)-p=6kJzaZY`YpJdp%l57jOqJ^r2g zsh?WxawNYFLrv$C>iWs0EEb!KU~>TLJ97?%`} zE)^0x$CQ$#AErK4BS9C(EzY1q;`~J=<-Px;)&~i?GOrK5+sAb?ug{6{cF9yfsF1i} zZ*^JNb8KP_lAvqzl#}G?d8rI4B%Y{xvg~|3l|h28_2*ZS?^>kB%6}8ExzFLhvDefe zH$PY2|1!0|^502qTs`u>#oE+gZLA^Red+c@@fxH;!hb8Yp<{xI|6b?6oBBVu*41U-rmP_}?2a3b$SVTL<|GDkS_bFytqg?tlNoxY*iwOQb@= z|FTE^3=(wt-|5Ite3th+I7acm67$zvMZ*97Oa2VDiY~63xaVxI|NW1@-YOFQmp%S> ztLWm|j9W#8g#Tra{23(Z%Dk0uOZ2}`VV27!Wo{J-|JxJ)yH#{$-cwT{;eUG~e+CJ< z{4Yu5C%A9t{?Y%|L4JY?i8?E5$W!_^6#h3sm;cR%`~(#e7dERQb8b%E+a^Jm|LuwV z8B|F8*s;2lx+-;^NP;f^8yfjDsE|0fLN$4}Rq8yE1YMceAQck7-CRWuc1@iDkf4iO zPrS8v-+Y4P)R|$|?YI*v$p`6s zK@xPGzNV41{%7j``4OkLmR%RP&-BW^)=G*rcJiKAp(u-8@UGoZ>zUd-&We zDSxf2$G>@j+?2e3{>F{1q}4q43Ei!qx0Ws!FSE=2xKu0YJuCIe9TgIdrZ$t#ds00o zL07X!TguS!sf<|@v*pd_U2msfm@UuV?dm<3Un#YIdnVCyDkPTeZ7tpUIXYhFBQI^ySKG$y*!mcf-bJvxK&((Tx(bM%93{bQyE-?AAHeDw#>=DHscJgH4wLVDD#cevy;M_jys#Y?ziCZqWo|vFQ;<)cxO0DLp zR*|4<=){(?v3-i*{^RyWSu$tJ;r1omUP*j=X_k~*)Zg!e!BQQdUd(u3w56^RC`Tce?iW-`{?;4hpHHWbgD;$YtCW6xmTk#@*4!*BKY!5HY;8PN zR7mt`K3uN;eu1Sk6LhgpF~PSm`DP&B+KdS*B*=0Nq(v21pLoUvGH%NSiHyD9G?a;7WLsrRyGD|&_txe!l5>A<5oQ}ps@_PCd)3X)dfmUxa)jdZ(QG4Mow~nj|nOyGWUZ7T~AbN zB9-1rWl$l(af@4Z<>Usk_P5ry?bmE>Ap5giZ%cf2mW=AvCNWl2NSs}>p-i2e8Y>cX zan$2hQ6bTOTtk`jYAS;SUECJp46ea)B^t{e`dZ3tC0sW#L50Mr^BT#@Q&a1M1YHFi zpCg0cYMK~bDkLhL(@5slPGxW#{j^qNDf)>UAC5@e4=N;XncP@jSaP`0rEAr$#`4@P zDPruqP2|K%Zo9hV^CnVfNh{l1Zk2JXM*XXS{B+RG?d9bf$QL~v!L27IsF1k7LIe3> zlcQsTE$OqRiBxWWxK^>fBnqx=B4=)Ot&KBC(8c{&Ot8I$&S)V2ZS2O4{fh}IBrb2) zKt|1VbY_As&i|O;y8W&}6Ip!L-`TE6Od8QdKG>FO6}LpXW6oBGBJ&y~K^ONJaR$fz_}m84>8ro9&Pm*K zO9N@xC^c)j>sgT<6V75ogXUCl~(Ez^_*Ej`RpJgNf6mB#;JE&IoG7pU3HYYwN@&F1YMb1#j$EudbH}2_t^qRA#N2F5?K$9Ru>gXjTH&Hj<{%yntn=( z;4GRyeS&&!i|cLX8AXLet)&yx>qAmwMS`w=izcWSilqpy!AhmasGmCDV%OlB{-f0| zkGMJ>D=Oo6k5Zd{cP=g|Ca91YaQi6r%QbF`$xP72EhZ+|cIG{~W{mowW~v`lNK|in zle%hdpTvwJLD$!lZdVHmrZPD04~(6l*3Nak<$8+yL50Nc=S)zwnxw{x1YJL^xl?`q zd8$>bij7lMes%lsooC;n+V6HX`xLi|3W+y6j#Ulzq>ct8=*m1+Z0~pH-l>*OacyV+ z;#N^1(QwLmb$oWJ=OpN2YvT+mB))xboGN)@DuV=F9Q8PZ`wSjMxsQnnDkONc%S_N! z<3&*~ex3T9nhJ?m#x_;M&c8b`KPva{r9OV!DZQ^~rY`>4eZK$gOXsN(|GqCl@E3Is zHp^ChtIV-3{<==w4=N;1`n8X`e*N@B1_`@ z)6O@m+OJQu>1}F{Q}?W!V(YclZdTQPcYlxjL4`zx2X0b(>ZCH*-qX$}mBCig#dQ<+oa^KI zb~mesrsQ8YF~M~}V)+p_tJAJatw9oWjqG}px~_JLIHuTO^}(HP9&oO7o-;(PzdtoU zsE}ZG+z%3T{aSvQy6o9h2HQJ$%#G@WKb(tnoI!=e4c&*U1)EbDBEP zN4e#46yjD)JB?RE5bYg37kheblS-{!Xh%yzdZ${M2jP4s3lWediLZQYVC`z=6sAZ*!J^A z%~q2?K3qT8LlXN|{aY1%HPtE-bg@rytEiB8H+gX+|$ zQvKkzyLjnL_515?9dOj+3@Rk59x+q>@x|fRAYE^DoS|}#b~Eiy8D*v`dBZ91l$);J z_`}s4^_bw?zP!P|)n!K>Zk}^=N!)wHZ1wn_)L42hK^KoiF~QG}_z4uxgJXgU z34WH9nV^eTuQ5S|#NdC;R^Qi1edhoPy2`)zm}>Dv>MWcJi3S^1s7H@VeR4;Fu4{&E zQs?~h{=``Z6%r!`?ou=QOgaof7r%2P9xL8)ct0Mkhv>1YI2IID-m_+bZo>O)nmo$l&MHJnQEu#2Hjb z@O(ZqK^I3MCa93$6+mW!E{;M>P$9uz$H+|3m3efjkXX3jNV#=y>OM}Z#wGQ0y3OsH zy6!(EW$GSRzc;G1JiX|e#2V~Sxs+_G>s)_yE+xNw=ANM9lOu6IxZIYdkCB=m9xj9F zB)%SejC{Pv(QyU|y6SH@Mn1SPMX>F~rj?S7Ifv^9dr0EPrKP0F390AENYM4-no^Rz z=%U2vo>;V$G+lS0RY+IPE+xGxrJjwVLZaHZQnL8Q6v6aQUn?c5nQIB@cyy_d82D5v zY4d3+g9KffTUES3aXIc?*ODQ}6_=wLx)J4bIdQ8vR`TpIGIv7$af=DIibTbB$H;wG zIyy5!7oSLq2`VJ+*jrK_IXjg>g07i&l$0+{P7ze@tXNWBJ=M9mq|B`%asT2HQoCs? zgUh1px7H=(mToD6%Hn;+W#sI?(<&0<78I9JU#2qHD!O)dDlYBMO>K!(K0946ce-$mJ8Ylcol;1eJ?H8;gUcFTsF>_{=kK(NMEfPhq|_^^ zRn5MPl@Z!m{b&)Eh>3W=o+3d9bg@ry1{D(XzbqtI6;16$NzldP zZk)j<2TCvQua*{m)b6kN*>X%!A;D(~GZS?2bNHB`LSl0L>8kZ4_niuv3A%Vb7ZX%S zY}}ly8vV2|al|1(7tiP73@Rk9y6kgx^RsTGGZS?28~~c3;TSc}vb9GF#J*}$bc5q7P8C50wI#=^s z*$W^3;3F?K(JRcy-w_-_`sEySN`zNYps5x-=Z>=*$FNRS#5?8m&^q#BEjO z>LZ=PUwNoq}IW)G_>!+&v4&9Q}XtEiBe zT%xM%_%-#+9SOST%&#I36i)Ty*N3aiLxXeeI?r8NU7l>}YW68^6%`VnFR3mk7jtxG zf-Y`vG4V$2%F^yRx2(6iR+iuX>uS#Cn4m&p{bQA-bcxi~PJ%A(iQ){-oUX@Km;MFZ zayd6+f(nU(ZL7=Z&8e{>K^I3o&Y(h~)L7lZhf^6O=;F2zXK?#D;=C$yL52MDF($Yr zl6d}$%5ve^sV$KNU3X2bENiYx5p};gNyb-jJv{ciljPX!zq6H)xT#QO88;?1R@_SH z;uaeBobBCnX=Pb5`tOVtiO(zPo^m12Sl3I48BW`ZvM@=;7sA<@4_LFx8b>bX7=baB+<3@Rj!T3AUoO?AJ!m6@Q6 zb2BEWkU06Ly7KDpsoyIiL09H)p`}8C-;x-&iUeK!?$?;0LL&1wE|Q=t^LNTt{$`V! zQQe)<59_g6ZGWnpJ;L!Rg1A*wNX%NWLlqp>-O`x}y7<{ZOi&@wuiDYF<>CQ}3=(wx zwND^P)a`t{T(fF;B7@7Ki@z}w_k#+Ff*q^LizlR>%OF7)e`6-jphBWf|C(~eKXVfO zAVJq(`wayWL+93#nOCMVxGcK(TNiOZsE{c3Su-gjsn3>3(ADMX%jJTDsdq-Hkl^ps z$E_kk*P3>n<;hhO6QfIoMCRYTe|_$Us?sCwEr^rqe56La=dR+p<;Sg}LgKRV->BwK zq`sq(1YO+n;|wY!-qO!#)EJq%J|{sJxBNJR3W>>=Rg`(Zrsg>by13=X8B|DgXmhd@ zXp_1=CqWmt{5XROiHV(0lkYp1$m>=XR0;Q(YbRgUanCI!o1ioQq3}2`VH859ut=-<--IL08!iJ4=ttQbdcd zyNIgjKH0iRkI#Wu+)U;7r^c{*VaI(@PAAEJ%hj1bNu@&K)pDKW z#chs`Gf2=?ZAnKdRx~v~IEs5u>L?F=?M9TN9%oP?@z$V@a(MYfMO|1`ZC3JB;#jT=3;>pW9%Q+vW zGDy(H?JdsW*6`7l9i^mlJ?D~Qf(nVJj_xSOj!SJ(oJ}7ESFFNzlc8Wt_opPvN(m@Y_9Nf(i+~ zLz9`Hi}zJyf(i+~Lz9`Hi}zJyf(i+~b(5K(i}zJyf(i*fOOctNi}zJyf(i-#4s&LL zE`F936I4j_9almsjZ58eCqWlK%Zf9okl^opWhUt2XIU{pg#>@+D>FeCKg)^SOwh$E@0g%Mg3lmi zCg|docT7+r!DkRM6Lj&)J0_@*;4=uB3A%XY9TQYY@EL^61YNxHjtMFxcnr==(8Vk7 zn4m&}XPlV{x_0mHCmX6yNbG&6kl^oW#2F;$I;ze<$*q~nph9B)lz~#dT#Dc?Eb_NH zxkrs#MTG=^g)=ij7x$;iTCfoGht$WJsJ(Fy`T0eF6 z`={<#W8;2MAu*|7A9-TDqcan9?O5Jlp7|{GRy-9FPc6Kd`UVztGJb{$AB7P5a74gHtn#3JLzARy*O~w9}t4w0u5Atl!;JYP^|0W8d_i^4=q~G#n9{VEI4-#~7TZl8bZijx;TRQA@%jJ?{f(nV_ zF6|>rKRsNl=*qn9at>D3_X&EGam(fGid#j6#254X%D_)kTL}re3eW8;yB|&w+``K? z=_$jjI9KMaoeGH}#r0gtPGyjwi|aq`ITaEo?Cc>|j80{cpeyr?;+Q-zp|1=Ygqn}Up zoMS~7_xW+pxu%+Z*++KmcFX0OjR`6wdf(GWX01)NiUeJ3ZJa@cM6-H*W=v2a!KW`W6Lj$`GbX5z z;Q3=_f-a7FOi&@gv%$;+UEF$Nf(nVx3XG6-cg#$jmyn=~zls`XP$9u{R7>PIE+;p< zgZ1t)7ldcAbRC`+({)UQx9GGI-d)o*mlP8rUAsc7bRAl&>zD}V&RPk-gsSUsew~j9 zzhA1A@Ec{i4tF{75#e_YwGw_IQP<&@4D%7;H+ZxXKDpC%_*EiLxWO%ulN)|HM=RkQ zNp&55UB?qS4#~+4-;Ju3@a;*u4&QQ=j|ktuua)o(X1WgFY?hBGct&Np>3IDu##$M7 zLM8d&WmktQwxU0jb_4x=Y zB$h2LCaR;O>@;^w*ClCzlSLVe7(MOUt@x z?(a4u5L8G!uD@^T9lE=vOoAh!ZB(yx@X z?*<~radAfPYfH-DKKb*kHxOJdiAqaKNS#Yl86@c9sK*&pNYpP^LLNFfl|h0oZas0v zcmH>c)SaZS_4SChf4`)Be5?LcMb~S`A0xwVadl>bu5wk6mD{r2mLC&TNVIEEO70(@ z${;~ki;K!g*Dq5UR7gDZ-%_&WA!OL5neB=MT^~>Xhg^2C+m7RYP$4ln=UC~nA(cUb zE^hg81{D&QmMATIieP@^xQ^uHlAtT!j0yzj^SCy}WbLyL*mcgWCvFuL5-VC3lY84c zIx|66(eA~h`13W+0I zl#yFzVJpdTA@SBu*GqNE$gAI{h%ZWR?0$JHw>xgX;= z7+OVwE{?S8f$zr=@2^%TP1E;G^%^|&-qq^aUtJyUnCidBt)fDr^l7Wr$5&l#mz0^H zEAv?fm56wFm3r=pR0fGnaNSyDm3m=cilFjM_G{|p+Sk~&b4hVOsE~MS{7O~)GDl}7 z=z3@At7=G(6hUS2wiT*v@4wS35}Qk|P?OuIGT0Bg9+y|tyap+P=eQll=BnvMoa@og zmaCs%ON}m-1=-8h+k>5pONz&e3W?cUm#H!Oo|M@_GZS#bX#{`vHH!M>> zW;qwLV}c5aew~)79ozJC2fkGX%dy9gI~J*vpKos!x-wrIP$6+3XPG)M3>kX)=3h=O z3A)~SZJFv?286X6;+E`O)$#atwpHPGMs?eH?PC`n2rg@9&E=}e5=S#T5W0w4MWV*j z%TIhp%eIGKTTS&tyUjm+t+wHH_3hmk+n$p+bbWW6*Hx=ky(`_ghv!RltGKVUOAi@TNQ7rw{C1Tj=;9vS^+5ku zQ#rY8Z?zUH)t!r6+c_eZ&~EcD9xD>z7jJ#59PlTCE?!5wg*zlCmkNpS3%foeCq>ZJ z`o>kNN^@*i4$!Tlaz&BVDr=^5G25Dx86?^dTdk((L0NJ>D zqTTvN?CUQ_-RJ69wCay(L!`>>uDxZ343XVSUCmF8tXcQL{L_1eGj5cz zHSV(MBnrzA`C~hJo@0SO5p-q#G>Qs|?gt0U*T=eSyY!Gjg04nS4VFIjQv{WLZ3j!g zZ0F*VGG~yu{JTL?u4^iT%c85>9fRbpzA1uAyNZLPVgJ9=DiS@O87NnFPi3%Gba4xf zdrpPKrmTU|xm_xQ1YJ+=86clDP7zc#&Ke+hRdg;cDRZkxtZzF&hV4sjiCh+4+)LOD z^Pe2EwR7ftf8GE&W2&1)oST6#P%ae`caPR{uqWoAUcUJk6Lh__ae%C72Ey765uU%& zdw}rFm9E3HSo!u0H%}TOwYIxueK~)K%&YKs<~fO#3x`O}?9}LT&p;RVF}BNj|H;X% zarR(&tD0-oB~u4Wo5rrbuiyx2++Ba8pzlZMIeRA z%5lxg$t6M8{mYFMYILm3>6Nd9PhpS6Qdd9p~zNL;?3NCzly?Wp35gTUM(l%XPIG>}~iR0^bi4 zkz-~Q6%rgb+aB#U|6+nJUdcGG`>+1Q3s)>8{@V2*UA#85OV9BcayVGV{>ajlV9H{%^uVZNi|R*|5KTTe`| zz2kbnuC9N`ZM*DWOi&?l^5`|H!49|eWG3k1_GXE^|K#Lu?fQ{gdAz&x^G^Sd)Z0J1 zIy}XmZ%Z71+gi0};dOS~-S+#Ns&QRc^GYUUm?b@UNn`1_o1YI2UID-m_oO*AlEe(*N zmv8>XYmhE(J~@xJO=EHzdn=(_RN4^+QJAY6pbpz`qzAF5gX{-3h*j+dgy z-uEablBlc_R5Gp#$cpJF;a(E}+bR-w*8DKp zqg?JxQDxiZvgqO`MmA&m`k}7<`t+!{!^J~gx9)P4uPm2GwON7+iBaDTad+IF(pkc; zB$nmcHOW%jRUK9OVb_$1a@ytn+{D>w3!gcypWE*M9OA+lBl=lOn1+!DiTliI>ViHP%MM3 zqKj)i+Yc%vZn$=U>%3(wg9KfxKI`w6KNZ_bsBEg}?@k+>y11m$ts-&g(thrU8nFy6 zi!N?s*$le_jcgfq*BPnpJ{nRhQGCf4sF3JZ=;x+vh#gatpzDsk`nz+k0AU$Tx({<# z&PmUg8pxdwcC4F@37#iftMdL6uJzh8+>$Am>lXg<^8?+~QE6?z9t!;sxBtr*sE}AZ z`%HJm@RUxi`YHs|*(!cwWC;98tCVUYXb!awtVkZ5u2VAo^T|7sOo ze4ngUzF`Hrj;uGtowp=iZWTiM;QzAkIf-os|9Kaa~sPr`INrEqX%hy^dO!EZUUT*^C~$uT2j4DecFwZ`ULb-<8(8KCwEf zer}9l#v@HPCRg5BH7}dNmXNru|9_Ip?n&v=1YPC#Zb){U5hK_Sw*BGr)+IL`5+kUP z`2O!}lJ)sm&q>hr^Oj#EFOG?2P$ALuq|cKT*C0c???)5~x=Qz)3W?!6uT9Rp4;lG1 zBwrvw7vHC1gY=(#f!j~pC)XvTnmwu86}N@d8ZxMmc)j}i!8?ETj#^QVGH zBV=9Od-SSg_>y!?bX>7CnbZ1NZPk>PtCOCer2n7IphBX`7_SXy+WEeq( z1jl@~RqV%vDW4_d7F6w1aq+T=_^pI(C$ZlvpC%jcL#xE?|FQ&Kr9VrkkhrMXr^)Qg zV;Lmq;^$b}9DS8m@l$Q_yDO6V)zam1Nm+sliC^zsk<5A>TS-1-kf7_(J60qOX2b}7 z4)SxJpAy+tQ6W)!Z$N^spFdrdj6W|nYN?QDw9~4j%_Shxj?3ER$T_Y3`lP%v?JdV< zwjWeTyxVYna^N?ybwz@%UzV&(a(l$Kl2xPDC3TNamAlrjO}3bj)*LI@R#72w^igY* ziL+xFBBLB$jvmEP3ZfydU{ANv=Fw z|5&X&S zNR-~%Nzlbnpc%!Ne1Sb@3(q*@`{c)!>CsuXRa8jW-L%7TqGgbv>&N4NNM>CT%dopm z%d)CHzB#EZq}ws+Y^$h{_}AW>ldJcNWssn&bgS&H+0rVzuea28SMVx5r*ir9&B?W+ zAJt<9E-Bj&DkNUmusK<=BBe_cba5SK2`VHW+q^j$cyzj^OA~Z)O)KGF^8N^5Y0C{s zs|E6O9$6>$JRYg-?oeD;O3-Cb>WLBJ_J8>Tmqp_8W4=zhKb2;uR(<^)L6_YfDzqve z2r49A+x$&3XBje5Kr*Q8GV$Bwjlam<(Pg<@lA5C#B+g&;drDN5jIHaePNtrdZa;Oatxl?K zmDcve(kcWM5-%RMI=Sz<*w)Tgu_cY(UY&f{3WTmO-w$4C&1sri+VD z!OU+O=(4-UROvYt5_Z>^Kv+LW&}H|QsX|a8!QXsYKk|NE)qc2z+viZZTZb&mem^Sp zm*ZNx)eW!J|IZRsNPNDyrTc1?{9ZM*N|x{cvKe+C7IBsS^%)fsb`O{;86@c9FW=JU z=&Q8K?t3oFYH{^GZohrg?{v2-YwJ#F9Q%Iv%ab>C zw{Fz`A|CFtpX*VaD>!KCe(u=IW8dj>joNRYV{13Bt4h`t*E@-4XS8$W7sR$i5_Glr zOFK7gevF{9#RdDihO1K-m!$29wu;0L@BYm#-DX;3d~jKG{pGKJbMxwh@IjIz$8fK< zc5gnJuJ<1*+PK;IwC1+p&ED<*vfCAjUDvj8-yR)%2e~Y|I9Af7r?2?}w}xNNZs$ha zoi3MKk9zZgphDurwe4KT^|4lwpo`mBy7Z92EpE+y`?&=x(yfn6Qg1#GR7gDV(0=ac z_UZU9P0+%Xv%+f*Cxc|H(SNO0@PW{{xkj?ryh{auk! z#PS6yB&uwQ)++X6`Gsv<%Y{|@q>DF#Z70#_>(*}8)v+;1g02_NZ|&ah79*$(Zq(X6 zoBK1ZBC%>|EBDm>c+Y)jq%ZjbTSZsf=Uci5Nm$RRkT~Gqtz6d=Vi_dp>fEKJn|Xfh zQUEzTV2cb~`fi3jB_st8ClWZjXu> z!B4n14sGhb>YC209CK=GH+PE|L50N6=Qnk~4v5Xlkf5t{tEiATxM6emc8}PMA_=;< z4s|Wrx?<1y8O%Oq2`VJ)=`mG~07%faWLjhQ&}__-S*z@6H?pi9ci+`5y*Hh^Bb{v( z6%wpliU4 z9og7B@%`&Lnz{7GFm_xW^PaY@<*ar?h~feMM)ZWq__lGyAk3A*?`r3=?r$)G}_ z#Uu6I@(W@aB}qPk0J$MyzP{@byJJL>)P^Ml#C^k@c&Wn0#C)gJoYXQEK~0+&S>x6o_`6%u!} zuH^>*Gxk|Rf-Y{y*$n=coxfh^ujQ5SFL~b&DkS&|a3#d;|FQ&Kb|>&EV~`4oM{cU+ zdf$Fsk-}|QR@lEorqC$e-KPVw?|Cc4`;`i67RbPdmLSoO0pGk%eeLB*Q znP)$c9Q@Nmstj0tYx4YS>GvhAwtg_#`Z#>2uTAo;I&;wYs|6BFF$!739ATeRUdCBRmuaESD1YMO|oS(Eg zJw~vHjei=Robg85cCL|P7mDM93W+Hbhb7A%MbB+rk)Vs~E!%S{BzD_xXma)RSOy8Y zs=Oc8DsFv^4jYtQ{eHTBxTMmpB5~*c8Oa#e5^WAXE9vxkEQ770i=SiJ zo^z~mOmJ*w2`VJG^`!5eyypFgB0<-Go;)PE@Snfiu9Tocf_G)p3~~FveBprJ*Cz{q zJzqcde>v!iq*d94THi9|isY49X`Oo0*L;D>$hlV}|E_V75?qpc^MRm3qSgE>l9$G$ zbZLUFIX7I9Jhm)Gyn5^v$x)prXiFa1aCvgpoV0HD$Q4P)mXr1Wvl&!Kj2U!!((U_{ zE=|zY=%ve&JsamE8C0&?@v>yE4ylXTr87uWbe)>K)gzX{Wzluk_)C*1CxP%mdH+A0_NbJ~bVscR{WN4Fq-zvIZJz!u`v;Mfq`$5-?WMcAbw+s^h zd3S13d-s&!NXrsbNOYKXS<;{atxCHg?+2By4!%5@Kkd(CkobP#<;lvG$gqB}Rdn%_ zsMw(5w#&7+aMYya$9vM{a;;~3PK89H9VaK>_d~0!=OpOjTF+)sA@RV%$;mf+BO{-N z$hGHq&*|d(Uu;mZ=iD0B9(ZYT>iTrc;F3zWio}8%QYq@%tcK9vB2r4AT-`CLHd1IH~2x}Dyy7rw>&vpK$ z{cnV2)cX7YH*x4Os#NQAkQ==yU85b=wQ|jO#yjXUgp$v8C?x*AytVtdeyryt=wb`~ z;{EddU%o(vMD?SZx%Eb^3A(EEToXKTfAcce=&f$r^M{6%xvovSYrXs54s%nN z9Tr(vUq08-oxQO_m1Vs;x{6I{eee$*-RKLBj}UZi+|a>Y`Pu&>xGWNj*0TiLe&F66-1Mu{-j?nM z6%wZ`Y45)67F$;&=sNN0_U@IRd;azgrYl#r5^muQ59;Vb(rl36%u>R?&zN1 zE4Hpk(8YUv7aNpD6}Y|5n_cFnUGTrQUA`YAs=ZR?_FbOR*?y3qYxuG<*W^fiGUU^? z>VUQ7sqBcgYWI}z1q8pv(opO z+d`J0LSpN`wRfL(!d8-3PPP&fblu#rz5C`JtSb))l`oukL3`JsW4hiO6xzGKpQl>} zw>Mq7xcy&tOC)hvoeu8wS=g@B?g=Va4(Z@d8T@B5NVIyrgRAL~k@q3LZxvnK@>6g6 znlEtsIcjB@YdbGpKiuBbn-2sP5>wtTbGtW+y&oj#y6K@Z_wb|`LFK9o%iQ}bQWv+k zY^$h{_^N%Gd*p!swe8Zyag)v9_ETA}z58r%x~{mrWeF-ICjPa(`~FvqbC2cyJ4k}A zKei>37;&U*$MUSWs;HY!)y=6$@1>b8Twf)F&tu?o8c1geDkPp*bF6Dz1D_1}kU@g3(yijtBiOS?tcVH;-gPYd4w9gY_YlhxR7h00gPE;e5_ItnZJJShk$WfLzGJ+*9G6tORU~-d zxY7h&Grzsa{d!;QDhnzk_(YU!2A`&lf7($kj1|Z6AAOcenV|)V1?h z-Ce6AL8KAVDlTio`U+Q8|FJ4-TFuc`k?6I>(eANsDP5YN>wv9}cAX~1h!0P#aKF0w z+L8xqRk(`>rZu90w2H*b=k{S8s%rO_CxyM|FZiJ z5|iJS@xK=DM_z&75p;3fsMiQ8B*x!X;dW{e+Y(98#ZRSd2DhKP4({gapO&_r+gp~P zLSopF-CWZ>V?8H9*NH>BxnAGm9n>Jdb_XBS#;v#|{miJ6i3d1GYAsL4|}pE51qw3A)(YYz7q)_H6np86@c9I?QHpo!IlX|M1!+VbA*h zKU+l?N1C>(_#*e3#656%msQ@iGTRR-B&vKCyv1g#_<}qJ%8p|K$rL=(=)6Gk5Zq z$jB=o1drj~xUY%ZvDP!%!bJm`xSv0bou6~LTO88V9o8^i?#ww&-7VW7BaQf7&zo&- z?ppRpUF?&ZtyNS=v^=DR>o67>QG%{L$G33H=EMm0@a5J`T(8H{-g1p(TSbM$d0RJe zQzysP6$!d__^Pqnp#p>tlD^3Eqp%jQuGP$~`6>PWl50KNDk>yy9oNi_|1qUY6LeMC zN)+?0;#wScTMPH#yMN{#B(ZW{3%5rN^jv!F|FUOybQR{ea1WHnhygpaaHDeR_ImI$ z&E40{)0*d3>B99@GN_Q)IH0-vraYyy1eIg9Xzp%4_RnOH=yzi?S8;kQgRP?L*fz~v zp?8d+a>nyb-O^rvrd1@~Jguo)-6fX6R?)?6I=il@khu5PCazDLSOy8Y_(_z_;K*sW zp|QKHVY+2-Nm+sliSK@H?53^4CxgfGeoG`l7e`t)g9?e2jheWH4lcvCV^19C#d{=x-9pk)Ws#G3)k1*WsrFMvnHf(nT`Q)D#X6&vRy=;9Wd&7eY}+OaL%q$RNo5_Iu1ChbA! z2k%G3`xNmmKG{}LAu;6ePVVX5?$>RhG(p!-haKT|A3ZZdP$9wZWV0D0=sI1VO1k8j z^k_LtP$5zJdr=Z}@u)VNL4`z>d9}Q9vbB?-i$~|#3@Rl4dc+8~|9NMUY^$h{;QLgXpz9a8CSySl{E{`FHY;DCLW1v8HiHCReMa_n7q+?e zw{>M1R7miB%4U$Di)YALf(nT$=jYZc5_IwVGR-Ky$gh`i$1J`#yu(hmRa8iD9hN5O z;?o$i1QilohouR+cutiisF2_~EKShGbE+&sg#^FdDNWGDD+;m%6%tjh9LOst{5$HS_uh0?7e(QZI*H)nK8 zmnP^su5WKQy*dbw<^9o8^Lc$-jp{?RCC}CC>z-IKSZiMOl+B<*Vs5^#t5}rMrHMnI z?B|;Ql)88gQhy>Ut|p&~;PY0dDyO5Y{RxTkSQ#z43YK`eUskv7*%g_lZ2wrRvp&Tozrs?>4|K zdOAj&vVVU!aJO`H*8QNL8+=?^mmY&uNQ@rS&pm#AY@Cyz>yldiT(fIp1eLL~`nufo zKhr7_QxEFvI!umbuvK*NQz`qNbF9@rtGB!Jw)7q3xXBV!NNjy=Z?|K6Y$f@0Gs#|O zN!N}q_IB$&`rXzpRKCE``ONyh?(CQU%s40U!14XuK_C3DaZVRUaM}ZT)mE{+4{q1T z?JzZMJJ*O3;`V>po|E|S#6GTef}ZCU_#HtPKlxH`AUF>8{jtC6+dTa|=eSXCJ`hw$ zv|QNVO}#j_Hy}Y5x3_Et6%tb>_jmo?jb)Iai=#Q4!E1+jwGgj0$`Vva@T!H<1YNua zK?(no_wP9s5_^2#&OP@_?EdW}=;9f&X2|mWU-nxy5?kHb$h|W?c9&)@i>^QRJp+kR zgR8lL_dO8#q~@~d;(f%^4(O}&g9?e#_opU77w>_d&7eY}^!=$x(8W8bXES);DBcO2 z_pHhiR7kLer3t!5Os(Y_O-*N)vji0qT+^iqx_DRUEJ1|?x0uodUHtAOOHd)fEx$BD z7r#5n5>!ZV1eYf0;&&%mf(nT$*GA=)lkq`=f^VV+DztjIu+Y?&FW%WC{mYdZ#T`sdrw~EBm z3v0Pix5rw=WzkiyWo>uyS22R^?fT@_?mq+5wzGfPR#71_g>}&LeCRm|y563) zwd?ZOrN6CR4+xbn6z$2h7xq<7__di{_5AYdOhVNG0UG;wI;*yjQxBttwio{2+S9g0aK}KGI-w|~2 zomH<9R7eb(P{Z~3G?qbvE^hg0dqS(Y{oFFJwwrQj`mS+FrCUX!+vT<04>#dGkM@JE zx>whBZ8yb;J;v8^XCIJ`yUV_=>1K{fYu;Be+bSv~2A*8gb-yj8OA~aRI&fd=bbzzL4(suK)zPUU36XSOqdD@{=zkzL4vNqh1TxM$!A9PwNyy( z9v9gR5_H}8Y%|wppZ<{yDkOMUjBEx8y560*qkCxXDZgbX=06z@nRsh*^+)%q^4(sy zC7=A9)+hCvmz;Y2{aGUadxEY_3;vl@e=eo7tvc<^OOm6e{Y#fsarKSKD^H}$?YhN{ z$-HUEkmdV7d1}w0Gn2heNR{~?-tpO%)B>E->}Cm$-eib^)8QI zk&I|_&u{$@xBtr*sE~O1$6J!RbJ33!5Q6LH=lQoKn_8rO;#x=-o+9}I6%t$SIWxKO zn3OI}&^2r9%w*7H5Y{RxV`j}vmOcJwT1Db-cg;-B{1O@YSU>2x`_h@o>CI#B;7QYN zPR4Jap6g#&c~f%THfdeu9kdK8B#!xJMsnM?u?!M)aeLDqSOygm+Z;4Q?i?A*AVC+m z<7@`E>cg(NA=%-Kbh%tomY_o74tGP6?DxM~Mb}&PZb)AKFWx~7@>@IKDUL2~q1jeZ zA;Gm?nxKpKk2MM}L-=CVFALpHTTe8=K=^ABTwpCO}w0Qj1OL2)~uroUQXXNZVTB~Q6X{bzBeRCP5<3{F6&FK^2X;bUHs(B zW>6t9Zp;lyzHcmp%2glTkPL5^y11m$86+0<)uHfHz2X`qMMTAA4P^N-~VM>Mb{hH6Qx#t6@pvC@$LVa9Jl44`Aj4+ zZqO}B_1dv-Qn@A4#n0okJ-!pZAKc$@AO6SQK@$ALunZrQ+1Ju__5L>`J+F#=1Ihd5 z^9c<6zSJ_bA5=*2DF#Z2+yCVYB~+bF!>{`7m>~s(phAL2=jp;zBumg$cEO_L zm}Qe98B|ErxNB)LyYZOch&d}WW5>HB=&FC- zqU5Rsgk|LCzn6Tw>p)Fs#!a`cNve$-^joW}A5=(`KBFf=*U0AExn)P370IANg6GuQ z1#1-vy4v+?;7(aEK9WI&1fM;U%^*QnwLZ<=6T8N~>!U(~&zs3+kf5vWsJ-0@yW}JN zphAMrbhT=GirZ9t zN>G-dLgJaz`nmlM_1+lG zx(2>^q}%)BiIIL#A;E1rn?ZuEsZCFJ^}FEv-Mn(LwNoK+$6o#2Iagc}X%z{&M#)uA z4fl@`yqoGL`_yz3Z|I`SUE8;&JN4kSPTLb&wR`nCuKe}R>S|I^#|>?iy7+C2dh>yx zLZbQ9I_{Bkkr5^6I{U#o?wF5b#2s~Nxks-&Qd{-PlQmtvu4&CX(x&YRt>UsiexZ&_ zx*V=FTdUq^t4KVtu#T&ko6@BTy1tuV$Cd4RgyyB~Nnhm~7AQ5Yuj3ZyQ`aAB6^Z}$ ztK)wB1R2qO&{gF-G9##v=-s4_d#7ExrnLuAg0B7F+}^!^Zj7Mv#pvzbM{`pbvrA`? z=)U9jZto9b8C(`!r{7)MP5&}Ra9dh9x~BVLbGk;WY**HEDkNU$Skuk9HTHgxplgim zaklCZBdFBO)pR?*oo;i-fO zwIt}`Cy{3Om%MKkKbNN7E}vJc(oZ5TNeOZLzkGoTiAOfobQ5k(>C~#Pza!}Sxo0hR z!9Wli;4`S){75a=y8O?yip1r+)ppPAg^YZxRdmg`w6^Sp@(W$oFtNPD;mXPSPxR$$r zMeLJ-pCxp0++c@NB6xK^JElvji0qJijVU(8U?k zEJ1|?&z4FPbaCc4OHd)fv!&7mU7W$r5>!a=Y^gLs7w7J?1QilITPjV^#p|rI1QinN zza8n`Y!N&2B0(4Llbg+;LgLBAXSrv)#40S03y}dg5uvJ=f zzAat4yh=`XCXU3ica|hKA2(Omn-b#oe_4Vq&IqL5^ffzwPGa$rLela3J0lrf7G2z< zW;3XesQ>PLN!RIUJ=U|KHBcGq}P)Jw1<4k)E1ZDnY`F%aHQu{NH9+qFD>$a@?;<^ zi>`5t?@ngqV&6JbA;I;QE?i$Fg9Kge-+VT?cdPVMB1=#q!S}y3LDwnc-boJH<>tt` zqC$e(aW;blT_+v4GCBXz*l{8i5*&}&3=(u*{N}pkl?jhT`ay-nfTuoBMxGt}RSF5Z zM$}lBjNKE2Z(81OB@3pkPa1uhrY~)|A!)TBt+^!aNAX3jFhzSw@K+aVmgW1uEI}97 zNa{^rfrV+36sX{k35 zR7h}cQoZ>YK^H$UQg0xrkeGJq++>f(PmOH5BWx&f={c+5Sf0^WwmDP-LFyktj0%b1{JF%gU`^&{mPC$gNoIX!TTKMav*Z%l4a3lwPtMo_QLX^zvRk%1{JF%BYTGp z5IJ+nvgoo}Gp_D-Zuv9M4$=%NR!au&=#k5T$eBx)MVHl@ao2y(DzCZiU7A6~YRTZ; zn{zo3IdjRf=(1WfwrMh`e2>rH^BFlRR!c_qu0y2=x~$fWOI|&t{O0m%5~4K#y_)sn$`FXeKj2)eA+j8)w_mcKosjb>1>S~B=-mRznB zL6_Bwqxp&3-HmJHs@KbI>-&}Fq| z6uSIU_Q?6CYX%joC4;|x&*e%HbXlz#SMKwAS%+hXXa*IlC4;|Y&*e%HbXlz#n^xaa zw)BB>G=qxOl99ciekp=3t2JZ&x?{^ajyX>=s8}r-ynlZ#SBjv^YRzaq?Y&N4U3-yc zP_bGvvUkTXMbKrnX52NmNr%^eouC<1tdmN)U8etr`8Ud+q7X^U{7$v05_t zjDTFO6hW8On(;!eXXST~rSAt7t0jZaI>_Zp5p-Ft8IMf7sq*?AM(etwVzuwb8>^G! z+dNl1Hz-BWWwmD9^LU|hUGL$VLB(px=(u8OGN<*k?)ePyRE?)wP>B*k=Wo z*@p;mI|-}BwRZ2t$vXVNU?mev~5U zvRX67w7IzK!};ShgNoI%TzgWmW|Si6vRX4vXt-&jD~zI|qzLB(oWu01JQGfEM3S*;o8@6e=j z(1#ajKd4wO%e5z7Yep%8E~_0?ML6_B)-|IPL6_B<(dhKXg@aB!LNlmX?fX&f&Sd}G@x{-QQUqOAYet{O`xP!+bzs_$ zuq;u`B^mZTiuR)vL6_BO&;G6%RIHZe+6oT7~#cIhIc0!lrh%e+0 zn7Xb?5p-Ft8P9KdZsDTahie8Et7W;rcBx24G@V(@C`Hg^wPx&e-C2c(1MkrcDppH| zT{ENoC`Hg^wPw71!LEz7lQ zW;CM|L6_B<@vpw!3f1>)s2NnOmgU-2Hkwh2pv!8_xa;f=g@2yBk7iJ@T9#{9?`TFT zf-b8yW7U*B3ytO-q8U`ImgU;-M>V4qL6_BZ(Vml_5+$@%Up%`@<;MqHs2L=z7FUZ$>bvC^gbWf?qJ(B# za^y!HCx4!v36ro|T(jLSuHz*kg9Mc*p&9!Yx|Pj%Cp}9gVYRp>e^S@YeLiH6pb{lC z zL4rz@(2R+ddzF7UEB#iDgw^6YbZ%|;?%neHDBZ3|P>B+n(ekV#%AYH1tot5tK_yCPh97@2sw#a339H3*_lO$qnsL__Ge}U05}M)1pNuNaAYrw* z?03ofo|B*wB{aj2KN(d8-wzU2i_3mFtr;Y!L)nk86>P0SJ$%}xNnDt3=&kLgl72hC!;D|S6G(O;u^GMSC?-aGDuK~5}M)1pNuNa zAYrw*>^UvE?UJApB{aj2KN(e;LBeWrRr^~LcV2_AU6G&?B{aj2KN(e;LBeWr-CM1h zJGE;VgCwX#3C-~1Pezqykg!@@hfi(pUOGOUL6V>nB{aj2KN(g2GciZPYH`^UQS|*F zK_yCPh97_a=+bA9uv%PSj%(>wHw>TcB&b9Q&G6&TA6@zk5>|`r^TjRQSF5leG=fT$ z&gw^8u`TVBt*8$;JlmwM1p&9S)wojqvzdC3J39H5R#-UB!S6xE}2`W)SGnUue zy|7KQu9`u@YH=-@*4RBXI~=!@pb{lC!;f))1nbuo39H3rXL>r$Nl=Lrn(?nzvnwAj zo^v)m>GNd8HBab1)oO8l|MxY?`h5ETxf}^9Q9?7CKeJ2am&J2V5>|_A*C$pd)z1wX zB&b9Q%~;y~qmGk`=bR+07T3?8u1dzA7cxjti4vOeNM*OOnZ|_=(N3$9HkX79 z5>%puW=xPV{*U50Ckd;?wY=+R$vZcO3=&kLgl3GBF+QMp&Pl>*arK=3X|iNq$RI%_ zN@&L4WsJX7Jm(}~wYWBavoh)Re#js}B}!< zs6+|PxI@O@mNn9IP7+p&>-OzdCMWJ2GDuK~5}I+ljK4jL=bR+07T2N|RwT^^gbWf? zqJ(Cwl<_yNc+N?}YH=NU$BLxEjF3TsN|ewHe+K!|;psUi39H5R>%A+IS+9o-5>%pu zW?V1hZ%FZ+lZ4gcTKw*cq<*!hitjlIDp5i+9+2_(#fJ2plZ4gcI;+LX%r zLNmI__`9`u&Pl>*agCq8GP$x}$RI%_N@&JL8GnO{=bR+07S~11K22s{9x_N!i4vNz zdwJvXk4L5FoFuFk*M6^jnryr;WRRc|B{XA%rLNjEq z_LS@gHG_oJ;=28()yeXuA%g^!D4`j$SF4o$pk|P;T3i!fTa&bUJ7kcc5+yW4_G*=~ zAJhyIR*UP|>7OT)D?K-35NKlCqnjw3&g6s$NT#ba) z;`(LDx+J$p$RI%_N@#}c)e5p7)C>|yrb&3HuKcRHB4t$X=}=`$5ehVYRqU zYrj4zuM8O^s6+|P@Mn;+AJlVB5>|_A_WtXW`BOs%2`W)SGi0w;ko};Z50bE2T(4JO zpB!>r$RI%_N@#}c)e5p7)C>|vLE>ylB;LIw#cQ9?6huU3%#V7dR?C1JI=_Bv`^ zvS?E{P9#AkN@#}c)e5p7)C>|vw5Ym>(og$xo@qJ(D1UacVeLCqjxwYY}wyf!)W zzK}tJN|ewH*{fB`eo!+=SS>C)3)ACW5>%puW?UuX@7m(|;A@+|N#-n*-}A|`tQObh z$9$c1e=7Zd`Be%CDp5i+MnAVp<@?3+K@wJrYwsCfCCl#%86>Dg3C&p3`J;}P6we1q zSS_x4AAOm8{6NScK_yCPM&&cz$}TCM50bE2T=ok`eLqN0i4vNzjhqkOT|6HoVYRsI zH<+41f=ZOoj0EQvw&uhpb{lCW4VmKS;g}~5>|_=Znf1(wXGg2t}7B$qJ(Dn@wa`K^n8$n z)#BQ^&gx|9IU$1tl_;SZH_G_ySv(&kVYRr*2dz%tTOKk

B+nalMScGm3MNB&-%! z^;&C^TaK6?&N)F)i4vM|oQ%I~isyqQtQOa>Z`ULb-xV@QP>B+nu~5d}jm7gp5>|_= z$L?#B1AYn_B&b9Q&G?I)4}MlWA0%P5xE?-lU2@YQj~CY!2`W)SGv>(nD-_QMNmwne zpSS!Xd2vk0AVDQcXol?7%49!S@W&-2tQJ@Ky&IC2$WRRc|B{XBBoDbeoJRc-swYWAc z`8p~4N5~*SB}!<9?A0n|KdAj6VYRrn8oMbu>dcTqf=ZOo4B4v{WIw1GB&-(KDPMn^ zeA7B)kf0JJG~)&te=il!2T52ht}_n#KKXHF7=t9JLs}*EFsOM@VtQObh(>EvAjt&_ls6+|Pko{mm_Jf*1!fJ8ZGg-AC zB&b9Q&6p%rLNjEqR*?N*xqm-MSS_yemwlJ)e{wiZBta!g zXvSSK{@Tm&sLvo_wYYYf_-*pWUqS{6Dp5i+WUp2!`$5ehVYRsIEKJuG2`W)SGw$d7 z;Ni_(Mcqo>Mw^COTvx7W=1$%+{r_B!1eGYE8IQfNOXc&$^Fb0;i|f{L&D{7OpDvCM z5>%puW>o9;+cl{qtQObRwVJs#KZOhuRHB4td@b{XvLDpnO@T8DIf=ZOojLq_W%;w_xAPK9*_2tn`+`LI4g9Mc*p&75q z_#0U~A0%P5xK=ijemop9NKlCqnsJ$&4=ya850bE2T;KiN*iBm%GDuK~5}NUijK8}I z={2b&tQJ?h4UOGp4GYCFNP%puW{k%CAPK9*_2y|!-RdqOg9Mc*p&7DQv-v?1R*UP5=bO5vy+Q^F zDp5i+WUp2x`@w=gW*}j;xQ=bp%oTcv3=&kLgl5QI&8|r$VYRsW-Pp`koE|brP>B+n zA$v7DA0%P5xQ^MPxx4w;kU@et5wQ=P}da+tHrf(Ky&v^dB`9^B}!<9?9~dg zAJhyIR*UQ4XPUdOn}-Y%RHB4t$X=}=`$5ehVYRph?9jrE%7qLPRHB4tye!|x93b-( ze!C)JwYaJs+rmv+5B+nA$zrg><82HC@jlpan+e3{kSV+kf0JJG(+}k1=$a3 z1_`Uh_0wG~+#RDs1_>%rLNh*>@%MpTujbbk39H3bnBT%ZP#!W!P>B+nA$zrg><9IH zkc8FZS~;(U+oMLvAVDQcXol?73bG&6b2SoHi)-9%E!>0ehGPa2RHB4t$X=}=`$5eh zVYRsS9N)q%n-elfP>B+nA$zrgd@ow=-wzU2i>u`!EnJ7OA%g^!D4`j$S1ZVVP%}ta zEv{ypo4b}hLIw#cQ9?6huU3%#pk|P;T3m?};r z2T4$g5}NU=oDbetoF8m)>|obpR{HxotHm{G!XWpB+n(L%nDxv6+QNWyAywO)IM zTQVhNkf0JJG~+!Pe-9VW2T52hu9*$aa4$a?GDuK~5}GkZ#@{K$^Fb0;i)+j&16{OBx^NOyqJ(BVE8}mx9FNNI$dj;IT(idab0_o)*SC|P5+yXl z&(ELpTzWo8!fJ8ZGxc;`k)RSKG~*I~y{ODj_%puW^6ONy!@Er`5+0a#kK0Q{%-kGA%g^!D4`iMWc+n5o)40+ zT3k0=JHU0`(taxgf=ZOoj6G%i-CUd>Bw@9Dp5i+&Xwt*eZObOAVDQcXvRG<{yG=W2T52hu3FbBO z_UpsvE(t18LNf|7{wB-us2_tQtQJ>!yJ2qd#UXxzWc;+oWCm@7Ll zWRRc|B{bto8GqA@^MfR;7S}&tAL_=x9*%uTP>B+nA$zrgKf3h&AYrw*zBp;9>o+oF zkf0JJG=sl5Bw@9sqqJ(D1 zUaeC0gSxIrSS>C)3)AB(5>%puX87-8{A`1NKd!&Fr(1q}I=^hSxVG4*r(1Ven0F>Y zB}!<9|2{^(Wzh^0R*S3d3q9Pnok9i)Dp5i+{P!__w!!yZBfSY+1-4K_yCP zhW|ds&o=lB5>|_A=dZfER!4>m5>%puX87-8{A`2IAYrw*#$MUoEj~45kf0JJG{b)% z<7XRu1_`Uh)n?!B?%nYrg9Mc*p&9=B7(d(KGe}r1t}Rz|b0^#qGDuK~5}M(^kMXk& zK7)kS;u>&kH+R^JA%g^!D4`ktdTl@3;4?^AEv^%Xc5}VH4H+b;LaBR1_>%rLNolY0sU-)&mdv7 zxGw3~&CQ$^GDuK~5}M)X=lyJh&mdv7xc+l=H&<_A$RI%_N@#|kpZBv3K7)kS;wn40 zn_Kfk$RI%_N@#}6OO*TB2A@H~YH=lVySXd&2-jbcpb{lC!_UuuP&^+bVYRqA{~+&2 zkB~uvN|ewHKR++C?%EF$R*S1~x9;w%ks*Twl_;SZetzE1Hu!Z#!fJ7KxwpF;ds)aJ zK_yCPhM%AJvkj7wBVo0;KC08h4ZA61kf0JJG{eu&%dER*kg!@@FQ41P^_U$pNKlCq zn&Ic?{cMBp2MMdi_5No)+_IS=g9Mc*p&5RD-p@Ap3=&q0Yhm}EZtv?u1_>%rLNomQ zyq|6G86>P0*TA_w-K2>jg9Mc*p&9;qZ9m)KGe}r1t_NyWxQhpd3=&kLgl72pc|Y6W zGe}r1t`ASGaKE~cL4rz@&NB4~!fJ7CSYP4F z>W2&xRHB4t`1yH%^_kBgVYRsa`9g&oxjG#Ckf0JJG(+}k1%LIK&mdv7xNf?#!oB)< z$RI%_N@#|kpO^ihW{|L2TsL&CaF6~YWRRc|B{aj&&&#a4W{|L2Tu*Q8=?0Dr86>Dg z3C-~H^Zx2HzphAFEiO9?)AK z;yU=qg~?<0_bK*+1eGYE8Jz7SVYRqcKKWwO>*Bt}3=&kLgl2HIkA&6YYJ1*`$+oBW zD`t?O5+yW4zU8#}K@wJrtLc;%lN~$tFJ_RS5+yW)vwbA27T3wkUQ8aSCr{he&qNYb zqJ(B}wvU9>;@V@$L8O45(pb{lCgR^}ktQObc z=`SZkx(zI5kf0JJG=uYlB&-(K8yjCq4tOtQkf0JJG=sB!B&-%!{qq(jS0!f_`$2+A zl+X;$_K~n!TqieuJvn%4$RI%_N@xaW`$$+Vt|vcyBdL2&$RI%_N@xaW`$$+VuGepT zD`_|Dg3C-Ya9|^0))nvmv$&D>S1_>%rLNhqq zN5X1xjT^iqS^Z$xc1ci)5}F}5<6G>2s5}Lu;J`z@ot8v>8lMCMs`wtRSqJ(B} zwvU9>;(BY;hskR{U_WRxid3S6X2@R6<_AewEw1GQK1`l(5Hd(mi4vN@**+3hi|fvs zA0~U0hhqj3RHB4taJG+x)#Cc-%ny>AMuuY_5>%puW^lHTgw^6Y_oDZck#oZ_90@8> zLNhqqN5X1x-EhKt$&eZ$g9Mc*p&6X*BVo0;+HHO}xotu?rY1opN@xaW`$$+VE;|dW zGCxQqN~9SwKj`mP=+8O3>^I!~W$tX%rLNomRoc!GieFh1u z#r49~LtUTSLk0;dQ9?8P{ha*W3Vj9%tHsr_^-#Cn;~|3tl_;SZ{(esWZiPOBgw^8u z_{|}%`a2|_A+nUmkijYBqN|ewHKilW;Rwxm95>|_A*R_M) z36nww2`W)SGyMI1{oM+E1_`Uh)$4=7uKVL5g9Mc*p&9=EzW#27K7)kS;yPgIVE4|3 zkU@e7~-C}IAoBZ5+yW4?rT`??^ftDNLVedO*ag2@7@zK zNKlCqn&I#7>+e?RGe}r1t~b^XaV=jB86>Dg3C-~L_w{!x^cf_q7T32&%4hp$A%g^! zD4`kt{=WWhg_4mYVYRp}e{iUq^=-%?K_yCPhQGhBzgwZtAYrw*#y1$|CjAmJNKlCq zn&I#7>t`E$1_`Uhb?M|`?k_)w3=&kLgl72r`}(^T`V10Qi)-wLVXpVakU@e? zLIw#cQ9?6#^(P6d#r2O#XSqX%gbWf?qJ(Df>Q53@i|gw{&T@a79x_N!i4vOO&+fwY zq9m*q*Xr8RkLN=M2`W)SGyK_IxL%Zm)#Cbb{V2EncOioWl_;SZy!w-b)#5r}=_t2# ztMGdR5>%puX87-8!u6sgtQJ?@Wux4ceL@BaDp5i+c=aap}(zDp5i+ zc=aa7efXKDp5i+c=aa>(?t}kf0JJG=o=v zlCWA_gC9QIoj53Dkf0JJG=o=vlCWA_y>>gtbr=;gNKlCqn!&3-NmwneftQ}+7L5oQ zB&b9Q&EVCaB&-(K@n4J11PB&b9Q&EVCaB&-(KrejCDkrg3>1eGYE8NB+Fgw^8e z_~2+aeE*O^f=ZOo3|{?7!fJ61`gOGXVuz4Hf=ZOo3|{?7!fJ7CddQkU@eDg3C-ZupCqgn*Pd<1xcO5;1_>%rLNj>vCkd;? z)$;SvZr14`g9Mc*p&7jTlZ4gcI%@i8cTA^{L4rz@&ZYzOOs` z<&Z&wN|ewHKmPpDrOzN?wYcWy`?`unA%g^!D4`ktdToDn=`%=JEw1P4^>t6I2pJ@( zLB6*T>bUKBV}5kf0JJG{ax7?T;>f1_`Uh_2G$qT$PQ6X$A?a#kJ#$z1_NxLIw#cQ9?8P z_1gaE()WXe)#BRv+TL!*_Ct&B2MH=sLNomDcm2_&MC3_WEw1`!^>%mO7BWasi4vOO zf4?i=vSpDyh86>Dg3C-}o-}OhAK7)kS;u<@vugl3CNV=~jK_yCPhW|dsA6@zk z5>|`rl3M*-vui>I2`W)SGyLy&{n4e*AYrw*Mvv*|9zQ>1kf0JJG{gUX*B@Q_3=&q0 ztL_K=+~DIv1_>%rLNomDcm2_&&mdv7xK7!>zZF zzjwnJBta!gXomm&u6)a){UBkrxLPjk@1|ZHGDuK~5}M(Ezw3`K{kkGywYc{EvA^rv zJY%puX87Ol%C{_|`r@Ok~+=4Zk&90@8> zLNomDcl~UG?*|F1#dX;5{_eF=A%g^!D4`kt_q%?!!Do=LT3mx0^mlFd2^l1)LtQJ?jTAkdba<7SWe2}0L zB{aj&&-<&-d_PE7Ev~(0cXZG16*5Rri4vOO=jZ*^XFh|3)#7S+P)9ebb;uw=B}!<9 zpP%m6K87cxjti4vOO=jZ*^XFh|3)#AExNC$Vy;E+LrN|ewHKR@rU zKJytQtQOZ{bvn4yXN3$BRHB4t`1yH%^_kBgVYRp#6xzGKpN9+*RHB4t`1yH%^_kBg zVYRr%rLNomJ+WzV@iO7?% zT3i$V+TMNtYser$B}!<9zh2v4edaSrSS_x~dhOk3gL@R$6$vU)LNomLG5+c^pFzTE zaoyaoz5C{!kU@e-b*n-NacTg9Mc*p&9;qZGZKd&mdv7xK6yfy?f>7kU@ew>F0xqr_K86>Dg3C-}=Yx}FudL|A%g^! zD4`ktdToF8na?0$wYa`&U*;Y;AY_oB5+yXlU$5=2KJytQtQOZ*7nZsASA@?J5>%pu zX87y1{nckagM`)My6K@Z_wb~UL4rz@&|g@);zo7S~ZL%Us)eVIM_;N|ewH|9y=AHImODVYRr1FDr9Rjtm(js6+|P@Yiem zUnBVp5>|_=+AC#l-{s+$fdrK(p&9;qZU1W|pFzTEam|}u=B8Z`GDuK~5}M(!*Y>|g z@);zo7S}^V%3Rl`A%g^!D4`j$S1b5mBl!#xR*UQY=4GzYTj5xg1eGYE8UA{0|7#?l zLBeWrEqW250+7SS_v@m)3Tl?GZ9aP>B+n!P!0%R*UQM-D%puW^lHTgw^6&IJ&0$VspqKK_yCP250+7SS_wso~-HWbv?4U zu1HXc5}Lu;J`z@o>yA3L+@n{93=&kLgl2HIkA&6YdUbd$_iQ0#kf0JJG=sB!B&-%! zpT)J@{VPHS2`W)SGdSBv!fJ8#=u}(I)j|ddDp5i+INL|UYH^)@cWpQQ%aB2WN|ewH z&i0Y8T3p?C+}`c|LC7FMB}!-pXZuK4Ev_#{Z|^>u8!|{xi4vN@**+3hi);Tkw|DQK z8!|{xi4vN@**+3hi>r5&I_{lzA%g^!D4`jg?IU5exc=L(j{EVG@L58FN|ewH&i0Y8 zT3j`*uj3ZyLk0;dQ9?5~+egA`aeX(xjw{%rLNhqqN5X1xo&8`Pcg)A(n1KY9D4`jg?IU5exSCI` z;~qITWRRc|B{YMxeI%?FSCfi5ZfK*BL4rz@&+{LwbJPEqyFY`V5+yXl&(F)K(hL$-i|g>Q&m}L;3K=A*Ly7U<&tQOZ%uRoL2ej;R$pb{lC!_UwAqf4Jb!fJ8V z+V+{`v=t$P1eGYE8T>UM39H3*K}8|y)1X)JIFSUED4`jCe%>El`hJkGT3jt3s!aO# z2^l1)LPYrOzN?wYc7T;pt?+PA3-E z6$vU)LNomQyg#~>h&&0a#kD#Abh3F|$RI%_N@#|^UfUmC`V10Qi)&=xr;{}+LIw#c zQ9?8PY@a{6^cf_q7FVk?pH9B(c2aR&k)RSKG{ax7?T;>f1_`Uh_3JfHC#xO}86>Dg z3C-}=Yx|>1pFzTEaoxK7>11+)lZ*WzK_yCP#&nq<^hcLIgM`)My1k+@d2MvaAVDQc zXa;``NWyAy-TO&p^1}-ug9Mc*p&9;qZTXf(`$58LarK^3NN(8nl;XM~K_yCPhQD6h zA6@!&MZ#)v{mVU*%x)htNKlCqn&Ge4_D7eJkt1QXxR%s@Ho5xLkU@e^Pfw`3=SD2s6+|P@Yiemqf4Jb z!fJ6nc-iww&ErA_2`W)SGyL`1{^-(Ykg!@@8!BE%o@yO3NKlCqn!#TKlCWA_7j3&B z`S+$UK1fiB5}M(!*Y-!3z8@s47S}s>Es*$UySrOzN?wYYX{^J4PR zNg;y-l_;SZetzB`kNOM}R*P$|YhO$r{V9CzlAsbLG{ax7?dKDg3C-}=Yx~&-pFzTEab5AB+n;jh>Bvkg9jgw^8uX~B!hekX%puX87y1{cMBJAYrw*P969EDLWHzovOu+ zlPQOj>6Td;GbU60&8;OWp<_xic8mvyL#7P*I))5IBvUfeOd=YcBx8okkQ-$vgoq+Z z@?XQ*`~Ftn`mXCd_i@+L`~LR3*4k^&>)U&in0_HRzal}!OPCCGR13d1K_V6)#~j^z(T=`%Gv2vUj|QFFL{;x5Kh>ZHyZ) zieDL?emo~Z#Y>nB{d``}KGPW_!m@Imyyscb{&bK*f{K?g8T$FWKD*QzB*L)B^IgG5+XuH~D@ zh~LTw86>E936r6p&+FM|I)g-5R<2@s#)wOaK?VsbUczMP=kt2@na&^)mX&LB%4qTD z>p=zyDqg~5=;!l#_LnBeRZd2pQ(rliLk6(vqh?SVSSK6f{K?g8G639o_(e>NQ7nO%2Og$JYC`G z^mdS-;w4Omp0BNEpXm$|VOhC$+?gt#pAlq`pyDM=hMupjXP@Z|5@A`n7Pd$gBd!G* zB&c`^lcDEp>)B^IgG5+XuKO0Iio#t+rS}yHDqg~5==s`u_LX-3}6AS-CPkFhRT6)#~j^n7hS`%GnIAQ6_8Yv|6gB45iOg9H^X zVKVf5Z9V%;XOIZX%GGkwIC1guAcF)IFJUtDd~JPpsWV7~W##HW^jR^kZID5NikC1M zdcL-veWo)=gk|MQXgpqg)hx&$LB&g$3_V|4&py)`B*LAj;kzWRRfZB}|5%udQdF=?oHKS-A%FoG6-H3bu0+RJ?@A(DSwR z>@%G~A}lM{sxuQs|HVND2`XN~Waz6qJ^M^&kO<4l^+n4`;^Brt1_>%&!er>HJ9Qj1 z86?88axI=YNvt^(?Au9D@e(FO&)3$!M$+vd5tfy!!rDn<%b*~G1Qjn~GW2|H{c9wh zK_V%&!er?A+WOZ>I)g-5R<60@CW&negL4KFRJ?@A(DSwRuaR^H ziLk6(SMQx9D%1-yNKo+-CPUBH*1ty586?88a$VXyQ5-!QoWqfz;w4OmI;w^57bOvv zmFry1iDK=vAcF)IFJUtDd~N+}B;5`YVOhCqPn#eLCIlHIsCWsJq33JsUnA)Z5@A`n z!mBWIJxGFzmoOQ8+LyRskl6L|OXl1lEGyS7aRbHviT1y{&j+b^36sI6eI&xNay^VH>WRRfZB}@jN_K^t7%2jAhis&{b$RI(*OPCBk?IRJEm8(PEexlHnAcF)IFJUtH zw2wqsR<0wXlf`F?f(#N=yoAZ%(>@YmS-C#Ft&iBSF32E3#Y>nBKJ6nBmX#~tzFwl? z(IA5a6)#~j__U8iSXQptUnGgDIcKDw?~&i|$>7sI5@A`nHqGuSvc}I$U*{yKcnOoir+p;CvT|j`h?KX23=&kl zgvsF3J`!PBxl%R`6=%l>86>E936sI6eI&xNa-G`sl*rgA$RI(*OPCCObr(DzBoUUC ztI*tG;%wz0g9H^XVKVg9UGRL6L|9g?Z6$|`l2?P{2MH=(!esDiABnK6T;C-Q7ZtYz z86>E936r7k#{|y@NrYwP>egnsSUN4pAVI}Tm<&GcBN3LBYhA|SqEg2og9H^XVKVr% zk3?8ju2EfwiH;S63=&klgvsF3J`!PBxdx7TN__BlaGpqlikC1MeA-7MEGt)!oI@QLS-H-XnJcQi9%PW9 z;w4Om-v0F2rOqG`mX&K)!pma88$kvMDqg~5=;!nL>{4ft2+PWK{^>cQ^?N}E2`XN~ zWa#Jf`s`9?kO<4lwQB8badk_OL4t~xFd5FT0kN!*R<05mXN$jo3^GVi@e(G3zXl`` zmX&LJ=UF0h^IPfX?Ifsp36r6p&#SG<^c9J)tXz{1%oNF0gA5W>yoAZn&*$~orCuK- z!m@G=88lNwo(M8XQ1KEbL(kXNXO}7>LLw|H*Ssn-#lzEs3=&klgvrqJwbfk~lR+XZ zE7xs#X9~GB$RI(*OPCBjUt6DD>UNL_%gXgt{+VLy-$4cmDqg~5==s|E>{4ft2+PW~ zRL&Hl+S}>liUbueVKVf5ZGCpBGf0GG<+^|BOp&`=kU@fqmoOQv)bl}ocBwN+gk|Mw zoN<;|JuS!}LB&g$3_V|4pIzz<5@A`n5~j=&+dd33NKo+-CPUBH)@PSGgG5+XuB`XY zR@VkW1_>%&!er?CG5YLMXOIZX%GKhx*<$|1AcF)IFJUtD{TO|AsWLK<2+PVfa@`#9 zQr6|^nBJzrZt zpU@d3!m@I`_Ur=Dv1E`zf{K?g8G639y31lRNQ7nOy8G1yqQ}|b7)64LmoOQ6zP5ha zpxZ$rEGyTbg$u-?_k#=)RJ?@A(DSwR(*~VEA}lM{!odqf&oMy;2`XN~Wa#!z{`#H%&!epqUTKIlZ5@A`n{#rX`QrP(g7aMxRJ?@A(DSwR(*~VEA}lM{eW~-rlmkHq2`XN~Wa#@b`e}pCAQ6_8 zE4&Je`u!jkFJUrjsqJrJ`t{(_A9Bed zze~R!BoUUCYukid%&!ektL@ITjsB*LL7W#wAlHHSp>D> zS-F;7jFWdi5oC~{;w4Omemp4k2N@)&cnOoC@5h{b$X*YU2+PVf zzD1ne_Fj-df{K?g8FSS2;GOC37bOvvm8<69I9VtDmGr(MLB&g$488rStxBIWL`Z~X z<@#i8oD`jd3=&klgvn^3w!fFsuLntlW#uZM-iy=XtssL06)#~jzERuXxb*8m5@A`n z229E!i~ka2kf7ovOvYzw`zxJ(JxC%fD_8aWIpxwa^U~J`2`XN~WZb8=zv=1MgCxST zaur*hQ&w&sWRRfZB}~RKbv?Ku{d$l@SXQn+9pdG{E936r6YYT@-DiLk6(JwClfRv#KCwl@e(FOZ+~j5GJQoNEGt**TXV}f4TB64RJ?@AP)D^ibsRJqB*L&i|$a0g14zT$76Dm0zC>&Pzy8@e(FOZ-4siQfH6|%gUAYa2~mH zMvy^*ikC1M-PHCsIDNh-iLk6(Z>8puA2$v%NKo+-CPN+7($sOVzHSGJu&i9obLNp} zvjrI>sCWsJp^j>4>NsdJNQ7nOni9z^lfDejsYy`r5+>tUbwB2f^y@(qVOhDtt1xpt zNP>!&Fd2u{^TBu0uLqkqt|B`(nrx2SVOhB{ExcP6E^q&Ph72UAcnOoCw?BP$sn-XI zu&i7|&Q+F|iUb)XsCWsJ@p+>Ib;hPYA0!c$mFwnum1VozgA5W>yoAa4Og$f*pZosNoxDsoqjz?A}lLcyDuurFFy)0NKo+-CWBXZB*LE936r6>zu&i|$*7~YzXj>ngCxSTauxXeE_oq-TKYOCLB&g$488s7vrE-i8Aya>VAwqyVMyZ!m@Jx>(0C7>H%&!er>}PoG`t3=&~kxiXHZA`2Z4);S3(UczLk^UySXcBwN+gk|L_^{=Y3 z&)Oh^1Qjn~GSpEmO&teK28pn&TE936sIAI}%}8xwhS0O?JE|$RI(* zOPCCGR7+FGLA_7RKq4$F*Y_Q&$&)97{VoYAUczLkqgt9e4w?)SVOhC)%%~>ii$Mkn zDqg~5=4F?o822^kf7ov zOoqN6qn|eD3=&~kxgI-NRn|EjoF|f?;w4PRcD4Pzn0`G-A}lM{)d5vy-`9c+5>&i| z$^x36u2Z^w(T(wVBk*89E3=&klgvqFipJ@e(FOZ-4siQuh^!u&i7Mc4n95 z_XQawsCWsJ!K*tGVOhD7i)5FR_XimysCWsJq3_4&rwzItB*L{4}AghW_YuCJ$M zk&V^_86>E936r6YYT@-DiLk6(vu9?JBXf;U?<*2iyoAZn?{iYeL47=rkO<4l)%c?< z@|W&G1_>%&!er>}PoG`t3=&~kxpw}QMPB$I$RI(*OPCD(d|p3o&>1AcvT~JsJgdx_ zbwYYyk)YxwOa`y+NQ7nO8vSKfx#z(kg9H^XVKR7iMb@comX)jf<2hv0`9TH=Dqg~5=;!n5zNpC{ z5tfx}!ml~xf|MYG1Qjn~GI(`IA}lLcnV~u5fEqyt2`XN~Wbo>aL|9g?yH4bkQ-2Be zS0t!-36sIAI}%}8xn!MqS!7|5L4t~xFd4kMBN3LBYx}@>IjBjHL4t~xFd2IL(`T1@ zT#*RN%9U?QysUfy$H9=G;w4N5ukJ{MW#wuzF<$;LC&(Z{#Y>nB{d`{C7uCn}3?#y` za?R}?FUK_qGDuMI5+*}$fBNiFXOIZX%9X!#ynNMm!Rx-VK^XOIZX z%Js?SoHAuekU@fqmoOQ;x+4*ml`FA%PPy=jAcF)IFJUrxbw?sBE7yXJIb_lDK?Vsb zUczKFRM&$qre6<|2+PV9UWJ+KK@wEFgvrqB!Tv?+?>gN}mi}UiY?$ZH`!7D!TfX_D zEstv1MNVqD%>4Jjt^Yq#f7O7F;>)|18f9Ak9%9Cdd8Rz2`b_c2J+;dG!YJ9R{YysqKEp`4^V!*^d}3XSeE0hq9^#(CMP<$I8;$a>^?ButBwIfH z+pY4;S?fGRo}z{2!8axvrPQhd^6&^-u63lStaNmYhsb~6toUyEDx(}MeMVH+Xv@!h zc}i>>Wy@~MQ-1FymoAxXh}zHemQ9-4^5jg(^6d$>>=HE}+N|Dn-PsUFKiVYPJoAJp z@42!;O#8t8cb5p>v#du+@IGW+o_u(#*#ApgL%T#UqfNVlnP<8zhGvmVuPyKpTQcUC z%?HmiN-)ji;ee#>=hkw}F^F#94pg9KgqOXQZ%B=|C@kO*eSM`w_r>)ij{BCAgJ z?XRei2xiAeX9RPPwGzw`)@5!5?)soYBAERfok1m-zx%&ukO*exMrW{AbaAibwu5~V z%_Box2h6I>RFVE$cnJ4n#Q zBb-|+wlkqEvk6rI6k(G`3pD4O8e zUGVK1?Fzmz6HQPFz7nHdT$0-kDkOsMzeHz{pey*AOEf_x_#VsuUMq)4|K>|{25S|3 zk43vU^4*qGArX9OB|3uyU9q<)uG`>CO?tT;3vR8bkO;oP6kRJ4bg@U=3@RjoZ!kq? zkf4jB(#;6IU80v2d}BnH7ks!+bS?3)=Nyg%UBQ=DqHD$F2HzO@?-^V!iQwxY(HSJ@ z3cdvrO$1*I(Ms^;MP07?-@7$}pg+cNJtxC9jvJ+BRvKj-${nIJ(|?0XqhNMx0R9s!M z*Zca*yQfbw{c}9NzihCoC%-IZ%Wli5kofa-ioE6b>k)KuJ-HcFNYpr(BC}NR zwSxp*T>owcN5l5Q{pIdWcDY=VOHd)Pt7U&V(eD0oeWM%MK1jSUT5VmuuD5;A#ck8A z)v?8cjv7X}x_W*y-7$l32wKVq_ZUz++8*%Or2lk!5GkKnQ%o<2~vsCy&rAW{0BfpU9EUk2Mj7i;LY zoC=94Up^`K<@IHdpeuIEi;vqR^3?5O*6rhmHi_l=yP9%?zuy;C6O%pboCIB!hiwws zIwpDuF1O6+&7#(c>t%4cB*ypIBDyW@=E)#ISJL#YqF0md9)ilQ^V>v?Z>)<;a@PkH z5(S2B7n4N~PX-CP;$A%{7TrF`Lr@{{c=4U0=6GKQ3A#S|c9+Qax{si;bJka)&|>T2 zlH8V4A#roF-D2cmUj_-f?l`kY%qrz0h9vD1$5+^O5Lx?;xLDYh=PWrPG7ahJ=_@KE zZr!n8G)VT15)yQ6S@>^J>~%XT-Im{8`CBn^uiZYrO8Hjo_`{CyRuj&Mhu*f&bXY-R)(4dd&ukNCmsuCHV`q?vRNE>J)#~KQ;IioA^{$&ig~aKiTg23p zz6=s{@tK~R!8LWD$G^p#e)b6;*Q`rWA@S7H`$fN%zFLu>Yv!Zhh+c6%f=boPd&T@w zc71S3v1>)*WXc}V=vLo4=d$SHdU7+UkXW|$Yw_~V>y1RZxD~h=d|t~l**=f-lJm~` zp4V<}lPH&OwC7Quc1V=fYS=T@F7LFK_g}Nmx!nx9I!sKIsf(^ha9Jc8988oC#`$VR zg02e*U1WzOAF*jn4|(;w>1NC6P@%ir{P+}8j=#Bwtlry}-F9$U$A0W04}WZz%WRjR zLSp8NY7csoFM|YKtgV|tg~Z2gy2<|PcN5X~8A#B@UT`zmC;3nGkoWeq%jJ?>f(nV% z>wC(R&97H0y6&5rBrlcq5qC80BcEGrN8;!^`pA0s*fOv5-CFHl)I&~6wzD3#Zs;z@ zr`YoN;vHpyM$dZsDrI#SS*W@_gIrp!i+pmDEmx@APF_f#OW|fvA<-l)QI0#~I~OHE z*TSKR^3gWFD;CbIn0~sqtaaLMQQU&vT2UcUziJH78L9zx2~|Xn?ZuELG8NA;-`EBN8c+ud&{9a?RsYW z+zcutes0@aCie4<5)yP>+1N`SF6<+yJe0qe9JbHaolA;cD-xwzCdp&^B&YTS=v$i|ON`HkksMDjjcc8OKR&x_}l zy>DD+_WdgAysl8O@5G6g94__0($U^rParMBBorOZ*@fO|<2c<#&r0a(wC`_7*xV?)mK_ zqjacsTGU@>%dDZ>4k{!TRX;7(j<>W+aD8wcY~6KSw664-r&d%*j4ORyJo3G74U(X1 z$(7^c@IfCzC3VLMQQ>Rr;*#8UP$98?`cGoaI$s6}x|%!zQ@ra`{#g9Kg4x1JO|-t=Wq zAyNO0Gor|BUj_-fxNW-YoC=BgU49W0UiW2?po{w$H)G4`AH}Obt})v|{hr6gH-~LG zd(IPL?t{MVyjb32qS9E~Cx;vVDE7>AJe_l*mxVM{s>`9sKpf zF)?(QuXm}Ch`r89(8VKz+gDUb^tpIKy!)zeT#=wF_7UgW8%M;#opvv?d+!lZAd~GM zjvlvGR7mtMbyWOR-PgM$=;G1N%~*2tQSn$6TdVD#9}y+G+A^2q5>!YuSb9VhobB6- zlAwz{;%0DLyZqZx(PsaRY_%jl?t4@;yvbK9jwQO-BW|tAocmG?`Czr#`{c`XTx7~@ z_dZ;bOHd(^CD(B={z*&6Cg|ec&Lws&J0Z4gwY4ht^>OiSh4)MiSzDK&LSobX$Hkj3 zSvodB7u)0#T|fRw^c!Gnb!g8%@p7w`rdEC9PKm)~?SFR(DkNghp(jDt#&M@bv9rEe z_f$x5&c0i#j@kYYYu~o@9e(I{QT=gSF86;o$&yLSO`BYTuG>;Cie3M@9>Hai*m3zc zvG|a$9VF=b^O4`h8;9TW)QSp;i7kE=O+WT!kf5vl>~rGqn?54#+#g~`PCI_SRpkaZ z+w#Qem&J<%edCG>i5@Mlh;fa5M7v)vir*^Qvx#o^T@rsDwR`8-zvg)0cma8#n%x7e zxqMl4Z*I4{*cntve17J#IC8{SD-v|EeeNh>-T!R;hgdl2dhK8fNxW75vY1lNcZ?!I z7kk956%`Vh-oGr?rTO+(B=DW{kfjOZp+7yt*dU z({d^#7RlRWow2_AJ|yTG^L;+Ka)Xbc(sgzo+4dfLUyMs~dzT7{lVftpwg2|rRU<(c z`_0XuLZZRSc)9mA-})dySM2q{-}Z6cEJ`jacf|YJL4`z*^QGjnUgJD#kOW=(rrj>z zS>(&0LgMWbW#q}Xd>JI@+SQ=AJlELQSHYX=^mC5jjdHqt;GvrGn`6HHRq)P4?F!y) zsLMa?E-lX;vwI?U4N@TyytPo%E=wyA7i=SSz}M_X9=~?4RJxc-j@a zuc(j+-gy_DL4vN}4R+B4mEaw8|9h=S1aFs%&S0(R3f>hLO^8lHK03pWxZn+D+7-NM zESd=3hpQEi-QZok(F7F|!5f0338n|{BhxO{)*XpdNCa;hi_RcHSMc7jXd-wUo>qdl z*8T6bA`!fgE;@s?qKoUsZ8_^3ypQaEuN8^l&1V0-R&;S~y0xN0B6#z3bOs5!VviDz z#NZ9edbwOu>{^is-i`dVZr6%uTdTPyz3lfRthFGF2|3JLzgH8w%l zgTI%RyH>sCSszqLG#*e;UQD*5$Iak90N$nG)xAqlA;C9##3tz4TJUC>@$l!Kc2Ie$ z))jGn+XmxecI*rid@d53pey#h3@RjIKVu<57oT9ewcTWDJy^9>+35jByu(^ zFV|(X{pMznpzG(Cs>&80`Uol{lJ2b}kIYT;tU(fV-L<)neB?IY^Ye^%Jt9xtZ|~{l z`@EUVR@aty6n;bwy7G=Eqt8Q4Wbv~0Uf8QOo5%tkYL_se14=jU6WY9^a4vUlj7 zKKh94^57?Cxd(DJlYQp+?%Yu!QD=H1nRwRMauRekdZVcvJi(VS=eY#=#rw9kGaDwz z_g=8&v#lSK75;kH({d^#J~{u0?B37P?m8zySM1)ULSn{?kI2KVeHkR^;+l19#Wl#a z_E_&Gvdu+b2G`*JADhWT3!>Mio58h4Vsq0+WceAs^+AHJ?kgXWqf>nZmE}1T+s@p!nH*ftE|;UnC8&_N^;}a~;UQnGNYFL-xu$Y=dmq95$Jjbe>lK7>06PbUrrQLRrpsU_fP2`C`d;}G-vWc8j#;#{BDRu^lhJUCwHS>)UE{m?) zn>3Z@`uT`4U#l^C($+WSLV~Qm)|NRI+*(l~Q6qD6SvS?!auRfLOuHFex0R|im3xQY z$habL(~&0f(Yd}+!f{1c*Lh9k{hNFQw@&sOw`R8;R7kK#ViR<&n)R3*UBNe#g9?dz z=XaJh7Wmf3(9;9uBi}4C$D-7YPs&0&UN_~zFZGkJ{^dItr9$G)2m8u>-F(k$Nzm2c za1VLgJHF%K2lqTJ^Sm|3)a13z!{vsf^G%txb^D46iR6cd%Ey0QV(8ceU2Ky}@K>1p zWgvgG=@L{(EV%fzy!NK=xd92f_#QtuqfztrGTR%iObc($*j08a*4~u!b#E*8?)Lo> zi3*8QM|;ULExLO8iUeIX)+Wo9OM7_;DkRPwNs;}kBwvT1YwF~#@}qU5JOmXICC?3# zUoISc9fB_Y2Gi|bDkQRAdrH=781ZC~po{C@%~-vto}4zKsae)Lz3R!v#cjFh-S^A! zhwk@eoIg`rKKEmSQ4Y1KBNNo#THhn7`9~c&a71elL50NG&+5nl=Pm8l>h1n@<&*82 zm}ND)U&zAGH!$VhyXwkOlkIkR7jLtR7Y+o=UX2n=*m?0UO8}keNXRFAyMewI&xt}Uk1nM zcNOZ&><4ZCut(f>P$4m5N?rNE>g)9`T^mo;m1{=$h;d)nlSPZ!arN-gdb0BBW~Q|q zm2Rz4@2n*+U9;Qvy8N}|k4cu`=y3@uBwj95Oa8XU(k{W8Bp<3L?|A5XwPJlqWZG6w zRyk~I>t>Lki~BK`V12XPT}%E@*Y+FR=Mq#%v~E*NrY^K}Y=SOs|1QCGd#+YJxvIvE zj4Kk8N7j@3kN9fEkx18^ck0P^NBanF2NibKmN}%|Cb-?W?Vv*9xn8wpyCmNhMS`yT zbJdm|7y1aEW$@`S&F77eh4EB4$v|93spKfHGlNdIlmaJXJx7Bi;)7AGOl{d#nRGFP$ zHvFxYSyR~`E+OB1s3LA*aTgC7n(~@ zArbo>bR_8FyXo8vzHyE3qvMiXf(i+~n=Up%*W8V3#D>WzG2?YSaoKi=)c%r zlYP;0l6bhGE!XHYLu|e_+_RlG%`{dNmG*jR=+3bsUrSrAx@wZBQ+kYtNN7A>eAUdl zCg+(T%GJIe!DW#swq=4Sd%LCGc95WJP|t~?$tBw+mtfsnE*d8;K7J#$BGG^7vtnG^ z>(z=b_J~`n`xd5(!d+~A`!;PXK7ZA|!D?ZPR59Y()1Ka?LL$E6qvCL?uT~`J+Hq&9 zcz%X24ih77t|e^%V)aGCnXy%q;68xD_p)IZ3QJWLq11i=slJ!rDn<%OGE0k)W&J z%1PpbI3K|^SS-&NaVc?xS%aHXMvFgRw`I4ls7yGWD)wBpE-uL>sF3JCHdXxD&W@Pa z1YI04F2TApZ~5ji;o741*kGTY?ViVBG@I*${z z&ial9B3niIv^X}0ccpIa*`Bx+BaAPOe7n`7~^oLS>__OamH5C${j;k+*GP$6;qm1NOv*Gx|a3A&z~+E27Q zd_5v%<4|#Symg)0^_0li$wz#bI9ycRGQ*^|s5o9s-8s#ax0M_&N?x`9-E9XI5{2dt z6K5;?GFabAHT#RYKUo*s=VnkLk#uZ;*m>NSL4vL_69$Tc2Ym#U#rX$|{#$OORwOoz z86r~N@@24AbaCCdE$8~^)@Ha^IxTwLxCGY$iFFx=i%K1RYmfw8qq+_g9V_~XTjB}-O?#tk^=;D#V&7eYJTxuV2=sjNs z3A%VJaWlB4W`B_+s^+xogKO3$sE|my)>AaB?c0}-po=}?W>6vV!H}LJcVAxy3A#Am z+>FM(M~ka3FE_`&4quKH4^Ml`l&2-UAZi@-%>$r9V!?prqNaE5Am1&(w<7R80dB3R zkSP1ir=oZ7PfQJC6Lj%c|1Lp=M1?FXM3z>*nH(hOirsQ5B)T4-CpPR@<7o#8y4dS( zI}Y4DLA3eE&Jf_&3o}k!CN_0W@?=mU!S89f86@c9dwE@g3JJawG&Vt3?Drv4A;Iqi zx*2V!y)1^_Vn_Rso^wU^cw1(#yTo5>=Zg!a>^AXxx%uMzzuq)G+P2MV(SF9;p58tG z^c>OpJ?pydy-A{PB|Cd(SHjC;!5j9!yBSnSoGCL`RC(P;G|o6nte$4m6Q;}(+di~q zZjWvT>waJAJTc|K_1eJ}lDM$(6_NcjU#&>c#WuOMqC#TppL0dNmA(uTbj9u~_D|M( zXREW~>-80TkwlB%W{de3ee0YAU9ra%6%r%Y%@HqUwWHGQD-v{ZOvffly+2R9`L(V4 zu*c?$aw~l8;MiTYcDA^>#jXSPx|>0TM2U>E#os?(Zw=D5z4I&)x!G=M|H#NYQ^>7W z`6~ZRvGs3TX0N*hx9!%oUJ(^AK7z`^!3#vsG1kQ; zx$U4r;-<0-#H<#+3=(v4f9z&({7gPDQzTcl%jF1l2`VIp44Nq-Pxxv@g09#jkqU`< zRc4BZr~5KU&~+QO0=FI9CYH*XLR7P(giCS>DkScoI#cBCX6e`jT|5%G1n(j74iwLW zU4jY;-ph(j(8a4)m!Lvo;GOftucdwO93VkgfxT~v#&7%1!l{s`_2qi;MrPlgI}&uY z8?r~-d)v#NvkWREMh-Y7W+hL)4nY^+IpX#epSbbqBKyrHsF2`Y+}H$N>^GO7LSo47 z*Tn1$zUMe3=wiRQ8B|Er8?jxqI5gVRyCmphPrDgZNIX;QqNxAicuxlJQ}e8!z2Ih0 zA;I(c*aThd1(%>gf>!{s3A)$|EauBi~us&a(zP-H}V~scKz+C+3oWes5<`aps8I4lcK8o?B%3e_tCuQbe0v5GbaA_J+rh2q^Ex@?;(6EGqL@Kq z^S~VP=gYo590|I%eUwAyZ|vLeQdycSr+n`@>*A8!c2FVlMRHELKFyawf-W8<+zcut zI`7UY-#+5YAVC+8sBQ-DS@1fVSK%%}g#@oGV-s}ozOPGAA;CAf#wO_E`)pl;3JJbz z)+Nde%_#@em|%{Bd{^9rUvtO>DfYj+1Qin9AI~A1&i4_OFK3fS->}NaMK{YkH%I5W z8C))jxR%-F!+U%gJR>Xgb{3hTnk7!2`07S#MWX%cIGO8H zU#-{}W{jE`D3ZabJkLe`0wMHX5*HbEEPN9Yn%NNgV%F9$X8WssmN z-;{V+`GRkKP-!wTUj8x1y11m+wIVUMd%PUiz?Z>g(Ure+ynN=|IMdT^29-}X=aeZ+ ztcy!>2`VHKo9C1ZpYUanpliX#9I|M6A3&BGGeHoNV@krDGFx z#lFU&LgK*A?6UkmUj_-fl8a=QllS`wDie}#mfcTT7nkI=g9?er=4`TT4qxw*psPdW zY;s>sAHluM?3r2Q$Xs@t;9kkC6%`VVKguG1>F(R2NYJ(OuPpMy2R?#IIrSTZtXb_o zic5-JD-xr>%qsUh=-b0_S#&jQpG`g%@e#a-#QPe2zpPs;DkPX4o1lyPN|&HQB6d4S z(8Z&jo5Asu_Ig&CX^=x(`bHuNy4WT+g9?eo$Fj(_*?oIa5_Ivn z>t=A~K%P}8Vr|wp%>Ih^mR*7h3C<~uP0+>r@Ge1x#FXkY#UqpLI~8IRbn$%7C8&_t zy)RAFxwOo4#34Z!&*$6>DkR#rIx2?0XL~v}K^Ncn?-Eo<@E!QE3A*whI4ize?t42v z6%w)Er_Z}iykEv^2DesJNbrtDY=W*?>r2Q=cXjcsK`JEpJ2p3i1YJpK73Fj4>ypv$ zPozSEzhiSVNYM4tu4?k>mwI_JsF2{VDBTPabREo4LuM}2+mk_s1b+?cW{{w(U)=(+_{T@NfRDfdp}pLW(9Yv|UB3W+H> zOUM&fd~@zd(6wN3aXB}uuN_xjEhU!@Of%~|ZEY#JyuK~7O>V8IkT|-!lq?fx>DUBa z9B(eMwc;JJ%^JI`?OpGXfBj&~+?rj23W;5B-XZhk^o@2Bba7AQW^l{tn!A)t$#5fE zEs0DmOUcpue0|03oG$jdTPrFga*b0peASmhf-a5)H-qCR<9)^D{e_~pN0;D8B=P=_ zcgTkK_(mcLx}KkYhuqxOM^rs?yPQzSwlMd(+hy*A8yO`ehGn@!jvwReD~=MnI6~c) zv%Y7W-yv6zzLCBnakQ9f`MbWBv#;o4ZQWW?A@TcPx65hAd>JI@Vz0Xy{O%IJSH&+X zxdasw{H|1Nf-Zjf$R((dNJ+{hyT9q1*GGab_PU!vg+%6M#pIsp_PblL3A(s#x&##x zWiC~fpI!BRuZRR)vEM>Vg#_P{=+=q^U3~YeOHd&Z`;Chv=!*SL**nhc5wl9!Gx{M( z`^51T-OUk>vk2T;Q6VvB$qA8ZNKZq@Cg|e50hgdcqF>3I<)H`rdooDS^}pSLBvCc7 zplr8ss3(KVqKn^{aoa(KM5fLq<%flR^D;=##c#~G8B|DAPAM-Ry)EKt2MN0Vw{Iwr z7`(88oc)+DgUh0e-@0(yL4`!z_l;yW>ASZ?g03#_w3hc@^ZjO&3JHFv-mMi0x;D2- zl*>0h=jmN4Bw~N_e#^pti(;?aUqRen`CBn^uf2-r$aiZ+g+!|fXT(Eq``*z=f-a7H zH-id^?P`uj=~2Gxa}soMD1YI2Y zZUz++&m~rpza~EA86_m>;>dS1sF2wG;$3p+310>Yx;XOP3@RkLfBBFs|DEsKXC&z2 z$agcSkQiUQqb$(KcYl`zT`8-($U@a8d3u)$i9zkU%HpRcdI-MzbNsze$l7E28rR^3 zPsj|@ZP{%Hm9aS!Wr?ZQ#U;4}6%qpnCCc}Q`!Yz-mG9q)GO3l1X#8^*DT>%TTMwxI zx%{c!Qu+Q=w^me0+@IVj69HvL0-+?Xyhaj*UFZUz++Y+r1Gu6EVC z$nHgaEvG^vc3-g_RsQTEpC}pKCbw3sJBgx2y2|aJ^zn=<5_BD@&{cll(nnP7+DR@R zXqCB7b&}J*vt`~jbZbS0#OVc{WEJ6CA0+5HyT6khHrGe6zM0E)mAihjV~p){Yej{` zoP1s7;ZeSOuO#T=n07NhJ^h3nureaza_P^uN7?Ic1{D(9pX@9fRQ8Q_5_ECoyBSnS{Q6aA`ADKKg9KgN zKe`#*XCxKuA}il@BYPhb4L(YgC9n9_2S*8ATu*MTsE}CRI#J&HZ(jxpx;Wn44336x zAL}gRg>5;PVS`+lI6utGEXhL-Em2=Yek|!|4wq* zeBV~fWzoeE>SjBQJxC9jv{0&WPf-XK+bqOjY z_#2wo1YLZt>Jn5)@K-mn3A*@P)g`Eq;9QE>1YLZt>Jn5)@H@=03A%VM%O$9g=sP~A zEH>Wv#GM3PyqD!>P$9wZe8nc{;=L@FphAM*`HD@@#d}#UL4`!G2kOdCioESP_aQ+S z?`63eR7mi98nFqwVt*Nk3W?a?=9u*RCQ+qgThqc_=QfEF>mM`a$%nU!{lD1%?$(M5 z3BCt3HbED!yj_9{3C@9zP0+Bd%9@VWC6%zakXKaEl z?onNW3W+QCKPZb1T;SSjN*1{D&cT6U3>TKZE&$B*A z&=tFPsgQW)^`5fYUA}R3-_#^|sq7S!-sh2Ca^Bg=ro2hbI=lLv{c5b+4k{!jXG)fD zPq1`sg02(mQslee`+gNqg~W=wgJqYAz9$VN=*s-UDA}vM@4aeNNW}h9Q}qFTW%Y)3 z%i;H`%GU2I9~kJ{qNtGI7q#5JB0<-LzmjG3dALytAW^EVjVzaW-`6BkRn%-rk43OJemOYKxj}X}2BRU!5(`OBQKmMF0d&`^O_qCjTMHlz^Zp*o*8XZfP zr%v1Da?QE~6%u`>Cd)b7e6=D$7i;TgP$AK%TC)7tN?!&Ex;Wn4jBPhplO6AwYK~st zcc>;$p0H;xJj-+mDkM1jA~r!6&oW(t3JK1>h)vMNvrLzuLW1Xyu?f1^>n=fs1kVOz z6LfL(xC9jv-)9&pcRoAYb6!G%E`Al&&7eYp=ctB=ST2$l{swDmnft@JSgIV(7E@)H z2!BPVl<>D}s>~(1M3}BzVXag-tgR}$M0oD3l<-TasvMqQM-k!oOO+CSqfC{JaDp5e#&dm@>3%{JBl<)||d=M4MbO-4viA@P=a-_pm8 z|3T=Ow9E0g$eF{`b-2n1pBt!hk56xr)rZ>u9%dMV3WCSocZ;k#SzYU^9&P_k zygcx!aEsg+Bi^xom}P;j)Wy^6n>WnIqKAph9AK*BmmTu&=L3(ADHr4q4*xKh~hB6_tLeIpv_0 z*2N{ot`&))W#i?l7m%Trum2)xTozs29<9~!Zqf z#Mb&i9ty|g378R>qW~x zH&QDS`{LJ&DeZk3YzJL$$xp?iT0Vm3xShtOiJ94~>y7W%i9bH~^)8hq3G2j;f!4(( zxqU^2#Jt0wh%xG!lpdk63A(OL{X`sl&yHi4pi-g7C*t=e*2Qd>phBYG6Q76^N7TH7 zpjH}-nB&K@D@B?2+Z%hFZSgD>#NT{5nc0wFm_FhNJtZ% z3$`(}3coX|>dtE)v+$7MvQCy?C+e-XG_ylO72H~pDE-bl(WSGc4H2=NOVGvITCe(7 zQIRy(J^b3LuN}&*|J1eGms`XyFFa^kPNLj`^6s!&TR?Cm6xE4dvMzV^{=8LX{>L_#v8=MmA3Be5kn}q z{&V|^MEJ$qpjH<62SFFFqwT^i5=o;%BK*Q`kP-0_bUpIaMp67Bj4KPMT2Xm4+a}Ru zwskSvn7tV!+7H*8SZ{cjw}7VNhgt24w8Q#N6RAy_y<8( z?7LA^Nc6lmQ2w0TW}Bsl86@bcvtpo3uI?kKTxdB^_DirXE-7{fiPqD>YHv7WvR)`~8UP`Bk&NbG4cKqj{FWssn2`Pu&R zU|kWzXyJHnQ;wbQN)kX>?GB6iEEkXYFLNqHg8(xyTYTdhbM3A(0y`J~*J7lZ}W z`e5Bl|1?l8>=>gRVFp`BqHN_sa_u-|cnP{H^cW=Dt@aVT>&$DB;^Q`nJaxPLr+34Q z@Yk}c-*4TqUo=SWW?YfA--wHa)i30O^$`-`FX5FE{-$1)V?Y1+=-XW)-|Om^_saEn z@tvaPcw3GlGT6UJ8Z+pMU8~0rZ4%4#cQqMoZTKC6pdC6QqPHk2B-n4JKFY2CT!JoM z$yl%bSKaZ#6$^>~?Rtv?Z|quQ`&@zwiKOXUMXx5l zbHw$zSYw$CM~kSH^H zv#52#j-J>AT^w(QNdG62cDU=eVnaduE!O&5Ja_c{JE*i|>SLr0Gw%8>;TxDr%HUIvDpsP{t zuf%6>`v|r+{H?yq<37gCph6;iPe9ODk)T#2=;FT1&EV6wnh$MOcey&7zT)=i5>!Z> zF1kfbJ=w|7wm$0Li0)kybg|dn3@Rid)wYU5wUD8fum9XNNEb(s^=i8&xTcnE{aU=d z^F~GqiIXXNM59~ns5BXB`TEbT6{ zk)Z3Tr}v9~D?!)@l|kh|kAI6f{p={=l5BM>;?|19vK-%vGWFG)DWb+Mmqi!%7;eV& z)4gS_)Ap>m_A|X@lcs8xuUan8YF&Z~iIm@a$)!sy?GoWkVzu0GPO>V8vpS;M5zZ-5 zN{5MwGIf!y;inxEWwjbO)3;rvdY2hoZtPmICac%?lqZ|3nbQBYR$MNL{3m+IdwW{i zZ8-_L;&1LDtM~R1R611XE;m1ZBef#&ahqVu(Zw<5W`u8`Q6nRK>x?Rg@6k|Y zL!|!`NuxrdNm`;DcgA;4O@gka<+{ixCxHkv?r7RaKDXFjFBMd8KFE{LZWFvt3~Lq9 zd$@`xyUBgyCYlkxbwhVKKE;;9Uk?TCP;UJfNuxqy_o5zhQnID3)%>dnrn6SuW4Htr z67{S0kx9>BJC6hzBs&>8H-(W83GKStij`XEuNWs+>R@OrhPi|Z+@m9AJCT@U5&C5P>^%Z(yb z8}y&M&PiO^*h?NRjIkRrz&{AOes0@aCiVki0Yy-GWoK_Wbfi!ggfOc|y#6aIM**>i0Y@zB#S#+M8!J3em-{luE z;dM*LCg`gF#u-s$wvS*tSoe2_of32I^AS`?TzdY5I34k|oCIBe-So5AG{~1hg+%eT zKZzq#kztyzwH#cnwj63Mro6g}QVM#P3h(n!$7^^{&A^M8>vj-SdOof0V}J~HEq zW5HU33@RjcWrJi3l|C*W z`QH9_H-id^sBJLJAVJrXE62s*gUAR8DkQkgyR~9FMvePX4A~gnru4rSHD zwjad#H&H9))_*QRSL}TW6%tRE_(3e1=*u8M7x!bfI_6(hEAG{H?>!<4WU|ZUl3aoc ziED2h5es)>lth9I5_C0KdPEeQ?IXA!_o!%ilP`k=UF>x?qus9;#cvhuF*Wnx3*zA(w!FOWMbTx2 z?^sKP1V^ZwL4q!h9+#j(BKBw}K^M0Ilac;UB#kX+4ZGcUN&I=#o}Ib1qCz5kn|5%X z7-o>5>(ADIh=r4U8R6Te)v_|Ze_5 z>#fS+Tfw7RPG#cs%i_g>@0oK3F3D{N6%wDHxh#$xv2<*LF7}~IP$9AA@@3Jzx$WuL z1YPWDL+F1Z`V8P;=`*6jM)h?b)hFTicvLxjI~4oM5OjrK>hTfEt^XovTo#FmEq)bE zKepM{YX1EPL09;8sGwGnfS^KR$K~I|;zP)=fXbk9Tk1uz>tE{a=xVuKk}-QTNDM#p zyQu!SrDGFxg>RUTYDf6pC8hL@J0%8}waeW&?zAX&_8;v~HH)N$-vCua_}x!c4!;r= zm60XaaWVc$JAU$IIxaG0w&n1PrBMVG5}WQnF5Y~}H`-Y%)}+|i$Hli5K$s5G?chvn z&aLKLZnt--kl?K8^u=4y`Aq{|;ag*(T26&T_|}+!2-`t|uJGM5Q3Mqd{LNR`j)?B7 z_;*XmyBessb*N>9zaLfQvqMVDwX9N8?vmB2*n7G+*Q+es-R`@;+hayGDPL5- z!c|20`&w0IFW9B)X6u%7SwqfMmY0gyJI@s(qr0Je6`i;@w8oWV7^V1^14xCRvcYw>+42nrHjqvgrEP zop;OC1wiN^m7~t#zNjd_{K)qE9|@J@qKGYXENHWK>pyo~ktlq!lDyd5w+6W^y11>_ zrQ3faX&en#2UL}PU$e{Q=rP_%Ku{s^*vYE0&S_t*NYKSGW|tmhaKxQ>vzpv^#Ew2L z$#^3HL50NfcdE(1YT4~SHbEEn7sS{ui5n+e*Y(`vA_;*v}glw1Er(x{MFByW>-#`>PVlAw$0 z$u8Xdt1_sND7C79JUqgeL4q!>O*i9GOZ5(jIreJewZ3t3>JWPc!8eH5`UJJ2LSo(d z>@u|>j!_XGL09G@*`SjWpUqXT|j$=22zh&pI*ZFICL+F1Zx*b$V@E72QP;UL_5_E-c0*~4T zsgPJTC#USRd|wkShCOdN%$Um)uUGm z3=yr~Ltlji6%vUH28mrSgNOv}2;ac3mYcG1s5m=*rm120p8cpbnEBo$v9F$WZJOOv zWR17wK94pM5B@yoKP|TrsvXSWa>MucM`eWHRaXj$YmE{_-{R_xq)`MF5>HO;C)yph zH8d3pTh4Z{?z!{#62tm{2;0H+F>uUN;)B1V*NvOObwFZN*I}Y##TlMN z)<;+?j=o~|_Y_n1+y3E_V%Lhqvj6KTvMu)YE|*2u2Sa*_+B$BT66b);G(2Y^8kEAi<)7$!p4eO%w+?I2>B#w+u7N0Hh?HNeW)gf;` zQD_Q?uvSzGtw|Bx#@tA)NIaT2K>VJH4Ap8Alg3)nbxYhpv40{63#h*0meZ}xaItin z?NM%NcHtI@q){R9UE*+2aSPT*#7EGzt>kb~@~V&EzIMZyAtL21yG?N4<<^P{iN*N` zi~d`DTNDYp%1jt23Lf+kRFaMj5Ic|GNUcazs@Y%E{mGZXTG7S*nA>u0YuqNdZMp;% z5*$5t-Kl>gdW#}K*DoL4Cq};Vk8x!PDkS(;Hj|;;`Y)1Jqtgtr`Py)^*S~u2BvGN> zNK>9WZj#ux(3Y*&{u@c7(r@J?@j=|vhTxKnHxdw3NK{xmNo*Np>DUBai)T&}YYzE{ zFIr9#4>ufTYO?CgMA3h-EmvJNNz^Gl#{73Tg9?d3JtvALmn&ydSU{F#KIP-V#GDy`k=Do&Q$UI4C~^O?842z|HvSbr$nlFx&ksx zmHt^Py1uBZ=ITaGc z@{AFe5>czLh2- zQtVoh*cdln6u)x4aYYwLjGK}1fiYrcS-a0@GJmvqAe$|7AL9~KNHoebT69_G+wYQ~ zi+dtBgZsXgi^hqIkK0;tU+EH5NDSRMR^)5x+b5Esi?ww#sE}xyX{;zJeHkR^Vz0Xy zd>;|tp5uKNQbg}XsgRhvagEr}x|wHxMS?EAYu3~%{hvr0-%rao+Z4IFU-k|Y7w?_eSIZyi6i!)DXUgJUokHC=dA-LEox+GS4^0qst@xs2xcGzrMsQgq zj-J>t%zPxLZ4-+5h7?OA=;9|^N$?rbe0Fs8EvG`_l@~gPb1upEVPyshy13UX39kEY z+jk68CgodOeLJX-IBHRc@NKu$z9K=_;gdRqr+@DG+b5XsTsca3gm1Qcr!cE+zO~$k zmD@pu#CEegg-5qb?JE*=@fqLc70RPZJYMI`t_hRR{BOrDKMxXXJY5rZT$0n3+d+b^ zp^Ixm^ZoJ7P|Vk@SbF@k&f%Uj^ZkD2q|V`=^YWTUXk`W!67RO@9O}K3`UFYP#kN_Q z!O!;4ULC^NS^4M8W1*6uLSn7IbO`_IjH9GzoE#-2=(>8d4&m!pv9A;ms#rSx%nqSr zr+mL}TIvw`ev%&Jh)>xYS16aAkpUej-f$7 zMo~k4zgBed$j`m`-(rc!&jIh(g!c3D{lnwUyv0aRAu-|Qny_WF)aOBhuIYcT3I7-;RV!Nr#;PJDdX@~H^pnPBPc&j9+kQn>t z4&nP>(ases>L*BouK(>wByrOIavaOM;#M8a;IimqE3oY-|0$OEd2mnjlQpw!gZ?X) zsE{~kyPEK0;jqM7k)Z4Uz1=m;smq_GnJ?V_N(SG@!1pwet|X|CxbNeG!&de2%}|UP zBnU1|33-3zFayy4BK&NB7+KvR$q<`FU}g3 zAgGY=_h_!NRwU?J``6P#hka7LA}S>K)UnD>kOWmh+%Y~~j!UY(RwVe`xatI5Grv7M{CaC@mIW0Od?QL_2H&W{H?8V@e|hoc?Vv)!-&h(m zWcm89SRz5!YCH4{pY8p-3?sN!Q}?M0cVD{d8s-bPzrWjZ64NiP3(wq(jADwQ>)OZa z!my801lN7k#ofazN9V4MzU&^_><=Q3khS8nzF1ZlYBsrNl|60d8Xq^w{#Dq zF36Rwx^)j<4$EtQzxyifg9?d#e&`lv_DE%rpevi(EnKusil9<+TDS1=5BZV7B~@-Y z6%zkGuv=)lFm+s!pzFL&vK^B_Xi!nV8T`HTvQJiD+ASP*P2P&w(kj=A3W;_*b`P(O zK^v6i>p!`dZ1bLBWO;@VU2MU*SM5r$J+FC0k1(p{kE|7m4Ik?f*6IA;){3s`--&F` z!{s-hUFPR|l;6R&9kLDjuk!psV*Ja}{y)X%Q8eIp1YK-5=5>M!i7_+k!UmhBjzki4 z@mr}fgU8QJdvpt%9Fwm*kGD#K3W*{6cMC1HO>H>|x(+|FTj=#IK0yo8y*p_4c46r? z`FBRceYOt^R(sUGKXzEyDfHYp^>i32BtE}lr*P1HIbFFOyuWt0QCo&R20m^Xq$>$3 zB${urZTRlB$A0^U^X(u(*D7nJL{Yb#cSxVs;iqiH)A_pdPG(!Yxbi$^RBh{)ScgzVf%xO3kam$_y$b z{Oz~#Y)}p=mZi&0$=~lQ%knq3O3m#vLfrbVa?45hJ78B?D=v#J zZePA|`zsk#Ncfv+SIHnj7mwr041Z&~EX&{NEVaL9c$Ew)B>e5rk79TLXm|2*GQ(7jA7HnlyaK*6`T@&BM?C zO7+jV+|~AM5%%6JU+&B~Ey6WxBO{Oa-Iljp*(z+^BX@C|%-gBJYpF zUYyjhW%&4~{P#=l^~$xPLgKp7EyI`}bGkY~*D6PeVY*h_i=$_>4tKuxM?OIk@6T%; zwyBRTm#x-+mAyN6vVezWFb;XjZe%h!K$Huz|h@XgNm+jlKp%MWZG=8Xekb|t9% zb&4$ah}^{`Nth|+U(LwpuawS29MD^cANzlcs+R6+n zBvu($D;g(9I|;gYbzYf4g~XrtJ1HzW?vCH~ZXO{SB>*bY zR7kASKlimFK^K27vyAc|xqBH;%;IOmC+t+N6%`WPht&zX_%?=0f(i-l!|DWG>{C?| zR7h|iRww9UpQ@6eLV~~UR43@-jDkvn3W-%_4it@(c20t>f9`g6XmVSsMLm0JpRiZ^ zldK&K>s%KWe?H3UuU_gCdiKlzzjCdpkl^f;N`e_Hw(1jZ_&lF~L%NcnLSp$Fy~F9( zq-O7spljL8-eJcqMNqlswBBLzyF*sl3)R<(#7+ZxhdCp1x;jDEA$@y?DfK`oR@AGd zR`dFV`t=6enmp39Z@6#iAgej+sWO8KiMhqTq3+q7u1@TAf4|V`r`*LkOqB!`5`#AF zAKLGbuWfaLuDyr$56=w;VVG_?m3`&S9xETpUCgeYL89yD{X@3JiMHRW6Ld}Aa6njc z4hUZ>Dr;^xAiVHN?)u->ip0`31HyaqMweA*w{cl?ZMnsO@a%&r;;3Evhk;wxN%1Q39{W(5>!a6b$Rd5qyvtUVt$xZ&aJHVQ-7qLlepv1eqr}F|64n!i!C_c0{Lre#r3^&-9BOciTS#7j~F3t{a3l= zB;Go_PiT~3%Zmp5j-ZR*e7QFgYzI63*gy1bm4BbJ-I%u+2`VJEUf4fOJU4YVAVC+8 zx5^AEBqogSANswP${;}(TXSUw=MHhU5a$|I5>!ZV)wo*5fyD4ZYlMNf-jVpG=CbJG zbHwuvu)ne$R7g~RJ~aut_zd*Q3@Rk5KcAWeU3`LiWd@%c#V3LDnN^hp6%t&->I7XU zO>7vNP0UA^D+wwjxTmWVbn&Usl>`+MJYuR7bn&;7N`eXr9{JS?y7=2kB|(J*TX1!P zF8+2>Nl+oN%G{`;ane3W(8c+Fl^J~c-aXqk2$%nwKiy&G;|;==+fPWe+H;$Io7L_& z(Uk4ve%H0vzQF3|e_ktm^UwVM^Yw{q#bxz7uwj_hH(xHZtFIM_2NyOB!>>=R6_-U< z)2$nYbH7XxT;HzuuND41Fkg3WU*%d+Au(<0TH&n5*z#iBauRgCJbA6q<(~6@+q((~ zRV6WrMZIvz8@Y>1GD6(?uX3$Oy#0K=u>B%r6b<+tK^H$+^EyF=#0lrr z4?X^s${;}(kNkXn;#%?exn^LaFk!F!Q{$4VuN8@I7d8q%Ovh)Q+zz@noYW|^|0YFj zGp1oUW!JpjUGPxB1j`6FvZVxObe z35OR`8C)y6c!XB&D=H+$y|{LGb-z>w3A%XRt;}Hmoc&DxqE|^!A;CKls}pp+Q`j}E zxml`5PlW{U)U3=PLDv;8>>SR%BGnV7LV|a=R%Vc(Yf!0exOn{WiE}L#5`4x*Wd;el zu6np-XtzWELzl`~&FVdp)0Jy=%!}t`2TZ=rmQ^?Ds_g0e^5u42?W%0vWMs(l z^`E@8XRn#rc8BH4{C8($ozBZ^K5I7js@;gXtFxK6?w_CM&&a-Moo^HOLcZ`EDVC^^Sbf`>*;NPSbajHR zS)*oVCyWQ-Yei+`teM&3d;iE<#yR;f?$h{;!HW7f<2 z`e!Yeo?WqaUa#^AdIl8|2Yo#)oAGTbg9KeX-fRmzg9?eYcb_Itj!b2cpo_nV*Go;OW>5VGpP&Wl(aukbt&2x!-p4dz5*VYej`b>wB-uZhblRd61y% z^3|@(Zd;xr_(^TN!PG1~m49kH7An_@3W@7>oSGdl<#(UC>@S(+jqhE$_{~?DL50NV zkyEo`-&6*bOWvNE4c#esaY@xPNIcu;s;sy!GGrU{U*$J7T`gCemi_00-+faTm7sFh z{At-QPyUg!0f`l7PtOj$8yT{E{a3kGbiIHxQEs)rLhxufw8OR8A*=t9??e)#Pq-$l z*C_Q%Dvw0E_0i-8g1)_=tk3A)ZY<+JRnp_lx2&5#2^P$9vq^L*hsQc2KNbLO+zL5s&F zGN_QKf73hJ?5#%rMigTP3A*V(NOA1YMh){%m$h z2EsFn^Iy-t-F%>>Gh_PoA7^WfKH;~u^6j8PqI!>>1YN^gts55acXA?w3JLb9Z4-R0 zNYJ%YzfHqYkB>=YP$9v0k5p!mplgjjt-^hqr+(|BLW1v`smvfjSNq}Hhr>25CbokL z3BHe~GJ^zNqh_@U(+*E%P$9uNQ=FFWm9?#lI02q~BLB4Sy?p?uUM+@W?;pf-kcDZ}0mX zQOuEIi3$lG)0Nvng05#bY7n+QC)L}gLW0M1Wd;elCLOXxnEg|#)lwnBW4bbf1YNxk z+9nhZ%I9KL5>!a=n66IHb#cFT;j4b9B|Z--BzR0$W{{xkmCJVsV?Iu0P$9u%x-x?V zT?1d-KWzW**u-{FA;Dw1GJ^zN6I&b`HtB-jcZ%U%4n#k|Ex zP$AK3V&ibvX~;+tbe(c%<8aWsDdL944a40R?{91M^!*J&)2?~VC(`EY6W5B%diSx$ zA?vcQ(Og^eCfAC@eG40hy16-BouKQx`He%(=KEP*zCQV1`Go~a{VN-XSBkmoe_JaO z|LNB_{P-R+lG{PoD!-9AL4`!`=8eOvJLP-YwjfE+wabg^g*Q%15mY`Ov0iw4Zth}s z^$Zf-o2(bMe>0WAWzlu)-x`G}%Tol8rG+CJgwI#zdvulK%D0>fiN`uM2y?DWeI6v} z8YyR-H9MvVDh&z^!bUIWM<16|xv!{@X!lF~u=epdb`_ItDV9jk#czzt3@Rj6G;9zy z`6bnANzlb_BFoS}MO`a?FHO8&zOO#azlpdcBgC!$iX|!}?)s)dIOn>Y&aL+McLZHO z_iPx>90JRJD=H+qo;WW1 z@8I%=;AS5Nl+od-cogfF1F1|f(i-tmZ}qUaip=5phANE ztLg+@95JmVsE}Z9sX9RyM}8{_DkRujs!q_w5$sBW3JLa>suOf^?7otqLV~@e>I7Y! zXI)89A+hY+Vd2Hrsh$@Jy7-*j$_y$b?tkUv@Nkz@1_`>>Y=259Z4bhN^h$>BO4<6p zklpwBh1TZzo|ekBqC$diPODDP#WPVQL50LB?*=RyC)+`SuIlegePZvAvRkjnpR(8N z<&Uzr+T=CI+w!H$U&*N)i6gQ2)kWFWhs?G8W`wx)UnM~oM+924RMbO2TmU|;Xg#^bY&09j-f(<8SWCo z^H>XAD0F&v-P%&G!!@JmE>XM|f^Vy+AS$+lF0UfS!N+&E3@Tnr2H&SqD1a!qOO{2K*OqZ#+r4Ysoz~hisCX?Id;>?J z0HWY7Sr%PhTgH+GhtzgFsj+2H@mezY2981jM8RFMEV{h5j7x6qTU-0UiUsC$E#s#D zoLt*rotrF!ir13Cr#BZ0APVl1WzpreWvt!&gxYOBd0jIKRJ@jq%BK!hBk1zlGR}ME zsM@P**QnJDDqc$lpK??vR3qr}+A=O`*}ZnnKW}OoRJ@i9K6|N9s7BD`wPk$RtyAsG zC$+N-Dqc$l-_24eR3qr}+Apv!B^ z=y%0)53Zb-ZwD2xC4=t>C={v@ba`zVj}>|@`0k$k^Pu9jWbj=Fg+eugF0U=)uCdb> zT)F-T+gDV)*6n!VqwLUjkCgic)d;%0wv3zaEiL%0_fX5A;iC|(QUZveFIs7BD`wPlQKcW%vF^G90-6|ZHv{-$8ds7BD`wPhT(+2%FxG&svL zsCX^Q^>+(fMm2&iuPx){SN7|?!`yQ$gNoO(Tz_Y=WmF^R^4c;sfB)zQub-J`Q1M!p z>u-v-jA{g3UR%Z)>o;F;!dqwBc2MzJmg{f4wv1{7U0z$p(&^(CtUWOQ%&B-S%k?*R zTShg4F0Uhm>aYU(YhAcrDBIU%4%#8bO!WmT_t5S6cJDe=pGQT`FG7a-Z3CVAf!h z(dEyh8bO!WmhpM-p`|%;p3)2|UQ0%!wufa)#>(&QwjI?7y1cfGO;(O9wff+%mO;g9 zS+0-JSw=O2F0U=)neWaht-j^1mO;g9S+0-cSw=O2F0U=4wBI?U(;80G{&|6l*RtG) zCe&u5_qw#auc{Grd2JahK0K$?zVNa3&kIz%mW+Sjzh`#VwO5ogsu6T~Z5j7GdsbmO;g9$?!QdwjI?7y1cfGm!}?I+GdBhEQ5;IvRt1tV;R*5y1cfG zjkYZG*;NW#=o~=nEPnVAVDQbSjMi)@2{EB;w0NwB)k^afN4#_5xeD|Q=veDN|LaQasOJY z_L!ZHv}){7YjG`Jy+K&x z?{b%^WssnfBrHSQpR_8?D3b76T>t4*KOFGJq;ducDoMgJwEan|vJ4Vli)+oL^+ML@ zvT_CqDoMgJwEan|dO){>gxBI)u%ccVyU*lu1_>%j!ZNh|Nvm3*86>bma+VZetmg9Mc%VHw)~q*ZA~frQuMdVA`h!Xf)zRo)H~RFZ^cX#0~^Wf>&A z7T1%jH4O)jiWwxRBnivV_9v~%GDvtWuCAwS8onJGGe}TL5|*LuPg+&Judpnq#dX4> z%|o$$%pgG}Nmz!qKWSB#LBeZs`FmRI*d;+FNmz!qKWSB#LBeZst?`%U;q*=8aYcek zlCTVIf6}TfgM`=Ox@C=);pnch4U(XeBrHSQpR_8=AmO#R_MO-&Jb7sBL6V@7BrHSQ zpR_9dPArh{T3r4{6#G0#P)QP&q3utvE;WOM*Wy|}dh77fX7Rh71eGLV8QT8z>QXaE zcrC6^UfDW)`614OPEbh_mZ9xWuP!x%gxBI~|LE4?&fDX!1|+B?3Cqy-r&pJnLBeZs z?bBuJF!PLf%|L=mlCTVIe|mMP86>|{i|gkzT7+K*#A{I!RFZ^cytc&-r3SZkvP-D+l* z`u#63)&-qrl&q=~- zaXoO-``JFL%Nqc#eUPA%BrM|wX@9HN&->%N~IzGKWFK_y98#`V(vwk`KL zNq8-;XCGUdwHy#LNKi=j3Cp-c+TZ72=H9bP)QP&(M{Ulb>%)M39rR9X3G27#r%3eWsH>eH=*3;B;mEV z&YAE*Hu~|HL4rz>unak?)yR3Uq~}@^UW@CN13%1$E{Yi>s3Zx?kh5BioChs~gxBJl zu=Ph-&-Y>m2`Wj#GUTlGfSd;{gM`=Oy8fq+vL)}t3=&k5gk{KCZGoHzErW#D;u`zh z$61?~V+IK-Ny0MZthPYTgO)+UYjHh1<&$juf|x;qN|LY)IjfcAJZKptycXAi2Yi~1 zogFhsP)QP&A!oIcoChs~gxBJ_Y1yaQYUjiZ5>%3eWyo2rBD$Y*ckhT9B&Z|_%UJMGx0>_H{Xr65i_7nDw9kVC zl_X&qYfFFdZ{_|V39rTF_h4EE2`Wj#GR~Ct*SFjsB;mEV{0>mdAVDQbSjJ#!e_xjS zgCx8bm)~(}86>DA3CsA4^atma`-3FB7S{_mew;n|l-$W`86>DA3CsAKw7-?*F-Q_# zi_7oZw+s?gl7wYkC+)9mxj#t4YjOFL1uTOEl_X&qOQikHD)$FTcrC6C*Z3$~W6gWY z`-%jWBw-oa{?_Y~_XkOMEv~g1f0Ru;HD-{Yk|ZqSDrtW`%l$zTUW=>tgpabL5>%3eW&BC{gCCUpgCx8b*FR4GEStXPz2$vH zf=ZIGj5*T&O6C3_39rTV^Xi{xPmGKiB&Z|_%aF5LjhqKddR;=oYjM@y@%j z!ZKD!fAE@ee~^UN;`(CIS6R)aF@pq^Bw-nHR$CzFLE8=zUW;qZQQu?-93L}CP)QP& zA!oIcoChs~gxBIa>Z@%3eWlWX!_hh+0NWyDz9k=KA*^lqXHb{a>lCX?T zr9b#mxj#t4YjOQ}=nvVfi(&=|DoMgJ?vVEPuksiq39rR<+x9E7N!!H?5>%3eWz3fL zw^O-4NWyDzt#R+lY(Xi0x09ffBrM}?X@5J*^{BRU5?+hzo|P-Jfd|G65>%3eW$5oQ zvt)ciGe~$XuE)MunJrx^PY1H|ISDFB!ZPHnR+96e_0>ptEv^fvtjsPS5i>|oNfMSJ z=fRSk2Q7ny*W&Vbvf6f#ppqmkW3sfrcIEyc39rTF?|`)o5>%3eWyo2rBbf0ylYWV}u!K_y98#!b@xI>_~?W{~h&TpN%5HhbYuF@pq^Bw-nHR$CzFLCYZF zwYa<&X8Vc+l_X&qw{v`O-&Ub+!v%JXwurU3E?(L)9JzY_|AhhxDoMgJ?s;tE1&@~d zgCx8b*L9;?hA}@rSZ*IAs3Zx?Sfkr-b5cooEv`uoTZWH+iWwxRBniv-O2!A}JZPT> z39rR9b54tJ&DwEak)VDA3Cq}4+TWCNe~^UN z;=1>P=3$@RVg?B+Ny0MTl=gQ?xj#t4YjOQ`O7pPrh?qfwN|LaQmGXPc%5r~@gxBI) zeqi%3Z(PhEK_y98#&gpChL!t+B)k^a`^{uK{t+`sP)QP&ae?#)7nb{jB)k^acRz0x zCVv<+NKi=%3eWt=bl!KNMa{vZjj#kKyI zTZQ%OVg?B+Ny0M5OZ$82p?pp%39rR<`dZDy#PKnM1eGLV8Ba+2JGneQNWyDzJ=L~( z=ygxbAVDQbSO$A{B)k^avjdukpZ^szNKi=UW@CNUz>+M?P3NADoMgJMqqr9gxBJF@t79jqb@On1eGLV8FE(h z@j((^i|e>YTZDId#S9Wul7wZ*S*=FSgC)IYAmO#R4sO>nlzPVu5>%3eWyo30=cJPG zT3r3EY8mQ|jTt1UBniuqvzqq@Nq8-;gH~%5u0A+skf4$zEJMy}3*894AoW2wYW<2TZcPp zV+IK-Ny0MZtX7iqp!EkycrC8?=d}*o)Q=e?s3Zx?kh5Az&V$xhBjL5UM$c#+?tCp? zGmxN?BrHSDY9%=jS_TQP#kK92)?x9Sm_dR{lCTUptCi$;(OUgHNO&!-t@mslI*y7N zB&Z|_%aF5LNzQ|oLBeZswOrXMY~3Sfkf4$zEJMy}B{>gT1_`glweJnB!lJe@g9Mc% zVHt8(^YK9vUW?0nVb&icK_y98#;?*JytO<&*!ti>p~tNJ{yMM4HSU}f!VhP~`|e0k zNfMTEi;U0fXoG&{B)k^aE3=Oe7Y&UWB&Z|_%b1LN6iIk3uBRRy7$y#n86>DA3Cn0L zzsF23_XkOMEv~ko9v2o(h#4fPBniuSUE1G2%KbqSUW;qyrpJY+?u;2Es3Zx?m>})% zsB(XhgxBI4dDMW=;geD%OF7|Nm$02(jUCKJYSTA*W&6{>K7(_5$A=Ippqmk<6&ukW8`{Nnn#g@*W#Kr zre8R$SDfEYf=ZIG3>}|8^^v?kNWyDz`8)M&Uy-1aBrM}Roi8fm6S^HFycUzE7sg|V~aJq;wNBnitnUE1GQ>c@LC zNKi=a(S}(>VB^b2r5a!GPafWcXfGukc8LbdZ5>F;pE+81_>%j z!ZPHnRwL&@{X7aJycX9nZ3c#gN5%{iRFZ^cJRt3FQMo@z!fSCgTKD*{%ZV|A1eGLV z8FLSO`+>3L@j((^i>v9!$A{fdh#4fPBniuqv)TeV58A#W;kCHtJ$yp=^uU-wf=ZIG zjML=zn8(WfK@whzYtPFDh3~hG86>DA3Cp-y+TT9q{vZjj#Wkeo;BejY*gi;5NfMSJ zXSI@?2W?-G@LF8MzZ)EGxISi(ppqmkL(Xa?IS*O}39rS~@!S(bx9%~61eGLV8K+76 zyRkf9l!VvfnzHP~&|z8p-X%dLNmxcn+TVD&9@RET!fSEW?ldF}IyYvJppqmkL(Xa? zIS*O}39rSq>A^!nlMQ1A2`Wj#GUTjQlJlVT2T6D>uIAl`gp23I^EnABNy0L;{pr=E z?kf^ri)&o-A)#ism_dR{lCX@6rTtAQj}MaYT3pvYe_|N(e7yD{K_y98hMd((dUdJW zLBeZseSXA=q2I8WL4rz>ungXDNWyDz{q*?Yuw?U?L4rz>u#6X^{cTq650da&T>Cd2 z98O;puc=8;NfMSJXSD@#9<+T$!fSDPFU+p5NKi=x8Gb}kYA7A!b zT&wNSGkmsp9Cs!`B}rI@{vIR0vRDQQuf?_DV?Dw;onrx3I}EF@pq^Bw-nP zH=vF-Xa)(d#dTh%Zeix+m_dR{lCTUNpV!d_%^=~mxc+@$x6pK9%pgG}Nmz!C&+BM| zW{~h&Ts5b43m^XwGe}TL5|$z3616(opcy2*7FRa6TexVOIRA(0xV1YjJhC zrF$54LChdQB}rI@j?e38gJcv)crC8C8}|r9rpF8tRFZ^c==i*hx?2Vbuf_G$X+1)Z z*)f9zl_X&qIzF$X4Z0m9ycX9RAM^-|XT}T?RFZ^c==i*jHfRP3uf?^nd(W`_l`(?^ zl_X&qIzF$X4Vpp1YjF*n+cS(C8#72yNfMT!^R;!fK{H5rEv`En)`fEi#tafvl7waG z_`HrbXa)(d#r4+Fb>Y_#Ge}TL5|*Lk^E%p~86>%j!ZP&!T^()E z3=&?8Yy8Wy9iPVUL=sezgk|XcyE^+!Ge~$XuHoO*g3=&k5gk|XXyv{z;3=&?8>)OZa!my9xwGRm@Ny0MZtX9(5XPQC6YjI7#xGp?% zZ_FS;B}rI@j?c?^&@xDPEv~8i)P=h*jTt1UBnivV@p&0_w+s?qi|fG^J;T6ZF@pq^ zBw-mkKCiRSbYGG1T3p@>v;H6nDoMgJINJB=@K>`g8y#!&#k>~RjZeLtUH$wq<#}Wz zs3Zx?;AkHSuf^46{g<*wZjTuxs3Zx?;AkHSuf?^~K`&(Y-4!!PP)QP&!O=bvUW;qx zHP2;##)lli6jT#tafvl7wY&w2y?> z;@V^Xh1or~_bG1&2`Wj#GC0~t!fSE8fBzF%uXFpBGe}TL5|+WyJ`!GwtNrOuWa}K; zube@GN|LY)`IXbh2T6D>t`-xX$eMKSU(O&wB}rHYNBc;4Ev_RMKat(hRK}$2JCOvH zBw-mG?IYo}xV9O$FzfJf%pgG}NmvF)`$%{#u8BjQ%#OR^xbk+8ppqmkgQI;UycXA> zDNkjCyA3R7kf4$zEQ8~NB)k^a3oD+^c6~i&kf4$zEQ6zcB)k^aCZ|7}U6LJN-VPE} zl7wY&w2y?>;ySX$^VuE~V+IK-Ny0KX+DF1`aozvc3)zM@#|#owl7wY&w2y?>;(Gq7 zm$J>~#0(Ntl7wY&w2y?>;##-IE7@72Vg?B+Ny0KX+DF1`aW((q)$FR)F@pq^Bw-mG z?IYo}xJD0Jlznt(Ja$P?NfMSJXEh%mB;mEVit}I3zTG@#kf4$zEQ6zcB)k^aM$f&G z?KL!hmyn>6BrJoYeI&dV*ORl}%$nUCzY|GNNfMU9(LNGhi)*X)Z)In_7SA6fs3Zx? z;AkHSuf_G!@VBz(e!zLqM--_f3CobPnvV~X@LF6;2E3I$x@pWHK_y9821olycrC6Q z8@!cmQyZ@tNKi=;+lHc>)GJ?F@pq^Bw-mG?IYo}xOQ6kS~laHcuh@$N|LY)j`or8T3p@> zTV;HZN|MMkWPDJcR;Yc>E;|nmf0{en&Z%CD>+jDE3C(8a|1YzAK~PB&mZ8sc(x(+_ z1_`gl^=SVgq0?0{g9Mc%VHx^7Cmn6j3=&?8Yu*nhhFhn_3=&k5gk|XSob+jhnnA*A zaXmKa#L(yZm_dR{lCTVYo|8VUP%}t)Ev~KGo*34>H)fEak|ZocpXa1cE7S}UUW@D9 z7YB!Wuf_}#RFZ^c=<}TPX@#0W!fSE;qc}KR^nJ`AK_y98hCa_ppH`?DB)k^ahBbr3 zm=<%&*NG&kBnivV(LQ}zp=OZqT3qWiknO0886>DA3CqyYK7CrDL=;JQEw0T!9TW~5 z7c)puNfMT!&-c}*6>0_vuf^5t%|W62y)lCXl_X&q`g~t~TA^l;@LF8EzB4Gi`bEqj zK_y98hCbg{pH`?DB)k^abt?viZY{4bf952pBnivV=lkl@3N?d-*Wy~f$>6ZXAu)pl zl_X&q`g~t~TA^l;@LF6e>IR30&W#x)s3Zx?kmnlK>eC7}gM`=O`ey3j@Y>BWg9Mc% zVHx^-UwvAkW{~h&TrVse9JYQYW{{wgBrHRp@2gKM)C>|{i|gC{<-7fZm_dR{lCTVY zzOO#5P%;W6ycXAmcb*t#eH$}KP)QP&q0jf#rxj`j39rR9X44^I+%GYM1eGLV8Tx!* z9c|DI5?+hz{P9D=pMH)RB&Z|_%h2ch>eC7}gM`=O8ui7H(0fJ9AVDQbScX2|SD#j> z86>DA3Cqyu`|8sQHG_oL;yUKGq2Zo~V+IK-Ny0Mp`M&zJLd_uI zwYV<$d1%<>x|l(NN|LY)eZH?gtxz*acrC7NYflRMj))l~s3Zx?(9u49TA^l;@LF8E zoN`jwWuKTqf=ZIG3?1#$r`Kx+39rS~e9B2-&;~Js1eGLV8Tx!*eR{oSknmbuAIv!^ zobqlwN0FeCBrHRp4x>-6*9;O~i)-y!CxvA<#S9Wul7waG^L_Q{^_oG#YjIt3(MjRd zQ)31RDoMgJ^!dK}^m@%8;kCHB4>&2z$zlcxDoMgJ^!dK}^m@%8;kCH-Z+lYsb;FoJ zf=ZIG3^}Wn^y&4QLBeZsb@^~;_-t9c79~L?NmzzH-&dbruNfq~7T1u=hKA`+#|#ow zl7waG^L_Q{^_oG#Yuyg?;bhhv2r5a!GC2El>)l3#XItfSXuTHKq!&*Oi#CXJYe`T^ z5|+W)pCr5%*Q|l3hHvV}3=&k5gk^B{Ckd~`HTkDgLjQ&_g9Mc%VHuqLNy2M!&6#{k z*raL9AVDQbSO#Z*lJHtwYqmcnl(vr%3eWpMT<39rTV)t)DZzf6f4B&Z|_%h29koG(hkYjJ(lNVenA zm_dR{lCTWz-NpH$B)k^akIROK^}dT4B&Z|_%i!!!5?+gI*LQ}8wc5n{4M%3eWpMT<39rR<);Gh$npeaO5>%3eWpMT<39rTV?B*wj zSDuI&B&Z|_%i!!!5?+hzg@aEHqrZt6B&Z|_%i!!!5?+hzmFXvkzitull_5bTNmvGF zf0FQ8Tz4!#IlR+3W{{wgBrJooKS_8ku2;LA68iOu86>DA3CrN@PZC~>YtTPV35TB$ zGe}TL5|+W)pCr5%SFbHj4IPKa3=&k5gk^B{Ckd~`HSqjX!?P#F3=&k5gk^B{Ckd~` zb?BF;hNc5z1_>%j!ZJAflZ4me`sUyfVOU+vAVDQbSO#Z*lJHtwo$eeFhVBwGNKi=< zmciMdB)k^a3BQgApRXS?NKi=YRFZ^cXzwo07bW4fxc+nH$k5`vm_dR{lCTWU{v_eGxE{T6WZ1qgW{{wg zBrHRJkBRd|Nq8-;59f>wvp0(wB&Z|_%i!!!5?+hzj7vs_HXp@n1`%3eWpMT<39ofK(1$A&NKi=>!_iMS@C_une8AtyhuncW~dUdH8 zB)k^a++yEQ_iW4{K_y98hR)a4t4qxw;kCFPY1%j3w=`yuppqmkL+5Mj)um>T@LF80 z=Jg5n>kTe{9wewF3Cqy=+In@V86>u#7k5_ZYpp)C>|{i|fvH z`-Jr;#tafvl7waGd~In}mO;X6aW#3Oclhk>m_dR{lCTV&udP>?x*a6E7S~#r_YO@u zoLK%mNKi=eZ!06iIk3u1!wv9d4WvGe}TL5|*L&@5-+%mO;X6aUIgPcbHOd zNO?O*P)QP&q4)3V)unC+39rSq(}3P#&WM;nf=ZIG484C>uP!x%gxBJ_=Cs~n^1CsE z1eGLV8G8S&UR`Pi39rSqY-aDUV>YzBuSify5|(j@v_HMN)C>|{i);BCy~F9(#0(Nt zl7waG{kwW~sTm}^7T1cc`h*)kj~OJWBnivV`*-!~QZq<+Ev{!z?GyHDe^Pm0k)VDA3Cqy? zclGL0Ge~$Xu2Hl4hJuWN5BT zb*UL7ycXApk^REGXT%H=RFZ^c=>5BTb*UL7ycXAnZ}tm=4v85gs3Zx?(EE4w>QXaE zcrC7@cIh7mZV@v`P)QP&A!jvzz95BTb*cM`gxBKQ@yGt5Z>yL=f=ZIG484C>M;kPQgxBKQa*F}s z*$3lyI|(XD!ZP&!UHO&8GDvtWuBB}Tg!kl`GI<*$K_y98hTgxcqYb(pB)k^an%fNs zFMJZu=Om~k3Cqy?cXhNuGe~$XuIU>N2use186>DA3Cqy?cXhNuGe~$XuCAZ=57`zm zg9Mc%VHt8(^XH3_@LF8^&g&mmJ`}IvNKi=S%**2MMpmwfE5e;kn^4g9Mc% zVHtY=u8uZn1_`glHE7fRq5Tdqg9Mc%VHx^+jE**F1_`gl<-IVQFG_++lCTUNpO5{) z+fVKsPCcrdwF9rk)wE&faK1ciB5xlgs3Zx?(D8YleWu$%!fSDDH@j1Kbi0^Af=ZIG z3>}}>*=L$T!fSDDwtJ^At8L66K_y98hK|qc>@&?E;kCHhJl`=i2r+{Ml_X&qIzF$n z&oqOC*W$W(aK~`epqN2|N|LY)9iP|PXPQC6YjN$}xMMhWR?HwlB}rI@j?e4tGtD63 zwYWAdbqIYwi5VoQBnivV@p+wnrWqu>7T4)#b_g9ibuS;gB&Z|_%h2(8oqeVmB)k^a zN&CxoOph5Ps3Zx?(D~Xr`%EH=B)k^a*gtm&-~SpjNKi=une8At+UTGgM`=OI($-x@bu3y zg9Mc%VHq+{tyX8BX$A?e#dXx84&mEwb>)3Uf=ZIG44tp7v(GexgxBKQZTpU4%A}Y< zf=ZIG44tnX`-3FB7T3`eJBFE$#0(Ntl7wZ*Sc??X5{Bu5>%3eW$1iuoqeVmB)k^a@<%#_Q&z+b5>%3eW$1iu zoqeVmB)k^ayKOp$dhf&x5>%3eW$1iuoqeVmB)k^anUgw)f6j{;B&Z|_%h37SI{QpB zNO&!-$3N>F?m07Nkf4$zEJNpO>+CblAmO#RzU)vF?%FkGkf4$zEJNpO>+CblAmO#R zE;*|vys6BrHScYwPSY%^=~mxTgQTCj4Vu%pgG}Nmz!?*Vem{G=qfK;+pVs zP1v$o%pgG}Nmz!?*Vem{G=qfK;yU2{n$Uh;JV%kBk|Zoce~;0-ku-yZ*WwzwxF$5; zKW31ik|Zoc=WFZTNSZ;yYjLgdbWPZCNxWttK_y98hR)a4yOA`5gxBJlH@hZGJ~L*J zppqmkL+5Mj-AI~2!fSE;eQ-_a+9GCwGe~$Xu2){@9L~8UW{{wgBrHScYsdZ|39ofK(1$A&NKi=M%kP)QP&!O=bvUW;o*!v%j!ZJA8N5X4y zJ$-+J(6sCR<$XnhN|LY)j`or8T3k0YZW!*qIA)Nbk|ZpHqkSa27S}UF8-|BVF@pq^ zBw-mG?IYo}xca=(Fx%3eWpK2QgxBKg-ekS7{hKj^1eGLV8652+;kCFvAF*C|dv44iK_y9821oly zcrC77UR*D{aaznEK_y9821olycrC8p%^QbTcZwM#s3Zx?;AkHSuf_GBevQMA@5S#D z5>%3eWpK2QgxBJ#e`VwFN-<`TppqmkgQI;UycXAY^Baen&0_`$DoMgJINC?TYjNGT zuyLrH8_!WBs3Zx?;AkHSuf_H5V~s=BC1#MIk|ZpHqkSa27S}0vHVy~98?PBiP)QP& z!O=bvUW=>M#Kz&S(_#h*DoMgJINC?TYjHKNYaC8&7BfgtNfMU9(LNGhi)+hzjYIA8 z@miDwl_X&q9PK0FwYb9F>xEet#S9Wul7wY&w2y?>;__bDD&vDxl7waG_`F_SYQMJo zMvrBqUOCLJ4ZIdttFDh`7tYQ9U!ML9f=ZIG3>}}BR%IC^ycXBKqaMkgm=!ZfP)QP& zq2u#3=&k5gk|V_ZN0kG3=&?8Ygpe0 zvyYd?3=&k5gk|VxpI%*R1_`gl)#msIv+uecQQlW1s3Zx?(D~YWb*UL7ycXB5mpzz$ zcz4VoK_y98hR)a4t4qxw;kCG~Tk>Ewe$yk%+d+a#lCX>^GCrtRmzqJsYjIs)w;+3N zM9d&TB}rHY?*=5{wYYA1Z$b9MV=;pSl_X&qI$v9UWwGrb;kCGWPbg(m*Ey=ZuSify z5|*L!we{*!_Z11R#dTYFD4X3OW{{wgBrHScYwOjeWE4nvEv`k49?m8m9WzK!NfMT! z^R?wy7Rw;vwYctD`fzsekeES&N|LY)ov*D|m%1G!ycX9>^B>7Z4vHBhs3Zx?(D~YW zb*UL7ycXA;7d)CZI3#9}ppqmkL+5Mj)um>T@LF77)IF9x&^Bg}ppqmkgLeax@LF7F zuk(2J&u?P;AVDQbSccBm)~ie14ia9A>(!ecm*-Q*3=&k5gk|V_ZN0kG3=&?8t4X^j zvbT?j86>DA3Cqy&dA%Oh3=&?8YrD&z$nO3re(#c?k|Zoc=WFZugl3TNT3oBW{zSIb zl`(?^l_X&qI$v8y8#IH2*W$Y9yC%3eW$1iu9c|DI5?+hzr^lbjc0N32kf4$zEJNpO>u7^!knmbuM~{9YoAOP(z9K;- zNmz!Q)%<-EB)k^aVe34Rb(v;H6nDoMgJbbMZCpJ~RwUz?aU z+VV_0Z+k7S$LmkbTKsfI`Fu`-N|LY)9iP|PXPQC6YjJ(L+xgki%VGuzDoMgJbbMZ~ zE;WOM*W!An&xEYQ@|Zz_N|LY)9iP|PXPQC6YjJ&k$$8oJYvlW|P#{4iNmz!C&+F_n z%^=~mxb9duKKpw6m_dR{lCTUNpV!%EnnA*AaW!i)KKs63%pgG}Nmz!C&+F_n%^=~m zxE2l{m;HEi%pgG}Nmz!C&+F_n%^=~mxGq>WHhcA#m_dR{lCTWz-RbNz%^=~mxK2KA zZ1&?(XO-Ir2`Wj#GPHN6v(F@=NWyDzP0Pk+mp&XbNKi=2{FtT3oB`J3gDbZOkA+ zB}rI@&ezu2XPQC6YjJg7X39rR%3eW$1iuoqeVm zB)k?^vnMaew%sabkf4$zEJNpO>+CblAmO#RMxJnC*6sV)&Ph;75|*L!wRQHHW{~h& zTz7qOVRrJIm_dR{lCTWz-RbNz%^=~mxSl!qqU?ZuVg?B+Ny0L;cPHmT%OK&kxaLf~ zD7$BI{B9>fB}rI@&eztvk#svqcrC6r^DoMt92ql6P)QP&q4Tx%ZY0eh;kCGi&All5 zXZ@H#f=ZIG44tp7cOz*A39rR<&4i1xr)R}$1`wGe~$Xu3vV)C~H#_ zGe}TL5|*L!we@Z!%^=~mxV~R_VfOy}@fwZv;H6nDoMgJINH~5 z=E&@YtFN$Y1FyxkUi}f-8yDvPUpYQVB}rHYNBc;4Ew01*osxYwHfE5Zk|ZpHqkSa2 z7T0F?49|`mA2Uc$NfMU9(LNGhi|d#ThGm;giWwxRBnivlXdel$#kF+Y(Cm@fF@pq^ zBw-mG?IYo}xE|VgNcQN0m_dR{lCTVp_L1;fTpKPLobB^|%pgG}NmvF)`$%{#u4&H< z%64jaW%+uS1eGLV8QQyx({GNfMU9(LNGhi)+o@2W5+DVg?B+Ny0KX+DF1`ajoBUaCZ8T zm_dR{lCTVp_L1;fTwCmXVm4_?%pgG}NmvF)`$%{#t_fp@WQ*^P86>DA3CrMU9|^C; zwbf5Uv*TWf86>DA3CrMU9|^C;b?RlqvZI#73=&k5gk^BFkA&CaYPZM9S?5n;1_>%j z!ZJA8N5X4y4f^nu?D>yk1_>%j!ZJA8N5X4yZF9khY}0pQ1_>%j!ZJA8N5X4y&1pI+ zJNe0&L4rz>undm&k?>kvkB%Rm4ZkgBkf4$zEQ6zcB)k^a@W;nw%O}PR5>%3eWpK2Q zgxBKw?1j^^)q2Ma5>%3eWoYj%jt`RXT3nl5b9%PCeas+1B}rI@_U_{NAPKL<^>nK< zvR1#u^9KnkNy0KX+DF1`alPB`jI8aGF@pq^Bw-o)drTZ3B;mEVj_Y+scEjYDL4rz> zundm&k?>kv3syTLYj_&JMXdW{{wgBrJoY zeI&dVm-oU}86TvQBrHSQpI%*RpYxl?ug&T`a;sfOc`dG|e!M2zaBlwpmG=))NfMT! z|{i|d8DtFxK6#0(Ntl7waG_`F_S zY6c0f#kJz>>Di%o#|#owl7waG_`F_SY6c0f#dX*GY1uDN#tafvl7wYc+zp6jIW4Z1 zt4+)P^FhoYK_y982JZ$W;kCG)?Q>ODT=%x}bvp?vNy0L8d|q0W?JE*qi|dlNr)EQU ziWwxRBnivV@p-+v)X#&2*WwyIa%xuW8#72yNfMT!^R@NrQX+~ZycXAWJ5J3Gm=ZHc zP)QP&q4TxnR~E}4;kCFn-e77Lo{AYHs3Zx?(D~YWb*bAy!fSE8)O2e0)PG_I2`Wj# zGIYMSUR`Pi39rR?nnA*AaUC)F>TJwvUesAVDQbSccBm*6UIIJVY$iGf=ZIG3^}X$^F>K`Ev}#E&&a-M9WzK!NfMT!^R;!fLAQg1*W&ta zyBXPgKga7`5>%3eW$1iu9c|DI5?+gI&#~8KlirRQB&Z|_%h2CrbhJS;NO&zS?}e>$ z{~(nlVHq8y{mm-(2XFXS2|*JT3o$4G!9o^kpF+7K!Qq=u#7KczUaH<{vZjj z#r5xI#0#tafvl7wZvv)^z1K@whz>*&`Tg}2X+86>DA3ClPM^F>K`Ev_-!HVSuL z8Z$^xNfMT^tMmtFl>37uycXB6u?@q>xiNzTl_X&q=gIi|QRVrfB)k?^x6c}cmP=v= z2`Wj#GK$jv-YL%)CE>NW?ikP@)NOus`TB|kl_X&qt)=}vTJ8^$@LF6qep^5MrEkn2 zK_y98hK|p#QJybK!fSC&o>@QKcxTKYK_y98hR)aibGbiA!fSEWJE4B)zUDRMeMN#w zlCTVIf1j0~FG|8|aXs9gT1_`glHRks9!{-~v3=&k5gk{KCtt96`%OK&kxHj6k zNhrM?+aL)lNy0MZtX7iqpk%3eWoY}8^Ppvr@LF7}cikYIIXz~O zppqmkLw}Ev^Pu$yNq8-;j{9s7_ReAk2`Wj#GUTjQlJj7V_6aUIyONm#y4%pgG}Nmz!Q)k<<6vn~yR?eqUH z6i84>5|*LuPp>ZZ^C021xJG~3K77AL%pgG}Nm#~XUEc0=UU__wgxBI)x2AnKYO9z* zf=ZIGj7MaAa7KB2kc8LbYCUO(u=9>Fg9Mc%VHw)~^y*Ug6$!7!wfU#*!nX&;3=&k5 zgk{KeXsupdY6c0f#q~p7yD+;LGe}TL5|(k1w7*x%{Xr65i|eRo+J+bJj~OJWBniu4 z?~a7m;yUQ)wqfpSlgihkB&Z|_%eYzE-`C~wK@whzt7e_HVVk;`L4rz>unhe@W{+}z zkc8Lby8HPy;koN$1_>%j!ZNh|#r_}(uf;WVUYoGtFEN7zl_X&q+PiBe*Q0V+6-jt4 zu3i7xCUiaQ((>m)f=ZIG47m=i)vHU*AmO#RK76N5c;NP!L4rz>uncW~dUdH8B)k^a zpk{5u!-dPr+d+a#lCX>((*CY4_XkOMEw0DTXd7Pc7BfgtNfMUvrnJBD<^CWEuf^5u ztF~d*q?kd1N|LY){XIsnE_Gj#@LF6;&T1F7UKle-P)QP&@tw54zm@xgB)k^a)0^!O z?pzTw{y$}B0&i2*{&6y2_a>>#GG|Pt{9RM)F;u#^NK(d2xVT(04>=)SLqsy=Epvk+ z5shvVB2yVslp#ZiD3av$-+M26_g&7~ubfYx+xqzZzUz6`w9h{K?6WorDptaaQQKL6 zbFY0KBoUMySH3UqmGf~^uZ=kgDptaa;jTaT?9%D03?zcG<66|elH@Ds#~?w)N_a7v zIM-v`vr9JyiJl>c=2K#Y%WF z-1X<4UAi$y1ZBsSad>4ZaLgZb5>%{&7sELZO?S^O-54Z-vg0awM-}O{+K)kkik0wU zIPYrd&ikMjgG5kvTx(}lk$S`Z7$m4z2`>ge-H`~&j%#!Fs?z>`KL!aZR>F(nysM=< z?}P3!F$0O9?6`hxS5;0N_m8_Is8|UvhV!nL?z|6rF-Qbu$JK3mRgstc7$m4z2``4b z{@k-mw;d#cvg2C%ZdLg^-j6|oik0wUxa-e(AM`#Ck_gI<>-dtYvi^|&UQ2?CmGEM? zzu$GgZE)K`A}Bkq8fjIf<#;~^2`W~?i{Y+6_w3S*K_VzSuJ;;Mm8LcP7$m4z2``3w zJ;wdE!Hq#8C_AplPgIfGr~LCo5>%{&7h{XF{$9HFd5}a%{&7o)CoJ?7lAvNGycj<_ zp9h`mqFy^zmB}eDU471bzYEHatNX|pY5J4?_Y4_GP_YtT40rvxXP0hYkqF9;Yu~mU zQf`kQg9H^T;l<#mI}$A(Qs{F-TCc5?&1VdW`#RgWC=gLD_MQOUW)>Px>)P zP_YtT40rvxXP0ga5<%H(4#Abh;`+ zA}BkqZ>DCEMyvc7B&b*kFNX837JMEg5tJR*tQlEkM6R@JeMN$bmGEM?`#Cx9gYNrz zghWtwT#Y}@BENR^W00U?CA=8!`g6}N-54Z-vg6wJcNRJSp&x?;6)WMzaKE2-zin`1 zkO<0-tLzh5C2Q7k*ZPVC6)WMz;HNthLD_MQ-jP*yJ>%{&7vopw^PqEG)axq}LD_Ltx|B^0zvaguLB&dVF{(SC2j^e=JV+uaJFXG) zv&%gj{TL*uSP3tNyZ+p>OJ~e8kO<0-E2d=*d1RL#g9H^T;l<#mI}$MG*!o1IeB&b*kFNQk~ z`W30S{ZtPr_0>Z8uENj;7ar~@OOELB$d;XDLd(V8zx!_Y|B-qt`n6X(?p@?5Q}cFH z)0e&Kl_yu5p_)yaZy{1wO;;73Y3nIfGA&lsGPKh4^UGD~5A?sAF{VNxkIF+ynO__!J=(tPDL-ZyA={px<&}@GNtO40 zoNgiRA6Qswc3tl&cdWf#rYGz2so(FE9W&Qhh}?w>%Ko>;drHX_`Q+emU5-CgSSlVK zVgcbrt4N9wZK^3*?i$fAXlJfhaKJtd)uE>FsoBJYgT zWs|7+@J45^>y93A_~Q+#^|PJ4@~+G4)YK34zng@=&$2s9{QZ#K@}z^C)ZSm)c(h6Q zceJ@K|IRbFtOjS1MOWuqh%YndmF5FydWwIqflK)J1h{202J7|jJp11<7@dTFPg!&f z5_I)Wi?=Vy8OGhq6zl9f6s*L;y9UE zQ6b^q4G|rK1YP@P+#!!Xr00Seg9-`%Ziwg@B!6Qe~3uctwSTe|LOz4FBF^SMl!=cFSA^=6Fyc;otom z9fOL0|L(t!LBhW?H#!EhqKii*vmNXc|IU85UiP6$P$A*pvmc!m3A+3{@S_PT{yp^n zJ}VOb-SN>em=#_Az3$Njj~V`*nXZe+7_+aaknr!hjE+HquJ=ETlTMp$$6fz^LANgd zzCO3iV~m*emDqT4}&F22K=S+TYL{i1HY;Vq{^!oL$VIx7-%`S*23 z6FdXpyT1RFhiJlo){?9E&qQ*|;pcEvNcc}XijF~oE}lP{y-S6J|Fom%7$oTOpIsD9 zQ1PEWcvd9*=L$u~U|n?iPYH@9cy{MMyT*0-&zOlOsQ6Ebab2v*YzGw*{_|g= zW00WBf0|1)LB)R_%fHXcAg(?0B{~MP@}I}zx;XRAmQx|&KWQa81_`>tR}{zAe^QfM zFXw`p6%`WxGnk^YB0(2>#Ee0Og#Qet=olpE;;b}d_|GnJ>++v5;+E%rv`2L*{)puq zjs#u)lUAa$V!i$|M*epU)=R>FdPsB(5_I{`0*NO4Cx*C+|KvrtTxG|X>em+^vb5ZP z9-!;;pWEk_d8{;hmkJ60iF_^{PSC|;zDY25|LKnZyB%yH3IDl`(OHq8%YO=EG{Miv zc@Ct?#Euia9vyK$RWiS<%Vs;yx9l%{67}_j+ROS&N;O^PH3yTRLZbWC{_@Lhwks1P z=nB7p^xk+smo@| zsgU^VRI1$i$BhWOI8J5^DkQ4!Pn9g?ZS5dI7sua>!P&5-U|-p}LD$QgOo9rD?JfJt zpz}A%imsir`^pQ2Y_p_wp{J!*s#dx_|FmrBeKRwWM60t;OWrQF7@Uc8aTS;?XTD3% z^p*W}biM2mlb}LkS3*BYYHiDk1YOM5j6sD&@_YT{@$R-5BL=;t^sN4P zXJ1*{=w{Xji5EvZtE(g>R#zwHNN2c|c z7Iki>9VANK-(R+ru*G0I=wgOu%c+oYkt%t_EyY3K%(t$mV(V7;YBZ&dNeZxn;|l1S_IrFv@7QKet&`|5m$LlQ|w#NaP#3MNLxOEHOyX74!OjHUI7b7J>?iCyH%THPdV{ zNYM51_uEyTH*Ex!Z8N`C1r}%*Ycg9-g+%tIJJpDRwiqPnDtdaCnpx6D3`*XkjxEz; z5Lx}Lx=>J;XD>XiG7ai(=_@KE?%cXp)lad_5)yQMIqy4F3cO|w_YD# zr+%-t{;6m9qvKAihu_iP>6io+5(m3{uh!+atq&4(EzbG9DqYVOqtR_&tIywQ=k-aI z7TeWFD|DHkcg?J*khnBwt7?5v)8PbNhpv33>QrfO84oJsp53g@EY>c@4v#@1QgxF$ z5Z}QPgLTox&%0&}DkM%7{!&djVT(b6E`FzH#^6Zp>-L?R-A8}J$B{J&DkO$Hvsd+5 zZp(@UT{9m0R`rOn5mc&N+O1w2smFsgg=a%Q#+DTcy3QwdmUhWDV#Anja^;6<-pXlLzN>6}VzO6`%ic|@ z_0(mv9jxo{teAGHr^KJqD~c=F%!&$$dR2N!^0S%_ zC+G_AT`DBsK#x?JMZ6Kd6#k1R)qi!U5kry^P@_|Y+yV~8%l zH}s^M{eY&;7_5si%06;ZZ8>j?!MYfuY2g#9`sLM@tOidztR^Pu7Cuw_CpCY(E}tm3 zQ@xn;GYhf1z$tbA?;m?gyZBS8-WpwIhGsjckeFZXlvVZdZW;{q#`uL%Q<3?t2qzZ)_IZJkE)8#={`Bw_=wsyQRsGX_`A>!(hrj3aMm)si@xdQ#?xkMLx#LTMn*&S-o zhbz6KPo7N2RHn@O=);;!f(nT&xsIu{r!^f;(8Z&jNo-$yTz$DoXI12zW9s|z?|T_C zTa%zdVnc&tYRSu*4kzehn@pn1CqJt`{d86bcI{EGJi6S=s&~vuHL#5Scaxw(BK#hD z5_GK}drB2KW4r5~3JKn`Z)Vj#+n;LnJ38NC2mVmip3vp8|96X&NM7o-$t38yYt#j` z{f-+Etc%3fOTViH2W;&iLDyf+{!nineA|*06%ylH{HB_GVv9k7u5z=^s)I{xMEco3 z)z(-&f4+Ch^|R~p_-U8aOZ{#0iVBHtEibFFjcvq}zg^Cz8M{sHH3##)nJ(`&Zo>z}_vz;eW zA;GhAGY0R1=H2nUYuY5Jkl;P(;RIbPX2(j0g)dvyAQcja&i|nX?t0Zi{I_2A4 zk|qC?N3N_IWobDT67%IQsr{Vox(^Au#{8H^manrBRJzQ{Ep6`C*TqYP(<=pbVhil5WM{UO| zf6qkMlx?o zVCK5~oyMXGe?MGT;oSB2;*BP#knnd1jwTr0-;d07Fe?PK+pA`vzXS4sE6 zS4x&Sd;I=yf-Zkg;b?*iiH40z$=qSK@3u+MAg0U2kP7E^Ql6x5Ribt%Q8pN}sXBy;oB1t*<{p z@V(27!FPI|2XP*o1QinDF-XvLW>6_PR>1Z-iV6v~$;^ts^yDvR`O8p~phAMba1AHu zdgzZbvVFxHmhqrMqH(|cav?>}9y1270q`mXKi!)I6%yRhBb=aXQ~vCd@!%Jhc2F4- ze_5T|yv}nmc6baD{9YuSpey`Z1{D(F-?5OOi{D_IS#ggP_HNNaW#o_Dw!Wf5BDP^U zS(8!sn;C-yUBA3sMOu7hBdCx_u2E4A%}KY6APKte-B??i-DUg!JmbC1KHqwSIrTX-HFPI$vL*d**O6 z>HN^AUcLKrHI-hoZCCE7kf=SaktCh5wVVW9joxY^1IO87%$}GiUwxokJELKuy#Jyu zpK0~Dl>hrZOUtQ{`1D*e>Dour=9rV9E4+89keL2bGdbAG7J~#`99c6fjvz@T|W^48p6%r{A50)o>Tj)gcn!Fk*>8f-a7~8Dr)Ax-xZm6R)m!d(@T2#dNvweGMe-Km$vRbEj*`#3PBG za-el>Npz0Z?lqE{f7X`%!&_MhDkRQ)UR(N|)3lk@JALcO(@!RNbv13Eq~Htnz4FfO zb!6lu{qH70g+zEeNYM38iMmqcYg-H|B-n3eR*z4Pm(71S^KyT3PrO`6(5;RAxw?$% z*}~FSR7l)ku9i%jZ0jo$bg|dXtf-J^n^sHaer}6Ff-cSlGX_U6Z)_cT-uW!$&JvD| zNl+nCc7APHSJpNjB- zC)be=SKg?1=~{oXj;tDPBgTGHR|*%=^Xieqb*0kEre13~E6uD%-4ibtuj;kECU3kP zN!A2sk4aD=@k)Vs`F)qBO@f)E9H=WrAHGpm%$G!_&2^>nL7lA`g9KeXj+q4W&2nG7 z{8UHx8{20RR7kXH9WSHiX*!&si|gMcIJRfw>&lAiH#4tDOd3&F_8zij#hFOg?04(R zd!uax*FpJhwIrwLHNkabwu1_Zi9Kq`lgYLfMS`vdxoS!Kc{YM)89W>K=y*%HJH|E> zsgM|1wyyk@;W5jRfdpOux394*NVM(gM1=%<-Rvt8ba76b1QinDBS?ZS9x==q?DzcX z@zUw%n;CNwLx;ypt=hI#%Q2^`_rp%S**2o`ti00j_jqrlay(L8mJF%ol?N{=Ad6=< zvWy@V5-%LAAV1`*a|42|S|`g(i92ociV6v~&+J_ibnzHt5>!Zp_Z11cc+59ruy@&S zF+ayj-sg2sn*6 zc78>Iu8hC!Q=Qi8vrMz)R7h~&xNw3l?uBL&R7iyHK}Uiv?oDUL;ErqDkB&8&1Qin8 zn=YK7YtH&rYF#VailRb-JItFgR-7KM`YzC)$-ZhiK|Rt?m#cS}t~OpBW?AP=GCijX zi~hVcc-wO-PfJ~{vSNa&U22SlNNk*@zHX{rlX8z!WozAtU|l4Nd^t{)xm(j_J4nzq zp!;~0a8b9(B$#{4`D4|ECvGMy5`70hug12yQC4)ZN6f4qm^Vrl?5y+c-K4Sl;&r`) z)w~v?)bOj%SbCQViMR@nse_|zS&^V?>pi2?3)5{ezN+3;<;*w8i#|(@QZKF@;gw07 z?Vv&;ckxl`new(6B5X!X~d zx@`6pm2sy=sa;pJi#3@96%u`)8>RkwQqP!hf-cS&lVI+Qw{+te^?Ny6JE)K-S#PLn zGcU!mqDav7%cSSj!c4Xp?DsiiC#cQybZa?IW;>{mxKd++Dqq*uS0w1VxN*EXeAt%N z`j|9T?6N+FpSb^d)%KJwvrT4JR7iZ)ajc3zV|zCsL05QRG2gQ_$E(#-b?$7RnH3ch zwWf|!`4ep|CqWmpHDgdA@$2q16<636g9Kgdbu$K!8GIMzF~%gQkl?#rI6+sbk3@a+ zi|sl!6%wC~t)~Xnf6=l&il+8d`?hMO*JF*;L%-{mC@^QJI#bCOgZWmh*;m#1S-aRiGX@nB$w&LC zZO3deNYGV!Tz{2+zm1@>An!oc_sg5fip07xgH-CaQ=`Ym zBsc~n)?^%}Dz>+cAPKrgb{VSLSFjPc#`ITv$Ln>#wURVcjtP7ilvF6%yUL4^|8J*kX{ND?BUq)niHh)E}dCz3c@uD=H)k ztV&f+jj?4#g06PA_fZ8V+XyO$MyIIH=if|LBtE;Vms+>R7K2&Qm1j>6)$p*5Sp0w8 zRkj6s#uaJMT}|Gr%RB~~eMN=DhFRTJ);QZ5Btci^8p&!;T^m8=w!A&m&|ccbn!>Xp zQK)K9HF=sX2J51W?+j)PDkR2^>ZK06Z;L^KF20wTF*s7QzDibAV)b}%WKDt!iR7!@ zRl{1gV+jem*dt~PDkMG})Lq@y+ZKZaU7T-bjK)1jt1GW8_1^p1?RZW-GWBh*JT>t} zRsHaLUfCq5keJ(Vsj6wccaVDva90HG6JW-mLZZyGpQ)ZbKec2&s#>>om8Bgd=wh#%?bw%noNE2CzC(adFU&Z8vD(lv*%E^a z2|iE5j6s4f?#pWuR7h}7&~SpT@codfkl=Fy%@}Q_zM=--s%QJ4?sHU*I9+D1o5bI% zUsLBx>NW94+1J#Me=qTRv`y=ks_pc5EWLZ~nc1q<``UHa`x8{}iu&%I?TN3bxo_!z zH)BvCak}&zRryUD(KzEwwQ{PCo;Z1?+We6&b3K|dnEL~xUR9I#-KZUGA&K+r|D$qz zZp(@UU2Kz?6%`Vj{+grmEVsoVL05QRv467GnB|-m->9$HizHh7K1;oJ!8Yb3=n9`# zR7i|iGh4l!RnJPZuSn3vIUP=v{NPo!WtZ97!MVF)^(=MeOFahcbu$JP z62&vlQvW@2qYtftKL&+wse4TfO+Vo#tX0MwB*LJJ;|ENcAxzRdj z?~-^aAJSppR39~rpsJ6CPCL5&(BruOWcTHT_o;% zeXiZelMpc1{D$``khoWQzqSjpo@Es zn0>`>-1zMx`^_Y%kl%o zNzlcfHe*mB@obR`s@_9smKeNF&9i>?f*FGf37*e~6Lhf`Oo9ptegX(5=wdIJ1Qil| zIz~7_S9tGIA+dPjE%MAc+xIw4>%=+t=|1d@RQosLWZD^B-aRU}yu18K%LsNTnoD+7 z(XRg{<&wXC)OS$v&JnX6thY(-TczB0H;TdNB!20CtL$5@X)^{1x~lECRrU_C5zIYi zdM?=+xludVLK1(h&LwpV+U_GGLDxqcb4lXz2Q9r@I7cq2x2>V4kS>~-OL`Wu-5W)P zM2WOqvSNshVDulp$R(NW8KlRw~r9#b8}@{oO29hIh3QR92kNDI;IKnXE{pEzBvS zj@n`{E4of}$|-GY+GZk^AMbVQouOT0MD1ct zW;>{m_$nn<)~4HHkf4k25@rl4Bs%Vlm3I!=VvwMV@2F-BUbEomXnqPe2`VJ`$ugXv zi`RWkf(i-lf^lkLGBed?zfyWH&y?;Nl+ot^@*I) zn=~6a1{FYWm%+D_OY>bX)#$df9Vp`^qM|Rm_@Qkd$J6R+{`{%tjeKR$SG+L$0 zW(?LfI7^Hi|N3UKBGGnbjO6;vmKEDUS9o7>JnlUnD^q?=iy9lV9gIOjYR5^Td72I< z=;D5aCP9V7mi}=vAi)-c1YLP1$4RC0w(+2nFg{NHoUL7~DLg9@bGpXK*!s2@tc$L^ zrQ+n-vtzxUHe*ovbYrZfF4Qj8WD-%W<`Yr zV}}!T@mOgRR7ixkg9KfCw=-jK{-nQ|RWc3GbBXiKB&d*B9iLT>d}N!6Bif zlHOAxoS=*6b0$HB#LhkGs`kajmUkQybn$%7j6sD&n@10;Vejjn4kzg1j{hb>g#`D& z4=3o#yYGzpVX19*d@3Zu_tWQ9Ctfe(X9hDXDkONtBAlRW=Gx*?@!rms5u`$bzhg6F zkf19$y@E`1o-P@^eQg6C4*W9E5`zi}{;JiC!Ts9ax>{5^R{YGXcSpNoa;%Xqn?%cs#U;Ii zR+45Gm&EqE%w5?`f-zWcI6;NPQ|pS!{?@jvNYKS>&8(Pvi;N}Ym6kVZ2V;;p*QJE~ zUhhU((N*)a67pLK8!_m$lCo^~8gC5B3@#}L7U(i}uru31g+!?bN=mJPnhq!EDt@Vi zlxk`tCLSs-Pu!vvKINgr7HUL90i2LGk+ znq!7$R#Zq#jx8?7FWc_9BSF{P1;u1eR$DtRzg|)n^-uT4JbiUZSz1q**(Nh9DkKiC zEGea9G#yUR#rb9un<^BQ)~j?~Te=jLzkkwYu4a>dK4rg>3WIr?V$ip1d}PRrl3wVZuL7qd09qC(=2zwef*M{O}k(8XRiWAM34 zd|nlwsALjUNbtE*;RIcL@{vhUA(5J#NxCkv-PcEgF7~<^g9?evi;KvvY5KWa;RIb= zn>b=A9E&?+vDkNqvJgzbg>h96u1YNu~U=mbF^eK^D4m{M?5`zR?|LzJT zi7H9?<;nGfEiqUZU3|uj*$yfsGIcB=9~HFSmqCIqK4Zp=L4`!6)N=CJT@gz=NYM4~ zo}oZu;JorO>v3BQ)8%Z{?U0WhSSLb(INrS7l-;7cr!ROSQS&^V? zW9uYYx_+Xicd3vFf9Cy{^S)C>-qgQ>xVzH#YQ%2+DV{Um%!&$$N5`F355HsEqmcw% zocU%9DkQcz_h^(FY5ROmf-cT{GX@nBlOHW4^Do=hISINr^UWAkNOWjXS~9e-eLg2a z7iYd1g9?d>NfqU{q#>4BLV_;Nd@}|W5<6eIR|X%q#UMc!XTBMO3W=^e9+q-H*q(hx zf-cT{GX@nBX~o)0zDBm|yCmpJUD;U*RGVPwT`D97JlRExog8l=xc6sTjZRW)OmELM za9$_LFin@uc2IdPHc5(4(Jt0x5>!a^ACM#;470@`L06vdk|g<28`1ce&Y}wGD_ajb z{d4Ivy;8Yt-WM;+ONfa*BMYep}%QCM>&~>PM7x}TJji}P4gDmK; zl{rH?$kZQnnO6gred;PvV(n%7x=yLd#R4ODs&)Z2pI;3ec1_`=Ktn4T; zIc)2Ly?E~Kj4?<|$>y_usAiTWQWNr}t0@!%|>i{oTwMTNxDR!LIhJ6jAAbaB3!F*qB(f4rl_ zDcy3`WD-wg+$C|>kB9X6e2U+}@ZPl_a zx;R747*t3++Npy~%V9evlAw#nN;3v`PvI^n+}*<@sF2`qXu=7)_`Rx0P$9wJ(1a6o z@q1O1phAMbx(O%f;`gd1L4^eGr3feJ;`gd1L4^dL!yHb~#cNq6L4`!`v{)&UX8XpS z1YNwAWyYXFg3tL1C+Om}ER&!@g3tL1C+Om}ER&!@qQ`@Eta)RaP zLxlvNr(wn*L09HV{Up7dEd~`53#Rsye0gmIpRmYhb@GU6W<`YrpTZeV(8VLFNl+ni zxxqtHxc^*B?~_4Q5lK8N81UF-#uphBW!pAIsj;;WYNAVF7n?@}T0 z?3>-C>bKic-uD(B$*6PtM5;iU8fgV)&~_5 zt(|KOO+K&@+fVh7QeQ>KI6tF@?0(bM4nBE}N4xN6pHU&f49(spK^J@7B&d+M@NiFA za>UjS5_EAcm@zoE15fvo4(D{etjQ#(khrsXimd+OMp@AnK6kkWi#p#EB;T&<&JFg<-~D)_QJDFlb}L^ zcVC1Pbnz_HB&d+!-522mT|CP)2`VIb{uoZs#a=fFDkOL|7*5c|*<%t^Nc@;#glv0$ zmgT&J1YLY8su_a{37(^RL_~9u^x!vGZx3k@+>7OugS*9?vPlHLqH~nsw`)$BHJL;Z z-Ejq3IprW*r)(0zxwE4LPeOId!TEI*5j?-tQG#cbIpyG6jwm8{uA!p@Pe^pi!IKQ5 zh~ODKjuKqCbIQR}iF`tLZiYyD@Z=mv33eoP%E8lhd?KQeNP4h0s-pzECpqO{m!l{m z*n!_sf*s79am6p`t^qB1nUvx~8#q!lb8dq2_T;1hBbQEBJ~m92e}M+7^aI<8;` z)F`6ggq%|B*Z+7#KIhJ(7H{ivaJ4>)phDu))iI(vYTBG7BbgaE8}c2NYK^z!P}+FQCkcuBo_UYOAahT3@W z_jS@`&QLQ36%tFklNB!_ zhEu=$ilnnHy0{*-)%)uZ!FQX^N*(;pZSu=qA;&8(fE$BH9}=zZyiH~|v>i)G&=qwQ z)k!%q_-;_E;qB5u>2c-^HQPaj#4U|)m*KN9OCmamIos*_xYF(N`ENF&^2OYe{GfjK zDm*{8{P?mivk%RzsF1j`YHms2hxfrCD-v|Er*#Ybc4Yi^gSvaV^PQ{mST=5*%K50K!wI^+Uj4ZmkZdEUtT?n*wd{2>S&`Tiw^mJVYm32l z(Dk-_rsl`n2%h717@MwUWYey*|zG)zSC$JT?g`<-2{V{z%X+#x@BmB>HsvR2@I$+;`w-cI zRUQzm>qNOVs_sfnGj>2Y1v4uWrQThmI(O8xM?^Gd5_BH}BoWBkgNoT$#8n091m+RcwBOc+n-Iv){B!Va2`dMk< zI)W~Kj@FfHB$7^rMDT=NKSsnx(A8|ndR6RU%qtBzSy6c`+Xj^|OS>4`Gh1VjXgg?w znsy#BtOQ-03ucVqn@XpJTMG7-of{^4vv0)tRLT6ZE}I0EJO@%`Vn^*_O(sEwMD_it zlBGOixLCv;a}sm~cV9$}2Ne>3ol2Ek|8VZI_@4w_$Kv`*{dFL`#<*GiclrP+_MFc5 z_5lOr)M{PkRU^;rw84EjM~3@`$kzeKV`zEA1Fj?J3cngfg+%wO{pFY2 zbZoEoAO;D#YA@?ADb;KQmGdq8OP@sTVol*ONVGcpwB+q#i^00+>iYcCvZc3;pwha~ z(^4z-X0jrY{9ZqKyt^$1v!aVL)NDBw61x)mNm6TD3=(uLJ=0hA*Rc^)cFyiAFBH-) z))bx%AoVMnaH~6;!(nj;r@xZvz;sFw+H&lebe+R;@S)d7fPo>;>FR<8tj2J z=+y7NOoFbDclMRFjX-#Imk92^a*hDOJy%XSxECwx$S`cu04aY=*L8Hk0GVIlX4W~0 zb&Cf`xkOv<^2k6Jk1<}8ul6$dSqIEX;DX)U(Pf_>U4K@6!hB>w4AM- zdbyu;j@3kX%c+o<*Y#;RAERk6p@>c^l1_rI$vd8wJ-36-77bTlcE^DNlK> z$m(y^g@Vp6QQ6+Oo9rDm>7 zD~=k8Z8N`C1r})9%!&kEoINJNeA9Y;sh(P-=Pui45>!Z(9=%b;AJ?-doS=*I%_FY; ziKHLw^1WJ@Uw`xSb?WzO>z}$D+{GR>6URNfS)Ezj-kZCJu6(8HRMBOAk_lo&+?hz% zr8!$w>x1n)I*M@I?#nqB_3z+!qLZl7V!Qfig{HOD`+FThSEJj$R-eCPBiP#DxB5;z z9%IZHR7eE-1o(Xw@v|a97mrUUpeR&-fsyGPJf<X0mc^cRA7Axl{UoX2p6*Vze#bxg%)q2_p zD(%X5m5oo_Ojaa5Y5kP+tznD7tmtB|o9&=NV#Z5dq~R^L7$oRAdZe=){KPg(sGLvi zEbWrDi#3I3MWX)xBzY*t7K3%s#W`li2zH=xW=62T>YwA-^4t+kHjSsgT$?zne@*(X_UDe;tC+nH7&1CP9Tny(+yV`B|*E2>`iW9r+3tGsgX1oEgAwRYOiYRsBXJlCkL$5r`nba~VEW2#lf&%J*)V+@{l zSWQgQuD&G?tDmdsa_}tls2HdB{HE%@_<>hfiBC_cRa-vt%4HupskWTgWiv+8!Y5Sq z%eo!CE*w|yy{^jzKRTvz46zZ6v7*>HHF0rtJTnF}A@N%0U)8ubH62dSRqw6Ss?aPO z!FDkB_lBNSvmdY#R7hNW;kY^#v9+88U4P&5i`p>27J~|jVr_m_ho&Hg*L-(Hk)SKQ zI?MbbHcDt&xXr569#n^&9*+Um!kLSkEvQ|f_7 zH62dSHNV;^wK@%i4&n6GTg{KEls$S))IPLdEvT^8%W7MuH^^3SpnJPz_W&!dEy6%`WU?*=63`unG&YVc6os-;4r$n8f}#pgiihC98>mD4W% zl&ZHzx0Y+uYzGw*y9=CB_y2C|D-v{F*>h55C~cc1M^jI#Jgv0y`l%Bt<49fRS~0Vt zLZbO2C)B9hAco#heoYQ7jR7fn$epo$T**1bC=wh~J3@Ri( z>3vu=yu}uS1YPWPGscs@T~NPQ(C?|42cB1tbkpUfy)UTF%WUtpR7h}!nlVVw#o1#L zR7ix+b`o@P6?ieO{fVTr<;?J@2QI3=4(qcsGb<`2g59+J^TZ$q3A+Aj^{1LQ!4@Of zZQ7|T(+8K-nshynNt;j=7n-J$%f zB0fQd#MVo{s|5!TLjz6>DtC>#ptj%P?2hi#%bGm1H3o@c2mVmip3rnSL07QDd{jGv z=Po%)@0gQnU>RNS`mv`}ku%q|!^td?9y|loA%f?AI_2OgQBg6n&@1P$99Q!7;VuW!r3LR?MWxH^^>Kv%G9OjOIMkO+2-@rj@vBL50N6J4?ygqt5SD{j8k&-Ip07*oVb&h5!1D3W;D3n5Y;e=;ANm zbUNN&C#zuJbEmG7lkb(PmGw2<>~$;2lXu&$?{=GBRpce-SGW!l{Jz#Hvln#jZnNE% zv#vpBE6K$|x?aZi2*>Td%&bUcns=WREN9D#b)nXgRZd^A-$|^URYmFzx6MQnbd|iL ziu77-BdBB?UReqp(=OKJvSmerF3vGsyB~uy?)Z|bvi^{seXPmzMtp(_iKXvWmA~Wl`VS}Q z;t@mF?#I|%;9gmFPR}JCIrDvSubhv=m`8kq3JK00GX@E|7WJPrGsI%3Zji?0-vtcSqXHiVBJODTQTgoGk_k zx}vi30=YAhyHV6%9w)os(Bm9D|0k;DR7ji{lS@{AXUmENU0r77mNxf;aI=cISy37D zV;)()PWKgS@|xhd-B%=?3W@o0m(+gF_U$VPx;Rd{a__Gbg9?d~EAq*~;kFng=;COa zF)p@r_JEkJKTW*RJ4U7q(w`u>gNV+@&x#6(HRp23sD^ltir5IcG9StzD$e$9K;^%+ zW8{&&`uM@vUhUQxBo5q?Q!>4K-7(RjBI&G)F3wOh1{D&ED#S|ie{9DR5_EAMn=$xX zcK&*uzn1q1_fN!a2Ne?h1-M5zZueypbOk$sN3B6BBv#Chl@1GEwwxjJ8*pB8;B{Y} zkDHR46%`V^{@@Xg+kKe?UA%s+t=?aUphBX|v!AJ+JwLUyV{X5ts^;Z)J*CUBSJk?$ z`g%$EEX!1uM{!NxOUccuTlc|g;U3*5!9Mg(k6z9P*@UFT-G;{iqSlTq9ZSsjFQZW_4Ft<8-;#V~x~9zs&xpcIPGdC*rR=wiQ_EvG`FP}QDl@-$lv5_Cn4N01d~Uy%mg)#Sape^^s^RwNex zUw4&lfvtC07hN9?>aK37g1P)-!{8TMWw*1RQ1%Do5_mAV@dtg zAEOY%X|)$7omtU!YfOK&cRUCUIDN&H^Hl3$YSC2Pqg-jaa*agNsgU>~X_%_;CB`FS zBk0;(Vwfs%#YXU0yKc-NmHM_`6FhdASy3UeAn!oc_eWvl@^wde<`PCEDmjg5%PSCYr#sszMfQ|U7Y=LAu*u)c$IKb)8PbNMZO%T%G@2X#Go=M_c&FymUc0AcnlJWjnmZEO>Hq) z7hQb^Kd;8N0pSLUxMSYCNn`cJ>-x8$56l~-3U=15jjQmOIyef1<91)pHzrU>%xf`9 z4Zms|4=P*l8KqvBu3fB2SML42E(VF*#Yd@U$|HuC()C%<^;Pw*Drdeymhqr#mKvpA zT&rhzI6;L(-{(fDzn;YUi1_UwLD#rbqtvb|!!22rtT$A(nU~@zzf5{gEzG1{Uv(U- z;?L-{>D3;@Ao1(&G!<7^6I^K~L4`!EspC}sL}aC#;fx2Bvo*)7)l+XK28oLs$E(AK z5hG{^v!aVfqH76Vo4f4Ajj5y6UvKJq+3RM@sgNj=dyKl6gsg&=lc0;eZpNTOV(G>) z>i2Sp5z#@Md(ScEbaDKzC3LOjoDC=Le_pjcrDq0f3eSqf`j|9T?DCD~6su57?YqvqEYVAs`DD#ahC*LJQA5PcPUz7J~#`>~%8+_aox&Io7?9BJNR?3W+)ESE+Ta znp%!mBFmKan>1kaN4KWzswNYFL&(OYCn)jI#g z2nZ@9T0fChzS;mHqLD~C3A$o_j+MO6*ZL<$Ku{qucu4_SJhRb1M35B;x+>4gD-C~- z|Az=-#Qt1eM)hprDVgfjkp5eAkJdU_UP|1F5p-iXlyhu{LgIyk737C}ww9Biiy6Ar zyY;)TNIDe~IUXr4ONOAYJp1(oT~RIfBDlmmCF)9%uM@nMzuTj(G%nV}D;K`6futR1 zVCkzfpVyXt=Mp{TK)Kay&?6+FVyEAJnwj4ia>w9H=WrAI6a(qH~L+uRmEwRt?wv zK74W=`EaE!bB3BRsF3)fd>zTL-!_6I=;GQmV{mL+wT_oj^Yl1#E|>%r5?Stxm!Ilj zmP9{CVVXU8%HE_Ydcr z=Z*LT6%u2=sVjwx*v5kdU9;blg!m}d5edEFjy5?SZMy@Wg-DN?A z1fPgv#^4iG_@tHK88iNv2Q3etE8{3B4-b|nep~3xr8hPXlXZt*`)6LcM8rKZJaf32 zbbjblPgybZaT#4+e>)vKm(GvjxZPJIoeGKIIe0#yf$Ipmf~VS%h`2F6J=aXS_IcmS zit(nu)JzVx(*J&~`fKf=LLzu#sUO3s-+e{WNzj$?-ez*L!F4e_f?3UIm?-bR7@eW6 z-1~c7%Sp_hm?&R;fEW=QLDzr2NR&RuYy@*3II)TBY^z;&o^2xK9|oaAI9ai-)29-p zZoXAfJ?)vTS&?X+vAL{D&~!LKSM|)zrOqfD@qODwxhku@OqRwb%ClW{nKRUkL4`!u z<;`UDC{2eGbZu(X)A_K>162RyCCFoQ^eW;? zGqa*XqGIJHvU@Prpi{s5a(+uzu$c_Fc83sMT*2Dw+FgR{Idhw)GO+H=WJMy+7fmHw zof~CESNJiJ>p9iA=2LC8?ol3ty>>Wla9`&82Z=G?IP3oe#v|eZ*AaAa-FV)Bph9Bs zYl(7ue%nkWK^KooW(>}s*J~z7zIHly&Nq{wLZa8h2~w<#t>q->dc0?Xw7!55^a8oP zn_Q!!9Gat#8L3Kd`XW?7H5I zLE0p!kSJQHjQp|ti+_%AK|4s$6_u4sMBJA17t%xGFROE#b?*Envsb<2c3+WnDkL`L z&n_7cBCCi8Tu0Ew9`U>ZL50K}Yj2n7$-3Xd3A)&CIv@Qvk{&!^)j3`TPos6pJR3A) zP$3aK{nmdsxE3gqP9=E4?!S&fB6tR{A0y(ogIUqVGg-48R7i|k|Fjg?`sP3LDu@w0 z57LPqJn_~k2T$1jpIHUZ8FgI26HB8Awl;WLx8q`lW;>{m2%g*>6@vs_!E=#)!VToK z-uZm)KXuqqf~OHXW%h`f6%`V}Q(XNRPW|r7dFG`56nRIXD|iO1PiVj)*o(oFdmR_& zg05U6&i5au`b)EK=X+yIB6w1;A0uKT=;FH3UgxhvMbd-k`#N<6Pi}R}Y@bIsZue!j zoJ8;p*r=>n7hP!>41W$*KioxiE^Y@a`SM*f_W^2Zv zLLzupd{hh)bTL~q1{D&)v+1K^kf4iwXvScl1kc<4*S$+3c-Hs-%!)3qG%u@bf1JH0 zu?H@9S>>*kW;>{mh`Le~(Lu~-zR<-daF{Wukl>XmUArHH1YJ>Ayj&pSuG$9|m5@CZ z)_BKup2-$_u!JP$(f_V%_X#Q_xD$#;IQ6@)NID6+CLSs-PuzkS5f5+(p2KZlQdDxs ze&%JkrAtxy`zPDybJm;jfnw62fUbA$f?_f!D`Myn*R{O(r4mxAsdlkVo;k>h3W-t= zl$2Tn5yMK*Rc3HWIk3P+u!Wl{6qVMibZgloW>!>449!wh(#F{OiUeJ^oxNLbO9bHt za@yiNKMK7#IkvbQzpSrcve(V5sE~MdP;nXjm!`uBx}s)@hq+m?7YDsoQkLz$nGqy$ zcx6c`9fOuTt#)7Lr#rgRSC^Ef^=w3!+e%7m20dSEepW($E1}E$e5EV*{yH(JkT}<+ zg#2Dl(* zHL}HER&;Srn|(!v#9LR3O2>+}7$oT8k;sg}l~d*P-7>C#o*AskB&d-1QNjS zTrA?wL=tpyrI|6PkT_hVsBC->F`W9{m-B9LET5dO`muMcrRz-dqOx){2+!^kR9=|o z)Z0e8Sd*^Y`+Hps5+58XDh=;PjEIe(i^qBG^$D)d%deM|Mg8@7@CfdCBR)ZeM6R*U zYJT0e&PmY48EVF$LLyVkk}`UaEd~j?c#P34@Y})th`3J?ckwZ^qC%p_gLUN7LhpEU zA)KJ=a)XDYaR0d$f(i*xy$v z#`>oCC2K^d6-lQ;g5zYyAVF8hJ{@F4#aI97s~`py5*#Np1_`?O3E3p5kcj$x9%My= zE?zJ5VqE*<{CXKXW^rt|!;YC16%y>jaDpyAjlm?SkYFE%6Lj%2l}S(`!9ENp=;CK8 zlb}L^S9ih*x_C!{Nl+mXb>~3DC!@vfAY3fso-LJF*->J0^zbtIJZ~rY z=uom(=3P%_3@Rj+M>IM5|_1$_b{0R6%xt$J4>Z|b++LIT@6w?%hps7 z9_F^3%7f06JuZEwU5p(bgGA$BI*TgQ)9bfzg09(ly2!ziAcCx@WG>r9w*RbM|1K*M zhst-6ADt(QC$vSgH%ZLACM#;4706s z5_CNmn#Zhk~ll!il?G6=5=j#0IR43`T>1NhBiKVTQq{eqQTIY0e z1?v_#f4!`j@3QP2<+e1PJA1?<9Jl*2TTbHp$2&@#Ldzo_a2-Jxk9^we6I=(C|LQEA zO6cP`*Nx|m_yiRar8ah!v}bMa1|;a>d^2NEAu)DLXGz*^i$Q`eu4Xd^?;YaZLcG_= zB&d+!T?^p^UAzauBiug`cg(4fD1EVte165Ye>(}f_zBsI;neTG%&Tf7GA}M7yQbN8 zX=Yt?{k!W7BvO+zN!KMyEk|nBMHlxG*A4LgI_;oBB7A>p5_EA7bTbAO65;z(lc0+` zsGBjkZxnX|=blw2L4^b}3@7O7ofa!a()72>CP9S+dpew;i@QRb1QimTG2sMVymn#| zR7h~X{yYHq=@KEAu+(dKo)B zD-xe>jFr@dwyaneU3p8z$+Kr|1oLhDaTfWttInP6Gqa*XV%Cf-G9njR9`RdFg063- zW|2m#p8uzJUBICt>FIA~l}rP4zU?YylRY(cdGW$q%yI91XS0w2AcQcX1>iDd3?vt^W@aLZn3g%@kzKZV#jNNWF+aQ9v(ZLSsdOou9DeI&vLey2Z8mv4VvE77 z=;91D`-%#Q(L1uru7_+fNYKUiT{8whpYwAjujrWs6%za)cuH^IzGI2~d%X=*q65Qj$j6s5~nQMzn#d|wj zVo)K$T`~TjvNw;va$5iYw<$D895SZSp(3-dN^ff+q{x_ADydW|rOa``6rckNq7&2u1UDvhuy3TWdTJPUE{K55by`KBI@4ff^zVCIfweMZ&Ai>l- zBOAnj&N%)*4#V^>!#*Q#4&y$&$2vc5e@pn}w^Ds+Y*0s{b#+)XL{>3hO^z zqAQ=(iEmsI4jzB6JyzFo*N2xLEj@0hHLee{#={|xum8xe_Ut<)Y=3mAGyCIPLiZVVgGz;=`X zA^7_IHv5*avUzEn_$rhhyo6L2*&(s!c2mOjhnMJ@38to=H6`>J1;U>dJHw_<37HSA?F~$6hCja1@2&nM6Eq1$(d|G+zFBK@@Uo#NibPiW<{Vuu7@^_mH$cpvFXf*lg8-8;J4IN1&o zOx1jUYX1E==a^f<_79X^QTi&M6+0xFKXP-p=dIlPL4v7k*0?#`yCO&Mo!WGxi6OpN zde`__sC-uJkhpp0iQ(W0|K~lI*GpD;qGT=aL6|3Kb3!}nQFSmr0~ZV|K~4twG!;ioINT0{=#258j$$*g2~~i zhv1OM*MBOX6;rR{NK}g2zlGqZ;i$GZg(KJeD}NJ74DWMeSifHGN-95zO!4n=>G|kJ z=yvdU$7A^a_70NZUkrDsrs7!3)VSRyhC{E+U4i6%^Z5%5yk6=K+YWX}@K+3skhK0& zT_nNO`9qe4>jzx#^|3>Ozc*9qAi-3dK`rCan^tGGgB=q5J)TMj38v1P+A2;u zCg)&>1lLSeI!G{8`;(4w-I%+I!ww0qnW}V`A1&%bvWq0(%pzEpA|bK_?fPmVCt1k z>ckco=0@A>kl<&!(m{f$aYt?yr~R7SYuO>e&vd1O1XCv;zHKZVURsM)Nw7nLpXr(j zrmpC*L;SAC+5dS5tBsR)kR1~IOjkNcFg5R*9pi{4IR`r=_?fPBkYK9!8wbUfACJsz z2RkJAnXYt@U}{X0lj3F_aecSiIC-tuA#vOGJ>!{U$7Y@t38n_gs;4b>%MrYr>L)wa zi6bX=w8vd~N}YJZUZuM9eA2Vpdj0yb>b3nX)wpZ@czUB!idS1KTb&4YNHiN$Kh8WG zjx52{kO%6=!#~aux7Dv3AG+codsZ(!Rwp*>RH}JL+S2n$&x()r@w4?~=y-t9e72U& zJ}VNBK3_j}ol&A|CYbthcKz64%LC07Zd^aUy-Vqpwk^mKOzrl@2JyYKa|AnI4c#DqIHQ!JyJiQ8E)6z_ zE#J>M_*hJxbZ5OdVMUJMXX*K&b>dg6O0Vc@pDW*Tc1S$izD}HebME~h!PGE0;;h{+ zN3c_;P$zEkR_W8nN2+|S*dejQ@3mvC)9~3e2f=k{6> zOz|&~IrLxE`mFeOY0Rzi_i9n;FA*Qf2ubTd)kStl%v@O~UU+kfE=BF%|A%1ew?pg3 z^Lm3YfjZc^VP@Ufy6UeyD-xG)RWClhJsj1!XT{W{OY6liwgutOik(Zptrzdw|8`A=M1z@w!t7di|L0g+Z6?`k`B+Txs$u1`VuwVh(=QIc z-;lc+MS>|_rK)tWLt=c_tHSP|J($@J5=`;82us_Xw*1%U=7wF5ImRCA$^|cm_x^pX z)%=Zs|MRRKogaENJ$N;OQ`|Qz33fPH#k1kG3Ow`)Y@%^#9~VjCekw*{#Hth zM`L*OtIKVl=kK&sJ}Y)e@R!qSCYa)psFGlZ#A?3{SZ$na2MMNX{=L+>`z;RlTwA)! zUZb}bhYwnnYR0pP%X7Ah+I^B0&#zBH9zUq|@c1R5U`_19I7Nau`5=`;)R_S1e z1b-jPi0TqoT_nL2e+SPULRA;pA+g$T>XotT;)m;97P>vw%eIieGPTC#w}-ji`)0PB z9TN1}!^<<$f8>{e@K{U@pLb`NRLEU*W`_h{x6*^#zr{gPh^J#_s2>H38pT3V_A6V!kL-v zV24Dn$G;3`49R^fg#=RrYcC6DZ3jZ1TD5*ko*TV9G+I%zf7IgZ(CWET%}28BDE~`V znBw`8;I}R;ERV1MR1!?_6)9y)|CYaSc-={GZql;VIf5y^v!!ez*df8$Ov_g12&VX% zE@czJ4hhapTDCezFvUHsluZOXBse!|+3Fm@6#rtBvWZ}a#P~~Rgl!)=A@kWK!PKCK zuM4d&$Pw(2sQm4-^WR?9;fV8k7WJ9=Z$7j>XFvb73f6Wfwy!pu*I{_uzD9UTI$jIG z-xw+s=?078>{sKp#0HWY2c`T;9HbVd}!Bg^BOnGgNot`+is(-z<=3vKbaq!nM3Iz}aPsw93<+VA! zYja`Mb@it|q3;JfUW=phzJnkNo|4C6%4>7%x#GgA_uiY+ULEXsEe_u2uuuR|@RU3j zQ(l{6)eq-ao&I~FgF4vpS{#*k*Z@)RlspzwUYlcF=d-Jxe5#K**zsB%yrV~<0HWY2 zc`T;9Hpd-*46drP?j7b}$7^x$?#+b)h=Ql&v6%AO9JLzvsoM6-chyl~$7^v^-gT%Z zf+?@fammZaSKUyxR+T!~@md_b%Tb|F6Ty_%<`~BAD{p9L0{mcbIwZN#(K6q ze&%4uYjN5p8~^U!-&}KnIoR=99F=#+uZdvFYjfN&qj9^}{=Co}?078>-i=@W zUe!P_<+V9_T>I)1t7et9gB`EM!QTid6lx-v^4c8F77m^B-Hz86hog3Qx;!?hiD1fWbKLbvan7=n2bhB$uf@@R;YVS5 z>!;%T6~yDUpJ>ibmJqs7X#C~7bJmk%h!D4u@LEz!Th0qt)p@e)$c`q&?js1+=Gf?r znH{D-b4F2*AD)tq*FyL&07_jb)I>1lwK<0Ea8ZX3W)C+9J6_A<`Y#2Wqb7nWug!7v z7F%}ssLuK3V8?5DT>ouhbJRpI<+VB9ns?ydJI=V!9PD^4kL$l#Y>t`;ro1-CmY<#Q z#H~|G4tBhj$Ms)|Hb+eaQ(l|n+zlJg>GQ#PwjJzvEsyKJcx{fF2&TL?$HK`M&#BeB z^q#ZhwLGr>a<@5ZBAD{p9A~`n(3}GgFMW2|@me0&e}UW_H4#jCZH|Afw|LIx5B0Lw ziXE@zasAiR%~2Dik zW)60|mdEw$*XF2+V9INA>{~ptcuUU>%)yS=^0TEW={C?C#Fy*y5zB+k8ak?C*)WMF|;;7g9=&)dyEJ6_A<`aGUFY9g5O+8o6LFD#y2 zcao0J3+#9;kNf24sxW-ttIDrcO$1Y3o8#L>7Z%$TmgxArz>e4A`1fP`g!6B@w(O{h zV9INAJp9V}#ch6Gr-M4!@md`HkM0-_{7UYCX|GjH1XEs{h z9lM5sO{SC`H4#jCZH|qu9bDX^_g&^-$7^x;ni<=Unh2)6Hpg2NPb+S_;|Jzo$7^|9 zUo&Hlnh2)6HpeF09$(z%h_$Qq{b0vyd0byJV~&~#ro1-Cy{B|8uD{(D=3vKbd0by* zV~&~#ro1-C9Yfj`Z#r&AbFkyJJg%?aF-J`VQ(l{6(dg}pjb`m*4tBhj$Mx@znxiIy zDX-13^0<}f?KKfhd2Nm~ zHqg%%J6?-}(9Z!PZ;GkMz4Tw&f()$rARg zzItlYIUnzSzBx#EEve=+H;W6-OAZq3WC?Rza?pqEM}1iu36tAd zJ9oz-2e`}!;G zXh6biNqxFzow(LN>$BTmN19zf3jDZgM`U6+HvDc#HAi++SFo*7cvRA32K*DQDeK_%N@yG+OFK-74 zcCv&ybpMmR${ZxTmedPtG>nIxl^i74$r9$!{ZIBPbCB>_Qk{lu9)B2+93bhPeRfH(lO@cd`=9Jp<{;s< zq}JN0aXe@9^tmFzPL?o-?tijZnS+GalDd1XrtySMX&)rPPL?o-?tijZnS+Gak~&~a zv-rYMX#`1voh)Gv-T!2-(!YrX5?)Kne-Xvr4-)KT33KTFr)QVyAmO#7Rt#?u7jKdN zwv%8dOPE9VKRvrt2MMnw_2s-4@tZ|B4m!b3mN19ze|mPQ4ia8Vs?9Sk;sf`ks|F<4 z$r9$!{ZG#>)j`5*N$uaUMVxYOI%gokPL?o-?tglAsSXleOX|n&&13yz)42}`cCv&y zbpO+{OLdU&T2gy$(Ja1oNIHij!A_PihwguRcBu{$UQ6n?bDP9Jd!=(x66|CNbG)S6nwlfC_uO;>RzD?pcosxqDJ6XaU3mR@+tktxWIY@Xdsrlo#iT|9I&f7__lO@cd z`?#LL>T5;9Yf1S?&-QZ?>|_aZ+}mo}oJY!I&L+ox85Umss2x+imef!GSQ3_3m;QgD zK!TktVUA``ZaQa0dCW<|Ye{YS=;E;c*~vkIoh)IFkGg!={^IhOlZ4lj`t9>YVZ=Gf zL4utuVUC$|I(L{-9&?iLT2hTRS`>D;Bsoa1lO@b?q3q*VmB*YUyq460PG5w#uTKsV z>|_aZ43~YpS9#1y!fQz#I^pv$e^zpkU?)qM;~%n*zgZr0lJHtmtG@p%bbBv3NU)P7 z%(0P-IX@_mIZ1desmBL?7WQ9LegV+-4-)KT33J>g``?Jzjp#NwAY8 z%yGZ$e_wrF8gr8HT2h0Xe-^&nEjdWAlO@d2S@yr1%VSOwUQ24kgwMhiJ(7b2J6XaU z-^%{ir#$8);kBeLX!?1Wc6oA;U?)qMW9zDIsy-f68gr8HT2i~d^m+L9p5!3GPL?po zFxme`m&cqWyq463qrV8lpGyuB>|_aZ$Wg6>90!YftR>;Kr0za!Q5Y~kIY_XRCCnj5 zwGMI|GzST|_aZ$Wg5*$3b(D z@LE!b9lSJ*oR%CU*vS&+kfT~rj)UeP;kBghSiUr@aba?hU?)qMLyl@iIS!hGgx8W< zG-z4a_^9L{!A_PihaA<4avZd=8VRo@_51u~p|EXokYFcEm_v?gML7SSZmeh%Dmxro3$w7jhEMX2ELCSH^#+)R)mejP}mWSD6 zl7j?0S;8E0R4dAH(8hx#yq45!>n{)c9GM&>*vS&+kfT~rj)UeP;kBgNJhm(hYMLA* z*vS&+kfT~rj)PVDcbA0MlG^^@W#N^T={%7HJ6XaUa#SnIanKwjyp~k6CzghXUr7!U z>|_aZ$Wg5*$3b(D@LEy>Hdz`@yC*qFu#+XsAxE`2avU@V39lvPqcA()CBaUXFvpd$ z|6Nla55BtU`!M}e`97aKme-QH{P6EWm&Z&0U%r(Bf}Jd3j-gL)I_JIec#wqGl4?2W zo3P-X z_I{9HCrg;4mW&7QERP3Ccr7Xa4yHLsu#+Xsah~jdrw4 zl7j?0S;8F8%l>zLc|1tMYe^ll_0q8WugO7zoh)IFzsY#;i}HAogx8XK@SJ5~@;;B0 zUn>&qWC?Rjm;J9;9uJc6T2jBQ`Bj)ZEICN9lO@a{N3{-e94zX22??(yRdx5*VXH~W zL4utuVUDgc9{jpI9wgzlq;Bc??{L{&$w7jhEMX2gsy!}ym2C$JuO&6J$+zK(+mnL? zJ6XaU-^zIK#`1WOgx8Y#dj5Bz!&S*af}Jd34mqmLk>j9k2MMnwwf0#n!@;K|2MKnv zggNA>R+QtQIY@XdspG%|_aZ zY%b%$H_PKe5?)K{m!p0TQ^zI;33jrCIqsMJ@AL8;Bnhu2b#Kd6Vchn~L4utuVUB6C z|Lsy950da&Qfoc3D$FUSzwIR0$r9%HQ1-uF<$P54a}r)l>fu$ZLhr+pg9JNS!W?=% zW~$6jsDp&pl6v;*Rbk;mxjT>@&q=V8CCnj5wW1scZLCJZYe`)`VO6+hXmXHXCrg+^ zj)O%x4w{36*OKzzWVP)e!A_Pi$9UQQb|{YrNq8+O{|#7kkYFcEm_v?gML7;u>H9&# zYe}8^>5pNzUUnC(8Q=33jrCIo9g@pEao@yq46sx=rJfUz39bJ6XaU-^u)-90%?F zAmO#7rc7@VZ>*JGD-!Hv33L1+``?K2c#wqGl3HV*CUL(ll7j?0S;8FK$^JK?JRT(B zwWJ>TqH)}RkK`c1PL?po`?CLCSso9P@LE#;n9w*re{6D)U?)qMW0hQwSydhnlJHtm zD-LTMXI-2eB-qIk=6F^1zcb3?K@wg|>a#|&9SQv?i5=*OJ=h>uus?TNKOtAPIJ|ggGvi@nFMtrSTvMuO+qN zH`~MwyCw$-cCv&yM#=v7=98s0sU*CX)H&-kj$=k82MKnvggNHQ{x`ThKS;uBNxj&* zaqRYRa*$vrOPGVBI}%XlxN<8PlQ2MKnvggKVT{x`Hd9wgzlq+Y+LacodGeS4V% zJ6XaUyUYG}ZFx;939lt}_n(bp_Z^ah1Up&6978cbNWyDLy>VibxVU3-kYFcEm_v?g zK0ippYe}8@Oq2Lgx8xwfPL?o-9Mw9=aj>Z83?#gk)Db&0jm49bg9JNS!W?o`^EIg? zyp~jt>zl@|CnX07cCv&yhLw1#T$-D4ifBS33JF%ZH^oV?X@D|wWPl7 z)hvErl^i74$r9#}qgqjpgXSRNwWRiXvRVADS#pqICrg+^j%r0Y4w{36*OKbBVe>es zkQ^k~$r9#xQLe}AF7p%mxgz1Uq}Dp3dAxXj`ddPRoh)GvIjR-qI9M7-;jx^SRQ=Ji z9d{%L33jrCIpnBTl;fZ|NO&!&U+-uhZyTB%B-qIk=J-@N7PYx37WC?S~QLQM~MXU7vAmO#7TI|z2wmU01 zNU)P7%ppg$q8ta!LBeZEHC@##wm2j?NU)P7%ppg$q8ta!LBeZE9dKK-IKOprkYFcE zm_v?gK0ippYf1Si%*KNx*vS&+_*2G%_mt-cn;+3P9x}D`{W`BDb@7FL;?L)&@7>jNq8-(dDBjdV+SM$33jrCImY8ViX^<2)Qivbj$;NT2MKnvggKha z^_a=!@gNDWCDnTAsd4`3%aVfxJ6XaUlVty!TOJRR@LE#-i&OU5CBaUXFo#}`xwAYTB;mEB z{1>jwL4utuVUF`;Ja|KSy(kHU5J*r7~Evcy^ zdc>o2MMnwb>ihc;>c;~I}Ie*$r9!`NA|z(%JYLHyq46yAN7a_)=uBe zAi++SFo*7cvR4&#J4kpfsg+%O#uNJ{2MKnvggI(WtExJ@JRT(BwWJn((K9Z1JUK|P zlO@bCN%p_}%i}>3UQ24?HNE2gYx;L(K(Lb~%(0#9e>arp2T6D>smHsW8VB#093ibb3;kBerY}GqHe_V2qU?)qM<8j&l=9kBVB)pbXz4cCuyPcjKB-qIk z=9qEVhmVge&kvIDT2c*{oEG=&lN==2$r9#}quLxf4%%x)!fQ#*da6%cdRTIhU?)qM z<7~Me^K5xMNWyDL?Q?bC_|taDL4utuVUD|G|J%Pj9wgzlr1~G)FW$T&?H?rA$r9#} zqgqjpgZ5gH@LE!Xe(V=-yEQpTu#+XsAxE{M90$!o!fQ#jyXf@Txl3}8U?)qM<80ag zZZEGFCE>NCCM-Wawq2h7?vh|9OPHf5``;)zAJu)3gx8X)+NFQ&dr@+bU?)qMLyl@i zIS!hGgx8YV{D}Us!N$o!f}Jd34mqk7$`OX}jr{bPqcl7j?0S;8Dw$o@B>JU>XnYf0Vo+Uaq`Yw6sF1Up&69CB1E>e;1k z2MMnw_0_Sb#~x=S2MKnvggN+)LlRy~>euJ`#RXd?2MKnvggIW9{cnr%c#wqGk~*ki zzj)64bWTlzoh)GvIjYT(Y(Hx!A_PihhC4-*#>ox@LE!5UC|}Z zJ0Uqpu#+Xsq1R({wm}^vyq44sJ9mlij7Sa=>|_aZ==B(#ZBPdZuO+qS!p`yN8|_aZ$h<_A&Nirngx8V^Gdjny+ottbB-qIk=Fs{1_sio!5?)Jc z|DWakI3zhpu#+Xsq4V=H>u%dY!fQ!w)45Ch=8WVZ!A_PihtALIY=gd5B)pbX$Gf}4 zvo1>x66|CNbLjlM&NhgnK*DQDeOUjH*ne_zkYFcEm_z61W!BvsB)pc?i)SAa51E!6 zB-qIk=Fs_hoo&$VAmO#7-uvQ^`0147Ai++SFo(|1>uiHMNO&!&=erylTV9tOB-qIk z=Fs_hoo!GD39lv9d&Z&h;*rTgf}Jd34qdOUvkmGX;kBghuiG_V)H^vyu#+Xsq4V=P z+n^2-UQ6nO6S~GfV{(vSCrg+^=jU~{K^-K#mehz_y2gz*PYx37WC?TV_jh%+K^-K# zmei=XWIL9ozlkK+$r9$!@9*mBGj)*gT2g~nc8$BuP7V_6WC?TV{JgF{QwIsJCAIt7 zhsC`|CI<<2vV=MG+km?IOdTY=mQ=Sj4vPNT2fDZduZ%^Msko~Crg+^ z=jV0xnZ8yeyq1)Y!fZT9f}Jd34$k&19rSkSxXDSjUd(Gr-TvZR;fB{vEUzOY!A_Pi z2WR_8crB@p8@?HyzArgQu#+Xs!P!0%UQ241!(R`N&P)yx>|_aZaJG+x*OFRwk~AzZyQIY_XRCCtIuJ`!F_YOjNy z4-enhy}TVH*vS&+;A|fWuO;=_V{=2di%uy!NU)P7%)!|{5?)KH%{gvV=J}+egA{N%fuZV(8bo zciBOLoh)Gv&JU9CT2iln`%>8b-Q*y_PL?nSXZuKaEve1Uc_myKPAhK*33jrCIXK%# z!fQz#*W|UZ*O=rW!A_Pi2WR_8crB^NK6pKBd{=UiU?)qMgR^}kyq45!*S{IIn4TOY z*vS&+;A|fWuO+qKA@jodXC(&-cCv&yINL|UYe_Z!`t5Li^W-4GPL?nSXZuKaEveys z=ZD1)q|Yu1cCv&ywFNltxD$% zB-qIk=HP4}39lvf;c4%O$!DZ<9}?_j33G6^kA&BfI{Sk6!WlEtIUEUgvV=J}+egA{ zNliTZ-O#Uga*$vrOPGVReI&e=)Gn*u3AbFB&Z$YTlO@c-**+3pOUg%KtIZFxlO;+H znIF`<73!F?LBeZE&HDNDc+aHdAi++SFo)jHN$*yu4ia8V>e+Fp$L_Z# z2MKnvggNwnPI|XOb&&8{QY~7a9@l#$IY_XRCCs7sbJDvNs)K~rlKS|KesTS`lY<01 zS;8E8KPSCgp*l!-EvW~q`^B+8B?k$1vV=MGeolI~LUoYvT2dQ#=od#cnO;6mB*9LW zFo(|e>D>y|LBeZEty@R7qib@IU?)qMLudQ+ZiS+#CgHWDwp`jb9({3gkYFcEm_zUH zt9L6@2MMnw)$RShvCAXLL4utuVGg~&uimXt9VEP#)b1bkjcyQe1Up&69D09Wy<4F=NO&!&6`S>oTOFAkB-qIk=Ft25>fH*} zLBeZEecQEPeDb2?Ai++SFo)dNuuAV%s16cdOKRoBe({~Vl7j?0S;8E8e_y>@p*l!- zEveU+_lqrFP7V_6WC?TV{eAUrh3X*TwWNMHNdC5eksKu0$r9$!`}^wM3dK<%;kBeL zf8g{u^@rpj!A_Pihu+^;?^dV|5?)Jc#OD3u#lI&933jrCIrRR%I@_QQ5?)K{(oy~6 z-+oID66|CNbLjnj^=^ggAmO#7&icB4Jo($?Ai++SFo)jXSMOG+4ia8VYLmkT#MvJw z2MKnvggNy7zIwMpb&&8{QYYR!AU^z5a*$vrOPE9N@2ht!R0j#KC3V?v1LAHsCkF|3 zvV=MG{=Ry*LUoYvT2k9p4U7j2O%4+5WC?TVY@gn(P#q+^meg)T2FBg?PYx37WC?TV zY@gn}UL7R7mQ>>j17qKfl7j?0S;8E8e_y?Oy*fyEEvYZ24~#=TPRA$`>|_aZ=-pxT z?)B;*;kBe{O&u7Q-;o?7*vS&+(EI!9-Rsps!fQ$0ICfw>^UUNR!A_Pihu+^;?_RGC z5?)KHORs@(dPoiu>|_aZ=>2{5?)B;*;kBd=YCSOixp8ukU?)qMLyl@iy?ebnNO&!& zj*AAwWy{mKC<%75ggNy7zIyk1b&&8{QvI(U5GTKs93+D z1Up&699;cL!fQ#5|8+?0SvNUIu#+Xs!PTE6yq47T@k8Qf4U>ZeJ6XaUT>VMHYe}u$ zW=JfyOb!z4WC?R{^(P6hCH2_6!SSh%$w7jhEMX3={v_eGq^`PnaNM_Fa*$vrOPGVJ zKS_8ksqgj~9Cw@> zaf2U|g9JNS!W>-vNy2MM?f%iAxK69|eFGBgWC?TV^_a9?l!Vuk+W6B!@rv%rL4utu zVGgeTB;mEB&R;nwu6=ECkYFcEn1ic7Nq8-(SGF7+=gmzH66|CNb8z)139lvf`VoWU z@Ri9yf}Jd34zB(r;kBgZO&%Qou~qu63<-9!ggLnSlZ4ljx_`ys_|e|UL4utuVGgeT zB;mEB-tIgk_UM)zB-qIk=HTj25?)KH?}J0)F@2JQ1Up&699;cL!fQ!&+v?2NZcuWN zU?)qMgR4JDcrB^km!2748JHX-*vS&+;Ob8jUQ6nzZ_bPjdnE@6cCv&yxcZZX*OFR! z#L##~*W@6Q540ORCSGL*rK)CI<<2vV=Lf z`jdp$lByMl#XlCOza=Et$r9$!(Op_EO2TVNZ8U6HTs}KFNU)P7%%P*Zv|f~i*OL0< zx?!=&CCNd8oh)GvuKpz9wWOZ8eOPSSH91JIlO@cd*JILpQ4(HDYSHvzaoQHiL4utu zVGgeTB;mEB&b@M2Y_&L@Gmu~>OPGVJKS_8ksaB^Ai^tDO4ifBS33G7uCkd}5wOyNG zarWrsAi++SFb7wElJHtmExsHYr=FA?B-qIk=HTj25?)K{;0Z(H;d>_s33jrCIk@_h zgx9(q7{e6`B-qIk=Ft65&n|V$x$k2=VzXcS+I4lWC3XK%J>s4+cTie?MS`6yVGdod zt!J0&AmO#7o?L!P9P(mvkYFcEm_zqJJ-bu~39ltJqxzKC^_Aox!A_PihpyMwvrBc5 z@LEz&H#{Xix-dCNu#+Xsq3gBv>{1;hyp~k6S>0pp_4}3I4-)KT33KRrZ9ThG2MMnw z^}#XSW4(|ZB-qIk=6GMO$LQImI!JgesR!2U9yc7593}LBeZE9eK*hal-oj%iBSMoh)Gv{r;|=UFvp_@LE#4^g20C zADSE_*vS&+(C_c+*`+#2crB?L&ptVh|2R2Fu#+Xsq2J%tvrBc5@LE#Kr<@#j4g<=s z6$y5-ggK6s{ZG#>)j`5*Nv(MAEvccydc;T0O%4+5WC?TV_jmQ| zQXM3`mej`Y_lSLuOb!z4WC?TV_jmQ|QXM3`meldP^^Co@N)8h2WC?S~QO)l!O2TVN zjULrA_IM}lgCy9=66VnF@5)sc+YS<5ORB~5J>!^*l7j?0S;8Fp{arn~)YpoH*OJ=# zm!9#IX30TkYFcEm_xt6tFsO2AmO#7I(^kMhOLr=1Up&69CB3i`-_tBT2cqh>KRu(na<%z zu#+Xsq2J%t*#_MX5?)JczX3httAmn*1Up&69QyrToo!GD39lv9ck`aH&5p@If}Jd3 z4!s_uvkmGX;kBfE6lUv1NwAY8%%Su1X*_t};JxFS$9J~9VEP#)D`{O#pC-X2MKnvggJD6URR%~ zgM`*_Ogknmbkn-|;0Q@%_N66|CNbLjlMu0B%-39lt} z&UtNPyY^kmpIs8{WC?TV{JgF{QwIsJB{lFM*^bG{L4utuVGdodt*g&OQBA^YNsat_ z+xXL;$w7jhEMX2^udS=k)Iq{)NzG~4Hh$6fkn(Fqf}Jd34!s_utIyOy!fQ$0utnSW z{oBbwf}Jd34qdOUtIyOy!fQ#bvs2sn`QC??w}S*bS;8E;URzh6se^>qk~*qe+c#Eve(@w~aq^?pl7W zNU)P7%%SVGb@iD#NO&!&JzBPl6UHS633jrCIdr{t8V{22T2d#BX&0wFog5_C$r9#} zqneKgNq8-(Z@+FAulOQ4NU)P7%%SVGb@iFNRs|AXOX|~Z?PFKDXGZB*OM;y&VGdod zt*g(}LBeZEt$4b99P({)kYFcEm_yfV>*_OgknmbkAGg{&uK!VTkYFcEm_yfV>*_Og zknmbk=Z)Jt{%clpkYFcEm_yfV>*_Ogknmbk&n??KK73wskYFcEm_yfV>*_Ogknmbk z-?Z%zXYQUHB-qIk=Fs)py828VB)pc?mFIVe?=4J!OGvPjCCs7gwRQEGI!JgesmcHB z5FflaIY_XRCCs7gwe{Ob>LB5@q(;BhA#U9$IY_XRCCs7gwe{Ob>LB5@qz?Y9Lu@lE z9ivFFlO@cd*JJeCNa`TrwWJ1o+95VRC^<;5lO@cd>$UaUNa`TrwWQX1sYBd(K{{t3 z!A_PihpyMwZzHLLgx8XqHLXJ&e_nEsU?)qML)UBTw~^FA!fQ$WvtNhUsY!B>U?)qM zLyl@i{Wg+1NO&!&`q9oYK66VnL+WKuIb&&8{QuAKlJ6?EYa*$vrOPE8~ zYp3xb39ofKFor7>NU)P7%)!~dt-5UxuRUgeI~I8@sY}1D7w_7m^#3b=e~_IlVGhpr zk?>kllP;|nzt}c8NU)P7%)!|{5?)K{@~!H{r?*cI66|CNb8xnggx8X~VP@Ufx+*zH zu#+Xs!P!0%UQ6n?L+i%#dM5`7cCv&yINL|UYe~&qStnk2b8?ViCrg-vvwbAImeiPA z>%@_Zl7j?0S;8Eg?IYo}q?VpiC!VlZ$MX3V33jrCIXK%#!fQ!=vZHLr#N;5sPL?nS zXZuKaEvawo)`^?_o*X3D$r9$^Y##})CAGuvwPUT*4k*7?B-qIk=HP4}39ltpr%)$u z@>X(?U?)qMgR^}kyq46kP3pw8+Z|Zm4ifBS33G6^kA&BfdbWL?IQ{12Ai++SFb8M* zNO&!&=ZDsbU#&_G66|CNb8xnggx8XK>9IPoVW)%2uN4V)vV=J}+egA{N!?bzZhYv9 zW?1v<1e42za=Et$r9$^Y##})B~|;n`f*-$a*$vrOPGVReI&e= z)Q_|4#|~R22MKnvggH3dN5X4KJ^Fn8*mXuaMv-7AOPGVReI&e=)W^@(kD+67kYFcE zn1i!@B)pc?kO%6=!#_^v3?$ge66WA+9|^A|)oe`tIP>h}Ai++SFb8M*NO&!&#$D^j z(;FoR33jrCIXK%#!fQ!wy?*^z^;$X?CBaUXFb8M*NO&!&_|OJ%>e%EU!A_Pi2WR_8 zcr7U(g{?L}$WE3phtALI*`z66VnP zdD*MXLBeZE9dOpuVeZuAAi++SFo(|1>)EAl2MMnwwf&T*!t`5{g9JNS!W=q3uV)E9`NO&!&y6Zj}PF$EAB-qIk=HRyhNq8-(^STy8 z_szSN&l5?olO@cd^YeOksoO!qYe}{E=bX^9dvcIqCrg+^=jZk8QXM3`mekUgb3%t% z$w7jhEMX449;0WM>LB5@q~3h?iO_4KW6G};33jrCIdpzr&n`t#O~PwQt*U+^tQwvi zB-qIk=Fs)pdUmM}5?)K{j8mQnOBN;v33jrCIdry9&o0$L!fQ#jI_-(@W9MVbuN4V) zvV=Kwy|$iRs)K~rlKS)NC&HqKl7j?0S;8E;UR%#D)j`5*N!`5Qi7;yOFNU)P7%)xI1lJHtmcYiV`{QPWkkYFcEm_yfV%T*TJ z4ia8V>g3VIFmc`E%dZs)cCv&ybiKBoUFvH^!fQ$08=nl*+9n4HcCv&ybiKBoU5cYX z!fQ#*ulH0KcS3TIU?)qML)UA|RTguQ@LEzc7d{n^=${-U*vS&+(DmAScB$Jz!fQ#r zIs54_tZ#CVU?)qML)UBT*`+#2crB?1E_)`_IWjp&u#+Xsq3gBv>{1;hyq470U7rn) zw@wZc>|_aZ@Y{eSyq44j>pmC$wKDA=B-qIk=Fs)pdUmPXLBeZEy?w`Xa)0XNAi++S zFo&+!*0W1>knmbk4R)9tK0G!#NU)P7%%Su1dOoTS5?)Jc`)lTghki|ecS*35CCs7g zwRL_%9VEP#)Ee*34clCo93ql3KdQrQw9- z$w7jhEMX3vpVzZXb&&8{QZIKO9onu)4ifBS33KTDyskb|2MMnw_0^S^gj?4ty@rJX z33jrCIdpzrSD&eagx8X~|M^kj`X95I*vS&+ z(D`{?eWnf)UQ6ovK^KQ#?n(|4>|_aZ=={8{K2rw?uO)Ta@{!@~-;;v`J6XaUI=a)< zXX+r~wWJ1LGBW&f{Q2emg9JNS!W=rf)7599s3zgHq$Y)t;i{*Sg9JNS!W_C@TUVc{ zgM`ym>6J6XaUx?WpXpQ(d{ z*OHog_{ebHpUFXjoh)GvU9YXH&(uM}Yf0@hb!6DG=Y{3hiUd1Z!W_C@TUVc{gM`e%4o&~r|5kYFcEm_yd7`Ta#ncrB^Uw_F?!Shu>o9VFPv66VnL+PeBow}XV&l3L?{ zQDNeC$w7jhEMX2^udS=k)Iq{)Np)H4lCX754ifBS33KRrZC!mPjsgjVl7j?0S;8E;UR%#D)j`5*Nev!xX&8NMa*$vr zOPE8~YwPMWb&&8{Qe8WZ32z>f93$UaUNa`TrwWMwwJvO{FHJvk%U?)qML)UBTw~^FA!fQ$WzUSD` zszY*+U?)qML)UBTw~^FA!fQ$W^!(-Fv(M5w90_)^ggNA>=JyvR;kBf`+3WH!dwg<` zU?)qML)UBTw~=%^NO&!&cH=J#n|DnP66|CNbLe_){Wg+1NO&zNABEX?kOVtf!W^9K z>oH|mc>RWJ?cBg?No`PjXn61P(*LiVA7m#>n1i!@B)pc?(LIKQA4et!33jrCIXK%# z!fQ!w@$jH<>Zs%(!A_Pi2WR_8crB?DH##G1F)lesu#+Xs!P!0%UQ24>#RJ0A(~^S( zJ6XaUob4mwwWOZhw10SJPI8c7Crg-vvwbAImej`c`-S~KOAZq3WC?R{wvU9@lA82# z->^&F>&oZ5B-qIk=Frhynja+LwWRv~*(dDZE;&fBlO@cdqq{UeNWyDL{cCuiu;IYu zAi++SFb8M*NO&!&+y7smu{rZG)?|_aZaJG+x*OD4NvVZvWq2wUJPL?nSXZuKaEvapO z9S}}^Jvm6QlO@c-**+3pOX|$4&j`maNDdP0WC?R{wvU9@lGcNs82mzV zkYFcEn1i!@B)pc?GoyxwLH8yH33jrCIXK%#!fQzldTvBmF(x@ku#+Xs!P!0%UQ24( z>t}~GPEHOI>|_aZ=;$uZ50da&Qd``3PFT?AP7V_6WC?R{wvU9@k{UYd?C`HY(s?2Y zcCv&yINL|UYe}8fXGFMlesYjtCrg-vvwbAImejAC4G%{?lpG}3$r9$^Y##})CFP^A z)#eA;$r9$!{ZG#>b^x#b0g=8_y{H|H|(VvXdpuq4V>4cBu{$ zUQ6ohZEp-a-<2FB*vS&+(EU%(F4aN8Ye~J{^@cFz?&KiBPL?o-&d=-Fr8-D>EvauW zm>iCJC^<;5lO@cd^YeOksSXleOKRrqN#XYwl7j?0S;8C@-v-2EIW4KCYfK7%e32X^ z*vS&+;I{!ucrB?{x?dlv*SoiT-cEv@EMX3vpO?MLUMmt_OX|uGCx!vLBnJt0vV=Kw zeqPTm_5C2>wWNj*n;5E3Ne&Y1WC?TVdTl+s6h$=&uO)T!&J)AI6Ow}jJ6XaUx?WqZ zvY3N}*OJeY7$r9$!_1b!NsoO!qYe~J?aAJ7zkK`c1PL?o-uGiMHOLdU& zT2i;gi6QKIU-@%If}Jd34qdOUXP4?A;kBgpyLw{S@YLiW!A_Pi$B{BWsArezAmO#7 zI<0Yim^D5*NU)P7%%SVG_3Tm|B)pbX*KyZ}mmW|_aZ==B&qyHp1WuO)T(_mjdcKO_eUcCv&y^m>e*U5cYX!fQ#LKWB2dw$}aS z&lL%FvV=Kwy|$iRs)K~rk~(($4PnFv$w7jhEMX449;0WM>LB5@q=xsoF|1!NIY_XR zCCs7gwe{>$9VEP#)KP733P-M)93Y6of4)?A|?>Px}vV=MK zZ9o!UORD)JH-~%PN)8h2WC?Td+khmzmee`N+!D5bAUQ~|lO@cd>$T-7i@jDPyq47L zk8cU>FG&s(>|_aZ=z48EAJzARgx8XKecvfz`=gVC1Up&69J*dx=O@%b!fQ$0dFhmJ zQnTbB!A_PihpyL_t1RXq;kBf8x?@T>ZACgpkzglFm_yfV>uiH=2MMnwHEimX@aZGT zL4utuVGdodt+Ng4AmO#7rk*t=^cj^LB-qIk=Fs)pI@_QQ5?)Jc&F!Xy>km&366|CN zbI4K6?=MQiYf1e!`d2*0oCrg+^*K6x+gKh^2uO;>4_P2yjeoN=OB-qIk=Fs)p zI@_QQ5?)JcpOH6*aUUiJ33jrCIrMsr&Nirngx8YtQP^tVA7m#>n4_)ie^blj!P`Es zA3wcqvK{ZdmQ=U4_2UhfmHvOBK!TktVUDk5z39i~@gNDWCH2x}8^qz~B?k$1vV=K4 zI`BW^K@wg|>V$Xe#Sbq?4ifBS33Cj@dQlQyOKQY+_2SH{l7j?0S;8E<%XsjX@_3Mh z*OEG8WZgJyMsko~Crg;)5}BVrzPw(Pgx8YlysS=ax*$17u#+XsQ7!x5N9FaRB)pc? z{k`hMu3O$vKEEQtPL?o7bJ_o%DUSz9crB^hf2bXIIwd(su#+Xsq4V==mDh`s@LE#i zr__$OKad&qWC?TV{wI5to-1Up&698b&s*P=WgB;mEBc57HS-nQ+{ z<@bXGJ6XaU`^f$`p*$WW;kBe1&8i#Q9F`m;*vS&+SR~`Y2g>6?5?)KH|B3bD&;iLo zf}Jd34mqlIkiE*z+evsWsa5qhh!f9A4ifBS33JF%&Buczyq45yPi_!*8<89&*vS&+ z_*BM&H$T-LXbuuy zOX{&U8^x!;OUDlq>|_aZ=>8|iL35DsT2gCv+9;kkIXOtMlO@cd*JI>3XyZW=UQ4Ro z{u{;pLUNE`Crg+^j%r0Y4tCJ70ST`qHMYq{@vWulyo3ZhS;8E;|LNJKI!Jgesagvf z#MiD%4ifBS33Hq(``=mR^`a!amejo?8^p&uB?k$1vV=M0s8*EYV3lqM39lt}SltG3 z#k$Esf}Jd34mqk7UYAos)wEJ6XaUy8r3frM^}qyq46KOLvGr9F`m;*vS&+kn_+gJ-bu~39lvfbJrc> zwCdy_!A_Pi$5`3_=9R~TB)pc?@h`WIZ#FBGlzSTK7NU)P7%<;bLf1}FdK@wg|s?m3?qi2`; zT9NQtQVY)CA+~rvIY_XRCCu@o?0=+;THaSSJlO@d2UiQB!^~RUqa}w-i33KTFr)QV)S`|omEvegvwuzf{1;h zyq478{=QS3wOMkIU?)qML$Al^*`+#2crB@)-`OdCR4X}1u#+Xsq5GenU8;kG*OFS} zyq)6~i_?2ff}Jd34ml4k>e;0_NO&!&=6~BI_Me>`B-qIk=8&UWQI3P=AmO#7o|?2v ztU50_NU)P7%)!we39lvf(t5kbllDjs66|CNbI4JxD91tln^+*>wWK~dao4zXN&34> zf}Jd34mqk7F>anQztB)pc?l6!WI&n-;HS`zGJ33KT8cXhTww}XV&lG=03uJMS=lY<01S;8E; z|LNJKI!JgesRujm8V}hsIY_XRCCs7MV|2Db9VEP#)GSkX_=yJClP1J6XaUdOb$ZE_FLdcrB@ROLmUS1|_~yYs=$7 z5?)KnM`1P|B*9LWFvpiN9+c~%wjB>|S0`Tc=OuQ$^IB4UF0367`MmW13k4GFWC?TV z{-)j`5*NmW0;ZrrZU=<<0933jrCIrMsr90$!o!fQ#L z*k;{0f3M^q!A_Pi2S;}#yp~k)u3B-eVaY*)oh)Gv-T(CLQeP_)UQ23r+gkC9N0WmD zJ6XaU9Nm%dT2j*&trL%3|I+gNL4utuVGfS&NO&!&E$&+<7EVeI66|CNbLjr3XP5F) zRg>^qQg4l4Cw6=|IY_XRCCnj5H6IU>@LE!nCax3DuRo^zT9IHUOPE9N=Oo8LJ)T#S z@LE!x9$P2=yLWPsU?)qML-#*DyHp1WuO;=`Z|lUB|4I%L>|_aZ=={9SHmHMy*OJ=) zxLUDRt;@=<6$y5-ggH36BjL5AE`Fm{eEY!UAi++SFb79>B)pc?{wJ&(kEu=$66|CN zbNpMzgK}NeUMmt_ORCMPb>nAuCkF|3vV=Kym+|1V@_3Mh*OEGa+IsQt&nE{7cCv&y zbpO+{OL@-=B)pbX?IYHY2fv*hB-qIk=HTd#gx8W9u}6T94!93ay?Z#3_T4g9JNS!Wkl+m5IkhwPplB-qIk=HTd#gx8YVaY@~H^}o~KD-!Hv z33G6CN5X4K#rE~$R#TIM1Up&6930(|@LE!@46PT3bxsZv>|_aZ=>Df?m-@LP;kBeT z9#=26S&8GI6YOLOb8vJ=!fQ!&zPw)id2(`)U?)qML+9t^x~Lw{3naXj)Q!FC#nJmF z2MKnvggJEo)3Zx;knmbk4O`TU7k!h?uSl?yCCnjLIg4^#v`QT$yq44x&)1EEZcPpn z>|_aZaCAq)Yf1GutZtloN^+23Crg-vqdO8_OKQqh}7lY<01S;8Fq%Xsjb@_3Mh z*OKy4n2iTXu#+Xsq3=WKpX#dgZLpuNI@-TKruB@%jbXu~cSNmITK`*J^}_rXvDTt? z*7<48o#Ju(?q~JOy&A`n?;M&TCN(-Y*8k}u>zw|=`SHqaFSUBh|2H&#Dd(cAJJ=!d z?kywY?+;v_AwHh>N@%xN(K^Ro`F3dY#-mohapK2e-xr_A5PM$sXgGJ!#CdhBt=SWEr-T)((r%Tirv)<5=mDEI2ln>;xF zW2=7{ao>u;@uR&<_2ZWhio@?O)s>Dk!q)dTjfAy6bh}#dUr&}k3zfuet?S0VHL>l9+?qDa4QZ>a# zs@XvzjXzg+@UfUmqsi3?zV7K9PE&lJDxVcQB+}X0>JAc2?K`7heCN(9GOsQ>B+}X0 z>JAc2Ege-q&VIlA$;XCNSFuAPot>@jAi-3xNe$w$d*mGKkVt1|t2;d%SqV5-3fzlV_nbANZ!^$UHhbe%zK{*9@8R!r$tgJb3T#s5FS z$0Cug2duswB$(n6uJT!NYt!{BecYP2oE;MB%GB!5iUd>XI@9U|&j5JTf8&V3arnyI zU+Pw;4U5OmD*f%-uFbGGdvvL;`5cZN5-q+Q8mFF=`zuO zG4?B^zT0PT+-X9NU}tf?!ExVb%BdR96X_uF%kn{SgCBDa5=`y>(V)0atK8>`osB;o z6tC!BPW?~Mip2RV2gS9o%{ln2nBphD@*QM{#H(8lj`QZ`93+^kd5_|IJAM3+xLL!} zE6UG8<+Eak#M*6!#A3_b`$3{2^*_D3Bp#nPI6l=e=isZ$6hD=f+tK&IA@P_#rLjS` zt>ELs(6^F$?7MGq?&D+5aiH(L0i_2%{_9zle z{c+u}*yNHN!7*}^W4{awuP$9R_~{=@!t&};UAZ0m-nKAoKIt)g-T%0IVVL?_spd6@ zN`f5{Z@nXrv{vc*L(K$JHDAkMhs2QPpM@`X%Q;9eHDbbN;ffwPqRnH=!l0(5t=<0M zW#N^TrPrs{n6JZ&FXdh)3&-sI zS3Zd(UU_z5XxghpS8fMCyG(H}s3iD&Kkf8Ic>DUl@>-ENbi(Ih{;b@V^VMaF&$jYe zu|s0j_n(Ds@8ujMnBuEm={TwF@=!IW^eRrh_8IQok){JGNpeAi)%!hrdu`u1a2h7GztlR19yFTe#&KM&I`FA@BUQR!fZ#I7%W z9=^RN_qT)uQ+&3Sj^F1m3x#b zUlS6y{<=6U_$ap>B$yic>XOjvtsKGa;B#LzXj$0!s2st^dUC>-Vbq+zvK=J49=tS+ zoR)KNJDB1#tb9M%A#um@rD2T=a}E+r)x71+kLVi@nOeHCb@7FL;?L)o>J`g-#*JHE zl6lWbFm+JFe({|7xoc#6+r#r3RJrBskeE86M?AV)?yQdlQ_pwn5$}I4M?86AkGSjZr8DmnFYggY zPAk=Kk2)cqb-`7cPa-=c_Wh_wJh1ka|Ak=c`>s9XiG6d#qAz;J1&^0H6R+tN_g{0I zJ?>Rsb&q3*Uz2gLL*nsnr^X?&;&=7yJ|vhru~qN*{Bb#=-9@Lz&Rt5+>YC-J$F|E$ zuNB9;mG2-sB&v4lANyWZqH89Y+Wd(AvBAbUf}O@)`o}A#m)>W(Yj%*hxN-m3VUOIW zgpXB``k%(mByM``^f=b~*E?f%NMB60em{o>6la{C9L6;phlDqkyhNDTV1U%c(soPz{Y z+zToloUi4X>^k)qhcRcC=5Z^Dh9iFnum5e9?VYc#`aVqmbf(o$kN!R!e*V3gy_TuV z5C1N7dHlZ-d@K?zCw&tZ+*6_}pA`wFHvMo#`1t-D(XZ3n;na=~+Veg2@h`&}LrUB9 z`t3`?3on-HN(Ue7qZVI>R?q#F?I7{o=;fi&irll}b}+?fTluWmAu+J_vT)XRx$Pjq z6kml(2Vav$Z!HcVv?{Gg;3HKM?2wqd-{Nr3wYl{SB$(QGt;J!jwR4}u-`4yp%pLZK zy@OSEe;u}(RH`{HseD$y9QAXUI<~Y5;hvVO!no~Ab(0pP%N$dU`X5W{4KS(fj?x#P7-H*!=Tv>7Y4@<&>cl@_i z7TmW<9J2M&u=}sMbr~d>s`=Grhs4ZtmW9dtl-`@l*NOyFd}k{OzH4hevMS6emOdFZ zzk}?MczD&S(EG65=ZXYV&wjlsEL@oTlKR)&L5`zz0i#PQ$#5Wa7nb8tJD;%iv>4zfey)O~&mzkHVaB$8l? zdvm4Z?9XO~`+FQ}e;Ll}S`6Jc?`HM3|C|$gb}!YH#9jwIA0EE1yQLOBHaB#;=oG6T zxa|L1KY}BzC;F)+L_v zBdI6Yd#_jzT-~f{RBmY@SQkCMUA9{F?qu^|UG%s(b&G1UzlFu)?is7poH>pC$P-(? zQn|m-<*e^5S9dl{un_ZqS*b3r(d}q8BBI{RrZZuNX3H5N@u7UBW>vGbgX6(5xbngW z>VFHKv}DByiDTtfs<%D%utHr(c-E2?dvRCpRqEB|85s`}pBz}Fp6Y5F4~`&J;WLr5owIUKwzcZ>b9(le zeZ>fg(JyaOr{A@$4-!_vdvvyGk7iGYBoI>A(1QFSE|JUeI*JfsNz-IB)D>}y}m*nUaDKpm1Yu* zkeIfAg&J1SHg`!-H79YU+S1ELa6C8$cfYYtExl}8=ZugDA9E5^@tMJFIU^)0KeB#tHTP>wX^tG1Rngk;xCN=&+b_sLBt~`JpxV#1jRy&;*du0EjF9L&aii*-V4Ec*sA9jF z9vs19S=Op|Ue+tM;(&E3TT9!jWrPG@otqxK3z~Pw^R8)=V1xwkNe?HenkBbOjp4R$ z;us1}rmfYzP ztcyh6B86q|d|Nw6P!-+|Mo5%iTtM~@w0V%AihXFdoPEU%A1+i%wl}bSyTk~ITN~Xa zV=vpjHy}aPh1R7d_E{Uj-;D9MWS_TpcY!K3$uj1QkjVW>X}P!7#B>O%PWLS%M+&`R zAs9LKeHl4(Sl^RKZ?kt9AyM(`GP2O!;V=3-ND@@B-%JliNYs9;jLdk^_I(rys=~*E zzwP7LWWKMs3@B(D4@O8d=~G&6`EaVGq z4yjuDEenx)(tKO|E zJu4Earz1prFe|E3&pL=E8jg4OVK_Y3pK+->@O!G%o${lJ)cw1?2;%BP3FH zG><0e?(L`lmbQ4F59wewr-S{q@ZYl{k$Rp&v}#R!Sio${kSNKh3%OE?o#cYOEiWliB( zkx1Rk{ok{qD*Q^#2#GP*ca@L!AVF2?&g{_yukE}(rtVc9O)x^DUY%Pc>9FnDfCN>k zd!R>qFhb(zNw><=kK3NrNKlo!mwU7aBP2Ft$}f%j*gQy3mAWT=vZKHv^WAJ7 zB&Z4>K}JY)+*MediZ%}tRB`s0v;FTHIpm4m`juCf1KCC8)~^!_UOTO3HnVv!LSp6F z>@uYG1k39Z5>&n4J%_w*y&vw+r`!{=rs!9~i>Kt0R&)N(ub0nVW;^&y&(}em$0orD ziEs}RRGoR~W~uz@o0gU{LV|5Fv*Is3`O8`UGSnm(A;Dj`h7(k6FS%9SP}}xCiV+g~ zZpbN_KeoLq;%5N-l!EW>&8!$9!5uxq393eScty26razf92}btJep`({roWG%w@ENU zg5QgT6I6wNmca;#@b6eiP{nVs&8)ab3VZi*Y%}%yeA_1zjF8CDxt+SUz_HAB5>&ms zvA!Df+fWO^2#Jd~^;WmOpB_Qg@imXCc4cj!m-JZMPn{m6pS@0O>#s7k(&gz5#;Wym zCtI>=-?5*XvrAubt`z92o?fcUm(Da**J|3{rB2@5Nmb6JuK+!Mh*!_<)bGh}+0|Lq zKB#GPJQyJ{ztAIU%K+PoB0*K;_O5EpN}ETg!zpU(5#8D{qkE}>dvtmG<9(ExV|!oA z2#Hzw`>2!+nl{@(f~xS|WrW1)VSQEdhc*uqRB>d@tT=)kwVuQJt1tex^%Y03UMRM}?R2u6xN+EI<)osq0atef0XWzB8tU1mj9 zmIphjU2!&|_~mZu`E5GV>-8S0*?wK-Trm5J5fT+1enHhdX7eCH73Z|+!L?m@>Hu}R zqOO;-$0QgbvANWXs?=56c#xoKZ`&7Dg$*`>*N=8HdaG@3r*|#kd?gW^qnFw}#x{3J zP}QVuin=hwMle$7(`5Dhu#99yqU9|;RH5-U4`xNx{-NE}>RC1-PyWtoKvz9#MXGdB z<0ochUXd6%q^sJuG`)F673Z`$OE|XAH+fObouJ2=bHOASA+a*ki|U@1wpl`gs=-ME zRLcrBf~%AL#?@?Q#Rv(mv~Yr|lb36$L3i7pIT;~wXkda`-%)?&V0sLH@l91b|04fc zxN(lb>h>ZZ`Q?O>BUHhqA6TB986nZSLT7bv^84u!RMo2Wthz94wuKlqaGokv<#RuB z>z>K#+UTWznc0T7gM@4!tF8{x?F%QUVw+5Yzry4%1No~>lVF6zu5$a;uHmaJEhj-0 z_wh459_;e4JhW)FU)Q{%6{T|7HGaAOfQs@^sg)KFMo3(oP+I2Pwl*Dts&Na7$cZns zpP3aSBvv0PDB1hkJV;R0{c5Z{|I(M1tQaA2L#0@0`h?Ac1XcVErr8cgNUWWhMY6wP zYdHz3IR2)`#{LbY!K`I|3wIxCAp2(M^5U{j$<38)zZt#ZK!P-$s@Fu)v;=u{oi4xJ z=5d*S+;*QnBP5!3NsuPzHEm|KAXlQi++Jt$@z>ADPfCwL`$Y|9=n(yPlVF5Icsoc? zwZ48sDfgz$gAo$!H#4g&&o+=gak_=KovAP7>*{jr*Bi*0X|~@@FhZiwxcc&ab6a1L zpo+b2X2l4Jdn(nJ9sO(`B&gzCFg-YeKQ>R4YZ5)0Cc#l7(QkU9+)~gs9wexGJX=d? z`jd@dgv7AzZidG{wXAc_(XMq9q(oV*Vvm^ZV1&eb4<|^07B&wOR1L3@ATuV|h}stu zWM%{1!eR;aR~8ed#kg zy{wooiJxK{NY^R05hOtsuVZG*nQx|h8_J36`^a+Lm;@sv@~vqg*=pKaPJ$|~f763w z`+K7V$-h1$^NK`V{{%UD(Kbssuc%Us5@hV1w%+ABNIsV+RhQ{{xo*sMFhZhgmPS%@ zh%GA;R5i)eNIp%l5qy=w*AEMu*OCQGzOt-ZMo1KFTt_}ju#F%Is&3nzAb&k*dnLmN z3HG|#S0t$7oHhwYNQ93d395L-Fg@7sr%onHT!D;?If-}HBubAXw%+BKQ#EB=qHO-m zM%ajAwkulMor{GYwc(D z6(c0rzHovnUNKC95fb5jMS?0`^Gy%-E_>nKLw%&wq<1a7%Ls{65A~DCeYW>eB&e$Y ze4&-R zJH3k^dAdz2nV7w+Uk)c2AyGN0mCWv?X|o+9sG8cpl}y-cBba;Mb*<#Y&*`;;9wcsj zqm|^XrrQ^u6;wS#Y-=Mpf|>75l5NNIe4UanN%jx6&0R+7{nk#@9a_bj%-&^$L>+hcq)T7f z`icZqoH3>cb0>YEe3Ja)?u`?De+eTbj(?aUC+j4qLr_)ZjwIQ#!sfw#AN61xsXk1P z0msQ~2O}i<%xohu6Kx|%f~w)U+DggSZN!LS?WFBaJ^RY6ZzrQ()@8QI%!&~bmHu*T zDy8Xgf~xSoV!pk4x0TOc%t&96$oFGg>GZU%DA<+ z-yiYIorXOsJ+jrd5Ij*QrTKkwWq(ay#nW}nb}&NX(b($JVrGKHg9KFtBh{q!vGj-= z@2e)i)@h zV)J0W0|r);>NVHrdpgV zzF$YUR@R=VDW49s5sZ+ax7iL7RJ}C5rhLA{=D~bVudX3I&uSHE(}NKbd&}39?0ak; zB&Z6{ihcF!OL4OMfL;^q1v4u~NKE-SPCglGTTvva8nHc2iWIdGj688LPAV?Z^OZG) zXGNmhzBnmf*EZW(7gd=z#Yv_8wl(wLd#k1mM!azN099ffKgv6rGaZV6ovr00sN#Gx zJznXPM+QGo-Jd_dCgqcPb>sZ<-#c%V^}}me<`p9(F1(dVa`u11LU3;Z?ux)){hL`a zLgMjTx2e8AJ!bJBK^1?)Z+b97V%5llYDp`xc#xnfyyc9Lc>kLVD)UL*(`HsAsA8|1 zM28N2rT(w|{d{?PVfIX2Wpeo;mUb{gg6C%& zIe{>7PfKf)Q<^`l=g;1IbIQ<3y3Ae&;GP-Q;{Dt*@pN6k7whM}S<3yW%b&z#b$2Ii zWa-@t%VH(2@Z)}D`ZxJyd-X^Ca*j7+Wrw5xZhA06;_tSx^4BjmV$2=6W%b?q_4(V2 zb4i7GUFLc;J(&A%y>6DD7Nyq?wva^CZ*P_#`fJ+sAVC$|WD<;!XjR$ov z75nE(!(1}3eR_SxUL>*jTuvE0&GxQ{1XbbliV+f{=H!$ihix7tsN$S9dzVDcn4EIk z_B#Gd?0s8K$x_`muQ+$VSRX5ii!{MrH$503v3E_ZsK+!NPEeJyFjk)2YrD3~(wk-G zSluUgG`U&+uW5QC$hCboS57H#HNADtz9MnY)f|$wgRLDTsA5l>Enib3r_7$F`+a?{ zoO1G#E_2Zi*mX5QnD7sU%xmzw-6|oVFwD~@ld~_fqS&?X1 zGqi%QQO zFIYT`2-95cg0Ogr025=zeTBc}^=mOGx-W!^brwuAK+KHfTXcU<*l{o77o$&eOEnauQT+JK0&vY_<`7 zPIZ-5XQMM2IjpPPdc{UCLce|myUNh3HiGWw>voY34n_Ngw}Zr(g%&gc~w>9b}%l2lZ9VA+Q*iAlNm0mlj;vGq5R*aAs zeWjaJoo4eOK~>rK?oy|hjbNl|N_VMRTdP=8cvd8eyWj41y2a+fx~MudySt?9wXG;d zvd-)-C*RX5))bxQ(42*Yaf~D-v}Mcasw*^{fnU z2UX#7mk|#Ya3|Mrf-3H3YZ8o*;9j#Pad=O8S$=(YI_?#B|L5hUUgOs+ zuS*yq(QQe2$#-?Ug}9h_kIZsj^&`zTSCDVN)Me6UR*aB%vUvqrl*#77S7cXHDogkG zwMX@%mE=USE}I^#D=u3FxieAMOK+24gv8RVqpTUI2f3hyh9N9UpyWL1oQHOZR7 zvm&wP#R{@L!S-5|by3Cr2u%-0NEH2F1(`YC=0Sq0{V&}kW!BpWMm86^R~DYtD%KR9 z6^R0C?v-=7Z9D0(E~@7Cswf2t+XzN(z3V<%Qb4O%Q+QS+F7CWf_GGnrur8`H4Xh-E zj@bH&k)MNQALg)wOxG} z>F{P1kvFu8HJRhV2#EzBSCK2#Y#t=2I{HBsS$n{?&Uuw-RIie>eoS9+cvUj9VuVEI znfFQIa<=Og399;@sVINmVIvs1DXyY4E0&S0NR%FbuT-gI^I%p~6+V8CoNr_!_!$yE z*WmuLW?wNvg5Kc-RlM?<1S2HE+d+aVKHHfdoIekasv=K~(Q}FO%_JBh@yTOVq=EHZ zOA=JEO{NDUB$^(tEHzHrMvw$meBL!Zc;`U5@`dH|nCQC*OoE>}li)pt;RIFu9Nr`t zA+b5BxD46Z(DF)#1XX-JXL>L~;+MB>mP1)uSUgBj#n*GD2O}hgUH)60y}zTyg9KIF z@!#}dgar4%4=1SFF!M)MbY7ArD@I6!@2AgCo%nef-!qt5F+zf$ql6Pwt(#F-QcAsR zX$K=D_{%rbg9KHw{}JiZW}d}^5fc0zo9RJf0 zgB~REmK>r6l^Q)$B=Q)u;PxWB$bSp{hy~qdngk;xk{69tpXad6L=sd@9WhpInyIgkrbqP&qgBB~J+{B^ z9Hnv>(PfUTNiafUO^#8j#AQ9l!U?K4LrsGDUVU(^Di^17XZuWo5fT^Hk5LB?+U70^ zs@Oi$gAo#EA0DHYO|W^8po+b2dhpyOo>#>al}v&W5|W7TiHY#>TSCe3bMEH)2B&Z7CQ+9omwz6RDIKSV&YSC7z-2aMS=3NA4R*aC?F|4`t8D#tX ziUd{sY{2wjgv8O$>d9TVPqNGs5>)Y1L(_v15}V(tE(;b+wRn)Aif7E29*mHvv$wLm z_uF)f2MMZp#*FE~2#Jm#Rgg9h+P=XeLDhddLxDuhtn!jP#pYqu1r^V_Fxz27K(twx zPtGLU-Vc(XYW0Xe)RQmS-rX@mg6GtmS&^VB|B&-)+pV^DcZ`q-KlA>N#CFo6lm2Au z@S%3Hf4MGm=9^hDLgKaGTFY4L4*Vpj;>w^SUocX2)BP24{eo&Slw#{79WREWG>r z5FxQV`+YL(4VwoEsyOpa4@OAbac=?1(s_ZU9VDpY%r`w4AyKhyR#}?Kwr>;(s>V#b zq~7RdBN!pE=F}y1;DC+bPM)t!EH3MxUFo;>bfe<3WT-Bi?O^0!QJ45ct5}msFhb(O zm0~jCu+4)6Rh3T_lhK7DmhpJ%o{|!2^_3rK`&LOwY^lrK4b{ww5fV>kDkX0}rD>Dc zSfRKy{ZzY?9&lrE88yt76(c0rKGTB)Re8=7lRSww4@O9Y_Z8dmjr$qnjpe&A(P$THj+MO4KPOiTU(w7aG^HW1JD@I66>swO#{k6g} zOGr>PK37ROdf7%W-)~!#kRy*}WL}YY{_7I5r-`lQ>?^7`r_GjUeyX$#-K9q@c0_4O zeovRfKS^bT#O3!&%iLbJc}0S%$g7iY{aAyczvWCTfMdZdIrTF7=~;0RL1 znQ!(LBP2dMR9tF5VDlhB6|aw`2d^1tlS;`S@fn#VBp&{%l$X4?ox$~;n9s`t?< z)?~JW5fUXYm6AIf*gQy3#TjaPFhZiv+)}cug3W^jRlHW39^5^JyPR;(5tCqq1b;&l zPEf_~RZW5s62@<6fH?6asN(mk0NmG!jF2#XbpymCsN(mk09+47Nbp{YaDpm+uWAyE zkl;DY;RIFuEXyPqA#vc$HPticFv~M1399&6mg&I=37+#6PEf_qvP^;z5o&TUoGBaJF}PsRs1Z=^k9Sp&(jDes0u$Bh!GOuXLEdX`UTljQ-3b@eL{+~ zZKBJ|$0SSN1-fiz#Rv)R0~$_H#dqE&!3YW7107CK#dqE&!3YW7wGd8F#dqE&!3YW7 zgAh(o#dqE&!3YW7gAh(o#dqE&!3YW7gAh(o#dqE&!3YW7gAh(o#dqE&!3YUH2Zs|> z@twCxFhYW_IKv65vW_~XHg5XDa;0X31kckjJxEa1vf4=%zw%3q2O}hQ7CNaO_`^o< zghig!$t$Xv6(b~g3THS$6|bl!!3c@C4x81Je@wHqoCH<8qM9CzkT_EAL)Ct{?UzU- zsNzXPrUxS=7R5|e`@eY4(hi=8Apr!IG{ zw?jSu*e8~(7$NcMXNT0%?`$U`kf7@R;%n5t>nBN=SusN5*;jX{ir?CeSf~vVPNvSF}4@O9A z&p%0R{M+`e%r~vyQqD~}GXCdDs#|4UCT(WL2#LPECn=|m&7;@M8EW5WIx@4*4ApU% zE{D&=jekv5`4;K#oj8xrt$jyjUv2w7iV+fz44J0J|7;@`FPp5cZix0cJ7|h}#(G*B zPhR8IF8u5>Mo2J2vv)~Q#a=fFMo5&*G+F(9$kuWaRB zq278jz1hxnK;p`>>FQi*TVIi&isNs#oDmWi?w+oGxni3oB&Z5sQS6hKR!&j>msNjj z#XdB%VuZxA6W&(+Znk~rMS`ln9jB`7xoyONrqk8k3-w4X+dEy=7_Q6gLo+KzNNlS$ zL*3ojHs-uuow{?Xsx&Y9x?*~;cS&qZd|S0ZrLP)U(vad;J0gTnKhY2;O?q|tlV;tty?yU;I*?ywAia^ZFIle zbj!i(>nI{PztoKcXOy|+;9HI;A~@I3jRYqoy5-;`!zdy+gU5{opWM0S;EbVE!tGh_ z;Y5OybKFRsPS;5#e7Q#id!xFMVD}`q9PDxwMFczWyOCfAGq)V_)O2$Sx|k`#~@oI@J?nuhSlFPE>G;xe-Au-f)Nt^Zpgub1Bm!GB2xS?j7ytiT#J;5v-R)i;CG~*Tb5=uD|X#MsB%d<|w~h@n|l2{dZjsC#XuAoL8QGVC+BR z;bD%~SB#LjvtKSrxgTS0C8#<+ELN8NX!Br%#OVL!lo`qJa5M64A|$A)wJ5jje1Dv! z9gL7@|6ER~Ki%d*f-25@osavkfswK=6ox%6ftRc#yPl9_GN5MJXWE7s?dueD-wn(^i>95e~@_TT(V^OKbr>$s`BkimT|3Z1S9wFNtPSSUswI7tVsNIGFfiE zV0$)TR#Y9y{esl`+D0()zeiq>`zBsj{im!*yf*X&kc~r+P5=;I!4ScK9A_A&Fah_m-2(Y*z*nRArUk^7j!N(dm;EY1&a=MT7fG+^l%z z3)#=}L;tf&g^zK9wRMo5%eaa?`+O&Sls&x*v=Uk|H(18g3wiz;3v0uQ&~M7VM)etAMAm(=6ImF5$U=G8AoDkcK2?or)^_Sf~r|nPpW03(hz=D!TndRM{v)TTMq8Uikj{78XZ>McIlNf zc*G&qcWp-2If*KpepP2bu&qH}8K~kl#_X%aCyuKjvvgfwO+2QCt<>drpFO8;PW;+j zwSLRl+N--xsF*u75#Dk}NE}W+q4GUrYX=Fc-aC0*Wf}~^@mu5066QW+%TZN+`@giq zrJM*`NMg?ABWnL1cz7031XUx-98nE_u@U^#neRnPKh;SZ%+#L&de!?6$IB}CwX8dT zYVBz&kLP&RAA=TS+RBhwwrA(ym+&qT{HES5hkySu_wIJmbF6-qn(UrUU8t%qM-gsD z-ox$P)Zgc)sW&{Up@Tch#g}vo+1lV70=FhzyZ+aSFhYX;77&h?6$z^NzQiY7wf8XJ zd6D>U?+2;kdqZ8jXW)7CZk8k^Pw1A6N}gHD&uDB9xdpesh&5V zUUz&a<9l5H$B9rCU%9Jvdih@n$ImMD4u032#2Y8ONVSu;bxwDxs=wSt66))#M39y5 z!PW-9)pz}PjWG#ENCf)?u&;a%5>)ZpWqR=2w^Pq{k+waq&%XckxetkVwsw(zThq*4 z*UX7_&onlHGD}S4R{P+*9I4#yt5yRe$+n zzuqmE{!p{`>9U`d+XnC9MCieK!?R*0>mEI#KKMU(FN1&0iuIBxy8Vdysl29jK3+;* zRwSs}_U=)&VWYd_NmR=jd4BmZ)gwi#SW~zMiS9X0s6J(F9;}Nh_PXi82#K{LPO74( zF&-Y~cr7PE)t)k^RQa_wf|1*QKCSjH&??pxo)w95lh3IAAJ{xt7gd~Nrbn;?jXP4o zt}|{q*heFE1l?A94=2J1iI&+es%0P9#)AY^kuw+7mRy)uj&I?5T)E*lwXXMP{`^@y z;Dnm;h%WP8pVp=lnLoRvRz~#d{Gi+=HU4hB&VyeMrMANZ9IqXWkofDFi)!XrP3ziI z3A!^YUNKC95fTlG99Q>Wwt0}Cir2Bg!%Hj@>|f%xFxa!iEwgQUg?sqkMUPiJa5kLQwx??gt ze1o*@po%NaPbVNA%k!OD^-&9d4Zgc^yLx-8E(a%&N3E#jHY?Q815JJ6qO(F>>Z{9F zUid)$Z^4t6XM?+EtWtC4H1;EP`m9##X6kZq7J8J&fiKsoCNH<~iG`!TRym(;=9j-+ zwp#V>q|0VIE>7K|n(WuPSAKGv`eLyz=e=j0`uW-CELqXx;kxV9rysSB@-sb{35kkQL|8CkIxkr@HETITv&b z+<#rly;}q`k;JattJJH_ZCR0^>O=WT&8h|>$m-6ISE_ccoA_hf|KMV^plw6He5~9` z6}LqH-OP#+5>aa~@E}3ecWYLtq+9d~_B{fE5fWVUW>##+z{H4ZT`;;$0pS*$2y-Wq zE8AD9#Q}Yl2nZ)FK~?y*gb@-?Z2d~*{=()#f+}9e%&d4-D_!qvHD*zIS2%i*XmHya z)#v;4vZ89rcWcy;thQOg>maZ5yh@nuV1z{YvjGXJ?tWvPT6+0e%k_#85}AHjr;5D^ z!X0n#;Y7G{T8)UPH?w7A)smS1%Sv@|4X#(dLE3dr)ttnYYD+I0F>U_}HLReHTzh?m zI=ocp&b8tMEMRY)P)4J+)7Zz=itD@EjW?C)~-`kn(Fnu^~^d|a+NN#rvt+A zdw0P1D%YL**^@L>iNo5;EDZ*<7LGNiN@L1 zsf5Y4*-nBgW_#V?dRB~(Xx?|7nt0CUL4qpwy6I73#5$F?W;=f!R2;BQWoy~iFBi+Q zR=xAGE}H}+B>21%PEf`9W)h5$2%qgFsNyQ{Jsj=iMA&k+>A8LD)Pnp;mMa4zB!b>cga)p_DZ)j6TPp9yK*0{36n$B8gPVpP`+s{P#OE$tvd zRd`mxuGwx@!M@&ZIoK6Es^yG4S7NJrcvJ^J6V_z5gAo!127IGlRhkYbsA3y4dLoqAggAo#aJMB_O7Q(|-dk-hVNU>8p)LW(XsIexk_2eGG2#K2- ze6L>WV;gf4R0TWCN3|n3cgcYI0Murf^$FJa&YET zl*h5;9qO^$^gENvmv*Y@gLOGLu{4Tcgv6xAKd8<*Z12376*K8SXt(OI2!z|S-ouIT zPHWy<&3n1E){}b#BP4j&v`@Hd?_m;D1-r&XwVV+W!LBi>gyUPd9wev=_Lhkv7$L#m zeCgU#Jr+;NC9UTCpMQ-Cen0Bgd*-2=rShw9npaU5aw3e7$X_y#yqq}6Bpi>RN3aiz z>k&uF_$m;)1^>eTEXI|-4=N(Hs zQpV<#62I$6@cUYqW-nZK&^8g)Rb*CP`Q`sKP49q+%8JBoRq{&YXIoaRi>lz)xlw(^ z2#J0l<&ocRpJr(}396pCEsspDogQ&1_s#Ow0IllUBDeJFW+T|6!Ec|#de`qO_B)A( z`{Zzcm}2WI5>$k0P4@Oqi&mnI#*DBUz5{!_@-Z6*N&tmf+LDhsAIpp1i zZ=2)cnz^4km$*f?AJ>uUwQrF}m9Cd_!OV&g5;xSlMFvi>WkrH2t`*mZ0jxA$etaJsZI*+{|Kk zNY&ChldSvm%GNh+1S2Fm?kX%!MYJQxiUd{RSusMQUP?hZ-_7Phf-3f*myrK(yuM<~ zc@1WpuIpX7M=(MnI6Wrn6#xmUMink9yO-PMZgAR-Ti5)|C8c>i{o0VUnH3`>GT&ER z1{Ab;kf6$%m22iixEn?7$I8fz7xjHB!TCQ?EoX#8#jnfA!jIfDk^YsS>e%;XvitJ5DYzU$Y&I zkl^PJ0pWNfNP;SUer*zrka+yoZL052k6Bjjg|{+E&i+sMk@vs3pfaC~^UJG79#l(O ziAlI-PGoQSnv#7_q8|zNp?7=qrSUc8^CkN4K~_G&2#K{PYRabr(-4m55$wS4)_dc9 z)#TTj`g_h`pZ%y2yn9v+`TFhzKdS<{YRbrmb@}b-)#RbyANi*pZvEcF^kBWg{{2xN z!MW;gghWd7`{c_0n*VtC2A&5aBnn2VN$X=eLqDB>U^|$5p$BWo%nBeJ&6(qIdUXxy zc{X}%Ob?C$iG59KNa8u$c#xp#?5XN9?vRaO3m=WGE-hy2+}R^RR&K%UD-z>6SC{8H zq2(Utq$Q|gzjRLSj+pIH_AA z4dJ3rgdW}Y#YyqH4Wj%^57tZKiGy)cafznG393eHkCP%r^;IGu{Hz$6@^PGeGE}SR z9T1M!4n|14`cjM~<>Mpi9}2g+5KiR0nn z8+aaEwNy3RRZY$(*a%*0-!4>5&h5}+z-yP^fWU(h5-ajolf#{CBS?a(A$L`iKd+^k zSB}>XM!MInCT*r@6>AF5io}3{)ueh2n+NNniq|pIgKLdz;=iqP5}a>=hg&eOS5$Qx z_Nes8R@;2W@d-vqa96g#!|^$SQ4pAu+XoE19sjYdQo~m6KY@>|Qp4k*C|Vl8M>1ir!wM{fFcA6(b}H zzR*hEo!%v#tf;#2jaHJkS{lMNaw5krw3I=yP5ipPI@v~gZq)sAtzCPmwXUVbgAo!7 zo@px&{%Gr6MrwW8R!UvYhzE&I1=~r*dpnz1`R!mbSqVy!2I?to#uqK~=rq+KIX&&3O34@efnvWSwNcg+=a2k}WIrEUENYJ84_W zHrq)wtJ+T5-;t3uNFv{lZKc!GSc7gx-ouG7(yMn{`Rv7vc#s&LtF4rL9Ui`c=fP_R zRlE}U>0JNEiLe)^JvaLV_w@iA)b(`|_@9B`1E?8S?6C5{!^o zcvEZ1Gs?EkNl?XXO%Fy${M59y&C*O%Luz#2s(A<557k1#@R35_4J%mb@wB zEOVE2QN_JxeGf-FIT7wp%l&I+4u45fy4t?&V}wL-mQ?Ed^T2}yRrS9dAoC{8{HGlO z!3c>{5A~DCeY5`|yk@wR6Cpv>yNCKnsY&lz2u4U;>)KwDH_ZEo2(ltU)$O@bB(cQ@ z{}4e|tzT~-XQsI)oVb1Rc(#_(^rvNh`B0-Ka-sD?lkl1nVT44=xaVb24%@G`NKnNL zy@dRS<9RSbVqIKUsj=6V6$z@MTJF~GJ)Fq;`VFPro4U2T4>gc|Gjw@z*{9^@O3Tfb zJ08)rOM)~xuYYBhG%Z0MU8l=0w|QLVAGfufsv8a@NaLyL5v+^EJ(cRqj((c<8{jv> z%Zdb599fg#9?{%8I=tnKkZ8ZCp$r|O`_1$qK^1%5B$#`jarNc<=DM}v?O=q&ZD;CB z`MS2gB0*J_XB$YLI1rA`&53Y^58Iw7*N%Vc&kXjV*$zfX^qZb2w-mJX6$z@i$G7hh zWX1Wqv3~<;Fe|;e%kd!bQ)~n2I>nY1394$(uP=Q@+lb*c5@f~%-9PWSpQ09Mq05}1 zW?wNvqHEm*DN$C_;RID&n$ZSekgBAh?P66(vD9vPXtBx+wwkeLl^Gm&$bDzzv< z#@=Zo7>VnjAV)9i)^djW?eH7nwSy57zc)&d{OfIfMS?1>8`FdHXT{lu(!NJV<}Qgz zwG(COYqpulxl0x2o0%0OB&Li@l+B-|@o>`4U8=YWd=FRcJ)8)~gZ;*l)ml&P5sZ*1 z*tm{-mSD?@1XZ`~PLRJITxnV7Jdc6rG>|s4VuZxP=Cx$O689AFsA~xcs=~A4=@HEE z;)K#N=eD&L4@O9gTTnz!e6c1Sf~wVr3QG3AHV;Nf+)yc2nm%D87$FgyqZ!p#B&b?D zF^gn>!`2Q)NO0FNa|B6H#XZDKf)Nr?JD7QxxV)g(s~9XUwFIx!VTs;Y5OyXxxZwAFHko zTI6SP>z>K#+UPXv+$Vbc5U-xysqb4kdAXJvboXSR2+pNT_3#Zm4@O7?=isFhj)$Zr zs0vQCOC>bmdd$k-N2P3-6qU*9VSQEdhx+f=#r}WpP9cae!{EeHdN^KIB&h1Kwx2pZ z3LdW7dze|38Qn`2+!LLl)_U@^Eho|GaEjV`1Rfq1MNn1Y;TKfRV>W`h?``{{s<7cr zzuz{OdQp|Ss>@#WUj5#~-H!})^?JRBYPLTk?I2P7ayRw-Hd|I41FA+2>8kcEwGrzk zcT`z(>qyZ@JF4-!b?%&@x&>Y%yml}`;@yWjs%*2-au16lsQRpLN0q0$jbNnXwT`NG z^^9aiV)Eurs&X!y2irl_{6deYEdyTlN7HM9|8TsPGeY8)U7c0!ga2nCBDZ%{YgX#W z{-NE}>RGxRobMjBJ{Td<@|GT|(0H2%391Txnyj85W+NDB(l$k17?P2!NW|vorFM_8 zc`z%g+Rf;#w!NK(aJ$%v1n17XeX=ssi|U@1depem^k8^$k6?tv^G#k>{OU-PJHS9Y}J%D@PT zmp9f|V}8>$>DoO5&x60OZP=@;I)9*Nl%GkkUJ{pMo2lRDzw}R5ZvEcFiIAYmnw3xR z7t(uXzpcg})4!ePFPZ(yeFM*f5fY<2yrSA3)4Sh<6I8KBOo9;-@BZqjrEl53n;=0I z`_1=ow38DFPFQuXSHWqtZkewJ&8!$95uART`fLz*FcO@w`=32X1Sk5YdU&b1KIW@e zs`yIQ6Z;RxBN!pkILBahyLXy-lt*wLq#FrNymiaL3A<4Q`zknR)Kvv1mPQe5ZE(J~ zt73-NTXDVRjF1RU?vC;xK~-=rG6~nriLiyiX~eFIJz{3X2#MenS9p^tzGYqemGu)ZpLjLzXmxjW{fd>ZWQ%PWt;!bD zfA=fD{*U__4iOUE2_+yLFDnvM_3k)ECHy(q@|uCK$bNfuxSErBps(88dW5QW`b7)D zddn{xt2Xo=+8mm6tr^|j;Zbsh29S^iTvEC^4U4!Ue&{|LK5o|4qlzt=Ch-cIE zRTM$h)3ZjX^Uv7`w(!^kBUSU0y0z>PGb=_&tjRG-mAGu{D-u-wzH^kyT}1bE;NcdW z2zzn!Q)AT=we_g6*8{@w2u4UOJ~c+A%(jg=396!IiCe$-a3bu*ep`pDd{1R$1WDA- zJX{qK+jwxysmfGmn3`19M$C9}h#GiJ&$w^y8lql#Q+jF4EcewaE}&gMaaDqe}MJ6!K8uAJ%< zMyrB}x?a{~5{!^I`|udGY(ko>T-0m_Ra`fw2O}gdtRJHe9!%rmcpfCEy87T)RW2^g zEb+5qWa@~qYST=uVol*$kw{)NR(+nsHrrVjRlLso9&Q`FhZEuId}8`gRVQ0Ut_&n< z=N+ort+ZXQcx9l9GgRl}rQ~JB2#NTaLsa2*HV+b1@fzcMxb=GvC&K-RxK9yx@zGjO z?h%ZT_;bvBwRn&Io+_N6Dz3w3_2eJZEYHr2kl?4ErUwbCj+FaQwO>BR;=u?BewJx^ zkf4gMYE6O>64vk49ItmtP{mj0rUxS=T36_-?oEFGpO(Azdk=S~kdY%)!KM0sN~)qh zlW}~&CAe=C$DccsXsu`9c`!nP;}lL%)wkKtYS1&b5oCk}$I0{{K~=G0%hiOU^Z)59 z4|BYBFhYXkWO|UGitl$#f)Ntd_ve0AB&g!&Wxj{2_8#u9OtE7Y$A-K3Xssvr2u4V- z55ozncp8IAFhYWT7*0^d_f#gq2nqIKI6)QPQ<(%KB>3r0I6)QfC@={|NLcS2aJ&&D zLDi^%^HixSpIc^orbkN1qlH%bk!Bl9$dbeQzTnRe6_?r%=)ap;F+zfOr9{#G7oGta0 z@5g(XOo9;-XOl|FAMu(FC#ZTdQz?1-DG-k4+~*HO+P+m%5?f{@D-uuLQ&J+W;Ne-g zK2C(~pz8UrOURxkAY8Tga3YL++oFUVc`PGYk(ht2xU{|p9=<`^tf<=dL2=2O%SPlm zQ%v$C>aneSs+f!}q|4!JkP#9Wt`w6AhtteN$IFTYRR@a}m-V062u4mfDlSWgY87kp z8tp%vv>qg0ndo{vYx7`TRPm~G-N7~RJh;|MUMeMbHqiBQ-IxR;B+5KeTB`T4WkrIj zvi(ZSzS(IA*UX7Yu$fc%3S9pHdZJuO+U3|#k#2C zd^0^5Au-^_;xcNO&4UD0T+OBj?;YaZLcG_=Bp4yVyB5L;s(24VK)40>7ofOrfy9m_ zW7TiH(z~C5D!xMwJRHx15fTd%7OHA{hge<#kf4g64VWH`koZ0GKGi$7-X|cOpo;s5 zn*<{yxTkbDK^6BvHwi{agzryHf-3HyZhCOvDDLac9jHu#5faQWoS^E!nQN+N&S91@ zXM_ZM+Vmhn6?cU;2}Ve8#)K18@v{??V1xu`emFrDKRYoAMo4f4hZ9usvlEkGghbT6 zQ6A=a>zo8tyx-6C;C_9jZ>=m{m+5@~GYzaHg^r}z6VUgl*!2O)(oSEOZi=fY&5G&! zH~XHcD1Y98dpTXT_i#TQL|qqm-Y0vqPVi?Ry|vbpdjumSZoTV1SyDjL;RIE4dsUPI zg>3}$%{=oyDO^tH&i0uejF4zluadNW3@!IC$7=@(s;VEYBqx&75FQkHa8wm}YRq`Q ze~x}oMb;kB<()5!>>gtq4@O8V__&H(srH&>os*!d!<$t^-bh3ESuwJ=MHM-IRI6B% zE7T9iYX>7FHr-T3T0W3oJE-DZNVSNbB_vi&t}O8bZ62(PD$ac0!)=52aCgVY{3)>J zUOAULBXgI;=0f+%!n5gRMb-Y7?vXO%1gehdX9w?R4v_FUbf7!5uDXmQz}dM_cOAhNHjfOS!$fLtq-m!syN@wb}&NX zlgFw^gX^b*hZ9tBZTf_xIrqCFj8xJ8RgjtE^{8>anI4RgSo2~9*`8nWK9o7 zNOUe*K~}}sJV;Q*`DS`>HpFGCAa^F}nZcS&f)Nr=Hm@LyGTG)8396cHt{~rjnP!$a z-fU;&V&XkA%h4*<6rL4{!pHBC^NnmCtcxnnP}74E5~auAD^)7lJV;Q*=Uvl-@6Y*; zm7krN1S2H)OT=)3s>^d8ma4J(&MK2&gam)78BS2u?&E4w=0n?F7L1VKFI-Iz5>(0l zN2E&|?6BcsjyJCuA;CQ^Ob-%Nt(#F-QcBtO{a}Oy_qZ@UNKkd)%cgR2%#43t0l01O z9!})9UN_56i|YE3`gw1bazEvLueokK~>dnZ zjq~ezdvPwQ5U=;08*@i)S$(%Io5cEFIpyS~$9-Z=jhr%jnl5v%*?@2h?l-(|#>x&y ztNv~qD}Vi>%hSKfFWaj>YPQ4i2u4V>D(==)8SQY@-oxFw1^v_F{oFF~^uP3#;}Ps1 z5)EtSmXx#b@D0)uRJHj&mwa>pgj>H4MHt!KEtjl{WF#vRb7OPK(sA(c4bo;s)uu0V zO8$B_;&_{!()?k)U+}0oIc3OUJPCa2uC zy^iHtLV~J$uI7-e9c%b`?rfa5k^Xlij~FvwTd-`dyq(37%NZiP2=Hs9;}P1y=!7cJ(i|-{j3=IVtuS6 zF48L26rL4{3(I09uCSgl;RIEDCNc@mhO@bHN`b4owVXXB!3c@H_vVzLlWcuOf+}8* z0}r?0MEHEi=kWj5S0s4FFg;ioRh!*!9fs^|XjxI*H=idk@bgmBgAo$pCnAubDqqUI zvO6Zt=c0aJF+zf`&V#HRuXjmMRpg<^<*ChSK5zFu7$LE`{?l^TA7dM^2+>E@36Jdlzvb!T`p{is5A$)mSf~wxllBDDbWaW5>N35>#z|r@AayFxApmjF8}I zC8h@ns_N{mEbsj`-QvLr37$7&dXS*1<3|;w&4aTn9*mISc|4{E2}3ojyd+PtdBh+> zg7-|B9wex0vo4>UNw&QoWP}9onKC^{P}TFVOfvJPPb_`K2#GD1{!p{`El!7^D*ur4 zYTK>YMbOc?Igv?kBuVWX^yea6E3f_5TE_OZ-7m@r3C?M=$=6@ex`5o^7@>LV|PJ^dLc1=GqU+^24^7$Os9}Y14xQRi$sMBz^9i zYZ-G!NN`S@9wew*p8Y-<_J+;Fh+uVbPMaPisJi3c0+OZk0!up>A;DE(dXS*1V%w~; zG}BUx2O}gRXD+HOxzZ!38Z+^ddZU+(;BKn*Ds-1?`Sgyh^^>~GY=zxh9o-ry(&toH zX?0fLLpyRNb7qz+Q~hU4RxKb+eJP&l#zCj*mknBl-X>{iY=$=+@#L3a~_BwD@M*Hc9ySR z&PY}yP8aAbcRURbui>tbxu+~uQJ;|o1S2G-o$VwEC2bxgsH(cBlk7N!c@=mt(!|{j zzy4=h#hN^^|8Tr^FhZj6@lMissLg`}RoQZOma&O8f^%u{MR%4=4w+Y8T7FiXaU@o^ zb9d~0%XZx*LDk1wx=PU*HiD7Is&tcE7iAKCQ~-0@$i}wVOCV}is3cde>fh& z2#Gp}yUB@@X*{9`s(2;R2Krz36G&W_rjG3{J$vd=qjx|=d639Dv%8#p&o<_)i>gDj zyGzR6G=yvB?gWiUarf+xPPgba!J5LeB2hJ^yHu@hTT!fws zBp4y_iQ`@w{#>Bm>!If*!yi~$-cwpL4qni+xZ@jc5=V%!?{E}g^lMJnOQMH zf~Wa}6I6wNmca-Ko(5-nkf4g6qnHFEB+8X9ET6|zx4gb0K@~qWG(8w0@k*aOGWY?T z2MMb9DV6EL2#LRU-YDyb*RZsM1XVnX(D!h(lN0ImNs2V>s6UxlJ|I_oy=3Me%#Pl=G~d- z*UNKS%&Zt8!IRU%399%^WD<;!h&mh4!yIq6lb|a6ywpjJe^8xswDMcqf6#8#W05ZN z`?eq}&&K#Bjzopcr<6=>ZW#~OMHRmhFg+L{@ylB`%b_eSEFL7N;xnr0!3c>x+bT+) zxk(le5>&C*O%Fy$RM^u{?s}w$#e)P@oNuNFBP4h}RzNu32$G-Qc`q(g_kQvcWfehYcZRQ60=Wpeo;mX#dO=NJE0TvHN zNU+~b4-$qd?h$FY-R2R42nmkA=|O_3-!m7Lo;zN!w1W{6oX4gI395!&{#%{BzoW&2 z5fWUFrUwbCO4Zw=supNx@nD3+yE%VScgEXxrzAnuzNDYj*9F^}9&UP0ZP4J6V?>8!zUOa!CzejgyVUTpo%>b5WWW^B>3HAK=>XcsN%>5gzv!!34S*j z5WWWqLxnjV5WWZJE(v}&84$h)397i#0>bxTgap6M3<%$Y1Xa9Z1cdLw2#LZE^^#+s zjx^_$??Hm9$wgn3*gs#k5R8y8&pyjsKSz9vZcXC7{DLzdUTgela9Rb+{!VPS-+x>D z>>Cq(B2c-JpzIPnV<;wu9)Zdw0zZ~rIwq$2Pp9H;Slrh0Z~~PZ3Cb?P(<%(YXa`k6 z+4s2d(u%n6Kkw#yFcOqq51yeB69Xb9P`Pzc6_kCCr*9n>H@tcu--D5$?0WD#jhGk^ zF@eghi>jdPdz9@^DK2w~fxZVLLD}`-2^=voAYuZQTNhP9+4uN)m9y^a;CnC=2Q1(4WKdB4AVFXn{+4ndg10utwG+F6+FcOqq4|6~LFoLR}?0XDP>KQq*XqxZANKke? zxPO04Oc+5`Q1(3*p6wLbcyycZ!AMYcJt?JBSG2q;8_PT zF<}H%LD}~xw4y@f^6xc#4@QEr>%r3)+_@V< z+PZhj8pQG(D@rqBC0sft=Hp!XBIDfW5SN%kA}G76tnV#XcQ#D8?qPj5;kpO!AXxT2 zUfobKzV5`@@!psRDmN08T_QL$&@IQrgb`E)W#6N9jR)epY_8&aFcOsAdV`aKeUC7L zs-Wz9e7dSm{M&_!`yPx0Ww+koY+>IcjG!tg`yLm{Hi>V%EQjyGNKkg`4bCj~J;Dg8 zg0k=Nw^TvabpzPKgoD}VQgb`E)W#6O5mG1Gkj9un?FcOsAdV>?MeUC7L zs-Wz9ymeRK_`O|+`yPx0Ww+ko8=OGydxQ~G z1!dpkzBdNPull`<|9s9!P$+`dN` zK~+%pJ)Yj(G`?)!nkDk%FN&AUAmzh!JC--D5$?0Ou#&{77)Ho5K*Mo<-$eUD|8%EWhn zy_WC6NKke?g75L%a!gDZK~+%pJvQ8*C%)ORr+g1ag0fq0X7_CJ;YI6RZ$}tGRZ#Xl z3O)Zv++z>7@jVy`%C1MJVUJ3WZ0;|^+_L++B!r+UDEl5aZ~8he``E6&2O~k*t@rKe z)#RbyAGz)kMo<-$eUD9rC&V3iuD9>ONKke?Qkvft3q zijg3qtB9H8s-T$tN|>=qG2j4W#2f$-5D*m*GXf%M6%j$uRlv07EUp1W2}aDAB`6>u zD2iFv-#Mqd>i6`{nRSdhDf^K_%Cck=M*fU86>I z1YNlIiS_YL|%j@PfGlh(52)c4@8DpQA@@&`d3K>*#Ew7u`%veTs1YNnd zj9mx+^4!WTudw}~l52V0yvoKhsw3#iwPlRh>g*Xm4!PJesN`B+H?Q8YjOqxwa%~y! zm)$vIdBp{mK_%Dny7~T5%czc^E7z8B*ggwpoN{#!%b=2LdEI)uBNaR{vU%t~UezR1b^4EyrRnRSl*xQ)I` zNaR{vEnjRFAJV50Sq2FzE@2sy-@RmJX#0~^Wf>%LEv^OQc8U*AlY2(T z>U)<26_>CKZGY0LEQ3U@#Wk(Z4)OK6DT4$Rm#_?Nf6}TfgG8>yRey)=;-~k@ovdSZ zKS)q<3Cqy-C#}jdNaR{v`MzY!AVI|?EJNF$v?|LWk!x|~JEtv!1QnOC3~hhXstU&{ zZXMfPT{tG07T2)Pwv3Own2r?*DlTCe+Ww?fSq6z*i>uqD`thU#(m5wV#U(65+n=;5 z%OH_!ajh6uFHZk3Wssoa5|*LuPg<2`)F6>-aUJqV-T2-=QX3>e#U(65+n=;5%OH_! zaoyRXPVD*j^jSiJic46Awm)fA_L)c`*Wy~Ze(hNE;q;kEf{II6hPFRxRhB^_*W&tD zn_BUx57K8l2`VmO8QT7&Rapj!T#GCJPRm$r=On1Ogk@;^lUDVto^ukp7T1imo5msS zL4t})ScbMgX;m{cgG8>y^^d-_;`MshuVs*+;u4mj?N3^jWsu0VxPCmgc5FO3 z^?gWCaS6-N_9v}srtSxcT#GCJBFb1jA0()_gk@;^)83_KkjS;TzWKk+;y%}=z9#Bm zGPM0ktFjCdxfa*Q6aNyAJL0DQe;v#O6_>CKZGYOk)cqilYjM4_UW0h_z?4CPic46A zwmv(w4deHHQU(bsE@2tk{OqVu3vpD7?k!x}7cEjB8#IN$3?ql^> zk)YxdmN8k{_}RrVCy88(YrXg9hMgv)3=&ja!ZJRWHr}x~<|L78agF+6ZrHm;${<0- zB`o7=Y2&RAFN`@!%9!(y)rB!9iCl~8)QjeZ@#{Jl_k#o#m#~b}r2P#ojyXx>T3jb=JU3KKN*N@m zxP)bVAnot!;+T^}uEo{q;yIzwktu@&6_>D#`=$LISR8Yb$hEj8zco7y*(ha@pyCpi z@t0cbW=tuLIZ5PNTphQX9R|L0Lh*c%pyCpiQAgU}KZ;{c61f&v)AlchQIDhy5>#Bm zGOl@H>lq&u$DAZ`Ev~}{z7Xb4O&KJpxP)bF-r?gmLyKch61f)FZc}E3JMKssB&fKA zWlWw?Q8u+W<|L78aUC`P`B3-iltF@uOIXGk(*9m9jyXx>T3mHDembbLB%C3L#}G&avik3D2ZH)>yFA9;r0G0g9H_qunf7XmCJR| zGDzfFT=#x9Bm6WwWssoa5|$xXwQ{)*S_X++i|dTxGsA?9PbprbNKkPJ%aE&DnOp}g zgG8>yb$@(5Oly@gNKkPJ%aE&DnOp}ggG8>ywV>{-aP6rng9H_qunf7XmC1F`GDzfF zT#qiE6^`wlGDuKy3CobH+Ou*UvCKxvI^O>!4+j$hEjuSI!R4wn!NysJMh>$W?8oTn8uu zdNeQ0L6XR|xbhv2mO+AwOIXH7(*8P0e^mE_M6Sh^@4>VT5>#BmGW0v2t&b>-2T9~w zT=@=A%OF9;B`ibR-&E<3>VA;OwYc&frD#8|3?#@x}2ViCl~8r(0eRofoAH5>#BmGWyGS za87YNNFvwbTKxN~q0K(&oRgs95|;6Zw7-Lk<3SR+7T3tDUI}aNN*N@mxP)cMRjpjE zgXQ{pMIzVY8ockzVPPwIqQ_W$Uy-2V5|(kcw7>I<<3SR+7T2mBUJBQ*NEsxkxP)cM zRjpjEgZ8;gBG=+N=*W5U{cie9BtgX`EaNt5e}@&vgCue-uEo#H4V|x&XAX?jV?~0B zOIU_n)ym~MX!}7T*Wzk<$=tB<>GCWB%OF9;B`iZ{6y-W-<3SR+7FVO;b3^^M@{9w^ zAVI|?EJNGhb;a=@iCl~8ByugTlN-$s2aQM>B&fKAWyn>nOs<2LK_b`U%D>4vR@*rVDlTCe-P(No z>@~&lAcHcdOk={aS6-dY~M~VjSRc)G}u1- zaxJa_Jw}C!AFnKaCX%4y5|;6JzawT=mKWBflE}5V9$P&sTyT5JAVI|?EaPEme;*d- z2T9~wT(2HGIvmw5Wssoa5|$xXwV84qw6PkAT#M`WiKD}l3$G|1D-u*(!ZKD%`#bXa z!g!EGuEo`S`snb|fRsUkic46Aw!ar!7si7maxJcYkBkogtd%lIP;m*%7%J^=+4F_* zAcz3i8!z)uSFCHrrR9wO`o|5+WL~(wQM6Sj4`+=jw?qw;11QnOCjJ>7(y;>X( zlE}5Vewa5ZELn0{aX&~SJ1QnOCj7k{~4la%d zN#t5wt;dZF4J%Uy2`VmO8S`X3*snMqB#~=zef{2uP~6J!5`xJV+wf;`;J{Yr?6kQU(bsE@2s)VLV78*W!Bh z%;BNcnv_9;ic46=yYhX^t;O*miCl~8t81?gchpShg9H_qu#DkfKT~#EaXd&O*W!9` z-mtK4_mn|`ic44qXZuLxT3kES9~OS>k}^n8aS6-dY#)hSi)&uLq2ZT%QU(bsE@2sR zRV$b4V7c}aN#t5wBUcRx@BW@LNKkPJ%aE&Dxm*Wr97Q76;yVB8A>o%((q|$GDlTCe z9Nm$~wYVmQAz|#SltF@uOIU_n)ym~MX!}7T*W#+*cu2USdAdfCpyCpiAy>6>xenTR zkVLM<_1a&DguhKl86>EmZTF=ddT;u4l2SG6*^4q66@T#IYa{Hw#3$EFMtR9wO`LC*Fno5k!x`s zH*I+M{^XQFf{II6hFsP1np6_G7S{!Xt_j0WN*N@mxP)cMRc(e`2W>w{#U(65*M$FC91oJnwYcuv{pWDqZYhHV6_>D#+ok>OSsV|N$hEj?KJ{~$G4sjd zu_8gmB`jlsw7EP;m*%(C=d=7T1fC$hElgFHTto2`VmO8Tx&Ue9K~e1`@dzSN?@7%OF9;B`jl< zj0X=Yjt5EPT3n}Z{8O0zfczGnWssoa5|%Mp+TW|i@gRv@i|f*bKZN~HP8lSqxP)cs z{JhM%mrGZ4Fo|4?EB~h6SUu+?sJMh>>?Pwtoo&zz61f&v{tZ9NAVI|?EaNh1e-n!1 zK@zzZ*QjH@4IQ49UlX(p5>#BmGES23W4!yWssoa5|*LuPiGtS zSdqxJxVHXyP5AV|ltF@uOISu@84uoF91oJnwYWZMwmLMQlQKw9aS6+~N!s6-;&_lm zuEjNH_^Pnunv_9;ic46=`O^M+6z2y?u=fE5iQ2rVJ8PT*5Nss#dP6&-7T4$hEj0yJTgU zd~l&3Y}dg|P;m*%kgHmmTn8CK{XRx#8+1QNdFXaqzn>NT*5MRy|&IaXauiH&kjS;Te%t1vaNH9qg9H_qune7_*VzWm zAdzcvb)7OGym52NAVI|?EJNq#b+$n>NaR{v^=kDGAB;*FB&fKAW$668&NgTUiCl}T zbC(Ok4?|K02`VmO89G0&vkjU-BG=;D_Q`(X>|rT`1QnOC44t3X*#^xZk!x|CzQuWA z+v`#W2`VmO89F~Nv+kBbBG=+tG_+56VOq){LB%C3L+9spwn6uUM6Sg(bL-w=_KcK4 zf{II6hFsOkb+$n=YLLjaxVBi(E3{jZGDuKy3Cqy=d6{*$3=+8(*Q8f_hJEU!&npsC zT*5Nss#dPE4Z0sBaxJbNfAk3LTBi&WR9wO`bbelE8#IGNuEq7#MLojieNzSrDlTCe zI=a)@2F)OmYjNH6e?7v+x2FseR9wO`^!pf{ZO{x7xfa)shxQ29eULIpP;m*%(D`|t zZO{x7xfa*lNj<_wbyL5D1QnOC44t3X*#^xZk!x{naA41{pe$vOpyCpiq4)3VY=dTy z$hEjOZ_q1T(mQ34pyCpiq4)3V>NCwCk!x}7uNDLB61f&v|Le~S zrz}btB&fKAW$668u0GQY61f&vi-XP&ZNE$zB&fKAW$668u0GQY61f&v&!rcH`O8uU z2`VmO89G0&tIsrpM6SivY-In?@RO85f{II6hR)B+th;59$hEkpH5eE!cqwI&pyCpi zq4V>)`b_tOM6Sh^M`2@iJV=6yOIQYH`_ApuE8e=M@NBbOi>u!cz2cpBq-UOypyCpi z!P!0%xfWOJtImxT9a07fDlTCeob4l#YjNGM>fG3BReC-g2`VmO8Jz7Sk!x|4@6$W> zyeegopyCpi!P!0%xfWN$V|&N?Tc!*WR9wO`babb)4f?(!k!x}7+@W_Ib9;JT9|(@EG;-c+R1_>%IVHuq5Bav%y9oe8)yktRoo+Sw?E@2s* z?IV$EaWy@*XY4pNWssoa5|+W)J`%YW*U&3_#Gfut86>EaJG*`uEo{w@vd>({ZbnwLB%C3 zgR^}kaxJbqck3E29Gx;qP;m*%;A|g>T#Kv2%r0^G>Xbo(ic44qXZuLxT3k~Hb%`f* zPM_^0sJMh>=;$uZ50c2WxaM{45+9tCGDuKy3CrMYABkLx>-p2V#C`Wq*IE)(T*5Lq z+eaeT;yP_qmpEiv${<0-B`kxpeI#-%u0uZQ5|5~r`d1{VxP)bJwvR-v#r0if*LYgb zltF@uOIQYH`$*(kTuZ;`8W%mAGDuKy3CrO8AcGDuKy3CrMYABkLx>+xAV;)%IVHuq5Bav%y9ejPy z_`|L#g9H_qunf-jk;t{U@+fTVzt0a+aS6-N=Q-)q3UzGI^r>6Jy>CBYb6dF<*Ci+3 z7Iu56@OSxjM-Wt8!ZP%EPWKn*2T9~wT+=_jEws5hWssoa5|*LQbJC|3>VA;OwYc6m zWJ=iWgp@&oic46AKF>*?R;U>yaxJdAubC1~Z;~=dP;m*%(C0bn(+V|%M6SiP*WFXX zIcx4O&Owr(;u4l2SGAe?v_j1wk!x}FpE@Nhd@5y-pyCpip-+d=rxj`jiCl|o>cA>{TZaOAqkf7ocmciLR61f)FZ_{rJ>zbwv5>#Bm zGC12uBG=;jVYl1DXTRN7Jm(~+xP)cs^L_Pcg>t9{lgPEW4jyuAxbEYWL4t})ScX2| zSD#j>86+?z5;P;m*%(C7Q=(+YJz zNaR{vYp<9bj(;L$kf7ocmLbnIEYqhIY6gj1i|euJlfv&Wr3?~OT*5N+`M&zJLd_tN zYjHJRZ&LWz7b$}T6_>CKeZH?gtxz&*kjS;TUOV%qFnE*H&Ph;l3Cqyu`^t6DGDzfF zT-SX(G4$CdWssoa5|$xXwQ_x0q3#EXT#M_X0TaXEvr+~LDlTCe`g~t~TA^l;$hEj` z+k0X-YJAEdLB%C3L!a-fPb<_661f)F)>}*r@#U03f{II6hK}y^X@#0WBG=-2yTQcp z^1o6B2`VmO8FE!C*QXU~28mpY>&`eagnd(=fdmzounc{^uRg6%Gf3oGT!&siF>HQz z${<0-B`kxpeI#-%uJ-HQ6rLEDGDuKy3CrMYABkLxtMa;=!Yfaw3=&ja!ZP&vzWVff zJys-gEv}6YoFsEaDT4$Rm#_?dzHfS-42fKe>zMB*h1Ey90qNcGDuKy3Cqyu`^t6DGDzfF zTo?7YC2U$ZWssoa5|*LQ_tmG@>wb{PwYZLN_4jbx`YD416_>CKxvI_3r`Kx+iCl~8 zhV^a@_peFkoCFn@unc{^uRgtAGf3oGTzM2WR>y-RsJMh>aP?>9Q7gibY0ujGC)eV- zd)11t-j#*Fm#!D3;u4m@)t@ACEv}{gR)#H)PZ=brxP)cMs+YW8ltiw@_4|UAp~fyL zg9H_quneyLB#~=zy|?YEaKLxZ6x$#PDlTCe@-1gxFG?cU;yS(6s!%>7Wssoa5|*K} zeQCWYiCl|o+J39T^bsk81QnOC46gnpk!x|y-&FSFxRgPHic44qSAUYowYXY7voiE+ zoH9sIaS6-d=#E6L#kJc}E5mE+o-Uqq5>#BmGB~;;k!x`^d2U5`^0kyff{II623LQQ z$hEloY_%esb6?6JLB%C3gR4JDaP=pNT#IYR zEtZBou1*;wsJMh>aP=pNT#IXA`!B+~H>C^`R9wO`xcZYsuEo`9{O4i8<0*p#6_>CK zuKpyEYjOSj-ICDxgOovnic44qSAUYowYZ+`yCk$*KYd=2pyCpi!PTE6axJbqHdzu* z+&g8EpyCpi!PTE6axJdcW-ktnyQK^gR9wO`bha<87bTHvaUF8!;?QtX${<0-B`ia( zYI(gViCl~8U-vE!Q|G4)5>#BmGPwGaM6Sj4_It7)HB-NY1QnOC46gnpk!x{X&~!=o za=(;8f{II621j=!axJbwFJ+LR;u4m@)t@ACEv_qve-SR4lQKw9aS6-d>Q5567S}yTFAaSbqzn>N zT*5NA`jbSi#WlRyve4PZGHn*Yo4Q48vxm3=&ja!ZNt}lSHn?l}BM?|9!nE6_>CKU9YXZ zOC56_^n8=Jw#oC>ug$f%x^3Px_N!6&d+F~FQgI2((DmBdyVML4xfWN=W1GgI3uYGk z)Fi05gk?M|<3a6RY6gj1i>uyn*^j$Z1_>%IVHvt!TYHz9K_b`U`t|On@y`A!g9H_q zunb+Vt-VXlAdzcv&79seK3JYINKkPJ%h2`O+Pl;Y61f)FlE<6IU23Ha5>#BmGIYJR z_AWJpM6Shk(QQrRL+{Nfo^ujZT*5MRy|%O}%OH_!aqT*&XP#ntTKrm^+FltF@uOIU{9zpK4Vi5N^G*WzmYbCbAB$CN>Wic46A-oGo~vRDR* zT#M`QJDbD>Em8&vDlTCedjGEWE_FXh=>5CeyVML4xfa)$ z#f{_1>!%D7R9wO`^!{D#U1|o2T#M`0iyFs4zdTob?~#BmGUTe3pD#)x*Wy~TqwL3{DT4$Rm#_@Ie^+~# zx*sHREv_Ga+bND)nleaGaS6-N`**c>sTm}4Ev|i5?-WOFo32qLsJMh>=>5CeyVML4 zxfa*v-|Q4OuS^*vsJMh>=>5CeyVML4xfa(Y8}1xO3`-d#sJMh>=>5C$EsJH4$hEj$ zZn1Mb@yV1yf{II6hTgxc{ZZWy61f)FYu$E^zkQxENKkPJ%h3CGb$&uKNaR{vZ``+Y ztY0VfMM+R`3Cqy?cja3a%OH_!aozjJ&hgAWQU(bsE@2sZ|E^pIErUd^#r5WCjpDMy zQU(bsE@2sZ|E|t9=&>S^YjK_ZVx#y;=afN$ic46AejlT=4VpnB*Wx;MkH&H487YGV z6_>CKy?<9{8#IGNuEo{mrpB@I^prt@ic46A-oLA}4VpnB*Wx;6y(aPIV^anRDlTCe zdjGD@HfRQkT#IXMwic46A-oLA}4VpnB*W${fu(3KGBtgX`EQ9002kTVE ztGZ9OK2EO1_2H?N@sC*ed+B(Pic46A&d=-WGu;moxfa);+bZK04O0dQDlTCeIzO+g z&oqNXuEjO%ZP||%PZs-dB&fKAW$668u0GQY61f&vzjc*yzv(H11QnOC44t3X)n}SP zBG=;DZ-b*_+aW1~1QnOC44t3X)n}SPBG=;Tyx!6A$%>Rgf{II6hR)CH>NCwCk!x|S zUR4>(wn-TzsJMh>=={8{KGO^mxfa*oXIIAamOW8C=On1Ogk|Xbyskde3=+8(*W@vk z@ztkN1_>%IVHvt!TUVb+#9$J+7T3gfmGOzODT4$Rm#_?7udS=kG=oI0#r53UPOv!zDT4$Rm#_?7 zudS=kG=oI0#kJKp9b)q%Qw9ktE@2t6PA&f)J&9b4Yv7m;@tsps1_>%IVHq6Vk;t{U z_Sm~ae0NaFAVI|?EQ6yv61f)F`im>#3AdyS5>#BmGIYJRu0E6VQG-OT#ntWBig@VU zltF@uOIU`k*Vff%nn5Dh;yUr%irD%4ltF@uOIU`k*Vff%nn5Dh;_7{5MQpTd`fMjb z#U(65*K6zQGtD58YjNFuP(|G4w3I=Dic46AT-EaL(UZuvxUOzf5vPnx86>E51Adzcv&Fj!9?mi)9kf7ocmLXTQ{Co5yaxJdzk93MdholS=R9wO` zIJzT|YjNdK*w}v`4^nXn%iwtM^!xk7CuiMZedk<@YvgZz;(oUl{$4sBq~a2m!P!0% zxfa*1<$dGf{Zj@BDlTCe@-1hcA0&}$aqV|O-?(49ltF@uOIQYH`$*(kTsx2N8+&e% zGDuKy3CrMYABkLx>xaJG*` zuEllB=)Up73sVLODlTCeob4l#YjJhx);HcBQU(bsE@2s*?IV$EakX#JH~z6@${<0- zB`kxpeI#-%uEUr1i7Qu4E1q)_R9wO`#$bMsM6Siv`}#g{@+&EW1QnOC49@nE$hEi* z+qX~r%Ofd+1QnOC49@nE$hEj0e!X|xaZ1V{LB%C3gR^}kaxJbGy7rE3Zb}&>sJMh> zaJG*`uEq7(Pv^$_CZ!A#R9wO`INL`e*W#Le-MR71J5mM-DlTCeob4l#YjHJeac=ieCH)W8Z;u4m@(H)6gi|f(Bz2fK}Qw9ktE@2s*?IV$E zacx=FD-LRuK1)bYaS6-dY#)hSi)-WBvLBTxg9H_qunf-jk;t{Uwp-CNo-j0Jkf7oc zmciLR61f&v=MQ_v4o{^F5>#BmGC12uBG=;D?~|VK-PI|B1QnOC49@nE$hEj`UE4EO zG){d65>#BmGC12uBG=+tvrVtK{c$OS1QnOC49@nE$hElER`!a|UzIXQP;m*%;A|g> zT#IYn#9r~edr}4oDlTCeob4l#YjM4?s#k3GYRVu%#U(6*vwb9TEw1m6l+X4rQU(bs zE@2s*?IV$EagBQD+&K07ltF@uOIQYH`$*(kT!R|+jzfP>86>EHULLT*5MR zeqLIYWsu0VxHgId;=h)SDfV|sP;m*%=qKYr?Op1AkjS;TwiqxVu9}`QNKkPJ%h36G z?OkdHiCl~8UlRtzMpvf{5>#BmGIV}kdzYF)BG=-2@vZ@J_sWz(f{II6hR)Ax?@}{J zmVB&fKAW$#BmGIYJR_AX^N29wCOxQ-g%KOWOIWssoa5|+Wc0ZHUqTul$?A75*dGDuKy3Cqy+ z+Sk_aDT4$Rm#_?7udTgH%^;C$aZT-hVO&=$Wssoa5|*LswY7Jt z86E-KRM#BCa+3=&ja!ZLKdwtUNC86CKxvJ&gn;?;EaV@KRemvyGltF@uOIU`k z*Vf*p?gxoni|dzF{o-anqzn>NT*5MRy|(r)HG@R1#kKz@{o;nr(>00&6_>CKU9YXZ zOU)pWYjJJ4uwNW=X38Kz#U(65*K2F8T3nZ}>lZh;F=ddT;u4mj>$SCasTm}4 zEw0zMJ3qcNH)W8Z;u4mj>$SB%su?75Ev`3@JwINwE@hCQ;u4m@y8%h$T3qi;K0p3# z`_vaDLB%C3L)UBTY=iCxiCl~8fi>sHPuivo5>#BmGI%#2iCpV`R9q0dbWRy0sJMh> z$W<->-UNwUi>v3O7sL~Lqzn>NT*5MRy|&Ia=&>S^YjJhn{=(S0U&uCdE|eTw~d5>#BmGWfJm61f&vvw2lNaR{v zd;cQ)(IjP%pyCpiq4V>)`b;xO z7C)2UoGAR>HVG;&VHr9yRdcs)@r^IfEoP9Q;u4mj^Ygm;OfyL2T3nO2 z>=qYYnKDRFaS6-d(?Ut)T3qeF>KeoLDT4$Rm#_?u?nvZXT!+hZ=zo5`SMgYppyCpi z!OCKU9YXH&*XFrCXs7#^=#NRw%jvikf7ocmZ9slb@iEM zkjS;T4tb_aZ1QW*;;|w@#U(65*K6zQGtD58YjHhze3y8j%pDZk2MH=JVHvt!TUVcH z28mpY>-kk@#S33f86>EE@M)nWaxJd z=z48keWv?CBG=;D@P;#D{Z{ESkpvZ&unb+Vt*g&8gG8>y)$sf?;$63;3=&ja!ZLKd zwyr+Y3=+8(*Kuc^5yx+e>tH6RxP)csdTm{OrWqu1Ev|jKoe^*EpE5{LaS6-N_1e1n zOfyL2T3okWd`2AiY04l$#U(6*PYWfHYjLfbaz@-cq`nUcDlTCe9Nm$~wYb)Na7Mi3 zmXtw)ic44qM|UK0Ev~gYof+@^DrJzM;u4mj>$UZ6Bt0J_axJdcE<7_H(z4JGmXQz$ zDlTCex?WrFM$!xtxfa*AZ=D%Cbx9c{sJMh>=z49v8%Z-rNi9+omlP;m*% z(DmASHO>cx0oLL4t})SO!OT zByugT2bz?{9p9=b9xD=5T*5Lq+eaeT;(F(ew(-hqQw9ktE@2s*?IV$E-H-Fz#tTnL z86>E zT#IYl1KY%@Em8&vDlTCeob4l#YjHK7-#XTgDT4$Rm#_@Z_L0c7xW@Eq9Z&9=GDuKy z3CrMYABkLx>(F|w<7rb<1_>%IVHuq5Bav%yHJsThp7~|UAVI|?EQ7OsByugTOD<~_ zTenG{B_yc0gk^BHk3_D;)%VC&@vO-yg9H_qunf-jk;t{UhWxcv{PB;JL4t})SO#bN zNaR{v&oyWjm-bB8C=yg$!ZJA9M%IVHq6Vk;t{UPQ0#FeC4;4L4t})SO!OTByugT zQx>#}-&dr*C+qO6_>CK-aokCo14Y=FFw-FZLY<2#?JNPyZaRWUV8r^6_>CKouAj< zrH*S!QXQM^4Sr^_Z0~$E@2rDR9wO`bbelYmzqH$*W$Y1p?dL{PY)~Z2MH=JVHr9xNKkPJ%i!IBByugT?K^K4Z#*$&kf7ocmZ9slwRfreK_b`U zx@K+Nc+UYTg9H_qunb+Vt-VXlAdzcvO}eIT{9>1sL4t})Scb0G*50LNkjS;TMr~g= zzOY-$AVI|?EJN38YwuDsNaR{vH$PS(f1J$DtEb1_>%IVHvy|kVLM~27FX>Wwc}QA zrwkHQT*5MRy|(r)HG@R1#Wi57+Hr%{sn0-yic46AuGf}tSuBG@uEjOGP3?I5tto>9 z6_>CK-VI11*W#Mjzjj>pbIKq=#U(6*cLS2hwYXk+rgm)5KJ`UOP;m*%(DmB#Ez3+j zA0%=ut~=}1iBF7486>E_1_>%IVHvt!TW1?|KS<EEE`QZdhC|N+Q?dif!t~ z?Wd*;5>#BmGVYP~SF5;Qltiw@^;-YBaX>}NAVI|?EaOvYf2)em7bTHvacy~B-Pm&7 zHN|5^f{II6hPJ;mjx3A^N#t5w6{G6LpC+da5>#BmGH#akw^i}^q9k%HuA95pjl&N~ z86>E;&_lmuEo{k%387G=P82( z6_>CKZGY0L>{yY=wYWZ>ziHfkLCPRO#U(7`K8y!R$q>Oc@wT*5NWmiBjE zalI&sT#M_pmK(gNc1QnOC3~hhXs_e6b zM6Sg(z12qXi>Fft2`VmO8FE!Cm+PR7qe$dhT(>XXFrKt&`rIW!#U(7`@6!G{71xWB z$hEk(ePF{_^AXwYb_pvtj(Yd&(d|#U(65+n-zqErUd^#Wnx8 z4dc3hrVJ8PT*5MRy|%7C)9WCKT#IYBlQ)VRZIt?nB&fKAW$1csxei(eiCl|o=$jkG zcaKOJB&fKAWoY};-lgsbiCl}T-KiVLlLn^@5>#BmGUTdOCf7mBAdzcvwfuSGxa8iH zL4t})ScY8H%H%p|86SC${<0- zB`o7F_&s_Oxfa);4Qs{aZ>0ph<`NKkQ!LWZ~LGo071niEMv5^zY~k&K@zzZS006p)$t$+DlTCe)1>{)ERF{U zJ+OKFYU^9Aua;|ZZMARxIP>Gb7yED|sJMh>X#3ONr5-C1xfa(B)9T01ZcG^@sJMh> z+#>C-NpU<#BG=;D`^WmR=iw=X1QnOCjGLwXotEw&#A{_*T+g)JBEInLEyZI+f{II6 zhPFTLUFxwSk!x|S-+qgD+2oW#f{II6hK}yEcc~d9axJdb?Y4-AhLk~qic46=P1624 z7RQ4maxJb=jkbtyueiB*tVmFC3Cqy-m&Su6axJcn7S)gQC!`D#R9wO`wEan|D%WF0 zBG=-&e@OlKZ2Oc!f{II6hJGJ&WpO-6BG=+Nx=#JLX5*AWf{II6hPFTLUCM3@CXs7# zT{n31*z?WF#q&Xeic45VJ!yZ_isL~Nxfa)*pVx~E?@SpasJMh>NI!Ij_AYflNaR{v zom(}# zz9MCipyCpiv75BN$;I&?iCl|o(5`jkV`EbW2`VmO8QT7|cd5sUM6Shk-jF(Rz#}Px z1QnOCjFHm*PAZNEN#t5w6)S7U#*0!02`VmO8JA1@TUZ{dMIU(pyCpi zq2I@7?^5@JM6SiPX^&d5!v^X4L4t})ScbMg?OkdHiCl|oR)<>ghEr1p2`VmO8CT1A zPCKZGUMz zNFvwbdTx5H7|u)?B&fKAWyn>nTzi*#tVrZqT-(Sz=P~!E3=&ja!ZPHlRxZ~;%OH_! zaa}OFc5L)@${<0-B`ibRpY|?wKS<CYs6Yt!m&<~a;?t!4<5|$xXwKBO5S_X++ zi)+Wn>%^8vrwkHQT*5MBUZPBA8+1QNX#3ONrDl-GwYYw+ zyIH*Hl9WM$ic46AejlT~OU)pWYjK_P{AO{#K`Da-6_>D#LDK#v6vu-kaxJc-&Z`$s z?Vd77P;m*%(DtXjOWh9=xfa*)TWuaEwM!W!sJMh>beHzmw>Taok!x|~QP@}=50aqb z5|(kBw7*%!@nF-x>=S!Wzux+Txfa)~N&Cd|%L;$5QG)~(m#_?Nf7-j$V?`p@;(BG1 zedFl|qzn>NT*5Lqx+9TmaeaE)zH!C!vBmx_2`VmO8Tx&U&Nk?NkjS;T&Y7@pj5nkV z5>#BmGPM0^?@}{JaCAo^*Wx;G#J=&^Q7MB26_>CKZGYOk)MG^=*W!Bguzh3415*YGDlTCe9Nm$~ zwYW}Pu}^HX>e}M5B0E%IVHw)~w0EidK_b`U+HS=j@%y7w1_>%IVHsm&JlMH79wd=# zas5=eN1Qe|Wssoa5|%Mo#)F>}$ActtEv{2uZ4uvmCS{PI;u4mj?N57`a;$2Q$hEkR zIkiQ6WWDrxMS_Y;SO!OTByugTvW;8BT`E%s2`VmO8S*V>xqL5bpSvV-Ev_f#H;=F1 zkupe7aS6-N_NTo|Jys-gEv`O~H;-HXo-#;KaS6-N_9x$q+IWyeuEn+gKbyz)C!}jF z2`VmO864e_$hEkZe$qTX`#{PdLB%C3L))MBF7;TE$hEk7?bssDs*(CvB&fKAWpH#y zBG=-YeQAsMc16k{LB%C3gQGhVxfa)s-?oTTuS*#usJMh>X#3ONr5-C1xfa)=%lC-Q z=A{f0R9wO`IJzT|YjM50?VjCKou8NQMQuMwEJpPr5WR( zkf`WAJ@i>qpi7BGZ(JDDV%&Dp9A#$FkFoqD4wpVhcL z&c9}o)yrq}i;sRb!66P9xI;Xs`y5mLGHZ)Cp=Y69_1#wS&6{R8MExDMi=W&(%9N&$ zZ4(z=R;XJo-XZR>WSB!V_;^kD^ufnW`J~zE(0opzzUs}D;gu^3b?Kh>`=M97^Nwqc zXnobWv7$qvzP4tc_`t|QT}m8u|l^|gy$4j+77s7s0TjiA1N(l>Wnhd~?0JO7wsuT)CBv|fXF^uU`6 z8O2#dCDI&Q)psIaH+^&WpEH3QeMi)ZJC5+)?Nmsl@8qgxP)Xmasf({v zdaS6B(C^D8$~SjaGf2>tzWu67@VKWrNOkc%m2MRk5@~j^Y6c0qKA!lOc-#?%_d;m~ z6%uK7v1$ehy4oMUMeMe8qI0aMkVvzORWnG?)u8d_@v2HMg9?c>yI3`Y1YO_!-)3>2 zYrW4aDkReEV%3Z^ccV(0W6_$ep!9rDA(3WJs%B70^B@0x28lGYQ8j~GMHfGnO80}u zB+ZQK>+%?u5>!Z}InSzFMS`w0gISfJlI9@)`>i68W*4hwaI5G_bA?q2erBX^w$;VY zn9^fKg@k@*Jz2gzubM%Et|$IkH=ZTGms*ub>u*#^>twX%XH4l<(Un%c{AYr%MIxR2)%W43kobAoPUVm5p9@Q$D7g4a)o&GvTNgbShBZ9ddAIYm=(?kFMtHryN3eIdpzf@2 z-KnS8>pr%4RyekIp)TDjDsN4HAq?nQaPgH&2`VHW8u?3@Rk*?=d%ge3F+zg0AXY6wmFwpUntA z%`Uty-wUN%MTNu}!)Jzx8+%8W1YQ5#(Is(zd_GKT3)!)Yw}yO!;p3orkwU%Cn=gg0#~$JAd7X`)52r0IxGt-l z8P052cwK&0mTnal63rf-5xSn~Z50W+_?cgt!EHZ$;0s~y)IZw~?jecYrpyYr-%+4T zGf2>N)cof|-KRZ*W90PPPI~Q2zrj@XI+%X7MV0hxE?VT5ky{3S%K`JOH%sF2WK7CfZapS38u*fvWu(l58_mZV=;)%wPom&dj} zu69~2KLOJ3*DAqJjM5A$B+@U_DqTH67q_;QNWXrmua$nKQtNeH2F9&t40ZN{dz*gu zRf+2NoC=Bbi>_7og9Kga_gSkF+z)Ph`UTOd1YaxtChLE{A0(O;fA_U&2KR$5Zei*9 zph6=3+G^Dd5_DC+=Z%KX4fWf0wR3y&!nxtW2HmVasIC3&OI83g=+(^!LN}+ZF1`cPtMzFY4hO zD=H+mdi{fNNFVQALV~WBrhXW9yr=N4EZy^+T7DERf3MI!-s<;Jc>SlsJN&qjtHY5G z6y|hF2`VHOb^9p1*wAYqBWx_W}H#lOEA+U|3@b3Ukyyy}&(=B|Q^+0|!|7`*SxVPUH?oD9AeT^#S0 zW>6uqYKND?^((v#5_EA+uQY>a>f>`h43p0*%<%EdmJ(D*Tztg`;k-w@ts+6!#1q~R zy=r*`m3@AGFWh!z;e7Cws^2OSEBd_~4%^B*=X@=?c%Di#sF1kp<+sDl^Z)FfNEcf{ zX$I$O*^}+vsaL#pjW=IAuXC69;G8k`j(h&JE^*)e3-j4sA3i=F`bS}&yEKEY(?)fP zL#F*1!Pg>j$R}Om5w*OnB0<->%C7OWo*prG*g5g{PsiJSoYuU1oOkkdR@dF+oVee) zg}QV<_*zT9=o%M2TXH@xUI1*X1jf5>!Y$KC4GuarB>U6=K8s_Qp{p=$bmHOFW@-VV_DfxUypWs&iwjRfQJC7FQdsdMr*^EyPh)F>IL71vayA_$#W~hldnDP zd@}s_x8-5g;DWN<)62r97Z>VBFIgETA6%eIGx%D}*zKs5;k9*M249OA9d}p}_WyOd zvsHt}F9~D16!!3n#-E32qYCwk-QNjgYd`N0?`^v(9Pr&UrkvJlRVbfPsJVru`$2`o zwEb3v=_3ksDZ%r>bMW#T%fj({yx?pV6%xanEeoAK^Ufd%y6*UOSy=RmM^G8^`ts2H z?ShN1RJtEjNX#1lWf(TY%OFA5(MPQaL#BBIkK+7ISA~O*`(MrniI&f-4E-8==YwaE zuIk^3e7Eym+32J%!{Y0`_bwF@zpejOm^;90A0+7Nv(<`l&V6166%yt5t`6Hz@-j%! z#kN^`&Z&^Nt?Soe5^u=YOh-A;lo zerlIyu;tvnYDHM@%KxR+l33brW!Um~Z>!j9>H2-a%1~n$kKp;>Ir#1KrD4z|-qEE( zqWW`Af-YVeN{ANMW}Q|A{xW!`yjaoDD2;rQ^~Q@T}D zNSxnvN%(R<@92`Ci&wkSj5{`25>DK^uvM?kUK|>CE7W|YQi2MJL+)H08cy;)MM==b zBT|~dw)XRPOG4)l{+Cuu;@Q4SLc8_7t>Sx$E*_E6t=i?AH^W8$eB3^Lwye1<)ZC!( z>BCnlC8&_tu->vT;=%%5JwX>g?MjI^?phvRdbzMwJHEXveAN62+d^(_DM5wA+(Vaz z`)(}I)f04apGt{t&wd%syP&XD3*TK3Za(f2+p4~`R)&GQ7XDsJP$5zM8hR3R%^AKb z?6}5Tbx(x^*X);W)#)4m6sA8=*xpMQ{t)&%xlr%+f9uC4Js-4vDkbRJddTy-+NzCA#u*JzlP!MJ>ryazYpKFDD)=IKKRG*%aX#UbM<#~ z9KLLuxNhIVC%}_G{~Wp>U1)dJXHX$Ad-cy@@nUbQNYKUoD}9%6+kZL!r!aN&pX~?t zki`AF{~WH{&AUdCpo>SObgQV4sQJ{-Va81F^NIvrJZ_~KJcAGR{XTSksBktn7`QGR zb&l6hq(Xwd^U@5ig68UYu9_|-sF2{A^y&$^9-CYzo^i*GP8*~`V)42k!oYWLb%=kp zsTGgCUa^t)eIg0E?rc#f z_WZl|%^mL<KKTQw4N@wk;{P$6;1BX#3@|M1QS3A(C3AH27Z=Vn@;9pdYC zz5Sp<;+(Zj<6XUmJ7yDGuslkO~5SM|q=3W;>jaMcVFbfr6hs}fYwJ;VR~R*^_gYpR;T zt)eSEd#NfB&Is{@359oDdLodz(vy3t66tv&s_?y=o@G*%ph6-&VWld;^z?imb#ZG; z--%R6q$l@O%^*QndJa!j;x_ML=tpWe+H?L`0dh0@sDm^ z4}b(+eD{>T+j}h7E)H&albzcU+wB-Xcy^-IAAYxQY+3sj=bTd^QFE`I<0TCXbZG_& zy6&ynIG);mf|GIhh$iu+;|o2Ox{o%Edmd64LGapDn!zhQ`$2pkml9M+RG&eDt~D1m zi_5n4#!*yAaGy%Iig$YQ&RO0WT1rqM!8=^5C+Irjhh5_vkNv|rA5=)Rzo23KzE9!Z zQ<}l=0QfBhNB5-!6%u@+NA(0#H00iN`$c z5mZR@JaCV=_?DT@86-j1p7YwoPFs8P=j-j+DXu)U@SWb4vpdF(+ZO8Ax9b!K{Q9ty z(fi1X*l5?ncVTxQR1vp1tx%7A_0V{UJAeN2#T{eEX@zg-u2|A3c0J-bd)<%gb&S0y zd*9qqA<<_1VX?~^Z_i24b=bWf;=qw!#^f=T@ztjadpogRWqe|6p?i0N8L4vOCk93Mdhj;{)2kTVEtGfR$TSeldQ!C>i(aYdg z(KYC{%D6>CkLbMK(ecTOLYr8sQ>gh~C_PqGNc??vWjt@0cRona#rJe+2HW-q zCv}Vi%L=c{cTXung~V3hbcoH5^tOrwT?5B-i0_>05&ZnPx=lr#GVaelOZa{z@%7Oa zvBA6oUAiA6=qkIoA};^QBdCN&D&pu}3g?-xRDA}Cc0b8Jb@bjPd@Z_ms^}2EInN`8 zy)Ez26@~5Xx2`hoH@#5vy->PUR7mW((8c$3X$H^j9(#9)?+yB2-d7~n zUtAGSxW#*y@O?#Bw_7XXp>sWgt&_)%t+{kRsF2_hsh*(gv71heLz{amIjE30@U}DK z{!_g3F=$o)*y;Ugb}bq*=fb${>-Sha@W%7v-M@K#Q7R<0FDgx0*tt!tluv8@j^v=9+Qj~s9q$lSNUV9Gjr`_)fiB&u2hMLB zFFd8fUaRAwA#V4#L#%%1jkfX1YYTrbC8&_7em_Xi^+1!dxZ_)11{D%KZlzmw;&rX! zE5CKJZ9io}tN49IVQ=evxqlpT?lI1>qC(<;-CM`;*LlZ^1YJDprCUXX#Hk}%$0;v( z86@c9d!aOgXRtw?w(%MnOX<6W=cbgPLSnaRZQ_f&dFO)!T{YVt82i6g?i^hzB(^=U zO`O`o%iw$T)8=jCrk@m!506Oceo!HC*>!E>KOg_Iqf6JEm2KmbmwCkSx69%VI~Lwo zM=dFfEg$b_d&_ra=~fN-YpeLt|7@$cy(DVBQWp1KRM^_m3=(wlbF7r$_HMXWtN3}_!g1sNl@e4)9N)QB95S^) zS5MHz_Fqcy+faqZ=0@q@+QR`H!k*W`!G;-f=7g6*LB{MNB{EVK!> zo6`NDLSjs>*71~{UW+0@*P-=V$J3{J1bZ3m4LrU4*tk9Ha~7vIyR1Qin1pFt9I@e`vogU7w$%vSNNFaMWwPU4cw zTE*6FyjII|PFLR}C2z7v>^-SLZ1-I&J5!q;)i~aFacipw-M4ML>!!n;Gf0KR-xjrq zpKjCkPYAkNuWTNhY~{VLsF2|Pl^$IZbn!E$l%PVQ`eQ|cE`H{hX7K3pxYhcyPHb>Z z;YgPfR7iA|-zI-`u6J}v&~?*s>&NT&^$02?w*T?#@Yi+T^_&Wc?p=Qg?=AHDS0w0K z@7s^VS+feg%+fulLW0kYtDc~X&q6CDsF0}s8FVD*;WGx)?cK97#CR7y}G!6(gC zPtbMCoF~JJ$9pY`3JE@8zBJ>p)uY1sw-?4_uO2%(9M!H+?|;UGFz=5`op#=#=G9?` zSQsx2ntyfJ^4LPX&ts!Qn`XltqO$#n@K(oy>)QGw!)~qrjNogL*zu*2Vb`4sbm@MO zpld*nQK90;!akJ}-1cLq4G-U+{J(4!iSq|t6NaDkXIn)Vk4WiO9XxeN*sg0~d;4~1 zA7QKiZE-?aG{oB~5_G-(*CF9=6TFO9_wOERZ*!5QPYOfA z*jblbO}cbHsF0}Ncu2USxtBqLuIjgn$Lg^9Lqpf%cMCiUrCUXXM8$1G!{Hly$BG19 z>m5EUOx)EY*otnSI66GJu&}q)wo%(3h$We3A*@>DJ8h=%zJR& zu<+gP-hNOa(X{-MaMIL1PKzQz*H_nG9qy>d7eu5g9?e?4;&qu zmwCsE1YJMQ8x@u;@wRGCtr4NouZ7R>6$e}sPF+=~xlg5AMTNwxXATdo)_7L~5_DC6 zthl}395gCSA6M9R?qBIvQ6bTK+{n3zas;fSva z-|v6@%)#OEzu)K({6(EV4yz1(8%;46e_f|^Kd6w{>DNBt>^CMl86@bs@cQ$@DU1Fe zWoH6!WAXU^V=Y`E-?C)Cm#;NN>X+r-W{M=s4J9p>OR{g-B_||HQBsyMki`iSo{hKj16zNFKeR~;js-#kf|KT94elFylccl$wwMDZCz#PRCB47Ru0t$jqj zpN)(Cb2F%r=(4}B*nGg3L4vLdWBZ9>yL<$dc|`_@KA&Drt4ORJHBj_^!JTl7HDiU-(e048Te4>w_vUg+;@$uZtX%&gp*LD|cGkqCs z65E9Wg;#P(Dl zL8V}ku3|`c<6=$Wts+sPW;Zc$vM+;m(ZwT!n?Z%d=n>t;?st6|Bd5J#u zJ^bZU;_gXr=<=lW=R~c2zUu&}keJfa@(kf@UDEs?9G?@A65bcOev3W<&fW{S06tnl=M1YI0;w;wyN94lIVXs!_8 z(+jhWTPW7I>*C3vLW0lJa5G5I#ryKQ1QimzCulf9SNQ#qsgU4v0^N+(lU^2st}?TI zVCNYkPkvM8sJq13m9xaj6tgD&s5DFbaCWgC(blb&i-%r%(=)m!o|rD~eb>0IeRsU* zSFE=viqAeUWv)jzgKfWU#7r@9 z=cW3=9+Eh@?iG>eV_&OC(8WHvt)fC=ic4GDqDd zxVG=D{fcOr{Zi|kqf6q2Y%|3h$9-c(f-a7<+p3k{&k}W?GIedaeYU7{pDAJ>y{}ay=n9{SR7lLcaf-NmvM+-KUDsk2 zxc%UoSRkheQPa#4*5ndYNZj%K6jAUILx&S|@krzn{0xboK=FOBOHd)f&$7Y^x_I{L z5>!a^`|nKgTY29-2T0IW^qa+^(VM<^;Z#V}{&J0YJ*V%JI}&s~IPhz6%e60i-epiB zF|6-lF}25pOAvJNo+Iv9@f$aOyU1~K2`VJ`DQ-AH7st&dsE`=A?Nu=?;`<(l1YI0A zH-id^)W%$ zNbn3GoS=)N;1X0w@aY)g1YO~yONGS3`PtRmdPcWoo&qv$ zbA7FlE|XqBb}Qw(Hi`;~EC}+K#B&YC8XWar9z_bTLonE?|m60=n8LD zzDPcK%~sQr{@3J_IqR4a<#jo3t2kEj-K*rB@ma^sCDRaL23tkfq4xRYL$~^7B9$MmSM^RYF4h!2RwPa&<&#Cv z`7&4+UEy<=3W;jx^2*$g`t}SY=;FF@`@vQ8N!@&M-pos_C}xn@&@Z1ndfK;#BSF_^ zALf%q8u|9SR2CFSlJ7oaT&&6M2Ne>Z_ehd!V!jL#bnz(RW>6u~Zd;OkbFVLh1YJC$ zx*7b;g6GjZ3wH@BBzR^SPSC~AeO-bI3Es&yoS=*Mvvmn7BzUh`m#8o(N%pNZRv!m> zuehJXkf(nU@dy?dw z_Pz`fbj@CuPnN9gBdDyXm`}cN{wdvd))d|<5}k+Vl}&#%bT~m*_&E+05<55Nk(Iam zGDy(XqeLD#VTX^PGPcK+veRMXVoh#8sE~+mxI$LU=NnxTbUj@C3c3AOAHluMv?;md zumWaHaIfUHiVBHFALf$3bn>kz5_D}on@gU2-$ziXq<&+NJGa?Kv8M1=kr?@9ZuxaX z-yV*2(N+JUE9CuAAHmO%__+q}FYC673JGS16LfK3=@L{(g!h94T|C;k8Js_{*K*4o z{moqBd~*pZBv#hWEr0sJHxo(F#Xh+iR7lL*pG&sRtjzto z-e2*vWtX5rg4Yy=6Lj%&c$c6;V&Y9xM6(Izo(kavU3@?15>!ZR+a42j|6J%f;*g+= z@8{eMDkNIB+$V;cL^#acn|z=g03PvkBje@`0kERg+%!M^!ce1KQH4s zgWD=9B>0I%I6>FcHRWWr>pOV1AQck)9h;j$g03#Hs`452bjhsuPozSEzhiSVNYM4- zmYVX37rS~gsF2{VDBTPabnS}Nk~xca^JGvV!C!;A86@cHRWDucK03gYL4^c=)#_&O zer>OxFC*JkTdnK;^5L@bKm${Di5At$$yi&XWK1n5)7zLb@5<&9%wWCY1QimGtSu{d zweq!!1YK;c+bXubdA4Nva*Ip#gBc`FbWE1Nr(LR5blti-S^k#nBL>b&k#BvIskcGJ zK`C=B>r7LW)3VT2mNiXnqv#yR#71_F{zw9c*b|l9SOQ-&nqiu zxjj8-jNKVc<-k&vi{A!nMi`JXD64D8(RB_ z8ple@vBgaf3;tSK7EHgKSwdn+t}=4WDBoCdme9o+>h_%NJ$_FaxqRg1j1`G}rBu(~ z@%5ZzMHgG^wu%agKhBnxllJ>ENYKSmcQg3hB|fi;PgHUVDkS(^sc?cWKKaNcsF3L0 zC5P;^*mqqY3A#AyZUz++ITx0aUr#pA-3lk@;@WfxDkLiWSwnt&&iA|`5_E;%g_a5l z-X+m(6$!d{?^lwMQ`kf4jtm~k_xkf`3fvb^uwsHYz!==yihP#`g2P8B)reqRRbqKnVEaQi`p zMBX17$Sb7pvn3LAb$I(;dB=I*Z$_z*;B)HTR*|4ba(-1VmK9*rdE;>>q5sF2vCuF)tz+;@IXf-cT{ zH-id^i7iXWxo3RqoCIB*`ECXk5^bATkdfxT^K%k(apt=jR7gCNQBD4qG1xOpNYKTZ z?`BXTvF(NH<)DMU3=(v4=DQhGNOb!0E?N0|-?Pt1(8ZbWW>6t9rfeHow1MyQT@rNl zUfw|#ziGT@bg7W&|6oU1_V73l!Fzv>xuw0VGpeU{4VcqjMkbrG+Yc&FC1uER&l?wO zatSIV`t{F{?+x{3kf5vZ|1xBkmOi4<(GF6SFrRGQsmAB@YO_*#|5UeCR7l*>ql5gS zw{M-7-_Svhd9sHdAJU^ob&wg~n16ROsE}a)!U?(_ys3liRKnMDDkQ?kiv76p?+&tk za@Ib%tzz3rlq}IvZd%pdGp|U{wYN$~`9ljIQKMs9Ij^5lW(;mCCw*_q{M68G6%`Uk zX1A3$3g7l1LD%seZRL;|K7#GdS*fGk^0S#^?4R2zDkP>C?kM*R_kH$Cf-cT!H)HjY z_OkEBE_&RTM%&BuO{N_FNh%c*9~WsaKiF$%H-iLS$;;cxym@@0T#HPpE$=j>@W;+SGIP={MDkOgUs-0|>;maUF7x#~D2KO0Vigl3HufLqV4~g49 z%#g`veA|Pwgf4C;w^dX~EV(yB-ts?R1_`=2-`ot&hVSlgC-V!_bJpY%R7kvaWjk4L zjBj3%psUdOw({^!A3-J83vFeg+GgFcrtnsgDB7p3TsX_OYFQUuoS|+86%sAmx0RFg z`1Xk;=;FT8&EVZrc$X92-NPlQkl=41&$3*C3W=U$l4PkdzHi(~(8bTP+zcut_?)kB zf-ZiR8xvIpQp7%Z^=;CKtZUz++e4a))L09;bfvAuO ze>TVXKh}#ItG3oX-16&sQEtusx;$aeMzP};^Y3n}sF2`&K*I^Tc;@XAR7mg|=x~BA zo_V_j6%xE^A)KI#XWlMBg#@ob2q);`nYT+&A;D`9!U?)~=Is(xNbnkjaDpzLdAkG^ z61)Z>oS=(m-Y!9f1dqYt1YJDyb_psZ_>ME2pzFw~Uh>P7@t(a86%u@&hMPfxuAJ5T z%2;Jz1{D(XCiRs?i}(mWVUf@3zbPT9EKBgaTHvF3W;{T+R9<3A(~ZmkNm|U+XMuUhkV%w>{rQ z{#kLNPVe5VtDJd!f-bLDSDl^v-aIwd?FSVS6LR#BZ;mx|I6>FJ%--^yAAG-xr$XYb zdIMyKalUUFNYIt@x#6y33L0OqsOXDk_6OJUyzr{Lfim z#`j-#m3h84@95u&c9rA*H0AJ_IP*jo*|?mki}SeFt}gQHWAi-gg9?dO>NAEW@A-%= zN4m=LpJ&ZDIi;)o<~3hG_~bS2?ZTgZMuh}h=#DN4x;W}CL50MrySmB6Kl%DWf-cSl zH-p=Dz_ISK?FmyaYjO!HB(Axqhg|vnrCLQ-_}t|hETg_B=yJ8Gm#fQd6%`Uc&Fd-q ze(#$lB8u!$VYI77f$Ue2bDFh@Yzm<#1;9}T1oe1kf4j(-|aaS64xE-BJUgN z%OF8l_=@6~%oyKOKK7WYmt*L*iVBG)9ec`o!q+Miblp|8r#xTSN4)(-cUfw-+2gG3 z&|TJ@da1n+N0-F%ztoDFW@xt`++Q6p+EtclX=WnF&?TslIFa5}u71+DK1k3NzQ1C7 zKbhD~wwr%BJttAVYBzc1d%m7?tmxuC-|acKRD=CJ6u~pk@#GpQXMG5_ECCxf!2bSyQ&T`FVZx`r+Z4^3Xx^?uG9%U4jY;UVRZx z(8YI|E=O1@bV{+mT~lS&N8 za;M7nsYD6F3~nSEvro=ZioGMLD%+>)B#5X%qA`1KRHfLvC#kZ%%TX4>-hp2!_6}yM zZ0~HAg~)M389Ahwx{I+=##~oQ?)b=*?HO_wqWX~a;)*sIny_~|RW5r6)GS2b@%d!g zUtZBfQFY}}^EXV{ep;V}ph9BR%DhsvGqgKPNYHibfV}F*d zOr?LCt%$s5z*Jq%y{C}e{F3>1onZ+oB;HW>Tl%QcMMMx2JDvY3Ic11C4_6uXdjnN| zboEv8ra|W4ZH6YOkhr^70r^lT5K+Uq8QmYwFZ=b#ny0;%V7(+tEl-lw@9|}jpo^pK zW>6t}{Bq|L>Qfa}{%q`3a^T~p98S~eqRO^5(|DTAa^f7hHhFguSn3fbIN~Y z%Z6qiyZxX-Vq&zQ?DC~Ag9Kfi`ECXk689t(lE<&W`iPp2L}MiA%Ce#?!Sy_*d0zS1 zyEF7Q=j?G?MTNwgCVAxx4;ea~pes-3ys}A75CIkqw#TH|dF8^lOb-{H$}4YZZ_1pZ zZUz++OFHJ0>DT$jiUeJa59gER_FS|Db*rfK8j&RXFEuXK6y7QlgDU2i%br7qsy}!| zW2}oVu190le-&ZB+f*xc(3=J2(Q8BYS2`fb;NFMCz1I|!)9d^8B_!y|vKKXtQW-oN z)Tw{9yhE7n%o*zTg9?f4jjooDPsc2YnhB}JTHC#_zu}-{y(nnA^mi~$OsOp2d z?X1b|2Ne=;ja@79wKQ}%LDyF+KNkJF_y{V?_O1~vx?fJKNNmr)MofIjm%)C}^@dz6 z=GOKRe2?39bWBXS!nj`lAyfSIiEnhN%uml0U-UCB*5r;A6%sS|tP-QtcT&L&4JYV2 z|NJVk|6MbWU4lxLM^}kI8XFh0U4jaUUhP+jgL~C=2Z>e%SX3WBo?a>{y!Vh+=n6kK zphDtwbd@+g5E-ie;1!LLpzEtoR*8;RgV6SXcsxBO+7)Z1TVa6Sl6M- znId($p_y$7Rd8EHqWs&LqC-1FYa(hmm!ONSHD2{sQPCLNZlAX5>xXg&FLkc=<)`A8 z=Njsslc+R%jhHw8z6)D0s)36Ly6znCu~m6!1ZGCNo05lx;Piy z4Es%`>fxsA`p9kTpV6~#*vZ~9=ZmK75>yKB?k%5bXI!kwC8&_7wX3(xRRtLV77eyJ z3A*gn7g@Fk6%v0R=`FANLtSO@|0U=;kiU<-eJu#xnV?nwywqQoeaf`=>i+%Zk(H** zPmQ!$^&xnvJ;M!y<>>Oy>U0vhWqh$zua#K$qL8VoR$7G$}m(wZ| zUEb*{@9*r(V5{ij40U@>g~Zp5`^t<~z6=s{Ejivt?yBb_sBD|wM?PD^xL8wot4M5V z(MJwE>6?kHi!SaZbVl$e8q9XCoZoKiBX5{&RuR{xB?2f$g~W3s)f()IHK^(jUM@k` zhuiwdH4Q*$dqCLhuhbsEUUQ|&_FAkgdxoJC`pYT@OkMlu^_O#tU(Pxwv36m9SvlP| zy4*9+#eIzKa{Ny;R{rLGa#ONt)!mc($>#M;`NbT=WWCPnj)IAP*q*bulg{*&9g++Y z-g7D>=5%^Yp3G}#-JqyxRy0O}u8ChhCbwS=!T@S}u4Q?JV5-+z4g-4;>!HTBDT<$9p(W^wBnQ_ey}%qtpW23_H;dSLf@ zv7|^xox$GP=MW_N5ky3T6-9*v$4$3Kxr3KW(8V(u<28TPCtf&XA@T3d2kGLup{_le z$S68wlb9gPh;BLYnW*)x*=p>cOHd)vW%5SRwXtuTb30$zbekA9AY=>LR&lG5*gW+s zQGA}E-ByvHi?hci*xoVSKNXKGFmspva|tRWDvaD9Y9BPSC!C;*^Gy@+KhfBpj^By3 z#mqN9U-kY@eDRkl+pE~K%*3%zekP7DY@_Gy-gBRedNoX$XEHV;8q7qxPS5y4wA%Bq zrn3;r9lX?g(Zm(}DxE})=3B%E%M5L-`tL;qT@4C;B|d)BN3gf{xB4oN`xrNa3JH6k zfW%lu6Rjda7x!Im2ETo~^{x%-Q?7P;thgRsf(nTvB|jC148gA;%LPUdvAcG2tDffLVy5{wb6$!cqKe0pfS_;BMs0=DQAN`-0 z-pkAq)?}Jv5Vut%7Uug-R7g{IrpPjPSr=X0W4IZUk93o@kC=DGb)M`d8#hr``Ko&P zuGS@}km&tKSGi!mpY{~L9o#ml>)Rofz-&V0+5=9O^DsSm*Xt(Di=*oZPqw=P1K7z`_RXWKH z4_r>GNPN`l5!vS!Uj|!67f0Rg2Ne=iUg#+6XZK~0plkn69ps*me6xhg$@C8L;V#C- zn!;N};`Ut`vSD6d2J51WbIi@Kcc4)-!`^j9mF;~rR9O@8KhYQ!5{+XSa`Z9ZdukGN zEvVE%J~keN%_!5PyL@JzIbSNK?tDzRH<{53gaH&m<(19d- zSWLgoM^GX0=d%aJk*KfdBQ9`J+3(< z9$k!#s0oS2NYKUY6mO9JUo^(~Q~krkqIbCu^}OO-FxEr{6%w2C91*v*G;}yY*W8}KOma@VE*0Bph6FiY5W5;Z^jQJh$eRw;MzatXS^_a#(FJW=jP zF?XCVg9KgNkD2D^zp7Q-t8M#cuPB`+FZ2h3_@Wq9cbyw&AACwc@sl3WEHK>Ry)inHkSy<5 zkf4jB?q)pr+bQvTRdYZ96K%c?lp8cK^Mo+C8&^Car(6AbdMS7aDpz5v?hW-(cm4xuJXr3m38XrJZenr z^LSL*-W`f#r3t$1lX`rFatE(yjCGM1*ZeopEJW69g3!U!4A3 z%-f9&1E>rt*N!+Pw){uk9bMJSnzY%QL1O6cKg3NB7&@Gw%idu=OF!&$mz2^o?_n{Z zqN#V?=p&-k@r(MQS{9AjXMifgKKE0V?Ng$%WaKJvK#Y0J%%8$J4u~8%P1!!NGz&q6 z#QHl9h{Z4ZW;#F|2rx2`rFmrI#gZu_oJ$Od|-Kbp!f^= z-(7+ViJ!NXm%r{;zgJDPO4T2{+zfjk7Uc^6^%)fs_8u@xIL__iSHqKj+A)NcMpW1J1=`qq#=Up4h|_GoW3K~N!a z|DhVP?h#+BNYKSOW@=AlaK;^6TvM*wYi1v7(%xu-ph9BF+co9c+GhQS6LfKpVQNog zd{+E=`PKIF`pNb3WPWV(Xo8?Zg0siXAVJrHe${2s>yQ!0qA@BYvdl!=D)wW~ zuxhgWhOB+k)mwsXCsFFRs&dXm-x?%A*C#`(%B_uk1eGqOs>(Hy%V`yf{ky8jkKV*K z4?3gz5{ylS?yeg03Do>L)lXjB2Y@_)Wok)W&Nv_i7=%^-qSMT1sR8TCV9 zxpb`=E7qjDpxnVL8lysDuDn*(eaiRkD+#)|olNEWugai8B4t@ox#w|T1_`>jHQkIq zTc~?LOgCo}ulCFAb1B6)1E}DsF27!kw=cGk7HESN6?jXZyqV~`;G=w{;8W+ z-o3-@KbWm+_hyjTojsq-@%BagL`6kotcxzrP&b1Li3L@YWS3Wb`w|j#aUQ!F{4G0w zz0P0DYa;j)4f;Wa1b+dp3FQu6E(H)CS&L$5~kOwoa&<+~UwOHd(^F}uIm@-m2Mq967S z{HosG>jsJAW2Wd9+WYKh*@8K5=_0nL8rS-1oki~arriC$2BP87=@)u#B2+(^!Fuie z`?F-&=c+4(#Q6s4qGwrkN75_=6%vm<-%C8W$Fxv4$o8E5VA~58=_-bF2Vwic?a^=4 zVDbJxS+|Xw!EHcdc*h~4P1Tn?{UAYCX11ZCS{on19+p1SLp-v@w4Eao??QZiP$4mT zM0c_KUG&_J6$!dHZf?)1kSI~Jo0vG+mqCKAEZf7jinFiO9i7F*9cFx3Q+TULEd0OD z;);2`(Pdq9y+5$CDA?0S6yDxd)Zb@j2Jgx=?ei|8Mv{-9LZZw0&Z2%D5J6{D@1rqh ztiHCpSeuzO&+R$uC9!v85ApF_-=2X4T@PQ~OBA07!nTS^@fE$rBcm>-RV41q=qvsh zfeh7a9TQ`#=(;LzKe1yR2m`3G;>vlX)ljiuk{MC1G*h`jqA@BYzRwscs(y;?5%m#t zeU>~_B%kvU+}ExhHBj_^!>kGJyWCb$Au+GW0MX}D--;qZSB0_tM6q2yf=ZYDeZ}Sj zm(wZ|)o$%0>iz7?V5{ije$4GT*BaLZ*QQHQA;H;Www?ML4OSEhx_r|-2d`+XR@;}vhVw)9UjN)J<3*L!VY)nH^my^v98)%4^EVo!(rf8>@qXSX zG{Ks*H<}=*kf^e9y!f=gp~DHf=1mzdR_yi>pSKtT=&g9?fMoyUpBe;PWRpsUoUV@1W%QBMYy35CXrN_C8j+2I)^(i@EtUp4h*ur9j# z40>9OZVe&`iU!-fXOl+alSSsYp|{N$A+GCSdYixMePYiD5Xv3A)HfzjNX%(ILOg!n zw>_wQ@!t{R*_VuqHJQrw--|Lx6e>4DJW&N1x=9zeimuOVbrSiC4)kmfx~7Q{;<+_u zhKCbWNc4GXg!ubGtdD4-A0+4+dt`+8`rPB5R;8p35v}L+(8|#XPl@?CjO+7uqeboG zW^L-)Z3c;7z8NF(mox-dnoCe2QD@RvQ7j#;GTl(ygUYYBjuR^Nb&b;re2P^+jA-;N);L<{>(tDY|ly1#Zh-NsE}B)VU+m2 zGBTnjL|uE1ZB7@rf4o8Qo^v)Fy7_7G&=E5;SW|ebNUX~{MwC5ssd+^gXN;SX?aonR zN=38JXgq7Axbq5A=03(HsE}w-Xr$D%v;po@DVH-r1W7IR07QxBL{abM{YR7eck z{FEr%!naQ(K^I%=W>6u~B*#;tr1WKwpo^pKX7GMQynBxKUP#ekFG_{PjCCu-+IyRN z_E#k6;=N{dtKxs6G2Wk+ceW|<=P%;FC(}F`R7luoNhQvTyM3+n6aEBbT`wq`o z9sjtl?0X_zE4y3OmFXu<`PRSc%6^aE>mlemajcGf=BG;$tc%1$W9rD+9~)YCA!<4j zjgg>>Th=9bk7(XII=tspNNn3uPY$18#?Z|mK^I5eCD`_xE7y^eCz{@d_k#+F2e;Rj zryBdliUeKvPpmCJJKOBS7BqvaW(j9_@muQ3IaN(>IfiaOsF0{Mx2{}U$v0Lc=;A%T z;|(%VG0xZJb5rG{$1gQ^xjjha_$*c4xW~|LKSe6j z+#jD6Ej+kS%Gv|U!P$7})hT8JS zdYC0q&8b;Jg07c~*OtG3jj;*+Tt)h!F-+0a6XpHmc?tQ7U`f@Wq zoNwA2O%PN_jNY0mOP2C&4-#}ue>+vaGtx&;nJ_F>?$~QwoNsQcsF3)zcB))f>r!)< zF0LClgYze|NNxF37c*9zZ!STF#EAdamVchdIuEdDumwrb_3vgPiJo_c)n?U);1!KgAu+sCs{A{0pQlwM==#5%jpV#^b1zL(x&Es% z_&f$ar-8IfP$BWb!4|S~UhEm7i3}2Sg|~`Nk6;T^_H~uVn)~jgLxqHW%6Z})vTYR! zx_;f;TlTuKhi7!DkVyWuzx;B}01rWhgnf=?mR6CVEBE=qvUYvnSrHWyyz7{|1xe7w zdx*IN6%twQU}i^`1YNvCo6d;;QTI;3eaCorIo1^3DiXYJTsT43>{Cz3^NW2~Sx_Ot zC!)9+e4+}Uv|^tzli23A=k~cWO6hUeAo;*=^YvVMb;D4(cHgWE^C}>s!JgrXea&Qt zhO4x)Z0h}TWEJ!6w0$mJB15@@S2RY2gnbTPf-t~E1YP#2b|j)f#;Oy|WT#&5>Q*uD zr5BpXJ@=Y_k5?b>2Ne?biKU4QRe$h`#z@eW?fPc&@EsRrXo9VpQa@e3`&`x*n#%Rx zi+WCC`ZMYB^Y@Su^$~Qv@=3bvb-+ik?E{`^BDXzcT-W^CL{_;Ago#kCVqM3Mq|4Nz zE3%BVHhWt|qE)tgv(#CRp1s_2r zb#P;O@GmnnSd-gxDkOfnr?D)u!8fl+(DhVZ)sIOaf}m)yXRyzmS7VZWZ)17i46};3 z(%e>2AyMtdCi0s>Sc9tm;H7>`c3m^sKYoP}U0lJ&8`uMa>p5rZrgA{)<+O@K;ZK^% zE9zaURdj{#6SPtWb+RU?e>Geuf2IdNqK9h zbvlEzOHd(ErbI>g$2Xr`*u&X=kf19|s{$e#^qjwt9$fp3IPsZjJAcWnt5@#e6^&6L zv9Z{dGTR=sDyo5t2)Z~T+G`0aB>uDJYWY$ZGj8DoT^u*l9`iREvrkx6`z!l2T2-Kty{U+Lbo4ONZ2QLXUQNzmwhgBf(U|C z@74Kv;;F+*u}>pbWsZp3Dk>!GQ(O}ns{Y`mo;jI#io8?ppS(WW`hO=Z)Az_~mogjjs zXfRfs4fc7$%Eb|JTSbM0eU@<|L)9O=-0eXZx2&=1zlz|>u}>OT^>U@T1Qmxk7Jn9c zmR6Cl&p%f#`y}-&gnb^pQtUIGRhgsiwu%Y~`*i3m8B8Bkth*d}&U|XX*18!~NZ4n^ zXUQNz7hCIQP$6NTO`j!$1YI0MH-lqhpSS(5N0)?s*7yInRdjKs=~l)6sC!M~9=N>A zD(_n9_JazEET0rbO^Ex<7rOWa4mX1e34StVYENX4pexHKUI7pdR_&b&lI8ZQnR?&O zcd}*gOqS_|&A*%469g3!yc3EhRQSXy_vMKZY%2clZsthV5PIOF`zo!}6 zC8#vdmMmXxaXA?zGNzW3>1})&Y!zKCs+E(mwmyQ&BWugbU9B#sRV2QAxU4+Tz?Z>R z(ZxCKjujOWub(d?+g0;rkf4iuA~%C8r^d0;a%^!kGgy;LP$BWh+0t^-e(V_nEE>#2 z5_EB;xfxVQ>?>79Zg>Y7s{Y`mjs^#c%9Axe)cabxj^9&8E*}X(+XI5ivy)Z5t&NK{ znacIwi!w;O_fr{J|7K)FeFRM3A(tCF+E81gZCrieTsM&AGcLhNOZlko?KPpO+6RF3A)bQ z(NLD`H`_x{A;HgN-3$_RwNXzc-QL{1TXqR5B*H%zB|#V8)w&r}NM!k5Evh*++ey&H zcjs;f6%zk#*i&wQWXXlmH4!R<1YKD^ld%NvO~vicJCnGrqC$e(DV(6|oVq4sT~qv$ zHENm_jZq=N?c`>VpsQW4wsKgtnHR>&W>6u)?c`>Vpo?e7EL4^dzFr1)^=Tt61g#zo8#@8A4{EcAwNMQwVloxHtzPrVL$)k~MVj}Fk~-@a-m zn`M}PcUwh;1g}nU31*xq-A*nzYOcQ_?GjW-9N*Da4w>P*dWQsEM`pK`Hwqs?WyavP za?~VUvaWOkQgG8gF9i%AHO^;hRLD%%c9p#?kAZ)9sxr&CCut9{J#v@rKKr{uR$s#`t{F{?+x{>a}snt zm6RdNJ?|r^44BhiMkZfQt4NHwrM;{(%9p`b(Z#)zyUn@QiuP$M7tS(Ukn6@JsF29@ zLR(p=HfBlGOcVDyOS%fJZz~V)ylA#7DjMVJTz#ay?7Q)D);WnK_h!gj{&%T$P8V0O z>4EyITgCRib!9tQaExg?M?@3K9lYG0llbobb~3*}&!ZZ+h@gvmKI2UgTn9J)-9ffb zHv4m~8|{rI2r4AXZ|ES$Jn1_ckf4k6&CQ@fV)UpEGUFRx1_`>jn%xXuJH)Gnc&(93 zP$9vq7QzX-cnyLkf!aAh2aEUJ;x-;Qe(`w%Pv8M1V=iYpo@2fb_psZIAg*Iy7<|N zOHd)fnIBHj#m`P$f(i+);BbO2es|`OPvyF4aaDulKQ=C?%ZQ_dGpy^^5pyG-%WcGtzumn_aw$R zy0%WrB^#`G`oic2fTE(Y*lW3Ej{c^-4_CiJZok!(7tYTvpExn>0-@Z&D;lFhBD&!U zSuvll=OpMF+v7^v>9E=UruHBp$e_}rL>@U|hjFncO(=Kpa$7}W=jJ@J@^)lIHEdH{JU8~Le|YMOU&`@OIR0O+_JhsYMg?Xdrw&s*B?xh&;R1fU|n=^ zzM0DPUzNexFeq1EdGM>tnTaIww#Xyz{@ORM*ebe)&An3ocY}|hQvLK5a^LHh(<&16 zAG$)`AN6IhRdjKNx?@F!#KyGDy(H*^K+hO@)JFmphAMbL<}eB+7+oK za~AiV(NiJ8UuwD;BlJYrrf&K za`DhhZ@NVEVuG%d>s}FgJ~p)5s)xUPO58o^4P96I#Hr%54@|v{vP~7sCm}=CAH394 zdv2dCD&1$4mEX@2b)Pb2-fPx)1G^^DUly}pH|fVJ%n&!eX3E#TJ6`mx_S%JhD0lFR z#;B0k`1cG^cq#f}07Y=+k&kpy(|V@WzO}7Wlk3_<~HRl zThL}uA<_KzX=2tXUj_-fINx*+Yz7q)xo?@K?i}gMAVC-Bv75nJeaG`tM8QW)y{yS4 zsE}A7rwCE=Qmvxvt0Ggx#(%H{bx<(dxuv+eI78i5Q6a%m4=3p2eWYE23W+TDj*e^Q6d^a7 zt;V_Fwu%agnKw=mcTc`(o2&6sS9xQY2w_cmvb~AapH;T;@)?Wq3RD_ zZma0pf+LZ!>c5KMY`C}fE23rg%h@NA7}$A+$dljqNh)U|UECj=_5_^>`oZHJkKzAr z3zFa-!)63A&asxRi8oCV%_jIhf#iMj`2+@jUTQORKd6x4Qw%hr+`%gvBSF`&zK6xs z9uqFSXE1;wsF2{hb5prNT!OCD$2W=QyGMF5sF29JXqT8{^@9qD2g+_1w~q0>-z7m;(IK0}1OdWkL|1+*PF>eYr!!;v{DUILz|I$1W&1&e zMEDs!3A%bEUnzGt?BmIxLW1Yix(l{dB58!RO7m86@bc-n+8A@7k!RA5=*2c|2|g3AzT%sUoM{@5`VtlGf2?2 z?S<>*po6{)DkM0k-3$_Rb^7uyS^4`Bo_DRD+|cf>l*4j(;o9zeZm4I z?@I;bwy1IayH=6-C!>J;`v+ur`$1Qh&&Vu6g+$vj1?1N?%t-4VcnP|0`tmBdW3Z2) za~2i6(`vl9m7G%V1q}wRttaoP69za4v1=mrou&ZALW9ys|x~LgJIU z`Q*HrzU@JRuKwzXle3PGppq|=PhPXt%s$rSjujOW)z0OWxgW*c4KUT0Xp971++(;I zR7jji$|sAS^Q~GEba79lGlDX}9&Kd8^U|n?aNTf%}wuWssnYM?0Mn{}YYzxkP*l8=rjSwu%Y~ zKFuebpey{d3@Rk}G&nbd1YQ5`GZ_+vmh~1ZbH9G!SR2(zYSpqXy7;M~+bSv~8g&~f z&b{pWG>QaW{FKVgph99&`g5YzzIQzRAVC+OMQHk*==qs->qX7`@7Hxr*t1dW_@%Wj z^BDmbwd#ZIqGP$cvk*L63Mc5|oOTH+BzU$IPSC}*=@L{(@N6lZpo`x$x&##xJiiJj z=;Ak~E!a=Y$=?ei{IV51QilITM8%W;&s+8 zL50MTQ@!MuDZVo=5_IuCxo!p(5+82sBiA(WWssmNXZ5}^RvCm23f{@^St;c|km7@* z?3LPjKzvul zl=*#|sa^e5Iqo-cBzAwjUA)|KsU9~?D0lF33A*@=fbp8Y?)T>;wr!7zx_>V8WUwx} zctmwGsE{c7&0^8$&6hkGBIze|mjr)xq0OrP;N=o@aYT&Q z{8f86j5`T_H>tf*A3+zltnnrYDkS)AruIgC1YMld#+x9hkl=Td+8gx|baAB_Z-Ssg zg5OPQZ`4Q7#XW}cCI~7dCOy4WRCwF?Gr4(CM1fN#n5KcenvSpo7IipnCoYHsc3@Wy)GWZOQNCZU0x>Q|s*|N^K^VS+^ ztJdA3GpN|I%HZ=fA`uV~>r!>mWy?C_gQ|C=RU4e5GpN|I%HZ=fA`uV~>r!>mWy?Ba zPrjCEb$S-i8B}apW$+0ckqC&0b*Z}OvSpnyVR8Gkw2w|?2HTv9EvpPZfg=(D5wR{+ z7hSfjGrl{}JuQ3E$2xiJ#>joKAY*}USK8KMAh=_Hmy6CcHopJiqu(WRHBB?jERj0r>$PoS!YnOWtG7@dPE{1BG#qqqRWjND~9r&aj*+aM!C#gaLc$cF{B#fZTmUYJXa!t~5{IFc?XiaGI)jQW zs|?=DKN1Ne=(1&<5o>TRb=lB1I)jQWs|^13JrW5c=(1&<@yzv`Q|q+osxzqAvdZ8u z*&~rKf-YOu87B|SNZqyMF`YrhmQ{v(Km9O*E?d?aM-I10t=oTy&Y)t;Dueg$k3_-< zx@=izBv1Ob-mfn_p);u1vdVDpjvq$QWy?Ba(b6(?HlH7^GpN|I%HZAj)&44kpv#tZ zM#hU@tUA5i^n;2ms|-FPAQA~9=(1&<@kyjv<{vA}_Ml?RDud5Dh(y8&x@=izEE_RB z^QD6Q^jJ}`<)9y14v2fJeH=eG2qWmSWu5Wbd$G*JZF}epDz>aL>h9eo=2cxI|IZ;l z%DXCsikDDyBvR(*Z!@n{#}Gx#Ct=IVb*S<-@m#*u@eJ?Tgi5z(5G?DAt9va=owv4E zEI58xmr`t55%vjysvL=g5p>zI&gft5$<*&w4%8V`Y+2Q7pA@V!!U(!-S!di={JPX# z`G)BXDz>cZwa*sT8DRunwyZO@ZfjWY`lZ8l1{GUY_1b3^>x?jhE?d?a*X?^~)%@8e zgNiMydhL^cZ zwNFpi8DRunwyZNAIhrTdU~wy*LB*C;z4m$QIwOpr%a(OUsWzo!x7^=QXHcUl zLuZ5$blI}bXji&sY}o#rO+Ruh6gNfg)%#cLQuW%;QFKNaL6x}1QMl9!3zhnmcT`IP$ z>ixV{Cy}q{!1%sBjG)Vwb;i-QJ!13JaVp55V#_Kcf7ScMo)PNvc2$lp?KgBfBaEQSmUYJGe+-RfFIh`xP_boIul*iRXM_=S*|N@vH5?ur zoHQ*sKaWtcWmWI$(P?7f?a#%>DvY4ZmUYI7{ljC`BL{=?^9U7NRvEv1c$*mZ%8T)g zFoG^y))^}{4U3ijD_3feLB*C;M)&&~h=xbi9WYfn5(y*dvSppIHv8b%6Z3oM3@Wy) z>OJ2eUGywFJDw3n&}GXyW2IZPkItZC%c@@cyHuSKM$l!;I-^ICGns!EYpXM;*s`kE zecv8N&}GXyBXMpJ%quFktTK3>5Q$W)IyZCPSABJ>=JqHlzsRqyrcf?hR`nJtd7a!9 z{8mQ&yGu~<5{g#Gk2Tk3eqU>t&LCmS%9XOLsNC~-B7+1KFQGG@x@%|MQ9qkAVG_2i zTyy2MvhGuf3=&klgwD7z);M+A*XAshge@!As2>W;rE3!zB&c`^ol)!fhpDs5_S9oV z!j_e*dyR+w$Io?*kGSwL*sCWsT5v)J84ugy+30qdKf9mFy zckh@O&mcj?OX!SX{i#)@Gf3F7a^>8cM~eK<$1_M!@e(>CSbu6&eH8SAge@yq=7~IV zMEyze3=&klgw6=opITL!K?Vt1R<2ij=9SM6d?B7ef{K^W8NvEft4e2(uw~`4zf0a4 z%v};xyoAmO)}LBcv7jF$Y+1SNFQ;_|2`XMfX9Vj{tty>C!j_fm*Z;dp)|jBKjnWw; zsCWsT5v)J8s&obkTUM?jdjqbc!cHE!HAVI}T z=!{_fsZ|wZL`c}Oa_yY*AK9|u)ObHgQ1KEvBUpcGRp|^8wya#AW-B7^8IZ^zLB&hx zj9~q#Ri!gX*s^jp>RU{n>XFDGLB&hxj9~q#Rb|Esby-@uI&Z&DMyn?>NKo+-IwM$r zYE|hB61J>d_BkzEgEdHkikHwC!TM9HN@tL;W#!6oLm4@wSYlq0pyDNTMzH?Ws?r%G zY+1Qp&rwc3)F`nANl@_;IwM$rYE|hB61J>dcaBMxpWd4|gCs%4OX!SX{i#(I>=Pp- zY+1SN6H&GX+k*rZFQGGn^%uM!4KhgBvT_|CSY93|p4hjOpyDNTMzH>Zcb7p130qdK zpSP8lzwXCz&=ORd!PS6A5(2vx&D0ipg0mW{~n2upyDNT zM)K-wGmpp5IZ4>Ea$Wbq0g-2LB7+1KFQGGbHQ8BrWc-|yge@!A*&p|dK|>N5B&c`^ zov|#laq8^&IVTBQR<2T4?-$jcN@S3r;w5y(aJ9yti=T6nuw~`i)95Gh_0&WL2`XMf zXAD$pykq>FlY}iRSF_1KitWo286>E937zq*TH{~E&pAohvT~jNeV=HxBauOZikHwC zSF3Z*@8aj2By3r^KI*wo)X%P-0Jt?+A0()F37xS(t-tJf%{eCtTUM_5SMC${-ZW^*1nn&Pl?SmFxBedquHni3}1{ zyoAmO&LBU%)0}gXuw~^s|N34rXLBNh1Qjo#GhR~buWS6AlY}iR*S2r=ilR9_if?lg zRJ?@FSfbY7(PQSElY}iRSD%!9;^&(Z86>E937yect-qP^b50VrtXzX8?-S2tBr-@) z@e(@Ygj#={cw3y!rUY+1Qpzh}Sbu|1JN zf{K^W8S1E(s*Zy?gM=+B*XZ&GM6(|f86>E937w&iY9FcNpw1v+%gQzX%mJ}yS0aN1 z6)&MP)KM){9S3y=30qdK5nmh>RkkKFNKo+-Izt`RGSzWVXOOUEkwJor zm(UsNs1{SlL7hRumX+(CyAO#Ga}yaPsCWsTp^j=XbsW?gBy3r^79BYxvJFpUkf7ov zbcQ;r#nf?7XOOUE<=Wr-uqb?QB7+1KFQGHkQ7xv9gZf;Jge@!Ax$TEVq(UNt1Qjo# zGt^NnrjCO;gM=+B*EhwFh?{>;96v}<@e(>i9o1s$IH)s7*s^jxT>FSf%S>dDpyDNT zMsNnHj)VG~lY}iR*W8E937w&iYB6;j)aQdFY+1QB=Q$#7YnjL(LB&hx z40TkCspFu|AYseORsF-mqIbDO1_>%<9L>T1*`W(}Mjj30qdKN_QU?n@%R)Cz7Dz zC3J>5s>RfCP-l>^W#vj&i| z&QM3SOm!U886<33x$Ifk*5Lgv2`XMfXG~D*?}hmJ;1{QV7xQ+j-}9-uY+1R+HUCXC z`N;gc`c(=DDqcco^!xbQ%pLLbK@zsCT$QK&D)uZ+WRRfZC3MEY`aA1B6+a&&Vav)@ zWan}5{gOlm2`XMfXJoE!ocdJ!e2|1KE0_I+I@Q8yoAoU zL7fjSkDm{cuw~`ivhbkzbffwutIi-n#Y^anSJnDE9sdrJge@zV{oTIKAVI}T=!}_a z{WXf850bED<+67c&>1ACcnO`cN3Fj(@$*3vwya!*a~u#ka;}Jv6$vU{LT3c)@2Upo ze2|1KD_5=p2gI1i5*Z|@cnO^`Rjt2f@$*3vwya!foezj__arh%Q1KEv<0ZBJ9*KVk zNy3(uD^JovF{9zi#5pGjDqccov{dWw`S|%D30qdK?xzllcNQfwNKo+-I%9)ce^cY< zgCuNOxtf+dBx;>WWRRfZC3MDr)cN2~@$*3vwya$53^^>O-}YX7tVmGt5;|j^T7R+l z`5*~fR<5(zkBasE6B#6^cnO`Mj%umuI2a4wmyob!U{86 z{CtpvEi2co4!?-8uO%`_Q1KEvLmkyVQmab$gM=+B*RrxF#4`&M86>E937v65oe$24 zpAV9-W#u}y{Wp>NTq1)66)&MP)KM){9S3zkNZ7J+-}@44kOUPkp)-o9^TDs; z=Yu3{S-Jkc_b)MLd?JGc6)&MPmZdZ&W@lCRR#hkf7ovbjDn@{%XX} z2T9nna^-mMw8)Gl_U$C7cnO`cQ?0+6>iuZ2&Pmv^a;-RhT6DT6kwJorm(Ur(=P`5C z_Y*+|30qdKPmY}yd-tll18oi7Cz7DzC3J>5s>RfCP@k)juw~^MH~F-9pd_8G7`g9H^Xp)=G`EvAlx zX~Fg&Vav)jboU?PrUw%56G>3<5;|j%T7R|G`_UkSge@!AwIfc6E&oYmkf7ovbcQ;r zWvb(#&LCmS%4N^Owg%gS1Qjo#Gv4I)gLfv&^un2Xj+RZ7mFtUj|&A&$?B&c`^ zow4GRYctoz&j(4^vU1HFSWXW5dsTdWkf7ovbViQG7p_SqVav)jF{zw9cqWlSf{K^W z8NaFT2i0*6{Q1KEv zE937zqUT7SLb=Yu3{S-JL=QvG-*kwJorm(Uqw z)%oCt`1v3STUM?=&X$&w_9rq(Q1KEv<9D_G7RAgpsU&P!xoR9MEyos*#n&JSDqcco zJgv?Li_|gagCuNOxeESTS{6)CWRRfZC3MCpwf??ZZLUcrVav)jBv%g}B1Qjo# zGuEs1*C+n{APHMmu8md8$W|*786>E937x^SI}*06T$?(Uk!OEQWRRfZC3MC?wf_3W z&j(4^vT|)%Tt*g3O8k161Qjo#Gis^z_hS5-R1&tVT(6%mBimI=WRRfZC3HqVd_PFS zmX+(vhs(+X4H6k7sCWsTp^j?y`#}=6tXz+*Eh~4mN@S3r;w5y3I;y3r<6ta!&p^VK zm8(Uyax&I7kwJorm(UsNsAjK8C1K0Tl`*xPOmCCOAVI}T=nQpKv*&{(Y+1RQXG@kZ zw@74=pyDNThB~Tcs^g#@D-yP>Tqimv%iq%y86>E937w&iYB6;j)EOjfS-Eaqoh*M# zPGpdv;w5y3I;zFgaZqQFuw~`ySTIHQjwCWjQ1KEvW25>!rk47CBA8bsY+1Q-v`CR7 zwi9o1s$IH=DDN!YS-?OUEA zE96aNkf7ovbcQ;r#nf?7pR19uW#t+;D@DHbP2xQR2`XMfXQ-oEOdSVx1_@hMu8MkLR_kf7ovbcQ;r#nf?7XOOUE3o#kJ{62H46LB&hxjMvro^TD?b!8Rvh z%gVKF?xS*ik3QC-Md2YlW->R)l%YdOiDZmUbD}g-2_;cTgUWD< z5T!H^e(PHMUhDVX=eh3V zWv&NF#M-&yFHUWceU}6kmGBvIKjvSV>p>E+cCPpfS3ZLT6_xNAx4P@Whcfd;NyOT@ znlI0_WA}x5;UuW2gwJ@x9e+bzf7BfwBS^&Bx#kYdwb!%_^V>;KQ3;HiHBemGBvI{JEoQxhw~XSUcCj zoX+-!ypTbHic0v5!t)w6YMr?rBoS-p`s&NhcH65Vg9H_o@EOzH@z*$WJxC(f&Nc16 zF1GOz@mU!VR8+!eobHalhce@XBx3DcueQC(_P;P>kf5RxKEs{W8oKkKY>xsYV(nZv z)a+_kUmr3^P*Dk=@v1xiHfOE}NyOT@N*>+Kp4T&Ekf5RxK4a09TV5TR86PAOYv(Gv ztDC*Bd&nR`MJ0TOJF6{o=Rv=&NW|K?mb}s3?!Gc)kf5RxK4X}>AM;k`dXPk{o$KOz z^X$*3hYS)_RKjOG=8nI{nd?Ckv39Ort$Ns5`@``;f{IG`40l#r?#_dLU6F{jbM^bF zhh6YU$RI&QC47cEt1WluL7zb)*3MP$&Yre;i;zKric0v5Vea@_n3*q1BG%3|b#G5w zcW?OKB|$|ce8zHj{Ec?~Q8@-l#M-$U)#+vP?hF|usHlX`aA&pU?mXx-NW|K?PHfZ5 zmM#-ANKjD;pW)7G%iVd`eMnGI37_H4YRjc}Da%13*3R|Kbv)r8JK65=tBG%5;v}_MMd~@hilc1s! zKEs{WmbvqwUsohz?OgFHY=iXSNKjD;pCR{SWVAuH#{>7ZvfHjs#+PI5Tm{c+W%pbf z#+^w}Q3;P*3MPtt(LY(gOEXjic0tlxgR5=4YC|0V(nZPibSlPtI6Xn?BMYs zg9H_o@EI~bFQW}EqX3CmJJ*&{Ep4wEA%g@JmGBudKJP}|eFlkGJJ&nITH2QLLIw#c zD&aF^d|pNyWI0I0+POadvZdWRCuESIq7pts#^+_UK{80h+PPM@Xl2iMAY_oBq7pts z#^+_UK{80h+PS(eYGp@_3>hS-sD#gu`PwqtAQ>cL?Oacn$gy{J4H+b;sD#gu@p&0- zkPH&BcCJs`=h#CwWRReu5_6L?bp9&cysHlX`;AkI-SUXpp*6Yp7i$ewpDk|YKINC=d*3R|o z%=b*&Z6SjM6_xNA9PJ|!YvRC42@)`$)vvxoQtzWs2OG zo5>(SMJ0TOyUQ8J2T8=*xhjucWlA^boXH?TMJ0R&NBc;`+PSXZy2?CV*8SS<2Ki1T zK}98e21oly#M-$|9ktrj-4!xOP*Dk=!O=bvv39O;z1}uAEx0MO93-fygwNn;ABk8y zSKicjOpoSWGZ`ePsD#hp_#lZ`JJH(LNHfcCIbmJ~1=;hQ1F8Dk|YKINC=d*3LET_K!{9MWGKz zf{IG`4374Zh_!P~yXGU)qgcowK}98e21oly#M-&){Q9ApeMjh1lc1s!K7*ruBx3Dc z@hWV?e~u4QQHdnOjStG(3gw!!$+^AlKNijN=hRp`*R${SvK8kfe|KY$AgHK>&ye>y z$=eDggG8*IYenZ?w*G@5g9H_o@EP(xCmC&!3=*++t|hEvgwK%oImz1! zC4)q)o$Ia1J#EKFLIw#cD&aHaeNOVWLdhTzYv-z7tEWBs#gIXQic0tld7qQKtxz&Z z#M-$&f4_$y$=eDggG8*I zt4zZlc4+1KnSLS(Dk|YKWVBD-Rwx-HV(nZ-io4~=2^l1)sD#gu(LQ-wp^F$nBG%4z z((XKa&8Uz;f{IG`40*q=ysc0&NW|K?+J2H}Tf7)DNKjD;pCRw}mA4g228mcZ*ZH62 z*-iUG1_>%E;WOm@zVfz0$siGH=bCjO&o-~}NM@UpprR5!L*DNzZ!44x60vr!{pEVt z3Ri^;5>!;eXUO|~a zv5-N6ic0tldB3l`txz&Z#M-&m@9kl$zZ)`0P*Dk=A@BEbPT?Ofyk=xxuN6*5RrQ3;s|*EnR5prR5!Lq_}L?e&sDBG%4TX=)#vcU;IIK}98ehP>Zb-d-;m zBx3DcU(WAi2YepRQ6#9SgwK$-!^qp~C4)q)ovZNNK6dY;A%g@JmGBwzeqVWey=0Jx zwR6p!*vH;{bI2e;MJ0TOyx&*eUN0FWV(nZly7aO0O~@cYMJ0TOyx&*eUN0FWV(nZ_ zYxS{*%7hFOR8+!exU<@Fd3(KNkchQ&HTkNy-Lp6JMM+Rm37;YF_m#KTO9qKpJ6ErJ zd)panLIw#cD&aHa{l4<{ddVOWYgrCl!?{^=AgHK>&*1FO>K6>OYpW)6Xk+bMli$DD zZayx|ttCN4C42^Ff0Br`bIt8~vprZWWRReu5EvgwK$xyD(pr zM68`_XGymlD?$bdDk|YKH*`Fk0?Oa{&y4kMn6Ea9p zQ3;>H*`Fk0?Oa!Xce5?qC1jAGq7puXvp-41+PMz48EE_FgbWf?RKjO)_9uy0J6HW@ z2HM`|g$xo@RKjO)_9uy0J6HEZ1MN4*h71x^RKjO)_9uy0J6B;l$o{o6e3y`*q7pts zuI|EoQ4+CsuHyy`vU`_?3=&jS!e_|UU6?OQBG%6J*8_uWL-+PS`(KgiB2A2LW#Q3;>H*`Fk0?OeA^8f0tk41ER? zR8+!eaP}vOSUXqEZi8&QB_V?Z6_xNAoc&26*3NZ$?Ll_w*pNYjic0tl&i*73Yv-!| z^*}rK#*jgRic0tl&i*73Yv;OR>OkANLC7FMMJ0R&XMd82wJZm&;nMR(si=g{kmFB! zmvYT{$t$_G>hF2}zIv>k>*=d=?S*daAenzff{IG`44JPjy-Ud;5o_mqeQzf_;GK{` zf{IG`3_1R!cPSYpV(nauMs%_{YeNPJDk|YKWWKiaE+vCRtexx4vYqV9+d~EkDk|YK zWWKiaE+vCRtevasl8&}m(H@!YL4t}(_zan^Exk+0AQ5Zl`t;h4wxkIeB&eu_&-ldM zkCEP`WRQrpb3Jo(M|!;eXUOxr(z|pKBS^&BxytqLU>D8~86>EvgwK%YcimkU zpFtwl&UIC%4t8qMUYX?}K}98ehCIJ3y-QgR60vr!I$b*0`2#}+2`Vb#GvxVQ>0L?& ziC8<=%wZkul+Qy32`Vb#GvxVQ>0L?&iC8<=-Z>rYIi`1JU6G)o5lP%!JK$3GU2`Vb#Gvt1Z^e!cXM68`_Oo?1u z<=&7%f{IG`40(Q6dY6(xBG%3|a8Ry&@s^N5f{IG`40(Q6dY6(xBG%4T=965TcU8zB zK}98ehCIJ3y-Ud;5o_macV1`PwL-`sK}98ehC8dp_luH+>_R8+!e z$n(4IE{k6d60vr!>Z?23ad(Cc5>!;eXUOxr(jS#|MIzSDb!;eXUO=x%s!Ll zAQ5Zlsxhy=T~Q-skf5RxK10UmW%ik5kchQ&mA|mQom(qpkf5RxK10UmW%ik5kchQ& z)m&H47PldT1QnI=88SXEv(F@hM68|b?jH4QyS$J=f{IG`3>lx7*=LeLBG%4zX{mbl z#{c>2`Vb#Gh}>TW}it0iC8<=@LTKJdi7gm z_FWQGRKjP-_`J+MlME8EcCJ26-Ezzb86>EvgwK%q+A{mhMT{U3Yv&qyT3!3|p^!m> zic0tlnXfIg&m@CHtetCF*}C@2yq1}DMS_Y-_zbxpBeTyWgG8*I>!I>>?GKwm1_>%E z;WK2uw#+`03=*++uA|PbYyaJ#Rc1LzP*Dk=A@j9m_L*dmh_!QF-L|eBIX7gGprR5! zL*{GC>@&$A5o_nVc5+?2=8up;f{IG`3^z}$k<31m3=*++u6CR2+8>+eWY!f4Dk|YK zWWKh{K9dX*v39Nt&ZuXnP7WC)sHlX`konr-dXPk{ovZ!0dUnp6A%g@JmGBwvtQM~a zNyOT@4(zLE@BT7mkf5RxK11ef%j`3^t_qNdwR3H4Ti@omcV;B#S`t)L!e_{QZJB*0 z86;xuT>IawZwDL*86>EvgwK%q+A{l0GDyVQxjwJiz!v>1WRReu562$siGH z=el)r1N+jFkU@fqO85+!uPw9BB!fh(oonTu2KI$pLk0;dD&aF^zP8LhlME8EcCPR0 zHnfY+4;dt=sD#gu`Pwr3OfpEs+PNm(*3f>uJ$#ptprR5!L*{GC>@&$A5o_m~@oYo; z+^CR2f{IG`44JPjPa{bNiC8<=*bNQs$rVEe2`Vb#Gi1KDJdGq7Bx3DcSL|qLYcC1s zC=ygu!e_|+7EvgwK%q+VV7#WRQrpa}`?C(4Mm`^chG{ zQ3;Zuz6+Z}lQ4&;C!e_{QZFw3=GDyVQxi+qEVDFd|GDuKS37;YJ zwZruwiCD{W;2JLdd-POP!e?-_uR_~n?ETj^_UEElJJ($YO4`RRNdBJw{Xr@!;WIee zM%E;WIeeM!;eXK=KSM68`_ z+#|*9$ge^M2`Vb#GdS8uBG%5eyHj!7{-P$C{uK!-D&aFY+D9VR&h^DvZaJof3=&jS z!e?-_k3_7U>p+R(w%nf~g9H_o@EIKKBN1!oI`hwBws5!0GV6*26_xNA9PJ|!Yv(Fn zptwDLL&zXOMJ0R&NBc;`+PMZDU)&y9@AAxYkf5RxK7*ruBx3DcZ`Chu=g$fmB&eu_ z&){euiC8<=>Vd`WH@}7q5>!;eXK=KSM68`_%`3%i*=9{M>xu*wmGBuH?IRIu=UPyz zgnj<*kU@fqO85+p_K}FSbG_TUgneUq$RI&QC42@)`$)vvxjJqvVV~L_GDuKS37^5y zJ`%BZu9gi-x@)zNL4t}(_zaHrk%+Z(-T1GPcIy6+L4t}(_zaHrk%+Z(wJ3dzJ>!#* zL4t}(_zaHrk%+Z(eKYVFyJb%E z;WIeeM3=&jS!e?-_ zk3_7Ut5QxW+p}WGAVEbXdlwyN0rYY5o_nVZ19_A)!dLlf{IG`3>lx7-lZ%DiC8;VjX7_a`HzGQ z5>!;eXUO=x^e!cXM68|bigmA>k}ro05>!;eXUO=x^e!cXM68{wM3L9c4ckKo2`Vb# zGx#(hiC8<=tvSn0#}nIT`iUf{sD#gu@p?%K?{B0)tZe1?qAOYhP} zj35zf=lXTTYv$J>A%g@JmGBudUt4;Yl0hQY&egZmYi8H>kU@fqO85*J?UUZ6WRQrp zbJgtjn)#{ub(wWVf{IG`44JPjy-Ud;5o_lt=7wh_!QVF8PL;+&*NGprR5!L*{F{yDUC~M68`_@%A@Nn_eM<1QnI= z88Tm6dY7^sBx3DcA1r;-49W``B&eu_&ye}r(z}!l60vr!XU4BE#jgq(B&eu_&ye}r z(z}!l60vr!eK~KLS8Ig~5>!;eXYgr260vr!+l#C;FC7fW2MH=F;WK2uw)8G#IY`9X zxi&qz(!HNLWRReu5h zS|Ni36_xNAGTJAj4U$13*3Py5yH%#j8{u3_f{IG`44JPjqYaWlBG%6J`^r`3+-pMy z2`Vb#Gi1KDj5bIHiC8;V`ys2$)PtdaMS_Y-_zZVei@!HPBG%4zO_5cm`Sg%Mf{IG` z3_cA=BG%5;YS>CsxoOBCK}98ehRoM?cUcTW}ivMw;zr(B~QN9pSNS}Tq}!>GnIe8C38L}K}98e zhK$e4>@&$A5o_n#eZgI({oas4f{IG`3>lx7-lb%ah_!RQ+i|R^yFX-*prR5!L&oQ2 z_L*dmh_!QlGii)@q)@UB3ltzhMJ0TOjL*yLGsz$kYv+1;^=R|M86krN6_xNAGCnV} z&m@CHtevZ3>Cxur+>k+nic0tl8K0NgXOcl8*3PxM-zf9jVn33kUcDH4Y4-!;V!e_|Uoy;K^LIw#cD&aF^zP8LhlME8EcCOM@Mw;7e-kw!;eXUKeQnSCZ1Bx3Dc z@0~W%{PTg3L4t}(_zan^Ewj%ggG8*IYi{e2=GH?Yg9H_o@EI~+TV|h028mcZ*Tr*3 znv*);ky%$HsHlX`konp&`%E%O#M-%%E;WK2uw#+`03=*++t`>#Hn3HYD zAVEbXe1^=|mf2@6qX3CmJJ-;4V@#PgA%g@JmGBudUt4CMNd}2nJ6D@|W6h7(hYS)_ zRKjP-d~NAnN(PBoJ6HdqcbT!*g$xo@RKjP-d~KP1CK)7R?OZv{#+eUVh71x^RKjP- zd~KP1CK)7R?Oc;ek2f{yg$xo@RKjP-d~KP1CK)7R?OYY#9&b)RC1jAGq7pts=4;FB zGsz$kYv&r&eS&HJb2!dPP*Dk=A@j9m_L*dmh_!Pq-Z#PYpC2+vP*Dk=Ay;=YUrjPd z#M-&uZ8Ona(Kuv~prR5!L$2=JdC+H&h_!RgpEl9Fur++Qlc1s!K11ef%hO1*93*1x zTs4EvgwK%q+VV7#WRQrpbM;*`(Y#bFWRReu5xKBG%4TZ_0RcVot~) zK}98ehRoNNr;#LsM68`FUWILt>p>D!RKjO)v@dtgAhZ6V`+eUa*3NZIv4Q5}3CZ8n zzdpF=BJS%g9H_o@EIKKBN1!oD*r-1bJOUML4t}(_zaHrk%+Z( z-EdrAQ+{&DAVEbXd+;~gP`1QnI=8652+5o_m~{%)SBQ{sV4f0qOmmGBvIbr;45NyOT@ z@(y)3jq8OB5>!;eXUNrE7#}1NYv+1tNOyB=pO8UH(LNHfcCN7_dzr1zhYS)_RKjO)w2wrro$Hj}dz+iqhYS)_RKjO)w2wrro$Ka% z`L$RI&QC42@)`$)vvx#pK0Z2G?)GDuKS37^5yJ`%BZt`(z)n0`-& z3=&jS!e?-_k3_7UtKZ6@X8*X5L4t}(_zaHrk%+Z(?O8v}6zmW(NKjD;pCMOwVSJE8 zteva;%;9E#?T|r&ic0tlxw;GEgCt_@Tx+V{VygZb&L1SGsD#hpXdj7KJJ;vAx0qUQ zhYS)_RKjP-{g^O5NFvtGbyM40%z`N)g9H_o@EIKKBN1!oT2}BDbLNd9g9H_o@EIKK zBN1!ox}(c*b7QTLL4t}(_zaHrk%+Z(4IDkpy!2P-Cz7C|5EvgwNn;ABk8y*YD+qn5&)-86>EvgwNn;ABk8ySG)?_@So#@R8+!e$nht=OS$Ge zxbk6B^vx%HKPuMF_0DfIO_@c>-_y?zQc($?A>;GXyOazPv39O~r_MCzJQgxYP*Dk= zA;+KeE+vCRtetCp&O>I-;~|3t6_xNAGCnW8OUWP+Yv(#}`wVmS^C5!-6_xNAGCnW8 zOUWP+Yv)?Lbh`QT?T|r&ic0v5)YE|YtVlaom4egFUtfj{5>!;eXYgr260vr!wH+Tc zBaVJD({Cq1MJ0TOjL*BH%C9RDv39OWTc(-bbwUOSDk|YK_%tAiSUcB{LDS5LP9cK? z6_xNAGGAMImu{1fAQ5Zlnsv@JbH&t_9X1^jqMJ0TO z%-5FQrDTwZwR2s1?=*AlO(BB>6_xNASGn;)>0L?&iC8;Vvw{zrB~wBM2`Vb#Gi1KD z^e!cXM68`FXYzw)&C4N!1QnI=88Tm6dY6(xBG%4T_`>P#+8|_*prR5!L+-~&?@}^I z#M-%9|1jOm{xM{bprR5!L+-~&@6u%yAQ5Zlx^3AEbAREdGy4?@Dk|YKWWKiaE+vCR ztexw+DG!;U$Ak%E;WPL& zAcSoF3=&jS!e_{QZ5f}CZB8QA&h@Xm=9n9+h71x^RKjP-d~J7^#b=O+ zwR4^Q=p55+e>g{xprR5!L*{GCXoD;ViC8<=pt*C*))zwt2`Vb#Gi1KDj5bIHiC8<= z+`)59_t7DP1QnI=88Tm6MjIr9M68|bh|}ko2U~{>5>!;eXSlOke7`7(SUcArOJ|#d z)j|ddDk|YKWWKhHHpp_2h_!S5RAaXJ;*ZeZB|$|ce1^=|meB^uAQ5Zlx_IO)GkHtM zAVEbXe1_bQkbm1^ZsvM$!M{t{tqW%O^Ifc+t8Lv< z_M!2~-wPBVK}98e#y&S+^z+R1Ac4Z7FG?cT&NcM(l6LVuA%g@JmGBwoyX(Q(nd?Ckv39P$BTLvpi$Vqo zDk|YK#<=nMcA5F2Bx3Dc&G!_yRkno;5>!;eXN+*i-)EWmq9kJNTu*l?ZgWn0DAT_p zK}98eMm2Z*t;k#tl8Ci)E&Q>VJ-buLAVEbXe1?qA7s|{RB@t`qnlh)DUHDAMAVEbX ze1^=|J}q-SNFvtGRkV9C+v3QXnRP{iic0tlIsW!!-Y-fb*3R`ti(>Y^_924=6_xNA zazEy~rpfgniC8<=xYot&n&(3X2`Vb#GiJE!!P7GD7bOvE=elTcF9)>_`5%IJxC(f&Q;F67pL`;A%g@JmGBuK zx#Mqa=6aAstetDX#NxK{w;_WB6_xNAZ@S~JdggkNM68|bys{UQ@wg(9+D&aFO zcE{h;%=I9NSUXq6B_(X_D?JjPBN9x_N!Q3;>n&T8>`kVLGVtJ~|x*z<;l3=&jS!e?xC*Mkpd zt_MlP+PSXiTgtZY8Zt;wQ3;n&T7ludC+H& zh_!Q_Jg>C<;{K39f{IG`44JR(&V&9sibSlP>ztoU+q}y{1_>%E;WK2uwmT2{3=*++ zu2*UwXW#rjoIglVQ3;p>E+cCL68 zwn453Nl;MsOlEwLM68|b=!UgzyHi322`Vb#Gv0LLgR?W^ zgCt_@T-7F@WzRh)WRReu5^ggBG%5;?%i7U{Z~Q;2`Vb#GkA4JBG%5;x_vFX zsNm#GUz7wDmGBvlx#RDL%aL>ekGkDz1c_KX*ZD8iw9T%$ zC$l|BP*Dk=;rgMCq<1M9Bx3DcUwu~7zWP+iAVEbXe1;r<(z}!l60vr!yo$B#8wKvo zEC&fHD&aF)y5sMm%=I9NSUcBSx74y5nuiP$R8+!eeBzG3(V6Q(60vr!ir?3=b0>!k z5>!;eXUP2+>0QdYA`xrn+IHKSw)*OjL4t}(_>7<2@%OLH^&p8@JJ*`>XW3^CgbWf? zRKjP}cgNqH%=I9NSUXp_x6ZN$OHRpba}rck!e_|wC%sFzt_qNdwR0^PSlgC6DP)kK zq7pu%g}Waky-Ud;5o_oA$7yHVCFMc}2`Vb#Gvt1Z^e!cXM68|bmk-ajpA`-nB&eu_ z&yeF!dY6(xBG%4T@YZu|`JG{#lc1s!KEw4xmrL(bGDyVQxvKr6j_tKHWRReu5gr!JJ%OCoNIUQ3g5dVsHlX`aA&pU?mXx-NW|K?x;=2NwfBV#5>!;eXUOpEvgwJT`?#JApxgI1DYv+nrVH@OnkOUQ#@EKpb>p^#4)Gx;irx&;P9U9}$ zcd>S^?spWkE&rYTy+8pHR8+!e$nht=OIcSWV(na8))lp9Yz`SDsHlX`;ME<8SUXqm z3PtUtk3$9tDk|YKEv zgwK%UPkNWKu1Lh%xt7)~Y`=UtWRReu5TMjIr9M68{w#`T45;lkrH>xu*wmGBw7x+4*5=Nk2XVY}(_ zkU@fqO85+3-I0j3b2V;X#9lihWRReu5HZMRT*3MO|O;LNrrjS8`ic0tl zUfq$1wQ~(Us+isNLC7FMMJ0TOyUV%E-52%CK_b@9)qY7aTk7?YL4t}(_zXGzq<1On zibSlPtLyc}ZHw6(rqo z?11w_1_>%E;WK!3ML4t}(_zXGzq<1O%6^U3oSDDErZS8|N4@QEDO85+3-I0j3b2Xn( z(*80dWRReu5!;eXSlnZ%iVp^Mv_4y*3R|X>Jql!BO!wX6_xNAyt*S1Yv;X*j*3am$@D!5o_m)S796EdXNMamGBv|9g=?| z8m-^k!&ZOy5&P1U%`W}1X;1samq~p`o6dG(n}z=G!7cxfXta31jpqHc7I2{6 zXJ+|&@_Extt4Z?|qTdS-m|C~D_ez~Y3(a{2u1@H?7MW9DO#YtEm;!}F^Il6$@BIm# zCbq4=!(MpAJ^pi_X)xG!o{-cf&K_pRR{y8csw3~Y!}e%@zgNB}aGPCs*K}X+TGr1# z_r(JWalzn|?L}QzdgUK)9A_WMOX|Hp9BAdgt)k! z(ygLGBFu)!pFx7IEz|yCuevoArWT( z=FgxK=I{RR86?8Y-254A6r)#gRP<~%yrLC@H->S%oG>DW76x23W+f1GJggMx}JZjr0uju``!)n1?98C zygsS<9g}VqU165qe<%1^B*Of={L4XtE}r4it>V&#`J(c<*_WIOi7*p1f2&B)73Ov3 zC)fkvSwH;BLw+Ls){-dUH<6^y-iM{tOayvHzG}yHrSoUpva5L4vOE+eP^a zD&g0M#Klj_-YOE|cZKq2@U!R&zY>(6VDB#cc8$2gZ_MN;sDxjM5f?uxy&P0Xgx`P3 zpFx7I@M|vl2`b_DSpN4`rHIULzU0qftHSTGh>LrEddaDf2*0$FKZ68a*^el0+we(ygLGBK!tZ{#KEoi)$pEL4`#44W|4VBz3MELcP{23(Z3cm%Cp9sGgB1-t>MXBq&|F-$|p39Xb z55ET}uJF5kQuDhqy>_XP2*1cDbasL+e&?qNwmtm1<9}ZcE+L8VyN&rz629@4DHp?ell`L=snjce5?qMa$rx zNEeTS^pdl^Pw($=`-Q-cEupwl1oR>^8`@TXMK1=Q<&AdhJ1W>DYu$w~7Q^)xRES=iaCh zTn@H(-&qb4)h`%m*H+asxEyq`h3O@yLSpj!H`~p}X&EHw z%D&{4$F4G^8+7*D_WG@>%+qDN`1+E+UNm)bdn?CwEaLQq+MV2wHdqr}BeN^cJ;B+3n6YbKd)N(KqK ziaq+7nRm({g`h&>`pWCfMdP##5_G-t>3UP9pOjv5DkP3>xzXG< zSj!+mSEYTM%!Ac5Vo2U*v-6o`8;n@`k@@kYq@MA}E>mbocV%5sA#wbBADc^hYkLU^ zy564qiK+NlvR9^;{FK_Cn%h21j*k!eeQMtOCE3HT8o$ppeJUB#NfT5^Z0qu=S#hFv ze2}1PVewDRsg1OZCdYnY-hAo?zfS73UTRw$|;SWbm`-;`MGig9?egC%g05-Td}MkQ(+Dbce*MtQz9ZQl{G{xy zBC)&QCe!42ZJYD6=;C%tXHX%r@SP3jp>>Db6Y1hnkj~(EEqk)PTJ^BA_G{y{tJ~(< zr&lKZsMl}EwdbCn^jJGTd$qmvP%_S)&YnHoVtY)pp=FSui>*y(P$BVZ+na2E_uNGO`wS%L;#x>&aGjLh)y-bmJ^5UIQktMbV#yob z?d~fN*DAU$zBkYQe7Z(dYSGKyJwMqKM^)-&8(xsqywXp%YU8|ac4F^j*26n1y4rF5 zl6qX_8*RBJcPZRXzwfiQ!dFue*Wh!vv)+Iob>WeQ*>BTKR0}jnQ?JKr!)9j z%&2k29<%nKmch?rM$40ToAZBPsE)n8;*F_ao6*a(3=(u*dBtusa-K$TEv_rN z*Iazn-`O4{YQM6_^sAz64{kxavhRu9+qqX(zV2(Y{a$U~r9$G5Bfc@K25H9!3A%b8 zzuRb}!_v@NNNme^%xUalSI6_5MMoH-_0C)=8RX*NBW)cmCE86;Xw{kPe?L|eQ3&fs?m zkLGj+6%yyJ`L{XngtoVnpo`zy=?oq@kM7-V3f}Q|j#?65_1k00T&=Z=M=f1{Zr)=G zoT?Gr9^3|h{QE02bhx&5sgTIN%}LP3Gede^Q6bUm$6e;RN45Qm1YOzBIENnJZsx8_ zzGXIkxZRX1l&l}_J?U0aA<@6u4)gVS+S(;S7teO-j7N^%VXi$VY1P`dwwo$llA52C zCa93OWWjcG;&km>lmuN|Bk2qtYrp=m!?gYQ?;N!xUhT8PG(JLW7562&xJJ^gI`zBv z&5)Ot_-~&wg?5@kM<(As{G>ENg~U;%cA9ZFCvdnzP2XFuJl8;ks6mOhoV_m-_cne(ns>KgxdgsqzQv|pw) zLDvZ*e>Cg=aX5mXMdH0*e=zg6YRf@_uHRbyWFFu4q|z!XBqp@}-n4jC%OFA58PmTr z+n&&f<=_2c-Yb#pKcBk#lB1J)!qi{QeFL@qiVBHtZGJann`uP5?|(Eu)Jl32H(mU* z`E5t??VSB-j>~qIvj@*jz5!nN^;gsN%H+7qoWhbbR_*b7|_TC}) zDH$Z_%Dx;_Nc`N!y#ss3R3(E1U0jFh?ZI`$7H&PFxGnUoc4wOki9+j&+uI9k_Y+Cb zwV+lBoAe@maFGf0wa;zA#c*aw;U|*%NI2G1`3}5_FCJqKsX%LL;bjnO@pn zcR_MrjGvTVyHrT*9$m^V{Y1N~MuIM`w{!*-5|=D0X+QjzwmnGDm3@2g**3E4aRCex8Hr0d=sU&AQckft%X9T2`b^ega3O5 ziEWv88|KeotLO^v2h2}!{e(B;i7WfMqCz6P^Dch|3A(}??D7*-!aL~x_g0YzZaNR}}8M;a$A>2`VJQ8-nu_Ob_oP6Bk>X z-V>>i2yYt8pFx7I@ZPZeM0gvXDB-Pj|9h)Qg!j?q&tR+Q;_Nc_~Xnk{vm)=wlsS9r&B{tPN4E-GKuZfL3X6G_mOeG5_{@y9Kd?V&DO4}b(+ z+HDcveQ>B%Q&`DAFCphALAxMnBly8Nfp?fS+4Qnm*b63qsjXn*XT>^6Lk_r7hARsoy)Pl^yi^vr0y~29j=a_zcZ|*Z8En~*rIriNblck;3ILAJJPg3u{`dVA_kLQ#nr$XYj1FdY=z6qV) z<|OFKzILgQc;LQPcH7lj1_`>jWz((V7UWjDwr6wO_D3y)TkzvATiUI2@^8&_2DciC z)h$}tGak^k2MM~mE^1{*jnoJ#PnXECcXs_dts?Ph`y6}7Y8h-5T|;N**yB#rh_(f< zv@bMIj){GHb8N$MNzHvBy{@Q`c=)Xx+jpn7JxI{SeL9`NWBbVKTH3)4lh5VelP0K; zIR3j9wq{eURV3&de0K}GvAss{`(sS~=624M!+n=)%umXmL89?5ZkbwYdkH^_u2Y(~u;2C7h|wF|KDs+;Z@+^%_PnJ@ z&3z%=Dk>z-Kk`c3V5GL>BO!u^V_F0-23 zOIK+Gk4~;P9?j|HphALcBs)RZ;s>v_qiSk1IjE4haCS#~{v2(44Bb1>w)$wEKNpQ$ zd9yA5-ebNVe1Bj2=pR~NlnRN{F7IPE-=vM#lA!C7ZQbk%&uZtvmoB*7mVR=EZ^^$_ z-(pwnnC)w}HodN>km%iXsJ;ICM?9UKpo`0tCioO4pA6(vn`wdyi8(*sZVx@7jT?}l zi|_GEXEeF8y)E+iRelMNF4)C(sMy}uWx8HxKisH2iA04&wH-a|zSi0kRV3&-e`#;K zXh9EU?NTA}-S&RA?>W5>L(p~aq%QWAWp^k96%tjy8)V;~JNPgJU3>;Jy>_XPD12y` zt=o8nl0kwlZvS+~l6ej7lv`W)&w92;L))x!QlEVGrFPubOO=cR`|8=dzs&K<*0%L+ zj{CNjdn6bAQr`}|^=gHnLSp}$_3eNI37u}$Q~ev*o7*+_pVjhGV^8|$CBELczJa}C zQu6mSL4`#2^}{uiUJfcG zZk^n~zO>|UYnQH-dm7jmZq-s>e`UgohI0l-dh{mN=*;fDz=wIp*0QdIop!frZY&;#qY5+ z!S)_?c3u1L2FZHk@}&tXB(82-*N&W<(Af#Pc>JdcZrktbHnfY+|2z8?iAlFLv>$KR zTE#t)t{KlZw9k#w2p$JD*VVJdZE{TTxJfSu6%u#%sAt>dX-58#PD0|+Isc1qn6v8u0Bm&-VBX6XL?!N_=mcFOBKDM zihW{OJzo!fqP$)BU=w8vQX%orZME#@<=l6#JNu-UoCIC<_SCdhkJt7qDkQjk=?oHd z@jE6>P$7|hU6G)R-}&hbu3fH$VqcfAW$#MXbef<-qOJR_ly_HYYnKFF4_^;2RqJ1opsV2bTTG`nl3r$d$*GXwd*iYbbn#tiX@Uxg z?C+o>K^Namm(JiD*Z4jx9 zd$-L*b4BB%KEJ~QX7!<4l;gZbp)uxUn_MpqT{p&*X_M4-7Ed(wtB+QQoMz+92Q3rV zq|)O}je3V8_*o<>zCGTYeo8{8mxBadgSt;J&3{goDNV5LZRU+NKVJWLT1BG&(7Vjo z>kii{y0}Ktt-5&bNOMx>q`iGwG&65Kn!LekZtIce)1_x!G=c)1}yeYzQG?s?-jUz1KR2Ne>ftBf?a*VHmd(3QPaTvts>k20Mz z_ZGMo(ygLGqWSDm=CUH%x*|bW!OKRQX{T!hkD~e0CYl$vCQF9mkrw`?a$H3A(bcE4KH$izb+*QYTLZaT3@#e%FZOKW{#nz@XsF3*f z!*QnM$yx>py13TU8T`)RS(M)~X@Uv~p6#*|bX9-ZnwP)P?o(4C@%q?CX2>P?D91;o zem%{W_Y$SoHBHRr-z4|>ZEjjW zP01iZ*Uk6#HSM+?j_9{?sM$X*aqU?@%oOaP5ufMYVrsqpfKP8-Yn-`v-4tK1sd|g4 z`e*X@^m0%kQGVudv%j{M!S%_(7OJ`6ak@wXAvu>xBL4vMR#}70oex?yr z=9e98`oH~mT18^T=pm-xlUfE_MHjbCddayxZfbjrSuiF4wn-D*1|*ghyv3Y(qqYS} z&~-&0P&u}24>P=1;^HS|Zxx9O=k_#{r)nAe zEV_7RNM}$XF?M7xv-No`g9KeXm!vberKZ1|XX=zlwgA7ieV@}#e)hok4;w zzLz&mP$9v0f@UY^%KkoNDkS(jf$5CvraWYZ9+T|tL%Pp2MN1|%*Ls@xW9e*juv&6V z{8VGM`Qnc!{2INk?Gn@efv1$Ud*JpN=IZAY*9p&0G=0uYX78-edC1IpJo$S%g9?d# zr_MCzJf;!N3O;C-Oi9vnCO>G_yqwfL9@80Y`^6(?naNuYw;WtT5(ig4Y>K|AwTc8? zT&8rZsE~N)x0$BQA}xaiUD?+a*H7UKr@LP9;no$`B8k>NOgFQC)V4VZy0Y(AR7l*m zY=*hNaI#mX*A)r6xKC#%s=YYNJh35Z`|xXLn;Oq(%fWqj@zUw$&$p9pz_p&vphBWb z!Rh9&FAui`=~~KP#jNG#;S)S_*o>* zesqrMwqIMjB@CmO+B96L1uymxIT|0z1u^ zbCbP0Coa4IC~zW;`K{7CK29SOSH4cTNaJmDdwmqCTZZ3Fh02YXLC z3_%y)Ig(yi9C735BG+4*phALoakCS2alNGpDkO$%{Fj+tKpV#)K^NCsI)e&{hPSRY zt+$R+)-DOUxTez?R7l)e@ki6>@^MNA?^Cna&$W=wphANE`RoK;TnlM}3JG2TWGCq2 zT1XRANbuJ&vJ-S=U%OODEPUh$d;0-x9H(W2l5U=EQ@^Ed{8vdkb$?QSII^^Tc2PTJ z3wEef%5JKYxc##t>;zq$k(4H=khtqW zN&DCZS_TQarr%Z4etD`!P?=Dnq@=qOQ3*2~@U#1OHj-l6_|WOOWHfX8|&9}I)lnpP>;{UO2tDz3z>5LPf9Nb6%r#>7qO=o*VZlxx^Adl#BRPw zBls;decDm>wo=J4!EdE>tEiA@_R3NA+pgLXMS`w%e;j2GzN8UUYPe?%3KvekqxebL zTSa2j`-SbM%e8MfeimJg+ZVCdj?f6+L*ji6zF#)oDk>zHot>bI-<4^C3W@B?L4q!x z?a~?Cf0jR1*cKX;>`UC=(gYO}OY0W4U%ssEi6rRaGNm)9keL6~QTDo`+P5ePx_I7A zXK>~~>Barb(!!7X?aK3UV*3A*^k|1?2`1mA(5ouI4imi^}Qr?t1^ zQz4Q4efqrX#QSBuW=OY+3JKn^$WGAp;2Tx!nP+uYwjdP}e2y)hL4vNl<+beH?$;&r zKX*rk1fOF|XON)l{`KeD+wbq8WKbc&rzq1IBU74G&)?X=(_0j zs`mS;8Zl&cHT%qm%ltMteP}hib$(Lw4R-0}phBYh#no)R!3mw6psUKSRc-Z_8gcjb zD)#y#5{19=Q2DZ|Hm8h6P$9wArdvgVuFDowwVP{c8B|F8Z_6=jNEJKuw`A5FTbOPY z6%vz6RI$5$*XG=jpli+%a>NOPd7?xE>pTyR7mVtQq7)P zETOX#ba8)66YtcjWZS-weAe17mFyq?PHG;_X@Uxg^-ol?rAuggI|;h@O_a{yk<;ba zYPMg2zjM@*DAcB!9kp3oS3J(?;#yC)iVBHRV_gd$)iOxX#eE^2!TqP;#g*-)m6hz0QGaJ$k=RkuE%|fWl5<_r#nz@3j zyIa`_x_E4+2`VH`{ke{P^H1&fib&9v{VlXqNboI*=~j`Ti|>9-6I4iKf8!zvy0X7h zw$i>$=D})7kA6trX0!8|uKowmigNuo~fiMHL!p-Kini!T1gOnNz}kSNr#s(tw+ZC(Zmy7(J2=?p3)YWF+C zUUR|-WjRRD^}qdw0*S$MYuf48Y8m`2y7*fc>E)n8qSzNrY!R#7TOvVM=V!0Bmmbod z8Kpvkzf+%X6$!dlx6QRrue@7XyHrSI|IPci=YC=;K9)QMaZ2q^&21khSMl8Q)2*UH z;;QlcOw*^dcQlfqi+g@Lg9?eYZjMIvJGAR_5_ECTPiIgeG5M+rcHZyWaZZ9R?)m8q zDkM6zKGhaztzDm!po@EcI)e&{yK~R9-{%ff_7W0wanDa@P$9ALzO(GmU0MbSy13`3 zGpLa0`hHV;#^>5^pOK)8dwx2D3W;%*Z?xr_X!mzX(A95AXIuWfiOSlgLSj(6F1GTX z2@1h?e~!DbldU(pk9Q58+sPJ~n$+p#pfaXJuB~!!;^HTz2`VH84$8GJ-lAoYpsUO$ zxi;@AjcE2wXKN}XceXBb>*v?klOvVyPffRq3W-a5ced~K(~k4%t2^6qclP${hxFLd zoo()i$=}l%R7i07vJ-T*JFm0tT0vWKDkQS6D=x=5zjd~qs^(v&bgS5Q5+_&aV%NUb zOWChT(6zm07yCsUji}S5gPlJxQDzS7V5fYZ)Vyn$ZWR?0d*^hp=NN5!kf3Y-#~tkO znHs_N9$BM{UH^5mk8%0Zt)fC=Mwu>l+a21yR}yq_pH64IzPFPd@J^mz?~6usvN>y$ zI{TeeDkR=4+sVGXJ)zSXBs@-pS?-YRdPi~z4Mz8LFI%8JL-}R z-MnKDkS);o6H1VJg*ujsF2{b6qyOScwRM5P$9wR zFlQ#{;&)kbf(nVg6N>2y6GCU)Nzldbvf>$3NbosdnF+f1T~?f+LW0lv%1qG3@3P_q z6%su!Z=#o+`C{O+4+*;XT~<7U3JE?>BQrr)<|hMDA(8pn9Fu-qp)RO(ogLxYy(?6e zrPtc}zD=vtmp{9IkN1iS3El@ZGeH-RyyFBF61)aFGeH-RyyFBF61-|5GeH-RyyFBF z61)Z>GeH-RyyFBF61)Z>GeH-RyyFBF61)Z>GeH-RyyFBF61)Z>GeH-RyyFBF65I!8 zCg|dkcbuR?f}c1u6Ljr5&`*C{ZBk(CLxlvNrxDK}L07>#19j@$PzDtebEgi}WlDz# zK4Fp1>f{zR-YY63_!Q2}1YO*s#tAAU4qetQS|y2)rL8=*qlwsgStyx$e5&d7<^{k_UR|-)l^<>AhR`)KBcW z&(pv07 zphBX<{62co(hzaa%f0mM1L<*;?XAcD?P}8TUQrni;_h+1^=W^FGQRz|r!M@N`$Ye0 zvZtQ(yQ?#=iBIh7p>wLZwzwWQ*w90NwtH@1eo!INUcO^!`9_FXyQ`W12MM~kF2pnV-VWW}TX)>& z+GR^|f(nV#+w{?kzx}6P(Up1Ke}V(iuZ~Ni67?n)dRl`ttBMrDm1&V z-t|m~;2K^ktEV1b*|{>W?NmsdSXAapZYYBUU3~xJBd0>5{Ei;_nz5k_5_DyrQCudE zP3o%$4RY;r8OD1>g+$A)ef3-w>JlA1)OlUiqlEt}x4Oah7%Its6h`Pg@@@ zT@nlbkQp_@(eZI`d$p%bPkrW9ZcXGej1yEy?91(`-?=k1KSYNYKUJ#xtmp zXjZR}K5aoLg9Ke%-{Kh`oK#QWbm0Sb@AX}WdV0rp_vwY7GUEgl61@5%GeH+WWyT3A zBzW~jW`Zt$%8V0KNbvJxW`Zs*^*BL=1V0UCCg|eY6DO#U_%1O@uep0h;ByHHy7*Mo zcm@>`{ETXeq~nq){~N4YEiUudVoB|<7Lz(o_+Qb9;(xm)HCu`kK3!bCS5o`lN*yQs zXJ=9TlTfAhpRe-~{`sY%_-B+!?ay-LBm8p>Me$Eal-fVZFdyNc!6ShEYdRbitE9B^57Pa(s0&8$}>==x^*Y5J<>Zat2Vg9?c$ z$y0QXk3$(G=;E3m&!9r0O|g=C&xx2HNjH#WiUeKxW|Sv5pC_~}qCa^3G5el#?TPn_ z3W=pHi|7Y$baZBduEO1m=#~XR7%XYtkEyeY=%-(HBYgTm5q-7C0AM%G@gw!)p}RuicLfY2Un(DYiuy=cBXQ zze4zPn=(^}zj%uN>5L59D;r=kxb-1%_35YRnN3665)yRf+lsnQNe1@@jhddSFH`P) z<{BCw2Ne>>w>VYbJ`-z6(uKs=cDmlGbEbg{t_loHLbo@SF!%sMim<+Mh9%e~84rwl4F;+f@Y(TkxB5}(0!$BE0;fA@z7D!X&vQ*YP0!S9$rK5?K6!76>Ut^&Yd6I0xhd7DY8hSqmM_ zY)?oL?-hyaujHvNog8h6q~qcQUF@y%%3q<9DfZnzZ8bCwahsPMt9|^w`uYCmcH|_^ znYC2Sop;TVcQ9#zqX@b#ANsCZF*`&YTE0TnyVfmte|?GcirY%ty3e3O!e84Gtye*U zE^fiy2;{F&$rSrrwZ$@Z&jQzXE)h$J+q~k-iiCgSZPY6V97WK@<7n5oLy{>fB>WS0 zql{#TpsV$W<*M=(Sg#x)y`pl>i7Qmj4Ci9DH3u_D+&FB7nzkPqL4q!>3-Jtprcy?@ zy8HmWZpCD~_Kn)#Ul)AH)p3GKsg3>hP zM7Bj2w-PqP{7IU%oipc`O9trkr@2|gx#Go|uEuzInw7y53qhKrd|u z!rBetufLKlfWPKSYJV+OzAeLT_YKiCx4E{q&K;uXlslGrPGZ^9L-e`1p{2_$16|z4 z*deF?BvaKd9IRJYb-lWB+F;$biK`zfFiJP+E_W1+#^FcK(M~-yPU_zaGaM2$K_^y2Zz2oiMF zymg4aVPS~ix6V8ksXTs#D%qsVk)`W1{I6wYxu5>gm+I0!w^&zl@fYeqdHIEW^nQ54 z{}Nsl|C@TLGoSx>>+7|u)N}I7dvRS~d5yYwf~)fp3HM5-m_b+OUR}R&g?g!USDV4n z`sWZt<1i6PGoz@G;BvG55x0583A%VBBQAU}OtJQtV zEz!06K2Qz5aPJz&7bmEY=rL`T>X{RI&-p%|)M}j?H8jIJ=zGO?jl`NqK2hc7Iy&Af z5_ECxi4*Magx>F~Tb^?3F2@%qsE{~&>`K*eyIXrQ6LfKXvqbt&GPSAe*J@c=cjo7l z{$Hz){&2Owiap<&IPuO8)Sjnrvg_{Vzduw>>bjaoGCm_|)6{Q%|q@R6V-pSk@8}JNkd7nw{>}N}D0=n^(M7bOqOT zOVCyK;OFYe(XQQmMA9Uf3@Rk1U-O0PStPWqNYFLnjxSZe1t466WKj9$*00peer_#c zORhT(iT8@c(?!2lXJ^ZuDe|qmY>O^#G2$81cJMl>Q$ID&(Q(3GNi6O9Ym%k*S9RnYhrgyoln(cF)??aV(6#l4E_&13p|ym{{@gCQLl5U-OPPB` z;?fPBb@L*j47NoV*RgnpzXOe|8UC&_Qv3U8NNtJqpJa*(iJVktJ$`rSGc^gio;s(C z9yAGrV0x1K!L9WRxYJ0FxR<>myB6Me6eW(!wq$1QsO_N6LL$3vZ{6cg%=2WFL4q!B$DCLG3ME(X zM0Ylk5&CcfBGpwo-4Mbz$gx2DU{PXPWJhA4lP0+tp*u7uy+?-F=(- zV$&j9`zMg+n^8-r{iw#}y=`4%KH9Eoe(LH~YqzPZYrkv%J)SXq+7>mrvvUoownhC| z-_`zE==m~sum445-T#JdtLl;+YSHR9ZGFy_JJss_u8wE4I%|h&aLA3L_kr!|)n{B? z{>^Qw@Q4t>jMpmfQoo1h~PNb_g6>mR5LFL z5mZS0e(!d*D;XL&3A+9|{wK9!NGO8}iOSdgs5U=<3_E-?qe#$|dE`_`^f`Tpy7dKQ zBwa`{MS?EAPw5WX|0Ppgf9kxoQ}wU%mR+y7E;wtHL50Mc!n@QZS2;Q}LD!u6yVT+d zAY6njtLNKnRejdGInj9Y1~s?VQroNX)wikE-?@K}XHX%LZw~ql5_HWwv`uZ=fDBJi zA;CEx?-j=}di)P+*z){iN;fa7h*?Y6cM|nJ_+IUM0lgBpdBq93GH*+$khr7D_iD~P zp$rmqaXaR^WB*F8xK&&C`DRt7fNPg6#R)1T4nMzH&0d4GBpGFppzG47HmkBTLIk&i z+|F|=5$_ch5}Ee~BksD$k42%LZZT{TUG75K)8X+(&fzQ&~TT^&U2&X+>DQd z3W?9l?NS&18d_E)==yv8PL()2w3ck`zf+aE+9}WM+M$jc?P|`Ic(16CXmjNbHD*pI zg9KgN2d5WPdPW`mb&G2MrCW-vr+u&1FLX7Rbi7woNNj5HgZk_dydO!IBv+p8`awPO zgZrF7SH5@96I@4EzqeUc>FVACuG8^eQ6Vw!q%G>&3qtQ83A)(Zcm@>`Z};7znjRm@ zAVC+GdOYKXUk<2WYq@=D!J+%rmAAV3rM?GLmzP8PS}G*ChQ>2U(8aYUPEa9{d2J^_ z7iWRZNdHNuICA#zmP>wDe{OM~&f>kILc-roJNlgHGf2?&=hc6x*^@#U{%+IKR)IGT zs=Sn2k4eXSMTNxta}TO1=Y%py(3QDY{;t{5D}P^asr_BS^NpO!J<|@V2M51yKQpkU z_&BJLcyISXwRy9nGZS=i8O8}JBo-Y!sJgXrOFA<_7nigp%%7zB1hAp{ZdG%+Je^0D ziGLoC)c)>JTvnE#%Ri|nM2OqGk}0-D;-0p@sFrWLY-hE9k0R*ucZZ64m5c}~BtAO$ ztD3tJ84i#PDrby2pw^xycSo0Y*^)H}Gf3RF@i$ffdPip_=<;`%&o>VL+$B-^7TKwW z)^P1EAHPdg*mKl4q-V*Le+H-!{<)u0`=>#5#(vX4m%nRF zzL8TQ;qMv~5q=yb=<@fL$wyEj!QXuOaU{*MD*kFUecq*Vw+?B`|9({JJ;SQ&ZRH-c z{~jl(koa+3b-j11{9ZNcm9%eO@eF?-7I9_%^%)fs{vI&-GDy(HU%t8S*uT;%f8TRy ztJ;+FbiE7Qce*EK)zLRp41K?Q>%;Z5eo%geD}?`jt<+o!u5~kPGjg^yY;PU?`K`I1_`1tIg`^ zR_SvE7fqb$+F^dC$V%!U7dYfVb(1eN1% zzd)DU=3H#a_9xgY5`TPtzTQx1YG8h_ExJzo&-r>`84xB&a^y4Ihqd&_Z@K0EM{aFB zC+TXg3&w2R<`rMBNR;1ETOVi>dI#ASU7Rbfb@w-!;@a@{z`DBcv#wpPJ=U9y2r4A5 z-BDLJ-WBQ<3A(tBxz?i$u5sI6sHc~2c55G7vfgAwP$BWsEA{kW4c+|DOwh$GhHE{_ z_@LZ*`sICYUE-Fr%zNkQ{l)Q~CnJIi39dcy3=(ubHMov0Qyv*of~(cr%|b&G3486@ax+N`>sbz5jFN`*w9g*A1lzd`tM zkf7_gPStdY>o5lmA+KbL3W?X()YKo%Lq^g9M-g;oomfksof{&!gp4MlkXD%3A)x#t*Bp_gR^A5SN>@?(pJf{%Igi!yK{G>N=yOzV1R0rdLVRD=Oo@ zE2S4KbIXb?*&&GAypky@BJ=3ddHV|MF-@_LN`?r!3T`f}Rq@c?fXe?G z7tvRK>9!xtwyg&+ zW#_Ng`D=Mgm_JD~4k{%03vf$_+q~igUH(qs`Q{)M60glHraR7iDDVlHXTbTL1Hbom z{V`oKy`n;b-#=JF+~yT0=;HU+&T9V(L4`z(JKs^gdMyczW7fcz)WwHhu}ar%PpD-d zx$jGAp763d;VOKmZ@XlAb!+$GYTkOcO#FT5Wr-dtGfZ9eI+m3usF3J9YlvF=D2QY< z4u1!JX}ACK;cCx>>9&XdKKuFJ!Gag{Q0udtYsHN2s!(xP_r9i?YW~yABO`YaG7e_2 zU4Q@nd>Q_^>Y|W1+$>l1tt@vW%|}onG3bGQ>V{3Ohqgn0JhqQ|cTQ-_K!UCgr}k6jrhxFhqEc>Ae|5{aW9b!% zYdQ~9zl}kLjM~Pe*ekkDE;3ksc@GE&$g<+hxuyMW>Zz%2iE^g7#vPJOQ6ced=i5}R z_wjxtLj+wPRJ~1A{X0Z(Tf1!BFx7v)n-ko2#d}4C#N5(D)qwXyGl~RVXHOig%5De| zRC;V3sMc&dmR^yleenR*i>PwBvmtOl&v2dKS_Ns+ttqN{w7mY z`Yo8G{#)b@ORy#DO-2M25;Yf3QtuCObY_CCxzi`9MH@rJhwUb*E1QnCJ$Y^SJ!-&Q zSJ!=Ql4@Lioc;HB1{D%Ry5FO6es^?cg02ehPgFH3CIcB%?khP_ozuvXTNX47NqrfZ=zm@z;ScK}qwT_ifoiz4wg!ZRjPl$EfmM+-Qr}x<+jp147*9C1*^a zkeJ4Gb(SOFMdmnZ#w&WVOe~-!_QL@Sybw^EP*e)I2E4n^x&`lLBGc53a z&^1GiQTH!(Yj|dY3W))CjZuHzfccS(#zBIviMz(A&;GtW(5q_MBh_`Y`&i|t`|eWn z3OLt?oyMz%d)(Z#t@{iTKYu_1lh`J8K)OFcevDkLhD9H)Noj9&SXlc0-B zJ)S{@#7is3sb9}UM$(1IwdZ)x>EipJ?ofKN~Qs!QfSYBj;s(k35 z)+@TW#>6v@yL_CQUc+rOa-JNkErV z>yfLD*ALWdawNkOR7kYHzL5TK1&E|Wk|`2&75TB4E`4{SBN?8cLSpy}<@D2!G&@50 zUXh^df*GZC(_b4NA$&%$9~6N>*6-A_?k%KvJ#E-O|!9HS-T;qOzzo8-_YY&GDy^1(?}Q9$Vi%yqkBac z*L>%7f0HS$KUZ$a(sdTP<-_&OdXo`Bg~a$zv-DXNLhlC&x@NwTrC%KzBBWyc@xjz`jc0>q5h$VTUK1(;sg~EWB$`n|9%+r++a!b z4w9hj->r!x`d%UHu{;HYzLeI^0_tJEY+rN^*=P~d(4W#1)6%uc5Z>K93!ImKzWssmNbFcXH2==hr zmY#Zd+t8hKsF3haIgdUe`(BZtYwza%y59wT0!x<)iK=^t=#OU)4G>gF_~&Tm>lF#Q z3LPGy8#WCc6;UC{68<@O5#fNN z2)g`J?MNg|#*%%lb+>-6+g>s6;RjpmO;@{rPdA?)2Ne?jiKS77v~OO?6bZVHJFm6g zdD&4JmSC@@H_g?r-=DvSu5tVKsF9PHIXPE<_y#hPA%d>Q-^4t7v(rQGeK8_f^Bq@F(KmX8*}wx zz1a5TrDD1I&Tg*e8XC`_LZaJ()_Uw1M`tGJTG_I-KKJ1eLFLOITIr3mj-^*5R*h(- zTg?e&a2#|sp4Lov-jlLRBt8x*B)%!pO81@_%4qg{OFeX=Q!3`P)O-86+CSet-~6CL zqUj$wdRD7Y1_`><~dEYebIT{)byL*iwAtR7m{XCP$ZE8CtJM&~;a18OKx* zCMapP4F0+EvP_QOoTIOK%*`Usw0N(mkf?n@Oa1w9%t2}2yyUlJblnbHVFc>7iN2(kl|B-fN{#Z1PXNqAT+@k@LB~eCJbtv0I|t2HSDS7|bia{~$5$ zQUda>{606Fdq>tN#UL`GX6hRl4i1m7c3W?K}o~j@2;g(xw zf-WvM*B|#cnetCqmF<;(8m-j)G#JmILc%}&HrgAcgOVvK{t3JPI)j9N25^*-jK;xU z(Zx@)@o`WgF=qK7UGAgjj;vQc!#@vF()|-}rS?zQ{Xcua=R^JS2r%Rd)6B218sUXIVBrw)tapGGV-mq@%>8|Fe=*0twXdA^Yw~t(Z%t(#_eCpphChwnKoYr3A(r*$20sB)1@u{ zOlPV6bB6O}P$A);4jmCDC~1}z*9QMQVR3PZ#Ct`BgnyQClp*b#SN#2;i|?$n+P^|@ z=J+R#OS_zDae_*W*qweBdcIzf@XtRNmw%FaKEgkbUKIaKXQ{c=j4C5JGCjNQb|9a_?@Xz}G zKYK+NXPWI*`j6ae68FI6T~>M5%J?{_kjVE*x+ZU~qOU(5 z8A%HW!Ow7OU#O%@7JJ9`aCO&8`mgUp$LDPKxJxSQ%gVWSXU(mwA1j0m7je|cs~oJV ztG9A4j>(#Ruc(lyen~amXecs*1YI?TSJNBkh6s*uRjo?8{USG7E|GYzsE`qMV=ppr8uQn6}|nC`~H$kJ>DxSB%T;nMGybe(U}Rl@~tHn zGri(c9QI^2{qpC>@(z;Nvap&yy9h=uqc*Sj(H&i>#ntpn*&(9qDb;lUgj-)Pey6Jb zrK+oWeB~OqeR+=R9Ve)?J+7*LwB4~}km&qK6`gxiD1*JCt6l9XI@K{m zP`PDUWxb*OvGj_>#~mu`ZOuX%>=j*Hr{l|t3W?_rSJItohcZae#Vt`hgEOb@?uvS1 zIk#r8r8q%_#BYC9)Kj-&%V4miSrbXn#hDh*ph99xg-UwmtH_Y{%}e$M+sf$u_1?1E zTDtbMsiYT<1!3)mpmOgtY4q2INu0xkK*Jll$6(FdP;CHg|3=(wRBu^z>-`0IvjuTW! zWd2^11YP`88_%FZBHwwnq~&C7CqWlKoyRk%koZsYzIy#FFCAIBE}h_bHx1g04>eI_goipE$Ctd=�e@S@?ANQw4BUy5_J9d!aH=y z`JoxLdQc~QX`Q}y9`tLHt2h2M)YiXz(n+`O?EXF8D=H*-bxNFI#=eT3^iw~%>u*TM z2`VJ^eA!Wtd@OYJ4hgz;&FZKxP$7cKVibUP69rfJ7j?PTbb=A!s z^|Znu43;#XmZ~o7q>B{pX?yZ+>6`VNn|s)rS3SiusE}BYyjkb2c64Uq(ziP6s)wA5 z*D%EiDkOT8?V{_P=X#r&pzE?eUGzu&L0HU;oXX|$WRHXII2W@sXOL*|Qx~ny>}8i* zW`eGnrMl`(qe1vyQ7L#%SH1Q}=lXZOBC)wH`MQ< zyPfG~XQ{6`>mFCRI`bT)LSpcc&iakpLi3yiU3V4htgAc_BB%_VeX~wXJC9c@rn7kT~JNj=E$+tR+den#8ZOq^snLj(X=e zN3HEbB~zT8@9er+4_tLD^PI#>S9jJIef3ZCoG#8_Hv;)Qopf=9ktZ#16hRlae9jvYoCg>D*+t)6)osr?Z>%>N5mZQ2U)e=ZxHGgj zAVC+`w|E8>6642p(VagJWssnYvpJr@YlnEX5U(|g6I4j>s)fu1UAzXt66R0RyysL% zoc()U{qEnP`?r&zi$};dL)tg5__t~#3O-#ye>N?2mu9v_*T4Iofkgiv1$4I;UJ7if z*%n>AkGLCv{VU_3LL&41sY%eqd!WZNsF28fe`*qR@ebluh>@SHpTSpn_aui&fF^!OI8-s{pW>x#kS}w zUA?%zb8m=Xe_OnDg8sRi>pRC6?-dmiGp3)QN0q?HlhMdY(Dmum6LhmhcOO~01`sNl zNV`i_00ju7HDuVjh}iR8)?b&aB-k&~cnVxN4=nT7RzUpg0CvV^$JE8Z&-->fOD&s~p&5=;AwTy`G>#qWkC~y4Clg z3=(v4&3FBYdd2nUv2Mln_)Fcp#+EYoibT#m#q}RE@tz0AL073M#dV$iA>!=e#q_`i zZr)A&rKq0O-_^XYV!T&WNOZftsBZbBqcan9-MFxbF7Zx?;96bo#S?VmCf9e)f_MfM z5_7knpsy>8ksB;&)+-Wp{kt`h#Nvj9^bc?T)BK=|bJLC^{YO5x zZY?398yDAS&JJx$*cM%UXKjaMIhj}dp0Xs)+g?mR@N+1GZPCT`%{6ZSN(R@4;U^T) z+dny$HIYP-c7^qopM};d_KL1ib57F#Ss5az)H!&f-tzph^om5&8&A~NCPNwQ6x?s7`5j_|me2rP^k+zP`OwcuZ=q%NJ90=blDnn+^QXAhm zmR^xK|Cw3p);-8bhQ>kHvvOP$FesdvG0zV>gv~#A?=%2yjOIs z#h%Dn?O!3dHeB8Cadp-4$FfZ%F|7Mzs&MhpH>q3`>Eia-^~VgtjD!0-?!*7xJ4k|C z44+|QV*6UUrqrLVTHhD?29o#9=MxzCeW}l|B0<-vfjiYBeeOH* znZW@upCg0= zWE@mTTwi&Ox_Cn9^DYUx%8XpC?o%LqMso2N>OlE!Hk}zW=WSO7hIK#ED?bh@Br+e- zlc1|#)sytb<^uv5R7mic+77|@iUeJCJD1frEFT`ophAMr9*Jj=psPTqs`}0Hq3`;r zkl^!X;u$39s?+~mea#ukz&NOo;PZIm86@Z$I=iNxacwAr3JG2_70)0+SCQ|U=@WJ6 zTO2ARc+FHig9KeQ>)fFCr=JoOC#aBkr$c95ufe^6rAvaYmF+w0mzGaHLf9a)z51m8 z*XpA`I$MQn{#6rqt1Di-`3RA8NHRr*1lQ^KI7ra7`t+i@`smQnHWdYOfm(4@`iT zt5R+W-K&Cg@!J;bO-2M25>+RZ(65a^Mv$Ou;L9a++iyd}QzeS&*C$_Ld-cIvMRn;G zuI3$SU4Nopv8`|4E1^}h%Pq~`T5qsdB;H(ELgy}UbY_CC-xin9S>>DCJl7xhSH59^ zQsm(hdR@}F{#~y~{I7Ef{pWYc2#$lUeBY6If(nU_l}hN(>bfOuM-U|Fs{irH`pXd^ zg33>WPuAZoa4u$N&LGjU{lVEv~2S2@zbERt_$ze>&)vXukEzkDLmL z_Zk<~bDs#kA0+4+B72;IjY0&KqKTsV^iSQ|$Cl#DiVBI^e;3h(ZpFH5Fd0iSMS?DF zG2$6iNbDQ9b$z zM?0(idlW&}U#*Mj+q;3V0VadWqpuaywX%<;S0wH^v$%fu9AqRzy`pQz-Np3}XM^y) zqH_1X;`+G@kEK^6&TN0Oe&||c1bao-zuR7s(667YXHN=cur0c{C$dY)_lonmRg>a! zuj*sjmXPSQu9$vtb7;%JZ3$hRH}PIkA@O0KVtQ#RltF?n?(J+w`cE>&=MwQLY<%)j zyjN66@M%7o3A!?WmqCRDp9UAtAVJr^`%Z>L$=CX;#f6?fvae0rB$>5ri!Od^81EGo z5-oa-RewJk`ZkILUHq0Ro5ouFOa9Xel#67uV@HL4^d5mNFA`ac;&5DkONcl$oH5XBy)K z6%stY%1qG3Gp2EZ3JD%9WhUt2ncp};g#?e5G81(140fELLV`z2nF+dh?mkXXA;F`i z%miJ$&N@y|A+hT~KmBpF(2*Ajx_F=5cm@>`Z><}kmo^J!kf5tzoq;-aE(jZBKFRP| zDb?T9>dl|-v2&i!X^HoW3JE?rEi*wE_e61m3Wd~tf*yUykahq41po?b&oY(!0pFbzDZhcBM z{{87d2HT>Gd(?Oa6%u7We?hf)@!>!Q3A(t{;~7*)4F1m(>X+){0~sXf;`$cPphAMr z$FfAyamf@3y7(MCpCME-MTJDZXX>S~Wa^ufCaU&tb+sepQ>Ko)=V`T~Q;)#NsgPiv zZC-k0Uh-rhv_;pjbj!;hD$=L@>6M4X^Pg71H3g035e zeWort)Su7 zegi|lN+Cg4-y%EJ&>A32*OF!}Sw4Q3s<6kUZ>YXo)m-jswq(bV{v%hIqQ4~gs|#zE z_RT9!(8VRuZ7?2OxH&uf?R|OXJ*VPp$>0+> z5(y9q?~=CY^0m$QdRy=8(XHskyyw`KP(-q2=H@wH^|=@^Lwh=g}ZTXgx_X8clTboRp~<}NYs z2NhpSM*O~mAQIjsZPDdxn{m;e(b->qnb+84Q1P{7@IHr$1c-!pNn3RJ+GZR)FeI*h=g}ZTXgx_W=zQ$k^Ron?lyypuO)+b^hhK?B)m)7qRZDdYuO)+bZ%!mYB)m)7qRZDdqfn*p*=PUwg~>=z@wH^c?>dx;pv%`bk%^$o*ES>7?C-4CZoA25Q1P{7@VD=YL?(hRU)zky=dH_4%;iW+~gNm;uBYr>qOaxuNwi&y2w##ZfWTefY;%mv^{reM% zOaxuNwi#8Ye$iy_gLl{rD!!JC_}%d{5p?<5W<0Z?QlmA8N81c4zLpH$jbFA`83?+3 zZ8JJQ^wE-o3*9)V_*ydfjDSQU6G4}+ZN__v)_K1za_bc6RJzGpP7lG8%8*pyt+Es{b1! z-Y&AF8kHa+bRtpd$1n0ul6{B}^GNtwTszKPr|vKMPC6raG$HB!2!gfEIJMtvS#y{5 zOPT$LcZuR_A^Z~nrA{O=5p?<5W(=u)XV%w?huI7&zLs|VlY(tVCW0&lWFqMDwaxf+UGpaAEf{SxsQ6mi_0KG}8JP&Wd~GwzZ@F>Fyjd=T zim#%`?a573${Rb1J@; zcKwsPZAK=7E??V>e(%4Y*SxJ;cd7VV+VxK$w;7oTx_oUj{(I84yt1!%wabc%uccl8 z^mLn%iJ;5ZHsh9`3a6UA(B5WH@wK$;pSNx^G7)t7+GbR^sbcD)Yn$5)D!!I>{dXBQ zBNIWFuWd%BiuF>XwqEGQQQ&D+KXJ9)zIvCm>%T{_8JP&Wd~Gux`t!0>uQ63^1{GgR zyZ-xYn~{m2%hxvJ($rO{C%c?%GpP7l+V$UZ+l)*EUB0#%_v_B7f_MF#XSTakd@b#M z*r1y#T4q>!+n$M_%hxvJr;dG6b7eneGN|}kGK$x_Mr|4+-?vMhNMs`D^0mzJRtY3@W~scKsPTn~{m2%hxvJ!{2U89e-8>n?c3b(yl*`XEQPpbott5q?(UTjVLz5 z9G@qs_*&Y1XMDCAcIo};WtEAb%hxtz-`3HoI*IM(_&ho$VAZP zYn!oX^{7JLdJV8B}~N?H+EH ztNK=+mCndS(B*5Jaq2?@QsufmXEUhyS~C1KGg8avk_-f0zP1^kPQNvE_IY313@W~s zcKtOoHX{>3m#=Nc>1W@Ns@Sezws}9O_*&Za*UZ?AOaxuNwi)wp&Pf%nQO;&i@wK$; zud=ZjnFzXkZ8M%3*eLb*_2=0PD!!I>{na}*BNIWFuWiQG@ikHv7G7dAsQ6mi^}ipr z8JP&Wd~Gwfe^M&-`0;IQ1{GgRyZ(2nHX{>3m#=L`pVEi&{w&+kW>E39v>X52o{6B# z*ESOK66K@Bz!Hdao?5F3zkJ0B&Y-lo6%s;TUk$5?rWD7315q=>x`26 zx(nU=lt_@E5+rQK*zZrs?oju7n?b_Y;@UB;gkJnrltF?@kgyqJ^3KWrdbaykjfAho zb?JiQ`txVy_fhlBT0(+Kkgyrm2Q<%qH>;u@2MJ$`>#17BbdSg7S6eoN1eG9RGoCJX zbN1hb_uIVz315qA0viXfl!{d@Zj3H7=sB{BlY&rz_16?86>C#37cW&pUf(oLBiMK^1n--Z`NHBRDy)fF!N7l zRmzNmgs;Wre>rV4NKgq9Hp9$6nN>D}gs;W5_y3)&>)t2VM%fG!RDy)fF!N7lmCYdG zYjKsXa*Dn)cX~R51eG9RGtB&xS!FXw_*z^oEw z`aqv3g9MczVKdD9lUe1K725K&xVo<|uakA63=&j=gv~JXPiB?PAmM9q`RBCEH*=5# zl^|g=%>0vCWiv?lT3iLrucSwojn*p?RDy)fF!N7lmCYdGYjHhapo+e+MKlLVPze$? z!^}UKRW^f!uf=uwgsS@etD_@G5>$eO%`o#%W|i3{CP?^NT>gnD^UeD~f=ZCE8D{>O z&!Z-Tgs;W5XIOQ;tz5KiCqX4h*bFoO%%@9}LBiMK`f*)#y>~12gPx!gBy5J6f9BJr z$spltan)H?UBCQd^sNC2DnY_#nE7WuU78FMz7|*0X4Unq+oI15B&Y-ln_=dk`E+SA zNcdV@zjdmnOI#Oy_8~zfNZ1TB|IDXLlR?7Q;<~t8RsCtJ=rbG%DnY_#nE7WuU78FM zz82SCw^i1MyGEZyNl*zAHskX%&r21Z-^gZ=@U^(sURqi2Z4qUVpb{i(#-`F|r3zJP zVKYehT3qX=R@AS|i9WZJpb{i(hMD8$6RcTQBz!F{f223x%ySY{f`rYOUvp008|h=t z%GdpN|3M_!(@(kO&@cT@U^&FPy1f2Ul?VOpb{i( z#=SDfKS>{RlJK>-4*t4Dwf{28AVDQa*o;%-=AE=fU3)>4L4rzy(Y>aK_y7o zjE80Z^-LdglJK>-)_uNNl_~Ic`aLH>B}mwemt_9^wA&qXlJK>-22|Ukeyks5kf0JI zY(|dEzbDeioFsfLuHns-86>C#37auQ=HK}AF((OMi)-}wAJnkrQ3eSrLBeLp zUM)-ZgDJDGCE;svJ>O=l>a#w|AVDQa*bLdLWyyZfW{~i;xW-rCrdod&Wssl}By5K4 z)!vr1_@t_tId@=)R;L@1_>%b!e+=`EhYOw zn?b_Y;(BJ+4t3n1_@t_>+^EE)P=uB`wtRSf`rYGy;@54gEoVN zuf^4&;VzY(7iEy35+rPfIf9h^pgra!;cIctslQ7to)Be_pb{i(hV0c+vLCd^gCu+{ zt~G^ssY|YkGDuJf5;jBjYAM+d+6)rD7FV6OcB=kWq6`vLf`rYGy;@54gV|=gOTyRU zI_JurYW4o;b0P^ULBeLpUM(g2L7PFs*W#+WWQSU`I?5nHB}mu|*{h{wKWH;Z_*z_j zPT!$!eId#qK_y7o4B4yY$$rpgknpv*{889^^Ldv9l^|g=?vwfVVETCQql3Syxf|v8 zeA1S$#dS~HUsTJt-M`DPQb14%5;kM-yJzHmnLZvQ;cIc7J7cff^g@(Df=ZCE8QYtF z)A+9R@gNCbi>vfEd(^itMHwWh1PPmw_fAgMUFqXN622Cf|Apgx^L~(^5+rO!Avqp= zHhnxu!q?*RzrnN_B&Y-ln{m6$znjy?gCu+{F8>Qqn?Zs~kgyp&W&Z6=9}kl7wYdB* zPHhGWDnY_#oG-_N3)9DgBz!HdwNGzX@2`?yvf2z1RDy)fcvj}$!Sp#u622Cf|J}aL zAVDQa*o-G+{C#37heV%)i#@<3SR>7FTxnZR(3nQ3eSrLBeJ{ zEc5S{^f^cpz7|*EV%ybY%@;?19QNN|3M_ zb7lUe(#L}&d@ZiOj{ixm7!qZWpb{i(hV0d{WIvcPpG!#iT3p%B?^b8dh%!h}2@*CV zSB?jFr;i6o_*z^~cKKONd@jl$K_y7o4B4x_EwjpwgM_ce^;+e9YVy-j1_>%b!e;D~ z`74u2`WLtX1pZx@B8#QND{sl*Zgx2swwA086>C#37auT=3m|P z@gNCbi>tsJ2UT7w+P0IR5+rQKH!}a~$>&is&q?@NT#F7KRNdM{86>C#37cWQkC`p! zCrkzjUyJL#-3Qg?&2o33`Q~#X2`WLtX2@PGCHp~ptVY7u;<{(rLG|F^D1!u*AYn6P zKbVsJpv@rRYjOE!vd%Z-AVDQa*o>(%|7xd?2TAx^T>crbHiHC}AYn6Pua=ViV77Tb zNcdV@w{84Q)xSRaoJfL7kgyrg$oy+4pGQpw315rrj4=n)+S8&85>$eO&5*rXp6my0 z1_@t_%O8c!H}3}tDnY_#yvXx|msi!frSj}LS~;r4HF$eO%{VCE#~e%_ z50db;xc0QEq!*5jGDuJf5;o%_nScG#$Act%Ev_vUWE`(X86>C#37audjt5t!j|WNk zT3o;VRZ&mf8fB265+rQKuQLChNx5rMN%&e^b$3_P6U(L2bC3j;AYn7^mgB+Fjok4d z315rrl)V-8DY;Pw2`WLtW{i{h_sKi%np6_L7T3rVD(MO1q6`vLf`rXjA@grQ`urdX zUyEy1txCH6q9}s|l^|g=cyvd?*Wy~;wUYkp`zV71l^|g=w#)n*oIV~T;cIcNeW8*r zSuFbXG6^a{!e%s(`S(!znp6_L7T5EKE9p+PqYM&Mf`rW&jPrved@ZhzJ5<)&nnf8T zs00a{A$v7{evpK(#dXWF%6dclD1!u*AYn6Pua+hI!Ib&TK*HDJYFE38PIZhjNKgq9 zHbeGm{+d)0z7|*KN2=)Do1zR7RDy)fkiD8e9wgywakV|Js(!RxltF?@kgyrDSId+A zpj}oZd@ZhhU90L}v!e_WRDy)fkiA+;_JcNqgs;VQ@jF%ZFIA%q5>$eO&5*rXO7?>` zgM_ce)%BEWx_=_dAVDQa*o;;3eM|#6KVjA@622B!fp*pO*!9u2ganl!VKZc}mXiIT zJB~tIo)%Y$@iLBQq6`vLf`rYGy;@54gEoVNuf=ufnQHo}!BGYYDnY_#{3!G9E4g0H zEGrVe7FTLjzx@U^(MEUc!_E)r#spb{i(hV0c+vLCd^ zY9xFuu3=AB(=UG>eP$p*B}mu|*{h{wKWH;Z_*z^whF8-Y=SCSMs00a{A$zryd@q`9 z-VYMK7FYF4s_8~UqYM&Mf`rYGy;@54gEoVNuf-YVEj1uOA;}kf0JIY{nNd|6WZW50db; zxMr2TMX!1}${;}{NZ5?=GXHK!9}kl7wYY}d&{bF78D)^55+rQK44Ho`(#L}&d@U~j z#Hsma-6cUKNZ1VXeay4z<3SR>7MFj*mCYbQB}mwe+vRxh(e(AABz!HdoK$B$es^?T zI0-62!e%U$`8QlXkIM8&lJK>-W)JVIuW27$-%f%`kgyr%{QRJI-SHp^UyI8>Q*XX` zKS)ps5;o&5bG@jXpD^Pf;cIdEXZYC+5>$eO&6p$eZ;X5%H5nv)Ev^ptbk<|$M89bu zK_y7ojFB?`eo3DnB;jjuUAm#OZeAq%Z3YP{LBeL3`6sg~WyV3m*W%ir+eLTi5oM5| z5+rO!p*h*vZPUktBz!Hdtv__po8FExNKgq9He-g&zozNqK@z?e*YpRw>ZZs0-^zfX z5+rO!4VizBrq2(O@U^(!Zhwm&a8Z;&f=ZCE8M0T)lKr50KN2K-Ev^nVyXlqJM;Roj z1PPn*w#>iv>El5Xz7|*UlWx`Zdqo)}s00a{v7pU2Z;wfzA0**xah2YFtG=jvltF?@ zkgyrDSId+Apj}oZd@ZhpOS|hGZK4bkRDy)f7$M)syq7*6B;jjuUGhK={d%D(kc6+rm0h>D?r~?7L4rz$eO&EPK% zN%&e^hnDx$o61KSB&Y-lo3U2rU%B-0APHZK>x$An^~m+nXKE5uf`rYGy;`2^2ko*V z;cIdEqp1ua=+1KJa?!4A|=Vj4(XA)F`gv~JD z$H=!VHiLw(#Z~IPR{F#yQ3eSrLBeL3?_ssldSy2WFDnY_#nD1lE z*#?tA!q?(DeQ!%$^NJ{g1eG9RGtBof=4^w>AmM9q4V~Olue&kIAVDQa*bMW1j5*t2 zGD!GZT(vJ~sXrecWssl}By5KHKE|AFFc~C#Ew1A?=jdx5i!w-12@*ELd>>=ZHkb?& zz7|*4Cvx;yLf=ZCE8Rqx9=4^vRBuV&M zT)nTz(UogN*RYVF5+rPfIX`dCHkb?&z82Rr7w70Q9ij{pRDy)fFuw*gXB$ig315rr zuEsff*3>A21eG9RGtBvUbGE@`knpv*er}VaORtPFNKgq9Hp85sH)k761_@t_D{DlK z-u_3FL4rz1B}mu|bADdVy4!J(@U^%q=Css%`$ZWfs00a{Vb0H+vkhihk?^&+nmylA51klg zkf0JIY=${MZ_YMIMuLQ|#q~{zR=W4hD1!u*AYn7i`FT0(ZZk;uT3o9}w9>8SL>VNg z1PPmA&d-~(4Q3o9d@Zgoe`uvQ&WbWfPze$?!$eO z%`oTZ&DjQ%LBiMK>b9V@9y=z=AVDQa*bH;MwmI8iGD!GZTrU;N)pvG_GDuJf5;nt} zpEqY4Oa=*Gi|gwfbM;{zWssl}By5H`KX1-9m<$rW7T546bM>iZqYM&Mf`rX5zuz@y z8%zcXUyEzpr!tNm(Ke9;l^|g=%e%@StW->_lT3nC6m#h12i$431pb{i(hV0c+=IS$(LBiMK znmIXFfA~g}L4rzq3yzB>U1_@t_YkJdM{rde;1_>%b!e*HB^K#bRW{~i;xR&f| zt-JM$GDuJf5;nt}pEp;ZnPo-7*W&U=Ve`%LAPFi#!e;Pn-;VyDsb;6&WUm+VwYZ*M z^{IMvO^5V#WF)8r37f&QeI$G>u4bovqTYQm${;}{NZ1UX?IYo9an)_RR=xRJltF?@ zkgyp%+egCJ;yU=)N2>j%D1!u*AYn6jwvU9b#kKkG4^@-8?tMxmNKgq9HiKvTNcdV@ z6Yu;$?Rh%NAVDQa*bMoW)1MzC;cIav>#b578+J^uS0tze37f&QeI$G>u3cxnuO8SD zWssl}By0xH_L1dB((-|bF1PPlV-*Wo%gCu+{uFB(AsFF>(q%%lR2@*DgXZuL_T3pv} zT%lenEl=B>Z?=gfs00a{!LxlNd@ZiC$F5Wjw?`Qys00a{!LxlNd@ZgCz28^2JatQY z93-d&37f&QeI$G>t{&4?sh&CA(itSE1PPnL^MfROEv~iuK2Qz5h%!h}2@*DgXZuL_ zT3lsDu2%P{ThrqpK_y7o44&;H;cIbSUwMtXctVsxf=ZCE89duZ!q?(@>+7|u)N@e= z2`WLtX7Fqu315qA%_E$eO&EVNS622DKNv+nYQA48)5>$eO&EVNS622B! zrQM&YN2)~`B&Y-lo58bvBz!HdVLjHXZ7)abE(t0@!e+=`&7U76;cIav7k{A+l#en< zPze$?gJ=6l_*z`2fApogv`@4xAweZb*bJWSBjIaty+8XaRpGg4n@EC6kgyp%+egCJ z;;LBZYc=ZgX#YWiN|3M_JljXY*W&u5|JUlHKd>M4XB4Rf37a8%HGh7Pgs;W5sq5Ej zS=lIq1eG9RGkCU-gs;W*bkVQX+1b%&1`hPf=ZCE89duZ!q?)Oe$5xEXOSp_1eG9RGkCU-gs;U__u%L1 z$olPUdcfCWC~p#kH(UZ{7HjD1!u*AYn7i{hZ9%29rU;*Wz0E zM=$-tj3|Qyl^|g=%>A6q-3mC#37cW==Vb0yXfjCnT3p|L+*23+EXp83B}mu|b3Z3@w?dOa!q?(@HQ7^7 z`aQ}ZK_y7o40AsxbGJg1LBiMKDwWk!53f8o{W*~Yl^|g=%-KG3w?dOa!q?(Dv8aqA zH_9MEB}mu|bGFaitxzJ8Bz!Hd@;iFyYsN+yB&Y-ln_=$nYwlKPGD!GZTe_wOALX$zl*W%h!rl&shswjg5l^|g=%>8}M-3mNA-d@ZiEyL#&CA4VA@ zs00a{Veap1?pA0rNcdV@2d-^6`BkZz82T;vc2`#zoQHiRDy)fF!%R0XB$ig315rr?s2{KX@5l-B&Y-l zn_=$nYwlKPGD!GZTtj#F)*bgn86>C#37cW=?`!T>XfjCnT3n~M>7y5a8)cB75+rPf zxxcTuTcODy;cIbqnBPY)S{h}Lpb{i(hPl75xm%&hAmM9qP5i5muKz@oL4rzq5 zzUFR)CWC~p#Z@D_ufBY6ltF?@kgyr%Y@fMXp~)cOYjM>d*jLwY8fB265+rPfIooIM zUT-o;_*z_*ruEf5PK`21Pze$?!`$E3+`Zmpknpv*ewf==5BxUTN0FcsBy5JcJB+z| zy~!ZqYjG8t-B<5=Cdwc|B}mu|bAMlR_j;2-!q?(@Y*Jr6Xi$_vf=ZCE8Rq`J=I-?- zgM_ce)v{|}Jy%5;B&Y-ln_=$nYwlieGD!GZTvycUs}GloGDuJf5;jBjYAJK~dXquI z*WzlnwU6GpEBY)-f=ZCE8Rq`J=I-?-gM_ce)%$@ydgcdF1_>%b!e*HJ`ZC#37f&IKS}snTyL!#pqDm_GDuJf5;lWZf0FRExb7c2KwsK3 z${;}{NZ1Ts{Yk>t;`-&10s8!DQ3eSrLBeL3qr2#OQ4+ou*S6v^j%85>2`WLtW|*V9 z=z38Sz82S?yZY;se~U6mPze$?gI9l&@U^%aZ0N5~s2Tm$eO&EVCaBz!HdQTzMrf)7O*B&Y-lo58C;N%&e^tIH42>sCY=B&Y-l zo58C;N%&e^YugRb!}doRB&Y-lo58C;N%&e^>t+tn_nsO3R)z$XAYn6j^(P5mi|eI5 z1N4R_Q3eSrLBeM6>Q55B7T0Gv19j*2Q3eSrLBeM6>Q55B7FUl~2kL9PM;Roj1PPnL zt3OHjT3qeV9Hbldk1|M52@*DgSAUZ5wYa+7JxH(a8)cB75+rN}ul^+AYjIt@caSdK zHOe4CB}mu|Uj0eJ*W%jWZm{l`8)cB75+rN}ul^+AYjHJxd9dzNKgu9MB}mu|Uj0eJ z*W&7ac(DHIlqiD)l^|g=c=aa;6t`{ZYYjK@AWQg9i zILaVFB}mu|b95J7FG|AK;`-miLv-c;PuZEr>r}OGoP-P~NxdRThBB4V@XOe`Pa0%6 zX+Y*7Gnq-s$&{g&Hz|?g7#gL7G~h&rlqlqFAVX$3QBsont+n>q`+T=^Kd+oW>i)Q{ z@4nVrd+%pY>)Fq!FoOgYmGBvy{YfIKt?T2L2S~+~FoOgYmGBwveoQ!Dltffp*WTF! zWLEJog9H_o@EM%_Ng}GP>(L1Vq|(0doPh)tmGBvy{YfIKt*cV!0n%bom_dSyO85-U z{v;9A)>XdB09i6R%pgHUC42^Ff0Br5>neAkzofMeGe}TT37^5)pCqE%y6&FbUz*eo zGe}TT37^5)pCqE%^#j*%@%f@uRKjPt{m-3Ux@*ql58F$bQ(gUi^{BS4`S-V%o9(lM zVEz>eDk|YK+=M5!KeUvS>T`U{{zyf{IG`3^!lfon5*N5>ahkWfrxS{Q0_Nt`8Da zRKjPt`P%O6(q)i{YU}#8SzAdmVFn2*D&aG}vG-%#*`>=M5!Kf9)&*_lqA_6x2`Vb# zGu(V_yI1)P5>ahkh1ax^L*IoNB&eu_&v5g#-Pxt<2Z^Y*uH4VGk-{~)XRZ$tR8+!e zxbN?}vr8M1N+PPQ>#{y=%E;WOO#ckNvkpFtw3t?RyaZDex39+~|hK}98e zhWq}mJG*rKAQ9EpRjp$incY9kAVEbXe1`k}t~l#(Cy_9}B%pgHUC47ea{;oT_ zbQvU~+PeA=XfN+Q8fK87q7pvCeSg=TUAhbsQEgpCzG*LA?+Y_XP*Dk=;l97?&MsXB ziKw=&7B_T|P9?$&5>!;eXV{}!^nOtiQEgqLM|P0*UxoW12`Vb#Gu-!g?Ohh%4-!#r zUFFtxkTFk$86>EvgwJr_-*xAsZmdW|wRKhfql2_76K0U0q7pvCeSg1QnI=8SeYL?rDST2Z^Y* zuJbE&l#K_%<2eZ`D&aHS_jldX2A4r1s;z5Uk&d!+SeQYAic0tl_x)Y>w83SNh-&Mq z|6>O+CBh66R8+!e*rQtXeo+!pZC!UP>L4dS3eVw4P*Dk=;l97?o;J9CkcevQx~*pi z`Mh_SL4t}(_zd^`UH7!XWsrz!>*`vpgH*XL%pgHUC47dvALE`jxC|0eZC%k-*gQ91 zlmr!(@EPv;e0V+hW}n*9uSEmDA4Iiv6)jj>p0w|p2=)&WR8+!exaae3_L=JkiKw=& z3bSg-#}&d15>!;eXSnC{ZuXhWAQ9EpRs7~!l2$p)AVEbXe1>~I?`EI53=&aoU6nS} zlmZfFkf5RxKEpkqceBr228pP)uBW=ylonmX3=&jS!e_YW^KSN;%ODZe)^%H5TVFn2*D&aHS^LaP>%w>>>YU>&@w1(8I)i870 zB|$|ce1>~I?`EI53=&aoUA^wI{g@VJkf5RxKEut|cC*iHL@J4>wyxpV)R5o)4l_tl zQ3;>n=4-pzXD)+8R9n~bqBUes*G8FRMS_Y-_zZVH#?3x+86=|Gx?U(=Lw?y3W{{ww z5EvgwL?^)ats~XD)+8R9jbztu^G=1}T|iMS_Y- z_zX8++s!_686=|Gx^AjiQzlOgGe}TT37_HSYlqi^B%<27T8^nHGgpQgB&eu_&#*_e z=z5SuR9n}vBQ@ozJz)k3Dk|YK+!;eXSn&=ZuXhWAQ9EpwY^ep$+s=cAVEbXe1@B^?Pj03 z3=&aoT|+0EvgwJsEwcYG9mq8+`t!wq6+VbwuFoOgYmGBvEzP6iv<}ye` zwRIh>QAZZu7-o>5q7pvC&DVCb&s+wHsJ5;NkJXW{cZHuNB&eu_&v5g#-Rv`$K_aTH zYuej&=1_>%E;WONPZTD>?mq8+`t!wnAI&wwHFoOgYmGBvEzP9@|lFJ|w)z)?Q z?mALsQFx3ZK}98ehPxl*zK!HENJO=D_1sZMO5GJ^kf5RxKEut|cHc&F86=|Gx^jJ5 zN2=}&&lyNiQ3;>n=4-oeBe@I`QEgp|X4R2NL&FRbR8+!excS=d+ej{hL{wYX+uiC& z{j0(Z5>!;eXV{}!y8AYg%ODZe*7atYI#Tk>@LZGx6_xNAZoanrHj>LA5!KeUd1GxE zHX+O)K}98ehMTV)UJsIpYS#~3!^MA(o{CEN3_k5E(ey%jwpl%YEQ)IDdh%G3ymnLY z@A2Osq@of&gHQWNM74EIeKJY*TpebRprR5!gHQWNM74E|E0H8CD})&&sHlX`;L|=5 zQEgo>EG#IM>xLO5sHlX`;L|=5QEgp+HZCYbJB1k}sHlX`;L|=5QEgodj~9?(FNGN- zsHlX`;L|=5QEgpg<`j_Od&3M8R8+!e@M#~3sJ5-zpW+m9(>1_>%E;WPNOk3>{k*Rg^H%E;WPNOk3>{k*R`kfOP{k z*Q#0tWcEv81_>%E;WPNOk3>{k*V_IC%E;WPNOk3>{k*QXyAkfQbP${Z^a zR8+!e@M#~3sJ5=Tg$l~zr@{;pR8+!e@M#~3sJ5=pdKQ!w>0t&5Dk|YK__U8iR9jcu z%?0JnU10_ZDk|YK__U8iR9jc0+DZ0WEzBT6MJ0R&pZ1Z6YU^tKYLZOO2s21fQ3;>H zr+p-%+PWGRzECQD6K0U0q7puXPy0wjwRQd2|3dk0L6|{;ic0tlKJ6nB)z)>x7Z=Lc zkAxW{sHlX`;L|=5QEgpqN)?hV)xr!CR8+!e@M#~3sJ5=Z+82^Pz7Ic3NKjD;pTVbn zB%<27@;_HdHm8OeB&eu_&*0NO5>ahkCzceFI+uqTB&eu_&*0NO5>ahkAFM4TDGS15 z6bULS;WPNOk3>{k*Y;I~#M~Zckf5RxK7&vDNJO=D^?j?5G}#`WGmxO75EvgwNp9J`z!FU038QBy~50=b|L2 zsD#hp(>@YWZC$eXLP;ARW{{ww5Bm&Mw_`ZNp1f znSq-h@aG0mZCz#Re{9Ar2>#u^{TT!mmGBwv`Mlk$dahk1@nGnTI~umNKjD;pTTbfl89>S8k&-B+7@e?d7emuic0tl_k7-+UAlgd zh-&L9_x5trp>3E!f{IG`4EKEAon5*N5>ahk2P-Z&bryvgB&eu_&v5r++}WkeAQ9Ep z_2sH%rsKuUGRKMp6_xNA?)khsyR;FhB%<27PNpt1CkKTYB&eu_&v5g#-PxtfAQ9Ep z^>DjoX8*1*g9H_o@EPuDpF6vB86=|Gx+-;EW==F{o;g+|sHlX`aPzg@*`>=M5!Kf9 z_tVSF-o;@C2`Vb#Gu(V_cXsJANJO=Dy|i!;eXYkvAB%<27UjKf%`F&NGL4t}(_zX8++umjI{U8z5*41Wox|x!< zMdnzMprR5!gWm=u5!Kc;Pd+lUYJ?disHlX`aPzg@*`-|{IY>mcb!|;rVJ5Z=Ge}TT z37_HSYumdlK7&M5Ti3!}E6lw;!VD5rRKjPt`P%O6()EKxR9n}VOIDfzUBe6#R8+!e zxcS=d?9yeBh-&M4YwX9SzSdOYuH^ZxO0{~$p{C47dPukFq*T|Y=fwRLTIWwm`jb(ledic0tlH(%SGUAhbs zQEgp?uU%ulYaV8hprR5!!#$sO=c6uzL{wW>g=f~7#izp0T@qAO!e_Yo+V1&;%ODZe z)|K%E;WONPZTGanWsrz!>uNb@ zjhTErJij7AMJ0TOJ*q{&H$ft*t?PljYfOWwVFn2*D&aHuZ9o!HZC#BYS#7SmE6gB4 zMJ0TOo3Cx}veb2BMIx%LYucBq%%E;WONPZTGanWsrz!>x!!;e zXSnC{ZuXhW`01-LCh3Zy{CJ-B&eu_&v4J@-Rv`$K_aTH>)=gK znwE#d3=&jS!e_YW^X}}@Wsrz!>-wziXj3C2%pgHUC47c^KJR9qxeO9fZCyW37-i<< z3dS%;4iZ#U!e_YW^KSN;%ODZe)-`|aNb^g@FoOgYmGBwv`MjHb<}ye`wRM#&JktEu zKFlCNMJ0TOdp_@GpScVYQEgpodyg=GycTAVprR5!!#$sOv(H=xiKw=&v4@A7EvLf_ z5>!;eXSl07H~Y+GkcevQ>N9G%`J=^SnfnI`Dk|YK+|`|%eP$z4Nkp}EO*O;Ke^!JU zB&eu_&v5g#-Rv`$K_aTHt8nSz=J868XZC{x6_xNAZoamgedaPqM74E&e$8<6@8`k{ z5>!;eXSn&=ZuXhWAQ9EpmDXgq8TxmaL4t}(_zX8++s!_686=|Gx^7JyZZ7XIEOV?# zP*Dk=;pS_**=H_;L{wYX?S)5}4$H#~5>!;eXV`ga(fdV7M74D_m@&fKkvBE7A0()# zgwJsEwcYG9*AEg=ZCyF<7-^=I4>L$mQ3;>n=4-pzXD)+8R9jcWT%*ht5@wK~q7pvC z&DVCb&um5x5>ahkgEx#aMeYqVNKjD;pW)_fyV++hgG5wY*S)hwn_nLcGe}TT37_HS zYrC^cmq8+`t*g)AC(Y>QVFn2*D&aHSd~G-T%w>>>YU@g=KgN97D9j*1MJ0TOo3HI= zpScVYQEgol3Xe4vYK9pksHlX`aPzg@>@$}^BC4&c!;eXSn&=ZuXhW zAQ9EpHK5Bl)8MyoKPN#&C47dPukB`^xeO9fZCwkGj5B>^hZ!WOsD#gOS9fl{n#&*& z)zUcAc=O4CFoOgYmGBvEzP9@|lFJ|w)zR9n~4TgI6slfn!VR8+!excS=d+eoe-B%<27YEBw! zilu}ZB&eu_&v5g#-M5ik28pP)uIMUkp1U3-K}98e2A}q|pEf(n@@rhvu2`Vb#Gx)TRL{wYXt`R-W%2{Cs2`Vb#Gx)TRL{wYXNB`Ear(8e%> z1QnI=8GPDDBC4&c-_sA97CXZX5>!;eXYgqsiKw=&Yj5deY99zQNKjD;pTVbnB%<27 zy6)|3HtY*CNKjD;pTVbnB%<27t{&Up6x$YNkf5RxK7&vDNJO=D%`Q67^!X&rAVEbX zdG1eL zf{IG`3_k565!KeUz5S!6@+V;i2`Vb#Gu-`{@cAH#sJ5<$nm%ggP6{(fP*Dk=!KZyB zqT0Ha=X}&$+d9l3K}98e2A}qkh-&K^)^UhwT{+AkK}98e2A}qkh-&NVKk^at{$JsF zA_*!g;WPNOk3>{kSLZH+&77@a1_>%E;WPNOk3>{k*Qv_}nfn%p86>EvgwNp9J`z!F zUC~w8yfdEst56bW>zO@bB^O4^mMHpW&X* zyR%D|K_aTH>&Vs9P1V=J3=&jS!e_Ys&z)Vm3=&aoT^mzgFf(5dGe}TT37_Gf&%3ir zmq8+`t?St1)6D&g!weEsRKjPt=kxCD(q)i{YU^6KWU4v+Nti)`ic0v5*tY?(tcbR* z(mAJ^zxIR~B&eu_&)~NKNkp}Et#A9hNxfiR=6O2_Dk|YK-1B+6SNX9b5!Kc;;kzlO zXSFbc1QnI=8T>XNiKw=&K?A0k)OKM82`Vb#Gu(V_cXnx4c`Avhwyu||PBC{+4l_tl zQ3;>n=4;!#EIxxoR9n}-E}mj!U6?_Fic0tlH(%SGUAlgdh-&Nlvgj1E?yoR|1QnI= z8E(F|JG*olB%<27=E@Xfs=t}JU6G)o5ahk^>aRN7EKB>NKjD;pW)_fyR%D|K_aTHD`n#I=F<&kQURC{d@W{{ww5Dk|YK-2E7L zcIh%mM74Dd>N4HrOA0ecP*Dk=;pS_*vrCsjBC4(H{u(cu`_2n9NKjD;pW)_fyR%D| zK_aTH>zSM{nRyxEIwwIzC42_I4M-xYt*h*NFPS$sg&8EMsD#hpw*g5+wRH_?Hp5hS zE6gB4MJ0TOo3Cx}viPwg5!KeUWcv(LYgCv)f{IG`41ODsL{wYX#^jl%!UJIj2`Vb# zGu(V__k6;wa}rT)U9Ubl)3h!VW{{ww5!;eXSn&=?rDR|AQ9Epl{Rpu=`u3RAVEbXe1@B^ z?VdKc3=&aoUFVgbX`XKqW{{ww5S`g6$)bG&SrL4t}(_zX8++dXY? z{U8z5)^(!74DTaiprR5! z%l{_HcaMh|B&eu_&*+8u zq9mf)x(1g|l7;^XGe}TT37>JJy&jyAc|AxXs;%qc;RR*Df-r*w6_xNAqwMqf7Mb%! zNkp}EH8@m2O79FaNKjD;pOI?!zipZGMM*@pb@FdXPj^ zTUX!l1>~xq!VD5rRKjPhwEJJV%ahkJz6D6|DIt62`Vb#Gwe~Vj@_&Lc{_=y zwyu*&7s`|&VFn2*D&aHiQ7yV2BoWot)%l|f<%Ypw1_>%E;WKvF>%kW@uLns)wRPS7 za3N{gDa;^2MJ0TO+yCrd<;RLdR9n~mmtG{(>V+93sHlX`ut&9YdmQu`B%<272ETcc z{P?dhg9H_o@EP`~mTr%OK7&M5Ti2!43rqTU;XX)$ic0tldsIue$3dS#BC4(Hidlu_ z`)9)p5>!;eXSn&=_BiOTqew)xbyfYXuynm6%pgHUC47dPuWgTmK7&M5Ti1tGE|!%) zhsO^RR8+!exc$!_2Ym*KsJ5>2>R&8Fr-d0LsHlX`aQ9>EanN56l89>Ss#))1xy^(b zB&eu_&#*_ebbB1E70_{x>jlz9@;Pwyt@@3(L~_VFn2*D&aHiQ7zpb2kW|ikcevQx~E`a$;caK zkf5RxKEoc>((Q53XOM_$>zbH)k#zkcJf|i>MJ0U3&-VL+uV-Ell89>Simt-ux$8j^ zR8+!e?6l7Z-_E=qyr+IuX?yzwf8360>&lgOy%E;WOO*m|HTh2T4S=buHddNj{$w zW{{ww5*?%jotr7W?m1Hh-&L9`EzASn;2%0 zprR5!!`+W@XP0iQNJO=D?R@N7DYrJvAVEbXe8vg8|Gk=dJxC&|t?Sd`*U4MQ!VD5r zRKjP}visl6%W0iwMR9n~F{#E3%%fk#3 zR8+!eG_?0)+}WkeAQ9Epb;&i?%c9G|3=&jS!e_YqG4AZrWsrz!>-znx>t$P>FoOgY zmGBvE|8r-TE`vl=TUXAZRi*g8aGjH&q7pvCo`?PHt$C5CE1QnI= z8TP1_ZjXaLgG5wY*NUmtr0&o#g9H_o@EN?iBN5fs_2~uGrS(l=1_>%E;WO+}E!`dm z-DhGB5>ahk-?yqR2lt1cyCkTngwL=?wRC$N^cf_g+PXSFS6$?pFoOgYmGBvE|8r-T zt{)_#+PdbyU0wdH5oVB}q7pvC?SJ+-=&uJ!M74G8f1|pr-W48eNl;Mz+2a zevpW2>$-VNb-8z3m_dSyO85-7|GBeEmq8+`t?QlJt4pJs!weEsRKjPt`!VimgUcWh z)z;PQU^S_AI6O}zK}98e#(KN|J(GDoNFu7O>vZ30((BbQg9H_o@EPuYj61t@{U8z5 z)>U(VRXNl<%pgHUC45F5dq3vc%Gdco)^y)n!TaiprR5!!|i|W?9z=DiKw=&?>6L!;eXYlHd zL{wW>&l34$!q;I22`Vb#Gu-_c_q4(FgG5wY*VvvHNT)+#1_>%E;WOO+=gux&28pP) zuGF=8rF?EanNUwh-&LbK}98e2Cwc&M74FLzm`XG z4G1$xP*Dk=;r2gwcIn27L{wYXk{Wqr&j(=!2`Vb#GkA4JBC4%x_TJpmJl~U<>w^Rp zmGBw7x+4+Q)>Zt?+>)bpm_dSyO85-7|GBeEJ5;G8qT0GPP0B5|zZ+(dprR5!!yeV5 z>p>DxZCz8R!;eXSnw{+2f!)o~M$CYU`^1VQ%@UQ#H zt2+`=ZCzInE+~C(3^PbjQ3;>Ht2+`=ZC%&xFDOs{6nHt2+`=ZC&g8C&_>YVFn2*D&aHS{^!mv-F8JHs;#TY#3ZS59LK?kprR5! zgI9MXqT0F|j7yT=r-d0LsHlX`aL?!MeNlHj&p{%pt!sLxBpIC?W{{ww5nd66k?dhnUd>p>DxZC%k-*gSVV zNP>z=_zbrmg1^+d;kUs|v7eH|Z*94HL5}HW=LfHdt3$W@e`?)Nww9ATduw{-xAU%- z2a|8}^=BPR$?&flE5y{2k4mB6p72WdPacyAS3l|N%m1&x9I)r2*)yn+`0tFta{8@t z3bB3jdQ^a$zP_>4DzoFZ z#R}25e-HEPu6|y5`G-`q`1x+W-r3+;^Wt^=72@?=rKM&4=e%;qm@@Lo{m=UP#+NHf zvv$)I;*+#*Ov%?edgaP0-fq}#^|zTDE(_}T`l#DwpZV|3cfBir!To0XolAT@ z;k`X(@s~jzCyq4lF6|#4?_H->caxo$2X&4zJ*53&ZFDzJ>m&az@o!JOnbAkK)eh>V z<9f@W`9U4e2(Pf+x(%;{UER2R9(n(xU|Wb2b1N5=t}h153eSBU5uT%D-%7aL@Jjf9 zXE2>ac#WGqg9Kf>j{a@>6&UG9B;F4yB*JUl>={(Tt5oOWk`iZ-2(Lf0XK-0`g;$f= z366Vs4(D84Pw`e!ArYRPWzQf%SMq`+`RdiDl+mR^B0M|GoPeBs{Zp%jFox2`VJQbH?ng zB0*Pp2AG|o5}w2T^Hz~~A@e*jdj?xYS9q?Ko#1Cic&Es@_!$!)D=H+ydqCMUNYGXI z+tX%vFYR+Tyno@A72aoXH9uqGt)k1_HE3?{U;J-^%OVlp56IpR5_Ith7jG4N8{WTi z%T3&KDkQ=?Q`uWZg0ApBQ+9%906gk{ac>_PbX@zSuGD#ev{)2;_LZ+PK$eUS>cr=8 zR7jLN&|lJ8YoDSd=;HZfd~~UhxO;McX;NFuAVF8zoBGT8G8#c;;urm7>&1bKOG?}- z5^0_K$?^PJ2A4(Gq*HyRLqUz;+1-Ce^bzS6xPHF1k6b@lBdF|4>LbY?XSx!eCo+S? zABTI(g(tKO5_H|Tt+(W^q-|GJitOkuPqoc-{i9ZqcATYh{EQX%pA z<$YxH8ZCnaU5WQ7uG`s@`pRWRgAwJn5N{O~66aUxE9n)r^+6)$`bVQnV(I2Svf_3v zgQH6qx5{`wy1vs_nso`T4VsqdCpCKq^{H}0A8d2-5{?hY?KgDcbfw@Xc;8v8a#Qod8)leRQd3b z>0LVLZH2oJnf1qm@yRphh*|fkHda(flv#Gryu1Ev1YKND@v)*pqUWUtP3JeX3=(v4 z{l_!7HC+C|K9lc}V7XjUoS;JD^bdQ@;2~#g6pT=K*#&RZI>?Y1#yDy-BEv!+4B6kj1`H-lYcN<7im4`=+ed3##=>& z#K~WFo2FlD86@c9sK+x}*EnqIE)Pa=)(wZvk}*Ney&z6dA+aH!UDAEp`XE6U_sw|5 zu+e+Wpw+?t{MtQxP0y`C{c`i;=E9VZmE#9L0Uj^?gPAohAoz(9&!9r0`lmmbV{d4m zB_!x#YvUQGw;nP%t`3&#m~RWXM+S z9vPRrc~)n6s^{4X0eCEL=#n%TF5(8Rv zl+uT^3=(v$YL)_ zHn_b!&{R9?BSF{NrtM|^YK{1)RePy^V{qo(YFv96J}aoVjBF_bAODZCB~l@gysf?5 znSa7r2)cer=^(ATYQ)|>9c1UyK$-GPN2zz-M8Dks{Mc5;4|+z)ph9A4(}$$5o$;If zz7GkyT2<;KYai5znoo3>1`UH&J#)Cb)HocB6|Z;WYmf?wy489}*CzrxF+o?cdwWRX zA{s%ZRKp(f)a+nAGdpnxi4moGNS&Lst%S>px&G0$Gl>^BbeF*!wEctE&UEpaUc4V% zQ%M(emK(aC%T_|7=>E=fa~Ex$b1R{1(TXl|@E(nza_iGwZ94gINe~R6J=WRtV}U?eoauoLZ~K zO+IO!=^rTRM}Ie;7Yyotf8><33xcgDo%704C2wl$g9KfV?l@s?d{84ev!eU2 z`^`JAoNbl`_iYl5t~h9JJf+RcAVF8+(WOFS;gCaS+O5I5iH{Wty0~WJ1lL-w_fDGS z>A{wfcnwk^@$Si!rqeyzc141&RYy*mUAwfcgj?T?4nLW(ubpj6WY0+~yy}>F>gBVJ z6`o-UkhKyi7l_Jw#0*834g)fow4pZ{h6s%t+hgMSO=trB;>E^k-K}*=ec+aVj zm?s~ZSv9nNaD8wc{MqLX^Yi>BN~@@lI8br9sk2C1gCywsa@8`^@#1Dm29@7amzk4; z0vDGQ?>Q9`z1uA_`*&#>Bg&vo8f}!( zB|#VW&3HekkT`tBC+6vcS_TQa_!$$=m^WmzDR_0TKfk&NW8RjnHgD3+jdFNH78}c`MkeIaD8wcRCs2MS$s;{ zZ|yv|9`#Un$!=Tt~kYqHUNuu$8sNYIt|h|}oORc7GkVBMCj|FIdj;A}@6ZdWAk z7`W1`Nz=9x5_Ius7w`E4dDoZ*Q-k9~<40DTtL_SFE-6k>Au;XCRc3e|?TAByE{;e% zgZtVatJj$7&4T@o>pxCVA<=Ts8Z-I0)+!QoaYW)7i%;z_#a<7_z1qpI%#2~dr!$un zC#aA((0hxy{Zj3-odjL{w2Nna*ZCVW?cv~z?2*U6HV-cdK5N<9I6;NPln4H6y5-kC zsY%eqKE*R$F7U0nx^8f8SoyOfMy9v)N0}WRzcn8hYp)z}sE|lJhn@soU-tgieEz$Z zL4^e8?8p1D@%b-J@!6eydoO6T**rEdsMCw@GEML3r}TraE01h3&zC(L!DW#c)OD-b z_f{t*g9Keeha53`7W7gGDkM^u{MY%i3`4Q*+~ggWe|2phDuZA?wWqqxFLXUF_c(JxANijaX}H>_1yS*h3OydVFF! z&DGWi3A#8U@m5hG(QWcN)2)HFm5`u|;}*~08ocuS)#k+~f<3j$kToW6Yi+NkLV{=K z@eIy_=InURnvN4xNN`SiVuG$&@-L}1N_!GVg~a9q7fNdG$CR!8&quG4zdHs`Ew)a& zQr?~wJYD$hfh(oW)L`Coyj66~>Uo8Ho^&>X%OX+uipypD>smiZ(3Q9!R7jLvc$w@R zs%4O%i(?q?Ime1Eyrp;<+0;mTxT+d~~UhsPb_+dCR`x zFZ(k{5_ECg;u%y()VsZ$%zRXP9z}w##Os6K?c=)1b$uxrQcPPPR7f-(SXM5cH(lvD z3A)ByUQ)hZs%20i@l&@lQmW94N(KqK(ylBaHXON&P`~`;W1eNeN6#jXuNQA$RkUfK~qAUEZgX~1(iS|7Vd*}Ks zE_?&ObA@lp&rXEz?{*5e-SFMv*$FBn!Z(^{Cz$Tur~kZtv%hn(wec;H3W@Md`Pnl_ z&=tP-K06WqnuAlqUtRd;ts)Wro}6%yf_^0Q}c^<^=I8IO@kvM|{T}S`#La8?4Ii=@RNU%@wR`Hvj z{N^mb85$?3kl;656BBf8D!sv+S5Lc+qC#TFc?Bfb+uBtT?*Z^G1+VVot)fDLZ}dn^ z&^5O6zfJoC!JWxCL1o+Q7tF*1!Se`a#|bJV_*^70L095?8B|Cle#SzAEcof_g@y@n-GZsYe$pFG;k z{9RkSN}c*yS5vKE@Coqnf9sm&Uj^6X7jNxm>g^8b`1+ti;`QRUn$L%5dlU(}(*M=N ztXi&Rbluz6Y}gm{w%pkMrr5Ti-gM_cW9DerwNyyVDmu{g{Uo5{{UAYC;?bo-V&%v| zruRH8g9Ke%v+-7O4RWpZ8~KR&;4f{gxCXoY-Nn?anSE`>Gq~1Byf>(exu}MDLGedd=Ywe2a-Oa?w=dxXqcyf3Tvt#kuwkx{0 zO~IryP4~Hzj_veuH@wA=ETU^3NdErYo<)~_q}q-wyEatv5S4p)+X);3E4E> zoPIp$Ut)qT_9;&ATbTT2AiuR4C#aCvT5+e@I!gO?CJDOu9=~|T&E0R2|68!qkI!o* zt4Ou-t9<>)kSg+jWtRIoPEaB7`=qim=hD?@A?SK){uOfQgCH-SL50N1J;fy7AT5Ig zUA;~hl7}AqP-ztv66aMdB+c&DGDy(H?_kFJL50NX$>&SHXSAM^po{B2p0VzcM$%~3 z65qqG_cW3nGlP0z`FrKUs@iu(&)d~N9+)2N6CGb_Ah)dv>L=RWDX$;Y=IK)*(X4v| zY5HqG$6GbOV2V7^DQL;tAKx$EnqVDtTF_WV3=jT2PEa9{xF00wTHCO(RD4d$phAM< z7H`%0%^S(UIzbOFJ=#zz-4)brpKc^aU(&ueL50M?ry9!UmfBd6po^m(Zxt01*H&#P zTLx{w&z^zgZCi6owTrm^h2U)xI9l6tQ11Y-p zT(&C`bslLT`+wKA5^h&?nFS4G{MFj%azE&OJVkC;5-gYdO}rmeNZfG#JyLtP)+!Qo zHO+aCyxTw{c$UHQhqqcL%lt(jDSIsy62%_4L*8qktw9oWUHWwc`Qv8oOoj>xj(U8o zNYKS?I!;g_k$4S~po^av@eGdpk;5rc=dyEI=OkWSl_C%C(?*x;oUUn4rO0RRX~e$@ z_LY=Y!8O2|Iz6P;_P6|c{<}vf>HW!T$~vb)qVH1=$%6dac?k)+_T1A{PP7g3;$uaH z1pAkmpo^avae@ko#A8K*E`H|6GdQ{&g_rjXlrmFZRz{Z!i6j3vSkkZ8uA@lM)$qe1 z^4gR%C4&lyv{8>q-yYgMODZHbKG{ub{Gwf@lAx<_tzj}sov}rQ1m7DMA6*i3@m*+f zf(nVm@1P?=7vD`6&)^%^_&z!=DNax!!8gq%Cg_^eYM2!6tG%Cr3JJbpKAv%SW*ez$ zdiw1rvu>9;Nz#RDf=%j1Qb`mvgSe|x$48*Ox{kodbpCrMt@T3H_? z=t};uy_7knW&C!khvd5{n9Y4#&knMocQ96@M zWqtN>i)V0rNUSW{PCnSB^_&D zunxGM;{BjPVqjW3$uU`5gCyu0Rj|F3ep(|&kL)1rzY4a#a%(%tm?wgoeTuh=3W=(J z*d>(-=)?qFiN}iV?LVNsy!Yt2j1`F@-?W#m_h~)nSkcA)CGH1_7B_T|P9?MqE{iUX zdOU-l89a*eGbT<@A;BY2VuG%3K6yZ1yE;YL+NqGpW$&m$ zhWy`8xB9y4$lK)My!8}}9&IoOfB0<;aO?Bjok{Utf?%j2y z%A#O<<&qM&ibT&Hb)?i?+Sblx(Ut4dI#P9~whwOJSX+io2tLW)>{DC%wFqi{2FF`P zg~VkAYs-`N4tn-&mjqoEX4R69D`*6j;y2flw94nwDiW18)RY3EWw2Fr@yHPGITaF5 zb*m{4cGWUS(8Xg(JcDa$;jB6`X=t$4xMt%76%q@&)sefd($+Z%x;P^73@RkvEK^5H zeyR1G1YO+T;u-%Qc##adsixn4e&|?4Uc0M~umAcgx2zpiOWCfdkT~&tPATxn-3q~X z3-GN7{MLWGRa8jadC5jI=-bT#lT=Rwl&hev#S`Rj%Ga`up^m4++*phAMbrxDK}K^Nc48z-oc;5$JR z6LckhA975=drM=#6NnJ|YiaEYNXuJ-?PvRS1!TmOpysFpu)i7B>eVEfoN<>Q#fF71 zl#1U3^*cH8*te73qm1r}C55EU<#&2z#`>bNspf6I&i`B?*^(Okdpv^*iND$xl0UxJ zh;b#7WMzfm{QQN51*LM`pyvJ<&tThs?0=zryWnj7U=K;$@WqAl-$w#EobyC1AABq<95f}67s|8E&b9`*ZyzgIKrTCdw*8!AMdI4i`6W+htsf-l z;z-APzN%IMnf+2Q?rZxOki#c~n)^+hpzG5Q3rNxW=d#z5m|LizEPhJcqnJ+DXFUtb zigb;j(r$A>d2`pfw2DOI+DX#)n3lm-(Z$c>_*ilKDKn;!EPNzb=iEZ$1QimcQVL1; zlG>I?f-dg=@eC>?uETb~Xa}soMFNkMwpLp_ElDu})+4c`+keK>plI*$qY^|b; zN1}MEcn^tppm-h}C#aC%y{yCpUA%gY6I4i4-qu*Ix%FY?cus<@Z5yk|MRPkU1QilF z>f9=gHwEwHiMNUbT|eb2DgCzeQ8Ho*mRqFnb@FwNk!K<3;yXv;t>P0mK3(Lv#R)1T zco#P@L04?tfTY%?LgKEiO=Z~m+USyqxiD^suxEW-2PCfezdPmL&$M%D5_EB-;~7*) zROxY(oZn%rvIcpdnrHnSg?I)P5n0`c z3u?|BiT8ucz5HNTd0@oZGMG-HseR_$@V$VJXON)lhHYJC%Mp!W+mEGmlaHP_TR+%C z633@>ldoP2=yz#{@GJ*cuC73L09>@z2uJm8bRfTzP;pzdVz~e zO57?ErR>w)t`}<=Tozq>X7`f5+qFH4N}jY{a`=_N#U&+f6^ZHNdr7~3S_YRzSHq6I zWVX==D)lS(lD~_bORGrSvA3rjIvi}3iTgoU;%%1-i5^e)lxd%886@c9eiLsM_o9^@ z>^#fo&$dS~gT%t$?We@lv$cw@RTH~Q+c_FRrCjCia>0A&(kc?$zvw3UwrCmb2VFc$ z#K(#XiFZ=%G4VGog9KeXqQ*0L&w|&{yb6yKR7mj3GBH6H@B79HDkS(O*Te)}e4lNc zphAN0nvD~Cw^fp*nQy1#yW(zqzmn8{;6KWF2^A7O7gdrXrza}J?Htkel!Y4KTQ z`QpQ%CLM1T6%tKaR+a@hwG5t-o$gyrdc7KC)ZAZH4)qS|cm|hMCvRoBIwe>xv*QF6 z5{oxflF#R8ts+5J;<4iT=vK0_tjH0ZO>#+zTSa2kqm^Y-1MOUt%c6_#BaCNIAyM+@ z%91uw%OFA5&d08ma%(k$%4fx|ledlqE-oo?t4Lh7>N+`|q`gUp%c5&;|0;6X=sQGDy(1y;XHNxL^D9q0;%e>LSksE-op)KB$nG|8{lxvxb&I zg0B5!1 zAVC+8cJT~uKR1u5F87WLwk2+Fae@kocW$pPjnv<@BtaMZ6wjbSqS?V}QtPm`21(Gx z<8C~IGY2YGx?JARk$o0HoZww&5}Z?*n4pXI;o}4q5}$P}CBwgJtenY^po`~o@eC>? zzJLBg*>ip?C4&TAJfDkaP$4n$)L-Ve!~|WRq1*JPP|{nYle8MsF2`&l*9yGYi8aheapP8^n(fse)BD!L4q#Xd8>49_nMMH zg#^FH7SA9-SBJN2NV$1$C>c~p@LQDe3=(vmnsbZXP-vc#L4^dr4I0lNL05})SIMHi z+IJMGkl?pk;~9Kk+x)d7&GCvuecP`nJktEuKB(iw*u%rkmeYaKXVh@>M~mQ{aC|FU zoL~l*o0yyvqqa=9}H@~!7knpDkS<2e$tF?9?*#ix>D+oF<&;)hyh*3 znFhZN^F8FRJY4z7SX2H=ji5q;t&O*e1YHvfk2Mu)Y8g~W{Ih;6JTlJoot?c;@m8_z zBtE-$yt%txKqn^XnmuK_d3T4l&hMTv!rYNJ=wZ$~Mw%(*gPMJcXHX&0FxMz^g=k|% zf-Y`v@r(mEJ!x7Ve$=n?&)SYQH8O&ldvlziLgL2>qs*LK+Fnb7E`AclGq~r>Y%<&o z{W};@?rCv?3W>UD!_DO#v^7YAE{6J|E*5H7AWV#ZrQG`_orrOwtuW%{3b*sE}Bd ze~h{6RIrUDCg|c88YkG^(>ISd73&0TXaC{^6%r@bjx)P=Yuhdfy4b&X1{D&=ZW(8m zOwuw)(8W=YXYhBI_?BDltJ9fB7g*P$BVCt{rATlJ+fZ5_ECY;~7*) zyw%_>Q)ByZ<>*X;F7BK03@RkHEE;cq?61vEAVF8+x6o1{!M7yFTSbB{zWX&!P$7}{ zjf*7cO8idQwN2a0{MAqSasQ}Qd#QfozkSVF1o2i;A+cp-OBwjMcK?b5UA#9C&!9qL z|9kc2ntx4Ewh|I_@vdP!g9?eyUaTqe=TBEMNYKUKn2BdlA#um{YVyjDGn5Pxbn!Q4 z;u%y(ba}I~w7Xe*f<=O^fA$*+By!BEB)z9;8L?%-#oxM!_aml&Xt$<_9PO=L50ap3 z<>+5blgG5HJ1QjjJN5Bak)W&S@L$cwOSG#yDkKvB=KU`z9i&y);Lg_GJso7{(xB#+ zA8!>E694(Jt&CUSz)ylMZu#*HDkNr=YAm%1O;fgA5_ECPk7rOJ@nr5>W#uc{{y~B+ zZu#*HDkO5%yIGd*)wW#{bj7xOgrwG`LZa-YRb}AybCt0o5p!Y7M}(W#2ZhAaeAmm! zXS56wbaBg%XHX$g;=0S^{BHA=evqJxTYfx)3W+N1^T^_y+Iyo&&^2!IN%Ks9ji5qe z)sd5C*Dj6Vn>_zLxsSSg&E5^t zNe{_gO2&-TT1ABf`xnn3LDxk`uat{YvBN>C@h zlS+lesaML%-2U2jMS`yMC1quPU5(%<&YXRfOwV&JYmh|FTd$Jaiff+?T!VCR%a4y0 z6%z05DJAu8(lSWU#m~oh20t^7bu1&l)IFE2gv2c$m62m*&bF1%#q|_#6%`U4FS1)q z4lRQOUEJQ{8QdCnFDffn=RcP%k;I@GW#z4}wDrMO(N%tMS=ljLBdCwL86@c9XJtHtZ%^S{PWaA|I6;L3zeAIl zpo`B{;{+8FvG33TNv%tQE(!Qaz}XON()b&bQO?(z?n3@RkPDt_49^ovID z7Z&+jo%}?Nw~7i0{t9Pef-Zid#tAAU>U93hH2LKvrROB*;wNf6g9?d#73Y~wOSNwz zk)VseL=?}ULSjLV>1O8#uPFWCZ;1o z3A#86@eC>?uDo)onN;$1Wvochm3VZikT`Vw4O1}lm!aaVDw1oT$#s74w))(K_L(vL zg1TG%E#{%y-%(mcg~WvS_L#+AYQKm;g034&tui|@e@PzJPuOCre4%~%kf7`4 zu^*U6doNY`L4`!(UuvqK^Lev)(wlx+{3WZ~o}OYZdMNn!ct5C+;BRmxCg_?gQ;eyu zWl$lpspu55?l0}B%=)&^o74*eW#V^JOwVdTO*-BxDkKICm|{}fX&L>~W||%E1xnh$ znWoFgpiaCcuKQ!UDY77V?!@i*`05u;zLnbZC@Lgw9sZJ;_?<>9Tr$<1{v>6}x|UwgEklc0;+LOg@(c1G1H=I+Vo zvXzkd*Tqwetkbpt*VO$rUNrZecP?8AiDz=YWaedP>w{YfU0k#AR#72Q z_Pv+P>zlL;5_EBUi)Sobl3z^Q7yUWIW%gZaP38qP&obi#6%w3%k(i*1XPI$=3JK1> zNKDYhv&=X_g#^zA6BBfC)Z+vd5=cz*4(d*Do%iLBo>%t+4qg~W{HtY0!b zlgRoFo{Z$IJ9in$S-&xqN!XEff2rwNznqhiob^W1jO46e*EusI>)ogs$yskt%1F+7 z%h8!c)*JXUlC$1mmXVzGX0tPi<;U{L@OthW#2Lxw@5(18$$h6bBRT5|`Aj0~t*5r< ztGmh0%g1{n>z%1*5@UN_Ae|14@~)mG^2vm+gF5SO{h0(665nmeCl$8_bTF=NXx-?N zpsUNU{L<)$GYG#v9-DQ6T(j2AB+W>kTe+ZgeevJE&VO${xqD0S?@@*)sE`<(JHPDz z5`=A$`%6tyjO5vSb4&AlPx^lktp2~2phBYfo4F-NYY;x*%#8Hc z@<^@$+4F*>+yACIg3Be*s!CqjdP_hjCg|d*#|bJVQrG5{@&&XE5_ECviD!)bzKAUN zc$^v)c1KVl(doeg(r|{BL4q!B z`Mx<(1{D%57v+~iA0a~}=*qT7MFjWfcgq)$XZ}8y&k_=NsSy<(%p-a71j>d#bIbAfgR$Zm##=>&MEwtQ%TJxOHAsRkj@@8>6@qZk$;y6j+S5C+eZc+4?c0So|v9_Jf}k9^UM3l<~7>q6^WQDde8cq89e_W z@!0X+a{jYg1_`=~?C32|wbckJH*V`KxhrM5{!yz){BgLqTzEn|8n9J#?Mvz-$scP3 zm7j0zBiB#Pbp4}Nk@(MuJ|f+;47Q4{rJMW6irY1U=eXxr=_~0K1J~?HedV&E8bM{! zslL*oVBq4Cf^E=khHguwLL#kGKRKRX%OFA5#4q~E){8ZQO4*zG%lb0s(kc>nPwp>G zYM+te_b9fCuEf^{R7jLN&|lJ8pON9miUeKds|=7Oqt76GtM<+wAhU`GTX@#*jAkVB z+Q%BBztnUtt5W9y(qd7tTxNTFY5=9CQz7x_gaJ}%-x;m4RGgrTtqqnQX0Yv9zqXp7 zA3lRUBysV80djbW_Q^nkt~@e8{@SMzUEk>|&AJ4iqFM7xGLrep7xlxpiVBIWxh-dY zCX%3wpWso3EmG6j-Y$Rlmme<*TFCxIgl`oU5?Q}^o7pPsc7LhqBsd?k_c+N~b6L$@*S_i%SZ;&VFXANHi_cPipo?hQqQE zba7j7X8)J!GP0gj+PelH>@)cuaZf5Ul7IX6esefAs5AYU8C0%ne!%Q{I&g7Gae@ko zo|hgpo!>Yk!=mw4(Ump(;>`6yg+!TU2hF?d&&cpSCqY+*yAPT5$3a-P`%6uKyz~!d z);RZEHY0iPSfg1ukF+o@2yHQj~Z2D@KDV9siAVJq( zukSKx8{CYPGe?(7@?5*zsey}2iuZ#GiS?^?nbIA#3=(wBxnQ?xR#hXYEbX=1)I0B7 zT1DdIFS||Cud&WuXHwl7WUJ`nHXZLd6%vgn|6sN*(lSWUwWIzXv*me>pi=VUz2@3c zfs0E@+$s{Mf7ojV579EXEV}q95oOpSHJy7-l@AY@-lc=}!9C3rsR3t?2GPtcdrud{ zhJ1E5)qUDJCqdV&8xET#W6mIatFq=_*}KlsoU4rFthrccZtbt#v)A<88tgg4M(;6$ zR-em$PNMp!KbT{0X!{^P8R+6?Onj_T?mlRS&kC0H(c}YW$(x(5>4@;${ zvxg++oZ4r0ZbOEP$VSjLy4*g~_(J;Nej6R}Wv5=sPTaR13|4Vf}XM5Lu+)2jtK9`=8*gUJVJk?X{ zIme1FZf{|W-2YS4mo|M!`uaCSW+YE}rlZt5&%J9hBROjp`RT1f;Lk`V@yy}wQsc0;pEI4Vnoo3>1`UHx ziKtaRgT2lAu6{-`KV#wq6%twR3BXwS3=(wlvn!s#r*B7^cbE1LXKsD}=)Mn$7dLd5 z!5hxlc5PT{I`?h5IEL|7Q6Vv+R1c|hlXfLcf-Y`7QHF07*HrHl-DK{ZV6AaU5s`Z4 zRzjkC<8Ja&hPKYREV{C7?RNR@&pzSBvTl94tDGqRKlYDQM{rpr7Om(a2k!}Jzi=OL zCP7!x{hj6JE+FjkJ(Nx*>4MJoS0m4*RU}$f>LhC)M1~JIvsHBQ6C-Gk{coxxy8pW0 zyz`2i*_)A^zuA~LlM#Yon|0z53xT~i9j~A|J zkc5<>k&7ZjxGK+Mtu152W6WGCG)tOfI+`?HL%LF2nsCh`a;c6;X09o&sWN0p`_VOv z>$kpppLM?PeOl+|_WaT7`|9(3pU+x*@3p73_FC8NleTmHdZ_eBq(b7CQ-3mZrlfSy zBPTVdJ4?kgMwXyLqU-KonnN~*JV-E$=dq%P3vzj#za)-y&Jy<=U7RE3|EoEP$A13V zTySFO49DMM7Poq~RNRW^ANiyC<>SrSA0*ED&-dorHtGH^dgP?$EETi3pAy1l%U>?f ztgS|TXHK~A|2eL5rTd)3*DL>HDy|QeitfyMr1=Ij^-d7(_vJ5_r*eDmYBTBX%_$X$ z%6rzE-DbigF(|DEv)Iy-;uMLaw}0I%yZ@Y|4c_^}8|Ic*(^yv^FFme?oVUb$zUK6V z_$jx<{5&#^f4%r#^PdM!3S15LnZ3-+pMP4S95do+vtmvf>ssig9&4UlVY**^UP3%L z=^0b!l(UlfUyGhL!~3OiwjMv-`ikkkIxYJ_C%tB#cqEM*?6<*>=E!F!K~cDFPK&BLj>!=vak8=CDZYsa|0e!NW68|v#w6T zn&Y>aHR_vkA<`b?q5f_(IPk!Nvy25%v^hRs8l4Fb)S98%xw>%SgO4qT55Xt z?4In~OFw?ZJkYCK5`VGpQd6-o{r_yKsF2vC4Hi8}FzfZ@OH7{~(iWU}6bULM*ygjP zVm&Ue%A1~zH?32Va6vB5vXiJ=>nU^2n)EDDByyz$v&x@KsE|0})u&9oCqf=1n8ov0 zwp2W;wL1P8GkL)uo#E&~qU%n}&4@Sus8r0F_4;x%X6w*V!t)@{^E^vr>p_J?`Ktj5 zX61xk63pT?xai@6 zT>h75SD1rOPuugW->fh#mZdSbbdksIA6A$H+k{HR-(uD#dr*uL z4<4i4E`8QCKQ299*$N~%`O8VEsE|0V)(X>kX6R@q!7P@x;7}+P6%uEUTw$hv7xEy% zEN=CzNAn3QOoJnOC+(o^=oO~cxxJFO=~mC0zh9lkS%L})URTN!%;NEuC8&@nf3%Ze z7F$8$kxQL&dDfhDI&;+u^FX6MfinXY5;~i9;XbkGL4sL(j(yIw|2*WOb4R;(B-39o z{X1Wfl!SCz1NX1<$>ph#m^koxbHN?w2kJqBS>;Qmvu3+*GroGw{Nw%$li$@@!AomS z<;>=#S%M0QS2w(94tXct(&Y(eaZ48o7v%Cy z+rDS6csp%Tx*ks)>FiK=nn(y{=}J9ih@5!vw@Bm`y<@)LHB=80%+lGRP^!d(3W<^Z zR+_aB!oy|DUoKCj>H4?K&8^bC#$QTvC0z(AB(~}LrnzE7XrGf{md-F=S`S@!DUMe4 zdCxr4I6bSqKIA>~%1lgU9pzin>6Dvfo; z(o%v7i5aK8WBS()J$bQIEXk!;zH2U80K#oq`OD=w(wbwdIhH%km2@Gfkl?84gmBsN zmnE2`v&NLxoC*n@HKsu15)0=+f>}DZOesNy1i$%8f8BdLGOMobG5>GLSxvtmjiYb= zvYkEX+MBXxQ3vJnR7f;xvAw;zYDSjG2|*8?hvonK`i$SDkAdH0^kmx|?9>0bH7WanKQ^%aj`@3_9z&bK8jwr;YmxZOz{KBBh!FeS9DNHA;SNww{ZkEZ)SyFaKb z>r&g^cy^k_U&<0xNNn4;w(YW2$b$s4rp>Nx?|krrSJJ_R4 z`nx<9vZbOzVvFNx{d}=$} zZdB+fA;ByjW7$&ih}&afUEB7=%_$X$c8%)VJNEjcQZb8XjBKeoe^tk}SUoG*w>)z` z(5H^A+O=e#=VYH#A;F_3>p_B9cYa^n9&jE!-0#bu8{-9qMDR$=3Bh_?G^VZ{zF^Zj zB|n}R2*I+G7`1mj`^fbvU7ldp+3(b|?_U`rsJu97J3I37%_$X$?(OT_TPBrwxZ-8& z!K~wt*}?YtEOZ^DLgJ23>f2R!ggi(v>-`x!+Eb3bIeTWvNvWuixGuN7?f0*c2MK09 zU$c=taRfZv@5^5c zH-!i)B>Jx0)#low9>r3TU{?83Q6X{s(8l)rK_L$k%;Gkb0wsSr*;cGM&%vxyA>XA7 zL4|~_9#eV;K!RBlciqFjyEt_0>S{M}bkCM8?Agbs_lBgirJ_P&%LAI((TzhMB$yQ} zl{3rbIU7Z%qxZD4FH6U*==wjUHK#(N?K6AY2k)0Pk^Vn|Szo-lr~T%$bRLCb&6845 ziAU~f*EYE^`CWP!iJa7f3W<6Tx3c?3)Bm7U%;J8^dQc&8%*2-V`BT#;fbs;hxHq#z zt4DURt1nN-AvV~3SNq{TY0Mc!5+av!xjYpTa|i8iU#V9zR?Sgaf>|r4HMI}T4G~m+ zy{x(Yy-zwmjoxW_+`pT6kT|?aOZ!IGlF^0&W$M8!9-&zeDkOgB*~->GBQ#cx1haS? zXFd2WJHKA%EDS{=sRtDj<-aB;!7QB#ytGA8Au-qPY&(t*jbddFINv$&y>GT2R7mjs zLy^eI9wfmmzQ4{AR7f1V<7;N*dq)Ra?GHECv~?~$AyNME@(*Uqbrngx?3$0w!X7qD zII~>-!`4UGZ9k|=6rG1Yj;^@w2>Z{4>Hil?l@L@&Jp0uV_OZ)Lh@5!n4E%BQrvuvC zPmW0YIdz`>(mlA(+>Z8{eL5$l+NJIh_L{@f_?Fw-+rLyFsr7KbFMnAN{;tm7U+SUj zs=M#twm86^86B1U?$EOju)nT8LOl`#@t{JYalXCn`9)g7q&P)_^Xn&Ak)`s;R?9@*~1Z#Ly{SNk=IceFsMT(_z zL3Ue_nA*RCJ+mKbE?BOVU>3KVBqx74A*hgO{b~nW$A&yeFl&?jAts3jkG}gaKEhsd zR{FdAB}q>Ha;2pr@#bqs*sHGnqf#;J{+1PXkJm%QmM>P=16OxRj#19a^vK)_JMHrH z{|jX*)Po9%1^p}Ram`BzhvxG17__RwHao8CCVp8D{w|3VKCZBB7p8Q1f>{&ZsIa^5 zk)9=rL{cg$vmUCj506c==v^doQV%L5uDzndzPqNxV-tc|-?Xo=j~s&b;j-l~muJg4 zdtwJW`{~VTwImMRw}YL29Xt{P@nEZE)>$jt+wVJv2%c+iY0}<)_g1gAfzEmVeU*6t!=os?gZ!wGK zv8)H%8r#JG*3L=rcq@9iAbY-IR=;sa*^6p*%3g62f(i-F%2xEqiASGxJ?xZP!;;?` zG3Pv6WBTAEo_N@Kw!^qIP6(GRf4MxB|GeJQcI%a9@t4wENiX#v@$w}-ZPXSXf^9-D zYeUnX_KvRyWow=g@w+|j=vz}|-RvIrK$FJDZ0K$ej`{@%DkN^bw1=Jc;lMv2m~~K} z9(LZa5JBaX^Lp6n+ooCcmP#joIoVcJNHo5GTm?`0pqY;!zFjIZ0vwzvTviGg_VoWU%fiIUkOJ6=yZ3&c&|;*ek#_kYnt zZ1OxB_I$3lop^P6Wbl`Y#3rR8F=3oLuHOEm+$OV#s+uJ)VT zWQCJBI=0ri_Vo7_CGn>xcDFzDd@xH$Rq|9w44rzuT~Isp)fNe6v4m2f4R7k9- z7-&0w7%CMBW^Gb)_xtjf%Rkqpo89-Ow6^bl+SRU_oyL#seX`x|z{S~`=Y%+YKxfu-t%Rs=FHk+O=o-Bt$#%Dw@B=FU>Ez=sFY4BkW@lSMS@w} zvsr?3M04)w@-?SI;(`U;?AS5scFTH@U>3J}mSEXOOzmRdJUgvz`Fc-ymzFJ;=Mg^cjVk;5myab!2Df3h9#lw-y1mNo&^WZMNHB|Yd?y~o zQt^0w;nJ?Q>)by&cDX-DyjQ=g9XKmgDiX}Q z-R$a9aaWLr5jm#5Nhs}t=J zV>ZWw#1Qvxx80%=kDPe0RLtU$pVY%;%U>?fPka|!dQGH@(+vvH_wj#kSwwtU6kDnzQy4edZ z+MHvT#Eec=_R;G@MJ=l5ItTS!@M~hs&0~T%P-b+l_lR z&6RW^sE}xU+A;R=&Y@C~VAf9WcDBD9wlr`D!1WloP6O#|si=^6@a)JwuuxV3FFlu# zU{?83arFq6@TY05?EIac4R}x?G4+An?N?7M{{wUrKW&z0`vQ=Zz~*Fl*($tIf*s%K}FU6%t$#CF{WzRk+fMt}#>ktfni` zxEc4}m|}jrazRp(9Y2_9exFp*&ZYACi{7a;XS|(`TUoa;GFR?1Ga+H_e)V#VD9)fK`Fsses7n>u#2oWs%hrKQ{ zZJxg=*={ejyv(%xEsf>p<@e>!%}0jc8g|1)=B(A5Qx6i&HV!i9zZNPLYtF1|#tby8 z9t{yIX7)8(*GrW>j_PZ!dp9jRkI=LRQVFRC6%u#;rLUcET6M|WfkL+u<9~>g6 z^!>fB>C|C!N=0JkOa072bweJk2ea;Ja-?}>^tH*}lqw{DIjK1n5<9HyZ#sSaw*Zmf zd7xRoG*woQ9b}%Ko5s4ndujWiLgL&VE;3E73we-WR+GnunDfVl2rAus4K+WE*_=|5 zs9$@Sd3SQigQa3t@7cr6YqyjTZWHJ7y6$`&Ev!zo_%l4lw6%`WOH|lRj4-A!x1hd#~vK~}OY;{;av$7)OL4sL4D`h=+{QSDhNOQ`g zn{(`vxS;PSGk;~tk(lg39=puCWZb3ZiT{Fd+47gm|Fq3;v*SO;CTD=!{d=3=AIK%~ zm&=bbz4x9JI5SWoarFyb%;c}rUrK*n48()q*LE8=(0sq&r#`U*xx zQn}xkzg(UKvx22c2!0{`!Mt0{bzh|4&hty=h)xOH?oUCSE>Y?jF#*wag8%MgrZYjZ1={lovq$`$|60EJR z?;S@hVYVJrNa)Jlr5+@hrRyStaAvtYYpAOc#}T(kwp3I|=qj%8$cYCDX6YKR1;S;^ zpZlh|xI(X61G2cj@BeySkB_{V9#lx^>d+vZSuW3`LDv)h zU$-s^UCS6A$+qIwWfu2rw&rX(y3+Xn+GVq-#3=uls|9 zt`1%5LHFz4pJ4_abYF5sW@)qAiV6u`E56i&1haVbWId>m(6#AHJxDN%+c4|FZKCUK z|F2t@gs%1d|CNeaY-vfUa%tIe`AW=z%UM=AYh|_`R7h;{rbw`yv_TTg;tCvD4=N=1 zW-1}v@5^6yH4kP5-*_d&wGAejeLAFfth|$L`urrbchmI$lOHeqg7%OFbu;_VHx_g1_5((G>Ii@GFz7c{8S% z$5y4W{Ji|W{JH&snpYh^(Y)Su)2)!^O1coNEs3F{t}zqNDA`t<5X?Gd?gaDwnIVET z{Nm7S%-QSG+H#9zOGSmm^4b$k^NpcxMS@w?Z%;J!c2Bo-(ZdC9Rb6bwmrkByPUw{G zHE#7HkrRRniAUB?Hbduy_Bjb=ZE}>j-lQ(A%lIXJKc(c0=?GNsA zX4O1qoSCtAh?srS7<2jW=@IwxpU0TL-jv3CzDjE#m5_Q+A<>}47;|N79J_)g1eKX) zjJbYU`b5WHlH}wsSL#9H;_+k5FK6L-P>@XsW=&c*#=P}g$x)IJRGu3$*8FmJn)Sbx zip1^>#+e^`g*^CM%;GUERY?AFQgbRK9(Zn?`EK8k2MK2JOjK|vY%8{$4$~%?##QO> z@|Us%6%rc`pKKOQD=C#jv-MyW+fCMk3W*<{n`}P*xWpqT9weCc+hJ48z7-`$Nm42* zw@#R1UYwI=@t4Y%io}owQ_MeWhmLms7PEMsPdr>5pbE1vF4asn{#F$(W${$ z(|c*?e8n>Zvv`E2<&h#usi=^soHNGk+B@Vyf>}JrBp&Yflxsomf z6%s#AzQ;WBLE2AMo?uqRg)f{rXl)+NC#-koPXsF3K{roY*L$Un5^?)T--%@lIY1k?D@bUY=qHhCwL zO8`f3-YD*W&P_HOD znt1u$rscu^3>@t>k8Ey_YO*v@&U&G_UHDl#F8J|Jo7ql>rvINU6%`U3osuQ!F?(Kf zd+XMl`eh0JE{W^vwy>XXToR}U31;0kvV|S>ONgK{bxjL<<`$b%DiY0)X=$q(hPD+; z#jIoQXlYlrDIwe@aI;e`YGog&%qKP6cvmZX$FMZ!sHg0e)!mcLw{%D>KOZr2{YIi(_T&+pA_&;8($7?hTZS+CvO z%r>YSBDVjgsolOR-M0s=Z)ztsN#pWukP3+(er;-}eO7WL=A=|4nDy}<&FpgzhX^Y1 ziOuZ7v1t~6Nh+QEmuKtT^5j-_?8?n)=Op@U@7j5d&{4utF^es@So5S* zEbqwMTiFNS-kfbk;^T#_>|VA1=%;krNLpBp&SiplSc%n7|zX31;!#K-Pl_ ziRvv^nc?+@1w2SFi}Q$QJ*bf2oYLh9W^oSmEJ1}t`T40yFpD#&XFWJ?6zBEk3{+Wy z3JI35Ji)9r-~4VasWUFHKd6x4md<*RU>0YE&Jt8e@Q5i-FpKX_vIG?pJo3vE%;LL~ zEJ1|?TX1=TS$ubrC8&_tWNegRIceu4n8opaSr5+F*J{Uu?7&6oJb*PXKhQQ=TQVnL z;?Z{Cp?0g@>3M0JinjKwrs??2k>9knKkkOHoGx4b+}lC?)=zIAU_aP;T5|N!JI$4J zA*hhp@y`d?g}bD5d4gGY3~Ot5*)>G4yj#vW!0x(lT6Wei>p_LYiN_ykdmfFN3zn05 zkYHAa&kwX;4Jjc6${#lIV0-f9>yqvB`Mn3*XV;|h+gDrr?&Q$^phDt-hYq&Cw!c2m z&Pg!q!kZ4Z_Qnz-DHW9u&pFtB`FWbfUvi1*Ury>lg~W^79Bj`$^pEPnEFKHqV$-99 z#Il(O*~-g99{eq4@yJg+Tpi@k&5n=bXP4#s+wbaa&aq44r6&8^2RHmtshG9;iv8@K z&xMH3K4@(h7v}gp=&P;mEAvAH zkLurs9%KjqV{=**iPOJ4$aY*8Y9DM-%;NEutp^nn4(af(<1On!g~am9+SoTbhxR!MW^vDEJ*bfAzegLptVYO#1haU&Wj%N_ zRMcu?_o_;d4E|Dp_J?tLyf+2Ok*nAi*qNce5URKIaoF-<@R%DkS(NVtImD z8|NQx+tp7;R%Hn)B>1Ifd4gHJA8K#+ye~AD1r-wf!Zqtbf?0O;k#@j&m|;V(oE%qF zNN|petOp5Zt(bkB9ojN9?*|nUoZ}+vL4sLpo;=;In><_Z09+m9FPHy%*mm~41;-^y zmj>I}egB=t57*e*t+#%n5-CtZFst3awzKbCn$m^j!nXRPPeXh6aTUpL-SS9X+om#| zcW&}-_3YF8q;ZybZde_=?&o6@VtL0pcHV7i%(-TZgbQ2`?@jgXTe&przrE_)Up`9X z+h1;E-{^2uwjMblsF3K<%>B|qsE5mzKR0s=w$C~LsAs3g|IfC{3Bm0{qT3Pm?9dJH zNDN8|W}WwDU3>o;5bpOAC{N|3L3Qo2{N|L3#2xkP+DE6tBQYo~6|-J^vW{(Ze2Dn+ zygK&m!_)bKC(f^9$9$IV=ina9i3b%Dk9=3hUUggOC?UZt9&gD;D%OJviC??bwU=KI z@*u%19>-Y^9@R6isb@dkEB#&mQkI}X;+hTh?A?d{QK^`{cEApL0p#!IF@uQ=^XE z>5XFo=Moak+V8j8cIyj61oxDEbUQm|%H|v;BzE7nzO8%}`@FD;b9o+D%;K3ZyFaLq zXjWC<4%nk)_HT#g@>E(*tZyH=G|l2KmG>Yq^uhY}qz_9xa^k_?V%CSt>sxbl$<|Fu zMdgX->f5RXX%>H}e5pwMu&BPR*fl+3$`j1ul_*Q_XxLD@)_*s2yi?2|soFGD+Gr5-? zGxx8_Z_(qeacA2RSC+h6$_YV*1fScJA5RQQ31)r%`0@77JBPk~r9y(w)L9P_%zEkX z9qa=S+#1+cR7h~OlB@>_W*zh4LH4e%Zx47-A;I-#vK}Ou)%X53_PoR920W;c;Ceh+ z4-%QIxvlMxSs{-aP)KmhRMvw8v(8)5(0(%{^gKv~1jkHeJxDO?l3!}tIomuO*j7|X zyz=w6X5Okt{(xXsqcPu`*LK7#g1NM8x%`Y9``Aufr0+%8R<8fLr=2n~G+vYn2_Dng znv-DG+-BWu$ND8}ZMl-UnL?nD;4z)`Ai=C_{&b{$`mWH?PK5-I>8u9{W^LK&FuVA( z(2+=m1dr*g2MK1i+UY<$;($8>`?E!Y&jUkVWg4V@jI_p7#S-b7O zi`}aK1A%%_A;DIV^&r8lw!OBtkJfxN;6a5%{+pl7D|P>fVAka6Kbsqeg$T~3dVHI~ z_V79s65K zmnWDt`N08p&i5f=&o%?>Hjk%A_44Zm*q-y#m^0EQ9=X)Xt;mMo`u?~9_TEo7rye9; zTi4(2`BJDTjRAdUHxeBHpFH-R%^3NX4B`c1~GlZSsz+ zNKheh+lGF&bBmA%31+qXpr3tfJ&voQ2bJz_HvBG+r&;_ZNlyN9QV%L5cKx!SJ#B2r zg9Ni`)#-1iRD}p0OOO2Ij*^*Wjw>lvQYs#CB%bc=X6(H=blxSwtcPA1X!n>MBB&gF z@F2V6g3T!viGeo^va?<+@sO(ISt@4nj3Jdy{>4A#u!SgX~x9N<20pn8h+B3>+TBebN&{yKAkt%4*jr%aAs~MXeiCx+8_OP zNZSN|seGwOv>Q6uw(AsXQT#1t?Oi$89y6?jNJ>Rz(yxPTyW2LWR3y&5Z;*X#S&7Fc zTbEfp^JQyJg~U!L4zi0r40(`X7OzBE54Puq75(j~=ILHz`_B?oNIaZ#XNDg`$1VwG zvE5`nsF3*ZU;XX2Z-qQaFpF2a#3PqFx!yjkOT<;!xQ-NOGSkQpO(rK%;GVf zC8&_#(^7eYS!|nGf(i*fEtMyj#h%72L4^dLmdX>%VvlK-ph6<^wB(VTT%$-Zi#@*{ zNbh8*kl@o&d4gH&^Ue}fNbqT?Ji#pX-De3ZB=~$)o?sToS!W3)iJ1OyyD#xzs7Us@1=rKh55~S5@-6T&E>lDk>zn za$0$US-cWu2`VHuSsPHWoE+^Wm{oqg)ETF}WBS+bk<|9mE8jI2El6Ybw-rkzHkqC{ z5^Y{uZ|tpS2lfYli&^Xu$a+vA@zKrO*-y7RC*VPXS-hfVJ*bfQ;I+1P`#bssJV-E$ zTRrPRg+!YVy4gP;c~QWF1haU&Wj&~n;QClaA}4#01hcpfUXgHt>o>p(c_cPjQ_uar z{N?f&UO3Wr`Q*~1hFoQ8+nNLI%+_N9HK#&?e(A4^fq0N$)^RJl+pD%39q^z+g4-?Y zK_Zh?ais0`M#!TE6cXJ3Sq~D-s@`%Bd&yfD2kJqE1drpa2MK14+xTCz;gG%o4=N3?mjwGJi$vl~^7MI!N_LV~@SMI!Ma!7QFJibUc;g~YCZ8D_tD z?3(Oxm3WX~*33OFv-N+xIzUh%kzM<2%PzGm&l%LcQp%@mK2%4#S_Na7iEZaYcB-8B zr>ca|tT;n(jiDMf=s`mL;z;9a=h5N4^%Yw@(n~yYR5Xqwu2zvDGWB4V#^Uj(pO;j; z`OiU#2NjLuh-+wMh#Hzzoyk%{JWknhYQ^{tBN7iP8pjdW)5s7tG^;w3rG$9wec^!> zTQ zSn}{ksRtE}-JG(S)jUAd(5&iAmJ;G|+QMy@K7QX7Nj<1&97kM%BSX~Ctm;gb65?@d z*Nc~)`QoU=gNnv+lwCIiL=DZV&SWVe9(DG+cj>>6x;XKmqH!E?b&L#AL$j(gSxSh< zfgiuWbnXEcCLUBYj-%|ngCJ^XR&^#z3Gq0!`JeK2?>;l}prWyBgOi>xmkn85IKzRc zp;@jCB1_}M6!ipFu2 zopq=j!7Po%W7Ty%@-v72Tp=D*G>#+Aa#WsRmd4^S<=_GNclUZR@t~q{9C7ZY@&vOq z7LV^wAC|xRv6~YQDjLTT*JdeCFiT_cIQH|=`TM(_ka$qhIF7htOnHJ?8jDB%7;<3h#&X1ebeW`d*(KwE>^XZo(n5D6JjPG+ve(i$W5)UdG#}Vi6 zFHbN_WAS)!L%;kBpTCxPP|-M!va{otBbcSJcx<)Rx%o@K{BPnxMPqjz%*@$ej$oF? z;_>E_-SRKovQu962NjLuh-(CtCzz$Ncx3}?)fnbk4rqLXdFkEe*B1epqGr4C9$~n zl2%m0gghHORJUP%s=J0bVm=9t-FgalEjD{~>s;^%KTT9e`UJsPJg$AdMdfkRJ5|a) z*Q_{0=n8;Rk8%XFG!~DZ9S^M>@Y2DF2NjL0BV8$2JjxNw(pWqmTXsz4Elrvw9#k~0 zj&yBd@hC?yOJni)Vejshr!A_Tcu>)}I?^?Z#iJa-ERDtEq+|P3p1$bw3fUi2G&F78jHuxe;!%+;lS~U2NjL0BVD;$ zJjxNw(pWr>T6lS7;}=>c9#k~0j&ucb@hC?yOJngk;Kr*emsJl)uIE%Vu8wr|bnz%h zFiT_cxPI|fmB&7Ncyg_!qH%Sk>#d7NIf7Xli^unEuc++Pv(ZvHuBd2S9qGFa@hC?y zOJngk?z@qd3m0CQcu>)}I@0$j;!%!Zmd4_-w9$~t-|ktEcu>)}I@0&o;!%!Zmd4_7 z_k-tGj%)mJ;z32@>PX*mi$^(vSsIJSDes|1i$JvAaQu)f10}~G_8dpbO{BW+l zvVQl1M>&F78jHuG1NW>Pd_$CYP|>(L(tbSIALR&UX)GSkAF_SrS>sMlJg8_~9c}5> zCLh1Y@r8PnBbcSJcr-cx+lr$PKQHm1qH%T9Z`@J#qFVB0nAD>j!7Po%W4jlhsn~YP zz{G=!#?{d+x3{-{sXnscQI24i#^UkfuG1>koH;!4prWz6o}Yby{dM&b1&?wBvoscu ze=j?tV*T}(B_32Xu8wrfjBKlN1hX_wJf_`qMCaYEN<64&Tpj6{nZ%On>0>PW}Th(|esSsIJS-nn0veAV#Eq#jf>u8wq+jd+wJn5D6JOx)@Gr9Y0j zH1VLKado7lcf_L{!7Po%*J#&J~d;Z}D4XnMhe1eGu$9`j!xn%}$4 z+{A-~#&Hyn+|#aYB46-GJxEXq6XNmVAy?$rE!#QqAfa&_eevd=_M6XSt{3qjK_yIx z$G9)9%GW*a{f=^!kkB}e+CH#foG7WvK<;z2^=IO=rto_6+S z@)eYLkf0JK#N+nngY$>RPbMBDG>)SmdbYCl&yaao#DfHtFd-gi9du@X!Y6;KlzNcR zIF1f)($c=sRYo3)2MH=+LOi7XxmG0}IT9MXHxrjNx4-w9TJRu2B}|Biv_IFX5)Tp@ zyWWgxP3=Q-<(pBd2MH=+LOi7XxmJ~UkkB}e<__B3zEaP7kf0JK#6#MjYgLH{360~Z z!S1`-5ATsLS*0E%sDugekoM)W7 z>p_A_m=F(Xf38)f+X}y>bR3QQsG(i(jQ1cxB}|Biv_IFX5)Tp@$5Ee|4eS|*`h8A< zN|+E2X@9O&B_1R+c5j`>)whfO?LA0P2@~QW?a#F;@u)#UW7nIppq_pEAHEHepb{p; zL)xEfRfz`)jpOK!Hg#>kzx#6u2`XViJf!`(R+XF+NoX8LtG1|Pw|vN-6G>1B6XGH5 z&$X(=gM`L$^xuxP?FsMtb2|wtVM08l{kc|^c#zOIj&z+CX@exFgbDGG_UBsFV%g^; zG6lRKkRKNc)q!OYtC~aU3;jvAw;zD!mWR5>cu4z`yG!vPp>Z4? zf6NZH&u89)1eGu$9@75g?ovERXdFlH&)CtPa_r4|9V`-5!i0E8`;)s%@gSjb96evN zkv(yQ_aH$fOo)fHKe@XU4-y)?Z8fy9{eF=5AVDQeh=;U4xw{k(5*o)*-<7-CTwCu! zf=ZYWkIy#Tw6y*0!x9e?8pqL`rn}j8t-J>bDq%uAKH6g0(v7_%Dax`%yt zu|KXzPze*_A#GglU}am8&^X4kp`5Qs=rf=j$x$o`3GsN$wekB4&zx7*de;2&yEBtx zRO2{$>#k?bWA~^3pCzb-3Go={+IYXhGbag+-F@PIE6n?6cn=a(!i0D%a&0_cc;+Ob zaUAV);|lZWMp@HcwiO8~VM07+xi)@&;hB?!#&J~hofW3(P2Ph9l`tV5pSU*OweZYI zLgP4^{KE=!U>om2f=ZYWkMXXJcQ__}<|LtU9KHI@3e#fQ>4j}Yf=ZYWj~T9wpI&(8 zB%yH}{qpPzbMWcjg9Mc@As+X*XU^Z(r_Y=uG>)UQN3Jl_zw2J82MH=+LOjlK?Qd-1 znUjRZZiG;+6{hn{??Hk}m=KS5UHcnfc;+Obu^XLm>9eN!ao&Rjl`tV5_qq0WSmBwI zgvN0+>-FVk%+}t61eGu$9y`|lZt3j8Gbag+c+_?6?;nL{ zP7)fs=fUHjF_RZ~4-!cyxB{@2bKxCkc(?=<=$(>DkyHyCkTD3Gr~(!Af@>tdwgl z360}uuZNbJ-aWks2`XViJls{S(p?7=4-y)?_lf&1H5CiJ2MH=+LOk46t#& z8pqM=%a@owJNWZ12`XViJls{S(p?7=4-y)?5!ksU=I4>#g9Mc@As+6kR_U&Ti3bUd z<7mivOU&nMyax#?VM09IRjtxp2a{(`5*o)*>kF5dA3FPMEeR@NLOk46tE5NKgqA;^D4pmF_y2c#zOI zj(SYUo11E#Rk%ixpb{p;!(G)X+;uSVAfa&_-DjUNbK83l5>c(|)tg}V+W9wan& z?~v;)GuNK&JxEXq6XM~nY8CD}n0S!TIF24(v&@`4(0h=e5+=mMUDX!5>tNzRLgP64 z*P^G*@P6Kd1eGu$9`35P)LjP?4-y)?uWKefW9ppZJxEXq6XM~nYD?X9F!3OvaU89$ zT5cA%@g5|ogbDF*SGBym4kjKXG>#*E3X^9X5>c%0+f->-$|!IAw|nzavJkhBAh z<0!Z29rOLJ>HlX5Dq%uA>bv&$QQ>)zgvN2S^DFO~XwdnEHb{a>m=KSduKl%j_oH$> zC!w)>Uoz+4W{#*kSwK8UPze*_vCy@@0}9WBBs7krgMNP7+G0T>YYn@AMudsDugeaM!^~cO9&h^A!n=-F5Kb7tE^mGNXqaS0t!} z3Gq1JwZDrC&x0g1c3(T~{=B*2OYcE~N|+E2cU7x&*TLkxOG0BeX5zT#-1}XBP9#Ak zOo+$ruKgWdcpfC7vD@cQt}xxNmN^GxTalm=Cd9*C)hgX}FsTO#jomnz(JM@?b7d|9 z@gPAZOo)f{D7x!l@;pdF<2Y(QVTEaMgv@au9wexQ3GtBjcU|Fmkc7r@bmpoR=7C23 zzJvsoFd-gyy7t$w&<9CE<2c%L>~p65=iY+^l`tV5C%g7Ht?)cZLSxteG4OeF!5#h{ zjs%r3As+9$_IGvRd60z0anyhM3#NZ(e=kacN|+Fj*IoN-TzDQNp|N`xzTri4$UEMH z1eGu$9#6aXG1A*0=MoYc$I&jMUpChoKa!jTl`tV5?y6Sdu7imO360%x)%;a+_(bnP zf=ZYW4|i3oaM!`agM`L$q-(ND`yfFjOo&IHj_)tNrtmySLgP5nHDJYq1eGu$9`35P z)U~Rl9wao5qiwprX|5RIw-pI0VM07cxb`=#@H|LDWA|*Z{w;HJEAK&qN|+E2cU8-~ z>tIq35*o*mK84A)B0(ighzI)zn?66u?Adabn+e~sDugea96dw zyACGLY9us{qj@u?n8#LKS=d%2sDugeSnt~3aZjbsgCsO|?<^NhG0zY89wexQ3GtBj z_e_WMd60z0?%nHxDdwNGy$1;@VM08{y7ssBsq}e}gvN1n>x3!h#W`0LwiO8~VM06} zckS=dLjNEMjpOLI!={*hE4&8@Dq%uA4s`ABrNZ+d360&j*XJgik3YV=P!AGR!i0F# zpIezfy6`+mLgP5vaQI}iXqxvRK_yIxN0oaX%oUyoNoX8L9i~k(jjOx|2`XViJf3sU zgF_0>gCsPLqw2ROntHo?4-!N&x*kG%&8Dq%uA-g56_ZYw+w zlF&GgzP@(6nZKpqA0()R3GtXv{ba>Ch37#M8pqKC&y6$R?dv^APze*_!QMU+8pqM@ z4aS)tdwCBMRKkRKu(ywd#&PuAkg?{MyS)bqDq%uA+*Pg8T?Z@WK9PjR?zwi|81vR| z-h%{{Fd-i9s#fW)gUNFg3610E;_+k5FK794A_*#CLOl3%M?&K`nrX(E>z8>C5> zc(|)trMnI$^&p|K8&lL`jJdM4zebUu5+=mMUDYbxbuf7zB%yH}z5M4f=C3z-4-!)U$Cygd`9}-l; zgm}2CTBW-VCikKwG|7$j)so9#!NWFdyt?KCd9*C)t0*JU{Vhf8pl!9@e|GKUA+ehDq%uA z+*NIA<2XA1$REuwA1^B0Uy+~^Cd6ZZ*Zv+W^beBI*o_@L^(QlDiuWKvB}|Bi zj0xXZcpfC7aU9*d@6YDCeY^(=Dq%uA=DGH_f8lwMgvM?(?&Ck3rTNDS+lmC0Fd-f* zUHf~a&_75*<2ZWk=bz05CwdPORKkRKNN?ZB!Z(T}Gwh+D*2rp5h4-RGf=ZYW z4|yLmqcC2SgvM^%YjMRX@gPAZOo)fPk8y8Vl6wXc8pn~Ya3vljsDugenCzYh4=+3q zlF&Gg&aL&6S#-awMJFC4sDugenC05vONHk_5*o+RWvhNLhn(p>NKgqA;vxO>uGhWN z-HPT&XzaetD6Xj|^&mkdOo+z;?s-sp8^nWz#&M);_=yJzDq%uAE_dzkro!_e360%x zb<%%Km&LN0pm>m=5+=ms4EH|f>%#LO360}u-cu4z`-UiuLBs6wo zCf<+DhYxrU5>c(icOgLf642T5q`X8zi9y=ncd_aH$fOo+$LuKi6dJP(r4*v&{f zVV&6{_8ugtgbDGu*tNgDh5kVj8pqM#+FzLwd;9i5f=ZYW4|i3obk{-IA2mp5?5=~0 zzc3dK^&TXsgbDH3(zU;@3;ly6GF+euIf6XM~nYL)Ifn4EV>XdFi?j#_K({hRk7K_yIxhrExu+}&Nu{ve@o95vi> zt=V!be;p)2B}|BijMu)UYx+D$LgP64Q~kAO;w9dL1eGu$9@5+Au7k<*APJ4#vs&M^ z=AG5vg9Mc@As+6kRw=y=vaLvH97nb5er|3(*5CV(pb{p;Fxc4AIB}|Biv_HAKlzNcR*d15*tT(&O z^d2OrgbDFz;ra(ZD?AU9&^V56?_F&s-R(U{Pze*_;jU`M=Rp!0yZzC8gPD4#_aH$f zOo&G_*Z%xBiX=34??qSs$5dSJJxEXq6XMaxwZA(G&x0g1cHdNw_|BYgq4yv`B}|Bi zyQ<~gbuiiIBs7jAeF~F%9}-l;gm}pN80l@0gBh8TeW+eAf8oSwapB-i5iRu4m z2`XViJmh_hd&`n|kkB}ezIyFaQ?rNnAVDQeh=;t7k=_QW2MLYiXxCduo4Bp_AVDQe zh=;t7k=_RJAfd5)r{D52)AF~Q3iqNUsDugekoPgt+aMk!GARZ(%cGsv~Mw(L|^&TXsgbDGG{(0$b5DyX> z$5HRu!_8~Acn=a(!i0E8|Ge}zhzALc7RGK?uiEpjpJzb*g@v$x!!{Wl`tV5(myY~4N?yh8oT#CI}bF=mwFEp zRKkRKNdLU_PdJYnBs7kr9ai=?oj&#+B&dW5@sR#`*Xy2mkkHumtG(3E98}kzuSie{ z6XM~nYL(L4AoU=jv74Xa_r9i62k$|GN|+E2>7SS02Js-FaU4B9vai{Gu=gNAB}|Bi zJl#oegLsh8*o_PSOJ7rKp7$U@B}|BiypNII2Js-Fv3qtts;{~3UGG7HN|+E2>7SS0 z2Js-Fv3qu&+1G4c&)=7jpb{p;L;B~Xw?RBeXzcDq59?=ER(KB*RKkRK$oIR_KOr6@ zG>)U~8}&D%2YL?@RKkRK$oIQ4`b<1XXza!T96Z2WH{E-Xpb{p;L;B}s^qF{&&^V5+ z88gtVdenQ6pb{p;L;C04bujTDp>Z5F+c?Oa|C;w8K_yIxhm6;j(PvT*5*o+Rup2Hi zXRY=gB&dW5@sR#`8GR-mBs7krHiutqj`+fRkf0JK#6$Y$W%QYNkkB}e`h7Okyt>wV zkf0JK#KT?HmdfZe@gSkG8&5rHm}&fh_aH$fOo)f{&%0jt#Dj#!ZVtLeBh1j}y$1;@ zVM08le_lqPNj*qt>{hkHGhCLS5+=lhy?q0^^|!ah>D*=-yRm~m^tX4+_j8_+pb{p; zgS~wuGc(AvRgvRcj%s~Tf zzpK3m2`XViJlNYuLgP4UeDXlsprQ95K_yIxhdkX$Z-X3HBs6yCt1biW)OmisJ`z;I zgm|#GkA%i?G`875TXCrOAVDQehzEQ7NN5~Ke}8p=9rdc8+mHm6Fd-i7?IWSF`%d_b z0k+pg-h%{{Fd-i7?IWSFTT$oP{&w}Q-h%{{Fd-i7?IWRa939uFza72O&u2-3N|+E2 z_V$s`*v<8FazER3j`tuzB}|A1d;3Ue?2fCe`r4na@E#uodyt?KCd7lieIzt?W7YD#?1c5+g9Mc@As+1QBcX8|%^B6p zp4Q!;+euIf6XGFHcfNm+gvM_CZuegHfoHu32`XViJlNYuLgP4k>YQHo;6wbimIReB zAs+1QBcX8|oin+Y9W&Q^kf0JK#Dl$kBs6yO?|#tB9$VYrUy+~^Cd7lieIzuFqi?Hv z+jIJP4-!B%!hUR{zF6w$m1V{#_DO!i0FR zw~vIzakRMm`F7}G-h%{{Fd-i7?IWSFJFZ$^V4pkFdyt?KCd7lieIzt?>jG?Zp=~$7 zdyt?KCd7lieIzt?q&;dyt?KCd7lieIzuFqlL@*+AmM^9wexQ3GrZW9|?`) z=*S!T*&p`y9wexQ3GrZW9|?_JA3dJovILbdAs#ZHlgw5q&jzg?zs=n9#{Eg(md0^3 z`t;k)J`bk9yax#?VM07)J|~&2P&`Oz97lIuGuxco(tD7g5+=k$=5vzS3dMtj#&LAOU9-)F z@qL9pND@@Sgm}2CT3%)=6b}*_yLU@-W}8)ydk+#+!i0Fp>@YH0p?Hwc*xfUXm~Hxw z^ByFqgbDGG`J807Lh&G>v0I^g@7d<&le`BBDq%uA*xN@!W7n^?=yvm6EAK&qN|+E2 z_V$s`*nOk8&+X=;U+*pKa}rd-gm}pOzA{^(+f+Fc8oTq=nA^;C?|TmtRKkRK$o#%C zTcLQ6&^V61d-m^U+o!z;2`XViJY;@fnXOPfNNDVyqkg&7G+f|4NKgqA;vw_<%4~(= zK|*8q4q&fa&4G7&4-!On$d z_g(6hv&^ZFdJhs*!i0FZc?~OMwnFhBp|Kn9vuLLI?RoD(f=ZYW51HRrW-AmA5*o)* zi<&dde?RpeB&dW5@sRm_Wwt`+QGkkHu8IWT;N$(`ptNKgqA;vw_<%4~(=K|*6Uj_kl0 z=7j0qg9Mc@As#Znugq2`9wan&Dq%uA*xN@!WA~lcbvK(ApYR?esDugekokRO_IlY? zBs6v_LLWBM^%Z#!5>c*y*|em)rz8pqK|-_A6*fA2j=Pze*_A@lpn?DbL)5*o+R z6-#HCzis_M;hup6l`tV5GQY3PUN0UbG>)S)rrlyjZRb5mPze*_A@lpX>tNzRLSuKn z>U*o%wx0JOK_yIxhs^IQv)4;KNN5~Kr?&sQIb{p)L4rz{5D#}%TPm~Hiw6mfU4K-~ z+su8j-{&N#gbDGG`F&;fdhsBkv3uW+XSgguB}|A1$BR~-@TD0ucX4w3XzZSG)_rMe zUX}iTmY@h4&yq zB}|A1pYBL#?A8T1;VbjZQFl%n`9wexQ3Gv|QPZAot^}PQ2xmlO<9wexQ z3Gv|QPZAotvFA^$HQQe5JxEXq6XLo*wuvFWshKVOlc5+=lhqd!S#?A8U?=3{gE zf!>1zl`tV59Q{c`WB2U5e2r<*$9s^V5+=k$di(r%Q4$)vKCe60n8q``2MH=+LOk46 ztvFtkgvM^I#(UP7Ij?#T5>cyRP5360$|=i9CxTl)JF5>cyRP5360&H9IZY! zU$pZcB&dW5@!-=P360(SCDT7PQ+s(25>c<||tgvM?@{T82?xs$yI2`XViJUIH3 zgvN1n@Qa_A4flEv5>cyRP5360%%EE7I8BcJsiB&dW5@!;rB5*o+R-6wu#2CeiS zB&dW5@!;rB5*o+Rggw`qZXbCM5>cyRP5360(PYU5h7`UCGlf=ZYW503sMp>Z6I zdF6A{`VH?vf=ZYW503sMp|KllF#QWNZmIVmK_yIx2gi$&(Ad2%!82Tzpb{p;L&j^% z-K9Kp9{yBIyP@S%$$hQHZq4HDTiGEs(*MsARKkRK$arnJyA%%+8oPN|PHtt#uFMzi zsYy@?6XNlZdmfa#OYtC~vHPxQf~&_}-h%{{Fd-f?UR&-i#e;;#Zd~78t?V7cyax#? zVM07)ytdq3iU$de-M2D}TGc*uBd zxx18lkkHtTJwLLQ?J&Z7kf0JK#DlYilF-=ofBf9i?$yYw zs)_d?K_yIx2WJZc*ys= za(C&rRSgmv$5DJ@GrMrC_aH$fOo)fOsukxKC84o9x9{QV@v!$GK_yIxhkU;)cb8HR z5*oYl48JzD(?0VaB&dW5@sRI#Q6#8@3GtBccjfLcG3PfPo4rS~8~B}|Bie7`Hb4dOvUW4D$Np5d|tl`tV5d>(wDZk4_I zfd8H@3X7y?>7DaEI}nqh==sg%jh$y2MLYcyQSN!><*2+2MH=+LOi5@UPhmZ z2MLYiXxtmF9$!9IxQ8P_B}|Bi^v}!aGw~pyvHQm4yDHmmk@p}$B}|Bi^v}!aGw~py zaU8YV>O_0Q81F%XN|+E2>7SR;XW~IZV>e$$%@gfooxKMMDq%uAq<>yUpNR(vjop~L zbyc=v7w7SR;XW~IZWB2{w@+y1L+D8lfoCK9HAs*5{FQd=IgM`Lz9rvkK z_NB+Y2MH=+LOf)=wv0Y=7C90cyKfpgRoO?c_Z}pugbDGG@!B%_OgueNpQQm_D zl`tV5GG1FopNR(vjosXa%e&fIM|cksRKkRK$arlTeI_0xGesPG;nsDuge zkn!3w`b<1XXdFj7ebdFZKF)iPpb{p;!;Mobu18No<2V{IwTpf8Z0|vWN|+E2KHZVf zIF9x^u#0_bl=mP(B}|A1pYBL#?8ct2>1g*L4rz{5DyuzEu+uGgM`L$H1N32w)x)v z+)jc@m=F&cuPvj`#Dj#!Zrsx0o$W5?cn=a(!i0FZt6FhAdJ-DP(fE#??d)mZg9Mc@ zAs#YbTSlKrJxFNm*5Em@vu*U8_aH$fOo)e!*Ot*|;z2^=II6g`v;F)h??Hk}m=F&c zuPx)%#Dj#!aby;Bwo~@<_i!YrgbDGG@!InJl6a8N*sW>tQ)fG;tM?#5B}|BiyQ&q} zqbH%Uo3p=j7yHdc-h%{{Fd-f?UR%CKl6sKP*wy2nE_TEu??Hk}m=F&cuPt9Ai3bUd z51xD9Ap6*|`N_Sr#%@idUkBNCx26A|C8&f6 z@nCNs35{JpPUT>G%rNgkf=ZYW5BHX{*gr@@WA_|2bg*sL$$OBX5+=lhy?rD!cJr`I zA8h;W;5|rC2@~SM-aZl<$I++r2HT+@&MQ3Qkf0JK#Dl$kBs6wo=;sW!>+bR%B&dW5 z@nCNs360(QgHs0EOD^#qB&dW5@nCNs360&{34I3JdB%H?pb{p;gS~wuG9xF zZ|FTpPze*_!QMU+8oR!`&j#7A*3B*Ka}rd-gm_Fv{~!sC-96k5gY2vqy$1;@VM09E z+eboUw~qV4gY1qAyax#?VM09E+ebpCAeAs79_;NSp|Sh!?xz9v-kIKm1eGu$9_;NSp|M+6=DGp4=X~!$f=ZYW5BBzv z(Af2#w;5o!dE9%Dpb{p;gHLxPGbQDTc@Gj)!i0FRw~vIzZanpu z{p@LDy$1;@VM09E+eboU_s;U){cM-Vy$1;@VM09E+eboUchB%aKl|2t??Hk}m=F*4 z_L0!ojWyWN&vtI%?-@u?2@~SM-aZlw{d^-|qR6_aH$fOo#`2`$%XU zN8cak&h4Li4-!c<}qdjt>sAgWCNyx#!ea=BFNJzurFm|13cz zOo)f{&%0KYJfD-$*gb#P;r734rxxyaNl*zB;xWWM56a!8yaOPiv70Y^_;9;!k@p}$ zB}|Bi^v}!PrFf9g*nMws({S5-y!RkMB}|Bi^v}!PrFf9gIF6pVbGY5N%6pKY5+=k$ z`sd~DQang#?7rumH{8x`;yp-E2@~QW{qu5nDIO#=c5CWgJKVNjJEgGCNl*zB;vxO> za(5{nBs7kr))x-9XD##|B&dW5@!;2hBs6yKGTIKeizavv5>c<^gL5*oXE>Mw@b zIp=y05>c*uBdxw~|mDn~+Nx7P3UVfLgWyax#?VM09kH6RI%-S^Ii4zn+}^d2Or zgbDGG@!E2CDfJ+su^VUkuS@L89lQq#Dq%uAWW2WAU5W<@jon;G7hGb$tL;5VPze*_ zA>*~>?ovERXdFk=HV(DD>v|6oRKkRKti^g0Bs7krdDDj4T^e~05>c*uBd_m(B8 z2MLW`KWE#aHovd;AVDQehzGw0B%!hU?(WTt?Xsi22MH=+LOl32APJ4*==!l2Tif4z zkf0JK#6!kwySFT|t!j|aIF9~vE43`l`tV5?y6Q?Z-RuzakRGH#Ws4zdyt?K zCd5O=Ys=lG)Psb^Zav|3L+o}xcn=a(!i0Fp=xe#V6b}*_$I&4l46%P|?XOWJsDuge zkn!4bcPSnuG7a_5>c<^gL5*oXCoo8Ka z|GJyM7bQU@Oo)e!*OuM}*;XVpj-&hIi|q$Tcn=a(!i0G6Yd{hjyLxmUYI}9}9wexQ z3Gr}Owc>gcBs6yGG(0@ip5E7ckf0JK#6!kwOK*d0D-s&JcQU(OVml1+9wexQ3GtBe z+S1z~9wan&{c6`-VqYHYJxEXq6XM~nYQ^;?NNDWlllkTn+o+HCAVDQeh=+{Vc5hjd zdXUiAy~{Xxn7ydVdyt?KCd5O=YfEo~Y%3BP$B{mT$@+sNsDugekp6iYeI_1fwd-v! z*lloff3C6nW^`O{+w1K?h5L3ARKkRKaJEnq8oT@5=X%?TS9=cHgvRcB&VBmW*S;7~@E}1YOo)f{&&%jD@gSkG z8)w%059w>7(Y4-!pMu>2MH=+LOf)= zwv0X#4-y)?Z^PG}XD@lddyt?KCd7lYg_6)Xjuzz3vsEv94-!*s8Ao_%7C_aH$fOo)dYr&gR_l!V4^E~JG$ZSDV~?9AhQs{TJtLYOg0CHvktOUY8c z4MyiZNog?JP-M-%Whe5U2HsJIE^!PP=Zgt2}$s!c~pRDlNxDsIAfnCG?4(`UM^ z@{kDQtkmU~bd*ac1s)`*xC!II)j~;xaaL-vO&#Re_kjlqDsIAfnCG?4(`Tk0B*Hi= zHUF#*QY<;xCz7DzCX9!9UfVoOnK9$(l&YOCPfhXfTjVLW(sM84nU+oRvDMekW-#KJXwx#Z4Fw^Sris z8_9T(2xEO;Eu)j<(a*&B$669p+=TJqYM~^;SUHV`a?R)TMq{wB&fIvD$iI^X|Zd1Qj=7Jk0aj=4~WX4-#Rl zzekU2IGdp2CX5H~4{kixNZuTk?)7aLXQiG@PLY*2`2TJbRNRE|;N3nFVVspZeRPU^ zv#(|LxFSKtO&AZ}?IRJ!`ugMb6nSG@;6Z|ln=l@{+eadd^|kZ%6e(LS@E}3OO&AZ} z?IRJ!`aaJ76sfhUMRr?}pyDQs2k-Wg2xGn0Gl=f^2h zdvEjXdXS*vCX5H~_K^r<{mk8>6qz|H@E}3OO&AYe-H`}mecs+HMQ*Pcc#xptCX5HK z?ns2O{>`#-ij?~zExWBqP;nE+gLnH#gt7k3a$6%AGd=JiLB&lN58mw~5yrY64>giO z_Xi#%sJIE^!MlAV!Z<7Ss)R=Jn0~j&KSq(D;wFp-@Ai=hW4)&AqK5KewZMY}6*pl# zc(;#480+uR*Ka5pH3JV4RNRE|;N3nFVXW_;Z*3q&B=8_X#Z4Fw-t8k1#(I69UJc~F zo`DAmDsIAf@NOT8FxJ19BsGxs8G#20DsIAf@NOT8FxJ;NnaR@eNZ>(&ikmPVyxT`2 zjP=?gqmrdT!(d-Rf{L3k9=zK}B8;YKo+hKJV;P+6UKvg`$&YbzIHy*K&BlCJV;P+6UKvg`$&YbUOT#VLrK?bX86Zi z5>(uT@!;J)5@D==XIS4*2Av8#NKkPT#)EhJNQAL|-=Ib#DYPr_AVI}V7!Tg zIe;0B(uT@i6!2&Do{#AQ8rTer!k*b!*^3f{L3k9()^+L>TKeu$L#vox5+%t_KM!Zo+t& z`}2BMdA}i(2xEP3Vp5W<91(bspyDQs2j2!H5ytwR(exzgT`uq-LB&lN555gZB8>HY z=R!%+cx#jFwjx2rO&AaJyte+8rLpev2#GMxN|n_`C1YyfL4t~#FdlpxkVF_~rIu-3 zRGw@Tc#xptCX9!9UfY~qntG53WBtCtsYH3{#=wIF6*pl#%=6mj?9zCU2;;2OxsN5v zfvW=#5>(uT@i5P8o3l&fK_ZOx`yXWzWqq~4g9H^fVLZ(9+UD%ic#sHVeZIRgL25P* zJV;P+6UM_luWimQjR%P^*5BuBnINOO1s)`*xC!IIw*g6nvHsoXbP*ZzT;M^1ikmPV zd>fEN80+8L7Z;JS2LlfhRNRE|Fwbk7vrFApc}RqDR_f7CMWo$L!M=n96*pl#^ieIk zz9@+>*8BGBipaP*fd>gHZo+u*Z9o!Xtj|RgipW)e2OcD-xC!H7p4T>Km!_>qgt1;j z=@z9B8;lqA4-!<| zgz@0pfF!~=EA``di%5xP!MP|2DsIAfnCG?iuPm8nT#*Q4{XNK}1X(>T@E}3OO&AZp z4M-x4vr<3ln;`2l0}m2Z+=THk&ug2z4W=F>!Z<6n)0YYI+P=Vp1Qj>owH4MEB@xE@ zJ3oyQW#Fm6!#v?_?oXIfQE?N-!#uBT?lxRVgmhMF`xg^sc2?j)f{L3k9_D#%bGN~G zkO*VF&P1`IQvKV&g9H^fVLZ(9+U9P9@gNb#S*bq_E-K%x2s}toaTCUa?+=m)WBtA} zuHkHgikmPVkLc$`f5?7bbn-7nWZ{6x-Z^I&XQf^}JV6HD;QzZ#P;nE+ql%t?A7;Nl zNFt2&cj68w$P+(L%0AyELB&lNkHz|WFn{**q9nptpYJwIlrkBC2MH=}!g#!-=U?IM z=S4|`v3}NIaH0%J3p_|raTCU4x1LSMv)30T5ytwy^Nd8Pb^5XFwjx2rO&AX||2o|6 zUk{Q9I72R0Uwveg3*5>(uT@i?QO7kx4Nc~KH! zoR#|KHAQ6B`3c$mL4t~#Fdo{z49wZUQdaba& zmq@o`fd>gHZo>1>^H0wzudPUgaaL+%b3wVLNHDJIgP`IjjK_m|ec%4s-=ilH#`>J0 zRzcZ$Q{X{@ikmPV3-$c_Ap3by5@D>r^Yc;x$u}hMAVI}V7!Nc5^sF*%m4`$aXQi%5 zE+7Zq2|P$paTCTvAJrP`SMttn%tXB8>HS`)1~sTi*;kNKkPT#>4y`qmP5$^P(ieSpV)b zC%=qN3XbO_sJIE^p^s{f^>NU~RNRE|F!RrxT^bJ(VXW8wY*$d)Mgk8KRNRE|&_}fteH`>WNQALI-#u4Q_P-o> zkf7owjE6p|rRd|J=RqQj_5G+tm&kuM2OcD-xC!H7=ASvcG;Kv9jP*U1y9&u2I|2_9 zRNRE|xE$Z3ClSVa&6@m$*G1D;cSA6n=l@W^!&@r zz8)O@+NJW-mCt$SYGJI`#i?6NGQWQ|`y7r06*pl#%=|NFm!_>qgt5N=v8b5*@MPdY zf{L3k9`p75tDJp3NFt2&`-8t1lb%fj4-!<|gzB*IwV|EPGGY(M%;c3Y94;wFrTnSa6cAc-*6>lE!RCR?8hJV;P+ z6UM{LKRpi{o3{$|ckf7ow zjE6oCeczm2ntG53WBrbMa*{kVIq)Ds#Z4FwGylxlrSTvU#`<^a$wg(@sKA2+6*pl# zo=OY9H$ftd^)c$}MEU-az=H%8H(@-g>G?M=`+AT>80%y0HHotF@xX%w6*pl#%=|NF zm!_>qgmG4C|FH=&WJTaXf{L3k9+UO_Yny#NNFt2&?^nl)NTt1j2MH=}!g!3<^KVb~ z^&p8b*6*cuEh6cqgE>foikmPVX8xJ8OWjs^NQ7}#>eAl|%k`ZC4-!<|gz;Fa=imA4 z?@f>hW4%t%!osq2dEh~UikmPV=JyzLc4_KCB8;|^!1=QyEGmo!dTxEzO%4=ygKk8LB&lN4}DZ?tdE1< z@ti~$>u-h)Ev$ba4$ezRP;nE+!_2?ndXPjI>)$Nb6c*Jn@E}3OO&AY-RBLR`M@?Ii z2xI-6zP`_S=c|DS2`X;Fc<7^AV|^U-JV=DGex_(@5vlld;6Z|ln=l?`{+Y8&Qx6hh ztnaauNRTC0`{%(nLB&lN4}DZi(Z@m0gG3l-rIuTjAhlWr9wex^3FD#fOQe{)4W=F> z!dR~t-ab(V_YFKqP;nE+!^}T(c4<6FgmG5txx}LK^vJ-21Qj=7Jk0Mg=IqjVkOY3e~DjP*0y zS6nJ{n*<&tsJIE^(M`|4e%aT9B*Iu9&v6ZB6I9%U@mQee-@5GU!77*6kv?ml@XiOr zSnqe|){(}e{C~FzDsIAfnE7YUE=^mJ2xEPIbxB=$;Ksm%1Qj=7Ja~0SB8>HOGVSZi z(Zi2tpYM{O;wFrT`8~$mZ7}s95ypD#K2=v_R^UN`ikmPVX8xJ8OXEQzjP-fR>viR? z(uT@i6nxoL!o>A`!-Vjrd#ZN{jk|2MH=}!g%oNjzk#i_a=_kk%q^oXSWpzDsIAf z@am347-yyaJ+O}Sdol1JLB&lN4_@7o2xI*lz~S0*Y(U^af{L3k9=y6E5ytwuwpnfI zcx&K6f{L3k9_IeMJ`Oh4T^=D3#`?X~jO(Rz^}vG!6*pl#%=|NFm&Suc7-yvpJ6TJ9 zFB5o>pyDQshq*s*?lu??5@DQ`dPzzxxxakiL4t~#Fdn?RBN4`Wz1JDnN!{9k2MH=} z!g!eZXU;B7JxGMH`S!rI@>{FGg9H^fVLYbk>%rF9*MlU&I4kvR`n9qs5_piH;wFqo zL|+f?%Dx^X5ytx6rB7ri`=fJtjHVeuSigF6UKvAcO=3% zD>bEHO}RQf@E}3OO&AaTD`#We+M2UsJIE^VdkIyUDUfCBoW4X4b!)4NV9u`V=W0PZo+u*>W)Mh>$SXh z)sVHX1s)`*xC!H7=ASvcG;Kv9jI&aEm8&W1@&xBsB&fIvLNqxAcY)=b3 zNKkPT#)DUPB*Iu zdC^kW$?{Wy2MH=}!g!eb^ZIwuOw;Ei!dPFQZ@5lQC(g`1FCjt2O&AX||IFE?@gNb# z`uE+zwdAVOfd>gHZo+uzUpb@SA0!dRS*e%*=XzOnRp3E_ikmPVyt*S1#`^g2)%CKg zK;S`wikmPVX8xJ8OVd^)!dQP7c~osFbtvd_5>(uT@#vzj2M1(d50VIDeLTlCoJ~-1 z6UHO_i!@%jX0H1CqgP~S^M1Ef$~#y6?|>h#$TMH-;`Wb9Wh9mL#n4@=VTk9tb)k4DS%s~_{?(*GSSNA$BF#@qIwLgMQM z!{zVgQyj$ZFF#ccZp!qOw$pd0TA#n;#hJ*l3(Zm@%RIbS7d*X$`zX*#L0 ze00x~UVOvS>e8muJO}Yn#JSJK&}45k8R>a+uqW-|5PvQ&yBrgZ)rcyQ@M|HUhQh#V4Y=C^I$z> z6R({zK!z>*KW|I6NAN_O$qJr4GjYpn3dq|Z_+!B)mefp;p3nN*3Z6AEMDR?2iEV=0 z4W2yvXAioQ2%ag6^&r8leJ9VWK}E(pYEFej@Jv~(2bJKdFq6eC*)^v^B6!{_)`JAI zf~U7)3ATIi%!J8eKiQ?CLLzt?BG!Whvr<i zQG#cLP0U$Ki7ZYwGzf@dyc zJxDOC*mr-cvHe{8-Qamav#sE{J`-~vW0#6q!BcwwOmJHyg6HpI>p_B9Ji^(fVr_%x zMa_2O*PIH8;7QQfQjuU*@LXps!7~6J^@FcG#1g@`mW&d76UoH!&*7+$2)=d{>p_B9 zJb$!XmkNpCYe%sjB$yR^yC{~R5`2BgWN}OJOGP61u28H8x5cdBD?zaY&+dY6*O;u} z8#A#4mEbEeURK=mM0$`2zW);IL4sMq*IZ%=D#763hy|v=Un?Za4VG$Ul2%gkXR!4Vu(?K zFE5(-%(r7C`I9FcH4nZAXtILu_L-RbO1pKbkO;oWXXy9@v$)T<36?$hy5m3BgEb@( ze77;SR3w-ce1$QV;5Bl^wnx;yC;VRxe*eG2>UhMD?Rumx*{4d*eb;OE|Gm6VWo-3h z{^np4R7h<9N^dEj|NBFHf?4r@%b-GHV3qyqNIjPa31$tSy>_HtdrS?e)XG{WC5w`3DkNc{cdK{b42PNia2xyuf!YbUsfwf*+1CKvhrvG|hxs!i?Oj6@Qj zZrGOoUO|&mewv66%yxu-LG1I z{XvDq3&)SD zyklG*B$ySy=2hgVu1V^8fVAky=ddbM0uHVSG-7gn) zmuY=-^5Aw!Z27R8Od8$RwE6 zzD76Me4mSG@Mv#IYwnk7*74qweB5sI(?+)qdpy4n^MlvU%;G&gyB_SR#7nwM zz23PQB_v85?k@FvxcZ!5!T<$iI(k6D7v}rnX(a%A1{^o%>Zizh|Wv zub=pFqpLcgSWon zmG{B5M^yiTex0^0J*+<3;>WfJx3#P42~}fbZt6i|Y%FOj+UYFRV`s1FnDr2hu6v8Xj*J{J2)<01^#1LzdgFzh zp0eQFCefnoQFX(guIDmHFe`rRQX#Q&%lCxq1}U2NIZD+@9K~Ju8~NBS)9$b$B6wa z)w0ely*~1(^2r~nB6r{K z#Wu0yg^ilH&r^zByGecD){po7{fTN==K%-7ZPDZNHS5)oo-Pk=iymj^f2LaRZSU}? zws4(Vy!c*Exnt`GD)AjZF7U!yb#==$2l4U`@2j&L{IYkLn5mvB=$C{gv};a<#H;dw zT9oXn2m6D4@Yh4Hs9%=d=_nNy5=W}PuToaIdXNOOzS!`d>UvolhX<9jk@wWOVSX03 zWY?Sui2fQ1AoQexJW5icc_$du^NG z%sKzWd+Ok7zvi52HbI5Nb9>)Y<4d~6E(vBWPJds0HrPe5KiCJ=W^Gcd|8&iBDkS3f zISFR*$Y9r;3W+**Zd329bd4(#%!+@+X>r8{HS|lrZ>u!>P)%8p(-DW`ibT_)>(!x*YDJaB|AHgI8;c)e}d^9T4i6H{ z8a48SI}26#n=4! zzKUDbO_TiCZe1!Q=6v~?+Bm3(!=vKFO{!QU|BZ_K_H0tiO89SG#DANkb(!bX#tI|7 zZEZdEvAW@Fzqau`sF1j7eLhm%mbm(Z z1hd#8cB!b4=rwzb>XqgiB_x=|cC$U$gXJ&YsGfb)pQ*J*Zc+swaLrmOBzSgid+;e} zJ{`}erfq@>2|kk^pJ3J^xl$TVaNUWcLgLFKMJ1Adv}3gY^>9Tw-_^fsv2$j5d3}+8 zcj5PY%S(s3lN|)J7WFMFpC#r*a9bpbl`Sp1Uv|}l1heATg9?c%E3cBhqg);&n8h}< z`-5%865dp*vTSeRy1PV$#O1C2BUAr$-8Ue?tTP>}NK#uD!FR^^F4^1N^r|YA=Qw(h z3W>xws>pSzvvVMrl{KuY94a--K~OpJWmP$O(0?Y8-gfI!AyMnYsqrOU}T zYh4~xNc`NZvQ$WV*5N^dSsCTaNWCggJBVPVI@43ZigG5t^Vk2W&)#!+1ZyUmtYB?J z6PKuTsXUtQss|Mk!K#IZw)>n)uZO(QZXx7A260+`vfcFnXLG2MTJDL z=3T4@31$T=*u@f5f;H&=eW^$UtINfDuvE+n){2WITF%hlt~t2G8*#x3W+p3GX)Klq z*26Ul$8N9|Z!AHDM6g0|EJ62RJu;KU(%K`D3W;E)u~-ih%nH^GizR~9@Qf0yTKDfu zMIu;_F4lvkVixckYHA@(s3-oeLMG$!CJhr1Qim^nqDSd54w&9 zB$ySfDIDuTg~a!BE|P&yiQFAIJSSPzweAAO}&hpJro1j91Z@9)Mn6KxBKcl-T@~>+0RBqBt9!dtR7h||kN5<$CU^fo)%l43%cMb^lDdU;X^D>z4^CBntQHqRuaiI7T}O zW<9#4xtj9RI0r$6#Mw)RsLNl>iD1^z4Y#N+*SLN!>A!Kf%9`XKy^d`gq4IX{;{`3I zs?AI0I!e{8$8fcHr@zPf>#AYu?$v&L?qnNvzLD!Hb?zrURhrx@He*7>s;8m9g31+cp?NYG^*=vKwk5KRY&(&7! z!5-&(s3r|!d(-w{uaS6bSPyk+KiAQK1hba@w}&eDyo;bx?v@^E#y7bs6^TuAd#D15 zuGVF#n00aeo@!@`i>UBtU-jTNUm5&Fe|7&}Kjv7l+lmT_nm0Y98Xa+YkYEb#x4nFweCDnof+#QsFZqhfO>FzZc0Vsfy?@-e9k>XB-$BPSIS2S%l-%{`uT9BU^$ z{FG`^Vuh#NTX>ARvg~VKoc7p6RdV$!4uT4ajx~F!>ju1-1Hr7+)VAu(_~#wOq){)a z%5~rNl*@O`Rp%$K_F|USZYwGzWcyV0_alD&;uFkboos?{Ve-vDzO`u+R7mWszE|y> z;Cefg1hcq~pY2h<_f7KO73;nBd8u42sdLQ+FCH?RooA67lOnf?1oJx0LEnxjd+lV7u9+y0~o%8JgnP@QRborN-@k-0_JPa`HLXdlOVh z44u|ozHH}eD-z6NtJ|fbLgL!m&1J`Mmj?-EaV*##?7?r_rOSDV?M<6tuaOwOAYCpi z>FN&>%(|`M1JdR@7eR%@`0cucN8fbJbB@tIx2H+PYy2#>h+PjVBwn~FO|EM1@*u&i z2@TU^;Y=6N+-t$%JtB8jJFwUoX0 zxJC&}(&XjlGIVlIrDAzWe3#Th`pk3nAPHu1KW5jQ<;{CtOF5Rkjx6VmO;90Gd_xN< z*vM6L63pWKw>{XmKetMg5}R`~u1KVeNRz{7U898Kidkw!noPag)w-Mq15T$)y*2)J zIdANGP$5z8;#SgVtgBQcnAJLOD|s``MerOxpw%67hSG1hcruuszuBCyu8}%2m1Pa}v*PNSFSH zT&>GKXV$!F>GH{2F5=3Bfs)?dzXsTp(nlKZUheht`99rbz(+4R`kV@hfzuw86@^{r zB_x=2pjB%*)6w^{+lmSa)-OK6EbcLEf(nWFZAF4v+~?aKY+bg((gQ=K@|>lP)}=z? z#D9lN=Jl@YC=$$S{_aS5X-bgoL!K`8p$H)Zd z6I)bBaNRh&bxAObYoXZ$6%z5+pd-O7u1#lqaK$yQN5?JM1Qilon=U@Vti|oeNU?#g z^%^ZRe%$qV2bo%Muwz_(*QTQ+s$QP5{F07x=_EgH zdaAY5P3`F*N`?OsT63m)EqJzxb?IKwA zVw*b1vF~%L2R%sSpVdK%CHwV@Un*v?MQq}OL)B$!osRYxgY$W;%{qEqEN%95XQ zno*oQIs)vG6+`@q#!B$&k!V|%ddr1#b6DnID8ablk@p+e&5s{`eD(*ZdU%qm-^ zt9p{8Gb8X(yy@`y{xTA z+`ltfeoJ$;E)^1OW+cnUf4MwZ-jSn{r9s2yxo9gA{ccZ|PV;=)t_RzSS!4f`EWe+3 z5meqQkt_#$w#Y@PNIX+2Sx)cp>G-8$7W>8~*dOgCHIRktWBbM?*asv|ooFD_4!C-d z1he+EZYb&cSDn}+&dKByS$Tu6aIS1T)=1tQBzD(mB!zalJV-DreyP}2(?_SsH~aiK!B((KMTNw?*Hh$;ajqFff>{%{ zr%2gyE`rJ(`%|RWDu29kOYuuZqVJv*sc^e%v~yd`%J*@K)ZXiwgI{iIBx9!gd$QLa zY9xd1_hasZ?NU)8aaBSic})L;9y@kPFss_4hVo%G7eS>|{f3fJGdHCoQDbWZDIzWp zmWo+CGT1ezLSkC426A6dmj?-E@mOMeu%}ioN|BkP{9a?v+5{C6D|)5K?G;^pPJ&r% z5!-_biPtKpNVzXuH7CI=jyK!m|At;FV{UBVjh`R87MGW9Px0daeU)D}PiW{ES5!!x zc{;BY8F7b$;MxLQ6@hR4+ohsH;hK`JEWX2Udr%>!9RR?i+kYHB) zno}Y1;-_a+zTg4yRH}dL$8Y2*pjRhtPBT==OZ*%9&o-S(hD z;(wi!!A0e}6*<*|H6&5*^P=+g2%ok+ zNHB|avI#0AI#keYRmbH)f?4s~itY1P%LEzKEvL3(E0S1wx`>Q<&UIBpf?4s$6%`Vb z78jAR2VEW{n8h(|w=Rhyd5Xvt+nahLamW=#nCiDlnbt++$u>FlAm{d}gd%d)-#N{5wiStM|1K;A zy1VK@f>~^7yXG4j7Ln(l^V@y%;39JToF8-E*aWjaez%B}XqKB6WurtHc*^C$QZbABW4o<5ekxB&l9eO;KIaIv2`VHi zq$f%5a;}j`f?1sZwg(jwWeX)qlW;?=87P$5xsS4;WN&HWw6a}vzjwXK$1x}>Xv zph6-~%FWVpyT2xnT`CgH`Z-@Y8MNaehlizLyTu1yC*R~5p98@xt~p|tig(<2caiO8 z6I4j>SKRmnv#fRl5@}3@#O*s<%b1H@txLknLc762pY^d1NR<8WZF1Kqu5)S<%wkL1 z9#lxw>T{!9+-0((2l+cS&-&R4wg(jwJfDwGFpI5V6I4j>3LrkgEVhD8P$9vuW5g$z z6~A?=x|3+F?>RSr%k@MG31-#X)l+tya1ku~sq|j*!J|3V zgEb^^dQLC->Ls7HYfge$+m82=s-L)sp(pxChf}d7d2DMQl0b9s%MQz{Zo5B8N~$NfWhkl>YNe1cj0-Pb0lkl;$L@d;*e zJzJZgLV|0}+Qh+KHDqn}>U3Ny?uNH(NV9t%cbu0{A<=hL4JrQj32hYg<9#}{Ez36*1I9ywf4e(>zgWF0eSW~V}_qR)L zo1j8s_0}5l*6~mw-morB(BA@-T5?rs z7eVFn|6DJtuJW_ErTC>HarUe0Wmf^02e-wnyrXJMsY9-|qEhAZI?`uNZrX~(y18|v z@hF!EOU11C*Em#2e0+&s$@4~+2MK2FZeLf99(L`0sC0j-uE;Dui(9h$g9?dduh*5o zl3gAon05G-y0USfYo2p2)2dl*>3FNZ$KhVdE)^9L`7*AT($!u2D-z5acCwcIUdBaG zxg@2Q++RL7r6N&f#&uG+w#$R1Vpi#+*UE3LTm*kZ;_n(1*dwg<;g{YiD@t||Ul;&`(ODkR>xwXU>qe%F!&vsfqFg9?c@N9#z#wKXvMc9u5x@%;Jjwwg(jwTmwHo!K{xmzE$O3 z>gp&J6%z5+)90^F{Jo6V40frgkl^nq@d;*aT6nt*ti04w4=N=1=9}$7f?2ZnX6fDO zC5HzU5`2%%_8`HmF0Us`)mL9}cu*n1w}89MSHE}mW1Ex34@jVXXS&et%6k zuF7T;^x$^m6I4iS9xzV*@sg`lB$&n0+NEOI=c=*l@pU=XgB~P`RT`@vsqu)T&q*-r z)BlWB|M!%O7`}CaDt?#0X5QV4CaT}=^JA`HXV-%YiGjl(Qxn_zbbNwY>CGmoFIu>W zAw8z3wBN^gHRM+w%6~LjT~ppgP$9w6+NC1Ftm(xjt7;8g9#lyDyLzlVF+~l0KDJJF zsaSRrpWHQ7-O}N>4-(AcSg<`ferl|lsy-Ux z*PJ8NCa91YuwtruyRd5{l3>>SiBr|b8UFs!_GmD3vMQPG_wCPLO;U+v{g^##6I4iS zC_G73{L>#}@d;*egxUnl`*;1Rs(OlFcGk}(sE|0bd5YS<-!*ngFpKrGJ*bd4b<-5J zW~R%71hd%cwg@g#^DV6`x=hzkFm9R7m`sZ;u+1=z0sA1hd%cwg(jw z%hQ&t?N^(iLL&Z( zizJv8e@)rVtvk!Ijnlk#|Db(mse8l!c`=_NuuDaS#E$XpWauNV->*n8i@y!n9#lvi zeyf@M=gK*bQ9^=Q{MFF*phDu4XB)_}W%C^#B$&l-%-9}ONHpDDM_%}8fy09Yv-ph} z+k*;;9$$hSSHkXTfqr8G>M=NP*rn8lHAdr%?qSpJ)3{R^)7L4sKv z`L+iY68W0cm$e67W0wT8tdS3sNMkA_s$5Z9hF-tK(N-j^ER1|unCJSSkXT#jdKo{< z_wksMWcEtj_CNH;M$arp!L4W({@`R7h+% zaZc^q=OVb0=l{*FAe-C1@6|S|RRvi!&X4VSP}yHj6L0ug+>%XDA#vuf@-p+F%Yy{7 z>YOMqlS^ef`s1!^D@kUD4?Lyw)0HIs0YBzysCKESkhn8%WqIZ(Z0u<>3FS+sMxf!q!;%`!?b;sT5~kYE<~kG2Q*8K=5dmR}p^W|WY)>4VC0s&Y=Fgjwt-yHr$2biGuMm^>~I z63pUwvpqN(_OGfUR~OFBNF*_AK^0m4m8(BkDrQ|Xyo&63-bGNUdUF+NFx1cDmh5^^ zAyMgEWx2YA%Yy{7I6`d?DkPdNsVqBdx;#iQi~CC3gR7@-l@qQxViQzI@Ew}?1haTw z)h4Kru->5o5@}3=S-h_bK%Xa4Az{6B1H>kn#rvuNv z1he>CmQ7G0vG3%0HK@pV$B~l+v-n$1MNvI#0A_?@r#1he>CmQ7G0 z@%xmQ)yiG2Zx)ka7JtjKJ*bf2_cY=Y%!>bIASxu{f1BgAtcPS*BmZ}?FVhA}=hl9_ zcFF)5w#<+1Qc)qnbwJ}2%;J@|O;91hXQ1N~%;J@|O;91hrxxN9%;J@|O;91hXAt5O z%;J@|O;91hXAt5O%;J@|O;91hXAt5O%;J@|O;91hXAt5O%;J@|O;91hV{m+eS-kSL z2`VIb#u=YrR)I+;)RvFmaqOw7kl^<;Y!4F5dLa3@YW)7Y4i73MzAANG-T14E;1?G8 ztxoPy?NU)8!LM+}Cz!=Os!dQKk<$GWb?2|oIciRVS=^)A9#lvis{X3#w$}9~5(#GU zOGLH@6%s4*%vXEgdBIT+ezTNcDP=3z9#ly1d!X?NX0a7)f(nUY_kXV*xyRL3B$&lk zusx`dC|`c9npy5;M_Z9#R{YkbLgLuzS5!jwm!a%Z70-7_<-6Eltv-L!AvI}`ANOju zLp^xw8;(*@Au;`}18Vgbt}h~xVAc&4HmE(>Uy`s(MTJD$={r=d&s}>T63nVU`5pD} zfVGZ#P$3cjOHIx4KCM>Ie9hYyzgKn36LZw15BmRZ*MkZPeuFDM!K@`RN2$6l4=Nq3GUNL>s&5@XCT*9B3W;Gu=BP*~m&f3Yg=)`RzLGI?q3SW- zkK>QTEq}~c#aHXCWs9_QE6 z_~kY3?c#s?j0y>s&~9B4%wntC1QimM^3GNNJK(B031)FD*dFZL1-0j>J7(u*l#sac zvN=k&xJC&}#jN;amvb>fia(>+CZpe-3MTNw+ z)P<_ry{Cvp7? z3sv{5oJJzExX-t1&Yrp_`B`=MMY$OzBxdD(PQ9At>JN?*X0d1OQc)pM<*nz`%iCQZ zB$&nVW_!H1rm(1v&wA$!SLwCX?tImcd6sDtR7mjYi}(byc$R4sR7mjYi}(byc$R4s zR7mh_Fh0R7wz^GFA;Gi3_yn^!dTfFUiO-iVQzaYw-#Cp=FpFPBwFxRDc#aw+B6;#e zGNbQceb)Du=(AWljz0UPW1EP+MW>bMyK6e;mTV&GuCt=0(s8u3I<|@Exw9eK?^dZ> z^u0|TN6)Wgi0JoAwG#bCnU14(Ibw+DcMY`?{X(LSqhB(NA)?>l(Mt4}I~_;AF%%HG zWzAnCGy3HmtwdKO)p7LeIsxIO8zQe99`KghIs!} zAsO35zd@{(i}w{0m8jpT)p7I+IfjU?da9M^N~b0(SOGPLnB4ag>2_>_x81&F3d!_u z{5bk+eGEZ`#P?eZN%fsR?KNw(tw=Dd$C$#>;>QaJuRlgFxh1AyMkJ{F3JZ5C+qf?UDIX0m(Nc*3Tq+e-T4)yCmAzDkwW|^6BjSY!4F5VyoK( z6%vun1?8F|E)NpS;^?tG#{W=UR(v?cYei|8C}lDxd2y}73G&3xejJ}*R@b@3r0tDU z!~QT>#IzL^5?2pTkbyU#&z%Ibj*d@~HQ%~CsF0ZaOA%Q(03NzTo=qkRW~Hu3l&@Z# z=BNi165Z}ABFz`LJV-E$Bi}EN{%^#z6%`WgRuz_{58&Zd;zEL1F*7Pka6Z3zO%a)O zJ~#Uk5(_sLk+Riu8i~y6+$upbI$c1R%4fc}IY9<2_LUM<6Xns9e#{YSs^I-a3_*p& zGu;wpVybJNlVDcbltei@?*c*_MKY-rpOGlFPWxHhl3yf~eqpIdd^$K$hNR^*qnO3{ zXnREOZR-8t+&TGWbdtYa?qi~aDVVjtBC&mDe!2C{3u^AwgWFCNxOp5Hj>k5XV$pS3&@V!Ttv0|3P^zhzOwbN{BrtjzpdDY zcB!b4X!dS?`MH~`2T3rCE$w;eTARN}=9lvxlK(5?A1yz>>meC-+TY_u@0i9MΥ ztn@?jGB}Ktm1nH$h3|wg31lM21x!I*;)UpR3!d5 zK0u0|aUBgXhZPn;LMDAbZZfw2?h9oWVxZh3)MN%sCC#v^*CQrEEbJBL)E5&BN0j(`8Z!|Hg% zkF)c$J*ZS{dqnMf!q4KCY=R1jzE>Po-Cw!DL!)-7m=%5cBBnp6kf{9LQT67h7kGFz zC&8?0cN|lno(7?_&0i$*kxDDzR?$`aQ^*88qQ<;eAL6(YH9Mg8qsgP(n`$x5N zmCJ(!v-UJQpmsd%BB+$R?4Y`Kf}h1L#V-|!zkfWahL3c4a9hmcULxwDgGeT4POW#3 zsR5Pz{@_gWh=|YWqe1XwmL72=wieP)Q{CLQEA0_|=1RxW zXR%^N`%A43s=hn@nKNeM0X1x6Zss|Ox*z|jPQBuqgWNMPi~AV6tUwzxAnp7 zBWnEne!R5pX;n1+LwnYGHD_)A-g!*rx!Nb<*PIH8g9DDK;`g}fL4sK?96ze^jsX$z zYNJO9%RctA!>Y#if2fD1BAKiqiN${&QhRs7!&t-+%$ivBkZSpZi{P)$ycVf)S5Ik? z;r|9`Ht+pKOsS%8%j)ryx~sF?R(QJC2kobHma&UmN9X99@S2FeQ?KLr_dk|Y>mq}u z`e&&F^tY)?)$`*RLYK(=>DCS2&%a>1@k=#sOblFB1RmdXQPXHuSe{42;K+`@2e|V}8vSmV8jQEcaupv;pD~ zR7li3`k?Hb=o%&L=ZxW<<=)o*xq3_w8XwPt3W?^Kon_()*A)v1W^weG&3k_lQ*)Mg z%ZJ@$(tzC5oWz%ly34e_u9~y0n8ooHl*s%)lDW3^gEG*p5UEGpoLOC^$wht~eTqG1 zBvxqNN2WdRw`fWIP4!~M{dvbL8P6m8KaoskHLlY~dOrFOM8qpq@C3hhCo$`IZ%IDx zn&)(9R)a@-OImY(FA*)3=fT=W-__TC+{f4i6%x^P0@zlb2MK0z-(`F7?%RpBy`^*i z?9unHe)l2q?AG2geCq{cSDQsLIk%a`HndAcg~YfDeI(^Z*Of2{W^wdHJ-kw}rv{wq zB}*3jy~Zs?iO7YcghcO_z2vzpSD$lR%!(Q9di&;2-{Hl!ZhoStoVn&7=10U3+!l#d z>w3u1RzB@*+%ve4U{;C4-KBmH5PJI_lu0G=lJ5Gek+~@qiS{+R$>#gu;Tc?5DrRwy z;g?7MH)4q1za3U@yr7@#)$^cm!eKT4Hb3TBtxZrN(YVJU_4Qu;gmKJ_iatrKmFP3c zI*vZo5ko|uDbdQ5JAYBl*RJ%o``Ni))$@D&*ejK;gZYbO(u3QLUn-Vl(=CV8D^KdR z4F0iH+%Ac7+YhPlYWTEY9#bS!DiX}vw)C+2Xp3I)B&Oz69$b4w^&jYGaZB+%Nc1aw zObxxp<-u(+i>+>ZP$98#;&D|j3;kiRh^aXVX6>qaLe<#lBB)&XeU{q2%+KPM;+Kj< z^|>e2-d9{6+!nJq#%z!13N*T>qN~p6IJ%BT(1W_x<}Z>-g~S5|&#E=Ax%z_yvocSf zRi7nbTtz$!?eW(|KdDVa-txxJ%8|#^yqo=)SABkNK;(PtoO(agpPjE%Kc{9?^XGZ= z?V+F^28ft?P$BWhJ!e(MRG;>@9uRbAskq0m2`VI7ls&3$_|xS;MLkTxGNbF4 z=o&`XEYUIR7bPMW)||wf=gz5atz3IJZi`uL^{9teDz@T-H~+5w*q@vJAaVaMzo}nq z`u!jEh^Ys&*iRmzv&~;5lUWxJJ+1EO{tx3SVhC=F#7{eaQ7MnRN=1TMD=VH-)0TqJ z+c$raOezby{H!Lwl$%nKX#DaCRc0t1W`&B3KxwyS5h z`f>CNX&7AI*ta_7Oqo^7vJkCO^2>mn=<@3 z`YrSrkA3fMQmr5DvO2-sdP4J#M;vvwHKjjxm0=2TMZYc-fEC6GuBZJV-DrQg@5mlk6f`50-u3-=C<4 zbslhdP$9A7g^jvS&YELe%$oe@$0}>7%YzDuM+$CKZ=Z%o#BZ@kCJAQ6uQ?SGC(<{l zwKZLRPJ&r%b+0_pQgQsev2UHatB=23js?F4`oEgePm5qAlGvHJPEBv;DisN4y(%B5 zMadwdrMmj{_f?mUt-Zb-v45pn*14q@AF2MnN?GOqyIm?OBx2@Z)Pn@GzS!`d>UxR2+iPEkS!kxZ7IL_)z2RQrAYULs0FE+m*0e_uj{#2s5d zP>JujJV-E$`!Tyz+^bb-_Mw`xBBwnZJxH{;VuKp`Wlp7H*1Rt^sIdiHqlEiG?&rCe zu&U0ohPJds0HrPcxxA#3YzND|5f8srLaJ64{&K0i$Q4cC4YIJ{3ok>H@ zodmOZ432u}Ad>mV#!aej8-G4;J-JC$TIa`X=_nELT6g4^D&cDXXh~wqnN6y8O;@S7 zEoQ~^pfU11I7VBJ*r+Pr?vGc_0+a0hMNFxvkhr(tCY3hVHQGrqi>1wW$SxHX677a< zQnOFHJV-E$t!{f%oVZC9Yt+S?2en3SQUxFA?8W6T-l(2^)Q@d~3JD%p;uFl`c(VyA zB;t>D63pT(@H`^EQzVl$XPxfbvq>#0p}(#YbJjTY2Cb%koIe!|Eql>nN&zj>hqE6wnX0v2ufwJ7=l^xOBG!;TW>46uD6b( ztAYm}di&-tl1b&hid)r9le&8);gA+hz;$LfZ! z{g#eTFpDi6C3FzUEMMz8HTo-mMn%8JquVFCI#keB*;pi#SYBf+x$f`sgyslLp@!^?=^18&o$|WphDu37GJ8- zLtTANf?3fO=40v+{qB-h_H_MDeOS`pt9>!xJN4Pw3-)kcJ)++L)kO5WpE{0y^C`yT z$bcQ{)+_uglRD?VQVYiTarBF&F$5J7bMF0G^(yST@?xo2k`a%5qx!D^p5#qqk6k1|65e*On=JWi)tv6Nrgm-N|(x`>2qu%VhDOf*J05f z@!vk9LL#~bOi*)E4bOuFv-swlN%sCCrc}{&&-J$6t#z5K|7E^c_S(M}lb%hVb<|_v z)FM*xXJ3iFU#n@hLbii%lgVwBT~thdc+#io9VKE)MdFIO#U%54SE;xyW<}r5jcF?? zB!<6ssr+>1bB>ymVAefXTq<*$QPvlU+nTA!K|4J3(L~w z&)EH;&GfI%6)%(RM}4J1lgs25*n_}M~_`9DkQppP*my-ca0Jf%;FfcOT`gaZdHQRYL%N(k*HT9L6%&dQ>mE6 zJ%(MXv|~l2(%yMq-*V5ntZNZTFMUCuM@*knA;HmOdyrt((%%Zp^_}3Mw{QORGhR?g zI7ec{5UfZ4u?aF{MQokCje7=$VA)9wza~*uKJL@;31+qXI#IrV#6?i~cydu0HYzuz zBGEcINuHT}frl=hT@Pk8YkHYMmOT<*T@X?xEQF{PqH zVn*ar>G`?Kg9Nia%3DHO4TXo^zWLMV?NCUxN+>2-1u?F?^a}}Qy*jp-tZn8ZxQELq zUq%*Z!y{Wl#8H3qQ}nC5~+oHL`y}2S@BCng+#M~CFQriE)NpSVjG$Qd4Cbp zR;)Sq!K_nuzD_p;6%x^}$HbfgkYLuN(&glvwXU%n{o0M**30=SNxNqLxglx0R8&ah zyS{>qEa~zf!7OK~v{@vRt5Gz$wW=(9*ne&%`u(4nno}WB>%*$D{5Abeq<z#c za`K?RjzYBNUa6>L4XY}LO3m`NOYbNVG4-HABJqtXa$V}|97@G3_LJ>Fg+$XymF1&* z{40R?1hd$iHc@5eRkC-K{~ThmvZZDB%YMuiL_8wmbCFCcBo_58E1xA^@T{7qY=T)k zXO@@O7r6*3e?44L&Uf{nPouYA9{t}K4-z+(sw~@ET=2A^fvkEkizC$bphDtI$10N4 z*7d9!31)E|+a7$Eoo}ym6^1C`)q@I&_-~VwU{-V`@R%7zg~TGcQW{QhJ;lm9;QY;j zzx&$tphAMbKSYU$=|K|A;_ufsL50L^mv2+UzPr^iYtKBLSBi|d!&6@T^o+`PJjILG zJ+@!1>L50u%_5n*Yc!HVyV5-+x(>Z=(a|#+$=j>^e~*^RBdCzrc&w4UIqCu;VmzWN z@ayg7zdl)hY~b+S@4f@C=Lx6%r*glcnPkzl2_Kq6F)~vX`pgP%>(Qi1?h{ zA6e@g%AixRePesD4@m53-B8j`yZVC!vre68Akz-G2-fhHqz2MH!!J8qBw8vR*lk5( zTCWCjUr*HBV37+6X0hE&viBD;1QilBwlCtyjid4A0MU0>A!R?Z`V}FX&TIJL631&^)o+4$-`Fn{d;gyQY zyw_9Yjd6Y!y`x0L)Po9%>7!HRn|&8}#1PCnnVcdkZ@~P}+2${j$(hq`QUh7IJ~y+L z#EsP($m|*L@C=LxXDzet-=T|G#G zS!4f`EWe+>U|dB^J*f1%Jy|-<^Ru|6_@yE-a#XT3Xz23bwwT5JnC-#2#yRot<~a$D zx2T5>?EMw9dXB$E`WI|sA8|Z_3JI>t7WIf2kFLi%$kc*^y=@K6=p=b&_w(XO^*c#} z@qX+PI@|n3GO7IXMMr7b+0WvZ{9KcMp$Cai2X&OxTJSJf48g2Z^ZRzH)qF2dS<6xaq0ZQa81ygP=lU{)i4Tb9bK{2xisk+CiQl>>{Y#-Km4jF63v? z+f>^7iu^Z(AQ6?<9k^`0aDP zOE*c~^nk;I3W;U+be8(xx>}b?>bsq#@}If!AknjA7pZk!FS}G;Jy>DxuN4)C`dpP)jbsebSB+y@tw%IiTA%xd;i7g1#{=ns!L`szSA-gJOh!?I<% z%4hHSqonp9U8Hkm*Jvkkf4wf!txRs_Ac^ANc9x!ZV-D&PnZHOTmBB+g%UciU#)HI! zgw9gw33zx0#)JC|W^qsC6({>YkxaJYyy9JD?-;*D+3HauVmzpj$XBhaY&(Mf(AnnC zCYZ%m_j66UA*hhpSEH-^px;1@{S}7Oq28&EFjk%cWkT~(*;gWg%^C4lXp{YnF31%%lFjOkfS?VCDkT~C`n+*8q zrI3i0iUhN+Oc*HX?OzFrXsJ3r(Lzo>r@wHb+vK)_4@jHu)_C!OR;}es$K^I*s**{C z#K36}%8J6Sx3)+yizPG#^8O;mg9?dFDSf2jZda*DFe|3!di&-tlDWBgOR4^pU)ygE zw2(au{dnaycS+IOYwemx4AG`{nza7Sf6J`vb7^wRCO>|(({1wdQCH2GbwF zoz`5wZ0FZDem$s=xZ-4Usd2ljtw=EI;d>2m()o8HJ^8`|}t zLSp!Wbh)ggtF1^di)(y)9??>9ylxrMLRu`!Y3#B;NPL&nLi)^em5Kzjn!MaxhE8@7 z6B?$;!kK>iyr6$Yy{f$*bA;M$MTJD4+tZ}tH9j4mU>4`5O|Wl^Z)hO}8|7wPk;r>p zOF3q~)D#>)j8VkQL5?eCJvFPP?7im#!a$kNZb+B@hkWJ4@pMVK%C9ZQo7ueg7cm4C z60P&Lk~h;XXe*6HGO5(NxRo>-n;Q=j1N3jZ_10YA5mPE=apVVeF#nHaa{QD}Yc41I z=Vt7ZXmU19GFrGsBF8SX)QU8jdbNw7k}@Jq4xjaF%Mt3;!>fd;2Ne=Ow@Q-|n_X>1 zf?1q5wg<=0d#74TxBj^qyCmi`Nte}+yGA0%F0(k^>{3x7F>hMBeDc->9+3;jF0(ib zJP)01{vw&|54Ib7*3UKRhM+>Ca@{emF2^nTxhDNW4-#BAEtOyOnb9xNXhpV9RewLS!Yj$;yXLC%lP{R(9?}2*DLe0YsjBO5k6kGu zVy`rf1w{olg5K-db_KzTT?AA>KtvGiBTb5tSfZjvDVEq9iiyg#VlS}}6Gg?YC`w|l z?^^?8sv1t(E^?4cq_8l|s8F8JF{r_bEVdY*T>g?ay>FU*6@o?E{=TXw`>QA);|s| zj(;(FR(ubbI)C(_;_Z7QV(!%b#fr@ zm37P6A+h?rfyEy0{wW|D)*4hiKBv-oXUyQ@(HWK6@9)0U_+W>`F{__ktT!cckYH-P z`-T?BkBta+di5Drd^7sDJS!3{nhY;qpA^%qC)ISHmXg59B-29D?TuRfz#)Uh&F_()DH^{hyI z`r_%uGRH<^kdMVw<9`!5o;U1tQZePy%HwkU*FGzDNUXN@z~YQS(X%4K6vs`igB=pf z?>L~CR~I=*FvY)0wGMuMep+W_aqzvr<+DrTg#M$7>*g)-Nwjy6pIxR-9eaB5w_iX= zTK|2`ffHc_{+c!iSwTBUQGI|@<^3OSAjbC zi`*W=2Nhp0ICUvsEy2en@nef4i!W|I`@hdh9$){J8%Qt}J}V>m3+Xp!UR6x_xboY1 z{*u`q+yv@ihs4Aa|4{V#xN`NI#tEkQiqsP9khtN!a&hk!(cAw|Q^i4tD$wyZ>hg3BRLncIZC75!48Q- zo19y$rFS!5%Hj8el#bu=R%*Y)?otF_E5FaEr2LMhOA*{!zrVMn_zbICQQdNONcf$* zmvWF`%I}LzLS*FzZlT|eSWXO}blCerf+@cTY$hbF|KvB-`3}9(@jLfQ z%~!pW)wmMuknlSNXNO`-5lnI1XgL3qyYS^Z0?T9hom-{m_T_ZN!43((2kcVMiUd>K zzFG%6B>c{_OF2j|#m{lA!|#|bkLCAtmfG)3yp)3-5`K4R5+W-%@YCS;6P6TTk=kd) z4hg@PF&$-fkYI}MY^{SM$L};QkIRu(ORz)2?`*!*vm(Ki-${Kb!tX~f9lxiu)O^)z zpA|bK{O-_8IcT5q#^uG}?QXTdoP4&m4t7ZRz2cX0kYI|>w${N83BNb}QVtSK@inY< z@HO%KZU3KNT@rq;@BijT>+{z90xCSn-vdXJg)@}zoB$oQ7NU^ex4-!oA z4ji=(c1ZA>DI?_Z^Qxl8LHm>}4d+_T2$T1u` zBzPqhC(8P)NH8^`|D>YZx90}O3_K$H?80%yb<3S)sb_nSFS;x`Ga&f5Th5+bJT>AR zOU=A|a&h0=mD-+_JR|)l?+3QL=e`q)zwf{Ft5C^mTnTP1iD9G8FUB9f#A~$_!PLPs z#ur~75fR+Nk9Rn~IBH>KYx#=QJ}Y)eJlWKuJKiOqO1fvB<}fqQZa01^q!MoYN=0&Jih)bH}F*)^}@KK)j_}I9VF3x zxpBpYDSAKno-?(~USo^PH;agA2aYbz`nB?jd+v9mi$7desd;`?*#g}N-41q0v}`-N zIA=?Ib`>*%ovFp>;*XD1&gl3^8n%DsB^@MA88^E4;YgehDzX&8)Wn6Oi&uYM;!|P- zJ5LTBQ~YpKCG~%MRwOoTIkxz=PvqcZF~!fcZi4+Q>z1=a;`S%U7GG@3Z?RV%?sV$K@l{66}yzywjv&_Qgv)D?w|wgDH-iS_eBMzIk#|@$S1zILhiE z!PL(?PA;~nTjEn<&x)O^$4@SvnO;fpks5ziB!=EKx%g|7=+n-}Vv2v~%^};M|H=&< zo%>xorr2wx-}0A%#2zij6n*DJf3NtLfhm4ME6+!tl0GYTNYqasU98_Xa*$w(e`Cxc zkFWpA4ZI!^uT#XU_*AkQSArc9-%h%@xaZBvJXPZaQ*|dkTO9bGYl6KqJ0$q+XRU(- zQy*?|YjMJZ*98uCNbtMNS_cWHcvM?UutOr8S1aqQOM)pLo!2_pAqhbY=aoq+Srw>*9TI$>8Yh?7!4%JTYYBEpgy-k>tVl4$@5{^~ zY5ga^GQ}0M_}=g;K9#J-m0*ViU&F=;rg%4oT7n%Cd<`2XnBqBAEx`^6zJ`qxO!1tm zmSBejzujq^V2UdWY6*5ogewQi`VNv{YQkAJ7416xHTbkIvum5Q`+9S%bL7))(yR|E z>w@opzjfMUhsuAieOBy{;OdlGf{tl3+oY>kT-sMl@Nr2@Y1TG<^y5Rpc93A|nvreO zs2?JNoeLJUO-C&ITb>n(HhZ;8JzGVu6`vJTdtKiy&FioPAuoYkopN^jbbEb+ZQ+kM zwolg&uhd-iRQp=7L!!m__G##i6}oX^r-$36#qAz8AJ;I|66}yz+^=2wPkn`MoM7s} zW!j~y4gyiGaI*hEr_U8_Q_o|5%d;YJ&{l0z!?AFvLOkULZU&EnH~-o?_1+2&6D;|xn0oP+)~RK)h*<5*jnis9EAQ=gpKqKdu2-oW zAA{_W_~xgL)5RYw@kuP}vm(LNyBoDmPu?97>?}HoH?;&iBsST#ed>Bz^sGoQwb`il>Ft?I5F#r# zaC9zrQ2R7y-ftP_B>Jr;5kWa%WFmA-C6C^rcM6W zUmvFUm(QM6x$@k~4IBs0^=qAedav@h9L<%i{I5{8&+`r)e`KG;4^HTU~0jazZR!99UHvo z?2zCqUF#sh6t4vph1;+d5@rDJyZU)#YHKMPs0^rwWxBU86a^=Cy6J{D8_ zusIxSp2`96;tn=y;a)e$%y#i%`MY|)oXli z|JNX7bQCi+~FVCu+cJEWH$SmIMs)=xV--}T%o%_vt=e5A&o6^Zpf*(!Z~ zK;+o7@^*%Yq#e{Do_+g9KCQon6yO$KeVaik0M z{#mK-F0Cl{TR-5xLTC60zgFp{ed_G7uDYjL>QG;~?%bpe znx{uMuhg}~lf#>)h2QUO#N#_RO*5~l)V$WL6H>?w?`190tK~}Smp(1h4{ufKYoA*? zz1(&8+U+PS!48RITgxMDhwYHG{*x=W;PpBBFU`}Xi~c{aRaptXJ|ueV(mV}Y42KDp zB$ztxm1gO-1t8?{4QgQL*}=`yBMrahS&_KDMYDA81#p;P$!EpXGY>RPYwsHopB&dT z9ko;CdchN}Ynn!XPz6;m7ZS~dOYFc9U6socPKild94 z(AsCk4hg>MjT21qI?}ZSJ0!wuN0;?eLV~HruTRatA0yUmnwIbS|M^>D4n7kSO-oJF znlJAa{4F8D)K)(?Nh_Wh5qzi8y{o3_lYh&ngv5rcv`F>Kv`7ceU&2vV2Oo>6`H#0q#hy#N zy7sKt`P-8%QqQ|8DLzu;&x*u1vsX7Zwq_`cm7?2vf0 z`@!jV|CtoLRwS5Ow6Je#wZ*vq67r1nU%7!D5<}&Rr0aE_{9nT2OA<_tII>@A`zfAP zSrH|Up42Cep795JEIM8tdsI5@oF%?nDl5Sb37)sxgPUMUf~k-0-#7hkt?0L}?2zC& zb*+O0Q_udnYr6gRtAp2y9TL1-Nv(qfQ+v(dF5URqwSj{j61?9`t%C$p{cr1#j@xlY z;9!RY@5fW?AW@T=v1J;1W#lNKLxO9jY8@n)I&N;O^ySd#e2^UyTr*YcAi>nBKP;1` zuY7m#TCqdo`S1Tz%zXQv|3NUd_UNyR7uUd51k07@CU@1nq+i-&*~<4K94mkPtaq9` zGFmUn4hepyYqy*PQ!`rkNISP!;$Bmb3@23xO_mLGU~upR7>;3%kdkYK7~pB2-+%iJ3{*dfvI<#)yN&Hfj`)TB$l zFD@A#5xkn}z8!|7Ut3kK*xJ3{kTkQX)V3Yv%GQ({PWyaNI(Bho4ej}32c4DXn~enb&`NNbLA#UyuR z!()BD&q?W)_kYWFka%(7z_iJ;(X--~GxgQw1Ji3af$(R=&f=Z})5GWemS;s`(K-Xu z1_#5T8!n#OYsxaU)OTb~utVaS#RF2ewvmGbQ=Q)&kY4>9pDTB;(@U;~-~IkdijSmW z`&ZWOV28x|pA1Ncj)@#3m|Cgnz%;pMMDVk8&v)`EncB$bN}rZJD}LfgJla>T*n36v zcb5cHcRoKTZ8R++*x9qw;IzhFzvWqx7a0$m!1XKJ=R1sAESH6M7-=(W34@swF|}F!khItEB?x;~>`eS= zaO!-`Z+TWEj=6Pky6=%C980~rOz|&Y?Uu7cV$A~vr`hu(2MMOQC#rRDJh!SFm`1g! zylWi)wFEmP?k>w;hHsTrtUPAMQ)UyRh*- zMzzn19TL2oPvZnrjenQH4hh~3uGT?ZE8soXH&?qTV${*`Yg9-K5Z zjl8{5^Bw`U&x#!qJX>mmnw$wPm6zA@133f>E z{Hk$+DXz1wCD9Vk>p97*? zG1cDH>Yq;?nr_;(r#&w3(^C7a*df6?r!`J6#XV6i!48R~?hU9|SwHP0m}>lfsh1!6 zk78hxV{L0sKj-!0o{T~7`iB$(pot=7Q~3Em&e ziL$hwGI+YeX-m|>C{(G z3ATeB68s$3I!G`z_Qzj}#oPA}9PE(bc&v4hV5;4|Zx)@`=^HrMA#p>~e-)e7M^~pL z!PMLR{#87-Zl79*JiT(m--rIIc>cReXXB3lD$ahb@=W+hz8yxeLxR7$aH6aZ5=`+G zal#zzkl@^;6Xqbn6yI4V%)t%`&P_UD4iYsfe5Rc+2S2+cI5+8pIY=-Rs*df8$ zOef4if+_yRaKaqykXZls!_&w2onQO8G6xB!rfzg*YVqxP0l^N5+IycZ*S$&o(Sv){ z>+|z_K6D?lyWg#XwOxsAt?k#WpSeO$BRnM?uZ7?}hDs$mJSBwtSPNY$b^X`pb<5t< zM;&EPNylp;c(;lgqGmgo^4c6LeE(40D}Nnq4tBg22k)U#DuF0@N*;?Tug!7r8W+@! z>w20w*zsB%yq`v?1ft|Ac`T;9HpgZsZd$` zqFoL?;#_mEXteG-2D`Du;aBjcz29a2}H?L@>ooHZH{f0N}iI( zV#;fC9MWcmhGsV%VGee@76-3$SSo=ic}gCODX%MzkJoEx_0oRkV8?55)LvoZkpB`T zPsw93<+VA!Z_=@0nHRd4gB`EM!7F-{N+3#}lE-4oYjaFIuxME0@4qt#J6?-}S8pzr zK$JWskHwVN=D6?=2Q=K)td%-S?07AX+N%yVMlj{IIo_UfY{S%H-`A;w9k0c~s~nX| zjS)9dzf@|BV9INAyz)SghNrJuvq9ev zcDxn`?-5WcHAXPywK;yQuWxv`!xrXX$7^x$UI(R8V+2!Pn`6C)IyC(F#m?qn$7^x$ zZVd9-ZG>RTYjYfb-G&XLXYFGScDxqH>F?fC+}=l4%GMAMHhHK$J0T%-sdQ(vRt*=( zK17J?NO&!&6>og7*tAEtsv|s`5WAm2ur|kqPqnSz=h8ju^*#5Lbi5YA?-^*@(HOy$ z*XHQG^A7bVJ=@6~?07AY>vsw^M`Hw2UYp~-NA{|}YQ5IxV8?5DT)(%lIT|CF^4c8V zY}Tv((AiDQ!H(DRxPH%Kb2LUU<+V8u+`C`>VY5G~)AxfNujO(5PSNIQj9|)ZbL{-n zkowgp&o&1;Ud!Y99k0#N7{Qd+=D6Z_BkSi68fOl6yq3rHJ9nF-F@h7{@xgQJ_kLn0 z+t;$=wLGrhZ`~Y?5lne)j;}kOUEi@C#g5nVxc*&+IT|CF^4c8xd^NIu)~s{P z!H(DRxc)tgIT|CF^4c78)*f2_^UZgegB`EsasB&ib2LUU<+V9(y5sozvFpBT4tBhj z$MtWy&CwXal-K4s`1Ql;H*2|agT5c^crB0n?T>@fDm$E5{oCFc!IanLD9_rb{zTbN zse>J_#qn$36Vh&TkEuEuBbf5q97hfQef{&3w>1YlUW?=7Z;nalwCGiJG)6GxwK-;Q zyGi|!i*_>yJ6?;!=kcU2l^P?M^4c6vZNFOmkz)@s2RmNN<1Q!nCLg!azSZq$j9|)Z zbF6p#f9m$!={R$+9)bS=3vKbd0byJQ*ksxFy*y5{&?@S2mAh~;$X*Xd0byJ zV~)lMro1-CX5}9q`n1(KwjJzvEsyJ~Y|POZ!IanLn6T#YbG{vYx;fbKS{~O|@0g=8 zf+?@f@sGOe=X}&{m^s+-S{~PbKWdJ~2&TL?$DZ5Gn{(v2{^nrEYk6G%U8*@6Bbf5q z9NmU4+wk0;N11~iujO%TkJ}p~nDW{j`P@MNwzK24IC!2=Dvg=5dBeY^*W0sNZkyKW zjCJL=R+92s9{1+u+NPuSmHR>3mXly7B8V5H-hk#H z!A?k+SS#2?=xP_>)nkjxq_aCH2#pZPKs(E~q+4uoDvI(D5gu${ZxTmejn9H%@oXkl&2j zc938vB+Q}XPezqFNO&!&8G|=W&o|Ew66}P8IduHVs4@o$uO-!T!}Zhro8_0RwjCtc z2?=xP_>)m(4ia8V%72$^4ifByggJEl$*3|139lvPznnG)33ful96J7FR8?N9v{u@A zT;(-!T2f=*YL)JKEWcJH*a-=9==hUSWeyTvORC@0mg(>v@_SB#osckxjz1Yy<{;s< zq&^wjBF+A1c938vB+Q}XPezqGN+i6N)NXe*Pp|zYk3kabgoHVC{K=>?2MMnwb$y3s zX~3WJ-x3n+goHVC{K=@YzlkKgmekwJHciXjng1q|U?(KZq2o_Rl{rXwEva92Zj$zU zJ^yVd!A?k+L&u+tDszzVT2g+W78@TV*a-=9==hUS^`O4zB)pc?oW-l8(R;}C0nI^z zosckxjz1YybJRh?Yf1fONRxDt{_58pB-jZFbLjY!QDqJiUQ6oRgPNwcSLS0M66}P8 zIduHVsA|ydAmO#7{EjHL9VFNZ33KT9)1ymuknmbkU;cj8wB3dISd;`iAz=<3e|mJO z4ia8VYVEeGrSp1Lj)O}j66}P8IduH#(WN>_crB@Y_gX#m`ye|=uoDvI(D5gu${ZxT zmed=UuaOSk`-=bW2c2LiB+Q}XPmeBjJ4kpfsi&4%I~{OZc938vB+Q}XPmeCuLBeZE z?K^DU^!4EEAi+*Zm_x^(9$l(~gx8YlKX3h1?wB1U*a-=9e6aYkIbE(DZVnP&OKSSY z8>G(dvx5XXAz_ZUmVIQ-j~fg&2MMnwHDUdY((4cA&lL%FLc$z6#`OqRUn>$`OUlpm zY@Cx|CnU^qpN#R_s^^^Ntn@_j*RPJSdudiBO9iu-P>{P$9c1Un&NjzKcU2UO2F zNq8-(mRrp&-Z(rvNU#$U=9n#GyrFu|Ny2MMZGOqz;@%(Sp6>Qqkzgkz%yFfR@#CxK zoFu%K)H45=TWow;c938vB+T)ijPd=e=bR+Gmeizg<`&y_$PNNzI~uO;=v6LX7Bhh+x|c0$4&H_JKaub)@W zIZ1desiQ{DEiV14S9Lo`uoDvII9kTvnCdwv39lt}=t^^oZd0>^1Un&Nj@M=UjjNt> zlJHtmJx+h3XtPgtkYFby%yFxXza6XRoFu%K)RljKycoS=c938vB+Ri!ldtAXtDbX` z@LE#)ulaa!+AD`v-wzV(goHVo$@u$A^_-K0*OF?#?_J0W3?^B-Mn&g<24 zP7+>AYOm8CE#^+o4ifByggI90{>IK@s^^>}yq47F(;g|VyDmFOuoDvIxN=Uny6M$( zP7+>AYQGmAE}H)>J4mn-66QEo#^2M`b50UoORCvQ4;M!-$PNw1zLtd7lG^mnIYr;z*+GJxkT8er)#_zGXbuuy zOX}k-<`i|avV#OWAz=>LtJTYX(9YFJcrB^FKmJhBZ}t3lmjpW@VGh}=)ysa+93;G! z)OY2Fitk5e2MKmU!W^33ful9I{udm;Iof50da&QommGQ1QXN*+GJxkT8er)#_zGXbuuyOX`|; z9xBGJn~$$ZuoDvIkiA;H><8^wl!Vukx~}J(;`!m(L4uu-Fo*2b>SaG@4ia8V>gKoR z6yH6b9VFNZ33JF^tzPzn<{;sdfmP+Ydsk=1<^33ful9I{udll`DMNO&!&ThqhE zj4s(hf}M~shwRnrWIt#Q5?)JcUh_wa3y;bU66}P8Ib^R^C;LHjknmbkcQ1IPIA~CI zkYFby%prTV2W3BK4ia8V>ZRF_79$2^2MKmU!W^_Qg=*ztY~_0c938v zB+MauwK=jMGzSTvvV90?1Y3lj+XKF zQ}ujs_FvsIE{`zlOnS&(ZwWRzP zj^-f2PDq&JUo!rB$nmId2MMnw<-fr+2MKmU!W{aY&suv|&Id_&Eh+y6s5wZm6B6do z@i$$LM|C?$cr7Xa#i=<+uoDvIxI)I?VbwWE5?)K{jT8S_TzPWu>U&Otosclc5iosclcRx>$BTNSNai`99{->iHlEuO;=})z25b-pLLU?1Y3lhRgZj6V>xU5?)Jc!OzbY zJ8zfYa}w-?ggNe#@waRBe2|3KlA3tlGsU7CvV#OWAz=>LtJTYXuwMUOk?>klSaG@e|JfEEvcRM zc~ZXL&3_X~uoDvIxK_sBp4Ia~5?)Jc!2@%PUgya*2kf;X!A?k+L-uO*vLCeVAmO#7 zI-W7NSm_wK7J)fPuoDvI&>2P958C-439lv9X8hcu)xeRhyw zCnU@vd$k7H588H+@LE!S7G|#%33ful9Gvaj_^FA-W*e97Z=cta8qt4J(e2xFtA7(o zuoDvIm^F0ohMx76HK`=Lmef6;Pb!AZ%nlOlgoHWnl=1h^>ii%HuO;>DL6eL9_Q(zr z?1Y3lWUtmB`$0QbBjL5AW?nwIxbN+As;?CZc0$4&pUe2$=i$ovAPKJ}wdL%|#Zx1) zg9JMvVGbRCk9Dn_50da&QbX^WT>Q03c938vB+M~J#@~kzSI!4XcrB@`$4@SvnSOTl zwIabzNSNb(8GrXy=Lbo6EvcV(oLp>CmmMV72?=v-E939k>iHlEuO;=(laq>f-#x3k z9VFNZ33IfVQQxp<^?Z6TUQ6osC&w0FZIK-$*a-=9 zaJG+x*OJ<><=EoeKG{KnoscjGXZuKaEvYAmjwyb)DLY886B6c-y;{BO2kZ4Xk%ZTh znz(Ru@#@dnL4uu-Fo*2b>SaG@=TRiQmeeWZMi)OEng1q|U?(KZ!LvIOUQ23fF}nEU zBiTWMosckx?A7XJKWN)Q!fQ#jY&*I*XUn{gBEe2bm_znz^|Bwd^Fb0`OX|7bjV}Ih zS$2?MCnU@vd$oGm585#U39ltJ?ZDB+S-)ln33ful9Iwgv+oU=_NWyDL)lVN?tlu{u z`;cHKB+MauwR+hP+Oa4JuO+od%P~dYIoUyiosckx?A7XJKWGjTUQ24fYsVCOtyDQi zEtN>H6B6dQK+XqyRL=)VcrB@A_8MDUzFBsVU?(KZA$zqt*$>)wknmbk-Ip6zY?!ix z1Un&N4%w^K$$rorB)pc?s29c+tq#f#66}P8Ib^R^C;LHjknmbk2hSK^e0@ZAkYFby z%prR9p_x-bj1Un&N4%w^C zk^P`KNO&!&3tLVsHt(7pB-jZFb8xnggx8YtvoJd!B*9KdnBz|}{+_AM4<7mNuZ#b5 zxZjSWyq47QyM9~z@b2vD@f8VnLc$zd%lNymIzLFlYf1fZ$alr`$=N}Iosckxt_lCK zdOk?PYf0U*#rMUO&9j39J0W3?nKJ&iuAUE)@LE#K-T!?tr{TWpYej;ckTAzQ8GrXw z=Lbo6Evfsy|Gqfkfb1Z_PDq$TXZuE0f1^mkYe_x+`S-ve+>L39lvPcepYK33ful9FydHaHs0|APKJ}b<9fN z6|--Xd(oML1Un&Njw@ySJzG5=B;mEB&V2iuV*4Yqg9JMvVGf<2ms$6EITS6E@LE!S zPd(cX66}P8Iku7WL7i<-2MMnw<@fM22MKmU!W?JG_`9rnK1jlANliNN-$nNa$qo|igoHVC{ON3izE&i>meg8rEGp*To*g9E z2?=wwmGi+HtLK9xyq46Pn|xku`9yY*U?(KZafOV(3##XXB)pc?6XO>a8!gHX66}P8 zIZl!B*S|VHNWyDL4QcXeaoT2ie2`!#B+MauwR+hP>ibb5;kBfWfAHhtia>$Ye}_Q?!#ia<@0`!1Un&N z4qdN()&7<9K@wg|YK0ab786d*4ifByggJD!Pxga$K1jlAN!9oNu=vM2*+GJxkT8er z)#`P&L0>BpUQ4P;vyY0a_s+*YB-jZFbNoTZU+3!iAPKJ}b<)=#6?fm59VFNZ33FT{ z<8N;De2|3KlG=a6Pm1k-%nlOlgoHU{uU4BTa~W(Ns&Lc$#SeT>dF=ys6sT2kv@eMYgUV|I{WCnU_F-^b`|gE~lf zEvaYQomsT|`LgP1=~KNO&!& z<9nT1Tz_$PkYFby%%R`M=xl>JNO&!&Im?_`Y;{a_kYFby%%R`M=xl>JNO&!&bNii9 z9Md5?NU#$U=Fs)pI@_QQ5?)K{)Ul@*fBPk0Z;1puAz=>v{jSb7h@wowYe}8Ze^hbZ zyzC&sPDq$T=jU~{K^-K#mefz{j4TemH#eXjh@y+P$Ai+*Zm_z61 zb+$nrB)pc?diM=2jvt#HB-jZFbLjlM&Nirngx8WfX7!Vc^`>M833ful96CQQv+m{~ z;kBgR88f(ebVhcNU?(KZq4V=P+o0P)!fQ!2tTm{3d`@`rGJ)Iq{)N!{@K{>4f& zvx5XXAz=>vK1OF7)Iq{)No}-y|6>$BTNSH%^zpJwi>LB5@q*hydU~$Hv>>$BTNSH%^ zzpJay)Iq{)Np0Baq+-gY*+GJxkT8eN&+F>$BTNSH(C=XLd&I!Jge zsSZ1xQta|^c938vB+Q}n^Sb&>9VEP#)PN6$6)$|49VFNZ33KTDyskb|2MMnwwaLWc z#ky~12MKmU!W=q3FSG9EAmO#7W~_Z$G3=@AAi+*Zm_z61b@iEU2MMnwypvM5?%6?toscjG zXZuKaEvZWuo|L*Q%-4q_!A?k+gR^}kyp~k`c7xJ@^Rj~kJ0W2X&i0Y;T2kvCG$^%f zl^rD52?=xP*`3Zd=;w-r*OF@8eNeh!X1-n@33ful9GvYV;kBg3v>ue|cE}DA?1Y3l zINL|UYf1h2g_F{#7xJ|YNw5s@_V20*+GJxkT3^l`$%{#scGvTpPs%WJ4mn-66WA+9|^A|HR8yA zsqLrPL4uu-Fb8M*NO&!&p|kp?^*ZMo@P4PMw?`B-jZFb8xng zgx8Yl-q0tF|2#WLuoDvI;A|fWuO&5oRG)Ncul%>21Un&N4n4ce^MfS3meiBI`lQ>R z$PNA_L1;f zQoFs`C+*!NA77DRCnU_l**+3pOX@#8`=+A@WCsa$Lc$!J?IYo}q&|4RZ+hp!>>$BT zNSK4OeI&e=)a94-OM5JvufI!zoscjGXZuKaEvW~49iN8nm>ne82?=v>wvU9@k~(_J z6Vj7MWCsa$Lc$!J?IYo}q?)gMV(NTSc938vB+S9tJ`!F_YVD6sOgr|^4ifByggH3d zN5X4K&3dGN`s9G@Ai+*Zn1i!@B)pc?t``kR-)xp0B-jZFb8xnggx8Ytv#_P+2iXY; zbLjP)^lF8AZqWYzYl@p+zRl*gyq44%hh1B2en;iM%iSG8uoDvI(CazfTAd#x;kBe@ z&%d_Vd0cjoU?(KZq1SWLs}<^YknmbkFYY$2*!sQd zieuVk2MKmU!W?=%C%sysI!JgescmkYR-Cx#*6JK233ful9I{ty(5n@ygM`g9JMvVGg~XlU}V*9VEP#)UumRE3P;& zJ4mn-66WA+9|^A|_0#NYi?7;e2MKmU!W^9KBjL5AzS;cR;;o-QrdJo+-jp3A*a-=9==FWaRp$pu zcrB?HdtOycyE!{ZuoDvI(Cho^)e3bxNO&!&#phgE9CB}VkYFby%pun`tkbI%s)K~r zlDcR1)Z*u-vV#OWAz==^zOP=bP#q+^mQ>qirWU`vpB*IF2?=xP^?mhfh2kiY@LE#O z^}eDgubjs@33ful9D03U*$(vT%J4kpfsgWZt zFUrSd2MKmU!W?>iU%gtPI!JgescW~ryx8y3>>$BTNSH&f@2giUR0j#KCAHS-mlx^j z>>$BTNSH&LB5@q+VY8^5W@VvV#OWAz=>LtJUk(3e`cvYe`+7E-#8s`IvzO zJ0W2Xy}qwrtxz2#yq47N7hPVgc6@e_U?(KZ!P!0%UQ24kf6ERM?1Y3l^!mPf^?H4+NO&!&6?dE}b4A%ff}M~shhE<|Ur&aF*OEH$ zKU0fqzs?R4?1Y3l^!mPf^?Kb75?)K{>^WB!e_HYO>M;Wec0$4&dVOELdc8VGcrB^J zFTSc6wQ6>dU?(KZq1X47{h&EWcrB@s{jV-oX`US<*a-=9==FW|>h-!EB)pc?Azl7l z9K39HkYFby%prTVIePVab&&8{QkN`qO>yg@{GO9wCnU_F*Z0+{*Q>$BTNSK4GKS_8ksn^z9SnTkh2dZO`1Un&N4*8bT z*Nc+yT2jY!SyNCW^`Uy%$|@PB-jZFb8z)139lvf!YZ;I z2WJNfc0$4&T>VMHYe{u{;L~Dg+w360PDq%8XLlsLmel6^eOf&C)!(Y`ISF<`!W=xi zBjL5A+CB71ao=;4%yZ&r4YU?(KZ!PTE6yq47W|9Q9Q^?G)YU?(KZ!PTE6yq461L*6a+ zST_H?BEe2bn1ic7Nq8-(>sEfZIBeVOAi+*Zn1ic7Nq8-(=N?~BwC$H2B-jZFbLebe zUN1_*Yf0^P{eoiMso6n-osckx?A3g|C<(76^~=o*is>(82MKmU!W>-vNy2MMz5JSN z$8!0&gakVwVGgeTB;mEBhP8jU__%X+kYFby%)zre5?)Jc)TQqh7xc*v66}P8Ie2zQ z!fQ#L)Aqe$#-!{Z!A?k+gR4JDcrB?;&%9SGz9l z^(P6hCFN&fORX1WCnU_F>$UahQqMVedbnL$-0opJuJu|{{Z?zAhL$S-z4rct?1Y3l zbiKA7U8;kG*OFT9p!R9ZyoTyAH3@b?!W?(X`Jf(Ms)K~rl4>ztw&TX^Ai+*Zm_yfV z>(Qk;NO&!&A8%}*t{# zY193)g9JMvVGjNMu6)a44ia8VYOm|trFk8)g9JMvVGjNMt{z?Lc98H|Qf>BXmwL9! z4ifByggNy0yLxn~4ia8V>VgGr(-F&N2MKmU!W{bhT|K%~2MMnwbUU8;kG*OHnxvrW2s#r#^4U?(KZ zp}*hNqf2#=@LE#K?Aj*nzFu~aU?(KZp}*hNqf2#=@LE#$zu!9Tu|sx{U?(KZ!K;Om z@LE!TxU_Y8^6=~+!A?k+Lw~=kN0+i4B@$jsYS96$)2uPsL4uu-Fo*2b{Q9CKyq46v z8_9OuogF0D2?=xP?|1d+Qn!PI*OL0?r;XFaA7lp!c0$4&`uklyx>N@VuO+qJ=NqSq z>*akE33ful9QylRJ-So}39lu!+Ls%r)p}+J33ful9QylRJ-So}39lt}#tN;|gt6H{ zf}M~shyH$7zGX2739lvfbcfdIu=}!u1Un&N4*mVE9*^pFknmbk&-H7aetIuENU#$U z=Fs2o>imQ{NO&!&7jJ2uS~knaq9oV}33KT0cja3abCB>_QaAtFI`!TvJ4mn-66Vm~ z@5+AA93;G!)JsRVNgwW+9VFNZ33KT0cXhTwUn>$`OX~Q?+N3voWd{j%Lc$#SeT>dF zsDp&pk~(OswyELR>>$BTNSH%^zpJwi>LB5@r21UZHuXFvJ4mn-66Vm~@9J!WI!Jge zsRNg3m##V}J4mn-66Vm~@9J!WI!Jgesm1-;rT^4t2MKmU!W{bhU7c-E2MMnwJyYk| z*+GJxkT8eN&+F#EvYLn=$W3qKRZaU6B6do_1e1nOcZ4jUQ6ooJ$j~l|Ck*l*a-=9=z48k zeWnf)UQ6ns#XZsqCuauqlDcuHZfTvPvx5XXAz=>LtNH!tNq8-(aXWWQ z(=N^q66}P8Idr|Yu0GT4AmO#7zBr&;TKmcDAi+*Zm_yfV>*_Ogknmbkb*FbrAAOe{ zB-jZFbLe_)U45nw5?)KHxT{;5ylFm$Bf(Bcm_yfV>#vd2LBeZE?eSf=G=2Z>$BTNSK3XcO<-)l%Itybw0>WNSK4?gU8%DINkTib$0CRwWKEgG&ps>rt;rw z&j;BF33G6^kA&Bf+N^#^+G}`rkYFby%pu=$`urdXuO-!a*pSqDkL)19PDq%8vwbAI zmQ?FYhok|kX9o#(Lc$!J?IYo}q~4!7Bn_KCvwDt0f}M~s2WR_8crB?Frw>UBZ_Ex7 z?1Y3lINL|UYe`)_c}P0-)a)R^PDq%8vwbAImQ?qCL(DN}-L4uu-Fb8M*NO&!&y*?P6K3zDY`ks?uCnU^q0pwvU9@l6ti7ptSQ9 z*+GJxkT3^l`$%{#se8UVDcv$PJ4mn-66WA+9|^A|_4t&NQt#`sg9JMvVGhprk?>kl zn{+rSt$crWkYFby%)zre5?)Jc{!0VXDz9b-33ful96Y-t;kBghE)PtTzs(L3?1Y3l zINL|UYe}`L8<h;e7sr&ueL4uu-Fb8M*NO&!&&TkG#uYR5#B-jZFb8xnggx8X~ zX7Pa3t!+MLAi+*Zn1i!@B)pc?qICwQ4Gzu@66}P8IXK%#!fQz_?l~|$d|q~tU?(KZ z!P!0%UQ6n$%Lk^{Zpsc4?1Y3lINL|UYe~JhaA4Zx+3X;}PDq%8vwbAImekk#$lvz& zvx5XXAz=>A_L1;fQj_jDDNX-6J4mn-66WA+9|^A|HEP{KY0S^rL4uu-Fb8M*NO&!& z^T!TKYy6ZQB-jZFb8xnggx8Wf?ejtD*u~jFf}M~s2WR_8crB?l4;Y+g&(97L?1Y3l zcs@wNYf1T8*iz?%?1Y3lbbelsF7@1b=R1a{!JYqL$DCeEs{gOU(`Tzy{(J532iXY; zbLjlMj4E@G@LEzUrV;6v4=<=5?~-6AB+M~X&Ik4AQn!PI*OFR&#E7(Tc6N|pCnU_F z^YeOisSXleOX`=)Mx-|5vV#OWAz==kpVy;Hb&&8{Qjgs*B5lz#J4mn-66VnPc|E#R z2MMnw^});$X~uflL4uu-Fo(|1>(Qk;NO&!&GcO#Gw)}8%^*txSPDq$T=jZk4QXM3` zmeiIfjz~w&$_^6jgoHVCeqN6*)j`5*Np03~M4CN5J4mn-66WBq0ZDi*sZBl}o~9p@ z9VFNZ33KRrZ9Te_%_x)bT2lL6Iy@b?OLmZ8CnU_lUjvfxT2k$I7@nSMmmMV72?=xP zdTl+r)a@YQwWOxJbZVNndUlXtCnU_F>$UahQXM3`melkUPEB7m$qo|igoHVCy|x}* zs)K~rlDhcEVX1Gk>>$BTNSH&{YwOXaI!JgeshJlKOY5wi9VFNZ33KRrZTXhP93;G! z)bbsNrG_oCg9JMvVGjNpkc8KgdhnG~(j$9j2MKmU!W{fHAPKJ}^~W)%q%<%)NU#$U z=Fs)p@-2(LRwWW%OX}ado|3k?G&@MJ6B6c-y_(-|f`r$S`mp&aX}8C+g9JMvVGdod ztw)!-9VEP#)DH`Xrd7Ym4ifByggJD*wjN!ogM`LB5@q*}c_G+od;J4mn-66VnL+In=U4ia8V>g=zErse;X9VFNZ33KRrZ9TeF2MMnw z_5Av$q*vx<2MKmU!W_C@TaQQ8LBeZEy>!qiY2;VgL4uu-Fb97PNWyDLy>jI#=?@#^ zV^I?9goHVCy|&Ia=ys6sT2i+yIwifiOLmZ8CnU_lUjvfxTDPOyu+*nlc938vB+Mau zHNW2k39ltJ;O=4Ru>RRWf}M~shpyMw*#>>BNO&!&UK^a6x(>|_66}P8Idr|Y&Nirn zgx8Wf;rvt6b3?L&1Un&N4qdOUvkmGX;kBd=`SR4XcE9W(!A?k+L)UA|w=Cu$;kBf` zI%s%0xo38eU?(KZq3gAEwn4Xpgx8Ytv#_OpKgdo|l!A?k+gI5bB;kBeTd9rVsa9(zhU?(KZq4V>)`b@Wjgx8YV_6OOH zcG*FKosckx&d=-WGj)*gT2dQs&@Vmz(4gvTMS`7>Fo(|1>*_Ogknmbk3%2Z+-jaJx zRPMJ;f}M~shtALI>N9na@LE#KZQd`v`0+_q2MKmU!W=q3udC10LBeZEUD>K%dgt8i zAi+*Zn1fdfCE>NC_Wi7HDmKUt66}P8Ie2zQ!fQ$GCD)<<{^5bu*NOx?Az==l-I4HG zQo9fCn_d{29VFNZ33KRrZC!mPZ%3Jg*OD5rZr{{#>+B%GPDq$T*K6zQGj)*gT2i|` z&?mL~aX|I8BEe2bm_yfV>*_Ogknmbkw;$3c?I?2xmGMD>osckxuGiMpXX+r~wWJFglEPDq%8R|_TKwWRJUAD4PQmmMV72?=xPdTm{OrrSZnYe_x2_HpTN3$lX* zJ0W2XS*PaL7bW4fq}t8uotmtYKUXB!2?=xPdTm{OrrSZnYf1gV8ksT!12?=xP zdTm{OCXNybuO)TI%DvNS6S9K@J0W2XUM-Y_*OF>E_t^C58`(jEosckxuGiMpXSy9E zyq44ommHf~cFBJeNw5Eij>L4uu-FbA&|O2TVNEu402+P28YJ|x%)33Kr5j)d2eTJ-v{>5Qwhg9JMvVGf?% zk?>kli#P6_uKz4MNU#$U=Fs)p`fDV8KS+2jspn4Zop$S3IS!UHArS0@ggJD*w*DGP z9VEP#)W84UJN4+39VFNZ33KRrZT&TpI!JgesR=tCm%5J44ifByggJD*w*DGP9VEP# z)M?X?OC?zoSJ~H+U?(KZ!K;Om@LE#in)OL-FUk%Q?1Y3lbiKCz8cDZ8(4+dfBEe2b zn1i!@B)pc?m3P*qyT@b)33ful9GvYV;kBg3zg(9#+$cLpuoDvI;A|fWuO+qLyLGAK zto^I66$y4i!W^9KBjL5A2ESdGTJMt`B-jZFb8xnggx8W&qgoHUb+egA{NxkyoF6rD0vx5XXAz=>A_L1;fx8syu(y2#g2MKmU!W^9KBjL5A z)@im&I$wTURM|(7U?(KZ!P!0%UQ25889S%PHqQVkn?(-8x*g9JMvVGhprk?>klySM0? zj-H+!B-jZFb8xnggx8WA_L1;fQg8R#IrWrlW>ogIB-jZFb8xnggx8W<^ytp%)Wz9Bf}M~s2WR_8 zcrB^`Z@re(v8`LASGTMD_uAhNvJ(>K(D`{iy43Sp5?)K{mp(1h4{z;V z{ale?CnU^qCw@Oj!fQ!2xlFdBoE;?C2?=xX*MKCvmee=1Tco=6vx5XXAz==kpVy;H zeXU4%Evdgf*&_A4Yp?2SMS`7>Fo(|1>(Qk;NO&!&`H#0q#h%$gf}M~shtALI(WN>_ zcrB@6ceF?c&fl}T9VFNZ33KTDyo@Syknmbk?IyHH_ne*`B-jZFbMV)IB)pbX>z*yr zNgHJc33ful9Q-vP39lu!;VLas{R?|kUn>&qgoHVCy|#SIQZH{unS|GpO82gsrccfe z66}P8IrwWp5?)JcgI=qqKOL4GB-jZFbLe_)J-XEGAmO#7&R^U--Lyk?kYFby%%SVG z_2^O^B)pc?)bpFC_czTB66}P8Idr|Y9$l(~gx8Xqv_bRq=;ql$f}M~shpyMwqf2#= z@LEz=-P0^}sLu`(?1Y3lbiKA7U8;kG*OL0FN3(R+3E4q{oscjGe+@{&Yf0VnRnv6t zHQ7OeoscjGe+@{&Ye`MGu4x+mL3WT}CnU_F>$UahQeLYP39lvf$#G57Q9I?oB_!Ah z33JF^&95&?!fQ#*-@0iUb9r`9`A{G1&m*a-=9=z48Ey42T- zgx8YV>gOhD#S`;BiUd0$VGdodtw)#YAmO#7nwFZTHDAsS66}P8Idr|Y9$l(~gx8W9 zv1Ze>eAj%;K!Tl+Fo&+!mTy_iLBeZEJ-&0(H1nG5Ai+*Zn1jCtB;mEBo*dpZE&M(^ zNU#$U=HRaZNq8-(XC7#p*4{TCi;`d`B+Q}fwdGru27NzBcrB^xTQp1eUXUFm*a-=9 z@YjGOyq46ngPWyC8nS}~J0W2XU9YXP4Z0m9yq45)uQW@yEyxZM?1Y3lbiKCDHmHMy z*OKb7OY<~radwbkCnU_F>$P>ZK^-K#mekRIX`U`!lpQ442?=xPdTpI;PzMRGCDpy< zs%eXVW(Ns&Lc$!nUR!4y)Iq{)Nqsha)%35svV#OWAz=<(udTBU>LB5@r2H&wsoxK> z6B6b)N7jqJRb4MS@!w6;w4oF2nA2-XZ91x18n%7qzn4lR*a-=9w3qSsSoQaVB)pbX z$B&w&i@umpJ>Dh3PDq&JIyoO)p}Jm_gx8WvJ2y`oOwSGy?1Y3lZj$lWq`F>|gx8XK zZg}%FqFZ*5U?(KZF<-{t!s_)!Nq8-(R#Td%j$fT$eXU5a6B6do@ptS#mGeOoUQ4Rm zq~__nE3<NC`W(NU#$U=Fsscqe{1c938vB+Rj+jK8VX^Fb0`OKRfamD35IW(Ns&LZaf3 z@h79oUMmt_ORD_jN@=sE`E#`+2zElk9LLM}JGr`El!VukI=bUZY2HrRL4uu-Fvm0* ze-BsJi<0nKQVln)n3fxn9VFNZ33KT9lTl@VOGtPvso7mtOz;0KJ4mn-66TP-TD|NC z?L3Nv*OHp~!3yc{Rr23m66}P8IsPo;uSa#gC<(76wcc$jq|!0jL4uu-Fo%vm8CA9& zB)pc?%NMVZ_Pj4UNU#$U=FsnBWIt%D9fng9JMvVGbRCdUUDVLBeZE?Qzsf z>F{!PkYFby%prTVI@u4JgM`iGRi>D`;Ng9JMvVGh}=)yaO)93;G!)Y&suPQQCH zJ4mn-66VnHr$?9iT9NQtQcVt8CGGcWc938vB+Rh}?nh6;Ye|h-p-KAa@7Y0uosckx z?A7MTe$cjqgx8WfYF3lf;^FKd!A?k295Vj&=u%%R5?)K{gd>`!?$^2l1Un&Nj>$6q z4y&FIlJHtmeimlugCy7q33JSl@z+p29~^btYU#7JuCZe^uO+o+r&qgoHVC{OQr9zE&i>mejKQuAa`iGCN4H6B6do zvpYSyR0j#KCDnD0)zj`pc938vB+PMzjKBS>=Yu4?meiy+tEZPgxvKhFkzgkz%%S5i zpAVAoT2d>%(=xqqS$2?MCnU_F<4;Cay}ni?yq46hqg$p2_stFx?1Y3l^!u1|tLK9x zyq44f&03~KD`f`>c0$4&I{x(NQZ}PZ!fQ!QDX*3WymV#t{UE_kNSLFAjK3Mx^Fb0` zOX~XfTBNtH&khpogoHWdICPF4UFvp_@LE#6y0l1FP0S7w?1Y3lbo}Yjr8-D>EvaWF zu9`-kl^rD52?=vt*6qLdn;_w}q>lPW^Yq3!*+GJxkTA#QGXActo)41nT2iAnYo6}; zV|I{WCnU_F<4=z+^|d15wWLlS-7Jl`D?3QA6B6c_DC6(&>iHlEuO-#()26BIJJ~^k zosclc*)sm#uAUE)@LE#0_iLJZuAj#s33ful96J8==u%#*5(%#*b;H+9(l*Cs2MKmU z!W=iq`1`ebzX=jvOX}ijP0|f_WCsa$Lc$#SeT*Jm>UNOuT2ia@Z<4w%pZ6am*a-=9 z==js4OLdU&T2ha6Z;~!KDmzH96B6baC+CBDbg2#!UQ24iflbmg_httPc0$4&vRA8@ z{h;m7Nq8-(ola{aUl8Zx5)$l$ggJElJ3C0Q6B6c-y;{8Uane32a_*a-=9==js4OWh6wZoo&$VAmO#7 z1|8iz4Ii8xB-jZFbLjZfqf2#=@LE#eH(xbfaYlBKU?(KZq2I^o(WN>_crB?DA6_+e z9+e#=*a-=9jFRzpS@nF7gx8YV@8lNgs1ve-1Un&N4jq4bbgA1x!fQz#vgT@O>K@ra zf}M~s#|bk2hE&f7Nq8+OKMS+-K@#kQggLI2@%Kpee6al*+oeIXFS6r7uO;=!)a_FJ zS(X1@Dv@9(B+Q}XPmeD3wIboQq@G#1Q#xjc>>$BTNSK3XcO<-))cm76rB6QkWA%8K z1Un&N4*fnxXB%`oNO&!&6EEwO(k0nJf}M~shmJozx>N@VuO)T+ot@H8U9y7&J0W2X z*{e0ke$dVbNq8-(k8bIdo>(xY`dX1-CnU_lvpW)AOKQgnozg**vV#OWAz=<3e|mJO zuN4WeC3W|noznh0W(Ns&Lc$z8yCdPXqz?OJyR`Gd3#+dc33ful96Y-t;kBfG9=2T? z@|Wx&!A?k+L&u*UUCK*UCgHWDx_-26`gCY^kYFby%)zre5?)K{fPJ@3z4y!x66}P8 zIdpzr_Jg(^B)pc?a?`g->u-@AB-jZFbLjZfqf33QNO&!&kzaO9-)@i{B-jZFbLjlM z&Nirngx8W>A^B)pc?k5{G?BAJqz1|gZ6xMYe94agg1$PglmB*}m8 zy`0^5IcvXiK7DTMSDgS6cQi3CAEo#Y%WF-1XP3=sI=5;5q_>ELB&dVG5GF|gkN@Cr;nDFPgjIvkf35Eycq8Kb6;J$eMQ1AJFcGj z%gB}o!mqDLP_YtT48FS~;g=oPw&7*u>*#O{5>%{&7lZHaNcd&PmH*c=vT#Z`1_>%w z!i(XqKljz8+gBv~vg0~FvaA%_8ID1Mik0wU@ZB8=zwEfa$o;six)P2-f{K;!Vz{5r zJNHGsc98JPjw|Q3$K`64X?I?ikf35Eycq8Kb6;J$eMQ1AJFcYz%1O>V;TR;SSP3tN zbC=UUe~^SDR1Qjdc#cF(X*?B*haOeFX3BT;P{C8pA`#};^tb`ZC&0jx4HN&T! z%#4rq&qr~~qnmb?iA|S@TMoP3|A%U>>EB*``S?;#nUBD*lqDP2%|e(ehNvSG{^yRUags zC+KqKCx*(nVy{@TO8x3+>Dl&mPx;}2k+SdQ*)$wB#~O1JHv@}Dga z%ZxZ(zVO>4^5v{e79v}|JaY8i37%4PO-?yJLYJdXV$sSSl#a z8j?nq-d^C{&e*%otQigg;%3j6s5~de1y8T~5!m^c58n;ZGMMW00ULN8yL$ z#TZ)*DkQ?6E=I;6LD%K~dr&G&wq38NkO+Ue7#Sn{*^R4&KVxyrTm|NMP$3ci^dvF{ zmGI{u|2_tZ@FyFQF_;xyyegUPV4s9P8FlMrADRRe65-E0BeNnwSNIdmNP)uj6s5~bsuGsPR@C$kwp0W zH?9)?o{U@OHO9<}uJE^B{x`w8NQA%75}6eVx+dZo&diFf4d35)>kV!>6%yfZRz+q- zg0ArQq#_Bv0^qZL$=7zMbvJFV0M3=#q-v~f>5bG^+cv5$54ZBl!LQ+{khl@rsBR3_ zwAoiA=;G@~lb}MPZ>Npw>85_FaBzES-iZEHD|+fz5H)9bX0H3eryV&3tMYHY6O zEwi0<(X}LIliEALM)1|$p)6a}l(ucWde@xTqMG*BWiu-(Uv2nI4UE$+)?^Y?NUR#a zRb^^si$Q{}i!s~Or)6vel~L)otBE%^g0A2d#j$<&hfV5_ZMt601v4uuBsz>sRx{JtdY1%U|E_mQyeFI0q9|Jo)~+jppnt@P?_J9vkhepO#r7JPh2btzomvOY-Awg2)CRd|bSowME+>2|2-+4qXU zdPy`Ix?L4|PSa*PNYFLst8FSVt&M2#$Tl_Tn-*RRi`3hyCal)w3SWM%etGp-OUpB- z+pOB1(5?|N$*N;6T`#YdW>!>46nlS@>fF(m6$!d{%{OB(_h$xurgkj6S3B535+xUG zQHz&o+KfShuKN2nt1KVe2);)SpY7y6_l3`3ihLdnpW5Oo;nQ5)GVeKUWlbhQg~a|lr*r-9tmq1#a1}{}&suVo@R>+% znX|{tiVBJFX-APUNYKSqV8&p+EAO1)<<`p{F$pRp4%|7ND>5q*bTL~q1{D(FGqECL zkf4jbZpH|oYv|VX$(@rB-7@F2Nl+o-o-A0a=e<@GU0j=HjPS{=ZYJRqR^9UJsYXim z9xqu|Ew2FK^J`s#R}3=-6%yf-XMELYex32Ihm2UZJ>>zn`(-=!T*xK;9 zuPzbXaw;UkC%Q(qg9KgS^I0Pawu8BcPY{hHSXcN=)_>m)62Ycr@eg4=EwK7K+uUzZz4^@TOc*~fRpsU=l9V%V>SPQ{= zi;vlsUzM0tLF68pYU;HO@a!Ep`#9~zN>9nk)Ug4i*HrWj5dNwg&POe{Ly+mSW|FT zB+exqP<0=%jXCS0i{oU*ph9BVuCLV_`|dRp>EbFdWAO7@zLM?TsHe=kWc$2!XUkYw zxqXs1<2JX8m5P=1=h>a#Z!WcO>(9B(7<9Fp5G#p`?nSUJ619%T%Ci}5S&^XYYD{No z7iS}OjO{MBzMt;3qh0B4vh(>VUO7wp?oz3jE}QLOU8hfVmgAr5dKud!sF0ZXS{JF4 z(iVdRUCh>uL50MpExSrT=X=PJuYE|+#a=LDuupQF?JiIC(Dkw=lb}Lk?Uo*LuJOIH zqU-6YadN$cjVRclw@g~BXX2QGy`{#Jy3BVnW>()U>Mj%G^|u~&ZS5vW3A&tAsJ-N@ z`?9645}cDeb63*uewLQ(EH6yd<!aktk7HHUet6jL053^QX!GcIf*t~c3TV*ba7_^F8$so{96e>&A)PyG3eJi|(WY_IaG|Z`tcx!8p&5e;i7}&l$R8tZ zF-XwG)ojM7cH*d7TxN^6o=1;6r3P>R)GNQ+__T^Yq{}9;rqC5NY1xOK>*AqbRgG75 zxyZ(IYW<#%Emwx?ubfpELR!i5@fnq2s4jmn?7W)uw5H7%tcx*9)<3WIT(!kuU5wE% z-#JzJ<_1evL#CfplVWuXM-~22Et;Uq=SqE}Ud^=GLLAI}K|T4~C!W$S>Vm4dNtc$=xSX5oJw3|BiM`kGF(tkH@lzlAW`m<^D3dRZ9F)F zbOp~u&UVhqLal#NC#KrwE)^1grTkg#7-(A`BLa=hLtbzqh*v!>t}BpOZsQ5{-q>s?+mcrD>-He*mBQE~T=>dJE4Y$rh%ui9n| zuAH|noKq=A-_NQgaXR6=%HG_T6;~}?w+@|G4-~f%91o7cUq7B!Lx$OUmkNpCF(*M6 zpBc=)qC%qgwX^Djw`}u@1YN<;IJe(Dp%(7bSD9}Po=`bc>HgvDF|(pVqF>RI>ZeM! z-X%d7pY6;TOVXcIt;*}H_G~+$3U|?E)?^Y?NYq+-LgkumyNZ&ai#=k-;99%!+ey{( z@cpb>5})=tsp_P(WyQHf7kk9as`%wE)!>iTdRL$9sm`cWsrA)|HJJnz5^1uYQAsao zI+&n~S38r~zwE5~e3#BD|JP^Kccs^P88Tawph99t?K5im>zWQG=wh2pqRXd0slNSn zR>uw;Qg1X{?Pb*`<9Rixg#LGvph6<}JM<*z+CJ`r%74lBt$QjY_?>+-tM=*sP#ae0 ze1{+VT~&HsmrMR%N+}Yz(rc4R(Di8IHMRdg_aayqiM=;|Q;Uz;+ChS@KO6n7-aY=F zB`YcyB*;22a$Y`b_v zoj763iUeJ3pE*mI`=8DKPzxvCs~v11iT6s~P*Y0Uo})<6#U3%UqCz6ohd0!wWZU(M z1YPVmGX_U+WuI%R^C~@>sRvzE^}E|%CsHB7SLbF7ehZr4j_0?gO@ayuekVPcpli*X z%+g`W>y|Z0g~W-gzpFt9=2?ipt7Vk>hxI+Z)F(2C$}-h+r5uu04war}A?Vt4C4(f^ z(XL>E3W>M-WR$6cU$ev@L051)sF1kc)Y(I5&U8x*5_GW-&GBGgF~egiGfArVZFjb* zkVv&JlZ;AhyPrscuBBx%OWd2bJ9qre7=KF^_hWXswLa0(aw;Si$)i&3CEI-;5_FCI zA-k;JY9pw0nVn5qKdJAFu_m*3sgO7~Hmhv-ukEfH3A)&CW(+DMYOT&92j8}h2MM}@ z$AiD^Fx>XpHVL}Id&@+|phDvJjzuMFYuoEY5_E<4$cc&4E|M$0wQZCb6%a~Ikk?M(p zGAx&-%@`!;dN);JX|gV?Wjv^msMkN2 zT#MJU$Be;y0K7}VclRbig#>r>2qx&-l`FlZIKIu&4k|;VZmKK0w|Xwd4vs;BpNj+& zbOqnbph6<}GZqqb@e^z_EAElP-YuB7g#3Qc)>l+WWUf<6Hl@)0X2u{v*Uzt4kR~77 z2r4Avo+>LR<|bQ4kOWCn8ro1AF4A}CMxAUVouA$4)q5msL+L%ocIS=? ziE7j9O6(t4iQu9_)`mYZxEvG_ank@!L@bIaIa%@55XqquN zY9w|xXe6a(*v5kdUENkUk}-)kg38LwG4f)!`^k#LcWq;pOb(wR)>?7T<&Wl#(wS0(Q`WAgsU-9X@f3vE|^(S zAyGMXW2v5KYdHzJIH%1R9NV(x8_2;S_cO0Zq&yKVE#}&03Fj4EUFJng?Hx9PtCRi4 z)oiwd3JLZ|FhSRvS*>JDY1=nBsE~MSen+Xiz&0L3E)0-H-!Af=ixRiLAi4Lx*_?IVY}+CHx(L07Hg-R05uZO?-rJvmCUy*J0p4Hf}5F z-fiZ!Fnx+H(jk9aubjPGYdQFh?UzVYNEAKUQ!X~K{i2ElU6nV)%j%^)Exk*H#N`tS z(zks4JqWs{PVOR~Y#MDLsE{afd7yl`aL_#ny7(JRvv;YGNPByzMAZpdVvwMV<8Q`T zyQqdt8_~e4>;0ZJq+TIi&i6!ZNjg^B664Cnsxs+RjHeuHSxsV`tF?QNq{<)FWWb2# z7J>?iOP^J9&b-&OnbnGZ)#ZgY(Oz8*Yb(j~N-eMa&Hm~#db0j^lb}K(xE& z-OP##iMB~qWx;2*7$oT8TrgvB1aoArE-yRprQBJg3(MGIaE^Xoy1HaIs{4mMVzz?{i4jw(%SUVP)w^_UKVMzekFXKr zzOEtp^6Pn3|6~m*x3;0zTFy!{tHj5m>9VNdV(6mV~ zllWsbq~LS+%8L1tNVU6$ls~SsHDi#Vi`OxeV7_Udh>{waVVOo9rD<}ITnaiOMz z3A(ucO@d>4IjV-NseC{4ip1oRHRSLKTUMNjbj^9chI}x_MsOXJ-d9yJiCz<2H)cDi zkeJl7s;I0_ zlf^N%J)NkKV6U5fMS?EQX_KHrB6tKz(8Vi;8H4?vD>+I!{d7NLPGZ=ID5+Y_wrV-% zboF`8i8seal%JhL>iibvjZ}vEg=P8Bs$O}>^4zj)R$a>oQX%om@iOv#&g%Cd=&E|Y zv=n*7Hm|6VVEfG8B|#UjF(yHUL~vh`po`ahGX{H?{g&~k%#!0}-P0yPg+xo|Z1OL5 z*m{=)U9*~{l&KYM1Qil_um7SRyJ~wrr$VAz=ReiKW46~k-vyi++`9wwwwH z?i&|O(8aybOo9rD;63O_(8ay!%oyBpjr-BDCX=8-f;-Ix6LihpzFuu@Zd*}QNN|UF zGsc>W6I8#&`aRhfO(&}Qb#%FMhZ$<;?ctVn-XPUWDxc{0OGEa(q_Q{FN$RVH+BG@bcvZ6My$IGtBLC;(Rfz(cHrqjhu7N!!sOamuO(wzIn=Trsu04N0 zS&`^Bnjp;rFdqnnpwg|a1||{IZ>@Yrdu1lqNtE4yYRK{OOR0nQp7i%&JDkS>7 zl&Jn}qi0MoK^JF?NicWDTe)+r`mL0$9aKmZtvO7!UKnp#Q6%X4dGbqYNh(_m_WRs% z6V>j8y0si9vmI1O+)dD52E_KZoY&`o^}KlkLzs_g|`W}D2c zsF3)g<2V&{$@XkOg0A4cV!oHFOi&x9>D<{qGb<`2s!kiPa>dwMPJ%9GYsR2L;+KO- zDoZ|F3=(v)*UcEbX7E{**BFzaLW0kB!315!J{I-y&$j#2R7h+dS5pnH^{Qok6in!) zj_lP+?-q5{vp?(m`@ekhv>N&5>lT71>fEjyqxuwD;JJ9Zj@b?>BnsS&S6%ndw8S7m z*9%kosy4^(MI>w=qAn$A*ZKWJRf-Na;``X)s?6szyy#8JB&n(Urg`PvMTV;)xAec8 z?Vv&;_uOIXQaM`;=3BN(KUMuF?PB}P7*t5ao$jypow3CrL09qd15~b~HiF9H9D`K9 z&+jKI5?jX(RtfLfVlXSZI5uX>IUZeG4p&R3MUIV0a12OnN-Ag6 ziS9jys3nJNF-XuAoE7`3MQnfdd!nwFy{bWUA^P|1h)=jn;%!;n;hkB|yCvC*C|LdXBE!HzGf9)P>%3)pRHQ4McDkOHy z?xE6Vv8_Q8bftbOP93UYBd9!-qo*3yTf10Oa8@MpR_vvwOt-~gU3Br8!HhwL#JI%X z>exD43=(wlxx|dYk(&KQoT`vnj|WHAB&d*xyWK<8scO5Hkf4h_V#c6C;-kSm)I)u2 zF-XwG`DVtb*K3Tr^~Or?xv$-qFRA*|-t)@SVqR61Puji*K!wDD{wq}#>vspaw*YrV z;64FnR#ZrocyY7p)oY`dVK6}#fAwz?R7jLgvr46DX8R@w3A%z?PK895GxOBez3VOQ zAVC*<-E7B^^y5{_PxLngczR)q3Cq-uj&YV4R7mhV4KoG_y0|Z|Nl+odJwbyBx`OvZ zrb2?}1e!5gPkTcRc~H;x!9C`x3|VxUy>1eJZJ4jF7S(Iw_mcC~4}UH9dbD-RwW{rm z6_(z;GHQ-$zD~OyT{ltnDXYJ|vp?nywcuU-?`8}tBrX=8tIEG)BkHA?rPfZ<(PO5} zQoBFaWv)jv26KNpah{rT z#r{eA)NJQf@xA(ry-1?TZ?o0>Yql{bL09m+qC#Tira9{Mw0c&WeMN#U&go#H=!f&v z@~?I7!&=Q(C0E(n!MVF;!)$fyb3F#^bu$JP5`|ODR)3$m*9g+Jr{gRYO0QSiT`?Y> zsbrT{zREFE?fP4n+3P03wcR}GP1P*rz1BHNys}0}JSJht9 zb?vXUK$UEv%Um}mLD$2mcB%XL{f$DzA*1II=8n|$QI`*NBpt5k#0@Y)z zcCjY29aKo9EU`e%YGR8)f-YW<%@~|NlaI_)@fCEvoS`N`g~Z^2GgYXQEh`dq1RG~?Oo9rD+EZt$hq`Jyn4pW#L?*#|NW25Z z*TE)1g#_a1nQSYX<-MJ${ zSDV2H)KibXVR@B7g~Z7I=hdwE$@d`W;+`XBU-1(+e!9qhGYKjrco#RApo{%x5>!YG z{^o5p`vKeMI3(y|znL+pkf6di*U}83Te{~zn2zDr#RSs0puD@fm%AY^zZ&2}@BW62TZ-ZO8B6cx%aB!S?yKV|qzlGmm0tO6-;JU|qDWF!Su@l|F#7k~vWlv!Ga+sEE)^2} zS7ntZ-`ir4pes15Ob=v|N50mX416S$q^_!al;6uSvtnP#x(8+9#K?X#31&qiZ_5Ye z^;Vh=Cg|cfl1zdMiI=Zrk$0Z7#UMe~?3c61sp2+*%7naG#s(cWkfd{L1oR=Ofq`j{bWTVX-OtYJZ+1?tmrz|DU-CVVw;Inet6ueccyl+ zrr^FJaV2vm$$85bgLTmrJa?&(D0?fTr0s6IGLWE)>&9#cSJAd=nPl<2d#xzOAhB~m zCi(e>?FvVNuHBzxk{tDH*Ig=0vu2icleCL9neCuL;*0pqvL)FTg9KfCmM~*bA<^-h z%(CKyEd~j?_>5}C;5`ezkLJ5@lb}L^?<|7}x_IB$B&d+!POiZOUEI&sB&d+!Ub7}q zd`M>LUwORuJjlJ`#{Zg079{9@Hwh{vx;>vs8qBv5tlkaL}dPst+X zuG+?fO7w&*^2Z$QVokwWk(k>pi;Syfi^00+%26zfym)z>*VASUDjRoZmV_nR#hOfl z3W?apnPp)oTMQC(E!dt(@|Cg?RMwZsB(L3m$;+KJ1!qN~$LNgG@JCGt6LbZ?$Du;v z$i56x>X0o43A*C*W{}B;Z3LC^@#&@8dF^6NW;>{m2<=QKB{JE1mjqqy%B7P-Rcr*W zGP7r$sU3ArHn@(DVYy|Hi@xBK4mo>AZLV~e_3A%W#Gzlssg4;oYEujkAdR7kXLc2W&rr+Ye>po=^Hn*&5S{UuDIkfGRZkzGIIY!DkS(jHZukZ zx?bO3QAWMq(-MOU3I2-Gj6s5~qYqS;)VX_EVo)K$UxS)4NYK@{dW;^K%4wbRRphDu`wPW7k!ZPGf{jE7>Xl6x)#FWg1M~ceNl+oNe|bU4mf1GjNzlbBkr{(4r^`b{CEzpq3 zx|tOf5?RMN8NOwUL4q#M1v3WcPl~4tN$uQ`>(L}Q6G?n{s-V<)(l!%G(Dlmng0i!< zji_+3fQ-+rTlmoB0`gGI{mc>)!_pL#q_MWX;w+(yGt_K3^S#u#psXEpKYc~wWPYdR zAJ|&XzM_lSnpsgH@%vu|WZG$43=(v)*UcC_cZug!@kAw)phAM@N(B>i@#G_uph6-c zE|qj!Zu?#z3A)(pW(+DMQZLId2d3+Dw}J_}xHe6K3W?&^E68WJZ08k`peuM6S}G*C zOQM+-3A(uVt4UBH5xnCf3A%#!lr4DifSOfQzoH);cSxOC)y;c`E;?a<$9VF=bcV{S&7__jo%x-0i!Mf<;Sr=wIsF29` zLtRNHwtGt?=<57_bE$pX_M1^EBzR7}nH34TcD9U_mD?v-dY1}`;4|+(U-(~@{~i4+ zhyvxlQzH-Rck!J0W>!>4G#h_WJ-5QPM&{V~1L12?@G5^UWAk zNPP3!<1*x|Ed~j?IP=XIR7iCD@;NE>z3uEX5_ECqn=z=6NGjA`a@Muo-z7m;!rIP~ zyV68U?@}Q#uuT^!bbf+`;NG7}Pj!;2WBYinK?^&{1JiZcYzLK>GRI2csoKSwOo9rD z0Rv;@!{N3VBf7{bSe_rCNnGM zP9k64F0yB1Z_B(QLDz}WUF3(RHljk84zhTFR^|@vAk)6rW!^P3v!X)c!h#M`UfITj z1YMU7caULoZ3Od8U9yYp|4Gj=w$IFp3W+({yU6j;wtKH6=;E9t zsFTF((dFPfsZ>aOmZOt=d_vP^3=(t|S=&)EX0WXf_TrTS9cAgyx<}dTW(+DM_Po$h zYL&Cib`o@P=9@97kofhhj?yUB7J~#`ygr&Sc+H5*)mh3tem_?q616^wl_EE7@s5wpGiz=;91DV^AT{tWyV>p22oaBtaLim1Yd? zp2A&DxVwi*P$9wJ&;%27@pDy^phAMbp$R7F;^(R+L4^c=brVd`#m`kuf(i+Kmm-*; zi=V5S1QilIhdG#_i}$ijf(nT~Ntq>olI;_B5_IuimKlQz37+#6Owh%9Stdb+1kd>j zCg|e5ER&!@qUST!WnDlr^%7IO=)D{DlzEpX zd*vO@x6W>TuTPCN+d+lIC5Y3W-(K2TA7%woe*J(3Set z(bBW6ZC^DiB!W+Bs?@)aRH~y_4$rG9QL~RcGr+c@sF2`^T4rC7plkeJ@lt7?Ed~`5 z?cR%*^;>MjgjKy{;k7&M$kkiM+|p&zW>!>&fOvUqZ~4z(wiw@k*;6tc(68t}2=$bS z*L68~CeFJOC((sm|!i+1f#ZF3trr2FG^L#op54imsP6nFJLQ zk2H>#4d34@E4qT`F4tf|=W~L%hjqPNU1nBPNSs>SNBVznn!>4H0aVt7Asp;Bx3}b9pszSvJNK4qv+i~EVegVy`-iilW^3AP z2d`I`a`u$G&GbxUADRRe5?5k+%H|hs>w^Sc!PhJ1yKPD@>A2*6T27)^nO>6qLtD$) zS9I~3Z?>ExRrhqfoWG#!<;a=@6%xIt#><@Dwya3d#ca(OR7ljV7%%@>ZHqyIF3vYI z#_seLrTvpry=Si<+EtWuXZ5QWzRENSDkS*ri(rB-zRENSDkS*ri(rB-zRENSDkS*& zF_@r>y>1dzNbuEQFhLh*k4aD=@xucnW#7xQEw4*R(8W_x%@|Zj@HMJOgftgQ_J4zQ zu~TjTyI4-y|F)P@HVOY%bdKWxcFifXCX?`^J1##fr|f6zlug2a?d&N2NvKZQe|;T6 z_~(~8iho9#Q}#dQh#>rP4IRZlA<-%OCmBW%{uw-u;@`P*%KoWDVM2HA1EFO9elBBYT}vcET~qxicgIc0yBqX@#^f!|U59n74vzq45ck?M(pGAx&~i?O35 z<;gFHKhXihEGr-@t(8a(x>(ABHS>^H?lk^Glx0v!<`uZ=LSx>`{oCw(h&XcehiPGLZW`( ztkSj{h>+&Y7`@wNkpc0M@jS0juwD}R*JhS-jcqYV(8XRiV^AScDMw~mTHF?c1YMjx zW{k`K_n=gm?7Y`^dbI7gS>(tl=dOxV-aY<789YLlg9*BF6n;ovjL|dSB&d*R8I@Ju z7;lR~g06bcJS<&K+hR~5vGm8Ra%?GLc&WMbiUeIpX8uQ-J*(%j*$yfsri31nxG!xn zNYKTZZ^ocPqH*SIaw#3wM@Tm$luUxIh!y1%T+c~OGRp3CbG@l;VLSjpUjPhDr zO$QTnW$2Mn8l(o{Vj*`trY*=Q%U0OF}w`Ios*_q};>u*{?RD{Pk=S_l$n_%C{(+{P4Oivk%RzsE~N1Vm3)Wg6Ba$ zD-v|Er*#X$?MU(M4pm@=^O>nLf+b(uq1N5hW&aaX=ikk&sF283c85CB`gyOWV1lmT zR~b|c;;rp!{R&$Q5(nTKm2SKG=&FsNaxrF``m{_NFL%~twu1_ZRpYm+OwBYMOwje! zhR@W%I2%D_&513lY47{Vio~HTThx@cwis*&UGK?ewJ6F)@HK9Sami|CI_-M*hfV5_ zZMNQ}vLt4c+B-nISd-aTR7lJ_zEO>JK9h21XfQ$7?Wr5p>2-P@n*^28-8ZV=qqU2% zO@a!EzMVFzvnQPI9fY%Tv5@!t@$za_{KK}MLRav611cnLgf^-hgAv22-+hFVNznDx zwvDRG!yr7nON@v~RvmM-^s@5L8Fg~!dmpcIpI}|*N^Md#)@quueZnc2S&=CA{wCGA zqozF~q&btIi`i&j^M* z;4Xr$X9j(yb}Y0JH@ELl6rkO& z=3AuRRyAR@&YeBt5suq^n0-aUKk+u4l?Lu2=;HfmUAaa=$y7-AC+vn}glq&|jfQSl zg`UH_(twi{l@{rCsOZ_+#n_(N8iPdJ!8_FStB7GG=;B;3WB8v`IxXCjr=NVYW0E)f zMqW*j)UWHZNl?jtEI}r9)GpR!5>!Z3KAIqDN+X7gh1@YGL6`sSi-_@{LgLR03G(3Y z&bKW7CqdVlEd8X`RuEoe+^qhdF;EJ>g$TK@_a39W<;fbL#uGlMH zbP{Q0p!|IXEf0CXT?AdhccZ9~=y7|1{QQuP?bYtbAVF8PRRbixl8vBpwdnxq8>3yU zDL4j+=9gcP99?WNSQlO0UVcIL^sy0CTIPL0swUh|RwUv+=r65$*kUj%x;R74mQx{d zAiBTAwzS0{LD$Ml{p4tM8$sopIsN37yxPT@g0mvAziB@ieAPA+Sr=WrN_a8cKOuLv zbLIT{bU%4wx?V+Gn?B(}$y7+ZI>uRpJ+TIz`rU^~(DlhT{bWmB5T4y7{O?~mR{;Mz zS5DdgE>^^qVff^MQu>Up>-6G*vMBfctaB1umkpFsF}B|2m4Pl^W4tEc`4dVm_T&KB zQ$%M~fBFDvQeBr{Pc>4i_i%O;47bB?Ia@pJW`F6NSrfr6r$S<3w-@AUMooJOg>+h> zWD;~u`SJxh^e_kwIODh6n zNTG2%RJQ7!|LI*nhW~3>r{5phdsx+q@9Mci8@^T7@;JYc508gW_`igA6#qB%PC5AV zk59haud=`6{PNy$Jzr>_s*U3@2_z51_n#|!URNc_9^gLLt|p;vn-93$tjJ!-PjJ-YwOZdLhP zJ!)*9Nl+mXH+`4t8EqSLj&u5k->8v;0!Gl!ilati->k1x?!}rmvm!wkXOBrR-=yB3 ztFBA++-3Vrf(nV^V|J>jvwHRf6LfLDdBmMRq2%LTzEfLs=}&&XO88Fg{X>`iZ?Q+r z#PKigR+pBw_vY@2TVJT^6?B>JWc(N*cP7$xWA0wn@_0LsjvySj`*2>1hQGn@L?=<9 z$$s_m8cl1f_xCP>uDTC>r9N9>BiLI1xB5;zUSrG{R7m*y1cdu46wZnSUA%UgG5G0Q zmFIRkcey%xeZ}=?5>!ZB$oILLdai><>wKKQA-8u)(8XRiV^ARxs<=xXi$V;ie)nOH zAYGh2+Uwd~f+MwT*VpQeefKjGzZ^2D74z zy>7OH3W=Gob&)zLZ81pDb^26iIsU0_mQcAG(^=ZZX%}k>&Wc2>qp|XAMq3QlMHlCo z8N=U!#+e!Zt}{;A-$%nKd&HeTp=2r~qLX7~+(p}KY7%rUE!kOKmUK4zu=w}sjuW)6~b(KToCU`S^*Vb;5l%UK0uZP0zaNO=AluU)hH;cN< z#CT0>tM}I-7@b-1ieVB|NYt#*TjE~CIuC_okf4j#G3|B!I+XM6o$$^kP7D1#OPn&> z=Mj$EeV8pLu^?Ah*|o~na@Iu`dtKM=25@7r7srh5A%Bd#pYb43v}v3)TzIdn=;Ao} zS-FWN)Ad}Ao-*u^t~Y{k+TcFSF(+|zdrvu@2Xi;%0e2B}{oJ~j#P$WD0f(US=DuDs zWS@5ZyR1lzDcD~X+2f4*_V{|Q?4Ma4v7)w2 z|4EJA^r`1c+^1KhWXB^$~Sd8dS5%MK6p!)^L%_pWf*EB7-LPL zD{9iR$arQ9W$LcQhSL&{gx@iz@GI8^Lxk_Ya1hS96}W5mZQAf90&Y5VEzL z1YLin{8{Z7Xp2FGM4{F{sS{HX!)v~~qDasc+;S=;;vYGux-UnJkPZ?`CP5d+=}to4 z|3b-}Kjl6-uM!G>;>|101#Jz-ph99_h70QHW||Hr=vq|ig4&P-LWgkr>fOetRs12n zCaRq{suq{o;$=0i*csL62mSA63@Rid)}SAQ1YJvRo>9k-B8E>;A;C3oX2o`l9(PI& z-X7VeJJmZ=#GNI~okYdmKdLLsk(J|iA0|Op@U?^riBW}rREs9qVvwMV*D;-r_t(ja zSG8{ro=`bc>3Ug{Nl+ni``r_2;XcfgP&ft&x@s*wp>oZ(5xfraI?tVm4dNw=13(`*M75(jf%P*475>njp; z-8yt$Jy6^>OHL=8SJ|6u<*f_nREp8M%(Y@>MTJD;`sY;QB3ld+bn!X(PB-0IQ8#`& zsahV^z1V2_kLu7`U1m?4Sy3Tzyxu8wU>3$Bq$4@sJiBm8y>&{zPM|Ad1bu>YbkDXE zs&E%Q2AtDoR#ZqVNq5_BZG*AAVC*<-Hg%Z*K6vxGWt0+ z^`NV&es^77+2@+-yvp`mON9hys2PIV}$9 z(iVdRUBOxTyJkCC`TKf1Wq()jh?Y~CF#U#lZNNJ3H3Mrh+d+lIwu?8^i4&R*Cg@@x zngkUR>u=mp-5Tqj4kqYgPkV&>C*-~YI9lwYD!tt~oyX}D|2!V2?C%c6zVZmV{F8cY zgyVJ}p=8!YVnUN&RfA7;Y;E=a-bK*m?+z8tDikKDkl1_UH?{Z}VramLLFLiJYij?0 zoZZo#dRdcaw#Fba{MhfR(({@QCg}2an2%_Of9{f_^vQT$4Jx7Q-9GMu%75vub~u@Z zlKnG49l}5N(<%F>L`B3%ll6>BdO^>h?5WPERH=2@Ke04|ph99t?K5im>$cg>te8pu zug|FON`vq^%xwq1Y0d9e^Sj(;?@}SbZ%yB+UW3MO8tC$OjfrSE6%zigF=4`Q2MN0T zy=5W@DkS)uFTWijx398%P*fhTh?By@(I$R+NT!J}Y=CsiHKUV7sT! z9`%3wZ0p^S*HunmvENB-nO#9@j)PX+0{!A4L?F`~TWKBHZ%$;-!@6^TC% zJ|RcbPP42J)oC~hmb-NF9UXjRi zuB=>ZY#Tw=MHknKu3i5PC3801>R&>Ub zvtZ0aVS)+?&K@%c3A&aJC?`4dAjTamluU(0#7y+FVmpqHEGxx!Mz+bT-Y1wliTuBo zk%d!iYmfw8+lH5sucK`QmAL$6WXl8hlNE{6M@!46D=_A6W1O~xl9?4<<+c`+RV4hD zQz23Lqta5Zg)IgNy6V&|CJTn!uA)>(#IG$a*>8dH+d+b^-#ZqStgW#IUBY>UlBtkb zx39G9U4j@P54ekN zbOmQcg+!IyMda&-woepE(8WIVddcrAww%{sw#g)@knm5BiFgG-g04f;3dsA5@F|&} zm4DieQ&+ZpdF1H3`m;OIW>!>4EQ-%3d$ZVLkf19fD=&~c6S*5jt<_oN;M;nf{quh! zT26(;xv^Pg!+&jAk)W%~>}=BdNf2&UAvY^3V}HmltGDXDVohEX9Jl)jB~u}>NFJ4H zFWEkQB|#U*NmuUubz)Ed|o})rGg09pjGKk7zdp4l*ceRXC|FFJ(Ft%5_H3o@eDKkl`_wTwU zI#ei`bR{ zOoA?dC-8_hNQK0jIhm!ylGiP-kogHX?>X?kug=F!$<2xi3EqG32*>R{OoA@nzt&do zuR~BFQR2nTs#mX#mUb-Yzfx7X`M#%gIWtdf-K+1HluolsrD=wH`d&(IR^59HQA-Z# zKJoXVcY5?@&cUkLI`oxKP$3b!V4&Ln28d9&9sUmdPQ3}+hp0QD{s+A+I_N}ENOd$*{op8a{wKP}fGoOUn<>-G2VkBH%)tL`WyZr6=beF`}{l130z zNW3t$uWEB#XXqv5x18-@?hobYsfP6i;kSe1F<|Ua_0ivvV`IkP7?2pWl*@>cAn zrcAfRAVF8ec=%ay_T{hLLrpoX`-e3JXGLP!|MgJm7TbE4bTE7R;R;#7sqHi8O?xZ6EcovI+*#yG7HB{Rn6M|-QSnF_Y@F*R#bAYPf%UQ-cME}TEzBOzb7Jw(`qkFGP9!V!Hfgc;Rzr#;Pe$& zPS=*h)zWFYN4e5;~K})bBssGM$omp$Z%EUmW|-GcI()|D&al7CV1^K zv!X&`agIT%-{-a!MS`y4;|Hi*M{NX^xYPaBzBBie6^XJ{`l;$a*!ZV_UN&5{)XHYMS`whK6zS=eDkh(aT8rV~~DI-|Wz)?A#R`YqPw3Tq~+YQ@HS|8B;hLSkT#2`c)!rh^H(@_#;F zl_(Ih#Go=c+jv#7s&+AUa10VL^^(+A4Q(-47hU~^ysXBx2H^$@xntg^K|QtYE&bcj zrxzxwJe_rGvy^F}jwga}-0s8q!~_b7g-sIGh}*XDptAR|MD@xH?P5*3a_{e5F-T-9 zoTx^XMhq{dyR)L}i^|o zb>P+rOIAf|4pXfc#(T=olV4IxQfb#09mlDtOL}d3wfiwh{Bkf!Wyz-rt~8UNLZa%l z@hVpgveM0P#)Hb`DihR(Y4;O@#PyvM)X9^G;kScX(Zws#orLbpUH0P6gfZ&RcXYk% zb+hGENaW8pR$Y%pR({J#(8XRiV^ATna_3m}TPef{=^)N`&oSn7as2Njbf@K<4d#~i3X`&Qu)Ld zg9Kgdbu$L{BjWBk*1eEI?p2fuiMiX?tF6r&TCP_l=;B_pURHPhgp#>GEqAubd;J&n z*wvbr7*t63XGw+MZTm4u&^4=BN|{=*`adyzf(nV2&!?3yc7OvtcaWGW;w)GsW{hoY}M``rXx5iR#3 zxWtMgH6;I6(O%2n?^#3Y6>8v>^F2{pl8)83^wp)$s!9JVF`ja)Wi^Sps>@aWs3rqO zG`A3RUAb6QCY`z$!MaGaO{yvjKGU?(OI4NWQ*>*C+d+jyn?q4@E!x&sBnjp;agXmi3F%PDoUdya)sSf;?lpHg9wbujt|8@* zYuaoF3A*Bs)sTYE;mQ!wxrLIqpRX?KN9cYZF{QeEv{sinL(LdeNPJ(qx@0(N8$l9u zac!D0IJV7OMoHpAJoW9Y9~XfJ23nhmDAm zs?~JA=Sq%}PCx0H!TILZ?zr8DITK0L&RSL4FT}j^>@GoNQqQW=ChmS>kSM*cs$>$x z2)RM-&WbM1eC^eLL&=;!^-tE2a%*+}aK3roP?(@XV%*m?Bwv2pc#xoL&iggwgE2OO z%H)wXMx*f}dM^3x2~MHg3r*N!`XLdhHt_B2P|q4DkMHW+f)i<#FZfwjzNO1;H-Fh z1T!ppvZq{ZV%tfF3JL#|^YANVKPwV+T|SW@eapvNdY1}`B9{lsmkS432r4A}b2KBe zB0*Q$+e0O)j_q9$6%yQa%p5@yba4+clb}K(Vh1z7cS+F29ooDYcm6ngCt%+(?k>lg zg0mvQedB@&x)xj;CAXK`zGXp$1W!aUWAH>3p0whhF%uqhzvce9GL91e+z@&G*CpOu zdVA+^*?MyRKl92ZLhhAe)X7HD`Pq%0vSwB*8By3JL!lyfC4G zy9m1cQ|(BE+!!0LG?H$8*Lhhn-i+58$?@j;-|tj^ryW#C_$QWzV>tD@k5DoRx>7ve zNY2;3D~3lftC@9TWZkQg8S2Wtzjw8q#GFYn^2LXU5wa0E`E_PTbL z;CfEox}glJaX(p+$iA(iq^o|ftmq29CUQL|IQM)iZO}c+Yp~Z2rw#7IeEuLY_G@ST zpTl^BJm4;ZF0LET>l0K+44EGz59hMYL=trIs$|CC{CTTNwB&53bLV_B2`VIdKNl^9 zO4wRXg05D*qNU|EjG!0D?cKPi%F2nk`kIlsPAS=xVyk!kczkCyY4oUVcNi)petx}z zH2GN5W;^)%+9wC)lPcY|dof6x1Qikm^Olg`4{rPC3g@?j1YHqXxkSiqIe#HNH0q|h zvRmiQUov~uJ8t(8N~S_$SFZGu;yAJjdB9x+UF;Fh>l0K+{AbIa=RBVv%C%Rd)6Ot^uZ);sUd!>0~AihmlhQ)Z8tSy3V3pW+&h;neRwoHHlGr^q`B zUH%!cVL}5A!Cv%F?sZ(83%YWRIG=x97$A+lUF3}|3IC+vaEy?Rpo{B9d!4@y6-xHc z_jT&>Pi}R}Y@bIsZueofoP>V{Y(!S9i!QcLSML3FVo)LBpG+GOg9Kfi$7T%w#B`@F z|4e76?4L6n5rYZ||8(du;RXu1eZ|?}pC|0N*du0ER7m(|8HZyy^}7#qJm})cYOD9x zA-Hn$GX@nB{#o%6F-XwGY|R){Ncd;dN5mjO7yHnR!9MZN+y2+ROTs_v z`+sId7gw5>)tx`iUX$1Zm%FTT*GjV;R7gbJDGKQz=9w>a@dOSt1{D&#Go@<}#~?vh z#2qge2)V2FnWaVKP?=5MwVkhI3q4arVzTRh*R_WUDkQiQibpv0yN^&Z3A!eoC@jyX zM2wIJI0RqA?O$F{vSr@vWw@tHLHX-P+xv6Yo8sw0QaiV2O3+neNKrYq*ha90yUG-lmg{wE*&}9FR7eacWa05AQan6rIFHXr^SkB(m_b=J&W>!>4%o|)-hWx4NV1llQS>j=C zR_w*W^NY%=gZDFnBu=g^D#bIRJhxzV~uH+3xWo1np(dD6{lJJ0@uT?e|kzb4G zGT&e6%Dul%3@Rk9bSWag)zq{}P-&8)h`iDCeqxY_omE(3+S_6mBGbA?o1>>7gw4Yg9?e0`3uU<4-mtt-+egG24`~0)ry~Z*IK$R zH7+P?$AIwcE= z9uHo@J#Q#XP$7|ZoU@wWvaNFxba957F{qG8)wHOLIb@4Lf-YWTbPK}m;C@8hr--}w zm|0OF(es(=vN7)pZ!QEAblt4|tmGT8z(PEP|1QinO!(f6g zzNaz?DkRv4!314=Ph}ERNbv4XFhLi;QD72ONJM;dAmnk*IwwKbM^BEDZ134t)SeeQ zO09BzymipGdW;*|X6`w5ilty5-fYGy8vIC9at+ z2d_aYBnAwOl@Ev8);S5fUdkLRg{RsGDuWhwk_V>WPgW$7p6Vo3$J$~rE4p}9GRK^2 zEoZ+DvTVK{L9QE=7_#Fg~aQ}qdF{eVJ`1K0%*)7}t?Ih^pJ7h10 zQ@{H#@2ZhVy)3^Rm~PvpnRU_i@9r~@NQg@%-IlMkT&YE? z+!fj+sF2`{2`1>`y%Uq5LV`0tn4pXIPE3Ld39jH^f-c@WF$pRpBEB0H@;GOGkf4j- z_cLQ~_r3KcGRbSV_3jP}wr7%jrN&uS?Th)ZshZCwc}hv=_pWKvj`zy@{z@ZPKhpoM z^9g6gx?&q=mW7>ky^I~46^V^IGfTn}TUM-#t{la($cvY41oN%;NgDa3o6eo>Gqa*X zV)o25GBPV#9tyXd1YKWGOCxpHzx+?{x`0E4l9S&_E2#$ReA|^vCx@!&^0Fll0K+^cbB{8vbaDL4q#Me4S4?E6$&}-LlBIT6)x2Q*c%! zq9-d!0L1ff<7eiN&YWNb3w}xr>F|c}0S*e>W3JY=}xLr#`;d z`k;$z(`(0_KhEoRjMSb1S!7_ez8d_ySwcdpWs$rKZPyakMHffbOUUUb_hIfSOXBgf znPuuPwiv97F3vYyx%bzJ!Pzh*O-4EU)&0yw5*eFjkopH~^NLx~HF8mUd2FYRpi=He zIyw37{bWU=PTO?SDrAentmxtlHT#MRi7{WMl>^V(VvwMV&%0&}zCY*tOy1Em2`VJ` zOT=J;uA>iBmejdz@93$J;4d}J7$oR=eSbw6^}6kyFclK~g{v8Z1YL2-Wn|LW?w03T zDkQkag&BhcU9+|nma>m`w#1-9g1cgvF-XvLFfp6Fzq-voF+9w@GCZ9)Pfak9EEEQp{3o zry+(@zx!}b?Wwgum29Dv4d2gK)n3wN?lr5uuH7SI-cSqP)zL2&pR3Bhqsx!3o2dGf zednKcIBxe5N~S_$*PnA$_SI;I1{{L@^Vf#?>S|HlCia4^TqB`mDkM^tSfFM#(R46D z*TO*yRFAPB{H&-9T)03T`|y6UBJspq3sm<@h!L{2gRZwX_@59;^& zBR9=aucy`Jh!ON-P$ALex7lj`HCqf4baB3UE%0MdA(8f}+0M?9wiqPn;ygBEa8}oz zI#WH=RoBa!Oo9rDr7}~giucNjuCH>;RJ;Dh2zr6s+0K#T>f#JFv!X(Ry&g=^#eJkr zf(nUQBFG%$@#nzU7VUE?vCxnK7u47(8&M3U#u@pfdT$ zOch^2yI50j3=(@f&QhWDh~c!seVA8jx(cV5t^PiB*OfZt5>(b~n5}Moem~C!B(98_ zqnfWn45xngVP-|wemoOttM}I-I2)Qry{Vd|yq{|#iNQVQstj3dcTzbM>EiWR=i@fQ zZ3mz4_#FQ4Mvw%r7=8>ljPYDc*OW>#RinwaJCNKrpC>TzeyJbBYX=n)JjK8x9Jl)j zC6l0QWdHMOR{Z3DUNdOGA*hhxt8-nsMofaP8YA|oCdbBDVo)KG@vWn3QGtQ~5TS4k z5_Hx2`$JVBHvS(%15P`rka)h(K2;^j_Ij5DT{(yCQIi!2KSpT7x9VD+ZeDc8n6u=p zN;SC0KUw+hph6<}9X$!U`W8tq$DZwHi9v+~-&1={@UtR8SB2PI(q{V*OAIO`c=m`H zg9KfvIu?%4ET-W>M zk6gdY^}FZhoS8j)@AEw8OtJS}$Nmpd*MQVjIU&KH>Bf(P1Y0kz-7r#2W*-u2Q=)(YD{oKfGu_xhg01+fa0hJR1P|H~^Zn6$XEO`2cV(E8u~t4RE3K%4aQhj4_CgRTF1jm!y7 zNF39?O?qS7hG*IyK}fK*{i~~|w@-}-PQDzodU|h8LyPXF9VGg+T|I5_PUPU%V(aKz zTc@dCM+ASCo*C0JeYw2h8U3%HD}Usika(&`%QXA?==(u}t+8^(S-E>eaMH5UGOhi3 z!%rW-Qsd`}6B1kf)*>}K0YAHn$z!Rjl3>8?f5 zZwCG@VT;F2<9`(=BwiTaDm`9}93*y7(JYyA;G()rU|yVg58+lgaq%FnkLxd+I?e!6B4{z zYMNk+`>Y!ioRC=h{YmN7PSKqg3AXq-xs4s1ka&3hsPuTx$U%awmAj5k)h$4nNUvo0 zw^BMkl!}MGywHw${+*V_|0+&M@Gqw|O|Zo?QDcG=694tL0qcyD$3cRvrvF~*yxl)7 z?zp1iQ}#A`{nO&zEgLe|+Zw*Q{J(e_uf&n~=#2%%H3!YH=gkOd>;D=PY;i@Pq1*8P zjn~gf%wJF~di;2E;NaI{i)Ylv4o*m{^X45zue+`c93&h`I)@u1bO}{vAAb2vt|*gv5XSO}!GUtG>6|1x3Gy2iha#Uzu9r z!kdeE{f7jPoD&lC*_W4pk^WEqG7!ENTjS>6T1>A*uR3!=g3nvS7q|Zx2MM;iz4~}@ z`^pW!B^nc)kl^>fX@adI#=TMO^v7$0=ZX^&{5fvyAi>sQ2Ypi!X{(HUpvmv^xDMd3xf~VxzAc?C*E} zs@U@BhRm;IkE8rQ*()gCTl~&8 zbTh#T39e>Zw=N>s;?HzLHxrzY;M$~h>mq_J9%&8TOmISiYm?TkiwL&(8>69{2~J2% zIe$*E>4QfGKf5H@8u`GLMVG%s1ScdK|LwCg-}s{Dz%!1k>c7nY=ELv-yZc|OV75 zOTHFcp3U)4m)&c(I<=EIIPokF{ymLK1w_SL^0nCVY>tI35321xqK!E?@hlGh1&&Gu zM8#Y3wb=4(j!W)1wzl?>W%c?!=ftx(_!l@T6%Z9~$=71bvpL@VbXe_*t)4IkC!WQ@ zzrazcfT(y&z7|`a&C%xKd*W}E8g+2uSsaZ&VFN_PTk^Ho@@$UDy-%%u z?D4_o;KZ{y_=z5s3W$ogT3>8Jd1;$oh3i-Wg%qP#a~ieSsLIc|Hf zTK~l{!_C2oXL0mc^nNkB%j0QUBjS-3k9OiDB!sS1+JF95{c3U!5#mM?o~5;9i}}T+ zEgvf#;oXGT{SJcJ9BZC*Z_Vr{Ppazq!&@@(EQJ3BKzkfb5o~!j$JnjTu6cLvICF5~ zS-!6SrC@V3MX=@B9EYs8e$D$W&ol=op5^QM-xfAUQv_R{&GGvDy>{7p&ROQ*#It-| z|C`0;Xo_IVvpLrP_{c|ZoYCOm#It-||4Y&4Xo_IVvpG&*qkaA0ch9iL!HH-2y8aih z&CwLWmS=M;y84{@W`i2O=bU(!uj_xg+Z;_1Y{qL=tqbY(d z&*s?Z=#8s89lDn}IPt8HW2Kvm?JEbDze}1T*z#I&*kMr7a-DJI_oFF-Ezjoo@|fY(*>avz2PdAz(Ynha z#li{ldb>T2rUq6v38fbG-1w>D3iC+`$~2c$Tm0 z>v-m9ieSsLIjVb|RXw%UbiF^XaN=3M?qd^ci*dVMT0U1z5o~!j$Fjv|Rl8O`)BE!Z zC!WReuZMRn&b;o5($N&bmS=N3@Zy=(jelCDMjf1Z7RRtddKPefN$znj+ZpY>vefH>+-R z->&B1#It-|fB&dCnj+ZpY>v-fTdR8Aiu;>`6VLK>{e7wCXo_IVvpI&h`=$Qpb&oLz zC!Xc&Hok6eieSsLIr6=M{#}YoqO7HEZ~W>7~}Pn?hQi2MJC>!W`%A{a%lAKX14b zCgE9Hv(g_^kMpvF1ScV3j%}*FYo@=^aFFZF{&mNO+dkl5^Xnx$k5L2~I-7924p{ zuYGrB!>ei}JWFf0Ijz&1x61pY?B|LECm~^u&ZG9KeWGS#dmJP@OY5dCtzWeyUarRDESw(mI!PC~*Q zdi=>zRn^Bq!n3seozvzZ!AVG%Lytc>s?0&cv$VeXKdYy0FOj`b<{-gINSH&9KRK$* zLBg}N+HJB%I=k<*(m{fgkT8cHe{xirgM?>k_1bgIG;nctkl-XF%%R7h998P5knk+6 z_on?J9kka~<>Mg1Nl2JOk3Tu8%t6Alw4Pm|UE2SY>>$BONSH&9KRK$*LBg}NdW~K; zeLp-qNN^Go=FsC$j;e;|3SY}k?K!DqdiLOa2T6jHkT8cHe{xjm@5BlT&(iY0h+^Ll5}bsDIrR9`t4no| z@GPyb$8}Dhu9tteli(yI%%R7hUR|n#glB1eKEHGNW--o#PH++u=FsC$uP)U=!n3rx zKG`|lb60-VfCMKYVGce1^y*R_Bs@!NkDi^=jMMWq0|`z-!W?@1>D8q=NO+dk5B)o( zHizYF9}=8|ggNy1)2mB$knk+6o!9G_Uf(xg!;#=5B+Q}5pI%+6gM?>k{d#(b^!vbk zElPrukTA!a8*E)|d1rTXknk+6S9a@=zUh@6Bsd8Pb1ZDPVYS&Nz05(vv$PgW**N`e zR=#d0!AVG%LyvL2g4O4WglB2_ot_=%Bsd8PbKJS*tojGbd(IAreO@fO>>)d+dY0CY zfBmdjTG#O3D-{x)goHUdKK94@ugiN*5}u{C{zIP@%}>n^5}bsDIo|K{UXOFidrlIb zrSAC%MKEpgoHWnt?ykkqrB%N;aOT6t+}|^>b&eA!AVG%<19JGFD>smNqCml z!d{;gZ(NlfBsd8PbBvQ?d|-LcNy4+V_M7_8V!?gcL4uQzFvnlz7=Nw2=Op1-TFd|a zanbMX>>$BONSI?yx#xVhyyqn0Sz3>b__)|(MfnSWc6^ZFBqYpnlN^65wrIHLB;i?F zH?H<^ap*SLL4uQzFvpE@{B2g=bCU2ZtrwqKRBSRZJ4kR666W|=j=yo`Jtqmz(%S8& zMa8<)vx5XDAz==^gM4<+hI>vDo~8Bs?Td<;FJ}h{PC~*QSIY4>w7lme;aOVq-&|Cz zv(h8w_nZVLAz_ZY<@o#ZtA=|{5}u_ss?*2C=i6ro2~I-79KGfEyS}{VB;i?F-MIFHkq!5pBs@!NyXXH| zEW0B+NN^Go<`^r--^B8slZ0n!oi*{3V%*c&L4uQzFo&GgYUDgv)pIQg&(gYm|HZ}d z1=&G@laMfnoYiXNJZKIQo~1Rh^QXmrA7%#$PC~*Qa#njp&V%M4;aOTY{_<(D@crx{ z!AVG%L(XdTavn4X3D44+@X}|+mak_A2~I-79CB8xm-C=GNO+dk<5NE`&aKZ55}bsD zIpnNXmGhuENO+dk{`)K`Cd|qX5}bsDIpnNXmGhuENO+dkElZaaE1Z=bBsd8PbI4h( zD(69Sknk+6#UsBc);c&lNN^Go=8&^mRnCKUuSUYNw0>LgMN!!_J4kR666TPzT2;=2 z<{;r&T5qnmwAk_A`TRkGlaMfnoYksw9yA9D&(b=o+tQ-8K08Qo5)$UnJ4iVX+C3); z&(fN;{nBFYr0gKUNl2JO&T3UT58C}83D44cx%tv!*MqWy1ScV34mqn;fA5m;EUnG=`J#C7yL_EUf|HOihn&@_avn4X3D45% z_~?@2ffuub1ScV34mqn;)SPoLAltlJG38cJF;%d~kPmkl-XF%u)YX@0#<< z`#}<(rRDE%wC@KAPC~*Q&E$UY*7AOkglB2_doayGf|HOi#~E_`9b4WHlJG1oe+Q^J zNN^Go<`^o+-#6v`APLXX@^_q?g9IlbVU9n`{osA&{U8a?(t73Q&x&WClXtS3g9Ilb zVUAnn_*-7CL6Yz+Eq~v>IY@9466UyGj=x^z{U8a?((+FhFb4@vLc$yi<@lRf-Vc)S zEUmRx`m|VSK>>$BONSNa)IsW!5?*~bE zmR9ZHPm8w}W(NsQLc$zZ%JFx6xdutXv$UGG`mDHiuetf269gwAVUC03_`9sUA0**f zTEo8otoZva*+GJnkTAzHa{OIY-Vc)SEUkSvTvF`tOLmapBqYr72e}{oq`V&_;aOUL zKkbX+>Rlf!pDPlagoHU}%kft&?*~bEme#K;ep$>Ln;j%L2?=w^S*=FSgH^pQA>mnC zwYPs&Y%o1LNN^Go=IAT;gI|^RgCsml>xSe0Ra|gec97sCB+MaawMXQrvd2Nfv$XE* zu&lWF=IkKBNl2JuncNRvTiy?n@GPyb7JOUOT$&vuI0*@J$XTsk&V%+iNO+dk%BOr+ z>~lhPkl-XF%pqsBs+bt7vH1Dp zd<>G{BqYqSuG|m4R^AVi@GPyL5B{l`c~N$d;3Oo>akm_Q|18%aNqCmlom(s~CU2e{ zBsd8PbIg+CZ`<;Ikc4Mxt@PmXqQ07cx0B!`B+T)i9Dm!%^{5`_Bs@#&f#u7KLHlP1 z2~I-79Qu09Oj(~$2MN#8dg`m?#iB*>=|FZqC&5Wbm_yELRXGpZy&4J6(zlqZjs}!n_Q2ogM?>k{c*zg#Vdcv4icP%ggNA_ zRxjs4bCB>XEx!x1=ZXX;Az_ZYxIVaN$JBSNdixpekh8QdUbIO%e8q>$BONSNbW zSs#@1pnX3`c$U_T*&Wig&GK_af|HOi$Io*7jW6#9NqCml3cGelyRVlWBsd8Pb8IHZ z-_-Jckc4MxJ@`rcw8xIwL4uQzFvmM`{9RJs50daKt-nrfpPo4^J4kR666RPgug5Ge z?*~bEme$w%w@>$-lN}^D2?=w&B*))L<^3QD&(ivMBY7Nu&khotgoHURko&=B%KJeQ zo~8A}uN$W+i?f3SCm~^uf6MWAOSNH7Dhbch+V-oB(*^5Q%VUrPCm~^u^W}c9UH69j zK@y&&wZ=Car#1R!2MJC>!W`$y@%P$e4SP~ac$U^_tF%v(&dm-IoP>lq=E?Cls$3r= z;aOVGb!ngaJ&+wFI0*@J@a~R;XKB4SuzmXVpV>izlaMgSXL9_FDenhKc$U^HceGD! zTjh5zli(yI%&~(Ue^-=yQb~B0*6qKyPyM&b4icP%ggM4weUOA_X}x+>hxBRB>>$BO zNSH&;YQ8>5!n3rFf3ib*zh8Ec;3Oo>A!oH3IS*F#nt_C8X&t!LCaHQ%c97sCB+Maa zHQ$p;!n3pnT(wE+dvtb?;3Oo>A!jweA0**fS_iDqFzKanm>ncI2?=w^S*2pQGv$U#n zJEgm8vx5XDAz=0FNO+dkxEng9 zd)~~~3?w)S33JFXtlq1GaKGt=UH0koHaQ8bY_0v z9SKfC!W_5D`n;|-==Yq2XKBr!bwavmcy^HBBqYo+1@BQL;aOVGJvk^%8krp=I0*@J zbduL&t}gEfNqCl4mnFxi1rxJ_1ScV3j<@9a`+IpmNW!zUW~_UBdhVX=Ai+sUm}8t`0~Ozsmc;aOUXKRGTfd?Y(a za1s*cm@dcP9_9TY3D44+cKN`x$BO=584#R=ggG{o>$BO zNSH&;YBh2m)bB@yglB0TwdJ7n%;DKVf|HOi$0Kt5Ehz5?NqCl4>(x$3+n<;nBsd8P zbIjTQy+w_dbORL>yC#0PQX9o#RLc$z!R;!oupgmV4JWK1o#|Nh+`)3CUPC~*Q zr^@RwPnGwBBs@!N*UN^aA2-Vm5}bsDIc}5VZ;$eRkc4Mx4cl*My8i2Ye30NIB+Maa zwW^#4?YSc1Sz0517@BUnF*`_b5)$T+vszWogXSRNSz6uCJ~8#~lN}^D2?=wYD#zc= z<$h5To~1Q)>4~Y^()@du1ScV3j;b7g=gRe{9)l!2ORILWd{jPLc$z;#~}&N()#7;p=sgz*+GJnkTAz9a{R4V-Vc)SEUmrU4Na#l z$k)^)I0*@J$XTsk&V%+`k?<@nzYDYLD-xW9ggNx}7+r19@5hyw@0S)H+_1jvSz0S> zyBsd8PbLi_ay4s))5}u{C_BVafmV0Lh2~I-79Qt~Ut~RKHglB1;a&ezD|H$kh z!AVG%Ltl^4)dqEt@GPyZw&|1J9G@K|I0*@J=<6}M+Mo^+o~5D4!f|HOihpx}-YJ)mRc$U^JJNHiO9F-j;I0*@J=(_=RwLu*u zJWK1m9=+3yDcM1SlaMfnuFvaggE~lfme#-a@15E`lN}^D2?=xP`n;|-sDp%OY1N$C zJAL+3c97sCB+Mb}61BS8pbiqArB%%7oi5rm@4q6!Nl2JO*XQ3U?*~bEmew9W$@gR5 z>>$BONSH&{=VjI19tR1}(%QIppY+X1*+GJnkT8d?&+BS~K360>ORMMYebOlxWCsaO zLc$!nKCi0{;;4}DEUow2?3;#NogE}N2?=xP`n;^Vn}dXBX+3x9zG>fC*+GJnkT8d? z&+BS~J`NI|rSLB4+TF>;^FKuyUc97sCB+Q}f^Saug z4icWFHE7O$>6{7KL4uQzFo*8f*3|}eknk+6yIb{5XAjB_5}bsDIdpwqR~ytp!n3sA zJ+g25J!J<8PC~*Qx<0R~4eB7_Sz6<7=$qDDH#zlTpn;j%L2?=xP`n>KwQwIsp(%NC={nIWJvV#OC zAz==EH=yo5QwIsp((1Ru{^^0<*+GJnkT8et*Vf%<>LB4+T3;>gn`+j{4icP%ggJD5 zUU#3VgM?>kUH4Sqbke8!+J^)uAz=#me$o5_f0Q6m>ncI2?=xP`n;S6 z%|XJmw5ILRH{E|}c97sCB+Q}f^Rnu04icWF_2{zw(x8*Fg9IlbVGdoN*WG9OT#@iB zEx!x1`#}<%goHV`+P7rn8%58xkGB0{o~3p3bFUZIynIx-kBkH-Az==#_L1-`t)6SV zRy=W6c97sCB+S9pJ`$d#we10~6c62-9V9pj33G6@kA!DwEx-1qqTj;oAi+sUn1ic* zBs@!N(QhvlyKLL=eX3MQa1s*c;A$TU&(gZ!?B|QGZ_W-9oP>lq3McZADD;*>_2?=v>wU2~nX&wI2yyEV5^4E6lcOnT+Lc$ze?IYn?TAQBpOwsML z>>$BONSK4GeIz_fYtpc1i{o!PzI+@cI0*@JaJ7$wXK4+Y`dl%z_n^{2f|HOi2iFHl zc$U^H%bqWGcq=KscAk_S zBsd8Pb8xkfglB0z{O&8oTDN5f2~I-799-=q;aOTQU-eqC-t6ok!AVG%gR6ZcJWFe} zediZvo{}9TI0*@JaJ7$wXKA(n>W$*6PT4_%laMe6SNlkKme#l-3yM$g$v?X!I0*@J z$XU(T2T6FAR^8mUitpFY4icP%ggLm{N5ZqT)_&>jVz=S>cL@njLc$ze?IYn?TF=gW zr`YJW{5z2ZCm~@DuJ)1eEUk^ZzFVC6W!PPzzo~8BL$ajmEe!_XsR}?u3 z33JF<&DRG>c$U_}f$tViuA3bsI0*@JaJ7$wXKCHs^4((7+I-DGf|HOi2Uq(@c$U_C zC%jW!eNw*mA;C#Vn1ic*Bs@#&)W5u4oHQq2!;#=5B+S9pJ`$d#HSLhMilHsCg9Ilb zVGgeLk?<_7ZI{1U+;CRDrY6BjNSK4GeIz_f%kRSeYkiQDkZ5qo`k;PVq26=$+-`XK z!<<=mPW3FUzr8dpZ8W3dzsoLP5S)aBIrQ_K^wSE}LBg}No;+??>Ty+ekl-XF%%Pv> zq^k|;AmLeB_x*HYx?_5Fkl-XF%%Pv>q@Px(4icWF_0;4OQ~w*Yg9IlbVGjK~C;hZS zb&&8Zt>$BONSH%E&q+V6P#q*Z zOY84-L(@e+W(NsQLc$#Sc~1Iih3X*TSz2q=3{B%Z%r37JNpKPp=FrtX{j@@Lknk+6 zRa?sA=$joRI0*@J=xU#STA?WFNO+dk`b&nSL(a(#5}bsDIrQ^=_0tN~LBg}N`n@wG z^?5KmNN^Go=Frdg)lVx_2MN#8+Tr~n>5Z?lg9IlbVGjL#U;VT~b&&8Zt?QQ!Nxe6@ zvHYHs;3Oo>p`Y)opH`?25}u{?^*Te-1_xya2~I-79Qygb`e}vgAmLeB%lZyYkDZ+z zBsd8PbI9i!*6ODfs)K}QX?-_sXnOOu>>$BONSH%E-&a4aP#q*ZOY4=TLsRD$vV#OC zAz=>vd|&;vLUoYvEUoYNmf!84WCsaOLc$#S`M&yTh2p4?@GPwh?>RBe{60HKa1s*c z(9iePPb*Xh3D43RzwWSf&TrX4f|HOihkm}Vt~RKHglB1;f9|mKhhMXU1ScV34*h&z z{j@@Lknk+6Q@$FOj#-u+Bsd8PbLi*$>ZcW|gM?>kt-b&7H1~t-Ai+sUm_t9`S3j*# z9V9$U>!>@2rw1O-4icP%ggNx{ef84{)j`6uv@ZB{c-sE@>>$BONSH%E-&a4aP#q*Z zOKY>*5oymc*+GJnkT8d?_UWe;s)K}QX>C7xMB09j>>$BONSH%c`}EW6)j`6uwAxP{ zk%p|99V9pj33KS@`|79HtAm7RX?-$#L>m1;K1Y$@BqYqCpAMs+Uat-ko~6}n=7_ZP zmh2$GNl2JOKi^kBylq^z(i7)9cki!n3sc3>=YW7ui9A zlaMfne!j1Mdc8VGc$U`QT}Gte*UAnOoP>lqCBaEZ zm_t9`S3kX89V9$UYuIJO)78&s2MJC>!W{bfzWV9)>LB4+9|!K?WY-)BPC~*Q-2K^k z$1&-}jtzTgJxgoyt0$)gYv#SRBsd8Pb8z=33D44+Iq2l{U5o4>!AVG%gS$UTc$U_b zUq+|nT4e_bPC~*Q-2F+yv$SSU8J*T?mmMTH2?=v>_a_O@(ptIe=v3VzJ4kR666WCU zPZFM`_3->r>G7V~L4uQzFb8*klJG38OV1gVb{m=!QG!E zJWFeb_eZ8xw#@H0Ai+sUm_uKW$@@h~c$U^$AB{{G_slqxcifYXK9`J-N>}^ z71=?8laMe6cYl)bEUg#UAC>0M%MKEpgoHV``;&xcX}xmbs5I`o>>$BONSK4WKS_9& z*8HnSrN3^F-z!6claMe6cYl)bEUml09+lqTB|AuP5)$U%?oSe)rS(Sd(P==x>>$BO zNSK4WKS_9&){wuCPKOT84icP%ggLnTlZ0n!_1oa&)O}=jkl-XF%)#BCBs@!N(D^5) z7e{0V2~I-79Nhg$!n3pv{^sP=ZeVth;3Oo>!QG!EJWK1l1IMJ3`ep|SPC~*Q-2F+y zv$T5LGbRn+K08Qo5)$U%?oSe)r8W5XG3m=SvV#OCAz=>g{v_d9TFuhf^q)`j?-CN6 zgoHWt?k?{aCE;0GYmOb8md?!%5}bsDIrQ!>?-wQESz7X>xEF4;kXlaMe6cYl)btd9ftaFq%PPC~*Qdi?3t zrQUPy_V9qz@s}a?y1Hj+-F@(Yw3DnIH0-}3!AVG%L-%Xz)ulQ}c$U^lq^!U@OOLdU&EUh_p$ELn7W(NsQLc$!nUt6y()j`6uw4P{pYc97sCB+Q}v zwe{*!9V9$UtK)tBQ;X(9%kKvXPC~*Qx?fwbF4aN8v$Wnlw0~+{WCsaOLc$#H$m=nB zb*T;#o~3oqYW>q1ld^*ZCm~@D-LEZ2l{rXwmR8$&$D}Xb%MKEpgoHVCzqVdo>f<2c zSz4=HeoSiH?Zoo?L4uQzFo(W>SFbKbQAfhFwALAQOuG4o>>$BONSH(4zbmh@n1h68 zX&rRzF==Y^Vddi>!AVG%L*KuvSC{%YNO+dkwgZnzv&Uoy2~I-79QyuUy}DEf3D45H z_S9q2ln=6l1ScV34t@WwUR|n#glB0jopDUsrWjs6S0p$I33D7I$DdwZs)K}QX?^|n zG3m5xvx5XDAz==E|E^wLs)K}QX)W8hf4b?*>>$BONSH(4zpGc5>LB4+S}&g5Kke3a zMEP8i;3Oo>p|8j2)ulQ}c$U_;uk}y+4ag1>oP>lq^z|6Mx)eu+glB0@+UeNT{oL#z z!AVG%L*KuvSC{G_;aOUz%se(#WDTU@TuXwJkT8e79-~*6>LB4+TIaPIkT$t2J4kR6 z66VnN@9Nd1I!Jhy)|jya(u1dG2MJC>!W{bkUA?+g2MN#8TI-zwX~;p@L4uQzFo(W> zSFbMBLBg}Nj@bUVG-!kDAi+sUm_yEL{`sOLJWFfhxyPjeZ{}l=1ScV34t@Wwyvkya zgM?>kb$;f!H0kW@Ai+sUm_y&ct5=u$T#@iBt!;ijE*;x3J4kR666VnN@9JuUI!Jhy z)`lAlOfNo~f47t1BqYqC@86YISlq^!>ZK+Mo^+o~3p5S_9LFjlaMfn zuFvQD!MjH7l1@INw;czbrPZ$0F6n&vtcix>g9IlbVGdoN*WG9OI7oPw*5kt+!K;G_y-~kl-XF%%SV^y8BEWBs@!N%a^;SmMJ?(a1s*c z(DixUeWnf)o~3p1(C+DoA=yEKlaMfnuFvc4Gj)*gEUn$!bWcam%nlNqgoHVCeO`B; zse^=PX{}rBmX7^AJ4kR666VnLdEI@c4icWFb=n!-QuiKx%AZ{loP>lqbbVfTpQ(d{ zXK9VtTOP;N*+GJnkT8et*Vf%#mR5bc zZt0UD`MNg_(QvLM!AVG%L-%Xz?lX0e@GPybpXiZBFUt-RoP>lqbicOl zK2rw?&(iu}%Ux3Q_p^fpCm~@D-LI{?&(uM}v$W2byi5AWec3^RlaMfn?$_4cXX+r~ zSz1qju}ga3jO-x6Nl2JO_iO9!Gj)*gEUj<4)uelO$PN;mgoHVCzqal^QwIsp(z@i# zn)LRf{JVq%Cm~@D-LI{?&(uM}v$U@MTTS}=IoUyilaMfn?$_3LBdLRgXK77*y(VqA zQFf5vBqYqC`?dAmNa`TrSz7yiT$8%qm(NioI0*@J=<6~1ZX|V(@GPz2AJwGxduIm; zPC~*Qx?fx0jie3|o~5 zq5HM<-AL*n;aOUL8(Nckb;u49oP>lq${QELBg}N=D)H_I_r|`Ai+sUm_zq#=lektp7n9y98$Isg9IlbVGgeLk?<_7NjJ7k6BcI&2~I-799-=q;aOTsj%}Ha+_`6YeMN$k zkT3^V`$%|})`wfm!PPzzo~5$P|J zT#?`;B+S9pJ`$d#byJ&G>Hdqeg9IlbVGgeLk?<_77lyY=k5{vU1ScV34zBi*@GPzV z^IN667G(zsPC~*QT`b=g6JlaMe6SNlkKmevn*+oYQHvx5XDAz==#_L1-`t%sgzllsod=O_}KgoHV` z+DF2(v_5#MO)7e32MJC>!W>-fBjH(Eqwi^x4)`EnGmzjUB+S9pJ`$d#)p1grbnmIz zL4uQzFb7xrNO+c3`@U_`i5q1H2~I-799-=q;aOT6HgA(^U(VN}Bsd8Pb8xkfglB1` z`&UmhFUk%QoP>lqxY|d;v$Xs!?7!9rISC1K==!`~UFv;ppS7PVPMLp*T^o3oR>xjX z78lNG`0w)R&mcGn33KTByc|{LAmLeBd!F({F>hvekl-XF%%SV^dUdIfgM?>kZ9e1i zV)l*ML4uQzFo&+s>(!+?NO+dkJ}*C3w0!W{Z~j9y);gM?>kz4p|j#lSTWEuSkAoP>lqbbVg0 zE=5sC!n3rN*F9P+AD0~@I0*@J=zeXzx>N@V&(b>S*hh=c7G(zsPC~*Qy4t5#m+Bzl zSz243@M!Tv@59RHiUcPiVGiA|tyh=oAmLeBzhCxfvH1S%Ai+sUm_zq#>(!+?NO+dk z^$Q;@&RzHL@^O&hBqYo+Rn`af>QWsfJWK1wzV*dRW3qz;Cm~@Dz8jE)XKCI3VSVw_ zQ`td+laMfn?$?%AS?qC;@GPxkCRU4Ss~%B4S0p$I33KRvZN0kG=Zb`9Y2BF~D`s`e z4icP%ggJD-wq9L|qe8;7v=+2}yqJ7sc97sCB+Q}vwdGY7bCB>Xt$P>$BONSH(SYwOjeI!Jhy);$+IS+qPTJ4kR666VnT z+In@V4icWF^;O@eibuL+2MJC>!W?`zAPLXX`pc?M7ytM!A0H$*2?=xPer>(F)W<=> zv$Wp0g*uFNl2JO_iO9br8-D>mR8%X<`wT9mK`KG2?=xP`n+C`s)K}QX>ES_ zyyE^}^6y;|oP>lqbicN)PpE^0XKAhQ*1TflE3<lqbicN)HmHMyXKDTN^t@ubL$iYf zCm~@D-LI{y4eB7_Sz1Sqn^#QzE?-}f;3Oo>A!jxJdlMu)OY4wT=M}xDX9o#RLc$z; zHy{bm(%SFTr;84IX9o#RLc$!nUt3;fsnzF-glB18{n}H-gl5@6f|HOihwj(b)dqEt z@GLFA3$yz{5}bsDIdpwqcb}=_UvEw-T5ouUowq$p>**GgiVnY=UY^fMa1s*c(DixU zeWnf)o~5;9$McILmu3eEPC~*Qx<0R0m+BzlSz0gjpICJJIy*>k5)$Un^?BWWrVbLG zrS;_{=M^`u)bJcuDkL}w33KTByzV|z2MN#8y8D@Pi+^vC9V9pj33KTByzV|z2MN#8 z+NkZh#g7BBg9IlbVGdoN*WG98AmLeB&x|~$`1!W%Ai+sUm_yg+b@!P%NO+dk1xqIs zZ~T@WBsd8PbLicj?mklo3D43Rb>4*H=OfN6j}H=@goHWt?oM}~iK32#XK76@CKQ)G zo*g7O2?=xPer?@-rVbLGrPX$m3B_Nw{7d;bNN^Go=Ft7xy8BEWBs@#&r9Vw5{(5D0 zkl-XF%%S_Wb@!P%NO+dk%mXGAXZ)TWBsd8PbLf6;-F>DG5}u{C>&ywo`p2DBK360- z2?=xPer?@-rVbLGrPZ_TImL1H*+GJnkT8erQ}fRkCE;0Gy>B?D*mKpo@^O&hBqYqC z`?YoVnLZ8@o~5nYoP>lqbicOlK2rw?&(i9%(s{*(DLY7T5)$Un{o1lqbicOlK2rw?&(b<@*2Lob!?S|~Cm~@D-LI`zm+Bzl zSz4pUpI=NoEIUYW5)$Un{o1LB4+S{prkL9yA!*+GJnkT8et*Vf%<>LB4+T4M)aSoHoe zALk@E2?=xPer?@-rVbLGrFHLD7Z#&tX9o#RLc$z+cc;70)Iq|tv|c#yqGF#tvV#OC zAz==^yOZ;vIY@Yx*6e8)6%Txrf47t1BqYqC`?dAmNcuQPc$U_db1y2M9h)5_I0*@J z=zeW|H!W_C^Ti=bO4icWF z<#%CrKS+X;kT3^V`v%MyTfB136?SdlSz4>N7*o7`VZ(oKygtZDNSK4GeIz_f>yQDX ziytOr2MJC>!W>-fBjH(E>pd{CIR4!1Ai+sUn1ic*Bs@#&s5MV2)|;FiBsd8Pb8xkf zglB0jI%jzC#H{Qf!AVG%gR6ZcJWK1bKMpINtj`V-oP>lqxY|d;v$WP)Ftpg?LqOKbWILyB!%U0Gi5lHepH%%OL8d3}(CXK4-jeQ>cy_v|3SNl2JO@9y&Y zAPLXX`p3Az#Tp~Bg9IlbVGgeLk?<_7oBz+?V%6E%L4uQzFo(V#lh+4Hc$U^iyALiV zznvW~11ScV34zBi* z@GPx0+6^sE8!W>-fBjH(ELl%!NUj8&YNN^Go=HO}{3D45n^nx+Py6wU2~nX?^j^sl^J%WCsaOLc$z+cbC@(NqCmlde@#-eBCuWNN^Go=Fq#lygo?6 zv$US?czV(Cw|xE}!AVG%gR6ZcJWK0?0jC#Tp3M#toP>lq^!1p$K1jl|w2tq0dU4Z~ z>>$BONSK4GeIz_ftA2&ki>;2%4icP%ggLm{N5ZqT&Kh`HademLAi+sUn1ic*Bs@!N z%(x9AMiyIeY2MJC>!W>-fBjH(EzpOK^IOzWDAi+sU zn1ic*Bs@#Y@526TeUOuoFozz0dUdJyoZmftUD5oBJM22jv$UT3`PyQwISv24@%slk z2?=xP`n+CUs)K}QX??ZnwZ%5KWd{jPLc$z+{OQ%DI!Jhy)+>FlDQ4WB9V9pj33KTB zyk1?ZgM?>kE&I#W#liPy2MJC>!W_CjuUD7qAmLeB_s*SO{Pt{ikl-XF%+cuGfcRQY zOKX!ArWgPDBs)lO5)$U%y8%gfmez~?uPW+RyR*D*C&5Wbm_yg+<*2gfiiBrrUGm(!-xKS+3%*0{0Lin?R7g9IlbVGiA|tyh<#s3YN7TGwwgt=MO3 zc97sCB+Q}vwdGY7bCB>Xtv{|gtw_&h2MJC>!W_C^TdywlaggvVt=HO3E1vsLc97sC zB+Q}vwe{*!9V9$U>!viVD7L$+{JA2*Nl2JO_iO9br8-D>me%fQWsfJWH$B3Re~PP00=toP>lqbicM>$BONSH%kkI}13b&&8Ztpol&y}04~>>$BONSH%kkI}13aa2fn zme!f|R~J__ySx0kBEd;Wm_zq#>(!+?NO+dkVNq5HM<>QWsfJWK2H6|OJt z{5pTnNpKPp=HR;lNqCl4rw6Yu?sz>rNN^Go=HR;lNqCmlX@}lWY<^F6kl-XF%%S_W z>$BONSH(SYs;%F<{;r&T7SM}MsdQ|`5Z-plaMfn?$_4U27MeP zJWFfr%o)W;4`v4mPC~*Qx?fvY8`MFxa#6C_el( zU+F#`KVNqCml_|00UdoRrn5}bsD zId+iy!5hl^K@y&&b<%`ZY3!WrAi+sUnBzQIpFg79FG|9*w0eKhGHtRjJ4kR666UCr z@s=Ea6U+NS5}u_s`l6Pp!@shF1ScV3jwj^!>s;OslJG38 z?c23VH*I=-`TZclNl2JuS2_NsmiL1sJWFe%`&y;0`)3CUPC~*Qi{*asp7MT>glB0D zJF0aWGdw#;a1s*ckh5Bi994GRPQtUambYF#O*<_+NN^Go=8&_R-w%@TEUgnBTRm+* zK08Qo5)$V4NbU!(EAIzMc$U^aC$&jO4$2M^oP>lq^!Ssb%AP9{o~3p0+H0h%_s9+s zoP>lq!W?@1$$8KmBs@!N#a?TsGp^1K5}bsDIrQ}yIS<b}RCY4;*KNN^Go=8&^mRnCJodT&6&v$QViux5IFNxm*2!AVG%Lytebx>N@V z&(dnPux)zz%IqM)Nl2LEcsc$~Dff$#@GPx6C$vqE^vVtroP>lqFZUqg9IlbVGcQ~RpmTr4icWFHMwq$H00HMO-+K6kTA!$@_Nke<^3QD&(iX{ zFuNZl!AVG%W1*}M{;j+p+`rd0sejK)?7Zz+S}V=`b6S6khW}ovkl-XF%%R7hUR~<< zgM?>kjr*o+`f-EoAi+sUnB%FQ@AWvZTpuLiSz4>rbWKNWoE;=M2?=vNA?t%Tllqbq5%RhJzkI0*@JTqMWe{PKQ~glB0T@j{pM>ciPVf|HOi2k-7kc$U@yM|MebR+wB~ zi<00ZB+PM}9Dn~V*9S>>mR8NGUDBp~vx5XDAz==EJ!a?fevpJ`Y2E+wmg%J%vx5XD zAz=3bP1ScV34!yhENUlfa$EuEmXKC&5k1bQLLoO}9A0#*l z33JGGXsupds)K}QX)S(#%k;=y*+GJnkT8cHe|mMP4icWFHDseM>G8^C<>Mg1Nl2Ju zUpfA+DenhKc$U^vr*}!O_s$LyoP>lq-jU<)-12^qglB1O^lg_kb8>c&;3Oo>p|8j2 z)uldHBs@!N;h9^d&d+2A2~I-796!kMcWZe+NW!zUo?mb4bkDNvAi+sUn4^are>2Ma zK@y&&wa!ypr|()%DZl3=I0*@J=<%mlm-1XyNO+dkO=G&Ib=J=g5}bsDIr_-!F?w~W z4icWF^@l(GIo-ETc97sCB+Q|&$LQ6iI!Jhy)=zK#IlbR3J4kR666Vn3Pp>Z3LBg}N zRybpuwBD!rdrpFrkT8c_hgS9KQXM2bORLi#woSw4W(NsQLc$z!R;$W+&>SQ@OY8CJ z+oswxvV#OCAz=>Q-I4Gtt>;(UE*-sNc97sCB+MaawW^#4^><>0glB1ec+_@j$!GcZ zE(uOT!W?o|tIB!M93(tT>x3(}OX>3LAi+sUm_v_0y}H!LLBg}N?*7|$>DO-AL4uQz zFozz0avrq%K@y&&_1PWUrKcC=b1ex@Lc$#S{#{*d(8oc-v$S@av|T#z!t5ZyNl2JO zk3YS-R0j#q()xSP?b5zGWd{jPLc$#SdW^0%sDp%OX&t&`+tg!ezD^{;Nl2LEMLGU1 zFYgCQc$U_0qqj{XZp{u7oP>lq^z|6My41%(!n3rxf3{8fVq|uZ;3Oo>Q6sO%Tv6T+ zlJG1ozYDYbK@yyVggHK!`$2hK)E>tJo3%`r|9+mG?>tLu@L4U=zW;3a@0AJ(PC~*Q zdi?3tr9M|AJWK1nmz$?87GwtrPC~*Qyt^aeSz5z4Xr3;4J3B~l5)$Un*JE_GK_3SR z&(gYJ_-bj;7ui9AlaMfn9)EgusSXmJrB(OLs%f*96U*xo5}bsDIrQ}yIS-nHglB0T z)pgahVCU>0!AVG%gLii%JWH#3TeGy%*z6#|Nl2JOk3YS-)aQzXXKBst)+~MUPZNN^Go=8&_R-w%@TEUoF&R!L{JnN&VkBsd8PbLi(e$$3!E=XE4J zORLwztE7Jo$_^5ogoHWt_|vOPb&&8Zt(SjYC4Kjg>>$BONSH&{=XJF~9V9$UYxBdK zrDn}8D4#15oP>lqcy~v_v$W26wOM*&uk0YfNl2K3cXuQ_OKXoKS51f3Wd{jPLc$#X zlKVkbz80y?W7$E1laMfn9)Egusm~P&&(a!nc+1r1hU_50Nl2JO*XQMRQFD;+EUgQ^ zZJB0_%nlNqgoHVGcSpjrv^E{zDvjPDJ4kR666WCD9SP6U+WNCr>9T+2-&Z6!2?=xX z?v8|KX{8>m(*`rMg9IlbVGiEik?<_77ss?tV|!-@2~I-79D4le)usMik?<_7wI;Vt zUBAP5&( O!t8#K1ScV3j{ghhT8v!) literal 0 HcmV?d00001 diff --git a/examples/python3/actuators/mesh/Trompe07.stl b/examples/python3/actuators/mesh/Trompe07.stl new file mode 100644 index 0000000000000000000000000000000000000000..ea8ba2b3038eb4d66e5f0bcb52a0f05e22590638 GIT binary patch literal 3079184 zcmbrn3)pT|S?@hX`!w6SaTnIsHcl`Y$m*-x1#8SkTKYir#$sgb1;dgxTG0Vq(;K?3tiSJ$b zW6PIZ_YAk(a`TTZpL5&OveyC2hwQm*iBTHQx$6;&mmTzePw$S)4_-X|ufO8qYcAPm z@xjags^-JI^*63P?8|Ri+~-3#u6e2~?eDzgk`kWe+=&D4J#6{5uk7@=ly1c>`r(h* zy8Ps2N7bB+<|FZYvu7(!J9x ziC_7%S1gWuRSIw2a&k+Ip>gIz?z=qm;FOQQJ?p-fr_XvmRGUpc3PG>6zq;@8_1Ay8 zPb3K|E5=3Qwcok#^0JrTTI-`r&`U90ddW>QL|8}+!~HBDpXv~_h-(nHOBF37-u$oMS^Um_>(vJddL6v;`-_Xd)Jqj}J`DGioHI{teYBQJ zD5gof8r9E9&`WuWu`*S5Qc@orto?k!OYzpLhvipyecr=t)5$joT1Xu6qWdh*J~z?s zI|k8O_E^5>&NP-VrsNw$YpKMOFWO`I<%1GEPtc3~zYwF3yC_AqnCRz|vdY-FMhl75 z7Sg!l&KAF}Y%M{rFJE+5xn4Pu{~6b4A)$5^&5T-w?(wER)b@PYAt$^+Cq#a7M7gCLL_SE+OCwR#O-pdjz-gv{+!P;5|bMf=%BrnF4eAB<<8Z9I)d;Y5zZ+|j0 zGS(9GI_ZShEIzmMDKq(q`QY|n`Q^oT7iq5kiXZvq#o4z%sYB4Bc+dQ`H>RFP0^#@u(Fpch+yOVC0>Z7k;6 z^8~#nJ!(wcxW>9w-F)oqRL^WZtp+V5RR8~JzqwWtJ%?VKD_s(oUh>O}%RbnebG!GBtfqmE_hMt!9~OKaq1~AD&;P(sAt{Z_V3SC zx-mwnd}37Ncw96*AGDCr-DH0hB|$GAA5YgGEV6K?fzOUQD~*Z$NkB96KD>T*Zle=;GBu#nKWa@hZSRY!vay;SNE zQ=2MUNN6N_%{710(I7!DjaUEk)OEzD)~>q!^>aSwamnk@Po}V9iZYz0Dl8nZuBf76w-N2nBby!W%6oHH(ZvHm^wF*Mj3bX7a~d!O`p8B_8Nf))}Q z^Do?b^KMc_FOBmLdE8AMLY6yz^m@05_`mP-k&>!@D^aS#LP9Bg%hA_%G)T~ky}*aeJ0B~lih4@EL9nby=vwlRm;TjEsv<6WF||{T$T#b835}@zw#&Ha#lG35iv3w$F&eP{7h;S)7&#{)z5aN`xLU6h7XRU{ z7j;T^7^;PYN+CwnHdPwKqvz;K9eq$&)MyKZu)w&+xKuYWYE!!?e^{j0WH)k)m{inlDb-1sw{*((Wpz5C?1E`IpK!zxiyMauzSeCy&@ z4@q8(X+BjXhT;6hmg62@H8R%bgI>}&{=XbFLsUzRS9*87@^QN%=%xIfcF|)y1T8A7 ztv5c#y*8IB5~`b5@0sXnSw%kRrMB??*B#nPm0IFecR$)KYD*_yoWi=QMNF**EhMyV zbomPsU5HU_mqhC|S`Drv47I1VZ~FBT*OwptYb8}0^ZTiyg~TwNRq|I-0!QBXX;&!9l0o-{aMo|KJDQuWFQ>GcI|Z zcsY=)DNQ8d~DAxLqyYd zOR6*uMr+pyciM#y_nfP*^a)x>nEqnx&P10~Ss;zOHLmKV>u%_^geYiu!21&MMI41pFLvvhKts%36CP~x@@t0>F3gJn)mHkET8^|Y3I?~zIEjC{Ohp`$-L9<1X@UZ z@|q);zx%4sbjDq#rLVDM|Aniyp$MV+_^g8FcN7_pK-_%r% z2^!b--RIclsi&k}S|=@zEjj=A*Pp$7>VvQoupuJtZ+g|UmKT5J10JvFCRK%?g@ip7 znc06uf?j*R@Yv;h9`m;~A1NDFR;{JRd+I62&S)s-k&i#R?U>R^+7xC1`_H&W3yE)^ ze@tm_)qg!fuPs}SS$_8OsE?8lwnVnEOD|c>(wE9lf1rBDkhtaMsBw8X{Ppd%-35{LRrsoNI z@hZ_0!%%DLgo}?Z^~{=W30g?p@%W=l8=EKSrIMap&kb#_gCx`k`{OR-q8H~9o~kjW zP0x3?FSXlVyT{dbwF_TimU{9Hf)*0$E7$z??nVZBu`LvhQ90)*qnt;)Z25(-Ks#QM zP~AkH=84v;mdKR&@{M2f^1125PhGzIon9R0TjDQ% z>dDIkz8G^H+ZQw3?kQBNBDF2iS}JkO-#rB}RVI~g#6_Kz_zKPg+!_w?8Y4vH?FD0z5LR@E-n20cVFOP^_6>{2cqPI7Pb5!Qm+M3G}aTt zki66f`}t6MBVM)qNa1`wXd$6C-OmRJda(?1ru{!{S*h24?T}8n0ZIKl@Iysm1h^LpQ2k(BeWkkGqddOu5a z^^Yq~5cFajb7D+fTe>7TmzZiq>C$Vy?b1SmGlQaGDNCt}7EZ5jYj@(V%l2NziuC(- z?7fUtcJ0ir&*zGYY3TjBc=zqpQ+|9IYvy~t@W+?2`dJgvbcNu$1G>-LCb;si$x{N&@x7@r>(NI2OPe_VA{i`|k z-pkmxpq$5!gn5D%5-P)f&PmWqzxVS&3yDiF*}IfW%G zfM)u&)>I!+(!;Q>1~aC)Xtj_~&BjiiR)a+AweNDWug_D})_JYx6E1$}j0RiAUa#M$ zv`W@fn<`pJoOtLy%gN3fPZbGzvAq?IQKid%C$HEo#F{Nc(TMg#LVB^kXr7>#@)Uc& zoEQ@~t~LG6>OXdcwJoNqq*+F!N-ZV`_5VgALoGqCKe}zdHXkKbwCuajkC(FAT&hT% zwD|Ed+SOcmYsV-;EtPoH!~YR6nfsWKmY|p3agVpY-M0|5kkEVS@y>XP zJv7d~_@}qUTEQRgc=)z>I{c8uGmrd*x360_Fv#lT)|0oz6Vtap^cCCU`M0itF^6w8 zXd&^E#Y>A`OE4v8ee)-a#(b)1A@RM#_AjX|8l&<-V(QhqkD}K*FZqdW?cG+7NQ%iq zLNU!fvlNpEdTqP$rX!oRi4?WvgBB7hh5nN}67*83H_sEtBr>k4roy5cjCg(C(>*(Z z77}Vb{hX7a7h6xxwEt&ZqlLujr<}4a%5a{b7u$48u#LX?v=^4XLhY8Ig~XTs_{43o zLN`y)Ys;2j+}3|`ckgqbx-FhAf98%SY>VgAY}2kWCZ%yrXJy2bt;2u%_-*lwOsVZZ z1E7V3Qq_N^&y?JH^W#d|C#gz_TGt0j9QvF`&6E}6q8G<8kA6%dnpxKLs&wNSGV_-c zlt6D+Q6?l*oBe0VjEi3EH?0QiR;3#?sF-#?ijq*xMq6k#7#F?v7`APjtTc=o6FCB? zL?gExF;_wH~5Md#qwxBs(Un2;5NuxYTM@G_>Gb|)n>Hw@IGA?@Q_ZTau zL|917*9YUG7q4AYji@QT5fNe5tP^A6#x+_-rMC{t$fe35Eig^s_}L&3GG{o_n@7y`1RKkt=9>Q$!S(j z*cyGYkkBr@z6J?;Y0Qn2v^+WapK(onK+h`G54>O7nxw+I_h~c=K?@0uBU;Ow_9$Js zv5gKGk5V=%u-}*4C$l?z*&(Az41P@O=!HLZ9nuUy+AZ5h?3- zI*g@VYud6XPg)UIm}QuY$^X-qE(u+kwE|l-GL}wai&E6MuJu%TF@LQFEhMC&wcM!& z33{=fQU>hbQEgXc66K@&4VIhlB#E-hNlQdnNT@!v-(;F9mOH&RSGpur|JrXb)nHuo zV$GJEEAwltDV46)&=oIZ%9&1J)1yeJe`w8q<5ba$y{pwwiE4jTitAGg-;ZUf(o>Os zuWc=rP%o%4WtCAm*WFdLa6QwAman;0j2LaIXd$7eAWeN({Q67JeIl;b%kJ6P2NRH6 zVpvG%xykO^6}{U2p9MTsEE5qiezavsf|i!JWoEo0p?t)srgDq%u_~ynXi?q7h{~8+ zf)*0G3+|5$Boqa|&^k_>S)wPYF{^0_J@XEWp4P`1GFm<9pY@`rr{TqT^(3`V z&_ZGu_FXpTEsZH{+V}e7B_B+o)(Rs}?pp|2NbrQu6ubRvl->oXanVcKan49f&_Y7b z-uq{AFdy=Yvx%6(qM?NOE{muS5_Gj(c)2p?+Xc(5^B5s6M+~Pz0~sK1fr4; zOIcd;iu9`OhS%oGiiG-2ld6()#?^Y&{FPK$Ag#DZnUK&3UdydAEzx?_Qg{C`QF>Zi z%S2;Ilmg4JDy&Zx35{d@R>HXG#ZkM}poN4+)M&@^1iiXfgE8f!?j+@|*|bL|c5GIa z*o%`aBs4$OY=1g$XI%8s@9{jSDkxR7kkGw(|A`j~dg=FgN;TC83yHL|Dm{~%C+H=O zcn0LeX#d*(Qa-{$LVLgB8K4vSpO&DPcBDm2g>a2^XO-F>xU^??v*)A^g;3v&XJ@Wq z@uz$+E_!YKi92nEysOr^2>Y{l$zUO&aKFxFiTb$DC0|=S@rG}Byc-h{7YUL2|EDdH zanXyZO&Rciee}^ipq&71ca1umSf}eMtY-s}+Tct_~{+oyO_HsW}vP4-u{J^Ug`yFN{HCsN0;VO&i`>lp$rPW}( z=e+T%#bM9-K_x6j`Wx5IK6ka){<(j4i%y-5+bsFcq<(ON2T(U-1S-0_;bJ2gmxUg|5qa7OPMMS^`ozt8umYN@?Qz3ch^ zbni^6f}q!=N96)*d(?aG++nTcpC-MlEnW5^5??-O$4t&i(5r37RYmU!*M30a%!6;3 zsSgsZ*IfT#O{LK;<-DyYrivC4D%}{Bs=r!033|2TV`fGX9Bb9C-f_+U_WIadDbkf4|9 zKdwG4q4DEcABpt-xm|rym@&0PYpI0B${JH;+Emd?<8dt!BgRD8+62;@`bWBow%T(V zBy_cFu7eqBQ$?@#dPNOdNa$+UA4^EIUhA%dB~@ypF}qv;C7PHS)HJEi**{3!{Pk~tzx;vk^fP}}{)H-5jP!Bo*pE&t@-=@F{IT8bYksnST) z&qrz{>0Kg?i8nmv3Qvhf)Z@;4f19dNtz;NJYL?60qE@Ld9%)ol&3^ON_qBu-bDG12 zg@mp|YG=)u=o*ZRUTO=G!cv1y&_W{B|GIp5s#qo(=c8q`Wmr^l|A^8hk;*Ey%IY6I zDhPV1q@(2*Vidu0m&UaheZb3y^;8H8q+T0)d`KvN2fzJ;ZRt*k*6Txyzkk7%m9P}) zFI{my_PwxNU%YgkSHEv+(23Sk3H6(Psz}g_wdu*p|BP$2kWdefa+@dUHQ!1!^FHp( z)Yo){i+;DcRzgD8^L{^PT&-8_!EHX+el&ZD5tT8u1T7>q_l@2>PtZ#-MSGhP)l%b? zUiANYf?gbnT7utKODRcDrcOP@MxpL|skD$#IQFfz8taMhlD5XLX=|s2@g_aI&zXhN zcj6*0di~fR{K?|-f9bu|NDB$g8Jk{PG)T}(ZLId@a9`ig*&lVqdF->(INz2PEhKdJ zs#!o&R--gXv|j3I>olB5eK1=Pug7oyf1_c^(>1EbMKAToem-a+q0vqGnre`sSGROM zRkV=MHBe*ORD%S)+M2b<^WV7UPtkIj=$Tm5fu1?Vl_NNa=VMP# z(;MV^&R9pj%B0mLSPG$MW&Jv5T=dfKlNvOsq!AVpdY0I4yIj@h9ypCFu?kpoAq`qc za5vpNK`+G=E2dK-EF=_;-!~@0YjP5F#?rZ*ajq-l)yaSTvsksRrFAIvPOXq>-Am#5 zl?JT=hnIFK1g&TK{rhvR6l+yU@$$*PV$xbwXJmkdg!HufSBNoX-M;fY1e?(ItyVb(%-nI^oB+Gh=wZ zCukv|(w)?~iKY68e9%jE6D_7q6)mdsC?9IK1T7@g-lA^i33_onF2tyOu>C0K+A9^M z8zV*`EYP+@5-N4=<|=h=@$0W8=r!LGX(6Gu5GhQtr+?d3WO}g|xbGMQ`-ECz^jc~s z-ymoqp_U)lu6cr9yb`qpziiE&#G3o`=Owg|(5!a%1ichf%pclR(LzGu%@N_HnELIC z7RIaa=7{i8Owl)|`3MW+RXBd%mQ zDW<5KHXpQ*P%UVXye9WJW8xAKEranY9KR>uIU>BI(X{qPBP@(p;rM;35f*y!KCvZeAu+!r zo&>$R``b;-zV2vWkBfUJoyQTgGrjE=ZJ|w-PJN0Qi%vL+xsTrY>l2JuXS>AAVqSw5 z5<0IYW;Jc9NYG2?AK^PHj-+EkICm(F~NGHeN*mK60tTIXOz z-LwQPBy@^alypl_UFXL{`H*f2T1e<*n0|ebpw}c-V^SK|R8w&Wp&E?Yl4>^ke48qk zmClKZ`!i~{1T7@|%&6`iBnf)y_kOBqAtAlE$DO7s;-Z)G7f%ohF{;eojZm(rr^wRJBYZNUcq!;7LG*uB7y?8}!2|nN9 zGY8%EMNBP03klx0&lB`gOtFh(N`!@k!twjYM0m9)5?5wiqlNMEwBX`Dsz>p(*>o0f zI)_~EF2#-;C(K)aHtU0hg!CFB0qY2QDW=F%iaa4nBP=ACryP9(Jyj$kERCklM{0zH z@hTj@Pc_0qFKNV>pOQn3u#iwVexGWDg}UMaP`HF{bYZ_?Wg5i5U+DOTvFsR|3@RXBcc35}Lv(KCI0rCY5}D+2n~ z@U$iBX}`YlD@%Iz_Hqv^ra0wjUW4&&OhjBHltO*Oc$zB4MK7kdO%>Cw=ZQLBMDa4F zmY{`%o?q&0lZ{hFFFh~SSAD01o=rzwdg>gh(zp^O(x!?Q5^1$B)y+IXFRfrj&9;Qr zxuRuAFItRN%=)c_77|QttFfMl+)BG&=d>{1Zazj`IhhZ6>3i|21E#P|6)hxGZu-Lf zv<6AgOLe2~tWOC&`PT_LvS780uelTLU|rzNuO(o1dZ6+iOJ zm9P})FRhG*MRgPLZmyM((D)d6O0lPZ+jd1Sw$MV1N)^+q65akQDecT(AuQ0A6$#bN zrI++_&ba8cxtx(f?xJfYGaPl610%ee0TQ*y%bZ-QKlMU zA)#>mzA+JAEcGc7t)1~I9KUZ&gqJj8be$4mVY~{*?;8{0b>O{+E#LN)ot^Kc(!zKZ zj`N;djrBx$@igt0poQ`3nU9{)Os`QS=%r^&dU7-++ApKmZ=p|COmfoN^$&hMT|2Ad zj;zfG-@89FlLPFuq5#gnn;_hXds<1F#h2!^)iSUv}+`UYRurOYQ-e!pCgNiBo$~0ABVY~{*?;8{0C5`ASQz9&kSK;`5VN(%9EvT=dck zW>e>5Qc6#@b6~Y2(go{*>P*3YW%V1pe(zr5t zUgD{uMdMXGxnWH6sUo4VveB^k_1ETuUTo9JH~rhTb`l!3`#EP^^wL!{O1jn1-U2<{ zPWR#U6jI&Y$4X;Mw3bS6fATy*FU8cqH=u=t!kZ()OEJZ)f10YWFkXe@_l=40l19w> zr$ks7ufp;B#zc5YBWC?mA}owo;rM-HBD|y#v;HX&7RIY^{Jt>}UMU~Fdjnb+Z_?Wg z5qA@cDMpNGs=~r}6^`FGCc;Y^ag~@7VPU)q$L|{x;U$fjWlo8(FkXe@_l=3_HTRWD zofhi*d~CkUc(vC@SGMVsJI$N5)+Ni9EiYea6-!~=@AStKT1aRd+dV-q#T0$M%{eV3 z6y6*WUWzID{8S?>j920KePbfLq!E37N`!^+DjdIWOoW#-qR&r>urOYQ}Uebs@KPAG#comM{ zHzvYM8nw??M(3(k3*%LIb3}OQ4qSIh(~*G|#;f}q-HA;JzBSI%1T+#wxz$`~enkrj zy_K?if?kR#%5AC<77_}_?;8{0#SwK%M2Rw9h2!^)iSUw!X0X%JrG@b-+$VUd0#7Co z(Jx(ENa#I{-4pauOi^xa&S@c`@aBl{QcO{9Q;o1NUWMcLjfwD*M!$4vVY~|W39XXt zzyH7Fx;=04%>D27uvQvEuT52Jsf3=3?w+8RV(O=g77_|?jtDQE?w~J%P1`Olj924W z&~461(CZEFe#PSVUi^f%e~cPSXdz+WHd*+$&}>%Y8s@FPbc%<6_0%k?wfJVO-VD^2 zN~igtg@oEd&?$2N*EC4bOYbh~+onZh41yLC`nrz3e^`hFn1;S^qc6(IqVMDAdvpqu z&d&ZHT|a7iN$A@=`W9ZJF{-TeMHPK5QWkxWMc+(SxZB#D&=-L8t;tA9)U)ytF_ly~ zL5ortgi0jzT0%M3*Voo-C{OwZrG77j1ytwtTk4t>>j_Bm+RQhkNpL(~uTkToSNAK& zqf$i+36?^uL4sba*+RGmEhO|!q&y; zU*)#jqf95A78-qmg!1QK3y#)q@$0W8=*9X^zUkjoAE7})<5;9{o}gE^*XC5!GSN4f zqMliXtp+V5^ev%iWAg;P^d+Kbp@kS#R(hK>#uB|{8so?2>Vri3+R-o8wrlb0FMaPW z#zeJteZ4pOM=kZ_oe0(xiS!jUXk@6ZL3(w^#8IhYdR11Ds?Ft`gz6^pS97txCDM!6 zm6l*lsdVG2#W`v~i(YJRZK~Q+TI(s2im5*fZ!MM3 z+-~;-y%bZ-uiI47LPFuq5#gnn`mq-s>om8uJlzNMtZ zpAK5QN$=)X!wFiH!XTt~(UL`#4y~?%F4c< zInf|NFP7m{qn3M(S9+Jd{MH$bAn3)KEgGZpp_5b8zm?vX?qy$W8B&Rs6CNk|poPT2 zJHNl^mo5oz=9N1)~=GJoZf5kwq=;gN&m*^lS-F_ zMxuVI7+336OWGAi|JO9MZ^%#Zw3KKElHQ(EZZ*U4bC{TOqwHF1UcOtzETaA7(@gZ| z42ml(B($F>VoK?WRFR<9{Jew~653DZ>(R`I$&4#nv=`1-s?CcrwW*?og!aPe4ZCS8 zAwe(gh0|MgQ-T)l*3p}E@?uQ$sUo4>L3)>Ms=>JEr9De}e{D)=FO=RolSN*7pDa=} zX(e8|(g+I)>FEu$sRk{|hu-hoyaoxCq2BeIYA{vwQr+l{z$rnC>Rj)pZa!5c)ZX-- zYS9=|J&r4;ieBA5=%q^w3AOy_!7298AVDwofA<}O;Ao&-9g%j%lzfArg@kr>M7g=| z*dyq5(my|GamFD>)v`)}^;%j;XmzzVa92SWb}tXI#-j zqU?q-dY+&cN7od2;>H!zs~yGBKbXH(gBB9nOFij>qsBxM^y1xXt3faA>W-0No}h)q zsi(ZCj4`bS33~B9x+Q2KA-(2~y5-1bDtRPXAIL85>u$sQ$IPKk9tUB@$|DLXi+}2(>rn= zF|`C!MM7n$z2W_wM_lycDB&7oQc8Cd(Q`E7M89KCE2%OnT{%O8gvPFBWXM=c&`a0d z7>Qa9jnvUHH10-Qdd^*sSiJ0@_t%_Tiu53dfjc9$7(k-c?g@kH0T7Gu+|BNdV^wPDx-=k>JoFRHD%dpj;g@j`2k0m7N#TMFX zsMq@5W2+qRWg@uIlDqYf*Qxycgl&2dG=xH#wdtdS9#jE#x%zVyGNUwrH0u2()TTh6z4>K|WH)z3L|I}DXjOuu@_ zVI2(;^iryR_`@DSi}JDM#-I6jq>6;f?VhuLb~mY_SGNXpOFV0F)!nI8>uu?1;Tj*C zwrk${Q`ZapQFa3@&<>(XGv=S1- zaC+(U^8~%5(X@79qy3+?_8ONoVqEDGf;?3b7YXIBKVC5|dZ`^x#zapQE$SaJ?lLAz zO!;e5MM8Zuu2;p~0xi*c)e)m5j9Q$$<4&L5sU6>Y(zpK|Gh`CF+TH!A@6>r>7D`u6 z-*s&*PNSOd#%2w8mJN+zCv`2Kly;k?D-@B`YFhB4K7-lx4T-uYB9B^r0P zKi~(R_Ki~&=_TP;xSd0rD$7f{at1*!T~{9bfctd_T6B#%=#=}r*XB}1!mo)tAK1}o z=3m0m2>AlCFc>-e5y#OZjQNb zzm5iTNH4X8+QzC%+WX;W1*s)k|2XZ!hkLvl+b5|SRp+#jP*2;sGtpIHJwY#x+M!nn z*U{Egk64E~N z9qaaZd0CO5*W12zwEd2g~VN#EtcB7KFtS-*6V3AyTXQ{T1Z@a z$zn>3skK*vUh_Gpg@p9Pad%u3U)XwrL@$K`EDV9IF?U)kpd~2tL#J>9+Tk_QAgGB3f!n6iG=k`>s zSV)|-ICiFgkf7I|FFbap26aMg>~2%}=zRc{kIGGN!c5DGqrnLmAHCF`b9pg;^EoFm z4BPD+z=@tG=ymmJ+lyXHFo&m}a%?F#mWUH$;&e5rrAtCF^?NM|dVT!s&t5+DLA|}T zw2)BU^v6UJ^iuunZKP>^(4v+YwZ@p*vZ95AdO_6xJVCE5TaH=keUNFYcm+^@jD5%) zA6pGtNU(*@6ZFz3(Jw1nNX)l(wzx-pdiy4>gX{++R910CZSz5bUL2KLg5@p^y@#VZ zV9mA!EhLmby?ZyUK@zRkcKe<vri`Ud9zIB!=sKNGROA z1tA&NSWkr4F@N`z<<}1BX_T|Bt!3!DLgCfbkj#n}62oBou!f!n33_duDnC`jQl%8e zuKRNGxc#n7``@Tk(W3VoqSn$o4eRQ|uyI8TiD7)=v<4>xy;z2xqWn+Nh&mvlFE#b+ zoN>{sEomhuiKLvz$XUMBWaXpxLgK3JzJ;Jy`7%_GND@|7jElr;_ueuy-z7mW{T{WM zqfd!*jj)gyhAp^KN0L;7w1|jV=H@kmP@ekt28@ed&<;=A)&s~%Przt!8f2@_D6g57+`{b08Nm&&QT1aTTI^c`F ze2{3pG$y7}Z&M{Ap0~f`x@Ro)Hkz)l`n~^794#a?GthU$r&nhZ^wRH9v(r?Cg#@qj z^8~%5QR)du+jdE44&TffGSw3F;#>j})^_zaVC*o|+kmkrS^M7Ws#9gs9{RA5P)z-u zfQ*Y?`V#GAC!k44kv}KK z#EmPy0myh6)4T==Y4mf>xah?c77a_;xMG>;3v;mtl4V#33$*n?Lf^;j?}21o^wL** zW0!8x@Kmurm~)-g5pOHB1T7?}?S#dzKV740T=de39{qP3hT(waL-t&Ho$DK;v0GVR z3~hEtCkfM_MeQnfU^Axd?Eg`!ss;&_NPk~AiPmf1WxN-XB2P-1=|8l@rEf4ts#FTG z3%S)u2VKG6=QfNgp&c%`78T^wKwx`~932 zeG@sx5^B$Q1id&CwS=C7>A6*!e|&1;&&hmlXiv5E{LI6d8CBMl$8^$MJF$$cvVl4LUSyCTEVJu(MwMsCpkB6T+yPZXi-*-sR%eh3kf}m zjM|(h=%uHR(PCOcYfhTAst){_vCSwI*3)Or6`LCLRH>fzY*ZG~s#!f*of5Q=@b{kA zw|3VcK`+&R?Kd?ixu39JXHnNAk$7lJx$LPr#UAZ#|nbQu@DIJ&kP>^XXJ8e=f~W=qgQLQie`sUkryJ@f7NLBHqA zJyl+Mj;!3WW<6D7N?W>qM2l0-^{iS1OTEnpEhJRZp*K&^i{na5Fzw2Dq-v6njJ0i- zgi1Q{*J>~>da6wO}R5WeZsC4#DSV*w- zc&ds99XTO#A47h7nn!S^6-uCs{yHtoxpyE@ZS37wu4CDLjzE_!KC zQD1`=66^)71_^p;w^(0;77`qlipHoq*ZGCI7OFMqWWre0f5_sQNB+XwdndQ(w9fF- zIh;Z3J+gRG>>3uo{>GK!)tD{~>1ni9c-xIP9ob)fWxP6PP}g1&6OANc8nlq`lMwUi zC)wHm(-QRZ_u+w^oA$y;M(8 z>Mg;v>-5V=)qFl^A>rp}c1xE8z2@5$EhMBD_21@$1ijd%TS6x~>bjvi(20(^>O_4s zZ8u|WD=8(#WE7CN&FCnEk)a2Q4I2AAJp4RD+Rr#x$=%LM30g=fwL!P3B0(=d!Q7q}m$sX+aYYLWg(oXmo~rdkcDVr9!XNFT8o|mB|wEBZO&=Y z%1@LiV`>RnNNBAnYIB~Tm)cdd1t-SDjVsoz>Lb$5w$N(OLP9;NUsfdOrT!Ro(`v9E zC?B<+Yfozl_9zl6w|=`KK`-s_h@RGJ&_Y5r8!dmHpci{^OR%OiGQ`;{YzylMv}zI> zyW-rJd7|~oUm3J<%!x5^=_zNNC!=SU5ie`D)u4rhR>mVw^8~#(jum3mSi%uNUNLe? zJI4G%SfCw!NJy_gQZugBYcnm8gi4`aOKQ5(Zjrctv|jm}Hc=mfM&(26b8+9VRfc#{ zz2b0&KVcI$`=6H5)HGp?Vq@Fv31MJ%bkS6QBO%g?mZ&B%69^( z;RG#=mtQU@8j|t3XvC`%)A#wtALo{#72XI}CaqeArFt%agy*Td7_vdm;Dbl}o0_MA}U7Y+ozn?Ant0b0N-2wE=Y8b9xTrs}Ki8BwrVR8EL z|J}p$1T7@Ke9(@??a%lhHC1Cu*|=hQ&w1ljiyIzug?ll7$u|gENId+&s}|q9^?g+% zV|w;l%bi~Oy`OVhNDRYOR=StZXwm*~qM_}<+Rs=+89)qj+9oAY6)wN}1LvtbRg zK1jU&`s)^-_(rsas?zqs)~mLK>aTW{Qk8n=-z=|P45wa~a%=zf|DQc-6u~l44Swe8 zKX8Jj-fGZ7BDJ2&c2m0aVo4VbPgPs)A1W=M+J&${YFD++D{;ZmAD$^)#zn8TZz}Ti zzj1Z**RLrfwTO>>FO4e)pK(=t8hasVA@O5>@F$DQ|E2dP5_{)+?%ZK5Je4S0kEN&l zwXKB2+2^iGZ5DS6v;@7{alSHknl7#YB)+<9HPfRs;>1|1tDDMBGYjRfKZ?>qLg(D8 z9H;XV67))?&>MG|DvhXdWuRWox5}!uR6_kR>febmaV^n!&Gtd{(&(KeG)g@7+1+a` zh}KJ^5(uTr{x`0g(ZI*9`9z{d}~H=WK5+(ON2@ zn3^lj82KPUFSeLggBB8M`EgC0C+O8}iIy^*kz(baSBo{bQYzKLH7doE;#Pwe67ypT z33}=G-OqhU%-0~}YQ5^b%kyEm)?b@*rcilmz7jJ!U<55BlJ>gY39hl8i1iPRBh6Q0 ziUuu=S8ZCe%QE^Df))}A$C^&cLHalKsECVR>YJL07mbXikvi6()RsPS;Sb$QBi|v{ z{#%Doyg{fwe)0mlYw@f8hZY}Pi?9idkt$u0BVJw44|~=RJYL3>6XgF%*V@n^p}EBK z|LNY{q>5fFg{elAA_>j{sgJf*S1;CPNtFfC)wzxUl~4~p;z2zP#zn9BR>GRnoZ(p? zNuvSVLYpdDNN6_jR=dPjMrT!IpYl+%@t^KYVCDg|HyDaFX zy|mgbJ4<+~7#9ik0^gl$dTl;P&`TvUNmbFPD{lF#^%k%6wD);B?ova06Sd<|URuf0 z-o+`wlxUxGnQ0q=OpN*-Pci1PK=35?~+9hRX5tV9raO5q^hKmIxH=5 z%R;+or#V+y1)&xbUfR2>owE&LDNAqgL@8>WP`gYcRr56%7826Xj?+fNvXk-=1ijd% zJ>Qlh{f#Ttv-WT*F6}7QZm>vI6>-sv?QNMcPFiS(9OudJvp zB1SmoZ>kY3k%Us)Z;6bHUQF#&BWjR@c1HJm6yu^7%dpj8nW#RZB{HU#poN6$e=@=u zny$5x4|=hu6^&5@&uQ0PSnLGb+}Y726b|j8;i+O=^wRJ1L|8~nc4kUwR6ZCNz25Nd zS1f+-#px<4XL;*yTEC^KIb~MLtlrI7xR=8);ZgCum0iN0A?a-Ngc)*!uf zc8R_SH6?WVNLW;&5ij=vwK=DSgz6^p)DpC)&Z865gi1l*jq8_H#6>T*=~jal5~`a>;XFYv zjxmK8l@C3Q&=Yi}S5HEsHZ_Zia3L&^W=mlqp>X7HV}tyg{1 zrf4{!=OwYDQ7MV~*PU>L3t@qDw;dJ|3P;UuOoW#-B0MF+!gv*qn%$TPFKI-0N`!^+ zDjYStF%e$Ui13sM3*(*KpJ%LnmeG3E=Ve7>RDEbICH7ge)^wi`^;8H8wEM_NC>*7} zF%e$Ui13sM3*%KdN_}G@yrdD~DG?UNt8kS1#zc7Wo@z>j7vohpdfLWBcu6C|Qz9&k zck)i$Xq^2o)nE|x;+D68LV{j;(<$abt}!O1aizD7A|-ln zDblXC7Io96iWU-jpQT?`B=qg`sAv5ieRHZ277}_RCFbz+1ikd0%;er+RNJLRX^(r3 z&83QjN+Ird=2Jy4mHOm9%2P#)-qMPDwaul9gx++FyT18U(MxY;_Gf)+OOX<_#7Mi^ zThvplK?@1>f__<%pqF}A)J>~Fi+XL;Gh=EAT1aTb=(j5p^x~-0YOt^AeZja(VJ~P2 zT1e=v(EeQ!33{mpL(etFq%^MBJJs@IgkwzesUo4?6(jgOK`-`TC&t8$E2dX1F~+FP zrHX`Fet%44T=e3|SMp&gOR0)}pwf-IEydJt?X-|kZAMH*!vgJl^z>qTYYAFNsJ-?3 zISG2PH@6ymKb!9*^IcLW#>BO6dXt!c1C(*mtNSjQ$&4#nNGRN|kM%@&ZSHQH@haTE z4l*u!ZSFY(35EN6gc%pT^!q#!77_~g_c}8!dg=FhA}l24zkQ`zecOUxag(d=ZUb8P&oE$Of^V^moy^W5<1Z#-d^TY z18KxvMoZ8_Lg8rn8x!HBm?AtS!oqkJ?)MMIMKAq6PlSbp!qKLusUi_x(unYs2n*v? zINJ2aM0iOf!c!tFj5q1^+AiawSIWm65v`qs!qMKQsUi_x(unYs2n*v?xZide7rpd* zpWtkXS883mqGsDv(LzGusM(E)@KQ_>o)TeUyb4FnZcK!iG$K4D!oqlyUa!s>7rjzG z=7^|s5(-DnPE$o9yrdD~DG?UNt8l;085h0u`-B)Z1Mu%}*tn=?$Xb2VxdZX^d_q|A z($yd=B(#pFa}N4X&x4?s)(Um{!j#a{^Ef|ED=|9HLSAWYYQIWY9`rY^(u!-cNFxYc z4I-xGoBmDt2nz}2NvB~nsTxBg(yLWcojW0~`6~`BB($2L6IU7y&j$&5X)Q#jtTcqD ziWaSf=wy}6r;3EuLUa~OqcKSpz0$f-k5H{eYtXt{v@6wYv;~X0{G~Oou#oUmm2(R% z?iOeXda?CPiKufD(wo$I(FlTGY?ZAB+o)DwbqbA2baSa9p_N~qFEgzV#zil!P3nA^ zDZ%fOsg1?BqL?Dw=7SazY@r(yQJab>!c!tFjCa0WF)n&(#jM|UY0+9*^bf`~pDGe6 z-ANxbv~7v>Qr-0XIcrK9Itgg=t%QW~r@PBi=VQuEN>#L7da0!2_crIWkVq?-Jq=nk zGDJ!k)4T==jYLrj^8~##@-?k}Ox(DlMWbl+qRpj>ghuV?!Sku27q3Ju!PcOD9@me} zwL}scW8zBGYA`N(aXfAbty)AMR5)6O)+yrmmY`)l5%fGEI=r-E*4LnAJrQ)PK|QF-lW&-AB>A$DIar0^e7SvN1L9eibQxxBf?W6ER0v-=mi@S;U$d-Pl>QF z-fz9>*B7T<`0%!W7^?kOH7veHotChc) zh4E=iA&N%y4-#6njv3%QK`*VV_3tLMej4|$T78YDAA0T+`70Wu^1-;Yb{F?Go683Y ztrf;SRnf3OT8WFC(@Uj0xmWX4(UMkQ)3b%mrHX{s@g^FRRMD&ZjLZpINazV`Kj$Rq zrS-umX^Xo2*}ECAXjMPznK2c23#4<;qjX7Vg}>jf7#F>?+8^zBod()c+7pnTMkuC9 zyDF&)3km7<@1qzOy_Bc8Z);OUi^?tT0U1+E&_Y6W)7*28iA$v$`Jfj^j8=md5^6D% zvBc2SKSG0E9En_GOiF3}JmON1inLQZ`36A?3H9J8w|RnI8Znys7(;^=jaO06)SlNM zk@o)do_H}XdTBh4(atqWs%X)ki5MRl(|oE(XqSc74$BjkjI}jLFKI;IoN9!Hg!JMW z={!L%UWrwmvPaHSG!i@-6y|w zaoRpW$mGv_Hz>S($ltR zJ*@^UB+@z3z3=>xpqEa!o_w`u)b&HV{q*Ef>DAmfa;|<8;WkyYkWjdvkM%@&v2RW_ z!i(`LJU{x72rp?wc&ZT=#;b7LCvHrHmoy?gCBnjZ6^{GFjfwD*MuewCSQxLuai6#` z5nj@W@RSG(<4t-~R(^QcNFKI-0N`!^+DjfHT8x!FrjR;SP zurOYQ`#Xdf7rpfRJP{TW+KHyR%FpWSFO@0to!Kx$Uw__ zqW@)55(BbWf`l#zcJM*f*@cf6lo(q*lHxwrjub{K`}b+wa5hH~0Oe z)u}K2f{2lp61JAe?^QL#P`oTIdX=zieD_bEv-*e6?PX_$4>As@a^ULs?|Qmx&{D#tQNC(6A!z9m zMi0Z=zVM*cJ_r0~*C0{C?sdY#OT{%v=zGgy=@L%w`O3R@Y<= zmaIp@HU9Fcf3xEm_nhV$Bud!4%KK5S0b=NSO$fDgwRqJz<0@ez_&(M!fEbFGsne^3 zJylnpea#KO|9}0aYtT}{rlGesEe%8JgCK_D<#Ev~heP9OS;Hcsr4sG?qo&a%=vBh5 zVL3l4m(@T^30pq+R;!m)m!MY(yM~P;M`=7!QP5Jtrok^b4Z|GKdgZV7xQ2}*YZ@J- zQM}wzzwN`l^}{en(5r+!rvGyFp=;+}x#k+Ql(6Na?5&>=v~&rhhv6?i`qZ`eJo;x{ zgG33NSNX<_Yjg>EG3&HM#37ZDL`Qz7* zE>Aep*3@&=s%R-;)3EW;_ETG*^za=UB3bO=w?7yj$nYhSwk@173dLUp5lU*;vM!3jaH5_XN;uAHEygiRy0vA92eBud!4-nV11)QPc4g9I&I!ZrTFM$jwLQ=EZB37gk9|6yS# zW_>zqkf5bYxW*nIdd}Ld=_$@YqJ+)s#6y=$o$Q(NL4uYp;ToT}vFbnmh(E;{NR+U7 z={u@AZ!~F;pruQ=#yxfi`TylRND?J%Ui#XqPDD)_BxvapuJIfj-9DA?gh`aJdEN2& zqnA1{HffNcrAxTRqs~3|sIR7{9|MUJHm?&dK6nvGC}H#3cb{W1UXh@sOSp!OaH~8fjwDLhyiQsi zi*c6(EnUJjY@}Z0v3(>_!sfN-3y;P1g9I&I!ZqxQv&z?~kwgib*Quu*TdrNhK!TPo zK@ERuK%#_mKJ;yXG?ruyClqg3x`b=wocoN7Lz14X^^0$OSndEi9SOnQNre>R;jbylLiS|x`b=w9_1P&O4z*AyL1A4(jY-gmvD_d zGPnkb5;iZ568@d?U7CxMpruQ=Mjqi@gG33Nmqt6CMW6CPf|f4f8hNC44H6}6UK+J^ z>VMK8K}(l#jeNy%4H6~nUfb=&-q0YSD_K~&L}=(*>l!3V*t~QVt@+5;S|?gd)+6B> zmUGP+CPbmlOS6GmA0%k$60Tu2sJV}8kSJmE(yXSoD-yJH3D>Zes5zW#kSJmE((J7E z4-&L=3D>Y5rMakUkSJmE(k!#~a}u<43D>ZZL33)?AW_2RrP*>FuSn3+C0xTsINclg zm`I|8%}cZXI_{F7rAxSmjnulwaSakBY+ky1iL1mgkf5bYxJJJ7@+%IB5;m`L7q&~| z6$x6pglk-8{qL~fNcV%oum#uD95%1l?!9Gs{`GOMMxwQJ2-mpV%IX7ojh;jao7WSL z-?IGOSH(RJ30k^@Yusja{=|GgNTP(zE1f{}xjZJ4pruQ=#ueg&a zVe>lX@1BBukZ3JAB_v#9FS{T7S}LoNLVpI=UBWeL*+6GsvyY+j$d=17dYBxvap zuJO0lrmjuT`bH8ZY+i5s){(e=kf5bYxQ1PER{0t=k|<&KdK#`>B!;0{x&$@+T1%pY zb3V>GI_}l7h7*dnTCyGq*T^~dIRl9jHZPUJneT{u91^s23D?Lq=o%zS*t}A0#=M;b zEnUJja!d3%9ElP(FSW`yTy#_JA0%k$60VW^plgsQVe?Y&y7PHAwtdhETDpX5u0EkbB3;RnrAs)Subio@2F8`c=B4Xy%?F9r(jiGUi=3EVYE(9$Jb<5%o?%opo0rZ%tNok=EnUJjG(*l~$w;Dv%}Xby`Ik0!Y1}12OP6pB8{t-YOdLs+uzBeu zwmR;TpruQ=hKY60~#)*T^HBYmg{m^U`SNUv_W}60~#)*T^HaYmg{m^U|p8U#M^m60~#) z*T`2K*C0{C=B2BTe?!AHNYK(HLPOVD*C0{C=B2A>%}2i0Izda9aE&|zm=J|FFUhIC0xTs2F$ppT zmM-BMHd5;z$2CZluzBh3rCvWs(9$JbBj2m}6^BF#n^(CD+l6~ICur#suJL=;|K9wY zu|9bEV$044=6P)no7YXppT2ndi4V@dlV~j+!Zp5b>w^!<`$b8Vuz7ua>lup^uiZ0i zkf5bYxW*@}&QHttgCt7Wy#DdZGcAAnWDOFubP3n^p0(X?wkZn*9S?Iuz7v^;MXmlfB61cg9I&I!Zj=pYnHN=t>X+NO4z;5N+(C| zQoABC4As&loZf2v@ALV7kVFZaS2-EaHAu9UtVhB%Y|Z&7d&=VZAW_2RRZik_4HC3; z3D!#vJ`OtN{<)uL z4JQz$uyhHh^9bh}Bud!4G}_($sPAMA60Ifck#LPXQo9C;5;iZ5+V`IH z?W{q9mM-BM`HGXu3UL+My~f4KJMPRHBy=SUOP6puUpaGGRie=5rK@Po2Z`2_X%ens zIoF)QHAs}Od1*FK>w^R>UBWf21~vC_4H6~nUT2loGYlj&LyC6QC7jMPvRqb`D71NL zc2@fbiPn;760VVFmaajfgw0E{%-YXM(9$Jb!^RTLsa=Ca37eN@%XPdWK}(l#jXcx$ zF_AOBxvap zuA%2KdeSKk5+!V2I&axeV%w#AH4?OR3D?l`7(KC-28j|jFP+fr=fk-M30k^@Yv_55 zo;*u~Lk?1X`h+w{ zl(2i{FMaM(eUK>M05waO2#p)E#z>-s%}eJA*L-NTB#72hzd2fdcMYxK=TDpX5Xe}z&xxGJF<0@hE+OlOov?~&{bP3ncnp$qV_WodvtAx!S%ze<_AFOeeuzBfh>e|mq(9$JbLu;IQEV1_oYg{F4UOF+mj#ngT=@PD? zwc0!;+WUhwt`asco#|c2T@ti(3D>ZZdX>j^dw;OTRl??_GsNrlg9I&I!ZoyZp082% z{$P!(gw3mbvwD~MAPHK!1U39xOQM9$OSHZjkj9d%;RG#R!Zox$Z!0rCXCP6+=A}~5 z$>~Xh1T9^{HF6EQ28j|jFV&{bT2C4zXz3EJkz3-L#zYb&Y+h=WI;lNrkf5bYxJK?# zu0f)N%}c#Y=eZ{h60~#)*T^G-Ymg{m^U^4x6X25u30k^@Yvd8mHAs}Od1mUGP+T!Tajo0nz-wLVDD(j{EOYEW|@*C0{C=A~Ip zZC4~{=@PDCEm3ng*C0{C=B3$L?H?p)=@PDCJxX&?*C0{C=A~I??dK$D=@PDCBZKDD zu0f)N%}cZ8I$n{WrAxSmjc~d*@G+4@37eN@{dL?WK}(l#4I8P~Vr(Z-!seyBmwNpm zK}(l#jeO_jR~!;0Y+mIqY*)Sx>h8`7TDpX5<%}Y;JYd%P{mYfn2u3$Ergz!N4x40PUk1|s`HUV37eOm*4O?)qP1i_ z60X73J`yEtURrgi{hS0XUBWeNWN6k0Bd$W5msU^ectwJiF5wzn?ITgb=A~7jI_{F7 zrAxTRJ?qv7Bd$W5msYdt^@9X0UBWf&iqotQMqGt*Deyi!j~;wf*OA1BvHaS zAO6jsUAoq04JQDqa(KSevuz6{;^KTiu28q^^^+>oz9;sb}LJmY9EObHZRRGYdL&*t|6Buj4KW zTDpX5aJ7#_37ePhUg}kX1T9^{HS(R8UvWs3uzTgZuwD5YrQM(Ts#Yys!fBo7q?4dD zw(A6_J%(-m45@_8OXoQ~@B_!@XG^L^{}g9I&I!ZmdEZoWp1Bud!4biQv~yM}=TEnR{de&r-l z!Z{!JKKH4)pJxpx6mM9%glpuS`~4t^5;iZD!e{PyLX0J;be*83OSnd^!3j}l^HOcz zdh_G51_@faglpuMxTbNJLelLZhtqktkvF(p9wPBVTJh zRjnoKk#G&mx#kQLqR{50*+8ui60~#)*RUGY+{ZOYl(2beR#V#*30k^@YgkLv9L_aJ zl(2bec2@fb30k^@YgmucT+}s4l(2bemRb8b30k^@YuL!3Ikjt$C}H!`Y`KnCBxvap zu3;mb?hSlQBvHcVrCEO+cS+FFC0rxlvA70_5;ia0y~I^w7)a34C0rxldHEHGL ze7Sd*>YM~EUBWf;&H>jTQNrd`z7*^lBxvapu90^@xCV(5HZQ%uTlXiDpruQ=M&8Nc z8YD{Cy!8HV-DgRHmM-BMc}I$CkSJmEy3g=Si$gydds0cz(j`Kp+})8VVe`^?95o+# z_l{CE($Xbd!*X8si;^f|^U}E@wLVDD(j{EOYOw4VB~ilWrSnnhK4cQKbP3n6mRRY5RrZULC}H!`c{R14lc1$bxQ2}kWxpti5;iZLyHm$260~#) z*RT<;>=z|b!sey(gX*|Tf|f4f8a7gw{h}mF*t~QOQoVkVpruQ=M&6mJYt%@hgw0D| z9gk~QyI+)+|DUoqf%fmJ>O6mfy|55nOhSucs3M{aQicDBLy-6Xy(9>w3@$Ajv=s#d zs~94!4O)wmx)$INTIodTB@~FF27{m>g;6l%*>od=pdf?IWWsVO1u_W^5J7u?_c?o? z&v|#>m*-pL{SR;N&-tGDoO{o?_m%`Te6A&t;hv9i-lwO^3B?4{v?rM^HM2{ zb4w&>DGAr;HR$US5*aox)#f;VMS_-+aE;y)4>S*w$gp{-RgQCHBxorK*XTXUHArOG zywtnKc{mcZl!R;avBWhY5mFGoCWZ1m4${hWi1T7`u8a6WIc~KG>HZQG~$9P48mXdG{8{zW2D2WW4 zmsb5_+$BLvNw@}2f0D?sdFkpUW{KU71T7`u8vV-4XB-k4Hm|%2yFu3mBxorK*HDjD zU)R{KzO0_4vk@6KFZDn5;&x_&1T7`u8vRW=eyv6#!{(*_r_rcskf5a`T%*4c$Tdi0 z*u2#LG^#cY610?rYxFl89jUBHWZ1ma|1>)^4HC4JglqISG`R+e44aqwpJutHL4uZ& zaE<<^Dc2y8Ve?Y|(`?-|NYGLeuF>C^rkx%n+6G5N+LA!ZJ{JGY+hPVk9_E9Dy>H?;|nb% z;Tn3zODpl?MAGJ^>w-}qBxorK*U+}sMV!3NMzW&biFzHISE=y!Zq{^q*j;GAdzA7(slC~uSn2R60V_V zIkmc!28j%tm#+WExJ!bTl5h<@ld9FFG)QFFymTL9%pW9ZDGArmPI#ZA77`gYFWrxc zxvPDDFbG;of*L;8lE`q+hgN}oylSa(Lh**BBwVBC{DD?hI}#Z-FO`B;flY%1EhXU^ zy#`%_M25{vwW(EL(;z`hNw`LDi3iFDi42>UTBTNjO@jn2CE*&qN4W-x44apFmsWvI zg9I%l;TnBpa19a}HZP45S_L)@610?rYxEJ$HArOGyfoTr71%UL&{7hv(MM|6AdzA7 z(x|OfVACK$OG&s!pK)A+M25{vvyWDtO@jn2B@r6=eo+z`HZRShBOiUP^;FSP60Xr# z04pMC^U`Wy)CUP#O2Rd)2J`)*BrFn88$Di&PM+rK}$)v zhV`g?zbJ_eo0nFZqo0$Yr6gR#MuvR9D2WW4msZPTydptMNw|iMaQS{w5*aoxt@_8f zOM;e?a19%&^ZlYEGHhPDdWl(Lw5rM25{v`|~;l z(=hzg3NMzW&bgp)c zS0rdD3D>X@F26@lBE#mT^TA`>B|%F`xQ5Ok>-3rOK_bKErE|_>{vbh1Nw|it2m6e( zkjSuk`KjzaceU%mAZRHGYWQ4BBEvl&IwjWnc~6xSiZ?7J;Tk>Xeyv6#!{((@&?&K| zL4uZ&aE)Gru0bNh=B3)yDY2$Of|inSjouOutj>2NGHhOIl{zKXG)T}=60XsElxvX4 zuz9I>>6BR0AVEt>xJDltT!Tc0%}b+%PKh-Q610?rYxEJ$HArOGyfoVBlvvXsK}$)v zMjxqNgG7eSOQW_xQ5kWevh6+hRsW>n$fOE&{7hvVJ$JgM^7Td z=B3ry=pQ6#DGArG9+lstCy`xJJJ-ain>WM25{vcPaF?v6c@Kw3LKv^gArB zK_bKErMoS9Yg*GFK}$)vM!!?!8YD7oUb<_fx4$(F610?rYxFx_u0bNh=B2w|dW&7t zAVEt>xCVFoNMzW&bQe!=<7*luXekNT=yxDJA0#qtUhQsVXpo?#Btj#1`$%NiymVJ} zqq|}K}$)vhV`gve=y=o+Pt*uF#0(OT1vt-Y-E`B2P3Ye&8zL6L_a4% zOG&tfjd0Wcpx#iZevq_zX%}dWyCi5S3D>ZZdfFe1xRN$6?PiVng9I%l;TpQ~irqdE z88$EN%EjEZ-X9E0Nl?S*TE>;(o)5iMu#Z>A_6NgK60Xs6?$>HcNe~$}FO`DcD%dng z&{7hv(QD8(NMzW&RGWIMVACK$OG&s!Z;1z*2T5euywoc7R>7u0f|inSjozbNgG7eS zOT9~P6>J(LXekNT=p%z`kjSukX_U}g1)By5T1vt-`UvM5Br{Re1_@e9!ZrGg5e zXQO|Rprs^S!+O-TKNxW(ZC+Ysj($#pmXdG{8yTkk!H6qq^U`X0j8`ORDGArG5pLQa zjJT3EFRl8=xJ!bTl5hn4Jr6gRVpD^{SJMH!BOP=b_88$EN&+99qt)G*ir6gRVpOp1$H4+&%FYV9kYp6|w z1T7`u8vkf@u8~x86p0L*m-grNRoA9Lf|inSjec_ZNE#$EY+l-**Vk#A1_@e9!ZrE{ zY}X)>Ve``dyuPyAG)T}=60XrtlDh_p44aqs=k>MVra^+1l5mZFBHlGfWZ1m4Kd-MI zHw_ZBl!R;all`tiBE#mT{ds-8xoMD~r6gQKy-Dj))j5d_o0rb1=_}Mtg9I%l5gOC; zgArHK=B4v?BOh8F_f+}wgJCHN*U*_htu8Ga6Or+nm(C52`XE6|Nw|j2CTevl4H6kP zFP(oJ?TQ2~CE*%6W2x1pG)QFFymXFp^bZoWl!R;Otf*F((jbvx^U`_L(a%ZHQWCDA zGp|}*N`pj(%}eKM$9P48mXdG{8{wws2P3Ye%}eKl$GA&^mXdG{o!7P%lg8bJM25{v z=bXpDOu`GHhNd1$~9OX^^0$BwVA{plguGuz9IA^%d%-L4uZ&aE;y)53D}?`N4=Q zY4cL6)K{pR1_@e9!Zmu2at#t0HZS!qeTBMdkf5a`T%(T+u0bNh=A}_WU!iUqBxorK z*XSdhYmmsWd1H8YD7oUK+La73!uzf|inSjXvYJ28j%tmu4S* z^}1=0prs^2V|sot;!4`QG>eXW^tskkMN3JzhUI*EelX%n+Pt(H81+GdmXdG{tHJ5{ z!H6qq^U|tjv?~&{l!R+oOU&<0kjSukX>~UG2MJnA!ZoZ%P0tTTTuGakR+*!plc1#} zT*F3&>G{EkD{1r6YB|Q3-Hrq;CE*%2!cET)MqEjomsb5_+$BLvNw|iM)cU5LkGmu? zY+ky0iCJQ|BSA|^xJJM7@)?IjhRrLl!fvRZAB=ghBwVAvfkt!f&iDFv7kYoruz6{J z{*_N?f6sT;I6+HExJG}Ij@AtRe$j|4Y4g(l{N4XFG)T}=60XtT2;>?hGHhPjpFeZv zqCQ@cprs^SqrchcNckX*2VqlKj;LL;y4NMzW&blz^{!!(kZEnSa< zYv@d$PM=xR_4kWLTuGak&JB+GAVEt>xQ5Pa|9-z7B#~kB()q{Hu1L^Q60V^$mO6c= ze2~bndFdSI=pQ6#DGArmSy7!nlLmuzBfR?HI2} z&{7hvp|iU>eI^YO88$DS4<6$#30g|RHFO49r_ZE8BE#mTbIvj5`+L=rprs^SLnotk z`b-)mGHhOcUc1j-K1U@%OG!|}=UNgO?)iAc^DgLPVo#M5iZ?7J;TpZH9%%X4k;t%l zsT4l&HK9R*mXdIdUW2YdBE#mT+I;I<4#zyGR^kLLCE*&qB_1drBrH8YD7oUK+JO@siLWK}$)vMxSw9gG7ei>uviNJU=u@XeJ9w zNrXmT50c2Rd1)3M`RH@4r)suzJrb^AIiKDy8gV6UURn)|`XE6|Nw|j9;Pigch%0IH z(yC^(D-yJnglqH_ndh8DhRsW>v(Z0D&{7hvVLfVkzi7mjw0UWjIr=#XT1vt-Y-E_; zFB)+rZC+X}kMW8GEhXU^eWmXs9El8@msb5_+$BLvNw`M8VsQ-;88$Cny~HfBe!pl~ zO2RezwVKa3j4Q+Dl~-Xm=z5R@EhXU^-0jo;d|W|h*u1nqKko06prs^SgS&ksGHhPj zQy=%KNzhUfuFxJJKIdd3C3gZ9!z% zyma1f=>^|&{7hvVIy4b50c2RdFf2=7Q??aeud`$_d3AmXdG{?)H($uz9Hz#(ioMw3LKv^cwVa z35g7wmufTak^4NTR^kLLCE*&qB_3!VB#~kBQmc%6{eDkht=$P)O2RdIk6IB)o0oc5 z>{;yeo^AD7Cuk`N*XSd|ib&eLG)jzp91^sYglqH>&NWD6*t|5_#U9dbM}n4;aE(4v zy9S92o0mrI*bDP{P_uy(w3LKv^ciPGB<)^zIE+2L`Te4r$-+_+p@HkcK_qQnnng!G zELBO&mQIs!jlKf#e2~bnd1*B;>VpI=CE*%YgSkIQBE#mTRn2HuBxorK*RYnD`-3Dh zY+hQOjs8J`mXdG{>ruHsNFu}LrB&wW=Okz;3D@W=WUmhr88$DimdAKSf|inSjlRW>|EU+Za{wf0DGAr;XKVdhjYNjcOZ`uyQPUtnOG&s!Kk@4t zBrVFzln+6G5O2Rez$>k%J6^RU+m-?S(ho(V-mXdIdegfMyNMzW&)c-WgH4PH9 zl!R;aljN>JBE#mT{-@cxX^^0$BwVAPh<6PV88$EVKdm~N1_@e9!Zox%uN9N(gG7eS zOZ`u)r=~%ImXdId{)B>SkjSukX&tInVACK$OG$)AK0inz!{(*+^vH)!&uKks8DD5A z3D?k>KCQ%$6G@wwt_wzekf5a`TtnxzwH}oQi42>Uu5U)WB0)<@xQ5PHYCS3q5*aox zU8jxyL4uZ&a1EUm)#_3jBr}&ucv@4H6kPFTaP< z=dStrL0U?J8a~&O$Z*exR)KxIYN>KU@rI=&T%+gwftHUQi42>UNF)oL4uZ&a1E=$e14EbhRsW>n$fOE&{7hvVJ$JAA0&}s^U~^U^bZoWl!R+o zkILr;Ekd~5gjeh0jGY*Lin^#_i-EjQ*L0U?}HGaw7S#w$c z9{q0jnZ5SrTYv6h^Sbk0KeKYQBxXxNxW-59Z0*OM>1&1^i42?9GoSvM{Zp@v zcYl(gr6gSAEmr5>-_|}m5*aqHAGqyjEr0PIND{P^gll}r+U{rD8g54-!{&AF^`G5e za_+l&8Iqu-BwXXu)(7psBh9rWGHhO#zwgHV`|tMdu0ev9l5mZW*uAB{X=~~oi442f z=k_oDSZI*g?S`c!oPLVkBYRW3Hn5xwBE#nOoC`j`f5x-^tmlKoZ0R%!*ZBA|pY=d% zDPC42GHhOte&Iju|Kf(wAVEt>xW@I*xLWT#a}5$1cCX!`-S6r7AYoZgOG$)AzAcnQ zhRy5kuiPDue3(WOv!&~ia1G1(b-k<>5*aqH^S|#44o7{Eprs^S!)oxlUgrym47=CO z4oABpvD*zxNjPmS@u;`mg+zwU>+3JS+2QCPBxXz3BjFnAf4vVbBrVEym!{!6cnj6dL&$|UCELW4w`$(p4kLL=WVN+QGNrCD_3qtCUTs@c+0 zLc%pH=UOwYh@{O+tASA;BxorK*XS!5*C3H$_xjvETF-7rLMx=Ol!VjP619eN4H6kP zFRji-{~$42x*iGFP;ZJJMIyuIrB&wW=Okz;3D@W=WX}hQ44YS5Eys98f|inS4IANf zZQx@fi42>UR{dk#B|%F`xQ5!4&4aE%BE#mTtCulLkf5a`T;rG8wVKa3Br@z?yoMve ztGkkL+Ge$bf7QP?vD;m>fAA$&^l_<&&Fe0Ay=woFx4*Rioy2S@2-i@~H3C_`-jT?# zc|G&#SM6VWuPeI-30g|RHQr%$ewf#TBd(;)>oK=|rRDEsU4sNICE*%7dvf4i{d$l@ zhRy5T>tDIQ=JMa{8YE~b3D@X7>PTfpBE#l&`TMTkpZnaGcMTG>l!R;8I`lv@v@}R$ z*u7r0|IqimqHB=Y?S`c!oc<5i|NbPe2M3X~c|GTX-`T(ZQ=vg(wse|=YxI%Y^FboR z=Jn_oUbDaV!+)#ig9I%l;Tq4g>p|;Pu0bNh?)7`tu0n%^-9JxDNrc90yT(Ey!{+sp z$G#f*FpVT;OV=ae8tQ-6tCWw0M25}lsn@;+^+AG`l5h>H!RvaRFC;STUe}^sk=X5q zr6iozHB@iAR#t<^uz6i_?rYIMNX(W_lW+~|QF%Q`BE#nO{<~d=eolgxl5hZuzjEL1eh+PAkk*BW+{o#&|KTgigER@d1)3M`RH@46SJitT*GpX>%kFM z(&nYrz^D%rw3LKvSPg3J3Sqw!+I312S;2L24S30g|RHEg8THI8eL$gp|o>SfFlBxorK*U**MNB&Ejqex`fy?6~rf>(DXL5C44aomyRUdoXpopK zU5|uo^pV;%NMzW&G-^NW)uBOxmXdIdKI6Csi442f@9p3J#?T<4c`z&`5gK`QM%oXCY4g(6%a}h%&{7hv z(XYHT<18dH>|TF>xr>CZ=wenYiPW%b&b%HBBI%xwJKopszuurRQ5r!g-eKu_BwVBC z+}8{wGHhNdg$v*H_g#YoEhXU^yt*TiVe@LW`FCA|1T7`u8vV}1f#yLH88$Dq%5Q!0 z-*ycWw3LKv^d99JBrRlgr%BQ;q30g|RHTs<**C3H$_quj}r(gS2*C3%0CoCo5 zbRQF4gG7eSOQYTSUlJN5W=q#2;TnCUb`264HZP6Z@4o79dOk?dQWCDwXB^ickzx1x zJ?m+qK|(WGSV|%^rt85Vk~S~Rq9Y%DuJu&Smaa#_H7w`T^W)N)%}cBPG47I}r6gR#M(XK$ zFyczuyma+4W(g9sl!R;aoj9MPNMzW(cnwD)ujp<-N=SHEZ=iX7&VwKI^P=|5%7u6O z`M=&@^L~2|*?n%6Vg23Sq=KE%@H$TX-orn#f5Fec$LVc?UJ-5@Z??NDPv|?mv_x2` zdilZsu+;u}*VrQH72&4wN$X7??Jbd(2utH;Kk}FRpZMnwc8x89UJ-5@>>sp5SQ?67 z|6k$VZi}E-gqw!)ppbT>Zj># z5%h|1i%GlfYFkpECBlkVEmCc+X>1Ynig43VOIM4R1}zb8@!F}g-AB8|7U5^p(yI}v zp|hO5tY{hW{`u=4TvC;cJnLudLbf?g4B8dihXMV-?U z;Z|0!LyOrWb~}2taMQ4scoc0nyqaYY%kDb#k1c{;5pFSAkJ8nhmlZ7$RzCju|9B1h z`4&O12saJO!;yNG+7&Gkmd1bhgWtt?wMEb?!cD{K;z+$p8ni@M8V|YZcQEd55%h|1 z)36qz)1R(EON6EIS5JCX&I~@bmjt~c+%$ChI%XVNA}kH9YShD8c#D|58Zl}36=Zld z%ZOKc>MxUq2>Tgv(JR7JS?Mn4LQ8}dugXpRrD^oi6|oC1#YL|OH;rC{u0czL6>qEm z*L4jLyYNz6^onrP=q>R``Jg4j(oj2Ae`)yu(Ocr{>^-=5oVdqF02QMjshmgO&)lcwe_yzFHW>F1%V?^lIVu_dde8hQ=$!b(~OrtK^#o z2rJ-0&?~|%ran@;1}za*ylS^My&~K+`i$cmv_!bYtNAK4KQz#pCBn*w)}iVNEl*nn zy&~K+EDu^!y9O;0R=jO}9plv&L9Ylm4XX=X8~7+nON6DNb*Oqm%f}W$uLw5{t(4TO zR93V^Sn+Bds-Dm^wg`GfxM^5R*OiygIJ88##oMmPT6l}lYIV$(;~K8LUsSzH`3SG3 zJ_zZlzcdYVTjXp19Oy09xBSfqo!#wjwjG7p<$`&mTX{=>hu zf9bpIX*na#eezZNkN)`kJbdQN3+>kzK1{e!Ryb8P`VYj!gsm*d53@ek_V2Qrv@z~p7k^5&qPa6{^-5WJG}JC_B>zLs7v?qCq8rk>96{vr|Qyce`0^*qdxB8$3N~TvJ^b}#ebWI za^cg@r^u&9l;Adg+zV=B$W3J#Lm4Jm2o;`fPnGyGPc~(60zuNPP4Tf3ttoz3eHW z6A60d3H%j73yGil$4~Bm_W!Etg9N?uNrIIIbDrnv&5L=O>tnX`v-w6Srd7LIG%}E& zm+};2Wov>>Nqx}vmi7Fp#jB@l{5eqzvrRYOAZQ_>=YRYOP@~;<31YVNCnry>p{Jev zsZS&Htdu{U85&K(a?VuIi~YYl``ByaE=o~tEc*GXtWtv(60I$?amAe%`)&U%2PEkA z{>wj+^OY0**K$A$3AL*j$F>Q2>A9IzS$V2v%jep&+E${}-qy&cu#M0&MpK=a`Jk7c ze2O+UYjDiS=k82{W6Vs@LL#52D_cp7aP(@e=MBYJVv5#3?CCR$E1%l3u*&Mo{_Fo+ z5cJAtuudcx7m0ixYn2ZY^x{b5Wwo>tTMlMRe`?F(&8MqY8YJkoJ;Jd>^BF~pce`|F zOMgbuhv@m_z4SFny-g{JOcgEquBG0GBrnFa zohlOg@}}N&lo}md4j31`^gU3$x2Ps!J(yoVwN&L-N?C)ZvmDTp-x=-sh?v&-2n&h) zg6K*^`3Qnu`907TK}&wo^VF##k>BcEX)smvV#}X%P78_rR_98C1ie;0YH3Q#0qa(E zqjyK0zFm<}{p+nzbt{RULob%doO4=8`uu)uPs}FH=U(kw)~pNB#Z%_fNjZ1B+5rsZj4bXpBU9R9?zvq3kh9K)}ts1dU2MRHJD!JW4k_RA)#`M zzA|f&pcmW1OsMU~-3W~(FFpSqXVr@|Dt*%<-tOU%rCjaUEAj@H;Dq2XW6t4UAcb=`s#7GsrSpTlEG^OQ$twFQe z#h?0PkC)obHwaotXw1Ltytg>LP0&l@{H^cvrh<^=1OMt;w}|*(zu?s#mUi7rXd$5# z{`3Xc6dEMx#a^(}&*HzWKA2w306+H0*Po49ElR!l2Eno-p}FL5U+_Aow+VVNwQC~E zgoN~-a?#O-MiBI3sm~f3cVo=ZC>mqQ>G}r=ji`0oWnA=P-<(s${w%K;4cPyaSk%vH zAtAkbydp7sJz{^WPki6mbsyaAhJ}PmAx6|WRT{&i=V+#mKByVBZdZ&;brYjDwNt|a zy6-bmMM8S3{;?b<=*2tUvj#0Bl)vb~+XTHd!$tp}36>ShM?^iAFfPrt(I=SNS%Vf5 zTCdc-mIS?+!dZhB64HxtWt*VaD(6e%ROip$|LzO#=j*{spZt^i*PheD+A&$JMU9#X zdg)&O&Hk~`9(!sq-rHUIQ~S?66V`MdpV$m#4WD;>HV2E{@Y^pN`hW5y7*`I zpa1-Q2a&0w<(&8Y%>Kvj(YzSbcB)A1c9-tYJosydM#tuS&`TN*{a^03K@7`?S9+iL zkN3F=f?mqs6E44ZLC~VII`575a<9{+iiGOshi=p8by-C|=%u#svLCr;kt(&st3LhJ zZc$sh_<1d?SuJ9kHE1EBeWNSBr_o6)YP%$6uf=Nc7-6X0t^LXWoN>MXtN&A`N@ISV zDq2YFc2CRvWvX0*1ie0f?vJd?%JcDt^PZfo`fp!xN%jfFwCc5~5f&2feZ^CcgIpdPoBd@v5zaSqZr1ve4{L-OO=A2&2U!?Zre2jQ)PQ3n> z8yX|7;l)yzHCQG-t6jg#oR63WGnXz2)y;)p^trRyt~xXm^iuub=}!Mp5E=)gjcQy8 zFZHNZsuqn5>IYG4KDPIkA!2H~nJSHg(b_e_J>jyuc+S;VYJwILroTV$`bPKY{hv1O zj<|-G=H1Yn30dNVh~mBYx{sYb{k1a*rEtVFROb67^eRi&!1w^ zY!ZtI)|zI67!9^-kQNeZF){6Ks9bh!%djvLfO0RqtK12IHca z+VnJDb*#1auxK`j5soo!Ymo3+tsG0{xNMH~^A7tOuviJX6T#wp6D0BXXzk2xLH+~6D0!~Dv{U@LJu*2tl z(B87x=_yr7DBiG;u=^;Ms#fYPJ&`IB^t#RWKIrhp_xh8OkB%(|vt`8l_{TkHLqj=_ zeEi0{FUnRjr*NceIiQ8a$1lAo+uQJ04U(YOnKKt1zVpveADIufM7FUPJb%BD4_Zj< zb~ZWadPqX z_doyec30XL3ass_-^3}+)L2x5>b39xveut9u6+9|T9`24k?6|MAvd*`{X=T1dR|2^St-e^J%i zNz7gs+85a>g7v|Y*7z9X*qka_NR)MM=yE`UUTUE+Gt3&akZ3Kjodn({=(Upi4T0u1=+^733{od zSM#}{^UO&?eXt&P85g~{mhe<9Ep58Ld!c36>I@I@E5mBr~& zMPj#n)8Q?yY-euQ8Zoxhi{t!E{QkfG`onYH6Kfoui+Qi7P^pU4&ctjP#6^Gp4Txzl zt#l(UdQEv6fYry>|NHxA`RLh$pm)pHZRDI55(;ODOd7|D@Or?T&dWIwfTfBS#>?j$ zW}-a>(Z=wvedw8-!}at?oFknHdj0V2&g9Bso1lfnZl@`3UjJv%ZOKc z)3rgzY@|k9^iuxnYXg;HjASa^C?A#j$G)qbpq*1i3yD@YIE}kBZaGkkd+ZDTFkASg zFM5uL)mLu(E)bayTGaA`XuTFhY8)qayXK`nSm#6Ojd<1aBZb@fpoN6mbe#_p^kNzI zO#44`S*h3li$g?GEGIf^r@w61E9iNT>|!oRgrJ{$A&U783fpYLxVx4-)iZ%_gxNFWtFB?{FAr z$G-z55vL zMlQUyW0awnMz|O&oyb&i>=O}V3CGG=gBB7>VT?-K#OyVC+Dx!Vkx&`dZI=YSID)6f zqOxN9QSXX6KV91;q23(hd}>&rJq;M`ieBpHF-tgMDbmk!pgX`{`^|5DV4LZ+>ei2* z&U}47k=_2*e(PCFS_bjNyZkL;GVi4#=%r`e(N#xtJxZ_dVE z!LMC+m$Pwq_}2Sxd%(9o_t?IHK~^7czxZt2F@5fr{ovWS%dI&u*6_0iEhN5w{{yKv z6HLj|KJpc*v7IVfNPOzPcgobJ#-eOylLByrDg|Ei6$VqEm%IOfqWO++ipkzSQ<+(SNH&Pk{? z>wCzIi(c$EJ<~05o~o!@m2T7^+rmuHLP9kgZDE_B*Uffk&#rbF7WF8O04mYQEk}%5 zgBB91n<(jRf?lfsx?Sm7Fy2|BQi$v5c4ha7akXuE(9d!}3kike3c2~py&}R(vu1ro zPYdH!IIfUqjpIakX&n(e%1KyYIiQ8{DjXwU5=%vd7yC^Tu0adqEnCTopchA_)L4`% z)~!Z~7=74!l5h=LNJt~bv2B80N@46-%!JyNR>@kowH9-ZhgAx3{&FU0A)%Vp8f$&u zhXlR!_w(;}%MBtdB-9qPrmHoApqDiAPC7EuX6LYwV5tMJ8f0Ab(%)m2SQB9(v0WdG zi(Z_&)*4Y$dLkmitXU_P#w`c5kWhG>JRK@)BE0z2=I~c*r-kwAsf)kaI1r0seaJ<^@SeRwa=uH1T7>qj%Y7$-J>*fX%|!$&4Jp1 zSC}!)siK91R?XU5Uu%${m)6$WTVE5p>e4xeW_jDbonz3QW?e7n{Lk?>=_n=I)0Rbf z(vG;oEWO<#E)~RB-(~D);qxXO2wo5|wuk!|L4aP+;)@+NsDJ=)ADV47F z&=oIZ+D;V-)vWgHPfiuR*t=#8m8i}~wYc84Z|AYv{gS%Z>VC(`x=$lyhn*CD8{- t?gz{96yCmqvUNCEDzb4in+Q)gx z%iCH+cT!_jGZVV!9TwfKfAAB(&U>(SPcD0S3(th^o`x6W)t%IupoPS4cZb9C9|Vo1 zDe2tn|D5??3bj`ld2-(*Xd%Hje74x_w^4c)V8lf)X~%m;W`Y(Hy7ykclY{w?*E8OG ze=l98Fg27gKV=d1K|=T5FZoZ6-X`d!d+)FM*A+pF?#h4mU9ApIm#T@d9h&F-B5JTF zZO(`Gal(sjY|h8ru5O>i++qgP?&(KaX%`?gw4V@p8vZI>#zimfX4Pdy;&_i5bJtL5 z8et)!zPV~w2F?V%w5M0ME2dX_chNGK+L5Nvh_WIfjcAqI1id)MB(X??>6J#jfk>%} z5=p`WbIwU9e{t=zP0&lV8SnjZVriV#iFY`R_qAzM8*g7L-q>qU+jowu9};T2^&5e- z=M@CK)bisEL@hlMkOtGMwi{ljD=QM}H&d!Ce*Mg)J9~}PHsAJp&N&H<;G^6IGZVAd zD0TN=LW5+XTJJ*}!tIvKl8zd1|(u z(W&-WXd$8XsaE^zbvp@q>F;qrXwC;MBy??F-|-?rFa164Qmr+@LZbDVc291bpqDh_ z9*`4@{kH$wxuvj>(AlrJ2k1oqH52sGiL{6*3D-FGu2P%J+nL?dz9)5;g!*~hJ97<- zzvY8*(d)b~|Cp_iZy0qh!hY;oGFV6`T-UiQQ6FFM{J-3P-D^MW@t#aXTqH#5|F2sj z?=hf^z?s`|Q!n!vQscpVN&_Y6QepflJQ$>PaDp{p$A{Lcy z`wE+V$JtV%ufF+rSS_rlm+Mr?5@nTNOEV(BiRR&vlUalD>g#O&jng13MfzC|@_U(P z(OYLDxB0EkAR1r?r9Lc|&Gm_Uhjp4UHv;{Mw={kAF?JtNhYq5DlL0AB{N|*^%bFc&Qro44M1Dp19>mg=+ITfA{hQwArMpxkrjf38Dr{H=p}L7Y4S(gFanVclAG6O)X#DVR ztb2O~prTmNXYDDyWIj^~_&X1i$~?AV+t zdd>6IP_aEP%y%R-Kh|RjiP`JeJea9cYme34@h{QD%3!2PIcNVM@s_{3dS3NS8W9)0 zI7`eLO8XVJ{B>W+DCh5Z<*#~J^%18bW`bU-j|X4!lA9nH7YVh6_deuToSrpE&`T}< zNe}(yf|xDW?yp>4{4YqAzJ(ox+U}b_{7Z!fQ$;Ve{EL6KB2>9F5{w?+Cro-YtU0g3yD_$$MWH+Vwq^1kCri)VXE~05v5C_l~rq%!#{dd5cE<> zN6SxQ5y5ho#x8^;`>s9*?ea|ZfVJXs2n{i(M zsjys|UYh6C@247cVzvxI{iaS833{lUZV%k`C$9e>Lo^0#xxVOkkHyUdh<3xFU1t?ZA}czh*x^i|F;Qx zaU_}veqXJnq}{W6{NpqVX?L`rPUx8SScZj!!f|eG);Latm$Ws0tu<(2yiE_!b7rcJ z6H#to{Hwpczv3UNry6OQ<2}}EQ-g$7meIG>#zt=r_v8JX{ZTW{y&vAj`MIoUA)#wg ztpcX9TBJc@_EJwfrr|{EgWZC7J%0QDlZGWvbJU27Uh0o^K4>AK(M|bUYmlHZaZ1&&kkDPc(4IApeb2}4p0+2* zb)PYM@Jt-DB%ym{b)A!-m;S!0K@)3xEMXy`dx>@1<*q)@z-e5mcgbiW!P9he&PmWq ze~(?jH4zpP3di41CcnDj z>6Ajyx~D&`!beV)1ML)RS4r{m&c9;PUX}hn{8i_)kdU5s|B_f5XWvk;v`1XZQ+Ta* zGrG`nz_jaBh4$7Wg>^odLlW(T1yYq7BPV+K6lTAf33}-q zR?yo7EhJRBt2#HaRv(cMdZ})r#muRqMRgwKL+zQMg@oE$)Xg?QFOJ7aEXoJlk8-ZF zQc=1$-F8W+)ODIG>)hhk&)jzDwcQeFA)&SqDQvN~-}5dqz1R!fcL{=hLM<_REw!6( z5VVj`%a6Hho1hnGqM6{At$C7IYoB^uLJJA4YHymLmtuZ7}qjw?n=+5f&2ElV|+2`=UY6OBzvb?!7do5n&;r zaQr>u*S~8byjIsZOXC_5EranY9Di@VTSRzCV`}Y_MpziH!twXDMp)>@>%^I$g~axW zcoOs~&$pYHeXG&F9v9b6dLKuu&h)ff)a;xpy$2;$EPBI9tbO#%UrjJxz1t;L7TX%M zkkETxVpTJziUhs%&X;<%#I);eNwMnN&Ic_d^ggF3g*jCu=%shQL>bP6-j)>gL0a#q zin^HzT1e=9MN!f-L3O=9Cd!BOOwd9?Z-%Msg9N=+sal%Sa-f=uD+twKtd>->(dXw> zv8?nCr?@_&_Ds-1qP;V!x`HG@Fa5nv6)hyB7uUG!R7G6$QvTu&LK2I5EiJ15xaUCa zBrMRL`V9>ds*ieQ$++mH+KjqM4Nny0roAW_0^{&;r-BU%2 zdTm@moGw))G-6B|7QcSxRMBg@?b1R*qidaW67*ufY02^5mMZoljiOP{jH&qsK?@0u z;L*mm33_Q>ncD7>8nEb%OwlK(y{$o_y??IiwTz2i`g=V`(LzFcF|Mpr6>-svGwMw6 z{toXs=&CPbnh9D+@Vb4QpqFBbQzUC5EF=_;zn@Hm*ZfA}!7K-~FkZebIQVt)Z^d_PK#|U~UrpQx^ydg~^EF_qx9(@BnRU{%Tjj7HT zYJ`RHDja`bYlMYf(ugs?C5IYeA)#>meXS7|dPyTz%WEPmBzOXUovI+{rBnU-|9Ri1 z3$-;vtX{Y-WpAESMGFbd22qCF1ichf)aIH93kike?79m%Jwe43J9O(*g@y4d9Dkn)jh122J$-$1Tdhw! z0{YhQx+UsvzrOJ+OS|{>SPv_vc+1hY2ID=Mh`2~7h5Cl^I#rB|UQF$rDyCic6ZL)( z#mksxf)*0Gf2ntyoSZ6p>3*rc>boX%Z#v@AUFS%Z#+4|MIaRcfXnT6CZng<}X$LE6 zb|$pX6)i)0(PFe?R<{ybNHDdt#&IHYEA6_@X<@u&J{HZK%!j=6y?E6DQ#hxJ77{8q zePMoGgCyvsy3u#m*M#o;>kT@xXb(YOH;z?Sy;z1b zK?{kt-_mMxo1holLK2JWgY8GP_LA@Zp=>2l>Pc9j?G=TEgzEoMk9bPa64`d?r8f41 z|I`0A2uqQE+RkWLR5uat=~@X1jgOJ17JK_Ww<~(Fg(k5mRZOo+^uqtWrJeap!UA(y zkx<>d;Q3X~85g}ymva(oF_FSKRg8;XYR6IPGr=!Z@XH=bZLCpdf))~5@7^>)FU1sV zl(j}!NGKeCKbZ(Gmin5A*3Nhpj=!HwgqJj8bX^l+VY~{*-%lpO>#jH6_weUFc>US+ zY(NX+RXE=FJZl^$!i#Uyo(WnQukQKi9?d#cB5FKN`*IJA&Z_;f^gDWM%~Y8VY~{TjtH-okLntS7RKB3PD8}VpqQcuuX7$2#;b7r{bVA%q!B%MO@xK< zDja`5nFuePHjHl>&jc-ucl!&(HnZ7x&cE94C+J(hSA0(ki>`YVEhO}2#G5AQrI@0x z%=w^&guqlUs-E}h4CsJe?OTBFKI+ySrcJlyb8zPPbR`k8qrtQL|7QF!twW$ ziSTOqsCpDFjJN5XhKN3>n4+(&Qxz7*t8o1NWFowz5q)J%goW`c9DhHV2rqt5d?sj_ zrh?Mlc1M&HsTJ#tU-%*PvV{fW10zCNN884 zzUCxBFWrrd>$X`#yKj-+ws+TZtNT}VSny>v{q`|o8#ndJt$lp~QIV7=NR*Z{YTEErTwY0R|zIJ8Gn6^_z zLOYGM2IHcab}*+pw{p@?yR#ivjcQkM4X9FxKHq%XZ#&5W3kkL9xMQ(R&`W(K?rY2h z)2sd3XyMG?Owd9?d&SYawh4N%7bLN$tkkOGPKsK4q+Qx|SpeB z6zRv_l7>>$coivRJvHC8KOwd9?=O^k^k)RjrX{`~hfrRwx(q&xqVtY%CMRm^Bpw=Eem@y?`fi}WLsz|7( z)%P+O7rivDtnQb1s%X)86?bkJ({`#zXsnzxEPnmW`JmV7T004i+I7wu7riu#MoG8y zwBPO9fV#WgX0P!UQeEB0PUB3>mO=1*@-{&)#Z+G#&_Y7t(-GmNm}1qxPE}YKufp;7 zlZo(>My&eRL|7QF!twW$iSUv}toqkPSQxLu@%NL7@RCNX`qxBQ7_Y+d_mhe6YWb+H z4QOG!P46^BTumsZ7%|qV3Jc>^IR1Vz5nj@WSz=9uh4CsJe?OTBFKNUob4`SW@hTjD zKbaU_TVJWv+d|tpAANgZ#H+JDn%Q!_+l7_`t(&#iCCiyJkKJn*OJQB_)ME)PBs7lQ zG(j)L6n%cqIV~gmtu-?TWf@c@hTjDKbZ(G zY1E}l3*%L|CbUa-r#t;auiIzuzwJ(+_ONyuLT^shY#D^^i{3OrFU3@+iWU+IpND8YJkYXBYKt)6`gkpoN6KuA}cCCeZ-X z&=+p>MLAjYeH?v{PGQpB+5ge}G15yy-{#S`@FtB#Wu-5w=xdR(=zA>sW~#zvYj;9l z0MfT6BPCJK%16YsiytRwQ3``liG*GN?cS?$uCK2h*HE7H4NCnz2@9ys$G6nAD%Ks4 z=5?BHNR!}rd|YG1MX&NJ$BR-$3kjCOtU-catl1=7gBB9{CX&8pw=OFZ^kREU4GXky zJ4O4^x3Bd5%&42Ge{^hai6qo|^u5lLQ$?@s{-LK#qo3g(I-eKf9-3*$49t1uHnV{?^*DFT785D zFR@oz9kfGY)%#9qL;oz6fHD~MWw5!NnHO~ z%w?F&vHBp z#q_GIB2}l$ISJKGjQJxM$J;KwIIqkEYf7aXvl?r5CTJm{nvMB!o1oX}a!x|u;HpPa z#zil-w>eewTUy6kBo$M=3ZE^5(Aw^%33@4}SYOYnqJ@OQrz65kG1aSAS{Sdwrz65k zG1Wba7RIaa>4@-BOfgHW%PK64SK;{k$wYYR*>`;bH^-8WwJ-gJh4FIb?9NL=mZN;z z!t%uz<{K6)tbF*rEDQJO8+erO=rc>c;m^XFKfGN9ks5kpT>Bn7v*_7#?XxJXRgKq8 z5M5|F%9Tv_^3rv$zKU8AxzaaFuJkROR~9RRUZnHdfQ02`Im$2Innia%{LZF@^ZUFc zEHBHE?)-*VKHFtp`OH@k7QcR$qX)d{yu;gF`Dc5TkIwR5`s8>m)!d1hnJjd z&nuot(Ch0jzuDpY@7D5^salkCrRq5syfstecLy!rruUXv!wFiH!XTt~`TOk6s;g8{ zDtkU01H&+hBeB|)#t-*@Bw-0R;|as$6CucZCMTC{O|jM!)H9J^_$GO1zHV8Sx-~5XkKv+5HXF0m_T|cvra&K>< zY4!Zfr+;Q2{ieD4ZzE_Sp;Fg9vvn&WL9bTQtv|NdLxUC)Ds|n}TWc^MyWMB3&Rag1 z!dYXs3_>wQUrAz7S&^U@+glPAm|G$Vl}PmeZGv8Gl};>;)2!CNOJ%J(zi?&Y?XseU z#B(nA{Jw5iBxbMA?V}wZPt~xfPsBLLm|6}ZAGDBA@2baL67*v0nKfEpv%M4_0d98q znA^6VI*((Go#b z6A5~${_lL(im(!}QNLO8?Y$Q7T!yWj^gBkMR=OlK64j|k?W> z=scP4M>8KLvmDW)vv9ssZC;FNP8BUAbQVre*sWU$33}-)oSv#%6SU~Gj-I5G7h~E^ z6$zaV(z9%94aP+;omtZJYimMhq4d<5Eb`LxWRa>>EAi5mMp#HlPfwt&HE2;j^nBmx zHAtuo^{n4ogQ=pI>PAllt_fOH=Xy5v^r<4D_NM1lQ)6lMxEwK6^eX$Hmo6tOiMbPU}e}Dh|lkf4sQC1DGUP}uJ z?Jn0fNP=G4cdlEByrMtni4<%3%3q9QJwg7@azqP>JPl*?HbF0rt}XJ$Ek{hRP83J~ zVE$$eT1eqw6)h^=7^xZ4cB)9IX6xC2anXw{bkbi}In9-jVZ&X(pH|5-LNT4X<+^anXyTgljBK zsa;J(&rx5Ae#f4csWPg~oS{KNW7jk?bZjQ*rFl0-qFF;Db+inPyU~`u{S$ZJKjv;P z8#%WW>1R38_!?uM#@!ebH6BN5o2%SKaI9qyR;pG#$_ZLXtnMM3w|?x7@Dx`+g<_+R zQXBoT`L^H75p&3#uQWQQyB{N75-Nqd*OH*uDpgCQiX|$IXnm{F%~a7sLNyyLzdQRs z%Ml5BX>PB36fIgaL{DWI&Kk6kP)zk$LV{jwp|gg1t)D%%de$9!e+t{ex^sW=^X!Ri z3(rKp{Xm4B5PR8=+|#|ZrxP(Hv8Y{QSRiNZjJepWdJM#zv1c9Vh7ZqKkiK|Afo$ zUF7_n_x#NM6aVo(-EyftQ~x!YsygS)?QS;+#q?wMxNo6Bf?i71=RaQ&v?w2E-uQ3- z1*syTa{J6P{@qQaie6<6_Llgx{Z*fCty)h@M+?{ZIJI5#){olm)3U{V{M;YOmLXy) z-NgYT==I)LJSEeEhPT-6_;eWb!Y!)Cg}Bs^Pap>AIxpOJHdJ|`~R##3kfTg z_TGlo$UuT#99L!y?g@%G@4;W|^{kkt((PEgmoY4ZPzwF4R*|ZuAu~ZQminA3T1co2 z{fklzo1ipqDhJ)-G(Z|5286Un7zh` zF%w4ZFTU<$XEj5r9pCt96{v)5kUX8ER?RyyT~`Ev)f4 zVwwqA{MzWaW6>bnci-tX^s&b-sGSRQu*_T%yHSw*}Yim+x5YC zrS~n5{L&4Ls6l!ue~-N8HU&Y8&z#rWn<9E`MoinOBB8pu=rwmNG?+trsV$5)HdNZ# z4}VvXTB7xjCtP+Hk5~O;m8wN`P74XM?a#Zu(L>=lK`)Kkp_hbfXg-hDu8}(WoyL-A zZ%&xEewHJRA5kVg*Y?sCvC4-Nw2;tfSJxobnX1!`B_x#d7>PUs{ntGD%wA(0bLXWY z%aP)Z8dSN(_`&@3=o{#>!6=hKXhf}B3FD#{OT9%NsbVQ=#))3Un6^_z!e_g(pU-jG zoY=ke_oZzhdB^o0&W3t5L&zvd} zs+*X7(%k|xF?)@kHWP1s%i*C;%W91Jz}H-GsI#vM|Kt-NcBu1%3eUtJU;Ti?pMT;z z-15xte1Pq9w{t5my>5S~bK7g;(s!PJ_@kG%(*liX8X|O(eNE6pLfV)7!m%@6o^ulP z`niuj;P7b|R2s|&(=OuDYpZ9o^!$X}cUlSj{^rE!<#=9@dc(+?SEhO%6`v+y7=6sNty&kcyLC?9}RZ9zrN9`Z9 z(LYGg>o(u}pp6>T8)D;ho61Me1E_pdZhEp{T~-_o9`U>j4t3^SUd-Qi&PnWc7uq*~ z8@)}?>y=NqF!g4FIeh%%9+c(A5^-W_oMwYjx+D}+-D^qE>kWVP@WXHXlIm=VRawDR#CB_Ei@W=uUU-Umko|y!$|`2mIUgkG#ZhS{Snkr$b2zF4*6d8s zLPGh|vv=znBr$tkXx|eDu{5RSNPRov(kKzBVoA@bqJ@N3A9cGTK`)M7vj%5_Mz_;+ zufPBKhadZ{W2f{iFUt`vBzDU;9p3m|aniA?I6(`EH~r2x9zOO3e^`_*EhH44o`R5! zYaA!S>!LsZhQq(SN2QVPy0(^~?+S%isUevoT1f16b`EP-X^^1T$*JxG zZyvY5E7Sh7C{?uR`G%;q_DsXE`Y>!cqJ_k6`MPxtt_XUu3_V5tSJQ|(AfYcc)pgFe z=rxzLlG8+5&ST`vFEv^D=(&)XwcR%fdgYg)DxyhPSurjWKYY708|z&X^wQs>Hhc6f zajp>-61&|Q%+!%2)gUb*VwHJ%jUbe#`r3eT(JS9#&z5M3YirS{4~-J>q>XyPR3DKQ z?@?hPp%LR2SN?xvWLO%~`d|?Bl7_#zCsLI}>v!+LZc+; zrI<3c-CO@eA8e~466z~c&L@qG3toJt2@+~0C`FBrFS@wtt;#AjXd$8T>YVpfYd8|K zm&U|a>T{|@#QpZ~f6YS<^)#C1SN*+yCXN;oS{dj&;_KO&1ike4y3T1K!Fhh2kBEz2 ziYe;}$lP{GXbnHD8K(LeaSbo7B_LsSuBQRxgrS}Wj5EnP_da%=2Gh>ahlPYO#x7v|y&B+D=f3(WOFLf^-&&p-sPyCqIzl(n%)6R)Y-nRGqWWF}EyV|;c#&zPNI@cWzU6;$Ed#$=IS6J@@Sd9!$ z&`bAobuVUz8xoFb ztWrfUy$NAeR!+>8x7m9#TfC~LNTE6Ak9K}WT=df2$5qaaTaIYaU9>1G#*_k1&_Y6Y zBBM6933}=7W3-r=(4Lc4t*QgRXKX7cJO z#JcQp*CIDISG2rBOf(b zR&0G7m4^TE@rs1@RCU*LUAl~mUL0L#4fY(}IgK%xeRC#gA)&jrb*f0vOZR;1KIqqc zy{F1c_mP!b)~u&$X=!WoN3=NQT=%L)u+-;#&_Y5b9eUdYy*RGS1kux9MEQ*6d8nAoTX6D3Mu%anVa> zifRp7NU#^o8YJkY(_*y-EhIQ9rN*K<*ZT`K7pgVr&4jV5f9w6XJ>XlPTfMnOZ|e*% zy@xYsJx3OIie1Cv*UxgKcr~U=LwXvm6+ZjMH$9-exQ$N|m9y z8#U6aH#$bV>^HLpEhO|t$H>z*K`)LNGr=}0LaWQDkLU$6!PZVfDb#$sE-MoBQi*7` zPGV_F%aPs=shLI=y=PLZ0EOBA=Ty-`LiJH=(4rcQv@@n{4H9ZGQEuA=y*M5xv8a`> z{U{&NKiEQ(u)uOe3kj8B^t5e)UV2|vsdt?g7zESy3KqqJ+q0|OFr-}r<+8fNznb&ZJE=RPGP{QtP|ygB@FrXkokxuSN#fI8KDu>3S67E$iG;Hm?Ba#Sx=t z!T)LVN1WMKDQM-V+)6LcAjo%dz%*zfq5Nr0w=OFZ^lEv+DT_%XPI8c7Z*J*fs)C@G zG^Uwz(g+I)m0R7<85g}cYkPW9gHQeP>0CZP+;Y%<&rcSU&|6B>+p=_*ilCP?qGp>f ziLj7R{QCd3MiBH;iNxPM_QihNe{;Jc(R%YEhK6Iu33{=Ob?2_3s|jyI)?O9%x6oQx zZCKPgAG)FouXcY%>23Fr$KNAKN|mlmhQ(Hr`Y}Q+T`e;;0`m8A#>xKU@05+yc4z;m z?OKL~g!YH)C%tv`8w9KuPADBo1mB4RkQ^smc}hdtXtJbq@8VH)}V!idQ@Fj zBA=5p_+}BzfI7KJ$NQqQyLlK z-79Ph#|X4)5*oYWy)WCu?A5tl3$E782SSk34M?^x`;{ z#GwL_Ir;2gWi(g}Kjio6mRj=BA=zCt_X}|n^SMSe#?#n%_HTtUWPF!;CYxhrj=r4PCo1lfn`|oz${=Ez#jec+GzI_}8@D z+Q0t)*`pQ_EECn>J6`##PO#Kx4O&RF*7K5^C|!E7q*KFFHJAIVvgK1d2@AA#HR^m2 z&$-}tHcFRq(QEFTioE@|9KGeQuFjEK#OpuR#+7rQeAWCm_9SQ_@x{OT+xsj2p?VUD zz4OH%yUtp8D^a!{OHcmHt%Srgo^_P9neG;t33|=r{9x>Dx|jh-{KXAN8$C)RPK>ph z-Bfm(k(IxC6s3iP-gB>VoaS@S2MKz$QmDpVrb;7f%nZ~U`BquYmO-dLM*TanG;Ss) zugyNFUK+iVghq*bKfIi4LCjtnl|U#}_TO?ejRrn;H7~a5mV@?tZtWab)IaJ}F)n(s z<yF4G3YyHeQX9|_4=_@gd14ht7 zqG=yHo!}bBiP-Kjy;{0gZ8`isECVR>YG}Lr$)!x zNF94nYD=%a?DOuWk?$VY{8K?F-XK&TU-2BfYVleBRr{A8MA!tDNR?*fh*$IZeINEY zkC!p^1o=O0t_=+mT1$NQ-`#iorR+TZTr|cVG24 zg$7%LX1HIt`k&oPYlf(&kqf1Y7805hr&iLjnV^^EtI@{HeQ8L$@`|{$o{LnSu3eE( zS>1GNrx)9F&w{6HIbyj>;{#9m^uM6aN$AS*PQUi4qCVzUJ-k?(nJNpk*?EirgHR7X z|4S+j#zn8~R>GRnn&DxuZleL)!kj8vNN6?i{x?=*2?=_guFgp)ACba2Rg8;X^Jv$Z zMWw5pM=5GOr#mhh4V0(4N6|upeKS+#8YE_~-?Q-wz1F6ET%E}QfBs3~bBU~4n33{~|t{O$PI?}h)r2ZGS z(u-MUZf_$e^LRxo2_67&)sB|U3sg*cjv_%Xt>5aFccvL#IpqEArM7 zb^2Q8T{TLmjg7MuUBwA{=`5{I%We{$D#k@Zy}(cBnqF7%f7)0w)Q6W!Wc+{Gc|GnjRXUrf6NmEBPL|Ftt_h}B=bR(w+o__3gic>aNsnCYdJRSn>7~=x zQBSRq8rPmBiyW$MbZ$H9W0c5HnagS>-n!Q*+I7xVRuPw4OnB++u1?NQ#G-t#6tz#N zQ>Kxs$lpkl2-XJ)Y3Ri1q+#ex(2H%_H5UJEgz8ymI2D&pl^K?@1B<7jVAER9=^ z*cw!WIw5`f(j}qRqm#OI&Lh3_V$II^V9(Ln=4eaon=?TR37xBscDzl{OXs!gu|y|_ zqxI}R+SaiMZ^fl{H-;jC6Z8T>z2s4=yke$kkHBKx<@fCda(@W ze6UPZAJGyS(@fApLiN8I;S6naZPW+7*wa#D5yAJg>nbcxf}QT&(IgZO?bPs8F)n)P z@7qLJNUTm~N@!6&7#F>M^hH0o|8I|Ov#6Zqt)Jyc??KTwoz$Os?m+Kg(YMgDpDzv= zK?@0m$39i_*6%eDUeeaL&{CsA?UY4$>D?vz{+Yb=juCz3Y)w#I@2=4IujHjSU+Bwb z6R{l6x!&5LuS3a;dFl!Bf7%bQnqUs~7L`alPpZtR zqJ@OsF%hM(P0&kkzR)+sGF40CmLry;@)32wQlB+wA)#`M+T14SRkjjKSxZ%vqUv1V ztU7%SlF)lh^v$Zwc~9D0gY?q7OY}vkHKDhUgheG9@$wwdoO4=8sBR)pGeL{$JW7Ev z%>*qZ)ZXg0OM+hNkI`3V4O;XjqZn5h(@fApLQhRkqff`?^H=mzOfh1tHNrwddN)1# z(2FC{tihh6`q#Jn)G|(&DiV6Ln7$jB?P_UC^O#64_Ov-ww2;u7%=87r)aY1i?NL_r z(!0p&RMDb75jm&!cB)9IcTJ;DnJRj5oKKBKBLjP9dxBvcS52zwTg;x5*BEyrLd4tIP!Ng z5nj@W@R|q<<5f7;S|=0XC5;HLiLfwUg<}+Uebv5 z{8}R{B=iK`>RFj3YA}e|YdmR_8cyhbNt|d@N}~RCB^==-EYPm#!$LygsM(W=@RCM^ z*F;ztufkEYCllc%jR>!aurOYQqh?Pg!b=(vUK3$qysPW;j?MRdX0LI-EHxI@hxSt9 zoF!{b*9lQiNmyV$M@B;7DD{(x@RCM^*F;ztufkF4Cllc%jR>!aurOYQqts6(!i(2b zYa+ZDufoyOPA0-j8WCO-VPU+hXW|y)?7vonLC}j=db5U}#fUYIo@9)cq31Q~^%X57 zwx5HXH0(R!vAQQcr-~Lm?-7KaLW(PkZGv8U(kZTxW`Y(yO%+!{)Sd}iNa(4jdR;<- zUV73g)T~;LY?enN-{XP2TS|cnZ^h8Rm z;kOBT={cFzwZWpcON-JT*Bqxy6$zC>T<>hBie4)9)peAoiWWVk71wH~OBD${=@?gi z+o__Lp3JOQeQHaQ61BugyV_gS)2u-Y3H5@ytVqyHy({Ww)}TebHtLx%%>*qZG-A~4 ziUhqlD$N?~YkFQVu2R?wW`Y(HdMdQODk4EI)nMqk#?q9QBlb?U{21XF({`#zsCUH( zzD>}JJ=lq*amx|YtCkpJ)ag=1LM^`@6B!r1IPzsaEM+ZK(GOI*akZtG>efyR3DsuA zlo}S8pQEQ2+uKagLPG7W?&l=v#ojz?@cC>$m&|8Lomd(-Kj}?k`w39SMX&N%GLu=3 zXd$6+T_4AZ@H*YqHse*eo(CBhy-s(ZfrP^K8DYjnFa3R+2nz{?>$A>`i(dNsHW3yQ z+h4(8T=e31T3U;Wb|p)EH>2gFohfOl#rcwswfiM;zJ!Frab9EAU|jUl-?xddkWe_z zYpgX$gqJiTJQI4OLp;6Ay9UyTtBjeTg@nS<@=qqhOEE=wO@xKMugWySQu~9tJ*H(qF2ku77?wTgu>C@)~O;9 zUebv0ng|QyRk&`ujEi3Sdrfe)#F<)iSJdpBDq2V=95s6~5nhTZ!fPTdj91~P*^`Oz zl17BrL|7Pa)2r&7anY;gV~dD7C!uiE>^fB>!b=(vUK3$qyb9NK&ba8MzpsczD**rg zhK-B5hpgQ}q)p05Z?UYiZVLPGm^de1?9_dE!CX|GUkUsw~mdmisk(@u=uXCbe) zH+9EBSRVAV9JL+SW|2k^nhheR=G%U^e1wIB@}#$6OsQHzBhsr~QoVOVUfVMcEhMy? zp*OBf8lDdl^wM64-m)?go+?_j7os<-oIX_~v=^dxu}m7PRMD&L8&!mAEn0*2)uLUg zW}_`w)cMo)yuw1l->TeOXu4ZqCg{c1vnHa>Nl0&1=cy3{z1S*e4YpD3zUnPBD$&!W ziiCE4^?sRkeK0P1X>U^Rmsu11E}7a`j4O&M!gD@oA;A`UG7+_@m?FF;!oqmB+ZE%Y zmv+qRwo8ll(xQJbrtMUbQ0cDvprLb1q?hWZ?&qv2Y3NNrr*9=Bls{cvW}PoBH!W4s zcIl;(j=#@2r-ek@!K^fB(Z~=fVNBZ^Bs3C5DQpw;(#SWp_N8&l5iJ@;qZgenRU|ZO zM-Sdk6}>nU%>-M6`gzPBr)!BMG{(eCG;1&}dT~6S3GG@$A5=J6hW07q?=wNm|4-SQ zKx=nZWxAiB7saNe5w0-;3L>2-`~gHlPQH@{R1g?8MRP4h43t13SIeNK!bSpUD6tZy z21(IWp@5;WAR;Ox|50usguV?uk>NlE>9GNX;?8%jHRpQP+4DR3J!9}^^3D0IcdfnJ zz1MCI6G87LL`Rf%%xVpK4iiDo8YE;#6j#eLLC;|#=-q_qh}yjhr{^#c^sGTbc0{S| z*2jvT!$i=t1_|~Ft_Ej<9um7(OS;eUoTuN$$0fEB-M3ihiXIZO>yjTPB1*r9J(q(X zrYpOi2M-ewrQgF|YlMgC%8oODqlt);M%Zg2JWN-1ockP2M3gkbUK8PAx=pWo^B2=% zR4d0WBF+a%$ga;)nHHn;`)(pUBxJ{xmvzZWM3gkbUK8P&(|yu*d#96&dy3|?MwI%^ zxi9?onOL;S_`q#`C3}?U=tcT+Mc8w$=piAy?jMJVh|=$2uQkHMbY({`IGTtkX@tEd z!ozfBM=v;}LwYa%>MS9bJ*qlt);M%Zg2JWTiFPyV&-BQLty+&>J}{Z}I`MycPddXy8oMiM=z z?Jl)7u6EC2C7Zcgq@n$~IIq>tU#!A-wIzwvi2gxByVkJ++)Xe_`)c*sg!WJ4{8hWJ zarHyjeWHA+v8WtOOM7>5UUOpQAfdg&IHyVtGulpEl$=pIx~p?F&lNpw_qAPHII&!j z&_3QuW0fmLmDk9epofI6u+}9f!6@wy#*wz9^Ut2mfJeLfQO`^%!_8>#J&&VHLOc9* zyJA|5(r$mW<3k!~OYNS3b~QpNt=d)QDm)~lSD!~QEk>zKao#rPiXI)eI0s}(GeHjt z)y;IyxiqdF-6#j6IAY8i^pH@CS&b!zw*CY3WRHAu93f2u29Op8$(k7KlRjm#B2x@RKBN2atpS0r?o zh4v2f3QNc48f26-qHnG>!b3uOagB60!6?o|Gr|6>*&yaC^@7lz33^CqUa50Mf>G>g zYmI2_Bz#Aj>;rI-nN4iiD|CPYURuTsneJ%@>)cN3x`idQLSf}X=f(7OrI5yh(%GeOT`BIw=2|17n6B*IqYsIQl1A8TjqosC*>RqDG!aqK2zyP0 zhv~|W^TeZxh>}LwYa%>MS9Y8y9!*4)G{RmJ;bFQ>uR4QdT8wJt*hRz{BnjDZp195x ziHMR$*lQv@OjmZCCmu~ilr+L#6X9XHvge-`)(pUBy=aPX72Uq!?YNs{;w7D zn$Vr9+FOxF_ql49Mz+qQ>yd$;!$kdMQWCNwiZk4Nbm=)v1ihOO9Z{U&W`dr>M9{kl z(GkTNZYJnCOa#4~5FJsR;bwxK!$i=#3DFUyvtaGzty>8_By>)z9mYm{^z6qTeBp@~ z9G6;tS#0wSXYwmkY1{9c%^R-!9}gb!(D#T~=t27PYkcO9A8_yw z@4BJAD}1xileTH_D_WZkh)qUWT8v8DH9q&%cRA4iq(M*Gropd)Z8jh_8D(iPDs9&| z^TRhkc=o66*CXK?e|h&e9RI=3KhiZwq-|08e3WZ|*pyK# zLM>e_UUkm2(l&z6V{JAdHW_8=j7r;c^^(V3e&w_OugALvJ!yMs`8+3xO-6ZIjOuo1 z+_P&~QRo@O{QRhClmw&Fb`2}}Y5iDj=t}hn6#_SpC^4|K*W*5Pzv|Z!hzwEYq7rbQ8HRws(%8~chuLycd z!jHnM{^IU?&$-R_xdw@}Eh@h;;~FKwDB4cgaoX$S?uKclZ3MrS4Hv`vHGF4}B%5sXUPHLU;bspqOy(UZ1m*!XDo zQ(K>OdlxZBb;33N^QRxb_r4##{8VXVlzT?Hul?Km?fX~RSH$co2+!4f{`2GZ-v7Q2 z-BSuA((cDf{eI&bCBZ1#PV}RDnlyBLBCWKIP~E8C=ek5SxFQ&pwrliucjX}iXM zx$tItZ~Dr;U4x#qP2+=q_g(uJTyzg>zgjbppr<5^-fYf$)Hm!s_#1!1HAtlGQ77-W zV<(N0U=(f7Ri6!9Lu30$tJ_AXO{opEW3`K5RNAi5=Rwz?CvDSEdsbU+8oLNarR^Gh zc6JSV()N;TZns|S_Aa8W1|q5xp`mq2KUVaNbhY{z<5sXSZj+NF|u0c=QmUpe9 zMtx|Mt_Vh@?HZap)N|E8=tE@c=w~dh!L-sgLT57S z#W|MftY}3rD(#l5cCO|GJ!zXpJHv=^x1X!62u7vt8dl#r=k&3ip0rIvXO`-dtsJ`u zMy2f<)(Ukd>>Bi>Z5ld5R-bGdy9h?5?HV?79>iQrPuixD-#=dw^pu3rn~kj*4r0wf zB5jXS?@_Z*{;tnI{@@cY{q-v>bWwZ|XPf57O z`|LWyv)a{<4T-cp>P)-8Jv2ycHp5dAp>bu`SV*L8Q7?PsnJ9;8Br$us9tqd5k{|EK zY9W!fMcwl4XQDnx&{GnwVKsQX*ZD#sZHqc~>@2h^67-aWYgkJ>=xui)k+wyB^1`#w zKSY(?*g+$sG^@mrVg?>(go|1448yODzShA2v+oEoAvI+W>7W=^9Qb-SCuzYxI))ii||s7Nw)0_v<$e67-aW zYxEj)4H9WvlxkD&yKfpK=qU-;=q=ILyCl-KD78wx+r4R!pr<5UqxUG+Ad$93sdwoO z@J)jRJtg59ePnPA5@}nMMhU$$zG;x4rzBjXk8rL*B5jM(Xs374Hw_Z>l!R;ak=iv# zq-{|ewe{Bjra^+9l5mYaY5rM0MQkVxC2w8|X)oCG~3;TkqFXie=JB+|Aht(M1lMS`A^a19&b zbZ+2dB8jvuN~``c?vkLVBwWKrYMtY_28pySN@p)IOKdhI=qU-;=x1I&#{PlJ|xY-=ToZ4-R`h^=E+rRLNI9DSvdkVreK4-`3MSYK+MA{a0 z=ldSp|J_H$ISvVWO2Rd+wmQE{KOZEKwneo!5WTC9i6rPL3DTgJ-ZBeIQb;|yYE_-(`2MKyg!Zki?{qN)be2_%iidycn zf4$4>+g@G{67-aWYdp{T-xd9QkVM)Rb+;d~H`kwI?=Nu;5|bx#Lc%p(Z&$lM)z1e> zq-{~J`i{HppZwm?AVE(_xW>z{?@S_XkFvW_Ht*}@Ad&Aiuo9Mp(?4QochBiN?j+K- zsIxxw{U`^C+0%1E!ZmJa=Yt<<$7&&wwnbg_CwE7Ekf5g|T;uz#|5>j((A6jsX)9{^ z0kkU;^pu2aSW7(UZFeD&wne?>uJ=IyATfC&CnQ|MdelMhgA0kYE$YH|+FSn5y?XS) zB|UactwJql5h>xMIRFv5@}o1n=d~V<1Pt$O2ReX zVr}Xb?ONYLB5jL$+Q(1D{6T`Al5h>1aSr+%wU9{Lqwa~hi^OI#JS9O5pKD2^-OF+Q z8F8-GHJnho!_)OhxJECzuNg?BZBaT3=lx!s2~xeq!)Pf55&9~o9e(u%TC z;)_3FcNNDxsL{s>dP>4I`UtlolC~&~b`QJsuet__$rCvt;TnCUb`26~Ta-rakK8&m zNYGOfuF+>4*C3I$M``v64H9i8Yo3yDy3d^LSZ$bAw=GJu=qLw?*;5d%(N_SjK_YF7 z(rRGT2MKyg!ZrFz#x+Q!ttea7jCMtWo|15lz9MVKifM&yQCgji{y}2$RD^5vm8ENt zNZX>c${hWi1U)6;8hwTA8YI%TsJ2>;@rndJCE*%2!s*<=$3zloTa;G)W85V{Pf55& zKVxwX5@}nM&R)hWL4ux=aE*TE?o8RoKR<1#Uo{|WS zE4#)*B5jM(GZUj6rjZ0aCE*%h_oNGs|L=Z2NFr^E(o+_rK1k4060Tu2c)Zv7LLzO8 z(wpW+yCOkPNw|i!#Dm^;7ZPb(l-_JM`UeSmO2Rd)M;-J&xR6NOqV)c=(a%ZHQxdMB z6>=X-77}S&l-`);U)u0?MS`A^a19&b4*Hn5kVxC2^d`13?vkLVBwWKr>VrPEFC@~o zD7~q2%pWA^DGArG8RwwSQ45K*Eh@jS*TxbM^ppfOe6A&tb}xs2J%SoeDBbXsglqJY z`ZZL2GK)Ad$93 zX|+7YD-!gSglpIcr*i`z6G^0PQCjtnahC)=CE*%2QtKSYHAtjwQ965xSz@yxK~G7z zMnCiN8HYsL7L{jVZ7gYLcTUh#60Y&zjd;rAV}J0`+hf;Uzprb%ZBbX<_tD#XJ@A|Q z?<8hVLAb`>+Wz1-_WMOiq-{~JJ>}f(17C52u0evHl5maJTb)0$pAV8q+oJyQCFfcB zZrn9U&{Gnw@mXuTAMNLZB+|C1_r2sX+p}JI)2=~+o|15ln_B;SOWz+Pk+wyB@>ajN zeej)5>KY{IDGArGGVEE-4s0K1Ln3XDI={U+(%Th@&1QH?!s%12|Gm4P50XgRqVmmn zu0dk60V{B`F^Yx5@}mhzWXzd zRTA`+glkw09`AL&kVxC3`nyJ5gT!VtJSE}uYpwr%o!x7xJxCI1ThxW;J{kRk#OxVw zJto46B5jMh-etdu@rndJCE*%> zWc}~2+nBhJNZX?H&Z;r)lAxy~T;ucB|9-RG`>~Kn+oJSlt1*9&pr<5U!)Ba=K1VGi z()OqeF?W&JY=);KsNpjwiL`q;Zt?Kz^?u$poKU*M)AdNWMlZRq8AzmUQ926W^tE5z zHAv7?60Xr}&^1V;ZBeStQ?A)`4HEQ}glqJc=xaC4I`pDoKB+~Y%CvER@(&xGc35_`6DG8_h2EG-vmdKLByCZeMMpVE%$`n@aE-nKa19b^Ta;DTL8660@h%BwVAfEM0>{+7_i%=IG}n=qU-; zu(3pIYS$o$^pu2a^p(Dki6qjtD6RU(xJ!bbl5mZF#^M?z(zYm_y^L9c z1U)6;8vV@6XB-k~dlb*%NNhI4QxZ<=dW^2*Z0zsSOK!BUx4~)*PursO<|e%{wvFv1 z=qU-;c#oYA+Ete0Cb1!rwngbJP3y<#gKN_uK~G7zhV4t-Q~MLrAd$95^)G$;u_BS*05wlZgvOO!V7+w+4Xt+Xxb*s+_UU6G)t zBwRy#YQ62+^MfO;v@J?+gdY8a1U)6;8rmD|ebAmC9BHL(QF=G^=;tKpDGArm9%mm* z?D@fwR@xS&H)fCViUd6+;Tqbj?PH=nKRD7#+oJSN?=kL@pr<5U!$#_ZKDOKQgCni9 zElTeYAM*zZdP>4Iw0GX;D0_Zzq?NWsy=K|(WGcuFEPG}pQYiL@-wkWLzMtzW=rzBj% zYEWw**C3I$MQK$t+7$_UO2Rd)C29@l8YI%TD6P&${~$q6Nw|jfD6K_ZgGAaErB&wW z=OpMU3D>ZZL2GK)Ad$93X|+7YD-!gSglpIcr*i`z6G^0PQCjtnahC)=CE*%2Qt!ps zP9klK(%DPQ5}OSPdP>4I`k9x{I3&`xs5}dcc~EC}PS8^luF=mRuiW^bok8CFd+Z)? z_2+I|l+Gr9`PO&rzmu3f1>qXp?IV%4Md_^g%U=!+67-aWYjC%ZMA{amv-@MO``%s- z67-aWYxFA<2Rc+F(zYmFrTF~gzOQSLpr<5UgS&ks(zYmFZMpK~J9P~b^pu2a^eaVP z4iag5)cM;#eP(Eo&=sigl!Vj$ikEAUNZX=x_3JwS8X6>KPuC;i8vV+hYmi9WqI4DS zFHgC1KUO5@DGAr$ZXb!XJ<4|F?j0H=e21@lO2TRG_K`^2qI6Ytl!L_V={X_c8dmb$ z?IV%4Md|ABs1FkKl!R+o4Nm)mkyg?k^`vY)eqA&PT``Y#RT573EA*=Kg+$sGrK|O$ ze~_3xU5|uoaJP>{+7_i4IxZ6h}ZHv+_ z&=_|~&{Gnw@%cmhgOOI!7Ny;+F@KPtrzBj%W}In%Fw#oeqik0$=PnYy!`D3}K@Fcd zNu=G&;oto6`LSy_p>&6*=Y)i7^pg9!ghbjFrK8~A7;+5~^pu2aaJP>{+7_kSJmq!v z#zog4K~G7zMsJCGng>awZBc5KKYxSJAVE(_xCVFoNTh91>Rm7V#oP9Bkf5g|T%(T+ zUJepzd(@M*Fa4Z-XV{Mw35_`6DG8_hnCKcL(zYm#cK$76*B~)_x*iGF=p(gjkVxC2 zG-^NpAyEzz^pu2aaJP>{+8(u79}Eo=n#sab5>9isk3`xQrCD^8gT(CVdL&%KO0Ii~ z{8*7l+oH4@81+Gdo|15lzLIeb5@~zX`Pq8b`-9Q0O2TRG_GwKOMA{am)!FDDBxX;i zNw@}g`$(j1QCek=eolg(l5hK*=cG45X>8XUpsuqy z{dA3eXDaL!?HVNLDGArm`<(QKF=>!U+oJS7r}zKS1G@$ZdP>4I^gbuODNPzA z(zYnQ&*>?T{K>9Cf}WCa4ZY7vZ+w#miL@2#wtBBaya6>HWT=9D3Vg><`YKu1CT(^bW{=tQHb!Ta@1KJL-c3 zJtg59dY5Id^Myp(7Nz(5j&?R!G%QH z7Nz(5j($#po|144y(6`cB@2nPElThA9pe=VdP>4I^sd)FCN3n>wkW;dcZ|Cv=qU-; z&^v4U*uIcR+oJS--!XrXpr<5UL+{@0bJRj2ZHvNy5T7a*XSkp^Fb16Ta=E%J3e^l7)#pGb%LIfaE)GrD4IdXI7q5@}nMde`Hg{+(Te1U)6;8hvDN z4H9Wvltzg^IDWIPL4ux=aE(5~xdw@}ElQ)^`5*hXu0evHl5mYaQo9C;v@J@b_Gj;S zQr93sPf55&pK)A+MA{zp*6lMc`PQyMLNi%-N+L9Jw~s{H7NuEql%vnJo~zl@^+>pe zm0W9v6_K<>X*DqFg9JS#;Tl$hTKl*LiL@!0a19b^Ta=#P9rsz1 zpr<5Uqu-I@8YI%TsIS`m$L($39QUM>pr<54BhT(gq-{}pAIB(1zZXZjTIeYW*RYc3 z{h}n&wkW+4ItOoObQ4(oel-`dr?n5R)Pf56jwZyz%ltkJVrT4tl_lwd~ z60TuAD(@F1k+wzYeKn(>lc1+0T*F3&ykC?=+7_kv?u_w@1U)6;8aBe^{h}n&wkW+n zXpFlg=qU-;u#r0N7bTIlMd>|AWBwpPPf55&zcW*F)IuU{i_%xeWA55)NYGOf)bP2M zMB2R^<9?s6;e^r+Pf552@BSo_wngbEjQf^I&{Gnw(QDAxB_z_eDAne;|B3`XCE*&q zCGKe+B$2j7sa1~q$Vkvr60XsElxvVk+oIIF#{F<4=qU-;=wpd%kVxC2G)j#7`bf}I z60XrlIM*PNwnb^Q8}}!Ypr<5UqmR_CK_YF7(x^S|vm`-JNw`Lzaa@B$+7_kRC+-TJ z?-!+~Btj$42T7!DQJO_ZIr?1dxuT~eT*FG9_luH9+oH4@81+Gdo|144tHHcqltkJV zrB%&nS0v~u3D@W=GA}uav@J@jv(Z0D&{GnwVLdAE7bTIlMQN2e`Z)=DO2Rd4WXStP zNu+I2S}l+9iUd6+;Tkr=<^7^0(zYnA`p39Sf}WCa4c`4pB5jM(*-Ok4^Zlaql!R;a zGcTWUNTh91c^2mDb`tcIglp)2ZS{4H?dr?wN!lMw+oII})Qj6a6C~&<3D@Xv((!XO z5@}nM`kzLlra^+9l5mawMj+Q9k+wyt|7lch8YJi`3D@XvHagI;B9XR5ssCwqXc{Ew zDGAr;Z)kE25@}nM`k!XGra^+9l5mawrYYATk+wyt|7o^v8YJi`3D@Xv%yJD9X}Bg9JS#;TpPMTPr5j2Z^*TO8rl(r=~%Io|15l{suGGAd$93X&tInVACK$Pf3JE zzAcnQ+7_kt^eBg(rqX)U3ck=&60V`^FAZQ2S0v~u3D?lGoLXH4I`UvM5B+|Ah zjdofEHVqQ=l!R;ak=iv#q-{|ewY3Ut8YJi`3D@W|j%$!e+oCl4Xw}&?NYGOfp^@(w zC6Ts8X%-#j=yR>-ik^~ijlKd{5lLH=Rs*9xNYGOfu34I ztR?3AMM

QCgji{y~DCl5h>{QTcvR5@}nMR+*!plc1+0T*F3&e7`7(v@J@jy+@Ta@4IbWfk|S3683ZBe>!aMTA0dP>4IbZ?^WK9dHC zv@J^aKaO@qf}WCa4c%j@yU(OSB5jM(eVn6zkf5g|TtoMY>h3dXkVxC2bU*6o=OpMU z3D?j)ue$q88YI%TDBV{(#w!x^l!R;82$$cZCy};A>Hgp`?vkLVBwR!HAnWckm4igu z7Nz@~$NWKpo|144oe%aIXCaZcMYX%KF-IjqPf1Y2=UNhJ_j2eivDVLfuAET1;VB8% z=q2}aH4Wi8T!p^pu2a^pU|eNTh918YOg>SkoXuPf55&AK_es zMA{am(N1@XH4PH4IY-Gsq(UVBq zqO@8b;}r>dO2Rd4gv;;IlStd5wCW$@E(v-{!ZmE9&hOEaNZX=x_7bzi{5^VlO2RdC zcBea}HSUr~+oJL;EYAmnpr<5KgZqPemy`Ol&L-WqD4k8}tx&C>_j67^gQTYfz60Tt*+_XQaHx#NLByCaJ1sdZn33^JxHTn*g#$DeZjI@%rDD7sA z`GW*KCE*%6^NQU*5@}nMcI9I3TJH~rrzEK1b1lJ(L=qU-;=q+*2>fHASBdw$@O080F z6>J(L=qU-;=sn6cNTh91>Ro!PVACK$Pf55&9~oSOMA{amQ9^GOY#Jo!DGAr;Bb;lH zNZX<`+Uc!=O@jnICE*&}?IV%4MQPO5TLqg233^JxHTsO>48r4ItR+tSgOOI!7NynM=pQ8LDGArG9yRR`Mp{W*lvbIepOc`cBwWKrhG~B=(n{K* zv|5faX0stdPf56jjd0WcV5F6_MQPPP#$6Khl!R;8NImTjMp{W*l+Ipa%wO*hhNmQ4 zqn~;C9L2QKwx~P{%kx2-Ih~-VBwVB4Vd`gh+UwVsJk_7mwkYk->nozIpOc`cBwVB4 zTkGd)B+|Ah?a%9Ls7-?eJtg59|7vxvkyLXOiL@Pf55&zjOIO8YI%T zDDBVd>$FXS1U)6;8vPDz*C3I$MQMLtU)gOMB60V`%r1hxkoJ86d zrTf(M73!uzf}WBHjp_NpNGoZJ(*1U$99kXsT>0~Z;VB8%&^>)xU0N|FBGa`f-8VSu zg9JS#;TpO(QL9U7kVxC2bpPXMS0v~u3D?j)mRem(gGAaErTaKX{~$q6Nw|jY71ioe z8YI%TDBX`b`Z)=DO2RdC&#P9K(jbwxMd`lUFzlg8bJMA{am`<%!8L4ux=a1GrVt<|M8NTh91x?elyuJ!YS;VB7f_{_<) z((dKZSEyS*@40e9>4v8yT%$iZ>E~)B(zYla1$~9OX^^0&BwVA{plgsw+oDvP`U-W^ zAVE(_xJGY@dsZL*{9vS&v_+{^>MPVug9JS#;TpY1xdw@}ElRyhU!iUqB!v}1o{|WS>G{D(D`|_;EIP{3=UUGdJtg59R`Tij!AL7< zi_&Uf)CUQAO2Rd)2B+r-Bdw$@N~@aDu1L^R60Tt_F~2uKB5jM(>TL8667-aWYgmt( zo*#^~lC~(VGDklrK~G7zhK&r<^MjFA(iWxFa*Q#X4GDTm!ZmD!o1Pzxw34(eRXnYxFniXwBg77Y!oQwJ7b+-}3FDL4ux=aE<;( zAlD#~wnb@w{@Agz`glcxo|15l{$`^Cm4igu7N!09PhJ=rB4I`Wv%cgGAaErTzH_Z9{_uJtg59 z{moylK_YF7(*FDnelj#j&{Gnwq22a4A0&~sN4<6Xh=+#;3B4IDJS7ntd3Hx4ZHvq-{~U|8cY{ z67-aWYv>+J-F>EVkVxC2bRXyFA0+503D?lQqPqJ`8YI%TDBX`b`Z)=DO2RdC&#Ue} zlLm>jElT&*j`4~FJtg59x_4K1pGkv6+7_kzgU7f_f}WCa4c&vRyU(OSB5jM(ea?{n{~qkf5g|sNr)hiL`q;?*H^N`k2@?oKU*qDGAr; z$LcgI$A(1O7Nw)`!S4wT67-aWYxEj)4H9Wvlxp)$Z`>dApjwF&^pu2a^p?1%a*#;d zqSPvH^h=>Zf}WCajozbNgGAaErQY?x+lB@SdP>4I`pDoKB+|AhjS?UGhwYdLHTpO~ zPf55&AK_L+(iWxB?ghs~g9JS#;TnCUb`26~Ta-raPdzs@NYGOfuF+>4*C3I$N4<4> z=_R2-LNi%-N+LA!e2_%i7NuEql%vnJo~zl@^+>pem3(@?Xrz_2MQJrK>VpJ5CE*%Y zgVXy(Bdw$@N~@aDu1L^R60Xr#WL|O-X4I`bytNI1*`Flve#?+$BLzNw`KoV{r`4I`V|(}Ad$93X-|FZe~_T3BwV9kDRK=GX_?HHrzBjXU%7J)5@}nMcHv|9Y_lOjPf55&zXItRB+~Y%o9xG)p1)Tu&meW5 zT6jt#H1h0@MA{am`|U4ItOj#` zkVM)RrF#}fyCOkPNw|i!#M~bwk+wzY-pkQHNYGOfu31adLl>QJg8RU1U)6;8oed%X&xkzwneE`#q_y({)CHX9Q3l!R;ak-;@cq-{|eCB{Au33^JxHTnqW8YI%TD2;ZphqT#{ zpr<5UqmR_CK_YF7(x@GKVLlIPHgJNTl5mYa~UG2MKyg!ZoZ%<^CXvv@J@j%+b$D&{Gnw(O1Y`A0*PYD6N*qctwJq zl5mZ_()SULMA{amRsR@wNzhXguEE_t5@}nM&R$}cnD+SkVxC2v<}rOuxXH>rzAonpC2TVwnb?@J<6fG=d>QR zf-m%xglp)YKCQ$L6G>Z?&I?9;kf5g|TtoM3YdtCr5@}nM&TmG$B0*0{xQ6br)Ou7J zB+|Ahou`fdL4ux=a1Grns@0`5NTh91I^P`qoCG~3;TpQ?k!{6T`Al5h>}&ucv@4H9Wv zRJ-aD^9KofN`e|b*OExPmqV+-K3=t4IiYmJQxdMxOMaS_V?!csi_%fhDzIsgpr<5U zqt~EokVxC2RGV4_HVqQ=l!R;ambj;KkVxC2)GDrzBjX&p56@B5jM(?4wm@(;z`lNrXl|KS&~Ni_$DQ%F*Xq&lNo-;TnAf zup*MSD6IxYeUPB1BwWL4FrObJk+wx?RWsTZ33^JxHLNA(^MfSPwkWO6M*ko|Pf56j z^{9M)kVM)RrB&wW=OpMU3D>ZZA)g;4k+wx?wLHcv67-aWYuE^v&kvGF+oH7UALA|w zdP>4IY^2WT2T7!DQ965xSz>;Eke-rojeh3kGY*NgEh^8#{CtoEJtg59&$f5gT-3iu zzuA1=-VGJ+XzR8`ef!NnzkTk*;@zJlW=}!5#>ed5+D|;u*9;pHXGdd8QxkGtUAy&NQFPp3(^#wVY6!D-e~ z{8*7l+oFEzng3_|H-8-(B4ItOk$wI$ubn?NQg+ zAMJ|7W-~k`;k32HgWh%*5@}o1-7db){^%bhW>426;Tr0Hy$>!V(zdAczWKWQqo0$Y zrzBkCOV- z33^JxHF`_*H8qK}ElREO;`hJ4kBKDcDGAr;J<2smq-{~^UAMaCsxc3$*E&H@Nw`KI z8CFEn9(A4lpSfXZkkE(|o|167k8rL*B5jM(X!pclechM`HHtbhd%7M8*XSelib&d` zG-`kQ%|n9(Jtg59ea3MO5@~ysW}na?(PpydDT&a?_luH9+oCj!j&k(5)^jy`dQM2V zhLv1vh82;tMQJrK>VpJ5CE*%D<7_ zL=tIRlve#?+$BLzNw|jEl+A;#K_YF7(%H+HB}mXy60Y&=cCO|#4vDlqisx`7cy?D3 zPTQ=u_jUby6PwLTxA#8p`F&jKwng3S<}clT>}@aTzmu3f1>qVhxke!C*BcUPThtSO z^`+Y@Z+BVOAVE(_xW+rI&iC_taHN&AMg7bTUuNZdVb>r*Pf57O#-1E_S3e&lk+wzM z>YA5rUvcq^x&{e)O2RdIk2=t?B9XR5UHtybx3~J87k3R3^pu2a*gAAiGqf~Fr0r2J z-~Qc0UeYy4Y&OGF5>EfP^}n~|`QRXuwy39`@h98Yd^R*l%$`n@aE(4vdpSs?ZBak< z%vWr0f4@KK+Er+fuATfJ7O~N&-N9Fk-iL@>11GhMieolg(l5h!Lc10p>i~5_tKEV7z zf}WCa4fT!Z_2&mkr0r3EVaF=wE)tu~@RUSqJlXoXmBao9k#;Y~^RNHBK9)!$2&Fqb zohIQLz2v@TAd$93=_tJ8WxwAwNYGOfuF-4IHAtjwQLQ$g+cikgQxdMB>oHng>PV4D z+oIGe-}i(6vulu`rzBjX_bAsOk+wytcRl*P|D$V=pr<5UL)Uh-x>Pwxr0r2xY%g1$ z(=|wF#0gJHINe7$*C3I$MQOBq{YRhOHAu{!u1CT(`bg~>B+|AhjoRn@c4&~GrzBjX z&p56@B5jY->=PO!+Dz6wB@r5$Yx}WcTHUrN&7z|meXez4_7sF`SjlldIMPbmqO=+q z^+AH3l5h>HL9Kl}S0vK*sF!E!*=$H?g%s_oB%HRExEF1gMA{am)!FDDBxX<7BjFm> zqi{Yr(n{K*w8|X)oCG~3;Tk%pjj@D8+7{JT%Q0S&pr<5Uqp$RROeB%EMQPPP#$6Kh zl!R;8NUd`m*C3I$Md|Ei%n~H%DGArmnb*f2-{vS1X?qmU;Yjf8t|X{&rN%@Ne}0kn z(7xf!w0k)o{7+x(zjqBMliL@4IdP_V|IY^{!QEHX9e#QUk8YJi`3D@X7$~8!&ZBgo7zjygpx&{e) zO2Rez$lw|z()OsAZ(qEpt88iuBsAiLrzD*2Bb;lHNZX<`+I`zoLxaTZ>3SqwqmR_C zK_YF7(y09-e;yhn=qU-;=rfLMkVxC3{%re!*M$ZN&4b}7iO|TiI}&MIlxERUjy~5a zSAKRkJYA23Ygoyr^T8l8U5nCcVAKZ*dP>4ItOlp^!AL7iL+7_kN z@))m3&{Gnw!LvIOXZG?joTxx|r2UA~o!sGtUQuNV=Efrgzl!SB;6%2tw%&PuC;i8olJcW+0KaMd>J< z`L2KN8YJi`3D@A+9f`Cps@3K{bqx~ql!R;aD-(N~2T7!DQEHVxeC|JX4HEQ}glqI3 zd&mFg$4=DWZ@}^ z(3s8#gGkzeXM^tsk^HG8@q3D>ZaPv?V?R?-%w)xf9^67-aWYxI?j=ZZwy9`*8U zJ?rzqXjdiSw6#QC({~N6se(w`qO>|2{e#5p=`;z~upTv?4@O!^Ta;Frqo0$YrzBj% zMh5M%csWR4Icy>o3ZHv;Xe~h~%=qU-;u#tK?AB?n;wkVywj9G#N zJtg59eJ9T6C=zLV6wl#ELi z?z2f-zuTKsurnG_hlxMC-^aF>{_cC7-c2wn?56R0ySnnozQapT*vi$5_x|2;`=PF} zi(pjPP2RRcw~Js@*exaPwySMP zfu69Hu3DtpT+`S^Fe>b(p_Z-|FAaLaZt3c-vyXR;T|~P#EutEc8oHOWA1iuBx<7Qw zH=rD*Q4)*_JCBvl?p%YOuvLynJo>LtAG)WnA{Z5R)36#m9(7Jn*zH)o8ZBlQvDq-H z*-gV*;z6|Ch-#ieESux#AG-)fh22uJ9;LH8KUVaFt#W+jzq}Itd>6r}u$zXJ;Xu7g z?TVhTrSao`@uwKCb`gvUyJ=Wm9H>`GgPyRZ@q;h@6O6mN2u6k7G^~Z_?oZdCCv0i_ z?W13wGlP%qCBdk$n}+Vbjv0rZu%)3@je1zKcM)?`BPI<$gN&%=8R<$-{bkY+VSghn zMuj~cD_!MW=m}ft>bR-DG>v|AMQkEUX)!A7rqOHAHRuUj>9+cRb=Lr~i72JTsIZ$x zZ;1yg2R&g+L+x1orIiCjZ;7w=H3Or8jnT1vL#2n}||cj0(GH^clxB=n1=}tNAK4Kx`tarNyXbr-tTQY1kh2u6k7Qqml#UL^&3!d5x74pmQRW!gnBD(t3VWzd@1HRuUj>9+NC zj90q|MupuptS)qJ;G-x#VM{~nQ1ygXj$H(!!fqN`DXCZKSkV)<($zXtJ)vprA{Z5R z)3BDVGcTWU=n1=}+s??Ey^GLlb+g5_ z*s*6?4&Uo`5`y+V_;=s6f5Aof*cWl^kH2gGZm&J&_V2y-cKf$~k$v0AexHfYUi9_* zKmE!dbkCdK`1Sh_xcZ(w>g4@zzJa}MnuO=-0iU|%_GfPKLeKB<=ih33ufO`R+m~N* zi7b1Tv+XJOzOx@i5r26~vqePR^b9p{FTcBE zImz$in0?Bzb7o=*4L!l(&stejdt&6BUJljfRE{JVrRP}u2`8ghM3b;%MGpx*Y2(i> z8Qp{ZKQqB7rF7{f_QXg@goi{vW3(dZ$!C6gIU=QXuEIkipXOOF% zjYU6S9jnx!heT@&ZCvqSOTTH5VAKaL{#4FaJ^2Ri(L+M*D#o$h1f%ra%<5PzD*5dB zQhQe0jwrQvYvfbdM(7!%sm?pLOyyvdo_vZnHfwOq$mi}%gJaB0&_g1hs4H7ZjBt!< zZThvvSYnFSKkVr+7{!)9 zmz*9F`K`{C1_?&3deqXCmOa+3>PGL5I`MWzLiMk=Le;G#dJdy_MCOvyLn6Q8yDB*e zMzK}S8u|50ODn%pX|~P{qrL4W7?t1ZWUdyCKKe3c^c-nKzkAR>-*tQLtxqeC6?2l` zwLCIc%n6D7VkL8B1zPqYqN1L4ep{cP>*&T9rQ;K$8pq@L=+Z+% zXOs0PN`g_ESEjMO3oU!hFUzsJKIkE#;}(5oE(Zxlu`SGm+HPEp&{*<+@kzP>Ucjqs4rxN^t;`qDy!1fz7+Bc(Z4^pMa<^q9;4 zSD`_IQ5vuQzegM*mRJG&+7sX9X({TqZ*I0yietFWRd`59FH&;C($`;GGX%jX)>DgZ z|F)U4B6JjvKkuDI$(a_TSpS~-5*lm`n$^zv?3+DZrqp7CpofIU{EJR`;+!tB}&fxY6ke_ProK} z74_6&gW$0up}FKAFMainTt!-pVs6(OQF0Q}d(2q}J2Zk|6p#9>p>a3H42_~OmYi7s zAfXYpZo5p2Q5tur9@Vq9?6E&9DnAy@rw7XK@SO) zFM9B9f>D~`qW{kXj}?!PhE?GAMk*SqXDx5r-hy~XO41f!mH&TnnM{N+0iB6CI0$?yHG?JwWDMKPt_ zxgxRIT(~`U@9!BJ9h=L+C~4gH-``>fF+3w(>3!{KeZAxl&7f>E~|a9<`-&p5AQDYLU{cK@SP-8$JIa zjZR`w+a)naEmnhv2t${>k3ad>GOZ8X=2tRT8uRO1(L-XhIX}ynxpEB>jQZrQesO)Q zyd1AR<=kx5|M-&gvQH?bRj*Br@Q`@lOCFQ`ah`l%DYf8r|`ovtbgJ~=MXg?%WH_;zQ zyvo6}7^SvQ_j7u#y6>ZN{9sDEHArkWkKQrD&1sD&{T@estuZ` zSq(BR5*i=RdgV=veFGAV@)_=$w!`0(_y07FD6M9LTRi-Fp039HZ~EG=9vWG4rlqI{ zzTyV|hH{XQ-n}09O+%wBIipm*$nDYP80p%ac+K^9XpFQ*6pzBJ!DHgH+BKUj`ABIn z^U)=tx;gV}zckv_RPsoRQL6uwPWqRE&^Q=vRO3oSsYgXhnWse~gZe?#nvdK@-JJK3ans-BQCgh1bM3nA1$3Nl6 zN7}2Br^fIMLOC2M4VC$N38TuR>l*Zs&@qgATZV#4PGXK4HJijDg0-gEAV!1THAoK$ zwU`)*Qp1dvtEi7T>iitXW`eCx8qva8zL}thgwI#KckLz^r8Yf{R~>7uJv^EXVuYji zZVeJXtCeHPoR-Z|JxagFF6B zN4>*oC;C6j9&@5E*6VxmJ98zOJ?58$^z=ph^*#;>Mm_PzPPLu*Hw*-8+Mb;yf9>DiZ~yM!h&ur%BJ%#^NBzkD(?4u)S?u(bt0a_ecu3e)5zAFO z>McK!D-w*l!B3vO|D4;sWt5|1%iio6=|1A&XYbHZ$)g;9c=cJ?O6DAnd@XzQkoe?< zXJvaE@v1=*j5>Dgto?Vs8}*UpU`u2hyY!Onj&jgLVzaUPEz6@zf>F}0kM8Ul=}PbX zGpd$If>CUh^Rc3bgnHC@zt?*3Zh}#()}BXK_iVwT zxuSdn6d878*0dtU(Wn))L#Dz`F@Xt>%xVaavQKmF-7kNwh?^o>_w)5*oXr zP46Zc#aUt|Hk(mX_ka2sS(6Stx(i=p36FY<4T2sL>MNK3#YKzKe_wh?uor&2qh_gQQ{YYsr?dV2YjGD?c0IQF?{m@GJu8nP^Wzv@!h7_dS+#xSk$~ z`$%VkQNM7bW4W@}P0&MPv(Xb6)yk3tqx5?mg*jKVXQV5=>D-`WHc}%kMyY)Dxq*&i zjAS~xaeQ>tKk*ao4%#_a^pI$EgS&B;#w~klaSyxnud;<-_^hY8t-kWbp8%2Nphqn~ zh}LUCq{d-lvuRQ4gLOHS-$++2KXSOc9Q2S-o36`2f>At%z0m%j`BIrf*-zp1HnJ9lP%%Ub)iOlH(o*ebso}Cvo!r zbeDzYNPo+oz8M^Mh3Ff_aZicHu{u}!f@9p{p)W>;hRPB5gtXM#zgkn@Xg}^-P|4$t zgxv%^Bypd z-fRxlV8^r;9Uc;@*|?Ku)*vxQ-DH1tU!Uh{uJcjP`qE~t!Iq(Kmqx2(J`nd7>ObxZ zn_J9KX{(ILm0C;?>i?5Qhh~CN`iA>dj?5K3`kH(ks}su=34QNAM!Qi8Z|xXm7^M*| z#!4qLR~-99#8|?ya@L@SgmM_8(r#jo8a-_$*rQ137}jl<1fw{Dr^cdV#rC7#6?J}M zZI^_4bByz;VMcqtHrf@V)X!sNNgTy+jI*(%1GcNho)916TifD?>LqaL-x@IY+5sW(hbyuA_ z?M<|#tsL}_&{3$b+>v0Ej{0;xacLsUo@y#Qs=-Lt*FELC6X+qK)>D_91f$q`dZGP4 z%N{)>9{uo#pB~3>H^C^j>6u^~eaa($GW!a(XM!FQ@BgC*o*p}Ny9q`eJNBce*H`Yo z_+xiJJ+3al$ShyaPy@YP#W5kF+N`f3 zGc883-^?1UTOHk~L8Wx_#hmQ6jzZjjITQ4dP|a$M)mDRpX>(Mh z#VDn8k2_s|2N50;Y71J^)fz!CN*Z}3ePqho6+I+))BzkK7^ReAtXvb}A+ftYm=>cr zcda$z=<11xuvxQCER9?C=pi9{+<7`w)mW?S!STznPe$?!R5V&B_VeqfZYB-KAG+ zkYJR?+<23gXQ%(O?5PjvTBZ7d_iNjel&y20Nh1k*NN60q zwyR?j$4BQIJZ^p`NgS)5wMK-8gz7{0o2+xiVt%?y`T3hjowW#O4r_B{v8!TkFLsp;a#l` zPApdwVLLQWeFkc%$Q3~LgkBdpWOtbRGabMA19W^Y1Ma={dixSMz!&Vp5l$Y2DN?X zIQt=?wp+guNPAvEFiI^y-aypyBLQhJziPV?bz;Ygg!;{tD@$L0^Ui~Vc=YZ~Dpp?kmL8lV&XpP68k?nsN2l5mYf?<%!> z;MzUAC;Fb$O%m$oaqY}CEd5pvrp2gJzV#EfLjLPf=OXOSo+X2agzUP`<%yd5s!Kky zy~~v!^>mLWA}tak_5ar`k!dlCxorjTf4zU`9MIkXZD);oH?iK8D_hqFBDXCz2zp59 z&F?yn>s*mwl#Z-&HW7=CZu<(`m))bUzWH}pEmwMaxz3e5ajf#&XGY{V(cB&-nKhWM zzRu>~I1R#bq`ze^zn5tqy>&K9o8RgTq5($GLqc!Njw9U?Z^%r{QT>~vp|J#!Ut5&t z5wFa4m0x-cq5+nx$phk)V+V76qy~vOs(-O^r7`6yz72UOhdo379~-HWll&f}5&0Fy zl?Dk$y;7S7S@!55kzZk4X^>zP+uK|YM(JxR{@q4PcQ-M629e)XT;+-cqw))h zM-uE4N@;hG8lL{mK}%P?%fIzoY6QWkRgdZiZ0=F{rC3XsePuqn^pMDJz^-ydf>Coj z9x8fHc=Q7j`3=~W28lUpSN~v5Noy9@gSC_)W)mf>EHCWC|#u*DUE!!d%T8c5UQIf z(}-8enHHl||1tZ_gvJm5#=7UXf0g~;kgGvxtQ;u~l{r_8(s(?Mh!IPpY;OYjZT+Lo zqAcG~I9zfPn(d}}uw!$s7&XsVL&f&IFyE2T{8*1AB<83?^I+ymtvyzEhrdJLc!km3-se5vJ!+Nu;*nOY zs@add?FBPohq<-55{n2PcWJ!h;urbxVLc^bM(ee4j}Hlz?^eI_;`!*V zh&k%z+rN9rO9o*%(qEf#Uh~=TT#-?l=hg408gydz3_|^;&J_tpu{J$B{hwuz9un%o zaolzjjN08wwDP|9d9AN$hKqi8Vy%RP=JUFrGp#vl^x(N1Y(HAP#E8n2W`Z6PTKh(C z-c2w{DMfo*6T>som0tA!-2|gJ63qm^uhw$Xu1r1R;Wi4D&!y5sLU!D@HftOvB1+mC zzt*jt9;Vy$@H}T1YTt>Av>5gEzyH6s&;OU|sYZH8Xw5kF+SDMyD7CTCnX0-Y^_0pQFF~&;{9*g^Q&n6nCO~V)Pb%!#Y_~@?OGo_ zBy=@u*VsPNVwA3BP4oHEl;$-9SAbj%WUkC;D`c)LVua(GXg4uO=^h=ltEF+u)$owe zRlLxiH4c5x$F82XC&+c3ag2O}Y5O1WB%y0%b)7RUM(Oue4VqNb2oDKeORU>2clCJ> zoW_;d1stW220bKrH{EW6QA#OxOxHwsNXU-gk0v5&^(N?!wfAzydtI5X-uzd;i>t z+J{o_)DD^Uy<~GgVa}EIfFnwGDFm%+`r|BoFw35HinXhxba~}pDQT~&7#ZLpAwBK> zC9yP}WlwpJv{a^uTJ2`^j4gZ2yY8yc-dg0aE(c3U!tb!KJqq}HiVB6LG3);C<)QQy~3Ee@UUCc?tvNzW`qjcAR_BxZW9O-Yd z?+Sl^dQ^@`mq)$Dwtrjyh+eDxVC{}8T^_@kpofI^gLPj(=Bi`!9wei9q-PD?t)aUe zl$P!~(%l@g*>7foQMwN+=-mW8By@CFb#7vN_7)0X3iBos`EHL)Sd}?NT|I< z-Rve9#ql_aMde`oQOR|$R2h$y90w<~&>uIv*dB1$Pm-&~g?JWN-1{C+eMQQUo>33`}rxwmcT zvd1S8c>lKOx(4YXp*8%q6O2+yQ8#lr=piBd#E6JeN>Mj!jqosC+41|)L_|p=>Sj%Z zhv~|W-;X9n)VMQZCUhPZ_e?Ndo!w2l`ob2~xz1~2zeeZLvD>3_gQ3@=9rE*!@Q|RM zBIB=}u>`>=X~c2!=%q1@2oDL_@q47N|E`IMTAkx8jcY`-45lkPes8h6h=`KL)Y>PF z@GxE3@%vgMJdEOb;!My(V)q^KBp6lR-)>^|tw#HLT%0@UeH^hm)6;HIvvaQW9+X(I z=nW^a_R%wcHNkZCZkJeD?AD-%gx>QKtC~4iBp9W4zSOHF=3Q?~idEn4a?nFU?{kWy zFz1Q{qx8;~IEFK!w->(dXw}@mT2{PH}!l?U|s5gugSYJcA^`DE(gNiXIZui*wv{ zt|Bc)seEw-A&Eu3mLAoATyvmy5@yU#FOyJx)GJG-#VFNg)Ju=5#qjtAldPrz=txHaVQS3J@ zJN~cbioHmqXw)-PYOz7kLqa2Xw6Wa;qcpEfZFflxc=Sf5=o8f5twF-yKUelzro|}z zUe8hVkdR)CE9+cET8!e1IupFU!)p#Y>x-0Tf*uk)Z{JNYN-4!%Bx@o(BxJ|$M-ve> zzma$_%N{*Umv0Ns_(eU6Z<}rJ;%)CC*RxA;$Bh#ftv_4!!9zlN6VZS}1f!Hvl&K}& zkfsqH5-d|szJZ=A5@AbYs`G^!;bFS6JY`)YX1{<5!+`?d@T1E2VhL(QXZd$+c{UvyRIkd{US=2Da`~uBy{~!?>0F)SB%p2Qhn8TP3YQmq@}CQkt>ZW zaYW`^(LpG{0>6YbK zG;^{XiqiMuRR_%BoGW@r=(y<%^XnQU!6?;@zO%k2bmd=f(2+-b2>QBl^SLf*;5OT{Hm`+Y1Ip&{#$JOx9uB*hlKiI9O>Nzqc{@H1bdEF znQ^SxH)nz#5?W=(QQu84ipOv!=poVeTUu@ICK$!Gki??;VEa+6J@>&spRFX0dJ<-| zy`u1tQ2jsX{*NhIBHJ#b)W&}HYyRIsSdR49c1FXax`}j8td)?^_!wnsskeXUcEu>R z&?FY+iuu(MJ@Y@cyt8~sm@ywK5~`a^FR4n-v>0__B`2X46FHo7#k3fub{t22CisO4 ze%V90jWx3EA=c(L_Y?sIQ4=?Mzp8{C+eMQPPOfbxnka z>B^4Zk0v7O=3l(y{?k5ujeiexCg@?hvg3WvM-vgnw`tD=Jxo{Ed~}UwJx7sXl&&%9 z%F&vbzl=V0!FEPmGADR*vc%haRTe^iG6`kwGa%4_=o% zJWN-1{C+eMQPPMWye7iKbY;iyM-vgHyA9)8#xp?=)7||AVw>6QJLk9Y>k0bS@ADth zY|(X(qKAaujCkz?qm)wgmAM@BkdS?1L_{g2=qqcD@GxE3@%zz4L`ft1%9;od)0G{+ zA5BD*G@`GpiSRI8+41|)L`1c6R6U9wrrY#Rgor+F8}8Ru=YhIZc~ziscXl~&iU>SIL@3GExk zkxq?8D}BAUR&UhZ*x9yn7^@}yCZB%a=x_0Vji84F%hzHXwI(9(%xw~a{O!gO#dLQc zE2hOLt>5bNT6)@UUpq5pO1pDKLOYGM2Ge4cb}*+pUz$?8vK?oQYFBX%sG|^le$Ev= zB-Ezkip6e%QR*vkU1KJgU+vdM3upOef*umuD~{f^n_v`sK@y8viCT4BNl|N$yi2=2 zR`igNMt!VEFiJU$y763Dj`U}5NyAapcojKhJ+;{OZyT>7za%tP#&yQs1f$qj)h1U z&eO5@7vdWq+X9*tLV<%TKk&J_ubm6L|0ufMq* zj5@K_PC}!0U2>+yD9xgAq+5R4zwO(Ay1LzFukjXAo!!Sy<4nw+LGb?M-2|hQQhjbf z4++^PMnsfSidFwQSK(p0vg7xoiHMR$toqkPc$lv2`2A=iqNEY4{xuOErYk#sKbnXr zX~e33O@xQ(%8uWUCL*epqdGUBhv_!G6CvVkLMg?FvCdU^n6B*j{b(Yhq!F{kng|cm zl^wqyO+=J5VwJfj!ozfB$L~iIBWl-ID)qKdzt6|kwMJtEdPry-yLN(6N-6sMTylCy$UZS5qLfnf`L#xPn6B*j{b(Yhq!E37 zO@xQ(%8uWUCL&52(dXAhc$lv2`2A=iqNEXheocgj>B^4Zk0v6jm7^LN=wZ4|??i|g zOO#Ud`E{MS9bhFkRUvMnsg(z;%|S zK0g$+_MwOA>ikA$Vrzm=jq_~+8j0e#%^LKO&{HYbPB2O-#c^9}golLe`2A=iqBx?i zi8!K6S9bh0!FEYeKtZC!O>!y>6ehz0XOXb6YzNp*QDh_6$PT zMX#M;lv1j5MGpztCq_h+-tM3;g00&wJxo{QSkQCHNigcM&-&TzfB&gF&;4W3ctsBh z`?kr}zl9bfoJH%ey~V@7dTJikT70usPX_8srR#FgLqcsK=$5$uYZ@dNrDqrQZPV0P zf}n?lzOJM1A12WN)6f@g^hG&&^nDzCk4`q}9_;_o{4w%NLf_`mx9}#7MaN2CRMFQW z<RJ`+3P_7Ok#9(o;COskW2D8X@+-%Sazzgb9)($h1fy89Nw@|*B=k)rea&ut ztVl45?JYITXy0~<_M>lK>HC>cH&g%U*xV9HsP*W3ok!=2QM>zxo-&Pot}hWq-)0Y< z%Rvtbwfw2qW;sYOO8sWlYZo0W_9AKM8^0=T*`rLSy)88Q1PPVTzZM*=-O|_JOfZV| z-(uUptv*77gvPPR;ckLaWv}hI8plN6V2XO?F`PB%A)#*xMH|~qFiKw{iWZv0qGP3} zNnHO~oLGI3XkR<}(b0A-ef_oX-Nl%w)~>JjM*kQ`y+t>IHASL*MGYDqnro0z z<(RlASIn=DRpjc#N=`y`6XhGFINTB$#d&2WSW`N>F{`mH%mh6oRI@QZ?j{&@VkIY` zZ*bM4DAQsT+uNM0`7N#EEs{#9UWLz|L1=Av?F6HgQmn7%T+u^9_K6V@rIhN`D?LnC z_K6V@rIhL(MGw=JePTpJDW!T=qlf9rJ~1Mq^z6I7fV-Xt>0!EDIeQH*tsa*HjpusX z!dLdbaz?yiLAG+MYgw|VIzNba^vM%%_>-+sN$o0$)X)>-+V_x0&z@_aMYdKos+%Ob z&~gwfnTXQSZBcC%wI*VvFHfxWWyhJtnqU;^I5(IGE6Z{aU%Zt^S3h)RQ+9lxcOtAT z%Ym-^MpQi8rKou3D~UW-r(Si+{*5ksw;x5_%X{IuSG(Qrt$pt}x_PYP?Q}{j-a98- zB@gW$?EhH~_FjG6{a?D`?Vi?K&cCkhF1*ui)rYS8Wv)_#9unt$^L6*nyVbj{g<#a( zF22tG2X4{Il(|}Ttdy&#p7Ey4iLMSRCr$5-vxXD&D2G8v@8b8rekM$8*7$`_|NoS| z3)F5`S>L-1^q^QQfe5DU2 zJc-g_QZ6kD7;a4>M1f?#$SD#K5JV#P$Y211K!B(X5%kReeCB`6-~86|Zg%&OoyYw= zzxkhY&FflguKC_-|8XyR&q{B}RVA1%iD|lZxmNE@G)ORt*Kn=TuX|5ddN2F=_wCRy z!6?@3qA{!FIypuCTUYew?(o&kG{qJ536JYKr-#HzH+*%IUtJQ6y5u9bY)-l%YIDg| zG3M>q8jjn4=@+799P72}#3?`XP5b9x82x6{U|NjQ>6@SYD-h*6>Ce2q>)mhO_`27V zXj(mA@bsHE?l%!y|1JbQBy`pF%xryiNiZs|bo9qa-5T_e&{fw{y|o6*F-JuIZnNpO%<)DXzdRIQ~l3)~D&!`do_zk5U-%Q1R7q28SLa}tb7N9tLvWE?ZTwsEdhKAm*CZtbI|6RMjFo_^goAQ+|k zzw6yIqFjeE>W9at_bMmjHSE`SE~}+D%U4k(G!o^xA~8nwD?QeS_6_MPS!rkolD?jk ztrd>WVUoS%Y1Y+Mly-~ABU;~Hn#k7-O3NM++E3(^7L8)eTM~@gy)L1Lg!Yr^ee_U{ zszHzT!s$)5qL|W{D|$$1FPy%xTWgSDl=i~utGYEok9OwB($r;*R96R8NsNt{{9Cx=ickoeysv1BLh7o^maL~K@yD8d*{5B zD9ZiWJ5p3@Dxb%(mZAEeal9ho-7rg?FXdobjN<4Ti3c)onP2TFcK=}cTJix7*NTMp zQm^{ptZ|oVF^YGuqXwh2tJ@>PZh{^XPkh49EMv^5L4r}dj~)qnNJuXq;Yct_Zp?0NRxN3cBS9&+KZiyOw{3JzVqV{4a zN+X|ka;yn@G{R{Qx1yNRm@9fnXzbD+?nR?qS^bGI(Ya!j%IANN*!Vm8pgkls+G(%a zqS3ICV3fv0?Rp!C*=rwPMMY_cw4!*`*ST_ikdU5J+D$M@*U%}A1U)2l6$ddh8}GS!{5@XP zOJ1V&XWnXj_1LFz*JGl_V_%U7Rk#R_wHytUt5uJx1U)2H&yY*B{*))eLt3#5MYX2f zx<5v2{5@}3LY91`(J(#z=;@NsRmgiS2}Z4QH9J?lqSA2dTV35HSM-oj&AR2c;QF6= zOM+3F+w&epkJb$Csl0}x20bK{Qa+ZDU=&;EsG(k~y~nC&J)zfE*s}HH{_GcqJrX|s zpb}+=*sGp$pGxSRj#FBQS?!7hqjqcXy@7JrSH;iT{NalpkgVIKVGjxEb$ZEH%asX6 zY1iAeCuSNxH9{r7w@liI!G|;#b-ZnbIv9A zOGT3<`Mg=>5q+HQ%~AGO`5F74`zCp~3p86t+O zJ6E6(jQa3vpSVu{A*$HaL?Ej+%JtWFi zspmF`-c2xyQZo^{T-aVaA4)v>6ORnZXMuJhi>SM0xA)#xi zU({MOmRyk-qk8M9!E+$k$xZfw~akB4>QLdc_i zD<&TMfV;G}3(wkY9&qCLreTgckA2z))7_mb=0xM}>EHadn!}^#%K0TxXSf@tF;}H5 zF>{(=l;)Lh`{r9G1U;Ig?(u}%)Tm?26^S}0-f-JQV@#{eoGpr1y;Vj1Pn5&;!E~kf z!;ks49U3MWrSd)I>f;lFo;q{haKch@r?fj)BvdzNyy?z~2202&wT0fsx=MLV*3Js5 zEwS{Eb1uGHO;=<4Dp#}WoF4TL6Y6P)ZwR_893&W}QM=QPsT!Kk-J>*8yWeRnaeJ%r zC0c*xt;P>ulRDS7t1Dtvj!Mu&LZe+?gH&g(bVY_-)jYZ6_K;A?JrcFx`k(QM*BI5u zu?P)r-YQ+4_M{rrb@TYa@{Jm!rxO}c^HxHFQM~G7u6PwS^mBz6k~5gH=2lYLFlLqgi;{q})9UiDg$ zVAKmf|KR}GaK@W)=U$)uT?)7y!NQ_Yr*|95Zn!1O?WtVQl@? z6O7tja(YNePu~XQwBFm z5{$azuk7z@XZf1=;zegHp5MRzj3wROt(_hccRJzBrA%WvNQ_aBTGwDLd3ma~cu1VJ zIdezU9ZzNd4CqCiK<+|~TRALTJvq8VQB$QI#Ye_Kb?VtX!{RiDH+xJQj z3Dr$LCX!&3>R(?Yt?PpxwM5q%QyQ-oJtWi%T>rZXMjbkI#=gD>S?7u~fcm5NA#;2j zHRvJ17P^~YltzjCTG2ydcWY;hyXT*uehl*<`vD1EE6=E7IY=;yqtZz5x=Taf;iwK+ zvm-$d36)RZ-mPnp#29sY`8{zEb12PQ^=+r6QNp?6l^%0N4+*V4@^(dnQ5?HQ4bBEZ z$6m#^{lF>vU--!byYxy~<}E!Wrum2VZ}~~@bZjb>pohde-teIPpTF!+lB-J(3E9I} z5R$1H2MI@=@$m=lf9hVDhR?cI-RgIR9F=NFW=ju=X?kE8Q8Nt^j5>O*bgG7Or5t*X zs81drT4F6ZJ^H@EwHDtr9H@_44thvT^Y^c7a78eR*RTXGf9CDrLAv^-ro7HcFlxNg zMPd$_dCM<2{7X%`KKd@ivv!SL2uAsrp;96wN}V$;62E-MLp#>HBp9WCcWt)hBXd>5 z9um`Z2s5>_q?SmJ2(L1aUBiURl;0aLEk^ki`=KS4%*9&NGnqySe`%v$Fw}>OQhSs= zBs5~&=JF5rkzo!b`k)C$Nkb?1EV){U=yxBk9{+xrqSW37V#yUfB>XF5i$+Q?N+~V5 zZPEHq^bdPTsCNw|A2dubir+LrLahW>QRCx_&yH2t>RK%t^pMbab>fGzH5`dCN@HSN z^)Xi>{Ji~V-}LZ(eT}9os(;VFiKB;vRtEYV@pXNWV3htnuXB1xaGqb6!)Y-}DJ}H` zWNf=6w1ywn3`2eNw0acR5|Ai$uCD>T!%$xXdQYISF8_~TxWIoYlV@ZhXl1NQPS5R%~3rqM(IQkw}ps}zeSw5fBWP2Yn|&iM!j2E zzZg2~j&7LVO>~dim3Lq>rQI4NbVc%g;Y@3cy3@YD3#l4&C~2kt?Mqtv4QA&`SHU~} z$6V1f5-02^ISKuqv#*cp+}CZ)6+LPt-r3ERcIS$OTBY|^?cEJqOcst5|=$ccbTIw)He@SeMMIb3NhEeYre()~fq***XtkH8NC!QF@-M zXE8g8l0AJh+S3||cW?BBXUNrx&=Y4z=`DkvI}Jq56+L?Pt*6_^o+}b@Lc#%!RjwGN zlMq(dsuH6|Coe?0swd~L1TKH{=BKB{C_Q~#mAr8CmL5Gt^R;41i$EplA)zOcuFc&9 zqxAIAEoLP2&Pl6Q)q$QFYegwrPoK3`9BQ!UO7*N~qwSop2s|E>1 zss4Mv=_Q%Bqlf9TcPa6p)Y^MF)Y|pL_F$R1f@+X?C!wCEXNv2RlVFs3vz|4s3DuO- zQVlv+x?6EQjk%(Sgj$U2sS*v;8h>XK@SOCY3uDK7{zgAB$#)V+__qnqhVv)C7~P#VEGWQG?$>meGIX`!?;%*fl%T(+QoP_o$LHU&4p?WI+@UK^>4rV(Fgy?Z)PXA=(J8p=^Ree`nt_e zimOIRUw`JU($$zQ4e4pLmi^G{-tpl4?JLvOIfI&eMXWSJqG-@VqMn4Ksb5{yzk`Kpfu^RCk` zovVn-%0Ul_dX8p#bxAO4ce|p8g!EkhV>w7Lifwu%bfTl?4b_28bkwZl`WV`7!^T!Z z;?SXg`_R=p;n}U-{X=J2Y8@vH=61{#JtTCNrPg$!cN2`#S(d9@6;w~7dVY1Hqtj)- z88zr3p%WclrriXiIAV+h+o%YwE?pn)1tY=UNkTc)e7n9@Bp9VDqS<;O=1`iqIvr9o zjXXMMQmX*j?Ehn~=pmu{$TjFu4La{kX}1OmwHRNw-2|gJ9xueKR>Jn9a=3r6g)T%f z<}E!WbPe6pb`y-!d71g1BG#1ppzDJ*J8IBFLjB)0yPIH?aHGZ^YTP`X}b-ZxAc&Zy?TRHb9In#l+JGV`>!!q^e|o7e(SUl zRpTJxD4k`g_1(H0^e|o7tC68<93&idY(0wUrgdHlG_C*`#Sxubfd7!_s0E{j3KJ2^8#xQdZ8upOTb<6uX z(_$27?V6uOgJ1pf>s)?693_aq$1jUX=#&!mw&m(B8cd5(`ghmtTEiX^N?-qfu3>^v zx+4Dfs-aw!|Bda6MD*rIb&ZN0BpAgu)`FXc?k1E2&p_Q#RENWd2-O)KJp3h8^ zqICb!|J_+qu11fZ0R^F!u9mrI7^>&0d1wE@Gi9CI7F_=mZ!PU1q4&f2m)^SjHNhyo zEAm+cqlSM;K>5|1xPCgwu5)X3N3VJ~Na+1ee(nbeM(Lf->Xd?#y?F2JR;{-g&b!`= z3?-kVG`dzN?E4%Bz5nt#3c4b`>SM|2A)&W&K6zmwicY+Dc24vr&L=wXsxL$_#u_9c zjr?2#ro|}bFh6ZU@5y~?fUb|v8PHp&yyWzd(3Q^5H6Xz#y#?|)3S-IX(VHJ%QKmE! z^pMcIBG=|_f>CN$ZVQ!|gPXUkTh)j2&bBaW&_hB!D!*1F7^VK`x*0Xt4^)m`&%LLO z1bY+-UAMelkzkZ|c(|vH8uXA*&AR39CK$yYJQA!ajSN0}g>B&gfmTgIW0%i;*-ea5 z@hgMNNIeG^PdR-Olb%^RUDoWVK@SPN8F!g>6O7_Gwh*(%5{>|h^2jM|kNFExjB)fK zA-#O0W?Ey^v9v@Ix(aG_HsDV{&ZsQ68rr9K4BDu>?B`MzIo8T_Px`>eZy2zp59 zJ<)0{S~W;8Dt4Y>E!u><^DI0h^xV~}Hhj!1dLohlFg`)2MNfaFl;1aL|}_t>|I8{N;j0 zqZqLkb-Fq+{e;iHuC)xk;kDhFcx!2oe<4pf(K^^E^>}H}L&Cq#HPxbFP7;iI{2i{`JnXzz zB|YkKFS>ej_HVqTdE!?|R9f8u>3Tzv)6vz8Kr;EOHL1o zX}Y3Z-B;|;=xOyR(XY7e%fA7k8uay1{rgIfC7-5VYyMT5qt_togT${~^QO%^KkK&8 zRmMIzM)kJPa%d{9Z_Dv-o|C_h(`t((s z!-uxDgd*Pdl^9n}I`@k4H1>s{hs3x3?*G`l;(ujdBC&VA^b1Ey3y&+x)>HDc{25yb ziSsYqF15LY7h@zCHIDP0DW~aT1|adtzuNBTQ5tbP*6Nz++Nt%aeEBF!4+))fuj@Fp z-C7P3jEbv}jl0a1MpVxX)a&KewHiI0P=9p&S7HusB!;M+eNesBy_1ASiTnLnI@f|2 zqckdkP_D}V=It;V)Uhj~*ruZd@%Px;Ij*RGZ z(V&Ovs!eNkxr{ywK@SPpey0;9a5)YVj#A&$N_^31Sd7$u2c@?3#*4pRqcrl}>*{|@ z2&tP;eSF9Br}k#-^_$o1*)9UJbEO&C>1sYd`H^3%=`y93q57Yg&#gg1Yl+AH-7ViB zSB%_`4Ro@#g{^|}5Ur|PhzVpd9k3=bbtbOcJIZpq;-!CQaDfO~P$?YK#*YNK~ zjRKAYqqO$qqJslJw@vA z_t>sTXigkjNyA2hQJSxM8&d(Sp;egE(t6IhI<|I2Lf7gWw{}LcO}8S{oXuNacWHd= z$v4$&#rC!k#TaXlgvxi9-}_2ZA7ffQinTdvjGj)Y2cL4gOoIfYcDEANl-3N7d}E9T z$JR$0(AOshv7Tb(mqmBTq4uNBi`)HvETW>yWV6?$!njun|oyLiy&k6wc=hx(vf-;l#4TPpeJ>4f^cTRwmT1f#Sj z(zC7g97PWajY`7^*M#OR2}Z>XmyM!Y9qG5!r2fgW((^1cwzpoAal9g-)tP6w93&CcO;l!5uQI-zLB7ZgmUPaXg9$qUXhWYhr~3!Wyj1(f>EM0WvBS8-dJ<-eOC=!g)`YmsX2Y$=2JfV$~3F4_L)`@fEE#78$ZCL(oA(Z~GPHcr4 z2}Vi7D}xqX{}a!Uot8!(uO@dB^pMc1U|1*4p%l5YI-`_Qes$>~q4d4_hyqZp!!7E8jMQoylQB7srK-xC2IGz_Pe@O=DREyrM#kkFTQM6Ka>KbG5q$?I9rz?KmAYN^znbCK$ywUCUi^q(Adk z^{hRdN=rLRwHwU2@)e2L_H`^xfMIW0zwZMv(BTyjRS9d`wl zT{pkB`k;2|<|TK28O53%%fX(b zz0Gb*>}exG4+-t7c01lpFiQKi-3vxSJBQu+vLNVCv3zR{ zw<{9LZQc@@7NeNkwT5eugmy;fJ&I{Diq~+|;5AWwxFs^Bk)Vf!>VGxD6*T5rmxEF4 zX^X}zg6FjBF3dZ@j_vGd60)tmXw+OWEk^0zcN6xISnbS|&>Uk)Pm57cd-1>D{MX0D zEUMuCEJNp@=r^6zpSkZqXRzp(qLzMM($}APOAiUzeis(8@%Nf=l(h9*Xp2U}#(fz& zyF|Z#rYM~;qF*^%6I9pP75e=vMd{=V{j%9W%qj;rjefnZ|O^LqaEQ=y#t6 zje?FlIT)o}>9?2G1WTw>RGjx?+x0?1XH57ijOAcjjMB*$`VFxqSLHhC&%EVTR5@G+ zyy_7fe@Dq(&m?r+T${TIMy0J}cCLICRpG-|NtsQ&faeQFuUmMaoESxmnh zxU{P|l*TcUQODK?N$8v~{et15(F!y6T1M$CvOHJxs86`$$CfJ+>RrR=lje$19Oqkb z85T4$uy-nl`hrBIv;vJ33 ziR)i?!nPNp7;z_T4++_>*`pJVl7{UyVGq-l?V3G0;V5a?UK92(UD>YLqZ5vjhV34=Vgn=toqQq6z{WSt?53&^|TPhh_`+AkdW=Gessc7(y+ZI>|wgH zebtXnI7%9}*MvPxSGKSE(FsTKo@z}vis{OBPdhr{C~4SU6ZSCO)i-f-;mZG_22C)E zcY33SzQynwM_)3!{`I{^zP_S|#P07P2aWPO;a=U79&<&HzV|SpuaJCav72C&zI5^( z(n!#wuc>?|MD3BFhlIX*%GV_%7^N?rybh`wb12PQeQo5N=({E7U2V;EGvw0ENBS8-djTm{mBEcw*N}~q*n!XqGT?%`_NYFz?9HPFzt84($^4eI z5_53lm)<0He*wz07?plYR%GTaJtSo3^>L7J)Un-dGhNyFJjk>db!^WWNXX9j2s154 z>ECw~_K=XB?{#KcjMBgFChQ@x`&TfS7Nht(EzzRfuJ}79QI6PC61m0xl7_|e67Me| zA=~>kMh&LLDE<3x!X6T`y_aIGLBdheussqw(ZOFY^QnO}e3vm2^pKG4mVb1@QA)}7 zny`oI%Fg=-(_)nVeK%nb3E6Jb>s*m=lr(Iw3455XY`5v76ONLG?KNQ!(+$0>?J_M! zMLBj6ZtWywyS=S*MZ!_iu)QYiVY;&Ow#&2_rGL)}u9i4cYwmK*j=7?TglyOB(FsQ> zCEIJl9;PeXHG6czQPQxzChTFlp_kP;(_&PVV;A8%Cn4K4yUrB}M@hr>ny`oI%FgSY zX)#Lwz9MF=0Q81e+PG)9q`lh6;ZMmvw=M%^d3*=9OO^WO)yID3U&Izn$Xj8 zpP!~TF*?seQSol-&YdV_(4To5Z(PG84HKFToKnQb-%$>GNT^IY4P(gFYz^mEZ%K9T zgrauOIP{Rv+YFt!GHBFtkYJSFh3J%(fvCBnNAE&(vdXdNiiF;U=q#2&W0fmL#e1WS zP_4N&=)IcTm1@>)p(MThiFaQ1kkETPx6mcL7$dg}seq0tpRwp@|Wn_rzTv#t-O#VEa-)cG=Ng1<|qHs*0fDcK&&K@SPG(4!NsO{HXe zP1wV9ceg91#VEZo%iAtJdY9(@!IXCAiiEE2st*=)Y>A9g-Q@k8H6;z51a$1JgoMhc zyUV4{=O|6&%59fXy3+plvE=lSh&Py-20a=XoD-(BTZ4o~B435w1fw+a4Xu3+Zr;+P zQPjQY*m6ZeqqckS?p!g7Gto$}HK?C^{y4UlNJ3+bXQEMqX)%i9@kr>ch5Mjvw+y|f z@V}1)JqHQXy9v>b(i^i}gPwzg=~07(Y)5gmJQDOABuwunL_2EtDx98!gy~U(gltEt z?dI2to`ZzxQG*2g1XqJ2K@W-Dt0nETJo|_^I6C1dY1m#9_Ap)9zV|sg;V5a?UK92(-O$TU{$g5; zigN5Cd_PD+c7B)2v>2s--%Z#S9QPQxzChQs0eb#34fD@BFMPph$O8w^C zSKW0aX00+ldhh>d=~1HHi}cGCw#Qu2Lqc}mKMoR((!bkYYuLkdWxE#~op6*iY_AD> zn67O1f}<0Tl7{UyVGq-l?Ot$n!co$&y(a8ox}lf#52nSaD90|sJ&J^Ex9N4RNH|Iw zw%3F`Ojovh!O;mvNyGM{@K5_Ip^ZLjs2sb+JDv4VwC#Lsz+5q&q&;J;_Xtb zarO4hE7>Jivo!R+&iA!?^XF9+m4k%d75biP(I`f|iF3&rrK`KTSF5?AC*HosvxQ^J6$!n^ zTWPFv#i;ZdStaNpp(m_)$w@Fu?+1OQOVZ1q@`VCCdaLhxW=czVG2+~FUtJP0yt0hIK#w33^CqUdeMsf>G>gYYn${5_%(> zUtOlfD9(1H#*5E>-sYT3?pND`2ANAW4eNYFz< z=Pzpy&GIC*VdJ|ZM(JsrThFLL4~aNOI{Td;5{%O6)~jFbnKgfCx1XLoD!*F$y5#CN zw#Qu2Lqc|5j)R1w*f-Z2j$*p9caJ_K93>6gYYlstu58~Y9-VNMG;FU4dzh|l-zOfO zaFjG`uL*mYu58~Y9-VNMG;FU4dzfzMWp|KFi&0UIU4-u-Nyzqn;yPC(93>6gYr-C; zE8F*pM<*O54clwN9;Pch-yy`b7^Q#TP1r+1J8?C0uSXxI#VGZEt(ez@cB<;#iagrq zs<$+b;tV$u^c*Bi z?n7Ncy3#!a{W{;mEe4SH-#gTDqgO&}&mDJ@3X4vo`4arf;@Zv5e@L62=| z_*c!=1U(rcdYWGF!P{+5IPoW{1_|2{^{7p~Dzyel=+`vt$%vqj|Am{59Dd->RSgoh z73GsDq8ubfPw0^djX!?SpB{Pm&F54N61ElP@1sHk#FRy?3AJ>!c-1-6vMqw&V@(r? z$x%{glCX#Be?@3VK|Yxk-KJ+@U2@2y`G^khU_g*U(DL3=N~_xDx}61ElP z-~4z_)Te0|F-8Ru8vpT2&)EC$ zk6iU&X*eo8J>9o|`p5S5tL$rH^sI@<;RpZY`FkJv@W&q_1roM>t<>*BBO@3^JBW65 zPnCwQkJGX(LUp5lFMFwv6~QRmq0!n^CFrrObfb-(*fe$#jItdXt$*yP9Q4?h2A>Bk z{bNNi%64d!RmPtFCk=XROGBfC{{OgEy9h?v4vqhO(cSjm{Z9|88uZv!x*z+@ckW+! z@hSUjf}V_sT%Gre|9tPUxBJPeLBe)Kow#4GU0s)C1fyt2uG(x+H8i&Ow89plHl;QY z^e%!?wnL-MgH?kb+e%mMS#3Eqb`gxS9U5(Rt{U{%j&wD*KdNc$B4Rb*s2~;%txMXq zqNk^;)kiOfMz@S$lXg&G!0RpVh7vJ)Jn~?|)!(?!8WJ{e#5lSrd_~FMrQnwr}{UAFUcB zY%5Bue)aRnRYow1b`b53rD`xO+ah!)qh2g~xyM-%jI!Nw758eDpvSh-jXN@ryX{_W zMKH>CXq5WaJ!c);>9H*h-C3$nMmcs7jItdXr4??~bJecsv8{A>f_`$2Ro`WoZtChz>b4bi4kwkf0|cLZh|By51#WTTyD2I@>)oNYIlJ zq0xF&)gWP8QR-bf0X{TH(326N(ME=bYb!B&LXSjfl#*-Bup&$=N~?ihA0+6>h|nlCsI^bkAYofkTGjM+MS`A; z2#wMbwT7!2By1~6tFzueNYIlJp;3C2)}mE|gl$D>mD&3_33@UjG|I@JHFeb>VOvpJ zE%)(?1U(rM8fApjy+IulN!V7DR{ee4B|%R{ghm;ub&pduNZ3}C?p{1gOcM!uG9onE zomZW4NZ3}C@4}*=lb|OfLgQtn|DF8naX&ashcKsxt*BqVeB!A zuCH(PCla<5<@1Z8K1k4$5ux$VO8@&ryw#sb*jCho-*I^Vj+g&sD+dXBG9om-Qu^QL z+x;L3+cj$b{{7or{=ud}VuB|lLgVG7|6SAW2T9mg)DQlfa&rCIe)B_O@H9OVq4Cc0 zwCl!pKS;v1qTc+kesKT94_Si*JsA-iSK_@h3EL6%z|wC%+^!V~pKGAjkP$&YvfSOh zw7qdBVOvpWeEfkZ2Z_-WIUx}mcPRIRpNeZWld!F*cf8?2s1FkKWJG8@u=KyutG0R? zMZ$KCnturGio^s@MubLbiQCq8XA-s*^|l{41^t7>;Awg!LZkGkZR>+G3EPUg=r77C z|L0!c``|**lM$iu)zbey-gXF)u&t;Ie*D3uU3t7BK~F}6hU%h?i8Be?ih9pg55~Al zf}V^BjXx`G>gssbHq z61H8Ar=I3}wWd)CrQ1EBMms8~b1-=*fuCXd}al zFkPd{C~?bAzP)LX(1>GCMubKi;i?7++lta?_w$$iNz))Pc$yxG&}bud)gWP8Q5v;B zbuVj>peG|jqs=%~gM{sf((Gdm5;2p7CnJJxGiO|@iD`wcD9xh193)21nh1@y0;n1! zY%5BufnFaZ=*fuCXe*hjLBe*8Dytf|o@pYX6_Py}5gMf>Y7H0H3WRAzX?5272Z_Pc zXcD2(R+d$Rgl$D>mD&3_33@UjG};QeYLKw4s8}s~ydptQMubKg;dF0M$3zmg6{S^w zA9qR6lM$iO?pUe@3EPU&-AkV(NYIlJq0#QV>Wo9ec0}iWAAZ{2#s4YZ50bF0D4ltyv#LXb1U(rM8gDIi{(^Qt zNW!+F{A*yLL4ux)2#qqU?cLDc50bF0D18B?v-LxR1U(rM8kd)6GN-opgCuM#N+&|; zEdS6TK~F}6#%b5zVeb#x{U8b3iqe@?I%hjHNYIlJq47IE`@vKHq1_LXu&pSao~4t( zLxTi884())cX=N3!FE4L!nUIH-HE2zoLiG`{6o7asYa?S7DiZAIxTi(Vfj=*fuCC^dMb)%i@q zwxV>>TyIw-=*fuCC@pc@+U`ukwxV>hS??bt=*fuCC_QT1`ru5$wxV?YS?}j0=*fuC z&=G?88K+oxt4@&mqWiEF=$jm>DrSKq0vfS z*9;_VD@s>Ezi$y5B%riMubKi;i?7++lta? zr(bpm4HEQZL};{;x@wTHttgG!`h|+nAVE(?ghrcjss;($iqh<(-_QsR67*!mqM^CA zYLKw4D9xh19BrK~K3(1q-mdKzC1G1pZ$EtQ<}p_v-!w?jlM$iu&Qj;+wEIC4wiWfauRX7n?}Vm7 zf}V^Bjjxop``LCsNW!+FKK$AzZ_aqrotp*;dNLw3?p*rcpSAacBy20{izhv0^VkR6 zrD>3$CnG|mlwq&rY+K&rOeAba)Klxpkw<^aM>JH1vMHU8|XdZAJO)&*fSz1U(rM z8l?u0v^t+j*p8?;Yjmmeg_x%9$%vreUi#m+l)aXE2T8)VqAoi3+2|i6Mo&NW)c+nD zre+Y$Aw&5z#YrlvtcBaS^85p)|9s|E?%iqdFz(|3KTX^pLH z>V#=UX%_9}ATfG^CJ`EK1yD6e*jAKQ1HC>-(326N(N;25gM{sfdg{`8rip}BNN!gd z5p-LTwQJQ0(~8pStoIKRqbFz*q0v^BRfB|WMQN4U`#A}EG9om}$e=ZK)gWP8QCcnc z@rndJ84((7rC-NH61EkkRev9MNzjuKq0#PGss;($iqhRnpCw4plM$iO?!4-ZL&A1M z@g9!EG<8o#1g+;WdXiJtSJP#e-f>^2!D+ zBy1~6r$Ff(+t46EPez1>p2z6Pnlwn*R+P>{)_J_4L4ux)2n{`t(Gx;xkg%;NousT2 zgF}M^JsA-idLE-Eozfs-TTwc1StqfD1_^pHA~f_oMo(;|LBh78bV9SvhYJl7^khV6 z=y{BuJWGRwZAIy%Se^eG8YJk+h|tjU7(GFk1_|4W(s{Bv!8J5U(326NQQk{DMDHi0 zLBe)K#V>t^1__-sThEd$Jt`v>jcc36Ov1LJbe?c8hu)T$7(M+rNB!@ip?5g#T9xky zds?;?rIU?&eUP9hBSJ&(qFSAo?+1HYwiR{g(4En)NYIlJp`mwbt?icY2YXt!6{QoQ zd;cIoPez1>-VL@sSiT?ZY1vkk&Zh4DoCG}?5gK~O*~XIc{a{bawxV=mb|0@u(326N zp?9@yOf26I_Oxs(N@sfaahC)=84(&~q~5l%y?j5|)3U87ogv=m4-)ibL}=*Ud7Gok z_k%qx+lumUR!1KsK~F{u8g;HEVcX@dQ`Zb6Y%5AvK_{n& z1_^pHA~aeJRt*xi6{XtLS?i%ef}V^Bjn)$PG$xX;tthohozxy0BwA1NF3L4ux)2#r#MTKiND61EkkRZVYKB)!)Zm67*z5Xq1t9&tp3Y+ltcNi)V>xB0*0^ghspbsxuA= z+lumCSoCue^khV6v^&UaHMZ9~$cNp(o%U4jCX1~o-A(@Ly-sfbPGa<|iO}HNJ`%PS zrMu#H z)>EI0E`*+#yIo~O(CrDm>U<_)TTyyi-}?uN(Gz+kLW6JnNZ3}C-a7PtPJ*6{2#qo_ z4DSb>mT5)l?MWZ6NYIlJp~1I(By1~6Z-M%_OM;$^2#uQ$ydQL0rWK{PS$+N>K~F}6 zMwxMj_k&K$bVQZ6a?9LBqQ2p4o{ShY>Re00w#%X4{E4}?X;eb#c2DGlL};{<*L4XA z+ltav&~FTd1_^pHA~g86kA!VSsWuN^ci*N#f}V^Bjn)$PG!K%ntthq1Upn3zBr4L$zgk~~(G9qZc z?IU4ZQJO`2IY^A2&?6BVrR3UERIe2Y+lta^pw|ZpdNLw3+DfKskgy$5PhDEi`u(8W zRYnBOw|!bunXs)Wt~zWU7eY>5Ot84(&f&q*g*NrQxK zMd>`J2mI?tGz}8;WJGA_JSUyZB@Gg`6{Yi>4juZpO@jnI84(&f&q*hYNrQxKMd>`J zkG$?NO@jnI84(&f&q*hxNrQxKMd>`J=bZD?O@jnI84(&f&q*h~NrQxKMd>`JpWXai z(;z`lMudjWb9!@oKS;v1qI90qZ+`o~ZyF@%$%xR zkf0|cLPKYZwmvwMu&pSa@7w!133@UjG;~I48%t&qwiTuGefxMtf}V^B4W0Gc#>AO~ zZAIyP-#+e=peG|jLub~uv3(|CTTwdSx6dCW=*fuCC^OEs%~3N6+ltcpzMi|Li3B|v zF=*78lZ0)TIFy zrWK{yeBZmiyJ?W1CnG|mwZuJ*yCiHYO0DufkN&QvL4ux)2#waGss;($ic;@7|Aqg$ zX^@~NBSNE%3{``KZAEF6_`M@{YZ@fz$%xQsBV5%WVOvoe?VkF%?`Rq%=*fuCXd`vi zAYofk8nwT2@?Dw+33@UjG}??)HAvWwsP}Gu=hA=KG)QPBvnL}K4ZI)hglR=-7VYI| zb8XGl=n0xcXq1v`&9EX&D@v<@ULPdr$%xP>HK?^u)gWP8QCijXc141oj0la=619e_ z8YFBhN~^QpKSXAYofkS}phSiUd6w z5gKKL)4f3*6G_-slve$H+$BLzMubMYW2qV>Y%5B4FPHFQjkBkI884()ojeFG~VOvrD z<=&`s67*z5XtbRJRfB|WMfsP4LxTi884((72Sn8%VOvr9ez)&WBtcI`ght!RQ8h@| zR+PTq?fWcA(326N(RQR%4HC8$^-a@%*mzfH-6yl$LDG{Ei^g(yN5ZzEbRI`9N85{| zT+Q@kL}-+fFZ)GF*jALz73uXsf}V^BjZ%Zleo+#(6{Yi0`aWb5^khV6l$N;c7bRg^ zQ99=(-!Do}MubM`QOkZ&61Ekk^J;oOCqYj}ghm+|mi?k6Y%5CV?)34B1U(rM8fAoA z_KT9Rttg!z)W=;C^khV6l#zPbFG|9;qI3>YpFc>@lM$g&W}IceC<)t&(yxwt?keZ? zfuJWN28}w`lCbS^^!+|fqY_Hjo{R_$?*1fUTT!|SecuuZdNLw3S`F592?^VZQf>DA zS0w1kh|p*)aZmFg3EPTNtL*#8NYIlJq0xF&)gWP8QR-cNKO6~qG9onESW-1e*jAKA ziN3Fo1U(rM8f}ED8YFBhN~2xhpGbn9j0lZ3QdbQUwiTsOyYI6kK~F}626umwu&pS~ zKHe2N?iZyeBNmP2evpK1MQIl8<=}o%dNLw3O39b~q9kl9N~?ihA0+6>h|nlCxa=1t zVOvpJ)%12nf}V^BjkY4Ibxy*zqO>~e{euKO84((#M=kqBN!V7DR++t@lb|OfLZgff z%YIQ3wiTt-av!fq(326NQAW6BzbFaYiqfjTkGmx3$%xS4?oSf76{Wiu&l2N)QF<~W zG}@h4opDImR+R6;V%<)Ho{R_$?blXc*VwMUte&K_Y%5CrPrW!aNYIlJq0vs#srPCm zY%5CrPoq(2kf0|cLZh7sR5eK0R+RdmM%BMBSJ&_wY6eWeUPxNDD^+BoTelM#!?a#|<} z+ltb9x|c&=Q)xX~3O>`55uu^yFt233@UjH1sW}R+rKsVOvqU|L@~233@UjH1tiXR+rKsVOvppj?w2267*z5 zXy{FNo1tu7#bw# z$%xQsBX!jvVOvoewY3Ti4HEQZL};`br)rR}ttibtT6Km733@VO(OAwGC1G1pnnim# z+FV<6MNdYAMq2@_2-AwvYM|E#33@UjG)fIF=ZliCtthQ(db=V)Pez1BX^G4Eq9kl9 zN~^QpKSF&j|#CX0aJsA-i?ar&tI3#Q<%6DOHEQ!0j zO3;%LT|;m7HMZ9``sK~O(z2~6y`R@x{;pwyo{R{M_REV}GfX6GD@yO@wOb)HNYIlJ zq4DNY=h|r@4HC8$rT6pNbrBjQ=*fuCXupKHl?DmhiqiXe?H&mY67*z5XtZDStQsV2 zD@yO@wF@RRNYIlJq0xSsv}%yBtth>p*KVHBAVE(?ghu;?)v7_lwxaZYUb~V)g9JSp z5gP56VygxT+ltcrdF`$W4HEQZL};{Mysa7}Y%5Cp)U-=1G)T~s5sSw1>+&RQD@yzA zdO5UvPW#nLL!9Z!h|tiUKJ8aKNSIcX_6_#>AVE(?gogGeYWJBmNZ3}C_CNM^MS`A; z2o3GA)b2BBkg%;N?c?nIg9JSp5gOVns@-SOAYofk+K<}%ISG0)A~dw;RlComLBh78 zw6C_0S0w1kh|nk_-12+$By1~6`-A(qOM;$^2o3E)*6uTvgM@8GX`geSKSCUdNLw3T92w4 zBy1~6y-T~qLW2Z784((7WT+Y>Y%5Bmgm#IA1_^pHA~f0vS2al3R+L6N?Gg(O67*z5 zXta^KYLKw4D2>|MB^DYa=*fuCXfsaLAYofkntik@Ei_2blM#!?@_Y0oY%5B$XfH>b zYiq9P$%xP>C0~Azo`h{hX*JO6g9JSp5gMfim*1l&VOvpJ)%12nf}V^BjnWdA-=imC zTTxn__5MMEo{R{M(xaB&qbFfoQCem8eolg(j0lY~GAzGGPr|mMv|8@t6$yGWA~ebf zxBMPG3EPU&s=trBBgW4gjahHT`Mfol) z`XC8_nj0lZ(?_BTINZ3}C?uvD~RcMf)CnG|m z-O*PK61Ei;clUR08YJk+h|p+HCbp^%61EkkrxZGEEXqNGo{R{M_JpNskg%;NJ#Epc zX`w-ao{R{M_N1t4kg%;NJvGwlZ=pego{R{M_Qb1dkg%;NJ^j)tcA-Ino{R_$zU?Dn zTTyz7r_=aCg9JSp5gP3YWGx2?+lq>(k=7tVPev>n%iBH@wiTtPs=XZT*{gC@-w)c8 z5uw4ieN4-?qV#mQ*9QrDG9ole4G!-Iot9}u=_z+_S0w1kh|nl4ad(Ki-33@UjG|I>@ydQL0rWF-$Pu$N*(326NQAW7o{h&@L zR6j7SD7^*h<1Pt$G9onE8!U~x_5GmJGOZ}R&Fb?933@UjG<4_Xw|yjRD@t$WJa?_% z589IvgGQZenU-yrL#GP1@#?_)L3=VHG+N2)y_#}j!nUGx6?Cd#Xpo>MBSNFqVAUXD zTT!Y_ohld_B`3Wf#= zdNLw3+Q?8fNZ3}CMhTrN7#bw#$%xQsBV5%WVOvoe?R2VOXpo>MBSM33`$*VUltyix zDi|6h=*fuCXfsYN2MODX((I#C3`2tiJsGiR4DSb>mT5(47VYI|b8XEPJsA-ieA`FD zwxYBe==DK@o{R{MQiH?$L8oO}QCijXc141oj0la=5{LJLPRq2Sv^wkkg9JSp5gMgO z4etk?mT5(4mD&3_33@UjG|I>@ydQL0rWK{tvd5TdB0*0^ghmhI$& z33@UjG|EUlydQL0rWK{T7mxYt_k;FiL}=*luFQjVj$&H273I6IHkN>(CnG|m?J&Jo zW4qq<>z6#0mTg7p{k(ofG&D%ilM$iO_SV*WH4?TJrT6ptHPp}`K~F}6#y^xg*GQ^z zkg%;Ny`R^wx`qY`dNLw3+Ro*zG)UN1l-|$l*J(q81U(rM8f^!5)gWP8QF=eGU)c=} z67*z5XtbT=RfB|WMd|&#el0jONYIlJq0x54R}B)j6{Yv{`qksmAVE(?ght!hUo}YB zR+Qe)>(`q@g9JSp5gO`$T92yEN!V7D_NnPts6&GUJsGiR4BrnrEz^q9e!E@{t&Ur+ z>i2{8WJG9aPoGwor5FR@bQPt2gS|dT(326Np}mP(T}p$5ZAEGSV{ca^=*fuC&>l;z zE~P=jwxYC;v-b}Y^khV6Xs@VNm(n0%TT$AN+WR>PdNLw3wC7c;OKFg>ttjoQ?c)^* zdNLw3$_O`nKj^efD@yx=`?yPjo{R_$?bj|VCXKr@3EPU&KIcAvkf0|cLPI;FwYroB z3EPU&er?ZP>+c8c$%sLt&b3U-w#%Vkp^kpua#abXYfnamM*DKI-m8(Yttedu{R(wx zkf0|cLZj7S)gWP8QL0V-3Uz3ZpeG|jqqW4nQXlpEL8oO}QEHX?73$C+K~F}6M(a^k zgM@8GsdwpDs6&GUJsA-iZDgn#By1~6qlA8iIy6YolM$iOM!2d$!nUF`+UZxQLxTi8 z84((7q^=qyY%5Bmwtj^=G)T~s5uwp$oT@>>wxTrq=vS{pg9JSpv1kn64>~Q=iqb6F z%hBfAnk#xTA~Z_LhwlfSmT5(4HPGvW1U(rM8l?t@?+2ZhX+>#O)7upZdNLw3N=saR zZ-RtvMQL@``v(bnG9olej~c!obXukrrB!C{=OpOKh|nk_!|?r}(=x3nt(HB;OcM!u zG9om}2seB`=(J2LN~``p?vkJHYknLua({iUd6w5gP4eqpiw8!nUIHe*TLW zS%U;U84()ogr=%N!nUIHe*X8bw+0D%G9onENmEsWgl$FX{rsIyII~?V67*z5XtWcv zss;($iqiY}vo_WsK~F}6MmzbdYLKw4D7~LQ{->=$f}V^B4ZWZD{U8b35%u296Q5uW z5;_^po{U&Dmb*I=wiTuQcD)?hJ?Hzu(Gz+kLPLA{wEL_y-Fm*L(=x3n?Hla%L4ux) z2o3GmesjAYBw<@o+W*+w6$yGWA~dweQoGMo4idH%rG1>ee~_RjBSJ%aMYa1(8YFBh zO8ZfJKPN#?Mudj;ylVHEG)UN1l=jv3@rndJ84()VyQ|%2(jZ}5QQ9Be$6XTiWJG9a z53+WjNrQxKMQNY2$NYM(+CtEi5uu@-(b|0`4HC8$RrhPRxodsC=+rzJF=*7emTB2` zIUe=G)7qHWa#abXYfnamM!Qz0mU2uaY%5Av;bZr=1_^pHA~aeJRt*xi6{XsI_q+D{ zJg8Pu33@UjG+ImCQ#nZ3R+L)h9e>3dBA9rWK{p?v+QZL4ux)2#q#UR}B)j6{S)8#+O-x z1U(rM8g0g@8YFB-)O$CVU1|*yn#t_Rh(%+$A0%O0QJO`2Ioe!Xb2WNGk3?vck`L#L zIxW+R(rTdB2MKyIA~Z@34(E$HEz^q9s;0Lq67*z5XtWhsEjbC>iqh(=_YV^EWJG9` z9yOdV>age5us5=hT(isr)64ES}phSiUd6w5gKi!Uq?6+wiTsSe;;>A z(326N(e7BP1_|4W(%p+^iS_xS_GCn8lo@9@U(|%tRg~|-;(m|>JsA-i?GCcu59Q4K9r#GH2s(otqWW=Je+})9|ttjoc>*Z+AUX`o*>+;&th*^BQbzMTjwxU#grCGF>gYO4NPtYVnqpbjH$w}B&lvV@1K1k4$5us6PaCtvS!nUHc zs_E^D1U(rM8l@#J?*~cPR+Ls}y?>CPCnG|m^r+?iAPL)w(kip}a}xAqL};`Xa;*;% zwiTt-av!fq(326N(N_9(gd<^FQCju)ahC)=84((M+egB-qICD-Sz>%YNKZzDM!WN> zGY$#cit=69`u!k184()gEyHrYXzj73=PE7Ricm@ygM@8GssCwI4Gj|XWJGARoy%LzgCuM#O8rl>LuinoCnG|m?ZB=Y zBy1~6{ZF%8Xpo>MBSNF?B(EAIY%5CrPqTGskf0|cLZj`7uNow5D@y%OtB%khK~F}6 zhThL>#iaTmVOvq^e_B0-1_^pHA~f0;3RQ!IZAEDvs#RcUkf0|c7LDcmK@zqVrS)_# zhj!0tJz5Gr(~}XQp*?+Ci610PD@ykTy*^0LlM$hz{n}cON`r)LMd|*gw<{9#WJG9a zkEPb5(jZ}5QMym-{euKO84()VE2`C{G)UN1l1jouKSJ!<)Wkc4eTX_eXgISG0)A~ed#uzWvA!nUHcTJGZ&33@UjG|C9Kd_PFSwxYD^ z@8d2BdNLw3%1FI@KS;v1qICD-Sz`Qtke-YPjdtf%XB-l?73I6IHkRP~L3%PGG+t7O zi`(zfPt(mCy_=7;!dBE>?|$>6da6w%&OeAb8>Vl`=y!n-D zeD)^^dNLw3-c{=SXJhR%k+7|(pS#0XOZj{bBnf&lA~Zfz+U{3l4L6ant*Dc3`0D1o zlRnU{AqjdiA~bF)eX#s*tGSkhZAD%3ky|z&y~p)Ug9JSp5gMN>&z8O%YwC%F?TGr? z=A~b-28n6vo{R|k$>kZ@JL2A;l%x~374`hnzP>sC!oO_gATfG^CJ`E6yx_u9OG~NO ziiB-NJ?=&SxcTH?S%U;U84(&cl;8i<&M?&n3EL4h?U(00tsEo@w0JUN(O6CkC1G1p z@4Ir^@8u{O3o&{^k3?vck{@Z;Y9?V@QK$UOH|_WOAVE(?ghr{sBdyM761F4ixc%O) zNK8}rWJJ)VC2m{Wok`eM)DK>A+uOFBX*NCtNlKIkf0|cLgTX1|Nib7aX(1Hc0}E}Tr1CAB&Ml*GGfrEb1ezmF300u z#uCnG|m zwZyunCShAqYL%CKn%lV=tY%5B$XfH>bYiq7XPvnF|Xq1v`&9EX& zD@v<@ULPdr$%xQsE19Z6!gfS`ZR6H6O(e8JvL_>gE-g`OxT--~eo=m|X% zp`qU79!0{oqO{8F{hS0n84((7gRJvGwiWfb7hS!%-;cenm4gI5 z84(&UEcb(@S5*xXwj=6~O1rWKiSqn>@npoJac$F>N!V7@%YOciC`Zv)h|v>zBtk>| zukEx+f!o);&~fyX9JS!nUH$ zJLy{V4-%s%XcD1Odem}1NW!+FK6;NM=;tKp$%xP>Bg3|hB{K=zihAi6j$phZK~F}6 z#-En{_rw?zXA-s*b^e80jJqW0$%xQUn^H?ryCPv*QJ?&)E#?mr^khV6sBgTyeLqOT zc0|3UTr1CAB&Ml*GNNldyY%%^j`F7ywq1@_-1g;dERlu@rQ1D0lL(Dg^15aqVOvqU z3h%%2cbf(YdNLw3S`AhW61Ei;wfVB9L4ux)2n{`t(dtrHiiB-Nsa1aX;s3p9kf0|c zLZkJlszJiGqSU*d^oak~G)T~s5uu@HyINhU93*T<)HR#S=a)7O5*l&r$%vra2v;>o z*jAKAyLW!}B~63G=m|X%q0vU_szJiGqBLrs{TtRGK~F}6Mw@Y}1_|2{rP;?CBw{8D zPev>nnrqv&Vp?GHO@jnI84((-C2my? z61EkkR(Y?h|FLP1peG|jqxGn&LBh78)VqHBs()%4Bn%iSFb+ltaG+RM@ATIH(V-E~jskqC`a^5K5agws`& zRs+30NYIlJp;2mZxF2*{rX%W_rS;T#a3Qopa=Xfipi4{C8m^X{gl$D>b=La_iO~~! zBtoO~sNsIlX_;1(R++t@lb|OfLZgffT2t3@kg%;Nt(N50bF0D7DHTIrndy1_^pHA~af$sv0D0D@wiVV^6-RX^@~NBSND+ zDXJPIY)8~Jo4fqpSDFS1jX3sXM9^(atQsV2D@vo?DYvr*iO~~!BtoN&)K!CoZAEF+ zzW$0Yw{no6CnG|m%{Wzqgzbp>qter?K|(W`JsGiR4EKX3Oe;#WXfH>bYiq7XPw0^d zjZ*UAe$Z)|R+Lr)y*^0LlM$iORx&kLBy302>zCHEz8`eE%7~y#OVl&{s-ZQN3EPU& z>a6z<5~C+*5}{Fg)NnuOv`i~XtIXcdNzjuKp;1N#y<@56AYofkv0Cn!Pe2 zXq`awwq+jt{6>3jp77~^Jnb&O^*5WVKl&G&OF#72i>-ezC#m4gsG|-NfAnLY+g$cr zAFA|jf>E|ZCXs8UznPz8tY)85uFKg|;ZW_A?UCka9 zc4(+BbcLnisPJ?`^{x5|y>}#kv?VHtMMHZz+qI&nr~7a2`KKsH(MSnK*L*Do_e9otiaQMN-vyRSXt&|_N~TGgnB zg}sXyqkK&w`!qd~0p8Ct6A)@^0X)((7aIN%|bEe0(($#fSe+i9tbwx~$Qd*3% z9U83$s|G!`m2TAkTbl-m$x%v+QMN;)wZyH;L62=|s2!`nL^(jTmiX4XW?+=<&}coX zYS3d_=_-Bw|Dge*_9%Ik7Ncy3MjIKb20gYT-M4O3uCPH&j*7Gx6?Xi48{w*k#w(?D zkWhW=%7+Gsa)CR+DBF=z8>y=XJ+_su+O1kpXn>d;rL-7jJ2cviQ#I(Z9qDSmvIdCB zQIQs-!d^5q*Gi-Op{Em?cY8TBDr5wsY=?%%D)lNU&|_QW(E6d*$1Z|VwnIZ>u6mU; z=&>Ew>f>lvy9lkEdg}{2G&FapS4qQB;pv3dbG?7;A{b>mQqml#UL^&3Y^xkvhpHz; znRXG3vK<OSp$hxac!w|vjnH1ex^$uC~8x#_#URC9IFHP77Ka@H5C{lq6cbGZtUoe-J#O3pTi zANGCqDvJ2y!(oeX-Lwn^xaZ&9QBM5(II<5PI(sB$Yv>D(`mI%oiZ4d~qLxFoIh11| z7^Ux6>K9IhUJ)Ttt`$8b^rcPxcB#-Uxc+A(7^RdhyR>{Uk`nfi@Ha+lf*ybKqo`xo zsQb+e;jekt8cd5({x)Y#c=xzGmt9((=W4btws)?t33^C;{!U-soOR#wl~AF_t4o4W z-hsa+=ppf(fB4eoH~vdjA0!y%FA3HfEcvpZ{=iij%fZr;P)e(IHLIVKV3f+_u`-%q zD5(#Ycgy*~I8+Uuqt+hQ4;HUwsxr-%8c5 zGp*6GHufk+vH!Q=a-npsczx7j+|O6nYSEyFM6`t%S88xcKQu@%>Z6z3xXf2A`2hFm zA)$8VacnoiD1A4xx>mDFK6<_u-)fgDO6}bm{t8b>6UfCHW4Nu8#&5KFG;(eGO7JS0Uir6_^RK@SQ2@}^EY zS~MCq?~!1Xeh*aV7UhK3gZ}kXMfq1s*91NOol!+e+bONfVGjxag6LXsAv%oU^9^2d_XL&Cq+xz-@Ts8x@eLuuY)-KuVMc9cv0jaxej)xS=K zTIY)Gic!2GW69|u;a~C1HQY)V#a20L_}4F$mVc#Ew(bp`(r$uL{;kd-SF=VR{W7I{ zjx^lw&ieZw*qnQ>Q$goJ;wa>!LF(7Z>2QU3kOfvDwJexP;2+o2#qDLJmvilRUK$l`k_a?ui7Ia&sCrLgX$4+#w}M?TPfvFCg>rdapmOy z_liV=1fz7-a}9b(Xe4^_RsSQ=Ai*e&SO4D=4-oTI+OF#M*Dm-#O-oVtc~96%$=7ha zR`igNo>QtsNnd|r&ET{c#d?a^_&a9KjL=m$^76k(O3t(x#rm(Q&(>gT(5!a$SKd?8 zWl9lif*ukY^DjR9u5XYlMroYC{dd13A>{ekw_H;_BL1&$dgGF-ypJVs6(OE;$M5J^767 z4h<8G;#D6tH12xL&?xG$guP%S=pmsIHE+8l7{$IhYOp^m%AX=$!?pI~lB4SGmuy^{A@ z5{zOFM-6&NNYCTSZh}#(lFz}Z2A{S0!xufEt_LqV_t~3kPYhdcOjc{rLX8BY^sN85 ze+as!zGyJrJ6`^r&CTb3Z`C6m`H8>PcDp)>+g$$K&7teQCt1CcVAPAxe%|KmUq87M zORnfS@k7ts{OY|TiYe{R6^UuOXmjXc_wO1F8_U5cX*}ZJ-D3yQJw09N-S`XN{S634 zseI>La=(P2N7w4`b@#1N$CfJ+s+(UrKIrweayb~Kw(zQ_+$YJETH+Nq-Mf0!md<`* z*qYUx(x^cX3B5OZ#ZLvj5VP7Yi7{#}HF$t1=)Cv&XaCxg)<^IC|5NrZ(E4O$edZT5 zgE6BKL5Q6ej1s()KsN}X;q*Cu5u+$B9S3w7H3}qLI*ukyu2>16u}yG6WR?)o1QpXN z28fc0LLZYg22i}<1rf#8r}lUHc$WNo`@Qe8fBRm$YVX?h z_t#W0=8scli;2VG_BDTNs+xugd%gR?U$ZZ(mX9}F|E#rD|Nbj)Tl)kt?RxF15sQhp zzw)cr{Rp+sopk}kW zc%10HwzbKga7|HG=@Wg;ZcNSe(|$})H|dX?KlyN6_M$C}`?)P|dcrf;@xw74*D!H7 zJoCs1*T=Pa@q0>rud!J+0=*tJD@nTf_qK92GCMr>L4LU9pjE}ec&;thR1}5y)u5fqP z3jY#)`%h^kw_FWA_Nn)7@iOLr_=kM(rm^PSapCo(*WTw(kPj2+ea4eMeA5`_++O4_ zsl7ZOTfFl%@$L^jqOrxbdASsN4VOu~s@;89bH2s2F@5Qppl)vdkU!emRhRR`WiRUg znrr@GKrjxbjWVvpiyoDj)-+9w4D^H4S{vJ!mI2YV-8EH=gK6!Ia8G~X16$7ND`UbI z6SMy5^>-J&rfLq;KK6T z-1^W+3wQo{!WI+ldbRYfCIemg}t@G7%!gu`KW6qxaq6<4xCJ4S>|K&el zyJ`5!{AYaUTN?3#-?`!Jj@MPVY0TcWJHZwcKlz#)&i>^yezwt#SpJz#oD#lR&-dbw zrV5!8r`H5}e9<1d*DztP=YGKr^Gf`WZ^TsGbaMau-8z3$Yd-&fj_b*%x2`#V!*6`< z*`q&9I{`Z)Y5%%se9qa6e{DWxaiP0ZtpxGLVq$(OGN-Caz0#9ZnXuP=zU0=kZ~x?< z+VZhr(@AgH;(gjvZ#|+x&XbRS`_^05R???%OV@N_i-~vNam(7?Hh*f+guSl2?v}Hk z`vuj(q+$Pb}s(tBOh~i-#h0o6f7e{c4@8}6E#S${pF9U{>-@Yd9SRn zV_JzhFrC<9;wRpGcJ`^CsGUv=HjmWmYwm+?`MriMCg=qj$Bq;BI^I9rMnC>%Za(|m ze_ZX=ZMxU6#l)+he)HMgw~Si5iQenx`HO5L!u8>jW_-*z)~CuA6O5I+I-k+$#Du+Q zp}8{j8n&3ImRLK1j}!LVT|cJcm{Z@fwjailv_!X_Uc(j>j9qEd#|eA+D$x^%!&XyI zeDO_dJ-cRm!WI+n__UkWHg=q_m#=m`VT%d+;CS3MVK2`mn#NR0Jm0-}{#sJ?XWA~i z@EJ>7>V2wgF+pE>%|E@Tk-=VW3#-PQGWK$AqYODuyl(j`F$enb$^>;_3Ykv)}GtFM#gq~d7STwAO4Gm@3`GWv?zz8!*?$r~kD_uI0nK2cZwsBaYP1mp2L;-WEY;nAPzo94UEr=S!AO3{v)@wL#k7PG~PuT0L?|a=kvp7!J zV&ZV%4UEyu(uBSEJ*Cj6s<&+MqSxIUEZ96!D=vGHzwx~RrI|x-m#@jxLYtOn}7ITXDn@;#Gmah|Fi6kTZuWqOn<92>LVq6I9#Z~1!FF{Sxiu~*~!yunCQLk zf41A#*HYEj`Bu+-X>+XMmch46(<)t0eX49R!PixHJ8N31OxVlqZPl14UH3b@vRlYC zyArEL+K&nJvcKp!VK4HOyDc7^pVW>cwIMp8wK2|@qwG#02Q?8P_S zyL_yvvW2h7r>w4)DieI~KBL{1i`LpT%Giq$E@NdQ)>L`ygUDFov9i~&#RMtLsC1m@ zy|$j#6YfzaD8q5vHDNE0;H$<&S-JhtyHe*@Yr7`s%^BxcjX6+n1EyWsi+-M~L?h-D z@i(3D1o+{P{jtZ@m42Rex1V`O^+(q?vfFRVKfG&c%SJrofxoYqX7{O(p0F41xaY0! z=DQNMnBcwiyfa?0N8>p!{Z&%WWazUjic!3@py@s_9Dm?x&+ z^if}VW1ezz4a^+A*RaLJmz{q3s@D@v$?d=W7gmkqsj|hydmnnun%Y%kA|EF9UZeXc zdwt7GKKjP~Zfiu8Vp&WO)3IlkFh$tw#y7s{hHh=5qMq|%iwR0${N&Dry(snWdE!(e z(+M>d3pJQ{+q`FZc7iP?Xg%Yco3NK#&ywl(pXtOF6VH6=Q*TTe9w+SOHr*3$qhJ5@ zFIoGFwR^%A6TkHRPr5NHbjJyMU3cB*-#C79_kk~X^o@DC{IlFl^?Ka&src#}#i z$6EALi7>O=(o5;)8M5=YB&fjFu2Lo@sLk;+WXEMM_nThBbxY}{28rpOM^O{hY}!Jv z;kfK|ufvTu?p7Km#zc<*lxTA65u?|z#RPSel0Ht@i~1k8EA9nzW(j%9eRR9CTkh4H z##Bnvi7h4w=MK4i=YMBvPsEF>=J<}@7RO6CcgVfQMIv6zBeJ5r5_4cWvBmKc-nEix zM8wPerq{5=@eW%_OO*+Gc~n|8TB=;Pj1n1r+Nrpko9{D$kQF;mkC@5ki5UBA`p_dHi(4$SXV>+N0>>|5&I zsh;EKuP1u1C!X$3vueb=M!#B2uuE^OVZvUFxj9LzC1?3(I-w8ntdf4v`t`gfNtk<| zPGco(F~K;(THd}#aphta6bsitR^YF$VS-sRYwLRrr^;T;tyx>&6Wn#NkD)9-ecJXh z%qeVhUG^2VFcnc*pHEep)6SYU7V^Z3IANFJQcUeXed(Iu%FGJvs&4 zyqv#Y!xj^0u$H^mFkvs(Q)OWOccSf5CMh58H(YLQCrQd`Nm>!Hn4mt`Z?aF7%iUgA zD_s-RKl=^#8jj0euGux`Wd6i8Md`AJPP~q3$#j8Tk1|33V9oyWRN2eDtJk1J*&kJL z{q$+uk2R-?ry}EC+gmn*Ua-Zqs7&OXyQ{Qto@u1zGq=i!(WlB56Fdd!>SKD-+~tJnlL!d$||%8m!l3{=quV%fGMYB0NdWtfnV;<{b-9>mUD&N3d6Z~x57Qa)6;l4UY?|m30q7Y4);HM%&pRxN{M~1e}2t}Q^;Cj^3;4+!WI)g;j?0& z|D7q`1=!-U7uq>zq$g}K!L#@AnHp1ap8|(AYx2yZDMBidIrk?4i ztXKtz2I~pQ)8{d2{h6wj}!Lt7_$-+`EYvC$O%L)k(HPOea=mgzufyAC+tOS=G>n~OvN$lyZ>3v zYhzT~PUsn&*gHeD?wq?H6SUp&i9oD*g|HVbKPM1XdJsUv>80()>uP0Xf_~GbYL1`3 zzI1!9Ew$xa|ModI!3e&U+s5=n@3obB^Pi&OGGQ#)YV9hiGQl`DZY8b{dwJB}azRrg7n{(s>VD?b*HRIjM)0pr7a2S<{%~uY5QzdtLw0@0w@Gzq-{q#QZnEOD2m6 z!s9x}lKS{lFL~$bBVPYoE#AwC#AO1K|9{^S9hbeF+R8xtxAhP10p}B-=etJECg!YM z!aN&DYRfl-EhaemopRi#%7ncrSyI*!6Qx^UVVl3>Jg0=OzP0bL&SBnO9;XUR$|~PJ zt9X~MrOkAo4{JDHzRuRZaT;Py5r5N3zL!b7oI0D_=3AXzJ{n<*2~NyTNmu0U-&w;% z@3nm6beF1pZLz68?T6NOl`lQ+Q`K2STz}npUmsIaWuo_5zL1$z6)@+cOI5xNiI?;i z=k}j@r0y)s*Cb~mUt!$m!-Tzl{Oq;+{xMO5wwTCQ821_`?B({>=fhrnO{IOean8qa zqPJ{BzNxrRl?i+03yGH#>vsZ|R2}b8n`P@o^se@;Uusi-tO;+u(_XtCwNQPJ%9mnE zyZeeH<{GrcM7{yL&$$VE_3e05;XUE4ADGBDVD}m(daq;s!!?y}P7<$cc1sg&*A^4` zn&duJChXOZkEskaJl4{#+IO+9+)7N)^4qt*FKs3EqTjUdiHDdfWzz|x&t_S^AwGNY zlxl0CTWQrEug$U%)J^iV`IB?UWiRSKSD&6>{Ak};Z|PmW0{(!<*uX*WuXM(HUcq}o|dtJB= zuBoE6XLfh-OEj4oY-u9r?jI)J{2Q<7XMLSU;SDVR@^Phe7ceF6| zk=+nIVK3_A@wdJF9tg)}g0}GX&-^!y?lnxj{ZyRVhRraFgKjmMH2x@RE#UEHT7>UODs8&+%5-}#e{*&))DPcr?{B7UUr)r{= z@O}8l-}Z`Tp;hw5BgR^4_P5{i-90fEbIsvmF~OCHcGiv5O~Y~7i?)yyt~J;QTTE2_ zU&u#GmCJ;2J}sj!!&PPJA1PfERaVt1H~;jg5cZ;^)ACnhf^fN`@!A)CZz~_y(@M;N z>b2S9V}krW_?y13FWnu{d;P%aZ+`JBH)2i^e|5$A(f7vky48#8JpI0_!AA6!jiBF* zQ)R+luFaO5<)51Sr2Uwn2dCVQ6ZSgZO864{<8Q0J#uYC8?rN>X1lRL%KX+Wc*Vcpk ze7OBEd&!9En0mq%6U=?nn~xLrBBr#rJ+WD~c+pG$KTg=oBT-NI`)ZYvdNTF2r_Q6$ z@V!)9Oc2h#wO->Q5ihhEzxJ)&7ROt9dY^L8wz%v?e;nt-788tasg;ICU_ckY;51+vKP;?G9EXLsg(LTgJ*!A4Xmk}12seT%pxP4 z=S0Ve-itjtYFATnq-wL6;3;0TdyNa<^O>KX)*IwJXWT}o+Xaku2=QF2aa(itAJZB(6GgXchemw>_tpjG2Iifm>`_rFDK%)I|+Kh z>Ris8>*{zp`EPs{E9+XUL(w}~A!FT(@bQ%f)_~*1E``uM)8FpGx13BTtQ51VM7)0T zPfV;;4Mql8OrXc=-%3oSGo6t3#6_OswOh?t%gSkIR|RWpN#Qsj&Y_96!(v_oT~oDc zn6Q`gv^cl_)K^2ZGGYQfR!YYjA?$U$tXw{Wrlh@a|z1TIt zTIWj4DdKOMzbpKx)j~cJuS>mr>)+}h>9wo}vpP<^F2kO%#RTiY>KlE?B*cse$x~7VjouM{$%nnDo3xldRkl#)DIaV1 zge@j$Z>gK(guOf-uf#+?+nR`1$JzdmV3ywwRzT zB!v}w{oAi1+snP6`A#9+CuoW3wbm}*5Vn}0<>%UUoUoU#L_OgzTYD!lbD#0N#1<3G zYVVn_7cpi2(5K246NIlu#EY25?aCI%OZaL;yof1%bDxh`953PgemM~@ufF$$Esl4% zwmqZMiQh!<{%z=S4ccOYIs82n_9CX#O`i{2Oc1^r5iep&-Rw1DalC}{`{hKu&`90v ziC7#j;rxC%v3YGfBYJ}SsO*_=yxiS&tNLIQbg`nHDNtG z^H+B)iOXJSq}-bKR7?@Em>`_r6F>jm6Y<*J<4naBk(S|j3Fr6nJx0U}jjpwK8nHND z!ufr#5sSTipV$+&m^i*8-h{n|``c%+`CEpPwgTTF1CQ%a#vl?i)s z=1a=3CpaxB^OapMti2L*px*k8h6(CpJhOCM_M$dZH>*ZVl`XWA)TU!viCwBp&_cU=&IRl9 zVJ~{uZr01R zQ_qg6d_&k`f)PAz>^NaBt}9*JomLH5IFTuR!rI3*OtkaohP~Et*^A%D*C<;|pqFuF zpQ^-VFJDo6!q0d7%z?YU#MBeEnDBl3al&52lwBlyA{G;b^ZVsQy!sP~H)cAq#qs*I z;MISkNBOkbI*Yf?A?Mwt?6_&f?9Jai>yyOyjaW<&&hLATSnP#HX3Kjb78BlqzfV;Nd$FsZ z|9^e%vk29kA+s0HOWm9MRM}#Jt3k@}IAJehN^S0mSWFPk@0SztLSx)^ZE?JWuSUd+ zn6mo5PgN|AmvDZ+oQPMYcCQjW5ja zYtV$fs2jesz9)F{&j~tMSVQ3J#z|F5VV|m4Ot3C8ZdWcJd%3+ejk%oon@(uqNiTgR zxuqAR{>!)it#yM~Owb2Y(#HvVc_iuy_Z()KDJ%EQp0LFPv&@wGal&3M!=A9kM6I_} zZ5}7=<+iXA6ZPTtL#@61i~jc7N>b`8F$Zd`C>9gc|C68iRfCr3wreli*jN7P|7#=W z6!BLpqp?soiT7%)#02AG@>H?czkR#1ms{vcOr*-`r9^N3JC%0lZzbkHUsfilo0q<1 zlyk>rudC(U1T7{h>{I2q>_t0HsrQ7xP~k6oklM^qdcqbH%y;jZuop39j+|8b z?8WcndmLL#5WX4_FJj8w%RW`HI9|f}{c<8+Xyoo?PsHMQ3Fr6AiFlzg?&r2RUcy%+ z;#K(=-Q(EecuVgpL`DW;N)O)WJQl}GIKN*`#0!n|;5`wG<0YKmFDK%~Zo_=bxF>9J zyvM&lJYU)7@0@>Pd!E3zeqZs$6^0)7C|gW$GU7cG_9CYAl|CP~m>_&LB3{IlzOvVd z#qko(@0SztLL+@;PsHMQ3Fr6AiFl!rzOpA`alC}{`{hKuDj%aBWsBo2y{i!EgT$1+ zvQJekj+bzLznq8{8tE&0A{NI>IKN*`#LM3k?+IJ_c#nN`nkVMDf8~jJ?yz}^6TM!; z78AAVFuJ2RVJ}uT@&uvRu!Yr=JaceNJz@A0y7T=ruAHomX5rB?gu&eSm-Pn8K)8pj%r%U-Ntc6C0LQa#zuT_f!(_kff_ z`h1@%TTIZV^TgsfVK4eho@?}k)605oTDbGq6SkOOtvJ2wIAJgMf|ZzPCA8{1NujkT z?P!n7$`%u7jLXV|y+~o|rlo355r6Y3X(~m=tEABNRKE4^ycb7xYl5*d&l!&s_9CYA zn>`VW3D!Kv&nz96y*z^V8XjfX&yaE6ZJ{S@F~R5$WO)zSYbMCn8#Z@#V-D|M7fT!DaAHJPJ%H4fd8hfI*Y=rkGA1CZZ zOyhe4TTBqX8WAsI%B+8%s#qK^;rxC%5ic|{>)#WxI9|f}{c<8+Xk^yECt`8Dg!B95 zM7+?*tbb3$;&=(?_sfZRRX#@d2DUif(z^^ zVtc}Gjr%kKMxvD4mJ8-rwwU0plzS%ZMNBETy+$l12|lr(ueo`V>--Zi7h7PZ=0O9Z=ubznx-*( z^H-;Mw6C7d7HTcutmVx>zErx;hb<;(3!y9W_V27=!d|?)$hS>bjVXjJCiuDz-#=W5 z0%i@qaKjhnu<(5xzDGyc^y1w9!}ViJuL-`*!?*A{jp;CJ@I@8A7Kw%LvGC1Q!o$|y z2)+QswL>v;d*Ez|UKzC@J1?H=6c!xj^?{I1uo`7mKG z`pvG_PL!2<5gL5sm)s6})T~pdg{DuKAb;&^!D;Pt{QUKVyw@EXW@Rn)DkE_*(iTc{n z=eOEy8gu;o)%Wf)CeqsZdT;v2R_f(lgloz~eML%#$||Y4TFy;S zH_6|Y3p5;;y?kBi3D*>*o2#1JLQmLYf|||s@i<{Gr*==IrcCe+uJI`9xa{Tj)@$^q zv~H(J64Q7V-di?;x!pYz_9CXtulrQlVuJA1h zEQ@fL^Yfh1hb1Tc5oT1PU9H5b!5ibOdtl++bJkf1GpnI)R$>vF&NGvV7o}TXHH+F4 zndxK6OrLP>EcS%GOy}O9Bj&tJ=lS9-7M_0aWRq~d&)X4mUZ!)N{KhNqcHxzGzE)x_ zs~g^Q{n>r*{DoGE?B%`VS#NFO+FSdJTj{Q4mDA~nE9cG;Cg;&!oZEk<^OOJlL1%yW zbwAVM`l;JLXkK0TxfZ5Ac<#5RYSpmC#BCq(L1(u;_~-9|u-B)*=w4^P{IQj%HB}R3 zMXJ8>rk_|-!qY)gQhIOhH5y?HDGY($i+<_HdSVvqHNN_HKj`dBzx5|~dTXj0;do6P z4j(+1)lUyJOxVk1xYyXqeTx^pmw&}uj%b9imuq&_n8-ONr_jGC(J%kVKb)TeSBd6? z$9%>**Kl0+;`Gg5|5XulIq^50f6Rm4f0}Y{C($hR{M>)|{?qiEa&7<4ge@j0b)K2+ zOV@0^Km%5f3EXtuTEjF(OWixn9^5PVxp`}*vsv0CFVfi z5=~Gd>Ho(Gd%0CMVk(ZST78#_GRYUN2p=yiTTFc8O@DkkZdWFHuRl6XJHD8z%|f5Z zIOv!v2g!#mCg@$`ao2>s+K|`d+Rwet{>DdEPv!TFsC_mNF-R@g^Z`lay=DGjyjrTyjZ_Fn}Il|0vIERVwnx=`;#f#k{SfF|LGQ@b! zKwPnyU_Vh}S~cdtbZ)|4$LA%sm|#B{>(O04nuaaxg=3`}FUQoU$`%vsh2ssoy@m;U zu@{cF>h^>!?AGB;x~r$k1iOQHmu;`%RN0F?OT53fC)f+cTW47C;(fBDYS&6y>7o&f z3G{daZLeVq`QZJ&t818`40+dYui;eLi@M>Bz&&9Lb!V$w+psZW(HCK$We!@X+ECCgup ziAj~c$X|Xh-}<-uU@RsW?bxffYAje!*o!fdU2h#RW$u$w#ETu$c)8T~sY-pAKrb;J zC+tNTCZ?XS#RR30`ae$Ci@IT_f0y$aoz88c{@LA+m$i>;n4pcZ1AMRHxa`HXon7C1 z!WQNa?DW2Rs!T9PVF&nL!>O_tzo)(Ja~_KcW>I;5d7Q8pbe?|pge~NQo!-fLw0pwo zH9;A&H+-D)#APp!5=~<&rRm%~hY=_JZrE#Qs_%m)7`wWWp(HL4_Tsvmk!W$A1<+um zPRn52OXO6^EaI{zGm!W+|8KCc$^X`SKJ{y)_OD`Rl6S52wP0- zo*~cP{LN23bjUR(;v&X{+-U9L+5;_v0yy?*y1%oDU5rq3485QH6>LpQ8d!} zcBQ+f$`%vUY+C-}-2OA2o3Izx_HmE0g*iids>`s~u*C#1jmHub_HqmDHR!eMJ*J*{ zLeE>+gn4rRlowaHCvy5hBjz1q-}5z})Ckse64Oddv?~+#It#>*hSR6N=u-wczxEfu;q*O!>r)rY9rHW&pSGrIoO9>)aM%c9`g;#~ z=s?4Sy-3v`|M7^hg?wE1#=rb0NRBFw=R~n|O^V+9<}2soH4o zbg61-O3q_3LC!N0Eza#f{S&X=Ya7SPwYce=cscEf8l>DZemH-wnB3GRBBFA(*RVLciZrIQJxaMo(;>GVN^;Kh{J{%Vs8GVMtjMfz=ahV{0;}Onr z*{fY2FOH%uRkl!~8L1u9nvY$oOi(wx3sh}kWBPpbURzJw{K@%Gy!q^m-Lk~>j!(Pk zjJ>afzwQ~IbH*;gy~a`HY`!mgj!K4f8s8?OXZoyH3y8x4kFs__@cNJ^Mwq zTcC*2fM6&4p0LFP+P8i4g*{%atW4PJ1;2B{+3h!tG@K8o9paAHjq+iOiTAwx^o-r> z`+S(_y&ijHSJ>gOSxmh2C8v90s@A>{_Bx((TTGzGy8+{Tq!jJtQeWFuOO-9Z{ohXK z9U`@3&uw8P=D>7ri-{+F(%BiizW1pzVXyoC-Lo@xmhXvo-*L-o`L}PqWsUcEYq!P3 z{qJ|{nx{S=CVHJ>eWa?Wwn}<>nG;#8ezt zgROK;5YxEVny}X!e&ch`9{pjXeXq8dpl-%vq6vFZ|GbT~uMb;jiK#Wm)R&blCg=sJ z|Ko(cuDkA*Gu{W;r^;6V`eXJXdwlFQY%$>$dYrHqqr|wZY%y`XwY$ZA{LkEch3laE zfeFegSJXZqChX-=sV7|SXz(5mb>N!q30q8%Ki<9D*Pw~s>*o1;;v%L}n$GFliHlJp zsd7p8sj|fcvyXARGGQ-|UA=~{21VCi#UFj-W6s|7g%@_|&3T#5Z833}{_5EWzA!r- z7nMfXV&Y9d_~^5*c#l2tl64_Xdv3UOC0S zYl(B>YA%{98KXqrw4oPt^^vT!9u-NzDqBqCD`Tt1kgyjqt*KqS`A_waSWM8nx}0|!A?)RMnj}FhQ7JM$zU(PA z3)_{|s$q)>#;a?8aWscB(R(o_R;l-?g2?msFZ-d-JmYONN|fKn@5I?+f|&u|5#QH` z348JTxXx`c;p_Z9ABoFe#I)9vkiPAjU=H8S8M^w|;@Z4CmypC<=e!M=9frIOm_5nt zd*4=_Hm3H_$6|t*#ybHWm%aEB?QSRFEH$0y{6uPsuQ_JFIb%$;w=_Y#<2V1(+4Elb zm}M>P&#(F5>j=qTBc|e}bH4%TcpcMm4HIaLbMCn8#djJ~(yPXtvgzDq!WZVU2hwG@ z5_6!h4-We2unTAbT|NY$ocf)W|;3pdew-Ty4_ zg;eCF#7zIA*0}fvb5cbqWXFG>DqDKuen)a{g6}z}e5mu3Tc0XhXeHU%?U;_I$^@-4 zd#jHV_M#Vz_fxx#l8?M&LaN3igDoZ~w~Qw_~|Gs~pPUVIaI+|O;{o5&eUtbIIHCipV&c%*h*_VQ@gYj{M4NIiS3>;kixEA zO~v(BgWhZF&AoW{TEv}yUiBq2Nbg9}AJaLW}s|-AM>WG#qTX^=( z)9tIL%0!)za6x02DtmDf!mg|u(OWoqq2i^UlET?>{bS{4i_2a-eca`I=B9I7c#4*? za!jj0BWy9jlgQNOal&3aeN2n#3D%sLwNeK>GiF9fn5WOo6}uX2siK~FHj2eGHOrIL zJzSov4n}!K{QU6=N*>W`CP*aJE8ceFVTS-0jsj|fcEhhEUh^e^g+(hr?a@$mx`)n2ywCQo3o3K|u z@>#=W<<{p>Y4g80UYTG`m8YKj(sf++^61)YxaaWXG-I&)W>45+f~U6QRGF|B&wR&y zkbA!LRJ?eOOm1DXEmc#ct*#$wapat5)etWAJ|DK2proUBoUoV2m7Z|g$$3(>%g2KC zZPx@Po&5D0j>}%|X^ohQtNV}4&pjje%%In>#l&ugERAjcVK1I(@T8(^yE9d1@5Exl zt*51G)o@()a)~rz`KK>k6USSk=IypTDQ+5b{QOPl#LJkD26~Lvgl~M~n{F7dzB*pc8RXgvvC}AtS;H0+?IgtI z^pnN8{ii4FMNHdstq710r`P!?pV4j+$4jcXHYFcBjX9c1RV*ebk(Aq#ruLtnuov}| zQtt_;ozpLqs`47;!xj_m9L-_rny}aLc4dnR^iuzQK1|rlZMr8o(UI#0b-;;^Ty;_( zUE5u-zLl7`?z+#vaknNsrM0JjaF!+WI5eEvK2^4u;4Dk#bkN5MdvTWKE>$zi)2J=I zoamT%-EVpgTTF1GWAb#Iu$M=So^Tt5V0M}MNH6FK_f8X}kn8QftW4O865(pS5>qKn z=bR47l?DsvOfm}~?Ec@U$`%vU$5_J_YA|VcOvg1$&|*?<#|e9RJYI>3R^s+UKGHwj zLRVrAOy{a-F~<026+&az~Fx6g+yj+gLmWM~=}iFjSDM>*bMozEHSX8`u{h%q~^e|7!HK6Xlh znIE}DFZ)26`&3X7v6vu#%<1-J<+$usdD1S6P9r-xOt?2!dYq~d_Clk(a&{WAn4sLo z{oHZc%UA7|o>jwd{rc@(zdu|#sDJx6i%oD!3B7GC-BrVJ*^A#(vwMwLOb|c+|5zi0 zy(p3V-ZV(n{J*|knW*0U#7(1N7YTd0jV;cL26q#rfb1=pmwfWcJ^O9Q#PqxoZEkD)iM?ntPhXh^ycn2guPfR z%2@=xM!qCKdRd9vP6s)5ZY_88)Wb!B^_}s#A13U@n$GT&f;oA$?wnT5YDUt|x=5Gv zsd7VE-R~^tFtGlWa}+3%lzN|YTTHMjmy;J(V%Dj3=cI&{xSZ(VQeTNV(AS^|G{)x| zI4*mU!trSftdr-|0Lmxl46y1n&bcinDCzOJ1}5yqDp1Z*=yPrhD?cew$J7(Hm|(3a zwRxPd7wsx-p%GJY)4A)G`bgT{7J3a^OwgmoWo5!%^vBdqui<_`KDK(^dRkAoN1349 z#_h_4z1ZQAp4MyFVuG4Y%Rf%o%RRU!TvLn;IeW!z;R2ynZGy2Y=e`^#dawG*;5t%I z#nn^JoW#U4%f#!N?KNyM!OD2@beyo4$FY@|7)v|?;FXaR?Tq;=F$en5#{_!gk=k+f zURP;}CMbpNTC%09c8lct(RqNV`XwxuZ zuiAO0x#%L4oo8h+!E@KlmitsWE_?BNX3l#e785)f<_U3ERx{e~r?wXw-HZ&ODMTzL zIPrZv>vLT8VrOPzBKr0>p<#=O2Yuk7XD|4*ySLdZNFy$sXglY&_RaTa=Hgy|^LwfN zIlC)Co6a3Tyi3D`z48UXed*d_f^h1o*SJW;E8hw1G$zW*7RT!^7pxj{pyr~9mlM

!{kA^KK@^!v0A1zfT?B%a9G>xg0NYxLV{^l3I zvZeh+zx0~Z2Y=J|wJ>w|T@5x3TTDFo?pL3__C=$6P80U}8z1@V)5qWTJ%b+grQiD6 z)2IB4Z(A(&RT6T`9l*G(4u{vB-Z_1HBW`=}>rbEggn!+_#|c|Z{PM@%b^7+t{5M;w z*0OSXpZgDAb^7{GzO#8be^st2U0X~%@IkLS{q47W_olI6JbT^B-Cq1Y&bcin4u@CG zrTdB_8e3eO7xXJW^tcd_x=~bhpsxS8+SX;ieS7N6@pHE-;#+!cdNa;E*d-Z*j$m@U8`I~>^HK*5K zciwUc@uTmpapl3!dR2cK`%2hi;?I7^zdL=!AB^5aa_{{1cilC&@G4Qao;f}1U*Aeh zJm-1mYi+LXbD$^e)sOQVGoPlbD}ae#|JCy&J&F-0V=ZMy+0pvQ-*^!30i)xiN^_h4O`-zGR{c({(1gU>&wioNF^Jzr;U6B+NQv4D`T-Ape^1Q0uenbwO~&#m2FZqrK^TFRz#mpdBo z_^S7{vT}P{i8;{Mpb7GK&3C?cP#=9A0SklL}d0nl}9WVJv3j4BhT=wcmyM>vkL2{l_WIo696M7eU8uut$ zOt^2ZscIS~dawUy9{w7xEdYqH3BZ`la?d|JMM3xvIx z6Y*?oe~q%m1fxc<&GCSg1YN-GEJk!fnrf+XsPWti61hcbT;WmHD z%5mAt*WI3QdLeTCaQ=G2789f}SEA#Dy<8$aVT*~w;YW^KIZfCLIwjp}FmvUbchrZ= zjrm*ZsV8hP!4tjlHOhp&n7@r%;)QP+&QECTWP*CCs(Ip6X{*(Y%nj$?R)YAudE%0p zp0F1hnHen3?LYMlIdL)aWHx!6u*C$kf^METl~ScD>h>b0ap~G(g7`E0s0>&maoNjt zQ@-=RQ;j}b-I|~TG6t^%P`|hn ziuRhgOwbG1oeSOP!-TyktHiV?wiUPfYCZ9y$KL15HQ1ZTjzhdy$zt!~o^VRo=bW4$ zPn9hu*nORn?(<>7UhKY3JvCw~uHGd}4yhaVZIgD&a4V5brAF#ldg3Qe*+sk0x#Ob6 z#EZSV?40e0Ic4<*PfC$>LUx%ZRmW>E787W&cF9*{g5Un@XP#6X>xUaIBG>+so~EQy}NGpVS)d zDy@X}melryEhcEkX>W~~ikr^e8mK{bNMF5lP0$C~sXNYj(rYi*Y@ZMJ9QHP+ExD)l zge@l6SDkizoUj-BwbKiFf}O)@ee6L_t8}UNge@lOEwNEqSsfxHob$KWNV_sYYR4_n zaoNkM-D{)VG%F&1hX~lMj2jr>zp>Hs3;9H5RPjm%-U3eE$qD&KTh< zXM4ixoL#~9ukhmJ3%+dD5fk}v&N;P%uS4PGJoWjo#RMm9@ZG0QV@CU(9QGnre0yn6 zIES2~lC)oK*NX|xm`Ew~`EXqJ;^YgyA-1M!E+_t`bC)9dNFBJ;%eVfmoTr{mP;RNs zkZN4VvH_6TVrs=6p$7UxW7I>=M2RwI?`zBo<0E@p>OnpL1JG zP&dg_PuN18rxYAhPuOCD_BL+2ChSFjOke3WY~duMj4O_*Cu}jnThra>vtTtcWY?6v zh$-!DuMvw0^zM1|v6n}pUc)_y`sdqyw2Z5z$^<8i@!i0+T}`FbkBRoWS|2pQIbnRk zaMf5c)Aw3?aTeJ)RkqM4lJl#j$^^Zu8-0eUvX{sC#d#hU7#Z9I5m4Y5ic|n-V?DnUc#x_%ZYfQk?@{~#qsX$&ljwJmeG4{&&yVgiTYqI zCHpL0YuqQKo>pQG)M{TWCJ3k0FDK%KM#6g{7RO6CrG7aPFEkR~6R|j6!YTF3iFo;* zYEQ(=@e)o?yPSv@8VT=-SRC)}ow#Y{=Koa+ z-gL@5sA){4G@bLdQBuNtOG!IzEp^kU$`%v6&oVA66MXwT^~~?-n|qB|Oz=iZ=J3Y} zd-0yk?%rUc?b<@xbI)6p8|Y%#%Gq2s$E6ZWD8qt`U1Qku@)J8AhD;T+TPRGFZ6WduJ?*vmb* z5mRx~xzkHa%ougGRGFaVkHYd+?bRjSetDBav`5!1M}+hT&+OiZiB9O&Pp zx0l;nPuOCD_BQV4ChXT6cS##D71zJ%ZQ}SFppMI4!*|JMnd#gX6NJb0 zagm7E)$X<(FX8cZ&~e%8YR?%=5FYOlc3k%2_v1t?CJ2xBIy)|V@%wQi78A$6g5kLA zB3@`D zyeDFDyoA%HFDK%KM#6g{7ROt9qqgg~>{a|9=Bb` zWiNgo6P_*kO3k$^HQT4k788V1vzHU`BBq4*L@bV%aBB8)B3@`DyeDFDyrnm)bH`<` z%EvJxb#8)iYIdJ06Y)YL;XM(H<0U+?ij+m2I zSA$qgu#U$$2ji#bA?(FkA*V0w37($k{4`c#IL`vFTAO;nM$CEOZ#u6P*Rr4yf~!Gd zD&P9I@)3&(^2BKvU8<&NB)zPXa_$6P$FDfHm|!)76IVKomJbv5Vl9MIRyv}k$`;l_ zI9cWDsWQP@2xqZ$8oN~4tJaN11htmdz`9!66*Zf-Fh{-q)tXlOGX>Z zxI#<`_xZ5Jgj?w4L~4_m65bQBINsy!%5m9?6|-^MwS~2`^bf~$JXIzr-CZA?(Y__x zi@F*2bJr9aoCI|BR$_wuad)}a`Bb^7RHg0Oi;~Xoea>w$Q7f1u4O z8VT=-SR8NZjZXe@T=uGb93yf+XoB$gF4b|_i{FnEv6vv7ColV)n}`=03Gazm`gosz zditIKALnfmX*KE!u+&lC032}4->3fX9jqjuovrU zT8~U@Z2Z)TQw%~;ka14%YDt&@?nCt!rW7>8grml;*xWFQM$W(wU#Pd zYW20AEnF>CCRoSYY3x#Eui-PYM%ZG4C#>U~o3Iz_gDL4b>h*7aLqQf+^;6G|X?33i zb?$je*90s4<96k^?8Rz-+VKSqwWZnY1gjSRK;Qfz43jNY*DH^sgUZtL`eO$vt?fn@&@p4@DVm!`h*EH5t*}|TQjE|1# zc&bdW%VPWl(s9{~-_tku8nKu_FV9Gi6ZZ0zs3+W?xf&iG)ChX;& zw%15&H^GYRxO5$ty?nLnHD30VZ#aGWi$0~@b6)$4-*Eb#zxAoR`_G@jP$3-Gu?wfm!csX9e$44I%@j@fvy+$mKmvHVAFDK%KM#6g{ z7RO6C_lcJi@j@fvJrRrJC7k=j%ZYfQk?@{~#qpNj=nm3x*{kw#jL03N3BtKg+^5P! zywFH^PsHMQ3FkiXaw1-6B)lhLalC}bJA@pUz4-k&5sL|S;&SEQk3NpeUi5!v%zJ{J zs;sSGVV^6jG=#a29*+#RTqMR{CN)7gUcSQhrEAMYBJ^@G z*Auo}Btjo2pyTB$Tu<0?kqCX9fQ}b;!K~%&TZt_uxTj@>v54Qg_1Wit_}u5+g<8HW zc9{O_P5#PM!u)_DZ-k-uJQ*7_WR|rZh%`y&NuLE~k@a+&wt1gdzN`oHp(b340}68gqT0EZ2{N zEeWIHZ~nCF$B?jB!lf~{+ml??Y)Kdmf4k^#I7Zkj;nJA<-w8dJR%J`VXw2i|yt}PV zP(K`w5xrLtrST7b_iIny{#mcN0gZT-WsCO>zwxMc+SZ$z5Q1n zi-L)SQ&#l*(ijo;a=3`4bRUNX<&(G)hM;cf_k`E_*b(+hxHOh_)d*V>Cf;ge*De~z z2zw=58cY8;As@CRjE0{Fto>t0*el`Em}eO${0|LV5=Mhjg8#qD>KI|KgiGU}-|@hc zpZH&oZyL5FOuX;-&A)W^yca&^Y){xSA}Uq4J>!2r`JxZ|!lq#&;qtontd(7xmy8H| zIb5k)t_Dqmv3-lH!Vt76+Cb6A2zw=58q0OCY1oo5@zS1Y%cXIQuvfyRv0R;-hAjzK zyj($SHck7$_gF?m(SPavUwi(pSN-GH&8`#vAri(b-w-bi6TPKq6Q%J*uXxV+JOA9zFu$5i zB#alOz}Qk6CTtlIrLolDU1*p{7%%Fdv89M_nMcrHpK8|k(wCgJ*&XT$Z+>1qlQEGnUf+G!=@}=+mWByiMnq}+@H~RvSx<2eCKAT$xBuJe zd}7wmEE**BO*fJtYW3IuwmO7tIB#hT}*WIFaWx|#bQ5thgJYU-GWFld_-hIa{>K`U-84;y1 z_o(xw4^Ac$#_Qj{^%nJW6SjxT(jMnq}MSDf?Z8a0_n7_X;2_15*; zbvT%?Wkhru?Wuu@gp&`x4NzmrqR|NAjb%iX#**_kBQudOUX%jo>z9TJTSi1_EH&6P zOeBmKwaIz+rD4LB5m6dTOKkI96A9x*tK@9=(lBAmh$xMvM>P!-3FAfY;sp58Fk#Dx zD2-)gXc{IG#*0ycGviCcge@bYG?o#rX_!bDFGf4gqAv{-wv338YU9Pi>v6CkL6n1h~83qCQ4(@ zIdg^`5gIRM16zHVuw_J)#$1EUeVT@egz;ilv$ZP|wv33wfTXxK7v93gh+F_r31yj@RX0%|vh66Q%LKxvai-S)(_RFkTOT!gXi= z@)^0uF=5MyD2=zyb^eIue$Yh1c-09+KfjELCTtlIrSaOi|DC+Gt?D04B#c+iFRJ=5 zVatdpjXyp2zhA3W{ey{w@w(wn*Pq?@&R%+Fy)@30p=)X}ntN&L$EruSd=O=Iu*anaH^Yw1yE;^ykcXci+COxSL2AuUmfQ zQObvj-cl(sQ5qjP-w(dC%4#x^FkWx^!AGk;OxQ9aO5;&;|C@W&IZvZZB;35Fzp8d+ z;vmb2D2=%#o-b{8GLbM|Kl;eWsDGH~EQ_9r(wKYH`O*g`6A9yW$Is2D{6FihTOV8r zTSi1_{NddHer4GqWFld_p8Ewi%bac9}RFHp__UG}^V+M8e6( z?KkCKZP921@otvVGf^5#&fA>9M8bGc3b%c8?r}`mG9pT2slldUB4NC$HZyNGVatdp zjin{FIh=`v@uF2e`$cbB`iBWyMnq{WeXwbmNEk1A*So&(jeQ?%ge@bYG?tNJM}%%( z^CiyqUhzyS!H!_TouNPtLT;w6TM|ml*TdxXc{IG z#*5j&Rv#v884;zi%w(E|iG-WiJgZ6TIUGzdLyBcYl*Zf=nZs3Ci3p7sv$L&#nCL7E zZK5=mnPt;3kuYA&GPizi!j=(H8p{m1X_!bDubM4qyfR_Sh$xMDgyY_zjfo}_#*111 zHtw3RWki(5a>vp%OeBmKcQ4yj!h|g&qBNE}uXe>Tk#KqW9?pdC?nXq>+(G`@vObva zt1){`7%xs$;Uwtoo->3kBce1u`ZJz=^1^>w>w_i|#)~uWIIFreOxQ9aO5;Dzb^e0o ze$Yh1c;#zgrD4LB5m6fRRqf>NWqr^@!g%op6ld#~h6!6nL}}bPKa+XfvOZ`cVZ1mI zinIJn!-Op(qBL%L>qnma`{jPnM8bG+W)Yg9`m;4e$Yh1c=6r|@1K;030p=)X`K9{*F5&Smi0js3FB2KzeU4@ zEhA#pc>SU=nMfEf-kI3)F>9=ZEhC~d{><~Ach~>B+z*;a7%$$k*y_WCEhC~d<{G?f zsq@K1!gz7g+}5s4*fJtYV{VD(OWU1HB#aj)n{EBWge@bYH0B<4zVyM#M8bG+{@K>g zP1rIbN`o2lGL}px62^-Y)A-UxwOtdojEK^hN4WE4Oq@(4j29=dZR4&9TSi1_%p>*r zGPX}962^;@D!1#030p=)X|NKvTyZ873FDRT>n&r62wO%(r_rvpCK66Q_r|Bt>u2uM8bHz{gq#Jddm+zV9_vP%ZMnA2h9ENr?gxL(=@&ihnnlBeEhC~d<~*FtDLbFnaSkRDF0b3$$&uBrOdJlIWkeKx{oMb4 zVYwePkuY948Lu=<^p?^yQ5y4_^W)~HEG-`<62>bh@s)-NTSi1_yx^a_=CS|xazAJy z;qsbJufO|&OMRG_7s^)4h$#9;{>f`z|Kie^_ls^s!g$^Bx_{En9jttq=q*K?C=J%< zm$I5nB#c+i{#?syC2ScHr7_pwT}z!$CK4{MI%{;T^OZOpHp_@8`VDjc`!n-iOV%Jw zB#hS`&-yy`4->s*JM}cbm&Rk}=P}<~eQ=6}^d^kgeee8w^>Y)pjEK^p|1D$5WFld_ z?tSM!(|BdVmJv}J-#_=iU#&55GLbM|oLRMvyC!TI5vB3|x&QsM+WRq?NEk0pw%V>A zCTtlIr7>S|&X;S{WFq16x} za^B_)CKASrQuy!>`QSyvge@bYG?p4{8YU9Pi`u;Y?!%&C!j=(H8cR!Tb2t+T<3+2y z`9uEb#_H!LY#9-yvGk~>VIpC?=v~)b^9PHD30p=)X)Gf{(=d^6c|HI1v#)vIqG5s& zCzcUW^fD$k4HF6D#c21wPx#$M!$fZ>Jrkv|jO|UsM8bG6YJcF#?_M-a*fJtYW4Yo~ zSt+j2cfOBBce2xnM~6#k#Kq4zP6sj!2~m;w5t(O^fDt`%4#D*mMe1OVK7uW0_et z4HF6D#Vm8{=O%0!5v4JY49uyUhKYpnVz#`ES0-#35v8%r^xK$dB4NCk^>5>@30p=) zX)JdvO~XXOcyaf#T_sG|G9pT2x$|mQ91{tbm+#?B91fdhL=?^Q7@p+J^Q*&4Uvl3w zPJ?9(PZ%#wZsNq)8rx0SG9pUjZS(!${FLP`G)yFn7pFjRj%{g}uw_J)2G3)7vWA9< zgz@4mWX|I)4HLGEh|=JB3{MErFp)4`oTSW&!KGosmJv}JJdfc?CmJRa#*6coIf<<_ zOxQ9aN`vPyJh4T?M8bG+LNn*Xm4*phMnq}wJccLFXqZSCFHVZ({MXVjVatdp4W7sF z1RV_%3FF0ivYg;r8YXNR5v4J&OFWkK2{cS3Twe91&(bi#Nwe)N*||rJh*jhDi^gOk zVZ1m`c*_T?B_Vpt_RZ1!UK*_7EM+ynKe)w}FkYN&yw!&ZTSi1_uokt{`TYLi7FWV} zU3c9B)UHg}G9pTYHMOPf&hHOyaV3lwCqi%i!-Op(qBK|=T>9Yr{@@l@!gz5u_14c# z*fJtYgEh`&EScXQ+~P_YFHX$f#w!!HjEK@;t#%m`=l2JgzFec`_XoGQ62>dvtgb$2!j=)yX|!vtiG-66 zz8TPIG=g|z84;zy`uw~y)8-5&62^;C;NCB#akV(Jdd#wYCwxrSwdc#+-BJ3_Bt;Ud#rz z`Y>V3h$xM@2ATUb4HF6D#jIv)S0-#35v4J=MCNc!!$iV(F+1D(hY4FoL}|=Din(ah zFp)4`%rdurZo-xkQ5y5ez?`~im`E5eX3N`nWx|#bQ5y3I$Gt%t6HO$H7qk9t+%;j# zh$xMDq&~^mZX#j4xO>S};&3ow%ZMnA<<6^JaZDtPSMI{9pPR5{M3lyI2l;x&_I3yP z_)l9-dz$Yi=P+K}P5!-yJaqZpL~q#>rQy{+6A9zRUGX3PaWqWWG9pUDt9>RC#*4fA z>)!a6mwcG8Wki(5@?_$ik}{DnUOc6E|8xGzqG7_85m6dm?K6=uUOa7i{k0EUG)&ks zB1&U7%!fF-Rplw!$fZ>Jrkv|Jh^Kc zCKASrr+EMA`iC!NWx|#bQ5s(DGm&t4&8u>ckA{f@t9^@QL=^4SJ`)M!#Z%QSA0~QB z>6s{vIp^zYpNWL=;_2{KA0})W5v4KL;JVspBH{9S{@QxlbJ3OHiFw-9h$wn_LQkDf zCKASrr}bO^Fwt8|&qQf>wa-Mtc(LlR^>Y)pjEK^hM}}^FFmZ*(i`A2DyfR_Sh$s!O z_L)c+FIIuJao2<`Bce3ke_?$vafQZ<)vWFMVZxRXQ5y3Vr&}LPT%pTrUX@#~T_)NJ z-(ndNokqLXnn*bL;F~{ntz9%4LA;x#QevVsmYlbFiHU^qq7?YXP-&R3Wki&QSNlvP zj2E?e{Tn}d(J*1lh$xMvC7y5{G?6e~w93DIpJv6C4->tm^h}h- zoOAXRwX!miFkZ|Cw)!w(%ZMnAWhT=!Oe9=hx38^dzdo3DH6n`kY9Di|5DDYO>}=~F zCVETJCQ8GreI^pdi&^H@&rR4eB1&T(8M^hs#1$GZX3N`nWx|#bQ5s(DGm$V}%=))+ z*Mu!2qBOkPXCh&|xO>^I5+-aJ5v8%*d9^E!iG<6m?!wk<6uUo{tJ-E65k+&J6DL72 zwsQj1y$(0tNL&fy#d%I2`n|Wd-wy{9wv33<;5;Wzv_iu~!gz6>)5AXQ35$jaTSi1_ zaGnzALGaf6*{u%ZMlq&U4~~F*Hmhj2GuQ{nGb8Y0)rY%ZMlq&U50V zG&D>kj2GuQef`tFWYI8T%ZMlq&U50#H#AHnj2GuQec9=kFB&Fn84;zyc}_pPtPh$< z7%$Fq`lgTi%0oO)zCKASr^L@8**Mu!2qBJ> zoO9+3J0dh*%m%jlFk#DxD2=%Wnfo*i6A9zRtY&LhCTtlIr7^ce=5S5JM8bG6JKOq) z30p=)Y0N!}xoFcckuYA&GPizi!j=(H8uQ4&oVsb4NEk0>%iDNm!j=(H8uJLpy+Ioj zO(cvLv;J+|HDSw$D2?TgrD>Q*7%%Q#a+Nq7OxQ9aN@Kb6YF8W+3FDQ!u(}^KVatdp zjb%l#-4F6EaQ2HPj2G|kZu@;q*fJtY<85>Q%YIQ43FF24yW74c6SjR-K!$Wki(5 zvU8wmm`E6}d?~mzOxQ9aN@Ljp(KJjXj2G|kZu=8W*fJtYW7)~kG)yFn7w_+G`z%e^ zG9pT2*^$yTOeBogpE~@_)9eau`()NTNLxn4sIgz@654cfOBBce3s8eI2_nn)Ng zW;I*8GGWVzD2-)C*6Q3u!gw(|+xmwITSi1_%spz|FKQxTyqINf{oI5tBce3skzw60 zY9e90m@RMPl?hu$L}|<;+`3=XM8bG6>)*y*6Sjnu&z* zqW>`(m4*phMnq{WCjvDM6A9x*|6^1w4HLGEh|*Y2Hae%QOeBmK{g10dX_&BOM3lyI zLQ~T)kuYBLKdy46VZxRXQ5wrhQ%%D}!g$gDxLTKn30p=)X)GsZH4PI9<3;~t)=?TJ zY#9-y!G3LKOw@;ogz=*PF?%Wv6Sj%ZMlqp2si~zet3}i~EADK1|p$B1(gI)tFtPVIpC?xWC!jl?hu$ zL}~EO9kWX`OeBmK_i0=IFk#DxC=K2nWOj*$iG=auesk;RCTtlIrNKLp%r4O|kuYA| zH*e#W30p=)Y49#5vr9BgB#amL|J%50!j=(H8oZOr>=F$V3FF0cjP3ei!j=(H8mxpb z*Qm)v!g%pKCfBa|{$L1OMntF4uC*o-PCl3gF5^|Dsu9E+%ZMnACFhTu%j#evVZ0~> zW`U()!j=(H8cPi}4HF6DMQt(*EDaO3jEK@$TH*=$Fp)4`v`S`yrD4LB5m6dTk7^nw z62^<(#VoKiOxQ9aN@E!rnudvl@nV!<7FZf4Y#9-yv5as{!$iV(G1@T;EDaO3jEK@$ zM(UHCwwfVatdpjkzVR=Zl(17%ygL zTmLX&%ZMnAxks(%i<(FnFJ_rrKR02^h$xMDWLVD^HIXo0%$B$D%7iT=qBQ0aZarVr zM8bG6>)*y*6Sjh7)) zwv32PgOz>8_O_xwuj~_7!g#Sh&no|>5yF-cQ5wsa7nw60OeBmK>+|eZC=C;~jEK_s z;knM)X@Q1`gz;j1o?REEVZxRXQ5wsaFwfC2kuYAY&$D}^G)&ksB1&WVqG!`EkuYAY z&$A1rG)&ksB1&WVGHKH=kuYAY&$FASG)&ksB1&WV!fMknkuYAY&$BD3G)&ksB1&WV zQf$*OkuYAY&$GL#G)&ksB1&WV;%(C~kuYBDQ)8D{X_&BOM64R?*X2zlj2HXuwtTRA zj{RzLL!4|G5v9SNKK83!BtqlGzQL_NOxQ9aN`t+L>^?)oM8bHn|8Z+qCTtlIrNJIc zcAuePB4NDP$GPld+2NMb7MXO|&SZSEBWki(5(xaM&iG=Z@ zcd<*XG)&ksB1&T!8JdQPgz;jOV3$~Fn6PC;l*Tf`H4PI9YGh|-vAaQz;=iG=ZDRh*i{CKASryO&%g`tQ-(G9pTY`$2X{Gwzy57_Z!gRUb5A z%ZS)CygtZTPQ=CCBw@U`o8(leO(TRYBce2xd*^nqW+Gv{xGUy#tI{xG%ZMnA<&M5- zm`E6}y1ReCqG7_85m6e;lZkWc!$iV(@sxto#ws5sY#9-yu{>dE8YU9Pi>ED|npPSn zY#9-yu{F4M{#F_$Y#9-yu{`l=8YU9Pi>F_lVpkd_Y#9-y;nhA93FF06 zJWk^)4HLGEh|*Y|K(>6CNEokr8W{}}wv32XV_oetkuY97Ro(KjJbNWoZGAA75m6dm z?Q>iSKUMyE0+Rh$xM@C3fqBi7PZ-JgwjQhY4Fo zL}|=Ds#_mST%qw|)nV)BCTtlIr7@2T-TGkS3XNB-o}{0fuw_J)#yrAx>w}z7NIwXT z7pp+qxNE|e5m6e;3KrvTTOUkZq48ohYrB4!uw_J)26tXr?K6=uUaZRH+O=OFjAcZ0 z8tq!^xDrl2I8|^NuP&?)#xf#GW662DS0g1M62^;C;8elVFk#DxD2=5Cn}&&m@uD_4 zRj@Qn*fJtYV`+&ebDg*K!Ne6BFIpw13YLZmTSi1_EIq1em`E5edKae(mWByiMnq{W zBSX_LkuYA25}Ybn8YXNR5v8$=a81KR!gw*-ajIZxn6PC;l!jOPOeBmKqc*1smWByi zMnq{WSDcm)6A9zR)rV6IOT&aMBVyI))&~<;XuP%0`e5P;jTf`!j4_9U30p=)Y0M*Bw?3G-LgU4(e;arIf6Cqk zY`dzg_kBXwwq?tfsL_s4TuU^MlzyZc$jkG*K)O8P)nSS5GBsd_LhjsZEsJIgw1kx| zDEAdC4~2>0p@5Lm;Co!IWrCtFcq$PkFE2GoM5P0g<{tlXkN+IM@ys#b@AbVdKW?A< z{*C`Q&oSp5b50WU^oY<%Gj(%+&}o@gl+Io}=TGks+S4OKLuYsCIGB%7Ov|>Sd=^&b z5)kzCh|nlIOs~=0u6zCZlBd$Lttj1}*H=VCg9JT2A~ee0+I+4?!nUGxe_mfh4Gj|X z^oY>-m(=E(NmULKwiTuO^ZKf5Xpo?%M}$V%xxAJJ3EPU&{ds+zHZ(}k(<4Ho?7+?% zBy1~6_viJM-OwOGPmc(VvXeY(kg%;N-JjRjfSIeQ*amiJFe$bvC5gOXlr`2UDMngDVMQPt)Z4VOk^oY>V-bAe~r9r~BqO||9 z_A3(f^oY>V9!sq*r9r~BqO^~*jt>&_^oY>VUQw+sr9r~BqO>2ij&l<9^oY>Vo>#3d zr9r~BqO`BJ&Q~Pp=@FrkX1M10L8oO}QQ99|=Uo!?^oY>Ve(khk(!4v6u&pTVbFRk^ z67=+l(9q6ktuCcO!nUHcU)#s7>GOm3^oT|yA8VPGZI?q|p^kB0a+L|CYfp~|jq>DV zK35}QTT!Y7eT6zSNYK+GLZh@`)*xY9QEE+ng*r4y(9{o;)S*Fwo*oezWoF14By1~6vxL4v9U3I)=@Fq(X1J_D z!nUF`+vzLRp+SP49uXR4rp_89Y%5B$w!T6g8YJlH5us6zI9Y>)ZAIzmqpx0v1_^q4 z#Hi6cKj^efD@sSvT8?t8&AFndM}$TydGq|B(=x3ntp;j)kf5hWghpz?=J`RVWm-{M z)zp4Pf}S1`8mT9a-~Q=iqa~xj&l<9^oY<%Geh(I zpwlv~D6N(~$1D~k=;;xmk!HB&`9Y^;T2Wf{*Ljx&Jv|~c(oC&)q~v**gl$FX?8Qfk z#exJqJt8#9nO8pIkg%;NpM}L3BtcJ)2#xXv8XapF`Ck9x_&lC%D@yn0FF!qgpT1wz zo*oez(+jl~luSn3-BSNFR z*=VhDkg%;N-Jk!;xz->-Pmc(V@`k3YLBh78bbtPjKVc0L^z?|(C~um|8YFBhO84gv zx!;MUu1L_+BSNFRF)M43u&pTFpFeqN4HES9h|nl+{>mC8Y%5Cl=MVl_YmlI)M}&s% z&-;9kgzbpBVR_oA)*zubquJ9VMvd|8j)ZMRX}?`9hj!2Te6aO|9*NMlUu~VQNYK+GLPL9ZwfjsO zBy1~6`-AJeOM;#r5gOWqtlekQAYofk+UM*!KfhOPB>jFVb&l)Pmc(VGBaci61EkkS>o2eU)JNGW}i&Z(<4Ho%y1LJw4yZIy=A{ONYK+G zLZi&oS%ZXaMQPT){bFm7pr=QKMmgeS4HC8^>W1Y-7g~daj%4=qh*4uaA0%O0Q96p& za+G6j&QtWo*oez<;uib8YFBhO83<3eFGBo^oY0uYJF$_Nm#^BSww!?2d$OMQOiXEl0Wbs$Au- z%U4h6kqC`c^6~y4)3U87?e(keL4uwh5gMrl$NPgMY%5B87HhvEK~Ikejnosz`-3EG zD@uDW>-Zo+Pmc(VG@{1)gCuM#N_$A_I440*j|h!4GmQ5KN!V7D_QKZriUd79A~ezr zH{Ks4VOvq!(_80V67=+l(BR!Z61Ekk-OTm)L4uwh5gO@;Gu|I0VOvr93cQb9?fpS| zdPJj1*Wq zIH+Ed33_@&Xq29~rQ;w8+lo@J^tJwcO<%n|6ZG_m&?qBnLYP*RMwjndEEXi_=@Fq( zW`?Xm!nUF`OVs-~BYa@Ai?f9Z`p@d{3`^zo?F6_VkER1LuR4Fs&#ZMQb^Df3WogO(HbP3Lux9 zgl$D>HBj4w1U)?>G*SzW_XkPXR+LsXwO^5-r$>ZF>WSn1K@zqVrPWy-A0+7M5uuSr z)Odf8gl$D>m08C*33_@&Xp|LlZVwW+6{Xd3ov%pH(<4Hotn~8?N5ZzEwCb<(E(v;i zL}>7C9|_xv(%FlT67Bs#dU`}?lryh<#35l@Q9cWs-XEl=M}$VY%P_uQG>_Oca+Q{C zMQQwL6o&>0dU`}?l)bh2T#bZnMQQwLHVO?A^z?|(C_8?$1_|4W()iP?8X6?%=@Fq( zb}p}V93){|Q5t_bI)nxZdU`}?lpWYvgM@8GY5eIZ7aAn!=@Fq(c9Lfe61Ekk@u#D8 zXpo?%M}$V%5uY_k*jALrpH>~AL4uwh5gNKbuN9NpgM@8GY5ZyR6dEMx=@Fq(o>0gd zBy1~6>rkx%LxTi8Jz~@tpC2S)TTxn1*K%n0oYteM-~&B9A~dw8Pb=|F!nC4vUQpYE z1U)?>G_+q^>rrWtu&pSa-_(9Zf}S1`8roy2^{6yR*jALz)9UyjK~Ike4eb@x>QWjc zY%5CVn{}L%pr=QKhW5N_btw%JwiTuG<~m=Ipr=QKhW74ibtw%JwiTuG|2prIpr=QK zhV~$9Jt_?nwiTtT74`T*f}S1`8oCp%^{6yR*j7}&>Qatf?el~5^oT|yA8Se2b~&^P zEb~?5DiccAo*oezrR2w^ax6&LR+MT%tH978K~IkejnaZygM@8GsWr6<3=IXljrh6V|GdPHcH5tTJa*jAKAmsWwHL4uwh5gKJ?$QmSUD@wD3R)L{G zf}S1`8fAvd8YFBhO0%6-fuTWyo*oezWv0#=By1~6v$j@&p+SP49uXSlh?6x)*jAK| zK3a8#1_^q4#HcYoKS;v1qI49kkc4eTX|-JED-!hdh|owg-1z(;3EPU&s=v;=B&8)cp^?b9wRe z{q9c^t!GMv#;s{@?QLi0HN%30ZAG2^@;jF=x!UjkBtcJ)2#xDgoBw>QeHJ8aE9$xT z`9>?>YK|q-ewIFi$(SHh@fATu900A=LV@H zm9VX-^R~aWJnNjlF6AK6dV(eq8ecj4oMTf@$#q4-wxXW%x_@1M?r*I@f}S1`8n>Kv zh2D9VHAvWwsKqK>?$PzAco5ZAIO9`C?Veku*l4^@JXY&`2fUU+QWg zVOvp0|J--2YI~5Nr$>ZFYQg=b%?A>;BkG`4?N=lgi|XkSL8qR$E`4_(VOvp;yWpTz z9UmlGPw0^d4UNAt1_u(h6?Nvl@3yMroCG~RA~e34#^0yP`5+0~irRVU-BR!Id_{tu z9uXR8hFh08aUfw^QCsi5+p5mHB7D2=~= z{EavtBw;(E?w;z($1W0!MfLQEMk60A``w=;=;;xmQCcu-kg%<&XidMDlLS3IA~Z@*%xh{AwiTsbdBLYXQ07Du^z?|( zC?hIskg%;NjjkhZxvm}uHEJ_KPmc(VGBZpF(-C#h>UsCE1_{kL_VkFL%M6z_NZ3}C zX1lXrer-JtY8K5z>j^y)p;2b)31M1MnziqLxHU-7(<4Ho9C5M+3EL5+qmMO6#E~pK zJz~@t-!DqSwxVq}k+MKJ_6FDIf8mZ)3GfW86iqdMJwg(A%dPHcHl}y$kVLPI} zxpePYEJ$dDWKWL>I`u@Y;j#t^+ltcatd0*7tta$IgoZ|wM-&O$iqa~xj&l<9^oY{xXpmSes;5T;{nKgu?TqJxl`yTS^S0l) zeBaltL8A2pO(HbPOr6U?!nUHG^SY~+k9hi@lyZ=ur$>awYt#8)8dX_?gzbp>i`1{I zK_Xp0A3Z%{)VQW-3?ytT>f-0W3*|@}Bhh+7k3?u_{H0N)attJFE9xazzZ>mAf}S1` z8mR^Mmo^_r*p8^H(XU7>7S+=ug4Q`y>AR_}Dq&kuXC844#s`Vk6Eum?NF!=IA0%O0 zQ8zzuKgKx;dU`}?q?ut|=8}PgZAHEDw*8o|NYK+GLgRyJ{GAqa;y}W-qRu*Jjd_;@ zJv|~c)Th)_)UQa`R@CSIc8%i)33_@&XlQJ_xja8e!gfTxC)JgYT_hHZ>gf?xG)fC*4HC8$ z6|H%3(I7!jj|dH2kJ0Kj4HES9h|nk_Dr=CittgGI7e4h5iUtXK zdPHdG+OAfYDhCPM5q0(Q(&3FogM?-rdwN9BWroWdBy1~6v)u>2^oF8AqVq}k z+Dx>bDG?f}8`By302m1FN&EJ$dDud4))RUpLL-eRoDbHtOe;#O%sS3V(9E}6-gl$D>)nDgb67=+l&`2}2&T+B^3EPU&*-Jf2kf5hWgoe(%ZvBloMv<@` zQ9Oqu!Lz#_(P&(wIZ?#B&QJHy(tc6fF2}R}@vicF(a40-t)8Gsghna(ekqW!tti#P zkx%<((I7!jj|dH(-I1`ZD7EIh&i_`?AVE)$2#wMc*D41I+lo@Je8^S*S~N(|(<4Ho zjHs+Z!nUF`x_G|CYtYml%VQGc<#`C4m`&~eb7 z9x-Z+XLlrQD@sSvT8?t8Rj%^cUG;<>iO@(TZ_WozI9)|)HBj4w1U)?>G*SyT=Yvkm zbVOY}_MUtk90{$E+^>2>(5WYC4VOz!!nUHcI;-P@MC%DX5}}bsRC7M)v`i~XtIRsi zNzl_HLLkW_=@Fq(MpV`yVOvoeU7vo@9Yuo#Jv|~c%9Wz5LBe)KUA;W?kG@_s zNNC2fr$+=`=EST)!nUF`+Z}x`YmjI?p+_P#%1oU#NZ3}CX6;X0_O((D67=+l&?rZo ztUbJco6k3?vsk~imrPRq2Sv>K@G zL4uwh5gKJBlXFGFc0^q{_MYkap!-#i2s-sdUDMART2q;@tthR|>i8hhdV(eq8fio| z=Yvkmw4$`itmB*nJv|~c(#)WHEV&#cY%3~O%bu@D(9C2@j(qmg12fg_7%isL=XN$%h!6@6I!SO+l zZD}Zd{eRhu#T>yX+o7Q{C}%o4(_=f*{Y+YG|6S3TBUGC;D(uiuTd0Pm;i&LbLhY^g z3B5UjQMMx`-ECLjk^()pm9BcE`dnzt5sb1O8tUol@zS8jcBGqjoh`mxH0FrBH*Jgx zV${%H&Qe$O)O7#TgFc9IB#kb?DBELQ>Fh3R&|_QWIPHahh4#>%z8=9S+o6$KaKGD} z9@|k@??sQ9BNhurg&i8HC$8Oh9TlER42%63A9DnwY)49IMCt4<*A+dsRgQ1}w|8Tl z&k>BW9U7?&YmF-PD|&280W(sViOO9O$vFbX9K}FQHLtSH!|mN{dmpL!-1{)}Y6>(v9|iZ_xm; zaFo(wlc<){Q4SELC%$*7v>0VOG|Gs|8uZv!x=LUFKQut(5hbtE zVwCOBC^JLWpvQKk``)F>6*h>4qarOvg&n__87^yRzEWD7gxXs*9~vN11y_Pmwj-r7 zQ)dl&Y%5*$TlJvO0I_hC(qfeD&?rZotU-_MNLR-zYk*idD$-(9*rSGywbDp`^i)E} z-C7RK3O#~RwnIa6l}42m=&`MGX#G&zV~${y?aJeAOTu8xm6f>E|3B^?7bs-!@VZIwgoP>qBr(;UGl+o6%lpfz>YpvSh- zjrFzXt2u&EwnHPeh0YD~EJ}}UX=oj)kr3sWBN$~nG_+FEs8U_gV_WHJ9jcKK8gm4r zY==hb={obuM;v-=N4jxF7WN#W)oMLj)^oV{7KBEX%HgO`uY~k8UP2><4T??w+0t9A z@A1`NTfY3M=Vv=&6)xg_U;2~fTRxtimP^DDXI!@Y@~?j? z+xzytF6Ho(*&Yc&Tc7^ogIDLAfAmVkzCU~L>T&Pim+jyC{_c)) z;_u_gK5E}7EiqU_PjKXCtx{AxG4ioo4z*@ej*(!Lo@2>RI3;>QghZ+GXqKPBiP@mv4$)#dN}f4%k~!6-jT zFx6nm$Nlshwa}J>r6r-1CjDyAI48j>&xt0ReL7-I z&_hDc|Kuk?-5!I9)>EF;+_Q$BcFIqECPL3j<)<^PQL@&KC`NJom*7-Usw>uydW^^U zq^?E{dPqcHhIiyji{SDwe_2}bF;nMqv@DtYVqW<0B% zYLwdZ8h#2}Jx0$MHEmw7p(zKW^yHKKSgXM~!_VDGgL6zv&_lvc)J?}A2}VVqet%~! zNs4KFq^HkPPW;rCY}M8G{n!89AsFRnuy!Yy770I(H7y4TMsX&}bu~nd4O^|JJSCRO z;is#n8YCDsKf|#`{fwg0ov+>2Q=W-Tgr6mx=86QP{AA#i;F^K!1b-*6AyRz}d6l8J zCds3y{FbI@ocs9F6xY|%qP-#c_lIey6hZV-&p+NZBU4+(v@QSV=B%8_$Lf>HXK zq~4}95@W9D(RVHNJ|smkr6_^RK@SOic~fsX8Z`{A;z6YxJ7WE0Q2mSR^MfoeG zQ-U6UXH-$rc1qK7*h9i!5S?l;Ek^l!pi_b#f6;UAxgz0jbxt*yD@L*Bw#?j?+3uWU8^ z^-HDYuT;v`xuH{WVq>cP)3%6>~zu zU#x6$l?pU$kzka+KiLqu9OG9iQ~fB)?X2_L{`t9T*K?HW$FmyeG=XEur4-s}Y(@-g5Lu^ZB`Er5``(#%#BQ zJXd`F&$36v33pvSp3(QOOi05X5}H?z{O^}_G)OQ?weFPKT+u^9GtrB#_|uLC2}WtY z`d_DQ5QA3$zjpS=b6Sde*oVVbO0L6cuIwQpJ*Sk3l)nCA&0vC2Y^R8gf8)s6BUB6f z-~6#o$(a_T*#0^7!5ZuhI;x%W^$+KCnNq}>pofI!{PT~x{s6gRl;-(+Kk~W`AM;{W=tca6E~_Y&pG9umsoZ*O1K(ICMnj)Gj~!6j#Ybp-g8ufA{0mD?#|O|Y&= z=veX(7rl2TS5Avj%W>L>2dmA4lG^6(WF4JO^ z=G|sQm8=b09M6jKY{2n9mSgZ3bje9buRmWgtv2eU<-fcA=Q_2!SX2)Q)q-c#HdmU% zJ#uuU_88O=)qPqkU?E@4_a)_P1Zx2*;}B(z@Xk6IFpVh&pkdPqpm^U6HIs7c9(;M9VzSpNCz z9-Y^N=brJ(PRf>FBGf6%`Kol_q*nC^Wq{jKGlXZ=XlBOUpPf7N%Z zI*EH+`rFHW*Zy#4^-6+KuRrBg%Wr+_$V!a4qUW$rzH0d^4~ZzIG@mOHi^aLieNTK; z)hJk74n|4issH(bGeq^&bftIuFFx`B1fx{G(=T{LhoDDwb=0*F&ry5J6$!P?FC858 zw60tZMyW5n^~DeC>@8O+xo0BPTYoNLT8vW5 zI=5r4k`Zlg4+*ub?=H?0ZB)HC*%E9i)s@FY+p?93mA?BA3AK&KV~tlim=>ed7y9Fz zp6j0a!g2m!O7j{d7K<0o%y4a5HA=s`)~6cPQwiyL4xT3%#Zi!nA-Hrm1NWWPGwKTI z70ag_dPiN6HN+Wjy??oO|BB`E(T8PQb7KGgx#lZJX;ypIqYv#9k*U;zOpAo(#}nTD z{hj*;Bp8*CaJR%A{*rwDPiVNbIvPCi)O+M~HRpftci+8gj3sAUihAZ%2Y(0UAR)b< zc;@$3jc&;qrSdtqyO*P;n~sUM+;c{wrd6X@3#|t0Bp=moS&SvGDOIMeT@q@W#W!17a*iECa%>Tq6-I$42fBBfzxmSmsHBxl!PN0Xxhp#wh^}8?lXr?n!{u#EI z6MeB>-;1Bkm1MSYp_02CfBcCP#$M9qu;y#nqKCv+&OKr5Z#7;mNPSPNI!EK7Em`N3cCu)0!VWkF~j?hlFO=Nt-8h*doCw z^-v!fS`B(gL{E&J!1Dy7CdZEqe%5}Lc*r{@Vq@hH&}i$!gz zlU}<$wliC{CFmjX=|^pkeQcg!6pxQBK@SOy!T!8Uf>B&cWQ`$|bba^u^tGfI&+5C{ zg|E4Uwch569ugWWSNzul%?ylUUl=t~&a{`a&N3>w(`C;eiDb0%6$!PC%QR24QME>< z#Ld@!KG)B6?|l5~^{2$jVsE)3u^4`Qb&pG9&+Syhb33Cr&$q;1{)fk{4*R6nIB8$Z z;-;KK<;uBjiPlqz6F&1}NU1VWyH1NyO_?f?+T(Hm>9J$|=-C6)i{VFSN=^?6*<+0~ z8k>Zpj=Aor@t6o8<%%Ar%jX+fBA$YXIs7qC-8UY?_4J5$u&xk16wOpUY{rSkR94OELhGg0ljepKtX{Y>njZF5Br ziD(<_#vOtiw$$UEf6-r!J^b9)pObE8Vq z(DQYE_D$cu_C0fbquO`hYrJx$uO)jAgT889_emVKYIa$q9O-Y^(l>*>D@5NY_MQ^W zWBpv|3y$97p)W>SL*?+EkVrlL)tdUgEALxS$-N_Co}h<>>absO5{%OC{c_MlLSI*P zO}FJB!6>%uNDP~`+t%nIEANdPiDYP{Ut3M>;hJ77Hd?S?T8mZ>3ALVjADNqH3ro#$DN|QTZkCY8xl)fYq4D2n6sRQ_rEj=5 z}Fy4qW=Na%a_p6zNWa&N~h!zj&go+~pk=8AKl2+t*)D_aeENGOM%mF9^y zs*bdl;D{ojI_&pd5{%*uK57iAEA}6aF1PvK`Ys8LX3z7ZMl#}QK=&&~X`K5gk%^Qe z{S8~X0{oaKeBjtP(x+9o{?bwZq6^%}D zzH{tI&_hDcrTdxjNZlG|z4kvI=X(WzwEqFe`Ree!mrpt7$*J)ipJ9t05-&XU)Z<)-^8};Vr(1%3^tVp` z*>S8;yCvu$@u@#~=5fA5H%~BX-@czbu7Bn3uAh4RalX3z(N90-IA5n`pUxUXC=FYB zSB9@_J^DXB^*CQ6Q*Qg$0O%p1T=lQ%GbcA*|Hv`#lUzlnHpU={hdtwmX6lM*F^cn8 zPJRdxtt@MPRlB~1%<`2C1(^Gl>x6__vwsblX)%i9rqy8Es&?IiO6kC}C<(Q!`$DV1 zv>0{J;<)1`cNzxGiJSpcqb@CHj8=ml5^5XQ^gO{RwST`~>0Hq7EK!+!9-YtZ%DH;h z7(!{-qKAZRpCLzV`ZrNi!cjVE_Rr|)VY;$?hTLjw5{}Y3!grKMA{oOLJxo{jq?Zgm z!ciPItp+_zx7$l{u1GM7v(l)MbH%pREaBOQy=Nq{20bLC;dyMHV3cy`dloIBex+5i z)@{*a4$HP`!TT>;f*ulTS*@|A*L_GZO1~fd=zGo(_K;9t(3-BVVS-W87_X$GAaUfh zhXiXKKVao{#Z!yL_sZ&v}kSGSV~Ec)FK__ANEf zRHyXy*Ai{iNz2LGtTK`A(T^Sy+NIamAi*fjxqg#Y&QAGf*wPr#wMvbHJg(C{N!dF0 zX*5QH9uk^IbT4l@qIBfaT~K*+4AdR?y=#!rs#*8ery9%^qqMfxz4a-fvo7sp2+s}6 zypJK}Ft2sBuPEDUh$wn`t4hkd?rF=TGU<-EY}R3^ru?6_c1h^StUIuyM#17uY_3Jk z>$;z+D3-6)pofGsbT4NHY19J#)t0N@1840adfpB zs!{EainMN6=KWYHSGp?FAGNKg5*h_HrJ^#ZALgnzR zrh4=ISQS)P^r&q-qcWwIpofIcg8MTA2}bFB$}>@`p>rkoYPNqqBPz#|mY|1(Qu53< z5`#)k4dujRkn~6-qwQBDRHpvC%d{B9QP67WevQ{3x{q`5+hZ-FE2&=9w1lpC+oP-X zPkh0T<`JyBC+9ys?3U2gQ%5mfT}kZ|^pIFA4p|+2A~c3j(!SUKb1VmQsC$JjQ;r=8 zdPwjMpOJd{H&J>Ppr*wrY5P4REkO?nU3>4plY`|@)LAz@HrFn5IBFiK>HQRGJg(qMkocOA92 zx+0-*)8s0pufMi-+o+n`h>d^Sl9SL3UhAzgEzw5RTF>!=HCQK_OKPj_C08UgkM(;A z+k;V@wQDIct~h{s@48<-OjWa zrQdx$s46H|^pMcGdH;$R2}bF6U!|IA*h3d{Bd4f^W@HL=J4C&wWzbJ=2B((R- z*8nq7{%HwDX-Aq<8i}m2@vhRe2QK#P?)5#Xi;>Vc_qDUEk7{Oz+yw|p%v(QP@X!F2U?w)~A#6Dddf8@BwtOr@*0&bqYzR%cU=OwdC@ zZ_IX0N8@nky2F@)r_!C&uptmR!w`sOqVsNTVx%>sPIbKiw0qqmxmS z5ml&mMEOgx$~(sjBvK2~L&D#HotB&gquPF4RrH*29S0=*4cMs$i8g9(e6Xeb%}J%p zmaTbG-=&9yza}}&6$wVQ^P?L>8k}p@ukv@X_uNZJsORTzeec>!7^QKOzb9^Dh@1^u zntiILd_z1%=_*z2p|!SRk5~0nLT%$R)p(VhX)#Le@1svkX#U9GSkL(_UxEJ)a#ab< zl{KZR(&ma$ZH**i2rAv1Kz?I<#8H&xs|uSXC!wQVa~v#Kn=3}O$E&K6?s?&OM?y!t z{#-($joLU4j=55A_v&u*OEg{?)I6!=93LdE|H2jRs;|*-T8!dRqSa8|FS+NN^GZe~ z|LEm!%C_3WyCGVFQEHDTo_X;B2&P3sec`4j{b8nC4HAq}&wt@l|DZ#(o~xIa4sZMp za;0x!n^52Vz?a_8(O|9^rJjGv@AL?@V6DX~M-9zH{c=PviD!v4CtmaLOLI;%qdxJ> zx3;+&)JxI^)a1D&d(a4-E7^S}89F8rR z33^CG`)`yZ=ZbZrdEPyvt;12Jj1Si?iKwgSl{MZY$^@fS)9(2rF^FKjOXI2w-j?f! z?KBd}h*9f3J|tAWBVP0Nwst2(8+GOKi_d;XB~p&`7e}1;echg`$0!}=HSU`h%tY&{ zgvL!jS0ot4*38){|HRtI{fC4`u9pOCg_SQ>C=y={A=S-`O zsw2292m6m!FP>4EQcKW7LTg`-=6QlqO3D3gN>ooxS9%`*^8}+f6SV}tuNFCpD^sVP znr5NybE))@knMeIt;QzdC~0f{n)Y^jm~QCddCnpf--&ZtjQXB8{ps?Of9^fiNDm3E z8Jkf%YLH-*`dA&!4&NN-9FIEUJmTpw&$o3&4+))%Y8BAb)gTQLZInjZhDIi03>FX4 z&FQEA-)N-l=@?bhVwA>XzZ~?C(CnsiO*Kd`s$07`SM-q39Hv=rszHKLZOf*_%ipk- zucDPY(KRu*fv!3ENaX0a)<+KsU5%QX+iO~k(zPtl$5~?trFPB06(CmwW3G}BD`c)L zJi~EKG*7fq+M|PhH3X+zRSyYW#j|#+vGF~hboDfzAlG%qI`dT~?tj2D61rB_Z*!)_ zDE&TZ!6X$L_K?uE#D3r9U48C>)4bxlfVC9Tpoau^)6El%QcAvKIwkBOA=|(2PB?1v zCg_62dpZ4HSEj2s|MlO+s{2~H52ewmJ7l`=C42r(gYE%4O1l(H>zaN&3$G;^wsfah zca@Ybuly?|-K*-%4DgVUp6>pQ#1J~emh$ejR3=AF?q-a2#k^}*h3>66hy8M}ge39~ zi*yfk%+;ttf>A6}3C{nCuZH^02np%wPHA7m1f%BbiuI#=j!t*JuIM3=@A`I2PJ&VT zyrL$rni<%4wSPf(E)})679^n^1iFja zXr%15ZO$m|8qmGYkw`hx-;lm5{9~g><#4*J^@xpsV|;kj>VB~9jw@Z(VN1|MLidBU zFJR17!QyV8+m=zR=~hF#HMHA7X=&Gyc5}$)xM>MSX&;v9d4e7is@+MOC$VS`mxEDi z8~2ztSM;dOT|d-r33^DVzqxJZ2}W@~9*IHaVE<9cwO7iu>ltGtlF{}=5~_9W<{H~P zrLVu1VAOn1q=$t1f^!(D$G`1eWJYlm|wgH z{rm2Oqj>kdCFo(g-Fw>!9k%!+0{3r=?zbR4B(#P}#SA=|$@ef@VzIBIf^GXxiedj`{$ z?cXDIj&PJTn%>@M*u!*X`}e7aJ&fXcVoT6NVtz+F2}X7Iwn$ z>1j8&Y?~{+2gNHEz2U@bA3gKeCz!6@?c$Ziyaqia^qv>5YT8_pV3gkZ(qAnx?|NI3 zSAFy4pofIs=j2*wb47wtdgqJluqE`iB)11?y`#!)(-QQM(EEy9(=9=Dy+6kFL%JpC zA)z*$wMQZu@zk$1NT@yfD@&%uD7B{BX4J^J zqDQ^Nt;v)|Vv;Ko>Y>d!XTjQXFiN9qvTo10qDQ0FXApbK6$#B4jYdjee{HT9HQ#sX zA)(o|Uvd(R;<$-(1_yOX5(GF@g8zLyW|}=nMl$4ORGM3NJy_C z0@xrJrIcKzNIa0xu!jW8RFV%c=Zb`FX*6vNRWr9)K)vy0QUiT?Nv1ahB`ZRXuphJzlA=zV^Xr#-v8j&)3vk8XJle-d;c7V9ul(mMmS0-`RrwyD|?u( zZ2!JH;V5bN>}5*W!*pf)_uUCcNuxi`>0!FE_eMA>%F#Q=p@->)-d+gL3`)r(cv^CM zn67O9zB}P4X?O%r3455XZ2!JH;VA7k^tX&#f*z(j{{`Z7WJ}*Ue`vm*pl|(N^6aoh z_eT^xB=ly)0~3r=N**h1Ip`rFdvAoJl#<8FRKp&oE8D;CPB=;$9xGGA9;PeXzwb^s zN*W$3Q^FpmE8D;CPB<#c(Hl|pFx}AG3*j-Slss0Zxw41p%J%QO6ONLG$I6tjhv~}p z@4FL@;`hW`f}S?rxvx&^in-5Ub;aCg*t&{iy;g%B5^>j|cScWwQM$9?D+sLyJ-U11 zYYt4QCFmicyE6TAP7;jL)kvSWwHmtn=KRLJyC|)$U-j#X9um55=$ali2Cek<-dep; zS1T6f(5of=Cf~S{NzwX?x9QqLg5`@?h4%>Oow*$eLHS+9j$*p=b;Yz8rS)6?yq2E0 z+ZSi1Oldw>By^{-ufen!r8}5So2PoxUtHPtS)=-u&jD2n9`g|!|E8TB@Q_fS_7#hH zf>9bPzOK;{%&+d(x`(rTEkO?n-7EI!nkN{=Q7{sN>Po%ZS5nm5op)*X>xv!{(&*O} z2}UW0ZkwE|lq3D6x1^yKHD5W0Y^R8gf7=!$p}Er68RrQ`ajZ-Uk0=tl=h?qz$+Q^7 z8NAitETjDlp6A&YT7n)D+CS0H6$wVMou(S@4J4%3uU)3aDE7BeV^Ev3H>kIJ1T&?P zNJh+X&J_ubwEndWro|}DE0gObIal;(zVekDrZk@`5}GR;jg-Fr+Hx>zZ@ry_X6=5- znHHmT6m?BUe&XNwHlVI<$I+|4g;ZzvzSGzet)~*)pFB@6N-6cv4d@{udvAoJl#*Bd z(_GoZbY=VZ-3doY!>j%&VGq-l?caAN93>5}`lp0FOjovl-<@!jG`#Ac6811%+5UZZ z!ckF<-njuiOgHrQLilV#DS5`2=E@$XE8D;CPB=;$K1xgpdzh|l|GqonC~0_=IVJ32 zy0ZQI?nI56`%0zW7Ml0@r1dV-)m|SR*~ay55gN9%Zq~gndG_sl{!(|bWb1sVKbO!$ zLi5;x2}UU;kNLLb^pKFfH^Na$$zy)1VGq-l?caAN93>5p`6*!!)0OStcPAVr4UhRL zVGq-l?caAN93>5p`6*!!)0OStcPAVb<><`}^f2Af+Y8~jL@9a9Pjh7t)0OStcPAVr z4UhRLVGq-l?caAN93_o9<}0K3s#OoumAyB@Q91+HS<-Z7poi(|{6=SDQ-V*8^KAl} ziCk~B6k1==Lqbob9GGB~QgXdbHS8fF+rRHlIEpjslyHqQUD^J9cfwK9&ubw84 zTFu|A)sunxQt7lD^pH?rFdd2Kf0G6YM(No_ecN=@7);PZLSNU>_YX%RfTW=>+~|vP z^62|G`W~HZ(j_?mN5_wvUlRH@kG_T1Xbh?=eNjbUi()4C$TDE7BeBN_2+C-)zH`%2%> zblWuJqhM`MB%$7;?{)5;D@M(a4?Sh-ajq{Bd2Dk8x8zLFMloAy*;I`zm{MW+dpFC-)IkOkkCBl9L^Jr>WE5^O7u>KzH;I-h@I_vX0b^y zigZ0U0FlZvtm_wVck<4GxU#vkUBAx@B31CP)|FpJ)n~hQw(B!rg&6DVnCp&O-S^VJ zPP-6xwzZe{+%rCr?butZx07ya)VI^^Y}fbBMaiw5GBf@S>#g_RZS|6?Ka$hhdFkEK z-Gz^3TdT~t?zgEy4~aAHeYe$_N9cLQ-3UfK?t+6>H$O1SRI{YIQm)S1{?M3{xH`DA z9eUTd8iNRWltUBJyWmrLv+8E9sPW5Rz1!+Julw*sZ_HIPhSb|@x+E5hyQjKJ-_M+A zkYE(+aH>)3y{0R@i=ThvjD`tDv1Lb%LFLe!Q{oM=JKN8_&o|Ol;Hc61hR4miqKCv0 zw|rySuU!(1y5LiHEswb6x=uOT-f+pjnnrJc`y`JGFTn+VPSCW0Oks&!p6oAweCjEb6$@ffLF zgB}v9bzRk)YOoxO#ht0mqrWnTtw!sqgi`WY8Hqu4MS@Z6ZzGY6wkMKMjd=Xe6O3Z7 z%)}6!j%xlc)lT}t&A%?)&hvFe4~g@(zqRc5D-vzgH<#|mo4KkUjS0_#Oesp>a?nFU zqpLsfl3)~jPpc7QP4`kX101w^-hE=Ew)0qG2Is2vR6?V2|mIYO$z<+UD$+>&?2m5sXs%-~aF)k!m2#`r)Z>?~OG|+-cg>VC|C7Ow`X6 zi8iX%bZ&`MPx>3y+BcNn;F(IO9Y}h5PNmffC*H$^Tn!==6}v^!8ZOcK&8LOvuNjn< zJtVZB$SLLQlz)ab2}Wr}=9F539unG57Wbo3j)V?tdbAfV?o{u#_Mrv|?S<15cGF%$ zf>GKFr>E+s1U=fVqbKPU#gyhtPC~nb^eo#{gK05JdzSS4+LX{iHhQk-9ZVFpA?p#||bq8)#RD^Ujna)&xByw5!AQmScw= z!Kjn}>9NZ*9&&80s{qodrH6#>F85oI1fz7{x!+3^eOYS%M0Q<~2e3AJqhXuz}>#U9#fs9*Vt zhx(Ov;cCWFzlwWPn>|spPh92N+18vGdogylHS@(zj!l9d&2ZYo?K#mYwYj1O3C&&F z!`+_~ofe~1KL6fo&_hDAUF=ocEC&fjX-&%SA%oK z8kL57-=ucOT+u^9E$g0Ng7bfdH3>%P*xnye^k~iCk;*!3HRvIsl=^cC2}ZGpwi+6> zvG+Kx(8p8QJKMT)f68n1L^h652~`XFeF=$3JH+1l;)mrZ-P3VOqsFjFFlt_d_YIW8 zx(a*6^3PxQ=$TyELqd9$9`jYoVS-UA(=~_nG+5gEUiw?hUpn~V^Ci!9#nO_v$ECl$ zJnGt@Yo1~Z)>>rL>rZ*r^7IQH(JA?1pM2Hw_FsHt@tm8Useja%tA5E@+Qp(0O6gY~ za%4w?1f!IzZ+)vr(4%tfyY`2_gItkNz1?}%j~pOZjOw;v>4`60UUoANXff9mZo9ednYj(G9dGek7CJ7gdcjJoL^FB*izR$^@ZcOV@mV6 zBC%M!a2)gV1f!%eY4emb_4b;UG(4|#i6j<1(P@!T`TFw}(_)nR@nlZSxuQqo!}Bgv znwH$TBB8PA3M@+Vi=xheSTY-LhzNmCB;EXibYzI<9>0ci+83(4%A215dq2j$%rsn(}{I4HEg7 zc*{LI8f{wX$XTNFyK8-_Q9YHA-cLO9duKFEFiPcn=2ZuG2zv67^A^1+B3jca&F6}Q z+UA6Je}6}VC1jNPLhWN!CEX<(-xU-q%hS()Ku%Y4`y^L`+MFJZ4-*<`N8J*1RoEmL zrCGbug~=K^o_j=TruMkgT;d*@<5RT$hPCDo*GWFsmf96DDMu#gA)(o>--1+Uu2dsU zu5zASa(hUq`DoW2=Oh@V-(82J#-R3Klr%j1bcuwv*BMBteEk`YX)!7v zA2(;woGW@%qn@dm(pZj3u1KhDJm=37ZB!j;E%Bl2S1aw7)g1NdM{TdP_f_^QU+}b* zb_q_;IX`^GF{|Hw!AG;_?4LR&-RF*dD{tAqTxs9-lsNZeN3ULXLF^U?A~Zy3C;OD3 zhlI4x{Jo7mUb(JFFzVG`K4$gO?Vbk9!Muw&_v&6b=pk|Y#mkj;uTRTCqK$gO%&xG- zqIyVNbm4MJ4AI*w!KnF?(?ddfdN!b64%Z^1SnFfI%DJNF*1un-J$JEVk9}bzk}<65 zA@R(ItybFgJObd&21X<4>G0raRx;=^=5*{Z1Uq)Ru!p8+FpO z1#`*MRkhJW;^gItGvk81a@EmxNO4k6IFpdjA)m zzIyzA)&VE&xs@$rS{j;NYnP9M?KN4#+2H+qKAY=f!lwcVAQ^SC#>{5$TU|x z0%$yXA2R31R)ZcA?4k1nqcltO>xv!{^Szxt?m-_pehqN{`kpw5A(V!-#?n@^9^pbc&1^aJ#sndA+Z>KblQRwf>Er)6gd73>&An0^`)kM zo0DKvThmEm2$^BcCphYtn$lH+^jwIK+BtS47*)Rv)geM6wK>xw@yqw!H?!U)!6^Oi z)-1_K=CX!8Bo>Q(I8r-H>WTD-@G5if8YWbx{<#6uVpM&LJ$howT&zWXB-1S6Cv7we zn)Yx}@`$pBgl3F;T>3Y4W*7pAF=&EO(ugi2lR(`N0`LqaP9eMfwHbSA+l{qB~X z=E@!tJkHM(jFQIKPC(keOG0b-X3bEjmS7au5|Bu3uBQRL!%$BHdQY(l3F4UxUwrWDobyvnrkU*d8po-qqo!6sy<1sd3~hEt7fkm*sz?3GJFuD3yaox?NPk~A(`us*S^2q;tTBX=R{GyJrloH% zJ6Ea&@Az+XMNdoIZ>HoV^gUEMS zRSrL6qFi|tOf~Ewp?dSYGEXpSz9%+wRO(~S6?=ZGL63T+3H9U27))raEL{#p>6^&? zaZZoEiR`(A+Vi<0p)UjXXKJR!D9(1R24`duZfDMwEkO?n<*?~jLvX{IL>pCSj8=oA zmW1liJ%65H6lbEA&~-3fw~F=04a*DBWeyb*F~NxuQqczIAnb@3|ro zZ%EkCnBz z4+&j~bZgENjMCLd_n4N@JtwVN)du;RaavKz*41aN6`K~!xl%jp+NeCF)v~&>Iwj~K z(e3S7g9M}0{&n2ck__wClkN?TqllwRi3g?LUdy50t}C{iWvU8lLFS!=Mw+fEPD@UL zQ5wy<);J~9Qcg=P=v?V+#qHGQiXIZ`F>a?!48aX+5^WUgt*U5!RXrrsr~7SAf>G_v zM-A2$dmm?|8oxPTkD-w*-HQ)Xi z%;$V%q$*0+kyTo@Y|hmXd5hzRdz?zHYtuovcA)%VK-aNr5&MPg!ysPBS)ubE+ zYx^z<)wIjkYA`KEainEp2rkY)yguiOoGXJ?gB}u-6*4sH`h!urrlBhpP2Ww_u%?Fu zdr!{Qs6m2JtdUHVf7;q5G2auJ7NgihTMa%3nP%yw&)c*wWA5loPbKvBq)A;RvDjbY zv>2s5MgG0b6+I+43g!t$X}4HkgB}u`l}3$0<Jbu3hG(3=T;SO4D2ryTR-*Yw`p zqPKNAO7Gz`t!HL@r8sM(^z}Eam9FM=X-H4Awd~`rz3!O)-B+fo_YCUTD`KJ%5=ny| z68TMtS!`TS98?bGm*t3bd%H!Lu5zVglgrV+4o7tosu9=Qv>Z;0 zQEDgGdP^|xdi$kwHD3;TNaXiuc59aeqvrb+JtU;(_HWBUf>G?#Eul9$>bRjc&>J0f z)Ny+>eYaq3FCnpS-%lPlxhFihw|ji(U6xwMNrSmeQ5=slBK1<2<3Z*xTt3AIOGgC4b@^Ujp!HAtw(xZdUoMsYqKi9x-D z{YT~S_+SqmiDV3GdPt}aJ<{e0M(KT-{XIo&DUCt52V1t)pofIUzgu>mV3cw-x&JY! zB{zfs*%VVn}nnEE=#TNrsbfA>B^qW3|V87aMa#L6w~dtc`8u50$>zpj1)Nj z#qqY4${hR*R_A3%Gnop`48QUZn#XeSoi-yi7avw_lRd&3Ec4u3C zSk$x}I-_$`T%SoPCR*no^>=4UxoSPS1{8#Px_aiQVJN?s(@zO(zEjq@Ey4Leao5rw z61qR!f6`lLza|)^dqsX1L90=}B(SrsJ8|{xAan1n)fs(mhg3f#bbqJ+-VYLt(mkEY zTMAP4;=Z$cweDs(@47G2lzfQNsIKm}@_QI`|I6=DP>s0O+mh2mLU-l-=7o_+I&t6G zInkXsztMrUJ`%}jTabh_`tLPhT8vT-`)^y&eR97wK=tGI4Ct;?zvT3gP)+yWYe0fg zx(np@D6}P~M|XZ)qfDtK=pmtdMQ+V`f>G*M?hBb1f*aOsTeXMt&c4uU&_hBas$W+m z7^U&(wrMpu4pffX&UK`<1V8uXA*%ev>!6O7^rZV9%OW(L1| zg?(XzK(8jDnaJ;bnJ3yPe`T+Xwt_mtSJtTCWXtEZ~8YCDMJI}BdEkfQ$79JA1?&{TYn=7WpDE;o0^OUfM zM7}bdt`JXG8BB{&`n_3^NoY`A(L+LSeDAONNH9t}Gy59!kU0FVBUi8f>@9WmI_7HQ zjkam`U+kOT>)Uh}BcVR+GXN!@{|1$uX)&sP0T4YgVd?7m58SpqYTr87I|$>g=D)72Z(@AsuYDLq4Xcx_iE?poSYzmTVAc>PU1 zL!y42Z#RNb{2D{f(-1jRuC82u@!9XldB5OOS1gZs&D*oBHT2<;y3Y`PNczkt6*(te^9`tCpwy&KruyUnPli1J`h^+H0+MM(Ou{Ip`s=SX`EB_mUZnnpTYxeaSuFd;mf%==xFnyQbTcFBY}c z>Q`xYYeBXLiI-gc?&Sx*Uqn9XGF*-lEx@x&N?cGt@^xypd)A`j% z3?f)3YQc|Q{-#W@)<+^4(SojB6484uK0xgeBEcy3{8ppwKkpgm zbN08EXg!rsO3e{xa5+dYian;)pofHdzK@CX1f#k=G389}NJ;fy?iOoprCh3qYgY1= z;#Pwm67zEj2}bGn1FwBZ%(o!ZYNP79E0-gcT7PZHnM0MS`AW=?fkeNQNYFz4jGK57&!W@_JqQeS%4 z`QOS>n)x1b)xUNKrE5a%@q_23vzC0+zjFEZE!#<8aISPjcDg#AANjOz=5(1-$x!}J ztN^S*LTia<{o`E+$Q7el3sVi(A_=Yf-gW*rW;9GNO7!<1nZDxFUHjOhavcBhe;P|( zQ>yujlG{Tf>hK?1jRdv?qqO#U@)@|>H-t`F>8H6ppRc9-vS(;U{lsNo>u9hy=m__F zSA081Y0cnvs-;k_=pmtFV$(|s))I`;@v8Q*6g~tJXI@TA>pACYZ~cmd>gvF~ol)%5 zr3g7^!=4*R%2?<8+t<6cO9L`~zE2hP$cD5_bpxRZ*U5i@J z>57YH1C^;iqUa&Pu{q`{YmjK8{vyp+7_})nuHvY)qX%Pt_ZDdW+-(WwSA>rrtdW+WhlFzIBhfs;DAq_z&_g2Ke4aUSl361U)3QDyT<^l>87%kt?e+N-6bg zmmU&I->Z)(05zNzqu4ePoBka%qUa%^8t@!E5`r3nQQbDr8roeNUyQi(MZLK za+qKg`*bdM%8~wtwc1&GIF*)mlxjDabLH|yZ2a5S6$$M+J7{s-Os1j9M?j>gw`*EwG{^M3tzj7~8e{*hIf*um;$L?>L7=jzt>(Dv1QwGaO7xjv-=W9T1(JFLi?)SkLL+SX}`8dK}%@ouzR2OAiGzx)?0!e67iH+ zudb*r!ZRGpH`Q=YB%$2)dm__f6mvV(a0`;q&glM#Vp@!19kv>*6SaqXB2#J!dPu1K zCo^0^<5=r*Fp48>)EGqYJ?%OR^G>k6y*rwOY-^7iIaf@JQTlzJu!qECXQqS(m4j(9 z>SeG0h2{TvP8>xQT-R564~o9&r18vs2YLsKzJ)f9^OU~+hBZATWc%(}#Kyl@s^o|jIW(_f@94xus+M%yQDT-xk z%Rvtby=g<=eQGok8t>Th9uGz-SNitSlwb+<78U26J5}0T(L+M-m~bu36O7WEFZ2zu zF;_!y!#YVoBvfy1&3S@R-CmM%7P)dQs?GJys=c=$3BAWe->e!-Ub5D< zAfxo|5`7VBO6ct)_NYdkF82YoC8vjk+QwyS33}A#t_7yl67-Nzf9v;M5{%M#^jK*% z=+T>uJg+dNmY|1(o|>(k&1J6E;;!M=-xp`IX7X_YI_$0L!9cAS$?E$F*({kn2mjAEZ|HRvIsws8*U z2}W^_8HqvV(A5ZCL05itCB&_%Rg~?KNJgxd>>(lB<=dTblr(Hl3455XY_GL;CmbaW z+f%|GrYqa4sND%iam6_$9L03?1YPs2Ou^c6 zMvYA9dWm;5DkpA#oeA3>iDbmtwml?dyJdGL93>6gQ^FpmE88u*JK-p4*q##hFkRVh z+1&|8NyGM(u!reR&d&?hUdw2s>h-cwV^DkOUW)fwvek5+;C32`WVE~6NXT}r?@l;M z8n&l|Jxo`&YkhaZQPQwICG26kvR&)D6OQ6J)s%1))0OR!wmab{Y1p0;_AuSaGjT)W z(*L3bO)!dQdaZ_@#qb(OPcph^=y{F)`idSB^Upyx8tFUXUfq*!b48Dy_b{QSkbGt_ zPcTYPI{6H#CFs%9R6Y};c1zGhLQg&Q*Ciwvr6--d4$2xsC=F{pZRDKjxh3aaea&st z=87H?dY+|US0wc9bGNg8_t>0j*h4~3q<9TKPcTZ)$xO}-2K8Nfly{$V>@8O$R0}@e zna>rYRO^%TsGKW$^puv*)%KPv5_;0nXMOXzVw9fD?63ONmz)#zMCV=o&F$1`&_hC_ zpkG%c7^TtWwrMr!(WrGhGo_ZGhlFN~e!n8YD9%c)2FIG77xY;QM?p)_Lqbo5_Roq) zFiI_Gy{s{W(y->}RL}Pe$CT!CMM9&?Gx$8gD30Jv48aX+=2tz@bJX5)MM6ElKPNIR zMsemF%aL*xx$-zr?fPs>DfN3hJtWkcPHEIgM*AE+quAeCf*um;Z~bvjf>9jJtp=aZ z=5xt>mNXMXaP5=cB<7z0Wm=5tK1-HlhBZATWcS-+lW^4D&bFDZ?EZ0(X)$VV*BMC2 z?(Y$1T8z@~^MpMlWcT+vGc88x_j$q|67yfdU|NjgcUq!HxnJ=+CQ**qQxdtw{*r>l z^%CzdAtBrQHChd(#VGwgPuN33w)bmHHApy08n#l(2{ChF-7DnHHm>9CL)*oP=z*>@-&-93>6gQ^Fpm zE4$z3Op8(aeL@Uc0p#y*q?;Y^f^9hl%7e@noNa#ME-gD5udTxSIx>u;T zFH8wtJ@@<5bSFmdvrtsroBIArq%!DlSjQdL@JPdijs{LCV&mT^hdm@zCcO=#$<<&D z=T~=0_1+0Z%^z{-A)&h&dgDr?k;_4XQMwnRx2!Zo&J{hn7os<->^)Z`bT35jVreuc zxnfk@H|h~;HTMSHS98Bo%epV5q{qLw=VcFx{8r`CL&xxBv;?Erd!~fjoP_iyZ9Zz4 zU=(|0tHD01yRUi+jcRmnxgw!Ezk0vSv^|&>qjYal@0Xbp{4SaLnCBIxWVMduVib==Ey3QPaqi>C-g+Vl%`rX_wHi!|QJjxkLU%1Z z24%Zv=styiZwY!f3Dfh0Xh-ReSzm*mO~Q1mK|;2pxLR%rdNv8u^Mq(e&9B1g*(6N2 z8YE;pN`1FqSM+QWrdtgX91~m(wgf#S=2uJFXL-tNADZVS_7d$|?B|Le60-Xx-y|HR z-)*<$poi(o?jHv?2}kL7+fxmDn67M}0qjmVN*cDOggs1Gw$FWbCmbaW+f%|GrW<;_ zH-9lLMnyU12%is6gQ^KA$-B&D^k3Oukr>IS< zMrquf@z(pd#GqBi%@6(6aYTvsDAHFjY`3|hhlK3@_}C;IrQdB&HSA%!vONlRCmbaW z+f%|GrYqZ{V0Xe%(y%=x>|wgHJqmUw93>6gQ^Fpm8+yI*!L%3^<(MNpqDaVgpPuH5 zgrlTkdrH{DbY*)K>`pjJ8n&l|Jxuq@ul%*;>E}P79UlqR{;Qf6qcmfwfzL9uhjP^m9dmQ5QQXbE~Y3Dfh0Xh-oXMN81LNtm7|L_3OC zDO!Ra5_B^p;eMmS;8n&kz_Ap)9K2O}8aFjG`PYHXNu56zt z?oK#L8n&l|Jxo`&&l7hi93>6gQ^Fpm8+yGnNT$W8D90S(Ge{D$eV#bY6$wX4!}gT0 zhv~}pdE)MbqoiSbO4!46W%qXoF)c>v_j$q|655HYBlmRnVOosR_}7YgN@%C5?ybn9 zeXhDoBU|Uu{h5KDO``v0QWCNq#Uor>yYy@lrsoOKj^YunCFt2COwSXd9mOMDOVG1P zn4Tv@JBmlRmY`>oFg;I*c9hP7buVw)OXwk?b6VYD4B|^CzHI%Cv(MQtwfbeT8@BnC zscPSl-XZkCyZztm)1Lb`A_jV@y|c~lRW-z-M%~avRYDqH`?F`P|Ni6mNpF;24D?ic zXPaNqYKTRRx}k}xgf#BB`;V^mKWWfY?VW9Y4Xhy+HR^^YsuI#T{lcBWuu8ZIzbKbAnjZD5b?H+ePCEMI#l39^3Kd_xhA+ z(&!R=%Cy?jNF_hE)YXEXYVU0Gsn&UdQPq}4nn#Y+e3A;Wpr_iZD}IA#j%cGyNF&W7 zTbfU#QKRH>)Xp~d*3T1+szsFNWes|&y|Z2S)^8H@^a<6%U%uz@TW@^m zk7NxJ)!x~z-~SF zv{5Fc@n63B8(TL$`HEwtQKRH>)Xw(%zwq=`e3gBZXgxhbx%!*`a@N+TZu-mabO=yR6YC z7)4vTDo2B?(Wd2e;~1qr5Op<2s82bn+R`Y;!K^_~wc}W;z8o5JgnGTBsx6Ijbj}*| zR9hw2u|19AJeSN7ZIp?kp>;{AD|&42Y-{!59F8lQ3Bjmpm%7sWDiicnJ62?_>2ZBE zA+*+VRJEm{V~0kr#s@vsR$ZO6jD971j%cGyNaOGi+++QTyPsT2PLJ)K?UVoMvCA_a za%>qNBwA08P_DlA!-uZl`Ru1;4HDIk^N$$8%2l6W6m1bYzwun6GYF?u?KqFpC?4mM zE}`=sM^!uLD$dn%Iq0dj&j&s4ra4h(cM~Gc+ajvk(n#&CbIv@s(^Ku8e8#FV8ReKG zbpGk6YD+_FT_17isrJsc*3%l3p)p4=s@l>>N6xj6we(bbXS;s?e3PK3PpDs|HN)C# z1`^d)l>XAV&+{$`disRu2jBS{>)S5-^{Z3#K%&~|Si5}6F;9NYbwz_j>k*@zkdVf+ zE;(!c`G5Zrt*-_W)sFVi+!Ey=q583>Pe`M*;C^Y4sCM)#%`MU9zn^B%&keEayXeAY zS>4@`uEW{h*}nbafu##NjJiE8g`-}?8<^v0}@6b%ye^a*JkbmcR)Zj7rq3li1d*?#83Rx7>PGs;1N zo<1RszfLQqfB$dtRh$KhYVU08JF0r$XlRh2r%y=Z&NNs3T{(j!QEk1UYqioFQA2|S zJ$*tN&q%Y|4dqOjM77h3>`~h*y)ia4NYK+Kr13-NoOA5w;_AnOM74LePkQb4O7DCP z4HES932EH)|5NrZ(7GLEneGzo0pgJ%1Oi5GN*d*=u(u#4WbJ?bNkCf!hBgQA;0+T_ zLlS9egFRH7%GGehLzEsS4bqJQhKoW(++ebo&1r-n@Q16-H8LD%i`)cMh@hvQ`s$tE zTWi+8vRq@Z^YMT6)LXOeb5_loCIAk@jZ&yB|2u+PM?%853xfo?*ZB zC6g0rZ`P;Z?tJU7oN&*WK%?|<`>ju$oJhOO`c~)fWxwl$d&UGBrKjF+ef#7@+MD%l z9)G@#A5OSuOrTLloc%UNO-`iETG9FQ*wqv6855>apBgxkc3cPF28h0-rK%FdE6z@2{c+yT{WCYJ4ORe{SOT%=+EUD6KJ#%r)oHnHlfZfC-zFi z3HOYNromWSHJnI0#&e~19-S+}_?jN2#EF(y%o!F$(lIYluFtcKN-$55XH1|`N|3qF zf=D{%SE@Zd!F)%aF@Z*@iOk`uh7)PWJW;KnCz!X%GbYd|EsD8l)o>#1nD44J_XP7# zdBy}9rDtGHT{WCYJLc``m3o4Cv^--1jncz$Z&3S0C(@4l5B07+!To?dV*-tK$5J(% zNIUMMG)nXY_cij22{hWBR~>PjNSpl=x^JVua>6}h0*#lJ_IJNui2K2vontnp%HFJh z`m|$vmtCWKH79z{h(O~DrTx9Cth}mV*-trmG*Z{ zyB~BS?alf@-&anqzku^g&~T#j%qejKjklNemCv^OK_}AQtpE619<+C-4@$!c_lyZN zUT5phPNYq!vKwXRL+v`8aL<^4{(*9L_mZ~a?nK&~^?4urZo3XAdXG}#1RA$3cXywN zyqcUyd$Ydo4m}M9qcL{z|Lb=V_D^X_rvb_gKC9ZX?_?CeSD~alh5w$%(W# z>$g1cENdT5be=gSPM}d*)P8G&lM`ug)|b7nobo@nb0^$0CeZkDX@4JUJA|A_d$WGV z51n1=mHI0u+%qQ7pe$OSI60B_X8o?K&$fQo3HOW%G&ZG9y&<0UO-`h}SwH_%XWRJU zgnPyW8fC=UZ)4QtMB0RUh>cxNxMxh5MjdONNIS0M(zWi@nnopvH$6&;6P8zX&frAa zQ6884hVF4%UR8qpk!MVx(MoVZB&~X-dAk!)&fysoXtbJG=WtG>9qr?3m+R@d6Vz9E z#snIzMO6(a(vDX9=|{gU$3a?cC1`i@j0rSa&#)kpE}=>$TKF; zXfv6r;Y8XcRGHOey>h}mV*-sfBa6K9xMn-%iE0Hs!Mttu3<)&a%(7}Yk#@{?)tY;P z`KLT%0*y99t{P6Ht$DlpD<@(e9iB0PM(N?WH>iE06KTi&hkDnZ;C?`!F@Z+AW2qWW zq#gHBIZ8OeeT_V00*!X(RYx2r(k7Jd!sxG@aL<^4<__}XZGAAmuXg=9?Kp`qPJ%|m z3C>%QXH1~+O%HwA?hAf7)(4$Pd$Z=uyEv;F4JX_)CeV0uDf8#I`#~qt-mLR$U}!ku zo-u(&8P#@gXzPPcr0rjQL&FK)jfzwEueX#qfyPy3L_4Rg4?2m}MANvo zX-rO}y;<|lL|#YHmgb0F@Z+usrOso zJ~@$g+2b{T?~dzm!aZXGjWXiww=rsRBJIsOzpsae6Yd!krcuXQC(@4Vh_6SOMkR<> zo-tv0Rp$&&q#flE-?y;5ss#BX&zL}?mEeL%TIbgC)lf8?pq%3y9M{*Hp)YOZ?`X7| zSm$u*xxSr;8($-(9>@1T&~U;%Nk@yyFNU->ST&qTJKA}Cp#%*lXm|3A39h5{3{}I4 zw4=X@FQTB~1pS9RV*-uV!&MC@(vE&NzU+X86ZC`fj0rSaPhB;fNIS-l_(BC5PSBsr zGbYezBTm(DBJCIl;~N@iIKj9i&zNW$jI~w6iL_%pS8C_6wi1l5@{9>I+6-VpBpve- z<$6yrPmpI!pixSYxlh$_BJG%8srK{)^BsA{1RA9#GKZ@gPNW_4M74sRVBRLrm_Vb= zEUShSX~*m}+qo0WKjj${Xq29TId#==BJG&Bt5@m?X5R9Q2{cL%$Gt)A6P-vq?myJK z_5}9>@{9>I+8s;Pa3bxvkJ2d76WrIxGbYezcV2bGaU$)F-M7`gB<}7ik@siU*R$0_ z&j~dCYayQVi&`JNXm#v{TeWdQc6l20@QYRteax-f?@sid5rM{EmG!}IX!}K-NV~ix zbo}DgW8QF^rs0Hp#snH~FJ=Cuc0cGu+MD$kUvo*hzS}hoC)_h8(D;0*yMNQ}2c1ZJ zv;NR)p0YacO?PM-PPk`GpmB$?KDcS?gHEJf_Q{<2)Yaqee@4@A!aZXGjdBgUC1v|% z9cRahvu@6N z%{ouwL&FL8j0rTJ|4Uatm}1oWT$($&|#Ff_`3QIAV@ zdES1_FSTevuV%tMV*-s*f~Q)UPfnywD4jKmh7;}? z6VPuh?eFW#UQ5;>ok+Xn)y2=Y_TfbDQA(UZIT1~8T zI49DM_Hphlzfw+zp`ANHeU)cSpwU`X)o>#1XtigY@sCZz3EG`JV*-uVGgJ*H(k9fi zR^NZd7n+6>?imx%t%s``PNW_E?iar8b4|ku`oZ)lB~GBh-YZrcN}ssnMA|Wa-1ykf zGz}-{&*d2tXtWV0^2&&$2{o-QIQ8kK;e>m}1auoYTV8owvSU0~YI}n5H9aGum} z1R6Y#;mH~rPNdB~k_*> z=|sbcv^Q(cTaJ_1D03&=GbYgBc??f%(QqPd_P5_|FV2TU!wL6{2{d>f!;@z;oJgB} z`nTWX{MX1UC)_h8&?xH?=djvy}u<9eiJ!1k5 z)}mUOm-h!VuC#d{=MGk{oN&*WK!Y{4R(H$$gBe%ayjOGwYadRyXH1~M+F)yg<^92o zD{bD7x`VZIC)_h8&|rk&;?+<2NY4hIQ9c}z@!aZXG4c5-v7**aM%(&9#{lPoVV^>eOXH1wz z9c!IPJFbIo21H-dQdJ4!m1j(#!TNkznW=LIC(@4c;NIT8pY0PNW^}ob%j6!wK4*JYxcl z)-zNMC(@4oiWA^N!wLEidBy}9t%s``PNW_EF6XOIT2EayoJc!H1I}{~ z4JYW&Z;*H+A(ieuhbLFqvaVBXp|m~ zdxP31I+1qVf2eou3GN5v853xfo_be(yAx^0eUwItp5VSlo-u(&yYs3ejuUC~{$Sq2 z^@MxI1RCuQ@>=@#dI$Ni`?eFM%6(?FZ?3s z0u5j7b0Y0%wXb~YJ==9SLA#S@OrYVbeNLoJsAsKS`vtx;OkO$Ro-qO4dbpZbPNW_E zZhXra4JYUa)1#C)fkx}8tA-P4$7t~KAJ%m^L4PjKm_Wl<`i% z`e4STcw;IO3%=(4~j^-tq;!q zl@rXP)nAPXG#2ZFEv}^F{zJWMPjEjV&zL~NSNohuJMN=$lyHLk8hOS98tu-jjyO)F zO(@-k(U&;ko-qNZZP&eB-QJ*2Dy;*Z=)2&{0e*L{C+%qQ7;5;Wzv_iv) zv^Q%`ZMy%rKD=o-;hr&p2Io0(G8Y<7q`g^lYSXb}KiD*!aL<@PgY%p?VGIo?(%!5& zwdupZ_n4;PgnPyW8l30ENoi;}k@jZIsZGy$(&L+k6Yd!kXmFkrC%&QKMA|%Oc<1WJ zRzKb}oN&*WK!fv~{Zn?GnwVVsgWYwGbYgBEX!8rlM`vPj`JR?S5CNROrXJ;oUQIoPNZGN z^K!m#wht%VGbYgBY|+*RCnwS_Ur{RO`(`_L!aZXG4bDhyeaYlR+M6}!`(}UTgnPyW z8l3go`ozhJw97kj<$T}lcb#z0m_UOwYg^wwIg$2e&H27LemLQtF@XkW@3t{&aw2V> zx4&;5yL!SsW5P7*SnEXEaUD1Q(1Tk$Z>g#T@yatMEU)U_ofBzCdA#?d4^UqcxmyYH zN1ic(Mk~Puk#y9ncfaF4O~VPwS)MV0MyrXt^t(=^9qr?ukNUQz;RN+no-u(&Yf)9h ziL|4gKmCQ@+BBS?-N`d1&}cnF)o>#1=&yd~)Loi}6Z9YQj0rSa4_7suNIUx7OF#L| zO~VQLL3zdm8m*_U8cw7gqrvCzcSh52g8p2dF@Z)KajJ$BX%p)D)o)($O-;iI_l$|A zVe5k)m+TnNmD+i9uBl>tP0xsEdBvPzK_ngX66N|l%cunN1bM~;8l?o8`z(m0V}7OD z(-X{h=Fzjnbl+i&hOM(vJDAT60e@|CDD;piz1T z=G0ZgiL_(hu3o7pm`BSqCeSE79QOvbPjn*fxc^Y^+7sLl$TKF;Xm>1C!-=%xK1!oR zPjFu&&zL}?-K*6R$BDGr&ye?UJ>i})frjt?i01R8B^dmjxa(%!6jOLx3q z)IDPYjkZQ#HJnI$v*s<`@qSVFj0rT_UW2OPMB3CVeNUL@3{JRbOrX*BOjHdg(%!6j zOLx3q)IDPY4d4CgMB1A*Z_SSPi@Ik_py9heok+WU!DZ+FUfuIu+LP*pd&Wf5nD6eK zNPDy9)TX?Swik!oo!m1fT3*e&Kb=T>v*uipEDzr=>Yg!yM%(FBQ{_b3<^05VT-3f( zO}%o$J!1lmwqvVmIFWWaFXP^qSo?6oJ!1lmw)3oNIFWWaJK=FZW$oMv_lyZN+77y^ z;Y8YH@8Bb!V*Qm9?imwkls<9ZFX}|vn>FVLWxwl$d&UGBrEj12i#n0^X3aTBIes|d zo-u)j?-z9Pf%aw853x<7F9KzNITlO zcD?lk?M|LCfkx{Ys)iG3M}MW=dp$w_A92|a3bxPC#n_n1oJj| z#snH|E?PC5NIT}cYRx^t{8OGWfkvBCR}Cl9j(NL!rJi6OEzg)hqum?SKGBJ^36KME;Q76*o`BmP-^@MxI1RCturmfSr(_(2! z?2Sl!v!<2Niet}&6Yd!kXs}m}1RCuOp{n6T+U3mU@*V)a zYG^p&o-u(&I}2%_>u@6N@_e_v&%o#q8cw)pOrX(DXsQ}cq`g_w${6KB!wL6{2{hW- zR8_-?v^Q&78KZS*IN_c#fkr!Ht7x`>)>rFX36Ek zC-;mAG>GHkQ^8Rj?hZF7@6KL?R8uL*!oJhNzu~pvR&3fg8d&UGBymQBV z6b&cR-mG~ZlkLL^_lyZNcz2NbC>l6}h0uA2fWIl?96KQYO-2Z34>x6s81RA_y+WPj%iL^Iso@3m}1RAV_w=rsR zBJItZ=P??)dcr+p!ZhmLofB!tbubHT{Z*u@62vRdn6SL6^Aac0j`Cm@7#c0FDnb6p zGbYezCAc7xj(Wu`Ff^Q?oaGr4XtbKRTk6%06KO~LU=|n}PEcRv853x<7F9KzNITj& zv%t`Bf_5j*m_VcT3{}I4w4=Xb78n{%(0|A?CeUa-T-9(Q?dW%z1%`$b^n>z@2{c+y zT{WCYJH`)YfuZ39{kc420*yA}R1GK6j&YD#XJ|OVxFpY*Xd3hRqE4h8O|Tx zPgE=D3Fd9`j0rSKi{h;NnpaMw9rIna=AK~wDbJWdqx1~(`Jzsw9rJeeNY41M-XsG};|Y?RT9>JMN=2O7sNxHS&xJG}@h49dVpUyFB-? zd$^u(&zO(~EBo~Ab*;aw`O}`$-mF=LXO+M8SLF^;gnPyW8m!N=LjesZ(%!6Dg=e=y zXgJ}XF@eS(mojIk1sYDIy;-vg&#sHmaKb%f0*&_V%zZSRNV}X>T=uW9dn7cRaL<@P zqkRLkYB-U0nfsJ|IP8K64JX_)CeUc#GOZd;q`g_Q3eRqy&~U;%V*(A<=h=xwUOAEW zX3Z)*yOKh~3HOW%G|E1;`Fr$Eq`g_Q3eWDU&~U;%V*-t`Pi_7ly%T9~*6gunmsn^x z;hr(kH0H0%JCXKg&3?PQ4tCG6U#(>Bh}mV*(BKShD+!R5_9MX3aj%Y#&azXH1~MUQu?Rq2WZ@n>G7U zvz{^yTn4H;zREKu&}c2HYB-U0v~zZeg@zNfJ9)+g8m(uj8cw7g{S~{!Lc8cw7g z;~=}zLch|DoQsC%7MwXH1~c z?pSKS>qOddAEi;EC%CVXXH1~M{a_gf>xkn-+8euXWB-*Cd4G0&y`u{~C#2!)gPi3= zd**I3?6|MxRH$g@Xo%oGQ=Tz_M!R=D#rWYw+Hrr*=~kiP1ozAGj0rT_Gk~h$MA~}J zaEGShMBMj>XH1~co@MNF9ZsYj&r3LMEUv=|o?pl_CeUclWU7V}X~%OPPE899CwLAc z&zL}?JzJ_8PNW^ruQ>fJG@Rghl00JqjrNSJYB-U0Jcr{HyU=ig=VJ1V2{e4Q&xy3- zc_OFrg@zM6-;-xdpy8{1PNc2pqSA08o>PWrOf-#owakw$^df&Yg&LmGF!SG}_7!ePUf7 z{^rwWEf%iT(lKk|$TG+LQ2 zh@_)lajIZwI6*nfGbYezHF1~ga3bw!ADk)}8ctAOPNW_E6{iY@h7ITAx@ooJc$RT}~AY4JYUa#1nD44J_XP7#dBy}9rDy2Y2Sp?u^LF)0J;6L$o-u(&o9Wj+(TTL<{zJWM zPjEjV&zL}?-LX^+C(@4lDE0Y0!F`Q9V*-tK=T*ljC(@4fL5+4jk@siU*Bzgs=L8xD z-yh^lp0rw4_rs2TuY5%``VuEtpO6KTgjWWMSe8cwi2FVC1jqwRIxN5hG#1*r(5Tl0(A@*5~CJ z6KIruYP<_jHJnI0-Z$Xu&7t80>+|xA2{g()ly@4ch7)PWdlP(xIy9VM2b(-&qG@#R z4~j@S-v3Z)=eIdXRegU@o-xt#s(XJ>1pD~Hj`vuU>+@SFRf8Rc@{9>IN(s*2n{XoS zcppc#rzhCSEzg)hgFTkaF1d0i(vJ6v)Czin9iH-x2{hO%%Ip#iC(@4hqtu#vf}N`J zj0rT@^UCZJ4JXo$_q^0A^#nU^I*sslel=5&Q?HE7!ZgprlL4PjKm_UQ) zG0aENa3bv(2l?uCXgI;RB+r;=8r}PYB9e~rT&bN$=b9?US9!)n%d77FK@myEyhOP^ z&oZh8^8|Uu1R8B7vmla=`ITx8Uv*rD`~lcHBp4l;{cWYvdUdXtX=8I^sBycDz5R(XJ=*{_OgCB24Hxfkr#ChOu_1 zuITTaTibKmaW2m5o)o|L1ncwij0rT_**mAua3bwE-{66wf@Qp*5{8M3(uH9qn(Ac&viJFcAU5LnaiZ%1ncwij0rT_nNC&1iL~R~sNem7 zG@M|4UY;?5Mmw9TYB-U0oPTxt?aps`I+8J9_!-=%x9IwZ&q~QeX^YV-d zG|E1;?tD=ZNym9)w|TrYoM63No-u(2>+`xFbRum+UB7zbh0<`sJ!7J2%=d#%q#ftO zDYZ3KGr>;0^e81xw7i;63w0vxIOk4zSaWwK*ik6Ym_UR5+J78-gzNdDB9e~t`c!** zf}N4_j0rT@W6AEb(gf@Iq9T%xa|hK5dV(FE@{9>I*elBJGc=q?JI+s3Ywihls>(Aa z&|uFiyU);YB5j>7s&?)KJGs?gjR`c^ug&f=G@MAgJl`$*wbi@!gnPyW8tf=$_Zb>a zq#fsSYLw^+c0kKBCeUanc``=T^F>7@9p{Vgw6Uuv>Q3(F855>a$66=Sj_Y{j3)ihr zY^kaQ@yatMEU(Tf*RkV7+EE@Ky{|M{?pA{Qk!MVx(aL;5BpvnYo$uJoagbV43CdZX zF@Z*_iMw2f6KO~LIPGVo;RN+no-u(&YlBt8iL|4gKjxm&aDsLx&zL}?^(9rqiL|4? z`sClPavY@hsRaFpJYxcl)+a8Aq@&+`#VKhxK|d(Zm_UR5+U!@OJe){7MuX43R2oju zpUX2Q&|tr|?gyPnn^4!UuDn7TPPk`GG!4eudL2%r9pkxDTT?X?jIZfYN}OnU#hjsP zIFWYDOO)&LETa<46XY2aXtbHkf=D{%SE@Zd!F)%aF@Z*#kyQ;R(vEqeT0u`RZhC|)Dz63@{9>I+8s;Pa3bxvkJ2d76WrIxGbYez_iA;-aUyM=GnD<>J`VErh)TF;OrYVb zeXP&x-ZJg@j-sC8_5`c#@{9>Ie6`Psw96irvR^_^qkFjrs1*iL~Q;!bI+LP@Cku?3)9p>886Yd!kXtXEvRl|w2<2%)A1wFw&PI<-z z8f~SaYB-U0d1hJmYpXT)gnPyW8g0d-YB-U0d^cRZQctk2R-Q3|MqBxzPpsdg7m;*X zD=Pc7v)^^XJ!1k5UmtWL?f8znMv0za*Rnig0u5gubRuo$?RT8VuAXqum@thxaypTA zT!)_G&Ki{t(O+q`rYGn>k% zv|~J1YUiw`|D9rF_9`aEZ-8q5>q853yu`k)hO$NWmQrze>2 z$TKF;@by6_(vEqeT0u`RZm}1R8D6cGYkq?ai82 z#wZsWPPk`Gpwaf8R}Cl9-mGb5jMkyygnPyW8f_1K)o>#1@-A}O7sae2G@NkHm_UQ| zdFEJ@hZAXU*0eHaPod$2d&UGB{x+Z!X_viGWsfzpz|e5QJ!7J2%<6Pwp8LXt1Y`x%)vP>CKw^f-Daw+%qQ7V81r=Q8b)Ld$Z=ABllmWj0rT_n_={clM`ug*4*W1zw3m1#snJd*JeJ7h7)O*HLtQ?JI4>fU9Q84w4;463k(e>sIT&j2{c-Zsv1tD z9qpW1U}!i&yOU>3pwW7Us^LW1(O)qO3=JpfKjaw`XtW-#YB-U0^t;RgL&FLBL3zdm z8m*_U8cw7g;|H_A&~SqOT%Iw3MjLUeh7)PWILNFsG@M{ul4ndbjrsjSC(@4bT&bN$ z=b9?US9!(+8f^x!Ad-%GiE_Osm?y|HCeSD)IG-=-MA|XGQtjyp<~#C?2{cMgoX;0^ zBJG$bsulDE^EP?L1RAA9&F70ck#@{?)tY;P`KLT%0*%r$%o6i?@BJH^UQ199k+z-ezCeUbiEVbWtBJH@3(kRgr+}Fr6CeUbiUUiIeBJIsO z@4|GR3@aM+)b1G*X#7^WAACXk9(_53sH`>W98uYu^_}nfrPWKHptC=n=shC>jZc>K z`A&Tm_XwlrObaU_D1bEk#^ZLaoaDK>(e=qPPk`G zpz+tG?tVGua63+LYji zK+|x-J!7JlM>(77?_y59<3!qo`pW7hpO(fajd0JHfPPBZfplHm8YxMY`hzW(a! z>CgQ0b{$Uio)Lk@XP)uQb4pFAdF4dfWqUS3Dhn2Fw_lsM7y>Qu|C$%(W}U-BbgvzO&j@@gjB zGbYd|C3vcp`Q${}gu2;Y)+;C6GbW%*P26vFcXA@_&H6!?-)t}2hZDU=DRBY~+Fxsf zlM`u|@%$TazL)LX3HOW%G`>>W--p}%pc83t)|*RjUh0+lD<|ADCeSE7+zL(<%wNQk6#snHymOHP%|HXKJ(22AO z^|d9hGb>ws+?YNE~eUZ-oY#Nmy-t;IXPFP;mIfD~vM|nJNt+PK{UR8qp zk!MVx(MoVZB&~X-b2*)eat_a!K%>>fI;VCb?PwpDfB5aKPjrI%D$kfeqqV52;Y8Ze zYR|mkx*P{-wUwaV$ulNuc|>2bAd)83&Gvrcw$f;QNhRDfCZJmnw;+;^e)kza_qH4d z=|w9+KbRh+#0fN7PrV?Lj?v)Gca??{^yl)72{hV>Q#G7On^25C(s05(W1?xy=ZiX# zc8upr?L0cyR58A$M=5cl6}h z0=mt}s)iG3$2?K3peLBOrAH}o0u5S|T9gxM$9z|EXCHsC}XnX~+GCde@%den6fvQOhIlajJ$BX~%t3juOK_}cZCZNlxw)=H$eQ;;zwX26+^77U%$=z}yo>&o@L zvS~Qso-u*OPI+_S{q26xiL_}SuUoz0@>ewtC)_h8&}eONpS*G+ZCdTst22M?)lI_* z_lyZN$~<(J5gH9A(k9gFSAYG(uW1@ixMxg2|NGMZHuL?U$0eJ7_YYTZ`Mflo=shC> zjn-4w>u@4%MuRu3?)`}0YuDj~d&UGBFD&m}MANvoX-rO} zU7o!@;f;13MPnvz}#iO;#SXKjx#Ql1%Oy6KIqYJk`p)Ba$Z6 zHCC^jaL<^4<{qlm-I7-xm+UeZJ@Z;?A5Qe15rIZ&QS<$v6KR)sm+p4T+PM?%853xf zo?*ZBC6g0rmp5NNeaiYPC)_h8(D<{`{+<|p;^aiy6%i@{k=@6L+Ie)Y1mkOZMnuaiyB|y<>6n*f zu9v);3FZm%j0rSK2{QMosd6H1LcQMVl@sn66VRn5?yBxOk#@`z)e3rod0Tpv5+~3o zEz0f(lSn$|yK2on!TeL6F@Z+u8Ftl|IFYvI?dq?bh0iL?o&yD;ttop8^XFpX>J z6CvLCg0hBI&KFHPuH$ike`EW-X;gxE(<9mm%d1l;IFWXg$NhfbD@~*2RVBzDdBy}9 zes||Y+EK6G_=2xC4JRmPdBy}9ttRes9ZsYj?c*MA_~)kK1oc&(F@Z*FgH^+cw4>Gj z#?}AQG@PK_$ulOANfYWCt5;6AXG}o1 z8Ckt@C(@32qFO;uFmFqbQsM*}ZDv_DoJc$7yK2on!TeL6F@Z+u8JJU74JXo$dAoY0 zo?sp=&zL~N@9vyPJMKT!yY>Y41M-XsG};{tJ$1bw6p?h?73C=51ot)aj0rT_ofjic zy&n{jG@<^)#x5t^GbW@_?m6qTS0~br>$t=H%JbLSC!!&Oc+;blIAM8J=L}Ay9p!QE z`~RV7w7jYW`6JJmK*R6uoJd>s>hGI|6H(6L853xzhLS3^u<99yaG@NkHn1F6Q zT-9(Q?dW&U`UYt@K|h!trNjv|T2EayoJc!HgAcs+@7i@ZL4PjKm_Wnt?wm-QP$x?p zl!g=T852#TyC2NB6mN{@O6@#4*DGgyP0xsEc{ShNIgxhEGBVfOoS|wkPmpI!pixS& zyB`#hG@)K^^~wqNj0xyc6M3fJ>XpYOJLZXM1wFyMEj=RwjW)Ba8cw7g^If&(o?!kd z&zL}?^bD-AR1GK6*1TQ)l@l?K4$qiCob1+ zZ&z>l$op1TJob&V&F^vLTIW=#gT%>4d~$W=uYa)8+X)XPJ2c*2o~}Hpt?;@>HmQ2` z?*A^S{aDl3MtCUMq4BxWnm*NPqI+bcakHm>V)aY^^6{pzjqp&iL&IB?dt{?Q{QQ6H zzC|e%ad{}&p}{qfGDc_j$c}hFR%YS7A$juBDc4$x*0vO}Y^jeU(c?vafKb0S(;*xQIcR1lp;y@OP!@MOH`(Ox?S!#%RmpdQm+;yR3IHSx_W;_^_kL!-5*s^K2l#7q4A|Ijd^wkW*B<)LJU zM(Y`>hI?d3yl-A{U11xsqfil-hYCA>Z#`VqpuZxng9PPG&WDB(C4-ajP_iSY)>Bsv z_sAw*>Mb=WG>q6$DB|)^vO}YdI90{JAFy#@)OQ zdW8|;p=5^!JrAu41^3A2I+#CXd2Ay*laVsD9!hp-l(OL7p!TBfk&OoPP+CG<$2P)4$qo(XRQOBRk@aJF>915zJO|w9I?B?RR%hphtTNjdH;gS6%+I%PH2kde!+Sc6Q#l z=G5$)?VPCg@ne6v`niX{pxPy1{7n$I`&MN!N-?%>Z2mf~OL2o@)?cey|z4q??s`728@_SEw{smvZ z_hWDR-s*YhJHCGJQ6G3n3w5WxZ@f)8ZQ6+mjYoaK}?H&H6`fnlb{E_FbzUK9B+pVc8Y5&bDu9)q`l>_eH^~U?{J^$l3oPZ$R z#EpHIyC2_s*GtdIE1xyoI>iYxtglWuKA_ajgS3IwV!z5FU`47qo3-(MWbBH>iEMRP;(LDe;f}RLS++SMabq7YRJ<|rzIq*$W_KMk;i2aDiVD3TTGFOn_c+0uHuc@5 zLbt&6KRw~0i0R5J${Qm?LLMjPcZ?QnxW|d83(>FCz*G6R{BPQI!b5%J^3TrWRVCU#)2@4*pkApT+fH~W z-kYg!vU*iAobtvI+IWfPFwYUx^ zJe2oDHLs?~v1zyWw70fOyz|>t3k@ec)b<|Eb98=3vBbMQcY9BJN3js|yM&8WIpLw^ zHv<=h&l!B4Fn=e|iIQK_E(E70QRak-Q<`Fyku$)^S^k}NiB}#c_}-yns^O>l?*YO? zG51kS5mtnIoZ!2SoWHaj2c7Uxd`*(mlxAX1m3#QECFda#%46D|Dku2zCMO-u8V#Fv zJuVM5e`nUqqfkL;J~)5?UWYtR%wG^)XmA}OJk&;{Y1 z`HP-MPL&h$w>lRZo+=OJHNU@d_c$?st8<~@goj$Rs40}DT`yb8hO?uNUay>>{5cis z@OtH;JV*K~caIbES9}*&?u3W(TG?yNU%xDI&0nc3Hur|AJ=+NnHGiwqQ#H{(_%bCY zevv0=sNFsGA0D{6_#WpB^2$>(f7kNRRC!9An7>%*sVWyV?K0sf8r0S2jaXNUsr8n8b6tEj}!DO_xpce zJJ4{#Ly_xa4fi-fPxO?le}ACigomQP`v0DIfS9Pel#nIDi2v(r-dJs~JrR5S8*>KLA16rR zbJuUE^mf8Sc`K;I6x_7y>171?+0VV@1ZCjY7hy%X#|g%gFJAfPN^d7T)X}co3G|+F z-u@O1<&}r>T<=pwzpFljUQ~U_(b|U-^r+*y>v4G~Z<~Fpygd_2y@9v?nV4wj?r{RW zaew7RAL@~-|Kqbia$?yA%hv~Hj}zpAdelBu^xx75$6!seKaRNQ{E87VVwYc&rI7;wYt3P_t{p)=2vWuU+y7o?CvtqKCix#RU zJQUCRZ}v|?*VtzbkN32zp0oPW)4#LoIUVVVf2q5v?!+ywdhY7j+rDEkdv(G?z4(G( zS$*}Z_e)|^&ls$Fx0FPVDSlwmSB(`=&<2`s?seXgvJ?yxSHcJsB^0 zpZyQ_xe3BUaeYs^{N4k?J>=E#x819TI$Elnplp8XHbF1*O4s3`s0*)r>OBXkq9(rf z3*TNn)TIkv7&fDtV(K;A;{@wQFaP17XJVr6I?;!kN(mky3R<4lKKtkAxIXgj|9MUo zef~IA?r~yg=hFH5=2TS;Cp^?=&V1@Juj+NY_4vhet^VR`E}7c|F)do{tRasRA9~GG z=JvQul?V?-s?f&~y z50z_^J>exqUa3v=C7VplGE{$@plsA0Gd$Pfad{}}!nmEg=embqH1{7K({>Ffc6Kh> z(!=#}Whj0hmq+hO0zLJ?%Ty^Y59O_(5>s%~uCF^&GjfLXtkw6Q@r4ufjI1Lre&wCp zv-@YQR`*w@W3PrE>xci?mCL&R#1U)V%=pWB}(;Wuu22OaWI>Ox$EBr0` z`k&Cy)iN5~?ZR8scEiC`Md|%A*f;>D-U?gx5YaRKt&!S5DON zsCIcWZg5Z1iKmLC9yS}k}F?+T5(BFA? zwV(f~v-d8$ChV$FLdWg|_c-yctIyv1^(Vi#(v@icOuL>EzDv*d;nO#q>6X@|p zd+1)n2@my*A3D3-FYrb4Mohs?yQkmo{PIn$a{hnuJa%>deC2Qbt4HiT_#12|U`HtJ z&wla`?7i^g<&?!ncd42Q;+4mV@>HaxDsny2qf|NJp>Ff|^Y>nIuT5S@!=~NdlkqmDcG z`HsE4`+U3YbZS`XsjaPf8}yprYq-Y=T7mkp?SzNg-afpJ-u*r2?mglcqP}{a?ls)w z#Ot1P?%oaOjcU6SeW-KG7uiOHmxt#x{iFJ^K2`2Qx@K8QV^u*3imeeC(xSq?|OSUK6 z6u&DM`c(Cvj2FG`-k@Qnr?$8}6xTPtHy{_)laag1A9DTEkB%L*eX88!M3jx~ z#+`zjcByesxbjcu8h+V}pI2?#%8idUV!jUdQ1eAZt2JWQI7sa5L@3(e_&P|h;-%&* zh1;*gJx)-k$JgP6hw?mZ7hV6;=M}B?6ZaV8n<3H8bsbLZ?9fXDZ9waHMR+LBk)G&1 z887{qQn;P)P+h(mGVS^sPVtu3Bj*~E_w9+qmCNG-6p$-@ewGIp3((>U&S{wPfvK;H$>DPvTB{-7brgBL1dbz8S22R(zvadrIiX#;M{v zjoRbEcOj+0b!azC#2)`Lr#@{@`xdxz?MT>8xW@_daD3%Xcqo1!Ux#~~;2WyS>Ha#L z@K9c|Gcg^^-9AT8-_zc>nJ5M`{VX-gLpi;(bD#tp##}T#PEfMi$`crW zsy|Mkr~O6S2@l0JY42Ahrr@UCuHBXL*RHU>#-vKjGL$N6j0oC)r_rFE@KAiiy}OP% zRqo+y^2)2DrOFAucdyt#F?J)HW=O3bP9z7IluiT9PghI^bKh3b{I6Md*` zX+7aB$_estTz8%DP~L;j8WVZt^@rA_GCx|~b%NHcety;{M!XHEdgY;L=Ncs{QBuU; zw96CV2R!8M=fp_QteZdHQGLt&Mt1xb|MIS-dy;taUA|~BmC)0O@KC(tuD8Bx*qLyT z6TFwMcg7=jX*~Uf-+Dr81;2CZE+_PK_#0Q>fA+uowFB!01uEt7?h8)niRrK1{wGi9 zDK}%F=J36Sdz|>O)sN45J>e<2^poE_Yiv)Idz|?E{mz(EJ8Mi_hZD7MX9`kW^{ zer_vAOO+EJ{=LVX&FC{4SZ zm7ynF_y5+1pU^Wh&-G=h^mM=pQZ;_2?c_Sd9*Pud&7vo$SIm-` zw?&P)Q?^%<0A&B0Llt^OJPDkQkli zal&)mfKq}UmxtnajS@>j9w)Y!hsWiieC%3ksHAu!LbjJ|C8pq}UH3SFt$n1u#z8`% z{H@KNaF55!TNi(~vU8*6R5{_H{0-MxqfpZ>@5ku9U4N_9-}9V_Vw88P?d@JC*tgW3 zAW-7xuP6FYk6bNIv#LZ{qn|xautRXH;e>~x&(%p|@|bGxrPZ|2eqRiIlLWjfZPuMI77nu)hxXIKjxw3hb;g=dR}>{W|NZg!1d_HQeI_ z8m#3mHJtEJUQShGD*u-M@pLfrhx-lBw=SZ0UQ*;PYv{!5F>Ozk6O=4#_J^m+LwW1!HONu+M@3xMuVOz| zJTDoyTAr7rCka|X#?(|MN|3uN)o`9^sOB@bQjgK6$~{i-6r?MU5f!*CO2KLJXGKQn?OyK=Lv-Rk3J8ba8FOXb4!2a1lOTnjeJx8mKxW@_Zl*T=S6CR5DDfL9X2KP#;)n5K_M>MMK?s0;c7URdnmAeKhQ5$r+PnCO| z;F`w$t`i>0TS2eEdX45EtmC}&)iD?0NvdWwJ;5_?d3aj?uqS_4ZNaRbyxZ=rY>Amj2- zXzQGjo^X#7JbNFX$>G;QsHcDEfi-tMg|h|;tGg^z9!~J={gVG2^mf8S@$CKe-!dZH z!&CV$zdy?0XsPOmvO@E`-?S2JN$anJbsUBAI@VuDU$1UA6Mc<=B-fp&^eGw9Q4mDqv4|DAx4G^~%%B+MQ~Kr#90h4ds;+ zXsA|hCp?t*F*7lt;ps&~ClHY;<;YAFqrY+|xIW$cY$rSvrKxj&DlrAeJn{5Bo!3UM zmZz@`PV6mEtUK%O#|i50_(UMqyhL~?YQ9b&iu53WhNqXht58SFD<^0-U8+j_{Pnrp zhsxAO*!Z`5+Ibb^m3y3^ zM^!!EPI#!{Xi%=6yvm)VzH2u2=#17_+~WlEQ)c_idAk!Hir@7-sJ{;PIKjR7_=%Sj z9*W=flxnFVj}y^m;+fob!b72={nu)4$ z;H=UzmdBpmqn?wxGZVCPJv*x!CH}Y$kIO?H|E5ou8S-CbnM0Jn@-CTqoWLHJIUbeA z*Ie<5)puR{H#OeF3B~0EB>#U|6Fn{u<*AJesQ=dX!95@+K$rK`$~o?wm5a@@0i`y= zig1q;ocvBcE>q=%hazW5Sw~Fd?)>%Sk`li9R=>7dY~EfTrwWhqYX0_FA?B~8RXeYw z*YJ4xI$Qn5sfdyy{-)jedzr<k+BZj~F^QPJ zwutA6Z<_1X{G~?`0hCmA9wUw)+waR`)^MT^)xKD{(CAX7uSOn7VM|c`PwA;GCG*!L z3o(C%aiQUahx)UyV%pxK($l^ySmLF1)$j8THAHx*MT=?~*0-qnOR*(hZ!3N7y2pw6 z8?cL1IpLxDdYme}C!FoTiTN9_3k@gwP}|yvm(={t$r7)ZY^I62>mDcOuSqUa<%Eao z`$rW98s67Zuj-eyTdGvD%T&qZ1U0{YU4ED<5gv+mQ@0LtclqzG& zbj7Z)^dv#q=$bM-SMG6nD9T@>PfyT))UUGF^tP|E|0`0J1bt=3lq!9yJQV$L=13u? zpvsBwmfmO|U#;V-UtcO5ymBWP?YeQWVSTDRR6ky&N?G%=@y-dx$8lfcL?7zFI5?+@ z+OFB%!7tHhW{_#(%DsI!@s7W`x}WuR8j8z9`6$tAkoK3~>SeVIxbpYD?ziXi&~AvH z@KBV;!!CL0O%Rl=;&Otz@S*Sh@0IQ~obXW8{EHs`-v&hQxn_0M^pbx?s`wVR2x~D$>Rhg5%p|2-}SgW6m>xdlAzs;Q{{w* z^3tryY5z>S?s0+^tbE%}c&P2QgqiolE{V3r2&Z;;v|8c>Q7a zq8`;_>IwHa!Q5A^c{|~uh)MNrNu(#^MNjR2JK>?cC+Z3RzFMRto>@KdLV6)qN89d% zhOx$y9w)H1Z>`rjNGKHA^j}L2_jtUaXYX^)sX9m~-@g90e}DDze;mEl=$<~_1Fd$} zaDvf5ZJRolty#ejwsUWfj5zmxMD+80Ub)8!?nRjeba^$Q;Y1&bmUcj+643^m$KtK= zm;c{sl;kl+Wn3PL_Bg%{_c%fC#&s<wW3_b(&*}$BtV#ExYHbR~_ z;d7$xL?4PhI##cy;7C<^oZu;*w0n&M-}5O?PvZ@8o-?Wi_rw9uOz^C1T;@)AD1Kj* zU=fQo7I~cDS>m|v`l`O~fumm;uaddP3ExfEU%3+=ir=*gxFqCp0$aZyPAJskB_idj`6UVrjW zOsrM$dxodX-Qxs$tp3f!6kPd+LP@*g;+hm{v6|6@rd>}vyDC^)Qwqn|;aBKH?69y@ z%^FU4D8Hr_xc+C_b&nJ1u~Ir;d8eVZ6c4pMuRMQPb5y+B^U6I=#H#NoRZe&)ejn$q zdz?T|Wz*-C6CTRz^mc+ZM^?niQT70^w%+CLL{0R%%l-vcE>%mE>%E4TpcCvMU=_2| zC}>~i9*SK9taZ*rNfCcj`L6JH&mOKr@p`UD*!VZvhgvP`!K{uGujgS;xW@_BgV`4_ zr>bGG+NZMhP@dDh2D>%b?Lb`YI$}2mwzr#}@KEf-61|;pj}zqXqRfj}l!vavLs2%W zF@37sLzydoT)QXS;{^3hWwV{|P~IQU#Kd)Y{o%^lE2Z4M>ALF#xz28`xy(!a{PlI$ zLv62#?s0;;pcF>z@o&G1?4i6B)UcBXZxhr+wOZGXup->!1T|k{*LK1~`AF0g{$*?5 zNzB}5JTGyN6U=IFn($D>r1?XiD)%^neKbO$h-qA}+~e_LAB|8bVp7{&UWYs$FSdR^ zoKPrVeeVhPc)Y{4?Sf9b{w9L&--aHSpnIHP4u8{xhax7GO@AHkaRU2jghCOM%4Vq{ zkH?Fx-w!7g3JsObl90#a#n$hK6B#OZM)U;tQQ9-%@p5<9t?GkKlsWgcTCd?gTB|+W z8>C)@u25Z@kjDwvBc%S~xu^&ag@*F2hMs~6LLMiu^}FKdze_@)7WX()a6zbMc)Zy9 zJ;H7y6bg;5ws#uxc)Zy9eW@Xjhw}Txo^X#7+jqn};h~26+lyHFR%7{kobH`Ck3+LF z-gZ;T_Nn3=6wO#T;Y4#E-uW979xrFRXlAip!#z%L&WmO>eX5-BP@MTPo-KLWIW0-E zzU|lH9w#`@Nx9Ic$_Wp}nJ>!2p5U}3m50-uQKho!3HLa`c}2?Uo^W-}k5T?O-4pI{ zf|Fs!<>7>fTBK?UrD>Ov(j5dPsM!)Ft2W=K%JYgdoOFNY+CAYOC*sVg(H*1{9*W<` zsdA4K=;4Mc_5)7j}v}PE&2d!s+^FGMpx#OYslmAV(a&%hCCh$4fXkv9M_P? z32gno)R4zRp`qFGl90y<-+{kOl?V^Tu73Xi{M@Gr#hgL27oV4UYwlC!9w!(Ll!x01 z4@FEW%_Sj^6WIFwa6+Nb7}s6*c)Zw0BNU35wEDhGl{_9VwthdHP^d`lXpP=I9&hL! zh0vNHF=>TvnJRfaUTpo|6ZDqy@Jyd?Zd3bM5#U?H%bLj3e!lUGC!W1Mq1wcxQ;xQ4 zc)W)bipvR7$Ty6asq(lyl&7{&m8YHOiJUJ&ydG0exW@^eUvjp|;i>XaJTK*|zDt5< z(~66y&Po;iigKh+m3y3sHN7aC?SzM71xqE{6RdNoW}v4U!;0Csmbk|WPi?PpkkHkl zJuY+ic)Y{wm>4FtDv z@}8(CyyY;ST&Ui!G7 znrn%2eI|+#Yen)nLHR%Skxv=aM6bIZiaPd_|K>j?QBuTTtc=P-*(lzl)e@6y&;3u4cE7%vC`O-GPEa;iUNO3IkIO?H?aG~?#wdk-syr?a zMLkxo_k@3;!oTc6YBfjc3HLa`eD|ga4@FFxqbxP#aROVvA5JKg=lYURZTEPw_50z3 zLZPAFbxFwM@nY-u!wH4D>y7u@d;Z67II$cJ+~e_L>%8Y);~=3>ewubqxX0t=nGers zmZ@^WL-CA>Cr3-7|1x@h3w^O-(vsG%fB4ta*;%DKvKF}hrzboV8smE$_c(!lG(w?> zNp~;HRLSGOsrN0jMIDvgMLZOIBZDpw;kH?Fx-w!7g3JtZD zB_WT;i>==eClm?|wUs3ykH?Fx-w!7gDz0PHqTJ*0hTc&KwLxN1TUn+`9*-AWzaLI0 z6dGzPOF|xx7hAs{PAHUrPrN7G)5p8*tJ6F&*ZnI`%yoy&Qyl5_8t!o-Rvkun^iFsv zRyOnmq1SK^t0#Kq;4$@tdz@fZW_-`-goom3r0&~#4OZWj-dMYftL6FCIIrB}1nY*% z=~-i9rq8*xoR7J_9OiL?I;|%b+X)XvThVikp78XtUaK1J*Vhy7ae}pCwXW@ihw@f16BBtwt=5wi zYP-^o_BgNH;{+PxymG=rkwTSCO;t$|f8~@k%SHMtrO?YM!p6US2|7VvsppK_2@mCM zWl5+-Il-Fe_?e~0<)OR>?=`%aVLyZVd9MpS;T|X0KQT^~6CTRTX{n*w-~@W(-1WFT zl-IXeW1`HxHc;Euf<300C`R;fN|h6|wDGeHkIO^RuPmOI)Ks~L{z^}7Jf`iba)Q3H z(}W8C}PsAf0-(IJYH=5emJ2}XlT~IB;@gUvGx1mghHXAS^tud$K%D; z?}rl#g@$JROF|xx7hAs{PAF7d$LQX`Jsxl99fi={1Tm?{Sf)xIj~83NA5JI~8X6^* zgghQEwthdHP$)Ds%Ulxjc)Zy9{cs{fZTm_kr-jBoAHF@1@v_&4k!_yuHlb;kc{6KW zc#a)=!irTaZ0>i)eTjRVpdY(w!b1_0+I)ZI?r{S9XoNx$liK`JLmrP8TfZMpC=?oM z^GiY=j~83NA5JI~8fx=PLLQG7TfZMpC=?oM^GiY=j~83NA5JJ#T*s(qaF53udPgDD zmk^WM{4!PYc)Zy9{cu8|&`_IS67qPw*!ul&LZQ&eHlGaVs-?%{#XcILP~3rYm$d8| z+~e_bf5V;FlJK|2{WJl3BIR3N1@kNSIKf*fH%)jbVp6^>HRN#uTfZMpD3tf8OF}v7 z@nY-u!wH2#gBk2HcirRhVvh+wRl!dtfEeeldz|1sjhiMs6fr5^`YU&j6WB*16pEOX zZ%Yk%JYH=5emJ2}XpD2$JsvOim|&Icj5GeRmF=@u-+#szs?AD+^!ilwo+NlKdeel5 zBBpVw+~WlH(Fld&bO*i&wyeAE@p$RSME6(jgok?Ci+^(UUw`xgEe{(r(U-W#iSlie zReTGrorF+A^B1Rh#8*%I@8a@iAYUq7UWa=qXMN?Cx*$6uum2VeCp;AIF7j>DSz{96 z9w+#^4&OhVi2#ZQU%26ma(MVY4&S50cDebf*g^afOz)GmGkwrgBn~D-=O68nJ5Nj zp5IbuR?HKS2z8WiNIT*E@j;D@%R>#nay*eL_c-CX&}%s1p}b^gqH4Iu3BHNM*X)*g z<%Eaw`ZjA6BfjmV`op)c_uaJD)E>Uqd3dTk)b{qlTc&E~e2GYH+gor; zQ2kGw%c=A_LCx=4ZNqxPL(y&)t#%@>ycMCrH-5R=VT&p{p`kY61lJc|3qIJx^>Jk= zFaLH4^*>P_((ric$CSeDgohfo+IAh8CwzlR<$SdAaDs0MsgCuj^0+({Um{Wsor#Iu zIl{00nPo%c<^`2z0TmozNC^e2zU z>oeyXcnW0N&(ju8uJeS2lXm*|$$qx9pJ())T;~aYC+o~I>Qy6V4c-`M-J_hNSmHgc z?H4?0Pa_X%)_;+IBoXi`p0kkmCp^^UAHH#Q<_*^k zuA{FFH`{y3r=w;ZHLsF5>qow3@9EEsb~9gjF`@*OS00MfH~;c4j41iU-?V?{yMAe< ze2>IXfhxB^{=dz_$kjr(0EJe1d-UL)EX zYbo>qH{1J(+eS<6`?11IN>%Skg4R54=T3O2VNYFjrv1Lp_{vJD;`-vG+r#>+ot-2o zn`itSC+i+Ycqq#M&UYOVB?n5cAD%qDH|8j@(sWS6bJq!aqH(I6=tE^r*ODmt#NV{f zzM(k5^W>TxNW4AA)iT40bC@hu69l1Rw@8`86*^8n4PrcJATD{FU_X&!s>x~pO#4oF zC}w1esVCgy1pCQiJ=(6Lpwqs4*b5gc)rZY}T*C?W!tsXPvX(gEq1X$@TXjpqJ?z%u zO*%q(Oxv&A33dnZF56PWpY*CBa@O-a5lWDBdSisus1R<}MoYIDsB-pe;4r z!*%d}-_bRkAP;%hZ>iy_@=%lwZv-w0_fY1%n|kzAIYE8nJ=IxbigKLxJyjlR*amCv zy2lA>zFKg^E)6FmDaqT^^U96CR3n=W#6|l-hIdNI7Z`=S1#?IoSJ(lSO zhI^c#w~M`M2d~2k4@I9CyWWhLH1|<15-Luv>z^7eQ>F570zJjFo$yfPpy!samwCO1Q^~ z#WUm*n!oZyxQk1>P)@E%t=eORjeneD9}A*shVKK3)!rtWrgxQ6vJWG5KyzVL0I zt8@!o{}W?v?7EJzHg;p5tlx?sYtU22zLg*zcmFfm>cX>DtNY)nUul@4%(YLuk9T{j z=wFo*`rUJH`IVY>w6~{99w+Jucf(Gfs&ehjMKdlB#kg|oTYl|;a1UeD-7dUE4dpS_ zY;FJa8cx(P@rGLsH2S#8$k{^iyK;T0k)9;bd+1|sy+uQWhvNDk^M>0D2=~;H^9D|e zh|*L{+f(HPWpmz}?l92sEA&v*g{)(#QdY_4vx1_1Jn02@sqxZ27O9#jbNA3bM9|WX z-w<>v93(sxy>`-#sTz#uYEksmYIpP{s-ZP}3C-WMPyeAjsbg)+U5LeXRKh(@(A$km z(A7OvN9#+R;L6n#)eC6<^u13XD*Le-cnW0NC*C;iiSbTn$i&mAo4#@<=uyYD#PiBS zd9L@V@?2!ZQ7iJ8;tF&f?s1}ycEfh=goonyu9hG%QA<1&8tQ$91W=vzDK00tzHtxd zae1gZJ|65vYpUEsj;g2jm`Y;izdlt?P&VrG=itTYi9S@ew4Qk9JNEY2ElVHu(fh9V z*!zn8>?i-g9{UHed*WSJpS}0%PkwLpJmZJXE_1}#xAKZpt3CE@FNw?Ech=t1E|1*; zL4*bbJK2|ndz?V~lHWM6$E#ks6CUdMpE`T*()CEgufx+0aoIJa>u`?~pMB|SkKOCb z>u{nE^^lTpBVuPKJx*MC#cD}RQQMR7P}{HEJx-v1t+U_1F zPQTsx^ELI?;Y1(mk;@XSS6-f~%^oKnyE=bM`*6ZT-RAMH^U6I= z&$xL!Hop}gI~|)!CEVl0b$|Hay(e7xr-R&ej}zG4TM)=pje~?jo%gZt-uuKo{(s8e1=_l# zEYICRb5IhE+_i0iD58jxV7C_n^zOA+H)0fpp)r8RcuPZqG~wtGlcVA^fEP^QG)jgL zkw_HNAf{;%S3~!|2`4BZD9AYd+PdwuKY&mM!nKh{@Iy*2Az zbJna`Y2;bgyDi@pQm9e`nN#;TadgB!tV+WP4|V=jX|E$G)UNwHdE91}{mR|L`wc3! zc&Fh^dGzaWj}u4BSM8VJ9^s)p4_m|F74>jj>lUPD#IrTR<@=Hza zu0eY*M5A^OyAmEMzYJ9nA<@d*<8tErZ+pps`K}Wlir-b5Bl<{O*O14FqoYe~q*jus ziSB{WEc3!OL~u>@+Q8%TPHW6#8+~Y)kW$f&gJK>@DeNF9%pZ`Sr zkjDvH*L3Amszi7wf2YYLs3n$*^pDTHDz1DluT~BBI6;41^)0#|dTzd`EnLbaui+d207lrP|saDymQ#NN(Bt)(BCH7aIDtle zh)f%LdM6kqMtF5Ok5r^?I2ubi_w z^tQrGxW@_C?nH~9KgOtx%R_OZhw4Ivjej97KKYzmpY$^48>8B-%ojta-O&T%`A2%F zSK5K?F&)-$f*h&$g?n6cs5_kKy^yZ4gc39T+plr)4Q8c^T+ojHIaThNiQ65xawqtn zv+{>BSH8`uau2mcJG(um!>MwDTB*I&hY1fwE2#HVdmZIE^o|LsQY+ZkkjDw~P5sJY z!b2UdiBlid>X=gHHGkG{54BPR^?0uhHZ*3Ix(*M;H<9ah?jF90tiHsx52wlrz6@OV z)E<|I^4@ON@E#dLbMA1kF2}>YR@UX%oNKVxGjzg3aX*)PF$am3Jl+}2 zxMt!t8}9H-soEpB@}qVCFp5)f|kZT#r-RH!b8!Tx!1T)P*RGE5>%>Kt*D&lRJq3q zYK+RM6H9Q*sS|T3&$m=zew7|4sMB?sJK>?`p3gNrue|nouax1>_E%2uOqIKy`?>3J zc_{B)XAN&T+&NVr>}_)<+~WjyZR=Dy;i0(aTerbj^F>P~6!($2S})n2swL7E#h^zw61T~@VGpbx3o?y!NvMR z^K+k(`^;e0aE}vvGi1}q`G<$%o(6X+rn=jx<%`%j z=y7={uc5PszX#doIvcIq*q3o=baqb?oSw9oS4}MTWhgEW#hxPlKBvk(PIxOgOn4}E zi`5$Lal(70Rb$~gIKPmwklMh>gnFv~Ih$|1?>9W9I=O|@Iu(j@I7Rc$jP4Y7jTS$D z%PH~Fr=x)$y*2jbuXyEs>!+_CFXs$0_CoAwghbPDj}vhcB4f+hIh+$7ir@F{ku6+@ zr`N9|5>aV*yrhb;N!PKb(V~g#kjDvfMEMqa@$XD{D9TB>J`jA`OTOjuy=TIU zYP;G8XIV0jL&H-$r^-D}aF!)=I_SfMhvF>Dy;L=nyHS~5PIOef-U?<7_c+0cj=HA9 zgopATVy=nSX*uO|NJbhwoHNNR0NdOD zoGSM?L3z{~?x6&gc8}?>h7;5n<=bJxLwSF^5(~A&>krqV_Te>jC7Q9Ey2lCfP%Z5+ z;h{J$v))tWB}E%ld3edr8t!p|_OFsXOn4|#wfFpE;mUbOQTNEO_1vgD6R;ERae~x} zo>S$7hl&%-FP`Uc4P8#%;{^8J6Re)9vxGu%cDtT`&8c#a$BV7!R4dUn&Jqg6iIvRn z);2h><35s&``-nSSRFhg82FWwT1`}MULqA zNKX5Ap(eV=iD=CaN{x=4B|MbZu@QJ^u$n-J^kT;;w7V^J7;67ISkWm|+@B%FxQCp- z50!;fu`)>yGfDp9t^qZ3)d)u;Sea^P|JgHTmD&-w|0f7}oZ$Iz{iZh>B0Ln&igXsi ztdU<5*ll?dm#2dqI=7Y;eU!sY@O-B}_rnPf#WS6~Qwm!0;<>YGHBU2?cAkq&SH8s6 zkXN@m(K!q}|I#@Mp6m0KyT=Kh%IV~Vm1sKg+*v8%Nt{k}@LXSsX3Qn%1RC|Z1|FA( zB8By73p^*+sR87V&KcmTlj_@?D)%@+PS@ueIN_mq3Z!!sW)1i7%y$z9w%r~bzV8)p=ggPn_0u#0oRe`oGoo8yhS-d zzSZ^02@k~%54E&e!#z$=va0!q2@mBhcqY80=oxhOir0lRgw<*%=(}|8%VA;;rLPQ* zRq7I4+~w4HGTgINyk4@ihI^dg$+)iRFyW!RA6toqzQlU~LaFCOTYdgYG-K|4oItPc zsXeYa)P>YUC&+~yOEO)tBSquK97^A`vAYKS%6UGgbw5uTbf>`gS*HS5?j9$2PP8`{ z?HW#asMvXCbI~EBePrQrg8QzTEzha)xI7fUYv#O9$m2xZ8Lnna9+!vW_i09k&_Z6h z#|ch+uV;Nucqn#e)*9|{;?5tx=gE`bb@S!ZY^kT}%!#&b#TfhMFZ49sqm`geYt7KE zIsO)|+~e|4`2|3$iH&P_&p+?|n@cY_?Xy%TuvJb&VdU;vLZR|Ifu_+@aJzo-4FZ@YeT*Qfkix0%E5m0(Ymdz`rI%`e!z=&9A3(+LmtJ-2zm<^hj> z?#Q=D5&tfy-}wtK+FbSTe{p#9Rgzd6DAzMQ#L>}>n`@V6b>h)?y=n8P2mYsSdpXU7 zdz^UtUCwRZ`t`q*sak?tPCdPk|KaO4H+|W)J(OSHtl=If?sVttHt&7iucpSpxc8d* z?xFa-zH;|CaddQD%iZT3(8#zl6!dd$^(&u(pahjal)rL%zVg<)H1#OK{3^})O3=&0 zi66Z2#hX|Csp>+i#ClNIF^9^!kl~}2kg8~%zkBkc&Cw%X99P@^+y8%CO|HZO;dw#{ zzWxROxf7o2E76Q7L8Z!xs6EgA6uIl6Jf~NUo~k+DU%1x%3riJkUTx)Pw!e8GcRel- zHMdPJIsUhtzWR@^UwdkZmwzPsmAhVj-FzDRO1Q^~zw@8}>*hKCvw9QBTj#Uhf3B5g z_)*3N~%J#pes-oqB`bcSXEjr{fBA9kVCnrG37G-&7U>q`t#DY zKll1J6SF4?Vwy&rMc3hkhw>UTYq-Y=YQDzA!-R(_Yhp_oXQYt-+~eDAnOl)cY zmeBJL`jP1?F{_4qJYMQFv&*&jSqb+zfvsmcaRs`LvxGv?Hkpa98Uu@-TF;=UOE+Be z$sUTH?`|*pUj>1>2+HI0e}+{Hqy7swzjiFU2`ow#BeLRUJiq5ReWJ(fF^vTE|HKSH z8cr~mc-UWj{8OaLLmkd5_c+0VSrF)I&kv@t%Cer<(i7!*yKo#=l&zJY&jh zk1LnQiO9phm^B(W6CR4W&o^9cPy3e8X*2!SxA*m0ORv`qdek>v_u)drYXc+P&t3mF zJrr{Wl~Y~?sdA4KjEPe%8Q4sCD8{R-V=ed+NUXdR7xOu#>cZ-k6XeyWuI(Pm>-4yU zp0efC^Bs+MJm#bS8)fbUE$X6Q{zy?CUUxl|m*$$PX2j^6JwV1w3%<{1RT>_bhdNwK zyrh^jeA5ll8+cuqQ{^5fT1#p@T-BF2;h`?9%$?vml)^bx9+!ujd%M9b7wi3iY%@aq`X2L_Ep_#!5-2W4IgcTP(k7kpH3HLa`tRP2;7X1=Rkt(TsC}OH} z*F8=Uzh)nC0j{CAJd~GBgl+#W(fefCIzbMo4_*nN{+^dKJXBfcU4z}F@fG>qmfhFv zccqu0j^$p8q0$Kt#a>!=%N`^e7(IjHa)MS6yK~R>iL-i!BCizFNK^k$Xyg+&eUE;( zMUTDD`~9wKus4w%hlJuu7JC=>2~RKkoOR`gQ{^5f*nO>>?iVori4xQmdMI{ZtDJh^ zC6IWROjk(Ruy0%CkvS5f`FGB%nRv~HU9|gGPF^W4YK%g$cbA>B6S1J-xyW-uc9|+w zy1pa(n`?;^Xt3jS(rDyNcqp&aU1I6~HiB|y4<~W4qmY}I z(}xKU<@If!P@Xt}9=ie0f8`#^>+!5X{ZXk=uT)E@q4kx!#|i4O>RZ=XLTNem+CT}i zL;AvV*9mG5J9X+mb*)DFH5MJT_f`8wR=1Sf6q-KR;Tp>f8R_IP+GQpLBI_6fg2PEk?XeW%KtD)%_S z857Ed!-R+8KORGNng4^`HZma<5da*;CUn^hNH zf=+Ob3E!+*uY4qJEW*$21e}ae}v|r`~5^^ZqLjMNH~3_BG^j0=-Y&`*D20a!59NK#N-SIlcO$riPI|c$qS9m*C3_{B5wj(EoWR!gou5!B zG-U4+@_4-1nroe(P$)EH?-TNPyx5vWou5!BpK-fLJ9ILMf)th z)L18|oK~V4^X@h$u$AlQClm?|+53b%9xt|X{rrSNp&@&pkjLZ2R<56)P$*wh?Gp;+ z@nWl`ou5!BG-U4+@_4-LxS!hj(zy1&C_xb(%2#@`2Jd2Mj>DUbsu{emQO~d3u!Hl@lI{)}^wUHQYn1RXKZ1GvOX5=rQVg<%Eaw zUTN0ww#NH{TBUd^mlfsMF~o;Yb>F(oO`c}7dCp?t5=2^qv&-V9{{aw;dEWyohdOLCW4N#BELzVB6HJRnq zJx*ZP<#Co!s0&+dd%W27IOuVCs0+K#-~@KPN7&=?Q2c(FkjDw^datv`<)QffFd>f< zhrfd1ad{~JPD|7%)hqvwNnA(lDT&nD{*r;k{SxgjaROWWHD(Qu%R}+|VL~1!u(g+B zU&9H7LPPdUaH50WUiP~NXlRu&6Yg;WTQ&dughCOM?0rHWj~BacA0C&7;`hUZJWgP% zPVcA6357yK_C6tx$BV5xeSSir(2%`P$m8*bUR8HJE)NygafncDcLH1WZ9i2`C=?p9 z_X&ACUhKN=dR!ig-)q8WOFmLFcBy3NRJq3qY?bW!356mi+53b%9xt{^_WXoGp&@&p zkjLW7~n>W)dY zYv6A=jVG?*K|=(oRZI~!{*6@0;{?~lX&6(g7HKHGJSFAa2|{^}>}%-Co#1H(C$3By z4W0AKL-8zxQ&uLTr^-D%3*lsy3s033JPYA0mPunTRURsy8&w3QrrN-BHPtIhRyi`~ zm3y3sQQ{(K_Iw@gapG`oKTD{b`CazDhCCkc;dAzW96e&?F;wu=k=Ty1J3GBLkoFx>B-(~M>$m8*1s}-D|P$)EH?-TNPyx3|5 z=O+{j4cYsIJRUE$TEY1Vg+fF2J|U0C8+ujy@VGowT*o0oEy@XO)#?3IIiXN!$lfR9 z@p!SbPA9|OsEo@)@%v#y9w*-S6F;(f9{>wVZgm6mwjj zo@pk#Ud4h2&+D|V<;kCBVScw|B~}f!4<~qPtr_59!b9;~tzJ#={8Z~#p1$ht2lst+ zeXGX8b$DDnyVJVn!mh&!o)v0MwQ4jYp2X?OJrudSw^r+^a!)*cje83hmMSNBj<=_= zmnsic-XrUTdz|17YklQTcqpC^DyLi2>tB0A!8|aE}wzn7zKFq0v61;i0@I>KaQZ#q)E;MT=6}T|2^xaE}wTVCCCk z!b8zxOy#ji!#(s@DreU|tl>oL{i*JFd0ZZf{#dA9bNYf?m0`;UnX?|TcLb}n{(GaX9>}V3224#5pE{jbCwW&n1EI&AK_-g zJ!c8ghY4tf@)2$(+;f%?eVBk&C|1Ed%iFId?s0-OEl(JO_|yCU(CJ@2{t4$$%P))F zu=TG@rF}y?SM7H{?O&We;=A7rvA8Gg-PXTXH4#S{>V_#)5@>w*Hy(WYXK%bsd%Nvu zaZlR2t$#&pB91cD4O6Hj(D>-5f7L1fL&H63@3#Imu!%UzP&Z7Wl0f5%cis8)7eDxQ zUBf+T@3#3>v$KSIYJ$7YPk!@fo!;)^f6_IaNSja(+C;9P;e>l?0{Yhf@}uW2{o3#D z8cw9W+vdp>XgD!@loBV<_;2_A-E&|6u}5|dC(`yWnW16CQ61_mK~1N|Q|9@u)eX}Z z()@j_qa!1ZobXU-ld9)G?)sa4@&EX-uHl}vxmtgp(}<%CMO+?A_RzTB&}f(99@+8b z_k8=TX_SP&Wtuh`?aD73d3EHTw0B#7tMxG9q0&a9^&^+jpR|iOa!=aim4Ach5HW`m zfkx{`j_FU($WV9`YPa>h^@j-$l{PW`(-++R_zBNH?i%h%d$-NK^=Aq9)C9Tkl9%55 z_*q~254(mFY45iAjTtm*!b7B z{5Wz?+PkfP^XD+(q0&a9)!So@YVJvUxAkuq9VR?f+Gw=)cTCHrR=Fo_O6@@{uV|Cl zhln|p2sHkm5B=EjTfgD@`=XJd@F>)7`#XR9%_s3y_Orz7sR&Z_=Ktq$$8US{C6wSEK?y2U+Gvb=)d}~ct-7oA z`5_`|VuVT?jZxc=xeoWF9W9Dh9M^G(@Vf?SqtWIh$NUcs_oN;D75_gp4iTh6q0&a< z-#zJ0$FKRD2Xqbhq`lj|<4?Z$6E+9R)+Uv7h?ql(K;zD@y5;GcKK-HN%H1P-w|(eee)Z<+ zyInTghZD1>B1qMT|G`D4zxnOo*fpF;JJui3f=N|Pcqq3aSl_5GVFjVM(vEc$t$6KA zN`m!{LZ#hP6>GJA9qvh6>p}Iqtxsfiw@1VZB|@c*Mk{aDoV{;%Pujb_Vx>*SbsQpC ze=1bkXfW5+h~u8LcU$Juw8_voM0lvQ(P$&*sm5COq`lkb_s`D~?x_jtRhu)MYR=$9 z+Jxedc8`V=?x_jrFaFq%oxcCNAHA`KUYtm~jkTL^yze(W<&{IjiP-}~N}NFBVb6Ko z>3ja(A27dKoJc#$gT5uM!wK?7o|-^ol;AluoJc$B6@5#T`Omi=^xaF$`kwLhO{;B@ zi)rt+AAI)agtK2FRZh64CP>w*TMzo`C&WD&C(_<+fA!qvgcD;!!wL7)1R5`CJ?OP@ z7w5={w0GP0{@JFTnDqxk!wL7)1RA$^;e(G~7k6=voJf1OeaPKUPB_^!uEPoU)C3xT z*k($9?{D|JI7d#Tz1#8~Rn8j?4JX`F6KH&_^;Q34tRS68n-jWDPB;-YG@NixO`!4M z*1NrStc0CNyUobHVtc}gv7zCFdujrWFL}ZfE_-*}{Wx+W?cMf4Purew=4)s;;hvg6 z}`D z_ThwkY66YcqE1H}T%1UIxBV|~y3*RY6Yi-AG+NJaI{K2uiL`gyJKXO6)?Yc{o|-_T z^>C-7Ph6ZxyUqGG_dm&g*9rI31RAZUJ{^7g;zZiJ?XAD#{x*I%;hvg6qm4MHV~kpy zNSkLx_g}}ZnQ%`{m`1;A;6&PS9ef)g`jU~VP7tp=HDP(xXMIkj9p%CK`k^uMsuSdo zJT-yFD8W4<>8MwncOM!~P|oty1RA3z_W7<8X-E6uZ1>P`g8C{?O`tJaRM&7K?P%wm z03RAo(C*}^2{cB}&^4S$JNhfmj1LVb=s)DC2{c9z*EO6-JNjMDq7Mxx=m+Jg2{cAe z-8Gy@J4ORe{SOT%=+EV;2{gut(>0t(n^0G@6MLoMgnMdYXfW1x4JXo$@m#50N9Rs3 zzNSYhabn~ZbA~-4>6n)&*VkD_CzvP5Qxj;k5@hbPMMKKrc8cw7g^If&(nPC1YPfeiFdIsjyUBijAW8SV_X(pIQ z%Tp6*v>uMNLGKftNITXa>Ro4o^?*DzfyP*|bPXrcj&+nqiJ4$sBTr4BF;-rE#Bm~R z_D|#*ZYJDQ6KFiUwZD7*Xsid1jxMn=RrYTC{kOg3(n+sR%Sa+S=dq#xr^+ z(rzo^2VQdWv)`vRjuY;w2{hi+%KWRwdeDiqciT9D=#8UKbizF~fyRqk`#XM9f2x1v zMB43{@IBhM2d;k8&~U;%HG#(8Ztd?~@l^lFiL`gy`@ZthliObVheN{&_tXR$A8GCH zePcc7MA|LX@>M6dyq0f!afihT_tXR$ztY;@jblCNMB2OU*Zkvla{X1DUxJ1clV?qd z6KK4uJzx3YSPwdp_HO%ZeJa8FG@e^XoC zJ!?F1cOvcG_R4pDtzCx`vqvd$0*%|W)!lm{uNEiL-fds`oAl?0*yA}oQ^SSaUyL(-Ot7@C)`sL zrqRb*C(@4Vc`^k>en(wiC2F zd1?ZU(KGB3Nw-j~m-zU%v8#BDgY-U~a8FI3F?zT?BI)RNzxNrxJv5x4A6z|aN}NDr z^weF$iL_%hc+cIW;ROA;JT-yF7;(CW6KVIWZEa8*PQ*wSo|=FjBWL7QA5#?a`L0^?OfdhHrzX%CGvuz}MB19StG{w0=F#D) z2{c*{$J(IxiB6;)>ksv=Gr@X5o|-^otXR5+6KTgfDn|(?Sl7r?6KIT;S08blNSjbv zh0$L*;hvg+X3hDo@q949uXe*W?Kp`qPJ%|m3C>%QrzX(&ys!JA<7@tHJRfu-?cJ6$ z@8Ya#G@NixO`!3zR_0G0>p>^d-fi=1U}!kuo|-_TjcUg?kLQC*0!PCM_tXR$|95*n_~x-5bRzBDmiJELq;xc#a8FI3 zar`6K-|tt(^Fb%lZr{9LziNes6Yi;rp>fmDSe!_Ex8l?0*zLJ=SG5Jq+j9PyTJub}rzX%~hCKR`#fh~2o0HTlCpb$jzQJ*WrNjv| zS`T+R`ozVFw0B!hV#|Kl3HQ_l8m*^39ew-aMA~hS*ZRFXuEPoU)C3wli5p|o;zZiJ zZGK-54JX`F6Qxi#Mm_{dvSDu=%yy|lXC(@4ci0@liUUh=}k*6lm7$vwz zB&~C6`D!Q{PEgMA4UQXn&Cr)N@^>^wP3&{H^xQDc!;PNA80t?o}{BiXl}KnYTPOfkx}$SR3>{(TTKU{h{7@`PRyQ)K;w_w^TE#=`$e5dyS*iJ>D8Nuyy(_L!wL7)1RAeuW&X&q9&{q@-S*F) z|LAsow;LKxxThx2_(-d}e>&EKPNcotzV-Q!*1+_60${QdEK(22C$ zKAF4zz~*81x@c%P;hvg6qg}&sOWA3Aj&tNh+Jt)SI60Df<%D}`0{YU{{{C>R2c1ZJ zx6PCB&~Re*C?!sy(VjV9*6yu@6N-8N6+L&FL8)C3w&{_*SY_aDZ3(22AOwQMfE znKJ>=aKb$`0sYb+zy7ADg+|*i>T$_#_uFs$@p0}T8cxifiWqryZsgVCMB2M;p8YxU zY9-uL6KJ#&JU7aGaUyL(>8w#SoN!M~K>to_f1la*TJj9iiL_f@UHuc*KAf06N{JI_ z+^5}-d0w=^#fh}rUYu)x(%QKb?x_hhXn&(GS)53Fx4q@HKV|)u6Yi-AG=9CczdwpT zad9H;-Ig<}vfp*WJvD*G$6EXQso49mIFa^l%gI(bemLQtnn0tCIHzNbTAWCmP*1Y4 z%L(_?glY7V(}}d>I_~oDTaI=sNIS-lk3aMSL&FLBb9rh4jWOaxUKx=zp_a{6=iWawoN!M~ zK#!4g%UYI8LNZD6PVnUpe8PntxThx2;C>8u z2+?pNZT3^&?t~MAL&FL8)C3ysxx_JdI?-?xYFi5mOEH^@YF|ydujp=o<)r^Z|@IgTxs(@&K<2@IpLm~K!ay$qwco% z2Q#j;d9Ub>);^qYPfeh~v%%2@+xvqVSK7QEbw_LGPPnHg(BK*8=u6uBgBe%ayyx|~ z)?Yc{o|-^|XSJhGZ0`?dTxs*Z+UHuo>x6r10*%&FpN_u0y+4?7rOkVHpKIfX6Yi-A zG zS9xjzjnSgIh7)N=JLf$2&~SowCr?eFF?xos;Y8ZeUvUC_XgERtAx}-9F?zVJ;Y8Ze z?{dC+XgEPXC{InGF?#B*;Y8Xo8gQO_XgEQCE>BIMF-DxO;Y8Ymy2DAFGC#&a#;8uX zrzVC5W9=T1bd2Xp?K;+Wg7GyyN{JIAub4CJ5lP3qM7h4sGCILLL7tjGqm>|YpFJY! zm|v;(%mnitd1?ZURuh@Sbqy!dj(MV5!Avl3lcy%oXf2AlXxDHe?U?VXHO~a|PkCwr zjn*?Tr|ud~q#g5i^-43rJX)TbK%@0=tPOgf=tSDF{!s5a6RZd1sR=Y%PkpSu-HEhg z9i>rXCRo?VQxj;6l~*5eoJgDZ2XhTK6Yi-AG{y?@rlbDX)|L z;i(BUMom0s9CRY>XdnOT*3xi-`YKONpy5yZoJc!b?Q?(N?&CU~pxwz+6KMF;J}1&9 z)Dt(?eU$GElUGi-rzW6B57+a`iL|5Njc*yF;RO9)dXy3;&=@^+*Ki{37!98D?Ya&p z=+EV;2{im^pA%^lYH4jy8cw*UCZNwgAI!KEZ;alvo!gCde1&j;83$_eJt>aS`7jlJiCBd(-l{h{7^ECj&)Ry5>BwLk*6lm7%Q(n;y95up|lF4FLA;>H37|ePMicq-_F@kw>Y}|a{9is zcUw+vy4CaU-+!M8_tXR$oae-eR%kep_HN6mP51i32M!G<+*1>1aGnz1aGnzS z;e>l?0*!XA;bok_$8|W7_HN6mO}Ba7RYSuG_tXR$?Oa3dS#}L4(k9evH;;Pw!-s|w z?x~5Pu|Dl{BJJIl^L_I=IBikS2WO8`;>5_Sb0e=7C(_<+IcGA6||fd*&2jy`d5BJK80Tsz-4`&}p8Qxj-#X6@+P z7bnu*Z8_gJ#}6mmQxj-#_U;&?7AMl?e)}8Nv1=yWQxm4q$66=Sj_dgNx88fS^O34f z5U)HnVR_Y8cTS`o{?KrOeo&s8Kx6dOUBijAV>I~4Juey>PSBsr zQxj;65vOZ7kv5@TyZQO2f8Nk=!aX%HH0=4H$0a+)bES42oqMVnU(-_&Bd?e<>=8-F zyhORa&N4c|JVBnCK%6l-s_RIwH9eHX3jaCzx!*vZO(vEqeTER>(Z*`_OSfd z@7&b;Mcq>qXpCpur)W5l_HN5ty7hih_tXR$;~9O|a3by9mbY~4{i5!v2{guDgRbF3 z+SDt3Pni1*PPnHg&=`9rx`q>J@3y?9TkjWjPfeiVyFZ;sd$;AS*?PaIdujp=-~H)C z+U*N2NB?4T_utc=R43e16GLNN-8qr=Zp*1nc^$rA)IBvZ@@n1v=|tMQE$514dH8-& z_tXR$W2X~kzBrL~J3sN&j~d^prd~PWo|-^o?AYoWPNdz=%ecp*t$jG*o|-^o>^$ol zPNdz=PI%bAvUcu-dujrWv4gH_IFWYSJNTf-Sbyb&dujrW)+es}MV&}{x8?kx?021T zPfeiF`u26ds1s@Lww!~M#(Z^aR(vIuUuAWt+ z6T~Y|O`zesKb=TB%0s)8W`g{YrzX%CCD`XBPNW_6O1rFPf^wFpCeRo)@tASYiL|4A zXt&r*P+#S#2{cBF>Kaa@9qnAZ-e!V!Cr?eFF?xos;Y8ZeUupN=OwfPGQxj;69!$1RB2k(}}cW{K(yuPSBsrQxjZ|o|+hWweA;nBJG%$DA(6nM%Q4TAWu!8G3GvdMA9+8Qtg=u<~#D# z1R7&T)-{|+JLZXM1vA0CO`e)SW6VXnh7)PWd{?b`CYXQ9Qxj;6Id#`?BJG&Bt5=!{ z=F#%h1R7&)(ECIu(vJ0qde@m?Js?j_pyB&Pok%;@Q5q#?f_05NHGzij7j+_S?qB5^ zZYJDQ6KJqso3>8hPK%`_@q94t-Ii8HD~>%APPnHg&|tqdJrEjBq`lkH%IJ+k!wL7) z1RCQEp|0UX+U?Bc_8tJeYG^p&o|-^ooP~7CbvTiByT9AsXJB*)4JX`F6KISRn!1J) zY45hQGDf-3aKb$`fyOwSs%tor_HIinW3&zpC)`sLXpA$qx`q>Jw|)BUJsD;lq2Yvk zY61=RYct29Je)|o)!p{K53{GxaKb$`fku08X+2-miL~2(hW5@av%t`B!aX%HG}hBX zok)APWj>wP!P`{KlG}wZ?x_hhc*l#G_*o+9_Px~h{%)3s6Yi-AGh}mHGu~2+%X?T!-=$aTkgkX`*6ZNHGu~24l*A_!-=$aTkgkXJ9ol8HGu~2 zKr$ai!-=%pI}P`Fz4cd4xThx2;9XAUqi8sh_HN7iKl@!L+*1>1@P_H=+ZQL&-fg*$ zk>iIG?x_hhcoIIwsKtr2cU$hqXzZE^_tb=G^wpgcX~%Ui3mpAbq^c9dD^E>WUiEp2 z6KO|zFbfQgkyo7{f8?nNG)4*T5lKhAVip)0PEgMB)C3x%CLXtXb>u|a(LR_3hK3W= zS9xjzjnSgIh7)N=J7*Rc8cxveZB#2jr;G$PvLpWKl-b-f)wGNnm~i+^XyPS z!-=$aTb{zRTOl-@a8FI3@sd{N?6g3`iL`fHp2D;1A~c+EPfegPzMXlBh7)PGvx?jP z6?Tt=h7<0o2{gtxK)Z$$X}7sg+lRw0n9y*-JvD*G_?Btca3by9mZ$LS<_Qfa+*1>1 zjBm1b4JXpxZFvgMuB6a#!aX&CM%$;hevjUXw0B#c!n3<7G@NixO`y^Csjc6mcOvcG zmOa+&5(^C{+*1=nWBt0k6KU_Z?6=G7VD}vR)mlYd+*1=Huhy^2JCXKo%f7)Z4|V~v zw+{{X)C3yrO=S1kSt4ofi++pMD<|Aj6KJr?j_6`{G2}?OcPlUpvPSC)`sLXs{j}BhKPP+PiJ+*S0ZgCEQaJrqRb*C(@4V zV3%05^O34f5U)HnVR_Z(3{IpS<-sno&=`5u3Gzptnm}We;2x25)GKz0g@zN9vph9{ z#;A$Mt?nKsR=Y%i(0=& z??l=$-&Jd#3Fe>j)C3x>XIQ^S??l=$Z&$B06U?LKsR=Y%54V1g-ifqh{h{7IFWYTzvA?_&~SqLN%GVL8si>W*Ki{3xDUrEcA?<}_r>I?2{im^pA%`v{X|aV z3k@f@zb8*kpy5yZoJd>uMWx|H+@}mrO$?3oX`d5m$NgQUcD-9m?)K+{^3((x{2y5*WpCk(LOj;Ff^Q?zRFV*XpA=4HJnI0+Bv5RhK3WgJ9%mX zjnS8M4JXo${)$rtL&FLB4|!?=jnOA|4JXo$ewR}PL&FLBL3wHd4S(9_MA|WaaH?Qv zI6;3dPfeiVPy3umTl-|B;RNFn=NqD46GLNqJ}4sT7|)g3b#(5z%lIl!O`vi1`JjlT zV_u?Mp9$s(^3((xVSE z(rS6SA9n0}FXlZD=^b^Lcq{0*$d}yK6X+cI*r1E4!iL z1kdN?sR=a3-t(^EMB1^xov#Ilh7&xWm!~Gs7<=fuh7)PWK7GEE92!pWd|sZKK%?zb z<6VHR;Y8Z;z5!ov4h<)GJ}*yApwZ@`ywlJ%oJc#~o8T+dq2UBO*yO2+p)tKbC?e^2 z|3j%=-{v4y3p?@Tsfm$S)BA%Wl8*OSl1Uo$CsR=aLE6VH=4JXo$_oLLBXM&xo^3((x?0IE& ziG~wt$9rDtm1cq+xAN2k8m)($-X9c^biA*o-gPF}IV?|2puv9aHpimhU7Sce-n-K% zF%#^7mZv7rU}rS5OEjEFJKi7E*fkUEvLQb{(C2su*A8sfm$S)BA%Wl8$+aa($g;bPeVS^3((x zV}#7IFWYDch#C_g88RB zHG#&MA$JWY(vEq%`k0wu9xYEzpfP6py-#!^?O1=Pcby5=1M<`a8m*`1jFhh7MB1^A z(kL+#tZU?{2{gvatB*KNq#f@MYP6e)T%X<0PlO3QC(syY)-cu{#S{H2dV5Yg&c%7b zBjfj(;Q72fHG#%Bd*>V)PNW^@`+U(KNW%%9&&yL2XpA$2x`q>J>wM8GM}Or6&*v|> zBs?{N#yAVHk~gjBI!7f z?AG5Q4JUX$FHcRN!Si{o2c1ZpP_NxQ;^ES8!aX%HG}iT?6KTi!a7t}Y)k?4vFFi_$ z6C| zpD!vR={R>#tzahD;VDl|put{IcAuf)MA~tFqFVDzuv1l@nm~g+uk1cU!-=$YzNp%{ z6YS(xe^nD`uy>c;XJ|N)cDujZ_G_zmoeB5U1RCrpX7?EyPNW^@a%z;A33fosQxj;6 zlRO!t`uU5ryF&cdE+0t-={#>4#K!g3-S`RvrHlbd- zdB)SF;e>l?VrVed_UmvW?HJFM+McSFV0=xFQsTtOE9MMc!-=$GUZPxIXBnMfo*++6 zpfP4LdqmPPzf$d)3FbTU)C3x1M%Fc)NIT|hC|G!x9D<*5lY#!SEWa89Hh>ksv=Gr@X5o|-^otXR5+6KTgf zN~6R~u&$A(CeRpbwLaoFkv8`k*spElAYYH@gnMcN4S(9l^Lec;(~j>b>Mrg~@U&f? znn1&!_BoMu+r!fKOXzO&Ot_~e&=~gs&e112k#>C7QuoMbg6H${)C3yiUdAaJPNW^* z=hV}Inc(@nJT-yFxF^#!oJc#qGpeT?Gr`k#d1?ZUac`+>IFWXIFI7)#W`gJQ^3((x z;~rVpa3bxtFQe^?(o?6Ia8FI3;ZOUVNISkpt7l;|!Six?Y61;^+UG>tgu26tp6Shm zdun26tgAaG(vI&5E4Az0T5`94T|PZZi4!BQ*5`xlw-b?ed>1*(W86dT8tfaCrzX%C zceeM4r0K8jxYnMTa8FI3G49ZJ4JXo$?^LT5%mn*5<*5lY#*>Dw;Y8Z)o@Lvwt=2pf z?x_hh#uJmS;Y8Z;-Ej3vGr_)Ed1?ZU@#Kd-v44+VMAGe9QQNPb{jL-4sR=av`JfYN z$9LQ{O3VbimgT7lH2nFX6KOMV|J-%#nhE#RglY7V(}}d>I&>Fz)#wEA%2N|)_|rZo z(vI@b-RPMhf8?nNG)4*bd5IHgN4?Tr^_ifY<*5lY{Ar&PX-E6e(}9_wzRFV*X!z4U zC(@2~uBRL`LA#TuCeZMweNLnu{gs~9%mn?1JT-xaKkaiO?dW&))M+N@2j!^=H2i6w z6KTh2pl4w-L4Ph!O`zdV`=N+A*Fhwd+`W%#4ijH9bm+ z6CqsR=av`JfYN$NWmQXC|2M$Ws$&`13(0(vEqeTER>( zZ{(TTKU{h{7< zCRh*1QxjfEH)1sm+$2)v! zw>|W2p8>5n_5nEIo|-^o?5*u6*x$TQ$))5*`xThx2;Q2grEXu=)w0B!t8MCL*aKb$` zfrh^g=tSCWZ&cf3%`7l9oN!M~42|{uK_}AQZJ9Oab&Pj2xbnq4HGu|u`k1?)C6eB4 zSr=q^IN_d}K!g3-%tz61BJJIlHA&VhC)`sLXt2kU`6wDrq}|TsX#2IZeK_Hsnm~iS zqRdCpa3by9mQ`i8b0^$W6KJsKmH8+dPNd!T!?pd|*WUR~Dm>d1+-qdb@ehQ`RNPLMzH)C3x%1ow!fqh2u!3=JnJ zXL)J@jZqVixeh1Nj`qPUFf^Q?zRFV*Xp9!sHJnI0+Bvhp&~SowCr?eFF?xos;Y8Ze zUoi^|4JYV76n)&*Jpxx zf;=^WMk~Sfd{HOTj`@{p&rC4ik*6lmXf<&?U(|`TW1gs1FcZw%?skd1?ZU*2Asmi#m~ZtUuJd&IIcLd1?ZU zv0~}{t`lj;I!dF&Ot7wzrzX%CE3ZCAIg$2mo2xLLC&LpBdTRI71RB5C)`QoK@6oq2 zh}yG8ozW(HxBY@Ue{A#Y@739#PRyQ)K;ymb`TYAIALolYk@jx;_#gh*<_B-o*`H3h zrzX&Nbu07lin-5`6KS_S6Sw)Rc6~Yr(h2v}1R8(R>h52~9PY@8w0GOP-uzdaN8k00 z1e6+Q}_P>r4LG-#W?iXnC~~?x_hhS_z&TWxhC(Hlc2DlJ&|7_tXS* ztBI$h?k-NGz1x1xQ*UvS?Zb)Lqm(#-2JLUO!NrNR+j#ytpLUY%+zI#81R9@c?eA@4 zJ?KQ*yY25k_S0IuQh()ydujrW*2A5SK5=m(?e;#-%RcQS`&}p8Qxm;BTKgM)`{G2} zyY2UX=+jPe{Gb+!a8FI3@r<_e`imcn_XnLwn^2$L@=9Zu6Yi-A)953o6KThFeCIFd z?9ZXm3F1wUQsRW=Ri86Bk#>~F&un$}=g6y0kU#R&1RA3R_lTrbuXHY_6H(6LsR=Yj zP3&`OC(@4g@zl4yYV?UtP+#S#2{cBF>Kaa@9j*4RH@`B+L0WAmXm|3|L@$r%OZJGQ z33ZE;@41aMMqkni_tXUR=;8K=q@&+`{13k($3c40PS6jgM=5avjnPx@5lP2r@CA34 zh7toK)3FZm%)C3x1CbLH*O{h<7vR*mio|=FjGqSGXMA|V=R4bSX=56UwN}NE0 z)}$8YMA|XmRcoFJ=AZJ^1R7(8+^@rlv^8&6f8|8Xqr+1ZXtW-VwL$L_ok%;@AL?Ca zg7ttrHPOo>);L|miL_%Km7@f;u#JPAU|l0mO`!3Mu~zFNjuUAUN~ zcKn&+`QXvfb(;q~`Z=RtlD*sB>CV?}-ut>=9ltv_-XtWYMH_Ch>k|xxRR^B!k=(z{jL-4sR=ZwA)}{WoJf1OefJ-o+W6swdujp=+QzTMJN3h^UxT1)d})P zo|-^ol;9qbwCdHfhlUeT&f%#EG`Jtbe6-c#BPY_1_VL!Q|D~bf1oc&(nm}W;sIK8e z+R@G*^}zo$G@PK_$x{<(aBr8{CD-9Z+Jw4sbM5l1q2YvkY65!na9zWRw4>jB)t~<2 z&~So&Fg;3%6KIT{x@$O*c8msB{d;LRL4Ph!O`tJGoUY+S+Js{Ck%klQsfnS%SUd8{ zPwtR zTl04HS5Cw{Iy^Oj#+d2%KGBJ^WBsAtbtYI3$Ws$&w4Rz3OV@BB?N~?UDB%R_8hL60 z4OU+7{jqr3=S13s(khJgpcC$?3DdZVJ`v)EYj}o6T(aXj9`+X>AHNTcP7rT;D#G&W z912dP9p!P)Z~Da07V|7RIW(N0oaLzrG)7H4;RO9)dXy3;&=@^+*Ki{37(c%025C4!e=bi=py8`KC(L&WW^RmXW#M@@gfRC&*J1 zXtWZX)`KFFCe)2qubgmCO+b$sS-)~8(vEqeTER>(Z%dC-;shFFX4y5INIT}cYRxmj z{8OHqK%?~x%&EJE6KTi1UA@vwFprj}CeZNJofB!t`a`|zOt2o1rzX%CD;9d{z8(~j zbgYVUlyHJ|jXX7h##nhV;`H^Ph@=ViQX9LRa8FH0qpdmny;mpFj_bJNJ-Pon?!B@~ z?F8|rM=5c_@~Y1noJc#$aUWH^@n=b znP5F2PfegPRxG`zb|URqN98Et1nU}kY66Y%B(9G*PNYpJt-`b(Y)|{fsFt3Zfac7a zm#^dC`&xhT+RekC^IO}Ce)i8cFM9hMHcx;0FReDe$Cc|jr$U`2cHjKo%`<-XEuB70 zcqrMS@v3%r<&onFuX|*Zs$V<)A1$@-92$oR4<$P^KGa&%`$kQ4k8Ct<@dNMK{P^Fz zYiJxIJe2Iv@D}AB*=P_y{~vp9Q3^#|9!hp-a1Er4(b+w+Bi?tmS@{1L8ixpSGed

Ht|v;sdJ%mi11LdLxY-5jYq>hvLjx0 zoxN{p93oziZdgG)lrl$zJn{wOZG3k8G~v5s&(9E02~} zCE=lDhej*Gb1HN9$d0^vnbnv>MB9&Vp~4Q0RufNEcNHo;Ni0X_tbH6JJe2H+$>)jg zk{`gTZTt|jj4_1VSk{ueYZJcVvagS^?m=n>$!ahXI zp@Nt+ZfaSzC{%bdUi4@$lLkcl%eXw0>?yC#wcv|;WD_s>Mtcd3k-HE_3PoHVN_J?B z66_l8kxjf&{x2IEMjR;=ad{}&p)qRWDc9j1*=SIYX)kddMvR*HvOZ_v6)M6*$qo&A9$FO&?vc%PFn`GMI7E0T*`Yz7ORGY| zJ+dRO-f8vf5W&nTYhT!*!Pr5oLPMd#lLYg*Y#)aR4<$QdYAuSVeO<#nvbhdsoV0|v zrbC2>k{ufD8kkde4fn_<-k4vjzdA&CDA}RW%7V2)??v4s8x7{6w1l{hLxhKt9U9E7 zXjPPkdt?(Y^H5qsXdEIuldp!DXfL7B zE_mUp+kcKZ#rjsyyZ_}!m;ch1Q?qYzba}Tgz2x1SAAaC9-HxyXhq&FJ{`%%u-}uH2 z#9gnxZu7n$eOtFLx#SmG3g6Q0l>j<^$De%h$rG-*&k4jOzwyN-d?RRzi`lsJ+^J~v}SzbpA&EInT1#kbU&EISzxV9R^2!$!&~T3vPx$Hk%tQc<_|fOJyg7>8{h@nY zdh(>J+xvV&qt4x@e&6FaAN`UK^;A9S#vk8&{GlJ{_9Gtt<7+NNazbP|ZYkSb`hc(O zxd`#!E)5$(Wit{K;PLw1otBdI`#8DKA z?-ezAj|hpDSMG6wH*Na6ON}0Z`+sJ_LlM(6p5ERVDG7O;Sl=<)BiysT^E0kPG3}>H z9w*kfdG<6sy&h_PH)oGncaJyEGoH@<+%`ftd)>LdN4Up{_ub*cn}>c`drRoNgoj#p z;O`OcapEWc`a_$4{~xOIaKb~aZxZZj_?55w>02njrnx+3&)A#a2x8i+R}1aj2@l0J zsjrMG7)rFkqt*`E`=>2l-mdBIi8kBobc7Y*9w*lKE*ss$E+S^ncyscCHF(>pzxCOO z^_@s*gv6OP=%Kv*kH9UX$Scnu>R5l1vBkTWSF475oQS#*{Ynqq;tvfcJk;Bt`oVR) z8qo)M>>ekmSL(+O6CR59X8N0~o>vQ3K6^e9?`pSDu6$}gc(a>eO4iB}y z$-GB+pRvAo*Ft$8GpEWuPONX#?P)mSp`uRzPSKY%#nwLBduc7M^{uUDlUKL@xBtB$ zJkiqS}LwSzOSMDAs*01>PUAYq;%4_AUv3~us#kGE=ve~Q+ zReKH-9%}tor>AP6eeh*UPW&QI&``U3=wE*I=IXm$R^*kZWc{w?c~j*nabo>qrKhT0 z&~ogAhg!c_=|sPd^(&RlLnxIq>)U#LPVTCYB7fAYd4D|Tu6vwdHCgwfPIxHBm8owZ zLd&tI*RSJndAP?3@=a}Jz78iml-Grspzi8!1bxY`-skmweNM0Rj~?{8ZqEds>)-Pm z-2-vu$6v6n=<7QZXvpIP{mMQ6-|GquCp;9nu9)UjxyK25qQ_kSUkeQh8Z6HZds=_fsX06X+?XPPF*>i#dY`59Q?)VdLKz2P=YHIQJ`W zD6ZV&@=#v>J@!Q!UK<$IuKLLD^>{s|2rI%pPSEFHbLp!;MXEd${ru;A`6~+o&pSTz z#_oamKmXPZYpUv6LaO9(f)xJL_CaMSMCIQkGb;nfQASU<+(m<(C@0xpchqNa$)Vm33}AJ?s{Av z%G>6gDsRt(Qg7hxeRL0!2M=+*s|$2Es~(B|)c@ShdA+rB=qdYm8^)T7R+q7PTg zVWd_YWJFb6SczsV#~v4Dqh8y!XTm*BptsjP7BrmjP=3dI)^Lv#T%TI-VZuW(!m0hw zgy)s#4@BLUcwCINY7?H?S;IX}Fkh)#trH%~Q#fn5#|iY*uN)>k)ZUdZ!BK)w-2B!r z+^f$ApLF$4Y;L+ZY@V3x%|#nE6CR3t{kQn*pnL4AhR1u`YkzX{vB&+xuIF^5C;p}G zrn(ciy!NLym%QR16th<+Jk&F<`svLlKY7n2)>OIY;_aar)#Opr#rQJhay6S0RGpZ@3S;IX}@Z9J*-yZZzEYw{m z=1@y3!81fdm*e;S#E-0Tz5Pr7&6+Cu{5nRU$kTsZuYo5qSg8uQ!7vHgXZs3H6>Lc9E@q~Xw-~SUDx>`nqyFC1sJzo0!&;E>0PmT4;JuX5$ zKBe~j*OBqIG4bYG9ni?QGL+}Stl@dmN41-e)+^7L zl9_YY3CiY*&-g^vtLe%WmxrSKFS_V|76kpE>L~q+LeXv%)0(D*o`H6tQtN&Ds2LDb z-Ca{fKd9PH5BJDx?$ocGwo()BaiZyOF1j3Mn+ZJHAws-YoqK=J zAGG(beAP%#5~MI=N|pJ3iH9n4w`;h^3Gz^TTT+25cVZ5eCA$&}gqIqlfqH|(CFmX} zs4?n^R*hyvs#G3xsK>7T*i3lsLqj#(uWu&Y<3t~?M(a9Ecqr=h)L#uOYP&p)2I}El z`>=)+eN-#^k~yw6MvYMXt~}h=NKX>zW#5&|Tpk|ETXTk|1o`$kUoq#NK3`|&tLfNJ zdc%EAe(0%ZcBCv2eDD6d-x#}T_%8j|{qpNN@#Od2_vA@8hTSz<=-8d$9w&b9`um>z z?DxIC)14UqEXSS_zDv*d;t!?@nPX3{6X@|pd+1ri2@m!7Z@q7O65qaPE@BC8IljZ~ z?%%$t)z1HKo`-Jkzh3$8{P8!R-21a^C*VXV?LYB--*ob{cePU%2R)@~C5TrZC)!<+ zma540NRLwGgonEIcijKvSzq@1c^v~=j%QEC`-q3%|9}QpuIu!HPHzV<+XCoEB81-i+c3WMGHPmc&NSFzUD4_Hnnr{{r1tG=~o{7{IETym1xFt>>ejx^Xik6FaJ{8=`^s`Q(If}Ht02f z)^Lv#v;y^GhY1gLxP5pX{h~j(;^douH0rC@=~=@)PQ2ieSDf5@WmVgqm_uFBzQ|S) zULKy)^pEPt=2W@IiL%Tax*R*{AQ`pUKb(3hwt zdhMAt+~Wj&m+JIk!bABeF%w5eSyB&r+IB5xFWH%Jj}!0sitSp*4ig@VoZcJH8#<4i zPS6JHe%IsjP(GLFsahg!+~2*TeG@6#Gj*3;`1B>7>k(Fjdz_%HT>o!BRnOp|ye_O7 z3s>&F3|Fprz2>h(Gv@xv3Cc#-beNb!Wsd9XBLME_c(EM#2XmZ%+d)D#qY|6IaRYK<3(>; z8w{-V)E1YA;`-{f0lBE2jNDcJkn8XNw%9>Cr^-D}MA_JG+$Ff>m>T!J&-m@NhCk_< zKhtg6%E!OWi1j+$L(LZvt=5QD<1BG>6rpH?^>vV5#Y@ds3J+h0dz_$7*Vo~Mhw?le z7v29e=M}B?J$Ebe&5&s4x(+9fj_4(VHemF-B0QAm$V|+hjF)~)DLhPgs43qJS&sb; zr~Z~!djij>Mw#cjJ(0L_d7R+gFW%3B&hQ#>M0hB#W1U!nn{(F*pG)j(D0e;7;kxS{ zCwykGYP6I^s#L>0R9V|Q!FMzDM4Ing>M1)rv-AGks?s!gzfSMI@$G9pGv^!CditK> zNflp9)*c4FYMlEdEJBG+`}%sS<}%N6=6jm8hSv3Y%+8s>CcqsiMY+p#4u81DXjB#W&oi>sV9e9=;~8yt=SdIl=et z)!XG&^xAH{jEAC!Q(xJMHC5jCL8veBzH-)Zj}xR&z0zS~4wWr!CcH&CK_1q1*9i~h zJ@~4zkXK%RXk9Av3#+?M(3;iHuNuvW_iI(JJQVF*qeLfKiuhZOxdZ%__j}c4G19kL zH-Bx^f5y{azP^#&e;fbsuBCgD_`W;+xy96iFM-U2hvFS~z4hJ0u7rD>;JtLcGaj)^ z<8e>>!prrn;Fr(c>2lp2{+!J>-uD}xa^|@~gIamK?yAdm$Mh+;|L2$ME;nPK=J2zI zdz|>L&3CVQGvO(D?0Y|d)i|6g_c-y9dtS7rcGXz84kz|QRqH4Z_47~vyvyg+Rz-wj zc$^@nL-#CUg78q6zv7kmot{lZ)a^Rl;{>@--??+bLy_y#{lq0imSajv9!gO0_IXcv zc7l7Hp!U>P?u3W(+A}V?|7SUNj}wo2_`@$(9v&tL*Au$KgonE1l5e@ZzH|5SZ@u^By1V@PcYNjLx=-zOx@#<bC*hVE?L>kA)v zx$cpX+WH=Vdz>Iu^*w!0$?IPI%W)=o7sMAV+nz-eb%f?s0;$QBEHwJQU?$*DKb7IF(9J|K} zY^{(ZZ2PxS`-DOHr~+6VwIfbhU;E4~52hC*3Y2MoxL0@LV^b z)kKfWL-D)%%6&o}CvI_cs60F_59MRmzJ^MQHzH(v$#!B1ZaH?36WH2EI%}LI6w2S) zoC)`Myu5Ys;fElB=>&lm zKYueZhkDRv?=-7Uv}g3I#|d`n)f!HCDEeHTq}7u%{#lM`1Kg{m9rSkHo=N`yl)VeI zeo0y0d4f6^Ga9)FN>EHBC?TTQtBvZe7>)G#9XTSUO@vOzaU%t0~ z_0)aW-c`FcHupZ0#!9%y3C0oD^0qySD;KMvc(?|#0)KrCCzv&}w!YQyRCy@o)~u~> z3GTYs#}J-3o%MYTErorq%f6y+QxTE%cB)ECJ8Rl_$P+8#*j|RCnEHR_(shC>Gb^yG z#=znvHkBgdI_s%~^8C#j?r{PQ)^fKRPIxGR}+P+qfZ&dL0#*A%788anZMOe50)PCd#A`Uh+F zSEtHDdGDGvC{gxDMO<$>>-(` zj}trvnd+m(&tE+EQCxGVcF*p8Fo4k#<#B@NCU@PgJk;F(hd@u2mkET%kGTw;aL-J< zac8`8f_!LHquew;rUGT<9_mITs>d`F?s0;<;Cf_m!b5RCrIBdX;9g0s+UvjH5shof zOt{AhV$#UB5(_zZ4N{^$==4f7V{TVYkf(aw^|(Bg_kvl2^%~7TSjTzs564`DC#jm% z%mmN8<>6`lW54Xuo_g4oaE}vy!e_+Z{%sWR0%Tks3T>S;G867`f@kmbnH-)ELOt_spU_L!Q@Co7 zu)fPe_2C51-f#OSLGKeDif8XX_SY-IJv^2FvtNihxL&FzqOH(;>vvcUj-<``U>!%H zyp7HInA_F8S7L54$;2~#l@+T1(qKJ7dCKsVuE*t}Sk0=-%8AQ8s=lg0$m0ZkbJMO` z@*-6tJQQnsb-VKPvUaDI;i=uvxf5upRqhiW%Ey?MSjdN`7Y&_2YI#CWabjl1-k^Ah2qX!$yUDAI!f z8lGO-u0ma}tel|VOsQ(|^Ea3794b>AVdLL9=T0z!XSpRa6LY96^&WnahL;IrN!HqR zQso5WSlvpzK0K6<+L;T=$~{gnqN*M56CSF(8noO~R=JbZcg@Bg9qrgm745|dj}y#K zneA`q?H-qh;&(j{N(EBo9w)drub+51;i33lPpP&V@;DJYtKym5KH;Iz&@-S;EbZU+ zzsQF?PO$e&&j33y{+S66#f~(^v=Uw8(pjZ#4_xfoz3w@wCo4fe*R!*((c+JMcw8Rp z<_~#$n<4*3);UD`Ywwbo#|iAZ&he-|{?ZG7`|RUi`+Gg!s|m&B1SJ1|+Y&u459O(i z4D^3{|KJ|5odDhL8abPovvRR{HlWl-SP|}Vf|K7V$8D;d@KBU2DVvCe(p|rv+)~0< z-}={9o6XzHb*k{Ftk!RzHDdi*TDLPNvxdjZ*V+0vPDQj7@wc3=-^*+sPMuY5*Kc)- z2%r(}ae@=GRnif8ATu$C8s8k1#v)?<+9IB(ylQP%>z5uy1kh47d5pOEri-~gRt+cS zP~(f08;vPd`fB8*6pjS-|Fn_XQnG$cvJvZ77&jVDc&MK_f91A+w7e{*?r~!M3gbq@ z2@mD%ZO(^>;%h4X+oCPrePZ?`v3^r=lPV`X)cS?QD+%ut#I)a|(lfp+*y5#k_3!hR z8X`Q@rbmqen|svyrPvm)_m#PH-Q&di4cJYpobXU{J5Cke6V86%#QF``jfN9*sJ;H- zHMM?ovc>B)n`xr$y2pw2Ym%E(IpLw^@lln5hL5$htNtbJkt)^fHdXRCLCf!7moHN# z!b8z-`uD^|ETI(RReHuZy;~@rQe{k;uGr(1o+PLn_ypzZ$j?|pZn;i>XawEQRii;AEIm2<`tX)qGi`G{5$ z?-DU4zV>h3(Nn^R`qRi9 zBHGz@zUy&$DB6NjxYl4#m3y3s`oENqo+>XB#(A}jxeQm8(LYqWPDEKntIY7~Q6fAP zC9Rgf5(|WvI~uQi{txx?@p@W`W<;;m9v>&j-vhtxhv(AW5Ob&>JNwryA_U>`8)tQ>V%a59PJllQaHVPTk`KJy_+oPk5;PR>I8tvA0EE z;|iyKcfD5P1lRMrpL<+$sO-UWKD_-fd(nvMG0lW~oM7&&-n>tEC}L83+Y;%?c+pe; z-zPkjk3=)!-&c#2#FMF~Jh_cR<$I~_aROWW)@F^%ghHXs__b~A?(uj-&)(-8Lh+qA z#pR*?%J=^0*-QSkdaKbrPB6|-y>``b!b8!~pYqmu`{+84J6m66V&%{&*Jaf{ONTK6dpL?9(Y1H1>o^g37o@Gtf z^Cgt#IfKsteKxSBsu?ju_L+r7IG+>k6LTo`=vcd2f+JPwae}9K(w;Rgeb1*oJ&iZW zdCr(4Uox@&VV;%XSy^4@9+!vW_e~8psnC$e37#d^ZP!=zeGeStidF$L7ihT03Exe( zPk1O|(u(PpkjDvZ{eCr}P@9vW2NvgY>ReZkmy`eMvshWzVjYU!$qE_kUfBC94Xgnx z6uT5e^GrYQ!ZRn!DJ#XSDiNfcH%p|hNlcEv@W6l$}Yv6hvm zom~~Itto|dK0Jp`^c@y$4RlS_s^Nr(@;r^e{Xg;5P_2wOfgUTRwT1`}wO>|VKCC$^ z-u<$2j}v{>x6HW{9*W=V(shp$=&5ezvU0*hd7IuRSaW1WoDyXZ0Bh@0=`M^6-geo) zz{(||u2+Lju!DeA%t@mqZ?1C>#jXL?I#;5lh`*(MSNIcG5BX5MUg{Ax{*C^jUdwtg ztK-D$WjGV=af0<=_64k|8d$9Msct=#m-MW`ZVh%j5Er|S*v*0M{bnXS6#KA5?-TBE zg3{g8c@vBJP(C~qb)yzDr^-Flxyr}2XTm*B(B4!x`-F$`@pvT`^5N}=oU>O-rK=HR zC7Lm}L?9Mdz@fad)I`AA|}lr=2W@I3GC|;3PntHyK;}m zi+w#pp@>O+bDIx&JYH=5el?*`zWP2B?(ulbwe5y3r~W2_@85>5YtTJTFo(Zu!b1_0 z>SoS|dz`?&9-&agq`KK^$m8*1>-Vb(g+fDhvnAy5c(L{S)kKEMoe?v^eU$c0c)Z-* zO{@A~3w6$Yt=4O}kJf4r_XepKp*z&?Kjd-3^$4lIxMLCFq0msd_0UT&LCE6-wtiRq z{C7(z)aD*%2`&h=438IEzem_TLZQ%@TKl9SkH?Fx-?tj_cqqS5oC)_hvA-kU2@h57 zZ*OAlTaE4Oak_WnJPysyc-u`iJEw|sP&8xVgcHquc;~MsJYLRr(ad6B!#z%L&WmO> zbE=&1P@MTv&z3yxoR*|n-+n&a;{@k9sTAf^IpLu=^F?Ji6P%W$`f!>vs#G^K;T|VA zuSg|56RytrF)AOYXTm*Ba579?A5M6vO{$hqT284c-9b=;nk`YY>hp7|ysS9GN%v>2 zJrnM6qMsR6-a$Iyq4>Q{m3y2(PxrXnR4FbGMgH^zVI>xNt$V0{J#%pFm1su1^(zf0 zsE>MP>2Y}|YEyNyYV=gOhgPE6^q5v+lPV`@q0>F*z~+2-D0uZ#IoIp?G$~IMs%R~7Ubte4zjz4qY zu1_(|gnOLu`}TdpLlKj9k!%ThoWR!aR}%^~pGcg{a_SzB*G~&x!!PtGKW#S7;*E32 zd3Q-WZaUFI^Vep5=5YeOi3s2l;h~60d5Xvb2@QFi@H~y^1MI1CLN*#xoiDB-kH?Fx z-?tj_cqlY9=0|c|Lmnrv_4`&s9uI|vX3JYb9w&SU{x(%2JQTb7`Ty&4pCJ@;2F+f4 zUh2JhPL+F{;A)^U+$TH~F{w7Uggj1Q>-Vb(g+illyYBILv9Cuc6ftS_eVZzIJYH=5 zel?*`k=kmF-aQ^~=v{}<${#Ulg>IWFc|2Zh{XP?nmh$jSpRaV&`dAU*Tf^Iy$kTql z@rx&(y?sfyiAkp%?Q3|vR}+fM2~x;6jJK)sxIC1nc21S2o#%<1FG9Q?(@eO>37%ha zw#n70@=!c4<*UA1f@jl;i>J;?72}FZWKNZPoQT!FsGEJlL$QLTnw<&OxzsYyQ;T86 ztZpUlal%tOYg{IjTeRyscaO(g=40W?>G>cO-;1XXJcV91U3n;Pp)0YFDo-yZdh0)mw0r(mq8W2pIYHgL=!I3zJuVM* zy_`Eii%|;aRC!z;igv70p9%j$g@4(D)M}106Yg<>`R-j49*USWN7-t~;{>*TznV}e zFZC^<*6#6Q>-Vb(g+fE4>z0tmppLn7@pk-$LK4n2e;&>mUC0baqzhj%?0{$K|2; zy}rkBj}zF}BNU35boa7Nl{_9Vwtl~wP$)EX_p&AA@p!TI`_+U(p;7m9_jtV6*CP}v z@=@L6xX0rSz3UJf8Hh-Vb(g+fDpWlPB8@nY-us|kgQd{jNkJsxl9U58K~BqsHh zZK~w)c(L{S)r3N!p}w*uoLNp3?~r#nVXLx6K-?zA3%2b{Dzj z`Bhz3?s0;3LzVQZu`tu;+*;1ZWyV4ZHCy60eCtf6h2}5L-<8J+&tHTkctt4fp4ycF z>Sq-zl*hYYRvwp!V*Xa&*SaTG`{K^jW7Iy@KB^sb<R-zd(!YNfw(9`N?86KC1VqDogFX^dr595`d+;~j; zsd9p`a?)t=^Ec0%pkH?Fx->)VV3JuNrw}d<%FSdTanouY-H0$3I z@_4-1`u%D`q0rE*e@n>Y@nY-us|kgQd{p-a?(uj-?>dC;CWuKR#x_;*c)Zy9{c1v? z(9l(4OUUE#V(a&-357yKv&=0akH?Fx->)Vz)ZSMrIW4sB^J(*4kC(kZT-nz7?hsl| znK!f6h3BT5zT}KmENt#~>aoN-&u>#DkH?Fx->)VV3Jvx7Eg_G`i>=?UCKL*d?DNTRu3CCLUhL};3dJ2b zcS+lk!95-?_cz>$Z3%yC+)oo=BvQF$E|_1r#|hp_xog5h5tGVot09jQ*!ulyLZN&_ z-4ZHMj~83NUri_!8q8p~rRyG#7rQ3>R0Tho0HQ8k_c+0O8h1^2C}L8%%{h0E6WG@y z6pENsZd(m`JYH=5el?*`Xw;?a9*-BhCRioA-~Ik{)a|p+KJ9+*>^3V6(wkE?dy?R} z=v@;YikRwDxyK3Y>k$gY=?;7mY}3lISxwhyq4|qbJo;Bpn}=G{H*0w_kS~>P^Wh#RXbYkv^8RnraKc0J?jqkd zT{RXF?s0;z>+t=dcCH0urIF^9^Yyd_2Cak#Tvb@+-#+sdA4KUJA2@6CTQIb|t!odz|2#NOwDV zR8dw=cqnggt41^8+fHgfeEW*;XR27{`>teZoVPy>_H3%Y<(*sh+(IXASo_!MB9e#`Xyh#g~ZGLRVs; ztazJLV+n7WYW%ofeK-+cJNoQwyDfhH;(K=*6KU;yy;uDsOFcpd;Wgz%d_~PP1~k{8 zhbqU!g;aTZDJ!MwdO3H3x>5cz7nfV2hw|&nOn6OEy1J@)TbK#=I6=+o`nXScsO#n2 z3BJKqkD?xzhw}C|r)oZ>HBXTwrg|1Wdy-&och`i6A|}nR=Ty1J3GC|;3Pnuy?A1LU zFZT5ag(9Z9N4dx2#l9Y)P{dSU)!gIpVqcF?DBgYN3%J|spnE)CpE>s$T%sPA3&!&} zZQ*#x6Bdqk`uB03EnVapeaAzd@OSJp%V<}FST%TKoOO?rM-lJ6#(u%0J&nAqku#YH z6{Slk&7v+7InyU4x`Q|#^3LKi;h~()djlg{UY3je;_b2T9Ec~I$3uQ?*N9fY%LPw< z6)NBDIv(QuVEeH?Ap(r-R2s=)GaqSRmX(3Pqsz{9oZ@)yt`Jjj#OU_d5TA z@BG<~-kPdrEUmR?yiS~)ymu?B_WjI_h7%sj%W$ia<(~1P_u?;k^NxlH59KwxYAob~ zlT+e^*yG`g?)hi!DR7i%p740NtlZTUJRt{O|px^JhLQ`pug2W<(9DtUMH_Z~oSA7}3g!zvbdXAMma-m3to>M?HVT z*S_ma{U(C;e;eT*Cn$BEnQdE%6CNr`I{IV8E)DlML8!MJX;P*zTOC~t2o(TuqzIzfr3|L+qX%3Eb8mf*OmowVM`m#mKM3pfAcO!d59 zR_<})TMzF!tJ{?mbErQ*Q#-z#s`St&G!A-9kptz!JxT%Zz59O_A)`-5wS_&h; z-Oj)Gp3zh1ajY?mQZ;*$pf}h3+zAg=j?_(OxtPa{KR;8d$X}dvd)0V#a*_mf^9^6i z$+}k&9*X+^&<9jRD}mOo!jq@>#vCP9nl5X2={mtkRHw>`IaHQ(uZdPp{4E#k8|o)` zwj8npiMQv-Ei;@rhsjd4KoBZ+i?lghqx;FHgQ({W#3hdt>?cx8Jvrl_<-!RM#f(fb z&4hcLU_V)`M_WD`x?H%2y>PKoebwB@HJo5C9BkJQ}c%MwE+O(2hx@gGb1bV!Iw$*SC`QZJ& z>uWec8S<{*R>M=}p{N_)2;36xq0V_X_4=uDg7(IHs;kBl^|)MksytNL2Yczd#|c`# zdT_)p4JSO5_x~Pt5#gf&yE>G1k14{6aE}x0>QK4$uuDaFs3-ilPdIz}gKo*P3ZV5` z_c+1oa$SQ?cqrDL>sCT2_2=A?5@TXL`jB&ZoXFiUmq#BbJd}^Fb6I(M*-@JiQf4@Leqqi8QH_fWbTsXeCsR5?M-)>i|M%R_k!oi%7zdg4L5ViztW4(%$|rY^Tc zMxS`fbv!U8#$Jr$fsrqEa$F|d!wAP7ZjFhGX-<`EIKkM(9`1TfR9qg4{OR{u!#z$g z+QnYA%lUA^Lop`Ct~VnV&3#mggz6{Pjk%9XeVZzIoIp=8?Gqk~GE_`6;T|U_1=asP z;i0G-cKWaNF|g&rJ=8zD`&H+6ohm12W9$ImYIr_86xVikeQyc(Fn?gD_w`fd1alO2 zfNwQCRUV4p>z3#qCzwUCPrTMpTpkKqPe11xbPxGpr?+yhm}bIL~KYq|d3k@ec6sda8 zdn&>`Ar`A4lRZ19lZ++iC?`cPS zKUMNL(XViKp3JFgd0{S^ad{}NDi?NFoaooYJKwL+ znB!_!&Jl{=Rq9)f^dy1aCqMoJb~HqIDDwCCSKgx_+|#d|cXCoh)TUzEPn8qY&7)s+ z-$KK4=%Hu}*~U_(t&**01;xzrsn7ec9xr42CRGb{?jHJw2zuJhcLtpbmkAHWsGam+ zx(3&C^(aPa^*hEAwa^~Eh30R$VEj;-^lR-XU5HISI^iBC813pBbahV^B{HR|r%5@N z#|d(-k!S?&|B2ESF^9@=EP@8NTo7-Z_Qds0XUN2J>buUl6O5>JEAg`OP+sbDs=O4r z;;0vSOpycS!#z&)t6ka8o$yfnt}IBpNzDXK;f2)gzq8<)QlZ@$x9z zQ{^5?R3o*=wB}=zDkrELjrse;94dR-OuX?8=jZH}WsLf@k3O8U_Z9mazw9&4*(JEW z=lt1MJmUOce%a4;&o_L|BicH5>|6Q%8)xV2+ujn-`T2*Rf6en_w?Gh~0l`l8E#V#~ z(7x^4FYWQ_W#xp2dhQ=S;`|whO2hNvX@_{uYpQ&>$BB2m`0SkB>)U)dF^78O&aSYN zlk_<8q8FZRi6vTl5*}(l=k9R=J>Ctd^Py7oP+sb5yXvWO&+q@iS=)0LJNCRStVA=G z3->tj_y?b#v+H}CDknVDy}tVVoSo%c;*Xy5=+*NBZ+-L{?|y4{j}!N~_hZ&P&G~R* z4)wTg4fdS3r)sOmi6@*rW~YBR;i2yF`H$JDK~9L(?l#JY_W>v$%8fT+wq@m`!Q)rpY;CK-dguKLEY42q7xp9`sZz=ZGE_hmZ)0unC7x_j}!C))&D->p>DeA z(dWDmvQ3p=0qBp~hwS6ytl=IfyoK%)9*R+-E-UvqvESOg#eKwEZoS5J(EEWCl$EZi zb3UB#P(CWngqJ%SyoW;_c+Jj)dz>JDynDB;K_})=x3=$z8?l7aazWo#T#OP*m6!CK zD)%_S?4xd1PIxFEyJii)8U!7C6@T&*9)AAz&%LxuujOUAaE}uw%ileJ_vdP-<51~@ zdz^UvkAKqnm%Qjd7NzSRC$OitAdu-AmkEV>^sj&7`ENg{(#W%}j|aXhq)?>>G8gV~ z;^d_5!#b%nobXUrr%HPrNuhS#=gH&t)&!Qc`RPO)Ku5G6CP?V=_av+%yQvxaO9Vo+Eat}UWl&RJ?u(&sQfZiL4-uB zbC1i3ue{eyJM JQTmHHb?Z4xUM0O6DKD(*_B#Jq9wWqLbJ^4Ylt9E^}T_|<)QKv zduxd;aWNOwm5fnBZ`#lcrutA;dXJLF2}X>&-w`{^qmTlLJ}AONp%Ewdj8rWmqTju( zk23lFuw(x!$wUOu@Yxf;s#&XBgB>cqpGsm_(~{ z-UieTL*53|o@DmDYYk~8+~Wi>)jI*5@KAh-cC!<(i7gj=n^F7N`I@8ln={7Lsrt3w z{hQ~{dR{BZ)-w1Cg7U%F5tP54k0o-mT=*M+9=`g{#Iw&b>_d z!kqR%dKs=nGvbXZm5CF4AGh8E>2Y}|zS^r@x~oP{mDh*ooU=Ogw!%!f#|hW&M2nw4 zu2C76hvGyJwS@>9|3cjV`~&ZC-s_xijB2+sUksggM-PnkkMz*4v;*5?+ShP`5~=rv zdt7s<`<&~&kglBnyhEP5G zSUD5!ae@?1?P>{bxo~0*l_SQi;l0)g%1|wTpYTvV63qn9!FX;J^N%;3_2*>mdez?q z<@s5+2eVM;JmKKJ91qW0xi81&^n%UE&=I3icSbX=nRw$FPk5$OZ3vz? zD-^2?Ja?Lio+|h7?3<_C*H4ubaYDi+jZLaN6z8*S%BmByhm#i~Ug}9HYysClR&Cp;AOpZz9tvRurbwl=i(BJW*99u%!T^FeFp ziS6Y)r2;kRX?KF2#xuoj&Ykd3^k$wlZV75iaZ!Ux6?ZGDr#V&bae@}3dg{ay+;ZW> z9LmcrRhVC;#|heWUFS}CsCndb4KFKieLgB>_{-y!6RfH7)N@<99+!vm(RJ4Fp2L$< zjlteGXTm*B@YJ?Wl@lI{XTEhG?Du@5rxJ?i$mG^*wx?=|w8iy9EsmV?tQx{gea?q_ zoS>wow@-K|A6I6=(@xHns!cuyHn&|TC~4(y*6_GIl=rkwEWyS7hvw%#BlnrXtl=If zHZx??$oYqd;+Y0dDyFvEsO7>vPI&9-saiFh@K9bNof!YjrR&6gOZ2!rl(*1X!{38! zqx6~X+t`<}cXf785}cm2DXS(H`%4s;hhk5WexFn29w)pP>=Pb}-D0(ddz|o5Y1LTB z2j>@ZEu=MYGND%WKk)3+9`UK)R-N3!X`KqiIh>+-XGTwoyGDzjzvY5>8Pm}~kI@?Y zQLlUbBkI*xkC$@>x%NVAG(w_jxW|cp65=@hWCZU2nF$Zo-~Bnc^gMAPAD&*%N5ot0 z7V&sV71t)^qkazO>P}E1Dz|Mu6qkpho>b~H;c4geOQmW*AMSCYpQBlpt`i<=zg@Y< z3G`I|b3UB#P~N6zf)gFNZcqoD=*U$^^)a>Gfz7SNiJNZv>_=_Zgcr4T^$*UnWFCix zr*=-2dz|1bOXhUY`-F$$EXz%*8p_kCOfM%oDqin5vxa+|;6z8|X`k>=K4Q#-w^0aY zm#Po7>6!5U;RGqqh07fSquU6Qox3oGK?gR6oJI zJ&|79?!cA{_c(#QS;6Y5x=bh(XSZwpYfhDWJYH{eTxJ)P%XIV18+vdYP9xwK0 zWat`~35B{|kMelSI&T@8X8<0`M~oJ5{fp~|c5_n-%>2kLdfErlgD(LEA&(Q}k2&48 ztUN9c6?w8<7L$f{aya3=Inv{)65*lHn68|YhCEJCZgoHRxIC0!wR?J24S(y`-_G^- zha(5^@BC)56P!{)Z(B=usR$2+hH5s#Iw6k}#Lxe)HAHwQN<_c+*q8Qi``_HIoQU51 zxYX#_Wx_*w8ykU#26q#^4Yl@)9jDM9542&ZZ9cf8Q>b`8(_(Bi_aFJYl0>Rz56^&t zprz9?R}De^Tu!|uaQRGGrFI1F|A|#gd7NN zkiBzjxufs((8|XN)_3Z2Kb-JTtm$k{DQL-yb!W9|Rx^}#)fYx%hk^Ak zoufdBsMP12yT=Ju<#h7GN;I8VcUDSRiPMP=Ug|5+jJXD#K%+j_z~k~zq_941fpv17 z8bJBzoB>vy>YTgB2}-&?*T4x6#VU}_QJ8b?9#(!-q8`&sxW@_Bid38XgomPCsV#J3 z32wRYx}`ppc5e%_hI^c#N7ZHJgomO(s%~Zt?+4@~>p6ScOn8rSf^w_dl@lI{9Ukgw zvxa+|pk~$b_X!W>J$NR(rWhG?_KLTKON6y*Cm4xz?#n(ghtgLD$6e|YTs-B}c``h+ zRJ>lZvxa+|U}ao++9y1ek7FybFqZfTKq!rzXlu-0iDt~Bj}z$CBelmhhq_Knbb?aI zYe}XncBJU~F^AGOZS1K*&pGRJy6+BKZ;P_gsO=AuJL z`^duM1kYVHTb@(pad{|y*UWiK$m2wRGTfdJZ)X`Emxto_X-0<7LRq=T2~K>kXMIk1 zD0XJn8t!r80q=h3`E!5s&YZojsk(HcZQK19`{u8En(oO;(57_Fri)(gPGGB^LV(~Ep-}mqK-1`idputMa>1&BOrMJ?UQSHE_wW74 zXc?^V%1$O$E#=8CKg8GBEQae72%=$YYaV2OQeic{n**>e%?!a+MoX` zuQ+?)xBYOpnZs{tu&2sBPCW3=m!G}z`PDtA6CUb|@A>kx$KLjXque4z{JUIy!FRs$ z>`DLPyN5?#C5d|jm3oGUI5~OE*&WOGbmF!LzV_^CpMLB%_Y5`R9w&bF!*86u?Ne^g zR4t*jTzGoF;cH)Z_S(O7M-S!sn^WZ;CqC=}FFX7FH-CR>42);5S?(T+-|Kw1$BC1Z zm$lM;$&NqNAk7vDwcdMGdHRimeBF83c>TmJP@MW0t+`PRda@06~`<)P-jNtWY(%f%ah=N0Qn z4e^tI664APpZ>D>H1?Hnj}w38dw=xoC4XAIiR8WWd)|Jd)n=5ax1N@s^>1z^PCWBj z7i(>%vlWC{v+7-Zw-};S89`c#xwbqC^RQCTh zRV`)9#WWi9u`A;BHXS)oK4wqGOaG`-<%EawmOpFE?dK=f@!Z?nOw67nh-tdwEXs!y z9?DzHtl=IfX!*J(?h_uWY>6#poRQMXf2Hz+$A<8We5m-#za=JrpC~gI@VR3W9h= zP#=HoTiabrzv}i>xufHa(7F7d?w`tG|( zm51_D*lMU0onY4Y@1FN(I~pQ96!d)`+P>mb&VA$|AGiL(e_L~&F=e_U=khoaW%yrb zjRwwyhhpyYsZY1nz9n?pOuvoo{eG>b*INc7>RVs-p9>9d4P4>A{T2VShhom4ddggo zD)%_SHF0Vs1DgpC#q}!NSPQ-c5_evTi}{>Vb-i}w1Z8#Ct=&U;n;u!{DO)bQ+|l^8 zuXyKQpw69OmU+K_{U=3z%&j^@d2Oz#YDQe0a|B3&9{lk4uQWU^54GP)yr!5le8#_v z(ZJinoGSM?!M)F~zOEWeobXWBt8*vFhf+AF%H#4-^Jq7ih0-PGDn;gVJaJ((AWwCV za*q?n^L$Yi=5A%B+Vc=dLeZE@DiB`_c%ccbtT#-Jd~HnOt{C1lars=xpF$;p`caLvj#KQ z{>{5qA6{05^F32mHA5KmQYp14HXVl_i^!}i-s z5dSn!9GRI34~2$i1|x9)PdpJ;T#P)L0qzs-ae`SvUL{)eODILEr0$`JsV-gjI6?fH zeMAOaLveX1ubT+l{$1!%?s0+=&=|ZDKojAi$~x~F>@JP3$R7{vzGlBGqXccN-euvT z*h|Z9*&Ykd3?7mh#bz%uF-X&8GsT=lft3I+sQYA)ed1m5` zXY8Wg=A5z;L5oo+_U^KCb|PBJ;td{^BI|_gGF7VfYfv61&|t^uq|vey`4HiuyiNCf zw-oWWTu{&K;Uq40l(HL4sZ#zTZ2UWyl@shbyW7d5c2cFdJe0S$t%ma91bXZSygKI| z%G>d*LHkjy(XP}=Xm3jGOt{Ah+OgVOCzjxr3vUh7AUmY5U%F1v2id7x=UnOaP+qfh zKD_6!w^?n;d)iF6#|idTs~ztX9*X_i>IE~w&SAAa_8_ZOda2KZdz^^3#HzA#bqI}c zp1-YzTA~xAwr+_YmxuDyZZ%YcPOvk&?ol3>hw?It)4~L_;*Vv6xw_XZPgf9 z?6OcO&Mx8mXN2O65x#P^C0w1eEBO8up*Z=1FPlxoLOwj_oZ7+Hp$O%9n)BfvCpc+? z?>Ys1-(K4==DknHujPC}n z?P>|7c}($NeX#`gxr!UjmIm|jJcmXK`HRvxVo$qmxuB;J!`nf3F<~E+$TJgk1;E; zkPn_l@C2Ro@+3sH$t+6tN;D&8OY%5@t^8e0C=?p9w}d<%FSh1dR}%__hU_gNkH?Fx zS=7~pLivnyODL4b%NumlyD|ft=b|184bA7b8uB>78+4m@Wfs+-h&fcgX|rl{g6AdL z(MU>E|J(`7UWsPJ-L^bVV5?@YCKL({*;_&$j~81tdo`g@Xvp3Y@_4-1s@bavg+fF2 zmXOEe-Q1rKY<`w8hsx(=tHwfou$H2ImR@VzC#arQq8anQ@sAg@)`cA&iLy>oY;R4a?)tu3D@l2={Z&I;e8JgyoIDYi+#dF@urjR zkY>U?yiKJ$A=jP>_c*~@PxZXS2@l1aPMQaGjU|+p3*I(TN_cNcX{W8JZst_E#|hqN zsmsa^;yszoy}?4;bq{IRJ;(J@PK zb05`H5u)Iw!fF` z?~-<632uJV+ll=*Ks_!GRlZBsWR?r}IDuW)$7MpHu6MWX@nYB4L66HrUGF)A6WH}0 zVUNp0@%ug@j}zGSUT2TXL-G4QA&(RLU%~LWJd}T@C0dl)m4C-1@)3JVBDJ=^WMJ{U zMEgsez}9|^S;OP7nroM8c21RhoWNGi zUQH+zG0EN%@_4-1s@bavg+fF2mXOEe4ZW()JuVLw`Pd^==T2a&X1A$wLZQ%*y(Q%F zc(Lm`_qaS1zi)_z89@L3MjID-hRo_4=ML!U`G#o8i>rY=POy&0IS2LAa}gejwL(r` z*b+QF*ZFCz#BiPkp<-?7zDcw^@V8vVifee#5W&?zF-6$;H}WBm6Xc20Fs4*3(olL? zCFR@+LhWC1+~WkR8JxH>Y4m(J;h|Uy;gpq$=&5oKYayJha{W{}!CDAsu}m79RC%aa zH>wC~O|5}-HMJ{hR&Ak0z5d0Tmpo4NQ)nef&?KiBo+dM(ij#u#0RW(|+aL-}|-6RcXO4`Qoj zuuh@hXTm*~3DNrmv_i3BR%^KDG9h}_Z~|MQe6~Cj?zv2e-Y1|HYJV2)p38*jS;Glz zg`(}&W#yjBgy>nr3GWj=8=MLEII%xlVxQ%cUhq+UT=G`JzQsCK?r{RU&iQ3Rq4-_) zoDcVSyx8@1@G_xL{4RT|A&&eSD=T0aT8nU;9JafFyK0ABZ{fj+Cb6gpU ze)IGn{Lq@f8f&bE@3q1a{p&E)xpH@3OZV@_4-1>IGL53WbL3 zEg_G`i>+R8HK9;w$len2c)Zx^1y>Uag@)`cA&7hApHYC@sVki8}3@p%968~@qaQ=j)?bN^^4`>!%C4@JM(^r%koj6^*r zR+nOq%j%hCvTLdqG+3|GeJv}0nuYn(mX%mF)IXeH)mk&aeZoVru2$bouzsrhS5{y3 z^n>R<%HOK7kPnZGwL9I{TrVF^uvVyhs#T*Iu@a}8dnihGbFbD@<(^o5jb{tjOO+F> z<83rHsq#?eGqO&&#|fUW);V{=L$N-nl5SD2f9(wg^RTL~diI#s;LV70&sDlku)<%r zE04=VvD&Y8d`ZLFQtSzcrxC=oX;*8i1y>WP=f<)IjlHQIHJHC66m&xFQDk7++uPO!^@ zwZruZ%fRLu^iXK1Z*Dc@aRNO(Bi$!FlwXNv!uvB<16{A^1=5}g_c+0IrB0O-9?E;# zRzt1biM}FRmafO;q5Nt$Ykb#}zUAzx&wog-sr&!(x17D>AN=jj{pUmeLPPdeLmrP8Tla}q6AFcf>@6XW z$BV7|#H$H~LPPeJkjLZ2)_vmDghHVqdrQdU@rGV?2kCKnsL012p*u(?uyvofO_dW0 zg@)`cA&yg1dmx=nzq)uQflwaZI(sj>eLi9cXtx$f2n+f+^CPeQO&O zxS4RzWkU2m0j*Geg_{ZYTqZ>C6VM99T`+5T+g9QpC%C6&g)xZVd(78d{Mk1=>jrB1 zWwF~2{*|e;Z*OM^{mgs){fno3(Jw(P?n(Q2@b6Vk#7Ty_eF~KX8vps+^o2BkAM51Ah!ZC~RNAEKrO$lDYrp${`MR#*p0vrWzt3sJNroaW4<&nOJaTBX zthh&ZeEB`!GHn_q;cuCyjYiA)Eu*YX+>`e4;BU3=6CNsUG}<_F3*$-4#EE;-rmXxM zJbT0(N(35h964n?K_f%qQK;j=_tx(d9x82O`afR&;L~Tl^t5ZZC+*`Q_tsw~+*1>j z!mEGclTN?qqdvB4IFa`8kl&a=qb59*+YqgsPRF==;&G+jzKeX1^R`F$apMX79^s+V zMx)jD>9~HJxF_x7!N2*lPk5-b(P-`VR97|kqAC)@07pO{05K;xhO@z7PFH z^jF^Y>yJdiiL|4v==Uf6`cV@e%573L>f;tPC?Ca@cGNljew~+4gByYxRH(Gk811SP z?nzs1SNG?8M6|>Rl{OlqwV#p?_oN*?ie4P~*dzR@LE31vIms#iL&H63$9Tp64~;#7 zR47#1X#8K#`LNSB{?EsD4fmvdJp9`4{>}4eJ@4U7<1*o%nxI|X_GSO;=@Z}obGwEU zX%p)H=e_K@MooAqw@KBw8gz|0F2x(yDB3`j)gD2cQmC}i7}vqB;hwbPT1#6FjXi=^ zuTW{DF|N*C!#!z}bFS^J7x%GbkC;P=7#hq=Mp?N>_VK{%Ln&NmG8@7}r9H}u`Bf*} zlXlF=RMPAGYC|yBQmC}i;MzgYrGL05ZOZC#XVI>(_lP-^2s9q>(|5mk>w7<8GX^;5SZ+rdF zaANkrkP;`*c;ZW*dGXtS^)1Y=7AMk<`e1B{d^kb*$Ws$&j2gUwh7)N=yJBpKI{%I~ zg8tSLv%VL-@NCTPZg0=wWFHUjc=6deXTLjJCTtk@oTMN6&e*^$#c9Qxj;k9(6JL;NnEu$HNc2_0iVPop4W0pwUK#i!qig zPNaQ2+~?kpvGK|Y_tXR$ZG^iRW8&gO+HKZ%_L%b=cb#xgO`y?6>WeY9FHWR=Jlx~+ zA7j@KC)`sLXtXQN#kfW-PNdCR(PP$Y*G#ylCQPG0HE<&B$OqpBh_Pg(suRR3Pfb`^ z^;w@2X-9oICD5JT-yF7~#5x z6KTh|%USf14<{H0<*5lY#z@^YoJc#a2AujI8cr~t%Tp6*j4Mvpa3XC&-P%szN7WJMz>78m%QVhwB2?pwW61bJ4EhMA|XmRd1dN=AZJ^ z1R8B*U{2jNoJc$7?HZM4f_bz&HGxJO;kY;GW1qI8LO^{t4Z;F2DnxPPnHg(0HHL|9&%8^-r8g z`*?W7>u)~4*B!q&G@NixO`!27t^fVuxF2*P?G|eJ`18Bp!MD9=S5CO6CeZl4*8g5J z?gyPn`*`>}|64n`{z;r)f`${5XHAI{X#8|rUwOy4A9Nz^5XiP@u+IDy7J+uhx7 zM_DaSqMMb>ca{5)I=|Z*8f_sy5MP)6KS_l%ipzj^@&EfrzX&7E%9Qs-NlKt zkB6W9goj)IaANYTDRBag)}t;)A6%SB`*?WH&$m9D<|Aj6KGHuV@zC}Nc(vB*;hQm#$6}eQxjN#`>mFy6RVOGPd1?ZUQG**IX|*fO+ntDd4o^*>F_CeRo?s%torcJ$h}f9~t@I!LeW1pQ8)nm}WW3>zZp7OIUB@BUnN6_4v6qfaN? zQxj;65pF{y9pmnoyy!m;4JQ}}SI?RfC(sxpb=Pnr?YJ8J_JgG11mn3pHG#&s;&crs z((bu!eNY-s#FZ>OH32=YoKaT&nyR?Cs$s|VT&bN2uCM8-2sFkFpldjhcFZ!?QlALs z3G&ng8e=BYHJnJhg=({!Y*$XWrzX%CGqNZvk88DKo~T|h6U^IIPf4ILW|m#UiL_(B ztKK{l%s=I+2{gtGxobF)w&v{`ubhZ^ba-k4jW)t@Z_vj?C(@4l4~?!f!To?dHG#&s zW9b@Bq#gHBd6jU2`x<#_0*!I!)vq{Cq)jN@g)v?^;hvg+<__{V$NFG?U+wlo+Hn$J zoCJ-A6P&jqPfeilA)ov;r_cL8V|~zxw2ueQyo1w5!_bonw8_iM0KzZ)iBdyHRoK{_U0$C(yW~UD0kC>w`|DeLQd?RGj6H zh7<0o2{aCGz31t_8TW%uquWCjfNBMsR=Z`;|qW3mj6EP2c1a!c;NJ`I0+mL zC)`sLX#AtLKKM)He$a`uj|bj6iIdXNaKb$`fyU`Sd&MKaZ>$eGk#_s${rXiaG@Nix zO$?3K4voc$w2uegnaF%Jjg@duO`!3YpZ%;G|L?dTbRz9GziMw;WPLc{o|-_T)!>a$ z=Zh0*9}k=~m+i_4_tXR$ttDQJw!1iy_VK{UX4yZSa8FI3(R$Ry=!1(BX&(=qf2Q6% z6Yi-AG?*cev1D-~ZU5#Z?aB$xQj2eJ+-@mx0*yApU5qhtaU$*Gfs@#B+;ze|HGxJO zsV~OZzBrL~+vBx#x-hjBJJZLzpsae6Yi-A)9BY)C(@35#MdKC zqZ7m{Pfb`^^*MtRX-9p;_bsffIzjo!Qxj;68r%>`>)cwt8j6M!)N_1;F81U#gNelyM_~KM?a4*l%U}R{Z5{mARl97 z=o(I>9phDe5d{q=7(e8x2{gtC*EO6-JI3AkvI81UFb>L76KIT)x@$O*c3eN=3l(TM z!FVoDO`tKZI9)Wp!>TH7_8NIS0QO6_{B?F83Xd1?ZUF$35T zNyofIr9KnP6XdB0G+GTZ_vso=q#g4swVs(^z9UafpwU_)bGWYIMA|V=R4zgZ|JX0; zMB42wp_`w6_V`!cV`wKWtYNZOSX?x_jrn_K_;#c@CAMB2wgo{Wcv6SGGtaRQCD=6p+g z%F^@UMB2wgp2UZS6Yi-AG@kqQuXyDDJ?;mcNSjd0+0A!yCLkJ4xThwdf8y(3@!A)J zM%ypyamjAa+h6nb_soR~coG0N)3D67SZw2y~8`*W1lO1P&c&}cPyW7PTLMB0SX zS)*t;;hvg+{;Agg{&L%E$r_{+X}7X^`ZrqtaANi-B~GC6@b*0BhoTQIPNd!T;@t5~ z*3X@APfegf{~Ke;;zZiV!`<)rW*e`Za8FI3@guGO{YH$5ixX)d51d(*{iL{RgPPWSHhZF9p2{hUj=VDx=7AMjs)N}0G<%D}`!ZiAo(}}brA0PhY zyN`Z8G&(`N=}}6Yu(IlN1}D;v`uKqNeea<$%BmBTk32Pj#;Cy!k#w}Ho9{ds8ctBp z^3((xqb2q^oD*qB|G4#i|Gb?JLqB(d_9{*Ki{3=(YE|-=7W*C+K(b)C3x1 zWat`Bq)n)2pMBc>-Z?a!a8FG@j}fkGIFWXYyYKwSKOP!RFb<|iDRBY~_Fl2t(8k0Q zC(@4V$Ge~KM?=F2#&daU0*!ISiLx>xX+kY$PrC8;q2YvkY65y(IY(J}T(aYOuGG#1 z*Vpt^#3(D~3|+&Cv}2Z$r9S2ionW3IPfeiFYLL0lhDe%F&#-pognMcNdd$d1S$SNt zW1gs9FcZw%(o+#=jG1NEa3bxP@2WS?1oKaMY66WmGBBs^8cw7g^LC9&Gr>Gso|-^o z%=G)1=tSCa|Dn-!Cb%DvrzX%CcPw4QiL~QBDz6ewa9<-&O`tLEy!sW#iL?o&yD-LG zC)`sL&^(XfNe*Mli(YuIb54V03{RVVulG9V#Ml_yop4W0pwZTFPTO;t8)!I@Hv4z) zb1RAWVjkep~AI!MY=Dni(TK{muJvD&_ zYlEW?w)Y1!uC#eS>b};`op4W0purmF7)#pwgBe%ayyx}7HeNa5o|-^|wc0Tzw)Y1! zuC#ey?SpOHb;3P0fkqptFUHv3-XF}k(&oLp54P)v6Yi-AG*~+y*QoaXV8)d;?+fNsR=YjOFU&vbRzBOADq-48cxt&<*5lYMvv+mPNW_Eob%j6 z!wLGGJT-yF7#X^T6KThI#R>4C;RNG{JT-yF7~#5x6KTh|%lYb|;RNHLJT-yF7^%C4 z6KTiQfb-l#!wJT7d1?ZUamDExPNYq!`<(Yv=KC`MC)`sLLxXE=*Ki{3xSlJu>$SEM zTwl|plsGZUiaEoENIK>vD)n`i(Fx`W^3((xtp=I1>|ex=qk6U=wysR=Y%OJok$ zHJnI0=85VBGr_z~o|-_T^(f||UBijAW4^22JQK`6<*5lY+Q`71x@$O*cFfx~D$NA* zXnAS^jW)t@Z_vj?C(@4l4~?!f!To?dHGxJOsZTYwJCSzWN9igt6WrIxQxj;6JFkAl zaUyNrAIy8WnQ%`{pfT_-daM zX~+Hfd)^}rC%9jhrzX(w)jlWE9_xdz`fr1RB2D=S13sddAtm{Z45(;hvg+9#6b_ zSviq*Jcqm6f0u?6JQqukQsM*}zS`$R+VMQ`-{1UkqpY0Z`JOyAfrhX4IgvJ@+N#`R zrQw8oY699<`w~Z3#6>impq_6Yo|-^ow8T@cgHEI!{o~8; zAq^*JukzFc8ot`+MB347fAFgwJo4cL{Z5{mK*Lx2oJgBc&pvzEJNeEqW#xo>Y65zU zaJ{UYNIS;e_?9smPB0FpM=5avjWJSp4JXo$tHDb?Px)|y@m!voK*Lx2oJgBcOY4Ku zaKb$`0eyLWFym6ZaXnXRXM*c%dMaX+)wDh+BI%fAWT}riLoZ$C3G&ng8m$JW^+6Fy z6Y3e(uAFdBO+a5>AIvtYcw?TZUN95P+tO1JXk1<&6p?hych#F`g88RBHGxJO8K(6? z5lN5r!F9ZHf_b#YtC~P#vpzWDN;>X8G`h|N_XG0O1RB2D=S13ZAC*@LC%CVXrzX%C zcV7L9<3!qo(p?y1i4*Rr324r9;v^`>cFu;n+sUK)Go-YS2TpBzzaM(cc(&w(dujp= z&U4~KD>R%)`*`5gricBFPahgixThx2;5;Wz=0d}Xw2uc)ZMx~E&mJ01xThx2;5;Wz z7(>H}w2uc)ZTgiTdHm3D!aX&C2Io0(QW_dgq@$^LD;(_75lAQxj-#w&>`CixX+LuPC+ieY2lC;hvg6gELacSh6^g_VK{^ zzByhw;hvg6gR@@8n7BBRc6%qTo$s6Dt`qL52{bsfc8u+d6KNk0obQ|04=3DH6KHVu z?zl!RPNdEA_Mcy`T{GdHnlO!it#u;p$j7@s=aWW1AF1jD@yb&ZR#yG)&WW_6K7Q`k zK2Bpvlx`;|A9-p5jZuReBI#&XZ+^qy9vV(i&+^m+8lxqiGVVH&cJz-2f7VA14JT-? z^3((xqepcOC(@37{>&HrjiKQL{Z5{mKx2#yUBijAW4!v;H$H4=IKlWKPfegPM!2rw zMA|X#KI8ZQ+R$)eaDwq%o|-^oTyeUF6KNCbO=sWn z!Vei5PPnHghK8*VdR(&Odal&2SLdE8uCM8-h*4I|88$@HF)vZ6ud|F!Fi()DCeUa# z$lPZ`BpvfBwVs(^z9UafpwU_)bGWYIMA|V=R4}SY(xS4QIO`zesKY8O<`$f|}9(YT)-Y@E& znn0uN5L)+(I+1pJF8c1jcUJEgbx%#8G1i1{aE)>z?Y4*IN59~#-Y@E&nm}W$ZC{|_ zMB2v#Z|TqXpA-buHi)5#{+Na*84@>Qxj;6y#`&wiL_}~`kpY)8JuuWO`tLM zOmqz=(moz|OSj%H>YkcF!*_o=k@oSxTeJ0kQTNmY8ov9}iL~1nTu%P}*@J&pds3Zn zPfZMs_3qAzw2uc)ZOVL%y*QNa;+~oqWwq}9bRzBJfpbN&K77BZdujrWvD2xi%89hw z`H63M+W1a2?aB%F)C3x1$5z*HBJFlw#zSti{^5jsY66Y1^Q>z)k#;*f;fY^v{oD!n z)C3x12VK{2BJH+!@Nr*ZY~PNaQ2 za1K&lKb&w+O`zfXMV&~S`PDyMuU#|Yo|-U?eyw#P?Z}6A^{g75AYOTD0uA5&=|tL5 zAKINX6O@lUHG#&c!9Fi>BJF5b+GRBp)U!M_fyQWwr(6e}NIUw6c8kpf?Ny$dKx6c% zuHi)5(a*K(Z6@e<^3((xV`S(WPNW^-3C44IY61=4{pm#7aUHDpi*j9(rzVERdOzqy+HpNsYS*iCFI}#$ z^3=pAt98Gq6KTi1M5VsYGP(xy1bJ!#jWPGx5J|`UO08!mnD59_6KISXS=VqP?U*O3 z7t93nHhF3SjWHMP8cw7g^Ii4knPC1YPfegP=G0xoiL_(hu2E?wm`BS~6KITkgFYrY zk#^jFXmp(k?g!+l2{e4as1s?&eUz>eGr@h0JT-xa?-z9j(`e+*1>1uwR=w7WLso z+O6%j_kEZ>g@zOEsR=aNdrRy2qE4jU_A|71ZkYv!h7<0oiJ`Hc7V1RW#{=`}%m;5% zF-vY4U))m@Xz-2~Gx5tr((QYx?fu=X4=3DH6KL?R8uL*!oJhN!vDMz+&35I4dujp= z-nnBwiiQ(u9}hf_$^PMldujp=-W_BNc(u;d5o@IGvS_^FpYk9=S13(4`zX5yoywHf_UYr2`j5UFL5I6s1Ig=p)ty; z6O@lUHG#&c!3~jgv@2$Tq2UDeEKg0KFuq#gZ(Szu^5L3@>_CeRo?s%tor zcJy;*fuZ39{Z5{mKx2#yUBijAW4vM(7#dD6e#lc3Xp9lAYdDd1jJwPNL&FKiL3wHd zjWJSp4JXo$>j$&I&~SqBT%MXhV_b2%h7)PWb&y$SXgI-jNuHV*8teI@PNW^zbES5@ zI`>p@eU+ys&=@m-4Uu%rOH}GJ!8}2pnn0t~;CjBO6KTi%O08!mnD59_6KJ%SxSlWS zMA|V=R4_K1x@Knc%)go|-^o+|4p4=3DH6KJqkl-*}&IFa`8z<$*1 z=T5k%CeUEdE4$Coa3byFf&JP!UOC~Onn0tCaO?Nzok+W#+28hS=eX;Hdujp=b`+1X zeQ_e~cCJC&ubtNqC)`sLXmCF`t~iSmX&(=LzxKFx&4hbu!ZiA|)`_$uAM6r~em+vw z3F4KfCakRboWY5-qdwRr78;|hIzjo!Qxj;68r%>`N4sK|SZFvwJRX~%Vt zU1_1=1lJ{bYGP=t-=lXT?YN#Rwd>Wnr;6*VJT)=OYW*I)6KTi1M5VsYGP(xy1bJ!# zjaGx}_voESJLXqvJu|_4N1mEMqqW5Kd-P7E9rHx>f|+36CQnVE(R$SSJ$fh7j`^;7 z^Gq=Rl&2=pXd}b=J$fh7j(NLArI}zJEl*9L(MGuSd-P7E9rqs^U1x&(0eNZyjd91) z$6Y7Vj{7KGC1!&A8hL604ekfqb+BJ?oJjj<_igOIaw6}~Ztr(=q347&e0`9!oaoQo zO@|=s8cw9G=M489 z8cxK0e|TyFjqxnwf_ylUc04cPw6VyC6Fk3=rzX%C&t$rW6KThDA5KjR4JUXGBTr4B zF`g}T4JXo$=U1Hm78*|QJV~CKKw~^3>l#j^9nax7#V$0Q;JKJQHGzh&_BoMuJWu2_ zzR+-j=X>(h1RB2D=S13iE-DQt;yGn_YGP=tt9?$S9nW`_+VyEIrQ6pB<*5lYe6^1! zv?9`u=hQ0onc%sxJT-yFc(UD7diC3dW1YRfyP)d=^9R?t#usrb0=b5B|J5O##s4bOzi7}oKQ$V zNIKS|G`h|N>qGL?1R7%nt7|xscC4%EDlrqRbIDT^XmID{>w_Yaj`cxZyJmv*I(cfs zH2SsHiL@ghoGLiRt4r&H^3;Tt)h(?)PDqJ}w4**aRWLM0>2`whk*6lm7zN7WJMz>78e>M*HJnI0=85VBGr_z~o|-^o%q+Wx z6KThMSG{>An19Ms6KJ%NVOk#)k#x-4H7d;n^JsZ$0*x`#?_;79X~+GCM%S6(en6g@ zKx5pobPXrcj{7K$`7^8yZfq zJ}*yApfUEIcMT`fj{WU?EjTosV0~Vmnm}Xhq3;?_q#gV8`A%|ZIKle7JT-wv+o#66 z0A0h0wBvmPzTO-fPOv^NPfeiF=ApdP&^4S$JKme%E7YOk1UuN|sfnR6y+0@->3IJ` zsa@aZAXWYSL3wIol-2b9pa}Nyg&ps)sMOcDQo05^3gxK@G}xQS?2=SDk#@X~qt-JM z?BtfGCeUDyC9_L3oJc#~D^f3*33hnOQxj;gSCrW$8cw7g??3CmFqw7qtb6B35K!g3-ZH~pbyEu_{ymzOo z#7wXQTArFfgPqaLF41rz?RbAs*RGjhC$~H`VH*8f>qOd-557Vj{d}aV6T~Y|O`tK} zoa}Q3C(@4k;49Rj;RNL)PfegP>bz?>k#@8zzCs-uPEgPC)C3x%?Vh&!=+?`O`tJm`h84vBJH^U(C9i7+z-f86KJ%NnlneGr@h0JT-yFxbx~)94FF__Xl;gn~A(XyS<+X6M9adG0v>vT6@x0^iOW>{WFg;_mWC7VsfnSn-VZvFcAO8V)b>=Z1UvE4 zqm(!?%4$6=)QPm?oI90aFWr@3N1;45fd>1vUp?*zok%;*>r?BQ33f)xQxj;g$CBM= ztqb<^MMWeX=MJhD%mh0;<*5lY*elBJGc=q?JI+s3Z=MNus>)LnXt3v%-DhYxk+#kk zRX=xvo!lC)Y61=R?y~y~4JXoW&v)B?ZH=xo;hvg6gB``}K10KawBuY(T_t9M9nkXB z1RCQcPp(n@d{Gfe$N8csGoM zPfegP#>5Sgbd0;-e?uBhFb>L76KJqsoBe9khZAYX)!-d3mWC6I=knA98tm8B{h$+R z6Y5Q8FM6RgoN!M~3=OWeJs(b_9oKWEwx?<(xW1-GDRE+y6?2BJ;Y8XoFHxzlvy4tK zPmrf3&=@nB4Uu%ruhe>Gg87a-HG#&Mk#!9x(vEqedcjOEZ?skd1?ZUG1KoOoD*rs{f9=^nc#jvo|-^o+_7{G zC(@4lC|xCHg8LeIY66XMuhy?PPNdCqhPGeZuY-I&q7&|^2{e4QkM()oTc#b~QPfl1 znP9bDo|-_zSNohuyX|3V`z7==dM4ac6KITQ05=#Dok%;rYpG}CGr{`2JT-yFc$RU2 zh7)PW_c^sXFcYlL%Tp6*jAt@k!-=%xJEL0VmDeQo8-?^661ZoET-bt`D-`PDI-AUF58f@eH|Zuy0VF znm}Vb+1?OIGhW?yZ9OyLo|-^oJfZIzPNW^*sa7wT3HEWyQxj;6m4>e2MB43{W!tZ< z-aHfTsR=a3ib>aSBJKEYxJIR!U|+2~HG#%h`C&}#-=i0ibXzNG`?Yi2b;3P0frhUS zI+1pK$6Z&6nPAtlJT-xauMawrHuLrmUaws<;hvf>jeg~HBJIeBp5m?=ogiL$Y61;k z?Q` z`l?0*$dpxNA6(_VGY3V^j?d zC)`sLXpFti%;8R)Nc(u8mvMCn4JX`F6KIS*+g-znw2udR8CSW`aKb$`fyUT--Zh*^ z`*@(2akUN&C)`sLXpBAdUBijA+q=kZUlg;B&~U;%HGu}}^USfR4=2(-9_VGvorzX%~Pakvl%S6)0 z1NQ}4A5OTZCeUENHuF(5oJjk4;GQJgl@so%2{hPa$$S(IC(>?ba;e>l?0*!XXS>GRYBJJa$KaUyLu9qZNR5|8BtvbU83C&B^^oinQe1DKcm1914wBziYqtg6p zO`njDvI3Y8m5z0ZOT8tuPOzp=$VaNd@qAGdRgU$QTTe@9y<<(EkdM?7$MZ!=R5{j( z?gcHOb(=MPLOxQD8qXIcQRP_gx;M9k)}Pk&3HeAP!}$Ini7Lms-J?=VXdP`$pOB9< z!j0#PlBjZAe|U6l30)6Z(P<;pA1Q6#E-{<>a; z`8*jt(a=auO`njDSEcL0v&;AB(-}nRS)`xM{rbo!fm(uh3 z>rapKMM+fo{PpS2xncR+m;3Bb64dkw`FL-t^Iwg%&w@mi)1Hajd^_dO=RlI6rccPn z7gF2(cC6tRB&vM=`iSeky*%}ZkCrpGNKn%!lRsh_XEyL|2$ zA1nDF(Q0~xe0=5fGmc3uC6^V6DyRMJulTp+XFqKpB&g{V@^Kx`7bQ_;SuIxSeox5< z32OR8@iCqjN}|f?JhF=ytD2AGVR>6Wfkc(lSn|u?x2pA#%4#I2=@asi zYVcsG^MOQ_Wp$HPZC50y=@X(;OWc&UJCLaI`RfOsbCXr=A0%3hBOxIl>VKsV4kW6a z=JQ+KbXEH~32OR;e0(SMzfY9wK@wFyfBk{eZkpPa$14)l^a=S$BiyEpi35o$r}uH* zann^DcS%swCvttH{#VBKfkc(hU;ozEZn~=ThgzWtYWjqHoR_Y={`qym-DLIT+t^1LOEN)CpAcO}xCv3|7KiIp%Xm zJI>BID$TD|<48!9veKGiLR31|CAHMcnjsTfCs@-b+Ql=}68M3q$^7cH;2=Y_?G%E|;aeL_Ayoa%fvUJur^Dt-R?$+x*U zy2MKEWgnTU0n*$#$*MlUgtp0KF^0IT@P<)V}rccO6>4O`U6^SaV*Iu$b;-zma zK1fj0C*&ioLw7Vo%Lj=n%j(kQ7oPN{;)4V=eM0mvrvCSV@p_PHS=PAwmgPIYVIL$~ zO^=X|GE(P!kf^d|gUgopdd!3T5rs_cVAm1Xresa@Fz32OR8@o`1* zF_5Toy7&5&w;~_O$4ImqM?#{M)p&JBqRQv5fBW*cp+40Av>r{3WT2)`$VaNdgQd*Ps3L2J;6AYWjqHsBgSB?pY2bsw}IwW9}kBO`ouj7nV0INK`rUaltKKTgDRk zFrjp-#*vUfS>+V~i7H2ZeE8x&D?UnDWkTg+O`njDQiBts(r#C;DLzOX?`Ov*xtuB=h z5>=Mf<;x3)R~H{7sOb};%Ltc!kf?HuyYK$utBMa28V9S!k&uv&GE!$BB&r;PsRp(7$x)H0vaBveyCOkNpAel|;*Q%ci7LlB(Y>H0v~H^! zM?ykAQjfy*U?nOY>s|NemeBgsnm!>PX=K>(SVE%8UblO^A`$E8(DVuUC@cLuCX%Rf zTz`0UZ3$fuSkouuBaPI$V#z*8R5`Ar>MTJ**EQDk3Hi{K*O#6bPy0wzSysLZ)Ab+; zYWf6xT%j>h#9Pl!&(PBOqE(K3Jn^4zEWZ~YnNYe_W10lY>YzN3sB+ZDeIEUt;-i#R zCR9Gw^a=Uk)g6f{N4t9K+21WbNT{Bz=@ar%TH;3eAW`M$A9uU#---_sYOmJx3Hc~} zF#8};<><99yX1St2MP5%Yx;zIl(8iHAW>ymUAlbZPP)sM+X4w{`h@5*!et*MsvP6) zkGW)N}W0g@$J(bl+Xq{k9pOBAKgU$7ziAu}r zaLe~S<^a=SWS1cN-^Yx&KO2<`Eoh3-< zy2hG5As^++OEXTs9yC#DS-l-|7YSJ|Q2a4`v@EsvN!clh6ES@j*iU&YC_UALUL__Ccb`vbubE z*q?u+_#i<|pAcO}xa@;Om1EpJ>X!CFLgQf7I1&=_QAXB>0 z%j|=L!uflvin4b2PS*>dNglL^v z^UiS|{Bqte`qa|7UEpg+vYpc*yVptqR|Cl3aWjRvfI*}U7 z%E$Nq``ggZ=LlL^4j(BG8}%x+D{3su$1lG9uQ6WD5wx-#K2lw5)T`u!8q4zW@QdDp zad(cOmF4h}+LZQkW*^j8mXFV$eCaqd#Pwj0pq1tDk^08QGY&PD(?^r5dA%j@hD$=4=$nkp_;j#~nS4wM}P<^Z9 z!v}~|z?Gntug!C;pVUINXVc1OZZ3` z9+d0!pB!&c@ZZuiAEFJJf3k1js3qSs2=;(yDp!6m)GZb4_8?kv-v63oYR(6FkPm7|oN?w+EfGK>e*X;z(ti9X-DltH$kkb=Ts`{em+m>w zIDPrepZr>m>a5G3zr67YU&->*p8EW;6e65(GVG+tmPbD9ez_Dy{I4TJ7U8-n0R_0@ z@9rqK{yvW6BM+R^5`%r{4Gz6)C98O2OVCOwop$r8=#`I?O>wS#G8}*_o26)^wy^cy(^`+Ge;lcVyh3*iv7PBr-D*hv3%5G^d_Uy zos`w+gBlXi7Ghk<#wq>qL4sD-p7YglzADKFxI+yIwJVQf^8~H*-pr(|2Iaifd?&xF zt(?>Mybrx481610jo{jN^CN*?oj zX-dm)ZAn)Ce&i4ScZZ;r-@)3OU|J;nKGrlJBxuEvD3{d`B{uA|ns{qV>H6)esSgsg znjhgCTsKtBH3MMfhF9X;dU=^bV`$C z(RBqFC98jj9coDEdxuUb+YkBQErM2B`}BQKLqgwe)cH$IK5|qfXr-@7>NKU17^9*_ z-?h|vNU~x|kpt(08WQ^QrcOEKcP zhczVp1<|PwrbR1%4|GaU<1c#dKPnRbR_D|QqoNgCew%Y@NcdZwQy(N~HR(}9cp7$C zx2hYR9p#)Ky0w!~{p(byX;f@iv|@?0Ij4q%zvA2X;Z{N`w#wFrzkaE-{FO?{x;Au5 z^8~H@tjdnB|s`=916-Rn~|&{>F>P zEBgMO3Hh*wgvOQo{Ev$|K1k3?rS6p4sHh>Kk?5J1{AI@n30i5q`v0D`MGRg6{NCvw z&1uQ%9`6rXDY*=%QCUMm{+v=KQu_LfHG>ISv7W*<{*9TlN2nAIzV;)XoHH$2vHo-F zgMF|yXjVJv8}HBQGNrIJK@ACw`DY*b-a|x1D~w~kTu zTZy8whJ+&AU0>GmL4sE71v$@ybIy1*1N_d{-Z@6)dJ0<;EGrV4OTKj;?hY2Lt#ev2 z+NlrcoP_*6^Z3mna!xCjdh0{uuEz|Gq8>~3*FQ*TMD4d-rbR1_yG@T8%ZmM3Rvr!5 z|Hpg`?t?BX67ts{ub5VAb>i|reD#+*rJKG!FltDs6g;A~QE3c!&(TcnKByVB->#UJ z>c*oseUCnpp!+^GDiZQH=^weQNYILRyjvgCkWl{IgXalaX@+zEZwZza%SS|iEMZ!j zYuzUpZR>*?5?ZhHdo2lCF~ZgdH6-NE;8f=?SpM}Z?wi+xXPxrGPRf>yfMf0O?cbWVNr!E|qX;ft0xJojg^KhhCT{5$MWL*nKa?k*2p`O}@% zD+yY?@}x7D-~H}=DltYy&EX$EbNM@W3oE8H9~Ftk;;iL?hy7IbQLr{2w33fU{g=DU z5LHvtmA|k4#=Q?g&`SAx`Z@RN5Y(uwj=b`o*=m1Lkxewfg(xlgpKCB^e z&6}P%_Qz>dCTOLoJW7m2j;ht1HjXR%i%L27NThP>k0nftR;pP?J4Tg+sB>#bsAm0i zah_a)p~U`?s4+$Y+atxT-+-F`@@ZrmTMz4F1dXr;E$@8{H9^{A7_@q;PN`yjDc zoIEqawP{r={q9nq`ly;p$e+jHd4g8#1(_IvOHVWK+*vK7u8>}^eB@!@tShpHIOX+s zEcfnTuw35v@GNUg>_0!(cx5Y%YEQiHVSOTkN;Sx|NN9XK{%v>YJU1Xgt31P97f<+0 z^7%jE!@1RLaF?gvJg2KM|A&9zX4S`-bEYM$$6t2qe@8w@$lpUB|HIWsH|Mlc{v7Sz z`KalpIq|w%%=oBjRV$W4>w{&IXSM4VW6o z9YW)v+o;ABTd7Amr7@;KBZK;ZYb}rMrDcd{+U^*Y#zD7sjc`vt`%XFM>MMPM8WPF> z^2qCg9-~S^jJq|hYNdJC{#rsB?+{VCCmp;#mydi;az6T~no20bno{-BUOUsOTe{f? zH6&Dq-rG_=DCZ9NHqFLLPX{IXsu2g$FY`R>yr<+ zaOSTis3DQ(tJ1sX30kR5H{(^oqP1J2*}x+leb4(Kk!Q8;Skk7I=BQ$&-(7}NA5~Kc z`Kx1BW!n0n6?=2FR}Jdh=lY7d?uF~??D}fDzxL7CO{4G9 zKlIOI=g~{PeDvz9%drb7S;y`KYDm2QlA~9D^o$Q@e{EEZMBk;?_u^-xlA9gIOG5ti zMSIb$4-&LG{TGf-PvYNGi6OXQ=k~WdA$?OTc5ggkdBT|UcYXdbs|Vi_I{_QQvA^&c zk6yj}GjGW0if*DB32I2ByCNy7DD{ZPQIVk4t$*o+)vNFMftrtk4Lhx-ru(#~o-pG> zId?w(;_BnaR?Nnn{IrgX*={{z&v^jVq6RQ^-tdB$6=fP($KBp_EJHFT2NwikS zr7yDe2-XKnTH~X~u{J7dNObEwp~DUdTB(J4W@vp-Ln2yY?4X?|Xf>HXhTycOK7MRJ z8cW;~*?L+Z)R55F;*&qM9^2SFK`WK?WIj)5 zJ9CmyAMB62Op8`rOXR4Ah)wr*k4xV~ivFy&t6lh-ky+|tYl0dQ>MNK0!J$S5TCpvR zJ_hBSql|LyblLJpA_?tyMM8DsJk1lWRV|SzaqX3#%jI*`TOPc6!!*k4p67Q@f3 zZhm3xxt;p(*iI{s^DXhWKmNeg;UD)J=Rs*^xF$!as2puew3s46EkUc_y6u5+Wid}sLt?Se8yLNnB?(&Tcb7sNRjaA#%3pJBP_Q&o zBQ07ffBkC%m7+&7m9EQ2rGEY6uI#LLsUZ<{gWb48gf;A_#XaS`zZ+ZlS+9I?q?>xw zjgJE{=0m;68nt{A(Q84BKDLR)BCOO0`}t73PFF485zgm>8WL*Lj<#eW|0mwyaU`^2 z8MXw=O1<`Tck7fJkm%>m2Z_Z(qeRdE%D8KSRxFX0Xf-umjbn~*o}g7zZa{_|zTu>| zw9-m*Y%%q^y&{owYe?wbFTI~Ny-HR4F+nS~vFu?8KW*uf;98=_|OAQIG z3`QR*vWUv)O*Us#Ee{S@WeCYi;zx$?dU;CN4zESO`@6}#W z>1)Z}!=SGk*L@O)ubN#JDI)z1JNjm@cZKL1#okk*ajYMezSHPE9{Mh%eJCH^6B4P% zzgkn@cIABw%DHzW%oEg*P#N}fPJ&kYy`K+iNa!1?F6lNOBxuE&9f@JPblVcW{mOge zMj{DX>DO9QeYm6-i>(?gnAW0ILqav{ojk1%60OzkSCf5xIjXkKYd!0GntdN^8Tvx0 zTP5qMjfxr)`iAOcXHAZZ1g+TKMjwMpm;Fvw-YvwM9f{G0+Ybr(^ZufFf>z3t_kLw! z2yWPE`dzAj?+R;MO!X403`eCFV?zDE@ll|bpq0Mi-sEG9iW+@Q-etAFs7UC0_a5zP zE^=$fC_^iaa2_i&F-FC)PlU%3j+LzsYDg$Tk4p1IYgKz%ORz_gP#N~yE(uz31Rs42 zDl4`h^)A=>{@N}H^=6OrqmLxS`?YRYv{FC!ERl&6k^Y7q-2uMeL*9K%%=9`nBAu?2 zu7uA!_nqS#+4{|Yde@SgN<8CE-$F{seh8)|Xr*`D{nmH39SLek=)H8mGajki$8%r) zpO5vkfu<*brh}s_}m{ow!PZw5#cd3B$U$J zJxeh`(CXMLuR6MUHW5jud{9F|rO>}~M}k%=_2z!!5Ke|2)s!`=L8q&l?O#DsLqe^m zpK}tlV(TfH&i@&9s3CFkQ=gim>eUAcTCq*HKG;TI^z>gE`wCNP32I1u;?0jg)=%i> z30fUE@bky^@7&$^3lBclcb7l>$@?Aa`_ydH*~bu`h8>-i;X7OR{m+j&*7wL1?V)Rs zgre%-(`O_feDA%-*e6j%P+NVF#62GSlQU(-v}na~EGIvN6Rj+3yeeJaL*8G`NvJma z_mG(ut=Ml$rX#ol$S1X$fjbsAk<3<_TKqtdz-Ts!m#Te07?KB!^3-ByyLB0(#TN~4b)73)@` zghwB?o{`8ts39RA9>?YhS}8(5vuFvmE3J~XZi^Okc$QTP-hbH=)R0ikYK=9$??ZxC z`u(W;-eQKZhJ@OJ)^vRzCTJxeIkHWNc|!wxkhB-fp%)ytHy72n#d_UePwFkQWM@%1InjT)mOK`XxDI{HY| zu%q{5{N66#YUO*LBawvkPBq@{C82#w%{$d8ef_mWYjxssa+*~pG#Xn&Lc8?(K1k3? zW3Erq%HfoMh8^_*-K$hTP`}nQNy)nQX?%{uAZSQU8Ynr z9bnU=NT`44nf=~T(TcsR^`R2g{-{Xn@0Z%aC0Tbx`n|T*R6@O=rc}HP%DJwt+`@HF z!!2KHD~}j$RMe2rU67_eQu_Lf`#w&qwW@6)Y~$ayU6IgzlS8*FTDASZdKq?DCL%n3 zv}H(wnwEIq%y>mY`S7Twa`X6DJ*cdxQQde%WlAkU4GCQ-^+yI0w9@sIN21n;u9e)X zS^v5s@?6pq)R0h09{EOMP|oQ?k+=_%9*HEh?TUo*)E{@57OmI|S|55|&kl*XrrX*^ddiC3N@HR!moSQu_ooBo>R?uZ}taK8En5 zeXsv%%m*XXvqI-7+l~Y^BzVGSq@Mmwl->oXY0*l)ea=WrP(woZ-uq{AFdwpd?llj{ zrOOCM9||n*vT%Kn(7pFle>doPf>yfse(8_*2x@d!{@WjoI@n)S4UwMEy!ek%gC(>! zA9{{sE4HyVA8ot3-AJ@8rZRC)-({tz0QRBh3C>fsSLre>TIp$4zpO}X_o)7?Cc+vL z>YI~xmBNdtOwdZt^!n|J@#@)~TLz<@&p8SCaI2grXvHyRBnIV!@ydr!AYzG(L=xJZ zlTiMA?K4l%O10^8e=;!yr`h@TE1%bbv>K_aS#gxYTZL?9BhQp@)VL=lf1 z$Oq$9+qKpH%8G>gO%qj0Uw>`swpKNNVH^LpIVYhJyp~&KTB5b8rJn5v`(T-9EUC4& zpQuP^9P76d)(5RPYS&z-tf(QO5!LN@o}g8CHb}WwS=F7S+%+3}bi8A;dhuSI(2&sj zRIB~zx}9m!O27MlQ1zgws3D<_TKKhwlMpVo3j{ z|3yBmA)&orz6Y3z@=r_9N;}e=(nw?s%Vw$M>E4x#j(@_+n0XZ^CJj5UKw^ZHY{a zR*W_>kpE5j(ABoiD^^-Mn^#s3D<~-&Ky&s7TOCC9B99Vo>S&>&epS zt8e<+s${*r+>c5cmzBSL7U{+}(Hb8qE3FTvtFN=^8>b_YBGTWmmN8*9BL~9k_936cOCj7OZJ=wmwE5 zBwDNZV&&9F6IJ!=Q;@*V6An2&(dsNlbUZmco@ALM3n4s09 zN0kC=dz8Nvt902{+R~+lguekhjfw=V+IC#M=uT?w2PFIr*r^W^t<_xrU`_d(lS-F0 zTVqn&rG|vRCOM6Y1g+Zf(Ul<|9Bb9C^d)Ua<(i#FWeo|ne0^QMAC(DOso&^(;v+GH zrx>rQCcfz{E8V54Db=`Qk5|=HLUrRjReR-}Y0*mc@7bp%G=Au->=AE#mHponRV6f5 z)|9H3HY!?aJgy~@h#{!7_CdVSKfar5kol_~wsTHGvt2U}7OahmR_%OMy`*PenD0nv ze(aAWBwDMjd2ozMt=+4;?Jv=IWl&>M&e=amy!Z2$w5z_xhtr}JXNlH_V!z-Pug!I! zoPYS@KO5`AyCGVFR;rJOo%)(X5UN|JMM7=inuq^srduB*Xr-2a@}ti05Uu9&<%Pqm z{~b~3Ti7PlcHjNQS9N?aDq5-KpY(@4LN(}|Yb>!3jYR!?L@SARi8Ll&anB2LBpOj4 zcIxZfs0OtXeINc|r(TdXYL)upk@~r6_DdgpT}z~5jy0S$Bs3GLoyCYzY9#w$TC`GI zaD>G^Igk%(NJRZ_ct}}Q)&rnNNDZr-aJpxN-4R$O^K?h>B^t`|2#n}jzlfN@2f>5 zacAmjPknQWs<#`L8WNJdZ>{yQP1s7lHGWN7J2gx<{Na7h;wZio=d@_`Lx1*{%M1Rs z_f{h{Bs9)9y>|3Lf>vr{wKv;*yPvZ^YR0+OV`7|d%ZeHjx)#+cped_CK1j4y>SBhJ;2pzJgyukvWm6v{Xw}wi zO1%6HJG#r|GSNLT*MaUi)s=zGRaVrH(A}uHvAw26E8WX#=JO%^v}*>g0J$0{G3Ecn z3YjYlk8oTQ%@eJa_UNEp4Z$g@sv)7fc=p};*!rGNx_cULkn28U9r-E~&p)6U3EeB} z*E!Rom42VpU~&~ctRbO$iT$?Ar~2Fjr*Xwk0c$SggBlXtO*c=_N-6n?>6EaBgk=A| zH({&ENzet0b2)vkE7R4B1-F@&FCN3lCC<;hl)rx{~eF?Q{$(6cp1*v|)Z zNJ2X-^bB;2YV<*ZR?Jf|&i{!s2mEA&g#77AY2SwlTFsXg%SX=~o$h>DQA0vcefv2l zK`Z^cT(rcS=5K~ zK`YgbTTB}jHL7!$4}G@;H6+yDTsQLstvDW!#Grhz{V3u)mAZCw zjdh;V*I!G}YQ7~>LqcuA5k~6qZ~GLPR_q1Yb}+#{p_b@gOW$E@f*KNP`JTJx30iR` zY6*VXnmdWL_UW%ns3DPv2XD8m8NQww=&nhi@Wq|F-CU4N^lwYxqMGv{Fj0n>HWRkdVAT!d6Pj zbu;y04bzqE-}feLB_FPvDPaxMmF(a5CaP848PO8lGr@Fqb=N%A7dEKQbzSS{HM)-W z(;i(LRDWTep?v*e4GH>_rT^lJ#RRS7!{wH(hhT!RhJ%R5N;Vv zSF(Q(+d0Bk^3k;R#)mabSF(Sf`mlypyiRNhYDmoQh$lg-?*8`VEPbmneLc?CPCAdn zt24dr=9+Dz(m5zzvFL;ouYL5+U!P#QI@`r7i+LZ^kkC0VUe&Zwk)V~%eCe;27`skO z@~Uq>AJmZ0c}^~cHYyUd(wQ$V!(0N5J>6V~(ogd@!A>9(x zkkH96{rVt5t4UNtcp7$8Q@(;w4SKbtnsuLVqheX<3@2Zo(RWKwLqcap^{*gF&`Q7e zqoRg{{P`Mp8kN(cmGb912qQ75*HWYU_dN&t9*HExTfg=}LiN#KSu!nJsWx3VqmLXF zHEJcUO{O#wlc-3jg*Mlm1#9y`EA_6)x;;llje4!GAodp(35^(ykCeXt+NfwX-*%}X zq0zOUa}u;-zlm`2zbPvAB8{T1XQmXkCa58y5!`KTo}iWHm8R_uqYr3wB9r?Beb4(K zq4VeZy_RXwO27B#C~8Q^pU0JHR8EUloKahX_jh>DL05fFsU@f(!Rz*Uf>uh&yGW*l zH6$ea_q_>QwI>o+X4s*I>GHJT(SA^m;%T#S7H^zGu6LKb<0ccyT7PNP2Mr1NYlr~0 z2wEv6=P42oBz#yyf_W;*2biNGVOc(!Iv?o68m24RzfXNwLo504m>=QLhczT5`}e62 zYiK1OUM)`vYe;Yh{xm8Rw9>AA{r~a4PjM7$2CrVYE@f|SqoRg{W&@YuJV7g^(r%_qMbS3-uy$M@Iw7qBa)G*!fw;#e!{*;oR z&`qPVhUrT7?=7Lx(i+{<*H^mL`t(FV-x{8_MBVMzH-4pwdv8z4vQqLXNAo_I?%ssc zBB2QN4dZE4Op8{GwvCFh>wcon7g4%QsU@f(q5GFQ+hp&kXr=q5`l|1g(7kD=rMu3K zO5=)4q>YLi67jSz>Smsxm7ZX^W?Mqfx!f}3&n-qz%=)c_8WN1Q^|4JjxANVub847w zHy?v$PUb^a`d+;1fDyJ)QA0xIrZ3D-Ymfx3R5$w0`jpU}f1RKsjh-Rs>&A}Cr7(@k z8WMUg(r;HRA6l`!Wgn@W^f&CNg*#sL73WsH!1W)t@ozjgu!e;Cpi6q5pcO}=mSE4( zD$`}fzS$DgkkBgAr9My4ie=am)R2hhEm52E1g+Q>Mq*HXu>GjkUh~A?99xM?eI$|) z&x))eq56NqiO=k`M7CX8sg3>m_y50@ND=8To{UkAD_XII zj>Mp-7_Un7xc?flGk+tIgtn|msBX?Xx0iFKMXUYgoP=78BW$B$TC`F-cB!`nzfi$1 zdnj73QCfl;5?b#bnxK_Z@)~98!x|Ej{rld8tyt<)!mXX@O7`!26Sk5MkFHa~8m24R zzwb@h>drUbXZ4cLT-W(tDm6@3vd?>NeQXo9;%V9~K@HQ@Js;hpna)upXr+5hx^pxo z+ApKmZ=p|~n3T}k=O6rfx^`Ciimc5C)1sAr?_c9kLqhWY2wN#7U%gDDvWDqO_V0TW zwvrEDy-W#fn6701zBgej`RMm^YM8F%{Smf`eDtnysA0O{Z$E@b2BqX4Jk7Z^Ojojh z-n2B)BGO+vB@Lyh@yZdhp29Z%ZEKK(#!BC3oF{0-zA`1;qe$qPXaAlh)1nne@YV-M z8SQ8AIM24w64a2;{)v86BxuEYn)+~SAR&MK(q&q-VtX5X461Xs2DNtgV5T$@Nr(~7 zQISwj>)*>@TC~!*GPz%pqoPLRmG9gzrTM5xXsm2}r1bUI=7U!IYwaX7YWH)_v}mPS z)FmD9#J}-vK;7Mr*{hyHs;hfHX>5sBQwi=*o+oIfl={~O)R2(8Kf+c@$*cZpRMs$E z$^LzB!dCL(RsWQ*hUrT7?|T!rk`J%?r-U_3SF(TKo3NF9c-228tYNy6{rld8ts)=2 zYXfSSZur{|;j0OyUl{HLPvVY&3u$6pxmY5ROFkQ+1eQ&~6^5IqHl(2^BO7`!2 z6V+<&E0x+eq}fa(1Jl)BAI)szdbcERvo2{49C*r7Pq8HHdZ#~@P(woF*r5qp zDJA#$Hs{okki0*_R!Yfze(J*-rYqUM?@icBKHTT0gf&c8vVY&3u$6qc&rbQaYUUGE>Wf{*}v~i*h)UMf}NHwHB47>pWvwq zJefd5zjUb~q4zWnP0&gyx!l^EQ$s@X{s>zsC70XOhc!%BvVY&3u$6rDOP3m^E4feT zDcNC%{cEY)7c3un*f+DRCk^)3M%8L6q5GnTCTOLU`cY9sLh}9yTj_KMeGzQhcBx^y z8plkxIVVA@XTS2-mw)mr_iOvdps|D+66p&#OMMG%j4D~{FHZ5$S5Ku;t@)d^dNWX8 zDjkUc5&ES^CFp~MT93Zh zxp!2wn(rTa%hdf`Um|kfW)E(oqK1T8e$#6U7AJW+hqO|^ne^I0b1)AbS*7&#*Ald1{fBM*8zX~#kkH8I2kGK!*j}*sBAYc# zmn-LNJOnaqG@i#7Dt6cPgoRz4{=M6-mNxZ_zTI^_;cqvuETdf&V)UUm#`WCed(Tt4 zw=MexcX2mz+ecl=gjJNTth|caChAIGk@yN?cU`Y6wh3C1uGa=2QeK8l{o?Iz-Z>C= zHh0(c`@A4h0S_D9`L$Jjw`+G@-}x%USXM`0b>!-{7k(`5LfBnvFYj5WT%G0ETdUJa zw|&&p>2}xk+_}iPeWzf?zhSfUj+?H2`|=Ovv_5d!P1Dnbk7QY^%((Bj?SmQ;r{3zO zt5c8A`-*!Jw0htvv zc2xB7TVK2B>Q`Rz{)xXasw51lwbyh>EEYFQWu+5hw|$VH70Ynyqn3M3SN>k}ln>7M zFhMKU?C4`qK6G+QoDjRa{Gb{qpy%o_j|0n=$7}h#GWR(MqRpe)iKKQaR~w*xd2XH!NN5 z8XH~Dr$6V0rTa~o=6@4G4GERH?wL(n2?<(7Nk@N-)a`>B5-N4w)tmZYJ{F4`#(Xfs z)<>(Ugi>-}8Hqtg#J5nbHQSI(m~%R!nI= z=OnZ{Nbj;ueK0LrY0r}0Uz-xz3#GTtq>+{0Cv#MjR+39sKCB@je|iIL>Vq2PL+|(P z-vRj)p?msFLYHxZ^b@VYrJq{a2MXPQf%%w{W3AKFp z;7Hv*NYIM?Kidu_I2veIhht|-VQYdK657?_a?7?ukD%2P{^bG7Q|@+5Evo=hucd~B zo-X%mkOZyt+_~RMWaa)`ccjFa*dKkAb8AS{-7wpu4+&avbZyIu@oGo0`v>z^iYdUR ztVn1t^`s9D8WWiot$6j?`k<9|b$eu(C#WIuw5R^^IL5R-NYF~V2wdtdK@AD{>yL0G zXr=s3M$ueW)TnelQZuFbs7R=0`?CSlq7_?c>qG6zcRbXtvMtCOR!zDS!UG^+62@jdrnD zZ95+%Xr(bRcD;cZy!LS^%1S$=6+26P8kOsVg#0awpR3y~Kv;%zVgZZG9=63D+o)Xk({h*!R`;Ur*)+pKmKJ~$< zXr5g!dmUp4-t`)8O zW7x*O!-hFz&L=(!rn?_CT@osVey=4#t4UOYqhg85hg;vIbjPTuA)%Ue%P+?HKf{Iu ztu(jydlWTVGq|U+3|k-6kWfnfv4jMz*g{($>b0@=IPTELTiCm6-MK&M<$5Cz{RxY^7&9PHFTpY!kGa_rd1|im&w!G+@(W>>fv|G5w$ENKjYyGLUpEkC*uN?8Lv1N#8N_WUW zB4~BZo1QtwJ|O}~1T`eS^`=wDax2F9KP^G4cO7}kOnor7_3VVW@6+UbjEW-ziBu}( z+=lIufdsAeg2KCF{SyaNGuj7k9~fgpp|?~>O4iJ)?U++505Kd zA~}ne=(I>EfBo@_Y0*mUcrqsDsHjo@@VLvAra5<1B-A%OU(FM(RUI)}LhbdWgV*QP zo!aq@Px#8eV}(pYv)wm;@@sXSSRBP%8@sM!u8rN;yZKx3%{p-;G*ZXDl^~vY-^0q& zg%>QB_dUFQ(lA7wd!Kfj?tD}lUmc0Y-Q#}XJ2`gwo{!2J5_yKZZqY`S@}jk9O^a5V zSAO^hZq^~F(HwP`r`|kUF{M&W`9G}>5_wL%?iL*%ZCYvOELQs6r9SmhHI(n@Wiwz29ZJtZ5@3W}BG z)6c$BPFG|5B&tDmPL2A93H7uiuM4_**d}PDQM=NG$v!lnyGLoHcE8hD;uf0ilePYa zjm8g`NuFy<>57=-BNNn+&}i4ML3(FYDv>6t9Fucy4GHDkBT+HV|B2Ey(OT7UEKGwN zHcB^6d(wR8Gi2g!)S+`uLL+Lwm9VU6#ZqshVkv6IaW7&@kpt(08WMT7>-KXJw9@Y` z!_mi}`ka!L%*+ABe;`J7WjLjLq_KtCTY zMOv}c$99#YqUKBgv`l;MV#gla!bl`x*ib{_@%LD*wCj5s6$x71_P19n?JS=XUpede zQS%p9A3vr$-`c4mar@hyFy^Vv2Z`3|#AyxYoTs~LqlUy2mM6^g4-&Mx^)H<;Q-eAo z*1OwOK6)QO<)d=bn+4Od;%IQ<%hxOIIhPglH=lD7i^Xy28^A%&6STVc>Bo)!T7o%z z+EY&$%Z(+Hi6J=62DNlaD5ZX{B|)oqef}}42j8-{x0V_bs+<0pNP0t{tcT(gLL(!rhc81pjBJa$;A+Eh7I4~s9$PIcMZ~eA)d9f z?MTq7ei^Dmgo{+?OpC;C-S)uDdY1&P^t)@bBp<lzaO@nze>^&0i=AWC0awGer0Ss=Ok#Q-^XZ6`ub1!u!e+sSCjK5 zDigHgJ56w*R)SL0`1s0`Vih(itI-EFBs5+f{_)-#jznvvF)>QLjY@>?Z2#)p9=_7s zXqsR3dz|mIUAoke(8@sH5ueV^Bxt4IU9;1utRca9ex9I}e2n!3q;0z-w1#ii425b5 zT5&A_7pcy_n%)NV4nw^S=sn5W_wHv%EkO+lrPSXENP<@S676IsU~)EW^le7(W7pRl zz2978Oh2kme&HupXPkXhd6xE{#(e1O2+m*5#}K(0Hhcq+=`y9TH9-vt`RM1I1g-R) z2AA~cV^GdnCi=ph_dv1?MCc z32I2tcP3K$`qLa$)1sA5^l)1U+xS<+;j3HSdX?*3-x&37WqmQU*&SUlJ^!d0wJYzy zW=iuuNT@{m`@)%4YjyjT-wVk;hVZ17{*R1l=^M5W*b#L{EmsDaxa+ru!e-n&Ev{EL96+e z*o;xBjX5f|{MH9GYLzC`jwgLEp|P@bK4_(HBKP|_HTov9#}fLUkBWr84BQ{7nHH@$ z+ObvLY8mkg?N-Qm!6xiq@hs_SyeI@e$_GGu~Qx}U3iF|$MpPw$M@v|8eQOWomV zqM8u8<7_KEWzc=6hR9J-qkG@FyS@LYNW=*VTRtXH(Ml)jOv)+~twtv=M7pXcN0|9+X;p z&4*gM?$~bUsd`WiGIkQ`X}YI4%{d8LsW#2>38WL(TuBS{4 z!3`S{trg3ydeQo-YDlO}_v@Slt=f@~K3G<4eH@jl{q}f8LeErn*K=CBOp8_=U0WaQ zIl6P|F_?X`C8!~xySDwPNYG06eEWS+*L?1&veJEI<(4&@qZ%T%m_OX&lylvy7Qs?) z^Fa*>m9+iM6SU&E(h`haId@c(d=#v0yChW7&R^?;Y0-*3EfYg9XTO!k<6i}ig_LxQ8y=wnbm zbbg`cLbV2+Oz5Zjw^}~(=tsP?cXEqP>$H{5;WVxH$b6?b`$*~QZ`deZjp_0se;TbN zAA99hNB5t;GF_cBsJU0f#7DSDKBys~lMppih%UzYKP^Ekr8K!mHYgvAm-&cvdp?-1 zqSD;td`x_#WFjhSNT@_yZs9NfZ3$Ybo?PlJ!Ps^BrK1X~UOuQHp>s6*rAvZV^X-Zn z67uKzk5uE|VMBseY||~F6CE{gs19_Zqh=k~N7Hr-*0vH72M+xFv6E-QgIl}%ht9Ip zI!-%+aECD=PjC_>G*)3PE#E0u_5>ya43)3DL$keX?v(K(Y^1xRN9Z=<4ygzBU3 zgBsPKV`ob9K1is=xZLImT5&uci9xM|?ML}=|6mIpi6pdrkc7(6J#C(#mCnoT?7M<&_Njk;$7W`Y_Liq>=+6$x7D1aqwj z$F^IrVM7fG$&)8oIjU{KRyw=g&%fHJsA0O2{hVqfvX5=TRywg#>$_<_sA0O2CnH1l zu}#=&e?5xncI!N4s9gcjiX%oc9RFhe@NRCEf>wUYt^9c(NH!k=3c?x^%AeMB)3Rb( zw2C}omqp{lJ2^qkBL>sHLlAjy??K zb26y;tl!6pqJa=}h*3%5fuID06&WFg2%IbD2pTnT%Up_}cCE`+V zb50EjJ(csx3nP*I#B*myq9<`a(SfBt5=m%lkc52n&oy9Lv{Hoq(-!oc+@}Vpe0 z5_&T3Jk1ld;y5-EgT@k$0J8GPDc>IRMdYOVIu5=p2O>ReLeiXADQ zKUyn)(*}19a?bU9&e#2V%HTT%+-F@qDCg9W&~u{6S~UA0L95t#hP7yMhL6MJxT@tjOeOP+3t!LMOiWSA8UCrJb35AJmYz z^Nsgez2r03)z#}5)z*o&DYvn2e!r*bE=EFa+Sd$9KK~8MIn$z5{Q@9bV#3nh^B=u_ zdE|jjE_V`=T~Faa<~_nz^*e#^kqK&;F27tb`jDHv7InHhG5vO5d~<0TdcteDGV#>X zn)-!2y~FEo>LIG^gBlX`>wJ3=wBpwoa!f-+rl>Ame&I=P%CVpGiA$D8y!4G()*60N zgE=Z{NE~t9#mmdi>0NV@pw*LabMf+Fr@p?FTSTOPht03N;0U77qo!4@L|<@=*B*jU z4Z3_(|1Rk^=Zi(Hwfa?>y=sv4LE^VBf7|liUvyijUfMp`TGh5t?W2__s_32XSzWeV zJne0f+w@=k|7L6-M6gU$gCD;5&$1Ouz4bv2iD*5qX?-L#>fH4~E0*-=BS+Pi`=w*c zr|*%N_)wpBUwQHREi1>Nc_;B z{pIq4f9<`A#NPSp>kp>dj1pz*N%4$-Z7U)1+%q;~ZI0$iXbD=i<9ub(X}XvJNPPCw zo0%S^5yxY#W;d0cTA%XQA4RDlp>yt4j!oOm`5-~7D23j*%cwM>dS;-%ns1d=tEq(g zqw7BtLvSt8Sk3l9^-}jv5*j7$^_cEl3!=5E{eO%qMK)}j(IAgqkuKYG_gBqr*Hm%j=IQonPH6$eanNH-u`Pe3GrM{_^ z_~@fxF;e>(l-kl;&;D+<(#UtW%l@rH$h!&E$B(^uQJ#!lx_sk~<>X*+RGN{UuIBUm zJo-C1U8Yn5%KwS^+&)NXE%C&EzVQ%I(Q3Y|s3D8G(>*K2AGY#AC+ zufFK(9Up8Bn&Dn{$@j9A)(ozvNIm{-+Z74TiA^ghSWD1K^HptQ%7A@n73Q?Go^w?D zYgZ&xR)=owv|^hsS;&zM8XtnpBxp6?N?21`Gd%jOF&gZzm5|W2&$U3-fAkLKJS(fV2hxY)jEj4-n zY+C7gmTB8t%}G06k}$LQsCs%RXq;t@G?dyG!FM z^1Ey8zSe$Mx61x53tDL}t#-@K5;-chSEofny+FHjMYs7NK`WJ&Q<@U>iJQM#zq^({ z?S0K4<5AJ}PQRX!o^Cy3Gd(T50#S>nRgMaPcmgbEvw} zzHP;>GOQ(1y~IduO-sCQsa>?woHH%87+Y!Yu6E8gM2all;BhJHIiYr$I;!~^w1$Ly zXvb;eBV{M@VS-j{(>dQMBK-{;)wA|+DlP3O)ow6H8$+y0RHu@-7?6R8%Sn910YDlQuT$}R*t-7rwMHW%H6jkT?X4U>{kc7@L z(KoBcoR`qr8l;uZF3}gEri4x(u|_58bh!_x%{etBR5#93OHiXacPTKXmY{}&+FQTv zlAx9Pqx(whgBqP=5wFEUJ^wxAU`V_3)e?=>$c`j)}BlPiv#1hJ?-u(-#a!9|eon?y{nl&LZnaMUDD| zb57s$QISyZYDS-KRJ7taKl&InGO%|lLcKwv+$t)M$0L!1wx5$wDd@X#{jzdev|^iX zeNaO}b>j%<30iTC8Hqvp(A@~#L07!G6XM#`D$4RmBq3Hy){v0w{OwKHNq^-2NF*VygsmYV*)_X2VJrEtJSD7Qx{_V9dlR;j z56e@+8m24RHM=)qEBUZIC9Gk(lk4+>wf8bwt9rj|^f9PD^en~uELm&1PH;VqL=xg@ zpEV>TyVUn4Y$YF-r-U_3SF%feZ^BmcVR=ee!*nIP)b}QA#cQf5VJoI9**$GY-wF5Xo^%@( zHG1E}gx*5(mBl#4skAwes>>Ev}#_A!K~VWYQ= z9Esjra_nkruA4S0YDnmPmVQ~0(6`TB&-&ecbLzty5_%)WYxsGBR(elna&0iE?NX!I zea*4Is7R<3e7!Rt6|Ge2lk2D)6*YQG%hziAi;9Habo5o2} zYHzNm)(15t)C>A$MS@o9U9Owf2Q})ou4ksy64a2;h|zCXBxuD^srA9WruPMXmBL=o z64a2;TcQ1{A`-Mx4ccG!F@&dK!``Wu?-7nE%|}H-y~`u`JV7h=;7km`4I9R*mgq5R ze^HT8%kPhgOp8_=`Nn*t$RaBD1C_3?wvgVy}9+l_p|w4GT$Z5#1LHjrZ!}64{hUtdCUY#>7T17tQ2-i6Y$*$RH zR3vOAAC{+tHB47>zs{K!t@QhZ7_f8xg&CfX0kkHc%ow(BY$oU{aD?JO*DJu<;qoPL7LUgjq{-YwH zXCXR^rSUO|idOO5s7I*Q+#2*;&FxAx>$Z@R9{=K*mo+5x9M3IuG*3cH(2A{RO1RER z$ls*SM;|6=#a7w+U>nubSDiwm65U@^B=qE0=gUm%gK5!9&n9)g%#`4F$<)R?t|%qT zZ9b?W!4|qV;o4M6mZyX@On1IrF)do@iCMqxQln>S?jKBPJ}MF_-ANxzXxkELrMl_& zbJmo6=p>;1w-OS{pRO*)Iv*l85tZ96tyI$fz0El_B;pBX&j&Rc85{{yn)g9MBausC zo}iURzNWPg!3`T~G>W|EZW($`;on<=nr*`LJR#avdScf1LCrQ{y7fUqvaPsUZV76(3Dfh0Xj{#% z!l~INOt(HrNVb*QZojOk*(OZ4K1i@na5dNx)R358Eoqu6*VLz z_jA5Y*h;@!Zu3D6)0Nzx2e%1Z>37RhAJ#Bk$-V;Eo3NF9Se_ErFkQ*M_Su`Tm3&y9 z64o%?@Yg%}i)qm+@-avFdXR+V{#7c|qLqH1C#)eM*>_&1IVWK&`LH}CtZCDI!E$-u z!#jJ5+O(>b`pqe?zhg@bT4h{&_un0RlxX)NeFejE8x=JqB=`HrHeoCMZh7j%8m24R zyE&R`OwaN?5~mCA$~wP1s64EKdn*nC_Qf_ zs7&Y{iF-~wU5YiXo}PInJ4Q9gho0B@x>isAyb9ypmXR2JxPOq)Q){mP=LuTrxmy2f zLeEcq{i>(0zWbs3KF;6hV^BVrmY&`Dx@Ld*Afac4zNQ*|Bq5%}Ip?%e=}xZIa#YmB z)7QASu)nBC=sDiR$0RCRb?=d7f*KOK!`ja|30mp-pi4R>J^rOP6rj;leb+Nn8qJds z=bpQCN$3fGzg;mcTIp%O+wqnUw58Y+5O*V#(xhFDQCUMm{`%KZOp8{^lds#_sHjo7 z`5KTZwFEUJR5#5v=MY?!uJb`Fju@>EYDlQXOvaLgM*px6T5%-GK8ElV&(EEfdX!_Q z@31vN4GHyNm)kr+D~%XUeGK+Njm9h2GkwqdAQ5|idUw2-7OgZMd$h|w#;B;#o(YeS zOldwU653_azXQp%XrW@y@O-6SVBal44GGOF{isOL zial-W!>yf!p2+q~mub<8vt8@sl_#CKeEK=}%GaESfBeklSAXN)lk3lx&|2M5Z4>?$ z%se65R=i8m64Y!HrsoOKw&GoimY`;vFg;I*wiWMEv;;NVgz0%gw5@oTq9v%=CQQ#0 zqHV>y6fHpw37x;JJv8H;)Pl9oifE;~ZEiiS4{AunInurF{E(oPPPd+XwP(=$q1}GE z^Qd^W_I1wHZ!EV_QA0vCjjP(wo3w0goA#1~I^_U7BCpK(y$ z>X*gNT=OeaRX#JFA@rV`{y&?i{n|f>7^tc8?wa4LYKTR(I$Yud!Brdpr%iVzV&Z> z^Wc#W`nBwXM3r~f^<)b9Akk_Z2?_c5Uk`rI!H3`Q^z4H~mH8zz`2ex#TWu3+>1y$+ z^ZKsUnavl{_&(NR0b)UdR#jG1Z+h+}SG?-~dS3QHO_h~fzRw9_QLU5~tt=NG4=FxU zR;aNYUw*G|nI<1yf^V5tSw2$Ek11ufpr*>ZYrfSwPtdB$@{z`oV>F(mOf0CWvdW6z z;F%*@D--gO#*rP3C-PCPq_NfRntSW#30hTIDgBp=@3C{nn|87fYO1`uu6ygZ32OR; zO5tzc{@|Tg-~DH@4-!@0UDt2S$VZ=`6=e~roOa5%yI@*XPTxgtzQHp`(5lMvk?MP= z%pVJCs=T}AH-F{{T2)y-QoG&ptVT_hch~%O(L6z`D$7Uee>>{AYE{%!S+#az+T9i> zsLvCvl?nOyZ(n=f&NYv?feq5KR1}B7S&{kEJkJ7F(K~0t2c71(5 zM?^~ut18P!Y3)182Q^iW9;IF!`IsYk*PzPsk=7(T`k#DIQ{@=1^#8-h9HA&|Rb~13 z?`Pd<=Y8LMSoT3pm3P;l{K8MH&N%z1jzEatR zk3K;w%8IJY2H8iOmeY+nN^Ky@YK~BwvQ?Gkqs)WZ2Q^iWxmImCe9RGQ^|q?Ae3aQa z`=F-E%DLwD6N`^IqO~$nd}v)#%8DAxyKAjJ9O1Zc!(& z(j|1gW2-9XsNz~J=YyIm`+CshZWTuV)rch~j%=i3A|eM0Rjtr<36 zGmxmVtn{aKiF}Ztrca3ei5s4`x&ETxzdTtFB&wX|+T|mUe#A?!Dn3ZG8Zog#s=v#} z6EAq~=5zn?Lt0-ARdXiNjr!2o68RvZ^0B7UB;=#i;6eEyQRQe?8e5{y|2U1HpB-Y= zciy?nvbsAn-G{ThyZ-8HmMfk85>b($rcWrU_ofl_y=TNd84^|AUBB+&a-|bv!v_g! z`h?(^f9ao=>BOuL6(1z1=@asClS?1F^TD`_vmjCB-Sy+|v0CY5 z&&US}YWjqHd@QY${^R%OyEqFHRo-3eJE}TwG<=YtrccPn4QZ_U$8rTpqRKjBQLZL4uk-As;_^#u>+aHtv2bNK|=ued5d4 zE1mfoK1fj0C*QQn zNJx~jI#|kTAW`Mr^<6)79O@&L)ksj&C*&j5;K5So1Boi{rf+Q>k9I|Znm!>PsU>bo z+Z{+$d3XJlvyMmqAVE!^kdM@(Hl+^^B&xi-{)?-RM?WV)O`njDG%{?;STc~P^6vWf zw>tsj6$xtkgnXnCZd1m@fkc(ls&9G1s*bxPsOb~(kw)rG8QTXERo-3S`j<|?{6T`6 zJ|Q1z#@UoPY9LW%Ju5n4oV!|rnmz#^`K|$pDn~x_ZGad{N>rIpy4LgwlvQ5!k*IRi zhtAgzAEm4^q4Ke&Psm59!3k06XjeM#K75c+JzLW!((e+dX`cPQvbWp@5lAvVsQX-s^#7F zZ{7C5>a5Fstwy5N^a%O*X6k=$D9`9gR5@MOKI*{gkDlRc91_&@3Hi7>)%pF)^&p8V z@2=wnqK}p_kpwk;LOw1_{cq>${8WEIqRQ!+@V(Nv2Tr-V_#i<|pOBC5PyO#R@l=07 zqRPALqpv!0b=wO+R(z14rccPnH&Xxma=9KPQRQSc+<$fR3-xU;wJQ?T^a=TRZR&rQ zm+L_iRo-1c@aNLW^(X2468Rv}XvRoL$j7_W^Odib>p>D#-d+Fgk3VpA_{Z&o1T}p^ zJ}$;{XA)JG)q_&Mxu)cU1T}p^^rO?&-K)zJcM?_JT_69c2O%FMT8$$iAs@F%S9hO_ zvKmNKd3Sx)TON%1AVE!^$fc0_U+PsG-Hjqq<&K%&aK>z91_Xv`lZ zsOb~(k!GAtnWF|0RhHF5Fn5ulrcb~}o@+@|Ir4GZ+Sh8uM<$eR)i@FoD670?AW`M0 zk5gafYn)P6nNayy(O2mS8P zWrUj$m5y=uDd+uN@j*i4;HViRAt4`Sq|QD_R5@mY&)v;FNN7B_rccO6nQ^iY5>?K* zO?}WlNW@GQnm!@A%$!kHc}{g&n$;x7eC}vlLi20Y^a%MVD}d~SM3rNeF_wBmXq{k9 zpOBBTlF2?uR5@9tRZVSIB&g{V@=;b~QC3WAlw+OfUeFR+w~d-EAs=OBnSGF`a;$gV zn_EKbPiy*we3TV(_Ccb`UblO^A`$E8(DVuUNF$uC4f2>sqRMgo;nB4vbUk2ApOBAo z#gcuHsB&CK)megsu4}C66Y^26yz-1gqRO)JRhY&r64dkw(Yk{COnE+7zpr-Yy2^19 zUz`LjA0%|%iZy*gK7RC}&)zxv590YCi7M}|b>>~1RV^PRsOb~(@s3pIFDci9B&xi- zu3rO_4-(Y$3HeB~+Rk<5`5=iZ^Q&+2K|=3F#i{#eA`%kvabcR#jw#OvNmO}vtrMZ* zEPweRK~0~KkM-5J+4-w-JxHR;yK9|U73XZr2MKEWgnaz*ul~a^|EF9JlBn|TTBm2l zN#OE9f|@=dAOAHyAN+@MJxHR;yKB975+|k02MKEWgnaD$-X#xtZFxROqRQ!;_v2Ts zIT3@BNENXp_pr%jA zN2ofkc&e z*E;{qy}2c*=@asy6>=F%1`<`~Hz(DuNa!rJ_y)(Bh=hcEq!DgY#>9a{m3P-ViLH*i zB&g{V@{vaBO&Qw<5>-xnyvFa{DIX-L=@asiW}Ho#qXrUH-d)%4>&XWRYWf6xqdwyM7AUJssC=yH6Y^1Na6(kt=ho`0q4GgO^&H>e zI5W2le`%xsE+3^O<~3Z^oLSDpjjxfa9mn@SbVD>?x%F)l`3nlVF zLjBH~KB0V+ksWj(3(CWA7!M@ zK1ftK=8yP7g?y0Ecy3LfkdHFsWFI7|9P?m&Lqk4DXkN0WPZS@TYqJj$RgU@G(T;O% zCN#fV(Z6RhbI@{wv#YoF|cM3rNG<<`>@TJKoXC*&iwM6Kbn z4-!?5b)tJgOK9C@O`njDva-xRNK`piueG0((E8JwJ|Q1zWYC&A`yf%}ShssrY6-2p zt?3i;kw!RO8{{#OM3v+E!=r0U=z74KJ|Q3FiY5CXQRTRf@+{F3x~{RNPsm5P^2##~ zi7M~nx-E|-adnr8dVO|gK3hHfk&ur+NyLku=jVebFArRIi!x7GPIsdob@K9|kN@HF zJBe1)Bjn@r>G|L-%YIQ3RZedS9eK*~@t57Y_#i<|pOBAtr#gRnxgI1@<=yqS-gIip z-|dPI64dkw`S?a^yI(BVgCwfFyT0a4&s-k=wmTFbB&g{V@^OdseDDM1`5=iZr+qR< zJZt&H`yN(&kf5ed$VbYot_Mj}SysdH$m?__ zpnQ;^rca1|`|~fk;^pBZ?H6TQmec+A%b#D)9h46et)@qmvN~AGY9LYN-E}?tvy|0H zP}3*mBh}!+Qs)DSD$B}ejmifJYWjreccuRKgK4j&olAxwf$j1$-|Lw-!kAXy$ch@@Es?HxIsOb~(k!GAtnWF|0RhHFRn7c?& z(m1OY)V zHa8>7g)~S2!3#uar+)R+e?R|vcfBXavld^9_j!KxulugOt9EUr#0e{_I%jYq!%-h! zbC<7d8m+7RFaCfktbIbq?o5hNFL+cb6}<6CIqO zy~;8s&}coXYB-VM=(VSx{*O(=3HqHZV*-sfGE@yGGK|*?R^NO2=bMHTZW$BMZG@{D zPGmU7-Oqp1XPbr-jDu-WN}NE0y;rO@lreF~i44c}pC7373 zGA7U{HOSm&K_rdWW!A2oaLbs0ZZoo0RvwqaF;7%4=n3X+X&Dh{w3%hqa3aGo-&Jq! z3Fe=&j0rT#$iSSsYB-VMn73Ivr2vWy8d+DyNWiB4oV?mslT_5}9>vWy8d+8s;P za3aHTAC*@LC%CVXWlW&a?!4+1$B7K%rMocZS5CNPOhEHIh9^0UC0Ac{>K>=TGOx`r z`(97oga@F@Z)|!`Us*Wlo~uM26YFd+HwN*oKA^ZW$A3@H~bmYiKx;VfG=P zy2p9Eq2YvE#snHXkKqX+8ct-G{nYo|f!xLLHoX9Zy+wZv-=fk1lgj>c08a$8T$uk;GWSD*W_uAw9*C;C|+%hK6 zDC-iBVYLAbCo;_21NYkF1lQ1T!YyM0jj}HBU92{s;Y5b<(w9CdD<|ACCYr`gO=EH* z!@U1-n&pGl5)r*cDRH8e)yY;?<^92oE5p3Ua+=i#t3D#!GA7VqEvnUdd4DkD%J6=9 zfAHScuAFeom_UOywbpja`-2%*hIy~(-qt^yaLbrLgSEld2h00|8CQmRKkDAr&z*3~ zm_UOy&Nh~m_Xjhs4D+7XeQdmP!YyM04c2Pgm{{H)%(ybl`)c>Gan}jAj0rT#NPW=8 z_VWH<#+6~-yStBFKb&yOm_UQI^LC9Y?+<2N8Rq@L`^?v_o^Z>UFpYYxbt1!&555@? zV@XR@C5Ts+F@Xl_^JQhG&KaD@aMTAUr-z0Ul#eW90*zLKRl|u4N4w&z_0VvFdX{BO zpwU|5E@Pq-8IJzJN$sKG1npIpF@Z+wQB}i<3`albJonIWf_^8PbGWMEM22IYs9w+$%-duc6KIqk z#ay&%IFaF)@2WTV1oKZ>#snH=WMEERHJr$B%-c08^#t>1S;hn!WrXA2ppJ=7WH|0W zG`jW#_XDzw2{g(`y{oa^i44bml&%sz!F`P^V*-tK=T)ybPGp$(2lF1TC)_e7&}es% z^?tD4L0digDdW0-v0*$s}QuEaueDBOIPwwS{Atf#NmV6?H!Vtu6INDrUgAWCqdwvrLujvWy8de6`Ps499&`UL~C1zDAZYfkwOYs#hE*GK`n*!Wc`O zaLbs0<~%1(f?{mvY^YOq&aKaPGQ7X$)TX<>`hxb{#|gKL2{bs*i4(2Ra3aI|Yff!? z#5X*yX*l7QF@Xl>IdL)<8ct+*f6b{)$Bun}({REqV*(A%bK-aL zH4P`+GA7XAJSR>{L&J#-@2@$v=@*{&Kgh6K)w3Xq0meAHxZJc08k~{Z#*)d24DYWw-#5oAC)_e7(BQ1s zHYQF^WVpN&SI+m%an}jAj0rS2v$l=xlM@-Q!IcG@NkDm}nZd zKIm~N9M^NDcD_2-RB?Sx%ZO-Y#hhV5Bpve-mHIr(s08x_S;hn!r3RV%EQq9Iex=sa z6U=vH853xfmdG5gYB-VMm?x?i^aS%ZS;hn!rAILrtr|{bIOeViJX)49fkqkOxHqU{q7xa8`wxw-J;D8eEMo$VcE?gRoXBw8N9iij z6WrIxGA7VycV6|1<3xt{%l@mphwBNqj0rS+_a|@sYQJcP_t(6oJKitqmN9`w*&#IV z7j+`T<+Amf!u+)p)T8m+_EGt$#S-mN9`w+j&+soXBuFJK=|Z!uq)rZW$A3 zv>kL+!-))+y@OA9mW@|VxMfVBQO3l1zo-)#-d}TmP>#D!xMfVBQO5Rpzo-)#-d}SL zQeHotaLbrL!}p6ikzwXn|9-x9^@Ll-glW`ktrHoJd}vqCtWgQ#m1Rtz;k!Sb$Z*t$ zb|>`&=QotHR~;b>RdWz`eZvn*o*jn)!(xehv!;piXQE!GpXS6Rjc8m&iF z4JR@j{am}=dV+o@%a}l;jSN-8i44bhrQLfy!T2G|m_VbAa8<*J49B>uU5GuwI4H}Q zK*M)`I+5YHe&lXSCm7FV853yu?oTH&9M{3|eo?MVvW$tQG2ah5k>R+WE4B00xt1>1 zS6RkHE30|Gs1q5Ed5KDWo@G=G<_WTl2{hW=XF((#^DDKUo?yNs%a}l;&B&^T6B&+q zqIyA3FmID(OrX)`qE*9*499#|y}2itf66i@&}eh&s^LV2W8SV&sVA66%Q7a=X!izn zOmrf{asQ#wwI{eAkY!Au;rm6M$Z*_8=_=6^+}Fr5CeZNxqE2L(=T~_T*As3T6KJqs zo4(H2PLHK0u{R>a`)hg`y*TzvIN_Etfd>1v8G+DnBE$P@dKsfpXgJ}PF@Z)qL#S#v zk>PUYa(NGcQ8hH2aLbrLqn(9xKt7zvaCyF4-e=(I5E@RnWlW&aPH3tcPGoq0O)ujr z7aC5uWlW&a&ZepwPGoq0O)ukW9U4x!WlW&a&e*CNPGq?3(=YGIFzW~nC)_e7&|tqd zb1dq^i42#vTi*9!_7oaUxMfVBQQljc&lhzf!(~51dFPf{U}!kumNC&Z=F>u*$ngG} z`E=%kx2c#VmyAzt853ymju$iWO(N;?h1K%@Zq|nrZW$A3@U9y3Q8b*$a5-bEyuX|6 z$_clO2{d@;j`=7WPGoq0&GVS-A5OSsOrXKLgUmc08oXiJ#`ejH4DYXbj*-_7 zC)_e7&|oFJU85!^GQ7X$d5o@IJ>ixyVH)-B&WQ|1K9~iz@hVbP3F4JyOjudfd5IGl zj{0C07#gjtDna?kGA7VyHMk&>j&{W?Ff^Q?o@E&mXtb8NTiVr*6B&;F!7MN|oS?nR zGA7VyJ*sLrk>Tj)%mPEh3HqHZV*-sfGE@yGG92R-v%t`Bg7HI^F@Z)K;i`rc8IEz6 zSzu^5!8j<(m_VbA)K$ZY49E3@Szu^5!FVpqm_ValajJ$B8IJ29v(C_Pg6onjW1?xy z=ZiX#;kceFwe!`vri$yUEMo$VHUn4?NyofIrQQ?F6J!|^Xp|b9&lhzf!!f^7>*)#R zJF<)kG)haH&lhzf!!b`(FX##8ZL*9BG)j-+tovG4PGmUdyXwt7!TeK}F@Z)I8Rqjv zoyc&^+chfn1oLQF#snH=gqzP7bt1!Y|Dn;fC%7MwWlW&a?pW%$>qLg*K1x@Kp5VSl zmN9`wyYs47949hdp8ME6Tu-=VOh|*3ea3dy`dQhhKWBJ<%_=;r{B67{caS37GA7Vq zeV!c(XgHDK{WYub>{bX3C)_e7(D=hr=j^mV!-)**F|VJ;g&IhM*DW=0UAzZ zxSUm7_OGyeBs83G%a}l;eFL;=IFaEp_bK~u*aZ_BPPk=EpwYf%S~Z-=@cx=rcy{xI zh7)cX6KJ$=vQ`ZzGQ7WL6`oy5q2YvE#snH=pW6IAdM7fxzh)Jl-BqFCgj>c08fBl_ z{5^UnGQ7WLk2Sl*LcPGoq0&3G92~6F0s&PWmO5vN0u>xMytUEk#w{x zc8P_C6V$UTV*-uV5_e16-Ektr(LdNF78*{_US$~*XtW+xHJr$B^mBHJg@zOKJ6XmA z8f|2#8ct+5#w&J-g@zN1AF_-IG};JPHJr$BjJxa-3k@e22W1%(Xta^KYB-VMxPGup zEHs>8JeOrmpwX^4Rl|u4$90fhX`$f+*CkoTMAMkRNAE<2<9e>t&R6G}Dz2}xjEPoO z^Y`eT$Z*U{RO<6AqiQfukY!AuQEG7h9=#J8j`@{ZPfsx4k!4JvQCi~sJ$ffH9P>o= zf}UXBCd-&Wqx7ixd-P6ZIOe;y97veYMXi44c{D^7n44JUY>B+HmUqdg<58ct+5 zp2Km9U1&JLb1_-Q1RB2D=R}6%c_OFrg@zM6-;-rbpy8{1PGnfmMWx|HJf{rHm}naF zYM&Dsj_12d?fkTs(yi-*vWy8de6^1!v?4Mb`FJ;8HhS;hn!?a6jcl@l3`=k01e zJ;C#DS;hn!?FoI=a3aI8ZlGS!6FkS4WlW&aRvM~?6B&;65B27rU_C;XF@Z)~F{v6( zWLWDs>gP_xx=L8a1R8DShcU6P4{|~w{UGUBkJ9Mc6RZ!(GA7VyD_B*-i44cOnywN( z!8(^LV*(BCynKC7MAET7sB2eGuwEz2m@tict#u;9kq=H4Y~$6&`k*Xh!piC~r9O5@ ziHHnGeQ>H^XtdI;1mz>km_Vb|`GQC~+7+h?hK3W=vn*o*jn)!($%hjej{d=^f}!CA z?NydBfkx|tRl|u4M?dFO!O(DmekaSAK%EQBGty)(3U9>xsNSdtu%28G25jvHAWWU-G2avbrDP*!Rj;L}M&*g7tY>#snH| zZ|zC0A5LUA_V4mF)X;E(^?6yw1RDQTo&hkDqTxh_V;?eKbqx(CSf7_=OrX*BIv=3n zM22HOHD9L<4JTNimt{<#(e`Xt4JR@j`@;FkZfH2c`n)V-0*$u!ylOa+;r;slAYTg( z4JTNimt{<#(e}_+4JR@j`}Fxva%ecg`n)V-0*$gyjdua6h7%c%_YL@Zb7(lh`n)V- z0*x{c<(-DA;Y5bxy$QZT9U4xsgH4t((KNdE2Sp?u?|&$@^V=Mxs=hxc%a~|o)xAF` zf_;1uj`vtp>hoJERf8RcvWy8d*qg}gl2kd7;dmcMt*0m0$t}y6K!ZJ&%r4PzBE#`s zk$OQ-u)|Z9F@XkqMVVcq;Y5bx{V4V3o?xe{EMo!<_PjE?M8k;;$9rBHm3o35x3Y{0 zG|C9qy+0@->3CmFqiavFb6A!!fd>1v%N&bwcXA@b@!p-T5dTqt$uUa3aIeuJ{UdXgEPV%Q7a=Xl-}5)JJ`PP(;$vKlloDXgEQ8m1Rtz(fVN3 za3aIe&-n^uCYna~ z{-B7Y<9e>t&R6G}Dz2}xjEPoO-TQ+gl8$+aN`0PXR1M|{vWy8d+Dv9aBpvfBwVs|} zz9Y++K%>pbs)iF8j(MVbK~FGmlVwbx(Poxa!-)*Xd{@1>CzyZAGA7VyGvun_M22JD zt}&)3m`BSpCeUaz{W>N(k>R-i(CFF|+z-eyCeSD&HD{z$4JR@j_ffh^^aS@cvWy8d z+MQRu;y97vcz;k=yPnAVvlrGAVM5OdG}@UpTx)k&(cjrQulDB*$GJGyKRtf$3D)Oj z853x86 z2js(v499s(pT1lgPOv^N%a}l;o#|9HoXBvT8}&QymxdFp&&x6<&}e5!iagNuMSJH5T^?6yw1R7>A9Nzac)e@&w2P(Tgj>c$)0poEoyc&U52w`DRLulC@zSD{IMK>#J}uOV z497WlD#Kd3Gr^8RS;hn!r3Sn6MMWeX=k=-e^aML2Wf>D_u*Z_!XQd0)^F>7@9p?_J z7xV->JY^XZXs}n5-DhYxk>NN$QN6h**r_VZm_UO)uk1cU!-)**d{OmtC)mlY@oG$< z!QNeVpP}JIhRgHavR_-HYfrdkOrXJzVs@XQ;Y5bxTuxmjdV(F$vWy8d+DV>Vqw4vh zB9e~tMRo1!33hVJGA2x;UTdAmaOC3&FIl%Sv8AdK#4F2~u(Eng$;XZp8IJn+$it-3 zO1Bb}k1S&XjaKIiBI#&X?|A!OUI%F2$TB9-Xfv{^;Y5aGo~T~X6U^IW853x853xMXi44d0Qngys6Rgk6GA7Vy&&aBV6B#c1 zGRnRvtvdCDTgC($zS`$RhU06rS_|t5*2`rX6KMEqpA#9z>$E+s>GgzL#zfPY@9vz) zaC}c#shywJQo8l)@@Y{@oM>e=uMe`{PDF;|yU1A|?HO{_VBerDV*-u#WP3p*yC)_e7&}dKStA-O9j_*{f7xV=CIAs|VXtb4vs^LV2%QMTeUt7JoC)_e7&}b_r zRl|u4$9KauD)j{WYGoM{Xtb3d#>DzPdJ##NwW6|LJI7ro+%hK6@by6_G92G=*Hxk? z*tIOnm_WnV2c5_;^Y;79*RGy$%a|~YdaZRL!;ud?#ho=OLAX!&m#9$Z(8TTCM2`#t&J>1RB2D=R}5M+|{a6PcRP3GA7XQ)jlUO99ILa zh4lpExh!J>4PWhZBExu{wx>0{o^Z>UXd3g~of8?3>$y@pUu$=nk#T)Zi&El5E30{Z z(1{GkyhNow&l#!)^8{JO1RB0R=tPENex=sa6U=vH853yu`k)gTj(MVbK~FGmlVwbx z;p>A=WH{!#>digD{8N@OfrhUSI+5X+w`)}D3FgtVj0rT_y+Iuloyc(9e`s{=3GN4E z853yu`k)gTj{7KGC3=GU8d=5!8ooa0M230JkoRys;g&Ih2G3*Y>+~r4GJTKr{tTBr z^kts`y*Ty(IN_EtfkxX~TkqAJ$ngG}UdCt?8cw)nOrX*B2v-d!GQ7X0moch_h7)cX z6KJ%(&dlLUL{y^PsYXgJ}P zF@c7^4d_IM%igH6$C_DSXgJ}PG0`;U_XnNG@cx=vbLOMHn?cSew~Pri*we?{eUnIf zf6aYC)`t^r853x*Uz_c0 z8tfHiK8l7D8Qx!WSDF3X3Ac<1G}!aXd=w2QGFdh zY1F$rCo&xQU>4ZMD|>&Ccx4$AR#uNGWwql(hNC{11%^f|t4dHlvWy8dS`99Uq@!Ii z3k(e>sApNm1RAX+?vf8DG93MbSzu^5L3@>DOrX(vRMl`I!_m)~1%`$b^gCI`1R8B* zs2WaWIL0exfuZ39D_l#yY6f6$2x$GlymQcp0CmSs$!QAW7=d{HMd9QPj@ zU3-H20a?Zb8tsmyj=N4|IPRl#mFNlXYh)P{XtX=8dW~`-!~1sMrt@T2(O{&``?D9; zJG#(w0*zlQ_k&lo@6neth|10yog=F7{`%|h_l4CfPU!4UCwj|>K;x5Teg3xR#rdL6 zWO#r5yytvj_3RsU_NNnW853x{z0~=S#oTAdi45nlHW`|88@e}B_(!YyN> z)<-#;>ThFCz2iiN@%qy0<+n-WlSa5@Oh7-Y>_ECD?hQ&#JT8SxKVN@&_1x$GdCP|r zy=6q8@#*J1|1qVd)Ut9S!)1T_OaJHUul`aRPPk=EpmD36FX}{w@!BbK(f{7^;e=bp zMAMj03w0vHOtR^QiTtaLbs0E-mq(wcW{y4DYYM{mN7JvVS!YyM0jWWU=v@vmVBE#if=Rgo&DL$suGlsEMo$V zR)Y&7X|*ez%jrbab6Ca%8m%SPIkgiRj{b4whu+r4L?>vkvWy8dT92w4PGmTG?U}dU zlGj0cZ6)Y;vW$sZA2F6Jh@|m4W$&r?kVYFzD&dwf0o_Kp1(9@&yU%;h&3PSU6s-i~ zU|N(CC(vjk^@2z`t_EL!KWR9@crMGBK%-r8s)iF8#*3?uG@NkDm}naF`Jzr_IIibP z?R<5vsp9&Y7Nx|AR#waz7DUo9FUeAGbB0PVPmpCypwVVB3nFQ}zO>4A<%Co=f}UXBmKLSN2{hQPQ)IOed zu#5>b$_U53K^+sF$Z*_$Xmsrf?gwNU6SY3#9;a$Jk>R+H%Buveuv`Z#!F`P^V*-s| zi+ingSGM1s z=q)2cWyJ_o`t^0vz;e=bp1RAXm9#B?JWSCz2`qh~)eofPG!YyM0 zjWQ42C0p#L!+EsbPy%a}l;)Zoch=N*wWUN>61 za>6ZR0-AfM)^T>@%WWrZymG=VV*-soDgEzhF(ytqO*qm@-9C?8qI1RAXd7evx(SFdOqPDDM2WlW&K^BCr% zl#~-0j{fn%$NomsaDw(K%a}l;^{A@hM24fEU-GzLZyHX}?_?PhXz*;8*(LdKBExvy zxVmR)+T=a|5aDwq% zmN9`wyW&(0Co+r|S08CO;g&JcG`QBbvhuhTj_bKnJ71kE!SyvQBchd+-47;_bj(Y# z)Js{-1oH%0#snIr2ATWRR5_7hyxw5#$_clO3Fy)ichz>C$Z*UP)eCxpd0SeP5+~3o zJ<9F}lSn$|yXwt7!TeK}F@Z)I8Fn?6IFVt^+cjP}5%cJ!iaUYde2`9L(k!4Jv!JXG9e=e?3PGlG_-Gy;K=!9FwglXKw zmNUGNZSRK@ZW$BMZG@{DPGmU7-LHF*G@M`@Op8+D z1R8Cmt{P5cIIbVx_eNY0P(bPGmT)=SuB- zbtdN%*VnWtB~G-mn(ywM$Z*UuveZji%>?rVS;hn!r3SnEK@mygb)&T_C)_e7pxcbB z=G=)4$2?KJpeLBOr9~-m0*yAatQt;aIOeVi zJX)49frj7RIg#PG|Ip~#6WkBTGA7VycPxz5^?p!9(s3V^R|zM$uaRX;pwaHUxZ>3N zK@myg^+$H?a>6ZRLK@|sbG{$U>!9L|eBArtUufel8X|}{EhECps?Hgl$Z*uhdGGs& zrqRl(5|ocDV*(AoyK^GLYFB^XG@OWf4$GK8qdl3}Eunfp_{J-ONILq*_dN6OnuZg! zS6Rjc8m$jj4JR@jz4jx|`h3%Hf_^8k%496@ZOTEn*ss{4}S;hn!r3SnE zK@myg^#*HKPPk=EK$n)tGyT@CJT8S}o~T~X6U^JvG9u7uGs~*sM22I&tKQrb%s*ur z6KIr?fi;$@;Y5ZtZ`XL`M9ibZGA7X2ydTtfm2}*HXmsrf?gwNU6KJ$MmO4^9k>R+H z%BzGE+}Fr5CeUararGMIM27LwU6}3%%W7Y{s-iI;Xrgi9dM!Cs$Yh@&_utop3LOL*s4b>B`gF3a?ufCRMN5 z{U0T@f6+9y5$>gMXneNxrcbq&=oW?1IOV54w)#*1{L!Ydjc_l8L&JNNTNFlv`1${Y z`yM4P;&LyALxVh!GOo^UQ8?oLi!uxUA5CK$L20H}ghPY6poGzoS6GsuzNw$k+eWyT z!Vwc~iavsZTNEZCLd3`e&5EcZG?L%92%uA4(L^AxJ6+!9(&#I*|@una4&^JqqHgZa#jtu zD2&EmU-E|e$`JR1Bf`BD4vo?`4s^wFi^6CyC!&W%cpK4s1<`5LJ4ktjCF4bp{?chc zl)sG2y%g@s>SS@B+@dh?Qf~B@&}gL#u_G_yaxaBLqt#&5aErpk8}GMM;+t2*TzVB6Zc#YO>MyKaZ6laDW$TM@XmIVI zSD_)Vuq45JF8jwe!o3uZm`aagwXbTpMPc&6jFX-adD=#}m%^b@^1z(BYPdyV;*I&W z#;a|Fdnp_mr7pNPsH3P`6h?!2C_N$av5jyqg+qh66}^huaErpk%RH2x5E|PE_fj}C zN=xU?t6p*3qHx3;cVrRXMlcV}t7YE9ZNIy70zLXmXp{_3uH$Apm-tqRY+I!;rzpHtjv3Iw-bK0~K6B$Sg)f`^ryb|}j{o#AR^wC>uT%?=0 zq3`>Ev-aNkipONmClt_dixba(;n_VAKp}qi)yK+y{3zX@e#lvSmp_yD`9fn{x>r8q zd8^NV(`Rd{F2C_Vt!{tvr)&6W7yqZZ6e2kxGVPX>td{@Ym*hEUzK1O>R8 z-`zQ}&hO)#Sf6$5qMn$f!5bX$uGI;9CyF-qRV9DcN@gP7E8)$l6ZVGFfC!0FRvuTr ziFCr=U9whEsGi_`oOr`2G_JmiH%3N;EKcM*Mw^6N@|~Z5iAL-yk5Y(T?3)_oT&c=; zepJ%zt=}Ya_xOo&9@XF0u>`N&xxPub#feXy_P47iKbW_K4kO$vci?XlZgJul{^_%; zU;MvE_2Gnj<(mYX8lLmqPv4h9Yf|+;)2`>%31U)r z(-Zcd=uulc@8iUqr6=qS(3bO(BL1e`d?ORfDeWE3qiQ&j??i5vuJ=Lr^8O#`AxWgl z%ZD}=Z!(@(FUqQ6)2>^bh_(5!_KCG?Z`a^0p?C}TguR7r8U>xYeB>L_C+wZ-O(NgtJ5k?|jrV_! zI$q_QdMD~Tyzz$8riPDK`QDvc;#&t}Ny$umFD=p@Z;3@&-RnR9e*+@l?TYe=cfJlI zD0jt`Z*7rwy}(RLv?HHk41FHUJ944pH;RGD_&;soD2 zR7};s#Lr((xEFJuv4&fm;Jb~SzqGs#I^kY?O_I};W@4&|Dyeb{-?ijCB)mMP@Dre!{4aU#DUx~V}v zM7URe4|J1oOMcPwsHt)yzty>^;i+;jZ~1-B-Qq-kt8-Js3HMs`s40}DU9Vf}hO?uN z-maXW{y7!u@OI^1ULt+Y-Qq-k#dkC3PPmu1%3dSCep#*`^H(uXthqN->)B4YSAMJ0 zQZ>;(_%bCYeo-c9sNX&LA0D-O<^vxyC@W7%e%JD_RC!9A$S+n}s!E2YT_@ZtzgTHR z%}0Kv@TD^3kZ~<8fcQZgGOU$?+)agnRi_qSx^Bl3V3tdwsaY z3Cc}qi{W+u3cRu0WHQWlp>WZmPm0O%(Bzo5Ce|MnagnKbw{l8D!AST)_b^9Nm_r4kz zUJrU_go#OIxJ;ESPN1ilDpBI+FJ=HD+{^1JeBcaU?B%e}n*YwVLW zyftuDyXbT8tnqqG;VZ%|PB7+Qan{@KAXV{Wn&(M5_w;fF_?geXWlojqDSSnESvkSA)gFO zwMz}<+zIrab^gH};$XkITKhZ}zG3{*0GK1MmMc zF{ux#teik^JYIQRz1I^~|LbRdWKg>0>jSgJ2}(gDYM&~`aP=In)arv=QOE7do$y7Ok-lBihvU0+`{E2t3;T9*zpL+0i!o9e{ssHzcmz9?f#CR<6xVYA; zPk3s34YxSKd}Z8gop3KtVXxs9C(zTlvYl|RMb4+-sPh-Be*dM9sPnj>a=}1rfJMFr~i927rzdCmFw+v>l zPPo_0E_&hW%U^zY5_78Da>fT|DM&cHzTPqhWnM+zXAz{crc* zLZl_*Mej5J?xA-;xEJ|*`jrnE5N@HY&bs-*)$3@fa)P?~iMt2AEGy;1y=V)s`l$yE zQbkL=?(^SVEwrVJUJ_xhYKp1XaElYH8(s61pl4#D?K;tWO{E4mh=P{qyFdRQ=eR!n z&HrIe6=VK5Rc>)&XXmmxe{-s;h7<1f=`(+7SynY4Z$0aobF2Ql*IqjJ31V9G+F3&u zCqDSvXU+X_nJN+PMXEGP%tTF9Z@Fw9SB{n{a;}kxavP5&9+!Jjvr6rpsuJj*6gff7 zYISit(R=0EWKVcaQC8{`ea$8lGkvumC#W0s$Mh#39+!L37RLSDEw?=Gl6m~_n6_&; zv9oi@mJzOxE4}!ATpzt93G_4uFH@zs+{=4GC8prYYKE;l(=u{~^n%s*p8olqk#)o~ zU-k9v+5HPvt4Ews!;FdJ^>fB6c`>T}&?8PC6OpJ=gC3U?jF0EP>E45N11H?8Ug2(y z75)}|{ZD8pw_FYGfAO7byo~u@bC<77jXCEY7hX@g;qL!}d^myLcR%TCQe&8N_ac8v z?cw>zc*`~M*1K-e$hgwWOQF~BGO1U!TX*K1XH3cTrRxNBbKYIPli_i9 z|8YPt4yuhZuE>jiqnPG2O^gim1Jzm`+grbNb4daElW~ ze|6TaLC>iwff#o)uJq!%E4`k;q8%c{d(p|;YWbkO$oZ_1mLy1F#*`}ky|a4_OSfvc z#Rf5!Liz2u{uvKVxis#$}0WpScB6)CBTQt$KOgnQlnhcDQB`Gfy7^U<(r zx3^@xPrLYnEgGJW-+BM}b1UgnnCY5!-QvWjFF${7Z|P4BI^kZ&j-9{v-aohcnDgN+ z(c9S7SFN_>!!1ti?0nY|2=_vJT)Mp_<3;bX^{6E};a=V<`?7M26ZEJ{e`T~E&I$Kg zwD!4l*|Vvgi*I?<*?Xs6%NGh_WY8|nIaL!iNU#0yy`n!et~~Lz5%!p7q6DU0w>a^R zx9{ye^qXy`Q^U$gZGFxAptt;9!!1tG3p9>xC){g$|L`{YfImBL@9{qy?bX|Kui+La zu7CP@d$*oHYVA(+UgwoBvW*C@4=-uPM~!2Bs@&oPW96dG3p(vO;a;>iT^V`}w>S|k zF?IrPC){gs{g{GdPJRB|ei%#C620~G8g6ldu}f`wJKPgN#gv!_zsIHnJ8VwRcbNTS@f#{v-+qUG~Elv=gOQh4-B;<9@ zEoaTwL<35y+~V>2`wcx2Z$ZQu{>aB2o3G)#J)(W@J>gzIdFruwX0e@cixWFLyn!*A zSvuif{H{{yQ`K8CUi7+qgNBun+TwCA@;AOWpcHjyLg}h}DD~TZkS{xI&h*{lMAVIT zg_a~uk*sN#7I)(6Kb~9oUwYR%%-o>VM)59;L*+ybOE7%Zgt6u?G&y&5-El%7+s>JB$)R8_>pG z5$@$B(i6QU<7FIE3bzyP)s>qe)2_ea#9LZrra8Bmyl+n=axRM#y!*xbS|Fr1`$3R@vE^ zozLfHm7>A>b$a)WZ(nQ8oNrWX^*#Mb6<Gmah+Mf2t%|r<>)6ZI?K2*{>I~z6FFy^9Zae|uFPM%)F ziQen9y~V!1nyS9ev!40B`crWYCle(r~O6S3HKsT+WS?BDY$93>vyI8wJWS|F{u)>45f+|BZB_lX*8%O z+>39xclnr8(1mnXoF{I0h>Ca(0H8c|NyDKplquX@Y;MmE3ck9RHIlEgFa`*#*o@t=a} z3HRb1cfIvpeP_ZgPVip3-WiYBrSaUCe8ag~EBLLG_dQonx$n06-gCa^#T)Ae1uFIN z?u*XV6Vn&p>&MU4Q*N$-n#1=RZgJwrR>x<(p74}h_Q|iCHMXb9Elzyy;iu23oi!%% z;l$EwbRXqjzk1czp4;DTjfhYTixb4O?U^M^5bkyE&9|J>txZJKB_D2af>IbixpTt3 zDE01n;uIp&E;S_!HK=&0+3_8uTb!WvjC1aUdwJ_=nXdntcHQE{B^O^@QZ=d%C)~^1 zbg$uU^cSA~!*gHpn0mr3PJHNfPdZmCblVB{I(F>)&mBLxyZr|qeXgD^zvm;5JXg=D zy-in*DU_yN&dSh}tw(&rOeesctD<)u6YYo^Xp3 z)U4XVcEY_lD`m0LFfk_j2tbJ{w?1O@8g6ldx=~4QC)|trAGa&+1$AZ#rJ(z0?(B50 zUNxrrZ^?&SoFJ?_v1Nj@~UEFJavw_ZpjoyqHI5MR_JlVA^$y$4hu| zt(``Myu9D^8gB7;hpnWh$_e-KQEAqwsq(sIl+ftot!E~xhFhFKL*v+X!o5hL)+~C0 zcEv22d0VuYGisPp(EiJwaElYvEOV^oa~~(%i{HKuxZI21@A&%R#P<5|xZKOHUCUIdrg$SlVXxUrOu5B%ez+W zV^Fx1V-izjy_~92($1PTUgU`tal&4Pt(fY6`qFiRD>Eywp_fdY#HLbYTxUHMFVA24 z)2`g&1RAX6E;XERFR!P_K>2qYJWdfn`qc1}z+|m>8*fL%@K|VC9QEnO^Q-QK_3w5Ir z)nn=jw>ZI_(s*QW!o9ek(n!>6aId6R?e)(ck**~@;T9)|Nh9A(Oyt}(NQwHO(=$;5 zeYlg{SowKI7YJuVwY*ipNK| zCwO`)FOQcesbj(|PVDTQws-agrZI&Q`(E!e=fhLTTA}h(eP_ZgPWTC*5qtT!P`nF} zak&@TI-jE_+~Ne!-p6Nhcs}rY?gt-LOV?94Yml(I%R=?x1kc_t{SQHJC)|r??{E0m zBf>2_mH*=Vq7IIhs*WftG%xy9tHGAEJ|C>($jjSUpO3y>-E$`T7L!ao(^pxs3Lp*E z6O^a)r*u6o_hL0`TvkqO_Nehy4MG+t=$ngnRgxE}65(E~>5bc!rmxEHmlbAKu^1;^F-v^|~I#;BI3 zuMJM@Ef7RnoS^NFPXuzpy=eJ5fhf|002-cN+OE8gR#r~XZ@N^K`1$KgxA)5Yg>U@Z z=iCWK@GQ4vdZPErQm_7#G`vh0OS0CEk}4+{$HuM1>%+Z#)XrQ`R&H^E5moJYJKZJQ`S^*K6YjHdIngD_D@f^7dz4v(@aziPV&_0 zw#8ERk;R_fqn?wR1pT~ws#fBUe0W^$b=KG3R%Xb5nRO0P{>t69S)3p|u5&D^kFU7u zW2KYy| zUuTPNoHnAQh`(t!zn6Jp%}KG!?O)B`2Hn(fixZrft&)z&>%T?AiQY@!9NkP+er>T> zp7y4>UFDY^H&fMFj5zDqL0=z}QsqSNr7u=)YILcZzZ%)6Fk+X6r#-(W$$7u}>f@${ z6YljVdp9imN6E{y>lP>SD~y{OPPmu1w>}^4#n)8g+oI8S)k1rsk1L7%rs8I*oN%xF zLgHbB_X%(L%T#4w%U(q9itqD|G(@=9qDM8MzDMPkV*B3Jr^f8xhetcbilqwPKMZbyfi8o@3luf&gK55Z6z2hlo#^g1~^Q*KZLER`%=}*p`a4+gV zzV*GC55|x9DmxZ^mHp_cN`kR6W6E^(sdBHrL<%tlRn{gfz0p6uT(7U5zf{=Fxf5LN zy6a%W`c%1Bf4xeTvgT#iJ14l>jmHuvdasS^;G8O2yJmNrU!u9=ao35r|MlzpSzo82 zxZKOH5}9vGm$YAV*Wa#nK+fND{cq0oq1_NY;a=3og_pkK4hZU2aXCR-_~2uIqtd;G z6YfRJzvOYhJ|KF_jjL;?m;Vb=#ka6U(01SUiC-INc&glsmVePNjtJ^pIcF@91|!ip zAJIzUT_VQBn;v{^O$j6Fg_pjnPt`;X@^$$OFTJK(Xq9~Nh#4z2`^k5|vL{M0N1e;! z1Xm*3*>b+?ak&?5K`ESTu%^l_PDK50dRef%k}O`@cTzqsPO z<#V#!ID2uOr{8xqSc%?}1pQ{5Dkt2_YqKV&{WI;l#R+<_%56L0UfWv7{oIM(D|>LS;q8ani$+wBsVCgx1an{Y=Iw-g5tG{6l1NL&i=O)b zcEY`UBNkIPb0^` z=*ntB!-?LDp0=S;iRgpPV(}6`F?1Rwd0eA1F8888j`QIbCm7wx*HXg?_ZpUNO_f`m z;2OwSw$yOKz51Fhk+;8Tm#17R6P}5w4tVC2GXuF(R&H^Er%~I+_KeHDc$U>&&!^Do z=L|jr^w~g5Q~giOkbP#M5zgmC+lk(bJv!E|rr=0bTAbi1p0s-nzAR?n^C?eH;|+42 zGv>&bOss#HWhQu5Hm-Az%f0x0QG-P)G-PptXNlvs>#O>{2aa(?tALpcG~D8Z@21;M zxEC>L#dJx?;sjy+emEho#YxZ&i*q@3uB*q($$#UsSXtL%9g5z`3K{EOgtxCWum&tI zb}5MFnSS1dXHKSFR*G3wB3^&;PfV;;4MqmDIDsCke={+K&a_L~6&HDu*J3qeE-Ozv zyDC^)QwqoV@Ekh94hz;m=TyxaPPmunsX5pG#F+zH8F2zVR!YYjBHU|xS$X-e=BRkL zmz7(bVAXe=b0^%3-^Zov7AMeC-SlPUgnN0L-cGRQ$ci{6${qmL*1OW37#Y0nvVVb< zOT3O&gHEu6fK|*+qa?4dbN6D`0BfByQBuU;RK6?x9kYdeC|)o1@Qr_?f2h~89?a@E z@p>8dgj<|oJ(zs~bE+B^t9`0l_wthNHQ24eZU^FG*Acrp2z$Tj3HM?jmgwz-Tb!VD z7j<65qCS)l_o8mpV)|6Mg*sRHxOPvt#R=M*>SjCPUOpbr#6&*4{g89^N~v@;V$4Jd z^exc|N}b(YbDfv?`RfVy+TIe~;sk9$DU8_T-+mR@y}TDx-${h`30k6ht!sy`2)8&v z%h$DQJK-rxEC>L{?Mn&ElveFQceu7)&}rA-MDYFF(Bm3(ixbS@@0f5eVp84o z`EZL9gpWqZiasBV^oEFLdm{eC!+Ub!=(C%BK&o(YeaySr{x zA8ew|xv$j<7WdIw?cv@a^}@SC_5MQ^CtMFt{ly)N2=_umoqr+>89_3BpWF^jf!2|9a-&+A~oC@z$?2oS;6& zGfR)ly{Jvq&8$&VEv#k{?y$}RL--9a2JRZcKs zbQ&do{`yq8*Y>vS7AF{8$2oVxy}aKeE7{JwoV;amXa9*F<)_WYS-f!$IqxoM z$4w=QH-BZ;XBH>W>xck02=^i;Ok53r`n35C(<>U?qySv+3C`hBS( zi+iD=F+Y;y8nQS+SidhdWN|MvG+SO0vN+*8@Rz9);a=?O=l{>oeVS0r88mzGd8zm2 zK2>gUf~$eba692%#H89>60$f!Sic`m$P0~e+jWb_OZaGnyogDw@5@xl;_(vJ?}roe ziqwwQ=-uM+hTc&Kt^5&_R_KGPFtS|2L{d~0~w5_#IsH-53i zv$qp9OiViEXuF2TdpM!EoFIjK!+4o0kITJ0wSB5Q?L1H9d=cXHn0mr3PVoGavrP_9 zm3#5Ll&|_O37$&!aUxdxqHeYm?!^k0YPKg>=Tgf+Pc4QOvvDhN zixZyOUSpF`ZqXjsxm!HmVLm3VoSqN7_+C79;3@1=H@+~xtU)K-i@M=E>q~+s z|D2$Mg*61eZmd+P6qc!y#R=9$#_h_>$GyD0RgF?k{7t*GaHW^NqTJF8RR7@{|Hit3 zEKbk|RnprD_wtdbC%oq{%T!r;-|PvuIKeDarM{hTFE7KMaElYM-V(LBop3L23o|iM zAKrebwO9PmPt2`Er9KlS5Nk!UI6?hC`3cV&v_x;a?nN8>@&D!DCs9(wU#yJELft6d zqqPzz7$23Vh&}%8+m(BH3!RCHRC#(S(ewV#NW156CQ6_$D<`O%tFId6+~abuqvhNQ zT8vWIr^@4UFWRw6y(jz&75-%pQmZ*iPq@Vi=DT-HxEC>Lj)?B-Zt-{t>%8Y)W0R1VpQhat zZt-||=EF0Z-WP6d7+`Zmn9*K$4gkhA5O>%jd4GBi^og&XoS2XAESF5 zw|KmvcN9V+12L%wFLN%7$4gkhA5O>%4fWt9A&bXLSic`m$cx>E`j&A|xW(h${srQ4 zWh>t~|K|EUfp7g@^OOifk9(9`oZw`{J0{$VnABJLe7MC4!bcasIM#uSv+3C`u%W1UTCPVED2dWUc&nQa6(>@k5P|ui^m&!MasIM#uSv+3C`u%W1Uj9Ato^VSa@3yZ_^Tb^DuRJl=9X3yKq}OY>#feyT z7~Ro3;a;q4=m|ov;TBd;^vuCy>It_v!K%#op3@2U;%TJr+jRH9| z@_4tGmB-~?%-_cMwQh;kzPK~>n6{_N304}%8XlK>v4Yvvc_}CU;>ot|8fjO$2c#6# z=fgMtEju~P;skA4Pb{_*?nPhGbB&(x^s-*77Vi1$3AZ@GTCsZ9cEY{97tF*&S<$NX zB!$+lw4*&PE4Mg-#<;AUa4%A*x~ZuuDdMl3l4hmIc%>A2J%w-l+t;8IjFo!MxSen> z?<-3}J<18zJjc&0Judh15xm#%QHK2t8t1(&^n_cSVE@E8RZh5<*V9r%t-%TO#-;0V zxtF)MS!1Hky*1F<)q_2znJ9r6;gl*T=xO6;86KB=F|I70m(*0bh4D&HZak*#sd9p` zvePK>^VjFYy^hw}onX`+=iK9RFRr30=}1rf8{Y=x>2_Sb@)T0;?zPg`6TKw~-=Dml za4%vS-y68a3BpGs3k}WsmxL@HFJb+DI3X`IH0xgyvUt3N z_50z3ywK3Be@V#V@ePu7LS*(em|T@uWetcWZw{1Ge!oFm%Tn*+2;9f6Pk9JH?!7- z<=C+kD^{@xbH6hlOWfiF}+GF7s8yoB}p;e@=X}S z;_-5S!=2cY@VCbOGyz5;m0RY5`ITFo;H{K9CftjdRBlTRS)3rO-w!9`FiH zg!TL3guKvT2D>a>w|KmS$Aq7%;3pG6j7!%oPVk<_9TVVM0fV1LT zXmhHHH-B-82VXtKLaphWwY(X~mr7?MfI_&%3EG0_h&+&2-o{^YAUaPGh31_@WA5i^RhBSomft z;bCj91YZE+Ta!wO>Y02fra4uWa0_V{L5WDOC&)QpU)$6mPke)t-)Eu(sPp`mI|kH?!D8JBwvzj8d0Dz`Y{rO<0Q;aHJ0#}sm70^)rS-DwWIGJ z)Q69Ww06GUtNxLto;m63!-@EcnrSqsC){f|CQh^xPcLPqR2?nnPEa=*^D`HlEz!OF zy3!L~QG(uj)q%nV4RK3&&h$x%?jVk@ z^Uh+Ea4)Cx-oS{Gm+2tCcze9=9Ec~I$JhC_T_Z{XPX|2tl~=yob$p%gd^KV&t8;ES zYwy%+|Gex%IKE~t@8!>Ye+|dpT23e3)X3B6j<56FxyZS+OJe4~>0tNGciMaQjel0- z`qRtqR8|+>Tf@vU{N zWyJ}xn;K5ImzUvEBg;MGMeh|S-n~UbgnN0-&KeW>;N+AzA@=zC_&vT@o&raS<_V9R z`EZL9XWsh7)wpz>aIY&rbo=VeTW=ZUqi+qT?7jT9Xct0d0;k+0Z$?(?JH%sDTC zs6myLdvW?^eEF#5yp$7v)4|u@?+YuHJ7c5j`FYRz!b<%nT7XAozO+)R$X}dvd)Rojvy%jM^StM9vhHDodr|*!F7GB$N}!DT5m%nx8*`LcY1$;b zbe&)%8mG#M-YZMG)3HM?z9Bg+zECE@h;m^!{c%<_AK%K+LB-|6mOkj!Hf6F zl&VE5siljCEKZ=u8)!=nw~!Cs?>oAN6OlPBTgj<|= z+QmOIk1@T56Yj+>0+o7CxWx(d#v_~)?nV9MSBMxS`fb$rd37<(~}uNnDbC&wn?7DhPsaBECdOns_c z!wJSN_Hd8KM8)M^Uv5sQ$MT?nT|O(|@jyhD`@U>3zb@v(;DaxZ8-{p@SdE#!lp z-paXR>IqMk6O1z29;a=qFrZYwwp4(He{e{&}-2K7Zb6(5JbL+&N zuiamrb#u^}rs#uNithEYi(a^T`jrnE zrk{D>!v`8pxEHDV@|Q=1Tgb<;o4@5>kSZrAw=X>RTkjxM?lr8z))FsUUHAED)x0gO z7S8zCwcX;)AFchexy60@%%7TD21Hl7Qw0j)ULSnzv*xrfhyV)V7AOAhwU^H2)|~5q zdcwWlde$?y)Q9Ib&rXQvK3&e|RQbr@L@AYaZo}rt;Dmdz@~3g7&xfxGLY#HsBWpbq zQ&+lOs?w4KDU7dLwNy=k#M2KE?&YQ4r^+o(P=@hEt<9V}(R*d+$D3r z^O&}$%88wwOXfbmop3KS7Ij`yMr+Tw(9pOtB#KzHM8)L<`5TW{9+!L3ju&HMO_f{d z9~yT(re)5RDktchx?XK3daoQYdV=CpMwD z*2b>uxYovQ?BnIlC+#oUY>8N6-%1ca^oY~j>cR_Ft4EyCuQW_i=h~;;$GbgMjIT-w zg6%@HRu*6 z>NWA!yACv*a4&vWsV_CsQm(ZvUi7~ENnf)?Lxg*gzbD;r_W|LSdgZ*8lOm!v71Q=q zIYHf=|E7BnG(3myMO(-=mMUeHY(6U}W|mLC;=VOr#`Z<3ChFWR^bZmAw6ksvIu$kv z_hQsex-nIQ>$!RqBenV+V~JX5^)KH1O$Ur0DwBGxZKVsb$VVmI;sm4JxCUL_Q$>k% zsj6vG&Si0eoNFX%&hO@w>`!)|jXd_d-LX&yXl+|D3@I@;4sgJTCXD z*T>CKw5G}}l&D5(k7>@wB2`XMHyZP|6TMgVw4Qj!+xPa^Ez217k%z7K*!xQO=b!O? zd+Z-v-gCb5_2=yU@-yC3EzkRbbILk*>|1%|$<-eFwwJ`^?>&3(r>~6N0zrfZ1UuQ6 zgj<|I`_f<8*yB~p$_e-SrB9u+ciDQR;rZ~iLtK92C?9Td;xn&U?Xi1(nGYv=ukYHj zD{N;cElym0)oMvh(b|)6ukAT^ixcSaZooJnDn434w718u?`5i-aIaIJy|>5C@+I-<%g>)Jzw`d{=XkfbcDFcj+C49r^VH|V ziQel8%NndXFHhBGixW>?U9hEpIN@G*|KSU^)F3CsYIhsu!}|b~59P+21F3RQJ>fZg+Qk>l<>n<)i77a)23fjJ5YxEV zI^kY#{p-i?J^HIhdu!d|1a&hW6P<7`>Yulfmi6HlTB2&rW9rMwEl$u2RR7xv_d0g$ z{5{?WS*FUb0Q5)gL-z5p*Kmsy-a@w%?!_oEE-SYi+jMIop*%mp!WkOC@Wo2 z`+PXzUOp=IgqJ%SyoW;_c+K{NTbv+&ynDB-K__~z^UC+cjhI4dI-qYWE=CEZ%1gRW zm0O%(_Azc(PPmtkUA=~14T6rnif?(;*?YJB;Kshbl9%bgEl%uA-??}D4{E1lQ>lbo zoVexp9=&(s>OUTou3MZS+`R>XOx4&Vh8oBmxW$Q` zo$n|k>PW*0_c}aP+UrOPwd+1l9=GQuHRo>O{RY)qywk8zA2lCtabjoswq*@22>0?b zEROTvbkJEWUcS^cu5%~ct1syyF@?-@;BRo`mzv5`gYsU8uG-aiCfqB(3^gD^qSU#^ z<-|{(dTh&l*9rIHchzQ#J`z_oWN~6==a^lol_XlCTOc&cJi3Mm@-)6T@VMM7PqDX_ zSP~a=QC-OxCG@5Zy`ZZPWu^8gS)5?RxbwCDJx7Kqkm!RV+zX93xu>OSCZgYcu*Q|& z4?AAJO41Q?s%VL_IFVl&+swHW?#1tOYFqsLC;EphPSCr$oOh`b;a>hulS$A@tP~j^ zUv^Qnp#H--&aJ6U+?w zj`;HG?1X#qyJ~isDp{QH>-=`Yz0jEJ$&kM7I>8*in=>@3C)~^D5++gVoVNkB!;rTD zwI`WwOyiw^PPi9eqFw9+EMn6E-)7W4cE0AQ{pO4@<5Yd*~8ZxA0A5jU}$VJylNdW#I8h?Qyx6k9NI=kH`?JXCEtj!Yxja z!meFS!A%EF^jGwWWZgIkU!FIyE*ey2JaElW@D$N=b`QZFQu7$J)PA1f<{@qsJ zd(QW~cyw|Lr*+DUb2vrw9+{pLSB(-sf71c+GNz+}9-}qkb8o)oobl?b$ICf`TzerF z8X-|M+~Nc$A#$aFZqD^TJ>g!&w0K4~kq=L==Of}BX?VP(iffbdvCt^dM5<(Qf)Y`= zgzA`^5GUII7f3_x=y&)_IBkKC(u*hbb2{kl zgnMz8xpE1rYZB->1qgPEa3X4YyE(O1sCjUBd}ljLL00 z;a)x-&%{J4@%BSL)IYq1&O{0Heb5QYP(5us;a;4VIo?y`HANp(eR$3G8g6ld{;!(d zPPiATTC9Ie8lMTO1rm(Uc)U;(4)p><%E0D zA5}NKhW7*Vk@cKCttY%kIYGIN+m#dU#SRbkv|ht4PEfOI`P&Ki@*dn1UQ>(=I(x<2 z!Ukcj+6hJ?o%^z#=)Lrn!R79@wD8PQ@p{en8g6ldm2u^1JKnJVJ2}&WaC7G_+k)rEI@1<|r*i(a=bJpi{-_I(8o)q{# z>r^1;ZgGNjqQzXaYB=FuvGdI4qD@Hq$im_T&s{ZJ?o;J)xfj1{=DZ|iae^nqJRx4r zGCVH#;`eSwhR{S=xy1=id>_yHoNzC8W{x%7;>7)KfB4=nee~9xz0RrHIMKG`HulXQ z^)%g`nV?PUo`LA=-$c$mF89hW09s2dSb2K>wYRO#I(AUY-3h{~rx3t>M93?@6KEQh zaEr(5UoMz6kg0P~#mkB5_x!}`TFYRCSK(x0)l!!HLLTq%>YI9&s;c1@C-UojhY{}O zUt_3gnj&SS>J6)pKjpPG?N@&2^{X>q{F)kO4!@|unku(AaptYpuWq<8>rONA7W?c#?`gc%PVo|nK!L2dEBqp zF!u~&!YxjG`2HtXAAIa@WU8i6nhrd@&wI{wtD7EtZT0f}^{H};6ZgH}b*oRl`<1ED zFrK|;xw{v?kMrRcCw6wOE2VqQ7LAN6y`ZnT>u=uyK@F;WsDG7opYxrathM|q&0#g@ z_2I;`Z+z40ZJ$tENR_@1_FmZ*(mz@WsfynDCwn)ncAoa8$Zh#A|GyjCCkQVSYVbYR z|7P{_Qtvg~;zYEbSM(YMjXGC-xR;motWi_dm-`#$mhaj#vCyE;tFOFh{d-$V*W+@p zzHbtF{BJsV`(M9)9;qST^0^pS&V1%|{b}qo;T9*p>NkIPb*wUjIaWvL)b))QPedKRE zin_%K&bg-?yS7{N;e>ldDU8NlPZcAot_-f1`KGLTOA_=))qf?X;CiC-+S&){rRtqd zFiJe+@xyDa5xrOT|2b79Wz+vp*}Fh%msI7sTQmnH(a1$mL^O&hq9o9*LV(`A_t%XW zMPS4jz+>WioOpt{C@uqd!9>$28A7}yL@`_gEfSID--Hts5EMjE?lKr?MDC~o zgmCJqS?`)}?KQu@|LigNd-BbC>aA7xT2*VUv#B@eeOJWmbvmv<*D-rCUfM^UDknUY z*Zf&yu0JnZ`*W{vGckLTAf{==S#%vvcqp$ivxa+|pyq2#JWP0~vL?2a@s5<|wfRTv zFEh6ymDF&0CEY2WHQeLG;l9KP55?~{KKF6ra0z-`bEuqm_3LO?&EI_Gops;((evH$MgO}XP!~aYeDRMRjh(RGRb`w~XDn?|*%Xog5Z~J7A z*JBz9>i>!HTpCU=mw3pZed0z^<)IGem3y3E*7xG;K7K$$IqIRHZ*!NA%|yHUnES}X zbzJqvKVPprW6EofE0@QK$iqLIH5xb*9*Viow>-*r`&x?lYcu`Ux3gZOHh9gTM}5=t zKU`>dZD54^sp~)8LosJiIYsR8?_95(U`(89$-rj9Lor@u9peI|!7NO1F`rYaF0EcU zL0;W>ZTC=Kr^hAqlr3kT?`XXJF(2)D<@IePnlYE46I|bIf8irVdCYNTC@;-fWA-FL z3%=*)RvJ!tsKd3yONu$ex4k%egG;L=PO$cQ+bgTSWR5FCU0RuYyj+J;IOmne<)P-@ zZZHca$dxM>na^>@h1SJ2)h)_BPI%i~Q`I$`m_z+)>#wZUw$O1GhpSyZ*5)r>g1Qdc zplaWg!Zlf3`Rqx8Hm{m*z&XN0F(=~Q)^?0?j}!DtQx7+UmNO?jRE%&{FUstQZ>gdF z?l#lYC^Of$ypp-Ua)Q~JMz{=5UU^&|%E#TA@bp4x{P63W3HLZb3N;cPCOnkq$V|A$ ziKC;J9T+*C@KDgo=~;uBE8o1MJUri+zp0#N!aYuK53nAiobXW0-|Cup?pucK4sE=d zAnvN#JaLJ%#cqb?hV8eNApU8dI4));JQNz58H~XFKXFG`anbW=HhGwEj}y!arg`EL zN|7q5dnjV6bJsmi5Wi+0aRIKOxIC1XO@wX#F46mB**ZZEs1IHVp#GefG(1#U=3Rr+ zrSTQ{{f^VuoOe~NtWQ~ZD9+MyTJ|8(Q$>AMTu#smIGqbUUxyPOio8-xTOxPd^ws+P z4n593UtEK;iJUkj6gyd*UEC6$63#j6$`7Z?Jx*}?S~)#mhZ7!()7L7ePAtL2vt+tL z%7$~>q@6s>97&bvspXl8*Pd{Sc6;R>7d1wqIJ?Wq*@v6B5jOsv^U4WMopG+LPL<;F zP;;G5mH9fHK#$XawT7qf(<@sg_XRl-ikaj}z2m)wfP8!7XQA8z@0e zNMCyHIzb!cq;7rXO0S3VlAW)^TMlQNRhPV_&4hcL;9Rxp@nOP4ab8=kU?w;@tlGyJ zWYtQ~^_g&w6Y-Q-l~=9~p&rh!Z>yntHp**!)4V9o1oQ$qpl*i?vJP&6L z&lAc+HPK_53HLZb`EPo-hQ?T{>+n$C(pHTH!r#-*DoiKAF74gXPGC!W)#$16xI7fU zA135+VskPRp(Xl~jLSoP@6Z0jlmGDdV-zKD-pk-UD16h2_Uz{lcn1sLLR;H;i=V&c z%sozEYcDLq#=l!aq0r`AXsgD+;*^C#@$M47e?}@KB_RZ!c{Lze3)kqO|)-l{r=J zae{YDC>IVB9*Q?#@C~swRZDQondc(cp)&AXpEca$1o@`YJWP0~vX-=zMXHpGlsVt5 zy7Ursg7=v4&8qdvN7CjJ^iaIJgfBvE3En;;4>_uM{T$GI`c~InCp;AGQEg?`a1U=XQorIc&4hcL;Hl}U_ZirH{>noUlX{G;hCEK7cjLW} zhw`3i*6@}?`Sa~QYR09d$_d^q#&-kPdbNbo+$VY{Z)tO?+~WlA3F8ZftH!{hwkxkZ z6z?LdQ{^7ogs$AR52wlrTG!P3l&SJi-p{WZ3q6CkPEyDdBwQ`2Qh&S>&6wM{6XXKl zjjQuYad{}O)3b(qoS+8xT~pc2sdA4KJkL_+l@omXT;RI64scRlNhzTwD(%!amD8-@9w%r8bzV8)p=ezyn_0s>v|5$3$21e}ae^MBu2)WYDDRbK z4R32aFQ`?Dw}P2)j}tr?rKy-!jb_Zx z(R(PbZ!_T@C#Y|AJ9olEd260E{P}EuF4>0adt4rh-wzY=IC1zZ z7#^30^6#`njZ(ex@0i4O#F>&vt(`9!Sllns`4T6vbzWoE@VGn_zaJ*#aROUsDYhC; zC=?p9XM#66FuLe|iB=Y9$es!JoWIYYntyRZp@>QLmXHSxx9j%daX}~)zsufg$m0aI z>h#44g+fF2mXOEe#a5lZIH6Ez$len2c)X!k)m@LvL&bF*B2?R*z*c?RrpgJ0LPPeJ zkjLZ2uIsMH<)Qe!CVaN!BQ;}}>cX5V_c(#AlD#;gP{bsAOUUE#Vyk2?PAC)_vbTgh z9&hMXW$tl#sJM=p9%g)PC|bG<)}ofzI{L8#c9x=j-88u(kzV#hT+ zXox^tF-6$;H%2vioZy;x8^)BXMH)&kyQI8#f>3^aTMgyA6YOU2#+6BwCqO|^l2HPtIhR@XP@m3y3EA5S&( zFyW!R_G}52xfAGZ%Di8>$K|2CR?Zq;N7;SlEi~k)$21e}ae|#+-Y>H)4<|endy~9h zW=r^Y$*8aDSBOdWHdXRCak#d7Tpo(wZ@kQ%I9#thE)T_ySzUMC!(N)&hsU(Na;4V^ za(B}P8yfqyB0LmjQ@3+3DKvN!(52TBC%8UVmus0XaW#=D)pid>PV4vi%H88c>|jxcBhjqkad{~3k7t5i3)Nk0)eQD2^!rS>=R6_$FafPl?3mRW?m170o;94n zRw$n>&xCu<6QU0j&nr32cR;?$&wbp7Vt0S;Gl$6FwW93HLa0c(%kj z%WI$V)xBTxTEZE~I#up*0=vHQ^Mpe2yX^To+~e_LYqYyKp-{vmdrQdU@nUNQaB)JR z(2%_)6DuvMqGsd7T0(2%_)oM6{lGr+@yhhkr?UQMuns`V?oue$reeIH%lsn^WZ;@=a?%k7*{{;{;_htvQ$AB6oEi9?E-+S;IX}P-8ZINkgN3 zNW(*UPt-M*P>TI?#YKx!+Fd)sig1q;v|#1iVZuYvV@&0-NW(q!S1M=MKCIzHoc*cp zczIkNivC!=UDsGs+}E79 zd-IQ;eDEKC?PmQs6U^0>s`G@t1#_5yRw%zqF%#}NPl!HDKr58rrI-o#oF_ydCZH9{ z?^4W!d(IQ04-?P|<##D&!ae5+(T53Wh4Q-;GvOX5c>gkIXx2Na1Dp4XJQR1^RC{I( z_c#&nk*>b;9w)Ht>o`v+l()^ThC+F~ z*oS)`Clm?|*;@^HJYHEFDE4wtY6E35@=lYt}i|NxetC**KkkT`(1w3>^$L~n&2$XkN^JXp55wp zf2V6Wkv5?oa6+zp`UlW(!aX$see-|((F>Q~ecv^lNPEA_H&dYD#OzT@oIvBh-{Utg zeDlX1-Zh*^+rMOnh7m_~sPhChof=P>=d)JVOkYUz=dq5Cj5u<_L#0isp8L4#U;1IO$B>XAUw9#l+e#OYEBlo1e z-}zImhY1grHX5xTxq|+rUBr=l(k8F`8$5@IIg|)AT0e43e}YDa!lO|8ou92gOn9iY ziRtgY;7-R+c>kHI|J8q^YdDeiewW{vL8B%-l-m$3 zpN>brd*pGY-M))FeS_x^;i1w-qm}pZ7(b5OllFe+-~2gDc&N0|X!Z73qndlt-tYX| zMTZFwl{Ol!{T+gj|hQgyz``vH+ z;r&nJtL*2A*;5gu@b~}a%+P(HQlr6Yfb{byw^2LqycX2$eP(qqZM&9qvgxS`@7~uHz8lcMZ}; zqs>W<`5zkYNjv&0{(op3B1nZorH#hFdD88VU;F9%b`AHWz2Ck4kG}Hs3D@1TX`CnA zQxnvyM?d1P96#i9zoTn7kv5@jcS_!cMooAqw@K9)4Z6l0m*R~viaHQ^b%>x&DOB2M zjB&7QxF_uxYpKhjafqPSD^%KOjM2GkxF>C{oU#1@L*o!JhY~R~n3s&aa*yo&j@gG& zxXxrYgojFdD$>H#NFudojhb0`sL zeCexidiJKzdhob%_sHJw9{lIuaPp`-UNP#f6SJoxNY#h``fbmC^G}gX(u%pUCQNL&Ul* zLZyvHD{t1Ey>E9<+WWp@rA@|l93ohMDpcBNFxS>(GE$O+&;*Ij4Z;9)0g8Y#uX(!Ma zC3pc1C(@33Mc)!-{?n}oefJWxzNbC)WX$faY4_n|?{^=3`pGHpeu-2$;hvfxRj+A1 z=xd%3_hg(%d%ydo3n!<%F*Y=ua8FI3@sieqJ~Qs(966Epe)rx#Icaaq`kkTSgnMcN zjhnpifyb|pyEsQqq`lug=uW4nyxB9Z!wL7)1RB5BW=encFZH`PM^2=@-|-z)-ZvT= zPPnHg(D+#EtN!O$K{}B(Z|FKb<&CJJ;e>l?0*wc@-tBc`CG14nZASKWyHnm68yZfy zrzX(&swX_*ig(A|k0U42-tQjpl-()sd<_jJ+*1>1yrtb|_}RGoapXkWgu1GoZ z?x~5P@zSBOIFUAAXury?qiL+f>`_Xb7tKE>5Jq-~E?2 zU2W~$3HQ_l8m(tI8-2;*MB4k^t#5T7>#v+}PfeiFdbqRECoWE;-DZ6!_c_ge*9rI3 z1RAZUJ{x`e;zZi}-Oa!2J~nbQvOt_~eOrzg5a3bxv z4!#W#eaT2wCx};`ny|d;vpy%%j`HCB`k^uMsuSdoJT-yFD8UVpbkr-}cOM!~P|oty z1RA3z_W7<8X-E6u-R_~`1oc&(nm}W;sIK8e+R@H=1AJ&WLA#TuCeRo?L)UO3?dY%K zJLSwQouL1arzX%CJzUptBJJpRc^7?LhZFRJ^3((xqo?i~PNW^90dM^e4JYW&<*5lY z#)#83oJgBcSG70xO2Y~F)WpzWtnC_3q#fhAQoD}MonU-Tk5b~q$SdXy8zSkLmnhfQ zSw<(AC&*J1XtWY!?z171j`@{p&rC4ik*6lmXf=^JT-R_S?U*O370d+lHhF3Sjn<-= zi*^ks(vJDATJuaW|CFaD&}cmabLy_)MA|WLSFbb^%%kP02{c*{$J(IxiB6;)>ksv= zGr@X5o|-^otXR5+6KTgfN~6R~u&$A(CeRowuRh{9kv8Wiv~Huna>6||fyUEY`@75c z$9nMS=rS8qW$$V?F3Z+WXx%{;l@r`fGWA2^vmJo;4*-pz-Rqzw*Jc9&{q@{q7}y z?Hf;T_hxB0;hvg6;{~?w>_pmxx_fIkZyDF&gnMcN`rF#-?&rsjyAx^ecUQmT?sgqc z%pRr02{dleR(J1-yjq+{d%t_tuiV4R!wL7)M9+oR{#vU#<8G7_X}3_z-?VylcO%?W z6KJ%WcsAsy>id%yef_ub3J4=3DH6KJ#%=WL8oixX)R>fSbXIpLm~FpWOeI+1o<$76R|s|}4# z5N~>v5+^LL`kcXuw4*#8{Zm@wjJ)au`6EwFpfO5tLnN(wrFpv(QO@D12{cAc>~lCL z(vJ4=y-(KNb0?^;^3((xqeXQMC(@2q`~L5EWsZZi+D_2!Tmxl%h5jIZgb2sFkFpldjh zcFZ!?T%QQ$3G&ng8e=BYHJnJhg=({!tXEFBrzX%CGqT7lk88DKo~TwZ6U^IIPf4IL zW|m#UiL_(BtJXXd%s=I+2{gtGxobF)w&v~XubhZ^ba-k4jn>1lHt2n#6KTi#L%r)v zupW@7CeRowmagGM+OdwxQNjtZ{mwLL8IXW?^}_lCeZkzZ~ETj>;84@4?2<>DTwtw{v4JUXuD&D$(jitm1G@jW;v@6E`pc85D zcf1iQ-sO*m6Yi-AGU zczag72^1{J(8~@b|}h(22D7JDxjIQDgnMcNjpOgT{@%Yh_6MCvyM6P1 z{i+ojPPnHghQ>>W#^OZU`yJ0rh}mHGxK}iD#qkE>5Jq-|=R%Y#&azrzX&7E$VEv!NrNR z_dDKyrq(#(Z^aR z(vIthuSb|hCx};`ny|d;a|S2Uj`E1_TUcIog8Y%ECeRoqxFM3(du#b>C>l;s&hZV7 zYkJMlmp1ZuG)7JAbGY zckGTo|-_Tl^}DUuHi)5F~3snnF;1Q^3((xttK*u>l#j^9rHxB zf|+36CQnVEF=m!s!-=$G_L}Y73Fe>j)C3x>XJAg)}`% z^ghvvv}66D-gPEe56Dv!Xp9w0*Ki{3SVw7;mF-t#Jtxrk4~_WYAJG2bBTp`S=gr1AA-mm;y5A#DzUe`qH-2|w_EZEKf7td1 zKX;rLbt3Kdl+fjmI(g8GZay@ea8FI3@#U{`9$zZr69Kq2YvkY66Xq zw7UDpV?F3Z+WXyGp8J@StAFh_L&FL8)C3y0Y5Rk}J@yBkNV}brxx@FIJmjvo9U4x! zrzX&7*KpiYcGmWBj+{uFP>&sNj-*~W;hvg+zPz=+-y7>eC(_>U^38Z?I5B&a5+~4T zd(Kz1yDa@WoJf1W%Qx|%;e>l?0*xR4!Rzn+@5g%3iL?o|oLv4+-U*0?6Yi-A=$HNA z^)G!&XteX99+&KPzx{?E9Pb@O!-?5b5hJfIjJ#T$NPEA_cYlt&S_${m1RAXbFN`u@ zoJgBcde85Wxwl$ zdujrWkG1yqBXRa)aU$*gjyGH7_~C?mY66Wm;+%~!YH=cMLOsdGE+^bm6Q-e&V-gLC{q0tHAO^;IIgymJAGdPiUl*i|N_Gb-^kyo7{f8?nNG)4(-h@_)lUH;Ca zq2UDOEKg0KF=}F;!#R<5w2!Mk`;+614o*;C<*5lYMvLkiPNW^J_O`eEUqizQ+MPT# zfyU?=x`q>J6Y7a4-+J4R4h<*VQxnjmhwB~X~(=>z0yoDkCvw< z&=@oQ-X}VdcC0_tyUqmb0eNZyjj>|s8cw7g>!=(hoM2rePfegPR$hI?aUyL(X%)u& z$_e+>1T^*qIN_d}K!f`++*w1ziL^O~e9Keb#~T_>xThx2;C>8u2+?pNZO&8Q>XbJI zhlUgGsR=aNzQi$iI?-?{jZT%PPnHg&}jP-SFqcFh7)P?^uQOK@&?z?aKb$`fkxYx zxHr2EXgHBJq4cFs^2!PK)Wpzu>Cjl5NSo(BZf)1WZi$H5qm(!?^6J9KtM>e0#+5eD zvE16qgIymH?x_hh*ozuv-ku-KxYFi%oZDEva>6||fd+eOqwcon2Q#j;d9LU-);^qY zPfeh~-r#71?fJosD{Y>Sx{bASC)`sLXt2jQ`jYniV8)d;&v|{J^;b@~rzX%~uXgl_ z?fJosD{Y=v`$Fq?op4W0pwW8jv(dM==La*cw0Z9C3vK*x!aX&C27BjYjB3vhW?X6W z{NNX^W7kZ$rzT9JkF`#u9oNA(1EMb(sp;RNkYo|-^o^bB3YiL|4?;tlYj;ROAMJT-yF=;6AC6KO}k%lp+s!wLF9d1?ZU z(NlK~C(@45fcLqFh7rAj7kf$clXg&3@`gSMMj&+nqiJ4$sBTr4BF;-rE z#Bm~Ro*&FL+)TKqCeRow$i5!zE6DqP-FTx^TW5AV*0ulqj&~WqJHa|LJr#k5@Af&7 zcC61o^(kpM!FpMqnn1&M`<_;3uaE0+f_498!&4JzjC&bpjDt?39rsH<_PD<> zG@Ri6g*-KZhVS+{k#^kodFk!$Iy9W%K8!pyfrjt)IgvJ@9((fNenuKjxThwd#~rVp zS5BlI_u+2x7t(No`(o))N}NE$cl(@3JMJg`_sj1#^2!PB@5xgWX!vfQ6KNBw?aJL( z8cw*UCZK({&xy3-{;pCx6Wni2k5b~q$g6d?&xy3-u5;%4xQ9#$_T4^tY66W`g46z> z2<|$EO{gbYy>h}mH32>D(Dzh1k#_7Gs1?iv_wm!ClsJKg@Af&7cI~qOe6KJ#%XWAbWku;&&uG~6yIpLm~FpWOeI+1oq(r%6EpzD<|Aj6VRiF z>v`ow+R^XEw~Wznf_^YPN{JI_jGnq{IFWXY2G96TU569&=knA98ot}-MB0Q}S{syx z6Yi-A==1x78JFUX@m#5$3C7p-RK&=uX@5{e(lN`(Tpx3Wp1aHwl%4#0*$fq z>LZR5X%kATF!~ZF+*1?Kyw8a@LD9GKZm63aUD@yNq`lwq)~1_1`#$5oj}z{x2{d@0 z6K}La!-=%_JKoxK*Dt@{&~U;%HGu~2bK=chXgHDfe#cvzF1ze+4-F^WQxj8;Ou(9m$gJvD&_?{nf!X=pf+_I}4(n|}D=-!(Lxa8FI3!TX$e;~N@I zq|JSX*PeX$$$n@!;hvg6gZDYTWb6+*k@kMaTbq933;yBIaKb$`fku0;;T61rkLz$E z?fs6oHr?X&*A5LQ+*1>1wD%gW`-4uTO{mwMJo2Fr9U4x!rzVERy4&YO+WQ^v_s#3z zZHw9;oIOg36CXj4jsR=ZA zC+DcUixX+L@w~m?H`|93?x_hhc(>?igNqYsx34I*_xol$cfvh2fd=nL9ev5-MB4iu z@Au9A$_e+>1RA{Sb@Yjg6KS_+;@bOtv)^^XJvD&_@2nkt`{G2}`yKE1&GEwt_tXR$ zynA#(Z^aR(vIu+#JAsLwDXawP7tp=HDP(xS9eaN9p&+c zx8F^DN#t%P$RBxX0*z6E8zSkbSFeA~*A5LQC}(+U0*z4j=Up_RPpxwz+6KIT{p=&sicJx=jaN+ht!wLEid1?ZU(Zh8O zC(@37_p$H&;-TRL{h&NGfyU^myM_~K$7t}8yWDnYI6;3dPfegPMx3tUMB0RU-N{cs z^^1mv6Yi;rp<(-j9+&JG&z0JBbndBQd`(Y9jJ#sbupyF;d5Lm;on>@_d4fDOfkrDq z<~|!D>6l-s_RIwH9eHX3jaCzx!*vZO(vEqeTER>(Zi@?RH=E6MyfdJ}>H?nm}Xh31480aw6?^hULHh{ge8IfvIpLm~Kx3TP>Kaa@-QJgR=SN%naKb$`fyOv_)-{|+yS+Q%A^*hMxfAZG z2{gtDx~}0w+U@M%10G}jl@so%2{c-txSkhvBJKT-_XlOa>x6r10*%(UujfUbNPEBI zJxDozIN_d}K*P_AI*~T>tN&*myJo^YHDMZktaT#oxDK7_Sv5LAyzJN5896h%-SyC{InG z;io^HNIS-lJWc5Y{kc3ffrg*{bRz8-2kY~qj7##=#L!sRgHEI!z%5ozytv@%+8oSAUKJvD&_=e6m9&~PH{{f<^fZxk9%xThx281E438cw9$-nrbK z1E5z84JX`F6KITgA)Rp@PNd!L@3!X|7#%{x3HQ_l8siO3UBijA_d8k{qg-e>;hvg6 zW4xQHYdDeien%@~v1jCX8x4JXoW=k(iiGR!(c!wL7)1R9*zW{yR9IFWX% zyX|=&W>2BvgnMcNjrQEq`hHO-(r)J&+B3Jz0z<nX_WW+vD<|Aj6KL?v z9rIB%oJf1W<9 zSbyb&dujp=p5Kv)^^XJvD&_PneFreQ_e~{f_$>Ies|do|-^|o$xV6 zEl#Ap-*G=iW7kZ$rzT9JukM^kJFbIS;OMU+Rh=MSd1}J)s?STDNIS}dSzu_4yy^t` zBTr4BF-mYlBpvmNSzu^5K{?A)6KIT@c--pMkrQc0`(PFr8ctAO<*5lYMvLkiPNW^} zoLOLKI6=FUrzX%CJww-UBJJp}m<5K06Z9YQ)C3x%hwBGTo|-_TmEih*Q76)l`ITzVOfcV(rzX&7HF15vs1s?& zJW;J+CYZO$Qxj;k7R9^ndtNz_cFcFxnrDLfr#v-*M(Y{Y_lr7_cFfz=E6oJ+XnAS^ zjn>1h?-z91jBm1b4JXpx@7RUs zR8nX-;hvg6qn%S*zen#x+WQ^5@SLs+4JX`F6KJ$^YU}stok)AX(unZ(F@`!aX&C24^feeTIe;Y43NOgb0nm~gS#iMUuoJhO9 z*Pxx(&hf(u_tXR$tOv)4vpA9Ve#d!jja@V0o|-U?KGr&sc3cOi#G;*#RCR)Q<*5nF zt3GFNBJC&-PKkxa$g56}Kl0QB8lwa^MAG|SuQ(+Z8ctBo^3((xqb44=x_jhA+R;8Z zB^DY^P+#S#2{cBF>Kaa@9qpV`Vxi##?M|MWKx6a_UBijAqrc*mSZFvw{~=FJpfP&5 zuHi)5(eH9fEHs>;AC#vi&=@^+*Ki{37(X~A78*{_pUYDdXp9l3YdDd1jDws?3k@e2 zm*lC5p|O6C-ifqhJXdPh(YdFJ@l~Fh7K;roNU%Zc{PYBKCt*YZ}V zXy<5%V4W#XO`tK>&KDRzoJc#?=e*r2G@M|)EKg0KG426$4JXppeTLf%4JTsVAD)^( zW8BL)<2sy3JMNe8wz0SlC%AthPfegP?#XlwC(@4lKD;$8G@Rf*j65}g#<;iCHJnI0 z?qBitx6p8c`$_WD1RCQWS=VqP?YIxeTkJx^3GR!@QxjzGmZv7r7qW?zgM<%mnwp<*5lY#vS^u;Y8Z8Z=hB%6Wqs_rzX%CI}KgK ziL_(?L#=rx*pHB>CeRo=CSAjcw6%|;cJ4&%tAwW}&=@;E^of0ckT(?44w8=jDD|#0 z!TyjuHG#(1!Ri`Lq#gTe8YO0eeJ*)w0u5GPzCS1;>DV9C*fkUE*U3{8rqRb*C(@4V z;H`qAzdE-+C{ImTUR}}3F$lXqmKl0QB8l%iNMAA{Oc&lJ&I6*nf zQxj;6nt050IFWX=58f&m8ctAO<*5lYMjPxJPNW^}oVN;wh7+_qd1?ZU(U)`$C(@4o zinj`eh7t%9N91pT=@HGzij z_BoNZ&dEr_3C1PfZ-{zL42@}jP(;!(o-4KM=-hLc@l~FhK;!)WpopYnUZPx|3FZm% z)C3x1Ceu^pMA|XGQtg=u<~#D#1R7&T)-{|+JLZXM1vA0CO`e)SW6UhOh7)PWd{?b` zCYXQ9Qxj;ko?+S_6p?hy+tn-01oLQlY66Wh)9-zv6KTi#L%r)vupW@7CeRowmagGM z+OdvOpFb0%-pP}aj8t0!Mpldjhc06yu z*PBDb3HImZsR=aNJd|e|x`q>J$8!^Wg*r5x-~^jIH8C`%=Lbb39nXI#wd>Oyq^dtZ zC{Im{yqcaL6u~*Zu;V!v<@)+mO4r~-p*%H#24@qQU6Lv%(vIhGRC{KElic#u1R9*N zWOj*$6KThDMQQ~z!3j@!Y61<;iZZ)I!-=%x`6#vKnc$?VJT-v^XI`0IqTxi^@tl`> zrJ3Nwtvoe>M(g3G=Lbb3z3=F$p(vIf`HFnJeC%NUR3Df9ftrKa-b?_DHXy+qUogiL$Y66Y%SIFWXg z2VbEM4JXJSd1?ZUQRZF4iL|3$@fGUOaDsA{rzX%Cb@#ZHM}K}$MAFed_zHDsI6-}t zrzX%CZLn)Nk#@9mzCs-uPSEb;sR=YjU(z+4NIUu~zCs-uPSAhIQxj;6KCx>!k#_XE ze1$qRoS+|+rzX(gyf*Vu%EO7YWBlN|)uG`8{kc3ffd=Uf;=^W#+b=$h@@kF zrP?zS%y;Ce2{guxtZO)tcFYsi3TA?Nn>;mv#+X@l4JXo$`L0^?OfdhHrzX%CGvuz} zMA|WLS06JI%%kP02{gt`zxRnwq#f%I^{z9)dO)6d5(D1i~I+1p~-{&iSM;cDBKQB*BpfTPdbb;$|B5l22^y<-HIl=z?WtWAgCeRq~ zLOMgkiL~Q=OCNZWG@M|6UY?pjW4zO;YdDd1yf^B7sR=a3n>-n#`ujyi zBpvS;)z~!?oaC0LCQPG`wN9iR*YSX->_(qBQq>9Km8T{wulk(9iL|3U-u`vc7`fXC z@<*PUKx35ohDbW<)oWjKn&Tj~q!X00JT-yFsENm|Jo@`ZMI;^Vb-w*lH(w~PbcU<H@;e>l? zVrVed_UmvW?HJFM+McSFV0=xFQsTtOE9MMc!-=$GUZPxIXBnMfo*++6pfP4L8zSkL zU#a%Y1oItvY66WhBkLMYq#g4_wSt*o-X>2?pfP5aUBijAW4^1_JQK`6<*5lYTF)@O zUsOcWF>hBNGZW0C<*5lY#!SEWa89Hh>ksv=Gr@X5o|-^otXR5+6KU`JcN#QG%mnKi zd1?ZUu~zFNjuUBfpCQ+9GvS_^K*M+Y*q_(hGVS<|qVD3(1iS6>)C3y7+vh~u?F>sh zFQL29GvS_^Kx5nkxImxiMB4FPOWh-%3HImZsR=a3y^J$7oJc#q&#B#knP7ijo|-^o z+>_}VPNW^*8PzVwOt9N7PfegP?k#l~Fd@jYRs zcD-9m?)I;&zxj}hq0*!HJdqX5me|4L+_RNHP zY66XMhrVk#k#>BiTCHFvIL9eZO`tJ$8oGuPX}5cp?Yy>H^Gvv>CeRo=CSAjcwBx(s z>Xl}KbG7o+1R7)Khd!}?k6uL5ZLg@E*Uo;|3HQ_l8ood1MB4Ekca0J=!Kr0=Y61=4 zA9NyZ=Ivj&j$Je1o|-U?KGr&sc3g+<;;tHBPuJ-wN5PfZMsb#>=N+A*Fhwd+`W%#4ijH9bm+6Cl?0u6r}(22C$*{F8Lnpt3I zIN_d}7#i#IgHEKq-!W^>>ln{waOI18Y61<;^f7loPb9tHu`bB+aKb$`fd=QbnUA93 zMB4iuYm%&2PPnHg(BO!*s;hvf>jlQ~bBJH>iW`U!>vgZehSDu=% zyt<<0)sYivM|m&{42_XjogjbYsR=Yj32um_qh2u!3=JnJXL)J@jZqVixeh1Nj`qPU zFf^Q?zRFV*Xp9!sHJnI0+Bvhp&~SowCr?eFF?xos;Y8ZeUoi^|4JYV7odVTL7tjGqm|(Leo-gVj`@{p z&rC4ik*6lmXf<(tzo-*w$2?K3U?!Ni$x{<(v=+6#U(|`TW4^1_JQK`6<*5lYTFhC|G!x9D<*5lYS`W9rU(|`TWBsAtbtYI3$Ws$&j1^1ocb!N()=?TIW`cE% zJT-yFSb6m^%89i1wrR7rMV&}{zkB?@`q;@oyFu^%bizF~fyQfEnSXc8 zeU6++yPcW1#mC$A={=B6xThx2_@h>LKOS?qBPY_{@9yxHG#%Q zTN`ZuJEH`hNPE9~@>@S~^0qH~)6j6jJvGtGqrIEz!!f5maw2U)ee&ez-!F~#8sVOr zfPPFnf%K|a8?-C&xMa6>zWdb4Zr{{e}7zu6Yi;rp|QR#)QPm)`^a8!beh-EG*)8vC?!se zyt***YH=d%)-(LQ&p6HUXnC~~?x_hhS_xhlWxhC(Hlc2En)S*F_tXS*tBGf$?k-NG zz2AM~lW%gG?Zb)Lqm(#-2JLUO!NrNR+j#!@pLv??+zI#81R9@g?eDE)J?KQ*``vFp z_A^_(Qh()ydujrW*2A5RK5=m(?e;v*%Rlop`&}p8Qxm;BTKgM)`{G2}``thN&}W|J z_(3fc;hvg6<7sW>^=Cg2&ks70HlaSN<(0-RC)`sLrqM@EC(@4V`1?PjcYh9zP7rT; zloBT_ulk(9iL|3Uer%_Ae~!HB1o^e81xpfP&t4Uu$=24C`}(r|+QT%MXh zV~jXm!-=#B#pojqC)`sLLt}lvs1s?&c&^m0qjOIc<7;}95+_DpF=yBiNyoe-bA8Mi zI>9_ao|-^o%w#r1(uDftN!BYT+*1?KV@B3BoJc$7iE0Hi!MrU!N{JI_(3;euoJc$7 zyK2od!TeL6nm}XBko$Ewk+$aT>aU!Ld31Pc0*%(gu{P*^q7!My`a`|zOt2o1rzU!N z#2Tk-IFWX&qjHp>7PfJ)6Rd0GsR=ZGF4k&&#Bm~RLTMGode8~?)C6=J)s8=B><=Ct zJ^$pskABAJmt^mExBt@TpS<_=zchY#V)j&o@`@g)wd*4%(xyC~fAZ3=dFId{uSB?~ zCeV08EA!KJJ(zJNz2E(VTfCrM-?N5>6Yi-AG>+Pn18*GbK_}9teZ1i0MNfYA&~U;% zHG#%xgJn=j~SuSa3XC&z3}9ZzVo?5!wL7)1oYo& z?eDkO^`OTkn|}9KPG0d5X*e-^DguqsQ}^p|B5g*47oFVs{?8lN;e>l?0*$A%^5_Sb#>=N+WXx1v=Y29%6uY{Ce#g9ubgmCO+d4T8g;kjmB%H!%|-9lmW)C3y8+1lU3qEB3$ zNW0w&f5MsdyH2>LCeWaUjGlUNBJKU|-G6Xq~g|A zH6e{3YHhuhO#Ab=WXE+p<7U4&`Vurm5N~=a!t$!m0GvoW%Hs_$_|HRQOcOuq2UDm zV0x4iC(sx@b=Pnr?HCQN{kPI^g8p2dnm}WWI9qOcyPgElu#KmpGBO=I!dQ zoQQdJcxnQTG1KpTq7!My`a`|zOt2o1rzX&7JvA$quHi)5v5v}7!U@(j^3((xti0a) z12IN9kv5^U3S&L!gnMejG+s)d2=U_UK0f*-*>N2Y`Lj=q--kvgh&MeIVR>}{1t-#u z^0>>leR61wyy^t`BTr4B;j23*(vEud;_E&&G@PKE<*5lYMom29I-E#5+Q%JV^uLFO z6Vz9EY66YX2D^q6X-BL5sp~&IG@PK_$x{<(jJ~96IFUA?UU>4HJN5A{UKPC+)=m*oIlsJLL=&8Gg6KTiz@og`bh76||0X=49{mPw4JLZXM1vA0CEj>z!6KIT?W!G>b?U?VXHO~a|PkCwr zjn*?Tr|ud~q#g5i^-43rJX)TbK*LvePNW^{5B07y!FoWRnm}W$Sm>$ydQe2tv5v}7 z!U@(j^3((xW97w&)7OI{k|xy4Z0vHvJvAYXw&q;dgETpfT=D95<`42VZ<$ z5J^Y-_?Acg>CkY3`YKONpfTED*Ki{3Xti&D%twcY6SO;dY66XMr>JWBIM z;j23*(k9fewl*jYC)`sLLt|PGW?YIl#&e~19i97?Grp#$B1T@Vt2-ysj#)1gG_&h@=ViLaSF!xThwdTTSGi{-{?Tm+Y7)suj!x^S1O<1R7&z*)^O< zJLbD;%`?ILQ=XbYqxB5zv2+b5($>6P{go3jj}A{wpmBaZsQxPHSbwN@oe9YYA4c;bySWLPOz?#rzX%CJ8^xCaw2U)X%(jRVB75*qgr}u0-AT$ykZ>(-`CHJ zzUDRGy}RvC{>jOU-uAmEcl+hbSDWAC%C*m_Q0IwXz5jbpp7xV(?(|{8L&*+}SGT(> z4<9?c?vYKZo^$*^TWa4iG!79SN_J>`sI{i|jhg5l*=XG4d){;MgP(ra&^SbRDA}Rm zEy_Kz(I9^QKla?B6pFY!lN4&3V_3C{?;}F5w zv(fH=)|BCgyhX@ZP zJ2YCI;w)#^aF1*>{_v46Tt|jj4_1VSk{ueYZJcSuagS^?m=n>$!ahXIp@Nt+`U+B^ z!jti$M|+txAlhHX<)LIxd3B)$U)&>`c*!@~OK6PTg*Z|u;_^_kLt~U+*Km();*Iiu z`Oq-pNTGuQphX!K@tqKi=3QrQu=dyhqB0QArh^e(GcKf=9dt`GR%s6QYaZQH^4<$P^+BGnz z?i%iqO}sI`R)2Mf@KCZtqm>0~gWij}M>ZPFLumW`my@=I@g;|ata9`*c__kI6c zyM5VZKhsk9=5DV9(DB><=qpd3aNRvmAujvnuRQ(6-?*&XKlSFXIlc3<+qa$C?=$g{ z>;CfTcmLWqch75I^OsK__@;Z0P`5k%{F}G8O*_$3^}r8)#mPVTvS;=5UUSKf&){lr~PfBaqV z>~WE9;)cHcS6qJjTTj0tuY5rP4fi$1PnoVg=*Rc{FYJIM#B0{3& zmB-}-Pulcnml{0+_y5d6Y*^E0kPF>O;Nj}zG9@y+EYK=`x35pJ-NOi+~dUiZvEkt2Y*d_O6a15hgwhIZwU7|@xy=d zp_706@2m1~!b7c35^Oa5%GdMsEtFr=TpqJ$oXu|pF>UJALOXZDLvc;&E29dA5^a#D zUE1@fEnc3k>CcHa+v{|M72zHy*5@u8-NP;-X3tIH8O}@A;AyA+)Mq2sXCkE$66e~W zhw}D60=JAJuRMRKWBp0S7VjpnRt@(!5p^N@l^(do9~w@0sJA`&gX?%Tq7U%cJx)-s z)Q=q|JQUB(^e0(8uNJO+_Ixs))o!6&`>+O238_5RXP;f8q04j~9%_A(c|&-gu|9X# zLU|uEr^-D}tWVT!G@S5IQKx^S=u4VnJeStuTA$i#HhJ|0|N4Ivgoj$6!MZ5naXGO* zkF~iDCp?t*L_M#T$g$;k_Kc^tTD$8NL zR5{_H)+YlugwGj#p0Iu=(215`OP^)%)+G8wLh+U+Z0MW;M$Yo@a_k-__}-yn>fx9E z?>WLlG54u8+~Wk_ZRGt++i}nd55?Ccd7IKotf_Jj-?ij@NQCm3;tF&f?s0-IZ}O(2 zRbybwu@fF@{m!hHN27w!d~p5xX$!S}rF28MXZ_CTxDLg%y$*StSic~;(cn5nc&PPz zpc}$H>lZyQIaN-q-|F0Gc&a><*Zld)-Q&ditGjG9 z%AdDFUA$g-D9@4k%H89{`W4^Jl{?{~yjIQ{>(?(^T(_C(Jlx|1 z`KGoqUxyPO%Im^RPw`T&+_3!!R?t!@a6E9d-^!1$y zG~{uDe&sIz?)im=6CR3OS4?xN+~Wj2(POUvuZ4ya9*X|z|9jXuVxjI*w%_;oH}<#) zb*JA7o0yb`+f>Qp1bT|86D@xJV$LAKLwPwx*!VZb!HOUkF8t!}7FX_Zc_=Uc9{VB< zuMLc9*M8);db}P}gcac)C+PF9yZkjbk}3~HKmYk(`>KM#^Y+iVp?e_y@6UMgnyR{% zkSckcAca4&dr_g`gopB0(64#Xm3w*_0si@iUa_W1cwRZdSn{V&v%7->o6Foo zd1|*Bx^gGbd(72mH*)13%5#0zpx;%WK`*Ml(5w3^k82L~fRn%S!M|7JZu|Pc>T!ZxP>(vNiauN|hml%skP)@6R~{E- zqh8y!SB++H-zQV$1bUnH(eug)59N2fXASo_!S$&HA0|8$Bb?g*On6>-{y@}yiO0oQ zt2W`Ooi*I!1oM@;)jHv!JcYA{dz?T|{mNm&Lv5~n363&<;>myenY;G+;FBKpLnkl2 zUD)iHZ04eknh6iZz5bj0MbJI=Rm0=GKJ}@)B(bK-J-2)FkDmPVJ4Psv>2Ru?I68XL$z}Kby3`ohd>tMN zjr;xGFFQb_C*wu$ga7zzZ-nqrT;Ic=eCL924|#R@E5D|Py0la|LD~G1n+LtkD_w_& zqAon^d+t=EikkTRkA8LcP?xTKO4y8QifPtxj}z=0J>xrrUWtXe>%<&tX(f1$Xy|hM zz90I&HLkaP^}kqCMW0`%$~{gT9X)ovzBN@{!wC=dfjfN9Hm~}1{Kn;vT5I*6KKIdU zn;@o5t6eqZapEn{eazY(x2Y20p-7c_iIwQ7nmvzQ`;|*e6<4mFhs@bN9UJ zeve%H50B}vh7(6ek37)B&2eQYey_`8_9TIx`rvJ<6qkqcR?vwhxVD>N`_9yioFP5& z;T-Zmz_^JWJ$GOi5exiD*Zp7c@eok#1HXH3b=x$6XFbJb^m zGV9fJ<%-KgQU15R?f)tW`a#uE`W1zu-6*CtO$$8(?Lej0`}R>YAf~#zriy-0wVfXB z;n&^1UpZ~1Cfwsh(?7ZVok6duYDVWNm3W<;t~ z9&@P2uKn0dch#oK4J>NAJd6hF;avN$h7)~MEBlf; zt~N%EQ2eeu+-jsJ3G}k>N@gw(59O^n!&8EM`<$?i&1Jx{;)$>&a_ zED(I}e*eby7ULF*@6vzMFSNJrH~YumcdyeY-4J%yXrbeDf_t3!t?Tb~`jd}%L#I12 z{#lMaC485j@5LWX6*9-3UMJAwi}uj7h7%s@@!x*0wiExGNi4xF$G5)KecCs*+WY@o zTn|3E&wAy*@rU<6y~pR;Nx+Fv+JEQ~-*)vecd^g8ymr=A?R4)-{5bad}aAUqV>b?(ldj2FGf?y8#T zgopB4Ip>vooS;QL`lq4=A0|B1rnaxS%b87`Tzthh-1GF7&um{PXmyu%qf?rz#zG0w zYTxz+(Vpp79{Aj_J*Jgt#&YZ)CtmxS)6=j0YCGvPu+~#sTk|&PHGkG{j}x>4^<#$# z4|TYGcpd$U-?{4a{@)+<)$8=E;T|Vm@bIfn-+6Ua+ntz0UDdwGRuNtvp40S?>c{3( zxyOmJ%p1BKJK>?Ip&A)x4fi+^H8D;CA0|B1X8c%!V@`ebT7T$ER1>}S%o^@-g1$?2 z`Y_?4e3Y1pqoXXT2RvoBma~`aOt{C1w}0Jktz(A?4@FLI#`A{GBc~Iz!Mfk|xIC24 zC3>osNE`QeuWH{!iuO$1l^DCJe1dkRb%1Gy_ez26|dL) zm1xG?UpYb9=$Z}_bEwRbE%CNjzNhEUtA6Dkr$2jb%q%V~RZbi&fAjRF&x|v-TMhN? z9?JXqnRv-x`^MATy;*adySI_yEj@*#N~xWR*^|W8@3_0gluYEV;_^__H6_r>;~W3h zH>~-?vj?J&maji>zHUjOO<;(UVpw}CgLfG=)>=JzsuG! zoTo>0Qhp{p)IYuDW$Vo1FyS62j*fT&qncSd;i33lxiF_{_GG;1O>2XJwVvAI@=#n~ zy*3~h)svCC${%w5{om2P?9lp^IaTg)BFe^2<1WE1$JDrMp7!f&4S&+l{#eA@TGS`L z!-(}dXhrf+^F>6fHDc8`PaGXZDB56s9i&(BQuCF*@9qS59=*+q6gwG{1O&ZmdyB_Lr-F1%> zJ~LP~TFN3-s#hMWtnHoPyP4XN=KGe~W#?pe-k)1lng-9;>Df2FeXTunzEQ2+_Y6;} z_*$~gFz{95JSTCx)9I8&OA&v|G2aZ z%&BjAs&flmxlSY;Cfwr$d01b$6CR4+>+5ij6MREeIXz#86CTP-b|secxjX0Rtxt6} zZY7$*Og~GF@=#769i1z|fiV|Nj}w%vPV&qePRyZheY!c<*Hbl@d6qNZx2!e1X7Ghl z)k-g?IaTg)f^Vp9PS*5PIpLwazO5Pyx$EtYP&zH-CA$)7UcwaSl3-AJe2p~ ztHwfJdHtbvsmw2}?m9thRzJULG$Wp`RlV|1v~!ITooFfIZ#m`;@ZIkH>MLTT=dBU# z?K*A7`n0FMVtpc;-}J|`mhMU75x4(Si>ZZQf|&^q#WU`D>br+s3HLa`bLo0!JYtu| z{q>+@RU6Ey8F0tmGf$=B0@1d zP7u?fdzLUkc&IC1`Ko(OdlM0LyAJm_K`zvH?ws&Y&jDY`ubX zj}z3M`pTW~P+oh+Mfd+K$L?|Bkq>=nOI1}KPIxG<)3b)x(I0;Jcdc#3W10!~IPuo! zJ?Kj9&>bc`)Mc0b?JMg$cc1w7dt9lz%Wru5-LBMqYOm8>V+p0@n0IC9&emPO{C-#J z9vP{<@e*``RMq$NJtePy&DXAJ-=r!Mb*>FMai<4<)q%Y7xIC2iV?FvMM3`A-ddXeg zL%y^tcY@Na?;(3!9?ILzxade+PnF7++*JvB?U@PpI6=v(E*vI26z@ve>@+O&iQWT{ zqqJcrwCAgvxHpGI+~T8*6Lkj>HoItaE}w%S|LZ+_HU!M zghDZD)+>7Vc)ZwJA%mT+sQ;nQ)I2 zlq_?s?R_67JQTm*^R72LK*-|+b%8luts%lgp|Rdcw+o4pQywQg*9~Yj(c|(^{C?x( zhZBd(!{hQ$K6Y(WrIO-_2-#k;omhffj@{z~w$72x8s`ax@~1Xu!aW`@PhEWY#NHdV zrpgHqg*3FjDOw|q=uiA!&9RcUEwPn%F& z6FcJAo`)lw`hVu!b%K$Z9oW!ICf>xRT%=!TKb25^eHos5M_lPdz@gURQC){cqrCW z>WO9z)=H|?UjD3zG?vVSdz>I9^?WO_aOJK+O4J6OUWsPR^~wpZsqS|@E)V6cVAf#2 zM)ME$ai0F1n2T^HRkNCz;GVZU+^xUwBfh@3T6RyayMNd-!QE4Z@_4zES`+SZ;^^qs zr}w;%X)K|{xz{gTuftQwUZJk3hg}KxIN@*jjM&@1jpA8=jLSozt@n(~gnOLe-h2H{ z4!;gUJ?<^v&~w*QxN4BFe#%1S;RN^IAN?ZfMo zjE+uhri#wugvSZyr_A=Z^LCHRL-D)r2c-h3a*q?N&Fec}PIxGO*IlZuhCEKh$*Q;~ zcbM={Xy_hLCzkea`(Ip#JWg=-OZNafG5(ne55t;HYL;c_P!udTMt;{U-WCMM&3=#yK=F)H=xu;SP|}Vf;YdDkK0r^;i1S` zQZ^9_xx0Qnxut}!zV)xIHk+rH>r~-UUaj9gYsC7sv~K5>%o-jqUuWyzI2F-S#NTqf zelN3mc;T|V=W43ZSA`fIH=1}9CqtaMJtY2Hi^RQoA>(%y^7=Mkhlk>8D*fA{E#AY#>`7w%rs5`5PI##G3yBvcyiE|( z;TDyi@nyjlFRiP8pSRQy;h{DyYGl~lqSi0Pws^g*%(?3xC)RJkZc^ohhnnkgs&FSY z+kq47H()m!PRyYWwGS_;^_!C|UN6~96Lr@;POM*(+@#704>k9XDhxEduccn~FKLfd zsbsgQlE(>Ze*e0BnJN(;igwe#CoW{uTrJ$dD(d91mk1fmpCzpIyVlksiL-Pc6a_uG@2P?nz(Xr zA5OgH53iqReUpab@=!iX%o?Qq88`dIUItwG8(#3A*YeP5h?($El*fG^{q!3lC|kwl z1a;vp-~69CJ!?4Op{V(fyx)H;h}m<)$upOq|363--@+C_-F@{R|6HNrsq#?N{A>Sh zMNopea{3Z!&=b|y5w#?qC8AG!>DN57r-UB$zK?#^oT`Od!q?^R`{-wM54Dmn9x-F3 zWZ(PxUz&-Q%`u0Q#|cIv>e+U_>v4G~>Vi_ZmS9hndz^^!KX)BHRh}pG^Qswh9xQOzWnQ)I2%zf3G z4-+1Wm{i}kM0zq_^wjNKuhdTJ5UggomPzWouUO^X=T* zBO}h8?;rjAoLBB~g0(2KfGMvQG@O`2(bCRobRyc|@L0UWPYjbrOCDoX#^s@CkM(u9 z#|e5ju4}8|goi3~x2MWIPA~@2mu)qi@KAHfw#dida?D*WP2>3zO7on-XMjE%SX0%Em?8VjLOq<%i4GHUD9-3uy;_1JRq1hp zyLi%`HO_s{r`+p@>O4rdvWDC$RPV#R-Mlya{?>@m@~7*VW_Y&42Z~SlQQN zABxt=4jKDi*oSu-*aKE5PAQ1yo_?;v^GcRuc8b|mB3{4qPfYAp6+MG_oIsD=zm-@* zXE`SAii>MfsLgK1npd87PF1kCrWDrK;aBJcCoI?lT~oDcIN_oEnnvLMpLpkhc1D~) zkDbz5LxhJqoL8Pd>^Uml!+GT%C)o9^uiOa_#qV|Qy2lChR5o*7IpLwaP9G-Nb7V)H z9OVoEd+Sr~F7ymucR9bn&LyEPtpuIm1OdC4lSWJ4T;?8%Qv>XEu0%@_e@pwW@ZDDr z*P(bl*CTBF8|_1_mi=IM$BEbTa30bB zngiS0%}jVG&S8l@Ot{Aha(7eaO)Sbo*WsZk8`YRORqmn8l|QaM6Yg<>`lhluOn4~o zk5^*hI=udH<(!pL?yARFiDt|-(Ft;$(_CwrxA^&+2@iF+Cc4K7>Vi@jvB$sjF0zO6 zR?x#PBD_sd6V+;6JHm=^j}z2Osb9)`~c)Zy9{o;f|`R@BnxX0ry_qH3l9Q%_9 zetsLeEPo&t;Y8CIIW#{ABSdVJng2Eom0hoP&8xV4JVrW@XTLL zc)YyZMKg=T8t!p|_q=FUGpEW455+rQ>e-T~owp@v)_3?i+~WlAb5btMsdB|d4G)Z$LX1Hj}yEZrY;XBJk%ytODHYJl$2Hw zl%Qryl&sqPoGQ;N-r=P6nQPC4dz|2%QS}Pa2@l2Zb*kLs1bSNIZd0YWJQUZbI|wVW z&}!X7`Rks8Yp+Bz;;CP0I6-;TGfR)lLs6P4n^mKy%01K)m8QqE5}Q;xK@FYOoCBM$ z!$Z-!HuLtLD)-Q8wSu^`R5?M9F=@2;`I}Sap$^ww_c%fCT3@*n9?IKIB&Yw|Qsu3P zUR34mF-2Gr?s0-1Ty^X);h`8;rnATtvA`kf9p|3<8~`Afj60Lt_)&~y>=?z2x z2M9(fC6_4@4GMlumAt@-lqx0oWZjf&P&;w$6V1vLU#jS!`%dRVEBk1Kqm+_Y-`Baahv~}p-w!7o6}ipU=;>j)p?4I*D}PGK zD|G8z*~4^Y`|l&6(b68h)7MwJ)%vs|pl=PYTcY0f>l?rF#JjgAS6eChl%w4mO!siY zX^~J4^$p{7u9z01nAUjP z*}2lV;wv)diXIZN+81@Rn_!eyuw1hvp>-~|4C%SWXvHjVCG?PBZbyxSgi9;!yw2%i zx@kFP-8oqfMd^F-ssrY5%oRN(blvoY`E?DFV3g`c-&tQ1dh@RnbmY+*g1&C-T=^=j zb7c<+t&8OCir0rxY;RSgTqpgT_te6jU-cE2R=vRWAF=V@SU0eTg!-Vb^lpMt9EnDP zJx8-lUn};_k)Vf!W|_X~y9q||8jb`#Bx1cKYI8TiD7J-#m{lKaKdQBtKknC-R^qF^ z5XFeKB6~=v{vZ3urzb6uZI@AMW54{J|5qnUj`S~9M(t7EINhVQ5)v98U8YDq{yVlS zMzMu1#H?H~zq+Dl{Hw@2%eN547_Sux)y<1un3bGqG3sa~C!rSO9FDnST8vUV_EjGV zexZV2_E2s;M;QrvNNB!$%LJp8lIJLE4SPt)_TLXD9L1}?CfwSYu5ADPaKcg2@aVcG z>|wgH{rAHON8RJ*`|UsP)7K~8OQnbD%JzBBqsBqPQ9Mn1BWKaq{)U|NjQ-}7f2dPvAV8sR9Vyk&w>O38g?EC)R#WFL)ilu~kES!>wCbY=VRhZByHhWpBzu!rf&_TLXD z93>6+l{H}x)0OSNA5J(b%8~UbdYEqL9ffcoR7&nE>s;BxbY=VRhZByHhWpBzu!rf& z_TLXD9L4X6j|4qqy1TwQtvBX=e$^XuKVj=Fj`cB!8@Ee3tgC4D( z_?-h&8VPzxXjLYE<|M%=y^Zv9+o++{H|ICj?xM7Mf0bV=dPr#9&{ulVm^IVaxwSeU zS2Gsn(6c4|O}=F&Q=;`R&fm3%1j`q(3eO1Vow;2ILG`R+M={;q*NSN|O7pk;xt5+- z?TaTi zBp9U}x^8N&N{;leoRWsCsPW1cHF)CDWrP3_e$ePjGj(#fAVgEQA#O)HlT-u?4uEmQc9ln zuXAM&)0OSNA5J(*8lLs93455XZ2$dm!co%jtba||!*pf)?}rnPl7?sfYr-C;E8BlR zoN!c>BYQTWhv|miQ3yXxC?$^=>s;BxbY=VRhZByHhVK$BDzeSR!CJtSlwjc}Awa-Uyo*u!*X`|pPnj*^D^{F<B{!s4<{TY4fpvq zVGq-l?Y|#RI7%As^J~H$rYqZjKb&w>lp`A%=wZ5{cND^7iBfW(U+2mmrYqZjKb&xs zG~DOcggs1Gw*P)O;V5bJKHnLgtJXbCSN72eN9hS%Pf6>MfgYx-=NmnVtqJ~WoTmwB zB=U9ZrO^C}9uoRh$}JO&QcAvVYYlry$oAh4Cmh8Qbxrt+GF{pJ`{9J6q@fw?`s&id zbYe!cj`e*KMs~57U+HzaLIGN*ejq zrHARt&IzrOop8e6wYq)I=AkFtSZ%E|SZ~bL=;?&si{3K9D5aF=iXIZOk4893r#tA2 zVC%L^57X5+W_m0+2}V8hCBMA+qbEFI>>snn5_(9KFW_wSEwm+9C0hUD6c2s%R36ou zzgeqa2I@>kUXm9pxL+Bsd-) z)aYq3D*ejwtX$DUf>&YGAi=1#&Z`DJB=k)rea&uttw=D6?QP5z+mF6|rSE6DZrt8R zf*K^$di1@{!*j)`-TgzqGIc-Kmx$cA*@MSi(L+Klf9SOhi<3NELPn|Ita|ONI%hAE zhQ9Hu(xyGC=!Ay*1PPT-UkhHYRY_m}MuJhS|A>wM#>ij|5*qoO!`%d<(q7wg)vt-Z z!Q^`8RUb9zA)#*xxsB~67^N=}%HzD z{i^qpjP*exzM=+=28{%x(lK#XD`9?ht(>c)m7Ij?#$$dj#le=yDBf2_f;FY9>$@7; z!bs3VLN)9A<8FdcM=LoAeS<3>MVS_(*xtrmjiP$_FZ4V zUB>o?#TVJ^VY-|-*Wfvjd8_eUr!D-$x9@+tPgszxa_C)_?3R3hTc6P=1E&$Z4XTeBL~%|bMxdFz>sqjYs6DrQk@!ZUq&Jkyu$CyO<~DAIm5 z7>H7qdFwCU%A>a*db26pU)vpsQkHqEH@}YZZ@U!b-+V2^a;;9i=H&f5UHajA6}6Z5 z;&ZR9cI>VFNWZ$vwesn7O3UZY$yUj&-Gb}?%-g*`zxDnzuKGYt>%HgSx~wkzWwliw zdhfU7YSEyF#ChL)>;3ai`p_*9jQYt-ZngjMdq$a-T+O;x%GGmEf6tN=y&Y6eLhs$9 zMkVM`4oyh!l8?P}B#PLm@#|l?_5KrH{1+>|C0CVTx+JFQHsxBqFVP^uC|<+0M!)Vo zUFp62$?xBxVS-Vt*+pYk$#rsy`nRs=6Yuzq@)kI*s84uY*Eu~TPP+aZoBZmMVALfa zyLofc^--Hku8J{l$JTJG{g-_)TE!g44 z_HOsMY2)jzvC;K>;j?bqxZgx*{cj=YA)%|TcV_FWOM+2xrK3Ma>eir#gs!^Y>a8_c zj%m7SDF<^nYK)#vC?)rmg_w1%NHB`+Z6S&=wnP%TBJTgY2}ZG1R$>lLceVH~m9B}u za3y>9wW5c_b5H-)CT~|H#;9*@+>Q_Cs(aKYJPtCYD1pmC4+-_IeB33$D7KzaBl^eN zTl=}y{*&$)Jyn1Ah&q;I^mIbKIq&Br7?qCHvs%eGW_)wwT&a9I>2}@PM^7hIHy1wZ z9k)O*O7(xYdt^kp4rSC2k5BJaPR484ukT!DOL3O3qDW{Y%5z0xjOtf?KdLuCAiATSOkw`t7BOe9oY>>>;83L{4eZD8{@c!KmHy5_(8z zKbh8}hjLU6dbAf#E7gi(N@K3*A)&o+`i0$Eg9M|r7f!#bTNCtXw~l^Ecl2D5(C#4p zmTj%UTro;}mh}6zHKDyw`qh~{iqh}NoU2tUsaIDT_K=XCeu1{uphxA<@B5CfK|Qd5sZ55-~Pnr+x;--NCg>sY)TjL7GRBM=BpAi#=#ij@g!J+e zjs&ArzSSsNuN6JIx*n;S((YW5P|fCd1E$3&w$M>S?aFUF)ULD(SFKO&N^4W=mZ;Ik zZ&EZSYA=SOH1cUD$C{u=Bb@edD~c(NxuS=J#xCvQUNp*;)xQ`MohwGEeExgH#($#^ z+CxI4o%X6N8Vwr>MrlmcuD5}hJ@@fdRFrl|D~eZroh#P|3F$ed-2|g_4V}_R&_hC3 z!S%nJV3g`cJN<`}7j)jzqx#qGennAxw+0EdG3@|fYcMTF>E5ng-)n*%%^$SW`{=nM zp*f0nfUh-}D@N(>Zg1<7+e1RLD8IklO)yHd-+qn+Jt~KGdb{M-9tq}`gs!3XhUX=B zT8!c-Q8ngJnz!sZ8gbn3(q3Dru@92a*fop{A#s3Ul%SQA52}dyiGmdPA>YVawK= z`?FsV_DJ~jgG!VgVz2&<`&2?}I!Lq9Y?&h3JemE)li68mh&6j`WN1Es2@|*hmF1gA}&eBd(CzR5^zSsQ{4HAq}uDHx3h?5`kfLhPe9n3SM-q3HPjci7L6rWB*v)TdTQ_-$h>7uUGuP~E&Yxuwd4aFS_z41dfL+GcN2_~ z#?ab@&E@}<*51>ShR2nZ5L9#Jv`DCY`FO>&7^QZ+8WU@-=u!XhxXYAEW|n_ru1KhF z`hK;97h@#Gs6JwhM4>ikAOB*V-Kibl{Max3Pt1@>=x%r84}PW36Pr-nIkoFrEzY~K zWotYh=7|d-kM^yYc-;L@XsZj)*=+8A;<(Z^W>7-Lqa9@ zNYsMs|BP?E#;87yMQCvIR_W@rC)J>?o5v59Z`2q)ozRGyw-OSJ;#D7W#jB`0j(ZVP z+MO#B^=_B;^D(V*Pi#^8yRZ79F{?h9mNY#2q(njEj^ngQsC@Yd$Fvw#?~eyZ(V8oI zbVWTi4_w;@3eU<%Nzxwcf z?H^og{KXZg?*IO;ez1Bj{P|PMI(O__dDZdFzV>aeiHra8l>KL361xS02n`Y1$-XA& zAtCMa{@}nKuX?RWFzR_oYUDaICbHnF1Wrs-Y*kfB*h+@oJ zdPqFxKKuLH^}Ws&2}a%N8T!a(YUly#d6-R?dzTotI z?KxKz%eTAaB&O+%@(tjicN2`d{G2luy^&xEpZb)umg~kVQi(Y@-3|KHC83n^UQ2>e zZ~yB@>_6!C*}hkLNT_b|F_8qLRR8)l(z-tAQA>2KF{SZZ(L+ML!1ceIVAQc=XYT9w zAnRQ54xs+%eaIXiM-6&Nu!Zg>7^P7nzgF~+*xlOM;=ca_XB^=^$bLXV*UER)u^c2A z#ZhS_c-^I;-{GhZShFKR4+)h|zr9=6Ac-;RjPgBk5OXNaTlH9j1Mh)H#f{wk4Z~KW;_P_Y(1H1G}S>`Q0B&PYF?ce-p?{sV`m7s^jHE(#( z{*zzy-;=9L4++`BuOK8-H4YMvI`fkc-2bb4Wg0%~T6L@M3OOp(kj$1I64Ug+GNNW0 zBp7vgu5_w~a-|%4kEl-`A6jB9IX(J)gKI5*({P|ZYB}g3G0i`|uE7<-C|<)7xcr;9 zg9qvAOHFy5lVH?%rHjNIGV_+d;P984bba)@5Z|?H>_RZgUxrGFkSKM|v`GB=osR98 z?~-7Y{_fgr$w%g@hCL*v=@{3T$I|Q>>;5Mwk*#wd-6an;9MiSYaOUwZS;?CaNPx}y4f{+l>@NN8rD?})GKg9M}W_q@*O zA;J6nx*Sf6QA%m4Cm>_nC80U|FlQL*qo>uQIG2D#sdN1r&^rwEYe4Tw*1q??>eQLo zLvIfWrIhakWLk{UmuOcz0gKeU)wdbFk6mAL^nP=VG1l&R67h-8{=oi4&p)NDrTy{-<{>NO=GZJ^+QF0Rcp0lry>fG0D%oROqCEnT1ly>Kegj%KdR_`Vl zrCyNlr)C>fIs6+FfduGsQN4SLinO{g8O`d~q0 zX6alpO5a4z`#C-OCbGv8YVXb!34IwjAE}uZqd3})8XS>DxSlyyjs!gd1H*ZOdQM_(lMf0ofA)z*%*EtDB zjUyj5c&*s_I4bq{gX0wmt*Pp*=lbe0Ek<#49W~f<^ybuKF#G06&_hCRZS!1_V3gkZ z=6z7leD0}=(tBi;mNi>*HAmj!{^1s9h-MuK@)$(^fJ zIT|*$T@t#|F5jrZv>3&nR*5;dc>eJGoHKIH3`PxlNUUba(CG6IM(Le~-c$^2w@`8R zjy)vUdTOo~4W`8?UXe<)|BP3c#O{{Jv>3$}I%@EDkY)7W__FI<{Px2KR zHJBEow5KT7poau|!KgukQQ9q*YtTc2qtc==tIl`+M2R zEjq2!Q96gyw0_;@H^o(>q_2PTR_SU?mxlB-TFd^acU*I7zWT~^b<4US&oRwG?=b(rF)ahvC=5XM6T>1p)2C+*78*U zXCxSLqdA4|423dJ8wxaifwu%bfTl~ z8>$1H=%~An>tkrU4I5htiDSop?x$93!n0eu`-jf5)I3fa%y-?b<(+f6Wv z-E!6=uk6l+mGe4D9dfo?8!{>m4u!n@or#apFS}`p~MVYY6V$kqT4idZjIn!d4 z{yy9}2Mv2j=(^?ooM|zNckOzW77hODm%q;C?}sbV{xklvn1oI#QEywW?xMl87^T0v zX4e|_kWl*i|K}Pe7^N%XzgG?As{G&Bu1G|0eq`6E*g=9(Y-26BY3OM}IZ%FO>l9kq zYQv(|<citWGH? z*^6~&w`#3sIPY2)8A?7!X>_gbyzg@uwEpFD6m&&=)yI<4Lqe-^K6zmwicYLMJ11I+ z^N9|;>I+efu?9&0}_nVDv-}n z7)wr%R(^a%nbJtmLqcmsuFc&9qtve47Ai3ZH*Zve8r9w-#^Bv_@>QLAA)9;L+f*X?$;`V z-xP44bypBU4+*Ukt>&Utg9M{u=NaarO~^aX!b3vuT|HYKbH%h6rN4XTye8}+p*O>N zLp)rof{y#C86}NjMkb-zggqp5;(I>pV_J;T&P=DIze^p@*=X+JYKIy6Wy%3lCnUtM}g$aX!A8V3nS`8$Dw z#;j{a57XtB3l@!H#9Y+r>csRrf9`dyWoU)hc4uPM(jI>yPdU*%*eUgRY0yK$U*{Xj zQFBFtQT!T1)tEy`xqAKPvyXpm&HE)EyJB@-&}b~_RL9w zQBS(#<(r3`_v)laJ>kVyZqEJ>FKwRqDv3&~CxHA~P19AIOXrtW;=Gft-aPGL|FPP; z33^C;{GP`*AN`sC)N{35E9UpYXI-|r`iCy9Q7m6vS6^LvNZkD%mu+r%|Es!2!}RX8 zUw207?|I4TAu&ytm8<*89U48Y9wqvfw|m7c5UN36AJxCF^jPv~>b2&t(i~octPc{; zxa!TDcYe-op{tC2aE$70p~tI7MXsWEzH9%=&GghaM`_Fd>i<9Vs96NBiE8kJm;Z5% z;#D6t=phlU=jEeDL8H!HAB^IaUNma1#_Rt2rR7t5Ayyjd^X@CpJ^c+kt}fGJ)Yvzb zc>LeIefM8qu{rtJww6%D+rAd#%1P&5HlD`55cH7vU;p?&Z(jL#*)NgUJ74z2SRmjF&=1L=~?+n!I<<_+tJ)Ka0bp2Oi4sIldsGWUKz0|#v zghq)Uenfh&1u;fxR05$~mH(T!!)Q>)u83lrjuOOw$JWkqMg1es71LrATmGmqwx72y z<2l>gNQ|CND5c?!GrJrl7{wMdYS2SME#LRV-2|i3mRNG8Gg4kx<{z=XthtqPsTQtL z$#05B4SGoI9!p3tN`JrQxetlmHOREas6Owi=Zp~^ITC1$QbA?P6y+S#w2 z4iaAf&^R)DC1%l}hv}+KYj(MeJ_|t)3E5uLi4wRR2MI^1Z)zsKXf!NFYOg`5Exqaa z->Oj>`R;Y)KO}_IO{hM;@3~W38GHTaHG8&;!0cSR8O1i; zicoVlZ+YFN@rkG3Sg#e^+d>p$tU(eg-wA*6wWL1Aw0ab4bJQ3;olp-x<@T8d2}bR1 zC9EmU86N(o7!8irN=Rrn@bPzKW679Sk2+eNGhLO#IUKJQ(_+*(+BIfY4XWh6iki>q z{fT;)%9QsgdPuNuF1e~2B*v&WmhlR`wnWE_Or>2s=<|oypv$2?=+-ynaLJZRK6*N# zKJS(f-~hoW&587GYkiNRhlEC@VT5Z!^Ogjo;trRMqM9A)TWV7OOquEVE;F{bUXpRV zBB9xt?{Ga{*NSN|iuc`-V17mT{=xE%1U)2_L*I#Z6O7^&83}qwOw(I;+&M`wO0=)^ zsG*swzImtm;C0jd&Gj@A^pMaSz5E_Uf>D~khxtpMegk}Z9JaG=C$d%O@rIhlkOAiU9 z@7YHbfErGVQLLMYE&rWk^yzg=LRY|J@InZxZ-lMEsI<Sb|6a5;uk!=idrYsE>q`fcMaM@LK@m}I%t&QL^(__ zify`Q`g!Hr< zFxPO&8O3(o6;yJyAJ>}Nm0OA0n{zu7^pH?Hc6+PD9NfHRYfuephxE~}E(!HP?bOXn z?))-}H9MArJx6<+-ImzXMuHv^+E?v%yqjQ@_G`NrjD&U$yY*=gvRfsu`bf}2B7P;7 zT`Q`K@Ce89tu@@PNGP{?OJrJ%Vs6(Ou0ayo8J+hiro|{;!%>6RMD^j8$dpEc9ulhm z)d*M6xYxQIjABn)G-eSzr(I8B-U)WJv!hAKw)Ub?bH%h6rN8ec>>;t*nJJ+;#*&^E zqn`PaU*7!D6XGta;QlT{=b-4DPU_Fxcc3#^^rfh!pO^IYZ{E^FLblh!A~ycJCLASg zeG6^TXxO+fLuZ%h`)7*M86*12*_xob&aTk+uN0+|FZ5-zftXbemRzTH=<865VwuKr z&_hBeZRopCgGNEeog9o(uJrAtHNg_<6cy+FXuDoW=!^+pg|Qq=i%~lHLf;Tua#gOA z{>@unMU}&Kz^fjy@!u%9>zRbEn`?77!Kk#A%+8gsqUv1VtU7uPlF&IO`exNq@|Lx+ z1{tNZOY}vkHKEf-?9ml^La5upy zjxh@{s~mb8p*QHtuik{Xny`oI%682j zPB=;$w%3F`On3Es-mvjq#u(M#mn|Bz>O*TO-e<{L({qCBX(5Uct9|y6knO8}IN>O1 z*j^L%FkRWc>W34Kl7{UyVGq-l?W=w`;V3>+tqDglUD@twhZByHhV3^?Qwcenk(7-M@nzG|G3vJ-a78=87Ku-ou1`h2$rT z-2|ibOD8`ejRZaVHI<))s67(&kkGH5@_7jfM(LMMo(ENpIh5wDer@EO=yyxbyV{!T zX3P~mB=mch{92LFx6fVA`n&t)TEiX^`bCQ8@Vf~{>31@#XM6e-LtWRypIZ;b=-qqe*PooAs zB-9J?Yej-l>RqmzQG*`!TGumE8VPzxXvE0d6$wUhR2ntd*YtZqKc%o2j08O-^sCVP zsfYxlRD;&58gnSkTlP-1e2;KUX?LzjsCRh;-%T)zJ-8BcaPyY=RZH|3b+lZOP|MH9 zM5e_kj(kfwO3orz?gzTMe%ew>d26SKglf|%EgHobe@D+KwzrX>hlJW&-p@%eioJQ% z;P12fyJY^Bv=Vc0<1f8Q?EVEP(_&QmTe2cEZ|NZ+JFky}grko3w9Ry7=l4OT#i*mb zXCNUv-y_Vl7^T1OChQ?0JKyWfv>2to?VL*oGtNAt$UYicFYw$ zBxJj04<{U@lx(jFdzh|l*X-ehqoiSbP1wV9Locgyrp2fz$1cKkPC~Y8cAYB{j*^D$ zHDM3am7Ui)(_)nVz9MGL0JOrZaZ&G(wfd%W2mJPYMU?Et-M}6aTF28l2l?A`6O7VY zp-x{|6MB2@^V75vqw_2j6>C#>?L;Yq{>|H1aSe|&Oz3Xllp;3%8|AQvgvzATFos;s z)^L8cN~&`w6t(+~Lk|h9X6VF~L8F#~1f#STqEl7|qUMSot%c}hm80j1gw{fI7R#Wq z$`zwx-6$heYid|cF5$%(2}ZH?tO?gS3F)ose9nC|X&#k3fu6|=nU(xbIB_YbDDJ69xhbyt0`pkqs9l+{ zw-OR6pPnw4I-jF7kt?@dM(IlX?_nFc)?8JrWQv|EFOMj~H@-2|gF@(rzh z4sPDkqfyko=xDhjp;6mCcz3QC#XHeRur;Wk`~GpXmPkTljPFFF2Ge2`$K#REs)hTY zY_|-pQ~2*ALC-4{62V)aFqUTd#zy))0OQffWrw#NyGM~CmbaW z+iSuerYqaM;BdlG(y+ZI>|wgH-3tyU93>6gYr-C;8+uv)U|Nida_l19qe#ehn_lON zgrlTkdrjEGbY;6298Ne&8n)MjJxuotzx8i7=RE)JWB(|q_Fwh17^Qx*>QR-@I}-Pt zSY3)au2#=HlU;H(OGE2*ey-KZpJ!ow+p-XghWiHzty+5qxSL><*46T-39X;{`Bkg0 ze*2;KJ}%#)F{>O*OKW$2t~pvcNNBCl&s2*>F=8doC1;eb?&?{s=8B$JeT{buN6Qrn zt>djUR=HwS`i`s;^pMaS*1Y5-7^U?=U+I$c@~`|t0UoXDyPlcS5?+ir_uN;PgjV?T zcEz+9rPY47;{zIKOR*;)-bN^;Rl8bpWe*AI<F@5FYYlryNYC#`cN2`_ooFQ3pLI9z{Yt&S+9N>^3EfxnT#;ZDd)ivVt(}Bc zWb>=bv>3&^-Kg=BvwwGU&LuxwpE*zb$nS2x{3}1Qdj1><&DEW&gM_~Yvzrj@D88i_ z33?6^rgsyf9mTg4BSFtW!t`!Jw4?ZzVkGD}NSNMDh;|g;Qj7#W2MN==3DJ(?TZ)mO zhlI{w)*hPWO=`o&wIW98ZJS%qs6h{jI7d4B&JPJj>2&MWS9@mNKeXFVZyuFj&3#>R z^&8t`uIM2lJ1@sU!cpv-YYj&+UD>-w9}6gYr-C;E8EYB zhZByHhV3ny`oIhFD`2ANAV6f67(D-Oz$Q{JBoL>k)Y=w zVR|tnu-5X{t%M#DdZyJ1V-TM^>zUhcTzJuOsrk!d-~RTo z)A^Mt+xq)7z3bNha{JULUMFIv$F|bt_o@bBa+K0ylVJ9E_VXXQV>v5)n(47E z4Sq#ynm|mBQd*3%9U3>@=Et}CKWWfoTN?Zt*ffEd9Hq1vWji#^`1C!tFa7dQR}Fe> zOT%9^TNCtTgy?B{-gUR%-uc9TUNuPAj;Kd&bX7uwgubR>PeufNhhMqz_{k4^V$~pF zTTwolA~Z;hp3ox^8vpGhc7H=R>8NZ3}Ce;*YZAf_y8O{k@-#jDPlmTeLIJ=QdV zm>eZ_M%j*Bz4n4Du72tN^6aWXkL@Tef6obGa#Wtx|$fwnL+gBd2LRDTSEmu^rcn-{9Fr@HFK`xuOG3mud=U+(X%EZhu8g^3-&(t(N8{D3M6d%TB+ZMMn*7-b`b6A zo+b@lAE#wogz859UiMNSD}qtBL!-5;O3-6l=|&s#^Z712lg*| z{we!wf}V_sT%Gr;|J&Z$2)Jkz4kVbZP$vPPCWK+e`0g)y-sUwm&E8<6OpU0{^$wYH$48KRfB|W zMQPTrejd5X2u9HkqCK%x4W?yVgq~#7i)Am*I4gotwp*^^S*;TE*jBpnMCNg~J*%w< zM%fOHQr~*!tYbSpwxyvbOZCYp$1Z|VwnL+|LOlsr4SH-VT|FVIPlm=Wf>E|Zque>S zzSq)YTj~1y=WBwVjEG#7Im6a-1`@U-O1Q$E88SwxU%3 z8e4++!!m+?W{z3ki(a^?vpcEVR@9eYzS-B=FOe$}^khV6yt|B`@4hJB$&j$Es8=1| z?CZqX&>%riMuf&&$_RRCyv3PF*jCgHpWl=dvp&!?NYIlJp>eC%KWgv&@fK$yVOvp; zxzGN-PWFs)kf0|cLgT|_ru2`#v%bZdNZ3}CzN4!1Mni)HJsA-iH=!yCOkPMubLb ziQCq8XA-s*^`(o?ME@W`Pez1B=~3I(2WJwt74@gro{4@=f}V^BjWRN9+gLJ_u&t=O z-1#hwS0w1kh|nk_+_sI0GYQ*@dhF&bjJqW0$%xP>BlWh8?K276in_xuoQ3-b33@Uj zG|C-k+wM^_3EPT#>Ql~I?p@PFf}V^RH0oOe61H6qeH$RglBQ7!rE5<{ghnfQosp5S ztteduov$AnBGVdNLw3T1%|+T@tnxrBY%5BmgwBi)4HEQZL};`Tu4<65ttgFlI*UFu zNYIlJq0vU_szJiGqBLsj)c?>RK~F}6M!Vxw4HC8^>Wp$?uQf>MPG(O=EE>AkRt*xi z6{WjqFGsuAR$}yo9*NK>CD)u`MVMBUW&^!GNYIlJp;2m3bDyd~!nUF`tLg2E1U(rM z8l@#_4p%iu*jAKgXT5)rpeG|jqx2}vMXLr0+ltaGv-fin^khV6l#xMm>Z(D)wxTp! z?&B2+dNLw3$_S@tgE}UXu&pS~`un&`f}V^BjWSZ}8K-KHu&pRPz4$IMO(f{ah|p+H zUiFSc!nUIP6c+uQ1U(rM8ZR&X?|%O-o(HGt81AWIE9%$pbZr0PtNg4+V)U$u(73T& zt3PXN^dxL6>H!Zsw*ULT>Sr7h^khV6TwCh=$J_HD3EPT_6No<4#zYeIWJG9OS^D4J zwRKg0B4JxmKEEjHg9JSp5gOlF`roHxRevI3TT!Q8bMpS3F8y#T2MKyIA~e2M`rjAY z^B@V^HERCx{o7u8UDF^j!IKf8@ru&_u4>PNBy20{C;!iKa{bv}`5`fQnjVSJcxQRr z_2u?FNW!+F-tvF^w_~1+lspQFUu+a z=U&_U;6l)o5ux#o(*Hi$b_kKMt*8rs{?yX0JYJEYCnG{bb<161F2scOPqzh&x$$G9u`9=ZtGLF|Du_rMqY^2Z_d60x{Md{2cowFSpB%riMuf({D(_>iYtMruY%5B?JJIh?LW2Z784((L|MrRpzoM-VlCZ6)IQh*QB=G?88K+odo2muE{DDzF=$jm>DrSKq0vfS z=L{rlD@s>E-?s=267*z5XtWxv8YFBhO0}t9?u7;kdNLw3T1%{RI1;uMrBMBSNE%a8-kZZAEFc z)0Z7Wg9JSp5gKizt{Nn4D@vobzEBYwBZ(D)wxTp! z?&B2+dNLw3$_S@tgE}UXu&pS~`un&`f}V^BjWSZ}8K-KHu&pRPz4$IMO(f{ah|p-y zYW0po!nUIP6xPO)c)F_uJsA-ie^iLyezw;KpSC%6{q0(R4qH*zJnU(kpMK2uw7-)W zJ!>K~{<^FW-oEV@C1G1pZ$J6m&10^-L(?EZPez2sJ4>CP)1C)O*jCivy!O0OzB@M! z67*z5Xnd`--Osh>K@zqV_0iWpeRJlU@7gp-(326Nao5uS-rLp(N!V7@mrnYP&ExKW zLen5YPez1BDZ^gL*|x0XOeAba)cN(~$Y@t2rm1@}BIuJ#|NC%z9wcE~Q9cF;2?B0*0^gvRSi|NB&o zi8Be?iqe@?ecUBMPez2sO{M?+PVD`dN!V7DPPXdz4-)ibL}-*d&bHm7W)ij|>SElx zNK8}rWW=CR@0=uTyBzm?%57UeZyJ?Qy4@3cBtoN=yv`X&*jALT!uNdFZJGuNdNLw3 zS`AhW61Ekk+C2ICscDd)CnG|mwZuAyBVk)nYL#bv*EidV4kYNwh|p*~s%nt1ttj=b z6HfTMra^+9j0lZ3GE@x`wj=5}n}?ooW78m^5yzg42)d1lRfB|WMQOCV@dv-sG)Rn| z&?6BVZEUX^By1~6qxQ{@{Zi8)K~F}6M!Vz0wL)5^BWm89ef*0}gM{v6_GCoR?atY* zRVPdHqh&X1U(rM8f_+1HAvWwsPmWBGfgBkLvp*y zh@jhytX->4m{yc#XT5)r7(GFg2#q$gtQsV2D@wD>-p@(UlM$g&Mh4BPs|E?%iqdSk zk5?q<$%xQsGyOUylCZ5P&HDSeOM;$^2#xl{QZ-1}R+OGz`dxwqJsA-i?a8a&aY)#X zC_clHn5OQ@h@ka8MsIS;{Azm93-7eA(_l6Cv8^bb+@up@V-81xo{R{M>&o+BdCPKK z8YFBhN~b{S9NW+!K~F}6hTg~M&6+ew*jALzLe_b_p+SP4j0g?AkI@@KX^^n3D4nFN z6N5v81U(rM8hRh2H=WWTVOvo;Z&@d?g$46-aJc#gl$FXq*$H*8X6?%$%xR<`xw1Jmj(&jiqd(qI>9wGNYIlJp;6W)9<22V zX^^lTQSqhE&>*3cW_6aVJQ=ZQT-`Kg61Ekk^Mrdjv|3_f^z?6z`tPBkHJo;>%I^nz zTDBFXlZ|_Qkf0|cLPKj&t`UD2*c(326Np*6MEcFXSvds?;?r4ylh z{~$q6Mudje23sF2zaQ*r*;bU!rtbZm1U(rM8d~FQV@dh_U{A}oqI6<*AFoKzlM$hz zwc0i&mfsKdv}`L%XL|Q>mjpc-5gKKr-nOy5{C=>fWm{1?L%iQVNYIlJp`o?&c8@B* zAM9z_R+PV49et1lJsB}*)O#%n+b)N`88B#6Lh0I*5uu^=`LZ%o=L{rlD@s>EC#Q!7 z33@UjG+GT-4HC8$rP|b4>!Cq{o{R{M))MzLCX%qND78wR)E*in=*fuCXg#WGkg%;N z^)8*~9vUR*$%xQsBSY07VOvoeC3FIOXpo>MBSNE%a8-kZZAEFc)A{P5L4ux)2#q#U zR}B)j6{S&I=edUl33@UjG};}fYLKuUQFqzbDf6L0LU%HIGGfuty|!wQu&pTFMSD5g zy|xmgC-g{!Mk%@G3@gI4qBI-m^+AH3j0lZVgPQwP4HC8$rCCjHS0w1kh|nl4QFFMe zLBh78G&}44g9JSp5gMgOX)andNZ3}CW|_U8lb|OfLZgffnp0N|61Ekk*>WGRNYIlJ zp;1OSJsZ?9k%VnUY1ZGzT@v(UL}-+ede37!3EPU&(~IvC(?o)vj0lbP+@iJf_%t*+i6ebX|mXg($nO>zSsTQ-${&~H4z$I?IU4ZQFOM%qwxaZw;-(9JtZ9&-CnG|G zt9>MFD@t!$u0HYpO@jnI84()oO;Ife3EL5M{^q~F*cv4C2Fjj{2)e!Tsv0D0D@t#_ zZuR%pATfGEk3?v+H+NNogl$FXE#7}S`2p=(k)S6dLW8S)By2}iS(ST;HAvJIzUIk@ zpt;&d!nUIHR<)Od#OR5fkO+-Z@@2J;gl$FX?QpLT67*z5Xp|aUR{KcUj;QA>t*5>h zT?oA~ce~1npxYaI)%i@qwxaa5zV{CjqbKx8ga%jpNZ3}CRvmgjCqYj}ghm+|hV?~Q=5mi>@mU|b8y295y88K+odo2muE{DGP6ZhJtQ3<8nJ&_XE z-xvxF67*z5XmGWUgl$EsHcx)X4>b)E^khV6w3fK1`ydJ1ic+imwL4gY1U(rM8eHuo zVOvq^U9bL)`?PY9peG|jqm2x;93*T<)N?kM-FWY&K|&*rJsA;n8xyMr3EPU&Xs2%( zN1c-xJ)uV;G}=gAHAvW2lt%4WKHeH6=*fuC;A$TU+YvRFK4=XRx|7+H5kYgckA!VS z=`PyKL1OfT9*NK>CD)#!daX#m zeVS95u&pS~&U*hKF?xa~5gJ_WBVk)nnq~HWPJ*6{2#qo_4C{kV%e102Tkhi(33@Uj zG`QMF!nUF`>+j<(33@UjG`QMF!nUIH^wRGVBz<4VTIV_GBq)vTIsxid(@)j+JGK?2^PFz?XJ@tdJ|yVLh|th^PCC&_8YFBhO6NJ< z|DQgrX^@~NBSJ&xIq76BX^^n3D4pkY?AXsW4HEQZL}=(dC!H`R4HC8$rSqIV_PWP3 z4HEQZL}=(dC!Lfg4HC8$rSqJA`tZ|@%@=*fuC z(AlD`56&cPD@y14_I^%+o{R_$osrtcl9_~UMd^IsK3;cnn~DJl+O3{y=$6C(325^M!j>A zu67*z5Xp|nMxoFiOVOvp}W%hnff}V^BjWRN5PF*!f*jAKg%YD2eK~F}6Mj7Gs zY*5EU61EkkS$`jQNzjuKq0ydLss;($iqg}I?-J8Qf}V^BjrQbK?>HoEE6Pt{@jOU^ zo{R{MwxU>{2lZQE?-#YLDE)r7@An}=Pez2sb*2A#zbFaYiqh|Q`@SU-^khV6v=!dt zx<`?)ttkC|x9`6qK~F}6Mq8=gN`r)LMd|mueIFSKdNLw3+KPMCAYofk{&H{BISG0) zA~f30fvQ2mwxax{;LspJPez1B+W}EENZ3}Ce!tuICz7BiBSNF? zNzjuKq0x4vR1Ffg74;p{zub6N=roa_CnFY(<>`)uZAIxkj$V$o7e~38>B)%DC?#L^ zi;}RdD4i?P>w^S684((#2ABP!By1~6=cDv}$Ry~=h|nl4aoI0Q!nUGx&P%>ul%9+T zjnbo*{h}mnD@y0p^nOl)o{R{MGBPatMM>CJl+NAh;}r>dG9om}2)FDPC1G1pIzOn7 zyCmqzh|nk_^|D`-gl$FX9Hf5#AVE(?ghsjJEc-=C*jALjI_`T{Ij;`{JsB}*)O#%n z+b&1n@6$9Yp>*xZh|u8fPZG8jrK`~QEs>xnBSNFqV4atcu&pT7X5W8Bf}V^Bjn)$P zbRQ&PTTyD2eIFSKdNLw3T92w4By1~6y{qqsBSB9_ghm@nss;($iqa_2_w|vWCnG|m zjc`?igl$D>wCnp5NzjuKq0vU_szJiGqBLsveU>EX$%xQscbuw0!nUGx_wlaKdLPtX ztrGNP#G=z|rTTz+~^!gw{Pez1BsljExC<)t& z(yXSpD-!f%L};`bSuHsU+ltcctoIKR^khV6lpeM07bRg^QJQ7;eolg(j0lY~GA#Q= zN!V7DX3KrNB0*0^ghmMBSNE{2vjvl*jAMKpGMWtAVE(?gho5rXsc^Q!nUH+|8#c<4HEQZL};`V znyLl~+lo^E(_Jn!NYIlJq0vs7sv0D0D@y%Ock9p~K~F}6MmsU9YLKw4DD^+hIzod4 zJsA-i+OMq{lj?(nZAGd7Y4#KvBw^S684()#t(s<+(jZ}5QF^}V?TQ3F z84()#&7EeK(jZ}5QF>16{euKO84()#?Vx6t(jZ}5QF`9&{hS0n84()#4Wwq5(jZ}5 zQF?Cf;}r>dG9oneTTaa`r9r~BqV)XV$6XTiWJGA_H>sLkN`r)LMd>|8zkiURCnG{b zE8*=PHIuNdD7}yIy(_*yXo8-M7&Pj=mV|AWL$km(UPZ1dp>*xZh|p*yKdoG=iG*!M z=_+Uz7#bw#$%xQsHCQ!B*jAKkQ?tO(AVE(?ghp$LdnyMB+lo@F)GRPGNYIlJq0xF& z)gWP8QR-cq1%?I*dNLw3+Q?8fNZ3}CMhVRVLxTi884((7gsU1PY%5Bmoo0cdL4ux) z2#q#UR}B)j6{S&Iv%t_GK~F}6M!Vxw4HC8$rMr)2ouNU3o{U&Dmh(kP*jAM8qP-mL zUR!fTPez1Bn*po{(~8n;pw|ZpdNLw3N)0aOi;}RdD9vhmyCOkPMubLbiOcz-By1~6 zv$NhmNYIlJp;3C&a=s`D+ltaGv-fin^khV6l#yXMUzCJxMQOI&$14)_WJG9`5pFqO zl!R?XY1ZGzT@v(UL}-+edO2T|gl$FX>BV=6@qAHwG9onElUKdtkg%;NKZUiiB%ban zK~F|>4Xx~JY}bmu*5;L#ZAEE)UaS0F!vsAU5gP5wi<&b`By1~6>+{;J5E>-t$%xQ+ zOR011w2%e~+ltcqymnoL1_^pHA~f2UFt^emVOvpJpV#h@&>%riMubNDqG#10VOvpJ zpVuy!&>%riMubNDGHKNyVOvpJpVw}l&>%riMubND!fMqZVOvpJpVzLW&>%riMubND zQf$>AVOvpJpV#iH&>%riMubND;%(I+VOvq!r>0$Ep+SP4j94_5ugjCLttjoc>*dhy zIqg>~4RNL?BSJ%a`m|r|AYocj+Bewig9JSp5gOW?sNHAMAYofk+W*+w6$yGWA~dwe zQoGNjLBh78w2!m*4-)ibL}+NQsCJ)8gM@8GX+LW3=OpOKh|tiUSM5HN1_|4W(!Sb0 zUXh?DBSNE$aLf1TN!V7D_6PTImjpc-5gOWqtleiS2MODX(mv;Y{~$q6Mudi*2iqNI zCShAq+Li5l*Z4hpdNN|rsCP~hwp|YG5{rJ`a#abXYfnamMk{%JRwH3sQMwA+B^DYa z=*fuCXf;?hNZ3}CYE!$!LW2Z784((-CGM3vpGeqNlv<^BiG>CUdNLw3T92w4By1~6 zy-T~qLW2Z784((7WT+Y>Y%5Bmgm#IA1_^pHA~f0vS2al3R+L6N?Gg(O67*z5Xta^K zYLKw4D2>|MB^DYa=*fuCXm^~dLBh78bobG&w9p_yPev>n%lGI>*jAM8qP-mLUR!fT zPez1BDf#j}dJ?u3rP)BQ4-)ibL}-*6T)sz7!nUF`tLg2E1U(rM8l@#J-=imCTTz;w z_5MMEo{R{M(xaB|(UY*PD9ti^KPN#?MubKg8J6$Sld!EQ&6fLkMS`A;2#qqrE#IRj zVOvp}_4jd?1U(rM8fBzjzDG~Owxaa(;=9E7J$iaFA~f_os2$Q8cS+b*l%K+)50aoK zBf19H2X&T{($dqUY(?p5Ql~<74HNWaL};{U=lZNh!nUIHRIJmjLW2Z784()oiN0!( zu&tY` zPU8y=67*z5XtXzwwHzdDD=OYbT7v{V8L?MFD@t!wdpX*>SLLd%589Ivp~2NY zre#}EdOO_fg9JSp5gMfihxI|HWm-{s%iY@*33@UjG)hYx)(4%IX+`O6eeWM6=*fuC zC_QReA9Px#6{S^&-p@(UlM$g&MuuU1&}o@gRIHx3pOc^`BSNE$aKrkbPAF7AFs&%9 z0`+m11U(rM8f^tj<8ECabXukrrPZu{{~$q6Mudi*yu8{+!nUHcD(8FGdVSEIj2JZP zy_RX&b~$vaU>mOvtPk3g5uwpaUZ2&J6BD)-rK_M*1w(@bJsA-itp=+G3EPTNZR%9P z&>%riMubLdiF>8a>-wP6GOZ}JN}Vbg8YJk+h|p*~s%nt1ttj;_ohld_B#P)7upZdNLw3N=qEp2c4E_MQL`{`v(bnG9olej~dnoot9}u zX_ndhISG0)A~ed#Fsu(cEz^q9Y}sSXG?AbuBSNE$aKrkb(=x3n&HDSeOM;$^2#qpQ z59@*dhwxaF$;e$bwb2o3G& z)9kVoV<4QaqO@FCnG|mwZy$rANBWxPRq2S)GGBA>d+uTPez1B>rqvMgl$Escj+tC zp+SP4j0lZ3GE@x`wiTsOLSLZ{4HEQZL};`Tu4<65ttgFl`U-Vukf0|cLZgk;RfB|W zMQPO5SExgS1U(rM8tsl#HAvW2lUC(4peG|1jp6r$PRq2SbQkUAX!qKhD|#{_ zG)l>b-w!%1(~8n;pw|ZpdNLw3N(~ObA9Px#6{T5CZ&xJf$%xP>EphqY1PR-U((J7F z4-)ibL}-*AHT-_iX_;1(W|_U8lb|OfLZgff!|w;3mT5(4w(K!xnn=)-5us5=xZ(GM zPRq2SH0$rUxJ$yeqV)9QyTmk+peG|jqdj@mI}QokitS$UoSz3rPw0^d4ejaE?z7T#>-nNi%e11jZ?M+~33@UjG_+s)E$w-b zgl$D>|6^}gBb;g}*>*V|`GV8inAmbv z38iaKMubMYR;QJ6OeAb8N>||%_q7HIdNLw3S`AhW61Ekk+I-Ku_xpWNt)vq4WJGAR zmbj;Kkg%;NwaPm^!x|*$$%xQsJ*sMuu&pTduE*TR8YJk+h|p*wL)9Q*TTvP%ZutDB z-v>4NRDzz22#q$vtq9YK(rEXpy=X3EPU&sQu-aTZ05W84()oj#D*A z*p8_8ZC><3Ymm^L%$|%`G?wQ<61EkkyJ#;*yVurSjh@gW5gMiB!}+34%e1028|d{x zf}V^BjZ%Zd`JztCw4yYt>FtUHJsA-iZAMm0PQtdLG&}44g9JSp5gMgO4d;tGEz^q9 zEVK7>67*z5Xq1s*IA7FhnO2l$%YD2eK~F}6Mw{u^5srjyMQPUG$6XTiWJGARCzh%~ z!nUIH^y0h3`g~D)G9onEvs%65FfH4P@>5tm50aoKBSND+LF!&RX?@;rQf(_r>+}8n zE(v-vA~d+#N5ZzEw5HzQQO}(#2k)S6dLZiL8s~RM1D@v>IUOk&867*z5XtXzwRfB}>h`P(Z*Yw8oMYT`O zo{U&DmZv)swiTuQcD)?!-K%m{zb@ZBp+_P#O39b?L8fI}QQGU*>w^S684((#2AB0g z61EkkJ&V0vk)S6dLZh_AWqpu@ZAEGCW$zy(=*fuCC_QRfA0%O0QQAY=`#A}EG9om} z$gr#rlCZ5P?S<{*6$yGWA~ebfx2zA6u&pTV>Fwh#33@UjG`QMF!nUHco4MaVNYIlJ zp;7KQ%laS*+ltax;C=5J*9Ymzh(V*?Yf0F4Ir{tEma9rAU3)SjG`QMF!nUGx75aN> z67*z5XtWxv^AZxa6{XtrJMwxTR4b_jJsA-ittIa1K1jm0qSPw=uD`z1S8J~XJsA-i ztw*g0(~45>@|wjok)S6dLZgigRfB|WMQN1i>o_Fn$%xQsBV5%WVOvoe?YxFGO(f{a zh|p*wb=4qYTTvRdy%tvQgSs13f}V^B4X*Z)upLo%+4q{>c)qCaWcFmlqJihZPMB7d z?xMXMTpt`gL6ZoLHUp?7Ct+Jrnho^&AVE(?ghr{sWqpu@ZAEET)7upZdNLw3N=sbU z2T9mglxAnWe~_RjBSNF}sAYYSgl$D>mf8C`33@UjG};Wg)&~jOiqdSkk5?q<$%xQs zGyOWkk+7{O&HDSeOM;$^2o0|Gk+7{OJ-zrYF|H5NlM$iOp1kTEhlFiK`6+C@K1feS zghp9qSk4z!k5%7OTDBFX{-<6X8YJk+h|p+zYwNQb3EPTN|I=s`8YJk+h|p*|eyauv z+lo^E)2JF6BowPgM@8GssCx#5gH`u$%xR<`n+aLst*#j6{Y^C z*;8ncpeG|jqy0jmYLKw4D9uAP3k(es^kl@MvHX6Jgl$D>KHbZq-E*3cmV(dpWJG9a zPoHMu2MN=P(sMzt4-)ibL}+Ngw&tVKAYofkdcNuHiUd6w5gOWKsrjfhNZ3}Cp3{2& zAVE(?gogHtYIZ3N61Ekk=gr>FNzjuKp`ksmnq5kRgl$FXxw(&5B*9OY`1?V6 zGGfrE_gWIRT@K9x+jteZs)W+DCnG|mmHf0)j){bAMd>PN78n{N=*fuCXf;?hNZ3}C zYE!eo&>%riMubLdiF+ys3EPTNtJEwoG)T~s5uwp~RMjA1TT$v=ngxai33@UjG}_2e zHAvW2ltu~70z-oYJsA-iZG@{DBy1~6qn&1fp+SP4j0lZ3QdbQUwiTsOTeHB>AVE(? zghspLR1Ffg6{Wk6W}Tryf}V_6G?w2FlCZ5P-9>vj+P${sik^%JjWz>V5vCQT*+8!k z67*z5Xp|aUem_XUwxTqv>FtUHJsA-ir6n%EA0%O0QJS6g{y~DCj0la=qn6(flCZ5P z%`$sGCqYj}ghm+|mfsJOu&pS~miu@`f}V^BjWWV5zaJ!FTTzj5JsA-iWu#ty zKS;v1qV)9QyTthWL3%PGG}@C_z2lIuttdZ*wXp=hAEYNELgS@{cz*jH{WRTF_T2a! z(XbVDw|m^QdHIul_9uzavnE30hO)Qzix<{8!$iWiqAq;aO`B(2<+DFY(326N@$ORR zzZ7$yiG*!MJ@Jm;DCP4xkR<5Ih|u_KX}jNuIow3TwxUkD{u`U~PWn(gV~Yem84(&c zmOfbiZ>xJP3EPUg=H_Kzv<8W3>Yj`U z`sw8z*){QOP)gDX+lqSb>EGI1aM6cbIY^A2ph<+rmoB{Mw9-=QwIX3#QBQdBKWskp zDQl3RCnG}R`U|emnP*jlgzbo$%3SoiRt^%S=!+*K7LDb!P!hHk_5RDJ{a%iuu@Ivt z^hkt8Df#hst!5Io6?Mule#d^V4-)ibL}-*6Jl^VjCSg0GZnfXr6^Uu;o{R{(w8U*| zyE6&fiu%b*ZnfY02Z_-WdL%+a{jc@GnS^aco%g-B-tYaK1U(rM8s9Aa?_=$Gkc4eT zz4!cEm)7I)iUd6w5gKKL+qN-rCShAqdw+iG{XXuJpeG|jLv5;!?K276iu(1h+5kSQp%KTP zj0n1oa8-kZZAEFcyYN}>==VX5qLmmup+_P#+DN@3Oe;#G_TBDb4HEQZL};`-PSqe` zJEC;=u?C5_lZ7WE7LDb6Q4+QlrMqY^N4wY7T#cT{35n1sCD)u`MVMBUW&^!GNYIlJ zq0weCRfB}>i2CNnt!J7@Xoh4@Mg(12qULZ_gM@8GX?E882Z_-WdL%+ay~#a_gl$D> zmf8C`33@UjG};WgmV<dG9om}2&ZR*Iwq2^ttid<`?yPjo{R_$wW)F+ ztQsV2D@so<{VqX*o{R{Mm&UVNz2lIu9Z`ISBf+P;j0n2i)%L!-eQ#o#F55ihyjQky zDQrdE{T`QXZg~Hz+TTfxo;48~D!E3W(yu2HwiR{Zvo70Q{X>^F4HEQZL}+}l)cOAM zJlNARt*9s6@$yo>S2qn3^khV6Oy!pYA8OBoBy20{r0Xx=TzSc#H4PHPFw{`cPH zd9V|v74_WH->`Yx*Q`Ne^aM>JG}=gA%R$1nqMq>LD>pyh|o~qct!jDAPL(M_11E&eD5ML zP2H0bUE{Y(UoYh-|2kpY<#^@oUeU%9X_!#D-4is4&}b#Ea|RN&6{V~2!OQ=+X^@~N zBSNFqVAUXDTTxM)FK-$o=*fuC(EAw8E_J0y*jAKU!^khV6v>sJ8NZ3}C zde_q)_8*%D33@UjH1uv)vrCnOgzbpBYIEuQvZg^oBaS^85p)~jss;($iqdHJ&dvj+P$_Cqi0QoMkzU-2YXtk6{XoguMZORWJG9`8r0mU=8A;vhmod=JxldQ3<8nJ!>K~TFH+~ zfrM>E=_=gs;ooc;Bn%hMeR+lta%w3nmZYn7||bk{whM8oj)ZMRY1ZGzT@v(UL}-+edUzgm zTBa4HrNwj zh6$zHJ)uV;G+N2)oPmUGMd>P>@u9zM8YJk+h|u8E9SPftirV~o(;z`lMubLtGqI=p zAPL)wQmg#gbN{Akkf0|cLZkJlszJiGqSU)S@$?&;1_^pHA~f2YqN+i{c0^sZIpI&f z)-*_H#IYwMf^K7C)gWP8Q5x+|xxF<=jGoXV5gKizt{Nn4D@vpGwU>Rhm4gI584()o zj#D*A*p8?-mY!w}61tPwlM#!?@H}Y3w4!tu?d53q+M27;6M7^67*z5Xq1sbYb>=KBy1}xX3HM0NYIlJp~0s+61EkkS$`jQNzjuK zp;1Qa;d#($nO2mZUiw{v1U(rM8f_)6-lIs^jwn9Ek>Jx^Mg*-BXx_Hm2ftAFi@xij z_dorF-~asP%8%=OyYF0V{k@!|f|XH69VFiPh#NL9`u&eodN;u++oAE!@^4_LEIx7r`joq4AZ{o4(LmB0aYMf6CqkY}=}=^S&edG#ece(uqhd$-NZ5 zue(5=_kP%jrHMz4BRXx&fG-5{%L!{LyG(F{lMa+~h-uDPVQ3hV(q!=7np;xb zkcWphntPf;(ywp**SY@J`mJZJ>v^A^qh3z$^Zc#<+F$G1txFn*J@+%~7yQeoipCPb zDBGdI@j;JmX()aDZ`rHW62U0jp`kJ;XF595V>{CQWLj(g@1n6ps5Wa<*rB1ePz_7N zQQ@hC+FR`tdP@YOY)4AE+pfMP1$t~NUG+%yxzJc57-c&&)YH}Dr9qGFNcVlIUwxry zED?G(twx1CYv@_dQdjg;;)n15Zj>Ww3<*Zrp6g0ycUglT+bYM|=l&JiL(lY$2u9fs zjnsk%-RAVzj=FjWddw2BS}`i@&`3RTmQc5FAXLq@-=&`MG z{L6oNJI47E!6@6Ik;<^qs8YY8$F?;7{a^ek=Bp)wQMN-PwZ%rGN*eUomc|pVdK>25 zC4y15LnHMNJ^h(A=&>!0&z}3%`N)vx_94M2+o7SSuYJU!$F?-Is?i7wdx>bHf@n1I z8Kk4aQ`426#!I6iBK_607-hSuD_!NB=&`MIRc{(Ep;2mA#L7`hi&3^iqqJbwpvSh- zjrM;>(Ezb>l+t39?a(Maaien3V_O>P#~LqD4iKd$zGJPl7-c&&%81Gu^w?IqN?-pw zG(hALC9l$AlOr9aV&y2M#VFgMQI0rSgC5(Fu8vpM0I_mZq{XPPXAK=| zrIG&Vsf3QZwH%riMg*g5hlb`VjVdY7V_W6W`k}VR62U0jp`kffqe>d|*p9mTB>L47 zp_NnZePM@&jvX3R(r{FGDxvjU9Un^sqijb?ItFS~Nr4{QDu>pg8VOORC4y15LnDub+fO9Z2Ahem1(og3s?lpfpC&^lBjA@|iIP}<#bmNRH>?K0$(0a72=Wy{Y2#qS0!%?AL3F&FPghmRR z6r29DrCqG=`leG4tfo8V{ksoa9mw|neV<j`Htcr_g7tZ*=%v?YWH~$-M@YDc{k4*?TwQ$a3)Xj>@uh5^ebx)+T8Qj~$h4Jmw%&i*BXTW@_{;rai*VbN3riOCvzgG29HDJtF=`B1jinoT)of>C;pMQ=EX?ud{`bwv*ey=kL& zmqeG~{GXO!lu~;2Wj8Jm_K@&9M!g0-e&@&Ka7uly>>=T|d3p`zmr;HG{`mGy7_w^4hLV3gk^=rve! zKToeHmZ@!z))UX>i%?2kznV18Nia%f@?05RFqAX~^|s4LaxLoZ8oehf4fg4XH9-#v zz5k;(Km**8IDoWr>`IMtE8C5 z#|_!zx3*kY-}xK=Yd|o{?_ljtsNS6x3BQlkmxBbOI1}Z%nxe+0t=1E7Z7E&9UDa!l zVAS#q#~SrJib{96c3V%pqbS1f685` zqDSAg)P6{cVoFg0mxCS>`tqiBI+`^KHf@n$l)eY5eT&9~*Mt80siORq(w?Bl-x*bu zw4G944tq%W3!=RS(_)mr2ig<#_=}!<&lL%OtFzZ&t{BCh-c-(j!M29(QN_bMaT`?#AuI28zVopf-i$y4&|LC{<3D&nHLY3chfaTgwp&7;t3UH6*(2hV zJKmCQr8K@WK@SPdE64uVs|Fe*7^PYtYtTbNGtqOd{^NlL2}WtY`hU;fK}@UEch$DP z`oa(Av=sH=_lB*MT!(F4(L+LdPAL;9ef`Cn!D%sy?G&-`ZyY&Cglgg7AAD#~a;C*7 zwtr52vIcvDj%sIq?Y%i&rWCOz=pmsw|C0ST9U@nZ(ma2Uhut_JSZiet0Y;CNP) zX9K0=^3BAwDr3+d64D#bS4^voI(_|bzWkGe+Fh-xhlFauGisYF&EXz7I#PQK>WJ#T zFcZm`wwRXM#5 zI&9rB>DHo&Y6(W^TK{4H9CS{7)?m6vT=C-d?a%+gtVcTX6aT93R&^40zTze8eK-8T zVD(CZQLjDorR#5g^VmwvxuWOjkG^#MOAm-BrnHwTv^ylNDzEeE5d@udH7 zzXhUtYP!<<^3Of&5Co%CzH=^p=zyR{b+!M7hvcZe<%)#b=I0L&y00sjgHh@WZ+z~9 z2f0#Dyy~_GWsmyOnXe36M>VI^YS2SM_l+)pM$j`csqd0#qo&k?JBWl%TVHt5ug+zjo!dEA$%r<$hlEdIrHZQ07iO5gp5gxbdAvBs+$Op8(K3*&K4&y7zycb-3((y|7L z)#}`Z8LmyMM(KCgdaqGEm5`q2;AMhQ90i$}f=hQZaNk)yqppxHT0ilq+YZdv85-ie zH-1mKc7M@&ecaL6)|@!Lf3Eq;QJU4Be%w)GA~Ka)kZF<7{CLXS?>)G0K!Q>E2zP7T z;V;SO|AdB1tE0jF&bo6>S9AW|?{cTAF_)ZaDe7t09R9B;2MOst{%Low8pDz^O67BI zcP~dxHysmiz3YNTO{+$+7FrF~Nj|FGx|&N~Q>si`yCl>$C*S28wO=(QcUp{6`yX}G zKMe@YgYKi6R~)4g<&@?;O_~`r4%}*aZZADUMALWYTxlM3Z`TZW&L#KBCD&LP6ZDWs z`s@9-20iC088PqHv}%-&yVh$7dHjTk(mnIw7Y}HpO1mrhtWiCcP!4NKRi(XN!l+^G zW(|5ss1E&XOI1+GNwiV5WoKd%!B*4Jz_Y<}3(`YEJ;pQ9tdWe!mD{6@x?rBiT7tb# z8t&mNUrW$KA|J2H=vpQir9R!vR|SjSZjX)zp5dsytU)3l)rNCPn^rnTl_>r0I_x#7 zrxMbub5~{B_Fxo8bB$LE>f7h~in+#wzO}BerpvzgL&tAF@6sJlq)a08_4;RiI6d#0 zqV$#d$NzpjdGzuxoUncIwRj3CMaR<#^pJS()hBHK*0VpDQ)+X?oal@7`d<8Et|YU? z{F0EKzGyGH)gZyB7ykGO=}!E+D=`H(ZQbk0Q`0xK;wh~&)~C)Tzy7mN-hS-e@FZYE zIPWid_K$AA@>6fh>56W0H52rZNLNKtuAKh6~iMjieWr*6OQA%9)VQLt&N_0)9F zKI_y44VB#G_`{n|nR`i_!ZETTe|_dKa8D>WL&6#a`Lg6+I+0qR#*A7{SW~qq^Qc z*RGz~^plJ4eAMyVM_dulTxs0+Da~19QVVL-e*8OQJZoNg%9UX=rI|>^v_%hz_uRC- z{jdk&NvDFPnHpn_V~{<+)u4xjMuF$CWr9)5Jge{ODSRD~S?dvNf*ukY zD_8%Da7 zKKU4=RGFw6js85f} zL4r}N!&2z{pSG?vYCrRULA?Qqaqe=ESgkZm1P!3fyCxXL8fl5vQ`6Nv<{T~)jB4r) z$h5^bobp>*=?=V(YHIU(-d>R?xjiKG?w8)r>d#V{7Ngk5vceQPZS9iaTB7F3M>W?j zqn7(FJtVj?m^D()B3JI=j2ia#Oz4Z6z9X$KU-~Y)p3JV-=Vq0pq4(?j?wh`S?R)0> zMz!z0*LdYhUrY8g4Em~ZeNN)&?dB|8iv3K9=CN_E^aV#h8WoKgA zS-WkG-fP>>#?3@Bw9>DwruJ}6uU0!+uwYt?Ru2iate@m*HAu8k_uB5B>&v-n+q|~3 zzO*^kV9(IEOWiBkPHnE}A)&9Uc2CyiT#;ZD``fHBsdhQ;6y>Ld*s?P*YqVt1HL+ZkM$Ez_>ouaxNnf4)E@6Y^MJ3IzT!K7_JFT{>lo-Y ze5*kZiJx9SbJlAK=H!CUfA_4hoGW@reC^ny=G@L2lgdG&j~bmvG3r&9eb<5ZY->b> zVt7a>rKM|@VuE1Qfg5f-p}98^NvCqqLqfGMzH&!`QL6Rkdg2r!)0SGw9<`v;&Fh}w z-U;-OQ12O+oCKrTdrG16f2J*ZNSu4tSqEH)%LJp?r(1%3^u_1=#5`80-4gVW_}H7D zcEES&mI+4f+xKG!##ip{`0>Xc@YUrHe&P`ae4UzoI%`a!G;L|G3}4wg?)#o}z}Lu> z+wnC3dPpc&<7@iN$@_15*qrw+SCOe5W01sypYp(kx?)<4;yjjZmA)(eBUqfbEjN-UyHQ2VQUALf8I`k|`LM`jQ&}uL(Mjf^~aG<->FlkQY z44@iyX*pxG8uXA*+qkBe2}Y^?$Nfs@g5I-4W%8MKKC>(5>RDq7rD=;E60&`U9I@%& zMD>KDbkrQ5(bL0pW%~@d)!0cmO6v&UQJ#rpOk4CYUD;hPnMQ=8IBr@EdYJC8m*iZL zU=(MiStI9)ZL3+rvk!aEOk@puNJzu;*fPN=<DUYHWO2D(-u7>WY;H8t4dEeif?V!c#T1Nn6BQs`05(_ zM$Ne*!6?4rI%_0q+S2rdc|`Z}`Vplg zm+pefqhp}%!0%mygjUVEx87?oSB%oyTKCp_LT6oijv+knTj%E(QV#Q4SI-q?TMZFK zPrIt5yz8E}JSvm!h|6XjmTJoXX=|5+j?B6PJ8Kjyc4BiaYF^jEB6xS9Rk0(fJ1JEk8-(x++-kLn4zL+fBs4yB&wlq@F^Z$B)liM<`KU#2lBK~1TsOe(p~uH3_QO~XB3Yb(zfZLa7cp{pQGd!+RB7uS89RvVSh**OLS zC_T|061r}3=zhhhcKjECoGaFe2+tpF9g?7@CEl|zUy)EbJgceRJU>+Z=VPY$~! zboJCxOjlP@#{@kjR;zn$AAc$|rclyzum5f?2Xm-RELm&Iq5C+FVjpYE(e|q&XQJ&fm5FQmt}ERIu!im@ zxJ)%(wac^^rMp?0Zh*%>tk&L$FBvd}1`z#ZTQfqqOpG-`_Y1MbHZSU8nS*`BS zGuW{=L2=*NXFnv=cgH&d>7JJfMycm}2cpQ21f;?Is_!~#Z*@gN=)57NhjLuLo5H<%%8>IyWC* z@gl(}{qCz&y@ov`;>oJGCbvv5N*cZfl!+<*oBlt_VGjvC`{iqZnJE9X1f%psnp2vI ztg&OS()0{mJhQvkeNtC5p>ghOXIUeqALU?LjN1QQUra0HzpZU9BK@Uz$>1R&d)(&o zxIMn*vd^p^dEMu7y1Nrji-bu1@4hE8Ek-f7QGon!9v?afOgliQvqtSrti5t&>)L>G z8?h$nA)%e$RgZnHNH9t@tDH5&q}q+IuzfRo^wl?ghgDH}dwHBId0bci_F1GGUrTE= zQc+qBrmL^B=^Ljrk#eNJY0KZslt(+oy0rdQ=S&2U2zp3p$86VhBpyghv{CWR(OF|M z;jb-b&)ILE`<1`+I1>S+Ts0mL`}b|y_LwzDv{CWJ%3h<%RrxmL&K#Bu<^QCa8aeUz zAVv5qjJ*a4M!kFcntptwvP@g_knmR+dkqqdVt;GP!6WB7UV}s%wKP81QvT+o(q+rmJgM)}L&9H^>~lqeQSJQb#*hZ*TJPyd$CG<9IG1(MIh!4$iq!Z};kM=a*=_GN^e{ z$vHkq-1OP2+f`qq;j|dVqeQErykCCTKggp9&yYKqk?+!GWD@Lj3pZS|3 zLM>Qp@vXClW}QEk>y?IEN)Z2}pw;64CxU%8^igZ=%+T=6Uyw zwhm{NM9@Pb>MD9=jh6-qMyaOV^Jiib!Frd*HJ83A*ALriCXx{ve#VD{%6H5w{-~|p zj%cIay8gRoTv>^fBmKn@=bc}(=h`_+$9awWrUf(6dMcrDGtLzWMzJ+>cFI4~7Cj_1 zf?aRR1f!OFiB{gHogZUOM>vl=wrs0G4+$O5$K#wt8&yYetHJ)G)r)6TrqmMjkkH!K zqj{NNlu~kk>xt^A=}OPzf0aFnz) zfAzhc9;O?5c%QQf#dqSI7Nfr7_x^Z&`9F=`YNUsR){M=loi#`>N`0)3W{2+_=NykZ z;ym=pG0(SkMGpy`i)t0n)YT*n5^a=5+769O#273dq?^-E|GUvh+0!wqro||Y$8kC6 zA)(n#vC|%2Hj^|V8v}*>g0J$0{dCLEZ6*5;Ap5eGAS|-{kJ)?tuH3g?!RSyYW z#j|#+vEzF_>FQ~`L9XkJb>^!~-2Z@QCUmWA+~!P+QTn}W!6X$L_K?uE#Btx{U41?S zr+LM90c$CwK@SN&O}9)iN-6n{X;0WgLbiY3op4mQ6Li61Urz7q%5=5!-*_)p-Ph86 zD2-0tA=7;?*~@ntbPw23dP>2xuIbma@LG~-OLvNOS4rve%D+<5y{f^?01pZ2>F(c5 zOrbMvDeq28WpY$^H)F0V=3P%!=-!%hI4%cENFqOBk?w)cxtcXdFp6a=!TCS&)llCV zAt628DIIH=VAOJ5v3_*V(djPN6+I;KUEg8JNia&kk877664GVB~9jw@Z(VN1|MLidC9T)>>Gg2mlFw=JVs)2)V{*3i=q zN=r{2>1htx95*e&C_RT|dYPbygle~I^CTAS;c_raZQ~x(=87J*x$B48EkO?n^*6W8 zGQlX$$1^dh9PB?Txt^7B?Rv(TiDa}rk%VepPjk&}p3>J}OE7A=C(=VgeZe`5)Z^dw zE;6Gy3UcgZf@4BG(W92y5o>}T66*Orb}bW(;*qE&_+@K8NvyTccwIsd39V`mO)yF+ zdHvAliXIZO_eMBMDUJITJxo{j-Uvr2C6CR%9QH6>+5UZZ!cn~Y-V*dM-Qm6Mgic$0 z6M@ffiypTiJtVY-KQzH8rR270%Rvtb*?S`#rIg$@y@owZSGIrOop6*i+%`R757U+H z-*+c!RDCj{C3GI;XC|1g&hDDK`obo)xz1~SzeeZLzT2a7gQ^$N8OrA$_K={SBK;R< zEG8Hw4cA+ao`MO&9ul(syVKWyd%{uOInESZ5bhaFSGIqT*d@YI(r9{nqhSxzmF?eq z4SN{H^Td{*hs5#|@gx{Ee7-%2rEfK+ugCe^N&9hlb*8u7+_G)1v=53`EZX73YahMy zHzt^__IB~gVp)S8658j*tC}`fBp9VVU&gB?=3TobdDXXE4thvvKPT5hn=2BG(w;A_ z!6W0n_K$J>kZuWjNN8u6aeI(pRF|tMl%_4Ul+Pg4 zf?h4DWj*HGT(PdShm+6GsNE9ukjQ&R4bLD+FiO9Vb43pc>G>SD&y~|+l*;ET2s1Hh z)Y7B&_caG<&qOlftzT=9P z|DLb=6ror%c=f_{DMxdgD|$%iXy7_rCK#oZ+?qXM4++`+eRsl9(irz$dYG>4y%CO5 zO1}Hv=gJ&yniMZPrZL>@;N_Vi_ zvMr(eT<#gtbC1y-vvDt>hXixmYV0IjT4|5loF1k-EXSlHC(EHIeJ@^Zz#O)@qKAa) zO<$PrTaW~!)HeFgdQa%ezjn}(NB0o)bz|qswb19v9um4QGVWKbA4ajiWsOu%`kS`Y z!<}D^6_-|{!0jKg@o(HWu!n@kplf=WU=(Mfmf*YvlUjOu;pL>aGeI}9-_loQxq4q!H^ydtEBKt0*)W?4I z+y0+Qq#Wrl?u^=_wsE?9>m?*KKe|kjdi>k=D@L)0&cvi#F~6$OlmAoXo#mT}WVCff zLT&Tv%SI(edk6r66!7o(s%O1+D*C;JP4+*Vz4^1#iDS3_3 zYuH0VwtwH9a1?93C*0eau5AClJK-p4cy{dxdzh|l|GqonsQcb=?Doq)b?brtXh09s zmF@kWTaBHBqqv)POVGn~bB>=0v|mQA-$L*1n3Sxw_dodcbUj(+ zGqScEOp8(aeSD5X4++_OBOIlaeD>1k${waG+rRHlI7%8md+7;#n67O9zB}P4X^h7? zJxo{j-UvrUIY#F=^f2Af+Y8~DK`D6z_a(Q7>B{!+yAzI*hDUHu*u!*X`}f@mN9k!p zf6KTf=wZ6cUm#9Lw)CCz2j%Mt`quB|&j?%ectp`dLOUZKnqZVt@>prhK@SPpdm|jB zlsr~?4SSfbZ2!JH;V5Z%tn`FEOjovl-<@!jG(1*%!XBn8+rRHlI4a698d3Bx-O$?$ z;W4O`JXZQ#*~4^Y`}f@mM@hqDr6=rRy0ZQI?u4WGJ@J;Hr%iY1tJAt-?(1fz5{(&ufhhVH&O zzj5y_N~`NvQ&4+oXTkWW;6^nA{)slYmj@>K$P5IwM&_jadi`bxg z!g*(IXF^cktJqOYce$>Z7NfL&8=u$G6L$cx7Nc|rvuX1wl;X;^ z&l=UQd=98u@R)CNMGpz}XyYnvXab3|vLK@?`BEcx-&~1}*m2#xNv`ZRlQS+5^$aad@_%}U^gSI81 zxzg7emkCBGC6Ak)u!n^1d5*7HGA%}N25&Vu%jkIq&-3gHEkO?nJwGwd6$wVMoq7%T z1`^U6*Dljy6#Lt(F{#bj8`Rr9f|=4xBqL@x=Zb_z+W1-q(_)n7mF{{;&J{hHuYBc( zDJ|!UgyzadBc-puwj7LNpN`o0x9#mDG;5Db&a@b%qo`}T)zGsAy1E_b;dK{Mo!$FR zV@tH2O7QvQWr9&kX?$)#4++_OBOIlayz1|BWe?Mp?caAN93>5}`g_72rYqaO?@l;M z8eaAHggs1GwtwH9aFjH>>hB4An67O9zB}QlD97mBfF7nBdV3*!HldU}WAwSQhv~}p z@4FL@l7^2GJz)>imF?emCmbaWuQGeW9;PeXzwb`esHLw|YPZn*oKITsGF?6Eqa#~? zz=6el$n67O9 zzB}P4X?V={ggs1GwtwH9aFjGW=6k{(rYqaO?@l;M8XogKVGq-l?caAN92Mml%?$J~ z-O$?$;kiU9dCd2@vWMx)_V2qBj*^DQd{5ZJbY=VZ-3doYqmKE?=*|1;VY;&SMmS1m z;5tj{X9jwhuFh|CCe{;tYn;0YXeM&K)lz7EMGpzRm2zl;QA)}6)@#^9LbiY3op2Oq z)ShsSGF{pJeRsl9($EUFuU&eWuIw?vT@|=9frxSK(nCV;X&jnhlu~lNwI!#AgzUW$ zj#5glw_d{@rYqaO?@l;M8splfhv~{56S_-w)KULb+V-OL6OXzr+q%o0ck$X`889<`dkS*te#^`+9j9Q2S-Uoahs=YNw12}bGNMSa_J z)|gDtLqcEI(f1E$B7mf!FWl&ha`Nc=IQkx)Y|72NoRSu^#=PDEQDDNgzBi3sPm0Vw6+o_>4=^K># zeI}BjHm~1O*Q!`oKq6`{-;gH3`FN*BO^Z>(uN+Ux6+I+a3#|qTMh)9MYtTbN-$XiW zbzo3eBpAj1*5-=+N8i5E_cPr#?r$wY4HD`-`d(+>f+QHVJU;Z6smHm#MC7r}5!~jA z9un&L&8RI{?BwYZGD_p78?}?#oTEq@`o^zHI~-9-Cp0`JNT_`IYr*dADSiF51f$sg z5gY%;%wP=?n#Y{OWr9(|QCo6V>qOsRayzruTMc?h=vzYWW6K1i^d+M445znAJ(uV$ zQ_mlJYY!6fwWA-)t(kK*Mc(3jcb*f~+x7KckB?gGwIpqOkch9SL8Cw|!KmS!m~u94 zF~6!S=W1^yC!w}+`D!V4_C!YUxY81ADb=ozYU~RwK@SPFtdEb&1f%v=auWIm*LW6X zT8v_UYjf4^(pq*`7^RfFzHW0x4++_OBOIla#;aF)n6B)-5sp$y z;}Jy<)0Mq9!cj`ebADe}_Ap)9{(X1CQF`}XU%>5;gY+<6uAH;R6iU-Z^SO3g_?KTl z>?H57AY0|owJh09t~TDIPaf~^CtJr4^{bhfHT1@~?t93ich7a7MYdKoYMYrTLes`8 z8AqvhBPv!=J>iwUJYMO`_L)UbFp9L#4H_bqW!m_QxAN%fhpueO_V;-kB9&#@=*q97 z{BD<`{La@*%yo6bjr+HcxZ-beE$Ug`i_g0`+wpAeM{DiQb>-dZl$Q6MldY0ly9DR| zOq;EDeCzfvUi*QZ)?Z)nt?BN-`HFCK$z*oi!$vTsx;|e5*#EdC#w> ztH4pC-r=!tb9zV|bL-dFq`ztNJ@>tR?Rw8U(Uf+6;ji4j_PB}A{BI)YA)#8= zHM72UNiZsEI>uw9ZVh@!sMd8=uh(EXR;$}nn@4|T4qJ`ZQwgQyu`&~r>WT!T*xzO% z8EsD_p&Ie{UnUsEUYUt0I33l}mm|`btW+od!j~*Hynasl-mD$?mHqvu}4rP#|?Q6w}IjdMk!jjA=>wuhb@(p$39&=W{{drr1iINFCv_ME3lwW}ySEh3L- zy?be5yk<~Z_K?u?L{4eeNXE1w!KmeR2|XnAJelrCH|5A0^ypbQ-Kka-Q)+WX4+%XB zr#I|+4HAsfvv7K=t|#cx(>i*SZtuAwp{IlNE?cj`Tro<|Eb0BVp3t*Udh1LcMd^Jq z=c?-^xpt*t4+-h%4YXc^9+gAy_w8MSgz8Z5`t=&j6{FNPdLytW=uw;N-PFD3iiG-` z-cy}5rs!SMhPh(Ya17?!rH6!izDIDRZVeKQ;`q<8lL^iSdaA>DXG#%kf*uljs>Ah` zW2X_ps5AcYQS0*_aAK{i0Mg7r4+-5}9=9L~M(MuuxR)r(+QcKW7Lbc%bUnUr(w$YRRP015FZRk<^>*;<)QF~c~ zg!-7C0Pi)J7Nc}**Hhm;L66oCdeVFExgw!8ik<-PHJB?#>38?HzU20h&??H;FP8~M ziT2gcmY_%F(39RSxwTt@`6Zz`)U)B^k~=L%ahAv$Qz%UvjvUQ69(Ti0o2YgSlF;1M z%nTv1gJ6`7yPk9=ZYQ@YFYRE5}f}tZAdUm$M*4vqDN~6k5txSt3eM5 zr8J&PNHB^$wAIk4)w9QHXI-J!TiCL7<^If9hTRh0{U8(R39&am_raOaJsqbs6O;NC z2}Uhz@VYLvj5%j1W`)>Gwe?_iHsNQaW{tq4^SBx6AVCjh$ ztgpH)dbQq`b`RJ5*!0~Ltv~hM3+8_HrDL8u_Y4tD?M@j;1fy=b@;P(fJ0gHY&_m)M zt~`IPw-TKH(-Mrje*bw3?ZMJ|?*#Q@j{jDJ9ulcm^1cnCmkCC3UTF#56BM!kv`6H2 zmUdIS1&eii^;AMR)K{(MTup(r1fy8%ZLa7cp*qwTwPuYuS0vh~+Iw>F6v(t;OWpXS zbLVl#luGgeHob(zYIW{B=9dXZNu%lQ!lv|pskhg(q~UpGNC?Wga#|!*zVUp;v>2s+ z+|7wOSM+Fnc;017DKqn5n=29;n?7F6;mK%;Hmc4TEs?18nFqg^S9j{icbxI1f5i%! zgpPK%J@6}aomhn8$f>8U)#Lm$wrtJE%{p-=mqb3o-MVUXmC6!FP7{pMapmrJxzm84N5`o9opt9N zwYOZ6$j8K6?>f+E(@ICq62)3CO_Bc-<#2m2UFkjkX?I`HFu^F5?`hW@J|O7HN6uT1 zoJ;PMmUBfyZF9=o?>*392^ponQ2SU_Nq5Q0UO~AhrtxvkCHKkcYHsgxHL1<%(fBZ- zk+%QVpsT`8f>D~aD_xkZq2swnlxAv=JIy8TZ#h0i>u=g<{&1b-V{NHj5nVYlK@SPd zcHyhGxgwE|cEfSrrj?F~B}%`$)@O}L?ZLF9;n`=!-zN4NEqV6XAst54Yet!IBQdtUhCC#3t_@!ZNA4z9QL+;&e~ z{GsEwpLc0IEf7R#h|rVlJwXo%X`lbwJD%~%bwz?vFaN>`+ZUWP(qK85cM%s~J1Pe~ zB)!B^^kb=W$T`pqPJIqQOhN#hlKR>Zos%4u0=+%*5`he zb4AbR|9+jG5Q!)D*cWCZ8PkRy5>I>Z_O_n-?sG+gQAhmZ_O_lZ?};y6e9G+k!<$c; z(_QZE^pLpMk*CgOYRf^QjXJ$=!CdlmRc-c=IAeY4!uTM;sKbBa)P)w*4zYd`Q1zqt z0aQP#H@ykd*A-`j(_eYgww^gx6w9||%wK`#@GddoQ{&w4Gv5}tk5sdK%t zMlvx4r=vlwT@p%ZJZecW>iW+HbSowBX>LHbs=ap4@YglmTd`oNT_^z_pWb25^dDU>3iZJrcjzT z8rx1wvxIZSnr?GN4+*V4#{G%}qd0f98ax^V9nUJh^HIldfAOh1p3+NYnKty0SWQ2) zeaBP%q+?OZ1U)2feA{EUpY`g$8q_X5BxE;lK}aTR>?9m@$|oPQ{h0@hG`!cf+E(8c za@0^mG8=kGtX7XnGwMi#1fzD(m3Gxou9QPRBkG;Uo1U0UPLJMiaI3{T4LjN+mxCS> ztLc$_3w8vfScfTa{+l+92kGidP2)Bv!Kk*Tlf)D<(}r(w_)ATyAH5giqjrv+2}b$L zP(valQkyd^62EZ7zJ>KJ2}bF6w`NH`GM6>%A+cKR!;#uqQct8ugjbn+*D#?njn563 z7Nfk2ebW`t48H*4t>RQT;xCCypKx zS{dj&;(dFNV3d9zw>do|c%1Lc;j|c~l;(B<()L{vTEjPMhNeAgS~ZGm2}q2r?(RNP)CaG!T{S(zv`kJGkH`g3v?V2YM zpZL4)-@fpYayyUq^8HGBE`=ZTJQt(`8D_8YHAKE;-X;l)ls8nw~XM&ZZ6P zL|>TmGmxyqnMg+49whXA-0?GzOp8(aYOkNtoi%c<*d8po_UiE43N1ko32J8|rLR97 zqiR}=(vBYEcN$i!qqpyI_;zk{ePh&5E9;A)&C}5#ku>O0zw#5E$51adZnMOUM3i&Q80d*>efCmvcozUj`n})J%&}ob6f-&d4I% z&YUY-f*umeVbias;M$`>8&yYhtHDuALUrh#zf3TSGf_+EI+(6o#rorYYh5R^t*c?p zx@1zD>k5a?%jMCvR-Kp2)_wrp%#aC2>3XiN#VisjdwOTIrqvSfS?dZ4A{HHrVH7!Qz z>SI^(#7!G|bQR5Y#gt}&OwdC@S0de-%LJoz_0c`1C3Me8t5&svt{H1ZDO*>cwN`9e zFy~6`tZSq4kXFm;%4$#0LqcuS_4cemf>CP!I&Nx7rcLW%x*T0fJSg?{S`PJgU9sI+ zrmCP8WZp?=r0JSsUvd(R(rDJT#-311IW4uIbEUHtw^N%ddPu0pxScXF1vhO-v{9_L zs-m?|^^j1X9=ACOMzu2^HCR{deVmnQ{LcA`gzl;8s%KxjOp8&RU0V%~99=o}9L%xV z67-PJRoii{NH9v*e8*!@=X@Tiiqdstm6k1=b2UZY;`renr;_VhwFuUFTMl|isHUyA zOfZV`N=q>BD!Fsjm7`#7-zA}%cKKQjro||Zv`kFF#rcQV=UkCC{f-9*LSJNA%Z@5#BEHJBEoSR4ceK| zclGbFe&Pu~@`};UE!wTqQQC*owBBy>mEx?C(%0X#QM#Jbr6E1d*0K-WaN`N%yRS@F z`wZ&XE27f~iKIafiM$hH+5Myh=l`?>qm)v;u4Mt0gZX7SB4+fo2-8)rbZl}tI*pV} zt3eM5 zjeoc7GQlY2s=NO&spNV`(bvdi`@Yd|PryvjLqfSV-R6n}qw)^s>1y%ZcMCRc=piAy zyMvW;wUcm^_HOt6uQpfoFkRWc>ogNtV<+J#?PaO;U0)7*n6B(@X2=>l2}kX1L^0iA zo2LS`D*#4u#z=wlUmQRD9J^{kD?gQ1dVUThhfe_oVGjwFPiwlqu9z01qD*+oqS5e^ z93(iJBR|ZQ2}VhyIdV1{_K;A$jmJ6DVib?sIX|-o-}>d-xqN>(N)Z3HZx)l#E+ram zbM4L=Op8(a-7VW|*h50;>wk|mOfX6{;@`7|a+UtS?N=mXG@o8IGPaXo6#G~SE*d(U zP!5z|+1iCxw)(KBz8pHEb5vZPS*;YM^N;$wv!qb4kTabh_#`_vDEk-GaCyGuIM459pA^RJ`#-5lbK@;dPv;&j$^l9 z{;6B*>UGZ5jvZ}NY2&&1cF$ae$6tCcwcTfTCe){W2H@x@ISEGj3xIv?(nCVFYrWOj zNjS>i32ZbbwFf;+mtQWJHIfl)QKzdN(~tbzn@i8o9bVg&iMy8e_zQW;iPphRsm4o# z9uodKUsH~pD-w+2*BG+K6iUj~Ti1X0j4N~AFa6ln>tkN=N7>dIzH7m(K@W*zZhg!8 znoCFLoFo|aGxvPU`n2=kI2chs^_pweXa45z7EgSYM5Wakz__kft83R+Os~tt`Nv$h zKKDugJ=@C!JtRJUzk};rp71|vuI9R8eqZ=2SFNvm$Q3z?<%@cC?b1WyKKH$9{rUI5 zp=uON*IsMAGfKaYOHL1o)#|ELyO%F$)U;}p=*#c=2Ztckg03I6ziYZJ`D#^L&0nS2 zy#?7GB!2PQx3AyzIroLC(vHD4s`iB%uMriwiqZM*?Q7Pnv)>-2P5;&ZZbsB3f_0)6 z{NP)DFGsP~TMc?hMDKZhtC7%XbGHYhSktpc&Q)9QZ=HKSwP&K!(3tmFdD%&CTc};8 z#i({{D)IRLX>-$OuU_xpx5*_G@y@TsymHKWSGBvb&jdXrzT@})czyXljow7!=zQH5 z52hX-HOk(T@-zRny@bT`FWk(nIfo~sB^cGt^OZ@v>EZ}L;?sY-Sr}28aXi&ArdHy!M!{mH_B|-| zr9Zpmn>k7|-vh4s{|1EAO{hJ-`(>+gXY8%(KiaaL1SaQ7M`Wj~j1qnCV{dPXRQg!^*rRfs{NaC` zOI}l|Wsj2ELn7+%|FjwjYzanb?ein&;cj2bk^a&eF3s&aUsG>j&(Mr|^HpCRXs|cv z2>07p|4WY2n!)W9smH%Oc5*oqB-)*Ep zf>F!8ge|2t!;k)1%m#bwB_y;O`1lQ@xui|2M(wT5nXby=9JY1Ev>4USc7>VLf-1Rd zQR_KfKhfw?nZ_fE9ugdzbFQ)mi8ktgruhn^HbuvZOr@PY81uWgpv$2#=-$`laL$%W z-g+vbG4GxaUi2oFZ>= zH^Xbg^xI4*{brq53eysdl7?3XB{=^lt|2=u%{*RBE)(>S(5j$WCr+Uhxw1N=l+w6% z=^>%?z50j(P{V04ift3I>E9`4pW3!0R0E!aXF^cEB5Vyt4ck0x=;=~D!>698r?2(A zt9#}6DGNsFSz0|UyGZ0*slPfc5*h`1I#+aC4ibz~T{)$msCV4rtMy7(dV2PGcMUz8 zs3#5;r8`-AcCjaz6Fukbk}v0q9uj)`+BMylg9M}W^tIb56H{>UE}2WHw$XFj%Dd{Y z)<{)}ncAL~c+Xl-(e@>0TIw;5(zCmIa<(B-&f*Oo*P`wd>M2v_YPkjNAt4PtaoT94 z;zT)2Fp7OTmpkQ1f73?otYja^ z4ieJS(|}_Qmz+`T$5lZkSO0OVsb9I5sJ}V4EkO?n^<($9OiaN|8}1KCv(4^H9BC~<4+%Y2?S8yWFiOvBdla;Uo*Z`X(=*8Km8|ua zpoc`fB{r%ns*CUp$MW?W?pGv~+i_21T8v_DdkwcB2|XD-9#Kq-QLMvOgLR_za8G1P zEkO?nwSPCmB{Yt;E(fDH(q@fG1ovszS(u*$+uPpJBxGBA*2uYHT8z@~%Y;27x+gOw zG{sy}(_+-~Ui-7_-}$LHiYmBX%g{b3`lge{GoL%q9xVD&)I82p`udwT^pKG4dtnh9 z|MrBVq^)nE%^C%Zrz{+$y-W1{Gev2S5q;&XC#bHyEA;&e7 z^M$@4Hs>nUlm4a+YfcP%ibmY|1(`rEkg zl3)UH#vlpp6Q(a1&KjjK?Wkpx_97eSiXM##mwa!z zBB9aM%s#_hF^cni2~N|3W(JN<ssI;8HXCfKxI47Z6(0Aj;b>+F8QS8&L20bLy zHqPNP!6?o#GclVGq-l?X}kK zgrlTkyC>{ny0X2B+MRF|SDZcJD5k47=$dzB3f8Vg86^#`=X(u%Nazi^?p>M5Eoh>R zs&CrN8kx}b5N))E>H*;^!>cYC2DFJIzEg;%=WkBxJkR zcPAVr4ck3o57U+HTHl>;lr(Jjggs1GwrhQN!cjb@>Ip|NUD+OKyAzI*hV7oPhv|0j z#7&7y{~s-Af>AuvYc=#PhSxZHlhN(3_cg}rD|$#QzX#c9r0;}#bx*p@6+L?2!-U>K z@|ndl!6?1y@k#nN=mYjF> zHMdQhD|$%ieU@=uk`Yt`nyU#iHmMapf z1)uLM=ZaCP_3k_>=ZYS^rR8(Az2%C8-gNX?-*T=Pr8hIjt3LH5=R`fxc~^gPJGC10 zkkBX?*A)pyX>_@5S`B(MYTeFEsU_$kp&4V`uShV8vr?rJPuU5KHE}C3(jv_y|`zv6dHq8#x|N#qvK zmlQ0nm-zV-60-fgMytWJ7^UBr342J$_Oled1_?(=!*)w(M+d*X%&P{{@L5Jn&_hDD zd;ac(qm+{Ep0J1M${vporo|}zzD(FdLbm&KpDPlMl7{V`u!rf&cAwszaFjG`_k=x6 zH}pn*muWF7%CSVax08_V{?_M;grlTkyC>{ny0XW8muWFdzmEy7mUyJrvCA#n=87H? zvfZ+~6OK|!wtK=JrYqYmyF1}1Y1r-wdzfzMjoO@PF)GTjM7YgK$ac&2xgy~xY1r-w zdzh~5aho$OM(OvCn6v`W9bV0gx`wQ~Z`yajSI;{lWiO5f_K?thJneHZzItwgQMy;C z-4}X7SI@nFn(oACKMO_0y{UUwB9%dZ({ny375FX)#K7%*K6}9^Fgx_+U!Qxgw$3?Z#k2+n&fMwas{(v!$e=oq+b< zOGv1EI=h_Pe2UUUuH1JSrJDBdZOQ2&5qB_08uVypa88)gvIYswM6QKpf>E0Jn%+JI zH*M(AEb39Tw_K6XtnCrJoGV80NYoPS4I1Y@e(bF$lF%IEBT=itv>3(txFvMg!edaj zdxq{)`1h8eXD4BLnGo$L-7y<$(6f^;-D;4K?I^C6TY{dQgz05Mw4;_+;q>ezOt%^& zWIIZIcU)KW>?BOL8YDO-xEgE;dPpp-BL*51uJ%)2dM# zH|M?ads<@BD&yl1`sH~6NjOTs+wL{&VY;$C3U((PB@Np> zVGq-l?NP8h;V5a??g@LCu56Ej-3doY!*);D!*oM$G(MOXqoN#3ghvz!+3wSQu1Gja z8n%1F9;PeXqhNQ!QPQy86ZSCOFTChi*XLYvpLTpCRL@`4v>2sv(~YQ1=o*PfPTXCJ zHLmWSc_lmNYLbTT*ZI6wcmBKz&StjTqp)0K8l9OPR?hm@AQ_}NadP4yo-PLzHGo?8^8L{uVYnO!X@Q?cy z(_)nF_PZbN&_G{`X9D7Cgi`AI)toDPNJwvd9>ug6r84=vt<4oZsyCklGNqQFhlJXu zIp>^$i`sQL7{wW*)u4xjdQ3N$Bs9i{H5kR2C~Hii6!*`amPVBGPVI;_K@SOyVAtC+ z!6?lbO?yn%phxqS+nL(S8YJS`pV1XBro|}D$DZx7#+)m9^vs0kN2au#D-wFjVtfUX zX)#K_du;X^_K=XCuaPbjjN*}~B{-gSH1P3CqrloNK@SNXSH`&_!6=TjUco5P@!@Bd&me5+=x!OtiTQJLnXh-oXMN81L zlQ6wZh;|gOQnUm;I|qe%60wi;=sQ0o7^U5>$u(|l zx4EK+gzRxSb`p-_*z7eN#dKva&psp^B@NrXhCNJIw$BrHCmbaW+dW|q)0OS>#N7!; zNyBze*u!*X`#f=X!co$&-4pgO-OwAIK{72yMLCuTpFxt4?eoMwS0o%I4ck3o57U+H z^Tgc=M@hqWPuRnBWsjc_Vp@#S@5_WeB=jV%j@0YYBRG5~i04 z(T?H~t|jQ%Ntj+HL_11n!Mc~%_Y!(Y=$uw}7=!rSsn6Sd{e>4El$yURwwmsA62CHK zTfeVX@BY^Rdvo?PKO$nH$F|bt_o^CVz>FV)nbEaim1mDM6tw5|C zC3QyGj$B>&{Hw3~-T&*?vj#o3qqKaV6U53Uw_f+4AIusgY%9v& zmYyHNHEHFXr%VuD#wo%J+`I6Z~o-t$B7dTcA*=wnA0jU|FnwnL+gk1dsh9^2C3^?-SN zbOfVphelduZ0Y}{L62=|XqM3bj=EYR7-c&&{>#Pp*?P~voR&4{v8{AJ@ps?9ec>g? zZ}$W}BO-Ej{E|ZqZ|jb20gZwuKKh3a%e0OjItdX<>;I>=&>E?>ezmI(O4p4HQ=ZqW(}=NN?p-Y z)79#umP51Kh+vfMxvsRn${O_8Rynkas_mg!dPFeFc4+9>p^>ZcL67aItJBx&3t=x2 zsWuT6c4*x9U3cExe5W%?UC~pCGyd^W>+>FPVi_MKT2D_zuD<#MM{VBrj3;Id61Ekk zRlml0BbqE=iPFy))9=d z9U7^E|ZBlSX^319MVJ{r&Tvpl3uxuF{%e<23^b+YzPFlg53XcS-1Xdqzai-+%kBZ@zfduU(r$C&inv zttfv(JTyqOo}fvD#?vo<{^m3P_5)g9O(bk9O0}T5B{WFTGa^ExwBSK$kg%;NwZG<; zAYPSb&`(dX>U;HN>%6*?x@|>$`St5-}*RXGOxcqMr8P z?QQMs8RZ~B&xi<(zey{lfBS9uD$a_8ZAIxjs@iWfG)T}hB0}T#bO!mq%NZmI+ltcH zR<$E)Xpo?1M1;mu((LxWawbf|wxT}q@RPQ+V{B-Upl3vc#se?B@WfBY)sGbk+lo5< zl_za$&)3i(LC=T?ja$-nhS$c`j}-~q5p{BUzTFxmR;%h65wpg1MPnjiTTyR0=VX*4 zY0O0H2|W^_kxG8B)YU}7wxaI;fs@f5B{`$WRFq7MIwQ*rztLC=T? zjdaA>lw;IH!nUH$KI_!^*tJ@bpl3uh8u_XL3EM7*z6}s_NzurJ(zRzqghnZOUXhWo ztti!k_SX*$67-CS&?qgKHAvW2lv-2!-G>GVdPYQOl%AN^yCiHYO1)BhyN3n|dPYQO zlo6FRNZ3}CMwfPg4-FFZjEK-EGeg!OVOvp}CA4RJXpo?1M1)3};j#t^+lta`r@iPy zg9JSzA~ecOoi#|^jR&=IB;rPV-f4-)i@h|owasI^blAYofkTGiBkMS`9Y z5gMr{Y7Lh)NZ3}CR%dm5kf3Koghm=sT8m~461EkkRc0OMB)oLG(sbMSX7mnDseetzES0mASdLlG# zOLg_8a*v*bZACreN&B{c>)AfXAwkcG2#uRln?JIg50bF0sMvw%!(~n+LC=T?jcd~Q z+qya5)nAdYttjtb6zxHRo)Hlm-uiiB-Nop9s+?IW)En^F!E^o)qm_*xo& zUnu8;By8uX>5-QIARE=9W@dB)qSIdc%ka`bX2* z-RsI7cM`T0b;>6ngL05)J&_X

fZ2KKPlatBHhdMcw$e$D%z*&@&=J<1uOcrBSuf z)hH6SbJX-h=vO3G@QjGiNIh{=`tC%+wxZtosN*p{NHm_JMRR91`@5h|nl4m^Db)R#dd6 z*X<ghuL#TEj(MfiSHotajJCUauBKS;v1 zqO>EF_VN!667-CS&^YPldv5(nIUgipTT$AxO8abw1_^pbL}r@7j%NYFDPLL>FWP3gN63EPU&&SrIdkf3Koghm=sn=%F`61Ekk{m<$+ zCqd7M2o0@}%Um*%u&pTVn5HjnMBgPr&xi<(G{bGmoH&uNttjopR_9$3^o)qmNHg`O z%<}6x=ot~AQD*9_LBh78G;8Y%6`?_bo)Hlm<%p9tNZ3}Cjz0Q^Mre?r zXGF{zI@V?l61Ekkqi8KhIo4)^o)HlmWd+a?rWK{tKy42a^o)qmNG+(fPu3t|TTxoo z)P6;Ro)HlmsV8a;mo-S(R+Ls}b$pPZXGDZX8c|w{W(^Xy6{S^X9p@zI84;n8W(KXP zvjz#s`xu4qH(-KIz=` zr#KZsmDV61Ej}{r>aTPrK&uqCtY55fK{iN^O2lIUgipTT%aT z<@u?6M-~kd^o)qm_*&|_pDX8sBy20{mMfpLKIQHAE*d2084;mz?==4Yy4)WmVOvpO zI_A0SryqAz(I7$3hzN~ThOLydO}dY>B4InCF33AaM!zDlT2;@82zq}Se}7ZX2T9mg zly}Ap4HB&<^hkt8y61diy2_HvLBh78yc1t&kf3KogvQHXaP{Nx=}WJMnuqm@q(+bdu3>(=S3@FTTvHZ`+~ghV3dPI>j|1fXz2cYsjG>EZAE$S z&$+HjmNuVA*p8^!Yjke&nOLo=XG8>jeHwq?o}RVTJxCI^6?O4>FT(gB z(R%8xr~W-Oj!)NP-V|eSvPb!~t*9fecrnH~33^6EXlVSExnv??TTyqu;w6}`NYFDP zLgUS8{QYgri4zIiiqf7{b>1aG&xi<(+tc`aNj&>8k+7{O?QB(#A0+4*5uuTeIGb{e znn>7=sEcvzBC%Rk&xmL=@{yB-ZI|PIXWhAs^P-UnrCU9rM!_ptsc4X(XGDZXnHjPM3EL5M(fWx;-BvV6XvVQ;LNWwxTrK z-S)t*6b%xsC-g{!Mw#2Q1_|4W(yV>Q8DAj|1fXp|K|)*xY9QCbbu_8>vehzO0clF1q*Y)8}u zbMINLNN9!Rel;S3E-SK9SCufWD6P)w_#n}Gf+i6fWo4N)NZ3}CR+)92lb~lrghrYf zw5HA)By1~6tK~Xhk)UTpghpBE=Q)vtZAEF-U*}yC^o)qmC}%8LgM@8G>FlK*B}mXS zB0{5_dF3Mx3EL6Hb2t*KRrQRBpmjY)S8~$&YW3>Nj@Z_2u$sedD@r>zX~)=@+ey$f zB0}RM>3lF#pl3vchOWox%Cj^`*jAKwiq-zFp+SP45fK`?9-}Mh(jZ}5QQA*dJGh1h z33^6EXr%iRkJJ4LX^^lTQSqhE&>*3mX7gUMX+({PS>w8*F_EyXDD5X)%b~j^CR$JZ z=BR%U4c)^jb(P*9tZCU+ly)|*?LmT`5fK`?7ggFky+2sfvaP6n`|gc?MS`9Y5gNLu zR{Cywf3T)yTT$8(x{ePL^o)qm(7nMj2Gje4H7(nU(%#f{oRgquM1+R!ahACxy+2sf zvaKlXm|f>967-CS(9pfwGAE|@2Wwik6{S7B>%2>Xo)HlmX{O$kxjnrsvxbhfS%ZXaMd>J7%TbQCnP@$sMaX)I33^6EXr!5X%X2#k+ltcJ zi;ohk6$yGqL}-*VuYANIVOvo?3yX11f}Rl(8s!Y~I?e6*4Dz&xm))My*<`X6rL)Oj zdcd*ecM`3qCqjdF`$*VUl+KF3`Aut(pl3vc2JiNfu&pSa-S4~M2TD0e&@&=Jqget~>g;qCtY55fK{YN>MHc3EL5M!TL{M zV+|6z0%gyL2)bPH${HkWD@s?t4*O?okZ3)jM+u&pRvt*_&QMC%DX5~0Dn zeI#rvN_QRVI442RhzN}|Gc@-Hot9}u>F!CLuSn1{B0__A`$*VUlOTxCxp>O`g zv9@SrLg`jdXko#xHU-7Ga^ERcl$`#R+L898=w2&QVtUIjEK-EGea&13EL5M(fX>} z9#k|)XvVQ;LNWwxTrK>08Fp<|JBA=#dDGGE-*_61EkkS^M&5Sc3#TBO)|- zw~vJFh?>$Ev<3+s$?O>sLGx}O3EPU&QM8tWMC%DX5}}bwu4jsJU6HV@D6Ix+dyt@K zM1)3J$z%-@wj=6-x%c$<2i>nmM9{q3r!|!c+ltcatd0*7ttV&_p~1U-By1~6tIRsi zNzgMQLL)nDgb67-CS(BR!Z61EkkvzL05 zAVJTF2#s>)m5(?iY)4d_h0Vt(J^fjZYSl9$g4TXc+6hW?yLNy&Y<1v((z2~6?dNpY zH=UY)U#&>cGa^Dm`#EVxD`}9httjp1blmqnsc4X(XGDaC_H)wCT+$$6TT$B2Y2Usd zD;gx|84;nO{hYMJm^4V(R+RR0`q-PFRy0V^Ga^Dm`#EW+G-;5qttjp1^x|`VqG*ty zXGDaC_H)vXZ_*%PTT$B2>8IDvEE*)}84;nO{ha>1+#e)iTT$B2=@sAkvqgghJtHDC zw4al9;8QtB*jAMGbGqmI&ny}w=ot~Ak@hv5?+=o&9Z~OFpL^C>MT3O)DYj=s%o_9E zJ`%PSrTu+tIkelN?+><~&?6BV+5@uG)kMO!qO`wnZ4VOkjEKf8ToiAVJTF z2o3GMTaHl^3EPU&{=PnTh|nlKaZB?q3EPTNuYB-R z9#}L;&@&=Jql~DmLBh78G`gPu%I_;0Bh|nlA zT-G3ATTz zvhOMyBy=RRXGF{zxIb74(~8njw3eeBYjdtzPtYVnBb8ihhK?|;D6Ix+dyt@KM1)3a zL9KnV1_|4W(yFHRD-!gKh|owqQERxYLBh78v^uNfg9JSzA~e#7(pofYkg%;NtupI4 zCqd7M2#qu|Xic3pNZ3}CR?Bt1B0D(aCi6m?*N~``l?~d5us7eyz&u;gl$FnEG*6kNzgMQLZjSK%;$r87ue5>+E$d_->uL4 zkf3KogvLkG`1A9kBy1~6@9);B4l)VeIK3Q3x`2o(-=;#tb zOb7}I9ipft*zGMKr_X^#j3T&_IHKbffdrw$=!nTOA(enP7PaIe+Aos-Asnf2WUU>AzpT_kH$n-)mRZuBs7H8q1E9 zrePvBQMWt%!_({vZTn=_Ge~wZxav5De6FXR29_Kb+qm`BvQ zU(`fwqIh4;HqK4hGa^c3o*CBtq9$S!#d~+Q`O1VnBce3s8E)M#Y9cmKygz80cTLzc zB1&VPsn`9YCSnuCdyux{hY5Q|L}|=NoOQpbiP%K()$ts==J)l9uxCVc8tqtXB6iBL z?e|$U8bP}8jEK_k?oSi3iJ}&^eM=_n84;ziv|wA8n21djt-0;LGGWh%D2=5jo^TvA z5t}G_<+hK^ggqmoG?o$7G)%-MiqW<0hcjW%h$xL^E@>JjViUzIvF+ z6ZVXV(wJwsb-$>I*hI1F-{xHt_Kb+q@a|6&v5DgBB}a*VzouXe;S5u2!- zh1I&hM#KSptBn6PI=l*aNVop!EfA~sQsKW3xSFk#P# zD2?TfKuyC$Y@!%{%&Mhf!k!UP8q1rF&Z#RCv58{*adapR6ZVXV(pcWm)HF=QCW`UL zQLZ#h*fSzZV|mk5(=ZX6D8?U0>(Ve`&xk0E<&9ZQ!$fSN7=NrfO2dRbBce3eug!{y z_An8fD8?VFr_wNC&xk0EAxViU#r&DO6>*fSzZgJhdqzZQEF-FEn21djql;BwX_&BQ zM3lxdGc*kov58`qU=>&zChQpzrLoL#O~XWNqL}Si1(t>hdqzZQEHib}FcF(5W^Go1 zrD4LJ5m6e;5vOUGh)onnA6A{EVZxpfv1+XE7c~)^D2}3AIhJE>%auJNqBNEjz>Ww_ z6sv))Jxtg$B1&U!!S(&3CSnuCs%Gm~ChQpzr7`!!_5GqIViU#cY#SdY>=_ZIF^{PA z{h}sf6U8cX8|NnM84;y1&kXDPMNPyeiq-NqUzxCHM3lxn!>#WZH4&RAR{h(&Yr>up zQ5y41y}n=6L~Nosd&yCvf4`_bBce2xGp}~UF%g@noP{lONuAv_!k!VaX>ezsxxL-d zpYQCGR&1iUKhItMO(TRoBce2xFE6rYIGBh{6!+)Ztxy^!>=_ZI@t@~5XQu@kCSnuC z{dsm>l!gg=Mnq{WU&1^`!$fSNxIfSCk&xk0E<%^z8!$fSNxIfP>n9?v|&xk0E z<;$c^!$fSNxIfQsp3*R3&xk0ECA-hiFcF(5_Hl0G z!-PE}qBPhm%I-5XOvEON{ixeGH(}3+C=K?!vil4T6S0Y6U+p$unXqR>l*T;6t>2?J z5t}IX2XFJP342CFX|M;G-Di};L~Nqi=e!+1OxQCbN`v#k<%lzxh)q=6mAxFh`tQ-( zGa@>TcH}e>JLO=PSdH@~SB)Uuct%8NEG2K}Y9?Y6MJ=#PtTas6Ga^c3X~CvpA~sR9 zCcDH+!-PE}qBNGCcrv&7!9;AL=#}geD-9F&jEK@$MpV-<5t}GR7rVqt!-PE}qBNG7 zp=p?iO%$^PyTnSvggqmoG?p2zX_$yj6tf+>#7e`2JtLwtmYKR~n21djvo^cLO2dRb zBce2xBTmyW5t}HEKI}>>4HNc^h*e|#9=(a!L~#_|%CQ`4TdwRG5v4JgeElB1iP%K3 z8ra&yggqmoH0BmuzejH(Hc_l=_ZI zG0)WN_vlT;CW^C{93}ei(c3d3N`v!3c1SbtnutwQ&cbR8ny_a?Y#P2l$h(|Ki?c~= zqBxu6tx%gr2zy3EX)Nc??Oe@7Y@#?T=IvIcVZxpfQ5wq`ebX=zo2WXw|CB|;ggqmo zG?pt9=d_23*hF!ag13!TIZW6yB1&Vq!qPNM#3qWXExa|YG)&ktB1&VqQq(j|#3qWX zM!fy4G)&ktB1&Vq;?*=v#3qWXU%bVxG)&ktB1*$|`%J_pimQ0MjjuFJ*fSzZW4Qv^ z%3&flQFS#k8Yb)+5v#^}x6eduqPVKMm1DW~O0L@d!FWbQY4~oR(~3PAD<=*<0342CFY0N#byFZw;LKDT+`fYreuxCV+#yq0B`-4d=_ZI!I@X?_L+!H6nEuv?AqTSjAul28tqu?v|^_myj5_S zuP)pljAulY#!~Wju0~Em#3qVb;H`qCVZxpfQ5s7NHVqT8iJ~=mt6*uEuxCV+#?li{ z<~DEl2a{H4qUe>pRj@Qn*fSzZV;NCR!$fSN7+t(oury5AGa^c3nHidfiP%IjOYl~~ z(lBAqh$xL^hHDxoViUz|$6EzU!-PE}qBMNB&qQpZn6-JUU}>1JXGE07a>QxnFcF(5 zjy}A_ury5AGa^=v?*3rX3QZJ8(XAZIv9{&Po)J+RzT0OaHc_kww)QY#&xk0ExdprX zgGnniQLJjVer3X*5m6d*PwegwCaus!u{ztvhY5Q|L}|<;s=Gg!v_ccbDsvm>ChQpz zr7_P8-TlF&6`Ckk%b8;i2NU*;h|-v6xbFU7(h5x!tNv}?HDS+)D2;ih?(PpJt*q_Jq!pVe?$7fT z(b6zs&xk0EWp8aeS2GctDDKbmHPq5DVb6#tjsHHkIWsBcFcF(5?$7g8*U~Uy&xk0E zW#{ra8YW^B#r=7{PFor#>=_ZIvFyNZ8YW^B#r=7{vRfJ^>=_ZIvFs#o8YW^B#r=7{ z7F-%8>=_ZIvFwO%8YW^B#r=7{dR!VN>=_ZIvFz+`8YW^B#r=7{-dq|c>=_ZI!T4i6 zN}HRAO%(go_zHDtn6PI=tQy_(gGnniQS7(d%E9V*$yIxPFrE=n8tmy~bvYNKBa$vr z>>J$L!-PE}qBPi>$m$Xe6S0Y6|KrxLOxQCbN`pO?tS-?o5t}IXac<+oggqmoG}tT3 z>JkkTv58_o>Nd_z*fSzZgFUaTF3~U%n<)0xZu6B1dqzZQ%rji~{9w`wO%(fsw|Uou zJtLwt*sndWn3#7b6S0Y6pYwM7Fk#P#C=GT-v${mXL~NqiubpGp{`tXpMntF4je4V_ z&xk0Er6-=u?a`heOj@CdqF3@2>e4V_&xk0EWkfX%6S0Y6bnzAH(lBAqh$xL^W@s8F zViUzI!B?nD!-PE}qBNEnu4$NvO%$^oU!g7y6ZVXV(pYBdrePvBQOw$Wg}O9M*fSzZ zV>#k94HL16;^@OyuS>&(JtJb(=$;=;TA_*JD7uwnIo7sZ*)t+aV=j63{9w`wO%$tv ztvyWGGa^c3Zo%&P!K4+MC{{IFzcOLZh$xM@C$8U{FcF(5R%hGzFk#P#D2;hUb^L}|=3T=)E7(h5x!tNv}?HDS+) zD2;ih<{c?*-Zc@MD9&DTlsFtr*fSzZV>$C`M;sHeiON}6jX@LkjEK@$-ax~#_R#M2 zA0E`kb8MoxKmX##*6;iGi^ek|N@IDG4r_+?e$fy~mniPf-}Bd_VZxpfQ5wq|ftrSi z*hF!E{@QDASmrAe_Kb+qSl(=OPB~1(CW`y>?|o`COxQCbN@ICLQ`0aJn<(zj|NFN@ z!-PE}qBNE_O*IV@v5DgT{9W$+;H9oi*fSzZV|im%(=ZX6DDKZc;xrm2>=_ZIvAp@K zX_$yj6!+)v__fh6Vb6#t4ern9e9%Pfiu$$F$2>Y3CU`SiJR@S&SkLZE#3qXUc3U~v zJ(u&r-cx!eN`pOp>^_^jZhOCI(h5x!`v$l6Fk#P#C=K>&|L5g=&_rya*#EfoD--sN zh|*w>CA-fkhl$ukv5#{bA13S>5v9RiQFfo9VInqB>_^?kxe0qlL}{?+mEC7(n21dj z`)arO%7i^5qBPjM%kDEYOvEON{lVM3Yr>upQ5x()X7?EyCSnuCKIhE&?Y(L%Vb6#t z4R%Je`wR^ev59K?wU=Yp{{5nd#WNy0jdrYcTCr1(hd<+i%bd96su83c&xk0ErLG<@ zm*Zd}Hc`~VJ3l)bChQpzrLnYN(=ZX6C|dLNuRGh0gY=R{*fSzZW9f+}l*2@9qUe=( z`u1p;uxCV+#xkOshKbljF}l9$GooR_o)J+R%goR;OvEONS>j#)?Q}a1GW#^bo)J+R z%M7<8LKDSo_fxk-!-PE}qBNG7x@nk*O%${C`<@dG6ZVXV(pZi-O~XX&iu$$FXFW3- zCODGCGa^=v^?cAoY@#@dZsk~xwJle@r}Rve#$595{h~=LG*PSuw)QY#&xk0ExdprT zizcnmM6s&b`jrWLMnq{WE3#H{6S0Y6b+(NU6ZVXV(wIk7_kPi&6`CkkncFxwVb6#t zjd^D1-Y=T8LKDSmd7H0H*fSzZV_E698O}s(qFD8B^R5YdMnq{WXDm&_L~Nosd&yB^ z|9;VUMnq{W=W6YUMm!wr`Nw-|9!v58{u3sBL~NpH&0HgI$3c2YBkUOwrLpwH6OMx>ViQHL%(eb@O`qQ02zy3EX)GgZ zM}#Jd(Up4^hl2@wMnq{WGegrb5t}GxiS0g)342CFX)H5b(=ZX6C}z9dLpmHx*fSzZ zW0|R&hKbljF>B{uSUV1KG-!l9Bce2Xx6efEin_~L?&TuxCV+#NQ^!Eqt84;zioO!h)j)~Yr=_ZIvFwO%8YW^B#rR{@Q5q)f84;zy{drbQw1)v58_my_JLAbF4?_f=~90h|*wB zA1m>TL};QoFWB0{ggqmoG}y1rdK3*4v5DgRX6sib>=_ZI!5&N2qiC3jO%&&8+xReH z&xj}u_KLE)M8iaEqB!5&#<>Z5Mnq|_=atnZ8YW^B#d-5KUzxCHM3e@5cUfJcVInqB zod0k0t_gcaL}{=Gne`|dCSnuC)r#%-VZxpfQ5xI{XFZCBiP%K7t1ip2tABpbo)OV$ zv}3J_*eM6Az-7LwTs4Ap;~5d9v6TD)b2$zsViQFzunH^<6ZVXV(pXxsX_$yj6s^fB zury5AGa^c3>4_(l!$fSN=#{JjOT&acBce2x5!EzI#3qW-#VW8gOxQCbN@JNBnudwk zL@`US3M>s1_Kb+qSZ27UVInqB%yz5-OT&acBce2xnYwA1h)oo;HmktWFk#P#D2?Ta z(=<%PCW@mEtIpCeVb6$IHP+_`O~fXOqv%$S5t}Gh%iDZq!k!UP8uJXdK0jz8Hc_nlw|UouJtLwt=9zkZe$Yg0 zqBwiWQKEl-(4G-d8q1kiJK~s#O;papmbpaF585*#O5?|7;_1ux=nsbvo^o%#(kh#% zPrdsGPoMM1y!+Ec@7WWj@veDq?R%cw)(i&|v59)}cYg5n+i%XhKTX&(B1+?RbDMud zt$hwAViWa^pY&&Q`SKn}6ZVXV()hi(@BUe>;SMHZ6Lrn4e|CD~HE&+((1blBqBK4* zkHPu>&pFnbh)vW@Z~xHgJMQt8MZ<(WBce3kHD6o$!&*}xOvJ9J51&5!J<%|6IBcE~ zQS=k$Yhwn~b zoc{K2M#F?XBce2JebP&K=ULM*5xb%eXY=)*r5q;aqOYD2v1+Vu3pEj&s5iX$aJH3W z)>w(&Q+g&!V=nnEOI=MSViR@0ue;sZ)*dG884;y1x8N;Hn@=WUSJds#wti*eaM(N} zqUgCNo-ciOG7+1o&%f#RXWRHN(R)hIL}@VomN7V)h)vXupLmC}ZJe91XGE07hv)J4 z_T_xgL~Npd^@(?wdr#&o6ZVXV(wJws^JPw)OvEPY=_ZIL7!UY_Q^zS zqQ3PH?r^ppKTOy&B1+>~^Z5JYe^KXyCSq6AN6mGWW0#4;Ve^cLPNN-bO~g()zWzt@ z?$1S|5v03$O3y@TEG2K}Y9?Y6MJ+t-fqD0*342CFX)G<+G)%-Ms#-Jeh$xMv zC$=@UiP%KZD{p%HYnM6EggqmoG?o$7G)%-MiqUn=t*_aRgN)in*fSzZW0@ItMCgjT z{nMRD|rhKV|om1jh(8teN-O~fXOqv%$S*iDK2i z&ATS-84;yHpPG+@O~XWNqBwimjuIy984;!NV|A|9jyNV_SCr4;O!(|>L=-(A)lUA> z^1X?};YFtpx$(Knyi_((pLX{boxbZ0KehaBqWA2H(xBwbK=Zghn21f(lfUytr?0&C z^A-&g_Kb+qc;npWXY2XkmR4w@zUh-*JeTkJi-rk%Mnq{G<|hZ(U?rcCh9qle7VXo zYpg`?DLoUV!T6g;73G*r#3t(7Z+?Z^!-PE}qBQ0fyk%+g$wcgmx>^0o#Nn`cMnut^ zLoI!GuB(lRP1KFoyi()CMDHouL}|<;YCRt`5u2!Y+~XFFa})NAh|-v6hVx}EnM}kc z>e=tPMe~&jdqzZQ{PH~h9#eDTWFj_EPkPF^=3Nu^jEK^pPtjB8S0-W;_1nLBuH%OZ zdqzZQFgAX2d4AAD?27vNxvp~TGI2O;o)NKWeD^%o=W@({8xcF@c<#sk577Y{jjEK@$MpV-<5t}GR*W(`gZx;;{_Kb+q;My*$OUhv)c17KM`n>7c zi-rkioOnh=(aQ|iG)%-MirMb9zyD*4hKb%&dL~L^nW>wGiP%IjYd`AyqhZ3H5m6e; z5vOUGh+R<}eWGEaj%4K-5vvBr+NG|XR@p>x6y3_P9BUiVd-g65m6d*3$pfUxiS&EqF%c8p2NWeE2Q+R5mEHq6Hn52O~fXO)!8;aO!S`8Gf^7z zh|>AsmR4w@SY>YG+=M+NqBJh$s!tyx#RM>KJ7rc18Id&V>Qu13+FcF(5YT-U#{^3Q#ggqmoG<{Un21djv)x~PS~N`bp3*Z>8p}-G zG)%-Midp;1Umgt;_Kb+qSdKVN!$j*)~2*^q$f)Q5y4z>dps~R%oJFWp3l#ggqmoH0GIsHFYb8iP%K3 zTHfX>6ZVXV((u`xiP%K3>fh#F6ZVXV(wJxJ?tCz5g(ix#m+dHF!k!UP8q1j%N1Vw- z?27t%9lK0$Mwg@7h}bmdbI$dAFhuB-<5TW4Uw>_LA{rq`ck`5Al&MSr-I!-PE}qBNExPSY?EyP|$>9%<1q!I3PU z5wU7?=Yt_a6U9+PB8GPiMV!k!UP z8uQG+J(gAu6S0Y^)pF)56ZVXV((u`xiP%K3>fh#F6ZVXV(wJxJ?tCz5g(ix#m+dHF z!k!UP8q1xyc8oF+yP|v!XCh~G9KA+F(Y%4?RqJu^-EF_<>t1)e2j2CE{@dxx-tnf> zM?U(e&tmiY{3aFM8MP-i#LqqKU8m3bp|>{rIN_++rSaPN>dIr6JG}P9M&ku1|8>so zZ!8+e2uH;(jX#)2)4P|RXisc3ZvSn+bNVm;{I?d3V}zq(mxjlOJ+aXsef~H0;c$#_ zRP55A4CIWXvpumZ-QSqk+W&RYI7U#LTU6PlL0eG6Xe6pU8$o;1KBaeza8&F{iM#Fe zEfnmDO}g|*`dMilBODdGH0bH{cr@&ZUFpud&JOQhG>#E%Z`vAF#Hztw&ZVyG+0y;H z_xxp*W7ZfFj*7k36=!!%!=Bib<1vr>MYRWe`bLDKVwc9;g14m2?TKA=^$Y4T$B4th zQDv9L+!N2!cN0~fjhGI%XnY(a92L7#nnx68cdf4MiA_2F{Qr1`#`!VAQL#&7F2gya zihgBJY&8DC&;KXQSH}oP#V(DxEzTKLXxI}QjW2o8&uZR1MmQ>VY0N!@-Jeavp4e#o z?&Ds%9vRx)J|r9!yENE+og_T;-hXiA}oH8{?%kmfD3lB#N{g6}vQ+7Hk^!#3tQp|6f=%L>v-DT8@fc8cR<+ zryTagMuUFLc&T!TSbE|woRXHKVwc7;qMC+1u}PQo`QN1>qKzoLq~)mCrLoKmO~anp zmF_Q`Qm(Q^91>M&IjZdXeVO5!2J;nZT_k94YQ8i?%oV&5j*49=Ei-k~uqQU@(r@WO zr6J;wDAICN?9y0{I8DQz*p)8Ft7wQgB&yPKRN1Qr$67SzKYKQU)kr#V!rzTt*cd_QbBb`VIA~V+1Rwt@o8(8XP+qRcIutJR8A! zZW|xR2uH=PlsE=5s!*^eHsxR)%1Ed(9U~kSyENu9u%>Pr_QWRLT3=_rIz~7uc4^FQ z!MQ=3MeT`=2J28pLY3nf;i%Z9!AglyMP1nwn{-)+G7?JT7~!bcr7`z(&b-^peT-nWx*aXIbGZ5z1fz;_B&yUm0zJk{Y0P00vGadUc#HMN{`7;d|Hz*|Z+?FB zO{cd%T;J^LuKn%P?|kUfn_aPlL)`iIf9CY3-u&iMh-)7IqSJT(^S3wq+G~Gg&f!~| zy%Int@BF>LarTs_-|r0K+W+`B&OZN_u5I=YzxCc{pZU|D-|U`v|I>FP3CC&5t z*L~dCSG?tmmZ-a(ec~O@dZOj(E8cg{({H-R^ILvzdG0l*U;K-|)$Er%^UkL)c+v*EkgX?*Od*CwplV%;7Pu_LuvDU z9PI0^eN<0O(clRVp0y&Xo)~#kvuVw)94p}{o@3z&C+Hnf5_4VIV}d7bcyn z0Set>rx3lTo}9e8#^JCLJS)Z1nX5)gTo{9n^7vnZ=Zd1PTtD=fjPqSxts3^2sJ>A1 zN(-LTFAWopddE%gTaQ;u@&%sQV}gE_dF(jhD4v_y)zw7Fd(Vg4v)a_CwU2A$DQpOy zG3wfU!KSVpj^fFu^s!#Ub4H%KOE1Z+)Dxb4Oyr5WaW6?)j;cQWOM`wjE6%<7)y@Ow{UXsv4V4dQUyIMY?&qYOi6!QO9RE z*C?ZwC(%gvc!(EJE2VqFo_uGND72H(z8vwG z$QMNS8cxem`5x$=uqR*iyn3!oH?)iPm?J<#Wb?!AxIBGYdrc#CODfM&!Q$A#c`#Z+ZUnf#QAkOj<<(B zCaAZJmA)J%9Ob^y6ZH06jbJYMsr$XLou4x+{hf!uq1iow=Ow@MADai_h7Y}XJ)<9A znLr~R6U;03`9EJY&@kaBYCS3Sxw6LuGtm=X@*f5oCLG0l_5VEP0x@L;@Xwz7=9U&w zpYbbYlTzw%pR0IGpqG>yF{jU8tr)nWvQ8`Q-@kPyXOlYp&8x6&u2JWrAbLA3aM~2N$ewb4NM1 zdySOb1bR=n;rupA?kLxKufe>VIfGd=bIH}lhY4oXao=@Xj$+>JM$}qY9?wK&Ht_gg z%Q0mPrmjq&H=eJYRv-27)BpK>UpJ`T!(sE7pcXQt_PJsX&&c6OoiWG}b=|DJGNxqcwVbBWX9Ser57 z-1Zvwm|(p!9Ip}2t^fA_z37(us^N6+^t|sm{os@ScGELm`Kf=W6MIa2^z**=^x9Ydt-jV@7cG2 z#voVp#20CB^r&Z)%~35W^&0k=;J(pwzozJwnCQDE`lxAc!3)HUPABjF?tiwX z^^Q;fr)#d5^T)Ze$Hd|A#I<~Du9}7kN4@u&Z`;>ZE5|Qg_xQC}|IrI?T*m|{?MCgY z5s!(tz3>U^c--eIgrmq+W{H((x#~SnT<4Xm<%*JLCZgWPbBWV(6fK+FuDP0xYV&wZ z(6YI^c%0~?wtJI3;g+JVGA8<#-I!YGr~jCsZ89FWc*^0l97SIkk8^uo^U%kw^M_M9 zu3_SEc-)a0u1{-=;`h}0USsoY1bUf+j}wmaC}_k~+XlY@#v3k=`!bk!pD5nrZE*aoj5I`zUpOn{0o%B1bScmRiChF zELrQz;V5b(xxKs`Te|Zx@z#$$qOqm5MY$Gw4cAFKs@-~6OTMMFF;$LuOwcwD`j`)I z{i-W@2uIQWcfISM4hZJK^ik%OL@}b0(we7}}Z;D7lF~YHQh*m>}G091SuX9B)B;OweO86RjGvQMpQc z^ifY-=dqq}??WR!+~w;DdrY+B)iSz{6ON)!ck|VPRd0`nqd{gkYaiDz(T-}vxuj2P zK1MB3{GK}8Yiyp4KyRD7Hl}Y6M|m`F@w6b{KIbduTnp!0>wGmG`>Aib-`RKEbYVxz z1i{zqzwynrn})Ba!&YS zJ>QEznk!^ZoL>{@@kM*+Uc-c=p8WUkKS%!ZMoh&`CwIB?gXcSYwM**}rw?9B{!736 zu(L1xczvYItm-IQ@@->~&hMzjHnxb zxJK}C!cn{4zSb^#HnVf_RiAgivpYSn_FOS;vP*N-m}o&p?K?iX#xwKESG=%nr?e8Y zF`d|B;`OgPJNv9p*G{Jen`df`HIG5}{9eNz6O4k)W5)?c9UmX=qxbyv2c13apI3i% zpYAp6G4bNZKIrV$8%Dj|L?88_`HO5L!tLRjW`4{(*5}F|6T>#2(dop5qv)YIGV~hu zn5dpuJ7|v+j@lhRrs7yr->~){=92V8_nuzE9uv%6>C?vvNBJnx6NkgrQV)N|1J`zT z%l3plCf@nk4_y1$al%p5^zL{*qy3T71Y>YK?>a3z|n)oslTj&fgEH6}{#S%#7)UHANzn2mnEGC|v;=j@}OS9@;v8kyT2<$1m*{_|h^{Ik2gHEWzNn2!u^ zYdIuW$!$;co{hNSH@-kAZA{f}(sEQ+rVW_e&oIdVULN! zfhRCVD@zlO;`h`-pR3-prHfv7Zm?kUOs%vWMft|(2Gn9^GHN&VL#@B(D{BXBpDTMz zRNH7b?o`}#LXUgovwm^y;ZOb1r!||g@}aL3v6jOgdVYu+wIWuHi^SnjQH;THImmC) zrROJy$ID@l3HtQ793~v)I$R3f{?peLqxN_1HK;csHO^BG6Ndw{M9~74c{hZkTq8Zv zd$x3$$CAV2grmB86EdCn2`8S?npc`@kJ--KH>64)j|rar;`yxoSt|V}grnTYn!;2% zeeIg?T4Kvnj%ul0M;-6G_L%U>VAYs&R=G+Kchs=AH-ax}=8iO9zRX>Ac4lwa=T?>J;{&OLL!QJuT*TRgeqYsuNez*mj8eG+#&>vmbpIpS|R;hVwP6~Z@)v!{f4 zY@92;;Fvugd@(W_lp}jWD)su8HT9j&vTuQsXGg+u!X6XU;ke``9L4YBa@b>nudAk} z`*N6Ylv{Qsri-=P*XUi&vNvueW`mXf)@rmzYWi@v(1HubT6FW6pk=d@r`IsiN8ROY zx390|s&DhHo%zz{Si?PoZ6JNF;Tl7cSL2kkXv>o zR*m!@6X<1s(Q(32lqq|^8Zi|&opj@FZvX5G>wC&#xM@QP0<=Upb0#o})w~<{a@i zop1&CbH3=c52zzOZ;dz{u%GqJSFKNE^IQIS*3zDh_?A!mBc(LQPsQ|vqj<(WPkp!8 zm9WPI&!y*?@k%`!PkP2*zdrX0e&Uu-yFOQkKk@X-?*FAfc;UXm49)HFhDTkWE2cmA z$=`f^u77h3%o@Jeu*bwVoPOh~*Avdk6W{e$SB>Mjvd6^x?{n8Rx2wiPIZW)MM(0tE z`q$6=E7$jDTO*t}gq7u%Uurkkkgry96SU^|8nV-Jl*i3d=*nEnRoa%?O$)mB^n^VoXxa3I~XroUea=9!cm@;R*jY`w=J_oW*_&Sm1r9Fm_Q@**m1&9X8;V6E;-+e#!2oaA7`T}dZu|^0-p|M^`S3&B?8IK9qx`4SS zIxR=>`)waTOdM|yr{yRgyY{(COYuZRY`1J9rsAd(drV+&J5M*2J&`CswYkMJ2JLaW zJazGhr+RPHnky5I@)NGB#!O8oJRg(icKuYVpYvRa*_fZH*3-Qv*tgU@Q$458Ur+Q= z4?o?#&8iX1#_^b7m)=;zgrk^q^Cqp9o#mhDgfYOiO2z@>ntPJiocnYdD`Afb<`M4Y z?MDSZe>y(y47uby`6O0e;*{rKNhrW4l*MCOma4o%q86R$rqUzwmBnboMb%#WJ_b!882lNr@1^@KepI8z$W z3?>}K`BY}2UW0R`^lG<1XGA%c^n^VoNGUVlN=%g88ssEn(DX{oM&GYYP^R&`>$Du@ zQP68}zb5Ms?&Cb?1+^C8N@`X$J;62ac(_{skZ<|iHfp(h^7Mz5-4k3rO_bB+O6r)f z$Hd`qm$UmlSQ=9)vG4USujOzKxmTDnwb+%g$AsVTS*g$e&J@oAY-u?P?Yw8CC+so7 zwfFHmIb05+p7gfQYqjeft{P;l?XpOFnBdy`jsLXh{r{ySq&-I{9fn3>Rf^+ln6)zKx;`dyo+H1sPqIOo* zHM!%2qtM7Tphisdzw`fBIpQ(F-mhE(Y{c?UPdJJlX-R1%n#P59mCpOfYR~Rf-;;V+ z3C4MMRc%hc%Hgyeb=_Zi&%8qZ&8^KL=D+!DTOJeG<2J{W_PE_Mf9LdbU-|nj-OGuj zWdf4_z3+)m%Tdm46`=jw#s}wsf7sIE-Nd{rmvp%{kla>m2zyNM=6C9GpDPoNqGrii zM@-aieTD5K&BIsU_zo*kJiR>56`s^pzI|5d*4NTHjkzejhSTNiY<%N%CFUIQH=X2r znRs|pY)YGNb*@AKGhvSj-k6=5uEY!Ji9V{nIl5|0A@a4w=6TF3)_#>QJ+4FnbFMm% zi0iIB@7rV5FwsZV7c2J~U9OgILtf0`lA-pWd8SrQ@;yk1e1&nZVZu?reD<>a_?XKw zo!Da{Ut!#9m~fQ)TVD=G@ii5`+eo^{iQcmj`KIDNS0)^lFC<=0(2- z>#OX4kz8#AbLE!OrqbuiQOw6%jm*SU)O>G3`K|F$M^Tq=Q@B`i6CCZj0Xy5=~YHTb?Mn$A^j6{q9TpRbQu(v>fH5 zM6W^KpZl>t*+vm1f8&dPyxFuzc0=@pqiBzZ-1wZ^Ae@#7`oi13ib6oEx6U@iVwRlRbHN5h1p zsOj|lm6#x0?`XX2rk`&0<91q!*(i3PmYsJ;`I zv>f$uKmH$1pZlkyryA`s!J4rfwX22+N72W&(VXy$ljk7Lx9mZKPt<8s(zg4vC7?KMm|YFN81SN53T z7|2|<*D&FzzGdgcm%r(Rt6ZrQu8E}$xaPF23=&RV*<*sMQOD-?EiFfJEvq}8Po>kZ z8N34YYGBDz`%kTqy|Ty*=QYuBqK{&aj{4P99J$&&Cb)_h?Ox-;_k8B7r}YFm*BQ5& zZ)58Ihde96wX$)WJ1s}?`>q9NsnUqY1lJPBeb;yOy$6nYC3gY0QlMdv3Gb#mPB@B` za>sN}#A5C=yCUNC8pAuPRM)GqD+a}-OX6*%6Vs3 z1^3pH!*MxWLKEz;;2!9jt5w5xX-eN%weN z*<*sczT=Xca1_6fYu6qV=%sD?x-#J?_vzyV_Z+z+PK~k$fP3p*?M}=L?z`+?;Lasc zS8G8N>>%JSW~VV{uWxflv1@>Pohvcth`(w6uJ9ME9?Fq)UF#KF|JL}(sO5ezcgIQB zb=VX3nBaae`vTTnEm+;{OWQiiHQj5lTZ7#Wq{Xfyc5`5R-1LN_*oPJRIAM zvskr9%Hb&5COxLll|8h1>c`qWVUG#=TiWJ0;V93?D=|?H_a92mUa8b>W{j1XjlL(E zpw`*VwYK@3K7T#osN+4+9uxG10;;i%ZWt!?t4$z<8+7jwr6xY@skMNzYRTZL3>QFhQDpXQKXc%>C0h{3GAy8 zi6W)6&0ZrOr;DB6FDDX(M%rdi#N%|a^ZVt*7Pak+=n2lFvS-5Sa(36<)d!nsbIxmX zzlQVZ-0k7qVAHGU2DS5#cuZK2$o$nAO9)4yk$P*0ACla+g$C-*N zB0av1`E z;(Z)ho$<6=TDH#>??K6mg*TjJ?ZY#FW5Vh3ZkMbqj%(Osg7>^+RnzCngrj)p%Xqcq zyz{oCton|Z!yXg7&ndOg=gNemc;`#%uqSw1Qrg2b@2E=K^n^VocwbR!x+kp8`(si+ zrhCF36TBH_+#V(zwae91O4A7~l`{xhFsmh6He93EmksK7%yj zD1IO3${rKwhTCPkmV{{sG`uz2|a@6s@ zYmW(L*Kx^BILhOuveW*ZbLCOQESh$9N);Qz9uv&q>0`$UM{!)~`tG!9$io|%GA68j zT*CzKpBs-_r{ySqA0MOaF@av@m3^*~mZN+`?FnDs@ihm|`jS#l*ki)y?Z*j6ky3V% z?1^|xVCVPCiA42pB;J_m#2%;Xw*{~96C=uRo2_^8)_cf#b}2h<8Zk%nH?R8SF@au3 z6mWrX6e*=lm3Seg5swL%X-U4omMasn(dgQIvPL{k7dyZ2HR5p;8kzGeJJyKD1a^Mk zYsBLyG_qRW6Y-ev4*Y$tLO67f5{1UN@7m*Zv9CrXij;EqeV?m%oGx~Lznn-^<#u$B-X5o0dRHNG=Z}5dxHC1=^5yy$8g7N+)L~+;oSBb7m1V>?Qxsi<8+7R zm^gB}97OTGc-p`@>~m$03F?h6% z^4RPNdrYv(OsyX$9OXLf342V`{g!IYO zV}ka7#KWI3=!x#Tj-ro!^Z)d}ZN!`-{_4(XJhV;Hy;?6Z!TgvqRqFL`->)3y9=Z|} zxpID~(FgtSm3NnKC1#_qD-*QMvz|FBxzlpg)kLq93Q$d%|C+@RvQv zZPq9~VUG#cySGg^ij=ZO*=xjO0z1E7P9(~;z9-V#oi28Mznn-E8kt@9L_AIxJHKB} zB{%x?J<&8qNL~Wx`QhW8%uup6I`f zzI_XQcgJMOT7Un;Ur%ReRnExzayTtV@%#83#~u^dS0fTdN;!Mk=PDkji=E#uClZB5 z&R+IJJWdxozh6!y3XSnNx5w#XUyVpqm1A^{V~^77f62)%Ae9O2e>~Xrszd$@6+2-$@e|o!~z_)&%`!!`lk4Ka}CU`UA zZ4-_nrHqxn9QK&Nz8aAzQp#A_YsBMpvGe=oM555hSlJWtI9=@gemRjSG%{B9L_AIx zJHKB}B&y0W8d3H*-O{@XkugY087uo-#p86b^ZVsQqR_}#*%R?NUF`gRIgu!TPrN7W z>C-*-)oHGn=lqo`<~hUWDo*rz4SP(~U5C*by$MHgXCqe-dJTKHdy;DoPN^sCF~MD# z@j0gnM{zYW=WV?Pci)oVx_4Kl<@(jQuIw?veZ$oBsxh(B=e@POQI{19Im~K_-|(#~ znK_!jdYf)MCS1OXC459A@6PQ?0JV1&C(7v_uPdkJDAsS|^ICiAZeN|5I;G>eGQpk3 zv4+!f6n8MYHlOQ>zq+!Wvqt(=&H<@~jQNVKf9IVX@|d7c=ZeK~!cmNsT-WFc=a>7n z>ESM4PuOFEd&L=D#|cMy6s*KVUD2y^C57IeyrVs?D|<|!F|I2Ujv|L?o0h9NNBqri zNmDH{UnPfbr;4qA`xZ38T$$^P#|cMytn7)5C==ZC9AC3^T8{Dz-fMW4VLwCWdH02$ zu*U@ZC&sxl;V8G$UL(E11bXAzby|*ce_J&s+T6W?-kuTclvZLkYKBX$Ofb^M*D{=z zqnKBA*GpQi>|wsjl^dsYJXa=|D?5!jeg67#IO=M>-2}7txa3aDQ5;26)0Ln4x4sR? z)$KZZZEqpv>^^rId!qMjg!d;OCmcme<8uRhOkiJ)NE9h$)xXbGJWdxozh6!y3XQD# z_e4BS7dyXSP9zGAtorvvJWdxozh6!y3XQD#_e4BS7dyXSP9&4bGN_qy<0d+j4nxr>F(`ObJQvBw1S*liPzBBhM^zU20pz`h!h zC{oIp-)qF0O1$TtZ42^ZQ)I<8-m}`{hKU(8!qI6Y)4*?EHQ?ktj5_F~2c9 zdB1s_F80-kL~#brS<-%Hu*d0ge#4pAp72xSewzR@QR;0g1?ww&Oz>37Z4-_nrPSMA zBOVjj`TcStQJzuvL~7LOV(0hEiA15n3U*(+_BdVaG2yo=_{{_m@mSzvb)~(PnWj+uG25O>j#?6 zordW3x#~R|!FAEwCLBdd<6PNe0{d!2qIkOlUj*CtU3;7^^H}J<T9Y6Zbr~l^b zKc^ob6LX0@Cgv~ToboNSHCJ;qfAtm*zIuv>R?9bQc`}eMm99hqGhvSj`a@mSN zk@%Y3zOGC-%Kfd+mHQ9hzT*3tX`A%7p0I`qdJo_0ygXNqIzB#l$~5DgFA-&Idj$8n zvd08HzZ+!UW~xYr$(>&FS;k6OMBG zS8V-TGea~?F!Lpc#|cLbN9~fUtxos`Q`*_J-fP%nf^P|>j~yo*#g~Z2GaOHoW-j3= z)65@NYY!9kwWGf`Xb;bc^me}9oAI&L`c{&@JxtVB)TFUMJ>jU~oH)@-oL}lHxw=}( zP0%)(^S4r5?1_%@aiu5RQq*paYVHd?VUGz~Hpj=~grlxjaua-mYdniOEl0V(^||Wb z(z?Axl9a})@ZPf#tnF@_a1<$Jeck8E9uwGCBN9bQ?QdE&-0ExJbA+(HpdV8)k>@yJTcCF4?H}3&V3eaRyDNEN-RRtc~&xsqIN5) zR#AH*D}6j!>0{^2Vox~Abj}SrVlK;co-f|w;pzuhHnH=4-j0~dGM#hfH&J=Ei>N&F zwGwMx-TyV$o!#kq|E1L;dwHMw__s8>_SU|2tKGG(@^(7X%6sRqDS5P);P#*C{Nxwz zaQ5vt|9VU7SD$!?xqaW%Y}$kCerv8)4SP)7_=$HoyYZSg-v;5R&%f#RXYaU2m1)h@ zL|u`qr#>-CC(7WmFukDFhtk?L~Ke)sE^^0HG>8-hHgwr)~ zIDFJxSHCvUFyScI;a+2__bpxYp7Y2z9MK5jD7WmYF;Q~foWl5~M!)fs{%pPqTs4|E zJnq}v9uwEx`e&!(+BM;*o8JDR(`#<6)?9Nn8`F8;8*YF0?Dtg9xN2Q(#QnbRc4tp| zN{yRd!)ZB+w{QOTZ;F`fiNERmQ}6!4)6_e2W7_%2-}%AQjGGE=|IUOxCa86;neA)W zgrlmaYdlu!(Xht^wa!(&y@tziIDBv|hjZ9#^q!3%rHqx8n5Zigj&grniP`9Tq6umw zt3bzcSHBefTu}_+qX$4`U+ppi`<6 zq#X8`V04Y=T@#LS@98yaeEibVe{O&FO`lXFmESX?_T}h38^LHEk8=}_8qU-cy`-Nr zK75*7Q9j;uyYKD2XCr8vCx7RwZ-a0Y?f7MsrPVJ{qas)=$+eXi^=!Cp9?u-j{xa1?vt zc&cts*u!oeo}{~au1v5yh-caM8qSrY*t5j*YkPvdP&{>phbW#WORjdkq}47O@t8o5 zC(!m9_D~L<@4LE&3F?q%{q`Epm7{1Io(S9%_R!`$n|k$JnV`S%oa(AERqvY4ohwHT z$6%{ndrZ*tGlDDiXqa%6$A62RLNLyg7P~rM5pB_pS|`Pj$&7LW`^U0JtiLW=&xJn zm|nw#qkJCS6ZV)uZ#=`9a1`a+&7!TY?4fouQ#+;OxiUe^j*kXT%Tey3y$1a%S3Kxf z?82q@(XY5SweN|{KDm;@oXB1bqL}&E$+0KwVTNN5H&ITh&y_tUn7i1+y=u%g%U{ij z$(5rhUw*IH`nSelJSLd!*sHc`ELcxCiaD|NaO?WjM6O(mMAZ)I{;JVFS7{Fu=#AUM zE$ArfFe&vK_L!g+(*DN@N6|Ly^xxN&J+wc&`_tyPohuXcF?N9OHCzryacpPT_nxqa z^#eP-ubwLttWnqjzSnTB9L4YHZ~NMf#{{dWT)#X{I0`yfKYPL+%E3&lxK;iF_qGE?vcY-$+#Pi+L`Ldpb6%#Ze}Qn3xuOM?q()hf@c9Vn5ok< zn0M2czT$oNJpHD7Jbx?s9L?W!&itCWk9jw9BJ*)-q(TXY@LcN=Os;k#suA{>*j+=O zqxqY!2zP1KE)-gg+-5vhZ2dc(yM!+JPGiBi`mv>Jf?61lS`&`i3{l>`wrIa zXvAXzy^UV;wd5*-U|$?;m~E;(6-)O#NrCxf++;r9B)rf|UNrz3wy6 zFySb2^^uQ^2zw~UwXgnLe}PZP`^2?hz4w}LTYCmXSG!XKX2MZ#d*Kt-yzhttX2Kp5fAqo|*Lqum+kbk(QNMKE zu>aFpkjp71?Ei0dBmIjx=1?rL|zYTdqhHi8`T zRjV~uQz1R!DA#(QD|<{(hkQ|M)mU?7qL12oPYa$3na)^X>QmgEcUdWng{ z;c@GjKTbFbjjp$YP4oZFy?sjyjm#@U0;uIGX_=sW|uOl-gQcI zX4bzxS0)&nIbN;dv(XcM)HY-E#7vz&>X!Gk)gAr#LyvgxUtoo7f}`CB{^lQS>%>K< zj-2eerpIMBHa7Edw@zFMJnUNu@zwXe>vDJDyG~Eq}F#|5Q2B9!?j%FaD}eIHD24QIzkiUUtU;VNW}9-g@V?1h@b6SG@YDZ62%8;-+)b@y^0w2nAQ%LL^c&u~u5 zQSJD6aTaa4vWFVYOzo7`a_n+tg0|sVpy~@7)0d-<+D6(IPsv~Zy0bHO%aYbRKl_1a z?0v=l?r-_>GxiVeHGbtK_dolgZ+T<$Jo)e6f9{R7Z{??MIXz?F_MUj^o9=h^9XHi( zfg(x+f}QMp!X6W7-}u89_IS0rGU2Enc=!F!p7_9#hRfl+Lp=57Q90}}@xJGrp0Rs< zUk(#})ECY5HX;s(&12$O&ph1|Q}ym zcZk%EJ@W6yc z$%1`dc{X_XGah)xo^zsHzT+h~aX36^UL_ZOoN&~OAN!zHuP0o>$2|JMYrVNf8Zi~e z(O|1x6QndAwI&?(OTYWDvoHMk(Y{xEOwcytInjipXn&qY+P8;2^u)B9Q|jx=9utg$ zwEuC!QP*C3!x_(m>~rNK0OK+HkUc;48uplQ4?RveidkY@SN51V-rL>d?)mEvy25eL z@tke^(cQkkohc?OV`9AN8PlznX}tl%{jWcG6;& zNUmJdeXi^=!Rlk&uS__~b62n7qe0QNSMgP!cfYgueC35*dUIK(b9+o2roVIcp|8wN z$3>+P_Lz9h&wk3Z znkU~6BZ~gk5o@mOF_Eu~tr|nZQKYoyc8TUcH9q1o!RYEr-f4tzl%Hvm1ieJH$o%-D zkE&JJuC7)MdrUB2-R-TTHJph)iaD`rz0VayuD5@~E578cJ&iWE2fvS>iL=K9D+9hG zzHbi`j^g)mo7-c;$N7CZl9r=LX>BJVecv^~8opaIbnUUFwMBU?A&I%oc^WV~40#$b zdy?7rzTI`&nA$@hj|oy5?*w#Oj^azSyPbfu)O60b8MBX_uQ_JFIde?3w>&|-^Y{M7 z*;Af=zvW)qUtY_>*AY^_Moh&`=Y9gv={lw38Ya*fm)vPNitjX}rdN$QXVbasgfGlx z52WjGC1#^<4-+R}0q zZ}doCsMz`!;%;Z3c*nEW=6qu`yOsH3Xtz6h!MHcEdFWT!f$fxzYnY%$vX}cf(MR27 z`HtIi7kMgI>d(NpJ+C25vG}c_%LodnBZl`oS zS0?C{*;{>_a1^6pyr0^Alyc-56LK}48SF7Zy=7k6=PGGA>UdA==BT-kC0FkGy@oyX z$`JJ9-58wFT3IGnj^dlh<8f{e-$c$_V(sI(GQpRD$1}Cla+GJgUc)moMB3SNWlz{+ zf*f}JYAUWj8uU@yjL~a&1~5S#rsp3g9Oap)C%6vAb*ox`{Msqk$zpRgtXr2%v^iHe zI4{S;wN}o{v3VcBZf0nNqqv^SwV0#CoIRcy-O}ob*Pn8Qr_0rj;EHpixXZwGr;cd3 zvWIKmT;0BUu1wS$5-w=$a^)!Ags`itM)V%uyin=VPRZdMxc+hHXG_abTz%Y?eCDQe zd$@|0x^haZKqKri!Ij9g=5fMNTzyQB=?U&Rv1+9axMs|X5}T{ftQET!Y`LPHxi*T& zG%d@O)jeU43EF1Y+na_7N74S(NExMbX>0a?snkVtcVnn*uH9yqjR8 zaZPbwaubeXG;^(SPta0Hixy0-I9o|O^|`Xg1U)A0)QG9L>D)vg<$BvxSYK@(6ZGkE zo11V{Kl53`b>-gYS!s*EIA59Io+?*8_qFS^9Oc=y*YL>U%4z0ckIkO2#{^ex$GI}$ zD6aXA#~|l?8L32Z9huU)Wm~SM%3B>j(&H#O*Qz00>wP)wF+oj7?>ONo&nrFQyi@Yz zYFCa0>-(+=YC7fXHJp~CJklC56<6mUd2ZV)a<2?}4SP)NR>;!W)*p`Ing&-Yy1qM8 z_3oW`Ot|;7T&)^T%Tcb8MlApIwQJ&dPjp(2au4k_{2b&w`=92#jeQx%j?VUM1aD7D zjr1B$%TbS+_Y{pa>@nd{&}*1*6uZU78upm*th8!Ov^noDmExu`r_bMXPP)wLXrRYzjeY&AUvvNQ-B+i}dj>i7LhLk3 zV%D(71aCs*NCCYBxBv8nqeyAHuC*`|<#2voj*1y+I9+nZu_@))Y0Sw~uHrF4jila| zJhlJygrjJu)Ot@i@4WpoxvHp9IqWgPdo;(jYr;{-`;|Q=&`bMQs`c-5Zo*OS(>=i( z9XW2$2E5UcqfXkR>$?lq_YxD=Ui7b7j zj^bUGyIjpESEIK4@v7X-*kgh>I;Kp=2}gOx=n3~x2v(PAkBowz@aQx_4msZL z>&k?qs1c6VD>0SQbk5r$InvyI|9~JtnYscd%NnE)t32 z-R-&m)#u6{r;DAtPAkzgE)t32jg_qL_T{k0>0<9@hNf|mNYvFvl+zuy`COoW1>h*p z7<1tISI3X+W2Y9{`#9&h1ikD7Y2i~rMZ{x*^0B7d*Ok+9RFz4)EIN(s@?yrLA{N~xzlo#kJ_!4Rt-P(>!)-5{BR?dfBGkjP4JcyM%!AutA^8Z6u+ls z_Zsn-AbtM#SR;g^sFD2MG|1Kb|9!tQQKR|cn?}Pf5{_~oTY?u2&L+qK`NiffwAif= z&wY7c4$kNjRo7<@2ckIt*nUrz$W`y*8c-4Rbb98h5vaXaEj#-!zEd{2U4q+x>aJxx zCb&O5e$tz>-w=-CUQymf&}-yN0_2xFaogKLj=i^*`I~mQNN|5={N4`}j^duq?kxp# z_UgWKdNp@5l6UTlbS0mvG}P6d&+;Ay?tkSy3e-qyy)U^vCb%n?H!rNjtW)=$lN0X5 z<&6%m^_7^7z6DL7F@CRs({dC!9KUUW`{a3R0QHmi3~<+JTylF%P}Af08kletcY*RA zg}&tWaOWpA>XdrI9uwRvN^2e`97VrMUueWs+;r}?r9F~&_k~`=9uthHab1~k6yq^% z(`$GfP>!vgw~^Kp9#JN!w{gER;V5=^WTf>P_L!h$)ANrLj`9fZ3AYq8L*BjOzHot1 zuQtKlmG{0JC;F)R%HTRvPsP<$&b*0Z7jG6HQPH+p%QJSM5m2@uQEbZ`!Qw0W?t#?$71CpSujX zQs8~on*xMACb&&_~-RJBFe(Tn4^$OC6 z3vaZYOI!Qq`*-FNUVrm*sr`F)SAssBbB08hh6zXI3xNCDwZ{Z@+NsyLNF*xX3G6f` z>dGFc>n|6q8naPr(WJ{8)9?KIKeO}!d_l8W!|z(KY1m`pnpt##%6KKVOebo$DBKd(i(d{wWhU3*M?+TCAt`mQ(p)TXgu zTzlQ>-BJ8LF1bA>4u==bwfo#78e3Xh6!ddH_9t(HpaoMuw0~;4FZtoHwOYPPb9oE8 zJxqN2&969p?eC{AY%2X2?4!26u*EZ?Dpxf+fBEcXr-#S9qDnjem;c?3s0qS#LJPj} z#XsJnT;I?o*ZuBGPOrQ6yp<5*RqwBP<(kL8sDB&#O4wuK<9_@VS_YxCNddm6QnrrxM^n|1Od46N&x9RE#VB)ub^Zdw&V#di_OPx`7 z^ghZro<;33!F%qh$FA?Ta+q*b)xv1rb*`9Eb7ZjIR&MI5_iO~?G40=oskol#qK=M1 zMrlT;31*4UeAw_@nd60>U9<8@0ft`CgRf3e`B9W*z_MfR|;ufrC>fD2( zFTMQfA6aM7d%f&`Y`Izq)I-o7fAwjH<<8hkPhW5ndk&upna(*PCtZ%`_xbV zZ~l|DyuhHY&Gni4|@}fT+ zXmA`%Z{P^`!!P;s7R8z&?Nq7PzkR78bOw_LH9gTNB;RCI%+}~DWHu@GcLHX|b6Yn3iN1xUf<<{&q zde25Mg75e7BMlRdI^Ij%Qmh%i{N*(pT&hIj)~Dx+v3lMA>7)V{^?_(=gFT{oFiXY1GcqwIZXmt4Cx0@)k@v z7=!73T@Kf5QS#oi5sdltd;u2-N3ka2+SYm;T(Iff9uv$;-3&J*992iS(Jad9h;ON( z{@e3PFGrcazilPy=PMJe&T@p?;;AdA0X1CE8o1MJzQ_B-_lM!VUG!}=#7t2CLG23ZQK(te9LgYLR)Vp zsH>`4Cr*{Ox|@-;;r!c5kbbvLTnf_@jzS|VgC)5Ar>-F`0ttVad z*!z6B2743PaYz(*ve>)0C!7=ZIj7{ub7hYSc3-Ea`*N6Y6uYm}PK}s~t7pklLfVFX z+vJ@(+-hV~shK*So_PJ~H_SV|_a%2)^q54kcbA>B9Wm#up5RF>a-Wc0rpeXu7L3OP z8tgdjH0I(|IYKzfeY%x<&JlmpIql3IPSRpWDZ9avtJFxv*1vsSnPAr$`^v_-N?MNU z`}C&Lm%{{l>;@cbq~wlrKi(85IsGTCM!!lgp}!@!JzVOBc|e}bN2>XkR8%j zuU!+2L3ZknOP>5X$}QWM!y|{i&FM=XX+2?&3HDW|A0HpfwQiF!(GR99Aq$PDN5?KRS`Opx1gPjp(2a&Gq;X+ab0j2@3Dr{yTuVXxsjp*_+Q zol;NOV}kbI&2TeX$J&&`Q66cl#suN_v~w1gonSnh6?-L`hCL>*qkTD%C{l{OC*pCs zyPcU}Q_Uq?T8{dTAN}UjfAjTq6m1%FG=I}M??K_4PK;;oJE(WC{KM_6XllSr*kb}a z_rfan7?CKn`4-xKF7X}@-d)1?&xqn3BYfp-PgtFISMdESqImNKUpDKAxh#Fjd20t> zha$>l>dRq|3Es59cb__q8SQs+IEq~H?WH~867m+6Iv_IeOqi0+# zS0;F~7~c(C`_)uR{a!Ukd8GBZvd0AP3F8ZftHy#=Z%A|@m!f; zbak`OFjtQ9Jils8%nTl#5s%YtPtf^UnFZ_DqK-l%>-oJ#JSKR8ZuhLrlokxpM{Q5q ztQw8rdP#OPl9RMQXTq^pVm9hbI35$&Y1zw(M4=ITPsHPNvC~eM6Ny42_MV8x>0+m4 zFDDX(M(jNikJH_qpD$Q{Eu)Xxu9vME6Yashl<8*h=#7#3d z|9`b$2uJx$uh-yNjI42Zk}>UH&ufgb}EmtOZ(lKX!$8+TB z)^f}_t6XIqP`f$XBBgO}x5osnnUq$I+3266ca-~EPuOFE{x%-xCLHC_+-vyxY(JOm zXGt3|71uxMZQ}S7piawC!)M86nd#gf6WHVSxJV@GYG>O{7khjhbXtzO+I0pK*yBCI zPRmjJew>KM1on8Zv(s`EzaJ;!F>(AW7*5Mk{!UBvsPrp;$E3e6n$BB4MU}rDIUc*G9(1_g=ywM>~FZ-$i8ad18342Unr{`ZzB#M+` z?}>PvF7|kQI4wu<`*9*36WHm~`&^kw6dJMjL_AIxJAL|cB2j3>-V^aS-O?NNU8m)! zD#tM*z1;+M`rAHNCK824>^%{W)5RY5U8m(JejgKFE%`{zu`4ax=gJ-v*lF3ziA0f7 z>^%{W)5T89UQQ$mjo5o49;aJ+qc(S1j;eATBhuz3u+y^pT$xA|8nO38JWdyT+~!Wp zQT)CmCRPC4;bmUrnm2dfc<(^2p6`e`dv!F3#{~EBc+bK3>Uju9aj%fKFYF1fp6C5( z+==0R7DUy(sZZI6xeWYG=XJ-mJZOaAXpodDw*IYh#AAXo@ivSuS5q{SU+$9f-U*_P zA93t4!QBkrxYB8~a+q)w_d7i@*Z1jYq+NS)CKK}Jy%~rK0?VNp{R*K_Ju_w4uPde`F1=H2^O zPt~dMoI1l4rHNd*?J`P7+P{w_r-wxBU}hThXk>6sn9_C)5*mqo6t)wL(#SWo_9?h& zmmZCx?nMX76$y>n?!nu0#VF21Bf-|7e(w3>U@eh^#u(2;qXyGr6vyL{(5{91plr7c z?Nj*ok)UTUVR}0u+ELmu%QfiPOPC%tNXT{+SIZ+o&tAgxc0#nHwy(nJ*-MxnHAu*I zl-h27tmxTGm>xAquupI`I1==b*uGlQeU_)c=w5YPVk^--ka@1?At5_2`Ch_N`rYFOE^lu+g@te!*pf)3}Ao4QPQxzB%;V5a?UJ~|<={{$(dB8ErJw;<$JxcxN ztXF^gNK9H~eB@rgH1{ac?nU}?h3zp{^pKF9_m91Vqx8G&rG`CBSGIe>{)D5XVS7o~ z!*pf47wk_sN*cD8ggs1GwtK<;grlTkdr8>CbVD!eA54o;QI2hddlU)TZqv(Lk#LkW zY%d9Wn67O1g8d0cNyGM%u!re>`nkWdIrD{wj`wJwEyXSj3S zoPvv^>vAxPBgUvf4+*uH#aL3%=pWW#6i1?}F@;j>pF1t}DCeEp5o>}T66(P|Zrce) zX~Y=nW3mQ48n0Z>)ZVT^BJTaku6QvmMrl0uXje7nT+yR@COkeerR}*Qp}Q>dE09c! zQTp9|bE#nu3F-M7>2`uqoQXz){aLet=PUIBYmWpyBs8z&xgx(|>()=7smI=bXoU@Ygq=`FtDQNAW7fNYJyFFuk1+?I>QQ7zujz5~jBkq8-Jn6eB^;Uc&TtLbRiJm0~35A))s# z>mHiUU+tMRf9P&MU3pY~wf1$%)o*N% zxuS=J?7SR%2}iMSE;Ss*bY*WJeMmS;8n%}j_Ap)9K2O}AaFjG`F9~~?u56zt?oT*M z8n%~&Jxo`&&lC4293>6gOTr$e8+zFpB-3J4lw%v=Ge{D$eV(|?6$wX4!}gM}hv~}p zdE)+rqoiSbN!Y`5W#@MYF)c>v_w9r|By=aPX71(a!?YNs{;w7DlF*&1+FOxF_ql49 zMz+qQ^O1p`y+rttu=etnt%M#DI;YhRV-TM_^%=WgdiHroq~sArdTc9Qey?gER*q6yjItdXU-*N^?*9FCcPQ@)UrqGbmIl9~ zwOWB#IZA0U%64en__Yt()&HbHk8Nr2YhbGth?S$17Ncy3#>pSQ>+Z`w_lT-Nk8NrA zt7c1ro{SK^TD|ZCx7)qbF+W;0NZ5|3$82;|LW6|9reRM;1bzFTx$(&1hd!xlkg%;N zznLO5NQ|D)BM};Z_ON#x`Tm>EtQsV2E6UGDg$9UK7PTbQ($(Ts=S<7C2tJRsT7g(O zO6rWV9l3hlxtCw{vVZf;szHzKC@r7o1hH~dq{XPPXN`w9jZzePIx#*!S~OCEQMN;) zl>CHttXA~cRyp`oYduye!6@6IQO1!IG@g_~tmv^F$BN(J*+%d?Pqss&j3aA}4$>Gs zJzd^gzglf07-c&&{=;SWUZ3~6b=9E9w#wmq>z4#Q84*X}&42o^^~>+|y;XyRZAJMT zGog_YjG`SxIZo>~?yi`YZ4vxdP91ksf>E|Zqty4h%^xdzY)gaR{HgOtN-)ZHXq0xl z_N+#aZE5h^MXS{|f>E|Zqx8SEdaha(J+`G$#>eu%c!Tc3q-;dVb(HAvWwsAFoKghoa%igplfHmDjJ+f@(Y30s8Pl-fYh+XzP4 zj+ELwST*Ret#s9%)s{nJ8^I{sq0wgNszHzKNLO?FW17Y`B31*A3S!pKx}+T|dV0EA zee`l@bjt`v*`AM;)>l=79@{F1R#Ck^G)iX#qilzU<_`5-^$&V%$FX|MMr|SNZA3Ym zhzdJ2?)vuI>|X!1k8j6{o=!aepB}t9>mDbx_C{j#EQ!d~7ry7{-9LQdBdZ1p+ltbv zU;R9Cl@W}h9Yi~0sTxenwg{ccs29tg&v6z6qinZa#kpD~=&`MIcRknA zV_WI^`{zr7o{WfGl{Lez*9;_VN0fTcyZV}8CiJ^K84>h%-So`e&%EJRuPmXH;!W6A zl)oV!grDFwiWfcS8R6l?w80F33@UjG_EZp=(Xp?H5n4N74@nkn;pF| zHZ(}klM$iu<}!j_8dq^vBy20{Q-8lH*A(B=G)T~s5utIbH$Ha#?zoDxB4JxmkGuEI zj^6AUFQTp1d z-iR6+Bc@(N?T9+L94~8-SgpDzBW8`On#M%JwxTXO^JJ8x zXw1au2|W^_QA&QK9jl3iZAIPvJtw0+NYIlJp;2n^NUQUSgl$C~I&=!!6$yGWA~Z@% z+-+@lB4JxmpFRH+^bZpBWJG9`9<|&0;6%c4$c z6{Vw~_v?oS33@UjG+GT-4HC8$rP|c{?n8qFJsA-ittHm=E(zO;QmfRv-9v)}JsA-i ztw&W261Ekk-laFdhXx6HG9onE$WS#%*jAKA3B5BuG)T~s5uwpWxT-0R`p zL4ux)2#q#UR}B)j6{S&IZ~YGq67*z5XtWupYLKuUQ74zBb?3+>X=BvwxYD^@8d2BdNLw3%1EtqoT@>>wxV?Q;#p#~B0*0^gho5_ zsxuA=+lum8SoCue^khV6yrT5K`~Pa353W{+FsFvCsGqyzp`G)u^tl>|(X%8%2L8 zAPL(wYI@MlZ7%&l(;%^eCnG}Rm8Jh(+0F+^*jCg-exSU${&esBkQh8ok3?v^yeIkf0|cLgO;*JCm>-Q4cNs=0ojRk??yB)EY7(=pQO)cQ21~ z&T>A;w8B=@DIa?%%0XiEEQ!##LpdM(L>#M$gl$D#^M?;ZeUP9hBSPb$rT>*)wX3U9 zBy88H>HE;GNUY$=h|nl4aksVIiG*!Mz4gJzp?{DVJWY>8Xp|nc+xp-{!nUH$e_wga z|5?}fJ~$KfWJG9usr0{(wL64J*jCiDf8_Ymt~_3mpeG|jLv_){#EFD$Mg8UF$79?j zK~F}6#yd-!x+1RiO(bk9>V=;^9`gqYdNLw3%8awy=BSB;?TC6f<}MPeRrh4Xpi$>q z61H8Ab58QPTGOb6((RtmBM};{9Ptzk28f~Pm8YFBhN~88C z?qLlQ^khV6v>B&rkgy$5ntiN6B4)MlWJJ(y=8R)i=Rv0x=_*RIXfFqe(X%8%qpbj{ z1_|4W(rTdB2MKyIA~f1crfQI|U8BmX#;s?yBB2$MJsA-ir6p<&7sm>OX+>#u*82yE z!P96Gq0v^BRfB|WMQN4U`#A}EG9onE3b|^Ku&t&+alJXq`cRyzLMA z`)XRf+E$d_s-ibR_j67Y^khV6eCs2gvA*EfVtMBSPaXrOsd2 z&Id`@R+PU678)ez$%xP>v)cNGwm(S1wxaX|l-{i$8YJk+h|svST$4GW?GKW$tth<_ zO7HRy4HEQZL};9J{T?zXl&k+7{Oz1ghy4-)ibL}-*AwcGmOM8dYB^!~Hn&q>ge z5uu?KavMt~61EkkH>T-J8_{-2(326NQAW7kHYQFaY%5A{V(a5B33@UjG|EW5+s5{Z zgl$FXO_hEAAVE(?gobwF+Ke-iu&pS6U$2cNAn3`6L8H#KBy77J`g+8mQ3<7MPez1B zD|uZrkg%;N9R+>gA~Zmj4HEQZL};{@Sl4hQY%5BwQcnbi z1_^pHA~af$sv0D0D@wgfUnmI;67*z5Xta@`YLKw4D2)>OB1&kGpeG|jqm6J?gM@8G zX|&Uq9YTWyJsA-iZKSRmBy1~6qqe?K5gH`u$%xQsGfveYVOvp}ee?~D&>%riM$8(T zYpVtc+ltaG+RM@A+Dg!q5uwpm01LvjqO=<5^+AH3j0lZVgIfDk4HC8$rBzLDS0w1k zh|nl4QERxWLBh78v^wkkg9JSp5gMgOX)RhcNZ3}CR++t@lb|OfLZgffT2ogI61Ekk z)p8%NNYIlJp;1OSog36Kk%VnUY1QAyT@v(UL}-+eTIV=bgM@8G>FmX`#A-!?o{R{M zcCJ=u91^w_<+HFhmc-dzCFseB(DgNZ|K8d52T9mg)Mt9Vp+xZ{~+lum=@j`>d z=m|X%p;7jnPbgPeYB@;QR+Qhw7aAn!$%xQ+;j=D(_5~C+*5}~2}`F5-(61ElPcYn^uY9{E( zh|nlCc%;?&M8bAN#k)r5I-iNvs(Ugb=(m;r_YLJ`sic+gQ`Rl*j-snJro{R{M)}yKh3EPTN z?>hSEe{LEi=*fuCXd^?_AYnVAp0j!6(Kj{?5*l&r$%vram{>JP*jAKAyBqKM`KCc) z^n@OX&}d_O)gWP8Q5v;xe*9;f1_^pHA~f2J6UPc^nU1JwbNZ3bGz}7($?VC9pxeyZ zj#Vd2D@wCyF9(Uy6Eum?Xe)rKLBh78v>NF3L4ux)2#vOqsTw3~N7OlU>shTxXoci< zl@UR=6y*jAKQnZ2KrpeG|jql^q%Q&$ZVwiTt- zav!fq(326N(N_9(OeA4jQCju)ahC)=84()ojHPOju&pSaz4Tdv1U(rM8tu%h&Nw7& zM-;*0LMqqo6o?PFU}dUKQB7#nLi67*z5XndfY50byKZ*weDDs6&VDjCMtWo{R_$?Wwi4Tb>{6Y1vkk z-U!|M2MKyIA~du&*!p03ez2!yTTyy9b?@gS=*fuC&>m+SOUmDrSKp`rcxvNKcH3?ytTN=HF& zP7e(d^khV6v>L1$By1~6wW)WlhXx6HG9oluOI&MABw<@oYL$9ZduWiLCnG|m^{A>r z!nUH+yYxQy&>%riMubKi8L9>e+ltaCp*O&X1_^pHA~f0vS2al3R+L6NyZl#PWj-`WXeP5KBW4ZFwN-s7KCXb=La_33@UjG)j-sTC{4Au&pSqGJ8KKK~F}6Mj08jrmh+!Y%5BuhJG3EPU&s=trBBZS!_k=Z1NZHasT!^iP5tpLW8?~By1~6 zXT@LniZw{klM$i8-98ew6{WNLLsx%KD+dXBG9onEm5E)=gCuM#N>?dvI`?~<1_^pH zA~d+$N5ZzEbhYKGV;;~nNYIlJq0z1s)pC%q9Z~0O{^%vvAfYQz_GCoR?TS~`AYofk zy83mif3XIM(Gz+kLZe-|s~RM1D@s@K{_OAr+p!`+Pez0Wcl$`#j;OLLcbYXw)E&O& z$%vr2+egB-qI6ZYmxILUiJXuKjZ*S?w~vHvMd|8ruMZORWJG9`8k~3gNZ5|3=gh6A zUKgDST`_mN%7~!b6?)bAM8dYBbhWdG9om%+egB-qO=Rt$6XTiWJGA(v}b?NX_;1(cC-5YL4ux)2#qr1 z4Euvl%XCDQUAcMgB2jnvnkOR$jXKwouHjPRs-R_B;kO+-d^13b|VOvo; z3i`%SXpo>MBSM3_eI#rvO0{|T>iaYe67*z5Xtb8N);vhUwxZN3fA;p)AVE(?ga&u} zNZ3}Cde^Ie{@$$|Bl33@UjG`QPG!gfSWr4L$zgk~~(G9qa1_K~oy zD9xh193)0h=#dDGQgYo>RF4%2+lta^pw|ZpdNLw3+DfKskgy$5=gh5Vxj*Q3l@UR6 zw@+&-6Sftl)miT!Bt}orBtnC`eI#rvN~_G?&q>ge5us5=hGBouX_;1(R?B_7B0*0^ zga&u}NZ3}CR{ee4B|%R{ga&u}NZ3}C&R+T~L4ux)2#t2;Rc9O$wj(Oe!sa z9`K!yY8oWy$%xR<`<(PCmAcZW<)$$%xR<`<(QKF=>#ntth?E>BFyo zT+<*yPez1>-shw@rAdQ?ZAIyQPR~2@$D0NTdNLw3^gbuO@l6^eY%5CdbNb26lbQwz zdNLw3^ggFIxBWp9wiTuKIsN9h{B+YGK~F}6hTi9-H}I((By1~6?{m7tyH9T#Btth?Ux3?=2^khV6=$)Lc?M@_YD@yP8?fruU zJsA-idbeongA)nciqiXidp{>ZPez1>-jUkIl8J-u2qX#EFD$ zMd|&%ecUBMPez1>-dWqm_KAdTMd|&%ef}UpPez1>-o4xAsELGaMd|&%p1W2n67*!m zpiyT|61H8An}6hCt)DlIN+?}>G9olu$?N$b3EPU&QF!l1ALy|pj&3FB$%xQsHMk&5 zD@wKb?rZPYG)T~s5uwpq;#%V_3EPTNtGxGP@7Xj+(326N(Rx(XAYofk>Rso)=sTMR z33@UjG}_2eHAvW2ltzi)J93w%L4ux)2#q$vRSgoh6{XScoKJmQ(;z`lMubKisjCJF z+ltbt{l)tq-84whlM$iOW}K=)!gfTxYxClZzO`wP&`f4eM$8)6AMAu_MQIl8CJl-`fh??Wa*Pez1BX^Hdwq9kl9O7D5e z?-!*fBSNF}sQG?T61Ekk_to@%PJ*6{2#qo_%=e3uu&pS)cc+h6Bmxx=MubKi;i?7++lta?*Y8gxK~F}6MjNTC1_|4W(x~0=ZLX~v^khV6l#iqh(=_YV^EWJG9`9yQ-DO2W3Hw94%LoCG}? z5gKJ=nC}-QVOvpJE%)(?1U(rM8fAo=?-wOuTTxo|_i>j5JsA-iy!(@cZAIzq#k0hC zzbHK!5gP5xtIjwiY%9uVVX$7#gl$FXC}Y%5BmgjRu}L4ux)2#q$vRSgoh6{XQm ztH978K~F}6MjNTC1_|4W(x|OfU}%t_CnG|m%{Wzqgl$D>_R*>{G)T~s5wphpeo+#( z6{T6Um!r+KHCOaxL};`Xz=ANXD6Iy1eUP9hBSNFp;QW4361EkkRZVYKB$PD-!f% zL}-)|ZhpTg3EPU&s=trBB%riMuf(jOP%XZ3u%zBttjo!>#mE?AVE(?ghu-k=B_kI*jAMG=XLi;Xpo>MBSNEn z(X(ohu&pTV&+9Ij&>%riMubNDGHKNyVOvq!pV!?yp+SP4j0lbPh1IG-!nUHcKd-xz zLW2Z784()oOR-ghgl$D>e_nT2g$4ro{R_$-D9b{&!j=ZwxV<&XYU^*=*fuC(7mF%`%D@nY%5ClqxODIf}V^B4c+sq zyU(OS!nUGxUu_?+NYIlJp;1P-`Fr#vY%5Cl2lsK81U(rM8oCErcb};oBy1~6_c{0Z zg9JSp5gIxlY%|V8!nUGxSGMP_@q6_2WW=CRXHF8fT@KwP7X7^CsuD`qo{R{MR`PnT zM#8qDbQE-#SZI)-CnG|m)nL^iVOvqEP2D9H8YJk+h|p*)ab4r!nUH+yL6XWXpo>MBSNE%3{``KZAEF6&|PAoL4ux)2#q$vRSgoh6{XQm zcZr1t33@UjG}=gAHAvW2ltyjcB^DYa=*fuCXfsaLAYofkntgOvT4<1bYiq9P$%xP>C7-`XPr|mMv>NF3L4ux)2#r#M^Y`dU*jAKQHN9PtpeG|j zqqM~Nd-No1D@v=g-akmtlM$g&dery8)K@#+2MAzW{px))Av~)HpTTwcj)LWsth6#EyA~f2$b3IohVOvo;E7ses zLW2Z784()ojJ|4+u&t;#yT5bOAVE(?ghsnEv8(zZVOvqUN};!nML9^&lM$iOuCP=M z61Ekkt1WtKT4<1By1~6SB>=cx6mL#Pez1ByW&+fNZ3}Cu72q)cA-In zo{R_$?)H(ettef^)7$t$g9JSp5gP3ZWGx2?+lq>-k=7tVPe#ld^KKsr+ltav)n1Nv z?Nzy|`-ApmL}+lgk7?Ofl&%i<`XE71MubMG!C`;UX_;1(u5$NwMS`A;2#wMbhy6jP zWm-|XTHpHz33@UjG)j*e_6MDoX+>$*q4#qV^khV6l#yZBA9Px#6&1TD?&l=v$%xP> zBiyh*s5ca~Q=iqdXYpFc>@lM$hzGcWJQ^G9C9K~F}6 zMytW9LBh78RGWIMU}%t_CnG|mwZwI)^SVFiv`i~Xtx|6l3=IMBW8_Zf6!@}R+MJZUXC``)?Cq( z5uw4|J`%PSrPV;M4-)ibL}-*69QFsDmT5(4RnyxQ33@UjG)hYx_6MDoX+>#u*82wu zdNLw3N{<@$2c4E_MQN4U`#A}EG9om}$S~{=IxW+R(rVdb%xXn~o{R{MGQth}gHFq| zqO|Jo<1Pt$G9om}NImQiIxW+R(%Fk=iRJ#FJsA-iI=d_LV4ZQ8mTg7(EUb+sAn3`6 z&}esmDDBVdE25!6f}V^BjdpKsJy#=PTT$Ad*Vj-(g9JSp5gPwe z>RcnK%0a@mqO?D+ueyc?33@UjG}@iZyV4+GTT$Ad*Vk!7g9JSp5gP3d?5aV+wxYB@ zudnQe1_^pHA~f2aR>~NYIlJ zp`m*$wYroB3EPU&eVo02kf0|cLPPh8YIP|M61Ekk`%!y8CqYj}gof^U)#_3jBy1~6 z_tp0CiUd6w5gKKL8=fC@TBa5C)8&5cKJJpBCnG{b_iL9Glg8bNgl$FXKIcAvkf0|c zLPK{(Yjr6N61Ekk`?WoHEuSB>CnE-pI@dBS+b)N`LLL3Q<*E`&*Pe_BjrQbZJy#=P zTTwa+`U-Vukf0|cLZj7S)gWP8QL0USg*r4y(326N(OTlV)JJ`O&}o@glv<^}LLC|; z=*fuCXg#WGkg%;N^)7vdIy6YolM$iOMuw_E!nUF`O6V)pp+SP4j0lZ3!c`3twiTt( zPG6x84HEQZL};{;x@wTHttgG!`U-Vukf0|cLZi(%RfB|WMQQfYSFb~Z1U(rsYYfj1 zIxW+R(k$A`(dOEkD|#{_G)l>b=LemZX+>!@(CdQ)JsA-ir3Q!R2c4E_MQK&j+Z73V zG9oleOPs$qLBh78v^wkkg9JSp5gMgO4bKlcEz^q9Dzo=<67*z5Xq1s*cz)1nnO2lm z%N}D^D-!f%L}-)|Zg_ssX_;1(R{ee4B|%R{ghm;u^^TM}?vk*rD4o4{mRPMw(326N z(ayZ;j6=eeUJn_84()o4K$i-SK8}etxm4}*|wszKY!Vo@q2xD+x$jSdNLw3 z+M9H=W~lEMby}tsrTzK4zsDLR=*fuCXm13n8YFBhO8fJN4xQ4*D-!f%L};`(8||tb zBy1~6`}3bY-x?(7$%xQsZ)mC-By1~6`}4nly){VClM$iO-ZWJ;NZ3}C_UDhf)2Z!P zk)S6dLZiJgt7?$2ttjo!KYn8k67*z5XtXzfRSgoh6{Y?8+yA&VNYIlJp`rbGpAV9- z9Z~PvJmm~)kkB1$_GHAYF`wO$u&pTFZ`aGAyXSm9IC?^lL}=)qKHYs*nr?l+sM9j7 zDBU;M>w^S684((~U;EANe2|1~Md|*>-mXZ{lM$hzdn|SLnaV-JwxV<&XYU^*=*fuC z(7mF%`%D@nY%5ClqxODIf}V^B4c+sqyU(OS!nUGxUu_?+NYIlJp`m+sb@!PxNZ3}C z?ho$cE(v-vA~bXlvhF^U1_|4W(tXYz^Xq%nW`drK2o2pCt-H^pLBh78bicOeuI2kh z?a7Eiqt3NV%eKq$m=~SY#>AGZN+?}>G9onEu{xoYV@1NYqI48K`rXzbK~F}6MytW9 zLBh78RGWWs?M|Nu)k-QsPez1BYl&->gM@8Gsa4+b7py^oo{R{M)}yKh3EPTN?|R(5 ztwDmGj0lZ3GE@x`wiTsO;!}UW>GPmQpGwe^5uwpWxCLQaQ5x-Db;KGZ=*fuCXd`vi zAYofk8nr+73Tu#{CnG|m%{WzqgzboW*XH7jtU*FEnLQaXYs}|^By1~6vuH0zn`>*X zMo;LG2#r$m;r*gc%e11j8tC;wf}V^BjZ%Zd`$e6WX+>#O)7upZdNLw3+KQ}}oP=#f zX?5272MKyIA~Z^m8s0DJv`i~XtIXcdNzjuKp;1PL;r*gc%e11jTJGZ&33@UjG}=nP zj&LMwD@v>WKJJpBCnG|mov~C661Ekkvlq`2%lC`glM$iO&eiIS!?bKG%4cD5K1hO| zj0lZ(2C2DrrTuwdNwuvg?a%k?yCmqzh|u6}9|_xv(w=(1PECTIj0lZ(Mt?-*AYofk z+Ee#6^3{q2JsA-i?aIWiG)UN1l=js7z5xk(G9onE6_%<&!nUHcr{4EJNYIlJq0z1s zRSgoh6{S7(zK=tKo{R{McEzh|kg%;N?Wy0&7O>yHRiKB61Ekk`|Wx;+O=2Zs(xL*dqR&yXq1xA z`-4o&wxV>eU#|}m^khV6lp37(2T9mglYUBy1~6_g?n?L4ux) z2#wOC=KVnuwiTs&NP9mgK~F}6Mj09A{Xr786{UM&`*=lyo{R{MGQ!RKgCuM#O84~k zahC)=84()X?IU4ZQM#MC&mSb{$%xP>GtRs}NW!+F^c8r|UE}^BJsB}*)VY>~ZI`28 z-)*_7gwnMqBSM3_eI#rvN=KnzrzSy9MubMI!MZLXVOvqEOY%5BmMBm3D zK~F}6MjPR(1_|4W(rD*Bq}7T9JsA-iZKSRmBy1~6qqg_L>O82~pc3?CL}+lgkA&@r zI%>yzdgJ>=HIvzs5wix)2RmU}QJO`2Ik-PKdV(eq8f^toOHRVJqO=<5^+AH3j0lZV zgY*6%3EPU&s;0Lq67*z5Xq1*X?+=o&tthR|djB9nPez1B=~46kAPL)w(kip}a}xAq zL};`Xa;*;%wiTt-av!fq(326N(N_9(gd<^FQCju)ahC)=84()X?IU4ZQ966^EHUm6 z(vuOP(ayZ;j6=eGR*H6RgYEQQ(CqarT(X092z9($%xQs_tw^P zH4?TJrT(YUC^SgWlM$iO?)a@5By1~6{ZFH6Xpo>MBSNFyxxA}+kc4eTssCwq2n`bS zWJGARJFu$;3EPTN|I;iN8YJk+h|p+vl2;89wiTuRr`b9*NYIlJq0#P$uNow5D@y%O ztB%khK~F}6hW6*RVp4sOu&pTdKdqiZg9JSp5gP3Yg{ncqwxYBS)haMFNYIlJv&Q`V zAPL)w(t5g=LwC<QdVP?fCnG{b_iJlCDh(306{Yi= z-mXZ{lM$hzdn~mcl?Dmhiqd&n?;j-S$%xR#3d zr9r~BqIBNe$14)_WJGA_-d(LOr9r~BqICY>$6XTiWJGA_9%QXYr9r~BqI9*Q&mSb{ z$%xRi(jZ}5QM&5lxodoWke-YfH0oSS!nVtyRbU&hB3G4Ay7pv5Xta`_P|C3) zVOvo;3R(q*1_^pHA~aeJRt*xi6{XtLDljxi(326N(OTkK%riMubKi8L9>e+ltaCp;cgLkf0|cLZgjvRfB|WMQOCtDljxi z(326N(MIa3LBh78G-_)V7#bw#$%xQsGfveYVOvp}eYENf4HEQZ#H=wtKS;v1qBM*4 zagVOvpJ)%12nf}V^BjnWe5=LbpH zR+Ls}y?>CPCnG|m^r-pyK@zqVrB!C{=OpOKh|nk_!~Fap3EPU&YPpYBBco+S|)pDOp(e&*SA&9EY2 zTT##c<(oFYaHZei;%QdoV;@qH=q!YFk^@5YWvN`v>_qTG87(GFg z2#wD^`@9oMOR2|-gl$Fr#7q9~=CA+C8YJk+h|sv<+{^XOv#LSDc0{epTJ!_093)E7 zXHQ1V8uQyiN!V7@yDwYq^l}u9nHW8xMy($rS*8cB0*0^ghmSe z)5l#B^khV6s7Re00w#)GoFY&uSn?@y+Zuf*9iO^^zujgtcY%5Af;RPr8-Jc}r$%xQsHCQ!B z*j7~3rr*m+f}V^Bjn)$Dnwo@dMX6O@_~Ey=F_8p484((-M^z0HwiTt`b?gn-^m$Od zwi5JYL};{;VL_OVs9Wv))E%rrLL-hn84+|F;i?7++lta?_v~N3y3d0eMJq9SLXSjf zw2^v2m{ycV?Qg%UHAv8t5uwp$oT@>>c0_6Ru?C5l$-Q4+QlrCGF>qs_H7 zSEDC#LLxLu$+c!!5T+HS)j+Qg67*z5Xtb3~)gWOzqQ1Ow>shTxXoX}?Mg(12qSkO# zgM@8GX?5272Z_-WdL%+ay~#a_gl$D>mD&3_33@UjG};QemV<dG9om} z2&Z#{Iwq2^tthSf`?yPjo{R_$wW%@>Rt*xi6{WM6K1-0GCnG}RWpS=nXB-l?BZ}v6 zBzSh05kZ$(ZT$`HdlReG8#bq%eMuXa!dBE>?)rw!r{4Xl_B)Buvm`=8CD#a4`t^#0 zZACr%m*23t>OPk?4HEQZL}6!)2v>uWlM7=*fuCSd}LSu50Im zBy20{*c&d}Tyf!Rng$7aG9olukJ{C-B4Jxm7k>Ei&9T4v+NME*o{R{MvJPEqhL#2i z+Y$A~&EG!pbxniBYSld%5%iCi{`b!Le6SOy74?FX{&4fwFIt1d=n0xcXta^KmV<i2CEwuB<_#TtA;Z88K^I)ifp&wiWe? zC;th`Q8Z>^^n@OX&`|#?y-MYnNZ3}?FI@R1)CUQAG9ole4IXKAK9R5;QCFf}kyx#| zCnJK^IaF)AZycS+Eb5uu?rrIw<0MZ&hC{`#+W zF@KPtCnG{bedCqw`9Tu4BkE7fvGUwSVzug?jOZHAEq%R|qx^Nkw##wJZC}~O5^0!F zy4@2riO^^zuWJSpwiTtL@ZQUQw`q`|CnG|m)nL^iVOvpAo3CgZB zNZ3}CTIGkn|9>_O67*z5XtW+xHAvW2lzP|G9`!$(1_^pHA~bYuSF1~vgM{sfx^i>r z^zx=bLL-hn84+|F;i?7++lta?_x4Y|tZ9%KJ)uV;G}=gAHAvW2lt%5-f5RFi=*fuC zXfsaLAYnVAH2YYCM9gI2$%t7)b8S0TOe<_fX%_9}Xmf2PM$eK6jZ$))5B9W7D@v<@ zULPdr$%xP>HK?^u%@qmT5%tEo^{iGTv_f*b%7~y#OI*9{lCZ5Pt#>A{ZAHau+2a)ndNLw3+DgBUi6m?*N~``p?vkJ< zBSNE$)H=th8YFBhN@p*9mLNe-MudjWygv2Jn4?J8jwqhPk>J@~MhqHPX-pLHCl`FF zjZ0y>98dVio7?YAqY_HDdzM6Kw2~i@0twrS(owko4}H05kf0|cLW5^_By1~6wfQF( ze5GlSpeG|jqqW3cm4k$BMX6QZ=G)T~s5uwp~RMjA1TT$v=zkT^vn+6GbG9onE z$WS#%*p8?-ZeF`y?Zmz_35_`RWJJ(ygsU1PY%5Bm-M78K8YD(f=#dDGHd0p&61Ekk zQTvDf#2O^%$%xQsGfveYVLPJ!c=M5~twBQbpgkEeYs_bNBy1~6vuH0zn`@P;dUn@6 zp+_P#O38=wK@(0_QCbc3`XE71MubMG!Qp(+X_=0wE9cfz=fRoK3d!v%BZ4k1QERwb zauT)`rPW#QA0$Rk=#dDG(xZm+L8oO}QCem8eolg(j0lY~GH6X*%R$1nqO@A>;}r>d zG9om1c1OatqO|Jo<1Pt$G9om}NIjenIxW+R(%DO&B}mYd5uwq}yfouXBy302pJMJJ zp))$qY8lZr$~otJK4`+U%W>!X-_*ukX_!#D-4l8wLZg+ut{F(!R+Nsy$=Cf;(;z`l zMuY~>?nu~HRMh4_HVqQ=WJGARD-&zYgCuM#O0Dt-&-#a^L4ux)2#waGss;($ic;_T z=+kd(8YJk+h|p+PimC<)+Yxo;=IG!1V$&d@5yzg42)d1lRfB|WMQOAG;f{f!B5xwMStg_-`hF*xBh-}#Yf(^`QO+6``Om-DChI zu`P{T{ro33&-&`eo5nVRQMN;a{evFc(op*P|FT!BZ3Lrihla|aoN0EZ$9AOqv9i|w zyQZ;?(9!HsVTXq5LPuB{jtWmFRNtzf(A!2Z%66or-FCGtDbQnE>8eGl&4tD`f>E|Z zLoHn`UK;e+j&$Eu+SR9<#x_FtruC?>XARxU*^U)Go%n&fzXRnc8Y#gj+w-x~*O=SRWdx&aheoNvBd&9LY{#*B3tG%JVzpva*r8Ec;;!4Sqr%gPX>|ns zV;jLJ+mTY~Q98S;$BG`?D#us<+ndnOw-Jo89U7$!yXsYHSM=DH#*hB#A7Q-OMli~D zXq39xRj-l;J+`Is{crd~jJw+iM%fOH(n56iXVsv`wlx0cX>XiohB~&V1fy(+hVH)h zj6;uYX=qiW9v1dCVvGu6(5PpSjtWmtS9n&y*{=P zjItdX8gtdFq(P7EI94A+yV^!*<E|Zqtu1Y4eBULk8Npa9jcxX z<=93r%64dIrKDb^V?~c`rK@$QdO~PyBN$~nG)ha?nOB{0=&>E?#u-`I+X$^g`)t|I z;o@5m>QyR-qe8tC(o=s4jS@B~w)|(Uw^-lyHK(5V&tLtP^8DueHn&=xSnb1y{(AGv zkGi1R5vy_ zQFHa!&)t3VQ+IoH&F_&*j@>-s&p%%6%P+dq=Czl+rI({b>u*|r`$wL?`INX(``ITl8J-et73EUvWY&`6LBt&_m+9Uq5an0w~0< zzUEL_8O70k#(fX(oPXB!vqpY&FMR5=H#gq%^EFrJU-_)f&5!?VwV!gvv*x1^*$I(p zU2?WLeA)x+Q55lKhr<@(x@j2-aP9BzsI>k*j_kvSP9KTM8hV05&sr%eo)~#wwN;x# zIc9=UdX7a;IEh{mAyJMMJtXv`jhEes7*+SSu!p|5jHR$m(KQ4z; zTIR|g5`LOzslog*%FpI33Ew>~&&3ygp^hc8edqd;pohe#kNU#q@%MRqa;!)&%6H%| zHRvJnynp%p<~RO(Rv#o7xfc&yM~{_7NKX1hB|N9G?ar;dh*F_Y}DYG;pgt8 z!7*ke=po@J>hf0N5sp#Orr(ydtD;!?$JN#2r?z~ozU9~cPeL%t&tUCO=(syA5`G?Q zSq>76;z(4F)f7i;T92N1YD?+*>8hm$2}W%n;dn&-jH1%reso7qJfkSW&k`B!g zK!Ez4mK34cL!sll`u6C)wkt;Q zh>RtthlIc4n`^k0Fp8~m)bQ6Ym6pF!DO=};PH8*AD1WPS$kn9LM_;CN&yj}v-Q)l1 z!JD)0aYAyem=k~3a{pX0CnWsE${|;!K+~E8qx}8JfvDy1S1RREl8EsTU(yRSxQ zEP2&&@2%(O8kN59G4HPSNXT>fC;p&%M4WQ-W%C(*eq}-$_K?uHa{vGT4T%N`M(L6ZkkCl<^vnNOqCtXD8n6EMQ}z&(R{+2A?CWY;in{k-hOLx*441jGhlKQ;QYA|I z`inJ#2}ZG=A~ybwnKL7F6pp;|eM!lg7Nc1IHTB6FYz>;#PXFRx)^wRt#G0UogvR^} z4qtlJjn(ea)ZDxyoCKa%B$*2AM~*zA-#OOVp?O=V>bWx zbN?|px~o<9kkC=^h&tvcW@`6A&8T_1Vp^&jkJ{9pHHx9@K0Q|?q_^lF^;nT$ z6t8%X8uXA*`P_rI6O7Uf=l(wuJXSnDBJ#0>X=$!?pI~lB4SGmuy^{A@5{zOFM-6&N zNYCTSc7johl25^@&Y!dSqnA9Ot_ROQ>$#h&jtN^kCX2Obp+|F{SOfBC%SXzd3Z;cXy43jpbmJG#>RI?zV;Ko}RAsKKC>Cy9I(#D&LtG-ZvrW z(Xl#w^?hp8!E!}Hb@Q{g4|;j5Tna)lG{PI}Ua=h*ES#zuYhu57w_X(x6=(V$kJtRK#x~I?mahWR}YSz1p+leu%?@f*bYf8t;ePXQH&csUJ z?T3Ww#{IF!s~k*=QECf$Kd0xKM?GyGKbX>X4HB!>)3%IoV_H2*zx${!HM*x0((@R+ zonRDuK_#Z(%5Dbsoz*h>3h6nUM;?7+Uy%*OS+D-~cJ2N-o6Q4`skX+%eE(eIm7_GO zJ>daI=R{X%%JNzyA`k&BnX*C<%?Tp*hbT#IG)7O7( z*O*Jrv=sHYD{lXqfS)HTwQGfL%iZuc)oPq)m8H{5oMMo+6p@hFTMJSKHk zyJ0n#yrP(N_3 z)v>*`3=u=yopYse(5+n~+?f~LrIuWMB`4@1QS>*5ZwPwMRWV}R?P>KW&AZkc33+^n zh|)d%$Y<*Dk@lkGvqtxHLOJXyb(QhlnNjJ{ts3-@&@uGAEnPt+Cox9#nw^PB1Zz#R zfk%VwHAoK$wHS{?vqmu@SFVpS>YRBT8ws{PX}E>6d?P^*i8^1k-nE@zl-l$#UNtOQ zyFHo>Ji<|Xy9S9mtEFSfm{ysiT9khGF)utP^p*KX{9fF7^ukXczjOYTxC^O7$K46^ zkoe2XkKg&Nr@ptQH0Fvq(HHCWz4)!UlFXX_px#VyAn@8_F>~^>la3Gxb=RWm^c3$-H*VJ@H54oBNdPtP3A|+RG z)FVI66$wV&{>M+C~_?Qlqc253=Qt8uXA*FYq|FonX}V z{=qhS_xGH<^XOlV_R2OrYS2UCvNKQKx#5(owUZd5PA*?$%Lvv7kF>@|k7Hx5=pm8T zc|oT&2}Y@fdS)0k=phj;G47zvLwMM{qCbM=4$lxbfq_(8#Jtp)JTg_DqntXprh!KOh?zp zM@RiLKNfe;j=7?TMAQxL#+`zj)@pH2zWC4Q7JmLqUr=rJm79MI#9R(~)bdS4uLUt{ z>?KyKh*BTS%c1-_UA27YaCwm^$rC$4qdnCsVNc3};gT!j3 zQ6gvnZQM1%C?1iK7(G2*jbqN?c7jpEaRV}~`Gk|6(kd&>xyAJJ_Krl!?IEFOzw~_8 z@+?*D#{{F;#;U>;I^)qL!L>xslV>#_T}EwhyY!IY%3#(gIg4Dmg)=H`?Um3MHN7LP zFJF3>U3X^p>vOY8(a`gCe)dh@zV@EEzESPn_a3iY>1)Zphe2O8?)OO?voqXfQF5fe zX{~Pt`>qguquBS9XdKIPr7t-89uIvn(i$py>T;946XEgt*JhIq*tpwHP|q% zMZ1TDYSwr1j2a}ysH1ik_x06WjdkAZSzp@BHP|xr?NYZ&*3+0PdPwN&s*5{oYOY8y zitTOIm~?d6?-b>`g;=vQF>AQ}kdU75FWOEpN@eoBUzM1Go7O|WEA{WY!p0WURbrLl zT&cyFQ2!q^8Z;7&(l^|Pa?H7+M_-fou{v0;Na%a_9_@N5YHPGjr#)k^lo7rk|UB3r-tPtRJ?(}}0v zZ!Kf3jzUKI0Zz7T|<)DXz zjzWIrjs&B0)Q9VdQ;1A!)s#J|L8q&l&Cej|A)(fjmz)Hn*m_!_>wl&-JtUrX#u+77 zS$&XT6x;Nu!8ZE5Gk<*UD@^kPlXJ5~|Jo8Zy&j6#GppbY!mP%5|%w>l$S1 z83}qwsAk<3wiArfyHXZA4U@)1jsQBME-golQG*^5sv95a?F6G#|9QL8xuD-!qNCvR zXr0;lT)k>c_1{tsdPvCj8FIvye+#uF9Hm(^KclCI>B{yQ@~E+waFo^&-cg>3VoYm# zn6B)_Tsviiqu6go4SJYv+DdA!NHB_{(yUQ)#k$of;n9b!XC|r!JtU;zacn!mDCN+5 z79*i{rB$-lZP8+mskV-S@4p-gdPt~dwZ>Xr_aVV3{eIj7Zo7rBhlJXK)^xds2}Vg{ zzLJiD#LQ_A2_AI-r6n>gM(Ouko#R|zX|3mD{M;^|YUOjDGf|B4Of{bF zC87J4hG(iv`uZD*G3qg!#oMeZq0!hL61qz-*C4?tjk$i4R?SZPXIiTd=vt-vf%>)f zBxUQ|XV91ldPry-(O%xNM``BLE~q@31GNKxa19b#HEVBusli+^N^5KFtuG0kb?H8a z@VslI`xtDOy6qo{FR z`>Bdz`FgzC6+I-Rp}pLt1_?&7o}vKd-$@!;|NHppe1perI94rdLD)k=^`ZMsmbsFK z2}T|4=#o(V>wbf!2Ge2`Yj!TV3cqGe>F8^muWGIyL{kGE2%j_4~f<4sGZ|Zg~k+0y6^Sh&*fkawO8me)!3P!hXmj7 z8L5|l3#DfPdRmNT&i&AX>(ONnXANbn-euwXAfapTXa7>r z+X+VL+WQ;7BO~b1RrxPn7jz^s<0!VVu^eN&y3EkXzxSsSQ*fG{ zkJ|D3+BB;5H}oWL>@ARp?jfPJo4*l=1f$gQ{RX1Qj|8N_{HpCb>R`u;g!;{ptCGI{ z#-lq%_3}k*{5zJMghudw+&VK7V^lxtHGZ-NkBP>TUTX)*6$y=Fc`IRkFp8sgFNKa3 zJtQ=ux*cyP7?sWjrSv*h{Z3NeH5>Qn_>Rr4;(KwzLqh9Qt@fAecBaKB{qE~QT|v2` zhlI|}^DAB?7^UBRm1?PB4~e+5Dz3?GCm1CSUjwSdRQ@ghi*ndQLic|88ek>bKO?~? z-I3;$W}<5Bc~@zu1Ue`LBANizt8PY#SaD zvhzBZ$Mx|w7ky&$psPMv)7_tNS|mj3|1Vo2(_$2J8wIHU*8ZV$z%SIa^loCkD_802 z+JJK#u_ovtp*O$lI4*NVf>AoM%Gp3nI=b-{wy#u=zWS!`uqsMVFXy?E$H&UwK8tkY zYiWZSsTn!!&hY#(J^)YLZ7^C8gl}n8wSMA%7dvn+_RR2>( zYUISdp!6<(raeuP4PpRiC?(yoL zPN;5NrXH`7Gc87`{yqDQgvJkjV?FX4UuFN-^Wy}?$G#>XOQiv(2vNwVJ zM*oOel;!IRdrMA2v)wQcHf+olqsIBFtCT%2%y%R-Kjvczi7{%=JUHh{t=+4;yH0B-9o@^!@*{(xV0mMycgL?NR?DAx6)Yn@gvc|0{B(Z(*BI+kN{dUzTVvSBz52 zKm9i{LN(Zr;u~iTjYN4lqLsw6L>d#Xy3eIGCmK;tJNwmRt|qk-eINd`voEP0wMu>Q zNc~(j`>A)oY9z{Gjy0S;Bs3GLoyCaJYNTo~Ek>y=IEO912uOn-5>fwq%27~#Z=xR) zjq`39<1w673PBHvI9Aard%QGAFiJ<-Eq^8^5j^hFxZ=Xs)Z@c?nu%hBhVStqq4FL3 zo39;@?t&Pj-njYOC%&!|B}e*;8RxBEwCBn>O7pz>{ZNCI7(Ja(zsYk&f>Er^nw|E~ zw5ErIda#e%c7jpcTZvZQr=1;rO*5SP9cy;fpofI!^Sqyv7^8X*9yQp0w0iM~%9KWe z9uivnx;Jkp7^Rfl-j+o7^mL`?{=c1I6i1?w;P=%cCvj!!DQCRC@S#0r@!3y*MI6KyBPDBYujb~Od3 zTy+l#UB$EZsIljJKIQ6ZJVCDOjD6(mOzeNaGZVU2me)DcVw8Sg)L@Yc4SPuFT4LUI zxvS56;54py7qFK?8uXCh-E`XtMkyulm@Wx>NXYi@`xA~@ya~Et@m@~9*Olq&&42m3 zShcUEeJJ%#?T~5TOZN7i2JHbmN_Q!k);0Zp7T!xTt+i9ET_vTj?rqG$z%DdB2nH;s)&6tlB^RBxpw72FQ=H*}sN$3s>?Sam@nl(r;ie+lS^*`~| zQ16V8ke+r*a}5)W+J3Bfe6;82bhjTXdPr#3H!nE}M(Owb=+Z+%daj%CSdm~9+w^uq zdyd)>*Adk{0NPt0j_#z9fo)g!FKFjdQ3tC*61syxyO@JU$=+D!jM7~L+UuN&k|X_1 z<-5WUojodt)8$c**!Va4hkLE|gS9)Zba@O%f*umu57vDFbFLZ|yM3-(M)63G8oFCU zcRMI8-F2k9Ib^fnj0B@}AC~Fu1U)2lbQg7A#G*c24o0bN++xOD(W5%|@uBue&_hD) z&2_V#U=+vWnV3`#wjY&T_e%Nbdc>HCVvH@3gpRuI=9=rgq_4k`VAS@ONDm3M1?MnQ zkAKHqWJa+U)Y!=c`-EDedo8si)&xBy)bc%dZ6_GTnP?>VWozC^thG zY0W1Qc>lKOyawqZp*8$16O2+yuA8wO^pKE!Fv3wv$#t{Tu!rf&_V4=>j*^D!W=Yt? zbY=VZ{fQpc?~E7;ok#he38t&FyJ1&f*rYnwd9C+rbRO;99-SL>y@;+*J^!$W1oaf@ zzc^zt!6<3?xYg(>m>}#SA=|$@ef@VyIBIc@GX)ofTL#mW?cXDI8{sHv46S|8u!rf& z_U}s#dl<#@#F3zf#P&PlNiZtCzrBc+Z#9;$$NAhz@8j_5Oi#PHX2)FVJt$tW=nW@c z`{%t#?$pZbpJ05_(^ekMu}TUGI^)_3vvA)SiiA#8bc4AffumSC&kRQL0VX&8$&#MUPsEYm+I>#3END)Ix`I z&W4TUV3c~-V%=VIMUQ%|&maz#D-s$p291)w{>EG}YJ1zIhlEDgyyPSp#eNgnssEN- zu@`9+bv-ksh&4eE360=xW7`QvXP%Un4vMsY?R30~jfH3yybIi-=HhXl{tw-by~O1_I^N!UX|wtwHBaMbul;?7KK zdYCTX7CgsK>QQ{#Y`lv%-b1cumwd-fB}%mZ%Bl|@64D!p0QL}!Qc5mUBpyg;*h7M4 zYRLy!b49|oG=@5#s9_J&mF?e`8ulknP|1Cmbb>yzSD% zbY&lmaFkN=?)x%V_Ap)9{(XPKQIXqhkDeZ;8+r#Jyz{4&yhFFll|4*XwtpW9jh6Q4 zn!di$t=6X<0ex$D*%EcNU*GtZC$7Ccx!Ov}Z#mko!F2a0oE8b?P~R|K=89=Cin$$g z#k}i!qTVl}beYmf&_hDkFZFJd{d2`AT`$#FeV2r;O*<`Jb#|^auK0+IxuS^WLx`dG1Vjs!gX^YR)y>5hWhG}?j5=7!NvOp*hhwgo7NgXTebh&SU#Q@hJ(OFoQAUCu5?b%x zGQlXNaI86f9HiC zzajZvDm_eBw%_+WYV0K(#kXmX1U*bw*L-x1W;sWZV3e*g>B`ZP7{83(zlFZoF=<&F z_dodcblq9yGqSN9Op8(aJwL~xhlK2d5sp$yK6_c_${waG+rRHmI7%8mds!0pFkRXH zeSgAH(#ZQcJxo{j!3al1IkIycdYEqL9fa`6pp@K$mnFA{>B{!+`xB0mhI{amu!rf& z_V4=>j?&$R{+97b(8F}Me}TBnY~?%W_o~+u^sV1Zo*1_1yhqVPLT^UAWr9&k$$e!k z2R$TYAB=F6QgUBeYS_bcW&8L22}eo8ePv15!*pf)_x%Y+NyB|*N!Y`5W&8L22}eaa zvK~bb(+$0Y5blFY$$e#+D|?u(Z2!JL;V5aiuPh0Bn67O9zCYn8eouTP=o!=9_SI=! zG57hau9*7_TUT+cH)_yBB6c0JGkOw?($0pjAdDLHX!pd|9GKEb&_hDIGWj_t2}bE^ zq|e(%4eh=;zp-~0rPcMT{8-ULLi>h3(zC{-mA>9vt2gRu#iAT~wWQzVn^!U=T7U62 zU3*Bdd=abgjBwtW+nEql-&O1=rn~)EF)c=E{g$8C(i6LVac0Vtw&#k3b{caHro|}j zU=DR&j+6f4%C^rM)vkOFsH5OMAF=UoxswAP5^B@FVzHfIl=_OVYm5Z*tNmKHaF%Z* z=pmuKV)w4?1f$psW@6H@Qmgir6t#BeUE2AvqKAYu@?%AUQOcp~rsk^TNPp!mX*h}+ zube~HQ^dxg?V-jUzF7I>Gysw-by~O8L0~JtSlwjBu1v@~VHCD|?u(Z2!JL;V5Z%)xRX{ zVY;&Y`~HNZq~TTnlCX#A%J%R36ONLGSN%)E9;PeXzwb{tD$0?a8_>gaL+>Dj&nA?T zM~r2z>|wgH{rmoeqomi0CVGq-l?cet&depYBRO-GV&1M=I zn6B>i(abilcbm|(*1B1HUGf|{^yH0pv1IFfCm&1bA)#^XmI+2FCHMKUIlCX#A%J%R36ONKb@AI9} zllR@jbY&lmaFou#b(XXo8R%iUI=|7G*plE=<9wTdMj{`#UJ9+R=pmt}Qf`@Glv46> zTWZ)tLbiY3pKugM)Ft5~%5-J>_x%Y+Nkc2x<B`OtzEy#5CJ>PyU3y69IgMK; z7^Rea+{TjALqhh!2uCR;AGf83Jxo`&f8U>Qlr-|AOAphPofFz6JNoEpZ=ub(D$)9jw|MBQr}C)Q{LNZD8K^In&O`u(pofIog6T*+ zkda`No?X-owFB7L*MvSY11B6bV9>@f`rPauLaM? zs-&;Kkzf?-KVswG7#XZVLL;AZxSe2B+G|^``Z3Wrm|V|1>Z1ldB=jvIx3TR6qx2=B ze1y}}q#jH3l&Qy$gVhI#_}bAAC-uQGQLSBH?{)v^N4=M1tPc|L6*XuyXe1bwj){|6 z3G=IC(^$gDW3J znHHni-o{*wZ)xpskyJ|gDtz>GLTkHQCK#oZyuKcDMGpzt2O}J%l=9UpJxo{j!3akw zrMySc!*pdIjBu1v@|eFoR`xJm+5UZh!cltmU0=YR$M%NB7uoD#x?DNe;3<%4SL3F7pOtfH2LSNigJr7zoO7E6Lrqy($rGDR6ZPkaa`^~wUHRvI6_BY>p=j>yzy9I(# z54rGG|BteFf!gjW%X61N#Y3?YkhB9FqT~4wZwTASK2G2o8o=kdwqi5<&L7=QHm$ulcQK z{rUS3g@^BXu6fV%oNKN5u66j{2Sk~cT+OO0u{~n>%FHdy_Y}rT^kxE z7{!)dG-j1tZ%)zpR*nAPDYuuqz)_=q!{fTm=^=6YEw}IT+9koL%WuA8cls^SnoF*V zG4IFTaF@fEeJpy$$<|dT&iww*IlTDN7&oH^(_)m~zWKoqfGG8(fAjv!?tk0P^{%L}>lbLeN7(wXS<+>)Iv3sHo`}kCD1H=pmt6*Im7}2Fo!`w=Lyh4o8jA z(+Q>Iv9b`e>WT!T*xweS7-LT)p&Ie{-zFHvURjAbIIU{&T`JXyzi=gcyRPUV@w~G? zv&;Jxi81QaJNM(Gx#}K`3D1K}DN5jS&_hC_E1!2sFp9lr)QIu%=GK4ia`==}Vx;Qt zo>9kgjGj(tH0R@-1f$ZKdR8wP=ZsJ9oGX=2Z@OLg_R-S`waq2Zddr;ed83I<2E$(w%&+Na%Ese#^GjV6GUYGfVpY z+M3W=DE;b89!2T*WX{#9m(<#ohCL*tr(dA0HRw?}^!vV(*C3%f)NlRP8q5`=)HeD> z;F_REZLZ&@o_wxIsK4oVs*A=Py=&exSBy%>V69zxNT}y~1V`%DAi*e({~9}+;B25% z9nL#bidYl$kkF|P*ISL9GlEf1{JU@3UHG80dR+xjW(Iml=;?Caf+QHF=gxUAQIyBC zPo${TR6fsREkpIc#`%hbPs1#2zLbM$F^aQmBp%4TXMS~}*yDrcYsm*V)D;PxrCyD} zS@SN_Vid1lM-4{lRJUh_ZGs*WPk-9?FLTVOL4r}djvfhmNJuZA;Yct_)L9HgY39>O zjx|A#W;mVURuoejb43pc&0RXfy=au0)xVe%ohwGEeExgH#(%~bw1p;H!L%5qwOyya*91M)lM_9!|5zSdx_7^T0v zzpYDd4+-s}eE)KrV3cUz{TvB;R1Tf=cFCB|hUQ)OrN@2ZfxD+X;8nfkC0hUH zz2;ZXeVTVYCu%-+jYO!zMR2a=Y@l4NMpPx}A+frLT%z@_+z}qqic=_RHRaahF=FFC z=RHfvlCLxxrn?_KT@tE=eAJR))GAlAbHy5!hI`+tc9&eyLqaXc<~k2|d$sN((WoUy)$cwg#UYD2IJl{M_B|yyT(DzFivjkdR)dmwdHcnP8Moy+1(j$3A*R$D8Z;-KL6)-7hL|;Ny$(9 zv!C02;)lPcc`hrzssGv~S9!@<+G*;9Qu+@MdPt%{f>FxVXFih=^r#%i-tu+-2e~4l zdb{o7ufLOAF)D4r))Sw(yYklP)%vxxd${Juq3@Px{Zrq4=F+b|e)^9uJwwD$yK@B! z!Kj;F{i93XS404XpohfYy!xW0-db?|uaRKXo6op#qdiz!zdJ$wnB#xcpoc`MmHOTW z(c1*0IIoNZp9zXM<5AyG+gaK}?KUj-?cLJ}T5>f9G7^kpt&h2)hlJ`-U({MO zmRyk-qk8YD!E+$k?#X>8e=kB5EYLdc_YD<+=w z(EGNh3(wu{9(vmNq+yOWk8|2b)7{P$bE0|ooX`7o&Ebi2<@}PUE8H#9n5$BjSUF8F zO6$rOecs&?f*!3=4|v+$Yt+f*ibP!#Z~1~mV@#{8oGpsA-kPHRSCqr;!E~kftxx!( z4Gj~FQu&^6?L8BMp1N}0a_^<&PH8(=B-A$NzTwnFgC%5?`adX&R3k&KYMxwjdq}9{o{3s;{jc$k*BI63u?P)r z-YZ?b?MW@Ddh`6j@{Jm!rxTh{^Ik%NQLObbSFA;?I37hzX**XW>S~vc^D(WmCblU3 z-L<}G%xVv&B@NF$DN)c^ahw(jl`o&+m=>ez`gn8}t+}E{HR_p~DJ|t#<%)#bM!yA$ zzR;Pm9Ai`;X+2&gf5+Po4|Q5rX}#}j&py=ISJ^-PBab=M`N6fuA6@;3!(aH3cUR9P z-~EWv8{^!{E06CEb#8l2T=u`tJp9Sa#i+1CU;B&2=OFCIDLRqKibqn`iK zM;t!$>`a5@VBSSsc3oBudPscY<-0?jUSF4k#2EF+Qg0bCP2EG{#V^{ei8*?ECm6L| za(YNePrnVw%i&sN6l;CyS2b7keB`fo<%CF_*kfNNXEeeQkUQl_ySB*v)6u3NB{yxdh=JS3jDJ8xrr zkYLn3zwf+_7StPJeG*Xhqu&FlepGMzWx=|xI2%0ng=Zh?%(BppaL%GP5-j1*6@%)x0j=(S5iDdnS<1f$;kq3=3;_&u_7uk?^m+vIa1 z2}Y^?^=qVcd(fkv=vHG&V_nfhLZiU#zfCae*s*gD^?Q(YuDAkdJo+3m=f_cl9un-K z+XSODOXPJ$4~gyG&K~!`KRM?l)YQ?34a6Ku^Il`yX=#>lu2|D!uIM45-ACT9NHB_X*QmkOAm})&`1{{< z=HbV_=g29&QkHp74~c31SBH0ek54)_l}gY<;;pZJ_~BDu{0B+x(nCV_@GA((RE?vA zqt1Q*!w&!AL79f%b*;A5cZD34YDi{J4~c1dSea2X4HAqxajx`M4dqHX^chjVd3@-J zwdC~Z_YH2f_)Wu+_Ne8chr~30hE&0e?)v$-eG#$fA z?JTJ$(j&sV%#+tJp)%#y226`levAFk6HDe|FY1*{vxI+Xqfs!lhl^52lszOgW8D3U z8~e;K2NGk@1f!&(H}@>LT8J2TH&u_nAEqevw}Du4MGpyoWo*$%2}UWUCATeF{}toI z9ugW|L&*mX6O7_-njoQGf?Cx4_{-vA|PMk%GGoq&vemxT84 z!=7PikDgYK;$8w0rOowgK%X$wuK|4~S?AvSQ>V_v8G3t2D5d-)Ak$)$zC^n^30S1& zy}r%pbL{$>qtBabjQ_F2&6Kt^NT^2gbKy*DjJi+#j@vT(%r1vY=(O|=X6H(^;1mC2uIL$wdvBDS zgudtO`ca#^-m1ouD|*yRe6pJ0{0nd;X|Fk9wsE_2bnTENJX3ohwG^o5=Y%r$^sJ_FO{k?Oc)2 zmx1${nrShLv)!n{8CitenRDex&_hBw9QxH9+_)NyQGLc3H8^TXs1Dupw+TjZCK?Id z2h)A4m;v6o(|t1Ax*N9448mr$x$bc2x?CRJYt?nRY`qU)H8WI#QM#Y2doi1YWXf+w zds-v$j-BrC47pkny5sC9J!Q~+r-7)sqDS|>b$9#Zb44QFkZ?p}l`BT+O$e*Hs>JBg zn-?NowUcvL0+)Y!^3&5|lNa#+aTXUOWlmI?z8raLkreishxFiR36f5S>0J(6ZDW!+pKzf)gZwrwSONsy(IH~ z^e|nHE+rn6dV4R2db{q}9xYQ>Pzy5eBs9`=PjOvx5{%Ml*1g6xp_X!5YC-2pS1WF( zF<11EP>*ptRbmcq-jf)kSZ`fL`>XCDp+23rISEFMGaofrSL}V9m3sWq`HF;|sp_uh zx^|fsqd2>c8XP&gbLu&mV{;_vA)&jrd9Fw>O80#8F{o=kk5onJKC(*7maVy(BX6;O zxW}pFx>qfNwLX@E9ulf)>unQ^;=D2v%)3hNT&>E{u(9uwP))mhqXyGr6h~Sm=HTM` z!@t|+j+{G#QG*^5s~s{l`u>Aax~HK#6+_=GRJ?n~9un+5HCKxU(_$2Bq!R5v#@Z#Z z-4mG>qu4`74gLFxHx9MEQ*6K`8C-n9t*T|^Bv>2r`MY#q&BsdC24HAsfX|Y^` z9ul0D7L8eLuJ;#eEmUvNn+g3?|BH9u`H1iM`RvUtdRwQX^d3&r`gNP{6jzOszW&X7 zrK>qz8q(8jE&E&E^43S>PhXj?-ZQARSHwyqB#H(-B=jaktrVhLaQ&~5V3bno_q7@` zs~pTP%Mme|2Gdopv^KdMD~*y&0CurRt|bd z=slWw?UG>BcE6&Bg!J70k!t+syeGjZ_UVz(8y&T7s15W+N3A+;kD>22Z0sc@jvf2g z-?DlpJiE7heCS=4+Q&(QxgB#w4+*`?QhPel+XSQZF3VM}3aYzNJ->RRqtoTM88zr3 zp*K3ZOxpybIAe?i`=|)*F5Mm;1tY=HNkTc)db_SG5{y!fXtiF5Ih5wT-VUjiMjpLq zQo8`z9RFjk=pmu@$TjFu3p(#iXjOW1!@4v!D^(1j?*I0i|m z4n5Mg2}bFCnfaL_wv@)8+k-7TYS2SMp3 zH&$wYw=M@gOjq`5W~drR2}hmWh+?{Fo0kHOI{-#;#wdZyzgRzfj$O5&ou5i8J)Z-q z;d4Mi*h50))1Gc!S4@jhQ6`+S7&Ls6gT(eYXIhNX--nfR(6EPu>MbAVOp8%mwQDUc z8vNBSf1S(U4_Bi7$N0-)5_(ICM%z-miw4tTl>Y9PU2E7wLh0*&=Ncv$r5f?ytA=t_ z{(tOOBw{o_wrf=ED8VT9u@>AkbTy$ID8I7x7FyZr!=l#Z&=sAd;{MDuDN5HL{qN3_ zay5E%4=4!rboI|U*>8P2<&iwq^7qcp0k zdms8e40`_M_b8}FT$~a(?r|LKK~N?(CfCNu1y4z*=93VvH?FLK^vd4VV_A zl*9aO3wloOw+5(w{GI_lb;?Ul4++(D{$2wTjM7sezeiy#IX!yv;~Hg3BS8-dJu7l+ zZWD}Bzj9xw#2nnbXWObhoOkwxQG*^58c}&&kzka@quXZG;5bk@dOP=#HWD0BBvfyC zzaqgXo$&BT8#U-5p_X;e-zFHv5j+xXDa{Oi_X_*M5dyuMgyt^4_hp+Hqv9)r%S=57 z7k4@RCMMmpbh>QWQG*^5dNS@ZZ4->*Jhl+C<`T{Tit@}UZO{1&QH*i+AtAkdre<1W z)XDTj5~_v1mh^nZi4?CNV^n<8W@!&Wv&y08bH47^QwHBD;5qBAAc7tedQP<3i&hO1 zjEa+I*o!tHpF9f>3Eg+~Zh6cV(_)nV?w#|Ru!n^14C@Z@P*(*V&r>r>8pDoELbC~b zNa&64`L2&?F-j*hosyET|7K~>L*o8-Jmm2Ce|}5fy$Y$skvH0w(#E;@@twH}kALNN zspETg7eam7*9?vh4HAs<7Xa6_OAiUzZl_V>DB&o7Cvec1Raf*dU4FS>(I`gjMV+qR zn11gMzozvJJ>j+8nRsexkH3(ooM<2HlzO~0=po^+^9|*wxgx?MfYS2UC^joglU3+pgRWhQU{E};T z=l|E2Hcxz&M5WagKwekVblvWX`DK;3==AG%&v^8Iul6=U4~h3a;P~#QZ~GrTS4&+n zzn47g%H8!}bw!P0`J!H3yY!H_-~F%LedJxQ>>3Tzz1LpvjMCrplG8(CnyxIh`-%;X zo>q?%{faO6wL2lyg03I6ziWCd`84%b^H*t3+=6Tm58+LE|u=_$+8OPul)%!w^ z*NBQ-#pwLQ!)tfb)87!KE&r|mJ&dSX1nWdC`0lHIrAD#VM-6&NMDKa|s8P^pbGHYh zSksF}&DB`%*DO7s+6%GL(3tmFdEVKt-Kbrr#i(&?D)IRLdH?ngUA;Tw*uIuf#P5G9 z=9SYgymEXS`$Et|;tPM}w|1}i`|OuU9Gx%w*zwZCqej_#N`97qV=p0b@umBvHJ9*W zj0B^`dA>8{ZMs+iNPO@E`;8H$8OL+2>P&T~-ly{AvnV|z^qzawl2LbJqIe^;5liCHx0VY=$m+FdTQ z&qB~cLbjjjLbbLJ8BegBp9W=&v#si zr+pH3p zk}<6wb#iUabX5-LaI7n)#i((%Ys{<`RLNb7+Ry3!iAI;ol#eKSNN{W}xvCl@#;Dho z`3j@9M8}RyrCmH2^CxaWmqTOFy>H0jk}Z{d^mIaF-aQ|{5rR?L6Y1X8dX1uogl45- zhHFCeo&=*}h0A79?T+*bWSp-^Xm{onuE(pcm=>eB?v4cWE5hps z%Qq7AkWdc25^WQVVvURhJtU^-O&cpG2}X%_O^+Jdx$2vDY7f?%_HS;dk)Vf!?&#%f z6bVLY|CaZ}Bi}MCcWC3y1aVgt`@}i&7Ed$0H!Oc!2&F&l6I)?Mf>F}&&Y%U?|B8Fa zPD?Y7caz%$JtVX%81{*CC`GQU&M2jn*DgIIl)iT#Q2=T1(%BCFbDbw`4A%+D7NLm3P%)uaT}2GqpV<@s6EN(XLC*wA5o9rL(&_IXe&~ zXYmUj*P@;i>XfN-wcUdDkdTH>oDLeLI8hE0jAEaz8I(4RVWqGcg7Nf>K-BreNkdU5E1LhhoIiuK*yMjut{^M3tzj7~8e{*g} zf*um;$L?>Hn1h@5>(Dv1P|{aOCK0v-=W9+DOntLg%X8 zkGBa%>Abc_!AR)juzR1*AiGzx)<=RK67egstgfgo!ZRGpx7KjKBB9*oJ&|cKin(2D zxCKe*WOP2Fm=>d0hoc7TMD5|8$dpEc9ujK*)eKkASZiGlMscJq8nXz#r(IWJJ_&Ym z?~W!R+uDmp%@xyPl>WX=*h6AUwvDzJH}Cz4=04HXDdpMD+SPptf=uI2??$e-A(D5V(qm(OsdudIu zgnEmL^L}!tUP$O26Rw4^988N*dh><8A-3eI)RX?rd)A`L;Wl8cM{N9Ol-%u1LiOg> z+$I>6_LAATaxJRO_06i2Z$T1zkBPonwUoSNZEQhC>D?vzBGj7D+ehqCjXGVP0~$+C z4+*u6%QO=7sLfpqOlc(OA))@3_gxZ<(s=Y(88zt9+lM@_Fr|^8hlGALJ>(lBn67N^qE1XWiaX9V;V7o7U(gM| zm1)?x7iE+*yq{ld*h50Upj-V`W_Amj7^C_xZ5EA6=zfV$G%6=ZgOgKs!w%3F`OjovB_QZsvq+xqa*u!*XyJb&II7%9}*MvPxcXfT5T7}f8W zEgG}hL(fut&XTRB>jbycLKGvO_Sr*1wrl;wgrlTkdrjEGbY;8NPfR#U8n)MjJxo`& zYyHH8qj*iVCLG0dWqYKZm~fOdY_AD>nC|K~adY9y|3?d&U=*+PMh*QI!+RY4lF{w2 z-)rRiD|$$5{|<7{DBlV9?w<6RD|+;M4-@(olCLbb2}bFcPQF4K33~KvDqjgvdnD)~ zpQ4@0Of*^)x1 zD-!ypqp$k5bHynAGBe-xsV_Mv>WR*~`kUKn)S!oiMnPUzBp9X9<+d3$=+UTkJ2Rz` zpofHJjJ#iwU=(MiQG;VmzZdjX3P-_6&_hDM3eB&INH9t*XuYa2htj;~=v2@549AqV zb45a<%QN^k!6=U4O3cB{d*)X?(R0+v<%)!Qem*BMEk<$XTgp*#7P;~`Q0@9^ODW~O zogNZuO{cVI6l44yJ)_v)MuHv^>TmftC&4I==23&c&*txv`CHOT%)yPn^d_>;uJ6%3}uD1N6UdX)PWzhe^Rh%+UTTbwUxSllo1`4SSceO_bKU|NjQ-?s^S zNXYhCinRs_M@hr>Na&3Y{`E5N8c4%e86!at3EA%XCng-Flx(jFdzh~5e0(r1M(OX{ zggqo=yHBrkMZ!_iu)QYiVY;&2r%y~cN*cD;ggs0*^s>Iov=|lT*dpB9Nyv78Tjz>| zqoiSbP1wV9W#@gDX)#KF&k639xKeBFa?6gnqKAZRx9o`tM=2%SYr-C;E88u5V!~0< zu)QYiVY;E0wK>ybRFq?jaGR5m?Ur5ViiD%2VS7#3!*pfmZO*h9rN6I;Svvqd;nlpT zd&qkFruPo`?)i!+*^AY{9uj(vr}rG>ch5~QO3w=Q_JuW}yXSs?nx4eyeHMy}XH%zk zqLe}Z=6yVI4UaTTXf<$35gY#*<* zNqYGg&%Ep*q33w+p-Xr%MuJi7J!`^kPC|OCHeWPMFp9l$)LZ{qx5W2@0VE<{4SaLnCBIxWP2VGq;Y?pI8UQF>yQ z_g#AQEY0JCDQ)M9glcy+1`9g&L`JD?@^Q|Vl7`*{bn?A~gvzI@%cafdC{5(beV0+H zY5#pJIXxue31+52k7fqvgeh%nkkCxzTG%ESrI~N&?Q?MRo*vDj9z`dYD-xQuJ%YD$ z#VD>sBf;LFaqjiws+ zvs{CoqlD>EgM@5Hako4Y^c*EjZxf;&wY>|c=O|%%)F2_-QR=&SUD0!tFgny`oI%J#L-i3vwZ!}gl6hv|l1_U139#i%I97UAnb60-BFRHnr! z{e7FThlFh3d0Cg7grlTkdrjCgru*F8?xCk8XNtzOdX&b^g|GUuk(jm1c<)#KKg);` z?NOvJSJ)nNMGpzt`S>_WI7)xFz1FaY>B{yfI5FWUY1m#9_Ap)99t9^R93>6gYr-C; zE8C;s#Dt@yVS7#3!*oM08y`%IQBjU9!Xt`=Z1?GPu1Gja8n)MjJxo`&N5P2+M@hr> zny`oIe)OmR)9!*7+;1Eo1=abho))7tZdN0z61qp?krPjsVvnn*XWq#!xtgV+=XJiW z)ssK(!g#l3Ar=jf4-$H6?H%AY!6-df%daN%{M6U4div_SAG+`3@+}&(%E7es?9SIU zCsz&Q_sy>>(k&{5pzhF-m3fb=#OLdQ@+|24qSjK@SPF&2Y^*2N$*LaxjWB#;8FL z3H6xOTvE^&AJ$+LXQHYxhf+L0cUl@z&O5au)&xByG=g1k+XSODV+`#vTZ10WS8iu& zZ)=cYHldUR&O^CMH*&J_urvdHg1GA%~w?;e|L4SPsP&-X~T z2}W@x8VQbPtp;ANGzzRe67-PJx{~LL1fw|8)*9~ZB=kf!uU)3aD6V#+#xI}$bGr*J z|LS_pdD@@--0l-U{57lV&ymnx-MKnS_**dBglI?cF2zXDbCfW>O^9|B?^28eJx2-C z+k|LG@h-(k&~ub9y-kRA6z@`u1U*Ly)7yk-NAWJjNYFzFhf{Bp9W)Td%&_Gi&|OX+Pb0RDQMhb;&huY>&C3hlK3B97hR9acr(N z9L02HZ_hp?93>6gYYlstu54c?o|tfyG;FU4dzh|lUnicJaFjG`uL*mYu54c?o|tfy zG;FU4dzfzMWmk|)i&0UIEy7ojBxL(Kah)p?j*^D$HDM3amF?@q6BCY-hV3cQxIZBw`CPX`mE8IxXbCfW>O^9}s zu7dR}Z{17iA)#wpJz)&u!{`0v{`N~QJuWqWS?upW`z7@^aQ>Quzc{78PtzaX^@sLP z|G^tY%=Fk+y8K?%KunHOT8y$C8h`!UkK6y%drm3u3ZG_rY)gY*(V8X@lcSUtqil!9 zt#|vzz5ZVs^w^dLzXmou zd+hIh+T*JR3EL6%*qv%6G)U-c8unyF(D(e|TaTadupg`%By20nZ>9(h5~C;dNQB1! zeE1(8|F+vMs2U_}E6Tr*3Jnlb7PThS)79hE=1j}B2>u>xnm|mBk~*VoN3LFd@zvMA z^mCt6HR!P&rRDEAK}?Q{v=|lkqVdS4QHnxOC&u587LAl(liUrqjItdXrQaTSRinqYH2CeJY1$$f zWji#=_&dGJ;XGgJ`vTmNZm9PRq6kwT;HT?4>RdJGu^s7ZZGUXj*dk&#;HV%L4ed)>UD4Ci)$XI0L$g~(Fv|8)SK41y z4SH;=9NI*ROFNxylGe(GH?ru~ZGF zWm|-E|xuHss)67<+sx^YG3dAD7wtq4Zh4vo^@y5_8NJ3Y3gp({&` z$tcGb!6@6IQF@`SgsTQUww11~kToVlV~b#v?a(MI=iX~AJ+_suzkj|a=*fu4RoOG_ zy=Nd{JEAmt-r4sI3!%T;lMz9G`EAeHf9%RIn}%Jk*;#qZ}mY$%xSS)3Q_g zXaA($#hFOhR+PS@s`rhC1_^pHA~bF*SCId^T|tttttfqMRc}NM4HEQZL})y&%x>>& zSHdK0E9!k;d-kE;7#kWS=*fuC_=-y}J?n#U_hTYqTTzdF;n|0J=WA$?peG|j(R-u;+J*p8@kN_|;_#58qJMl2fFH;tKuZAD#m!8s^L(O8Jl6M7^Rkg8wp|W=8zAPArcnu{YfnamMk{&Uk&&>iDAj`AuOAvD=*fuCXf0SZ zNZ3}CT2t@44-FFZWJGARo>=$0By1~6y;ARX4-FFZWJGAR5mhxv*jAKAm)-y$8YJk+ zh|p*=L)9Q*TTz-N^v?LuAVE(?ghrd;ss;($iqdSSchQFi33@UjG}=sEHAvW2lxA(c z^*=O7(326N(N>(QLBe)Kom1+|8YHxm*^?2AhSu7uLBh78w2Jm}w6(SpqbKx8ghna3 z_6#e+w4$^d=JyCnOszJiGqO?2fxw^Z~SzPku-Yo~B14G~QP3c738<50bF0s5ky!-+Xx5 zpIL(hJsA-iSK+xc3EL6%urh9LYIQ}z?=?_w$cUgHQ?Bk_7T28RdXQ;_t*CR~|1gw; z#OPTQp>ayN9{h`_tC@stMZNX44@Y~DpeG|j<6&j|l~JX>JCm?oqvn5wennz}CnG|m z^u&GZyE6&fiu(O;IuqlA#NcUqBtoN%sC^rQGYQ*@y6k_IxBOptLmz_+K~F}6#_eVN zy}z9hB4JxmmwfjlO26`aMS`A;2o1GGn-gaewiWe9S3d&tE(v-vA~gQE^r>s(Uf)c@ zwxXW@(MMqYAVE(?ghp9$_HB)tN!X64M`GmH7TZAGb9 z{^aFvZR3LkJsA-iZ46co61Ekk(e<(KdCNEkD?v|2ghrbgR)pyqRc47hzUR$NgM?-r zdom(4+6-4UNZ3}CX1k}p_z#)}iNVwKNQ6e4sjCJF+ltbx{TC0i1_^pHA~f2HQ#DA~ zjwr1@)*un9T6i)d=(ci3UDb8aX+^q<(kj}^L1Of*iO^^}fT}^lwxYBf=GAWSPtyR$w%NDQ7vlL(Erv#c5BzSd~5kcz;^3U7zL4RLOyI0$a(py#ZCg^_6 zX@Z`N2#tU7tv`A2g8v-P2T9mgl-_x#cU6Z533@UjG=8_V`SaWLAPL)w^4GvZg9JSp z5gKJxJGiAiA0%O0QThdx-mM=RB-O7GbY4HEQZL}>id58QaxKeX#X61Ekkw`b{1;Gsc+o{R{M|GV6e zxv^ajlCZ5P{q97+KM4&I^khV69Q>!NANgzT`5+0~ii$VCS%U;U8L?$SNA1U(rsXwX&<=L4ux)2#wYg>mH7TZAGb9>KB2bL4ux)2#q$Pss;($ ziqh!P7fM2d1U(rM8f|8%8YFBhO0$H%h!Pqk=*fuCXfs^ZAYofkn(g#uhtMEFPez1B zo2jb?3EPU&tgSCpga!$EG9onEic>X6*jAKQAALh3G)T~s5sQY_+NwdqwxYC(_Hwkf zwi5JYL};`fz=|-fDD4J%dyt?fBSNFJp!PmhgM@8GX;;(x6$yGWA~Z@*)E=&Ckg%;N z?auo6AVE(?ghm-r+KW~V61EkkU1lHWBx7_C|67*z5Xp|XF z*9LV?Bw<@o+V%H&mjpc-5gKKt)-_JmAYofkx_a>{F-;`s$%xQs*J^deAz@olz6xt| zNnG7kf}V^BjsI4NpLvd-4?bge?3OQR<2h_az4g)0*nR60zNr13#OPTQq4A;eeDEIa zyeJ9VihA=I7w(>L?LC_Y33@UjG~QO){DO8pNW!+F{^r#emGa%YX^@~NBSPa-rSE>Y zT@RA5t*Dz`{iC~c-*9TvAVE(?gvP05{QYrzK1jm0qCS55kMExJ(EBzG67*z5Xp}M> zl$`DL43dQHhguW&HhVyB;KATTy;9UTBaQJ)uV;G|DsQv&vnT zS`HGn73DYag$4yiv-#ZxPATfG^CJ`EXKHutUCShAqe)s26R|`Q;MubLb!Q-vXXA-s} zD&94^wE03zQ}<*<&~Gl|@AJ!9OFe@mVOvp`UHH=&A0$Rkf9t9L9vWws`!T-}V{o=d z`L(U6dtLD}80RGD$%xR<_-k{?Ov1LJ?taD3V!k3lPez2sYs&chK+K6V3EPU&JFEJ< zOM;$^2#wpy`1{#7`!SQStth?Os;?g;=*fuCC@apstx+=x+Yxmc)-Dp$)IAw7Xw;RH zgl(7O0Z+So8|O`<5=yswLXSjfw36370}0!TQZ0PZ=iRMokf0|cLZh`{)gWP8QEJUI zZkd_}33@UjG+IxrdpHud6{TKz&gXr)z0rXLJsA-iZA4WK61Ekk(RJVZ{(aLRK~F}6 zMw=O`1_|2{_1xWe-uKp~K|(W*JsA;nn-i-B3EPU&YOE8;uqcPP;Z0P-p970^yVhLF*f#aBn*Efxsgl$FXeZsvQdRk&)^z?6z`tPBkXE?2{%I^nzTDBFXHyii% zAVE(?god6)wKgxmAM9z_R@AX$r=nkxpeG|jL(kM&-z~o%>}lCnl->y4#|H^|G9one zY_N^N^83M_mTg7p-PC=Ylb|OfLPO6u+gwt9KiJcP_vTL4ux)2#q$Pss;($iqh!P``kl= z1U(rM8f|8%8YFBhO0$IC03RA8=*fuCXfs^ZAYofkn(g#{_0S+ePez1Bo2jb?3EPU& ztgZLChXx6HG9onEic>X6*p8_C9O^Cep+Q0`nLQb?XlSji8YFBhN~>ruM_X$vF?vFe zL}-+fYtOJEOe;#ef!-b@=*fuCC@rYHPt_n{TT$B8^nOKxo{R{M(i63Zs~RM1D@wbw zK0Zj$lM$g&MwIrVRfB|WMQNAW$2kdlG9om}%%DAW)gWP8QQ9r{`HBQR84(&~hSRk{ zofApeR+M)AecmNOPez1BnW+yvx0A4~C|$jHm6#?H^khV6v@5T=;*hYdC|`xe7$iYY zMubMYf~?nr^$PM)Uwas7m8;2OD@s?B|KULoX@4g%de%f}@M#|j+ltav@n=3`4HEQZ zL}>779|_xv($)R3w|reI2MKyIA~f2aiM`fA61EkkyA-!w{Pj(P1U(rM8hqME!nUGx zx8?fN9@;cW(326N(e4!0a*(hcQP14{&P%L8LU*9-$%vra9j~fE!nUGx_vIz9%T&@^$B0|WJJ(>+DF2+ zqI6famxILUiJXuKjZ*UEX&(vOiqhTT-X0|A$%xP>Ex0`GBVjwDp1bs(dS7%QbjRHN zDkFk!cj(pTGYQ*@(%t$#K1ht7&?6BVeA-9CwxaaZp^tMC^khV6l$l|8KIpVeD@spK z`g}!#o{R_$KJ6o6TTyxn)aP9i^khV6+;-&opwlv~C_T;U>jw#XG9om}iZeVPbXuk( zsyvlj)-DqD319PM#Gp~vS`xNh4t?_{*2kt%38mXTkrNW3(Mn$TB_wPsO0}SG421>> zdNLw3__U9NZAGay&v?sMH4PH48JsA-ieA-9CwxTq; zUiIS-Zsj0BPez1Bn;B|3NZ5|3=kBh&^(&hO3C%e6WJJ(yPOKUvY%5B$oxWupZBAnJ zgdT~|Xft)yAYofknzdi?z1AQ>Pez0WpZ1Zk9Z_=`gVrFSmCT-u2%1m(NZ3}CR?%J# z5~C;dNQ6cyxy}^Tx*}m)QQ8gk_8>t|MubM&$y5yzwj=79OYd1fA9TOUh@knjPkSm8 zwiTt_Ssx!HMo-WrLW58HNZ3}CcA0&glb|OfLZi$K!}CF>Wm-|%E%*6~1U(rM8hqME z!nUHc>+ka}33@UjH2AcSgl$FX>ZPv|BwQjo6O`t5y#eYj)3?<7JGK?2_c?vRZ=Bce`;ed~BSJ&(bJ82Fq(Q>AqVztehyKe) zHw_Z>WJGA_eNK8amo!M&R+Qf7bnMu_ZW<)$$%xR<`<(QKF=>#ntth?E>E_owp=pqy zCnG{b?{m_d(xgGcwxaYtr=Pjt`k=F^khV6 z=zUIaY|jTt*jAL@=k)Vm@^70433@UjH1s|vy@5~VAYofkdY{uN?>fI}kf0|cLZiIb zaCtsR!gfTxbN7s=J*{bw(0hvQ$%sW`dD=(9wxaZY-(C*AZPCvMM^EUH2o1dhveng0 z!nUIHe&606B$@`v+ltcref#(zK~F}6 zMj282HU?)BwiTuK`}T28f}V^B4ZS0^%_TDl+ltcrefxYxf}V^B4ZZ8N&51J!+ltcr zefzvif}V^B4ZX9r&FwP@+ltcref#=Bf}V^B4ZVA}tx+=x+ltcreZ6)~6A5}UV$i57 zCkfjw#~t7O@HWnyMkSQ4JsA-it>pE3kc4eTsTSV-zHjhc617_idNLw3S_`fS(~44S zzU%E@(=e8hAd~3Db(wD%#7@*4mn@ z(GxU@&?qI>o?%6pR+M%Fy*)_KlM$g&T2OnRszJiGqO_~&{fY!V84((#Cu$E@HAvW2 zly+x*e2}0gBSNE$DD6e71_|4W(k`=)a}xAqL}-+mL3`?|LBh78v|H};6$yGWA~ebj zr)z^cCz7zODDC?Dyi05zQi;}RdD81(;KQBs8 zMubKgQOkKz61Ekk_to@qPJ*6{2#qo`Eayc@*jAL@yVK_@67*z5Xp|XlIWJ1Wwxaa@ zpg!-CpeG|jqs-LHc~KI!6{Yte_4R`UJsA-iWyM*}i;}RdD1CL@Ygc(+9|(FfV$i5- zEeYE$M?de=G%BHV?a7GH;OS2iwiTsX=;xM5(326N(OR(XOGwyOlv=Z&zal|TMubM| zi3eH-N!V7DdSyRHMuMJ<2#q$Pss;($iqh!n=ix}ulM$iO=8~#G!nUF`OZ0PnB~3a#s) zR<%mdlM#!?ay>}GwxYC(_HwkfwrbFm5us5^zMK~&VOvq!4fOUPK~F}6Mrpz2yeJ9V ziqfv8_bU?gWJGAR9a$|o3EPU&?yQdw67*z5Xp|APoEIfwTT$9&_Hj;vo{R{MGBYga zMM>CJly=K~z9K%riMubLtv(a94MZ&hCH2${Au?T8YJk+h|p+nFsm9QY%5CpQ0)Rkg9JSpv1lxB3ngJ& zQQA-Ua_HAo+K-lk&-7$OXy|^7cH&0~(~8n{L2nNd^khV6=(lRxT}p$5ZAIz&ruQon z^khV6=r?!TT}p$5ZAIxit&a~9^khV6=(mH~T}p$5ZAIyNvyXEU^khV6=r@qsT}p$5 zZAIz2xzAT5=*fuC&~G`lyOahA+ltclf1h_r(326Nq2HuxcPR}LwiTuO7=8U9K~F}6 zhMt7CHEJedTT!|nw$m;!G)T~s z5uwp$>Z(D)wxTp^YZn+ABkJJN^kl@MvAkcDgl$D>7479{ zYi-RHJsA-iZ3nO-Oe;#ef!-b@=*fuCC@r|WUzCJxMQK;l`xOa#G9olePh8$FO2W3H zv^(qLg9JSp5gKJgE$FUL+#Q1(udNLw3+Lc#baY)!!l&`|tToPAz zm7pghx`v+YYi`#QeLb63TDBFX=kt2X-!)9olM$hz=kq$DAPo|>6{Y9%I;{{IB6BP#kf0|c7LDcW@+534O6To* zIdpnX=haF_oaxDk(9oGaomV?bm{yd|4fggRK~F}6hR!DH^qDkB*jALzKlXk_f}V^B z4V|&n=`(4Nu&pSa`iqffUuU+H!=;_IbL8GpmBy77JIwcn4yydDAO4pu@2#r?qdaXvnwxU!EIwckw zBCUdNLw3+RRWjNZ3}CW(l1V3k?$VWJGAR8Ln!Ou&pS~b~+^%8YJk+h|p*= zb=4qYTTz;|bxJHWNYIlJq0v^HszJiGqO|(xR9a||peG|1jpcjvBy1~6t7tDrTWf2s z=*fuCC?#LMM^D1GqO=?6?LmT`j0la=g3I^lN!V7Db~U|Uk)S6dLZkG=<$LrbY%5B; zvpzmZ(326NQAX7AJ$e$h6{THfALk_K$%xP>GsE&ddJ?u3rQLF$uSn375us6LxaE8F zBy1~6yZ%1!lAtFeLZi&o%lGI>*jALTUc5?--=n7|BSJ&hgE}Ftd6$H3MfoZ$#vloL zGNNnn`JmqAq_lK3DO*vxn$%mNx`qjQG9onEwR62zBVk)nx+>P&twMtYJsA-i?TWr? zkg%<&xVk^JX^@~NBSNFynb@m6NZ3}C?o#M&V^Izg^khV6v^y+SgM@8G>28bOnid)) z=*fuCXm^UL1_|4W(p@9H{Vg;|(326N(e8Lv4HC8$rMq8xi(P1tpeG|jgHQWN*jAM8 z;^}RCp+SP4j0lZ(2eOufgl$E|-AHSYpeG|1jpb<{3EPU&UDaNWcJEcWs?P`Q$%xS4 z(>|tUTT!|@+}nc$JsA-ir3HuQgHFq|qI8$L_bU?gWJG9`o;W-obXukrrMvZge2}0g zBSNE$sNwmb(=x3nJ$2~goCG}?5gKJ?7@iM0Ez^pMrzalgBhmrMdNLw3+7m3zyY=~?(=x3nJ z1_^pHA~f2HQ_DfZwxYE9=q-k!L4ux)STu&`gHFq|qO^+ka;rXD`GOZ}>YI?sSK~F}6M(K&e^FgO&T2b1a_3=T1o{R{MGNOj( zgHFq|qO{BGg&X>-k_DhCPM ziqi9WebqHINYIlJq0vq*@1;S)wxaZWUSFpT4HEQZL};`V*j0msZAIz%yuPv<8YJk+ zh|p*!$*Tql+ltcjd3`N7G)T~s5uwpe#8(XxwiTu4^ZM#>Xpo>MBSNE{?5`RmY%5C7 z=k@jG&>%riMudjOpZ23_a}u@{rE_Zf3Uz3ZpeG|1jp6r$PRq2Sbl$F)L%ZXatNQyv zdom(4bf! zkg%;NjV^tKIy6YolM$iOW`?Rk!nUF`OXw@qp+SP4j0lZ3!&MCuwiTt>PG6x84HEQZ zL};{`x@wTHttidf`U-Vukf0|cLZhuXRfB|WMQQcXSFb~Z1U(tCXbis}bXukrrB$?- zqph_ySM+2=Xq1uh|nk_YWV%2(=x3n?K1l~CqYj}ghrVehTji5Ez^q9ZrO9pG?Abu zBSNFhaKrBhot9}uY1iN9T@v(UL}-+mTJK1y^DYV7iqh4KSBYsNK~F}6M!WK=D-H?U zit<%hj6o9gWJGARH_&LUo%F1Kn$D@?*|wteeEzBn;_vm{ZOa=;>B)%DXm8Tdo}s>9 z)M=Skl%CH&@K3Bkf}V^BjrK;MszJiGqV#G}Mx-(U?A^khV6v^Pyv4HC8$rRVeax%YXku1L_65uwrE zm{m1M*jALD&p&Zz4HEQZL};`(e^m_^_I^czo{R_$ow3yEGnIpcZAIxEXCEIV=*fuC&{KeI^YOwiTswwSB%KK~F}6hR*Kl^qDkB*jALz2lsiG1U(rM z8ajil(`V8kVOvo;=j=JZzE^D_=*fuC(8*|>K9dFs+ltb8ZLeMH_lw$-5raluYnhg9 zm*cT7JiE<_EmxILy7pv5XtcUItCV9RVOvqEh4+1}HAv8t5uwpquxgO7tthqTJKlcS z*Fp7?O3;%Lq0xHcfyzO`wxZN4@AVVbAVE(?ghm@tRfB|WMQL84((#1&8;GIxW+R(ypfWD-!f%L};`fSuHsU+ltcetd9>8^khV6 zlo2(&U({)tR+M&`eVmh^CnG|m%nZZ(MV*#uMQOL(=PMHQWJGARoqnC+NZ3}CcKvb^%lO(f{ah|p+vCiW@^3EPU&Gxh%5fCN1m5gP3dOVuD@TTyzZ-k*PvpeG|jqunX0 z8YFBhO3&2$a~u-%WJGARJ6=_Tgl$FXnRuMvnL}Kjpgc&gl$FXyj?FxyZ5SG)vwEUPw0^djZ*UE z`5@D>ttg%K>+L~;o{R{M(t^wLK@zqVr8A4YUy-0EBSNF}#O3)Q3EPU&*~>mYNYIlJ zp;1QE@_dklZAIw}X&>h#=*fuCC^N(Ie2|1~Md>VTpRY*JlM$g&X1L|~APL)w(wW{q z?~cY%5A%f%n=qJ|CnfBL#t`I*Huk)S6dLZi(LRfB|WMQN7k z&v8i5lM$iOX1J11U(rM8hqME z!gfU6=g`me#`lYAC9@|Z77bhvcEYrxw2Jm}@cH2A37SM`v>iY#ISJc}(r%!)2MKyI zA~Z@1F3$%^*jAKwHN9VvpeG|jqx8h(`5+0~iqh_^j}H>`WJG9`5w$!YBw<@o+GX}} zPJ*6{2#vNwuI)j>wxYCK?(-E1dNLw3+D^aDa3pLiO1u6(?~B)%DXjfi!#UWu^QN9XWKOdwgBSND*Wmw)Xsu8QPr?hM84(&fudV&4G)UN1 zl&)`jzal|TMudjWSZY5i4HC8$rR%glK1k4$5uu^8qS{?bgM@8G>3Xw|a}xAqL}=*D zt9F;tAYofkx^C|C6$yGWA~bY%SG!ATkg%;NUH|uamjpc-5gIy!to^7oNZ3}C?pE~m zg9JSp5gK|DuKlPqNZ3}C?z(vG8h<}XPeu$Hb*&{~+vU(Mu+3MIt4b(cdom(4TFK8U z<(Np=R+MT%yTH&OK~F}6Mr*;ULBh78)SB7_h6V|GG9oluPdrdLNZ3}CdZl)Op+SP4 zj0lZ3qN)Z7+ltcY(k?JGNYIlJq0wfBszJiGqBKir7Z@5O=*fuCXfs^ZAYofkn(ed; z3=IXK*Ow)=_e{O(T@^khV6yuGyf55(SQB4JxmKX}URrF?!5Bnf&lA~gQ8^xfNI z4>yspt*Fy)xqWxh>F;Up*djqsMuf(#Wek@8-)pTUVOvp`-+agJy$`sdX^@~NBSPaN z<=)a?$DVp3VLPHey?fcmtU+R$x+f!o{?T%e?5%NaP)gDX+lqSL*`L{6eCeOIa*!B3 zL6ZoLk6&`>S*54cx*}m)QBQu!Kkh#G0c((;CnG}RmW!{}JI|^H3EL4hmA&YVtsEpu z(HBofEE>z(LP^+G)Vr>l4tqI@#zKsq&?6BVrR2w3UCktHE9%Ve|D40#9wg|=h|nl4 zc)YdwOu}|V-Q}?ND-zSxJsA;n>52Q+cV`l|74^-R-{r864-%s%^hkt;#$OwQGYQ*@ zy6B7Vdf3M~33@UjG(KI%-_7lMkc4eT{qZyJT6&M?D-!f%L}-*5Zr|p_nS^ac9sKTH z5Bt1Jf}V^B4fUxux6dSOE9%ESdDp|fevqIiBSPcFW&Hi^bK-iCgzbpBTd6CrT_mQd zdop6ssB0|=+b+kGU*dOvHjPRs-R=oJ5~0ybUa!?i*jAKk;dy8K-Jc}r$%xQsEm$>3 z*j7}urr*m+f}V^Bjn)(Eo|=ShMX6U_e)HSfoJfM6j0lZ3qN)Z7+ltcYI{lWn_H|IB zwi5JYL};{`VMUmZsJk3K(2QeGMg-kvxT-quwCh0< zwiR{yEm!TXz5F+t1_^pHA~f2F+N-We*jCi#H($Lw{pWwPX^@~NBSNF>Ll3kkf0|cLZh_c@z&-u3EL5M9r_iCY3iPg z2wK-rt?!n)>V$1YU3B{O7#}1?PtYVnql~EKdXR)|MZNa{$1%=H(326NQD%mHn@eUA zwiWfVj~&N+MS`A;2#r51WJGA_evEdPswon- z6{TKz)3^PPra^+9j0lZ3qN)Z7+ltcYdd8#wd($96Pez1>?(J%KsdA989Z}cqu9#oe zG)QR1u_q&fZZllfAYofkn(f~9;g>cI5~C;dNQ6e4sjCJF+ltbxeg1#71_^pHA~f2H zQ#DA~jwr1@)*ulpS$HyH(a>7k>WXQFtthRcy&P?=t;FbA6QNN`j_bjmmT5(4H_+RI z1U(rM8l?rb_o=xeVLPI(S$fYjk8k_@dNLw3bmjGt=foOC!gfUQ8jb|7?lNM~xL$Ljh}Xa1_BJnt z?Q%TnZ|`V-ZyJ?Qy4|xTLZg-ZxD-g(R+MVtA&>cV(;z`lMuY~h?nu~Hlv?xkFZfK; zAVE(?ghuO$dzFKPZAGb9KIqziY#Jo!$%xQsBdThUu&pSKu3x)=9Yhva^h5kZ%ps6AXQISJc} z((bH}4-%s%^hkt88BxRapwlv~DD5))I440*MubM08MLRabot9}u>FTAg5+vx!h|p+PURrTx61F4iO<21~=!(v( zT1Iq@a?QD151KITa-8~*+uFP<4HHVYdqR&yXta{oJp&2bic&3{^PazJ8YJk+h|u8G z9SPftiq`zwra^+9j0lZ(XW~HXAPL)wQm_1u3;(8Rkf0|cLZgkSszJiGqBOeR_oKHq z4HEQZL};`-MOA}@?TET=ci&(ARMQ}#8ONTC2)fOQRfB|WMQOG>^B&e9F?vFeL};{` zx@wTHttidfH(dGGtsEri$%xQsD^ArQVLPH;S4NsONN6RqCnFY(;d;=7X+>!j?d51| zZOzr_2|W^_QA$2s4>~Q=iqdYNw+9J&G9onEPNwFHgzbpBX6Zfa>p}Ocj0n2)MBUS` z8roBtu&pTV&ieQuF?xa~5gKJg4cCKC%e11j%k1Nv1U(rM8f9kCGnQHo61Ei;yJgQ; zBOe;!PFMX9DK~F}6Mtc%h*C-OUBZ}8> zBzSd~5kYHCFaPH9fBV;c*GG0Q{)Im)XDX-ZzQ6ESyKCR8ced%@JL@^pu={_`dwNFV zqbEU3Q;!n;?GM!ZP4RD5u72vXf4;lRkN-vW=)d*9Bj#jsMdCLP{&ykYKWdbu#&R%< zHL~QZ=1O&=JnOHjGet(k$>eGz-e2~?%GvmD%$4%(DAov>dH?ih{K1kF)uwaEb{YwK z)`Z$;{C6~0Ds4ouM##+j&;FM;EUh+A$CuWm_DIk(62H6D!ZtBYJ&H9l5+8cTHA@fw zwkuz|^n7ZM1U)1k|EAw5wQy(siczeQQA6n}&-$x!*vG_?el-U-w#P_ZQ&JH%{u>Fc zAC6*;keT;t1LawN)qm@MN5qj_HEh%%5w-BUcakecu|`_*^}pu5>PC6i|5TkRG9peU zS0nMeyU+~Y|2dXJ{mN0Sks3V*Gw(IFofC}-=a9X}>BqcF&zgwxEkrSn=1QfFDAq_N z=HTYN=0Ufb<`1_fwIkL9JtOh{r53gcjR)5iYorphH8|^Q26fM;_O=Fzm>ch`Uona` z5^v4^{pETv)}@CY`@%!zP;H`I*w)|68^v%!h#uP_#`R;1V3h69cw2eOa6voiM2~H0 zM43GMY!QsI9U7l3yULHY9T`2grNLEnnzjf=*$xfv6X~%njd4}mA{b>mG*kxVjA_Z^ zDE*zQXj!*5h%qYG-Ox~5sD_zVc>3x*uI*a{qijb?I(4R=A`N+j=QyG1a{c4(-l z>)nG)OCCq*?=c3w1K1+QD9uD4-7OmWO+%|Idcu~%xZ@}qDZwb)OI_(MXVsv`wlp-S zXuQatCY^212u9fsjnab0-RAVzj&%EuW16-I?n`WkM(K%r_ubLc)79*)@e+Dl1fy(+ zMj27M%USD+9@|P+tAfT$XlxOTvK<GlYPtz8`DBGb?dWe1nQ8nnXtyIU|(iXue+o7RfA$i52$F?-MJBznwXT%t# zoxnTW7;GB#PO76qJ))!_J&hOHi-w5uucyT*+e2OHY2QqbZKb1n(|D0xS5E)NWKmaI zjItdXtp%$FJ+_r)e8ZWZzI;h?*Vo_IGjItdX zZA4WKdTc8trLX@jdzwHj>Pm}IwnL-M3{`_3+mUYH$<}pHvrjFDqarOvg&luyGhEg1 zuJ|aS_E!6Z9*FXXo))8QM@ns`t{U{%R=Vo9>Sv(=V!0krT8y$C8g0d?8uZwXbo>5# znm{b-krt!EUNp4U*4mBL@|rd}JE3*AmqTMbBN$~nG&EOf22y_Mv8}&rKJ4wWMKH>C zXlTyWsA5|3I7)x#uD`B>DKSRHbwX%p?Qlc4(Bg(6xc)#3e0x9HqZ&-=py& zyRL&N!6@6Ip`DUOm1ufw>+ibW(Rh))TotVdM%fOH($fz#szlRcTYryxOd2oxw?&Lm z{Tgl|>YY?ag?dCORq1KG$X?dLM#MV!j(_^k&(SEYQEz(SV(ahAs&9+lKt*b43x2MG@+e=;f+IgnOw(_p=*W075gH^*(N{dmpL!+&OwH)-=j{0f$ z18OaRSgz*E7Nso+j9%64e9b+DF$9@{F1(%1ivGJ#m` z)+jAT*$xerK{->K(_>rd#(L%X3dC~PNog_4c4)M9P;=r;k8NqFz12QZ4iL-TGo{5S z+o93c!Ky)zZKb=cAH`nQ!8%hrN@+35c4)L!O)Jh!kL}2NTd%4Hh-LMPv=|lkpi$Ra zuY*Sk>1o`D9@knDjItdmanC@HZKbOk(fkz}TLhzQhem6`pU&eM-<<1fy(6N^PdD8uZv!x|+f3byO|K7Qran zq0v^HszHzK$h%gevLmb-TZFIlNGuw<%h~EG(h5&cSL3gjqph_of>E}Yy3$?FO3-6l zxzhOS?a}rOD}qtBL!-2y?u%A}9@|m!b_b!>)fVCV0VG1B^u*=PgrmaK)7ALv<710p zlvJ{wsNKP^}i#BTLhzQhenwhmODlC*jBo+zxI5!MKH>CXs9hz!Fy3MvOZB)GzD6O3YwEW|7g&YYa7sl5=z7;`leeJ$B0y!xoFSR<8~gPRXHM{!O( zxm>LYuLeC|V>u$-h+>V5x#DcV+2`bPH4=S(?0Gs`yPi>1SFDjSR~&a7=O>pd5}b*) zbHymu$Vez%^$z8I9I0AGF$Nnpw#P_tF6k;Gadc+rGaL!Efku*YrM#;L%09WeA`!LV zt0HPJEk?0Mdc4|PdDXn(cGhS;`CO@IbfVwa7&VwH-wBZhYh)zUdQMkk!Z{pMYRr7J z@2-h5lh&HdZZV zOsO+tu1LhJeP{iOQLK?^dd5>;e*MG${i)Z#?rzW7zx_j3@6I^3-%USo>N%%hc;)U( z{`2ou`;>ok)$ZYc`g^;_J^9qq^WS~1S6%-@Prd27Zz=0KJtV&HSAJ{vioY-Wl9JLi z{m?lty8hYc{_1s~bLL1e>XGmNt=%s^{%uX;{BvG&{hJ>D((69AXwXCA-XDI=?ulRZ zwx;pqXJ38&|9jKzZ&W!*FzN|U{;fKfL^&=l#M2A$JB6T!#M7VlnwWiRIYeA{)9q&- zB^V{`3t#n~Ru1Lr%tAO<_K=X?E8p{;R*uhp@vE=@%(Gwrh@%9fRO@g4%A1?U9fi2H z5%iEy+kEudH#dz7OPhbgzd!Yn(jdX8ryl?9-Qyqofu?bBA-=s4^pH^RdB@v7&@^uR zz00qE;m##yZ@iAHxIk+D(bX1pCH<4lt}|LHkW`cUr?qn$nZXg7w}_H zCY2#7h}Z^cpamt20V0DRh=`3t8*o6h5ilrWG@55`CXpe?7!d>vpbRp`iKgu)UH4k2 zPTgmn%^&Y|@lbW|T0{L-t@R{%>wo{xzuU%u`1LJei-~vK;k73(cW#`=Z9lH_6Hhvh zKP`p{dtLsDe|GYzU;Xqph6!6tOb_|fleakj%r-`h=r~5!VwkYkd4If|{H>Fp+s24l z?}$B%zKhCke$CHsW85k9cg}-f)MA*h7yA3+OTMs;fnr0sjj+W8>izKZzPOF?)j_``ofHX{z6qJ zP!wlhT1Mje=VlD_w?;sx7b>fHpuZf|zNHBCSMxxBp~E&06ZS%XwIAp&bl3=6OrXEo z5A+v0JRt0a{wlA~U+AzAwwOSFl~?F5bJv8u&|m2T{Uu?G3G`R`K!2%06ZYc!rE?Ru znBe=Rb4HXWg9&@FPIX>E*o)Xz&ly$duvKSUOc1Z?IrX0BiobQbXW{{2FLIjN(qnA1y%DyUX!?tKva5q=@PM!v z`lCkn7+VcC!WI+gkGj}nY)^&*!d~c)THj-APoGBEVgmh9-+K)77dkv3?1lcgv-B9~ zj~gsIXp0H-$33OTK!2gb1HxYDk9%B?f&M~=jj+W8`s2RUW1zpt_yc0!>)j{0b@mwO zkK1L|!L*D-yEnGG5Bggp&~ug5A?@MCk3!gD0{vB9ZEs`;guT#T>0^8AYlJN(xB-?v&|hlMguVEF z>DE>TN`LuH`KKcC*IQ34hcJc4r1#wXjuL!~x6W4yr=TF}HuRhf1 zY5MMOdeqVT-*w3WVJ}zhX}V$%uMgr?5yKV}zw*e>p8Wj}{OvZzi~jbEqo4n!YaES) zy?pzari+4jeh|#V78B3^-cO&r_yK>njqwLpz14h<( zzlf0$!-Tzj8=R)61o7e^n7J(`SSRMyW4tO>_LNxRk+7HV!O@L2h#LmMsBAI8ezQM4 z#(N?|$dr+=7rDmmpr4{|4q^_1Oti%W8A+b?72^UU1%jz=BV~9MLhW_Z`V9Rf5+&MnVYZ| zibZXGtwMjtxw^KPc8I>(2{_fVV)VUiOGNZ$h zu-E=?yh497IwTWqG4W6Dc*U+VOjBg~j1EV_UjF^uG=-XGbchCRF>%4Y;>H&W>pF)( zha+JxMvHd(elRL@n4?OI3F4ub9wYQOqr;J~*M8+>bkG!d_^TukC5D z5w@7%`~2Kvg#Ko9$f!)%i`8JgdW_KDj1HN(Ehbne=G9|_{*Idt2f|+LD*N7Jg#M1v zA)~Uz1pCeY^cbN(PU-`~USwz8^h1Bg=#Wgb#RPdvp7j`^KPt`vvG3&Tb=0dnh_&<|gdrcVgsj5V^XxnBe|U z`@uaF9kPQa?B(}v{0&q=L>+8-Ws3>!L6ukBL(w6bXu@99r_u-a(5QoLRJNGlK3Dpn z2BJgeVZvVi{lo4q+6Y@ra1Sk=a}Py_#4uqm{~l$UxQC)cW^RiK?xA&Fh5nAv;Yira zzujqd@CY3;DqBo&53O@IGUNyyj)cAZTdHZ|9*PdhL|aU753TwUnSO*0N5WqIZCk5@ zN9Yg@+G2tm=3X5Qtkj0j- zyU!O+-uR4*PhNJ$sdr)($o@mZ787^7^m8ZQ^vn-6I)1D6CvQIbfydtJh!`g9#cq=Q zJ;oPE(+rPL2M$1Eheu0 z8=pFP@}f^{W4!f==N|EAB<#ia`C5-*!WI*JpPyOjY5I#8(R*TK#4uqm)`?Z=F|IH@ z{^$!quvWI1V4av(kMWbSvY(F?9tnG~-|SV7an~R|7z8_LiwX9d{pm4oA2~&CjfB0( zLUOLhAPbYQ#RM5ip7j{Z{Z2jcg4_Oei(z8lt6pK#^qC-D9>gtU9)8h{#5*s_7#H2| z)Z;Y*I=wg*Y91dBB1g4vDdN2^e!J!oGe6Fmo3IzBTkVGlTTC21_RqB+p}!d&vL7bw z#VK8R75baeAz5OJiRYjDdgWEO{X*#@6g8&?P1uX7 zSvogii;2H~$e&2(p}!d&GAa}HqWaf)75baeAv3qd#4rC~{M()I$f+3}j)c9qjqO!~Ijey!CjQUM&fisrX^Kpr(IGKR*vqf5 zX$m#X=nxIsV&e4E&u?|G>l^|dj)c94UDcUUp~DI*4i;VT%dA&(A$Z=x;`cc{1d;?8R!-Ej;u$qeEtHiwV|= zdG#2fzZo5lguU1!c6V0?XLQI8+G2wJW`BB&&>v^}0bwt)lloG!q zRGb#W#J*R(!de}qs?Avk^F=oj=%vR9{ZTm&2dGE!Rhd=xCCx7o27oU8_eNMd-t3dX5;|4 zr|-Trekb#iqh}0+y~s+kzt7{&LA)Y}#|L4HiM#*XCr_StmrrbCoOY9UAMxi217R<| z&)0ek6SkP(`~1vG$KNLsBf3M3j2I^D#X7MnJ;rYaal;^3D_cykPRy&v`0iL)R(K@r z#eTE9J;qTG-x&luXp0H_rxmb3MjWgCHBpL|aUdk>pvA@xi;? z{lp)<_^JoQzE{1%;`fO`{Er~ci5Py-jl{L4FKlC6e3!c)uMyDc#i>y9cy|yvs==}& z9{BdRYaXG$IcILdUYu^VAECcFSJxI3Cy)PJ`w{w^(IGo%!d{%xl~y=lbzZo5(K@;|(+LS&*e=|BngSMFXq1Rm~eT1Us)SwA_Q8i2FCTubB>dRjsornHr zbchB`*o*34=T+!$Mu#ZM784)1{A+by#mX+|a3t)-EvC-h(BFa%*+E-OT;*M_(zzQM zvYb)7puV>cXe<^hpd$?CRiut)nkPI zIN_F&uorv8zVGVbj1Kb@O^XTkoBioALVujp3t8fC*^BI~S5fGXYOs)rwwNGq$+I3K z^hd=xAojiL71rt?Rc*;Sm@m4KKrcN;=#R>IKu`zMi*uyr5&EM#w^0q29YNi#d2kQS znVYZ|=V7k;G;t5j)wRV0_lMdK?xE1rc?y zY0wrE+(YZUik011XZ#Q8xyEeKmoT=&7BIr*wT z_~?coN;{zYx#(412wBgTl z2f|)_pRe^8CTuam_xZW6)qP_`zZ4^5R3_}jI0d7??EtgTTHM{%&W(Ed93Vd zvBIpb348e!7Jmy+5H|^e9kj&+`_2CJ7}t%Qx>aNfSz^LoWFa}%=kbj}d{+=;qAe!K zNb;=5_;;T<`^2-(yZPoB1F`Q_@3v{WcM!i8#N&hTi*6*&yyxe)F|PfYvyayZ==9=L zsCnEzh-XF&=CN-n;!2-+yXF!4o6+G&*o)H*we_`vK!>cZEhb*^mH5r}Za+eQGdg4k zP1uW5y7DUYH={$c#1<2GzyBMQSE0Wd9g>MA>_xRHeT4pIbV#<_V&XG5IF>#_QA=vj zguSSmrE?Run7HyUULc)^{uXq|s7%<4>R;zo=x;%X%-j|eAN{S@>bwg5E$EQdHDNDq zF=(gndFXFJhwPv&Ccf>gSL@sj{VnK_EHPm(ZevvqLVpW7Bol2haqe|rwW|!%6#84x zAsRGcFTcX3Db%!}Lo{fMiRZr}{wt(VSl2lOIvfdm5xc5$=x;%XIghlMARc<@F+zU} zsu~Gmr8S2rytSU2?2V}$+|beKDsguTdxx-EtN7Ic_dk`@!}KYHmgLVpW7 z%uGzeUgUJ$`a*vTI?QZOiwW`=z4RDcMJ?1pf6HEc1zXQu6SkP(`~2Kvg#Ko9m?uMi z%U;Zl_3AM~e=|DF(BTvcqn)PE-wAZcJoYU`PFxPOJAkZPJYl{i)549iM zL(w5SXu@8c>zNDF#61)pk|nm7;2u_M* zz5EKBChno=kR7ze1oxggce#h6L$bt#y|}++m6#^(q3DoIw8aGX(5fHYL(w4`G+{5l z!de~NL>+8Z%@z~fF!$=<1|6bW6ZRr@)pPEl=rHGz78ArnFJ0%q{jR%h?(k!09KGqR zt1he*7i@{Q1YwJb(=Y$olizpo2OAy#8U6PiZGPr) z=O2xPz1U5%zsI=xmUv^tu*JmXKKbdB-}s=9Ze#q&S8up^+lRl@=3&BKWF^_(V>}{= z_XY9Nh+&I~>woG!=IN7guVDaU+XbU*kXe3^D`?wO&^I7Jv2tf zs7%<4bz+V^#uCH>gJ1`3F~K@9uO8#ku@_g16=ro!*o*yUcYBOS2Ei_}gSMDpzuBK2 zV-q>`n~^CaVK1_foa-^ZHwdzkdDvotj3m!`jQ9NH^G-bfw0j>A`(E`5i~klNh+hlh z?GXc=<%@14uJZbf@s~dt{|)a70i9l)3N?>61(BoLw-oWE%e_PM2>s1Da})OBbgTV< zK!>cZEhb)j+FP_Ap}#qI(1g7>r7N!>&>>l3i;4gFJ8w{4h5lxA$PSvY7uBZp5&E0a zA=z$=iBq0&EPaHcmeimLdr>t@=O%11@sY1wAf1Q)7Ies{OxTO+U*}cmZ$XF5+!hm; zUGsH1uR?zdI%IWC*o#|Cox8Dn3p!-aZ87oAe|xpg-O%5H4oAXX+{X5*!GaE%hb<;v z|HrS|Rfgz;a@xHYbT|_B@+&OrU=ZjK4ccPjiIjXdn zARc<@F+zU}su~Gmr8S2rytSU2?2W3Yp$Y9#DMF4S!)^w)^YlC+p$|Itg2 z5&B!uA@lIJ>_tx3tuOSqpu^1ew3r}|(Myl9Rn$Tq^tbHASFr8sAgXPIEhhLrKld1+ zzZo6o$&lZ&7puV>cXe<^hs@j-6RZ>S>M=rpGdj!@F27|jcC}s;p+8R1g&nlT1pCeY z^cbPP86A#_S-vmPV#N5wfH_Py#A*6JWtZOJ;AFS?OHFFi)+ zkIH#KPzTeCbEM`G`lC9xQSDobpzhW@xQFJ9kj&+_t2^zk?9+BI1={qE3DPQP1M0w z)od}r4HJcR4Tko$59`>*w*gXHln_CPM_F^~5 z{vP8ITjHA|hAk$Z{R^KydD|O)bQ|NujgL0palzwxo(J@HR>eaPlp2V&o=USZSp3qf2O#Px&li*6*&x^MiG zxV9g^{;}UZ{?ZBoonD*@HIL^6@z2{)?OTet^VQ#>dBn_T){2>%uotIW?MD)R;zo=x;%X%-j|eXPxyromZj1 z1s$@wChWy6rq12iy#*bTCAOG2<;Py5b2oBoK~-dl343uH+p7kRAcid_-gxS(caa_##|Zr` z=rA)e344*#b?XcLE$A?_JuN24WAxHvY!$Uo2mLL3@fB>lI*4i;VT%dA&(A$Z=x;%X zjLL+)m>cW0tAh(V%+n_=CRiut)nkPIW^~Bv`djv5kJ$HJ9pn^U*g;!Nu;1)YkFhtgbC4xIff>a1YHL zG+{5!^~|35jaLxpkSwvq1oxoIEAFA_kW4gTFX~h2gL^1CB-?EubWK<^X#eE^qm}%l38g;PE+!hnuL+iZa9*PcGT@&`=-jio# ze@#RkY^SI#Cb);zxf?mf8)qg4^_T-Z1(b(>S~#43>eop@XjX9V%AAZ#&lo$5o_5-UHqZU$ z_Z$%RVmHbD9^;pS_=ObcOTux_~Hxhwz~4?ov><+-J&72$m|(xz zpC02rks*(dOnKHo*o!PA=X#7E4uWhX6Kyd;Mv`Ye#>XFh-ifQ9`IrM@->Y6>({zQi z&O33j#wlO~W=<|-(2$r4*kT>D?%pu7tGE$DD0 z>_xRHeT4oNbchCRF>%g69!npgs3kRM!d_I((zyv+Ox*MA=sva6dFXFJhiK4*y{P_m zUWNV^bjZwYG4Z&UzfR{>=x;%XBVjLYF?H^S{uXqI25m9%-WR+^=Wgh4L5I&82zzlG z+p7i(Iz)rEnE2WIy?R#}rYSOgL5Cw@FTcX3Db%!}Lo{fMiCh0ee-Cz@L!iTvuot7P z>ddInVU8*-CWwb#dW_KDf(}Q*UaWfEGD3d~I?UBgiwV{Zz4RENzXctRguTd~x-EtN z7Ic_dk`@!}KYHmgLVpW790_}o({<|${VnJa4ccOYJVq})##T`ab9YnQ_ zu*C%5=jR?H^tYfxG-$$JtVZ3!Lw^f8WahS*V4av(j}iKt(cwtgi(RePMCfluhiK3i z6YMwp(_@7GW_0+hfv^|ZS+AndAJt$X6Kyd;-jZiMM(B@W4ccOYduY{<$n*_590_~*71rwDChB0T zYPOi*hKa(u219=vbckwA*o)CtJ!e$tFh`XZ6U0L=J;n#`_n6K5zwYTrm%iuxV_UAZ z?WBA9>8IX_RUrF2@u48z6U6TXVT+0EsR%tyPrBYiHaGj_4;=mRK-i1jB>Q`eCj@b; zAny3y^N(#YkzE*jj9Yx>UYkqreAUf~fv^`@S+~BM1o6*7T44gonD*@HIJLe zw{ukcmLjslYL5~6o6#XNH(@VMx7v@;-<+#!i;3(^+hc_OW^~97ny?qAbmdj(Z$^h? zi7h6wmu-&``diQ;8Z==qs!i!5^tYfxvVGsuJL&S>?2+4Jgrb(zpb2|XHB09vY%!6& zg?o(9-+~Sql?i)M{p-96{VnJa4ccNNyAk&op}z$kvbrYh#Vw}JT?ll@4%%WOyBzlz zks%8@M1v;m#ciyr0R%cE6Kye(-JyGo$n*srqCpe(@+)kbAkZO-vc*L9lirJQJQDUI zc2#F$pu-$hS$a2XzDqpx(qn}F7Ic_1Pr_cTVcjxVD|DEvn-&wS8+z$6LVpW7%pFX^ zUgSdEmO_6EI?OCdi;2GfZ`{TR{VnJa4f1Ae z6Ry71`@`eK9V+)vx9ml(k-xh-*odqKX)!_Gl4m_e z=#PrCknR4~zE{1%S{-aeR<(T5jRXqY#W+EXk?3`>dvT8BXs0Rk*NCjnWuXpsg1TGt z;2w$&nYq7ZFV4eSb?%|Ly0)0${!shDJro_XgC^|7xn8-zJro_1CAOI0=7e7QT5%6W zhiK4*y{J!_)6>K~6djW7`DiikN zzL2NVG;t4&I@mO5i-~@}&hv_UC^}?yP1uWjPo9PKi}gAU1d6ZY~etkuCy)WKHOY%#$N6NUA>+Qw*= z(}cZ#S3cUlu(McU=n4Ii)(-$N%2-U3$tX@w$81 zHC}dnkB5Hf!kf8+eOTy9*}B69vFkJ+|9hH#=`QCUf8nmbf8m#JqYm~#*lX86s>Qh0 zUH|C#ia-3@7k=dm>PJ5iblN=QwCG^pV%+qpuROlz$G-As%){TZ*RI=Di*c_Y{?nGQ z#l)`De2W2b_Q$?*TVj~77qMHHj~0Vb{o5s-u*C%NS_k45zVK4gcv_5ey#=C;J-j=Y%1f4fqXX_T@%MX3har|j9OxWx4+3&8!Fky>{ zU2pmpBSv%_BWp2C*lX9Fuf>R2?}$B1bRumXg5$e%45cG+&)pvh{e9xh7qu8B?6vC| z*kYjAP;Mh^F@YB8tlVRK<*6537@2ZF*o$sgt&d`h@xOzJY;1%rCeR-pqI(SV7a4y* z?0aqdLADs^FI3eC&OQ3@+&e5I(K=nX{Xlug5A>HaH({?` z7tS^h^p~q^iwQa&*M6YC&|#ao3477Is`Z0xG0j&9l zpuZ$+F@gRvkEaR!r3Ovdi|?1tP1s_B@0ZRQQJxGY?8Q1UN3v&{AoBFF#RThA=N0-3 z9k$gqVXs}c-4+A=g$^5GiwX9d{ptE3Lqdn`Y&T)AUH_;SgDeakHo_JY^jXi4MKztTdg%=FJg0Q^!;E|p~FVlVuE;8&zX7X@Iq>o z3486jkF|NQx}n2H*kXcp%R5SBN$g_skcCii)uztCYLY%#(9w~o+lt+ttX zK-i0%rnXe>Qgs-WEhd`&=xp6$Y!!7t*bDu&es^uHOxR)q{k2ZlEyng_XfaIK3;nfz zkS)gc^l5}GCeR=Cz0U*vg$@r0d+mA#_S_AE8!T&OiwX3{J*CG$e~~E%guOWPxvlm6 zK!1^qjj+W8`s2RUW1zpt_yc0!YugX9%>(^~sv1Eh<912(k!bhEwjbzkjet(CUH8fs z1O4Tw_AN!AznTa7%bA<7*RBg^i-G=fb!{<${%SwaANNsq(1g9vU*#40<30*uiwX2s zd9}Tf9T4_Hf29xf7s_pfEhcuo=~IK;MGpvj@%_>{-bw6PvV(nmx9M-Eb4HXWg9&@F zPIX>EFniX@789&fomc3O`{+p6YyUm?_@6!J=n>~V>%>R5y&BO7xx4Fp@uX9#gMG`A zp9|uVL40J}K@#PT1bsnTudSft-wQwGQAfY|&Pxsmd%0>y$B-bN8N?+K!xj^CL}@+4 zT8y(la>mgWo^y?(k+7F<9}y#nYXreOY%xKfme%{M&*RFsJGv7UHMu+eeh1g z7887*pTEDwxK51dcVlG4Fkvs>2BTB#FJ9y5oFJIFEhbne=G9}I9V`2?SmBYdmv6Px z^wJ>S9t5MZ#RU7!{`44UMTVRcnKBag^6h+@ekusEkxaD31RYn%%pT)sA9ca)zVP^` z9}xRq^)88jvnGg(gZOyF@QY<6=m*nd-1AWvT)0L+rx&Lyx17G`rv>rF?Wp!GMbI0k z<`Mck&Y7FAm*0ug6#6?xhpetGCg|}~`w{v(Mu#I|FHRoR*5?uWJ4T0Oi7h7RRaAKu z`kT?=NZ5-LwDb}Bo6#Yovc&{Fmr5U@ra2X5!d{%NXlJLv9bt1N`U35rv6Rcb7wbf#T{$_MI683VPZ*_1+ zhnXdLH!#8ex1M1wM(A%wha+Jx-#%I$oY5hpvc&{>+_$->cpwtqxMv=B$JHVi}3n z$*}Et=#R>IKu`zM%kQh`h!6xiWK{c>BB;AH5ALBka})ORJF(Tl6X=lDwZ#PIVeLog z?*uv=348gyJ5Ag}qYkz#vBd=Upvo)mq3DpjGGQ<3Q|W_yXw<`3GO|0?s5-Bhs?u-z5H9MRtJyJA-QXd3GQ!IKe&gY!;!F;f7{mT;8E1U zR@H1VvFl6NG#L6jLWiiZhiL;;IIezQM4#w{YJ$dr+=7g{fDrcN};>joe`heK?s#n-F-6n|V2Eokzq8kbN!Sop4cE+j4YXo$9aVpe2 zzB`B~ZAZ0lDT3ZOHILBWan9U?y*S-!KOk~-Z81TQpW2Vm-;54fT@&`=l&-uA{mtl* zwX($oy^1QYLVq(l90_|-ZAu@ZzZo5(C|gX>bE)(Zikee{ChSGkES;OM#RR>hO6Q@! z86BcQ6ZWF|*LfBCo6#XNx5WfKuH#G z(cwtgi`&>MVJ}8o z)j9Mxqr)6kT1*hH^{8qwLVq)=8VP%`>UGOtb(65g1nbs%ZM7JozZo48!-T!ap1LiC z{$_NTS&|kL?0@SS)?$SIW^_0b_9Cb2)))Gl(IFbN#RPfWdY`ozTSXlZ_Tu||ZC3|T zZ6j?>J}dQo6#XNx5WhO#JqZp(BF&>N5Wq0H+!|KgEKm0 z2W>IIezQM4M(B@|`hc((*;%im&>z*H5w@5hZ^^SBBlLHS4jGk+eXn|jwK_;uYcuzY zZX{YK!?x$4KPu+|0i9l)BQ=lE-wAZcsP-*IPJn!FgEw z!95fmGAa}H;#{x1;vR|)$r4*kaIRNgaSug@BVjM=Io#RT_-I zCU$)Zn+8LFN9d5XGGQ-9TlJiKC_2nhrNspC(98BLx!E^uUKo8q&)oKEOv|qG#aX9R z2m3avQ-b)NApXm?A7tJ?Owbpk_1X%0n*P6sU19U6=mRDgzTTHOu>`#yJ{K$}hADJ=|_9EBF#y*e#5yVx3AQNpdLB|#HtjD(oGdE!`PPf{R(BF&>SzTL9&}*yqBlI`t4w|qRr*!32=x;`cXwViD z^eU>n3jNLKki0TsFRD%HBlI_;L$ci#6ZBjveT1Us)SwA_Q8i2FCTuZ5@2Jvw=x;`c zjLL+)sQz_ch5lxA$jogqK@Y4tuR?zdIvfdmaf`{*wVk31I%LmnF+ne{I(I{V3pyML zdvP1fGe7?J?;y}2in7H7J;_?@{ z7o)A}%&5>|jw&rCh=*Rf&Y3wn90_}|>UGNq{VnJ)S2rytSU2?2V}$+|bT|_BB75q# z6#84xAsV#B1pD85hPAZ{{mtkw^D4h(FLJtWeWAY@9cH$t#RPfWdY`ozTSd*(L4V6$ zd^JK_x*^9ZcD!V#3qr*IX(qe*jVqQH)=x;`cBVjLg zwO$jUKTgqw9kj&+`_2CJ7@@xz9gc*($j*8dh5o1p3z=w(3G$Xa>oG!qRGb51->Y6> ztqxMvmaK#Mq8kbH(qn}FsGJ7`buhg+M`|9SKdN&Z)xM<&&XJl2_t2cV343uK)_!mg zMTe}eEhab*Yd^S$<_?;$7w39rPy82EL7+o4Xp0HX^~x*mq3DpjGGQ<3Q|9zEaSug@ zWV`T0 z%hka?qVGCi{B->LqI<8qKi(4G5QHrz=p@p5Z3P`YKp%Mh&F!KO=r<08z1YpVExja& zTL*E~AZ#%~f0NcTti||_=$-kdfB){Is|auBwdV4av( zk8z7w*_Xx&vsNbT#c9Xx_87Mh;uS%#gSMDpzuBK2?Sx7ea7>^0! z_kti3Z81T|74odd_})*Sed6E#@a6}^zE{1%rs>&1d_#2gykf-gi*6)ZC&RWM_x<$Q z$7=+1dT}b$Jf09lj%wdh1if);9-+S(9Wrwh_TqG_{eVD+tgbC4=_ycq zotv=51ihn5=b^s^9Wp8t_M-aNc@_Fw&>bwg5E$EQ7GGQ-nF=(gjBlNeR zLw3*>6W^9S4qNVq{uXpdmYA>?x3Q`Qp}z$kl8LsM*mW{&F(T6!bT|_B@+)kbLQM-g zM1!`N*mW{&F(A<4NZ578As4J*rxa(BFcpM#5gKVcjx9e~rl1O^XTE zt@YY!F+zU}I?NqR!d~P;-IhXs3pzxDwwPf5ThFi-BlNeR!_2Gvmc7X7y7h(r7Ic`| zo)#12aqE57Vr&()PzU`jd+`-)J$FsmVuJ7U^R5og*NTzl$&lZ&7jt7(dW_KDj1JMD zEhbne=C!MXGdj%kD!*kf_K1D&F+zVcI?PivEhgA+_GecIXLOh+brSX>JL^>x`kT=q znP`g%@|HZ?)j=xG0kQ8@udr4JscK8s!FQUU|hm6djURChSFh%AB4i?xEwNLhQ>ue~ z8`YP##9g)>B+&)mGC^OE)@v*1X?jp}sk|`yfR2Q{*v+~v{lu2IQ^c^v1pQ4~&#)Hb z_o8>^jXv_FHV+f_A}j0G_nIKSCx{zH3|malr=|5iYcWoJ+|@VyIc*^9#rOGIUtJTn znBe>Td~SoxJG zLHu|S?4T_s*l+fy$9R6^6qzy-_9EBF#y*c120=D54_i#oafLkVF~0fC=bgATdUTG& zzE{1%rs@AgH_y)n@%<6QFS?PSA54#N%9+nQUL&B>i<Iak(J=aXYGgOA++OsdH!b(BVkfi`!V9`O$wc2z1Ci zY%xLSG4#^)5&B!u;Yiraudw*r(}F;UXwViDyH1AfOoTv(BVjK_Th%%Ax1hruRa#6C zul1;EF_<~38VP%`>S(8*SFA2Xu5MaPux_o_R*Mn(TTse&-Dr%t)`djwmE7*2*5Y;xq7887* zpL_S-vmPV#cZ?31xru$RdWE$*NL5?14(5w) zBw8oKw&$TgD(3+~9ZWCIk(x*7?*uwzRQr}9I7ez8p(bts2ZX&i4{JXla&>Jn!FgEw z5o$U@hwPvUdvUH;UO{A**kXcnz4D5CC^}^3ChSFh%AB4i?xEgfDVC*`ULbu$Nz9tqyL`Av?*t4V>~;E2L!~^ zCoxRyd(|s!nw}EGB|-d`ApD{m3HrhG81xujBcRiZQ=#VZb3x>&_AN!w8>i+GGoN$j zChW!OR{H^wt80r1di>OWg#Ko9$PSvY7pHXP6+~u%0p6E$EP$+hStZ z$*`Rzv9b#~M1v;m#VsaJ*J%pq3^tYhH%=WaHAdg$`vle5ksD(P{Z`q5lVB6I}RNDw!Oz?ev z?&ogkZ$XE7GUT`H#oSo0T^(G|VV*u|F~K@9uWkM4C)~p7`djv5kJ$HJ9h}i&o}y_n z!G5zpJ;wH=UdR%E%U~w8aE@OP+1#(JM}iVPfB_USX{cQq`8MgZZKx ziPp)m?Rn^r%6ULg2h)plq~;O&qdK=y?OTeV?$$gwt8(Th?8SMQt3FK-=#bU5#RT_< z+K*7v5jtcCP1uWbJ+o(;AkZOMVv7mxL6ukBL(w6bXu@99r_AYT;vR|)$#z>zP@hU4 z)WB4f342jzQ_a(4!WI+M+0r@pP;|(sOxTP2LY^_x#62|XV4JxuCb%!udBqJQ>R>zJ zOxVk>uvP~*Q3u;8YKsZ(J$3GKQ$mMii3xl871rutBha8NCb+*<{ouwIb+A<&6ZY~e ztkuCy)WKHOY%#IxOV~6R`rDvGRBOUs#IAbIsL&xZx5WhU&`Uo{o)Wzp?;m|Ye|X!g zF)h2!7e9PTb+B)vIy;CT3F4=>{UFf=-!eg85c@mbLfd6Y%xKfme%{M#kfy& z4du_#K-i1#^R+$?6SkP(`~2M3ie9E)ijgrY6ZT@ASd|{*2ZCVstd%V$SSRMyW1QQ2 zvK|ojVpr=m@$*4EEB1sPw8aGb&HnTlbfYCx$PyFwBG<^qK93&_;>mOl4Z;=^bX+0N zdW^r1Zl0$`kIs?U_o`ReG+i;ed0sn+n@0@4=thEmFg?bnqbune0i9l)3N??*M_1Au z)xM<&dgIhQLVq(lWF98$#pzc25&D~Rb!{<0kDuC)&>y{*+YXwr7pHXPRp@U^xbchCRF+m=qmwqO0 z6}3L91j!dls4f^}kEJx1tn zMu#I|FZPJt?J+`sGdg4kZ85=qvp+pX=#P_nAxliyi|njdQRr_*hh(BHCdgaztj7rb zQE?84eXn|jwK_;uTe1%3i*6)ZC&QLkp+73;0YM#1FV2ygN9d30+(xx;DS~sP=D|G_ z9Wrwh_ToIO{oo#&t80r1&coUd?xEfb zChA~YD_cx(U#Rmc^tVBWtgZ=r`4!gc;07JCgSMF9-c#ppWXJ{`qCpe(@++*>!3{bj z6KyfU{jKUpWcmgjj)cAZ3Tt(66LqjvHCs&V`Vuw`hW<9_5Y?Kn7o)9u&Zy8~jw&rC zh*$OeucKGv`=Sr%Pew0ATXua7fAEy*VBbbXuWh;i~+!hnN-t;ZTjeAel4XbOyUhFEn+hc6IxNfc&#J*+Q!9KprezQM)&$r!ZH)M$k zdy$3YT#xat$SJb%%phzrvFkM7=5ed&&G}8yqw_%nvF}x{u;{S5CC&=MFS?PSCupBX z#5lfE#25+a^x{;gdC-+KN40M$g3hPtrN;>U&CDDPny?qATkQwkRnZ}yWaF|Kj?Og4#`9l_M+O9KIoi{4$1a?%eI4ke3y>8 z=%ue!C~8R!ny?pDGu1pzCTuZ5XJGWwW6%d19Wp8t_M-aNc@_Fw&>=Io#YFE2p63-k zk04ff{)llr680i?RcB(L!yHvvUfnwa$9IX>IuN%Q zp}z$kqCtPlUaVo=GFV-7hz4yj!Me3h$}L9dZ$XD>(1g9ng}N<;{uXqYS&|kLegC5) zbc+%CThL)`&j1sDqr;OPyWaF|twMhrbVw$euov|y zbGmo1M~7tlzGd6NKEAu_G~Z%S15;5Z?B!QjtAjhj78BIj(mD4~bjYYo*o*r@o-xzJ zJv8cIo4G9}cAe(iJVJjPbja$Ou$Nz9tqyLY4$f%M78Bfi>fDVC*`Px-Xu@9H->OP* z8;d$Pqd{9taDS`%5t+V0hiK4*z5EJmb#N1PuvIl%OmM?QVO{6kL(w4`G+{4dS3PG` z=rBiBmijL7s-B-b>qW<`O)JryA)owx$KVgn4~8p|2z9G{oc`KcZ}{4-}$oR z`Ror}`1R^wkHtjxriY%UTiy5E<6pV|?_cjyUge@kr(|n%?#GicmE4L+v z340NnE+0L{)q}XzmaxSH@#s|AV_fY!UVi-4U%B9RIgk97y|VjQk8!0S9=j!MF~Q!@ zaka;|W9<2xo*I7}bj-tqy|Rm1kMTo6e0WRPVuI|Ub8L_C(TksV{D|MZdy8ShUi9Cg z+fI-1w<2sYLFY|6;Px0#Kj%ru@u$TwVK4gc&^xEcFky>{>`mWe#2k)eWG#jXdu4aN z9s?p~--tcSwu3$2rDG@^iF=HTLx1-@>qQ5Iy|T+-kAY%Cxs9;J1nQ-;a*y%EU%BAI z$dm)ZUUa*ne@&0^q#z<28)1tH^hby29s~V_4iAWZuig)`$3TCfszz|`(Nzb_NYLrJ z$3TB;1ax|#nVJXs3mvu?`<5cmU(Eyk<;+dkE4y&^d7!^sU0Y0`zuFJ<7dmXCGGQ-z zSJB0($3TCf!$#O*0{vB9p})*T6ZS%Xr4NYAc3VuKKRR9a{Xl=IK@;}k`=xUewwU1i zrE^Ba$T+V|*o$>yj(x3|brQCiV4do`LVuyd7Q=+S=v~EL^%&?cbl3=6Ot9Z|?vf#) z!*;ftuvhkv>M>dtZV6jVkhiKIk?EnsR-;VVD|=V<7^o?9*a%xpWT*MQ=MbU8R%=bz zi`bkRJqG#<9X7%i6U0+JkF^RNUdW!CuvhjH>oHi}&|xENF~Pd!t!A3gU+D0d7$)pR zE^vzX80ar_*a%xpu>YLHeXX{cctF^ToTj$)7~5=bge@k>V=B;|1`h~(p+9P5kFnKY zBWy8&{-}#R#`a`5Anb+ysP#PtM9jVswwOSF)b}0({e=z>2z#MF?kqh9`r`)64%%V@ z{c%s}G0`m1@Mznr-Vdu12S9s~X5>e^xg{ndV; zKklQ9%7neLn`n=L{RmET7d`BP+g&S&pNJTKv5W-$V0w&i zefR|zt`X4b#pzn}xb$HcTzK>CsP-*I&{wMF5&ApMnVYZ|ibZXGtwMjt=#bU5#RNTm zYCl4M$LMe*?8V80+Io!8-!VEQOKdSgucFGU(BF&>N5Wp5ps20K2>s3IkWtxUf}TsI zk5JT{8Z==qPFJ+kW0B=x;`cBVjLB?N$e8beLI^cLNjbKYHmgLVq(l90_~*_R;F#j1C!< zEhflg^wMK&6?H(^3vKeXJqkZ-;53!l?i*X8mw235&E0aAv3qd1nb1S zdW_KDF*+Oxd$FtRdyf(NJ4T0$$`%vsH~Z6Lg#M1v;Yiqv?5r0{=#OeJlZm#NAaBXD z9wYR3Avzq1eXn|#v^q#to3jq)i)AFxOOFxyqjDY))WP)fYbpM1!_YW7WK{c>BB;AH z5ALBka})ORJ2ASx1%VD(U0Y0W9@c(@{!XC7k+7HFyVJxyH0of>5?f4g530Q49*Pdh zD--sjK9xSWhejQ2qq4;W^{Mnh4Mc~`!-T#3`-k0Kv=O$Lpw5=gxrd@dVwkX(e~%LX zHDD0vkeS%Pzi_Sm#k*_}PfUp-?S+~9y2XX5l zekEeqVuC&`^n>X!-u{GhkN7hZ_Tu||tyReFqv z2JzM)SSwphuujaY$GByz>`P*WN5Wq0H+$7%Tr-GY4dS^G!xj_lH~X{QkH{%9g*`W6 zFS3wq>@of_2(l5v787(_Al)B%uU#f)2;RcB3IWI6Li$7{RsWd z=#bSlVJ}YU%B#@dj1I{XTTIZasPZcGH>1Omuou;)^bz`-(IMGxiwSxzl|DjIb866p zy{MX{a}&0hpm$X1JoGoCLq=u7UR3`&uR?z_I%MXyn4kw%omZj186A#8?715mGGDYk+fCSu+t^+;n9(6wVvC9FWY}Yb{$_MI687>dY??w%Gde_r zwwTCHhCK!ZIvfdmG1{ump}!d&=BUzQf_Uhq#|Zt+sA?qa#TwQvgVjyK789%+dg(Dj ze=|BHh6#I-J#||O{mtkwvm`Ah*njlWV}$-@bT|_BBB$%t7y6sgVP<<;OpwRurN`JR z>VU8pUm?z}4x-vd*kXe3^K*|8`kT>Vo(%add$AgI3lIIx=#ZJ)VuE#IUOh(WZ$^hB zVK4TZz1r2m86BcQTTHOu?9X;T`bpjP+=RWz&UzJv{-_3xu*C#oa>cW+(XgfNZ5<|lsO$;FoHmb zWVZ4s%p#F+n`^(qlZ}^l#c+ z{-M`6I_sx*kXddAoPQQj{lzX;aAwa_9Krw zAne6%)@|vrLA)Y}Cq)cfOwiwielR`8f4lLeM?d(nmmHlv5cVP~>(+OE5DyCCkwMsE zf<7(ugXuADf3tTV@#j$kVK2VV*ZNwSu*C%5=jR^d%ox#mF)~JF!d|QstI}iKJ&0cm zf|=W5f^}kEJ;uvoWm#cX*Mz;;Z+5rGxRAXFf<3pz1pCeY^cY|LscRhFKQd(`>_x7T zjXlOUL{5>7kB%6&n4seddDdfm>TY*Gah;c3bwlo&*!QYe*ff18h;IwxF+uo6Hxl%N z=`lWWx4R#&5zy(ysZjIyXb?H7eM=D!j2=}rkI>)D%$bJ?dvUteeuVyJbja%3VuBt& zwI89s86A#8I=ipQT^+@3jNLKkeSuot(O zI(I{V3p!*6Z81SFuR3=_e+xPs343uH%QHWIzZ(QPM1!`N$WDe`ACc(`IwW^Z*vqf5 zX$mzh=nxIsVj?>k_81W8a3t(S?5fU;3LWOC(qe*m=%vSC=IC%F?8U0rEhF@|pu=3< zw3uMs&`XaI`diT9NZ5;9sM``*f(|oF(qe-BM=w1_=x;`cnTbi*i=3`oU+8Z}hnekZ zF+m=qmmXuQsF^zGZ`q5lVB6I}RNDw!Oz?ev?lD4tGdj$ZA-`oW=Ei#M>fnqH^YlrJ z3D${u^%$W)PPm2D^|$QBuGVWJ^f#kJcF-0R>^J+w?Hp z?OTeV?$$iGhca{KVZvUVhqWKvL(w6tYl{ia!`ct-q3CcV?8UjB*%KY|g2*hf#RTVi zX(9h}jiEhf0XRsD!e-=ITs*Mz$0$-&zOzk)Tft{a|{GZ4c1B4)zfC;`_wm|KD{DZGZ6*9BOSnFU9vF}x{u=Ni1YXtpZdW^LW_I>=#MEe0L(|F_P)2OaE3f?i&A?yhyPhp-p7v8o1Z9qdOUI~jI;(4%_nU=Lw0 zzrxl#*pCDq)VOK(7;7EuA?)Q>*fcS!v4j0cFhUg8W2|+s&rzk9Ut!a<*1>)xSZNg2 zW2|+shp?AlVbiqM!G0vj7!=lHtaY%5uoo(*Ti;p-`;j2?(Myl9RaEPq?QhwO?_=Xj ztq!8vM%ZG4@AGqyLFepiZF_o~u$Nz9@y|b2I@lB41na~~^cZx`9y{1W*vqf5xKpom zupbHbn;q>j=$t)vu!peM{wr*)gZ)U5k>qcWLFa5T-aYRj_Py#Aw%);hjX+^N###q^ z2vnM0euc%~6tdF6ek7>WHIKCp_7L{+D{Q@k{YY>g)_$yYu!pdhUt#MV>_>ugz4B_U zgFS@3s86MjwGQ?pL47KHPymBSzg8N%mhE{P7I@m+l%dfEY4)!CF zeF?h;*E-lk*lYiFx7NXaBp4wI>oM*f-5tO9z%$~X+4f$IY03T;r(bRV-8N14*b=u6 zf)&mChY9+E&<_SW{wea^jy5-nKA%PWkG=YaKmTDM?8W!_T3=lgwwU1i{M=*w zT#V=jF)~JF!d|QstI}iqL=fK=1UqPp3D${u^%ysam1TulT@&_VSL-$LT|vAp2zJmG z6K%g^-+PSDMNW|^BVjLctzJd{7{tATU{to4pce~y)?++B`e5HJdUP^#6Z>BEZkwiO z2JyW?oCtzSmhZlipdU<+@$1oJbd7*cFHVJ;$1etvquRF=L0_qwN9b=xhs?u-y*S-! zKOk~-Z81TAEcDXn5&E0aA^Ty%UYydESE0W-v&0q?^eU>n3jNLKkR3E(FRD%HBlI_; zL$ci#6ZBjveT1Tx)SwA_Q8i2FCTuZ5@2Jvw=x;%XjLL+)sQz_ch5ifqO`)a*9il;7Ok^j+9s>d$j)c94UDcUUp~D{yH!UVux2Bh@g9|zw344(Xbz34!&|zjtT1>G2=%vpi^tYhHk+2sz zUAMl_-+~S^+tXr#JVq})##T`ab$R(cGdg4kZ85<*F|QsY^v4OeuvRAQ#jdjNJx1tnMu+U6EhgA+_NT`P{c%zs5cVQF z$=@C$^f#kJMrDf$@|Ha7F+zV-oHlb4`(E{KYju#Swqza57u`spmmVYZN98;qsDtT6 z4X$~F{;1AvRQr}9sJk_fP}31QWCu;yi}SGd10q+~789I@wIAF=qYk$HFkvsw^~x*m zp_wJNnBZKmyy6~;4%tBy_M$#zPEQl}P;^MP+hT(HRQjL>rlL&Pi#nTXj*f*QY%xKd zEuC`@MTd;aguS>gRtGoekWtxUg8N(5kI3{5IwW^Z*vs#>RtGmx2U}IM#YFZc>>3RH zZO|dAHDNDeqn&=1Fe-GIqe_bj;-Qxw>$dcYE%BE@*kXeICiH`0gz?*`=$(15 z=mYxhfv^`@S+~BQ3F4kXd?5&1Owgx=elR`8CDApMKc626d+~j~)>qerEhhLrKld2l zA0v8njEqs4uovsZs`MB?7{ud(VCJ@%V4av(kMW_{3s#ubHDRx|-@DhuUkAZ1vV*pm zV87X)9)p}BQ^*n%_96?(#y*d0Z3!~b787(_AVwl+Xs#n-F%|YBY zh)+ZezvxDSelR`8+oQ)Q#K#8$I=wg*Y94P0B1g4vDS}Q^HIG=UnYCi(ChXNtx7~gu z!Rp##g8o>wAECcFchH2rIHfDEATmpAF+s1Q%B#@df)2?<6ZWFols-a#3pym*Z81U5 zrP46uoqRcbZ){H6Lg3wornGwbjYYo*o*34=T+!$L5IxT78CTqs`DyVc0q?| z(1g9X#nibQySJc2G-!(ndU@5k8#%S0L$bt#y||6-Rf7c`l8LsM$WDe`ACc(`IwXb( zd-)YMO`)a*9il;7Ok^j+9s>d$qCpe(B6d}0MuiS@RB16mJoM6IY}abenI~Z{*063F zN#yFL#RTit`qX6|Tu@c+U=sEs7wWb|mOx~dq{RgLk6!vbLVpW7%uGzeUgUJ$`a*vT zI?QZOiwW`=z4RDcMJ?1pf6HEc1>3F;qS{8-VuJ7UbB_`FThJk+GGQ;~#(M4Q;DQeG z^ht{e)`@xb7@5)@zE{1%S{UQ8|~agGo>a(~EN? zM>|cSKdN&Z)xM<&>Tb=0vnpq9!d{$*wI4~ay0(~T=izQYLQULc+76nq7w39r&on_~ zme^u~bG`D4dnh_26HVBQ`c(Sh9*Pdhc3VtPpGqIpz*Lk8dr@ao&CxMkge@khv!!$H zq3DoNnXni4g*;>8T^mHy!8UVSOmJVQ^D0($gAUQ4348e!)?X9o5DnU5f_qP$yOC48 zab~i_guVOfkXNw8cdBCF~ju{cX@8 z8Z==qVplz9ROm2Al@=4kLoYqXS_gY9+4!M zdkA~6n{``S>tH_;^f#d&OpihDOge|sx!2#a7g<@izO@ea#4tgh7W%>T7~3A8dmZc{ z?8Wzq!~Z``CTuam_xZWUSnFWVx9r6_F~=U`2YSEMO?FsKiwV|=dG#1;9qjp*z1VN| zy~kMVU_TP2NgZ)S_LKN0x ztaY%@QKgq(VbO;-R(I@RKN74o3hOb}I@m+li|nb}(pm@mksxDGSdT#_jveeF?1c*I z*0QLHzizK4Y%#(2`MJkf>tIg|d-)YMO`*So4)!C#Iy=k)9qb|OMSUuLL>)ZnU_TPnr_u*C5LHnJ{VjX>6}G#JHo_JY+(S#} zYaQ$vmA$wx)Ooem!G0vTFVuOp*1;aaUVeqGcd#Fc>`U19e652$guVO`U0^vDU#J!e0BYyR{DXBf$u(o_{!cHC`NjK)>!i)xnh{i|7YwiwQb!(&4kmxHP(k^5>=l zVK3Ch*ZK~cuw{?fcCg>Zh!Nc~Mt1XvVS-UW;l(`#yJSCJv)*7*ZrFS4*+Meo@XWTGu5=(I^@ z_87N`-kevB9-aRuVwl+Xs(0Ho#a^GdN)T6#7*w)+_l*QSL3@l_$3CnP(CNjgQ1c+4 za#Z`4BItZt^9cRTtQ9jiVK2YirYZC{qeC=kiwQco)_#QkW^~97ny?qAbmdj(Z$^h? zi7h6wH+^5L(BFa%(Vz)?QEf^ep+EXmHx2GvdIx*HOGn+z{P7@@yL zWHm^O3G$Xa>oG!qRGfuu_qX=F>fP4rAXRP2I+!oIkw9TRM(B^qc|i0!*uAL1Ioe)p zb5#45-oc*la*otIxQDV<%-n>%{BCP?@CY5EL0e349@c(v4@HOUpb2|%u2(K_4@HM$ zi7h6$IiZ)nR@_6;AsRGcFX~h2gL^1CM1%X5`Y!b;Gr!eA?xIamChSF>EuB*}ld#1E zb+&ZQJv8cI)1V1^abL(&X_`WRo2Y|LgSMFH_v<%q*NS^6I%IWC*vs#>RtGoekR7ze z1oxggcO$1Z=nxH>u$SL$tqyL`A(?243GQ!IKO)mN=nxH>u$SL$tqyM3Z!~C&iR?|^ z^D6YWL5Cw@FJhyeewHw*h|#L^zNL4t=exwKdcNAh{wbfTe)RFbcYT+h{Hb`|t#+^v z3tcH&ci13yz3JnBe~k|ILD*~8KdQx8?O;C;blN=QwCG^pV$d=4po4u7_S$v3YBA{l zdCS z`(E3AkS)e)2m2MG^`>uozS_aQeQVo~KD_9%Q}bBuU_THjtLCxV!9ECk?RsjqFRga4 z9|$@g*M3Cj-op;|LD&n;w0@8+#%c%qfk1ziSCNT_9qfa!7y4`cAX^NG&|%A6TTGz8 z(nl!ju!DVk%U*oHbZ){H6MVmP&WIQpXNd`Wu}*o$#Jx*|Ehbo}I}b~qJ=PC8*au;+UH_;SW3_|*K#;dt8Kx=f;9&>*Andj4UDaYlRXglp zKM=c4^G$;g2OaE#uov@aT_0PF)eiOp!3b5)*E-m5N0nZ??qe+mt9#JFejr%syrX=L z4)#IVYu81s#aQiNKM-V0>j>S}YMY72@4W?O;C;=&yBtZ!uOo*axxiwe1JlVyt$sUm;p=`W9og zgMItfwjX_X?YdXC|9`cE{Xn3sn#XDf`ylMK>%!T-wA#UbAkbgyVBhAk+QB{ud+oZ3 zwiv4&><0q>01T_g!KjQRiV8Rv?e4n3xqs3V5U>~Eh*Z$3NwS)aYuuiN*j}aY14?EZgVXyrg z@@fbBfndMc(H>*9gMAS8+P~?qcCa4^IBj2m67buT;%rwS#>S_S%0zu6D2=2zva~e%v{Fz8-Y255iu1?_E0g9(J%F z2znJ&UR@BqYY#fu2VpNx(9*|h2m67b=Thl|uDz%V4fS_S*lA7yY9T zI@k}yu9IP#$7%=rAndjOn>+eoA9S!Eh+QYc76am-gMAS8+W!sYY6ts)V1y{F>ztV% zbgtxtstah*uf;yO9`!BE64)y~_{QHNm(ZN1qn4r#< z&i^l6?;iEvR+aZHjVMSW2-HJp6&mjdNCXEX!u$QgU|0=`jgnMP34+lcLt?1PU8#_I z8Jc!95n~Eg<<=+~q8y1;ly`5dh&D|kR)V*Pcxff|60B8=mt&u2uD#~^?6uea<2S~6 zne(&fUVE=+&oy6u=R8vfdlAgyZ$(ZV><7ZVroI`+@Mer+;^+ z4)!9Lwf~Kmr=o*{{XqEq);fcB$;`oC1he+Pxw9Yr!NGnY(w8vym5GCcy$ELQe*>vL zcyzEI2;ZRg_j6k*-znnTH^NV}oj*v}NhG|s zM3?dpZr^%&(^o$3;u<8F<@ayB)Vq4Eh*iWrKMx0c-4zM@n}lar)X?8{x%~Tkz4$;d z%lo*W`tB>@Z6fZiyJCcdeOki%ENXoDOJ8~MpZg31vwVGDt*(OvBP4u%|9nr>_#xfV z{dH%)D-z7&+*ZmTig=_5KPyH^_&Ir9wZ>2A$-Y`ocqEwRx9WFQ*YVvV{(BLAgN%^y z`}X^(HM~Q-Q$~VW`?<}#(7VwDBP8s&;(b4crA`Z~1o+qQBN%<|W*zYjg# z+xB!BAz_c7{ywC?#X9uUCBZCzrTcUz{Vmp^cL^gT>{ZnFmGrk*ha2I+P zz1tZfVb7(m4=HMC8YICicg?PI5{!_rcU0H8^tV`tzAF;U;@nn>^tV`tUO6Kq?19z4 zSJK~N9gYOEe2Qsb*HWav#X9sGWQ0UI8OFCnJ7j5JY7)%i+$Ki^5v?0ALc*S8;d~S| zw9^;s&>AGcEY5AENKK1%Xbmz#BApDQh6(F%B$(yey*vA^tiyI!EkeTete2|uZRNLq zy1W*%{0#dkV|%(mFhau5Exfj39n#-o9kw^vuEi|QZKX(mi*?v`Njpc8@cR$Xu&5#Z zE!N>kFw1+opZcV~#X4-ey+ufPABXo@)YufYxDWDL%<@$n%RXq;2EhmkU*A91_aXf) z)?xcHv}-ZTPoqzF(%)hodgY9e@N@FIY7Oacu?|OqS$;=;yV(a9>#%)ATZDw)x8F~# zv3;oz1hc$5z2|C;ts4Zv2np|7@3UG%`g6xwyxU3av-;c?eb8NPX??IwbR!W?hVjm& zKX=Xp;Xc^1IJcD|{kc2GUF{>C@OPxIV>%%>;DT)NM z+-IAbOCiAs3HRBqbDu-4L*Eq%W^rzdK6tSXy>doK_`J}+S3ZYYhaEB(Sl&nL)a}vzr+!lS%Q&A9%kns7f_Ydv#i*;xXl3*6+w&;Tw^}*VY{mqA>n$xpFi?Z@(lmN2VWllTsYXPdOBbH z-Tf3+%EyX$u86A$KOgJD-z5_1aVWZ!SAFrluCIN^i!PUeV3yxzKP|mN#J7rgvIs^< zq{m^@cicyOj}!4Y)nJ5#on6BFENXn`!{2`KpOIjeukWkX zFEt59Ncj5x`94wOMtAgX-YmFC+c!UV=L`F!Y$6?fX_LHA_ z^S0MM;6UuN`V^+$Uy1lJ5jU#AiEbq9EmPmeT~B`M?Tj$pviw!(>v)!kc31mICqBP< z9L74Nzr{NA%1JQGU$_1~q`##-T}DWx$6?fv{+9LzNifS_>AtU|zr{NAE@6a3dK^X# z>2I+PM}k@IHeDam-x4}h4Ms@VudM4sidvcmNifS@v+JA$BP8q{)paiYE!LqmNP=1J z{{4F;{Vmp^SI!8D^f-)XCH<||;Ycvcru@BP<-6_O*>`0f zw!3N(66tXmHKf1QIvfdR`5E?8hM%r=*q&~SkVucis3HBW)?s^tjbN5{Pd_b5f2(!a zc1eqnNRPv)A^k1Z;Ycvcd%BFY`eWhNO&JxFZG+aDe6El%U5xo?1NTq5R8!U z_5E}9!NofCU6EjxpGH50OMi=X=#?`bvP2t z;uKb=3H8DFiZVhXJr1LWcF5H_v<68qi&I!BK8IR|-ieHmNRPv)p`CuU4o8AnoWi0H zUeyPqt1&_%Jr1LW^mkPsjLu1dS-#ue&wW?cVY{mqA;Gy#|32p@ed6_>zU}ds2YlCK zS4PtL;+gvUqL2Qq>ZBZZ^$#}U14S@G!cHRLwI#Zg|NL)#)b(3G>y?)e8VF`_3M=K) zM7&bO{X{TA!u}@V85TAE?l(Q?`gtGv_REJ11hc#=`>F34B0fvRe-*<>qQ&bq)p0J-T31)E$E9EsJK1+n(IU^+ezWsh`jqlT*`UdTkkzm$-3VWr9mx}OC zWQ2qrSG><^jd%X`OK$$)dmnrK(1F-z^(jn_I=}OhoA-a?W3TrT!HI4p!pSh+$9sPJ zCATxebj#utR?2;U=Owqlue2I+Pz1tZfVb7(m4=HMG z8YICicg?PI5{!_rcU0H8^tW1vzAF;Ua`(4(wiB5M>(DD_ghcuhR-ON?k6NumKV1^c z;uI#QSP|Bt-#H^B(#bGtNPnw!I1yZ9d>(D!q5fbT37&WB7)jG5WNid63 zSSeD|Y8_gGjF3nt!>D1xIvfdRxwh3-*CG9_)?r&mi;!?V>!p56q`%dw8VP1`3e(?u z*@*UZttwY1;pb+()Ed&?Y8_gGycV;(7p$GS4(V^T4%;qi5fXm?;TaasO8Q%^!?qI} z!7T6Te(IC{R_n0s_7)-GeH`9rQDalo>ORP8G0RtRtgeFuBP4u%|6HGy^tV`t?aR=v z#VoJQ&#Tsu{ucGYwS9eBgoK}y*Hvpse~bFy+P-j&V3yyi-&L(4{VmpE`|h>~3BPZ@ zpISruTdc#8V3v2M_iwEs{VmpE>jo`C!u!_ytk#hJZmmOWkk{I0^(id+pu5`I`e2*r zMk1UHf?58qx4jU3@M0Z$moP%Y=b*l?d=9k^y%R|=%l)bCX?@#8Scl&2jF51D z>iTdGw5qH@63lX+ZE7xs1S2HeXS>dQ4z&(_S0tFlDXbKqL#;!voDmW}FZAz~&!N_# zpDqbzaSDq*c(o4w&KV)$b5H;7`W$K)skQqXSh;)4pkq#Y3pd6o`maJFZEmU=l{)9uHW>G zJ1=*<2oCnDp3WCf)4$)ao9;eX#6K4C5D|=!NGC(lrM%*=Uak*#;oS#<|{q?T? zClL=6@nNdL2nqX}glAaP_`pB?gzInp!h2&KB$(x0*-w2B7V(E7{`7@#u-D2-*rz4D z&!WbgUhtr+|NO~7Fw56>ow^PZjF9m4{qtj@M)}3}Uj8H9neU1Ov;3UA##-Z7wT2HC z;Wx+#2|p*VtJZjsp6s{i3H#}iU>2vaQtmIpZ_)3Z5fb68W>39X$2V$+c&Cg6v%Cwv z8|ym$M-kqQUI!y2?6~56R%^WRi(Y>7Cm;9O2V$Sqr!f8f5)pqW;v-ap6WvJI52n_5 z!xz2$c1DyZAIwsI28^4HC3tItaMTiVlQghcqE<@=ES zmi7ioFw0-*zOSUe#X9sZVT6Reiu%5i{ub-dZ;%AD+-F^loQ_gguwKKBTC% zX^;f7+%>z-Niagf-ceoW(%)(w`mRVY%iX_!ucW`#I`qmJAz=@!{=Jg^R_oADmjttX zim}@2JJ;J=twSq{5fbT37#h?LS*^p7V3to~yKb;rhh7IGB}AScfCQEZ=SK&b}+_u-#RQkZ?WgrLIHzTdl*9V3wbHKV|so zT8HiFwg?G7x6n(h!*9?!90_K5FZ9!r^tW1vZI`qN3BUjF42v4l-)bFt9lRE^yr=uA zPx@P}!?xR7goO8Tc%Ma$O;M}+Ag{$NU&XPycS$fp!q@lD^?gWxi*?w(4DDLX^3(7d zYYpjdu@1d*Mo9QMd0n-J^tV`t?F-kg#Vo(oK21n}{)(=CgN%^y`}X^(HKad(sSgCR zygU0;B>lM?#5x!u;eG3UR%=Lq?l=cxpVg31<1b-u8n2 zn@%FEL+=tsNcg+n_m$6~)}ePI31+!JwLPtGq6q8IyPXjd?oVAG?txa7HAsS4oWe>W z!3YWW*{*Y+L#;#K6$xhfywJW%rT83b9eU-Aknnk-f3JKFwGRDsNid63Se+)ULu-%` z66s4A?_4|NY8{RQvp9v7;?tOQ=yfnc!soZ%KeW@Y*5ODni&I$i!K?aUbTvjuq%UEt zL;AZ~hgK~KX8CS=Klfc(hwZLfgoNw$e*TN{YW%ly4*l`(g@e7Sr}M?9{ziAOkGnGQ zP7!Yt!TF3tdK`)_<*$Fq=UktAdF$n^1Hml6&3;Z&`z&gF!6QEE>Ob!q2xj^EzFPfKlVF5|ukWAl z8#Vrg?&vksgOp<9T`)e!_mbB$&l1On>)Wgx{jy zAR{Ew<1lJ?PkEu!5LLxm5qlWaiv^PkCS^i4*ePyEU5=Ka*$6?fv{#NVIJCOvl+-A{jJua?}`Mo-2MCaO8Q%^L$90>66s_ZHS}ax z>(Ck`!7QIDLp$-^)!SRGLu-%`66tXmHMFPnZ==*NH3??f6hL*T8Hh+(5}TS zug%XZ``~IFwy#f%knnfK>#8-RKY!s?KV4pnS$;=;yS0Y&=dbAMH^>Ny^f-+7A^rJF zy|yoPyB4#&*SvqT4+i0#$Owt_IE)(7pF2*}AhFNtQ&{vtceS-}Sb8N-@!P2_qzY4(j{L=TPg=JCOvl+@IQ>F2(0i>(INM5fVPnb$z%8Hbs$O zmiuf|b15VkA>ngq*SXK3>Vt7tB$(y%Li@&);&Z6_V62=G66tXm??X@aY8_gGB$&l1 ztWFcwp*6?|iS#&(8a`WDht?noX8HWqzWJq?@VDJNkr5J}cdVDH5AF1;b?6!-n8hh9 z`ruW4FuEEeB+}zB)*<~})d!<f3DB!1D2ye||!kZdv{+SUdHdze7a3 zt9_&s_Lb`Ekp33y&?_gwEKXtad=cTN>-WJ33HxL9_aXf)*5ODni&L01D8f3l1{on? zucE%Mq`%cV^u8j&EO(o(4-?j*cRM2_Ue-Jgn+DgWK@!Yz*X%l1b`p$`uy<6~x%9VM zhrTNk%yRd)+Uh%({#NVID`$j+J+S)sO8Q%^!;xSXr?66_ztuYQ8)Srp9n|`FS36|2 z4y{2F%;FSQiuAWyhu(>dkgz9Ncp}C7&`w{i!;xSXr!Z+ygmq{QGD0Gq45Nnhw_1lI z!7NT;rTDI_!**A#Z!p56q`%cV90_J|3M<7=*E($PBhKsUkR<%vte09t`dh8T zkzkg0kF`_xmGrk-ht?n?B>euvGc2B!^tW17ZC|x(G0S_ppZcV~Alhzk5fa|V)=OQ- zrl{3@kk?|Cui{wtL2EDwMo9Sj{<+qW{#NU-eHq%dnB}$ksnieU(~!7T4i@87x(>2I+Py%QNB;eG3U zR%=Lq?l=cxpVg(DDF!7NT;(Fc9Xi1)z=34ag!`|vr`I`kVP!7NT;(FZTqp*6?|34ho7zVbQL zI`qCG!7TTuwx>%mVI6w6GeW}ssq4c%uqlcJv)pH!noA+U2nnAngR|L$ssT&+WEkOZ?hg+(8{ zT8G|=jF9m8t@jV@^s99^63pTh7JcxlJ{Vn%5fbTS*!tkrI^ueoj*zU@z z@>hn0>-B#A4!Jwpv-l@}1`hVBp1y`3^Bdj4KJMzBBL0nt=Zo<3Y3C0Tc6tmaWznU) zNG_F+ln?0F4Ft3NHv4Jm`PJ9*@{o7H!Cuu#RL9D9J?XBf@t5VD`8)Cfeb7KK%e%6l z`W{jJIj?^tf)NsS-VA5!sPUWf0QH|g7zk$h`o3EIQj=h0M>KExsPWrc!zb#_-lrNQ zd>5v?T0bX0uUg~xL_A8w14S@GBE9LO#v}ADUZ^MRr%Qraeye`FwT69PP52G&Bb$T0 zuIu;h_fy}8yqz!qRy)PJgaos^3%wg_jeorn-ieHmu+ygZS*;;=mpbSNljO?0nkSVXsu{&?_gwEPvhl z`;h(?>(Eb^5fXNA?e9bSTdYIBK@!aJSGw;j`^s8}-X)BXNN@UhR?^>U9a@7VnB{KM z^(Cn9M>Yq0UDuAfZReLFMXgPPB$(x{*>z5W5fXL=?mCzLR_o9jB*83q|Ngy_ z{#NVI8f1h-bp&tUE2(L<4*hgVFw3Wy_H`}AgmvgQ$Os8LHTUnX^k2I|T+b(Gl67~Jd5jtu}f2(z94f0yd@}BOeKIw0@4y{2(NO&KIvvt(i6t%h! zl3>MSEm(u-A3{zWsi(4=z?!`%*W8S>9{jzu5`p>4)*b^wqCoAMD2t1PW&BdwX@g8UF{>AgT1cn??_*V z&!N_#S5AUi{vNhxSc=b~)?qtkvF?^ZqBTf@S)9V64_2#NueKV| zIY}_fwR=A|;a=PBsz){ldtKM{dOx2z*q0yqsq~}wKR@7e?|zbfcwV>sl%~6>gS{fn z!QMpkruRReIM|C|R{BRpjj4nEKs0aqT0_pgM+bWm%t{}us39NTql5iGG;jJ^!^FYC zUIeqe4*T%bXEk-O9|+%}y-l}u%pB~uyJ}f}ANJv?HKq>s1JS(cYmKRcy$EKdzncDc z{eSe&f9 zZ~9te>R>N|S?Qw~HKq>s199iWtAl;5F?FyPvCrE4Afv|A!G1!7H+H;_se^r7t2)^G zPSV#h{`aYa{Xke*cF?Ztm^#>tU{?Bb#+9ZH_5;zp>1&OtgS`l5rO#;8m^#=Gg!R|= zm3HFM!CnNj(iJson6QJkb#yrWin{TikziK(zD5lajF9m4yUu+_zBAV#!L0PJ zjT%!2dqqh2IrZ<=)WKc^v(mvnYD^vM2cmh?*LOa3uouCs^pA=fQwRHjXx{X-hWg;q z!CnNj(g!PQsH+_v><6NG)7Kg%4i5Grn3aBBQDf?0KM>8qep|=P!G60de@~p1zGP8j z>R>+*&6~c~P#?UpgSPh-uf?qNSBn}`2YW?Gc*pq5U29Ao>_spued40Vw%g;b7$Fh* zQ$MLSHbor>W~E16)F8nK3F|MMu3I1UmmzA9U{?C}MUCz269gk9tUvenx{j%Xy{^Tq z^dF2GQwRHjXx{X-#?--H1hdjdF=|X5><7Y~!RNSIW9ncpVxP77K}LgtFL3~U@wAM>CYKgnmX7IMDwPv&uZ#m zFM?U=Ga5Cf4)z0K{q=pNop^Mx7s0G_MU5IJ+HPlrMDwPv>yV;u{m1Wv1hdksHENL9 zMK%X}UpMrZI`Epz~ejx1A z65eM~V{;9?>>TVxFpKA|bPWxH5fZ+>e||;Om^#?22DA1j%c+C?K%|pl)R1%U(ZOB> zv-T(Cse}DM__sqZf6|{i*bjsqSG+T8jj4mZhk>tub}5 z7vZmV%i2#~QwRHj_^Re{81G~1U@wAM`w4RDU_TJ{`04LM&b>zmdlAgq&AW34`+-O& z!&t}E!CnNjc2jtnI@k|{J(s#ZHuvmM6tBfB{{A7|vx8uSguSD>&ZiFcx+`Y!_bB1q zyI6<*UNJ%sBACU~$BBdeKzJXA_gU1KI@pU~ z*6tKlNH9Xe*Z0r$yE}ETR}E(EPnJ^$`+-O&!&ry<;L*We1he)h!Cr*>V9VN1UQ-AAfpDkp z>zF#&i(uA%f}A?o4}`ym{e7qp9v$pOFpKlq?2JhtEq#%2xf5#FYbevum0IP z7oRK{A>sbi^|75r4+OLL`-eP>2Ehmk_t~!Vse`@N!L0pnSf25-cV4W+c5ZLqD-!8s z7|&|zV6Pg?;%|3KnL5}HgwH+wyE}ET7s0IkZ@i`s_5+c=gt3mPgS`l5?SFGOb+8|Z z^d*cMQwMty%-a73a_V3|5S;YVtMSI}j*O)9#hdnX+lhm{?w5ppLBeZG^ofJL2xf6^ z3+LXWgZ)6*5hXmsqQ=z0UIeqeEBmQ$>R>+*_Gt<4v#7CofbJdaMKH_Pcb(b|NH9Xe z*Z0r&M2)F~y=pLvbK8l7{XqCR`AO6oQwMty%;MZu%GAMrApE}lMr)1DTlUhNV%ucG zto_`!`PT-)2njo`c%Ri8QwMw9)jq4wZDsCYKOyV~Q)}2c+s>iQ>$lB-?t?9hb6Ys~ z9v$pegM^)^`Z_kx;#fJa#Vmi_+A|F2-lK!PYLKu$R(~H;2YV6B;@np3++wnmEE&>EoQlEcAb-8ghcuhh6e91FX4lOz3z%x zoZC(u><1#945P->!CnNje2VGQ-PFN;AkvpGYD^vMMKFtV+lhnyK%|pl)UZeO!NFbx zvpBb%IM@$FIvGX{>F?-ZFM?V7>CSg`aIhZ;-=XzVbv|{l-|nhqaSDq*xHMm6MtEI6 zX)CPOm^#?22D3P~ojBMJgm+AMhQ+g*I@pU~mQ~PCeNzYff$+``@3W|}DQfRvFM?UV zem}jEV1$IP@1N_lnmX942D3P~MISsm*bjuClb=MbF?FyP!7R>g(FczX_5+c=gz>Dr zL##vhL0*el`?+oF20<`F!aLIYtgd6~V6VH{XZ5))`ry&QenNzkVXR~7U@yX5tz~g; zJ8`fd2zTnfj_m{xE9bSC#kuXo!Co~;`21jn)n_$zuouBBPGQjpj}G<&kxqv3tfmh3 zBADg=)b%lSupfx@C2SfzI@pU~7N@Wi2m66=pY1wVA3QqPi(nS#wi5^Yf$({uf3Kzv z_9B?Yx$VTkejt4A>EGR{gS`l5ac;}0XzyS@5I(=P&QQwK!CnNjIJccR*bhYd62?3C zIrQLQFM?T|;p$x-9P9_ecWAwA-;&3C$n^uB{ou><|7$qdt9m+L{ImVsR?6p!_;Vs& zB*IVBO7gWxq?4g&xgvhay{`YuFTLnMFw5`XdZ~ByLJ@Bi@!zNhBP7zvFlv0`C;sl` zX}|LN%S#4=S>DIiORaIYh-ZoTQW1=huun^PpGA!)e$v}7{_|x6!7R>grI28Rgs<

gr94%{H;eGf86jcc9Iva^_-;K}KVd&z63pThR?1uaE=2g9 zGeRPr3}YSl{Ot!{K2JMkB$(x0*r%d@jk2T_>HGL_2!|kf56py zm&87+&uyjrf`|_n@d6Q?&ql(2Ftx_7J>{vlGs1Ms@>ij+<6R=!UF{>C_s*p zi&yS-kYJX-Zhg9w{ub-dPnQuA=}Q>zL;72+!;xT?ztUD))ra)Av|Yjo344b1eI@-Z z)}ePI31+$5SZ%e2^tV`t-tCN#u;)_OhZMCm4U%A%PnBKgBp4xK@2IYG>2I+PeODxy z#ks8%>2I+Py>doK*aORYsryP#cC`+zK@!a3+*XS8w_1mOgN%@{gPQeHYe;{qbvP2t z@@Z_>4OZ*W8f1h-`Vz*z(oSEkL+@P@%;MZ8w=@yfp*6?|iF7iI8YZm6kzkf<_wMYw zvJTr_wFn8({M@XUT0{C!sF^{ub-7?Zief%X_+?`lP?bI&8bWMM!ubhxb{$k4;gF`yj8yEMLX3 zs&f*Iknr{Wb6tn@w^)bm%h0aHEU(SatJaYI7VEHmeOiQspOe>BYe;|o!mWO~ycVB!AzjYnbpS!_o4KhN)`_}uc){y?(an{y9 z+O_sseQt|B=&rW5KG-I@kq9Tlc<0ieJLiFLA8c9vjr>~e;+=FT8DlgB$(whQQJMG_#E1H2_q!@UGMwK=TPg= zJCOvl+@IQ>F2(0i>(INM5fbiCT_5g&R+TkKf?1r~@+=wzBP85syUu+MwGMq(B$&my zE&AZaI`qmJA>s2v|6b|IUadoGkOZ?hw?!YkT8DmvjF3nt!`Qn%hgydt!7R>g`ujd2 ztV3&%5fVPX_5Puqezgw0cS$gdb6fPmtNLJcHAYCJFJbG0SL@KKCBZD$?)}_%WgWJ= zY7r8yXT8*K$!j0=iPx|G(Z^pN^v~g7uj=W1@hbg&(MN9%_HkF=yAk&m!3c?TG8A3P z-Jkza*C%|2ey2YW%<|jpr={16_$wkFAc7GR_BRR7u&D9T|L8&2AN%ufzkKLGFw48L zpZe|)@n#VZ6~PDz`?Q4jS=6}ard<8!!v}&{zP_)vbpsHLknr{W^F2}HO}e9p=+1ms zB$(yr3mX8vjsx>U*?Pyh}(h%e&CKvDSEjh}VhmPGp3H9ap^1YK>2Q&r5Fp_@6!YKU9;<)1S2Hu9o2O%{jJua?}`Mo-2MCa zO8Q%^Lu-%`686CA-z({FwGREPNHEK%7;C5ML;72-L%%^rNZ4D=dZ~L?`dh6-?-CNs z@@cGh1L<$I4!si@A(2jo@x9VcU#-KDU>2vaQlzHUI2I|T+Z${Iv%DAj zX-WE9twU>&5fXm?;TaasO8Q%^!?v&5wV35S-A{ee-)bGU-QFT3ypOGyx{ggztNS3Y z#VlXNvHGk?FhauD_s_M4^tU`jchSj`e&2pSwTAS!ScmOP-3VrRclN1B`dh3+??gsOc;9-T z)f&>DJI;aFXZ0y8`k=eo+WKId=td%(3}atOf9{+I!hNu1`8(3rA^o{K$6f6sop9gn z>+m_$I`qm(Fw5V=_6+rRokduOe!7g1@b|F451&J=L%%^1%<^}=?S)c&4z&)gK}JaU zyWaPe&!N_#_Z10dxj(f%t^bmz2i5PhB7GfmW3@NP=1JvrWyVkYI#_`)t>_ z^mnxmeODxy(FnI5fVQ4 z^zW|Eq1K^y2?=I#3M<9uQ0ve;kr5I;zxDp1oqn|rM}k?L!lDme)d!=iF+w7J30oh$ zT8CCG31<0jdq4MGS%>YeT7-n_SugclVz0)7gT1P!^Tjvm-&SZ2_HkGCgFHCc4@5c{ ziav3$7r`vQ&3;;%I@k|{{Y}C%ENV<0>_srkyRx79rVjQ4VV{=pK8qTg2k3R@U@wAM zzP{_!r%Qqn6288FeoWMuI@qfQv;3U=ylRc9gZ)7GIr&M{8dC>*5zO+}&hNd}m^#=G zM0l&&Q!myrb+8w~Ebl_^##&?QU_TIcT=CAVHKq>sBKBE*3OjMIpAhzgsWqk!_9EN| zTb92HeH~K=`+=}GPG85=!CnNj{B`T^W9nc(5aEZG?_=stpI*KM?j@>iV#2uT^CY@>st*qKBACS~ES!6f4)z0)PKHrq>R>N|S)9U3@m(Dp><7Yk7#>wo!_L_U z2m9@=T9)5OKV|so9vtik!cRIB7B!|0_9B?YDXf&KgZ)5w$Ao8C)R;Qhi(r;j&`*6+ z2m68W&JXXisIe((-8tBcV3x1nPp>2xA>r%$=lb29I@qfQvp9v7GIg*Y2tOx3iCSao zU@wAMoWe?(I@k|HIvK{ZnmX8vVAg&Ln>yGJgm+~4`9+PXgT07-R-eL79PB4VI2lHb zse`=;_raFMDXf&KgZ)7GJJQ!Nb+8w~EKXr34)z0)zJ#%kse`=;W^oETaj+iYsejwbRx<1?kt*V`ay$EJ;3OjMI9|-r^uJfsby$EJ;3OjMI9|)fp z`uA$;U@wAMoWf2V><1!!3FDnl9qdIgi&NN%gZ)7G{MI@{beyAuy$EJ;3OjMIABglN zjCD*M>_sqZKiy3o><7Yk*!%hB?znfbSM_wh_}cy4mhO&w2m66YCqvOE4)!9L<@euD zOZK(2b7=FmY!MRaWEeH34)&_SEbrrf>YF;)4}^VM!uu?0Y#yL{2YV6B^7Z@al>{Rs ze0~3X->5NluvZOc`Dyf1_|(CEAncptCsAum9qdIgi*wtFgZ)6HlVPl5>R>N|S>A{WwV zRzW}YO&#n9!aF~_&!WbrsJ(-|2xj^E{q#zL5fZ+>f3DvvJ7*sp>{WwVoZCvVbN0c( zejw7xFxD}3uouBB&TY{Lj}G<&k-mgcW9ncpf?4~y&Cc0YZtDhZULxTg86JmGW9ne9 z8vCq1w?!X3I@nK$a59V4`L69@Z& zNMFKOhfkFU2YV6B@^`&YcP6YuYmgBV=}Q_srkXRbconK(Gu4}{O5tuvG|b+8w~EY58w4)z0)zJ#%kse`=;W_cZb zx|=%K4+JMYeHrBLcyO>+^>n^?{(f!?=iZ}({Xp0kB)qmnpE%fyV3yy%^-_1q)WLor z>~9jDVNql1U@wAM-pBpaH+8Td2>Y~z_gU1~JV38I2YV6B^7Z@al>{Rse0~4?`%z=+ zV6Pg?;@o!PU_TIkPJR-#hMlty4)!9L#kuXo!G0k8zWqjPjj4mZ2xjf4u&IOnK-h7` zJG0i9I@pWYXZ5-5#KC?-*bk=Gm^#>ta35@0{wnk-^&Qnu_-fbCeWVlisOsyOI@qfQ zv;1}I)7{j;ejx0%)!)a|!CnNjIJccR*bjt#zWTnhbN0c(UIeq;ZMr^8931Qi;$_X_ zuxT*;=y@$>xodWv+vnFhY<}Afc>^J0BeEMKFtV+lhnyK-iNkoR8vt*rWR3U@wAMoZC(u><1#945P-> z!CnNj_S2p3$~v?L86n|23}3>iF?F!t?y6;R3OjMI9|%8bE3AG?rVjQZn8mqG8kBSP z!NGnYyko4eT4U;9FM?T|!b+Js*bjtvzV%XTY>HZ&qS^_PS^nSp>6HW{Bz%4UTx(1n z>~&Yn;@lQ}@aSMa5a~-8?|kZDFM?T|!cH9Q2g2{$Z?vvs>R>N|S^K$d>R>+*-jU%A z80(li*o)X_^||fD!G1!7lVQ}DI@pVFA8c8i+fE$p2g2WxzK*Gby$EJ;3OjMI9|(UB z`}>$W*o$Bm=e83E`+@Lx-3qJkeCl8?f?4iDT^~~i`+;zO>iTd;v#P8?UW-|r+fE$p zRfB}jpgCl2-l z;qzPT4Am?C;9xI;S)AKW9P9@oeF;N@>VroIdlAgqPj~8rM+f_X@E!JkK6S8H_4GBo zYd^Q?cQSH!JUG}7gq0Y zW;k0%jm-me?_e*2Syoq{?np4QBbqmT)R;QhtA_8w)LqK*bLyw?se}DMq&I!km^#>t zU>4`LQl<{}1L61WH|jeqW$Iurf?3{$eJYwd*bjuAHoY@zjm=ee?_e)tpVglmDE0<&AGSDfbN4W%U^}Q4!e??Xnw*y(g{1C_H|4h>~&Yn^4G0TcT)%Z zfv|&Xe;-o^dlAg?SGw=3se}DMq&Iy$tEq#%2xht4bbZ)4``}btF3lt5{!_rGjP}W)WKeN#VpQk;oN(4upfwYnvZo%9qdIg%cqz=-Ax_r z2f|Lx{kv=D?1O{72xf6^3+LYT;9x%xcAO5!+gOKo`q9B&1hY7WojBMJM0(S+#@@kR z1he+jo$tyzvsBA8_r^i$u|!G0jT^TXLXYHW%M_iSE^S-!qwI}HZG$c|{<^igB# zV6VIKU6^tQ;M}I)(Cb@raIhbU^rnv*QwMty%;MY@eemdDKM;Q3exun3j}G=Cn6;nV z?3``o?i}m~!aFjY-(wwHkJ>xfi`ZxNxh?wO(ZPN~goAynabs1rKG_Nqa`-;utKse`=;W^ryiaj+itU>4^#`Ay6m><1#f>El^V9qdIg zi&I!BQwRHzXb$#K!#&VCbRXok(vMzQoZI%E_l%Hm2kknaI@s&3n8ms6#KC?b(rG@{ zF?FyP!7R>gCl2-l;d4*_?oJ)-MKH^!v_9QU9qb3f=eO1wsvrHq!CnNjIJccR*bhW{ z)5o*&snTcOo#(v>W_cZbx-+3ZxOcE02;X7v=Tis!@`K%vUjLlFOZWVMYEK>P6-fts z5$R2@e?D=r7s0IbkBS;o2m66YZ~CYq=iZ}(y$EKd4_4H$|EC?a?FY#SiS(wA8YT`7 z_PQ3cybk;Dye?`?9qb3f_3Uk0>N;i)_9B>-zGP8j>R>+*=` z1_?$;q&I!k*t|@m1_@@RZ(r2d{8EG1MVf=Xu4~6oI}+D-K6S9ywV0LugHdDZU_TJ) zO&{x+I@pU~R{AJLjj4nEK-~H8&A~ouOdae+?6WpM$fz-Ou%8gs8{6NKse^r7Yjd#I zousd2{O?l-`+-Pr`dG)*!CnNj(w{S~GE9qdIgD_v2eh6(8~?uro-)?YYX$2z2_8~^b-NH8mXU!w*IMo9SjUFW_d z-R>N|S?OROHKq>s1CieJ@vNo}_9B>-{!vk5>R>+* z=}jLs)CZ3a_9B>-K3GvhUG3;#KM?6nA2m!I9PC9fEB(Bp#?--nAkx9Uu4Cq4zulF; zC;oD#FIm)>I@k|HI?YFose`=;W~IMc)R;Qh4}^D2I6_B_se`=;W~Cck)Yx|WZQJec zI_`rcLVtF)jvAYy4g|BTP50Z{&q**s!ukuR>!`7P8KMRWW~FamtYiE71i=Ui>(Bi? z`{0cow7qf?%u4^ks4;c0SA;}*)5kid4)!9Ll|G75W9nc(5a~@HHKq>sBKBFEA7s>+ zI@nK$deYqb;L*W8uC@8m>rT?wGXD3egZ)5QSw3mj_c3*_7s0Ib=Zq^&9qb1pz3Jmw zO&#n-Fe`mVqsG+1eju#BzOS?sj}G=Cm}Ql9eVFih)H{(866sAJ>yV;u{bwYYmAr>Jxd4T2F8>0}r+rVjSHD`xFamQx4&fk=)KRW$h=gse}DMq%UFAm^#>tVAg(uoI2PKM0y-XjZd37*o$D+Zr+_c*bhW{97c^d z%e&S(^uFS?n6;b2?cBS_xi|I|BP7z7FluaG*aw1H{<>Oi^?OBv5fbTS7&WF2_F6f! z_P=3~bMMi?ejw80FltO4>_sqZ|C^$zgZ)6H$6?f%I@pU~*8VqMQwRHjNRPv)F?FyP z!7ToMu9T^R{XnG0Vbqv9*o$D+{x^_Q2m66YkHe@jb+F&=$~t_7vi6;G>R>+*>0}r+ zrVjQZn6*CvOdae8B0UbH#?--H1haVhIB~Ea2=9FB#ZMu++G16?8}M4p;<;;2FhauD z_s_M))WKeN#jO3wa_V3|5b1Fk>rfv&I@pU~*8YS%b+8|Z^d*cMQwMty%-Wyyrw;Z5 zkxqtDW9ncpVxPr{W$Iu*A;OzJYD^vMMYs>Pto`IQb+8|Z^d*cMQwMty%-T2Vk}rVjSHD`xF~!!mWSABglgj2cr1dlAgq|E6f_U_TJ)aTqnG4)!9L zwf~LR)WLor(&I2{Odae+Fl+ytyQzcyK%~cE)R;Qhi(uCNH;_{Y`+?x3mtKu~2YXdd z=ZoLl&uu3T_5+blhN4d#>_sq(bK8l7{Xp2?#C|aMM2)F~y$EJ;3M*ymU_TJ{X$kMM zsA1=9|FL^Euf;6RZRr{s1S2GTeg9n7F?F!lT``MO*olMvK=?WNNz@us2YV6B;@o!P zU_TJ)WEjtC>R>N|S^K$d>R>+*c3kn!tm~LM*o)X_^|`Ig9qcEB{a|X1se`=;_raFM zx$VTkejw~b)z>j~uouBB&TS_S_5+blhVee84)!9L#VPE>!G0j@^VRp&)WKc^vp9v7 zGIg*Y2s@m0eQaLXdk1?F%<`$yYO5zp5{!_rcU0H8oO_QB_Nu`w&TS_S_5)!Ltp2^4 zI@pU~7U#Bb?p?n7D<5~U7d9g#(#bI1`P9K)HJHV@?Zm-;AnZvN&PP#W>R>N|S)AKW z9P9@ooeZPK)WKc^v-Z>7)WLore1}$8)%okc=cgCz&`+1wVixDN69@Zk9qqd5aTx2E zI@pU~7U#AT2m68W`?tdCI;IZxBACS~Ec)PL9o}0jXM}`zzV%XTY>L`D*sBJ!IJZR~ zTuixhGD5=F_s_M))WKdgn8ms6#KC?b(w8va$JD`I1hY7|ojBMJL^>Hpjj4mZ2xjf) zwyhiN9qb3f`^!7CKC7vNy@-8QpWC7j9v$o_L^v77I;IZxBHRaC7U#AT2m68Wccial zI|1w+>_sq(bK8l7{XnEIVXR~7U@wAMoZC(u><7Z%b?c?RkEw&b2xf5#i#~YKc{DW0 z2nqM6t`Di{=wPoJ%;MaZXVK6gBP85syUx`Ij}G>#!7R>gCl2-l;qyZOUQHeBMKFtV z+lhnyK%|plyz{Apy$EJ;Zp*1??_fU=KEJi^{E36T2xf6^J8`fdi1a0lbxa-XMKEhW z-Kh^=4i5GM;XCa8++K|b2YXdd=ZoLm&uu3T_5)#Gknq|Ped1s*f?0n5{j_9X%Y%dc zK-k|TJj0@f97B%|_9B?&ecVrdatu8>*bjt#TEhD*YHY5ddk1?F%<}d7>6HW{Bz%4U ze4nT>b+A_rX8AewQ~1=uejxmu{3L3Pse`=;W^ryiaj+iPEPoaHI;IZx1M&ItsOsyO zI@pU~7U#Bb?mar#4}?8_`umtV*o$D6ztVkQO&#n9!d^vvUrinCMKH_Vrt4$sU_TJ{ zT*VehD}^QnWq?uuFN{{4G3b+8`@dtmkNl|7LU4)!9L z#ksA_9qb3fUS9pXJ9V%Z!7QJ~cHQ9UU_TJ)WEkHodsH7B>_sq(bK8l7{XnFXVbqv9 z*o$Bm=eAOOR|g0Cf$$w#VO8gL&OSKUZ+F$QIJccR*bjuCba-vWI;IZxBACS~O#gO` zcFDoPejvPK!ZR#t*g5;)U@wAMRzW}Y**W{*U_TJv`Qd#QH8w?s7dEfOEMMQTdO{|_ z2nk=`KiBs$b+Ff6F^h9sDN_ggf$($klc+VO4)!9L#kno|;L*W;ApE}lMr#c_XCEBw zMKEhWw@n@F2f{ltyaD5VOdae+?6dmZcH&?^A;QTpYD^vMMYs>PEY5BEx9esO_5|@2jbUy$EKxKXrXf9qb3f z{i*B2JEGR{gS`l5ac(iD zse}DM_ztbG`n{Su*sFRvU;OfZZYyQ#U_TJ)aVYx4!CnNj{QmoCY3g7<5b1FkHKq>s zBADfU+)sT|2m66YkHe_3d4TR6>_srk*YBrS5{!^YC&Q>Qb+A_rX8AewQ~1=uejw80 zFltO4>_sq(bDO>;a&bL4*bhW{97c_)gS`l5?dP_sgZ)6H$6?f%I@pWYXZ5-5#KC?- z*jwhFs4;c07vVnGviw!()7{j;ejw80FlyL2``}_D`vU-_wUuz!G0jp<1lJW9qdIg%cqz=-Ax_r2O>QVqsG+1UIeo^w}o@> z(ZPNo(&I2{*rWR3U@wAMoZC(u><1z}4x`4@!CnNj_S2p3>fm5M5b1FkHKq>s+g(|Q z{u*#@i#~XCupfx@IE)%o2YV6B;@qa+Q_DH~;9x%x>2Vk}rVjQZm}M38Q{U9VejvQ_ zt(W>u+!VEUuouBBU%#JTNiagf*Z0r0#?--HHJHV@t(2*Q{XnG0VLYp;gS`l5ac+w~ zcyzEIi1av&8dC>*5zN}pZBqyPfk=_srk{i*9? z>R>+*>2Vk}+ykwuorApyW^ryiaj+kV^f-(f51BdGi(nS#wi5^Yfk=QVqsG+1UIeo^x1BiH4@7z#Mh*4Bql3K&X6>iD zse}DMaMG(@jRyyNRZr)OpV`lC`Y-9s9P9_e9wXs-C;G&}UIeo^w}o@>^?@(E`|@Eg zdcevE345i4XIRvjI@qfQvp9v7GIg*Yi1av&8k=kAb?0C&f?1r~(ls;)Mo6TSVbqv9 z*sBJ!IJbp!??n#U*E{sA7$M>36pnLIW9ne98qDI{7S6pF`7d7|q8f~lNRPv)F?Fz4 z4QB1&Y^xE`$#9! z<1lJW9qd(uS)AL#xp%P+{XQ5WksgOpW9ne98qDI{7S6p#2m66YkHe@jb+8w~EKXti zJ6^x=-o-lnQ~J>lMEVj&jm--?6vb;X%cn}KZ97@Q^PUkB>0}r+rVjSHD`s(S(>GC` z_j1s__?tU>4`LaPB=i*bhW{97c_)gS`l5?Wen`gZ)6H$6?f%I@oV_6;4*l;@lQ} z@aSMa5b1FkHKq>sBACUw?Zm-;ApHKrGc0OM9qdIgi&I$i!PPpn1{opYeQdovCTeUN zTz3xks=+MIZP5qU=C{oV318no*BVm?d(~hT=e83E`+@Lt^15n`se`=;W^ryiaj+kV z^f-)XHFdBT!L0qBQJuouBB&TS_S_5BSbJl zB0UbH#?--Hcg3vzbmzNz%@@7=rrnhl8o$~6k>7ffmFw>yC%x)NZ|6|^r81Jv7eBtA z+fE$pbzKtn7zu9~(I*b}BACUwEu4Fg4)z0)9*0q5>R>N|S)9U3nL5}HM0y-Xjmt*k|=AO#YlR2m1+OZ<+c& zrVjQZtfrR5DJ-0OZ|xjvclmv!6X|5wp4HL8UNxA-x$VTkejw80FlyKbyS+hPi&>o8 zN-<%7Sv&VKLLxm5qsG+1UU$VTPGNFOlk2o~_{*xn2#NG1j2fF4b|{JjvwW(w+Ulu~ z1S2HU<1lJW9qhFZX1V)YhqZ>Cv*n;28f1h-dK^X#dm{WwVoZC(u><1z}4x@&A zc#jVDBACUwEnV588!$p5Jr1LWz2XlJ_Nu`w&TS_S_5+a~hf!ndU@wAM`{~Yib#SmB zh;%aKv)Vh@Z+B%K`fI?sEuYoi!G0jp<1lJW9qdIg%e%*FtNY5k#5&wL*bhW{97c_) zgS`l5aSDq*xLSwSAR{EakFA&bP23a}?%5=m#kno|;A+Z#+l-L#_5E}9!J~t{*1;^! zZ6^-)1Cbtw@vNo}_9B?Yxh?wO(ZPNo(&I2{Odae+Fl#@zO&#n9B0UbH#?--H#6GLf zZP5ph4)zlwyy>IH)WKea`(VrB+;-w%KM?70*q+tJ-z=X+c`asfZaZR>N|S)9V64_?&=LxYTvNMFLJAvGNx>{WwVoWk-f z8X9DTgwLT}=TirJ)nFFqwo;}J_5+a~hp~>SgS`l5ac({WwVoWjDn_iE?R$EyY-B<$=G-e*x`a}C`)*sBJ!IEAHaXb_B$@b&%k??;WP zgS~1ni&NN%gZ)6H$6?f%I@pU~7U#AT2m66YkHe@jb+8w~to__Jb+8|Z^f-(fQwMty z`>Z~NojBM}i0~zh8dC>*5$=O6i*s8z_ukq$bmw3{5b1FkHKq>sBACS~ES!56`?5Yq zdzTRs>2Vk}rVjS1!7NT;Cl2-lksgOp!+!J!2YV6Ba<{SC>Z#Af!NGnY>~Plgv3X&K zqIfN4`BZ7O)fyxiA(2jov5u*Oz3z%xoZC(u><1z}4x`4@!CnNjIE9@!*bhW{97c_) zgS`l5ac($4)z0)PKHrq>R`X! zRXABGi*wtFgZ)6H$6?f%I@pU~7N@Wi2m66YkHe@jb+8w~EKXr34)z0)zJyU@Q&hNT z^IFW}+!lRsHD$kTMo3tX{yF>LY8|>elVBF-wi5??t%F2*9L74P4)!9L#kuXo!G0jp z<1lJW9qdIgYd^P59qb3fJJS2NKC7vNy@-8QpW99x>?cI{62>~F4)!A42U`}WuoDOS zfk=QVqlQnF*5RYHcX=&laSAKN zg!*9Yc1B2~FJaV>nvM?kx+`XJZp*W1Xpj*S?z7fQ-B(iwd(~hT=e83E`+-Q0!&t}E z!CnNjIE9@!*bhW{97c_)gS`l5aSA(eupfx@IE)%T@f{rOMKFs~*olMvK%~cE)R;Qh zi(uA%y7OJV<9Tnm@mZ7+5}fp;TKUo2In;isjHIvOckJi369;?UF9~}?hLf`B69;<{ z%;FRl&b?PVhdxC9oQ#l2Z~CY)b+A_rW_cfb_t)J%b+8`@dv%7hb=25gL&H6r*J75h z?^vxtf{`83yy>IH)WKeN<-0I-m$Epwg>&y!&b`+M>RB;D!rrNV5~fR;I@qfQvpBb% zIM@$_-?!gStub}57s0Ik+%|Qv9|${bdY{!AcJs7Hr+un}3zE;i%2|Kv<_c3*_ zR}E%yZVTt$MGo3mYmgBV=}jNcYU*GgEC12leeO10A5#bWk!arZQNymiR@KhIUPSuQ zE6bR_)L%;Ma3;$S}z=}jN&u&cFo*u3JcLx202#koy?r>MHihYv3!B+{FnHTDkn zs==)Nbhp*mJJ=6|>xBbx)R;QhZ|i7ToZC(u><7Y6I-HcF#?--H1hY7|ojBMJM0(Rl zjj4mZ2xf5#Q#bhce{Ho6|42G#ghV>cM~zKU;hs%`S)9VcJ=>}cf{`83yy>IH)WKfs zNC$gmac(RJOk7u>@+5=JhV7(L0ZP{!04)*b^+y^V+zT4L^b+8w~ zEY58w4)z1#?_qx*QwMty%;FSw;$S}zJ~>%0^?gho>_srk{mI&?=ftUl{YW$i`*_sq(b6fPmt996>BCE=8iiFQ^tusVdv%7qB9A1lAoWd$0clqdQjF3og z`gm48>sp692YcNWvpB4I!TyP_?tb+8=k#5=yjr!V4)%(qgT09K zrq@58IM|C|R{BRpjj4nEK%~=r)R1%U(ZOB>v(g7EYRHH8=wLq(=}jLsOdK5SMKCM< zyrRa`!G0jpo4&4N=3u|wl^sxvveK6-Zg5d!^XI&2{+!_;HxPE-3}@@8v3YsBKBFEA7s>+I@nK$@WzfBQwRIF*5+WZtn{^v|9$FU zKM?6nA2p^9_9B>-E}U_tse}DMq|tU{-pAMvbY1{XkfMeP3xO9v$pOFv}{l z8`bNgh6y`pdnYnN!ukuR>sW^rb>lxH!L0OZjT$5vA>r$Ho%@b_XRbklS?OOJHKq>s zijeSg>ffuWgS`l5rGtIcm^#=GM0(T5vzj{Ci(ppzM@5aPgZ)6HH+|GlA3QqPi(ppz zU_}jewWEXmK%_T))G%>yuouCs^z(`uQwRHjNC*46j+uk~c31wM_{*8TWKm=4U_TJ) zO&>L;4)!9LmHui`W9nc(5Z*E22pu)14)!9LR>NopSAfxMvbY1{e*~-{K@l5Ws zZQVbcgT1oS*D`8M9qc302`eic?4!oi!CnNj(w{S~G*5zI=T(Wo(X zupbEPukS1E#G`|~2xeJjK96P}JUZA9M0(T5I;5yu|MC0SU90)gD=WQPV;v-R5fGuj z)cJNojv6GGmHxF+W9ne92nj!@{=J$y*o$D+eja?(hO@hz}LkNRPv) z@$3KL&dYmV`QXb)FpH;;Qab-JCNTkPM)c6WL*$>ha9tmdcPsraX;$ubl zt{5Sa9*0rm!@NVZQ$~VW`;-0$i|}srPGp2cdK^ZL5C8jbe!@e)_G=ErK8q8}8(;S3 zCw!oYXR3z3yFN>KSC2$^(?^XzdfA)bG9yg4to`Km4iOLA?rI)*vG!(&I2{ zNPmlUI1Qd$u)PoK&^1V;$6?fv{ub+SB$%~70Z4y~b=Y=^b?6!-(&I2{NPmlUI1wGKyuS>B!Azx7#3f9?j0 zcOoMs(&I2{NPlm!4o702#VJGjb5~nhA8hl-NLVkgh#JzLJLiFLA8c9s$xHfsf_3P- z+DAI!zH7bI8a{`%m6KrBeuDHl)H?LjWrRd}9L74NzZ>gtB$&l{H~Qd>b?9Bf2#NGK zj2b?NT8AUSEcd6b51&KT2ji|7A(2joQNum3DT)NM_P?1R!3c?TGK?BNhgyezRwS6U z{|$@Jq1K^S&IpP0IE)(7-^Dr{31;noQzZRetV7=wBP7z}FlzW58af;ZX6=9DrCoTj z4!w67A(0-3QN!m@>u@BPwg1hX)O4{9twBaeq{m^@Fku~z1hY89mEv=#b=dC8s`6Kc z1n0I={=;j2`tm2=^X{9!_)A~BGLp_0k9qZzIfa$-J0kvgBN!o(-t?kN`IfuidilmL zecZ)0NHB|2SSjBp;@d<#Py{0+(&I2{eDP1*efiga@S@9u27+0f!t`I87V+I8K3oJN zB+}zBYW$@ayz=5dA2ATj;uKa22}VeylVQ~OcHPl`raSXpkzf|5F#X%IBEC?BpA{n{ z(&I2{{8K&IH|hzG1hY7WmGbo>zEyC zNRPv)p_SjZm6Ko=r?67=bZ^_!WrRd}97YZ4Z?O*jbV)FaQ&=g|-(nqlmoP#iJr1LW z^tV`te!3)>#VJgV&?2lu?{-E=q%UFAkfN5RK@!a36c!pxf)Nt-j!(&I2{Y%4zy%;FRleb7%g2u4Vx$6?fv{ub-7y+P~H_sc9!VbKQ{>#*$- zt7;_t{;ij~ccs6@I`p&RwV1^zEc)PL9k$(WRk;QU?_=ww*4Q+-xDWDL%<@$ntM7vZ zBP4u%|6FTGe~We4z6|YJ%<|Ll8fy*dZ?O*B_o_um_&Ir9wTAS!ScfCQEWaba-C9HX zTdYIBK}JZV$6>tl?Mr}?NTkPM)R6w%aSp^jt50Fk2i?_TmvEvR z3G1akE9uXj^FWwxS)9V654tCNRPu<$94iZ5X|Bf7JbmCj35{xksgOp!{<=z z&~K0gvp9uCAH1j!#x7xmM0y-X4WC1;Lu-%(vp9uCAH1j!#%^bXg!@z1hkKw^Wet*G z7N@X0iw406iS#&(b@&`=9a@7Vn8hh9`rySnw4xXxksgOp!{<=za3q+;DJ=Tn#X9sG zWQ0U|97YYFl-ie?1hY7W2Vk} zq`!-G=zT?kS)AcY@m;A8-n6@Fot^~ewo)GXs1Lb5?+YJ%dHi!fdu1e@FFxVbPv#U> z%EyX$u86A$Mo8FWB)qmnm-4DFzSs4&?|9MWG7!w-6sG?Qt%z?G@njK|?UAR{Ew<1lJyhpg72HAsS4oWk^PpNX&zy%QNBksgOpLpy!74o8An zoWe?xnpW%38f1h-dK^X#6V~BKFpE=IDZVS~u-%na##jttI9PeaTqnEzr{Kn31)duTRU~{ zN`H%W*mir1knldXUhWe$HVqyKX89_vQ)`f5goLl}pKA^2Z?O)2S0tFlDJ=TnVjX(r zjF3o=!&ry(w^)ZG!7RTczxTQh>Ca!$)o+jy66tXmHKad(saNk363p`M^!}|iq`$>F z^iE`igunCNXZ2Z0f9^O3VxQHgu;_#CYHRC*ZK4|q>!sF^{@ghag!^F2;uIEr(A_!i zY9HxDdK|{H@;THx^vX#vi&I$iL7y_>=`upX=LhShuEXch_6A8X%is0>TLYg%)dypj zFhU|d4r3iYhgyf;S0tF_{?zs1b7<&L1S2HU<1lKt2U=C_oY=0#Ece-_=2A#7LLxm5 zqlV9+)}d>VU>2vaQhW|oAB>eVLLxm5qlV9+)}fyj31)E$tJ8#aXbmz#B0UbHhEGb? zp*2W?S)9V64_>W9??gsOq{m^@&`!Tvha9*0pw`ny_(RxJr; zafXXNcvT;a?#u`Y&TXYk9qd&-oi84$zc0F*?xqg*1CieJqE8&`MKFs~SUC4y<=lID zfPAVMA(2joQDf?0uNuta6jsXA!G0jp<1lJ$uAzGedlAgy6qc@`K`=tXel!00o~SW( zuvZOcaS99P-isWxulLupVuVCG8Agq%gS~1ni&NN%gZ)6HlVQ}DI@pU~)_w|`I@k|H zdK^ZLse`?UeO8~sP8{qfgdJq+`<1#945P->!CnNjIE96C?;;27t2M|7iS#&(8dC>*)nJxSXVziu&Qk~b zfk#){%-J?G7=wLq(ul!4IdQvzaMGbq! z9~|sOFpE>ziG%$>q{m^@m^#>tU>2t^{r?6t2m68W9a>>k=Tis!?XFrDr?3+T`+-Q0 z!&t}E!CnNjIE9@!*bhW{97c_)gS`l5aSDq*xLSt~)!t=HpjZIPEo=t*ToWi0H zuBPm_%?OEfGK?Bi2Yao9S)9U79P9@oJr1MB)WKc^vp9vFIM@$FdK^ZLse`=;X6>i2 zse}DMct?8w*1bD*uotn<>QmT>gZ+dEZ~9or)WKea`(VrB6n5fZKM?+o^mR-f>_sq( zQ`m`v{XnG0VXR~7U@wAMoWf2V><1z}4x`4@!CnNjIECrIHpjj4mZ2xjf4JKxn; zyyqo1?XFsx0Uj85uYLA^F(kyBVk{V zaJCa&%K!Hnm+MnreD~#Z2ZC9g+tklD;%OonA(0-3QR5MR_6gVD`K9;9I!G{!Q&=e% z5$_Z6DXPH;iS#&(8vnzK9(47ekzf|5F#XqhKrligoeZPK`@ieGm&fbQ9g z`u{n#hDVF=8)Sq;dK^ZL&(yo{6ZX?3!7R>g@)!~EJ`sL{jF3nt!>IA;+9BVho#I_W zf?3{c-i`I^^I0Oi8@&!jNZ4`3`|L4M<7@7E`OPao;j<6KKC4e*a-0(Jk45}V)!;-o z65&lBHC}et%WuDFLYQt@?z?>*FA&l0Y9HxDIvGX{>2GN(C&4UEVfwE$i?9y;bQvL$ zzJ#^Li|<~nL%%^1%;MapzwaZW?Gi>vq?2LPkp33y&~K0gvp9v7BK4^#Ju4B`q2C}QB+}zBYDj;pb?99}f?1r~q8qH%q1V9(iF7iI8rtcrbvP2t;@l?J zX%W_;HOL5w^f;{R5MdpT1hag%)=vGF_^zzOc2_MzB0UbHhV-{uhaI z>##lD79o)yhfzcNTdk`01{=XFPGQjpgJ`?Ns&aJ_>2Vk}q`%cV^g4JgW^oFOKDb(k z)*vG!(w8u5Y#Llgf?3w4uU4NG2}VeylVQ}5{ub-deUJpR{4~7AT0{C*E&AZCb=dk~o9ITuda2J!`nypdJP_`KEsJwoDbk<2bKKQF z(h2un>!sH4Ikc^u1hY7|MIXFahkm+@kns7zdf95|3u+zu4U%9Mr?BXQJ}t#AVT43_ z9LD?bIn+AzP9(uBPGQjpFY1G#C`L%6lVQ|w545VRK@!a3+?Hq2AQ&N$PKHs#=g`oh zYLH+S=eFpBSL@I#XM{w097YYFFswsskOZ?hw?!YkT8DmvjF3oQ!l>bMsCDRFLV{VG z!s=9H9eN#%knlOwda3(LJN;@Mjs&wfg+(8{st-n2V}wL{9M*NHhIMGwl3BQJuouBBPGKhw_5+blhEZd44Gs5fUW-|r!qPP~2u4VxlVQ}DI@s&3 zn8hjV#KC?b(&I2{Odae+Fe~1wruw=|zP$Rr?j7t0B0UbH#?--H1hc#gy&G$dse}DM zq{m^@m^#>t*k|=A?8L!-LfBj8zENZ9U@yXbux0tH(AQz-Y&(ZqANxor(&Ml_tD}Rx zYA}ma*olMvK%|pl)R;Qhi(nR~uoDOSfk=wLL!|EqsG+1UU$VTpDL}xx_9N=dvvfLi1av&8dC>*5zO)_rhQ#c9P9@o zJr1LWzU@Z`dlAg?X>8XGR_o9n(u|NukHe^8ulR$5y=pLvQ`m`v{XnG0Vbqv9*o$Bm zr?7DDJv!JAM0ysBACS~Ec)Ql!G0jp<1lJW z9qdIgi&NN%gZ)6HFJaW!G`QN2p4Va)r?Avu5R8yWU&5%NK6rGn*IhA-Q`m`v{XnG0 zVbqv9*o$Bmr?3+T`+-Q0!>BQJuouCs{S-EJupfx@IE)%o2YV6wtUiUEIM`2!@TQL% zQwMty?t?9hQ`m`v{XnG0VS83b2YV6B;uLn`U_TJ)aTqnG4)!9L#VPE>!G0jpmoREf z9qdIgi&NN%gZ)6HlVQ}DI@pU~7N@X0i-ranA(2joQDf?0uNuta6n5fZKM?707&WF2 z_9B?YDeT0-ejw80FluZw&fdXZ1hY7W<&3j;upfx@IE)%o2YV6B;uLn`U_TJ)aTqnG z4)!9LwV&>$4)z1VNw1XuRX*5XdGD89{^ot)aj5Fe`Qrcm{a5Ygwo-0Ie3ghV6~T#) zM01)qUCLV@{;cc&E4`LQb;gD!q@lDwZ;pzhL6*o`L0MXi*s8k zFWv~RoDmYu$*|V=KlEh(m7cJlE(vCFZYyOK@e?Ba1{opIJPvD(uh0%zv{SrGNHA+Z zx4l%vkBIP2WQ0WXC9E|b^!zv6JpHa0T%SG=`>Z~N$ty*~vqXHd2u^e(VF#I7B&uyQ_Vq6V2nW){y=d>(DDF!7R>grAU8^b?B$d2#MxoSZhdsi*@KX zNP=0M+w^zOMOcU4C5(`0PKLFH^tW1v-iaib#VJf)rXs9E?{-E=G>^ktLyB6P21ziB zb6aRI2}VfRJF4qk`dh6--xUdFac(QcgmvhZGeV+y9M*M6f2(!qr%QraoWe?x{#NVI zZ;%lZ&B?IVkp5Qd(7S{LvpBbvBK@t_p?4x9B$~%zt)ZR1h7JdUS)AMS?-hx#4y{2( zNHizITEm2OI1I>#(i75zOM;7JYEF4%^d>6TWJY zXdZ{PhV-{uhwTkEf?1r~q7SatVcR8EmDfR{c^uXn(%))TwVl`qW^oFOJ{UyX?N*g* zknldXUTTd^gRA=>uf;51#W7zgH5ddVBz%4UTx&>wt5wy$4DDLX^4k2oY7OZx2(O$G z63yeV){y=d>(Eb^1he8DJ@fmw8q(il9r_J2Lc-t2ct3IWk^UCz(7S{Lv%J^5f9pD= zzr{Li-JnHC_&e`?R@Wi@x#O(vgS^&0tIuuG2i?`y)(6`}HxkxMts(una~=ry!Is6j zE&8ClbKKQF(uwAASZnwkY8`szB$&myE&AX^eK4LbBP5!~VXfhFsCDQ!NP=0M+oBI% z)CXgiFhZhv9M&2>hgyf;i6ofCDJ=TnRedmaJ0m3ApSnJ_lVvE11hY7|(DD_ghcZ=tk25lQ0vedB*84sZP5p>)}h}ZBP5!~VXfhF zsC8%!l3*6+w&;Ub>(D!q5faUpu-4E{zlIJ6f?1r~q7Pox2cxSoLZUet)*8~^)jG6l zNib_a-TAK62XFjkV1xwcwo-olb6;@%-{fHbIX~YW>|H&54garKJ(*LO-iL^{iTJah zyZe?A5_WnFCuPy4{2lpVKTO`s_g4)P%;FSQ$`_0H7!m)o2u4VxH+|IjXnDB*pP%-C z>$eXCv%D+&sqdj8-Xr2`e&Oz0Mo6U7eAIZiTtofmWdp%1U*A`&Z;%8dJED2hM~z?C z9et$k?5kCSMEcPyi&I!B|F?+$RK&Mw<&2O>Z~Cb5P(9ga>k0eml3*66Fr67T!f$XN zc~|u&*LD5A{eJF>8vjx|N|_4#YmI zPhq8e^hSJv2u^e(5#IEz#;t3Ngz1*WDJ*K-{_%EK`$#A3d}_VaXC?hD)}dEUf?1rx z)T2aLht?n?B<$eY--q-KOh9 z`dh6-Yj7XgJnwbgbefMEQq5^cUPnA|%{g#-p4*dohAz`QH{@s=SR_o9jB*847Dy_C! z!-RF{oyZ7@befO%A#JSIp*2W?S)9U3F<~8AQH+pCZ+h0a9SLT+wzX5&A^o|=ZM&-; z`4>{H{sy_O>w4ip95tlB)jDh|Zv?aAl&{l%ts(ub)}b}X2nj#8a8iyM(%)(wwl`=U z`dZB56c&AOwGP`Zv8qO*zW*QH_LcOvT8Gvkuf;6y>3-^y{#NVI8f1io_i;E|$2vAe zt?q*)nC0s`R-Y9KMs`GVu#Xzj-)bFNgCu+xru+u|G`z-IL;72-Lu-%`66sAJHKf1A zs%l@jeyty^e&ovXJBqg()1CAeMEi>NNGJTh{YLAzMEYB-Dr=C}VwU%s_itT?^cO_y z1}#Fu`_}uc){y?(qgL;BUTdG#r?A?iOth}nCc2Rbr}=nRTdzG3wGY-i;S^STt##PC zb6W=q_uak@pF^!fubkIn7N@Z2gBR=28f1iozlZ&O_#A2-`VEp`7N@Z2gBSI|*d>gR zNN@UhRz8PXht?noX1PCgefS(|9a@9?$h&eUrqg`Xa1XSqtU(gYa-Z!wC&37b^rnv* zK8IR|)*uOHaSDq*c(o3#K}JZVH+|IbIn+9|21ziBQ&=e`tV6#+Mo9SF)4#huhgyf$ zAPHu13e&z4VI6uWGD5=Vx86UbrmJ=6-A;m8oWi0HUfrXtK}JZVH+?*-twwZC63p69 zcRq)@*S5Rro&LA754xW9QokkN@qVwpecy-Oar^7{dgMD{i0jYp;9DZ$ExdFf09| zqQ*D;yMKQBg@5>MZ+Wz8FhZhv)7Kj1f!}xg-JkltAND#(Fv~7G{u;e5YCKHD-xu*~ zA{Zgjyy2#R_g!ze{qp<0`3WPz ztaKlX8b2%IZ*K%6B$_vUt?`|D=l{=#-Erd@B$$;hYEk3OB0l(zJ8rykMo4(~*lV`d z_=3Op^4kaB@2LlZS@z!vpSY-D;xBFlBP8s+X$Ra|<0JmnOK$ZiYLH--y{p3SE^3fq zghcbEuQhZ>x4N^aL4sN7&KEVb>Lhj%Ig#2S*w?jVs2z!GjSslvj@uu8zt=_$63nv7 z?6y<)t`#fg#v5dWMDwPvHNND2Z+^==zv~SLf?4T(80&bB2<^ro7$I?|9B=JBU29l> z(&2&FXKk*JQN#L^s$%6F_`>E8Rq+hV>^M#`NHlNyZSQJ_NQd!lC&8@rkBS=Jh0$&|rb{^NTT54vIk|LyDQ@fFoz5ATVob<8W#oLuyI?9AACdixN_kVV1vpz5%;7yI*f#`uFsacd*ayLzy1IC~@|Ba%yiKs52$HDw>u3|~ zgK!s)#fPcUCfHBJmPEvF66_~p%OxBdZGwFe?&1x)`-9}{s|5Rr z*m4Pn2C2Qcigo2je8C+~uF{#J|-K;wr&@BFI+5FR9Tc*azXR<4?TEkG@KCM-wv5A}!IfVn*k8^HA96>JJ15E6R|)nL z!JWoo`8?VL`ykwP`~qkb>?eX1Gm;F)b+ifgLAc9bA2$;0CxVraU-CLG9z5egAIn|- z?z)j+9~ve&KEF?mHo-m!clrBq?1R?{_7kyX9FBWMayC9BJ=@1}m%oF@K6ssA9~vgM zB*UT6CfEnzE`ObmeegQLej>Ic!=ce8*ava!+UJt74_+tOHv|sL=g}tE2f;pAU7oL& zrA@G(h%L!*Tt}N=AB4L+CoW5yU_TMO4{=ytN9=>w3HCv_%k%Dy1pA5Ly^h0DqfM|6 z!d;%im!(axp9uD+-5-}P%i%#E%U$fV`@~|x6%%}i?mll5?BlH5<)5RBeegQLej>Ic z!|}|+f7c22LAc95-5LAfb%OmwY`KI(qfM|6!d?C;)v~k+_7lPPTkQNvOENU)Fd zHBm{1&^Hq7gK(GUwi^ld6G6TSc`&KbCfEnzE>B@M66_~}oE8#fQsa^udQ7kn!d}6LJcZpzu%C#^B}@&HvnylW z$8y(kZoA~y-jTNHiit`xOpP|dKF;dcwa;xg66_m-JebsI6YPUvAFM9k3V0_S)h5_a zMCB5u#wD|OT)B_sF3)Wvx%a;At}7nc7L=9_7g$o((VsZdvO)Xy*`$^*fnumUWW-+Opy1q`@BuCkF#=@=e8RO_7hP_ zhIy~r1p6S|<+<%fg8f8PE@5hr?Tim`l#k^u&ut^Q_d3BoG)z>IVQP?3eU)Gzgu6Vq z-AJ&Xh)Oa{4U)6366}L;*KxYztgaI5C!#VAQ=?6=znm4WqRVsJjRgCN;J)Fo)Myjz zgK(GUwi^ld6Hyt5snI6b2jMPUuz&TDoPCvGKM|~a{E`|MM~y6OAIn`FpW4BLgK)(J z$LIH{L2~w0f_SdpyX)MyjzL*v-B&uupn>>C1yrAC`z9|Zegb$M>PkzhX&l}nf!moI>E zB@M66_~}{b~0H zdmuhMB-jVxF3)W@66_~}eRlVGn_wS=yF9nuNU)!X$|cNu)h5^n;V#c@Hxle8qH+mS zgD<741p6S|<+<%fg8f7=@6^taS@Bm1_CdJIbK8vs`-!Mr!n}?)!9ECgd4{`@U_TL_ z+m_|4pYwsIH-5p>?!NW&_5^#>x8#e@JI-y(@<)RBnjpSC2v2k-wv5A|c@Ol(PpL*pEG_A}xR&xE@?g~dBR2%aL(+!YgB#^KQT>R2JHl$mhXac=uFLHzL` zSc$Hf*fI`>#_xT>qYu9HTR!xPICkxG8~fm+556RbZwn1ibTdJ=%=-_Gm%iZ9`;LIF zF5U{bDxdj_f~d1PR(9egkwA=JQX~9##)n+F33u@|uupg4zjNJPS4?afhvPcJf9HCF zCfwz@E&kr9An+j`bj8G$WH>a!e`kEix-#J|cAMQF;lDFJWVO3uV#_5Q8sVsOdC-Kr z*fn>bn{dU%mSi|I!hdIc$XS_im*=+l+unk}hg`WUCblHQp%MOD@!?Fk%Tw5Ri>~+( zN4a8R%Qzewu|igSI1}#j+_o&?zZD;{5?wK|WgHHTSm`T1oC$Y%Zj1L-5cm)ex?*C> zI2;-f_;4oNb)4=vD|}dIRr|JyE#q)#g#T82I1}#j+&1>X6(82!#Z|lkOl%p4LnHjR z;=`G6m*=*z53cwS54vJv%Qzew;lDFJtaXJCIV*RuruVPD@ZT99)@rYci7l6KXj~k1 zW*_vi+{IC-ZTldu9fT_;wj{%$5&k>l!+JB+vE0SAaaU3!{CCEO_4cWXi7n%BXoUaH z_;4oN#Z%?Er$+dXx9G|fbj8G$aX2)>f4r%$2zRkM_vtSDcgBaTL|07ko@brq{t^CT z$GIYoUHjZN_Ca>Fwf4c9=w<@HZ2KTP=M}*|SY4jN;(e97^Ej(xWhdBo_v_$06d!Ws zCfwz@Ez;70sJrWmi7n%BJP*D@>j|20m*=*z58lN-xZ*)qOl%p4Lxb;7e8{>o;V$;4 zTGPwIcPKt&wYy?sOEMf9?1AMd6YgT4EjKTV30F*PNrpp%?@)ZmS($K`=eDsA-r+;8 z+!YgB#^KQ5I}{(zgu6Vq#T4UZ!#0;;g`IQ zHo-pBx8#f89sj-Pvwkv@l*d`M3HB4QB^d^NBf&lhcXxQkWDYRr|`CfH8|i7TwkUl?eXGs{K0J1p6S|_&q9 zM3D1^!&0M7un)prp29|Q?>UltPbBxcVq(iB9MAlco;@68!d;%iw)E^lxME__&q9L~OZ)L!(Ww55irZ!bWoM`bod-O?U4f_sSI$(CreQ3Cg zud#hMXcO!wVoNd{*U=`}2jMPHVK)-&Ct^!792#wceGu;Q6c+#9pi8iyh%MuAXtW9T zm$Sl$+)+}6LJcZpzu%8H?KYqz)-X_=w;Vw^MHxle8VoNd{ z*KzUSN*=wBp%_HkD3@)UL>!G0pRPuz*TS8alQ5bp96b|b-l zBDRdfaUE@feGu+CPGN0={X}d@hC`!Gun*$cwNGI;66_mdBpD8kHo-m!_QC4%6m}!Q zej?bZM^@v|XcO#%aF?gB8wvIkvE>pDjW)qP2zPl3yOCf&5nC?d&}b9vgK(Fpup0^X z6S3tI4vjX!J_vVt3fsO#hX-9TvE>pDji+}B_Mzb}PhmF_>?dN&B^(-Uf_)I~@)S1q z!BgymXZAr?Ol-M?L!(Ww4-I#D3cHbDKM{Pt)y^<>oa+SpAl&6C>_&q9L~OZ)<2u>| z`ykwPobK8L`-$KTaag_+NzT4Xun+Z0zWBAj^EkKNNU)!X$~c6+kzgN$yLg)TCC`dn zOET{(*Rm=mD&sIU+64R1aF?gB8wvIkQMrVvaY+q5ks9h_xyy6gmKr(;S4>orVQRDq z_HkD3;%;!i@?NzG_7hPVhpEvf*azV*&uupn>?fi!4pXB|un)pr$GNRdu%C#^I82Q; z!9Iv%*FLx1NU(1RvSm`EO|TDweXzQCE9}!p3BNSEif zu@7D+*iS@d9HvH_U>}6LJh#PHMywJt?+*#~6Hyt5snI6b2jMPHVK)-&C!%r*Q{&>n zk%jGJxyy6g=D|U@Vxp1^Q=?6=kF#=@=eA{O6YM9VG7eLtO|TEbU7p*O+@eGu+C&TVai{X|s8VQRDq_CXxG_POmwf_+2au+(T1?1Nw*tS--OHxle8qB0Is zqfM|6!d;%*ZY0=GL}eUaG`a-)Al&7-?M8zAL{!FMYP1RVLAc9P*o_4HiKvXj)VO?$ z4oCS|?(*EWeTxpl6%&O+@eVmoMJcZpzu%C#^I82Q;!9ECgd2YLrU_TL+ahMuy zf_)I~^4xYK!G0nt<1jVa1p6S|<+<%fg8f8P#^L2Ux&-?m+;yDp+64QF@T9jaAMyN` zp5FO6ue^KT$N$CIl`Y@mHy!7;op`?>JfE4^k_>~6{Et_>;Pgu$e*4fc;V#c@@%Kny zi1)nhUz}Yru_YM}jkkTm-RY?hJ?Zod6X7mTVaxJ2gZQu@J|eEe6%$*M;m~-=L(e$z z>%%9)U7p*P#e^#+wp_xY@sv2Dza3}BS($K`=eA{edJu07f-85$#Fk4qG@cyK;_t^D z=I)wsm*=+lf82xMDY8mjF|p+m4h_~6Yl~H4!d=I?tq3$+F|j2X4vpXO#G4;{vaT&u#JTb0N69u9zSn3%{gB`0rd#(1g1@w=D|2?vQ`oYE|5kj+YInuNmPuLN51Me7=eFU&jc~;Td1&}0uOs}o;zQ2L zgu6Vq#m{$xz=vG9D<-yF!f_qpzZD;HcTKp4aAI^lkj?*1yg%9zd zD<;sxFZs+b_v&0%jt|*|-Q~G$yI1GBySQp5wv5AZ9pS$fSJe|N!d;%*#y&WRS|zv& z4HG>q?FA-x(j)8?Fd<@r-!xsS*C; zExPgqT`{rc5{_qnc~h_TrmkbTi?zloO^qVZaK!}cmX(>;5&mPx85$;zUHjZN_Ca>F zwf4c9=w@Oh8IJ1+|FLsk5$uE2<+*L_gY3>L9z0fdV#_70d&M`yxVt9Y<+*L_gM;Ai zx?*C>B^(-jht?A`;V#c@V;{VWeQ>N2S4?cVghPYxP<+TrG~q5!VPhXW#XdMzyDKKx zpLTy-zAT5MOt{N)+x9Iw2vFFc6Y2Or=;S4^OXU-DhjCfJ91C13o^ zZ-{?46?b>6{&7}qg8f8PE+O=d1p6S|#nWW<=UKH0_7hP_hN;me*azV*PhlgucVymI zK4*OonjoizJebtDq=udj3HG7kE{=juUWW-+OmKXDpBim~eQ3Cg`^5c9jW)r4A}W_K zHQEIGAl$|C=DDW^$=O#4_7g$=4^K2T+64O`+{G$nHKsO+@eGu;Q+!p_jNu1SHg8f8rhBz!W z+64Q{Syh*(up0^X6EPC)!iTBRCfEnzE>B@M66_~}6@$Z4qfM|6!dRz7}7jf)3I7PgP&E>B^b2M6Jb369V2Q=?6=kF#=@r?6#d6YM9Vk_=O$O|TEb zU7o_0rA@G(h{`2QjW)qP2zMQ)ur|SdB3O~E-_&Rm?1MOV?Niu|1p9`-VX4t3*ayKr zSY4jNZY0=G1n-gkI@$#LAl&6C>_&q9L{u(eUPqf?AB4L+h22Q7pNPsOOpP|dJ_vWQ zKjEG9AjDOI{Y0=o?f$rYSq?|}Snl!^b|b+)G)%D1?mll5?1ONZr?49d_7hRLgn6&p z1p6S|}6Lj?-P6U_TL@;l7{$o5*VXkw^}``=@(?J?dMo;WLkOTl`EWh#v~#C;!Qw zM?VuJJ&q*hpyO}sjm*jCMRMqSCc<5w!s5RR58{)8_)~FKu9(=8=7+{zq;39OO%4dvJ8PlUTT{{Ho9!j%J23HC$dXX1<= zjx*z|Opr4Q^|I*l+!lXVaS+c7;tg@-u9(=e>4(O133ssy_o?UyF9a*m6%!S6YgTy+m>_X_B;Jne2yd+TkkxL&U7p*P1p*)9C|68u+4R=9p9y!Nz3dyg zkK>{@5{QRJ_;1CBb>&64%X3@aD|}dYx4u72aNkCf^3VwXt@yB>U=i-}+&1>X6(80r z!By;0Cbp#cp%MOD@gW}cvE0R)-oN_7e=9z$)m{}7tYiF={3dV`_x|R(yyDT`|F%i0jJh2>+dNRlVW%W9?l$ zBc6L|g#QLnZ_&N76FhI8Piln!cvG*e5+BQ5tToneYJ~p=QM*A^Ot5ZQXQ^@7qt@DS zia2)dbKBSl*`wCl)oP-fiIHGGp2uacy&`fS%ro)aw(Yg!td14-!6bN(?AO6}C_d!M zO}NW*+t>&B${2Uo6%)J<_vgWPC_dx~nsArrwy_W1#XdMzi7O_yZ2EDp_zuN~c+iBq z*q>@mN1AyM_>k3ptXvZ8C_dz@Ot{N) z+t>$B_z(}eVq#00AJ@TmC_co4Cfwz@ZR~?5e8>}Y#RT6y`+Ju!C47hnO}NW*Th2K6 zkd^3)3BKR<{Uh9T!iRX!gu6VqjeYRMw;~>N#l)6PKkn52ObbtQxAAS56 z|KdH5p30tJ|Ckc&A)fu2Z@PcuXMg?UKkyrm#GXh0*dvu6l^S3B+24Bqk^k%0J^sCs zQt65bk~UxX5Q(>FJmqV?{r->r+<$!=*I~k4m4lTUzb=U1b0J(Yu_w)=0r8zb_g|lf zh6#6}P5wt}{IVdPeIZ;ifgVYvm+SbLZ@K@9H@@}Zx{f-QyDFC~HJ%*AAGi>%nAnr% zxsFHTnSa+;JoNz@Cfrr|YN_$*LHx@L;fe_|E;A7tjUWHPuetx<-u&p$FyXFBgG-Hn zEy5KOByVQ2H5#vf-D~dS*U&KGuF9xO4HK@IATg9A-+Uf%4fk};#<%)1uc0L{v#neuLJ*u4~K?{V^`)urUw2CR}F$M3le&$%tU6>a~=4vBcQ7b&yd5D z8u%}KI5duxoxp$lb>P3caue>V6wcJZe|2|VF|jAja~=3Ed^pa^gu5zdG&S&F_;3)e zn81Jgy25|85>2?PQc+U_qE@>rCh*_x5BygiG~q7NuBfGk30F*T{N3lA5ogBx%7nWr zzcw|v>LOe*!F}4_SNJb{I5bSSt8#c#1OJ5&2jPl|J!zh2&I$=1j(58WcU68=YK&EQ zAzU%Ry4C&>D?NNT_9zqXsvNA;z)j)9LAYXKPnzdCAi{@ZuQlN=w0Q@l2L1~l4#E`^ z=xINXdlf!>oM&#rU6o6g8r@rrO)rNO1fWwj5&6%(xEOtwbj;;1XaUHFeZGBr%NVgmoMFK+uFZ-${^!d;cy zml~J1&mdeef&bXww|($I`0$EwSLF|;2L9sQJzs_hf(XQFZmQ=?0;hj5p_&ie%WnW!Yg z)aVlIA&y=9Tr!e-A0`L%cgOSa#4;0P%cMq^V2=iLb@6uPD<}WFOR%4b$|X#VF2Nqc zU7iz1a_>DpWL>#pqLK_#qf4+y!(E4YclpDS?;Hu*ca`sqLuaBg4pXB`u!nFLZ_wQz zU4s2gR4!p^gqyZJdLPSOyj^h{M;ad72vCD?OT?(+9zpI|=|m2sFF zU4lJ?yZlw#C)m$KWgMnPmtYU!E`Oc(3HCF=ie&w!Mweg@aqQaXlCck7CD?Za4oi(L z!5)Hru(~`g^$GSf!M?j+N0(p^;V#dKeS-Z=RFYv{N0(p^;V#d+eS-Z=RK{UybP4tl z?(!7gC)m$KWgMmkUzND3zAW(}guB>haT|ZWeTxpl6%&OMzJ;!pFe~!{8*v~{| z9HvH>U=QIg|8%EMu%C&_I82Q$!5+e0{wYNDaWo<^2N`;{5ZGu3HF??iApkr?i1`G z+~v8gPq3efN-|81F2NqcU7o_?za037f8#Ead+&Zl8G;Z6x>J&k6Q3QMrVv(IwbJxXW|fNbWs<``>u`-BZFJu9&D?!qn&z?9p(Sr?8RS zd&Y-&&=nJ8F75ufq-PIDnQ)iqw&B4o^WGH`WJm2j?-J~}4tIHO>l5r}f&?`jmiMYl zu!nG$=e9nl5r}f)#^bQlm?-hj5pt zu(1zbCD_jdD<8k4#>ImpJ=@1}m*=+4gM)Cz1jpz1snI3ab5`#1+}0=9&jk00JCPb) zf<1)0Jh$};_A^mQhN;md*h9GMIJb2P_A^mQhN;md*h3t<_PMQ3u<6YOWAatTwTOR$G}R5K2~(p>u!nG$=e9nXM+7{_s8X1bU4b#a+l|}?OSvZu9#q--F@CA*mG9y^4!)Z*v~{I8Ros}66_(| z<+-g-u%C%aGE9vw!5+e0p4+ym=>C_-cZn+|_zta|p--?!!(E=j`ULx#s9eIljxNC- z!d;%>`ULx#@Z7d6pYUrw@bpEW`?R~~y=qUeN4=6Sp7NQ;xh>}NAYK*3DF{z=CMx3) zdRhL$%b#?5%MZNz?rtL7u9&D?!qoVNhra)gUo+t@j?dBZ37T-lL?s!f#)CMcCpfb>D--VW+!iS@ zLHwg2xL2;2sEotZ_|tJ`-xPOvCfwz@Et0c>;3@J1T`^G^hpF)eu|ilWtP&IMI?ioh z8pOv3!Af++L}eVN#w#9q^uasc692#DL>#;Jxoufq9K?48@gN9KbTdJ=OlrLBkw@=4 z0=l|*E9_J1OM|GhI#zb#C6|oD)Cm8b@gdh?!d;%imL>dmuDk1siOM)kjqu;Oo}dYL zc?yg7ZV>p8RpN??$~a7o@ZT99&V;+zZFYZz|IWjQq2Y>&$|X#VaMZaxXu@6Wn!C?U zxMHG`3{xZgcgBZ!(1g1@w=GNf?~D(*a#u`L#$jrN|5kiB6YlcdHr}EuKE#8rn5ZPf z)QAeR;zL%VD<&%AFg0SOulR5#+~v6~{+ps8@F5;_#YANsrUnE) zoC$Xwr#sFHAJ$pbzHOp14pSrix8lQ@aF^${u@A2Juo$=vJxQl1RbIURfn3+%;C`H`U}7{yXDCR-!8=c+a!WQX~Awj&nsEyY{(l?1SuT zYwd$I(ai*YNsaIyJLeU_K3H9z+v0E72%^sFSlNlnI7|(`L-8S3Zo*xj+r~b~SH`%z zu9&Ed!_?qAw4R^|cX@6b``}&dgJYGrVxlq*Q-kkNe8{>o;V$;4-5-314j%^LiiyfN zObzzHa+C>ovCo#9hvGx- zl?iuw3d?B%AL2n*OjMF#YVf6m5AmQ0cX@6b```&5vJzb}Q5lD+5i9+K4`;$%p4-Mg zc#3^+>}sx+e%A+9yyuH$saS>eMvtKq8HKTLRTTb3@t9`#DTc+V;Rd(lgR zeV$d9U_TRNjF2q@-6z;XxXV*mpI|=|m2sFFU4lJ?yF7*U3HCElxrC|FCD=o_%Tw5v z8amRmT`^HfhN;md*rVYtPhow6{Y+HGVQO><_7Lv!6c#^2j^ylbd&x6Sq=vd;qB0Is zqf4+y!(GQItV^(;iOM)kjV{3+;@GuMVSR#qN02R(8eM`t1p8ohc?uiJy;lkLGf^3b zsnI3aL%7RRSf5}&6P0n88eM`tgu6V2^$GSfQ5lD+(IwbJxXV*mpI|=|l}nf!U4lJ? zyF7($>Dj}Bu9&Ed!_<_7Lv!6c+!z&r6QIo!bYC(`epC>^830D96A$~ahMuif_;U=QIgPhow6{Y+HG zVQO><_7Lv!6gKw3Gd^S=bj3tv9HvH>V2_5oj#F5dU_TR;ahMuif<45sYoEgU1pAJ_ zVX4t2*h8=nR+p!+KEZw_D&sIUx&(U&cX}R5K2~(p>u!nG$r?Bl?^pIdb6P09`8c%N$>>=FcDXdShpNYyiOpPwV z9>QIo!p1&$m0&*;m2sFFU4lJ?yF7*U3HCEl8HcGsRy;mr$MLb;!>>=FcDXdShpNUE`OpPwV9>QIo+qTru6Pfp}n5bOB)aVlI(Quciu=v}P{?$+2 zJ?p(6clz|uaK%LB5~fC%V2_5oJh$};_A^nrgsIUb*h9GMIJb2P_A^nrgsIUb*h3t< z_PMQ3uP=;jq-`66`rE zcX@8>6YOV#L@gY4(P$FvA>8G;txvF@iOMBRjV{3+!d;%i`ULx#s9eI-=o0K9+~v7# zOV1u2bj1XDX!s>Hx&(VP+~v8gPq3c}^3ZTtYIF(q5bp96)+gA{MCB5uMweg@;V#c@ zeS-Z=R4!p^kQF~C*h9F>b6cNaKNFQ?c)5-y!5+e0$LWr}P^Ijl)u-OR$Gl5tJ zFj2XLsnI3aL%7RxTc2P*6O~JN(P$FvA>8G;txvF@iOMBRjV{3+!d;%*`ULx#V1L^E z(IwbJxXW|f_APoyu%C&_CCuyS66_(|<+-g-u%C&_B}|Pj!5+e0p4<8a`>=FcDXdShp9#L-YG+s$zWDGVZyz7aU7p+e1bZ}0R4(D=I+_G~2zMQ)JI*Th!3T9# zICLh^!(plMV~@P_^n)*c<=uDx^*!T|N+n->*asZvw)pS#gZQB!-VuZ+Iun&~2)!(y z{`oIBz3T4mcW<8vcX@7Gme05l=OA1$Q5lD+@j=hJJALQJJ?ZrKCc<5w!j|Qi1o0g~ z{OcfGF;N+ZsqxsyKjXx&AD;+!c?w$=6Rw!3B*WDBTX9D3A7{o{nQ)iqwq>ok!6nTQKn5c}y)L>1qQdlJ>+;yDWSW^(JL|05y z#$jswwx4+Oga7hrFCQ8vj$Qi{wk!{V_^BZNd1!c|n+dXIQscM&#GCIs0=l|*E8wbh z)G3HMt7By+D&ugwSLeEN6Ylcd7JoDMi(fei?yf5)D&sIU!hh#_f+pPMxh?)%oFHnI zxMHF*4pSrix8g%qq6v5Lb%xvWUWNZwe8_5d#YE*2rbakwEf1P-7rQ3jNevUOn5ZPf z)Cm8r_>i+Q;V#c@@pnxIfe*QIS4>pKVQR#kUGX6vG~q7KZR0Jv;zK;>iiyfNOpRDm zD?VhEm~fZpw()LX@gW{`#YANsrbevv6(6Eu!d;%*mL=S@;zK;>iiyfNObrNpI1}zV zPIsIYKCH8OF0Nw5nW&7z)Cm8rxT>CD5$^KbHuk|m z)GEPMXqc#s!_)}>t@yB3ViE3QP2-*PNBD2WhqcURfn3+{IdB{iep{-M+FCT`^G^hp7?%W5*d9CXQYE+&1<> zcD1$k!J6o10>7k2_>Z0QieMkCF81L4I>LYK&f~0(m7S=J!|h)21u(AMgu6VqjeT$s z++9~pRK{Uy@EuxD(1g1@w~c*}ucfg{Trp7@hpEALC_ZE*ns68UQ?2P`;X4!`vf5oS zQMrVv!5)YY@t_HJd2ZXjMF-)EiOM)k4ZcJ1A!lX6U7p*jLtJaZU1;N-e3x)m_^{5ZDkeO)ElZbRk9s9v{D=Sa(k;P0 z&#FtXp9yk7$b*6I6YL?}K$*hucZO0b^^o;S}YHM#_Q2zMQ)ur9%VCP-XiWu``#U=MNZ+NZES!M-EN zgGr4p!5)Hru(~{jjpW{Yl0#n<&*NCx2{Nko>*x~f(Quciu#wz*#)q#A4OdK%kF`IK zF2NoRcX^YXZ_^QNhsbRtu6J$s2KJOCjIhMOTg^lFiH4?PPmAhhsJTx4Z_o_>8FDtWU6?3G&czSZZ_$_7Lv!6xJu$&qO5|rbd@w58*CPVSR%AOmK$y zB{jMP`#P)Y@)Xu5*v|xa8o#7QmtYU!E>B^7g8fXeV(?39bP4tl?(!5i_Q9(J`pK58*CPVPhX$p+4#2^P2liaD0BB8eM`t8t(EG)+gA{1ow$Mks4isJ%qbF zg^hji{0|>`>H39n9j=(*dGkb5qf4+y!(GQItV^(;305TQH#NEhdx&G#K85uO_8o!4 zQlm?-hhQJ9E>B^7g8fYJ9@(#>OR$GXQFZm z^Imlc_7Lv!6xJu$&jjB+`+K)bu!nG$r?5W3ekS;StDT`wu!nG$r?5W3ekLlHFz;2D zU=QK0<8;?0*v|xKxbNrR{aIgf`p1zR`hp+X6YNp1T*L4E-j^Qcws;;vyd#MB{_vh) zKNBQ9lJE(=EWbZeDnB}sLq9k)cm{Y6!d;%*mgVI^JTr)|55g4_l{B9k9}{Vt|2A?! zziuMj#X8=<`aUX%cLnkKAKeq|IV%$+Z<6qt8c#%OD8F7e5$@vn``4=pR}RD_n?5z( z8E5pX;>^A>G)!<7P;_~2TbBPA#IFqE&&QR!VuI{ct}8V@D(>tn;tq3nO}NW*TYNKI z2%g}vvLBb{&GSi(?}-)ij#w$nM7WDpxKBmjeIZzhu9zTcla-kozdEux-~BR8zcl27;R2>+e&Ay;m~ zUA*1)=`Q?t#)o*&6%!=5?$0CqcgBZ2K@;xcs|L5>f@KN+o$(>7#1#{jO`rEF{I}vm zJZQpQ>^8eU!hb71#Dm95CfIXa5_N0kFH1OTEf1P-7rW-}a}%zZAQOA{dH8R|hj`G0 zyF9loOZacahj`Ex6PXD9mx?+N)=KZ}J{#)@O9yH-D z&u#JT69hhFCAwmQ#A*DJ&pf=b;zK-W!d;%*BCRHVuO{I}vmJm`uE)-is`>$o^-Wgj%* zE{;zvufv2Z2O^Ho?^7fEx8g%QXo9n-F75``m>S`~6(8b3S4>obeQJdN&bX@HaQm?` zkDe}`5l=TY!heIPx9DEk37$94CpE%yx(5&j!Q?FLmb!MbIgrAGLV zJ!)mO`&h@WeQq23;2>&OtBGzVaM-57Uc1gj?t|Ioxh?lvd|114U55$YBl~sm9f}XR zav#fGp4;Mm6$C!SgRYq1eYiglzC-aLPtb(BJhzQ~@D3lcN?b9)mlJ-;d&PGsKE#72 z+{OO1`-AULe252+mHoKvPqp&LKFGJ|@Sq8Id2Txru9#q--F?n?C_co4Cfwz@ZR~?5 ze252KF_GWb^}gae6d!VTO}NW*+t>$B_>d>)iV41Z_V+H|q4*FFnsArrwy_VM@F6SF z6%%~F?fXY~83623#(YwN7` z%6?q*_Wis|u>Xbke&Uu#&p%i0(r^0tPmJ%xF2SBkCD=n$(mem%C)h){tMa2#qf4-# z36eHn7>S#yL1O5fU=QK0&yHMB?rv(3|2Zev&qO87rv}8FU=QIgu7muK)aVlIXM!^% zsq}IkO@e)$RdrP^S!$3NIw#oAL?z9qMweg@;jYS8ON}nUekRDcBsn%UF4>t6DhZQJ z9|(6<8eD2z@;L|LiV2c8Nx)5wO9to_;jYT4OAQmQm>@BfB;VAyWSI^P6Yi?qzSMvq zx405kN$43B9hbyV5{XlzOR$GMVs|0%pcU2BnYQ(N~m0&*;l{BB% z0Wl}oL%6H*yi%h}u%8LeQ2Tk4U|(ldU6o6g8rWyRHB7i-0{^iurpD#X zFf>fKt8)8N1A?yruG|$9_>cWPHDVvUO0efx?yCI3)aVlIXQGnkQv?51#=4K?uF6qN zjV{5SiV6J3cU)@3K6sU24{_|uJjm4O66`yIFU{2G672I>nMY4o>=F6x83d!2);*I zyRMkPf4e`zQTP0s33qXPj+WP9;!x3XIsWc*&WJNZ!-Tskr8YJ2UlFdD;6Cl|t1iKw zW4Y@%5B{FVUU&BaZ+gRn&wcKmaR^b#7oYeupSUI1=UM&!Af6n=?+L>Dpoz++hmQY# z_dmSy?*IFiC$0#0d7odFza7LALHyp(aK%Jr9Hz!UJ-_ho4S(QicfW5U+~u#2_1j_|2EII#za~G7eKC{CAHJxpEWkI!=(`zx%qou9&Ed!_)}> z-Qz=^hY5EbC*knlJw9ZWxMHG`3{xZgcgBaTL=)~hOyNuT?~D)eperUSmoPQLQRniY z33u^!#XFk^H^LPYm1LM2;lDFJlL+-8#cO8FH z6#hHoL(a+-6P0n88nHso_;4oNb^M7}`0qS?7#gmasEotZ2>+e&A#2x!yN*A(3pbtd zAs%$aL}eVN1_VBw33s85ck-Es|IYZZ&Z;UVD&sIU!hdIcI1}zV?ws6Rd{}oESD|i# z`-WdqBm8&9hcn?W@AG3HJmbS!CAbO=6P0n88sWb)KCG2kguDFpG4{bTKE#8rn5bOB z)VO%?%ypP>7v7|H@Zca^F;Pi|sS*A=<3lt|xQlD!ex*kE?~D)Y?Nb#Km2sFF;lF!) zSZ}x@+{IJnxu-_>?;am=R<4-fdGmZyBmBpk`igKDtCRJc8sWctd|10dRZLXIVQPf` z9><3>aqRNM68>XXJJ&vl4^f{9{E`~sKX%S5f_<>Mj+0mT?_qq%Ssg1oQ5lD+!FMP= zoC$Y%>WlxwEx$6x-F3x8WgMnP`0oKefe&ZGU1;OBeCB+I;=?+ts+jQH zwq-RQ66{g0l5r} zf}9reU{a$?u!nG$r?4$G^zI`g3DXr59G~B(MweiZhPyn4#kBpiufF@-NC78l+!Yg* zWSAOVf;}4U@)Xu5*v~}e5~fC%U=QK0;}q5<*v|xsE3C}a=o0K9j$Qi{)+g9^1bHy2 z(IwbJun$(3r?5W3ekLlHFg3aadkA;&HGmKENS9pXI}%o1F+n~S4oi(L!JcEe%TrjN zU_TR;WSAOVf<1)0JcacM_A^1|((aEg!5+e0p2D{D?BPLIOjIsmUPqT;kA}NEh4l&c zGf_!~snI3aL%55tN_@zl_X+khQMrVv(IwbJxXV*mpI|=|m1LM2U4lJ?yF7*U3HCEl zNrtJ>CD=o_%Tw4$?md6n3!XX>h+Q#J8HcISCD_+l;VQa3h4l&cGf^3bsnI3aL%7RR zSf5}&6P0n88eM`tgu6V2^$GSf!OF)ksnI3aL%7RR*yh2Jp6!YWj?eE?qf4+y!(E=j z#y)tCeelda=!%I-GE9vw!5$5Fc?#}R5K2~(p>u!nHhaSH1a>}P@%$@)!=F2Nq+ z*tJh#eS&>Q;Fr|s66_(^2dm3dSf5}&6O~Jt8eM`tgu6V2^$GSfQMrVv(IwbJxXV*m zpI|=|l}nf!U4lJ?yF7*U3HCF=_uTG}F2NqcU7o_WZ_z`7{Y>=FcDXdSh zpNYyP%zM=(*h9F>Q&^v1KNFQpm>OMzJ%qbFg>6&OA;EqoD#gRmm>5X6Tw7YNpygk7l^-8|@&>uR^ zZOigUg7}&szC8#}bS5g}5IX+v%rAV>>3ja&tFH)md2Wlpbts6p2k{-D;fjgMI82Qf zKj)|KzWm>RpKVQT#FbHD$NU*9|t?(!72EGAqr zQAviW@h9VqUL9w~S($K`=eGEppo4fU2(H`}6P0n88t1sPpAmO>Cfwz@E#CP-@DzFG zu9&DK!_@fdSRt&GnQ+%}Zu>Jq{P7@IiLRKajKkFUy)St5!Iyr^hh7oKu6=G}AAIz| zmjv-`q2Y;cCdigajhDXQ(ff{ot}ahuvD$;EvpQCG;w6!whF?-6{CCEOT)7E%d2Wlp z9Y2V=yRMk1jKkCj|DEdznsArrw)lIag20D(&=nJvahMw6zcW5$U72tfyA5tj4~GBF z_>k4^iiyfNOpS2VxjbmXUF@2>&rP^uqLK_#Bm8&9hn$rOcX@7$zwIpue8`o%Vxlq* zQzQJh;=`G6m*=+e7G3cnj&j9BWgMnPtdJES&V;)>w=GNfZ^ehKL|05yl3{AZN?-Be zOt{NaSiG--z=wFy6%&LlHa3X6(8b3S4>pKVQPf`&iJs_6+Yyw+{K#Szxu*| zXM9+zy(%Uu<1jTYjykgs`dIGbDAdyDCR{O58HcG6{yXEtdNb6q+{LwVS5hPVcgBbH z_Nj`A$~a7o@ZT99&V;*osyz492>LryYSx`AF>i% zF~NJDb(R|8KX#le;@Gv%ZDSu~S6gcztch+W@Jnih|JXUN2=>A1^4vD|L3ZbHR>#Ut zRK{Uy@EwW|xpEWk^4vD|LB2A^-F3x8WgMmk-=XycO}NW*+t>&1Vjo=bperUS<1jV& z4#kJ8D--Twf2uXTEPRLJLsq*hCMx4FHP{1j6&^IGFC8nMz(_;4oNQIo!ukaJnb?vHhenrR58*DJ zH_x3v?-T52V#_!j8eM`tgu7UUtj5&n66|MU%QzewU4lKtv1^~g`ULxq7}@kgqf4;Q z^SvY?Mi*~|{W?g_COMQW(_>{Pwj{%$(IwcU;Vw^MeS-Z=Y#E0`qf4-daF?gBKEZw_ zwv5A}(IwbJxXV*mpI|=|TgKtg=o0K9+~p~3OV2(e*w4h4WH>Y;x%Vo;9>QIo!ukaJ znb8FD ztWU6?i7n%BXmkno5bp96)+gA{#FlY5G`a-)IxBqmp6K!v)+gA{#FlY5G`a+P2zPl3 z>l5r}V#_!j8eM`tgu6V2^$GSfv1J?%jV{3+!d;%iHV+;W>}O(2G8`IRf<1)0JcacM z_A{|184isu!5+e0p2GSB`4u?jUU=QK0;}q5<*w4h4aX2)(1bc{M*FJ^y3HBW^ zatVhj zq0uGSL%7RRSf5}&6I;gN(C8BEA>8FDZ2J~HB-qcymT@>Vp57$bL%7RRSf5}&6I;gN z(C8BEA>8FDtWU6?i7n%BXmkno5bp96)+gA{#Fk4qG`a+P2zPl3>l5r}V#_!j8eM`t zgu9N@U6)`#6Q1;LB-n>~C13o$zjB=0ZY0=G1i2vO!9d?gun)prp4)CD*iS?y8Ky>? zU>}6LJh$CQu%8HWTF8S*jW)qP2zPmI+fqZ13HB4g@i{_jvxXW|fjRgCNs9eI- zXcO#%aF^${8wvIk!Sm*crbe4!AB4M(b6cBWKM^FZurgDlO|TE**tJh#Hxld{f;^bi zXcO#%U>~e5&ut^Q_d3CTBFL56ucJ+{55irZ+ioP-PXzf``}6p;F2OzscX@8RkzhX& z?fj< z3@_L5asSJT4@uAVvD|f>?%D+V&@jOn;;__c6YMW%Rb8IjZY0=GL}eVNMw?(Cgu6Vq z-AJ&X2v!UZON}YoFV0 zB-l3ueo2is!9ED~!RqqdHuk{>_>lDMV`V4UsrTz>6YN97U7p)+B-l?x``x6dJjW)qP2zPmI+rCAQ3HB4g zKD+z8O|TEbU7p)+B-l?xxXW|fjRgCN;JXKhrAC`zAB4L+x7|pvp9sF+ zYG=5SU>}6LJh$CQu%C#^CA?fmmtY@+yN=Ucn_xc?oFNWNjgNT#OHc3ooLAnx@8f%d zJ(Wtnc>?xt6vlv$I4DrlHqo* z&fF`m+=RP4x5c;5=e%+d++9~pRFYw8g#XU<1WmZhbK9~&;6ql4D<&$JFg3z|D?Vf; zns67p&F+uz---`e?XH-pB*WAQN3G>S6Ylcdwk#%GF;Pi|sS*BL@gZkr!d;%*;^(_T z;6tw56%&S`~6(4eUO}NW*+jxtv_>fiNiiyfNOpRDmE3RUdm~fZpw()Ks1RAcG zsEotZh?TzLLo`gd%Tw60gqv1;hzDIUQ5lD+0f7%^!d+lnYJ#>G)9`=F2IE{;NN+Xr#&AY3uQ@%epfg#T82SZ{_p zmb+e&VZGssa2L;r=f3TOyhT@@perUS$uKo8Z|b$) z)O9R(vDR3nsZj(Pu9&Ed!_)}>vEvL46UVN73LE<%yV_d&U`=#0fnQQ1{Kw9DMX(Q6 z7klu29pOKA=M@hgD?3pchugj4n_=8t6Yk<$qVD0?2M593b;ShV5BMcD_ztZnXu@5d z+r~b47yIB?C9asLjKkF6I}{(X5>2>^Z@XI4%ffdkK4i7KVxn>hQ-eLQ9A&~??6c+O zu@7#9D<&$*Fg5rN#fO}g33qvJ8~fl1A9Cfcn5c}y)ZjZ5AL2n1?&3SN-jz8`#6CFQ zqOO>zjKkF6+X`2)N=&%RbK5rK3=LOIRK{Uy#7aNmLo`gd%X8b<2T!pNj$O?a6P0n8 z8sWbaKE$;q+=VvY$#)57g%9zdD<(YY^$GT zmta2=B(AW|Qlm?-hd6faQ&^v1-x1`&q(+xu55YcIU7o`F1pApFS8BhGF2NqcU7o`F z1pApFA8UUeU4lJ?yF7)BNVWJ=+x%B&hB0-7dkNW4X&y*hubO@!{_Z4OdK%Jch&4A6`T^P_r-th{zaGTz@an28RD?i=o0Mftg6dXSf5}&6Wli(mKt4x zJ%qbFh4l&cGr{x6VX4t2*h9F>Q&^v1KNGBc{E`|MM~y6OAIn{y!ukYzG)!=OexDj$ zf<1)0JcacM_A^mQhN;md*h9F>Q&^v1KNFQpm>OMzJ%qcCQ&^W^KNGA-)^BQb3HA`j zu6+vY6YM(zhowfBU=P7QSY4jN`ULx#;61WmN0(p^;Vw^MeS-Z=@IJ(0c^zGXJ%qbF zg^hji?)&21`>c4ExMG6$Iu1*XF2NoRcX8FDtWU6?3BG&w_imS958*CPVPhXW z;Y0R8S4{BzRy)JkaZbaB6X7mTVSR!mWP6tyKBN- zp2A{34+0R(!~6H{mYN zZOa0I4{?+$CMui$pm9GF?m~Otoi7^qbyj;N6YM!IdiW(Z!hb71tSc|VUEIU{D}%d> z59{t$#RT^azobU^Z^ei81dDJNYhnLd3jeM6uvSS`Oyu+b2N#X----|MppWG)*7W|> z7yeuEVXgM6m|z{_m%NUPqgM7oAIn`Fg<8JbO}KI(F4^>{5&m28VZ9mZSeykEUEB?> zaoY!1e252KF~OUN>q?FA-x*ic8*V?=-o-QGxu-_>ZxHns-77o6^XB=aM);36^~x&o zvE0R4WBqRX;2>%@sEP^JE$b{b!hh^IYwb8i9J}_pZR~@Cs9milx|zUXo5lk)W+L~& z?DE{U?X}~qjurO7BzTYP*THuvKIFRch?mYybt&1!FMP=D`1bc|erstpg1bYZ~Ren@zbP4t|QQ7pV5y`z*3HA`~s}LXJk)WL#U4lJ?yDEh?8nQ>Mo+{L#x_bcxe z{wu;26Wpi$ebpt{b1Ziq=fU6k+SlEE(09J!!Ha&wo?s7A$rsQ1;(Sx%+&rrn1@R$4 zd`=MFQ%zLHA@s65^wD2<_vfB?;)-yW_xWXczaai_5HAi5S4>pKVQRed|9#=zyWaG) zyP0s8zdn}b1App;ckc;;>u|+HWgMo)w|(@(cl??Ocky=RXnC(pxMHG`3{&HM|J>8= z-apO^4HNDAVvR?1Ac>-eSr0YR`DS&6QgsEotZ_!a->TOaS`~`?_)y?mAA8;lF!) z$lZ0tL?s!fM)>a@AI^lk4)g93{=3JAtP)pDRK{Uyg#XU?a357vMk}hGd|?XT`^G^hp7?% zJLAKdaM$rCMd80QKIE)iF;N+ZsS*A=4Ie{yXDCuG|$9m1LM2 z;lF!)I1}zVej$hd?(rdK<%)^QI82T3-#tE@33stN_lYI^$8KHZSzZzDVxKKH$KT|cU$293#YANsrUu`k_>g;L!d?EU$k+$( z@F7?3iiyfNOpWm09X^~1cO8FH6#l!zhn$rwCMx4FHTVu4KAZ@59e?5#tMCpVvUXiD zQ5lD+!FMP=oC$Xwe{vUYy2FQf&=nJvahMtq_;4oNb^Hk=-=X-h&I(uIa}%E1wyefO z#v$sJZ}Ialf8Q;^KF{is2RR7OXC^Ai5V}vW=UDFY6xJu$&qO5|rbd@w58*CPVSR%A zOpwz;9!zR<3HA`~@)WkEh8_~^XM*E%gw*H~>>=FcDXdShp9ykvxD%<-CD=o_%TrjN zU_TR;WSAOVf<1)0j#F5dU_TR;WSAOVf<45sYoEgU1pAI44<l5r}qH+mSqf4-daF?gBKEZw_ zNI2X5(IwbJxXV-6mY#h`u%8LCqjsNn3HA`~@)Xu5*v|wBYB((KRhM87;Vw^MeS-Z= zRFYw8bP4tl?(!7YC)m$KB^jnhmtYU!E>B^7g8fWXl3{9e3HA`~@)Xu5*v~{|9HvH> zU|(l7a^qqr^Ay%6*v~{|9HvH>U=QIgPhow6{YB^b2M-DMGf_!~snI3aL%7RRSf5}&6P0n88eM`tgu6V2^$GSfQAviW(IwbJ zxa&BDbqV$}QAviW(IwbJ9J}@@tWU7-2ppCgU4lIX`(Sl>3hNW>XQFZmQ=?0;hj5pt zu(1z5;4Q~K=!%KTB}|Pj!5$5Fc?#}R5K2~(p>u!nG$r?5W3ekRzTa9C<|3HA`~ z@)Wjxiyji}XM%lp_j#9K58*CPVSR%AOjMF#UPqT;58*CPVSR%AOjMF#YFs9kkuL9J zxyw`7HWdxR6%))mwKI$z=PJRTvvQZGus*?lCMuUOucJ$_hj7<%y6Y0`XTo#avV6j? z`M}c`eeTolp7*Lf!5;NWzIe)K9_P0BKh}eIRS>5jJkgn`j6>*U`3o<9(&;Tf@ans} ziEx+awq^OVL40ixj|Ab0iOM)kjkiDZr|%y6v2VO0+{HTHzxv)8#Iu8Vc4)X_qB0Is z;~O6O{yTongu6ICN6RN@!W9#hahMtp;*6f)%;Ky}xXW`}q{IaAkAmP{xniO+4pZY# z$DMss+~JvUm*=)f&I*F3$P;wML}eVN#uvm2VWqH2Ot|Yfw|!|4A0GrO(G?SwahMvf zc;wLs?|4i6|CSSR?AqtHWqENB-xb7zAUx5{1lcmF@v=uAz3&L<>f)_{tMZw@G>AH@ zV`V2^a>+PMjqu+YA95Wg+~v7#S;Bwky1TBJsEotZ2>+ey37T-1=eBt727wP*C9asL zjKkCj|DEySOt_2PX7@+u}M8m^eAjKkCjN1e-qCfwz@ZCOmXVxlq*QzQI$#)o*& zgu6VqElc?Cj1ReTS4>pKVQPf`R(v=U?(*C=-l8i$#DlJwsEotZh!wKpLp*50U7p*P zCH%MILsp_ICMx4FHDaZ&_;4oN<+*KH!c8ka#DlJwsEotZfWU_{;jZI!$64XSI;+~Z zO;pBVYJ~q*d^i*C^4vD|!4)6Y-NjYB0ZdfJVQPf`R(x1bun2c~ZX5gHiVtg*;6pS_ zRK{Uyg#XU?a3i+Q;V#c@V;?-@L$2Hv6P0n88sWb)KAZ`6@r-!xc^%!9eXu6FnZPfp5&mQ6 zydu~KtIJc^vV{NGoyS=nD?3pchpEALC_d!MO}NW*+t>&B${2Uo6%&PVC))O@0 zF3)XaAH0iwaI6wnOjO2UYVaM34_Q|x+{L%u?hn30hYy2r#YANsrUrXpIm(2)*k{Yl zV;|fIS4>pKVQTOliVyLi33qvJ8~fm0?1SUVT`^G^hpEALC_dy~nQ)hcYa3}R4f4pXB`u!nG$r?5W3ekLm8Fg3aadkA-V3fodc4+-`&Q5lD+(IwbJ zxXV*mpI|=|m2sFFU4lJ?yF7*U3HCEl8HcISCD=o_>o|pV3HCEl8HcISCD=n8yY?xp zPq6O@vSm`EOR$GvAFM7}R4f4pXB`u!nG$r?4$O`;cHi6P0n88j;+4m0%CyE>B^7 zg8fWX#$jr73HA`~@)Xu5*v~{|9HvH>U=QIgzAEt{e?F3XuM+HMqB0Isqf4-daF?gB zKEZw_Dwi-dx&(U&cX zXQDC=Q=?0;hj5ptus*?lCMx4FHM#_Q2zPl3>l5r}qB0Isqf4-daF?gB&4Y&o`!>>=FcDXdShpNYyiOpPwV9>QIo!ukaJnW&7z)aVlIA>4JG!ny?enW&7z)aVlI zA&y=96xJu$cLaV(jV{3+f_<>MJcacM_A^mQhN;md*h9F>Q&^v1KNFQpm>OMzJ%qbF zh4l&cGf^3bsnI3aL%7RRSf5}&6P0n88eM`tgu6V2ZQr7Y1pAq&jKkD;dXr!e;Vw^M zeS-Z=RK{UybP4tl?(!7YC)m$KWgMnPmtYU!E>B^7g8fWX#$jr73HA`~@)Xu5*v~{| z9HvH>U=QK0<8;?0*w2I~y*|Mn^~$$+*)xxGTc2P*6Xb%B2Ls(F*h9F>bK6MnJ&`r~ zJHO~dS656_#$jr73HE5X%X3?wU_TS&w2%jr8eM`tgu6VqZKF5^1bc{M*FLxP3HBX99!zSyE|Rm~7|EfeXL|>=FcxvfvIp9wO4_UF+h*h9F>b6cNaKNDnz;jp|{U4lJ?yF9mzl5r}f=n_TmeQ&^v1KNFQ?m>S`~s|0%p zcO9p@F2Q~#I71wk8eM{YomF*tZtD~5XM#J8!&0M5u!nG$=eDsAt~i%{&=nIrfBcdf zU4lIt?(*E$C)m#fD<8k4Mweg@;V#c@n+HdFwksw$KEF?mF2NoRcX@6b``|hD!I7Bm ziV5x$cOo^q1bZ~x<+-g-u%8K@H_s7W0C)2r^@e)sl?a2HQ=|62Nt z3vmv@6%&M7Sth>{9e%zBze{Uk(#X8=<`hH0e-x0*W4#E`^B)gCYlNyhG{4-Ac z`tgZy7suyl`2rcG-z9XQki?_ml9j74btd5nP zsEotyUY+a8O}LA<+x|S_UJZh~>xzlWI82T3-?^Tk33qu4i~klUh*~ACn5c}y)Cm8r z_>h%o!d>h(yFbEzD?VhkyJDg;4pSo>wU!4>xQktL_qhpIOjMF#YJ~q*e8^duaF?gB zWeNYS_>e1i#YANsrbgV^6(8b36Yk>DJ>0)CxV!kU?rv2~RK{Uyg#T7tRZp-8cd-`mPQDXaB@ners$!xt z4pSrix8lQEiAA`JHNAiJh5uH3SgXA%CMuUOH7<@?*#~_rcX1SI+dhbE2jPkd{K)T9 zBmB4G!+JB+vE0SAalf{GaK(r9_Nj`A$~a7o@E>oumAmU>xr=ASb5D)%A8*l>C+Lca z$~a7o@E>pLl~rQGU92_MZ)#lL?JFzM6%&S_fcATMM;@Gv%ZDSu~S6gcztch+W z@Jnih|JXUN2=>A1Vh`T0BmBqiJkIJ^*@?aK%I=8Ky?8^bF|^XL-nA>8FDtWU6?39^dzb=4)< zL%56GX7>lg$A0ano$g{?xnhEZv)v!0_Ts8fnh1BXYwkWb;fe{eqjsNn3HDrvyF7*U z3HCEV2G;(*>JscB+~p~3B==q=*v~}e66V_N66_(|hcuUC)m#fcN&MK zMweg@;Vw^MeS-Z=uww8_YIF(q5bnYS`&VE1Z^egr&=nJ`eEgCc7e|dOY!mL{_|(vj zl(BT}AY3uQ@%epfbP4tx%Uzzr`ULx#;68C(sS*3&86UC_`dIGr6gKw3bL@jF`=Bc( zDwi-dx&(X9%3a4PtV^(;305TQH#NEhdx&G#K85uO_8o!4Qlm?-hhQJ9E>B^7g8fYJ z9@(#>OR$G6RwzGpWS`lCD?Nv?(!7YC)m#f-wXTus!OnkaF?gBKEZw_ z`0m-?yIq1kgu6V2^$GSf!S`G341IzEyN=Uc zmta2==E7$OQzxRC(b6Y%*Al?zgdw+OOu%8K%9!dCw zUY6ew9S7TIiO!R5$<9g z?_Yf%6~w!Oc>Ry=3HF?o36eKS_)Lu_BE6npubT*Was2)3)r2bt;*w3D8t;rV`c-je zUl|%EI14DcxKG>_&URV;V-UYGh(8}!?uv=ZrcaHJiaYy?xWn9C6Ylcd7PIq(;0Ycp znPAUxdEPvq)cBrQA@7KlvP^`#ScR;{ypHd_5UfO3Opvt6%1n)49od}k{-D>Me)~im zyY{(lSw7}MJQjo}x|tvobkn#;VvaT z-fsJJ7ydirLp<{|_!2;lC9h;z1wFU99Q-t1tYw;zK;>iV4;+e#z^&IBI1dG~q6ePc7f= zCR{lXaeRKC8sWbcAL2n1oJDnUH@L=aA6)Sv9(2V-CD^A%`0tFX>J7IaEA!~-;u-OD zQzQI0h3zC-aLSMFoE%X3@2 zuY!nuaK(eJnBaZ5KM%e`@gYypgu8gJ?`whYP<+TLam7Ss)91b7I}{({K@;v`f7<=Q zcPKu@gU3oH*mGR=r&{@AALLtfc+iBqJhvSQS4^%BF{2maq7(H{Ji8fAaN@|J~;v33rjdL)uPi{IwtW*86|)!(aFK z%R|Ez6O~P$8qfHUzj^9&;X=4#0zI-#Q{y-P#c#R)6HooS57%|nvD{VZW2y1{AYOkVTrpAE z^r`VLi<&@kbyO6N-rh`5$P z94e7aIuf+Q6C{R`NSqpfIsEri?|RD>;jT&D<<&YzOL|Jtwa;`{8#IES@2(Z(1g42AGOpl;fjfI{LSb1k2B+a zWx`#RQkxoFbrG(Z;6Cl|EBqHe92zFvRcX7af&apXgK)(}Wz**~XN80h$GhExyDC2_ zHCTn=!$G)WqO$2z1OJ5&#~x+EU6po~8n`KZI0#ovR5pETK!gv+UTeZ#Xz%+u{tF)t z!W9$f;rrC!%EO0`^UO`StJ25vI=H*x!$G)WqO$2z1OJ5&@6j;fu1Zl$4g42A9E2+- zc>cVHQ{%D{uLyUsrrBFk!-Oj)SjX%@sc~`C&@kaH{Kp=d8YWyZfgi`dIKJUAiV5EHd~c-&{tF*o5y!5~gG>$l7p@uvI~iY>RAz$j#?-)n9RXck_;0@s z{Kxkw_v%>L3H-NT2mY%oH{q^I;mqs6e|2|VF;Us{c^&wV?@`Xmgu5zDG&S%a-=h$& zn81Jgx{8(f|FiY};rpdkUGG*vOc@k~8B9|%>gXV-L7~FudHjwX(ov3vM+FpvI58TD zR0z@!os3S>Wj{`Jse@60qDB~u_-kZ7&o)Hxn4GXn(m->%&ZuOFVy7%KJ?nL^y`KBE z@8|x5>*70Wz4qGs-uHX2dwqX=-kiuT2xp?H7H4f%CD)3lF2WHLtW*D9p+C-})G*;JPkqaRSL5hlPxW%X_=;bB z&28>>@n@+)j1KlAQBH=?a|e3}XSr+79qdP7wz%o;NXd#>dyp9Ys@=3qY(<#Cub!ZGy1!5+d{KGnug zHx2^lP@dco6XkK3HJWpF?39skmQUx)GIOx!u1u82Vb+*A*hB2I`dkw4BYk*x4)!ww zZ<(wybFhctOI=xfT{-3Cf1f$nk3@MKW{sJHJ%qD7Coap(!G0vl<1lN4bMJ+NJ%qD% z^X}Baek97{Fl)>l>>-@R7qsgG=j_qJek97{Fl%h?*==9>TF&C@irTnR)8K`JJrNV- zahNq`4)zev^6!ew9qdP|n|hO_+p zTCE#gIM|Owc^qbqnS(uqv;4bl%YqN~=wLq*<#CubAVvp!2xsve=#c-uEHelDktmPD ztbud(=wM%Wg$~Kucg~rE{YbFVC@gEt9PA;S<*q$#>~MUVxQILlGX<=9PDQV3d^ssc3YtABl1@%o;NX zdkAOwciUPYyl}7|iSjti8Z!rb2xsve=#c;3`rw6w{YZGyJ9{Hj2e!ZC?~_LF>|n|hO<0{%^mDV z0-qNAV6w){!5+d{p4-l@p*sirk>L7VA#2PW>>-@xDXcm79-jNQyW3hhVxpW3v&PK9 zo*K^b6gGFTABplM%o;NXdkAOk=eC)H{Yc=r!amCyGY5N!eO8~_<_`8V0za6nF>|no zpbu7-=eD_n{YaEAVb+*A*h4tWb6a!ny>PG}3H-6pOV*e<*h4tWbKBg(ek97tFl)>l z>>-@xDQxawKN5H@b$!en>>-@xx$W$py>qZ1iSi}P=a@OzLpaM**xbQ>B+AJ!Ys?(% zA)Mv8ZSG({66H&nHD(U>5YF=4Hg~WeiE=W`8Z!rb2xob2n>*N#L^&B|jhTZzgtPY3 z9d~v6({5=F#EzIKkHf4nbFiHD(U>)Nq#Pwz-4-NR%&O)|ffiLpW=eD_n z{fs~_S!3p44?!QSEYEFo2m6sIU&5?0bFhbSmglzC2QM7#N1}WQv&PK99>Q6k+vX1T zBT>GDS!3p458*6NVRHxjk>EVn^)Yj>hj5nXw)0tZ=U_h)^x3ZSnS(uqvpl!W9qdP< zdXBhj5nX zwz-4-NR-E6)(FSY3kQ1$XR(jb3;#WSqID3XgZ)U9$6?mkTtg4#=vmit7XPiEUQIY+ zqC5_>#>~NJ%Hpfgr_`B){YZR8I1r<-tTA)2hj5nXwz-4- zNR-E6)|ffiLpaNG+uXr^B+BD3Ys?(%A)H0G>H3&C*pEbc9A*t%dr?(6Ti3OmMb|8C z&K>NjVWK<^v&PK99>Q6k+vX1TBT*iQS!3p458*7&ZS5<1;b1=!<#Cub@OB;@>>-@x zxoz%XKN96}m^H#9_rk#*!dafe<_`8FQ67g`W9DEF;jI01$6bvM_9IbFhFN3gU|)BI z4$1Nq*81RugZ)U9$6?l(IoLxu%X8b@!G0vl<1lOBoIN_&LpaNGTkC@t4)!Ba9*0?D z(_nM9_O+blDeSDlMmS=kJPxzQ%)y?!a+c?|xr6;kl*eJ#m^s)(ILmWe>w^~#_9Iaq zhgoChU=QJ}{oFQlupbF_B>OjO%pB|?_E~*yn>*Og2o#nzW)Aic^ufyV+!jA!W8z>x z66JB2HD(U>5YF=4Hg~WeiSjti8Z!rb2xob2n>*N#M0p%$jhTZzgtO>ReY%@D*pEbc z9A=H}WZ4wuYdMSF*rz)aj+iKq!>loLu;;Fv<+*L{U_TP&ahNq`4)zev^4ylw#OPo@ z66JB2HD(U>5YF=4*81RugZ)U9$6?lpj&tE)58*7&ZF2|vktmPDtTA)2hj7+@y5p`! z2m6umq_-^p>5qKM@#;sOc=)Ivc>L-}IbZybZ`jXm%koFq9Z2C<1lM{{4e~Ks}K6l$6pZptUk9b%N;>{L=X>&8lLDz0za6n@oB&CSFUFS zbY*#NTb3^l;z8S8?IWEikHf4H`a9K=n{bxrw)hF-L7+oc*AWxtahNqieH9}EqY0!kTJhwFs zo(V@xl#^lB2>q?-kh?PBEYEFmZVv(-qCrPYl*eJ#2>q?-khL=5EYEG>G8P0nkedTT#_WILmWe>w}G`)kRg*Fi{?dStInfqQiQF zML5fITkC@>Iz)qxm?$U1tP%QK(P8Z?bjV#f%TrkEgDX0$-Hxh8qC5_>#-_oQKIm&X zi>nahN@oo=!VweYWSBKVe7wz%o?G;Yjijg z`>Z~eXz1Tx3xZag$}u^eWVlRahNqYht`vuaF*w` z)&~#K2ixj8VuJGnddV7`L(w5`(1f!*x3xZah(5TYK}SrK$6?ms9EuLvS0cSMJ%)`YV>!z~Nv(CCA$J3C^+bKBg(p6ca%@&9~& z{5_f7bock)ar^P}p8br&(_fShlIUV2@CCsS272yb58*6NVRHxjk-*;sKbWjBbFhbS zmZz|}gZ)V0(}EvN)|ffiLpaM**x5C-xo10Kg6s3^tTA)2r-rjUg~jjhP8{qQ6?Ro*-QeePgC61;ETXx5lH*h4sLKZVU4>_-B}6?SIUm^s)(?6dk5Hg~X} z5%|GmjXNg}_7L>J%JLL8cd#D`ym9(-%pB|?oaHHO?qEL>_+$0=F>|noaF(aAxr6;k z;Pch@)y%;j!dafe<_`8Ff#*`!$IQVV!dafe&hFVwgN~TMJF4q^=3q|^XL$;nJJ^o| z9$5W*HFL0sa2BVS`nt{?>_?(}33Knx9PA;S|noaF(aAvj&@cwj(CEKEKWyGY5NW zILlL5>w^~#_9Icggjr+eU=QIePhoQh`;jPL!mKfKu!nHgehQm8*pCD|lKq=CW)Aic z`>Z~N%^mD#1bWFD(FZRa>>=obmE|dH?qEL>bn5;bGY5MJXL$;nJJ^pz`4Z-H%pB|? zoaHHO?qEL>eAiJ})|ffiLpaM**xbQ>BpBz1b2wSvc@Z(5-#Jd3iaX=3OgM{mVpX!nmk05jAb4^|Oq9oA)_8Zk3s#ubHQ_AJZOiiSg5WK( zOB^v#PKH^7J;mN)mzZ$Yer{t=K~TdH6XkK3HJ)<+tFC_HsdpS-J`nq?KDRB)rw8%l zL40cvp6Esb2brw#p*gFuHoxg#dZ<1p7MR(3^) zXwZbSJh!#4=!y=}ha)D+<1lN)o?6i%yTpXEJh#Qa^bP_YQo|7w<#CubVyCa@5Dl7e zmZz{~2{oM(A%vRrLmoa29)^pO)Aq5VcDxVxl|_vqtD|MTfN$i*Ocux}W+&e=9ny z-ChwB>|^w@)kqDl^g&+|cZ5&B!vA$MiMSv(u-b?$>JI;^ix zMNE`0Vb%!!@r7GiU0=&tyd&Ow)(HLa6kedw|Q)wfbO9bR&UYvPS5S&Ur!52P?~S+p>iI=+5n~ z_K{AM$KiRcI03XLH{mSK619fm5)OgM}4LVaUeA3R1MY)|fpiSjtiwThKJqC+%j!daf%a+*Mg=)(~c<#CubVox#S zv@f*@XL)XGeUKTa)o{c_c^qbq*y%@fhz3nK%X3@ngU9HDt*bd=qMQt~M(FQ|4pFTM zXHgsN88<^IPW`QK*_gtNFlSIakO!Vwc(pI>K< zcf~VsXWW$uXL$-+mY)yebA#Z?9WlW=@myKsy|J?Ij1^{eO*qR_Sj>Y#ydwzSpd%)D z-@Ko!@oTX|ekgVdyTpXE_EXqz2ElG*CpuyR#})Qj*7%Yaz3%Gs|ICXoh<#R{!ouY^ zh%XG{Q=^6_x{<&SCTl$NMX$U5lM@2EvOI+?%hv|+dD~s>Bb~rksy|2Q?^I82!dafe zmL>FeLWiubBPPn1FrOpzcS47}K@-mM6c!FgL7+o+i6bWPD(d?x^tYlzcA^Pq(QUdu zAZoWeVgkRiu8&aES{gLrEV^dbxd}&1;2qU<9(S~&Lo{f@S)Rg{CG@wVL!R6b6L?_t z?^Wn;MTe}e31@i}p---@L!dafe;?E6&K!?!6KaHDXjIu6&=Z+!TU!qStInf zqN>`7ML3H+-A{e&c8J>T6*0j+MlV@oQ`AZy^tGJDRfwJYAgXPIBPO^$zs?$=KfVm@ zu1q+KXJfsxM(A%vhdj9>CRit)D{F-QPUw);HQ_AY5$`=~g#J$GkT>Xv3EnsFCu@ZM zPUw(bV!~PMPWErs2>sCwR(7HzCfK*^v#b&NyKXuhh<#R{!df4^Mu*i0YoZ$o^pZ6~ ze^=;mBc~gZ9mj;TJcYGBc#J;Sx|$;<%9k)T z$T<`pqCpeR@(kDd;4%7O>&}jtpkD9iGY5OBm#^Ws-}Rlhu?qc^F>|mV37j5r_=KK2 z*h4srx7kliGY9*TD5v?XF>|noa2C6=pZaDF_9KDwCJvujBOF679PA;S#r3Jfe~)j8 z2uF6r=1re9W)AjTi@Sg#i*;hXvc}B8ek979K5Kkjc(URgTAr-^TIokm7Vn$)o;79; z_8I8}@0&N8HD(U>5YA#3vK#YCGY9*Tz-g16nKfn(_7MB5K84L4>}Ld?pywLbIER*V zZ_R-8!OG&R(4PZW($T>_pRf}+pZ4dNIoLxui?3UMA2SF0k-)*VzmJ)NJ%qFPO831m zbFd$Y@}|$VnmO1*IE!x6^)Yj>zaTaT`>e5fVIOhN_Ok!dYCupI%KkvLiNc`m8Z?u%`xh0Y#Rluw}tHdvvfLiE^;d8lk@n2YU!- zc?yf4AvAHY9|_(!Z!~Mn9PA;SwV%Rp&PIoJupbF_B>OjO%pB|?_E~)jn>*Og2o!d% zafQ~a57rEreK4~;h0Pu8sbPZeNPmu*gFS?^JcZ32>_>v{VSgVp2YU!-c?w&WnS=dE zlsA2@)y%;j!ddjEu8*06{ROc(*k_GU)P;jRMETK^wM;5PYq{r zUg+PenS=dEl+%1Z$IQVV!dafe<_`8F!MUe@cV`av5YF-xHg~We3C?fT8Pbn_bg+kT zmZz|}gZ)Tw!rb-2BfZw1_Ylt7Pj@p1`;p)ddq1B!*#FPpyXov;&;Kvqr4RovH%0B4 zgFTUQu!kt8dH(<0!5+d{=P3HSqr&9qdP< zoaVCz#OPoT;jHrW${I5V`;p)daVpIkIEIc6_H|d4RqkV11IN(O!G0vlX+CSr9PA;S zRsL#OW9DE#5_nwV9Gf*Z@64-m!o<@D!dc}Lmo-c{Vxl>QhO=(g*gQa64HM2PkGia3 z!VwcVhT`O#HSqr&9qik+lvTccSz~iQZFjYch`=!vN8+q8bFk-H&MN=GtTA)2ABl3B z&l)oadkANhk7CxCIoOW``okeQYs?(%A@*762bncy4)!wwr|YaSbFj~Ar5`<6|noa8~(@W{sJH{Yap{zOP~@ zUO3o8IICPyvxW&rOqA1nK1V3(!oi+vISaQdu9h`SIAQ|*@$0NHbFk-H&MN=ftP$Um z3kUm=V4eE+YUW@M;jHrE%^EWY`;p*%^G5SI@K_%m>>-?0{!v*2ANSG0ek9np)ftv0 z`rw6wJ%qE$2P;QX zHCWxz!G0vlX+EE0=3o!utnydO8Z!s`kzmL0<<1)0PHc|QzLv940o^ETm~g~IIn8H{ zO;N3e31^i@UDhz+hzayZU(6bO8Ab>*V_E($>RE5=O%U$5$KOPS!3p4PYq|4 ze{DX;cBXC`bi@Sf)W26V2YasNto=Or!YAK(c;H`p`PElly<~OwD(8#0{me~g2m8FM zuM6VAL40Kp?x`lq$q;&3UjD`x9zO3c-*-VcYkvZGZV*oh;`vd-5fkNPm^FUzZ$IPk zNniZP!$>&G=au*!mLQ%K1kd4!iSjti8o&Opo_OGYBjGHcyTbWIgd--(<1lM{cHGgs z;?AgH!dd&1sY>SlK&bg-60!`xElhgZP_4a956)D38Oe@sQXd zFNvKp63*J6^ndTAFTeWpL9i1YF;O0eS>u}@bI+6h+~>aRg4kzyV)@u0z9@*VjvD+< z4QDBK^+@0?lQq8bG56d%BcLm5KY4w25MRCB)jraR@;J;Ip}%W%$dj9J)_#Hv{avF& zR@V^|<#CubLVwrja3q|yn|GJc-!(d9mpEdgJPxx)=ked zJE6moaMu2Jib8)UbjV#fVxl|_vqtFegbqi-S^MAd3jLkXAv@6#6XkK3H9~(UbT|^u z+W*d7sOf|b(V!zH%HuF=K%m2saMu2JAVYsAbXa$Vs@QQR%E>Tmg#J$Ga3q|y@0_8( z6FRKbMTgWdQ67g`BlLGdha=%E_xbo&LP4Oz+9l|a8YargFl&VVPUvtXoV7cz&<9WG zkh^lkM0p%$jZK3WgtO2lS4*9naKuD;9A=Hs-w7RZS0?F8D@>p z-!(cM31{t3$f3V$bjV#fVxl|_vqtFe8Xb;=v)G;N-(0KE-!(d9Cpu!HJPxx)=9TPb{H7y4tDwAUdS_NT8Rj5&ENZUJ&%b%Gys}p}!}gL+)xH=|p)PW)04v=x`*Q zwVxn4hoVDP*AWxtahNqie^=;mB%I}WccBknp+k0wBPPn@Fl%rQMTaBdEYI!B!Z{Qj za#xO+D38OeK@UV#BjGInZo>I2+6YHXl*eJ#2>l(OIz)qxm?)3KtO0=zN5Wa2;g*GSC_1dWLWk(wgy*(U^UwVB;bp&c-_?)3 zsOLA)ghM@--`g0~EG_@(}bw;XPH}O z;Ve&K%kt15o)H9Z&=C{mahNsOA?%cqaMpebV;8a;*@=#rD38Oe@hdOB@)5C%TcqTPAD#e=ok}dPYE3mZz{~dEiTKxvsm~M>;F)m5M0p%$jnLl-9dcJDoaHGje#a{a zbjXuCVxl|_vqtFegbqi-S)Rg{CG>YfhrB^YOq9oA)`%T)sxP$(XL$;1-QZN+z!4MW zahNq?r=QRvsx{#(PhravYC54qH0X$l@;J;I5a@6uoaHHOS-2~7Sa*f0=&2^k<1lN4 z{&?~W!dafeS|4O}uj_rFDr%T0kHf4H`a7Y+k#Lr$u+|4p=&*JPI;4h)@;J;Ip}!M4 z90_N63Tu7vgbr)Bqbh2cU>~EGtg&hEf^ZgBp$=C%Yp@ZHnBe;SI%|afPUx_{40SDM zc?xTN@PrO|az{**$6?k8{hiR^NH~kP%6re}2>qSVVSPm_Vxl|_v&QzNz95{%?qvUF zjjbD;*t?FH;5*Mg%Nn6SI?e^L&+1cH>w|Q)Q}w}`=tcs)WR1`to%4dA4_20^u+|5! z>aO;YPL#)C*5J#74(kL^YvL?VVXY5x%4nE&K@-mM6xRCSA^Kq3 zC61UVkHf6NITRhTuS_`0Q&{VRhvx5j^IX@*cCx%6oaHI(d=_nlBPKY9cAaw$ zMTcn6gtI(_wLW-=KG>ez5fkNcm}|v36dkfwCY~MU!ddJ}c0d0;exmin!G0vl$uMhd9-z%V+t+dy*C&=WOgLhqdBLurM->Xo8Z!rbYB zB=FioVOeA5U=QIePhoQh`;jPL!mNRFHah(5cyeFMS#+DOkC}r#HB6K*Vb%ymT{zf7 zIE${?b#B5D6ZoN_m#i^!u&0KzJcZ32>_-AWG!&LKW)Aic&f*k<4*BnM2m6u04-JK7 zjhTZzgtItRqQk85$>DjA4%xeom?$U1tPwl?!oi+vIm=Vn+`)b%%E>Tm%pB|?oaHGj z{>8||!G0vl<1lN?9PI0^&>>l#!sZV4Bf+|%u&gn2u!nG#r?9z${YbE5&`Z{sIoLxu z3l;QJU-ZEX2m6s==cAXbu_>y#XZu>t@)S0Au&0IzuFtQtM)biGI;0Q!TF&wmHg~Y6 zh6&b*mB<=12YU!-c?z35*pCG7n>U&@W)Aic&e~65GY9*TU`Milv&PK99%7%>r?9z$ z{ft0iS!3p44?!QSEKgx`2m6sIU&5?0bFhbSmZz|}gZ)U9FJac0IoLxu%Tw6g!G0vl zmoRJ09PA;SMSns&{P*}X$T;;i9mZ~V#034R>tj1vHhq|I7Jats+=L@0%9k*oW9DGb z{W{B2*xbQ>B+8dCYs?(%A)MtYZ0=w`66H&nHD(U>5YF-xwk**HFC6Sgg7aH-hSqT| z9PA;SB+BD3YizEeM?2U5YF=4Hg~WeiSjti8n=fV?dV_+;jI1K zHgm8aiSjti8Z!rbh<#R{!sZV4GXig!tTA)2hoBEu7GH%v-OU{AN1{9qv&PK99>Q6k z+vX1TBT*iQS!3p458*6NVRHxjktmPDtTA)2hj13Bv#yVsgZ)U9$6?k84W9kzeJy9v zHBlQ^I=g2#4LV|?oD8$Z%)y>(Im>g~+`)b%%HuF=%pB|?oaHHO?qEL><#CubW)Aic z&hp$gcd#Fc@;J;IGY5MJXL)X$JJ^pzc^qbqnS(uqv-Z5Y9pcXovqkcd#Fc@;J;In+BT~ zwy)(ZPhn>bHo_4TQ6k+vX1TBT*iQS!3p458*6NVRHxjktmPDtTA)2hj5msu(^Z%NR-E6*4WOX zO;NsloLu!nG#=eD_n{YaF@Vb+*A z*h4tWbKBg(ek97{Fl)>l>>-@xxoz%XKN96}m^Ee&_7Kk6Pj}G=FC6Sg!js~MU!daf%nse{rQ{!21 zYj(s0>%?s>_-B}6?SIUm^s)(?6dmZ zHg~X}5%|GmjXNg}_7L>J%JSSccd#D`e5Lwx%pB|?oaMP~?qEL>IBNCxF>|noaF*w` zxr6;k;8oQ3)y%;j!dafe<_`8Ff#*`!$IQVV!daf%&hFVe2m6u0JF4q^=3o!uEYEFo z2m6u01FL_pW)Aic&hp$gcd#D`yuA8%cjjOZ;VjQ>a|ip8C|||tI@%p8Yar)Fl)>l?CY-3Az7Z=<_`8F!AhgBtTA)2 zhj5nXwz-4-NU&p2Sk{<1*h4tWQ&{VRYxKbreb5mT?0giKHD(U>)Nq#PwzCFz4)!C# z^|?aUm^s)(ILmWe>w^~#_9MYM@myJB=3o!uEYEFo2m6sIC&R2UbFhbS)_!iAIoOXx z`4VQ0nS(vVKC91da|inwfnKsk=a|ip8 z;CqO|wi++J`+yF=GQ6k!sZV4BSC-a`j|P`LpaNG z+xaZIbFd!?`fS(v%)uVQS)SYG4)!C#d7*!=W)Aic&hp$gcd#D`&OQCRJ9DsyaF*w` zxr6;kaDJ=KFn6$raF*w`xr6;klrLfK-I;?ugtPY3-ORy$B)CHqmNh=+#=`?+mdig;iUtZ1D-Oq7!$^s@ZuS3T|ckSD#R)iB{K-hV$Wy?G;k z=S@F*cChEJOq7#h)_Bun4#!(=ebDiD2f|tG<9_OUV-Pn7@iFlnj+nsN1wWXq@fEi| z>d5~-dLW#|^|@NEt_ep>aD9HAH9j)#=m+A?xGNLRVx9Ua{PzcOPY^u0BPPn1Fl*ct z@8Vy^3bVQ=F~s+Rtr8P{R=u7*k|>*ZCP#$;-iCjSk&-DHxl^4WR0iZ_p0j|0bN;q75a4d~=>?;FHw#5sF$%gC?9s*X%ks;fM*mqq@#Re=9oV zu1q+K?%%&xp}!R!^5l+~C||-{tI*$y4q06j&hp&WzM?BSWS2N%qI?OnM(n8-Rk2G< zILmWe`?fcN8jhGKC&R1}JAFlm)G*;JPhravYFg1D8g#@&IT>aR2y{3S&Z2hj&fFC` zM1zi)pdNbJt<|ZXysqUe*07&4w$(k=>Q=-A>xN#kM(A%vRrLmoa29)^pO!*@ji_Bx z5fi+B^pZ6~e=9nyomhmk*wg*g7y4V#VeR&cm|!2Hm#ncVYNZeQTF&As#Lj&X)i%Nr z6I`EPXN}O`iVo|`P}g!6&&GOXjnLnU4(sbv5fiKv&y_Voe2kB~S z^}(9xMgqNLjnE&R^MarcRu(>_ijJqCeH1UKY-w=#bs+ zhza^r*9SeY6lKC$^x0DLvY2qh1bw#aoO38Te{RM#zd2&Zga9-%&E6$Kh!%sah*#7;k=Lu#0C zmglzC2anMQTUT?$MEMftz6$*v(IKie;Vf#So&1(?SLhH8I%2|eTl|gRUwy&xgMZ(h zhd=!R-NByf<$Up)*MI143R{*R58^|EcySP{54sqM@;HQEmNz~6*~jnu@Si@sWFVZy z+hq6WlfN~H?+xOQ2jPebyi)L%$r>O0%G-|*|HYe*PZ$Viu`Bzj?}Ikt$w4?`0%sSz zWwORoe)+M-_P>E}7T4!$`5Y!3F;Py2S>q$)86F&W#$B0k7VE^SWQ|7z!PE2Pj+iKq z!>n;ntn81)3Xg=dc&ohKtnr#4PC@Vn9WhZJhgsvnu|wD?>=F~s+D~B*3F2)*uoE3I zQ67g`#m-E$BU288HjyWpTd^qzXb6$K|C=CPjn-Jw@lXfw_p3Z>laQ4=*r@& zfU0t>-XFxD4T9&`M>kedThZZ2IEyvxrwmpX9oFhr#6)=r>*cd@W~j6=J!sOgLhK>+|cZ5&B!vVSO3uTF&CxSe2|1`s3@8U%HuF=g#P$auj~>N&SH16f3rsD?}QGk8&t$Zc^qbq z(BCyWM1#K8KC4e*tq)$K!|H=I(TxOp$r_=*D|9##^ufyV6c+CCL7+pPV;|{6c^qa9 z&Y|dVB%Hm?)3Ktid@H9r6ZEIE(Lk-&dSN(IFai#02M{zOOik)=o6x zEc#RJ>1BaHhwOGoOmLp-`e;3nUN{iWqR*C^m&Jr5CODUNopTOFhuoD3XK`MrZ_Kj9 zQysbHqe>9A*v9q393|ns64idq3wKiVo{JDq_Nu zUQBmi`r;$bq4=dbQoe?t_P7r{JJ{!4%^d8Bn7|tnPf+N&gFS?^JcY&IZx4TUoI~+< zcEm(^(`SvDgFQ8z#ja%c=X1;)>_-BxP8>e7#^xH@+_QZxXK{UES;K@QJ7V*u&l)oa zd#=S@K#}DstU31{aSnZDtd%1s%E3Ns%pC0Ve$$VhEKgz0xwm=Ve|Xf`M>@g#=KW-i zpNu_)bLcV<&e~65GY5O_$^=fE?6a(ao9AzT*w-IFKWg||`>Z~N%^mEiF%o!!o@-oF zqnvwd2BZ&GmZz|E2Ob^lb9Fm`^J#yMnS(uqvpj{xIq?B6JE6nh`?GnsAnDiJ?{?;3KN96MpU*LKu!nG#r?BSSd*NU| z5;!&Y?=C*r=nxJ1TF&wm7W*m)bVxUF#6)@1=W~QME*$K+D`$BMn>*N#M0wNiYU~{B zA)MtYZ0=w`65Jtr$r>{U`?{;j@)S0AupbH54ZUQInS(uqvpj{hKDb67JfT5HOq4f$ z)|ffiQ^Q%Ppr86?4)!BaPV-q~Q`FAE9>Q6k!kT;b3U%kZ?!IZ~N%^mD#1PVLXpx5pk?DNU#YMJFJZ0=w`67=2v95V-d2xoZ;Yklw#eQ>1@ zI%0zFVSgXd2M_45PBLhk8qV?*Hg~WeiSnk;wVFBD=ac{Y8|aWM`ct3oW)Aij#O7e1 zH9}1n4)zdqvC;>9w(H!4BPKXuqOhznbFim|vpj_@%gn)kB+8pUYs?(%A)MtYZ0=w` z5}bSbcX#Gs58*6NVXY4y(P2$RD0Cz^zg1_LJJ>@w%Tw6g!G0vln?BcybLi+`58*7& zaIFs>|8Sg=IU(;O?+w+yqrGSD5WQp#)@nNeTvg=9e(I6uKOg*pFMQ;AZsWh_T5YF{ zD^?UGjRbEHeL|n#;2|`)Bb-%pTh`ci3G?8UBPME2%o^KHWGdPb&Z;RaYizsy_}AZc z_mv|i&`ncrdyY*}oJDtpvuX;<8YUds5!(cr&#`?OjxUQECTg0@tenEK#`g6&{^NM^ zn)`^Ds5vodChhH{zayN*TjlL$jqNMSG;!sKiJB9$MocVxshL=IgtOR%?76J5b%SGQ z@X8SrHT7i;cKSAX?TCF=PGMQ2CdioX;>mktBv9_TM$Lme0=lyJD)i^rx-(Pi)jraR znjo{rb^>TmZo*l7-TM33P8m$wSB{vdsV{5%FLA0wRlGqH`>dSXa;>)067yg@d5@T= zIWcSe>YwT4QwWJhchWY!2pak6Y0G(q1(Rb4mLv&Qy26DxhtgtOSwXeXaz``wR~KIn)E_Hmozst?w5wEIYzk>|1te*4Tb`aAhYtVuJ5H z`z&jq4Rlx?r>?cn%DF9T)CAf4U{)Uq^m49I^WfG8>wa_2B&(*dbB#uDSNljOYJ$uf zoI_DnodD`NoW=LBR()AGheDu1M@(>j=3!tyz`>2B+4Jz}CJ$gBZDuT9l< z!dcWtZMz!GgS+X@M9qm=K z@#lZxrsF3MgtOR{ZTGjX_BlbkD~Qhs!VwevDLH?BpEcfc|6`B*?=uI&S)Rg{#e^d! zxIVwm8t;xf;?B4$6VCD!wk#002f>p&VuE$zxw6K6v9doGE6nPeaF(aAW%;Eb-W~*R z&=C{7Z{APVcz^7WAB>&CE-~S({S@}TAlQxUL`O{U=iThHtnsxkdfnCM{h1eE5c{k? zg)Pf7gZPs{d}`G2L^l%rX?)gr>5E=>{e=?(y0SclEz6e#@%h_b?IWGwZ}s%&2>qSv z$xS$m(*SBq4Tk8wj#gBK22D82 zQ&{}WfsNqF9WlY*K~#2I%1;!R%q_s(BFy<*(D~N z#i_7jj+m&w6`D0de=9m131@iGJqQkl?RK*jTpdNb38az2V90_N!hG-|(D)hIa!&=>nm|)$|OV$Yet?01cU=hyp z6xRCSiVka+pem}H;QgbQtP%QK(P8bxBAn$ZEPh5x5a_UWdz}YOu#eG8*4Q+-(g%Gl zXSJ)G=Qb0LnBe;SI%|af_%gJ+GT|(qjrGd+0f7#Aaz{+CPCQrE2>qSVA**Y`S-d0O zd)5g3ozNj~&=C{7Z{APV2>qSVA-lwcv)G+|x(of$4OVudBPQ6l?6a&9`nyJlBeBow zQ&{VR*XXeNV9k9afnKsk=I@jdMC zgL5c4WOW@e!TF)T56+?JkT+<;S)RgLA3Q`KY`eq}6MWbEzTzB;4%vw&oYl^uXMJ!E zt=;a33Hnpl2R#r~p+OVQqR*C^&u7s_IAVf6+jSmybVOBkLau8$%TrkEgN@+H9WlXq zp?|M9hoVC?Xu?^Z!j^?|C_3Z~I%0xzPyg<64n>FT5);ny6c+yuG6-~tq8u^7`K|X4 z&Y|dVB%I|bto6ZT^ugBE95GRUD>OC8ITRhDK@-mM4A=VLG5TQZ&W@O%9(u_duXxI{ zk8gYS3lHD)9Y1?;r2h5cvz~X$`QHzA;;ljatsqz*bV0-f|7w$etqZ*@zw&~o9sk{D zy`|MK;Vj-}KP|l{h<69^jZwo96a4E_{_%!hVuF7u%Rb8*PrUzCS3mL8JB}|Oh<#R{!j|R9LHu|S-x`D`x{=^t z>t>BlzyDR&GXlD@_$u`0cuEj;SNljO_*eh^Iby9&_2ed;#n-LBk65clu)2`JiJ7R)=5#RL@ zidsv9CY(jr>^e8$hzb5>f7f~FZ$*dPl?i9j{rmSS^tYlzp4<@={Dgx3y^57xQ570A z;Ve!u^>uAu(MF&TM@;aO7W#KL^tYlzc8LjRaT?oogB2Z8!x0nw#0d0~`iPyrqC+%j z!dafe;$J8Pfez82BPQzS%w!D+bT|^uqIU1j+!Z>kyQ+u@>YM`U z@g3>U5&EM$x4YU$I>C3OKL_8cdU6xa;(J(Y7=Kr7BUoKWOz=JI?}Kw_y+ISs;=5kE zCw{*@PfKl=IAVhDdf!)^L(w5S(S)<;PhB6JL(w6--4PS?r>+lrU@6Lkv*@#>=4CPA zhza^^*E#1$C?5Cyer_dh0C95GQ2728_HGvI^~KmGe?!da{n z&zLo~pKgrb#L*EG8U%Aq1_d|vFSzaM*x zU1Gvn>_Yb3RwD>@BhTT8iE^mO8u1h5ulR|&BeBowQ`oX>KQ;RpKe_(siEbqL$-r6T zFT~He|A$dyB%mvcuR?#0?WcdYyV^%OQ4SSZWBUo?7lgC;y7l+5{S@=Ix{jDAhl;H6 zIWN8Y^xwBPXu?^1rTf0xej0n*C61UVhl;Eb`r{|Qx92e7EV@nC$M#d@k7&>l6Xj5m zHMXC1-}GU^S#-^=a}$o3D2Ixy5&GjN@Z&^tG~q0|fB#->KjpuDeH<}S4i#AgzX?=@ z22D7NQ%rqbn`=)a(4ZqG%Aq1_g#K1^hz3nKi__Sy8?5})cNFD_iE^mO8k@7j)krwY zQ`oX>?h#ig$`KRgDv>ope=9m131@M)y*qPP=&yo0q8uu+M(FQ^4%sCpoW<_!Q_p8$MfVS_E~)jYklw<9adMXiEbp&OV$YeU7^E~pbu6S-;w?tn;TTSt9_&s(BAvIgf+ zbjWjtk~nThX8+Cd#2AYlNDPr6?25qR)1nn{dQLIaFkg&5;c!ns(l;YdMSa zLVcCO$340~u2Vd@BPPnBB5QCCMTcn6gtI(_o!#r&SJV*`EKgy}vbne(d4rCaC1`)2%M|PqkCd$D+ zYlQRr)q}!ub0qdzeF|Ha%~kjKkf`B_ZX|FH%^G+7!e6<@2XrK$E6Y>ZvTW|a?XLEb zPLzXv*4P|~F9>IO3X8v&kuJw=bsaHL4)$5&8=ia@PRi{KnsAn*Mrg47=#M6x7y4&l;h>6&<2M z6VCD!7Qdeu1Uf{6j+iJ1`>YZAThSpJG~p~yVau|)nYXW~BPPnhK5K;jR#b%sO*qR_ zSo+aJpeRR7l!JZN2>s#wel-%#@)VYS^ym;pIbxz5?6U@b^yqLToaHHOS;8H7MTd1) z=#cJZq8#kA27dJDa3q}NDQsDy53cC2Ru@%K!$djQXN}O`iVpdT`dZHN6xRCSiVkaE zp(<*aCu&Y|cK4VrM4r?A!s4{;uCyWJ5JoafL> z*4WOXO;IMCuQdeC&}jt@Z1&?{bL_`eCcx^d3fSq{F6sV9`MEQ zyYVT{c;}4|e)i3`c?yf4u@%G%f;a}@h>6?Z|K1xv_D%0<^s@YuJ05iWo}c-;!(kwt zh|dnf5fd+bUHlB8=l$YV<0t;e`wxHU-QROTIE!7$?$6b|FNmuko)9%0 zG4V0q_A57T{M7%u)%fmP-*Mo7BjGHr&(*Sq2}ewDeSXbKFUu3+j_!{;qlO7*c?w&W zTZ4E@5UiCWCRit)D{K6tSlMrj6&?v^c?w&WR|mmc2K|Cf1cA_ID*pckBtnuv6e(Kd*U;Pmm#6GJ}VaxKoAbu=}tEl0LZY19RQ&rN!GxCv?b@n{bw=uw@DTooaO*F>!dwkL!Je z{!aA)eDRCVuITAC}HTe>Imh>5@VMe)-}&flxh z---@L!daYR&`#Efx3{80H0X$lAAIN=_1%pfvZ6yYXu?^Z!j>iUx1vLKq9Z2$=WFji zcZT>ITd)3z6&;R*vpj_@OQ>l@hiK3d6OVh`-R&pPq|PDG;Yc{kQ&`>=I;^`wRji^3 z>YqSV;Yc`(J>5@zp}!M4tleG_6YOL3k~KC(T@cRVD%8ofGU12`uFtQtM(FR< zbQrtDgtI(_wLW-4hdj9>CRit)D{F-QPUvtXoW(ohz2|d;{`iWnyg^4y@Vez5fhw4`}c}-C^}@VOgPI^SWXk@5DhwF zf^%s9?#2!|qC+%j!dafeS|2>3Lw2GgCOC)o{=tb49gc*vJcYGBc#J;Sx|$;3sj!vA#RJAd{Uw;IoV+uetE|JSd(Ae_anWcTNDJSB*K9K;`p8jhHF z#sB)A8}EG9{acMsc=25a{`av1;ViDt)v|^OM@(>ie$7fR%WLC~J}d5wyE5S{)`?Zg z8gCEcjvyW$gd-+cC!Q;7yfRky`(lMzT@%jYeeD}vw+I%0zN&HKq3>=1U! zNH~jK$ezm@>_T=Ugd--{k?gaqar@J5x%#fh{oDny&+1dyvV3L`KO6*W<%w=2KIipS z<4d1*%k_+at}MO^{W%^RMBUXs(uuGChM&}P#FJmwlbdiBU$_1~Vs)=;bsaJB6QA_s zdLN;`6FOvdO*o6Mbl+E@zY{uSmpEeLS)cf$+E<~!6FM9TXVGoCK0<#dbjWUZ#Kb4R z`c2YDDC$%iG~q0|X4kn1M@&5LM}9~;5B;6cA$MiMS#{QE5ffkicfViX ztI*#G9kNy?oW&`oe|JNFCv?agbi~B{pYeVA?#2!|)tB0Yvp9|Iy1}Wsfg>jV^S^q- zxic(F?DP{l$CFQTFzoG^wU!4?}QF(msG?A?;pKn zjnLl-9gc*v*wg*g7y3J)!`kf?F~L4YFIi(#)QLXmYdMRn5IgrlRNDwgOmKaEoi### zCv;d}hPsxsSPj|6F()(HL4aW05`R-eLJAEc|bwemza66hssg#PH9 z7X)-=@g3>U5&EM$x4YU$Iziv<&#|2VE(mAwJ?!seJ7qM&5fhvr`upG>=H*za1QGGigPGB90_O9pK4DpOX%-_4%zLFnBY9u^+69TMVW9GeYVuR zEG8T=!8x?+oO38TkyQ+u@>Yes$AJhpDWja6XxC-KZ6ZVuv^K{#UK*T3g|H{SM%?{0MbiQ>oq`NMbL zci#o!EZ!!&KWjWVh`$uXv!aG0CSG~ty*Ix23-8-%yyw@Sarh5+J@POT&SF=x`?JRH z`;BKDKJXQfJn$TjnE1xueb0^G`EU1cHQw;?Pdf0wk#H8*=W1EQgd--nKEGzAm*scj z86FyUMhz3rVx3r(tnr>8?vJPE$sIAlI`Ldt zOz^&WKUw2p?5Wr(BjGG|A$u-sd{_|dMs}hjCfJeev#jwmci!`)kN+DlyCC*ieF_WD zmmoeUh(8rIJkgEBKl`Uu;|+J-bMK6Rt}MO^{W<=?U%ThtkK68QAL+zD{NkU~bA&Z@w(Tq+E<~! z6FM9TXVGoCK0<#dbjV#fV&Z`hev|YOiaM1BO*o6L*>!Hh5ffkk0Y4<2hyG6Jkh?PB zEV_UHUWNWn=#VFO#Kdz?Z`AiH^mjssBjGGgG5xz6`a7XR?#dApAMvGk>$@BJJE6mo za2BVrT{k$PLp11!iK~DA`g3Q9zZLd3UUou!&Y`~(I;^{@hzaVUm#h)`JE6moa2BiHPZ^=VQ`6!0J}P2@bwe*%BlLGd zhxI;+a2C6#pO!*@Cv;f5q#`DG|L7%ag#J$Ga3q|?p6;i<(BBCi)^4we3HC91$r_uY zE(m9F73!S(AgXPIBPO^$zs?$=zY{v-u1q+K)##`2(BBCi^5l+~V4ZlbtP%RVMu#Ke zEZ$L{CPIJL=#aZ|#02k~_mee3f7j@6B%H{C(bk8W^cCpuz+eak+}8lk^?(cwt! zv-%X)`XF8HRDG}}x{*LHStImE=e!{3gO$a1q(4XK?@8#8yV^%OLEr7q!8x>^+=R3E z9`^Uq&Y|1tI%0zJLw_HfL(w7c!-TW=uJ?Tv`ny7h>=H*za1QGGigPGB90_O9pSnIc zhoVF7$`KQs=ej=Vfu$%D&Z5tjnwQ0dBPKY9cAaw$MTgv#31@L$sIStpa1KR>Jh>w# zIEVJ{73WZNI1q*AWw( zLwo<=9EuJ{!dafeS|2<_A8cLC5fhv+QCMm)^mjmqsMdtDxZB>(IftUdx~qzqpdNb3 z8bAM@S6}~w_uX=R^8>!&=q~f9uYSXgM||U3Zv58oJ>oWZhGltQ5dVB595L}zzx;hS z9{;$t(ecxb5C7nLecb=nYM5}AJHwuE#Kgb4?FVlxcl^j!?57{?svXZ z&+&I|`H?5plbdjsJHxWPEQnfNM@+o;ufALFBlLHL4teJ$oaN52ETO+EbO_;yiMRjM zecD&Ccdu$EnsAmoL)*J&!Vwc6aMv$MAEBtL(x3@vxid5ko(V@x{ITo*D4mD?uIgK2 z!ddPN?OSpt95M0ukNP!zuR?!U=#bSl;VgHC_!)FTphE~}{runm_48MBPyD@`zxV2% z2mI*0FABmD6Myr6{Kk#H{Vo6Zrl{NB{+g>dfB)V0e&t8)31_*NEX&tC{0&!M{>|Tb z?{7cw8;*{cc<;^czk$N?%MgmaLb*JL31_*N#7`;=0_8$DV&WBdy}xy}tO0>?N5WbA z9uZmRIU?}zq#=#c6o zfnKsk=#O4|K|og)UAsR==C3OKS$_~Gs6YpEKVQ&eT4ovmo&l=6P!5u z`{3k?4!J86&f?tF_Z25sbO_;y2~JLZU(sz))krvt(_q(!2}ewDX6*W)YoaP@m~a-S z+OBgGyNIsK$+hd8lPjvCh6!hJI`7{r&I?62VuF)v|6Xx&MTgWd;Vh<%{@vx|iVh(h zF~P~Te|I@sp~I1I7Qe?(U1C`{zoA12M@(>X?foP4ca085!dd>k#nuO}qYpO15fhwA zQCMm)^mmO8sbRud+%0O$ZwV(?bXa#)5fjww{hTL9ha=%EPkr$xqxb)v>%aRmf9>86 ze)@hMH1VO|@%kIz^;>V1(e){gLm!_f>Jq@U@)9N~5rR@^B2j@VtNS^ZxnS z^ZwRP{O4!Sd;WX;z1JW{&-;Q7W zQ=eCwdESo%j#~YF%slTQ_F3s{pEW{%Cv;ej(CBa^a0WwR`5ZIPdkAOYU)}XF^Sr+x zHdn-~fzL0hD);QV)}6}2OBl7~bC__%L^&B|jhW{?*K$_+iU0ep#?146ByeLxVOeA5 zc@N<%yq(cuK1X={UU=S*L^&B|jhW{?gtPFKMu%Br=6OF7<$ahnW}f#D`>gb-&l)(` zqeDB`k3@MNW(^4Zgh#?zJO?`5)!2F76ERV)h*<;YY;dESpic^_sCv@v?#L+rEC^FC|LJnv@&dO6p)LWjK%e*dTm%slTQoK-&cd8L`>{YaFPVb+*=-b3uO(%C+1a1KR>*#~>X zL^&B|jhW{?*K$_*)Mt&E=lun-dERFYdLXK@=RHLE9g;^e8$hzU-ZC@gEtJnyOD ztUR5+d3)zG&-;-mC&R2U^Sp;}R{7NP-dESo%^-x&Wc-ybO;P{Z= zcjw_xe?a%VCsJM+KlPtpyPMm>nBCC~ z!daf%;@@)yaZeCW2*ME)IHKSnlQlm0mA4-s@rySdN5Wa2!j|R1L40HoPmUUnn84Wu z2brw#lwW@AvHfo#oVB0ZOgLhK>+|cZ@$k5#4~jeEu1q+~bK9~&@bo;nBPLiUo-1p7 zZ>;QFV}<|tKsbxH+NX){3*t>d@CF?*!TaX@WQ`Av9l}mwmzZ$Yes25VAbuhUcA_ID z@MvLYW{vlM?dz`o>>V$@Aof{(3R{+c8^jBPcw*GxcY|u~8wng_vc`Y;+Sgrw&4hri zEYEGr@^6B8eh|-z8v95maMS6}5&Ao!L!R7(v-rC8_YwL#)#^H80#~5^K0<#dbjTYt z;VjQ>;rki{I%HotVgh%gzOO=mYwbi6&hiwtETO*@9kSaUF@Z}{*GDL7Ee)D*7UxB@ zlV3O!j+nr0s_Q)Tx1uWU%7n8#w=GLNbt70SM@-q?-a3q}NDQsCne=9mfgN~Re z@58JS`diWANH}Xh-G%;EbchBWF+n}_k~KnqD>|&_K!@xfXL)XGeQ-sGwYqiwFu}T^ zm#h)`ThU>?!6KaHxvllV6&=>TLRH+A3En??$r|iLbT|^uVo&!|U+8Z|hqc=)VuF2) zUb4ofsP!qay1tgPxC*hI1{>js39iqtvqtD|MThlesB1Zk)nL7{1_V#flRIL9b>g|Q zM(FQ^4$+_qXYr1B?^z@CcS47}K}SsRzIi`cBlO3YdS#cGa29)wU79sQex0+mu=-%leItQhvPS6d3LTCFeXz1Tx3xZag$~i+KGF&L zZhsEWq3Dq3FySoD68(K}4z1O7#01~N{ysQ|qC?)G31@k3Yklw#eX#8-M@;Zt@B4~# zXzfH3&Z0lno^E~chz{B9j+mf7b$zrRNG}`+XL)X0788z`pwD)la}GsS+?5Gud2VZc zun}m`5fhvj`uB=+C^|%gCYUec3F@Jj ztno27o_)OknJ+wi;Jw}Ro=7=jeCiutd-lBF6Aui6^{MlR37kamoPl1JAN{JQ9Y5qr zZ)r75IE%O0PfPzYh?|1=oi}yQd#anj5d{aCtZ~m{4#(er>w}KJI}pxdSN2oi4+Qa% zL3~U+ha)ENg26#1YkbA6k2>EARZQkC%TcqK_+Y5 zcHgV6X9RR*@m1*0@dZI}S3LPX(g_@J`g6pSpI9rN+=R3Ey7l)_1T`EnfumM`AECcf zy+ISs;w#G}x$t>}>5?uZGTmAXDcQEO?? zgtO?HUFRkoF@f7u*Lmn~MTgv#31`v$`}ZpJx1vLy+z}JFX7%q?=x;?;tgZ=Xaf+$0 zYx{~ef?eW>2^_oncQ^LbimKQpCY;4-Y}XAMK@CStl=orkBX;_V4$+_qXL$-+mQd4* z4$+_^Cd&ITYe1mGk#H8Zdw1rp&>>ImhzaVUm#nd^)v2DmuH`J&u%9xDsMW2A3Dyn0 zWR1|@iVo`y7U3-RLO(5q{#JBYyQCr}c>m}nYlQw*bXYsF2xqaU`>8MVx1z(^?G-V> zK1MHDV^h>hAM~}H#Z`!%`yi@qgd--nKEKWyp}!R!)|a8Ksry?d; zC!Q;7g#J$Gu)c6bIE#10dq4L0XYoC(HH?1~w-KzaBPRGB_V>X#wBDczXYpOHy|65tL(w6-#1RvG z*ZaQW9EuLvi6)#yf2utl^I#C@klpTx3Hnpl2R*P9Wx`qX*;4bem~g}deYWeIb0|9G zu1q+~Q&`MuK|~*HPwt2b&I|o}#W@rmvbrXm#kr@xl{rm7pg~7WaPH~f-PlviI45?A z31@igtMsK z`#E=o4ta7%Oi&NKWR02UJ&|(6c)*?eDJ;Ai!$A_S(Q=Ti^M{G@K7^io-c!R_yv=@E z!U+?v(Q?A9h>7w(%o;P#dulj~UD;24Gtc{xDDT6pvAKpezinU3SzMnOR|@~AbS7-m;FE zC?~_Lf!8*wLW3rp#VMw~u5-_O?#cv?T_`MT%slTQoW*Hu*9|T_??>XUPk7@E6qYsc z+D3;wxv%9cPhoSGJ4*R1n(b(WsRBVJ%qDRK|l4)Jnu(>eT-hR#-^y| zNAGJn%TrkEgBPCn)G)#I`SrF|6VH1HXL$;XpPdlI=y^X9r?9!_{ft0iS!3pT55Z}* zvOI;wztxYg0y^Z&u#a@2ybrU+%=4Za&hiwtEHlshktkQhtTFSvhj13(b#$1|H}kw7 ziE=W`8Z*y(2xrls&`#EvdESpiIT>aRdLTNa5BgfpqBnM(n{dPgeYWd-=6TOuIm=Vn z-1B}U%E>UFgL5dVs*`?w`<&$|Z0>na4HKMu`geEcc@N<%PhoS<`;lPYsm>5TDP-b# z58*6NVRO&>ktip_T&tPqJ%qFN(;as;dftzO=eD`$J=Mz*<6U30pWB+(@A3A{N!jz6 ziSj;#o_pR?!&$sd^pa0L^SmF4@;=NOGtYYnXL$;nd)|)(&MvsoWR02UJ%qD7x1D`P zkGKOnVxpW3v&PKxo*K^b6c#&i;(0$3IPI_!S!3pT58*7&ZFA52k-#yCH<~rBVuy^L z_Ylt7&utK+=lw{O_hHtUdEP_pv-;dN_q?AGILKs;nddzOeXz3lDxj+T?=#Q)k@$*m zwL&jhW9E4e;ViyxeYy+%ox#Q;Jyr+hO5ax%;s(bX`3-+)|h$TQ)8di zr?9!_{ft0iS!3pT4?!QSEYEFo&-;-mC&R2U^Sp;}mgly)=lw{OlVR4FdEP@f%X8b@ z^L`}C$uMioJntc#>8g=RJh8Jhz?CqC3y~k)Y3ZozFb)A)MtYZ0>nK z5}X%MSgzH~^B%%kp4;Z0_ani%r+;^6p7#*W^4vD}ydMe9Z`B!=W#)Mg;VjQ>bI<#c zC?~^QtC{CLgtPY3UG%{V&-;<^+!jxM+e42(@X|*f{^0-7J@2VrUKzjpDf_uCe(qop zuMOf42f>P>q>;c$1P2-DWx4q;Kj`>h|J&DH5YFQLqnCX04-ex0Aa0Esj+np^1<#qR z@mrt!{=-}U^Y%?d`;^ z5f{WhtIuuA@{AxpF^E4DH9XOc1P(G;;|rhj)aw}mU0Hk;`gHf@LDXICBb~rar$0yN z?^I82!dZOX`g9liJJsqsVggs7{ysu~r+R}XoaMPK{w_`s=#X9FhzZ<{`o0SNozNjW z(S)<;HmEIi9{M|>Lw36(CU9x$`UpjxN`oexMb|_-S;K@QCUBeTIuHGw&>?qa!daf% zmL>FeLWexLBPMXo>ffu----@dT@%jo+}6ILD>_6`j+nsxtABT6hpgyuB%I~Bt#yMH z9il-;Oq7#h>LYggiVjD@S)SXLCDgQ{Lp11!iN|f8_gMo19gc*v_R}4Ag%0bks&AX1 z9(u_dp}!R!j)b#3x3xaFqQhFq?-a3q}NxoufOe=9nyT~g;L6TE-) zk~KnqCv;dlu?T0er~9cd^mjsswc9IVf_;o$vc{&U6MfLvau!!1w$orE95KQ5`E}L^ z{hiQZeHrRn&f?ivudEUJJE6n+`c%XO>%?x^v73pkXQ47H6W`3#|_x&>_3T5fgmZ`@Z5FiVoR{CY(iosy)3doI}weyWJ5J^rx;5dLTMP zgC?Bix$S%wZG#b0|7wbxksbHqeB z8Kwq9e@AqPYE3w6KizRx=&m$5=FFfx@0+*()4}5;nA%5Gwmb2)ZUFRko zF;Py2`Oasa_uQ4U=>GkCHS@e5iSjobV_UL&J;Ve&K%felap7$fc9io@4 zfy;Qg9Q#_%@)Q<-KQV}MQg*}yD~-ak#y<+@?9ua{yKG_anhNu@YHh=6Mg{EKgy}g4g!wc|Q`oZ{BFu*uK;!zU{u2v-VTi)(slrhza&B z`z&kBJny-yeO8~s=AQR60)=IbnddzO^I&E19qH5E%=3OE=+yl=wi7^ma$n0?d=L9{ zx1BN?;fM*&5B+`2Jny+HXL$;nd)|*kc^~Fl%{=cRoJD`?`j~m%k3=~cW(|5EI;0Q! zTF&wmc0P+X!Vwen*{<`M=RJ4jEKgx`&-;J0XL$+>4F<7#-mgTtL}iW6^B%%k?7}$}b)NSt zQJzm(qw~CnIA+bct@pg|2wbAFM(24CK_9Fvz6$d>I?wx+D3_?L(RtoOIE$~_obEc$ z`;{oqr>xO=-a|Nxuk@Vm!t3|S^L{1DB`Rxlp7#*WqT5V;be{JsQJzod_tALXLpY05 z<zd2Wk8LvB3pSE4+hvPS2558*6MG3b!r53k=V&-;}q zm#D1KdEP@fi__Sl8(ewbuSB^-WsT1B9>Q6k+j`IYl_<}rtkHSiLpaM**tT_^_bXBU zQCS18?bY+X?g|}}<+*M2!7I=El_<}rtby0|>Uj_0EYEH6XZk^)LmZ(UF~N>OVOgW| zyr+hvpz;f3vMIm>g~@Y}xfyr+fw-tg+1IFF8<=!gkU z9P@p2p7+#nmglx@3;kVr-me5Fr@5~>&wB`G(Vx%`zu&gb^L`~b0Zx6KPnP4!eJy9v zXQ$3hIAVfx>C}1WdCy%r%X8c4gIAvSE5V6;ey=*udkANFZtFeoSAxj`h2`GuJntc# z<+-i*yk7|>r0NXux1$@+dkANFZtFeoSE5{l^Eo=tdkAM8r@PMcekDBVZQEae+_&BT zKfn2@_wRVZbS$KLxfK4t@A{5IFNy#DZV*p=>QnE3CJ1*K6F64l@Cm(bFa8tXbpNy` zKmUqwmODcd?|&v7F@f_Yo}gLdxBlQ)-1852Wx`qRCEI4g5fkNRpEbB6o`o7FoaJ7! zZ9H`mhsfFUp6jwsJXh9ue5~vnV}+?YQZ}^@^f9V5{gtOdzw(V;_;Ja_0@{hmz(Ko%vbg-v}2|TJ%Sk?%|-k@Bb!`E__ zyHE7NAW$xA<%o&$rq3D>D0d~Cb?i~0*c+5vcZCjl4inTvVOb*-dxLUU!dbiz)W(&z zEfjl$av>Zs!Mj0WStAsCgK}5GS?nIvmNi1LHz>FERYgp&dr(-`V7H^(m2eg+Ky6v$ ztdBuBVuGEI!m`F$wO53*xIS0Q8YUbu!S(q$Yn;C&qlO7*u^Oyb);NE!2H}Va)`{oJ z8ll)5l*?L~a2D^Ix0^LWu{S7}H|U57-Z$?jYeeUKC_3jA;VgD1`!{Pu=cIoO!Vwef zTlQJj2>m^X4!J86$E^9Mk)w0c2gj59&nZ^|y=0BhAHDX9fUYdM_I!@e-y6{(cXfm^Z4yoaY3BIQDeQ=H*z&|W zLkLGqaN?W&BlLHV4p+ii{?o|O2k)Z~j;`j2iSnjT4Tk>i(IIPP!dcucYRhj4Cs%Y> zcU2J+)SLaBCr5`X;Vf1iwPlUJ^#0#)|DzxH)sOzm7ar$96Xj-~&+*0I^&R)m`{!?e z^mF2r;cGdIm9BG8{HZ}W*uV8Ryz2J$hhKkFeu>X|))O8sM~nv^c*4VYPU1Dn@00k6 zAb#$LUVr0=37kZ5kb#b~PdH~kFPuYveIcAx&h}XY;yFQlW89S^Cd&ITYdrX~zyI#n zf6r6yUcC^`!s!#Q(X8=M5Wg72%m3l)ZyYgE-iKM^m%?Y1e?E61oK?>DS;K@Q2jc8z zpEZ6p?&vvjXWW&E@;l6|^t{g+zZ}GE5MLipzHKvNqP!22er~Mn*Tf35x+a`ep7&Yf z!63da2;QJ0CV1bxpRDn=*dgpKc8LjR;gQRp%NlPF;%9jr^ZUqohz$6?=Lk5!Cf6AlPD*{tP%PQ=PN<4EXyTZap7&WJ^f!pyB{O0IXE5}V&k_3D(IFb# zwn;b(4_?%kH9~(oI%Kyyav;Jj4ZUQIP}E);G=XzkWtFpi)-d6S3EZa8OV$Ye?dXuZ zGU2T9yw4h;za1T-K}SrKlVR2f{q5+G)ivR)^1RO)p}!p+@&+9-QBHFpStInfqeFJ0BPQ@%LoZn)w6UW@cDspVR(jrN4G46YikcA<<$ZXlalaDIqBhz& z)VQy^s)z~dp_jQ<=&+u=2xpb&eb!)g(P6DFsv=^7bwe*%BlNeU!+L{7IIBGGvjzk@ zoV(;rqlO9IKYGa;p}!p+qCsEFS>;ooH9~(oI;`D}s)(3iAETG7aaPn$AM~}H#Z`!9 z4HJ$Wh_fqV)(HLW=&-&FbuI1!Dznn_K5K;jc66A1a7Ik9PCQrAp}!M4tS=nv#kHKp zJL0`(jnLl-9oAR0A|`m>yq~NQ`r}Kz*O$5oXR+7VzgZ*ncS48N4Ju-Seak+}8lgWr z&R!j-h+|fI-e--_-ymjJ%jzqEUM@9msIe0C!OEg*SM6;(_u6q+$H*l3j?Cxa9Liep zN;YA^TT`}oI_C+Z_vasE1m6gtvH85YsEPf9cCY# zgtIu?)t=rq&Y|d#-R{VNIJ+Wd4SFD|LW3sCA(5Eot_f$A=Y7`T9EuKkgN~Ts+%vzsu|w|AAsRH{tn$3i z8k|GXAv@6#6U;lae}p#f&>xm{nl+=UttG__82g9)u$%a1y~m z27256{xe^6w?FwG-G2T;IE%N*?#~)O7{reT@v%WTVgg4L9AvV_fAW`q-`$t~)RXRh z$3i%ZT{%yE5MLa`Z4i!_z}W={nXK`(|Kg+X_~*F`;ViDt)$%z^IAVh9^K;htlDMM} zk2~Y8OgM{mVpXyR#76|dlRIL9b>g|Q##>@#|6!~!t82npyl>ua*7(1IcykcEK}SsR zzIi`cs7#6WvPSAd@vdAzVp20=lyJD$M72Ac(rFV`LIIQO)NF{hiPuPj13l zeBI{z2>qSVA*<_%30#5Z`w0D=&>?TogtPcc&wUm8JE22%i6bU(8Jqhm^tYobcA^Pq z(QT$aLVtr`w>x42m!_$YP}E);G~q1Hi&N(&95I30)YN(CZ%0+!l?i8Ys+`}e(BB|< zaz{+ynl-;yp}!p+vbrXm#VKZfcSCoF!Z;h zLw2GgCU7xBFR72%>HE;(LO9D)*tUh5c65ja9Whbfhgkyx9j=74xZByCxvQbW^IcWM z1ohBM)(HLW=&+u=2xqZ|^OO<#+tFdIZbeM6Zs;Xzg#LDPSZ}ZhXR#ONX({x#qr=)I z6*0m4M=x0;^tYqK+KELti#a$lKn#01yp z=d2O>+tFct8R}Zj;@McQtO0=zd2&ZguueQz)(HKb&>^d9!dbi{-h0*v{hiPuZ_p7F zyl>u5)(HKb&>_3TgtORdb1Dk`ozP)*gNm47-?GoLM(B@@v(pECtz*`l!bTsYtL@bX zYoc2T^pZ6~e{{|(f<9PTp2D^*^hb9dcXfLZI-JwHNYr6t*LmKr1YR&W$YhPPYv{rA9>Q5%pE~^h;xjr3M@(>ie$E=5=RMbQ7VE@%WsT1B zekIDuFl+qAaB*Ed?;)JUTjjlH4Ty3~cf>@wB4&-V8|}gKo@+UaUC5rx8b#nU>WGPQ zMa&wV=RMatX3Z(A_q^{2+-R~!=Xsy^o8F0J@l}}5(RtplM7bhf*6Pah9>Q6C-RAqi z!4(~%K}SrKD`M8@JnyODEWXlnUv-}MD}f^s3dho z;5_;L7uUCCbS#Yv5|Vdfr1g%TrkIdA}0nikLMz&wB`Gc?yfa z>l}Brdfu-@xgs9c>fm`_cZI6R@)S0Fky)$Zr0j^VTds&%qw~C{hO<0{#kr*MykCiO zMa&wV=RJh8P{BO)b)NStQBH4&N+pFjON|cjf)`+fl<#`X`EKgzE22qabj+iJ{#H?}tQXf3;so|{S6jlU%&=C{t zNcLIQ=sfSKam<=iSnqk?5hyHcbe{JR%!8H1cVtd?o#*{Zl=tCft*$)pA)Lkca87rz zR)e4qI%0zJ0}9I;o##C@oaHI3_q<<;az)Gp4Y1JyoYd>r?BDmdmCQAcf3JIOq45P z*1&6<6}IO+HJs%sYwAzLv9&b6e+mPYo00ikLMz&wGet z)|}gV&-;$RjV5b!p7#*+!OHR!HoSiC@fziQ93zt`SH!H*dEQgQS)SX5*YD|@&#UW* ziE>5E8lC4oHJs(SZQDA}`;{nH#H`VI-a|OcQ&{}F`akvaCv^B=td%1s$`vtd;PZ

=0)OqBOw*62L%xt6m$xAmU)D^ae9Sp%pkyR zqFfQPM(24C;VjQ>qZ?d#-mgTtB4!O-tyj-`2xob2>pkyRqFfQPM(24C;Ve&K!-4q9 z^L{1D6)|gcp7(WEsERDlZN2CHN|Y;N*62L%A)Mv8ZS=t_&-;}qSH!H*dEP@f%Tw6s zgZt27XwVT8<%*a!&Kewk+a{dlx$UCCK{#TfybsT7)p*|X9M19-)_dNs1m6{&D{J7j zjSlU358*6NVZG=5N|Y;N)`&iMLWlH0U&~p?xvlfOr-li3B>OjObe{JR$E-QG^`7?~ zfx@yz=Xno7AFM1-VZG=5N|Y;N*62L%A)Mv8t@pfNiE>5E8lC4ogtI)ijXua}Y3ve5 zOq45P*62L%so^Y7VWSV;MjzbigN~ReSH!GwK8p@TnQ)fpw#!*`5RRBASH!H*dEWCJ z&hp&Wd)}`^xgur_&Y`R4J%qD7xAmU)D^ae9S)=p3hj5nXw%+r8CCU{sYjmFX5YF=4 z)_dNsM7bhnjn4BP!daf-MjyQLyk7~=ZQJ%&Kl)?tzUWO4-ahcUXWuzeUKv049mlzC z+rBG^KOe+<2H}a$M0p=V$A7`>Ge7k1xu5i!+xJ=sXL)Yhw(khy7w(%o<-4JLJ1#r?5**IO{mKL3~>f>_kUQ;L*Z9%Nk$y&ab%nwZHl7E8>_n zr?74Nlpx;oJD+{`9#O*+-AdpflQsU#JHO(-BcLnGQ`olst|02Jj*&@xX1H3-=Lr3s z&>>H5!daf%wk`B`LWiubBPPnpFrOpzcS47}K@-mM6t-=lzY{uSUpZo;oD8!@=j>;4p+ii$LWr{LWgx% zsESoIK|S=6H9~(oI$Q~7v4&_T-$&?gM~Ah#6*0lOp_i-?`rFZAy}=@!#a=)=StInf zqr=))6*0m4M=x0;^tYo!H0WzN%Tw6sgF8B`-HxiLZi0P`Ub4nngFAiD*K!tDA(qc! z!Vwc(pP#cv=&sBrau%z>GiHs@-w7So_o^Z$SSOwnmCj6TENUPu2+iozP)@sf%zHyK_!=5a^Jd=!gmSE&D8Mg#PF_SHv-E&TXR) z($)6rgEi5u1bWFDp+7q36+s`YEYEGD57M2-T^%EnpzqG-;2eq$d2$oZ;(J(YIQrl% zI%IVnF;Py2`5c@>(IIcpgtI(_jXrpb4%t_ZnBcoU_Z8<*bchB`ILlMm=!3T(aNg~X zn4mvReb56@6&f_*EYEG1v*;ikF+rc5I_DgU4$+_qXL)YhHqN2wkhOBeL^&De``{dk z4$+_qXL)YhHqN2wkT>XviSj6}!ZQvplzrJ~#+=q9Z0azs>#;JN*tFu7tBZ zw~an{7kzMaHAhU8lVLtb=6@()u%KH#{+dlpCpK$jh|ME+&2xoZ; zi~rVS5T_vix2WNWiE>5E8ZZ9De|P&u|LWVX2xqY?=c(^Yg81`6{EevLhzY!4aFEFw zKmME_x#gd~xe(6c`dls7%7h~(xIRB;jaSDVeP!GkcV)s^d?i?wtnn2=d`1wgl_Ms~ z6)|hPIac-$#tQ%4g>aUquxE#ZV`LKLWSGwp`a7XRp4^19I1Qk-T&vLEsaDq!6XkuFH9~)^6!Zo&~0 zxJ^x+hyG6Jkh?PBEV@5x%l8rbJE23K+z}JyikQz4`rFYV8Z_Z7PL-%FYsA~z(IJX* z#6-CwW{ub(J33qmXK@;v-5~V0qeFJ0BPPlfF>Az5-_hYpILlMmwuPE@bchBWF;T9F zSpxzcu7tC=+u5DDD|A?QRS^@^LoZn)^tYqKm2j4)ux(>?(P6DFs^U$VVBOG5*5D1I z!qSVVSRlnVuJ4q&y_Voe5E8nHv}(BVor%TrkFt02%JJJAsn<%*a! zVyEAs!dy zPhrFB_cpwKZy$)Ya>PWrB4&-w^PU>c@)S0_es9C;_tp;fE5ZBb{bY@^8|@Y0tm71R zcDx;gBPPlfF>7?5_uSPnYffRk=Y2=uMw2x<&wB{^U}e!oQC0rF^Sob)az)GcqT5V; zbe{JsQLczt^6!Zo&~0xJ^x+cb@m$m9yynsEywbuisO6ZVwGQVxn9T z^Eo=td#>dyPL=2|Yv8pVp4;P{J7S_-5wk|;dC#?+#i%o?5NJ%qD7h4r5ID^ae9S)=p3ue(B3WO)kfJ?~edToJRzUv50_ zA)LkTL2dlL_q<<;@;=NOo##D-vrxf2^>v>2E5SZSFInTPsNtUNYdMSS6U*l?;fM*Y z&(B$-^StL;&hix2d)}`^xgutb&hs9^S)Rgr&-;}qSH!Gw{!*Xpc@N>N;}q6;-me5Z zlKq=CI?sEEW7eF)de8fgKw(*<^SppkyRqFfPktvb(p2xoZ;>pkyRf^#Se%Nm{MJ%qD7 zg zu~tF+*y|picf>?_K4p!^ zVr9QKR+!Z_;Ve&K+xG8+_{ku6az{**OH|f)QtS|R%1SuvIJZ5KJrx8y(Ge5n`E;)F zsgFGLdtUacE8>_n=eBM8xF9|%h|h`|p6FHrx3;YD&QE#d(T;$wEKgzacX2-Tkw<^` z`L2$UNt8=e)(HLGqeGtDgtI(_ZCmK?zE;-}6Xg<>H9~*)=#cke!daf%wk`B`j}F-- zj+iKysH_qCJE22%q6ufwZKgg#eJgtI(_ZCmK?gbrCNM@*DURMv+ZOsep+k0}BPPlvDr4Xl^pd%*A^C@dUpu?4L z)^WNE{hiQZ-4&{0H<&2@sH_qCI}IJ4pS%cXd2Snh@PrO)b?f|LqCB6nM(FQ^4p+ii zp4&zrJfXwdC8&z$Fv0srFIgk>cS47?6N_*bdwQPwLVqW8$Xz*Nf_;o$vc_41SA?^; zK36+va1f4|;QIWWH9~(UbchB`IE!avy|PB=?}QHP>r)XEtP{_bH9~*)=&-(UML3JM zI;V-y-#t2HtsF7I_mTILH9~)UsjmoUvDfBw7y7$Lht&-#VuJ5H`|MmJb~-v-iDTBB z+eROxtDUM3)o?v1iPt`V)G*;JcZO~I zXCfRif%7JwpjqQpulUM){^2=HILn5 z(REoTo-3c@t+BG75-YqC&T?mnzsniK^Uj1LCh(i&{bY?V|K>*?ebO^tH)@!0*0D2u zWf1RoCLA&G!e^%Eeb)Fhzx*q2e7|q{Tcd`FW7g~pp}`=Ybtc?pR$@4Oj`#6~U;dQ` zI|910+!?m*6M}f)T;mv-1kR^8eCBh!@|z!dsGi(}v)mctza1S!t*#>`aB!XPBlLHJ z4teJ$oaN3CF0MhKLkLGq;6yw3RqVu@+KDEd<<2nn?oI7>M@-dom)ivQPcZO{X{oSBL2xsBW zj7Hc?N8Im^9d+d_XgC>O#J6Xi{xH6T##N;vD- zqe8JaD7Wqk9r7F|sE5MN&+&}c-Jsl+a2BhM+OpS%VsB6`gd-++Hz+J?gko<{?n*d| z-Gkb)Mkw|M3wm3Q`eQ*%| zbIO$%da2Gyue~CmD~ql@pCk15Ms&zs9V3(AJ2Iam^v9Xuif|UEkNG}Af1FDO;fM*o zrt^Jpaz%&Sl?i8Y?wb3GlPfxeaKr?iVD2lr4LV#2XK@;w`hck2?uZFG+SCVK6ID^e zgtIu+PMw=LM08y`^VE6V5vTA`!-TUqozL$T=Y=91F~JFAey=#WqC=j;gtM5<=XaNr zD>{U5!~`d$`Q7Dgg$`H3S^OD8b%|{o=eINAhzU-7>K}1NM2FNc;Vl2z;^>3-(FX_N zh>7y1Po0PU?xPRBks2nPMQzlU-x5x)=&!-F^q2qeaUL{LZua>c-|*pojJ};O*1% z{^S1kvoD_azv(YL`{H@e@00j}AhsaN^L{0862UgcIS^-8#H{hoxT6n_J9|~sFu`3wWmY=dXN`Xm#502UEAiyz zU{AyZ>%?;<{b8}PFN+msbxk;{eCo5t(}Vb&Ab5k0nBaZ$ezL|}Vu$?w*jw-V@gw0Z zyg6~=%o_h7i0==Ao#==OJX&yZ$r{fH=j>m5@>kt`@H9~(oIz)peoP|dLp12ffjGM&=KG)r zqAE0Kf-YA2D4+U#4ik=;po31Ga}Gs^XwZbS%BMbSa1KR>XwVT8oEPTzigPGBWOYqA zt9FTL`O`N_hG&d&Y|cK4VpM+ zrB8i62d7GOm>QfB6Xj%>H6ZA4R?mh1zoWQ5%pE~^h;xjr3M@(>ie$E=<7<%P-&$XPzI%o?5NJ%qD7 zg>75sdA}0neV8>m&wB`Gu?yLa{6794lkl%yJ?~edybrTR=Xnot%$ieJ?|I)5xY1;d z&htL+H@y?dqKnSw=sfRNqFfQPM(24C;ViyxbGqw1?^mL{53@$+c@N<%zS47Fb)NSt zQLcztqw~Cna2DNW>Z9|#Ux{)u%o_OoqC>oXeJy9v52wyeIAQ{~sj2hM^PanM7Tte- zuR72Bl_*!le2&iZ9>Q6iV$dPKA6~y#p7$$Ju83Kq^Sp;}7N@b<4LZ;Jl_*!ltbwcb z>Uj_0EKgy*=lx2QD`M8@Jntc#$AH?c;zY^?x^pZ8siW+{~zLvAN zJ~6H|`XH(ugd--nK0jv-oU>QYd#>dyPhr~zv3lOGM7bhnjn4BP!dafeMjyQLykCj( zKFk`O=RJh8j#F6YdA}0uNcL~m=sfQsj#+aG>pkx~0)=Ib&hs9Ed9boPh4r5ID^ae9 zS)=p3hj5msux;x+?^mL{53@$+c@N<%Phs2EdET!?xgutb&hs9^S@fr=kIwUcCFoC6 zAN0Udl&|G1Phpp{=+K}eCOC&qop+x1+?BIDh4r5ID^ae9xmKO$J%qD7h4r5ID^ae9 zS)=p3hj5msu-@~2CCU{sYjmFX5YF-x)_dNsM7bhnjn4BP!db`ZuJgQK2~T?QH+~;} z(cRlVt_lP^=u1q+~b6fm-EI~Xu2%g*#6XkuF zHNGHLmKA1oO*qSQ+qOaQ7I}k?m?$U1tihgQZ?Q{EIO{mKv8N!|iH?{kSH!Gw_tUSv z`Gw#2vQfjtF>B6k+xB~d`1v6Ianzub)!erdxY1;do1cE|eMdl7mglx@`=lW1u8xsO zl=tCftxomiCYL$t+F>8eWc63;8un1>)ZX11YM~AgbP!%;ylq+J^ z2>tEouy$e*&SFo`Q(x$BM~AiBD`KLY470{rgFAiD*K!tDA$HKvs8oz?ZVoW(ohy=M&w-Xd?%5fkNPm^DIw ze5rSKi3w-1*Vw;VK&hp$g`rsf~T}MomD`M8*99nPCgtI)i zjXua}Y3ve5OqBOw*5Dk94%vw&oJD`CJ-uz5L(w6--4PR<=g>>mIG-$sqD(l8K3i(u zHWQAR;2erxvIgf+bjV$qaF*w`(FgC)Ay4jz3C`E(C2MfPKvihagtI)ix<8dWYY(ujMSRPb_PgaKuD8 z8J^dw@x13+&hix2d)}`EPCKkb*62L%A)MtYtoOWM2^@oXqgkW#yoYcWyO7<;@1w?x zUUDbe{JR&hix2d)}`^c^_ttzwnX&)s7DTNPHQ5 zEoXTO>pkzOVWM0SvqtB6Uw4HL$?_D|d)}`ED~-akM(24C;Ve&Kz32T(uwzhI*62L% zA)MtYtoOWM33fhu$r@)x4fkwc%UPbnde3`mnBe;Sd|s=@^B%%kp2B+1`;{ms!>rMH z-a|OcQ&{hLzY^t&m^C`jdkAM8r?AfRekIELFl%(4_YlXdIfeC}_Z@*=vPS2555YWG zS)Rgr&-;}qC&R4KdEP@f%TrkIdA|~T4^ddw=sfQsoaHI3_q<<;ax%;so##D-v*=G~ zhu`;}_bX9OhFRl$vK$)pwVXwtoztBOM@*EHVb>&FAPm?;)JU*KJOBo#*{Zl#^jT zN9TDD;Viz=b6<6y_bY+B(cD*^=RJh8Jcae1_bY)*)6~b=J$oq1*K!u8O4P=cde3_z zCUBdYI`2I1A)Mv8ZFv1&dET!?IT_~r=sfQsoaMP~c>P{^-mgS?A7+it^B%%kp4)oQ z`;{o~!>oa;_3C*K;Ve&Kz32T(l=orQ=sfQsoOPV;xU1FkekHg=6qYqQ&-=Qo%JSSc z`rwu4{YsQ8V%F$9?;)J!xoz7z&-;~N$DpvR(RtoOILlL5?|Hux?0oc+HO?9w?%BSU zvplz5G&l%HOmKaE&KjNPJ$L0S&u!b*dET!C>%>ZAjn4BP!daf%MjyQLykCj(KFk_; zZLgm95Y9TzZ4j&H{YtPS*}qw%^Sp;RX3e>+_q^{26qYqQ&wB{^U}br3>pkyRf=)f3 zqw~CnaF*w`-t&GX%E>UFqw~Cna2Dq)beMM=eelZjekIELFl%(4_YltV6xMs*uLS*R z>f?MC9g6a`oaMRgauywgBPQsxQ|F!MJ$L0S&uzWu{Yr3NnBS|;^B%%kp4)oQ`;{o~ z!+al|=RJh8Jh%0p_bb8qtvW-x%dejI5YF-x)_dNsL^&Deb9A2f5Y9SIcb(_`N^plL zENlGskACmFFMY|=ZXf)D>3L72yfPm5wBy{iZ66-Q=LK;WgeN)^<$VafZU58Do^bc= zKlUZJw+rDc-amTDyLwF!|3eTD2jPf`@;=NO|L2GOyW0=>$#1_RoW(w#r@qI6xC!DD zqJ|?T@PfgOCTsllXa2}7|Ez?wxIS0Q=P==jiSj@vy?I~BpF>B6k+xA&O{JkJp-w7S^=H*zl=orQ2>qSV;Yv7*ZZq`}`a7XRcDo}caA`s>StAs6Dh--&7F~1d+=L@0 zaGRPs5B;6cA$MiMS)SYC-)RT}9rEOkm?-bVe2&oHjt*DCS)SX*S9C{*XwVT8<$ahn zVu$SL5Dl7emglzk?`#Kw4%vy0m?-bVtPwkXM~5rnEYEFmZVv(-qCrPYlq+J^fIx>U z;VkZUc4zJi9oAh{#6-CwW{uF_jt*DCS)SWQAKcMltuCrUIVM;)^pZ6~e>*y?H&}$T zJh#RF&lv2oY9fTt$xIRB;jnLm|=rDGP31_hybGi%tozNjq?udzUMa&wZzY{uK31{(+c<=cf zp+CN&J8#et6TENUPu2+i@ul9`B_^E3?wnIm=5ex~pSk66K1RH8_W&L!R7(vplzrKFBF! ztga&_$`vtda1O0EXu?^Z+qR8!C^}@9IAVfx5PHcPoI}y!N;r%DH1)wb6dl&7uOcSs zPg5WCz*3a2IAVf6J9QrVyG4iGl?i8gZX12@79H~Bj+iJ{#9S-Rq3CcW zoaMPKrwMe31|2a`u83KKlM*^agC?Bixoz~pJ9NlSbi_n?A7+i%>38UGC7k8CZS=vr z=!2uHIbxz*5wk|F)C-}j#PD}jR=3d^(A4x2}ewDeSXdw zo##C@oaHI3_q<<;az)GM?uZF?B>OjO zbe{LrIA+Z$toOX{2=tOQI?sCu`e0>w3hO=ZSE8H@v&Q)ZFrM7ka+asC-t(RsCd$b$ zYjmFX5YF-x)_dNsL^&B|jn4BP!ddjEsgLM`x9ISL;+yD*3HsC22R#r~(FaX9%Tw6p zEIJ5BOwebi&O6V0p2Jz5!g|m9l_)2}T&vFW9>Q6k!g|m9l_>AStkHSiLpaM**kvj@ zc;2r>IT>b+&hs9^S)Rg1AH0n|IJ%l6Cd$b$YeXNsMThi36V5tLcb(@wcV)tp-nRXL zuX@Gp6W{Ran@|7v>3L7}a+!L=yB+7YZTqw!esd6?7KA4{6Xg;G9eyJHl zML5fI+qS(&5MLI=XG9H0Oq5Gh)_CW?ec|mtf6dcwSHfBB<9X_Pub+S6?YsStPrKzg z95GQYQCZ`Ap8n7+|Ez?wxIS0QH)z5U6Xp4oHGVyw;l1O|sA0lcd?i?wtntnu-VsmF zlRILfJfE`0*Tu>{K2~@ooaMPKG#JD)gW#?lF;Om2S>t`#Q?XN4!db_;?a4u~8`+7D zm?+Putnp*7c;um{f9PH^^;PYJ_Ba^6! z9@!Vd5fkP4lr=(sCv?bNnQ)fpwrvajozNjq?ud!<_0UV!2>qSV;Yv8mbKB^Hr=i31`#^`(Fj1aQ zStIm!LWlJ}ig1?aw$TSq=&*JPI;4gP-amTD8lk@vI$Q~7v8U&$FZ6dphqc=)VuF2) zUb4nnQCEbsxC(Xhdu75A6I`F4vqtFegbukY6VCG7wr!!m6FTI{9WlW=@myIW^mmUA zSHfAmBi?&HN9gY!9dcKWnBe=!`^g%izk77J63$|G&gm}nM>jaJ6CE+ZzGa_fjnLnt z=x`;DS#xe1eUPqpsy{gbvxej+kKHnf-%v zC^}pTXL$-6eegE=;OJ_Om?+oae2&oHEjmQCCY*Jg?l^~{!@4U}#h1*4=eFMSp6caN z_^x+7>tT0>-t&GXaID1P6MDE#;XDz_*%|# zXXriesbQkr?6bz%%XHK@T<&?be{LrFj3z0xw@U_J%qE|OM1`ymB6DKO=b#|dET!Cdkjrxjn4BP!da*QwPlU7K5o#UBPQ7SC@gE7ReMD^ zi|cc>tYN|t6I`F4vj$(EasfBtEY^wj${OeI)wnB1Ot4NoSJvn}@41$hp8WevQxSI_&r z-*m7iixa?nj?VLbCHRia=jc4|A)LkOW4@2h^L{1xn$GvpdEP@fixb)0SDokmO3(@B zzM^-mp7#*W;xst*0a3f%5fkNRpYMaNiKOAh~;$UyW zS)9)2_p0-}=gCcQ!kFKy&hs9^SI^|Np7#*W@}DjCp7$$J-t_s-Lw{GE_YltVpDl)iOXGRJ66H;wHQulBysx{euJ1ov z+_uj1ekIDyK5KNI_YltF-PAcK{?s7c9p4(xp|?LQ&--V+^x}E{zymLxp7-(lBz_`@ zpZg(s-Y*2MB)HK)hr3F+R6Z}9Lw|iCoRxl;KlQwi8#N%F6T~;hT{&W+ToJRzgW){;w>Vu<&XOw?FcOjg`^{JE3VZxCE zadt(_8owHM^qjae?#cvr0hL*2&-?KlzZ}GE5MLipesQpmh>3DVO!~R8vR@M`%<7tO z7Jjh!gXVKQ7{u2F!5ehMM7bhnjkm=PVQ;ZZOgIZ~PMkQi#@mDVnIPDSj+iJ{#H{gP z_>+Ebl*6Qv|Jbyg-jI0E1G?yCp)L04T+RDN!bv{Sb7zB59j7*|j z5wk|<@5Ea1B5&GNFA#czT6XlAS zHDXWg=#X7v!dZA!50BjO9HGA*9kLT0F;T9FStGQuqeFJPiDTB;*?!c3K!>TQ88K0= zh=&^YE8#3^56@!PxUajah>3DVoNI*+>&c677Hf!h@_n$n=&)9|A|}ceF>8eWc63;8 zun1@6UI=IV@f;B7aPE?fm?&4otP%R#(IFc2wVcJCMmt#}^tYqK+U*rF!9GSWS>vpz zoj&MmIg6_h%NiyeIS^-8#H&5*#i+99(&*upJozP)@MJr;WToJQI=#MY;USH}WoW)*a|7MNQ-w7R7H>ik- zaz)G>d+oTZV`LKL zikLMxhq6{Yxd~_SJ*+j{HqN27x{jFO{D5Av2Io*z#Tztn%sTtjkG0|)3X!{HMog3| zV%FdsiVm|6PQqFAr`pro#yJ!nvfCXw5NB7!tU(V%RcO!zU99wR@u?rrVZsp;oG_=( zIftS{?#hI-E9il-K$E>rn{df)tbeI~P5fkN#c&Ksi zoRe@CwP!y+*BIT|5fkN#m^C`jdm`nC@vnaIB^S^8Bs$Ogl_>8+=-%@l!dafehS%>M zUZWoy&eo2YDDT6p(Rtoe!&&UgdFtyt?^gn67aU}=#@T0d_-*@I&f@ySxYEUEbP$f1 z;QIWWH9F6GuH`IGVZ-b9%JY6D%E>Tmbe{JR&hix2d)}`^IT>b+&hs9^S;r}?^Sob) zax%;so##EoF>6j?z2|*L;2@JVI?sCu`e0>w3L9R(_jrwddhFd}WD+=0p|GscdEQgQ zS)Rh;@5#L9D^BR}v>2E5SZSFInTPsNtUNYdMSS6XQy~ z=RFYrMH-a|Nx{xtQ`dET!C{b}lh9*7R< zgT9ut=(AJjCLA$ApPf4IJny+HXL$QZripZ9v_6~GZW>C2)%9J_t`JFd*VZH9yLrj z%X3@2k072D#IL_`dfszaCdw5tYdrE%w|5`#%qQIa$Axef`*@!EzBh>X3*xuLb2wrG zFBlwTvc_jV^F#0W=K~kQSzMp1D{O6Co_U5<#7caZ}4GVG1np4=eJwJ#K4B~x*@I$H*kg74foGC)SE5H{mS4ZfNJSR)e61BPPlfF>8eWPW1*&ILmWe{4Kp8 z&>_3T5fkN#m^DIwJ33@1ns64~X6hsKx1&RLyCWvb$uMh#qW03D31`tYr_N0{Vxqhc zvqtD|M~B>%31@k3+qTf(jt+TpM@*C}V%7-#?Wl^?HQ_8zVdE=02zH4hCdw5tYs8+~ zQ5CzygtI)ijc@xPsNsl-az)GtEou-;%1&hp$g`rwWZ zYnPxZz5pi56)|gs{&sX&JFy67v8U&$FZ8#g!`kf?F~L4YFInTPsGUCOYdMRn5WDn2 zR67VqOmKaE&KjY=9Uaz}p|0gDo{ja&8lk@(9oE;UA}08*@LX9V^mjss^@S_KS-d0O zd)9#9E%F8(F;T9FStInvmwK-+bzRF@>@{|2)+mA+j+iJ{#H5E8k|Gx4VrM4=eE%YZ=(;6UE+v|az)G>YQ^ZI^?cQILmX}=!19YkSBM%o=Cc(1Yha zgtNFlb+U#DM@*FW;d!kZ&wH-rEKgy*=lx2QD`M8@Jntc#5E8lC4oHJnAanfmBF?^mLn z46{ZkYDZPSGw#aQau!{4>fD4QCdw5tYjmFX+?BI9RiZ>l#!g|m9l_*!ltkHSiLpaM*Snqki66K1RH9F6G2xp;!dFp%cT_3p* z9fqPDF;Py2S>vpzgXcXpoW=FI8o%#7?^mL{56^4Wc-})e%TrkIdA}0nikLMz&wB`G zc?#=2?^mK+5wk|;c@N>N;}q6;-mgTtB4&-w^B&@uHK(xN^S&ccSk~w~?;+@emE|d{ z_q<<;az)GP z;e(+;M@*EHVb-7rqC@(i31@i<8ydV2j+iL#!>rMH-t!#J@)Xv4-mgTtB4&-w^B%%k zp2B+1`;{nH#H`VI-a|OcQ&{hLzY^t&m^C`jdkANF3hO=ZSE5`IvqtB658pkyR0%sQ-WU@x*c@N<%&utf<(Yp_d=WxUX*XQS~(Rtoe!&#o&hS%@yGrsYG zJJ!k(6XkuFH9F6GYBr?BDmd-|@A{+PS>jCbyc2^_W1 zOFl>Ec~1>zd2ZXb&hvgH%KI>Dbe{JR&hix2d)}`EE=^M(o##D-vplz5{I-V%9WjBY z)YN(Bc~1>zd2Z`H?^mL{4|AQ6k+j`IYl_)2}tkHSiLpaM**yw{- zp7$$J-iKME^Sp;}mZz}Z^L{1hPg5VA=RJh8JhxrWq6g3Wm7vc~op+x15YF=4)_dNs zM0p?PT6LcH5YF=4)_dNs1m_+UmNh!hdkANFZtFeoSAz3fb%x&a9>Q6k+j`IYl_)2} ze2&iZ9>Q72>8|ssrp@ck}dW!Vwc(pP#cv z=XuXvIm>ff?|Hux<%*a!I?sCuXL)YxJ?~edToJQI=Xnp|tmE9)dET!?xgutb&hsAP zm^J6N-t)dAaFEFwo##CSeXz3lD$MDw^Sob)@;=NOo##D-vpl!;p7$$Ju83Kq^Sp;} zmglzN^?T)czY^t&m^C`jdkAOIZKggt&-;}qC&R3P&o8P%gT9ut=$fU?;q`kV95GSe zhgoBIZ7-hp+?BIDxAmU)D^ae9S)=p3hj5nXw%+r8CCU{sYjmFX5YF=4)_dNsM0p=( z4P32P&wB`Gd2Z`H?^mL{53@$+c@N>N<8;Set)BNQQLcztqw~D4yF!O#d2Z`H?^mK+ z5wk|;c@N<%&uzWu{YsQ8V%F$9?;)Ip3g)Q~ukF?IekIuX=p}2MH8{MmeJy8kePUec zqQOBpVuI`QbJplQ@41$ig3gP*XQS~@zZffKNfdJ4HM4t+_r6xkEi~%AXqC$OqBOw z)_5#d_P=L^7s6Sd+qUhkL3~*dyg^4y@VrPGMh}aMp2dgJ3s8IAQ{i7WP@z z`1Y4R_2y@u|KnH0F>B6k+x9I%{8AAAI%;^LTL~Owvc~tm^r`n90bN<1+qUh`1o4jZ zT^%EnC?~_qTHV)^n{bxrwrvaj-Ph_mVge7Y`94B_Cv?agG~q1IZQB<5I}IHM;fRUy zKFsF`{hiPu`^to~=r*V=zi^?y6FOwKJ7NNtrm2rm)TuOR!daXu(N5Md;fRTHGR)@) z{hiPucV)s^p4;M22ZKO|Jh>w#%KI>Dg#J$Ga3!4Oxh?+N2|=Jk-k>8U%KI>D#11*t zx7~!ZJhzQ*a3LHqQQn7HBlLGdhp5(svplzLTd3)T4$+_^Cd&ITYe1mGm2lQ^x(ofC z&|%#bs$w^opdNb38lgX){EBdv=eE%YPw0>uj+kKG&`Z_`{hiQZy+L%yT{+8h+vtNQ zbXdCtRjow1B4&-y-w7SAgtOSw^VApmJE6nc?G-V>K1MHD&sBrau%z>dS#8!-w7S^=AYJWLeXu6F zl|V09BlJh-ydvm>mF2l@^uZf+$Xy*Hlc4X;=ipmaPj13lp4&zr5=TswlVPqE=TLOWzB1t~`cv)cIA2A#L5J*iM@(>@oBE&! zqQjMNmglz1S#%JNn4r&2opTOFhtx3PEYEGD58k3fp4<@=<$aiI#W@rmu7tBZw~an{ ziw=2%j+o%wGrzl>lqF?wmV{ib0~Vr=inTQ4%zJ{oaMP~^ugQcgQKfC zVxpW3vqtFe79FBm6VCDs7yo{35YY#3>aI`~Ul|kBLoZq5B`YJB5XL{Zf zDVM27UKxKLaG35sCy1v6@yCL2#6V+TlHH$A{tH3;)gX8dM@*DURMzicf>@wL}iV~Vr9QKR+!Z_ z;Ve&K+xG8+_{ku6az{**e^l0ZQtS|R%1StkUC3_CwR$3ZDhPI>BPPl}>RjVfA9?8a zyzEt1#4&45VcYg`L3~sYpA|Jc(X9kNZdv1%<9dcKWm?+PutPzSjl?F{Xi>^6!Zo&~0<@uB~LVqW8 zhz3nK%Tw64h5k4|b(BBCivJ)LKQT|a`BlLHAQmASroaHGj{_HgfbchBWF;V_eSpxzcu7tC= z+u5B%e;@COfAo?yLVqW8SUa%@XR)W}sW0?*LWkUyBPQ6#=p}2M6?H{8i|cc> z+`A?mF~RluIctRePUsK~ns64+#(HIq(BBCi*4L*ZCRit)D{F-Q?$Kd=;fin;Z*@)+ zp}%`{$XYpKg6|{mCu@ZM_)=dH&SJ04sVMY!j}EIFRKx_|dG^`4M(lKSxDv;#Ifacr zNLM>mAFPRPCD2RO2>sDHuL$~JW$_)UyN$n-8X8B3+|@BM3Ht7Qj&Tk>Ke-8Kc?#P$ z&Y`usj+o&5Fy9B~P;|%}G~p~yVWSV;L?0Zx#1RvmgXX^C9EuLvi6)#yf13K>9EuLP zD@ROlo}2oh2coK#a29=b>fD4QCODT)opTOFhiK4*vpj{3K6r}`d2&ZgaK4`3E6$i@Z8pW-c$YJQuwD| z@~}HY?|Huxcw7z->7a+}^p)p5gtOckw$}50C2-!v6ZBo9#@Pe(9@kJ`%USLWz2`kO zOkBL_M~$8NqIR(ak>mODf5c~1>rmvv$#@;N%sdkAN_GxVPKD}mo6Z!~Lkp7#*W zI(CN6^L`~>_{_8C{aCBc^B&@uH9JG^dEXJk&3@GAJntdsQI+M+(0ksm1kR_!^M2Im zJntc#<<8K1-me4>uJe6#p7#*Wa%bp0?^gmR+PSaJ9@1m)`dZF%XXriesbK;~UG#F% z;Fae+gtOckde8fnz&U&B{OsvHp2OF2mOI1v`doS5Q^N!f$MbvDdEP@f%bnr>$MZh+ z5AMvv>oxxOk?1_{sbS*cWP{^-a|Ocy`=ZNUx|yG z{iuQ0_Ud^L;jCki>OAjPf;$|Z#rYhK=Y8E(W$`{xF2CFpmocdPJ zdkAN78l3uosNL>}2|C);$NBU+_O1zMajKmn`<1wO-sf{Pp7(WE=#a0P|7@}MykCinoBgQKdEP@f zi+5A!ply3gxI2D-IETLA?bGxAHE)0Q#q<7&Kk({{=RLnq;s=7*g1|u%=g^hFl>`SF z==j^};ZphG;T-xt3*oGCw$B<69~{JA3&If-<$ahnep|S0{_AiK{nmwW7QUVMgJz8n z3E~|=e9ccx&wC;!@PffXCTlzvKBN5eiiL0%*QZX_FyY97IJ+Wdjd#W!eQ?~_tD=Sp z?gA>a((^uR{EHx-5yW4KCoczkA|}ceG3gJBm3>*PFsp0AS-e%=Zq|5u5T6qSZ_p7F zyl>u5)_6$>s>#7B%FmeCr+GM;~xa^{Xwu39Wha^h*{$q;hgqxd}&1;5IdN9{StSAsRH{tn#VP zwF>?1=nxG$Vxqhc^EpC)J33@_O*jj0=lZ&CTj*~`hrB^YOq45P)(HLW=nxH>a26ib zs4br(^tYo!cA_ID%KI>Dg#LDP$Zj`r%t~kbtPyJ3(P3(EMog3|V%C6&8uu&VENY{j zLyh~otBRN?SH!Fl`rFZAJ$Vt%Vhzzw)__2VXwVT8<%*a!LVr6ttT$NKa#rqzH=S!h zpu@RKGGd}!5wk|pJ5Cdw5tYlQwz=nxJ1TFzpxv468h=v&yGFYj6%lhrB^YOmGfGFIj_gC^|%gCY;6jt-kr&#yJ!nvJ)LK zQBH?MgU{+OwaZYmDyfh>3DV%o?5N zJ&|(6`1k+&t1q7SNpzm~D}j>;4l>Za=RJh8Jcae1_bXAZh*=|?d++cX#dX@(au&OC zp86p08odp|5feDO;2@JV&aR=uZ`*{kxIVF5D-({G;QIWWH9F6GuH`IGVZG=5N|cjf z*62L%A)MtYtoOWM3EnqvG;4I8_YlrHPGOzr{Yv28!p_VZo##EoF>6j?z2|*L;2@JV zI?sCu`e0>w3hO=ZR{|%h`5c|+J%qFPy3J|3^SoaPJhOAiuoJF^p`sh6GR|1!&sSkX9QI$RKA)G}&oH{q*hzZ=Lrp`Ohdulk#Q&{hLzY;j8 zp|D)5&hs9^S)5|fA;0fE?^mLn46{b(c@N<%Phq|1{YsRRVbrMH-a{O-<`mX@ z-gg8F%Nm{MJp_HQvOIn^B%%k^e5ED@8j<+#W@rmqCrPY(4VG0=z-|ap7&hKS@hYda}$o3pwCX7cb@mu zaF(aA-t&GX%E>U-s`I>uaF(aA-t&GXIQPu&Zs&Oq;Ve&Kz32T(aDJ=K(0krPILlL5 z?|Hux;`7s6Sd!nW-X1@VPJoPuz~M7bhn zjVFEV?cEzc@(Fj}w-C-^AJ0?Ydj;`#g7{}aIAQ`X7#w7>#*2UZhu-nePc4MAxIS0Q z)ivRW39ir2S>x}<9lb}~8FyvES$ri}m8|iGAf6lqPwt3`az)GMb)4JSQxNP#M@*C}V%E6(>DS);!tZ<8sA1xmHRrZ% z`@KQ@d=URQYIves3EXJ1#?4Q^_P!&aD~qqfobEm;h`Os|WD@0ycv-7cJ-G>I@pYTi zU98n0SY1aqSv4VrM4=eBJN{hex;IAWr_53@$-Z%2phL=(=U+f03g{&sZ8 zZg<2)IT>b+P}E);G~q0|=G3_fM@-;0HFX~P+tDF+Wx`pW+qNzAx1&Rz+z}JyikQz4 zE4!mAG-$$Ep4-M(bP#CJ5fkN#m^ETg?dXtQV!~OT+s3zjM~7(85fkN#m^EUj@92;k zCY!7- z+|@BMiE>4}tQ9AK@#H3)#aUv$kMo&f)NsTE=LhtXH8_XX8#Li8Phq1Ea#|X@#1Rwa zikLMxhoVDvq6ufwpK4EU8|P4T$ZmJU1pR61gC1ClGT|)xY^gc^J1im`F~K=>>YQ^Z zI^?cQILmX}=!19B2gj2;Vxn9TbFDaGpei(I!daf%a+-iZgN~ReSH!Hr*$N$^K@-mM z+;*99MmKQ8M7bhnjo9gT=#UyFoaMP~^ufF6gQKfCVxn9TvqtFe4jrOe6V9SG+R1MT zcZCk?t}0@JdgvuUmG3yfPm5Kfn56Phq|1{YsRZJ#_DR58*6NVZ-b9?vuat z^|$zKJ7S`|53@$+c~1>zu`B1PFFZ!?hSzA+aKuEpB4&-V&*;JPo*K^L`dp3QUwlRf z;fRUyK0L2g<9W}uoaHI3_q<<;@;=NOo##D-vpj|Mp7$$Ju83Kq^Sp;}7Q2w$$nT@Z zi(YukZv2DsJ{&Pou83Kq^StL;$E-Pp^`7?~fg4TM=sfT9e$zXVEKgy>>-Qe7QJ&)% znMAoFW{uACo*K^b6xMs*uS9ttW{uAC9>Q6k!g|m9l_*!ltkHSiLpY0WGxgDV-mgTt zB4&-V-}X?HujMSd=G3_fM@*FWVbr?Aln_vnKs`k*5w$`vtdbe{Lra26_9O^HT<@HEoX6kVqB^ByeDF!ybsT7)p*`RILlL5?|Hux<%*a!I?sCuXL$pkyRqFfQPM(24C;Ve&Kz32T(lq+J^=sfQsoJD_{`sh6GSE5`I zv&Q)>IyC5OIg36!b#B5D6XlASH9F6G?#fx7!g|m9l_*!ltkHSiLpaM*Snqki66K1R zH9F6G2xoZ;>pkyRqFfQPM(24C;Ve&Kz32T(lq+J^=sfQsoOPV;I?wx+@TAv!-c!B2 zGJf$d9Ot&)^L{08CBcmby7#rMH-a|Ocb6f9uzY^t&m^C`jdkANF3hO=ZSE5`IvqtB658$r_#KJp_HQvOKr-p7$&9nP*qTtkHSiLpaNG z+wl6m^1NS(az)GSuLN#WC@gDqp7#*W^4!*Y-mgTtB4&-w^B%%kp4)oQ`;{nH#H`VI-a|Ocb6f9u zzY^t&m^C`jdkANFZtFeoSE5`IvqtB658Q6k+j`IYl_*!ltkHSiLpbX=w{@QPE5VLr|7MNO z^B&@uHRrb8^S&ccSk~w~?;+@emF2mu_q<<;az)G5tyoYd>=eFMSekIELFl%(4_YltV+_r6<=lx3H?1JY^);Rl& z4!><*%UPb=EKK_sIT_}2be{LraF*w`-t&GX%E>Tmbe{JR&hp&Wd)}`^IT>b+&hs9^S)SXrt@FHJ z2|UrJKF)sILs7n#vplz5{I&<-hzZ=Lrp`Ohd+y3vp4)oQ`;{o~!(6M*^B%%kp4)oQ z`<1|R4TWWm&hs9^S)SW^&-;}qC&R3PyZq{T58*7&ZN2CHN|g6u*62L%A)Ixb?zpSZ ze)#$KXwVT8<%*a!I?wyMD|ASf=eFMSekE9G6qYqQ&wB`Gd2Z`H?^mK+5wk|;c@N<% z&uya*UU}ZH1UnzSWR1@A9>Q6k+b$YBeL}nsM@(>ie$E=5=RGx?<+-i*ykCj(KFk`O z=RJh8Jh%0p_bX9OhFPQYyoYes|3}yR2m8BSb$w5eADW65NKL4s83y|!Dzs9ELhd;y zkwR%C(~>xbiy_3KiMF-|2Pq;yf(10%b_CmLFDhf&@n=yJEN!mb^Ev9I zLy0w7Dq3h%jN12m?ayBO^{mg@f83dzyVvVk&wif0p1s$}_kLgJzO8fKS7N#kM~=>U zZ{i%a`nKMA-w{zSb055O9p32;vIq44o>A<=dgr}!keDXJF^|r9Z-PG?-VjsNMc{J*SBP6^(t@`Mk_s+p6_HB6z((NnC`>ztUBkt2}ZGR>z((Nm?p!KqjTPyU=+Ks-g#dMpF`)) zpuc5PCqCEV?4w-MCK$!Ot#{s6Vww!cJUZvS2}ZGp8+WCB@NV9fE3^{q+m7SM-}wXg zACdRvlYe+Q@11?RGT!>l=e|vUE8 zZ`1#yDB=%^_#_b=Au-*DBgdEjg?Hco(1*YJhG3M}@jCT=zKHJ-@hQr|5fV1L*f}$D zeCk&{ckh3Gejym;>-%cs4U*sp318noj~stocl0XVneU1Oqu93{$M=bNtB99~;0TFn zG8{SnfS&Ak=?VMkl3*13w&VC#5#KJtZ;&G-{J#BuMh>qKuartK>fE<^6?!$A;0Osj zTD;Cij@P{IrFVb$Gv9whoTFA3b{wB0;yoh#tk}_2!Uma<;|;HS>0?Kjo>BfPtSCcggm`|4@B<$c???d%>aUJ^Ul3*13w&PI!U0jD= zB^)6!O@`xHss1jm!%8s9yUnT()!)T+=+({<61Ft0`cOq(W(|^Hly}Wl=Oj2n!nUbZ z=c>Pp>(F;af>G?-jzjf#aUFVHafE~oYOa^@tW)<3sYx)3eOv4Xm$@5ogoG_-u9q#!1x@|s?!KGomFbvRf193kO#?0OkF zt`&9hKFDh^%2)AN?t`w{AUHz8*Z0pOhwAU*I-FmIc`ZhoXYc!El;4rx?wE(_@8UZ28{`NHzi+?Mk>mQMz9AUp)#>#+a$I+VAUHz8 z>(=XRoHvB&8O6TsI8=Y$o#U>~Ba85N zWX;209@n9tE(u1lZ;O4 zLtTenS0ota{b{c0<52zGyAHkDIYPqw)2a{efwQ7WFv|Pvtmfk&!4VSPXIGv39O^ps zU6EiE`?lBz@3jxcD&Yu;X)+w^%I8qmp`R5AMzL>;eem9O=r_m_52b{XQFA?!`M0|+| zj*yuCDAW2)>dU|4{*Qd%12+Vt*o7U($BFnF5nrkt93e6NQ6tBPe*D?{A9?O&_myCj zSLHhO{fxi&?EOc5`^)Y<4~~$S&Zm*%T`zy;-v3mBQNF&fHr^l!j*ytnr;+0$n#0f1 zojC^yM)@n@r!sPUNW=#+R3K&=IC*l)nmV9-s1!&%f{su6K1FS;X{5jU1}K$2oHnjPloQ zy${vjqwCO5mm?&mKWgMq{XM!4E5RtAYSy|^{XM!4y-GMjV)~;-4%Oeqbyx{TdAC{h zq58YH4t-Y~Au*j#*Z1-AXD+h_NifR0=Bjf=C&3XC(-JjusQxalL*Eq%MtS#lwT-o_ z`n$LeJ#&tbnEt4dL-luY9ae%-KE=4&Mh?~A#dYYr;s}Z9j~Y2te;3zbB^c$?*l9Po zxDH)|93gRc^+$~ys=tftuo8@77j_(~ri<&)HOLVXUo6+QD{SO2;X14YqkOk(cUJvf zT!-_n<_HPrbG?ils=tftuo8^&Q(vbH)!!xR@cKUH2#M*B8aY&d7uVr@ACq8|SC6Z0 zymQsx#dSDW$s8f!_wRZcIaGfa*I^|Xu|32IYPqg*!41UTr28^V3e=o zJYyatI6}hL_s=7T>hIz@^j(o)l%K{rg{%H9u0zk9BP9HsJg<>M_4nvHtOTR{j#f9J z`g?R8`mQ)a!rw=~pOHiL_vkvT1f#q!6GX|R(<#! z>N@mYafF1=bE`hQ2fC^%!6@&uvzqn0B@i4T;dAM#bDu+9ht5HQQ9dusuhMb&9O^ps z%sE2B=j-*o@;TIXSP4e?+%vzG`f~sxT!+3Zj*xJl;CdNr*XK~zVI>&FF6=mb8gm_b z?Q(>K`<=Ca_#EmwtOTRjg~dL2uYE9fHI9&&KH)JB)!)7A&{a!z((`zAT0B_+0J`z4N{jc3cjJwEMxUJM+;tT3(A$+!>D6dG8z~mYd!=t`5-1 z!D}&!JHwga2#MvUcaE#eG;)w&6nBQ+c^~gqW>V+*XW#G+*zBF7bKaZq)Aa03aA)Y9 z_m!}3(r?tXT-d+&`4?;s_50wp7~J45fhuY}#g!+Gy3bo%7zr za^8>M;;lXExBb_D>h3+C@!MbcvXA|S2ktT?md)NdI_JG}Fp7Ig@4TVLOK^)>V5$Fv{2W)kY2y93kQB`{(gK zJcnrkC&4H`C(m)@FyYzH@6{Y3;pgOejU3uJZ=CnO7Nh*W{oY58&Us&nWwZCQ($0C~ zyf?up?>Jt+BS+`FuY_0RaK$@E=e##@j#|H4?49==F`W0#(K+wO{Z8k-{tMu%^M3sM z&Us%6@9k?Io%7xVqkQ^U@1t|xSHj=M;k@@eI_JF!M)^cGS5NGmkFGsY}Zk+diR^Gqo z*TAQO^}X_W!FA|o#Ss!dVXW^}=e&0gM!7d%-`&o6UkRU-Tw$ZmJLkO#M)`LPu0#L( z-g#e%WwQ_B+rI13b?BM%T8!fF7JKKtbC6gzd*|q!_a+$S+-pDAKKST5oOd-xNI0J> zEcd}j*I^|X#osOV&igr!dEI5R_dGi1y$MG7-ON*serq7R<6o9J^!_iwdH>uym-GI2 zy>mJ5_3sDqS4I5T_rZBz2wO?Q&LvugBUvh6EpzBc3c;u}+eZ!)pDp6|=&m?IB29*o zkVijQXG7SO`Y>`p)xQ zjUyN1v@b^IehfU6^`tL|vWtk>ekTxEJxeG;^I&UhU`Q>?G2P81$?3 zWdBn=VLx3GjIs|l9P5$el_I`Hgx?@XNTd}pa{Lvo5U(w-5)zEEo6{!F@vMGO#E**b zO5_NMv?4~1SIYnS$^ZPYMA(2+Z$f5dsaviz`(|NCJG0OhxRUfLqC)c4@J4a5$v?4|hRn*h0K@x9A zlwHEB&Pi~DM7j?nhwAUib?Cby!Kn1q$FoxXJ-H5DgB&4|R>a7m`g?L6`stEjl-YC$m-qjo-kygZfR<6T2^GPtu&(O6q za`@@G4(HRIBP7y_7&%mbPp-rH1}DL&u@+>uk7s4Vb+}f^7$K1+!^olfdvYDR26-(; zc}=@^Mh?~Alk0G<_Bler>)7=&zKPe0dh$NVYca}K@z}^gf+HtF*Z0pOhwAUibvVBa z^IE=(6?HY+$FoxXJ-H6YKDb6mq!lrqmFn-}I-FlPKQG@eqx_Ei-p4#te;3!`{EE&I z5@|(@9I8Kmsh{STdJ>HCTJ!oHIaGfa*Wug^<_L+jB93=HcATfV<4oclb#>myv%2n4 zPit2j*(>3C$$ij!?G535a7Ot%GIJltb+3)PI*%+Ot%xxXpF{nuJaZC^^7n8)!{hKd zbUs~guVFXXSIKiLpx72#K^J#yorubsdg(F;af>G(Ij~qUS zx(;1~93hcb#F&TAp{_$eT@s8+PkrR@In;INH^>nZX+?}2S|JavL)Rb)M)~|Uzxl`E zbExakE0H54(ux>4R2vUIE4l_roTIL0`=A89(tg?_AFNAX?{rA#4({LB{mPc`t%d?7}wA`$E`=VuQ@cVT1jR z^Iim_yehr=$Ctsxjq|<`HoMp$Gjd$5p=am42u86B3)ipBq(N|mgs<EcuN;hG z7q)TU7sAiUPh#X~o%bRb#V%~)yf1{`x8LZ<(K_!%FzVcewa)uO*wNyZIdZhldlBcT z)rD=G_YGl#%*fF???reYoKft;HqQG(*hIDF(K_!%Fp6DRxPC9L!?($i%MlVbYOVLt zI`5T(QS8Dt&ig{x47S!)>%14iDDO6|!%>5+^S%(aG_Cru=XX{Vuf-^z7gwE=;0OuZ zrdFM|&U@Vzqu7OQocD#8Cd09=TIan8M)?%uIvmgHy{~xl)BpOjf8hQr^v*d#Vwwy` zj@Egv9E@TYwsGDUVwwy`j@EfEf>G?kHqQG(O!wi)(K_!%Fp6E+#(7@|-=XVeCgkU*A8E9If+SIT*z*Y~#Ey#55U>9If+S1f$r6ZJhUo zm?p!KqjlbkVAQz_Yn}In@QU>M9XVR(y@+$v>cTe8`-X6ZjU27>UWE6-8O1Ja%14iD0X2R=Y1ij$#CRoo%bRb<^5^ZN9(*Vg!iXa zAKn99Rj<-+z-uvzU09w)gWw1W@3X7UTj#y*ic##sHqQG(_`I;bSFQ721f$r6ZJhUo z@VRGwcU$MZ2u86B+c@tF;q%+v88*&)5sYFNwsGDUVww!cx@w*GA{ce4{(%)>t|1f#r;*QxKjMSPNo zpQm|ngoIr%VM~h~Z+gY2J@}uWTL?z^`o7wj2MLal@b&%k_ePGNqdWT3x-;Ju2}ZGR zJC2u%_#P3SIY&sO6)|%BOg-5@uP5xMOM+4C+m6G8-=bFuM@Xa-iKd8K%jkYLog zZ<~a3aD+s<4IERao8KzbnFb<(Z#H7Lo45`K&H}R-QQtM)~XJ+8OIg&ngJ#;0TGdB1R6?-(|i* z5{&X!dUbcIzl-b8tAryY(ux>4RDVydL$5>O=MS{XMx3J#&tbNGoE@L-qIMs`Aq%!6^1^ z@f8iitAryY(ux>4w5Fb1RbC||7{$IVzU@Ic2S-Sx6)|#Xr9Zh2U4tYT#lG!0R83E= zL)RcjNTd}pa+q)(R)SH^y>@5cmFv(m=Lm_kBJx>X=FI1{7{$IVpVehP-Ff~XkygaW zq56Ar9nLp62}ZGR)44>1>u|1;d5$8H?!(BT`g?L6&XqU`MtM!IQ=jVZ$#pna`y3(R zbsV;|$Z@TxC+~y27NdL>kL5n-sttl8Bz%4UocrLD>u`P<=Cv5*x%qjG9IC%3*Wvv7 z%n=g)u6SM}hwAU*I-Fm)NifRq$nSmRFyXi8H^>nZX+?}@b^TI5%`f%57Nfk@yh=~s z_Q=5z5@|(@9I8L>I8UxY66dJZx5Yl_UF~V^gR`TngzF{uLGPS5g!jQ2#lG!0RDa%` zW9H|PMWhvRJ}aLYV&)_m<+H?mhWfK=^qR(D?>QFv@45xfb-N)kU}t zy-GMjBCUv#!{<=fp;saaMtOglYg&J5QiSW!tDPexyg#k_@E$lTiUgy)&(3N-4iX$8 z;dAJ!bDu-C55`@QU=;hd*ash6hn_h{NTd}po|Vs`t|~uW5{zQsHo6HDu0f8FNGoFG z@Y%|B=o%!!DE4jH<3tXQkVq?Hh^Nid3iTkL}m+6QA-;|PhgB1R6?--GtS z*f~is%DG)T<6Gjpavgf+93jC@Z`d7gocGF}u8cRIyReP(z7XlA7rk-bi(nMHu#NM+ z5NSn>9If+S1f#qv*Qu{{-WMXRh>_!J4GrHmuf-@|-(%w|N`fOK(uz2qRp-3dT``JX z*v5HZh_oU`j@EfEf>G?kHqQG(q!lr8w9b1Gj5>E=t@FMRX+?}2t@B>QIcjxb8|QsP zg!4Xfw9b1G-UnwCyD4TIan8MzIUqIPVLQR>a8BI`2g=ie1>o zd0&XMB1VqZc`t%d-fdQWw9flNq!lr8sG^=+RiE>fpZLIQG0MBiie~vtRV|cU8H+Qg_7>5@|(@9If+SIT*z*Y~#EyL|PFeN9(*7!6W7{xAZ%14iC|AKc^|j9XLZlTja$GCw?7SDj zC|`e_UP*9-L|PHYv+A7p%E2ghVH@XtA<~K%Ia=qv2u86B+c@tFkygaW(K_!%FzVce zwa)uOctv{sj|-9S^InAa!5PIaEcU@We;xcyJdZ3Qt%#AM zb>1rnqu7OQocD!D_hIB{o%bRb#V%~)ye~vr5hF+IycfYJ?@y~fTIYQs(ux>4ya&3f zybtnPjPgFa>YM~eNTd}pa9Vog-9!6a8BI`2g=>fGJ6&ig{J)7v=jm3_K0KKv`s zecQ%)Ux;b5H@$J*i(nM{wvF??5Yvh{aG?-(ldH? z-WOuJ4@ZvHc`t%d?AyZid;bf6&r2RYLAFhfkeF7)k)w6qD+i<4w{4vFg_u^vk)w6q zi(u5bZ)=_Rg_u^vk)w6qi#SKEzHQ^YZwT9HMvm5bFT(rajPkzgsv5iV=gE9(*Qo8M z=aEIcNd_EO*vQd3@0Ej5?AtcZ`$9}B;>giD??o_*ecQ%)Ux;Z%964I&y$D9J3)?vF z3o%WGBS-7J7r`iYVd>jGJMRlI-G?Jb>%14iDE4g|=Y1ij6>;Qfo%bRb#lCIhyf4JG zB90ub^Iim_*tcz*_l1~N#F4{xdDo#=JFmqk_H7&Iy>gJ4R>YB`b>53$)VaI!UAYeD zUAYcjog}9FaO7y6_t(2}9Xg7A+s1ich-pO}Ia=qv2u87Q+c@tFF|CLrN9(*7!6W7{$IVYw+y6FT`{ojvTG?UIe4qx5Ykq(LVU(eUKw0rWJAIXr1@U z!6^1^8|Qr?rWJAIXr1>W7EcFX9}vy0DG&z9C#MBS-7J7vX(y zMzL?(IPVKFt%xH>>%14iDE4g|=Y1ij6>;Qfo%bRb#lCIhyf4JGB90ub^Iim_*oAGJ z_l215!;zzP-iu%q`?frbo}KrFnC`=oqjlbkU=;hdjq|<`(~3B9w9b1GjAGxmao!hV zS`kN%)_E_2QS93`&ig`4E8@uE6W@*VUIe4qw{4vFg_u^vk)w6qi(u5byYpRXAB^3Z zBP7`A_0D@|pRSA-ec`!p>z((Nm?lHhz4P7#qu96g&ihJC_uG?-(zhKo$Pp5@O|3fbocGSbDE4i=^S%<(WH_Ex=e#$;DE4i=^S%<(WH@qk z&U+J#Vi(ps?<+A)h9gJkyf?upc46WAeR_*LytZd^gv4|ojvSry-Z>a`?(RD0eI=aF z6*h8o&igr!8O6S>civZGx(`Q=&UtTwQS94#=Y1un6>;R~ocAUe#l9`}!5im&CA{)o zFC$0iyf?upc41kA;oIg2318noj~t!z-Z>b>zO8rOS7N#kM~=>UZ-P=*f9s3GcJ3&O7J52}ZGR>z((Nm?p#VtUBkt2}ZGR>z((Nm?p!KqjTPy zU=;hd-g#e%X)+u+I_JF!MzITveegm1;G_3Jj*yrp!;zzN-a7}Q&fT5wsygp0;e4*J zk>l5V&kx+c`Y*~){#Tas-XqhM@s`g!_ig&`AVs|DO0c6NVfTm)GN$!6LH{rBz5m{C z`Kh%jU0dU*S_@bM_>E?8{!VD2-6B4Cy{q%cBJ8eO^U%y6=gdhkihbL0sQw=3)8z;WTY=X5 zQ2kw8hkk=37{$KrI8=X^s6!DPAz{1GT34#Si|f$qiUgy)+pPLf{asv#UhNzqVN27h z4^`A<)*uN+dDmQZPJ$yOrpa);bJgF)b?Cby!6^1^`g46ET!)@HM@UTf;mD!-ySNT3 z!6^1^`nwZExDNdWIYMH(4@VBIkjwnGlVB9Pu;b7wOoAgMru%T@Q2kw8hpt)@jAGw* z9IB>^>(DjG5famVIC7Y99ae%-&h6S6HK_W#xDMxC%@GpL=Xx1At~0+O7{$IV_Q8wm z&^b6l!q3h1GIFT?F0RA*23?1~Uq-QSi+%9oI-IM-RaFVUf7i>%q58YH4lBVZujzH_ zQ~h0BhjX>h5fWa(Dt!oTFCX7W<%gwaeTGXGd2F*UQME`t#0tLwFyY zQS95~<`CgJ^j)1t7U6w&&BNa+*I^|X#l9`}L7y^$;0OtyAJ+TuIn;INH%Nj}?Au}= zyw^S$tAryYd=6Uc%I8qmq1P1&MtOglYg*?k?KZAMuXc`*h;wMxhxb5NRV5hZeRfu} z{=RPz93kO-cGbDhp{_&cAi*g1ZLtsDyAC~bj*#$qVSTTB4s{(?f>G?-VjsMB9r_J& zgoMvM>$~fdlB>$=iUgzBg~dLY1V>2t{N{QY_2F}<>(Dt!Fp7O!?1T5(2V+;`2#IMj z963~f_pU=%EeS?Bx2tV@OMDJ>9nQO&BP5*9^)hmN`LB8V{l`4_j=L}a?B%@oNLr>| zt=|Wny1V~C#3zdQ_eF4oMEavdAIJOu_S^1X^d~=XLomv3)2n~n)q6y|?@xT-?$;^@ zM@XdeDRTVpmuK&P`+xGX`(IZGMtN1n>W}X3Cq(>rB0LX{kVs2ZuEI@XR?vBK=X3;{$rK->oO? zr%QrS?81)YCq?{_2+y1&B+?%hIX+%1#4Du|jPfe-;vDcIcuSAZJNPpDG@rLK0 z`M2NtO*h0jYIR}9@k>Sg5)p4v4t8{vu*dCf+Z>iHKs!t{*tS7FWLSH0o+7e4=b zSLcyMq(3ThsQw;Zhn_hJM)~XJY8%f=_4hcRE=NeDKPqyl{vKV2ejg+l<*)QwSE|29 z*P&MlM@XdeDRQX(F0MnbL=uehZnNq`^>=X{`mQ)aBAri>Llt$IHAsR{?81(N1V>1u zB`R{L{w}UV*B}W-dG}x6E7jk{b?BLMghX1RB8Tel;yU!xCBZ14Vq9(GovZ#Xu0ua7 zj*v)yROHYKxwsB1!6=``)^4EsySNU$5;;O5ollWN^>_JrRaGSz#V$<0dllh2bPaNZ zMEav5hY8nVB^c$qUAwdD@8UX~cQr>yq(3ThsQxZdhu4`;f>D0z>y+WA>pGlIcaD%q ze^lg9{asv#m0*noGdKo#c6?H=}Do&ModL_XT6288F9ywHh7uTU{kOZSVH$Si32QRL}`SqD2B>bE_ zuaQIb_vkvDU${vy%5Qab6RN*Q*P)*kM@abl==U>nsQ&z=z9AUpwYIt<)!(D*aP9_k zgoMBIUT4=FTIsICN}Qus7Z&@VceTsh2WLlD3D?WWq5AXAc|&*~oKgOc%)8Z}NmY%z z4t-bWkwtjlUGs=@=ym2K7{xB^ID8JBPnRPke12H(!{<=fq2C}0M)|uw*TQkA{_b3d zUL_nM;d9VhS3ZZj4!sgdFe=WWSsy-!x(a)gBY9oNgq;d7|=!Ps#~Fp6DR?1T5(2V+;` z2#NFw&wcRTb?B-k!6@fm`?=4duERNxIYNSc+s1jX?9)Qg6sM@d0t~4t@B<_mr>jqHqQG(*f;4nI&!qmdl8H}?+mT;z7WsKv}u>- z$k96QMVzD7&aiRbH$)gd<9)QwdlBBFW)ydZjq|<`b_=h0w9b1GjN;C)ao!hV+U&=( zlDYRz2JKiSycVOlGi;pq%0a>=+O@9iuC>F~HOOl*iaW!`d9NHK?8;sBVQa7J&^dT5 zMsa6|8cc#CBy7%Jb$)evM-CE<;?59XAA7@t;0Otuv)A{kb>3^{jN;DFJMaB&r@`L; z`%JXXd*vW8-SlIXw9b1GjN)FRKbO%t?+Y<)_9I8@ycfYJ?j;-NeIcgJe&lGK_aYc| z-lJOQeIa~@uF2~>I_LfMu4a_qhpX*+rWPUR_A_3)9N~4R&3@!)o%hPYD6cnH+sM&6 z?+Y>A^dpB|+pb*S6|co8SAnZ-qmvn zo%7atubDH-&&hKfIj-NUxGRp3@R!K*8uMtK_sYR2zi+?Yk)w6q7s6juztNGSb>53$ zly@Aj-;twr-WS3v((7#GXr1>W&Qa@kiyP;CLqvtmo%4HKhhA6w&8GkNjPeO!&7*bR zD+dYh?Q0&b^Iim_e3Du3qjlaFV!G+av(nD_=sNT~cr8Zx+_l!#UlVcTyjKnq-U-&a z^4@XdycfYJpC4C!n7DD?7s5N*st@m)t}4&tbS*^r9K7nB#AyVCcji^+t@B=Y#VDWj z*Y~P*-WS3r3|H8AAFcCV1f$%WukUW_yf4JG*^eBp^Iim_{5uBM;i$n+`h|bu(RJvj z%MlVj@y(q@dp-iu(Ay`AC0jvTG?z7T0ej2u^M z=-GKMf>FM{^Ne|r;K+%XHv7oYI`5Su4T%wTHQUELTIYQs(ux>#>%14iDEnZ;u^u^E z=Y1j4iWoUs=e-C<+0AJa=Xh4F^S%&iMT{J+^IpU`>T0&vzfTYE*%3PEM%lf*-bd@aFGRWzBS-7J7jcfdn(bqL zt@FMRX+?}2t@B<4qinoh_0c--D>1Ezk;9%}SCw7Ayq3*rt}4GZyM$Mrli&!6bRR~J z)_JeHVpMwS_3w|Pb>0^ut%#AMb>53$l-a>Tu-h z--qk>)_Gruv?4|hd$4bu_ae?wSF?TOFkv6|$zWfIv?4Oc*?BL5QJzOQi<#r>ye~vr z5%XEyIPb4_Z?bBCUv#!{+Q8=e-CV$7p;-s@Vv z3sd7xu4enl(K_!7kygaW(K_!%Fe;t*k)w6q7b2~Qk)w6qi(phb?;}U+ye~vr5yw04 zocAKmQCH`EjVpMwS zBS-7JFGN}qBS-7J7jcfddg>!b>%1>SS`i~h>%14iDDO|JK3eB}C8iZIa(EAPRh^vo zBGPxLsPxq9-$xB5!4VSPL06r(&U;;pQR%6V9If-d5NSn>d9==Z5sXStedK7J_k~C+ zV&rg-bK|@h!6={7*8b5t?+cMu#K>X0{EhQo#5wBfsn@?hj;oLU?7S~TS`nG!?7SDj zD9>Z<=hqx(=Y1j4iWoVbkvaRbfBM_+pZ)l6y64C=V*KRiocp%p_#6?RDdIm8!H$lE zO(HhPm_CkQ@rpM;e4%X3|8XH0#lB5{j!eXtiTHF893f#NiVZR&$Me7MH4m@&>mUD6 z2}ZFCJC65=_*X={QaLz6!e$p6WJZo(D9@<>xhn*t&V3sRj*#&6{qxB2uj-EeC*7Iv ziUgzBx5+aq;?Ici%sE2B&&l%|IbN?P`+7a$Us4E0v2Qz$FBb6yBK!t9Lc;Ic?`P!r zEUgf)lu9t_+_(KQ5qBcI5;;P`_7<h<|`JH$F$FKXU8{! z-=5CCuM#%Mj2!R(%I|!9e?yp_QS94}07!X~OU57pnrb?BLsVAQ#9Q~h21 zbX|iSAz=sCdLOF4i|f$ug9M}4w;hM-@8UZ2y5b0lX)+woO7-{TI;;ev*o7U3>hH;Q z=+({<61Ft0`cOqZ%^D=ZD4!QyJLAkqf+Hksn_6|Q`g?L!`L0MXihbL0sQ!ZR%sE2B z)~xltQvE%-4qbyJ7{$I#e}B6O*P-7aM@ZQIwZ6MrAy2NuN-*l&x2gV~T!&tX93e4H zhU1-Ur9Zh2E5RuCZO5VddvYDR2021vx(}~4D8hAE2}Yf}JKvS-aNd=x%Bz8d^SNF| z4%Oe2>#!1xV&4|~;FIgnHOLVXer~Rpkwf+O(DEaBP6_Tz0O7s)t`5q8{!A6b;S`9{;sce<#VX(&?}Jyqr5-OH68olgX_?% zog*Z?Kdt)k9_TuB4U%9K`!@akq98az!u#y1bDu+9hrTNkjAGvw`(O~BIY&tN9J;<& zK8LyvU4tYT#l9`}!3Wo&-ylaw_}sI;yFMwo4lBW^bKmB3sO!)xks~C0ep~y8R{DeM zuo8@7-xmAegZ9DL)i^@JCrnq^wFZ^Lb?B-k!6^1{$KkuuJ{Y?*M@TrI>t*El+F$>;a&Ux1S`j11kAC|7!{3oP^lub`QC^kn)b}?;d{D$c5y24> zcEQ*nGv@K;U-W4Y{^uiwV3e=#tBt2if+Hk+eg8ai{9n4GAJ(1uu1GM-&&f|^-iKd8K%jkYJQop;zO` zVZy7?IXFTht%#B1m;cB+@80q6y!GLOg*Zp8E=<3f5b@0-{$CO7=qh0w&3GTL`jK}& zeoI4`o>BfPta-dvgzw5TKaVUTt%&nkUFOV5Fv?%I^*&U8m-%!#LL#k*kwf)&nQxE; zqx_X#>q_-^nX7~&B+`l)IaGg7u0yXx5{&Y0v+6_j_vAYCYUcr$t1# z4qbyBA(2+Z$f5dsavfHJQO><~XWy0U&@<-ADW* z)14zE(ux>4{03cz^9@ddQC$zP^9XeelV3=({4pD9_E$EBC=C z*Wvv7%n=f4MT~i<{``e|^3&zD80B~5_n!NpzoJimgB&4|R>a8RHRYA!RYHPMUTa>Z zxet0bh#VXtkygaWq5AWV^W+*NagJJDSnPw3uEV(x&W^4Uu9w^g?_7tK@IE-B{2f{I zQ2lv#j+viF7Lo45`K){bh?$dMl)s1TefS(YpDss8`265{8T0TtbiP3njPiGVt{(lp zIODVwtAryY(ux@K@Hy0V=#@xKdy-e*^x`y8r$Fz$*3qkLYN-#%$y@6(ux?*$|nrhp=*!?qkQg}-^$TV zm~ahpghW~qBZpRqdz|=ElVB9Pu;cJ)Z0-geA(2+Z$f1?~;5u{-l3*0Ou-FG5v=7Fv z#t{-}MT{IihiV^;os$HkoO|u(zAM+Ezdjrx!M<(dyjS)#V!ZtM&t(_3ao!gqZT6x! z&U+DzVi&e?-WMXRh>@dp-iu(ASEX0~_%gK4`$D7@F>+k3p=am42uAt(&NFh5;0TGd zB93R(Iq#K&QS8Dt&ig{7`!I5}&U+DzVi&e?-WMXRh>@dp-iu(=xeIHZ_k~C+V&rI@ z_ae?ws|(vW?;9d)_K~A?-iz=)IHTBwZJhUoNcUmnXr1>W7{xAZ%14i zD0X2R=Y1j4iWoUs=e-Cg2o^!6@&VtIkPqghW~qBS-7J zR}Mz83k%opt@FMRX+?}2t@B<4qkM{S9gc6wKl~N9Vog-9!6+ih>g>E1 z!6k|(R}Mz83)?vF3z6=_$k96QMKFq8*v5HZh_oU`j@EfEf>Gx# ztaaWOBCUv#qjlbkI7h86Y~#Fdh_Km5j@EfE!u#NiVi&e?-WMXRh>@dp-iu%qyReP( zz7T0ej2x}=UIe4qg>9Vog-9!64TIaoTFp6E+#(7_ev?4~1)_E_2QS8Dt&ig{76)|$O&U+DzVi&e?-WMXR zh>=74;DhVX`yj8yD0X2R=e=@}NGoFGXr1>W79If+S1f$ruZJhUoNGoFGXr1>W74 zTIaopbJXhFHqQHouyf|ak)w6qi|{@;qu95F>-W}qUx+u!S?mfMIa=qv2u87Q3)k=E zPk#DmJp6R|ojF1xt%xy?)_JcSjAGxmao!gqt%#AMb>53$6uYpE^S%&iMT{J+^Iim_ z*tex``|P|gM7j?nN9(*7!64TIan8MzL?(IPVLQR>a8BI`2g=ie1>o zd0&XMB1VqZc`t%d?AtcZ`$DAqFmklcdl8H}cXzGxz7T0ej2x}={(4ugDpxA|wvF?? z5NSn>9If+S1f$ruZJhUoNGoFGXr1>W7{xAZ%14iDE4hxgJ0`kE7I$C>>sW3 zUc@E0bJXhF^!H_m_!JRer5x<&DiH>mSi67qHLrc_2-7o)UD$E_EfMps&LfMk ziE7P5^>^{iU4tYT#lB77_Fw<9i|f!&mm?&m$#6U?)!)T+SP4e4Z#xdv-({{6j*zfR zY^^KR-^F$4l}Lh7?AzpC7U4SdYUc@keKen@jmoqpInEoK@yB&-*z0TzbDtB-ylaw*tzC<897vc zPp-pCFp7O!>;_M+L)RcjNKBLA$f1?~-*=CL-luY9nLSqycVN8H$ShDL-luY9nP=M93kQ7 zp8RxqEk?0#i+%9oI`kXl2noM$zn_sq^>=X{R)SGponCWe9;!d@22WnQ z93kO#>vcAAsQ$d;+z{ue)wjhy=w0n;?t`G?-VjsNMJ{V7zBP9GiT<^o@P}iZ~2MI>8Z;O4hIol z=o%!!DE4i!58k^DJ#&tb@Ofc(DjG5fVPXt^GqQ{lRru2}ZGRi+%7x`(W&993e4HhGQP8zX$Duv2&7O z6nnVi@Lg#ijNO?dB%IInGIIR*JAdH*Bl5m{@((ZPy+@`iD52(>RlrKkcdwb!4VQRqSzoaa(ww; zc=!DeefXav zeE$t`j#^!q{tgHc?-Ai=#g48LHpq+|Z+P8HA3MVIjPh4u&EwNW%)2^|EaL00R>YA* zGk=^jC&4J62G;w~(|w#zmm?(X;9BoP^>=X{`stEjl)utzU8(*qu0yX9j*zh3Xss*N z-^F!U2}XIhS@og%ySNU$+BrhPmL}KBcvh;Y%d9~XjPkCz>YM~eNKBLA$f5eXxDI_+ zBpBu0e|@i1e;3!G*A+)d*qXJzSE|2@>(I}N1fzV4akY*5Q2kw8hkk<`Au-*DV;))| zm-(e8!6=``PP@Tn?gktoVT+mTW#rIGzqk&4S0ot4E=+%qmk8IPpA|<)O!wi)VZwD- z2}U{h+MRt@uETj(bA*KRxn4#N)t_g6LomwE(6uw($Mxw3!4VREZmyS+L-luY9nLp6 zuf-^@g>_m|{asv#bCt{y5`O=#mytvDcX1t7f>B=6>(r2t`u=(3Q2kw8hx5xYuf-@o4L`4uL-luY9eR~;goK}y=QVPu z{w}V=`MsLgVwB&J-|onv`n$Le{RTNg!tdMfXXLnksc#5Id3AdIjvUwBAPA0-@VfOn z8#z>e-f?b-bJXg>VjuLb7SDvgV=s^X?pXbskxSzawiN z{_?mE{d7q%id~rgJoPwb1i=v!K0mDY;d7|#&^bsj%HQ?57LLQ`P}iYX2}elyyS~RQ=t% z4*hgVFv_{te(t++9nQO&BP5(}?dPxmdf6S{^Nzb;{mYi~-r3VK^&5qyW?|b|6&%FGbzv+fJN3AaGIDSgR z$BOte07BK=X3L-qGKXHJ4q z{<^u^#Ty?JKBsfAMEm4s}^>=X{`mRVY%Deyi zUa9^ru0zk9BP7xv6**LY7uR7W80Axpt8Kh<)!)T+=)2+wiS$QB4%Oeqbyx{T`80Og z4KA)j*C0noq$MhHsQxal!%8rUUD$D`nl7$G*C0nor1L3qm~b6df>FNPwL7c+F0R9Q zS963!`lBL;>hIz@tOTR{)YmCP^>>LnyuOb)LL&W9kwf)&aUIV0F$qR_^{ms9>hIz@ zoU3GxknsC=y^Qab>hIz@tOTRHrq`)Y^>=X{&ec9gNO&E)UasH7QBgMpqkI+T8Ef}i zgF$eFgs<jdcoF{asv#o;gQI_&IrABZunm(REk}M)@7BZbJ3< z=sNUWafF1wkA6QRhwAUqbyx{Td3CO?NcHF4;Nq3Y5fc8+d!3COs=pUphm|--tu8F~ zLGNmpxev~ct`e@7kwf+8o%4q9J~*TN9a-~G{XOG4^j)1t7U6w&&BN!=Idc+>Vi$HC zaSpvcU5=3O`C+{epF>@Tejg+l*2WO+j{%KPlBX8l)NG?kj>G3r*P-uxL(HE^*PjaSP4e43)7#u6X81a z+T{od_dBkak;CUu*I^|X#V#!N!F%n4v8!=}MEZp1K6vjsbk&kzl<#)!=RSwJ4(DCX z5fbd%j^nqy^1prjp)Y*t^UHZ3clA3&{Dg>qO$7H05_VjMLt6B4 z{K0pA+vDec@oR4gMsa626C5ECu5B4U^|vQ0#~1xeU-#&Ld{-nG#hu|yaD+tK>?4Qg z;JG*l2}W^eI1Uo05#4v>(RKZtJg+g2|3^>u9eTpfL4r}-8II#eM0}+Pzd??Wuy4}u zXXNW_e|N4!zd;g=;?8g!s=qtep`R5;NTi!Sa%d&q&9zH{ zQQR3~?Iyty5;p42bsQCSH*1gtqqsAi3678mGjP_q=5RN^B_tTdoguy@NpOUO4ae(y zrTV*b9s22#U=(+T<52zGxeomX8I=Zmy@NCH`Zs;&-5WmZ>4pDX1V>1u%|71XyMEpu zy8D`c@U9nL|8vg-qqvtG$MNi+y8Cr6`t2`#!pD8X14l^MQSAyFUj|j|oh#S#Ai*f^ zCHgPiM7VPOtT;jT$J=9IDtmSMFR_bA*IfPdKC_$91*e5R7sa zxY|Yz5*#7nl^-tb$f1gL)kY2yjPmt8Hgb^Q2nk<5DlBqbzdn(J1f%>k{JcgE5*#7n z=j3_i&Uxp`_0uK6D8FyN-H}5Td*{ma8{`OywAsfzv~&8~enT+ItJCXuw-Nm+Q{yz4nGMJ)^v9uX(8czQ=Xw zyE>07!rzfK57nQ~3^xR$d|p}aL-pr#Ne~<%;S-1JWjrgNTwRC0D-w+IDQc}NpIlvs zUL_nM;hkWuEAKY0s!A}*r@>VpBsfAMo%gc_eR_=?BpBsW?W%J{Cvh5?&U;_;ghTDuo8^o?-pYpeAGS|yBbGGq?FL(SKIiO_~hz3oOd-xNI2ix&pmV3VI>&FuJ1U$;tT(a$B%l=H@@(jo;~-2 zB+_Od^Z051_aA#aKI5;x@Scx76O8hcc7=^M*gEe&`3IKs{>4AAocH?o8|Qr?(tRj; z(j@Ef!h;$!Dj@EfEf>Aboh6_7#w9flNr28;(Ts@=V+vc?xm1g_ML4qSE zVmj|5N9(-Twd}Dm_2P)SI`1P#>%1>Sx(|bHo%bRbmCpOf(K_!7k?zCD(K_!%Fv@Pu zFv3TU)_GrubRR~J)_E`D9CdZxM-IET?ExLW?KM(~a39Vbx6b>x*42=xsC3@X96_9% z_k~E4VdQ9?_aYdT&ilAh>%1>SnhYaH>%13nj=DPUBS-7JFNDotuCTExTj#w9My01d zaG(bj~sIS-a79Kk?zBohpOq;c`xD|b#>lH z4ih)d`$DAqkU7rIdl8IE=RI?ro%e-ED`MpEv$}EKU+>Cw=qH-a`^aJ9#(7@|KWSIk zcpt6vUIe4kc^^4i=Y1j4iWu`~o%bRb0^u-G`B*b>53$ zR66e?N9(*VM7j^hJMWzLBF<4)=Y8a8o%an9?!%cQ4EAg1{2yNZTwLqwPE?flbJyYc z_t(Al>EygGM4AjEN9(*7!KifJ$CX;=eIe3h7&%(!y@+$v)p;K|TIYQs(qtGpTIan8 zMy2yUaAa5|t@FMR={}4c?s0CM_aYdT&ilyGI`0dS?!(C8Q{|2GUc@=->b#E} zCR~T3qSgqBG#N6-*?F&PF)E$+%yD+!7b4wrKlS~mzHQ^YFN94ZVdoOP zao&qy6#KS~^S%%^qJ(8Eay&0T=Z*7T1f#r;*Qu{{-WS4Vm$0Qpj;l5F?7SDjC|`e` zOVcwN1V>2t`u_PRBZpnvH_m(IU=;hdjq|<`eolT8BS-7J7r`j@Z5!u(A^g7mMn{g; zc`t%d=Ps;u-WS657O%{a<9)Ju+UhwSxn9{mC!C{J-=^Pyh`4dyH-rr`BS-7J7vbO5 z&M5Y68|Qr?Y@%B8Xr1>W7LMj2(SFGrA3ZwMTKvh*J9MUZzI7G6288F9`B=d-s`Ry z#lCIhyf1{Glb^)M(K_!%Fp7O!?1Q(?`$G7A`;Cqqt@B<4qt1O>>%1?7S7g`(<9%o! zymj7-I7h9%E%w1%=Y2zj`!I5}&U+Ew2WJ%fwvF??5dMy=d9==Z5sW(bZLRaZ5dI#n z_t840`k`_rlq?}4tWlk;8#qu96Q zSu_Zaknldc>b!N{D+i<4w{4vFh46V{eXm;Qy$D9JZ`(NU3*mFm`tG*Qdl8Ic7j_)2 z^S%&1zs;Rt*yUY^C+EEgMzL?(IPVML6Q(O{d`q+s-a79^FzVdh`E-2ayf1|BaP8+; zyJPt1Ig&<$0c;jQz&5NSn> z9CmH{3EMNuYcYy_+i{qXDK>oc93hcb#K<9I=&kc!cf}~LLa({8+D&*h+GWZS5@|(@ z9If+SInGh5Z`(NU8^Si4?~NR-^In9jbVm8Bu;$S^?+cMu#QCglo%bRb<*(c7?po)4 zA<~K%Ia=qv2uArUz1CIhye~vr5hF+IycfYJ?>4JGTIYQs(ux>4?D=(7*|*JWG0MB< zs&f(?A(8IG$k96Qbytk??!UfQt@FMRX+?}2c5S<=T!Xw8qkM{SwT=3)soBIdrq2-) z={}4cwn4k9rj>mXjAGvwuHPV>gCiu;WEeSYwZ3uQYvzn%-?nky7b2~Qk)w6qi(r)R zcJ0o-s~hKiA<~K%IrQc6%)_M2YcYy_TkM0k&im^;T)F;!q!lr8_zm7T??o`mYhj(1 zyh?7I_k~C+V&rI@_aYeODp;q!)_Gruv?4~1Yek)%_aYeO>#x%*3679R_hIC)Yx~A| zuN;hG-*y~!ZQnTW3z1gD$f0Vwb>53$6#KT=2XCGCg-9!6%14i zD1XCNch@@a3z1gD$k96QMKH?W_0`?A&ig{76)|$O&U+Dz^8U2yqjlaFBCUv#!+W5s z%KIR%#VGb|8|S@pkVyAoihWypMuXr8iL@e)XVp3Hm4i|2!ZyzPLZlTjaW&QYsx+c@tV!Zw;0MUK{aFT(rajPh5( zRW-goa*RIOHER3md1Mi3MT{J+^Ika^<*%E+MkB`;y!qM7@BRMQJbbZoaD+s<4a8BI`2g=id|T^es7)kg-9!66K#ync*y$D9JZ`(NU3*kF-y^MLZ&im_K%_#P58|Qr?(ux@K zXr1>W7{$JA%14iD0X474?aa5>RZAQ5@|(@9M>9rvTvINqu94)4F9If+S1f$Ma70J&Q&~kzf@2wmgdl z!4VQ^MT{J+^Ir2{6#KS~^S%&iMT{J+^Iim_*oAGJ_k~C+V&rI@_aYd@zHQ^YFGN}q zBS-7J7r`j@Z5!u(A<~K%Ia=qv2u7W|yViMM2zGiK=e@G05#xR5zHQ^YFGRWzMQ@z< zA{fQKZR5NzM7j?nN9(*7!68&*<5CUx+jrMvm5bFM?6* z+cwVoLfEw9C-LFP(K_!%Fp7QK#(7_ebRR~J)_E_2QRlv`b>0^u-G`B*b>53ON3AYw zhragKd0&V($!g^a8#!9%y$D9JZ`(NU3z6=_ zcvh|RUIe4qw{4vFg|HcHt*h2~FM?6*!ZyzPLZrzs=FvLuMKFqeTh!o_EB906MdkW7r%$ z=aHjz-s`Ry#lCIhye~wW4C8&Y&U+DzV&ArL-WMX>hmoUo-iu(=xo>No_l59^3@c*f zXr1>W&QYsx+c@tVBHV|OL;K*Z^InAa!5PKAZR5NzM4AjEN9(*7!6^1^8|Qr?(qtGp zTIan8MzIUqIPVLQCd0_lI`2g=ie1>od0&V$8AgulSu`q&*J2d=wmgdl!4VQ^GK?Ip z^ImtwDE4g|=Y1i3URd9&)_E_2QS93`&ig{7$uQ>8I`2g=ihbM0d0z;h-{#Js-`xH8 z|Hgys@FhBB@LG&w-?nkyD+h@*8OA(X=e-C%14iDE4g|=Y1h;b_rWr z%14isB_=eI`0c%M~heH$k96QMVzBn-?nkyH$)g@;(fHvdlB9TXOzDR zuB!3QTjzZt?5W7{$I#-}cUVUx@o@MT~j0&U+Dz@>hCwcdhfj5Vjkwb=5lW zMKFq8*v5HZ2wR#~eO!IpQG>h|qkO7#wPg+7I`5T(gl$u+&h6U1ao&qy6#KS~^S%(a zX07j)Ey_2}dl8Ic-?nky7a~oD@y=W4y$D9JZ`(NU3y~(n$YHDXjq_dvqu94?ocD!D z_hIB{o%bRbb?)wbS2xc4Lii3{VdGoUI`6M{HKW+KZJhUoNcUmPqjlbkU=;hdjq|<` zUNK=AiyW=9Voh49J`TUz9})?nDPc`ZhW7{$IV z_Q6}{eIfju{3J$>)_E_2QS93`&ig|6i|RKza%14iDE4i!58gWO3y~(nm`Cfp z7r`j@Z5!u(A^crm>#B9$i(nMHu#NM+5Z<3weOynLQG>h|qu94?ocGE>!u#y1^VWGU zf>G?-HqQG(_`I;bSFQ721f$ruZJhUoNcUm9^VWGUf>G?kHqQG(`203^hGCb#ao&qy z6#KS~^S%&iGK_h&&U+DzI(K)i^S%(iLs!`NUR~{uXDgzzrz_)sKKE_Z?v2c!J{*J-JB-WS3Sm9UIOj@EfEf>B<_>(ux8@^jiXI*p!lgoMp5VM~h~ zS8M3md9NId@>SO9l>|pf`1=0&t&yX3-YW;A{G8S)ymj6e!q3U`8aZ0$y$D9JZ&RJi z`+DQNFNBRjexoDD)kb@7+a|BYsB_-W}quN)-o;9Bpab>53$l)utz zUA4~pLfCG!)>Z4g7r`j+Hmg2Vf49#2LfF!@>cgI2SCw7AycVOpYtCv8*KZOWA(1A- zsKM5Gue)NDcmMUhYMu9mNcUmnXr1>W7{$IVT)(%@`$DAqFmklcdl8Ic-xjXlTjzZt z(tQ{?Y_+~|-iu%q`?ihqz7Xj?j2v?P-a79^FzVdh`L1r9_l58sx?V<|x6b?PUCk)= zZLtqtrb(G2ylz?%V;-&ZUO5=WzD<9!My~A}=Y1i(V!|>OIa=qv2u8UI)~QeX;H~q% z5MKFVON$)W8azAiMKH?OU#C|R93kQB`{(gKTIaoTFp7QKakS3+LijoPNsJt=^Iim_ z*tf+#cf1KX`-TYj zVa%g--iz=)IHTCN9Y^cDFNAmMHIM5FAZE^MF^YX#?1Ojn>2icbnhawet@B=Y#VGb| z8|Qr?(tQ{?TIan8MtOf)_2F}<>+s~fFGRWzBZv1uSJlaRFM?6*+cwVoLU^BDb>2Gf zMKFqe+s1ic2%i_$_o{W?i(nM{wvF??5I*;~UPgUfJC^X#^ID8z-?nkyD+dXm-{#J6 z9If+S1f$ruZJhUoNRwf_bM1q-&U+DzI(K)i^S%(iL)XiAR<=9dIPaA`EmME)+_xP^ z>%1>STB1a6ocAIa<@fJ;8FwYe=&kd<5b2MK9If+S1f#r;T`wa?>%1>SI-erP)f##~ z9ia1CjPk!*r&kgjA(76f$k96QbytjH-=_bLzH{CeBAri>qjlbkU=+Ksjq|<`X^Dy) zt@B<4qr3`NSJXQ13z5#J$k96QMVzBn-?nkyH-v3%Z;TwR^InAa!5QVR!kS0xye~vr zq9RA@ycfYJf8ADh*E;VDkc(K_!%Fv?%))!o^(?K-rLmLnw65*0aG=e=?;%Dc^~ zkJfo#h;%-U_W^@Fuf-^zDraqm>-W}quN)-O`4l-?=e-CArgIni)A<_~RIa=qv2u87Q+c@tFkc(K_!% zFp6E6ep@To_Kowt5b2MK9CmHrIPb4_6)q`7v2Tlg@YZ=>i1bHA4!gE*ocAIa#lG!0 z?Amr6x&}Ey!YjrVHojM_^Ika^#V+hPTIYQsyz*Ty*KcCyycfYJ_H9{%VbA6W318no zj~uP@UO5=WzAg5_TjzZt{G9wGMvm5bFM?6*!eSr1b>0`k-$%cnk)w6qi(u5bZ)=_R zh46~>`W-o1=e>w?)au(d&ijUNg^e7o^InAa!5PIaO#lB!=e#e3cj`5d)_E_2QS93` z&ig|6#IfE->%14iDE4i~(K_!7;gi!^SFQ721f#q^t>1pM&ig|61i0#h276wMQS95I z2Jc0k4fe`G!spUe=dJTz1f$ru#XflJyf1`Lod0z;37Ot?dc3bDY z2u87Q+c@tF;SOo;49C$r??o_*ecQ%)Ux>5@&wcRLc`t%d=kBg`-WP(M-o|;a>}e_d zv**3!I9lg@A#AJ+hqUN)XFl2*%6*AZ+!@XUM@WQg+b-zQQS*5&ig{x6l}xicvh|R zUIe4Kmu#H(g|NYOy^q#;FM?6rOE%8?LfAyR)|G9yw%$%7^xVA|#hqc}yjKnqHtI&b z#QU(dcUBay#VGD2QG-cvghZILv(B$h@0bS(MsY9MIPWzN5;h#K?^Wx(7r`j*B^&3x zo{8%14iDDFNR=Y1jUsCG?`)!sVqMKFrH&&GLQh;-A( zJX+_y2u7XvsMdL32;ZS=a?Hc7?HlL)^{!@=--j!AoEci@eIe3KAMipZt)_GqDugGx4M~>EcFX9}vejB-Q-Zw;4Smdy4`^I@M!aL`T@(I9oIG$DOyf1{m zBWoV5^Iim_e3Du3qjlaF!e3KY*m&oy^Iim_d?Iu0jCr)q`$BjpSnKL~>Wh`gYca~_ z$5kIBI6@+A_VGTvYr3jj=Oh^AQ|+pA5~q>ryw`QTGp{=L?(aHu4ib#=sle4Xo)rm> zknjm(eXm;Qy`CW80B{} z&q4aFfqam5jo$yIci*Ki@drP&ocDk6L(6%ue?JJjMt|)4-hF2qr7fh-6(Vi+qBqWa z5sXUbedK7J_k~C+V&rI@_aYdTp8CkqI`0dSR>a70wT7OZ_aYdTX8XuNf+HtlS`i~h z>%7;s(vTQYSLc1?Xr1?kNGoE{t@B<4qtbaFIa=p^A<~K%Ia=qv2u7vzK613q`$D7@ zF>EcUx>6KMvm5bFM?6&ypJ5M^S%<(W*<51 z`E^yDocAJZPIFbgSW#)Vj~pa8LL%LVk)w6q>spLT=Y8a8o%e-ED`Mnmo%bRbmCpOf z(K_!7kygaWVJo}q&|hj^i&5#kj~uP@ULz#ZiWoUs=e>w?)YW+(Ia=p^A<~M-9B1df z2u7vzo;l9W`$D7@F`w0q^Zt5Qu0yY@blyh}KiwPWeIe3{7&%(!y$D97^FDI4&ig{7 z6)|$O&U+DzN>6>{Xr1?kNRwgYxK`BJc`t%dX||6XBsg*+rp-Qbw9b27%T;U2@8dYG z&ilyGI`0dSR>YuN=e-C=w9flNq!lr8w9b1Gj7sNygv3Y9If-d5NSn>9If+S1f$Y-hhbXA?4 z_af4rsHimCM-CDkA>kd=6*j7?b>8b*j7sNy=^of8)FtagMs0?IVYY8|Qr?(u&9&XXm{LMzM!G zj%$vy^S%&iMT{J+^IjwA%J?(qzHQ^YFN94ZVbl`6ao&qy6#KS~^S%&iMT{KJcg}ke zjA9oSuHOf{Mqep=Hb+RL6)|#LJ)_~53$)VXhKo%e-E_hICaWAxT}FX9}v`nHYpz9DR* z8S`kJ_agk;+8M>ZZR5Nzgl#&mu#uy6-iu(=xo>No_k~C+VmzzXc`t%d?AtcZ`$D7@ zF>su110*B+`8tIa=qvaxjX0+s1ic zh%^~Sj@EfEf>G?kHqQG(q!lr8w9b1Gj5_yit@FMR={}4ct@B<4qu94?ocD!DD`Mnm zo%bRbb?)w3=Y1j4WEeSG=l%7r!hNME_H7&IeIe3{7&%(!y$D9JZ`(NU3z1gD$f14k z)_E_2QS8Dt&ig`m<-1 zXVp6IMKFqe+s1ich_oU`j@EfEf>Gzbt##fP!Yk72cRVZYgSXCm5$CAYw{4vF4G}i` zm`Cfp7vX(yMzL?(IPVLQR>a8BI`2g=>fE=r&ig{76)|$O&U+DzV&ArL-WMXRh>@dp z-iu%qyRg^?Z=LsrNRwgY@E+)@Iyvt}Fp7QK#(7_ev?4~1)_E_2QS93`&ig{76)|$O z&U+DzV&ArL-WMWGhLNLn-iu(=xo>No_k~FJVdSt~-gS6#-iu%q`?ihqz7RfPy23`C zx6XSJj5>FBt@FMR?DWENY#-#=d9N9!E8{!QecQ%)UkF=CY@_*J(HrNz2u86BI}V#L zZ=CmqNGoFGXr1>W7{xB^I9lg@A<~K%Ij)}3v-4gAqu95lXEX?okVyAo>9Oal-FX^xoc*$ecN%g&ig{7`!I5}&U+DzV&A5}^K2NQW0i1(L|PFeN9(*-4o0yH)1Nhvr`mP+ zPxP!fLLyCuk>hI5j*23|D4!}_ZR0CSf+Hl-eHb}f=e_2^DE4jP`hAjfJ8F<4B+`l) zIczg`9iE)`%E2i1ZSfVob>0^ut%#Asu5DM9S0b;)DE4g|=e=@}NGoFGuwDMfc`t%d z?AtcZ`$D7@F>4TIc=su3U%S$=J7TocD!DD`Mnmo%bRb z#l9`}!CU8jA<~K%Ia=qv2u86Bi+%9Pb?6%82#GWqMviMmg>Rb#qu95_KKNwHhHj3K zNcUmnXr1?(2cy`xZJhUoNGoFGXr1>W7{$JAhIQhFM?6$zRkpq^S%&i zMT{J+^IpU`YV~a!=Y2zj%|3Fp&U+Ew2WJ%fwvF??5NSo6&+68BFM?6*+hQN|DdTCL zGF+kl>XY#K!4)>nqOJ2@1f$ru#XjiM($hRGxk84gI9D`MpEiO+TTLFM4J7{$JA0^ut%#AMb>53ON3AYw z4TIan8MzISE*YB9Vog-9!6D!JP@dp-iu%qyReP(z7T0ej2x}=UIe4qw{4vFg-9!6eUKw0(ux>4TIaoTFp6E+#(7_eG#N&Y)_E_2QS95Y2E(__5fbS>9M7tA z-YW;A*tcz*_k~C+V&rI@_aYd@zHQ^YFGN}qBS-7J7s04=-_|K{@*i-UD(EXuN)-OiWoUs=e-C6KMvm5bFM?6*!ZyzPLZrzsa6KMvm5bFM?6*!ZyzPLZrzsa$J4eQBk}Wqu94a4cG?k zHqQG(q!lr8w9b1Gj5>FBt@FMRX+?}2t@HkRSFXbkD~es%#(7_ev?4~1)_E_2QS93` z&ig{76)|$O&U+DzVi&e?-WMWGhLNLn-iu%q`?jpX@NIL1L|PFeN9(*-4o0zW+c@tF zkygaW(K_!%Fp7QK#(7_ev?4~1)_E_2QRlv`b>0`kE7I%Nt5Sc>%1>Sx(_2q>%13nj#_=&#(Ccm zVWWv0t@B=l_rV$EUDQ=IcIVc4Ux+jrMvm5bFM?6*+w^VkocD!DD`Mnmo%bRb#l9_E zzZV;6zwS4E(E~?Fq!lr8w9b3wU=+Ksjq|<`X)=r)t@B<4qu94a4cG?-HqQG(q!lr8w9b1GjAGxmao!gqt%#AMb>53$6#KS~ z^S%&iMT{J+^Iim_&fQ(>ye~vr5hF+IyuaR+>+nz%`?ihqz7Xj?j2x}=UIe4qw{4vF zg-9!6R%ugXJ>g>E1!6^1^XM!Un(tQ{?TIaoTFp7QK#(7_e zv?4~1)_E_2QS93`&ig{7$uM%X&U+DzI(K2M^S%)2K8zf#^IpU`YV~a!=Y2y&g+-3m zc`w5I;EZD5wsGDUB29*oqjlbkU=;hd*avT&_k~FJVdQ9?_aYd@zHQ^YFGN}qBS-7J z7r`iYVH@XtA<~K%Ia=qv2u87Q%d==yEk{VC6)|$O&U@ux6#KS~^S%&iMT{J+^Iim_ z*tcz*_k~E4VdQ9?_aYd@zHQ^YFGN}qBZuwsH_m$zjA9qIao!gqt%#AMb>53$)VaHB zo%e-cr1rnqu95F z>-S#H?faMLS#g9!S`i~h>%3PEMzL?(IPVLQR>a8BI`2g=>fE=r&ig{76)|$O&U+E( zsMWV^oc9e8Hv7oYI`2hzADmI_+rstxXxFGM$LEnnq!lr8w9b3wU=+Ksjq|<`X+?}2 zt@B<4qu95F>-XY1bPaNZM7j?nN9(*-4o0zWJC4?QUx+jrMvkjJJ1UCTVifzfjq_eP zNTd}paa8BI`2g=>fGJ=u5O(7g-9!6a8BI`2g= zihbM0d0&XMB1VqZc`t%d?AtcZ`$D7@F>4TIap)ic##_HqQG(q!lr8w9b1GjAGxmao!gqt%#AMb>53$6#KU9 ziXMH2;|PhgB1R6M_*{pTU=;hdjq_f2MIx<;k)w6qi(u5byYpRXAH3=ANU+lzcE=m% zy|Sle>Ko5}+s1ici1bH^-Z<|?Fp7O!xPEV)_k~F3Q{-r!_aYd@E-YNX_jZk*4EBXc z=TqdM!JgM*6uYqWj7AQQkVxlKGzbt##fPBK=X3qjlbkI7h86Y~#Fdh_Km5j@EfE!u#NiV&4|7-xur}{nheR zpGOvv{;0^&I`5T(QS8FP_51iGU;p-4R~#Xc{;0^&I`5T(QS95o^?U2QFGM<@B1h}I z7r`iYVfybTzWrqvIk#gT93hd;r|~{I=e=?;%BM%3PE zMzL?x-v{vH&)z!k3z3$n$k96QMKFqe+s1ici1bHAj@EfEf>G?-VmG*T-WMYMQIVr{ z-iu%q`?ihqz7Xk;iX5%;UIe4g-CgUvFGTvIB1h}IzuuLr>WzwG-?nky7b5*pk)w6q zi(nM{wvF??5MD8^7vG_F1Fb~Y;g@Q)^ID8z7q)TUD+dX$eAmm!ajmG!tSDEmYmHIt z+hQMd4Fc*$eOv5`W^FVo%bTnQLAs;IPV)GZ1ypa)_E_&`{0aX-?nky7a|SBk)w6q zi(nM{wvF??5I%9Z!p5^|o%bRb#lCIhyf1`LPHSDY&U+DzViy+s;Jx<2s1J^i@Ck6$ zhj+ADQ6w0}zAew9k%J>7d@fye-a79!4@R+Xi+%9cd0z;h$k+F(b>53$6uYpE^S%)7 zEL>sZowv?=5sYFNHo79$q0ev}A(1}eSi7zBUO5=WE^OnxFGTu;BZv0ETj#w9MxDF6 z)_GqDc6uA*{FDkRbzn&$QG2n-{;X5Pn;AL z6*+mRSj8Y9Cpk;0igMN(F|Eg9kf4Gll`Y@9R#Y@mp@JAuKtR2kmc&NzN~OfA9ru{e znDc(-yY?U7b@?&Iy~dh{-x_ni?(h9g#Dnj6^1RQv+V#8-;yi2gl3Ve--yzZyG;8d7 z-UmUCsx0@CTk*V~2%JyT^FC|rdfo@&EccRI@w}gi?q;7gc0KQdaF#p6t$5x~1WvSL zU*UF(hb{W>vz+D5&|RmKaKr?Tx~Z2O2d=&7kQyeO0`}yV>XL?t0z_;VgHb zTk*V~i0)>eHFiDkgK(C+&#idgPegaK&l{@eFySn|N{q49FyV*^=819j&Uw}IK4#Zh ztT*f4YV3O6PegaK&vEQ}-Us2V^PfiUdfrb2J2JiEv&OFHeGuna<7bPv;(5PAq{6bs zuIGIabk54+1b`0PTv=yB-OWD7vFmvsgtIu2jeWK2 zc|Q?!g0Zhor@q{~ewMR14Gw*naKuD+v(ItRHBl8hH{mSK!9(XJ&LYt%OLuhUp>w)F zs-lJoXK^}5ZEej>IAVem#`s?CdfvzEI?F$e%+7g<4(}Fk<%o&yW}kDl>v1 ze{Td%%CCOo@VuXiaAyM=&MMFQRs-VhK|Cnl$`KRgir8x0`0g)1 z;{N`CiEvhV-nSa}2;#j#+!#LSj+iJX!&c+H;WNsgyG?|%%GtivFyY73DVY&0&ePm395c1<{|JnvhL8-sXe z5UijhCdw7D)%d;GA%7fu>s1rstn$2XHE_ITH?k8QF;T9Ftp;;+eK?2yP1G=Pp4B|> zTaC{P;$woiK1V(xGl3gTuW`9Y(48x*JnvhLdxZmWz14YS5ao*4YJ~pQ8o3E)mFIn{ zfrBdq8g#@&xgxe2xHY3HR?x(GR`a}XH9~($v|TbHCdw7D)xdQc9il<}s8KG@a#nfX zw;G|p4IQFEN6v_on|-ShirPwpCdxaJta7$L)ezx`iSj;dH9~(II%I#Da8`NVw;G|p z4IQFEM@*C}VyhAQ+t4AiYrT3OZtA<=nxJ1Sj`rwF|C|ATrhyGS{SYJ5ii)T5DHDYyJjnLnU4(lsg z5fkN#*lL9SR&C8*zxRk6X#jY^S;#x{n6F7 z(Fa@gnLsbS2A%T?K_9HF^1N>~LVtAUe5>=wAj%c7)!-ajBRAo!^1N>~IEO-@K}SrK zD`Km`ITTf~f+o(hn&*A1!8sJ7?UE5OQLc!s2Io+8*!tigoK>Fptp?{%bchBWIU`P< z_pJs!5LKZ;6Xl&qRyo_BYKU;eM7bii8k|GXAsRH{tn$2XH8_W&Lp11!iE>43H8_W& zLuS{6v&!?n)!-b84p~7*Oq45PtHC)G9il-K&MMFQRwMS*5gnpIM@*C}VynT44;`XG z6X#jYv9Q$$H677m)8L4hC|AT*1A?`f31^k(eXGG+p~HGBR7J#uZ+dZ8d-tP{5B;$C zuiHNSIR{6|5#uQr%e{RI3;&NGzB-8S2*ME)IEmm!1HCNIz2ny(zvrXgba>1}ILo)N z`2D*M)`A? z2xs{gwk#$bF;U)!t;Pf6js7CujJGo3EZ@Sy7dZ$_Ti~nxv@vpqNLl8Gc4d3Wy0ymmg<3peD%F8_hy0Ux=3!k5GKCQPpj|`%` z4_l4U---?yxd~_a78bvQE{K|4M@*C}VyhAQThSpaXu?^(g)K|yZ$*df5=Tsw_hG9M z`rFuvGvO@X!j>iUx1mFJyCWvb$*|Q3MQx=)6VCE2EH&5(M@*FWVXG1P+t49zWx`p$ zg)K{rdP9e3&=C{meb{P*{x)>TT$yl|Z(++4`rFVUE9i)cax!c+Vux(#5Dl7emTzIp z68hWFAv@6#6XlB7YQ#?8(BVut%eSy)2{mo#5DhwFqFfPM4G45N6VCE2Y*~0KbXaeN zs_3aE$`!HI2>os7a3-APdt3Iw4IS3(qAF^bVBXM6s}cI!&|$4$5zg{0Ec@Vw4r`a7 zLu!~{{n1OS!A?YnGvO@X!ms-lL8ax!c+P8!_kgMOB?cnUF|)HRrdBPPoG zu+<3tZRoJR4D~E$`4*Oakgv~%1|2cMJTb0TBlNeTL*~kavsfe6y^SOEx1vK<&=C`? zH|x`Cg#P$aZ|o8i&SH16e_M^v---^|iH?{kSHxB$^hd|JLY!xfTUho%y4qHKux@lS zfnHjT&>x-i3PB&NEZ@Si57M3Ut?;$_@+~a;;4%7O?si8^l=oq)aXMM1 zqD(l;x3GQ|O~Mfq<$c&{a1KR>XwZbSd<)Ayc#J-n8g#@&xgxe2oI}web7jI=zJ+BU zJfcHZ&=C{mWY}tOQbLDl(1f#m3(G!uM2GA|M@(?vK`*UF?DQi#oC#<77M6YR7=19i znjgAR3$a^gJ_APAR^L{39 zCBcmbdf)RN!dbqB?R(zOM0p>!8hf7i5YF-~Y}xg^pNVosY&A|kqv^NpXF1Eau@s6^StM+oaI|seA~lod-lAaiE>43HTFF3A)Mt~*uLleOq45PtAW?{?0FC2 ztn*tK#O!%L6XlB7YV3L5L!4)gTiCwm{T_iEO{=lzc@IG!tSr6?sH*+%cx~e~iqGhI zWDw`tY7W>K(6XlB7YV3L5^DJli7M9&$Lxw0&z|?x zaF%aj`=0kRQLc!s#-8UrgtL4Li=RO5c;3%Mc^|eKd!G08R_Kr{W*r^!zwdkA&qTQ* zwiZ(-R7uXx_iM7bii8Yc~IIN1AH&hjm+YcL5% zOqBOwtFh;K&s#amx3KJkTlB&0o$*$Vm?&4oR%6feo*K^bEo|TOekRHlvDLt9yIk4* zEN7kH!XRePduo^{SHxCh&+{JQJZs#-_C4?S2o%<8?0Mcp&<88ax3GQB`43HTFF3A)Mt~*uLleOq45P ztFh;K58*7|!unY>HRy43dulk#x3GQB`N^LyK#=lx8SlVPi|=Xnoto;B`m`=0lEL@KQM;1$n%2>M`U`QEng zc|Q~7irB`n=Xnp|EZ^JqJ@03tToGH1J!8hf7iyp^+jZ`=30pNVosY&G^g?;)J!d)vO} z{Y;cAVym&|c@N<%-`n;*?`NW15nGKt&wB`G`QEngc|Q~7ir8xGdEP@f>-=`N=XpO9 zzUl3I-c!B2GM;+J^LyLA=lx8SH$8Ox_M{!pdkAOw-nQ>~KNIDO*lO%~-a|Oc_qKh{ z`Q6^x9xl0&qTQ*wil(eb4(n0ymmgW6$#*f<9PTzPIgr z-p|CtPp*iq#-8UrgtL5a+xNVmiE>43HTFF3A)MuV+rH=hOqBOwtFh;K58*7|!uCDy zXQEsYTa7)>dkAOw-j*7?;(0$4<%-y9?0McpILr68eb4)uC|AT*W6$#*!dbqz?R(zO zM7bii8hf7i5YF#gcWXQEsYTa7)>`+6&MNS5zy`=0kRQLc!s#-8UrgtL5a+xNVmiE>43HTFF3 zA)Mt~*uLleOq45PtFh;K58*7|+qwqNJnv_syboKAJdkAOw-nQ>~KNIDO*lO%~-a|Oc_qKh{`dkAOw-nQ>~KNIDO*lO%~-a|Oc z_qKh{`3s`w?BOCV;^{QqmXtT!I`GZW78y)Ax2lL$vlbnnBgald$@`^KAnWxSOMXZhY1{|!qJ zcMReYK{#Tfdmm*M+LzOI%1-`B4&-7Vux(8Q`jXYoOOP0 zyEzDUBRkO%6WtXtYkcw--~ZxqFT4HEA zM?hDW?`_NSnL*TBoks@Iy$`cS=x?o&n{bxzZOan+ThSr2>xhZ&ikLM*e=9m<1x+~1 z_qJsT{jIf295KKox3Ksfzd@iwH0X$l?uwW- zAkg7VIP3g&$6KMpdMi{#Pc_k95wk|T|(OnUZo*ldC29_{4<4cq z=IlCRqPrqy4bGwHkQFrHEZ^I*4{}<{UE+v|?uwW-IESJ`_LT`|`QDa&@DP14_2Gz# z?qrxXPAAJNgtL5a>u1p<95Kg6P;`g}O*qTqM0Z8Z8k|GXAsRH{EZ^JOtq2{WK}Sq<@58JSJN<|bXTn*&w`CtZ zMjyzikLM*e@AqPYE3xHcewcN#z90M%f#Bro)e4d)LJWzqPqL zqNF9NmsiFwed=;=-@=yVp9k?{C&CdExRT&T1HCNIyL{c@6;HkAff^>9_!MjOq45PtMOeA zx#8kBKK~C7A2bo?S>qPAEZ-W$TY~tz7`bnBGl3gTtMNS#x#4n;fUYdx!j|P>LDXBF zM+Q;ehpk48{IW)F!dbqBg-31>HM@?ODDT5oBlNeTLuS{6vwRC%meAjd4%sD+m?&4o zRwMMcqQjYRmTzIp68c-wA-mlX6Xku_YJ{TJ(x3@v`4*NM?1UpG%KNa@2>q?-khe17 zEZ@SGCG@wVLq_h1iE>43H9~(YI-Ch-`4+Y;p}!R!vVxA7C|AT*BX-DIUuqN1@+~a8 z!CKwG5fkN#*lNU1U(q2NG~q1Y!j>h}w4y^a=!l7OMQk-7(BVut%eS!T=Ru&udMi}L zSH?uSBDNZ#KSqAZ?D|>G@+~a;AhVl~~;5FPSX&hjlR`{0TWYnPzI znJ6d2RwMMcqQjYRmTzI%2Um1hyB$?g!$i3vwi+i5uJl1a%UL{y7*FaNOu`Wp<$c&{ zg#K1^SYL*Ema}{d%RacGLq_h1iE>43H9~(YI-Ch-u|}+J8%OAGMThkjt%!+oMQk-r zU+OD_v)G;NxmM%U4U%xgM7bii8lgWr&dP2#ah^49Vc7@iYHRhuy3x%9dTBL6e{{|( z1bwiwd<)AyNO#V+I*$yZToGFhzC7rV*)`!T-@>vFa>_`;5fhvrP*|(MITRgI!-TVZ z3(G!uh(4IR#1Rwair8v!4n>FTD-+K0EiC)sA^KqMc1KK%#{ge`4*Oa@PH0kK}Sq* zPe3oN1}CNZQk!s=Z(;pbl;3toOqBOws}Vc>fDX~131|5hmVNLLeK5P4BPPlfvDFCu z9nc}FHQ_93qn-9G;jN+%W_NbPgzs(3^0x1I*5P|!{@ja4+_Skmq9m%9%hb<*%K0s9 zS^hML9}42(LHK@VqWq(v!)xoh#~!}w-@NMz;Vj?6mgQX^{Mf@k3gR20h9f4*^QqN% z*jpZa_{HzL{b44Y#ja%cx7mG05N{5GaX4b4JfB*PXMOn12mZ{2vv@vFYc)(bVxl~s zT8-Do8~qRQX4Ej@EZ@SG<(42G90VhG#6-D7wHkMinf>FK;hAujZ(+;w#X)>ftRipa zh>7x#YBgRMJLJz|r_6-2*lX;@HdoINg5AhYbi_pYN3|O7ebg;C-}uDmTp`Z0#w{#7 za=-nSn?F8?Z;Bee(ai)tZm0El)GgQc2$9WuL)m?;0KRwMLxi4JGNS-yoWOX%+s9kNRtF;SjRtw!i?MTaxt zEV|9mN9b=whrE>|Cd%`v)d)qcr9l(U@+~a>t&9jqOqAzSs}cHJ(IIbT!dbqBElcQc zMTd;s5fkMS)oO(PR&+QM&hjm6Swep+I^?Y!F;Om2tw!i?MTaxtEZ@Si8?5LM4LV|? z{G(cp(BFy*gN~Re|EN|2;`O1!nQ)eGVapQwThU>?6{Bq=x`>S<$GK9!4)0W?AH0iMEOUx8lk@x9nOTad<)AyxT3?_CFqcGm|*?UOREw3 zThZZ6ILo)N_zmMhphMou5fkiV^wMga6m^Ag7TV-#?R#ay5feP0zqcBpzZD(wRwkU~ zTUhqN6&*5iM@%qJjH}fM{avENnQ#`XI&Kr8ze{w;TRCEa?<4EeYJ~nS(cw%ui`~io zZF3d+qZ_R3L`O{UooAo58lk^y=x`>^v&Jnf`ygFytv*;cx|u*Pr}YSp?-BID%JMBN z`{2#!kheOI41&Hp#=$wXMsC7czJ)Cd=g{bbIlGRS;QTPwgL5c4WIaqc%eS!XgBQ^U zbC)<`f^*Q=SDZu9A^XaNvpCxgeQ*v%hrE>|COFRxeb56@)l4{xK8tp`20P)13C^WM z=bS^)AvH`m%eS!XgNNvYIdVr#aK0YjE6$&y?g{9n?Oo2H z=x`>Scj2oRh!?Ju;5N|&bj+nr) zGCid8KKPD*_mazh@{{+^8YZ0O&Je%zOoSsQ(rX(p?5y#eXFdIrKa9hKv)mct-#d$N z#6|!ddPN%ktYne8Guu z#6)+q&v88U2XDFd5ug5ZS;K_0&O5`?gShR9aKyxe?|AaO&l*4QzW2ZOwlDd`tYP9j zYjlQX`Nkmbej?muW+FX7v&L)Q_x_vq2gToAH3z} z8o3E)xic)wlY*$(b;Lw>v(Fl#zYBE8nwxNzJ41MY27wMC95I0t?buhb6EA8fnsAmo zL+;&++U<^*z)?5#lH&+PU6ck*ILngBF9Wl|}?6XEF_5$TH4inCDFNvF1 z5GWVI5fk0bK5Iar+?jCJd5;RkUZC81D|ASQG(kNS*1n>l*b9_96V77RQCsV^q1X$Q z3*m@~?q;9k2*qBY+?j9|y9c$k8ll(=lnddA33g9h=Li+N&JT8-29DhWqSFi(uDcg_ox zOAQmwV!c`2RwER9fpQ@nG11-Za~#n*`LsoJ z4tXmR=UL-ti`hBpgGu=3lrxcf$#I1K=(Se}=*psNk8ye+Z{2{-RyH5bWK!64HM4dR6BHT;w)00_wigh^U!&`5vTC1VZvFQ&d2wP^Fk4h znBaslzE_-FqjP2r6VBppKEAu0T+tyTcf>?@v(LHWY=sVI!dd)`p}NGfHNNPXFSxwhlfV1g`@Z)4K4_x5+2=T3@Q+?`xjyZ!*FGdp8Ge?t zd^cQ{w}!jp8^byDPfqTR>56!p+YitC>ux_h@8f@O1ir{G2m%L5oI~F*5#9SR=s5d? zOC|o!KRyx8YJQjR$S1|`lnvr;L40=jH9BIVdmm@t@<3?iz2#Tbby7hnaP9w$BBkK0An~2f+$DVxl`4W)1vn-xhm| zU1Gvn>@_?(TaDij;*WxOR}hYv=-!7}1Bcj;3Rlm!O~iTD$=N=~@wq4BJwec4m*vm1 z`b^*;b6wTAq{d7@R~A0QV;oT<3Et{FGKlVEm^DIwD>_7jCY;rM>T?|Uu|hDrj+nqv z3%#^);46y`SwR!$StpFBY6W#mJH7;kuS=2^5?OSrHaanIw5fjuy zFKx|3O&dBygMOB?m_xMFYCxbvH0X#4<_*2H8lk@p9o7ogvz*oTLO9#!T;a%$4$+_^ zCb}zP&J{lK=#V~W!dcy?K5O94jSg$KqbjPKU>~EGHja~`Hu|8S_7jj+kKIvd>zL=!0~etvXIU z>pbh^d7pE2>QUS1YOVTAr1xRY)v4EBA?SmZMc1y{%W~?q`BvwVL3Ag>tid@HRiQx> z&fEopr3V~b@Hjtx#Ap(4qG1_5fk0XFl&VVj_9!M z#6dW#`_yL*&Y|d#-R{U4QJ(i%gC2;g(4dL#cNkgSr#@?#aKr>1bm*LOC_3b=OgO9i z)Mt&*-w_>-Q+WH5nc%#DUfSN}9EuLnpr7R|&Y|_K%szNThpeC@COG$u?=I(1bjU6- z;VjN?)g_jNb0|7QgN~T!-iNs!p}!+KM1v;Ivrf+TIad(quxW5aOmrth*En^~K{$)r zXs3NkPBkv-ttw)odmmyi>e@-0iXTn+R%5m!Z z^C0dY#6zQoBPP0&Vb=JH@Vn>F!zaR7JfEkvahPz#ME5?-8V`s!;>{iwHB2~*d16*t z4T%55=!0;?M0Z8Z8qbZHeSXaFOgM{G9k+=W1o7-3UKlkTG0|NSvj)!DPl}x~6V76< zu^Zbs!aw@()F9Z2j+p4Kh*{$U!vFKOk9^`4;yi2I!kQ27?SuHLsNoykOyEZIl&pb| z=^g=HS#;4cjz0|_(|W7($RN7+Vb%!!t>}=En{XCix3M0fzZD%ayN;OXu83J9^tYlz zG-$$Ee5J>}3jM9orT!_&x%aF%aj%M$wA&|%GP zoj*);SH!Fl`rFVU8uYWAK9VeOJSN15oZh*=}_mk#zb;Vky_IQ6mH(IFai z#6)*8%o-;}ZS+AC&f@vRdLKl!NjPGndmmvrh4Go%b7PG;8^**?vLq_h1iSB)v zH9~(YI-Ch-v8t?9s}cHJ(cufDh9f4rlVR4tIU60$gtORd<8~MNThU>4gNm5wu83J9 z^hd|JLY!xfTUho%y4qHKux@lSfnItayx1e?gO$a1q~13Eo9)nez14YS5Zx6q$C2mI z)5uLYi|^rB56+?JklA&_M0Z8Z8k|GXAsRH{EZ@Sy-yjHd$S!fjM0Z8Z8k|E@hZEr} z`qR({=TLS#8g#@&cSXz^^uSV-31`t~ht5qnVxoH=W{r5GBRWKbCY;52p}tDl2a{l~ z95K;d5wiy8P;@vG&hjlR``{5BvgVGM=&p!agL5c4oC#<77M6YRhz`-9BPO^Zp_itQ z*y%@fI1|qDEiC&We)QSZ95K;d5px`&zhm^l?3^Z?#oLa4&Re0wdaH_<@J%n=HvgNi zKfWPcj<5fhZ#g*9y)yplhT(aiZw2xCAZ{0g?`I~un|;vB^6iiMisMT!UY9jYILo)N z`0wF@_@9HgP1JD2M0Z8Z8aLnNaQw_WU3dJ*iEx&0Ve#{;AU-vSI|t#2iSCM+HC}nA zPdoDGP7~oQ-@=x~gd--pD`M98w0NU?#GCO}CY^5QiWbxg#dJD`M98XEC$P zFtcmIS-yoW3k0jkE^)*}cSXz^>?w8%yTpXE&TnBwP{R=u-4!uwJpWIA^5Q>-tLJSe z;yi2I!j|QSgLrQc|1b#O=w>3_?6bxXgoFJa0bN;q70^!mGQ2d1daLuuAi67J&DF|W zF>({m@-1vxLVrmxyN;OXu83J9^taXunsAnHVapQwTWgm%VxqeuW{uF_h7Q?@CY?@Ma&wZsI4?;!dbqBr3O3Uh>7lfm^DIw8#?5zOgPK8uw@DTZRn7Z zJ7S`{B4&-4*$q{pK@-mMEiAvHNw7;CG0|NSvqtQx4OOvAOgPK8uabXdCtRZ+u4cSXz^p}!3s)=n(K zS-yp3AKcJk?RHc}4HMnTFl(GNxX}mwENAf)V(pt~!VweQ`!H*S{x)>TTbXbcV`IKr zjnLnQ4(sbv5fj}NF>8eW_`+?>uAk*B)`)d)H6U0;R?ra>-4!uwg#P$aZ}p|FXE}?# z#{O+JilBxgCb}zP)(HL4aW;0liSw*+3(G!8SKF!&){Sl^(90vUM(B^ud4-@4R+evJ z%M$vdJLg-SM+VVd5o@kEGvw@=aF%aj*$0zgb{#R%T@kYe=g?X~6VCE2Ec+m*rQ9Ws znCPyES%Y&ZI%FrBaF%aj*$0o&2XnVOVxl`4W(|5EszQS%oaI|sKZ_>eh>7lfm^C?uwW-Vy7R`AsRH{EZ@Si4<4frW><5>M0Z8Z8lk@zn%zZ`4+Y;Hw5vdAg%@Bh>3DVY&E{&Z|`*c^|!w#$6>-*zJ*1v z4dPFO_+O)jBPPlfvDJ9{lWuq9&reT;vwRDSe@iC95fkN#*lPS?ywPLg&8T6*S-yoW z%Nv4tco3|hBPPlfvDJ7&%q%m^?3!?vZ(+*T$Q?0Ju86Hh%b1H*`1?&hjlR&WS;wLp11!i64Dc{G07i zSgQen4rjtyzJir8v| z{x)=2D_DfH*b8Wq%5fkN#*lL9SHgw21{48hr7M6W*Lx*V45fkN#*lL_K zxRpN8A@A!f{x_c1#$mz{6XlB7YJ~n)bVv;o&SEwgW2+JRThSpScf>@wBDNZ#KfZ7q zvunaxtP$(pYCxdF`ifS>M7bii8lgYF)Em3R&vF*Kll|LjK(HGbha)D+6|vO_{n2r* z5a(Ir7M6XGuC`SltQ*}-pqEx7^hf8sLZH&h@+~a;Al*6N>O3-taz$)4IEU8AO*qT9 zuiE>43H8?4uDl}-qS-yp}TM-1~aKuEpBDNZ_(~szI zCYAj6Rs%*%1@Iw=K&j-{mgHzy7tG z4nOqD8;_23M~we)!@YeATbBPih}-@8O^5Fb!VweQ`!MKb`LsvG&ob`&(!+Bn!dbqB zEz2hc@smNkI0#2fbnnBg@w^w^?)cD;c;n$k6X7i1!s7q$9K;s|@nb~y~6VCE2Ec|POctH@1+z}Jq$uMiYEN1o& zF~iKR31|5h7Qf>+h))lK6?DWzcQVWx9~wL4j@cCc2YhjwAH9qC-~DgtL4LTb9t@ ziVoQ&j+nqp4862*g#K1^$WAojEZ@SyUo8l9$ZmJUM0YaGafG6_(x3@v`4*NM?1UpG zx|3nn2>os7khe17EZ@SGCG@wULq_h1iSA^WH9~(II%IZDILo)N@FfcZ9kPOsn85uD zy|ncR{cWgj>O zIyB)d-@@X*_Xz?WqCrPYP!GMdxeEPl=&;6t4(YA< z=&)9>2xs{gmVIzThqX&k6*Ww-{^+IE2>os7uy$e*&hjlR`{0HSYqz5+YMAKWhq)dn z4Q}*7Kg(G>g&0rj8cf0w6Wz%$YlQw*bXZ@8dX}>o8}rp_g#K1^SYMxtm|&h5SDUNQ z---_F3s;1*SR>ZG)d>Bq=&-(`6*0kjvp%gx=x;@b^`$PtS?o1-X{!N&4yzkf#02}6 zo!M%H{w~qsOq^$pTUho%y4pr(^NnsM&`YZk`lEARA)qVEx3KJk7w8ZTo<|1JoeXo$ zIftS{#$m!)zJ+BUJVYPN*>%JO-@~yUoI}weD`>)5zJ+BUJVYPNUE+v|?qrzb;2eq$ z*@-5cvF z9?>Bqcfenc*Q$ket7ysILo)NxJL!?x*#4Kgd--p z_hHt!>8@`)@aJ(8;Vj?6mc@i4Cc2Yh)>z|>9ujZHTbXbc^Te#Qxq4L)_X>iMJ7S_c z8D@rFgLqQZ@QrRJ(m^I`{PCCE|8kFj zt}MO^V;t`e;+IZubsiZ6PE=zYp})08Zo*ld2F7}X{#JCz>^fqiI~nFULVqhdoC#;~ zl^**l^taY7al}OTKFk`SzZD&_6HPeFx3Fai{jKPb-R_8q?qrxXLQ!jJ(1f#m3rh`l z!VwcVsG*m(uR?z-I^?ZPIEz!|_+EwnR&>b79Wl|p4|5zbvl}`@gC?BCDF(GQeT4ot zbjS)iVgk=K^wP!=`rA;|OgPK8uw{u|m;@Sh#6)*8%yESNHgq@>&hjm6Swc-4Iz)qx znCRYzSpxzc&V;jkZwpV>AkbmGRrPHX)I%?At{6EwoC#+!>!_`*N9b=uhc&wuF~Pi{ zmsTV6x1qzCa29)EoR-)n=&*K4MND*8#GI?p---@vCl=u>-@>vFuIR9KJE~%YCfLX5 zrH$jH!IeJfXE}?f5NmT~!VwcZpTD;np}!R!)|a84(zZD(U*QX*Ty7ytu zRp^f|+{WzsSJ--8pV|5bQ>Fq9Z2Qx9qc4 zBlLHP4rk&#Yuv)J57O1P>VtKon~Bs*&Q<7-&UuBP4_20MVc|I$1Ulrc&Le}M?~ZYB z4y}=!aF%aj@jI}CK!?n(BPRGBj`iRiiVkPOS$x-P_r&j~4x)C6BPP0&Va^rjP;|&n zG~q1Y!ma2DsD`ntw%3k?DtvVxA7=uU=NgL5dVnh9t57M6W5 z3HGidCOE&1{=qpE9nOTad<)Ayc#J-nUCj{_-N`V=5&Ao#LsVQA@uxQo&-;9 z$Nx9{HLp87@JaVPP{V|?d<$EazY5~fLEJqEM@)3@!>sXFZ+P|LqnGcxLO9E}u=pK9 zLA?3zo_x4DYB*v7XBRwY+BkmqsV_b7=VBt9g}QiJn_Ux*nCMQ1IgWS58~uK~8E<96 zS-yoW%Lm4&|4R_el_Ms)_hHs}WX$aU8#6o;&f;swTD5U}T@Zf~1S{x>3D%qSX>)bo z*dgqcnQ#`nklom7K(HGj95K%3iSB)vH9~(YI-Ch-aXK6N2>q?-klpTx30#`cOV{99 z8Z_Z7x+dD`8tjB4CUBb?IuHG==#aNE;Vj?6mL>GJqC-aRh>7lfm~$2SThZZ6IEzyZ zYHQ;N{jKPb6?DWz_dd)Tu|rl=H51O_GS#hykxZ5*M$6&==YuZRiu zak`~tjnE&8TIqv+ma}*Yu~x%`BPMu0e{XXY`diUqeHrRm&hjlR`{0TW8Mz}Sy7ys@ zBlNeT!_%!hVuF3kK5I2X ze{`HH#Cg`Zg=HV4tL4ajqnnBJKFqla{n0tE5YUyycVvts^hbBjw>pmuqB|L84bGu8 zaud$-Eo@mhht}*mVuJI-SP#yj=#bep;Vj?6vJW1j59Y`nG0~k2a~zyQ(INZFgtO>R zwWnh}qT8TDcDo}c=ubl*^uW@f31`t~OU=t-!Vwen*`agJq3DpeGT|)W!m7kJl{Fsq&Icd9`UST?%!ISpmE+X+yda(!1mkeT zM0bhG8jrvJ<^z9b!dX0@r?t5<;fRUu`II#t6L0k5cr$94aF%aj%kr=wz9k4o?ud!* z`II%D9W(nIF~c+AEY_RVZR7aiApTAlQkH znCPBQS>tyecgxKm_tfWHAGZxDa?l;<37i5kAq%>-_3Kc6-J`QvW62JtHs z0bN;q6;M^1tB?K8Tdvhxoks@IU81r^=ZR4%sD+nCLE1StInfqQjYR7Tsp(BlNeTL*B{}6W#MEYlNcK(x3@v z(KUz8O*mqrdp>22(BFy}=Q=!l8#`II$cr?2R6CYZrwu$Z^l{G?tD>|GBXEE#Jl)>zx!&y_Az>C zHBO4ULO6@(^R%|FOgLhK=kxbgBlNeTL*B}SvwRE7KDeSoM(&6S=818&8lk^SbT|{v zVpYd&BJ_8O4tXm_Oz?eVeOissA7AP#gtOS4<8~MNyF`cVL`O{UooAo58lgWr&K2T3 zYuv)J57O1v>VtKon+f#NYJ~pioNM*LBItva%ln`9kPNZoaI|s_Q8wjgSkr_F~K=#?5oh<0UffhOgM}F zH1rYrJD@|}$`KQs=Y~G$fv9RGoJF4NAp1oYDOZtRc)I-Ch-`4+Y;oI}weJJAsn z+;`ARtHFs69nOTad<)Ayc!)lD4GlVCqPqrHA3UH#G-$$E=eIlF3LVy4Ri`)Md)u@1qlO7*xic&a zqb}ksQl9tmT;_>!wQ+oU%;b zFyXB8&hX|S-hLt+G4bF#o;>ff#zWuw{@32?>EY@b<1lfaH9AB5cK|_r-HC9QnTd4x z%o@*q>-%roBcLnGogx0+L=ZQfYMe&~fm1LJpKU$f^7LD7u92H?mODfIexD#}b{#R% zz3Fotp}z}s$XuClmOI0;g#IqjA%r6)aH1XiDt6*U?L-sKa%YI&<0Zlo6FBOoUUD3v zsEg8|31_)8qy{_Th>3L0?mCY#T-2ArgtOck@>_CIUmr(I;BY*?SE0WPbja+QaF#nm z{G2)nbO_yBGI<*~L5m;j6FxANIVD zh_l>FmgTRX{R;=l531_i;P+O}JioHO&5RRB&_oRn()?l}z+?j9|DnM06RDOgM{qVpdv>)AuR~M@%qJjH`Ff3zW-TnQ#{C&FZ!q zq1X$Q3*m@~?oFTLh|bBk{R-hMb|?F{)rihX|470S6YN{|SsO>_?@;Ve!cV?9ED zoJ*2$#6{U5!~~sS>??W)s+tLBaT*-@IGq!daKuD+ zv(ItRHBl8cOgM{E?a;Z2vq*W~$8+h-L+3FD&eU1MgtIuEkM9*keSI7;!3kr0uQ<6z z=gb-=oW7k^pL5083LVabv-lZ9b&2>*IzgaA2uDnC;v4-V^mmC4 zXTn+j*<$v=%jkniIAWrE)8{xsf0yWx8YY~@+oHDiE#c&f4(qKdVuE_3pEGiFI1|od z*3nL@@gt9Z!R6oo*6+UdNe`BTeY~%U?q;9kc-3uRae31>z4hAX+w(pm&hp(b)}#4B z9zN*g)tIh`cfQT=y#Msu4A1-c-y87<;Whf|H_G#VBJdtbcdnq9#_#U+3ySI&<9L}v%2Sf);Rfd;#8TAo;ZiTAtEMl zc1gFitnuFP8RgI2Cc;@fg*rSbe%2?#ku#!P5wph0FZK92QNsjp0o6u(^1RO)e;K3x z+!+0r#mKvZeMC%j@58Kt?<;QR%&rM%b)WjIabpnA41yJO#02Zj`m{Ivz1Sgt9DD0k z6X7iO8Xlc(uJEsAH?k8QF@Z-*x(Vhun4{~%IrML$hKcj6le2w}}m>{mtk&nns z;2_h+5j8IN2)c7+;gveZajziitom&ceVx^P>a)hlr#dz0 z$Qe)K(fa@hoNGk6mg`4R*p26Sz$cou7QeQ-da))%?WYaaxbi--Zs+pd%)_ z_hF6$7iDzF?3!>E4$i2pt$FBgLx-%OBPMYF8sFW}--Zs+pb2N;QC;8s{I=ucp54F^ z6S$bAS5l56cKU`6(V&U*tdp~Su6d|wLx)X+BVwX^A7%{*bT|{vqIP-~XARy89oAb_ z#02%wOWV7lzYQJo_3^Wu#T=&ha@K%AhiK3d6U-ZWX*EKB8#=5NtYC;g~Pp*IBF) ztJ}sA`diUqeMKu`g7s#7T8+@(iVo4BpXDreCws2d2>tPG-`I(cm|)+s&svStM(lWY zyNUCxljnWTRp^hdwv9g6s?S7vALhPd9rg(NU}f)I>`_$(+OgLhK6Xwu)=OS>Z zgL5c4M1zi);Jh%tSDZu9A+u}3S>2~TYj6%lhpeC@COC(V?=I(1bchB`IIH{AXN}lX zM|4=XqUs+ey7ytO2PZyshz9+v^Q@Ckebxvy9noRa;E0&$PKH?ng0+|lXHk3fbKVLa z)>~D?1ocKge@6I0J~W&|zwYGjSds3P@rkz?p7;4yPYVKH7lGm^B_4Z}b=OX1tXNXE9IAN~`hZK`{Ee z2H}W_o9^_EFJN3x$r{g(nSF80Fmq+XS*+@~-Mu7;?+Jnxbi_n=GRztei5`z`M<*d^A17W7&UyOn+Y6b zT8$44AJaVoy0Yk^V;uOH)?1xN27wdR7)R)DMTd;TgtPd%jrG8fwPx256L@f;mo|>j z---@dK@-m6D?RpA=x;@b>=H*z;0!kQRp@VHC(eYk=r%(ip}!3svfCXofx{VkY2ye* zZKXjI&Y~X?SS!dZ0x@x6*sZ|D#WI%1+b8D@>p--ZsED-+J* z6jNWsAN|El zILo)NWeGKH=nxG$VxoH=W(^2*I1|p|ZP8Bqmhe{Su->X7Ca8yA+P(_?ZRl_&oW&fD zQwFn(4r_KRVuE=?FRe!CZ$pQ*f<-usy)aHop}!3s)-I`t3DzIIv>NP0bT|{vVo#4# zU+8Z`hqc=)VuF2)Ud}YQ(Fgr3XYmwby$_<=Bpflp^Z9$L5&GNEVSO3uSE`r}Kzu}e%ii`_YH zMYwaLLw2GgCfK*^vsNSYN5{EBoM(+&SoT4>+E#tAZgew|-iN8d&>x-i3PB&NEWRUS z9HBqDbH3GiWDxY-F%Hh5=#Y_{a2DUgu^ya5Yjzzm(VYx)9GpYZAuDLYS$x;WzTzB; z4%sD+nBW{V_7&$)cH&Gpi~dx5dRaJ!qC?Ec$Gzd09+2VuC(9 zbj~>x9r9KtoW*&ezDn`4*C3(~rUo4`!FgePuQ-RIL*~kavwRE7K6pfjte_(%IQNY2 zZtRdFIz)peoaI|s_Q4}MWG6aeg7e$xAF7lGSbgw_ z4pFTMXHk3fbKVLa);KC+f_mtseM^2n{2*T&zQ_+fc{Ns~J7WBU+YHb9e5*H~h=-jV zB+&)WGSR&cgO2}-HGD09AiPE&G7-*VHQD{`tsWl4^MiO$5RRDWPKH_Iv%;VAlkarh z@oOf+S?o%7f2(oFAZ{PT6N7NXME5?-8b1*}qx^ZoL^zA*^R!mOgd--plVR5Qgm|OR zj5p)0OgM{qVpdv>I|OmpAQ-tLCUDweT#w8e&x@I5hM8Rx&SF)^Z35zrPGOgra29)w-Ppzf!ER(HI%1-GA7+j34mZy~3s+BSm^jZGx3FdT{vh5J#J2_E z8{JIcAk*gRnc+&hM?hB=UxhIaoKNem&Le~9PKGsCYmMB5v-rA=^@zDzYjzzmfuk0B zY2yg}t>};yG~q11(qmtR{?^(hj+nq1Z0xJh--Zs^i6)#yw;B2f{cY%w-R_799L~^7 z8%HQ=D-D`(7N^Rga}$o3z#$5~v>Ktm4IT1UCY(k0AK$Cc--Zquxg#cU%|b7&M$GJn zs?eYbXK|{muj{ge{*qt?9Wl|J40B(_4%tu@`Y_=vPGj}W4_~qqfd(Bh(Y+6|M(p$r z9a6)DvwRC%mQd4%4$+_^Cc5`w)__2VGvO?1kM7J{p~HHsikP4tdTHx%8u?lyFTz>O z;W%ZSW_PXGt%wQc4ZXA)p}!3s)(RHkEcU`UEwM|`VeOKNm|*?UOREw3+t6X{#3G!< zo*t*Z(BFm*YqwX#1p64hv>GQxZS+Au%UL{ySnq?VHVH>e@O=K>YJ~nabXZ@8dX}>o z8}rrs;D!$C>r)XE%oF2kH9~)U;WlR1&vF)P#JaZ{5a_VJq7^a0db2*Q#_3DFu}l0c zXR+7Vzr7FA4K{Y7BPQ6l?6X!Q^hd|Z8Ya%O#w{%SAYE;%K3F%pnMm)$)L`h3&UuBP z4^|f6kui?YAKf|M>O3-t?qrxXPA7mIxd~_SJ*-(@76^36>^fqiI~isT&Y|d#6*S>2 zzU#GnmW6X@?Gi^!@LeDKigPGBWG9+%7X7LA^s;acMThKmM@-P4hCb+lr6?25qR*C^ zm&Jr5Cg`(6=bS^)A#Y{ES)3Q@8?!8&L!%Go$Q?1kd0~97VrGx13JscYmTzI%2a{k0 z9WlYVXMA@#DWOAli3w-<7M6W52{h=43GO?if5c8dqC;w!aF%aj*$0o&2eYd=Vxl`4 zRv$c~LsV_m~K0u`6}z3*x(jxI++*nCRYzS>q?dXOusmFcHq;`8=(CsZBUyqB|L8jVH$& z-6`ITw=&@@=80KpHU3Eu9~T63<%o&yWSBMX5;MyT&xEsBRaUpv_^crQZ4j)WBPP0& zVb=JI*dgqcnQ+$mEezs;L9l|3nCRYzS>t)(=6Rp+0iB8StZ@rlmLCq{3xl|b8otrZ z1P(GEkTt$9TuJu`=*r@&fU4SD{b&&NR_BpHbSJ~C5&B!vA?snnS$y5bdW8Pgnq5as z;Le3!+BiagD>`I7OgM|L^w?LSzqNLWBPP0&VU8p8x1vMV!-TWwHbWnwzx6XuyWJ5J z-N`U(grc_6pb2NuHHXekIAQ_^HT2TvD)hIZLo{f@S#YC3ajp>OS>qO#eUPrURUfPy-AtgDRwMLB=e$DD2P@0B zu=u?nLDXBFM+U)nWQ>DzC^}>XO*o71;aCsOp*6dXnBaRj)`N2>I%EY+IE(N4*jJoG zYnM1;g75m+SDZu9AuDLYS@fr&56+>{2XnVOVuJoO^g$0qRcO$Jv*@#>=C}`vaKuD+ zGR*HT=TLNr22D7N^Fn=<;&+7wfeu+gM@)1l!>kcAdqjsb;Vj?6vJW27AuH&J3C=y^ zyBj;?h^l77S-yoW3+GS>R?ra>+;>L*h@E~!hcn?U-@>vF9-|LtS98QfcQUL#ctnS& z)`YXpZ+E;EI;^*L#HilAGXDN;hUb00)ysnTksv-S2{tRidfhzZu4 z^=UPp7dzxo30KlR0=lyJDvWXbY!LNU=aE4?JY22DI6{9bI%MP~oW<8| ztVif?MTg9;BPMVK8tW1ITWbYPIEz!w*jJ&y6&~=>?bSJ~o;8q$m;Vil)+UXkXgd-+!P(v?m%|m}1I^?ZPIE(I&c3O?l--Zqu zxg#cU%^KgU(BFm*nOzgk;uKR~*ZhiZ=#Vvc#6~D?1ohBM zTl3K0h7N1wML3IDAE%7a--Zrrb}M3nc}sV$97pJHLx(frEcOE0Y3mXC+t6X{l8TsM z{n1MsN9b=uhqV)na29(S?X()9zYQJMZm)<5_Az>CH9~(VYNHSOSJ-y~h4+O3+C`tBG9=TLOW$W1tl@8MVv&Y|d# z*>%JO=ZCQ#oI`5`O*o71dhMQN;T(z%>$Fr66MWalzTzB;4%vx*mb2(jwWq^hEeLeT zZg<24{b}ff9#|SQ;Vk-WsX2UKML1%jI~nGha}Gs^yp;)OabBozO!%J%fesnDBPKX6 zjPF&RLr-5g6VCE2tlcKiA#3i43C=y^yURHgRn3I6d<$C^&Y=+OL`O_;ejEKGcKQ(= zqCpeR@+~a;;4%7Ob~Q&#bSJ~=gGY3TYE3wc+M}QIR_L(asv;(+hh9$K#Lxc7^ZKFk`SzYQJEgtIt})i-}xVi#`c5Jfp+qB|L8jo9fMI-Ch-`4+Y;p{5NTqCrPY zbnnBg0f7!@!dblS=+3+qI;^*tT*e^`{0TWXTn+R&T%UW{m~6JcA_ID*thJn-UsP8 zSBUehaSO{nNLSmc57v!tCQ>gsSD`;T=M{oJSXq2W#yCQMbmx4l^T;6RyJH-jLu=$F zoW=KWtOw^%bja*FVuJI-SP#yjwSp#`#dp1S&$4h1MThJwM@)1l!<;M5q3CcXoJD`C zJsrQtD+qMRZg<24{b}gqbh1oEnQ#_;w$vQIWwV`LlW@cYeRk-ab7=Izd@B>q;=E8_ zrTCX&L7+oM?ud!*WSDcsITRhDK@-mMEv(%p&>?H?hzZU;zWSDam`a7aSRBOUn)E@nuw?c7lfm^J?G>tB8N*1vu76~bBU z%5m!Z7eU-Ph#!m^j+nsNCEe1p#&196r3e1ZgtK@)PiwPl!VwcZpTGZ7*7&@5qo0X4 zqlO7*`4+Y;4+-M+K`>X2nCRYzS>v-}W?vCAJQL1hjac0_j!zBZB|)%D95KOqvp#Jc zZ-^bjPMHa3vDes*tp)_U5yBA@c(kz3T8%&b>KiUT=U#t!g*eX|x3FdTy&%3Mi0_XY zzR}GD4l=FAfBNbhF82uN%Hpdq#_=0L+~f3C=aE5lC&OHi(BEZ^+=R3Ex{dV+{ax1V zI${D>ps^mIzZD&#K@-mMEo@mre=9mx42 zm!_eQP}Eu)G~q0|=FqtbM@-;0HFO^OThSqJWx`p$g)K|yZ$*cU+z}Jq`!MG!^tYnJ znQ#`TnEF;OOXzP!hv>r*6W#kTYs3y&QPoU1i_=(r^Oq%dVJ93h(Y+6|M(A%vhtx3P zEZ@SGCDgQ{Lp11!iSA^WH6YO8OgM|$qdSNGR&-czRS^@^LoZF|j2s=#gtM6SamrwJ z(P7PQMNBYn>CTno2>q?-5DofS&hjlR`(XSxOZQxBm!LzwmL|F@V%7-#t>|zjoW-6V zr@qkNiVkbHSHuMSINj2+#z|3E2xsvW>a=gW2}exueE#0nBlNeT!}>DRvz+BySoXmc z9Wru9Omy$V97pJHMTaxtELN4ZYU2p~t>}<7cf^v&Jnf`ygFytv*;cx|v8P!K@-mMEiC)sA^KqM5=TsQ zC&Qd8&Y|d#ePzN~^rza>%fdMn9kSaUF+qPC`k)7*s+n*WeYVuREG8T=L7yEu=NyU- zsbRudzJ)FH!9(=H9JwPVx|3nf73WZN$XuClmTzI%2M_3wedUM=&OPJ18$0BHs%FAj zzJ+BU?1UpGIERk@!8sHiQp1F^d<)Ayc!)ljUCj{_-N`WLD)e_ihp5(sv#34#Ipl2<+V;$ioY=Y3S~E>lbV{^hgV-6sX{pdcO^gd--pOH|Nt zAH4pthrfOEyRHz<@-1vx9v{RTgLp*LaKuD+iOL#3{bvt8+~>u&Kg@))*p=hd_v=A? zTM&%H5fj}dDr?;SAKZN4&rCRr=kv5SyCxhl(LJBC#(x)Y^jq;})G*;J-@@X*bq?ak zgJ9&2nCPBQS>x?7vyX`xo(X6978buZDu^Erg12(SM0bhG8ebke22(BFy=g{AZ4(qKdVxs#;WsT6^iVkPOSBq=#aNE;Vj?6vJbB4kdZrLf_Y+Gtw!kY5*^Njvsl$} zn+W|~qC?)w5fgkLS)W!T^mmC4XTn+R&T%UW{m~6pcA_ID_|CJ>T8+@(HFP)==UL+x zmVJ<}wpJgk8{JHxmsTV6N9Vjk&<87v@5mTO=>F>9DO&l;U!S^mRszyGz5J`wIRGtnGA`8mV!ciw-~9sylh z?hLW7e*675ec7qTd1MecpW^V@*5etEyXEE@xd~^vGsGD#h|fRGl_Ms)H+{}k=ppPP_dI;Ve{u+FA`0j+kKQrx$kCIH@*km~a-)C)R41aKr@9 zPlaWT)7K|!m~a;J#H_R$CLA%rJTb1`IWJHyvunaxtT(IMYJ_4hP%eZcCb~C$jw3qf z&Cxlp5YA$EvVU8R=$!PABpflpzGa`aafJSELWjJSiSw-Sv&HP3^uZ+Pedv(tGtu;N z>YVi2D+F|9(Y41oLVvGChrHE!WDtBu#yCQMoEfeV&f*(3)+6*6&e@G{#6dS<=Y2ev&OCG;W8f5?HB2~*)A{&bnQ+7eCyepE;^Z2gGi#V|7I*XU-R0zp4jH*4 zCb~C$&J`zDbT|{v;%5xiCE_=?1c44A95KO(Z}gAQ-z7Sn31|6di`fS+qYozGh>7k^ zpW_JqT}B^#Ej3Iyi?>B>?OVdh6&==FRm24KMn7ld=x`>S#jMv^Vp-ny%`dq8xNrFG nYj?NjeY~%U?q;9k_>#Z(ipzIC=&jctVbA-BILmj#W%>UB&(SmC literal 0 HcmV?d00001 diff --git a/examples/python3/actuators/mesh/disque.stl b/examples/python3/actuators/mesh/disque.stl new file mode 100644 index 0000000000000000000000000000000000000000..1ea14ebaaaf89e44efca5f4edd88e9ba48b219b4 GIT binary patch literal 175684 zcmb513A`;ub+216L5=XjAQ(g?f&&gDcyU0k?14c*5HxB~L5u;^ z7tk9C4v29;1VsXO6Y^9rh=PiWS253M6mdj@5{Ym9t9n&^b-L@^?f(7FIqU4TzO`!Z zs_yFUy$?C)kS9I%q?1nC@!;8$_kGd>~s3TuDd*Tg`9U-V8vHO}MhD1;dSsnJn z9i|p=D%#U7!e!GT=StNPmtQgw(RJ%)e}C3lS+0nl3X?DY;lA^OH#u@9;!TGhFhBpC zH%9rCx9mATb=_%EmT~+9rRw{~Tr~UShOb1;0T*06JNwLU^j7Qaugg7Qf5POo|D@9V zYP5RgLw28^dh88RzRym(+xKI{8813{cIyLwHZ^>D>SeE+-Tt(nL|LWqxX=E3lud`6 zn>gEj|A)tN7x6Ea`Wt{V?G;md&W0!pY43p)luI0rr*rY_~z%M9KGil z^gFq7)A=hdyFOaAV^Bllr9azre(v+GD=|_wtUgH4O5dM-R!U)SoDvra*O2JCJ6q1b zG!lav5zl`2wK*T|Y4sRRC{L&D{e_VjOfRic8D29&u-p&d>NjSQtXNNVs;D7x@~eM6 z8&4GpT5W&kk7ft%^lu}nqK3r1@B8bSmqMK?61CMW<{$MD5*KU~D4Lr1bxjB`swTRw zSShym|KvUW4wG6_2*s;fqWMoTNYF}USjLqSB}}Lxp>p%S673bkKFUXDZS?E0+^_q1 zH~;Q;z7}Qnf@s?Rs{03tJ)d=_`H80_IvR(Bgh{R0Wd5EXrx9+s7+qJ0N1d_Be8Y~3 z?h}+kRlSy09F;N=lyjCzYP)H?Vi{(_gt~M|sNeX=*CuGC(Qc5Bn5tUy+nJZua;fUN zLY%hu9kZ%F`lQwQpw+YA{Xa9W|2iKWGgP8JI&+Mv32I2FZhV|?6SPXL;+l6dR>FPi=LkN1eFP2SV*FrhD6U3<+jvrDc35uBjr zl7}2OJMiRWMNjP*B+h;Mi)U|p6k_yPohn*A?a-IZzIxN68~O0L+CDEoe)jX(qoURG z|KRx9i8nrSgrG)#k9$?JYR?m?A)ypr^rvGnNYF~9@SCr$Xjhhd8?T^INuT!j$%>wa zrRzB-q1yDBY@47JTYgPYLqcuLXU=VcR)ZcD5*H?{Th+~HPE7TzoNv6flTiIXX}eY{ zabL7ru5?M9eb(`_b3dHgSe|C!udMr#x&}z+^ z=j9et$DrR2e(c$~wUe$1YDlcR{aKA3MS@nBpZ2WWA9IYL)_&BH&&s7JE3dV89P)tK zExYbH(rcA-A90jhAEP+B<`^c_qbLcj^v1_T`l1!b{2U|ZgK1aJz3sO1K@AC&^!Nxz zf>x^8_9*IWWQ`2x?fK=YrF*I|<}rs}7iIfDf70l4;rBiRc1g%u+?kSs_kZRC1Bs8wPi$kBp%Oqxi-m4m6u@-U_y%F8u@iX@!V4+LgH$IRw`Zhlx&@#hJ;FC{rkT% zH9P&}PbyvaMJv{SG!F?%b?&V}$EYKIaqZM}@jR1zO14fgRU|ZmpT7Gwk!};T(y0B% z550PXkmg%=y)0@({MDU49p&X(A_=AN&3k`xBnExaO8vuoL8niMzpc)hUXAB}{j<+Z zO}AuOkUi6wFIus0)~S+TAER_+@LJPY`TjS5U~1O-$)7Oc2q3>cevFPj!TY(7 zJ|vXF@ez)`XvNf)Bq@f*bMHAC&%F=oh&tW}nOhOw!rM8ghJ<2!@5-q%AxucnO2;ej zn>E3FFzq77`#F8-DC+H%vFjMrkkDLW(4)f2e9($1tYc6^Lh-!Mw+UJea&9ToM`xqn zF#FWIcbnTk(^HRqF%-nwmIu zwr2l_l^A`}YNG3CwQe?k9Y-;WrVxtv)1x2Sh~WgSl)o3A@sJUM8kN=VS3S75V(dN> zIp-dOgzDzSTRPn$Xr;FBp_lD4k}9>t3vPW-)Tk{T@s1?xh~u$K1l0#MBy_#y1J6iw zCc;XhwhC5*D+oiw=V=6*VNf?u4AboT?au1g(Cu^UH>174z}A z-H*+!`j;O$F82v}8uZ#6!!;ys{K!ktA4|H@JkbeSDOF{Z=!uxBT601kSC&haa_%FM z%58isp)XpgEqH26F1*fNLqav{SLND7ZB?%6)dXuwW#xUMuGzw*()IR3LUmL6V~e1b z+QN80r{?N|kICc5a;YNGb;mSDxY}2-Vm*~ys6J{I`;e$G;q_Xz zj52$9!|b5#Z=IT*ek?ihx1~zNu^+m3f6n_2v)OJt^zypdwdd|t&V^?}!Yechfcv!gH&m!H!367OgbqZ*iA97b53_zGQXS zC%5daN^1KA#XogENGRUp4%?!{7|lm*wGMStqNEtiNAYXN#GCHch~Y#$*7jB`g%Uw6 zk!2E(YBzN`=fzWD>Qs?X-RyIh-%ia|KlxJ=v{L8jc_kK{XQ}0>MP>}H6+a2Z13~%Afl@*D2yvn_+M5#-cR%+AL zc-2FxwYx?~10Ug*OBIQDR2v;jYF~DY>aAGnB^O@jUb^(FcxCJ=OvDNbT=R@|MrsZ~mSKf3b{-A#rxa{mE<1D(&$&^(%YMUwKBletO>e+5FOH zq#ZChhEZYi({pF@!@rvR%Ib0NOFMS{_LjBtQ!g9ay+dD&ar2L6wtENrWR$8HgT5H! z+6&jt&wSCBNAj`lHv7$wIx_7%dfIHioT^W3IAp%_#WxnhLg*7FhrVO)`Az$#oPXm`PxKnwakMi-jjzJBH(KL;;$uD*DW`MM+0&hF(>MWPFjnQwM}+Oau|;UgTaINH_3KmX~Y<~w}D_n2#U zNSeJURi4_Ks5OPy_uG$#r^2Mtbziiq@>Bq;k4GK&$Xq_!1@Ckh9?{4-H6+@5=vNY6 zZfmdJJs%m6C`%PJ^vgZ_HIa7qr;+U82d~LTGTlQlzRR0dFWq`gKEAdIYDjdQ?kX6Y z0g#}TzV}k7^HFPxU&R}rg_EF_@>k8N`#@o$QuOtJO4rLrrT*imrd^tKs;D86>SlDm zsP&xNpPDpkea|~P-Fu)mJ-D00f`y5Exkjzhi9w8z(w2y>OEE~Oy?N|9AC)gyF@H6| zw5vyb?*SXj2XjcG>(ql2UB@6nE0#!2)SBW~V~nS;P0*?;Hz6T$cEmvqDurIs8sVx| zk_l=^=t%ADEqS-!Muo|WUC;mHr|2=VQBl!&Ra z6zLNt)R2&z$H!8=;Ar`|aJ5mD|LTX`>;=Wj^3hQw2@_>{#)yF#kg<@D0(cYkx~ zuyljUiki@^M?Du$?NrsomAQ>Y!u;!#a_;%)x?;t0OSb8EnADm==so~%`E7z$?fT%o zeXN_VyU0p+>{wfCN^OevBV3)Tm4sU<_W1o#wT6BbZ|pd@l5ne|UwiTFw%>l%D71F_ zCrrNkoyF_}cYA--oOsG&_T`ViH_9q?KR(8Mg!tQt<95D$w)5LQ9IZC&xPJD@GyW;c zDrvP$vzsPcC#WIuo*%ED?SI^d3K5*3Mya~|!RP-TF-RzXH(z&NiP0y`MmVImwz|Sn z^??zB<&#o)ZnPSdRgOUo36;W)2mIqm3=*_bsULIjIU_`^xomcRc+c;Vs;(=c80g2!$&m| ziZ|ZR6~hTyjkc1Y8e~gUi}BHpp4zFZiHm0c`HYW@^r+fbv1*UhwWbiN&CmQ|ECvZ$ zsl`0xkdM}>iaF=l&hb&BL@OUfQxjLt(yRkVgBYXsRjf3wjOU})6hbo&%~`B2ruLIQ zK{ZH%RvNDcIX5m$s39T$`rnME_LDwgB~e?cH;JC<%a(sLeEx8r23-@`eB&zuG^dZ;F7r5RsIEn`qa zf_WGNJkOcq<`6D}6tx^H^5YkVtE_(bm4=9Dw`f>b}l7 zHIkj+6Fu4lt?qxuLG%4Kdsp2*f=ZW~8?SuA{JnR4ELt&kI|d1zBd@O4nty%#Jawum zS`E%+ga{Zx4GEpOAHT*zf>ykOoxFPtJ|l&t`_U^V^E+KOt;@=wFrkKoWZ#2O$5=_Y z)eHV+kNFv2zIPoXC9Ie^&$T~HEaE(Pf(1Xp1bwjcfOyue(SmK z=2x5cJv!0ctn~?#kH2u+x!(u1)AifV{hkkyc>b>Y{>#*C^^-qgLV{LD9eL0B;O+tAbd_xDx!)h5oO=qD zbH6Vn2Z#hUBvgh~K6)&j#c^M>8kBBDcqx)N`>d@S`JgXav1W5V!pa(~Yi--P-|dzO z6YL&d)Zn(;+%uOO>!v2CA@RW*wwwDsEp38UKRI=~x!?a&6V$9(v)$b97-H<2poWCn z@%TMIBxt2x;P)8SF}`rkHaR6*y<(f3cDA0CL}_s(4%=m$Mp@Apt=Oh>jG!81--XrToYZl?cDEiJ@g&-$gPiUp(dyy z@vVp5qtV()(28w3#|X+f>sD4?AIr5X5{l=?k{rW?x+T&|dGaGsP1L=!lpA|J?H=R=)I?At)Kh}6KY7@Y1jWXKX12R*&3)PLW0s6VSmEg@tc2VHvQ5+ zJXTg(Gx+z()(L7z9CqNZW@mr&YkP@q6SUfF%RiWJ{+?4tQuTlKIA?bCt-D3d-5-DP z>~+uitLRsA`0-RxL*n-LeSS7wyZPE-sz}g^d8+flyD)h#p>~-1F}NnEA#u*v513ti z?6K2fsz}g^&+)5cJm4SKO-@?>cX4+2k;xxT_dfbnQC5n44qp@0kU0A5e>pw-PyV8w zCmI?iBxt4Y$LEREkT~&sXH9?et6fWskkXc7xG!4ij!OT&&IdIlZrI8{jy*kTtLu)K`rg5}-Q)RF--oJF_iG__3~ER`XLfjwR}+7K)}Ku4>ow`x z%`bM{KF6+!p(YXSe2}2k2{+#>=c$fC4GET8BtqiCL^=o%%>H5yh<#J9!wK={s zlfG!h{@-UhB`&7Q>sF=fHORJ56V#AU&3apC6SUf-n@$JkmV$Z|`+-W-bIX2H$DoFU z>c&gDP0&j9U$rYsQQC{cS%yl%XBK~V+1)3bzC2y?jxj{oCrqdzA=$4XMbl_LM!1#o zcgMR|T$_k7sG(oUgX3UOjFp62u}$Yx#TeAk?`RDU2wHK($T5Oa#d22<_K|@#n~4~M z8WM`(V@#W%l~U;YlWRhA!;igx%ej3!RsH|VIh#dUrLgC2cZ+gOP(wm(;f~X8ADNMn zpq0Kads|ABG*5I536@B)SLxCht@QoI$6XTbvZ60qam>#>MJqm=E)zj5 zkxyLX^XM2mIZs@Al8(n9p>?7^k1)qDp(bdh)#Uwm(LGXq>4wCG2{k16g!yFagyx01 zb{oM3Hqvu>u0)S zMYR3oPr8=s(KYvUE6sIv$BLOwv$+ZBy#StejncXkLRO4j6V#Bh;9?KVu@rT zC{@zv{uTRnsxvI_J@g4tRw?K%6@70%`D1sJLqkGmKmPuLLuw)@1_@fJ+;sPgIiKbL zCWML3syytr}&Dn64_fItI&!glbcF z+lX!xv{K909X&&Wy+|v2?_KR4MGXm^3m9*^Bxt3zmACvlAFM%Hc|D6B)JIUAQ=?RQ zozqi01__l&y7z8n>DIoA6AXv z<>fBgM>y8gN}`OfBoxEP$~HkOt$PNePf$Lzj`23C6_K}a=BbWB4GG2Y-qj{()h;Wh zS229tU9PN1D1SbJ=Tya<(-*Cnzf71ACe)BfE4#6NPJ&h}^%%oaq)$5Hczy6F%26rV zrr&l)E{*^scqD2Qw9*;+yL|KUBjXh{By^?WWl!CIgwXW}Ki2A6$deA(D_ZHA#qrmq zqiCHfzEMY4+&ABlo|>#{VLqSBL{M2#LqgZ+$Dg@Of>ydpHa_bkp{tAjq-wtBd|b^EN>%UCkVS zia9m9GU`t*XY6*2im)rO{zUUOq3gA7#k#49x<0naL|xK_N!JIx)^tVDW9ZtX=c(AM zKIn^9x@tXMR@zPBPq7y5eMLJi#@jA6BpAC+)k?ziq}bkiYJ%z2HF|Fu?HJUM(Eb2# zm30gfv>HuSQ0cO)MEFy)<;lx!7{fIrl)~|+X44m~R3d|?X2(=fqdNDejnh**RW-5A z+@DY0Ce#w$N^QD&Cb^|ZpR@zQHR>Nua12hi>9_4X!{|&x{n7K(CTOMpUzJtx7}RJi z@j77ab_^04yS)C}1g&^vs0nIF=xE@5vrW*7$C6A0)dy=z4}onGfaCdJ!{f6^sDFJjX#l8 zeL#KPTue3QYP6O-sKFdVvkJG;e9>v`v-NuFjpLs%(cDAht^CT$dz3tBxS`>iC|C zkhm~WdR?P@xL=lf9fN&avm?#pyh6V#B!wZ6isNx6g7U%k zqnvBzXBJDgT@osF%@sx4k2#OOSG0CowOb-JB-9o>g~_|eAVDkkf@m9@V4qM+^j=F( z$<_&KNT}uev8zqcibtZF;5j6off}7t2h|`oBzP{XjzNM}`rhXcL&7yAB>VTP6KN-?~ohlFeBSF(R!6Fg7NS-*(!`k;nHdu>31 zR{Gw{txi>~DeDB$%MorRPhM`r7)3+Btv7AdzKWH;A1~cnQwZf_oX~v>z8=sW5WY^( zPK9wocZK*-SoeGQ@tiwH>YUTB?sV~^Wjh8nBy`t{AF1mYBxt2OV8&+vOuO#0^O;OL zAJmZ09dup_b*f0vN_Xse8PyqriMhiJ85iHM1ofO zemqswkWf5dw+&O}zG$WV`KmY*LHVFY_3!Iw#?FKZDd!%8gz95_wnSgFQf+$Odz zNsC20z!PuEFp(bc0 zc{~O+B-;5PQCpRxT~1ZZhsG$cXN`8H#VpfyNoYj%BV3GO{`INbF0GiSWSf51Es=!A z`3+a0wf9&}(2B?1I)kHZmjyNSD|tD>tzDEuHrg+N`ewV2{`CYBURJn$JCHwa^q0z@Rx_KgML>h+!qO@Q17Q7ri#93#njgM zVA^%;5l_ zb-)zXsiKC2%I(@~jv1*z60}m?T=J0PMhIPH*Ik(wd8+I6>uygn^E6DAmk$Z;K^SjW z^hGPSw-_U&NMWKD?&(!u@!YBxc>UL@qK1U}pqF%;pcO}=nqbe-*)K0E_RX50hJ?<3 zd8xMvTCogkf*KNOZ$qlhHbE=4g-issUA7<9+PP1E@$b=gNvQsxcIZn+TB7pdbxSL? zvFHE6@rAGy>63OLxkh#4e%Th1ZTg*de|iiO8XrARZGu*8p_vFu71OH{-RI>g?aW^$ zOi1%YPZbH(&Dm#-<($4~wOr0gsKs~+>r~Mft<;Xa)N6w8UE=$ylvyU5_{Yv)lS0~&`tFXaS zXblY$YUo$8Kdq~dv665r-6Jsmgjj0mSJ$F+?a2J=Cx60(1g&)KOINhaR6qG+&nmWe zkbmf9yI6~m<_)t8ZcQs;oe3LXbJm(dXczOwiP~zJ^9&>;kFSb&=B~CXXIOK#O{mX{ zl924{oz;nArMDR1jZ;0AVz`EWCHwco7_OP&vq!>N|kdW-(7kkgSYicXyW2~R6 zbX`Lt#ao7OTAsWI4^!nD`jzb8uTB)Jb&V(dDZ2M<`jzb84`aB7R@&Kr?1%1crLwX| zQA48r&U>qq*_!=Rzth|0Kk$qsiyrS$)R55AHa1SsN}k4h6g4CyFGskQJe9su%2($_ zi-vwBFGskQJbAw<5!BkLprvFuZ;H1J;eAk^ zN?$4IN@e95`jzb87ke*V*U(Bayx$B7*N~9x->*)%)rJSXs?i6jsr{ZXo9(v4NUzn| z8uzQK`o5OcRsHeRHZ^GnL|VnuQ=JcLNNC4}pFwC7w9*a_KmSk@+Ogxl(te+mDxF*M z{M7_CB(&G4%6Uj!m}u_dYckS0f9Wf|ItDc)SR#?gF-Xu#XIQJXb0(-E(Jm|IBklJ| zYe1&3&IdIlwAaW>q)pIDdzh-Ss`BCMGo{^ETgsF7v^oYgB-CR3+(4V4m0G2rL8u9) zS39=64p<^JK@AD*78`H7BxuDponr)zK5C4Qv zEJga*lj~868YMi1tfyp~ey3;rdU{D{B=R$QZGu*8`9s1-0212uG=6rFzG%hqv5vtp zLpvIM6lKlU1T`eIgK|7oBxuEY8piO_C82oZrAuG5VtdOmg6f>DL9N|;Fg<0$gtT|i zQ$<2OZTzeOebGwe%HYgIOcga6ulyVdJ+)IsLStnW!~E-0=Yv+uwRRF3^T%^eU$oMg z?MCHu;DLqBh(>qU~avKSv3 zs3DLJbMY%MorRPu}N;F}Gcb!sH?a?9o>q&tgULqa z4hb(^`jzb8uTHp?VrT|y*80hxR93E`U&;P`HaEfc4&t4qd`qc_@zSM+gmyG;oS>CF zdAZf8qK1Uzp$s=iEC=Bb&XUhhNqW=WdGj%>u-wT8d~X@MMqqINqiGk zO;AH(@TR7aIK}vqy}e3r)k#mv_BUDS?sdJNMc>;`{)7oNsskrfPcBFEkf55NmF}I73lo~l1bbD`IGijdwTUeWGD1A zWxe~rO!bpKA@*~7+OXc-VPC~J0qH$Fl1E!&5TWN&>%AYcQc6l~UY|XgE`5Rs<Fav2hv+G^!#Q$(ciwUVkl2~ABeuUpZp0EzIlz~;Nab7VuDgd4GE?&2M|;dw36(l zo{1QP8WMV1>?YlGYS#M6pSlKVr4sSBkj+g96V|PsPp>cjW*kq}}RXiX`-;>#9ffSWVDMPoW<4sGu0K@)oBUdZ&}Q8*lBV zNHM&HlTiNB+oAfhGXMJ21g%*A$u|8?rRy_!>Vt%y z9qnzbP8EI8O3#!YAAR&RX7A^EcC`2H(b1>RM>#^0NKd!^i>Vpu$0{QJw))_BrPi*u z9GR{fSCXw0tSJ)dne>R!V|5MEYIM8`Y9&ms%F0uln4B_~jh6A{I(-f3C+Ad0$tQ`}0f$ zy0Fmb)1SHNL{l!F3KSNI9{u+D=#biCZcqs8`FPQ8@qHyR?fnyzVxC+shzOO{Jsxx5 zT;Jm9N%miU$`Ju0@C5!2PcZ8=XB>~wb>E&n<%&;fEa_hNyMLek?r-8d)hva1?Ytre zo`>4uNvAPSUJ69QVshoC^H*GUeT?zN6E?N{d?m_CRew&7faQZ4636}Vrt{-=j`w-3 zLeT0_XKXUxu;UFeUPM9y!{Ur@-agy;ruZh+?vg`po*i|}XQS25H~nUI#y3AdLQq5E z@U8S5f@=z)5Edup{ItEl5H-qEe|E4-c^V_AA)!1~sY=;c5#yyl+jRcycV9b**Bi$_ zsdPOhB)aa-Rv%-nohhLe>uDIH)NS#rc;`Ovy1J|kt?QgtY&~@h)q&3a=-X5Wsa>7? z>R->iy|oEiZGYyEW;zcUxGhsqlP(woH=Dnaz&}y_t#Ta#e-emrsAE&;( zY)dS}p3l0|{KQkfHd0pfMXT#R-p#-J9S|YqM)je4n!g@>J^S7NGjl7p&}8cbH6%{k z`;OUosz}sUznyt0MDM|4bY0PCwDWP0o|3H-)R54~H$Lu?pcVUL9V3-)yv|{YP3F(t zDviPV-bbZKgv8b36$!NkAHkFD7(uJiQPkqpM+23cr%L(rBSRgd))Yc@bMmXN8fjM~ zXr=nU_kG6*i)igCY1I1MsxHHlE+0ix>5@=89#0j0)mEi$a)h9=(vF~hUq+|>J?Y8W zU7X2`&j2)Ua}5dY+;LAih6!Oof>xUKxu=?-hJ7J}%4Emy#b|dKy zt8v2ToFa5rm8=v`cU27uYLqA4vnDIWc2A^IS-FOU%1!sL(OPm%&`NcqyWEBZHL8Ez zZz-$gQbj^-O!r>q7$He@s%WKN;Q7mx38{a$hJ;$a?&+kpvtq+UK;`$XGJ(3eIDPswOLjH**bLi;tUvPy|sLC}h+ty9Ic>#DA|j6ptf3~ESd z$E>%?-Z+I?kf4?J2amUQrOL+->@Qhz6eWSZElgBjRz6zNiX(W+Kmx;p>D6v%@3qVy zgM=#QB=E-D0tD4LebI{R=z@r#hJ@mck5?pUrTqE$m}A6LQKK64v6h}PVM3iM5^6Ey zV>^A(ify5ep;4wkXVq!E>USh`8kPF}3NeNL*O3=cuoEzZ>nfM%BHRgpMWE z$dE#;AZVrIm5)Tx*!=4g78?6}B-5DaBb>%cFZE=beka0PxcqvbP(Hlh)C4sol)~{o zNP<=zV{(j;TFJ9=`_U1{+pCUt?|<_LrnHtE7R;@VA70PxoKr(W$1ZPUIZlj0f>ui5 zpzQ{wifI?&y>^g~K2SQIdk#q`h2tXwebGuKGCun7th0KN&uX+==u_|BZDhVHE5B-? z^VIzvxt%;6@s4`9As;#JVHiGJD|}4~fxt_{LjiKRx=PeM&}% zpweXw`faC5DY<+H&mnW0-$Rg6W&ZV13~CBdms_$P610-+tBhHhTtcFm<*>c22`&Q%{ysGjb)!)X$%=dI6w)9l4tJ~+ql)>G`g zbX`MYv-96P+x;r13zJgi1g+S5ioIemy&~3J^=CO%8_zijrSR7${&`QAD0NxUs%~#R z5mL@i@MlYOx;xiM9`ajhU_{jF}!9o5!9||r5JuR7$po%G29mk<FT{8^;s%|D8f_a4XNdA}#w4DzlHH;#WrTBj=7s zZq{2Zld77qqxMaA8;QYG#bbN6Dy3eEH@yB<}ZO%waa3s1jK^s8PlNL5f-QKSCh zgnHWUHzm46SV_=IqjsTtCdSb5yx+|qX8_*sG?sV^jrL}(PgrRD@G^YZmSX_JI+WDC; zN`6m%@>)xK+Sesod&Aw*|Jr;PF%pq>x-gzw>u*?4Lqf5SdwVK{HbJYuy=CqEguPRq zYJ&M-+C`jt*;qcPA@S35XLIe4r+>*|L87*Ltd-js(RD>b;_S0#Ln5R;SO{9Rb50Ej z#nb%<?J}oz+Sj+` zGxtLd56va|wAp^S<&z4FT2qM8J{Xh_60}m^9Q3G2P(y-!zD^bManzC8o9b<;q_8Hs zu4qWe(|Fq@K`W(jd@P}cgi2(5WFSE+j$?H`II3xU)V&k3pr@LkhQyjR`_6SA1+68A z1qoX1bp1Ya-EA=>I1X~0=O{rcjc{HjB-%#<`l6M3nveN)3~ETIclnVa6G1s=&-vEF z_MYo*3t24JYe^jXj=kr)6C(TXg}R^DR{P9#AH|UP_zU;RzElUED%I2YagZ7ks?EX3 zU;$H|yDwVt7#vd;Qu@L|x%Jkda`U#tl1{cxP(wmvm$&0KL95XkG&C&OMpbUQr%yiF zrt28gkm$O7=DItO){^V~K`Z8uR9MuS;#c+WDQpw8VyV|e7alXe{i$gOo#t0Rerno( zmty1hD5uy(-*DS-bw^7D{ogMRBq#~z4leC*b8!upcu?KQ+V~od(5AAcG?}E z2@}GC8WNHRcUr_4D+#yS_uG%2fA0ZfG4LGfPVXXgtI-%SRn(B^I_)PLi$Q``tEZ}e z4o9aH`p#866}%Kx%sDk{uiibkE79($ASzvINOa*5xrMd~TCog=gx3KHz1?xV&gqL* zbxB*4kRpYJa_%b@ypN|#PgP3$_oHnlXoWZR42cxN%8I^7ymad|jafJeTIqYQ&E9=V zT#Vrw5?!|jGbc|{>`~B&@VW2uF`Q7I##b!#MJqgEp4rIlsxNnIOPigacCM?9`D!v{ zIe}q;cYtPs?V=GBE?fr8z-nCp+307H_%G@Ky|9rDvMwB^A)Sq zp!!&`)7q@k*v_5Vbv{;TGQnNbnTRn+&K^9NjT@yHB-G4LD~yRO!{ z`-~bAcm_;LPXAly`iigGs@(ZTL^;n-O7HY`$4{Q|PciL!Pvri`eP|>fddFRVN3OZb z_t(aIBE8&VjF2LQ1%2r)m6t#G{N8Vgoot<8sz~Uqm^WW{-bkuQ)K>ZKT!x5sUNkjv zf#v)IjTj||#Y*%C?)LtT5Gvgp5BSGurMF@pbMQH%L@80+`#db&J~tuW$?B;hp*P`v z{)h2y=@mI=d#$Z5o1GutGn%TR(YrG}?exSTb*f0{otj<>ZGu*MkLLczom)~B5*HSF zqvL0O@sVD0(d<8;;qo%=O8wml)yK|n`*4ZTC#~)uv|?Y$`LLAPOa`q%ZTHI`e{b)% zw6{!{kYacZl1TjqIq$KWpcUI#ju8~2ZgCf(o|j3L%F0`YN`1UtsSkQSXjP9Go{5z6 zD{^1s$oXA+`{{U(qK3q1ON==uK`Xs&wbTt$MGc8TOLWLa(UK3v^D&Ak?2Y3e8>w-e zAfec0d@M{&&?=>BY^0_}J<7*+#x4<5AJmXg53c%0NL)?SR#)bGt?L+FS2Q(oS?-UK z$T3LhUBBLIL$^NP!(GRyHHFYQUn{s3D;_iE6jXM@$uo+NzbRbktAjC6Vr}zj7o730kp4 zn6i~)dl}D}r<$lWh0v(vE1A^^x6+KS+&^3xKN_U@xva{4)U6ndUK5&C`WfhzF+3${ zPMWL+sR~BfPde86dO&roS$Xo9-zAj(?SH3yj1yPd8bNk>navwWzmJXIu8i}`km(L*&+TdDrX)=`S#8WL*9et&&QlS-Eat?Jq=Oj>_< zZuQs8N3(O!U$zg5K@AB#v0}VFNYF}oDD|JCsFgsYcB^~drLR4apoT1d?ce1J6 zd|&5J&)s@n-4mAyYDk=Y*4Fd!dw4(o!foe%fA&t-Z#(zC^>{|mQ=&KLZN6dbUSw(* zL+{tC$|}cTKA84xx4Gwha0h722kYbJA8kGN`v+Ol%t-1{o^}$4?Xt~${Qg1uqSaQf z*kzO4I3Cn{%VL=TEc^coRPl8q~x8yzj4hw2XJZ*N*`S{(kBxp5S zA2A8YJ65^DM5_af65t<`S%jcUS1i_2UFJB=ijY z@%y&x7~ABW*K|o&YKfkbFI-aywJYzz#a^w1zG$UZ>HR+vA#q_rjas|+B6@1aAfcW% z-b(0;RvP&RZP!v37VJ67xj*+op1f}kQ{@^GDs>+p+XSstvp%}kL^al0+x1j&?5YWB z)OMXvFBl&gNYF|n-}vZ5jryIBaP-tp6$$lVKX$bVT5%k!iMp?qKEb|O6SbxgY(0?( ziL1veTAlx$d(Mx)X76%T%LFwf_*Ay!-D7Az=zUPT^>m$HI_=ieb$VK-BPTW55u|+@ zvZ5zaX=dp$NNBg7_Jz<|a!t@m`@6J*Ye;Cuns$TPQ@Lz6n_Fq-?6FCu8M13gXkW{C zs_2VW+P~tZurfx`XwQn5C_SwtN_t6XhlSToo1m3;bZDPOwhl?MG4a4(&E9+H6QV|h zc8N%L{O0zQ<_iufL;|cns3D;gYEM&dnE%*5WN1`A+7l%;J!Nwf>KG(c(%M~>twWM( zf>yV`@AI>V-8PmFTB**p&r9Cg1T`eo-qKFAlp6mX79?n;w(IfST7Sdh?vKBCcFs;I zz3PKrAL$9WW2H+X?Zen7=3}`&NJ6`uv_pj{O8uM~?OD>^6;i^*1cE|H*x6KbfbBV@yp@Ln1vD zdaSjRpcO}=ItIr+#qhSf+_+0Z`5W|)m~;A~6;oTMiW(AWpW0Y`kf0Syy^f*h4EUOZ zPrT9H1AerNL`Yn^r@=KO&iVQQv-|HdcC4i@TIrd&{;b)YDvJ{qd_Jw74d64`o45Gl z^gqt?yVo;g1T`ci`@M_VKE_x{xYdc@J8Sy-`ObA~j|4UJtEV|Qonx2~79?nO^w!$8Q<%J`-zkP`Na)$f|8mY|B_Cmopw(#3jS36B^+02~ zJm`G}8ha)0`0@kSzV)5yz7YNIpRmwV-Q7y>IdEF}DChd!UNLB;cMbSG25o{G66tLS zV^)&6s4-&IdIlRO*_o z(ZA%>uDncWrJ5b=Bo89k!qrM@tFih>QIm#*az36a613tozLSmp4oVfiXY5VL=TEy=y}A2DkLTH9;%AYeMr0xAeby`rcn;jo!H6e%V6ZT7Of0c+VlBH!gUd z+61lGH*11*D?+OaS+Mog1T`d-Ld_d!ExB%2v{H#^K9Px#B%4{8H*8h4Bgys#B z+1~WOf9jSo zLS?9#Caopc1g-Qwi}AhZ)aacl?svJiOG0m1@jNkQb!(>;`%O)-{fO{Z!WLQ+)R0gL zy}d;uB(83|v|6r}kWd+p-#0;Dv|=yF`LLAP)mQW7HN`quu9c8TB{Fsw1bxv;slDUf zmyWb6S^3_mmG5a7-w{v0Bs8np^yOo_4N1_dohrUPf+>u%!9V$nk$g}?LUOqeI@gHR z$4bJjG^_p1uXY`YK@I(CuKm*IY(7FzLqhXwk5|&9RziYSS~DENb(NKWX?&2;VNYvohtGG6zbzuGJN zH*0;;x$qZX{MM=d(^>BSdi35=)>-aB46{ksid;hi@4=I^^a(2oTH!r-*;+za=n9WN zagQm{we70T&A&d%dC`!N?5#4{rr$%ttrUCwS$a&Bu1EQ^^cb&>K@ACA{~CXm9tm3M zdfWK3^q50k|MI6Vitwi|=2Qih6@7{D{=wLpFrlvVn%HLU&ueTGx~}F{x?(o|j7D80 zbB(TfIic%2-a_jb)R55iFV9n(pp~wLjh8Mpy5{Az#@Ou`By|1DTTGjvm9E6U>%RXo zrM2XARo^uvbY0E+4Jlofxo7SloCiq`ke; zQ%z7qLbd5FzfI6eEoS@~rg-msr}pa4MrBW{V^C8Q+te|7EcGZacl8fX343rf4hc!U z*2_mDgO?~{_wExIuj+dY5*mrdYmmNZ)gBYspH*)DoMn0Pqr@;(t|6fv5dMtkHbJZ9 z`XC8iUG@~#G3bj{9F=NeYw*_muu6r~Oy1A@PF0*<*gjm+w6?7nPOI^uPRv`_2#EvnL4sEL-b*AV zr~j4m;TjU!6?pzRZ*0VHf>tcI93v>_I`67;3i?*(U3H#JGG~MO-#_&{k%Z1y>dcy3 z#=k)^YE6F2^^!4ky|#ZZcHE8Yb5zEuQ>CjwZpE2wO;AHZSHq`Y`iIBTT5^ivqmNS6 zze%@K{&b#nobZ(B+=b4v$V%t=biPJ1Kbp6f-0DoNmnc(M6V#B`6uG(UCe(rUS! zlTbXJEuw$Pb6R;9 z66xA~d@pix-v6#kmsYG+i{zqmCjL*k0m-U>8(#^ zIK5S})Q2&=rbsA;&Y99$a#%3B2p{2=%Q*?9cDyCh7p<1d2ML`;9q&=}MJtvebDwhV zWup4}fehP<_--n=MalUG52(x|_#m{gS;c&5+Q_pRRIAq(x@)%#g!ovvCk=h}Cy zw^YcAc_Ni!_?()A_6lpa3ausA1g(@Ro%I|N%%OIUd)k+q?~>3iaxVqOsY{nu+EK1I zp=9fjq_AKqDj!}4?K-E1gv!lpGsiKZu0dLjwh~KON|l$Q>Re}`<#V|jB%z(ydXI)^ ze(D;em3Ck2T^+QR92VMH?;4e;`&A8k>mgOIyhx~SJWn-2jq2P>VYwJ2)ZWJ1E`8BT z{n7hMohoW{FNTjR^i&hnkkEY@)#%e>by?9$p1l7LW4MNd;%$8Np%q7>ItF`=>R)dl zlEreVBB8r1^hS^DKP0K{wX|YS%ajRqk0POanDhn_T1&18TIn9I@l;WxKH)iEE>$Gd zyQ#QqXm;?7tW4k%3lh)1>OQOG0(yDQpw8 z;uw>Opq%SYU)|@dZ*@k{TfXK*E@#4oboYR3NJt(Zujq?b`o2xLhJ@rYb1LadsUqQ4 zis5px_k6g9ekGS#RAEvK5^kj!E*E=`;TrlKTvzL{6vGKxDTbfp7{+i73GJXg`=ehg zR}_T>Pn8q28a*cy37s$TXHzL9UjJGTx-9qpNvk{8kdW;4!_G2YP8S5*J{h9iiGwV z_^Pj+Dq3mR!1%0BZOK!jmgs3$d-GDSV^Bjvy3&L5+H?*E2oU1T`cy zDvh@*613u|RL5Xn(+&$?rKkos-lIrpm(%#Fh`wm08uWNERUxGgVy}6FTy+hnBwA?Nv673xj^hK+|?u3xi zR_{(AA=%5Y&If(bYPr=m3CZKVmcD4U+<68Pl6?H9X}8WNIy?K4aj3Aa)VmxqLF zYQH0UqYSP0+-X;s@1Wv-zdDAlpLt8{x(jBXKK(c8%$+>}ce`DGJ#rpSYbU=uQ%@)T z^yzm*D?MxU0iXPzng~jjo~G-*^laRHzWQIi6=RolrInYbiiDn%`{~nvRmX@qXFh19 zr|CZa*k6tiOs}3{`t}Qd7p<7Tk|yPY8WMV*>4zts_1yYX6SUH^M(=eRh>*zi%*>*> z2!7Y)QfHJ@R$d=E$K)x|(}F!uZGu)RtEvWbs;Eh&o9bMpUSgLhb*f0HHg|o(Z%68b zzG|ywTZ#Ksdwcq?#_mOCE2*tY%g?#6+=m6*kIL#>FS)f(`!cDjiHm02zwZ}~oO^3m z4Z4+{9J}Y{V}#mI(Oi}Zwb0@z=cI4DMN2@S|a`GjGm{kP8C}styCYSZ}v=3K3G#CZn)s*zeg*niA!vR zbGoFf9ut)hw_3K&3!#!ODP#=#qE+4ANU$}eqd^*->8aRzoqJ0pq32fbdQ5%t%@ol z=-ZV9t+YEyGtFdIey6Li{wx$-$=Ce=(x<%*+l>(E3i#GhqpPpFCqsm;@Q$Y{?eR&z zln;-g6nboV@K3sm>>3g(5#4{_mho>;&RIT+r+ZnXWhq4K{#T0O=_R3EJ-Yja){<+2 zR=VP@d)X=?h@eK-=ymsttd>g^30=F_oiJ4l`=?G7t#rNK>xNWVsGhwoX(xxbu|W;? zSZXC+RwUAsLRZvBOcj06O5c0U)~TX~gyIeAJjZZfv|>B1W3W|gzmM+2k_BVe1T`eI z*GTt$(OPodqiChwFuKpIB7z9k6noclt%QV9>-EGqbt|EjWFN+)0ba;hv&T0#2r^XPYnZ@gvp z)1$|pr6(&VYO7OcYxaLw8GRHe#?a3GBi`|#UQ<$~o$@8MGEX0sE;WVVD%`F0cSv}x z$&<@NqG))gpmi3f_EoI({dl{oHHA<$A0MEH4)U>H$3Q7xko7_-i!2v6_*($J(trpBqWz!P?#a%R*KXWR*K6TNgvXiwRAyP_{zX@8lw;}tQ`meMY?bT&es z2JI@R$~7buZ+sm^U$j!5eBD;3iW-%huL0?)Ca58yx~bNjA#tg6Js-5}2Z%H6+x7z1-Ratu$g(^$|PAXg2p&d^1 zRd|U~pOc~0a%Uh(=$S>`b@#2$0mRa!FIw>|RY{X_P7Mh?5$M>H###vpTJc?kIYv+n z?aS5~JAJG9r`NOEo6DInAsr1|Lqf8*>D39hVw)ZkZbiS6+r5^ATPcRi!x*liU&+2& zTAgq!#c+8@xQ2cu`)X-*!mSj;f>x5pOP3lFEVnua30g@WZza@_VExxINYG01cx$JI1lw^Pg9NQ4 zkM~+?NU%TFF-Xu#vLCf;f*KN!I?$f=a)ggcg-IiW`>L$MBl4THqkTwJSggHz_xaZ6 ze=Uw`x*y}zV{eEuV`svsItB^l&toU=9)rGU#S*DwP(woXwDJ0&6>GMRK@ADDw~emXOdHXdjg#(f_JPA6n@tVE1^; zfpO%k32I2x?>>9du_rCQ{qr|pE*9^6nBr{}l+EgqzdmWPLDH#op*3c2IkDk`G#MJvctOZ(eixp>_3Ums&o1G(cnG%AA8 zr?i4>G46NTix)qA*F`Y~HIO^LPop9jeM&3H7USM`Jb&@xAO1&-K@H@N@6)IVMxW9O zvc)+6PKPai{`|YzF|Z5NK<@Ykj*4LPDXkz|jIA!)f3fd(?h|8B1G(cHI4XkCr?i4> zG5+-_k6OI!!w-)!sDa$oZ}R}b=u=ujwiq|xvD4zZGxv!xsDa$o@67z{kgD`E_4Ab0f>Hb5}?lva=}#$(>`sP%t- z@T z*T0yoL|9s{PCx_qV z3o!;YkUKt&zfI5zvc>rMO)s1L-;3TAV^9OR<2wS{1g#)jjQ!vFzbAio!V_Z*Y9M!f z*Fl@06=aL?f%ly_`JXedkF#)UAa|eGaL9bafuD)1$u>bN$QEPYn@^hj;Fjy-yqy}z zUDq9ID~b3v(G>(W4Z`R?##$5YLtj~r`Plj5c;0W?TuqopA5Te^O}N+jCoMkx%_rea z1kp++_DO`+3H`f;r)`2(kj+cK{@6<%sewGzI-!39vBhW+w1RAY|J2qW^XI=l#-Ijr zTv_yQAhsASLaPb4f^0E%wDre-zw4qHgBr+jWzoN_*S1E1yHf&d{vA=4dkiT3H_D7 zX+_X)T&1`b2<5}pA9wlu@i7K9kf&NFyzHs_dp-(5zj2k~Rv;|K{Oky6t@ClG5YmKj6n_Lsn!WwzVpxf7$E33u2S3zgvHq9 z!0F_Q-#sYCpa$|(>x6zU&a@)vH?C6L3WUYD)Yc#0fATgl1~ri5I-%c-V=+L`Z(Lcp zl~xvI_fEf>(3~Mq19_@-LcbTsVt}CExJq#=5a#&Pw*ENcE?~X>qV+?8_Pqj{X z)+RsG+F)7{^cz%W2_AVHIOasWu0Kx zMgH)l$&Dvo7*|E z>Q<8IZ!c64W#Zqn~>C*Z2D3rZ0#wNI>q6I_9&pOAfiYk3pi= zwsM05|BIfztTTQtk8H$NLUQ@zrGI!5|BIGmprWrY8r&a zP#*fRB#?mI;m&D`L4ukFVKGz}{g@a?K<-rEDs3~j7$m4^5C*ADsil}0NI>q?Zq;g1 z3=-5d2!qtp`(sof0okn7|NPiRf|>?VV)SRc=qt-HAL_*^AAO8S$Zye%5(a6k(g8gn(0Dh3J2eY?7{k3k~UbJ8>j^Q&WrjtGiD0&?shIy#ui zv?kPEUDF^8>ib}fK>~8@wK~eB7$ns1T+<*7>PLncg9Kz*&C=0Y`5-|}gD|=u;bIID zkmIi7`k(HY@c% zk3oW(29aXuSlgEsePuZw&poyI=o|_4zoHo>EXIRRIc2Z^*OwIu$Z?iYN}YuIpKBU~ z#pq`;F;yfWo7I(QS0t!u5JvYivc9b7E6Z`7=)IsO)c=ZRl&~1qqcj(dF-Sm;^IiRK z=F^&xf7dh!gKR9B_*g;$azEGh@rp$1nMuvK#uDVm3GPp3Dvi28iYY_ zdiC*>Q*S#zj=LlvcSpbW;@NG#^%x|mX%H4;-LGFcdGzro#uy|Z$Muz3X37T%^$piF z2*pV2!FW_70oknbN^e>d)HDdAFSQtFzC5it&pvB5_v1F?PJ58`79TUW7$m4^5C;9m z`uK@yUQ+o2-JQ37HrKmDI^p<`2@ElLX{$>sQR@dUI@wL4ukFVbFm$ zY&H34zvd(X+1|A_pX;r@DFz8@8iYYs7kgQqEKIC?f$qNbu)XJc_iu_pf|>?lkhQ73 ztfj;lBp`Q(zGLsX-rk#Hkf5eP81y}?IY~e^t9|UbQ67T?H4Vb(wXePK@^jO=Hjsea zef)*{ARi=ZO->03i}5j=mwc&TbCQ7E?R5P&Ny$0&=(IGxx*s zg9J4V!eX3aedDcfipQux0&;iMk^ALiS4~jUAWDpQtR(?C=0o@7nE5ovh=lyQra>6= zJu9p2PDyJ{5|CqkT>6Y_`xqotKCWpH7Nf7hI4>aqIku~_&-y|igM{kYH4VaI^er*Y zMM*%8{p0>OU(?4Rq4w&U24OM!9u;GdfE@ez1yAxAB-HO*(;zH{&2<<5X~%RED_@}F zc=eU9`5caf#t+vt2=n{!=X`zr)^~nEj6ni&9Cr_St;ZmtanLml!eaCzb&Np*ay%N` zw6Dh?q4C@`4Z>nv^2Q4H4VaI^fSv?RwN+D`L6fon$Y~yH4VaI*vOzcb&Np*a-6sO zs8kc0N4us$SPUECv^I!iA_>TG{o$i)O=vyfng(GpY^0v}*iHg+T>JP@q9(MiaZQ7; z82!pC9&t!O?yw4*)&w;T!eZDwbn>g$_%+BiIHqQ~d+F9|=BHlfYc&$JW|XiP3oEM! zy&+wLBmud5_`z%DXTHeSI3%cP5EkPGtMlFaYmg)$cj;YHU+s@kB&cZ+7UP%JcE8_W zgCqgD!yS&(nxLjZSd8;+J-D`C50Ze~;T}wjL4ukFVKH7}{qODldXNNUn?dF~KrIFd zY8r&a_*WYff8MVLNkHy!$En32QE5s_NLY;L*xYJEzaAt3x%=loeU#skZ!t(v(;zH{ z^^M2&YqiQ3XtT=q?OO~I)HH|`1M5Nh%5sM%3#1sCs5PU6#ju>O@5?HXfZSbu@g9Dk zu*D!jO@pu)R)g#NIu9fuTf2IU-&t%iNKn%tEQb1@^}~gUfdu64GmqTU?@_iGBq~iw z2?=v-J!;YS!9W6Xcj{O6^n0Hz1_^2!gvB_~*0g_`#*#n+a(D8R*V=gO;}r>N8id8L z5pL0siGc*YjOM_K~00O80vrhF)EONY*vrO zv5N#X4Wh(|$66AQV?IvU+t+G+j7Z3D(d3knuo$1TvO4|^X+1~+a;%Tz-tKE05-K0p zGzg2K{-=@D#L5@wzFqmeokXhVq-hZ5_X*Z^kL<5Ol7Jlh$1Bgcxua{@bY)|Yc&#(%}Pffk3oW(29aVs)?<)>9FM`C+L)?L==fSRIVB`gS?%RzMFMi1 zW#m#<>1IOn1lKeOi(xgmm)AK7$krAfky}qqP}3kR#^yGM`+C0~Bmp_j6TKJIgywBo zQ&K|0VyORlA0z=e&Ud{x*M#Puu4xb!bu#tM=V>=1RaUE5T5+t;)aZQ7;7Ce4(dMm}9x);Rp6>_I%L-z0VwiqO+X%H6UL>sIA@uajKBmp_TMXP`7 zxWyo$_eZ&=L0F7Stwib~>p>EbJG~30e`ETzCa7r;7UQ8d zCVstN50Ze~>8&*VJKZe?32GXI#o*OG5|BH+E2n?wy~Q9wO@pu)b|o&a2T4Hg(tDnc z@9TpEH4VaI*cHXR!;}Q%PEV{W`5-|}gGgnyzQ2|lNI>rNexy<#y6WQuH4VaISPic4 z>pYNv-02NYrCpJrra@Q?YrBiS?FJH%JH0We^bZo$Gzg1fJ!;WkqYoq?cY3c->E|S< zX%H5pzhV;CwIm>SdJ|C@uSihSAS{NBaEpFS3?v|Tdc%>At~EhTgRmGjQZM?kJ&=Ih z=?!q@_(6i224OLHeUJp?PVc4jV^>X3(;!NWc&sG>Ip$;Xlq36o-lr-O^6Q!gVKLrp zW%cBf(t3~trgD|LXiE)iX z0&?shdSYmbK|<}-H4Va`zDLCvBp}Cr{_OWZr;kBG{mwNF!eaCzLySQJavZNd__1gA zF-U0qa7}}-82tzrV~~Ix$K7?eKdX;HLgS!o8id8@N9q`Z1mt-9xcoGaK|b z=#Mxt1_{XVIC#{N9)pCAORi}U7Nb9M#uy|Z$K$!DwkC9ZbxngvWu-kuF$M|9abDu3 zp63ja&^*C44Z>nr4QlQ)AVA0YmA9Un(0s==4Z>nrOVk`L#vlPX&J(>C)P&}3u4xb! z!+MnVs>K*2AjkQx_vV_={L?iJ!eZFSkgpGtfE?%AJ}T9O=FzTc5Ei4K>BljV1mw8> z@X@stFxgRmGjQcrwrCjmLGqx>jQ6I$1}ra@SYe&rR9I3yrfYq*-g`fS=DEQa=^ zu06@G4<0jHbJN}WaVg8))dwFld)#4L^xu=HHKT;Z_>T3zJ^OnUNkHyCxBIcP!#=rX zAAo4&idcW`}H6R$lWhLa-8LFn?42!Y8r&axT~E@ysE!GNCI+q<40aH+xOD# z`WPgrX%H6Up4R`qnD(kwzCd?B+4*I&r|-6XAApFZs&GwpUlF<$`@$UoZxR{ zo7Mz14Z>)hkLj-!t?-roc6j5I#UN2@MhWx!H9K?n}3CJDZaAh$_P}3kRhMncq z8OT^xBp{nrnC*Vkefs(!K}~~5F?8-#F#-w5-Km$o&fn)Xjj75+t;s1NVU8{5>-(|_ zBp`Qqr=GP%`XC9&W|iOJXE8`n(;$q#*!tgg{eDprkh@cleIxn@iCU9W zLc(G^*RIdMG4;Vf0&=(Y`ENo$CqYevuo!lhb7AL2W1W+L+--LLn=xLIpr%1sjPKfd z@V8bcCI%9ayLCsr1>-IWY8r$&wvl?#kL`g30UAqeYH$W-repcC6BHC08BEifnfrboC_!6o8~j5hfqM zNlob;7^*2TglUOi)Ip?B5$Vj7B12~0r<$~xinIe%v;~5x35_%Zlu`K*wAZ!HTIc-M z%)9=0l9lH=zkQvrz4zK@@B5sAkVnq&M(#rbaoktW_{5SPBz&Dq83=jgop?~#$^sqr z<5`dV@==@UkA&~nQU*d$)~N6xfjDaIwby<=JxI9Tl`;_W$d(~INFdf$uRZ(Q*FKOQ zB&ZC8=s#2a``Ab~jA-3Pwmv*|&??clC#dqP4Ux2kRb;~e9VKpefnm%jJY=|RHn zc_{-SkGH-0&U! zk>6P7iUi`wOZKx)!g)d|10fGx!5izElR&JkZpM8@g33UM&Kxf8T@r{Rx2syv3FmFQ zvh4{8d1Pi89wZP)j#{<36V5+N83=h~h8!Lw5J%o#tx_kPN0%}X^6+@@SMzt#1ie$& z{L?ueB!O7#kgq)VcP>{C5>y64P(I7JP}s@>t@YH8KKGY6wTb>nP#Fk8cWONNj2sV= zK)m=nrun5Nd61wo5b}7w#)HpYbLv(WXsvI5^m%?iN**Mr41_%1q59`%)e2i#ptVl_ zG3WlSqBhYV2`U32=m%bX%Z*RaGk1lpEYSMB!DG(-WkhYFKN3_1LeR4?9wdQSTU~X& zeu>c@B&ZC8=%3T`n4jOqgDh){_4|*ja2zDMa#=zinF07*ok$?o?^v$F^&mlIAXKof z;HA9g`u*Tu7GnJ#=W5(nB&ZC8Jai{sNyE210j!`F^TIz0y649%|t(vQ5-TEcpxq@wWgz6? z8RTr+_4~oSEX4ZV-8JYxNKhFFd2oJ^1Y-Su@S3gf>I9X6*gaxANCI&jhrh+G&GpCm zL6=*~KnU_k_=fHGgF68_u7|%!yn2xE`6*=}1mzWs@gNDrabNix#;XSjU*}Q=LQvj` z2ZgOH&{0491!QfaKN7xQOBo13|5J7FYjV9P3B*y){hj31gM{l{DFY!WTZT9e5{RR{ z@|TrY4-#%aN*M@2*}{bf3B=Lv`n$!e2MM=>r3{3iY^lS81mfsF{GH_0gM{1jQU*d$ z_Bi1|0U{lrv#&V`Dgz-pd(QA6fjIi}+S^XJf8CXBPe{lkGl1|QfjDxBI_sTq zo>0m_$U|4qxleeIKpZ(y-94RfzEjFT$U}FcbGYyzfjDxzss){J-d4&$$U`;iP<4<5 z;>dTaHh04LXDI_A548;2{2&R$k!x40)CuR&r3{2T)WUge5N#p}#4-M;*0mEJ50o+x z@=!~CsJ5L1;u!l>FVP8)Yf2didGy~8?gVK4esCYdb%M%3$b++eF@k)~Q_uD9BjOm> zzVb;=%m0(`ICEDtGF@pBDok%;JA5F=gCr2g`1~thDGw4JFPAb9@_4hZ`D62aG9(bM z^Mm*P)jSRo9`|3L%0S4&zcui04ivVsK*#fvFTASWpiIKgFG?8*m78m}!-E9kc#3n+ zU;dUn4ibJ2Q_4Wd!|S#E#MZ|_0~3+9sKoYJU!192|wQ}Wgz77sDE+i4L^zb!6HCwE6vJ1r#whd8Hm;6 zp7c18Kpf9^%RBaJBmBH|SGGMNA&>mUh|krD1mbw=yq|Rver{aKK&W8O_K`rWtzL`! ziUgH`5dBHjzwP&ft*ouwm^Y|e&OVlZ++DdWv7f8ROGqG&>+!N%zbQTPTm|9tQ_4WdBd_^G2+-@C-n~yr4-zq7m&!oM zBk#n6!d4dOs2@N4wdFy=_iHHwp>nehh6f46QP1D;qfgG`AmMsf%0S2?+mi4gfmmC; z_U!ftzA-&WP#Fl(*}{bf3B=Lv-t@-uAmMg!SGGMNA&+dS!-E9k=ndZXyz(I7_PmsV zkcWCT_c-gh0s&fEom2kAPK~g zW$b5N=V~LICzLV}^3WCZ+Njto5{R|c&A6{fP#Fl(nUUqWVp&@pxn0$QPB?GdmCF+H z;O_@XAdY;uYI7%?f0i;3^2iK1j)Mf^b$)PbuSmpvT`B`1kIeL=O(cOh#vj$XcEaO< zQU*dEIbsP95{P3|wD%GuJgzBaAmpJrgTo_F`}|-LptaRD3Oja!%0P(DHL3R~)U&Yn zpFMmzs+{GBc=21CzWP_59slnHm4Q%UeuuE$417spD+~1Ew>Evt*MDbvkf1UUD))(c zhu7y{u)bfE1meYSZMy#Y=cWeGWo+^+`- zDgz-8UBOFv%}*o{YaZuAxUWc183=jkPQ1u__e28m;`jUR^@9YJfslu4)J4|86A8qN z-|xHEa}rbrLLOJB{=F~9gCr0ye!uVDUXh?O5c0^GAGfU>)U*}Q= zLLPZ19u&5+Ku7&}^56T0^dRB;wUmKSxldIcd|%EFl0Y2w{8exK`t%^-dRNLo$m7$h zf1k+xcw+)AmqW>J`#wd-M#r!UzZ*v+zys95c2qWwe25Pj-{}b z1v+|z&pqwh^dRB(yp(}Zx!L1{2MNU5>b|p|`Psje9wev?#OmR`Hatimj{dy%cI%yk zaR0h1+n$h+$20UkC%>&wA(bQO$R+Bmcfxr>DFdN$IX_4OapXjG_jJPfPALN+58a7} zx_3z+jy$nyK_{HIl`;_WP>niN9VCG`^4+STFeZ43NDgz-8uKpx}c=4}vFTY-t%0S5DlX@QW!1`O6 zRu<^RztY{;i;|!+5b}7x`i>{&_a;anUi>TFeZ43NDgz;pYgGsTTaE`wAYS|{-F>|% z2`U32k8DdW6t=QJ>%MyN*}h(s1eJkMx!zOJy(qYz4*N%`}H6}Wgz6CD|jid`H2ML#qUSi?<*2i20|X0k;RddK)m=p zFMItUL1iH1p&E6Ob?`(2@#6Q@?Dd=km4T3lT84{kOHL#ZFMjXN-d>TQG7$1m3wM!i z;)w*}#qST=+g%b=20|WO{Ye7x;`bo!{Rasu10fHN2T34Se)W&GzN-^d24eS!(H#lI zaU8X(XY&Zc<(4uK^5E)E5{Tn^)as;8`23VI5c0??7nKX@F0OW>Upht>xAoFDFY#oY#G9X1mb9~YV}?x+B;1~tG7$3M=#B*9=m+=pq9oie zl`;^k$2J}$fjIi}+S{#njw5&fTFOAkBQt=95TGM3sk7b*=Lw|@ggi2n2@ev8BPXi6 zrxVV1N*M@wWJVSqBoIe#SGAxM&f7{E2zlg8LwJxt9Qkh5=1w^OEM*|%kr{G$kU$)H zd$mfPa2{RCK*%FA{b&;#p85TtpD zgZn~-tt`-sYngjFZF1}cm4OhXJoMl`U12K=^x|6P-ddX+J3(b21St=_(YcAjRu<^R zwai(EHaT{J%0LM6dTr-e3R_vA7uPapPuk?z2`U32NY6@ca6YQAl?8h7GZbfm+T_>? zDgzy649{!D&GjW9{5{MU%3-;?lg33UsV2?fWnx9A@UOc|p z?<*2i20|VlL*>1DB7u1EIBl;VB&ZC8JUkZk2+!w=1meZx&ApzJpfV6DSZ&Egwk0PL zh!>BW_x6eem4T3l$L854o=6~GJpSL?T@q9VLLPp`kZt>k1meZdG4}q01eJl1hv&|- zk2;Y+y!d%c^+@6;*5Q4JD2@ev8qaSqExq6Urzf{UVtRC)b!-E9k=!0u-x4t$A z_phZ4ggi25cnASHa)~y?7Sht4FlSu@h7VLXhX@z4Aq2D+~1E zS$MC4(I&@EP#Fk8TBmmK3Lb^6EYOQ*;k}win;bhqWgrCk_q$$+q_C9*dhsm0S0!na zV<)H#gdoq)dqtJPRu<^Rv+!PBrA>~VpfV7G)T?ddK@x};ud((jvDJeFm4R42w(%ed z#EaM4?Z=UQt&jXfWgxVf*YxGNY6R%T>jwAhL4wLa$iwe0$!mThfmqK)pNsp71eJl1 zhu2uXobtPb3g8Ua!5k zS0tzmgbMbx@QPe}kU+e6eemAylAtmWD%fj~y|UOIBoHrN=e+kHB&ZC83g&o_1ma~~ zuZ=!x8$nVTh}|RlS`vukIJ`P|}gwIbY z10g7{V0e%~9QT!1iLD+ae4R@f2tj!#9u&5+Ku7)XDzVjrgzwi<20~EQsPG_xIO@4q ziLD+aT<=O52toP|_J!B0DQsndj`qr{#8wXyZa+#H2toc0i`T2!g9PGecfCq%^&sJP zu#|xilr435kU$*$hgXTM9wgkJmogB7{7o{iS5w%^0v-LJSEa2UB-}5RG7ziB4dp=s zarEc4x3O0n;r_Lhfslue+&M!W2MNTHOVnBKg!6<_20|XXf;ZMRCxJL}qPlxJ;e4l* zfslv4;a>MH3B-}xRW0a*^R`k3LLQlm#)HvA2TBdPxTU=@VKUwfl#>|50XH< zU=()j1eJl1hkv8!H$f?kv8CVTq%h_OGmdes-wNgbcf#Y$Qat{=3?azx_w^gC6t=QJ z$N1cDx6&rZPI$ar%0LL>c#s6*e9mxndXQMh{i`w%^6>kd{Dv`wtt`;-yu@!C(ZG#>Pu(iFC`K*w_*zco#p96RCXFr^HHplnORg9PGue&x5ntsW%&JgJm{ z5XA8y3B>Un&Tp|>JxKVuSSbS`=)v=YMSzayiGCa3>OsQK_evQELF(1q2>7ECO`Q4_4pR3D4J+ zG7$3c_g?&dLxrs@&~Y4otDrVHcEaVBG7y6NE@Z#oP+= zLBjQ}lz|YGZAo~LKpgFr-zvCzkZ}7^%0LLpHZeR%AdYs|ZxviUNVpv=WgrA`wvPnj z=s)~c!PSF=+w)QeLeRhZu{-ba`wbPgvOq^a=(iZI9wgi^l`;^k#|`B{0&(=`wYRZX z8{z)7l!1`PgXaf}03CTro%K#QPbg&|3j$o$yN4 zQU*dEY8fuFEjf`u9KX$~R;d$Saa+nj$U`mMMYf425{TpXYSp@S!YhYM83=js*MKAt z$M5c{&F_R)K$kKQ@=zajk$u#O1meZ(wX5&y1eJl1hu=u*?_n!!Wr2?4@K>m{$*~hI zx0Hbpl;qu$2Wm z>W9BVy?T)F{aVUE2+BGb9wZP)J@;3rR}T`dccl!3plnORg9PGeulyD2)q{lFk5UFg zP_}U4K>~5KyZ#FG>OsQoU?~G3DBJe%Ab~jg4}XPv^&sK)yp(|uq+ZQ^RCtg;9Q~lb zdcAs(aKBW_K&&2q_8J}}5J!Jrd%N|{LAZY{Wgz5{8Nfpb(2+~jS?`4Ngi;1V9=d|t z_a;anj{K_bo=!O5DPq2SgM{bjOBo1xT&Xn~PtW(skU*U81pS-YUXk$p{Powb z%0S3N-*7*CKIaEXAddGfefnRP2MN#5mogCYc%J45e=6q(Ng$5*M*X{wlm`jV&zCX~ z^2oO2LSZWlv~r>koL%+kXXm*hL1iFR?l->ZcW?YR>)4=`1v=j2^}T21LBjL%r3{2T zuGZQQf3exeK>~5SL+oq6zdT5Ie!i4}P`Mo4kwC1i?mK(wOUi=;m4R42w(%ed#PNQ( z+S{#n_K}~w5^qKkcY0|rM%`R5{T7aeF*mz2`U32 zkIcy8$VniM_YPJq=!92zmNF3XP>s6CI(Q<1INqOFwYd{ssancF$m5@Ae())|UX%pl zcz0v9N}cdZ?otLq9=;Yn!wOF%5Xbv0t99*!R}Pml5Gq(L^+mSrClZL`y`0rcbiym3 zOBo1x z1md_JAAf3jkns5_WgvVU>ot$OgaqQauRicw=XD$)e4R@f2zk6q&oaJ4>(vytvOq`u zxbhX{LBjWIDFdN$Il3c(IO_TLJh?nbxZagA5c0^jB#wgw;%Kiv^?%RyesEi1>h`0Q zfsjYGaN$7$akRT{zf>M1+zys95c1$`9|^?K8+_(1*qBvy_35$K#Y! zU;R64TS5YH$;qgYRIJK@>( zQU+o_SI$dXS)k*4ko7crJ6Az?e!i4}P`R#unftV|K*x72>#2GtJU?H`K*%HS-3uQF z3B>Vz&YB(Qgy-i=83>j8q_6tc!*4udT`x)kaeQZVpZ_4?`T0@?LLM5^9yC&o;~;@p z`PHM(Yqq8nR0cvG*(Qbu3B-$M;cM2Z6I2F59)Di*gSY1VAPL0rHQJgz>xAdaOBo1x zxc;dg#&M89tgWs(-{%KOP#Fl(ejcOeGWIx;Kpfu_uD$JqSI_OrwkIT1@ZUJya_I+i zevky>_%8B(JxF*JU?~G3kIZD^I7lE?>vJ{kD-u)&LLPn|llSh41mgHkb=87ScvWU8 z10fI9sEe$FClZL`d)rl;JK@!(r3{2T)RtVRAB=NF0&#rnyIQ4AcwKEN10fHN2T34~ z@1Ixe+6k`@E@dF(ks}tj)F%>%<2&xvOLW5PoJ$!973}(_S{36#5{Q+zU$gaHouD!h z@^JlAJ&f@n3B++6^%S=gF1M6{*w0nuB_t5X^{A)O+qnwD=ckl`kO#+uBoN1aRZrDB z;p<$=K*%HS-Gjnb7U-xSH9OD=->;<%gv!l27#<`LM?J4uj!wAVl`;_W$hIUrNFa{( zs%C3C;r64HfsjYGaN$7$akRTN>(mLigQX0FJhG(@4-$x@H>laOPPjcUWgz5{eN=dm zK&-8xS9vlynKpbPA>LohiaZM=$ zA&u>lFFRo>-#oGMX2`U32NO|bNZI;4T z7U;#b%&n0&Id+1|KnUV^kObnzwal&R>Oq3aKnUV&9|^>ZYngk8)q@0;fe@rT^x(cw zVJi#t;#%fjZuKBRWgrCkd5rsXdyqi9xR$xMUOh-q83;kyCWZ$I#EWa0vyRn+1eJjh zq^F!WIv-Wo$^yN(mN|P`JxEX)2tm#fbF9|N0=@VdinGAgg9Md<5ae7p$DAh;h!4AVFmyRB+}#;XwlN;!(_gUy-0P5c2RCD(~GB3B-#> zV|)D|L1iH1;jv)W!4nC@i$|4vJtskBAmrgOt@BZZClZJkKabhlD-u)&LIvm8!0qmd z1meY`{Jq^JL1iFRu%9tx+kPT}c=6MUz5gIVWgz5{W3?C$l0dwy&tt0pAVFmyS z#L-?k3tT-&xcw+)AOvL#7ak-KN4x7RaP=VJcCeIz5R@%-c#uFG{fD!_)q{lF^HK&v zkmn3Mcc8G91v>gcXPv7D3HM8-41^%(y3Tp+K>~5~!L_%YaQ|A$K&V_DxpRi_Ab~h? zi8||@aGp@gK*&Q^aGM__fjIK3x_dg|e5aIwkcaL>=WuZxBoIe#SGAxM&f7{E2zjVR zITsBN5{M&5t=ilP=bxnvggn$Tc+FjSkU$)Hd$mfPa2{RCK*&Qaoac(7O(cOh#vj$X zcEaOqYAwZCkuN_VHghd&`UK-Jc}7a#=zi|3&rhPjbB|3B=25e*6n(ueiJ3{Yiq# zK*-~(v|jY3xn7h6;^l=`d{M_&?|~#iWgz5nzwX`7=6X>Qh?na=@x`;3U-#Sjjx7>Y z20|WxsP&@yyHME50=?Y&(J!5S>RI7YFP9zX7AG~8Z-;aYtSGGMNp@MYe zm-1YlNFZLm?fDNo->(M=Dgz;pCu(itZR<5ZkwC1i9)7;xS0tzmglN~lymwC|5HEl2 z)`y?(^@BuLwml&s57)n}gC`P*mzO{45$Ah7CqZQ(b;yK*6X|~10j#R6C;NsfjH{N ztsni(Y!gZNel2AnDg&WSvggcm#j>_I`t#b`PPl*FmCF+HaQ*Z9?iIGOKu4CbpLG(> z6G|Bfm7AGNc#uG>t-gG=-&Z8441{RiiHEv(Ng$3qv1&mloVV@DwkIUy;o4L+iUi`w zQL8q0!ue+@10j#hkmFpDK%9AdwO1t8JbG0ILLQmvN1I3jag0Bzb?t=51EmavJbX|2 zPEpv(0v+S1y_X>2aZM=$p>man9$ZK4K?1RqZ4`Fw1eJjh{d#%)^lNH7c>CFNUjDXh zm$rC$+~aRQ`_u>Dp8qG&mCF+HctGdst@(aY5{PvUZ$G=|DZiW^B&ZC8JT&$=s8(H4 z*vbOEyy%KMbbRkf4-!-cLgl*tWe(TM0Z9kDfy!`&}U7-IUL1iH1;b$ej<9)73AokIs z?;=5EAa;-FYe^uE<9ORw|J!U!(jy3$yDQtCkdQ|ndE^Wv5XbfS@EyOD9wdBzN*M^B zh4q?;2MNS^U%e$gNUYa+RR%&Hc_$tewz5D+{rF$s{)_2B!uM+_1EF%WMui6n#8GR1 z=sVw>9wc1vN*M@wWXlj9BoJ$>yU%|4bX$6mpfV7mUH^23!-E9kXm@|}4}Kv%NVpx` zm2FQ*$iwwdcS?AWKpefnO+Qs0B;1~tG7$3M=#B(pZROslJV;O(2+@5!$g;LL`t#b` zPPl*FmCF+H$S1;au1Fw`EMq_GB%CLdG7$3674)<4@F0O$TfH0i6$vT>AzF8$pXuj) z#j>_I^2DkIop9c^E0-nYp&Etp;7)*!9JOk5C!BwlG7$2}3^|U21meuKtGyzz=FzJ% z5c2S~@EKOv$^so@hH70q;qgEz1EF$V|5U5Og9PFjNA0}?36E<^83=jg$SZmr5{R|c zHVQj-g33Uo$JMv&@BN4{IN zxf9MmOBo1x+@bpS?Dbv6F&-=ebmZFADs{qnbSVQN54CV@JXi$i7=Kjj+6j*bN*M@w zc+NT7_81Qq0XjxSdoMx4@+Hy&|#Z(W^2L@=y!c#)EggVI@Gv_@i3aPIx>}%0S42qdO9aW9+l{5+ppX ZDPwo>v)ick>eeQEV_kEvp?sGrqIc;@p^#fjAO&v`D z!Q}{a1OT9 z4>1420MtSPe{dso_+K7a0wndT?Ka;xNctD%g>g5e^hf3lqz;(=k%It`#(x;G`(HT_ z0O9t(>0tHF!QXfX2iy**xwtr91NMg3Z#Z8QmXh8kX~P%X>Yuxm>@g_-q$Qv4kA7Q#comZL2N&Hr@SinzME}J$07L_Tf}g+yi{V{8fk|3Q7R1K>hpE5q zl9H69LjTCz+5&)z`0aJBaw_sSW^aDF_uuEjy`B1xEzq{>(-8mCw=wd6F!R57A53TY zAG-7}onbv$-=)d?(gz-6tet5meqng5vi7H0{>#5THvcKxkMf2uR`_E6zxDC|jV2)} ztsp50!2fv%hzpkiFzW>Xe**xqBmfLI0pPX&=TW~#6yNr9P~Vw*S*gr_{Tg|~_6Ejq zpZ%IU5ZD3NZ|lSfYrWmqFhp>`TEiGzhldLX?781O5Nz>pTn*2t-?#zh{*58nvh6Ve z&pIY|!0`*iLYc^5=O3Q!r~T#!VAmfEfq%x_L6|=g@cyB*fjz(UfoBO*1=tI>_@y)R z4#5A12Lbl|?gM6Sfc--UK=>COmdU&q?EgI$nUw(U7Z0o(^C@ufk4!yq=ucZD5dFh% z0uKM7LqOt>Obc-IH=RcX9Q%!7pC12%4T0nzIl(~YHyt+P#BU6H`Q#sr1hT&|a}bdG zjbR>z|G|oXFaSz_FcVPygCU^y2Lqt{2mcz4m4E>8LepRdG=cXZA3O(7zym-A761b@ zV52?(UFZO`0D9p1YES}RfeercM-fZd>6);i29O~n2CV=(_y+1hIV|BBpn`aC4ekgX z*x(D05p)dN1S8-(_zY@5F?b15!9(yDTz?iwfm@I%BnvS^Q=k{Lf{(C-*T0_N0@t5| zofH9?L&^{bv;<4&gmtI_Z$UOl1~=h)6WBo<(0S+-v9AOTpy!ms)o@D7%K53V-=cn}3k*M^QmDi8}a1N-0$s0F1U5BAV@y*x02bfDAl zqQ?(yfKgb(FQ5+AE+6&)2I#}>c_BSW0q#Kn&4FRKm%hP1tb{d41A@Qgw}VrV2wc1P z%l1C_w-xS%LXZxG;CcmM?c!+f<}NAO1_yE`W)>8ysjZ`xotvqLmE+B87u@ZguDKDd z9Iu&PbGbphz6;t7hgn+o7Y=(K#YYYBY+>czD=2#OI9?f^i`&z2JBDnR?RovbMHPVE zM1Xk2vbDuo0Kodl)>fH10M&&s(_Z)rf-m3g`zdLS)3SI?wWAu6Qm2ldkUA-S6fb>R z=BTuW{0TYD)0*lUn(}{?zPbyecFk4O)ORmy?t}eN;|TU3UA?vPadVwCl zx9LoO=(RA~cFaG{VfjUe@s3_tgJ1k-w)uDdp%25o{)>Kgo6h}*J_YyVe{}R8`XU^K zw{_T-39m}OisV0kgYBdTrgOt97O;V@?e^PxZ2JPfv!=p#8-SD@hDo_F-YyW>l~w|P zFuY>?dk1g~|HZ%c1DuBw!~gO@SPp^<^6j^62CLkfYmf-|^nkxtI;u0~qw!sjns6h;lh8gAPF z7b~Khi<+UK-ZuVy-^Txy#c%)cwjSM{>i;M0jd{vY4}6|vdCa}%yv zhc8K@i>o_q9Gq_eLr-^?ZR`hQURPKt7{g-|@Y?-@)3&koKe*@@kBN~6%<~Dx!o=%V za8E!JFg{}aKXkkQ!A_1hx1YORwk_qj=4=Y567Wh5;GlF0*aJ7<0vv%AoZ$!qLm>12 z!hhlyzXrGgb9)0hPrO-P)Qz1P`ox0Bl5WZLK}s+S*8khfp^F<<47O;1)pq zDo6wzQjthFtTMrc8O6L^P^_q5h4tUU_N%aOmz{qK1hP zzP?osxLMhoxyq5y0f69!klfH#HS`qjHRkO%sXuWM{Eq!Q*x2F84Iz;TCL}YgHO%S1 zo!~QZGxO}1Qe)YD&I)ya#48;f^Mn#$V^kqgw#@aPx2iu;#X#RZ%4~ZTY6F+fM zRt_((pmFN7rk1vjuCa-!nK|rsqRlm1yX*E2ZtgcdJiWYqLT}v;3%_$WBKBTf{QUGuHMO+5`i7R)wy)pXJHB@g{GbmG4UdeD{hXbf zXDlo(Ew8M?+5SJ~{ITeN?158B2*JdJWI}D*10g)Ojpb%y-Y><%qjnBuMcREpI+&GL zJ?2SX#SWZ|(F~up>ld~?A}0n8&TgCZ%cB2p28I0pvgnUNf9%=n1RO{>h;t*k;Vf=d zMQeX|!>tL_N1Odc_@7>*TH^){`|m~DpgbDgny!r}GE^Vvl0(J{V?)Vy@*{~G1`Z^V zyVjA~Sog_(x4tgCAgaLa5qHq8cM1XXmTX#(!5HN`Et7Ab?vJz0hfIQ(UIW^5j~Z?L z3yV)QakoV=TzWH-_!^D<_^a{fxeG#8J?b%@bTVgt%WjWD@oztQqcNeIOUl_x0?e<> z_K2Os(V2Sc?ONrl(<0#fNON-17T7SI?8TpsIv{NvAb`VpjfHp*cyAW`xcDxl z^w2~QE5^UK3YjVBKi*Nb&N?@~Znuw3vqT`~USV)$yMJo=u;gq1mW0j#Q_(`*{x9*b zcPGY5vIHcyUrjqUiu5!j7$@3|UDB&XN#)Ls3|sKX_PYcmFlwx`PeqHFS#RvcarjvJ zu#FZ}JdA(JlxOh))qu(sT4=iDN9KCPL5eJ%Y-)LieE8iyuQoQCbEtz)VHbgh9ZA1f zywN1^_fF~>saAFM>%%lR*GQKa&(!GDX^JXm{0+l8o>TqV!a@EeyA%VZEEZI7Uh9WW zJX881jB}F`$m=WOpFaB*IedU=!INuKJ(>#Gp{q*EuG5xhyj_Ga zhewgwwcSu3iseJptG_3?pWo#by)RM)r#iH5B{DIOk)xY6PN}SNY=eyvzg}I z^G>-_Ik9s^vZ{rH$_Grnskmb zF*;SbOm`j|(X9E1H^#|o=wqIzQ2AjHa5eJs@w>Z?2kbuW?Q<1#l`ZO2-uon5eMSI} zJ*J3ZvrT&;I+w8PizgB}3=%n69K7Om&_}ytN?OSr=1)nutS^2UNto=T#cwg2{51~C zZ(Qvi!mkUjH=r(;d5R_{m6*xi@_T>pcHIS5aE#EDA>mddkd|jOfWs+LdLM_O`XwG@ zH%G~r9=Y$W#9|Ru9he+HhUG*&cD+U9#;p2s>CT^_UTo%=$=>Mh=la3OJ-ciX@nvIb zoS*(`n(-sv;FhpYM(pI`Eob(mQc|JR#^;W5w4g-Ci3wIA;qov&4ssADUbzT6a7D+G ztE=U>0+S(fe~0>P`$iv?-u2Sw+oLBFdUsC6+=e1X+OrxcUu$GC*lNc1sGe9Mypb0O zx)CQ!YR8b;pc=v%??`8y#1Qu3GG-SkIWS)Df`;G7ec>79yt5BopR^C*hAL-1?O02l z8@q7-KyWCJ-B7JOn~pOVPS|5iPj>KZwD$LkpsqRE95o}^heP%cLdi>6^ z6&_CH(^qco@^zyWKVRL`cAIF=S8mzGqUl-{d)DCt z#D4|f*<@FedUv-V-mqvS-FxBfo>Rt=!}|VZDiY159c zP*v0xFcroLY)-p1DvQ1FHZb&}@ks~2@sU;Zoo`8XN)H`D)5g@1`mP?SKrXm$Qz-r` zIk578uX9huf}koJJ z_4ip^AJ1#Apn%tNhXj(0!wAxD%PwV+q)j3Iwxg(-d)WD$k?Q?sJO0jAEr}}g?`w%a zTmIvy%3pUmrFD?&e`T@r?v@sX?*8;13tssqm|*(eIu*PN+)pcT?oNuW4#&z!I#N2y zSA9+NT2S3(uVx+u)}B1w@p)j4!>#s|XSsPo)sT#cH$d|Wp&DHO`nm3rJa{IIUAc2DGXqB(;!#$(3abt-P2% zU>4h#WmYR7i1Igf2P$|XN2ak{jJsYy zB#o=#O#tr>fofOv(4B*N^}*|EXC2p1pW^AU6M2@FT=AGMekM-a?_34bM|)|l;5zF9 zSj}UfRK9%MY&wFa-B-Elvtd$mX@nHOj%oJGjKMaLusO~d#Yl#{o2uG!Z6Nwzj zipDZz%f$^bg~(_A@%iL>J z)`VSLAf}FywP|6Qh$zwb>G$z%8?;RHa1>k2ke(kSC$3^Ig2=y_HwIQZc4^{k_H&q{ zw*Y?ZEO+AW#6-_At!E43s2g?7h~)0zlJ=*QLiq`Ndu+%uqIXgHYoLpS8nwOzIS2sTG2GjUtz&_r1+ed zmBjFjThCBSaF2o#Aqs{&+(@vlK6A{} z+}1oae-S?t!5XWex_epCY-Z?VY2JEvN=f3)$wc!5n^#&)h%W0AZH%Zp<~to88QlG$ zkaTb0qGPZUTSw;x=Z_DGcI^?lKLU~OE~pfyeij@~?$VBhBB_k-vWl_VKsJsEZ@-xJ zkD}dZVXi89^lF>sdIwE;c|@qd_WUQO0~2gitM_kc$|~{ZsCxPh^hY~PuGN&(7Wnp( zeeY1WzRL6`Ew@Je7Eryd>cCPyTAoRjN3NW!AP1K#yG7EFAC&R5mUuyJ&By?Y$t5^# z9b3;r{8(=qePuEAdbt^nbqDR$2+&cbAj!SR0 zwKHA^^~t1Lfv8BzpVg`5rP4)n%T{<(yj@6%^9x&G+z@%mqtmf+x+s0WH(wOnN_A;toloSJ9cU}Cw^@G8ECm{X>CdR^uU>Tc6GcmMzYRt&5yWdi%WB8F9jUSo4NM+Sl$_Us3 zf_PLGnn8_vta{j0!PB@)r7~G}rrHjL?O6#t_7!!?M1F7!?A4g^pCz!j*T^7=M|^#ACvd=ZS&)$3vS6fEnU-4Go*o{pS{hlVcD;?CLYp|P_XTdEi!Pi6APyq;-bJ08HI zGCh~p{Y352^}mh~MU(D}AVaizSK!p_I=boMe5^En^nG~0cMtK3G?Y1I<)RyW~*iKsHaL$P@WV0_}?0Sd_-3He%38DHqv(0#rU>r3DsK z=zT4T-63u(iwiZX*D-Q^%KnEdnA{cL3H2FN2JLnp?oD&?&E?g)AA@ws%pt9;*`*(= zxi_>DALZzms$8?*Kf5G^Kr_%!i3C!_O4a+{m7)zWc2QOa+T|GEjj8g58Ur#a%2`Ek zq&4cXP`UNf#_0!?a?BR+ENdPP+HGY~Ja7lV8HI42$P6^9+Vm3IQF$Bp%1D)#AvVM* z-C6Ox36giXQlC#r*HPp^mkIPkHekBp7udMxlExu99i4w#~bn~s<`Ayld|%akPo zD!-&vvd-WX^AZPzJm}4K>GsanmyHt&X4Zq^BIIH&*Y(skzgMv^8=^#W@8P%R5}y+8 zXRgN&x_|aKcX7g)cgO9Y&r)9TUJFUXav>7qWhy&P)NsBd|CGdFZAsB! zG>d|JtyD|FUUgE~ns_|w==8l-cr6%}_)eXPy9Bw&Fox3}RN3=vju~Jl1NfBsy}X({S;5xTZ$e2i4EV};NYyll$;SmbKF$_%Mtrb;Nj^K$1F@Cq^E8^t4AGj(ep zNj^FCcTnK_jXvj;^wW`?N9l7mv4kQcb72lB-!etx-k3?6K~Lh-Ft;G{5Pt)ef|hQv zaA5`R5~_SZCyP{6L!R9yGKb~vxx}06KOI^0Vpx|nC-;AEh@%N7Z-LAKL+uP{SDJ&3 zi(-m1{iM%Lf?OC<387%gptU}Eu?31sZz6}9z$&rL%=Y&FprRvkKC%Rca8!oWIaIvs zxmN;MagNXwf)7`^MXWm2QNJ9Jx|%mlPjTqJ%+CR6dS+lt=qcf~rvw?=>B+Ggb&dVR z!e$PCPTc}H-rmUIj$Q z$iA(MInL~xh=Az0T!SHF{G2s2;aJZG3#uha4C$&>DbAuSt+ud;&1?xeU?F`Q^2lPI z?Y4dDRxT1tYTlUG=b|ypBUOm>Y#r0zPv4IY4UMMdaNTGLLZkFc!W}7+3a!#Rj(-1e zMbkh~YN{{ZOflRW*N>UF)$unfa(1^p>^2G9 zMW0E-iF2A*&eBAAA?`+($tdULG+fH#sE<#cpO%yTar+I~*Y>t$4lAxhs7x1x57l}M zl4wQ!Mvkobk#?cb-ei20{A2}wa*V)qY~e~-HkEZ1@WL!?KR(f4v>@*pw&xFDCv;uPvz${duxgp8pf3l6n) zg0<(hsxRS>u$N3`xKIYN<@0plThJCE8r9kp-y4eR*}w z#4T|PtVS}sbaTbI$}~q^44BVfFLwv-<)SGqLA$JiMrFE5%f@VB;C@$A11Zri!~faY zwAWdieomghpj9EB(r#!HpKho9oKi zh$8HMXpPjaoP8aU80*#5jO-Y`SFEfcq?(RBb|yHe>NbNWc({wgItazAhZpPv;lmQ` z6s|1Va;w(`Pj4@4R*ORUP1EC=H1^}h3WZZ2>{PU*cMVWPGeJSi{23#|3>3T~wao|Z5PeIEy2#lqO9!(xfbjDY zPW6}pw$A!NxQZ>I4oOMHjs)vZhn3fYx+#NnsBjNW(Jia=~}Hk|8#rbEH85y(VmAaNb5tkGWw0< zbu9S?O=|=j0gj8!M4i}o@ow1aQr145JJ-gp-R7`v2 zZ_8DHasc+sTD_*-(w79GF}=Q}RLe}y27gHf_c8qryx?A84);v)2i?0S6=(3{a4yOQ zY`-~cYjojW0wYXyAY0?N+`xCZ7UtT!?pjp%O! zW?+h#T&#Aq6ER3BZz*rn$2bh%DM=+_bpcsnPMhwma?97pG`_PbNUI?&9?4(Bj$^^N zqebY^VyYf^Ccn&~PH!rU_!el=NLJ;hIox}2(C1mUun;RF9f=1LPS~oBn6559955cX zz(D1VduJA@ETlT6krY3F2T9KLXfDNYN1=pl{qCR_t|rmGJYwlSqPe=@t~vG)fp*m@ z!mAN-ByD=Hi%EJb=T#t60vpI=nP{nKl_DxLn~T(h)(~yzYcZb$!BJG+ z_KKBMln68#ymlcQ~<_ZEpVg456aK!8%Cx zjnJsT(}5+n9e#KHdneD^FH1%IaB3NZQR|t*Ox41>3o3ExtRj-N3U;f;@!_0&rd?rm zO)9iP-u@DPPtPe*=Nl+tpjd>DAGf_vw14!HNMQI&ak0P{9pOOF?8USrY$H@WdOF1c zcvPay>gtg%ML$8K=X0PdRCo+Xhpc%mElxM(^0ugliHe)*OM6Y0Q=zbL=hlVk*J(_v zEwcUTvWWLy{UdM12E`}Yt86&&n5fExZbY?U2Tia{0T`8)G|)rC1Kv5TdfvlI|U6=${BqotbEQM!_uZ@WFF zBfLhTtM8kME53$IPDv#`$VLN;P2S=o4XHWJ@|l7iKUpWE#+MEE-as}>PDXv~3_|9) zkdmucp~*>2SN7!K5K$#=!hlEC^nIEU%7O4i^T6fr^0;QGb%x4R2Y9+eo8Uci)y<21 z{1Ylye+ZWC*Kil_^W;|w2#Ks9m0Ip@SC&?U2yE0T`N6?p2JaKE{+ojXZiyaGmBS1~ zoqZTe{;cWbL7SlW`fklJlsNF%G_HSuRDx?=k4PY^aCNU}^Y^bs+*KcOn~|L;r;9A5 zpLXdY&|8%Z5mNHw^KPxLgg$&dRH=^`ffp9r{!CAeL_3TRaW*TVY?cSjT{+vHIYi)c zzwyA1ziFLaaLfe^x=OMNg^%gm)++{|Mmg`I4=p{35Bg}CXc>^WW*x-bsCEwxC;>^M zS5it*iQ`n`z%Uw>9rovImdt7HpcfJ&K(up{1!su@V`($4X~kA*o=;>B z&p)|rTr7gw9gRZrZ^6f}R!lE};E<9izqMw>8)ntxz!IUXlK;(6f3w@Ql)TTC!9lem zthm7g^%`m3Y0wVW+8O}}R5CJVniAJfB}JBajc>0+*_=u>7?z`CIXF2{G77E^@{16F zd{Ww14MC}MbaJB6I+Y2xbWLBYweYQ25t==O1TT{*1DfA#MZ#2jL>AVwpz*J`x_ZY! ziZm+yu&BHxi@;c@UhO(y(ZLIS=o?UvPH=uEptLa762$A&X}Aj=-FLP2alBrL%i&Ih zTZda8vOPj&^ds5E65+i)eL#_+dKS7#$&J=>?@6OaOgYUcu=2rm_*@mnEjdUi?wMPN z0ZPfUoX(&!9r3vKH+SOvcx!I@;T3ZMb^1!P9LHW!toz}$qBImvX(Vy?_#}a=;z+R( zB+yudp~9V%K(&6@S}s9W7g$`}FaYQ?#cCX`XU)T9nvOf+HB zghh!n37|*Dv|U(iR>Jx-F+5s+zJ>@n!MbiZC5ZYslktR|d`-VUwcUO^WMCI>z2yC7)>8a)EP zx3r#Ea4Llw;VkxqUv&`_Jm^Dzg&$kb)*q-Ew2KMOr?*B}+z@^@IT^oliIQ^r1oQW` zbS2Cj+&$yIY`_!5tE77Pe|VZ;E^k$jL?Ov3GsuX5O1yP3;5u8h$iS63TyfF$Yv@_a z5-i&Xf0~y%7o{;B+WSalnj>A#gHHBjWcn4;om+OSXl2f&O@OEdWop665U4{NFkyC#YsPrbs)pVKww^|aV4OvHrlL9e?AFhkivf=!fX&6dAaOx_rtNV#Up9mUc!OJ7%;WrQ7fx_ra zbpKi)!9JYKnVh&dN#NO~V??8(>C?m&Hfssl3JPbxPh|1Z^rV(sNNOIMF{TDZDak5g zh@C;K)sg%>JHKyYT%~Brn<4j-GEs>{WDbki=afh4w5T{aUx>csp!rpT2NqZs&QzcG7D+ri~i*aq(`(6iQ*6Mns^xr;D$gy z#{GoU+#p1|;zkbPYI$4`+^z318`{Jtp2*$waT3nV(;ozB2v!ez2%>nO3n{oa`Ee?; zaTAW1xYBapAG$z1=*3^_HMq2D$dpjaOS(rk=DXt<^=^mpvU_?%5Yq2Mkk5vH_Cw?H z^1;F58Y_lSYt9ZqE`6?6mXIQSyeS51;_cV&HjUR*v`$dj{K}8-S@zdF44vmm1qhZ2 zvAT7CsjjS5qr#8-CmGn5)cqk&1XdG_y3exPm6|P&bsw}1;=h0OA-l~nu&~fS5?mvBctzGGtWlAOeSm}K1VNfRo<7{9 z#9*wtXPXFpr;F>$3ni!A2K?-E3|#PJ%w+GQA`4mk760%7T`Ck>OAyX&Hwv zS5bLEDml%cs)LPjshdi zsc1rh)SBFFc;3}#q$O-~*e!p4L(!ee#F^bhaEr=K-;aSpWbZB8l4sZ6P#)_{Y8ltE z1Rhhq4pn_Yacu#Au5*kNEJhWLIu=4G(RHy>7lU);0E{7uABik#g5L!8a^y|?{4PSI z_H6Q!-dG{w&G-c(Z_D2678p;O)tN+5v|!XwXApLt?7kx3$U>M zVbj={9vUq{p=V;7n~`}~XMJA=a%Lgh(|OP>n3AMi#%4v!l4nf9d(Tfog$xvZ{86o# zX5<6Wp`CA3Baxfl3oEyXcvMPdf@x5BKSMBTY|=ng#;Fdinl(n?zVpHC%AIigACD^L z=YX+`)v`yn$CSJ%wx^zvy5=W7Z6!ZMhSd54cdaYqUxE}UA*><0Aw@q){PLbo zbeDbilXlDX`E#Vu5+>m({AcS?^OiUDAM_HgdS2n(ZBcMGI|+5i@$`qp>Ezg``#INn zlA>*9(m0N*tgo7R6w7~j%YEd@t12ZvdS_CmhKQ6F&n_2N?H{jCr-*H~sLn|>bO$Sc z=tViY1nyflHdPb)mWWxoMGIZW4+e^_(H6;(cHa)z4qPj|lJu(Vhs3}%H|mnB%bC;c zM8Q1x%f=T=E(z|o;iH#)_CyIMvIt61g3RJ`zV@m$mg^w1D(FHz&lMV#>!anwO!t>e zF*XZ)dO~Esqom({?%9i@=9v;1=y;!N4o&n)TqTC( zJes3h8A@XSFY(@lNvCrfXe1iCs~3K4y+C z3B>uY@f||0TpDB!PvNg4YbuDd579%5xlic1R6dg&)Z+thoa!Ajx-B^XDnr7?md0bU zUYcm9baO%QU7OLJ`v*;g54oxdyo1_2&`$!qK4>Jn$nmiD1hFV^lZC`Q?sU1ndvKGD zH{}5?O5bgDUvmgJh?Sn?YR)`cX8bKPgg>q%UcEb}4mZSLEKZyHQS}@Tn6C95t{Ze` zB6S2N%cP>YKPAcYi|@tP!e{F8zUw`c2|>f}wc;K0R-{mml;OK!Njz)Qe35f#^K8Y^ z^T*%pz%fX$_B^F`nUR&Y;z|IA>&v^MC1p31vk=8vmPJfCKX%Z|a#WM03}O#)rz#59 zntR9v8Vrj!PUINhE4*Rw4q7i`(`0MPw~NV7u6d6iyAaHNnx}B;b?#TUIZEi!dr1Wj z-|(3c8u%*Ba@#%KTtW$W+P6oRx7$(`MI2d%P@)o(W3AM*P|KJ>i=AB_R8>W;ra~ft z&o5NyJfdkcPr5s<4zqv^ZfDTLo@NZW`ggIXE_+qZaIIp>)j;;Gl2a(wNgs?Zq& z+~;-c>f}Xi*4%`mMqGa2O=sLR6*#jkIHULo~DSH<0R>+cMasW-o4 z9~Ae@py?jU`T^nCZ%?ADO+j@tbuQF?)mOJogVV2mSp zuO5yzU6DqX;5Jf&lq=|nAQ9O{SBSgQN9I#Y!wRNB1AO>K`uEDV3W^7YR19=xe0|(|6IQ53H1l)$Yb2 zXE3CTW~#WZhpc2-iwybBP)dBnpzK<4P!E|!DH|*@SYn*hA=#0zzE?Xx$#Dkx>}zKK z^88X+%9|yJGHK?4`MzYCa}M{8);`9N1~Yqwfo$PSXczyap;DLb2OU%X#*MDBrgZcD z0iQ+GY6ZQN0IVZtT+mYPZJB$iFHVujg?Yr*b%~5w$*|r|KIg|BuclCff$1(~?DXW3 zvo{OM5BFZ^q3QlqvUsr5`fZ`E+=#gOvJdBnWn6}&qNj=ZdpCt#edDOIQhRh{F!{Vd z)Ed)G8lG{YtW)7u`_4OGxfg>+ONpuvFtaNrJTz>=4*tuT$U>#vEpKce)T?U=T@5H^ zvgF{f#JF8~s!QWsrx-Z&Ix8f<1qt=4z=`n|o1rcu9qZ@xhBCWb-_mJGvZ*;tEE$1g+rsJ-X-}PnWVz zBhqF=)NC#>LAv&Hv_?o3D}so* z*FF|}#VM2H0@d)v!+F66!4)I(xjM@yeg+(%?RN|n5N7hVF?oN-SLp1T^MRZsw<2sj zais9m-W9fWT0S9s?M*T!7>r52(zqrUTpDWJb_7fpKNf~bu(+#MCz_p9~zly(uWT>_&v-7MpjK+ZCk*d zM-o-|li8zRMa+*p9y2~OQq|r}o}BX_Z-Lhub{)H~?(F)oQrZzPuBg&yZGg4dw^nl1 zEO6&fsUmRlMMUWq;6@|69xbahT>etoD2c(QPz4DnT;`3+_orOnN0P+scjGXUTfj!{ zTuf)~#oCNvdEB`JCHI@ohTjlQ(GRCoW=+mz9s}IfsmNkZHsygm}u^vX4$ zU$pf`)@R4>fwb3JDJAoWOb&xo&ULrTtV1!G1M)^)=7>|AeCXX9TR>y7oUi@p*H>-d z%vAI%FaI4litHM<&`eU$cy>4R@VO$t56QRu#fMss6z?3*w|mkr^!}Y^&MNApMrpFw zjb<%k=$=awOWrEIz46a8ne&6WJ7n_MMiQ-j0!-`ejV4}4;Ek7Z1+?0TUejYOg+fyT zk8LQ2AKHrY)P9a%@p-Go*JAC+e`Mh5u})KanZ!c=$=24E=Lk@a^Sw#zN*R{eC&J-J zzi;VcaAQ7V?8wAmiBoeR>&|>S75^ht!_N3i{$E(s!3lfUcN=slcI4xAa}wTEK!4_0 zx&h8(puC3kBvQU&Grs4iPg4A5;w#64=KxYPOeiUc<}m1(i+g=H zNw%m~a-FY9kMds85NU1L`V{`KN5pT&zdiFz#M|s|66(J>%Hk^|wQQ(Ic`Kp(c2Pa(B|x1o_86RK=Ic@O;WMw~dm{^AX%+dL=dS(}~KIqf9C`Pk=WOtqemNx$gc@U1S;BU<&+sw4p5Ckl1BjVgpF<5$gIrWLl&-TAI@X->g4Xla#XVr_m5KF)UVK_UY%wm?w3 zamIHgk4^UyPbdhCkI}BS2U&XLJeS%+W)aG~e@jwgy+;g8*x1nF~ao9lg^Oz>& zdc=Lt7^e$;0-n1{iMQ#QH)>yZPRWvKtn!_v2|O{=knyp)IZf3&&m0*-sjV&d ze+=9Ev7IKd72*2vPBY^rwROfW8Z(m+Ttsms@>O0>8c})jIkjT>>_2(=UOmbsH!Df z(P~h$v+MFbWrA=rs=#4Bo`87GD?%Uccg=@5mUIqQ>}X_V;<`#uw!hb1+J7o_Dg^CA zoSGd!BlyDQQ_^a(R(bHUF?th-kgorlrEe2cIWlmunXKQdQKmG zvd5zIm2X?(KHAF{-lfF`H%2s?=`ma2CzUPsxo+jPPfmMrD&d8h zW5yTX=y0D8)^k;Q#iCNQn32W9nc^8%OF&Q3u875GzL;}r{IV_xR2xF2Tb0OXrgtWL zVTkK%Mh#68FG3wA=(#f+@R4x+NxL()UP0%YDH~-?x-T9aPiUac*9W;R;pqj}ndc(V zOjlE=gF(LYi5^RtT7y-4T2w4Mx>YPz?OOYU;_5u=1wPcE6cdo6%4@{dZ)x`hZ@&?C zNfj@*^zn`Q79^g}(fo19QsqknIjMY+hF|16_^x_?h2IB{{P5xKXDk869XwjtB(qqP zLMzO7@sAxh+1mnBHVbqz`yM`#7+N97a+>4v#wiI4*oL5^j?9;(em*PZ#1C@!COMN! z{=PXKTKD`|nD#6ytBbU+9Wq`pZ|s6plN%;X-qVJIgQIXD0<=nzC5`89?_3EyVrCKE zaQ|S#dg^d39{=1{xRh@bBj@TWvpj!6W&kN2jbGPthR;KKc^{^E9l2(_?{=+3KQX@^$M7HE3 zsKt9GTAX)EgvbUr;VV|TbRS(xb>D}m#_c-q-cM9o^)=qCd&aBXKOaJMHCg$#qQ?4j`HStB=ym=^9^n2=^NgX!om6sHV&-eVh zOLqclu5+9psHgQz7Qzdk>B~bBzUK#ROpW#)u8L++8D*%Z1L6rp&#upN&$a;Ti0Ie_ znXB?~G%TxRfIe&gda>X;fARLa&L5ghEuGV_50rrXSgTNc%HY)5JPw3+Q=!r~OS^iH zFP~otTT#NJ+IwR)L>^zh+Yp(Gdh7qQy`$4;DD+sli&r@Vo6Ky+e&B8U<wP#s)0k&t-M!_@=m;V zuq>zSt#L9OqqCBb!=iX|gLpNR{ZB5HqGxxdF#`=dY(-A(U@Z~|$MfTrFr3TJ3VEb= z#$<_0CAu@YRjfi|?Jb#)y<^RymLoDT*`2CYg$`%(uRmFFt1}xb{+m-Ke|0TzzfP=I z3OW8Na}jvO6jR?AFzqmNRx7S=RMSNv$ah20{QdG{6^jPWzQj!IG4rAtFO^rag?e`4 z=V$AXY^Ybc#GNxj9{YW1IG2yup2i)@CN{KaYN78Mto5=Wl#;d&gT5Ikl+Lg$`sFk8&=wlWe z*|too++>buRkqQES1}*HcIVv-(xK;Op!k|_MF;6OqU(eER90SE!SB-(`L)Lno8UN7 zou?Gmh*1tV#{&k29G%n~H1YIS_-MN6#CfhGfOn!ps@BDa5*`sdCL)CPF39sGF&QfPo*`7Fw7qTEVnR6^cPIyH9* zgyDrJa}=sC{EnPxfY-53Fh^5g4{cKg_2 zR!#rD?)j$7czS*p?HxThTCrv2tYQ-FwuN(}q_2y=!@+7>Q=H91B=al%fY6wz%>q}! zgOL>`(V&AQ9mF}1$aRHx_KMT2!+}m2=gT#HnSx=2e$FI`mZx_wIVAET(dVn2MB7zm zh|Phz^Gy-#iepl=LmV&GD6QpOi9O;T$f(BNd1?$=umGRnWMfdsvl^YJj zKb@nLljZ(0YADa)l48(W-tQf-4}8O@U=N*;XiRh}tZVE^O@>ql%~SnOp5x0;i?0mY z;hfOaW)1)UlNMC2J(Yh^dvK-3@R~Pz^Jq7=DN1+otc>ragubBcd0w0YJ+f@Wijj+X zZGL}AsC?3J$4K9_yWnYGk>hWH;ccXVk0-``yv9Yl7dLo0jXa>qrL1!GV@fL@*ZrD@ zx;)`*nHh>3s{11zdQSDA@fMbObkSB^%cJJH?<+IX7v^O0DfF_T&Mcc$7G8-ci>Ql+ zUGV`%E@uj<$jg+G!1rFC=%X(!6a-6s!?WZBwAF=P3HTVZ)4ioQU{3DG zs*Q>-Qqn3fA;EK=D&^%`1-9JRIuGful>T=8q@FVoEkpYl(SM}p!eS0@h(NRtw&gvF zW|3ZM0ZhM#>m?r7o$u1ub|iZAy3tx^UcB2UXsy~{s^v%&d>3G9eE{t?@1zuz8m)}d zwF$%}M8e1Z6NXK52$*a5OCC{uwZ(=$>X!%8H?r1NGX{j!8>usZA~$ z;dXgs)p98j;UoV%4S^o#6QjAVtW2($lMr0X8qP(IXtpU;clx?SSiDOR*8@0*Y0vq= zsU*^%fR87Q@|wAgq67vee=Ih?D}*@ZAlks?%sV6(zNZ&3Q)i!C{lMC&zq*@=nOW{F2zT4bTCrOAt1}*Z_TKQV~gwNN0 zUFq)M<(=coD%%sHw*O(k0PWh?!e{qF^63^aI6da*Iv z-a@3$?9$>KyT6w^cjozpfPX-!QWj}uh5JK8zUzlWa?f*ap2A+!%%Fy`hLa&;J$c8Z zNSSxPI}t;$CGYS0FlRF=x3m3v3$!$wKR-|S2fSLxi$=B!4Bd+Bo-`$D1sdV8D|tQZ z(_=x2b#+cQyHD*6?jdEL^=s_A>n%6%;&#*VJHCXfw3;`L|Fd%$JM&BaW-*9iK~JR3 zKM>@~TbdXQe%Y6zQ_kNy75We8e3!vTBW5-ynVe1J__TcWwHn@+46WO&<+8r7=HIzF z6%W#J0@KXca{`zvj5?ElW!I_FL7VZvkhZQEz}dU_FMZ!0>ew}yDYv&?@LvE$MXFJ0 zW%AXTDhC98Ty5|e6!SUQ$(D>C;;wIQddQv%G~AXx*712^t?y3wbjsMP@!ewMVDjM! zilhb-!Zoc4)JqZx#5sc9GRm2mjBgGJ3oDPfPgh4DJ}p+itT z2ZOL>X^00Jl-wzCOmmw8?MI5je__STiv6z58ah3pyssh_{GDWv6l|AiD_MT;(O;AW zRzeM-+siZSgxp-Vv6xX&`LXG=xsU`d0*%vFr1Uzw?$ z=y&IX!8C)Q;6WLcwsvD8!s$kV#+Xig&5mVg;dS9lD0M-hgP0ejZTnIQr8LOI#ZYFI z-*Tq%E^_-oKd4sq^@L&7!d4Z0;MXB$&1%&h#4Q4E`Q`6(N8HzCXRrb_cVX%?jQ-Xs zt7a5odM(OH1ka4Ja#|-tR-iQk)sI%^@4`UUYbB}h2+eE8_9qHqVXUS-*vF<8^I8Bq z({P2IU0=X(R(SHAB0dudqx$a;VpBL7>#R$T3;3ZB{sq}gxkEvYf%SwnqT9Kq)%LmV zD7Vkmzl}dc=hJy-t`6Xva~*FN0v1}k*sdseO$21WXZHUeO1@+gE?J#Z~|tnTc0Bh7{*PnHhg z?poCQ55_Id+xRac%FB*C?HlMErv=f+u@Jch-bDl5ikJe=`vJa#)v0b2zVW^yP2=f` zg(FY(?p3Ou=)Ah?Qp>$U%Z>?ZhZW3nBUXsk)W38{QPj!0qwYQmU%zKt+PXm)r6Orj zJOh4VHVdUvyQ_CID?@=yW_7f$A1(ex#wLTCHn>KlP+XB+dTIwHJHkr%i+@))Txz#P z6%~AOdCWz+>f&m{uxu9*%rE?WzWPooMV!N00DVM3OMFIRtXQk&n-Nx(&g6Q^@Er{# zQEG0vvBXvxNJ&7>7~*)&{*q>vk2$hjDcR%Lil|s38>PpP(xSp3zFGgVL5riNL9Zj77?_QmCLri@H!E)(EGFuh-#W9}$bimn(7A z-b;M5oy~zL>cdcztzt2;Zht<~r0;c+^0=RIe<-uM(EMQflnrADF>VYpb#-qwv#(dA?C;CmHi1%KqRggWX6LnmQ>rFLFIKPPR?1>F!Lsmg`Y*`UYn zm8&wKrikgnP&7=uy@rWS(7_{Su;+t`E9l3Ag;qFOwZWQz1Sqt;d(=TfT!i7DZv8&S zB&%R&ysb-iT&h+jf=&c3NAKk3bPnb&CA*O7p~2~qpo9Z@`gT(5z%fWzTGQyql2<=d z%w)Ue$xcF2G;tAYx$+vM!$q^p2AVcT@|Svi|yL}Wp{Y!#Id#s2^WCuqmg zK~3b4sbZJv7f~;3ec?3bUq|`e&Z@)k(`lJqqQp$5X_D+$y<5A&N@oGI0R~KYNU|Rx zrys5`{$nk}Mb^Wv)@k5XU<4!Wcx&fv!j!5BPeB!Y*H^YHfzc%jX#SCjoSu*(bW1zd zc%SgL+nDDAGFOp4tc>YMRZ-J!P#uTzH=Ll6aFc*vY+}Z?^bpMcH!Q29Q{KKFh)?G^32f^v`*`Em^m6)R2VOv*}1<6{!l z%Q^rKidqJe=5oRBCjH0NNn-MqbL!(-97s*$GBfa3iSEupS8|6AEh?Puqg`YmMJ0er zhcsl5@A4_h1mtuj!n-LRZdWnFnrt-;*-~qy;I%5?v95zp4R(8zv9Llwvt*zpNev=N z1d|hME}2L59>oB|gK0m}AJtCT2N;@l!}ME?!FRXNWY|ejpZWDcQjOSupOFVE;&#j& z)Rn_WZOcUD1--OYOv%A=)|~_2Ueo2(!G=g_9=i{pTazzD8O3HkeLbufv4Vy$gvBPYNJQ@3rD6v6#f$zK`w(TtaS~y_>6^YU0d9$>(N< z?+rut6ZqTw8|Tki%dVFjR|vk|HeWp{>wMmhZf>QkaM~=5CSrcHh;-z~>uTqhE3XZ| zTH`KjFgx58j}W)Ggz6GSo@;k;+b>~G22GQ+<=!#ug?RE- zGy=szp0GV zrOHm(vZ9C%2&afh(s(#n@k0M1FS?L{(&R=kr>xfn>W@C8QAfCRXI6uJW-y47U>|-O z3rdE~^Nq%1Vd$3+zMZsy=|d-Hu!UdTKs@OlHSGI(Il$`-lOg{a@bz7{{%g~wNG+3j z7pnKj#Bb-sDuctKW#0LGpo?DsI7Cj5nEV6m(vy4Zqu(8q2#2Jl@tF4R;z%;{;lOb1 z0qX4{RaU@I2c7&;6kz@XE<7hJj-xwk&zIM5DTJSC=bu7tA8PblM3KaqsFpMhoVhhF>BYdLV?RT9&t0@gnD(C%3IBBYou$!zq?|^W0WnvuE>Ys!M z{I4|v%jWzp=qS0?CM=124&Kzh@A(Jp9sB(74_9F!f!ahqpkXC!4+j*=EKCQsEBVhd ze44V!dD}IZj>iyZ?0^|ku~YX zC9OkP^3l*HHDxurePRazQ^Z)1_`+`vhb409JO}k`19?FBcJR9+yiJLXs8tX-` zB%|~AUd?mI{s9-O0J+C=$G$|VtT0XOCEz1z36EU6%*VH4%2g*)w6c}4gS-@oKo!`U zM4YL|*puv?pyzT*9dz5tG1i|{yDnz16ns;f>FC-bylWJkJPV^xms&(D#`iRn5j`Qy zA_FI3%EyItQG;=*E!F!=BFZ^~cZ~@>F8-Z?`s;4^`p|861t=@Q45H>CSHb$3GE#VW zzg2td4=2QxX4Z1yr9{&IzynG))j>t>e;VT4&5^IxMJhsv-2=rWr7GfDW4e2@TyHdG z?`>yR*|>EC8uhz)-Z(SGC+{blgbm=p1p2BFjQc{L1?981y>UB_Y*;2e@ zpu3}1(i)Rgo+qrZD*~2}um{hH4}~ONK`9dzOyO&Z*n!{?@KDV5TjWjKk}I+n1m^Rf zh8s+1nOUMOFe6DCp#>{?7ABw7ZJ9g&{33P;!c`o2ij{;Mss@P_ST7kR)_4k)7PlQ! z0-U{Kjn|(MG0goyM%S?xU@cd|~y-SXgHpuGD;Ztwh+27qE(3h2+ zin>yOQD>)3>F@`#b{RZGUjF;hU`y5gg08-icCkrA;=#LDJ0(r^yP<p1MVD579H{G z7pOY)4&oX;eSC4qqQC(Y0xQo8Sfv4I5Lx&dK)aio`iol{VAm7Sg zaozfzyZut9%F&!R4W{3PFe_);x?;T@UKF^v3(;&ZQTvJ9>Ez@ygXLz~B$ zNq78)IHfkD*2U5dpDoyYITC!xWkYD#7J#%)%-n#*yvoM^?nhlA@6Xecdl;F73KIh^{HQ%}4YZsNk`)8$tap;NPs`hFOJ|v? zUhek#*w9)ei&STpBauaENnEHgk_H1aYzL8?>jRA+RtL9ZRJ@Y6r2lRZ-Ja<|Dl51X zU52iDaFZ)wKOli60P`CBKVtn#F82qI5HbEPxfzqA=crj>lGrwBO{0CoEcv9{pG@Bf zD;PaT`LD-pKnKYCO_N}0(?3!lbXF_D2d!^DzBW>y4}~g_)TDDirsi#D=1JXKNPTH$ z({wZh{$3_&dnl)I()$C{SFzsltM!E_URjX&ELr$*XX zR+arDhK~L8yDxEv9xPsen9q_1SP!0f62UK5m4SxT#s9+Oqvl?kLi2`U;4?|Hk;q$y zB9{eqJk?wMiBG&6{*K>i$^&GZZ#OPvvZ&VT~3#|!q*`cYB6K6jTO?B#Ax z1icVApjZ?s?2F+2QBh8Z9qoZ^6J0h`gq7!0vcn7AuUH^5N(?{ffn+JlR|MIJ#ug0M zjCR2YX}xK9iv=>Az~fsaRL=33o^bPVCuk2%yCLZx;6?G#h5er123*f23S&NQ%V*I^ zduO;NNhzSElm%BT7U=ZG4Z*V--LZ|}5tp3Vg%}mow5VeqJ~vfu)#?VfN-{bkzA`vJ0dO^Uw@M?@8FTp1?jGHC@_e`V-4g~D=ah`8`p(y zy8%zm%I@sTsK#u+j8tc#-xtFqU_Y{K24EoQYUG?MW{YqzLz{t1aWUlcF&9~L1{N!L zfPFY&^x|2>W(%=4DfY45{EYpmSs&aXu<0=B54RpoU}6z}bfJ9zdu1CLaRoctls3i+~?S zgF~z3ZzPjunn>7pmCHjg-j)g^92Gba9_VFC?|lkWli;^;jr@#nn&Dea z+~r~|2L(@WmOz7JzEx7f50ejuj4V;T#M!&DgtqUtx7o)|q zhj1h)5}*uOEMK!i7iDlJIO(Rx>>+0Yp5uVvbnBZy#-!4U1rvH(mdUfx!#pA4g!Sx6 z1{R{T`IL%5@LEumQ6Cfr9s&D+MQkJ350YZ?aPPRD1s2*La-8f-&c8W395-V~I5UKZ z4ngaK&x$h#7h4$zU_@AlsIC8Qb0kClqnb{ywHh$Uj3pHsmO*Sh1N8G?emO4-L|P4( zSEOGpO(ekeSGgPDdT3=aPN@DCQLsrHUgdyWp{A8v%-loxmT4w-!e&P&-pY{b=^_>H z0hO@r#5|*kZ(K<;cYIc3>Kw=5nIYPh1dNP!B~bSBlP9~V!fIrh4xdI64+iN{;!=#w zdC730Tr(5gcFc81lsbVttd%x%ogJ4u8knQ`;vq*uyB;oP+C+5Gg+TQ=)%K(ZfZ;4H z3T{&QTUWHpZ1m#|vDQA6cb?>%wGII|W8-68O{ zG~2OA7T5QtdxKx9oweoSxJq`~5J#}3>To`nA{0ccLFqXXZ;N#MBbK(KoS=72oZJ74 z76tgrw4s7*Cewm*AMW*!!4`CPh;vPH_Mzj@Q$XrrunGez%Ug3z=`q;l=+I9W(i19R zr`!=RHe4;FD*e(Ujsw|gkEd!(a$>Yv4yG@@jvVX~jVWovw#nBp9Y61PZ@XtxbBL&C zPu$!On4Q1pT!)FeFTs`$^#Lh=TQ!Z1HY$a#BltL;rg)?@Mfpttn8%YmvmwnEDqcJ2 z1{QshSX z$cHX{4hI`x3KgSk|JbGAZ%EH8LJv92AeNZYtCE_r3&Nw0XNt(^cd#&onGo9t_xt&f z&b_wFKhf}0st%wTfhM$pN|p3MJqZI`3gS4Bk5rns+y!FoLFMjXg7;@iUyD-$H5G?M zFRkPSc&7$6-~F#Xge)y0A^X;bEj931QIU>9&_`|mT8XX7%A$y_+Y8XygvCun6B!U% znK4$44V2)d+O{q8&#XsY`(qe`ZBg+g%R$Ip2qJI`-QkUAC_>-%AY=ZTPF{h+ zLuF;Tw!!{Pv@JcdrqSJXQj!zy8M-PB#MwW~5jDfMp&fhv0l7CFf4_&0$B_{wD=Sl~ z&56HwT|~j~jW-nbU*nWn66Ob4cJb5jli?l^4F@n2KN2I}N@OoBq40=6;}0$wOSrg< zHl|75a)HH3zu4giX=Ffw62=5m0ivD?41eG7vCK~a*_z!QF`HcZ_`E~O%j*&A=I!zv zo~v%S)=<3(dxU*DO-(3i9!2G@_35cYV zo*_|X8H}jEq{nSUg$S@?kMT}&FzN>aZ-6Xf_&yWc$R_0av&=C3A z%LmidJ#l{smgBSjY(R?-np={}cuw3#2+uKqB14}3>(SGj4eVo0jz*nO8wVgR;sava zV6^#6$HlU?j}?8mLOq|%Sl2s9#xjFW$gW_x&cIl#;|yfZNJw_I_b9k)d*B<9&Z!7{ z$VjqSsHci^?r1BijgHFH_vB2OUa-I2MoG);Hq8W(xJBKrUA`%%M_eSghEUKH{UV>c z?reE1T5HWMAw7~)6x=;(wj)K1y)amT>4-nLq+2^+m++GU#=zwg{Av$G7==RT3$8V# z4w3T{e$sNmC?5T3mOipg|GyJ(=7G!gzGR_=!8F#>TamG6!|^6OBd$PY3cK8fZfFDF zP9aIs-jUp)jV+Vh)FKrTr+EjRv_=7M!c*$ebR{3TW%BS@Ls^4ql4p-l0IC8N!iyKt z!SBZ1(t`e^l=+hqZL2Ek9?IR-3pX~U9~UGYvXNC>G>!t>w*ZEtWd~-`v3WBke_%HybN zy1j;@Fy7F|z2;z(_1=AI`RX(}m?%20cru#1X>L_9{bMS2?w6pEN3L4m9Q%c|fozr* zT6+~Nk2P5Q1FrYA))ttU{`kc=wG(Xq{27v7ru6y_M?t}zzeYBn{6sxA6?v|BVDi+X zRVry%MVI_hhnrW1VgnMTs=(vW+AY^SyARctF>zhlcJlPL4WOsX0kQ`>5)wt~Pu z=r2gu?OhB&Q6#eoO!MUC{vfQsatYazW4E0ny0$&M8y&t?*XHN`GvNxnd3UtM_0@}adAIqM+tvaOS5*$ zniYZxil7+dI+t8kxe3dIrRVD&6u_TM-PFB$L!!+B|E%J#E40Bswt|RLl;xLjKV<91qAC@Sjc6MTm zNqk64YnHlGeq?sp zinjw)^IQwlrk76+VW!OwiFN!n3R5iWB_9{{l`O37NBRrf?7>d6Fm|@6cPe*^@g|-S zfnq9T%J{+A>PM3ZE%&=<-3rCo4A#Pyn*DJLy~h(Bca&>xyY#brgq=Izo)|Jpgg?&; zPTK}GAA>q0NErVNy;Ip3N(zsgQCB^zf~$G3hgh<+p-8UQWUaLL;uE$TsM%>6?ODTE znjzJ~U#&-3zLmK>IuK0Z{48{Tbk$Q>4*Cy}HLBPlur88ocyr4p{nZP)H5*zT7$b@> zl3&rRf*p94J=5Qr)jng|Jz<8FI#OIW5~M?R5ZwbS(rP;pvBCPq`8EC_-YNSXE=7O< zU61dsL#L3(q;K6FtT~pCaCGc?B22b(7}_-yU!!k~r~sV-NqEBF8?DWoUnpog9T=yw z3eR=@V5oVdnr-$&d*Vi(%Uqcx1n;)XgH{#~n0M4p*i5G~a8+is3s)yyCuRmKC99pu z#s;9=q#`7%`)Pt#Eu6iuM3h94(j0H4Ufmr4!y`TMroT9}%Bf%3eqX453$IGfGV^8} z-$xX<4|H4q)C;t1uv0s3;0 zh23x`)OCvgLhi{O3uIzudXJMydo&f-H1P-^7>uc3yKr>>t_3?W^>lGAnoRfB-g@tS zOss;vC*}OTZsbc7D|2|m0j$0;fjNB|i6IP?V40}@993XlH*3{K+aoU5VGH~98u^!> zqMy-$%|UC6nCaVX-a0iI6uhxP9B<`yZkEm9Rcm(~*=+q&Zf_-7ia(rkCyp6SL@-#M znX;*K?pG!Iu@*$Q!IoOfo7a!ky5iETXP5frLF~S+XW`P(iOQf0(rLETKrtBj(NQK< zNBj5ke&X6#TVn$-PQ_4>4GRRZ3KQ+5?vz0SA)Ow#v*cpQjg zt14iAyf#1hS`0%$!8h;CsO|V{`=+VsqvPeCl<$X9EkloRZ>7s<=3&Nm^x&%PuH_Q% zkA0Q^aPrs@m;roX9X_XMB`I^V)Pa@p{ z<)=iSd144dzpNU^2x3yy61t;PG9T%2G?JPkk1^JJS)WNV_vMV<9R59?x7l(~TgbZM z3u*tlsMr@LL3h;;Yo|QIJ3_zXbLOTj!pT89XMB=k>)w-{1e0re}Lx zWdMqe@t&6lGpSu~MV^G|jkJu`wU%7Qxp39vST6yYGaD8MAMDG4$*$C zbh}PJowDJiz1ne2SG96y^9|#gE&W&TlQfg46vNBquujT~;19V|HCQfYlqSHXu>k8_HEr_0OuhKaoH9?cL7i>pob+^Fbz;Jx|o#%kmGXgMpq+0!xNII=ugTe@EJj z_1lv=huyezq+;^ii(ohF8=?M>_B(yDa{95RMUJ?9fSa=Nbdf0;XtT&l=pF`n)HiRu zcN7i|1~@%m1j&NmWclx%ms*1->mrjILgc}g)bP@b-9vhVNf|eUGOBEb1Tu4tQ@47K z%Rc%oU8Cez;EQnD#Xq8wxKa0GLNZk4NF@8L5dU@r|6wTK1QE;=` zDpF~A2gs;x#k|6tRz30X~V zcZ_kX2aOTJtgZ?^cySneacIw{DF^8-K*}PqmUwAf81LuS3UG?pVa!ZTJClI4Udz( zEn8WS)(kTOf16zDY;mc)D_*67`w)```4|UPzOnhyF!{^Q2Sy!B;#UVN`h1?VK|Urb zq~)Tn)(1le{ZKX>;L5JP)(Ty{6ft=I!ww&zR81#6qYb!LHpyVcj1iW+0;9~bu;R)r{-A6 z$#U=A&dHn;J|gozJwM!%S>bI#;G}hW+Nr-(P#X4$Ik4>z1D}ep8mmS=9r&ESjWZ5D! z5vyBj?!GxYnETmU2YwM3)_bmpJ{2LKOwD4%o8_bXOE|Po^&Xb<7db|`Kz(>g^vUvy zOE~AdtryV->UY&8z8d;#zf-|&R<*l{gIyfo#!nD-zN-32{ly4H{56e;^)lbAMZ#oP zc|A`jeunXuGi9ts}kmleV%0=Ixoo*|eOcpX(k0%1;&p z*kX%145d(~Irv}F6ZPZgctM}%e`IB&6-#G*CW znVku*Qi!++5o_dss4bot3~7_Qo{GCY|K0#$`E=;x`-gYl`=9(%yPkqI3V(g=fy*DU z7rzc3m^8zpf{foK1Aksi)j!Y8{BCIy19R-C^hq^~9+C{MMq9J`&IWw_Ot7p}Im>kC zP)WG+t4l+J6Jdsu@psD1x20usR5J@mRlDSnvR=a_icVyl(lV#!?{nN2MZ99fZ~~L- ze*4<4mOpZ8T3>-vk;T^6g|9!a4s~YA*Ms!cGs5dL*PH{)L@nC~kUnAD<(KCc7n2?t zEp*E#^gE6C{qKrxJZkjbdO5;=!|8hHz|}9|kFbTG{%|08g17&$P1 zxAg~7yeq7@YtF%-*9`cO!pW%kt1@E^nn2Y&+u+)3RKP}4?wZ~%kJ~ zpu-ZXYe*w@7U2ATeI~N7f4p7wEYom@E-bMBI7Ir<1AOOrh-1CM(riR=fw}?*2^FIl zL@i9atr*`NI<<<%>XH)I8a?MbTS-vXx;c)dHl{mkzMgUsR`zxFI<)9I?&6u3HDHzY zvOatA?TMovGvA&W9v}H`+wB0^;K*ls&AI5PUo@TV3k54@x&w`0sb;lf9x86n4uvs2 zdqn1RwcuCBA#Gm3*c*#0wV}Z6?k@ng9UYS-L#>XII_6|DJCX_e&-l)Kj(E8Dl(4#0 za)&uXc5a*a!^f-UnQy=?_^y4HX_Q?CWmQ+d?)_y{IdL(Y7`1JZQ}TkXxfFJLh#78- z=!ptWe({&W{Q{fCQRfm^(4SQY^8bC?kf|28pY5O`N0E{fQG}F;mNRntskT^X!~k7F zCp#N%jehyma25=gsaA>iA6kE`Xu5@uG08NUOe4fIq%v$hAg?;kIp*v9zR`Q9_V4bkJppo(CmLrjCB!*| zKTXR1e)5qvJGv`*1|FQMNuPpQPCM2FY~n1LfDd<;$|^6!pL{nX0w~>`YsIe0)2bx@ zypg>&p^se_jso@7bVr#5$(wCGF+Yx2z+oLZODVq#ekR_W&FD5LIjJ4Xhx!OQ`^SCu ztb5c=*J|?v?tk)_NF7Ho_OziwWY{0luA{d-uUJ@QGQX^Mb9lUUkLm<39(Qan{b1L- zAd3F>8rYN5QFrNRC;zb4$J%w#A8enf81?%*6m>_An*Zs@m&g~WSN7&SRmsdEgQD*- zeKw)%=ARjy4P!y#VA<^Bi1mnJ+CLyC*yfiz^_nJpD44Q>HuN|%rU{TC-*U=5goBxu z$y{7BHaa^!+%K)$o-k0EKc5_xbLP2?{gL`apuF2Z#JHi*F|5h9AQh76l1HeX;Lz7) ztUg~krI^E31(k5q(X-bU>)%yI*AbYo#n;NUm0{X>xW}o$`G@q*o-kfA@3oV)f0_y! zN&Cg6cqqfP<5H~Ph!JHT@6v;phP;xRv6GSz6bhQ#@d6i@-cwcoCoWkqY|cKw@0P{b z{Us%Z-!nhuXsk^6{H@MU|8kom6pQlp@t}AzQ(xB@W9L{Y#yVb!^NS>nS()KQE8_Ba z3du|TX=&@Xp$+i^4(DU9a&AoLI^@&TE(h`tnvL3N?x+ddk;`+rPSq=}f+(8ae ztMr43m$MVQ#l(zu1;`t+Cw`NUWN0h9rdiSYu#(smmYHe_QO7HC7BjV#~%0dz>OQbUg_)}rf>jB-@mOQ z7ZNY!o4M_#CorA2iSB1C6(j|DnMcGLJ7^?Hw*~*q-V;ue6aW)dR!B^OxxVUscD2vN zU-{P6Y$ENWC`n?<$VL1cI89?WqV6w|aE^FItU%sx_uj@Mgf&8MwZLNAD}DPGz5DPF zdml+S(A`^0e3t)Za_r}AKpK-tv~JF8{c(B!>`~-^u|B4we(day+f^ST&A96xMbTOV z0XgUV3>Dk|Vz*AI<%$;|e0#nG#FoOtGSNbhR?$%$1x#S(bTPA2690D360N|G!dWA* zWG42jU;;!Bon6GJ(I0WCkI|7UQ|do(l){3r3G(IiKU!&Z)xq6mJkP`5WcR<}%nQBt zgLp4?5#wVkHO7xnfC2nRM@4~27X9tfriY$+7MkJ;q^Q(jYDfP6z!5J;-r|gcvqPDs zCY2qBtbB4+hclR7nftypU-!&r2XH~+=X7P_JyGruVZ%kY{{DDOncy;1*V2skKch_B$AEMD+^!$l-Pya42zWOU{o6mx6Q>x*cw` zy0)#yh@qU|{MV7(a0l#IrBF*(SU{r@J}UT9RrS}=9Spj>+wF2hQ%x zm3DMv=94@h;cF!6;YAThnd}Wn^Hjk5*Z2TfZ9Tsgw>W9)SjY3u8-a(|)W>Yf3tZ-D`6!p) zYdBZZ?qBU#$@#+9TBp@57i&GzRs5(5!CV<7q3fR=GmFrO#3P6t)lm-f9SBBJihE<#O%JxScFE~x?Ml^C+`N=||5P?licgkE*BGj5eW zqfoQjom<@@F|tPxu;}v-Xwtdf zpy#9EJ54QBPrQFfLbG1=P!`S zj)s#;@P8b{TSbZ7A}a%_v%c1g-#hM_)swXg{sD+jST;+@&_*xF+NB{_x#|E-d;x!D zt(|gZXG1Q1Gn?fu~RiOUuljgAvr)a6|lv;U;9%-dPZK*5~ zqfFsT)dZwf2#B~ripM3>QJu$pbW-E{#q9&0BHruw2WPsCl=4k!rWdwOel+xbX!`p% zsayF+!;w$B+pC$?f!c3Lw@ck(CcIC4K$Ns?c>L)q6%JR@(D{}CrvtlUUUijL)&8iYWE=J-0aE;o%VZRJ72`OiY$ng6uSqvAFQ=gY#&VIpkEs2As!31)XqXQ z_5Au=P31*^;|M!2Pv+1EmT5iA3jsyh?`D#hGZOk1Xt{PT*@&{j3;IR~dv{wg3>T9K zcw8N-k=`Zk^HdL4CL>I7G?&9>o`QVi2ffi}G;+Zx^#|9HW7V-H?);&! zV%8z^P*hq<1Y^cn?V3pZ9CRnY8?7Q#3(KG^frhW~%RMO)aZ%RdR`Sqx~-@@5B|C*kt~no6Y-8v0^S>?r|dWyG*?x8-_RoRFzX1#TDWIu9I(}bkQ&LdO&q@~LH2`-3 z3I{1YSRDPrinW+6)I3P1Poy-xsFlP8Bjv8TyuBK}h;>fU%3uv4>{2WbjafmfvuZ@n z`CXrK40M1&s#bs}2@mf_A z9g*Ae`-*zNI23TXX=fe>%`7V=ZoB?IeN+g1H zV@7%&-2Q(+(#`7=4h~<4)Cq@(zmjlqHe%wdCiR1xkJ?KNj%OxLv)nBW$;K7)l2iTt zl)~if;!;fCSSvV_vzIC}x*h3-$N5LlT^IAfCY3>H$U%<6drcGbWf^gMT|zu5Q~%Rh zxlit1*(=9el>s(4ES3yTSjh}d&z6~{X^ZH=pf$m*))S7T-yyO}xVXWAXPJcR;#KZ{ z%fZe+ruSA9NC=ZYx{r@0I6f(K8SMKX-!1K1%p~+c%#-Vyu`?CZvgXm3*XREL$-tlM#eQo=&KsH4xC2!*& z@Id)eJ_fvaL86O>%z;cJe{cu9nRTjuULu1bJN0!aZ1Q+m|Ssd2KkRM^A_u3yJ|Q`Bv9V*%c{&=2x0ysiXgo zWe*3b??Jj$djhL^`Hgd~>YqpZye^jbV7!sdU6MQ!paWS{G8loW5TZ+ zpQAO;Pre(x;C6$O?A*G!YMwaN zI@%4AXi=2Sv#x7JLWSS*JylvE-Csd*Gnh3{5xAmKaQF7RVnB7cKHhdNrISi{daB^) z&_6)^osQxxrBthKXkiG#Z@E0|W!Tlr?W7b__(ltVZ2;UnTF2?q@9s%|S;NfJI(Vi6 zfhm*4I{9Fnd!%2^L(L)bkG3d8em$@9^^wPNUEnN;X%=N+JvJ1~2!ESZ1021d(F2F} zpJ}EZ(E)&_r6u^M;g8_M%xU@T7ZQ6V^`erDzM%VWRG4T+*a>m8oCf|iOdkarhl!`u zqshBC;f8k&!?@+eV^@6@kx~^HJh;$CwzrT9>c*3c4fAWv9T zE8gtt9IMPR8s0a4D8iqeJBH$dQ~j0{NR7Gtn^!d-m>Yl?5FvE;t1)?X8w%5Z}M z)&BKxHn$v>yTo@;B*?vW%TA+&@XdC;XYnW?57m?*d0MkIV)`d^nZA2QPi?+ErcjVFT#+jkVGy(e~$6v3|M=#nJ0_u+fQ5$*hmYuo5yxZ!w6fv5j6^yrjhbu~!r&*#Sq$b<%36lA$z z-Rj$~#ZUDcu2w^76bh78cAIA>`)Lwyt6c3!TH6U2id@vj3{&g#8{Xfj^-7wQFjXKm zJ$1i$UBOplX!Sofd5g1;UD_i)O8^HHFc`kRoRRmcqRmS};$GPxaX*&xXgtMm=kOw! z4)M)-?rsf*QkG%6h^Pc8@bnRd|2@``!6XaWs*2<#Qcx`Yb^@LwVc0<*y(tC3tNzFJKgLuQ$IR?r()zo>^&y7~fcreo){m z)ed4D8Yo>cNRpX#S@bfvGyXio4pF%4ghleURP{Bq^^M;`1Tg=wts4=C?i%dI&g3+x z0Up?l1PU94tELy8G?SuGkmKxfkbtl;&@OZCA*o&O`m&Lowhb%1CX}jOAo-v{1@)da z$M1JFH6o_uKCr3PhXPWGZLPo64jp)(EhSK-ad^MUduq@dh$Wuo_+3m>jA@~MUp_$c3!4X9crZdZ1T4pnP zN8`bn7~<0om}whVGSVkSzeNIOCXUuNxDs#EsypA0URrnByI=FwB8X^(j%9|Iw7XVg zjR=%*X+oV5p<^M=USf}&?X|0&C@#IaH@=Zjt(x=sGO0+%wk8xutKWDUoZ6<}#zAh= zlBy2Ilb5<6;4GtMWS%$@C&rXzj`Ge(QmL7CC0)ONp{dx*CD5K3XY)&ZNkas9b6++OprmsGVhERdwH(g41}voVLP*ZF}%}^ zYZ6+lNl*Ek2eRReU?vbo$L^5R#kxSoW5G!w_C1>7HlK*x%q^nV;xhJ zjBaZ;)j$LWpW$Luy8WeC)uVRFo&huZ>=mZJi=abXA;1_<#CS%5o%s{tfkS$5oxz3W zu?$#RmAO}QT6LK$-w_pWh^b>Pp(G^Y|Bs?G4`llPb(F`}2A| zpO1$!HzizY4&?OW)x>#x@tE-e7iirb5P2iob=%$#J|OR|qQ7-GgD~113|Qv>V|TwK zWDT6isNOq%cqD;T3*za;I=3Z(eI2-%CY?UAL;yiOIGzP-a`;3~2PSkQ_y{n7YU1Mi zcu-|@Y$w1KZ^k$EUTt41LVtl>3%A7jjouOz!W`Isz5 z?%afA3;e0zvuCb+ z0%keWo*D9(`$~dUg@Sacf+e#mfU~^D3tgc0u}?Rd%{Y-cbaFhIl3CX3%??3`B zpA7G>mTm#)kyHs~`Pc;w4rSAo%7Zx%Q-U;4sR1v?9eQD|a+t ziNC-!BM~sM@g_}c0`>_C;CY%S1VtWtQ6c=B{{gpE#wKGGnhY$?1^`xZ#jv|8Lj}!F zLB@as+yVFDx393=3F$*5&q&{`-$<)0^%dF&8&sUxEdbaq2qaM`i=ZlrC+p*cd}4$G zn0XS-GU-ak!+iNECO5L14exYZX;D3}oVFXI1yTMxK1qGwGKGxObjQjXDyZ&^O5f*y z1mx8AWqX&KI3o8^N3;rjx+Pt`1N^`$=&TFY*TmhCFKjiccTMdcWqgXW1N`HesyPE} z(W&veV5ZA3As@6<#kb>Ouqjqu(N@#XB?>Q|JDRB5&XnUeRbw~E2k#UDHc;xVCah&w zJS7AdC*Su#yj)c_v4fWkIDJHbL$`^n+M62*8IvjDJe5(=N*z_+x@_@QxXWHyq&#LI zY;z*fLh?IBuAY~VfGX5Oh>`o~*by5U@Ao^+1C(r)4FyAuK+cm9V`wd>27{O3!jL{B z?qZ%#CUS*?73BpISR4-efxk<5%Rah3c%2qk>bPKn2!RAS)^BSK@2qVxN|Es0YPqM_ z0PWK5@itv-At8RnJMD>MpyW+RQajr|MgnGZg7zYzZaU7` zF$KZ=c}^auxz#kX5fj-XX23JsV0*^FImur7)4()_#!z^W&pWCc*}Fuqn;F{{xS zPY#hm#VdAZS0QoAW$U7l-{T#tFgO0597@G3YzAo>p&QknV%Z~ta>u+p@vTBtQ#xN% zB#{na-8KI2LH?=GD+$>ZgWLOpBCO$Pkf*)5W9$TNdi0s-j^DPO$^HE77%elVnLe<6 zi-F~flciX99Xp>vZ%Z1fCbk(n0bsqkLb%qAvwo|^lod-X&>7DraHjRAwXz+bAvkBWWOeJ$SIA3lp?gswARNm zdz%{y+P*0ue&k#WA$;zTT8|SBX1d9zT>>CHVaGad8vDoZ*27rs@POa$UTINcf#ZL> z2p7Ias4iTC`h$!fOsBfZHwlu@w852Tgugg1fYr&o;n?(+cydr4SYErkm)X|K)Kn`Zv`3p6& zy;TkkM6DHWI6xCDy1%cQcajglo7Cw+!PH#5xgFdAc&5>hBox`zN!an{SALONtvYJ` z{fede#T;fUpf&Ve;jF5!Pv!lMs3qI6s8ys-c*hL54OWQmM8=HiQZH1v_C)>Wd52dj z;7sE4QaiJqDHI9q8l&qDTX#lqX_1IczIrfir8kYf2c--C2o3T)BrfVem^0Hc z+W38YoE$sDfjDR9__khMWXQDR)Q&&iGb6w^5JtU7voA;IfaO4GX6ebygd zDRthktE_4O@tF)BWO}h{K{yzcaY}pLU87u$vc52rZ06dA#ewxE*UH#6BNQB+1oiv$ zy*qM=qwrCFQZ&Q4TWz=}i6tBB!3UhgsFIwd$tCa<5;Cu2$Z^l!9G1!sMd5!Q+SVGe zn%a8P6B&;eUZ(HGnr=n8TCQH7q{?Wu=abs8&@u3zGAA8WC&T(AXAa8< zfN;uJiW#P*(?no_8th=I^TRZfeiKrlR%=oV8Q9mR6&iGL(OAXWtnV+~@pz<|RN-ge z?X0mU7%sFLfFh5c+f+q4UQ*zr?%RmktnU_`gdvy+nfRV-@$runE4$$^1t7WP43b3E zjgoh`>7-a2IMR^4B|mlvvx455M&I?Bu`s&Ql}Hyb%)#jjPj>Y(z9OA-m>Dz{#(XJim(d0-aa&4wn0)ZcqS+aG8#6;|U4~#g<#YyaAfj z9RAgKurt=x7l!;kP_f}K@kxLpYBgWZmX%a?+aV6;i9N*evW3Z#NpK{fl(J|v6yX`4?4XOCVbxCAOF7;X zUo>h~s|L((wh`1mB(cH{De8bNY(LbgNS9c6e}b9a4KG3(cI3|ULgz8y2V(a1?B(G#0jh3R=sfS0_@t2+N$nHZ3=->*1XTS@ zazvXBySSE&Z0QSbVR>|w!Q}qy5*9?_OO>a!B zwvp>QS=-;F@EoF7^fki%UN;VGG^=WM-G^itZ>?=_hD&?F?Bmg|`xFqab z0U0e)Wx?Cx7lhiyv?un{`Iidg3SRbVqwNHYa>K zvpMp$BJ0i9+tukQ!L=s-#Wa1dOKQTc$5rd6|MAy7^XhW@i}+=?kSVLBf!vvkkw>2& zSChT?#NmhP6XSoS1{ULn^hVVGIduW&@x1`Ki!*!G8XGaom94cstoAL;5}3KqLg8@6 z7iJC#W$tbXRmOK0&X#{0JK$43p8{Nn9wr!df$R!w`OB_N6_3*cpE(AfeFJqB@$GFy zNoi`%2lwiG7l+%o?i-_9%pZuA-5Q5n$C~R{zFT44!%1pKK)ktD%Tcv~QE^F;tju%K zgy+L;bZgCmt%}jFb6)E@24&HP;h)Gfazyw~5DoFN}v?U%rr_7-WIE z9~GDV?~CEfGT0O7pn6o~oml3M6$ZcW^0$Z|Qj-B~Ex^fPmvE2+;OJ%IUPL#z^CBJH z!0sII%HqMlkleD*YPmT-?Ar!Wdu{T#|9}kJ1M~NW8wV2^a4f9FA`ud&P9 zOtC}6wqerDjQcs+`<+_{)u0>%GNg3sgmQa6<;LkNO|8q56fjYVD{Bxw=I>o@O!+&( z>}p&v%?B^H{M=RPanR)_K_GZwqYb;dqYVy_I;}N#x?@aagE?<3*GbKgWW6_aJM4gU zemq-cptLFU`Yk(&UDQW09sPJFZxyt>Axl*V$UwACWTKFEwdmrr6G==Xm|7lKl>HCz z(0+eF!S*0z*g(tMScMlA%IJ95;pFO#Kw!7^d(eUDkYjo$k1g}cu}pSA49R}1<~(!5 z|FRBb_atM=p3o&`P>R5st~GOoyCmlgi2;OSD7_BRHp&a`P)XnO)O2TAc;l;o9{QTe zjn_<>xeHh5*J^s@AuPutkDC|SNaqx#MQ+^4KXZ(Xap(rO;|RO(en5C{wlfBopj)2PrEbS8yL-XE@kA`9J}-M`+j z)|v_-trJ1W$?WBWHD`j)AN`Ju(_djOY{*vyoUR{>R&8x<5;LK|}Ip%vO$sCDvvc8C&eL)xR^&#bj_sG90MlzGmLpTDC} z1N)_<3@B*VUq8SI`CQYr?;R$V7F$h*_IKDsbH~oo;Z8M)-@Op~FBB_~`e%FMR?CjP zxZR+8_n)=5yfR6=2}l$%4O>-oxpuBf?>bu<2_9gzzpf>8d5Brv6pT>d&t9&85QG7b zj2|1PW%i-bGY5YHN~+JUcIVZSA9hws;)7G;=`k=L$A^K9Np6ZaZ#<-J&BT4KuQYGD z-t#MU>+-D{N4Xij!`H<|FuOBAa^IrTv574OSHnQ6D+0>Hzxlb3bip;B?W4;(-_bK(jQzDw3{_qw zfp7EEQ?Z67vDn*{(X4yC4vk-SvauJ-T|90be~{I!w+HT$q_Mx_{e;2O?x659@t`4a zwRr7ty7?W=&R>x~e{VPY^Koph7Mpi$+42kgeFm0!ysV(21KrtlHSUhh_M80^{KqdY zLdNEk*gtMB&9ii5qqqOAsxXygo9BdiujzgfnOp_H)zF^#%wAodU=dQ;Kc=`g@*)3E zh3GLos{VJPb!}0!J8vHic?A7I;`+M`zpKwOkFOQ33ln>}VQ)sB# z;L`00Al;-ZwLPa4B_kKHbCPo39R7myBc}rOL5!Jk*jy-yFZ)fZp>T-2I~ipKLI|G2({>t zd9`>BMO5yU#X9jgAkc5$on{|;ctB7->5|Oay=sin-p)NHaf2*}?0=#z@6k#9%--tT z*uY|;)TlKftuuGu$|De=-r(u&4UaX;i`#tlRs&gk+VIXkU8l0|kMlSElx>cbml_Sn zKl0Rvf_EU6tNXyIq`ji(J8W3)TU^bbkD? z8;kZj*4K!BH__kjGgW5QWPW8}!OQxVepiTL&A0lQ$4vR$oXGn$$bBEV3Nb61ng#+z z5}p3%OfdZ|%erK+(WBuZfwGT&;qI1t1!bjW_Ay)Povj(8x{O#Q&UyJr9= zP3F=oxw77qSX0Pw2*3KCi{vunsnt<8%VC-W#?y04=SYOOkJZ2J0+Tu}iq%~r;_ zyVue#cS_q>?28%Aky2|{VHB_XAAD>ORa$ch1mH>ZvnUr z>V5NO@bVufv9aN<NX0k-Y#pOL^-aZ=`H< z*YV6RkL!(sjv;yCM_ufyQK>MuJN#Lw;$J6mdRmi1Yb?+@;d7Gy=jYH}XKL`FL{;W`#S z2ocz!sK}*Da?2H+b0cIuU8$>fKz~x^=gKEWV0t3-^^TSMqYUSY)=G{VLb%}kkt2CE zU9m&j82-k!J}Y|xp(+ni$>rnW2?X&ne244C4sQ0ulZdG;*CU!M%5i4de#@d)v^|f- zDcnC3#=(fI@xPD1wdUIhPpsAPGk~|&8qa~sYn7KWi|=L;aFUX96iDuyJLmK~{}}a< z@=~&ra*6E69uCj5@&yb>Ho@4vzr^jE>Pka@uVjOXrKlTk_Fk#1`8)Xcmh{ZMl_jb~ znDa&qu56a3|JKZ_<-JOEqF;%_A5RSSRzhl4Ww_hajQ4&krB~0SQOW435#vRc!Fqk0g-gUBuQbmj3EmUlj%{+O4SzrOp(T+Ny zHu>e(QODIJ2y}9{`k74DxiZ-P;7UA8tsoa~>>Ydw64h-aQ)ioEcKu47O6GRy-20=b zl;U}_Ks}fP?v>l$GRkgZgI-psa|hTJn=#sdZRQkKR2{{=8z&BkpTt3CnR&209qId0 zQ?bqzvD*&c!N&07t)X{e+na8WBYhsb=zU*xz;uD#$p>!$ zD;-;Ls+8GB9H4k*Ds^{Zl#S)9B%*$vviw@KDMTD=X7@9yjm58Zz0XF%?R%gabWz7t z5LuRp$=iqCc^M=-_6T4#$8 zyB7=f4lsdxUb>PXuI18C)|~UJV>))^5jM&yVzu;y!OMAd?Wc1=7paLuSwyAY+Yf%6 z=2NX_D8WL!(&+hDPiCps(r{I{gQ!B=(cqBLkS+VVN?(Wgtj-*YNp`@pn>f^reJ|$H z4ATou1DeP_von3cps>>O)R|6q3NP?Xe_|hDW|w4tE+@Iy&O#3;xa)b+yf;5?)b9FF znVaxR;~i)`eXKW=JD?X}s$wF^UjTJ}apbkKDacXlXg$M@6ry!`V9r^;0~qhC*sVI1 zPkFnFjo(@Ofu`jiK0l#Zv^~;Fx~*ODMJUR%Jg&WyE68&~ z_JkI1M4!yiWg?F(a88Kvm!t@kZ>+>D$ z*7y_MIPe2p{9^QbjTfqzoV*$vQ>4my_t2HSZSuYRMTCIy=75;SlT$2pJ;BavB!P3< z)B4yeNENa5k+O4yK!i>@rQaFt5U+m2s2PbWiuoYBwtbAbdZjyJ?ms{SK!R02sdC~H zeXza?@5VSumr4=PnS#;AGfsznB1r$>y6x!o0m4n`wZ+^$%@0ReO3I2Sq-hz-$4QS_ z#n|a%)xA!qEaazbcD?b4ZJWt{Spgxy^Uf@tK{ER|`=R$x2ni{vO7MRI2o~Jk2R^5E zhd)y8mM-WRcI>nwwFOBDX`kz73H7yRz6j)-U;P|Ka6{u8*AF5x?q*drUVOPF!HBh~In zZ^0P|XW6}P9UlR5wSWploWjq&YS$U{f)H#^n3qGX@4(DQ;?|92N|d>aoMKCsh+WydykzT`M3rMv3zoV-iD;GXvc4F4KQ z>9$0ociHRVSAk$ab==e1<;X3aqKC(iH)%CnHrAL(3Rk~HgteZ&e?{r{YO3Zs*|Yq@ z$%dU9CT~ZL`5MnxWs=-(xbgfzvkDQkfm>``$l7*g_8u`Bc~aD^3pkB2zDnG-p0K)i z@Im{tX{8z;%SyFl10mv3B$t=3#3k@RJjKUBTX}I-`_7dw@N|B5m|6BenM0?qw+~6` zI{M6iJR3RY%ljD`>8JOHTj}nB<#_~%&8;+BEuYZ1(TnOpV_b+07b)QLMS#cAEcM%1 zL;xjYqvov?Yh)pLw7=sweKD(HZ8|0=u?d7`)$M-&VA{3{snVz!j=l09z`i6Zzwi5| zu{q-IdqLt%Pyh2y*r5Evrz1iRcYCee`j?O4;I}V-cdJTC;(q;qY~i=~9KQxK?u~wX z?i`63}s%~Z*K=D+&z`AxT@VcJOHv6Y%QQ+V7=YlKEpX3e{w$-kZXO#wP3Lk$;t zwX2=2-jDyurUIk(40)w)c$YV`;0`V%|@A0(usztS-Wcj;c&=2T!gxESN2K z|C|`*ov3WpuxREXj95Y)Wg#B3)U4U$P|mwMUG;xN$Z$Xb&J9@S*nv-%Yttw7%V@CZpIR|uZOD2k};Dg=GA zd`V`VZYj|Wj^&Xh%$bdTI=>rok&jj9|B7ob|6^(1z2Jh<6bCwO9P2J1N<4};*INR8 zJ}C2|>peZQ1`xH5oR+fp@{x4oa!+ptcjl`Ln+!b5Z z;o$mkfH2<+xkf2DPxj^Uv!mj`YSk(G0ivF9BthXUe=cg2q_ z&wsf~*Pt2cya?uUz`)p6!iRr8EF2&5jRFco%-EFqHJnIXraDBbkpzyS^gE##rpjpYq_?DQFkQRd(gLE%Ff)EL~{$TdyC&{!ao~&75~#;9->OK zzfc%WxH@|ICA|LN8thY09x`;Iv46asm3+iuT-PkIA zuf_e>#q7oH?k^!GS^?MgWgtOypn2BC#h74M70d=07FCiBrHyxVW8Ye~`-<~as?mYD zA$~=+RYaMP8E0BxT`K^azk@1K*}j&RCz{Umz zxxF+{JS#FB_dk&Jb+_}Sssg)Wds^&wx$Ias&eo?vClVdwLST5AYx{J6C)*;SJx5<+fJOB{8D1K%K5vaK5pzZ~kvUhX^J9%~8e=1x*P1f~i_A*=#ML~> zK%~K_`ClPz;hWbe0M{*K!|4B6no3neE5tTNv{p<{wjCyAhnz^=0T-3?`WXj5Cs(tc5ByTNkWE#pE$0vgq+QYy;CaMWNW5Zp0YO{H7gDlwWd-Glm(ZO?* zTTyKes2>8?>eL6IywI#3BbZW^UD_qNKiB^fj#PoXvUIZLu3-2oEt|b+hp!J{1<)qw zMl$fWl^W|wJmkLyzJN&&Jyo#SH9k6pvHE+;Hbb3yl4j$PZIpsw&7FG z6d_W~><5PS?`vHOq|qDG?WoSLwIgT73mEpBF`AG<2?uiG>Nz1M0KBkItor|GV`1mXykp5|xR*S0}ilQ-kU#e@vw#q)@7hIm5Tq)%vnEWO1 zuyx%t3}-lKim4xthXI>Jvur1>aT0{ovv_$i|DkEx@>U9>ZCcFpQN58+anoq$9eoFF#e>%6e*w@D`q%jxzA|K zUU6@+?L7E+puBZ8VBJqoRL@@2i-eb)Dv-{iJPpV`FubGHdO7evp#HmcDLdL_nHkSA zKM5Al)S8DBe;H|Ua{XgNU+HPj>sVkXN%pvX?{wu!!{ECVo=%kH^f$yM0Y@Rq1YRIO z*l-&Pov7x|Uw=4ff#el5u!oZQ*+VR{X)A>7t;&+*_nW22ZH1lp6SzjcY_IC$# zJ-rRfm0AHzUxu`M{Vo^)1>b1nmU#$Y{;!Ws_OWi6`?Z|LYXs`l+%qDEcJ!x$;+WXX zJXopA7SN8`lw4C{SSO|^@MH<4`Slxc7~KTT;1nI(PsAdlSxD+Ip*In8POfXL#w^Dg zw^L@*?=PV=qJ&*lni)fe94YwYd;)l-{L7U)%-MBa-p;p1@=8R^^-ZT!b9TB)$rO1> z&ib>T#)RHy*{CKAf`tqov9`NONZ9x8)o0!c&9P)QIo$bk2@4GLR_zs;IF*7~IPq0B zgYS_dH*gI`5DDGG6o(Lz@D=WVK)GuhSIJ55ui*Qzt){QBNEaKK#k%Q9zzUY9GE5SB z_*{FTpdxj(g|qT{3?t>vbbcb$ZR?KS+#|fu`bE1;w;*?1iBE~q)lStrombD@Us!+T zVJzC6l@`+~? z^;wqMf1b8hxw=EEqsRm4ILUC6 zIN8|KiZw;gj;B6#&2ATbf1iDi&!JYm{buAm$bQ}V^OEB4{egNPBR$+|HLu>T9CpB> z9;k7Xn_oC(aU(I03?8=^ZhuST{M3e;S=71@Gzo)j)KXWE{9Wx5P*Kl>+N4xC|JrJMs#*B#9sRy?ulV(pdwuS6}~lu3sxxrA=Yv&;I&e z|4bgSSD^yi2F%Xceml>)HvEC|=*h$IA-J-QXcN5n24;v2|Ap|Z=;ndvS(~nrp!~G^ zu+5oyaKaF#vJG$9bPEtD7aX=hMjjA?;W0CBosIGQws}gKf=cEL6+7|DVeS=OcaIKs zGS+R?QGXJoQ!K8soy;x?3Vf_^E;O(;Wl7}vI5Q9Qv<8}*r)2Idj%k-^DB)?Xn z_rkh=)-5BJa`;c{+6tkAD`KqO1&!7eKtWNS6O^=^)(60l$VgdHvF$Q+RtYw>5t~h@ zopOOd%}|n3JP|Smll+)G@EY6)Zt|haZQv@pio*0W;$x@dv@dd%+U0h;wGz>Kd-2GF zBGJTaRkY?zHjhwjJV8D{oSfgdNF?<{UdzucxiMU52%8chL}vF3+wW#VbH`EOGt;a~ z+WG~6o(%H=Pq#e36DxbM_LI50HCmk|d#ObI<*i7<_L9pTL|ZTSK7bCV58z6Mh?s`O z*QeZ7jSFnd<=jdhqe@NN$ymRJSgsM|Nus zR3RKoh)|Akh*UAl`58Vr)ajtCjNeq@pZXfwj=qmsSY?nI8u8O$nFAcaB7KkhAjZ$A zT)w|5PFgP=K1Lqw+W#>^hHEB@FZgo(;c$?AkYg8X{5eHy)H21Q{r^bw(EXVnLUuI2 z8e*e?7(cYk&@tIP1KJo6EjsPp|BiZ;LtTZK83&94h6Lfazl9xzjsZ1@IK# z0Zg^h-SpPxVI@+0e=*z#gq|3+v%N6X#2I|MOx3bg4+*@9>JEw8~VDd7LC% zMMU}fU@Drb3$Nd$kCdL1Fu`}2<-mK~ynVB`2iJCU?Y_bmm8rx?zly?*y66%TXR0kI zj_vP&;Uru@VWAbR=n(Jh1$F>>`51n0>2YN+SKu&BWRf^Ym*{%7SGdC1IIM(kmL)1G zfp=0~g|5!#wrskD96mIK%3PwX<&|`gO|Ss@g3*MA&^(RXL7%b|{KaC%8o)pQe%XOQUh z;9B*q=YZ!r6KD2UudjBlzS58;R>{Lu$7uCv+O6R~$Yo2*t1w)AUQcjJ(Bp?JWk=G6 zs}pjb#{ij_o6^L)FVv>wm>Tq)(hJJONXRljo>c^hXL$N))aHS2CMRXO0wZutkWA1N zgjsN?^jv3$6DxPF=>hyo_VQXD;G1212we((C5I+!H+~_Xxgc6AdC2V6g<-)A+4!=M zz@hKvOhX3Sks??k7(Naa@y!~YA_J!{a7By*-SUzOqw#UJ+;SvIR49|ZhO$6? zD(FqD%8&M?X7O^DwOZZ$O4KMS81Uf_l$C@`F0o^+H#VJy{g8o5Gi?$!^}O;CR-O?k zIB^ZvR6wUo&i+f@8~;NI28>%5lbq==PiP0OX>(OiIBfb=(NorNkwRjAqqR9wapd zlVIZVSV)cy#8B3RxiiVPWTo1%3%OSp-vAH!fe|1!_Y)47ap11(bud_AIkUvF_39Aq zGASf5`S$t6Z}Sp;%L7;2$#_Fl z118z~x+nzhG%UbnZ>Nh_o&kRDOIZ7~midQBi5Z&nd8v4-@3nXH`MFbgh+E zE5cY^^h>~A`M48jOd79a;q|cmV!5M43mLMm0SJW>9r87qVs)*^$JvG2Mw7UH3i0QJ zk7FF2XM1|#AJaXQNy`=UQBDUfOAsbOjj`UFFYqEO+^WwtFQ9t$M-P89QA%iT`z^o@&mD4gI zk35N#2R5aH zYYMGStSMQ`HNYG05XGrI+a>ALQf$08?kUV)4hVFzHYgNn2VC$AwK5@kpPkSt9LV@U<@) zw%`eBJqgvPBgMj@KcFfMiW4!YDTE$hw_Q3234>-ZxeH(^BTq7c>t?3VuFrY5$}Yau z0tjx5@_T+fqvUKQcoV4Brm@f>!(%B?@yt1}I|&e|pMGkE$*y)>4Q$!g!ek%GX*^kt z-7lTt`B(dAx{(4f4C%SII+N^NRr?hq5(zh4iG};+zo)nnvg1~#yP}KgaLsuV;u$Q2 zSJrGAN8thGmE2djtCjq)VmnsN^xlk!K@s_oO=J&j^Z*t^B-%A=bkR}iC;57Kr5`yt zOPt%)2vnE~nlER>3NPD){D(m_dYWPtj&ib8=b|S_gvu(!!`kX?=|iA|F}Q zg{dhSiDra&DXF$_0W!v{(dCJQo}LANBu4I34FR0dz?zDV`2>^UO+8yA@F6vO%7Lh7 zZL}#JXap>| z>j#L|==+*16FpmQg9hRUSr+U$hpWU?m>dwEmu`S~u5S9NjFh$#nFrzr2uj<=H=gGa zKfZ5P1HWvw1Y(PWI~E;@@4KE3&sL%TbEH5&`iq45$jq-F1$aAn!!l)mTnjk8`p0@P zy1)p5Xp3^u0prT7B^9IM3{AX-`fjF3tZ*Oikoyg6cQ0hu3p5%hM6il4lpjfTE2H>= za>H1+x($FBoHM4$OLG_{4pT9m*%Rd7I@kfa-8i%K#{1nc&dj+Kc?SjWT$gZgF`$(n z)F^MRJtCIRv=$NE#CCC!fglI2bPt=o?k3{WW-Siw6<%=Ks+(4j`_%U$vEsz?d^ZpG zAudTf_eEU*e`PkAsKYEUBem)3|NnPeM;AhwM5;*5JQsUAPQR#vnE|~f+piywX{|yN zd!HMmk>!o)Eev#yL^1%yeIVp3T&JA@Z3Cw=CzXumK33Z4T6^Bxd=4mRU6%q+kC}M< z5I_sQBSGWVsKIzI`E`_2P8lj^j9eLua*YQ?!&d5r}8ENz!G)mmg&bgiT8K+A3>~dm%bg) zsK~uU&RQmp#c>&FW4Ote>LeV7S8H%63h0J zWl+alxib!%-gmGvqC(XB4lip)9yo%(l81b9KwXT)s<{a%BX2(-N_>bPqUaz3l>+sw z#%W6m60TJ#7NU7akwV!X8J0bT5B8XW^IhbJc0!gq0gIa1PzpfSj7sgMbM7O(*I15k zG!X)dpGcGkL^JmiTPToZA{3`H4`B&r*q5ZH-%Lx1 z*mgeVqpK!0OH6*EL+4^RSgxDw5u@&LF`Av(fZLtPZJCvw?IxdJqY~&YXSo0^nKLqNdi^Nd5sTb2ZQN2X_-69wZ3supl2(D zL2T4sX=YA?grIz)80|wicJ|+NN%IDNY8n@e+PWLQBPa(`R2coM4BwDVUp}J}yeVqJ zywM>`&mBm#1~RDA(Yy{mFoJ(e0RNndshJ?2mK5B|xUoni%3v5=W4`5k5xjiZK3?-r!s0edOG4v(K_1{(6q=KI!6kp;+O;j7u zCMC*~Oj3^ZTxkQg@~z}-#NJ*G{BnIdLL(QHlQ%qw1z6F1w7u&iSoWQE0ZMF>)CwFC zdUymHP=`U|;(oa-&w0;&=J}yDs?QYSp>Vk6vTn=t@>lP99U>4ML;M;&n+~4J> zkGRqSiHB!0rft@WoNNbEE3}&VB*|2GR}zASuL5$yQU3v{YmAg4^0asiiR!kS&d!Vq z#6lUpsfoa=-1K9T=AbU%rkG_Y?b#2Ubp_5itks$gF>{G^osA!k{4EG{zG0o>-Dp0n z<&wYrZ7JFBLG_VPsVG>H7*DwB!8WgHtIJ^ntdySJ59oKv-Cz z{eYoQyeH&Igc4s|8o0H^c-$xpw_o~(CCW&Q(HyKuqp4O7wv!;$%En8Sy)VVejz<86 zM?qt{8{wdU*r))|6Lt!aoA70=m-e+C9L80z+#=grf3XqySkLG|aK$SP;E4?YB)BI8 z?YLOTUAJlGqrnhGU2_{Ib-5-8K4pWMD&Zy8l^}y8HN_lLruv{Mkzp@Qk36w*kiyPs zNv^azvvA-n(>Pr`paX}~?^n!}K61gu_Bf;&S^>U#JC+Q4LzE$v-V#sg^KmSmW2jxEi55m+<_lBS{uIJ+i z37CGAxpsNMBeY8jL0QkbznXA?;D4jK(|^zH(|uZ7)gCu)c#6TAf~hUZ`FBsfxmk%H*S-HaR!lJX7298;-eqDAjzS+B1rjyxqE#EcGRYiVoc~he=*v zMEfq21SbBO4{dB$zNB{H;T6;TUu|x*2OPLPq_l{sCFa9Ti81K|T=5 z^H8&UKUhg8=>C+Hx7BFka2MZ{X4wZvJo%%e>X>1B1dq_SzVVcq$UOxKjaPYY1FhkHCc~437M)qr!Mwd*AtyAk| zbX0FH`r9*UL@=Gyyz7}9gnv7(e$NtUgPX3hih)W?K6RjQr1Q&wDkSys@JX-|QKc`DbB&L)@S+d!!KIsr`g6bF1HJ^<5>8SAIA%>2 zk8i9s{|r-=hoLm zOmQvQIn0yMOdTeCjdh1Z8rGIq@9Nxt%*_uY^?<2?Y**y+)!_HvC($$3NZlMOXv0jny* zu9w0a$4+0({N>BKE;3RAk1zU>F1`BW2ae(rf4GnQbTFpxfCr2FQSA4{2C(KPZ!ABE ztB7(-X}#~cw>dTz)_MN2j8a!jt7FC^RYeVk$S)8`FK3;_uD<^s#n3= z;?_nh-Q+HzJr$*o(IS2> z?qUPs2v}1EvpW8#)8p?k+Fi{nD(SqCVxl9_Y`P=QSh6hh8Fj>+OwBCcymsMH`*3+! zF0p4Nf&U)(&I?`k-J}V@KYou>folb3ZqxSAn570@b3QtwHWT|&R)zQi<+?Cv?Bv23 z?Ln+;2C%Q@R9MwttQuh@nH+z-$|k{PF1v<2KZQTkc0AGWW**LRlCuKt(^ozJ&DIXyeKLIX#$s z`LFR#I1JtfDP?Ut1W$!Nus`%eBJI0}xJlAws9+nmtF~d1zH)9?pu6qk=c2?+%shVx zv_UtxD=D1wj!^`Ku&vKCg}cwEJ6_im;YLBxU6}otz@h=K6D{)Z?7LalDZ@l+U=(Q$ zCF>iJp|6s={Fd@IIl;hUI5ZQhvN~Dztz%)#MR4ZvTsgOPmA=lt{^DnOLhz@Cu90O9 zd-2-wF10tQBvUX2P@P;q>~~oMUYg^s8>gn_4_})~HaZg=aeZwm*xVymmxceN)#oK|MS4g1!b-3e3JS2B9x!khZQ- zvM@;h)4iCI?tc#rz9NMUf|e)#13g{&xcp+JXP+p*s0eXs`()amq>)HfgM18Te7nHi z$Ik6&w|u+284Q-3oz?nd^rWjFRJ8ss%ksRjQ!l{Wx>HRJR?*!HDxRCfV#Uf+4Xv&X zd#nk@yqa7c*#dWZ@?q8BbG^X6FpFzl-Y#vZas%Oy(Z-tFh92z9`toXVDYxrjlGjo_ zx$gmN#+kM*oN3ED9`*R$^vXGUBCwu~fE+>$E)U&C_EyE10W{{%24aR3%+>Qm`R z#9aU){*VvhFtQzRxRY?8Ch$2Sv=DTpTXs1o>`YVl*-gp1eXZRKB;@AS&yO)dTM=Fh zCX;d4gmcT(G&RRp=3&(rtuS;DCFFL9!=G_530bc7ESZ4m>9ucTZuq^0?Gn-*TD~5N zh6?Tgl+b17zGPp_Z;M-|tm0>X2K=QkP46$@7 zGC|?oV%kR>vsb090bxDfH_@HeT< zV-fS;c`!ST>abgO(eWEdD6Vw4;x~O7`8+EtZe3PzSG7azhFjplZ^+J8A!%lTWkbyz zL-xVXk9UWqzr=hxN%A(bTcIqOaDP1fInwlIR`Bqe%{k{PH6dAAgN15TzgK?LG~@K> zAhSO_^w*Ai74;9ryTkb;LpRdwqYkM9K1stUh_?i!ig;fm3303VR!3_fZ&p9Lg~?|? zf3YcU?ue_#FHz@mH~4+eHrB z{`G2Sr!)7r&b1l|X)7FRObi!7WHr^m4wWj)7Kx|q{pq&Z91$3r)+;zv6jk&5K14ir=lxM3xGB2X3w2Vz zEdEFR*U&F&=jnAMjKgg7*4Q`kKI$D)2jS4UzG`MI(S7{Vh0nM;`Ko1`w{(bCzpg2!nPu=bL4q4 ztAJHl?SSozIa_~qK8o^PVF`pXBAw=J0pKl9Z%^scD%xgh8_xMg0GcfXtn=L6ZCjt% zTbIEra;c2SkKVH(dN020`x)CaK`phEgMT`wL;eH#b3q)Znc-pm&aLm%s^8Oi{#nLZJ7U;(R0UlpX&5z)2Yc51t@Z8D{-L@ADsTzR_0V}iJ z_4nwME`^hwebIB~qC26XIerS{CAj3#YUk%Ja=&z?-ICOee}iQpV|+`N7E+bHd9KCq z37#a066~2O#@6b`@M8)%Z#U_Q0|n{D7_8+=e2-|!G4t>)?O7dIq-P-8s`OqiM$c=4 zP{k|(QoFyBBSmfb-9&1XgfrEGx^(#&=UOhr?tXLSaX>{UHlk4EEN=k8diiYQA$TCL z4f-*hxJPU`S&24kz0zU9%N!U65R)IZ_f4;D1*lkD3p%O0BZXpb zpH*p(ST3>t1NC1te{GK+#64jYOA`FXqWaF5M)XD*RUIb+%bux1g^LXXat`k|Zef0y z%iIg1{#Dqfh%V2?_f%&7R701wTiJiopl0SE%><7bp1lMZAgvfZ>HfP#cGP=Q2fN|u zN)?miLhSNYWN&^AQLnL$`za4DH%_y>A0-m}lWXAUK%VP%W=Qay`hMVH8C4zjBkOrq zo|aWv=H1GN{`OB~0zKuP#@EP=pL2?Q&$qz0u8&?VdU-nHhqCsTA$@(8h(oNkG=Di} zWeT?n)%xh+=-8@PlO|SgWqOf;VWwxMC>WZZ{2q9yVA_cnw!|v2Qg(NihoFRm*lpPX zr$!BZhzA9mI}$&|2FsV&1nr`){WKJHP^x zu+HuQtl5j-_Nfy^MJBr{RZan2_rzX%sTd1$no6gc|I_O}9O7fkR=>ETFW5|^W58^u z&xYdSqTe*W@J=j+uB{hSf3jZ5A4h>ELQ8-w4cwu?q#K#)#um-3n17L{fAL)<@~azb z{xve4)s`EjnR)k9^rF)b@yOEmQ$o7LPqR_ZYD!zAf4b4^wvV7PC?oNzb7HEO^#E93 z$NpZy=XjPMe#TF_u~jXUcK;($1DENdeNt0dZbX!L&00Rd)v(2yV}pVFv;Ml9inK|PUmvZr$KL(I0}hE|G_lZlrJg}yA^eN9pn<3w z!Nyq=fCV4o`a&rE>y!OE{Kk8K0POQLU^sClovi>ITr(>UimEBy?(9rVcgRQlief73 zftKyw6sEi4vijju%15KBxm^+Vvd;ssy|3l^cLr}ocoHkeNRZkc^{@V-m^D6s_9ZU_ zHGY^7A`0^!A*g&dEBR`=$@9f+CF|qC;IcBIq&f?jd5AEmC;CTawbY?QARvTE4FVG1 z#K(UhSQGcRG3B0*UcHbOm#<&U zyLMW$-ii7RFPCwnki$SYsJFF?1q>o1zcUmSmKkz&u~$fmdFExa44IVA40wxz@A1;p zfG$(bFNG<8#uH(q#8Y~SzLPzH01<>_L;6WZgHB=J)#+Rb_kx-Ia3wyEv@f3tf_%GG z!&#HN_upY3;&0YCCYTfyY))0&d`sn#kfcsDy7orj))mJ1ft;tIwRjV{hS+9?#$z zfCZXopCo-OM%SbPB2wo2KDx`~jbs3Xel5+*yT;h0vNJu>N;%sE$bjKvx*N(| zlG~4sPhY3QS;?D$B~rgcBb?$v%}LJQnhz05422DY9BKt8Q^osuRcp`iV=J9Z7DV>3LgZIV!^NBHuezs=KPLD++hS&!OC&(_nH2K&*JOWvXv#pIMn~5mh?Ue| z1%7akBkF=6a+i)6u)`B5WH;I;WaN08pvFqtJ_SE^ib9@5&l0z<`ki}{b-YG7SrJ4s z)=BqAxR!tDIq9r3y%Gy<$OcDSl{QW8un@%ki#IA=j@}AtpC=}7T{SPi!EKs40b&Ak zUo}h{o!xS?G%YDuhS=;09H=gGm~J1lchb`mLm>}2S*+FE|3G#&xV+6j>`h>jdhw}2 z*%D{6q3pZ;0-7nKd^ z1G(0Io}#<`yx_DXNf_+vg*YJ)2>ejp+y0a)7gR?n*aO6~wXt3zyICeKtEY7(Mj5B0 zLh~`VzC2ZSPSfCgf4b05slPk{v{XW91SrBO#MX#%{YQVzVN)1` z6j#YMNP5basWyNZZ7^HgZ)chKRrH!{<7^XdZ;|ykL=T#n4gMyD!{eld3+_P{2^uXf z_gH%<&ol^1zZAXgVE8dO{YM3efujAI0z>5ey5XwaT878VUa?e5z%x1~q@GIA0r%)W|HSj&O- zP%Omv`y9n>I#P!VAQK+)3g4M>2}V9lb#a4&)=ONG%_gt)zb{HDg-8IF&-0bsDXu_V16teuQGSFl>q`18A*hnl_ z@m8SuzTYO^^0=#h*cfxt9;Zn2qy}v--+Ilgm2u={8Fo zc##0lQDQe7)8Z(uiuPQlM5_2!bxl;GP<@r$e3Q8L|0ySy`?wOG=TA#Ma#~s4E#&nG z{BV3d%9Mp2{SS0x{_HxWape>3)w!25-Wu$z`_p;CJsjH_c~Z#TuOIb4Ps%VUy9N7O zivGKyjWPouL0zwV>3r)UnD$BY|Y3nS(ZLjJ)cy#hb#I0?51I2 zTF{vtx_&B*?VJ<=7mYwUCp5Zg{ao&wKCOj(JJoRQoM@U%fI$C{nqNY?I~yo4q879B zc}r>8-UjJ*7uIK0+B+ya!XG9BnH9w6kK5XGA6c@kGn$jM_n)sYeDX9F(ld#;RK)*I(Gnk6$`!Ul=9>VjEssa~ zDn@9Am9Z~2#kd)%HtoL~*+dfWi(XvYBU(u+zLZa=ee+*`r{yxewzx0R8!kXh(j^0H zrl&~(#Ri@a5i8ra>q&1cM|bP301Jm*t*^mVfH*10Su1d#7TlfxOH!Am%6!+>ry<1l zBFz#5y+k`Mo$rE~6E~L^ZBprtjPFwE%k6tXMZ>^)I9+m)&MdGf=g~^b#DUhkpx8XL zNDL}l7FM|byo&#MVwIf5Pcq|{Zr^VGyvE!xuyh9bEbRjAVA!QAe4UZ(EH|{(7?J+4{jFkfMXM>Hh z4pl`w;*m);jFZ|N5=?>{Kw=!A!rtwM+J?sXk+v9xjN6w|=nyn3r49I2oT%=#_EstC z{~9Nb%+WJ_fZrbXKFG>q99aEEc1z0KP7sid?7GJ*dPsxf`qop|O-{{kb+yG@0&4XY3=w zn7*ruBLQ+1UeCkwJ~KLB%zV=MABM_|Y+$dXeX7-N(n2>h#7ck|@A<-HeFKi24(B&j zgmjv~=YIh0%!MNR2ql!}l|%^=a+js$jA`C;h4~xzORu67 z7pC(6y{6AXZV}hk3sbC}qW8XMIRPV4+ySH-vqmn(2@y`Wllyj{d26bGxo5jHs+@b2 z#p3|%*Mnv6@gyE->y8qf@B%M0C1sS(#{!u^%FOr#e2Q~TpDYj3;+GgAIL7zK%)5VT zp*`TQys%OBs-#SKS4av|58=J3hRB{ z?*f(D0qAcPW{n!$=qiL8Fcl>AyT}d#olWLj63QhH9u z)4ff%-o;0HKcc2c+k8v+HSvtNwF+u7B>vnEoHw~|NJ~y2_)&OT)jWhhF;XnjzeKE? zAOiBhpGfB^loduVN$SUnuVzuk_%Ygj9_gKG@Ee2}<0D3OaRs$y{9Q?2E}AQmh7CPB z0B6Rb^dFrE{>MX=*S(A_p9VbjcctAm}uT0z!WKk$q zX(p%Iod5ub47sUT8yg2H$kR65Nn@DHl~3Wk@~{(*^n6;H(azF69w2YvSuJpFH4~Zq zG#xkr&7iMt+p6J*=Ig3g;rq{P1yn*Jvi9zSB0DZ&gzKv~t9e~Q2c9uLO*~}M%$_`E zZy1|cnpy2T3xiN)tb1$QR(zkrr_ixa`Q$WKLST3sSglpQHW=AVt&Om2x)7-frurU9 zt!{k}1n(uOBac2B9j5+om-s>X-yl*MoT;v^re70jR?J$m1ScvMAEwe`*H~!9rV#NRv(!0YqbG6~#Axoe_ z-l;gTm|^n9m#j(eM_CI!VNLXfW@07?$aHlriV{wd4{xz9UsKHI+4E?5q0XJ=Z`CYh z1z;a7z5mMV$$X(GTN819+xo98>4c#TgLW&m+ z%%P{*=L~vNF9vHQ)s=C!gef-@OkD~?Tp}|uA0~-^Pq<>FN89K1@A2>Ul+4@h^i~I6 z{9A2Rlg8Bq3JoyJ3bmCBT7uaj1K}9#qsaUD0iUaHH?B*sGb&^S(3OAB46`?X5_;-2 zzbsB})fpapeg(c2;gpoF@G9XP&?ks=6D1pgsAX2MIDqaZUV+eZ4t1 z-U>M~WeopMdsy^9RZDNl5QEG+_b08AS;z$aA-D4dOax@}jg623Br%BnEK9SS-^en%IX*ua zH|x+>R7z?vdIvGHCXx36CKS3Ve4#c}7<6%3&aV}{rjO$cJ+gVyF485~YSvG`eIC4v z#mpMYLRj{{0(kz`Plam_St@d~A%`?mcIctuzzZUB_>20^*f{0dPepF;wWNI_>QowaKUc!_?gTTpgw135plMqn#JQ~=sSCF? zTkVPD%n*l8_dJ_JLo>gyNX%ya1M3dDa2mdos4(#-g7aPc3m)pR}EO{F$w=M7bR zJ-^_4{Et>Yj;&WS6(_wd2C&YyObme(Q=BNDz?cbmGvv_N{3za>KMRMT$qv@YdkYAJo7S5NYr&B#SPJyp?k{zQ#8m0@lW!HeA4- zZb;FN()_W5GX|ewppp|8*|syz{A9q*V5I}i2ss!j8jvkm%7dEr0#XX!Vb&!DyGG{^ zDuH;YnIpn=-1putyc2j2S-*Bb73STLfW?imV5kB*}E!^lO9sjLmGYTen5;?)De>PTolr62ym>g zxOMuV-ZXZb2f+WgHYA^n%|b?Ig8{@*-%3%9aKXZtGcT@{hOABy_wMnQI)DxaJAb{A z{hlXlGtS`lKtpdL-AUyOPP)AnCR=n?ci%a}#0HZskiZKv-5C@CAl|l`$~(0LG?3B4 zfog-!SOEeNkgXYK3vcr}!gC!N3(^A5++mEioGZ0uvD1-@5pq%KrgyzbJgd9G?xO-T z=a&HS46O~;k5kS|P0$9I=KZ<6%PAtwVIu+gtQ>(ZbmLU!pQbf!ZT&a_l@p2!+)L8) zXgfXTtNL3acpUp87RL(SbIKj-&yUvh@G>Vnu7 zpeU&VGmyTqfom0gXYhaO>jIz;YDkYbPxFaTmJ9{KmO&=+RG@}jL;>l8KPn61fb+*Y z=R3xlvgeWWc4s9k#3V)1I$cNzd3sDh$Ik{VH1xrEj7U99lJ^!E3*rOLMbXJ*>6Vvp{yRta`b+rFzmP!2t#L<<|~OLXErDU2TBi^3l(IhBk>lt<^B_daKC+t z-@+167|g6TW79^w{Z2co06t;Gmo}~ShN)l3;#*0lI+RQ+r-Egk0E}fV{O?>axw1YiCvyhP-1Cj9N;3QC!S7=yain8?G6$Kfua10sm`MAB{0n}9t6*PHjurx ztHjja7b7#+MwH-t!9&8VF{-iFL^_cH2RNM8t-8LKW+C@&v{a_kGu1Gx0t;oqj)~>H zpMA*3ZRMz+0Jn$~l6Xag2!ij93{* zWGca6>8zJ?0J}?PPZcKzW%l2$0l4YPbwqNv`4Q)u)V9Wj5vVeey0ssa%{NWKV_5l0 zTMkrULx;^*x+*xAHOT~z*BwhJ60pmRCTy^Ana!^sPwUO#uxWquwWVp=%G*S9hOT4y zJd`-l$2ON43_X;CBDe5CWyWW28500!%funmR*k5tc^Eu9%J?t8F`;@tHK%k)_c?G} zedkk1P&1k&Gb%0n^0Zu&xk);#vj4fmxd!&2gMu#lEqn#1D&=REwpi;9Q!t?W{@_xexzx47(1#28c$mBM;Ox75AJ_wPZ8_HVC zJy1c&z&>V5FJOfeqd2YDGtOq(MzbE$%t~oRSskJU#vZdp&}A0%K2HX$_Xl+&B$D=* zQ&Z;pmf-K??I(E1Rjaa=*p63&^2y}NKB`B@YomoN+{83_HJ|iNoD@9Duq@05$I3M$ zLL)Q#8`N}7nd84RxRD=FM{y$s@9=%Q`_IRCK@s~w3`A%EJR9OgP@6^|D8zx)9ID!7 zCG2Tvuxue#RnxLhZZy2m=?+d0JU$MHYK?sZytWzuT!fkL3y|{kM6B$7dCS%(znbyF z-MT{EvPuYif(9t-`CGNyK(yy8Su>fV%a_QpHoTFC)nSU&YpWbv@fcy;l^=aR9cY?G zb-qhN6zVO@hucXRbx*);q=sy+zFnU+&Kb>+a*eQ#18{r5ZRCLv8p^I>HjkM`^|Sk0kceTA_k7cHugAf#{S#_o~^dy-1bE9J>{X zgb+9U?o=*+GTuGQdZ5J2*CcBcd7irjg#oRLqe^|N9#3NCYESVv`sj_s=;85rf;$G= zvY@dUAu-~~f)9_#e5nS^an4s};)R-R}*7{&(j}F6ewVOn@N# zvmvYyU&rZ<)%=VO$z(Vyg}EZ}q1q~-3>Xy*t}-g`Ctg-NhUx+#)*Anr^wojTP*c{p z?2--;%&Gnd-%KcYlXD+Xxzn!7jmOI1Tb;!B#zF#skAZkoTe*gwtFr_k3SM>=d7^a! z-0if+kjq^*R0Io4Ep?x*I%-sGcSt53YSg0$)8_gLD0W z(WCtDdTzrbEgRIB>ssxZ`RH#q0{WZ_M0udZ}SiaKDT&({s8GS!XeqWh|iDkyj z6?}?8jJe(g3g+Pd_hyOJl2bZab>KQl|GvGMq)`T%0U!OGXovu zZ=Df(q0RUL19F=W@(j%}%xT_ffE6wXbP$X6VP8sVRQ;!>3!Kvk^sdvLVDRvEuL?;m z=L>p#cPbyMxi%xHC|3t)R4K@p_n01f{&ej|AV?FH-8ck`z;^KqC6jK9_t5|d2pEC^ z`D?S=_WchuJdC(K0B1>WWb<+BJx?3_Z`QLd959}6tTxWjOaSum z3n$bS3QbiknYp40ureagZ`$yZysf|wyR+9NmIs8QU~JrhQ?b(t)v_MdO$(?@H4sx` zIfEX$7qqKma{%yk3juB)|7_5-H<(-#s2{v1~jHSPEkj5PFXh#AtO-WknR1*mJmB&^b1{9#@vJC`NfOPkVknAk3j_kA4@h3Mo#*tCVRZ*~Kw5s>d3RN~3Ows4;x$H~R`@1iZc!FsfAK&X5v zBiDQD>-uo_eSljf4Nic7shQ6~a*hj#`18OkRp_+6+(WxBNN2d<6ydx4N4MgF=Mt27 z%)ZRr5&)QwFQ)xx(XAd9M~pODfyf}+tv>ajFv6v2|7?DqOIPZIfEvx5SK4`FL{6ZS zS95&$TTR>9oNd1=N58N-?kK*&%mF4JNd2#A7m&dww#`4Mvzgy=l3iDQ3Ltb`X^v|p z46+c@v}TDK0(|1#2Drhem2?d3y5JOA+G?WscC~R2l#2`W+@b{#H@>V7&+}j6MoGoa zaW@eDQ)#7#L_pUF#zEUwppVbDVCIx8!#>*eE7|Gf@-s5V28-tV{&oG_a7%s2rWH0O z-RnRyJ9-eX3lW4_o5W$N_Ac8*nM5ZIu7iMrAOXay>Mj{Wz7PlBs^Qj#n*lcA^|I?LJC5a*%C^T;%I;&;xYlsaq z>v>|<>mH`8AbYj2Sv2&2+Xj%SBySkQLyF&g6zLoGF>~*T{FOj|Hn^s@@7Q8`S$XTRo;!x6uWKV-x7jr% z$R017A{`srlY!jp6kFUqr)d5T!(livv-SCTOxc}E6QZH8UUC=IP|saf1MmQW0!DL} z2m11XJgqZb+NjM-dpZD(W>%`xU0OaJsuRlU&2EjDJnHZcv83Y)L@B$8B~t+&4WmN8 zQk~P)Ga`vfq;_%^uZRXdY@)2P`1&knI=G{1egFb|R#ojp_m$2RHi>{mTRQp1c%zc4 zTd{c;Gl0w7rTNginX#`QK*5pBhG+NqYA*2vH8S;u6nm4;8{Dc^kNi~Y-F;TKh<;7t zPLPex{;|*H-%B3T$a&6P!cI|-U7M-z%{(qm{arVyGbWQuIfYG;ZV}bd9=BT08&Zxdk7w! zWOA$Sy}e!V<9J^S2hAe5pYa~;r_d#VM{r;A1a=(OI)*)`uJB&VY(X9$+Q;SIurQThzx zn3YR9v$AaBZjzp|VC%FD^7mT-DT2~0O>cu6ynRbZzMvUvK3!-#0EVw3 zY|m?Cll+}upW!B$z;|n|#<_lvy6lqpSyjA>L_n`G3nT^QG0y@?(V1!p^57b_voAix z^yA|VZ`WYk^n)Sfp6L)fag`6*;&E-GpLI65qhmt!)uNT_ixp42`E$; z>gvi(_{97<(=(wAm}bD+vqy^~!TlSZ)Os4PJGlAX+N*34Y^edEB&ZXBaDo1f+u} zgAhCRPanKb6=|ZI)NH=){|`hvm-M~NRZ=$vGA0KM#wAaD@2Ht^Ck|veTY8oAlmv`> z-1|lqjG^Xa?-%45oxVnPr?`dXt5t6^;Vgi_Cy}&hTRuqub%Simec`paThyN>JrkH25kXdSG6k{UvIEwOlu8f;5IQUC{zUZPzBYq( z{YAagExTaVic4!Fx_%3~!XU3zPw$kz7p?ZbmewmU*APlTuJQ>G#E-fh=ajbHxB%)1S%>Jh!UGibI{tX3F=JFU9r(7y{=mZAOQ_owW-2qj z26Ozg=pG`+P>}L&3-y#ZzCx&iqfiIBEmBTPYjgX24@zF@@*C)J3;A_%=*cJjvgxpI zgyvlXl50+7bsFldF}>c<>5FN>VAF(L;D{g}4c4qE@zEN_(J=8j&=*4YSO8gg*Q>weiT)tqgng zh1kwsoA~WE;9LG}^5qvWH-MV%TeYAOeOwtb2jbCc}vVNgOgk_NuftjhVJU(_ zKx)dA7V4J7^ahCE3E+G6)>!x*VV9}AIxyjZ*kIjNZ@ZD#w<+;3pg#PYrla z?#|usd8hJ(q=n~Wv3m>WI!Y>Dm$V7)ntZ%-WAg4Q_A%{G)&b2hp*(LVt>;C8EI~AR z%fVz~;yqIr)Vzo}zdxt^!%t4)lw#ECfNiYUdtzSz1ZnPYdE$Fy)17=BuIL9lIfL++ zh-?4fM52e9GD=<^zFFPY{NwO1*=}Bg;eFP7abb$* zzAhPb80+(-Z=SS zPh&_pr5Uv(IUKbqiq=KtF6Bo~p6QM7eDT$=d|lTOh(~uO&~u+K;qn~~{w@g0Ky$s+ z0T{*KouKaB3i;(2d3`6YJI3W%w1_gR9?ian-&c4LyJ@MudG5^19bC|u1EM}ACQ#vI zm3+j*WzH+X;uC`gZ1XJoe;^~Q%8t~;_Lg&b{@15b&vNsDXVYt50V-$w=D*`2!Tyv0 z4#98u@5soWY61T;_B`U!r@KgeRf@5CjUl515h1yx|IOga-n>xy@ozo+5NWX**qaSb zJb=)A)`q&gl!r zd~qnk79a|g%-l@G{PXsDQaiJf(TO3(e~sHTYm?N**|5})wIOeQ z_fsAbPHj}+a8`$h$<}QPprK1}`Gw=*p9*M}%Yc1kem>__^L^)FnAA)13Ct}VoWY$S z4h$DwT~UlOeg3s3=j}S4YLLQurC`&k%^lP@C@3Bp3P8yFUF(eC$K&rLIowW=(M!h{ zjJ8Ia&AqAq;edY|^s}^RPbUh}IhzYCvC^+zS^gFU(md4oSU-rJPQ0#}0PiUDd0yND z3m?U*bk|jQoH@^rFZa^5AXW}n0>b_|V}4ze7b8z{0z{utXmw=HtZE-$THhqFjQA}- z6BT7yX|}?MVVp^O_M!O=yRB*eR%&sbS4&rB@_U#@r@Rt;#sY)<{Xuvj@p!XfyK(Si z)xAk}Ifd*rma|Wi8@lqjiq7Mgu6Ce1%w^wx?7r6T>jufP&BhJ)(J%$E=tKt4gJDWE zqPsk1>b?s9HP76s%*3%{;k)nAWnOYx-zJnT(ohSDBe0LR9v)I}KDgqHRI^?YrM+BP zEea(yUxW`DOYo2x-hgVf$IC{06pnAT zIrooe>T6BOp+AFTA8r`EHP+&jRmU(~A1HEq%ik(1%yC(=^o0<_!{SK$vda(3hl~}3 zUV!(nGm|--s{)IUA1a-Doq_hGj=>Y86#oL-W<&PPE7aJ0c1Un_js0Dpv^1((W;Ct0 za5J*`MPjZ)Uqgl_hfXp@`0uKyel*&-TAh4l;=DvgT^%qY8U9*z>6G;3pNaw3B;TUc zIokE*MzMI?``>xoPs3a_7;^h5v!9#Vc|J$j>Zaqf7dJy3)W3+=e5iMPcva~J96P^% zPJOU2{pr_HQ*}ri8i>T+egC%ds8`}K7XfC!=mM4%Z+Su>po3%GDLz8&pFMw;GE4c1 z;H8JGZeR6PvcNm1gtCyMfN$av_Z|Lf(osdY!UW86r8l)KEDNhhoLC!PG)Zel>_psD z!O0v_e;YpjH9Tbd$WZ0&1D~!d?@eIQvJfVqOtH+f{h2b8{=KNi75Po$*~r!I!Cw0@ zlhkUaECIv0F0Xp=HsbK7TbC61(N&`Ub2O_5FRA~uCG(<_tCBE^_m~TrX>+TR^O3N9 z_*~ZEFpGMz(uPmHr{(n!FBt(QeA>Ey!2f~DEpJ&ChlF007Sf;BLPyL;8BX|B_WcJM zFnm*fUR@8z{|s|91pj|C9#YJf3B(12@9Vc;7P_q85pg~}naab&PCB+V;)c*imI{Ue z#FF&O4S@a&%786xyY%@G*Y%9^%u4UxZbUE<#O}PS4$Yt3`IO`X*|t?H(Zt$(LD}vZ zKvEg6$_EBP(X%F#U04;AqAIz!%?f&&3H=a!;h*j)MKx_Nl~+N z<0Vr38J*EIPkYx=0r}?s)23~nl+f+fY~j;$ly4D+a}0g85dWeN3YA91(?T$yZCRqX zLT)?Ur6tfO%48va^Y=9`5 zbJ6S@RzHqs#9unHb-$U=Z56ra*kbi0tcB1C-~qHZ_5jn1d)i@8ph`)HF0+q)U0R~} zx@w-spn;p7+mc|BX+G{$V^j1BzM=FrmCY--TlA`X$R za>QnE>npGB8J~|H#{Uwl!cz1fSuYr*cud9#@b~zjNd*lhyhSF_Uo~}UKDf{wE50jm zd!f_qlJ$3;jSSe`mY#Mt#q4(L@>Tk*nr?{jm)9xO$u{`fww+J&XDwk|H@qDX-0#)*E4I*yUm24=wT4?n1m$Dho`^AXny7gk6MSd`H7X@p3V%-IkWE zuM1L-QQA7wlk5eVii_^30x&Y=NOAQ{>zBl5Eh)8)tr!L$emjZ?m_qtDxU#0kBd}CF z_p2Hh(6ho>!+C1ekqKUG9(Vb&IJO-^07q@FMtZLIl;1@Wn7EtiP?vQTd^wGnR51X}71 z*=M2fo7Su;hgzaY?a0*W4@US>xkrP-^W`tDI)>;(k}6taRnshFNkyQJ zPQ#xxlv6^yD=NAA>mKj#!DwM)*b|=H360MSyY-g);%A1L4Q9GMf{}(;b3y$E0i#K|>RVsu93s6__r5 z&&hB1uzr2tmj^V1GuYoN3bqQqpOaBA(+#0kuWq}(N4@Vl9viK)(p|}K%9#1#eCAR2 zvZ()rTgcVBu^*2Glvi1*d&kUMX?I6h&c$y>H&?Rt3txaxyqI3vdU{Yd>K%C<@+D#TlrBVQCH(x zj7LJTLHe?z_2$o?wv*M%YyWglePu0*vhEE9v9tCot~^K-)D!EAWmsCIM@UL8s>`>U zDMI>|7GIq@sI{=3U`NpChmMxr`ZTzLuO1u(vlvJGl~mw8B+1_vL zOHcdWZAyySfr*6g#koI`MH3$XXja`oQafK4Rl z`KZ~kdc9VOXYZ5kO2gn2p4_-JOu9j!Ha$&sMD!L7KpU_GhSS1l>Fv ziJJg-cAyY_JmrGdKnLd+jAd zP8kVNG{u!OUnR8s2MBS#{ixi%)x2U5TruGP5P?8a_I`{k%^Vci9B8MX{Q4g-iTIQH zGgr#i<*DtrvZES9^b3`dY17soXi-VOi@}aP_$Q4gqI>tfF?+asKmE*7>ZgbG@!g`I ztJgDc??vzGUb2RS6ptP~9TA#dTRkD@?nbzBVEI4by52fK#WeL-PgPRo6jV;747W6E%EepWz$zb66*nM8whmV`sR=fcCypN51zb= zxpP)JP`TDInqNh_j9lE^X;8ReylXsUQ)E{j_Gidr^89naMo;&Bw7D*|6WonmmYu*R zw_Zs6{QCT(zM_Stzxt$!+_+~dccmIWU5dTh{I1~NjA1Qs%}@25HDZur{Vc7v_EF63 zcj#Z6PkgGsaZ#Y`SvuuYR{A)p{M&YqzsL1OP|_kCz30Kb5@i!)PW&tN$yCaalKlnH=aR*vooy0LoL_9Z$_z)J1fDs;RY1g8jzI1@n1$G2 zwIC+wCIR<>JF9JTCRg&^$kUM%tLr5aFtca%+G@sXdq;?eeCkQ*)m<3L$ow0P@K))~ zos#KjjiOMPF!HsTD@@@v7CCDn(_Vj%?KTd6y~Dl9cQq%1x`7BeTak5(Q+&4D@PORU zVH*IFX>I=Kqs_F%zVv2N_vEhGgRwu|T3Y4IKv&s^Jc{A!mditDCDl}iI?x|wr$O)@etsSI&&AB6n%lk#O%EmZDcN^7UX~U+Hu^s~OtCE1Pk_L1DT%8@T zOtOJ8?M3X4=7Zep{wWSUHE(M>QVuA@=S(YY$?q*f%dsUdTg=WK>k)K9DL05a>&Gp| z{I!2xpuVxaTNk>*5G(K{IbFsNfNd1&^U0;uc1{+xybu}+@f+3(#Dxq%DG!*PBNzVS zcM-bnfwV^_DsxXUKx)mDlRm~@XqX*H$-e4ALn!BP=mhb6{j1iZq42<+SdN^4I}mS&urM{Ue? zHXl*+b>8^$J-TAz@yYZ*D$k0KW?m>ePly!Mx`Jdc7hN5~c8ugxtQAtg6={dBNlURl1qh&P%chS(Ixq8qHUP zLT@llA^*d4UV(A36-2R5@?JzVbTfl4(T58pBdNbG(z)m(@ z8qIcCXNcw)OcPRzq)%rI6y0DgXxy04@9qE_eUK`-Q8Lb(`Z)JBd@B+d(q};gj^3Ug1bifz zM8vU_tSz+CBgrlsxi>VhfT>;_A>~jE$w`ew<}1#&njh~68kfsEM1UD{f!=?Yw z^#MH}17=GK0qe+#4t7|%Z=74zJx}dO&i3dHX-z#+Mk~~*gMNymmay;$jJ>7+*3Ib> zA{vMj%R8lZN}o-Sj55{3n^k_Sa^Asp2U&2)4YNw&Rymp4SPuOxpn?3cyo+92ElQjD z)3J!f9E|Y@&W-AExvQZC2{EI=`UTGW4t_b37~DXOjqbo_h9N6Agm7T|!g0A7VA46m z8k<*gWS}a3BdH~9Ga}wX0Jjm{jzU}|s5U*+bV8q=%zk6o;~&WmHs9(m+pqu9PN;TD z(l<5{BA7LOrPP+CUW4w6Htm6Y>-*Jhde@D@-qCS1%_q^7Lq`PIE_Cuk0`%8bcdc|din@lZ?!s%=FcB8(zy`2Hy?HKvzh=<*@z{h38%In;k?H-%r&xf9 z(Vn+kx;$=LP(jJM1CV(%R7(mrY?baCBSMZ_cJ&NG$Wvh5Af$0hfP8?9RvEWH^(tjE zw9pYXCk6anGfJ$rj?L(@SX(a??TB0yQ)JB$nu=I~{hw8zYZL?x{(&aK3uUTZN7>+HE6&pUP>=^|12VqE zoRG};7JD2Md*$Wk>05$gh^ubHn_pkQw{sOiYpxIz7v2HxI+gQMRb`URo5~+`| z&i6cM;6DQGN`@=%o;CI-`YwM$aLHQ65?y zNgUnQH70>yQze$%Aw-lpRRu$tla_h5&kdo?#Sz25jP#*@w%wk{C_lxXI$_>CJKS)y ze!7!d+aJKx!dfW*`K@Dg9MMksEl!C>Eb+B+$J1p`ULv|I~`=mp}nEG*~Dn4>*iCu0FJXiBIMoQ(nkib38i+5<;kMv~q z*9|8ikj+GS!rV-#cnXTE44xsqiKQUDcc;bF$St zgWfdhmHX8laUvZm&Z`o0juo`xtBmqpD zjri-XN*dCCM{{_NLqg<>zsN4%RL$B zY>Qf3(=sM^y`;WMhg+;1!vHwkOM_j}!8v?zGF~``XETEzjCM#!l9T^P7YfZOy(M#& zc^1;ZLymeFy4%mT@Zvn*`?mK4XVWdw`NzorXMpdh(~hQo_dr?I_9_E1rNKpSMf?Xq zY{Nngvv}alyC)3l5WwpL^;FvIFYUZGl|Q`mPekO(J78EO_|Ljk5@t6t>O&fobQP9h zO?r_j`Ct#A37)*8HLbh^9!)0RhrJp=B+5OF*|ZGArwzha`HpJ78j}2O^S-gC%R8N9 zif!W@)afP=wn>PpK#j!RZpEgdZ6zs*^Wl^l$mY-dkv#i*@0Un5mTI`7SX|zY4y*N! zbsM9E1BEKvOk5YZU#rhl9o->pjS8EKigjabzOW$(KwGM#ddOgqZGjw12Zhe00kmT4 zA{bi*=50nXwh*CZYl0)qrE8>k1tO{HMv+1(*M=`AZ&dHp&om3VyfI4qVYb)2=?n=Y zX$bwo{_y!Dy?Rno$o%;DBM9i^j(ygsit=9K-zWRMk0I#9^TEj}!IH#ZWsn*+h*Cd> ztF}O|401vR{qsq5vkLP6hp$8P$HT;wLPh!a!-^-H{sRttmM*laf|Ob8@i?=NE0`mv zZ%bk#86wro)gFqQVbJo8#CK}m`dN}NWUJKQa@s;hb1FGpv+6a*-1bPt?COp-;L6gY z1u#voCekZEtMPc<)oVK?-QDx8CQ-$m_F|}Jfg$l=|8 zTzwJQa77k_`pA^nFxCRt{`>B(Y&N_Vzv&7?lqeZZ5MPR|&z{ZhH2w?)RLiGbC<+o3 z_VONByib>`nYoC_tY(+l*!$3uUJWqVju`2imsM-J!bHtRQ;T$s)j~JTc0m%xK>&aG zbou`g#wYB9!>N{kR1y++_+@(TapV76*kIC-imBZmFfe>VwJ|+rxYb-Yj6^FB4mAmo zLm(wZr{+n(YTH_&lfIz-1?9{SiSfeDj_ehq`hs(Q0*TsOV> zx`!rbw@k+&o@fxeYmKy?gV9u;ZSukAd0h2`>LMcGzD2b!5!VyRzG<0mEUXo>%-?jC zJdS5??q$a_get^8ors6kZ6!XCZlHvnRkE4LznOdb`?DHbz4XGnAgrxFj2Pk=qb%Ja zl9=mMhzSTYWT6pwo*gZrb;rrg_7o+V7NAizFqE@jPuSP~E_5JC_pjC_u)HS?p56`4 z;1GMXSl6`Lu(-8u2MX#XE2i=4Z4Hg-z=&bqf8hjt8N|}^w%bK~ zAb%4BX=J;sF~lsoAASZPaK}{YUcFUT<=w;KU6}rV+XepM2EcqYSUHOXVaw!-z2q^X z0z({tpO&p z@GtB0iI*=qqKE&u!HniDpx{#mCi*rlG*yqDfaK#zRKHmZu__H9t2z|FJ3hS&S{+0T zoYW?^wzngha_V5U(Q-)IvT7)~rdw5eyG}Adb#jP!(Ax2HA_T;={biu+7~a*> ze-Hrq#cH)MqjTRKKXW`9&8J@8*$&kf5F0yV4yl<4gRbONDKmV*TI;}Sfo8f1Y-EGI zT!49PtEtl5n`~+GW$z_`0+*MNcj7V`hmI?u6=$@s6s+_}`%K%lf|m!{_7$Q6iUVgu z=uo+|jBX8l>rx-jQ4_y{>(AJ7qXHG1klSoWE8uSB71t% z4K+TBlXwro5vQT^T4y;pA3PBK|3U;2p%jczF7TJZ?pmD~*`#VI*8p*@{-kA^?^4FV z_@dma0hD>fKFXc{Hwz*o7cJCot6fX3HJiHI9aIo1d?@#+V&it*wlgpUb)X}`CXb>_ z+N%vux=5Ib0RKtU;d>egPDoWqZ`w$DejfifRPKeEtJl0KEFY59w8L%5gB<6&<&}R z%KAFL8=poZmxWnVV64YN3hQX86pN!^c@Ecp=j+?p?nIx(KR%X|qzfi%z%vo+7v^#!Pa83yibX1ZgsyWK_ z`Xd%e3^z#)>0eTBtZkBK% z!I)M@;0Qg|c<~vinpv`tXx3JD6y*)$ClYiF23d_=`preLh+T|ZD+Hfp;{e`EOZ&1C0cCnG-8ZZ`L$N@CKC2>~W@`DL9!M;g?!5NfLSvAS za`G;6zZqCdsp?$d+ehtJit40{?3u#)18_2fj%+Le_Q_fErMbG7yk9GTNnB!wI8byL zL6>Tg^cS^#%;{dz+h2`}tICc1IUPI+#L*td1g$cBVPo!7T&l-9xQZi|MF|#6R)F$` z;m(9_TnSr`N4nKeGPe-0yL+@Q$;lP!sB>QdZc0RLw3rXv;9{%g9&dLb*$zDr8&~}> zFxb6TUt-`+j9Zi2Wn)pM+6%dhg^h5HtPezuu2>u*86-|^x$fjSY3_odo(yaK&&@T5 z9;kS@uVJB}?gaccqCOWuY7vobvjaU>o-~^Au0W)~4HIJD>gtv|`3=UVE@iY8YT0U| znqv61dTIjnWR$*-f9^xkuik+c=?wpHSG^nqmZ^!o(oZ#$ECt?R!|w;5w`s#y)JV-P z%z&=Gl(Ti9f(4v{9`v?03(4`HDDNA7uk%San+4$pmN)b##=H8y;4-@K^xZ9IL7D1l zTXSv2Dee~jOlFwCln#b)9BJ1iCJ~0DaZ9vFTW$~hvXiI}?z%Sr`DaxQ_@*du-(X8} zQQFcesKxqwvusi|6oI$(%E}z-eJ4O7JKoGd(c2cgj(d5 zo4d8bEvc8W`{Ss+Dc%|fTIcJwV1G6k0@g_OXX*E2SZJa8Otc~#-71Bl3m~NJy~D!7 z$^NT|NQUt33D{!}#qiITd)!+hK6#mj|Ks}n83${kT7L6p0AdXahD5{xhY3zO2EThF zjs~*;N#y;^6fN_pteuJ$W6k(fCLVN4EYv1N10YX6mv^Qn=c;}vFafhVxvv!za+$8S zV4^&-k~@;12=K$!Kp+SdYuGmcp3KEjm@t^LkOo+KWJ;3hVvvyO-Rr*{$3NspVF|mS zBs;tc8Vz4p>8Ej~QK;E*p1o3@)JkFsq44C~aQ3DJd;_fFBwQD0AvXRaW8TnD4RkH< zejpTt?iAQ^4Q|{Nabh|o+|X}4k9-ZuG|cTFBFcut3^V^g77O>(7y8$`dz|w=`thjU zvkowYP{onhNL8O#z==+xNy;xG7R6LyHuUvGFj9CuVC`IhY>*#ixzl3$V*i=_(lsna zc1UbQ-1*i}1?Ala`}<~&Udt2o$C`1G;Hg||m$RcqE!1jHcXVpFz2%xzz$f2jo5t6p zc)ztbTR*u};Wd~}iwvR7Pd7E1XdD %$Eg!KYWFRp{@u!sKLGU9q6@&@p=RbqqoP zWEwf;?2g2<64fSPqb1dUyS+ugL}zT6la6p9q3$un`kqfAI!yXYUwD97eF|WR@`d2~ zX?qBFhg7IUQY^wBgtLaaOV!CkO7<2u`L>?atm%oJPjp~cThQ=P*r)VDi#78{jDl$| zrkX50W=F^KXy@L5-!Padcx7=kl1t8_CCp=YwE`!ooEe1foE$WMPHj8K>ByW%q9(im_w-Krs;U^8y=;a7am8e zQCYBp9*F*SqO&MAdU$*|*%5t=Uy0`>lkxTfD5*?2@M0tF?J83sD4i%1B}kNocVFiA zp$j+fp}JAqW66C(bjBNzR?FX5VRi4R$cYmUaS;rW06e}q0I?k=Mf(yF_p8miazCU+BCUETF&SIO{Ng2kRgB{Ot_^l$Jed3M%;VzAAreIdu z@6nYiN{*?sg181$Q;-4DCw6B9K1T(qYOBc-F{+EqpmZb`Zn8`9Kx7WG-z?=eH8`6Y zof!HEA2uYsy!-o*)3%RKJZ`D{%ff*hO&66267Wyr9v} zw&p$<^gAE_P7BMLel5Bs8QCpZX+g)9i@CG76zLG&P|1&&&=_PXg8EZ4JRQXrWIjCA zrsje6&UG})XOZ3xkSVda_a@)_KNsoTdu}CaA+bDF+`9L8y}&Hu zKI`Kz)j3el<-euM>@9ruoU(u1^s0UFNSOEu#a84N-Zt~1MtP^6TC<>?2dB!>X4>5l zp@WAdSWu=G1J>tUS9FYO#sE46{Z2gSB^-9g5dUb#>2-@o zC>+M%K(7fj^67&uPVb(I{?ULpEn9;f_RSUz(G1pu&=`JsD^-zx9VgYL!|QSi%nd(?;Gw{8=vxN){9q?AbB-u zu;cw4cbxKZUp_0 zB9PBrV({P5ifsE-*|P`#VfiV7X63tyO!7BF$cYZ(KJ^h%aEi?=myf(LI!XC{^1xi# z8GUmdkhmN*rwxSY^eD=RIa>GX1JL^&w;JCmCRrawId?8Ut8bqmyG^HiYyTtlS#Uy9 z1QW9*8S8!)l~&h1+Gd!#8RbieQ+XHp_W{`Qyquh*^+-DMHvmW%-SD6rAjoA#l*d}{ zvB*E)uy5Yjiut?r1UyP5?6Y}eH0 z3MoJ`6Lb3(*I!h{1bbB=q&Ag}BF?F>t6~?w=s`XmICSo?&yCOmJz=4Mbd!f`JYMg| zG!o;CqN{Jsal6YC2xBIpqlnu2RX)-hf_Njh{n+$`51ze2HBZ?e6O^F=vld@vPmhH6 zrcJ!%AD02ZVHhrZZLRp*R3KSfv8`ibKL};1AxUkwzGs>2_ixiIw*o`^@VbonC1HWc z#hoP{|Dv(~Tlvdi(LR>`A24<9yoc%s)1ZlcU;p7#ZrLh63;NKs&!2qt{=DKgTRx>M z^Q$4?i87xD^Cjmi(~m-~#W#GY-a~+Ych27mSNx=QPD`wSC-Aiwx(yP>c}p7W;f-GA zum~eW$U7Tu9`BO$9k25HmGk;9^nF@u2qGv|sfhgreu4SGD(mM5ABnq8@;oaFA-+EL z$<7|rZ8mSQ{Pd?pJslrPY*x_p!9&f%o$Tdu8&}~faG7jc|KZ?D_rKf#_E|5A@lo@1 zviRy5kCu<&jT0~vyvuOU57`@261NY(ueuyZYL_3_F-|w9p1czM`E$=@@40f^TzBW{ z+sOir@*MVW$i7{@^|9)Fx!LGru$?*9pIRx|#$@&QERmx9mBn{(#& z+hJ|Q7m97y2HDh~L&&Y~UjG624o)V@b|uOPDDV%z66reJ^AHiiIxYs9PNUn*+1cV3SIQ_W@}q*QgIqZ+FYMg zquMF>5`JgKA_A`TkA{*>#fI6t)B94l$Gn_jMxbzT=U1h#>-5E!e#A=!lE`_(g`p1< zcz2@+rRcFq)1=rVoD%`2Kg-V-mb{N~&r-u&s=DnO1LvZYmo8Z! zp7GWnN)3CN3@oEtZm&-*K83Z0io#uuwh)pDFtMFkLkImc5`WL!F^iRa0B3@o=eoT2FA){Uw!;qjre;+{f55_{dIiGMlT8J#!q^?zO#D_fPn zZ}!5T=i?QXf&fYlcncDL?(y|fhP5Y@G`lCyP^f%y&2Bn3}-_QoUui@em= zB-wT>U-Oe(TK;tuulv1u;WaN(NWp~`m3c5@Z|LRn#SAGsg5~SVWSsSl-$Cy<$^|jF8b;$y4 zQ)#F8Clv)3*;lS+&dl9#mPfUFC|hnE$_+10ctu9~HZkumRFY$_5Dn7pqim;hm}6(F z+t|zNrH`UE#AGan+tn#{v3f!T8?~@?sz$J>0;gW z$oJ0kqeOGb*n?eG2iE@ldQ){rWBRZ!Ssx}gb+CIMlKf>jvhlZ96!UV|?E_W@Yxbq* zBONcDLnA>JSGlQ&o_5~5e{58Yikl9B@{|y_iwEyW?=t*O89f(t+HM95I5r0>OXqU@ zSQ;NuT^L^v*+Y|FQxd=Yl5!tWm!k{sJ-4H^kY97bcSL8Q+A=A* zH#TfLfy-kv_$@;Bf;F5kTe->6L=-n)C%TYERGD%guB%?x%$u5Y_vKJfXr~PWjJ{p0Z^< zE?i~MK5+TZ#JrZ-;}Gvy*YR=3<@OTlh*oDinjNgLd9AQ2?c5Kc^ULY+1=RXl+EU+^ zvxeQ_khe+-gwc8LAh^|hWNsoD)E;rCN)I9Ho^|e=zHYkOC4wqW-=(*n?;dfs{e3!e zn63O_y|{NvzxJn({z_kQ_t}rt8w~Nq{LMJK(PYvv(>%4eaO8>x;J;?-OLc&aU!b4R zwUwG0^cp@^1!7QdzKZ&!RyNtTN&4-yf$w*Q$dL4mzGinmr=Y=>+4%*H_S@-ygXz-H zK|UpQ=v9l}onbAh++h0PD)0Vly1UJ1wGa;g#z?^T$q5_^(LEi?F26Q3YB;jbVQBl! zCz@}%iS}N>uI`wP0MzH_e8N4>rh71nsFQ9fq`h}EHbEPr;`=dpyuOOTqbJLsv^p(G zgv~ejfH3Zx=lMk|`!Xz@4HS{A%Y&S9`{!@0GM5fCm5=!m3qT|B1fG4lANc-kp-lJ# zhv>;v_sk8><-Usu)y$Z?Ch1|}^9b&XtfD&YRZVs^>c7j@up%p{pMOB(|2Coz?%rGt z>onLcj6N5ffHGa*wYga!vZH7A9VV?Br)+Lt=JQ!e_G>K+OR%rGb*S#zNpMEQbFmE3 z9N?vF3UXef7Pii{`mZ0xRq7i;QZ*$LpI5!&kKWy7GKHd4IbM%?UW!%jm&SqHy843O z{Ph?&;S2g^ZXlCt|L?i)U+2}0g_|V7`P;0giP&HsySu%6t>oRAs`@%0Pm*L`tVUM7 z{7nY){-K&t?^fv^2cYbav>|#HZnNCcW?Hat6bsCwrM`NyKGP z@u=ED0&5t2`wMAV`p~q3HI2N#9v{uC%K9p;RfcCzpVN%`kZ~c5`J5;M?OQ4p`1h

BEQn7?JA zr>9O6bazeAw83$^~nvO6pqH>-ydW(065w{#FIUD4)T zx$TWAO2`QDvVIMAg-kf=YIO_4{`lRDCf}%ZdWn)q1LvGYmn5QTIRnA4xit_X40xRy zyD&iqB*SS&Xm*u@hgNDrD^Elrclytj!Y30t$M!+-ODKo+Y;e+SxXws?!(+g4lp&!qS?$s>y8V@zAoE*PV{46Hnb1;H|~tMyhbE0 z--=|N`B`>F+h$F4?TuoQ>#KR z45)IMldh&0-K}JigP|{S33Z8&cS=ud{;TLRK%zwu%3`S(0E%1dcUKu2WH{0Qiz1T2yq*0HE2!Y+B=y}9QJ^?;fv(S9Pv|V~@G4iP^bL=wcGSsUu&e+e=;Ikx zuC`#14OJc>wn$IZ_*ubjSLi65a*Q5M&SE=ef9I*1;`0T5C5+jDiPkE6P8Bjcl=VW2 zwW>#F^X|`977dml_m0(m@E2a?)CYOu#N%@I4hsd$SDI4fo_?$(j&5U?JoIL@9T_gOr~Jb-qE!!f?us%eKE2J8RCzoG4!W&caL%Q1 zDq4{TF+};$W_3Kvd>23TAwh7VGn#&Ggbh`T3zP0yeW^4vT4k6-x}WW_UDFjC`weq3 zORj^hsuxbG3@Eaj5!N_8GSMh_?9;tSx>I63<~s=r{69QQ4Jp#g_!@F&(hq)IPR6hg zk?8StGvo0-Iqv7CBn)o6`XxYPsA7CM13doPt7B$MK_~WKVyLkszWrbCYu@yxUq0*w zJJMO8%Y=~O+Hu~?SZS$B9DsAcLmsN&WWtU7F?I>BhtZ^5AQR4G;plgkXtFd<#U0!*+Ei@b9X$v%=mR@%ij> zks4m>w|(EVqE%Hco%&iUW5zL%rNOWjB>vx_*F?scqA98HJzD?9T&>UD#+)fgdKiA8 z@1524(u@FZ`=lj$Vx52aISN*5g?TL9Q8r6Uk6c*=YZxkT{{z&*(y7SAb!QcPx`;lq zuQ2?>@u^3AQ5TQsPM83sABNR?KA_>2Kj-dS)>x4)4d9sIT(QQ#o)ZyMnQ!#Vk~I_q zDT?!qTWrP@seAGN$=ny-za>7Q=rBnVE3r1flG9YeD){5WTIr19Y z-OOK)t4=?D28G$XBk(7DsQ#_`esBLd@+8HCGf*C^*HVXhJ^Ma++F!aBt%!;C7^c?p zhw49g^>?Xd0jO3e;gMO+@bLYK$9XxNYyIaM#WmN?LCbVszC3j9_8}v2i!4O=IMdss zZKwV4iuh!Yc0wohL4=z0PqyPXmuNd<$a0OS7mms-e`RS$3e9{&alg&mAaq5St{AjN zy)Bb1X+ucY(#MI#+`E4t4ceOzCx+E5coa&lCq^CcHXlVdZ6#*AjA%w1wlMQ6a{PFP)G+^vr4ier#n9O3FP=b(+3hzGNI9TkzQ))%5Z_S~I9K0olD; zuG1SH5~bV;>7E}}M!{!?pRB7d=664w_EGZhg!QG1-(|7b4!gR_&|_wDkPQz7MYnFJ zyccE$yQ7~2nPGJ|JAl?X>a_dn*{>%a1G-CoL=CJXLEU5B?yq=!?rUAi{Q-yo^rlI| zt*+;K^z&{An8|j)YvmU`b+?lJA74Ij85+-@y1<$l6x>~)euRp$$Pi>LjcV3_pd-rJ~b+_extypLW)*-0!Kj6(-m)+u3 zn_j{VAH`wPyAy}|-bJT6jgFi@EvwoZeYMbtK`+`2MFR63Zbp~d*{3w)Q&&^%R&FfotD1bTo!^Mr|+uD4Z1!5(yFzn-}@cL!#HnbGu#o#`4=Q`f&_3W1rwPO_vW{blg;Ol?D+{al-ZElu?Z2CbN^} zTWVI~6I5gr(Q=s7v(#HB-G~8c6%|j54g*^o8e5({4F}net{965XNgCfa-qzicPkCa zkJXnPAO8pVh&H^seR={t#tkSqX}4tbb8;lmCdalw#`DTE))Mv6;FDcXDq%e#zv29` zJi;GYMqpxfd53bE^e3sXUK`9ErF;JYH=VMn%jMq~d?RX6=hw>}g8u;zZ=Ykwf(H zQDuz#c?bj!j(MS1p7NbqPJSoas7om6vmnbmx~WgRBN}W z@Jt-%KB3O{eFTkK5L0P;pY;#l1QagZC=qR(!u962uY$ZgoV*0Z8iu`j&DX@;i!E^< zAPT}vI8Q#tp@TJBfHOo9s>iaTI$59;G-LHwo^N5@8*#pAt_6ArTiO?& zuQ4D5V~CR;sYa!6$hSe$Tcx0kWyYO5DnAgCZe1RaTceCEb9wCG9A=qiAcq3MEyStf z?cIRVeKgQbDm$=RGA$_h#%9F~J%^egT*!3%SFKUmFr(@QpY7nLcug4!wg5jeaE!my z(hT5IjNJ(vrjvcT62%70#s{Ig2l`zPc$jk3f?9R0l^jn86vYMb&bAK|t;a)VF9@h4 z2C6jW!_2&C6Uzy@)*chLi}ca$Xdo2Wt^}$B{WW}7wcrdDYnc6i09|`{nePoIkLbHP z2H}kyngG8~4p^-HczJ}+sou+Wv=CJ*nTl_VT^h#LyzpI0QJG!i5v@)iZ(fOTBT68a zP4-mN0OvsS4lXTglN_;ycQIHDGZuC=fnf-`Pb@Uh<}H*74yC#8ow1@um1^PjYsTV^ zr_zQ=z@i8?)zYC&C;&vkX(eayhKG9#{It#?R2}tgR*UVl$~CZ&Q&}_rUswtn7~}(M z3vBz4&px*z)MCTI4gcpFi51@i!*e&P!}7&N6(OXp*a(KGeVJV&$8;3{PaP#>!{G&r ziC^i2FEi0%$W~?2$^(VgOJhJtt>b(3!0D9E{Z6|3>Z9DPEi~0dzBwvD6xlv|@0{+U z1#CuHZ8J8@Kc8Q_zRs9ko#+t^iqxd-{21l)T%#nLczT&&m$J=rfF*eYiwzljJSpnk_VFfk>xAgy8QV(T?bQqPn z!_Zphjt|z!ACl1C5#6V-DcYFmR`YH!6#dLrjVMmj+VEWBE*BZuVdVIZoRpp2(q=)k z`0!e^#`CRRVNGAXx8{p$Ty=J^p@sZ6NmBfK;Kl83r=}bbSRY${c~k_&{^OAhS5Fn+ zS?faXC6p9zyO(aj*_IDg9ten&i7ZGLN>zU^*WT*(_D+xk%$!-ZTJoSYNGI(-p!OdT zII#K~O6XfI$d0VIfBJ*VijjzgIVkkwyaP^hI>y59q8s5I>w0@uLiq+ZbTaQKLb>^QvBp}_^d(vg7)2;<#g?#8Y7tXW z3l=~`Tcc@&>AG@-#XjN9i=ueiw!n;zBm7W<6=G|}HEBZ7`e%oY8NI);s(k0o<&S?< zITj-Q0CiFWK4ZJezpsF5cZ}Vgn-aHfjn>fg-;Y^WVfFGs79*-vq09+{8KSO+l|fCZ zC42{QsUT(5ScnbJ4ln1c zzke+dvqioSxYStNZzW*__zn^sWqm8Rx%b_gY3WYSSHZzfzrjBPO8?@DXA)2hNV+i* z1x526h7!GfeQ)#GuguNkz$zw$2~HI}jERk>7OnAQF!hCId9)uj1~;r=hQcM?{`iE&u$`z4tB64<&t|Vl~aw>{mE1gTdrZf<$7HYX*A(R>{dB*MGwU5u_w@`-sTRM_NmYT zA#lYY(hvPlx@M@1v1SBs){6MWt03O+*=Iv=7J}JxPm=L+7)EG!X>1SjTW-O<5&AmA z^q<*z>W?3X6YDF;ku3)x>KZK1K-_y2ni(`?7dUAhyYl76(<^i5Ji35Ed=+HSJ>z0i z9!+p?^KM+Mi?4x@Y${6~w>`YYHOsYkHrh}3avoI4r^LqoeE+e7F)e%D0Y5CocWt?O zCUG(FcR1x)>C5EPVwQt&-^`rA*vOq?il*krdE4o?!wCQHC4KHX92A^W3_^68UN$m= zm68s42S~J|l#w&qZ=@tsNX{asuHwkW$_j(A->QgWq4}ULKJ?SttA)Ao6Srh%2oq`? zvYXW7%Mv&=fP-NZQVv+={ZsKU=!dYUDssF2{|W&|9jP~{O^(L(;fC#xpQN3-3nLD- zdU$Mlik~sUCs*T`A=CV`2c~H6Ifu;pNEyq!W3;I_Fbq{={|mkP{;)@vWL#%3L``>9 z)7O`fdz0GM98-|%0V$J)$oK9(v%R4Z3@2J{*G$M*qc79How}|__|8y0;n#Ng6ZPf| zuPm8Q?Wq$h)JQmJ1^CP5o_A>^9E4;j&tAJdtg@!7{{wOLU+J4I56YtaaSeegTzWsN zMDM`^#$m_ty5@&a5S6p#?3D>YZhjEqnkMLe%DMhtim6e;r#BB!u%%C1A;KA5d?uX% zrpmt;-)#MdJTdL)q(A}wa~&CQa$xhDJ~$l zNJl_cI!n_(Qy;U9D>Ma+)wM{hb}h4Aqt}}x z2zv@GTASheH_W~r?{)O^ZG?ViR)a*73wPe471P}QxC>ND2gmgY(%u8g*3k0FT;3N| z-6diuW_`Ut?M;drHzcvfEN69{i4gRuQY8u!)ijRL2&wkr016VSK^a`nzj1kjoNyyX zRU6n}aJBj*&>QLz)2akeEql`=rnshi50D)b1UQe9{84+R#&JY4qE%a<_8%aa9fpl_ zneEx$*SKCdV$m$)IT(iQaW+{tqFaDwCv5?dFaZR;ww};Lak4jcs%Zp^s6Tw9g4~Z)6Iw}?fl^qKzAy4+(bHJ6`>?{ zWagWL5>`!GpDJq}FB@PTiZEI*Ci<`6ng1p&WV+|6Jb&$n$(m<7x+*? z=UfmI#(_dXg?y^ii>Qh2UBklFlAiaI1}v5@DUbiuvJD!dYAtTDhV+wlyyW;(`znGB z23c(W)eps8Q%plK)KCb%ogtN`3_wdUC0a+nhqREL$&VL`%p43Xt}^9;z4`FPC5kVH z(V~h2#{V4Pk-uf~)#}jXGP?^?`VIeNkM%o2>)x#~L#n4NgWb49N;u$ZP#H=Si2`xO zJf5{;>Q;lf^z`DolSnnzO^fMe@-s)982x~U^UR`v4=8#N>`q_oi=5$w@eYUfyb^e(0vG4dnmw4(cjhl^%5r_O}& z`7VY^<3zvkE{9vj$qHe!Osf>0<9St)gCRH6UIHhGxoDX4?3p{qbD0wd{kFegIo7CM zpUpSr)?I!BdI@o)HV3@jlN;}S&G5|ifi%^cp?W~MVCP+kdJy9L7GoxgA^#3&Gt}rE z%L3`i#y1XYP;Hbxz{i-UJ%iBeG(P+wktm|S7K?X*GM)!CJFHHElESA;Z?v zP;f@g%uVRLNUANAI=u!3R}JUJh$$o#cd%A>@?Eq>S#S3tg8W{)+#OYh61se=>b-ve z^}qu75`QZ1WcjVa7U=RXUNnlu-z_x*|6Zdd2?o*$=8Y5AYEaRU3DqAZH)YyD=a!iq ztOUFQxhJfDGXiia_i6>N9B71)jh3w*Ji)<5q>vhv%1=nNv$nC`Xp{=K#Cq@FYS-A% zhl%#rDAA%-5n9Z$rM04+i?EO!U$9lScM_2k!r-Xi7CygWQ`WzB_6^k;ZOYoYHY~YS zu*B!gLeXt@lG6Dn`6?RbBASrmq^$aYq|DB0TJg@oMi-cQY@~vDf=34%N~}O~>y>K} zAEop^YS8BAvC@#nK-O`K^$%vb?xGJHnCRtU@yFB3#Yuy+o359|qzYNPJ1tUb0kdNr zD1@h94BmdLQn4HXhYnB*quo^omr6EFbO@%%{|xp9r$_BWMV=rS*WxvmgSY>5-UKI% zuGSn0?FkEawt2({)$4IuDq2jdWb_QA0s6~4jH$Hcgn|XjI38{gmd{mFC_Wd)BTKWg z1mJ>EN9AZ$0*^=Bam$yH?X7R~x&;9te>^ZXu!mZd8yHtKN4>KpH;a{)cxLCVXU+xf zjd>ZPH35iZK$b~g4z__=r0|@la`iww7Umvk zq5GW2e2S7XLWZ>$n|P+Aq%iB{fuAQc{xt5$KCZLI3O=CbVY`Wo3`_plSgqb3xTx=p z?HZp%aS_o^n~G*6g4Ddd;$|mFG=J!3q9e~%ULGrM#PUaZqh`#M^J52OfNpdARx7?> z&|>Ik^q1y~1`P77hUpdm5my@l}Dp%qMg<_)B4kZ?IlU85w z8#@X|qdkRVXQi)4BQ}+(1$NTi4jpkNS6*~x6cvRt2h%fKeaAYGKDIMPtBjUY6`gpZ z9#=_rsZ8_!q&IzX7*>ryf=XDtB`wA5BsZxqv2%djToMxmHr~0%{sjP(KqXhy7{#ie z%Hs2|;ujvuNRg{CQw|)QEi|cHN$bz$WKNWGMxGi;a3?pokq)iDN~4KxwMC_*beZnB z-3`-cug6kYAREGtMnp*)GSteZtPbgo8`yF!e&o?4Lh)}SLH&5FYo32fR?;Mu`j+Fl zqEaC8xEF@lQR@f8Lk@w{M?k>uGj(AFsao$Lx5CULi$e@|CtpxnS9i6x+X#$e5yRo~ zfWQZ_Vab>P(?~)0)MG%4jJA%61l=Ddbf{tjxP^Av*L8r1V}R9UQLU; zQWBL5rr)BZvzoF7$yk%m5UV3LQi=!x12lOQA*7`idwxEJO_;z2>osU9cFu1}#z#zp zH^Sy^d*5=&g@3^IUi*)(fEJrCQt6lC$tM$KYK0AIhIR%?EwTyV2+&`}bCoS93;GD)8N7LC5+G&89;_cqOg-X!K+Iu$aZC;L zt(yBmmbi$`7?%Z`+l&N?OirW|4Tx{p9P-;!R5+h9gEs3IZ9G~Oc~TF%xh9}xG|;;l zqA|aU#=#8FgGrzPavjK~{|l%%g7lN_a}DgFq#@Ge)Y*>0^YoA7Hpm3G$}og9WE|HB zXRQgf0CNh}8oel-fqb|-u{Gj-2Dx}n>Vi2tt1kwKzs2&0&CBTj2U!(Wc??>=EGVEY zJPFZ5h?=ocA(ScW?ebSLmF-HYzXki{9ld*4oG2pxRq;%p1eZi{f<~~D=*Wb>4~mA$ zI{phd(fDHx`w^H&CN!1DYSkM%py?!#jY1)IKpT534u7^57a=U_Pn3PBj}C>g!sARp19oyuY%sa@IRW67-OX+*t+j%)|l1o-5F_r)(Zi z>>!AXJxNxUowfm=z<*ZNr~TpVdgM?B{hApGSowXc(j)llJ7Exf<1!DdiwHeqDWT1T zn9YP*I2KXl#(*m=nEm&ULXzkLc9}rFEwas=Z!$|R^8x2L$cGM&SO|P|$9+$iJZcRH z`_G!=Mj%z9JR#I5@G*ZtvhC}wHGxr475>jNrHzv09> zJ&46l4x5tEiDb!E%L7l8UKMQ&R7t9QXxRPU#eeJjCWP4nMQUDY2F>cpsL?zwC9A+w zCa(ycF3p*be}vx*+D z3ilbDfq`aDIfy~<@v+F>NumCkdd}f@q|nX^1+(bTJ%vzZ+0X4lJm1-P4Zp;d%%ZSo z84fuBahHw^s2RXDfLxY3{Ujm_KOV`DhZ5_hU>0C>SM+z4A5i!dmaQ^;0_cNjaM&qB z#M?!9*fa{gs@zaICw8)YCdL2`UYCgJtFkZoryn9Ki=?*v~594CD{1lb<+3 zf19~Tv-Z*31wx*}#hS(h&)b+@bU6fPyyrc1Jkbto^FxQShQ?{N-e81Ad*NU-kPxjB z5CJo@77w+^n_VC37ISgzvGBxoZn)hXJM%jh-=COjRyB@)yUYa3etkC)^npP_0Jg!( zXiCP~hO;BTLL}h{rdgB2)UO^ds?6VZIi8Gyjkwo|svgTuooNB&0Z{4^d2o@T)WGu; zm?^q@)+1#Z$n*aKYC8Q$Uxm*S?kh97GFB|&^5ozD-x6X@Ds&Rtl?sPZZ4#FUUL8k1 zaeTJ)ZgB^Uh0MRzm}n*w&2+4`qdk1MY@>|;y1k<}Y!E!*^M@K%`mIN?*}}sQ6Y#&@ z%LW^^3qL0WM}1(dx-H7QvEDHE7CR`Y9>hGbtBF%?bVEj`yG4#EE2`utT#4#(Jgn;x zzNdzG~G!@c&6xYT5{cO&-QG?X+Qj^Pfx(6LeGctbdMRWLPwP)a1(TKCkr z@I{+ z_tpH)TVt6P&0?zxSE}bUj>}s{v~qk2ky=WMAkYJO?TN+t3s=6kck6sqBmq97l^@?3 zAB`YpHMPo?e*i4bJh=Q%^=SxxoHWa*F0tb1R2q$IFTOF4kFWXQh`RZ6Nw3F7r#^{c zHHZ1jmjHd2da_5xva27=Pp!co2(}NEMd@>;jBYdP%U?u$%tweBN8d_DaT?GIW{c_h zDUe@wpt8Fsiq0-uchlXceB#x+q(I02|L%y{q z-iaGvm^GFg;_}`&jCNLiSEUs73>*&pl?so`x(m$fJYsX;Dg}1H*V-hGi>H{sTD7QL zH|lxaoWke<`}^W^*d9VWy1Vk-<)b!#95T3Od&9cSK(Cwm`LCaj`9pF&^x59KI>ULq z^j((Rqcshgs9p4KL>wqjT}cB{yIs`4caaSaf-k-N9@5b2aYhG@3L5DaFjk(AQlCCI z@^z&mgV_gVQbwHi8>}+IBcB`iBxjVp{ug+|b8LB?tC~=7oVmO&d4$iuw15Ad%jKA* z{`}?`LjU7cX;bBraI9@B&h% zSmw!!^7o1fwLPK-g9D{~VUd;pwXR2W#)EYuQn?i?A8uOihne6?WOc`7yPn-AD7zrk zF}IsUVu{P$tIwUWJ)Bloa?>B$auP@bIwi$yv~*!lkELGIpBz>we3Bm`d1dCe-efc~ zRD`8D%a|Q4Y&?DUf0wtv8|zRK&}In=6=C4c)S#H!cD(0u5(PB;O{&G+BYEU(oK@aR ziwPr%0gfeC7&jhB-;2cTUc-|eeFd0Q8_C!+(|Q@tJ42hbW0EMrAgIVGXo)TQNHf7+ zHfOPag{^Sxfm+Y2&xZ~il-Apb=JTjIkdvb~{#v2D?~17U{5-RAAFX|5CwIQzVc7Y} z1w|<>MLoUvS0+DOiVU=2Zlpou-cl! zKzB@9-U;0!OEsM`#*w8z)k6$icV0}FL)CqOh%U6wE#D;qAu}|zszs_ESe)O%U)*~s znq>2&#wchUhI6n9)_Ifj>zC$4SD}~3q=lDW0~nh+`|Xu(=~A%5BZKr$(szl|D|Dvi zhVoH`O9s0xQC@-C3ZC{o?xOYu*x-4>W>NP&mdu?4GWza_(7$)r&;8#@m?Yiwx zQB+{A6n=>G%qFDdg7?;1&>A+X>qnkI6>n-1ksk_MXR*|sVR zt;gvz*X{_wLeizh%pbTwQ=Pc^WarpRVmK>7L8)bT){(5G(Qcf~^(8v`dG&fUdEHTP zW&9Waf=UYBla!~Au$O)0xYJP8+1?z7UD%{`Zol61gH72%eRgZzZ#6QX7#P(Pb!0h| zbLtqTPF~Y;z2H%s!ZCCD{LnRP&#k%O$^3-To#BEd)vNku#LTx*n2rigPg~O8>qP;f zYm$BDJjb7Y2|Cq~g}iGK*4(=!=H8hi*r6rVVu5SQCi23>xBuOhFum`L{|!{9yv1z% z6<#uv@Lk2?$#jDITHV7)hu28qjsrSrl(F2U<@>EX>Ks{P9Vd;c73IQ>O_9$W?M0tl zSP9tBUG8z*`&&eR>18jHY9hnh$z1_c+Wto#%{$em8-A#0#P9&<2-x^*yO}BXKSLD# z!0Yf8>7GQx^hq#Q+vELpKuC$%E{}lfaVdGdFfC>U;(2bH}M@hpi}J)R7YG*>b(pufrt1I@t#|L z>*&5PbxWBqBnD;4G;#BJK-Yf~sYEGB{QK$fN9^7&+cA zlgk)85^PRu{5TFP9Ag}6@~Ad{X8W?}%8TzmI+NkyV>?j_V~$~xe=a^fx0v@6aoQWM z06UCohch@lcb6+Og(OZN7OdjtBm_IT?n+;bq%&SNX_PCckhJP`kgNPA9a1IDPitjG z#qPI(+1WFv-&(CbP!FwK0<#>G^@-#}yTcPlI9FSvRptbYDf0XC=N{NUvb_%MZp?54 zPF5>9hBz)%-Ld+HmXwPbp0sOfbllY9~vLqb@!H3Wf?Nl zz|qNYSmdSWXivx4%NO1+W;Z}HMnD_+9X47!{nGf09pCE5)0O;<3jxM8Ol&+x`aB_+ zfqNbJ^iXAr6u|P9#;?16WiJsh9nD(>)x7i)^A|7W_i6t44U8rkGA7x?M2Zwuvy2oT zpIQS(xbKbHafA2-js6M~vGzJwrfMb~j+(8f6xhwa_!IX)rPe4ySK`mEBnFqhd0zZU z=&CU_g3+7s2LMda`c$1E^}*)P+7r{G3S)gPCV_Gc^PrDx(!`b%%py2=uH>RUQtznI z_74=QBJkT!zo2hpu5)v+BnD6&(otLO9zH)=#1372q!cSH5bC?1FnhmsbT;}3j%~8V zg(8@i{LkXo&)Ho(anGmK%p)8Ov@=D9+LY?t&lm-%>y0WpDotZ5Q;v&4e+GZcT{6); z3Y`ZdG*#f654dqpMdPS80WUf4_)=j>gJ`m2PvOwt54Jc*rmg;x%@KpIGGm@Ac2_+c(cL5MyAE^g zdx*W&HM@VwL;6()$#5;h;up^MCLK8y6Rw1+d_)bb-?dBRyGfV90aCO3$kCnQXe3tt zB+dh$G=E;~%1L*k#r#B4Qp0j803n{=U9^W&^W`#%6|97j`ti+I?#hPqRMOEiAy#W) zGdlWi>OMo^aHgk#_T)fd5phqpACkRm?TlJgd`&mczJBuP>*&Pa?JmzJkzvksGd;G7 zW}iX)@7xCk_47}!9=o`45?|XQ!DlE7_6Br+d}y2sEN6Gwth=wKkD37PN$;yUWb(qh<$HGOk@6k1tOO6gg;>>tG_(gjz4#5gDIIs#F7T<1}OF za_GU$Ledd~cgG*8Ljh}35L^(D_pUM1W?!pX8U*3F6}F@BMtbkDH|Nxn_uYipoK_1xGYp4_gjgWw^SlN@C`Gh|w-*YNMz3#>9*1sMl2F;jmz=hwRjq{aFFW znk#yNGh)w1b`X55!iv)0{6NC(?Qzk$?%y85=G6~A6PFrw4t|Wgtx;i-S53hCkxL<%^F9<4MKUWwb-a`f-#W(R%()(dKBH{+hl;QD9*{_Z>{h z1@^6M1DoM5+~nAD8a*T3(7~bA&GUa;HEYv;%@9$lwq0zJ{w(D-xZ z(F5^s|A$?%ft`W1DgA!(r0!^xNjEXsV9&lT zL!lR?Uvx0UAYp!bd;~k99w8LFLNY#`wtJjBkK}?QYqw(e5f_yPJjEX%!TN7hbw&PT zU355#+iL2+{S^4|T2U?Js4q$y5To-hlzvBI-iex$bGV|hL|3(4Qj&xXYXcZusBOu~ zyTa*%EeH5O6~S; z-aYP5!n+GkYuA=kraJYE#l+qQziYi?n3(I?W_d=PlN=}stv&FNuAre3IpQ5&`NdW( zkAi>e!%%E(ZL@3HV-^@jwfhIVytQr^D+Cf9~@rYXG5n6~1CZrODI*~7rY874}3i^7Wj)6gaza48|A ztj-pI6ui$;y-O4yEEA!mhbmPcU>{qvfzLFP?HW!gUQVf3Ux<~NO!breb~TUgdz#k= zBAhpz#2UWrk>}jGBRiJ`ZoSWFCChP+$R`obOtTBP&P6#kp=}1bcDKF3>f-LLkyji& zi<#e&>~z4!gRS%S?nJk9KeV3`p`5#)WxW4fFTC5egDTvXF?Gv2HBJ$6>}f#tN-y%A z8OXK060a11zSV;SQwrqb)BV?nz0A(r5Z^W#-9>$0R&hWv>YdXWjQqC^7_S2E#_+jS zm19V6lKw;SsQJwp_qUgA4X!A>HVR@CvWS~&|6yP{)0lIQJvB$8y=3&P(Un2nWBWk@ z*|8zzXr@BN%`a!wp1gTv0^ORp>u><%XVv`)Jo?c27yY$@`a(pF;G+^Fq~B#%Ll=TH%fe9Zw9!@5F0kCOSKU&mWY_YJ$%8 zbE`q-$BTOhV7RV?-^7P3lG*Wrr%n_ZxDR%W5K4zKhMYulgBoRQuekyGlo$}E^~O9X z_&)J%d!05;qqzl>eoCZ_rkQ z;+w3I2;uY2m7yj1(}(2c7CMm{)%L?JQTa}9dTC4c>lG~f98sd%sW;2LF-xWZK!xd`|&ZFd%ZgdRMBP$&E5&vC%%6B}-^-4(A> z@kPP><&!P8n$qGJm2&=Tgh5$jR#nKeU*RfEsG!F7&tYDnh0Dg$RVLTmaSivD$ehs0I?()i`<@bl2IKr$HzdZwV`F@)sZ?3((p4}_< zWk}p<5A{N|xq$cKhB!4h`tOo%azgidmyNcKp!(Ee{&s7{)bioy{=x49i6XIbMDY0g zn&fpsQ%v;!+Pxd_zVQObVAJ!{oA(+92EI9`!8e-rd*$Ef4cBveUJaUGb;T>n{esrn zTsUpchXKoDwT}LEwvP-Vf>8*7oVVlluJq88+*iI4I)f-RYJ7QpyHt%vZ`VGUw2eSe zb>~L-Q{#_#PScU4&WNF{Ja*C~Ibe1r(|6Fg-YklZ!D5AA7Tk$ysz=%ZHH;R(9xgMN zo4sQ6W|`+=|J}sXACR%(kza;6hTn|#9+O5*W_1H(*Ugv^v=LFIsA9Z}34?Fz zr1@Juy1+l2KP2Aatw*P?2-qTbZ$1t)tzsACFFDN3CVh={{S`X>_H47f63lm)Gyk+& zRnhTr+Bl#D1xy!5zIj{Vm){6B?xE?RP|jUn^2SxII^@3jjd)D1CnfL+LG^1R$O;A1 zmeJaJ4g(_l8ZzY)yks0?TMg6k;}t5$g%|6u)?<3w)E@JaFJTS9VZT@N<+C~QH6xl+ z(P)qCeh>uh#a+B~cq>Y|eAnwZN-7un>u0mhDeof}LVikTbYayB8N7j(yg1EeZlf`A z;`&o0eybKr%0u3MF|jMw>rAFzX3bX7;AnMJw{d<@J`FV{pjW;-`Om3r0*du7FzGe! z9{=zx^~A)g#HP5vXH59toz^ryf@vbsRPdLkX`H3FNFZ1srwlYayIHT$-hG4h&9RJy(9n6QPvqg!|TV}pYU)Lx19DV{ZAe{OTVGqmFa-{U(v$i zPa76<0C-OssY?TX`&2sBam+8{k z`kj;Y`f)8eX5h7uAN7?_geVjUJppf(_YO6&?Kb28xx_FXv;GtC6mA1^j*mx~9 zcc?EAxlC=AY23*@B+l=W03x9Ejtf7NW#!k06a>ZIC+{Jk$(TDj{{I5ks~-uCw&G6v zO-|(73TJ;;6Teu$Q+J_S)n|?<73>1TZ(3az7DCo-`LwZ)PvR_#wa1e)II;hn9wm*u z&`w3+wc#Mooj(`tJz`#eXij8rolf|Nw{)Ua@e9@AuX9G9^AcO6{I{2R2?OGSj_qR^p`#{n=%aoo~#tCr$iPpk3 zYobw@?EwG!Qk}e!3<6U@IqCztg5nGRMc8LjTFyn|EqM+~h64n-VHGV4p*yV8AHiOE z9$LjRF%N~kynu=H_G*ELUkw1tzfa_<5rs|`KS7Eslq|M9tKcB+cq{Tu*hwUHnX3^F!&wwK{h&SpXi&ss+2M{8QP zKM=VhK(IiALF3U+u5e~A0i|MhHJ98Ani8}4%qp!<&UtfFNqh!oxI|Tv)F-u=HDhDN zum>q;?Qzr*?ySB45;M=@m;S5BGEsb{ehR}*68dXe3@$?0BR8biB`&E_swMPQBCu6@ zp4FQZvu20YhGgyX^z21Y$|---6h?y83hcxuTTQueegSXY_4@&{UfpkfI}HqhP%GW2 z2H*nTQh<}`^nd9|^50nAkwPt8RfO+D3oph3|0Dpi)-NV4QRT14-(5KY*>BQ8+)8(R zWQ3KG!GfQt9c06r)!t{&9G33=Lx@kt$e=YL&mwYB>>4$assBJ8?YPMWtON=HZWSWa zUsotA{_1v4W%zD~3Bahtkp>qmMjxtNR0{eptT^A@NqWYKR5Q0IsLI4gz}pu{RCV={ z{lUxXvTTM^zO8XKe`Ou&&Ks9$0}gV3R(E6S}Mv_xIok??B~1XLd;*Y2#pcI-Za zL|;6nBk#9cs@l5c+DGJ1g3ha8iH$mTnNnjhhtM+(Nui>Ycw4c)AtzylrLUYIYy@{W zWX+})IMwr+q9;Ilv+KFedZLw}GI&$@tC|QrRWuAVoi;fy3av05Kk_vpK4yN}N>&E1 ztCg7ce|hf>3i@9>nL0tQ2bJKW{20)M@@}V- zNd)l-5)MsnF?By$6AnqZYIiMH@gz0UUuA%>dt^i253(#LtZ`Ow%Ck+v$@UqbR@QzN z2L^9!t_aqcD!Hl?^+{PHpyEBzl=zB;&t_l^oo}N&Sr4Nbyg#vSWg(y3?*V*91sdS5 z(1Jm;WLug(gM*bkMChJSK)FsTv+MMoURh-`8jyZN8=6+y(gN+HJQlgH013D`$Jj9GZN2Zn+OOSbH|(`x+PB zqCc7`sUSIuOaQ!NT;#glVA_^!5Eh#bxV*4Zz?d%JMm|^tL>oKzd*W0 z@7Fi8f)hoz0OKD@j|uSrP5ilteo9hu^Yjj8Af+kT6``~>l&7=AN*Tmlvd>ESo3N2sR{~tX4naq)%F~F!N_Sy!nyB-=zRwJJSG0fyI?cbj zDBqRF$p#nR1y8o(t&&h&Bf^U^c$w2_VH!;5fizhde4{2aYTUv_b}?e3txwydj_*@1 z#nOeTft9pn>Wv5Ju#dd4!8**POat0TXJKa;(;Ote1C5aj<*KCD#-~EK_=AdrSU4<7BsFV$Hk+r}$Sb3wY7+@50w^iKq%KE0qC{b=BTrDQlPy zaYtTP7RrGpw`j4-+g&0mSdbsjy1h~K-!D@bb(#=MbM`B9aGUh|Sh}q!Kad;7s_+?s zesH*UeSA*HqQ=Tv{?XR6a1ts_NP@XGT^kZAx<6w`Fr^IbZ16qEY=U$Pc^_*hBMje& zF>kCEk2Gk;2CHJ4$h{{ZyADnH2465?mw{JAu3Z`&O4WnKv6pt-Rc91wvjklHU2w6M z>e`G#jf1z`6w@mQV(upnsrT-8tS;3SJ1B-!hOqoq?A-}& zRMTuyG0v|1pZi+?N{14VUBj@A1^hk{DT`n!z0%8Gx9;x7}Ga%;M9Pzsf(ACp1$p zWlC^NaPhV!J&td$I6&SCG9;bfmS4>Y2kCKtx!!uS7M1WUVcwCMa)me=@v-Ql+SHl2 zG?p|@qV$0|uFd#1^YjN@=P*iUom7dqW9eMyXy)Z^rOV!j!zQbhW@|6Y?LQSz^}_mW zID2F{Y4qu6eCJ*Kn`A@McZO3!jz=6r`O$;gvlU|N-i~VlK7pxSBGdTp_Crl#b(xu1 z7a52)YQv&7^qBrC>!d_r2FIp%Jzn!wBT20r5cge{q5GDzmnu|iiQP2awLnNV-C||* zU*Lu=Kh=~fd$kn%JmQ^d)_ti;acg|fE55s*#SOgwnJl+I?lQDSrZbhHlxh-qU7DaL zZFc(yV;$6nToSw=40>chOt+MP%dF3WD&H3kV zur&~LC$k-up66$gHya*E*~EdMHL6a-qmS0occeue9a5_62M20O-#V^j3Ae0Ka5{he ziy!jSwEel{vYS?fcsw=bN9BHrYE4j_p7pyqe5dyLiOU!1X1Jmd-|UNF)_c{0?pPg% z&xD%#j+TBX3w`_PUqH+KJGHDxZUi!>{PoG-!%vOhEN1GB%b>st>e9;}pA@VLH*#?( zj^nk2+!R9v6I~=mqpXZ)>+5x4^iL-Y!3xJX26QJDNaJ9G4>3}&xt#0JG(}vD*rvN) zx4fQcCe0rmuL+rJz3ANW2*D$lotQMv=%lv4861;;@qDQXW0jq~F6|zDMz%>si(MA5 zTjFAo`k%v3!U~)RX)LK5OKnX~l4{w!0*>tsG3!v6<1?Y@0B(fn+l%1NBSEe08xaNR z-dao4RH%hx;Nae)vWDY@LbENmwm2vuO6j*Au9#8lXtnGM<&DWhuH?ScoUxe4&#w>W zx4OgoOg^HS>u!i2_UWd(pJ#t$m?bKY$S1ikl@Y60`Wp!tI{-gwr3Om%zYdq#0p68o z{d+@lNc1hRoWh7D9TlHq!p9|egLT?smQ?O5wO!0XP)e$Qv?Oe)95zNuvB=%G*UdX^ zmI6{a?4rfGnP@#T$Y{~Ek?~GAkE*}!1OV{cye}YEStQpiDyV^7{@Ki1G-%4keDfN? zRvYG!f^Gl@ld^E646GEafi{PV0!aFAK|*ufr{@f*?fAR$G!h|kv*{W^u_G6jL=w85 z(MeSU8`)QU2Np>YH7&bS!?&NFmcfGzZH$)y(4FXP)PPNnJ|>Dx#)1s zEq4;~O2v8<%)^#`B`tFc`)pX6j2=U3*@BWL)atb6+-mtjrx8xt2CAvmzxPkAe$m zfQ7+xqTEWiVD$rPFTM+mtLm5E&*qpX$H!M}Ob2P~Vs3zObeKC~Bq2V17Z8Cng)$N^ znZF?yn6CsblI>j<2SEcf8U{W~yKp_&gR7gjOCUDLJ@`Q|tmQ5Dm(ntSAV>T8^>-S| z+*W<8+^Y?b3KMCdoh|&C&rn|`_e+U9Y{5GhT9^r0NZtu7wyhHKH zri+Z6NOH9?B>L(dAFc8d= zzpapd-X!*`&GUp4nYgBetG*x1%Uya*KrRq->YQ`dTi;`uhJ(9KzB(w^hcS187NDR+ za05lzighY#Fj41_UkOTAuDjShl##tMc{f#x#MnBUmwGG>(A>9j zkZf`t!@`ylOw?s$(6Y4v%Fki|m@%B)){?Z(QEKJQr{C1IRnB2W?zNWavT)MTgJksR zp_aPYuMG|v7B)?X=%`jTE-o5g48^Q7Bn%;_kyW+*fL~|#vOP& zdkkF2%09j&B@=p5z~*h>ZDRn&%^4KE`%l;hmmAmg5Mx9UqiJPo4xaQKF{1?oBKjnh z^JvNCig1SSpwb&b#R+w|$#0mV4Z!6ID?;)0&%G(sA3t*LXij17YV3%Cjv)Dzkbd6~ zWx_T_C7}O_goN3>854H3x!ZM|k+(lweJ9TC$?>7>KcSeH7?Y6^3?`(^PEw6A0qnut z3l}D;*vbB2E@ajJ+F9V+;@>DgL4kfXyBM%v0k*chK{hskT)ooUcexe{QydCS*uljl zYX5I{9u*QRyvTN@G9c&jvT3XEZwQIMgv-K4UN`H`Q)Tm{M-+j zxaY)tOMa1}Q|{&_*h-gyBKEgSU}d4oMNCUabj9;hlmGE!Rl&SK>7SHmsgc;LHBXptRC(&*45i-OB{L zgQ}8o#*{@u!z^emPp0d2;!r{`J$#^d*}o8)te-+E$T;yBhI1-{xAT@3$tCBywE+ft zQ|e?W7D=}1`VHKG2lee6kp+eFQg8IoO!&&oEl;K1hY5FSaNdTL@t!7>ls++5HUPK@ z3;w2oaMB+P23_%SW&h(s9%JlX2Se0}$r$LEp!iB*bPq%bwmm>R^I0Q&I)UPvy>18H zdO;G$H_h6@KGBrn%PTawBNNTu+>n#_d91j*TTw=F(wt2_$F9M(31X|_@E=^CBCPJ< zrZ56-j%9;2OABCpYs!tFNK}@AmB{JDe?=&@h?`!ce6SUzLQrbu%0GsF5i=?!0#)*3 z@PAP95V+WVHuM&f^!7nlXMJeaTe;z+bD1hlqs3#(l~uMVa0U>$L=$z9O6gA;0OOt{ z*wj3Bx{FL`)LK!nsVMk>HU{F!T)PXR z;L!^uQFDL+t4Cp779qj;GlAj$(vU94HY@T#PO|ul;@$edh>~&KA>9UK(hwQ6xT|)3 zX%JHL8|T2RfrHaV`hjFC_02xUWM^4#2Y^ejSh9}|W?Cdl;-vQxCIFOY>HFcpB*t5Kq0i_v8in{lT zN&B3>Ww*JIwq(OQOYx=3MEaI$(KG18xDm!64}`*3zzAXFffNqKFspsa2JxRdvpc@z zBTNa4gz#t2bvr&@w@Czl5O_TYOYST~$(Nzj%dfN~>UQKJs~p7f1?P%{g3_?1?ZF0a z*4LX5qiQXNYA9@@>-6!pS0XXK1I5e*5wkGfj5t~oaWDdbPJFC118_Ni@Z_t(=nDBN zz22oNfKfhwc8TweI>?3!1@cO?P<@8lC}H;t%eZpYv%4FFHFgc`n`)_BWw702RM``> zpk7Eln%TBge6-1?EC#@drG33-*#!}(^vcu7EmXxi08?ORpTD8h5)GON%10#_2nI+- zvc$@OHS?UMQX{zWycF@P-H(19#T$eQ7t@{L-5La0lzD-}U8U&Kio>3|p`Y9Th$I#a z5JazhK|%jlE@p!yaTm(|seYn(9E$Qn+jwcUX$5+FM>5o9%LK(!{i5|!MA;(zMy%5=O*j-b{2%#E+LPEi&PSl; zsd+*zQ*l5fHkg;5qa)&`E4g!ZqLiA7Gg{d_hztkoz~JbKzwS(Q%*~S~GtMP@=#JOd ziJb}!%WC%h#bYRGIW8==k7cyfk(V?fEON`+Jt*#0OQl-Vy!M+=`LHDBmPO72Fj`Cu zHnDgsla#~?XI||f?9oGh?3;YX0g2TgATbIi?Xzpv@u|lxm-jKI7z0lo6+KvCXXhH0_^~PR4XH&HY0T zu9lpXm+NN(f?hCx2J}9~t_dsL6xzu+uA<{fvA=Qh+H4X;Wq_hj@ihxgRPjQ60N`-u zL6vv0&~0r@bF(j$qB+eT94+oythKyhqLFFH=R5mlEmavv!e{Vf=>VRU8RZfm#R!NP zOd(P&8CdIBCw%=NTsksXEjVuC&w(Ndqt0< zCLWrusL)DNMG^XIj%vgGQa~oVf=iVm`VW`Dpym*Y@1T5hR(lsaqmxo_$$eb57gT4n z5%K{2YO*?D48AEpZb8^MOk~P$6gWb9EP=J8RCMn&Y`PeWPP4MsdO-Xz;BhxDURzJR zU!q-2O*!XJx#~`cI}=Y1)?~@MA7uGH1$K#bMe)YSJ%mmvOV2Q-J=k-tly}TotC8FZ zY|{9alPeDJu2Bp%=`+1X*f)LHjxvXSx5&5qyri?aZ!@Aq@yP;LitY`XTUXagE3_N4 zIRLqugOy={a0L2oB$$qvH~!{`n~-SZh1w1{`9cp7Dm#ITGAVxmI*pIfX|Mxx2hxyX z!}7XVWc(kZ3}*Xe(qI5l_EXrlW{2=KB;`N1A{#fBMaPtt=aM#jdM1AWG?1lhjCFk9X$-+Y5}_VDXk&(D zau}c+Qqs&bW+6&>GF8*tAYz% z!hVEWLOJF;Cl>o3gMo^Q@xRTJGMn|y0aM>v0Da!x|Dox;r{D3bJy{Ls`Wh#RzBB>1 z^p?zer=hPuwEAjD$FpRjd21fxKUnBbg3Oj}-?%^0cVVT7fYRPd$s%S9MIUlxd*Lf zi*6Lf-SRy@ZUP24DznYq%p4ylb%F0`=F$7|6?=8Vm~}Q~rP^02ZMrLqWvmnJ-Rwb0 z|Jpr}%|rdCMDgrHFkG#yVvQz==%~U|1Z)~Z;ggBvi_7dxcRc@!8RQpo0i_gQ45eRZJ~qp2T@$`-Bwn?td!RWLvW3BhiYoU0gk-=t2lkfF}7r1CR ziV?S%UaJ~i<~$VC?nEKRaA|*Mw|&mO<*8uq=gktZ{sr!p?K!+>=}Yn+xkekWd?P`H z&zb9)r`Da{HqbXBWA>t3bG>Yfqb?R&Hv72k1H)<;yJD}^z5Vu~;o`qQ`1{;ZnJ+8H zn3#MIx$#T)0`1@5-8i6${Z4IfS}?s}@ejt3+mWVxgToNTlkF1_FL~$ZZZ8oO!;%^_ zkD^!w4yX@4pLM$C0Cn!ojWDwF+cny*)#rO{gVG;9G&vla;FVIgv8~M+7ZDX1_lI9A zmOiL)P&$SU2R%i9{kWxi<1uGO&%CA5QK_}SZou%2dT28(=t0f|K|X?AW;sjdVC5e<$sYl(P?-9Szji5i3NJx zOneqe#s<#E?h9u7kB=siOvEhN1dQ{=Uq*-TndKqLUM)6`y|w3}DvzbS^VYdu^brC0 zVjLX@Dp`9jDZK_aC51W+$FdrlSYC8`QW{i_Dy)iH?SA<{GeL zQrFrQ6F!}gR)3h0d*Bgp6h0O0gwJ>jaoMI*f1ul~l#8}Nun3Rxe;l2AJk#&{$2Y@} z$SIRCHRV)}r8&$T3Q5j~iXu}=PD2iJno|eOoJ-~SahO9nR8CQbYz~D`-BmDR=j>-|L#V=e)VRjgf+8AX9zmu=I$UT<9DUUEQ@{W zlj!bmc&%x7_&lnYD@tJSSm8A{!xv5V;M@jIqM&cUEl%aV^wi6zO59~iIq%{|^>Q+L zr)Q*|vq%JY0kuIDv;Kabx_gRmuSz#hNT~sy#|Io6_hi4xgT?}S!-tRof+>MrUHWH( zIYL|Z@ImcC#a!3lWZ0-%MnWx%`~xUGRMP>US=endbh4lDDwkg`#GSw)@)EtZM_(=b zp!7l2%5c@ub3;0BZ>u8a=vE&y!!h9EH;r{{9&%8~{t>JnbN|=ACEf(ozPrT1KFEeic=T>v`1< z$XM>)e`Uoh5NTxsLo&WQWIi{a(*^DGMw;rTCF_W7p#P?EeAE2V{6?p?g@gFt|Hz0` zG)PJt;pOlm<-z^qhAqeSBW?6|t%N$}*HL1LK6AnQnk!8lim}50fe%o2zdhGfe4}{z z#91tibJcVOV8l|U4jfpatGv2(?y{+VMW47B%!6{q=acl>{v~^V*qLeQnlGaNi^tkA z`$mzg4Xr{ikP?PL>{lC=d4VE|3!2}zU&zPlG#=!I|2!XgMlrX|#A5CFixI(zBwt8! zLEct{&plPMt-pY@cT9T^@$Nx;kUjO6PBn1@3gDIi-nsXscaV{r&ty9wE+=0!0w}6k12nz?sQN z)U51^emW+uv#Ko}Wd^E5ek}^3&8chyhjA=%{kr&{pwKujiP6|T+(3<|X~lbQjKV$2 zXl$-oTG!&zwqPLA(V_NBG zoY)PH*uR!WyF((Y4VmHR`ff!_GKXT+Sjn2~N8=$;nAKE9mo~a96@{WOXf=^hjzJOO zdZHmow9^oJSc8sf&9#4^I5Q|CVP#nGoF8gfd=%)Q`(dPXi+7mkZ<+k2+itL;5k?A#E<{=_`&Xv&3-U;gQH&PHQF;s)pE*Puw3I9*sOj;kb6@2ciGC z1bc=!f57!<7Vy9T)R2ewi<cQ6t$T=0V7QS52w+cTmgKDv7DQMq<2~4 zyqBS+7Y0Of0KRIL&hu9sniG>Df>CW7rEYbJ)_(a<-N+=qSgP7EA3piHT)F{d#UmxD zja7QbJ|ssI<;6X<_Mtcm+`_mOxTU+h?0Lfpm7`Q@py#4rKiV;ct?{lVI=yA_UpcS= zMH&su>rG@lCr2``X9U5hws{-q2yKU^zb8(QJehNYV#eW!Vx`)gIg#PMnhyc*9}Ec9 z+crdeitU@p?aFHy`_y`qme{O(TvcuTk@PF7(!DF#n28Z#X~W;UCMb}=L`;}r{hfc9?94NUhcJ2aE46|=##P1raoaw& z+o?F2N7QemcWEsnI=CI2g$|{wzE_L4#iw3^5xv3A1P#7-f6VZx$H=6e>n+)Ue9;~X zC=PiwH|}Yfj-|vq&e_Q7%1q4wla3vZCf3OP2^XaYcX|9Qk@1_`x(*Y$pJ1t%oz2Bd z=V1#bWLDnMUg5DZOHS2Eg}T(=A7;DL-9&M$J%0M?+c2riORu$h7N2s{XOZ00sOLFt z#Tc`+TZ77*&tpse@=CZ{i+2=R#dV;ZvpfIK@He%zv?H@P}NX6PD>wZqrO z3GS1oLu&$(&E7lfAdkLFn}a`+tE=Jq+8nc3lTNGxL=iwc>})CSXnhK1uu2XEyX~j7 zi7C1fE##)W^Sh1|+L1pI0L@56GU||L>*oQJoI2-^7gwK`u!K$7i$KQz0IBH_v?%bl zjH(e=$@PKRBM{-p1?X%CP3-&Ad#o4tGn%U79j34Yuk-n19_YVOj9bn~_ql7wNDe_^ zfI-&Z^Ne@iO`URqB;%f5jaip;=>SH%V}A{7PsWs|)RprE~vIauI^m4mm`bHOg+?!tCDv;>Vl2XMK-90<{ zzMEBr2xi>Gb=d9ZhVb(X90Wob_NVpV{&ud@|LU`gpV^pa<=McDcneM@NacxaNOUY2 z{_-Atm6=ufz2-x&_05FTLLW`~eYT2u@PV405Av?!`=gaV}@Po zEsgU7jP}bCx7uLPq-~Q~W-c|;!2W@R1=Q!&QRYbAQG)D}0FN$~vGEQxQVSq5oLx!5 zm1`nQrsL6#6v6a6ssaN8q-?aJlEl*9rQ_Sqd9L{lL*4 znquSw z3Nwl9>sj;Q#L9!ayN~tfi=kxmFl_%v4sPS?1=*Avvh%Yr7#;M#ir6moRep_io7X&} zM-{D?3Bc^Az5I8sgCuswTl1%U=%cJMY3!sa*5uJM5{GL<`%(mN9^c)YrrXiY1S9Mm zka^5?YoKJYt{5{S<@t>PQ^(Gj$4eRq{KZ{TisR=F_JI9$tfu7g=ARK=$9(`X1BO$E z29of%6m(y#7eYN*v1WsbO`qLOURDEqYks}3 zmc>5oYMwyMh-tCSsk^AD`RWcjv_ISbR46#*NI+H~MCzJZX6K zVc8fuE@`q#^jI7z{`gwRb;AAW+rlYsOrSJ(#G!_D)_+Tp5O^8UhwD?+-iMo@A-`|Z zx~m$we-7krE_nnQ)*#E#ugDJ7MS1w&R^b$pU3fQ}gf~AOh{# z^1*mnYUJ8ei3RAnGxzy${}$Bn2(;woh`9J+R+~t zjjDNyBvr1H1^O-)bRPUT?XO};oVQB$Mcp8#bafvh1^ZU!LlAd4ghyaq-3?ZsVp}iyX zBtHwJTWghX0oB@&(n}w1ZTkKE-j&WHJtl)&K+3;u!G}vfYJn~K&lIVR!F1rX4PXCa z!pS^B8Vg`pdpX8c17V`;eOq+0Sv~7)8cNa7{^nJFbVn{t12X22*Ty$KDooV75UVyEz}EUe5GZv z_f9Uu`RzCU=s52tz0gh=&C=}eN6r`5HOo@*O60TJW3#AAjBUlva}Ef!n;N(*Tnl*!P-tO%hF?i zy}U-^k!1 z-Jbq4u*{_!kP3@R3<_HB{CxLL(#uK)fS|vALL7@xyF628O3)D*%h94037?INTq1}H ze2$OHKd&{PT}qj~CoGuGw>}m`YcA4?A?QPh zpn$X;JnnVmU`lPdif&T(Xn(mLHSva>$jQ6C`_1%`m?zC#nIsbk>Aw_5Xb$m9PHg@G z>c89WNG*kbAQFAzb-+5+Kn`{;Ct%Rw-ji>W!uk)!=*y28eIBIT_z*o3?3%E~u`BCP zScmS~K|Kv11%DlXyKb5n$2mC%IWrh;<91nXY%{EKIp}DrxBGh)+@6N+% z!}&5G1oEMdp_`0gc2{}beLw)$w^ri4)dn7pvD<7x0#vpI@O7Zw%)+lZMWks2wD$`2 zL(}S?*49ekhGZNe_ZrROLDB^!dYcP+O49d8`YoeXxB2MKh2DOPz$(Z2=PL5F1R<4nGHj55}bVc>nTZ|y!AMW+xzNGZHP#*dId z(T`0s8$|m0+oMKNFX!avb-fpC z(bFtlB#C5Ye{s9}EMhynW?y3Z-KUi$@98tL*?Y#>!2`Kt=gI^3S}*%M{0=8QMVw-H zEqDQ=v|hf@Y+3dX7vI{!stnfQ5Mv9T02 z%4A3JyV^z5T_lF1?tn?yHl$GJep%k$K|^Kg`D3Tnxbnj9oVkReAKsxx@ed8TNZJ>y zjtHyY*a6^Pl{=0duk|LG-MsMJiJm8OT9O9y7(;*psZ^0m3Ah^Y7Zq+K& zgw65Vld(H)%~l_CU$)&;G&ZmwV7gi2;AWV-N`S(8ED1^15bEAFgg;u81|P&n=7dB* z4^C+-ot(OH3G@&2$Qa{1l>O|tRA8j=4`|Mq%`wfrd9vu1E@Tu%Sut2J!8w!7lrl~S zSYL$t;xk71OiR9eJa+N^BKxuql6+_MK%pR(xMl$k20}d2K~z`^#vE^VPjA5w*I#7a zIUn0`pa`F>W?u#wCB%_DJ0TZ@{wLk1PrUgco8@jF6ALT3rP-N6<#v?%pnsGOyCA}^ z>90lmRaE>wMy;Q4;sCO1ciBIJfFQ$4LuBdoQuU%@EwpJsE9A(?0&;1H^UY?-8|>Jk z^Q)1pO2|9VCCahOswWr7oJ0ttUH3ir>`Rh>01oIz6zPo{YYdN6V2JLpmf1fGg9uz>Ji3|u4u!(1cplMw(wLv^%;1_J1Z z$5#C+2_p4}ijS~EI!}DP>~tK#CNkRx4=hYTsp8Q@EZ_?#agcbJ*RJpO=-K{?W@R0h z{IF{~=(-mKC<0qVLFEKMySa?|PgS>y5HtD=Mq{Ch{QN=4xen*8?djK~=XG!{9}QY{ z9yr~#!FeWyl-19L>y-fyVB&R|m#OO9A#yULHqlJhPOrhx08mK)%<`n%q;z=+8Yp1* zXOQc4*Zt2_Z)A`G z48$+O{%(97_hM!HlVDeN<6)t7A0Eg?EqRsV_w5RW&p&JmV3&(QBnuG=Gq|A(cSi4P z(H`}>sR5a%7biHQQ(9WsIh*oUx}`+!fG^D9^d!s1aQn1&^!Q1 zcv_yD<-xf=T3MuP0{pd<6;yGf0BY`e`7#Wy&V=Jeaz6^2DXXhOU5&XF^0_VASXHRo zPe!tC5L}c>k+$RCsGjAC5E{DbxwtTQ!b)DF#L=N+OZIz%9C^+}dT<_GCk{Bk;qmC^Ua{jpJ{p(da@|aj68 z0y?(uBON5Hbp9tFPY1=T-w4KK9a`?VC1py7j3-ex5$sPc>9ZzsLxW*9Oo`p7PblDu zC7o*qdg7-@&X7JlTxXc!IytK#B@D|E`)*;~&kZe$DT83Mr!+}D>mlgCt`#R%S#^ir zT!Vpwv}i~)(2@!2&&U0I$|vZx*XQJ!@pl|>mqp%+#c^)a%<-?KH56J2P4b;fQLVWL zC-)%4t@%1Y{8c!8>Z|+lDPY7La1+#8q(5GtMl0Ft*ER>_93D6cIn1L7+@WIc3eO*2 zS?uBl!^|pWzXlo1?q=hyxM0jU6E2{N91kJ${LEs4{hNeFeX$O$a^GWF^xciT;t80K zm-4^?a#3GY_kDLfMT;im>KO1>V=Qte_n zk634JpqqndkAlYaL3xo)uJmRlK*1G-1B(&&}f<@56sY2?&;; z=tWkN4#%ILznsSBw8HNWp;g{o2t1U!5me`3FH>h>!2^+c(rnh*&klO#IIA2&C;vHA zs;mCr1mTJUFVFaA6CfKSrMFn^P{|Z2o*&t3vMVIw$pwV&YC)^_953I^8%`EV{#GEz zr_r@Xnl6f#ZAGpD8I8MhpU$b<&U2ct{8iN!G;5R)Ki|wp3;rnk5Jrt$xSi8l_ay$H zAp6Z8NkHkpeqU)gmvtwEC{Qy-(lis5WCp?0VH-07K|D#*oi_ z^lIl$%E0J_MfDNw)v?%tVZobo6<%x1y6Dl|)(?O71s#NVl!NRbnO|PvKK<-Z#8V56P4lCv5yaLu~-I# z)|URUvfb2^OVDDajBA$PQcfT;NMg-v0cK(2F{O|HeGj>3=fDP%Sp%b4w&g2O3X zqWlyccR%piijesMOjq?>io=Eb9o?G0_DE4@*KIuQ>m!mHgJy4A1~B_eJ0f=|9bl4) zHDjarmHl&X8QQSmOBo!k#%M0%DS~tb)EGMs__ity4OJ;| zv>MZ4{EZHk+c+Ww4JxDB0L8sT3()KBe_r)T*x@A4GC(i`MVXa9_8k);POTkO+thOZ z$a<_RvN4ybs&|jt&vz(3Xk#SQg3%Vp>}Xf}%}JQbqv+-`+Aq0}l^r?!krF+cN9Lyz zmPgvF`!s=*3@o{9$Kz)>m72xBH9y3#=KW7=ofkwNTBY5zRa)Y+<92xiNuePE1Iws4 zoX%QKP^Mf7dgd^aMV&Nu%ovjDW^e^=CHNfn)J) zEL9UxdX9+=Y)Y`Pcz3b4s{Ze55AE(gIWNflr>SR zK_+D(6yR1t1CFEF);s->=-6e{0?%SQipw^IAh?+1c^`Vm@{bfWKQDqCUflvq9V7h!6R4%R6_{8e(StEyUM0q; zt>c)ce;!9V`*Ex7+W18}0RBqu2?L-=_4s^ohJA7jD+h>BAL%@`D$tEY#H;9QPUV<# zMogN4j)0e-77BQ{2nz)MpNf?4h!514ES>XJ(9<@?l>ZGL3!nc*5VA{&vkF-lo?k1Z z_}D*2OIDIW*4w1tf?Aksg+Y4hxu-U6hmW@PdsgXQ#Mn}=4(N_X{lAER}m*`oNhO(yM*!EgbD z0VFX?>Z}$XEfc^E<`DY9Ls^lSY*aj3gbJehXbTKVYZD0?6uR`!Jl@1Yk-=<&$A{n| zaO0gfoB<=rt6{<+x_;=R65ereKi>c6145GwQWg{fdVa8$p-{#s;uk4SXz-E5W&u|k z=ahovlM=+Q4`B7gZFLZOca9JWTj|eoga(D66~H>8uEbo60$n$P=!}0Rie90`FtdyO z=#T5@mDyuUrwcvyZa~TQt8{d&&BHJ%ky%2A_rXCg`1d28v zzp_pCq+U7zPFcupy3ag(`Yb8!MCq2s64v0aEdlB{d0_9FcXTXZ5}2Zxls z^`qN>42cx7xo1P)zU#8nNP5D!(poVmvx#83hxJ#_X1`5vwiofTpTI3O$gNA)<%0Dh=%#*ef^$$_NtqQUQTYtRtmwJ{A`ogy z86dPs+O4tHsA|0f(u1H@O@bORdsx;R)17dup`!BOpQ}x;9BK5UCw}<|DtG_` zg*OoaS74;jV~#1cxi_Q;(K80-9;>2k(zDvnyF=spy&|MOd!@a7?h)`W z>${_lPkKce82{97^7BKn5#(R#;6X_ILR1Nm(=Q3HSdwa{hVDh4C(l9p`2A4%MvrKE z&0jGc#q=ZV?i(;&xD{vIpH_NW=hj9+_HTYIv_hsFXCRt)F_&Qs9G)Ltft3wH@t;xa z3;qkVax9G@S@hT3c6WQ|z*nW#5a^5IBEf5^2E3FN@8d5H2a)_ET0$*2a8p>ubF~h`_M51Q2N6M{Q-O(o9_y zC0)-JGBr^aj}i5f3dmg_NoQVmE%Iy1`K%)#53a0=-L}AO?(v1dc8C0@4rnFPpF_T1 zlzZ@-bjXc4v}3kkSKaLBwaA8+jvQd7)5_Km(10MnY5uinv|e!m~ABE zHt&cLR_c(}|G0(o*hP1iaiojy>_%SSJ?2)5`k!vUe_ zBvpK5dcUT}@ATCOEo6a=-Ks33=dM6r?|hNPPLFi-A4X0^PwdTY*HKc+dK>=&68 zY4=Lffb(D`U;qjfv_bQ_soZ)Nk-272o3h{%cm~W~u10=cQ1Q*yD!O{m=2)Sc%cnMJ zI=Xpp5VUlL+b=IH2uQ16vQSu3cEojslg@sG`Tyzrd3*XA zC4&Cn@?ulc&7|{(DGYK>0*)(`m_A#D4awa z=zp2p?g)5sN;8d}g$B3@(%_jOEYK7+EtepIX}zNZhq<1XWQ;Pj^89p>35;J^x%Uajy-w5qY% zvI4NGVo7RC0ADgIH#c9#eS1qfH$z#}$5kUY93F8Lgu<3ej7ZL*HAomUbqVqNl-4XT z;~!|KU>49?gy=+>8LS(Zemsa(BB@7FtRRp3zh@8I62sD7gF5A+oAx}U(>ZuM+0r~n zc!D`U?#110M(%t9$PVUa%u#u}H8zKj!=3(sEwsq&e@u}W{d`3NI@LEwI z&>x19+5pDOt>06EJG_idxb4+AFCilEHwVr`3+@2|zqf2zy*u0Y`?O^ zsE+U;R1o>V-VxVXZjK0`QT1nT{w_oo%2~yUvt%9F>Oh$UCq>*NQV>fz&6tm zp3a^(7|>$wMyCI0%x(@55YP^@rCdAkcgn(pSC&x4GZ`nJTGM3wBfg}AQewU*W$3qH zlRoK0)|@JJ122T(_pJ~z1&R5zNIj-$TfBMTymUQ~YU9H7`3ZCwc)}P*$h=;`X6cPL zlFxl;UbfttDh3B@qoSZJKd^4@S6e@=UI`f4FDROzg|Re4>G%Vu8qo1D&~f}7`D&|( zqN@T%B;7_gXDCYswNT(5L;Y`3MhPaT2vVu)0lnlrsZ#FNHwIKo7qX{wcI^E>S&=e7 zwjF(8HWu>W`1j57Cqod13d7WkSg;xqo9o+^T^A&j(JA~49-lxYnZje#k}3!KbF`O{wJ7HQvMinq1WV^^ys>^M8SGBP zLV%c|AOp#vzMu_u`qG~|xuNO~G_V-J6zYT)8{uVZZ}DrtF#>$FlV0a}AGhrP6X4uR=He71 zX?j6gI`;ZFJwtl%xRmb_LHmUf(48&v9Y-B*#}Wu!guxbNCPil;V7>;won0=AZ+ zpG{)8Z#1&>+4e{uj69053BUod@jal$c97vX<@R+yyu0;Bk>(T%eJo0)HT_td}KA{n}IC}5|sUKdJB$^ z+x6%kWImHh^RR(SuhPliG*Z<8lN_*rztCi_fScnsT*!;ocd%~#kZu+I5UJkXc6m2# zTqBI;yIMR$4X<$2O&K76!DN8Uf*zybm2yZ#@BljAxc5a@#gc#}8Wu3npY`QB)f&YZ zf~}a5UGJH@V>##bD1u}&OII;F!Q@p_8d{KSF-VcJ3UAeOfbZ%W_G?qf;(&YkWZES2Dl)mba=z!Kn9lB(otqC2yQUU*~ z|2S4nIbEAEX6YU?_x{ozFuQVUcrY?|sRP>t6s<^G6W;Jge+i=qstQV5zZ1mzhL05c z?rBrz$uTD!LPyt2Z}y}3>+K{z!P!}k=SpT_p`Jz{K_n5d-+aDo8TU&vo1IeDg{`|H zj=#(*?Y%Y8Y&KsIrD5OjEb0@5f1ax}@aed2wK|K!)zYzbP!=EE`*fa1E6tyU`J}V& zDAe#Hq*X+vE&GO}`3$3gTRD6^F}=vb*`jy!@xTF;PMtf+nl?)@A!1) z;_oa7Rh>L{KseQ`@a1F_jo67$?5j37{3U@pC?Dy@OGm0;+cxeXDY8$+B=v1+zU-RY zjn^-!RXO+srDV-kFEZ_#RAlN;ouMsvk<`{bUf*qdYqJ#2X8tzZ0AkiNHcD2%mD*fm zg&*p9J@UcP$gt^B#jjthoz<}QrLfJ#4W^TSYwr2X)>C>^*J6sOPM_!4YK@vKAA~}Ks4tI= zHpBWc?yp}F){u{gn@L%BCE>HeT=##qkG~}yx!PTCPhTc^PNp9_ z5>DTCcRlRa##=$fyv0|f@A+ngOj3W)oP&@+^SJ?1^zn=&p}>#pmI)lr?=cJb&rxJu zGuf#0_SwW?WIiKRCu#x3u;tQmVIBeOUb$5>XlL0*u+-Rta+2;UI-Q|Q+N~ABO1si7A2HNAC&L(}6I7K&7Xn5ALM3uBzh$TiWew zVW0QS8|;Pe79Qy;fzDDGqX6Oud_EbY))92f=x&D<4(`0fA5U`sJ(&w_7_Xf?~aaH4wN1Eh2pwYbyS`p~pB{2`7 z(%GQO?*NN)nD6)cm#(+C?8z4Dn2Jm;yT+sIxgxo9zj;NabOHSsKlrOFN!cYm(Rl1= zex0kZ_&{x_sKg8YFFr#8Jd9|d8BWEG6taKS*CPJ1O{hBBNtJ6+X73^^kG$n+C!8IR z);Af~Yra{c8FSiU>^hLcYbx~_T4x3tPqY5aiDAK z1kLKJck7QP5>4e~qNAgk{r^3Kw|~*S%S%=JxBANKKUvFz^ z*bUi}bs0jt;U|04HGw$5w|8tVv0|R_Eqe(jC$VdP-2CUg^?STkFLnutix%1HXyDid8+|JbC3-k_fGjY)gc^pEI=8ItQItQ!^a6>J7rPvwEIh+l_eK$wu%xQCvWbW7l zk=i-|En2hzj_h-?A})>E-507;_&=x)`-%PoiCct7so5=8pY1~K+EwXZw3E`e9D}Ph=j+;KTSl5(<)*K6DUL>dxg_Xbg>fC|?z~ z4A|26lP7$j*!N=;?3L%dv1@I|FL)Z@ZujbTLtMbHIXRUSz#b#L3|eAD;2pC11Q>U+34BK`KQzf~EYbYy*p zzF9dIHPXJlqd0A$F4V13xtt!A`z}(-*ff~W|35=AVyTh21$PX(dFR=}jsA(tzr5UK zvCRALNC&B?J;#L$u^Qta_<;oZ`B-9v()wJVhr_G`e9$yz6PyH`)lMcJW3^3!~6~b!$?mMWb3%7?Q~`x7_NzUuw82BVVqM$$AJ;? z?tRA{Ty)32234@+ekL(WarY(F>^r?zs0>K>V1@ynxcD(3qSvjaCEP{k>(bp0$p@@G z&SB6VU2IM8S;LxUbrpxhWu?E|0xMl#CVf9ukWbzc&9!;>XGN$a>FcK^uVB%JN0Rs# zE%en&x0JbWB@1Tp>P*R?@)`B_fY5!byf!s1Io|Iom;}JN+9pTd|8_WuEJ0v`^oCtXDt%$t_^;BC-v3!%#S(4YKnL2gJy1D_%j!8rk%l%_bN*`nw#C54zYJ(oujLj!(tPpZ5@&qSRF=0c0r*KCp})yh z`?R@97WJqWpw;z!CWhOsvXL3m7xe93>=z2{H&09NEZVfF{JuTz232S>g9gHrXnpqj z-AB$R1fR`Mf4Xbm*~@6DNJEzOe=lAmJ70Q^eDCT9c^h@{+ptfVKN>|B8`L-pS!sM+aCu zXWE3P1Ru`1hY|h{(3H38#*QO7`8xh`}pNM+%Mmx z^=eE?TD-*Wd+4_1XAg_~yR3jAaxu_n?&FcTo|NV7fb^f23}6l?B!kKXt<-X(%moeX zzsWalRiRKI#57ekLhz15s%DD+pO}-9fEs}qrHne12frw3v#NV0mb79ZX_upulm`@( zO61SAVdo4@yIvT?LxT;YicZ`n{b&*q-=zo2p+PWN+$7@Wz#8BAPhGtN_9xIZ(pP`r zH9(ZtH%>X~41Z+|pd|nncymGC>%LE9t=)v94K7AR_ee2^tC$*{QsdKUCnJ~bg!+DM zz2wC0rhF1T`)Ze@YI!GVHSegDa)0N1>J98fzk=~mDtN(I8#{Et?V-HSyVnj|>{xR1pPMP4bF#^yYg%de$67P;$e4oS`w-H%glBgfzm1vt zPANhgra!u0e+No@WoO*D2M6^1KX)9oK7~DVn07UJ6`zD8LP$E1_LZStPrI&0pPBp= z^$hPX5BgDjLq#_F)K}EG*qGpbTr!UoM)BR-OSLcGg?T-X``r|Xl)(orMOmbG%w0Pt zdGwXjV1Qk5>eb9OBzMqDbx6k;E`AFJw_`=yNZn)UE~}|8cev$w%cYuta&j#coif&w zzfLx}`#TO2w;0rbv|Epf=NB`JOoYh4t1i}xBej%b1k?t0hjdE2O8xIxe|D2V$vk2L z^#M?ozX5;i#K|Jmk0-{0>_4e(A(pmEneO`rEj|VyCL%BbC9$MtuN%Y4uxXqH()9do za~n5X0Br70@@pul*IQgOP z5#n~3-Ttquk0zomC_?WAR&1GBfu$NNu&RtDUa%2IVwJj#%8bArllG8p|0 z(-)66OvTpeO?G{NI9XI(nMrX^Ch{u^HnIT^;lNv;bMHn*&U9c~bN|5RaZBj(%$mUW zBjP?zptRf}#z-x5<+jtzv#OHe#X;Aoo1nV0NXuQZn67SCs@ACUSlRcB-?P63BUsuF zn_mMS%SNszU-YJ64t+hHBD7M6kcW|1AX&%016H< zK(u}3Gt%@LsOpi;W_D^Mb9cZP8YXH zgZFW#=_(h>%<7-~vJwesGKT7MyX!19WPNn1Lg8WfAlijqN`FUvtORXh$pQsi3K$(= z+|qpJjl5|&7y3{Z8-7pkO{2$oaBiUMYx={g`>`xz5Y2usU~tcVgY_rbr%Qc34(_i_ zQls7JxnGykJSh-!5rav0rFOPBax|*yr+V9`H>AhaB7^_=ygpnFr zrmg@g2M-dZakP0yWagP~s`931jWweC4l!mOF6k)%QOdR zOb)G<@_j6VATk6*bFS0-2HhXuDnTu%S>7);&6q57m&W|UALF{u`NjB(_r9@!6M18C z*Y1eV`%mdzZ8XpajYx>jh#p3e@WGE8Sxf`eQe1R5JGI1V_ThX zJxe=o0E*axCgokoJ&~A|l)SmUwTBnj49WN{_o^4g3HkXY8&hQUOz)CE;f&>XAZ}DN zEC>j5m~f8~QIaatZ^5(=CAEI|_|WP5ZOa;sY56w;(jEf?pum-DjUR3qyC>QYo2+Ar z%RQ=L-k_k3#aj`D4~rR3#msc$4ho7Kxf~1MPtp2C70==byW~V;=NlP?=;8m zYJ!=uKwJ84gGc(9_LmJojEKrVs3ry-d5|vQ<44!QsbPnT>D%Y_ zCl!L2bkw|DbgtR!ImYzmk2U{5*Sp(-_EbvQhK*=}zHvs$P>X%{?9SikX}dYGK%ifM zLz18Cs4BPHi~>SMI_K3!1*z?-`XwI$wdQX7WRD~psOR8`$k(J{PQ@&O<;@rU)AGYK z>J=d96_^fyUyp>Rn5}8{Jsk!cYYY^*ytJ+#!?9wci5^J?PQrs#ONWEkqnX8Fw>6{@&=saRFOkc5XIPSpIyc>RRNI)+rg)c23W+Af@Jvttv3kp<( zp61ly82`R2c5gsG)Fbg9XwWqA1e3KzJoxH9Fa29OV|}Yqv06=}3(mU8k3F(!y;&K) zhLxREFZE8X>Yx+qA!B$BwcC)l@VDLdN583pXqfpt#_eB%Q@TsmZMVctYiBexmURPl z{4j!E*gUac3?5`W&n=R%69f(bkWm#Di)ZyI+Q~tb2)FyDn zbDUP#Dt*-$xCywygM_C?XC;*Vpq79yL@ZNUr^KLk+CZ5PIwmP2Lc%EahWu&!Xe6on zRek|o-nZE(1QA}~^c}p2#z*S?q~00{HDmFLaPse!?bAnV?sLAryk9^=0#IM1*diW# z_CN$i(pj1UWk$__BJ&TlROqmq@l5H%y$Oqd zAd7J&?zh%lU$wXm#XaQECKtLUM`0tVZmD`MjSlJmBk5fHnf(9%f6XvSmZBz`k;{e9CA_HZV{pQ%K4@B1fImLIME9#r-9|0ad`%uKN5o(7&7 z*&3n+$qWh9FAn_d>gXBIfxRO#zz9ID*HGl~XJ&O-E)!3+c*e8j+~2Qa zb``+sr_MOMHkT6}$ZA21U_U8Df8;$;{Zs2bPJ6f{7vF0!l=zfC(Hz{Whv=}a6DQa(f zM{s-ew)$n2D_EWa{%dWY`+f+u07nS;rF7TZXY9Imw99z~Qe!;Tu16ZOY}}-B%_$#P zbC2-X-;o&`aM(2;a_f?gd5u&o6E?x7+Ra~IS=3Vs`Mj|pZ`h1jUJs{B zlQ^(<6;&R=?%Hz6Kg+^QN1BF?`uSeFs+SgmBok2BQcCg~f<>M~U;H+*62Vl9tVvm{ zD2El=|J&iwVRlFlaZ*1;kJIn`AK>w0D$;a%z>$oPY{?(cqC|b2iLIn=t9}};ol9jx z`}n+TJGB`-$Eb$Ki9EKSzd24nWZo5<_%l#;I_B{=ZJ2!Xhg145$>oovk&>F=klP7q z$0C=DSW4KS!aA_}n>XLMs$*+2lwXEetJ@neXhucZr8a*OIbWGn{EFqrz&}|Gj@)Bo4d4e=8nx@%hNxv67HZ?qJO?VTF1N#eNFqc z2P)P7*sF7?EMlGf&5dGcQ$3HeI*0n4*0X>q%Qg0VOcUH*j|zZkUpF$x->S-repZ&h zqf}xn^~G*?&_$Ch^cv#^m6_B~#9TTdFc%SXOgkA&i>wi5qg<59Y_wITv@7XZJz^?E zDJn`kN=>ZycmY@o-Pg;Z#TmrtfAqUwC4Ej?dtAeDd zq6I{I;IBxl^UUUARMliesGI8A*%KAUoBR5>br0M;9SQx^eno4nqkoRR6IspeLQ>_5mz$JDM*RmsclbGwaq=x&%J`Hy_Cr}Fk6;9r`zfm0B z^X3`NA>07W`sOPZIJ2m=*V*5?9ZDCo(PN{>>@arZV&gFf-H2WrkT_TW)`dZ^i^|6E zFf3Mu3I4vs3A`Z4sBYUE5SuQdEmFOc)64sJar?M7EsSv*)ylp8{}TP)Jfts&lK!@9 zGu#%Bkk~7VV|wdq;LTtx?DQYbi^fF=ffL33i9kXFo5mN2Xk;Kb&dD1;xU`meXO zXsflZ`2>}d^f0wHAT5(kwfe}=nr=yxT+16xlN)u!-RPlIJFWgQHT>}`6a{bm~NueN`V1Vc0_|5R29 zn~5KwDcu|X^x#~)2r-_C(z59HNgOa9m}lZ)OLS4zO=Zl6XdtymkVII}V?rmnsa%`Z zky8Ep+gPpjZXdU7CAk2sCIrptCMhZbIUC|&W=S?VDP0)#Jur975dBKaIqB{O+@UvT zFoGQ67~v%Pt6sL=@7Zb-;GBA?=m#SRHp;bY>EF`(>zG-9wKF1LMWD{`L(i|X%bTxqh7=AKweqvhIx!}Q7XopX!R#^S)6 z(Zdzz4{If~GW`tfKR+P*!Mw+xeASE)Pt&LllmKkn8N%R`Q>s;cbK`!BsK0(pDsB%- zQnU*WN;0?Aj??9cseLmJe=pYYh_O9_NfK=L+9mhJdgEl^*d^c4Mi0s`{P(jD8IN!V zH5*jWqUH92`c8{%@6#gw_M>?ju#Hs#Ld)l+S`pVRW~d9RCA!ruqY>L5n!Pr7!=cy@ z)VUt{^N#hh9hzFL=^oqXwVC@Dtl8t@ z#B!&}g%5|UW;+omP}ytyf>_})iKG$N!aZVWwr!Fj0E88u`|5vTCa%>v!m-m#1j-S# zjQ=L>&j|or6C`ZP*gfd(G;tjojWXKeQ0_E{!i)U}z+V}}B%EgW8@URJb?9rZ@+c!; z^=*a4&Xf?zIk~g!BAbO0wrK~r*g?bhv z!A4HVfsro+gy5^1L!X*9ObI#xR=()ltIEmRN@`l5V%b0tH+D*O^rUIfFd2-njpi!F z;>30VSVWekT|L2+5UMByY7hnz;;Jo$c)JFN=-b?l_) zBY{!`9(b8JWT&SeRUbZVhPmPUx78|4K22~lZm&o~x-V5ft@~jRqB&e0|EYpxlxxL* zt2UxH=WxTLL-Oh?+hqZB?D>+x<@>?2yCdt=g~AvPj7|2E%9=$05s+tG%5}48tMyerpYq1HQa(Vg4*M-5){7|Q>&!G+j?ekx?ox7f zlzHfl7xjd#N-#@eLH#oAd%4$(z3TpfS9cxEe8ym~g5Lc8t@x0tm-tQJS>`|B(cecF z)P<(oO6HDr6vHRD{=69Zp^$g`wwxNWc2?)=Y`B-hA5^bC*k-jho9R;cfoJA(Qiy$&O)ZPzQjaHt7(L49d#+*!-X$z8%MrPishgk5T zn>VxO{;go?Q-(kBR+v}XBI1TK9)6i#8$`|5%mZyLga0iSHH-@zWEg`x%xjRg5SZ(} z(i{&tnr^pfuhIr5k9S$4%rLU$CoEIvsoW#?h~?B&iU@Jvw6;%+nN$1SVRAZ>wK}Ke z=se9D%A%dg90EI~29f;E@I89?Oty24m*jAFBDuVE13wFfFSD^VZ*FHbq*?C2mF?_2 z*i&2&a9)Lj4YCJ>Of2fcC#ZNnV?abogXp=Cdm#e=vwk9#Fotn=VJ+J zHSpR5B)GCCoc$V{B4#KN(%I8pTKRha?8E~Xqu~!p-XAmvDbgJ11XvwwKtDu&Wu`SQ zpp*F^OB6dCFQSN3K)dcp2j~WYwTVFk7tbGg;^%T*cft{JzDp8zvh)&AM3#U@gY5fE zWmvqdkJJq4Q9Cx6Hfk6<8&!JROn!WkON~}lKo+D7a@lE`lP^9os4OsS6?4DEF&bjUC;Z>NIsIueJ%Sj_E2v;ZJkI7C~r z?8GR==8XP+4ryByVAxc55j~4bH65$aNoY~g#6^EOP@MvTY9t64BsI|b1UKVU%-Zk^ z(HcK1(SNzr#(^|HKo)99Z7k~%deNc1t4)3wJ~odNle-zLc!@|Ro>hU8`K?TMukYoG zMwd2rl*q(>wzOaCMu=z6D^MKS1;tAchz-^4pcv2O2v1uQ5e)j}45PGg=Uavom`74K zq8;mMTm3BVrt0+ME++xWA5yZ0aG(IsY;5gA6-}RqgfKe4o(>83fIo#d8;irbkW!rv z{Sk+#m=lz&R$h|<^bUch0fa-r`t$^Yt2tVOuT;=>gMl^lv8aett|c{f0i-Z<`twB| z)sOq@z506_>b_yZO(omfsVcsRab?fgu~Ho8oazynBJFaeJF+OODt>rW`3Kwz@DwJH z*W}X$ntT-Ab@4d4wa z>~C6R_{ExLRhXU=MkJaJ_x>R~#8{D?sU9rn=b^O&qHF#~H9Pz(Wo~NZE<+tLs-%Hd ztF#>=PP|ytKdi%YbygJ&3})UJI!N9dZl7{ci4LXIaik#|?u7Ecl@Q&Nf9V7)G3jg$ ztL#P^6AflKF|vLFLekChA>exadIF$2K!-Mm3hFwo%$Q2=^i~mI&znZeZePq$v?=|@^S0xMHA;WmEh9l9bz zNjCRnu~=@sWk(a?!Jh|MW_S9YBC+T%;b5v9cwFTBdOGYUW-QED1u0=0x{>aC{d>sD z3cpB=4Z8>@8Tn=TUOvVy>iOoOWx2vp}pzdh+H^2XIsipt=p_*GZVM?eQaN`QU} zkdTL3MNm%G;>_U$}4DAE24Q0R$d7Ehj&v_54?1C zYmZFL$H0*$BExijE52mrr{Rj4rVZNaPQ4O9>@n)CnWtE?5i>YZnXnEW!L`nHTP^ZC zz<7KoowS_Zi4VN+;MjSTw7N!Kr^AM=Q1OO;kt_oU5`6WV&7(}rCo`gRhHk#Ro?p}s z{@tu#q(*z^$d2Mb9D+XEs7;2%QhSngBmck?pu!;nk<({AGL<71dx>0|@q;JGs)!Z9 zIc}fxF)S@|y%XO{i|S*p!>?SHB>3wzh{~c&@{t;@EkfH`g93HUgCRdIpzf0-Loq9p zS-RP@C5Y=1ra)4BBAnRQ6Tc4c&Ugsz@)Uq21+RS}BtXLuc_{g;8m}XqT`ZueOpDpk zSj4WRXxmnfD#{;QZj|+gVUodOBOtiKmX-nk2m%;1SEeNMr?Fn4QF=^iPrdE#7-Er=;PrOM>r@`0^hIclRI-bRDeOm zwrZ2ryX7G^efuJynf*18;uy>|fk_;kn@1OOmZa~FyzP=Ksy>ChyJ6Y74MU_25+=UgEol4?X}`IR!MiR?G$Gm{;H6S&0&dbd4O^BdCQctGupo zkXR`>3y6wZA_GCB6j1C4IfH`?4sDB^@;8?w3b4!edo3LLqX31q@=2*^x}tTXs{vEKaHH z7AT82B|^&zVO4X_IL0Y-(OAaa>qR}?DS@=*>KxT=v5p>!Y1$f&Exi}uWGbcouS`Ky zB6oNh%fh>nCVLE^$=Qt=A2W1(}fyA5%oL-5Zy7&2z_wWdbvh#z2 zMch73@HK+Y;;#Qq!yJ7C?OOoB0#*7kU^s)D2`jsfRSgl+Rdt0h&(`yP0&)RR_iC6# z5npK_z9+}RkOm&di=X`vER>rbw37vjf98reKCjN;c6Tj!F?4&%(C(NYvQL+k#;KLY0$P}(f@;=+|e~7DUz8c+l@#GjKA6pC=3$8Xk zslQm?blOo~i{=S#(VHFj=bGxfccYq2Cd^Hm_kda$CAF|AGp}G?+wxFAczk!dXBy=T z+!VedoloCUoB`vFyLGSq!dsEI2ya!6%C$q0ey|EOsP2t@1XZrKa&8q~V~q1RqEvuR zKpw2Z;Cz(j^s~9k>>S>? z#Fy5dcmPKzVTqs~L*G_t$t8lFdtKjtALGUYJ^s99x^c7?*;oEc_@;fyO>OOPPcTp> z*?}03%twLodEI5Of*ixOuxONsWaea_$CUCm%;0g$E4gQTC;_Xrv9{^30gVJr!$zMF+p2WmdW=10+z*I=bW>>W!Db!IDyN)5 z7afnB-gpWL<@WV-XH&@iN8IHx@^Kj$z(QL$wtjwoCdtU57Fa!!8ap#s2pmrB)$k$3 zXtX#cPMGHBO~de5tg-k%2Z@=ycpg~){OMX-i$gq316E{ghl8*Z9DX^Hm*e}R9siAE z0MZmN?kwQ8FQpqVbz+X|ZxW_dV>mf_QjtS}IYYKkXKn4Ku&FO>^(kX<6Pg;NCg*h* zIXXSTY?n_?U>a{`TMKW{I?xn67Qg}12GcpQHfv$^9HaD4>RZ3qcTU_#5x3d%7N45K z6z;7s*To%=e;TBSMpb}!#`qHm)Vm!0>{Z%wFfxEyPJg0z#1k2V$ChYIvxO;dccQ-* z3t_%Rei^mnB!Fg zhyvl|$kaKQcbJx#U0jixFB z^7=t^h}mBg#Pu3XhfWXIM!|#gDy-9F-62HHd~h>uh2Nxy?|A^iym%EM?T4rU+A=w) zXg^J{BW!nZaSs(ytoN;Q7iGm?RngCVXtVmLk;r3|HK-%2qa;sl$#Xy=rW*|7g#9apUwLtfbE`e&l$Zx~VBdUvu9Yb?iF~pR($J~=GCTOzISdU{aB4GHf0tbj0fozb^m_2Ompdhl{Aw^;>JEEDjI zwYsh96v}VbqOOLPtokY{UwmAPUXUN^J*%|sIbs+t5ln}HQQuB`7!)Z^^_sA(UtMD- zg*Hdq8eP9HnNHeESC(zr{2$R`Yb6+>=*A9C&?hQrNFg|TAgw~R6Jzk%Lo(eHklcwM z?dk#oJMb7fj~pwHhs|_9#rOz`ZHK-h1ylZ<0?;@Z${z;Zyq)zWvc|n;bCu1tS1U7v z-mMmT(IRI91S#dQK^?U&TR3P1rJAqIfsy62)y~dPwEDPQzBJ41V4f^;6}=q}B+At| zG#exdv15}5&wB8iECQc|DktzeH@LWI3wOQ29s^KiBK1hlo3;<`11^I4jbbclNe@p(`+(u0vSB%pJ^-5Sx2bKfd#Xly8xcSW@WAzHr?XK`V|T%Z z+gd_kvk4YcBx-Y9d($(Pd-Sh{GYc~!!P|3s^FHVF%O_6E8dd%f5_5%+mj^*4Q4lqv4;B<8D3?Qw z6=z+9-3j1W%wO)-@Nh(YHJ>gNYJVv=8sz)K&VD)2Vhj7p;Mxj@DL(aVL+r0!e*o&) zN*VbcK@(A`a!SVoQ)xmqgX<0%F|{pNtv=AmbPt{q?WBZ2HLMmo8@#yN{snXkX?0U1 z5B6bDn%};v280KpbBq$ZNhi($>FjLAy%m|xnG}mYTkXt^_efBZGjX-#&^$1K4`#`8 z1pgeos&HYyF7MMHZdY_xamfNjF1s(WaQVbv0OkY`$VrnchL_hLW?U?EJ#dS!1jHnJ zuM?FhiuetV*+8@NDMGb-xgx=>y|Mb`%0*DhvY0pq+TyYBdR_bqR^ojhh6 z0j^7l-uckdNBXGOpVoKKWptGKOzQGvnwmaZJs>BZCd%(HAT}LQAJ1$E7>Wzewd0rS zEMTuf&5R==M=|u1!*KHagLASdx zp({*R8lgNdQ|rBPMjXr6hn&Xih2!H$r&i9TwHU}eR!?s4-ID4w3>K&#JBQW;aiV79 zrzm52((_)*4a^uPbX$=@uV7Q+ zQi`-MA%1CmjgR0uI*7B>JVkQ77Y46#$*J7u8ILe>yz%5V0Z9rB-&XKfN-AfJkD0j~ncG;xL5+r+ zjWaHNTDp7{t$FqdBfciQ?47Zi#E-b2lV*oEX#0xw=l1j+@y8ikgU26pM=#taHoDWt zS6893%@Oiy7m^nSEe>*;wWU1>*r>-gV_@u}1D3ZLoen&>Y?VR;W4qyt z1BK*WmyO*1wpH7a19PpNRQk<+6r?XKzGWV`kfRWP7a2|$3^>J3ABAx+9 ziHA8r>X3iH}n{C5~KT3?1AX{E4W%b49N$(^RWjTN?_#&a&uf zCkF0$G@_ODO>hJvnuoNdB+{u-`v%%(IHg{bEViW+D_J{ z(?vVQ2b<>~JrIq)0jB4U@5s~^4KxunKat;cql*@x{|5H{x^{a+rK(-3zo%+)6C!xs zJ>^dmjD2Ic7+7NQnxOM(=+?FOi2F{^96eNp%L>f-@M(Aj_!S2AVlSL_(35+ioU=1@ z`#qxSeBP%sFr{{8Ta7S>47FQ-V|83P)M$4*Ai^9vB`=+U9Aohv}Qh2)F`3RxJSf%nDXbQKvVtozXYZ4ha%1h-sc!D|EUqY zPFg>!oV)PaJb=0F^0ZcVBPBtmpZlbIQ8MQZ{k8S8O#(Uk^v3LtDw+UKkiWKtV^S%B zIf1MHMAg|Sn)6ThdHpq!wy!#)&2x(uHOf}c+J32BcZhz|a+H8jMvR}++H`UAka4f# zCIG1nS+KF;ZR-2u+)|}S8?vLzC-rww>M;$ZT*OrIebIxYcM<;IU37}(m&OCMo0Xc-{Hr*NiF zkz4M>j(L2<&2NVm)eNK6f9+-MSHF-t%><(kF$q!a;(;ILUQ5+3lsy!<$9}mL`Lh>Q zWC;8LGs5DlUP?coQFaSi--x4JvmECX*<2Z}&^`qh4#>!~*UmGg;%hqFMBIxn8;6SO z$9#@q8U3p8^nX3^U8e);?hDqNoDMq2dG;1P7i`LDj}&AfV9L~Ip=hgr+aV7iyM+Dp zScD2BVdMjnmwHKP`uoX)P=(;vsbjl#eY6wj!RBJ;u*QdGUJ#F!G#}U!CHH8CI_RUG((W zvyA>Y3w1`lfw=>9If<*Ke^FoMs`)1`$x+om^x!OrZehI z&3)#R*dC8qy{RZ{3p&B?4~~mYtCThy!p(y*bK?w=SNAeCl^90d{T>_lJ?0w7{_t^; zfTsZlLkE!uA;D!h411<2h?s_OrinBg!|^%4UWCavxuSjwjv7s&VDcb$B~h&SKq>1_ z;@Q5wjo%~Lr%DH30^i|Sm{JM!ce!Z>u3&sl&L2Dn1=Pco$g#QUkPc1Fh?}G{g!J-( z(z6653fSex^16J67Xv0&sQncu^8@bdro!@gns^ruKbU-0!qzoT=eSBWcv*O^H$DA+Sh z#jvXkdJp~V|JQe*;ZM&G`&Tx1Z%k{=;12Z-Ja~5N^KbMwBfvGfJ3S(5rhyLIr;ZD?#ExyCmh z|7IW%$Yq>#VOCQ>!@g+*^qA%ucMx8~vp2=dRF4lb3<7jI@VKqXe z19x_%GLJwisa^3&0A-~4>f?~?q&HDv#%Ic9y1i@=A8tET>FRBiYgJP@mnxY0gJHhu z?VI4HH_Yd-91bjAfQc|WDZRPqzpbr7zRd=5ow&EDI8(CKy~dych(s(GDu z{lv%5r-)%m>`B?J#JVnLZ3EK=X~nbh1)fAKcTqHbBTDu?%3|vqhtHr({Jdk~*L(iK ziLPK{7`-mY37m#>}Q@`4=QG8?rRDWilCvv8M9oVvbfCpMX(GN zYrc@9O4stVM*1pE)^m)>xi}cssZvOLS32Fuj~W6$iz4jq>GQnvjr+b1$J4FZpk9mJ?R3ib;*V|YGL%0 z=)hKCcXAHrD~_X}mYV|qO8rU!uX4}FhhlbX{zP&R=(1kmzm;e!xr+qSIg@&9BsIpW zxcW()Qe^sQZu$=LP}k?P;$LXQG+yV@o9`$K{*c8sw&Dt;Xy4i7hczq-$_UN5iDqZD z@K6EhGUHfK4(_9n8Yt_n{&xdk4p?|qqx*8GKCb&=i+47Dvlg_``zxAEhfk{ zZ7G$p%CvUcN>sg50a?pZC+6t02N#;XGkOkwHcvUZ5uAD~JcwC`*K78^FnaPBv>5q; z5KH+I#0tdi#k5&vbxgGIH)1*q&mW>c{%7xDw5E+&GlT_Sc-?LC{@4?CF;otFweO?n zL6iOO1#fffe&LX*J4joR`y@;M%mqP~@EpqJE;{6$4z=)LHLh2(i7d{K=u;JsfEZw4lfrI!ojGgLqBe=3+_O z`JCIR2Rgaa2F?z{Cf@z_-Fs?xyMwN)Uo#itLA89xql1}F7xva#qFjc=foc(&z0urs zhy-XrR;vD;dD-tA{v1hN50qDPosC9?g)hGn@>S~))uNdH^;gf)Pa9%#5Dm#+$lr#v|%JM%Y-Pjin$tjYjt-dqu9)fEvKE3-ToJjfgp~zxzwc$nd zbvPYVdvLqo9Z@Uc6I$v~A|C5`V^?L&)k+Ra*H1y_le(&Ne!Srwx!#jpDJm}9Q)_{e1Iat^;4Zo4z_I=z>EdbX%l8uoj4=M#<IIRXyeq_q>5Z=JN~sXsL(gv6o)^ES;RV5r^M} z+y|rcHk=)<+z-}yJ7yI0Uhg=9=F3h4r;;TVko>*8fySevdZjn--kI^=L$)IYGbIZTU<&O`m9`^GN2^s-#mwU_Q^J@3jY$&Yf9mS(aL6OPL{ zrhEc-!{xJxhNwwn)ny_BTTY}HGnbaJZq`!x3AjVXEM!&;832BbABXFP9yrPv&R`aL z-RXG|_Wg0Dhf&Q>-Ob_VRaX^+QT+D1Z;45HwFJ-f`k6ugYiPgEtCNlj4WHlha9Y*m zRpXw*dk?1%VAzn6)8n49o1DV1yAM8|6Fxp(L8eJ8n6S%vJE3Lf$=2$-jRHTMpdqRF z`w=dN|Gqr+ixjvd^+7=c#XS~hP)x=%v|!XZPW5`PSj@d=lDld5QL$i`r+39f{!(rb z>x|Od+oGr6=4MVcRr?rHe)Zv{y@dIS{$_!f#bfb503E8IIzCtl?@lA;JVStq0Qayn z&ot(X_VfjhU?ID=jSGW~cRfq9$JpA?X5sFk$_qSK?M#b8HPI%Y_b~^nyIedMe%?Qn zI3R=~F9AAazb*PI%2?cC{i15F*;M20d|A^Fbw7@mtx>kV%SRobDi1|rpW1Ie2@LtT zFLD<%b?cJTR_#$TJSPFF$czQol~hIN7l}`+&`YaAm*4sS`H?fl}~sQe~ku=|V3OjrRQSIx^ZTSg$orpI-C5zezkxA2H41}S_W`vzko70AqeRygg z%KYP%#N*GD<~=bS>_Ztl%_CZ@Q7Ge`HdgQOyHF>~%B_@;P% zN%5s6qib!Ut4(eTxsc`&8$ae!o)1j!aQy3^H21{ z&a|x7muZ+$PS}rK`WE?nAe=-5!<2m=!=r}Gd=Chl(p8ev$b{WbEIE4Yffq*&XfFiS zQXkM6MR!(nNV;J=H^J5y&wKym{+V|mFC>r2wMP@zZl1A3qv!g@$rUjLVYkvfGNJ2< zW8HPvV{QjsHiAv7HaCv7ryDWvb(l}MV(P}~&c0M`9{unpapypFW1N5fmX(bALA1`5 z3)`WqWhF+M=TZe17m>+JW>gXl%Bw%0@zJL%bKAbvtuv+n zS=71u#9AhmZf_7%BFi2;Tw1qCn9>cqSRpA}0E7B<;Vn9mo8WiNCyC6CfL(5B!9Clv zta0#5=P62+@L*uyP1qcdM}3jTn8TJ1G)uHIKuJ1Dj8pQ{2It4j5O_Sa9J|x5BL03O zR4H~662HDzeJoVzr=VrM9YuoFb2eRu{{v*t#x!WXHyax#@UnVkw*A$|t_ClyJWSf2 z#}*io?g>>FEy%v@ytp`{u>Q8lnx^r`w;A@nw3?f`?!qmL)65b1H@{O*p@3cuIWraL z_RL7tAX;V0Vl?cH^Z659XbmOfhk~EcPX)%#X=9W3S@G|O^JJ$ZUx7SD^hf6Z%pa7* zJlQ$iD!-U=*>X-&j7`$dZFqwhsz}d%lN(aA3I7jpL6pvrU_CuD4MFGLytRw^0qJ~u z`QAKuNKA`?pW3HW=2!XSUdgU;0@(p>a|OWgXPR8n?>gjYIRp$^7ALKs$8AM!L5&ko zUi!BzR;BYl0%z_pjjv-%3Ib_>4Py1QM*C=rnoiIEQF4cy!8jqmU_9#g;7?4hb&_YD zE$ps0aIt1QoG(2Z2vSccF{}JSHc3UOR#h1q@ATO}l=t)M3&nB+$@rvqLgSt!eW?+W zY;Uk3e3@Txqy$v~Ucr?Tf15G8ioqP6o-%L1n%IZ>Fc3>-c>>#We@aki_iCH6_*}aZ zNztLj!G2q46=$L|rf96`wEscc16M&&4KE473J6|qR;9=H&=#NHfk9}B*W;Is6O`Mc zUH5veHwc(T(zFC6zc~o1+?$c)mJS%h8#f)KF1WAFbaFR)lUp|)?3(8$!P+0NC#G!{ zx}Z2Y8B6Xmyex2A)dkq|1#C|A;31Beq-PPVyQvhW2Lif%;^IOaZ)^|sHkY^H3WsT z1z>fpV7*$gq^^!{OFfv?w^@9BqsjS*Q+4-9ZZs%ue~VK8y;oJzXw$&@W>_^E#4=TYOlU&At+WWc zVue{fW@jPWFpxeYr}7`Qw87twaMGB(cj@h`#jK)?$#1Dyp^y zQJ&KLTS;b+i7HkM2okET4(B2v2|9qXFMnY-z9=zAovpk%`p`W<&5rpcCWYo zUIfrWw(5EcWtHdHy&gnnxHF`j6$D+J!R_%d1IAae5u1+ZU7kABD+yvWtkTClU*RRi zc)Sfqx9HO?9pMq~d_gfJer_Sg*xM6IP{KqZRyPNr$=#d^ zgZ1CzV5iU_WeO58xmLg(cTve6TB7ScwA;9dD!|`Ss)Y2zmy^i*drOphh9cl^v6^oR z_L{PaxAH-|^j84$=26Q31U|XT-37!!5wmbMC8iTwDt0OCm9`j{9Qg)DPYXi9v-Y5y$(HjnmyzR+!S`U{%^rOyUdox z_v7+)`0Qdxab7^1ZuwYL9TQu6ufq+7U~uyO10)>749-X~48ci4>;>{3di9TB^2!?6 zbAQRwfGiKL`R%dxVOEzb7`GT;jd2ep!%c5M?$vBWiG1&Dn5RM%vVw(vlXC%VjU^KN0>oqt>2N%O}5;} zBepb$5w`yoe72XE!)!P%R!TCHQq6!V&4^X>xHC!r6y_Xs(((*+I(wIV#@!n`a|RNd z5xo{#v3)(z^^1lvLF4bhH%-O9y}Y`*w*PC?Ezv#lsk41ff00?}vMi zZERNvT4mnl;-n`Zsz|;ODmHjztWo~A;sdDiXaqFtINeppUW7iv8(shUVJei*z0^5r z*1;+s!d(;a=(|E%9@5#Ut9mo@>+UY*h0_83Ehi&?$r<^`)VpnQ%JBarAJj-VK2+vF z=E&Ezy-H%Qk?Bz^Nl~MDbdFb%dj%g={qSw0h};*Z+nEg592g zAn*PJUiP02p1oS6`B z9E5g^w#&T^@NNrVfuC>`RYGC)J;@=ZHJ@A@Ug?+WXry$zGi!Lr1Yt6Z-BVs#H?Ws^ zNcOtf?hNYsBcwZo>-xQ#Jp0PX)aWv81yc`FfeWSYugyz1S(R^(h{}lS2aM8p99{MB zRa>sl*h`0f>!$luUL6lNiTC7F#r_SGQKLsZ4IKszFlm?GP zY&oB9>g_Q^AJ$foD6Q%Et0x=|z4W{w=yxqOMmZK+a^-S{g`vns=p3=XOZ53L?bQ#nkns;W*hG|fWm=V} zQ-P_Gtiw~ri`>Z41Hy?Q$=u?E zS%DT=_Xv%IBfe#pu|wAoRr zevks^7wCRT{V|O9qwAPero++PgD6uJ@ zn+yW=HAmRWbvM7b6ZrHoNj(OC+I(q~UnH!YQ2#%}(G{AFLrQdwEL|*#P5IMuV=2xC zU3lu%uL1J~HW%!XE|3%zyMe&1=$|3}fe$1}bEar`^O zByAC=IW|*MZe3hDn#+tjxh3S%Rl-OLZSE#BgwonvyD}X2E~0Xa7_zw(LMNHa7}j#X z-<{w0_pisp?d$9Fd0$?y*E5i}lr6c}PAxEEW%N-jT5n*3k63I*w%|HU`9Xy;V!Xf> z)Uq-tUjp2*H)c<#3m-LYNoa89n%^_3MNG5lbH+NvC$ip9!0kD;D^D1`J!9xWQ(Ao& zrnU~T;$qfB1R-5nqYb%djd1)cdyHbQ!})hWk3qp)0nC0#Q{GY&`jgV7C8fl-4SQlz zlPht?4*vZw;d_IT%h^z=U5mQ8IIh1>;Cq-c9AA9VC(6O%&dB-h=e7!`Lkz&$<(Sf* zXhvYx+gsW>j*3c@4eB+~mt0josOQJTo$$j%#WKK@NFZ3nzmpIT%CFaBjS|{tDBisO z=q**{tFhBd#kzV)rXXbD1VqYJ5S_fdg0Zu4q&1+xly+jGx$JtFe>GCLTzHrFzVSaG zgKR1`&*n3RmTF^Zl4cW`3)@2^!w8S(mRy@{3$P2y-d7&-)-0>=?LyvBwzH@B-R!ER z*`-2~t^8eXsj)ybZEidCN|X%x800mx(u5*j{z*4C0Od)FToavLm~RjQIn7P8@l6Sxg~aHF@_>*_OwfzWa235>&-Ff zkGi*mvGx{6I6y>`XUi^Iv}Xid#ZA!ms$mO2_uu`8Uv6pJ0voZ<15^%~xJ;`VZ;}&T z0X2*^TNMTTKl=T}y%*0y4NG9kOL=>r?uf9cOl^o zpfUcWU|=NDV0kA^8Rd@-_v*AG&sv6*A!P>KVnvh7Ib2ZI=Wm52SOX-P&D7KyHMN|L z9titFtBdzIwB9<@BUcS(OtysT2x42aCGTnG#(to}3JBJu&7m8TM5IYwR$H2u@zvap z(+YSvtX$g{>8%z5Q=y`Z#7@V#$mx71Ghp3Mb=ovH1zp`@3dUszcp@Hbj^D%7qQQqh z>M$E=`%!l@0ayh=^R|k|r5WUAwhVo0BzGx*DC~Z z;2LqnRO(`=wE1_mcn=!unT#r zWek91kcWe+Q5q;&>U+Ogk5lJ#wFD z%qfg*S0>1WW~WHWp|jy|!vDb!RF5j;AQ$rp=b3`Q@(N((0BT>{GIT-kM#`XROdXFW za{_x372xt*I;3S591ibZgj)<3fua`l{b@VFNqKbZe^Fd#P-G9ZB)YX zL)6x&F{vfG`T!{}sPLG966q~yAjHGr8pDTokuy+mvwo8pFo^e9B(rLIC-UV%9fkpv zdFR%X9%Hv)G@^3E;%khPw*j)##(O61Ir`Jt018V%?&*6^d<3yl3LN!6g;Lwdh-10}f? z&CbDbw6&$=0Rf1zbX(<9dMrEiL~$!(tm1opVY95C)91J7Fv1fv)7_6@@n8ta2nfTIVmh-!PZvL9yRlRA86XF4;l}j&T==^ta6Mo1lx}c2Nk0~ObWA_x-)>? zi%C#Y+y3E96n@Gi?HL;yMj?^T4;@3<`SdK8|* z551?^ni)gsQ5!|=Q@nf9gDZ^s1j^}j2}!+%jd?b-=|NJ zVR?-))j~DQg92Z(C&43EVP)$SX%MsI=~$&4dh%KmIAaA==963kS=+8PVNK?e=jwgd)L9^0+s z*da*n0Ap6vA&CZKfJrX6l@Wz3kbXi5S6qtFrC~-1g-iMD7HGCH1Z*dMf~gUqngU~b z;10#{$!+tqa?V%lqfT3O&Ie|~__hX;xr8N207M7$+b&pWtrxf)6tw|lma zY=bd41T?PBPEXqcGB0DyP>`;SB`|lCCa>SL=nmjPx`U=I)%kY->1tAhV`ADxUxrfv z1ye}Xumq+$m199S+@9+i`)(qovi)0|h_T#5Q9m*HCy^L+RU)tqog2+_;3;-_tzCeY z;OjXr7T%)gdqdGx;1%-qQKgI#BBxMzC|roKcG;6lM}V7idppoJ!!Z=l!I>o>wg3Ot z-F3%PBXFwUCx{~GAU_8kKfo0C183}oq_eV%#~Ow!{||+E3%friK^z-hkwaFC#_ZHytM&hS^F-cZIO!L77NqE%CXJ4J656rmij~ zcGc3XRS`Vl5ZyFYK0mX53IzE)cN3*@W^l9M<>=XJ|CM&xOz@8JT`A^kbPrOQ2G>ah zPK5?@l@q{p$hqZg;VW{@2Gzx>0n4kLsa)qoIqM1i zKOkNsk0HJMJL)HQecE9<*zxfpbJ#7Lq`zM{!Jk4?SuBw5rmOo2F}OiV7M-QbUF@NU zf@kjy?ATizST7(bly{XjEJMGBjSaHZl=$DWtJU~L-eiA%|HGP_E=5ROE5^a+y> zWB|^;x4^}=)7-_(pS^s(XWd!LxA{$Ii=_6|6j01~b*?GA!YxX!%04@w%}_8`&{-aA zbxAq&V}Ut<{UJ)^&jh{r5uiRd@kUBbSdnajZ_M~HZt>{!{W}K$$hdH4qwV?jImYnL zp^Ni%SNH1A&WuE(qS&_=+PTJONQFkZx(5U)p)9T5cE*wGjd$~vM-*xGGcLN?#*y8+ zu%5phE@YfVIUH{p`zJX%DI$YJj-GD5Y1^vMAtiRGJ-~2gk{*R|-}>uOI>W_Q!Q#j> z<0Kv07KuW2ULl!;;O<9TT%H=nK|%Rn%nv9b zG}Ahf^s>cts0c8JjY}h3Ha5VIoJqfwS_74?jgl3r1PR~Z)E79Wo7uGR##9J^@X+tJ?fs+dD|(NGT7#Y->C^lb3j^ z^Mlq)M%{RgH>M-@)Xj>kQ-adntv248Axn6}ReX)(=WqY`-am#z5*mko{-3LrMt^hw zPjx+cd$Eux3_ud`|DaVnCJa;4AHb)l=uG8!*+P*sodyg z!5hc*{XVAD26PJd*jQcLvkG{OS-^wl1XP zdjlA@xLo{t#^Sm3e1~4A;9|CJKvQPDx(p0sXSR0Z19aC#_Yiy4CO_c>jLuhH%MUem zmR|fGs@)%Hr5sc6$)HMaFB0Wu-b|f!xL8?u<=tbF%U!kt|Bs^sA>j6*8MyeKe6*>^ zC?;DGfG`UPkd5!+k1F-rfCnqg8V*SE1i9=Iw?4DXbB#{D8LwkkZ&o>P!CW&!Mhmq* zNjZH!xA2jLQ(Ri=bpHxmWFSXPv5N}2QDOUIB9aUROU0^yMd`7%pVnL3wp&Xr4a>?y z>6Ejd9VfhB`2i?7Nkj71%X?2u?!Kyq|LRRAG@6G^PBS?%p6-pQr~P&QjLm>BGZQKc zOwtYRJu@!9@slQnl``*w>up`$s<-ZWVe)sJ8DMVV!XhVUi8e0WmLE*f`_pYR67;In z%gZ?rRz8f^IBa^y9GWXbJzb7FE7X1c;(V;Pj{v(_FSs!38P=D9b6=E!EGWY&+dI2+ zER#I_+9(WdBlI8v(fwMgeEDK`>#h`2_t?Rx?6=-)*Q%Fpn*GXukRlQ&iyASITfxd$QliD=X~!^EE#eBtaqMRCmfAmO^(TBwFqoi)RiM;T5;PcF=jhK@{WNi?B8`n%ty^CEtIdVLfg^YsVEI3>A8KN3aI~*{UFq9LH zWD7*muKq+8M|&){`scki-s($Vs_R{+ZQ7H@I*F|2Az&U=r&9Yao%+oyMbQ59xBk}F zE1=CBH%Z^Q`)c6S;rN{a-q6+f3wx46k3)A~|F%D|91(vVwuC=@t+(>CvZ8qDv&^o4 zWTw6R+8W5KPrcEt#yetRlg)+%y0Kkw@y!dvG}X z>*vK~m*fA;#FbowUpcM=ESh(Zn-BFZuNb^?upvHd>y+7K+75nno_+Uv<*Z)RUh!!T zLAGyOOVeR;_xcx7Hk}Awt{Z>WLj-TWZ4A#@5=SH%xy9lcn`K`^uaNGnSp~&!<{aB6 ziu>#H-F=64>IFrt*1k(9+)VFn#zv+< zwtMZHe%w^pJz`!|mOu7kY*i}q{f`50nwe z7`Faht9Rf(;NE*nzp?PpO79JXuMdBZ*Y+%hD#l_%XXKc4qw{*_pVbuBc)Wf$~;< zD5p(WTfQB$qt>FMgc^_4)ZZ;el83M-d4J7g9#QS~{|*cZz3zICW%jnBx9q}Wofa33 zDLq~#NHJkJw$5K0Q`u9(KWsQ+fsLJA`%!MQ=v|g!KXXv~bCB=q61Pxf7k@sD0}SA% zqPAVj_j+9b^e1*L%BD*@QIQhhRucKJE#^cX2(Cj4`*a%vo~hh-RKDDh$+1C^WB4kSyF;F zdho9yRz~d5OP%WThE|9Cp81k+s-(K_sewAf6r%KZpa@O1e21pp?^r*-j!y_ZQ`yTD_|)WMvgDz1c-eW(Vk3YFeCj zI=T~4^$#YPw}h_mEYJ!72@-PV#g8xSDE|f%w(Z5sTp@_mgXm_fU*SUVp6@PQmRdEU z)m?g#WI9GOJehwp{2yhb&8&}acztwdrF+L}QcK5J!b-5;%Q|EzZWcG2rmebOrq?>fU0>?0!ovg3J#jc=YP z)qbwwsK{`3A2039C8FQ2J49SU)S4XMX`xE4?VfYr@*Azc|3i0e?x*VGe*6oK_cb4r zqc1gnd=0wS)SfozzlR%0Q(?VcCyll~<%=bxw-|L8g8tWEn%DQPJ!v*k&ze?N`}eJ} znX%{83;R?f%N77I<^Lg66w(7-<|?XLt-5py#hDX6`(>o&O);rNlgFfHvJ6)XQ4r6_rpYaQU?i%QlUh z96^rIo_R4Mq1l18!-bw&3oop=-QgwrU& zOL^kjYt$9@Kdnw!i%0C7Ux;^Px{_IauX%m0T@@@E`lo%w_L-pmt5-$OJwqgek7M;D zPG^43Ac}({O2v{3;c|0@X{We=F#`lES9Oj|X#_;e|8dUu<%)oWwlKPnIfmnJ8+{H+k_gG4o^&w8Z4v zC#JwcUFmR#lHZ{>)?yvQIwRp~^k8g%wf?<$X{u*u+n`~{QfGdURALQM&Q!?j0fS%- zZ%Q;O@{rC$d5{KI>YZ7H(9un6@WD}!{{TznOXR0bcfTh8%B@^@3GsTd`aZyt^G)>2 z==?df`RC6Gm5G<=#OznYZZL4u4|QTR*;y^t<-YwQl4mNrMv*=UmgRKPJ~H zki?Wu(x)Nzcv8uzxg@^0^fl9%oMfF5PpaY=Vu%-B=bXv(4o9?w=n7Op(*{uY?dj`+ zYTsS@kDj>*kSNMNR=Gm)C4Hf$?v!BUU^iku#Q z$NXsPlP3`+XV@Ac$=CK!s>pg09o_jB`Ram_TIuQN7hVk#QLz>H$&61iE{NJc4mKzF zCRcnsXK3aP|9ri+IO&rWiY{G>)-p>Wj_OKUVhT%O`PWKWyTeAehb98s5pM$`oQ=F1 zp4Mr@FHw$Hn3Ny-^nQRa^J2^_UDX>5SmO=R^vX33Z=P+B0sX;S#^i>Tm+d-1+Y|fm zoYLK8va|fpZ{u2M42UuPx=LBbW{+m?wWx(%aCpYwaRPvb_lo@kx`L%Gyw;ToVaQK6 zBvMw4x(e(lzV@}@T~U81=~4W_TNT2Aja)dGa;j+48Vnhcq>#@YyiEK88nRy6%Xk;I z&t6mYgKwE%PIv+;{DP>Fi0*1Dg}*&dx+X9P$G(4y@i6_`&@a!Zjl3OTeoOU?M@Ycg z_oU9181`HXgJo7rB}p@jWK}4$w=|Yv6mX z9H#x19WOP$UmDU+jtAzz0-k*>I*gd8Z&~hlUG|C)z^{584+XPnUaE^%=l$iY*``{+4Gwvsbc1*zp7~$* z#vdzxF`Q*-uae7|N2HfgRI&FD+jpt8yT#rU_Xe57E8x__l5|PVnua`it&K82nY`v4 zFrR%aoU3_}{)cD@CUW81gcjQGa>l7e_XaI-Zsq2Fe7ZU&``FiWo;IendQTiGe(pTAMFdKup@HA9J zM97<0z5!jDVGk}lo7qTS8w>hvC_UzO^IM&3;;Afu!;9{3i*&TlxA6g7;|~5d<9^u_ z-`kxRR=EpB`DJ+>G3`n@wn#=oDUR>m7p#zDq7)`RZcFGKzpVc`JUJ#D^Lu__ad>^{ zO@R@w#dzx}DBC0j^8V75n(~n2J(Y3>ezy(*%KsE#~;-W(uRc(8#Rxt!Wb)!N1*k=jfX;gBG?u1nnfK z)B3yh=Cy+pXKy6hp2U30vIBF#D32cJPJDiy{SMkgYJgRihrMY0cT6x-x%yF?3x>G8 zs-OG5S^Pki&9JLOxJnv^6gvDVhIfGdeNblmTkMPyvH{oZ;?}8nIt2#_6Y^-c6)r#6 zr}a8a5N;ZV-ZHkFSV|xZUrflw~5X>HXt0ON0c-Kj`^_nxC z<>a@U@y`yQ%T&6f5;&}a8NXK8bVhb?@NagEieu6)&MGV$Gbn@CESyV()%bKv)V8V3 z{QPmqR)L5jNuHFM1Hr{Z2URXN2$PiB*=>9USD4+M?mBAala|`b#mw_Be7z#l@6^z6 zr$8AMv#~BF?G(1Zn@vhYYV`BSqS*J!nI`F6>_4h+OQ41pa|D*o}m*`!YWU`h9 zuWCkl3$$gLe3zM?IQ`CKcjZ@5z@;Gn?%7Od%X#9p*bp<5tU^Ni87)R4bp|hK1JJUPCcF!17p2tyh zCQsjH9FgDMH{=^{A(3j}AJ&iKwwW%ybwtde(nC+w`sRS4tHB*QT@dE2#&2Us1Ti7; zidg20{2*oBb?Vm-3SUeGfFOD;sKnbsTq&sm0;D)^#z=m$~vk%R+&32i`28)Lccm*ty?%si@S!Q`Iwm#$%l zSlMD-airs;S9I?mCsZFOy^Ai(<9;Ery>qrSe}DedCLQAC%bK1tJDzrX*s z>}2y9b}~`vq~DMM#zlFElbq}8j|rk?Qv~IgjqWSD^WGA-iia-U(9H8jE_2kYP%|Zo zM_t`Hy+@*&L>G;Zkq+&q{{zGRWDHP0X&&`Cb=fK%-y6rL!ZvzpkCvxcA!TID2TQA0 zCNHj-j*cz5_4*q>hSYX9!F+yU0y4mu9$xn+R}uOHFHkOSQPxR<&1Nry#DuX0naN}K z7ON8$#Xeb&a96J7BnQOHi=$?g$m|srs`)F~{QJ>g9v@z8caI;ge!mK;N$On*UYVV9 z$9D8UUB6sJ#r0Ru-UY59+Uiwi9-paBYACgLHM`QOfdkQ&(QLlmqdX#Ksvfbj_vK^h5YM&p9lu#|z zLe>HBCE?r_*xf6@)v2sWUow+L>=orp>O>#hYe;7Mr>`(M*V^Y14k$lKP(kD&zLSt| znAOZIT;IdGCa;Bx*EKu3O7S(0>|yPsd%OGS)XXYh#HztqvCw?eu2*r3(OUIn^^gp= z1^ko$fY%xqP9}`suV^M5`*@xAi8P8YYOOyM;dMk!?TNo$ohqh=tx=IH=qw&L6GJ?fpYour^8Dvh6yI32Ks8 z1lt|~pBlVzd2T>wEi|v>+k)Z`!t{}Ry9I^y;?dz_cBru1D#_!GJL`|az^x9A*;sGB zvmdpk*YmAP*DhRp)#|VZYdBP)`N7)x@0L@m=?7>V5l(wzIrxMT$F`;v*vO>w)15gu z&rCGwN-nCJ%(AAvOd;6aqAqs~)!X*|3!7`c#F34OgyeDk2YrMnx_7?ChiR1%LO!6E z&9#lvj9xHQPS;T>+ezOI=~=gzpqdGCMl)Mr{b}?79~>&R0hERnX7pGJ$MFUeSzHI8 zfZWqh!x~Jk#@{lAusfoxla~IUwSDrW*#Jph?60L0qxy_Y3;(pPt2jXyyfKMR22q<* zF5VRYG?5mQ8?Yk0Sv~vY;su0TwH?DdF@>umF%zTa0nT23amDnZqo?hC*hT?b9Je9B00Qs?g z@a{(~HJ^kq<^l|fYj*$U0C(9k!BbK@F;6e{E?7->d9Xs5S;b7{fj`~Ph~Ho1JJY6C z#APu50nXa|IWv=5G9!l0x@OU}B4Cc6-kJ3e7skPQ{%?eUY&N{0lb4%eNUlrJR#@Ib zmw5xiGz1Qc2(84E>2o;cG{7IVxLN%yGNZ%37i zx&%c_Tk3iWJ5z}`oB$8&nS057>|m$SQ$ax7dRL^RhRui=BZ82#=q3f#?HQPDZl&@E zh%9k+V?poyVhnp9knw!YZy-;BSiU zzy6|KP1xcV0T)0;%@&94Wb%ZCtEX6*npR@!M&T|(M!j8u<{_lBFACfWvk~r{Vl;_G zbeg&0+-YSijO}p##q|4`+EQ8_;Pc(h7A`1w?kS<0x*;QnvJ!3;D~nVgI|Q7ZyB^CG zF>e9y7d|{SmV_}1Lv8i8;!gk3{jNLi(eV`CMUwk0)H^fPP4;302!_w<+OpCyW? zz;Wo8=g^Let_3s(BJ;SAAsjpocY^1IVMM7z+KhZ@StH9a?xY- zfT)(GB6d4KJ!Rs`%526*W0~m>j(0*)Lge&mxw!oY0^o+|>gne|!SFG~C&~1;lUqfa z0hjhPA;}pS-`>s8J;^0kXJz|RdoiN^XJz%@1vz72$~R#CS`xB3;7*~+@6Ep3G;uyA zVR)$Evzu>fh;7L9WV5QywCQyeH2Gf|wjYAK*2>5vC!WiN0^52S9>bw&#Po{?7NAYa-MV3@U24*ccb|Jf)&Ck_=ixS>ptzSCOc zA2Po^1nw&`ntYEHiP3a*`W)}mibL7Gv>K1CXbQ*M46_kYRH6t>@ zMJ!Wp<@&Va@#mO{&HRr=n}yMA!R|!2@lcd!YE1>0i`&pZM@bs=4+MkEy7M$a2Du|l z9Kz1`#DwFxDpV*k&&w3avRJjVA=ii!K_`%{-hzNmacl^H>%=llK&(Lh!I;k7j~HHK~gXe$Llb%(t%43wF-bNud>|O>J!85Msvhy(PtyQ(xHpd=yU znE86BM&uTxLrPHqhC~|W5m)PV8M*60%cC!jJRGmbPWT4?xQWer<9w>wncRNNeCU}; zy){&$zjI-W8;bIWE@eaN?wDQ*M!8WClz-N}JetOL_e^qb4b4SSOjQ<{W;?jiB<(&s z>A(+&JK&)Xc<#M;$f=0PO#LyGEf+0a4Aq-$ILX=O z-m~!p>Zdly-P!M~P%|w!HQbUWjB;I9UkX%Ez{WwZOoD>_xdo;kvO@~=dQlw38L^LD zh{eC0D2PeZ{kwDF+5#iI1*x(snl&jhC<>Z%Ll+ z(MkHWHih>|*-Hq`kf9BDFYg3Dl{0>TeE>1_^oz5wIgU0-S2C5?UtZ={q!@Y^E=(lt5dv>rx2R4J zQ|b>!i|9nd)rD z%=&4_PWGX|?OETTi8KQqtFV}Bx1eD$bnT@QjJ_EaC;b~LXKpgTbraH%c(*OURKODU z({wYSopVcqNgMM+4G*G~W8eMrI@9`IZ>=>ug>Y#+tMjObKuPVQIVoI`Lx2m=!^Zyim}z^W^% zL5;Jx-C4=+$p`Llo7A__fV#`BnG2x1sX%>$ivc{L|I*|mJ8G&;s)S(Kljx*W%EfW) zMntAEvN5{Ze&>hZjw}`La>&I51?Wunw#ZmapN#Io?7Z&MOBz1j^M8-m__;gP@lbIu>!ge0zhNV$GG0O-HF_!!3qplY z$K!R4w2i5*y|ZbE7ciVJyr}|DP2U%?>k&J61w2yh!TAoNrH|{lYGu-w50khA&4`T? ztx0>7xqskigv#?xE~qR}ycrhVv1XL4rvZ6Mxr`5F&hQHqXimR8nvuCb^!ks*qNV_6 zh(n=LfX=!-l-s^YUIvNl`$J7(ZF*Bb^L)$3L3Mk9Mz*JnXKL3r>=xk4V-79h%dE0$ zv4EI?!P1O|ok|&`^iykYY%2#R5Si{#BfCmzhN-Olb$EYhPxQ1^b@k3MZW(x2#+@Jm z(y$*H(g5jK^%!DYWVzckh~~`|-~uk68WTX(Kmplu5oBP*4h<)F5g8gdS4mR=!FIs0Y~d9t zJG$D=H#GM)YEFt{AW#J_e;|YD3b;}HPE_rzm^|eQtl|V{L)lq#OKAuSB@34LB<+2w z-k^&b^ggk{hpPzda{Q>Qm*KWS-jTmo>h?miTWazvfYWY4;yC7%RMGhgv3r9Jzp8$N zV$dC`TNprI&J%=~DRTXVrP<;`pQs*JqdW7BQgpNT{df*1FD&zA`$m&yT&6iVV-#rE zBDL(Sz}^r@=NFIZ#32QXO9k^uI&|5rMbX(0UT0&+XSVA96dRRLeSG~zm!QDN;cm@U zR2&o}g;=-UyTj?KM*RnbQ=&4?r(Du=@5Cg5kLXg>;lH30s>I~}3{#Y6EFF=(Eunq4 zQ09}-4d&3@T>RPw7)KBJTrgOs|F4q0ve7bbDX&R3&V|0rF^7@+FxGZyK@y-%Z}7I;Lr8`n)MQ}Z>=5-%)r+&9d|_cviBBzm7H4l5swJ|jlGC=7 zmM4V3R)h)sC?95>V0AKw^8CT#+s0o!CfZ!aBG7U{+05ssR-LsR*+F z_TdiOnJ_*z=yl)|>VA5bwT*tj$(J(13c|M2_g@sUXf;GYXN=NR2dWS1^2n(l=3{$e zTUK+8-~vt66tA1v3gEJI=}W7C7SH~BYin!y@<;xnOY z6eCD6XqdKukyYH_QYLBNb>91<1T2J26iXfQQ#A;^t3yLl8?7UX7i3u*LaRKL>+RVv$yqFn67H?4I}N%1&fu1@eq zZ-m80IVVh2Id22uZmGRX$@Z$EkVYPGd|!ULzzLo~X4--SfHEkLXVOVRJew zM@|*H-0wVBHO*WEA6CBoZ^PuB&bQsP{XPxIS(*`Kdd)Gci8#@~O9qeqm$0w#sIkbA z-x?Ne33#KB&TiVicBKag7D(AeBF0jUU7KOBFZ|xpR~4Jl6R=-a+Zv~}6jBc{T_a&& zvYCgMOYn*aq)Zmxu@9SOBZUP7O`l+T(HSfW9kJJ#h1P@IHEEi zsi@Ha7OdO^@P4KJscm^g*A%C?4VHu1f><7MrE|?8#j=IXFB8Prp(47>;YKXUh)~e& z+1fdT#0>y=vmGbMq8i_>^xzY4d#tvAB#fL^4j`GW+wK9(wL>wVmbTS#7x3?Lw=@O= zq&7mnqVCySz@Td7H*QMT&NpBQbAKkijIFkFMO1bt*Lk2y?B?OU`O!G6N)!Uj03ZeY z}XYV3e1cv|0NV#1XcOJ(*XjU8?-d`gfwhvJe4s}-7`Qe zMQi#h*h8S%=YPZw_a_Bd_B&207~uI^SiVSjPvtuNF6`(7ls$N)bN zQZepwZ=%#;Z=f@e3TKimkp!mepgOF5;ObjN|N5Pm@Cm;+(Tx4k9KxS~b01&}5iU%E z+~ux-?0FU+3>!I^5vpLomjHr5)+rAoELXi>CdinX?vjaGE&|-j7`9fTS&?nO?LK-i z;rbPQ>a?j>>v~x-JD1!-x>pRu7+#=B@0;~R4^Q#o8tpVamfpHY+A)Ly=p6th=m-ZX zC>CVxLPo4q)TbFZ6vdHLC9E@qKP^O8VKfW~LmWN!O8$Ca3--6g$h4_!9IoYeU0qte zI^Zv10SNyE{~4ar^1RWO-0m1j1Q;TVgvtY;8fF}R6^f6SI8mYf$!-&`t?7FDrQnX@ ziH4+FWj%W6L7MzR))c6LZU%!WBL`%EFdL)ane&Cl6!P@!`RE!|Z*j;Emb#dYzj)-p z1_hpB-(F+X35)06wTC&jF8!Z$0!cfL5<m(eKgPqZB%M6rHi=cY{3_F^3xsB3)07!I827e-F`9th+@=XXB%Dc$XQ zwIIOu!gXP9?9^qj0aY%3!6<>!gWo=vXyG2a6#vf?J(v+yt3%(a-5OXDY|UF}hOLLK z-$!kFv9!p&fM+yid z=eSA?s+WiZkC>pzhQu;QQRJZ~BzG1Z)>d!(Y^5M6B*qFq7gbnp1c}LM7=s%@XH6yd z8}N^B;;YzO#Zowkodn6GYH~`0dO?}bvcocPc?J!~s=0V(<+!PI2@-rB*_G}!{Yesl z)?(#2tUtY)RA`_Xl|XpX&FI6MJk6FkgMw}ub*@p7dE)Piel|feSa>ps;`?NVRa*;N z-lC=j>`v}9_O7qM8`+DE`8(Zk-Ni9Xg4s2uP2tcSJ^RuDOMk8!9##*I9`aE8TQ{>o zi5`eq@n(!Ax)dW>OT+4KRqc*1ZXpp;D@q~TIt+j$6fl|u@OJ-g7x^`XeM>8u_`TFG8-l9I)FW*be+$c@ONc|3Pk zNMt}}>R8VTGrY&VR9FLdtN0P!{M2#TQms2k5nGT5c)ZGEH_YMnIObVT_vlyebA*J)5nakA2TDg(b7cRtjXq@<@{A zQPNZe{fe!0L7@wH9z(*;FY?7fC}h@L?!?h@^T3^m2!~O-rzGbHV%buGrul$j08ABQ zw^MlwAgwFqT;T5R6=K?AF}oFw>N4v=5rs$M(DjyB)LR$g5UrD=6k>|RiA2o+?jLu` zd{=CP@^+jCre+VT5Gm?T(!c~ljd!khXT|95Vvp1xtG5Q+AjzI~^|6fM1RJu={SR5; z?`vilKb5~9zhFdlS;drC*f?5p#yCT3pn{~pC{hDYv$gxe7B}`^Dj2Do7>S+!0ovUF ztypkA=>VMd3aCPF2(~tzAex7r4nS1|joa^aZojc{$;SDYUBqU;frNGl$>Ecb3 zPdc+Z@<3UdT}B3i+(D2|0>d;4(J-^6f@yD+9Ng|+IAsUCT{=Xb3qQtQ!t>_+Eo^>paG@$xbRz`0I)KH+ksl0|o*qt*xucdU=%RuwUn~ zM^ND@P{J4ap)GK$b?cTSB?2A1#;suRuz%Ea&UHna@ z{S&df%Ctd$MrX$9KOn2I{!DAJxkL~tz!kW%uJw*KZ>hCW%1gG}c0r9= zrc76%Z`YdxI(H2*S9SXaCgWX)z`(wS%{;19K8KQl6b548ux#@tLsFq)v&dfHq7Y}2yAMfItwSh6e#q>Il$EL5U z$(6`{3zV}$Y@0CTJ4|Xn%~8DH)o@s~9|9;~vpY+)3D%E3 z-)cO;Z3(baB=&u8zrZ+a?!-fWoWo*H zLx^T`j7knUE2qdI`DyNJ+o!jH1Ne5OH0QNW+6K#e!byf#I$5Rey&kHXPI*B zLSR$MV+r73hib#ylUj?0N6r9FNEI9yKC!@k1wO|T#>clote2XpqrU8O!@H4jQT7UJ z;frBSc{hY4hN_44CC>aIaBZ|ncDL1?JD^vq5+oj0Z_UJ`E`1vx(rd@3e^oWT5`)3& zN8nRsIxF}<3N)il%0NWHm=0&3KvFJ|g2B1Uz4GqQAJ``p-_z^in~aqv{*g8t!Jt(; zytg1ys5e(a5`9e_(>Yxekd^-f8V`&=CM&n;5p=)!j&lw)nJ;;zjc?~?iH5d6Cv6;^ zq6T5$n2%+KC<^F(oVI0gUE|ry|VMNr_AODN>D)wfO#{se~?Gv8jKJ{$yK1r<5 zYL-A$W%dh@1V8VSdxG{DrE@#>U(98W1*ZpV8Dn7N_sYV397MWkV4Lxov=LR%xYH-$ zTWo26Lr(QkL@#CMG{L^eUBlkhM6MoY8k91AlsL$UK8I|K)}8Jmwo#U?$XIcgl=vD4P(w7C5LhI!7RdxMA z9$k=SjWhea0jm}&)$I;LEwCHYCZTZd?G^H1^k(O2P?a*FyuE=6HydcZMy~k*eum&! zrKt4@ZT|zhxicZO!528A#>_RwS+{i1exr)*SfNnD)ITOU}AVRX4t-h z^YOhfLDzPNCY}dcpq~t>YW4Bp%;)4ge-DtEp}#N9)B`Rh*T?E9<9bF`X(m{%AuoB7 z+^z3xRutnD8euayq;$BYaQ4jV6+`oTku&Kp!eMOXhhv>#J63N#hCsx5T4goQt8+y_!LMVnz1n`qhVD-NyYI{oxAXJX$cf zQ=(cllkZmFT_P^YogDPQ3JoaT9%fv1Hhuda@cqoIPdf>wwSP;jBxgqTdw#UvZc_7x zu6;B!KxEvgz`|((`~Fr#b{^l_-o7HFE59l(?3n#|KkBSPvIr`LPgXv7uy8L{anJR4 z+$+QRkVUfx_jX-AA<1jntdMY|G}=mRZk;0=TVo<#?EE3G+3Wh@tDTb*-%dR7ofXle zR=vM_tNWCA9fv^uiMm6{-;l-8Xy<4nFITduUERfM}_57aiX6#wFd?@00Bm zK57x@I_e2S!82nSybhcq!cl_ayZt&Y(7W_!i>l%Nr_qks$dspxK*()TKXNoT}5Qi)J2jLP6 z7Xo4XMy<>MwXd2!_{iWL)<=>5q*rpmd&Bpof6GbHe)q03K#>Eop-y_+c`Kf5yQ9Sn zNq=JD-KDZ{9XLAwam6n&*wyAn)!}X5L-`XafQnU+?JC%Jx#YIywonXdBF`c9-0DM0 zy17qy#BQxk=;L-SV@hbX#GJ(y&FMm~IhsrVtZ}pfU#Z|psnk7>>O(2qe&!>}c{B83 zUft=b70#-0QM+Ip&fWRRW;I)WHFN%7^;3Nc>08!15(lTA9SLj*bVIk^tjHq7h)4Hr zDE$KC>F`9EHknhnDy3-L(tPd4+|Hd8naP8w?_dh?@(Nwnz)T_SJNanrsBkBN`k8m< zR>@^82n25G*KTx*p2`&1T5u&>#T1U{63C;I-$YhFf8J?c5+yC^bg9Ie1Q+?=#yo5@ zGL2e0FWT%XMn>S87~PwUD{(jXH{%ARGSsj@2-UVTN0B=^?|8WUM*w_@ng8DtuDN4< ziGqeplY?&4$t^u!&v_|0^n2ZJeV-@F68FWcEy%oIxc*}hW-3jrlEN0dcu_O5(xZ;3 zY1l-5@bhQ(Nz-%NqjwpC3wk*|Ltb!^L?w{8QvdFv0IpxX7I(iF<9zz@dgNYH4OW!k z14a3KHo5-`-MR zJYI1X1P|vBER-b9TL!jRO6XB& z*G4uy(-u;~9L-)@iIz6^K>_>NUyBo>5z||8wTe?Mp+X(iHh4Hs)8TIXI+Z-ZNZ`94RT8BclNaR!37BmTbH!IEq-j|wyiT>V+Th*gN0yeYrBc=>S?fUJ?;@sJMk zy*2&5z%G9^J^9HlzKlr$TOiIMGUq^xLyeLQa!viK(@-r^ev0<&Qfkt!Ho`7c#X~dc z=8fEYu2QX&@v8b}R#MEoUp0g^zd{w^EZhg1k1AJ6zb?3Jk`M{qPRP}E>fFFn-n^mv z+3{@7Q4xqrg^Eq68ZN}dGBQc=ut3z%Ch}f=jq%tBrRz{aenr zjtkr9*HzQWAlz%fCxi2pAMLA&^fNkDK{N0|R;-)zIsdfsG9Jska* zKb-FeEk);58B0qI9lHeg`zdBp{i!IXFtDth=HBz=BFT07L`Z#QLN95vasNX(^kei4 z1{EM(>uzEcH*c*%^v{lWt!ta8%#|amc$w?Jc^)l%jW>0RY9}{m_No&C8$1;yXmrtU zU=VaN0ZkQajVDV++^db{<(i5vrQOUIXZ5O3^h1ys2rG$gVcU0)wFYX|nv@ZQG)z(b z6~EUdYBzT0dY@89#tF#=~z!tZ-IO znXuf{`Qax`=TVBf7^H46&!3?4NwA?w$lG&DkWh8Gzr?GTMIr>Peoj%Ad6U*OY#VX6 z{T#BnbUl@C_lD5vxl$$-x4h$~&v0q&T8SfB)`yBe=@44ZQR>5pT61lhMNb@co}Qon zmdRbGdd=N@CfD90W&!}NnCW}=dVQ%^5()#JOYb{GhOTK%j?j$Z56?8ya zuxR1UO9N67>J9RC6i_>rJR^onRgyUXp)45w#xJPlxHsB#RC{A88`W4nklXB(9(UW{ z-6+kGCgHJ{po*mD(iQQ#k#)h>a*gU3O)Y8R`(srBqqfQC9^G~FEZs}BCn|o3%X+Pw zJj3dC8(itVA3kH&`WWA)w;hNnaLHH`eehEjCbj`xEu?=N!@XqZyF3bGh4x1S(cW+G ztc{~;nd%rS!kqt7qJ}er^6=OOs(0?5u#TwQBDAyXE)Qm_SjVElnz_$sS8(d&XIXm9 zDp3=nb` z%$*P_8S(c`HS!R{SeqnX`p{bcob*DsU0m?^y0BDH>t=-_UHad;Pw)oxwF- zQCE4}^S4K}6rdJdr!~&Yw0T`{we={sr}BZ;;gB#({-)qKmvK z;qm93ao`|FJ*%B!4TaqhZlSnsKm;l{mcQw&Ni^AbBWZo!#U(lekJ-gX3oUs&$@S%+ zex)<~df=<{cN*Zj+2mPy_K1zO4T(DA@2STmb7b&*UG4enC?CopHvYd9$iG7QrzFzqlJy&Y3241@#HAuQ$wf6&aX~5^7s@IOisCZpP_^(g$P{awy7mne; z0?-!IyItdWclqqe{j3-wWr$PG7>N>GjkUq%IHecJP|jH#C1OI@2lZ zsQIRUxp-kknJo~rQCvue_X>V2Tv%&D6wh$eOl-Vtt_TkP5Y=v6I@5h*Iq2LvVHd~u zE;b>qS8co4j3;cS?QW>h9Bo(Nz08a5!CMPx(gBTB{F|uc%~H>+(_QT298;JXkdn|9 zJb_H)edtWHV^IdtlWod#bi~^|neoF==d&?WY`-T=6Vj@E^f>wb-5$N2{;n$2o%>dL zY)A0oBXsA*U5JvRWfW5LM5~{`!Zpd*AOC`k-(wh*N4EJ7C0CAL2H)mdNR#pg1{F)^Q_6y7xPdY`|2OFAn;t&6c<(Zl7+<&7f110VKxqruU4DoCI!gcB2L|U(KdiY)QP}Z;@7^kn`-rK(Rg8ci(&_8S^ z5zu}*ys<>`k87yX>uNnmsvRu2H`jUa*xS3`R1M;X3{fWo zZ~ch7d(fcdIwlj`av+^gnKUl64JZr6L&e_QKtK{gs6BO#$E$8rCWUZwG?T81$M4P? z1EZX)p|BFS1Fk!69Dn82Kg+y234`={$wG+AW^zqZ0L>=4CvuXUAV1^qw2BF_ni2oD z1pLFG^PcTCKQMTo+aZeK?te1Q>joODzb4<)vq3^>X)o@u777#0%kcVTFffmkZE$b3oBy{wliUJlPNkf6Sp1Nzps?Tt0#nkt8 z+|kttPeszWhuq?Tl_h*gQF&&m^GHs0@{3voG>za`^NYK(Q*o5^F3^iS0J0+*G#x3@ zoj{ZRJjIJPZ8MW-`%6yV;U;flKsC+f@7Uw8y1pP+kgHkA@+~z9$?f%)eR&Z-6ec6| zLNiu4>CZy}SM)YX_VWjgH zZ|O2#7D>;`*$^HEZ9t=lW5vLu1lW><8bkB>v><$h>~D$TO}a?w;@|*8JPoL82kKH< zEM-iT2wa#+>Grp%<9ZHiWvSqR@wKDq?cVSHK-cvH);+i0`Ni(^IIjAla<{!5FAX0Er8VeUW+q)3b+7UoI zq2i!*s**n>UWIg`w}|lKU!=YsWlH1P=^vO~U1eyVI=5fUcTc3_W}M%?H50m{Wgfjj z*L#$6zi>725uFL*{jrp1pG*cf&ZW%=6}CIZ%JUUZF>*)s)dL|V{Ut=#EfXSPq-i&x zf#ZTY5G7L@EHiCODHn+rO1WDQ7#V)Fq!`j|wP4i@|D)-2i(su`Da>&~ZgD?FCa%HM zgkd8PbY|9D4?7MLv^ZSqZjHxO)3%P{QiX|$w~4Ae&S3U9W(Re`M?GuiKR^%QNxd(w zdFcLZC%tj)Vw%WG2)tun<)Pok8ywY5^P#HMaIg@AMqZBGjzf*T3yzs>LMORMmpsP~odUKTxdO@e? z>^!^^mZ=arDzf3rt(uyNyCL+DU4Kgtzcx?l*nyYiEWlg~%&&SeLGD%V={D_UQ=;$G zYnUK>Bd2ZH>u*RZj+{7I=Z4Ps$dXMwTwhx?MXd04juuzLRtss{H}S^7XMr%z?69MA zZ?&lIMQV&xL~uFD!mmApqiZRh8GS8F{F`btjzO+yR@lLT`pX;BxX}c3o{c1J;%3aR zWxdYOl19V^7&2I`0KAqBVzUlrlHb>@8j0}9f$`1zu^eD-hO~qZ*#J}75D=GV=1PMf zRJQ^;J}Q>d)gk6CreVkIcZ6HiMF=kxRkEE_Oy zz;mqiL4FKmX(sRPnX*3S{;9p|OW&Y^O%ReDCDHrJlHxd)qTPA{qCBf-w8H%aYOFZ! z)$K!Nc{`vfs;Ui5pv;*(Oj#Z#{Eqn;t9fV(hT0xAm(siAVUH*+^;g)2vYyb){Cksv zOsnB-UN$^gq%+hX zM0-PBo>g@SS}Zc%*BAqw4|SB(@^Vx`1|c_5g^SCZIYg%OhePvcc?j5DQ&F$B1FkJv ze*TD`T}Gv@7K2h!`E+m`K}lxA^p83Ox6Z39BU-ToX4 zG=i$0|6zT37BgZYjjU@r1PYq0_tCbL7!s`vlJF2+btZ za3;9IQs1*=aG7-!0^eQZA>cVO|LHHAgV>bAib8+-Bk)hqwQ%BuRjQE4VLk7O9Acnn7b85Dq(D#_nawKz{Y2VBIn7gm zu3Ucxw1;?hKG~!fDYs*emjwXM^~MF5TcCuQPWfl7vQVJhZct)lFF!L$9EYTWUuUtE zj9jWV@6w)+cI&ClqGUEgH4>+r;25_T>FcwSv$}IuNSr!nS9TJxc%DW7;w1poM9LoDO z7q;@!Q{0ZWQIc?XBXg9*IA04ij{FKt8OT(bHy%$**`~tzGYtz1u>EjE7^ri}-?l?$ zK_Zlu;d{7N_2y8HHWc#z5xWU9Ff61R5;7b3?3xO{^6h^F$o$Sxl9exyIa2a|=B{q;J-oCwj_JtlQrnt%hd$bo^HoUgh%*z}l{{{Ey5*j4KXarlC3j)mkU8kyN#gDES)C}NKW#CB2hQ_dES)@5pk>S>ZYiEYdSyZx}XJ6O{O%jD3 z;cK5_+JyQDK>|7#*0FdO&u?HL?Fgq&JDk|rXj@WV9Ll&q$9K~VhI2Bpf24#N0)>?kvSv;!~25M#xC_jl*ux-K_m$&8MiRl#ZGV{ zIUPvLUd;O3*28Dg;kTH&wbg3C);MGeSx-+!!usbdlw607JMd^VG01~wim6S~;pkt+d^*;W)EO5}pV|6{*#dDj+0`@$$+7={VhI+O zVM%Pahbpi8vm$9Xlnlg=W^}|q9h;?bAYTa+4}~EMxjXLKEg{uaao|=XgZ(uWsp}sG z_Wf0VUaoFlM9QkBPajIYiyT3aVZVAcwfp(gFHCwWi$imHivUfJftz*_sAjo!Cm;yb z^R^N7{)ebX-J|D0=!40(q@Rjm;di<$7$tD*Se1KE+$xc`1GgOjvE8Ti9~?a;YN7?&XBE3y(&bj#3!i%^ zp43=2F`3eodaV%KATi(vtnOOqf3IPMK~eu2jbt}A^A4zvepDgc5BhMLT(>DJ7_?ht zlWQ}9j^*XZO2F{4zKwH>f0M4|?}oGmxp9D>Bt*;P%`x;0gDm@P1NfxYY+bo%w4&KE zZ02pp+eu~h9s);!rn-s=6;5;1N4G=(I0c*5Qre!u%GP}vL(?V~YJ`1J{Rt%&Rv*pg zpAmcQ5Go(LT-2TiOYM>l{gBsLc= z=r(bR;Fx$&?~4THcm2&$mxj|@y2*(|0#-c`3se|6 z55s66Xm&R)Xhn^vY_r;WJ|Fc3e*GvXhV*lKy60}T_OBg?ZH zeUHF);dXGds^%UTSem-*88CUIb*vLB^xS)-@3E0$*=?TZM7JF!}cB=8Pqf$@ERd{+L6co-D3NHGa+PLRmp9+X}` zNjQYna3i&WlI-j}-E?i5d!niC zhhU!jWz_C1mQ-pc+C2}kdONNbSYM0SL%HXuhsn0PYim6dS?*?3gEA)@E}owrI5L|A zgsj|5I;gKT$F$Rs9=Lvf4%@`_+Qak|JW@jKf{qggl_c?C78jG%pK70FsoaE;SRNvZ zEt5{94Q}#tB~-9A2h>nkdbocj#Nt5CbS|ZSE$v$x5vQGb!4^nQ5jSp0e|F~v=LeJI zOXRxMv9;WS9xaqY-H+$|%RN98fW6zciib$K?hUgLcMs`wZXkSD%t zpK3L2ggD9D3nK^Tz>O{|@0uW~Jw)ynj2SE+nm4VlP|k9L>P4}2CzzT8abaO3o*H;= zvAk@xkh%&g2aqZZAJA&wAMG2b`?=P$IHkJIN~TK)2EACsz_SBH7^q~F%oj&TeIcmG z3L#KRE`+SY1-`?=0A{X9ucqNO4$F}ypleD3Uiq!;wwH}9|y?Iy1b2BQxpTb4F1#mddcb?K^_vN}C0?j^&F`?5WBrjtQ1 z``$>Q4XPS|kijRp@SigxN1f1E$; z%%~6rGaIOpIF>x~pl*wqH*vFqT(?dnIIUzri99`ed1ZUu`I+F{9F-$s_Aw@Vaj};r znX^L(Z*@4#qhiXE@Ta|9Qx;Z`BcAy~`N6XnHe{N;1X-F7wc7PfXL)S-?g@jVT@8+=GWLok~yK%3;D_C<%lQ z^FT7Qrb{7KSn;ym5*M6Vhj>M;e(&ieZbVHHKHJ51v5a z9(PydelT_ksiqc`i z#)p#1b_VUV+vzKL%Cu599zBdk-|yEyG%u@eKv6X47eFoGd%^DA4H2_(O6?D|y;B=3 zZ?;1KGP~a%elt%YpxQjHv3(wdT1YcLyEP$%Syp>lh?t@3@x72LI!mm?5Ay@t)-mYH zkwuuQ?=py@2LG3kZ4eQck&v#ZEqGJOqZP=`ZLq*k^hJwfgtN$fYDr=d#ZUXkjeT%N`gif1@cl(^v73x*gMT zObqKmGmoRs8QIhI+X%cy|Le-gGyR3113b9!Y`Xzf4|%ybkU>azBIf6Sd+pxRDhrG~vEnY!Q z8JqNJ&vBw`9-4%3$L_{v@w&8 z9O)NbzVp2Wn#|~@jbeajP%sV22IaF$vZ;EMx^=~l3GAbqLwUO8*232DYChDBjBQji z2)BL$3OHpC25fcGL2YhL7a`&b&zm;isc6e#SZTo%Hgpy!KT?=$g?D{7?_P3$=$k2< zY1Pft$W5MpXkf`q-A3n4n1QcCcn3Z8K=lF!`U&c?TstV!;2FtI-53u^J!R~kB;Z9N zq<0bFr-(|f(v1sp8`+ks8a80jb#)^X)VOIZ8%4(q!24v5mpbU7t^%47Y!-a=hxJ6w zj>Lsw1E?}WcsR&5T(A1%^VK$$=Lae{GcM3D)P`ALd%_Zuimejy-qp)ybm&>GkrizJ`}StGajn6S;x;l|31G<* zGJ&ceYVK_;;5Vo!W)7f#xBVv?J_K-Lx(G)W>{2aI+!Ul6n`=_i^A=ya8-kfz(9F5q zW6Jwg?oW;2Q6fNmr2D&@iw_rem9;XbZ8_I1b1qibz!H{9ejk!!U)ywhZ_h&la+A9VZo5QTpEI)aC%AH{ zqH>TSyIQEcFCuhGZ5KW)4Uz#HKjR5VY1pf4@-~xjF$3e^lx~3Yy7BYNUj3l^Y|L*Tb_>^o{#dto4YK)|Dh))6K?r^RERQ)BxsPdJ^K zBLR0Kcmm_D2a?Cs(v42-bX)Lgs)4-#6FUKOlr#^IKaR3hctu&%E8U!8GG}6^`I3(p zJNQJEB8DI0{jkStNIaEvEt?CHgqa&kT(V6@HN$qVWS5cLn7u2r+)A*g>Izh&ZfJ61 zr^wVeAV)G=fgw$|$CIF6&_3KhTniy{ybW3lxry+SqtB7pauOA zIZteA1jSJHM7ZL{e%Jvyu)g3;`v6kQCA8jm?}&c|*WSU*K$qsGE-VnhG$*)tHc!il ztB}WH5F4P~S5uG~F%1?jr^1=&berJ4T62Tpren=j+9WIjJiZ2p^-@&G-x^E|&EwDH zc4GiLkEbDD!$N49#)DKt9Gfu$^)5A-gFy#7gn;70bJ&0>3?>cij7!O9F`tc?@QOBJYsoE(d-C?5myCrI8LK+S2%0l$B^ z@E;)M>^fkb44;dBikR^1&=i&&98VaAP=by8O`+L>y9S~=i@Tgo9XZuponUb3`ASY3 zteTm2l=cTM#_(wThZzTpD{-a!6s?xLwQNYD1cJ|(TC!udF|9WN)^6V=_}-2m1X3rS zKpG`P`BqZ__1fOMry+V7%gfhDj~DH~fz2IAtabH2{Wi>EG~g_iG$e$Q+jFB5+&em7 zYsbUff*!W4AOj^Qym}GwDl7hBNBkqTzSI%Hjd6dF69gF!{E40Kl9cBkUr})aAN<#J z4avH4v|yZW*O}pUnp+Eq9XjB$3jrr28hrvng4>}TawH%Asd&L-Fl9kTf0b}^?BZoO z4rDDf&f>rpWJz*6aH0`b)z@=c#A5^`9?mZsYGFj|_PrTHv8R%mVynGyYCty&;xQ%Q z(1d`YE>Umq?&C8W;A6E&3ogjUvZ1UAC$2BZ0vN}ohD%bBgw-RQ-b$tNc^ob8ixSjb zWE_#OgEJbL#fLPZ`-h0aRw!_XO2A!Xi~!2!WXC(s zXJHK&l9i`=rV5)lY+e_A9sj$9%%E~ILOz7Y5XqN@#6TVrSEMRoE!#ZW3- zSsw+?$<}&m!_@DDwZoC@vcaICkNM25%(iw(^+?M;l~U%PuurF-ArnexvsLW> zo%92H{?FH?$2#w`Q=bc`v^o0`IUF2Bn7P`hNP&lV++!<<01-i!H?cMTB0o?qP$wDm zH8&+$TdfLcsTg-cwyE-PyBoNjb(cLQf-$3({s*A$Wo6z?`QY=QOz*;B*6-v9;jn(n zoTb~+h2Blf57ja!#^2Qm?q8VRc;O81Z(`lROTlylQr|DcNn-k^KS6T zT?{zY47ZFBsA1QvrpwFye)&(CYEtyz)iww?e0D6#Q*O{daH#tj{Q6uci>$`%t{;*& z|CghNvET`qBO0{p9W^{F<8nNfjTtViIo2ypFP6=!H?>12GN-k&Ua_qPygr6?4w>@&WC2O#s>K~0MB`RV`z)Uuz@wnzIsJ%Nhq$bLR>@&Q$<^(BImS82?qF=8J- zY8GTGuXW%f0$LJD{uXO(nZKH^vv(t#gU{&F)L5$LMngZ`KA#vg&E@~OOC^0fxJdB^ z>vH=@Z%98ZWU<>a?)BjkXR!g4d^9>z$npX%8l~;j=@qZTqqjB_`f}itb9XqL`2oB& z;@X?2omR&`Xuf8bd*2!H z%xIE`#@uQpjtig3plR{$3dr&u_9(fTUVqa#8p)-w0g&*8^P+KsuKk|x3w1Wdcs{A} z{Bcx{7LV=Ze~DWoE29pd0dM3(VDH` z@(0Tm=Cj#8>Rr;diwd-pLm#<>QE;0*3fR$q&RuJVaED(bNHLJLd-j=eJ#b2jmO7q1 zO>kQ_*MYpb?(`E{bB6)Vg)k|G<@mA|m#$hRaY59GI=g?j5vkza$rHpovYKdG|AAES zm$uhOhEsedI&o>k`_bV;*LHBz@xw&SAc+*$Cf6!0_gY^uuoW&P`?2@K5&uc+h}FnW zHvtDrn}~U;ts%C3DO4g1kf+O4ge=bQnCWJ1$BCdMpuICLVZGh>oaE`_Uj)m(`)W#T zBE0B19GpC>DO;?nisR)c+Ch_TiIJsb23h*$*7a+`K`t<>GBjucb&iT0psREL>cT z*K0v;=VxRz{HpT%THxC0 zRPtDpjZ+wi{c6?ic!gT}W9?N|NvvK{Oe1npa)fQ))`EnPq()J4BYu68F%T&6}AlsvN?ER#%ZeGtKMJXVoe%!>@y z{S0}}@afG)BFwPnQO2)J3;H9n4K zTwIcAZm(2IpkE|$#nRhvpGW6T!G8$cw7uc)5WP@Aw!}|(XxaFPW8A=|Y(IDS$Fr$j z_we%HC(UgtG3UAD{ag-v!9so>d1H1dO_^aN$wfD0V+wz(;h&;-Kaj<*CQzo0qkmWV z#S>wUVs_Bp^^)uBQPzem%v z|M;ELWi>_T;UWtdK?aOO$#K$r@y9KwA%Gq7jeGV)M8_*%d(={43Cj4-*u4u^Um3#` zO3>Z7x9iKq>jo>f*N*o!aZ+3hYYygrSMntiU?Au z!*CQ)v!~{$=d7aVUdyU)T0)+&r zW;a}(WS2yF2aep^JQFrgT`yv#<^Bgel}PmEv<_j@d!0>Ap$m%t2OvtCZpP}?dk>0Q zzXO8({ew3@ZdYwZ3w;x^rKX~DTMyK-4ysFBf9j>VqW{0Zt_aha(a)#B*=(GYCtNC)Ue0FdA+tt~N##CPCZR7ud+KMC1_W_!W zzmBUp3voC#Ba*!h>`!RS@l{e3XRecpN*! zT?bjOGV(zqrE|rv#Ow<_Si2z>6Zwya1Fj7xiE}R$~KJwm(bX#r&izt_A6~*d1h*A?%nNMdLWjdkGv_s*~j; zJE;gRV@5*!vBkLuCQGM>P9I@(J>Q$Afq})UTxs;LR~^<+bYx=_Lp4y30RoTj9OmSu z3+d;1xOTj(Kh)d7J&X{V#K>`WOpjQ8>&?y1{N}r29d*1709RjDGFLbMUGx_dp%RPp zd9)dB%e58w$=dt1PuddW3eF3{-P(BcswNIqtWpcC&kv%;Ts!_5Pur=tH?|!EI2ZM2 zJj>|!;72C%nxh!*H8QVJI1K?Ri5v1xewv?teM7Yx`)hLBz^BU8*K+?Uo;0)I)0S{khTjcH%hD6g3^e%iY)s8OrZk`K4B>tK))d z)Ubhc;bw!9vQ#fhSfa=HG!@4tVPo^lck`#6M#WAdoFwGIJ_^sbKbaZx@VCf^e-H&` z9)X9|n{$iz4T7bUUj{8cAbSKyWjc30aU4bG({707?$>HSPJ z5GS#C?Gbzql=JOOT$TOHj)#=8u`-shl~R8eJ{SmOC_4yg9m&wZ^kQt)Da~a*EFvT= zG}r7hRHRG4=~COm7A;5Q>ax=Pd*9nLlELfBW2Z9VzRj|luT|uyisS7%Y>a87htvc6 zLm9SD=Z5XM6c-p!Hf3xxZpZi6%KQ9tkWML*+3U{u|+NDkEjAUc$e3W-Td#Y?vp>sxQsxhM$ zH^1z5Bngh=mm3eIN+XU=I?_1Vja3h&w1(a~d(P+wUGvDd*0L$sSa??bT}-XBI|wyF z{$s4@q$gI`l5`##zz9hdPT45UFVRgAl1pm=%s|6Q3rzeDVJk1xrW zni3#Y1&bRQoYk(K<*dcLw(CQgPuw^cUZy9fKM30&O`(}enU-}m>0IucRT&RdvHzq{ zVX$3RI>o219+{T|I3Iqyf8Vj<1-g`EZ-+n0dqPDotaC&6XlY7GkEFX`_ zoel21G&l@a0z%#@pSyIH4<_-8d^~Ug8)7Z_RbjspY>@I6sPBMK72@SvGd2%?UHrs; z_aJ*JV*xYy)%SiUc~l8Nlfr{!&%l&X8KAhUjdJVpU8SmJ6i!oTJGkrV*PIq@&x?yq ze0p8KyO*HTu+6O^Ao*_Jy|vj(1t%`E6k-Lbnlj+H@wPRDr>{y%R{vqpGLxQq7HfYk zQ;Vn0jfw%8Re}OfKaA$9Rp^SEi!nt~J=7zE)Fq%9HEE-hw1t*K?05e0M-~CqyS3PO z%uHcG<<`D+;{b#iGq6aRM1swWiwj~e>wkWRX(z+Q^X%FE{qGp{Hm+C5otO^g6x|JB zkcZC#eZ5ncyvl0|Rh8Uk=ikg-T6ntu#z?;fY;<<-<3_)Hl6m{s z$J;6Gvd(89KO3@kC?)x!Dh7Dv>CW*exn1Er zb!oSC(`W&IOqMy^ES1LqoN{xx30phe6uMRtdrXTR=H`DWX=hSqt*UZL#BmgcZ~|}^ z8`QJjCo!GOZD}$iQzI$s!jzVnjl12)F%h2wsq%|%SgVU=%=uITxn5dU^^$ecq9`|?)?$T> zj~xstXYKJ~xGCAKn{N$sl$2M%{r9iI50XO_mh~HO^rlcq+dexGWXl_?tZx(nMbDK* znxTB?u0PA^}4i(>ZF&t%g) z?~PC(78S0cIJ!D+QH$>%z6g-xIQSyQHTCG_L7l63$B|-H5%B^FIl|g;t)#n^2>7rh39ER!ihA3cZuAq zmj3d84tX)ZAD=HLv-?7oN2tb0V^3Cfw)pLSP9>x&%Bv!4TIB<;2??LonUOKM6oonX z8m*)EU*C2=V7QgBbXmEbvsx@QpEWErxH+X9Kp32%#p@w>s1#!bvmboJKR-wOA4}&R z&UF9(@y`rHq60M|);82>w7=3d}&Z3e-Q%Vk-!<-pHw`OxJ-NedStUx(-O@kFDYJtj;hR+f3h6572-_n$HSISt5j zm%!miIsS0y#1#Q*Ju+M-fFd}2Zv>JgN2`-!`*KRA)onkc*j;4EpEf@%NJi66a(~nh z>3Wx93@{9Ppi4BtN4UpI^w^t}dgnd$nX4$_s?Y3{4+H>NFBliprR zlZuNKVptl8bU$sq=X>yb(>vpcG^AcFxFk!C%-d0BNDlnHP+h-&4^;{3UWHW_&=%_l za#rUs0ui@-=jx7)k2wO-d9;dm(H>@^`g(iIwkyL|52WtVuRyolVi;kZ_6SAeqqy~p z*O~I~mzLGZ&uKmf7|yqw4L+U?kv-LzJgi;Uz5o@N3;hnz#x#qx|FvF2ER(};zwNJ5vi5P@DWqua!-ks% zez_*xscLuzoN3m$yf;$e*Y!c;kLIy?&hNit;9$4IrH81@h5h$~2 z?<+Sd)@Q1*?z&;t6V+avJYp&=zrhI?z=->zB^J+G805 zcnRuBGaoQvRUb~?(ROo$gVM&nH_~(VQgc5y)iVd@URu-UUGT+l2D7;2RTsxlbcQ@^444NmTm z_Upo9rw9Yfv?EpDx^dL6$@)PZwvb8Rc?RFRC)et(i+X-h*v*#?NT*-8@C8eKq>-JY zY@`NRhb|+{xz`KEy36rjS&1bs;FSBuq3cE?yerhxDJIyDZNqP}?;D-p4hGg_l?G=WbXf>TR*v}IJ1Xm>htpe|N$qtA zsT?NT`q&Rce8z(-5aO0O+t-&H*Kyny<&qRwmTe64+^)`H`uZp$lf+rj0pK7T#yO`9@bFdA~fJjm|5{&6gO zs{@V#v1z4k6H?QT>W|h+UbAk`KYlP#yV92D>kqTm;Yd>1^Dno$V5SIJ^#SS^y=$+a zXERcDxL+T8z7l_m@GO?JqjS5P-gj#;4q?^MBMj&O_?^leU?_;j6@6}z>gXyL1S^oT zRNAT(og;-R1{bDYE-cf(gh@%-8s%zXctK5uU!iSyu;>XjqK~$8Z55P9z>3Rn_;eVY z>k6Q{M2k3O_MZi3S?YB~H{tWw6ow`5Ao6oH)V@&?;*Y2tefQhF(;3v?z_iPKc8<#J zd~VvS|7O4BFA@F(>V}Z}gDzcPXZhwYoLxY7Zrkfi?xY0|4X|<_SiQZA-^>=Q3zFLz zi<+QryvuER)psT%S>#Na#vi-lO^Sx;j7w0&%QJT;4g9jHMy9(TYi6_v7dISAQ_i-x zqZg#XvbCZ$S$QGgJ$)4MN_NgS#rJN{2&|anT75&pr!ea4@Rmr~-KEKEFRakVkCl<4 zCw*0yOP&iv9LHzb0~hnHd;maQk>-on<6owJg}Izb2KrF7wxl zdX2Q*+Y~o^+1*Q|a86zu(tJ;FkERLUM9-@bnyeDpyw5RP%+h5>Z&Ap%_X+YqhZv@n zLZC8$A1_WW4&^4342BSalFwAVz4h)S)`?gd8Jxs>#`4YIb1g9vrCbVne#?>T-F9b?dY_k-A5MvGZN3x{X1!%)1H`^%OzMvy zKbRC-8kp~{HMwf6F1m51P`NcVVze;NPafCHBg8c$2V#!vgQ@ML&r#IfQ+}HC$$(X_ zivl0tR5hnobh{$w?&%3A%4vr3v+^?B<_w{oqy-OKno9IZl*0Yur;8@j!& zwJ1!A5)4roQ0J>8nBx|m*P6#FJR1tnk5#8+x*2ihqH|RW=tr5wQ#^+mxFn1mLk2nX z-JuL{Y6p~agAKdYEm&koC$wbWDDUJe0b2qk`hGN(C)V)2%pmC>k4lP+}2yvjFgcBYRkW^f5B3g^FQsUwCiIIxl?Ca4>e z6DYAt=b80*4w=^gt$Bd_CY7o^MnH`Q{kfiAjlZR?CRh!?~;J>PbC&UFs6)SZ@;aMf+)Z)1$TWo zC{YN;l4;)lksYnlCS?X!)~i5)xnM3()hbAK0Pu{V2sWE4O~2dAQ$Gm@@&fviUrI~P zxanU_& z97>ME3sL-8I9us-`1ytKVS_?L(c7~ z;7gmTNM>_}yWq|tru&BbE>1eM1IkBIEnm|6OoxIFeac|*Qkw#yAJT3Ds(*8K30taS z5C)2cnz0%r3ks{~RuDi@2UgOONdc*o0W(+ajf7oOa?VwLGZj`GnCXP>M&3sVNSze| z`0NA0DPsnp)_HJ1MH>O32uU966WiB!X)7sBF!uvW<(6ks2kj8v8*_La0``!k%1r^R zK{zVuff(S+w>$?*rU&!UsF;{(gA)i(|4Gpp^3Dms?`dYxUAi1@Nq?+A>3ae+y%9Cb z@a^Ay>3%69f68DYhrqM@>Gac@%?F5RcEfHf@zMC@#=m%iVg5khIQG;ke5l|8hqBS@&!pm@HaG`3;hR(i`Pv`5wc^& zT$xJaBNbFw0;N$KVadg?9Fhrd-U9!nKY$WfC!-$+T8=!DGyFR4phqA(V`D#LJDuhS zMa1kWIiUG%3DrdwjTX1Ygn;|m0orbhy;@L@dvz{ILWSb()%8l~?4a{U0C_wij=GS( z+f@2Ttj}?uALe}G{@EeDfKBuy+nUeEwhfgda(N_xQjqth7NZ2Cb+?+6ak=4k8}rxX z^{uaqiCb7hT^CmJ<=nU>8=NF#4EhwE|EzAbxnUi@w_Qv-x;v_RO(FHk=4=P}K0*12 z`MkI2?rZ&hgDl$7M&g(iLVU_fq)XU=E+vERT;$nF23OJL0O6kHJwby^K=}^CAkbek zHylDyQwFEDPrQr)e)clMOVDYmDoyQZ{jTz@W@5u^v*OBbVjl@Ot}xFZ9V~^KF?G%Q zyHj-qB-Mxf&I;8HujEDV1%8OBCdY=aZHoYeyDOXN$<1m8PyGxHC$gt{{KcJR>o-a= z#|fz(D&o?H-H`2G=Sn~~DwIy+$6!-5t9VaQ#P4g!OiY8#APK6xF;CeIm^bxEM~}6H z0WfEfNV9FT^RCxdA)sewk=F|~u{&8m;p8dvsK?8LP)49w8jJ#g817c{ysu1C>~QEj`IDd}M=Q{L2n{6>rExm8bt znaGRg$7^#8TE%aOyztw!s*r8X-WgYFB-D%F*2)#J)q%oq!k?P`T46YWZn*8p$#2Z}VtMN(PR8O;v@=kliOTfX}N!Ap-^I@IFuTV{4h0x_4tMuG<_A~fQZetl%7X7a0 zzQlB+>77s(P2xq&-AgTYo%2|6r@|nZbO)E3fqVP=A1BGkruVoM199_+A$}+mgvTz; z9lYSELXS1E%GlnqhQ>nWT3i~~1o~uj>Q!)_sr%7+na*&xz;)wL(73vijh9+(l7t33 zekIOKIw*!Rn@>##wNRi;`*}6eIbc(K=9_x<%MM}NP!V8u#J2Gqta+R+CzDTJ{tU=j zB)6(FHlsmrlV*22W2DE*GB-D4B6g^oNM4>FOUe5sW;y56G6|yeu?Gd{meQ!HtE0+> z(GxvgR(hZ$=`6^}EQ_PQA94Y$Z`jYEEaP=O+pAW)m;*vI5COntP(AoP9tv z@kq3J)Wpb&zo4;6g;n7>Z3tNC{Ffck2(jr*^anT`*FxE++w%XnJeA%ZChbUfD7SWn#p=m3L2)zK~F22@&rK`sf)5EC1-6H z%o`Ky{C&Z@YzbMe{^vdz1_FlOScos@`#P0TtUxK@A7zQBytY8@0Gifo3rT)QXRos( z)y>Dxis^&C%B1{NCpRqQi|iHVnU#(A+pUG0=nZro1& zHetQ^TxTN@Y#eCZzBu)`y!Z6fT-Y0>NfKTh3d&+Ez#zBz5eAiQ$S}C!pQ3&;4Gfjt zjtT_oZ$o-e+8m6Pm5ad1=bzQ7O{_R7xCn>xd|kFdfmmceq~0AR!foQq(_(2b$wB^`fE zX_KJ?_w>cP)DIsb8rZUN=K(izr8clk3CMFTL>!IF&CM!A(PSLsk_ZYBIo^tBJ z={w_^!Om657t5J)En#6rpm###N|B^(d$)+s+9*Xz1{hvRM|P2Mzk{_A$=o=sP@<4g zLMP8&fOqYs-RhBmh7j#((^3<-o2ep*$H3h02IqHNX1NkX+eJN=q35q|GmqjAl+9g7 zK{^$Q`kOoY8A*bY)Me2eaP!&^N-5V&nP>Iwnk~DzThG zKvChW=E~YeQA9q(iLm9fZOc94Jv@jpVHQtVLfwZ=yVb1Rlprsvsy!w&LZ$5i;i^8-y0It~Ipp_h& z<+%6+S}NOGAg#X)251$tl^_kg%CIG1TKSVl1S4(@l2`+&LS(xsU3387sj! zsSWTG>z7h8?Bwd_Gm|c>)a#ShX7;bbh@)L{VFy6u~Xk!t3u#>E= zNWr|{M^0LoJAUcrQ-;nini6x4m~?56GNIes;$Feal8R|+=3FvZw+w)1#ADXrih<6< zb+^&>D{fIPLu(Qf?_SA*9E0G>jbb;VZU%u_t_zC8<)ATjG;VIjS^s+WDx(6~m$7Lu zimD*&pU(^Az*)1yq!S|I@5KnzDCJupUGSPS48Hh3<@lRm63uYAlvDiai^`zv^%|@3 z{5m?-UuS2dDE7riyLdVGuoz=2`6zdgrurXFyu{tenD@(LPX{O7u_UssupeZj zTwpbddf=rEI=#Wr6@V>Z^toPkw7E6jx@~HDBo?ioabz5QtAnC>n-O{ zVCD|Gpa)VP+s|2@T!D(x7_Kh48Oim#%}Qw5QH&DMp>RZ#ynlXQ-%Z1ib00j)Oi@NH z3dqnpLJKnatZ<8aDvKqfi51egPF(x1cK%SR7s)mbw`Kdtu@_Jx;^zZp-WojCMudZR zmFI7T3gZ@7DSA(d74xnh1Qe|n3}c6dZfgr>aARS5;ZUsD#7Ad#-WPP?6kh|oWV8-W zpJ8~pD@xxUgq-;o-~$J&c2wl~NU3Nj7(of2=Y^L6k%@k75?QCk7PCm|Yv*NXRW7D- zpnO^dum6l^1#rm0G(kys2F$HPHh=fB_DHRnfwJs#!Z$P05E`nY7QW{tPa%>i&CWqI zAacF|SlHHs9bM>6)}gi=%IJa*n|`v+_v?NLHrphZMPvCx?XgS9Sr#wF-P=p zw?RkgB|^Pu@C;e3ZKcTldZicy2GSkck>{plw3fy%8LoqV3rtgK%gtOhF#0BM&&#M; z=`Mg9s4JEL+8A&iiM=Co&G{fL5TKUkBQ>KN!M{wIivg@%MFk?K29WbUYo1QA`bkaM zoh17}`S0dx6yrf-6ciD5JJsZ_e8`09oYxIVp_R3U1edk4pRrGV6GLZ_zy&n+O5F46cp}QiN3~{IYRUC=vjs#nZUDuJlfC}kh>eHY$ju=dpJFQ`|!8~F#aqg zBC%%-*_S?L?Non!7Y_Xl!tHv|uubZD$B2eK;2#?OLd) z`z(XgJlY8!6{o(2MzF!C99LRVi9no5W3Cc>GFAw>`~t8z%p`9By?lp`Ve8vXIF=)? zwVv3*mSV`Z0=$1tN55*}j6Ef(_nuRryd)hT?PSdd$vqzYZPQYFb5}t0_^FQ@EosM@MUhp;!Xq%ZG`2w0v-u5Rs>Vf?BB(ZtSCShI z;TtH0nA!Q^Ec|s#eOGr&9wF{Y=j1j7D~1XlQ%F;16)KMnUTuo9AqUP63}@C(uB*7p zJ_i{C>t%ZWj#3QEQG-myO0k`?FS4MM6cL5IalajA>n~`6q$m@~8C=vV<7bYTD}e*v zz|;wAJ^?8`UoK20v;c1J=whD}2AQ9?6d8$$4fmPTz5UNy38P|Z_-bBuUMorL`F5^J z4O$MWSRTeHR7odc+xIn-oR`V5KRnR4JHhgY zd{IWF#9Dtd0&jxCG;o(`!h%xxeBdZ6F3(&&y^>R;!irjj*a&F&8?;k3rZW&fJTEI8_~ZDxGf19sHhq8jFvmlY|#6uZ;9Ta5!Pj& z$MauQ?WF%EA+#oI#X+ZCsciq_j9KP*URQP}pv`0GZ6GJCrYd#vCZI7`AxF`ng(zoR z(wEpasdf18^fQ}pVU-I4=*gD}x6SvT(F8hsy3iO6o#^edtE@yrMuqE_noFb)2tG`t zc#X2O@kBe?HvAvp`0q{|R&hkM%GFPMdyNT#3v97xv=SvjAqGNLD8JNo^F2ofOpS@C zXYCVMYxydSgRE73x~>0Ehm;h5;EXLFUEE=2!D>qcASa-wLZG_!o5-&0RnN_=k+yqX zQ-%h`g{Fe0SoLY0ofDo58zkui^`$T-rUVc%1Oi86^2{aeD=dXU52_rGFhC3e831{O z26_2`&=MN#qu2oCxNbO3j?mMW4+qWx&~%3T6-ttcsK5FyI37#PRAj2Ivvx}W>p2Y} zk)ffy37L0uN^#4=%dmWryfpFg|Fc zi<5~!axHZY<+W1siVN9svj&fc^SOPH;(kAEB2hF*kKd%aoJ3r(w`z zeovcA!)W#rdXQaNijYUBdkSLUwY6<6K#Q)g-*rUH6E6brx z8cgFzAs;1rnT=6q#C^!Kfc)_~36K$Wuy}Uh;##3orwfYTvvhOTYz~@bcDP5tBqD5w zSTd+mB8Mv%0ue-I#u-b(^UvSxUaIv%W+^#S#0V5k(1*@Q6ErE7dIhK3!ny|AVWa4^ zMQero38F&a*bObIa*Rh*?>0C){v0q^C|45;4}x#36{RO|;+Vw%r_SASSbS6(kKXu< zNpZ_KbrF)z96t|af5aAO!EBhtuB|WXyN2H@-6nG2+&nLPmK>ma$fVe2U-ICx{`EFw zc6zQl)o;q~L>XK<1^z)#T@vrq=T*}yw2Nt(BoX{d# zbEvd1E~A$RZ;o9neobwsMVwI{!7J#UHvZq`wTNcosQ&V-ic_6D*C*^xwrONUehqr9epjKpi z(S>X|#lsL%DVTV>cl~`@BA}W+#s%F|H3wOLW6@F9>DB!`<@F2vSN%JnP2SJ)xys&4 z^=NH`lAAra7{=)5{>TeBE$D`7G2=^R0u*sHw>YfIFYvpu4@dW1LxPU-oFN0gHZ%NM z_^g&HTaDOhON<>i(gkHO0-jgn@0h~p4^-_XGVA)mkxs;CLGRzj-V307v3?ll%3PvJ zTrD{Gm`QC@$lZeWWr_`Qc&RfI)n>1dxWz#D2S1cDyd>C5TvJbm97s;Ewo zp6KlYT0WAjZ5vzmhA)%N0$#@EGzFTU{6^Q*1iGv_ullYm>lO* z6El{Usl?bj++C3o!rsupDu^2F!UkzJENmvJ-iJs4Awezq?_^-6e zKWdSoi`c`A7{#1Kf57;cnnr%*u8u=i=B3vUzLVU>K6r#DnWQOOZeSauZmX|6F<=g- z6GT4yCk<&Y5SP?vut!*(3Y{m)FG1VH)L<~hl2@9S5x#b(ds90*x~+T%B}H`pieNU` z`A*C-{Jg4Zk3KA~;(pKUM*R!yc?qZH;VZvsp6PLrd;YO)VR^U2R5tWx0Kf3&V}Af4 zrgBMI<}-afCLYSa%mkZP*G{Lq{-HjNRQSSiSk*c$<#IMYHPf6VQV#w%cV^65>0pNZ zq*P>MR_U-Lf$Z5=n2u}bOOJ0Y!8ESVuDyO1_RE*rt2o-4lS&!nBb~lQ<6(K1B6~xn zI2bQJ1>M1NJ~scEmGtrA2z%c_qcW+)F(OK;8z!50LGKFu_Eaz%CwJsHreixQ^TjjK zN1qZN&WQ#z>;VhFu7ODXA%>s`*E6!IvjsJ??Qs3npyW+ag=y#^F&!}8**yIPcBL%d zcC5vWQzwIoRK?1!B-{zMzHaiRrZRMMael_$!+7v$ZZetLNL{6dRsH^-VEfRjfQ2&8 zh=^EypVcF*fXr6krAG{^_D&L*HNe3sVc0)J?CVPek{Jhqqa;*w-U%vX$^dfl!{Sfy zXf)j*+2-A+zvbm_8}4G=9zJF%!~%6+Yx7K2&8@AF?`8q2 z3a=jO6&rJDoRw}N$#1vr`3SsN81_zmGoBGp)BU5xJ9usJ+6Uve$p(@19;9+-Pca76 zM(&*%zWE4AB*=9iM}oulZ}&qIoEDj#aS6b3e;7W@6VvpnmfDK{u|Is`Q$MNR{LU}XYbCBe2u2jcdai9a4PYt^qu;4%{f(+?W4Vvqji2LN}J59sK93} zw@1#|Jg;wu{eGZ&edS|oFD|9tz#^);uF_q6Cke`b8W3(_1D!?gw1nDr(olVYq6gF&D9#u^bvY)EADp`Yoh~){*xyNkLvIF z?pCPWNsnVnv$h=<6X!)QMx5*SxRfhF4u1%)owp=)&u!F9_-lPA|FEMOO)CEY`-FQm zh|ulizfaeAc~($=)3vMFXiY=p(+pkxe^l9`N;fB;<&gc21lJaCX1+V|duB|q*|Dj+4sbdb z6V6S6aj*A0|6WQq)=W7r6aCOFP%_%mT{PF*>n6Shly~AVg!T~7Hqvi`eX^q3dP@Fp z)IIB{&5yb}fs!--xMqfWk6r66(aQ0}EATmi;KE)4>*R-5U(-xh!vx&E2E;IAbcy?! zGhxS0eEa1u){CehbZgGeFlps;y8ROsOW962%5SrteDUiso^)HC){WkNl~PxgXw`U0 z;ogl?-u$-W-`br5F^Mj!HN@LREW)jCDIpAK5e&{L3<#iUP8q?HTW*V=O1#XKSu&g7 zy4`d%mQyvALQAg+gJ$hJuo%TNw~VRLK9VKXS$DFz9Wy z1EW6S%uOF#_0`~md6#Akn>0&$cMb1M?D>ANZ(>GQ`?#55oCK-9uui`>!k;2mhqG?x1-Gi_czP0U0RfU^0iX$)L+r#*^mOmyHg+7C0 z!wiv7q0hY>x2ZZv_XJq{SdhOkSwfQ@kSLqHj9~qb{X0&TpWzdPbc#0Ep#Ch+yMJo? zLtpKW$G=q=dU@Hm5+u>B(ZtViUvhS7^y+UR1*%Y#g?77ivG>N>OMZ(= zZ%#sQT}tkasb}icPawtAB`7NW)-4mL{E9nN*C+?tejL75{(gV=Jp-z)^f_UKi$^*W zK3m5FV2Ju=S+gpb-4;mSQ^zI^f38ly*LRb)s(#2}F}XlCw|QW=VMjY+2Kj~mQOeO= zt1s=a;-BwTwNlU7>i+H6rMlwVx-zOs**!5azxY>QkaSkssf?#;AN->O^H#U4?XM1= zo7g%3@|S^%JrV_o#80bf=B)DUM87w^2SF`Q9*Lo$6m9)y7|g2^Ca1q0P0mi#i~K$f z<88cp@@U_rr{-{>f_8gE0bB|s3)Ki59`P|<$&SQ_j!whMty~MuPf_??H8<}~1Y|10 zr!j90PTRd$SseJ%ZcnE9Wq`g8(6Qm5Evx-MzZ3hDha4KAkEP zj0!G3u^@GM1QzvyY25dR5ih2pqcmq=nGyH(+DJvb)SXUFF+v1LbB=7O$q1Z|KD;j} z;URZ;Lb`ke1d=w#l%A}+e|!@c9qcgiu?!<%B5mx--D&7x)D_+1`-<;4DXwhyTU3SZ z0bw%NUhj-7NXOV)3;DJ!b5`C2rw4c+`1F8`*Vz%_mS+bhj2YX-ifn8XuwojGOUxf-EY0rssKig17(tmdhSr-~Y@59%>JrH*K zi(zdjKd?NlJxiUs9+OT8`xC4sc%2wSA8u+M+&yTmFmmKG(G%`E!N!%$@*vmzCa*k> zPrVp59ozC$I!iQYjREe2edP%0y`a~o9Rwf;y`{;c%PJQb{mPWW<`Yx8hsUT zzN0iTi0tmpo>CBH#6(0tn6LsWJ{FJ7=aR(DYedd}E`k{-aR!5+_orbo2chYKTCFfbDz%KjcF-OB&xM5>AH1FbeNYXDhrvC{KTUnyxh#Z4tD6?OyEN z6qT5%9REBu?S&=-7nQl;>q)0}Zs(n~da6s}r`R8Dhk3IDZv5|=%>UjOJx^X%1MmPi z4!{29H7oIyb3A;+e0PYkw2k}O;1SQ7`ky{`3p=gDF^GRqp04`on>-?>lDy2LGW%*3 zYL2}Uxw69LU%^f~3K4p0V?g1OxYg|SYs8e-Q)ite?hKpCOh;a@UCxiGGkK@P zSfGLttw&t1hCh0oXxb5>h@dpTn7`(CH5=l?kJBJss-#0d8mKr>zMhZ1{V>hyRN_j} zJC)*v4sBiROl$~40#f+<=A#e2ag(jPBOVk15Bbou`*+98t2!5x`nBE`ghV&xj`*uU z-QLEas)Pik62DOW+DYmQFO=qgBdT%CR~L(WuSH!c$MF;pZUH@p;73{-RPoNVR50%^ zqW0+O8b2ZCXHE6hvt|wj4eo~>U4-bYnDlRV`Bg74p8DOrGjb;7tY(XM8ezZJnd;}2 z#&IxpzsGTIP|==^z2p|Qq!z96a+!Cp`y!sFJ)6ofuyHWIgSA!DtUlVC7d?ZOe$ps< zl@Mm64o?;zg_g|lZWs40OvFO?3t(;y3LfC5h`xVFO+D#TsPN^pL>dN$HP(q#nSXe? z?vje399~Qu%v`?#@%jUL$Dz)CgOH;g#Q?A9~uMGVa0=1kMhmB100 z#oD56S)1R{D_%lD?oy)z<8UT}`yD%c@l&1dkt?!vzP@NZeHU9!WE70JT>mvG0 zbx(7<-}Y8vZI9*@Q8Aanl+A#M3^}uO&wL8Mg+@u&bL!S#T|Rg(Rensv8lv?Z4rQT#(O^)#`aOYeleW3PTA%UX4n=>%42 zHx3RzT)CVs{4AS1kpx1Kal9Y8-;6faKOImlP@G)(8-my64DkAi9ksJl6>_p-(W15| z4F3JGEf`_UVk~qAx1(DVWC-M3G<}BZm4p}DxSDTpK3?bGpkiF-%s(~flU6&Y=BQuX zSnrR#)}L9EL6=RxlD|8mk43LDn(O)+=$DDN7l7f!+(h_nPei}GxfWzh91cSbz&YjU z;zvhhCdAlS>6jL9Iak84*etj%6D$PNQ(BDg;ce1{FYzj>GwE!Tle;5Jp$x%n{L4}E zPg!~^VGGV~R73M2eBUcU+j=)x1#bTH`Eq;e1g?5vXGjhw8yB-i6W3X`cUAR~a((ws zV`CT(S<@Tne%~UDMAPL0rga>@>&u07vi=(RAL(Lg4@P&RA}?q%)mKWWr6)^#v@3O{ z|8~=d<_Wzyo7S&`M$%`}q>26}zL6p2iEUqhetf{umXa~lI#aag&>_*RLPGIy^2eiKJI4;YOLS=e184P zkph~Sq!kvuQ_q$B^h%}NZ2So-hP*kgYjbJh?A@CBuf5zf8B-PAKnA!dx$&`MFLNb= z@ZgB}_=jK{2J>%Asf)5|dN1VR`zl-eeWypU0Udb%uw)v79Oeiv8{Tq}hZd$Tr+<6E zcT#TcSwyRt?ry<;5SQclKG0o!VD|pexyO|_FdNiqXGc3>}NhZIl zxi%*&D^CB>Kf1+WCk|=HUwom@#iM3Cx9}}t%>sAwOa}w8gns)$Pz@fDn?bwZZVX6s^P8v!a_2)bY)jQ zlbDMS=>&&zd|rPv`4Wlf`Oh}Z9iUU?zq7Culfs;$(+lWWw$x8C6_P zL>DeOPSXdajaJPA6&3O>*I&=jT{LLvzLJ(Lxy2|sB4QtDz8=zY`c{Y|8mVQ~yW{2- z?x|zQZrjfHyWy+^?EDkrq-{|05=$=Psgpy z-@33@d7aN$87s7Uv=T0rm`ty?D{&j%E^<>S6I9Id!M_l_=VWRQ!N;}l!wnVWv~Pjs4;b+XCx z3&{PU#H$U}o}&DM(0eR66fY6<-v9P;=i*X68#@l{MrYbQ@i_dJD}aw2jB4J0KRj@H z^4`h%x}m>BVjs6pOcz)Eu5Xya`%_m9#5=l=)8=_efJuhi!)~Fu=x6&iPs(oLwH+{F zknX6w8(Hlu#@FPNn@qg>ZBAd6Q_VXaBqONKK;?vAOSn6ho3BvUb(6*r6}N;*?96%J zweS9(Ts*bg82IX+J0Ed-gTrB*1u8vCQlL-grYSM5=gWQ%Z^kk!m!S$Ck(q8<5fg;X zhI!t#PY3qXUKj#6VD);KH^J9qB+AcMQ1kNx7U=@G`Uv69+@j)?o+BTt|Mm0)2M(#b zSTEC@P@jCh>iNe7Q;uqG7(U#Q@XIgTq|R7`!++6D4FbQ=HuI(3DJ_&usNN{0E)AI! zKVr@OonVg=0VeMxXv1OY+p_&Vkm1)l@t-Wr&cQpO?z{ko>_g^4{@?kglSpNr`9iy+ zh^{R0$D$xeW$BXeRaKc3<(7cUxXJSu$~RQue=)ucMOxL>N!ow1`RCT4i2joGh`68C z(wi%v4tK`H=KCq;<3pe_U_)wni!ybMMbQn^^VhFFap>0kUuunnc7RiA@KmPJ?#W-U zcfK;31K{Xd!;N1!o{bM96G0%BoIgb?W+fM9#aN+zo%~>We69_z97oCGPJ?*4H|+6$ ze*d{}?X-#hUV`eSPx4O=;p7^ThRhLJRa8sJ{`d5q_LIQ0l^1L75JmTz*gwe~!_(9A zvidWpgl#qVnA8^)meR+KliO~q-JELI0e!OHE<}$$*rdt=p=u`XEu7g@mvp|oIq8s? zVUOg39-qdhcQXUHN_M5=FA(T<;164-ysoqBE>hNS8m}4 z^ih2$aZGorW6X*HoK(@Vm~hQtc>M4ORbTXx*=sX(?+adZM?-dBt%q-vH!xam$$pW) z%6&vbuOF^n6+|vwuycvnFkXDY>nZ$SWs66Zdqm?F4qDGQAra1z1XnHd(!mn?8t>v+ z`}#hP;|soWzdrKE=gRYYB+mv5bwH7`N9#EidVv=-uE!F?2a-rm>S)K5O;J(;jRbT4961l&q0_5Hr4OXyS9A#s6R6DBtn@AvNUAg(zyoL63%| z!|r`D#@^yrU&%gL&1V!uw`#M0&PzO%51DOrhc5lqY#0UU`o1OYK&=j|{$7rG7|I#R z>#J9H712>L9>BPZKQPxM?gTR(5VEWv8@`Quj3)b4{A z8U7o5cIxn||&E*#S|HKd;fSLbLXf z!|_P2#BcvFH!cFC48H0|9Nv#q##k8%3Yg=JF$Ah%QhZ$k!vXZ8gt!(P+EB#7Lk6)D zW{b@5A+KTXLC6?12mYUUz^bcBeV~t=+P`x<1CpzA4J_}~+jT_9+mJmKi*T_Vo8-Z6 zj1nXZK0i)vO<^M<)j)KG{&6U@&L9)1k5+7ke*>_NdTZXerS&3rGib>l%$`aBd3`?T zkmi;F)1qpUE#VUC60t4*hmgH{R;p( z+i`Ypb)JupOs3KqbzXnhRSt*B4r0PRYk*7SQiQUeN7%NVQ3bk#5xuZ)zi1RPKTxEM zsO_@^49=PmX0XEV%J;zw^l!`YJ+JtTNg7;kB4B2Hy;N}8KB7T3u|`ctm`HSX18Fl@ zRLbXGeL@#Wr~fiuhbt3rm73nqXV&9x9+Lx;44r|i{ca)_XK!=6DLebpaENC&kDygN@7BF7sC)5lk6 zB8?$DaRfpv`dpzvun+&yYRYI?5cV~84y(6h;^&Jg^XU5fz*(pGVVE7yT7V!7_#eMN zr%sMkQGGO?{Mq!sdc|OZckPK}rM|-?A6`s-P&QFw=!kq;cE)O~!G_<867&pqbn0kp z5QxL9(Y%K|r&tg2m+<*&t#5thWSTBUh7(v4?bqC-0d`D-i47&|JU|!Xk-9@VCi}ir zX))SOE^BveAmjfB_4OI?o%E3=fREIb&9_xj(Aa=|{Vke6An(Il*h^39YF|zqQZKTK zKDqoe{Z#MVAAN`Yl|A)&LzNJKz(8GFFzJJ8wdiby~n{(H&?6_^S&}^x@`UgJ%*z(zoQ!fB)0) z=JvO%=6K$N>DL!ex{-ZYELI(;%TD1t8eW3YhW>|J?%Er_+X;ef#`@z&9o^t6Q}5R| ziZWpdumP`)ZCiKkGb#FumeoMjkx)iNo|_UEw$%Vb;C7RA5Xa=3-y1wFgiGJLRW(92 z2W}0?+Sc}MbxsqvZQVW|mxA|bb1FY;XDjL78gvWUfEUS-mR>XoMq)}JElvrJ9a7yl zKSpBot6PI3Xu;hWQ-mGg;g#~^Byj)Sa z4PqQL!;aE6(3dX_Pk_mtvor?vSbrxo+*vDcm-j=qd--;|#;)7KbJcr%N8f*sb@GJ1 zk6)u5k|;Y$_SEJof|xiBl!GdzP5*f$4E>8FLz=A?YgR(GV)k@ES>Kb3V!@SwHvi-r zn)fkxRHy$s5b=y3KM2O9`V-Td(Ci?;OVmqXqEGpWGx_|Br`74Rl;_*_78UifI&Pjb zRPdCPS72l+q{fld0EB4tdUK)L5=m~9avTL!1lw-8J1r*Ku;=+(_R+cbSqbyWn{R~~ zDCW{H(kIVxW?IO`HW68fsk zH=$WdoF}+05eTSr8(&E?@hb#O-d=raH0Z$IXb)irmP%!C4pytT%&AkSte@Vc^J^k+ zi_2iB=C+d+m?k{Zv51HEv&ycB@COP{-tdJoZXpk^`*+Ih<0- zBF|aoy$TlYfe;GQorox-!Yo5AV;|+x`oTwm^ILmn##C#;4LFG$H?ooQVI!1# z<}B5WZs!i96OxdaQ^-^@GL6>C*__Ayd*8o*U6GOWS4$tS~DVDlx9#|G=j~Iws ztSD1QGbtjVrn&gDs0!8y&R_(r$Kg<4ydFg?vdMKZn@65Nk|o;q+v%y}nc+WyqCBRR zQ{_*24?*Qla4BN)0;WQdaBC_17en#(#?VpMe43XOK}EFozuU<3(c7jgV zT}xm?tss}qwk$Kx36=Ht!vbtYiF`@&R}F=!MXZ3lP2bpz9i^bSkoM<=cBGP` z1(S6h;Kh$9e`!{Y7ru-^V6<(m3m<@?qblO$BjXKU81>Rit7ydq0QP2Mo)$?jk^a0G z1XrwYQW1Y+Oa+us^&SLsa3zq@UtLLVo|+I#4N>N<)i&%EWUL}uImJrlk@r#U@n5ra z?w^Z9&&$d{ScAFcTR)2uR+frrdJ^zp+d9If3K_eY1kp*p0GqM|d`QT#_KAAI6D2)$ z=N$X@yr5!FqQU0zBS?JBbQ&0Ud?d?WLiij+NGo<>ZB-Id3u*eqZCHZ?z_QPXMBK|;8A@4Z}(|2Pd{ z3xz~eO??>15t6(`yShTM+rr@5p*40(dz%IDq(ZMC5HfAb$fXYXujrIM-jH zv_uasiB5vjDiAy9?tHq^+FoB451#oG^OY0Cxr81AyC5TF6`j|y7qpM2ha&T4M4}V( z&oYrlir*$9J(VEs&RtC!3xLDEMdyZ2d}J=EWWNox=9w^b8_>;FL=5nKI9Xbr2qNGZ zeMRYIrm=yw0Iij^@@%t*sBM0#F-(fS$tdfzW#L;2}MZHEI%0fQo*Ql8zkI-iC>M|snf+(Es@B|wTL zdOj0}n#_za_@>S5f1w=8GqVtlx&O8mtF)i>?dl0V_yYR@h;C0A^nsYbouEJ^?1`i> z3(_7NVYL^pO#M_`EZf!LMCNf-Bw%s0$8u^=126jW(o{rqY?nMl)Qg(j6mN?4RJ_ zKaUzB@CL+!(yOwenJn7Fo=D`NQot~43B6-Ody}?=f!bsst9cq34%~2YW)KlC5|@s{ zCa4td;EvWk7}u)@34*(j+x0YN+>IbTQjS9LIDSYLX=Ncwi?l1`$BZ;yj~r)j7CI%z z@%OzfwX*X(0!8>zyE?Y^ErE~7N%xbqjA~R4m`p0`7iVy%>43xfspz}^wqiAb>T!q^ z2kC2~6%;&)K{`9~vfZVxy&6qkZ6%>Ls6yA(eL9S0YmPddEc=h zlTi348hju<_-9e$3NW(*f`G#%&tLD&(5Ve`Y)fKA+4oh~8hg%l2p)=r4WUArh3?Vs zymMr&rIpbF454-J)A^COAxD&doCGTTv2;IEZm1!S&PxJY#LY4 zTAXT?O(5_%9{u;)P8)%JsD*>Sr|;qnzy!O)5ao~ph}$iJj_73d!I!Oh z52Cc0FV6z5h`7~=8C0MfI%|+Z;dN$i8R1|k_8l5~hD|F?K_ZGHe2X9vV&0(i-^sa{ zkZx%j@~w1=tw#ol$Q4S;MOj22@1w~ z$5x#ffsmT<4}%qjP;puL)&)=OW8F|sP2+K9K`t1o6eqc{^$pja9N3I8IH}2q87Z3; z@@nRbGV0-o#@NQre1-tq`q9A|B%l&5We3-=Hx%bf_&EYP9T;JhRfMM12~!RzUY(@? zMAP^|VaH=0GL|s!WrEYK5EWAee#gHsAnTv6=d#426E9Avy-8+K$Z&sb1X*KS*~{IZ zm0lY{S3FYd+6<<|MMSA5UD#J;W!O$SO-MmLKoFabK>hr9MI0JD*%dv!H{NE3`UrRY zT0dKrFw@R)3;j;BMn}Jci8aIkRsz{+yUTUPpNL{a|HC{-52W;>od@#YKNl0w*GUex zeyj@Vc_h*vFiYf6lfd}cxZ$@OW*Mh|r1jSh7phsP#>g!fU#PdZcy`Pha4s*?Fqy{E zz*X|gULBk6Ue2*c9D%n-GsdF_Sclh5>1#reg`l{(Z=}Z@oH4}elUTfJo#~S(#kcwG zJzv?w^4Gc&dtDNx0yuwO+EyJ|fD| zkF~q4QRe<}+l&ff>7Fl5xwmzw2JIY)EKN!wrEoklYM@Nv7-cyqLWpblqi#V7q<$L= zI#u;NdcS<@3x{M2ozZYNRAJW&5`MKFTfku&Xy7}dINcUVj~|v+Gu+VGX$ZiGirl$E z8Alj=Bz%z*ckxZOZohtHbaNE#tN0TXEO!KfjS1V6K znuMCy7EQR5(TCOYwIH`Zc@xj?(e7DkT}Osz964wKy;<|qUH!9^8p7I6V~LE-eC_yD zn_kNc2!&~h+{Mf;^kI*?N1o!E8e}3gGb#NE8~vt1avUkzuJ35TxTEk&jCbdE2RW1h zE%^~2O?5>_?YWA{AOp59to{TNp;PCkXdBe5i4r#{^~p|F5_-S3Z*>ZEw1w5w;?g>4 zyJ#tw^6U0ARCE``_825CjcgvbbP0m94&O%!hDuaBE;Q+asOT4vWg}j_+zr+aYM>`_ z!Wvt5f}4AGFE;sFXT0@A*91nWdqdg;dE0?!P|SxGpBIEHvDdyWE|uUK=f?#v)LVSg zUYQ1S3JawXffk6-SwTv0YIE>&s0Gt_sYEpxr*5X@R2;({^uAN?=QD92t9b$h@W=?d zMmSXt$2PPk^d1i^VM_=?SP~Ku$cP#Um$!Cv43MaBA`0Dk^aB zyHM+&kwFWev?@7F(7XyE|Ao4gpgdzJOp0Z)t(Y3RFm)0-5MPA4^jWf0tm@E?==Rdo zTz?Kt^qf0(z+l(>lHet=V(YwAYJ$%(#&?Ei;lAWZEYJec$rjylv!_*1h?;ma;mHzF z8{}%gCRx;T`y8bJ-GpF&gG~dkaohxnZ%gAQ|M5)>0XT7>T+`|% z1;pwPE$|<7W^hKk3Mc3)oHY$ypK1bM!lx2mv!-;2F^EY1RBGLP)4G!ZbY5^ZHq8-I z!J{|(k)RIXfGl6C1@DbETqw%bS_*X zm@kcKy=GX zSY)iNJI@IMhb^wHIokv($NjAy z3KEbF`zFg66z1~;<=@@sTpqP`W+R+?HO1eu24xK=C+(GBy>6QrEn=83 z2*HS4Uw5w23bG=bgtVDD&mz=k3kyzdPU}FGd_h)|Ti{PHK_J_->}8b`1W$hWo!c?2 z2RHKy{l(NC*4Cuc+kq|rqsuv|1)7|=|!w$g$84{zFkPpgmhv=AS%Xk){Ebpx^*y>Zzu$XnLTW8RJ#vk5K{0jDPSLF7 zChu&z+@b)!=E_<&J@bx@s*9fqSS;rUDOSk7*}3tL$NY<#9lxOhs<`Wm%bM|}iB6`_ z%||o{hpz2?Pcvl_e|;Mrx~$LE`1~>4bZ|YoDi$!6zw>u2 zJ&5%dT8fP-LY1weK^NkCg@G*}_S4-%H{+tQpj#Za*Pv2g6sVO?fSIYS4!|3shfwct5QzAmy)bt=W zOrE6{n!$+haDZDanxr(qs|HBo^8*L@3a#+mVBAi|@L6*N!E`MGl zn1hZA1#zY3mTld%go)lm3!$7R6{--*(y}kO55}8EN1e7^-;A(qdAq>^r%(>+s{g9$r-P=484o^w0wu?fKBYY&i<2C1zMIP_%@hY-nYjVhJ)jyD)@|= ztzCz?W=La{`PXb{=)V+A|*E!SVQvdGIK>jgoZu z!){YcOFYQ-n}3*LljM@6W21t5plFd+0^$D&zvBucqi26Buy2|2&J!U zrbJmB#6L6GRs;`>GdmrpukRmJjPJ2RX)-=$e#o4+w)U;bmy3mZsq&13VpjI|eKmHH?l z{stR>Ryj3lA1_T#?w?OUq}oTIgs3&|(iY^|fX;;HOsP!S*!ZI19qC(OXP0sV2l;X4 zT3WAy&Z;E`8hjRQDqBw7rt0J;=Z+)g1ZDmomtnEw2qxBkbe^`(LyddCk-qG`WsPRyII&eya5fg9lB-u_4T0|d9cBgo%QHX~!ta8x)K z#h>a@M*XiCwkONmpo|5eCtq|v$144hz6GnLUg7+FAcsy)CIAmY2f*7s~gs{J@)kU^f3g{R`RlDOu5T^*yU5*VTD-Kp zcIK}v^J50LFiCD+5_&jx{7i3rk)9v*es8A>j4x!y08Nv>CFeLXtuQ1Uk$uJABUFeB zg!unLYY#@=7gPO10xg;YBQB2K_UnoFjvvV`9}>tlSepyW`haS3EYWBfFU>~E0R`&M z1CdyH!p}gDOXoVYc6KI@$JF&iOj@lUx&J?n`CY;gH&)b!&eHwsGEHX^yOiBIet^U{ zBdT?|Dt)T0)BJLauziL}P-(r6BBo@LKP#L|`oK#3)jMx?My&|8*>kAI*FBUWRA=}M zB6FT;%y+1)W)aZa4KhSOv~Q0#aCrmcRMYiP$%8A^r)x+~ByYYefAcO4@=SGH=(yss zVQ{g;@7{IQKQy(BIb5)OpKtt9*Z8eR#6@~GNi)X@y(_MdEDQbcd!Kys*T%@X6V$#n znpe%Wum2A#ZBJS%xwKOECv5%EPuT#Gi)kXNXTtwjVg!{q)z+UrYs8a>8_B z2B+kTs8NHPb6~-6q|lw7#p|y+*HPnKO?9ablhZ)vd2Hx3tyKy7c(a|S&9wB~LwP8- ze<8u^&wT&tBast}53k&C-SskVG~?wa%T>H}{pc~&%9Xtt=}u(gd^vvgGheM-;m?il z_y(U0^jfwzwCVDZW<005ePrCyxOoZCTw-thunPGtQ>**D=a5N&(?d|ARQ3Lq9=g|x zz5vDMgJtmsq7O2;UP`KEAWb2{gKiU9rFjPx7?v{%>n=FF7P6H=$*hM-peo$T`n<&N zbHOz0Xi?g9q4F=bak|yqv!-2Xt6&dI+5FHuU!}cqe;4+DzdI@FYn&9XQaF5_CvpE1 zD_nXT;dase0K?zWm=nF3GZ)rsnW=d5&l~L#0eSGkeF)5(7fW~KPyc~{*in>CwVb)$ z*56JEqH44r^&i{nx&F>82&6MMywc32)T&Eu)spm(djIUJxk9dfMm1kXFZ9LkEw9jh z6S`ZWQGIGPa^NMe{X%z3ShUwRu<6##;qF5HHnb0Zy=7bf6|19qcpyVyoq0rk<`K-M zW%WJb!x)i^kN#0YDY0uc_>gjSk1X-Q#`B7+xT;IpNl;Lz7>6+ysO4058I)90fByZ# zi|$Ng<=&!Tf)9*9pezFf_y*QkCa^xb1yueO3# zSYLN7ysGl_xgn$WOh6N}zz|-<4Y z)hLu(X@izU?GHWajnm_RM%66DXg6E?mk(R?5>T9)`6}ygJDf-c!kE?7U^=&KM6_X$ zGFWrk_3Oj=S;PYYo%@o|>TKy27}U*CP14`3B4Fktl%JLI{+P>+j<=*Rf*dewu}T=F zwg@^U6XGk2*5X*7PD*@JdYGv@gBRdUK+P$Ux#pna*rb@Riuf!|NegTd10#QLc>Woq zh(F0k6~}lzWVGG&6fe8pg`m_ z?UjIk6FO^{&^-0Izv@!!5qk!w%CcQj{TZZV96o3&jSlQUO}dWODBrsBesAyY?Z8|# z?d8d&y0W|*c3&7M<>HsLn(tl?iu6=>{T*Gs%Xbg&#;q-<;p6I&Rr3|U|2261*5$uq zZyIiIQ8jNcV2}1c*z4O>&32i8*Ajg%&-hU7SQ^Bi6DxDw-k0u6=DAG;@>a<|k&Y(pxKG$=p;~_0V@E3HBnuqkjav_o{ECmG zJJ?0tEqQQr{L{XO-DwB04zbBEt@@u!%zvt(kfH6#84LyFo3etp&#uk*vzNZPj9Wt& z@c=t1iZ{b?xtWmaKJDH`z3{7|~h41+O{Ltjmm2o#@C_lKJgL<%* z9UCy%sL_#LF;R1JSh3~vSK4o%Ec5 zI!E1(R)a3Oir9<)Od6VOr|{scb)U5}rz>rST4Zkf5)D$ISIhYB!gq-$v`|FCuLNfB z%-I^sk*5d$roC@7XXohXc=`vh--U9bGPa{5qfh8xwn{#%X9KYv`WrBxA>F zh(NLi*}bo`kfHVTnb4V!8KKV1>Eq*on7?zs_g65hwA3f7ti` z93;K9!Y=n7OA9=3wn#sGbOUo4g{F7GlddYE~YGE_SF zWUjnNz<5bOGvn(*LlPp+s6UY)$1z-qz{Y=eo+$&qo=IceMUq@pt#E+sH zF7|aVeFBVa$JkBTFNAR)u>QWS)A>Ov>0}Y?_8`!F=vap&dG336RxUx>I=r`LMeTr| z?)$3NeNSXHhX`(LVloE5b|$8+x_qR0DKrcJ5(%Mj@%nKvSK0I#owgvG1F5whQyfR_ z{ZDt;F1cau$lMyTkEE5&O9#0s!3zHJ?Z&YJc(qYeD2~Ig3#}sq&VO#?0>8gZuX~Y1 z{76gr&+jUGWgreha^TDwEND8PEMTdOjIz@_=Pob+K3I8aVFjk#f;G zdo73vlbE`kK3=f%$`fOMWMS57)EU}I|NHxPinUV{nBjo(tJAIXqz8-LO9RWd)=Tq8 zkE;!CdbI)j`~Y3#f>mM*g+4$6J7v+0NhLlz?XR4w>2QJc#;W@qWsW>`H~)~M+W4v#GP*|A zVsPZAqzz3d&E^T12SbOtE4sFqsr)D!j@)&+?2iRQg$lck;aDr~-9GsgCbvdq>C(8) z6|0Eo937)MR&bMeGi2lkQ~L3DpXn*Hc=P;+mY)V&_M_w9_jX1qTo;OqkHr1^Y3+aE zXU->RSV{R9J2w-12aq~xGlu?DRFZ|dC!{tg(V5R>T857Q*7l*d=F;1T4}$ibX`|}P zT9WQ7_rT9;xomBsQZ30KKl5t;;cg2krq2}4rfrX6YS-=Df}tz~;2(|)5h`n3RX-d( z>1^Mt3ODzfni@YSf}zxLKg*TZ}Y;vf5?e{aVxcP z$6Xc_XG3P1_;4o65s|x6x74L^R`^U;p8$F&*PFjO{}*1?cJ?h*2_4c4(VM4+8hEYn zkR*eo`C|bPEXQLlIk%sS&CQ4Nr3LJdZ8r{jNy}`J5TV{vtxD!Qzx!L-uY5H6Ezni6 z_Wyo`Ca*b(*DL-pJ z6x^HpS|Kj#JArfm_h!c6&$kb8i%;Kwo(!5Ymiiq&tMbrxP#FYY`MYB$|Am~-Ns;CT&)Df(tvp4J|qE)z3BaL2U&;t}62zw9Xa{g*mQfjc_x(>gnd86{E@inCGpv zoc(f|Se?{bAg3~2TlXA4WZ!ereCmE4DfeB(wYIS9@l|P<;{E+&HT=&Np7T*(c zr}XEJ)p!-WLMoG`r4XLYO6;iTQCae*r*teM#2u33#QR~EJ)TbC!$8Hb@!&>8WkcD` z;%*POLep%dHL-S*2r7-2uw(7#Ljq`qi*2Ti5K+of{zbXO`%ac#ghlZ$M)ZTI&v*XP z>-=0LBW^W6hne?xBcoMZzw!!3zO?cRG3>6(!- z!&5FQzVQAE^+6uA(>~TwX-U~R^_$j@sDY?Vb?4A-1RCB(QvCG1=5S`|!JFqIRMTSX zNPVuqd&VeF+TL7Ir}Ft;A^atY%wMesI;u7Jb*ALi;5OxCjaalRzAnaP>&=puipdz$ zkk*J#kIUZ6bR{v5980a!h>f!qmvjFLfvc$HZ8rRc`}6s_o#hb(w6oq-lif1kJ2rI` z-WiD7!HGX>gu+dib53pO$l-DVe=}oLD(yEJUxcrH?0Oge)w<-MhC|DqhWbc8<@6LT z^V_s~F$i1YW3$y1?P+I{e2PT(FMODAI(O3zTeZ?3Ua+hcu(Zd$8HT1b9TW`^mAE}-czRHwLE<{D@umr@vFmCDZ- zRQl@O-T6o>c!Jx-oO#Izej$cv;H;RK9eHnWdrDYf%-_r5xEhpbh3*`_=U?bsh5tq$ zy;}UO;z>8&EYK*rGD4HENDObiy7HS*TC0DtS7*s?d56QAYArO18>8>%?^mSeo?5D0 z8@8NGS_^%2O3t-y_g~u$)`H?L`TdYs?OyX|Ju)#{Kr=&O9?84OfeArCGX^hdEx8-jm{ZR=o3>M_~XDgyO3pv9{;1b z!|jiUHzlotDpTrc7yZJ-eSKe9g@AQaf7PTg%k$I)E(%n4&A$ZKZt0rpyi)E^F+L@E z!(aaF?OmyT_F(rqrXcUMyCl;rBWyB^ z&H;+PpNDyVQ@Z9lD}Jr8t4F|_?=n?itgpj!7$K`3w+WTMHH@b!=I(>ep3peg`F@9; zg3Rhb#-vPaV)XU-o)=?Wb?n^Oo?d&zZ6;+>uBwNZH=brwpL3ZIKit!l!O1n!jilso zu&J>r(Lo;jOUCZR(R`DRF^fBDW;b`N4qSdi81$Vj|6o^YgEf6(!?8CIfk|?vwn7Tb zPCpUBZoI7`@k6HIq&>)&iXtx;w_{{mhC_ORhpfUBmLOOe4EMKwSZk&07V18#g}sH7 zYBYUuBV}vb%bhYzbA1~k0rQtQuJvb)8ggKa;l6r4d+AKO`nsp`D)+HTW$7gnPM0tl zAtCkpef@j5=X_CLG}T42i+@$|blrl6Sj~I)wTZOOH4x1PoFOh~;9L^_@>d)t4%qtrQ;&jH|MQdK!HRv@A z*O@wfYB|cgqP_Zn`*jgF<<-Pst-1#d?#uZ+_rM!d4C{$I7+SfD3I`Ul{dZ~#zp+E- zkh!T(!X&4+eGgx7m2^+5gs0t4SMaeJvd&`4G0!~+CP8uJmf#M|KrqJrLSAc_}I?$ zRG<-1g5FXogIuaHB0*eX&B4q$l8~|l04(($&L7#(-qHgJ#TDT_#JFB%MK>Qw3iOvw zf*3uZfvjs%HuZ4DWu^5$97hL;$VgslEqo|Hfr{d}L4kHGwZ)k1jqgt~hSkyw%c1fRi- z0RyirbS@l7E6kk#3+dkeJStnqBgohj$XoO)_9X=&x_S(L$k<}6`JOMeysqlmMPdnHtJgn9JvpMO>hPl!~UoG8^=W+Ia`wjx$*9 zrzJ6;Os)KPbr8+7L()R0U#kh3Z{E_>giI;+6Yc@%ke?1E`x;8y`wjO<@fW%P_n2L9?2PVBy4hflyh14gW8x@n zTN>f?#gL}h%hQzT=}aav*Qvwo;2H)HW(00~eU7r;(;jz2ST{pIHN#uJr5m~9^Kg`V zpR}El?u1|_cp67-*Ae5o15d! z5_PH-ZqXA*e)S>0RjQ2l45!`0$bxzBFX#VZ8`B!nZeyrgQnxb`CQx|#e3Vc!=P<9l zqT#jClYmQ`mpR)^ien*T-wfmp8w%kd^cZsT9dT@Tb#F(g0mF|oqTMBUvmIO3|ENxZ ze9kBU4d)#Bgt*!hIzIpQK5Di

Vzp^fBL&H|@3%mu4fkS&dY2krJu+h5vwJsOUkH#gJn-4(#t4WJ)NPA;3 z$L>`1`HA(GFifL-(2$o*yMVzg7&~d{Er0&IwD1Q|Ab34!ig-*Ts0~MY4*fIyK>uMT zD`CwOJ9g%di~R)L_lH$uiNzk7JZ4H!8GJZ4zg$XzX81(ZrGT^$_1Z@8=HunZfF6F!WvT zPi}2U3%d+(Ap9&jR6oP2G*}I-IF~Ku<|PPp<*qj-LPs5_CX89_(~7I!#zc$FnHQ)l zP+Im5=J7o$*l`$n8!3eJb+!7$@UG9$+I3+3K9? zt$Q~;{@r?-$jW~_I4#>fI4v;yk%a5V+SC8J=YXVI0Cgv&wu=Rz$aL@o{)OFHFg@Qs{rFOmT%c&MjgFT|EQAvp~ z-?gn_J!EDY#I4jh@JBk}h-sktQJTEMpGGs#n1)DZ5wjr23@S4X2aE8x4GoEUM!63l ztY%lijM^Ouc1|wqAl7sj!dIPN76Lw+cypRmru3B|Cm`t(8?^r+C-_vf zH}wYI_)lY)^VX9x)fapE-k+KZ_rp9jHPJu^YCEre^Nj(0cs?q))hhAwr3cJ>S`(12 zLb<6n2oQ{{FKIBIu}*m{)6uR&fM+l$7V?&#n$26vxR`R|p%DvAgBGkz1JvyqoTIkwusMGBVn@8J}lMWrms-VhV5ZQow0|KN49+z@P$#s!M=wfPGiJlCQ9t`T%!Y{mtkaWShf)`T-i0@I%oqjUp+BF)q1lw=BpjNLmdKbez zPKVMdp^dfakGx#-rl~fDezo}(KRQOf7^bbBu!t=KUZaBL8h3g#q0J!8*8AIVAuds) zyp1sKC{^xX`88pJ_oIO`;7q=B&lh4N|I8D4V5H0T62JHG`b z=KLaW+t+#Ddz7ofK?kpHo-P{Sa~^Xd&TcKvgo*3WwRVJgFokqZZ5gSjV84=-{#JNL z6Bsn=YQg0Afd}eg3!}4z^*HV5>+P3KDQuFh%b+TDR*f|v(*swSlICX(t}hmDHFkQC zS}Q}+Qb!`VJf&{gI2QYkG#aWEmh~68#XUU60HQW`HZh_CYVVz8-U~NV+Y(T%fXD01hKgl+H3`HRk`AP&LA|kSR141)mt3UE;aCbO&NT#06-;eu z@}+x~vfChB<-ECPvpT#9JML_GKGfdDo={QS;S@BS-@%Vsn_7H@){f>2RQQhY z;B-`-@oF$5BhBw*9a?WSnR_=@iN5Tx-cT#DLZSA=7;u4fR#k#S3m~8Sf)@mZxhb(k z#)zis4k~0XkUsE)3PbgdZ3cmCf&m|@FwH)D;#7|byI{tJ?B?+u*pcP?)*d`&(W)a9MA$r<@NDJDQE~4J)V2lB zMqm{IFl*+oAzwQX%%=uqsf2SUOyMkSEzbQOzLwEs&5NF1nfAUzouhqw|=JKfl)?M z*TfME)||89>F>ON9aEkxYdDv~89Uio=om3FEOrF+V>kGBwGCN9A+&p9oX%0Y-lXmo zI>jEi9~S6F#n<#Dkhi%HOX)+?k=)M8Q2g5(`_{QeHR{WGpB#J)Cw=#hevV2*K<9W)W&%lxk5ZV_ud`j`j^qV@HX! zS1xJ@7;tdz^@f=8JV z9HmJEV`(p?ODzm;dTun@69q49pVXdOuKOX27cmo#Kxo~MI0)%*5rK|N9y?V!y`{%S zB*B@%m>kKv^K5f`BG7+2pPV1R!ZWn$j*wPtQk<~xsP!sadji6wdS4vwz7+WN2E!Bj zmin%`nIAfp78GYo&EaET*(2k6=L_lgt8-C;#!})dFbV7oQeucpUm}b(*3{mxJWJGZ zm7A7KTj$F7Ol7!l78uYsm-oASZV*X@D9I(P3b`_qlPxmMZm>k9=!e;_^G5Ys7TWnK7k#xSY8 zi$1ZdYfu-8GOclN%vFKnyh0$HA}GXYN$IYuW&zB9qQG};U7jM-L)HkxeWIsjS3_zn zPjE8km<3>JN&R`}wg@s9^ClUhDW`zrqS^(<^GkPdea@v0AV}+<08@l(;m#w)f(=VwJ7Y&XOpw1IG0yuqrea z2<`}Sq$B)kxxq~PBD_p(U^x1QT1%Q+ic;w$Y+mz+L)_*I8)lHbweSc;c|O(qpINH` zAeTO4v^0F~BQU1k*%=b@9On&yJVDptG>E7;%PhFP3OqqoDAHkPj&x)g6xOO``BqYTPT%f$U%V=-k>2&7F(hiD_a!Lsz%shYnMHOq{9zplk-ho55e$0Jkx^P79cZfoGw zoWQC4Y|+FDUyu-m&fJ5<`l!<}=FSqL32Du=5a;F6Y3k9=f52iJ${^;_l>9YHhdq%{jg8d)NfIFROZ;aVydf<7y zNfkHEmPxv|C#b7KMQ~Rtx3dOb9XMDlUEE+woK9WyyR{!gI$vu=|$>8Fm z5?>Bm-z;J*2_E~xZ@O#@_LeH1vT3rbXhZ6el9gg-+SCQRQR3}a36}P_12prkBqyHP0Fi!R(2s0 z6Q>&3?My43V48Veu>#8nowgt%!`-Ld++l5m=H;^Z$RucEv`Q_T&KYsSZ}xqo;p6p2 zta~3rrW0?=MmTUHNg>kFpk1h;u!*TCUR&skvvZ97Q=?-PoP$85mEynV$1{!v z)8vTNj8oaosxLG34Hp5AVAytYHMT(%L^Z!?^~Vpx^$l&+>1mHz090%1lToGCpN;|n z2?NmRQse8ZEvcMWr9=202jb_s(#)`Hnwnt_B@iJkYkC%+HJAowzeyr?%VPqv;4p^c zw>z~y?#A3tt80ainjF6I0l^En?2hh2k7qEz9tmzscO72^sX&TKuop4Gy=qCc?XojN z1?j5kvDYlXlZW#a#*^v?ooQFF+6pIth41Ya(>Sxuf}B4d(ie0w_OhmN8LKXLemkCC zXpCUR!coABC4ZyPx%Z5U<`d73y|i7^>geF*7z19K->Li}-*Mzd@RTjSr-!D1OlE5r zyUPrjOkpq09)U1-y2OP4JZvKCFlE!aw&A#_3A6vs@(~j>rD-j6Gn>mMI&|VU<8+`P z7|7%iqay{(0nrxYLw)m6QE_bT$2I9KGy|SU;c{RM9 zHyzV>yF|;mc4sgnnBkp80KD07_{*4Dfl`WMxA32F?2-d8K6C{PCs&3t8xQHe(>*~M zWQFXFH{DJ^s}p>1~azGxjJ_y=EZHgT9tlg2-KvYx^q48Tl9bU(n^E0}RqdJa^Sm zN>_3Au-a(yV)@@#R%DRzTSgE`CnLIB@@4~EdW-$^*Ro+(;OcBWJdfR&t7r>d7)T7i5wihwn>xth4ILNb*Q(}`i8eb-F z#g{Rv*wgNGRuez2D*R3b_MZaGswpGuguh!8R`(I)h>yuFY%L@sc&>R?ATlo$A=4siuOF|7tj-Wo$ZAP(irDjXX-m$SL2^l0;jR?2((du?kp4*oN$V1 zl7mJzT%G(v-eIcXE2uyZljU6cB-EEh#6~JF?wcrjLO|#E0Z!(5g22n&OH9Wy; zs|=AQB5##k(&{0LI1BgBE7V(!YE~L>N>p8`I~Ab?X3Ls<*nxSrWjH*)7W*k{P+C1u zzSA}<7akv*S3)wt4DRU#I=Ac(PYSeY8iF#jHJ>3i=KOSZ@3ra8-yuZOw!T?ydefzQ znFx)@C~p3F1zwN~b&Ij|VeZiV>w$wZF7^m}U#ZUcgdH`d`gQ6{O5%eh_R}mlBcv3T zT1(V}D_l-&YU_t71aXG$N?CNSo_yhoIy4Z~0VqyM^tE;S zCWl)uZa6C5Q}QQ>s_~qOOWrF~k^kXSZqbuR84C#%wpI5zQ^!bJ~I8;6wFTWAPt-gDqJXlKjill@OFzJ|XzyC|p; zkfl>`Zk8<*>e~{0+~yLPFT9O-`%MF#8mHNEYOKYz)Ba{tiP<1NxIWG-#ym%T{!Y(W zMziU&PBE%!@iC-%JOy#I{?5uHm-8pBW}$6g6LSML8>@H0Myc@^wpxq==Gh$bAe+X>HD^Tz%cj zRdOG5WR5allw*!D*DyKenCtud{Qfn6?X%DO{W_k{$8%FcRs9RCyf<->ZL5tA+F9^I zOYt3PhuD5$w*}EsYu@B7==g$-4bIEbZ$pC~M3ES$ZwdpWd}p{7M}_ciwX&NrgG8%c zyL^{uyPKkuH@Kl-o7#!i2_}nhe5&1u@tQ<;bs>jNBIi!oflrJWqqcT)A ztV?j!GI;ekvFDRKW~r6!K$F1jtuKbhDkuKA{^q5u3$%+|bZ}T~W-j^E?6{`}Sxk>k zG$Wve1s}T$-Tz)7+k7V-=_xJ%X)CtohQKNhG?5QFl4L!EuC8=mg~Y9>YHcXGHNTyi z)G~P&K@qDKyr4#vDtAnEl{uk5H=ER$;kLF#AF+J=5<27L;)=F27l?53s|vN55Sa=U zxtN$CS)b>hH)75(sCf%9bLI>=y5IB9;}?boD9h<9mR!Z5wIAa8z5?@pz1AG( zjFAU(iF9`7Kl2bejUGohw^DHkH+WN7};a~^xidKua9aiL*t=VXSN1u9z$V$nbq zm2`BM8)Fma`9*oTRX>x~vu((xK#JDEQsHw^Xu84ByaQT= z-X>YA)-A}%Nu;w1&Xh2zZ*ny#fnnAbQ&O(1>%s?o%nh!fN<=*B)`1loxM6CyE(w z-%uFk+nMjRN-mihIQVdUjcXFJd#aZLgAyHV&UB2Nbiy6eQOR4=O}%ydi8G&pnkj#Y zU}jE+KiDV)6rEF2kn;iPqQwhue1y1tLj*{KUsnAhR^4LNv!V9EJ=@AJk6-_CnbT_% z4h4<%UoPwPkM_!B2pb}FYw6zLHoacNjv)SubUdpuRI;sd>+H=cHzcR^2t}{)$WC>n zwVoP1f@?@c>0^yfj`zKLs4}->Fo6 zb8bkw^^pc?(HI%7cyTNvicS=`k=U65*=h4+FyGe|N~sHeZ$MZ>#Mh$+>h`XU-Q#A! zLe1G)f<;;uVSMkK1m=Hv@{rD}60rE1Udq5%|4Zn`Yka|uaRj(`>EknvS3-iHwTmrU zE|gDpV^VKPJ_-wCA3#LWhvV47>a%t>2cOvNU%rSasZl4~!% z*Zk;>uhBlLv-Cct^PekE-@kGSG{GuGYkF=Xhy(Rs=-EP5#@|kFI4eWgyvRgi8vZDC z@AUNB@2QPJ>=S1#VIQII57wLXx247WY6T7`fokm~3H|v}Pkj0x*ng43H<6iF=%aEK}LWkV4cj4lD zb|dQE52{WQ=zF1d>Z-wxPyYi>yh%q)5I#2fXxWjDTn98gB}Nf*k!|%4ADmfHi%BHh zHXskKF2q9DmVbXs9KAa`b~>>t66&l0MvHt)b{8_}@;OWC>2RU(ap-82sz&^PcBl%2 z0F52k(EFvk$W;Dx;=5)Qqn~pb+?{rzn?u7NAD3hOguZE=*{7P)xq`^U9F5yU-<4%T zid@GbN8IRxeS5c@S64{BKZG~?nTxRL_si{JMwyQHl)cA|6rl|eU&Hk-dQ>9oK(XS+ z>wx=L&@1+`(5z;%#N@9U`CDpArnM7oF+<2m^AYB)8-C3i25W$n2!jIM5LwJHtG71p zPEeDk@QR7b3|H&amhL~@9pMQpH~|^@QsW5sZg60JOnQ{S$Df0&=nRGb_>K3GR8hL1 z)-Ob+VGrdm7yL{~=n5nGPHY;U(cARU^@V1-eK~<%?=-r*1w`@b~(RJYOQnHfcrR-3? z24Ux71{nka{;s&$H$D4Sgu4GNv2qGJNYJOiIBHf09-laQ?!e5aCwKx6v>52Lq~5xV zl5Jyj!$pBJhrcAU4#5ez-8H@m^`7meTPvPJvc-M#Fei$*p*#Q0@2m-voDVs6kT_9? z{}+#D5%*l*rZ;xUzR5$uRg zFpSs>1RM)z=s}Grw2(fAJ26kwdi%=9FIJqV>kni1=2ME&mmD1d4av}f(o-)k zA8YXA>BJj6WhL=dt808p_oo! zjh=mPL=b+EqLpZj*4?j1+8T#7rg2fRqKphn&Lrg%pwJaXz;V3F71AltgKYO+Lj{3y8@wq4jViA3mTFiGL zz!-l@g+roF8jM%Bok^g23&}rJl}X2ZLUw&x1G8cf{G*%#k#t+RWfqr1rYj7iPEol2E( z{51*X05!58166lu@!1Fe>T7fOur3vDBY?T3k;8kVbyD~Z{jto)9ng1emtK&h_T}7I z2!Y!!ZYbn;8#U8V<_jj}#5M4|WyajGTHHPkH5)`zyIHc&#C4utMI|nM8UK=-dYv@x zdpdhY+X=tD*ur`Zess z^offyXvR?aV2eg65SX-KA~y!x%gKe7!3U`fD+h;;hl+sJDS&N+Ug6d}y4><0FJkWf z-#;8;Ew%Vqk`q7gzc&3cI$Pyl*NdFqiI9S{iU(bSP^d=A0Rw*kx!zdT!Z!=Plg-+B ze&1fqpsk3GQ`7f6-{QTVM`f(YJf;f-hAiN8fI}tB-Cv&mcTavCA$hsFP?cnWmxtKo zDZ+$+l8Txqr%LCJy>jjSgqpu|va;F_;uj(&&kh|d!!t9Ow+3;-e0=LT9Tg=-wQ!%K zdmWSayX#(X-|@IxmLyCD6`hJP6 zhRC$GE`~ynz$Zv}-4GZy>v!Pbw8QwF=gMbG7JX&QPlX?R=@Wo)q_ltKG4==)S1qhpc{h_-`KSba?nh#J@gqpu50(bn!Rz)WFR7&)n@pHDyLSO`(=tJ}dYljr)%8 z_HJhUb;pq^UHgn*>f*PS*bpeuqFp5BQnzp^Y#l%>RO*6xK`-A<{?-@G6ejo5W<@Xy zV6MZDCHddmu6-jj^4atLkjgCfUe>Q4-HL{7=JmIUa*+EcGvjDc#@u`xUvK0qL?ob%)76k6F26_J0~F@o{)Qo zbIM##wM8uNZoZ|9Mb_&y?b|=$`f;<~gIh503qDoO{p9kIa3}G<;XSD3eMQe6^`vS0 z>@;Zno9=py7`_*DNM0kY46lm%LITN7Ba-w-v%uj&jEVuUr2?r zKpR3G$ud!MRrC|9Wi(ov)l=UWo1_~0O!c2cJVrTD17!X~PM zZwq5O{{NQlFQe-9WN-mB){!S(fNIB5-wiarrXPsdpeo{PWx zmsr5@qh!zd@F^89t0+)h+FXA4{`JK-r_4OsChtl*3Z{}jmM2R)Bb~y>lPUL_K+=uK z*3=5c>&x!fA09JW7MLFW)?_Vvq64Z^E6Oq8%13J4$e~pw|6w-3dIg&SemYt-#K&3a z)q5b07QMgYxZ~5O4uh*RjXuRh zb+fLJI!@N!v&-=x41L-I`d`)|6sATZFS;|#`r13EvUIU>uxg!8G3(+n-u$9eG2ifX z?5>l2=m~?B6WY@nGR2I+^%DDl>YbM-Zu+PieRNniGkW1T>e6sfI)6Zd;MCVU!w;2C zdi@rvkd=nSInXog{XUIeI)QHYu(b8>0#&Wwu^T1P9P~LcVQKQvHuLUapuv01iHlae zXA;ps(sQJ52w#YO;M3wiX>z>O*6~mkXn_)$>8fX^btW2`0i}5Tnqs`mn!J)w?4-ex zoVC}cyZI*fv-aOVA*P-^gtGg!`J@UDpwp=J~|8l6F(kq+ekKhTB zY?th*Ek8LSdg1KfQ%j^axcNKrPyLsc-H1EVI7RS;Qzbec3Sf9QB~K>2&x_|C3KK;2 zLk2fR^7%WqRXlO_j~w&-4wWqVYXk-I`)Dw85L5~7O(-DD;})7Eb2&t1K4{_DxD3b? zW#ZjLhR@^w@jsHaJL;2f@!v3(h!JULG*s9B2ZSQZcJ8)6IdK9a^T1J)L!<1t#XYij zi%oxs?bYc=xkF(KPahKk3*W*JEXg89{9=RzEoh@x-hA^bEOGyvXYEd(2Ge2a;{2_) zK@V3HQwH#-2TGa^-=Dy|Mo5703hh z;nw6`sCKEsX5FrJaGsONVRh=J4lFOvO?p1kb&|#{@sRJ&-CAcqZ8ok!f_5MTeHc_C zUAtm_R?N^USJkGD}3YLNLY*Uni@r)oZQs>+ zy|i8u75#j@vmX}O^DU0l?RI%aaJk%}1^5W_!nQ&Yd!Qp6WCjVdfv{4UvJgCWk5vZm zKxH$juS6o&Ucqz#B&%%L++$GymCZ`RIVYh1DJQ)kegU&he{#A@TpYSw_{s&ibJuWr zQ0!p-KLE#ky(Myyd9_TxG|YcpCo{|Op5l4+p4-RR0hf+R;RD1(XXOef%k2-NSOxd4 z*bV7x9R1FaUwQcAe8zu3{QzY5JzJ^suZfzM&9Xtg9Uo?&hF|@ziI4w``XYaKrF)#f z2`w~F{gL)Z*&Q_g=eWPnk2(MKBiW+%*PhUN9KR=Rzp}^SaV1zQhLv2|`W_KH`BS+5 zTtQEF@>3P9pw6NHPdg4~TJ(?33x;XY3}6RsL)hU%+uMhFpG(Rklpn8ExlX)G-hFv& zr*c?E=f#s1QJI&izIL}Xj<*qVgq9*rU+dm$J>h#&+7Oj(fMx9cda*Hj#l=g}GN#>= zVqwvjF0!SQv{(}(=6C!^3htH4t}BVV`%dh!^zC$<#;l}Qc2A4(mhy$zqH2|bK0Cw; zHRyh43;N({4fAy77Y-=MSKkcX`sx2*qU;)BxKk#wtp#4;kticq(`ATJ;flZ=QS3Rw zp>~~o!C$l`{}=`xp!Vz+cH-CN+DgTFNLL;gibu;!IzIh_8U407ooOrdVq@hVIoC5m zX!l|5r%zYspZ%*tofFWfRY*D4gb*IV$&+n(=YkM_ru7Q@xSMti#Y|#yq~wd&sxRi_ zo_)I4%|IKu2`PETur3&Z&2GSg+qp#n9SdHVrIt+q(~5F+@M9_9OP4(Kg1NgH=u1gt zTeRho5F~m{p@>-V1V!VIo?r$%jTjQ+n-#9utGG^xaFA^Kqyo^ZF`2-XKyAA2uj7!R z|MxOMnD&1EpBLcfpz8xDGgP^*q98L+=-f~wF;eiTBG8!tMp#uFnIZjlts3N#2eN|M z_4DsYUg;7;K;Ep&P*C?wW&&&=EeDaq(<6ArxrI$CvarOMW>l{r_w9Ugo^@);7Zya*YL8)J@=QAmJ7B=QUF>BaMt${M%Yj4Jk27mNfNQ{G6*8!lBS& z=JfuwQU(%2715JkF|u&?b(Zp%Ls}Y5o95ynpvaaN21riNWbX|)VVC!;!6XR-1NtB) z)sS>WgF($Vj<6Jyb&AMJ3FySW=j)2F4n|N+@4qug)v)1(O(u!`94PP$h?Uc+&}TCA z_=IpDVG|Pn0Sg-pb7|36G8q7d*DNv+??=}9dQcn)Zz5=dB8#YF7)63AWI3KV-={{+ zK>+)aTe0S zxa`?toU@T%$?Qv8dbKuPGBU{ZgJPA|SL_>vm^B9eS)r$R#Nzg}9|70Tb#CK-1V=^6-b%!GDOxT}X|fI_5C+W|*6u9cs> zW)~+5_)b|kgriucK;~&MR=pdTjpQZh)Q9+&RCW$JAa0ZmA)QtYwQ2tW#HJ@^t*1Ti zt9C{#9>UCj39E2Ivj0E{IW@Y?DG-sN*duFU`Q<97tdWw>;`PrCno6eLj=!~f^WB$Q zjU^(P7CYMWT)Y!BjtI?RGnievZFqpkPGbdN8}D2qn8<7}a3g=LydRU-g{a>8TVSTV zX<@+WWIW_Oz6>ETH6)NMKb34Ax89QZ;v1E4@a4p;9i4oi4fRGIw&t!N?FGAMFEI2FY)x};Ma2jk0C zoXmtEEjh1o%^3o$q6&!RxU($RCn*K3SA9V=+jFRmRf=erO6z;jVC6QJ61dEkq*2k|W`xL8WEs2mxdICfYaAWpz3tcQOn0%bXh<(;qr0 ziujVckd;B0>fOjW7GjKnCNuuTJBt97V4I)*9g~!o6$FAFQD$1(c(*`KTqMA)18$7R z$veJ$6&iHBq($#Hl(8#B;AjL2>kl{xue>T{^U|14D;9wPS&_ys6huRK24w~G$#ps0 zCpuPn#e9%%$w$ToCYv65G-wjHYH5a30DZ8s_{xRAm_AelH-?j5I`)8|# zJDT()R}lD@o%UujCCaBGfVR(CV3=+Ex|Qm{r6IZ{ zIgr|)+{he*iRz{R4-8U~EEyer9e|Z5?>p6sCj|9r4!#;gOA)V&>sIl9q9C+mhVee& zzph0vkSb6Fi)n?z;u;rrvBSv0p|!B)a9B-Yg>ak~a|BudVI64ob84mHMtqE=)+y60 zrYYXYCUNjUK~Hu%{Q;;KZrL09Eve3pW)Q6ga7fMd!5rpy6rXJLX`SRsDgV5ElK*+U z&EVrXL$yJ19nAnx58~W{;!r&utb{jGcdM>wj}Xzp*NZp=#x)_e?{ErukZ zsFJ^Nr{vhT;Pnm0 zilXXO8fHZUWt^eIz_pZy1E2_65xP7hg%c$JmS+*(8iI=!VMq_~&MT_u9eu{=aysSB|X3rZuI>G8L_wtaw%{{%jPHPf(hwnmmEkx;>dGp zg-XQ`)ag?jOe=WWg`h`g%_miIiTURSpsTHCQ5k&2;uuUma3gITxHvCaj~~1jOX;%*8SW?ox??rQ{AYf7I`^X&7A3{#OM*~ z0m#fof0{+vJskI-AjFH~8#%#=iE|F#A|;$8$6C8BS38(|EEn4?F+wwgO+^6w5?>SfDal`crv<9`vi{@ z7?Z`YOy8-7ajsru!9ben2_HSVkJ_Qu3;)!C(%TTXLYa7rD@CfP9)cm7lC$S_>75hY zBAw>^B`f^^6l6W%1apkUj71-|n5S&mBP9KHeN}pl3KTx2*mX^Zg9`PfgGy6W(&@q? zQ4nVXf})8(>nKu!pq?J%fc=|iJd2PMftj_X`i-XeTU@6g7pmo{-+)$@26FIFWn=-mDR@(|Y%cO6tAfWAuOpmIpZLHhwBXkZ0Ck_n+h+ zytdCg4nEq0-2U$-F_gFVvwEPu-lZ@J?vIOz!3 zIT~s7xf_tZG3pjvm{LQ?{N=fNuK$-uR*mW?@>QnEVaN`n|6vMJum|c#G~1>H6ySuN z0eQLPKY#R&50;C6!L+>}Ir=j}XRIpRKX-0K3;Tx}9~K)%NqGk43|$|uCj1LO^7S;*nE@z0d0!6#gLi->^-7LzL)pw|b{7L8`&qqepSL2Ss8MEZ6f zTA^w!huHfcP<|tk(P=Ay1`kVKK(8cNT#rtm|4!zz(TU90Qf4N{BKjcTjT!@x5)*3F zjT{(#LF!1-MsGn{t8A)`Xf-^q9rADH4_vA!Y-HWW?ZYkQsahSI_Cx zE=KZ3zWLYyY@jHz5h-hP>J^yaP=AU(m|3*&gg?WN zpdt^cbspqzn5TGvwSZrh(0BxhF4jo#xeN9%W6ybS?TqVT;!FWOI|pRAQPcHGz0vG7 zGDyaTMf@hS#EZFCPamV8C1Ub{;{=W(saeSKAEwoePHqIY4{i>Iv8*Q(d?V9#ZLp~i z+V&-?fDeg2&Wr=?@TIF$QZXdjI-xDgCr^Xs0$sHDCWWxR;?>%z!v#oFCbdEKK-naV znTxpsl1haktxoV>wsZdgju23JoJp`K!|(!b=9)}xW+%$nC(ngW5C~dkSWgE(NUQ~5 z;w|L(ztg2LEm4Cx;w`DJP=nNkx`*w9?|m!m^ zSM~Uy(3s^ug#-0DQN)pCVTejgV1XVwzm3LC3m|_3(14yedI|hxo_XJZjT+g^9!S%U z)yo63<^|g$ z5CT_Q3Ov9x&I-UHaF&$rv0S;NQCbxB|J-7?+Svun;Mn_C6KNmpawk6k6-y-qYKOVrY`GAs3tMeUf3ozBuCmYUkSX@Q{wZAZ_z`;9n5 z0zljA2hLQ9@ryYURS<-$UnSAJ14}m7O_^#wuE81Ar-=s{jr|_66sYW>u`p!@Nk=a) zh4|<2Z1_YtW=&u&x*Lwza)7Y~WBJk*qsv*jwd6Z^7ygcjM*pMRIh zsD_d?^pTw=KI@j}ku;$#89~cziqfru2!t#opjsK$T+~gFxI<{mNOyw~oA9hI@acnY1vV~;F%G^TtkhEV%mG9*0$exfrT8t7X3;RTM`(!8d?1onkRwE^5ocgRS9 z1Sr4egoZ>@d0Mq0tb$6wMTp${XOQ?igY(Tn62V07Ib#;$pYk_WfK#+s48qsIuWKoo$+iL7GG8~$ zkKcXHDd~_!#)BgJ5*6PG%6)GJ+dBGKA4f9TEJ8TnSj=c*<#qtEKu2Ci>Md`B{T$fK zD5(g$EsPyM*(wg3(Hw~WzqR*b(z~w&@y2jVNGgd zxr{seRU+@C`c*|b?rs&CoHdAw>2(%wfH3uVxjU&Du_SV-onQ6e<6C>!48Pr9IYrZ{ zWGkYXt@VXnhnP(#E=r9s@TpHA#0@i17*@zvs2#Xa=%WzN4OVHigYPEY4xX)lvT{N# zp~lm`UfC51wFH>hTfKOc1ClNnOpAq8AoPL?^<>N3ac| zWW>RfMvr7Hg<`Wri(($0g~$Pxv(I#&vs4*DGn=?F{Ilmsrsdb71N zn6?epZY8TEnJjP#^EcN`?Q-#u$k>Zt5}Pz>+uM@AqxzGCoy)-^xh3$Ao8-ko8RSCJ z6OP%p4i8!!0>RDQnHW;Hxmrd{ViZ*(9rTL@Bb|IzPzT^7WrL$khO)s}Q4o9T*Ch)F z=Q7DtjCk*^R|x_-T3B{K{=qRaMgf5aA(ferAv{{gl`iUWbE^?XasjUKhMvk}gi$2C zCzbc~O{5b6OSTwh+vsDZsCY0+w=pCft9Js?R;}L$b510hhdO_Qe>0jGN0Y=O;oj~R zDPcLnb^v}al-_g+DQF~-=VP%Oe+RcBqR}qFjh#Bcnl^i{0cD|CxJXm|XrPtVvv;Uv zg=@VP^%eXm6XLlR2blk1*o4g#CDNB^UU$PT)MmlC7v6fID zJsB?B&@IeBW{*g6j_(;}KkE|sUEtKBwIXZ}>z+Mo6GlQt4#6Sylw;>lgwrnFn#ne1`}AlV^t>v zG#s90g@i_(ioWJu(TCrKjI8mX{CA{MLyVBFT4ZW&(%P^>*`U(mZoVF~Af zOd`lp+_I^b0P2VWCaUHKkEw0Cv4rz&D<0<21n8o|{XAQJArk3esS9^iXkUtD`se}h2Vk0)c(kuWk)@VDW*}8y91Hs7KA`P@kUe5s${~Fm z?*>}sxsXZ`qI>V+4p9xefiV6Ctq0rsef#V@j{UOi5o;|T&aOy&+&y&|18+uMn>%T($tda7fOC8xB z0x<*cRRn}*le?hM`B~?0fV31m1>3q%EH^y%UXQP5gb~A9-m~fIJ(#ei7jSdQiQPSKfZ~y$HucaUS`^t4jCyE{l~jjAB~qLL9A=a=Ah&v6@{hX4cS&{i4bvHOOdW`=0B(Br zaQ{1Ua&YnbxfydU8uz6^g5O5e;NHUw)K2rFOrb>|?sQa5xum+5TMaAs0ljxNfKns6 zXX7Ipgx138W?;W-$$9;WXxe1N1NwEubeLAej!Yu>BxEpGFc)|x`moEUwg==gAGHzM z%)3^E8PXYAGk_D6KVEb8T3qq$CQJB==g2sim$rwu&Ta;u$wBj!sr6?=Rc?As0!9-s zFox;uf*HryLq+B2K)OWf0p_Sa3LlO0`j-HvjyKdNIf2{_lTo&*B1{2*19~NP=^4QA^*#C`#|2vAPy0 zaET29;nV~*X%gA7UQcxmyJiC*`U}gfa?SffRPh&&qve`v*fkPS;5&S%G#5GcRqk%O zfM{uTB)yh#-)`~Wyuh~(P(*?+yq7Ri{tn}gzV~hBPoJl(EPTgk*FNAlosFy|K0g?& zQ}F()B-$^-lWqK4Y4}{QvUe_LVT6z7EYk0E?^*);fw7{GIky<0DU!ET^NiWc&oaGSiYfwH z*ug^6x6~h4xgvh#k0wc& z6EE)p8N@M!!v-ay|G_<1Iy2j&ib{?a2x2j<$#0l*(LFg_;^|wmAy}N^Cq*DnLosMX z?++PsRFb3ItukKAU(4r=gg=NH6j%IO>pQU8Nq^a=+MKDCrRmHt+3e_+i1-iaG01H2 ziP+IOtnA9WH6;878nLD(%pXI(ntk7cekrL!fQrxyOyLytTLMR$uDxIPP z6YG$JrcSUMGLg2({xR`(JfKW73#Mn`ZcCMyRuS~oTLQaHoTg^ix*=rt)TGY`BeM_y zBZZxLN#$W2IxiQ%0BFnCH{OY*-(JVF`m}ET_@wRgS*ab8`BJT)uG0nji>{tO z!*SzFNg-!R^@4w7jII(pGJ#1?1V`oT-(V*n8Z+mP>j+|2MPLpH|G zm~k!igQ=G|Ojk+Gsr5VQg#jMi)~HSX_Hyw!i~DW3vo{qRuWxh;z=U_U1o*3P!QxGLV(9`E9cP;K90$+EqW;+ZD5y?T;73s@X68%zfv6Bsv%R zAqDV!PM_PK>T>$aH^sRoH2|UlGux(IeP1M)n|^Oc0V8jg;<&3EH1qijTgKN%Y|bSt zVRS)uTiYq1#Q4};L+Ua73mI`ErNJVJ$<%x2WT!ts3wx==g&RP1cu$;{?mGV_*S3y| z@j+4QRhga-jjf~+m8ja;?LLfY4&sf>jX7?T7YFES?8o9GW3MVF3QHT(`U0GHsZedW znQfm)uy=~{(^D)c8~@w?%@^mt$Jn@gHr{Hx1jIh9k@NJLspd-E3lU7o1AaX zG#Ga+i6sR3ZP25b@s?$0Vo7FhK5{sd{n}2rd3cEcvR=xnLD9l8vYTvL+2Ed6k#tiX z;zvP%2rLK{+)gA%W}HQ^QFFfdL?ARD|~P3 zGwXg@uY6C)g$S4J*$Bs9A8Bf0LGO0l-0Quz79&d^+^1bCtYdvn6827w$Kg(JV?oPk ze0M!(QinvuGiZTMcnKZ-WGL0MFo&^XuKDomMOoLxfQzgBo)oYgCGp~g@s+YNS*TsY zMDdqkmp8OZYcNzeLKui~a>C+ry$#&en!3e|dP1H_WO9WVK^jD=>`!fg90Ey8HIi0j zSDCkMO7|nxqV`~qtaQ0bdN$(@wtM?ARhc)-^kgcU?Cmv`db3HT_ldOpT!sGZGqMA1 z4U=a2&g047quGTmUvJAzpM9Y>%imsotB5=u588*^TB5ZfN_C_@zoCoE1C24;o}6Ll zq5xne-bpRXA%^Jvwkf#gJhQ2PIwn^!3p*0gIJ~f%J!8DjhgqBP{SWvCI#=TV1KM5S z6WvZe@O{+5c!XsBW5&|3ri1mBAHm~V&|N$D*gN=voWx)LFpoQ?*~O1A1Lce|o2y2M zZVx(@fKi;i&u5-kFRaDCn2_-)CV5=q*r#y zHG?8v$o#`(G<0X3qn6ppwkq{HvE`DvZ_SOyM@Mi2^GcDP@X~$-cX9eB91;5^U zrX?r)O}<6DkzaOFr*-?VP{C97Rtx_7=X;+7u4W$A$qwIi@SD*UwjD}8OgH`%doLsM z&LRI=KlJY!8Qd8I9^De9&7Sp}H;nZ3J7MB=Gc5)O$azoR?pnU}Xfz#wGwjm+Pa!rg zzKXJ+p|lSJ7oPFhuWOW}5A%8?@pl@XoaTiHbircDz9yL&0%rPg5bss0ZB!(8x#nS> zkM5Pp+D_RQr@TAQIvk~}ftd>zL8pT@so`aJt7rV_>SKShEw${)k;1{du|-le&3}k# z+FU!VPNfz3KCz#~!t_s@&vfd(hefUHDXg#Tp0B);omMFa!h?6@v#imV#>|{!ug3BP zu|p#-ww2yRJlQH*Lrk)BP=7fH;f{5Q-7Jw76qKr3@bja*(sd-CT~O3kAjJtz84vH z24$XC*74eFo{IZezmP+o{_f-BzC&^UG*_PHdFo1X!oE3_4~*lvN=T(L(#|r^JvJ88 zj9rBCIWxXLo8Fi3yw?|V@73oHU(=F=8<|P)%y87!9&d;3X#K@B#A0~e_DmvkZ2MN< zHWh)&b4tRMJ825Q9S=3_h?V0s>CR)_vKtoOUH1R@ohqG;7JH)NGZ6DuydubhwJp9h z(WsyHSZg@z)jaj)7L`*I~=Sj$=C_&L2du43{+s~T-r#SZm_OFGaGN9}KX84aiXO>u$*e{C=rQ9f`Fve6**A6I)}b?b z1g@+T^l}GKO}tgo+E}yEwmOSF(A$Tb{^+l`!2RcJi~zS0T#E|UdKIXB!f4lJrb_vI*#*06ck{Gx9yCv8wpU~-U~rq1 zBEVb6uAdbEO0FE2tx!QL=BdLZ9aD!)I1IaCdt_~OO}9eU=MN*g-5_FKl?g-oV(&n@ zJxzS*^IFv}7>Og0yL*ptLf?y^KYV>P1u~AHmtQNzWR{F_f#RvG>=%lMu{~78j?^=d z{)UYimRb8Q`6UvnJtM0_G-}Iy?Uxom~OkDl6A2I z14Mn*qs$1CkMGUYL#_o=KC-^lBxh5(@IN30V5UZD`5qs*7<<-S4)IGL3)2`+Z@X^KDAS%9xQDY!hbL&>v zx?3vElR*IoJ(bjFy=e{YC^;f7AK{^TLZGW9)a;{;N4 z^!A5ye>XI{A>Fo?t-S>cNXHUu+cpGX2r?jXNY20htroA*HP=FBd^bLI+-NS{rwE<&;_Al0`v8s{U)^kyS1KZL;{j?aOs0pHEzdK!Z`sX7RrP<^*ov@PO^* zD)R&kdog)n|#^58ub zTA=gvf>Q7!?{v6w*)g5&72VX3!$(PT3v$uN1&%EbkNkx&|x(a^DgXC}W%LdsZC?$?Pgj#ptR7&B{K!916@Z#FY?cM)!Z2QW~!6*j^f76U)$43>8rDC*cp zzS};+iD1{U4qjCjlerP|Hw~o?(bJ*j7G3@&wX#gvGV^f(J;YIS6{Kyq-a>W2$4D_R zY zu=Ab>C{!l;>2H#k&qE7L!N+npZPNM`L0(gB#@( zem~QsK3_@|yP+oMUaiCt7@@ZGyh`=)?2ux|50i(6nl2$nDQr+@8T^6WWfY|Q}I?~(q!cy_q)k{-h>h5#BN#Nx6z(Z`eYrqhu7*dvkozhdjFuF13S8S@j; z_x#@P)FsO51MJkk{to&a!|_4slcVe7uSoY6ypdju5jIruV+fGJ52owk-7V?WYS_S1eL74Yi))k(yvuWAOQ{2MU&zUVQdt@Zqg;eVZo3tw{mn zXP}%_#>&Cq0s<-B#d|kLDl&Avh@-Z_?wcC-2k*50&3^m$%gPr>jkBlN#^OO+TdZ=6 z=HrL&NmABA)x~JEW9@RMQumy6)gRd~LM^32n~?E8lFr4E$^QTU*9?EVU?0Fgd8`L(%KwLHHU78Ig~>Oha^KbBooS+X*5gD3uD~B>+}8n z3EOpD@AvEQd_JBuy-2mh6Pb_LsqX*sQim6yLluX{aUsi61nE$4yDs1MnilwGc4u{W z_-=4v`}^g+!PXI({(xTkN(e0zG&T6#+B@fNokBCd_a7jFc;G79it1xL4X^b(6}McD zuH}qsny>S_`GrB>W@-}{UcOrBj(^q8y@|Ya4`%n5kFi~yNJF3sC^AC9;Jvl&=!LB7 zh!$1lRw98 z$ThCirG5JwMKjS0_+jxK(~XuCrUp1I6qV8hR~7l80xymP_%+k-m$dimTp^aTMlHnxO||>RxfZtaMKOHg8EAL=%*H;Ygc$ zCyi1TeKOuGo5f6|&$4fDCA!q12g;az?{XLleCW3Zwbtn(&Nc7lUG)w%DuPRU#J_2= z)5qxcX0a+S@szaA#+|>;gheCEbRY34EOTgAl>5c})ITzfe?aa$Yo<*m@}m0HzCRRP z$k09!adP2yMUTV1 z)l`Z3CN0|c&t$8;QF6zvobloN$BzGDSepJO#o5;}!aR(FW{j!bFQ~lRmucZa8ZNh3 z&VYttSgi7hfWd1sM+?0F{h2UzY%}*zQw`GpfY&W(ZZE1#r1stMyg7<@y>E`b@rVAl zxxL!2;<&bw<@(VToYn57t6wFRktr^~e*lY=Fw|%n4Swv4H@8q8>MF;t_#zMnZ_m|&Gn2bKj~wR{ERV+TQ7}}yrLyVsbJ2|Zz0y@uel#NI$NLlN{y-2Cz|Jo zzGuI+Emo_A{g{SLZ5@ZWU%dLDrN67AY5$%2Vx+XagJr)|qxpNc>jzA>?2@LA&So=Z zA`{rRIS1UQGnZoW|9)Scn*6vXf)&7^h6qzVv&WA5rfr>U{2^TggI?RjmHDX+JVCkN z%e*jg^|7|8QweB3As2%sG{iGFwi6i<=tf_Ax?NRmSpL)c_YbIVCirHXZl&n^ee~7L zYQduH2j1orMx4*3wuVEm-{Q%cU*j}FJO(Q6Og~>lpTwLUS-O1FaU@hQRA!dr;RW~f z>rM@demX8Lj$^+4YhaWzo7*5#jkJx z1S%GVcF9R}4eM4v0|cHisgF|AoqRHLqX0USoRJ4gyuu3)K~vk>Ujp}P%qtuXu`Y{L zg-H6Ro+odX%!tWB&E?i85JK7=DvnIP$fQr|z|=>ad2!@C87?yRjUxN0LygAw%m}ta zY#&5R`m%zr*!3oPB)kx>Jv=^FF=1t@5OpiB^Fa_0xDPVzU>h6LXpuqv!#=+;ut;a} zN~OLGV1hr^-$MtBw0{ixBAw`6WVLK&pnYVGa&IN7_7X0RU5Kp~RDOTf?m<*N4%rUq zx2)xQv*GF)lFA?nDwone!+mQj=N}+qA==vJ@SCom>)I}LS^<2f#W)ye>_$-Au5PIE zjv|iaQ!s#Syw6y<%W>@i7b)WK3giM7o=ie>x`xIch^xE(HHuyfX8&fc%Kd;d82K-)h%k3^Z}I1sriW(nQt6t*H}l~d#G%udczOI)&_t83B-+e%Pz zdlh@7NyPdItId=8Qyj1NN4xlyA-q@eAE5i3HpLIB{q6j=FFQ6ARRi)K)v&!~m-fm9s4#)pPt@63}P7A3>zV#CDn{D4t z-PClfTP!LdSG#$?2i1+T#}fmyl`iCP74?*2zG5x;Tn)$WVoonDc*RI zHW@QQ!{oudYIf;yek0np?&gndkDV!6Ob`mUBArtoW{nyA3^tmfFX=oP%e$;Vq%Zed zjDkpgKLM3U-H6L=ew@G^L+%!eqnz*lG9`BBzaC-3cG6$b$R zTd2E!hWg@5vXPKwFb4hWKK6VTBY^^j%Jb=w^aC{=?hzuEdW%ILWapKk+iHwPEmx2U#O+|W03q|l)fepoJ^FVTT*>txh-NBw-d0P7)ObZ zWeTu$k@Q)|Uk9zrNTXslqhhZ2JiJo}m6yr^ar>M`Kj8lRd_;4l7e-t|Tz4e|Y;=-D zGqWxqY>xC_>%t`wX>T28Gwyl>0wj9IChQ-;YUBA`RZz3lC|D?}6w4dHo{J>17!~cy zoVKh$`yW|bVVI`2Hss}SRx4njRwRdU#(>*dT*>pl>n2}^^HVIcb$(vO$002z*wK)p)8L-c^Cke;I@~OU!-a2-N#_~ z6mY1c?U7Pw!_`YO%4Pc9qqGa;qln^2muk}kzr40J!N8~Vi-R#2ZE8y$$vsLynT2s` zw_GJAY8^ETyckTu_Owl_Im?2>L^T!*BMt%EQ+x+mT~qvkugVX!H=xolT`$PfTb9uR zGq1;{EMi*-J6k zA@bhMA>f3pK4g8pTk4geo?el@39$lKH)lZb02=DQQ_H_lQ($(XD9lO$ON0Nzi8Y%( zjPNjh%f{hwIxUHZl@kL@HB-T;U*J9kMpd+7O~awxJ}HtXmp2AS-)w~9 z6VHn&?B2JPAast^1b#UDfqQ@0U;%~488`SL!?Ob^8bx_#fTKOAKtT_dR! z+PFZu>8(@>s6_wtX45PuLiD|GBc*h+vwCb#)kT)(Kf)8ryq%whI{L5PJ&5 z50JA8S?n)cu^D%ivdkHAEbBtxM4Rh`d*#_V9mK47n>2XyoxsLwbbnEyLK-V7{7!X9 z88FJbqmIG~0oW8$UsvBq=wOXtoup;K3ibEXV31mYkga27`-e*({C}rh)xIF6R`-8^ zfrwcG-)IHOBSV{%DfU4h8js?WP&ywifM_WPO(t%cAZPukR@>E=dFi?#>;US0DZk%5 zE>T-8))lrW6oPG7K3P^-LQa97Fhhdsx$5p%A-~41kLbs^+YT(j9Q>pD$O?%dYOE5c zleaXWp_n!8kSEaw=m%{}6clX}QAS|qL9cqB0zbzR$}GZ_SY60{7iHp53?@%m*0I_< zkRj9nx49Tl=>dFxFB_LT5FEjaj9dRn$fx}@1AtA7jAPRC8m~iAOj)R^`JMtSAmd2g zo%>0YC#{jgSnRFhR1}(+Vp*o^;q&z7r}bfEHRP&Dgibssy{knn<~ElHF9h7=4QfnT zledJQwMPK8)8be7y%B)X}^qE^kzl`t)O{d8=`Y+^02BTs5i?_z=YWc4|! z!cI^gNcKgou~@=nxVfMkjQmIl^>Yo^)U5f&sO3KwX}-NG1x;cJm?%ya6ZojpByAjI z<`uTOsZ+}zMj%l7ahXOLC|QU&=r*Unci|=QSo7fP999KFxf9x(Fy7~rj!|Xf8szda zopGdx9CFA2Xrp86Ps9qv1U}{OM7gM0Q`pSFh6`kC&i>1KjP{Um>LKG|Hg<7XNPuYq z=saQXf51!IJXr+?4L;&KBRD)@evPR7us+is!541D6iewB0I*9R`kn|97$Oulti-{N zn*Qb9oB_92MU^#Vf1(6oF$RXMTB)+6gW*gs-1YEaS$$mO_rjJ*0Rjqkt(Qei`jad# zBB0E7x zI6_b!nmL-s4iSg89�g$JX&JaxDo`f&=lR@NOdWQeS~#yz#?a zfd(V2@Me!frGi=w6v3BlUN4)f(hWiopYwESEguZTF7~Wr7*sqBfQj;p1!A9c?OIids6Q?G-Vk?29Qf<_)5?wcgsC3^WgdOD}*iAE2T-AuZUU5~Mw4bVffn z)kGP6#{6CpaUugizL5(j5APs6Pv(CKqp79VP}X|m-h&6VI4O?(7}HVA4-8!Hd6FqF zr^-G(oB9tRQ8IWqAk4{4ny?|T(HbU;5SFB5BP=_~g6tf^pg%5xe~bS`aa2AVY%Ce% zoD}89lU7eg7i`F%d2Y*~t^k+8@VLb;i`tDhGATV6WJr1{?LEmFc{#Y2Tdgy4Szk+? zJV~1Uy9T4lSezGb>KV#?4Yrn6SjLJYqx!=|lHmo0^JhC}*nW?%WfUdie zWj7k5VCwOYgAIrlMmX5SA_PCq?~PB?^bP&rULW%i0t^Xr~ni@OwrX0VSKJF09&o) ztFz<7qhIzhA{T|$=>62i{u+yn-Ky*{c(lk96vInDq>^$$WgT6P`ngj2xOoM@-73gpI!A&+$%)Z*$EoCWVa?%v<*w;9& z@lFSR$}O(^HB_7#M}HV*oj(AL`2o1C8lw0U>i1~g*UO}#%;aD z(rN|EoHgedFuRuZn-7X|YbPizA}xkGz7PS{ML53jeu~tOzLzIkec=bM0^$m{y~L2@#em+v46j{f zRI;gZf}b(r0EMy94OkhmhT_13C3{alE~d87Gi5)29}QO}D&Un{pNIl~DHd{2?J zdLKEFx09nals$SIc?&8kVC~CLLL)SpXiq=DO;?fK^#k;Q!H`!|BmQ0#?Se}5n4zW`~+;x zrF!?n{OhZlWDt~II|N(c1>@dz$6msCMN($1W$KW-$?y=c;3#mar+Te&-pW!EdbKnW zB3z?w@Dz>fl7b~J7D%VkAk$cQ%g`NsQ+ILuDo0f%3$}li*h&$_^IR22{jmT zu-lmks_lSN)(#BRaIF^Ll`A~c^`%AwoF#@*T-9&0T5VjtbhIoOU};F+O^ZpYRDKpQ z(@RxQyiV|Z2m4H=Y#P|ADlsb@aiD=op8w;3caTBOoA_B{5y4TX!jCWU%t5|UjD`S5Sf z!$;=31}1ld@cF_!3==IXg~f(xs_gcb;-}q4nMLM;XxXL4V;YJ<#%VY!tfPfg*NmTmPwGjH&#Aws1s!gu~&@J30h3IPgy|<(MHutkeRL#FQ~G52Fjv5HLc8y~h<2(hRMU zVW0o5*^xb>Zs3H@c(oq;2KWWiGV$TDX5p={?b9xZ?X){fq=6o2!p~29_XYZcSgp@Kn3O;G& zCy-#9rXwQFZl_xR5k+1E)`1z=(*4Z~4^nmQB=6%CV`4vKu#6K|{Jp|0GV+do$rM+b zPB`FjAjRKA;V2B>!f}Xv2{>g>LUIEV=!I(Mj_EusWAhAh?c@Vwze+3Uv#pV|Hx0@L zT~Q$n(95$I(Baq{1~oMn9<@=m3kpNhFv3^-=7Y$+C&&w5q8thd`?Y{Q)p8cCjPL9B@uSa#2fY3 z7Nx+T12IO$#8h z0&kH%WeEXIR(W8`BAlB*&j3_Ha{9i@nxaik?2&A_)*TL~A{T6C>9&MM<8A_S=M2~i z1DRJi9gyL9uC0e}7-3a28PEzEu0_J_PpO?G;_Ae4@3bNLT3CZ6P+^0+#_9?VVQ*`d z|MKWyjS^FpEsNbv>(f!QH(T{&GA9U96?q*?BxkQg%*F9B)1svUnkho78Vo~KYm(0o zQ8L&Z0z!;i+Ytzsvl$rU;%LC)pi|cOy8eWj;?(N+>&{0JM`eS9WaF}dLp?#Rmwgw} z{{*RhaB7EA7uTGW4%qRXPz2Q^9OYl;C9gi4T1cs~DjTq}76GTk{W{n?F zK|yyNsNLFW`@%$4S5ek5HrGA_c>h>h(agIl1qRlEH+eyF2%%Wsskt=A8cbF77AcRc zPFtT8f^?71Mh%LJf?<&6|-*xzIdPQ{%SyvYmt-DeBL7PJ0KY!on7jdN?_hQDvr_<_Tc-}! z&N8}zJw;4nlZ(T1l@r!p6)x5C#b`pD zJbC{;$uP&1-<$K%HMvno+H0q{W|{e_)`{|FC+(v`=t>bEnFlfwkc%Tk(8ePj^9>^o zCe8K~vPM*DCuvv_$37!Dy3#GkbjS$2>4i4Tsc~+ceZzWeM)$6pj53brO&paAl1~czZXTDh)}Up9AX6RxKf9}VA8yX|=)<)4z>4rM{UVYK z2FU*b+Az%j{J+f$QJd*pN0=66IC=P+=A#We-;_VJM{bI6rvKmH@Zf_wwTc?R(#b^d z_KGrG_^SG=2OyMxsS0?#O~gJqNR$X=kE&6k7y&& zj5NG$*^gai`Yjm`a+l;2lKh7P1_~K#GF6RRednb^Bqr4 z-RrI2d8&Iyfdaa*BMoMswNmW;$aGYr7Hd28_!GZ6PJviqn|6M%d*?>0kAs?}hN7u@ zPF9}uxOA$I|ACt+2}m%&+S;}l6@NQI^ZIl{a4ci7b=UozQO`W~X|}1kdUn;{M&z9- zJ4)eDCZ=u6?Ri$Wiiy~_LseX@4sJ*T{Ydc>CjU}X**s&>>Xw`8_Sci%%RIC`B@sM~ zisj$GM$OBzhEpcPF`SBMMQ!MjkJ~n$$m$0{ZvnqmmG7;2zIQdzf*zoeNnFIN!!6(Y z&pi}hY1jBXkFQKcft{EJY}~q3`BKS-&`BxbUCef8A?69u_Vc`$DCo2So^BZ_Rf|jc)=n z*iO!Si`xnLUAFYT%8C=#yHla10!{&kz2>eYv37LfRFmt4b97fYx$QQM9*b!>QU( z>`9`j7TUpM>qLHUKKJodrCr6PV3s-(1D6~2<>Kob2`?$UOt&YuZ*DGMV zEfBf}+}U+#wi9vF+01}@DLaC#=W+Va)+*vw)d@k6gr=u!LnZAHvh@*R>Wq!hJlT_b zhd*mt>9#B5GN<_U#R+bS@M+ zHMpOrun=J$39`$)vjA=9^K=%2){OZP4x^s+o8t3qj${;h$Y+feLy<<3pD_W*2Zl^fMPSd-UA_q_Vwqp z)a%-CTV(lS3RU`$@vhRcgw=Ps_HoSxG@GXfec4c6q!P1oa|fKdIihDIVvWI2I+|z2 zE3>1j&JctIKPc+bC5Jxz@$X?v*yG1ymWS{cjjsSX9J=aWD;&yi za;R@sht(7-+e}JLO5S_X48$>hGHF&J+eV0ptL$wSPgcG+5I?KLMf~NZIAw2f7K#d4 zC5aka*P!6_wf#QXBRIpI|7vhct3bRI2lMe3iNRE_Z457Nm)wr|80-9o*jB z!3Xe#r(_C8$^?30RKKrb9H$!JC_m8k+ALo-k zHSO|C$uWy&KrUV1IFsl=UHwdj%DlS_@&ycfg-=EF2N4eUbK%Mh__zC2(VxWbIkCNx z=*xBYi2H|RCEs%3{7ZMU8t*KAlqXzUoT|tVM^$;MN4qKH{8@K^SA3tvzOC2up_zQM z%V3^*Yj)OiU-Sj^;y>?7lg=NR;4z|EHEZs5e=Vgpz44RhlOt1`bu<}}IV1O7mb-pE z`_Ycgl8o?cCa7*c75AQy9gb-vB2;nuaK!I|?Za!9?b0I6fmpZR-P`sC7vn=q=b_AK z8eSoe;g)5!Hkq{1UjK;@?10jT!w`RFBuJ|u{rQ@LeKc&OBFsPPY&mQHiKKsZXJHkZ zOF!O~Fy1OA@1MD{-_CWyI69B0mB)+X4}tVl`Oa5^pLRzVxjEHWbT%I2r4Wa}ay(w}3DM_BnEq?I z)q-JyH2iU(D%URj(3_i24PCg%Vr-Cp$fmy8*=T?ypL2WZ{$z|pZP^aPERYczI}IAJ zaoR@@K05g$di27>5%sth<>9QA=GTmyO|D!Qk*K7=A& zZGIVvO03$;FK)kG51B~XcNe>PeOrFvyRA;z*>s1qggWVvhg<)a#^j7SpODZR-)oiN zDnkY$U2hnvG;M4U_|I{4d`CeOTZB1iu=JbDtg)p$sZMKG>2^OnFd`S=USt;OQ=_?j zIkgBe%IT;>DncY>jKh^5I*CD=v1e;^S}n96yqyQ^lD$3^1q~o9z|Thhi&37X*@X3&Vp%;9!xy`1>@e%W zAjH%H%)WcmVCA{WEz(s}yY<9wz`{?Tu1n%9DyYLy^{zz6t2=fFTsdmvzhi(6tFc4- zeeIptI8_iExbIctoDApWjBx9e<4$qTt%i@UZyG4G<$rS>;+Tb`aI*&wOY_oTpXhS} z*y8+C;rv@0?}iAM%PBiH2g7cp8Uu#eNJ@tf2OVphY|zZO--{_1#6y#`F)WUYYHb~hd3z9-5ClM1&) zm=~Yr_K%`Jy|3IM1S9PEJvkd_U9xPP-7RFFzoMG2z0}Ql+S@Zf6waF8YVwDy#%32o zLzTw&BUARM&Kb~fMkf^XRaxxtxP3Wa>3h>CaGi0Gj`j5{|IuHlaE0*yTSOn{Yd`qW z5$mQ!j&Pb;`xZJ?aOR_m{BV52aBp%j)}&+5OMneBG#bd^Ip=H-ZZe)+Y*&vbALbma zeQGGSIN$Z{QVayVY=@m6&z`?uNcE05NrixHMoQ@)%g1sX3}GE0LYxK$5W9F-jYV^B z9NOH3U#y#XL(g!rd7_?4JoNa_dpBO$_e58ZrUhFFhq)O`4pd#YeKRZ<1> zKcKwo{#BZaj}pd%8tNYx8Y<-Wy!|mK^Iksr1()6ZAv>rcq^;}#tMBGfde;7n{2lRl zcyCX|`GJ21OCO|ebms?b-LrypnF(-uc5U007&?;LVp2eb@}0@57HaeW>H?}N`NM@> zgU9vF{c8+0!T9MW9y%!I-Py3R($nEt-BcOD2Lih5SzM{@ul@JG?pronFGlYEx$Q;a z@V3D8Jkyn5GG{-g4eRb91%XSx%1FiWo+lwDo#sU{F);DU_k6wGoz8>~eOcJWG3HRg z1%;dtOW@L_0?@(f;s=*`;d3q{ zV6w(Px55v|Kj4FD_L4=ILf3nxZd%>UJF0IOrC9sB)#h^p(Z}FDluG*#;HoH)6?7&O zIW-eGBFGg@wQvrDO0Ch(TV`l8btftX<5O*dnoDn=t=vxtKx-d=t&RZTJbPzl+{Tg=pBg-jz;tb!yVh$y$$cH($0-?oO|KG-npFIhKu; zAMiO~Ge81|AY6=jm~ianVFNiLabs!+TT!ag+;@0bncNU~bMh}<>QpLapBtpApZ@a3 zc-4lq>6S{z7KZcBr~646ZF>R`>T8+{D`jO@JD0vJjemF8y z*#>=Kn&W>GyzTmTNncg)c7}L=Qds%@<9UkVtF#`h!ji)n;HAAPDXV@{dqMkQ{qs{p zwhL-Ix_5$pi`$ZyhhNu88yuAqBoc*9)3{>jpFei!gsUkeP4Uae%)-j=jzJFAx~paE z%CAv>fA){(Ol~0N!F)QUnSXcX*A181_Q1XSF`%?7XC!JX^SNBlg&Q#sk#(mu0AL1e z=u4;eTPA9zb2_b6XOf>IYj#WZyuRtNb2Co22cq)jLb*#=)UigU3gh9<|GunCt-%_0 zrWqfCcUTg0r{ZfZo~S4;{Nfs)4?0oI17(A5SJ!46GjBUGrK`>8q~7YdOv0-d&xXA_ zIJ7$04zhJ@Y-SfUzE;X0&8ShY7iGMdYTYsQZ*#G3UH}FeU}aj$ ze>)sYyN$mOEd&lHDqTIpL|J(7f-%J-ab<^3bIvfyAlas#7tr8{|>brave4zA~1(qUx__4K7{%LF-6=#RX`cz^B^0*AYAS{K3Ik z4PP-KgiQSp_%`P3}84^ z>o+3$4Cg); zeSgiY3O1RY3SF9aILy?=g^4C_srMpwrUZ$vsrIq&3i=~yK+{fQpJik%)kJWS& z#fiQwX(;O|Q}Yi!bOoCF^tLe7+2iD--ItYF$IGG@R;DpJBYSh2Z%PBjt;$j>n$9^jGDlrHR-j231y2v-|@Lla5!M8m6tOwrTdN2*`tF^1*S_&2oO7{SBTiv4xdK^O-gtxtLh)WSKgZWt2U|g zPQcOzbeSX$)_cy){A$BeGxMfboAHk~D?FiJ*U1Ss>w`>~y?hnmMK}nc^|`8&cm3vH zUM0Mq-xZd)HD4GRe*gI9s`IFoRsStF>0njslLJT1B8e)jPyVH^G7(VKRc_qN(5BH{ zU%J<#90xI@O9i=>T+%PSuP?!gBRa^!m@?cKD)hAYr{hSl>y^{ubBpW!71thrj;^x! zWyAD!aBvxLJ$>$)=m?wesXKLfCw2D>g>xtguhnVTS{bBhaVfs^!W$ZV$m}kQuea{@ zh1^lLtn_{trcFp)Z1wRY-Z=I6myl6rR05qsXtyj34+}5(n7^qWCWomP-0C9DUaBwt z=kQ9ax_KR5C%`s=*7E!N`xdABvxx&fatM~ASq>}A(_{Ut$i%4Fo2{Z{=(`p%Jdl(5 zFFa#rAGZwzrlb2+a(9|q*(toD>EF2i~-p+=4~~y!|E5V@dOAi zk~H*=3%hCY=a-B1T@al9igIf+4x*OcHxjZ5^J$q@A^!Zvd^-eL8atHbYOdv1zc8%FO=cpR| zq28Sun^}wuOiuog%gt9Dz47_Iaotx<`}>EsQ&^nno$;6o$3+jXA%Cg@`5dv2(t0~C zap7G@TmDrTa?-bAY4zoGi9%~e^cDI4faa4SSqsKH5|Ggic*w<7N|=Mi6NHRqgX8Bf zkmgF_G)Ah{Q}yWQSc1Mo+QU`S>bnJ_@ty|!#2?Q#>&mbHgE;f4Z079QzY$=(k>A^7@XWrtx~DcxfLni8el$%p)fJf;UCV z2UKp;I_vX(>BD$ZZ_kI^|A2VPOta_xA=q8ieKXI*t^ONmpIcZC?W#lugkD6~Ou2Ey^O}Ff=S&KZ2i17~QSM`rqf5tj1w6<5LEO!T-FvJ|_pN3PnpI%6x;2$zU z9r}vrSrE4JV%-)FTrOavuCNPk5R^{Rr>G4IK3~O606(yzwq70GDQF) z5x2-}r>Mku`Q8duuzGvr!`f_MZ`?oN;h&kHnC1M@ zD~!A5J{{$MLp9Yz$#`>4vQoiCtC(K=hqN5H@mFEX?c*{{dGxXBU2bn?xHN-WNi*G;k3sxU+8{0~an$=DvH3y^kLE z9m-$CR8%xxIiLL^@a4Vst@h+IV_RX!*v!wK#D9}M#t`N|J=eO9vdGqzW1Au&T?WHF zFV4iX)G;W0^S^TT1Q_kZR{`qOS-$D?^&q$=NQ|}>&e*Z{ASAeA046Pn*A5}a$zR$A zifi@xg}`4d;<}6eHgMf_x(S7Ku|afUlp#d7%`N0@KLKOe4)uEjHL z0ixoA*)`G`(3Kbf0~cFQ-){jf?@*0BWDT|~9M(Jb81YXWVzmHD&0U_g%=#v-yihzd zf4XLhHRCYf%RJuF);8hbxBZ=FTf2*BwW!9Tg*kC1)OT`oUTB4l`c8hQRGP@f%hO>M zRvf11OKkY(w{eQ5`Nfl4>KO_z+>zlw{Z5&3?MU`s772O9TXP^u`|Mp}(kfw6q&&e1 zu=citmb5`p*e&J!AA)!+q%X=*N|)RKhDfx71Q2j^d{(9Dtone9klykVefxtDR#9kk zd7ZT8h<(UCITvE5simHeP$nnL+Dm7`m>Q1z)RF?@9kKtWMqs9) zN;r%Vge*T8Pyc-!V2CCae%xD?`42e6u==RV^^hmj?F)8Y8SWvgy>*ZukgvmWm1$M8 z>LLCo%+@2F(;mLfRXaTyx`PI*5sAuuog1UbkE+S2I(O4%sSlgM;KuP~c*rJGw-k!} zd+Vj5;pg61d{>OY1>;AlA7AP~E^Fw$q9KS-`a-GkH@Nb!K;yeUaPncx2N1db)W1YVo3S(OKy1OI?X;}V4GOzMo}=QH-lH(uFyz(q1llL1!Awu7c4aY;cQOCg-N zfK0`R%^w6I84g7`GzMVuWKs-uQs2>Ah9${lqC!3ZU7F*;muH+)3SL!-xmtZ7)6fc# z_N9RR5%_{04kKqBws3~b&?GJnXj- z*O5|+5PmZ7Ahn5?PWgrNGwifp5`EA47>Z16!qXjIo?M?>%v;njbdN>PA*#L2_!ys78vqQ1fA*g#QQSf(56 zfFMWTT62hu3^SIRL(jvfobCoiK<6R!@0!XlIQtxfo|ER_YoSF__x{!}h3>PqkL-p% z(4CN*h!7PoY`>{V%L^6uksJnSt@kI+NgD9nw})C`nHtdCif`ndga4f3=N zS;yExr`y(}oF_p*tta?T#peY!jlgxWG1`!euZ#hG_`-jHL!rU_An0c2&E_dsjqSx! zwcA}kklOq}6*Z+6${RtW9k?8yhV1c?+8LI(@gZrUc%jtoF^1FWDk^!VQ$MA-W`!@( z-A~Z+C4eu#x8W|kv=TzB)33N}nVQScS&m->z)0te4TDAgR>qh~pe_WL1b{$G;1u}* zL%s15EO2=!gFc%5k*E<}+l7N1H_#=mrBiw9WL$}1o#WVmKvjg#1Qa?ElcL{~F=woQ zsHoZe2Phdy5|53+7&)LeNQ77^N?m%yYI2GDsm2{d@k??UrGG=D%3Q2J?o zh1PixOOZtTQ*_}u#Wgm##|0?)!@Y`w9efI{@B5&0atkw>sMV9M_Q407j?Jw5JY!@R z5UFGgw@6#+%tv|-t`k%Zr&tGi+l^QbYZ1Rha8MRW-_kW9q{OB+j_oPp8^u~p1cHx) zf57C)E;1@LBPT<0EZ*==n*zSQ-9+>w8R(RT?v%Ukdw#-9DFSR6?ULXI%^`cY!DbFlYDq|<8^e()5)*OB_k0?yF zRjH~$peUfeJJ1#|DgQdeBnL55DZQq`S=;%klEHq6rH~dvw|!VmdB}tIqgcOo=-su_ z3UB=1s08_wGw*K>a?s)w-y+y@(z7g2?->#ELtpwQC$g!au4p1`PII5W!N5}>uw!TP z*||7K2F0`##m>yFX~c0U{? zEiW#m4ljy|hp%>XpbVv!qH)ijqE9iM0hnnx{xQk!$_`EA?%?MHz<28RN|!0e76?!Y z8r28z4uQ+biGz0j`9oZWc-4wN1tOaB9Qj@V;~L*)IYS9nxnZeXGH>+8T2 z9o1NP?%Ifg_I3)#+evP8$@r{`}EKSG^mhEUL{z9dAF7 zCtCq#%Q_okz#tf}pw!aT?7=4U(BFkViodQraZqzWfCshnoe>GWM1skaPX8gD9)I3b zZ}}!)8qE}ys5tLe+Q$tM&WK%Ww}GqrL_jHDxT&iw{{on9VQy$uwF1B^&MSLk2C0eD zSRJH&WEoZ4v78&&@-%|GU2+OM2IRdj{-mswe_2-WiZ}BGxoK*jlz@3I6Sb9j3^=ML z9a0;*!tO-T=wG|x0*q9 z+(O7!)LE~6x=>%zWNGR^B(dSpx4;x22(rDK0_vpg4P%{ga_Gl?=2c`(wI~MK;U6G? z7k8VreVNp+{N&V7?U615y0@|f`KY6&<5%52E7SEJB|)`8e;|Srn*p#~8|69)g$!6Y1`)FjYq6%SkELB?Si(>Zv)hW(w*tB^DQ-ox8O$#tMpz+zYro%&Y$D zM1x&yC`tO^3Y|CNtBTNVE_7}?ZZVTDTyu;(kSuqty_qj9s03rUX2Yn};{;6oQ&QzD5sD3R{9FfdJKH4EHZp^A~a%v zJZZIaOAt^lGj)ai3oLs;iBH}VXnZuUQH-K@-L48roLQWVcjM zgT6KMEk;Has^$s+>J21oZ367N#o(bQTQ9fku;I*?fE_{MIS0(s2n5S%h^dcJSDfOA z(^RIKoQ8sLPNT!ieOpTTQ~^}7oGe$_sEPkPpV|wyaTl>jvF{Yy&>}nOTMBP>lnRkF zX6}DXOfyS~n|~_RtRg*efibCbDWSV}K_TkGoI-9s93-zA)OsCj3n81Wf5|ZCFXvSO z9uzK0t(GGeIxKY=s#@{ew4{>*UEXfK7S;?sTjFbh9E#`1A^XX$>%K6CSIqTo;-KWy zn$kpsM2AC7Z>ExFB_+(Mh<@{Zzc6{*PT&tL0VLsz>IIO0(CqrQeXFeP)s4VhIQ@$mD_6vo{;b6R#34&We1noR0 ztUfom|5j!msYO4@3I$6F=a}(yEn#l}=oYihw30Jm<1nb(^G^Znp%@HeQ^&n17-zP0 z3jSp=VHxQaRxq4X+dc`Hfo2gYriM-n5)R53d$P3*4Lp=byOaMS)dV3G@kc>Ow2J9u zKtSE>XW;1Qa25l(iBYas4kk5fsYQY9OD)Qvm%6d;yvzvOas@gM!D4yGpkpZ+JjtNQ zWw^Vy4R;zk0~&qQ-lZs4D-(ws0DMq1)49W1lWgtZ1E7C+c=0VVLMXJnPp>o&Ph6@_am5H1x#rbC4E<>UZG*HFhg0hO^LDluq8ux*ezk>G>5YjL%eqYetv zrv>PvA!M9vTp^}}BfX>_WYAxzV5!=~Qazw}2LMa98=>OIY5*I*{&nBMd$-g8-tMmi zBxEb9?<7M#3A3VE^}jPb1B3d19G!b0)BFF&KQozIq&Q8+)RbFCE*-|qsFT}~yL6Fz ziIdBa%iM-gzH4(W)!dHD=!R~T+YoapWQts;(F}8)`#8VP`Tg5}`1JX_-mmxb`FMcw z%VLHZ&r~!tU9|To`9Ea|nug51XSfJ4=FgerESymwn`;+I-U0u(PGJS3R&G12$S=T& z)#gRk3eQ3%$T%a6zKG>s>7S`d!HP}G>?dddssYbKF#STlD-EnWT=2kn;B~S@2exMR zZNG%@&3VCoUYRid?GY+?s{y35q^kg_w*r=uPA3+tHclmM(5K_n#k1g2mpv()7XSsJ zELoz$mL+?wbaV*4?K;CQ(;&s8XafZh@HHfS3ZIGS94PC_p7%ir7TLm6mA#yfRbQi2Vb-a`brB@0w{-vULtGuMof z9#_wm9#DPQ(zOVdF77_suGy@P+hU*nN|p#YN&;PkYO#myK4arx?}QJD96_r}%pKHI zfRKm=9GaUSrT3w(t?ZFx?x>;~WJ_KxWO(M@{$|CFQ~agjG^CEimUM7;jwB_+r||nD zjl33s=5BQ9X0qOgP+LL;yJ~4pAk^1%qSwRVrto7|_LkwKe83R>7tBTCQ?jWBU5 zNGr%&;?t6(k0-MS@syP!ku2*Zmw1nvzev@6UsfsgJlpN_Q*|&jl+riy59GbHc8Vbz z8sr?Y0SW?Rdnk=Vs3JL|UuLzz%2E)dz6S15r9vH>%iVHX?uNh*)G?eW%SBL0{8!sW zq9;o#r!}-$X9TmTXaa(QA{RG9$BhnK00~CtWL3vO;4Ur=&H@udB0Lb_<0#(STpP)Xk1EW9ur3D>RnMArfTG-d8x$I9JQ{sj~nTm8Zgahs5k25I*~wqp|_xC3Ay?UtXF>A&|CeuatH z`IaOyV1~daGtL6b_niGQq%NGjBe{21m^`mAE9a; z7+9Q!>`_!u*xq8>ym^%Haj$}L@bd{!^)d*_f=at0-sDJzKH3}BAD`2Zr3<*sfgKam z7FcF&A)Oh2z07tJyj_?m>saF0!8uNH~0bf>{^ImVG}Cq5eeJDoGMUWPI>4n(lx79!5d`zZaLx7xA;tpZYpuqSxS~+`Nwd|Dh z%2!)ku@1Z-1yD17HK5&ipN-^v&j_)ezJm#sLi22u?o*x)h9d`K9H|Q<=1w%Q!U_@5 zu0Jng?30+hFRR!b2Jd2Q^Q=X*O*?JDk4P@GyaS`4%n33B2MzFdYT(l%&xQ)rUFgD* z{7qv=9~9QE9FuVT$*o@JL!qLrWW8E&$0eM1JW^)VpUWE#Kl>E_0e5`QR-Jw%m(gt* zyOM$~nO3Gw7ohhb8$XH1MnfWMyDibihY~t+f}94YJvm$kyIuREMSTXEjT?uS!(s;> z+G|7H*tPEY*nL_obo*am=h^A# zfWk9xULAHhC3^zUf1J0Gw8=>Bdr1Z9+IyNIqf|r#&L#7zro4u zFb5k^_Sz=y`5{K}O5YUZM6V$oCYRd*v^s`jD-yjOV1r0JC5E%L@N!@iBq7u=uoSae z=QVRjI0lr+!}vbXyjaRd1$SF`c$gLB2$LQW%v>D3E6O;2t-A846ke_6G%(5}$Dzv)7he`Mu51r^EsRLC8qj>|%ts zi(Y*>nqBBoMB{CL05`Etw%XDYupu%gaS3$BU9Q-+0NCVYt{D`AIl?G|cQ{xertovP zGGP(nA{GEc!GZ&Tkm=fvZQ+fS9PQM^|f+#nB zU-ZR!nM^W_ZGBYZC@Cb0X9`Bh2k};Y5-oi$i?HVEB9Ud0L!lUowFrd2Z3!VD!MC8L zn5ud~{DuW0y#1`Yn+AU`YRMFOr~;E^4(a>yzErp&AR>ad?HoNDLI{b`-f>(vUa4jU zqLq_mmvqRQ*mLoy1v(d(1rw3wIA=goef? zXz8_EN_W9QNsiAD_*nwC{nzOT_1*!xUpDjXqW<33+PwmixW3wVYPS#Rj3yR>Pp9VL zm)*(9Nf!Jam+0}WmqieWfH_^46MMD~ zA3mCW3!e#&K!gjO(7!TjMnHqyCn>yp!c@emn_a)Z+2OYneqUYuO3e^8{UJYlsqW;8 zB7T^2R^s`UgQdQi8V2LRTzA7=XXz7*J;7H3$Kx>K{3Qv|hT&i1sa7K9us?nw-+3%4 zGlTl2>sD6iP@#{@2{K=<$Izw&_Y>avrJqu0_^x2O*eE^l?2E*9LO3A1h~j?npQ}L+ z1?^u_Lu7#5@lU!vzk=m~EMWd^VNmYImPaB|&n4zlOqNOvDbOP)qbN=rO1#C-j&t|0$s^|5Wr zQX;axtW{l*1Il~ieah??LQaw~L}3m*lvg1=PqmkOtv4IRHU>LTojr=l`Tu)p8k0%i z1eGk+rnb10l0MJ2T(AlS7)1Ms4x>mMA|_p7GeC}T8{YS&g~hH7FuXM899FALTI0JHerCmKpq<;&Ij1fDGY=URdJ=Rmvor%k!G!{Mo> zqvk)8;VL@>pXHZaIn>B0_+_@zO(Qi13?)yW2X}MUK5ExdJ-$LscjG4iVW)!;+4^lr zOU5)C3V>eYzC~$$P%8$bO(-?7=j{$2_;A8o9N`n`XlDZs`V4Ki_BzpCa|2!9#QO3H zaP55l5{qOujH>MvgHf3WcWKhCLe4rJ4skjYMQ>|!lnLY3L|Vc9ujCiLozqhCqzzR){F@o%#9Fx#EtW*uA|P#!E*l z#eZ(GIZ=-2nac($giG~qARN~5K2>M3*OcAN^R*6RVZRh6)f6?7a z+E?FyX;|CZd%~%TD&S66-4LY-W?U%_{j(a|nMNrqk?Ur;=G3sXMJ)P_> zhFdte>1sdm_W7f@&JQF10uxAg^hUe3Cbh%*HY{v!d~BKzt2W8|S!IT3@*Hzc{?OuX z$3$AcvRu8teO*@2)?BmxQq50yv?R3YO0TXpj}bpj9(*Enccb3-aO$1k^GRd1)`CvJG+xup2QGUuq9Q6)KSEn6Wzor8N6(0{S{rh#SrX7|flKx18Xl3xKenkqSb zEj3x`$_R;Os5zLK$OCCReaT1mHSg6Ozvj(0KJ5In(sFm`cGPW2s??z)6uVA>lfZbc zNkwS<(I%*&5;SXbx71&`*|i2=2#8beFUl`HoD?AtMA}(DZbf%aha`YZgwt33*^U*W zGSygc*|I*+Q{EEntED1!k~0G{ge5WprrLTxb6+AuIA{I^qMW+LL(;I)=f@)2egEh0 zOH%9o9{4YCp+kD$-Hq#&jGp>b&HhcO$v3g+D>lkrt_Z0*aB;cmFHoiETCxu`O(9~( zi45A7_{)l`*n)wrY@YbuN{uU;(?lr1J{x~E`Fk>FGfs4K7T5Y_9r_X4xg=r!HESx}7K$N_xWj+9gIC@y%~QITlk+O8 z(?0Xa1Gw|xnd;r7>@Z$Jfn0op~?*)17F%&W32k2-dsjAyPN>-W$r>CI)c{zzyb0oL*IIeRH}PyhWpVGmQCJX(_fC_@*o)r5leRb2b@|Mrjk&5wN(c<;75F6|Y*wia5DyKp}2bBt2ViF?^y z*Pk8V7D}wEF9WN6(lz|FSm+@Tvup{N(5LPORat>5iRQaOTIhH0A$(B z>TJ0>`QvL4`og|4L|{9uh}$0FG>ada)hY5)Nl@K+*NL9R_#q;yT$VGmi&UsqDWIni z3_?YQc6#}rXj{TM2X@+ny3#k`2Ikd#>tDaz-fFZ>JA2iVWGKt~xj*c}zPz{-X3Y-w zCAu^@5T&`!Sz?Ov@+;W|uqr$Hw+~O`X_1oMUx~K;;PUD3Sq-Y=&2u$^{jJvAe}Nx= zHzLaJ6(FQ?O){_zd>QvvI3;EQ+}TS0`BU0YbZl#VBX1}*T*I6Zh7LAqhO5YGdQ zE}$^Go{|IzbA(pAnmU+CJ)2Bf%w`Hb*N=F%=uS7NZLV$fuvn!aPGmm9x?G#-Ycfjz zEb&}C?_3@G79?$%QuM4NaMv;FMDPAh{+ITE?J=c5WFI|$%u#Z5q6olqcy6;;(h{1g}@N2^OybC>Q zF!a&cBvg8wXI3Y9pmP=zmfUW?|LsG4`nek#725QOzIgO>a=V3^9G(qEDS;@&~YYK`>ZnI8qOp@k5Xo`dUaOW;q$ zqHa}Z9$dA!5BX^I`9_3+K{Oeci-O-KL#2A=&=tH~$+F2L7t_8A2$^j%p1JyRb>Ce_ z8IGQ3ZnJ4+&OV_xG!HUkwcg~M;#c-{%Z6q0cj7&ABS#_Q45e;Se@&bpXOfj2sg zx>vs${$`-w*@qd-Z7mp!sC+O!2>L>F)^vz%1r71uZ)bEKmZw&g{q1U-UM=T)vGkM( zo{97b(zvMc&71giT6au&@YeqX#|qunkWnNj0P(mePnYs`07I;det z=TzxE-)o-#0=hiXA+!qT7JV=3pVmJY&kK^3d=^L27S|Wzlhdo7XmD1Ijch-IW{^S_!q^Z~5*Zmlm3f{!{&xd~s zDTm62UN&%xJK$`(_PXR%=OpIx+A5hdxbgDuN-ux!biKsjO?*FpgJpl9Oh2O1FeQ|^ zIQC^0YwFgn9-)skY=R&9o~-D_SI6{-_e|`Q{|Jc8nm#k4{b?o@H^Ln# zP7^H?)hMp@OrZ7)$!5REJGqjA0ARtlBPx9F*2gxt4-G>m2VUAKOVqzdpKqbBZ?UfQJ$V_UzYZ;?!=OYB^!vx@%B?4E#MYz&l0J%hozJhyr!!Tt2BG*t zv(SbEhr`MPZj7J0hSb7$3IiB$h&~b0$&OylWr&;1k)Pt7u37$Le$H8$^^C+fWZXV- z={M}c*m|!WCLn!#WXnEt+>GLhBJz{O-2ymqJB~S*kE(zWA_xcbb zc0%0}PVaOt%y{m4_3fMX$0(II4=OuEJ!Tvx-ObiMC0;{&k2cLCZxdV&bzyXpIe>2_ z8E4{8#QdeVSAxfDA7H~^Gc5d=c;Lqd+#d~|frji#b}hKfsZt3bzyJO(fT@GG`NkBQ zYEZMg$@V;N8XN{4g@H7~eL1PcwL^#=W@RIx5KPlZTB^IQ!6Qt5t&b$zbz}Q3^ zQ~i*izsJJ*4x9A~!uJc^2O&3q40TC}Zoh6DCEw)~E9KG-f9_AFq9hND_8}ia%G==g zFrUIwz~Z+JNM=Xrx2!2$1M_j(|9?D?#IQ{ewC|o!uVox0|e=ST2b~`et zO}5tIja!P%L(-x#E3y9$*GAx%=3P(pYS~^+FqK=WA`AlplS^vXnY+Ppf;nO`sCuXYf#kdmHrrUU`k-F*8s`r zcKtOC;%Yg2E<;gb-}R>`KK=2Cg!ShW0!tYi`oY(S#ih){Ci|!3U08(oeQ$Lu+@AZ% zW4?hQi^QFwm&CEPm1|1D5khVzW2zVimeLsh(df;!BC}0j_wgw9@~Z?#?^E6(crv~Z zye9v6QA{{w=@9_r*X+0!-!rUOw0dPRQ_4LqeA|%&VsqUTUniY_oisPV_hB^~hVtO0 zc0VDOW0;tjp(D42>JT@Yao#4m`Pc_4fs8^OgVk$A&~lv}SA0NX74tLZp@D}Ev84m2 zrJ0tdQZ6fW*N?O^3i8Hp6>|<%CFGl8&Px(5$^EaaW@%sgyG=y@Htlf7f;n2MzR59; zA-7r8ic^s14Ro-QdM4$!uWhr}Si7#j%9AUqA+MV}V|Dd~x&b=36FNH3xYlCCqu)AE zQd4)YY5GBwcta|kw-qnf^+%Wwe}eZXn{Y=iRe-o;kr-Dz2U!fAO$aR}p-)0xudic`cbD3n%6F6)zqf ztNrb3xlh=GHk3aMOXpJkXiB*&CN;E+H!9pp)0+YWpG%5e7l95e#&yBq69tS=|LvbW zelD@pS*nPX)I%kO8&>t=?l;L^zH>bK_A|+hn%n%b^mvbWbKJ2x8uoyZU!ul8$36#mb97~K)$((^gDj=Txn?A%ZKSS1xu=uS{vbs+qIVsPyeS0K0<}Tw3m?)lw)YE;VfegbQ)5hK##ekd+A2W1;G79 zL=q^)9E%6Q=l|}|TSn@-mh=9cTUJRT18h}-Z=U+9iS3f$3AUt#X~4TZYGg=UewX*Q zctSmQ$3ZOg_06}&M&m#KCQE%qGy)4av#Xi<5fx?+Mw9l8;xwos*jMGZC$z~{Htdwqe zSDk2ELVS) z{XkTe_0!{zgUq-?p14#oy5R4OH{0Q(w+nMkLxEngIg{KUQ757UW39ZWWMwpB^H>j6 zmDq*WKP%oD$;=m=vA;P&M__;wLxvC0$o06AfuP&=duvuGT3!*|`D*RcB@niA(&x;h zZqhPqHj8JiKS9)iZ<^Ubcf40xR36Jk+3<|~Xw?sq z2|xuA@`JwQZa2lOze+LGlBIn>l@T@{2&S1UN@6x_RI^BfPaBhc)oN%1BvA$SGH zwzzK`3Di++KIlIr+;;s_-sjyrqI#={*D>R#(<4&4)9ZiaPu;%~h^Hfhptbl|U7=e{K zeec!DC4k3x!Zsxs>COmnVzcq=L7WV-RoriMAEuE7%ex+)jupdzIIfl>mjzUr;|4b4w%+O zsxA&ke#2?$+STnpuIjb>Z6?^)5C7|IN?zpH(k;8_X2MQ^@Pb{jYz~sSEg{^gg+DPf^h!%$hb-lH~xd^H>LCzG8 z@U=e>R}|aSxFhKUuXtP?f?1!%kGx38u#-bNfcsrVGj5X3HdCJ!llaB1S|gvv=U2EP zB*i5=iS+j4oe2I$CD79HUv`HIWkR>@g)N4v%a4$MNQ^miRvBgvyZazKFBvP}eB43n zD2cP3o=HT@bLuKKviTy!V-XJ(Yrbd1(#Wv$wzHv8&~%+avVK3*?inj=YakG&us`e6 zxn4S-)PU~?|7JS#Nw*-TUW0)kjbBO~00JQv14&oXs?TdOj+TqkcbuQvq7hE_ z(BSka^pqlqARbDJVz4yyJ)cE&8n1x;1LLOeBLWe3e6QZVT*?cNmv3)9-1q5GmU;H- zYafit7mf)p65n}Px?%3*CDBq0IX1p_aEQs2EDO$Ux5^lKrX{|rTXExxVR?90? z))iaP+t!V`uCFuyyDI#6<8sM^6QuYB-wJGQb1PA%nzmRHwwg?ojSw{NITw`}dY<>o zr^&Z0#DG%LJXUFA;Neju(dy(Op&=&xtUI-kI!4L0a z>o`vyRM%VcXF=!4)2Q=QpN~PDDsKy}O}5{dTav9Pm$b$}PF+=24laDu#+&ApORw|g zAbz(GPiy+1Xb8Z9Sy_odesqG|2fu5LmE;L`qwo%+M9Pe*q1f3q)==M?CJE+|h+vD>U5 z{xe1hCTAy%Sq7XHbp4X_Tn09Hl%T=>(6YMi5ECB;&N}k5P$g2?_`f0WYTmGKhTo}+ zjc8UR66CRBLLyjX`52#(Cl+?5m^+njnQNZZFiOCEZ%2b8od_9F&+FIyh7Ws%GuzY9 zw-FJ3(5N$OXIEx3TQ8p3f{3%g$|rd<)g)&ryYS3OSk={t zQ0+2H6d;9zI83t;VTJW$5k;`j`umO%tLQ%2FRys@n2-h;`WPWTC%nxd;iD@F%Huw< z63S_dkQX6J>L9gSuuX5eBK_X37+l%3oAU$Xw5o$3z@Pm7n3NW+m(2zL)x_J`YV zBbT$x_4d>WSuem#H|d0{fKBzb-MDI!5pQ#6AmbB{LupGK$Y33OAqLtKKFV<>jr z#A9X7%chFbij{ztvzjXG*&2m=(O7@EB>O>IvB_W!pH7Fpih>u3B%y_4ONxN7b%yL% zQUg%5Lh@N{R|6}4TVx$BZ@o-~C<>eD0#DB;h{s$Dp65<;n8Qv4rRFoW+;k`!0j=A> zG5hT;$EiMeMVKsb*i@20^(1hZT&q)qeJKCqc3Y%`Osg7S)yU6QDrbVLKw_aHMb5cn<+s~gcRsVVKe zf#84`)WO-|!bcC<;4l)W04M&y_dccj$LLTpm?{3?E+C}tn~FcJmej7CELL{DCj08w zTr`{H!yHKIJ6E?2^f|%?h;r4~Wwbo&XAU*?hXMgy5sBa0t~UBD2<9$YFrGX&V zK)RYa1e!d_wbWS+?7GqCUO4S2d0^Yw4-Yq)a;l|S#Mj zN~e8c_Qxyw!+9?52)jT;WILh&6j@y;7_N3m(~INVyhIllK=ra;+O9~&1}0Ss@CShEqn_`Yqq!}*n| z_H?Qc8sIO@s{ac#V0G;h>|L4fu_@Yz%*_?>UF`2fIiXYqTXqIosbHT!{ky^uhI>As zc%NUf<NZBZ- zZ8?lNkiA8|Mw^B;+fEEZ4pq=FMBf%S7t>XUP>w{$CdqQ;)a8dlVZRC zmLbMx^rLYu5L&m{OK^DTi134atXk1n?^QRokvm@3H-={S51OX3R@Qu!@;J3+fK{!6 zj==4C!a8@?e1Pt`R<}7ik|`_NonK6BLCJ6Q1&~U->_ZnGdkx~5weJAL;Sy!354rQ$4@H5+F)dtN`d>sO)F*jU-6@ZM?hAx9OlD-9MQQY<4^*^YWt9!v7uT@WZ- zVNW2>bD3Pnh5PX?T}}_`<}~VKpF!MejM-=?n7-p2Ml|>?sNnk%o@eINT_YmVpwtjd z-ukW3$`y^@j}o=5_xcrRZ0l)_pxZ1Eg833S`{}Y=(3Z-X+D1#Enajw=UP7T=nd)LEa||g$=Bc;x<*|(w5G$GAC>XHs^MUsytmP*g2$5qN}gy1^t43h=_>c zjuS5_MbOG8EBT&@OnA%gF>yeBN}S*cIq8qiqG!m z6n4Lb$YxkiOND+w_#q$3j`^NyjrLm5#=dcsa=L{eacZ6BnL>6 zF{x~1LQS8yR@*0LD z^pI#v<@F9(-y0?#v1fpvPt5ToZS+(e=Gf*RE1HdekVotZ8_b&>njBdY*V;JA1OMrx;AS-u!mZ; z3MS7Cy^3qBFccO7I>A}lURF9ACF}_q-t+%6inYQdv+SXE2pMvTY)M5oE0V#rHk4o@ z5^aC4^ZU?Yir9BPCbO$0T~P+HnzQ8ENffjp!Z&E5{cOtaFXAyYyi?f^K?pB}GUXK; zD?h2CVDf?s7ONScZb=%3o{kVy0Mn!p5yAkVpFa#96?Q5*W`rx(TNc$zMaFC`RaY6o zWq@%ALnZmGBsg4IyMH=m(PR|k)D)cSI>X9n#Dm3LiHDtTk$kKggqF+z9b-(cZOe5A zGx=hW$-h8IyhoYw!3Uk&=PLFvyZu79PY-uYJ__Mf%~(Rb$V65c9Zm~J>cfna1t`Hr zx!{8$qxe5A6d*I3C?NAyqYwuie{LZik9|}a^0rG8BC?*kwPv} z1TD~E%BEN>ep_asl%=Oof+t5#mna|VHA9t8j2j&Tz(xg>S-s=vgLX=i(i@$TO;(`9 zvK3Pg7>2kGW)Z;53Pv!BFTjJb^f6+*Pa)0PX}_vx+Y}`a#=@J8V$^TaA+88E*Yw~y zhAJ-YC4Bb>T3D)4?}>u|>?Sj~f2E8h;GP!bR{(;jS+t;XD%UbpujT`LB(KqQ>_Z>- zFG^6p#Q^aHe6$m0%$_K1i{pa{+gt4PTjIJf8{ZvfUV&WHwjHeE%dMMd{UVJI!6X>0 zfD0SzT{})XL~ZnF-%B;PO@i1g_5h&cI)j!p2@>U!2OADqcCz7p0C-HR5Jo8P)^%Wk zB}Ul^>T0~Fg(+C(1~i}X4xC?CP62t`<^DfHr^djW!ltwlvM3O7MABpFYK z(!xw-vXdKR`V5helm?50+8#VBsYNIqII9$L6uEeZz2jZDnb-lB1QDlIL7;}ARuYEQ zVJJ=7S^Kx$VV_;tlQL9%jjbeM@XZn zHkE2S4p3vqGDp)%!N<)EgCeS|Chyj z%6SSm{aj)OS(}hx4PZYQ?}KP?(cQ6)OFV`dzswLp9$V}8`CjZ$fAVAP@`gKlKlgFb z4CD8?l3(tviDbR}x>>Arfcc2rWs)AAEFdsb$AscSW!GhaGQu=Z`3_7rUu245M?XWb zNfL!(4L3K+f=ZR7e}R1dbNH;bY&t_8y6w1#?w+zcC)x$X>^R{Iw4>*r#19^P=X_K- z<-ajObwa6*g9U>jajvH^J|U_@s_%~5K5YupTY8f5YUY9_lZ+7u%-3SnV2OQb@PC-Z zWUa@ndWh6`TP3F-ER-LgX05$@&q@dfe?s^3f+Bqpol)7|_*vsPldJJZ9McgQo!f%ZB>{SipAe*~C{itd!(M>5j^kEdaNFf__I9&ATw zL(CNQ7#^UWLaELZeLAkWOq-Bci|!@(ya(UPDN$n~lWJXD5&<$&NDq?2aB6m(E}t>s;4HJ@Xlctp}Nk;()(BhF$26Yb7O;3R`o)d;bEF$#{a3^Ic z=p<%LX6Vo$z+Y~gyD`pQ{DJK&eI$rHs%>#=z&Iq}_?^KAQDAK_e zc5C>kFetr8i;C_RCG5;X=ByWQYlDlSX@^Ttazm7 zxVtQy4DNJdoG%;xpx}qsc#cwa@_hNFju7>uC#@3;bolh2#6z3BI(8il;hjSk$FHt$ z?8Nz-fAiAn=!DC2nX+FqinMgGfC|{d0lL^r5e!=6DYWKnG`N9t%3&{p7VJjQ0f4=a zri<%50nod39*^YtLQkx)lpuW$&Bifs%BdLKND$(EI=-n6@5J;A3ALx<7iBkieFt;o~+IqsQ0jFjpiZPUnw z))l(Yf>OaJN$Ht^@>zojIEUn@&7vKkcrk|7WPy?-owdd3h@Vf1aUe3MUj!FfK#Kro zW4v?CP_#;8HqtHth&a#A%)m&sW>XIpg_NKWyW+Q$LEZWwdl@S5=k&*eW3PUarJ|G& zn>+C|`P)4QhI`YPqt62xIUnmU)>@5L!S|uS+YG=_j_5!t41T0ko@Aiy1;Sd?d37YY zk)kuUh5OHJq^^MWKQ?W~RJ0CvrU?XVoL8(56|wa^4GRH_?1%EDWAhM;e7U3N5qXki6ELAYLj-2STZBs}vy4aIt6Ro&BJObKe zA|>U#lHeSZ)NEwExU*OEJk@DTXgBTL-&gqgv6l2*x=rWg$=RL#Al3sT`VF zhbYg6jR+x-2b=YD#sHN-5Xy2!6|=iMX*Xk48)4W2+PH81A1XB{P-xsSazF=c>>OIsD%E#skLzO^X(vcJ4lWW%$&8BGi8^lPL~@_-yPBNs`p@QYht>o|s%1~P1v z8X}7hh+C7Bv2hp97K_zU)uti57SR9o`hh@Av#?4Ly(xQF10k{<@g7__sT&3+V?soQ zLCi-01@$@j0t*?`Oe?d>uP>FLiyN{t+pRy{>i{%9t;}K8KoE;&;=42zvN`6JdS}Cd z+xWsyPEothB9gl|jF~HIQs4s!YEPaf4iB>nu-rU!%RD))w#+c$8!Iz$Aekt&3P8!& zTS7SS=!pO89k6W2o)q!-;QZE8n*2WW*v$bkwGzEB27p=r}=3va9TL&MhGkP+OPbor2x z@7_ck_-VXu`Up|2rAzePfO0LLMLuBrD^d(Wmrk&-?&1^?7U?NHZ?;`Gr;`OB)!=3Q zz@hpGA+uf)wDLMzkRI^d52n#Tj)~wbvj=jP*@&2(%_7Rr7W7^mPzjMTlez|5+@Q0| zv3lFij!mBrl_*51Qu3q%e5W#z!ET2|^s`5ox%Qt)D}ooW2{^-SA5;~dR>?H6iMlP_ zgMy`p&)*w43oW04?$Rh+dsE8cz?_Ez2dW~!hs!l zvg=6w-&22ldxMgx30q|+#o;<%>9q!A%v0(Fud;ObVB!Ax$0t6&Kfe$1szsf79Y(H& z*xt?s{D>reuQWF8#Kq!|kS*88@q;qaPfjL7l3G@_*ky!pjld)$AzZA44D%Jb3b$8s zr0?t5joWfgDCu|+%{O8zCF1krxD&=!b@R1mmI^meRmx>v)-R^6DhVE{rosl^H#in} z+@nQp-f*k&ga8E}`T`h~!yVdpedN8Ee{2lnKoQUL#Y>_zRFF*5rH~)Dl^SDw-fL7x zeY;Z9+VNwaDu;ls?_7HRqiaT@I8%warX_N%`O7Fd*QLbSrEcVe#uO21jI?n*=cj&H zEyJSboS^=FVrKR}fqAebI>twSl7t}Yfi(`V(h0T~4Byf>f!;qdI;*}L1nZW)J6lSU z^J1C|bK9>-_MY~^H{5s%i37NOo96z{CC)jBt{HAy(uKp>JL2;9Gw=Ryh8X>O2V{dc zN*+A?^`Wa<)|e;07RkbDnn|a?5n6wVFreFKg3GKn{Evy;{)adkk{u!iuO%c*Vgw&6=2Q- zJ*#~SvZ3SqE3i8~qP(pOJa<4`@8C2PZupYA`n9H#uv-gQ_3zvhpPD?kb3=}9r45pQ zy;)bNczpG{DtK;wwhHX<(M95T3(by!=qQ(2>2uh$KT2kFk#BzM;VdSDNNi-rtmcU+ z6Z0Eq8ml1)A9!yZgy*V!Wjfm%`TPCtm^E?&@;oSIdHi8cln$ zB)^~oSAKi?{=?qHx-jTNR>}`KXzu;v(akB7;D`-&qIv8mnX9UgJI+yKOV>!Co_4^0 z$jSUoNB4Q)GFiN!fm6p3Xqca3p026tHOpLEt?5YEyPjep6n$x-N2$v-C~DSL3MZAX z5vByS+^Tmd2i%dGm8A+sflahPw>pQJj-XJE&FZO?k?$TIVe~n_E55L{$8|gGtr`s!iI`)}`edEfa#=(1^ zyFc5QkrD|cpUNdl&^wgu<#@kt%NLaemWnl#%Vz07YA*Y8l=%H`%#J4C zqo-3W@@jNBA3(GV)o;!DB zpFoPQ+nuiK)i01`Q-WKcM}=!dJrH5;PJ~9GIW-j%=AQDCLUt_1Z6C69P|lv_p}CD+ zIeas~AC>P2HQN7!anF6;NKIh5bE?xks0e-LoB8Av{M94-r@k>`Nu`0T=~Oyf>07dp ziWaGK(IY32TMMi$XkNX1bJgXQ!zF#M>I5;RZ!`8=K_e; zkM_H5wM=BX7fjD{G;MF&?|m1y4H$g;;Tw^R|uN2rDWAf#I>XDfgCtK}<%Flz0%?y>Qr`OTgWW%i%U4l9Tp zg}(k5c!09(m>ZhWknA>O5U!opr$yuwp{wwpkHN|-Qb*dVMA@hRSFJg0Ea5j050iq& zyb8$(0#CaE`!NDDd8N~XLpb%!?e&vS<@Q8kUHb%@VjdsfI$~lOJymo&nP+G2-_aFX z!=Hk%x1OS3QU5Ctz_3w}$wZRY!uqTxUz)CJ0{^-wV))K6##6?l@KNI33pzbo0~WFT zs(vIyJ3)f`i3+)03h7s)GpYijDXsTg7W>X@O}~isUtTW(l3&s*7rqds|KNb6o!=(6 zuBD6}I!HZj$jvp5&z(goiP{~Gl6$jXb-gACSD&GaL%1H?bvlmw&2{Eq;1PONryr8Y zdSdzJI+c z$3#cB>OP0jb1zv$u?x*utMVpuGB%7`Yyu$#=8*0zQFIq0IDRbrd5x%X$+2S7?$<(Q zfuDRdmxgLOFfPCsF&9tm6^_?*pehyg%zu4-UpRV{s8{oijNZ0_gP1jj+~AE9-5oEw z_2DfLAwDb4h|P8V{g{*Pt3~nb2PNP*GDKEC{goX^YOuY~kH0T) z$u*Pc>AxtTGv^jtmu37c_$@D+aqG=kYT^ulZPFK|Yc%S2piM;ij(;54aX2*Oi zrOY0GIxzEI1|O2v*=TMNyMON0kM<*0zk0f$q5p&ydEVi#3uU?7^jC4lg(Gu(HT?MS zdG~a~#4;JPV@EQ29(*?a{r^Zh7e^-h|NmbzOcDuqlMO}X(7~abIgIJxl$;M8CVcx zY)gXIK(S^}{!m};aDZ_F`gOA_G=(+@r}P~YIiIJs6Hgz6_xZhiGdJCa>%X+ZNDW0U zr% z>pw@B<$GfF)fX2ZWo?&e*6Xl})zo8#5x3vWKL7VexwMvf@=QKffpsUa*D%|Bt@2Up z+eHp^>Gc#R`_trOT@lA4=>EDxr{AyxPd|GhU@%gGm!3`JF9{G_h;7K@JI6loDe8vg zBVGi73Z$FN9>87@w=8Scj=o?vm~r^S8>{0PefZ-Ko36YymMq~V2m#t?JdwDon$Y+* zc3&OM@Y&1*DyLoBStN+D=PUpKSBJl1cBc1Uq4pe5f+uZvjqxP&Jt-hXc}6c@p;a$1x79f~e?MO10v~<( zi@N?)v=k!3OS0_elTu+TD0~a2#Lx34RJS3X5F#R@g_ET$inU;O4hE8gKwnILPiXo- z*$2fo9(BTI(b1IJnR&TY(BVqZ>nE9B&(HaShVD&B) zP8Uy$Q2~n@;|rWr0DA^F&HTXy`o{A6!bm9g6silzePuB5J@~-Cg=rU8Vt%JWM$hM} zX)b=g`M#y*ZIa$ac@Fe93{jy0TEWX=O*<|rw`=-2u5qEmTal{vk8d^B*xhC5w@0Ho z=Q+7~tg5oxqj!AjG9jHuP1jku-w}r;d=I`~yGdyuR&;wX@Qq#u75L2AaaWlO*k4?X8X< z^aOx;09?uPtOb=OpvFe4M((j7cBpK^?}Z0dDi*x8~sT#rURrFr|rD{ zw_LPeLS{?WupQir8c9F#C_L(%Nu%)C_AU#d{yilShbfTeJ6M0cKhy8@)37)LudNS( zeb>LPd{|eK6KM`*r1h$UEtC8IT$!ohw4R~_)`?B%GsI>blNRK`-?ee>DVW8s^0|Rx zQ;#uAPJV&x*pSoRyT#sxihD~{wBk_LZo)sNX0GH|Bli59&YNpCnY}yt@|}=5v3vwJ zH@Ei9z~W!P-4z8}l;y#}xrdRW@~3YpFOFvRq5gko!9hq`bUEHoGvc`**E&%e<)QxB z?7eb}11y-iLc(*=Dwy)$`d5ggS902{K|X?XwFyMj-ZQ2{r&r(-UTLN7ga);Q=I>jz zaCn-#I3~9`P|!e>sIC4Dr43iQWB`}sG6KGASdK9uGz3@`K5RX!kSydey|7rd2F5X; z8T2m;rQu@Yz`<6VY(mA0;`21}oGkhy7c0Ys0P14-~_w{PvQQzvS&Q0sqGMsg)> zON8r7+iW)Ny}pn%x+yRyvMGjh?XBgDN776(DX|5dXHTSxoiLkn=q8AYb+K2N1t8&& zb9JQ~7=J<=?{l5s`Z1CD;6Jg&!%E|U{n%J@=Vf_5B33&Qt z$7@cosGdXl(eK8h&GS{@!C`iqDJKk?tz5_u`-f>aj;PL& zJawDYayB{KG34hj9UtkpqSl^ObW$Em64GDXc$^qo3q$Q4N2ntMC*I2RWaCda;ZKF& zKuZ9(Sm_#&3^vp%3ug81zuqtNw8y(~|KgBWiiX?==MJ5qgYKx?m`}oA&(J*VHL1Wd_<=W(%*RnAPV*3PRcT40`))xbOX1Qa~OTGkeJ*Q?&h_OYKfFKmBYa+?{m6}hCL z=5wg;@8FhfaPorU!#c+cS=jaiABbM4vb25LHDVv#s?oy+x!?64YyG}ulS5POPa6b5 zo(ul($%|80m$a4U*>k80oODx!`+qncX(|elW(+;?6Hb#>h(~act#aLDthS4PhN(j` z?k7`mmG%HUT?_jg?|#v;WC&s$>BE)I)&d)eEU(^i>e-v0^86-)9Mm+lDA4asXF=DQ zjqFkq&IEo^f4z;9Bz5_$&iS$F^>u>`NLy&(T|v{K>Q3Q(+bs>U#UJ)xw_$a~D+C5p z#W*w_F1vrYX|v*1y2%-8ShP}C_Z9%UL___`8y$^Zf9dBMSVy~dH{azOT3tT*)K_@L z^JSKTVhL^BhKC)kubKHM9$N-7^iXaFi;dhj%7;BG-aeqpQIM*4Oux7n2?RKOITdAX zGT69Lv13X57yb3XExdoW0X8h6fw#}@K9EZ6k!_ly2Bm!NLqC4sIB^ztVuocwQkz` zf6H6yp@pj`Uix1pV-}g9Q{8vE3-t48fr?ew{%Lxot!u7?E zT<@ATrko1x81tLeWbg5{d{X$)XeH&1yL0{S(tG6qvR5P0kTS)69ry0E-fYyF%|!D^ z-L-<0R5L{Y1M8RF1P4TpA`vvXIXXf>20cG_Hc3`2LZ&J1+*x>rR$!ZxG__Yv>@VQb za=W4aYQ>R5b~tNuS$mvrMA~LJ{^sK`R)!f>qxIy%^fXB_?c>^;uAuF(p={}uVPH!Z z*g=A1{eDw-lEz1tL`dZ>4!n9d8Jmq6cNOG>gs(NFB5LA9EJf!mK()dt_)|64# zV;mn@-Hv93-Lx&0ExO2^555ym^m8~K#qO|Q9&EM1vmN8&Q*XTUL>v?qivnY4?(Bix zTr1^_+>~63LEI9R#vG_Oz)ZfsEi~O3wKxH14{d{cxlgb9K3py`9CdH5{e6z-X%AP_ z88bzaB2}MdX_0JxLpy}v9q89T&ivUMmQb1qP@@&Vr2E`ZG~bn`&Cz{3vFcTb)wJw2 z{lKKTR|cN9j$^C6R}05vV|XX)K@7#}4cQacqK8vWTCa1d_^HWka>32kh2a-hcmA~d zcke@S6;tnc-v{|fXD;r2ja9UKhJNgCRTL}>cRaF|=AZd|P82h(l<<11UtNp7Y2@&iMkY!1RL{jzx6ijqvzLDV|8LL4@#Cf3;_HU>?Z z=OoP#4l0e9CO^KqWPe7@2nyxW23}qon``JAkIU78Ql{*}qR%kCkeAexn;)IiCrhKnWCj%vHU*8X{|swu)XC}@QbK^kN( zL>Z8*{`^RjP*K3rjOx92G}$h4FUvkxh#=czrA2|xUDdK|YR_>HVt_dC{==y+KNS0_ zXyz0BkGCZUo~&vdl}U6wPZz+3&WHVQi~1#|xgY$_{wQx1x=Z>#7LW!98!!>Su}QPh ze8(SL4AD@4V*}G2NKvy>DHleYTtyfDiSkCAv8oW}ZVf|&;JU94d_<4s=4ooLfIxo? z?WaQ5&!*F}7ewySeA}KYRL1aEJ1Y_vyhB7%7_ht-^RD;3&%BH3F%V8As*LF#4EHp{ z>Fk6%eOzDG7uPLp`Z?%P>49QzI*mpBpE2B;-6v&pfOLIS8QX5wr*;K&~E<7PefJ9@N zUz)KtUD6JQXJFQPBHx9Y?+qRE@?nTz(?E+HD?25)xIQG;Atw`0lcR!TjHtM_jF_Tc ztuu%F)zHx@nb^Y3xpe?5!7r5Qo_OtNhr+q&|_1&}MXfwRw0mHZG&Y$jw zEv}7KL5T$OyrE$&Wp96zUk2Zv#J0DLxh)xFIw=rth^Tjj?aXnyu5iw}eISwo`y)I` z)IAl?8q;9BNYx%~_~sbsqBcn`1d|M-dA({s5o^VnRCXN!*mpO@$h;kir^@Y>1yr}$ z(U2-yy~c)TM)HNOE?|3g?frB*kLBf*?fdnDJxY+S(f*pMZh@ueOa7)BvTD^1Fnrj4`c z1kgTiLKF>U@@!SWXKJv>v>mQcDp#aE14EYZHO^{Uw9Sg5n;eL@>VmkR&$r{G;eZE0 zVY~bTc4iN;ZI8xLmx*FUhCoguP2VO}?SMC*=6yMH?^zVZ(~HC%WGD3qrfTu&1{Jj- z@SqxMG)$Ti^lEo;sT?q70s%0Pr@lbz3Hu4|=%bdA&AN8y8}63yU{(~~F9LE?Bs|5+ z-`6DxRKNas)@kUH+dhyT)5VZ82STFMi9r-U_Re0$S4vtFoK?iXoVf-Ceb@~9gHBI| zCB-r%UE(MMsgP8(iC@i(0wNL|pnFs4_4T}6HKZ1B@)Rlg$!G7Z42_HVY=UgB?(9tELg_?ov4%?6 zwG9uAR%Pg&K+b5vE%*fSCOp*`#cSRc2HZ10>KWh)LKjJiTegHLK`k3s$N9-#8C2g(cFm&Wve*lm-7582Z;19GO13-^ zzu|-|-PAK`lM$1#GTIBHs7S%5IdDVp`-N6<5Fp4@_tnd0K%Bb0c-lac!K;c( zB+D~TZrYQv{dxE+msE0e41 zufP>?xhW0dl{ru10$)FS>aAQ|LUq6fV#H6We@_gzV9b21nnOnmA69LZHX^53M}v=E zh^#%9gz7W*QRys;0)GU+FXK2X#&%~rlBT#F(l_wxRMBNXy`RBU7~EOU2Vym}Jh3x< zmEhShRZ9qmZ#bkr3{9i?I?Fa|_D=Caz!CAVO-x@WE;uHBgQl|%vN!o1H4eMyVzwJV zsxr$GBmC<^*8a4EAZ6^2{e5QAe_8jw#E}=aqH>J#7oqNYZE{KoK7cubm4ryRDR(bC z@LFBt(mA$y&mEk1l2Fk8N_Zi!d&YQY1FF9r9;tpsKW@@rF)l7dfrR)$OFc&VRa2p-jlF`U(^8*lpF|@%X zOd+R@_tZVC&uZq%@tZO_@*-)uIo1CI@50VLwR<=v7)sMwTr|ZG5&_tcmtmrzcS}29 zgQJDpg=Z~94UYg;Q*%~slxB6ZN#kKCo=O8)!=o8$^T{91F0DRcb8HK2Uu17Q<6RZ+ zas?|x9%CT!0IH<(`6#VNeFe~A9P*(~1(V4l@hE8;ys!2gLp>m*}kIWLoV;H!Y$ zX{6Mxrl=?q9fXUD%}eh+*3m!igdh%T2ul#80#h)dFc8Ccti-~r7$3t1+4{KwU>p(@ zFWEt1^-o~rLpmViD&sdjYhQBVgLYJ}`tXP~A4pB@2YM$hf@!rV7#Mo}6yL@HV_+{{ zoDqZ|@N>~0Q(j~`izX@tlA|qafCoh#R0ID8UH4|wtwFg(exf@)AE~}my4n55PeEZ> z6s_#~`!0uHG!jJIuH_3cadOilxYnSZvY%^vnR0qY&f0pCSbp(&Tj_&2>aL+mz)owki$ho+C~G3xau~9jeXPmKmE!uR_7(V=LwcfMGvi}&a&m`Wa9=gI zWSuXZVsTLSS203d7RY9^N{?`TtNW~~WsodpTvsO|r11bC!B>5a@mZt2GkE%AOlh?L)RI8-9N zzlI?an2K&i1efA4G?^-GiMDa}EVy}|R?#p#TD@U{$j!4IBH!OH8gqyf0dSE%zyWd)0-CFC`5zPxlfTaaPh|>1T7PT>!OTiQj2)Q~IidWA zx6p8akPk)_If<~c6c)I_mN+uqP3s0$N%%j?Q2|X?rFgjDmDcOzGvC{TIwY}ZpBFd$ zG@nc&z=Zxepx0PyW*b0(?XrvK-QJkY0Qb-dz9G<)vSXs)JMoA|feF8xA2Tghoedgz zI-GuYs1FxMZ*hwr^$zB0ME(Ujiz@_|32HFOm3^a!g?0K$xM2FO$rP^dC1a_>EtL!e zUuV6d;eyEO`78AP_1hg*6#pXa>JFjl2>b*=@jyb)CqPI)ux~Tzd_{_U2J3gPiA8X6 z{K?;)(bl2|fNGEFHR;jl)O^7_7h23_xJ@qWNlcoRw2ajf>j@ov@soz0`UMDThaj7k zAaQymXTTU#dmV8lmx6~}A(;did_j{JT!0;GX@t}KhJgNpr#KA^&qQw8rp+#<&wVI5 z{@)mAg*d*;Aa8)ImDA|H@vbjFUr?fkh@|F@tEbEuLH&NnI7Av2a4CdBfT)>{3*A+s zT4nPy={#%O^L~@DdiUkVi|hG`UPRf5aQilVrt2>q@Ojv>)nJL>VCON@a#nbw^MSOf z8f-qtcmc&rpbe<t`9e`^2|TS(H{Y2?tKJIcKuefAgd&g-|Gf}q2oNq`57i~zzo zmZQetrBixWxxI|nYVa+^;`fXC)bg~+5n;gUgN0i_)Lq%Xz%Jf61hRU6orP2m39Jcn zL2>ff#$h731}2Hx4@GfyX_OFO`0MgmQ2W$CxYST0Rmj1O`cKNY6Q;Pm7KkVQOx&w zmP70Nlgn3S+XqL92REJZoMAfnsWphi)$*XI4m@Y{NnV2i!8YCg(NFWYj67p7%4mB} z(M?2D9kZ`P4tyS%F&y4tuK^C=SL!SOmwbqaa^RiM)sg%qh`GzBE730u5J509K~`6; zeVJRhzaiEBP=J~q_-AJ+vrtNw1G)%Y!(IjzPzmd7+fP@>XSI0qVa#+8vbj$c`t2}| zjJPiTE&M3C3D;yi?4rx?+I;T@2K-CgoFLX&%mo6B$ptfu=T-{EiuJISOk3HvZjs;8 zQY-?KE+M>@XoLB3=01A%%7zyAnXPpKfLJ}CET^Rxokx*u0F+R@Fen&>t8vRe88-q( z_M(pZgBO$iVcqROXOX1ZOBC>`JHNA~^55P*3s zsprB#55OO{Lozc8-uVPm2Si{j8bme&y1PAGFqi^zoCEt;yXdpJwq%Zc+#>x6{eORl z?9(>zBkSi2;Wb4viMz@sNL>;kqz_?->CWtf5#va?dGV&Ey?=t>{M#VL`6+Y;!B5rS z9>B^o5nEf4%5;$Xa37Xeq}0U#BAfmKWNWBHaOxW)j5@7Y$!J9-r-%ymk1{M)X2C>W z;o#uUQM`he2t}3xtpxkll4GIJ+}scL1*S|m7<(R&l56km4LG2*zbZN?JX&E9b0BEE zCNRFM&%)jpg}Un=0&B^aMDu_DWiXE8nj7I zFo(X$gQP%)+x^AO`*PRuoX)#TCMzr+9wYSBvuoB2COgE(_eaFkMF_Ng)bqGS)(<`k z@vk8u=7)*7nq(&N9@F3#K^(sl({>)zqKOqLIp>iBL`|vs!G$tT|&1_!c1%^4xO6 zL8r=z4&80B{KBJQHr>HU^-a*NV+;Y@V6$q5iIQcTa23-&KXq=A0>3D)7oXBi+WzlW z3>W;?#vgxV7?E;!kgE6>cp%oiRxCi1ck>zsvH7r83u5>J2XjC)IaLl%1I`>U*EO_$ zl^gyod++d3JSk46SVT8dF;!F}lszd4EXV#YHMMMvh}@&(`T1(`LL>&EQ1FdjbTW8Y zUkPdW6I`3}8?nK87TKnrUnN8bwZo3GX~)7*)V(v4<`xIRSP`FKn4&dbrHTa>f1rvl zn3QAs%DYpxonkS7Ylp*8I%|@Ra5w`8z$F1B6`6ksLetmS*zu8D0K{A-a=AMKC>nGL zsiZQ((xJJjgDuM2o*mz5%zo_TK$@lCU@VWGjsoyWVf#B!0Cpht?&?*NC_tT$`9Tm3 zU+v^{M0c`H0X?ndCkjGZsV}Aq_IzUyw9zsEAeOZ`tA-IEEpy zk$8;g&5^U?W^iaqxpoW@r%vz!CLS+I)#+Djj{wru%C)xwv+so}P}JypZHlzCr*NbMeM% z+E6+IJm6v&61mL+XFGweSL2f6t$tq}2k_2ZbWLEKf(rSKFNbcu3J3A%a_w6w}Yo=W73$y-DB z+=uSNRdfX;f85$fo{E6%lm^zswefpKh-Oej+aHWCf&I$#qnu7AjD7y0M_Jxk#4@J4 zE3O_shE`{r)oA_RTSmzetRd}{wz$7Q!CnTwzF$@^q=@OS?@8SC0kBjzLSFM{0FhRU zYml*w)WaK3NSXeD%~&e3@cWzK(82n1#1{vv^v=h0Xy)zJ0)T=S5nFlg^@bJjVB#5j z%TB?q$zDXQ&o7b3rBrT&vno+6Fb@7BUqF@C9oVMRi-T3OFB8DPYJzSgTA8^BHtL4( z;CuI@ksAhv#-Ppt1)#&e1ij4pqfAhPLkYT~356g#7mLOiW{Is92O*=+`hz{_6Mxcb zh*X{;1P2T-lsih?wCS(Hr%ZOiLAwYx{GbGQ?@@&nFHqs*l28 zQ1W2dm~?oBc^nNn3$gdolhFaV^Ya+_1(9|b62%^P0`(R_^EN1aKV6@hhrn6TBH&-k zP!x?~sa*2uFCZjmHDk%xoy_CDS`x)L;BKVa%|kb;j660G6Isd-4oe@sgae-0Q1_S(4KapN#V$Cb5I zykv|8MRmhL0B{M!2n53buj+duedY=e2?5d7bnqg!&Y4rsHMW9DHkl&M8WAIXuJW4p zuhJ~1?JzbCUh+g`^y)CUlgI2|W%_VCJGt|lwmAe(5pp2$KKI-hvC1#7ZH*aYr9fr| zf8S4&2~L^Eh%*RUL^;=`B7KQ^LU_0b;R2S(njFX(e7T$gp6-^KFdT5;h%RlQjuaUz z1cdbsWPk|vE(R8yCW)sSxMH`g`I_oFJR~Kk$cDu$>);vTLANQ-suFog4#yqukf9GQ z=R-Y8yAaTgM6ewBBIE(31!Q_FQLP($A%_o3BnU!`pxpzS@_?S~BrCsA zM|`TqGRMljQwl(bpgJHOAoK@E@84-vQW2{?*%iNP_#cX9EZa(;xREYEylUb>szqcwxZvMB7kfx_F|&Y7Ui+|auCUX2lU-#|lON_XYdJp-HW*Y`UNmOxH?#T-@T{LcrM zTPf8@)vV3!eXfahJzwG^{`m{Em_qY9-dBP98?}n&!R7YP%dbPTwzOs1oejaDgW=hF zsfXzurSbw#di1mz;^6!p_V4%5pPqHg=$(7DQQnriViPB(=*8*pMktvZ#rrrQ zbVYO1THuhB!8GCR+F~A4sIbVIix>Oa2%wiq zp*zh=|NZGHRF)ZGq>dP#6^1N6e~Nifmp(at*Gr*M?#~t|^!m)|{6st`22DU#4^n*1 zJRTnxwoje3+*Jn+5Vg;LJGP&d4lqIx^QM(O?~gYY(uqO(_vCSSdM$ACskmHLo=THPL+~-PM~Jv-<}h)A0w4370CJNrTgK{+P&wU|S!6K+j9oJGs`U$~SbV zZR-r|=&P{U#A#*s8i{T)H2KwJiZ4*0ks<4O@gNnzH#T`jr(N5wFZ*-;YUG-8JQYC< zDSwQ}cRdB26}9Zg_sM2n`jw%}OPuM{kBCCtE%MU3Bdyl{H zrl+a_efOFH+3y|)J$WIq7#)@fz@81Im43dUY9_-8xovy+H|+ zXmB!*%9>Gt8?$m@ zSd%OH0<~FEY5#cAk0`f8>k;5bka-9gxOA`o45VYAEF!?tH_bvoMvb0gv=RfZNt8O} zg}z^9#--JVAX{<-fSU(R1SJ~falt#33Kh=xCy&xi!`My8_qbO);hwtFXY_mY%^O^_ z2u6tTUDe3r4Ik1k$P1@UU96o!e{fzJ&XgpT9Q=|jO>C;_$SQfv9c)cyOtn_upk z^ntr7mcl%@TrZZ5KNouXcRUrF3UgdggRQ=aIMLhc1@-&cDlMn2P|U!SBJj?kDKT5f zpuUnf<=8CeG_nbKotK~+1gn?&{%^`?O}j?P*+YO1mB9cD3@^+I>n@xaQ==i=$lxCO z#+{P3-MC{_D#S49UX3uMIw4Z^bHOt5ew0LSOJr}-=Z9X9W|InZpKrG6Ex)(U>N0N+ zD-^)tWjwe>T4snx3uVjk3g`RR?o%NmPT1WxD!j6ovXpzOXa4n1(u22`gE|dED255j z!(uGVA09tZU_ryMkL5tRt`CG94CWwHY!>ZYPNn|roDQ+3R5R;&oa<>KJtGfc54XwQ2cunM634BuCj+3`kd0;m^$BD737&`i#m=w30L*2Vp8HD>1 zh_LE3yC5400Z*R8RFCM#3UlDQich`uj@%Q6rNXDwJGhCl4x_(7Ki+0DVtUZMdzxg0 z2oSiw`zE#-3@iPL5_;Fk%qa>H`+mi!Kwa1VQ2o(VFIlZR7kV4+VX);Qm4S^X*mYahdkuYtW}sVs%u2S{YMW z_h@=g%E39MJ*B&aw;9&3>2;;;>Q4sAA~#Q?QZCaGyY%U*B_(?&`rg(?Tm$VzDY%tr zu~ko+G4!o<+^kas5}sJq8T`C7YHTPB-Wt3ma=hByHCkM1g~bZMRkHc-R^J5BtXmC* zr0wSI+y969oP6@LoUzNvDg9$W+6OnXSIk%vPll-=x$IjoW^GK_Pcx*zE6ejIWsY7* zo+l$#4pXK^ezjcQ>}`7BbI2?0-tXv1Owi{D`w;!C6z$t~hpJM1M!pas4YFpm{CV17 z(aqXP#Fh3aPIPFfJgGr82h{1kd@FgiA903Slz1SsjjGS&c~txqkEI7lk_lokbQhB! zltCYUiI1@K}C1PSO3K}giYWj}n^b1S^} zm}wCSJKM$qNvV7_r$;Bm-@AA8WVP|CFr(;|@aUsS6Gsplr?2NXwj)`(+R4S!NTpMXhIcK2BiKo6?$y zZg%Hl-W9#Rtdu9M(mn&lL93aRIaR@hxjU*qzh|aC1|iHNhM;uL5aKjNa!MPO7V$sg zRU|^)SRbz@>5f zxaH*rt|~+ScBZwQhdh9S7h7)eoK5D9+x5wqz&XLe`r*ni*J3i3-~@))EreKqxKqK- z!DX++DA^sirRbCoR|LMV=jG3-hTsLt5>gpzjt;>NdiXy5Qoq7sDP>PYT3Y>Y+JSkV zgU^0ISn80nOJZ^ZFGe=5{MPmKQW&fnm#zBSpl`Rr(C=p8dfF0u^TJe~NVI$C^@v%J zUdPJuYWPrJzcQV0-0Jj2xn}-G{wMWb<6Y6IHF=T-N5yuHu}kgM9sAf_=txy% zMF}&|kUpnI*QCcJkMF`ZzdOc-BgCGjya%9_@}eIcQ6d7TP8)iedEX2lC|lHwc3!^! zeP^HKTtvy56A}fDBp-4WZj&Q%V_1Cw%wccr;!ij&( zRj&uHMQjJfXGLR2w_mR$bZDQ^c|(1C`vilp;Su5;cGF<--y*y|9|YmmvyY$#sI=tm z`sSPS?l#CoK)P7q%6Z0?H)95uiQ$>eX^zI7f9iZs>FZ4FCnXEF$Ow?KH}voZemW)F zzo%C{9i12*H8iO_EpOT+EJhB34f5>2-FSO>CAo)gjPQ(Lf&=#ao}eGo#))N>wt^Ed z7rpNhq047SM?ANnI&d65)NF!ziS`~Bf z^h*}k)Vy>_B*Srj#eO2$+r!cdtay)tb+o1ew$Pt_x_`Jae zYL5qJ{SZu*dw~z2iePth8<2XA7j7O?7HTwx&&RAG9G<0j#EwrlW)jA<>LxRg%^-f2 zNsRcB0m2&;9dRi~_G+u_!*^UsUkmti_3>kfK)LE)X#az$RWy5;Flik(ewOFQp1Z_h^kW9pu*Wl=z&k;w3%$YEm z45nP(g&W#+eF3+8oU0tM!}%`Y)YNOVk$p^69ya4>UAUx!3_yEB&;RDS-nfMLmgT8P zihjh^chq=ws{31duz1rTex6=y_FML1*f_Yqjr_)?`A*i2?pp^3VO-(TC(+O??wd}Ro3<-vZ>6A%K>#`HEj6vStP0q|I8@vAgpOZmJv{PlK z($KU?O0&Cid{O#^>Nfd0!C$WsVjVBr$TEr2N5g}egXAT2q_3*y*tNrRQ8^`0i?L@0 zJZM=;W$o=RD|H6zhjYfJ#im$ES=I{K-A=QOxK}6zO8v3?Y4KDDVmjIgBl1D?kA>Ua z{WI}v3s&0-=rS?+Fjw^{6S%a&he*upD=~5?Yas;7yAOrhQK|7(c-q6t^Z?id-JtdS z1IR+VH;W21M#5R53Bzu&vKI zHdEh$m8=n1`n$?w12aDq%|3AgGVao&3w2_<^E{XZug^i3IW-UKg#3kKD7$hWZ0r z67%*yEAE|+?fBA)0ydZ>;GPuGr8$itPJ4w^ZP{;y*Z3=Ri4b%vWc<`>IYZgP98Ekd|<;_zKeev z(xHdX{rG$@pa4F4nGcTBCZQu@NU=pE$1gf}f%5oHhPD;1kt<#D3Uc#hCI;2TrIXj@ zCtE>9aay)%oT2tA^>0Vm9C~NawxTu`_$?*BZJlE#E4=Us z1@Hr09t#c{=i7G&PTxP>v9ir4?ts+0gK!CUT1vlTaVnsk z1vg;@1K=oo<;{QPB@4%-;d`=y-16oln!n2uRIWn1W9ap36+K2@ESldKPuMue{RR$- zf6E@6ACziaG`Wv)BJHfGuZn^NSM$X+!Ety>z|QvGYi=bGR2R7uaD)Be>9!~enijJxHxx~rtwVE@gc*jy8&#q-qD%4lKc78Qo;Xh0N z1>3cMoJdNdWB%~ewa%VA+A#1C4d_om+0@P4IwrC3f*IVYNhT>h^AI{MxDq>9bJRLjNe z;e4=;%_2OweE;4l4NT9M!`+2o+iqobOLT16Rh2yqTmeow#6U!KNr`yb9D~^AvzQ^r zQR{3GM~zVNsYhE%=vIuO{GAJHA#J(G>X!d`0S{bdBG&pSQ`hSc%7mFSN#B<@KDHuc zr1Kx=bY>=mB)2N{>aFQ-EV}wAF3ta=jQ6_$G{T0Q^qC$#9{A28rw$b@+rqffcn0H# z+l}7U%g120=(3X3v*yokDO$t6wjSP*ugBN+_;x2(kL1tV{{=4OQHNQH$u$ClmAC)% zTDbNX2*%L5$8{=4a=fnGH2&yq_^4Es_7}K1+-4~CL6k90KgPkXn#BJ>8}=3XTp20- z^T4z`=ci*Y=f%5Nbl;TYu<(Tnr;uChn2u?%y2r3!$jPvmP z!<1$sm+;(*nm`S`PLCX<48)1J1~BkHKD_!Aj=k#UmGK{d6tTLo89wcc8y=^drYoIO8rt zw9L>v+m`U=#rN24wb|&8)mXY@XGKvrd8c_-_0G+!V$pBY_vI&;%Jppb;&)COZ(C-NEN;O_$^OFPdb(*WeH9VAcbH{YR#2 zYfc~0AZjod9_llR+5lwlUslVBL4#Y*4>Zsd{o-F#qSh--`A?-w-U9uG8RG0e=v`HV zIe|>sbJp6gMV5)Vaj=0ha-*kxR^ows0hPsHq1te4<9I-Xq#ALsgheFq8tQuSzqb#gmytzyngeeV6CH(8z_<-)eTSWOha zxn99+Uqn_uI_E>*wGY8jq}fO5X?fUzhO?q|=e{BGK5I7WnJUb{*@IxSBB=7k)xq1? z4ARQ@2p33n#&e}UI|UZVT?%bcnri%K;A~HM7i^Kp*Lp_%Gmi8|%Uuv@e6WP~XfF}e ztQ2o{oG?r5zUFvz6`x>z7_`J4S&gmkggm^f5~{juNOd};)o7`u(s@vwU!6MIIzeUS zQDleG^2Ls5l%U#R^cddvUq<&&sWnQAb)cB&_x8>e7avTK+H)~r%ETc9?}EBHdgG;B z&I=#dW*xKW!FKVzdyaw~(nTzCP-h3~YvchYBaK~VrRRx`6q2sY<$^~7{DL$c{|-uC z{l6MTuaBSea(_puoYD5H8d7L^o=6$b{|Hp}*nxWVRdw(&FMGQaTzE%oIp~1j$T}2W z?k_C&uOidO^AaPu*|b-+U`Hr(S=_by4$0)u!YymH=1m16Xml9a#4Wr9)W#6`Xyfl- z0!5sl=Y%}>qWe+9Xc3CN@u)Y#3nAjVeEodmv^b(Rmxfc3wGW;v+j*lfZM9 zA72$=h*G@}5l(aik&wLg%L9to)#7rM$eU-#tmU@KM^N`=`SwmQ85kfmYsASVugR{h zC$@VG?sc0r6EWT*&Dz)duz4A*%d+%%q=+5Nu#rX_Q! z@-w9V)Ah%08ri2$sHs2Jk=?-)oyPHXx4H=*rm6%3!uO<>XrJwAN%yVRsS101`A)`i z0iNEQsIX|U4|Wm<%1=M_5R+4LL&;^cIWCLa$1lHKHMN@BK0f5Xd5FdnUdn@spM0oq z{f~kIIFqAbE=E#vJ@?Sbx}?2jP$#4%u&LI&aSG6W6uwAxx%7qa{k+Hd}AyT zERL$Y-e}=5Q79^N>wD?mvTajBfbY8s#sozX?_x7>sdoTW4<%VPa@e^a^M>PRqs`s> zSQsI+kEvo{M?|>o`d;)v@_3>z;AY?E$Bc0ZmteE)(v4?OJUlu4xjV9&gOQ@kOZ9@e zPokji{oj<+F>zx<&ZM7T0jG2eH&G{wBw=fHw9wPRIfz+qtWJf>3|(%5%6VC^{6FH)G-v`lG@hom5MVdLB6c~V+!=V#v&t|b^sLaKXe4%&4c};uawz9e`$))a1m~39Qxott@ z@*wgx=9sM!iv3xypGmo{*6jEM1&Bo1gOegxe3Ckq;kj&96S<(nNCJ?$*dpLEbyQ-8 z4sM2zy=XY|-R0@dSD*qXv?XR^Kf&7HaIjFM!mv*gnBQ*TSUx<*gDnU{&O3HqzZ9oU; ziqHDUY`PMhtoX1^uI1HxbkZ1hbvC1qP+|Lt^^IIeQUy)2A56*2XNs3k^uLv*{F8Rf&tAi~4^QoqIgf`ya=@ zGt8~w#A%MrIF!(lrIWeL&SuJD8u%=u^eNlU&OJ2?ECi@z%4L$&9{p@E&7;nrT;Y}U8fwJE zxN3+-65jx0%ERRKY=R``OTrnZlO&U)q~W*nq%X)g*JmOIxn|~y@;VnPGCeZg>k`$Y zoDBIS5_Ppa41^8`c_;+G^JwORyZ5cJ2-p|w@wbrfwr^vbD&0ulw!>=pDlFR+fb(jJ zm8BbYQQR=Dli28no4-eD6n}un7|Vt!V+xKNXxon{5i4zF2I6DN+qDq&(T^svzsuQ| z-T>8IlBRM3n+&iT5)xXsoX#fw^dbLr3QkL`SJhi%8?s{Y0FFmKffi+(L7k52!ExE` zCe4_}o(M9h@;sDr4MC~o46c4qGwfD*+Q!mPVnSf(;H4f~W)jAU&tESaNLIF%ygOnU zeRye^j$YHI#L8vR=K!5cQ3^w*=y|30K;8`ixe9aoyRn z7fEg+tEIpnMvQVUBc>oA(v*VS_TQg|kW`loW?o6y0q2)2gy%>5XuG`;4Fa~^0Boonzp;+8dK_DsEM3o!HtAz}3yok-J5mLoR z{=C(w#*@UeOJ}zm-f9{SvySLzZb}8g44GSl0BoN+J}QB@vX%A4s!GP*# z&X6UpCmOJTK(N8ndPGW;Yg%e z+v1m0$h;noP&Q}ssa64wDA&P4jq6a%brxRX(J7x0Jc?*Ho>F@NrYietcH@?{W*>DQ z<^HFS)hpyq=5$Hyj@BLTzum8SK+Y>!f^y~WouNiP*HEG)C9KWg+1G}sNvx6UC@@no zlWvTsPKH4%?D3=XmFZ3F5<}1Sv^U!Y**dy7@b&$63*UVmzfD;IBO7>X*1eIlq|y)| zfH|RwVL@&DwmBo0LT!`Q2IF6%kphn1{2BAMt;R|4wXBGr0?@}TXNyj81w|P>Gvkx& z>Z0*a_Yw<%DX3~RXXc4`|Dexhs>T`V^vo2>I2hcW_EnZ4K_u19^kPFfBz(!xkhiAr z*-JbU@&d9?YQC7N@X@0>{37$)qpU`xF*h%cr;`0FO6UeaCn{i&cjDT1C1EpqJzsR} zSlYPmcwpB2+`+F2jZ`!cwYIcM`FD#Lm8*=WPgq;VErb@D2sr(K&a6I-n?~^yfMc$2 z`5tR-Qm~-ET^0(TX9AjXoVJ6RM&2uN33zGg&t6gDYZ-GqN18Fn6S~}d{Qd(o5LOf6 z@kwQh^Uw`th~0?}vEAuY1e+NScqZiL|K4?>H1qJdAyOR0|=RXiUxm+MXcM?b6HpfRhpk-KItc59yuz2h&W8j&YVGtxOvNk|Vlb z@98Zi3>^<7^R5~9ml^tWob|IKmHh2;5x;76w@pJ3Nb)zfdhheDUZ?-MUx==lTtQkn9CwoOO@5@!9x~9>jho~Ff?4y2w&2GLDgRUv_9v_>-rEcz6|Emf0F^6hcYhv(G!YlKXWYf1RDdS$>BU zyL7hIYauOBhz;aUh%d9J0Rv$2Faj-;7vMEy*=vpGgUI!wQBJpkaXNQCJsL`5+2d_v zN3M4jPD#0h!KL|0K;rY<+T8DJhEZjMNM5o}=fy&rUp}EsBQ$s2xuz2S z+P^TpQWQ3T6m0LqC|{2Am`t}XhAcyUIw$22*bcg2yrKB^X#JiU**gE}cZMcfzHOcb zMXK|GyhJ>~a57E-O4{#WaV*qabn@U^eNmr-Ls7gsEBiji|DdRUye6XHN%Ws=@6*=@ z|2?{n$E=!(c>9Q18~!Nmjmvc=Cl4oO*hS8QLvcMnkcYvG#oIX6OvLdq;xP{)`z#cb zDsyz_1{ratCq@Z|fo0N#KD_jOrSGI9=6Gji0-cIv=g-ls3 z;i(fSZS3cGWP(}yx(PBC=)~I3iV9}zg?y(a#JyZ#$tnYf6RiwyNmw%D3ruU$y6JlQ zU(gRhNUq$dz4=(SPXrgul>vj%i*U722`@wt_|a19-*3e<4lhvEvJc-VdnXdJ6|0TD zcJW!q6q=N`5@5?yrP`ZztQI>^edzI?%yk6?uRm70(Q!G^q&t_Ut=A{XHqm9`2*VScsAz8*PTiR*X1|Iv%?Trbzt8pthOdN+!{%HWIq^Nlg(5|;?Th6fs`rH;pfJJ- zHFS`=VF$8fcqJbmBo1{UQpGQr#4a`?>TRX6f=)6g1)E3#ODaA*KQjX$2!IyDHb)iN zz!7dbwCX}XjAByBOm`A-ZpWxsz0FrMliJ!xRlj&!>3Fv1H_Y+y#lGxcg=VbPu@v7! z$Y=(oS2n<}8+oLx@dsixACbib@Nx>{!CJl-=I>jQt9~P4pjv+jGo-1hB3x-pa z>*f&Jkpj(rQvvi%4==1o%XZXri8cYcb7FIb(^*NMi=is~G%ds4-6i!L1VOlNhVinX z4V<$T;@t9&=}NPCQvyZR?say*B5o)I6#@)7DD{TzCx-j3=wyPZhQ;F=bw z?qj`9R(X_V8P;E66(`97+g-@n_@kgHPVHHwnE1z$Wp<$KlvSs=tTz=A z{nrn1V;QmCl6&e9mzMkAEX5{(dh0g_g3GkOGmZ2R zaxezx75_AJ80sS>Wb%K>SdQq2cQOxeLTF0%J}XRzd$v%omKD( zKHsR~^X{U9;jB4ch%htc(FgOzMhf@8c1&xEMF3^PqqKZ@0*ySLnx$NY9E)4V=5PB~ zNFS46mjghonGADk5bfoMd7Yj6G$XnWN7u8e#h9ab1&jTq6PEf6%7590lG>rzTzSU0 zxtY*xbo=a#A+L%Zd_GcD?^4H3UPr23O7z;0CB(f<{Z0Iom~y>byp(y5)Z}DV7O>)F z_27~QzdbZ<#Q}#M{FuIczjXRW2q88udsQPZa{7-A3EuDmNMRUATHMn_KgnNw3st=f zmwpS$xLA(ttw)zLJLm04wREoOk4d^#$Z@$MuiQySUXB$rjr^qmHEUjA*#5Yb0fXYx z>wBG%V9AM$bl(XeymcWno+f-520pR4#d}lk$meW0a3N38ak=UC=lz{r7P&IZBYq(K z=KWJuSW0ODr$1j&{RUfW6`i;bJz+F$q&%JCWwfDV47e9+G z9;@{jQNQx1u7Mmvy?_m$bzp#@KzpLB0yKYL*-X0w0Y;|^3q0a6;y

_(gM1?$*d9 zDzi?Z3_oWimJf-IwNa+f(V7eB-j=t0!#GntP4-?29c1BekdsmfObRy4wr|f0es43WM=*k-Ws5a8sv=F37U+UT<;Kalo4*0} z4q5~gxwcWHv@`TSNY3O}^!!`pm9~>i6Y>nP7#`mD?$$JzdgPY#RLeP4n=y_r!>1e! z4r@Oj#2&ZvkzS#&F7Vkl9>a9g@1In5L1_c&EBSaf>%}?u3udl3NfpWun}ls%qMnnJ z|EyRB&rLp_$7WjTERS|oYMu1THkuTa2!X$a)Cu5EJ+uY^y?(dLoNh^#< z1bx`w26Tia(GDU|o58_OB@cwE^J`alII+SAsbzWWg)WaN-4oyA&r5iBt&>BD%$N9T z@tBLIRZf6k`!Auf%L^eTxjv_LR-1uz*%^yM%{pcv6)HeCN5yWNXD4-v!rCCg_LD!| zMgF0w5YJ~BqC>6RWk|zA$u7>Ua|rZWrvUsZ^FKnwjeav6k=mqME#-#2HOWe%OUF2c z?HYg{tZK?nr(f&B0DS$E9Hk}s`ggl$swSYLkuk^#f!QghP3X@DFXVj$7 z!j zF-ytyVzCQtVg9Z5^34qN>P9qgAjUytp^I%Bk2C_uf0Nbwd_7$}Uizna{z99F1cJ8J z=M9s3l&yuxdxaav7DIT_M;9+WX^w{xaB`!$zrftDiCKA!ZY`gzN~l4Cu<`sj)0)x{ zb=As>SbO2T8B#T=D#Uti4irW2CL+c=eDXaz}A@sqQ+*h&g8IX5-? zB_MqpowbLi$--L%qxdw#moy(BvcwRj{3V$luo;9s2wqtJ0x~x0&)a6!MhWAeYkBE6 zQ=2DA72{KB#t+bVkCKdUaTQdOXi`yPbiK$;XK@LRPCX-9-c0hH z7aDusqP1hyJDOK{v=PN|51T<8<<dGse*>**7r-diL>rJC>mi zqmfrf?z?wYPEw4_h~!E^;k@QMBDu2n%6OYDr&jgYm+XvvQbUHMQ#28%X=s^qH07$Q zgh=9%2H|PwV24-9$1WCLb9`m~R5uT+YlXE@Mys@HvBntVc3Nls!skfvAdubi%mB_X z^?YS~5LBz_KP6`3wIhX|kWc0syG|=#B!ZXOhWIiFSPWvIpJJKAhljG1I@daR37Myu zqKw8KoD^QQLKR@1p-K+fexJN;s_h%t<ZhQv z0r&=je17E*Q$gz%6qgXrBeZB0Kx+3Igp|cz=i9p*u6Pqt=FUMF(ildKTxa|8T8>f; z32vF0{U*EFJ00cgoC#YE9a(#dnRKEaImgK|{&uEd(+O71Bz?iO<`=0?!d_qQRE@VY zcG_-I@Y9&a0!P7t`GUsD!@Nuw9Z8uV3hV8%}>@RT^v?p^z8z9YJ_uREdrY zgL122cs`9hFLd%%SP>ryV?&z>V>#5>hNR9Bgn2)9CjjOu)e)h-7@cPudk_{X$$J89 zaZ+J^?|yf#zXD4C5rpvtI8AH@Uu04iESw?N^T$&mGbQCIL&TR>-q3>#t9u)iT=XQ_ zSENBSxS2irzF=K7|fP%4EWB*Mn~!q3+Z_-&$;t(+af zG;k|y(`mWkDWyh5Hq@UxxxjXh&jL82CsXN&|?LHpUQITU*~Q zw{~dN>mfD`WetiF?V?2U>~;uz7aSZO4I(vWohA}=e#G5Zub;B~3?lC-^D-zpX49G}$fk$rmhrc9XuD3n~b@Wj!HP?MPLvKGyN$$#bCvQie8Sius zhrEu_xy~;psUgH>kAWSRJacMKY)H>xm6WG%fKXC%~6eVn^4cQsX zn$NqZryPHL_0kSse5_d}ywa?}>G%Odbp&ENveKyZO}O({rD&Ife?;i@jCiRat;|!u zzc#h>oDf{-iBGPcG1mZg2L}7dNp0ZXfAln5X$@<`{K;SaDPj^91e>K3H$Qz$+5P=M zYdeRPcUuDS_rh_lL&J!7UpB5L%)19otsYwm4K?RRlN3j9*a&Z22y>xSizCX>-%@ut>1Ppl~(x%hj!egXb6N7fbcPCOv7VvThO3CficQYNyng!eBhbjJ%pN=Kkk#~CE4erFa1W#X+ z)_DnE$>ykd&Clrf=o~-7Pqq4rHq#>wtkwgYX!eE!@Ok(~$kEpB<8OjkaZo&noVb5D)>UF*)X z;umdJ4zd1v%isR&dFxK1iv!P^tt(j%cRF#Oaa>?H;`u2v+ogXyX{}nMJIa+GHeDfu zd*?dCPqbID^klv5{Vzvk+}+`YF}X;fFDR&U%p=rMpFS>B(m*3+&9tecCD(Iinkb$U z=E(p)<5^nc*~wcbVLZWlNl&|_ify38C3BUc2;#&U#Y(-N|a z8FM+WDoqmF6Mn>NUmpZGxJ*saM%Voobn(!AKg7(Y!#HWLJ;2ZZfxNI&4xN3HGJ)v3 z!S^Hh?5TM(rP<_vHWDr{AWhmjCx2d0{%eSo9K3UoPn*Y1x}LQ$xa%i0DIHOaLWJWt zm(TxlsL$d~$4aXvR#$R9NiaK9BXV}(Gg0@?gYL&%Dzy!kcVo4S(qC)bz1ZAz4bSe* zmHAe3Liee*B05N$s?dr0_Aj<+XVB36ohoyfZTginW%f&z>rMA(Euj+e*#KWLW@r-j zq+27ixpAM&;FYa7Mh7jdoZIlr>EDgT)1Y?6?z%Y`Q@|0vH9he@Bm0b$er-&wC0Q5- z+_0$r558gQQ@aP+vxdP^Ecx84T0i4^>8j9+>*)km40kfd)y^>k)^cfNB*GBY$%FGV zFW4@hLcUMzfHT6wxbWdW3m#Cr5v!i|C5e4no&b{&8ch4{t zkA2rrVnwO03hltyt3}O3GXM3*yN9%rESz-nm&PC-*HGTT~@~&>47DuHi z@;@uN+wPe4)}Pg3l4+?ldt35P(wCJd#Fk8EI^2ud6E(ci(zyNOy7dND%T4Uq;}+{V zGR*=0F6za}qrjf{z0H@YM&-c!o(@^=dlN46&#K)IR|{?)lf3xzOp&qc8B1D_^vldP z5B#%rQ@f^8dvr{=o{~ez6a4`J{Lil2Kb1b6{1Iyy0=Jr?(QrK>hLCLM^z$P+N!Nmw z3w#erqcQAYK-pRF|7>y1Vt-- z-+a@Y`IplHT=R`LbtlycEeM-8W+a%q$V7Zor{Ofw4mYE7e)r1hp%VcYy1kH;T)hQ| zMbN&fr(NX(X;)zVIU0hE%{bRJg}A+M%NuU|oSa7Qs*HD+|4_R7weNW6*7(-pS+}1W zRl<`CEw_x*OaIJ^5$(P+W$lQBW;>^sIDZz^0mFmi{~(_Tzn?^%CB>jV$6=_hUzq8! z95(o>JGY9vwVWUjREqDU=fqE(mUz(k`>{XfUUC(XOK{@%U9FH%1phu0<4vCI1L3om?@={ZN6M4!CN zh4-W5^K23f_IO;El1d(C*DGGSF}E}9OH%dvt(Un~`R(^#e>zu%uAF-!TYlngJb`fl zcR2O%ae?leIGMr9nXBI}{NtHi#{cw(Io9Ey)ZK_?FGZ6JH~v{wprpV3Tk*@i8~tDYCwh61=F^K3!`6U1xDTCB9{;B;%*(Bjdo>a2Y^iloGnCMz{xkUD-el)4@Nu z^+r~5hJ+dombpgH)23>#VsHK4e%+*rw{2eQDM`sXP=9UT1Q3m>x#!K>5x>n2RnHeP zyX~u0qg;Dx~mDQTO4#kyp)|+7-{-WKDVUkKT$se_yo#1)qt4+nWn$)?-o^Tq_qiwc4 zo$^d`5?^*r#cgF;ACEC6=jH{hmn}qrFl)6VEM`K_+4KdT=;7Bmc0jMjtL)R&zsG)Z zzk}GYMn?#~y>xr;JE|((4$I8^aPqhAHp#mkQzv19G8=>E#vgL;mA!^H z%+v|wgx=3d^Vz@Os8m@fG@)cA;#J04boMCjPl(tvr~$A4X$1u>=mB8uQ_BI8W}?ep zdKOTa~6_-ie{4zvEwgeN!pl)f=4uKoQ)qo7nL0tkUY^ z8;v3pd$ET<#^sDgULjq2DVM+8xnP8Bb}KNOs9bs!EQ7NgKVTrED>=Imzxm14KsyoF za3h6C32rU+cQ=%%5*VkW$q9XBooCAu90W>A8`?>H#GyPP`*-v{V)0+}Hcks`L zTVC3gb2h7(0u+l3uJR-Q&sx&aDi^AD^K3@?=lAQV6dQ}W-IHb<-#ehv(4+OJ?`VEQ zrudr0g@rmxGo^L5O>^HN;*Ggf+cFXm9^gS;`08dx;Hj9iudky*a7;lEQFrvI_`973s!2fK~=|Sma zV~dkQx>Z-hFZRy#eW;zQ&p+<=UlmPsbw8Cn5x(3DE|FC&vOwvN_Z8v%K z0YI^Rd=*}MKOyN8h2{f#=UYQV1HZ0xqQyFVpipIBZsoldbRtpZ#_!sjM0Xt;l0nB zkK=J#EMBM6SbiKj{DXs%h=%1zu9o5Oh}46BtBQ}N8m2$2(l8rh9B+) zMYxHZW0Xvm>X5?f9bDQ@3ZZ)FMOyYF_w21oI>>F{2|r&_uS@*?!}5yMzdn1|AeLFK z^?Y^J?}W#%4%nd*z61#1;o_>9GVL>>OgP(!%rc@frbuU@}d-1+Q5l=nue~=sc(`dCPr}dd0 zbvPZ1o6ie8qd5Bh#rq#^7G>~&rFdchR8LY?=QL&rZ;MQZV=N^EBF`l+B|jL%yx05H zbTqX6(Z9olPo4BXM_htg@vNF!N57)Z>Ji29sl_wXCg_kWa49}!K2zzno01dt4#8-} z?LX|*IkH(+o{r%k?Ib#dPLLIOrdyQNHTCaZjN5ngD!Z?~CjG^Q6YImbR?i1Xh?3In zOMB1U@^vhHbTwc1QJ~+|3?s^b?9{xg?+fuCk-y8dA5cB$(eY)rudcND&bsfl)F&+j zcHpMVdh))oKI#Hf?DFsiLb|@;Kh?q1!w>XJCnk`+Y)mz4-(5~=pxbHE_vhso45g{&dN7;Jcd&G+=GZn_ST#dVCjHn>>N!e_lXqXu$Hu>h6^l9s^CNH$i-7~xB zkSKPqo5bC|2fB(bdTE?7uPv+KY*>H7#Yc~>Hu;?Jc_%x@1LYMEF)#b=PpkR7EOx~D zN6*(bco~9VX^hN<<=)eO`J(zz`|tM&gzoiqlwy#4Sntc6ISJ@GyR;O;uY2*YZKXy8#;BMb18UOwcJOJy%3oaqVouwgR1{Co*feUquklb4AHBGJHT zmVEY3&yT$?-*w1|!%&XQGNh?+M44ceLEb?GRFkA1E&uVpA@R`lcfPXrAU0NOpJh%v zx*~+q3%E4%r-lCnXI(y)eh;t81MJYD0Y=Zcx^r(+f-X{-L~~b>j8f^9ay0T5RsV8> zaZVdAAJa+<8Y~rO9Iv_aWd|#V8N=xN zrzZ8AGIH|w{DqRjyZ!*-l0GANUCSf)A@V0H3Li*uw9(TWDOY$A%rUBCkc>|Cw+SiChxfAUSHqXD5`gV|Ep6-l=u96f0pg-7eSgZVJ3wtzR)`P z>CuUi+qWg%LZ7e`HrF-zv`-o7|NFH0+sdC&^u?T$?Tq`H!wpa7V9I9`66pIh>l+{* zaCV(9{S@RmU(K$DMvl!ZTQ07*7URDizuzf^(vh7A+E!^TrX;wR^r2}-xGJMY*eT0? zRc&(iTx$%Cv?QLC*?2Cz(tJCLu*~taiCIV+@(O=Zy4m{8Bo+)tUL;>ib`VzPAn4ZE zV{-zOpiC(JLl(WpoWnW4`{kSU>t&0Zz8%nlFtwLGhz_|JS`M6=GfRA_WUbjNw#_&k<0^)%4pnQLf~Pcr5hHHv@E zz@+=53^dB*Zl1Z7dEl*=ySQzjkOC5IUX;JH{rD;5=G?_rE$Q9Q2q^kD?ropE7_AP> zFld`RlAiBb{}FL5vrBkyCwCfaXI)7gZ6n=<-9~JKa_{NEht^-~PA})%9z>8-A~%0q zY&Jy<$#ab*UH>|S-@|D3!x(*0yb_*%PX?3X%v`V7`YTOk{a|7H|Da!CYN?t1bmKFB zrktY8jB4G?5T-s8DHEN)V*2b7-3({*3)oujKF zrtSvzpPQ~cbgI}!B27I~P#msK#>|Dh!#_SdUD;R+*3MyT)xL@)qy_qKEWeql?(Wtz z-yb38CK}RG?ePz9N5=iDRcM)Sj{N=m%&kUVDN2zi=l&?%KIhI~M7IkLIQ# zTXAF@iB8U>3o*uSy?H?0OZNMtT92WmURB)mFSOKDy3@50yTmvQxW<2K(#O03KO4fy+BYG}wo zkzp-gV>@NEUvZS|8;+Fntk$0>Dn)AYNu>t1S${W%R2;qXTk5wl%KGEjbj4t=(RVkVL^*PZ_U8w!GJfWrmb-|9Pm&u$ z_1sEe+gpCA6N}H^>+bhzr95s8e|_^)*w5?6zohK=9PgdhG#zcMM1AtU5*~D#cI5ut z+31)U!E@EkU*4aRUa!6Tr))ApyCuECv=E~+9QL%RiB3GcNY=qIRSil5m&abmKRDg| zbaHYzH{ElJ2K=&-#tz;FUwvR{Oeq)-FKpP>I*HV*VNIfjOp?2dW5C#cV1=)Q9MqsU zXy(O@;?8B98j^dTE3-mgo4e|9^iZ4g9!5AXeMvE)9Ax3iAHCO*O1M0*=VRQD6D&z{ zMxL#pVxMgra5Q$NPqpDY`CnGPwQR1iKCffdzSafpj91v-h<2l&EP0(*c3OmMC6lKn zy;4E>G7fSg^dFL68n+@}z4fmiwV1oCL;(BeU>m_7nl}vY{%i4UG32qbsu(+-KT;BC zTQT9^n%VN-?X%_XBO;Vr^o%1aU6+4Ey^t(iup51vJ4qJw==5AlqgBuwMmp502a!0I zA=m9s;>|wa!`c=ds7yCaLoV_wp`nDkHv>100^7jPPfr9n9gA?dxxku(*Mx!K9N}5R z9tsUxNj`(v%PSr&t=Ko^Q3@u`Y~gz4<7+70SI?C6_B)Lq@ zRWU}OZtEOx+j70!IY~XKQncESF>>|1U7fT0;q21e&$e>WVVEDBq_aNVMN^avghjHM zVDTamT;Mf%-p=CvLFFC*c2U`>s{Qmc)LZdRO^TX(q7@3PUMtQ|9;yBdt!{mDZ*J~n zEL8ERtCDv79uYsPnCJ-&GdBX3?Vq68Ngd>dbKx4+XXQR?72!nw&HtVb_-BdApkx z0VTIrmup58%t*hyd{XHpw}cSRy5(IF%6Yw3u2?`+_6uFLlt^A|o!arMK_+z})~rbO z+HaoDs>#&H7LU*tqJKX6)_fHNdB&CgYSpQL#CNEIS&3=R z`ZMEi+7P;G+Y-09z3jQ~#<`v8zyFk!`}G(1lPIl$C)2?~K?Tj=ji13)>7~gi26|a; zSE1h3v~e^+n7V%W>;CNzaU6t1{XMz=LAV%5TXC_vch!{BXCmz4|~j z^3xB`7Zg$?}gqe^1_p0)o0FeS97_HafvYdv4$pHS)5enE*!jF(r)9vd_E zb8}U#&aKAjRLHT5Eu%kNLLfXj;85PVtsN*w?#>*_sDxL+kHXwk4>C=-fRD_1#~3VE z4wxVyBg;Cc(a4Vfv=oTtpiT`gx$ohT1{SW3c>c^*1LhUh#yo*(67LxRIp|sHDI~_| zYCX1pm&;2U%8lDVvGn3OHumP@CIF9Se&!-OF9L3zoKLij{Vqlh4Q*zJ7{-NJx07C>M!`4qL$YFD4gkS#3*V$lQwYCfr#q)xO>8S znikDdAIjJ+2+?cy0h>?g@+XdZvdJ#yhq@Bes1KIMz% z*fZ<1hAzBdM1n(wp@SLxUjR0zs)sXKCmpO%Txa<2zE*0tneYU5rJy{D&zTs!i|bZ`_|Y7S9@J)AhDKVEWB>vc^cT;uxPSJW4e~?-+5>g3Z{2B6aPJs*j&V z5y+Mjox`+n6~@1eCd$XEQh0=&X|Bt)WUL{Zc$*V+5Z2*udXCBDF~A%LZh&XLTY*hS z#3s?l1S1M~2N<8TRw!MQm9%=@1FU4D&roIXj_h|#Uu!|2;%Fq_dC9)j7P%%3 zdl`ZWZKm`JfHLlveK1)|l%U6G0CC0hJ_&n_KmpUQ(!1Pwvo3}KsSK#0HC!{R4}60S z_h)AEg$^R5yzIHn^wreMao37MO7U#Y70`#%O zqeuSE_1~2?);2E}p6-LlwD<_1M#qDHL=v5?+BR%->b7U?iG!pI`uRT4>w>v z29i(+&0x{rqNb==19%A#e^xvUsa~P zlTW729Z%0PNf^hZPoxG}Z;i)BX>RiR6(DXx`;+C|IXhr%H*qj&58%*BtQn}4` zVS)5r+ckJU-&VR|ql;x)2y6xNFD9~)xK*DuUh7ofgROR#T-x5Rf7&`K?{72XS-Y>C_8$?Md#&tke8KW_26ef>3_n@ur~) z502UfIt6k+H55@|EE{lDp%X%yX+x1KxvNG9K_@{a_R1*6pRt$pWX}i|lkq})+ z35uZdwn>oO-lf?(VXIaLe>bUeByyclZTZayIerj*4IPHTftZv~(&VoggcG8mSjAhz zPZXB+_y{rQP{5O8!bFqp=A`W{$A&;xu?xYP2q9_ZDAaCsXiyn)uDZ@!DOL3Sqe&I4 z(1vI2yCs&!HPJFjOw$n;C8wV~bKJe#t;LYd`<>V8xc*AiTMSB`sR~Qz%7-O8;RAVJ zOlwF>GmUIJ{C{2*$Yzp$9JU&h0PLCPGpd~vrG2JN!qzr8{$+diE`u^ukTASgj{WB`TAxxxMLZzCS_qnmdiYy%n}z4!ksFDPMLuOzbvrR3aaGckQd|giut}HWBOcK~!e=8Y?qv|)DK6wx(PHqrv zePyyS<=qk)=*f%-(tpi+;U7x)L$X_@t@mu?$}fw?BlUy90eAE&$R{Wdujy^V!GNtj0y7muc+T$ANf%+}>JNjd-!Elp#nfR3aAp&3a{jvGM z_@*zVH~L8Fuk-y-L1baPHe_Z~jSy?G(tb@9@a^2O7AvtNP&R z^zX_St5CApJK!^ztXL18t%Her$vB6%{soMXvbN!+-VMH;Q>VZ*DbFS(_|f|jTeDSq ztAQY2>Y1zZo?IURp1*D4+-oWFucqqu@C7R2xG>J;edAv%RZ^fnR08*uluyi0Z3SL3hB*@xMzp!%r_;EaGa~+xC0h&0xH@Q# z4Vu=x_U>c``jz$%-7oGO(StG3m$G1YfV9x+Ehte`!s67+2smpa znH7X~^ly(9{HoknfMEru@>w}G3B+J9-=Z`^k^Ku|h^u%BXm??(#y7M$#dNH2h$@=q zbh-npC3LF{ir)!qHXs1DBt17Sj4GnfR?S5gf?8=698FBPa*nJMgk+mjo3|#2=tQqd^zd0-P6H^z%Wj& z8s3@ho|OkO0FSsNU;0m?oJs#g)Fmfn@pl!V?HAj_**P%k8m3|15f7jG@kRtu61{rn zoJe9y(6>hp3)2kN6A_c1_`gK}akYLET==5!;B2ifuHRs^%abHH+BckGyyYDAM}}VE z!g5!^BeeIc%E^O}Dpd4>rZP6pJDG8kNg#jDnhL&{zav{!7*PSqNMLYg(o_kyecWJS zNDmS(x(P_f%`fFy(G0wT?iaCpxo9s+CVda2DvAy{bYdqB$Q8K83}f@ zT4c@ih}aGgS0J5eh34Tgc<{97hq4qhWaDbJ>&8G4FM!WFGAw0bA^PcPpMi|i7+WZsxw-kLxF_OIYO z_O%zjSo=fQWSx=h)M=)}5rr~kODp^j!@?;I-AIp8MmChMnmzvq6Ba`5%W?4mL8o|l zt?seAvnwkNyypfX2;InG>g!f}AUzblal5cel{b`Q-)ZX3-I#w>4E$!Xg^%jD(dgO5Ytj$XW zzG79?+oeCP(CK{sneYtbH8v&$|JK3N&`<-2C_HfcrPs|9d) z0>hf)89=Zp9}FQ z(?)JYzT_$Gyn7~w+_+|^$z1Aa6_IuS*>MCLp~~BgcDhmIl?ILhyLPGuLR9}6w5D0w z%GI*!YE#`+Hsjbj+rRHf4tZd*$}j{kSjWt+t)g&t|4Iqf(*3}Ne0(R5p;hEHz1*Yk zd`u=@Yp8`?+E*}{{-|s=-KI+3QXIysoR~NJ4>k!8`+natRD!iIZeM&7(CbUaM#vw; zNw+@D5Xgc;>AVNGg~wxwo%xSj4<8p^=cn4Duj#PIwv8P`!Z~)adj4+|$D0yE#7!4) z_In!S^Vs>n7h*)#788d1sCyc3V9F4x3BzNLR!MsXmf|^mdDJ(-odRgds_&sVgix~w z?bD z1_!uTp-F=qg%WnoDB@%2AZtv|0w|;i{*(b3bovB0tYpmrX=c7{nw_Vmgs6mKq@b8+ zbmFKUNc%I$na1ks=amMSXN;?k#NWy^VH*4rYAwyc&4N2NdCixULEebRo)3pfS&HMC z+;3TjJmL7=!qgKNOHD^(lOeUOqU%g3;fqqywb|SKv@+&`tlb_|yYFosMiOlr9QZcY zss|QuH9+uYvqzN6z|TmnkFug8P^FZ5&Hd)X?7DdS;)64ab+`Ea1#6v~VFi{FWJYO0 zzNAE#Gb2e8vAX?3F0aYONkM$1u!I1hsBomhFLERTQ((B8T@*J*jpO&61oLgF2hew| zL^fV@D_+~%1^#a4Imh8EaVH>zhe)_Xz@_&;x9Y^=WUSsL3=b6{uKO}s-y}B>Eq~fH z2!V^H_#oP6jXeU`NIP0*yF<|ORf`0K0#vAk=2EQ){#4ml!2}qUcOpm)En_sAYrAN=cUl>-19YcrM=~?=>o%A}3%net`hCUDH;@um|zStnqD4t0k9?Qki4#PEI3s)di@FT-@lla_Ti@Hyj#_f`N)7z=X%Fayg zWo~TtU1JVD2n2ra*AHCB{ZbkDohok!L0sya^a`*L zSDle09+T*rin8l<6~%AC!> zvni))FvBe^)#>&&P&o3tOg^?LnYYk;_Mowy{dM#%ifuoY>b?KP*X>tcAc7zgA|=CT zh&z^4`RH5j$Q>f`Ad^K|sYGBPqK)JkR1YO#4&p5pDs>L&S>osb^-oo-rmb;MfUxe5 z?@s1ov)4_co$4mGiIF@yF7?VVRcfk>m-cmiow;Zxi{|PP$jKNS-zm+Itd(0xeWgMPfY!FI6MYrrXS2rf75X!&0Udx9w#(3L6 zZ=7eB|KGHuxQk8M_Gnly^_2jznGNW;$66OImDw_o=IBe*y^B~^^?DL;3TlKGPO%ok zZ!y{K505;Hmbt#UcZe!SeXrLDUTIoeTYqyeWsqsGPTo?<{KZy$w_v(1zMYEcu_^Ca zk;UM4kLHT1Sr5|@Au+oO)4rnf>Pb!T(vmB`s5x0qb3zbPsnAs!5jV8#J-S}ZuFLl; z125#vVAY_{-nZ2h2``(qk!uJpC354XpzMkJB7me@YccwBU8SKk-F5|1;#?y3SG3hxmFE_K^P&G9u(iU<SP&YbSh9VLxQ#svuoy z`~MyfkG5-{>-~AXpRd;o^y{IXuq8c35~XR9k7^JMf3(~lrdj#?9jpn)M9lh$Yz^QR zJxGB28ZK_3l5Rr@x=@1glD=IUEeSL)QW%#|I+t@dnEMen5H4nWQ5TJ^S$u!#7LJ$;joKr=*xa+H1L;z5Lg12uclDR9AL^#Tz4ln749@8;zwgJQzGaU zByHL-_co+LW1hau5BA!9-he^nAbkM%f_8#?Xc!A`nOfBxs`myydWr<-E`#RMsgt^Z z#0K|eTZpI$c;~hnawAmIY(C`=wXQYJ8+Xd#Q=8`?lVsaL$&XUJ0mifeBF}j6Li)aB zazbBB1L!v}R@W$w8$`ltl?+vS0gN7wd*KvDW@Qx3RXOAb7Mqa3Sx%|5r>RO8+CZzd zc#bEs_>7cVtg?l7=%H|h{s?=lzs4y`NZhs!Z&PfXsgPb~7m`q7(%JpycNp^0Sua~% zGI)mp&22m-#Jo~Rb4+z>Yay>v;2F0G(@IzoSS_?|UpH$qjza~5Y|nySfDy(4pSiFf zR>;@8{6>>hkg6GowWW?4BLPf{g(%MyxjD1`treOg_6cb7nzqK=F%o5eH&n1e|(BB7h?!q^&X1=*UXR$_{>c=mqQ zpTeLfU~>y}D*`!aIk9Qxyy533P_=r0C5jb{GLTz%ME?O;L$ce*G}B?|C(vgR0fz~2 ztb!(kyGCB63gmO*=y{ zLWicS+gH_o(u6fG&abzDY*7W=&VBU>)W^-1i9<9SeE=PnZ1%CK)uG@%Z=y(E!zLsG zMXLq$kCPE34KX+U=sQJm%S~+NFw>NmUT;$vjIHq`hCfAYo(Ask1n7%>PV+%qakf}Y z3sLh<=C}y>);OmnH&xIK)^YjpiI_RbO>q+iH|gtT@9M=`0mhpE(^9Z=<94e-Ch1eo z4oDkIJNi_0{0`9b6f!cHeYj{u!$?N%-JW_^Zvs<`OMhm4o~+8V?-#LWS}K2FTv@mi zI{cd;SuM8%?J^**sc^dJvvOcGFn>fjOo1}+Y*Nm0y}*Xb-4!-_#j+b;ce7^fV#sw-CtF~Hx)?9wfspTV6Nb*!AUeCo908>m`nC^IW|i` zeyG~hOj&2i^c=a;Ieqp&fNIK2VatTy7qRFtl2bA6k4$ilj(spsd8hf$UvU?+oKY%~ z&i+%uy?x)X?cJ|li}bxPuBt``wpcSc4K)1Czd}j;zDQ1buRby^2;#I5xt|TOsnU)k zT(50nsevC2x_5b#uexte?b|O05rWJ?ZO@$yJV%J#lA?U=%U3Qc@0xH&%(?xT?7v$= zQiB03Dtm17(=gvkF+=lOb}12YWcSU-gJJf}1ba?ed#$9KE|A}pjD!U(|9tlC@Q~yF zVOAH5`b{9+UnE__0M%dyGw_6tNsR|Q(q2{_i>ew+w;>ihsRL`1_+!&5w8W9+oh52ubwM<_v(#8w~2t9_| z#>E3RU+$q9*apeci)!jOo$vTCl>Wx(ZK5XHRbTr*RWSMr;k&VoA4Dn7V`~*-?l>KP z4!Ggsz&LW++j=R_qlYCrRys1K>q6#q3YvOhE-33#=UljBVU}MY);_MWQFjMo|I6?( zQYb#I${D>dv=am6dD)qNen6}_VW=FAW=%>$kS&=qk8!;bGrp=}bNqU%SL;?ZZ)onj zihiC9_9B_OZ#$h=6aFS6K@~EA8R@MS{QMwohpBAR*9#1UC@4@)Lk=sDjH(c`))Tzz z#NbU34u4NwGEOhXfy)WdB9`Rs(cdH-Uv#C<@B*D^FDRh%c>I?%Z6$$bmX8ueG#YdxK0O|y zZ$no|3#3#{;eHd2Jqp%-?J|>L`{46V`Xb*&bq}3gvxk>+y~tU+aaS*?-`V|E6h1z} zY}iLU>u3OT###D9Hflavp5Q@C;P9~5JCbA)6vh>1=RK>xQM|iZ?7Uvhp_T1)| zA_Gz!ofog9-1|`%HlYJAdjbXB+H|Ris4u7@@T|7Pmy1wBqj0*&)g_F#a>=AYwGOm> zU8PqGqq%TZoX<_~q+SfR#WJ`;!pQaSz22p#KKGCv`c8x^0IUsIAqafmTDwt$ z{^QeV<}fJ|Wu!VD@TCIlQ$AYV)k>9}OvEb3{Al`XR!6wTo2Y6M3te~y^qe0VJEAIP z)sA<z3MNJ1r{q;;0<0_b}R|bj&T&}*1&hQ z&KV<_CAZ9_J^wkudfB1@24II?e{=u9B_038;KrfHig z$Cuo*=8v7i_aS#}cI}0@ihY{Rgql{2U~~G<`W5ed`Q90?lAZgw;~J3PGe`nx&9^46aUv3PQ!`Q+%MrM^ zUPIOB+8&kEJR_U2Br7Z-CP#9@d&=BE>x6k~^|6(+2)9F|kvHlVTL6$Pr=jlbApuy>zTIg z2B{3*`DimaLah2w`uq6q)ZEkt1Yq1(1}Kz9Uqanq_4Yg2FEewU^3pGd7r(vgupuye z*DKw)Ya*RRUf*`iYnL*WJ7r8FfKfhDA(!PdtsjR6>Lg2$mvisYIDcv$e@8s;5|sb|`#zI3;rh4@T{}Mr?b8m`-1CM*k?gJ|+f*mYM#0x|(I2 z8$H(t1mzD67O>1cZ967&^NT|jB%f#>4m$+(&wCk5_9T?YI4uc7>UX%J7^CO*u zl4Q4IVymfrmf7y)fe$xEZyY=~?cQPXk{|XbzHxH&m*XduJC>&ZP)uIy^NrCMd#V~Y z5YY$lGTMyWW}_BqA?s@a6r!6m*tm4GOIEesL+o&;R`XegTqJI1_{S!>)+`E7LmDx^ zMHQ`9i^M2gN|wQ;YLBHi;8xlrPlp=3l=Tv@J#<)|iVMsyhSLTO95Y<11uV)9qME|N z<+a5_9uuiQ$Ah|-*XU3~i(3DBzfeAd)vaWB7nn?QFL&_N)tsBjw^*$XK;cxm0i*+6 z8B*i;Kr+x=-^yfSB1>%3MC}B>%*S_{4SZ-QR7qjIGAOuG?{vw#7Y9BvkPpF6Xy?@n zm`Kl0u_ON+(-3NPK)8{%Cun}o9Ot`*?FZ^`DdIP!adN$;1}dlt>Abf*Gjci zGuJXxr(+3h*#^ljM`Nw?l^voG8KWglCwiUsIflN5lY9t!0({7&=8Ajel6ra8tmVE2 zZ?pu#pS()dR2n{%BQ1(aQHF@^k(J zzfdfk=J;H8&(Na&uF!McQ&K}6 zFKg){t#PgidtdWuvO^O$_kZ)8Zl=P`{(Oirv?j!FR*vS zX!X|8;SAfqxLk_WWDm%I&{_1yDnsIC0RqQk>>3#4r78OFyikSHy?Iq=DwI918P{jv z$nq4pcZ6gD2Yi7k6=<$VWUQr=qVVxSv+s}n!r)!H3j_$Jp-}Mp;V=>2dp78fFgO*{ zlJSz**v1vbA3J`8=lPv!2vndTzcxHwfBz< zd39p$fwHnjh5iMj;;uu>77 z;`-xw(VF5{@7LDID$TK#LRfZ+uyfL}&ULp__ncgff#7fW4Au5E^3yo^Rhq#%`P}tO z{mB98CR>?G0M|Sbh-Z~@NAH^dTX*z=Jb&zcT=|Y{wzX{} z%ZdKA@yQD}(Ub~M?ZwuXQkdj$t*+C7rl_UO^$yVx_Qs<1w&Rt2#Sf1q)(Z83O(+OZ z-vJ);d{@{#&#@#*^oiw*{n35V)uYXg^Bw1S)8y1*BW0T_%>1sJ*=Z+HN5!_n=&SHo zcjTWe*G=c;Mt|>TOWnHJc%thHtZ)t_1M=pT9-ouX7M&O~mh*yhRb17|AFNBdlMm!V zHvW|6@suZiVj>7&wt*Diw}CJ2Cs9F%$0LY4VDw3;sr#od&258Zf9gj^ee}$+0 z6}RGnQjyg=&z@GILZ2MX7@1f!MJn^OY?eGyT6&C5TXVG6Hw}z*xD*{4dTh+1Ei-3G z1UeUuE`Q^$@j=j;ud3IKJ!g2dQt^AcVqk0D)M^|}_URwOnNstpYL*i z^Pd;zKSj0uP2+Mp`1NqeyC~<6V>f5wnkhaaBDg`yjW#LD>380T+Hc)Qf6ir1#IarD zt4|dt$!ym8#IQa<(!%F4*m#1*V&(DV$GB#YSBy8J!?CsRb-ts|tvv=}LxY05w!SH@ z)Yt=U-Ytr2VF(~r=*gwjm`VPDD>(hexlf=zm~u&PbN#mJ!=sH>;i9H71OoeWpAYcrDs!pgnI4i?TwOoJhW>o^_1J~Pk$U;0u&H41hEL;2y?#SZ zhRFq5vzfF~4;Pn9iVysxY_lzRVZ&o9OryheT286eesM^oXp2Sjre{dES&3|e5=Jj_ z^|IgznvL`^DqSrXtQ8Wd9J~1+U~(-!Fc+-zQ<%e)pO(DbDn5BShZxK_XK}wBV;Rb{dH&Gy-LbMY?9&O>g44B&M~+>y(|DOIkEbG2`ERPJJ#d$3k4s4F zmC2TEsJtV4nn;k8yYvfuP5rJ-K9E^6dqkidzbL@Ex^+CNrao<^e2NV(f;>M>GK-9P zl?3gN*ksxrGspYL;`VDFx^J04_G>-h=gj(MpV~%1y0|cQdD(}kPu%*g2+!yXxA~Bl z>Nv+8HpWe~u&yKQ(t;k)K^e9_V#ayv?OziHK` z$yo0ymFc5O1q9=(jouS3%RU;xcWq%O_*X`8H2+^iI&& z;Als0m}D)J_nmq?KJ)G=Z+r7;`dX;EA{6ggh0*yRfm}mDOyQZaP1;k zMoFX_!_bAt`v=t;Yc>YMv0!EVx`<$EMbV4I^pWJSEw6k6FC$1{t(oZhe_wYAw-YG$1SgUO~+nG2%?1d`hrAq7lFWc>aQ zcp@eB&f|O+UkHPgyQk-n?<0X;>slLb1mnTE+L!K$5+rJ*I)%{K$wVN)^;kyqyK7aQ zu5^eIi|q1jr4lc0gmcvYPTzB`{1KBzY3rs?>TcO~nieWqx_2Uh6fI`4 zJ{Ihi>ezCBMs%VjJK{;Q&%mZpH4&GyqSgLB4is5l-xYn#_!M@lSB9lqW;@#{Hfg|u zrUA_B$eN4^!{v+0(?)ju@K`V&|IFu*(2$6KTk~Q9sW@p4z=cg;4eB_2s$4N0+k zcMz_NY+?-8+WchaY~021%9{j?<%sRh2mze6-kH}=<*8jA9bI7a5Gm~Km6d&p)W`l0 zf>%r(G9@zeH9`6_8iRhTGK6a!T>ju;I(wx$k3Q?CNkb*6{w)Ys=)N8_Bx#{5|Ycb+KF{u#wJ9zmef8G+g4b${D-) z@Yz4KS7kBwq(J>E*CSWCCxx@}o#zvbx0wSQ!DD^T{|{$oGcPhSW=l`^*^Jw^4byzRA4 z`7O4qo@pxAU_+$Lv|9fLWJsp4B3}HBm(S0sz#7`4=&QKaf1>%muEslgs+yqt&`Wxt zHL7B2@te;xLzQW}C2P@L@mh1s$gps^<4z?Xj-gg=8Nhik<6g%yAO>?q zF{+>PLVj)qbW`|`!Eu!C@HxHUHx-*d&Fas0n#&OSF6}jIx-_@HH!9rwInla6mHm{< z-mE-%i5xKSFK^R(ll#P}^`(!vfe+8s9{lx8a!JZe^q&Jm2~t)jg}m3t%;eIC4~Edt z`}qYHoBH8S$0`vCWk2L_xd1*t7ys>6kE!MT^QGDk)|KsD`f}(orN?ovHzY zE{ompo@b{;jr=?=^YQ!p+l;R?SPI>@RPeR=-H?O++WZE1a6Jp`sr3hkIk=dLT-NV& zkyja>rxUbWbZ^AV!sJHBJU~xdAZl+@vq6-^k<1VG&!_T zToQ(M&ME0~&1)TAl-xwCjfN4oCG1J{y0O9e{@$+rdrvUp7Dy@{VL36u|dEw z4(k==B^R51{o?ldd;hp(e8^o@jel)KpXE4@ez*=9J#(v5=E)#5-%yp|FFhKht)bts zoPz^G`bz!h)TITKq>;N3&f5PVUo3Lu$FIS8AvG){fvQBoB=JS(?P6M<@1EZN2}!Nq z&iC=!+ZJ1Y`)I&l>+;iprD8m8>w%$)jUEHJhf!N3|Eft}5u=5qKrVC59>vZ7;WsRh z>bd?);XM9+O{lU|V98_J?m0t-YJh^vk|!jaUj! zyn)TAymVK+r~gp(1NXS$GGHEC137)5I=+G>Qw`=PY%I_xAN7Yv4EF{Q5d{^)BNv`s z$@rJ!yd&b=87uunR{og*vcgcL3WiF&lf3=?-w3IggL;>I|HycDtuNMz>ng}^p$gxc z?meEB2qRy75b*xDRxGvdlc8FuFDpI zSk&ZSH?cWy{KelHs!B}XY0m)hLtF!qHPw=4JavnC_3D$JfGN>40s6sGM&K9*GMAw| zAB!8MXEZ)|B<+d(k#*}JNQ z6B!F(Ilk|tc>`W{VZHnp6asan6-w2h`8k_q3~3O&S_VV@DZ?A5so|TOFLmO>X-Ejg z?Y)}>6*XhSYXn_~f{0rjDGZ5zS=F5Es=0R?n)fcMVWUt8K9h1T9?g)_7PYoQPdRvo zATc0HYGPugj|g6{ypaibF-NmxAuRJ@1*9G*@s=?13vO5tUrwDof^Yp(2Ks0!v^&H~ zfirjJ^t@I}#+nFdu-7|b@MZf+M|4NDNmwDj1i86yJHmF50v+SnQdx0xcQk1LIW`vj zGi_o?Q-?ZbYf|&?<92J+O9;Sppxy?0KU*O2ubTpucY|ipFYwSQ5TusD_+R$Fau=K? za;Jhf+OK+~Q=Uj)?+&;I$QqV9az5nFTIntu9n@YPZ5GFI`AlA;W{oc5hAChL$&;Q_ zSvMa4yZdbn?1^}GArY{7Q$zn`zgTg;mIaYbWG4MkrO<3l3?Y9P`ehI+0KW4PximN8?l zWV@5=uo%?E?uZT=AF`xImH19@ugpY($*l6{n$OA2go0aj6SR=-0uhY<|06a21qU)x zpg`eHT{K(B3IBG zvJ>TM$qs&Rb8$q{q(yd`R|q|G-ca7rTrSa7tp01PYZjowe<3KfSua4F#&mRtdnD)1 z1ZehEUQy_V;8Po*E!Y+dbC0#B1j94(NtoL_Z@b5Ue~yxxlQ7ttZ4RVQKoB+zD-{9r z*+sPp-6m%2zEZvz6S7jSEX>+cbkYKFmp7gY&^p3Zt+rR~YPrqpD<>j~nP2eK6|zM7wNG-+G&886Ab}+Wc)Am0v%F#J8hp?N#IO0_|eqb zx&vWDD_`7pWIuvF0aNnF%U*7*VQz|vi}F|^G(Q@ft=u*G=3A-sck`o1D%(n-x{T zgGT8X>OIWCs~GC6C*)D%$o>{#^CO&dp~w#)OdRU+Nuv#sA0|7Fx2gV|+IHK$sZ8*O z@etnH6}!cYA0ELin3>I>p74T^{4COE!hu%2YF)JX6soNm4lL~RKa+ES%WW6LLj6h?h1BP6OH$L1QAYUDR* zG%A6}Z{auKSf;dP-m77BM?}B{O|&H+j{IbHMq=E){=^@LSu3EELA;fDAkp5~MSUa)4&*reURi4|#m44bTI>#ViEhxa4eD*Sz-NN-6a3s8)c^ZfgPdB2Ly;k1uHacVzc2& z2;xD_{mvcx9&pD?$bf;T$J^1IUlZ?D0l;_u5^x5;WHgGVcJN)u5cG06Xhb`gl1nmc zrOthfEhyDYUe(2bW&q?Iq=E0;RO)!pB(hu)%y#9PS{IgF&pn2lL`@H*Ma^H1a0}_h zC_|_!9s=ZUDy5d+ zGB~uS()24dwwC5TNO7@SsjSZ>#~MWr>ZIXoYHk{JqC)FT|HnHXs1S6;IznuSyX==& zOw85ArQmeKp2?MREsW8xt;W8;v2FhzE5A>?H${i{fq}-cO^3|d1h?uBP|2It7IsLD z*hiV9k_gZbq+(}m%N(2pAM1)wA?#j$NUt_)$A)K01ZN;FM(GFTZoHdmcLN3lGjMVzN$@J0|3m)eL7Up5jap5SfZm4$7Y7Euz`vUC~cZ0w6CZyeF;VbK0yuBLf> zcW=uXU2N`VA)kScwf_h6DY022b;q-L&ztB5xLUCWLIeDBE{^i^nYoe9DQLZaVIjZN zjV$tq1{mp2ZV7^9eq+j&A6t`W&Y&0sn6gX06wkDF1Y-8cwZQ3YKb_SyvHm?}buE0G ztRT&A+%7E#%`4`EOR+rkdCE%;+*Y<5!J%@SOOp2QQUv9u0wUZP)$JNAkkUr(8H&x? zE?M#+jXU9UMt=xW4sO2V_`%!*V84T1bYFTWFA)_JW;l@j3D??!#Bn?h23>K#4dhStqaFQ9EADrH>+s~ z_0@+==JfuVX`A&=OwR#fH_#J z%#*45B@K;O?~jBquMqyck+xtd1f~{}2vH-p&N>E}PW^N<4aLCSi*zl|x>{Da4jN%jEKUTIIqV ztV{)BGHP1(8$ArEO+k{Xo1y8~i)iv?cGDtOx0e+mIeCie|(ZnUH!H15ftvnN) z2{3|H>gVoFc8WD`+dw~Xi{nk@>_l+8Z7)*%{=~|n*_1<_wp$i-*$MD)f_)X$M|k4< z3@N7*b{pg(MfPBl{mvo~MjB;zgn=Corc4!p3#ec`={EuNLa^REdNP_oJc#Gu28yY? zjK6RyYum2;Mz&NEsFKN!@9Ye`94++vpA%#|xR4J^5Y-;!D(@es_H_s9+sCZ4_D?ZP ze_#KUhbf1Qv!|wlnY4|aqd2X&4~qxh%lvJkiu* zl1UKLl2$aQ7rAG;MmbnobuJ)MmO>sN918FKX#jTfk-gn+kInoxw#^mQE?9XfjL1G7 zvIeU>A-dYU@~Q(&3(W!slX-c>T$=%ka>r$f_mHstEUrGX(ba(jk(N!^v0HRNGXO{* zr4;x#^dwJx0}YOO`GtQfcSD%;Wvj5@p9k;`G=R&rbZYIZ<3~&HX8}uAXK;iHY{F=o ziaO6!Moezxjz^k?T?D>se`}zmb{3W+H9%)}!vE*cPD2WsKEZd{A zPehw2TJ!l)cR|zlWCN5B_>miTs+$0)lW4gZ$sai4YQGmYTVZ3YAltcoqhypP-kes3 z&FUB6&ftWH(`~EZ^Tx(s!lvk-qE*5@!gX0>>;2jjfjS2*W;WZzBkBFos??z9zp8C; zDhP2sYHN-RA1|=fiieCfh<<}?1NZv=5C@WPf)Tsm%#gm*1`wXuF ze#W!bYJ)`kq;a~!*ga?feOVUF@~?PR-|3LZxbwf<_UJN9v7&6QSfw(Ms5>zf)CC4$ zo1v$hz?#li+ z5vE!!0#3eU@LEfdCW-aL!w`%DmjS=)#gpXjguPj4TwlMP%4ZUHH7*4Z)w@Se1w9KY z-S%M+YfHu;xcc$&j3Z5i@jQDqoLVSC059|$=$qKm(^aG441gz$%lB{CbXcF&Hcvrs z$PyHj>|(=%VBfGD07ZMYFmY-oh;<2014P&utnI~JkecN{_M^)o)`&Hut#;HY)wkJ7 z1`%ZMOWhH`mtbTvrPd&+*Lw1wd>Gh9GX~i399q{j&JU_@@t;jG?wGP3XH4cBe$JGU zI=2$Co<9ygSxm?36V3%scnF9yz79*pX<>$m3JgGY92`49ugG%L$J{_Z^wLN@ZX}|o<_Q@rGt55Y_d^arj4G}(^|!iH2slR8@#}+MzvD?`rC-UiJ%i9u0*^zk zC(3vTL_DJp_4{J>_Oq6rPLSKko#3hLy)*)$7i9GVFw49~+FSawP?Sy>d?zwmw=8;* z?k_jBaiBgQo3)rUs=2kgKL^Sz^M!(Ed_CIWashg)=J{t5(Fmf5c(e-EMPYA1R6~!r zYn$Y9m=0|LhfMMC=!lS3M8YuB8i-zu`jkBS3@Y;O1wQ|EAf~TY8wSUNy?!PFl8`e9 zPlW9A*viw{nokRBufQDJm zlhY%qDWFy00e($>)Eafhm}LW@!jw>HFUi9DV8=j=UDz_|Hjjpc6`sw#U=S}lQEU(l zh?SlO3&eq`O{Rqj{FA8Jl$h}_*lLv5hBhFs#>WcX?re*ya4w>KH9YDF_Bn})>e;jo z`O;hy5J!RA$^b8q^LAv6!q0d~9V^X2=s>Q++Wnw8j0!Ql!(_T|dYN4a5R=SkZ^5jJ z>%XECFUmGxlJsn);jJ^#;d_Qx{l=k#e+@#o$)$km42xql#>Eg=16e0gp+;h8Lq_F^ zFb)|$#a8fNumXu@X>NdC1gKE>`%^A}ZWJLC1stw?e-mS3I%M}4CMVU35W#Kyc@lCC z2dBd6N~?u14UA+Uh@U77qmq>UpP;#f1u|tIQ(g}t5ntN8v!{9WJaU@+z-Cm%pdm(|KH6u5fWJqy@?4T*uBVU`f13e-}0N5txA z)`80U%ncT^;B#VI+A;kqYmV#?xI*&Jy59$1Fpod-x0A)XwARW&NOV#qQ|k?;#H_CZ z;iDx;0&6Z>Kcp;ctfnB-PXlJTYAv&#-r5I}9wx1(6KGv-Ur`}1?4;xy2pFV|hzS1s zyzyQ8!*0Ird|fn~Wi_MWP6PE24SXJjp-7s*DD&K;%QOmSrh)0uCJ~-1fiQz;6=Ro` zrr5qxWsf4G5C*i~FV_ZA<0ZURO?DOIaFx*tV1sVZAkj{Q1tHrGzdgOU0ztXPKB+1M z(lkdzroj{$tecg?fxHK_t7r8x!8!-)w$Zfp_4>2m911K=iJQh2miJBUjqtMJdw2c= zz8opUR!u}6T|F#8zaT@R`GoB*2QNodYoh4zK zE|tobOi+Y=rW3aic6Bs}(Rg9VLcxBm`5Hq>E}P1x|9lTg(RGyWnvZ@tNj(A`lx?|c z6(EyJD_25@Hb|z-KJ2^krxkqlGr<#En%XBr{tE_6kTb+U+M$aknb-+7&rfWzOS05} zgtDbez{QV{C%Y8#ld&E9j&nS;qUFw3#$bCLG3v%3!OeO39VNnxAc!rwgJy_bCpDQ2;8`PlmN*cH+>(&vV|T+{0qQmi@b zYdXHh%?q0~`A`C~vg3(cd!-56d%<_H#6^(O^Z?Qn6aAUYw2QK=1B2;(LnN|t-hFvH z0XCFp2gjVgbe-JcpYoj(!SsOXD^gka6;ReIZ~tu!zGYW<^IH1g@s>8J1=JCo%F7GN zcJ_DQSFxR@qOn`EuG)Y7dg?CvFH;#iLc1Y_yqxGvIffFz&T*^~y(50r-e3II+rKd#&R*vs94`?|d6+W^z)F%=F6Pp6b? zHS=rmY__sd**cqlbQ3zNGbD^oQVcWbY1kKpBbSmopGxFaK{A)4au5g-tpDf7i~e|2 zR{($bD8G>(Ho5-Xl^vIGEn16rTA_G&E2e>tskn0f@LZYYOZDDl0)Qk}0@%owV;aY# z6+(mw;Y>Elg0e|T<5WJ#sRziJl&_ef9S8kqPSl%ID`665&L5HD^!^zF4FeV?X8)U;D!5M(~x0q+wgzg@_GIur~%M0o2TS@k$z-`Kh=4vIAR;E%NW1MwEx{9(({-5Jjqmd zI!u@Sx?0t68G3L;+P3q+!dP58aJfOLM@GsK;=+R8!tPPoTNN{7XB%b0X8dN?4AbB& zXUAf>Pk|r(?lIFHU!*u>z~Q*am}P=wW+$T-u$Ebz1x8+LCTvAFZh^IBh4Q#ihP2E! zg91RtgHoC!ecuaq%xzY?ZzcP+7!Qs(@=HIL4@tavORX&syJYwlUh&}2+sD->zKy82 z7P|(~rgQCjw9HawKbG3p;0hHe$nAZ{;zMF5Fyjp!&bm-6Wo*YuSno8M$a^ZSA`oEq zasHI^r9YzwTNY*##E|%m=>HAr&u1BTi#Q{GFoYX^tW3H4siXbubR+8byy3}$O0-6s zXQIa!smGVJTncj6n2(P&PNXIX0 z#dU3OER)q`UWkr>VIe8FwEY=BVK6%{ow@9+K9hJdlt-!;mNlVGsuid|Kcg|~@(#dv zG5frqjif1_Jp%95+56dh2J~RR*D{&^eGB%KWHf7Czww&sqM-DI+*q|54=hESa-@p! zYRjXNJQY&L4ER!PnHq-P69d|uU!~S*EVY$I2D3OeylYbD(jX8c8T~zMw&-$n8)Db1 zNOphkWuKZwlYnr;5(ma%F)c-e#ndA*8l`u{d_=S4cLz96KS*=RidS0L(p=og70qlG*3te6e!`Z+*u*>`uw47$(lIO_g8M&ilZjI~B~W z?Or`-zZhlP`Jr(ngJM6eTmg4G&&zj@w+gto%wjn@J_($f+M6sO;>XD=uY^`XeBbQ& zBX{s}6pdamdkK#lFz(V#CG?`1tigd#B=YC5+B0e#+*i_&TMHyDS6ON3XVQy-3j+5S zC+g$+5gWjvUQNeJ-@Lc-4K@O)52>y(Hy7CO_RGWF0ty9+0Rd=**?Gu~^>*){@sHjc znz!IMI^2^V$!T`X{(TX($z{#zGnwlLi|0(YJwAo)rN%v(PMu-wU!AlxotEpH*SvAg z<-@x++5|6SguV0s%MQ-0d@tB_F&Vh?TTo&4W+H2d-NAEsKPz80?P6(saJlA&c7)vl8+e!?d6|S=W7LIJntA<}#f-KHi}r^Nww?Mk zV{@0Yu<8x{GvSOll8xV(ab~0F9&1qwya?^fC3i`>9xVec`Tqejn$}0=ArAO(Wo8FN zF2-^A$r3JQ|ER{j>&qUi$ENOoUZtWJZWP7}3t&aR6L!-_y~uU}hN|2A?9?W*9Au4b z8N_k^Jt+)5m2mpL`+9VqvjXAF0kD|<|G5bm1vLRD3oZFM*$U@p#3MA+ zITw?!oK1n@FwcGU)s7$*D}`fCfAG&AHBa6pPmvbe><&ydXeMy-UJgu&@e$d9{NH~N z;I!)a#8qyzK|f$RPVwmG?WJ%#gAY1mf>DW6(1i|u&Hj|fzcR4Kh-tlG##>aPQDT-4 zZ1(o&xXCcI;e%IcP3n}`DAnNZ_3;?^oA=L5@@gWlI&~A>U73qoP=>r64;%kJS8rkmEE*FL$l2iJhq8 z``B7*HYKjNo5DUI`opu1|AgBEGh1S2LcBEvJMyQ|SN2rBk<<@|`OQve99!)FtxiV@Vk#S-Phf;D)V2+kwkRQL!vD4i` zJ+YV=u&g@$P8aT8Mf9Z0<~o;<;JKxPoXqF98cZ**e!WZGLAj?4*Zx?VkgrPe5P$dD z^I+kj;rt)jzP^XLyMK)?ofFj)19jJ6r>pkwsozyoDYIx!jNhb<%CiA|VWjcv5(k^H z%N6y#z*KHP*z%6hSmbM6EuJ@l)O@hJ5Y=6+_&)u5KBh%w4o?)DiOs&KFgbaF0snMc zfl~meAlNkfMSYvw?h~q?d&l_{m1!J?62(td;K-rV4M?qD2=|VO$~hQCZfKFUdFEu3 zmL_RG;jNKsMdt!ss4a|{rrC$07#kg$@YcAd_2r%PQO#zPao}27Oe4+On0fuI6<+r8 z!IVZMC{Wj_9qS(Wxf-N+H@ib~j4J@9xVxMa3BcubRi`Pr73UTh0pRLk{;|_e$t$f+ z+aXoI-S#-RG%v0nM{4}$^ltD#O~r1yCwXaUgF#$pqd}3u>4UI*khp~QMf~Aetk*a; zN8i*kf-d{CT$)~gsH^4c+HgiQU=X=kD6-r1<#O^Q!HqbO3YxU^y%sFZZ>&j@D=kW;_-qiZM=`}GMeUvwFlzCQ)7{ksRGo}J;)|_f;&BaYJ8XfAV=TSLtCO?!i zcHo;}TLps{()H){2<_dHE<8X+X%0l}!z3Z^!(aZsbJRcW(O(PQE*CCIm%dkEZR{G< zq?S8V1-@AKZe+XsY@3|?NClIHkacgNgHmTTJf0rCz}%`MXNQJXx+8%Jqhm=}{=c?^ z;JBtTsc(@&0P`iivsS8JQwgNOFf;TCnl+BRG_jHHC-{^>(LL+!U z0^daciY%UoXrA|pK+rDm(|7v#{@NYQf4=p+!V0|r0xa$^5N;9s$XAEe9t?aN1L}YO z2KUi&nXp*h5DO&O^X1==zg|_XK~PblwVA$H9pC`BP$7<=ceHM1(J<2AXA{Lp=|7-$tViUbpn`CX+ZwQs zY(Ahc{tdl*xt|w`U+F`JevSXS>$7S>m=2Aiq?0t4x8q#KNh^IC_upl- z2LN-?A8<&Fs@Anjd8ui%m3*_Vz8RGVHyb}nbPJg*SEY@p!lw|q`wkFH^Tgz{DiCCN z6&T}AoO!#e&~lX}M>r=PIF>%*D~G#{IU|a}w+B&7E-%p^PkeGIx*+!ya2y?LepQ%n zFPlG0{yo}=@LC7!U;+AuIgp;=b~d?-9{)Qn!uAHrwd$ zCnvKK6d1W+cGp{^_wV#Oe2eeYU-QsrE6ViQy3+H3dSF20^;@vuNS!RIB`$$U%Ehfz z*aP31Y3FL7oQPYsZ;z1%X0v$`oyXR3ca#bl03yQS%;tj7xCvd~S?Jn(H`%>d*{lQ7 zr~I3gt*rhJMQ0w!^#8~4&kU2C#kcKiGex;N9DSLa`bH%8(czxbv%pNPvs?`x_JGm*Y3CCku<)f)R=fq z&;+&7)b{e{gm1*_C}!E@SYN(6PFK5 z4PJ4D=w_9U=u11fx^6fm`%nG>-&AeO#=}uvOCOJvxSTE_c&HkdPZEFCQ;9-?T;RV*UDZ>0*0C ztSV|qwHq#5SnYksCnfk!Q6k?&5l)-p9sR(T}IG~4n0 z*&NfI?H}%+xisaR)yjQgix%;FyT>7I|OT^%%P9gX`)Q4qHd) zXkuIH741e+QwRK?6Pht01E01Ys}JVew%aNwlY^#ph|>*0x+SDeU~P_|2=O9ZLjAYx zKM*rA$S2L{*>|2jwIivdJ^#h}S#kD+!_p8I5rFve7`M>F-_al&^edib+-<(LaBbVI zLzE;fH7kZE2k+i3^*F9-eeL-8&1|)>_P3hPYZk~gWxDZ4R5@|!VlDvi>cCw7(;#tm zWTU-a&*GO>i2rt|{c}pI^6#ctS#Jqozr3K6nEL&kE{jQmLPPiO&o>@Cb*z8a(!<;T z?ZygL)2Af5*?>=Vegd2OIjF)s-O9iLGkk^3Er1`fuL?V+Yfd_4W%k!hIE5M&m@yQ& zl&hF_=&ms~?^`pw2#g#?JCEjJ-WB#ihMb!|TTI&txFCtB!P^g2D?HrkZO zOa08{(T4U7jH0jEdAcO}Qr%y5<(EI4n{rWJi>%xe9(U67mdDm9n8;)|EhUea6=`P` z8c0yIPWKMBZ!&yBBU7Cum{`G%JO}#ygTg1QDOE@ftfsJ~vrOBn!e95-q`gpnt2s{3L54;Du3}L) zy68=|JL!!a5;w%x#mClOA=z|@Wp6Xbg++(9%FY|q2RCbMvUPv$DKzw(3nZZ!pu8Vf zZ{zN*3%K`~C3A2pvLN@;!E0`ag0! zl}%3EzHxHJ!{vOevHXblVb;s9u6@e>=c{G1j@$8|S>V~FY6h}~8r8MK$6voKoz$mZ zYioXCQ6J~J7C9!nn>br&dF^YL<$Q4QAwFnPv|KW$h`F3UHdSgvA_|+PQJaJ(ZACK! zgaTf3M+%#5y^dLOae!C8r?{69Qd4O>mf5XaFHNojq1Mg{be(2%%sza~SNWk*Ww3TyvyB`qEbq3q{m_}QhkOUgdF z_b`J|HR9sm?LB#&X@lZ}#!L(w8(d?4C;Gsdz49s2d z*xDExQh2vF=zM0Nz=uxG*}GEh7vw&d8~5F{x)H%iV_yB6khBkWIz3;x#U zn_G@iL0O)-k*JH4K{8CqtP*pKr`i*lfCaF+U4A=u0Jxw3wCOt5b;uHp(fb)M_EDJ2 zmnK(BWex(mP1PcT`aI72)^S^pxaWZnzVKMj-<7a3yi_SAoTV&7u21duzSHok>esJC zw#-C0fMmQ66$|*;tAGnQZc-dmowA1;(h_Dl-`xM2?kyjgau0OqxaN1OgGe%0yQ#O*rZ% z%$|O6-mxROt}$BEAJiqb_iart#!los>md{Ih2p1Q<(-iw^nH~{HdwG}l8VY{+zeo> zjp>x@B(R*6M-tZ(uJSn{@QH6mDbN8rl3xAKtBG<>4MPCPXfsU4tM=C*eA(*fW4xZs zKqrc@w+X~!AT`011S3XW-pRAeZw(j!TMr%cRe6b=TQbFyd^A{AR3MD-IeeQARK#Z2 zS$*Q7?GQDlRKZx~h>mJh@-?JOiWV4r7jbF75no!w&FzbI7%EdAJx!5pi*(A65FDA# zLnJ~Z57Ox{M2gQI8vv;heiT6!WDOl)yuZy@BWFv5 z8{Ij_H=T09@ zcwqj;KHv>MQ%ZJ0%xjr!b)CjATM1y~t-jI-0F=!@Go+w*eS(L^wM}p{y2O$Sy#yG*0R=cN5J|t5!y@rIN???m+x1hQ7YW zOUaY^yq5jh@88AK0G;c@@0154%E?;F6)x+$EI!ZXEG7nkH%We#@AKcE6Ywz#>w!Xx zFbRT#!ut(+Qyyz7V7w9X_q|w!^phH3LF}D>Vq>++bCN9VhUg_qL86o!g#JC|+?LG+ zmAG?E9|m)5`$x_xkWryUn%%|R$w|B$Ci@53zIhNP3R;g{mKcCJ*#}mF% z(5rgwVt?B75IOa=(h?zrEt^n%LF_Vq3fTp+*KDJgm_+^Qe*AEO^2NfNffp?ip4npG zC5kdWJPErIz$_~)P{8M8KV-9_dW)sbLAVRvfYOIGNy_wHz@9d=tpjeG{1hS`g*7pK zU)55`uK}ly2;Z}QAl`pSiO@rCfH2Ay8J!Cq+$(dyL|~TTqaZm^X0Y_MG_P~_OLd^r z;6VT>ivmg;|F6N_NVE`-va>XQNQei>ZfGeHM{{WgfZU0{Y11wfjG8&pW-gD6h}cSn z`wmY*SdI^#FoN2^{)lQg)FjXTTqTJ{mcuP!9I!VH*# zn^7okI9TlCrEE_{U!2jYa}TjPt$*5Fx`&{4R)g0L0$8}qi^%Nko zeo1tr(gc@Z-)?a6tFR`aXA#a0wp9@-Usd!T4YIKl)(1E(x_n*GP^iE(K-|AO(-GLj z^a{a7Xa?p>kX)-ax=Z!2`R1h4CJS%`M%N2~mJFm-$7`B~be&XGw=LjZhfn&gonh#{ z$i)T@fP*^FA0cJ)YcUqq<3UB3_a#19J$P&-IkRwdJNyEqw=~XcvM>P<$o2}C+{I~n z!shp^#I-*3mD63fY+QXm>lg-Mz~IOR;v?mKs?iR)f3^eRI4uz@5t37wZ+7Y44cR4^ z2|{0qy+o#jZ)6<}cNTK(`e{HL@pK&rd+bKYV45nwA z$T36N#Kf`=Bm%e+0JfQU%%yv^Kxjj8%||Rb-}IV#M%epLSBIm>wfiDk5ogDgpGVzG z(ZbhYl*!6Z;la)gkF`Plvj005dfk|T zjV?V_PBs;K{#wi<;5$ixFu2YlL#!d<-)*8NME4!@!b1Z$7KZax?-@a23uNAT5GcV3 ziLgC=J-)+K4KUO8pfWJE?m`HE&+L0Q z!*h0tA0{2m^%}L%V*%?-InYcuU~Tyq=(?P`F3DxE5R_k_+@qj1M^GL)J-kk;1@P_v_QHO8|G^hFEd!kXW>X zds-8d6lq}Tbq;jK(^yF zxKo59S8wBX!1^&-0|}ZTNUjNAU5(HYG>R9jaakFw-4H) zOPm){?Go0FX=LgP-Q-tSmqG{VAgt%~n~;#J5`A`zp`gU~pw7h|uVcL1z$33+8sVB$ zR~Pk@D44~3o;9M%no;g0+IxixnfVG=Pu=zv^Ky-ELe2yg}<$V#}azeZppy9gk=jE%3yX>0;znxB>LDF z%;+r{?k=R5KCpF|d%opF=+fFlR2rr-8{T!*uF{>@u*tPYwGj!Etp=Y|m_O27AE zRE?Isw3*3nI{WE$S3Jl;4jw?rul?SZNI#fHGp~~8>pB8Q1Bd1-UlkArZA#eUzhEKp z6~90SZl_d3!!C#kQi8@?7A6=^v^QvcMXS@32T7%o+w8R-h94>9CQ(Q)fg+UD!OTae zQT#cd(n~7TkvJMO0hDAbagw=jfGvTW94y5k5$Kf|B|~#lPhv`_*(sr&7BV@qVY-Q`hCRNi}ElC^}9LB;ko zwor^XX{7a$BE0q)(u-PMMidB-f0jdWd?G~?Z_)H=229Kh5{binSO;#C5fIhXSD1g4 zE+wSjBQ7zP-r=@D-p1|-vqCAcHXZP+%#r2 z!Qn{oB#j!)Y#r4;*2Tye62207ux6J|KuKop`^UsoFeG0^9t9)R+ye(j)Cm3SvxJ^d zOZo^+UBIuK^I18FA&=CFCzv_cpe46ZoBIwH@Jyd+X>ttO&zL@f_!P8nlY66z7!p2a zZhq&0fFDJDRLZZ~6XH&4W1^V5goVqav*9qk`5o&m0R#%c9hy48GHz;i%3}2;LN0^m zom)dbxO`T!gNX9>cVfim${|1MpQqWJi_TfmstfuDDuoxB=)>&@I2V;ZB~yk$xS5xn z?hTZ8tX~f2!^ksuEnadnaqP1&u8a{lEQU2B@7BuR1_=*2@ryw;B_8!fk&y8qcrQ@~ zeWS*1X^x(+Me@)<6J`|z8EHL&FR|lR?(%RX3haq&cL*mK>4cDpp*>vl&Dt>)eluEb)Tne)SvAlnsAJ_3vAE68I38I5E(2ID{X-Qd zfnJ<&wUzw~N*}8aQk7~KOtf1fENao)0DCm|LwoakB}`OUKqdD%^aezhI2$=AxG@{YRa4B%%Zs*gUdtE@E3u}2NURx z+$R@bxttm87F(i}p()XX8TlA^yewI5g%o0KrbSd+*5AVce`av2k_BWD1oDCLy(zG2 zMe=ha?^PYSd#4YQJg^qO)9ZyZf$JFYKj?}ZQLKvB#+^Kxq@L8QPj}K$HKXH)N&c)^ z`3C#Nl>xE857hX5aBZfUi%~EoblE9~{dC5o6iWF{jWn`owN|lOU{8%Kr;4358~xR; z^C?|^czxfgt(W3sYrrhemB&{a`VEkUH2ERaCkLUL33#6vAqB_g4#=&7`5MSB!S;T) zq%iZ?zz=%A7s55Ii}Cs;BANY=JEZz0b_&IThEsi0GlW*lw>R_}G|cs?FsZVz(S zb`RI#4pg%&QjGHE`PPKzCNmFciZ7i|CL3Ua_Wki+`6({jJ|OBqB0A$#4N;lSIh&yE zj=u#lhjTw4+uMaFH3lM5_<%myXQw!K+{nrtxqUwu&hH1f|I=lKVv6wS>yW^9>cUfl zCZ{cJ_^?>*CO>c79xQYx5y9eNXM~WP51C@& zOL!!!{cMv^&){yu?NAq{bXtWEB40aov)il?l-PVtj`RT4O~MeB%S*_xk0RG}u$p!G z_&Lw?C>pN;Yj`zZ#xl6oBN;->wso~!R|_B7W9~dYaMJ(> zwDBqz-6DTWH{P?($T0k&b&kZ3hb2E#q!Rs}TA3Rk-I5ut9+jZ46`;d&6rRgD zzm9kZWV=w=2aE=gS}Ugj**@VC-HDiD)MK6agw?`a7K46jzmuK=NmBttUKl!3_?!;Q z=jBNuqq0hrd+Qm?rp;W0BIeh`<4A^dB{+!hPHMRa%&UTHv`V#dgIq9%+!sSgb%!sXjFxC06mh$iIvwC=Tn>BVt< zL9!8N_q8vtUsu;4;P=;b>u4a7%?8EfY-JP{+PnKhtmJ1o2==j8P0iD{hCv+*<};+Q zLT(a~&qeusxrMs#S6KT5NN!|6W&uo$FUVa{;0PG@krQ?*poa-`9&@z6SOR69V~myd zM@K3+xRb(t5#}MftGgp<-;GAOh2&s0vXcl9G~HcYsR+F+!|*K`U1*j922ewDTMQ0f z4f=Lt?KK*+g1p5_4za@NUQ12R@`x7hO}Sx!=@PQ8(z2vfb9>RQCKuiV%_@X;;Q{nV zBwbwoO4W-}Mkm66gfID5f~vxcQ|u4dxvhJ-P+|q(sPiFhAJu*c@d@0F*QkZJxw*#L zwb_rwWH#grONKlmL=&OO~*V()dSam7H^?2UdPIlsyMp&L^l5Si2O7 z-_SAZQNVoIFFJrQ&RJHzH2vTXkJe((nF)xlBsWBXgMAk&Ok3U1eerUbBmy|9tj`M1 zQ%fUb8502=`S+5Bx9GVb=+BpLP9o7?`&RTTJ&df-yhfap-p6wuLLI0AJZ`cDe%{hN4K6x*W>q{@DsFH!!FCZ6@L`+JcP|~6y zHnTU+rmJbBXn$s2Cr+`^u$8xin~Ax_bH&|9&k{8AqLg{Nr4FZO;kp$gHv-+Uk>=Mz z_WD*A=zt6y*(Go0x8^Q{aNUmtK9845O}HT>BWBAwJsPN(r9ygLxDZaivtA~BBCde9 zpYZr1H?1ysUeJihJ2q)W<^RiRBm~qUM3aef1b9DR!BUXxG~s2y1yCMC`-8-v`@VA& z0=fTH*x)^MBIFQVNaSm#g=<>9-+f&%f!m%+%j=Aq2_U)ne>=(zA3Uv`18ko~5Na+b zOL)@|RP#Sy32>>(cD640w~$s6O;>T4kTdWTq`x{TLdu*#@RZ~4T9y%}WIy8`5sjuj z=<~noUZ?6%fVv4L4LTRCYYw+UdfRNM@Rpkj0;JnEf&vi-p*gb0I8 z=Y1dvKMVb|P+RX_W>P6nAFQ-DLu4(|{Wp@|+142rpxYrWp%{VAh{mjhmo%@$M20f@rKKBPmfhf(sTA3 zpo@MrTuR@1@H$%kSFC&t_0Tc;ObHyEo$rN^A#`9G&HAC=BRnwPV9tdTx)wDRX!$zHp1ms-8UnDc+y8Kr8`al z!Dcfew_pF_55&-AsNe$HZtOOJEC%OdsLFl0-Pi7h5g9H;qgzo;plMia^C$?xzbmQ^ zd)U#$IVbF;@%kR(WgV?iin|sow+DP2-U4q6mzZ9B6C#A&2KfM{B2_OIH0N0hX8M!_ zCS`AF`86!o`>Q*Fi26W+SrrY}k$5+{CoP^2pJy(v150aH{t(>rzsQJzJ}@3Un7SI% zfx{{x3d>5AM0g2NL?xZ@h>C^6fUm?nl|gKu>fzG8u6}IflcfwB=yKjPs+`gisQil3FnJXF)I;wAQr{~sXfwvne@4hI@ z92(&=GJCEd@%n_)JU=R6fjL$He5)(;iEA90b=-RMzOASgQltT>c4pwmXs14we6n|; zsSf^WIEKrYpZH6|C1?f`pDI)Kw9=`CU2JBH&sMD-@DhC%bBs~ETvMtrCi>kRpR_z; z?)m!C!Dtobt$p#n-SZ#Ru|k#N4qlmeUT?}onoO2V-i;LbGG&~8l`F)jwQSrmC-Ifz zrKTf2hJ)Q!I!E%v&wi3o$T_gpy^?ct&hB1p#*L(eom`Pf&E;4XmA?WtWOjUmcHjKg zRXuuZo_;hxI7WE!{ce4P`1tCJ)(V=^L@Y|9UH8W(D)K)|h1Z385v4#+i}OOin7owh z6Kj6EG6Ks&n((cD6E!2G`LlRw?CB#&?QMooaBjI}ZRTAM@N0k;y4!~{!e#{W$bHpE z%_4je;5f(qYk!lgSm{3e)-?6k+4sT6922iR@yv@_hhr1Atc|-&QR3aX7KLon!CaOMUS0{j3_!VYfjH zOe}BRG+jO2eTvxZqzryBQx`b4dRkw(<5aW&pBPMmt6A3{c?-4)$lM&tLPCg<5d2;$ zy%K-nug#%pl{e95dI?Braz8A8BddhD_iF@Ld}}RJ2Pn3O<@(oU`191$$ZejpLHnB} zmx3l+jAZ$Zz70r(9`1V_u25_~As3YBk#W*j$^0NylPJgaHNdC-fC|0hQq6+bRWl#m zd%|X#H{%Qi8_98@6T;KhXJ3mKziq4ymbfW4Y3-$A7!ncm_Pb1SeJ1W`tpRDeAX2Cw zc6MV*;Ch0Eu%4Q)?#sg768c9y_56?+rM-^Z z`*iczHYkJ0J$-?6Z4n&t{6G289ZO-V~T zcP9k5qM8xn-SjG3+~%;i7jtpJB2u%^Tl>Ak1B$9U@YN#5NSj?8@<41e?9bMTy;3t^1>dp+QGJ4Z=vVgd3?Uh93!yVt|xOQ`oi z@g;zF>mKj5>uo!xZyt)Q2D>ATfHJhin-!CAvK%7$#8@|;&E=@9OAeTS~$ zguv<``t*2TqMg;ukpKirijj`SuNK4p2dQa6;btmEl@3u#@YZS~a8_zEfOj!n*Ul0f zZN^_MjfvNy*kwhfgg>_t@Sred{+sT?%w|l`oeVWb-ZP9LPAXi1&rn_7g)1EnCz^wG zXP!!M`7#}+1*YVEeXOf(d=nNnBJE-%P%G&aK{v6tvu%}pzHcU+~*=LNyzkOo5)+=mo**EmWG3I)W6hl(eHZ<1&#&Q0GV$tWWp*}3-94W#cu;eG7oo6p5)|5@Z zp?O3;suU$D`^h@Z)BoAy3u?`Y4H(Xv-ci#TOB5Jb8)n|nTYfsrE%Z1zk~%y0WmCEB ze-QW7QU*SW5|2BlHcgHZ-&|^`ua03Sc>SC;uR>r=?VC35e*EhY9xr_c@d+pSV>7wM zU@A!3{G{+VZvj`M%@h%H=Czx8{L;KWITdXl^OC4k;ct5{MVv2#&2EXq^n%;D-E+%p zQBB`dis-(T1q6zKxOMW*jK`d_)xR>n$1r|1RGrWWB+FT8 z*AKCO=-E|!iGT0Z@2S$Koff1!D9JL8Z`P=E^hz{tq4#ZDwv{!EW&n;9j%AbA5!YV| z7tZT;h;Xp2^Bj4R+N`Z7HC?I|A^y{^{YNF=SG++*jTQ2K)6U4op9=eLwojZJW*Yco zz9;k*@K{t-N8GUImTPxYCh9ImG$@*kW_AXP#PcJ*4BV2XhIr^G`V;y!8~(Pd=IE<< z!L`W^H-{uRsMuyXU#4`mzqI#U6Z)$ALh?7 z4A-r^Hrf8ommOe^Ngtqg>>Q zqMJt8e!cotQcp#-@_RO60I_XHeRej*HA{IW&;!690F-amPKo|cVLJ3h^5QhOiu2S~ zi#v{5OG1MQwxmCQ=CNgzz@?Os|7{wnhceFn)3Htw;gCYp}fBk>SsRKkB3E7g6pseOp$tDSvff`1CAaO6iXS)u&aE z>eABH`8Q9`2tO`1K!6z4jdkSPq7yZjT4MJX9DiI*_tA0>0aOG{#c~UtG~u|GM$-U2 zvk=(j#*apo4{ZY$AH>j<`_?u}&c1(qDNd;!`}L8(tBP%MRS3b#_{D`uhcO4*{G$W6 zda!lX$=%vL2pyrHP2TC{6K5a+KYFG69pgGzlE>Zg@PLiacW78IOVy~H;F#&pFt+`XG({zG@qRC901oRd7+h6#xj$WI8qpZ1Co!I4SXaGL zH_$H!n(Qb5&aY7<+V{SKagvYz;fbj7L5c43buYcgW;ER#q;@vjuK+O37RyU9w{S7fa7p}?68V;F=!01q! zgKU=ggRS-Sj8ljnJ25s5?Y$$&kG}FVs4OpS&GCAieVvfaRYUXFoOO z^Bj4sycU`^XBRP2wXBl0DcYA@ud}saQ@RlUOyz~zIH@=-ZR^jQ>bhTMzOK# zReIORo|ivAtlY`&ViYSUpWk1?eZIlcx)zXHwJ1$u=XWB`bN%Umze>J(#dBJg^z+8( z>-YM-H7Vr?-<3WhpKitn%s{4U8?dGX!sp0z&W}r5UsrCNS0yJl`j>H7HVBokO}d22 zWNGY#-3D=C5^2JSZw(>-&SHyafBL8WKHuQZD?E-}qILII-UTv}=s{?nd>^_-Q`X0v z{cg;+H!k5CQJkbyQrf29*gIBlg(u_oY3+^<9B#Oo7HX>}(ji{|;H}kP zH1050qcSmAoFArkCNX>eIJz{l3ut?O2E4r?j5=unIjncPE-Wlqwu-ln{X<_INN(J$ zN~Mqj7S@@S-nV;ppEbr(YuF4?eN=u&tw=>^{fBqS+6&Fns|(jOV~s9fa8GT%(P86| zVr~`=tP7SOYe&Ou3@^qdKDFI2WTjR^{-T@d=xotL;%DvCPhWyll$>fX z^m{P6mqKVqTbgzg^jI`Q;NpmKT}-l9^qVkh&KcM39-E6K6TQ*><;73GEC0?@dC;dP z-+mLtnqyh#r0qEa8}PDD@fpQKX`3rC6%;mm+wO({VrotFV_2j7(uli%@uAkJxwjHpH)91zbwds(acE1U-kNd-9|Hh*Kfl2A|EE>FGqnDcSV zaz=TWU8=h{G4Wz9P_a3$l};`W;gzS--R1CzU2 z5jKm8f6Xt+R;-<}QW>r>Jroetvv&Q^=jiIN; zScx8AjY-SjCw+wZ?LmCFfx(L)v!5*Utn(h=#-uS>@c2u*2lOp0(wDCFnuppA#x@0;OTE&=F3W?{Y` zaUpS`pQtI$hytc+Uy~2#)I~p?(6YxWy4;7yqz$KjJJCY2CQ;jf3tJXVST8(1vx$t@ zIkUVewG4Kc>nr*KLzbq51-G|w=;Ac`{-39kY8K`ebz(wD4=@(FdgGYVY?HUF&!Uj8 zW`wPS)`>pa@77#q5AZ;MY#uSWqp6XPrYu)e#6ssoop$~} ze;5mn->NmbjIHUp-MY^|WiXx=-+Ss>vHR;(Z9odZ*|z>O=b|h9=uj~Eh02z5#ucC3 zz4^dnWi#z!Z|^>y*Z(4^OAIL1j80WpaQxlmk@)j_2KU?CsL7-z$xHBGA@(mVCJJuP z9Yj^SJ$#3DyWpJ#-|rBgejHgcgq-$4b>}i}HejtT|GaQ@6SDQu@?bed>^j6YN#O*H zq=%*7y?vb_eNTf|-iGl~fJv=kE|+<2-OLT@5W8>eronEN-&1UTFu3`0)AyZ31a?uKLyt&+t;$9oW9tBGHijmFV@b|QH3jQ28`zE`@D<=Lt z*~oGv)c;Rq#m@Je6T~Z3nr!-(-?tEtB(~i2yWre}uWA|%8bvxiY>#LWl8Rm@0n~9S#eTFAv3qaR$t$V|lc-VsTbFTfw{}sL{!Y4| zxrR0QfhXVkDKea4yQwY}uG-FK^?piOc1|2R=9QZr_9eWe8bi2h!qc|1zYpgg+?V{3 zQ4=2i#=7-dWg+P-_s6KH3^8}1ng#lJa!b)S?}@Kp`i5$szAKj27zQhYaWm3K>TNEH z8`VO{$a(n{Pw0a~i}FXa+;NKRZ(;XW?lzr6{kE~L^GW3w0+`FDcbEzJU zDw%w(cYw2G6C}`pk}^5Y@@%eJ>L zo?7HWOna%UL*L)b!^ak{(5{ApRe+;k@LlZbgZD8Ty`R)oYG#6)yHDc&RAS}VE>D)7 z{&n)J@xj?flP=?PRa>i_2^rf2vYrXs`7q0{)0J2h+$uCX=4`?!byI$fj97^W8xo)j zVwb$&JRs=Uw}ez2=?Tx69AYKa%%zTviO<-{IGj^o9#;_|scEGyd=4AW|9#2T_x(BK zyvvn9h_FlCD7*cxU*;*YZ2X=#Jaq(Um0d|TCOoqEo?~vJhRgiR;WRyyc)fq7l^93% z(JM)#dJ68=|8`HGqu!}HpqP|P9o51XAXsAa7Y`4aa5KWkTivl{IZi(wdJIJzwb*#- zes|MJZsH&q0Z**Yg5-u(j@PB7HQ%p3kspzV!8!ur$GRqoS-JQ7SkFSlcb~tnUx^j6 zpJL z6`~=)VzA})K+qa?(C$OrfoxHIZHk^X*e$$G=39w4!ry5;H26R0M!cTEwS66_t$<(V zmJ0Y)y}diF%h{G;aHS4keKzvm&qrJC_tn-#9~BzSaba?Ogm$S21MpEdYJM58uH)|Ag8Cn&cC-UjzGG zX#*!@8K-4cZz8WNmz`tBKM8eA z2EBW3Zq-3wE<5qjJL-a`w(Cim1+|Y;IZC>zuVN4X4@$O2EvE-ZD3D-r{&4u-(A>Vr zl%C{W{p6I9e`|EQ7I~bc|75loU&j^?G@k6PJDxqb&-)>rn>EiHQp(F$qH|7vKt;S6 zC0z*OBHpOVK+5#ULa>7b0+S8IQJ+vDz4o`94&@JOykK(+9xv5esc>0q28uSp%Gw#~ zUeLxX<7;S+Lx46T((K1SwI}(s=ck{R-A+}NCXfjWR%M+^njt_~I6a9&?uXgB1$ARP z-!iqU(V@bVmx#NfK<}Y1);Q$6-)M4kl8#xi&bZ+s0pDd8iI4toMcKo(LJ~HyrjMejkmcB}{FlBduwSG8I69=%d{9Z-j}*CH#FZ;8 zONM5Y#}Xe-w3K0erdL>Y{6w|wXl2^>EnB-G8}bB`wJ!!c#Hb#fdy1z=H6!D2gKp^cNg_B4a7pmV*-m5F0Um(iJ<`I6^c4x0od7_1+~qft}?KEQD1Wf z?2jCO;JPFFPrd1aWk(;IZah(%Ur*p_I})~!{;v4=c@#32_om!o{(wC#@IACoo7yRq zmPWpkVZ=GobFV!V!H2z+-g&ezr!Qo6olBb+5K%+>$yUc#U%++L$*;Ei?=4zd`V`~1 zvOnOOAhHIF-dh2C=Dc)Y&wnMx3W8|LJ0KZunv$rrs?x@k1D0;!=vtHWit~mpM?j`!ptF%T6;Dp%gMVG|+O)#xgzG=zm zSE*SU-Lg{4IA}Yh|NNwk3m|DEB}VYLExAJ7c79>WThyiXcVkj-UD z+y7zhJD)wfTOAQgAn*70JG`I9p}^qzy{2WRJ;w-%sX?%Y|B;`@rm*P+a$JJ-D`X)t za@OY)zu(9bs=dPkHMad{>&-5c^+48STG6URg0V+W|>Jz(0MX%&mx?D6{K9(25hKO8#ZzwF>|VO8U-lL ze5{_GaD`(6k*7xj>F1-i|71b@O|g^2mI;^eprWjMZcS)^?d?d-P%lRH@?PJiRZ3Fs zU#ytEU0g07_U7m-CJ7Hl$N$=@Pj7vU+}aZ-563aEGxt9;aNHFlO)ry-oBEOC0X(|xbUHzbs> zZN-#=5pig8A-EJon2(KcU3y)(T>c$WSh)tjJ||p<=k&Rx2P#^yZUlypSvYC6*k%5- z)m#6FR6sLkjbkI@$&c#B;Yk{9I@>NG-~xgvCk;xMjwU=cNEss<3=(mlQK;#>4Gd7i z#$WK#;cLf1d*-hC!Z$|DX+m={(FTDi1Npm*@prqI8iEwx_{M4whtm)B8dA4~X} zR3DW(;-kTo2KS8GWb|^IKv=yy02A80h6KRII;mKXM&bRz^U0Qnh@4npFgey-BBbI% zcwvN*8CdJXh6*X+46T)cMDKK=MG4>3)P1o>l(43vo%)q_aHIC;bvQTYIh1J z*0%xd#G9;_h)_&)UFxE?2JFcM_VM1HfWhw^0A?Joig>YTdTM-4>gd z)try`BQ+{yJ*m zQH@;4ak>S$G^!uX0PI9uf!?UVsPa|>wK3l;FFW(Lb%)gby^zQ_^%%*~<|Am}=R#mE zKxf@+^!+NxT0$CnCdrE;u;IgxHCU+wWhECoWn9|fJRK5-2P_xnf$2d5XQ#MIfr2C& zn=Ih2&L`b7yckRba(xyD6hKx*O0gtJqLDeHF_onXVt|*1i3Bou(O!Q0Z`URC=l|1M z1H}9A!>h_^M87@`xPX&t_Gkgqcez?qjC{f)^DpYJPFxuOH@Io88$@X==i6%R{X#X( zs!|8(-X+k##!grXGsEvA0i)E`N~AK|q7bFitu0^^6*N|Bn@J5#-BV^629&uV9Ne-0 zgPd1$`8qv$PZw&tyQgh|2W(G>v>OlQlJ^1$bTb6Hue`1b))=4!n@U-L{%T2J4&tlD zV9-tt@)VVe%2sY!gv1eq?g_gB{ZWW>{Sywk#Inrl)1n1b|8{ohflEji2rn;Up#8-V zX75v5`=zjAzHU@^Pd|X{LFfR+hGfMN(jk+y>grk+wS_3vEK8UPLi^|Q2auTX#{`;g zhP;5#Vw}xU%MR>B;Hw+lO0t1pNI+1V2tB&1u(8ctEetlESKBS2LDJP#w+(v?5oQ;q z^Wgb<-iresrDp%<=v@4nZvQ|2nPHMfrMtO}DaxsGD&~CX&M7%d2RXD#C)yC2(?+Q7 z*&ItXr`utu9PScACfOXygd)c=TFd!t!u`9xzdrz*$LDih@5Af$dfr1!fqSb_U7;r6 zC81Syut;4e)n1B}n>-|AD&0sVv`W=k%C#+v;;5!2J6qYW34;{^5UP@toEEpVH||Yj zF1erRtk3V@`cB$7>>V6nbdJ^Kx_#I}0Q;05ZRcb*Y}&AO1-v=Va1WQt`vdzYhKS_8 zrQ-gpk*g^bIx&&XeVFICKW^H9fnTYT;|B;;ZG<+~tvg8j{&Hw8v&q zB=@ctU=Gr0^SKhMkG(JA44h6nHXY$4SQ#Pz28{ZiUhD7Nta^0F>V~teDy-FOSMJ*8 zbr?xZXpGnCdvz@0$_w>j4#09Q)C zn`*G-CCD)gbr8xTPF~!*8$hF(UY%LPNBpy*SRVq?xJ2|%ixkL6qgosm$Vl@V*Yx>T4FG3RR z3LXO>2Gt1s{=RGH-L9Ly?xXR$6uMbYiP>l{HF8@kvlKq?abd4Vr{8Yf$@yeI zvD5~NJ7>{I)nSxraKC?{@y)0q#ZhNdMAZSw9a7L$mZ$N*Hh#9BWW`ZaZRY$(&^=L2 zab}Y!ZUtlSsyh_SZWULz^JVTGEk-X4r0544JGrG*lXM2+Eaek?_33JIzw{gs*FiQ- z`rf(iQ^)rHkheX{h9|IzNL_1tlCc!fKi4?#3{b|3MMSCV4nF)T!P2pk$nC&kfbS_>-mOZ zXJ(djQ=P?8pGd{4`H1WCcC)%J z#gp9&jR*G`|GyB`-Z!NeFf82p2vPs}@eFH8YHpBC#Y!$b9Nx$!O21N4P&JOi z&e=M(?)arw8-Z~&b_LW&NDQ*iPu`EZlTIC?=6JbkDN9CkIdFu)5-A>rf1lO3<^4}= z&BWW_nXXV!@NjnzHpaXT*HTuV^b%ELOJLw&^Tf(pF*qMji<~ zn#m*el2An8aO^z@9pTc45{7S*SBskt*(s^J!r<9Dj<@moedUGFfx((9@D=n4Lr(Cv zg}}a+dw`p&jb$nb3nnz;`j=O85z9({%t}uV4p6jIq|m%Oew+)}2VUX}WQa&1gQX2& zy%xxuCwl-FMcl@*)?BOlCi-9!zeJA7Gt043H-eDiLc&im1AkEZ%-&nhg=J=+%TUa+ z*eB(yhH6T zrRABPYLE#+^VQh`%N(e@Zx%Te?RB|8B|~t3D&BAvsO`@jz}uqWbmVp;ze=lJ9NNHD zgD#e&Kr(ZokmLol?J7eHu2ev$bugPzh4`sQl6JIP&F8y@5A5KX1OvtYuiVF~Fvn?P zAiNO-KVLEo# zL^VLM7A3>c{=o5lIwhM|p$_|W~2U|ABV<6l~5NZ6)1o9Ivqdh^ZxE5@QS(OKpk zd#|)ur?WgXfvTSA*6QpyNq0K4Mfed0fao={4POIrGf^)#HNE$+1L_HTbX zzJt>nLn;z$V=Ac`DlYH1ZCAaE6eN4qmb)$c$cn4WLzsksYx4T<_zH`ex&PHQj$#iG zmAt9yK7n)lpL&b@GFy&tIlsszFh1r(wwX&tlM8*kK#&er$u)|-B+?9oGokpdtQM;F zlBvya&0pDy!XVFwwzf6f^* zcIMrfl~^f$GRa-L^zscfnyD~39%MMa*@IM3%}$yH7{;9`Yj0-+Kkc^D`{XTGC&=4?Yn^fW@Lauhx42QnUfX>% zNq7K&NM%9R;&w_D1Cy0uYVY3^|6qR;v6bZww>BQ)@kEqqNx|N=b5dbEWz$Lv$QLjK z8bHZr-kSd-pp*?HQ##a!#*N+?CXY^Eo$6UExKm$>@-N}#D%{IO1XK1VpkY~~{6df? zZdzlC#q`M5i(QI4;?&-tYt9gPCgA~ljzTZBnQ!?45>k+@hjLC40+f`p=ow{2-XpJ= zaNduxh>)V>{bFR!nFcjz6^m+{>W*dSD%c1{QfRG1QiPg6-AJe{X^<|UBZm*A!nJ1+ z=up|E-46SNo?Qk<1v!O(;oH_K%o7);EM4kU^JZo&kg7LYr?!bb(Oz5}C4>P2^YJ=t z@7||MIO9yD&eYa*2(}hX%1`?xu71(P7vF4(9Z#N7dM~LMBu#WYH@%AzDht(ib~7eB z30rC^(se9H!rYld=O#Au5?~tv*| zf(|$=F7+E+DeB1AKjT%Z4OjpFG}!@H__&nXpd-Be{L9XLY)ndl5N|zhmOg~$rdmUS z!4Z<|K2aHMY0OFcr@oHbvRr<46yeNZ^-gLSU|r23FIE`x7#Mqqm@djw0+I0o8;9~s z!;XgeMefIj=o4TDriLzIPSKWtQ%)S~vIL1NY&PiFM`WOBPCicCRj@?OpAw2A%|f^8 zkSng?FrBT4h-)O&b7?5#f0PF?JM@;c(@pbm)V+B3`%L9c(~__QEHf|P$Tv`+DBc;aHU z&Inpe)WN4`RG5R26um@M2?60671L|`#qFB5cImiZIr7)$cR5xJ@VQTHjr={6)>GX8 zp;O|zLe|)eCDFL*t(W|trW&H^BQ19lkO&cz;`=x@jqo0BkHQIaqmmc%@eY6y1DO+8SE)~Si z?mw9J<7jKEAjM+m5KlpGin$_70y(kOBH74po!$^o4<%&gXepJWnoP(5fT90>r#6!d z#O4`_L%VW)eYrT(8@$UY@l4TW0o#pJb=W?wZu06(&-^$EJyc9dsuhNz=igT;NwwN; z>%>Oc@%HUrKDt<}`1A*zkZOcH$xowQfIJMn8!fN{7C3s4JjwIgj_o!1LbevAhoZwe11N5A0T$>3O>0Z6Gys35#Ee`uDfNFFl zCdC$|g9HIIj5~#p8W=Uk^$bZ1PS34l7;kmX$g%W#3^{05eS^sSAHZ=7!c+fe{9tPP zyffnGvAdH=cmz7W|aE5(_xgD*Ob*6+mpwi@85DAgQ0m8kOQeG@o6W+&iH;v`vd)nV&#BOVnho`ph!ah+cc;ZP`CwmT6Is=_ToSMR6%uy=IAW(m?`+gZYpSF@Tc*%7aTjM6o7 z>ro>IFspZjwp zyT-&BwrS|cLO9(#we@|VA3-Iw0u-kg)dL^>PdrLQ+aT!TAaEf`o31J1rI(8okq81C z)nb>_T+E{_6onvCn`CA38_R{VuuJ5fi$oZ8C?@->VH1>~dfkL(*~{-vx?g6&qlg$5 zXQ1|kRi9zZzhuS?H{(5wS2;ydjTc;P#ZCwJMr?p27~!d)shuW$+m)4 z_SB;vFMEtS3L4b|@)3-K?>h1+SE;zb4P&Cv%Bj1JlbJeS)sB9r^xk?JD_VT4BcwAGJl|{$RxT?|GxZ-t)xLU zn&77O!(Au`%+6m+CJh_%$?MLf12m<7kRN3bPD^B${?uPGK}c&SWiVZjSML0160Xv2 zxO4HhqG@SXL8ivT*r#wfg-6LA);y_qVOY*7OSYqKwtOv=nxA7|J}IAgrcn*O%p3v= zckuI$L`!8f=HkW^vVL22AITks$BE*xGacCn|o zw6zY=*+H2=#&9lprYgU8kG3|@59M!tp=|FvN}?JLc((fL#Idj->f#X;GII+bf3CWt zscn1aTK=ipnsz{k`b`X*I~&N22n#(~gB30;CKHy6({596!uK91C0H^O8W+p7zUS@aHj1WP zeiQJ@WTx+FAo(0p_kD9Vq01lm2am_p$TrT;aM(`;*+VJfl(4zJ0F52z%)_vcEH7ZszuGdYUQh0v)GhGeC|#?XJzA6+`V zJcg2+$`z(YxQ2VcEW*N*q440I=%Sa5!Qg9`| zYdE(RuaoxTTWft;xHnpN*R z=3ah>U2?P!o_JRCnrqvri`ELv z6wrJM9S&djX;-h3Pa74GOxIDRhn{)h-Am)>ds9vOx{DDlx<`IZx9^`EI(KEv2HHMR zsn>Dh->r0BTHku2&xeXul(6r*3KDM=(Rb1xO@nE_AFu7S3xvv#e6lYfY`TSs52Y31ZDZ@6n#kgHmS76XP& z9FTYAo#AVAPd~Y0S-x74j#ku266jhQbW|s<2_JBlUL^WyT#Sd|iBZ8G#~vNmnp|ia zoLS7dbAkV2{uw)Xv>x4Yn0#B7C#jvE?I}`zb0^xBdyEZ+Fuiv-H8D+vY0X{J!eE&J zVm7u@^V&T{&xe=p4Jfzq=tR#nu{nj*{!gLmai1E)AY=`X=6$1Ycm6}=lMTV-6#%%@ z6Q1o#Iy&y2OrtB>c;OZmG!I`RJ0DTnoe{ap8+e~UG3{Z!swt`0U>WbKU)#>osDQ<> z?BiHpR;GG-mP@*Vh8A*i!KNtw(0D-AokOt|Vq`(ebWG9fagMI<0_TpC{cqlw-?jN`sVM2x z&rz>a{^v;0Yl^hViSAxMgE*yTHv8%(bDppS{||Z{TIRo6=(WDoJQ=;V>Z3UPA5^mW zg0WS2{)y$6&3|y6dAEQ5y61V;qQ>-H+RURLjW_>^88hyZq`vdXB2(hcwPNf!VhbM! z_s;9_pW}lw32V}i8T9H#-g0^7wjpNvs7kz4r z?FTW6)S3%5bsjrBouwhVR5Et;bExu;KUW(~jy)tlF*K2R(PJpMkdp8~PbR7E2QPPL z&%#Tr^p4%GW|tCE7PB|QMBd4Uq!&DR{ycO@s?37xf8xttYF=KER}|^}XttrdXdsh% zpEh4c{n|C0RiBg@$rZ!!sha7w-}WV!@-Z8dD{R5VXQvCoJtRl#W_1lsq@q2lFb{Yo zmBTg%LQbVfxMQc6fe~+_KdVCOHAmW+OG_%aM|N6H_E$QG>sqBlB zHgaA$0?Iei-L=50i5$s1XX(skXxY`Q>WS>XcmAU8eN(o%m#yGrZvXY`2fg%a!GSg? zsBtdF{%8G(!z90K`H#c*j^xK0_@)54|8UO9f9`MCnwFCfH$+DTnP)&QjbW7@ z@BU5~-Boax^ZQbaWJ}EGh5DB{Cik;)K8Qzw$zqa~W!Qtv?O6vsJeHj|y<;Dxy|QV4 zhEl)>M`;hGwT&)uFML$#UvI6?MSdH6jFygZ`cU+YWvuz|pX@RJw4lu`4%+`;YX3jO z4t0O;sw3k11_ft}euxnc&uKviw)alo($-K*w|Q@fXqUfPDYTyuF>QFTPrlyv)46Id z%I_^xjj_RC<&Ukhyh)G)+Ld$jzDh)9yLPiEW==7y23$NRoz8t`4AdxSe{SoHs-&^1 zj%r;^u>N?623M!#G?!1FBcALC_v_JlY~6|_b6psz`7QAq zSUBGJv?zD<>Ltc8Tp-Cm=cA{|nwdwpl8?^C3=^eRUJrJ#pSM_6wlUq%{s+mXo~JbL z5ruF*6%>3V=g!&mK$d|oE-;*f266w+@N##X3FS7@(}`pD<$(+=4+<^5M%W?LmVJ#h z9Hd1jE(kpR&+3Wa?H4>b+i3|`9M*A1_J^}jS9mDp!A&4j>3%#O*gR?V<-yvF1G)m} zWP0*$7OJ3{{h`fT))09c`@&c0mrhQm@7})m#)>*l_oOvZV!~N*9hRxy%q3COg5~7i zW8A_Diz)IT<_Y6Y=gj@ZL3>-nv*sc6?5LXJbJ@Duc5DTZbg}QCOv?e5bXm-9j=H_OE2_ojZjIeuG|~xkL{w5h2T9cg7Ng<7p68 zYnZD)sf2M1K06-Ad0=3&Hx(FqaQ9q3#7mF-wBiz`+)lK<@ksb#MFz+>3KVry>XT-c zk>=y2-RTI_;2#) zi^4Vxze+qYzwPBZv2*C2pFic@`m$pf9h zhR4A?CC}s+`HK&!mYA`Tf5?SzYnFoR>&VpnYr##Xhz98T%>bh?DbMRl$kK=?Ya_{q zo1&qZBm%Igm6HP(r(r~x6@G?*k8QNGX)Oz^dG6GZy8#^KRx~QsK9>+ zjpXff{QhadAiGwBNvH3T*o?`7EVxheZF_0Q_o5IPP)u0w!m}?uGgl3c%`#@CVs+Ab z$UjYMUl!r}?nyp893(O3Xx&3|BwUIa_@3d7H~YyAy^Rw_%fdQ4cVt3Hq<*QQlY#}G zQKqqDoT|Eb{%gNRBU}{zztv`ySIE+_^pES`6Sk))p}XQ9U2HA5ZHIzoLRJ(hH57ba zVCkXwly+RjdY5qI!mI1--^OR!xos<_@8tKG&jrVx3X>hM4}9kefRD{U&f=4Jb# z@KbLdb!3$WFRlm%D=`-mWJgu9eLaGy^kYsct0!Q`3OcALs(WND9QD~$z!Us(#mIre8!G#oeWWGoMK#+xWBc((V^5!p967wQb@MSfo9IYboV)EQTTH4jAp=fcKiO= zVd2VJ%dM$r^`3jq1R%$i#g8v`DKJTr{9FXarwA%DrTRT~)|c=+5=WB0oigwz0V7~eemzK-K_6{^o5i`26`jfBYm#;;(4Z0Z9wPq z43DUHL;xJos9(CN4okhEyd>SR6t%g>h{)@y?kOrs{+cjQ_izlN9jSDi^Bk|Lt5454 zG8TlQjhV!(0OP7e=EtPE>sGscG+@yQyo2@3UMPY*Tyqt_RU zgfU#5m)-#;R!*}k`b1@n-?fLUALVtQTe`%xF*o+joihlNKJn2Y&%qbXFjUg=juZAA zeiCw6#kY9Kpa_O0Mq|cKePI9hWy5HNGZ!|K6a1d#h(y5gzqGL;#kP%gOVXy&UjC?+ zDVqJ4`i#fdM5n#wy2>Pz@6Akk9DFE}uRUCAClQ5kj3D-5CCQH#o3$1v8-$x?>Gw+m z(>H5(=Q!LN)G~#4pDe9TK`w*MYirl!8zpK1Ymhsnej23I(4c! zwH?1RU?S^9&$k9I#7DyAP?Oo;KXfw8byGbN**UGz9*lgMG?vV)l|FfJsOsu3L+ZHx zfeJTC!q0mfF&fo{S>RNEucAfTOOc-3((EoKeEfO%uhUoIv&0bI*0ZJc(_8tS^3Jp7 zs$g|%`l4$tVfpp}&1{_}OX^pCDvW>pk*)z+{P#!T7;YD9?XHfhjCZNsdws;Xn2&i{ zesle7!mfxjqp=5TA5FepIUs@Ej1Q+AGl{z`ZlKUHNCEC;)!XakR*#&X8P4WXV&2tW z+Y$@Dye%7$IJ6ZxuTp;aeoKXf2Hxl@%i3JZ(^n@v0+zYJ(?%Af5)ZtTys@UHLZz2{|KsfYvOn1ZH zanD%(eA&Mo*wLHq_Iu2J@l`0`g7hYeT)|>bH9;#J;femNFL7s&i&TA5^tw?~!7=i-LUZUVT@Um4eRS}&Z2#_3@&29u)ylmq*yZv=H9bBK zy*{UXe}7qhvG2p~HS&h<+2Mqu0R0R_?;-SEPoLF9MY@OfkGF}V7{q3T{@*1R*eZ21 zcfu+)+b5#7jgj|%lLyPc8`b}@#C#Xucz~p;U?_OB`FfsO!y4EA!%6enghRQ_RL`b4 zGiq%935#%Z;LfJ<6NkT&1JBiey27gj&&93O>jSF(?ey*^N=Q20W7w)^dTG+^C-&tk zRHmu>(6Of#E1s31+@TsbI`Bed|71aD&okO`Oan+9L;R+9o zpX81KJCJJlN~s0Ms|kM?cFdwPy5WBni&x-Iedt%{R?klx#`;(PYW=-J1LK4pUbsAj zsN_4@*J6?Te(F=AReJ_U-fhU>!gCz9yDM(sDD~g?kx_aq?0EfYx3`b2uBiVWLJeP} z+N}3|k&Jd%LzD`jwIwgiCvDkq6 z-OM|V`HN-$K_50s&MWo!z~rUn(a45IG;XA(?zexejj@ap7VIDT7MF{s`QcZG%38a~ z2kHLG=3!LCa?71VA%49ZPBu>>y=_rSt?n}JGWRxLSYmGb!I-RRB+?Yj1v9>ADc8L@ ze{dL`>BUXe0di`>%q52-7yeKoeP*f<7FSnhyb^v+nH(xTkx{{hfaNTb>Nb5QbGH z3!i=3l`vAHQRuvUJBZK=gsN~Ew;#u%=Oo3UWivYU>)kQ=59(62onJx1WzW6~q0*RE zQU=V%^fg;xf#yF9Ez86y8!uiIjJ!Y9Ab+eWZ9OP%eopAwPyBUc!{NaW#hY(@S68<^ z7G{fg+Shz|tDE0bQP!^DppiwRm{07y(Fo1buEXDUS(|0VkBJlRp|-V-)2Vb#*!GD! z9y;cO=^Zt>-S-EG1d2?|pZxlR7QG@OPM0!&nw>pS5R+izR?xfGDCt|vj>Uu7T>tK( z9=Ej*3NJqf2yI*ocvWY6weNVn4#d6wF_o=1^0Ghh_XXk59OVk;5}Vdu`O{^9EpPD5 zf-|2Z@VOMt?pSRzJA9p))qUfSGjfVA{m*XS@=^LEy}`tK3M-q~y&?NnXwxo-BVBmo z;=A8Oc<~182*S8$KR!l^os2-a7=6Af_Myzo*%r%_V=MgXJ@oX-Xo4=7xeyhNd5qlR zpl>9Zx)c|e3gn2cd4@UhwVLNZopc9^3y%e{&%|^eS9e^-eJL1?T@|^u@G_v`Zvs3- zN@7_NOZr|3-|?C?_X7LX86`j~CrLZ!;d*=N0EVjKcqU5~sLWWpJ9fww%qvRE+9 zE{hgy>Rj?~7XNMV(e%8^?=Byk14l;@s7-8{`PjvS;on-Ml{J&2EXtlYNzJeS2c5mA z^Z32wf6#0qQ2v{J_1IRAOuDgbeooc#qH@Az=5HLW(4Th`Z(|;EHe(zRRsG0|(8wmC z#ed&GX_j^)e;+R@|5eJrn`|u8P`0ynN&up!frHfVpo&4UcWOuVlxq}qO_xbvK@6m(qA)Pb(W8Yaby|sw?hYKnsOxr zhK>EJ3k?XYp02ygjCZl2tKi(YK9qR07rn5x3(|`f0h22SWn<6xc1@@fBGr%s7okX% z=`;x}Bpwan6t25sJ5L!Os#QW_TWly?C-g@g&e_D8A zr+^4YvP_5LtD)CvT53J;u~>;urkZocJiHwub3<}>5Hi~1$U~r%O1b>1a(CgK^5NC- zS5eQ-JIxK={13Vt&iTe@zfiW%`eIQ8Sd)1iJ@ozkSr7PZaT^#mhj*a^B;&5LA@|hw zEARuJl!ae6_lH3;Fv&)pX=7;?Ng=zXmTlR$4_--FRLB*<6Tz+}bMs$=&Dr`Kzd_oE zXS1EQ=%NuA3LT{;VxD1lN|a2LtBqT|Zg)_qvCBI2V#v5M41E^ohk!g^7`OmEQunc#t&` zyR0CQE50i}EEGp(>CLLkqX}_j<}VAuv*Zcxw#Og(Nu&@g*I7ggo*khDm}hpBc(=4A zf74nNBS5NApRld?PbL$(U`Y+#!sd#{aj*;52NH(q86E8{p-6HY-}(hYpQd_L(UQ*WP_8EwRN!yc zpUahcEEo8m9syE~9UOTzXzCWoR9sZA8w?%7Elhws$`)NKK0d}#eH>}#Qk|V$v-TeZ zME^V3@{f}7HjOK#(;{YHmC*jC?=$qd`0(Y4P$utq_Gw<|0`>2oKu%IhQj*Y5Be`>> zCpUjpo>kGEcMr~fo_N^^SERuoi8gZ`f>8}idrtkPOOYhnIMxc4-6V~dq{w_x8E9I% z`qc@zO#MFRk5ry2Ftq6`ra^c|abqX2AUhxmk)PB5lGLx-qfmLCY}Z?C*rdW!rL||st>#z&mWKvQeiBDA zHT|sPvTgyvMYqjjNgBH=-u6wkwH9YUL+D|xpWr+mz!!5(3%y*R31_81q>2-^PFn?h{I;*L(61kuqDJjw6-s-pp=1qFWZ5SD2rL>G}j;x9%(w4cPL7_8Ur*X zkoK6>%(jT}Zk7&tfNI-0`UF(i4T&PjL4Z%=S%kL%n!D1pj!>~UUWpc9FH3(Qi5rs% zSsy`){rj5D8bS9znva>P&@3ifC&ydELsg!1&}3nbX75Wguam>xhHZg`)Ug;z$jF+d zvlx#+3^EqSpB1|=Z30!%wj5)jdW{rtbx2!}3APS&SH+zfo!^uu@x+i^1pkP&e23C8 z#2p73k!F63i4Tr%osizHQv2P1`Tc!b-HhX6Gv+ASxCWC5*qoRC)?fefZ|yR~bwyt@ zU@FtIM}{_f^K2exIuvspkw!u4RQ=dojSTkVT29|1C@$$=HFGuA5Zbq!QZwM#HAHAC zbg4tk`OgbljzPOR$G`~O%2W;ZN-^d>gGbFCwRbw29B5uI*E-mY99EyI)_D41H^-bW z8}rh#4PoBA5e3OYO|=WL?t2VECayi11W}U*XV}rwF^rqmW62bH>Z=(x=0Q;$1{VF3 zKV`AUcVFre-kNW8BsC`q3Jzj)iST)

mm#RCM~T8cSOJpi`MK z@c5f%^as7KQHtlTj{oCT%o3sas!i{2%w_oB!lQ6ShD|K&%p=3-9gaG0V1l0c84K|* zHOM%4HkWuUZ}CB3yUv;&k38B->}|J{974X-p~9wbB$mnq=~WwIS21JYSwjpZ%CCcs z^G|ce*qK21F(X_LYI#$Atg{aH{QXVN_*BcOq$Zqq*sglw{~lxZ=h)Lx(iIjw>BMGT|}lu*X~BUbOm zoZxR`Bq^~SHG86?@&%hLyPfXK3lBt?abwJzkLSjca=2J;dim|&TN>87 zBAzJp73z)^0a!GnJQFTEDFw2@)+yosY}@uvFuX851?X#(n1l$IY(Ss>GP;l}asJ*G z|3I`Gkj?^;qDwXQzSQ)LU^}YhwEvo+Gb39Yi;h12vS6NZeVWL{SoTMJ^RkBlF z9PM%gu=}r}{N9aVN4V&LmE|ex+?~ouar1!{)OLQAl4=63R|X4`F9k346rlkdU%h3{ za>?5qZ7E!trNC9xq+nO09BL5MAg`=dlER0Z37my%4ChhxUF#VB>DRs;eoKO>pK2l{ zfBj}FQTPhsf@gQEY_76_m+MwL8;Y%~#k9Kpc|@IWDCgUd_>J`EZk@+%%$Y9Qc9o`> zhPAfQ?+LdLsrgW-Fv2ZVe`ngF0UX`~G)JgEP`g-q)aCoK9!h)m=V3X5M^8lY{Tzo4 zHxh`qod~8ex|~H_X6`&8Q|Mt}EOeog(|%D|4*OGr-C!e`@iZAPU1a9h?`Ea#(pY3a zF;5tkg=`H?Xvrb)Z_oA;#z+dLj;0L_b#4_WXH^d%+G8F^r~7Ww6`!i2SVU)0m9f*X zxK2c*^n7vKA*Uz3+%d-;iX(K7to$B4M8Rz?IM*1TH8gZbVMcfg|HD5#DpuO_;_H*a zUN{HbjxW`B?lYE=Dy3(%v52s_7BwZAi91SAIKWwG$J%M8BiW<5pydUE(i0yb(OXSu z|JaLfqlAnfjCiPNnJFe1%*n=r@`b@!_b3_V^6V1bs z*2a>Mv0z)@s@ zY)_#QeW@e-g`$Ag{>EdogdtwlF`)2W_Rh>VMM-TCN!MX@u~#dzGP%KERR66|bXTSL zSi}k^vRk1Pv&>52IA6H=^8w5GKfUsKFD^UOW0-$i1=9L_8*UOI`d^EMA(i?z(J> zcS21^zk%XKCL)$Wv+}32nUy$F-M}v~I&+2XXiOMLkFCe$c<>%UPP2JD)gOu<((-lq zxA4~Y6tf~EUD)jf+RE}aD4wv(NZi|M6>P{?oJFXPMuB5aj!q|^VW9vN`PR22Oo_q3s)fDOk|16X_yE#)72$ z^=q9VOsub3mh)uNu#>m|BJEqAZKLihUttKs}ayra0>XrM_E-pXoDj$!sV z5>hg5BvLBfQeMt6V9dZ$}7!s61z$A)yWM63Yx%N z&3k`^4gbNrgAN_fAt$vnz@681Ii(_cy%i#fi>txvw`QZ=n1Ci#(yy=|<-ugmSik{E zNo=#hT=LBGe3j(3K2#gVshuQZOyTEZy4=L?iJiYEs4kC;QU{+zlMMdQ%;~zDGjbe^ zws~g3DvZjEi=*n(?f|o+W^mShVE4@(t3d5BdghuBadBk`Ut@Qu0AJIzrFTZHQ4d{a zA#^Ghv>Z^zgiW#?m+M|D&emDvifR4_MPW{!PKSj~0GVWr%Oj`E-Tf&Pq6>YtIY89c z_X@!R3D!GQzEJW8msdL-0U!vLk`|&;l!*{_nXxPW!@^ zvY1N6wq1ank>mMttrMZ2(UjdyK2ON8HtVj(%;S=n7~&1DNx~9gaRvJy1hB%BNyIX4@VKq2;jg<%0ONf?-afTlt6uYnT$*6tp9 zH0Bj(_frIHQ#IEpZNyZ+OJ51w0>L;AMP@=dbrg}9zrmnj@gfw()ivI|W#qP1Vf^TZ zgzmp0<rqrGE-XHUv11D>pl z@ZvKj&kVQnMRB0-Kc$@1pqIl2s?fCfF~=|>aHTjy+BH(f{=d|jl&oe5X-aFbhKmi- z_pr0guCB2C9H%IXS<%_O5J|=|EuX^cn>zjGsdltwHQsB1Ca{MGib=z(G$wY@BhvZ+ z_F}9rDgOt*OM0pMA3g!q#G`gNVh0e6z|jd;GHX&;(}}Q$@E_2yl>W67@{vsm5*#?i z?P+YhNgQ?LjZ8;YeTpW8t7S0yc;nn1-mlFj%ZI`pS03G00?*i8GZJ?o%|oOb+E`JBmwJC=_=hlz}Ey zloZ*~ssyLsHPy-akW}OIggSJ$K=?r3eGw=Gc^l4<^4z`w+jigpPQz$>1*rI&+e-v| zSrH2Z(hhBdU8 zx{$L<%>uDNK@A5Q z^g}^5RmUOYMI;FJljZf0tfdzVo1{F;J4S2J(N?70mNRj0WUQ^{)+z-jcfVl-K~3P5 z7*ApZ(cx?Egh7QH4F;OY&EymTRU#LGCV2(9M`70rcwi1^E49P4Bzyo4{2^w!F)3#_ z%9EpQUSZf=_>Z880Aad+&XhgxhbWKQTx>q(sPYF^!AQpZLmJ|~A27e5F)0bQY~`wB zlm4)UH&jRL=5JT&)gY%LVow-<5>6#YZRuG^Hec^3127uZ!9m#^2SR5IN6yqNeR|(9 zkKUSJ##*I401)fI&uYMnL8zT;|H6Jnm0B)hvLq&8bl|ui&lEpLPPK8kyNM`7{r-3* zmg&1Ed>cIIjrxuw_e{bzO>g9A1@>TBnOQ6D?B>(bd2%Z&YbE9bKW)aq zG&URTjB7{xs=&1+LV@A0TEP~!Kw1F>QpIvBgL77KB!o{rV9JAgO}N?66fU#@ z9Ka1%#_-Xkmv{*{7(U8%h9d&CrGdh6qgXi@LVlT|?4Euz*Z4Ku`QC<`9ShnS*JExE zx%=K<=*dOo{?ynjCnR&pbyKb&L=4%DWfNryRW)4y>!|iFQ6II-&GDUvJhM@L)dA5f z*)KR;Vzf_&na?xry6B&+%0**cIAO2XA5%-d06@5~PG)uv z_+1+yX0QxbF-ScM!U{3VNX;jSJqZANlMD02CHq% zsTq4jG2HZB7mPN`lP9k5fuiQjoqDrh2|pwJH{AX{{B>97wDgA*OHKy4)1r-a3KFI7 zX4x$(Maz!YT-%wHJL?m3LA#lxm(w?2;QT33&ZTa1L11YobM&pePPI4te}l2I{9+dj z!*a^O83A+LU(OhF6mw62g0SY@vDE0fZL6C)ORAdv8=>P3XVuTC7~2iFD-uIm?umVj z9ldCM#IE&2c9v#u057Ie`Mv$yaF#WQjTkRqP>@|Uhl85}!KL=|DA_CA+n%GEN)ynmm zg`yL`RV<^Y!}eGM$}MKT{7Iowr?cOFB9~ATz*#CUG1De(-1%I4f3JOaFm2_jdlS1M zvQF|1IdGq~i~gkbMMLJ)oX?#no2sA39~Wrsxs!n#u0UFQc$)Lhnw@%tO}k~3lS%C# zqpiE&3guLi%-k=A#ojX^{O`0cz1UH$crnr6L#>f&&mYV!KeyDzm-}mQQCBa3iBekK zEG^o9s|eCc`NN1y!GSTq!#$q)-G8m^MuCThVhk^U%Q+i#~$vORf`wp}^?{5CF5`YRi*Nls&#Wfm9u&=Z{N7ApLe zi1>TC60xZ5yB?>|YLPmZiTtWF+8@uL>rUz%5>C>bPpO!>nfd4>H3Y8(w_N`&-0xD_ z4l;SO4S(uc$o*sc?Xc%jnwIY@8#}j6aM8F|%EO=g?i@1abo)Oj$!y|8<=scltx4n* z3WoKG%KtW0(*rYTh=ZDW{Y}X)|m( zI3?#pN;ynXISo0?X^2X*5kg_)ta9jJgq*U8LZ-->5p$eF&b+^`_vd%J{r-c!_PSoz zbv>WY$K(F6;C~#G!aM+V%1VRRV9$GFw%1-~-ybwM^f_#FSVnCOk6si-f%a`3f4}y; z_ItuSoew3XnJ}^`AFx~Mb6h2O;_iV1!s_xe+PvZFED+G`J@FALx}zotnQA7VH^T&s z*|x14lsZH{#g~uRO+J9R?dfWEo#P8K;r%Rl$2HgH;9$5K_LH)6jodYv7MR_ z5E~^@U-j(!t7{o?8)(;%CYkzJ-T1;;eM*Z(Or8X0dTI2UJO zX4v43)xWlJ*+j4t0r5pQ0{%2s0m$B2G6*COhcfCE_h-rbMNyYDF13m{X)t3FYn;Q? z8Q6j=p7?92Z0W~=U5IA&LHIl6GM!=l&pwKfPFq9nHu0Zs{@UcQEmKm?$>4tEG;F;~ z-`0ItnN)qp=km@-3%vD4O`Jhe)Pp9*7lfj>Kc(prYgbv;vCSb*(O&1lbmdytXXRHH zWuJD^106I#4^|qTrU=N{dzdE4)Tr6E`Dv{nXU0qpdC? z#k&-wq#*r)IYR#s9?uF-<^E2UGEX_U3yvA2!&Tk~9oBS+;~NtYPHZfP5x4D+Kg$og zf7ZDYr!ViG)X&3Y!Ii)ED)VC)`ow#;bEkQnAo@5B5ie>I8XOf{A zqFT9p2K9rv1H%k;n?><-rIcy#)MVz)HXbGvZ2i$S&Z2H%GC;54$@5_DaufTV7=b+RFJx@)ARTVtUnaePV~M=E;hx zi5>$)4Qiox-o36EUzQmk+iIA=z1@|K{+xd#=0N9o+fDM4_pY=PfKmO zpZ+Fdx(CTy-RkS<`)%N~=xu=;Tm2sPednkKHLh<*qhvj+RP45xlhLe*pN)tYlJaxw z&-u+By)Lm`R4QOlU_hEb3yXwkXc_Lkcf|MGnhWo4YZ%Yu`l4n8)UEe_feNF>Dj9qU z?8lvcVjCA;ybn+> z*U}IlXK1h7tMBXJjkRn*GJkUS0Y*rm5LcM1D8Ez z2_M8+IwJd$8%51=4q?)TnA7SYzCht_{J>|?TB{$YeI>?ZGC^3z=ef-bzqv=BEv<$; zc~4s;m#;{Mq%|GUQTWnnzMf^vw>+1Czv zGLiBG%roi7J6((zzqNO;OLhgde@Vl4Crvmz6OV++U{f6*^ZvHAQ~t7mYV%HSYGZHP zKD2X-mlf-XWgq+s_it6Z5try`$&}e8WD<$?cVog2-VaLa=L;Zz0`{!0M zst@P2!t#kQf(7T<(@;{xEWQ29!Qb)(rl-v4`1Leit@PVU@j?=dYVwENZk(=%w9XnNrp{EOb}{zW`EB%5 z-wz)Py4*GzvpHR+_p$HM^~?u>7)+2+z~3c zy@t>>2-_ve->Z@J?#N>sxlxMwB!+0W9*fT#R{h$$_#BiZ_vFTA`rMzOOGjvYE>8eme_{+@=7a5@ zC6g?xJu6PyhGpykN}2*7_MopBOJ;6+ojUd3N@oRn2TF+)nn`|R-SfAHL#8pns1C88 z`@*mEqQA&i$EBufPW6MvwfzUK1DhDIrYAzVRBa1_-`Wl=K69cfmNHJBvI%6zC+gl~ zfBU&G@BPL)z)C5wYvYsnUrENS@}HIa9uUE?N=tImAaEHq<#xrZ&Z{OAd}++2od`J) z*Yp*os}}xg$F8&FHD|&>o=#3iL9h$>Xr3AMfj1ratTd5m)bh%q8`WKiN0kLNm*O;! z{|h>V;U%flRtKJU8}gmp_cb%vJ+coR1?UGQR|AtS9-nG>DBFw&#Bj$mioGf7>&`NU zma9-M?|%4In-@}*JC)BBVmr0>FFZ7ex)tISI3M|*Nqm2nG2HNTaZA66{U5N?&RNbp zNuIIS;?rIP-Wys`a;f&X>8A3>SUMmgE3)&T$Mp^$g2(ciw#ID#u3PK^`SquohjPTp zuSJVi7J$N5UvlJ?ch$Hhxz^@i&=C>$pfaLsmE4PidgmWg)3Xtq??=HLT62|b%@5CA zxnQrKGJhA7ZdQI^inWVsyX&d}dQjh0`hfi5OYHX5pr9etV9Z};Pl?)TgX>E+QR({} znw=SU@Vbb$_vW;vm=eH8pKU4ixCKYT_lAOfwJ(hW-+x??%)uXGA_+$|D zp4>;EgR}?69LjV-z+t0nnZ-x|S(*tn-M31-`i~u|vD#DLMZ-1MN~iCdvZthWsg{2w z^9r{PgiG|rQ>8AvyfI~F)Z$*l^u!mLDS~sjKQryqrfy5EM5PHQ3jAPg**z~%@`%rr zmmgD;rRH#$xv#S&FGZCv?KUV~SD+GP(wlb8JpB5+}D18 zHr?p>EkV>UIU@V#=>pvpt@RDR`6LHPsUR<%AidtZzY^fJ2k>Dg?Rq}uEjjCD)>c&s z=k=!-`~T?GxtAj=Bte(@e1gB9ZO~&fpXb3VX$1j>=GW%+dL*rdQz877^YH<*M@>bvVT=(ZN#^muuX+jq^y=%(0?5|2d#`^P>VQSjS zDian|47OCg@~RSL*SW#j%-s2vR9#Vhxzc{<;+?A*3vFnq4m^U%gFm; z>W8!FhwiH6*0OHqWDnI0u2f7|FsB#14v9uV_gEi?6ES8+OnWq~r9*Z(;&m zXp7OzEzvBM5QUW#1~c@ugbeMBWSV4tQv0l4c$rXx>*voO%YE)k8)|s>P5tU@BChA>YnF?EJP91uK=D1zQ<{lylc@JhOUL+W80K>x;+0;lPS?ZzlMTUWNZl|{E+f#C0Pe}}$ zn_KJ`pv%8Ur@&jTuN^UI#&Uy?Qz!OQh6+{M&JhysN0a54oi7PY zCk{?Z1P4)NPIpCQMk=%7w6ewjVLmQ6VSIU@fqLumi4mIWn}~pxjS$d0#2xF1=eGLH zAlv9K3y}kDXkB7AUmsoAJ3dbRvpnNkpH~oGu((b$;Xe*f0yCy?R4Is8v zXS+SJe60L@@W}BsPdC`~!Ki)7CnEj}&PO^gVYEtkf~R9aA_!Bff3W}dY?~~KjXn%h zLI>P3K7|HllWfl`e7!9afsa7ZW?7RVyr`m0n{cEal>+_{0#me z^nyLZ$8Z3$Q9?ZKX)%v^1)EGH+WKS|jUB0}Xc%96?eW{c`XO|Q@uN>K^`D%nCs4+G z6yTdiPMlj=IB8{^?p$Kcf-f%sy8Q2MA&c#AF1W3<#C2^Ds9lKI@B`(sJEzF47W^ZA zy1}T%a@xlVp7YWnLCwiC4b$gl$IjQZKIvc0x)j$ev#BHYiQnNz_tvt(jGmQo6LTUW zlVJN-f_Ho&J-WR`J_wFuPBp%MaYaI@`qkeP=q|wEM%DjL^xHH;y?pUfqdBbcv(ts) zik9jwK&vRU+R-pXqZEW|H*v8$1AZ4qbt z9xUI~d#A@lcwvEJ9RD-4jm)#>zJ;39aW~aXcKjs6lahIIe$R?4fwS&ilGAA z{9w}rTxlWmOginXySFc4HzDl&Yfj%k0wpIta?zd(o-Sg2Ebe-F_lEO~4cDkOSfRC? zfA8}zFOwg7UgYml8`s3@*Zyu>#~d;2po*w@z5Fwf&lR&UKyAQ6UCR@`#lO*77Re!)+K)9(^zm;v&cN0kI&s;^4WLo zW4UWD^ok!8^X6M0x+xwETV)Lv@s{XCd%V2(v*=?ry&B&zAOA+9zn#1Yi#&60JE-Zi zYV}8tkKtN(4!?=E0?iLO?+~J#q^=Ej312){n=n76-?)`V?WwnK-k!TLB;}I$;p%f6 zD08t(HUbabtuD^Is@OiD`M37MuLYgkIn0s)kQ?KK{;ntl$>BJ>D~U5#WnwA;X4_W7 zxIIOIyZ=@&+ipj4Wt`on7=qFvB=rL!4mS6BfBljCTqXC+)KB}6;q^cF7=;HOfWdE1 zP9g8QEI3dVV29NQGN!+2CqfFbCW%@-IJKH_BP6$6cJuxC*e9B2=cHP`1NcBV8_<4cD8f@_y%1yPo##q_uF*s%5O%7(<6CHr0O+Fk0--`_M4L_aAIbg>#h%t) zrU?6gU2A)L>kADt`|G&Eb0jd}3;qwIRd(Tu&zUf%M%-6#u%|9oc|+`gMES4eWLJn8C=l=t$na3?G^*Xt7bLE{E66Q6W4JrRfTu5k(J!*AV90D0#=BzLB&>(j84 zGT!CKCo&NzhPfk!0dFs$H+c9+`8lFOGTNc`x<&0m$C)IyT+jnRDikE?k|y%(Q1e-x zSQuM3G@#6nN{qLb_dz~xOeU53f-Ka45oS*DB#)laDjn)Mt*ec%ZXB~a_VDAGkIkx+ zF7j=!&N{1!cy&+r;w68eom(AzTcRU@aBmY(YoCRoYm=V|qleJgR-Sk+{7Lco;jQE% z&&=iB*Ym0_Kq?uuJ0YnGy)Oc=!D7Rr%4jM!&Sj-p{>alR>D)l+>+j{vY#Qj& zM*B5yk-J)k)@8q3RL^!Dy%4bg()G)koG#RJR;oH2^WcvW(~YKNnppp7A1v|Wr3jku z({t-aS$_G|ZL7O^$M|CCiAA4w>+heAg%ezpQpVUcfJ5ZVA8xxNarm>=@}z0xui!u_ z9Ov1)3RtLphiIt*3Vn;fFm!4Gm;nv0Jz}jsM;uDfw3aBG4*N)?oa43fv3I%4vekP- zqI$PSsp-V3V7=yCt6ZETh?knSB$9oMTaYngsAuOVeWx=+Hg!AlputU>2Y|HCAIMx! z`QiCO?R>=iZobdt7@pG~&ut(VTq(REfZE*V$=ttF|3&M!I#glP7qSJELv?tz@&^l} z(bd&M!lR^I^I4VaWvdoZ(=)L)e(kdq%p;PpD3-i6Rwk})llGc0Kw7q-W?W|`* z-Ufu)>~vVb-$M6KiMWF1y(!q=wTYKebg8z*P>bUVS4U^}mu?m%|CN;88#$klkJlRo zDE?+Z1zQ0Bv=f22)ys3!=J7JcoanNs9$&fbE1--x^8_lw1(feR0`tyX9x#<#+$O~* zhF>eHZkjHy0Ji4bAvL3%1Dcc=UpT)ZNg@z$}dJO z=E(<)SyR6SWp7$8a7>@go@?jc$XR0MN`QX3VNYu%`ey=Qkd$|93bPzFQPjVBT61ce z+cn;*tD5^%Bep{{LxxrWazCXxwEHcv+{dZ;4U@OEsZ-r!M0@p}Gl_oheO{&kmyG;K<=(bJf4t}+8 zANO~<(1VwES8QqtH*0oTE+Q~$kX2kHY6u9F4t9b>p#ELv&BZZGc^d;0kX&rvdW_7r)Kkgn~oBD1A40pOwOLQ^M! zq>J$%8VvXb@(bC~s zWUl&Pym#|O#YyqO0g_zjLYm@@1ZBLp{!0sga|8=Vavxdvq0aF=^j4`0t8S;J;8~O+)VA%D z-xt&r7V*fEy+{!vkOgHhVQ>W6yc{z^LcX|}&))f*-4H4h1J_0r*eIyb$@A@i+b+}n zvr>C{x_6^b9cDVa1?UD{sepGHiPQD+yv-J~Ja~`ESB8y=xQS}gSwK(6XeaspX^l|^ zQFISOv|8M23oGv+$FK&0HG`+8OBn)?GaX=I{v043L-DzZqS?9_>!Eo>bA3{RJ| zGWe?eNR9-BQL<*Wy7*Uk6Y_Td(|Bf#LQjDda%TaFb8DK%@8hxZsY3#|TXmt<8ZU1I zDZs<4^TQG?ag#^cJ)~oy$1wIj#Sj4gb)^9coE%Q~5~_AMS&*7!3~}Y7oa`c)pYSXk zh&435CFno*bqz=(6^~wQ+t(!j$y4rVCW~h2ahN`lzw({Zba|)yeYNqs6G{GLH`>HD zeNzbJ$1sFCP80U!vbUCEMtffS+~H(T;tO>lJE+}CyQhf5NXM^jxXOlx)ksb5OLRB&dpVEAjKTs+%sU>(Bnm<(G=0lOAT%{O zd5?etIfm`#2uEet0bQW$u7`^5sH^bFS(FtrdFe?yPtZ7KS*veLSYp^CmIOlC=<5-0ma7Q;F^O)=b$!L)})wZ z8jCJ@mb5s~KZEKd2CWz8BNRG-$e#U>9D&S4Qh6f|_+kYhGf z)8Sj%0*tsWd5mfkYNxQIg}()sQ`s+#ImG`W^*r?yOM8du` z{D)Lh8|PDBOU`C;i{RsF9a7{K0c~gh7a)~{kvH1T*@~c*uU>%m20H+=QSilT4P`$J zWZruxA*1Cs7M7*w`CuaBA^2X|NYD|0@f(oC*XWX*t(i5nR+!YhOq)Qhk6AC%v-gPG zR?bHNVn$Fy0}z10)d%aGp1^>xoysTW-2%p(BhRcTH(4f%N)V`4Kpdxoe;(qo|1V&g*e1%7^dL9yH0Y2}k^!~2vsPek9_Uhb% zRjTr!^_18O$cUUFUqmW9uWjf7Jn;pSvbUsq{ex5NAS95>x8OkPXWPcc1#WrO zT+3W^=?*0#nhQ?!$*YYRdYf0Y%6WwJNBNU%Kt*MS727Pj3mJd+V77!`Ah5xCMTuX~ z!(E|#&cf_VjGn3-{6Il(_l|jw1WwC}oTqPbOhE@r^)k7FOGbjG=8Xe^0nI&IZbt|F z*zj$cp>TdPAfkZ|MS~D#n(-b}zWD)zEa2P9v;aF$nzY7gIQ4!1t9Mo?`vN1V1!hm7 zbAHz77Xbo`$}O<2e4@i^aDYv(Sinh2gyj;&A|CbR4_N6C62;)3)=Km&X ztmxWWFOa*K{FNaPjsq0l&O(P`Ix<&TfELKCOf!lpPqfx@my*fj0?ql}BJZJxThvG( z;Zwu#g@EYKCg8%T0Eqe?9&9C24B>=9ftS<>U&HTRQ`UzrOrzLS5LQ1>evsdI3ZD2 zsh*4ilSS_x&u6~JnoZJ*dft}$N!iFeCH-geU1Qi<Y?N=}D|P zOY(R^Cs8a-_6&g~dD4If2MCwHGEKYrylUKT0yAl1%mT;Kt5H50h$-EtOnCd2=+B=KU{dI?7bY$Tz|U?I}9K+;YulzQsVKBQ|mX z57njFDI*@DKLA^O?=Bte$R$w1`OggNM17zbn(3wday)IV0E83#3n~Dq+k+^X{(~>l z?s|RSm0yPwdE%XKHYlylD9t(^)|=4*VE{V|QaI~hkUkU2yr(u>BODd=mmQyU!P$-L zt5*b^=2l_TAek8YaUiD!D(_pFk>4z z0?s9D)Eb)(zuR6T43&A6w(n33&eb)H=w%NU$z-qb923a_#GyMBC1QmF8ZivK8;*d! zBc1|b4ZP^byji>?>>ydj5V~Yc3N~fSBkqArC!-0eve|%lSk_s_2;cm7nqGkQ2C*r$>*nbsoNl8O z(<}v)Woz>nsjCKpl>f>Aq&k%JE?=ViAjj&csTbdvKM50lcl@NUy|XDr0LR>%{zZa< zd^@OSMKKG8&n?BQLIHT?)r6v?4MT8mygp0!T2iA9wE%R<-g{`b>7DvasC9GtdnhIf zQv-`K7devLiJD$3^a42pQ*0vWj@EO47u6lQr`R@m8bj!N0VD#4Rl`D8uS5qkP1k^U zlUqeTIpBeWA{S@KM&zE8$>kIk!U(U`_59B1&qJ=TJkdI9YjR*x0!{n5LIp5q2wses7SyXLvxdQ!tcYy=Fr4D0zp zpiK9~|KR@6n|0&n-ozf>oTE)rlcCmTXb2j_tKJ3-2G{e~d2yLQIt6NNY17(o4Bi4o zm_c~cs)7z3+o`W_Xifx$uRv-h{d;nF%&v$Ag^!u9Y+G$}(K8UdaijM`wMHjX3$+6- zZGfgxeW$)Bt; z&;|a`#I>(XnDalksuu=d={nbHDZ*}u@204rP5#|6e zv^}4|5Mf41RBv_+UsS|eE|^TNOHZ@Xr# ztV;3JuqnNZ60x#8jcu^$K0tJh^cx%Z&0D0lZ1wEEjai{&ikcZBVoyp#b$tD21@|+p z%0}w=L87!Q&}sj+d95Am15)5Z0o}F|1APwp0n?}8?0YbfqXNw0XeOYmLw-hWjr*4@ zqft5(?Z4Z1l6@H<$1|p(KUTaHm zi1@cPbrs0!tV<8ySo(a?QoC)*V%cjB)8R~5^o9kzDDdwg`5v$ul;iI(_ZM+0% zeE27*`oqUX%|YpY^nk<=wIX8pOBQ)u)cnH%|y}DnSq7WT)>!rC@7k7uxid8_8=knhUstkRZ$UOc+tf!VF|PEd_-`?gfq^?)&8( z?7Fp|Rg#lyGuVWrd0Oz|A)w{Hy`dg@yC|9=*v4rU{y@v}({qIFSZlNuk%4SUk_3;! zu-}l(vFto#)!nz1IA{~(?9!<-Am3r!TK>Qg34;d(-0B78PrAcVP|jL0W&Dqx0ZfEa z-KvxLN|z}Wk+sk%V*9*#ZD?E%Fs z@vw6K=VA-^JrmqjNF*$o1QtEgfu|xMam;es1?i^ z2GEvig&Im`8pcgl+GkAegjLj5NTasJa&iuY$SxvIqrR@K7oL#^8R`mR3;4oUh@rlO zP3x{R&w(r-YLT}h4>%xz5j-TgSQnVTIM3u0|DV!Z$)BXn3#7+D$E+mVP;68qb2A`^ z=d*!qc`-`nGtkLJ!iy;CvEW|(YEk$fhTggv&lrAiR;flv4FWhWfff}HPE;Pg@RNuy z1iri1vck;e_E&Latd2%JJuwKIrUIxKR-)-DV-&iZU zEirkpopc@`NNvVjS8M$|7_&D*pllYF4F53lgnuC<0*rhK5h5P@c;SVf^&$$1Xqltl zi?~5f<+Lpxlx@$dk6K_}2iAr~{3y9tA=frO|wrhW`bJ;wNhi1^p(wE`qiqXvPu z5Iv-Sc$l9f5$$O@RBw{Z<%0=%NGMx@^%1my^2uG_$lGAtjcPlEJP z5yjrSA~1iGFJ%IY{qli1{O#{vkq&?!%&~rv>Xf!{e<8qjYywr0v;cubcErk8@}VQ@ zU%^6ReEzsYH!&A^l86*B^h9n|wqX#)#2E;a^b1!WeCQG_8HWknwjmf)dZ(k|m7{~e zE(5B3yducwK84Z&v#9M!etGw@A;L+$5fZ?9I0VksAqM0R9ZP5wjj&MUIlx26)<#_1 zmq}sl&=i3{ul=?n=jY8Q=g;U6m=`bb?v_p&1E)UVWW6k}BH-Lefm{##F?8q{B39Nc z!hb{064(xP)lKY!aN#Ja9DcUn6wy5v`NC9*>?KDrzt~MgM4D)!C)76{p&1ai;m%Dn zkUW)xJM_Fu1O-EwSP+x5F@cCZy!p_fX}*MNB+N=QUDujk{J+E4|AXjLN(vqd$z>?E zu@%5QNx=gG!(S3TKvwnykhf*3LO<~AQB{a!Gzxp(a$dLegw$ZB+7JrRZ2q+&2Mfh0 z=(qzx72^GT$_9c6r5titJ5lUb3QrfGIK{jtDX>gPk^fU@Rq$ER+tf)i)VSe`DMLxpEcBshkFvj=PEx~n*2t|fEnP>5%l68Y} zh_{~8Em|DWO1uw|R)_%%4*&Qb)1hR#qoi6@ye`;OadqEQTLxZs1_fDC&G^BY`~(@z zXxw-H-$xDw?yvHR1M4k-H!<@h7wjj%Gv;0x{@&n-uhi|P6EVP-zdmf4_1SvP)H=LAmrQ2g}*mEo`{4s z8n4f*bo&6~+}h|fX;WK42T0J0)!4 zFmE-+3~0FD+g@UmudH9`wM>G2p@j2v%{jsA-}^q)YJ^Tv{QL(#vrccCXEIbT^ZAj) z7E|FMxNk(N1f{h0Cdrz1N{t!G0{W1LqUeY-+~S3~u9b5VgAS7FtCN5q_1@nfe-aP( znU>BM1W7@>jb?PU1Kvh?fG8KnVpd8Uymjk8{S>~&x1#+1;p6QGKI{Jd@qN!(a#Od* zZJy;N*A5m5yseeW=<|CT^6Pi<6ski!b{E@RP!+F2&ghH9SMSJ>h$6Ns&)sxhi|7T) z2tt|OKOL^yQar9i2Bol7hLTMW+9jlZyI}${GF_7m*wa=)AR>bY|X)!{wb6Tt6X<)PTARQTT5 zG-kshY^Z+Idy=0orRpk#{a(+aFsCs!{h7g|p_ zM*1tj-w_4}mvbNw_XZ#LKM`v$jo^YP=VfAm4Y8NsQmDC0TJ(`@R=*Tj>J7YF^}5(pWQ$OclE z$kQ{*dVF!Xm$qsb6)Y(bI1{eC@XS!->jAQhW~Z?Zmxl?MMIFXpC|$B9NL;#o%^lqc z$JP#%s3HF3FKd{jry4aWczor=f@MQ(G;Vz0gU0CSe)h?Lu(oVM7d04at?3kV435(T zZ15&OuGM`RZj+916$lbp-3a}~a3h9!{6TqZK%9ox;P2^MJGOI!uZ`TR;uQi1nx3Gr z{?!0NpE>1lWAc%PKRMB6ELDbCj4HgEGO#2oUb7REN#qSp;&fXGBrr~&zRvC#oJBRF zmZrl$3DukvS$T(j?4JPwo5jAz$V;fq_-N z3tAuQUloc&kA?RXRjd`SBD%E-QIx9TajFWOl>};o(RI^?ZZq}}nr}b#xG$<&((F3U25+&$Az81D<8P2(SWL!_kOs5O}V)qfOT z^k|aumX_yXrspmp3@}&D(j=zGRyoS zvS!<7=g^z`+*OMUz!3Z!ZVfZp-q&+IPu-~ABB5guRsN#E)$XnyY*f$xQ;4=Gt*&wR zH7DzG&8hsbFDik58gzi+_dkZe$ANj#VcNoV?8HkhCiCFSm2hm}tI|zfWA5a=yd{1l zx7A?}unCQebDi1)AEDvfsy5u~)3{ipDRG-sl0W(XnHPkshTo`jR``JM%M9O#&rqO+ zwf@NFCqK+So`*ezNOaUVSS0mQ2uu`n_3f)WUG*P#>CLK`7-|J$bGwY~)K&CFKzO3# z!~ThCU%h8qv-`2*c8oqW)z)Xo@FUlY#im@ zQq>g~18otp>pMl`prl>#d^zT!5-!&u)KyX$&IdN{v;h_Q8W+2 z?MdSHB!2DxTNbXYr=YoIDnch>`EY( z%X9KW4jZQE)4!bxzP2fwZ5z70f384c9W@|oQX-tv3F5HI8~S=G-?SJ?gxo9`N~{yb znu@K)e>jm)^MqtYXhAqd#0*OI`&U0>Rv&ygKaDX&XaOcV<#~@w&Yz%L*z@$&1&6`7 zP|*f;IM2M^tFr4~k~EcL&C?be(BKBh+FMTM--8nFMtXLT>9I37^M64%dOoQNX#R04 zIhd)$iR$CDx==?BaTTA?Mflm%W8{Fb_?c7kwnBMRHm*Ze!M6$kp80LnA1yWur^-aM zTEFSzP@Vo=-lC!5da1SJ47&z*8YZm%3ziEsbqWu<4IaO8bSUj&b#gxtU;~H1_LO_I zk}rDq96Rg<-j=fQlIWrUD0R@S~&3^SDs@YD>xP5SpJ<-Ez{8R?p4}S z3FO|Pm!GDGehpJZS7sf2k0G}rW5rxK-e&Gbva7b|nVIuC?Ck)K<<*ks35X69YFkvS zsInxU-Z9nSiI>TOjN2|I&wr2OKX7#j5fOQ+7k(#v;gjRPp!`gjq-cGdia~b<{>EKY zBlH%;Y;&pAZa`j`u{`W28nRoVZPSs21ajCHv);16qm+6@P1SFg4ts%vIx^X0#J%c~ zo9&ZH$*TeT+3dHLFKjb5n`P92rM2ht>w}#p-vtAyQ+keUL@MY;9HV(eQ!@#cwjEHWwH~Snys)GFn*z=AW=n&-LDYo|twcdhC-5#7g}mwU1TwtN3^GQooOd*1sTs zy-Y&Vz(=nWS1_@ZTl43~0`)%UbrZY!3##1gA0O8F(j+T3HBeK%wsrlYkV=y5`d9ep zxZ0<|M;E?44$Of>5dEY2`g-1<_I9m$aX!j+=bJMafu9Pf^tI zI7n(lpt5*+)L_(BP+^7pos37St6nogJ1llpf*;iF{P$1h=?KqIp>Lu-u8ZPHHFVe! zp!FCZm1y*j>gPM%%qg8^CO8+xxv|2za#%Y3#EDmk2b92d_R#8!?{yR?keckIA}C56 zd(erQF7Ubf`$^t8(_5Af`GblrJjWEOc-VZ~Q5;)?PK(`6VnTIO=Wrd&HsQx1WaO!s zuYkgR6a;MSJRDoRbl@R@V-*XO(b#}Qvq5pK3T!PL`wD6pBdjtmjB?no1_>J~)y z;^`)>QJnQZilXvv%_P5~qR%RbFGR;<8uAt5HOXOQq2dSVulv_z@lw)ldGu(KQUvWQqWghwXkh?d**d5`=p zpx~xGTnQV&Ox||_A7yC|hFt9f`RF*wU_P0j$^IX+td7)Na0jhu5u`>Zi@FtJA<&7tnaxfqMfN-xgcdTCE42JW_c>^8bLX2Ji967;Bxhx$D_p|^N3^7LglwIoqX4XI$u&hbIo>e}n&Kf@;) ztviPvAWRAf4}3h;vwHBd?on&&{}E|LuMfAkW{U<+gTxl6*IuiCm+})6nIw$rQts=P z?e-0ADgcDIk(9nugBM&TLC-OSwrR?cg+T7rx!R=6MPwIhfaa3ozTA`}r724~Qh%4H_HuWK55PPe;iyiunW z8O4)FA@ z?t_@b9W#>+D3YY@wqwD!y`KL}Uowt$NP+Nm8m>75q2J0e%muMVd3@%2c^NSJ2}{@EjN^cz1>^c<@`pt}=~x#+AX+T(YC4G-?>?!yos zQ?5Omk*G+fU}1qw^!FR|jO<27En~YaGvo1ae}+0G)%fumoVY!pik+_!mVbFH(YMsl zq92>M*6L^X7@v7OJ8yT{VfEfId$H*&dqZHlkgodN635=NP&v0y>99-`^+c%nV0H?F z`Y&tSj=B?uoyD~dFk=BZ9#jG-Y=#xcI|c{~cyp7lgLnJ{D<_-yFW#cb&cFjyeTDIk6} z1LZ70baM+8{d>4H=Wy~$Hu|q_@Y)XiQSQs=%@m| zYYV*g280q}2~5N$$~;K&-;W$Fw)U%-6^l?#=x4rs{|JrTf{9)K(euiqAWjMC zT;{t4Tl^O!iYhmAI?#F~)JAbxOMkj(YvI-d)JlQJC@kWJIi0w6)8O)fv}B(5DS&_Q zU`XpK|6M-}NCVBJ7r0#d@uF%u#VDQZ&0oa^$p8)Czps1iG*8_x=lGil$gN~W_Ipsc zxWCYH^#fDII5G%Ko@VKUhT4aZ&pg~N$f}<02_evLYm{|$yl6T4;e2xgk-2!jnRd+a zK2egoUcwt%EZ)|+SSK>Q(+kt5brO&t^gBg{^>X+i)kd zNA|4z$8oMWOr#i>%`r=oyk;7KGYce8S1HO5%X$x^yZy_R!~8ZnOT+!4(>dGWDofahpHJNMZuSvz zGJ5AY$lIO#vx-Z|&Ps^5IYa+3Fna2>>}B7;)eS;czDQtsLEW*5j@QB+;SMMF_G%uh zTgIvO(r<3i(0rgc$++48+m!jqkduSS;!5*UFFN{sDH&cN|snG6q>##Cv%ZA9gWC`JbSpdz#U- zy|5C(W~A%cZ=}so3SRw=s)%{BbHV`V+i|^Fh}(6)xQE%L2Og<{JV{ffFSTT%s|O(? zUTg@>JpakXr>rfAYy2@g-Sq*$pI&NavE{z>gq%%T89Dyt_1_=Of(MCXuXk>@3CB#64zl;t-NoZm7dv0mW=*brIJ0!PYM{s=P)KAl^tY$`E%RdbXcgm-Gnv5N9PCs) z@}2)0n&v7Ezf#YtwRQ727%V|Q_uW!2{9u$+@z+z=V5j9RZa-bD6eJyQR)Dh-20})z zm{tAd30>LkWClM3kfGCV>Qj$q<{WIsNx|HQqOotA1P#6v`t996~WA$1FPY7UBc3(0o2BhwHrbhZaN*}BN=))zOLa3Jr`QGumtqUj# zqpa(ekA%Gz;Va)iqd#pvhj%Q0&fy3BeBcUeUsr}+NuCfs0L!eRPT=Ly(W_V)V?uh`~ zznY#O)vEZ8lh&F!!#tEZiVT}~eKGX@-yi#?V^?nIhVPz!oy=&IY9qheSF|?_ROCla zx}^#5|K3e)sF7~dDfz;HJ`5M!9@?v#Jz~|2_8-^Ta7&B+$LZv~oL>FcLiBQ)Bw^z# z-%RD|acZ7Gu0~0g%LptZ$e1w{0V{~#rBwvw`laP@P9QQcN2==VV$o*_%BVoIlrpt9{I{b8A8t+ z03I@h(nei7n*A$wHMJo!$kBS|mNi`FZ*!L6th}&WA{f@6w$E%gpZ31?)bTahpXo6{ zqNiOx_9DW>dpDymn3^R&|5RAVMa$K$&uGWki9jMAq3zK_Oaf+s9nb4R82o%Wy8LVd}xgZ{zY^PDQ>;*h;-u3LN z$hPn5mz1u%I^<&icKgcCe~X!N_EHI%KJnOz}Gdlw}{e_hU+oq zsQT`>gSC-Bu;u{(xvhw6JH6?6XRcPA!K|GY<-#p(JEA&iI zZ9hvo@2|r^eRu=hOJJ_we6Ir|f6rL_u#>1fDFNK<^n8>ErVr`%ad|It_W~i=V6Q;ft|~5k!xHu z%iArFFzoZJE9DFvbZ3ksiN&9M53 zqJEmBQ9Oe8)3l8KTopazL7@3iGMaR0WeBkOZDcpn#ly>kj^M7&Z#W1U#}E05I7lS0 z5X#{GwLD`1Hw+9}#Dpo?7hejlm;M5Ia#}IG-7+BHRz_jckQbnDZ!z`U#%n_G`G&?jSnWn74cumV;}5M>pAJ zklMwts!-J`l)CKXjObKC!u&>*1GFZ!>=D^p2zJYMA;3ddXVh^;U6G+^4@H$xU!CfT zt~YhT3**7717NIdathqY@ev>bdUFHc&BHZep&N}iQ(H9*(7qlR0roHQFNJ^i8G$O` zw}AC}tY7rYNAvO6V|cFlouZtk)>hD`Xv~5!8D5 zH5!OODC6^YUGT^GrVU`}fk8KihDWS1o50`V#Q5&ffQ%{xuoYVJ*aEmaZ1y`6V0P3& z=~LEq(&3zfpP1Er5mryaa=Z~mk1{^+b^3#)WVsPOQ=o3*p1bl3pNQtL4di}o8X zK7oerasX*U?ileXZ}g29GUa(*_Akd;rT-%^u7KM1l)Xyj6m{|Bf*8)wNz6Smj8!E| z-agn3(-^b7%2cwSIbCBlT4(}aHVVlXQQ6@V-cbJS)#2Jny^SOi*fqDbpof|<^6T^L z#bPsGw_$UYNB7*TSqRV_|Ir^poV?SqwaR*{eD&d|0fI9^rOT2MP#t!WS9ihwhQq&{ z0u7)HmKWwEL`QkS!V6}bOGvpOSwZ?2A7J(|&ZM6|3WF(W!Gd?r8ZtP-wFRtAkUdyn z2>ZJ~G+N0O+j7oUmZC236w7ZNorpgeF*1<8%v+^P(@lgL>n0V89KeF*kcP{`OUv7k z`4pXdn<-1QP=OjuLMQ1rd8L+X)s=d07IprH5YHhlw4rV$QXj@`L#ty(>8Pxcnwy_K ziCJ~@Mj+-2zh+_e&p;Wy6DwSt%zqyX&fS58qpF`e{xxfeaHcd`Hi7v}`j=|PZc`#= zwo>ui_WM3zgv3Q8Pt_N}?9aOD-P}7)lLm!ym=I{PshQ^tzxbC9%OgPmwgV}piSBuA zp+{;c@E?`%Xa5y%rC9vV-?Z9EKNPsf!yrsWfJ1K_`eG+nux$L!_B1e1mxBl{f*xlyzs*8=Czz^+&&$Kp@NGS2b-LqFWQOF`fL{K z;gNh?;0{*M`{2{3M_%U&k;z`^yp*?Sa>b{~Qh8pTBp$fS;ew}`w5!gB?!oP5xdRY+ zTXLWw$f<#X)r#KTi!h9~-Koj+sr>@OxH zHg8_!^O*KsPpaBW%pm^RyZe8GckyyDPTLA9ENU)j+tUut_pNz$o3$~Mr)e@9P9dWW z8KG++JU|rHkTxbqH&*YcmqV{QK%4!v=PArS=WdJETV$GaPT3{BH_=0#vy>nsFA3mZ zn3!GILGX2FQ+j}*Th}?6CiWYY9_3vtO2K|fGEE+LW-8v3xS{gH4Tr2_@K`9&jCtY{ z++VO20uB$H-L({Q({qCdYx@hMpX)-?8>UTPb2psYg;ER5&n!=JDmRpFNr{bg-`ume zh`^?W((%4Sjk=L>@Qo#F^UEZvPTPs2$0UswwP;Um}v`Q+ewN zhoK-x$Z5nTWjlw40YYo6&F{nme;=}T=RhLy#b;Nlu9VAqg&?r08oDR*S9$4!CyOe? zq#Bge(M|tvJNm1$I?2+c4{(s>&zWP3O_C=&a7@@pe|D?C$$LfIbfB-03H6<*%{ur0 z$iX7rUm@Z+HK1~;N2l*m!%T0Kq7fklIHGXdd&Z7Hd;`RrL7-$GMfyaa6A0-m1UEy; z+uJUM1x#C|XQcuw-g%wO&FM)4{GcM}Xf}BAM$!kd2CYz^gl7_nah)Yo56_pwJD1Dm zfRm+QC=IKO!kGF(5Q#IE+heem-&{+JVLCA!HX!|mj!{KG>D4^DkI7n-lXwaZEQE5` z)KeRVyXOWO!;5WY{eN0PZ$h7YM}-I#9&&^HW4~=#Ic3>J2cpOHz>)ndPO81F`I=B3 zQ;Cf#>-b1?3BqB__*3yCub1oOJ!X~qvnqbw;gF*u|1aD(xUCgRmIf;Y%`*D6lacsG zP7lL@N@QRJV{71e6|^Cr3u3qOHnTVSVz_nN^Z0H#?kuwX_+!b29gf^?p zF~y-ob^5ce@gRY*9x#5<^-n32cm#I6BOeAy1RL!`04URDk5}n05z8*($6>}z#rSlno1x!B@og4UpG^9(mO{$?QJJ)MqmN5fB=Sxg!@Mn zsls4}e6IO5cuxzzgo9N(WITo$R&58n|pqKJ-AmJ<0PVv z1cW9-%;KLh(KVp$z$O%8>6w+958i$KOta?*Rp!}qkEv44#%6d<+S z=zWge*RyE5@sG&41SUXU{pkyAvh4fw9YMlYd`>Q3D2ynE)tbmE5dqYhu{7`g;65Jf^i9z|V-co(T(Np;Rg;!I zAI#yLsEBD;N+IWDU+tWZl`Zd17=lvU(};S#00%k>>exH5+WalYWf8w=9*|eSmsQ)- zsX&-#y*Ke58G%o%g%?DSC0|jLnzE4XM6TCZwFKIYC8AcI<^CHMiM%+NUv4Q zE0F?>RZ3k{iGV6m*q2Efa{RC#7MgMiQc~IHhJL2PYPIPwuB7l7rfmt?!NKP~3fUwIyAV`Q0 zt2P?|KUrP9bP8;9YXA`NxBmb-&?xtYT8_-6LPaz=%)Gk^PX8pDB|-t=?lN$9v?P1%OzzH@OZy3Oljv1g#}%3dCk0(reilLL(oJN~;62Y+sAV5+#|+-fGarlOgSZ^L} zP9zYys#zHc3=&EE%N$}tG?<4xp2JZ!D zKkB=uhGTYKQ+tUAVG`lPMbLx*>93zKJ_d_qpv$<-k{;b$g#raN^u7gZpeDw1=Sq+&_kKkOq33rz3Bulc|zm`?0qm5 zf}mKADz@gmJcPz-`^_TO`QQkmNlPK2{t?kMyqNnY6oc}eH8xirgd+Qy%jC6Tcj_%b zhjK7J0)gS4-#nez+=>@QF8%avJxQXNxs&5Uu4UGtbUGxWc6T_C5q%3I3T!k#kyWeY?Dcnd6Q+kdTl>Z1Qcf|1cSK!q?>ALoji;jm-_|bCGO9e5e~sR^6V9Arb!fX6g(2R z`O{oj$sflkI+h?Ah?@!}`D;-c90(QN#K8^|Va9R_C6UsMes2-uDvQXx zfO$J7narXq4WgE|=@bmlPE{$6vcaKkr2vLw%WxXsB!tJ7llL8>m``toFi-vgvQ&sV z%_?haZD_o|0?}@)2h_o(0JeLJLfWHtGk717TBA!Xs|>DHpn|^`6nays#kenw$KW?J zp?3hJ&*0z(0@o6at^)QNEpaVvp(}TocG{*tCkf=dIdD&f!8m|b#TKGAoC?@mWGsfe zS{TUm0OOz#W2Ns(Q|FRYiFPq{^dS3BxZP{ys2u{B&Jo3TBgqCHrs}~};1~GdTdmOw zqZ-Vf^N?!rzoc{txbgimIzWX2GjUQjZ$KOil)aX>a?rSjM#!8~FP!Q43G-ac7Z*En ze@?#?AS`e7-yH)R2SjexDK#%Aka9Pax^g3{d-ovmpyGZ%g0=Wx8pFT~tP#959nEY) zv%yQ+?0;{~G*QpwK>IK7X+#ARIqCH_c;h5s4ct{bhpQ;+y{5%oiWNsCgO~IX+BZBGGdh|YKN*kCj&3_V~9lp`FrM~!3%O|dN+j4R_e;0t{(Md!}^n?-V+-eXz^gs zH}FO4??70=mV|?lfiq>}4*zn1C*D92}d=v0WC$lL7 z!hS4dMVyAiCqv;_C^&^t6Rv_LF*UhdD(+_em2xW|Y?^yy45nCu{^MtGGsF_xr!v5w4>af0;RkE18CFDozgxXwerq-lU^#$~!U&atCx{u;} zigB({jM}k4v@f)P2`-94+5oGmSj$R+@TEE>0;+U^4XsgwB$rOFq1mRGl11;|?Qs$j zh-rPjcDTwPfLMB6(i!r~NCYDbIb7xk=#kPOin$q|sBH&laTIP=b!wOg*4!>1-IGPg1%ZGyS<#fj<4eGM!G$@)r_wr?Dm2; ze=e5cR(^AdzIF_O4e|2;^#FhyDu$BcqZx+S9juv#ZHlvEzx-Uvza2G^2kY`9u>Ij1 zZgRn*0e9?r4LEeO{~EBXHv{W{_kTw>1_okVN{s&>AjsofOE0=|JvP+(3(H@8_emw? z@6U-L*G8UD1b5|my_i#LvrM(*wb;^f?a$R-^#5MG3Yo2wTYPQAG-E%J06=v>7`k@K z^ZH}ny3#4isLDTjZ+mR;i=;v`-$y_p%LL2Pv;hj zX}R$aw^Td}xK0=XFBw*%47qF3!@02l@uv~kr6++;a@Vi?)~r+kUHjBqH}u;l^GDL? zw7qaUV~Ka^7DL`XBfaL$W8k*cRaf)qezVJWS2=>Umy+#5v2)6IVVNLJJ*G2UL{bP= zLC1c6vsWkWL!m&ug0eq|tUQC81J+(X6Eo?K`j>d=Z)%d5Zdj!B6Tm_EtKMaE$mWAX z;l?<3MdJ3?kimx!9^H;mGh3eacd{%ol1LJxQOv!}oZL1VF>6IN5|DQ2+8CP+$_~En zxqevHkZBuT{%s9qs?izcdrjs=J~OpI0pq+I<-}<6iRt(E+v$5hI~QI)c&_%CXiEx(4eN6mY)dDj}C!I0?Y+l=g=nlBiLQEyYos4K9azcOO1OExFM}XmI(>jh~ z<~7UoCu@GjF5Y*h9}R7%c)$E{x>t1nRTh%pj`>wW)Hs`gn+iX6Z8K2X7`cOKv#}mq zu}Z;7n)%!CTSHZm&NX)w1}4>@WaK1-^xN*9{y$w664$g{?l23K%!l6yg}?l4{ZMqu z#pjqMdV@%$C{a94`MG_*k~&lX?x^4tvrhwcN5I1SklzcD4%!;{e9n|bUoPL9{BMvyl24|^S{C0z zIEDy%Ew_4_&36@vUU$)hFa2(~zPlZfyoFh2nB9oY>sV{ks3RBZF3&;(8J(+~_$U|g zeGx_bP}n(N?gUNie$H%5K&* zBj{+~gJYw+3sd^9CIKtcYTn3*+$BfFW~Dv#)%;^RT>gKj$*HaTyMdSF$-7+UTc2)q z-|Q+hSjVuaw-x*k3x83OwK((XgX}+52A0Mx;JxIJJ#!^P|5uCQ5vacVi^2= zr`S4u*igtsV6QCUXH$RUk&NRNXo*OUD%s~$TjIvI@SL=fN%oyYL!Efoz;0fqk3z$} zlyheTPV`)10!SI=MqIl6)9)@%ZaktZ(|DWJeUWf`kIW0adp*KGaV%$%=Lr3G`GoCbj(*rcGYNCZ&aBhum{s$2AiU0Pl+9Pffh|?&Xd}tSc zPs_R`ot;|u{15Oph%^}|OcL0_emqE_Pm=xs`&N;Gf~e>^x!DtmsPv(fAn6Yb{$1!I zPf)Hfez-Ld4jTzLb#3PI_H}){icH-f;1y;^qo(MD)hN6`szXaiYp>~N}QqS2d!e8W&aDRY%kD7zwo3{&Xli830 zFpx3Z9POyz7OmRjnDgsXYN9uU$RXw4{t-ZJI&q&DF|r$9ij}tfd7FEWSt)Ul>ezex zM;_IE{_#-@Ft@`5+3^myKKAI+Y&FNK_)w?9KiOLL9tWvcoerH?kyVLH-*OSj$OFw; z3>KRVX+LjQE`I@QAY2MLy+s&rkW5ujeyw?@l~AkHx{`B#+4@GP;`n^o0pM?@pNQtkHr=E)7;=&$^dFW7ve(G$w?opHbvF}CsNRYPqs5ytr z;LcytJG1@zjnsXMslGh-KR}~LJVwRBq#41aA+pqbO4_+VD*Z z6sAY+Ni|O+(>LM0Z%nv3R;>Q?EDi4u`A$?U{)$;!%3*HB z+1&1$ds(ZXpb$?fj>_HHc5%SuTG;6%)aE8Dy|il1)JY4Mhk^&7L(VFSZ4sUgX3qI?p3hD}i~?F!6Kiy{-4;7Q>D|10Q+29Vd} z$snDd#_N-z0v)^~p#txW7@XTu!jICB+umZnyJZF{iQd ztgk3d=A_JvSCC`DLgo2BsuYBxk+i8silr34&hI28C_hq?lo#8G{fi<#d{&$KF33d- zqgp4x$lVw|kaYelD@|6KR!K)iuI~6k_g_fpN_Qz0)$i>CCaJdgl=jj4DV5Z5qz?&v z_{_g~wYjIehIQ)zbjWr6OI0*n5h zPrYXDW`hkA3jm_ve_zCk{fLgh1vO#y{rsXy@i7@N)0ePG?Ovt_8l0T}_utDAhctSrEBh{2A=-89*(bq(&`Kfx zoi#*?ybm5=-=BkrT5H$`Cnf536;eORP#4RC?PE|~;_?K|1&4fMew+lS#hHPO-(xICh5(Q=DPr{dBR8{$#T0@t-1JSC&&56MC}(lvo@yqS zz5IgFnbw`d`Ek705QB^iT|0%htAF_QSDnH`oQoxy)IbyYrLj6jPHX+)K3RZRXoxYo zTXg5cg`wVmK1|tVBYLCo!$dvQC$}WuWnHtYxs#FG_*2|>?q7#%a{h{V_T8d25urkf zV9oF=#1P-c_YyTh@M$oCXzcn@cR5PDe;Ado-TJ^7h)YLW7R?nfHBXf>QqyVj^IsPQYQdz@Pj||zkTlPCY z)zL}CH(`GjpUeLlqiHDTsE@rq44I|R^ItH2UVZ&GJ-W?U&ivRXQSA?nQr_}EC^NBb zbuI8EMfO#{;ccXO$zj97K7v!2@h7 z1hE*}0mz$d#bN6%^Ab3WM36vXnEIX3+hT*#+9oDB~}T3?p4Eu&;%ZdO?FLH z`ZKU)v-!81opTzb*)%LJN_B+0<$A;EpiVj&lC(*}W}*H7hb|e_b_Q)9o{nZzw;Ke( z(I^bGY3d)_PyO%7_7Ce^Jc!f5>2s#fX(Bor0a6*%5_4`Zte=)2agS!4T8R4KIH&gZdCpG<+ANG?>`uK(!P?Jyn%we4&sZswr@dye zIO8Qx+(zanUm58=f<_}a*o`K)vRjAn$yY6fDp-2yvA7-;u(JQx7bq;7^|94P+AS=> zJ25xY$Kv9@cbp=pqd&^->09Cr7Ytbc0|i0Q)*xW5>`jf%(J!hu+u01(%$6Jd#Jx$% ztYvHus=WGwqb6^Rx{622u-VI%CQl7+Cx;zM5)isF8O^+Q)8~C}53aoY@~S(tQyyXg zB961QO40As=QF`kTlIgpZmF{Ny_1|Zwy)ol*Wb9O)gL|ZW|mBT`3b`x6=Nznx=X!l zPb)9?={oY77BfYiNdbk|GM(Z8kNm(Au~}%=lz8=l#Zb)Wt(S{AU*1GyNGrz-F@1hC zp0jU!*dFp&7vh9bjDMdub)kd5JiWdj=@C zw~_vRJ>OhX2zye=5Eg=oDD=Xb#r7O2Vp`O@%j6yZu;yl#H=FYK?{NRiK{M@p@T6Z@ z`>w_W4xD86v3hRH*2+s)=g#wo^+<{iiR*DZAoz!o{FQ&JEz(G}(@?-G1lm-5x25=V z!Ub@aJ!o;w$5~-Ae$1SM*ma%qFj*WK@l3V*dhAT_I%5~CWyRXP<@L#lI8wN>I|95$ zBoaJo_{#rz_p&OvRAf+}ado-0unq@GT-9tAUJ z5z*M+0+dnQaMYOm}xp`)@d?w;atYFniI;*b2f^{?fU$Kq09 zbT12OospM>FPFytYRhr{67~ci&{E+s?0%`^vz2y`B^_jVO4jJ0_H?56_1^!kNAD$& zNUkT2|Mx!rqADbveOrC~x%iFlmC{Z7!KUTs)M>NAD)ehmo(|rO zvvsxF(>^arO&ZeHcB6dsA;)c%2mjR$_-%THASFQ#?#eA|PVBMI)2|xC*94FD;%{_7 z`|Ds9mZ~HzJ=U0q&fw_x50Ae3wLdSh_WgEKTWFd*9n7c{X{ynAf=171R!Iig1Phif zHUGpPxyDMW-0i%(PhV%9kSjDhgUyLD%OS{y9oIvOdL=+%s36PY=xK8L`S)0^<@@kieO zeI?K4f=ir4`=Ff(6>yO)B(nLh!Cz1QQET=rpHu7ce z6578`sD3Y~!f?mm1?I_|vWs8e{rg($?mu_1i%61SKD7_N72=C+`fG_jd$lJt3~DCy zjiz)Y$!d37U0yK%pie$_0^Y-XCew=>Ndgo0SuLO571l4o_DCis8QdE-92-DFCgl0$ zTahpPN$YZcK;GR=46rJ{n;Cq?eAYa3IA4Rj9*|958iB2pe?6r88bk#izA#b>=&w39 zH~le8@j{>L<$}pOQ2zJE*|opZhGY9W?gt*}t4xd8YhgL9$(Tu3dAM&gHB72?<6Ri4 z?t5dynqArn-oXNmye53<=^@pezF8E^Hco@{5&Sqk63>K0dfs0fnZK0vnD}4E#|pib zYD31>(~f)7B;v)yZhU&f2TSbq1=hb0?Dx+H9gRJ2a~J8ee!WAJiO$7pbhvqyK5vc| zMeP3eFfCUXh>fN*sNJJ<0541+kz->tyUf&&#SKyFf#1^7;mz(c{L0IT{|&YJBkG~- zN`B>$jgqc+ei4QiXGX{&BbOaE(*GUW%xXP?Uy^$y3l7;!yVZUk44jS;iM+cVllOgf z4x0ASN^c+l1!H3rzswk^dw>0P-*7~kQ`gDlS6*D&6QT6i)u4v=_y6-@oldu$;LEX7 zc7$@7a~2e*7?_>PRBX4jPM`k7v(@Kd9lNAAp4wj;?il-d>WTqP^sUnKeVW!^^jFv> zYLky9<~^XJ3qQ^Cz6*@-#pt*L7UocBANzxODoq-W zen4kt-#TwQ9T-8Zz|TW#pRF6MMV-kdmE(>^l#H)Ie+D@)KFT95Cqw zzIB!z_*>!hLs;$1c@e6em8^!K9#+Pw>H(x0AHZ@)gB{!@Cpm+p{*q{!hE=7m=N)h< zis`#+L=C~%#UJD-PM?!vT`{H|J~fXM1yyY8tECsoN;WiUdnl9|iI>b_#_Mc=mj7pJ z9Z=K?MUQ8bpVN7}#s?GAQ-` z8HWvUKX^kid)H;*C4(bave4Bh2A1ToR4BAa=@?%~zSMY5-EIb1_5^mf$%dd13sTLk zvZ?F=#j)yPqGpvakLkWEROsg=%@isQberYSmA)2g(ja6nC6Kdh`~$Q<>)X+=4W{Js z$9EG-d?7{Bc`t#5PG%f^#{Adm^j^IY*@T~VMv>QuilR6TT|H|1vzA9y!D-@51z!!g zT~4EVlbS;>NSYJ_x;Sr(v&^3PHWQI?d*RupTftiPpCp!s3%O}s`jr9mU>U72**LGO zutOm`m<+emX!X9^zPkI{3nTQO_XvBIUs|`fwrP11|JF)&GFNOBdBQBC!7i{6(+n1{ zY?Z22ypMZ_%9HQ6st$?(v4*9*SIJ#@f$Y4aH2Dv0JLzu^lggtD9)Fyu=8BjSAn2 z1aacb>C$U%Qe3Ke%7a0l@$0=tCzgCRp%b$A4rFy>?4HHh<#PD>K>VlE%T^GV;5rVO z7J}L-f1jtt<18Q*C+@Sj&N(k$Ht%7BgVz$B-;Q~i@fBmE-U&l%^79}Q>zE)7hbie> z;$6M*wZgn!i_gqW-i4xOh68k;%k$v3qB^t4BPdq*Z9qU0A&ybHNA+e z0hE$GZpxBp26KkM46#7tG~)3d%E7#@rwnN4Cb0t?u=t;0;)1L(v!D^brz3F>W>0U_ zq8SexE^i_PFM!kYTyQ0O)wPd?%#I9aJ_*;rm>OSCt}Q;( zV(0 z0KP_#YgI4INo7{jE7asM*I|JSa85)gJzHd;nl~d2QiS?#n6E ztL%k#JD&v<69b_m{GOJsEL9$H;xP2t2Q$?*KLF$O z9WK`iEgH7!xZ4*P^{q|h8^N_J1jTPijhOGH4P%_7yHY^78{7@T(N1Kj_EUIjH; zR-6LiesDGv4~yQ3@!iZ85JCR`*vdRkyg?1FU?8&_SFG{dR?un+uNWWb)la(mSanf# zJQvnO{sYu9J?*=Qh;Lpt)Mutf(I37X?xfX(N!2N@?x=t8z@VYE73vZP+_4p*6i&@; z?fti(!}Un(=4-swqLDXXw>OAAEEkY*PnX;8|&xkwKx`P8=oO z>nT3JL6Lg6Bpwvy08`>Mv~4w8J-(2*Y61 z76pJ9<2Cyy{4%Ig}E&H5yV#lSN)X%`@?e zjCFx%OEP30F$dswMuc+>N@|C~yb=asO^SS$9%7q$QxKb*^eCL!D>yhmf~uDVihIvM zM$_QCT~UN#674!wBG5i~S2;$#Aim6Z9SEh>(kuJ_oA!rJgOCa#w{;%3F92F0JCkIu z$*T2NAEBBW2|fll?`Dc2uWwCRno#MrE5&{b!^}ry(gf=N*zMz^4s$Nk6&5h=*N6ID zhwdJ){clZmf_whH2GDOn|Dc|K^+}kw&gvvS7hIkhCb~QmnpRAV`kB4KIc>X6_Uo3Q z9YR@GyES1D1qz%$w2fL=n}TZA_&dxa=97the%slZ>g&VX$&M2*v5^9@Lh$sXUehEU z-gyb_F8QiJd%LlpkZ-K9?WPvX4JQGwdH_`z=3j^4^yj3uh9j8Jnw#*RWDh8c4$@I+ zk5P7F3Qf$#lG?5_@T^hAo7xx?PCDp^Up}>8DUTAdC(pie3MU$R&wY`O40E=rH<5mV zGTL|EJZ)5N_#)|T6ANcp80?*~8K34x11#fOh(|~2V-p(ys z8Jgsyjm4OlL;w>o4BGzR$0QA3?1QzG^bx4haT?bWTTYxsfFu)`HYn3u&O27+CB~Su zh*5(uy|%%^hal6kS{tsjaC-L#j5C_?wYrV+?O>f*vlz^VdaWSGX(d`Qx@w0Doq zlo|V>FAiuK;ZRg)i=;MI3kg9itxVDfOrxGT`@sfv$#q^CxT0!t%HKqQr9Df^Ky2L?9;g@94TNZEv> zfQCN+H3~0Fd`_IBK(M=oII%*%Ctl(>D@42fEmy=QMGUPVXTI5C*Y2_)$^38#Vh zjRNay2=*<4;s-;Fm^hyy`_H+AadR^Y zfB2=Dn*ISBlJ1>Am?lYKQoB2PV=Mvbf%lV~TKdaVp`ysVk{C5$q@$C;Ss=rUPby_$ z$5d9FytEmU1Zwfg^f#HtB;gnxoS5JsY7x_JzabGB|ItDxUNokBf1OY;5jL1RQEc_A z`JZ=kt&nlz-b2l2-XJB*=3roIB=Jg@3!$FCS}k_x0EF5=)rw1b2^3?gy5CO$|0^GU z&ecIpjjmw$DC8xj>` zstys>5(6)PUZRCu#`N7itgL$#p}OfL;We-s45?d{;6jBTe7 z;j48E_F(r!RARdUJnM5)OAghQS!)ZnHYMc3$I(z)ibE)g0@g-yanjOz%Q{S^g^YaY zvb_dKYIG=KH=~X*EFI36eQQtyXu#ybDI};!HV9p|-!>F9NL(rWIRxH}H*#iv2h_h= zD9=Vb=$nHC(F#V*a1sJru$OiEbBOc`5aE6a>_^Ay zS{rt7loC~Y5>du*za@)t31}@jcz$HLNClo1v^E{6gOf1xNXQ>a=%-z*9cQAFV~0v; z(Zz)3&Q4xG#dtOV4W)wL{)@rn)JAO(vosRCWYZN#2|UX&G-4~XcouuYd}!ANkQ$BK zyT(6RK!l+Uq4UI>jdf{+duw) zW>}<2QIpLS<ox#A<0>~OTtJeGRiRwNx5gvrCO}pSvln#Ws;2)LXqP%Vln5_ z7~kJ@{~o``?=Sx(5A!)(*ZX?Co=?GstPcE2Q;++ENt2(m7AjBw5 z;x49bdOOS(auzWYV@95^`Ir#`zoW1jf$mOiC8mxh-m$#7DDJIX4hAO>k>am8%{3N> z@DM(-^S$yZ4J|R*P6rdi`vA+%TelUalP~Ioir^ccj@b#x1X30e6Wb??>qR=P#!G)h zlbR+8lev&8U$ol-KHkcS8SIf?Zthy$hLGAVC*VpGsSwr$$%wS{YxMzrxs6b8Gu$af zu}bE+omEG=V5VIsdJ@|co2AL&dd$%R4u&8R>hScpNGORf8F}*=R3Fkb`zkUoBFzVH z{hb958ouqP&0BW}bMr$0t}53Y1ss`fYs)eUhU~4e8U;T|8SDr@v5X%)S%vd9usz|g zp-I^cvqu^a=-;Prf~T7_F$~tWGbwzEO`&XpM}4#?!BPWi4>D?g4qZ*JexeYBZ#-zl zKcK;QIV?G5{0DXK>j_tjRlwASaNY`~1P(A4NUazRWx1O)uOLvsVFr@p&*TLXB!DSz zt#zS@8fCCJ14*8OY!GRmRC8F zFEhe6Vy=CewZ7pH)jALwDdjLg-u=L#OVBtn9o3@BKqJ@Jgwizrgcv54-~@%)T{6r8 zND{4pz=vPP{!;Y|R>DqXSw&PzK3%tIr%)e=8%y79$GU!=ehTwylXZJlG#0t@`oh=qmviIw*XFw2aztXv4U0D2q7Odq`Z9 zMj=we5yc0ak4JD7CwQsWL(ZwaOO=5we@T8OBOAOzd<|^jmo7HhHA94a_`u656TNGC zvo=D>j(&7sC^Tq!H9uPS{?B11Yznv^kU!C-R`5=Yh;Gr#S`OG2I+$g*i|5E9to6N1 zC(d8H`fmF3D(j3u-&TmWL2=t{L)->^OPGyu$hIQuq!ev`Q=2ksJe(kT$>#kcdv8=a zCVZ;^Hoew|F}L}cT7)XstafUdId zZ`Q6FOf9&XQ~U$gLjD*%d|v-zd^&RomgUj~-`a_cnPA;Kr5&vgPtk4_Y})E-baYrS z0Wv#z$;;v(89NEqX}F)Y^O~KDzj7zf?Ym%;b*>TTFy zxT!Df>|w`}Zc;bpIMOem1E{0acx(`pfWfoq0+j(HM_>Q`!ORzpAE{!8GbE@P0K$-q z5*M1cHUqGH>n>!3Pu7>vu14Iam`pZ_wQi4;)d*ZgP2siAQITVf=q>I4ApYjhmZ<#S zsR|;UH}&}b*&-GOVZ`DiaCe+SCdB^Flq4aK-(1ce4=wz^^C!coo)lcJA_7qjW933B z*iZUF8{)xja5z|)7AZ)tz~R-TK7pFGWF6tIJ4EnKZm4)MoihdYF2+ta3tFp9Y|qe8`$D$XLzWdMbsI+)9W%R}Op9D;RP!DEVA9lK zlwB@8p@*7?MB0>2ni8)^2vPn!uq=iSaUKk4_5|X?7A!Tt`JGxr6XWI7{&JrsPLjSlT(+a<)<3&S*#i5k@sFlDesD9)r?s) z2LI@DK7gEb(hfBvJ5UiMq#tq4>Vx;>0<(*%-hhEbnEkHl#cItd+~kj_u2qg=qe<&m zjndC_wB}0Z)zX_#=>MR7e#JdKdc4G&VKIx7J+FX{)ie&*$`qdk%sRgtUzd^;vD$&$ zbx3aA$#xv&y+B~0szuEWOl8AUVpVJlp<+`4em-<8d&=uBlegH#w-r$~m?`S>E-zf}~ zXaZ6J{zWu=>S$_dtK)cLdKj@v&st~}l7Eo70vYaVdXF2oe;HFS-L)ZMD?)ZeN9!!h z=4oZCGT=CVeT37VOh;WD%H=N0vT}wjiU1G12f%Sl-@*Bu|CEB`X4%|~^-j6*WE3j- zRX4|K49$33ZYGxzMS%f4iuPf&wwpg3P2_IaBK|6Rdp02R>w!EYFii~2OF2^8O%xwC zxHtJeg~|4)l?mPoPVFI9w#a-cf)oGo zzp}xSIVanv=f0^z+hB?~NT&KBR!Sc?J(!jM%mp*2VTBSYPt{7 zSw?oOiLdw7mD9$B#48qepwpG2>;B;D!<+{uUWBtch{Qn8hD=%KVFUSUwdBK7|enkgPcUbE5Fk$X(47?_5-J`-wg{vsamH z%o6UX(Y*_wIsdYQ5Ok23w`+dv_1XQOdz>1q4cA&-^%3CCGX^eGgK_c=_K2Y`kn->?#fFw07HUggobSgYtfO;wU{39^4mTDDvAWTh zO0l_4H0Ugffz@My37@f)_1~ycc@H1RGwc0e532ZL73yEF%6kfC=aN5`X!gRWx0Kt5 zN(I-)?*q@|j6s0I&r>PBTGR$rrVXZosRBPW;*=nvv~R@!lb_yZL*f`X|0n=0DcX+l z`TWdq&Cx}n9DekS%@{XknAC^1H{DxzoL8?*4rT$RY(CubO^JpW0?qb}$cnvu{qXZ$ z{2g^lZhLT3`}^0H3$}xg=oFW0w@x_&G>XIJ3KkqQa`mggXvi&adbA3<=y&Lv{G}6$ z2h9Vh0PZBowX^&RlJH3m6WmT;n`*T;3CEWXEJoJ%dt;Ni&I-HaSK^e{-x?%SU*ban zCF!>9qYQU2R^;KZ&6(!EZVs@}eqvW6wm#{mHGmE2^zw$2GVC8E#R8nHh)rZ#;wi95 zxRke;qe)Mw7Ey3F888hJbU^eSUxbIZr~RMpNWG!py~uU$v%KN+bKINBV&WVqJ^~z} zBZb+m9Lq$m_kUP6qDh3#8<5s}NqlvRDYm;;>x4ZhF?zRP?0pT=m=Kri7?fh`!Qf=QK7l<^ zt$s=@#|cz;*6?xGFQEQ-|>|@!LpT%xPb{9Nx^woJ+`YcH_6sh--10Njt zHw$93leCcj<~2s?*UhyPQ*Tm{(!{9Fnu3C>VP~t)T$BAg+r(J5o9h{fHjB)DFpA=r zMO-tiK=uoYa=1riowwYrAag8vW!s6^Ny292Bq!EFYWwqyuA21!$~yMu+vS|(64N9j ztFkMMMTB+u#(~ENvU?51RIeOydh|f0$w7WIAb$Dq;}S<$1ss7$D8M05+gH@vjpQ?O zYm#9@bYFZO9>H}jy=i3|LVbftB1_^ra6D>edh#tJq!V zaPZn0CtnnO zlqec2%RK&t`=niuG%Ta7A;#p7V(SFIC~2Nan|ub>^vqE|l>y6nQT?7mfu`v%bFTNy z*{b_e5s~j^2)cTu`F}|d2-Ua-a4F91gmQHL_U>>C4Ti3E;f5&4#c#wo3^_mn54S`j zZc(?D604gd#f_pPzN=>m2P>`p9mU!_r1`h2IPRO{(q>2SjHo(swd8+LGNNfSVo7-C zdeQF+Ly7vk*B4qTBC;$0uYC|mH(rqC984neozAt6@2*oWJj1Eh1bWr0Nq>D$EOf$z ztM@BuL?y-#&kDAYaV}4y4JYUmrI?))U zGG^~YKfsDkvEbgRHQT~QYkzKy6@EUsM|zX`%3q)Q?AM21>uQFba4sV6J1J{j7Nh?E z%Lkca`ybq0$V$J%8=b=RDJ}}tbq>7OEMB)#9=>vTIC9t{WBb%Q>_C)hu!FU4w=1JD zTB9UvwFJ9hyRNr?_Cx#^e4mN~zt3prugBHuV@BRiPyLoimFyJ`_o~kQkShb<-w>~V zEY#yY-v}I*1=UK}qghRsu=5vyzmZ`U6SZ2B&%FDLEgHf}Zdxfl^<-+P=w)DL-cj0}Hg;6209Nv(`}c4(|C#x4 za@yu6QWQA^#5<7B#Ps|x9j49VLW4l(= z@5w;eDQiwuS}HBEJ=ZRH%_;%DJrAM;@K}!F-I<%L=U%sY62X+@QMw_d_gZS;%!k7n z;d7~pX(`%?^_^f`qw8id1Qntk+K7Yfz|}O z&K&M{S~5SyfDIBQeB^0VniEkU*IyJQ71Jp{o;*ZdX${I4v3hjnutE}HZ>Lq{3Cr$s z;?YAV!HjGVU`XL3*8cL6ZdZSlY`v7E*&j;HD7bS#JuI1mJ!TBDCRxAro$^dC95wr# z^+zUAP{En-u-2Yq)fWGikRDr}E^pi5#@<$}MsWZBA&GwI(J*tR<->bG5X}7SR8xC` z5-mj5@Wa0)E%U6*ass=V^+SUGgJt?E-1UX5ToZ-Fpo6P>wALYF4Gz%ZE*u)ZVtyMy z-)`z8C_SdzB%>zbpiK?n$-S`D_g5NnWS2V&rq{a-MFI}`;SqLG7d&EGeb~nxrCKMY zQ?h*ss*2^9aIjK_KJMZBKQ{hM1wGvD{*oe@C03TAAHmk#^7kY~e-H39z74t5i ztF01K>1Z=o$;TtUgonty%-OqIrMYVyPJS;*7ieCYF6-|Rf~)O~YL%AF3^~?Y&ZAx% zs%7EBYgcnj_kVVNEuXSsiaoUQ9_#I;HB%%ULqy54{pg% zY%1^5kwTL_VAJodwCDV4kP`p(#5l({jEJ=?6+VF({FwbaA>Idbc9n(O=yjey=XJkD z_b91Msv2}S>34rs9lQV7g+HY$g78DNaf+{teyh9kf+h{0I4nxqZpBW@U^X9dK85cX zx?G4a&+MN&|HL^J(KZaVYZpx5fbMS0@r3f={sPEtm5CD+F(!C@9WVb$P6~)clNd~# zOvT;JUs5MfUL8Z>L!m)}BAQpQoB#ezdbpXIsW!u6Yf%bo%SAN_!OUS_C&!QVPE^Q?OZy*WtbR)M*JAcV zBa7BfYlJNx#1SFplf&^>aR(CyV?Zo*qUG@W(VyNS$%dV`5z*xE;*63E!m02 z&2We~yCA6VZ9jQN^Uxh-^8NzsWX(-z>h{WEsg~a|N=z*T48S>u4Hh;o*k^y3_y-5E zv8ICpwdeYk#YfMWEiI{{>_23zV6S%PZhxydWprVj09MDRy6`0;aiAeR+#o_X_Nbvob^G;80 zZCN}HSv2)DlN^@MiF~Lcgwe;05D8A7%crur>rSj)e>EoW^)e;RX!qdbBGk0og6;0t zK4Y2#!K>tbhYRkC56x5Z6bOLyD&Hu%SoTL$nwC_%vMdv{sek6JlZ)5Kl-lvV zV1@r?+}_(n`d^E*5O--el~%*u1Z0(3Tabc9@x!T#@`Yg=k6|+dkJoL&NrR@+t^RC>H0^Jw>#7&pfNoeOf^W4%oO9My#1Xd5hs9FT64acQ^v!gA29cS@- z3#^E>f53dVz_d`wzd8TOVOtfJRoDSf>W43yA|9{^=SGgB&v(*9qpeO<%px#>5n}hh zEvyfCIVeV$jW4|2l=rvu;oT1n%pq)ke%0SQ{`Y<3vcoSYLU@?aP-d`j_mDU3 zo<6*Aa1+w(K-A<0%U5>qtWXqn^BbJk3HYNo3D!)ANBcxfk2W4MOKgq~<CxAX}6&AmdA!Qw(a_PKLYB7i+G?iyZ-&|iT z#FxG)6O=RKAN0&>58kwPIG`{SBQ?goa^$3(p&A407LWA8Ly}KLQo(23y(h?(7%UkF5 z-=d|~!V_?3|N7iQ?5Y~p=dEUVNel7cKtAIp=H9=@ zNfa9nzU<^24CtX_PrqRA)wUYNMRkAZ>vv=?0d<@lXKp9q@m*CPUf;bhiuV=#&SKub zFJjMp`nK@NEn@1`@M3At1cq?ndqwP*S9VKiI_S=F`(8D@aW?-pCz4u`PN@*AJG*8R zRVOTy6G@kK2-j{!X^6=A>)~J)%XaJL#>60?h9-)8u! zW~My0=0~MKQw9YY5DkSwFL+kOVpZC> zb~`ge;5(Pl%LTHpPD*v|JfnQ@A^!ER$b=C{>g=&zg`y`%10~;qaJ^xu^UrTX+PnW2 z=b)YSIJ@>73$l1_hzQS8S-z9slW6H0W6sHZee*|6yRU9}W%7qLSA@yT&41sPJ2%OTi$j_me8mb=ouPC@_5Pc1L2?!mM4NCWwFa;Dxp?lw z9`vxQ2Ge?w?D*^Vw(2*j-+KqQr_MDa=`tL}c^1bt#k#p-IG`s#ztplY+)HNoHLFd1 z>7XHrm)Ppm(tqBC|NQsB#re7P6CGMO45a)){oI+xRO@$VW#`Whzzn6hmk(5Dy4BwD zdvQN$bgd%*ThZ3|Ox<+qJ;C-Y{anGvq+F+u^M8|SN^qPF=Q} z7On37$uu2Y=RKA}MAdkNhTMsN-ln(qI~$64jfb&Gt|cYj*NlIT;C3?2>v+koAqxk- znE3dF3+;*@JnY^CTZrMaoyLZ9)Luxj6tTjsKRZMj@9PL-F4xj@zsi&iSh!`&Kj3h$ zSicOwuwrJ9rC-EJn1u>8fM!Il|0VM$hikkb3-N{ZM4P3Sd*(dUig|W0`C;{0v)^W^ zsXZtZLvY5a`tu6klo%s`qx(z>1zit3jI0VUYsAzR|E~6wc;ov7-v)^Qmx-4FzFLKb z{(8$GAAe)(**~V6r`NA+&t*L2t{fU}v|I>zv9snwm&po0GCg!|X7felz+Q%MP5a^D z-aG$;;8m&1B{#v>Wi`3%pAB~ooZ;M&x~vxY`n!^?HuLgi8_VQtK!JGC-KOL^tj4bC z&f?8)V!bk@?cYzu?Xngq21Yxv`#m9O&QV)v`0=bh$p!JrKrX?WfzcnH@Vub9 zhf-0_;D;g8i}6a2!?1@hspx;g9dzz+L2f!@ruz)t%mv3U=DOGLE@UXy%AZQ)a-9q{ z=L49bnWb;T%qne*ew|Bqdr=WX<;$X6JeT^NzxQD)R?=4+y?%A>zN!#*_jBU2Lmk7l zMs)~W8w%^P{7bC`tWF+n=r$o2f^|(@V~@(9!p8pxSvl2JogSgx_GvMva}@pu*#N?{ z^Za(=wUdvoT`~V!Wq;vhV!E7lw>CI0<#t;B)Vy>`*O<)X1O!C69<4DT9+Q|3d{@_g z)I^A^KPK6uC_|j7O}^jf&=FV?76#5hih|P02Kt!>p@6e(+&xZ4JCZ$=u=OrrrO1(< zd0AwpNr{>wh$q;a*?rqzPb1lvrl(MX!u91zycTI zJ)XFo%X~=!I~CE^UvBk|M8WUE3cc~Hc8a9shfhJUr#F}e&x?!=kpwz@hcsjg+dgCH z9kU^B|0={9sRt6pzBF)f^)R&5YQsKu3i0CwGiY_3bbdH-fnnOjbOUkcN!OpFTgc<5y~bq)~Lt6bpm_HDeNehhxqDT#U}~BiPxnNmTv# zTSUcR9t9AIUzfdx4Pp}vV))>ob5bV2>EyLjPNRZ4x!b@%bD?H>;^P{%9^b?txMzf^BD%}#zZ8HN~VRv&F=?@`Y!Ejvi zcA$)VAe)Y2g_cBE?PY-o6nVFdTpC*~Q(Mp|9vi~Kly_QYr3jG`?gQB@#lhtk=rm$} z-r69*w9sTp@+sQ8%ke>^*c>a@yx9+F!I6gTA=8sz=0`2lqbgThSzUHX4Yct@2C?dh z30fjZ8hZ0;+eNbZx%ZG-$a3fHE+^@Ef_xs84QdkNkZ<4-omqJ8ujqgzTMo8mJJdEC zM%^(;Z9svGbmUtnnK#ewKp#Q${$xnErTSwHDS!%knKpe8&#)6eRCF?VHc{ zGa8fshc#)%?ADS*OFAUZ)5YJKHDAYw?P_IbUA^f+qtWM>Bcf`7opW*&Si*1}P_Gx} z86H$XW1lA8xe5epkZG@*Te(j&K7b+-t|n{w=5}Evv1C>cQ3gJdifTgvM_hwm$X=O> z6wlUAGJlprO6K*v+6c83xzNgqW$&d*M|F9ZV;a@sD#qP1h3+y#vzB^fh`&2laY{67 z&tlQc3r8Lc)7ZI07oDU`#zZCFbZ^!;t;iiDT;*CTM?w<7l?mWyTirl>Fol0@tl*xp zwpfRQZ>3sD!&8SyS(a(;{*)aqlE#tZC4UV%6QGISiNxuyEW&r&KyQXCKQz(t*3 z&6_wi9+UKenSIZ&TsYRi8G(RfZ1Q_@uffG%hi~VoP0mKq?#fr@KE z!uF$PFGdEYc7e^;Z?q}_Fj|{$X<~#P3T&(*9CLJrBEw`^zM*zQ$y0mf8*M&DTaU=i zE_EV+dpr$lrtEEUIvl>VE%a2*?4t%C_s`MhFR}V?&QSZP;Bova|(!l54N~r z{-%3-DB(C6*{ko9lQc9Myz|T_T6DimMvjP7v>d9~(Ra|SPgtrq{JM|^dqzcvD)1v5 zxUQOF0k%Cvh2HmiiV|9baXX_8#IH#L4Inw9iY}${(T%bvl#>K#m}m*3k(ZLCKXTN* z)RQ-}Cyeqp?A>iX`)QB>y_x1;hk1m@m!E6=J-NVIe8t?Bwbu8%%izdhzlcX`58?rf z55`9jnmeRDl7#hSS9lC*iCI*~_0&9;ZIQlY*< zp-MU40sFIqE~2hJDe<~Kp_mIq%3=1&45jc6iUwh0eDKr&d;y@6q}I z8f;FG039@lE(31$e%@EJAQhLCY}q@mp%LlVY3SFxZLIM)L;JhuV=^s_nrpaUuZf%) zu1qEuWRnRemiP{B664G2$*eK}D8v<78bL0|nBIjRzEeoDpSTQ^nZ?#8_JL@R({5D% zQDZcElGSRIPs@B*Z&H4nY_EIm!R@9$a!+_S6N7)m=lI7jMhKl`1gf_7w_j!xXha)j7EA_`44}Iaq8Hdd>L^; z4y?ylBbWi6leWSvw|4ha-a%hSxn?t}@^!6-_lm~#lEfe{SFHxg_QCF#(Q;w_&IYwW zk|G=+` z>d(1B)GXp=kl9de6M8bqriW`6t106$o7nfk#&9Fl;eXJ*wH(d_zbw+wR@i{@Y;aA? zE^*AL(K1-GkQnXk*Add8e{TkH(k$-U_x2NXw&X&N(w$w=(rdup+Xdb;XQST;va4sc z>ZZFE{%GR9yV6npYGJ;ULT#0CI9zweEP7J z3Bxn>w)7q1whgTjbOFIyHS>D%M^xR695r*KHh&LwpRK%g6M$VX&G6wW2TqfTx7`xn zv;+XDVb-LDQF!*|IC~8x-JH&)aUkz(qTcdqu7d6`KA0H>ESme&__4;Uc^*9P2ch`% z_GL|+h?!Z$hs?A$qY8^1(Bw)}Q(o3F?2h10tA*_VV@ZP;Rl;#=g2Y{!eZjyzlbJaT zYcVW}TBJ#2Hd1$KL{*SUR1lhlRM;t^Nd4{TrxQewvVk4T#7*}2d5t_jGp7J&!~Kwp7Jpm1dL*LiiVXP+kxq?pT_pHz$S8Dx>(J5z*wm zcrAlP6V_O~q%z@Y6(aQYJ(z!pEF17kanQ1R78Cq~9ccOMf2@(CB%TE_uw1UJffMhi zAQC{?0|SUeas_&~(S<4f2q*FOl=g%Mjx1-s<@i+BQ^w@dph?s15^W~lJWmB`b4a`L z1;;e=i_A6aKeL0C#PHJ(?RhI^{1fFXSz4w3sei;zZxXMwr2>nmdzo)G#u@;493|dc z?VsdDj=TT}K!i-b2P;H^_QT;FN&su;s_(hbQ^U2Rz$zvDLYO#S79)~ozm$pN7})%~ z=udc>d$LXqy|g%aXBbmU7uD&OiEv0}tnol-Zsh_$?L_-D4M2t#*$%-=Vy=$6GVC_s zJaa=NZ4o>UK!VE{$v^9)6oHBRF9hFt_=COV1Ph~@0gwJ-f#OiJ#s(L;HgNUFBtR!1 z_5DkU_|LR+TuJ%P&aAoPLt)}K29ruZl96VlMEczGM3N%*L_UzH@}B!AKK(Z)IZ1Q} z9FT}*%yCvk#XxIGd|||GcYm=76GMr>ReI|i7_`RAe5voCg-x!P2%JT0vgjaGsqR&y zY>t+Hi7#lDuj|0AbOJZ3{G~I$b;c=fc?e5)2FAYujZ}d=Y8BQ0NJi%8>Q$t)T!s&> zw1_;mcJjmXS<7^@Pn4MTaS&Cc`8ak!t*rN$+Ez^YNcIrK&xjcW>3h;af6>UjAUKG) z@141|02T_l)7xv7V(_;dG-o8$?^@entm3>hOl`c?%H7e8nD~WcCq#I_;}r5@ER5z4 zTZq&UKN#5GGo&m;=MRFve3P=$0#$sKRrBM;cN4j^du`Y;vx$kvQ0Qi;{oA)B1-_$? zVy`?X&??~lHJL_ayCi)YTVhLD8hjS)Kp@|N+<<6vxbz-qn~O*9b5M{GD@MM})KbV!1X8iX|e`&{K7cW6nv66!%%=q_f*)zwhaHpw#n z)I8#ApCM^^S#jD1g}^aI^(OxZ^{TcQE0Tsj1ukO28d<`V+7RayoL=V^N1n=^0Fkl7{FY@Zb!%&6EzuBf3+s z$=%=(GJqHh!6{(kSuWjMznSJ=*KB+Z9Lz;B?z7O;1XeCqEyNQnl3O5gYiUo3l~sae z>L>u_h6c3g28pceDLr?fPKvxE;}~=i#amLDb)9^kb@Opv0;383UPEH?29(UePkGeB z3s$+tVqO2qGc}(f*!j&t zn^R}Gqdi>nuS@bT%R(K30Z*SJ4e^R;CCD)W9s&uzq!|kP{$N?CTXzzU(Zopx0sD{7 zKT$jbI=*8;d>L_6O9N@)vfSBNmYb+_zqXB|SUsX)R5{DHuSIieP7XJa`u;nKiHG!k zIGLHFHaD-nd=?_^oOCe)l}B?+Ww7t}zBCIFH<#tIq#+HjYYyM7Vcf*E@IrrG!B1JH zilKxM@*|1GwKRoCfxpf|6Gj^3P@T?F?ia=AO?Igibl#47$fa(*bJ)K63paTKQv?Ob zv<{f8E(;3v1LpdAzz;V&ivqw0>1W)<@l3pyDpXYKVPnEQZ?{PopXJwWhzI&H8rx%f zCB(J#_lR#0F`)M@)h3+fz+m0>NPoDu{R+cdnJ_7RPx(5JTFbSx+$SOl3j=iRK(ZW{ z;;k^bHE`u~9WOIH($eO|4aIkyt_7|&sKuZqCIK#4gA{EI8*`5L+Z@EXP&fjDxbF_z zx^{Wa?9%kQed-dFPiJQ~Y=nzIYRKJ0MMGkq(TDE`%EzS^AL0$9tPy1jZhoM1m++~2 z?0b2pJ|KzhDqtNy%k(o4zdnOPhQ)_W1nt)2WU7ikOl-$%_iqhAHzIUX2PXvF(0!vz z$nCF#xx((yxSN|d6|Z_$nFNieCVmQd4qa*R+1`VLZ*==IQS&esTi-qsIkyTPqT7x+ z)R#|t-b0#?b|y5#;;ehO+7pwa5nnSazhzQHB|(5xO;7zZ6@jVlg7xXKsg0I96}*o1 zlGf!_P?Ko3KZ$E&D<{tI*O%9(E<+i{L+%i2O`0eny_Rdm0~@EllQhn;zSRH9pa@T3 zxLz2|)lFkeX9gH6g{|d6JXu9qST1#9L42sN}*6$sIO&>U|g4E{C&4eV!iP5da9tz7X5E95!{luZIE zl#X|rM76#$M`6GRF8_Xq{KMzM;q!8DIn=+P7EKP z^+Q8qzRmybjsrzUHFYvWpru%D3v_VuCN(zk>Yd4R;vCjnxXK-6k z5^wTf*$vXA9{?p>0lzSUSUH&)4_J$$x3!WUWM)hS&z)No;h*&t0|S~jnyH}wPX)J> zlQTmtUlHukg(k|(tw-Z>6-7}yNL6(lT4<<4?Qsj1B2GTL3N4v|G&fv52}!;S^4IHp zf1-VH%tl#RIn%&iibhJvKMC&*T>@-(X~_FlDorSVXyW=fMYK)HoBH5ejkty}>ucwG zxMJ-rX%--2JKcC*eM{sKasHPqB&=wp&&~-n%;aTY`UTZZJBG z{v~5-t_4B3Ns9LmT78goYexV--jr$dXEN*6>I^PNn!8R6eSuYoEl4ZVoT`_|!?pSY+Zt}oxu3bm`NV4^ZfQwVPS zwX;?fSc)8|rwNxX`oIgu?{c?PDN~SZ@c71N*aFYS7nMNAo*5@rgB63|Y}Z1SAH)Ub zx0Jw#_7G>msFz~oP$T~!bi;m}a~+-shQ!iCUS)(we#0bQJY?kJ8F-~KCo-%AQi@bd zg3)Nl35viAT(0Pjxd_nQdwg-N%K-cC@QH0#PAYo$O z5Z1T1NRufxgSc~3Cn-d4WpFB(YrF%wf1(KyH7b-d5DM?fFHt4$F;Ky(4mNdy&}>$; zjp1uI_!O9DK+QBEea*l~ec%k)LbVWw-l`B0!#(dIz09T>zc-65XJzm^C&d6zdL(O=YiftId27Q636+~WUZW)8Nz{^i#b%_@~O!^C_bu(JI$`C zn@+UUvO68?M`En7mfkQ@GsQU{V4NjE0k$P(RB;+q(!#v`7)IN@nBfYBEVz`i?}M3` zj!}aH(}KZp=(|3B{V`AKlLyKXpu9yg2Df#BF3Y&~TMk-fv`z8m#cRPV7glgGvvr z?h-~`KVVPbj+z;B!8gKXV?a~}sgLZ9Qx4#u;S3a~`zapic{h9OEgL@vyBgDXL_dkp zz_kk0J}T_Y)BqUzZGt;5Ow2O zMR_%t(yKSlpDybxG{rQ2eH0^N7{ualILnk=es=J7*|o=ICYZ=hkU<;k)|yV%eIj$= zs4oU^fHr<;PB{<^w+#mmKYUg4PO|neFswFi1zgQ4J(0AKeeMC|kKEB_ME5iJ)p)k? z#x19~Px1;07VU}}s5u&Ex%BI;m_wFAH2pYPmO%gu4n=WeuDYjL@C6>d(X+g3na*Y- z06S@pa|K{x@H+UKru`)T=p@h^?yM=$9~uiLU0FDIG#ea#d_)b!-%sw{36o0VkR0)Qpg%II+IB5dm=QLfE=&rOQ0NR)5pg>y7vhUW6G zf9-Y6rdYRpZc8?tBBkIMxE8hcBaA2QS+nCOlmZd6+gD@HjDJPf501Nc%$m*8$O~P++s(i?bb{r{n5HfT$J!k$JBb!X1ar*1v={LXp`DkpiIfS?eVlD+BEjq;yhAIG?MweHKIdT zrd8IBg`j37vwOvM45m*DU?DD>zsbiw?!R%Dh(cXGCD%m+BTYL`^Sk8*1Ht2zq<-E& zLPFKwE>NS!;hNn6WWP{$AlJT?)%mvrL1WTTdIiVroG{);q^imp^hHc$(^&=MD*4 zzZJ;6Bh{eYHWw}*F+FJE6=LP)b^;1Z&XlXVlyJ?Z6hV~15i~i58@+y4-W)pJ@2Lk# z#NyDBtzk|vetPOLi#p;Gg6-|JU3)$iol_Ug)d%7iM$wWt|D9SCdbQ&MkE*kgg0t)U z>&7n})q?2^?fJB;ArkAG?s|42-bIt3peIrtQ$dXxU1H@5l^spIl_8EWc-Gf1&zdiI zPP}W_fSN!xZ8DPk$v28x>WoiS_ppGcvr5lXobj-oM4@2a{C2ecMfvIx6uIl8biE$z z{wO0LYnqOlRnZ$O6tHH*GbA<&v?3vb;pYPtN9{Kp<(eUE9e0Efe*2TegDIgg5LtjLcsEdnw zv<#)z2kKD&2FJ#iDoJ%aKj{=vC@ZX+_acOdbsPB2Jr%mqRZg7ocMu!3vh%)RS&*iDB|kz>O1 zDEA~KvHw9-Rhd|J;I*!_g{3;hLA0~UrUQ1p#z^!Un7h1AT~4_5V%}KMEdCIkom`WD zyDw|iI_F%0>h{QRBL5ogE+C zD&Bv}=EI6c@%#l5W%0YUj^1=F6`{t=#7CPiSkCoiY{RuX?kW41FKx%(+sA5pac9FT z-)!XB0K^)j^)0n8$ZcE7d`ACQ9c@5fBu*W8=ZD=3{xkH;&lRUhjN9x8r#0uM2*bU3 z`fQ;L_$YXtTCU%m9Dfi12&Y&5?(dgt*qbA{YRL{<7OWR9orv0rsOyO6`7FnHa#U2u z^|X0UFm}vklt--DG;I=IN{~?AT2#b#zbhS}NUz`X{W-}C(}@+Oa`E!=oh#Nj#93Rl8fstQ8G-08bZ7>G}POO2O?~C&P4>2^w=zgG+gNL+tVa z+=hLTo~%U9i6LkaVH})|gppz>Fp#8xInuFb zztY|oifafhz&0`391Jkz3^$MV73U;yh0aRIRJFEQdC}JL1zQD&njas^LyF51X}gA zUZx3K7pnrVMZJkTdu|^_kwVIPN^Q6+XjGdph#g%G5&rU~2-mtTKeQRSQF!Fx&R54; zah`IW=lczb*yhCl!_m3NGui)t{F-5sQ$=x`O;JuA9Ev&2P$9}$N^)B0;56s6A(Weq zoXatXp>ilf$PjZV6LLN_nx)B^G49{>{r$hk{@Ata^LZa$uh-M$N2=ERg3pV?zfyr; zi*bobpMR7)T|S-to%Ry*(}cZ4!7<72)ZL9Q`+4XcMLGE0-7q_%x|Y(;$6@iTP8OT}~F8WudkJ>9P?Xj($ zU65M34@(gi4gZd~A@Lj@nIB?(pkDcLFX;F;zuo47FW9K4E;MW%t&rTo+$U+r)Q=9B zamonRM{NjX(Kdf&%t^iO6BJMx_6PUKzc-6CA+qXP;H1fq!MK)CA#~9=@357=TEN#T z=`j{zugD8ZCQT?7pL%U6wa1UTghICVtna4i#lhh;Bz>ZyLo&{(VJ>`#xRT18z-zwZ zR(vd^;*wT#I;!8AwHU5Ia(r>?=!zCHQ)<6?n_>5@BuhW~&sO3w{E>MBWQkwi19R>M zr{w2Ni*OoS7Ao$LF)Z>iGkei-d-%xrRy$hVnqpXZd7EX4rst*eBX;eY~undi1wj%SGaEck1!4fwI;3Z!@VKK6Pq zNzp+(?4@@G-qPNp3a7h745T4>rbZt;PFvl*!|YwRA;FNz1xK{dkDVS}922?bE?>O@ zlfe{hzOf|~^A8K%>(*QOTEG{%sH=o)-4V$S4F zGDHtpLT^}q<^GYEc5dj5Y>%>2{^D;%eFH}vB!rz5{-2}+>1 zU|p+5GwrM~oC}Vv2H}nwH+=bSH7(xHZ<>OA6>OkLRbOc$wWk{Yy0wn}^!K`DVkU~N zotOS?(!k&6mHV(zlXZRM5l?OnzshHKB3;$%Q|YNlCAi;m8*|Exv);THP`6)nlzxBi&BFS!g-nL{q5Fpa^ zWa8%P^i|=9zt^!oo2)hFj;?5dK%}PFmzyTvU%+;JxPA95EzYI-JYi2|rnJBDhex$t*tMt9^4YAFO9Z9>|vq!p|@Kf*I6jTMzp z4A+GFF>EKa48GcAG4Co{`6$&B3|a?sY7+L#3T;rh{dUKraf;Wlz+I2qTOf#H7x3<#=dYOnT~g-< zFU}Q+4RLfVp9>ac(>o^w%R$a}nvB1fx$2lGn-R!;s08 z!P-b4tBNQB0ID4RDUp7{=c357wY+BG${={B_Ig-#lW)#UB1KdYp2hO`#L^2>B9?^ zE*w!u&L_$EYQ9GJw`N9UP-IYS0--tLK9^O)v9IiN+GYVnllVl($m0C77^K|n@nd9UAcF1p#{8~<@H1n0fc>m4(@OGS z_|@WthN!5#j+u{&H@S#1APbX?$%PluHH_sr18&p`6=~%uO(q7EA$IyCcy9MbN9LD2 zu`Rx8nndYq6okdJQHv&Zeo0e?il|>N@3Y zTM%?UVr5;0aUjor&(&ZUkb}4}*$qu0_SU_1x7`Pgq}OfVz~YbIX&yYK8R7%7w(I;nt|TSIn&m3RP^1`L3aBTl;tedLyrPx0QPDk% ze=z@z>^Xz=%H-V!K$}O>4LZA7VJvF>to%RVZi7=W86L$7y`51M+ailsJa3c->>v&_ z24oq0YiB+`}#!Nrkb6IKn#QNP5I7%Q6pz8sz;qM3BK3#X1y7ghA@}AcepmS{C5tm z=QQSAKLTN~#&47u(YQpP-~)vjwr=BhVRprrQ{5}!`{7FVC#vexgZ>KL>Wx?vliY_+ zCTvw}=G@68%KR|MGRI?N_zHcz<-;X|L1-bJ(}j2wfyop(Sz7d~o6OImRic}QHotve zpMpdyu|`Rj^KP7h8m~GpK(ke46?$Zz(k5dL6uwm@ym>Lkm6jMqh;Bj9o?M&E4kQ#M z9wSV@>0fED&B-0ZHWBT!wy#hPM?(LpW*Xjb=a}Hd+z$P1Y;ubozs(Y9um2m5O21!fud{l*D&xI%|+dt~0$ zNRY!9{t~-j6Jxzy>RJn$DCKcb7pk)F%Rhd;uOF+n`Z%Q$x*Br3l&^Z9 zdgpP<&+*6efSn~S)bUg3{Rk2B>{lcJ>_XD;J@v49DG@y_)1QB%?SHFl=@xgT*m)eR ze4mBofAQbrWlglN%l5t7$fENnRiH$-|58oY75@69Otp`Uf@>EcgOSgu-B)vs&6tX} zBm4Kh9qfJN;VUx))prDyKi9pCj9rcOlkma!`VtG(#fiFc43_i9D-Qgf?;Z`=nw;v( z*3q;~8OnFov^g<9xt08uzac}?bBp~s{m-7=lb8%vbHAWx?(+TT+Q-&l@s-V2%2m@t zls2kwLm|)l1%E1FO?1~OJHoQ(v&fdi*inXq729Mt^x#9`f55|g2A_Y9_kj_y;1YQm ztgRNy&ZrK4efpv;Tif}_1WI)CjZWYM*VmG;3}@^0?-^7s4S@zYgc;QtzO(wFv#3); zZgr%zt?I4g?Pn>`tHiWW7Zj{i7amyEpH|Oj^rp;Jw=Rv{9AUSr5orXDz@W<$gzQl6 z5|@}jFKPF8JG$i4t#juEhW^}gxveHIGisCZ{+`J|4_>zdCRLzrxjyRbI@D}hbZtGrw8!cc~!;87?x#)!SJW)r_SbZO?g%R_tp^?ht0miaBBXZ9+0 z;iC(=?ePgN6J$bkEBf=L-Qyl-4u7iF20X3L!mp~Xn+RSt66o)|99DE7dU(Up*PobNyX^DQ<K<`u9bP*&Ts!^mr(4XHuX-yNZ4h=@ z%Q=oh3iNX~q_ACL0s*wLO=NnAX^ekz{W06_UdiN>%eyJW_6po5W%SChg01@D`S~Cy zNw?D=66;m|s6ND>N)@g!BgDf9+PR<8|1Ii&4`%WEShykVCTu>%7FLF|`PQth{h)}OQ= zEU%2SIY#(1zft?fRjXz;57TQxTW9xMpZ#V1_y%jslUtM4`+IfhT;3RNI|`p|8Hb1w z-Rjq{(JFDKi4z<2Vs9&k@)zaJr2o$6jOkdTlEZVaoJV@Bp}-^DeF@3QwhoheWu}vD zW{^?x3hB3sqN`UuUUg_|5%0*8|9<7j6@@3^KAK~(FVWq~EYgT}qvWyCC54xk7Pq9X zi=R3?YkT8A;3(8~JxbfNc=Slrjy_o_e<$injNAO=s}H}9FC7`P@idwF5{Rm@UCa1T zuxt6nHa4z^>)W@r@S&`64rCfKtEOKAk$a#J{dw*1^=TQCkH%Ky^{+abkmY>Ryt!a3 zPb+o~<^1%@J`6ma`b?*};3x79-e}scVWOLlx?MP!d{qhp=8rvUd*w}(c%bD5E34Go zupYTM{&_n5a&ZCYO4s}VobUw%5SD;639S$FpG6nHzm{q2*BD8*2{>h(qg}OcwcBKo z{d09Bojb)t+d{p>=?cSuN=*mk00HIT?VpWR&uppBw!EI_A;WDf8!(UJPT-j}qOnu@ zJn)k=@H+1lKR{aAprt&D_n=({`*q6>LVziJ_lk+h!I^2}kQ^p;t!;R*-MbH$+V44W3jVg8!F85Z%hUB$qac8z! zAPAW$BI6x7LH%edJXHHWS-DAPZr>uT*{y(rGz|efzt=)WbFiDjiKb>6f{PZ8kemZ0 zb9MSE*nx5z73$j*Y*x@q?tskqk&39cZ-7i;mv1K`cmMkkAur$7M8j{pfNLo{7?Y0i z($gj}Zu$=Ad8>ekN)bj>{$n62jbOsFiAW244z73F@2hm%y{cV~K8}+mt%RG6?|P_BY{`ly=S`bRx@lwyOHjei(8T z%od(j8jOx`cvY||A*brj>f#>S<+YFT`JbO6Ui5U3D3htLlH1|g&t+)B4fIH@vE|R* zALq{}6&7&bf49T4OuXrwT$3ECw#iJmUvOe^EhVu^OxPbO)7J@HiKDf8xeMAp;Z~@# z+Q*U>M>0vAK4=YOZ>r?llrM2f7J^bg_C~}G^fEwirXpBy!bWtHUbSeF^o+dRbz}*gc2_1Pj9I7>G(c_8P0gA-G!Lld z%E7G@8p%-1%|UMYlAz_N*{#x(tm@{A+E_NKBxRTy3UcfFcvnsF#LlVdtPmh zP&DiTb}4Br_pC2?gwitcv9BabaQYdo)Kn`0s3gG7kf#aD$$1->~U zOBibek2Q)!T&Rv)5 z0F$g0*)qvs-1MI*+I^0qdbHq(kAbfcTt5#ex7sWa>iwS7oajq2$=iKx$bOrXT&gqiQ>~YAX$l4;dcbGe}{t)+|!%dA4CR& zt>&+Kf<0Sk;nH;}??5>guC|)V{A-*w?9Uj+CIAM9Qu)bnfsjz5okfu&wpv^lNdj|P zTVL}fCPD~#ITpC&5IL0Qr~f6~YCE>2?a)h2NxRq*ePJIdPc?5-OlFIEgYOBxau0Hz zG7mFmZ?N*Jo4QN@ief%GH2_sj&Cr@VLGdb4i`KUAF*P5p7iH`Y5mcFyO!Aa&X;Qyd z?VO*)E8;w;YT$4KJiF0~C>g{-xr6A;l%IX@@}V$|JOk3I=U+)^U}xcjo{ZF#Ce5`` zuMi+9df`nq2lW{dsQ2=jcnR*PY1xaWfbl)<&Rh?O9d_33%TSL&PBI3Bc3( zo?i`%&&^Q4C9mF>s=~5g_yl0szn0NK(?jqF0-&6ZBZK^)r(3-n{P06lhX(F&Q&3RK z2RI%4xl|c0%c;P(O2!dP5yPGfIqN|%(KbZO8y(R%>x2k9Iw6|@nnRSTS0<@C=*N1v zwziuf)o%DXJqPWf#;#saDNyqv!yiGafM2Q7Jnx=-g#+$Rt zIL`kehDMLcM6rBuCVdz6__O*k+B781=)QydztgKzxLA0kk?(?=n3tDl8pLi@w{0)q ze)uPi)6qqpBK1<52wmAAE_NBTs5JiF5TT9v6>!%`o~V}@h2{jZ%UP2dP;XFBVzJLx zB?@Kd96`MleLcivkA zxvrf?rA?qHo?pNS;^{ysnqA8wVL)n)nBJx?Z*v~mcPkL`r=#S3^0d6 zTR-!Ed3vR4g8mNXjSc=zUK+UU*o_bda^t`v{N<^$Y8SuvtBbY$FOKt*-HR`N5)DP^ zT(2Id_ABj#3(h?RFc|G=!PT`cS9&C^-@L%^PB7np;}>3zz7wS^Adct| z3HQeGHpiqi1Z<-r6(^r>cuw|A1;g`Kf7YFKQRs#Xftoc4RE`x*D}X}l>&^jU5;p22 zjP!>GC-$P)HHLRHoz%T7m%)s7`lB{cuX#!VNxu;`KUE?T&LXRll<6gjjv{8-3;!7YzWucnxm7$(Iu>dvhid~2hT z!py7;&3LAAf*;^DY0}$tg8bE3&>p1_+m(CjSS(`K*!}u?H)2aNhwBw$fpEIl*_MtPLZJ$c95E(llZ<)$MRG zjKiRUn*3(nR#CKX9zJAmF#iI(f$E75zwUDNR#ZzP?2n6yB2UA<$IwuM7ld+-`zWwT;zFmrog{PAWsY8Q#;|qLz zLQ@E(t*ugy&kd4+OyeK8p%>xY4*|jSO9T1cmOHO2l+>wGT7X=>5?K-}m6xk|?54~a zEJ4uJ8Qo;YL8G(um4=Uj43$_NMRCFrGo@WCH`liO+-gW0bNQ+yO-2GVcmn6)a&}KQ zmmtht^U>w}p^=w93mXJ)J#aQ!$5~~~8Lfz74mg6}=9ldhix$VUf1XJ{##s(u_szj- zcWidvYT)VDyr_GaZ*;r;?cJU!s3&8zA^~tbI~=tEsLQ~KdYTc4w63#j`9q~>rAg$w z(^DOEu?c-|ZKtJ(n1*6(hxSSf3b_yxYR37h!!fRBxxpJ;0TT{~XIZXU^UtP27X*YO ztYY;NSMTJ}V-bhDrJkO_R5avIco~PgMALAf*qA!Ka4*y<)T(mC&L1R&vKTkgFQxYR zQ*S2vi82Rc$Q^FdNu+@UKrA3?ObsPr;I#QObGZEUheSGzFg#$e*X$B6ZWXZi(p!M! zB>;4HDbL~yxccuc&gC_1m%?M0PN7?=?v`C9KkSlyRF>|3}JI8qx%JgrCqK>cKXZMs^phNGsFaPk933o_TV#*NFT<1tigW~^RgU}&INtzZIpPQG4g`Y^w z^HE|&%Jax8v&>-90UUV2v@%}tM1M+%4s3cNU=M`U1e4`kBFqU&TZd^6NSkQkl>njCI z)TFAZWkphGMOjEdVl?`Zx9$|HN1fshIvG^ig}!8U^!rB#N2GJd)wlORJJ+htTq3Q^ z6C8RT3O8s5ZT;p}SqlGsg*@lCU*Hc`b<0C>0={kbKCoRdf8m|b(QeL_qf~QhE1j93 zk&8b#RK!gD35noH-A!E-zgGnw1|U1!6C16l5;KWz0^WiCW^u zP(vQ_r7R}GQhhU+D`Q+Ge?9E%Xeo!&32irei+sTauo2Yb! zY@%y)IPjzZw1IurPDzh_Oc@RF`t>n)2pZJVTfSPLrN#pJdf`oLI>)2B4BUM?Wu~1E zV7^-go(q?x8bFbky{>qC7!w&>222?Af+1tX!OT*QOS5xspcgOZ1MX;TOm4##)3oE< z4_LAak)b0v9hKia9bXB%oRkwripKB-kS@;YTA=95`HPI35@0TJEN~nVs3t}+HB&M_ zZoR!Vp&#DDV2MrFuWWZpN(c99tZ=H8f>-LFodslwfHw!bLfs3?*eu53@c>|#jx4!& zYEjw|G|(>V@GqgrP%vOt+{U|`ytyKaZes^A4?`?sa!zC7BV>X0jQez=7fE>ZobFIT zzkyE>Tke5YFn*(rwqClnaiS|+9ckK*=PQ%+rCM&1=9NJJNQmy3stR+=Ou+C0SvuMj z%xrzUN|9m{7j;-Sz%8pAd#i{~2MYQWXi#XO@v8yymSrxhCx8{96q{YZW<@6VP_kN6<6BpoBAaLS5nmcsiXb z+d3L;y7O4k@HA*Y4Xu*F%$x8Y#Y$F9%amfMPC9cLV0dD_E25|lxCrG4-=+-&fT%hu zYI8y}G%`=lkS;hB6EzB!4VPxm;wQoG4VZY-F2~Z@L7^GSJg~oTY*gZ4^i_nnqAmjr zgGnUNHzoMrcM63`$UNY)m4Sp~Ek*@OMcxx*`<9F2|*8 zsDXwV7yRXH?Wkh*B334mD5Nl^6<5#`#us3Tee4eTS3F!?1)K%1CTy(n~G&ngBU zNJVCr0Dwq;2!voDv$|c};o{)rlt_an=n3}axK%TatV3iKhEO26=l)Y6q~^0jhu$2L zfWV9Ut)qy!R@+E_!~d8`#hod!E= zl7}>3^r?JLSRJ4b>*mc1;bKs$>V;1<-jHDsP12>HwIATfjf9v*0Pz`wH_GzAFrC5B zk?E4+cRn*;Wj_2nH1et;`W^{7$uMChr=xn=9gN9IkbfdVfmP`e6g7BxE~K%%O%XFW z-`k0mpyLJ+WSW+*J2V9TSgh(Mef1TL?nH8)PCHWz>BKJUrgSU51pq8Ztk~@d?m5t2 z4gR?w$0Q|~Xy6r<21^omJbm*$^L~gYk=}SndO|`%*G%q@w}*A&G4WNGfdV%|VZ1J} zZ?%}_`4a+CvdZsKtY*4Mi4McbwKa8Y>r-gRQ15n@9m%C^6a)h$65MA5L5wI5wDNqT!)M zoBf|(R6$~`lK0Q%X7OT8j{E*wGzh%P!LJ0A(V|1vZbD3@NcP~(8pHKr?1gsBO!^V6 zWW{?JJcy>be`ggWq1tQL7Gy}3stZG8;4gd`2j3Z;lI{ScONV{XDZ>SU?PlWDJ2jjQn}VtOO%L#F~31Uqwh=I$+N^Ek7+zN=r#fA|zan?4!31@+4cp zx36tWv>(QuTkjit`!|4+ke%L;X!T?ENP&Ptk$*k*8>Gu%1&l%bDJ`#wAaxWnRza)8%e<19YTW9v02ie*31s-rfF5n~)R{9eo2$E{00u=VU#Al_% z^_3Wd$rY*1wDa6LTOdZjMOT!Dz~X9GRR;uk1%%7gX&~UHswa_9l*8d_< zKM9gb)mIS}$wQ$R8UDC|l)ul0JataNn zka4{^{$Pb<>ey)*;GrTBMVB)kqX(0qV&M)i1w_z+b3r# zgx!Ye)q7TUuu~JNb9pl{B8W~oJcMGtY+~L76O~CS-rW8bFD7QMuYqW4QDP)qgfu`K z906PmyCv2TDkPv9ZAh!WVyB4F_6eew@*AELM1BS6z$R_X;xZCn#K|Qe2{qBmiF|RY ztW+Rkd7F+P)xr57lY3@R0xnudKKMVt1=mK>4veS5qhem_D2E~d^HHffLpA)HG!!^nK+lu=9kA(wyZPg75agoi6g!!A^OmHv>H_HZ>w zl+0H6-YlfXFpn-SLXyM|qZ^+r9XED3XP%Z?xO3%ukSf-TMB%N`beSOi#wGN=A6P0i z{wb&&eDqqYf@2Pj64~2i3eorvXxDY|K-@_)3)=Kd?|dSNZcucT_rj=Z5IR^k_f}Ws zgA#hphj2YRS9<@|zHmS~5&7)OxCYBuinza=vS;(_?4}#D!%;85Yr*fzUeUhEqPZN4(+beZGc$hm(~Gmh4Mv18|Pp89#zr4M0dZv?W!Uz z3z>xLX5Y>*4==pwpYq1B%N-kpo=RO14{+)arNLcE^*UH($!XcHW5g=><`lr_G&^4| zoj{Xs=tf?W`BVi47uBkWOLtnzYn#m~P9_y>p}_jsrrU+}oJun7W6aj+{#rpQ>K`R{ zU@(4wg@z- zC=V{%Mh4V|N-j4o7>;#$>#JjDQ8dN`UPeu-o2N!o^CVQ}aaZK{VN8jBXLECTf52s| zC`Psmjp4I)^>}}wDSRLz3?9`qy7#m4S-qs6vnJ381E6>%a5l*KrT@mvsY3hR6%-vo zMz+6wHmJ_=J{buJka(58hhyX)@>1lD6S3%i4d26Xxf}BOqwe|;t%W&IvLewE1aj3B zg6}-oZ=9}g2*VP76~~%$yr{4aRIX+P!{_!Qv@8Ub#{AD~?`Xlnb24mu16nkn9yFyh z5pGa5h(BlSQPDdN!|@gS7{c8~M+&+v8}to$r-S6xrzr)8{-+z#iGKwRSkEOsZEkOi zmfy6$7yKQX8cjwhv8BVo_TPD8s_;Ui8CKF?Auq&_$+8;MFFa|O>g}E}(dw@ufZ5xU zzVOe7;D4JkAi8V-WD}NY`4xqR?R%G14d7yzl!&^!AdO1S;CSCZpDKkoW@VRV=QORK zzqU%2*Pd@MrF8)9(Hy%7>~1n?5d0+(`}n( z&*QT37n+cgtOQ!LChp}x)cdawB*FG{k^qX#Rfg(rd0{V1=4(D>=G*6B2VX}Y^LaIS z(OQ#m3d|~d|GwvVFpka}^SB;El#u11jK6bMK5dT`H>CE$+zDuLDM@X%fN$@u*r)-dwRU`BAO`=IJ=S!S2d0N9m;d^eA zBb9Tx@ePW9lME?Ga{}lJpyA84zhd2UGU+$ZRAdwRK>ko#>602Rmr^E1U!_1__TtWf zn=yhWmXg&Z)Pe#FZfqsyz#q|Nb^GD0BSw~fI%=N+Uk^e=zxw6QNf9?x zWf!YX7p%2y?OEKCPN`^qlf+IYoi;5E%|kbqy|}Dd70-2R>x<0aSYkn!vLTr7u~jer z+5JD@?G_E08$`zwQ!0%5ald4))8T8o3EQ&MUI}jyHv7%4?_bxSsgcHfAt;{!TVu%N z@?G2Bc_fa%0seq4_6NF&F=8~UpEsMfyB^xKc=HT_$zTjNcpal&=qmoLeWy!@-2Z2L z6LLKyZ5y@VqOV$U@@iZUCtPr7K zc)=Rqo5v)-K|Ll7lB(NIdLB(HnntelRwo{o~iqoaYh09GC_h zVOsBxNrdF zBUiWtpgtEM9hyqm+Q_F2*xVlM6HM#8)U!p|wHdIOMqDGF_}BYiR}Gq^H}2*$`B*9( z9zt~5wODbuBz{MBYfb8j{uL6(Rhb3Zsi#9Vo<4a4y%*m7g~37c8KyS6yFid-6`#3i<;5 zkzJI^Oqj`AqUBLaACcVRZybz0q|DeC$&i-qI)C)uA3x`!Y2_HhmPW2C1X>TjWlG-H zfSIk|=vGLLnI*Z8pnqjv%ne`sAb0^J#H#OzvX{qgudV0((sju!bcKVi3}h*aLK1yr z?DIhCtC;7m7*Y)f>ZL2*OS{BhxBe|KMSD%Gl*<_1{)XFr=l(mDlkqFow*LA~8bNv%@+ZErPyuII~yyw~q* z=lV`t6w5)qz0w5r(95OOS(8&m)hyqQ%AhXI7zU-pm8*0^qf~KLam9c%eV}ATptGhN z=`SMeLXWk*`*%P0yQ}PoDl8hsU{a7ql>6%s2xePHyJ_{6Pp+zHU%iyO6OZ)cSx>n5+ZU~WH*sMW^dP#w1z%iWlndebQk5}K!fx97Xffc5|oMUZ0@iFV> zQB_TP>1@fvNrzxrw^Zk9O{6qmmE|GMZpiM;WM`|G+;C*x=iv|b_b8mlWfL4;A#8K< zJE|E}VF>ZfRQs;)Ox!WQ6s-Y}DNg}Vj{*`gj7>R~DM9EG{XH?T_S*OH$~)h}*V zmZA!cUD7Uo7rH;Ty@eS2iB}waxbnbInlDkYQM3bFKPthcE3PSft3aYT>R_g049gmv z8K3Sx4AHM7wi6UZe2FC5MCD}9@oO^aR-b3nadq3Nv7#%2>jk{;yoAj^E)9d@F*$|F z$-Uu`um4`$ajzEFH;7QykEDtS7vDUawsOr(;3vus;RE9?&VA>ge9b#2L(=gQYrEjc znc+oH#&`Qo;#x!C7W;8~Q1puR_&M(!uP(*Nc#i6cP<`ToM2toOMs9g9`+O;?J-s(2 zXJ?vW3o*>T;hK{9)!D~zPO#uW9_!+>mSLFq^x^<+RC}g&Ir5U`t4G>2l=krCt2f=b z=MwZ|)jXsR1`NsyzP?>reScME<~F>_Uf~w$Id;ASvLj}CsBzs-L-kE@AIa|Cvhp?i z^C{_*qf$^WyHMI-BfpUXQmwbfSL=ijIZqAIG3L9Z5n_gyZc6%5oQN*~0%+cm9h0L8 zZ+Dapsx#%Y0T278Pa&=)30%)rD+EYU!xdZ8zq$PPuD{Kcy+}tGq$fABKlx2EZ6OA? zIF7re9sF7frb%$4e!ZRkydPPczeQT?3qd>;^o$v^xq2mMC%~-d*@n18MbRVq5YYaX z5Qp>J^UEj@G7&RT=K{MJS*WQY;n5$RSJ*Tuz)`S(c^FiA>dWt*K)%NbFASSzMWLSF z+!_IYCrVrz2wx~3S;gJX29`1XN{lW|>)X~)HQi}~H$|N2jva&ONca=p2&9y>X}(X+ z{t|wK3J-~tUok3Si=mzfvDmMp#rBikeTtag@PN;Tk`u&niw<+Mk@d>#ZyZlU}P$#8IwL*sThR z$as!AcQ4ys*9;MXLH?(zN>O9bWiV_?U@XX1oTc)nUs6Y9STHjYz5r(AIzsvt`nGtS zYg!sVZX_39NTd(Danc4N^Aw8LWS&>~^UNC6vC@Z+SHwuKttTSw$)Kn6o9^r1^)Fa* zVqc%8CK6wjdh1LMl^5_7X3SWxV6`|SD1AfKdpPFJyI+#e|Hh1* zdA|mpKz(;5iqGjbv|?ldKA)gJTzby;jx84(&MFAXt4;BUhdSc^C?tQnAk!!G^-1pw z5LXj31}NM!&s*~Pc=5F5j-CHlNW_)CDY53aIgT4qlveE@E~ha8v0<&R0tC={8$>ei zXkD0BjQ7_Bz5IFZ#*QbalYaHeU6YiLNlh8Xf-or4-ntieQbx}9r9%PlMhYfF_SpBJ z2u4xv>z1%LoK~*d+3g1gq{ofH055^O>y|pUF-?C1T$u5%8tC!$zZk)UJU#LG65zq$bz?b zFFObF6x+QCE7AgU`~0@vtUrGHY;D?j!%!2KLfCRM{T%K5Vp0*1UuC;}oY^hD9Qohq zUi@vo(V?z;;zy1}1ET221OKNL$wsD`^}%L^gcSpj?-3#LuHp@Pv*gBE)7zMf)M2cI z=173>iKJJVaK}V!A&h_>I4) znHVr$UURvf7(1QAtoerAZEEt2Hl1S^2!kbJxK5H71}Bzp{6EE-FkX9 zseyVk1o^lUj2Y?0)h0DxRNekdv<1kcSQq>ozG}`&K?#L+{~_tr!;KgESJh@{yOH@0 z413nwr$Qehad!@%*mJ#=sMmIw9&bCeX3Tw-iWlD2dc9g{EeI>5u|l1ThYp|Md1ky- z*<*_#bCF5Lk;x1Gd_L-P5DJuG?G90+=V$BKb92OW>26iIMs{fJVuJp-I;i%Hy{_-6 zBf$CyT*0|L7kud6vUFa3?r>^J2sUvXe(^_pw(6E}6xTPlvA3Zwyx_C=$oKPtGEUyeDl`mr6pegYHs-M(^GX?6(w1&KxqjBq0HZS`{ zBCheB45m?so8EA(jRwU>=7#Fmm7Zl1Gm5e(NZpA~w<%iF#X*NkorZ5-=KY?2x2V*u zL`dgV>f#5`=2w0DLq;$OmybFeV+fL}za+HLu;X}1ECC}hF0uTCVRBrpj`Ic*^4Qk3 zXkNnN4&6cF&xRvS=I@Dt4dUY+ha)rheya`|7OQj>r0hL_EQ8HfW$RD3Xy*~IP^@z_ z|0OxD%oEO#SSW6N@%+`P80DYqeYjg?0K%exoZQN=al@JJ$Czn$?c-*mFA5yvXyTD29*n_PrWb=oInL>Q z&u_44m57AfJo;&R#B{#p`sNPw7tBejfQli7Eb>|C`jO)J5%aN26&eTVHwEg{vWSzr z`TO!q<2Usfdr_Rk`5WSe+f+S;kuY7y^R64tq6Yh)v;I2B?y5c2+4f>fc>ZsKNG-JFlg92VjuRq4U|BlNlVC6ls)HG(;v5$~+%JPp#07-7Y!Bm<5?6^bU?D#5getaS2R)Q7YPi%yYEqdKf`}q-_CpRFVEUXAMI7J6NA{taCO`|F?CH> zo$t*s(|UnETN3tT{+7$zDq$lC;rf{G5U@j8wBISc={_4U@O?^xK~QS&L&S(Aes^V$ ze4n1AwC+4VfBhcxw7!YPDAmggH$QFs=lx0N#F9JSd|m^i-&2&e>@8L%+vT9IcaWw0 zIE2FL&Sc?6kxu+o;{F^X7e!{8!#AZzYQM5z?bm0sn3XpN(x;AJ)I&UcL#E zo9g%moe1qlFZzb?I>IHwJJ3o0swB*Dw()7Te}?yNib}VYp1Idmuqg&;g8UBsiw2gkoc`dQoo_3oSVg||BX10<@DEhzxt`8V$2r zvvrRDLu7IX9JyuGQgbM>@Pvp7m{oZscBJP5p*RFeAzk@qVw1q3c2U|58Y+D7bF*7A zDk=uAxnUPc$Wn`Q4U}gdId06BKIsUS#>>q6Y0sM28MH)23Wx=A$Xu($cJaKMfAY#H zsq!rk+v)`C_R_g92On_g{UGA$N1or2J%`rIkwRKsYl6|9sxi{rIDJxUuZY1R`sKRj z3yZaGam8=LeqA~Tw?h6B`>qDhX*RSWtP7;j&)cA^(OX{cU5v~3)K_zhUXe4*Nqe;~ z{g$b{SJgJIOq|}ZEEO3}R_Sg#OeeD?9ClyR$9pFqt0`S-yy;09y|QHCWb+8EACX=4 zPiS6(RPrC42)iw4smd63usj3Pel>*F3aT*kgjE&-kiF?CnG)PeGmIk zyCrdkmcv_1k1dA^_M8i(y-A?9g19MD-y%yf5>~xIHL?I0Jzz3aKnWQ|UnfDj9wmaQ zv^fC<-1VcNTwOTq-+mS9qVYOt646o{OkN0|T`S=I0svaHLWxcoe5>s*!xUl&t~;d& z;|1KB^zu1G2sQx(AaD1}+wTXlE3};O_Mcm7bc9~$-)NIi8WK4MlZOqh|0?yT02_x_ zpy4x`DfuP9WkN!WkJ1vX#c zp7$T1J0v1X#;7rjqnglh)~&~M1Q^2sf8+?^8g83gBmqT(`g5=9aM7RzjJ8_96T_D? z=XjVOd%1df02;MPLMg4n#JbSsP22EGa2mMmdn#1yPh}W3&-=c(Zk%DavXJkvG5DGS zMjd?vPAjErg^_8JTOi5)(RgZf#9xQ27ROD!Og-gQYF8#2CMouH1$;7q0E$d!@#;?w zaNH|k=2+Im@$YU@g$KUX`amD#1tUjAviLPMs-RIRT|tLw1q%L|k2}Il!~4`E zUc=HMs=ibsXDtyFLMPsEPo-4tniW+-x)gQFrB$5cpe(i(kJV|F6U^8}#? zPYJ8g;L^)S zb^pS+@nnC%G`58EXBQSET|!Iw|G~ zZ)le-UvG^FL;@%(y$){`N$yoU1B10Gdco6RR;-cr{aa-D9~Av`zsri%Ml~V?(Pmnl zf*lpF&}hN$UZ8?K+$leb%}m#hTrdLzze_x*_%n}h5yUjIYj7}&u3cFaYb(M74?wnq zbwSx4P?qksu)dnr92&Z-L^-Z5HhW9=N=yb#o-^t^c(%nl(-7gFH`4c?^Wy50^prq5 zZ9h)5wNjTK$3}PUDQzz&BdwIiC~3h4ty#pVL4g|>PUL=6Gs_J>|< zsR@VK!W65gCK$BbE0^I8YC^i1KY?dm&UX0w^SsZP&$)W8mlgv25ys|8V-L#kpjNKb zJy7=E4;g=SjF-oQFcg#;pRJNjJLE_kZPnfc2dX(ar4u>n;1{_`C zS8jvDNBP8$48}E`xd@da6RJHgN~XXnI^ks6?j6U>K+=vwc{SthA>T1LO8NtK$EQ-MM|$#UI%2E396U6hkHrIm@ zHG`bWToylU;bPoxk$OCzc@JNl3$8}L^ zXRe(ZZ09uk`i3{bQ{pKb98}hetEAwWN!`{wnXK5vPm?jT6LbhGuyCWkO7FbWv=WTU zN5D{L-fbNtKPS>f6I1_7eQsFMH-1ZUw|Jy`R$8LT`~v3Ot3$a3MLIXzKF9dq!>q0S zkin}qI?DAARPT=JGY z;42~Qw}CcuD|}@Qw=l8t&MZ3jXWJ%?ibv- zq)+s1!xGqkAoDv!5?dKO2w%0vElJv@#PfF7TwIOi+^Y!-mTsjtTuKSv8EN=W(9U8b zd44@I>=V{Rsr?&9eunF)atZ}g-SzxH(B$R9*d^A7Zf&tOVBrk3m%y(i4cGF;sP)WK zGb#!M$;y@qE+E2&?Y2Yhu2!;_Bo$knPcG`5Y>5c!3C>qKdXizXX-!W4Y~M67v+KpH z)TdcvxjFPHuNOwAQ#1mfQWVOv_2(+mUz0>VAz+!U6gtz*G> zaT+!4S8_A49mJ4EfSNo7$p|L3eP#rq8 zEki!Z#s335L2xt^&kAsGuSKzP$5`_ck82Lk;p44iLRO2!O`mfj<)04ISt@C>%n?Xw zQ;XT8N_Q_)-$p~TVLa6g>wV=`b#uiIhgDx~F?PK)1ue3$KPI7TaI1;0pa+%X-jA|# zX_no9ks^J|pmK(to3l3h2dD3LevYYLoUpIfk(=rOvaJ7z#S8Q5_8msi_$Gj=+T*D! ztBz6N!JkW4UBVF<8{Ku8n2eb$beWu|KLTZCSLFc3{0kWdp{M;7tf<}aN&{uO-p06l zt-1`A|5k@=YUTyEm~**7-M2}??6C_$GvJ3{mye|X3vG>LIsqL}?nc#0+hamX^UD33 zBN^ppUP9&&zw>GG4qO_^ov-qhzRhfa8N`o`9e8bThT_A}<(=RfhCdC9@dxj)I*Juk zfYSD5pGBM4 z9-6h-L(OZYEj&(s)zB8#5+BQ0yEN%Jy^0-o&A0T4dTL9|Nr1F>op|2Pq+@~4BxVVc zR&xVR{ewDheuJIS<^Jr`!G}H>EQBtdOTRL5gxw_x`i#)VOQ{q~fL16w0w$Xnyy*}bpd(7siiZ~w< zy|vw9NkQZnR|3p@v`PeFY-=m-JC{IAOv#Bo`5YOFv>-#kAVdWz<2HHDbNXtNniY3+ z;eb&*?uOxNpcID>1Ux`VOSkPV96xw2DW<`OwAmV~hX@JcU89*_#>oaBUzj3!Lt4`p$e=|A)s{ZgA3#qxn17K9YCKI*1&uBPdu1#ARk8uw z%&Li?qxFE+oJE{~=kVd3Fkrbv_;FX7VT3g^;n4joZo7hR0;c+3h?r3rwMrUWB8r83 zrV{M0tx#XBcFOup%~V|$O@PC<;u3-xu<4Ivnn*frtc>jz}RRGO~ z6y>2kBp%j*(#FO8R`atkm%dYqU^$qpa{ZIoYEb6^YLoI5Fa-b!BxFg;yW(cC8H5th zeP8brB(Ir*;6R}8^B>`U>WPT%cdX!aAy8(5+j852e1vh-fqjAlXt5S>S!v0y^-uW? zCthB4ri5AgcHL_X$b6X_6IUeCP9fodDTTDL<0~eKed?^8qu9H=$jEPuoNFAZz%9=&o^I3NK}f5Hl`lJ?L%yj@yK-PK#Wx}YWpeSnihN1|rdrgMUZ(PqfEE|v zz|kxQF2y4ZvaUrf^B$&j=Tle|wMi_L;%x(Mr|nz^?gxCxysYvulAJHqgS1XWkzuC| z%!B`vvF`n7q;ftm9F@O>P;z$a<9638I<0-+VVS`1dc18FMvbPrqvIE1pT6trxokSIchEzYsr=21rMsaaNH#C{2buHIr z=-BjH!cTlRdZp|4k_Y)`pgw-M*y`n9oZ%EQE9M@^U7(o!kc&3C?Qd&j)(T+W*mrW8 z26g0e%wsv3(lm$196L-y5oG2ujcwNX#RmyqaSx>0l}1h=>aLK};(GzU5uDPW#cM-- zRuRGZaAk&16`a`z7L$nx4b&7*A}+*gZ=ev`L?FoJ3`zb2Pq&-d0}b+J6clZ^W-}8` ztAlSAXMjfb-Yemiyn6@~VLcdYyULFNVqF(_Z-7RVEVI5*E93oY;TB%`T>gfi1n&G& zk&=f}Fhs_Jj;Qv?@d(KIJLn1rkJ zgg3bG-gY?DNR z{U3Z`T)61>dIpqZnjNST;BeNI5v+SV6jMFWxZ)N{5c*(G{R1JFHGYZNbBeiHaILK3 zDXkmpR-Z7*TVX$)AqoU?@CfR?>7Oj1wM86mu7H$ARvr!OYLZGCdD z#p!|SMsX3`5(z^Lga2$2W0n#r%41{OlY}!`);pHnAk)W#O_-!2-QQ3x4LO_xp#;qM zGUqFrx`wS{P_h&co|x?uj`O_oCXO~R;*cs%S)lvVM6eI?7jZ1d;G*WW&)G6u{MA$1?7tW)|Q*esFFoCtX*;3fRQ&`>&|wOp>_z2G%X{8EklZaWhZ~b zsI)sjFPxi=7|X3*nu>MQ@e%D!jpZ|fK|6COMbmN$9UXzxGmMQhXOO$$x%wXJ-d-Cn z{#Q@`iH!xYxMxFj8IVhLS$a7kkoHZ?)A(-&Gas9KAc(QB*jVJDoSIjTP6eZhEe)0U zTExnl!5B|+2Z_#j3+i$xP#U}7*Ll#wXbvN- z@j4fi)RmIibZ9x+ViTpCrSPmk_nOW%npTa}Lr7GG%ibv0-*n~Z5tbxChs0fl=#&`#Ho5&T}( z)D9Am$0rX%diuFB--!VZ$J~hSA5;e#Mh+@n4AZq>v0v{)nu0r#F3=f}U~?S45r5FC z!hyTv1Vw@4tft(O9aT_`zVCb&jl|~?Ku!wN2r(;&$sl-blIQ(al0lTPm9QgC>;DTb zj_wRgS}&`uTSQ@({XeVuG-^Sau-R@Kx-Yu$zsFpj#zvtbok*`xOm z&o%(x%CZ?aE5Dp!lu-Z1AGBiNK$t!DOvihX8kd)9o9f4 zZ+Q)!qA1kLbDr;y`}h&$5%auanRHt6zKE&a2pcEmoa(kSef)?OA0Pm?HR0G>kGWVr zN62F5tQCz3O`>$JWHcSV94T#Jm5-dHKbu1|2{B2|&h6=A<2QF5vvV>T&TE9karfEZKU{~i9OTz$y|xTIgACG8LMu~n6xY5FH*P>j>)}8` zXJp93YKa0oKr`B8h>mlgySY*p#C=UD2ayrgyyfnAA@tlYis_T?a>FjBpsCw${E#r=%aI9l@>cLP*W@5Uv43%Hz^hnK;p@CZS^AW;ZlBu_FhEq&b!N1daXQhF{R*= z&Rz^{edT4~=q;f6K`FD|f zpO07|9?c~+{gs2T8IZ2HyUZzyr>$tb*K#);<$2nS#nA+qvtfF-POxi#A&i=cS>^@+ zH|_sIqPWB9pbf^sV&@pJxy2$V>XF@4Zg#gPl-$=e(P7}&s;S`~+X(!5kU<=gZ6=e` zIcrPevYnbARE@heK1P%wG7IM}jt5}!d@;Z($L=P7b zl~-&3mV{miA>n&}KUU2>;A;^xLl}J+JQO;=Ol3K@(+#fZ>nvVN-TSdn>r_>g=9bsB z{{vT8czQ}09Bds8o7d;RYvuo4P1|hUUz~cEa9n%Kq~XI^kFhIvQr;5%2`k&jY}ucNU)!Io zI~nt1YY`Q1T~glm z$;p0dK{LT$y|7hSp?iC!?g{(hh>(#r6sAU<3&6#Yc>hA)w{QJzpOqp9+T$iGV%*cC zk(*WNflrP9iSG4*6&?+h3VSo zD;pRYpp>h%Q@K`iZx=$ko$7OB=br2(FtU|PB78#EGjl5^bn*!NccL+fj1KB%MNI6R zFX$G=j(vDUY0;rO2e?k^!Lw@;ziVi1{@AME-nrTN^@)nz3VZKdW2$&Dfr(uG)Y3J2 zU2-+0X0;kSwEp|CKu^~#&QZjeB~5A$%mc3|V6&28Z^`McZQ=#>Km|qH$ImxsE5R5M zzUb?vNxr14RHU4o=eV@glYhI}RP*hbBD;$k{`81W`1bvdYC6R+uDo8 z(^OEvvXpQ(BktB16B?LP}yCq{ku z`*cRI+lsUj(YYbXd$-~B!6isM8Iy?^ToX)iV3s0& zGA;U`$ zZw=nPJA}QvY4@bjNn6{YEOl6_=$xi$XO8)G>7{@LMxpveeoTHe0X1<7svNb}uglbX z|FTsG?-q|fJ%qnpSJ~(z|3PVU%RnbGqqQykP{CGex30W%09PIDDhb-$a#v$R?SX@O zGOyS2mA0cgCNb}*Tz_kx`f;PKbNAc>oEw9&BgX?~cHPQUBcId#KJGNa*di`@S6M){ zMPaph1TIJc1dZ_PclfEB6s{#1^;9FP?wxQ(U^dxN-=J7!xhFJDdcZB5`>1Oz@l(%X z7T#WRI@A_ypRLvb^Eo$4b5zk9g zeP1FQj|JNDpZEp}b;wYN^z!zC7qe&olCsk?VM#X2o+Zt-Az6Vi?5TO0%-(y^2Q&{R z=tRc$*Bj{LtaW!Bkp%rTxU^vO)Ha|vxh-7Q-}()K`+Vu?WgEqpt*0#|_k(Y7%ljBpJkQUkCtzDWdQPb;^SZEo z*KdcZ9LuIDzXSVnZ28l@pWTLZyy8lidC|io-n(O3Zn7IA<|<7k4+^kTa&7C^#cLzi z6GG?d|E2D%zm5q=Uf);m{0i`KWOg<5|8r^iqyRACk?(nBt|awXLG`zN@;h)?J*9?2 ztgbgI{W(#*1g(t+&E|KIIYy?yOYkoghr%HBAMB#Q7Cup}V=+C8dxlllUesal7=MbV zlfcLSa+LiqbSSe`2&mN}YDrpvjL& zd=OmC`wp!cN|u*X-#Dv!5BqB*p448s5#q{vtkWx2sP%2Sx|IN5-3#tgbSmrNeyKFd z9u{>h+^_Ln8G`M_`gM9F)Htt^vbl8Mo~#|Hb9V=%_g5nY9tl$A!nY>3F5>udmVl~% zYtPt)xZ|r0J8*oi=?@cj1`LyQOw@v7W`PZz` z`el0;A5(RPHe9#F{Mnc1mF1z*T)Vfw5cPI@0A}+~lf324DTd6o$IazZ?JEd`(|N?B z%$xs0CMN_$y$9#t!oQc8at`@yiY!?z=vnau)(x!O{%B+G%XR{2z}ud*iS}fJll?g+ z@di2u+x|9aEkDyubR^aIXgFIoJ^AJnZoaV6@Q3Pn?sio0jqE)~ee)N!hB9~y8`L4kD? zvnAj!cK2(K#3Ne6NcoLTJgq*NGLn`Z%rp&!?+b5SEW4?7;nP*jBejEB>C_*z1iLEs z_?eiLwu@%hZh0A{82p|~r4tKRJa=uVZ(f&l&uo^-ZFe$XoI3sHLdi=>N7F3}8_vP< z?yA?p-Db?keZ1?MMvd~SCs~8S{FU|09xv|?`|EbPzB#e&GS|O7XgLN|7TCpGGvu-M z92&Rlm98JG{3F?XFAfKvUL_N=CeGGd)8|U1w);NlB&ZA$+Wme!CA8`O*x=nAT(W-h zv~DP2V~V_p5p4|*_{oSGK0=&-P$4VH*iUzlbIdN8~K`1biU-h*%jx2i>l4` zS(fL>zozk>k@q{_tnT@mE~Ah1$Sq9m?TI#MQ_*~)%1BUD0dnDp(U<$TigbJwwtavX zTdYxUk6C;?&isBz?Zt?aABRBx#dXSSuY7d=#Lffv>gkX)AIJ;39;@FzM?aB0V(0X> zm>oN~E8&Rdmsk$bJA>wW+WR0fP0iq6DEwZAU_Le8{dDruWz`1^Il9GW!K9hjJM-CvuRt!}jzK6SrSsr6lc@Okz)&)?$M zJ3q#V-3Nw{XTt@p!j-5XG%B|v4twy8&@EyW>X5Hi6l1!K{X;V(02sHuX@Z^kB z_qX1Z^D^yv7eVD%J$Y6gE^9kP%GW|7c97un!dY-!KC~Xv4>8d@SG(+K#d9i{dpx~& zJdrPLY`|AwjT#pTf=<~t!RbGXN44E_ZunFMnjuBx zsSksY`X6eq@O{xpga)>~)H%#shnmWuSiM<%20byji985TkL?py!RLx@o8mQWClf8= zwM-YWqOM2Zb{8Frqju*e^}kBfNW<5AL^2{mTaLDR|%vcFZnprmHuX6yvDYjGZL3flZ*<+kA# z$YU3MVvY`wHMr;DGA-9rP5H&c)!Q(Lul2g8FZn-W_Sqlny<^yhsTr-Q{cyO_!tG4^ z?Jc2@cs1Ym@e@_nIsctmn_E6Ht_Rpib@%tw_uLJ&xY=K*XGo6-Rp+#yH9AkOsYviI zz{D;+%TpN`8ho1m>Yr7*DYe4_@JEqvuC~>cRO+tmbKGV?oJ*aU0uS4C%Lg3`C!AMY zL>Xbg9bZ$ar~7T(CuJuZYs37aW@4i}+#gkWSZDVQ#!mc1Zj0o2;@=pt@?`^X)w$C$ zu05YR&^_Vx^^yNnYfdb~7S>NW0OxAefK`EE+1HO-K9;YS5p)!)tg7W|a*nTj{rP=Y zSev{;UrRom5qVwU;z16wJ6c_}{zAae8}w&a+oYzk`-n@9gHvf(?XsUBsf`xU#0kCa&ME7yNcc z`QDC$^K=C`_U^vclRm4lN2`W;IC$o{0oI)1c2K%YiK?VVLpm`_Tv~DER7RTQ;ukf1 zROx(e4WPZ+Bj@cuYaXkN%o+K+k|Lx9b(e@@&twjj?0$MiN6r|xkprU?{?4ttUL1D5 z^;rQ=&e5&(r7x;OZW1AZQF3S1XpRHQe@+6dOkRcU{EcI zN$M)NbV83Xk3hiLm?weL3TG^zmW?&GGfl*$m5TwXRT^jW1MR9Xh9r#uJ(zd0Y+ORQ%&NEA_&?qfvtcKN06V zgOC20;&T!LrAo~8hP42&ck_Ppd1sIR*@GC3qbh$s(D8jZ*vV}4RDXQg@#R042Jal| z+k;p&n{-C^7Nr|Fy!3LEspvmY;w6YcZeuWd5z$6f4Oj2Ym4$gm>1k7p2x=PlwwcNe zn(n(8qUQyh6Jc+bt~=+%HBJT8k+=$s-vh4+R|38796nfDXX@na6$?V^S?y01QuIlR zZ-Wvgw$$Wr>p+f1s(5fY$6L{%OkUh!H&+(dA2#L1OF+aGRWS3CFWCM0`juZOMYcv_ zr&*&_&_^@>`R7w{UvN*)0gb#5L+y4Nme=4Y6q@=T3VQiz&xLTU9lQBt>pI0gpc?gx zIPTaxN0RS0OU=IH<_K#$ z!zFNa?tl6G)N|@yIPs^n)T9mf5U2sJRPH7JZ%`4Mq!^nia}dkEw@;frWZLC=wearF zUFVJ17j5~sbA^1`lPMq}0XQ?amey~bge`JCHsbat_wu!>!(>pko<(2B#k=pcyk#mA zYOOJl01Q~Zl`0r3!yQ#mLizS^w7&JAYi?F!TNy>ZPc){jb>y0FY@dq5CjWye2}3Yo zKCK5@x(+8ng^|kvL#^0o;=Mxr6Td`D)1idu6%p8_>G;LQxK_(K=DlfWqt*;|r}Uj; z!VOp>h$?>r{#DHnhn zojMDD_CzvVXPLsjnsP!VumBSoQXbXgp{_btGr@&{K?8Z6dRF1-HU5W`vKs}gMFb%J zM38IBo#DUHs2rAIgBj(aj%H{ih*_L?Z^wrI@NLr9JM)l&w0pRpSpM!ez2!=_R?P$l zFh7m%Wb3Uym3J{`ikR{J^|z#mJm;V%GWd@TVTaSG3_p#DvwjqXED1aG{$RBw8MC$_ z;(tlOhptFJ7EvdOvjpLMIicZQ=>O6buzNo&g$o(;-LC^l{LimKj)p|}ONP&_&!Bs$ zBRNCCt||}0a2Px{puPI)wbxG`u|`9*Lykj=Q+3w5-@Y2IKflW`I|wpZowGpB<@qyGz{fLBZ(O^dPb5Y z-G)P-P!jrraF%V8zS}1+1D!r;&^T?Wd&&Q`-jSvgWZAsyvgjB>Iq5gD`0FXELEq&I z^6bx^GcoA%H9VQ-)WY7wF@Pyec?U@0ZokK8W;XM1OP3VjCBA03xs7MAz8T+_OCvNr zRh!Bu;$5m-UX+7bC+63Uj3Y`9ynK9FEsU6qe<7vi_|=_1G#)Ie%)Mc@ybKm%BxSYl z-k6tc&n#B*<6&N|8S1T;4Q{+NW}}f#@`86+3Ar0(fa5r6!}C0`e3SFZNr{vz}2 zr)Cjah}rb_ep;UtCuZA^+{opx^{+ho%$!_dWy z-00r=XD)9ueYwBBce?1-%|_IYB=2!=>cOUM{xR;om?xj2B1hzBaO-^)US7H@jff$5 zL(j24&V#fL)6lJFPcRxml}Gx$a%( zY6&BG(?0}$7?~OW6JTQ}EOn!TYrhzyTMP||5r$exv+8c1$N#j@8XP4EGs=ooTCun6 zD3R;O-anY7mtVAu7_C3}FXVjsgUPOjk57r`rhxcA`AQ|vcVDV+g7@98)qe?2rF-mX z2sr>7u)Kfc3Ip~r`h{({^eVbkua!zyJ7C>ja+KIyP;MEtM1T58IY9MW%c$R z0Hxe4ZHyr2)Rdj?x8rumd)K!$VMXe1OfXL-K6_7;Uz@lKALsoIXI>ROb9cnsPrN>s z)EXI0GheaQKTXS`kbWSRqG_4o015GmFs={{jb}-+(2=xL{TYmYORe3U^(*>w+}&y` z5!;tkHhL=`a-M5ilae;@BO_Sc+rR&54N{}~kRO%LuN!vg+m`kI+&x*lfnFB* z)8$?>hgF5xAgfhc_V$0m1F5~`?ZO(97X6{ zJBKQ5)Igq-)z8{J908T}m5w9uPWjA$P4*Wzzk#_}@o0LS90U^2sg0A7t8T&+5Xm!| zQL0RBubY{WNe8rL<@TgbG;yCGWQ;|49S-AHga)M)?(zSRl1| zzR5>5n-S!iV(gg*RPg#6LSZSCb~{AguF%f$Ka7Jm0wjgAhq)>G53VSajUBPFa9dQ$FY!9yGz8GAhj=IgLPMj2P=e$$vo2!) z8p_LrkhJmQz)$g21D(+ZHD~R$0|%{=mOUQWv_f%mgau4&vFh3!kZf4JVLgKmuZ>+e zQ&c-k(#o1}V8onnG-~4DlMC4B;6jO=|F@Oj@Ar*_3BX+H6J#H{^^aZFMrbM{6kBB5 z4!_pg?~JJp&NtO?O&T)DXJ%PmUx{$3Zhsl9S@*(Rn#3N{liAj`z=Kj(QYGiJDa=FE zRuM4vP3wF5%Z2lZKa;ZEww`a;BlEnqi35{HtOr9JM+@Ahp;HVz2Jvu7r1j;GQIkI? z(KVd#6{>xV2RX&IIYd;Z($JMj@;t+a-PH-!UQr5u5B*P2ckO|ZsX#TsGQ_|YaTyAQsUQoJPAevskCJ!r|qJ4$Pb#st-9=sct#rH zkR-xAw(U%7pD5S-JRNb^Zz8S6Og325pKtKtM(cS34h@@dtL}SyQgX~Q#o|Jb6IJ7S z6UTHFl%|}Ig|Txipttz8n0;aI+XFr;9;{csGk!l%S|&_k|6R=!2EVhFRyyG@|98ed z%1zX~+4p$n=kJV2@lsF0Au@8_u@0KQ7bSKbcSvKC1;md8v$IAb`OYn zh@ZP?Ct1_CQT#a;XcZ}v{yy?tLfdPGfi29C6spnJyfRyEOwBmBZ}<|FoD)qbS<>zo z5{_%=mV+&|K1pLNS}sDx8IW=>x>1N1n}rgZgJYSxEzyb1c6JQT527PCMiul>8+l#n zhM!NfuaPk&utuc$6c_bt{jfbgu6nic8g>u^E6JdQA#`zQWOV7V!P;|@)0SeKtPdHJ z0NJB_ah5(?mx_H_5BhFs_@}CSR*k;7Ai!`baxcheCz$+kkd+~0^9!U!L5Cer-;y8b z!HYlru`Q92mQ)!*%X4rMjTty?OTl-q-DlK379=NG@4@$$3rU+d;NpMae@54@XLLSL zKT1&{^PJi6Znd4zvg0{Q#JNPU?D)!me}Vz4R-(53Ab`i*qM@FV4SUJ*FPLSI8ryhf ztJED=EwovvVU_fizLg|5 zo~LwVVz8oHD=uFWZ!%@Wk@vs%L{{z?x5M1`Eln}brG1+}KDpYA5B~i>F2Ow0D&)wi z@e?c;tH=K&*PJy*m7`hguAH=dQ?M{~1hVcl{D}fxx?I@Ix*9CSZ}hypXqh@pojFzM zr*mn9?`H|wnR(BaMy9}?ZyM|%h`RDjzb9Hf%iEpGa-Sk?-_ud*qD4O!W+s=CZT=#P zjWQb#o9N2>Z0mlx(LHxKQyU#L&^=JSm@nJxXYs<5^)KY|5H9*Itdw7U7Yv{lbyHr+ zef~K={bK?$W0%yns~V~pQV%z_lENpN)F$;niU=LD6u6C$71e;+q?qR1{3Nko?QLKI zVX*^$8%n9&RBN+ZZ-ijOC!BPYO8s_uC`}77v06Qyrfsb0wPE*eaY+kaf|~AkqJ%f) zD>x0;#lF3!%3S^z!ri`nePCXItkx}-v$oD>BV{g#%-VS8en~#hE2(qB%&cG-W5CEz z5*Qudu}1BDj8^^YhjAEAmzWFi+7h+G>gL~R2hhUuN{eXy1Acz>NdzED?fp*I*g2-} zn0U}ag!?^FB`!t`y+fLGULT`MYl9!d@f-T+L30A-8Z=<+4i8RUT!AyQS6pOTFI+~D z4l;A!=Emh3Rkz}@Vf;MjfQ~G-`~g_pptCJ6Dkh_D(vA8dO|u)sJi7Aumcf9T8C-mQ z*GXHuL0m&;2z%2viB?V1l0Kg&ZVv1D>my z%2+^ICsOU@m8-MIrdrWTfcK3*Asw(Kp_Z^VZpryk1JqoZ-^&q-|9n4gDHa%MfDsSS z_CfM$)c9)VJ>2k$3*@r+p}fiyV}8q>;dVX7=J8 zUA~zW)d>$9{N})Vpq1yuNe|ahT1_J1CkCuD?OVn?Qq=hyFEGf@SMD2s4Bc7cp5D|7 z6g0=p^5G>rJa?NiVzM66bz|FjBTPLstdU^m-V;InYm5xiS)8dPXiT{d&an~hV{6E! zeyev<#%=Xdy)n`I5VJga+1+P1G)V;lY?1<_=B@_c7C~hqCLBG+vZXbKX@NAX!&##H zuy!OPxR9Xup_>3CZewz!I^XVUslF}Y?sSSNcz`(tSD6Pk;h7nadqjL#KOHVLo8;3L zN*Eg3b`!4U_4eP33lpHVdM5MbVLobfGw|9K*4{hPy0ETo;l`ymGPa&~Mw0=KmyT18 zL+BRMni<#(A8B23y`Idjp{VBtibtV(7~2Ps?JR|eUzK@`S-ELySNtHp3S|Ls+&5mL zKIr58?fs=%*}>{~4Q%5!6jH_82T`=ITw8|ppLD*ErqReZXWmc=xB>;;B3W_F2xI3{ za=u+Si_lrJPKt87<}$1Y!1^M(b%*}&9{elY@^18ecM)WgGjKQ4N(IOV7TixTla@K= z*B9AnKTWzMaxWF=cm7Inc}sL{B@P4Qk~W%dO!x(8CYB}I1?1<=D($HUUnnVwv>EGX z^o}9m@#(AwuOXyqg74~}L{b5mz+Rif`;F9KZK5KS;7#->H9Kgck-g>fb9pZ`(ws_C z9YcaKa(7qGB!Ne4Jb#yLZaS65zU|)Faz3eW)0M^?7$TevTFZI*Ft1_*Y(%{Z@ICMv6YUC!02QCve19MvHwod&n&*IFH-+u9~ zm~K5j!K!8WFhYvBZMjKsEioie5I1s(J!5>U-`v;u=SW+#X2t@%KU>AZp3n-JY3d%o0MH#HrCNZ@a&`2#E;TyK}_?))4u-_lUJ)j0Z%q|HU(`Ww4yDc*$&|G?_I{ z@%ByC^S5v<7r1lk+bedQd6NrUiHvlS$yQB+&PQ|}K`4de00pf4XgVX8Bw}V2auizO z*6&HmgZwdHG$ZP5596uFlvnT%v;P{xYq4?oW$I8|$olLo&AXYdwz7agNN>Be;|ycl zR><8&2flkT@ywimp*4?t5cV9?+6fq;TODHN;oXSdUd&^VWP30*xBlf&D#xT+Wm?qT zFz%qalyr$>rXjKhl=2Xb^GC*l2DCDgF6}x3EljLkrlb7?V=-uO0r3hxwyu=}%+uD| z0$N1pESN<4ywf>%58t4;sM!JpdQIL3u@_%sw{|v%9%0$3OKWHi)cm0vy z&!zsbC1%voRIqnxSD*l=r01H>y;A*;(3#q}+$5k5VqKIicckSuKgib87NX0-c<3OK z634bPi;IbHsRvE^^J(ktG3FPatNH5q0*{g`#TjFTX8~L{TvmPcTdNg)ae+-!p#=>O zrR3sss)c#8g@}MCVX+)&dQ;e}+EfsCQ8Hftl8d4CxvP!&tntCOi7D6%R-tN8O9}xc z>aHrXfCt7lVVv{Dg{_O+`2r0=h^33nf)z1x@4>Z^NJ3t zdoq|L&gEstgyXUdA;SeO;fxZ@G?P$;W2V!P!1Yx&T}}m_&9tB%otrB}FInAOd=KgA z?2XbAJ=;(59QRV?>cVGn&vXrp+39>x`4r7|g?WW~%_@U6QDdM}xpyM6}y-HoDDF$ed`SGF_tR38AyT1>lb7dpC zl+*`vk#;!As*B8Yf1}o#UWYT`7rj2V_`9`URgASmNcd#Lg%xJOZOEp|e{unZ7`j`7 zNM+_Z5TI%)tT-;}ZE|X(R-p@=J~%g@VrGTFfPAk##!|tObxXHQcK-B4%PgEiwLAZW zcT5&}3AzZY=+=$zp0Lqg;szA!Q=C6ARS=!-N6UgzZ1Kz+B60o(D4jRE^y6}NTIeQY zf>!mKK5bCKR5=yWvCwWy=?jnU5%FTN2u|X7er{9;%tEDug_rq%T?mWDP8R#aW!z5_xRK2 z+D9DLt+R@7S6-<0olAmZXAaU!k%)2(L8u00IgfBaiVscE&8F3_5czFA__mGEI!vs! zpgsNu417ZJ1nbd_YK zJEKHt+w)%oxrE{d%{(iDb$e!*t!N{iNOzHqJ-H3OY-=(}km?f}S75m{S{d<)W{ZeU z))f+aZ|(Rs@_^QG0(A6UmgmoU`!#C^`sVU(%_BG~z^HcixHcwkZPNO(RWZIc*EVwY z6;z8&Md4&eYFGZwYK&@G4jDs}%|`QHD<(E^^Zf^3{*W)6phx8S8(Fsi20GR<@od%% z$Erawb=tefRwM<4d1Jr6A2q^!5oX^75N%`vg{63K)dLN7?aEHC+oJwUrtisx$J%;= zLmHkQShs+)oWiN+DRzLU$Dx0!n#h)O^AimoFPi8^YvfIl)rl#=&1kl*`uL=g%-Yru(zkE>d;Fp#tlv(1NvKs{f>6#{ta3wCh>IV^owU9ItTk-^VK79W zYT}lI82}wZ!VT1U0Q&yl(9gyPN%FD2Me4YGyM|BA9wTdD-e$4o8e7}vR1p3#)xdNP z>3+ZjEDt>*B(Dh@eV8WExb}9k!m8ug=k&E(_BFNMg6#ho>JcXa`I6 z-62Y$U>0!-a;|Mdq^?ts*4XTzgv>?;_1|v@`Ys&qzI_%hs~JlEF1!y>fKC|2g~$K( zD=ys18rJ7_gC8=@!N)QWAJCSux84gPi3w>AL`ADlWcAJTX=59H z^vY;PTt67Vkx*e0|4{w;X3i!{tsma&kx22WBA$2$%zCU61l$H88;$`Dk0qu`jjvOf zVUCG(1uT7S)bEr&+%SY~bw$B#$Cfz08j}SZwOhbgglvx;oL6GMd@KM{2Rf@hct0p& zf0`0^5Ub?7vgNOrLlK*fsIsjyh2sD#jhWiTWy7H$AU_3Uq?wT_)UUn8n-dUb(9dCR>V>%c_2YP$O7=5$n5I?|Q&ff*I83DEm`%32f zv+j99DE-6Ey<*jHRct8dslNlojvZNs5&o6@8wOdR6WJ>kGnTfLl_mWn>*zy+RScVa zPq-kL_P%1_if5Pvb#6>tnytPNH?}JPDyN+JdL@Vo=#7YcT}-y{JAfH|E%4PhV6avt z?Jlpi+(hRnt4U{q5(5h75uZh|Sr2wXF6w^mG?m51VY{oApB#BOwjm2iJUHV}|A@$* zeK;3j!W}Vt@aO{|>*tETgFXGbxL0B=HNwNKP8WG1+4&nu(-e=Py{$Z6xhs?Faq4=e z(w@)vTdNPMhkWeP9%ch{ga^sqK_rbm$I}0S9;TZN6UHiMG9m0(ZO)@LzPoj~+<8jR zB{*v?RoFTw?*m2ayyJ-`baZ<>b|=5RRUyh6Q8Dpt!#IAuUTds9WBHs|x z)v9e6e>_IGWk3u2%GC3N>2pQ?yBmq}k2uX`a=C?A^sRrmiDqGn_uOqh=b1&~vnKv7~!KRhE%Z3qaYQ7fy61zPcXrknm~fPV-9;kpj86jRa*=crTERX~BYYfC4L z`_^TMsQioqkBtG~>?^Wg5v8M=>VYeL)~sE-!_w)fAGuCGzBz}89aF`ci{%BkiU8=I zu!a7TmH&H9POEB9{f7g+TCi?TYP!okfMMRqyP%yyA56WJ$dpDCF zvi{;$sU5Q$P?@b(Y};HGw5qb0yI9t#F9sI+ed|^#SBJbGgR*sCZ$0raR^?Y4GXozj zY>{skVr2D1D1OS#U*-=0ggA3k+6WTk|U4uqdR zkvK(_0P7<|$+A!LXma{7e-we~J|P6T@0%rKbZqY>QgM75m+0H^S_}*kUw`N&7<%Cw zsza)2*L}UzOVpcfAD`c1=i51%!#Ic>`ViG=3&eDGMkg5pbJ2wm(aTUt$5S_b)pdl% zt#~5C$xnm$KXZ+s5z&0xecb;8X)nGGj`X}t@kF<8_bm*!-ftV7LSGbqF-BofEyiuW z`v17NB%wTir6%-tRmf&vD?lU-xng=nwqn_QHg27@L>#v}(umCkU2J^f7PAce_Rh6u zk^ECiLXZe|&I1RZvo^H9f+fbDlXO{7TqhKW8&iMtq*EYj?SG&nE=`joEaZ(RMIpvE zM`X}0mw>K#`d(VE+n40taY0C2-{5Kl-Sh z6Mia3dxL-HtqsbSSVlw@94Wc_g~bARm12*rO?~k)vXTJ?`{;sismD@+bnH#7>qCTQ zNYH|>*JnZs6(^6jPO?g^s|i(Ol#5-dVBMpv^1>b>PVAE6fkX&X9^o%6UU1waEz6#7 z#(&J1I|OMC91!J{yY_Ahn(+-2zm2det+V$0+%FxaeeXzyN?8_Q&FTgsj>+q zAToAn>#(4woY&O;xS-1NcuY>gw}vO40)GNi-;-h8Kp^u0ru<`x%nMAKl!H^5Ek2Bq z;x}jh;`ij7y;!ZG1l61v0R-oW*1%=to;yWPky-Qjlb3TtrNI6m>gqO?Rer%sEmzId zV4eOs2(%aRGXXcBDdMx}v@jGg2>iGr0^@A&1VT|j6U&g!9i(0e5Or*kh*;+YO-+o#!5^&uZDjChO8@bT%h<)Xjqy6;s zp}zEcQHf9Dy5IAT3+I0Xv9?N)B5KJ7a^N()zN^;4K;5iEHaD|du+lg0&Ic8r7ehKn zx2Zk#shApSL|Ko4aUd&u>v(o({CT$kQ<6)^Ji4-?&dEr^P6~=mIlpfFPkPcX{yZW0 z=oNOw|3KC*PJbDDCCP#D7r2Dwg7=j--ukW0{f#CG?}(f|7{WFIa{l#Ziw@@YagK7% zs-{K4aXAHD`XJo#@}4CPJ7c#a*tO2iP>MFrO4}8fZ{i-)Ju7t38VgyYyq8~<{Y?7W zd8lo#;Mpn)Nsi%KICw%_(6~H z*wW+mSnY%87=;Sq6XUW`Q%%s6txV+Li>X7OG7lj5&&kE{*Ph6I$lCSrf54oI&jAh& z4Rh}Ni88-oKqjx2`8-MfRUvdZZlGmgN0fh6@8!SVn^K7{cilc~AQL5A4^EPqS0C-T zh6bDnvrl?W1DH0`t@jOEupp>k-aYl_n5wG{kkzjd!c0SI2mj5uC(JSIza(oXVWwF_ z5~WZ&_Dku;q8uuJKfQ_)Wv%%&3i`b|_Pqpjj>1TL%BF9{?az(|q%^&;W$|2&Mv~j% z3;sGuFgS3?|8&ucieC7qGScIBwRJhp#Sqf%75`;yD?CpcsUS&glF``99Jqf=8j_=;BJT<6^y^j z@6GjAXJJJOQ=!h)R7Ue{0s>Js9bUzWemm*Yh!O7A+@y>DfIO`pb>bI=c|JazTpy@; z;Q%tWYyXUo=`|siMhcu)Uu#O}#HI8*AOUf&Y&dke^ZRs&)P7Ar?#2rP<&Q?z`5FS+ zvl$~1;9DpMbZ^f^(ciSMHu^;>AjwtXGDJnesFb|DL`Hn+Lr#*bOF6bf!(@{=Rf~DTA1YW5*yK43k$$_AZa-Cq?`u#c57-C|uajS=&DO zba+hv4+WhqH}wu_zXf?j4YRHEJ^9f*)0L*!X@aC^<5qUo3rdYZWT%!apC3;Yji$Kf3E~>IIQQicOn z{$ix3QRywrHDck{$3=ttR-#5i7UN$2i^ew&rCA&$8-Kgi#v}+~+Tq*@ zeCYaCR+r7myt^nH5|Mzl&zFm4LQ z*y6!`LqhE(3Xd;9+NQUFbwDCWK-RuJ-E_v7o4E6y*!^e1Rp$e$caU1|JMD0E^yB`>jH>4hn5BIri?@>P1br0r|x7W%t8=f8jX>YkO&AJ-m- zMaM=YFf6PYQpC9_43cJ7;-$f7IV_#pal zE!8AKp|cp~CdB>5Cx*lMxv@f|tQ+me`f}l~hvLZz`OXKM1NScW^tsdmiok?D}-5!Sv)}dAJ zajI@}sCgC*1KR8>zA?g$SN;7#9lzSJz}a;;NRrbuJx36_&a1f%9r(o8<5c!^>i!$e zdFmlj$0|8HUE-Jov28s?|Ei7jve56@jjpKGcO*6A`?Ln$nFU|yPD8W`#Ev>#xZ9&CG_#TCDr|Yb`snxjA&1fkCi(*YLa3C1@bt%9&A@@xK}`&tY*{ zLp7|0s)NO^!4bd64>U7yKC;Q(536kJ)2751K3__0J9;P!b>Xt4|FqZol0{Rl*M^jd zhU!F55VcII$%@D3shd?^`f*Hb0uivczB@M)aLq@WWEMwkZh7_hYv%oqo|p59Pxy3_ zCxieMI=S`*Z0g^tviG4!?(zB%2y#Xr9+g`6_8IXSG8a#EIjFPA);LC*qq%WC(tFk) zBR=Ue!k`}2Hqltmawg@iQ3o2%o7}Lmf=I}ztfke4A|I*UJ;&FsD+<7mISQ8Cu7V3| zB@Eoffo0`y4*)+~lg@#?ca6G9+I#;tAq)TG1Me5DjlRyO8H(=l(kW0v+V!}1$0~!o zMY|^i-C@2l)(6;Zv#y2E2nHsEw1YMoQgFMc_l zF5!|v3?Kuukf;4^xtjOR_B`Bx_GFyMpMmbAyt~^cJo3*YH8DWKoi-B?E$r=Zt2Wa2 zBTZZY@wSM57tvf1b6xt=pxg`S;S=?`IBIo4&8voV)O}gD$84nU*l?P|yE`VbHw(mc zl=+6=hpcrWaMxGrzguQU#)b|BBY=QH^Xjg-a$|gvXEj9|a0#RfM= zx3p|pQFY&K)T0Qz^2@{qse?xq#)`%W%~seZW8mFL%_4~}z1`Ajmg&~jUlarEm**(cEZXzFFHG?Qj>WsNS zaiMOFp9JDD2S`wxu(_0b4BcP!`Z4;}Cqj_35sKswT*RD*p4ZDUC1%B4UP9^zk-bIn zh7#cxPSs=eI(7o_XTQatN4rG`>EL$l+62>TgaEZ>+K$7W#Kd*P30E$?5T9+t&in`N zAJGMR0ly`UqLn|V7}wsC{C3haYxljsUQ^&eL+por(k4|}QR*7pW8eh#e?NAgUB676 zF$lhM5jsv4KrftsviDv#b@uT04HewxCVdc55$Y7QcjcVx-k@c8Byhcv&ycor^>OJDMx4>THmjS5YQHV5w{L*Vc7L zSOaTwe+ft7MhQAH3xo;i$m52C$K#kbgj_9{y=;7791&A~PC_D(WZ;5h`=d*;Z?QK7 zQnK}$2!NJLZPTRdBJG>zC+~&AU@9YJpy|Rb7nS+z++i-68vgdC^aqfB768Xysi@CB z){gG3V)Tb@RYKPU^>zO`p2}Gm2in;I3ddMTF_N6}_cdVPlh>)z!G}%%DE8>xd&K;! z=bTKn{(55wf1F#2w_iPCVW9lRS^$cG>oeOdkCK078Caez+HsOB8E2hFldWV7G;RG4 z#7hslZ||R<1OrkPPn|xm6CuhgY>`BMeX?ogI$#I{ikBMAy zX~SgLK}>t&ErlYhFD?&M)*4fM(Fbk~`)V=srk;N+bGdNsq&(o5`N0SfulMD3Ogv1Z zu^S_CS438iKicUV%uo0h@Gc9xSOJp`o)zvF*fz~RLnSP1RC4c};d=8$C<<`8aGu4K zwBP|QUI>gn+7cH4Q%U_-op=!3s3q=hoIZf`I; z7UwTC8_sVNG3^hXR{j-S@o=E_K>`>mOEX-I9DYRGo4q~akRHFh%a;bGFqWxqFMWLq)S;|`|~!%yA{%c8H(sD2{#!jHNOx67#7Q-A zd43i7^jM$&gTscR?c-U{RI67_A-&p;uTRF4adQn)SDGjtNqI~Lpdb;Y z9?gR*M;~Px3}c2}kS-^v<7?yc{gsi^GL@J>IG4aO-8BPSi7so(-886mOS2 z};epRc6r4 z&FaH>bTrex$$e&G(N`L#a6tv?`==pVW#*r%d(*RJjoY7Q7dXlj)9Hwt77_~q(@ZM# z*QYy4$KB^I3n6=C%U7|F-t3*NYZvj4qrf2)@v*Q9lW4t}tx~&LxC$D>$8>T`Yh77p zTe26X&OaG?^@B8t9CVzsL*|lO(jYg_KfbeG40$B;k>0TVPUJ|pDzFdg#~p-`0gKMI zrL}$^;XrvuV^42M$?EO0+I1m)m^|XMzh2!sbF<>wBrQ+<6V2YqRR}PBvjrXh8mB~^ zm1-<#dL%P1=fxeowGE&d4#&jo>~(}bf9x3y{&VKNztGP^sWFAk_auT&74|Vx1o+vK z1@zZU8&mK4=PCDa_?q|X$K?XFW9;)EsPttyCAxnybVp+>#cL!VrDlS_ROHt_a`Roc zsD-x-AJ6bJ<{(eG!2UwuDkShn{_Op~v~owSww2mIb_kFq>QX3KVLw!$KX8d03(xF3 z=ox4_v91O?gU3_wxWUldx2!^q0vs@2?I+5bKWYwEsfyAuBdQbo+EPFN-U#k-x+wSZ zUX+SXFbD}CU7~7U|2{AA>OVH5#0a#HGN$Ac5$waqs(9@(luL^^*-K;Y4%%mKr5dN?df-oF=tqQI6P zXjs?o*;mj)5lJ$}P#klNx1cb;rsqEpAD}DhRaUj}$v$Rbyjw9AD%GT&UxI#z9yfZL z+c~d;hbIs<20jEo(Yt#G5*e8YSdT+Lss1#706?Gyi`~K+kUPdIZ>Smy z2KgN+19eFkJ)&&iy+40%TaXKkwBhB6z$UlF@`jmvC1rPWJVs+>oWuXfzB28WYH%Un zXIY*wshB=2U=Q)WfCK+4ghxO4*gB$CyjsIjomQ^c(Xk^0luVnl(4Z6w*tuHT$rbl> zt?&0@P1ucH_-yXcvj@M_W3wW`e$F}~Oy~2Kk6FjQU@X6nAA!DCa65!(irs8HVPOIT zxyP}@UV_|5LI8oe**6a}$?!hV>V2oYBO|&Yz*qk6%Fjo<2GjdGZlpq4i0-sUkQi9% z$Vah_Wo+O1WB%GvUH83S6nbJIs!$Xs|a{|T%fD}fN$$9U=tb`6(c zGW21(gjiiGZl~LyR;UB7H#Cjowd>KW3YDfv7K5nt$)_n|EgfCJ=L7*b_5r9dvF~I4 z#+H`%BQJc9+YYP+^z~cm4YDvfqy+|$X(W{3Xo!aIXhJ-+4)dX5Yn%D>j){b`Mt?uI zw>k)s>~N}4aEt!*BOi;=R(i`$Q1}Mu83es#23n532lYhoAJ`RRMf61kr%lH`D$~n4i*68|16VJ zqiFa-WwG%vH+T$6J_q`-?XR;MEu<(U+|A!t&u!b>EM!vTlJlNd=MMfzTw~=8&npz` ze){mQHxyl95<4rR&wI0E8S0EB@7N0IZyw|)V=_14N3{BiH5Mjq2?|S_<>uUr5rD*` z4yLs&7d@Fb2w?dA(QQk{-5qn3iQZ_Gp}xj^8*K}?lTRGfPQH9Hu4i2jC?|bm+_NBS zIv+5Hb)XWL=@MJWlxCB|{LQmge3$J3Ljk1HcJNp3>GeZeNEH-q_CTs-XeGCb%Ag@t zXRdZUJd`ICHa#01In8|8EYAP>}fs-oJD1Qwd}OK z*g$pquk$z%&k?*l@hLRDfqf-5ERY>chF9}E3IGEVU+oO^bQFn{i$MW`nehVDKN(AK zYoFO+zE2WH(`us;9wGqO=thMJS$B)ha0o%^y2^V8pjNEZ*{+#?3s>KP%ELiNj&loP zt*yqn0D;W{IY#ThF@oByMzupJF3zOPcajqPo?G<(h<@G&>2DDY?2E2a9sl8-%BQ`c zTJG`V?ovPRGj66OCxqzhuI;1jB~KXy;8@eb?FlHOKOh=FK|2sxvChLaM7l->Va>9M zAprdb4U9prxn@ZQhrNe0SIbG&5rp%6$3kuL@Uq1hMG=)?|mo0z? zmjGT1)hQ<_ZTJ6zEpq$u(b)yEj8s6?bXg652v-~ZFPH+j*KO)u^o3;+kzUB|jMp4Z z5j_!vEOMv~OLKW6)bd&gunP3LK z71v_*P-=wRW_cq0f1s~}vg@3Cn#l#ooKT5AOK&TPIOkh;g2V*%Vyts4*qjzL*&qv2 z>vGe3g(pj#FcSP9C=#op??AmxnldAp2qwwiV+;b3AJYXl6+M?G9b3&6nCz?Aogn?M&sWd+)!J42*e2~*KE?|* zHGPOQ!K>_af`R^`*v1fW6260Q9|@3SEyg16+x!g+9d)cPRtzwLZy_)WAPQtLaFFcn zYMUjHc7mX0^_xOpEn!OPOQ()|`12Q;9#VhKeYDOZ_F?6H!7rI^#{|Qs=`FGCB+Y3* z_$=UuN}4etOUHjY+}2ljVcEzLBAYfYXa(6ylna)QRoxiK;i{Jw+@-g!i#=(Mxd)b8 zKTdWbN5nq21rX5$dKL5OVd!akMwXLMvk3^d9AW3)15f9pu#*g_WU{y2!)2Gx!aSDV zk+$}+pAG#%W21P{4nZUBpdi4{mq)n0w7#Tbe;L(MWp#Uz1H zTL8=hEUzAO)8JCLjA0ga#tiVKy7}w)$M$LuT)6rhPS~K{uopC14eT`T>BImYmQzAd z$(Me*hYRsgU%kxYz*O-t?i4C<+&(_7;$)3`{dTBOYgsw{0Z*8TOq`XaFR*`j0lL^Q zmNrZXh5e0H67mOm2g{H7^#_$GD2xe-sm&f8;~X{{OM{>U4Cd@Mh*Mc0HP7%{tv%-^ z@Ku5)eZZ>mSDDG-pTv%zNtQizhzlX38hw7il21m?r<>(WSp_pp6{cX0(|~oDEr+5Q z2Fa2D!P=5Tz^&=`{J+Oq0idj*+}WeP7TTT>e~Jk;t|FhVgwXve#XS(+0Yx6O@p>-r z97ES<*_puF=vWwli{1GAXs=aq0ikGdQA5oYHw@%k*juArWn48fc95%Omll_vHyj${ zj>+UY?TPZZ0E+4uKXLp$R2P4|e#Y_?A2xEX(-F=r`S_DRKo#q4oH>vtPI8?%i? z^w%r-nLKP_;Na_XG`qk zte3j(gxEBFA@npnHVnsLmEb!X+FjI9vcY)$`1eESToR_P%nrd zRGGPSRXzq9{Tc)%2wR##C&qPN6%u=v*fz;beEu>~BW?-!NL}|zshurW0par-Dd69O z6hk7ha_whBsEv2>9PDhW-%n+)2nt5@b6tK2&W&kWqZYh=;+>Je(PAM!+xRZE;%I$6 zov~R)o}OKZ@J`;aZNTi8Bh*HN!UXz0|Jv-Mba$YZR!RW{^*%+ zCk*N_fx9@1TU3>Ri<=k#fz6ITSdc&41_dB|N)~MSm}MMruM-0eh#R!8-)wz%ZhJ(N zoE|a?1XpJKIkvD9p9={Mu!t{ zW^dc{<+Bc&1NC`9?yW)q?}Lg^%<<;5c1#xW7`UhkHaEHzLIh#e(i@AwW*D4*#;mG? zixP4b<+ZU@RssJ_C5Vc_Tp-mFSSkyEN44X+{$#Hx<_iyQ^Kwy@px2t_KJ zdTyCli-s``Qi1Rv54l?M0nVDI{ivHUD8hE#rJfr;VNV(IP$zbfh;_D0od3N|n$ zL(&pP1(X@4f?5nbMmwnV5ie-3`GaB+piMy>uQU(ll!7_a&s{$2Q-?Xi_kA^4&_U9~ z8r!zJtOxOZJ0espNp(YB@B4r4jkxX%Kaz$tyQpU~f^CNuAo~X&_YM@}xxszwyEaD? z($d*0gX@3^X7%R0Y-2uxXkrhCbx zalaJ^wXHup?cS^^6QU}s)fq+~8Ejt_BY16y4YY+X9)}Ve4r)QgcDFyZ?R}f*#L@~7 zpT^Z9b|IEJalI0TAyMu?t8ZO110x3RPa4CmAYbB4$G_kMsoR$I_lXz3J{jTVMbF0A zO~Z~%wF7K?MP6{Po)sz)7^Q*KjKcu0 z6h?Jl8LI_~pdJ{HX!IOv=WqeJA1=Of!IV zB|P^Zed=w)v(Q_=8JtB|ld(l!;~D+KbhH(?H=6fev}8$a-+fKr=8Fbo!XWtTrz_co% z?I~?+3;j*t$G4_{VgVfNk#ZZa2o@Oo z90YTjDd1sdY#V>W9JCH(Aisbh-0!hwR#40qUB0T%%tBKqFxA*%+6q*`xnr3DiPz3w zR1}_}LXbTSlVhmpC6lkl-}^8^C?g#p7a#`Ecguyy&iyAi zRMejeg#iX3v&i^ZCG-3op9S)-RKe8nZEt@RQ(pjs?r?PpQsi+WTTl9lYpJE94)r&{e5s|3%P&)wg5RON5&rn zs7HAedh*miLM;|n$-Zt7*V!X{D_5Pol;hSH5c}m$3!qihe>OBXppbJ5O|66gQ5T`# zC{_B{gu7c?B>-|j8~4;+IzVrG#|ljGl$G{^@7mDk$NCULI@akRYf^;Nbo5;cJZ}}< z2Y5B~>~E2^bWUj?&isnDuUbOArt?8Y{3cymDT;@@1P?il6GypyR;lw>k)w~ zl&=tAggg!q4y^M^4XKmtFop$4Bq6Qu2H|$h-2)fvF(5ic&1snb{IUuwj-)MK#Zn=591i$2ch!z@(#oVJ>V(X`3y7Oh=W@Jn3hcPat6ocTTlV- zIf%X8zlOOU6gux#uRw~FL>l_qyEIyYe3E-Xp^Eg{hT%) zm=KrZQlcOmln^RcWm8ysz}N*}g^ga&PGo1x&Yg+~+I&k9nhe<>hS2Bx%rrLq{mlp> zQv*Z?8*;1k-qwMg*UANbX}E4)AR z8QdS)56MiOE@)e%!}NxJA~(K&OpVs!l%fG`op%rbJI^wK5HZkqAeCPNc0rvNiE+`1 z($t>RSd|H)LZ<;}ldhM`WR+CfIO2Ixd4O-ADIsla?W?p>;PbJxJYr`CXtwfaWFX^d zjAK@(kT!S_3zXT#3LqRokuit8gDsf8&QHTD&|FTlkGbil*w zMKd202FGCM6gr@gR{8-jiuuOb;|(N+Q7v!8j5D2~-KdP+NSpnEn?T5j>jew&*baTj z!S&Mddp!smMmv@?^!jm!jyQ~&-1=l+$-!BTPhvJA^5-49+5I`%#1eD&7yh~|cj>ec zdVx3*F`xCsNnvdGJ*uy=?&6)%IE*IUb$ScWM+2Ut z)W*j&1emd7#RUZ#amBy9!o?~;*wM}-JyK?qpil2lUrtb=uN@a?K`#@0lvkkmn!*HL zzYV$Xcb{aKkw(O7KT8c2B}4N9S>Iu!1wnRwkV*`=0ICQ%(@eF|b|aLI79C|;MESO_ zH)tWWBY??gZaO|{gt|xGfAJ0M^l@M;q$CUjDyH>;2mv5n;bH~4te^e`-Ztc{t;rc9 zDC`gZgzz^bVZaDsTqhd+Pe`9dzsI;LJ(K@=V}+Rc$8=&$d8)ES0hIA(l~=!0=frLJ z0$e0+`Lfowu)!kKSKH1*oGlE(8)GnfKoMS6D@sH_>rNYu^LRoDLAn4|MHQttrgsL9)ae?dn3JkTYc}e_?P|F zg}<)=2O5R0#RlfsyS8beS{&h4Hmd~m3GIe}vM*Qj3F(B*0 z*Rte6%8SX$-D^`${z4i5@% z*wJ=$XEFI(p&Yd_)IuWc;F9BP=ri?g+wyq(Q%cVc+D^9u(4Pm^k}7Ej-wS|-kIU-l zra1fTpRldJ>OAtN4F;=c-C32z-T6%^htzJsi+;@Gf+|{JV|`G<(Y}JWB_lP6mp6>$ zF%5bXdRc{fOF7B4O24~iISDC@ueUp$3a`MR?$Zlt>wB?@(H@$*Hk_hlipLSP8|629 zPd6Nr7byw-sE+IRk8nqn)7dqKQnUm8m;jxWpTX=$a`nlw;$zS_242ZA2g<}@3# z%H>*Xdai!)bU`cQ4YvB~j{OgWTL1a9(^zRoH)v_;DkKufu`;$u5Z6t6dp8*dN@-mz zh&Au$PJ8&o&gXD_;w&Ab-!_e7|GWpyk-e_(lO*|RnpCg_t-JauDnU~DL)PeQZ2k<> zUN$7`Ly>y676QUrKqiTS1&Pz=JA^;C0iI3wl-FE2e987%7DIwvBXPj-&-$lC6SQ}@ z+6{3>Q{@NVd=7UDo7ro_`+Z930lEj0vzU>SYZT4cM(558y5JR10SUEjMhb_P@}?Q` ztf%7l#Z%l5U}E2kE+^z^qDcAllwy#mA1d*Tl=|4KoDivUttI=EWt)i^tu|TG!%(>W zv-}qd^{(+0UxW!9x5W7?nqGa!3#lql;18_?WL7GZdOl175vs+ct~1Ru<`Ox*0@azg zDTH3;!&-Uia93~xh_8*4tQXz=y++=bciantFacoo&j$|J`u3rBe`e`Gh=1Nj7r%)8 zFw<`WX5ZY2jMwVKDDy`x=7?%17y6HfM7R(3JGA6qc&Ra4E~5nX;*NCvPt9i>q)A>r zu$J3u8x~lUFJgNaw z0G!ux1|h`hlbmi|Tz`ZpX8-H;oUzcy2Ro3)r|;s@uN*U-fu_y9YAGnJ@sT{airr@Ks`Ql zCf(kP9a;*1A1!RQ+V@Ch?LnhBUajyWirCz&JXncXo)>M9@;XG!>NEax`{wJ*1M-KD z&dTfDY&dxJ09`1}hgwHkX#9I%7Uo%>+4>_i}u`JpCxqdH{m>0_bJvzEvq`HuL zifMSfLpSr>oWj$3I4OTsp`?Fs}ylzesJ_{VW7 z*lRm)F7C7kE_Px|#y4F0-+)@VnUV+LjJs1i^Qhh7jh}0lXX%nF;hOuJC#HBBHQue} zoul?77Q;Y-5gCI>OS8S3(|*gG<6g)BuoKcqCo$@3z>FK1D$qnqiX*tS{M_L^w4>f; z0+LG?j(yb|d&beoeYH?f^$W620J7R*|F4g0*ERf!6P9Tg+aH7Q{X1&@W#8V-nzQtI zztos>W3Rcx_p4R(<1`=>p`mg#HGC`o@EpW9DAb2ss&lsCtr}A7>JkU~-TzG7F-;!B zptF7Jm3b}Likx#bKhx$2?){0Jip8Q&sn90|R%4I#+FK%aIIlCV_UC=F zG#IDQCkYUPwBXTLrE4vB&QN(`wlp{LE6u!lLRx;L>xgPOFOZaC&zSxA!YgjlB^|oE zieujL*En%ZcD=R%b!+ZV7DFdspPHcOPf4L@sZzxs#(V^Jd=>LHL z2v|6PZw(!)>qWYc-ZXjE`62x zbiu~a=B4eK1p%(<1IX*IzV}3x$9X;}eNY2=ap#3P1!##65Kl*{CXwTRmZV$PdFTT* z47Wo1>1A(xEu9`NDt$%`s{GY!vHvO#nQkW@mKD#E=b#xk9KU`OHAJsZ@Y`q*J75QO z44WO{la-zRJ@catnH-9u5jz~+iy|fDIU4g_IM#K-LpbdTb+T)*fnn$Kd*S47T(!{! z_x|bVuy>D1I_}&K-5yy_C{$qL%~41jG#z;*P7&!0gXH&BF4)&ysd(H}EoQjT;}aNH zXAIl@^`cEKAfORG?c-~gZ{Rf9c&216MA5KwqGNfD2rW@Q`u5qLk?GtQrD_G+xnl_b z2%+CxB^xn=Cp8ZDHt^u5=~a5oOOSo*Z#(=Twy}Bj%FeIiC;WH)$==D&`z~!$$VV`u zT1C&l!3h^wO#9jV2vl!?=KnyH2d5<&Cu>E%6g*T4C9RQ0w#a@@VFaQ&JqDL7v8`TXt5?%7gFd?D- z{eX_E6)&2goNMm!kRG~OZ0hsNySu@Le9r}Fm9!V%#e5ByOGO<<+CD7~F6={81*f2% zk2bS`Vh-wYCCKGyj>DOU^6Z{S+q+A%K_F82ccX5ad4Ta;{luYRa;v#r&Dc53gS*~q z38cx6`T@MEHoM!*SIyJj-VCp%MWyc!@t9wJ1C2%NBw^!pgWhi5lT~_6oEY2Mf&wa* zTNAR}4&K}HvAZ2&1Etn;64-@BnMfP0_4`%b=L%iyVJc6Xk6Uy`}o zIXEbtHtv;jztBf+(DIm?j|S`Y(|eCH`b(Q2wqyleu(=pR7~tB40VFGf$l z+(#rRz_{VFF*)xdyIMvhTy!ig0>X9y5LWS>_UiQ~oxJll!hFpp@Oaz~PX9P7@od=1 zoPwm3Orb+k3FLLA-T6(E<-_I7^@DXEC%BZ>a;%xpz}1wAucrr0lQTsd4uX12Z{0qt z<_MGawBT$@M(cRh@x?{y75h;#MI#ijni%DPFun%pY+z%$KaNzFTbLpEUH9*ggybS2 z++eX^-9*{Ns@F1hWwOMUCi_4>YU7ve>srnr8gp>9^ZrX;f~oYawMTxLQmxr$pG}}E z@y603>-m*+T(T)=`PWB0yjr3oaCY1x*cb7CF8xmA1OGKySsEz4Rin(j>|OtzLYJCY za$p!5d^{t2TJrt|A$YTo_jPqh+9MV_A3p-LIMXlzXFFvMj=O5&2z~HH(aG%UC z5w0&b%(YIY)tS!SWJqV{yvm+KG{88Na=qY=xsp+#0MK7>FLYMi-g>4MjW+raI}tPdNST1SXssu^te)bVQ`$NU?WcKAHU?ZU#6*nc$biR zK?rMRGAR}|d2XE^B544Rz&Xji$a%pjZa<<+vCxK$rI-z>n+%?@HeDCwkX|+lO=bBO zdHk?B&|0pO$a~eje!B|OtbFC_&|K1$Y|9KOSNZwBs6`a@ydLTK2TyAgnU5RH$+vBu z2hZ2OO8r@Eut>nPyiyuGHIi`k`N)Jx`s*$$@y|S%w#B<~TN971KUSzGPP@i27*9#t zmJc+anmjiZTb?AZ$hy^Zx|2>DY{R6&msqd)m^>Z#B9}QI(=G@G(&&Jh+KIE~Jat8G z{*J!Uob?c3ug-bDtL*Wj>yXMm9jaS7DD`vp`0BW6>D4Fv*Iou>MZbL=i5nCzkhnYd zUZe-5#5rwj*aeI;A1z*yP#~CXB=$`>{EOAyvwu#Y&Slg;Aj~<+moice3=_^xI=7{o z2?}+P3uwFv>OR_#Gi-@(w=I59H{O%mf8~4qO8i!Ov1;TJUYits6Ub7pVKI*dKOTSk z=6tHRgv7K|4y-r2!szm&E(f^~|4&`p3?e=qvi<`IY^72{eKy`X)g0^JYkE_ z0(ia|<(i=P&F`nS1M7cUf+|_>{bhtU4COv><@WMog^Yi_HF?8Vn0>zmNZ1|KSyke- zjuTDDf2kYz9M0M-6C~Pa;n^XAEL|Xb@42a!*~7BSZslqhWtoD5VJP6K7ShsCpyl$hLR*teNZ3INU=0yRas7= ztFKJx*4&VC+VjAyhXA`~yE7ec`=H2P&t|;x!1n z!uO}^yx;A4co;vI@2{fP-)Mh6|E=!!>8S5t0M+9Nz|O%Y27eY+Re{oSVqS?6WBZB& zGzn>lvYeN9;e>U|`oVm&f9L3;jK4q1MBkfqbxr&?bY@&R3P9;wWLYWGuaS4}YX9ky z!#YSDxH|TKAD3zZyIkNLXV*nO`P17~d#x%`@u^9t@TVz&oIU)*@;|NoXUyHkv`^D} zK^!H$G2C!Ucb-uM3wRX0p~RSrs4f^NlEtauN^2|}>3!OjZ8Mea%-kIrQja*{vb_0(VRwYHeaf z^i-ac93)URU_EdU2yWPrdPw^D<3W9^Pt*T7I`?=c`~Qz$Gpx|4xZAQBsoSZ8Q`*eT zQclTPI;dz$DQw7LPD4??Gv}!0P-rNj)QCc2sE{dgoJLyCEX?WtUH$&|@OWI?XV>R_ zc)nh*)Xw26`r9`~NGn0lqj8;2u5YameXNR|u_nfAHHM8*yPTxuq~-137Xp=Hmt4#4 z3W=Y2HxE1$Qg=z={{z&{Gdb*Y*Ozok`%?Bfn0$b;!QF9n>vVhcGe3fq|J4UoyKMzm zgHP?XQdSPm1*5~M`WEw*r!awW14<5lVB!e2b^1^F$@x<;vX&c9J!+@Nl`D+P!C`RS zph`8V?U#-j0*ilGERcApF;wN<7MP3_8iqV;)!@gfc8fWK1ma@eaSbu~ng3l6&_ zIv!mQ34Qv5urKhLP{y=(N91I!ndz$F=|S8&K@sCM_qzUi`L*EQrBCR~h`}wRS@BMI zh0w!-vwlT4FNgV-G{d>C16wFanz3jGzj>I~xO7qW`qr}33PIcaE)M%577i-+K)CtS zOg!{_P~kLrcdBL8pwEuRwR|l1@Oa+NFaLhAd+8NZSS2nZ^)QVVry{G%{sWYL&kH}j zi&C_ySKkT7Fnag)*Fl@#8A-lPyW!P$?2-LG<)j*sstP{Y=c|8UrhlNp@%g13J=a9i ztCn*g_Z-9WJ(ydj^XAHZ=ZMLMD;g)R{oIP;dT7i@*eTu=6a&GlLF?T4+dXfj^ZkA6 zc)nDv`|koI_UG&ZruoY#mv`uu)X;aH_ryiO`~+(K-K}MiC6Mv^q{5!M@K)(wfzPFg z?aLuh9vFM~<7`r#FyxTGruYP_nur-J6TJ? zg1w&33TaQ+^Md4?FOv=Yq!qWfu224Y_Bd&BIja&yb-fvB+IgN=$f%*#z&yrkBbd>(QASQ*F zd2Q>NlrIacRKuMX76{JXNd7Y{mpEMRI(O=Y?MZek;QCSXLf@2u(EX%HO&$Mk(=M=O z%XIUVYaIQ)A(*Rwx)dF0T6c-_;LVOC9E z3EhV!@5x^8qnx_z8UTpH-5#4IrdFNcj`FHC`mWU2#pQi1^L_UHF#c|^4s#0{0f$Rn z>ij3Oxb$}2ZA5uzUV4K2j;*ujZ;zMM@rJtsQ`cTJVJ3<~Z-4u9&kDJ7dwoiia^?6u zciapU9Qsj^9KU|i_wm4%&o8e9JDzJtXZ?I|*tMO!g2e~MF}&p5l;o4@bYEcCY<-y3 z;_(*Hu2yGkMG@7cC6@JD8#>c~xd*e!DSM&LUTLaWbr5XUXSina`=*dAQ{z*$g%N#+h@Fepd3>c zqO#u$BP$Bw4)&bjbem`?P0$$6mYobD`9q)x^h<;d2yovHCSwlQeYsCK(y&i*vCODwKe63xVG-&#(RWOqRbF{l~ZVoX8TDTwJA}`)h2v0m&J=p?=PU~t# zxwc*?%=>n~Dxz)^98rJ(@Q4So^VQMzffq2JjAdBmv_ti%bu)0-YA9X+j^l@1E15Ls z5J;`B&0CxzFa^2Simuswm!X8d<2RD2%|ew3RuWzvVW7Oxck*FD4TLqUz^q*3{ zK8>PNH?%sD`CBry^DcyhLlP5kL=Av7@2nu-D=KdNWqFjC2^cPMm5}Nw#x$3apyaHw zqgH6FG<|ndZeL62lYnr)O_$A$&^^f+wC&7%QT~?b&QX%20!$`!xfu({7q<|N{c+%$ z3|N0cLRWIT3y@o5X*8N+3N1(g>+3SU4DNC7-qoS|XzU*W@d$K<)QNu^qDWwb>r(MR z*JcJ}$AW$|q?<{NTa32BFWR`FH)n}901U<+?@kwS?R^{olVG+KqJi)Wk|P5~*{ByC z4nrHyJLz(d65$zNq2O*5WOwN6HT=|pZx87K++R2a!sy}UZg|$fKzXsY6+D_0ZfKvr%e`0|$7B0kk=@w_?t#ySm=%&| zgYviDe~3GfXZ8`yS8leLYy>%!2yPereNOy7SDJUOd7yA5DpRf%{tY|H;driZT!j#W z^<8Bly+2#m-(_$IswJ^pga%{Pr8x1en5fD1xm_sttW;uJ(kr6garW$P1^w*{DKwOT z6~`p*R>npO+O3J{pA zq6@5TGqi{rE=9_fc<6I#6?Jk|My?eZf@?9opdX4c(^gAg)J02K>wL~j^z@9Gse+tFfiTpY zB^B}GqhS`f4%!+hFUW$pVki?hmHN$6i;p*d=|Z@Qkbk~yE?EQ6UI}I>R2za+sa|Hk zh@snS#3b9#DG`RF zaM*$h1R0j!`O=SHtXDUx6vV=cjs@qXCsqH3A*UbE;%&*9D3l00y%PK+H!kE?0l03S z&4MyCp=yx?P5;_h5=y~X-d}j4E*3=xz(B(Ce3gu(Mbr}|YL^U<{Bu~A?>F{3nj}1l zwgUXunrbltSJh=Cb~1w0+14*+c=z4=TIEqWgs;_H~Dcp`hEpia(d4|)t3q5>i7sa4=p?K4w znAEoKML0kxh9um^Kim(QU=C*pKh zbGPOgL*kr2#>PS$_KCDKDQeL&2RRm%CLRX^f{krCZH(~fttumDlS86zc_l~C*1}!5 zx$qu?Rri%XLOW$f3;;4eUl7(hsRz(DS9q8FMrH@6wy|xjf3daXEgRa?&(0g1cBgV0XLvnQ4^J zF2HgxXq!m>)_rS7Tl?{#0Lt7|&J#}C4^o=S$HDw}Mu^;z)fa)hO|j5+aH|Hj6&0+c zsrr~X>Q*rU_AiciS^}bOMAV=ht`OXUM=X#Xy4E7oOwD%qTH@5?q|g@OSw-{k2I2Iu zN(I?~>H!vY#Q|F2)F7AM*f7c1(28=X6?8^~Xz+xhA2F}qd#T{i$%Y;Jrx&)$MBd5o z3ePDR_e`<;%!nmoY_56ZU-l9M-x-5UXk{nGQWf-H(A|C1Zs_~_4cNsZ!0Mv@@pdCb zZZ>Aj>4d@+Ne^nLI|ynkex2lK{8Z^JCs3DE)uTz&`KSns+Ti zyd=P{9V_GwXOEA0w}93&Ee7jvoRkL7>8+7h5}p`ei9MDcn_G~APpS_}CYd#%3riQP zQFQsQw7{bkV524Yi8ouHck(-E#8R+S2bIk9-Hwzdq`UXxlkGXRwSd8fp0oNBx8y8h zNcqs_=_lIpl0h&+*yLuo13?T&|K1@L!Zp>v3Q)1$Gl&)-8^@GhZE<9hLE z*zjNVSZv4@Wf|6y;zs8)Kh2<2EM!7(c@q6k&=yiVVR3f*> z>%Nd`!78s^$+q_8#w^^rF^3f3QXK4?d{R3mT|<#)Aj~;`1kiop}nBsrXzj$>z)e99aP~gN9-VV z+HOKMZI?0?Ty&STDnkUbK`Qytw@ELKQrzO&=ec&ck|VLQlAbTqbM=H~+hg@HWVDWJ$!p`C4k;I`YrINiCn ziB={m#vsfG&*+xm?_5X)gUx}12FuDZE2*1^0!cxypHZ$pAyTXQ6ut*FAzEfX{%H_H zSMGfdvf=7`;g&q!`i7>3LvY+*c&ocm{Rs_*$u3j}jNCvN@-3hoyk4y>4=i<#_VF?# z)1T}D;S}{Jx{;;(QGP(+2wHDsV6Fr{MQxSz@Xoa?2VXIVDKhs)Nn*nLny%R*+2#abPHK+p*b6**T+M16SoG>I0b3H%6$wrx&THS^!KVX~#C+mJ;`NrI>|;m{ zoDzye*V_ON=hP~cFOUgA}eS25WG$LxZ{^r?q zrj_Ts4FM9tRJ}Unj#}H?IcTyQ;;5J~T@|9=A)iIW^%Bpz^^% z!dO=vD)`C&gMF06iUhc}U1sCDTU%g;^tf0Y$awy7kid<#f{K&>Mi(f-HtXOagMc@$ZaBCYaij$65xr`zFqAsxy6C+FIz9U_`C_(cF82GqDr#`R##g(rBq zE2GrBBILg8TYGcJo&Tmd$_y}?K$5_F7<0ISuAr^O0X|sAI%$7quE@n z1KK*Us}A}I#vwn}&b&GH_A1N=a;1`o0k&}pXwX};#S zTRv*G1D$^lIh6NMMKl;JWH!ClR4D{?EoPU73>X;FX5>}K!(+1j~g)~yhrFYPiHsr6|W0+Yw$5!?dy+=%^1~!B+>r>%=s6 z60~*AnOoLD-*h^uKio;MV)hsDzf{uJXFBn3E>`17_^JcsPb;+Y7u9AfRyL;3ySiY8 z4<{IOIVh2U$iWz96%cdcpOHZZnR)!s+-SAn)j>Wtj^SNgsKLa~gGpwJsZ|zDPwb3& zN>mO^r@^lY!G5`|5uAXBZVBjKiJsGFDaCyduMccEh+f^qX%UI%Ap|poqsbBWPb}r$77Ep`#e$S-+pB zS4)s+uxAQvfgyj}``GD+O*fjzcQeE1l-& zf9`)RGl9&9*Ra0d1uq0(bT)JmMM@dX0D{SR{+n-cq>pM&zfH-%?8QF{9QqnZLz|+h zZ@QCf;zqvFQGrb9BMKLJ*k4kl-dRS_f50Ag>nVKLW;Up#Rpf&y6Vqnf+-Gt8l;cS4 z?|zBb`uY_F%5S4PZODgsI7|X~Cm6*KEpNQ>5*3ZR#Z=Mt1BIK0Nei(Sy7k3HtxGLb zahHUkxWz(`i@wTd0s6X;C3Osmz(y6(<<|FcEHay9CSyskh+0<1*l9sXAA=<21Oyr? z(ILtyFrCZSjVX(b*P=v zajl{bqfNyr3BBCe_K-?g$mb7~85>=Ip( z9OBtI-Yi=aZ%_+msZ@pZ0}~aPEX8bSmMoKm23-VzJ&?P~Ayjb6s{gEPF#yb6k_Uy& z?HR}KA7d3G2Z{HH+Efz*FD(-k=*a}&4e|%g5CmM|%}u_1!==JMONwPJU{wOfcwaMD zYoO@Yt$}CMqe)sF@B9zc>u z1uLX%{{wv*?b5?eaJ{|wz%eNwJ_hD6$*ayuh&G{E6S)*) z888T>Hu{#pG&cM50GhN;5DqZAeus7dONEfilqOEpRY=i`kek95>_m*s314BgNZ1!# zi2WUk6O5qWme}zdQ@nPtQzy-2QmNfyHv4g<0wV`h&DqL zST@`?=Ic&Y@4J+H4n+yXOx1U~-Xcb;TepWKx_6kPV(I9c2k{?lD#~Mt_`z zEwFADGSf9hfFsfcMVePyL6Q27|80ilORh1FzN2nZMT*m7T5@J>69hsDRGVJ(poj+TF1*^F+dD|&4!+*GgUb>C;|0w}QaDz}gw%gq7n2Gfi}usB`xMiKz< z+He54ivrBF_c}PS`x}UfA`b|yNPsuumuUveJ1(xT3rfF)n+fCEI%)ao-Rbn7E6B4| zfvJeKHL;R+G#gpnw%?1g1#-KK(MNWteC~>41G^QJD#b1>J65$y-QuRdoGb%tyttO8A!^0Xy2xG=suU z0o=XoKW~P2nR+)(U|URCfAXb>;U0g+1W+dIEmZXiX_?9h0+YeA5RF4IS^EnRohJ(r zL>r&-!KMH=3U(&?o|d76&BqF852t>iaPStx^F9R!_Is@cyPsP^+0TiNq_uYi1lWoT zkd#+l7)xgyLbAh(GXBv}&#k`=#VZE#2GURJRACVsz03?C$T9tWZs=5`FgVv`Ze&V? z$y9c2Z?SG5+GHeWAFfm z|JcMfCM}vMv>!tv$R?QRM~YuE;Z3PA19?qCd#-x4s)VUy+h4t&E^OwjB|`XqHPJnX zwV=2B_CKK0#w)eFT)>+*?U{ORtbzj-=a?!zth@IJD46==yk+xW+yw(>0cO;Ez3!l$ zbX2{K{?kqrYJ%V<&Ipl&`f{G#1?XA8=7|_)ar59;qtYQ;3S-#>I4w zHUn0QsRMzk0|UsZXzlV&NJ0fVT087l{e_`~BE#HUdXfsJdEN9qeu@gFlVlZkcWSuO z5Pe8~p0=4Ga&EyvIFPOl&B+C3DF4Vi<4g2CYjqo;rtf;#A6xC;RLc=agc5xt0n3Pj zU!@99^u$)q#i4OGsAk*T0KNbpSUb!Dl|@G|Gs%|bn>!BR zedep?O#N-c9cvo*b2T_Tp%o4lA`~_s8qyovVHYq2v&(LVn(ME8XZ{BqQhAr*i?{gF z35X_b3SLb3JK!fU?KutoTi-K$FVunUo~(keiJWJ(h|94F)H`1mb6c5qQ?%*w!85+G z!y3yc3!Na$z%Rfb$@vCFp!s~MD^_)EaTC-21QPk8;BoH#>BfeBHfM`@*9S6(Ps; z#MmhqwF?vuAiAE*f7}>coJ}Stp;eLmjBKoTcJG5bCp zTec?V{au!R=?(y0cfL*3t-XFmPsSr^hQ%wfIV95Bvht)0rr%R*h;pHy9`1{r_* zc7DZGEAt)i-q71QZuyuLHeGFD+D|R{(&K#ORGwYVwa=8!TUu$qEnqTzn?f|8gb1u3 zM;@rCCcK_!VwJY_q!c85rsLjwCB1!Hde`v4zxa2duUTH(+XlM4BDDiv|GNF&h}VL7 z$76ldx<}Nz!Z1QpYriC{oXYT>7%-g>KbB>nCJ0w0EFp?x6Q7g=YBXmAL#3F zFrs%4NA{k!9akN3;Xar!W5crEZH`PbviJ|soXAv13F_4)!=1vwE%@*eJ&kP}Q;-<0 zt%KB+q(c3c1fR#Ho?!wG`?EFbse*W6%F4x=@qDBs?H`3S?t%K!7%qxDIb3v4@s0A2 zhP|K_iFy|;5s3G=C9g9!RAY%12j=z837w8tKT4hjwS}ue6H4x;+bbCwl1GR~z;ffx zV0$s&L$E2a0DiLN(d`9Q zsmJ8<6}G>d?>v0X%6_=52|h|I_xIC;8vn%dJ*%dN1EOp_;9we+(y4G~^%903Wh<^x zhl6y7gG9HpRhsR-)Fz6VI>)gu>PmiGWP`1qQ$5a=h=bN+xjn9rkypbmsmU(5r^!U} z?Ws&N@L5Y=sOifavfiXugXNS5YMvWyZ@OFf^wJtlx)bY~8HL@*R zRQfIy%2eNBT3Wasmnq7|a!nK>-z{@&5_jmUFH&QhA;0vxw)bLZncBW_K9S!Xl_PG& z9)U}+yisJKEB|~&OJnpm2_w-A;QX6d zOwhX@3yK|qK%rgD-m|_*R{b@TaV^Hl=FZ5Yd){ocAR2{f1U%H$FYL8$2@-oF4GYC| z#}qtU@tIf)>%0guY2r6KHn8R14+f8|>EfU>qQ>&wE2j`EMKS8jpUQa^i1Lu0J)DzQ zPDK1Ll#z*R#kM~8A%3|0b;Yq`#Ol(060T3z*vl*E+1N!9ewRiQv_;`=)AV#mb;Rm zvGCk&bkiPkUU6*2*(I;8Xq<^Z zh6Jc9&VCeiedbZm_O%!n>s7SZKlX9|d|B=DfKI_-xCnQ+)TYr7+aANRdnRCoq*A(FY7?_`6$&#idN>d!FJmu1$u z?+8z)^S*-#pOXFQ>z2vS1q1WtiTlLP6vSQ?LiO}TpUqCLf9$lK>8y;s`Mu7?=M3(s z1>)kJ^rf8h{{gZZ^24W_RPt`daCtExw{J8abSVBs`dUl((hN7UVo`h`B)aMoc~eQL z#{;s~d?E6?y{I{CdHU!;9d7R14V2M?PkIA7a3Y*~+QU@yVeg9k!#%i^Lx6Vb>S}N2 zMNGDM^>W49!@Zq7Ok!E&79^CSe?otip;G78@gJblMk@N4_b|K!6O!{vq-zqEE3sQM z>r?W9k+^|J)7{Sp4$XXp?rL4j7F#ZGzm?w59t{b=c4CoJFuNRr_6L1mJYomXZ#6^g z#|nfX!GHhKJ{7W2uN+JRC*b@CoO^XK##S{=@t?7sAM?!PcuJ1sTNb~SrEsu!2Gio8 zvMufg;rNx6r@f!JvHbNF^OlGF4mOywe+aTOoI^HCJ zqGjFzs*59ui|3*bH-&{~DpyQ0?{m-oGW_3VMwYinlv8nSJe=Cgto~)W@I3wV148)m zA-Qg|R)_bypvqaHBGiHl^Zm2m|700)dYya%b^Mzw9BpC;Ld5}8I&O+U`)2yE#M=Kx zs>o|?0x5YDY5INr>DhCg)8WalUdkUJCGAYMV+9c>&{8y)chL5dXH04u+0?4RJpgVR z7dLtCo&+f%y*)VWSP&>P?>&4a{Pedk%+a0MZAtPACQ+_;w~4+OKcg%Zq=cHl^G46K z_TT?z9h$tEj&+gN_xUD89n1xM28T81> z2Q`r&Q~0cnSzFpEjmHijj(I6a2+}uc^XK|$t=|s)Yq~TQyna3B%C$3OsN4rhGpuR$ z^O2@Yf9E5rwnWt1JaXIwL^J=O1X~JloZ83D{};=DxX>zR#aL=Hz9CZqko}c7DFe zCFYfx*pIuAvk{ePxc|_V{igvo54()rbb-V&hp(*k&0=(MofiO=%#oFg zXLdE0dEE^8-%qawVfrF%EJ&bqUnAj}2E+Pli*$o>21`M&gAn@6ce}q~*~#axNB25C zgM+>ie*%=*TB8H-g6?Pc z)x)hG-JP#m*fJ*I^$MHSs$X5bW%FIz3a5OA*r^C1ye!MisNDm%89#@Ls6V96CN+Bx z{C;8b?de`0^=rCe2!|;CI=-jt&bI^knb5dodk13nGwC0q_j;UhafO-t;(9T(;sMSx z%k$De)P)*V2=^yZ`${ru)2mm{=nofR!lHI9DIHz#*FP{L4#*3o1cOGx`o?aa+g|hw zZBjig8bW9s&Zrn9{c<&X{MgBB1i8zQrfG;7sq=>&(dIMnQi{E@w6_}(s~RnDm!tQf zMDfeO#Wy36gn{KOwE(zIVQPF&62+AZOu%FtITfrvUrQgGfpLV{UQtZg^{;g?XICb!WVdfSvdkz7+I%wYx z2==@*uj9NJOsyFSxNW;_o?Jv`gx|#6MSCcB$VRB*br7_bEtP4zR){vAps;g#+*OPW`aZN0$a0 zM6i2;xh47AJW|~~K>oXnJY0BLEdWOqV;1|tKPbr z@kC<(w`p_ttO`b$%zZT~vtEmUBWABZ&DeG8>A~)2y82?t?Lx+UH4u3{_ez)X_50>$ z?l6Z|8kOlcKp>izTm3m;Ak+Ij3!HnJ$ote^@w)#(BK1*Zm>*09R0q zT|CP@`>kvLj!2uso|TB1y^G>gl~BpgBr#A8Y02ZPhFIMCu@{Jb7+%)Ge#``)x`FIwm4NK?BI zNTpUS^F8;wZR_1pOyix&Hop$nX61&uB$ZZ5;eKI|SaiHj-kaF4J!gFB5#v@J(t~6| zX-Y@(bk=qBi?FucW;Lh?w#K^7gKt+j37>TpP5t+~t&lcji#HdnZ%MdYf=QGYcHKrt z>KOCe0)F=I1#1)U$L0I&J@n23sqtEGTbeIWER-?qv(I?q+Pne_Ql~ASFGr0zf9RqA zmXDr!FDk@y(iY|cc#k}vri`r2%dTqo?+53P(XoR0363H%CH{@|5#)W!cq%m$`kDx} z4;y;tI}%u+a(@|fTW{0J`ts?9kI;^A^5jvoURZ!f#KT2~CU|N5&flhUb!-7S-iRBN z9^ta<7s~W}eZIZiHgK@Uy%h!qApARd^>ypuVlEDc#!jD!*<*WDd`r@kRc;sAHt}x(zR+IJ zZn);qw5Uu12U*T$mwKi=v~w~$?UXUG|&QjU{6 za{anghQya~vwdL>N^Y`k4ZkQlfoJ>DR0p{q|0gLxKvOKobaIKN(nAm5B%ea}(DH2M z+^{<&nkKx6ZwIOvI}r1^L#7$C2ajc%yx3~qF(ZFtl|#Tj@`4vBtDF^}7R*q58n3RY zmg3|P@w9^GAQ^rXC`30__eGKOB4|M<7bo+Y?2`S@qeUMX- zCk=r4-R>@$l2>b6WRh*YqicR&%Qtv+>eG%|jpNYd$&195xPU!uxa+dwFB#060GMRB zX!^mbjtgVovzEOdrADpSzHgo`&pSML_rk6|ZhB+?{YEGbs!F?5J9iQJ@qa7wT0QUA zXDqhhIgzGd#c)b?+(vh>a(p2?SiR`#NY=jhd2b+i3xm#R+h8S&cB3_i1dMitx<=+I zBk;oD=Fawn4>#wNvm|vwfH@p@OsDgeW_|a4xlnHp?oU)PI2nzt6%KAOvMN;1Nm|!n zhBZ?jR8cn`xl(g#1BP>+-pl>@DPlVk(D#z~4&>enGI8@QO!#MV$Dg*8;Lfa0AHj|H zFZlQRu>k+i2KIUF(E+vZ+>cFu9WuGP1^GpHSGH091GcXonzKUWw$9&rWi-)Ku)dzR zT%Qw((f(mR-TlsQ<)7i3ud0$hDuIn}QRD$r{nIy<7FTXp{&v<*G3fF}mxih@dfQT4 zC;AIq(u2G7%NQ7+p4U}5x&szxvaYUQ*ED-h?p{~F!TT6kTrD;jx8%*QQWMjgci&}p z9ar{bj|r-%xkQ7`ZjRyD>7Z&g3zO!w(+dV|Cgg8*O<+jFk5x;VEeNZ|UrL}$jhp-1 z4-A**9quH;N0R~T)u3j*GLsa!7amLsEUG8{LOXCgIs-6utU48T#gCmAbv@qR`RLp| z?7JU+Dmez`=i5WYZoOAaePjcSX=L`d)Oc(sv<#5GCXf7)^3M=UR4fdq&>UbPqvx-v z+NDOhwdUO#`u_GETlhI}SgXsc`_S%_)k*JWj8CZ{{FkoxR9(-Ga4Y!u__s-?Uw(^N zoG5~s7W`4VA&>6(q4$+WF3zWXkf4zd2hVi)8cjd@sXj(t3~AQ01mLl+EWGeX*R$I? z!bF77vRSzM_v0r0|5iK_eRe?fMR#i14_y{8=1d=j%d{0=K9+iBORK1iKlN`F;mXBr z(LTR8DzaZsM?M)ka^^fFX>uK|*Hto_RTcpi)V~f5bjTfWz3cfl{@OJAZVNA?DM6*Q zbs&SeWsG_;D)gLN`f1*!7h!s(*ZOo{V*ZrE0%-FaIvvqh?GvaglZ|CRe2sMv6IA!V zv>=Ip{14v~6B{hiH%3kGft=USv78{@RZl+Co%U`2Pf`_hMnBs0)u{4w(ZF5bD<{Dj zKD26DlDfjooYEpRT>syh3NA$h?RqYSaL4^h4Mwr=)hFvnzna`VZow2Q?mYAt&Ed?; z(b=6t19eXOE3<4%D_RG)G?59R? zPkFA_Ge-f$N#Rc_3tzoz@;%DRX{-i+2;XXYw%OT)yH%gBXd6#$6$fB{zTCrm^}4?; z9P>G@io2=Qb7u}TkQ#s!i){Y6&>sC=aC_C&!U)PW-MeBm;og1u4MgSY5AmnS`L3n% zn05O{ZC8)CCN+i8mHbIPWU<@ip+3{z?aa^xX05Vm9_gZHgxkucIZ%cB^#~9Gu%$}#7K5%U3s<~8ZhudZ?^pj(?3U?1kXX;Fxdsa7Ot|s%GDB6Q!qO=$gSN zx1>9LWw~X%RX2|CrNRg~YmZ&nB#Q>lz1!a%eVsaed2x9f-*h>gJTSTH_9Ykf_1k8* za%yKiIZYUsVEsbT6R z`(Nm4pkYYC9LlZ8=iHSQbLyVCFBb=9M13drlQ&m8g%_?r1r1NJo9!u!#C`|hp~QrU-t=<<{6Ft8I**+HZ0orxbTkPMNQ7M& zs&6f9oD{8>3@ByjFOzZ6c%LngoN9BEaniA3D&T%P?z%qCxBvsgy7@u|99HiwOhQx=WJ- zFlLU{#~uh{&DqT4B{`-)YcHf_^fxwN`f}KJ=35vs$t@FopEQLJUVeHYt(JllA-DpE z3QUMPT2rD#&Z0J zs4qG}x6o@L%E|l>y{jJVuq3^nFK{1$E8Rrhd>V~vKMnfNWNnPRu>_+6U5n>Gz7sR?E#lKtMN7F&QTV?0t1cMmbkn>$c09pmN$wA%2L#G@I;ZHmL?sSGxHs_I~dl zF3OY70=0Krrc|`3ZA*Zl$RIuEZ3#|g9V~)q6L~@qA!K{R#O4QrPO}R3=#t-B6O zfYGW)*VXF_v^pBAz=~EN5IegWkWST2m$EkQa|6(z5%4_SVTF(~Td!{|^4M);-ePv~ z39$%wx8H)g5~KvJXo>~!)Xk_W;PWGn9>BJp$VW~5DLQlE_;1(^lr+e&RsAseJpV*O za7|F|HxjQ^Zy>SjX;ST*?J>Lsp;H(9hVTA>Efcv|%mkuHQchR=&adWIc#r_oUT_o; z$D66APm4;nXTX6A)P}!<`AoXL-CmDJ9A5(6-Px+i7ct27z)p{#0d~c}*U%Ojra`g~ z{D{&GUug0p&^X&p{jPHSB7CSY`G%{LwDDz%{mSB`Tb63NR@vUE$mOf6mJ;2)-*W2eB>@M@;;Og87^fQ==1#q*IJ|r*bN1@sb7ApU27px+=_*zg3!@+^r!FY_^kk(wWQb*)Sv^eh#0iP`~MX43{3yTx{C7+=&HE&YjFn4&iA!PePV+Y*$CTI%H-|@5yl3v?g z=6V4t# z@vrfV2}BE?26Ze^Rk@w)`S)n&1OM7=X_D&_^tZmUuCPys0d$o78aadmXeFDX?-8=o=XLgGFrXf-#Q93*tWFt*O;qPhpH zB!gy?Tj;ypFBeEglh2F4V>2hr`iEGV&uI66uZi6LXw8U{(5!l zGDNCm6R`ioo_+4T;~ytFb?E@D1>G5bl3E>DCx`$vOx^QXxuX4phaR-DBam0_mjT~1arG3Co}x%23;+It9;|(& z#Z9Myr&w+8wu0Le9I*ZSYQL|cA53T`M1sz9l`-!q){bomE@_}lyETyW2)zQ(Bk{@b!kI1TR=Rox*CPWaxqn8R>5EQsGO2tOY# z*elg=8G)TT$6LtXdc>Ek+Te=dJ`y$Ss1(hoK)9YqD=xL(7v63~H`jn(?F0LpoUgqK$J!dbJ=|Z-A$`qiZ-}){87_We*xb zE5?Exjy&K6U1owVilzY;Us%tlWMuYA-fKfPYDY#|b~#5~s2kg1WjeA!Gh;l=UT4o@ zNTNc?Y3=)s;ybHBT+S=t;1R9l%F(+7LP8HOFlIqd1G((@_ka}<0QFp%C8*(SN-TFJ zo?tp_&wT|PPCYjcqc#ZqM%+=6FdrjUtfe2Q;Z7*R8gM!WLVWu}`B2e@wm#BkEWWXQ zRiFsbkW{!!cVh;aCJ0aNk2+uNU^eupMK95QDPEbi$Q_NbvTm_~iufXd&b{~m_;=144QEd1q<(n|AhkJ3~| zqYw5#c6vw{(`gh6tZ0vZtgdT7m<9^|IB%hP(0zwIc7g*HTGVv$9Y0uE-IM&2Hz98Arx+-7J7|wp(MRd?KfE}V2hbRDG z1kJfGEy{M`52#G5!dZsL_?<@Zh%x)7&9>*-%m4uvG-{vIQiFEz zJl7^5?>?^e==WJB_D8BrPIJ~QMFN1K-xeG0w%nUuEvGaDzE&N@h1({Z4w>ZiDVgd& zax0(^?C?=8XC&v_DG&0eC1J1%Hgm zvj^c(SD;M2+zil~4sJQbh4PBJDyZYeUhcBY|C+iHsk*TgT>L z{%l2v(Xw*l#OtsLi2@lTdQPY0O+nESc*wyynYED3jQ@aauT*+9_ZwYVT^C?Nd>aH$ z2qlV!NqIjccNoOv`4=GuHkb6bg1{-bpw2ue^NBsHU}xz$FklG$cx&bG{olufiXJHv z)#@hRLZ{RP0X~B-2in->b!R)ea^(JT_^vTB(B}ZP!l?z=fa+yXOtRB&s3DFAzUl@N zquah(gm^IWGJFM`=rY5Z32b94&P3j}OM+~or(BKY&clbZo2?i91_y6y3}VdGT;H?Z$t`MW$AU8Ru}D6_zr|UjGiB{0bJi#c*by&Mw(7KR-q@E zQA@^P1%4a5@zo3h`m~*#efc_C&1{=6caYpCSl6;@gM=Yl?A--or(J+rtNTPbb_$!1 zI--Hyu+xNKrOvwuP>W*k{`-qa88Dgko->nB+;5cGs_|}^E(1r=abN`bs2LoT8$gQ( zVOVg=i{OB%>_JbG_b-dhz`8vQcf|>(9tVo!uJkR~;o-(qC*KS7@a+S?uVKcW3}Qpw zBaNN2Q4?qd%1OX*A;7|pNIXlThZ4il_KR%(g1v13Xde#y7{fz}Kx1Rzy}>e$YZvYm zgc~OTaw^hz=T?k1WVtfg-^XmLGB{b`?V<0)*ErO4gz+60Js3&(JAgk$(3Wk# z5z7bxu%XeK1HC|aaK7Ywy1iXqf=@cK73U%SWpLBo+2Y&^2~G26+uIj`JJ)!kK_nqT zEIbRch;MMX0FcJYE7Brr-azL=h0T)a?`FHcJs?GA=MLBnM|Xno6$mW+X*NN#$6Pzh zk4Dz-*0r7q%+1;07O6QiM>N=CP>gJl^Lb-o>;6#0^rj+hl@^_w@fN(cg3;9V5_XEE zIgc5=8wkaE$a)3wFFhUxIteh9gd!_=7vMl$V9|Jbw>nYskFfbrEZ)*gZ#Iuz^zRXG zAO6}Lg&_5>Qhb-4TeYY}{*xOM;Da`;h1;65$svA&;m-I4;z2-h(?T&~Fl4EaYwDDn zJ7fXJ2qBS zX-IWxHbSWwv?!Q?vMYC!9_EPaYU*ubM(Rxa zt6+of|FhWdLyxS0nOk|kUw8LipB{xdXT(AwPplo48rp2x28pX<12pjHbod9+!9 z9jucQ@ZPxli{DTJ7^)9i^Y>&-Zkm0fJb6sYsi?WS~@A5mBWS z{UTDdB7CJ(vl-GrL~xKLh$NlqoBld-QB|zfV6603bq@A1gU3ngpC& zIXN=pJ6Wa^3}eYTfq`uevVQJ}Q0Y}!fCsg9pH&`cNx^b5bNOwsn56!sxFD^@KM)o! zvibFL;yQ6KjUx+G9`-Mp=WdVVGz^^~nCCTWnsHQM(;VQq>o>0BF-mtV*pAv?l~PX>BGZIh1&3)mfhxQZusQC2B-s& zy;}`fu$p?MKe-Jq(j$_$V+`Q+$$c_{MqCw0MHcl?4d5Utw$kJStFpC|g#KB|*Qj+r zyv#ko$u|fvjnE0^QqwE5L}NhEO>vQ_RezkNJ|$xyPC|jqQYpT<0dmU=_ivhY&}-_~ zWef6THJIR+LaWozf2`IIJP>|9Lz!F!nVX$PGEMLUcSK39i}(aa_#7FX*uFqxcn(|z za_zSW|Nb=~ri zHde6(AkJy}8U9!#ttBa`TaTltK2~|_g)iz%2PhN9b8=2w{4$`NRGc_-bCwU{lYyS` z;c!dX|4bhx7?3frUA(MuC4TdE8@B@E()s;W%?AqT?9PPU3Q=2LRrwy(-p)zrBJ;D*;99KuQ5Z@JmnAhtMQPHd=b62Llml4hLb4?fab|4x)@Rm zk}&evkQ|t;sGpz**^~m{dK#YIv-29Q2}T5}_MI^>--6{bKM+bj7@|xPc*p`mWSSqE zyW?-{frB?SDpQFzn}roOw}uokO$$4+yf&-$9-JPhk1VrpH8wC zz0c3zHr`d6 z-f*G=SUm-FA&3!1k@QK%oFiS0M#e=T$ACjp5OH3=uQWI6)V#p&{;@LM|I!?tdjBZKM z5`SQD##4e`Kz7;0aNUYQ^7-nl0j>SkT`|8KrA0iHhPW4EXhz$?VCsUz8dW99 zfX_1CImLb!gn@h_w@?7EDvVWgYe{HOXO(byJWE9P+)@*Zp9vG+jG>#VaBYetuw!IU zBRG(lCsP^FO&qdXU1Q7xN)hXx)}p2&@8p({5dikVm1qt(wks02}9%4qDkV%g;$R*~lHzE8ZWF)ppiKUdWQy`8pWkxJQ z`=YbAC;F0$6?`p%s(>Ay})2$c@tXQBBvQ3>W; zmW53P83qZbKs;K~IRuonyY}r97vT&N(xiYh zu8$02kt_YDM%A0z450mpFL-4DN&uPqiVad8%F<#e@JN6&&$&z9&KB>%=X<8ooX`6o1~@QBfPr;doJwZl0Qoq^pY<%3#?H=iSEx6O+J! z13u*hh7)JkqRDUEQF@GfT#_l;Q;$Pa>o;?hKy(!uPSQ)g0Za6E{?ta|=TmvGKpazJm#3(QJn9Ab zKu24_AA9kqoa5&{R85;yV!c77=-($FdwX0VxwK!pH+rDe*G>V8IhuS5VJdFIMhBe2!>n(uf@L(f>B0L0GT)!QKmNL zm6e{QAC7B~q6L~UgO>gK(i1GAx(}e@#om*TTS;NTpODLNM^9s zE-Ki_$y*4=Ct{(8tuv#PRo;U1?LWjzCT*gt3w(xjEHJfqbOl73?kX|6S`v&5Qc4B; z*$StC8<}7ppS6C9aul_$3Y_K*%w6q)C0K$kE4)Q~GWtKjT{?=gYyuM@D zg?DXozRW}k^b_p)0(Op*$#B!*jtU#f19`Th=A&e>`pP#aODmk?`%m{c{?t?pC;F`2 z(D~=0Z>5tok^c_&*WTP^xm5f`68-*l`D8}hsb{(;Y6R zVL1APRtw4gX*~5=o4%K30eVvk)a1W>_JpMpklHqVWVu(JhiUwRdb z4lsOLsG1!>ft{qly&1LkB}1Nflqq^zlR%g#9vlET<~yJA)6&L*x- zDs2cg#VZrjFH&;Ma2P3ZfTbvQ?A-;QBR`{;(@YA24XgfSZIW!!+bau=NDrzk=$Mae zlY8^hzy^hmK|32E<|9%rjkUN!w>~5#l1+cIEE>EN+>f^;ftrZ@;Z5(jP|56nn-0VK zs^;_p*g3$_dx}>wIR!Ky(ksQH4!DVbnt%FOL3yA3sVkf49)`S=V9D;lWz#E9%_9Svx+kZ7V1KPba9 z2M+%J_kxqw9>Y{v#YLiH5YIX=imVTr!5AhhYwn+x@YKv7;cnWkJ*mi&Mms6_He~cA zwC4SDxO%EcKQhsxCfDri4;8hA6A19@#J$uxa-G1D%1VoG*!KSR>EJ^@6@}DW*3z+! zf57A<*X!A4vl+>^%+xInYXewT&E<)(1*Ox&9V4b#wUxR1C(mm91-VhVS+2pl2x?Kx zdXg1LB3D*j7H2PczFjuCzRWJ$Thu(4#rQ%F4MK2fmg*vv>9)5Wyc$jjOOYa`HdIh# z^OWnXQf^OEmJ7Y+`Dn0xVANrhd_V{8A=)KzGnyH zZywqYn>kCy;6UdEEalU*Lf{ld_q$TdgfQ-zPQ9}{IwLu@(T2tTksF@h=d^iuS$R5y zg}uDGy2j_{9(3Nnyz?Jm^|GmPYB`id0!~_cnUvf2$RDeO4>2RsPx9CDGrIOq=8ya7 zvfu7RPK9gM&grJzJmZRt8z~t0_H=3!yFdf)jO=(b-#o>|GaB+z=#kAIIe&FO|9!p94PrO#JE894 zu;Z2<9<=r(OFBzIyGsU4^VX|5U0`5=TF=mEDGCOoa$LtxMXPCkNN#NY4+wy7@GhT< zh}&sy1%c>l1(bm2zjRF9J`z?%>gxxfA?I*s2|J=EcjT63<_gm<*IY(T>UnC zGhiBn;^2`!%NR|^6*j-{@4TKTH`xlAjcZM__76-ieIol-Dhp^Yg!i7eCGqhVt{I}9 z*`780# zKCZ=+AvY`^9!`j`Q7NFEtD*H(`^)^yLaMc1-Of$IOa8Sht<5i7Hw94yTYD4l4ifb- z&L#;5+ZLuJ%KrmqOzL*6rQ(Nh zZynjYh&naW@$6!U_*Z$M_&84Av8O@lhuTG$D6Ts&afhij?mGOeMoTIFH?&_VWpbi) z*If7+oRZW0&L6gDK=GU0p2Jy15kc-2S?B$mg50^sUx z_41u&gV=hPmyb+9xY_wTLuOG4C)!$LXg>{`You>qF-^R#PeP`sz!brI{QLVS(_U}h z1_pRznf`f8qD@+vTz;Qo#o1nFy7c7} zyI+YU#tvQ$;kRM7@3-HqkJfl*Hr+7^G`f2kZYYGz-T%R#oxMPAHMPb}1~oD9Qd7q|j}t*a|7 zzw`WPrkf=R7$t|mFtgP0l#UVo3vjiR)O@7($g+APmu2w#?VE3pt|=y;SKZ#kj`jD# zM?){~UKcEq=;j7qAertS@6{omgJ^nHTf23nQhK%h3+ppUuZ^He###vx>5soxJu`jN z+h~w>GOW(@Ce3Nfk(l?-p*@-4tWy!VB68zraQ`IIGMvZM%;l z@00ExVWVA(leizbR+=wV$q;-gQi_=yPM!lv3?0g7*7)sgi%D2Ue(Qk&mx^ z+v#}{o48c%AaCTWVgw7G%7?&7(49+nhNFmjjWWql0?yZz z|K8-&S$PyK!yo{^?S03{?P`Gm7daX`9VdJzp=ed%Lz+8%;H7)H_0E+P!<*DOEECJ! zbi@~o7&tzq>{YgR@<_mMyOo~45c|w*FI7|{em2^#C2DrK6sp8A-yZf#A|2f9$VjQC z%amR6-${t|RBcUU24Ml|a=;R3o9t)A^HlcM|KoK+gZ3hEfUx-4A^2nS{oBl+rIV{b zI0j68W$b_S-Aq;fc9?dL%^d9Bc=XuSecFv8G8gxV-MY545j<^58is&1VYJY*F>LKVa-l&N+;^B5n7AwLrIb#BY^=S9c>FaS{(Ri%*`X8^Z*Tvm-Nmk7 zj63cZz3d;fizZh1@_O!-iP5vy-rm3C*Jg5saJQWUWe~aF3!R3|r+ku683$5Ur#z-v z7BjW@ASv#;b%3vI-biUeuo~@bq>WkcySH|-iE~mbx1x&|1q31JIr}*YC0b7wpqz;r zOGU$%j9T2il(bcoq*?O`IFSVHh%~pV%H&;HM<$X2=Ku^Zsy8C#i^Cru^E;+q>Tzyk zDk^#GDAvrq)@4(TOO??0A*CV2jzdI1x1~6&b5QzKw`5(kL?bMV02R-?6{)EjmeT2K z=tNC7jLrxwpmp%P;}=-Q)YP@YrD0~`8=IOy^CmTVqg$yHv*c)Bo*0QR8oxo=8^Ct@a?1XT%RMaJ4{Rz5P9Sin!t{iC9y5 zJnGQeeJ#E2+ics1vZCvqyH`?}{@~Fr3cO*tWE{QPYCfO=c#K}Azcz3$D=p}bk#Az+ z>h8sUrycvA?VeVB767k|k1#9mZ{I8(O;0_!ZbzS-Pxgh$D>ZP+?%zFrtK@F3yW!Qr zN;Y+9fp_&lV8ZbE*n`=y>82?#ryZwp^sSx8(RU2L5`9O$@beYs=^6HFxxI zwXyHlaTBx(L3P^iK)L=m#9n)EhbiK0%nWRkYcqbaZ_X{ktOZEr{lObMyj`LH0}?a@ z#I(qaj?8~<5B)wTRb7Y~zQAYQLa_6SVoZD8_ij?!#myaujoB!*5`n`A4%z(kH%RQF zjU6A$+=qkZoF^)dzCd}H?2TovtN5tV2Ee_%cXLOZevE2F2(TG$#PM*OmX~LX;e;Rv{OV!$^a6L7n$BjVORYlA1j+sDxFEij>Ui?c`XH;>E+G;@9 z2%af3gGX$czxqCT`}{Jjqd-PYsTRJiA^%(>?4h+~55vV0S1@0C>yq)Ysl(aP>hyn9 zVCyj$!#}VeuNX7od|LK`5dc*B`l|?yb+!^0Z*&vvByo98~?m-!|*5p zZ*A3VA1|^SknGI1Ojt$77X;QwBMfCmx`>jh5JKMv`uJ#|8FpMbuCA6X(xpb zuSB&ST-)?+(tB`ulB(5gaA9S1^T^#JM+Zkc+f|}^&dumKM(ko^iII@0zv;FbHW|Kd z;0PgpEQ*_9(e`oqeEW({T;}m_J2wQ|T2@!kEUng7LQtj1)gb5Vu4KTN|(eW)X1ea{I#^o1n-8+9T$L`)X zyEIk;U|I4e7}tKDR&Tvmsdg{E<3C`Wx5|0%*FQRx)Ra0vfyA%?s{W7bS%4d2cKHk- z%~Qc?CC5s{UO+|YakoTppGKLR(+`I*LNNELUuVox@u}_} zf9mLx^Izrj0In~wC|$Y zF0$j@p3FS5qIg-J?$b95o{~q-$NK843nKNFUm{96=O-rUu!^78$JGb^1IkW&-0Ak> z4YcgnLoJ|s_;Q_F_Lf2JOkKGD1u8%FH$7{LXYHvSRvXA-pNHj``04jT`r@o|PFP5P zR_R|Z)P3PUX!$~yb^pyI*#5sC;4}8fG?dx9oIBUQ8mi?YcUL3ty4dxEszgU{xrr<6 zavp5{jTM&<7DUJmZaB=pn}1jk`{u>;1L(oWH#ZzF{IY^;UOet|Gthri@BKzi^gIA>* zI#V=59|-HTu4k$3U&HH1-jNZ#x}nDMH+(KNBdFdrdnhBIb>!(kn8xK%In9tJ8ufn5 z*XO2{RQKKOCw9Q~Yhg}!(h{NZ$1BH2J_fjav*p3A9k1--_SgZqDPrPNbY#r{(dF;a zCR|GYXTJ=0jU#6WniEDKh&j`Vk-iagVW+L?KmznwDZ_8?GEa*_argqW@krZ03P?NN zm#N08!6>hI$9Z?I>!Nu9d%#@|tdcbfd%ntNjuMWMvPh z(r63EhWB+!fa!?E7s>h_bq|~+zQ1bT7;c-WPAF)2;I#dnttcaRChpXMzT#WuX)3JW;Rj@a{EZ2O@Uw>s3ZQ)6<|Qy&%CSLbh0c_GifQ2fT{ z4t5$l!OBQR?u&|DSN)+oyuU{7Yb%4zX?0q$6RmnYmAC1r!SES96IFV~(r^vG?fh+l zl$!xBBpiEPkj{e6w2Z{iyi+C{-1Qtfhb|o9ka^*SQ7JPmh64k!gg>Z9_1Gnkhhh4K z8<+2>ylxioy|AVZF8udz49x*BF7%w53MCK8=_(6Wt@!k`3%AKu_|&iX2wQyR*;nv* zLS`<1lD=?cb1hM*qigpcpoo7TVp2gwCS3pw4l*ZNg!kbNfxSJuzA1!%>x!pLm*8tC z(mM}kFaNx?aiWk}bFOu5x_!oGB1+(xG>dlQvbSkhW=`WF9N)(HU>zyboSI3T5F!6<>fKV3E38t<%-61B`u9v<+S!Nh z1=q`amMzD})OS><690RN5@(Y}K)5{5Cvm&}8t|}4avN>Z2aLj|jg@z2hq6Zmwhxd? zQ9b=-z(4Gb50s#M6#znEkK~;0_k-(^?2`0-BXU8Zz-1<;J2*#`1Gw6yl4~EZNU~wz zr%Kf(HR(TAmbn*Yy{u0_2K;6OdeS9&i2aKNQzqd?tp4RSaMw7GSe?-e$Wr{Ff(+LP zq=@}*SCdFK0JCd81E)l=HfaJ|U&+DBo|(HQFildRz%Kj~8J`Ydt=2;ytYtThn`5mz}$TgPCI5#M;4NZ*U z4wFSBxYWpQjmQ0bMgWkYaW;L>7BqeU=X;QBMVM3ESqL)Pm=Qn9XJ>L>-Goy0lu|PH z(ygFKHuOEl0|ULwjp>o?)`Od%KVv++furK+5m9TASa^w}0rr@lX*;v?b#!KGNWcLSSdxXvfaml_eaL1Bhg4&K@o0h zgzwh8yO-$*RGdp1sVK8b%p7|oxMgy3B~U;p*U)|3goJDow>88kb=U3M)Rv)21FkaT zsL83_gKEQhXHl!3X4WQ-^lZ>h6a-C>4sKL2K(!7i$NC&Ifrqr=^y#>K-zrUDgiGPb zrFLwJ?r93;Ne8n&FzRQLZ$bAXlq)8~8>IYVTW*@jrWiz~MaW(Kp%M(*YvCleKwvGV zrjSHNZ;!WvsS_tW?@4_^#;~6I$9+%svxhUl9T>hZPZp}lm{zcdw6!l>lTXQZxBGp_ zP?!DtS8`IUdm|G~eYl2V+ZOta{jFp|N~5(j@bjj8#!8H!tM>hZ`xS|$fL_aU(aKq(`T8XUf|o$pXb(hq~B z3=3U6wo!F{WYnXg?!=hW88Kf8kc=y$%>kkksW3}^PYo-gkq>S7$+g-H60=DN{%jOj zEDGj@l10XbOeRmpqEb{+nBu?!muq!v^QE|MV*lU+aJOfN^pMb7RT>S-gs>E^#B|G8 z-hKGUGgp>?IwO*H`C^epBIWovs18%O|4bZ)cj+T58Dn>+H&SaogmJ)838&()Q0u_x z!8RM}^;dWCH7r|GQ0fYqjQ^Y*3HQaBBJw)5-e8B(>o{$FyH6{(wb4z`0e;?%J-Gn0 zo0WeGcu0E@gh8EP^Yd0>KGAG(+`*ADVjArQv}E@4iS-!2;3mOZrns(ye_9?scz0d+ zc?Il9|KOs`G}qD^dfXJJqwm2e(+ zM`>_vjnQ6q!MhuLt#L1Dwye7*upq{3t6(M^c4Jd2RwGX2?PNL55aK|BZ<3JOwz^U6=LmxgdP9zrn_`+|MC6$q(dRwXy? zW%^mK7ZWios}=6Wo(`10iM{{-92Z48She4iYx10mw{P+uZnd7CaK07orB5kX^L?i8~>T03%lm7OCt zwD-{_>AC1q)X2#9N76Nx63(g6T$1hNt>CSxDJq7~^40*jO+e_*mCU2$LM<(Er1jOu zqfL?{Wv5e5VKD3lqGb|n`l1}FiQ)=2VB&byVtj%kzWHSW!t2&ZBRh{(W&(}rHtw-$ zTw^mTv}kw}3!JI)ufhY&^2j<63n7uBySa3f0^o~^l#v1J&r2O|*K zo7ZD`vGUs|<4C-o&bd~SjLjwYn;M+JK1m)~&-%_uDdXMW!Z$=CS7(}I<);E}{xRie zkDjGVhV}0_>Q@l33SclY@Ni04=VvA)PV}WoZU6T4rx3R4#P3YSDqT_5HB$_cCHvx^ zeBe++KyCKl=0C5d7%fmA$Jt&Hw*LpT3bPt2%5cVQnkIduAmJsn+3=tmNKvm;8gC}c z(q1TwJFpPlql>tF-m{a5iOk>JIEThv%N!0A#^@X+f&8g`8^{$VG(sg;9b(VBrRe8} zyF2C0{B6U1rcZK9z4(~&OkqKctw@&7_L@-d(Bn5+SAjVh3T;uH-c7Pu2-_;m%{H)L z|C5(02|XY`!ZO&q6Op`c%c9s)Qc-48s4mjEuX`%Z9mETPL#|jyyA*|BtpO!w_R*}+ z@Xrt<3@&^dr)LL@LSvTcrr_eHAV%9({Hp0VXbQn?S^L*SMNKG8^u5kV#Y&ryqB5p? z?H<8Y>3C^Sqf!T$v>7)GW0xu^V(h*&hSWRk>`0!hZ=Er#pHZ0$gZ}2#|S=-@M?+W<1pDBiIuLQQg;xI zM=>+{(l#+MmDFG)vEn;fNvbHg+t)NtJR{j99oxJ;l4tN0is;;3WA1R(v<%GiQ) zcO_UAj_;|{H3?go(qMUu^=Ulwu@<_~T=d<9C$T}!nT#q0zOa%pp^ zzfStIImp5|AkSC4TXi_FK{di21fyaUh~0Wi69bX42K%K&Gd?GP@r9(l8@3+ED9VGI zy@^b?xUEnNFDtK&wBi!nR zN?Uh{iOa>l4v_GJ^MnSS_`Ls4n}0ioc;BvO#qbQoW4Jo^>IYIg2Ff?iQF2WzW2 z4Rff3I96zwTzPq`15Rw5!E4^dY<_C%afyf~%P*VYhXUn2U1dC_E_XX=fE?ga0m;_= z;L%L)1s-)G7NP%|h(ECuidxKsy|^**7eyfD(Mf@~EP`&WH&@DK)2KVCLiNU@rt(Y$ zq%;u}qpsd|k_Jr+eT=2O@wMR#9MdnoMDyheRXX{>PBPFOajEXfjy>FdpXmoaBaMo~ zu6;h^ZPx9}ikW3CXTtV`h$W+L(wYM#q%6F1@me)~=;ul|aRlZ{*%a zwc?Ec2D*LI#II6$DaO3wUV`M|Cp`?=c$8R=B^gZp0QvL5%MuVGQ%u7(b!?e04DTsB zf@T$CR6rD_1HyJtG;}G-Xt%;+BT1C5K7?mcIomVFU${VxxcSV)v=@xU31)*1dMHcL z*MvwdZNG(DlD*TmFB9h=A6~i)|Ft(^VYt+Otpo6efNXI8Q0@|%N z8Hln-$ZNE3v(5r{fuQW^9&aeB7sAvqR`4raxAJiw9{@7c?Gr&AU`QX@f*X{{VGQ2Hpl| zzEpvpXplE6V(`e41nK8mx|~o}$|TTkeo?81%S?b3Ql#dkFW(@IEN3=j+6Z8!!T_(W z!L}anP**$0`QipE7h=ZBXJx!*#V8ae>d!~*6eMkB`^t1kg1>TnTC%mt6{R7}YA&Rb zP=sNGH=1o)nw)u{GQu^HPzZb`4uHaalkbxOqPIwd5!ro4)5Mrf>$4xjMg;& zGw&P|Ga(uo59k94$e5jOZB2Z#D?GApP9JPApLnFR@QZuI_Px1dj#cNtt9`=*DIr5$S_Xg6xN51EmMrSDp ziwxjpFqU)G!OA-~B0aBLWpWYUOg?}(*4BjTjElqv2h5-^Z9aB_G_f<+a->Wh{XX{sO|5>-tAi{!V>XWUQ<$G6g3F552SubtoJX9Pe$+J|%qT=(+Y&txAiD!o zo{Z{-!4`8%P~#ZYy)5VwNSdWTNq>Bn*{H;8aLt>zO_zs_r-)pu z_9h9^loC!O8_=c3x3BUu#U@j_@s>dDq`Ut_o?*HM?%!QJ%A&@ok_npLB2*q&d;!tKpLOU3N}~l5H40{o;76f|7LuJGQVhA0VFm6JppQh^043&!N)hgZC0<*q z##GZJc#_Y`0Zbxn`emzzjV}^tZ&*iE8Ru$3r3;v&m^7!Q7QA~G4Z073p`xb(;)8 zWRM-}oUQmSDj*8spGGiYH=`(ETk%RiY;d{(0>%iy$gtgstA@(wTB0ra0L&kXS zrTfZ;+PcPf4tP*EGhxwsV*GUhGV$Gm_IXKKtVmC<$u7PwE0OW69yJZ<@1opwl#h>>|SED zeu92vtY`qVN*4y#7bnSdkdfrA2MEzf`Zq~O`6+igy-Z^& zEGuSNpoA9;1R?(eWbBxcZJCk>T-kR}K`0BF>SBZq6BK_+!Q|T}6>Ir;t6U96A|*np zKBI$tz`NIY5}phW(j`%2d{*D2Bgo^J^Frrs%lW8B2emNSPDW>ooQ_K zQ?YJa!$dbDmCqSjWbBhl)`SxKe{6z24QY|OaGbba-ySJpt4AdtCe%0+`7u07QGM;G zwkaeQ5RLCrg;Mr7#`!&i8!c}O{s*%xcx9;{?N2uQ{o3gdjJ3Iy(=NoR{-GrF@mItRpM&P##a8_U!_p>S66Dy$nasHxcV9l?+-{KS21p$RLk_NB+BPjesm;Q71A3za4$2xHnATk9*&m+LQiyH+UI0)5I4H) z=6P(z%B*0gXN^eL$WrxV)O40w`7q!ntQ6gzL{Es&v!PYgP!Vx3ovbh|0Gv%44!mp{ ziH*?FcMkx8{fe@yw%}|Qp4@QU;;+PhP+uw@YzsfhXDPyRfcTnE-Rh7rVuGO^Yk<%0 zOYh#5wqG;`oYk9GWO*?0l>rP)C*#P#T*NN2EpDKl_2>XXYz3)Fw_BQ zoi(Mrl+@1{%l8CgXDs_c8%-wswP|N>xW?xM;fyW^N(D&>mL`S^#TU2r`1z0;flM{J zNpZ!Z$qa#&)^0dX0_QEOeSi)I=_jrZ4cQ(}OHol>dIcO%n-V3VJndLcJE)y%@9DO| zu#b>7nDSIa^24PSX%Kes8PIYitQfXrf*)XK)Xt4=cmd8YlS+<_z($sOa+I5Ct|rJh`U8Shknj_4jsC_x&)a9LJ4M@IKDAuueC<>MKc2}$|1 zTtw_e^(%5uJ_aeuAlG5qe7V3E2Ked22V&&MnAZORpf$AR4(bGSBKLB7LT7xYJ3Eof z-LQS2q5{QY83c+_WF0vBHn0Zdqac;G_-?!u?U0FDRMIkKjlmbFPeoqSOQ>DyWjBCc zCP{@4ydMH7BS|OFgP9gZYfi$eW44Cm*HImh0JOLNS6?DH8$Gg@>fSvueW_ig*k(ki z@gFeeDxoz>6+0q{m0x9nUGjmVZ?2Be!x8JUv4MXL#zb*rdi&sAS%~?pjJ_oJkPWMd zsCVNFqBP3v=1DO;#=q}oi zvQtqBXg(A)*=0QN@5g$gYIcam_uU5Fz+*;{mY#Z$TP|+QM1#m-FbDQo7UbXV5cZ&3 z((i$(2{pVm!? z{rQ>V)AnBN@*U7oBCUlnePwZUR1zvCX6j1|*XkP5%PE!L$AEZK>uLF8m;$9EJ80 zxpp_K4h+Mck4tVf_*3!S_wGcOgJR)?XFyLU#Ur!$qv;pfTxm5^C;A+^n-qZHS>O0P zjg~rB`&hb;7&Sy9ISe`cGvz0ekas{4;PjuCEnIn09-k-sXr`7DU#GYJUb_9=uYY3a z?SBWK!Ho4r1xj1#E7^Pf z-?Xr7FHKVuyBV70tWMrkQcX)j%L}EondY6}ii7|qShlj_i zckn2{F2WSIhG7`}?s}~wa8{ka!DY(BI%9Fx1}rVEDW)er#bpXFY1%Q1|Q`_LZ+R+J8h{|d0c zuy2zfJEs}<{ii*;ZhY-1kSEEl7brNNu{$W$nAi_82WRbm{rneRg+hb0FKu<`waHfP z&iIz+Hk9&vSx9fo=yRV8KsBorMT1b2Dc=ZPUCZBT?UK!v_*qA*U|)SD?I1OB<+(LD zzHpw%Ik(((p{;RGjS(;vj+?c-fg1v!UX;QU@cQ9$XS5J%uSA1Y3BOe;`bWP%y1Bwc zA5j2YA0qS{sw2|53w7|uiIB6Db*Bg{*Eq%Dd~KZL9poALVLeLFXDfIX@=ge_U*Vig zbs>MjNIE$Akf*5E%oRR@2_n<%%$|$v)!BcsFR0e zbzdtf__9oj(exEpFo5wFS+gX($>t+Nl>J66@rNKFU)L0I>>$JrNa3iB42FI^($)g| zX{4HfX@E(1rFLhMIHy^kkz2ZQ+x42^OK#%GvKs1Xls$c1U`rO-~? z{$W=##etAkxpsA|E5S(jd6si4a+P0L9evOQG&3C!Ru#Ag7VNLN_J44GzUSPj z?;lb}eA=LgmMSA--5O^M4oVe$Vtksq&GSVNKZgcU*!RQV6DL?*f%ifC5A|5W<+ zR)tp9hTZ{(MXQcKUJaiZn&@ahj)2V8Lz|N_r{Zii$ z_N>TpE==k_|Ge!9DHxVhGqeN6=pXeXQeKmy%{-)aoDF1JiPx&%jJ<10&^g#sar$N0 z*3C4fD9N6iEV&Er<^t5)5yT-_*;GgQ9!{_8(IB{GFX!S@ZTC*2K;RB`+5HX}=`&cs=l zTS76-deKs+si*&*q^+0WQ^I^yQ)!0eG*Cd)vLV_Pb^wl!O*B*bSrU1T+l7Bb@y*y< zwq^d0O!Iv{bFBMcdgpU%t668SEsGDJzTV?!gq_muWJhX@4-3b8ly_6?|3(@bLMrgfmX=}jH0Z6&lllUzM`0x zSr)?yPVz|Hkm-99|1hJbQ;xQsAWr&=Ww{!-E99`Dr!ibF3+0SMvltBTZ?%>hS_Pbjk+E?QXwjk@&0yue$fgj zFTa!~=fhyI7p%pf5l{&y8vyh{6H}jiH6c0UBiG-(*o#U_5%Yx=MG98C-#*}D!Nm66 zDKJXj0zIRnl*jfe+)uDgD-Q<1@YaHttyC#p-Tb3tALd9qVVApf=RTd6Jm{X_&$QHA zCPnJi+n#vyb!H76ax1%itSuty6L^ah#t=mEGUepgL6pA!rQ4s9jgS0#Z3$iJ`LHTd zJ$O+)Uq{LG%N%iA%t`Y3=Z)Ni)_>~$Mf?fo@#1cEzY#^BZVkTG*ogGghghHH)32Ku za=j{*;Z`m=|Hsj}hco&AfBc@wBoUGMm_t!cC5O@+X4AnbIUhO*p{SgO95X{yJ~QV~ zbIM^PB<_0vfxb2kDPl*@o>vc3*rFU_Dv1qj%Np`UuF8XZMQ7E~zt)ryVycU8wZc3p| zgz4UY{F~1jOjRS{90|WB6ThE5*5rfwM7ku|8}5Ewiko+R@qKx|V0pMgo4eNR9C~lK z2xzIVzs6tub9AN@K-lw*YK3LqzI2_%Zz~yvF|^@c-B^zL*lkde%l)kPo;Io>xUhZ& zbcyHP;G+#A{S?k zQoiIgQ`m+$Q7Jg)@x`Y07_YR4l zQHB%c(_uIAZ=OAWeYF;|--x;}TXZ>4^g{U9`mW5r66=K?&fHVpIQw z$1KjOSQjUqex&27$b?@!4s~fhl!x7`i$eZFrzmQKqIM85*kzExc}Y3*QTg9lBY#R2 zs?dndxjdC@6I%;&7r=&A7tG(i-T&@ZhY;RK-+fmU{m<-2^yTA^er0q}AtO>sizWtLM2At{9Rpa}_+b(1A z-~X9PUSD2(c*<9Y|7}u$=Mev=Pg54$$KdnSDdSu69#Y_pS-JTId?TOlHeR>0EtKM( z9aZ6YN=M-WI=H(S*{6<6Dtn^MM(&(X>r=$9WP_{0h>KRImL}A@)_AW6KVX??&agkR z7(qmL8=DRje4ry4-0|-B(wez_WsH#8yOy!-LANBoV{+uZC6;O6SnBh1*p&u;dBv!! zFp)Pl1gAYuFRYb&K)RM09JYXi{|dI8q}u?8|OB zwTA*bSba#c{il4*YVL)zf)14b-k2xMNEt1+Cay^s z(*+OOwT^uam-OiN@;`v=ncTKk-7MmNermhZ44G>AvWlG)+SP|W5{z>zd}f*%*{PeZ zn^J!Yo%CYJ?|TsJ{lEL4XF4W)w-Nh3S|4jT9ln43Hu=@9*H31SjIY@mMP13lecvdtn1v;f51C`wBp8M`?K+YZ2os#I@iSLViTJwz`fr#f3HccD2{Ex!29z) zmU&A+iC?t&A*GlX&dk5^R`K$TJl zj|P|Hpa3;@p&T#n(1 z?GTFC{7ssMF0+Vo!lox=I0HI3g1-i?gcy`cK5leX$HR)bR;e?Fer*en?b7r*Q9K%9 zs3y67?!ql|-ek$L$X%RKJrAm;-QTF>?E9rV_~6Al-ChX0{nm+i9xP?Xc0PY$4OVMD z%z!V2HDy7ZT5XF=FHP%wAc&#=&le{RO;OVbt|)l_aS+aIs~x7)&vx z+N7(Nr5lTby>8Jx2j8o02f7nY0O{L1f*OP!u9YfzAV2ri{NnT~6&>+1bw!kPcbL+Z zOg;a)G%g8^kze4jm}tj_6NcWZ4CbBrwJ4uspu8AyAV07?dc@ZNJs$CX>Se_y)q97l zcjaBm(6uK^rV%mZ-7VH#txG?Ratj1(?O$(W8Dw$)Bb5BLkCFk1Qe>xj>sDR?oc6Vv|9%UDhW4!*dBf>R)Q~%z2A6H_d%Td?&rR125o1y7-5vb zjHMVmX1g2vyBvK&LprtXox{__t8LL$D>1eoVloA@r!JXHj(&;9EMPn}f*1$#?UnNT zX*vtz<9fCZVB1vIi05hcE&kAU|KGb~3g}m!D)`_KYUOjGf-|W5+nDmN9;#Q@CTm1_ zcg!+9hDOT{2Pi;yrQYcNe~7aJx0*%)mJ3n?o4Cl>wN*xGue|MnR}k?41NB|ppa z=9LR>7h%}Zt#8y0bXw)7c}L`1guY%~%=q_W&b`ki`eo@ttw~8edO1F0BC!~%HmmnQ z{j}uz?jNq-<`nE0Jv}>5Y4kuoY4r@jBGJLNZd`N%)9$+|&XSWuL=M@p?)zfc9J?;|FS-)&m`F2< z@Lb^5#&W{1#_65YtM@&4Y$~%so7pIq-vDPdJ>$L6$pEIk?F62`x2YPkbFI8Z)B>xS z<^X!2L*;==No8H;+bV{8|CpfDG_Hv$FoG~1FX7%9x;>Od&{pr92CxxMu1O=TpGLX} zdxFDPjYBI9L2ie5L*~a=4m8)n+m(`U!i(qLx+=W?{;ig%2M&&By1&Xx9!ZV7G+RlnFHcu0c)DOeC_y;*Xn7=|zTlqeOYJA^-maafj=F3(+Ss#S`oqt0 zy`X98Qu0wSdQAc>yVf6!et46TGwm7Zyl16U&&+DqINcY-wo`Ra#6H6M=vdvZLnHfP zRv-D(b0IgmOsNF^q-J}4F5Mr%!8|KxkWKA{`Pv$Q;w|}Azx*c;KOyy_agvR<>YlrQ z3ir~R=v;Ltf|nY+{S1%e`m4hGn!g4F$L?7m+)t9GYL<7*iaFOZAbZ?ip!HPz^u3nn zA&oNA#H&&-nQA!C+}C+Xis?O7ce|6M>f~}*0rNsipL568b93q@b%s~A+LrQXXi!OX zcjNP)i>o4{nI#wfcT4*h7bhBfx)c7M;-gBHYGCMI>cP*MA!7diPlcAcl{|cp$7EVC z{~8ZE6#rXx;S;jy_;X|OoMPYNtFd$T8d;1L%KbgNTXoOnn^zF`$9ZKzf6>t1pT=8p zcL=S>8h95RoGi`CkJX+#$4gTAjC9q^DW+(C*hbq(_xSEoRNx~-E83ot0 zd%t^egi7qVa{KP-H=h@8zZ{df8_P=utEiX%0V)+kLrRqK6mblavc|H_{xkYBz%lLi zv9)ZAiz*Q};k&qSv7a;g|17_^fKRmJj}RrOTQZ@4-%tL7zll)BqbFD~u0sX>F7huG zRs}%n>e@Z(!9w$vaB+82 zn~uQIg<#ozSv@mkPcX~PmMw(!o?l!14LT_}Wwyp!rcLY=&%uj5>u-}~K21+mvn5@s zzrGgh+3y7-V{NQQuVvIdfyN4OGYIxrTgw;AqW?~vd(lE?;&Bz!I}IuWar)x#w3381 z2`lKfN{4%AMIvc?Ch9TniM>qnf52Uf@RRF-2vCqU0Dv`LABN&+R;5d04P+ww&|R7A z7j=8?OcT<{8v=joA@lu#=6V2j5Zre9jBdj72+kR~Vztx~aFLnZbKXlS{UiPq4`UWq zQvlo621iqa5^=0~N|B~K0BV6j6|Zk7Wg|~%o|eDGGWX;})ma!7goEq6vlu?4s27La z2j+{yVYM4dX6ZTl;%DQ<)Zfks3|OxwVRqh*ZNk=`nbOi&jQb!&h#j%TBK{O2mxKhS zqyqrgDemcMP>f)BN*iQ*QY450xx2c;eJ3v{)<|k40uc{1ums%QZ0Hg(EymEaf&u@7 zM?+$|D2!5(%0}TmaYKtcrv*hq6m~MX#&??q{;ht>sTAHK{XPMH z6h=JWp$rPgL;^PtWC8PP`R+|u2H3u)konTl$m?XgsQn$KD%T)l}1OEe#qjoYuV_G`iCx4j-Qj;zH^$v!Ku_T>4-~-*Pg7bc}%rk$d+YGRkz% zHSS%Cs{G)3<&e z@JzSY2+(vaIFRdsQ4!p10GjzeH}&*1xAo;FXiVFz3tPD#EUrt_-b*g)oF?-`hOMH8 z<=fyO$GC$gx%~aena<`eiYA_1#IBPz}UItPo;CDDYS^MXLU)bd6Mm?Jq=aD z25!j@qO|6wYNd0}?$@yU%n$dodDwVf^N#u7W1Gkj`FeR=tm)d0S?G|9l7N8%u{_Hfi02LBIu@*&C9iSE;al;RBpuD#4XdORIO;6ckh>XcI#luB4q zXN;sJbu1N+uahp@D~%+5twlikK-TLO1e@xLuEa+BRbw?x`t<6rvXX%e+s`L?eb}z_rvJ>q}TfamYYYBowAQrJn+Pn=OBGnL&!$ zlyPAYIF&L01RP1IEXWEE7rNPvhvEY_mMPBw)7UxyxlcaWH@C#re3{Epgm<>9`9rY? zI&qR2^~9mebe$M3E<BfPaVpfKi^s%p}ySBxK7q#^{F>e17 zg(1wLk)+b()=j|P2TnI3pZCN@aH$MBBz$y?{w++&VrgH$c6Qh?J-y~n`Zwtw!h&d> z@83{@?3@ZsAoG+t^c_lmb@HKSmrM_2lR9$8R82$w#P zwd`t{*Dnou<=Wv7+R4BpU`k)k7+Aq}U>E#ZhFuQ4-@A~o0&yBKu}Q9Mz1n^ZX5+qb zr9;H8IDm`OAwYOBeIk7j5InCm7jh1H@Jx|yz0RHiN8s!tG^XX8sNLZtJW>;DeAn;P zL(f-;%W8Hd)wvu_54NF)12vW*1F>E38~6aOdrE6yOKU7G@d;ELv>@p|TCLe}Uvgo< zrf4vj0K=;h?kG~G9!Ej=W|li$@UED~4sKI-%un$1{0;8O$OGsh>6;hEhY4-S1F z-F}xV%m_&s?F(2QSTu{yMDot^x=)e?&umJ2(aSkRYb5hzb;p0>KkF#+VmH9!h40fJ zMTvj_NwWOm}7@8L4ZjhlOqUfo7Oes${h-!E`{Sa2Ct-AbX}o>d4?2 zAUh@`L2O$gFH48j1qFrPfm6F^gev5p#1K9+arV;`@J2}HZg%pW1;2(*CQ%1VV$7mj zlRor3BsmYnx``{?5Iat_uK<7mL$N?!Ly%_;6)Epf={NTac(oucEWBZNRH=rIE}V}8 z(^TE9VNco5Fu3yVD7+029@! zH#@^10ldOTl?t>D&JA|r1Q^ouX*XkB4K>TAI-b@-{BxW-VH2`?fNizQhZG0g|BLE#p~8 z_vAInD$p|Xh8f=z-Vq>zIgmkwaqj9JS;+KZny0soqo0!O9={dR*=s1j>z>5&70sBqX z(63}QiBeHdG7Y68o5QQ3Dcg7VFen(Egbvebi;J&4;@k824k)H&$diz!BwS>=(DRpV z9-4vJ0n)X{I^K&QV7OHXPO%L^&tQ&|4ttZS0*AjL>dx`H1_UC~0caOCZ*v6YyNSRQ zNiK<*_cUN{aVwXOZ_D$i+%N#pGR%xR8p!u`1J$6;v$AcHODjPLpS>R)TDD;M<9W2j zHH}NkJb~9*Hc^T@l$lliMCVN;nIY%}EqlBMCU8Z`rHu6fJa8P6AS|ktIME>D-l~H_ zb7_YrNs2Z7IjO&1D!GjCRQHruJVk6|h^254zesuC)35~Q#S z?M7<1z^M|>4Ki?4kQWEc?wR)Cm=jUE1Cj$DyBFvtxw@HotWURBR}vj@Vd6wardXmq zazq3QHwR4#&>FUEk=J9Jlma^n-C;-(QLupobo(Gr_%A$yN3FvMtjp5}r-q?4VxZ5FC0u&5d69MiLRIad%}1Aw z*B3D``S4JRtp?Y_&%-Z_v_U78rfFI+Sbgx?j;qtG<)as?J?tppqK7j(8^FeU20e-M z#>2X`rAOHDNpI5dvo&L?EI4CGu^&?t}b+FItvw*Tj5P z)Ds0iA(BKtq{~t~?FF3istM_dKR{qv-(Aq3l|JYwJ+q*rM>k*Sw->;6h2QxYa5|o;F-`}vml_> z#OMzPhbOG)LI8Y@JEHfKVy(|Gko z3O35x#H(~VCK0?2FJ}VwGo8eSGrbN0sqkH2$^f1_yqcuoy<{x_GM8r+k26>XO~!5$ zHQ!+bRdsLD5j+!G=xXCj5g$lI#EOW&1{^CDV3u@jpLdi?C){3912S0&$j<1&sYnWT zgv0@Ne$HDr`?NkD(xE<0a6XV#|6@oOTv89TH({GT_$1;ieMK(e9URIY-GGvDYxCU% z2%Z|Ic&$A!QOX6P%)_Z!tf-4QCToLOjWKi};voqMd*Un|MhA~S67&v`c-<=|IC*J9 z>B_RodR+|ZrnM{*y=t)r9HI{3g~I%by$?$D1h8>bcSRQ|;=S^iwkYG&s$wirZ8<#* zFQ#P%Vqg)xfj0aY`5{m~#r4FGJ6$=%fM@bLN;L{_X*P_B-H_bnGddh*W|}CsRk@6B z-wmZ9&!vTL~r&+Q3>X%anHmg38a zfVAx4uJmUIxE>Vj#_AdX7(LjD{v{~lMRq);idV`rM9$`9`)It*adBppp^xMjRuphc z#JU)}{RJia&E4L+C6D0;xg)oNdaViOLqNaqtafp$2mXT*av4$NfovbhbnTC;+l$qZ zfj}Q1Opifc%LLr+u5fsbi!@E$C}iJ#ZCml7<>XS3?{;pVHNqJNx&^?1ZRq-x;{9d67jyS-{3>^nQnNNb=BuY)NQL z@{WE-V90%d7fK%V$sPo~?qcbKKFx6Sgg}t<3Tqj|Wi+-vxmmyqh0cZS{S*<>cw<+u z&0^gi+7QpE1jMg>p9~#Hc~-lv|&vzuiEz!-8J`n{V9ZvAKmxq$L`-8RU%?!lfgpW;fN^2l`capVi#{U~cJv$16 z6CL(QX<|m`My3-%L9NqtenWto>NEn8##@h8s;f?b>b5*}Ub~qnz+W;Ujl6TiQwMn< zXQUFVEn*Qb(1dsf1t+GmhG=WK$8dYZSDWzpBmex@cg9o# z9Y{D9MVmT>;Wec_i`QCG5Bfp$6Km*N-q`Ewm3XYFph9GX1@%K~=8Rxj ze?N5ew|I%b#iPYl$6~Xivr#H~939*<7-^V?aV~()GxAajzaz1tv`F#DJy|pDXFIV$ zMnR_6=XV250A*#$&T9`31K5Ow4@kj?f~No2j<;ScspufjANg=(P$5YQ3V&yUh@9vvZh#}SK&>h?kA zn9d1(nZ^nL&#yAS{q#4}Wwu73FjmX74l9|CB__5d_2TX0z)=l`{gLu%m-CHQR74;y zkxrg5bPBEZ0PwtsU}R3h+0Zd-7h&Wki;^pW6iEs^`CIHT9}-~ySs=PCZb5^lx`3qO zYH~HKxj36`Q@i&5!3|(5oJDybrISpcIziqChxxNLqqB-gDj0UuoqJ>+*Dcjw=_GHbO`jx3R5 zyHbS9H;#e^@6E>wk+oj;;{?uBiShhu+4T(h#|&dbuXcysw{hRSi|4gflO7#O={4dI zLBeKcvEUIyLU^U8?eT{6#SL+N3gqqOJCu|6lSrF+3r4-=8Vdfb!xELiiZ?p;fyZ_& zr72hSD$-f_r64`S?wO9sH6D^L+OK*o=S}2frOw!5M?mK?$a?X*a2`niP~NAkVd>Rg zA{kBe<96B$w2C8KsWlUTQH{`Y-?9I8_8`70zT_k9^BP9Al3Oi|YGhnqlEmZu_ry+m z`T9KO1t)-G}Kltoj97`<-P zo-xn>rhDjqAnr){Kkq1;AT0F0IxC{x++l=kx{rO6GkOo_Gb>SKI-Yt7U zs|H$15u1#7cmf{VsT}cEGbYb7SbiZUS*Gr+H=;E9``RG}!N5Z;|9$gq^?2kjw>ARf z8D6mlNv-`f@XgGHDbZOgTN#N#w^iV^(kBuhYH$*Yr>c^ouWxjLzCWC$DO=s&3B}JP zHR%9l{$37;p=4Ml1Kx#FryaCg+QYe5yO3}+bI<&X>8n@#%^XNk3_Z|M5OcHn@qns$ z-Q4eeaw9UY?i+x-2vzySaB+o<q0l8w8S=nWp=;FHUC zKtb|oB6aGZ)I@14uI=>6c5TVVV3bmnPgZMEVgw^%LFv#1dW+~3fAz70pr4G*v{*_Z z2l@&H67wvQ%hOXBW}B4Zx|&m^=fR9)>YkM?{Y61q#Ue0B3pIY=i8sYl<~ zF;7P;%0p9n1Ram4*qD$3yi9I=GS@$f1HLcuY;g<7!nlSCMTsP9-xIQO0EkoGB%f~^ zQ3Mnu={%{;&GQ{flquWqD~?mXA6Csx>Z=Al-0dUJN|~N;E3A+ZSGlI?P6s0s=eckB z|9Gt#{nYHm`Rts|CQr?yiCgt zqO`}n(mJ{G2xKJgtpyM?lxrTw#6=+ZDoD;T)AE!@Y3Chk&u@kKDe(4CkfQ!9%gApX z6#-eLS7!|pYwulDtT3&>zH^MG*1<*m8KOL>J&P5&kL53dvpkWb8(Wmza|Jpei8Wq5 zZuH7@(v8%6-v7kaes!ef`oubo&D{HF`c^3EavwxA`1_-xj$clMWG78E@hq^AvYKgK zs$auP`!>V5iyyp0Cma0?XLpcKozje7jvnWs5yY>D$W=Vi`44C*eZ3UgqUnBV?xc^p z&5>JyrA>g7tXPw_#eEs}TYSFGPj_R~Hson5MIu-EI9xiQs@AbQlbN5%E1{J+oo+9J zwH7qagt0^jr*y@W5xymPTIU|Ns8yaysD-7d5FsXLo}X)5sfpqG-{P5B% zPk9~X6PrhA>Wr0wqL=Mns(6$2zg}vZf>1JBC1*?*vTN;icUzbSA`mo*+ub@Db0&zi z5r3SG6sF&2-3abCEn^eIZn}-J83jT6Lx^&{o$ynb8;9+!t4G1la;A5^jxqUG0%fTz z>eT!9;d!`d9B46IyEM-qQ}66S77baQke@%a`8y`JV)=mVpl%Hgh`&S%wf!@QImlnC z55`>G68n--hqO!WXd&YF59QZ;J@&sf7?*?ph3))*z=&(a&iSe1>g+X9t|83=A)3~w z>A>W$*nQ&XNjtlNI_k(hM~~16{+RqpHxcYy_JRDX9slo#VP(|{I(~s?sB7(>=&2I( zuj%dI?JsW)ouy^SF0Q})&Dm~8mt*ouz=Ae>qogdvc`~8(4Bh9+%OhUm z&(%`!Jx6S7Dhf{6NB;+OX7OePfCA{ohC-V*x(?F#&Cp@41-ey!W>Hc{ZBAJSof|-1 zlzzS9-1bg*?8@{DM=DPoFUvM{U$0n8z?QG&AyFeHLGZ6#MSAB;;T2jJb=jx2aOq!e z1+>KTWLW*3QgO(--r>(qg)uRR*r7agd4&D6bDsUnNf(W}cwr83Lk^66c|0PhP4!M< z!d6Q%jS*PeqFqm4lY;?tX>0y)Rm1x=|y z+;W%JPvU@7un;EzYTk^3LZV$pZ91lmW~@N*bHuD}COc!L=%csA()|jBsCGZWCzG3! zpqV9$cC*!GCKhI?>8JrZD$7}St;pMv);6*&0A6iYiO2~!a#Xu1WM%YJVFcf{k{-eK zC(?I{JKbZ{3x@7rFE9JK#iezH$C^eXVA~(*YGvrIvbhAeX*MP3x=@oQT-P zdoDfy?3yd^g-(mxYE_ngy8H0n9dXjjE^yG&Ldg{Ssk5R#Qxd=b%05gNWElm^MV~zv zB%yC|oGVxzXehM1|LgWGgnWZ?&D#1}Yz@Vz=F0H&Bs;$3Joj}6v945@4I;2`JDfmnF-&oB;Nx_mXw&GsQa=6q7j<;h{5;m<#|f&%!To>G>4 zti7vE&6;ob^*cF(TMlp1B);Oi4@vfW_Ga{v!}PTiv`Mf9FS#Gv*ZHr=%3U7op(epl zw>5)mjcQ$LXZ^_>Us1V1wmB9kmr!RPf!Hw8Cyzb>KOTAd-{OHEqzOTX2+++>*CNii zn7>{l$YVZwuyK{=@7MRYjyGs? z26JdLHwwM(j;nk;w_?E`=!l%vN^i)QDt-QPMUn4?up|0>QiN98tY_HyQ)+~ln@+?0z_R?sN=l67VdO{TIN>@%KJ5z}) zf^Gok44(r&K90VJV|AV{rRLgIK8|lco7BthNf44^HceS@SPX=G`!?3GAJwgL)QLI@ zt8N^0@O0pOr6Ra*Eh?CG|Ox03dL#Q*shwC#V(v$di2PlK)sp0L^v4VrCo-(I;U%vhsah!IT_ z;zci#Ph7m^V99SRgnLszt%3ls{ySgMJg*8YH_1vO3$D%sDf(WmG6=jA+nM?y4?>%*Eg=d$cvm9fIHD& z*-yT9&@~KGYR7i69`NdL`^r0m>as>T`IP#CE{ah`+ffMDkkXCmD{+gLA|A^VWEMBY zi%gLja%9)2;AK(9L5t}^sNoHG6lDD#v8Aw-(zq1zUhJKdoc5IddS-DUm zMbP)x&Geqr1wm=6?ami3PIpX@PB(9D7u`|#@#}Yvl@!0uA7z1UaMs8Dt)6Dp zC!-J#+Q^@}x@sm6$*59`ytkr$>u**#(PTl~40pexO(6_Ub%3#S6bsk61%;^~JP&g` z8~vN?|NGVXR9`|`W@udJ=26mb|LC|y$)rGf9N`7L^8oeL8c`tZ)~6=9?T5qllqP@x`tND9s2AUg&b~e#T0e#Rqyi$k zs|C5_yFb+)z%U_)7DA@-k{OBIr!v>yoNYQIxiyd>hR<-9};a@*dZUj1=jPS+D+=~h4U_1FdsWO6w!ooZ-R?U(c( z4jx(@s$R=Hc_D0WK(ieFYX+>cpQtv4D9Mn2-U_$$_sszf2-d zGZkvj>k5PCGIZsm>_7Kj@hHh4h3Rh4T%nN)E32j_)h(%wI1UUo0>6)t%ScxCICRHQZ^>L%PAkX|70X2r^1>9b>3$B zN1xBwc*r$W;hP4J5=*}c)3A$iw3u$ZQYFUfM`tG-OnBr;DLJ_c@lgAA>v~K|zKHko zJn02GI_TFIixGFbRO@HN-zeDJ^X7V;5=3XaZ(47zcQ}iNaH#ttF5DGm6-|}Y zcZjuSx84Xuhy08b$tZ!&P_hmRqkpBDF+ZJB#%be`hp56Tys%paJo#n2LCx@aJvSqut>4xhuGmPAA@8yxwZwt>Occ`^TFjbE%OEs=l zJPK@&jw*v=JfQlX{n8q(s|#SU_o-2NM^GTn*!?rlOd?w_{&LKLpZJ@S{*n`{>!^|F zE*tJmR_IZPsqH1b^rVGU4~yEEw)g+s!}yLFsS-9%jDcHimaT4=Mj5Km@7q5Kb6@`* zbDr)SrhL4-^Xs^1Vd@uxYcW)S*4%#S%HRiH^Y+WI{JbLlP;KRNnikIQW0N$wVxBSt z_*ILBM{fIFOaA95tugVz$cJPLi)m8eQ4(vbstPAi_D^Ic)L4QIt~>GM2=9l2iLRXN zK@eN*=5AGJ=%*) zM)Q_+K|SO#N+y`X*PZ=EFfHxqr@_q|m_CeT=(2f>!UVnmrUotv!bcKfk<1}ctXZzZ zQlRwf&EG{%W29=XE}H*;fcOpDG{?^mCYuME$zHsv8en`-Nt&b2l5dc6)abyA2hrzd zZ;O<3FUoue!AOfyEX#xkryU2E>K_RfF8C*5GwKgk7mhs|^B-6&D^>pH-2teHzbW?U zkiQap>+@5YlGCdak|H5;>(pu+^};&@_vsST_nauX5P`X4M*-juUMAwaR(!3aUz%{B zahUYt>}7#Jf21`RlPriC*LA@wTGsyUnD$cvrxn$MpAH(MH{p_^I6J0gufZ!T3Um3* z6$;Hc7-kw<5blY-@V9RPAMB+bWS!QV@YK)iuF;K@lnD7w3CBF_D8ixf&(3f9ez2c` z*7+YMCq7)N`=u1=KeSUm1X`~d@}tI8x)RZP>1w{;Fr8+BL=7ysq$o7IV5&6o^o{V)E7qXA4=>!|KkNL!X^Ul(!CcbjvZ()n6OfglPXrVSNGI%f5rRgSM4IMRbyTs zTKwBlBeq2Ra#oRPDmiN&(Js=Ie7J-}+f6^8)Dk{0Y}|SA$K~qo+4avkR@FZp-WoYq zUc6g1@mEpbmd?$+Q4&)z|J#+CsB>LsSlpIzuvKE!zj@}pWqDlnE$N4C8i|hSwVk3$ zBau;thXFrtMHW7FE}kvVZI9SEj`cVf7x}h9i6WLJ|Gr~Mp7|f}yXVi{Xb_2K@qEqU z*Xnfgts3v{ULzcJQe<_F2$@whM&Fn-MdkDoB6JNiZ2toW$`e0xe-iK*(Fn5ad>N?| zWr`>*OOgq6%mXKiNpVd?9Z&rYs-Wo;m$wq0#zu6mJMk~OR>PZFPxC`uuER&mrhSx+Am8kkb&U#Eg2L)#i}|wHy~A+aI%JtwCA`fxS|_V zkHV7Y_&cVmv%d;%QSvugca%SR$yxUOf*#|*s6iUMl-{?ja>R*M=juDqHN*ej7?kIF zH{h04RFyQ|XY9HK_+I^_ZEXPq1r38@$jt(oU7@?B@1&h-In=VcJAVycSSNV`K#41$ffHQnt6JlK11)s8w!jG*7u45ed`{;H ze@<%KH4{E_O}u#=&C4?9OZWbqb*(5o_N<7Ws4_>${f&&*NWAK ztIWXB-S^?0cOf+qwi(84;kIvArp|;M_kYI&2{J33)mDSdG zs`M8|+|JO4w>y2q2j|b2X1Md{vSt6yXrPIHa(Lj;>%F{d{ye4Zf)21K>QDJnKp$xi z9rVQHcW4mUu#*};`EQXH`eg8H?Dp<)36si`fh=TCO zJs-0BE|z7u5Ul&m?-wZQVXl##FC^qj8&d@!3f51dnfZtfDzLFGK6LxMdebz?)+vaJD9LJbn*%ahF2H54* zMDQG#g(gv1`UHjqUpg*vYEX~?R!x?`WpSTF4jJ!i63zk-ZsER($*|=G zGdj&DH}@>m0KPpF2+0#>Y+$;^AesA1IK#xjjUzUmS4}XJrVqpS5!50Ah|$#42ltKIk}*$FP_=1NzX7P z#Ujb7NE2lKc=8f~n7R;<$?1hyvK&_D@s28MI=Z7{fpEm5{DD1(xCEp|Bn(9T zgO#fCCR~z zM>|%Lj#`ghJL`{i+{105w>*sRM}Ki>LoCb&Kv%_cxiXJM2fmy=XZ!VzFjK6tUgMMu&Zh(Kx@vTDySltVHlJnw5k_bk^-e)8K2PU>)R!3w% zJ7k>If0PJBY6%ZXKc(bLlA%M@xi@##(WAGmnt|$Yn<${bG-eafzq;B zMD5|I?sat#j?1PDf_wGEWAnKAqp)dYDeT6foRyK@h?ZRfx)tUa^$2>BS?Wsbulpa`DC>|-=&+Y gM)C-<-~Ha6cgm~4Y{R}HaT7Qom@6llTwT1=E765rUV7J zY;05kq`?)uhQ)&hQgEj0#d?~|%q_9Rg?9vL*Xk3KqQ{V`L)Ny|dAef5l53fqH{{)t zmyaQLt={7-M>we$v*&3sfjB$d><;t1g{Q_p+DYOv;5!Mz5D6&)6swUQ#vVOlgAHG1 zutRaX4he@b^`4#~^%@S@om_0u-QU=}J7BIR&^Lx>ZUJFz`;n~nYuP~ez49GLP~D_l ztarpWB+gvRlpWm;>-SsAk8}6AodTQu`Xl9#W)F+R`)#x4AjOn^F5f>h_ zk~5NO4S6j*y?wyT9KhEK+upN?t)VYeY<+_PNvq68^Zb2(|5{PLr5Z2t^K=MkD4phcUjt>;C=e;SYyh z*XMosyk5^2(HvQZ-(3}6j%u_siE@Bm{9AjkZ~A&95ccVmy3sC$@@p4{44!EGgwY`V zm%*J6k*umk#r42eqyyQrWcWl)cf{Ot6cqqD?Sh9hK4Ut{E?SFGb z&Hn>3KTvNVN1xUFj)FPFZ19E)+F@N)?gCYV?*Oc%f4R(Bq^qkJ6~Zni_)Y1R7$FEl zaiA9JaLw_Ym*Y#QyhQD4Xq;o}LtHXyh@(^^qV$|yZQ=t2#*5R@&-vA0g=8n&vwh+D zQgU17-b4iqdt{`@nib}=*EP_Tuq;UN($>8kIf`yY=Us`74HlaOsnB`gd@%~)3`X)Nd>wp5$nX-XU% zNiCs~gD>nlGfBWSqs8xKDn3r?a!*Q0x8e?;nS42ETd@ijMgy6eBkgcb=g3lNCz)8E zTs~o^eAys#0tTOpy772?o(o~G3#BOg!`w33IQ>e(W=aXp(0qozt@Sj=->^7FNpmM; z^+Nu2a$GvY1|ULBh`KQ#wrtBe)~TrTlyVO?+1|$U@lDehNUQ#il427r;{y-@{D5uEsSn|CBu^zq?3_GAVLyImXFuAWua~3e=(n(LW>Dv)jtj90h zcfm{_)y=8)@i9$&J?xl-p4E;A>&qU?H!I7uPz@cSSzhv#6C%0=Hl}Tf*cU~-6-F6x zrWufl3fL$Iy;`sNsU&muDiqXV9yAL0J_In@WX^t8;vVExEebKy`j)4b`Se3{46+n5 z(e4kWot$VjCW7&plahpMzaacawv!JslA!9!Z5)Y5N(Q|UXg<6NREgRcDlRKzhH`{n!kdbl0C z{e6$l|0`Dj!|-XnP$e@Zxsqyl)9F#YgDUSRq^8x9YFCWpeY2%j7%FSue1>E^9^(kA z>N2SPC8P_E!}+( z>P4+80<0gvv~{ah*V~GjzyY#}&-_FXuH>zW1`MIlkBZM$HSR z;(Se0g0gZD1k*51k#?Fi3^N%Z5Uu@;N0RC&R$NFctQ^Ekld7gBqVC|rPy3d1rc(z8 z$i3fG(Xg8wiLBU5BcrJ$vv}#UiutWkg|Cl-9*U}Mg9k!+%O(D@h2=eOWT`t*&I+I4 z7yY$nL`!(cug>+Fc5PzyrV}$hLZhFylUaRdJdzPB4-*zmpH;AX*uSA2&}sy1|jo&LZNTeNT?rMGeN3)3n`MML%3 zh}?R!_(#9oLfd2S5`kHe@aeznay1u`K-;!_u}>#JCQ^A)I6ItuqUCaAx4|T#D$d+G zA$K$o5!|m){u6{41DM|_(!3ITf5$lkie=#9rt`bh{3IuR8k3c)e*t>TCn&Pb47~Gm zkdWQK{F^*R=`P54U)zo;Yd+D4Gv}b*Bot_ihd?}sHV~Ixs~rUfYsPJRWRBOJM}u3x zoj)=3+52u`GbuOrKXJ0RjeCVFDFXge_zpjcTI!wjW}>@4e^{zDjnTZQ!OE?qk5Aww z=DG3_%1XSd+Y&V<4S6;JaIfHYjuQ8Y3nEAp(q;VvkKvaKD&m)Nv%=xnG`{j?R|?cGlTih*@5P?rPc*=kij|}6tN)afBT2SkydNa zyl|*$!tte)#dmYI5cPqA%yO`vHjXvRoXBFU<20d2(u{>CQMm`~D{Xm3USl?kL@=o7 zCUg)E9WhI^f2-jYX*5fZxL_alOj1 zcn98K0(c*SDP>iEr5 ztzTNDuo&#EZ<3I2L7j9aqyG+IsCrUq)gAF4mK8u2S=v(PvDml|j~|?Hlg(|W+7R=z zxV}rOV7Mam)66=FRwXPH)lNi$Z@O!}7T0Uix4)8OZ{I=F5=oKhFt4%A;1s!CYGU?% z%(hlbW~GB`sesYe4Ac3eU+gg4uwd3$`#j{*#Ea21p$!{JSvD_|W97IFz#Qg1)(Obi`c7I7-i z!8imY(-XvrfFX=J^xsqe1Lp6$#My98{sXHq$?% znx$zHsRQaMiLjYRy1Iv8a@#*(gVW&P8~qRpSFbAZ3zSJVU1ElFzUGQGs=SRsc`)OR zlB^LleLN4;7;>X?8KH>ZP5EJ-bc4;1oh*?~CLhfK=z&h>lHVTu$# zx6$4XSESjhL{E`c{jNkM^=?NwP$qN@-q~4_0i|X4z39&*t3w#oaMLI!8nR}RF1;o= zPwn{sK^?8|X(gDRAM3IUVu^r?qMY9)w9QMAIDHS7OW7D`S^jQ4OpmD-l_N!w8kNws z_nf*Q3X|1>+;fj|Ai60ut8Y3;+{d!FaVG~Jwp{~%BR`(e!Qh2g!g|BP zV6j$&igoumSw6@GrK>-O)oKn()>&ROBs)L`6A_z?l@=HyGYI`j%S3t(KLbiipJZis zc^t|If#{(3ZPF_)%|yl)?fIBK>O`+ThTtz3(B#2hbtC4j^;yX$;riu@#T{R)*&ipa^iN7xhXUfy!Wn0#1?9`@IRutysU`{1=DXCVBmR zg(3>pCAMIga%chhtj$!`B~pcoQS((>#L2j$VaIsPuoA*e=q)6gV*>;zr8S1DKXVH3 zP>u}io&$3ONp>HWS|i0X>`IktmG^gAfFrGf879LcM_7<%!VSHLN}i@V3~8B zln+?J?&EP20(=u3v9j4KvE7vjcHktY^Lb3b)v!p;##WSb{k>L&SWI!k)?3~}$l7T@ ztkglTqtbOX|EjG-?cp`X)Hfaux0DQ%NIwKK&6ov=`Y1!6oT0|EU=K7x zoD+KBypg5Co-x6S7XyD&!a>3QNAn$lBeD=xMAQuiHM)1RKxt11xbl6m0Nz)Xo*-Vd zmn52FDQnN!wu^2DcBU8Njh&ZjE7`nlR_5b92IvGZw+C1|J>YYuBM7EOZ3FAYD!7_r z#uzELYBl|By7$06)w2SN`B(?i8)5|D{b={f#bEaF*ZoWaBR?Oyt4;sf59}sn9*zIr za&K(BLASn43RH>Y{9r!3EX|$)&uPj0mvEYV4FU{?+T){m|Jh8hf{h<*PgtP4FX~OB z)^Gs^1|5LR(lr4Q84YiZzGKUS1R%n;pgt8uPECP|K3ak0BGz<{-BT*%SuR@~EoTn+i21PK|>p}L#SdickNGrgw z^;opsFALJLP~aG3H$I;(a(SL_ATzl}m=WM*m3P01&JTxkM5o0FU86aig5S-Hro8Y~ zrRPBtj6F2f^89?siF+U73l{k^0;?B!SvySCsq<~Ec$J8?wc;tu?_hufIruB(&^TO1 z55GFoR^UflNdR+j77K1khKSBoiKY99<^iL58wzg$Q?0*>-qBcPpiBhJOZrrEgL~iJ z{QS;5E_y{XZH|nnq|(H0;LX?0Y8{$GpeA)5i>K^>n=|h8{6c+^RSxStZ!hj z8yO7S5--0rF?5fGE|>0(PGyIJDD|)(dF#Omzeq#iGDz~sG$5k#=%XNXqeIYB4jojl zP@1=k_0NK)oTZp~h-S<&YIIOvo-c_}hYN-iawoQ48f`l9tJFeFVl)@hm&>bvQuZtJ z1Hr^%v6gP3mk_}XEeY!&mZ*VtI~z#%S2nLAA1Zt3mKZbRxVAHILZ|!>NW~;_KBd_a z^~IhY$q4nmuF!HYs82RDrc&>v!Ri`xaIsJWrjagOoi}4;mgGwsf^+u=+8qtl$KZYm z$}uTZ?Gnjw>^5i{8o0~4Nb26b8TRCz9_lW_YisStBhK;6lQ2L&H`28C%Fssb-_E$HFh!yIMa6s$O|wHQf9)0v^GzvUQS z--CRp7NXk0czl0O6^Yd~c95usShXRSMtOY&jC?+VKMi}Ub4Q1jaC-8bhI&vEe+abj zX6eOxDOjl2`~Ec%Pz4zb*dvb-zA!p>T?(chdxk9Y#GobgGJ=K>fPeCEMcHE3{(s#J zH69s>%-4Esre5T2YxC7L;x;P>Am86xy)=FC4bq%1v&;MPz262-y0lP#li*c}{^&%~ z|CV18r}Zoj^V^#y{RIgeKXK{CqlSxPU8I+1SkgR{sQin9%GGL+A^Ovf`JRAG6i zeageC0o7Y05C0BaC$YuPMmic!M^-PyTc(*BSndP!Uu@{QW;vX%uYWH8RAiQh5+fBayZcAX z#AJ$RrY|f&${6)MXY(Rt{n9yhtIbP8-YBE|?Hx~xvSw%+=hk#xXwSsVWyb`>t#xOT zI$b_W!8Yzli<89Fg0;u`Cnvk`8Cgw|@{yY%Ji5*?sf*ewfhs{9ByRIdk@_`d*SlUN zz;=IH@SOS6RK*aVkgca->D2Xl7&mV73;wUZpVE_mqQ00UNSX3$#Emk;N!(+!7t2d& zu8=BuDyU^x&9^_T>om*pNKnmQZn^WeE(+g%9jpwDKpUW^Hqmie>0UQU730VX((lGW zY-65fpD93GCsFiA5U~gT?RZt}Ksqe0-j2iBloLXX$NxxS{c2hL>{ z$~=FKn9B2`php<~E;iPvE0mGP`D^nR+(J*furD?&T{n&CHY>nBtzxRrDM3<;C_E&C zWd7t@f?RVXVW_+$HcHjzCf(B%cop2^7_U+zU@=`z$}TZ|Z+x#;0-Y{>FU}CG!#k@q zgWobrY#nZBmnJ#+NbUui;A8Y}0@uFD9QQL4NoqPM3F_yVU%Ov={0uw#d!4*W8CD8L z&iZ$>)Z&X=e6y)@*U&a{s3 z(AwGlkekuUWw)(TaQ!}KS{ftwo_eFBIT8COYRG84yr(8$@0I-HVe+1V$I6j0MjV^b zN8=n1)T>*9f-k~aBZB3PyXO(|oUD^P8Tcd*43u4YeHb;I_qv|mb*#qo55}GC!na#; z7E8j;Ti<`&Ea=R1*l&`3%akjZFYJK}K1EN+vCkqo7ZZLS+ZXgvsJvbpfav&itoFO$ z@$D|rjbK{ksqqr7mT&qcY+?jZ)iK1G*oo8r#lDtxSX&DIlpb6&cs7=yh_&9?i%WhN zgTD0p!;WpRepjAl#OgErU2#R0lIh#|G}=CsYsnQee<3K+Ve_Jk;S`LwNnS}&=tE`K zSCY$PDmkifP#-VcycF`}01L0=TRay&4GUZ>@#uV9{8w!P;3l5~ol;G-C{%)NmCUom zA*Yoy3onI)gdES7I;~MN!T9?Ace4oZ46qfKVqYy*u#G*?Gu*+tykCL!hguD9O7#PF z_v#C)m(Ppn*v7~`3F$PgnV!Dlvz8Z&r3}$M(&?23Q=B8F1x*~nqs;=&k;%neR=43W zxXeLL$JvOkHajW$^qsoZcqZufFUEn}BCq4ZUsy55}KzW;``~QIW zh)*>ZZ{@1Bu2E~nU~MS-_t%%nNJE7Sg(MCl7FGS@DQEeP#SQ|Mmp$e3P(AS<*&DVJ zg`wCU5B)rw&71y_ve_<*7Ti-%_@418(3X+*^lJ9pi;P;V2^by{>$d59YVF}Ay^TJyeExqxezl}R?_l_r^{K2y*CtP4_YZx}w*G(RcEU{M z&d!IXNj;0;dGofHF!3M1!kvfuzdqjiEvy-lvwmu@$e|&_plAA7EnKL&?N|F!PtLoY zvv_7`6MA{@^Q*#wufG9N)QkVI=(Q#&s@wop3P#&uS^1xrM&aV(qr=&wte& zaI%OoS(@F}t_$cnMiG24_|9YvJ^QHhB-O&SwS%6F{U3mEy_RJzK>bv~vmv^NKxub0 zr7s}r$@IXO>%vMyimoRaFyLgY18*S*7KDhgQg@k5lP+6X#zRI_OXePC^OQ z$ojIoZf@prq!Q86$kc(ZsI5sN$Y#Hi?so3@_JlepqPM^DY@%=cTD5LlSJH)QFdI#K zKy!}51NZ^43%tv$e}_I+OPuek$huaoxpO3A(@SRHebQCTU1uu}qSYJ&iBc#n9eNXd zf}&;WgG!8(MPbV}GZ#+W`>2{D`!5+nmyxFBP{4;mdM@y|` zwhzRz-gcd@snY9^c_|gyq;0|z`;E19IXrEnnVUY-+)eU-y?~MOw6tIji_>mm* z&4ISQ7*s3ekNNzgU)ZA2QuRP0dZs6ES^EJi%#rvmlo15TqUWNVV39AOACh&wSwPFEBl6VKr~! zU@h5e8m`f0w5$2Pl+n%+q4333-x6;44)gp!HAw*nvQy=Rq2U0}20;$7bE9p|XdlYiwC@?Yd?f0FD( z2Yo!XX9(;Gfor$tuL#bad*W{J!wx;_{rxF!UoF zrsn-V=49V`r$(F1A03hssx`f6yWM$UaqE3&gRf?;M>^X0}Y<~3L*|M+@| zjv>4f#Aaew>yp`cxz3=+-?F9M=EuMXDV5mg5zy^LSO?(Rzr;GM1I~+Q+Tq%dy=O(ciGnuzuC30r}Rle@Y_W={;%c zRtTNxnfY|}<|X&KCSnb~Ab;k+_1(S$ZpYl>muRdy`Npi^(>MS2{oDTqFYiW#%|Zg=+=veKwZZA*hsIJ z(~0Tj=l@>Bv^U2D+e*6~bNbBz%`5MSfxU3J>}_pm)(h|uY1m)A8IvFG8xl(TE7rlC z%Ga8{zOR3<^j@Gob1cV%pt4B!z@At}4DBWxo&TE1ybxDG!_4`J?Bw zvnH$8;_`<%ZQT-j&9h0!?CC&-90fII-Xbce#QNxwF--`*TR(l3BYe74MtwAN2jiIJ zk!ZyQyK07iz`YYgePLVL!de0*+cJS15iu ztk!j~EWUs$U`$<{=Pl>mY{M8y2E}YH;Saoz85JrMMvxU~TX-iz6CfI?3k$Tr4UHKu z^*!o35Uef>O4z{kF748cqaVEYS9_UF-KlP!!hL|Kc9zUseo}aTY!EmQ*69luu<|;G z%e7W=5*=Qob|@j<;iv8YAb*y1J-BXb#~oT8sW5Wq_2YULU*^14K9}`^ka*u(Y3|rA zXs@h8bCVau{cCj+-BLQ-4D3=-g{4u zG1h|=pyONPiJs^jZ1Zlz;ges0`_gRnMGl;Uxa3jh$BiknnaGIjS*+v=)@BB&SGDe( z2(VIi(hFwusw!Hnj~2F1vF7BzZzY@C?yl3p)_;hUz~sgsWn>rlN`gAkQSdg>&*K)! zUFZ2;(QijBJsNkOa;zp^KiKo^j5^CSGDS&tX*9g)<)iVdZ_|HVtvpbQZV z86mzTOk!(k!_^eXteucep3mxzS{EYAetl{SvI_lB>7dXl{DmGb(oH+SOdM(2GXk69 zMok9Wjrw}Y(Utk2h@#EjovghX{&IBBdbhjN zy1nYxls7l`KgEI9cj1+rzQX4bpNYCeiTf}+9xh2<=eBdtW38cI2njB5`1 zhC4aKuBh(?sBt{WL)fstlkqY1V24@vnS8yydsxj_&dblk)q*>h)JnsBDzsQuioBJV zAHF29@0Rf-MknzX_zOcznARV7WXdT)TQcKvS{UZ?!J7cMW zJi{F~!~;a=;lp6)>_}p_VkOE%oGxuP(Yg(;7RS>5Swe^^bpLeQSaALL zA$4Vq64b_~{AzmIT~?Glc?ZM875Uve?NuXE_Jwv{Zw~HtZEI8#ANn64{qouNi(;*< z1D%oiWgoO~=ot~XP;DsF1Jh)(ZwY6!#J`FwpA1E0pU*zu@K3ap7A-PnKO=L+B{#*f zMzs3u>@h!^BpgF45Vt;5%E{AuKor=7vdk4ygx9j=?{Pc%E;$CBD|IZ@=k4EZ)yuFS>) zGgQ0Jp_XyK_eWoK(|`w~EOsmZvbVPp{Pr$o6MCEY?>T?* zesr(j@VO6njMp@OR%J;KFIBW1Nk+(HE9qall$8v#Rl9aK`2)LxsZXGkCOn*w#CvD# zdN2CQ;-m3la4&F9rOXlt2Zz&NZAF?GqaZ3R}JiGW6KgW2-)}Cz}`h!+hFrM)#DA zekvZMbgPm)hJlA;h6AHfRaCt^e1% ztA$%Gj!Dai;_tQDs&uPAuA0}Fq!t{*Kfi8Sjg|lY@WqFJFB7g+ChS+rF^RY~t*euC zgVS-iRjP1eV1oQodW6NwefD+dz>%G_$;WUhWTw9tmDT0e$_3;wF&L%2=1o1Q zfr&QIHY}C>#_>nM`^#iu>ApU-(OE)mfnJlI!_ z$>hoe;w6Oq#iBNz_(z&A28L?10mXRsu?oevI$7HQ6k5E?a-kbnWEwIuQZ<2>Q={oD zLj=7FU{5XgE#{DFmMQbTpMh!bu1h*^_L?hm?7k>`N66zoJl_Y^^t2T&I5d1Opn{iC zioSpZInTyok{)5Us_VfFEl#h3|FWOJD?+G=;y;t@=Y5_$k=|dKIcOwBu5Ow7k|{ z9Aq&ir`lqg_`?(>o@#_DXB6TOA)jK+;uoloMO>&Xk>^Gc&+cXL`E&7ek7yy z`}np$`HKeVGu-$FsGDxm9@P*VY<+J{8|-KFm7QGGNRw9E-)fDNip^=cc>}Mkp9EK@ zsexa(s2FX_FLmn*hx8KA-5XcN7sbx)rwh2=FM><*85cs(Q&} zCw@@mg$IHa)fJAN_KA}}U7*E5b+pYDdgh$wWI|Kxm#rFHIheqE<%fIZ-DP#G<(Z)- zfurj8>k)$Z2vN+R*!V0hG!zGNrps*zyWr+59&CmU(n~Rtdn1g*^;^!m9pdyJ6Uz(r z#-!mQxU%daoo|uuWO8Wn)a8z+=~c>O!Zq-b-itnVv=kZZEgI9n%>nZ(~LCS_F0g(h%_H=oGZt*g%ue&f0$R?;^p}}TRuTr+6@Wp zOp-eXwm;J?Ed79M7v&oMyrkR;XT9j3Nl7)_E8&x#R#FMAn(9w^Bh4l(KS83IJVxit z#n0x$<|=p%^>UGF5rFY3?f!}+?U2dN5e_4-0A*Q|I96uu`+zO>BtM05Y>`c3$`9r5 z)~~(Q5j@K1{`UqfNtC>$j)-#Zo@4xgVM!b$2-5`!Q(`bsFCVJxnYOkmt2%@CwuAH( z?=m#h1z| zh40@UWhvOQYOqOKxNotSD=GC``jj7I31&9_7gqHQL;j_}$+mU^B@-OxZdrdD5MkI|U~)$Vv|xM3GtB65vK zb5=ILBk1n2lY;pXhmG2Vh>)VDtwig#xu`g80Q5OZv)O!%MhTK#h&#G)q2rgq%1TsR zx*a?)O)yJg6MiZ^Caw6w+XU_Z1CA!>VHOJr(H)U+6%tF!>eudRJpi`&gJqlqQAzBn zL~sd=jz{v=YV;bOkOxB0rB@6OZ52R~>k2cgrPe{pYgxzm$m&_n)Ysx+Du5e?a+uOd zSWff5KGbd4Tj1!)Ia%6DHwMRld-Sz`>eU6s`&e}UjE(LuOBfy9YG3rn#cvt3$#|=+ zhRnm#WMrKWsmIeV&38VJGYl3(cYb#h3R z;5p`ZM$a&--Sn9jSXboglfF2MYx}KsU1emem%Gb1+A#0664ZP7xXu|{QPgDk>>zSl z;)G9tMi`H#C~|m3G@vu%YIkC^Xl#Rv$qwWYUe#NxM&hKDN#)KWVp74~L9!;13KFcn zjd_hirDSLvru&O&5J0%YUSEdA+SaLMQtt80u*9u>dmO_glz(jdaeK|gC( z7ULCHmW&$6IXl25fqvfpzRc)C+CEGBGguHyNF`pBp6cfHoAF2BMUJ(ohr$T8>GJuHg{Oy6Lf z;uL3vE$I046@Qh;)(F@j&K$p|s^f%|4F#ut52b6bfvs+zq3hc>sffI>uMwEECu}6}~hF+r#l( z)~XrKpO@o6O`{y{>aD@da)DWa$a&*By1`90x&Tx-lYsy?h;lQ(0t=hibg}I8?K(Tj zZtW$SHQGcFe$I`;JftM3GsEe2`=Qz|x{c#uMSz9sd(Z@O6(M09iz(1zX3w+I63jaOw%Dbq6x)VUPR3J#+78%|~Wt zXUrUF@t5|9FD9Xp(VnqmU(?yDS25SQ=ei<+8+0VFT^DO z97(O7wg-W)I{LX!ENxeMeTN@cd%Z*ds&7%BEY~o*4DC-CoH>iEL7o9aC}aTQo^_~P zjwpdN5LW1}IcKl@dk?lz+k8bK^I$;1`xGQy_nR+30CnA<8Dn}(7o(1x9-+9ZNl0N0 zqa23Lz;;o=)!xi%A;w_?)5PI}klJ2dgT%i|Dz>%qr5uwS3g!hx+UB^EKMDo`$oOJG z7o^&s4`u;K2AG9&Wf_Y_!%#&!1dvZCf_KBWK1xFB z0tIR^w*#GX3-yBYUI0e`gBI?7PBdzxKoU`c_N!rpAy6f%dEoCXM3 zxWhDx3t@xNU!>tw<2BsLo<=Q5l&kb!7wwy*bh5+`GJn++6bxLGQKJ!9A z`cXr|!lubr2j|hPW(`8%yDr3ZlJ`zwVx*5L{{tfA&ulp3*|UQcykDAoXaZGTZaPPT zatP3C{Ep<<#-MF>5AU92<@|_;{XSFzkoq_K7CIONCQta(N)m`SLyPk{;`h%Kri^DNazE!$6T=L0GSHwIKcbqmm;7+}DJ1k-%04!#0(VoHurm zq-eG&`;(?&8-1$p^;0mMGiMbOXrW4}b*hikEc7hT;&-?9D!_R|`|aAV%f=|BnW%yz zfqqb#lV!&!p_c)EVTvZC;m6uHQE0r>7e3b5izF;bZx_t||3dyKb=?Yy-gL@>PC1VH zY{>w(T7$?WI;ieib=nRJ!YI#dY&jcm5|Fptrh=Qyz?6oQr2Z;nU{^Lw+$%%~=Wbaa ziNqkm^l`xO8eBe@HN@TYX4J+@NwB2AK$6NLa2KcFZSo@X=ctrX z@haRj3bZ}YKu26jU(PpeqCS;#Z4QlxOisqk`9NDtMwe&?n0XVYU^-}&umq2bQvcL^ z5M&veFU4ef(T!EfVQ0jjdRe+Rjph$caf2CUVy$XIlMvJy4C3Xkn^<8tgq*3qyw45p zlU^j&xXmrh98uREuEecN?;Eb4(c^h1Z9dS6dAL2rZZV>? z6&M>F=>;EEJL3=mIQismTeppYhWXV(HfC$w05&xoZ;arf#6PGkt6$ce-V}*2TA195 z{QrQRrwp0kAqfDs=~7Ut<^_#M5A~DcT{f3C93V7AF#Y?7v|x@JS=Ib|?jUsrw043@ zLx#QoB`@VOQs~;v7)=deorhpt*&{y+iX|$vbelog0%6kun!aVYnA%7w7IPLtO+lC} zw=Q_wsO6N}3cVhd|ATTEBOBabQk7p!Q53&EoWR@gbCL3OIM=hNZ5L1>6OKjy)(0BlG4d#zPS=@3tx;-x~W*6Mjsd0t# zfc3S)t;z-W{S?x`(vA}F;~^XaMGz8u0<<1q1r#1u1#iT<6j8ceO5G7LWLXEU&t#VK zdS!Rq2a1HQrTSorpJP>$lP=8D$=Cs+e7!Y7R3B`ozF`mN-k_*YS0nfvmHi{gQh=!N zL$iI?BXfEVDrd(XDNNyCFRU5wrHomY8;%>A zV6uQ?`=~T>gZJX-gewgJdh0ZC8Xe~DvXGsKf(k?w$RIXmtXZ1Wmrl>+%MvZj@;Yey zvxJgM{rLs7w9yCLC! z1$Ze#wf5N_Q{Kp8;a?MB>A8&|H*%9W6$rxHBQnk5C6Ww3Ab>Zz2$D@^T_|2GBX4P} zu~QaM5IRi;k?6C|_-G0F z@m(cc?ga-#nq*`o3{n|(T2L*uMVCphO()qqG(JGD;Y?~m{s*o}3QmcX=1yH}jYG)X zh{UX!f|bYExmt%s9K&wk1b~F9%1^r5JnH=jkZAtYGpllhCQD=VrR`Jr)MOeu!?*%m z~gM84MG$?k<-r*%*QKyL)7`tSM9n}W+W+B(DKEnJa$Sgqi8{*;43 z!hknLHnH29~FOfig6zvNx9MW!qU^vrwu6#u!!gu0JFECWQ+^mB`4xoQo-Fg zZLjt=Fa6pw1lgeo>Lr24s3s#Epw!NgQ8wn<0(Cg^;IWbl z(@?SYRY3a?vB#7E{@!F#uU>lItgwWdT4RDYYF{g6-JRS|2jP`gvL?YbIfy0jIPa#}5btzdJSnv)PCiNoAY6+Kh^dd!I*=SKRPSf(yoEukeghozSr3JU zH!u#kBLe&$v56~9mjBkeHn)>Tf#8z;7|*;aW)tWGH6p8v+%TvTU^ulBy0-cWk`#em zp^yBjj!>A-=x5=y&$8-h^7a9mkY>sGv&{9$SWlaCqP$9YE1AIX!?RCeVI`mk-qbng z)ET0l)DIGV_d^qKBj%+L*as z5(Yv6$PRc|=W&-OV?A~es&)@I$<7t})#8GRX>C223LfC)x9;9HiA%@JZ`F)i7!yE) zRX$Q{9Bq;*FoO3)haf^)43DiU^ORM4#C{$YDk>H@8{nlwbg7Z4S4gWCM~4Z<1pu^3 z=f7hAv|Vc#$9>36!rST9$+Ezc7^qnljLdF2=cEBVfZC&6I9wvhyiPeDXA{2UWeDaF zdi6qyx@@|FZJ*%C9$is3%c@EBN*JJ~xL)03>x?A5!;iSoB#82d-U5=)GzE24{&03` z%lml*kDl4}s`PkJ@O{fbn@mCXp(hJNy}(n;3e{|pl0vb5lZJT70zM}fp@o^DVl-^bLeF+E;}TB?VYp$uyp5>Q)EuR}gGMTvqLvTg{$Hae#R3Hrlxi+7$pN3qgmHTs0Qc zV!@8C*+FevPKnF72LTernvFSjIMB9g4BGz|(1)w1R&#WAB1_~A4V~G-e5Tx1k_9=A zrKtm=kqFGqu>4&ncpk=69KM*(4N_!P4a1ap!{prkb zUlEvlKk-li_9yX1ij37@pTO`X`u8zoXUncG{LU#`!icJkb4C&$&O?gUz(w;bW@>Y} z>3`ulPUSeg_&Pds=k&6|g>RUiDZz|jI0Hc)kOyVGz(Z&Q7bE-xV_A=yBnmhCt=q2S zwCO;rlnH5=LgK)RN&QDDFk+BvIp}TCPWl&qUPV2Wc861Sz}xDPg>zcH(avJ&>fVnQ z_v$ic5?ZcdQ~nN|KM|B~c7{jj5&u$FqpM z;qg1LchYMweL@u@mX9_l<~;am(8KHB9GuE-X=8sWI!1J7#=YMaTM^MPG`69=-oUj- zQh2z(%R9zt7~}izdREiG=D*t_PG&8rJQd|(!ZnrWIU5k4r_@&Do?Yzk3dE?IjK ze|vY`=og$HKw@sW*bq98G+k=lBTHxcZaQInC~^f;{y6CT&VjYPW&u79goxpCH9L6u z80Se((QQ$h?YZ=ihkiCE^vl5TSpAK!*V3tfrwFdChtU-R5=Ic0?)tSomx6>faqNtc z$uAWqTnYMyPWPCd2mc48C%4U+^ZV&Z6*jd^Q;GfoDo|FCF(0Jh44x6CBkp*9Klu9$ zEzX8dXqENRy6&Kh;gXjwQ7R?fjZckv4LQ;aP^{ct)>{wa@n`gDT*4E08=p!aNS`7q zy9N_z#Hbyn3#q{yEnw>`Gr5FWf$g5KJ$r|hwm(ix-~EgOp=%0W4=QYynH2cyXY}tZ)Xgy(^4dS@;V$phv(Kn1D|jL+5F*` zx%X(thhOch1?P6s;0%4|OXe$4RYQQD#X!^iA))dM>q}N_%XFH*K{~y;a(zx(g7Uk* zRqsztI3i~5X{pCU*#Cg%Ix3wy#ImDLEyi+|$1RjU`8VlbJ=c_z?^&&|@P8bgi$9b9 z|He1Na>!XGV`|E&gF|U^8Y-vce5&L$rGwLu^I0g(=8#f3#!Tec0a4DIQwT-Q3^Pm) zb3S~2_xI-y*yFMLw)gvWxUT1=6plIBdoL0N>EzGw)NNw5FYuE%u`ApKY}a9@l}}75 zZ~N^C5?ct0Cqy%_v(ksZ8k=ZjRGX(sEPU!hTRRo}{TO_{3P0U^<@nivhAG&e6)|bw2e&;1`29_u))Mj`vGa1z22G@_T}#vd!Oac2&-G3L9cxc?UbdDlv+B zaW0lCIRH_&&dWDRGEBWHgTJjKzP6mN)c`oHNuc{eXECak&@&AQqcFy{jwtNKKOvt{ z{Xa|8YI5#Y37>^q`sv|mn7exkA7J^ez`UM&&q0a6Zc1gLa=9(9(my6w!JS{RAd-i~ z&GO#}=z-xX^!X3&ha(Z?AyuY-%4FiL_frj8WT$}mFXMw2!8^@oGVq+uv+KrN$l-w$ z&4svkMlu!}=+jr63o4pqj z@OA>`HOQIpTj%|y2=`7EfQ=snLP=_s+*?kapW%@^Gi;yyT~v1jH-xM#{#Hix%dOZC zIE~u1cy^A8=XKAnWsHv0eYmaovbpdZ;Y;m_#Y%&X(@DUPy%)K0baLQE3gFGY#;t;y z{>Fz%cfD-}zbPG=QA`lacUx6m)UeZaKUS5{mD2Z(w@NnBFPmH~s(RE$m0d_f>Dft_2Pzy_rsf&0tiv7$NuSvl-H92oP8#h zk>x;==GTr4_O=&4BBq^#99ve4ybLl%p`AU-qYoMxCiqWAvtR#QhciKHP;#MyY-O>Q zaC3LVU!l&nh+EaEDuC|IZqW7myOt9Hy&J(_Yv42pZ03i_FR}Y6xaxmX9>i;YJg>))qO0`xQP8ATXFmSC@(T(3O#^p!4A;i(&%q5SqBw8LRuaAcr{+g`GY zhBLP4$fo)uufyS+uCuDy-Ks~TIgcM$K+xD32hX5=-fPYKodd>No%+ScqsQ=f(hlm^r-?)48+g!nmb)q5w z8*~qdBw4)^`sZCotmij-hiZH9xD#=!x})iiUk;UYZ^GE^(@W5`XLY;(ug|jlD-aPM zBq@3XeVDvyUIwgkdil)C+|HY#R9}t(@X-{Ex>>$p)$AnOq@k60zoYhOL1trz z`zY*(3ja=x*r!OYFyi|d<-0*<&zh@Od(~@qX&OdWsXG7gcEe7e{!H#%b72ra*HC}p zoDiSS&xz48@j%;CvP}HDsX8^7jH{X>PS^aYO<4Vv%`>BJHexlqg9(YGXJ$Z#PXUDt z5Kl33`?6C)1JCK*uVop4_fMK2ozIAetd?6H767z)jaD!HA%_;i2@m^G)8uWI!vg+1XZC?L1iH08+b87N|E@Bk6 zi);@1l+1ef{D}SavRg6ee*dCf8HazUWp+34QMls5sWmB0VzzXWlRq8^kh`JCL;~?Q z#s7gaKg94lt0I1+jTY~oPo=zZ1A3pY1nTGuBF&) zpduR7u$qeNu1xOs@v%N^0p#JjgEmHL`uU12Vfp`a(hZ6BF}9iwg`Oygd}TYF0UU;0 zQXipCR}=d=t&H2+blJd3-+iGKyTN<5*>C+ezFu>erjfmjSg?;@ZV5h>_LfuL-73AK zb}#$#u-iV>8_^8y48>laG|QW_)j}BS*mqq}DpG+~OJ4U6DNuc{dnwkXr-`CU3AL4a zsafYAC~k*9L56bM9vfX8J*W$oBuMxIDX7j7q6?+O3wK^ejQoj5k4Wck)S+NU@wKB& zy_xxkXNcRQ?IV2PMg}$H#+>%!PqUOp2!5lQkp0_BLRYl=itu&3A4MsMMi?$M3Do$0 zVRAXduUa~vw+ME;ZVzlZHgm^i&iBqv=xWeR$_n%SK>A>e!I&*=Y4g2Ap6Uf{n-mBg zxT{tB@4)zm)V3$@)p1;bdrCuM`#!*}{>k5C$WpmCM$tw8j zIN%6M{MEPpeSY41gVn^&or7YM*zP2^Pd?D8NTagTUIEDqMp*Cj%P*v+Y$RT>Zv&TQ zVv@_o*^TAjEt#L6)t8$VYbgd^`+CQnro|16QoEpjgHbv;o$Xlchiicg_0@*gdyJ;wnTZSBnC z9aXGv_b3+s>LAW*^v(?>#q~IkCz_sn0KkTK{2BFrpX414GtfS3>i4@lwalv&bB{C) zzwHF_pW?grW1}_q5z-odv7`8ChGkn2$;65SHWi@h5A;!Q@23~qIdgJN*F}#?mi(yx zeY|FU+W9Xy2c}rFbx>2LfP`0f9B)MY@Zxdygmskaze0JP5XA(?gyIe=Z-et^LTP76 z>C|z<`y<0tvz3`o^UBOo@K|`lIA9dpY|E(sCCVFouB{pi4pzpKDFvLsRc-zhRX=w6!%; zICHKMOxTsG$>j}|P~`ZApX~Z7t=prV%7?pqwl>f^+z&cTI{%bnhnHVKf9zn@zV=Ar zI@4T|61(o6NA=Pzy3IhHkE?Nd?bUash#D3kshxfvoOaG~q%x_BbVq^;Et>yaxG0u$ zMLLfWyTo9c)*cU+W>XOq^Cf<}gBNDeN%nY|pcmeq8Pf3COdr*q`2ybc)YAv#F`|QC ze~N490j0&+=_RdJ6DY^+M*Kb>)V;9_)a^ylM=ziM_y?zVZ-IR7uQ)B2O71UfF_6T~ z8~Ii_tR}t-g1Z5;o-cg{B%>4A7czGv)mpMu_>p_ICX~T0nP0*xM)CG*c;~5DMlZ=@ zVuv89|LdH~R|?qv;8SL$bk5u@-&eNr6DT*8b}eN>q*PGJtF2-$2*;TlN$-MW`!1l^ z-bg036Crats)(Dz&`eqli!_ku=R@?hU-l^b)r34?kvdMx{Hl~>y&6b=?$=qYOrK*N zEXo_-cyjqqV;OyLHiQteG4jprYy8; z8rg0e2pGsY^*evz$Y?g|_LG?T%Ra|CG^GrN$U~Q3U?r&|Ja?jwZpXRw6<0sm!vc-3 zRrf!UxLbtKaE(y^Twa4D&pA0I>(qR2gsBGqoFPbv5Q4~{K>*lmK#6M9(mJyjf?}|= zpx>=W`mc0t?^+CKcZb)7TDN{Ufvq*vd``WGs>W!jV&pripJZ-PO*+!F}}aap+C+q(pzl;~Zigc2%y3`>n6Q@$S*Y zh)3;Q7bni?jV7{qvT7u24r)pS7CkR5lEh!Ifv2$Uvb%&(Yul}yhr9P7Ly$rLlD>|I zE~jelb#}7pqhNoBptZEsVjch6AAU)H{_<+V+{?rzOHV9d0xa$fe0NrvWM0^Cw6I8H@ZB6Ez0^!+g&DC;n)i1-K^j9uhrhJNn7|XH5VF~VVNUEukiBz ze?5>YoO*|Pq8ipxG&rKO=uZ5P^gvHL(^lbu+LE_%-INKK{rq)ohq&$4K6+tziS!N0 z>VHnso=6DrDWv-rdFL?l%DKB-W6+R1UW1Tt_+@8Z7G~P&`iIt~ryKzvWT9TmKB(=& z=7rL^w&YpP``TFmkO{QFTG|%NaesZr!3(jRqq|wQGP8m@%_YG>lVMRb>~co#T-#Q_ zK2c$DYwgD}Zx3zUz13>n+Rvs^GYhOuOM{o=u>bY#(X5g@2UXG2P1>F4{|V@|e^b?Z zwXeyv#r(A*DEX*|V-%QAim>+Y1r%UMt{|5UzOijYXRQHmr`yamSsVm9rxl7LGVEJ9 zJ9@i)O($}F>q0Uk0}>t-o|6fS$wj(Hr}QX6S*U`Vizo5CB?5lgEnhLOzhJuliu=Xe z%{tEtM-Q;`cZo_Xzr=Kh#O)^f*85X%MjdI~A>gKV$U$OArI$V1&&H8}Dq0Mtxd7^? zVidOyI>jrAB;O)7|vK`l8VXGAozMRo&S3|#$2_w1@2nL!7ArC*|_ zaWzi?UeX%j@G&Lq8m%YT+Q;H|`ZtA4=LpA)wg4cf&2J_`m~uI$KVz_3j_Re(Nm1M9 zroTiAeo3%V2$+kM+7GqUEs`ETb?PhUkyQR3;dk%1W#_!$b5}wl(*NC<(tLJc;QlDi zLXAU^Ce6P>h;V%K)A#n0%RCM*XNP<+{+T7tOk6&1xQ;w^bhCg>nSd(0cn8$kPCXTM zGpP}%XI#CkDy^?Ooe$s2#K*?=Xrap98Fq?)6=_#I8glS~(jER}fbn5-lo`@Sj2~e< zsLg-GcKtpD6W4)}AK?sF21Z&%04df?Kb*9B^I(79H*${r&uWnv?d0v?a(8XfuPsb= z^=5s;SzYSulh+ZyGSi%%)Q)wJ2g=E=Ejdb^dPKaB;6CLXf@8E9r0jC15Y%xNDWkh~ za)R_&7S*iJDjJeo|<^$l9TS@h|a9!Or(6lha;2 zDHN@SUeS9di2;XwWBg(Md)AOH#AzREYy;gYL6+yR2e%k{axC`Q&WovnwO22zu0I_- z4_-F~P1Nic3{gT#@u{&`-}mCoE+A=rg(~%XPgJ7H-MtLALl@m}qL{JQ3wF%>a2XJx{22+qOBTfysuqA?OUEb;M4VGUM`{%HCyV7D{ z0dT*g5W9J=^r8-qpM`nYQ-sBzPm|lZ#v7`&3#PaaPplFXnMdb$B%kc`oh^60rvCIs zlTkvaOr!XyN|^y%30YAVT%ziD_tKf>(`?!vfGPzfsc`1)r7#E{%SahrvRBn?_woIx zzMnnux2S&^FBpIBYHA1_wr4GJh5C(M8~JPQtrGiMp5i8Tz5JP`?)$PVr4dkCs3B@r zu*u2i@yf!ND^GW?6PRzB_G^~fnf>+9nfU1Y)u$IFUr1aN59Yq=oLN3VBwd2`Y*|(% z7%0pI51Yp>_$pIbZI3zPO-6g;39i7h%zy6)%K8{cnCZ9lApsNuq<4>UcBVV*atY75 zY=@#Lg#$7i7~Y52PK8y{lA!yLTW=?Gs(Lr>00i4bb?h9&F(UN_N2hu&FG?SpGJxMI zFRu@ru3kHvB$FI> zzIctpg>3ZCIa0044v7V*6iKgn0>XJJOGe-YPHg ze>2pb_-QV79QdF+c95wX{L7Ok$L(9AP8o@(Mdi=AHe@|CCf7`z z7#ur%W0cTpTO}O*xafVvshmAKM*3ckYA2GfA+*0ixxwB0b!$=VbEzHm^8M>Xghg9K zmXpex9K;0E!9M5N1cu9?3%SH9%qqbH%@t{)7)7r(E;j1b3Jq7xsPa-K{GEBr$!P}7 zB^Pl-WLn}9ff!eo>_bhEio6!Nu@C_Zol;JgfiJcIBYN8KMA00yWlIJ&jjRJzMsouC< zZuQJVoId9DBjBn9U5@o z1OCYIB^WIJKZM!S5@Gxl4Mi1oH5U+S6wr{u*{mgN`B5~?Awe#^eUVABkuA9lLw?;| z%Ru^S8wjHr60m2bH2S}u(>49wKsBtOy$MQm0=CRsl>~3 z1UiRA_>)5pyCKm)te!cW%4|ks<8(ZKq%n61NWinjOI(~ix<5H?cMC57aSKFDoAx5T z+x@o9BILlZsuJ~mzDz$V!-Q8|)`TTn{>X;Aw61JU0b2e=MF+CyUc7gu8W4yX8UkXW z4sn{6s@_^u>^}i6AT&KC^>4>?Jc@ZFlBlmF=Iv|%h;M{AChYo{OFs<;6x3cxhJz4) z3XX(0L!T5;ev6OhI0lKF6vP9A6`JNY;Aa&O6h=`czZVBc`0#K0vDz-b-xbNR*a7rj z`3m&W!?IxtCjI`UM`oz=pQrz)z>3A&<~u8Q30E4i^RW@~*FNr|=XPva%!yc)b4>2V zP!Rv_f}c^Hg0;e`5xs&XQXjYwLi-wy;f6)>J9CC7)Z}t{{_ma22x!R{+|zSg$5`}} zWCJ5WREwc6`qw+q`?@_SUzlO zYHO3BBPd9PDAZ^M93_xWVHC0OA`jm9Mop_N$wOV)q`DAyR^f@rcc5$~<%Q!Q^jh37 z9Ve4q&j)oG&?>%^lzsW$&C&Q^s!RxE;n7ubcbbf1Siuvi8s^TR?ES4bzd{aI>H{=! z0H{%L-M2TXWsZJ86Fmk(ypG-uue90>i>K;E#Ig!2dV(6YDjT5@t*we*ztjRH!ibixJXB(dVW8X{76oUH#qNPBGoOl3Zpkm>wQd{eZu$VlMH;c4xLO3>O+zLDaNxtIA zXa`zgRxZ1*nT_L{1O82tEyZAbI!Gjg!yMCDf6Ck7xauMRRO<~W7rm5I{dzcL zS7TGbp5H^l<+u-5#Zqyj{mHZ-J+dqV_;n?JG$`?RvebGcEIy1y!O+k`{%OlOKo&Co3y+0j*|$;d6W zLgj2dlYQMy_3o}{G=Qr_=m;%S5A=j1h9T)XNyW(&&+xK zK~g=S4W#@GNyM_GvNSB+yxP%YhoMA|y%f_$b$^YDA1wp@$uTvS%GqKMcdxo*G8O>M zFeyD^!#4zSfCS!SqO~I7P5>uV7IF}6W)lC@Q;w_&ri9`cyVz32Qw~wzH))X@7g+9l*;P-lXhr*M;rIE$oQ<|b9zQX$V(UwLRO0&$!3O2BF(?;Th>;Bb!?xrH<2;T)Ug4D9Zml(dZ)d3_ z_KN;LuT1*4SBR_B^&-~h%OoRQ_HtN?Zz75Wm)0xj}mX}INF8|BbIJtwW1rX#|Ow}X1BdI z@M7Z>Q)|9R5^OvxM{R@XiUCwd8x&I&6;9om0jz-wncV}lOsnT{%X_oyuj50rj`$APq3m~^gKcIOq`B@a1HO_ z)G>-i2y3RmoNK&dDk@|h`p6rsWZI`n2?qW8Tr{Qw9f{(*1@JZd2;`+fs~@g2+OL6LkQz>RLU-@>zw-^gwt zn>}*Z(%`RKf!+r3n}9^J4Yg3L0%U4HwmSa?(-`eJ4rJA3f1Z5(p>xmIj0G|W@!2o4 z>FG+d<}*q^yF7P{1=gr6auyw?DJrQt5+$5Wmtl+W-~(ffE$)>hc4yarOb{VR(`2 z?0+EsE`pY-Asp$JHUK<3l7?oTo3e8)tM?HIMVVhv9xc5bAK}(KHJdgt03(H!1*1G@ z4ahG_>0Z$F`6!rm)D=E-qolTDftBItYpQNtAAE1Hd|Q7aHr1#{tC(|yOM7xQ)Ev^- z*i4(7#STej1?4^g`Tkr2u$al@0TiTmIr5}W7q*+R)aReeS*Ajc1Da-hWQrbhDzC>^ z;Gzk=Or87sZbh+*ga)orww9t{mGOb&6F?)Bf=>UB#W{9oWo;DGTvHg=EAec6&nbF`yT;{ zLdWm?AjDDi?I4SGap~|eKGtu_^mxcYedtM>V`ehP$xo@rUsfTY2dw|aW$6F!{ zu=x-BH4ug7KsRXEuWYf^6uax)BbTK+zvpi4bref!Vcv}VFG+0 zX{k``-fs|IL;x5PyTcH#Ns8MbAA7;0OYX9d4!U|xm3R9&#u|NtdV-ibLY_DZ7`l=Y z-MiDzpRu{MhnTyGf;qC`X#;Q5VxyR`cqy&_sjj`$a#qr{GuYyWgOSqJruCM=m9x*N z-G?HxA@w5g;qKksqJQeN(d_+1jfX6+0AQAM2 z5A7wwo3@}~?W8v7l_Phc9KH9XfCj=K`&fJZoXtfTHL(wjXdV7`ansytk&JdAz-NOA z2>y7wIC=tkf!K54eAh8$BOF8ki4goe*{$maE{sGKen;9+BB~v=$LpG+KW~l11F#-; zHSk=*Dyt`azprMrCam~-W%iHk&!=|%q9k?$X41s*NH}OR9VAh=N$oax1%QD1U&I81FeQXMRhk4AVUl(Pz?-FJy@WHOn5qGZgo-{ruC*H^VOeH5hao(m|! zS3_N2#-K5QF!UnS`{>K1sa!WrzMP}7L9lcqqsQmEG>n2v8CYfPS%&35z5q-}#}DK~ zjsqv%CO60|ZN4*p_ZzJOKs|9sDA#9-QhfQ)l9d)Ki$8xwcsuMxDoFT6*LfLqD^q~6 zR4M4!8D^AVrHDw_&+5;aSW+qnnSqW?fqtV@X^{O>SwyHQNWZhr``JHC%? z)~!Mk!}l_Qu*0BW6ig1=I-2L6X|9=>AF~lhmYcPkLn6Ft{_R=%av_18v-Zo4^-Ar` zLvZ1$LFNBccbsMpI6SRT9=ZvPvP^xr9M$pt0UXr0js^=MiN9=O;6C_&tXy;G+}N-I;vN*^16RU~7l7X2heY5$XZC zywgsDM|b7GXz7fO1N6^}r^4myZXLO|i%;tw$kTa?BcBrZ3sG$#ZXM+OCe_8L#~|OG z5X+g=R;vjIH0WA&mO}X;kl0srdoDesP zSn6L}UIX(V83hwi_Oi$xIq-0cbGepTe;Oo)zi&$_CcVlo;0m~Xum5;Ua?vC~-JFg1 zX8a}MoA$yIGm(4R5Q(_R_AcsYYVESlR7}Lnv9R1Cm_r=U+h~nSC!;6^<+PnX+Oade zaKA%&GJ838a%d#k)1MnnM-tvgNkQCwY3!c#Y^@LDYdJ0AQ&s_<=+PlOpQ@?T%cL6U zZV3M)5U7V!NxA7?%0zOuuMV{GAFBW|Kcc~so!qs^8g}W+WD8fv=|C~f>VDC~meZd$ zu$RWkdGyRst0>-pta^Vm@N9GOG!*l#GsMfFD=jCFw43Rn8M~lik@A^?Jr25>3th#f zWyb=8DDg%G^wz(dkceYQqSwP&$uE^FA=oU}V=zDW?M^@rR%u)9KG^y=Gn2 z>-lB;+wuQ^N+bIvm@=_L>yHvyk7}RwXHb*}qK!v0I8b}oZ0(osG2>_$)yY(@u~)lZ zc%Y9?0$sGFl9!k_?*anY5{99Q%8vwih(%wVG?6SBVh$p`0Kq&dpwZz_%e*OJ;3naV ztq{pg8b+8PRtsRmP{(2I&!DNh5w4<@F@6I%5yN>QapoZH1hOBC#OMW2W%TElKmQUi`n^iqvpr;~p+0=n6WPtIO2$p*7h2!zmZ!ElsXk(>F-*)K{YBm!X! zO6d^@AM*jM6eq#=!TKON(P@dP19|Leu|y)gI(8sD`rf;ZXIs=wlhX2t)OUye2C!4yBM&7wk7B9Uf?PKse*EV2oH(|@lhHX_3v|t=Zc(W*k3p@cN1RF#3!Y!jv|8Cor!Wrp}X3qV@=wy+KcIz6m9D zI?*IT1S~#m4oNoNgnoT+jWUhrdt{n125r}s%Fvz|Y>X}#@f#>NTbBd3D}}!UL6~MJ z7_TxxKLohy^%4zxWuANpRHmXOG5jGQm)T&qmGPW1`4*mm3dSI=|84#^T3-lnAWOu> zj%PrY7y`=iO6N!4XMU9({7dW7koDZu0K9E|Unzwia{2jl*`(=K7mRrn`kr#$6bvB0dCyCf|Ss*h$!oPP*}aFj1rX$nC$tq z>xct;<{VCP*KX(sEo&9`@NoD7(Tu>C4t8e4bx@D@XEZ1-V_MaLF%vpV=k8$zND{U1 zaOaFcMD6HsKU=F8e(HjmiT|SZ%c;n@LfqlNz$H*EpRTxqkJg9W7`2!XCIk30O1}?* zru9j^td$5iivax8$3X6IK_Yd@sM(zX!~w+X8?5sE$lT}F-8epxDK!Yn3f`K<<2I#U zIab%&gZf=c+jt63ub?I>Q883Py zh((1JdTHR2jXd1pI7>Ayp0t6TV8FD)$>Z(SMKpcD4VKu(62DOB$pJDg|zcmXWssvFTtNK0l@zJSUkq#}vr(=7~M6*MGHkv|_Z0 zl?zS#1nd<%v~UD~_pb0F4^+|gZ?wNe_uQvjCF&f>?bds=uc3pBHJufmObWj#Fh}Ns zlg7aaIVgj=V-tSI`(>3;O{TLFW0$-B*|Rlu+WwEW&x!_}konDOODncbM=(LT@y@q;z^kOiJWPnjU(T$h&7j-ds`){D!&aKkL`Bw^q@s;HLiE8|4lWk zFAmu{KuantQ!e>QZNdrA>y%?&>Bk3u-2BiaqZ&1;uY);sY234ox?HOq>;b;u6Y5OJ zsynha;>Eb6Aruu-A-+Eeoa)Yl8hNrk*Z<16MQMI`0;oD-)zyDU;XTD44yS+=Ln>~`Qpx;zb@G_|ZjN!BdDm%b40MdP0yu1z zxpKLXji)j`9J_G^)mu)#%btSuv5MDAI@Ukf==K<{V9LLrd2e(sq1)qY0G?MM{Ck~E z)1w}vm&rMyj8SnoudTCt6jX4<7sh6`-H>G!8m78?O|vdoW^Felu`kVEW!8;6DL%zK z($7_jcOB#1yhlUin1%Fl=gS#SC#KVhEf7icQevt|N;+>)^AWpnqg3wTB2mWkg4+A9 zcBnCf185D?0)rO!&YbduX+F`8k2=@>O!Mo}8SiuC9e1D>)$5(_OjPG+LYV$#j{cB; zmmW|S`004wGrA1G9Dh`G{z8kOLUOIRM_65W4HZKInYOYYPgc^lp%yU`$(4Txf_T38 z20@UuRO8Q0f0R`sPl%K$P{MUqlhSU0N z$k%!12t3X!7JUR|)=#_Ic>NUL#wW*M(bd&ghw-6_pXTp`=O7P#lb;F&I#}mY zKQ598Iy4aZIyHCeCwfJ@6Yn|vDU~0K zq=k-H?r(acb-mT+R$3R;zK1_7)P245r?*|*+WDWQe#7g7x;^UIl#EFoWu_ z-R6}`urGLrtdL<7$!^6~end+tk+9ESdrNGutByr!*nY_Z28!-Mv=?BV(dcT7j=F7p zfLyz)o8Y&jRmrAc#sDy-u*bhMczuDh$C^0(@AkiYVt=dol|y1w__(wbxIWrFR#yvf zN5ZI*s(=Y@=8cbvv6qH&BL&)L9Tk02Az#s*SA<|N@aO%rsyiRj<`9ttK7O{+(URxs zs?~mMPBDVSeeFX<@#RM;3wtt%wF|XT;{vVHT? z{>_cfHz-#y~ zd`y*7`rbYXIGatMY^aE0n{?bYy!)|b;2aeLu%ek+c1N1yfLy?zPDo!fSXLx1k3W_S z)Yi_B85#|#I6b1L+(}=mJ3y89;2Qo3Z2|)DqkqB%TPe;tV9nD(Bh|J5-V+?2JCuE( zsqy)kc#ryQY%~?JYnOM_&)u+^cW~}S&*(dICG}M$jPV9Bfk@vqmfVZ54I)!Ma8{T1%^Bk7LzO zC5-zMBwih7Lv`)e%UN>jrBbpQRsLZeUj9>aRJ!DDV3bSsM0G_NUm-0X%&m+Ued=?^uwz(%jQ3cgzI;5u)=;Hzppx z>LfUL^s9;3eAf=ofiFW%8#x-xa0Fjrs*D~u(#VKX6H<}S+2oI08ewM*c^drcvEQqi5D|s?>}`A<*voW1U8^Q z5?{9lb?=Uh`G}BZGHJUsa(`xmpXXDtW3}!7@4tIHKJe6r9d$7~B$h}ixuZyd38{sz z99z`bx4W%+?~BD;SpCY?YG4)!bZH8kmCkMH2c%v-mD0~{*a3$5;oBJye|saO%kN*) zlqY?)M9;_7hTVXo280yO0p@XHskiXk{3}x}uT)l>bf>1PP)9kPrMFK@e36wdI#<8e zYc;$&& zqLuV6-qr`tuKHZH{S>gtf_Er%XvJ*Q(WnM1KDqZQpbH9$l*;t2 z)64#|S>KJe3*}ZE{ln|BlunrdtGZVr_}pm&C^!f*XtVGmR9G66mNd7vt@Ce_D*E>8 z^6DwQh^ukXsBj|beuyGgH^MhA*o`qzb7bA|##WSI!sHzdpaC(2>9>1={uXdGUbk`B z+!np?zFac>4U)Zm*^hBhBsA856&?S$gsYx));AcRdcqi~7V^Ds*W;q8EmjGGNrnts zIyRqrep=gw7!St_XoZB@@j~v0yw89HM_u4t4y0x4?3v%^hX<+@cs#pn zUg0vt!xBd^sfaB9_+J-JJ&9|@yS9cuLs2nD<;}Hq*C&hRd?C`5G4SYD#YaoFH_yB> zs!ke*UF>X%$jIe$THfBX+I^h*F}IFa3ANO;$(ql#d9JUL4?W_D?$LiV_j~g9ljSHqd6D@^y$n((NDi{6YQ>{KR(Mn6;=Rw3u4|CTTT**ip?g^$?!j#JLCKvL&>p1HT6^qw$1xz;KN!y{vWuXK;M7I|~A!O`W;`vW~%z zZx3w$%%~ZPUil{*??SBCQbKKitgD&ckWoI7g7yFgdZD(LhQwsLle1#%+F`rTfET${ z7C$n12)nL+@E^!T3bQwM_yEG$aqIFKk10Wl`hTDcsIpEO^!Wx*N?IduP-=g9n$jea zvg=-G7m1<{tuvPHva7hVCv^FUeNfB}T_bJ)_1XYoxl!VAQk#yZPq-3roW32p7r$j_ zkq(yO+|afp89=l*BmQ;72x@g|t6xx`A}DD=NjUY`cOAVJC;T?b(2`KeB1lp7>yEE# z%ZayD?1e`I$^9kFGdAz{8wJQ9T%sXQg{^|mBA57r@=;LXjdy`=kuL>n1gTmL{6ICt z5bgHUtliHignF`Aq;CnGX3EWJDHPoL9+rH&PG~m4h8p021s>aP`|1lrSJ-P6kgjUc z6b*i$>A%iv`7?x_r$@(e*upVk8t7b)Io{QGxL0AI$GKuQqnOjTY`fd~Drvu;3nB?x zdb{l5IXmDv@;IU8$1N-azfCoLsY9_6Zgsr-C3cxheEN5zxL2#4;)mhG*EfQ1-0OS} z;WyO?C@Ob(8+>hBWnPjtXKrAc(dPd)J?Zy&LGqpJbg>s55FoIt#jVfi=jftc73teQ z6%jr*XJw3;%Z?3+@L=n@zy3@hn>yHvn=&zgM$L(&F7wygttbJwsk zY(55%fziuZNu19r-LAyh(tY5EGb`!x5z z=I)p)67d?d7VYfc5U*sNE*sr4r9eQuzQ?H2wxyJ3l_mn6ZoUOswfnU*@AB`Q|8VDT zu1&hyD>-9)rZdNEh~GqU&^rq$53`4gdFzJK;o%xmgTIxeM%)yiZu~a8nF+=RY=8W4 zX__}*HHH+h;(+&O0qMBdHWv-kW}EvCyeH@~>&gQNdjFSxVXtD|@H@Hm^4&xEPBn#D zBNsNd;N47R>Y67F#0R*9vWJK6T5|C*R8K~Uq~h8S72gbAtS1vL-GfMi={_qOp1_FS z@?7_RjoxXTo2BPbdNK2z{#|EzoFBXiD_3EvzzL?uDVR z-U%W2bV7w@2<}f|4Ch;YZWU8sAQ3W0m-*9rjs1hyD@WIPw8b-vCh;i&E!3W$_1UCD zg_S=)=~wtS^z$DeTE~5~zpEzJg_b;gJ)%1xBQK?bW%uPL>wexsl11rT5g8~o5dbzb*V1@$ff;&FD8B+<3o~b1m){L{wVm6vHnmzu{qlJrPn&)6nk}7-LM?% zV{q8ts>%|Tl@XEf{tz6H?XXWuvsPGhN#lCCU{}=pRjVlUY2vh`T9i-eqFCR4gouzE z`;GW+g=Im*8tPL?<_NslT#f8SWEU!(xUji)LsoU*5#1_ z%YFmmkcRcLCHugAjo@2C&|&eYDO@I-ftIp^#D5@abIL2jXT$lE2N-TT+YNG3zJ2Tk zUo>dC0^PKq%l8!f#iXp@Q+wyXB$6RZ+AU;_z$qsY)mjw5X5tJ^U%?S?>-AUM=gu1) zNUA*&{+9@Pne65}<}xI{PxfIDI5pfwIjMLg4f%nmow<~~Da~QrdQ1*6ujQ*cS#9Q+ zZs*F*SKABmfzi;iIp!!tI>;a_VVP4XSUSpRMB6K?1``)V_(5|^E%tI*uPOpTwsk@H zicJ>Pc&p^=&#yKP%N^Xu#tbA&D3@1m4V~3$j82J%mIDU=(txS{d2}U)YxZ_Nhp^I^ zA+V9$qemysjy^`oa%yI0u27+pYb?>hMR!C!uEh<$F_5gmr=8xNyo*M9o3#u<@cs

0b3?J1}K-$VU4RQT8c?SM*0f>YAC~VLF_|LkC-q=ozWgMxPN2WRVS{`DbWqb zQ+?HGi5*^^eIkZI}&CDFROW11RbO6fPm$-N- z@91@m_B~598jfYOsZWBg`YlDqz{eV4lF!y?V{WM!U8i89_4gGNdq_@EkK&Y5%s|xg zcV5-g|A8j^L5RHahFOGa?lMX$%Gvcts9=>=Mi__Q)G7eUJ$f1JWzQi#^YJ>T4$q(3 zs6^EG*Q75)3y$#D=E-%(EBVChz(+XNLCMu?eJ+L)*1z4>J^RAvkFM_8I)0jY?lt47 zaRcFA>GV==Ix{pU(pcxgl9XIbr*J`#w_xtB;~Xbg>!9ICah;Y%?;M*t@=w&dsUek7 z{A}cgGjOI@Dar4k4j$^L`gK9#A;l%FX4C3WvGcM9m;aqVpK3YM-_0WP17KT6Hs8@s zdbcIFVm{&;Z9%khKuJ}okj9xvpEt5|x!Re+Vtt&uKe}z4s{Cr%ZqG72|A)56I>!SS zEG-AIW1}fLWAhboI}hENbGj74)Rl<>l;%{6^}V5##a9NVIbkM_ATk!bZM}7QPkF|Z zd#LTL#_(N^4eYoK|Cly#x6S+z`0ZakV80V+^^i$_Y83kktxFmE4-~KXz_5ct6|G|` zWhAn-aJT299elcCd;9F(K6<6Pu-z}#6u0A;uLz9dE-3!sIaBh??d}h|PV>V*R3vbl zC&t9LT(sps~3-FmO5;GsCG@t*LsY-`Sr?tvX= z5u`M0@q8i4LwDp?d(fFsm1J>4M)Z=Cbd$#Iv5cyI*lKZkFC@1YctYQWuMe6Ooc=UN z;0rkz6Yyg(+OFmKKjgAMytBsl=26=D&3DxE1zlUuNV;Ecqd`cBq!?pUw5^^eEBAsa zE}D=&KMAT2+bezfABa~|*Y7Ar_{1+Shbi^6+R_*B=_-}j24oqS6$;c?Ja0}~Kj;Wk zKvS9x%o^7mD6uzdCd#Ah3jOeGm>z}f{JgfJk&OEi>!2RAgFkJz|MMsQ&39LQLI}zu z1u-**_qpnik0o=WwZNCaYXJ1@v-oGqo3N^9a7sxvyU=JwSCp9vzwy-aoV?7d#9hzm zcs`M|4ysFBdDX#_0!hmu=2cvZK_|b0xPil_I1CXby7r^=k$>G*(2JL_G{QSGR4d^K_R{U zTWQA}w%ZqLmI!s>ikQ~7yi#X>UGRUtdL{)NivXFEzWTU!vV8pP&rIqZ)I zc0%oAyS>NJg6;g{r|P7#IJ_;d*eSjEnlPsRWHnqH4Tr)&nX|$ZwUKLONW+| zCU*d{&m`XRfqH3m3LKkpi!eYqih12)ekmIx(DQ#BoqIgf?f=I=Gnu3ipLsL394LKh+(m`t@={T&fa|ee?NHSz|C}g^mLk=SrbDYB%_wTxY zfApWnBePxCuFv&;y`E2{M_}=PuoCoCxg4@$O|B33HjXPwpSZmhuH}XIOMliLo0fao zN?&r+mb8z0Js8+E49 z11a&a?*lrdxHUaw=sbRiFZAGD^9o}xNyH9q04=Uu?cnIp#i0-;bs^1djXK{B7GznA zY@#DLid7y8V;wO{tSq&5L3gxkZd5+8>j(X{cIlwssKpk@)y~UxloHp|jfI{E}fXCCVO&(}f8G5gap@EnrwI?er_QP&zhNh>HY5Ev&Jx zf()QUlh4su!Fsr=^TMq4>m2`TImdt+UD)|JKE%|=Vl@t!tm%Q53YST8rSnC4aZas;vK> znHBF1^qt`0$VYzU5UR+c^E$QESJ;aMtf^)X<-sZ;)5<*4LJ8G=HwQC?NSMuM1S&ELbZU8eycfs;hz<*T|@SP`L_NW<`*NN=b#H_SKO|J2?HV5wh+X!t8H5R z64BF;-x7ZhQZDiLD>gjJZML6*NQG+3M}iT%t><#@bd2a~ZktDOyiZ zVr&g9O{;O#iWkejQFqgb_nL1sYDFH_9GQX#`A2s=laufejviN^hB6j#itG2#fAxCg zeAoz2HKBH+>@I8zR%^)+3FHOM#3n6d6s~MS>Y||DRiO_k^GP75j`lW)2>i}o+n~ui z9tA4zAl0qq^<<}EbyjxFWB;<`V<|bCdMzFZ0l8fIY+z@iJ5l|eu%NXAjM{~7G#et| z3*17UWw*j64R>sOSl+8hDT=ag-UZEkVZ8Cn@JLmF{)^0LY%&>v&qLOd!jss5adO*_ z+L)Jws26SlI%@JD%Aor8I%XsbC`U?qQt>E0Q<${exq+~2QQQr3jdn5mzjqy1`gEwYebiq6ncYK{l0hg)Thg{v z&p=IP-r@LUqa{X2(o?P`rNrxhv-amyzw(tsOtO;b(^A*wxd&zPA&MibF$p(0pC|~O zU?*JkOS3VURfi?%0MssB(>G9}BtTci>;yB{(i(v2?^qH8{mTpMCmDF-{yK55h20%D zTBqS|cg9K@IQO9P>@54=6r&1iE8gmxLEV8#wLV$d>(8L@e_DO9-XSKd3CX{Y{-R$G z2AHWey*j%}Wh?h|5o^BZ@uB2;J?BJ|bt153E01FWn--_eywp7QlI<6yO=8XE{gGkh(fH>MQClL=alsi9YIg(hMwev_dB!)@=WZfnwkcohNqHzwvSiELkzv+ z91VHrb%}O5SEK9G`FCMr$Dwr~9}&*H_!}ad&#y1D zo;+PynLXC$?h{BfePty1tlnl^{KHx)4l&;dX-~S&WzR*2iEY2ot@@&|^gFd)ms899 z*?K4V{q}BqEnDxB$N;mCkjwQRvWhN&lrGeplMy;B#~G0eW%CXG$cDeZm=yIXU5^b8 zwk|+J8pmzMkq8cd*{OBoo|-1_O1`GwgpDy|hwF#A7_K1iEpBFq9EhK;=%i`4P-upI zew^HZ?@ecG)~rY*QN$jL*7Ry7p`X>6_Q?1ZgUU$bDp{0VhN3er^t^ZphU|i3-MvU9 z4yj6w00OvHFDsQ_?Kj&WP`ef#fymIor^$E7?FmiRVhOOUpv!*huDdPm=}n@6gU^m= z1fPU660+^Q?lF%C$JOdX7ly9|Ot4WS1POY9SZ~;*qmfi_*|NDFo;K0@BLmz+tPMm% zcbdFyJj&V}sp2U;{<}kv6QY${CwA0P>+cTJ#-;@AZHPF+K#9nTAD?YYjSe8qz4@mZ zKFUM%PyCb1CzIu~pD?@nA~Z5dy09c4X{6dj7Oe5$h8|!b#rhG(&{K{r)~#8gpY`-N z@`8yFvXZ0741WjMa^SFI5*n~O(;%`J^rNI|Daf2@>UyNAre0}c6)8r!V?*qHQ$qpE zN8~84;HzUcCSZ-Gkd3O;N(pUI0EsTPgEMK~`o$(p)Up%&Mjtn@>ycC4*&|y)fmSp@ z_8%#1CrGV9Pt4fxf0^7uQY2SIRtgT`ZhOBbm>55{^Z7xVo;q1p)(dVW^&?%&&N<&d zj{lw7?!`+lQX^sph4_2~8mgQnY?Y7qDbXv#( zH*fFo&qwZjxdtV-Vv#0Uq_PyqgMPyS4d93%@sWKMPMu4elK}Ax8|NG$OFET#P^(I~DA>zz|EZZBeX&lpYN|BJg*825SS3k*sMgd*4GujC^p+Y~x`v|7jnr4s=hzXUYYuQW4}J zEnLjtMKj?@2ffCx36akyBmaedf86Vo!9rl_gmV}U%q+_aIdGT&|0fq;eU3Zlj<Ag@VFZkKdWvJ5|dm;{jT^{)0XYzP%zKOm89AqWDlnzp0Xi6Aq*n(JCG#7r}}9dgCP4cdf3zZzrKA89sNN(bJN zm%7i9h#C8atJP0vDaPIO2y-FGlA(igg?)1*!*4zJZn(ZrG-P-)9haTZ1b*O$2C3_< zU%3IBmL(tzoBiWzbB}>ZsC^w~*PU)2#6v9$UjGZp!OO(!F-`^0l$OE)Q`S6)WM5ZX z&6QQEEfiUiS3fF;6XE55-#@uRs@m>X!H%;kKQehI8L^)ki~Jy7sxRw7tr`YCzK0CU zkk2=o5P`#O4giri@eY`}3@&&*V2&uq<6F{0jenRSNm6hT4qY7dIe9)3Z%1m^!4O1Z zo2WKHHC9vd9}PUIbMbR0ivlx|${h{m3;#s9oXX;5r|Gi{f$=QV}?7 zY*x;}NlkzMHsVAZXzZtVOWO2mb)}&aF+UGd(+cKe@MCj%-XT@vXR?ooQdEy#9a#y3 zcQQ*-70(&ATY`39aW$qI7Hb|ZgQ>l%iAcTgH+p+%&3haO;d0E4PNa})5-B7oSy6pN8R|Q9~ z=JYs+qT2gS%U0qKf@-y*&WT*R+;t(eY4_WGFOMQC@GM8;xMd8#72iVUVz{H zbq20e;b4)W9ia{78@)|bTp^AoMF57MHr@nsK$5bzho`<7eGGihH zW3~yUU~C{3Zs9+$eAfgE1;Huq5G-_HGwYTR*(`LfSRzg_f;unes8yfToXZo4+V0w`|4VsjaBHZxcKdw6}9KT$9{IC~3~ z*`It+ZU@O^@t58aAHG9oZH6Y+o6Q29^FFdixOl}SiM@ay)O#PIpg)y7o8ejcS7=Xz1Bsk-YDg9ry^$LV-8n5G#)1EG+CU5(a&f z$IX+_gAIx9$)6#kOaDTk;YMsD@JqpkHv46lkO9vy138j^BzZa)5E{>-g}9sf5cn`^ zBr$%2BHQ2!gR&Y!mi@U*ngJxlXILH8P=Mf&Ms_j;*|y^pS5Twmt;L^|v#YCU8Z`v) zwBJ}sS$2GByy4w}+0VLW2eJn8^++`5@_74c1dep+MTlD%QK{j>1`Cdc7Z&vZop-!r z_PQC&N#2b0P!~$C#xhNm!l$3WQ!YVS4mN>5YVDl9*E5i7x-kBf#0)&NDIK&^)8O}V1FYh(rqjT@#o zStA&Fy=mid;FN@bg)W&QK{jc=U`Vxexqg=U{g;JZpc2z$vAty3_4;Vq+u6!MAZqAd z1a1KJty4iJ_9%lv7+*SumSwix0*K!vI(be#`jTwPua{X9AcB$|V3D!>=N+@R*;4Yg5I^i*%IU+tn>LmZl0N+oX zBP(Mk5I} z0H;8DX8+diDObz_T2rzm*Xx<2(EwIa9rNGE=B}B)`k|QwDB9(1xNcx?C9V$GrOtlv z4;Aq}Wz-&a-u2j83d1`)sFQ}PA}U8C4f&pu`cJ1$q81)`#K0V+R^&QqoJpwQ$HTS* zb)|;jHkpsVei7C_I^ye{m6J~ZA!(ghVK8phIH*34FxQ~#%q5wyE?)~&dY*Q-8}Lzp z#-5DmU*&5G(_}gVjfYRU(vwVhFe$XrTI(zq&-Mdd<>R{Yazgk>{nCgNTtR(=ySTy{ zC+T~X5tEvI`2oqN}rP)?o)L}h+)@N zNx^wru8w}C+IXBuQTlqxM*T*<`Ms^=`HfQQx)o_0#(-7__D#2fd5B9Y>NCv%wrfd< zPd4CS5TFQ%0di?sz({&!u*H8P4Vo5&RhFw+r@6WolAe@}r927JG>%6S+7ReAqb4(D zz&fzJ;`6*V%d#DBT#OJQzVVc{e4bh2c1df3#Cpux~4OvwgK>9@hqK@ znY+arlKcx7B3~mEpZ(bb5}B1d_g?qdyhY{_f$x z#C(6(Q2e-tKe4YA8xG!>jt*=0cWaBcXUsD|wguFXUAty~ z!zzf|A+Y~!+qCKyKZqZKvxi?VsJBM_(f*^|Oe0kC?4q%zldU`@c<^emm+NDjV*f7* zU#GRZAOF11`$E#M8$ADYWpa}Z--Z@2)dcJ_M0cd^ucBB1hA*xBQF{Olwj zS}&IpXEP#B)!&^tVH?U?3M1yWN%bW3>qDiP6Yc(< z6IH7%?Qgsj!ZdDVWtu2;-#B(B@UNp)TzJ;=IVP(7xIl4}Cey=raExi~*mPp~et&#` zbTGX)+gZZ7c5Z+S&%ODqAQ0mV@+Qxmhq&H{E1~T;NB?L_=gVJPk3=8IS3DsW6wE)v zq*=y4e?wE)fw%v9vnF39XisL@^^b%XnyRY9xoi!OM)(+ z+Ul(3+v*)g;s*j?x{KoR5apQg!R&h)NkO6=@-NjH+9id;aL!dRC#)Fe~Y)vU@?rLg8I< z{q84<<3?P(fftD2m)-5i5032XueB7+H99F7qU-7qkX#&>Kji+8>((1^pVhkRE&V1) zJ~nLn6qB!CxCuTVjztdGy{dk_I`AMn8&Y2JL&MXgLH96!a`-ftUBHg zqeF@!wL8w_p6icLPzsj!`?-l1OftRjXep1d!LpfW?itwtqh}E$OB}=}!KWsb^@-S4 z0cP+&FKmiOz&Xqo;ZF>2qbOZaw&K(s`#e$kvf(la=+x-%-MVV4?v#q4q-Bqil^KRo zkHkjHfPTo6E&2KEzRgcfo}zp(X&K)8_?__?-qaCD)ov_nl`8s{=j49!RqlaO-aK!b zvx0mmEBwu>Pet3x?yY>3`}eL@VfUgp>tP30HjjY zPt5p9d=ybs=NU802mKrR-2I)5n=SqXLVrc2m|q?=&fMz7K7UJkXmC){UJKBWo5YVi za#Md%RQNF16>ozUrt!NHR-O+{cbh&zZ7DgQ`qn&G0iPUK{X9D@y@E0hF!l3> z04e{VXz?U!DeThvmy6oV8;8Pm=vRYSO{fXah?%iFs#}g>3 zp7(x;Qc6%Nh`ataty;C&!tPxRNR2NaK@1)%;!4B5E8-VEKM8VNx*}a#ZoMgsNI=b+ zR-aGk?Mv{yva)F=DQH=}U=prv=OJE;jwhCkwF?#Z%p#lzzV13NbC0xGyF9RQ7IR`< zZS29Zhl_H>*Q~D*T1NFC1-EyNKn0HaU)~LoNEe@ao}Am{!5Ja>c1#tQzC{@ zd65V)vm;5d8>>X^RhM=Q7nJ6uedeuvtk=~L;)P+pxqy>fmgz(Bijb2X7?&OTxN@b$-+AYEK%%JK)A zqJyg^D$_yL)@k3|MxJ$#HUZVLbc!i zbMB9p@O!~8V7+r)_naeTB^gkkWgp4WBOZ}=!rkx~nzl8CN*|9_jye7>q$55wH|N_! zlQUt&tR5$qO#!56Li>>0Lv;($HV>T#YTs+&U2hGLCdkW@rzZ#joU?f+$IQ~`E5{=< zvaeYEIMI11d(j$a9lyur(7gTK!C0AJ0j?dN?ELU;>E9{`%#CUB+qbIw&i5X#@Q>^A>v`{USE--Jg_)X6x4@bT#55sv}e1A!`;PlGqs)Ah?I`jr;bc9S1n`*D}fD7|IOx#4!dh!JH_FxX;o>T3`iZb=*YectC&BU>(#67sGuJL9ZXT#6 z8S)Yypqok(30oLM$nR}*2O_s&)FF+3`FQx|YR48NVK73qeIi_}kuz$nML~>e>h6jo z6d&yC%Y7pL=?ic+cdHh$?v}`^u*Le}*zMGcPd!HChGfi2-(Zj8Ie%MPc8oxDa-&at z!GMQ53Ns0fGv6lY2tcB5d-y_N2yLhVKHa_G$Uo=u0- zOV163k6?ur33iVHl_yVhTo1kLj*r1vu1}Zy{IHFos@MoxT>3_>I?ZdY1liu_wS3L1 zeDqga2uAjKZgxO6d=2iOJ^4URj}p9Ep~@#mwgWX)UfAZBjRDkGBN$5W>tHocYgg%s zKiPX;*zS58A~z^&=_8C0HF7N0i!<8K?ym16RQCPu%D_KR!v@EwoOooGzwje}sd2c=q%G$tFT*Q;#IBc29>-k8+f@=|JwatLj>H~6^fG< z=XHeEa?q1+4B%dCGqgW;^2M`KnkrpLGB{vxOT zGka32wC?%BUC(H}X8aXlhcwn`5a1n0$&A8Nw+!rVjF~A5gFfgj-A~-}d!(<{hl#O{ zmGD8g&|Z%-wbR7(=LSo_#q4;BQYpx8^ZKEM8JVA!Iw4LCZq~cM7&F&xiNBk(YgE11 zbYEP}9>s3=6A+IYY z@b`@CHX7M0C};7pi|2Rw9NQy$D&K?^QuF~Ak#@yJ@NvG0K1_ZZS;t-6S^2Xo-RZ%n zG_#!QKNiG~U!(agJrB8KRiCwBROs=R zcaxhEi>u_3UoqaVbe+r6@2^ke059iB==S~lTenB-4@Qs)&+mWa%a5}UR+>IozMN>Z zce-@Yc8=xf)$&H6W160x++R`aLsoz6zvH*(tussDo3g9GzwUaIB}waqC*vv9QnD8?CfYY|PFeL7?tM zDth|AjU!bxDs_Q$4Mp18&{U;H_L%BtuiUg_Sf4VT!*FUA8-xwQJ6m(_>~%<+FHe#) zpY^z^+HAe?@$i7I62ghv7pHqZ<=yW2sEF6SLGwH`JQ+Cl9Q5Z-VK_Um`-^6-= zxBn-vai}LXwl(n#iD1#d{F;97!KM+Ze|Yu1i}Q2Xg_gxe%|CkE&b7*(@{eTQD6seb zhM;bGDJ;F&y0>8I^80jV6679$%Y5I|8d0U>J){U10GY*~9o7ZErx%`X&nA6}>epN? zP#cc{GN$=fh1$fXUeX)-EiGf%9AggU*dR-pl9ABAoxk>~zxem;u~92q421F${Mpez zp>k$@?q~ubox96B&R~PLroAM+XU_M($*Q>lrefvtp&P^Lqw|qHhwjOXE%v{) zczM3>z~QMuG386}j-L|T<(MbW&$uP)oR>IRI>BW_}zVNY$v&E(B9)AxLE*TUW1RM6sP!3-|wqAE)RCiP9v?QE0qOv&n z_x_qH9qeW<>z-sNI>9kd+iG%0i)qFKVw(y6eL@}*k2l!mw;b;e7hoi^as5{|oeDkI z=#?sh9F=h+z%GC@g4AQL*&R5fs-~$TnuMNp?i0@6Y0nB}Z$UUSvjutEqF&VHev0Ya zXR>y*UH6&caD}lRc?JMFw&Vysatj+qWtRV9+bYPS-FzQJbSiF_%ftWVTXARLXGdk zFORvwg6Egbo0UF8T2Zs729Z~Gd`#K;N5SRSTXsCPxWOsDarC@R64Bq>KI=nva;UkM z?ankUrH`7s#?-@E4$CjJXP-Rk33KQuu`ujUjQ2#XTG;&xyShn}cH?R*epv;d7rOnL zp5Ij>R?eaaU(oq(^B>$Qb*oT%ofu#w#K+GJ?t8RgT<7Gu{E=ESrYxP5V%jIXIG^<^ zZMztR&+&0GbzAwlWQL!Js+ zm!ngcmF~~jnkL^lc{f;YiS)eVg`{`0(&wvxcqD1hqBjn7zy>C`joX^@mJjdl+0gdC z)@1uZP3`3x;4d#Rujwi-SHHEd1pDR=zf^-3uG-X*UX}N9;z4xRuTEK7!OFuOQzibZ z6}6)$AsTGTVS{m{cKOj%*&*0uoF3Y`LXy|GZ!-i!dk-<1u2Ehct~U=BP=RdfC1kJ~ zr;A^^4D@We2h|^YZr-=SI6&cCf}QUFXiDJU&K1`WZzx%MZy+H%EI&(FhMpeczcenx zjl=%wta+0%dsWOdakqVTvUj<_Ztv~e53BS#=1hvFJxX8xVIrL@IJJWj4=%OC;h!#~ zoQb;gqAuquu`PPV7w|Wh42Xz}zm7%UV1%8Vewpz01zAhsRFrTcWv*Wap=a;(b7im3 z8b(+JY~Pvozo4}0pYIEX|Anq)pY3!g >y|Bsf#`L>FECpjmiw;3_)*Li%gthI+ z9|)T7DQ?i-_Z7M}{f40;`}NQDV|cbnM#W+>d*!ApuHLW*++}uS{qnpUca<61+Jq?? zW4-ZO<-gL`dO8=z%^ni0{7OARjL+t#^p7Qb*&%Z2FLVld` zpj;L*E%sY>zSEpyoGxpOWF1TSd-Z&d_~J;j(xZ?Z5v%p-@as3Lf^EABh;5s&*OlML z^+^`AA5UB>n)9z~ZkjR_t+>PDF8_n<&1^}u(VVOLMVLOFuibNy6n#-SB0S{b{&O4k z?F#(UKC5j|b0k|CSY*WC7}wZYzWj1WYEuXUj--KJ+|Y&v=2$ozhd{?9%p zXPsa8#$EnKa-S;o)-bOG5|5|ZZRgk${M65PcvaCQzwnAh``4!jP{iG|SQa{IL^oc9 zo4C6TGrt9+8yuxjy7!xD9^)g1pY}B-eA>%M_SejES!H&s^N2&PPV?&wF)J`TBM!01 zC_eKIpW!#L67cqQK?Y$SLS{RI84m|_Tf#pS^5$;^4~9WKolcVzCh<>?lcD5T1sTGe z#>{`d{KWQ*dXdK7#8;_YWd>?irvLVd$(=I7vBFJN_!w)7W#&}}n!AC>0 zH4H7vV~c&WJ5tr+-Kcb6TP(%x8FRlCzAGh|;Id=cX4;F>?sw_gslJO#%aMUTx}m(| zd?(X$AGBuoU!O8Fe%XI9;*q(hV4DW~uP9d;eMzN;`rLq`{z#ohhnd~EpH3XT zFm&6yq9l5;WaF>!71ka9ePZ9AqxRN_d<7db6xrf8Y3Sh!#q?5doJ|93Xp*|@UM1V@ zjK3w8Cn$ZohKvjvo|tfVx$C@>JvAAD--O}MYOL(Sv=ymom#Ta?`R!L`^E{@-fk=?> z^Wsm+%)jG5)_5R08OWiE)GG`63+ldp#ar<486)Q+OrOr&yX~zq(fPPQd*-tq?+_as z`b(EjZ1*HlLA>8~%@O?-QHE)^%P1wlgU}rc)D9n>7S>qVBhH*EFsG38K(>nXGnJz&kqRzyva) z-CuAW#wDy>ayJuJ%Ji(Fc)C!#x|>AgysdulLSCI~dOHEplVirnS~DbX`LF}gB@{WS z(0PU@&g3HvyJNnBBw#T}ct^wRcVz*tj~=+pa$WMQ1@W&Qz&G@ikZb zrM8ca$8W&{0{w*k{A>p*8Mp~ANeY5(|K?4}jSOyczPka^BGF{;-2PaKmdNy71^?AI zCHb?=NO%!PL1BSMN;X0uu-TW>aUo<}QRtg3)zm&1c?&C*jrCLGheW&Dc|)O8C5suINdMhg{7fMZa7E2RaZ*(1O^tY5~7@_|^k{4D!*C7M3ap#k?7rv$|r@%Xq ztMW!y^W1e0-K(oL;1Y1zHJ3O0EeZ=o1JJhm2g?pDr3TU^!*)>$JgFjQ6T*+~o--AJ zna}Kt*F$rtnvn8{amDkqx7OF{&08(pTG~A8GhDO`g}X$TsqsY)*gGj zdDwd*^9fBX2#*xLJdyB@k1=&zhLh3UenA$8&Vz7NsViDf5hlF{#l3E7v=?PLjP9ZH z$rDY4X=cW@DV{n5o2sBt*W26eB=2`=7xt~e^X|L-7IxHbvUvehOV$K=WuT+hEXNBGaRvJu@;DA4npRlA%9&r(T8U???@HEX9E|PrBmw zw3CzV8tawt#}}=f+4OGZrTlw%(*v;SsW{RGh(Kv^75p^&7h+ZA(0lc3LfZ%Ro>e*} z(Q5071#kNj|Aicj5tpHox&IaVR2G_A;+jFayi2xqZUgZIBMyf7Y=LELqeTg&05p|! zU)zjAoX8ev-1|*stATp@x3n*|^@T}3ThgH3CF=yQ%WMs6S9ZL1jd3bM z-uu4!Kr-}qxm$o5Mh%i^u-!N~TBS$D%rFDmD7AjNRCp`MAa07RbFrDT0kKuj!=N`2 z?M=6(r|!t)kGA)>*A5-6{1<{0?Y1SFh84DysiP%znp7qMyc|Ew3x1~|gg+f_e-mY8)jw`|pFB3AjFPS&*V?Tl!A`1~_mBU@ z?^pAOY7WhU3|<=wuFVlvttWEux((azsnbMY1_>9r79T1hc*I5NGZx@Z0~$DT4-U=qAQJ*+Wa@HeQDc}ntQj(KdFu%coFbUxw<_Z z6#@RH#RJt%A!=TCK4SggtjigvN)@2yCU}-beU5r+!0~1?YHKu=3`=bq3pW`|o{Xc4 zdS~*?DDjp)QshH^9uUUsJ3)r2MA@a{r;xp>leIu+r9)0m;UCftnx3>bG1?eA&kCAv z+(kkD=J+r{(KFktHO23f6Ef?e5W!g^NH`mAEomTN@j;6T8vLG|<9jqZBk}f1@n*R_ z=JxCi!k9)wxvmgtKy8GK!*MOfo(;sM6{qDR^+LFI$J(V91MCJ)PSV=J$` z5*?4`HeTO;IH$J~X*!I6aK=B?s&BRhHNWCop*#tVc+Y|{VNqWhcFZh{k2XX;RdDm$wPenr06Zf8{qE3a zV*OYF`X!x4goS4{FeM>qdFkO)8}RdS0D!-sW ziq?NtNbv$ePt_d|Q^VmY?EI!L_%jB*y zeUzC-Faa)`C2x5YuQPLdQ1V7(r-st&<1+-Wu@|P@NCS(g$YgS;CqB zc1#!7pnjgZPN@WxAWkWo9%5%%2d$TyxxkxGV3pxhHu+X)y)m4zoPx>h`rnY&AcK9^ zeCkJ5gQ^N&x4&wPL%L(rUcSPP4$B=&m3vG0WodCE4?1K;baQTv8(PN|@~rA@h1f;& zhq-l|`1#==**vW0KJ|OsA*T8_62O=sW*XR;{pR<$sU)a8^rmG(sqs1Z|F*QG{NjR+V|QIdC}?@<#Ge+MExvgG?; zoisYemq(H@JmS9)F;~A&KY+MeQ;F>yy?2Mt%*q~eoRl*&6y7yY^vg1&|$y#ou*SbkKUWa*KxSsV7A2I@*UR;cYfyjqRRg|DD|9D3v` z;d|)hEmQnYRT>SeKNd87?uKX9AfpJXT2dw^DFYu-hTC8;1yL?D&ukv()wl;GU4{YH zdmxC{sB7UPGN6PsSHm7!Halp%#;_O7G!Lz$1Uc0J>jy_+OAWv&3N8L&_dbbOyK3R9!8PH2UCm5K_m=3eS4Z;I`GRlCn502B$$1J>8b0F4fQ)sa+(k&(3y zgE(D+h&xt`ey^&2%QR|o2TQc<6oUHHUlFj0i=!`c6sEkUlG55cnGbmzG5RP{WTO_O z0X5gjEO__gI+l;OlYkM+uagF^&*)K4Vp`aFDnh9Hj1il z=yTFL2A#zjDpI>&8VEElVVjx$Hm+2GF2uAG#jNff+>d z;Tbql^>HRbjkIp4~nZQCWM27E-egKm#? z6O}$7U>Yvu=^N9y6#PT;t`vlQ7;y#QuW0IB`yC9dIp`|+`|Y@zHC=T_jJ&RnfG)Dm z7p4nDED$y=?s#U6D4Y7*dJjYx3z8HmgcyB;R}}cW#XLwfoLgB0ch-e+9`vekK;s<5 z+fg(eKpLB5@tghT_jgIwmkqT5^X+Yn6J*){8c{F^&Z`}^YC#?lf*@IOorAhjLp@J2 zu)f9aL=nRY#?B(vFaB40aBMM|9q7!iP`A`~6DAtUiVS*Fia`)IQq+rvVjuB39XC(v zRU$})g$Z(ky{?+qOs<%TG>uT>Y`n$Cv&s(kEr{k8yw=O%X8MVJ$@!U;rd_l?3J9OQ zqCx&+aHg>5$sK-)!+Q!LZ=v^_TJ!XTrJ8z-D$sKjT<_&VVIId$q*CeC3Hah4}{JfniiX@iAW`rj5=xCVzc)c@TN#6 zVFkJ#=WigROGPP)8YA#!ztS9S>gHzLMOdvS!6T`Q-T}9*IwaYPihsB>%WjrE&)@mD zTRn-+R$g30L&MMbAyjd1ww+v-m7;hdmuFyMk!K78V-_%ZL+Xrn8+)TWn2iNC@5Qm>=!j{A*+Tc`W$Aj*MYv932KStSou%+8^R9+UE+cIu#?1EH7?I zSdsKs!Jc5j#+(90v@Y2Qvk>-5KJbeUFg|7+w&GUR=gy{RhIV8Zl>ZgVW(K1ix**x+ z-b(GKVy-a7Ue5#0_6-FSm zO=BWyL1IP~+sN@6Hf1fh4>ej>r1vIegS&PeSa^wNB?uW0=aCWFPe^(b>+P*mCg&cP z-gPk1o0t&Wq1S$l0ecWgD_aLf3%ZIASZgbhW}OQ+?4a_jHD@lWzcN7Sn0Ip!dKTcZ zC%|>-I<-akUsE7pq0!9Lhc*(n0$OPtd5`VzVLyA&rmA3G*kebmne26dWxa6zF=*Tv>Xh>d7%gPGijk*`MF0bSU` zJ>3u~3M6Eex3Ox#K-{_FlIg<|oZ(|ci!~$!`wdyCnxIA3cr+C$ItDbNt)a`{bj6L$ zRbi;`43|?pATr7Nur5r5@mk0k)u!OIpgq&&K&pky&;vt z(#70AnwtBpvCO0j^u9Bt&4j_2XeT))TjRS#rmK^M4r}5|8;uhcn}QlJGTmObtZKoD zcn}&!#FGbM-7a?xf~|3pQ>07P5I!a-Fp^)cI|hhgPyzkDK^yYRnr@x;#yNIu^>sz_ zdz~t*&y2W^D&Cjwk?@@lFlLK`C?D|6Czonqm;Oc>#aYu2vCbDTtwQuS^rvSvi_LfqoU5xzHzm<>) zT+wIfAU)9pd5sRL+?CCuif{$kw>fwF7uM|60usY!YTf}kT0-i)jruz2q{b1@>L z9bjykRiHrcGPr$lJt5g(@6!+G4vo#p!1srX+?4Xh3pf^dw+ctDat9Z2Wk>H+X=8Tb zJrVJGxqgY?`}hm%ZqN|B7-=M6J}Q8X%AQ6WxWvT86_JUA-fn!bd8Xc>K}=$5mCUgm zf_*rr_I4FuSZ%XYL(@Ab^kaL$9-zp*z(Z9C9`DfkMtZ#jevEk2qT#MX2btTnVBS@? zWP@*Hnr_uodI}<^5&YAC^Bs_1dIcgf63f`HMEXCT&c&bU|NZ~38HPlOnzu1Ey`4%9 zr8&$v=t|>+!fhxRs2h1cC%&hk`t1^GS_C`%q&y0gQ$-dqW$<#4Dvl2058Ssy;&I7Ay9W zZo+}hIj0);MxR5=7wavWiFIIzuwXdY-3USb~uU)LT)8 zTX1Yye;R;nKvSsN*aGwlP-fK?<`D$kPdq`U{o1D1tQV`M?}~}p-jjZngm z&WoM}w^Ttp8wMPhf(pf?6&haa|2{jcgmGJ8&| zbu%Z(0*h2j>0%bEuyAnzkQ9KKY$OXmm7ZFK?`+&4CCsEim@x?n~}NbzG_9p0wH@n28&U5)#*Iup0zu@L7*Tq!Kc- zbHhMa{t>%l7Y4pG5|569d_DV|#vp$F(4er3ue}z($B`*RIVPp*ciysdKd1vr+FglD zwVEl*)$|;6^TPT+iL33_hi8q1-@uVt(iDWV zJg4h%jA4SIm^XD7bhPagPA7m4wvP4r%-*R55Sm!dqTmzf=7M~|nJgyA^d0%sa@6c3 z26Ruvo~^yt3WKl6CQD}~^JlSbMP>A%??rw8FP4f9(+3AwIbbkY z3`ZbjMRWx5(W?Xn^qltf;9Vq98^)cNlePG)@J|PF1%KH=-FDgUy3hymy!p1u7%kC% z<2eJD$=NM?-`!6LPCiwDy&QXlq*s}Lr7J}WuJJ1stKzI8e@30`8r{Ui$jATbuNUwC z_-oL@fFQ=4!jDiyb`9663`Tyr@Be@b+N{WL=}oK&1q&;|M?>smp%Hl+C%I>@V;-fZz6k-TwF={ji+gyvr85Z@as0 zwkYqDv+INK7AvIiq|{v9^}oAb09A+4se0|1T)%{07l)dt*z1->yO&A4ey4XiC~L^= zfHthft$bH#C82Z{O59>F4&)}?yq|rO;eQ)L)5KH7)xU}Bc#iYWDtIaf3`&5}8^X<3 zOKZOL(4$(r#dVm&$z1Vf5$D^WN50WVYJ?XKek;4drB`IA2%Io-x?Mm~4<_EaOf6KW z74UEXPdY@90e?bR7VLP<>r#Qf8b+(ah^U?5Z)V)ioJvys)uCW5H{yu34UZ;W_k->_ znqIk}XVFa*Iwh4v0tWAy?&5oIrLsE@|GFjUPQ1_L&_!m%be|te{49_wk@nz6NRn9S zeBDH@K-MPH`pl-7D)bCdLF>+&V)R6pmD>t>7M!O>W)5@Nzt2L8*TSlF6H>F=z?70% zEX|bDdbOgCS77LXXRvSNgVKTAVqbDw-B}SG&<0hF?pGe^xi#{|N={93733psGwy`P zm0sKz>$_HIE$A!wYCo`59KD5Iu&gO1Y!qXC?2iGW6VznyZZOs(#FJehLXf!C#nY-4 z1vrI?oSnarEo`8wz$-f@LD)lfy^Y6dXIg6rKhU0o9t4&Wk~otUOje2SATgR=0J5)2 zSE>(wzXXhGIP_lbzpjc(EaE(NJ){v&Y7Gwa>C|aiOoECRINW%0_lDqYz{T?pSyIpD zp#e-yZNZOPaJC-tvEnC>SzW*`6@l!)4p|jD`f4-S@cmi&3&oqA7BMzej>1F%LgK#!1fp zi0*o9wD?qM*Cn%eA>~_zrZaR$PtRBes{AO1ZmYe%1BVt5hImt(%-qi8q&_j{Zr5VX zE~pH@H(Ii-GfUaFTR9A?Er~Jh(vg5W`G~^B&uXVA^*N>x#;sGMNi`apwJ(Gkx6Hs)J!*kVNkL(CIj93e}4SL-E$${xpKdqYfJX_IbM1pY0Wb74; z4s5fG`|e-o!WKec*^h)2Wf80C8v21+*}3m1Z*Npr?dc!JL8+V6F$%+Bk}I{w`t*6~ zOVrWY& zVJ9hOj-PpV=s!TkAz}aOsT7v)>QEQ*OSRb+KgcK#x!C%(q79KyD0qq968kIYV!wy* z2j2i&m8r*K{|pw~6Vu z*@-tsIeB5Ot97%Ncei#L3&KvjKC8W-AtXCJR8kp*jStsuKH}8^b^A9V-XY3|^KU$UQ!g z|5x+1G&@P;Pq#2!+}<+F?_7wYAi~~oH{(NA$BxV(*P3`4Q!r*n=N+`i;0yVOWG?&D zo=r;F*N_mo9UDb83pX5Xr2AR8`c}e(2w?|XrmD5oEG%dr#f~VGJ$TC#9@WC@gbmD7 z_^~1(EWL_=*k_*qI{j=%@Z}RfRUI@>XSkx@zF*mqogJQ`P3Ab~^@g=0)S94ecsV|5e%rUr z-c_Zx0q!t|*tpILJ;$LZ<84-VOjk=IM!p)Wu}Xu{3-^=SC;e-zP=LTVi!EQDqFGY3 zeDMb-*^!7t+wOD;Z&^&T=X^d)8gE>bKN;gfG6xldl0-TYv0;ChaK66#6Skk_r5csi z^*8JQE7(=DWq9~QSq6CD`-M6rL*w*efQj|*u3IK37n`4{fAKmh`RyE$q`!?H)7rZ7 z`>VN+!KsJ_IFtN?RoZ`g^!QU#2v@DB+PM2{kkp_0I=U2$t-q%`1ZA_ zUAgG*%RXQ(!}F7{R-DKkPG>b_wAbyVeN2DrgiT*&k-aB`x#L%6y;@|mdN`Et z7X8AVUB4G(BQ_s??sxO8)1Cz9GGo{h7pE+Ld8D)UaDHUi1I~N+alT6$weRP~ZPRLTBs!@OBQ?KoteEIR{i1)0NAFGtp!ccQ}=GPN2_!NIQ zpm=J`1A$MnxF*)mTgz{$#mq#u3jz^`dh*8T`w3^vDvOUM+;xy!xIdw9tLtXXi4X*j zwWcZeoduQm3VmtE;|IIcapLMDe@r`sDi+A$(-Pmm4N|CQD|>zw2dveZKwVkyv(>-d zc;_@6-M9E!`gAC_+B`w!-#a(!Nh!mrhQS1^C|y zsY5_Ae`a6X%X0q@T8;u-!2R(lo{lrMJ-gn2FuNcH(7)?CZ+>m%BK&8~dfhT}v|4K* zN&Dnw+wod8ohkzL9?0ajeXHA` z__`&ffgv^Q1!QmarK8v0oAxCdE9TiqNkmDFDQ_p=>3x~7J&Xv+1ZtYqhhPPdZf7?? ze|t75wmX+;+Ck{M5c)C)cxXwxEu6;nPm9k{s2cU5U?-&PR5ST+WzC zeR6{VIT@1MA`VZM18`z@2B2$`q_`kc&b>QXf(lD%b=rQLlO#;EuFJOS--{}0eL{RG zwNF4ymweuEvPjJOIf#5c;`IVrsiK)F9U}2^vl{LWkc8>93H1~8c{vbO1gFooNrdcGelg!ly-K}wv+TTavI1nbxTs!$}k(gQ+eWqKl%k8XFUe^TTTMjs;#~&=QhoSd;vh54fwN7p$*vRFeMS7P5ZE1bfPlzIVQUN7Zn} z-bp}EXF!`aSr9PAJi=n91!4)TY~(ORhqrlx$t(3+t4zkP7}gL58n6=vu#YZ zIT+S!tNR}fU7$*~eq@Umm=rsjiyV$Vp0+nEpiOG6}7^Q=YfmZNF*#+hFtklDqpRga4JgWC|zga?Bv^6`$PA z!r%45odR!EyW{xev+0kR)?E3@bhRxyHb(BS^uv_vQQ?eZB|ZH2Y>U7(BzT#g#27R$ zg3lBmNMu-ck#y>44YzH(goGxCpotrVF&Q^m{;;|RZK47z+V#|m9j?pw?D>Zpk&fU% zgD?wJfsbnP=Z-#e9w!+p3ZSj!rszq}o=X2RM?)1VhUE;uzsvjKboFyfp<0t%v+d`9 zFctj|Uc`Kgmbg(ppk;q7fAz5HP8IKib53pc{{ef^faRntS7yu<^%0{oGywEvUeBsm zIbIID^_$S3RlNJN*w?I*<-KGAYMfp@Ymq%Ns1g2DC@8^rnsF5Q-^f1fR(C~j6v|N+ zw(SULtsR7t&>wE5I7**Uz1I{W?w9a7f(l9}{r(x1io$;hKYiMycU(NSFueN%)-xql z2595WUewnG^~#4;1Drx`7Ej%BQ7Z`zQCSIN1xAt5Ntt8=HTZArAkH8uW8e>*3iS}( z-2ESUJ}JdD)7~iyIHf>s26LtVsq2VH2M%V`#A~2tX>ALC4o@^XM{GDsWELoB@9U~^ zYfmXEjW773nP!y_Pb!tkckpUd2O--lImCYcL%ga7$_CLA`I?}@k+kzh7I#lehlldz zzEU+RX>$-EXvFe=;pFhho;g{05|uQ@p2K$rP@lIMd{&d2zw$ZEb~pF}rPSwV*hSpk zpPG;D`25w0DDmYDr-<<<%uX)=W*()vQNw;*`K>L3J^``*nfat0%%m8=XxNBuNO!AU zbK5&{D8fYbMod2X@&cJ8EjpNmyARF9fjn0X>x!2AO41b z-HeeDt?&JecXWFt&~``B2s2mZjtRwqEq-g`j5#faU! zbJq8qp;r2O&Uxpf5@`E0t~KV!T3K_hSn26-+hYk-k&T^fQN}d~nUG||iwT;$&PgAy ztImi26YF^Cf|&PTcJUR2&FS|B)e*)NW~WldaAahhSAy#eh)(8!i>d5%iRKVTN~Bc= zXHw-pu2AEC(xZcGil&y=#2J(VnZE`Bxp|6Q|6*h&{>gBc0bHM`J^Ch^WFhAzC!~ni zKDula$dNr{c}HGb!sZuZ)%D!HPYo2r$VM6p_02MH4p5&bsEZ>l_cg?V^Xhr^MlFVG zk%)kxJO3>2>rHu7rviLFfX^P^5^#QOHjZ(TA^E-Z?AJ@cKmP*%hMKsd6s-SEI1zI# zd@KAi6q)YowBNVEd5Dk**k+f^ROH(Sgj)t1YW<=uUM`{U@kO9+2^%&#uFU!FV!+Y5 z+@JbKww>>e%|03p>dL{tbv5{?<1cn~d8h~_YC>_{x!c(cuU%cK2+VWHb*cR!x$D)O zKeS1kvY9cgz_Ty)hG?&z*%`U&!ZZr4K3C}$aE@oc?l9-4vBGD=JIL4SSzfpARCkVhvHW*4w+Ogh^T-I#s*yZ1ANA%*qWk1hQ9K1Od`DmwSUXjX>U~WP&_I%Nh2`$d_|30VrnAOMv6&`SsokuUPO193TaVb&-tx| z!a-eLVT+6K^rIIW#{vUl$M)am3^c*6CyV)zX53D>5yTP!(QY^ugUu*#m4Bjvbb9uK zOLY};h_Ft~kgt7JU$LeYQKRzY=dFmlPiCfdpCDv3 z^+&VpV>6lMV2RNc%@KBVSn)tx?(>NDdf&ZpWBK)ugMHOIP47O7c?{$)O@eyM7IR5S zhAOw&#-;a8d)#t@iw+9%c}pGlUUMX3FBqB78OBKYK)2Ra9#k#%r=I?8+WF(hQwD#= z`3c}jIrNJ!)xbEkQOcWzgO!}VVZt$%*3*BUkFS8FHet3SyGaq&ET@Xn9OBfT%gVub zYLAO^^Qv7^sWt|v9^i)6df~tY5`8_scsPqt)+|F$o<5M>IS8i&0os;e!tx@1+eEyD zk9hEhjFI((fr!ZQ0~wI)H$|IBGSW#0_veN-8 z=|4YucT>Tos7>;f4Nw-|p>U{`ij&iK&obYZ;s-6Y1ZiWC7M^Gn)ymj>ORdrR<`1m_ zXN58dUn;1e2y<6T+A}YjP)gWf7PV7|EQd$dh z>ba)`XbdAA8aDc}c#}G~!UW(T;RyF{b{9qk+=H(Hz>`;$I<3_buSk~`PxaZ{>;(Q5&CK|niyIPL*7JmE z)Q7j4P=s4Q2uI>U+PaRm4fO9^QI`e?;u{j&*C#c#$f*-6pfEH?GPaRW!=FF3vd0&u zwZ7`l529%xx{)359%@D2xSRKqy5Md9{`Dew>m;*ZMn-^_pF+xlXdl<|RPCt|GY(j0 zC+t}8dSt33!y#QT<1A20#+R6o0iWRM!q4tmUS+o^V%yP6p_qdrj>|`5+spmLL=Phak(`n;BbkG?KV9!=c(ia=H{S@N+6?6nc1;6CW&kq zL4;XqIwt$Edm(VO)=kPqe9Vt5awa0oA%-AyCDYdrOA~u2U|o760?4` z_OM%waDTi0oFFM_Lw-c6M573TCa!VXAMycN;K|?iP0EvyCn54F-@ue)L8C_x(7W2O z2?94#Wf!-IplMoa81m^%CNvNsg9R8pE0Y^hIl16cN%mPATt#-Z-3W%*ySD?*!c)cY z-I$8M`P>>=nqHsY`o#fyHr^^2bD#u=7Rn$iJC%u zYrnkTB%l%zapTIn`px-KDK*37J1UjL zva!?NBb!C(+I^sShjWeEbOUWQ$eD%91EtdOFCVtTck4+Qj2!m$dz|RNcUWPl;BetM z#8Q*1M=U^dZ#ZOp$}W!v&1omV$+i81~RO_wjqd77GaW&bdG?V||I~B1k6HR1n>YLXpDL#BO=FLNQ)~ zcfks`U!w{9=u!;N?c_;_tYbuVFF0e9a(UL#bbo||I&P9uAZl%8)?2fBpnh1%|H+Ak zfDm95FiPP(+ZMrMlJoy3u;EcQ>=_g@S~!aP5xOMi_u4)!@r9Z9Av4uGmSq)CCo6;GvBF`eJuBjXTlh=IL`V?z)18mQxp zYI@eHQL%n71)*Xo!Uv11eG#q8gNsRfR^jz@SR%I|2uFU4I+F1_JUUjKYJ0F&TL;-Y8$j4@vhzMNs*(KPYw-N zw7Df}@5Vf$NGi5H&;$Z#qXhn_dV?+_9GfgYT10BiTGsoAiYdu(ibn^8yS$cYBw-{&b{c{EAgLHXX1|7HnKXqwP$qVJe zqjxXx5+%`Fd*-C~nTR5fLQwEO2uBG+B=r0ulF|PGgy9R_b!tzt=E#7=H}=H`25`p) z&(QyX1IsB9(1{^1>FSuITezAM2VRFAI02FU-nado`?}p9N zYZeVo?C7ts_U;qJlDSu6$A&DO@=O&?pt)c;?iqF#kybQ0lG7(VHlU0~=KRz?ItBV& z>}ou6Hw!qQwLue2_=23v7WGeOmPwD0+SBy;I>gud0R@gE1ziLPO%ry%ulMJI_wPpn z0Zal6!*#V#dj-y~{|)ycTt{1on97^b)C2xGTB$Dvq;T1FQn(}QL<{37(0A~f5n<4x zCAu$hYFS&Li-R^IEv{tvr$y$sA&a?tKax1^poVM*Me%WXX}okajI0u|1FBOLFCWca zxv!1UUXk;;^TlW_sw+4v$nr>h<3fx^m_2S4YbodfJ=LMjOfJ2 z)1}9ai7nLxbkycZo=S&-g<4Y*1m_Ccf54dbk#5Jpnb{(|sFApb{v39( z)PAr57RLQTaKKjgz%_MB9Z?`_F4$7b1x$mVQC%A@gv%MIIe2Q*FVZ1AFiwJ)I0RbG z%H@=j<&DZ(0e2a4#E;IH9yMysX7O|LFQK2>I>C)Nh>Ou)5HtcF>M5%HCBb&Vad+V% zcK`|v>hVbWPY7Aza+m+r^G-+QLR^5kMC!`gCP#MHyj{(-TM{*Q&lEec8*7pp7Wq2m zYl26^64+QSJmIRxiQ_kE!};f4*R{D3{76{7#B`VK#O8OC35y1L@Kb>INDTY=Zg@e zz&n9s{+IEs4%tdMy_xqx7aiquE0(I6X@qjscm4?&; zO&ZR6%UN^en;-afQ9wLo>2!$XDp8R5Bg$3 z{>$3Dg8=#3zoSx;bc}GqvI%rtu*%#K>y6qY7c5truV)j{z3&5t9>%C7V=pY}&=2fm*eq4DHs5V4NrhG=6cj zDN#x5tEUQG)PC0;BIwn!^hHzSVBalFu{u94XA#U!=u)O63gG`5^Ldv;M=(lpj&SMk zvCD_Tzoslx*x(Rh_!A^p0N6h{kpsX_cZ}lYeDGD9hes-kQNy^N zR0CIA(lG0F44vmznuwgsZ53bJ@y&%nBY6h?) zdf2j>Ur0{@?9(~H_UtjR$Gk+cBLg(jw-pmN{3Ls`aE_~Y1<4G`SgJ@tIfPeO_7dc?91Q~#J+ypXCs$%8v4f08kg&*+0&L&moFoq6 zc?3inb10*K`W^HBjoxM&>G#@22GA+U!}=7?%{wn@M8#WrnBZ_Akl^TqIKZ?R0a_s| z##fv|Wx2nB<^#1hX2N0BnS{)8sWM}3tnn^WFF-7n8-b%3%Rp?zKDPLSjcyMVHnQ0I zzY1-gD46OLc?u3*QQr-_M&11O_U{uo!1TS7TG{AMMW#o?*vJs%K=w=RR1i~?R*I<& z4-sr9pn%ZDrO-#TUm6SGV`ZgDjphqEEks;8#xs}?a1Q-S`nJgFM~4^8A^aKC zDg&h<4tx|y_qWF_9zxiMso=hR5Rqfjo_{{AcdaH*)7!`ZA;O7!vj!%UJovPvF-(jY zK{GZt3ssemIivre*$m3Pg;f{GLdas!i6QzXieZ-j#G`4@hE^#12Mq;%{L&+PxLpg9 z0o6Em_3mxJ5#22THXvN5cbhFD2GJlcWwgLMMyeQ+y1$9+&F3;kbK;3XL3}_?R2r5p z&K)Y#r-&lb;HJ58QQW#8-_#Z@!JjGYr3Y|#dKgHLvc(^(Tu2qUl zcoqZBp|xt44XeBgf_+-sV4zVD3=J{KyncKKZ!8Kp9#3igJ)2RWcp^aoljARqiN^$> zyVSi*C{5Dke6R6D4jsmlY?u`qJxIyZN{x#2vLuAZ!s!eXzN>Ei>vLPo%_0tdt~Pu3 zE;U4?tlni$6ZvGy3P~$9$a_?lQUi8q>zO z9{G0d8wWhr6yEdRpuER&=LF=2J~VHf`BL2>9)HWXea@jjr@#Hr75wS}T1b6(74W=lEn( zTm@_aSh;`_wQq!tEr28TqM2K{Cu#t1sv2jQR_ap;FJ*mx z$8O;RjxBIYM-7B34IRjIDUA|Wq{73Y!->Sxya_327Ik-?AfAwV!T3NOw>P4Hqz2oO z!!W_DB@xhtSsOK+m+u~e!;;H>u%bEKZm68GvJH$Vgv}G~l*Y=4eOh0minp|92$C`% z_JFl$<44@Wet4F-j2bxAREi_|gw84s%)#!K%An!eK?|UxDrwHU;VF|e&G>w@wmmVB z_V<1&F(HGDQ4hjj9}_jt_0G8wY|5qIrN$Pd>{t=tfXY+q$gX8_IFFY}8GNwm8jA2z zTDp2hhQo7b0?@>dB+50-SA0r3_4r=Emc+~Ab)A`@wE?vv_py^+T!#?q?cU&1Lg~-) zURn|4n!>V|gKTd-ycs9#%eg6$Hefq1`Bd<=p8+;lWUSKbWx7jRw$0;UAiTZSI8t0| zW}daO&>rjBuEzo#*G3r3Ly_IQwSh_1jI~wK3)@_bc0X3xx6)&Rm4oqB>S6X_nPs(wm0H#heH#qL z+{IqxPP_xN?)CG!MS?DQ$h`TfEp@WXOAJ2e&9Itwda$7b>+R~u@=jD6bUin13NDno zhD@yFf}ANL#Sto9QZJ2Fvm9yvn`yGxK+(#1(U1Zu&8u06CsZ)Q1Z>zg{_U|#7K0DY z&`H>tEw-y*&xSk=)|FjSK1A{z7U?TI4kKZnf#0`f*%O4=rlk@=29| zmolBC?x*Q@aaF{YmjrR3jEM^lN9rFXo`R)A;m}CfQBv2t)m9FU1%&hDu2rA62jX$; zF77@Qm-9N8ExWA}`bKEA=sxd6XhS0Aowg{#yxYr$&YKc79(3H?J@EPsU3VbjtF{D4 zyfBIzV96Z&_q$VDo2En%eYo&ZhnA@VL<-@n)d)Ia6X{25(_j34pvliwKuHU`Jnk#KdV2M9W&9aR zZkG;}eRv6YJPrTipm(GKnzq0(J4kWOKNr`-!U>*hO^$-fw@y;s)2wW(SAT0e3*cLk z7K}lLIZB4F+be&Okpf0{5fGC@PUWW);7d_?ZA)7A2XdFQ-&`}Wzv%YT$#+5E$B`Wz z@~8Fu1JJbaGcR0`uJMrv)SdaiFBbZx)@xuHI-HwOs}UxzeOykyrv?xAoc12uEU`Fe zR`HB3ou)Q9XdG4G@=-aW$(wi#w6^ye%ke&uRz|9%txP#X$w#m2RXosX6q-_QNijEnF8sPhoP|unp|w8u#aP?hF|fSSmp`lm5^#l59wdVYP8&*`L`8G!=7J@l6q-sOVl!0 zf%?}tdnZ|pCrmOZX`DW?S^CD?_p+q?sXfF8TUi+W&$J+;OWw}rrE%uR;yd|X|I_ zI2dQ}@xPNIsLu7+!I=Tua329n2$g2eG_b7$$Cp4zgTA)X@Ea>bEk~X?veuQbs9k*j zLs(u2MwbidHaLEt9Ur1ULB9^OgN5xnj7!aQgx~EI>4dHwLo+R1uL?b;`I$) zJ-XP}v$^}$Uq3)hj3z}8P(+J%2C|ADp8sWdK4}4>o7Wfk{)<;rK+MM|W)iz1ZoMqJggdcgzc*lW!rQ^E z8uL#u${)P06)NrrrJNl3+y9_%;b9G3In%yI3`S@{wa5-V|-R&YKk zTX$3C=X&(cS;vo|-zw8uAS#OBwS5?-b?GXVIuYxo@D`bbKi~@2nStK?58(WRyCF2H z4B49c&StY8J^+DuzYm^KUus0`q#s%}pO{xHWvhHyn5g)J-t7udn-i$oqWt-d|0xRh zt4+M{$>Y-cwQ;!!^^k_<7b7BD)ISS3YetIFQT{4|`+vga7+?kRY$r%NwWbvDaHb`C{DG#;fdt0#olD~3ZH#zg7R z55MTu;n@KcCTKjBJo@kH8Gng!OL$p6DBq49=&8^atCdQL$jOudhw!Cl7m+CT_yaNc z1z@d9&h*Fq>9$rNbU=>Rk13~)gW~Cu8##wnexk3e+ik9;pxkL$0#L*ngSc7BlUjmo zYLLVybkra(J(x^;6xmH_{tn>Dhf|~NUEPHuhni2Mk@Qj*k~-y@^SR?!ahXhIfh*)p zxZ2;_tGy}j&5DmM9?azvDaIQ7K1}Ude2cRdD($)oS_R|AGHk0juDc~hm+OW@k-4-z>j$KF-ftY54&LKymEfyWU@%dD z=6-@v`@i8e&m-N>Hd4(MO9u?V_g!oO^s=O0U5cNf@$6-zPtFhB3r@Bu%sNDoHEgs; zzrGE=!o^=F$?uqy6yNCR_rY(_d|za#gK#-?7)EDw0>RNuZ`B`USK=R>iImKw!|nOQ zKedW1jAc}BXQ-H*9+>|M)b>zKv2tULYna*O`&ZrGq$NH7f4OJ#KhJ)oC1ffM>NbEo z71?~LM-yES>-v;Z`~Y|>ZE_+Ve&-Uu9sgA}eZ=Kg*`xGx-3lp?Z{-5BiL`>7&V27( zX)8qbkNNjb{r4Ye46SfRPt;*Am(hmF=TPwKE(Y?fVyK!LO9a&`NsQ)lLQ}Uv$7Ie8 z%SXX#Vk>?%eW?@N`V|);=61o)vWoAoCX3jT2^;a0VTzScvc|Jj+hdKMg5|;)Lefcy z2myaUgY}mj`O?YH=tKWg6$H^aQeE)I5KMpGFDBSUoG$jogmUDGd`dhyt?M>rb*D)vwre^Te-W_6juxmG?ulz>aJ&;t$uH$<=&+D z?m+Gh$ItmpcYQvh&VXJ}Lcw*P-(MBC zDsMi8+U2Q*ttEqn-|X+o{={7&y2X)v-j70q4x;~>tD zcJOG)c1ye)R^0Dm$a#ge#(C`MJBj%(gJUp8R*=R#yw|jg#!}L8~Ln%;-@k?QV;ZxNdpM0i!HZaEUhQJOBWWN^M zPMmM*Got-^kvZ;#Q4i+@QND5vx8Y!?0i7j*l}xZ~iI7h#xe>wYBaLVEP&o)H4@idM zU!GPtQi&HldTTcKZ6)Q;cbmwNXQ??Wd;5Z}CFW!PY03-a>}uNB$izF>Q`bEcCvQhd z>ekNt!B4PO4{7Uk1OTZxWPuKpso%^Ow5ktXo?zBwPfi715fH zo@6EKdLT4x4Z?5@V$ZQA#^mvLrv2V7@y-gZPWyQY66^~#LHAD>HmFu_3mJ%JMlZhp z)fK>gXDy%U3s1U2Ci1aRQ-Zz48C542IU$}|q(;`l=;%v4<*3G&<6aF&k#Bw$qa$1NJ?5rSqPF z4*K4Ee&X-)R$DjDJW~1MM7RsazZwIbfKk0N=35EO5s6xrn3i|IsQ$9@jZ-#qbPt1p z;U87v1JhpzE~mD6+^hq=dy)0F3XTo1`+sIDRebH8kBqG6ep%48I$ia(xi@S>6-`4! zLGt&k;H~KD>4wKbwntkofNJ1M_9M^Yfb_QsY2FRhFgNSlb`CGB>_j8icd0$=NkgGB zvM7D)_1uxxz<@`9nEn^raGpQv59^-PoOoU^5qKy8>mzUdZWdqN%3%52olx3+|G9Q> zHBogz&;i}=`Ksj7$Hse}`*l>%m}zQeqE{m`Y(k{QN4HR_6mp$Cq`RH1G-~=tyeP4- z%mcZZ^qZ9e+P`$88b~mcz8u%<&m)dVFyrjbVHH5~Irw@v{M_shy#X4n{I)KB>Sq~nu3s_NJFO2N+_z;UxONg=j_;BnJ*`qP zm>3LbKLBq`qSEX@+=qg@S##3!y#Z9?oCDX9=IWEfPhvb~B-eYWGspl(@6Go&Pp;cN zdTM9kaip#R2QD&M@3u4gytOucAIeuXwlp*npCG&xA;m7k{QrI1KVd0xKXXh?iQhvL z)TNLfCr)+tUd`n)+i>&>WoTHT@*#Jbmg4~=xoL!~m8|X*;*EaNPLz(gCgtc5RUH$KNkHD;9FosRI^Ooo{ z_>G^>2H|@N3tTQ76;n4zUPa@RM4^tdAqyvgh3Yv!I1P$1#$X3Ul(X}kiIJ}Z&S~8v zwInoMBM=f_TeWH)JC);x-xP+3cbp=CbuGkqc?3GyVzf3ZbfzvzR6l*q%@jS6pLp33 z0p7|i7E3=QCLT}KTdqj}-LbSoNfY_%`C87LR5kHW-;OVZ^DT9RJOmriPTzags)lMv z87Y5h2E(41?^Ug*WkE)ZjQ{SQxpgbWl@176eYp1gs7wm{w~pvuc-B~*;L~-1H=i{} z8J7Wm1?-DOtRgb~8g5ziBsHO(MWTE;tqq+hF4 z7GPp-0N)!uzSGZt^!)vtK|h$>a;2{rI88ZI-+$r|3l@%CcK%Mnkc~Vgq-0sjNxzXS z0ARWV*FQw|n_a-&S1l9>%b}6JTfKO`CD3TRF~-+@rI%S8K> z{svEOoJt$rmC3Fx8}NwDFq;f~6{#M3z3rmo|B-a=@l3b>AOEaj5?e|&*-ZD`Id#jS zn>mb8A(dm&K~YmAry++q4NvouwP>CWY*&GVDDRKynX16nQK74;ykKey| zFrQt!uJ`qRzh2K*S`JGCLzQ(M7ax|DDO3D({ZBlCPF{13`)fdagAOU*5!op!iv^W$ z9pn14I%2ds4DRx~@_9y2b^DUUrQ7$T3UwCQSK}T-*9-&p93Vb@4GjQrOU55M$uf7J zo%o&+Ui5f7EUqu}#UP&w~)`? zRy6q`2Vge@3755(x-NWLS{S*cgj45X?=HXCYW;aqEB)==R0m;l*WC5gKa2NW?z+2> ziqg~lQt`Da-^9E5v1zMrT#KTB9-K|3erY?l^v9v*Zt`*`%#%nl~wqX7T-Pel2 zep9kBt7l@Ut|!vw>!&1#HGHo#xw$xIAU&xj(aP{}C}(5)GJMY*^B%Y_%2{@uxs~cS z-`t4LttBIrd6h90H+3%z_MN;DlRVelFYTWdEf=+8&b8t2@LSRPh4{)Deb+G+hhr@Ch*WR3wfilh0&6;xE~8q8gsQ_ z7r3az#leUBO9Y`!!nV8}4>H?=t5$*n10|zMi~sof$WQo5j}0*8Y?0{P#E&oY%HRAx z*0iXFS!DE!fSFy>&0kFmS5^1>zyI)G9PQP~Z6Dct?w}P4lV$_g%70;DS>TaCS0=o; z`8#svky4-zRj{G;bLbmN@OsPqRcySO;iLUUd45Ywxj`eXrN3KycFi~=lMSy)~QC7r@ll=$w0SLJ)HxwKe02|5;t zI?D-j-%g)vmJWSD*ky`NjK8OBYV^917YcbQN#TTes!3lFjo*_g zcWaapb6Jm?cZ!c{-2rPiSqm9HQ!T0tSHl{^`2fB&REv&FC9F~t_zEy9m!Z57MZ9t~ z?l6DV#nO_6T6R_LRqGc&b4ttAsWEd*6q;=fP|hUp^$0S^;hd#eWVFlMu1U=>?LOpl z+%qgRq2{$Ec4mUWYY-P%cS6JiDgaw=Zb!NhPe+D}fjsxFbc{vix&~JxbcALq^+yVu zAZ9RvDxi^N>U5$i>>uh&3; z=!`t$NmHd4bYviPGCRhcP__0F*)T?4qBYmSBOPBwCdrAi zZ*ip}`JTQzKOrMTz0M!<9uX-Ezc6x(-HNiV1Po~BBfFs?l3mx3b~r*IF~d2eozMK1MqEYTXGOeNdDD-ffFbD-U(WH{A{O^DS z7=I0cXZX4#Z)P|13g^e8={Git6WM?-4AdpQ0OfLIe zBMF@TD(`U?kTmpd$7!263{WzbFu`;OiAxYLcmsqodA@ZzDE6}ES#Ux1i0;&&BbKY% zPyBk?2a5%Lr-K->Zil<7B9~$_q)DR+o&nc8dfgz;?y+uV|FTzVH^7 z^&`8;Bmv98n|^H@wP=#OF=sRVq+LPx%4r#Ms$7Xkx>()PFX4q)H4>E6N!GEe$z(Wb}xF(ZP#C84q)x0usF?Y{BHTavz z*u@f;2?nv5CFL=B+zGk884EkY_1z;~`+$a^tWccxtiBA=u@P2vJr3LUpB30_aUW=^ zT9r#4IC2kSL-TO@PJ=hwd02wTZgefx=;s5u<#fS&=y<9wmlK?Xtsr@Plx$SagyN-$ zH^TlYzqwJI&%F`PVcFxXB(t7vdG><0TRSS zA_+@JYG~#)4y|?|lO7}~z{-03n+Aq-c&E;sR#S_IafXA%z|JxMX+yqt-rjeO(sg_F zA|!Yd{s9;Q_Oqftt;O}CE?5~gKwboR8DC_#o)5FLikwGuWzA3X5Kk`a0!kCK^Nbe; zndiRHg!fxbr6*#oDN}ZMRbAh-Z`23kB3+eTRwTu~(~yxHOEPH^BlkY#n0y=zSos-7 z4a8rw$B*{|sR8bR)`UWyq?OTSgvG>~11$biTeB`lmPd5u# zA|TSsVMW~z#e{6E%RtV|A5+<0dG@w9;G5^$se<*obZiAPZTq26nmM~t%P?@5mJi)( zf~>g>T$wVy!V3i*L{X=O8ole4-m7c&gB(S`9GJIB4U&&~(*a$j!MKJ<{puh8z*XaU zDpBv>t~qm7@2Ft>U^O@&y(dQv|1&{~Aw=qn4^~pT{cH=nMegJ-J(KH+p4U9~X)V9n zcv|SH#0Xu2Gv1FwXZ!i}_=ywCHmeqh9pXhoLF+>(s30|#rJySr;gA$Vm7u-Cp4pZ2jwtSSF&?4Y(+&F6R{e-)naU^c8Kqkj3#!X`_ z(g9&|W(xN=$oSrNUuO^nH(d)W!pQLkf)Hej?<-s*MPi_Jk$Hwc^g7l>gc=%S(hXAwf!;{CP0MdEH4` z4c!!^)Uh0CQV>TXt{=hwp7Tgeo|jGjIh6o*Xf!VD$%kS93*AkJZICcj27+CvlQU4& zHeO>h#n3$V{c{o|e2efV)_0UbS~9Og^CtL}8tU8C7{)MOr;|`tZ|HE98`S|q4RQ%%q)oH*53Uf#-xM6QCGNE+ zNCXVi(Qz7|lPql-N!<_GCETR&FdojYxIb!=%ls8!C;L?s=#*~UR&_p_3r$oJD@d@_ zyA6t(D3;1v*EQM!8(CL)&%)Hyi7IA*NMt{5n`);U$54k=gA5UR+&n{ijZgC$o)g8z z&3C%`-2dDeXzVQYKPbHz%-+c)WZyG-LbDL4>MXbfZ1B`+?#23|nDoU)L$!*At^H6+ z`KsciaiF=T{5_?6V_B>Trf*20Qr=CZh01zJ(FSX0?eJsBrGMeKMc@zVuvKJcHedYR zZh%3USyfKYY=hvto-N=SS!-R$ySB<;UabJh(w_Br3vinO_C6Gz8ey1>`3dOw61a3+ z4R-{16ER{e)UhH1h1y(qj<*nuBg}>}Spt~-V25(|UvacX%(8gO4vKpFUqlC3F{_{R2^t`1A+;%JDRX+a^`AG_YQcl79AGgm-3lh3@#m44C+gp$v_C!w6WewSV3t zpIAF*S!?&BrxnFupj6+L4b;-u`Lxt+IEz$06X(Fpi8O9x$Wo!n+aYeJ4wygNSd5*M zYvYgKBq;#7oZ<#SoSzW?)_rC*=9`&4O0e4RsAG9S6+DBPc3XK#H$oqpClMCGk;@}sU&SpJ31O~f4zR5=?~}s&xzsHM^4KD81XxdW zd4&FEaESkwx`??oDqMA>MS9`Fh~}CWAHY|^$_EAzi_yj3BT=>v80{T?@c!)mr+H{1 z(HJBMgbjP;q7>yODXVtHO6VHn09Y5nsB zZb7x=Y(K!RwBhPdW5d`ZHZZ3XcvA|nK^akeNEI|7bYbRU{w0-?F)?bP8k21}3^P)OLxyD_}e+>V=?Qy&tjLwt353wLNf zIE{h$Gjj+1+Fi5&0tsh@TDd!A)0XY!fU&m1AAr5$CYU}c%Nc6|BNil%)h8&$>h|T- zz?A}t(u)PY^k?daGI5isgQyX^nb-Flznq4SApe$Cpyat17pi#^xZ$c)DtW^0z)KPu zgIbt6rF3E>44Gi+0QFnond$$74*R%gu?39042iw%x;zQ7dB#D5r`JarY?h!9LOdZ7 zO)y>2Kem3OUUxu;3|gHZOpx)4PM7h+&evVFG-%2R*M) z-CRc?n$)<>JT=F(u%)K);RF^O&nKGep6)p1rRtPG&lq#r%F+iA+rRfie{{a zV$jFzYzm-nu>BQPw?(~*m;5bJC93}L5$Jm+Ag{02XPAGP%SLv0wjwQr-7?OvwNV5y zHs&?txmP$tu4e;DG!kJX?27MQwTl#N5DJ=A$^0rG$jS1>kLU_pD@d-V;)oPp68eMB zc)PfykR>0PP4_}1LxJui%MF56{>#!zmjsXCI67c}72tj1jT+j`ZSAKSc}-$?xdH^7 zhXM&y7M&upoHXJFqA-gcm1rY!6)ez*Qz+|7V>1`}DWw@>g={`ui`Z)sU0)SuQXiTP%6sSt~6tK5wUj0=P2}%d>w(+ zwc8|m!-oA&(>B;e8o}H}o?=H?l|q6dcUuzJe$tVv6Aepi4%_Ax-;}G6&GM@PE`)aI z$fxmCkOkyD`!`qy;iF{p@DQw~W3_DAWf0?(0v+cHdC*+K&>F>p?yHA%iB3Y)^ZOnr zsH$^=yF-_nQ2XD6c?dv&Lt`Z*s}uDKq-sq~*|t5XnNb(upWxgbPt*YEqJCB11AipM zyKE8%%I_74-OQqYdB5TVPSP&k#6;Vd8fr%0f#=za9+PyCuGoq#YNrJ2L1Kduq)aqF z?@Da20YGHnvpS`j{KA-#Vq` z)W+{F=IR*F0S3Fl|DYYRl2K8$PGmjZG2n1TcK@}U>4^#E*+n`{2_!t%$Q7X2rqc%Q z+nG1By;Q7wOry>G%%A^j=+=_#QAE#l=8fzqKI^b8!FbwXn zn6P)j6gSE;5bm~tSK%g_VY3FNR%u7>1Rp`2cu(R!bVa0gYh%2nN} z8L8nAcEZDkRxesFkh*>|x<@|ldth9{W^*W0`buxHXo}JOS9Weh2fRvQ0Kijo2PGkO z=Z$AE^)&EwUPGA>P4*lGaPBewvZV14Z;%f?Qm$FZ#3W z(dg~MBOcMiBwQ;^VY(SGuB~Ho5I(1$8(#_j2Fe)!q09`;;FXO2sWs;ZKRsx&jN#3p z1whGeAIe^8Pyz}bb6eeZ!D?iva<*g3?-!?25&nb3x2)k^N@$J*yqDSu>6p3vz8;m} zuYX#LuF>3~_*q?%bCqy_Hf?T7u~wxd`Uh?Y2_s{x4iJZ#WopQ-QkZ&z80-KwJY$f$ zi4Zx$+q=g|!isj?#f=+7YJ->mZifLeI!jXAPRWgww=HH#YLYPW*}^r4R;u!uV4eiC z419DS;dD5@srz#6VlyBs%7D<@Gz5xtUK-Y(DN{~LducJ?nlMlIq)hasKkVC4k}G8p z0-_NlWWwH%)VAl1owia_mERnQb*F~vE+lTxrQ|)rzt>nTXp^s6@q~-P(}W`sV`vpw zM)xfhZ6pfh=^9Qa)Zk|)Y@qeVqDk09lT^Zr?^}$QSvL7GF%a$r0a@)C_(IfBZ~#9y zJ+luXS>5sPI}jL%4y+c7dHh*c5*EU*?$^soa-Sgs!nb~d=+^~z_x)b{i(sbDIqq`* zeFg1UO-q^CMzcW??8DQ)k_a6|`kiYs(5YQA%ckq(I&ZgIcCmk95g^RPxtr>>0m>nY zpjrT|XnHKaD{to>wCk=qjtxUYhm9IUD^8=^oF$Nr@6G9+^thq-kc!hqx`#kv zsC%D6gl~iIZjTT#EgWqckUVqac}u}lmgL8pK%PpFS)Eu!mJC7+Dz;2aF>O7R?#x|# zx9f)K2giRL=bvoh+?`3X$>%R0{~zSB(Fwnsvv@qK*V2o z`r*0ri~m7cX*rFUNZ0NEc8Zy@eVav_p?Xu1VJM#2P)dyF*1tFBZ>pPJdNpOgKC$t5 zlQ^5vEr0Xj+=tA>fA2gboE^^TT~Z#h(^|N=lwNs`J$J~~Z0h?Lvn2N{+#SMFnd{*d z#;Gt)l)ftIVd{hX)hb?aZ*KIQ$mLUXxO|cHF{4J5&#MIOp}M~scvw4x<3P9VwFvs5 zu{5L<^(o;$X!GXO)5)m9ORWfgm0W_|&}OV{oL;VPaFVRRgR2NYwdR+Z^)NgSN^8IQxJ?ycQ|HEov49z8ia`*FkF!$Ng=Riy{{^ zP&=KMhY6P&8TxJHiN5?@GY+i#-?%3_+J+Pw$_+2qu`#iEww>{}9;ACZ>?1-m3<19@ z>)>K)$u33iWC%X2(t!9R%wXS7?m%vO%g-=x{@5jUeDHiSR4J{Racy+O29g`P{KfOw zzv%<4eIvVjLmI@-CvF_m7e?r&4Mef~&4z6M%h-M8%6d0}z%_zb`GX9>)<#YJ2MM^A zB#wKbna!xoW&Qan1pcY=mkZW(w-ZTnKOyT={xhp*hSRFrQunlQCaq&ZuO2^;<&`2I z^{?h;R|NFcv(B~e1neH#sd|7F!mj(*Od8NjQG?2PU-N7F*Iy|`eacSTj0{xYwmn17 zIRndd>{zCBJ#VSxC;{s*NcfC{1g*?a;$6tm^xv%AJC6Pxi;x}PgWjn+I=J6?)E*cskD ziaN@)efN3ZsyGz)F1kW2A}Q>$O8lyus-MFy!;3^GL;eo+U}+H6WMi2=j2rh2PxBsL z%BpBxi@}yCUuvt6wS%dKVq{|zA!}6{{^fcQrNu0_vApExG1`?R%Z(NE)WnQy`iZgs zK?MhcX$JFlCSNoj>WH){)!A!PSPO-HyY%X{Cl{~UV5LU*nRG?{bn}1E7B%G!+Jv}MuBSt9lco;z*(s2rw~N?JWkJHKE5TM% zx;N#0Il=7j87I!v7B1t#g+AT19eZc;(z8J*gZq^gmC4!TANI6+d6|m)P~tL1t||K?RG~|B2U=v^RiJVu&M@$ApxWMOb-#Gs z`>@^UszrIpvt4=wt2t=GkrTF%wH8Hs;n2!zKJ%w!fdVOk9f8H zBP`NE2)@>So1`9DvYNRk&?r0St5Wu`SAae4X?A%RW6irtHsMhiQbD?6#1 z>nk_jZozM?VCu3CZ<$_P?HP9EiuT$o59*lu2O{{PT2X2rgU_y@G&4sKBdfA9fHWQG zmkS0UmX~bUTN3|+M%?jcdk>O(cUesFY}fji!X%@NTL!h~76*PgrJk{Mwzi|q>Egr8 zlXsZq;bx*f3c3McCjoT(F&)})M>FT1=VHrUYkN?470DC+;|E^3NE zP3@>O+Yxnma@`ZimOQzvyw0m{1KkzuCapP9m5}n)6qey9sw^x|c=?Yx@x3D#9m18v zqn1HX+-gsy#eDObVx>#vx*V+jWvw}3&Tnn3v+uaX96kN1^#4~ge?GP45o)w0a*PB0 z4H*ch?#C*J=l-%z8@a%upDi2M?o+3Q{>DpF7Y#l{{21Ccc1DoU&zkAj^N#Rr zf2ZV~(LfYjR(hP8YT|mO@O7Ay!<&v&Ni}S>nDfG?Pc@ipBW>W1=JG+wtm-AY_~zk| zk9RE#uWqfI>v)HxRg^2taXcq>-j`Y$Bp@H>BKVMCL!&Qv^NrW8)Q`o!yF1tAxAy$~ z^V7d=4;2UBrqY8ac>Kzfg$W8HYqD^j2X(RRf)f5yuJDB1?H)^u-LyU7g1Fq?Jxsq{ z{oGo-%{P_#_aM%NVZQdIvUs4;pSfFpfo+PLXefE~hpIv7{Ii(3mPQ?%=G?qszBsF* z@JJf<;BMNu9!IDG%y3hu(@yTH)i2&s<|r>JocgF`CE;rorvAb3jnULuk26&nWfy0R zR!QsC_|)Sbp?}aXrtXk^s(2uR2ksn&CvV>MPi!^#X|a4xIro1Md(Xk*7yLW_Nh5+5 z=;Gz3{YMkKx3xWVdj7n+8Lga}z6EZe2Ecf8mH}Z*06*E^jt@_s@`BD1Exrdo){KNMl06sE>k(3Nfnu>M= zZcsRi0<-U5uAY0rdU-xbVXx*J0-7^Z&*%{Yx zVLO&1CKCEy>tni}{iFJ~c8ps_$HC_%uWzh>l62%_V>LgXA4_XNP6l_21)Y&D?~gj3 z6WDyTf4FtXgIp#$AE(gcc%r_I$MT(9J)4-Y>Zqmn%1?D9^5Kt{AElcMX#>MM>;4w5 zp3NzlNj&9683)agm)*hn77IFh5pBv%svh$3l1EM7h@iAgEq{TBP~oK7!>)^Z58}Af zq<~T{NUxA%662WG_fPOOj^|T_lK=D+xq*>eF2P&G&g0usiVmU3(~&NJBuAtQ+CVC# z?#7?jhC=b~%M41kJiqUylg2Z}e*kye&sj|dHm-21qx4XxmGQY zuY=uAxiC6+kD<9#7@tNYl=|(LOkRq7r5T&gThM6R`9hDvH95Pdu>X1K*fISo3>Da~ zCob;yyfe9QC^lj>%^nxBw6x}O{N5w~TjrX(1It&FtIxRIhU9s;%U@^#`%h+$K03g( z%O_yLXY+mFzo-49YBwh6WRt)M#O#Y8fmiw@$Ob0+O`@*!_f@KhE^KXo;8T*X0WlC` zjLJ{;zxVWCFTYoQKdLbR?O+_~e8KfythR)n5&8qenk6oZc=7y7W}2q>@Nz2ivKUsn zXEgLe$aTM_%v7DQAQTXFpQ-}n>q7^^$B1Vb25WO&|5QKLkUp1X~1KopGM?hw|iMA{Cze&n^B^cWM&XT>egFJJQUed2n+fsBSc)z@ypzgNAE$P0KBs8a#`ccML}n#X$n*R%5;+u?rK z?Ct@UCX+3=;81-3%kOfnwCCIM9`R>?BpiMA;G^N2Pin8}z9cD>oyqzf!^Bnp+0e;i zJ1-ZT$Hx&cDr6j^iYxTJA@NG{(DfgNpL`3$IWwI=H!6PiI5$TwQ%m0Dgdb-<#y`fn zA4Bf#v^L6&X?}c8mp;&3?cMT0SY+-0<#TV-9|QN`@l0LbDcL2_#bBOlXvM`3&+tZ@ zy^D_YFQ5OEtL)Mx6>O}Ghfj$vC=NV~Hc5NTx-$0O7~aNBXDn}dt9_(R3x?gi1*(erk(b>R(5Bg zi(vtz%CbTqha0o+B22~>^zM6^xR!62xR^N0)SVBT67gq`tQIlOT)U_9{=|4}b78Z| z!>K;ug*yG_5)wWDLW#QGywHyKQMUU>zSVlcYQBA*&FE4oh& z`zL&4f5Hi)*mwE47HAQ#@PgH@Kl5*e4*C)XGvEX;@v-IAywUl--3=jGUPqQIpi;P6 zE-&^^4_<}ha0l)T_V-3p&R0R@NF!;G!&&HK5pY4h&m*zNxAUERhmytcZt>P7tw(R% z#qFW(#X&GAzIWvKtsXs+?-lDnuN#J1>g`|9Xb>;VCH#2#&nwTccOFthJ-H}E*$a@e zD$mhyTOmOZUw)p9NO|}1h0aga*9ZP-%l5)+8swgdnQfKm*;`!^Yy+|WV7KX9H zyV6&KwXyLdH+Qt9u>5@GA2e`=Wdu>5YYO5l)K+=`h>Ve=>o%7`Bt*mGEH}C7;KOdr1 zW_wksn&#awa8#$cQlG}tXXN7Z5drkx$ zdBgc_(r=6!)$iKFXZzF_+5WXtvj9UjMN(lCX^cf@H>In(MZ>MZ@d&kk)^k^`cd$Wt z%ei|ECM1be6Hk==*rh*;W{Bi0yk^X@lfqo8uG>=f`BN|MZ8e+1d)QYvQ(%8sPWu*A zJ=8gR?JaL`YyYjk?oGtNy?11V-#2)C!%Bf}@MXP;#MNc8#3J_skT|&KK@lVB<-IibcZrKFY9b?(lPsZ*OC3Mx3YEfm@Ud5umZax31I(h(ZGTUn<2z2KQ1EkC7JjK=}@itD{rD(tv|i(;ygB0$If(EZ9thiDGb z>T6EB`)Iq8)mhTXqp(fEo7-m_kkk-1`H4b)9MCo%`Mz>w%>n>t5I(jyHlBWk_tQluRMUEe9tBbD-H3gR0lXol*e)M@)k@lE4;7oQ0REHQm+Z!)V9!S z*h=s0x35r`ukNT+z74oM#(}>!h=Z-}S(yc^m#A|SD`$0^e`G4H0OthrBXw7w+m4zu zLjea4Wkv4AFigm7{+_=**8fh&<J&5%7+#CCp?{ZGVF^|~j+fN*@m4Ru%i2hbQQ=QX}do>85Nt60cKCPt$G zL;6V>X--wv(B|USg*^lTEY?;4nrvgyL)up6NUdP~g-2Xv^y99dLQ;2U^o#G7zgUHTb=Umdger`n zGLoGv@5<@&Z-my*#dYuIi7uaD_usyEW~YtTEBpo{KbyFuExW$l@%YdObWK|v7{rj#Q)x{$w@y~0>-K!fx;`*(mSI+it*q?G^8bFV zvQyteuUf5z(4PdC)j964utU4sBsif#=w%lz>EUy(JLOHi#}$nv_}CSOv_P$Y&jRnB z_|2=j-hW@Bzmc^Yr9ab$DI#~v{?@b;ceqL^L;TKU!A1o8_#t_pqtC-rI$@RRbJc=( zLi(n$Gb!Tt`+F^XLZ>h<6Yc}xtZUxQcKn=jj*0wok0`CH=J$nC|GN)-UK%t$;BOAN z{w~;MUU{TNLAX!)++3%;$YqHZb~m&y>eAb=;X}H+%m?r7h$*VK-_W_ZwX+m~J=^*_ z;>{NUE+fWcrC2F1`M*1N>dv}|`zkira~C#EW`nnzqDE#c$h(B~E!7(yDd#;!bN+NM zv+IWKRlq-24U1Aq1OC^Lia%LzsVuFvkTIwZ=Tc)_6{@|DSgHERO z(#CWBaSdmLzY$i`q1MlA=uTHwRSIj=Uv2gX1hBr?MySEj#rFUlX?~%LhL6sF&^&4Ee1c$-E{ptfU}8;N z^pg2QGypmXkXJs1YwYCQ;idyRI<{9D+`JNp$)ym6%rJ2dUkwH`L4pu#;w;TkX44(E zF)tH}*Rbq30L@H1xZbdvT9!opj^!W}9?-)Z|j$d&5xJU=foV1_^)$ zwR)8{I`=MvDi5Z!hgD}|WkM~Q;f(mW*I`XIY4gseak-jkx&Dqpg5$}wW{=>FJB5U% z2WhzoxT$ldcF-qcl2L*8G1yc}eF(C*Na4^KOgut06we+xi`Lew`-T?w&n=eR4?sIF z+bedcnKc4o@0PeGQ)_3apIeAoZg0VSCm9d4j65s=GP*Al?(0ulvnG$D59+YC*{0;z zAAuU@byT;V@j(797Jbj$P4ShIEs<*9*veUpJd?F;I34eeK>|IEv!~@w2~{S^VAiBl z(n+u1*pTfO%M_QqQqkA3v>p_6mtn5H&de!c$6MPO%WzXiD(LiV$jn27b>L88wTxxF z@lI=BYRn!qUb@8C1F5?*XWK^i71kk<#FZ%<-ITYQ(M-pgvl4LHfA)X03QKM5C=6pS z%+>qHoBK@We!YkGt!%t1AQxF=4$?;Bw}TCuwLIhKr#1>;auj>N!n=}Tf%`;L$xbrQ zEmeZHe}@E!p-Ld(W_#h~7$#}rfo-XB3(}OGeWZSNmp$%LS61_Zi)imd z`h7o3)6e~PMR|>TbiC`%_9yw$0a6U1{2_}TR7*2PZgfh>N=H>`@dL;`>@mCVs+>Ok zD$__H_LWaGuMw!mb;vP>Mr_Ug_84n%%K-7!LrKdVW zVPnH`jh&AzZC~k){cROV2LCJM4_9mJEOw0RWB>v-;~Z)_bfd&d)=1Hf!MauKNsu%; z#DS4^4l`hCW0+g;I*pc$`Tj4>rt6VZ=YMX$oR*_A_SJ!~g$xzt%U?LH=5rw|iOa-v zf#UGOrp8IAzXJ||o5@w0Ov>Lzh_oq@HOy9?o;!#ns>2GF)DBUq7(>IFdIcktnhIVI zzpH?AiKQ$B29&5mpn|6?x9demf@Jz;-hCjmcx&psgw$buKrZqRxk-Bo1gHS z1{2i3M@Xj2cZW`a;?PA^Adwy1(g9DKvBE;FVo@5SR?LDRR>-Q2c|v3;zEHN6&1xoY zMxwyqGg45$rm9zhG@0HsKBM;2<6~Z?P$hH;448ie=9}tOwM{*~8pkYN{S~SkI_ZVx zokCI^<0Cg%`f1XiVI-`{Tnh$h=m$T>wT#B1d?TqK0~kH}gP9p`F_zQ`^qDHt zI2GSOBa8zSIGWbEg@z|vN}KC6Up7nENz2F@Rl4JE!tdXaaTb$mGzIv7=ZZNU*qY#t zr?j0Vk+?_9u1BWkSe<nYmOVOk*wGHx9Tp74&RU;xl)TC z^TO&!Y){fcLHlc?U{Ux&9adZ$xBQ48=-){8nHt7yd>bI1wuQ)XG$R18r=p`++5R19 zmP}@EE9pPIi>BnxGFKWsx6n%pV@}Ag6MPB5JWFciO_}|JIL3zKYoK3#abk-3A)a*hN+J(EV*!x^ ze!uezZv(5{O;dtA$#o_;H|K3!J)Huf5z$Co=+)ey5>J3vnxwAhA+mRxWyh`o==io; zF(ydLx>ABt51OV`;1;;}RAvUJv-+Nj&3`Z3|8|(Z2U`rOOs~G}BXF(VPf?w2tr|ig zM?17`aHahV6xWS%v_TxlqJ@0)OcNvl$y5!xkwJRl*T>-?`@HUbF#>*btb&iFbfu@I zJ&3n36{E-1VR-YoKI4Couu|#XYJU!krVHAv&qN|Sk3by`Ip=#dSd4fbRQ0UQ zdYynhLfY|a*{}X7r(Y~`oFdw|lT3CGFm1zRGOsH!KX+WotyG+E{b3hFrWr4gkfz02 zI4A3sGrk2oLzBjh%saXY4)o)nn$n`JeUO7Aj|c=62MMn+G(1Cy<%YARgx**9?26?A z_#x}h4K0ZNUy_4(K&Dx(R%4g5q;$DBMGxIKdHi5DzNdVt=;a8dKTNqBTiy4~Bog_7 zwx0?iNBG|8zL?jUc)C~(Jp-siOCF)?WW{m9%qft8unN)_atFs@FpE?rBEl^F4rY4v zb_W(wXmi<8iH>^YJ;9v&Y(3zaC=jBL$r@esbU3&(2g9e1;z&1NI z9M8A;bwIb!6C}AEiQE&-oL~A!rx2%$aRY*QvxGvUJHIbr^M(Ur@+S32|9FEm*CQ5>-l1BPWlhZFlfID2ia zcr8}*^xKaY0})qa+%}2tpRPoelw_x^;;7e^s3mmIu;FzFc=lLAy2O0w)VMt+kF`gU z(@4p{(5S(inkRyuAO}X*7&OntrGhcVv_PoiGgCAKU;IH+(G9MQ*a-iu`Jz*LSYxcB z0}R5|`*Z5vuHk?itHuKCIt^PBVJyTUU%RetvxH@HTmRU*-P6{Zrh2-gnbYyx=&cN($2`rA~TDo2EZsdzpCmKe_kejPsAkA8{#gb zq1{}2i^9D3OnT;lx8?@aO{#NMEGjT&c50%FhI$t>WAU$@xv_`ZG=qR2 zS6>aCR-jK@m-%Vz<_F9a1!uaY>+ zP3AX!MKxpnT;fx`uw9LBF`?KL?Th|R!Z5ZXyc9anCU_`;8d)?I7x}fH3YWE33By+^ z;%^|ZbK~zd)?L!c({zDy!iM*@L$3lUIlZbB{u>{Xku1!Yz9=?z4)+KhmS2br-cp!J zr^|tMfGy-Li_~AfLzuJ{7dnJ4EMGK5c2{qyY)6Yf<5lpe$$>x!d|su(AR`s8&N!=) z*TPi0?O0uKG(NGcVq*g}dVjY!o#R=M z^M4Om3*t`u?p$pjCIF7f(?$lqLCCKEA5@ZLKBRUZPT_YtK*O>Ev~zaY2C3lKEVnmo?4w1=7YVdb=A|@0_BZrI|*3oHhbpKjr!nn{#_Pq8j#yooqOv!#uM{ z-Pe;$)K86-fk@V66=qv`ww4Gy{RI`oT{UT2&t{h_(8GSc-1(qqTwMkTpowrF0fH*~ zmUg|+ROzDOAXJeZf^8d$f-x_LKj&N@N{{1JRoaFtVr{2JLlnNR;6+0UHEu|=%u?u5 zeZz7!F40gzR@YpEcfmc6Wi*ZWALvfKS_#zc|3yVds+sCE^S0%y9df>3JsiePlxtoV zY^*u$Iq>phbRTqlmD~AE6bBfRc%OMGJ>%=l)$980I65WSozeqT+XK4Q*&(BgE#rj3 z2Ddo6dJDS4etJvc4#fm&C!x{#FK}f&Md~mEp?Yn0G_0MdVeQcRo-j(Y_CIZ8*GV9N zI)Y;u*an2*JHT&i4e3Cu#!GM17ygEM^Q9f~T?-M+7ji9=L{)76Z0ARmnQFrT3lLRN zF6aF2&xYmUt@P(Ru&tq#9y}bYaUQ+EKXfzGGHrMXpGx4FC#on`o+p`lF@O)N*oibS6u!Y`3Qu_LE*MW#c>+OY)S|NJS6*YPxyJym8u4SJwU30#xScaM+sD%ehJ`eE=OoRnVMz zvCU$$?k1%(T5BP{yp1Wn@?5$&ES zpoeY{)dz}>CeZTh?KIflS_f@Y0cy6u(3CvJL9-+f^+!1ZzQWjgH4z#|VKqWi`p?M$ zq2zyrCjH-O+P9H_rZLq=gTkn{O@oX#)&DEa9YpvhBNg_}bRxS`77n|Jz!+z(6V7o? z#1g9&ZYkoiv^8hx|EecJAzG5tJ;KoKFK5ATN)fiSt%d+S)+B5LYQnE((LWI;a(l&3 zZC2C$*56afQncNu1?AdBo_}|ziLwAKF8Hw5d=LR4A+|>d`Ug!Ct|D#_nErUI(9-GG zGQ0*RXumkKN=erI1*`^%3$$>r;mfbZqlOXB=l7L(dC5ki6o&?0z)e<4=Y)mL_#44D%R4t%0 zZP8=Zis%L-4B$5(c4i>P^+{5cl$Q7*cEE?n3MtJ-Jp4G}N1{-(x&ix3g*^Of8qtYC z=B7i#0A{^Wt8Eh5mDKT>E}UIzGSte+;c)foC?5x6Ac<=~&yv8?<=S2^ihBAU(Z2O( z3lez00eo;=dvFgy+``@#1T2fn5x)#P5N#I{kp1s$%&j<)Rph&6Ap&|UJzr4~pT;mM zbgZT{%Y;vxfE-&>Wg}IuPIBQ9N(wE*Az~{%n^t#jI8`q~AR%woeU2AA~EN8}=eBZ9HYEA9@mp z7PH_*XBNjbf?E)|#?(9z0i#2?Z&vqSW9UHhj<=CyaM-FSs_y*O!BU*E)j_;42R}hT zWf{R$1$;QT0OV_;9BTlc7;qztX3nGg^SvMU{lor&?b>y{53kqrl>ze{ z%C=1#7C~KT+ZPfT9rtsC89&&Qz2%%u2e^b)7Vh9OY|!9B1vK0Utazl3j)xc{C(I96 zJG1lKh&44*MIgzU$fFR}oj}_%%S_=S)+%)EVhqiE`6IePlUw$*vq|WyRXT{b6^A>3 znJ{b_4`umg%?OQ&0CUg1o{M!~73QB9G;cuBs-USKLK29U_#|#y6ZRLHmve0z`X{Sg zg=PqBo5K^Dg(t9}Zx6&C;J_2u6{B78^g@wK#HkbH_YRe~{^OKnZ#{{ZktQ`odq%+ok3=p%S2Z#uaX0CB~hl|hwfx8VfE1y+s^qD2gR z0cC_aZo7T`>d7va(WE~J*6S8X1Snz?{7L&+1Q}0~_cXHBK9+Q71S<^2ZSn88bSiYYpk)+d3$wlUZTbLiQIC*YEps$vYQFNrFpw0l=bCeg z|FEDV;O5>yIlnh{$EBVj2(&L~z~jcEI_EvRj5a!CL?n{X+rkqTE(WU9t^gopAxla$ zMZ}zGEUL*6(Tv{i6H{7BNgwSBrA(S$cNN4J4%hxtRfma#hnchcmc=$qhb8q_Mr(NW zNaRgzM1#Uv&r`rNNQGPCm_#VG_kobav~3~z1LkpB0wUH; z9`eeErJ-9yqoAxU|Mi^vdjYV;4I1SVo*pWNBLmQFCMXq#E1*>oD&(Ln-%Yz4#C-X3j20>u1iv#h>KUElRW&g@!TeP@^H=&(1CU+ zdnL1%X|P)iJDo~M4?{oE4&jwq3#vsvmLN;as4&XGkxyncV!!lvrvk}Maqf-V(f|+& zxxskw%!@vJ3J2Vr@`;4=gO_(-PXAfO-rgLA%A;6>E;ri3#jgIFDi~TKD|is}*bk*P z3IJj&{Y8c@!qfG4LxChWa2{p?Npzvo5vqT=&5~>bzyui=zGVTmz+c@0-Bw^=kyqZ# z%ra~Y0`~?l!sndBivq{Z+xcCePjHQ>!-3EkIPMHLaSo* zKlRLB)JxWSxDc-^AOHc0OJRLOc5P(zNll82YGUq*%%&4B&q>mLCOVob+dsrSKwPd#w5R&x%*ohW5z%&xQ zlZR+ha|kqlAN_b#8t%nke;#V4IA>g8T`Wrlk8&YeZ}o?&)eGyO2DN95ilDVjr>p!2 zUW-|7e^!cyhs}d|d%~Yd@dIF7dGbQSp6sv9lsYu!*@w2gbvBRc#~(L}cDpt0J-|^G zJ~kwY4BFG2lpddJ5uh=92Ktnvp_zhvLa8;`z^ z1mE2-_f7@#YckKXQ-{cF1fJj@fK@d|1}aPxy2RS;xYsFS+yaZ%VofK(I|fX%r#aAxDEfGflW& zqEcW>@^p{+!I7QC&Ae?m8zkF%tEN82#wMS)}V+B}& ze5pPJ-g@OK=AD=>CGpwtIt1J4W^==C9C7%R!u428Nt-^z2GHvr_p`9F_LK z%>T0v--Tqwgc;C;Nu`xpXpQw83$E*dJKvwD3A>~sRxu}g{gUNBo(76XDpf~dMvp3c zt}1h2HO<%`udHZDsvVgI=1uZ ziGp#~F}pCTXZ~_Vj-BRaDwX38xaG>!wn56G>d}Tr_kK28U)f3M&``LLQj=aUEvoB> zh;-+5>hKygO%W>+b1eV4e|glucYyZ+-p)wCEo8;zxd4r`sxP6nwgun}t-g2)k_{z&m?|d&^ zEkwiWwF%+1xsww9X`I!`m~%dcdJ3Dg`D4V-b4N1xMm{HG__UBbZgesKq6(c*a^1$Ho4UFrJ zLO;+Son$|j^-3<qE z>kQ18myJ6cM40aMZv=O-Pr0Za3v%G{=8zNv69WBL%WP z$j#Df^+bY{ZsR>*CTI-o?wsObLB9jj6YwK@&EO=>Z}$~|k^o_Tem>inoEhERdZ+%xYTPko0|4&R)=;X%dI@3PV-&jaw5 z;{gg%U0oW}UXztHFp&BeX*1AxZosv_W!fs&$p&O=6>vk-vn7Qv|NqK99 z{SsU}vMoyn>J^#)K};>! z8ygOAx5@U>OI^2jN{Jio*znfEdB8Kj5}*(~wx{&?J%e+<<-V+aKk%Z+Rfl#(E~Ca& z@MmkgA-dS<45egP85CS5JGX*AzV}L(P^r$rHF*Fxa%3I~T`e^4z9(|D)}Pj1d+57| z7Bb03X;(A*OWjdL0$UjjsRFgb7u1A#mIom&Fc1(2u1ghiUQ|Dq5M!MCwp+p2=}zse zxf|!THC5WEh>Ag^b6=eTjYxqZ2N z1*E7>(Z=1|qg%hB;V3F`$8qQ@^lG2wYU@)aQKRcr4Im&ywBB%rt#?xMw|mKu{;!zV znX%JIaFUtd;v>kh#aEi$1uYtWx`mE!n zxQV0Eb78DcfjYBBrzVPgn%U5qo1D4N!7Ih&b%H#q-xxrnBn zv4j|iNgA=@xsEwyqrc4)kOU#fUVr)|%We4jnI8FC&!OtLxAwMoi<0dn0`Y=_xP!>l zE@MN+qsXa*X4&DU>x7!%FY^lb6JzrpXWJ+feBpMVuueP&KcvKIGVfPGMPIH99`$^r z40ifwz?O2(%#|=I65}5;eqN!OS{Rn?qwo@Vw7EEL%{*H)HvT$+}W zJn~$=84|Z;U-aa}F}v?2FYV#ct|_zVfc@~i?`@yo+)%$Amd386JhZYz=z>pO472t| z&QSKD4|*?V{4oLd)P*Mw4NQB^YbK@VGf&)o6IQHiaj3@Fl3lrDWf1%@|L@%!wZ~ie z8BPW@>3QUUiG)9D?meX?=Pgx5@4Z#NPkC?~H)F6g0*Q&*(D8(CloX{##GR4Xv_7gh zJ{;rSAAPw-_qOCfk6`CNKudq#57hWSPB0@_mLHky*R;Du?INRTA+p=o+8s|EdG0OD zkfmofR!O09T$t6@I;Mi(-yYynvEiGihXXXJZOi2JNlGAh)tb=hmT#+#2zkBUo{DEh zDcY$&Jf$*MVTo>)3tbf;Nr&-5n``ZUQ;Ml_LfMxpo+cAD)H|@&E2w@=OOX8@bMzXA z#o{PVYe-E%US4+k}%JyfF!#*blKPY(M&Hq08bu(ZOWrDeY2%AHagL)#xiz z{`zLucn2NA1EWANjmkVsY#&iDme}ZUB07p-E1fS^&;(s^Q$eHUPTo#SXus8xq^0hE z=&uqXV*6yme1cYn^*i6@0mRDo z9fC}{ZVJA9xhJe9T=e5YEQWXy)Xh$iE=W{5XfCKN>}JRwOE=#7m46Z||FXQwbd!^= z0RqSaEZNb@3hf#{7K7H`F5=&zAxIUJVfV4qjUNnF=lSxepn%chs2102L5M0OR-P}A zk0@*xS2zhmeZcE5=$+@4-*(S`AXRs>aKT>-J}vZ$@B;~=?oE2A?}w}%W5$mD(0-g` zB?*%4W^?r7Dj2iSh`&!|PKX?zyfMhz3l0Vnw}<_<^+gaIG^b}a4%chsD&viF&1$hu;Z5*GuW|c%ULcAgc?JpIl*oYwWKw_9^y#*dMe4q0Df-{YX>stU`k&stvJK zP#!NEb$`%2X>=g)cONrV>B-yhG-A7aQQo4uoq*b{!9ua>iX($RD#=urXtz09j(yF- zRSh;Jc7)!G9J%$vwY>VdX=QN>DrH;9gEG+3oJ8M6w?Fb7c$;X)e;x!UmiPWRAsIo6 zYtX7xple^U@>A@QTU(P}_fx3Tsj`8VNMuV=Z*i}fRjr<9S z+d6%x@A%wjbGdjWHd#Q~!LzI4t7Tb7odaoqfhztVVo)%_mYmjv@oDv=yMYM-#gAV6 z`@M^@dKfdxGXd&0BonAql+I8Ukb4Fa|2m;w7%Duk*d3De+o}7d`0M)?r6mbXo(*vR zKo9gBp(cR)Q2kj zht++Ml*@1h~`ksPKmGo77dGE+Pv#Xwx4tdZFHXbz(gFdDP7-k`6fKOAEF7WBK$z1iV&-!vBc!z!6MFE3wcQY_pu z;W^yf^WkY|?TfZkt9L92CmyK`;M+Fgmc{&poWZ*qv z9Mj8G8@TttTk%QCb#;Gnk=xs5M+ZUwJtY?vVI6(9doO4C>)c-(cv(%t5)SKX(hO2I zEX({c4X>|uJjj1yrhdZePL{5)teP@|CNy_>sz3Vdyl=1X3)5?-?Zp$_V|>O9odIP+ zVk(P#5+HNEkC6tz59dj1k3jPm4LJ}EB#YyOj-i_8%?AW-d7lmdLy+ZEy{x2iS!7~G zi%(@Edo<>*8c6PqK9vfGhX%+3ncC@_5WW*1@#eX&FG%^@;#h-o43hj#lO`zH%l_{F=e1eS2VN*pT3l znYQZ7EWQ8UddqC%il$%Ijp*HXb(S5SoJ SqpAAq+$F^Izr1W=uaMRYGU9>$rxLCPu zoC|%B=~KC)nf!LbKM3T(>MF%$L{Myd>g1P$BS!rgdKGx-3vyu@jaWwsHmiv2TH1EU z^~^D$sH>;7jUsS7Jty+mV3Chc&dKVfuUIBh7-_<&##Qi0 zw|t7^BEGc`8`PK+NrzH*#|`h)UM|q}c_`wcm{GYfmi>sQpj*4(`qR__j>LnVwn?Zk z5Q9P2&|5oK^X#hZwn=*Zg>PjVw|I=jY63mcs59%r%rb$W+v|mD;H3Cc)a;+r9FQ5g&d1>BTg|Jh zOs*0k&!gTeytzqZSnD=)AgP`PTlOiSHdlh*Lv_bYp1xxqb)qOFDk5SoZU`sl*W?HO z;hU|3SEwOfMkigv__n}-YaX&1?!1j;1@p9`J@uT!J5KJN)(P9Y1lCx z!1lw7shdlW z05vjO-`y+OF>fU?2&sZNJM1zDX5wbzm!X)R#1PILJ}3~_>w{lbI|;;ci8(H^HYxo4 zB&4p4kbq*#M!r7axSD4t#uKiDpJ#yh+zBknD{sJ)w2#O?$^Vy+wCc~GOj>LdZt!{d zFJ-`lT*cT~@Bj;K9sr^2Vf+r{9CNLK*e}AbL62BX?YQfY+>hZpy z`BIk?;CZMm63!7(QI3{HPfU8K!UfW6%<7jbA5;o(EUJe{T(ZBSzkfEsBk(^l;~sG6 zrz+5^H5}19z@L%WRn??QJ(F=ON^uKDZl1y&c6$p-HH&&;Ss^~r0ED0l{{76ubJ_6o z!RlW7Nr%sB>pn|p1@Sv}2Nb`SG>yQQ1AE^$KzzkEK)m3b*$OS~r+Wr{DC6yBk-CQ# zCVG|3x9Z~9qH)eOrJBBc*Yf{Wy@g(qh0)|eE092`?EOJ&yw6;?dhZ#z&FaHc z7F`f%(j5UHlvXl9`q7J6=GtLR>|ZF9J@p26=!b{$j6BqumGdAhmMp)06D&%6$vg`h z6a2?k_hiT~ArAr7fwsTFem_*4&3xA({m@H?@1DvW1C}vGp@zVNbKnRn7Szm+N6Kvb zX;;7x2cTN}CV9rwno0S9b?0)s57i~`^y==ImkZBX)`W3j! z=CP?K$eQU+-4uie1I!=F@x0$&XNkFVa^wneITm+bS&Jk?8B&y#UL**b&}~1zs8exP zSCuUzn#WHTYM#PNKh&&s5C|~gp10)C50O?g- zpu5%t@Oe#IzRsz&psU6|JolS94Pf$4xX||*V`jp0 zC^3wn%AtMfXW8`(C8P=s*~e*Hw9HW1w*cgY)w|1i7Av_>0U|Nc7fR`Qh(Hb^O|V-V z42(0_#xb7k1hU?}o#j{-;4lZ->41Em#>GXr-39ZpH-7Y=q2}EdWcI5CtgBSP*D0>nBnkzXsY6IGvA1QE`jS$U{9)uJ%zTnp^+cgj=A1T6b-{THNZ69r$2WL0mYvR`BlY zWXRcoBbx!zEavY7JBC|J^Dyyi#4z(Z%{_xMa#DN73(c|AA2tjI*4OnmpX+r3Irgb; z_0lvlG*3{PJ0vI;Ix6)^1vPBIm|pa4C*ryUc4oMC&kdvI+J1!K zPTkgGvOvDuL5IEH5_0ouW+Cgh6_0G*Jg{VV$CN~ftgEE=BpD*e7qoF|!H+qf=c}4h z(bY(dAu;}kuGYpMS+nnvlAZ*2e6YfTK3zQwbDqZ?)D9;CKTDmhIWnr~L_=Qj+ZTx@ zoGUx#;g|5=mtl~8BE{*NE_JBt89Qsl8= zis^9Vx&l5K`i>qq-20!RQizHzqqbNxz)Q$I$zH`QAQ0~vqkB_6tLlE$gk50IagJ}a z-Uvb(&E_#j$lQ!Shpw9%3Peplx0ALxs07UosY_hH|4})3;y;OP?t-`l2p)|U&|_+G zNT^yL_CtT!>XG9{x=Mn`La3p6ULD9!N2W`2jQv$0?1Si$QJL@XhgBfLmd$-B z>!{$e)-*?7Xq>*bZ7SShh0qbJxtMxn>`G8OreD%5| zLscWw2?&T4^$92v7J&}W=^GYIghcoDk7e=eH_LSjsLN+!w88(*a0>pxoSwdJ05fv%jB^9M=lf|K{f&rU*w|lb~l8co;57XStxUWVFaj_fTD$`a@RK&iqbj2f zmq-quJw#`~HZ!{^FywxXrJXud3eOEjasw)YwR9vYlbj3qIOmPDiarqDS!bLIj{&Vy99p@2W9T})8#=aZhM7+W~>*L=gzScu#LV zuky(H!e(@?j4_9HizO(-CL~s#y{JtUS;y=baKHmO^(Z&9mfue(_#gq$u(N+`cy%f< z113Dpg73+=6KeF@NCJu-mqTnRrYzR`36=O7op^=SBjEqFt0y-1Kx-HaSvpZUFa7N0R3`dKD`^JT1vV|8 z^m&06=W#EyqiHH8JPJ!&y%*h-*n@w_D`9iJZ+wtXCqm04Z`OY*xBy%m=6bNqxpNthZm7u@l2jLbUb%ZwT4^ z9zAXZxt8?$FYk^zwQv21BTQVD430{vs=q@YGF;;IYB)#SGpA_7~O7o2|E>cHV6F5heqi zDs+jsh#z7S=~bcx&!y{$51VZQL(iHWx5>(%cmz_QHI0t+a;BGoJgDtrj!3s|BKrUzU;+oW?3#%qucIYC*ae!uT1&vGahrl7R>mS-0tEN703LCF@!(3h zIcYiTDI9)iG&)C~K4Uy37st9p_L)Cm+loV#`Lb(D{;2WUPe7O%o_jJ1!(40BE~8LG z8}jFgeYgoEMUo=}O8JD?cf08)>5~=iD-ZYlqgh(-C&Zs~;t+8Pe8V{RE><>3PNh5* zAR_}U95w0q5GeC{iI#?YdM(mjOMpJxsqRU1>HE;slMeb%Vn+qJ!5#)JL*~a;xby*& z#1Js|u7A#8#F76113~NUGY{syHBQ>aBBYyJ;}W|0K@xWiU~?1pfMmx=7$T`HE3B*h z5T|MP=goT>`kz%?gbD&2tMg6J(6zDG-*E=p(Lj-%3dLI$9pJd0>kJyk;}!SyR>=?% zD1PElZP@x$RGaM4DhA5PEa+`p^2Qr!N=v4p~VwEf)3bRw*dNA*}Oyj zbv^;+{tctemw=#3>uGN)g+vhGh2$uP&%A7*q3+tI;$SzZjy*UCE(f>3`XLS#nTv!H z#_zhe-*z#_jrwtBWb?=MN`?pm6MEMggyHsCBK$X%lJ<{{W!!;XXkpTXQITf^LwO|# zph#LWsSVGm`FABoa27K;;ebt`IjO>(RjE`^3+src?wCMcntaE3kiGtZCo}ci0<_4< zv_b?jgAV0W=U-LX1-rZ25S{)UjlG_)7b`o}y>daGun0sIv;;yRix)cZsAV$uXbC|; z-`atA_X+ns#0gi)e}FiFMZuF$PTIxC`r#-SP(_|6isSj&-E(1-PfZ}YC$dXjS4-8T zwkIQGg%*T$)$Z#CJgf+MaBz5Y*P5Lz@C<5-ZKG@6~BNEA*HMg}V13;qydj0m)7miBV+8umo9P=i_^RS*6QlUc;Cs?r1 z0)-G=Tf+l4;iyK?^*EzFOi-jf*fQ7ErZPZ@prLs}I{9H`mz`#K;;Lr?*tuc4Cbf8} z9PYpTyIe*>WzB0IUm0{Yrp$n82SHt%5RQy#5aIu+d)fo+wfzD%*m=NcW+K=yd9A(C z%=VtkP@E66xVEPT821Ih1ADepPwRs*MdD!1fB^4N+LLY3#fl2!2l^f({{Y_^It5w! z_6oyQV>wteak9xh0X)(wWNsTxY?sSKW{$GD0W^b#sBflRa81!5+4*oLX@jm4oPgFo zsP>m>t$-sliK{thJ=a2Ey&~C+aGH-gt80d7sF(rW76d%ko`DCerp$x#Sl#`G$!%_7 zLU~(Bo9NH#?n}m|%mxwWe?d(7S-bZ!H*k9-Y6dCqdeQg(NnnH@xN3l~)+1I2kRNv>Q(-fbQX=ut_^r1hHbv zEFz+r+6gc-1~+ncR^pn}89Cx&9&CaqE!6cJj_0Ky9f2;vo4d2Gg*d? zM`)&!UB!@Szll(i3FLOH!rnxUC(U-|=59L3t^9A+;n|uCxK3q-g@MX zoI65D6JEbGS^EIgGSkC;$h3uLO`GxDRJnvz;fERV6F&hE;LzYi*jA5+n+jruX{ZfX zpb0+!!%hr|p$KEh98SHPtGSJ!J*10~bzCmg5{-szdy`+|EB_ip^Tb%p>&=Zm2&xD; zUIlEvE4%POZ37j{zG;*sIexJ7Y5-FUt`N^va1U?&R|CvhyiRAh{gFq5r=AaZMeubS;4U`i z3h>GOOn9q>C{|$p&N;0$G{~oRp{VRkyCYOx-z;5icawY|x+9%Y!Mw3snr}dc zB{~7Tb{?3P^<4GyR#I_u9Xc{YmN!OK9FR!|4a&+RyNv8sVxDui`AEMyJ~H1j*9j{# zPP~2kevNNLJWQh3S?36sBOLHoL8WfwE!wudvKwCGr)z+%MS)|nL|R3LZer)2ge1!N zEupM`#+p=i-|8O>Ic`z85|t@AeDfYY09%Ag z3X0ghmAfS9mwS9dws;$)HR2 ze8e_GJ;LHTmyGQ8?-y|Iwtwc|pce+0>~ZUf4RjrRfO6Z-^r90}D4^?15*z7aSZ|Fj z0w)!voF23m)hm+L&J8qMYxkJK(8#w?*DD_?;`)ctl{wFwqp^|qYYPKmMg*n3YepLR zGq(qbDaC(OrtRFd(>SKtl%u7Q5y~K~W6Q#AG1&mnZj9aa?1SY4C*!w|O2GBMvl|GQ z$k0xi&os%SweFRC7Cf{E{forefZsSHt7*RaQ-OAc(B3x`2zSkh!70o$aOb<9ByqG@ z^{k{LRRtxDY=qCgzn$aP=)&bPl&8KA$1=g#f%)7!-QUB$Ab+1#iWt}MqE6+?AseT| z4d9RlV2$9HZ`rDwjmpC3ZO+6NRpI*1zb}Ryy z5%uLl?!C7y!b+m6U_Dd;7k_v<4rn^isgM5B1^nXuUa%N1{mp@&(`SQD0i)wiS1*aD z%E2DAu+{jA9d60K6;Rdir5OcSxK+Q87@hbpj$dh} zJpz#@k@RJnH8!DF=yYipTvyXa*AI~tjR?T+TlXrp!1Y4)SE6j>JtK$|7Uc?f*cDEw zi&Qv5xP0dp6<8msK~ilAj`u66P4ma@9npP_l=!xticub=F3_$Vden#vO0&1;X;8&&JHFUg zI+{_0tx@KE$IP$86*({7QXs(SF+jnwR=k3p1+ne21f$I~UbWM>IB)DSafX-}^5TQdA*>x4}+DWj%*5nFHXk=h*t1ri6hV3*Ki7;(F)e ztNsCwpt;SczFHD&VFbo+D(sj#@C+Z;d;5)INxKsKHKgq1bx7w6O{+fw<29^}A3E^H z*3~GTu(<{rc7gEgDrft>89KjT(})*Ukm^@yoUH#|y#*co!Q=OnyGnYN_Piopka~)- zQ}f{{ZiUhx&F)QT0oh+MHQzPr{sF3s1~wN*d|4elkK)r_$-Z~s7vf^L+SKije$A^y zn%=`j-ud=jkINgLf#!a4YVn%1_K;}3=>YL&uv1PWhluJ#Bo|Ii8CoI8(Z}SNtP8iT zY$^L3NKngk*;84tz3OK+HWhr(tiFu?Z1TPl&fft)J@KG=olIS^)-DheD2SIHYK65zf=9d{ zF>4*(62*N!!{vR~TG_iXNsF3E1F3UfwmXmPEgEl6)!bA|mq3`-?t(qeX_?@G*fC27zS7HC^jbubkB3CcEn zU+~5f(LHI8WJo+JF5_8q76JZ(mhvy#mj8g47N2I` zLEe*mH3;jkJh)<3k(#zMJC=RrSB*WF{sB=n^^3WMFrp~M-V5|sz`Ozv9U?+j;(wYMs&Eyr((_UIq*3bjnZtadhI5v`2}_HWJq z0}xRmhqfX^nGGX^QLCM)T4Q<%X8B!+@Qr@wB6P`%DI1JXp@!5ClzDYs`?mkq6S(7S zETdP_&Waf1ddpd$yUyn|IE$^d@U*E-dm>`IN$h3X=&Y24PF)A7E4~%8hmY7Az+S9K z1~DY2&P69RiS~iAM|lwk2NNF5iybThEz{3wUdkyNkS~cx$}}I$cKXm@pY6Rg$GrcT zaZcPgB?v1OKi;^Sx%_GU^Gk{QuS*{qbV)L{18!aV9InV^E#z7Dd4M~>Yv=d+V7SV} z#gAd;PrC9jdk=niU0s`Ndso5J7o}3H=DmIp()8iJ=Q?!O z?EOFcJVMMH@+A%J>Z0(T0~z0UEY%-2_1t!LO?2<4%&Oa0U&(w{5nI&WE^n;UK(#BpgW~CaHqF%ETx>IA7Y338h{C1Mh;M$Erxp0^^sMa_Y zuiYQDUANMuA`Bwrq;Cu-m52QU$n?Izm0N9f2kpG)2Jm6s8<&-pX3pI!yp!nGTA%Fy z!zoG^-_p$iPTC=5*sBX7%+d?3jRT%Urqxjo^ERqAvT?Ry;l8}1#(TBXC$8#khPVW# zXMy6aZtlqH+t(_$Gc|cFH5i4S?74)Vh0M@5ROc@1RiH3t3d_Z>wkSJ@>b?A4ayH!H zVeP%vxl@@V^xTU#MRyzL?%sXgZ8M}NmkWQ!54+MR(xlFj5drR2tcT97U7v{^vwqme z3D^gOpcrHMdztoWpfNRh9dV#xzs%U4zeWywj*64u@sUFL&M-uYp*h!sMfKdvfmPiQ zEp-1jU;Jzj^V7E`?zWJl5GAi4Xa#lBX`Ab zLoCUEn8p|vN*7G4R0qT>8F<*L+{3rtwFR|l00-zC1GheRaSG2y_6nsJnlAbcH%s)g zS)X=OwcW&DwOJoF&JxHP`&^nQ`MLIvr07*^Pb$41ZsnV;VSZi4y^3f)0O?26e=CKA z50u=0W=))ISfH)GUsZBg)w>eng3*p~9!~Ddd4ow4r}O!v>&30Yjeh3;>G&1kZfYm* zu5mNYLq+s92cEAl(&1hu{q^(5ZIwI_cWRepNYdHz`Jd@+kz8~M^2W|o^6lJRYtIHG z_C6UN^tJxEH_b2`SL%AI{B6fY^6I!RTJr&k@68RY>GS7DmlwjQw7ieb#>SO_d9xXP zx?vpZJl!Cf!f`IlwCjk%cF#k;P+o-MK0+q)wZY}8^B-$pHauF3Io>6!j$O_>w8neu zH0bsRceLh|7?pFUZpU9^jSA${1*-|CUqcn<9 z(ecr&C$gRuT%lgzGTQ3$td-GCiLoo7pwue&`*8N!9W6@?<##2*ut_{Gbt<^9EuIp~ zqw*=cR9E3)px=UIy2K+D)Oo8)iQ7Y~d~JJbs^@;(|11b>o@)A|S8ek%;OllgRgx39;3 zh06~;|lZ(nKmH2@35Mcs_XQ_B}u6Q_OwS`0|+b( zyIJ>Z!R6CA=LL3?L(&^SJC|I7mAco74#y6O?KZ06sjuz`hJWn)eovm<${XQvC+N*kHIrH;HNEzYkS6xV$$#ZV5yR*MbHore zOZX?2$kbUbJ4?V+xX0*bt z>AP!{g5}K+XWveF+zEr?`{G?|Et3+r9l}sSyZoVXT7pZ{T5T>7GsdaqA-gD7*MRpg z9PES+nACh$JN#smBYK4HqJl|MF_@0x? zvpTpmkB;PjebB`;PQGbmofc3Xt5UosX?^MW-eg!9Z8FZ{)Mx$p!&(vmk`!?3cSVc} zp8PQG0IMlDG{>yG+~v5&;%+ubR{W6P`_cZZ?;Qw`AI7XH!SsAdb60(G%5Cf!O)TR8 z+);4%mI20R_{&^BqJ-A-(aHT>?S}&rGa}o;=oQwd`Yk=fyEHY!(`y1g9AFqQV($F) zH=e7R|N3`jcRg=^(;B+(rtBlek!gfgE!4boWDt9+@mP||Tm%inI8|dXD3FXlFhZNT zBVVwE;Lxm(4wy^`9YPu>UpBjSJ2pSA>1SBiSN?n_ zWn>z`@qD7~k}ekO)*1Tik`|FXjWu{j5oQL|rSUTPh%o&|!J?`iFRIWp1I%_j-)FQi zl#^HlPZ+L47qnKrysel|_mp3!&SP|9UbpH!_dXjD`&U~#0j#dI>Bv3~_`I2zp=-nT z*F=HJo&NYOV!OUD)mOneZLUGI1{@a_ixK30KZ3SA{Nrzp_d<>(%~VfkSjo;yikRi;d{jCaNjC)O!S2zYN6?q_%`P$$tRrO|A(V<@n^dI|M+JnlQb!6vZ1(hDjCHb=Fq_@IZNG%X*#3L z`D{qK-7|zz4J+qVIye>?vN@E=6gf_#Sq?d$`Tnl^_Ydr`$LDi>-q&@#->=v6m3{_& z==5r3p~d;|^_T?5&6+LQR>sl9kH@di7c|peTm18!Bk_9IP`~QKTgrX{Daq)+XF~sp zk^6}8d*T)+DwjIL*fa<2t4+n48NGjIV|X85&hS0%<9upQ-Z(;aN=x6_RW+^ZEui9h1z7)iLwW<=9q~|AiH72^a$d+CH^6B=T zw3X=ND~>b!JimY36X}xMV4`*J@0N!FH$pnC4C2B6uOLCr>L%yHpfqSsd*HIkQoSH z0{zj`hi<67gl^?P#r>-;)%=Zx=hM*yyr%Xc`QU{wA&NWy2L=7yuDrE3an+Br@Cv1q ziTe2=H}SOmC!NvF{>YS1X>QW^dt3Sk&y0LAM|&SHeP!CG$sY5RJ>TqiIiWtm?FQHr zf>6hohFJywgOdE`hmLM$fR0@0&uoz2&?!9+(6tP|Jkfb9SI$EMAvd$#`4j$v}@+e){N&*|Ug$CT$2i0LWO zD?IWFU-p|l@xe1g;Ys6rZzwR)IUKw&IwxbrSB|gsnc*vMNL?ExMQ7f$nAbzb-|#@1 zD|(DZNc1J4W>9B8NXSIivFABeW6tX5Z|n&b0e;cO#?FJrx#h*9#Ldf@TeWVrxArPt z{{F{>FD;`=U}_Amuaj5ZGD3F`CVq<9xyz#I`G3LP-mf6v`? z*rZ_0+o_sm7-Q4=_Wm1IU)s&PVY;d0a$xz!2_FxgJ5lTm+RnFfVzh4UhmTR?mlKCr zQf10rFPk%6&a*k}Han>@%!e*@g{WD{?Y>$9R_DE>>fbx`kO1W2iG#g!G>&{4>$o}6 zpxmD_=6NRcvwpAN<#UpkESh3F6^ewO$8GdH8Y)d(S}4<{icfIZ{FkqD)Z)n70>z59rg(|S1zD{Qu{%o;>xte!OM2 zAHG*~f3}5*XE>om-$6v0RzK=&wFSJEXa5H^t#y0*;Us0&qBONN>3d?ieW?pfe%06+ z>Mn7m@TEd}Zl+rjl;Ad|hTAZ5Fd<-B2y`&or4EG-^!%O<6O$SNLAo!YMA6-Ow=qcd zEU@dE4hk?4E|&}zgn;G(hyGIah|%ynigb3P}EP6#jQp4mRb%a|N-X zkKNFK!Uh&^DB)*k;*rd*mpv5L`e$NFXxqRFPidnlYuJ%KjYgjecZ#gx!zqR#Kns;I zvmHEMV`ppA5K&kPGon+}C`M|wxJIGh-sTP4-Y+K;t}ZbU2xK)dYB>2!%99W;b6X8$ z@6#TLUubIU0KYiOwzmywRzt~QD4RFX-jcyG@lXGoE~2*1Po3e?aD|cr8vSxU9~}-x z0W>p?XVJ|xk{D?H>%)zu+KQ5`R#Q+Qt5c4}<;s=3Mao5x9f{Onj!ozQ(DcR_?zp)9 zJ_!Hg$nJr)G;o{%dw0|I0Ounf+v##D*mRS)b^5B#F-6@sxVDXYPtV2-5i=a%A0V!S zJeaP>IP(2yFYXNZc_mrDq9TRHtcEunxSZn1sx#9`s=mrLxcSted|5lYdkG9ns82b| z7O1IdcGarvo~J*0{2J!sxw$hX_xOlcuq9N!j!cIkaxnBy64aiqlb*u!92vb@VrM-C zcGu4EbJ>lS^LLG}X#y61;Qt^sl(96ePWNxv*?&CF#~FpEkkogK3dRWdkAH3ke?Pr5 zxd^4Q7F^(>;IVz8CnN@-Z$)*EU(O}*h(#VBhrUTtS`$?^81QmJwCU!}CpSz(FhEZ@ zTio_M)qIdUgJYZ`_{c}uiDN7=8ru2j=Lrh@s`;n0aWxWA$Qa}9YLeJjdV~N(YwnjO z-VzB@3i*@!_X);qcR1*{IGF_vw)Asnr)>LNBB$=ECg8)@9YlRT{D^H)f^%$XrW~6@ zD2<~Ms9dw=GAipX+Zfvl=4beXW9d~AW)5b9!mS90ZN7K-P(b!a0Uo~=RFvv+zi9{k zHJAi%Rh%a)7en4i#AQ<{p+owH=O9K$8{va&0y`BmKhEMjNUc{QDl~CbWmV0v;}`!+ z;zJ+1MvWT!N!c&XVl{~|S%xqG!=qXuuJdypopNx$0i`SZI&0*&q3={Y7eFQF<_cb0 zvHp0`%IUCH9&PB3a|SOgarsWvw{h+AV&ut#qdL>no;*#&47 zO6*r_R={`4L0G1hv2?$1Q~h~SyN4kzXbY1!5EbrBr(ZLwq>#vf!`eVqQVn%q5X4RZ ztQAW67wc+T?%Ga?2vTk5a=v*MdO?fZDQYkSEz6pMV-SBx0l%nxRwP z@^?<6s}2O`Tq*?7SMBJdgNqy>&kkL6 z(f@3%p0;eIkTIZfcbZJoa7XW?r~Xi&uSH)fc}c}#u-uhI8)#q1phi*6kLtkRVYHS=PVQ0gCZ9i)(9JQ)9kG{y4m^QTT9^|X&5&8? z>(q!KIfnYGzix*}?AqguDIZc4wg)F%$ma+DVMr7q$^y(pbV|n_hNaUCC0!tm>@PGs zw`+LAq|A3s2Ppv)EHz~iwCjj;N^Tggai=O@wKa_?|Tk7 z@(Yn)ZD1k z``9F!uz)6zyRv(@H0)V_nPNX9KHd_zbojvtM!sieucWV6`DlQRzwG<92nWN24QLJE z++p#E>sJP=#`>g8yRz?^2AM4=XFVD%>~;5#3wdmU+-QIZuFV%=Mby32CE=f=e%dc#gQj7G?8v}B-ZZUv;9h~{r38EU){R?+?aO>zY?iGst3 znbF94!N$*gJNdE}nJIP|P#H*SAmQ-V4g`?w*9KVOB+Hg9(NTO_?%xiOk&AyskaDlH ziQOXuVHJuGXq1Y}wjfU;h}p6Rv~`ctsx+xNc9sH*E^8GyRpPc$rN$_Xt3)y+_EF?p zSKr6~Hj;39N;8=r02%aVa;@z4`(Q$SljK`{n4AN;jn63uV=@%e6Zkm>Tjfy9H{OHM zJ)MfICrq#XbBG-SDKR!AdCJayMLRXvNq_u$Fi_fmpJ?OnXu;r1P&2^`@Yw<{h0a)# zTQ+;8&T_cQ_Fw`Zz{1RM{xn!$`t*pQ>?usyR>bCUo{qj;Ple$z31gyB!ZGA8t}oV<8Ql zS~^hgb{0W8%bJr>B~l061IO2UQa;5j*4se-?Q?H#XK0E*avW~oBPv}XR}QTbtMvp4wCTLmA zkHz(l8>-=&m616F;ctJ_weD(Tz-%MolmYJW*ZQk{IKk}#4PR3w<#9_zTdtKV3N4w| zFQcLXIMmfG?$I&8s&SRKPa{-lQ!Q`Bi*0<2O|_YFUkfqGsKwOaS51I&#h^hkx6X9M z?V}W;GD`UGyhziMROiIVCTFWt8lu-=vQ6?;9s6z^G65McOsn@FZ1g}IL)xcdBda|y0eKyjOBJ^Ohew@f&Ej~a|sX# z7K3-wy2l!;I?QXWUgeIU4cgQ(W0H#__GXA33-SYB#OMVC(V|%W4gtM2xo}ovH~UnRajl@=MRh- z#z5Hj7#1$Q#;2(>1c>+iWAV7vL}jXiTFZ!m5`jkM6zqkCvdByT*HPNmPfJ|=AGB6- zrYU=Mic|ZD$9Kek(0++!+a)UMB08@{|s}DD7Ywvsd1x=l2dp2=pn0{M3 z6nkQmq%PHNLj#0<`dL2u+AHl)-2WihnVjGS$bTnvpzpwLWOQ`)$Bfwun)ujz;!0G4 zYI}12ES)d3BFWdo=Q!Yl^lwtFvbh|mPs}wRKdZ*UY}OYq6x~0gFi19&Y!I?VgIPO` z{EJmfjFAiVjvd%so2$6dnYx&VGSHmAJ;oFpyHO%$=W2(9nJ~j0E7nrO$t`&rZS)x_ z)bf;>IMQUCPrb&i(2sNBe@g=T!{F^0GjvqwraD5)H4OfA@;c02u-iwe%2#b!b;Fhh*G)BJ7FJ6RRg)+8XVG^o2=P)iF-exV*MOjb`e=|RgP0=0oC zfXvQ&*V|FbDsZrVIyu+N%8JOb`ahg)KSj~8l+7g`LtRU>GCB`d0o2(dHdf5TqBM)yB!Vv8+jHDC$f#w;4Yj#Ke5GawYsRV!BT(;0kZ==CNC&7vx zJ`jQtDTn@L@_0uF|C3G= zC3Gx5n`079x`(P+CbLRJTDbGw^K%ShmDeJ$D&xUU?CxB%ZD0N1#6V}gwvY)RBdFCr zm;YG1#=8&$1EJ{Pt!(uVc6w>4H~|`N-r#p9r`|cqL4sFiE~G^$0{CKN zfK}RD~0E4w9hX_+nVwu(~TdSTvC1wGv#E{x#!@eVffXNxk&`hkt}=3(GRU+8t1Wj)=P`CnWaWU*7vR->MU`2u~2qBrV6*A?11Eu4{PrCM*Yd98} z`xx>F7Z|{+ZqN7SR+%0}2mGOe;mL$kWYb@i%Xy+9YhAvUjaXHb0T5O>=2-Dknndz3 z@ex}G^TY?Xb@)pio6#{Tq=>{Oo-kvH^NT8UZ`;nZXTw3i+c>#*H0WUJ{044`6EnjQ zXBveBwswFsUUpS>X=gZj)gk(14W~U78Dkrzp%Yvw&caQwdyYXL5(ibOi;D$lDvyr> z5nIV^_;*Qq$xXrMcUxGZ9Yo&weG2Wbo2-S(tnsYDad^X&u1Bbmw zw#zImdlk6j;Zy-vQ6RMYM73si$RHaZi{V26upNVg4`mQCjl|rZEvSNLeYRR9#|Vf` z#Qj{TUL+%+Ro;)S3Hyy`3t&#II#&;E#=1i|aJ@VfOwB=tfo~%>L310&Gt(}#NyH>0 zwvsxNwQ8@(t-yz_x?TU16A$*g%S?YnS^F|s2!6mY`8kA>W3tEWf*l}YRq%gD*!1`w z3c_wU89H7`pH1)x2e;XYf=e5;lcEi1qQb|F-ByjGqXfbKpes{$P&|m=rk0lWSJ zrDC^WZA-h_5TV1AZ?$I5|M%ERASFUnCmT(CsWouuoZV0kAd~wM>}0~#wsQZzzWTbi zzkDn3CsIH-Gdm#IhAWQM-cqg)k#~A;;#NX(TNaR6kia z5=RNnjf08~4b@>=RJ+oGsZeli99d{5X(fLT1Oe3*!%FEf+oAhr3&v#YemRpzs1k`e zD}xU4NilUSrC!TSX;)sE3^Xu0iIjoSgH^dQ+E5-W`3}D_I^%=C7%YI}Ip2H;d4ewo zET;^_%x4lp^f5shF4xkEI`$l{6F)o+`rmM@yTB+42bR2?-iUJv{(bZ%jW>y(JGilN z=V2SlfDFj`nrhyPCPG0iQ!6g9wVBLIZ1|C{QEwKOWMKOzovP(4iPx9e_BPQd=(EL~ z4#HL{Ji(&b?}ItV)b3fqm_IhXzea>2O<~F6P{O`cY04)7esf$vQqysx149-F7i2{f zbKfHhwy8iPR_-Ye5g4%>4I%Fiofst^-|NOzHedtH`T71-H(>e)M+rRsy4t_#^gva{ zNHnNY&YbqzdZjhVXc?0A&~}8P2Cdflt_ajSa1r-AOt|WB^;Fx3dy=rJ^qyn!h%xXU zb6^Y2_#dy$jCnb^0$H>{+M`GMlEk^GjSmh^#AWQ|PcUFSEwIyO?5VNGU@goqy^NiY z{74TE&J(PX=W?P_>PO7YmE(JqNcL6rvf@hg_~BeeiJYtc=!`_k+J5tD?JMk^)IdJS z#%r8A@7JL5kr&8$sdmj&FC=^k4rju8Q!j)T{iu#3G`De!VMuIjRYJw&f`a4?>S8yly|0ym zAbl{+j=DYa@3Z$q|D>g+H?w`D9(=sC`BM3OB>Cm*w(0V;#LYR6y2JZE`CoqcKH5?E z_LR>q$e5`&hil8pSqwXeyYN5g9>^I8;tTuU9yW2c7?Pf%zp*l1y%ROc-o1#Rc&X+z9Je!mo=DBL zZ+v%P`>#@iCdHqNid@|g-WMK4dn9fGF3r$4$1!Rld-pcG8iSol)u97?{qw-y7! zf}>um`;P7EZS5G4;aB;KnX-z{+^oNOChPS{Y0a`zgV73e-#P`n_LAXd7}Q2 zmf{%f!!-=VF1z`0Y4+upcdG5>Sfy0GIGyKFH_T{F8z|dRiTDAhesv9oJA(Nt+S(EusyEgD2)Uc3b~5LH_!vbc15z33Wo2wblYm zPrWamp6kUvST15jen0i>+_)VoHB6xncksD2R?_QE+|zriugrzLfm0Xt!d>2e$zl!W z>TT9pPtmaP7rOq|);X3G@Zm^R(J`2cmBhZZmG$05c9l=K%lDFB?uSobSPn5g+9{}# z-Je`@eqC?)VWwyMV(E6t*yss(u5FH(e^i~?o}==6FMPJ^2#%##gnpH9KGSIym1x?P>oWB+*nm9=g49?D=eJSNQ?E_(N`A0I-L@1hlb zxKFRj=dqS>xc*eBLetEX0irE&E-h?%#JXqO6Q%9@Gk4PAJ=DOhK-log+4DD-;{Co~ zKs?-s9!%`a3uAvuXP+BNIj6Ot1^Brnt1NZ)xjys^`=1 zq~C7CzLxUpmFjw`8~Nn?M!xrvBi(tE8eeydo9ZrXq&8DeX_NU&Ou5lky-O|kP~%fx{MM!si{SXGjLJRi`i*-QQ2S`#Ldif-(J~Q#6Z8i z6OWpH)r(r|;XPyxmhvZF5VKct{9i}YQ@+Dw&jCOG&6@`#DrTK2c4Yi;CdkRV|)%XXyw529(dZ0V(}6ixLm>;~uA>lDqNBY!!# zYXepv60e&(-yCMinkpN45(MA$e##XpdTv!jspuOUOh$eqADVDg-F|3(AW*pG9D=#4 zyNnnD9K9H=?tSM7)d>GT4n_f+H+h8;8UBq?`VeA0I#dPN?wpv%3Y zkyUfr8;g;6Q`Lk&|N`N77*ywba?PpyyeRx{_qgdF!}g>N^%Zw(gC@0V?o z?HJC22~%ud65qHbFuxN)IIuaS8D{; zd^8WMR!ldP&U=L#aBk0O{Cbq9Qh%(=2Qg+Q#%KG` zbZNSmlIvcOpD`&iieYAx(Y5o`G>-&j+Edz_{!dx4AD8xksWa|K(#4f$m9dUl`kc%^ z9fnai$C~3B5TdtrW@=|@*K?%W!lh<>8o&RN)v>O~GwA2`7sB`(ORv)R`tR0dex4oO z^`q}!x*A{g_15{){V{#V5A7;e`1@n{P6jR4!zAwgp4*qxD6zKB?A(%jalZ}GQnpF0 zZ)z^ex1KvoDShL?ESciM6*Fz`VaD8*4x6KVi%^J^+eP6)U&CJJrTCraBQR$C>mn6} zkDN{q*<l)x{Wpuuie^-6kx;NUX35WP^%vSJVD+15) z(c#k!AboqAw}*?QYi)z4pwc}()lhJ=qkk1P_u(zQfz&A6ppac~AWxjI_o`~;Pu=zu zznpKKW-lImyz$#EcrCZF#`?;qS7~!Z-?{+yo8^g%k0ak+Y96yen#+?ye-{2_HBjC6 z;A!EgHVcFdUr;Z3V?p(8`0XN)utqI2H%c$hj$pG?e1E_t^Hd-cNB88hC;h6^CWIdi ze4MbS$U~!9HlRBF)6#qD+5Kf%!IJ|x)VO`Oo53-ioBIxT()OD2@lsx{3%3j&E$_*s zdLKP4C|NtV^uTWEApEt|lN?IQ!x@>~3tE?MeE!~Y|I_Y+l=Pk(@G;I$&D2D@x~ua= zr!@C!?*YCF(TGvEQsMG0JI=Pov0cf7>1jPPQx|&9y>2>IA`*{^9zNO*?wc_h$moE( z-<9=JB%LH5nt3WVHoaEJbhG0Yc2`84XGl={v(_}!CX#x-O=;csUcan<{j#m!#C;>@ zTK(HbH=kW^NDfZm6dy0ZWvah&_HUe)mk;n&BUajBhXI1&sm5Q^uept%{HRyRn_stN zg$UcK2N!(zAA`-n6?)NbVt>6GO5d(LFXpBQ5*as2qn+;_b^KCLYv}CR*0BG?4t0e@ z^mh{#6_p#+)7#>u%Zc1>H&go=al2ZwXoco zmmfZ88tpU>7V&j2(O{=E^~hSaW+=bE`|EUdmkPG(`iHTofc}j&zLax)_wDHm(@*F4 zOht{&j?&!7pH;h!Zk;_Ref`A)PNvcV`dYk@9wc~qeWFV3O=G3Jgx-icoH76oogo14 z_qUwF)zUz%-5oypmL(okaVDF8(J<)UNmBZ&(Y~TF)4+AW`|Z(7(^`+*qvW8kV5y8# z$RxlepU(uK8t-sykE(oaxo+g1nSSP0DDIyO(`pd0Dr9MDOn*Kj7h)?N&E%Ju(+dgA@jT-^a8)C>g`fXQ+?M z%!nw|tMO~5T&}ivOfofgiDXwZJs*}~ux{?B)mLlejB|3gUbrX(O08##CinXzURh}4 zO*0+t6;=)^_#!3P6dBlkOV3Z_X1|Nmdn^AT?=K%SPrG6i?c5@V;#cU}Ro)q3q#|78 z%?O4x^R+llyNHnK7euDsUHduYjf~I-vic{&Ki@Kcs!SyolQ+$FpFIGn6X z8^o?IFXivkC}GN5|F*;C(1V*VJU07%%I6Ld()#bZajW9xoyXp8+kFb&%Kj^fR;Ym& z;%~${9;E3$G6^QsToJC4&lOc49+5AEwT_riu}561!qUbNZMpYpgHbn9?)H5M8_e}V zR%FS)vDWMh*4!L(-)*}8>cJM?TG%`bU!99LSoua>tSnBoBEmd{eEGFS~0BZ^=q`RPrMut zus+YYP(qt;H5ijVN%ull0|Lfcw9DV0TK?C$t}t#Bxb6ON%|jgRql#)CRthU?^HWKq z#O)8-5!>#yu3CHsMgr(n2Ve0Ag4{Adxt2CZK;jl&8JsE4Kj2UssI+BvxrUiCIaBnR zY2lu5xCSn_%tPXFPpulj1X*k-IQQ^^Aah|uz5bdXbVcEOyZZRZ$0F3!1+r53)h9z6??hqK*N&>>JsT= zas4ON-1iFL{S#j-U-*A+BNdq8#c^o*WW(hZKtM{3iKH58{R)H~tFU@`1T3sC(mPBkK zg81$jt#4I(R*$0NA8Z{?=M+^{=p2l2Yx@4<)rB)Cji$e%PU>JcMS6ZqH3{|(?R$d& zl;{VHm(o}DmxdLD^4aufE%|FBG)>Ql~q@E0k9KoQeq zebW4(Q1RDv-u%NY3B?(jplL|6^P}PQua~)>v?}+PUflT%Zzr?)IfwFP|9!);w0C_U zXIJ2S@~l3u>~7?_ugx-zpD%Qzwbn(ppYXaIDt|_HunK(*2+>W{B5_??*bQV)?Y3gk z!Q#KGdh?Z}-VL8R^`Hx$@^H_#jsZ+Q#p2dn|JL^9+1(ROTgtNt<{&Ba;^IR`E}sNT z`ZbVIofyl~4i)BPpH|m5bT11uxu{q;7vbcKVoo^^sy;mW{VC^mV{KmGF@^5Cw7VJS z;^j{p-7e6J*DkEGv5oLvlDSKfKg;&AlVJn{v4yZJ)2J)yG#kg*K3;e=xf@zE`6in6 z#hznBeRW*~Nj~d?G%Jz2h>~eyg1&7s4QbeYYQ8d`5L(Q6c?`Oqhg%k&RaQYFZa*nB zZF%m;)FRI-4A$MOX$5N$uW^mNjbv$)aIa-Sgdv8clebQT@+37nw_(BjAH@K}7%QE8#shOvU4zY0Ql!BXxj@ z8{*35%TgD1J&T0wzPC#`_NQ%>PNwwPNvkFj9=V8Zqb!|nBF>j3FVyI@VIu#T0JD)t4Tj8Vj!TZt= zj(JX^@KUvB?4$0Ll)qR09ea`@p;-I(kXlC0DzFp0a~scXsM^U(&*i_*qJ;0PSKrE9 zZJ(9YG3N=TkeKC7t4q~Oyr1=_qQ&1lY}maUw!^<&alQ81n%iFGm6)D@P`_|A`?`@m zZpwji5gvlA`CexbYAvl(%G;_9Z_WCYB{Yy+E8aNw{w{-P2LIF7&P zi_E7yEGhKkk(s~p`??oArDUKlQc zk)(i?Z_A2G;O{e-F>63mc=lyCO_0+)CAhIsGkKlm_G{DdXXa%T0&h9Q5a)pStRmWt z=HRNoPsD7x!1g&=07qBG09bEgmWqF;601777ogS!UW9{a6!IsGqqun!n(IxqmaGQj zuYw8sQi1Xf_Uac%dqME@S9(d&OcSHQm>bY92Xc9SGvEsGWdNZ-BGbA9F_t5i%AMqt zMv5#vzCol2o<1oS@cr>~#P{rlKkSccFuSSh9r40mXM0Z{smA!Z1)~6V1>}$YvhC$v z+12^}v=yhE+#_eIs1aKk1OhnEfA-#{J@g_}remx6XJKYi8Hz)m61uV=o+8LaS0!=m zJ#t4~EQ9}e&Tl-oUBqL#RBjA1V%AJr@s9#*VL>5-)yIgvZwALm9oO`0;gMnvhhKi4 z^1wp*2$dSxf>(pR)%)7&YD^4)HW3xX4t*SmgKywK#0t-A{<_r6MPY7Z@n^}Mi$Eu4bND$KHO4vu<9RE+Qn9JE&Fc;g2Aul(F>^`OA18!6A9ULpPCSL!cL}TE zYNe(cZ+=SS;HBp^(^@F99&Q4)7ed za>`6`u$p|8_k$zJwNgF{n`$ENUhNCRR6!x4&?Mta)~BfR{-3pBh&3mHd=gE{RNFY1 zJ$9C*jN*KTFt7jN00~8y_vYA$nk-p2wUp?^`YJy|G z6hR2*uL4>8G=^Q=z~n2<(t4-N!d$JK=i&5RK!F{A?O?&!cqtzV`86 z;N_OpLEGihL@0UJ5II@kkQv@hyzY?%Cr|@=7BMBlRwe$JkzJQau5Fiw+K-JRaW6M< zAkGU?)*|H<8pdy`SBt`ixpJb&?B^%6_nLPLa^h*Z1=^Cbnj6Z+c-<8Tk$`!fl3p?k z0(OwTWaiZqCd-)Ddb2%ss?sG_STaNmIR{rH%NCs?vqor}0Q;IXH)w9)u-!+J=PdHZ z^FvP>HE>eHOs9dX1Tcxt8}&A~+ZDu}2Bz4KX5t0do}%iOW^ElGl|{v{H+LtRO$laZ zms&R`MFOU!Y|O0NA#I~{&}}e-bxeX<>yI^CQ2uBkb#ps!w-jGEWp7(G$Wy=$gew?2 zz=PG5X+}w2v{N|O4m?89zQ8sFtK*+X4PMVHUMe&kB}NZ-Mge_MSN_JV{s{<9fr=}Y zC*6s3van~S+2~oSh0&JG9UY#+cARSAHb__guDyfddT_qa9T%gdk@qn<8Jnf|^C;H* zLP!Aa-*yf~7;F4PZq))q9ND8R34q@L&G@^)B}Vtgb(_LnTAY-ulqBaYXTWuRL;Zzl z#J|s9S-8zis)?9v&X6wtr)HeBH6q_{2t&auO)`GMcG3wn{5zZIby?3xtbuD#L?_(x zfTdB`5%!@h5jl({fX=R`*xRJiT&fO)!Pk2?)t{V46VV%WOcXDo6UHQ1`ZZOaRz2Oy zHbWH25aQUlC1s2n+84jJFfnB&Vlw7KP>^bGKK^m$NF3WQDzu1DiuLLU;J(fm$T=9P zv*8G^EJ$B!G89byC>9{lfru*NLQ4^H-_0pkMA{I|-%XV2H%hDjPEjUO;ES3Ai-@7D z;vd@r=5i8aSAeP_`XX`LmX>Ktq2ha~rwz&s_8eoI`-13RxLRFB`m`E^ysinb+_Hxr+8YZqYG0>ayHp@ z&I}=tXD`ro_hMrH1>$$#tcO|v4!{`8d;M784OEr9SKsP4}%r{Nj zvRp}%O-GnaQ4J2RnnB)qm?v$y?|ESF}?xnyAEA*a&xk zn>g25kC5yP1sm$IE@|VyD5{OWf%0oa=S1-K&>k)FlS0~apJ1xtWko$ef#7c_P@0n} z4H2WF(X#O29Ch9^uXRfN6FsX*&&@b$X9RSuKlrg+wBmeUcAU4?zytYEG~jWO4Wf8fqK(umFNz@M(d?8>b!9Bm+HKrSMHC zpsX)me&`d?Hf^dg3g`S(|Gnerkc6SHhY9G;oU9T1uH-%agO>d+x2XU+uu2MpD>jD8 zfj`!tr4_z8GL>YW;9LL63}#;yQ=q+M@rPxSJr3))_t*s}Q|4zO=~nlcw-H>Hm?iH+ z4Sc59{BTx>xL|B?fw6sSG}=)<9?p3>m6XD0<$^>;6M`$e;r0@c<3e9VI~^5b%HKKq!{js(KrcW!;!k> zKx=B#AN{ks9n%D?Z~MsypB}BSmn>xi#JW*c)UY|tD8}Z-(OBk2H5=?VneQ^)>ETOD zA{0#dqUuIUyUce{df+&2;dgZTzZJ2)cthuT8rb$Y+zRN}6Fx%cb!}_r+pNe zU8b;wlDJY#LiOks0Oq6a`+N;0IwuwmK%Ji#8xZ(=yojh9W=hhl>tJ<>OJZ{@ByvCl z#`g}}$#@uu-JiluX9ECC6Po?0L;h4lRvzEc!IzrgF|03P%W~%5en%?K7WOe+6m!lmJTNbsHOZR9|BQ{6jg7Cxb%dCx4f)o zOvyqZl!1!cn2NMFi_Z9|%Vbw87U-+Y+03pwQF=FdY+HZb{|>sMa~)G`D(LuxC+B^{ zr>rg%zJrVevDA=be;$T*h!g`KVC|mysIQbTSoJj74oq2Ith1};P{rMF%Al0u(ZADg z1P#@uH(*vk@B+}l(ttcL<#lnBFDK^YO1SfzUa5>Au+@R?Q%;EfEIF1+HrtsRn;y$4 zT9F8l$}02AO)$FZFTP4LP@oHvZaCGeqxf>mG7wfCKB`~_4oIdFCu&%_Y-55%fM5T8 z9T)=gkJ`%kymRm^mJ3$cy(Iw|%_CvgxWT;HRB{jA!qBC(d}rRaH!Ty~3iSYrGQX1q zgrwVrR1!|%+g@nZVQG#0XH&yRVSpCjb6j2$Lg0Ld6N^U7q-nW8pag%Z>Vw3e-APaD z4q|`LIO^9Fho}c-K7fli)zGO!ZU==_grb{Lyqrge7_uFP!3;z=MVE;o$DjSnvh7RC zZFi>;tECo&?iwb)W`QF#lMpw4%9{uLcI|*E*7l$AapJ_`1;(rCAADLkjYW~RxrS>n z*3QGtH8fIs`Q2Ug8Tn}%D>blT6vhO+xIy9XFFK`4Mc*j9hg{N1V57HhfWWeOLS>&8gqXehB z8e-d9G2)X((Z_;RX!;-<;Ot0$j`$R}07AfT1y4#T0^o&##u+b*=w)ZXRBzUXitq@= zraG@sZyES75k*}TO!iZXAOwebGdynOELE?J(T%k!xKvqufWn#{2#-=Xq)XM}*z*i1 z@=*&k)yg+mklC$|qz6<);e|L4I>p{^D?=lYD5N`EG6bWgbB-s zkF~&GeHMtNk9Cj`gzFGOxd?+8nd-}!t>RY6#2fq-#_X`1E7D10E5Yd?6)R(rWDw~I4Xxv zf%iJVlU{Gj;w`N?hf2W44a2!InJ6^z4G0rBnao6cZ=qzM;fFY%Y&xY*ZPi{S$8uGs zHlf{H>h?&pYJ2K%;5>cizx}cOzLheasF2a=l7LgixCDtx=<$lDts4GVk;ITN(S<+2 zcUCQTSx-=8Obsr41#95I=L^=K`~x53=fu&Ak=kT#)oozV@w)(k3*#YOC+k=K;a{Nx1-Jutt2G8o*TESaX11 zupbOyvMlWj?O!wE@3TAi2%D7xH9AG1c$Ub*GEd(arH6E5f@i!>Ey==j_hV2-W zkK@e(=TQb#P-%qB>!Je`z2N^iI`?oU|NoEQGYmPDsHx4=ltU+nVh%GpAeFOpaBNBk zry=LVMkvijh>B4TLq&?rp$svHLMVqhHiw2e=QuvU`}_Ob#dXHG|=vND)79Py-sOx-Z`~npw)oz%R>;*34N- z>PpQt0@@fMAKRq$$mA<74HE-~t}))LhPgx4$BpU>4u-2+%U-oqg9?D^VBmCW6QsEb zjLS)2SycxBQ>ZwZoB%rl(Lyz{1Ekzbn(X3&Jyb&W?TDPt14e6Fi3AE(;$%JMxB))a z!J3*8HMm?sU2al_R0>s*dB-TWo04DDEn3I|zzP^mhP5`Tz(Q#mp*D`Tbil3n4~!0G z@vI99XmOJHF=rU4}6vD;CfD+9O6G2XI1SL@fRUk22>L{u}zX- zn1v2Ii4skgGFPE{d#7P7KIGvvq7zLvKsScpC%qtS>C8YzwYe^ocFymI3B&715XWG| zEO}xO2LA{8N`XLqHQ-;}&K{5fDZHes+?vI`;{4B}tw$RmbW?wmy?9hG4^6bfi;zV6 zamIKrsy?HOW*)o|c{w0w{iEc_WqHkco}qB))FG2rFj_+_h@J7U)kQMPhf24Zfu&KzO%M9(l?zcou8AoNy0JCnK zB$gG=4ATAww{81EN$-`uv>GU+KGw6?DW3w=fYVG5D0N9yvng2c`J8%Id&c#%Z(U+M zGN$sC!#wqTA0=u8&1{NE2qJsN0~|uY63!np5Lu-s9(gKH4~|iI*ntq!*1p<;2D20D ziSk+$*sfY7FoFZAXVWzJEEopIv&_>ADqN(89yjTR`0dC*`Hqko8u;){H|&9jgHrh_ zF-A%>b9LT7I-YyT0U#%km7cMu<0Lf1UrX!<^FuI}USVH2eKg zKtYxlQ&*SWnOyXdHMzqxrSde%>M;%kkrsQP6jX3;BT z$i+EF> zlSI|58ZcOBTP4lJcQk~9YJC&$F$C9<=%%--sa}tJeva&G#4;pU?(8-ZvEM#kU@6R( zd{FgBsc$C?uY+>1r(KKkzRd=GJNXfj2UZXkN5~O|ElLGwF15a9sd5`3gRYjk?jzYU zqM5Nj^5B%{Y?hNjs`#f3^Pk0{O_NOkFd8=WiEFs;_Dz59%!_?y1syX~3vN6SU>jjP zIQ;MhW1ZEv);H%bcmXaJP@Eb!%V>maOFz8NZ_m)d?apApC!7J!a)P3sJ8MopVX_oP zY3hBWk#Vxtt7l9^rDq-HB+bv^*Dbt4BTrpA@j+7~W{45SN|e;$==<5d+M{*{dR)?U zK6#zm^+>2h%jV!9k9k&xOxp|kSwXm8xhZAs;P7Y+msFvMPb9FQboq?c+zPEfLrKkj z{q0iSpAEn{<9q8TcszMjP3L4VbJW!rcgm=XsQqrz_H$_L&dC}#Y5~`*GWCY34-;Aa z!N3EoP?~Q(ZY+#GQQdcW`iSXRY4jNUq@V3I(E6nVbyn}HNBoOJbq|Ie2V8%AGVFJoi~=Pf ziU7tYUY&`!ZjyeT#2VT~H6Mu!c`Nf{^5QLMK6 z;s1~zo+MAcd_0b#(K?%TY=Lb?UfKLjs7XrN>4Yr9)tmGv>$9rLd7@>Sw_ho^xk%K; z<(+936C;BcDw%3=1E}6}4__~Il{xUV8&+&GV~=)EP`mzu@b3*yrDp+JB z5Y;dpx%sQR-?(dN58V0qqJnF5xrriV1bIwdV<<1D>0Nge&1J(DvP9X~T)e*AFLLV$ zYzQ`Gm6h&a{P7B7`6dPqcfj9WRxOq zzc9JxJMkDoVTi*251^?y?0fR)zN~t6));Ooo;J$zvP~4$Dx$=s!TE)dpX(~xPLv#v z)&|OG{3f&^!1>;#xW{UPb=UT+`8mPH`UOLtwk2l>s1KGn9N2tNS9c+=CnMt{4L2Y= z*)mZ2*T(*hOOdDJBZ-X$sWDD`BcnNS*6|7LMKcCo403J))l3EnBe+zz!5hJ^$WS~O zsd?aEcJLirJi5&$hB@B^>_p`x`ksFTZU9O)8i7PaOF{!E&unzsl6iJhK$onwKmVAe z!I$kPYA?T51x@6jtTmlO?lT_T6U;mdu1lPScN!r%zt5yQ$L&3YJ1cc&E#UQ|ilk3W z_-d2zg)m9{&LVnxA+qktr^WTD)%!oAwq^6u~7O1$s>nJAW#eV?F=h*KZ z{h~`-r|+_j4i(FgX5siv`@}GG;(vh4pwyqC>Y1pVP5T#*ovTgqOz=gE>g>X6X&sv% zjZni5S1-(kJ&on237ZoY;qGa+Ov**q2p;_6HV%^`@ z(e$&K5e=s!AKwAjZ+y}9$$SfhV_8DQ_iCGUp=7>9#5x~2L|DLGhCY9w)7w2c+_2F* zN^Jts#Pts&uHoAl%D5$^mE!M8-~6twODQwz#*EdB3^-^0;bup*@7fC@yuM`Y_zE1G zc+zAQt69b|_yzuCnECfp#x}e1BX$WMk@}0WBL~O*k$=BPM=cbVe<#a+N=gq^26oa* z4z8~s+>x6Zds+yO#nd4qCo)WN#}BM}Cu~KIScwhb%<6`Sh0N#NVq&rH`GuuDf$)9Ct9R?C0^Evj&%9VV`A_bvC7s z{XUea|BNWIvA(uZn$(R-`$CA&Sr}Uk3)s|t>G|`{J?-d@R)&H*84qf}RX@8wIT9|F z=uVw0gj{yXP3RHg5wVeG<&zEL{6{(x%aM{MF#6bxW7@Y4Asq3{F3bhiz?-Ve$UaVt zJ|}}>9R4=yaZQq@x-Ezk`41>z4}TG}wodrj&SlJ96Vy#qPxDCH9&wN|`}^8ew&3vx z)@7Ps1*6gJ9`k}qQs+afC>?p$!uzM6pR}3fwDrr|nIHmDV>eiSlux?hC;wbjS0z7V zxM25pRq^CE(4M7PHAX@o)NltlWo{G+(oWibxD?A&Mhr4?m6}AdS^L0?C;Ai?x z{MrgARo1wo>$ z(vWnRB4yTgeKDQ&Y3~2{d))L;44;0!{`sz0RlTgsHuzskpKF{;OU3%mkr*1A2kOgG zwtH2_$7vV^!j0#v`>6^hClehuVC(R(Ze)<^2*BZ@|HfR_Z7v)cuQZNEptA;oi>Ys0t6;zebkQ z)MxCE_Doz&%~nZ6Bil#JL&3Lh`UL7TilAs6!L$85YG8{>@@_Tas(cD zVlXS>S6W!yQGdBB3~V#BtKwm`#mSkrW~X!NTREtD(|HOj&#K90%CWD#3$_G$Kwkh= zcKt8UO?tWzPjNx((`6V)U%v<@rO)Qc2U=p6S-TbIf+JcYtH2fd{SPeK%V$S-OtKkqGf6sDdc z@3xhHErnsiSsbgGeI=eyFm7o0EU=5nkRJ-lmOPW*R&@dKe3V3rX4SS)VyjM^Jm;-w zr4EqYX)=33UHAA-YRZW_(&9d6KOzVT(F%SUZfo55UFrR9K8hj{x2LNKBS^z{_{9Tl zW4c$2&N*L1Tz>cc9rKhW3}+4^KPuem8y`HA&Lw}oj7kyE>=XxOi2n-bJ@0>Dg~~Ww z7Vb+dU-8x>%Nc5VihfY)XS{o{pTE_{`W5#ft(^KHRm=AipMNG;vz{VyR`m8G+=KaJx{#c=v*U zp^t7LQa7MjdfGPJ*gBx_L|HPEGh8uwSoc8HOf~nnwsO7JWsloP%s9c}^|Dgc<7x97 z1DZc085Y=M=Brygt*9pKcRbuFomud-arG*(L}%B2hpZbe4>x18ytiK|?mL8kLTos7 zIW)qqFh?;Y@6oPu`MU;Z6Gpt{_%Vd%_RhCITfD@dIV*C$YcCgu&-7O~yE#(Xc^~fa8U4wpm6;g2qJR^Id1^ zn~L>5OJNiOk-`tWOb^Om5;|@yQ(}nAl70PJhcc|}{&M2iUi?0nkkJJRxBlGyi9hbV zGcd->yzQ3g9_(`9Z5@8zAmp8C0E%A`c2_iR-VEkHwr@+Yi@i4PF8_5%-B5f>m$`Iv zl(0QaHlQ(9{%zXfKBXnMli*3cT#bB;Ow5I!A#LEoV^eS#epe56jUV{D*e{++#T z((m6#E;@cL{>3`h8Nhmdrm?&uN##S;hT2wOfWkusN)P0%d!Cb{?rA;zlgHnl`3k!1 z%>sSFwVz&Sf2p1qjd7)Z)kV3^Z(c3C`+4=jUQM-xfT&PXvoLsiy|g)iY42?7hV^yA z4&g&5%A&@1YZCY7tCRlyIFm|vVc;6wv6!fLEC1JVdRZ00d#^|z0nAZkuH+BY9oepn zJ!8A{diZD33gDm*lPZxw)16G#Lc?BG;iW%e_7B_=GWk77i#v z<@i`^6(zMYzqKgo(&708_Lapuq^a_+df-pBpj~4 z$S-xoHkAtH?md^=gnwr2tp3YjPECYg+Ew|OCzX8WTie#REIn5EQ0ZKx7`Ut7yK(zP zh1RM_rM_pRm30Emeb8A=TslMxWAM*L2UHTh9s=_&Y<>q>Upt2zP8OU3j)@uG3y;4R zyXIiLKRVIuZKNb@T-~8P58Gp@n~#^<*$p|-U2(Yj?!+gpu8rJ1Q5V|{9Q#t zZX9uioWuLhwf~lX!8>0szi1}Md-+gYt(Z;16Qyb^(d1s&@%N1kA7)G)2y@Sxa0+{U z-BB!|0CLbA*A5$V?2Yai7*!wnick4G^bL5IJ}R#(*<FH3L+cS|=G!q_ zMM}GYB4zJyfI`yPI0R7#_iD>mQ>)~ZlvIQ)t2A|}DL1X2>PCiF<3TR-wd?xdW&NG3 zzFx&3Vc7s`r#v`!6s=p)95_myqtd-nSITzwHif<#aKS4dOP(Ob%#z}8Ss@XhsHc7a zDua+Fjk@Zrd{wNvn(M8S4hagmlE-g!=ry!U_c}=IU^qo1ZZVvjocl2k1f*UZQabp# zaE2k7yO_+cP4&JR9N~Z2aw+03hC7F0ec(FqvKz|W6~-mLR&w(E6N{1d>sG&XL9s&D z&ArGD=LJ1T@$sAOVIM1T4Sf;UOS&zD{l-F-)1WO7%^l{L$>^I}jWBsg@0e8m$Lie} z{ZrtFQG1y$GHJ2v2?ZC@f?07+^~ISj&hSm%o_jqLxYm6w4DG%0r;ge z>qrh&h8J=^(wU2xN%2I?0wr#yli^k?#l_UK&cX?H0t zUe?;cf53$^U>_J3(p@Zl?AXxPYt>Pc*B&78FR!G z{6m^IF*A<-sH#cpaql8=jna2=gtL#!^1uE&)th&;@x&y`4Dgh(G8EF3JtUv<(@>Nw zyo#{d;&3mr|Ehqwab=k**^6Ci20f6yQw0T!ELly-UvjHFL)rFwI)&ycnD@ZrE=i2O zdqp{h(mykh9yBfd&?2D1wnVR4-wv-?>6I8R3RIsog<(6N?w< zKhypLP!Jjq zj$5mFmngSx!16!f)P%DP_i@tqJ*E$>Eq2i~xtsRjAh1mDZIGEtO6=P@2%5iT?}?<`Z#szk4`qJr%TN5pz5c~opEzxnXVr1VIJ3))%u}%gGK&T=hdk@C zW_^{nv`DEP`LK;YUn|z9ylfidhpuHughsvPznuuZMpAy7R)6YLR-C;Q=p3o(=*sWjmQ*dot(zON*MK($u8NtvL9u>2SvC zN=e$o3nd9P+;kHh`2Cq&*vJZrbP@Zaa zazJHl>dI#0gn+y-B7Gh4eh481foTl)SL4E~4t3<+vwKNoGPR znTg9+5gA{}cE{x_L+rg5dY%&f`fP%lMz#1OG5Qaoa1f^$3-!C~aY~0yNHpTB6oa|x z<-j@RmjC(cZPy1)F3bOV-MN>AEP5gSzBWo(K!0yDl3y$3inIl` zn$uM#P?j6B5s9$TDh(6npfM}+(VI43|Bf%=aP^O{Z`F>US_A3KB8t)7U1@{z7-sIS z%1Cwaw`!82UVo9Wa$%bf2Q}XP3W8-x(PYlcH+?gm1lA4UDZHthT@qq&%hy6a`ZpEK z$W5xKfalJIH(_G{%&GLCX{j-)gYE6m|1rxNvF6|RuvQvRlS^6WI>2+3xc4*6m22E- zXfVhDXP$N^)#!p#H1)2RgPeO9IG83N)tbA?+qr@+*dwhMsT(A?r+I@h)%BviE1k>T zv;-QYNPkt-ld{Ip1v&S5eNqT$-~axM9??A5ASYiLXi+M$igzAkld^hcegU6<8$2Qm zWX0h8K@IhEV=T-XcR<@zo#9tz=WE&|f+TI)#$TH%oQ!&NQd>TVrEg1usp<@M|HU;? zqS4t%2Az}~O=6+IAocwOojQ=sDy*uZ+6o6u*e6g!;aI&Qyt!E-0M$dkNlOy z;g%ak_RCkw!FlT;woA%O%yGORr^hv^U%!?8EC)Btp5a;=fM$Me0vXhTT!Gl* zPN643=8Ei<&$TD&clrK(yN$A=hpLcQHi<~~&_?$P1jwY(Y z;aed#MptSzM#ae#NP+Fi;dD%$EBJ;=8(+1Vh(bgJft!GYr_dVIDJ1~^(A+Ks5p^wm z)^DljytogHziR~Ci61%=t;!$&EIPVpC)5TWXL%E1f+Uc-QC%6F$?JP+Lhun;0$b%C#Ld|g9QxmIrUa}`Q6-F%gRKbk0n zR2mdP%Rv@EE|toqE}$sJ>a^FPp$O{EC!c;HaH48a4#c((p1vzQ3M$2=xMr^mog{+= zHy1M?GlmiZh8li59X_T7?ceIgOmskR`>0NbS!m{y#2Qe*xw3sPAkpm5z>t(2=s95J z0ceqhYEvh2P6-lcMm{-K9;>0#+#dN}CwNfCOG%D}pwZdfi%kL1-L)1wVEX$!nFxpp z6WGWi^%{hl!h&x&IRDMNNPSf-sWa39tu=eR&&4iilROGuxCx(S#dBWEDR4;afuvRU z38s9eI`?IS-GT+MGVZsMUn(fCfw9iTXE`YgXaLsV2vp7-7PfBV`1P!#d1sIVhccvV z`wFf+D(;Id?S^qJJxugIn9qCMB8nIPT3XV0oyP77SDq%+DHWiG|Iv#+3ORU6bZUb` z=DV=E zChO-7HdaxM*e|t`iD$D%KeU_UBval&km^b8SWq+~y+0NFG;txoQ(sPTz+P};tA5$b zwkWGQ3-q|L+Fd{{hj6$;!h>7aPuy zSOwtzGP*6vjKoS81qo&Ji7@8d4E3ga!as8E6CsKvMpocP#W{5fhL|LB*4}=?u zM(fZ28up=sQaQ5|ly|v!a9rvSl%AbUin%NVgF*{HrCsx_B9oyVr>IxG1%oKC!HPrJ z>@1faB6c`srJ6KBZp-OF1&Ot(fc9NWv(n=s99R+?VJX^f6XX0fWH;=7q{3|mu0CQl zlt8vogx+%ku((VBK9GY_hhhHq@k8S;BOdqr^z$XdrNG1TWk9MJz%tj--?aJIEca2^ zv^Jo?HkqDoAKE*7(;8Do`fQ1mScgn{& zJlqB|8pxlZOA|K49KkL80tjO3Q{0E1K+8EXR`{y=`&u}uFdq(L1yu9`aL0NDHB-5c za%~J*9?U+MG+m*K$1G#mt&6=#m27|XgaVJR&N2fm>E2fg%br;vR(5QE5@n*RsXtA) zSMJtl)`oUtrAj8O(+3kqX31i}W7*^8xZ&nH0b-wE((|os!T=2~&eU$J&aS!c>aPk?&uVk0S29Pe!GcD4sIf38KgNjQHKXBas|CD(0@BgHpB@)=kce z=<%2);`>AJBXk*nspW|jpv8feRtDj+r5vmE-P!G*%tA@t)cxYUL{T~T|BizE4_7xX zN#_7~N=B!^!(>JB)Uyx@C^Eg+EH|H&)Xm?r{`kkDCS2D&{;a4Cqgb=kpYsJ!uXb0G zW6u9i(FYJZw~bZ95aa4B1fg@QTPv9XuxKNos&|WyRv>_JSNAnZ&-hzwt1|D%L-63t zJ>jh3ANndMmdH^W`#Y&thI_IK>(ZB48u>Sz3)N^}Tt-$<-HK5ZZGPJZU`SwvF z9)cR4VVT`MXpUDRtrJ)i@dgg+aJ#7_5Vmi?WheCg#W6uKI>^{}u7SBk)@RDx9TYHz z8O>Z7G#d?Zf0>2xWFR8ZhI;@R;1Q`^L;K;5?YQBHIuA6w0Ayo~+%{P7_viX(KPRI0Gf3l@WCgV7^HJ86SD$W_&oqISebPvNML>8LVW(Z4nw=}b)HC_6p;gKmL8{bFGnE47o27j2 zLK-kmuR`(Qkuj62XWps4F;UM&C1S(P7XHo`;k@}<@7#=s~PKscB3Exh*dUkS^_5*07z#?2!>b+ z2((bs)<3|Oa@piU9T8Y}p7NmDTQc}QvEwa)p{y$1O;Q&T+P5hw9GR(j|7Ov6D1myz zD(Wjk5tW@M0vm#&5#e_s+GBow;s^q5uqzd=+?KkFCUveGI*=l*aqzQ|T!(_K1Mg6! z2R@1U1Hc`Zlrqd&;1~J^3yyz)Bbl&xcXL`g5Rj*YfG#cQaOj|GWQIhP43Sy{Q&*&x zaH)dA_5YM!LrFYyG#n;41?#jFxLwNYMK1CNV%z7tJ1s9kGo}&~YxT9*V5UJ%#l*!91x|ElS5b5Z z;@=U&e+4bR)ulxHs2~}jM$1-qr3sgM@*qluOJaR74sPQ748end{K4y%6imkkSO^}~ zbCa)8<-{A>KMP)&RSUJ|SB{bf{acXg@p`AsF@J~>^a&JlmPS|TCoxkX zR=72}V{C=)zKa#Xba{EMhA2Y>V>BWUXtH`YEg^%-?UL$!)?Vmm8Ya+z$Xc)Uh9jRyxeAGRGLBE6^_DZdW2pjzbyl*=DZ5b^fX<)jX#5{v>aYhD4+^>NuN|&Mp|y$JGZyI7--3Ly1uiIhKRfnZ=1&R*rq@S;AgW z)9Q{=3(1I-`aoB)vx9SrC$ohHql1%!Z#8)7g)48hp3nNG-o3PauZ9#eD%H`qt=#@| zX$ih0W#O>cMO3V7AGS@z?Z)8pRA8S?n=tu_7IMwN;)r~i3uV1UZjy*(qzwlP2Jl|G zBICwZ;YhCJlF10GJpeRy^s}W@8w3p zXLMR9zI(G%Fug(ff9L-AO9LxV6-!_tY(m`cPE@wcn|wAznw|#uh?u5OF|WDzK17YFADHY=cv+J%%p07q;o zSlD}&lR^KZw<)&=3ChQD%?uVgF#JVJfdwDUZbWEL^I#%|RUvCfphcRiHeKUC?Et?7 zhPw_~zi1j&r#1Xly#u*!566vl$U^Z@pO)G1@Ip?Sg7}{3=$-Jp0-DeGB6lued$8twsng66pwmpHMbhdLOb#4jx)U{!$n%G*3H!=K4B z6eX4Ijn0rB0$qi|8&&Ql74((d+Z%xzJP@lm(v6EjM3cynvQ0NjXix(XUOOb8@-88f zBR~GqYgWJ)3@g5sxpvJTOD)ZYiU~tF1+WQ&zPue|f0Oyh>-n?AvRE8$$`sO$A|tkT zhmtL!b$|6#@w8|eXc7yTpiLN+&rQ@LgAUCY(rAWHC^#sv6rfFzuo|FZozbvc7rz7D zxuEo2P13;m+m3De&Y@=c49GuFZwvIJOC~nDzq*q87QzWu(JTya=}!ts0^rO;r*F5!CCIm-<3El5MeX<;Yb ze|7SVP20P|V^Qj~T|T&uJm9!T2v5vcs+X@KyxS9ohJoho!p)!6zM~0reW8sH_LQOO z2>%@VcVj7pcu3?8fZ*Wfsf3887^HMJH;+bxVJZO$uQK?9An$`f4*8Rn`AsrgGMXI^ zoHbI;kwe4fb9x6-9y)=|F2xuG>I;c(M5diHIT8{P(F0WKMa7IK{hP{DY4(k9x+v)0 zyfA-+%?0m@$g!c+Ft#TsZE<`1Bmth+7f3o z;GiCH`kFiUr8n3ZZTv}|V>Eb8r6NN@yW?8>So9)1(1| zflB8|NSgF+k!J4tj;$I8kB822mh!du#efqyBgN<8CM3$1LKcm(+jT&ivD1pU04ZcI z#RMahtq!FRDbZel`YdzK39{r@+K3rohwShm(^iIwfbQaY*XYL>yEgeR&A2hH;Rag- z7@#9Sg9h@AcCdyPp43h0`Qwl<5}4!HxhduWgSZ(yim+W6GM_US$nc*BEhm*wTDr`8 zF5hrRZqr(e&{?R+VbtZ#_ktp`rXAP^G>Rk;!;B@DBxXX#8FQckIZ&1V-(Y0kU(e z@kvK%)B8gP>ze1AOF&z#hs)}Jfb~)aa`wIlH8p^uyxq?W13B1CUb)cZ09LZipJR3+QeyWNV)d4E6u> z6`b)cpeG)9xwZe~sXu4JnJk2V^U9l}CV@{CGQVKPx9@!ozBl<0pD;zlf?R9Qy62;s zs3b6ovnRyK<0Ag8D=_k$!gk zZGrW+hV4U?6RijIAHgN6Wyl@|wKod&KL1?KI`Im3YKY09dw?;-ph!zYc<`dCurOE$ z+Qvuqp~V5ghdWNG+2X*PLZLV~92;J0qiFr(H2Fm`;C0Km6I?9B$mpN~@4x*f*ezZ8y8_I|XA=%CsY&h-c8vbKagECUV0{o>$_BCQZ)w;61Fm;ZbSPnA z9w8y&sz(ndCN=9s&~gyqG{EwXmEFTz?KLjqu`D#Wf+qi}h(1Pk(=wG~Ht8UIBUA0H zR9kP}ZCy@o--|VI(w!{3WApiN_HN*Bol*0w=sf>x3M3I9iNhWgqhqCT-Ll6Dj<@?X z5;}@!{biQkqTiS`263Pu+M_!@T_Z$-C3!GPxSO?ZDRetwJX$q|IA-GEk49qtlzVt3 zybfyP?cFU`N;7$_k5`h_4}Ne?(yRagU|7EmJ4JHtjuk?l=_0ffOFUst|33D4oX_OI zx$$qlpMTX;l=O^&Q)5o?RfDO|15RzlA;KZxaNXWgn+Q3S^2n-*&@KhqXO3UgzuTcg zz3XPzjP=Dqh~cUk$;a8H%dVwKy|CiQZAaAycJ@iXJxnpJR7MR)a0PX_YmnU_9n*64 zaYh0BL>7T1zg+;ul;{CUff4@!m$$@1zS-?D8y!z#EBH%LdW@|UB^&(RC(sxc1D!!N z`#=)^XtBp(>d-3;>s%vXognM{V<5zH6{IyBsvnfQC?x!Qssc>#DNLCa$>j;U6ISrt z0eW>syr>9D?Y0$<3r_d;{e3Uptmf>+ry1ba2rH-<&w;_qYR~@)V-)3s=CGx9+1Gfl z2V1o%7GNe@08-b#@N|Xg$+mW%-9X>CI1LARxf?0F^444UP+~CImc}oOox2E0 zKEiQj;b}le>5RS7i#fWY%3}qbmcbn8QX;JswTJbn&0gIgbPJh)j~2{q|NW@6t|i0G zmwsFqumxA75oK+auQQsSg*9G^_`=}wr%ewfS-nDOb>>3)Y`*Oq^>jd`0h08rZcj7Ww$Dw6cv`O=O z+!(#5lQui&+n5)Jy+H}myKLDwf=JHPMR{uALE>lH#8NX9fAVvS`?y{rxPS4v$? zh!=(S77H21OFOcoK8uKB1in0;4UXBBpmy3@Pk0yr%@2>~RL75d_DawU75wFPQe|h- zWvZf+STOQK=DT0X?T)j9;3+UbG-%tV?08GhNK1~HSj>5ql>Lj|d2A~@4t4=A*FUXl zZcjaaXw+`3?GiHA7@kug(W$An5xpB40C_N`iQ;_vf0=VH-)DP%w(U*D!uET6s?pJr z2`8h4)SFv4SPWSB!shKu!U*EHJJ>z=9hFY}$g{{BOU^MSJ4am8^g$aHT7Sm`G@4Y+ zEnrn~qQ8PZ-R(K9MV3Y>E`!UM4<~P`HJhN@y!d|Ho5Lsd&LH(kseP;^)=F`}dPP6m zdr+()Uw1QHwIEE`Z*U9Td$fA5E8X_&Oh36h)GGj$|6swLQ^8L;xPlzP#m{w2#c%&z z*Cs8TZMUj>aId5L-m&dt3!$8W;K)7YE+OA0BKOpwCLDt-9=BF7gT};VUmw9VZ|-rn zi1aV3iF}0l_6j2XSCb7I74q_bhjzoP(;mbb-2LY9c#_ zLZ;@f8@)e`pU~oE*3NNc$FdHn<7OuoijA_ynhgHRn+l>D?PaIN3|NKi$LrUZcQ?Nx z@1|!+J{{SJRIU5k<9T{!qOvv#Z7ysv#0TBs#Zg1Q#!oOf-Kap=LW#n9XTZ9b=-xfa zL9N5~mlZ%!)BUwn1ALP?D<$muBH2mfmrHCraO;z0b>g#Yq?RcVpdVZ$^@*(Yy9tI^ zq-9p&yIxG7y@Ej#wlvIxR{0;GU<2aSAW_bAB$3Bs$xe61lckMqUfoH3cgt2NH3hot zvP@op(XkKgl6`k)X(LLxJZi)*^Ml?vqoDYq+uiw(^Y&e3^Gu$Au@*K;n2VPl1kBY^1ps`Yzyr0=dZ-dW! z3_{Lr|3=0HSPd@Uc^Ie>vALTZWvGWp_!h3-^(JQI`?c4QJ?)*}l0fjZmCf|NCo)f! z2QfGm3{v%d#$m(u#>^CnY<0Pgg9MOGZaNzba^bq3{l=s!K2Cc&HwR5@V9(sVajOyG zsQ}esqO-vm#a}P(;e+fB-%`}uvHW7la-G?c?b)VaPKZ^dypU0s8uD37{qxs82Yz^0sCwT1fgiVmK6dk~|DL{K{g0%mn=WWDH)!bCi*6Z3V{MOd z|0WHM$dfR$D$}9_|C9YrC)x`;9VA*1fj&p5FSxip=k4woBkm5Wnp& z`e-hF<|LIZvJO{0J#z2RJ$ofWopS(p!`@cWPt)RTvS-eV-ZiE>jLm;=Yk2OSo4KzD zG$T@kOP#oWOB3M~=B!$<(L0xyoX^KDoi7ijyFbxjM-FX-N9uAf6b*d;Gz6)Q zaga)z1jlNx;H`Ha{z?p#{s7TZ9v%$q`x|~NjS}#QiWc9W!1%{G)Bm92YF2;i^S!cq zPZX9j#FoFQ&we9+d;S+hAla*!8UM=c@h*IFl*1D%(t!#Y3rk{T`=&oBmR^u3^C>=e z+b7S&JLNwhR^7>Ei*x(=ac?J+2(S`0xn208$CTsVigxWG)bX*HxACUdI(m!PLU?n?0X^wfA?sNC9Wh*jT?G<&v*`ZS`~ zP~QwDW}Adr<%H+|*>k+#&879C)0a=le`{m3rmv@lRZ6a2DUt))b(bl+1lud|Ij7ci zT*)VWfH}gBtPE8>hBxk+Rn-R{^-#)YHkmS~R^}}?Dt??qD~czYk?OOoL-Cu|>A83O z%7~Jp__6@xqG6?Z&bPHJiIZX4^xD|VpI`E7>ak}BjFjeWTsKm(l0L9S(CfZxI>qWn z=zEHu2I=`u=j59;A48{CU`Z34AsC(|x5g3)Pr(TV{mBZ~@lWYDbb z;qOq|3s(2=N6|n_xxnXR#sJq*qCDgI@2`CvI`rv8F*o^|b@E8>!B{cJ<{Rb_4z%k_P4^YW-xI<}#$rgwXjGWmkN5-11`US=e2W>uU$DS5+{KmdaW+|FT2v-eL~? z4Er%r(|C2N^Vcr+i==3;+jcus!1DI7a~YEyBN+khr>?N)u4T`#TU4_vZJFPeTc6d) zV+~Tv3q&2iea!fnkn=OH!sGX8?cL#phi?U_z%X^VS=wOWdkL`<_umJ!>o-0nniHN$ zDN$QX5)6K8k)upE91WX9*H$sIv{NtUreaSobs3-sa<>TUx3VCNYks~L>zd(H-mdXL z`?EfFJ5OXP0E#LGR^L5X)M4C9T!CndFSZk??;lRMJxA$HY?y5Pscb-K-0p{3Z!yut7YGxyYN_ufNa=v1;{dfW##>=r|^l#4%d$U zwy4n^58>2y$4`2opUaI`KX$9vn5iI2A*%>ktrfF#ndhTDLY>*T5TZs&NpZ&Uy#QO% zcYm^-i$>HRiIy5*(63_iYU_Xn_S?t9pz35ULy{qT_2Dz&??sk@M*cayGehw>As^?z zf8JKZ`emgPNW89>0RkBjVc#>PXqHo6rmbt}&-Z7BH%9xtbp#8r748#=09FX)9_Ojje^3dc&BxJ+V4x$OL2A@9@tl zT;)tO@64HNKSUlo>N?r{eERVmVoKkCoDwvC^q>h7hnfaOs;?B2JaQft#Gid_;{uxxd5<5sB+uK5 zugXwEGIq*4>r}u0tdHKc_GzX9aNGJRbAAGp8+2`H^%LHxsDGNZso!4Ze~ngnSgaA? zY+%P|vWHVKUO{Z44w_yb5b(XW-?Yy?{(@e>;u0-q5ZqD|{IXQ1{PA%ctx*@1FklK? z_i!cCv8Hb2<3<<5>z_k($l&TF*~kQ&R*WQ$8K7#_BU>uyjXX zHNT2=+oBMcfE`=Nsq~x&rfNxvT12(TQH&gVrJ!ZmE&13)R%+GuUBa~_`9had(7g26Q87f2rJ`FuQEZ-tHIt!&40H5WBQ*WFJZQ&i1@wm9)wt*pXJm-}6M->V1j zKq#5OLpwFda+C%}&qNM2aB5T6T}&!#_TOM0lRBI{zU$w79-bv2*FDGBV<_kE zK=flDs#e@*_2yZXPk-#D6j1s@G@RppM}581n>9(Bx`9PD_!xQE{xlE!)jAl9ft@cr zkNh7r>Qw34(d)9?xq2ucF*knxe$E!ZPy_J@8?AcxPPbA`#$i)&9_-g;@_2owE6+&7FX9>Bv@V_zc4 zxQ>uc+FHU|zNto2ot5QmFOD~zDVxhZIm!~(?bNv~MFkqkMA(m=dBvT*+xb7}OucSX z`OukfvnuD3MCB7B)iE9Q$lDLC+#lS9LjI{l_^>{Y^Go5>~b?@AMjXF$<11O*?9RA8Q!ms9zJ3+mxRt zCr}=Kx^EApw|*##)>E7(*S90B`(d?jvIlrF35GB+81B?y+-}leONs;yg$L#7J59*P z5mU}KeGr4~<|~jX(9%r4$-F_w;00E_Q_eY$UJTvCSqN-m3T?IF@nl zDU2sYJdiFXBa)95f2n=7dZAekUhJ=0VcgT-*Kp)|%)`*|pd+zk=W|z@ZdIyPcAOYw ztu217I#QmnC0}l+Tc+&jRAVQZP&#VS=n%q12j0hCF7EAC;qBXLqPB<#yA3k+*lY+BhTys*R0C z31w=3ysdEekjJ&C6)EshPMc^NNv*vF0br5xF3GCb(%ilrNaS4zTCM5-JJ@bV8n#y$ zHnJ8`{&M|*wep+ne==30wCK^cj_(VvyRAODlx3(=NOts;4@b4s_bt6u6@I#ikU!%v z8-X#ra)Vy$92TtuXCe)brX6|u(m)f6Mo0VmC@Rb0 z2q?=tkt<;Zi1Y~IacTkKYv=q%vy)gf?7^~@tGq?6{?weZrvxpL%0++wQM}y|dETV# z?|-ke79x~lcb!+foc!4QA(Mt9Fzr|KKh*}?ErpMCnXeTBSnGS%*!kG& zG8aG&&>5#$o_y#EUq@wmRbUu{zGSi``(9q$uPh)rI5{-@q9$=T8%ov@|l0#71W4?zi*>I=ROm%x}>cKJmOd zLuz`us1t-3s!>~Fysds|2$g+sS2u^Wij$#-7H)x<6*tEl7NKHCVUSLOdd85v5e>Y^ zyS4WRJ+)bNOB>cmAmXJ!TK>qBXBqYpa<{B%>*>xg#zxUx<~1gJXd`NI?4NXPkN8gb zQ+sq;?rC~-x5XrH#Kra-XzWY3bSk&N@kC)?QDdK*Mswf4I#uXA`R(X7?w|5Nw>$gM zfiLKLoT)lw4A${(`VK!WHZt?52+`qzJuf5;oEdl@mN59UFC$6?qH%`#~g5!U;y% zLrEHOQ})Udj*pIVwJT7bndZd9l?CauGd<77?UgC6cTo11EbbLSR_t_=Qm5CVypeH_ z^7JV!r8N*u(Kss1iK)+c%z7gq6QA1z0+n-s7PP+*C+qlT2Z0<}ly4h<133M58x4>~ zCCVyWuh{@3%$nXKyVZs$5Nu!iL3tZb6#=XyZjfm|*i?#j9elLZm%#1o3dMe*CFW)M z3v}c9d5~6N&YEM{%iavgPwS$gPCwTE=f-do(F9s|D{EIaQ{bmkbGfW>x2$_4+v~#D zDp|bPCx2Md>t;H!B^zJA-`;X)hS|&+vrm4g0<|;z;AQ?E*&pJ)&O1opQe9Z`(BFdt zUn24C!g8+@Ms~|})M^T@SP__R2B+4BXHA@u1Vz<&2r$-w!}`$XkD3I+3{$lQ)2b{+_lRT&FKa+b80iHxzL8y>c!$LgN3Zu zd|5nT=OMVX?m?rHP(k}M^>3Ic_YloB=2xR^NY8k0SU%20C0wsn zcGHvSh=n}4tNQ78Wv2;=AWFc(b>qQ3NQ&vossLVT`CO=j<`t2o7OsaX?rA>%9~4T> zB}>qJS3H@gjx8hd5=OPr!Eg3Eu1Ykq0@t&E|>g88RSR0I8rFYC|);`kLSpc$--nW5Gz$zHh8Thdq1gDs33{^#8v^eyXz9v=B2OO%-k{n{bYr zfCF5#nzM^Yd61WqU2-UOL#HAw*Kzt!RiZussGAHY0d&|{73|*G#|-aBXCKA*0G~&N zSXz4gZ3>qXDPSVzixPA<^dS)+%oQP@ZFS)n$oK`UUb~TrsQ)s9k)wN|nKhV}`>pRm zmX|67W1@5ZtB>Gr<~r7l_}Li-63}#b$kTthzPiihFsELvOZLBX+IsYf_*HNK{Fd4%A;z9&`(I`K#Nni=e3?jSy z4X7CTK&J0R{hX6juKpRi-kjhw7aZGpnGpcxSX~tWCIZu#e6dfNl~wN^JA?`4q$bmM zHL)>FIuj3Ma$BYOiV$HYE^Y~6j7<|<8wpV{ZjbB+J{af3QM*$eauja)ruWA1kJa5pZ^>L?Hd|ab~uitH!_qJD{)N!k$;cVr<=OslKLyiv^$0T)i}A z`+@waO@NKQ z_mrW|48tG26T!rrG}j%vs@D9daI4H+ZHF^k_#~~@e-BwbPA!iW*Qg-mX*l87YU{z`|5;6}u0Z_CZCj_g2$pO$SAnNa0j| z$Q;44E7IhsbBB2-SC9;`EVnmFn=cWb0YPs;z}tWeLi(ZASk{tT!rw_AWvKJkBGI~X zi@S4$FP0ly882EoLB}6$`CyvXp6fHju%R0XppY)l&>v~kR#m;U1oim1cSkFkMzx$E zk5w=|1SSH*X*XCEJ<6}lwo*rNLwa0|zXWh(JOV9FVrE{3!5bvpqMB5Ray7UPC0n-FcqQ>NQx7?wx25hNLMREg!B;K7asYby;==4I%vxWl16yAa5@15Bp_dGpS|pmk&=Fl%41qB5lPof7$raz9 zftiWx%lx*;C>VPt>E!E~l?{Nlwc~mnwBLd`rV58+Sg}p_GZC^rW5RH?Xj1^b6<0MV z)+T5bYe%_EX~x~KvFZAFBPIg|Pq5C^FkpB^zwzub>M-WDQIieh31_b6s^wn zj`wt@qkEqWN2E5dR{vlshAvaoW*6s`eKyW+sbUr9LB2{znT2_=wJ#n_w7 zdO;suCCObAIY6~@PX*=KZ}augYNtGnEcx%E?g!7xKb%UCTowER1rOEfz7}IHPISD_ zYznT0wM8$i^dz^9N$Cb49rrS0QdT`)m22q)f1a-?u*5{soNJi(d4R1b7cw{5+6iZP z(p=phPkO}1wV1C1+eOouBLZt7=sA!dKG-p2o+D4N`j=tG<+0U?-=(@u=@ro=0`d|p z9<9n%3hA_55ZPMFO%hvIyffG#Y|k0y@OtSL@ra%18v!K9Lz|VKrz!xOl@FL`AIEME z9pp8@D-T@f8j1UfNyey#4a*>zM_bGtkBjTCnk~ffL&rtp&R0>%VQxwoXu}@c zVgbw1%SK^2MkEO5fIV46+E^9T4v$(~t@Q5~yBF%(oo~TDTzKkTOAKGNf@SG1K+gQ;ni{_k@JKL5xRkEH@y>V7fJ9^Ui4zcOMVY9F}-eQF6)H?{L7Y10F9_M&)jtWpaSJpJ4!JS_}L%7Qa>Q(o%Osw;%*Z-y2;c>I338 zzqq3-kA@`Zy@roES0jz|NLRIeELx&pJfKY&?$AU&Wey((&od={cf%o^)Yd-Gh*IA> zk&lh!+<9k27py6eY`d z9fjW&T#~*x){NwA5|QM)t@zwdz!OD4O4r7x$UL;x=QNRB<15Ywvvd%YL`TLlC=eXz zs_yHcaq65t&GV3rmS*vNXC`zZ{NRm{PB>NOmFZKw_)%>BY? ziH_qHNux66F&UE~!QGCR*n6y>yD){F|xgObl(b0-wVsKk#oFpf z5+SK-C~q^N1_eIdunU2Bg~IARW#z(egwYXrtY~TZC;{gzva?axP{oY@&v(=uJ!BJI z<1*^IxfY%qOVN8PV`9!crTgF3p6|1N`i|`*$y3O)wH5mYnSmPG^dx2)K6BdL>CB`= zV}BJ8OSmRdl;`n)fqAg-qRi%oa5Pr{HUfIExpZJt-7^>O-P@o^SB4;&rHRd-ieX3V zLO3mh9tNrq?f#qi4|;{>6l@FaZ@8S2j)jR@P49jidcY`znUN3wsbPkf zJb&dUU70CUjK--JrPn~7S33tWELKeR5{s6 z#*ISD^$5-19R#Uj>2=|aKzg=(FuO304uw}}Bujef&MP4j?hVMx{>3>zkB;8>Hc%4#w&LM;|( z>L@-pJlnoFwIZ2c_z3O)I6KOCMgZRAz~OtUD`7&ZuH4ZPI)V|l(#<5>;2=imaxsJr ztHN2v0j0i8$59@qNEeUU)+p{mtykp3-jq>WY?Yyc(d=esFJCFFpmX0H1wNHLI>&@~ z8Y9QS=wFD?guP^%gV+Ongg3FKhv8~E`wZ=s({O&wW{5nJlAqS!dy$T6KXtt(VnI@{ z0AYlf71Ru;e6XYErB@hBC@EOqiwPvuZ0WlpPY&+KS^B6z2-)m4(n>7bwMK~X39`zF zSM7+3<8e5jyKkIK)WXD^2LkWlnFQ4dNO_jp$SWEe2rXh;Q5=eEaa1ln(9GgCCYn>3?DTbI z&YqZsL2j`5P8acFuaKeWuWQ_FhMJZLpF*;st)kvodn*qn3fqur_-WD1H*UDj=1Ff8 zABdy*UGQbdZ?b%&WW_sS0HsQ(Gw&faE?{ja#^kFN%eO2X9en^N9@^S`NozUTLog;A z99hIPZm})$CtX{n7>|=s9XLb=q2y5#+N&l9VQ(cOROsT)sRGX|wVSTd=t|eDSbG#?0?1Z}w)5tdW@bDIf59?c$EcvleU+BR!P|v1Hr!gBU2H z^Rmf96D#sSC|U1qpdvef50f5=1$H%sMturO(cP9TQ07eKK-zGI4$b)eokpY09e(q9HgTxvsWZO%0-V(w(@7rKBHIiyy)#_l!cKM0uZqBkRwc%$# z{SwBLMsu0m<^D$Bch>4`eMYxYcw85}bM6OyiHH>g?9&TEpB~{1}#QE)>k^lNZe(l8H&^H$`5L_}Twt(3_xCd?#kh=P1|bvw{x-v7(1z zOEzeF#_ssf-l%&(oh;^9LOT#8;&(c+9v}e7q06{wVT84+)klwUT^~ZCu;4I-)}GE? zgCqJOr(?MfzYS22zMO1gmrUTKAkX7d>i}XScaRZBf;4^OKF?W?-x=@=$^)4|$7=5I zWMf~n;KYXnH?b5rtOv9hCLo!d`1;rmz0!V1c*&zJN1LQsA@o7B-1SNYn=Tw)$h7hR zm&Z#3-2F-*r2O=`%g_3i8w?J%G5qMD!7%bI+y0!Cbo-R=|JngE zgXIh$bXtx%b(WR)=$H~etX05_4k2v<{zZ^-w&Y5i>FMb!T+~kQ2VU8}2XOu<2Kp}* zL-u{{o6^_6yWslLxVs689cecuxF+}iXROx?1`e8LNi0~bb~YfPsuoe;$} zpSJY*t*n0K@rD`9mv3)kY=1W&tTJW|a&p4Mc;$aG%Pv}PG&8GeU4!7uUt3Dc_pSe% zmU=cY#@lu}>V)-3MU8K#)8j7G*!euCb!Eqlr&5~>Hn03kgLwWH>W+IAl{u*s5}&SwMO8}$BmL8Ovi?!E|}2JGC*i3CRKk<(@& zsxIal_jJB}eS9$E?Q=Rn(BnlzC60;4)#w%zaO3^cP`J(WUaN<$#0umr?rJ<+oEPb* z=_ydJ+;E?4-3T#s`K-c2Oz(?Z=hB$VQO0{WwP34LeL2gmPe3TK+z@Oesy6JjG}DNZwtv z4!NNr)Y|j>AD-oAi#0;2Nnd) zctbsz?d*8>V})Q6v=_v@vA?$|&sn}UYuT{OGzZ^2^#Eci)vq_J^1h~Jy!KN|Zh#}w z*E>)cw}4={Ld8u+(T{f-E7zMLR#Waz+n=&&hn9T|m`i}74zegRc)KTvy6ysms#Qb6 z-Z^8R4UJAaR1w7jW~Neli&H?0Be2-hu1Sjj-SqN8_*MASdR;78SElh{`&i4N5(y5s zLi_q5?5&EY+44+)@YP8I!9dkJ&DR0ertpu{5VZL8a+Gl=@`%Ye0TBp8tpqVaOW54~~J%;U{ z>Iaz6YW~^-Qs_=s&FE&t&oScnMd_9P>wnyNI9Bz_dd{|mEI;7aUF$4fF0pAZ@Sm=Xql2(-FmLDzfzk8fma z_0#_fipX|Sih+2wa?_Q)S(bm`L~Ke-<#g2q*=|O?G>OrQwQcx-5S@>_3_CIKNH7+d zZA5A;kN?oX0vKnFMqBrp#uNL$mmjI>Pzl`aV(Z;;DtB)DoW*n+teftdQj$vTt+Jn= zO6fr@T@1i;M+fpWS(9!5gL;3|#*b|O+=D%{fT>GqK05)&c6YE<>P0GBD;dAAK3o7#(6QWmVcYIi_(Yfx!P)SQ7 z-Y&lE)qxCRC1@cy`pxmThc)&H;&XDxH~je}WqnH`YANZpl*(QDv)qL8 z-p^pBH=uPrb7XjDyv~Ghx_+}+ehZSI)-LN~^>*ETGIpo((dqoRTWF$t8i&G|auI$l z!i#I!G0G)<)>ZTuxg%aOhQv)gqW#=-tk37k^63{p)pi$DX?o@i2>t}q0&Kg^P49lX z)u)`CR-*Ge+6ToAse-ZLZv(OHlWEtZ)M~W?6^Q#DA z`_y9<+ceaeB!NZ`Hp%kjUqRa}{j?|-mQ^7S_JS8L5CoaGrd=HPlqg41D)0$<^`BSn z%J&aydkYr&UyQ0Qa$9I8o(=pgSLYqRRBn)wY1GWLa_L<&KN&u<&+_zeG`6Pp;M8_Wj%RWx4jX4kO%D_nY14LieYF zECe!vceXk1Yzq5I@YbV!rM2>E&qU)nyyRaOQqTJKv2Snl3#|1?AMasSesn}VL_K(| z_)mHw7-H9K+WN=N-B-fpl& z?j)rSB;QktYbJhZ7$n%8W1o1M`JqVf&ffc{eAIyZ4QZf*Uv@`Ywz? z=Dw+JLHs77x?eeKv3qa*esOxFOBXSUZuzMdw}k4hNiq0v#;8gGc51;6;z|v&D;pAp zSGQI(I38>zn)g$)yb1>w#NMz#t$$x3jh9c<7P%CM9Q-ZMN#d%Vf^0R_Q(XJ|`-h+& z{<|$gz+5wsUv-^Rvq0f7M*CidRH;1XoJT#Y%rB8Y6seW+w14_3-hq&B@sGdfjW1;r z{TIJLnQa?)TvvSiVEwmnvHN{uYahkLwW2K6CJmK+@p=886Di2B$NP)=D!xwK(d-y& zRYUy+f5h>=g<1Re_eIUDe4GWykPw|Z&D>Ww2hPotXhl2h!H~Fl9LD{2!JRLZhxiU< z`UdFpmis{$kRxO(7n$s*%QGUUz*l?zW@KejGtv5ZL4RNQ=@uMnQwfxh<&j zt=)GZjkC_lXT}psf7s0Y*!<{_Ql@&tpm_Z6JO2HL7k&*Mgzc8LrVPOPt1h?Q-s*iT zTvk)S_M2JHD%l;W^6)*;n9np8NmpF{eG>dukZMF*Xfb9zl{sJ-(@!YR=)#tjzTeH4 z*3IQCNy>>P$An%ambSFIooNx$INxH>vt9H@WuHlDFibP8Gl+Web=Pdvb0st(6SR2$I|Y=u3fDbeCtuq{4##Vx02Ck=Cf6Wi&xb+SF8AVO zf4#T;#=%P@k5n`FiGNr;7>!3eZIhj)#gFG+{&ir(;FQa^_k&724cxCGHuYn$$$OLS zO$mfB0TiRr{U%qjb=7hK=dMge;TmUwY?VauyOE#R2zoGS8_gxX5m zw8`gMsJOK8@#OLA*8A@l?0M@qS>F|Hg17p@vo3Cg8QtA#^A?p4T1%m5(w$-Z>iVlk zgnok-5iZKqT-vYxW|5!#+Va`jVvkK+>VvlxpP!2Nox9>Uhjo8Z^~(H&+e+QXo=M7Y zi@5%oJnd6J86LA5R`tywm-g}2%jCTQl3&B`6)c~JG#goZ&i^di+y3tMHR0#{A39BfD~6fx*a{Q(xa;nQI*-vN_t z%&Zl+=N@PNded!p{B1+iZows<$Lh>GD5NuRx?eJ9gZE0Qi|DL3$bDe>f*rRu0Ehs% z$9*-I&0dZFgk$i{x^OLGtI`RRf70$-cgUN~gZIP^sUn}RuCn_z-# zPwxqTR`gGC!K+gO{qrz3+gCV5H*rxd`-7p$b*@R{PSiySC68^cP-5OyTz~xH6{4qK zBL!{IeX0YSogrWcq1Q8ys_)wS;@}6Zbjql2{312C5OSF9=iadUw)Dp525H$5|08d% zn{@G>+V{5aHM6`TV|U-rPik8Re!Eo-og=yS<2s_{En@zB6ukQ{r%5AfMJj>Cx$c6! zx#t3!XaJjK3w}qGn)Ke+YC3TFQ`$=-UTXvo!;JWNHssDnb+Z@LxOJ+eI6pF`%Pi$B z1<%8REFu3}Zatn3_GaR}w0Th+dt2Aq@vDbX_jcRUC2gI0bFiLA>!*r+^|jhsTL*j6 zB$9tE-o~}a|81+eHbexVLgN2=R_#A)cE7#dv^VNi+FXFfke22v0!|0bEpwSBZ8@#E znt#EkR<=<%%;GpGiUPbHC-!*9wc$e=J*)W)PbDAp+LiPNhuWKLJH8(3?--&{b7#sZ z!1J)3nQIlWJbLU9y6dKkG@mk+q`ZZq3z*W$vG=~}uujNF)LOEGN_?%evE~Zu z4Zsu9=9~}SOSL)~xU3%kU!&-W%>Mf^Q$3b4QA*#kBa#+(v9gl9*+w4l{n{_6#Vl zn8!9*UT#n=%x`$mP_yZc_St2vi#-e^8)&gIW8GDI*c+@op$ByW1P4t+6 zzlT5Gub!Lx%D~mdVBxPuo#3%s7+A|u-XYuBvK=!I_OUEpH6KqO?0_)fbp3Khyjo#l zQXzZ=qvR#BjsfEey*;?C|fNW_yRC;6`<&Wp8;XzZJl zBAw<7gCmqdl``$a6Y`(d4CZW`?z}XAvh{zE@~MFO>PEzjOvABtRdW_{`Pkxyi;nO9 ziOCfFpsA-ACY@Y8bS5%)<6c9k_15m(MPC*GdBhmT^zO|2ay>ln?`O!+@=f1Qk@JL$ zDSH#G(*|0=?${7iuV?coD&8bAkF`f&qm`X!=cK{e-5_VB*FW&PVdtan8QA1<-As1ajRaRnmO^a z1od57v%9hOpNJo5?DfixYX%zVAGIsF+YTJrWhbaZU!8N*l20s_F%OJ#?L}@f0uksN zbF4DjU3vEQkTsa#9~UjTILY2zC@6~W%La181A)8mFy$aa|9Py|!D(i#k`w#|GvhwL z$Bx)+Px?=~_xPJt<_`3`W8IJAI|v3ORYo9wydPVv=_}W9RKp>RgJefBH0%%OnEQh1 zX*Wu%JD-I1do$o$OR>hW-4U)nUs&*yaIyK-9v)vgSM>Ko_poJ8 z0U@@j+`lpX38@c%l%UuFyRPQ>6KHd^~&C5i`tO+W;{kuBG3*~2}Xan zbN!}8q=Nteci*{M@#bM@GBTAMzwWIs4w zVE!c=V^hC{We|0c@}Fp0QeIbYl6rkxNLrey_EkjDSkT(tdWDw(RSqA!rm*J1N8@Lg zqM4^x^WXHe-^%z`E({Ws=zutyr+sy%)`O$Z={6IX=|>UkdqcWw>%S!P(1Tt7gSNCF zNYSiHT2d0_;E{&e57Odh?U|`Y!E8yX`5A1~gxTs+!0SEt@_2bt<9E?DGj1jSH1FR( zEqbrT_givP&zw0NTjDdzCUzB(Hb+Z0@))lp&nhk2#~2V1kA$#d^>Ha~fo zhtb}*7|twx>$#bhyJ$oE97!nzqh|FImizo;lkM;Kf7F0eTD5{I#LjVCZ{zA>0VA2j z2-@<;pv+Ilm5c91Ed&F80NHe*GNq>2B{~i*O^AuV0t^IO&vZ586IwN_&qL$ZuI_0> z;eAaNRY4^UO}O87+u~`g>2>{{J)Tx)c=V7jUV+5y=+4zYThAPNQ>CSON|RTO$E^QR zkNrXdO)Kk-#e<{gOnnBkPWGLDp_Ck|N@|vSjj;8vpk&$s22Z<}6A+_Hv3m;xoH!JqvgBL+}Cg1O%s+nxBQ>MYxHZAe%dnM8SgE^OM=4%en(PsRuXyHKim zBi4$+7F`#QeuI}e(tJw!>41po?a!S7pgEEK`&`ax=n0L=SR?4`*_RJ$F|9K3hd-!H299mZy-Qb3wfQQ3r#gX$PZxBmj`uS&d?7p+xrfZkZZ9o)@M8_J5 z`!7S!c|l}z@5h@>6tKk1x5*8J4@Z~$2eEzWS54aE%a*y z13(j}R8A&b8l8ui6YY0s`vuCAc$GNV3)Y)#{Vcf@zh z%)D)oSI{;Oip|uL{Y=I+==v#1ogRz-8>-dWvv@#Nu@e*n4}0R70y z4?oOMa!+h^;#8}6>{6mie$aPqV&zRSTx(|91bKO7R*4TRn8`q_;8-#KP6xuw`m6m! zPuQY?%rVIE{z+9xMpwq&g@i?cnLdVLq;DK=6XS#;=d?VqnFOPBi|qV%bP|vklX&p!bccS=)=CI?x;M>yJp0PQfb7wn$@+FTJb_DR?Pt7r&&&xc4*W7Fx*O#4O*q;T<5vCHL!gePCTgvf2hXi60y_0RL z%ZN*(OwPE|jp{c1UYs;0qucgg?+g!HQXre6*|}GK=+FvysdtaQQJRhr^{~bqwBwS{ zEojd$p0&uq@YB2n^)t)f^T=q{!@vz5sP;T!h!#+E3K|?QzotJ7ujmXIgi1SZ?eM!E z#|!cTwEWxX`N7XQWP()&M{c&3?FaebB$C2Kl03m5t>Un)lXD0_6QQrm$WJ{f?-?`e ze{QkNbOt=7U-~W-_c-nZ4zOWt&;vVEF>xf7LW^6BZ5=z9=HV+YMcua)RUpawR+?WQ zdl~OBN~sqUKs(Tw(vGFLO&ji+g*LtZ@79A5JGP|KD-Fw1mF7Z-)eqd6oJRDnFE@WE~PFi zS0t7c9%lb1*^S`U9T1L<+(H!UH0&jW#7&VDzZ)w2vcVNJ#V5Al1v zZ$CTC72V}B7>v18^JoP?Z}TWkw0uR5t}_oSz=Xv8#*6HYWEe&Sc?eMXzve{`LuC-G8&53v4V>UC>>mlh{WwlZ=YN z^7xAE1L3~VSfrK7xZ zBzY#%4&y2;LPxabA7QKWneQ`?UMON*T~6fFeCWra1EyjnP9X8SNPL_~`2#jM2bXqM z8rrpI_k)WT>U^Q@#yB>7U{R1KebWVhj{3``;0B@`Tc6SSMoVWG459vc(zvq1cxpCt zQr_GZHe~JGfq2iPhv&&D8F7#0WIy|;)>X5aLMGm`zZ9Hrz{7Q(%lu;*rIk26ZM)nVl5E_ zc}+o=Tr`Fepvok!zYJCF$lnp3> zQ%v=@sq^N@{?7|Mne5p&rRfYzr~q4nC+cD5MQOZBNN?i}V$GZ<2KChBuea7vOT-Fl znqy{02XaOx+x5^Zg;BxlHL#ek2DE9$%`$tfnwYoDrXAv`o%@(X{nTxXEGG&%5?9bW z@SKkDq{)GzaWzB>Y5RV{F;Fi~CAeBE(8LzU@sU-UNo|HJ%UQ6r!$Cj*B-bkH0NOoF za9Cywp`o?F;=Y|{fiZwaE+?DR+#cs?E~wY{=E+_-p=7nJ#aNBC_ZkKn16$ZW)7;Lh zZtRe@v(-{oA&&Erp(2Fh`+?qlC*zUfK|Xkw9aj8$RL~l@aq+zR=b1&Yvwp>O{5ZoI zTv*S{k{{c;9Rbb7e_mPBukRuwK5Q#TFGqcTtyjtMs-)P>>)@mba#=DpVRXA?Mk zf)icme6+AYdvtKE3(^^$6&*_{!!-u+&}(`PyYMYv5SL`bo zOVoP{u5O|O=?Ivuox6wE6y(Uni-rIkw$G@PrX;~lY{Jd#x`1|x_#bp-W}zs+Wg=3W z3Ez~joQ!nDo`m<&<&n=f=iiYxJrvKgs1{9;`-;OBw5fJTD@vi;T<29M853BAil~Nz z(V!W9tc$mahf%*}ipB3tj*o>kd@#@CQFgVrv4c@Jwh z=<+isqxEb;zT8tq03h|wnh3=P-SwS8N`mZF8zU1VYXQre-1)JlYu2<2)CXUSbkV$x zYg2%h3R&KD2t@a7z%SzR{B(ExtA~kNDDWs21hpegrQpV*FG%Y_cM3>I)mCD-rJv}y z1zq=v5!iSTmv>P3Is_*0O8EYhG}{$D(qcr^ha&mY|DJ zd-?&YR#zIUSf#N)PwXs!Fw^-x%icNexTb0Ikbziw0sdmUMpkY&ea}gqKm{$JID23} z;-+pc4&;Uw#XkFDKO<4zjER1?9EGx;BB7S=^=M98ct0R{F)(4yYyJg37*8gUeo_Xr zpTO0d2{B24#5-2jvQdiHj7>QZh<3qi>0sq>e3P*=t6ZR^zQn)j8KH9tk)G3xae~bm z+G5{Cc{361R!B-r9*$7+5EAh-JL zb++wf0@jxDAV0uhC6rg4hY(nXPt?hqQ^m(oa~hdvAkQ%3xdEr{#3n&M2M#Vmj@J$C z(|%R+z3He_!w$YaGdi|#m#&%E!u|#h8*NPLQ+wZsq|vDVU7C*8Ji`4yLp%=-*9s&o z{f^xUrYFCk+j5-gtBfihb&xVB9x*RJ%C#R6?49pYD8h>9)QH z+Z21bJQt2OGNXF=S(_r26+6Sx+|)V3ov_#mT?w$Dw~FFL>onIFca^N}6Cw&cYsl7? zam)`yMH$KAMmTF`Jp&p5-KGms*RUeNloGPOq5T0~8>s;2#Q3|(^>>`2f?_g_q*(g5 zOniL$`td(0W_N)_5T~(T8Z0DQ$kbG6Oi>6W2_5pY2vq=qg-JDPzEqF@q9$9pe2lw8 zu$of-W`Vfts2Rxj!4@ki^!GH7b21>dUxM1H`4)u(z-SVXKYJjli^_y1^$=Qg`615g zXQ<)uVxk`HPRJsa7pPZPvp1RSk8$g;aDn<+ z+M&x-5&~^ihwABOtn#T{7au72%whc4p+E0=AvQK@QCf^iFioG_5m}dOIFGH7%dtty z`5l`+omopY=1z%iKMWfh5q5yA?}Jv-`ITs02?j!7!d6^gv<}5gi&$ARE3VY+{4ulu zoVte@A)*{}*D9o%mR9n)(cIK6tzsTpWhe8Y%~b61myn?S)ej=Fd3f2SLR)Us%2vHu zB08?UIT!{nL*OxR-Y@+lXM3I0Qc1EJBfla>on-vtxs9Uk)VrgJnsQCj0r;B#Hh=W_ zds=Y=K3~(46ze*@z^_N{{n&g>B3UTtP~edwr|d|r>r;Vi1e)uaAn01Fg&URktrF60 zI~O+{lGdo6SfGmDm*9l!1Yq3pBBJKwE#H=-2_-1CtWb&0Y@U2d@&}TdsVHYSk8{B$ zT#4GV;yf1&4t!ooeAfnmyj;Du<>vpO?KV@^Hbw|h^5tT++pT;*Ea>_u2AhY7 zND3rONaqJcAw~&Q2_r|rnSkE19+UA}SdDK~h8o`8{AEFNjWD>oe7nWCANx#fGq3{h zbpdCfLMu-@?A;}qgi&fLl{a6ok?th0`Zpai6sT&3wDIg6_z8H#bC9)8SErPQU(W-D z)Mwq3vI&SpH29`U9LT%Ksh#ia5xMX-U-WFIXoBk#Y2#c47vS5le5B3MSv_@tIxB=41}>+?}1A(3S43}2f_>nYMB zBx{1m@4?B-n3Dc6c8$OUnP?qV zO|eIm50Gb{POCrR-lA~0Ca8Rzw2?K!ANA8>eTZ^BObc%z$68rso zYdu2aG~}c#{n+a=I%>pi)C^(xx>DJJ7$itwyw<9pOmEo>$7rfl)uKULbL*zLN-T+*vL#0aE+bi-I=E@xH00F zd|2Idx#cs1&pIVV()>&KR>EKSFhM#)@sgH*9|Y*#y5lt^oiX=0Aw38kG&qdygFZF} zo95_IhQrg?N?kJiRGTh&Do>f(K_Z@31yRSjv;KH7AgO2-Lh4Hcq`^2q(OGga>#2DL zUM*=dk#CD(>{rhBmjix?s`DLmjQO)zQcS)wmpgq%Bo^DtcX3B0oGol6>SC0W3@mpI zkqj*#wYaSfLZbqTvYQE{U&i8hy1!LU25Hde^JG0wZQfy-iXbTz!r+@~k+o}GRC4PC zVV&-LBZPUFCXp6Htt|tLDA%(uK6}o@_dh^SBR{25qH&V^VhI<-VT|J+~b+<|2IB{A&jCXV~TF44i4SgFr$N0LOFGi6s6=e=d;bRG;=Q13^^;J z2ssVe9158tXGRQjob&Aa``nM;-+Fjd+vojxzpmGHJ+B+i7%OA?dLHmj`bB3ZfFwoh zEWQZ~!62nvzs%iRhBIsb2`;2H3OH#aA&%GMUK=1Mvk_*{_x?;;P0f8XP2ULuSF&G5 zA>}1kTsQO=8i%}3ENu+p+DzJ?xCj7Dh4y|%ug}ebLMCrGfzx`zE3NqOmc9fr?~qWe zMW-Vczc@iwS4C(D4N2Wxh5RmP;e*d?!Zv%&K)&ZzOXt8}kUsz;5q9*UWu)7a;kIP7 zkC+ZH@+n~!@{md+m@^<#!Z}OI^xFkpp1w%3iUow|z_mcWCKu_w%mHPB|Eld^SAYx-Yo7v_6Qs==JJ&ib>9?WPRfJ^Y zLY+dk3TWR2MxC5xuK?cgj;@2B?CH#)krX-#TnW4#uQRjL{n$O20(oHl(;;`DWpLO< zE!V&{fQ77;fv&@vFekNO>NTDS2HQ+UM;K*tsaDdp}G zjSDq^`lD!E(US!M$Zb%dJZCQ3?QWen2zlUpol{yL2iXoP=s35|P%6sFfe4(=R;I}9 z_U4pm{lr7`Li~z{!n(*!Sv=hIQXTSZB|ZZ1bxNbdlz`Hyv_xPUBxg?G}NtX}J$w2a-^7uNQP4yo#6>)cxEi2F&;RMj)5vw>e56EPLff@<@_Hct4WW z!kOp65e}CksYo@JiP&}D8Z@mC5Ha%MfcXd@_6;tYnJQ+_vH+$1e;{SPKxw^zf;L_d zqZr1{hjpNv%j8>>VFZFVL~bGx^bZ)C=`AM6?9U=;9ibSAX>_vl7btl0bXrys(Ph^j z_{e%hqNOFBA2YxT0EQCht?#H4a6S(%LDtk_8bG>&8GJ7Ptn9SX8&gB%}&&R#V7 zvAlpx&3$7B*F^*2?_r-BB#0U#{ZWGQq5g{!G1$(2q7F$8}GT* z+VA3=Aaq381&o?1iT6*B{z_qZQ~K=0dX0e)1zj=<_tZO*-Gh_(>aE$0Gnr0TJ3BVI zLDjLo%BwLbnU`8$w;Oi_bV6Ej+i{#6EhRlFghr#?43klFvKRLPq>g0eh9i)UF&;TW zKE5Q^ClFNOtW}g$tsY_DulSv&_Yj0R$h5pDynHG!#E%;eBtHL{9TxC0?4$u%YROgm zQx-lH39^n~p>K2ta0!jL$>A5R$EqIkpoZ65@tWzRcfn_pQDBaK`i!^viwux*4-&}T z=nYr|fO{qlI6(%e8mRu(qBYM#x&eg6b-#zeB^BFPiOjaKDk)g}|>TeP7kdAy2 zxN?k1XF9mPof*>~mx8$?_dj6jckGQliiO??%serOyJ7G3P&xEE!POgreujor`({_CpM3*~87co8{%2X* z2PgpvxUa7u9M7;Q?|8%g(C|M{xk5DYSISBE;XE?N(!y=!`O%vVrjaLSD(W5~7lGEY zoOV|S{h_{-8TXkT(u?zu+2N*bA&zpk!ZWUdvWd3mP{0Pkuam}z-m`135`MtYORBGz z_gm1ob=c!{H!c8QyN3X}tZqWO_{BYL9s6R6F86&2^C4T#REzvst&c6OVj1 z4?1naN2USnUhUIKwc@*-p3#7ov}5zsODXf=ybKzt+6Yu#u|$ULHRzo*wd00g{VajO@^ z8kG0s*xP4nzJrsNHwbc@umFljzH_R5&6L5>$phxW(2N)_!6igo$7XHCa%!{Ja8&r+ z3#HzuHgCu(KqQ!Pbh;$p9Xr`PuA{aCNO%TO1T3RVC#bD{ zhpK82XZzG6#WE_rW`l2D-tAN(L+jY>m;7hn26)wuY7+A&vAb3R@@Gqbme`G?uZ4W}kGfmZfpBF;zQ}i3rx;AIvr|~g2J@VC#05%mi&rb&jLrG1& z#~-9M;4yxTa&L`6PQqUT`F1Q?X1|vCUy80wO5m#c+i2t>M{mo)k4ygbEQWRKnRKUv z+*k!<#|qs0BZhJ*$_86Qhx_Rlrrs@}=Vq8hP0DM&*?R?D6pH8ps^ z_q0BD=@^mUSu6bkAnA(-fxm!OD4h3hzx&TAuZ+U{EDUDEb`*xIcvy!(9~v&miwgkJ zLo*kN=LJ4_UZV`SI8+a4^4qh9MOX3W#))BK4u^#Ly??p-!hPLvIM6xAu_e4%OYy1k zb6Dc{df%FlgCj)+4|80-aqt-_Py8Ke#Yumf+fZobtT^Wc7~(w#R`}?tW9RwTs#f#F zvO4ebf-e;XP7p}U`Zwb8!;u!0L)ZsMx!NzT><@*Y0vX{^|K5ubw{_OB?JZBqkISoq z4E#>0{ktIP@5lSQ<$y1|T@xwr9|84>r4!8=N5tb8;x_ziA|L z5oe42{@4YJjiZ4KMX&uoQVN>aVAn~ETGkM8G-2yRS_Yah;u5c@H)dV*v>u9H0G+5X?KsNdQIJs`X` ze(|rnOR7X2cLnvaq5817rie&}5(f7%=6mG0^kxurGB1*GKZz?HZz=yjP@m1^(kk)~uaN^+_UWqgRy5!>Iwbbw9w_*e zQ9PG#hD)+vfwoEmtzc>=4dh!iBRq{4-*8SHyi-tHJGwBs!F?rviJ5kym-+v+<<+F4 z8Qug7d(sB$-ZgGdwsu&LrMn4s?Uj^6sgWXB&UpW5jBg_|;*_pLwh zy{jqs-9ftxJ4P_fwA}t$p&mzN5JrHNk)nx&pDB)q))Mb=r6;BcIPOZf^Gb&0%SHx} z{f6k7%=_H42n(6xZBSyUT-w*+oOcijj{Il*wQwEa?1f!pECkyB$v$&uT>yYecPuW1 zyjf2oUIR=T^z9RQ*O_E3;ut0)gpJW8FSnG`Mjhpd-P|!ldUc)D8(q9mwV7z z#|%tN=gZvFJ|7w?z$iA8umlMlX}pS^XC;=X%5^@swA2-VLRGxiJG&}I;ILm!{rUcPnb;MPc$(t;+mk5PRM zo+=c;8}_nOjRdCZ1~3yU-^XevXZA?A$kxp@%Vngg1U-Bb4RCGYDJh&dG?IBYUZs(L z7=PYZTOt`}~fF0F4e}Hma_>ZPtLy#yq*y- zQXktZ4It-4b>(764(HVpqe;a|@@$0xvTFCOZkcaTwSR6B0vtu{iI%9aZJ5j#IF_=t zjBb4IqHF0j3s=7a(a*zSj`vXiMm*4576ewpASVRncU;G#7e5}gD6GUnM09}i&eSI^ z8@_M?bI@x$yy-QQWxMS4C?(>CeQr;P^GKoUyJso2HRS78WbPFDPB4jo%W^fk&Pv@> z^Tm()A3S~Yb0$(v)-S}P!>#lN=vfk(Qk1)hRWMuybqXC~k+HYJAJtr+aU=Xr_ zx3WTbv}=xH*qHADTJ5Cd*N5wA*u;7sa+ZEn4FE_yx#XbSS}7|CZZ1^2q?Pfd^39(x z=84l~J-QJBMR(G#{A1Fg=nZiU3D>wQwRgK0F0PY7Gk{*1hc^18-tOM|sLIbTDb{GP z6kOn<_~Q2C1l{5S8=AYA!4Ll*?o_ZmtuJY#-Lh~#Zp8d56*PI&DR{>3$Ah~LmOfl} zH#>RM+^oXTb(f>4t8-7Xd<58|f^1fTpR)6C@D_uxXK!*cPVo2j*G9H0JX@S)I3;wJu2XrSCEz}575d7D%r zB!9p0RuCK{I9+ZS`uOCdAa3M$s9Ddqo1ghVq;zACjo+=m;Ebe(%GI%d*gU;e2C$+= zTy$$k1{fsPl5T`lp6Jrx(VVQD84`XdG-PYNJA6R^F9el_Dv&;9q( z_m|USc_3A99^~AU#fgNzn)UXtLMBEnV`&3h^1^*a9{pN91Q-rChg8V65HMI$E1-Mk zUcG!cJ^Bq<^I_2$4liuDN&~mH1qx5I`^b(0c6w)U-OV+g|FPwSv z@XcfM`eerT!%spST?X^bbU{i@mjZAX?it0BvtMtO{Wy2eWI~H7bw`@Qmx{@z6YOlO zpg!v!R?mC-Y{ZNKluY%z6umDO&ezvtK4)H+#so&MyBv;u7Ck^FF_`A`GZNWLH@wn( zmSK$C17pjLcI(e7lJDnm#okkIWxU07L)Y%ug-{bcf9O0E7LX8`!^%Eec;5?Smr0~m zzCAPcY53pRua$xm|6pk-`F-DZmxh-GQlsLbt~;Q`WZj7BBOU#U>)&GLPWcieh2IU5 zT|02pSRZ4+KD1~p(RU@}jADX}kK_4n2D&GRYy0#^4Oz1d8!;QPA*M4oSiy4m+7VFR z-yOZ!ez*GTQ@d0D0|g1`)P4rq&A#{c_zz-g6++_Ck_IX!q(0}t!=VY91HzfB5uk&^bro08AxMR>c{Obcf}T zO$Bgg^iqN!GH5;e-ob5=o28%s2TEIdiaM35;uGQGyb;jbUv(=mM)tYmNYg!TwLsj< zsF&NflZ{UuJ<&3+88OdU%xn7eH0Y>pZ)ROj=pOh$E&cP!@u|B;3>lT-ItTnn|5xWQ z`YW98p{$=|3f55c=HD@)hO3Ly7xPqX;2Qc9%Y#>BGhLyNCadDNeR!zj`F5h?Ow%+G z%DP4ey9|Bk#?zx7KWD*mLbUHej1ft};Q{`o<6+5^oI>qahwy--)%t4XADQZv<$3{8 z8l<^8H4b+Ibei zl5+`@#_^{GLi`YCyc)ba=gh>H$&YK@2&2CXBwrsDZWq)1I3n8z7 z$|h}0*dz|)s9#&A8*Z4Fa_VgP2ZNUw2a$kft&8((oiY&{B4TtV0U*qZWsrZfil#46 zf1j{?$4HJm{!>dkrP%-ZOs(iSnat7>X`t1Z9^JR2sR)yO-*jOXkhL3Q=g2C+traIv_uEuYB+Clb(< z!nBild~s-3Be|O(9w~+vef(IcCg>655bjV|X{}t-+;DzNiquUpluR%v8H#>R1?(;O znC!=>!#&v5COZwy@DnGBk0j1@LLar z1kM*WXz)S3LC2J_#T-ZN#hQd&ECr;(P#EE;=B_E|H1kZp`4m~UJ|NXQMl;;mVlO)S z`dJPmo+!AL@cDtn0IvOf$fu9Pw~eU-!?$XjmK7c|=(CKqkEj8OH`XYtc33iLZgw8k zyDr5Z0FeDjhd)y9{9N}r^E2M(&R+xl7$U#N0`cdamkU0IU>$GM}fO0fPG>qrNjs%nj6}7Co z(>?XW{VFf3TkxBExvsMwe9v}v^WP#J8$(wHH>HnsXzq{V^C-z^!r-HV3+_74NnI4NSS7v6cOW zh4|{4vpUXvE_OKMp@gI_s+R`$LTp^i)zlR{^7c0RaT@FW9hwahHoxSHm5O1UVji1^ zIIwJd*^?(8pB*Za2@%}W;f9F*;(vtZntUQM9?(^a|Cnai1ws(3>S~2a-*DT_Qb}4y zN}nT7s!d)C&9bv)i&&r!N!*LvNrSZYUw8-o^>orp;_O(!WauP={sy~namOM+as$pf z5!9B76b=#b`&UtAwuvfFV#^BX_ybm~av|yavBUe`s1fFyH~)x?tV(_?nMq?$f039& zzyc#%o9b_Qxrv6+aSd>m%0J7%C@##x6Q~ zITfkOCI-1bH^aM6gXng19sGJSyD6K1TAYAm?_5Pt{i=#bWCMP_zx`@cdH~YR+ z3Z`uZ(%Tb3MUWd#Iz`lS)TVD#ya-MD*S3pK75fw0;kbi|U;p?e%wpWNb%p=hpf(kYdGNl<^6$xvL-=H43scH_kNRF>8Sk%ENjB>Z7BhTL2}4?Q3n$OfzZ> zNpgh1KK85}PdUibd$Aq`{IdWz)N;!v3VTO(VB$i{V$NvrvC5-taNzB|{VnTmrgaJC zv{ek`%LR#~)~3s!?p24W{@NfqD(_(j;M|PO_@yKt#m_H!y(796v+uq2Ld3d0cU+W{ z@e99y_Hx6d>oQ~H%M~jhNvFg*JqDf>VO!+)Gk&)fzwHwlzbE{|RGfpy%_WW|wKk+x zTuL00)p6=SSBN>=oPkb{)r;GUOw`g-hR}f;Nrvs8I21sj)c^I5rU3SOd0^PPyo}@E zntPNWFptO>gJ-EKA283h1kzW7CIj=G zYC8d>)U)!CNiM8-3p@yN-ia(TALo)YfHfb`H}nYnO4YJFXwSNN;$PT2x_C60&o|*Q zh#b#bqQg*>%U@&J-@(&|OU?7XcL67x9lxhhxDJmgfd80=RetHFWN-AdzcGArK_D=&zC*eD;xv-X91vfFXsA4#5NiPHWp=&u44~Le z<4$@HG0BmtF%kn<0vmYpsylX#klR#M=o$N>?>Z5313YqLP0a^xTG5n6`f3T#e}|n& zD!4o;L72gTUByEl|KQ4n^Hry>dlCWwvyQXgTl*jqU~L2xl+F9XcpuM@Hc z@{A@;OSqG@P3hsf7X9dIGfAzNopYQmW{P3%5s8!*xKkWWiZ5YE9xyEhVd8XteejU6 z&Y@kW$i=-kjXUc?>6KQ33yXBkfLmmM`|+FSc_NxdzgJdnq>@B9jbbXVJNOtmyf>Z9-x)wwWqOZy=o-qy$1z6yf0gJgXLH4*~JznaK?hZb2hNGZ@GHTGSdZ{ z-Jg!DtWcDi1nCI7&3FsK{d&aQ%;mIaDrnt3Q@3z$@sB34qk;OF#ldG$o#;Ita%XPcqe21*Rw?bYy9F#f6tKejS}ueR373 zFNeGG*(bay`gf)nYY4R)5bFswOM4!dP>MdI#>-t!ZZYba^`t6kOBIY{}ogI+`6)Cc> zPwe6kR7yLQy6aC12vK=fb^{8iJP>8TEw3n-nIl}M|5yaoi@7u!scKU3b4KoxhtiOD z-r76MG5wpaU|B4ExNtoKicr7bfj$7`2=WNyimvzhu`JXQyKBRLDNN|6{|}U|+_lv+ zJ~3l0LD}lp_O8QnAigQ_*EgJt%$|DQxBw@tes92zAj};3Vg)Bv)Us!3yVGyG zK&6W?;yRJ>75R$1T2v&sw&2lOLnpLAgkx4*P!2d3 zh{@B-E@<%ciPxe!^}+@Cb-~~?!nST@f`e(4(L^Sjf&$aQ1t9emX@_WzLqxP>%$K$5 z01|)8^qUY|b{ieIM;@r?z&F+j427C9&_6-K*s8SdkWd~o5R8CLqhdP>i={6ulCx+9 z${m;Hv4b$cvKn(WvGQxyk5RvoUfIaAnT6sCCvf~g+g}L63#dJQy|o0K7Da>19UG4h zJrQRGf-7QKAogITWXsQ~J;Wn_35k1H}JLxY`i=VJ^jiMcBZUxIX23GMq=kW}6dkr` zSD2OVm5smnn1|3M)H3NkKAxU%Of8zIdU-6JJs-3XYAvZT$!Q=*7gdAcEZq=tZEmzH z!F3nkXKf&ZoyU?n{k%m_T7WP;+$FRR6f{x=&B6|H*ts?@L4=PV&8_C|4$54N^0o;m z>j4#uw1N}%lga-U!11N0tDDMy&J%ab4Y4yAHDMW}_dI?P^nyS$wYGkqm)VC1Jmep0hh1H%N8lhR_ z)yM(fw@HScSYB@DR{ng8iQXF9+G0LWX%-|B-JxHYytckUngsmX7j$ppGaPXYzNFb} zd@d(?02%X!g^>WDu1g|P3>2O5yH-5hpSoDud3R|!C)!7Jqq5^$d%h5f7U122lspW$ z7XVhJx14b`=sZ7WX;o)~j?*xgyRNH#1i9FQe#SCHUMrFw)gbynbMto-qDao9NC`Bs zUN)A&_F6=K)djXVqZEznJz{7q(GvK7PA45kT6cojd)RC8UkpH#0v!y_U)=GKa((x0 z$J%z)%C3)kep_$MUjrSbENN|2Zak*2{TN5VfQY<|WZ$+h0T-9$L4BOy0rIVT!W? zLR&=>I=UMK4`fte%s_4#&Yesuh&Ic-W|<~;+tbMerJv5)2f9wd2<0Bs-hhi}yh4DO zap7+O0hGA`fO-(L;pkEEIs8Og!lTJ0lie?C#O92D>&}tVqQU`6b&e3^OdJF-UhYok zb%>lY=o-z{9|C$sDz@^6;a=V*tt7F7SY&keE6~O|Lt&PoX9Ws8aVF!?Kwt+e$+AGj z))moOBuCle%v(=Hg==)~J$gqugpVe3qpLwzPs|jJ!hHt|&PU0B!ZKxz4S~$G?o)n5 zD6q{3*lW{iNa0%-*9PSP|1K!Mv(D(q2=80E2BT(-yUNbr6+Sw1lANVQvaV%TS3niK zVY14++P!=(&NVmcHVdcE+CRC`97r}O3ai&5lYBX~Mb1x@^qeI@c_>FLO@F6=HE(%s zOzWa(8@K`@+o@-b#GH_qLdyG+LacadW`}J`sNuDMen5YQgiFC_iq=Bc8^E|yZ1k>w zQLWXp5wn@VO@M#Pr{s-N%b3{&9FsmQ_oFcPDPw0QyF?~V1jTsAs41!zs=9A^9T3}~ zK(0hR*}GWaSRvZjt3V5fgFB~G1@sn}2b3J@5Z1-E+wjFP6xMn$dsN&RsZsAbT2Aq* zcC2S6a?kIFImBWYoWr~}cfx=MCQMp^O-G2{$hi^8b3(DqsOI=;5bF;|{;UCaRhFO6 zqf4ENoDAs$ADP{?aZ&CTvB4b{))sLy0C?8Gn%n{^O+5ydRS^(|yYdl2fLk~Wc$Z9y zmRh>+13ymko^OLGI>S9Us?^`7#3y6X8ZE#YH?zyC7}Kh;!u$ccY^W*~#K)odpU)L` zCCrF8_pznq;Q;Xrc#?Zm1ZmPV`fr?gl%{bve$FMypPZAB2qZVC5&Kv5&ZxDd5>Bd^2$ zOwwC84|Cx$&pUnaIq=V*f8NprA;MT9XR{<&Ar_RhA_m-busQA`O0|0z*wm%zaC8kPx zA6u{lJWAU{Yvp<@%{`Et0kZ;5;_?g5xqH?xj*uG#uoOP45Kbna9D1z}pwG%^!Wr|r z&LfMa8&Q(td9pTG;O>|Ey!(8Ni}F4x{D~P$5hMmw7CQCuie$9xhC2E7?pSM#Vr!DR zvM9)w4%!?OV7ehYr*X%5{!l?Ivgp~n*s5~V-YKS;zNh|;AkU!1Yr>Y@)sbR?IRf~k zY%k0}UjWfiE|Xm(78)gpM)s&kX1Ei0y#;BvK^Gfs{CnN36GwtuX2O+wyL$(m%T!L+ z39EU*8rs5wLDl0YzC-$P*=}Gc^Qrj zzlzd`CdfgU20f$XCNe27hYzge2KSU~ym{`Umw^h10U3nTFNwZ2?S`g1{TI2nV@$5M#73jKYoS=BwODD(XBZjW#vUj<=QJ$YoXgK#mGW@R9n8)`#xiopOSGXer9@Bqw$ z^5eWjMe)2hP{2bLGnyjE{VCMwmCH^7=0wr9c}vM9(Ojt4Z^E2RWfjOcCm%vC(*GZ* zA9qa86ON7jaej_Zd4`+K{i^TS+`gCa}}w0|Ig*q7w2}GuiKwAGC1TEa-jMl?0%pRirHWOZ6-0_nIth}t7!iGsP@CwnW)Cb z()!PEFUZV{h+SiIhg2XBRTE<6_A(#OyNPIDAp*WXdU~g{<$5XvGq&As$Lw|;BCEP9 z%a;s z=AQ3sDoS7k=YlKQQ*7WylWPk1vD{#pS$@|d5NjEd2?pQ_rG(JK0j?k)evtZPa#=6N zFlCWtfueOqq?6K^(YwMH8ue-9#$ui^owX`C4bt52WS>%F!x%=6+<1CXc}vze-jSeT z==ynZ+GquAjy{Zo1-zow(B-1i;ObPPQG!3D{}qag>}c6S*XFk-BUcDyEx`G*7v8Vq zC%eNg0AY8Wwj_T69P?QUKs#6(@9(HCzNc`nAvUyJPvWdjSXwDixbw*Aq%#H5UsonBD6mpuC0+a zx+NJeO zSf28HE-H`;&g04ZaUs^;#-fALjGEuC6qmsy=NbfXylS*L6E!2!`z*8u!AzQ45dWP3 zp{2-kv)4D_Jkfms#03-t$xe@5;{Qk86e922j=JfCqV)bS?d%*GaN?l?Nc0UKaUw_; zy3;S>l7lYMgh*;^%s44z9w9xy;^mGFilRDmjWT{5y4trM=FPJc;L9-8Ez zS6MQ=XWR3e2BQHnAou9#{ifHl?M5iCw#&sszd>;?Ph3Ef9`0AhNANq z9u9LVo%e#P7fLn~T3~R*>EI_to)@sDZI;mRy^a){tI;@=QVNl=Ym;>>8HCyXt;|z| z$3++p0ne(fw~rxBUQBGl;fCClw+Y(dzfrw#vSif4NQVIf&M+(9CL7Tr{0brT20Xfx z5lw^B=}+;EAewxrHS|)dt^`d%4u~HEGYY<@ZZm&aBgrteG4>o>ek3}v(O{ZD(4cCi z8tA1B0Wt4$YjW{O#4EQeRG;jz&X)bA^nz{eV{kEVjcl*hHz7wS!*atbf!GuupX`US zzM5_#KXQ$*$#vSd)^~6!4_fkuPFYw}xGPToc|Y5nokIP&$FDfqmogCQ^F}IyqODUn zCnOr^n>0BS4H&{fJbaT*Nm%;%;@oFIfw;ScSi~~K%h@zeUTY4LR8*kgqZv7dhzI5s z$z-Ii4I7D=xj_Qrv2^@3NA<>V$a=1~_jjJ&Mi9yfs*sD49F0<63?5HejE2#OP($3m9(*6aD~2wquYgzx7{UQ~|1Kj+GP{wg%+tVT zvncr#z9gVj3j*swmw>>wT@q8Nl5vA)|VJtqRt z0%xuY3=o5GuH=dpidN+2dFQdMgCr7j&&?rL_tgehf(2-uUCG*WZ)^d95HU^zM9zt) zPO%Jl#QCvCbs%EOmIO7h#v$Eg)ALlM@K9$D5L^xhEuk(A00Vq@$w)=hAJ)Ww@l-X& zW0Zrd+zv-oz~ZgGJL1*v{GL(Ms5>NR>pN)&PlZ5fbh9vsmo#(k#|oWDljKN=7%)e% zNuEz|pwSsdx$fK`)3DQ4*w_lm1gaP06%gmXV9LxiqKsrPa{^iG%X2v>M4}RAr5zGAUBk8XK5mv$QP_9(lnVyVF zF;Z*qWz9N_nm7g+GVUF`pWbMYp6s5S`Zake&#@Gm zxl$Km7%3*}cW-EKDnir4)zv$#!xO{zJN z^hKMclG3~4iJ%N5p*%Gu`< zt`2KPUo4KhAYZ4T1e|-nOY(-TAH*uai;4uy>lD66=j0+0R!+Tn-*2@ z$q;elU7F--Z{4jyz(BaS$q6dfg0&C8ECk0YzG!p;gN4)cC{NE!1wChSX36VAtd_|O z=p@X4bg49#hY>dH9!B zAcggEH{&sdBS*EOtns_Y2kFalR~{vrRlsO9&O3oQFT`FQJY~&+UF-B~msAg@lnMx~ z<2&J@&QcF&_@D3E$PY(~2q^8@_~>*>7+n-*6v5;t6L{N<7#kmvBUufud)WSuEl3%w zvsxtVHn#m?L)j627e_2rQ*e_LY4#%2=tmlt=^n6zX~ioPL@@`Rz5Pe;>&%w^c$<_X zcV;*BPU|Ho!`=B%((QLJi=1;8ed#GI+agd$mybPI0l20Oje6P=5*w0BXi6U)b!<|4 zXIG;WhlVZTzzxBwA>aWyp#@@m~gUmi*ABV}G{;O5SDOqU%<7 zU4ENRHh?>6u+dnHD?{H@Y%VKIaOQ@y{e2LRg>9W-{6QG?O@RE)7vZU(sWg5seGXmk zTy8wCdm|6>%182k)GYx}%e>Y^_PXjPSPg7z2KayidMzwb3`AF%aU-el*druOk4ReU z$DO`dJTxx01b52N^P|9+{i%AY+3IZzKzX=HStEg<>gF{IAg^ju3jNVcQT#OV^b=bZp zv;FbUZJLF3K`pWszoym<7IqHpf9kpv35=Y3o2=t^-Ytd% zb@EGH64%%WiIAF|#=JQ4DT&gv9p>H8_IM0uWaN##mWCA`F=|E1`y*GFmIJT4vt8W6 zC==SpYCLsq+*~wZE_#5=6Um-y?r(e+rbM<;jaP~5QP;*NaU1=#UkdJ-fA;&fi>!R7u|_PDQ`d{_Tsnk76oilYWY3qk z?>+`}XW+KF6TM{_3#hJeH`V6#e*Oo#viZ|ZQ(s4<>SN|+d%tMgw?4wGi0m~$R#IRRqVf*~!f zqS3rswR1&l*rdKefRVhC@86_tA2URnd!+^-`+0ucAD6PJH87g^oWe{>fArN7F7iT7 zM?_4AHxE^Ax949SsbUiAmSMJr(yGy zi$iK~;!w@6OJxy@VF0pqvhjn$J7b-Q8|nv7SM#>wJ9d(k;2rd%atrqq*15KWF*}6! zk%DW%>9Cm@k8b~&fRFjju9&o|jqV$#M&yu_+I?zsC~s$l`Xhrx5c^~P|3I#aUQ17j zv**m5xqQBR2@6y}-ED(#E{!&66h=q{#o8-91iZ-dJiCt?FpT5M2c#zHE{(*c7sMc2 z#P7zD>0J$u>Yya}`RO@pX4Y#&SA!aZFMEwJA^KW?E}R&P?3sAAXD@IhXfLZaDK`7u z9Vh?!n@JQowT=j#|A9KHpHB4Dp2E)y3SjL|59dPhOZo#D3 z*Y!|{)58{(x!;{Mi%@X6G5%Y38A?2dVM*i_@13q!1su{lk{3*fG^VUsrJn2YUC!4hsP;PPPv)qHze4b^A z-O=+pw$YzuT6T{mIg-h(pS&weQ>wAy1zo*j6hYV{$|%%)RiCu|!zWF!^Puxo;02I# zR1jrfEBWBTr_L@-RrcwLd&R*+|H85#GaLcrKzxjre@;k7WHO?6#dTd zht*E+$aq{l5oUMvwflqWiL5-3Jk1}WjVybr9mH7Qo2rqZe=O?Hlu-z2`=@QY&xtt1 z;C)wBCvG4;@&({p@f@fK&S-90Z^r|BnViyNFc%>r(rbgoGJIX&h1g1H{Ow&?^RnPM zUmE=}9DC=uZ25lm;rny!g?jsh0$I|VyKhx=qY{7oy16G3P?n|rccSao32Z|NMAo=k z|9X{wiup@mq!9pqHLW`6cgeX7bbDf*ypV;orQ;4Q2XGi!ZICa-R?H8{lW{!bb>}o@ z$yeiS%}H=SrM0~D!~b4sc{$jvw4LIE{<4WMEAVymyl;7Wvd~mdOjJ?%qP8K=S{f0{ zym7va@7~!_ZAolOFCy#Y_eCL(Uo#swv+|@d{+7jZ8K1toryf;}O~83)>dD139XR4= zTd{!WgZYMi=J4b3i3b%YLL^pbnB*LhtAP?cpc_~`eq!KvW7U`Cx1`KV;ok#6918c} zl#{hx`R?ua==f->;Pr+()`>+(HZZ9*mY=tDcZ#QbSwK<9t?AEa&a{^bK!V*TvzNDe z-5-$4h2tnl8c?CfDi2^eM2Q_!*f9bkogXMSf0aK}&9a}R%==(6o;-PD+sNvSyKzj{ zJLIL_8bD_fG+wbiSme+2h0GrGO4NmEF=d0G+U*bf? zgz~NbR`LLWpP{ps254nyk=qpyX{b3+ssLnT`>Q?6_|~9jR^f5;*re4TH_|K`Vz0FF zeRKL06)6JjX1*RqrJ=4S3J0AXe>@|1C)EH~h zbF7^nZtlD9=d}GQ0OVtL^nPrlIuUnPBdI^9j||(Q9=`%~dO_jD$U?QJ76-G_lxNbB zBaVzd=f2-+(DR@UA@0h(HvM0DuCV(0Mn0VObW?AzN&Myz#C+)oE={Yuoj^WZYdx!$S@JM{%pr^ZPF22V8Sr7Q5~DGW$kOW` z8mwpM-Gw?4$|o${Sm*wIdOqRK+kn#_nr;_EX3tO<9CrDs(W7>v>z|$KvHiu@UYew2 zXiM?AklV5yf8ALM_Eih(`tTn}=JwI+=Tilx@M0rIA#$4$mM1|!HD@ZQ1{7q@=QkjM zrv<{=Dd`FXzZTigcC4=8LX*M!HoLY-eEYV#uiEex2lNpLP~~yGO$(SA%owvv`b`5o zd0F(T_(QQ2VdNQWljX&357^8R9F{9}hovfLd73lCN7MmCaHCEQ(NCZtr5ycq9**KKQIEb5g6$|LT!wp) z9)GBUteZaX3`7S`AHhxmXh(DBGLYZ#^iE+*5r=06mg;h1&~0OLu!9fnD{C-vd}T0J z?p?jm>9wNj?m8=@C9!w~2>XZ673t+)Aelfxt|N~Uxv_G*@XEKQS1Gt7CyvNS%aDUx zD5aAMquGi=k}A7aPA3OG-=2|>GlIYn-*oKAZw?M97-vrM_DyoSaw6}4zxFLH zc*EsOH4geEVR~YbF<+2u2q~Q3C+4WprMjD*(g+nsGIBhX?m^+ zakCPCPi>^M3`0~Ked&Mi)4!pFVwd zc2%_$)@WhU1sV#M^~}5QoDXwn110E$H9GU2QFC09SPk_~e{WjtNh)PhOr3}8nlOK^ zrl9^qjP?=lxh7qn`N$04ulHrXnaPNDD&7x>9vR4vG@JkT?z@5RV<;IDNQE4Es605# zsA6cN=hf9(PpYjctg|PS@%zg&9t$0UGpq$OW2Y*)AHkw2&9<$P_U!shwO{&#eXao` zG!#;XzsxK2h3U7d)n71o{_ZdnNC>OmvtE6+t0OgVCh6rtjH}+R=W`$`AUAgJ&DRs6 zfiBT9gta7^0uo_%AiJaAUL{S{zwh&n6v+!O#~fd+L|a}=x->R9!1(EZe&7!+LVaQu61 zqkrA0?JHHKe_>NI&kj@Iic%{nzqYjSi_aMvLZ?m=R@9?+%wbpTFRVOTGhBhQ`@&dW zuU@8p7|*+V{_nRp%zHDlBKG{AI=YRM;$2x#%C;7Uy=ig(fnFzhE_7_Vv_f<{8{K@@ zEK|$S2A*PSo;^Ocn*Z*5_JL6EFJ}ll{y@Kq+^qR-#J-0^8A`Ny#jXd+u&k@LaP?Jp z6*54Z?XWA^i7mm^R+VNGWbjvt6_T7;xYCiZLdoJ!Rv4+>kXn{lMX1Ezo-m+LB_kknm!)dn)f z8*~p9_eo?a;-BpGPwJu(qzy8=AEZMHsgZ4z*ek_bKM^Fap83tLwd#7Rwe<|Opz)5{ zn*o_J?xbt=Mb};8l2a#%XenSUd{$O(ulVTtOhI!%!BBF%Q0W{ZvUZuit1k0xkRLwo zR~Ewg{JE$<=ZwktN7$7=4_1s=rgu)|ui}U-(tOrGfD|`HdqkM2!9OXKDAvYUl{jq6 zNsJDgP+lsFX&EG6Vmjw#km{mI1$?(c-7QC2eD2fJ5suLly0cwx&=q^Q8M8YtsTJ^2#lQc}Yeil9lWIn^@H&AFy<5r) z4M_c}1Kri>#uK=VAX4|XiPQUSwz)k@B+HIm|D#8)8q5n%&kbgv4f?x>w+&n_lid@b zBwwhS5)NM#UcTot~NAn#)-UqOhwZH#^Zp?0N5|0?NMVRJQFR8#E~qH~&s=7_y8lqD^i*Mu-NyT1)LwpsB9a2KcV&`Ce_{t~*?eBGoHA@cH(4-dIe zV;-x8oh`dQ-qI!tQHYX;;*(>I)^=B)k~WzCv}+yaAi8I*cJ0G@n40ZJmxi@w#kL0O zde+0`rFPEDF1lgt56!q-TtVWY=Ac;m*Nufpc=$}VMlH%>E$m5`uIT_GK#7beRG26z z{2WY5$hd*xCwMlwAq}l@D%(IM=9x^|0^gO6H(l5H{Envq|9(#e&aljZzBxH}Q?Kes zOC#+ux?epZ-lK_4p7HPNi2ODh-ww=wO`IkmT6v`lB z%vHB74)ci8BX%t@{(w@YYn`Yc-=Pih`_cp4BPUrpcwh^WgR(6Pc*-~DKG_uj%WBYN z7(0DJ2RF#ZF<0fTR+$RGsFUFvcUGqmT?ATw=SztiouH<4^i~Y1|G~YxOvDwnT;CHH zH5Xi?6+ePdQ+w65`rcUGy+~{&>M1kf2Bw;xuOpH(JQ;VkyxvAJV63M-*Ec=U5{zdq zA9j)uH|~eEJXwgHT7##@JG|Cz)k+`txDAcXfl9Sq8gNM=CLFRck5Ln1KR zFhfO$<3Nqrc;aHJ)||S1eMr#(x-8&a#SN~6=m3jwM>Nt(&WY@Y)P_aDhO3Gf&#~dv z#TrkNrZ#ECyY)5|N(I%Gsn~anvcl*1f)g@0jWveE!&>?EA>2j|w11nkqfos1iwavp zEArDx&gS*keVT_W$B+JiMPkYhs%}XRpcm5dn;h-cLmkmn9Fx=CSF9RJj#6v^CYm6F zgqGGnS1ALyOYoghtFY4yR5S51mi+W#`mYmzU}{VkNl6~Us=02~5LQYfQZ~Qip*K7L zT>>85M-Z@Io0x~>apCGQjd$_D_@!f!o-;P)%bovKp|jH+#jmBV;6pb^C!DNqWxbzc z>Fz6wwcVcXd=*NP>o0P_bjZd@q(0moH#)#B#eLC`rs!=Bmc|>1!ppbIbesytsZ2hA zZjbg`Oie{;1Blv$j!lIcV|J}Dq1P=CB}uQ-T zQ{cy{r!I|YpRYR~cMbIId@oXUO-y=6O?acxMPum79cUZ8Rro7K?x(sR)zYU3V};a~ zkRH2dk;%mI#KIB_N$Uq_RwuH|k|G@^A%YQgt4jqrxm zUOmh0vqPybbkm#r$nDG3nHl=;FSln{x z6e70$^?^r=P;h7$d9y7Nu0V-XSuA~-`60WTaRGr+%lWM$f&CSFYsrTh{t4wh3c*cz zxRz=BCI~*@Tktt*&KmzqFD zXl*D=Y#yr<7hn|ZIghwt-t9N=&_mo9HrGkbpG*Hh*4XK;5j4owqSBKvinS#MKQt^? z0H2UtZr4tUVOT`@0tLVBggj?Zs|GNG3mhOy;o4_gXOv|D*IJP&nTxo|u2uVH{QUw~ z_2{2>{s^(Kc<14VFQlctC@>+stVx25k}E!MkmAaYqZe3r6}h0pE|jDYX42zl8U7l) zrcEtcg3iKa>5&%%VHMpd&$X>$5X%KqwV(a0;z&BY^jEIUA^$(Uv8 ztUbj6RZ%v`)&2y_8Z&n&rdK1WAP1TB_nr@rZf~H|OKh79auV&%Sre2-jiCWphV!-O zQmVQ4lxjlE6(r(vij%LaG;5)$I-qLyUDTQ!bfRsG{U5US5FsZ*v--FZF2F?UzCUUc9D#k9>PVZG9Eo{jp-^BgEKXMqv9%B2cE%@5DiBRo zI5jg@p%XEQP=^5poSY9OXVYTpG_+8huADvgDlDC(df0??)EoiX2l+a~$#$>xH^1A; znZsV=vy~TlrO+7FY#px?chUFMQo;0Mp>$&h`MLCb2>xDS*+vjF9-6?$F*Y-1lI9n! zx*q&Kp8RlpjB2ip;u93S6>~x==4mc?Bl18B_MX~^M@e^NiwHEvSlxPUi;Pl`GQ|lG z!v5;ncTYu)(f`^)BGO{>4MggRzN6gPYwk{iR0h_E-UHi_#KFw5MS`OntSLW#YD3Q) zjTjCa^WD_Qc&4SXFZ~S*IB(_aq4A@w7RZ|}*8R)j;-BKn@D-{wX{Ga+!dwDvWN8ms z;lO8e5Q5SP7Npe&+i5f$*`w0nhQAFQmf7^85};>hP1a_}Os;UdlE{WuDbDkkLmJL~ z9-}FwOm5&x)j~cy;nv>tgQ{us?ucuS5oKe{Z1op(Bo26$#C}0iXELCm_wk%k9l0R6 z;Rs3~p8ecTW3EsV0Y`^nR-@eIrdwQ7aOz3jd?yY8>Icb`5#P+d2g?3vaRcbug*8V1 zmS;Id$1j$@5BAvNAiz|!g$!6-(9Ynf|Dc!MvwXfIkyhR0PKEu6U;UQ1<@uL3_T`Dt zR-y9XyFeU5qsBz;n%xCEh^WGfAg#umnZnUTRl9N&z|lQB4MX2vqx_TqMgE;z`kwpAsoYo&lXBr?Z@$xGVswZhk|56 zKyokX?xv2esECr$I;J{UjUb}7e0Ckx3`trn8BDy7gJ&7Euq(e)B;HB5cUwF_8q@<; zF};Dg<|28--nEfovE#%}s+EPDo3uQ<9%ac&%8}!9;=9Fj1f`mped5N&1Sdu35(R{7 zu2hssz+(BSlUtCoY(gZ9B>LKN!PEzbs8WWhv}&D4BVkpoc5E(k_x4-oj>DCMWE zUu{GA0>UQjeu-qjaO=E8LqJsnrfcs-!cyPa=IL33&M`Meo4)iJ1g5%=tUwu0>866e zZqX&Jl>ga~An2q2+z%8;?=a45TWQ5Q_3)IB)9{0*GT77Uh#;nqnDrL3qD{8pl zOj;%jT%X%>ac+@TJkW3DWPrl!{{#tKm&5n3t7qWQ5{Q*Tep=l#Ckp{GU5h0rnhylNN6fdBD460S z`Bc-%REScI{j_{zsTi@_ju2mBu5c!^C(MEb1|bUiGW|1?1SBdxM~F9x4lngr=jnCp ztxN6iWgV5IzTv>tdP)w3|9R)TkP1P*k&uwxfWPweGt@sHF0vEx362zMe(G|ucAY57 zpO)U)DFLNEO^8-N`&*4VxAr+uot+GpuQVZp2hJy^$HY4vxqa7s!_z{-a*iEm<|0wq zX5Zh$9$FhT=%Oo^aT_%#v?$_iSzU}iPgB6bmh~GcYw~bV3 zX<}_hZ#|@Q(V$Xm{kbBx1Tw8^h7#x-4ZWp?X?0BWW&)P?%#<35$V{Ng9ip7Co@BfC zx=3VF-Mg(!DxEHO%*${ZM?XO^9}_3c;Lzm37>)&&J57aTx&z5n?{IKM&G@%K7m#ErUF0Fs4*4%S<6W6*&<2*l7k6V$l!Qz z`(dW+w)6aBz!`PI7?1daHPiQNlo`qXpEEa_>%tyn(WoTal{r!70H$OUoWv=Mp z`VFo4uu&wimG(Tj^#_^@GG_wj0Me`0N4vE}l+wXVI=Xx>OCp(N%uVMXAK5%;SWlwT zL2LX+wUgUS`Kxgr3DyeEgRID<(t`S0G$bAS$zC4QYe59ztFnDbSqP{5%D#)hMR5GR zzCHrCQA!W7gXndb_hk~6(%ZAMhZn`=)@a3Pda-NAF@Ft6?dPMa5ZOLRqFf!q!IN0} zvF5I9bb)ojY5WgO60=AvL*JQUov`W&Ju&r-&Lrc?e~>gt@ZK=#3N$z3*Ct2Cisdwk zZ0=65@W-Kf>4#2?o~_EN)9s!7Mp`%W@PZ>Oc<|XpF|OjA*3bspSCMhvNwZ}r&0BF$ z+`#Qdr?TJv%-X)23R`@3Iq_Y9qB+4`@acj#bh7pkb=^wtXGV>V9~V(MFV-=%#oNsb zoOjyHS~;XKRkX*emZc=a68%vl&_`v9k{mf8Z9*vw)S&rxfs=o z)3}DsD7VwCiVLR2TbUO32#g^Ce6;=|N8GY<@Ch}9^?51ICC z#AUV$DDbf0s?&Vu60Mq3<+FQum1=o{R2RcR(yQ=4*2OC7tL11p=$cj|yo#IZp`ksX zaGl)^o;taPAsK}Q@Oo2ISBl@dRSBf~#zjU;tMRpV6BE<8KZn>8Vx=3Ylq}T`%`rg_ z#ilRBNIYkuWMq9B5e0efm4)U9{8j-zLf3F)mVkr53N@GiyuhV*lf@hr!n&`lx!=~Dl1#r>E1Gd4X4&d1LsqLog;0)#LK4MI;w%&W z2<21Z_@aSaWAVQmVG8DbVZ-01?(OhB)9!h|C|(3sK>s;#MIuKI4zTqjvB z{_25u&u?&1cq8gS6d>>;B#EHpBz=}qp}qIMsbuIMvruaoNiE8Rp-Hzc6~Z;Qp(a;B zeE}@RRKTB4z4qm+GaO&W(znN2cd8AS7_Eee`bgQs^Gk(@EqUtVUM8XzJL)vDx!ztt z4rSNY=oDt)34*C8;^gtOPncPTMKl+Q(Yz5fWkhNU;!fx^Yw4P*0`O25 zt-10DZf0E@5>=>bVoUM-S${)tyV@UwRj`Ni^ln(8O!WT=QPnBIz#IKB&r@dOA zZcY}eebewoD*?l^qjX?zhc$Z5-9!3+>i|gQ_m!T1_ZQpwp;)IVA$iJb2joK-;nu{a z6Yx5XMoO<1QB51Kiqc6Fc%4U)%~(K|g3L9-Wd;|g@eMgY0(`YORorXu^`s?zedVD3 z4;25oLMc(CWRUvO$f|<7#pjsf3_F!S@hwFfrkGnIvm-Y_N<{wq5qi3N_D0)kw9I2Rwu&3vGb?52&N6-(@1&3mcF*Ms!) zH)naWi9Uj&AhgU=hDLj8(F(8ue}?ja_Qb=)ESq#2fMizctYri>ZoIWIFK43=xF!$< zBP**ZqSb(0-#`B=6M>eHj#}Hm=I$ruH$DQ9I5!vvk*IIioeD)&Al$#*(qS38NP#;E+(nDq!sD;VAOd2V@1S>e80`?y+0aD+}G%XgeK!~H< z9@l3{3oG0liAS2Qx(%wSUkr%Qq%r1X)~Q z`z{{N=Rb(|05@2VF)ITz&>xwnLOeERe)r+=y5?8fEAO@))9Gs%0ax4#>C3)3QL8`F&$=j6S+6?Q9xBxYMJ0C0Em*+L(!ro*AT|CQxAO_k?@_XrA z@0*JXU03cMDs-HUPGHXikX@gpG#2*GBueGz_DsM@s?SCL2QiO$)Oe<JX_lK_#pM~j@?+}A!W6JFwA>BYk>qyGsvdqWOM=(qgHXQXpCaK!1-TzgZ9+24%JKHT=@g!DJ5dqnra^Y*MQ~x zJEO(&5@_65>?t9=5jO3Q|FbEI$F(uTHx;SIH$OSIhsCzVnG|H3OD@~V2`38Z^)pO@$(fD6weF*GEDfDTNG(ECpuxe5KsnhMnC6$$CIB^<_n{W2Vn?D?q< z(f;C?;@?Ioc)Tc5d>hmJp@v`;Q5t&$|1-Q!SE6dCJ;t2-13PLj(v`fWOUi!_gI9w+ z|H9cHvW@LQ21&qxT#H_f*Zo1=b2sF3+>#;T0}fNY!Es<8UeIg`*j%Qp2E*|ST=Ym) zsV3;TVTKyJR1u?_wKaVI_E)=4ZVs+%LhF`IH0HV;x-)+7F_1&1qlw)X(Q;&VgWu)B z&sXJr)q-)jr3nM}w#VOl{c^-ivIF)ZLPc-FEcNkW`#au-L};!K{@PvzwaT4;5+U>G z#oTyZ3taW6;Dp=cWra7F&eNzOfgqJ(9CSEk7nH6G$PysgRCwf>{$JL)yN@Z6Eho;k zkf^znYHH54D*(6CFv!Kkxr!^k2=mh3Kdo;0DDhJiw%@!NwEtBrMRXidu3|d`Ge?XN6DCh@j=i$B$FX+kV9!MhW&0Mbx6&6i z7O}apFU#VlH|5J5`q3%3;=W`Ws+IbB8%IK$?X=dqVbdV|=5k~I&>eoSf>+b;_?a!1 zl`ye#*tzX(=|96i7%cd^+~Q&M_psuXd~{}G1XcUie*}b21WQF*ecIW$a;b)eU)m|E-~v5NEN> zk5MlHs&}R6MnYoNeF(rGj}|m%pL;tjvAMA+-}KDNqdd6aOPq4t*XQScU7VyzbiY`G z{fiTSi5QL3*fHE}VMsWv8RT8aTt%9SqrAY8;$^60*Yr`AWgl-|L;TP0qanM(x$>DD z=O8_P<h)baUfS(<+{sLl7w11{ zyHexm{W#1=%lQf#kNn&k6pvLtYA~4k9}oW5VGuTZ5R>Wuv$}h}Qevh0)_R^89!f7e zul1wd^N4sdN%rlc`9ETCQQlt>P?hSM`l^N52ZCYt=+j8B@z8CIb2SzcF0@E!e6P@o^R(W zjFHU_RF!L-Y&}8BC{kHOi1ps?y7;l#wj`e78y}Wzcn0>7~(9@Y}oRM&!Ox2wxAh5nXG4qqo>O zl2X|z_7B5DQ!JJ=W}mm)-5r`gaqGs7-D8lkz>f!QpcStQieKC18`XDT^WFHOB#kvf z%Cwv#vEn(~lAe0AukUJBks>qU(+9fM{fJ#pt%>3LPTRTNstT>ujP^M3^KP)xu_=x` zIez_YMVA9xIZftQKibE??en`D!*{WyAMmbxi#f&oF|@Wz5#D?=DZP2VTrbKN^*3IT~3u*&#o`$-b7wm_}t=9*c;Gf!4dc>6`*%65kj>;Y?x`h-d z|Fe+LMhQVMtWR7>espbUq#6oMlr{&#{g$v3n`0k;wRqJsSYtr*?}1IGb{->8zv?Bu z8cFIr@jVx{wplZ5kIf+%lWV2@B(vbvQO!5V_hhyL0Dt^?DUoxV2tyvTH3RW3ywsJ6 zrOYp(XtCLT)oYCBB)-6d)x2{bO-G(K>s+~_;J*8P+Eyhq-fz`=GqLzv&!Fpco!xtT z3FIwxOgP5w@79Sf>u{36zE?3o3?#K++ZnH28@^xsreS|aa58&Lp4kHKc9YmISwp*f z*7O)6s>YR$^9l8T}AC!=G8gze;D!(fB7!AYb2Rlg54ULG(fTCVGs*G|A?oS2 z3l(+IA$W7SKVf(3|A`!b;D7exbLbDq=)pRi{r1j$DSle0o5-%>Qhr?AUqC7`JZt^J zoP@T!jEw|t`q+Qq?r&0l&GC*`s;WyO#l&s3fn~2d^4If2_-~ER9l*xkqsq)slU_?- zx<2(npU0ngQC$-ejq=hd(2xDaz&^)U#MziWkJ@ze+(gaHU;L!~o@Z8WSyRQH z2ez~j?Q6~-f@k5rT#AhTSS=r8?~+G=*BF{@cshTiYi4fIJK3e8kQ)ACzueA6Ve90H z@kck$UqLH>&T?!cUmp`Pw}q=lKG1iqDYLmTMv0Di`bt*$W(#u$$8p^1bvV)DU=oCM zpwel`+%KU|1&?P_9+IxT8#G?noEJFJOgH-<7iiK8yDRqofW(^XtWmdr*V{lTP5Qxq zJHEcIU*;gN$swl`+od0W-D7DhPfdIvF>t{sETd8@QfhnU7vT~E@Skc{@7H8U+i6S1 zBD)g`*bg2$CN#d@`?J?zz^MN+{(a>0UrRlwt{My&v&M9v%u&YtvCje>%)D7I4_x6W zaQz;BOs$6vCM2-=-Ln;;XFmA{{B6DQNKH)a=!Lb9J2zq16+%n1{0W7IJKrsi7T+Qsh7W zXApwTfi8td=DCfG_x_eG4xf}PFJvHP(M#~!gRIn2^Y{Cwzde5xIp1_DFVI?0z?kQ| z{pk$aCt)1Z;7sKBM8SLGS1T@YJ=T2w{rlzg!r7E{rnah+-6Yw}OAj8nx4u@l*7G9VG2*^7I`k9 zan#KP=EmRmvCrA)Jorl}+V$^`FBj81n^Sz8*Pg9!Iumr1(5~f93x-WndN!ZZJY^EU zO8_HV=5M^-RJp2qbgOt?bPGJT0ZY+_B>V)O=V-JWR;zA9wATf4@rY-7!J%~LGH!aw zIgBj=zSf)zcut(Wj|;?Lt?V~9`U{-y7s{&drM|FtB8a>m|6<%v^#02U;H7#>56Ac` z5WKVWWfwo0NU?^Vgv54Oag<@Uvzm-8cU_wA`fS`6ehOQa61>_jt9DFOr$9=073Z0t zl{-F_jnLeN=oUUZzB`q(M7g+KryCa9xdwpVnst_rFP>yrypiz^kp=hC6Mlcq9}Q7m zjyy3gv)*+V4Y=IVH(mEwukqp?iLsYjei&a?>q%aSn>Vov<38J|8DQ%es%lD=*MYA! zo^uRm?8#RM+55@lrf+liIGF7|trPSuc|MpLJ#DLj_zmy2%zd7DJGk1Ujmg!@GN2&` zbtT>Gcc_v#r>LEWTcoIr?C8l1JU`zHhxR4f;ihoQ{0F|tCD%`=zD$hv{q^#?%Hf6B zd*P79UrZN#eBrjjP4(UT0`?q&?X8dCbq|&Md$e9Al2k`42K~>2#S8kD)=e4D5jYLvqhTG= z|Im~?gWH~$&uOe#?zxaFK@AM$y6JCi5duf6G1ffVc@NSKkWuAG_CHU)OJeUhMF0%8%r)~_ath4 zdGmJW16^7_isU@x7i65};U{IWsqRCq21bvtQ`aFaHJqzz=g3Qj_W(dG_wTwsdy_!7 z%$R;B8!9R3Pkc$ZcbN?{t?)XZzY$w;Z%*AEqF{6Lg49QF(|`q8a^PQ;_E8HX5AC1< znXH4^Qs2<&`r(6_i7+AG=h#z0>cnUF$iaQ(3i(qUBvMNN1 zSMJr5SF8j4Rrnp<6yap*Dr!$k08RIr`z2z1Q z>^)27rN$$1(lvrDXXw^-htKzp8{S%!eivZ#HNU3@U-9vKmiLN@_lu;Rh|If9id|#gxqD$4pYV1OxWLVl86g%Med;8WZ@rQS+qwZjGmFFTX*@1N)w zq44&cQFrOy+gwyyQY@nT^%cnS);Hz&3ojVX+Qj)va!l;}N>VxOU-3PP*YI+IWg=h> zS=h~girG4+IQAo5J!UH2DYrN(yYts6xUYE#HI9cTB>;|x%`?@%yd|6zF-9yS`;K(o z$GPg_;z!~r;0ZZ(mYrp`wL3x3oq1*p+|}9FLOI*veR->Xa^kVT;XZ7A>(0>RjhWFiqbB})m(At3+>zTOyT9L1aXg)L zb}7*$n3?}VeXwc5Ovzj7j-`NtQ@U<7BnCAmLpO)t-3&wtIT#$@%L@eO)oxQy8_BBQ zOXL0rT^@^tSO_#p@jLv@}sb=}de_V*}{&nteRPu-c0t1@sG{{-? z3Ara++F9o0Sa!*AT9%!DCdjeYd^6(_5>>CLkF=cgZ&W$6I6$n@Mj(4Uvhc3k8F3g3yKV=5=P=wS0{ zv2Np_?#X1#Ek<{@Rq_q3;O`tCX`KlI%kK0Y%G`o0eQbw9yMw+R8vfw9?UF^XQ)ue_ zC@46@v}~DN*ywZ%I9ikfbn#ErjK7rzkUA^zR=Q7Yqv8&wLgiY+BXJl*-M1s8iD22K zio@s(wpEJ0`R|Gs$wAHm8UN$EdeCU=gYUXX-PL@-aSPvQz=6RYVt2hdh>mPA{i5p| zntHsQjoQGL;>(M5b z&3k4PX`N*-VRRbmcyC5G818$l5VbXdMiljY{>ckcJWWw*3zp?4oFZ4GNM`B3Bcj6q z9r%2BG?iVo>Ou3DrxHYjqC%}%c2uWKub&^fpu~eD))INP8dLGQ6lT@HyUmv+EKR{V zR%?{vMk;V{%rJ`s0+B$-Y%S@#A*uyt2>W8CY|f}Nir=jaLt${jQrdj<)~=i-jM3_^ zY`UQ|DE5O#gPPN&#lkVnJHTGu3}TwN7ZWXHYE(zh#nor zCxFuU-F9j{J7jBz%)6T3p=Zp6aVlc~o~u|f2A=#M6qXga>h^++ zoHiz6j1nfDwNF+`z4uBWTa_4%^Dbl9J>kqknbd0U0E>}C(^V4R!9+0|9j?I`?JHQW zX{Dd!V)PML|0%wjT2I}sH2`QnM)+Wv{vKl8V)1C=Cw61ddwnT~xX5`@FJOk>>Pn*D z*P}}#t^#**P38wFc2ByqLy-OrADTGdU^Ra6PheeO#j<;2PZ++@A*hQSA(S8PBWsvy z5YvjvTE?&+Dh5VOFRoDyCbLDP6SoN4d$`@**fGyjOVy(do`_y#5A1O1z|2TOcUR^; z@>3JVyh=w}{9YG>=E@GpEp$TH3V(E{1-_;IKPcvZ=CnA~pzo_n%Wp8i^>vjPsOssl z2;kPW3_uj!69IW#moqCDvYm9On%9Go#%XQO*lKy)+HrymTb-BC5qHkV%FJ}aR>o#{ z2AQ-g@5{n9Y;yvA;5v7KQ6*tR5N)$57xn{5UM9k=DCK7hT;+cf%KgMG%1ODKUI|Bh z^p7am9&DiDwTpXbRzG3AqAEjHa{8jf96L`kJB3I?_ zEu-XXTmY4VfEX=xvG35uxLJ6ElwHoq^I$e<+RDM2ETf6e%*Ert<-L3+d1AZfya8*t zITbpu6>c}k!|)SsD3FrHX71l)Mx&65jM3wV2kJN8DbekmKaf@Hqp3GC;!g4%qKSoz zlWgF_^)#SuZ3UA6;K);5AxM%{fxC{k*IM)*iF;%yGdaI;Zp@=3-R?ZSZc?=7;z2NOLUFAc3XdkkiaMxs{eMzZ&g+d+-)W-VQ%As1aZia7!9M&m+jr6IElC z(<_BVrV~GH)vKlz8J%uQnYCq1Xf@UC)WgpK$Veaa_+-dBw`J2^-$;umsYlUeL(-#J z?}H6v*YQsdz0rq0P)3vng0JqfZ}BDY6C+iofI-`KV8Ay>L}md+aBfeO_>)tx?XWXI zv=Mrne^1~vszwd~fwq|4T37308gx@}oFFIrf$?Yz03{dS1JWdI;msRhVqREr+k*TK z$2W06!xZ06V=of0Iip>miy8aj;gT^$q9|ftQA@|r$SlNF{*5C%!3Vh={6@bY5{N6{fx$MAxqXG8tWJfSfH%nTj=pv z^5RmlUM97oAO1t+!G3dO3`S96#maCQ&kj~wX$I&s;T&{)1ZI6gV#`zJ659=r*U57u zOxSun;wHFH4LF_golIIsoF?v?GM{UQ(S;E63^6GeP3*_E<>Y;=Z%$*>&beV)TSoGW zv=~*taxQxDGk)rd+KKkj8Tet3DkG-4#C&l>DGMlga(cP<67lfjcJj%g**lTwr`*2Y--|+>4Z!a zqAyavP9r4poBhg|C@pxIkUegVLil^a3;%$SsfuS?x%n-5_QVm@_cCyUfC5nF0oY`NyO-7ZaO7YubR^VhFrwm~RGMqI~ zpAITaq1@|y*B)f6rfXz7z@;?d%qAQ<4m(QNBzkdXI-jjJ)LYiO=QB)f0U*mx!b`2V z0jr^dw~~^fxlhnu;^#{-Ty@g4&d@2nw&!1)1et$yim|_35RU#}fOI;S#idZtu#K5g z&~|Zw0c&s}wZP}gVM7&URr2&Tbg#O2hQ2Jcs0;w(#czd3-Jia9 zKG4aOXzaBQkG%#>+9~t;=9H*qz8mm|t0uFxp6eRJFON)(0J-M0bbEml9C z!#&Q{JOFr!mCBUEfh{8PWZJvsr7t!{O=IX0p!_`P-0EASU;lnZZ2Bv&-$uY1Ay}w^ zekUTj;A*yf9o5idX>pn)a*x2Q#ovZeD2mIZevtc@8@{hDm@Sk}HgDAmF{veqt#S`i;4c$#9e5xrQW4&C1HojblXY5| z(L7IW#6?m8;mIGyREx`hI_LS0gC<-n_)5e534MIM`;EX})@Y)w88~)?=ZipruG)Q! zWzKily#{F~0}j`rmltni-W7{O6Awbf(2L5*f$P8WnwkbP3O6DdY6S<>xZfYXrmC8@ zvSu7zV9n^t(G@q77WQS9^wih-^X7Fvc0N7A>rDS9D3IR)z;hMzTQ^#;2fh~*4kzFc z_Ygnuk*gko?X~7rFiEhY)Tesq!0d)3(SRR|iOYeQ!B5^3`|L(~j62_(7;P$Ei(f43 z^OD>wgN>LI2n(wN((4mMa!}$ZFRlFp&Sxx+9356}>+s}&Iw`3e|HsLPzym1t==}f- z4xiq&#Ov8QMAlQNV#ELO%QAc5HDFkzavctZDGQofH?FH~Zv@i>p)zdePLhDaqxru! zL6JHaR#x54znO?8VoRj%LG$4Wv>lL3e@YJzqZow}4<>-s8SIN-Q3$q{bBYocX@*WR zEqkB>D@osxvGn+JR|%wqAJ3r?D0)>cgR5drhU4Is@BjW6fodCx^LZCakYPx|zu9`J z6v=0+yG5EO(tNuUykp)pnMWA31cdRslCo6dib}O%kKXz!)uD+hT4F0*=OOJ~gb<_J zM?7%GaZIoFX_Fp^!^FSU4RMN)9!a1ZhJb95B{`@?^ZC&xk=?cP4_typeO@6n_@omW zn~Af433_97>fD=jjcB0-U`xwy#`V`pATS1f6n`qTr1B_k=G;45(-uH})oCf#U*cK< zv?-Jp?yHu!Zq$|Q6w=Exk6ev%%goqbhA0DwNKcWfuB|er@c)x5w+*lni09q?rO+eg zU_Kd{2!WVvVD9P^HxW?aBdz_X7rr|xmNaxfm*r$0Y-iz44eg%rSOlh~x7KZC zpzy){PLKv^0Oc1;;0sdkjHO?Z6u*mxPae9k+eZX)^X9-N^>zyTsY970a!mwOALTl4 zg@hG1$}Pk-d?QHCDWY7A66)!UPFJ!uih~kG0}E%KXA7s5gPH-?&$Wl)>E{=xv?1&} zIY8;FU!U>zAfhvWr~?d!d%ukSnBtNhsu-7cEToWH&<;X8LBG6-;m+>jGOZ9PuG*m8 zYl{lu8oeQJsnqy4FQLGx7@0!e-QIfZ+9)2hkXVE>1&-(6#7z&(v2ob0%zb|QT)nB=;B2NnZS+-!(2%US2RWaspEBC$i0{7WJthuM1?Cu zV<Au>qkK}%P!2`Dz%lCMnSbw48uw!ycz4?s!MA6)Rir46e09I#wIjy8)*+Ivg1jum`!5 zsRSl^i~TyuPSd|o%iP(=yc619%>~7FcJ1tQE1NJRKF0|Fb#{6IU9b%H-t=svPCu~P z%K$%~Dfby%weDO!XY|l@916vqB*1W3ZGpJF&a{O$(ES1#y~=GIw>O{wcA82=j_g$1~^|BM7@k{JWj;7{uRSq`px9!B^ z>li!@&0t#?yi^D3g+{b_h{jQZd^7GuhuNZ9K5+CrFcu6HRxaQ8B2N)yq=^RX8gTH} z`|Wk@j%eWo9vLzoY0UjFD4N*McWTipL;nwUs_0-mc6YLaz>ycOc2)W!L+J*co)C@h z4rFB^v#5G-o{JKS%cUbN4n&0l*QUn#1fB)AzxyBr{cM?thEa9c4W{OHKxuyF7zDoG zZ)yW_QP1_GD*Q7HZFLGEd-Gc*m(L_;!ga%@;~8CL&kYR*4=FD6J$7gR^F4^=lw7K1#QBju) ziM1)17o-z+lrp64e^n&C@-M_2amKwlL^q@QM>Cw)Cezd#>;;BChp_?}bK}(=%QrZ z0wlQ_JK~f!Y}h~)f6qtz{5LzStGL{NY67Q_dewT~@cX+falgo$Llda>9Pa`L!pZ$O zNvMMQbH+)khFcIIw>=AZ_#z|NqkZJfNY!frL90uQ9QkA|#_`6k2L_E4 zJIM_BxcDP7(;r%m5@htZ4=k=mUCIrY7R_5_lr3e}BT!A8A2sIgoWV^rBzcij32v12 zZ)cqkZNy5MYX!HCAmeiKq+U|%T2|fQNdx*qaF^4DY>(ez<0FM%z{Eg(Ve-eU;5Y{l zBAhs$#l|*uQHY0{(S#YeC7GzxxataHa%R(rX|keIq~O>@kp*dnebqH1Sbr#K7<^c5 z16%9yG95S&kr3zgQr^IqK??Pi!??EobWjSUh}}w&lUN;n9>ifs>{}1_8XwD@UCM z6d5HrV`scfUo24fwo=bjdc!vkF7ofP)q`>T^{W;<(+-3wM*qs~0fpGEB7i^;(Oje$ znzLkI;{Q=}?(t0he;hvybIYapHrY^9ZY5Hh%a|^1$^FtrMI)Cl+T8DksKn-4Dxq9P zC6tWZiMhmtQsy#7v)q~c`2NoCKaa;e9ymVd^ZC5r@7L@3B9$qfj_>1X+0PlmujK@x zzsTu@+h_NPWuqYMSv-cv^_LqFtxf#J^*+WDJv_6I{SSEW)qaZtm&>t>o`3n6MXmr{ zb>p|~r(F`@f$Y5);fxva!QA?xQ(eE)8#p5cXn?g2O0Wc7xq4FEe9C%>v+wrD5L_te5SX#`C~+NLp-!5H6M8`iN*q6M zR9H&g3YsjIDKP2~d@yPymQzHt%)#$V#q+sv+pVlXKeaiKx+(yzM4*Z^nf$Arqxk=q z&krdWDB0DlQx+c&Vz)upY@<(FE)SasfEQa^Uu#;8gn$mTgi|!4Rf&ss^fSy-P$WEg zRp>!BVq?T0DC@cyn|2`zjy1DHvno0}t$ZpqY)?ft{e20Kez<%q0Rih~!gFhwMd;Am zHRAy^?|Wjx5%FnkOI!G^5}1A=Ge!x)7%^6iLjX&0g}~x<#bRi*VVS&IWL;xWhvoo5 ze)F+UA~HFcZnl}4$#;e!zFa6D5vMDb`5?B>Owr|Zv92{_OZKB47Lu!y!@O^kLvlYx zU}R7zfLI$>nNPCT6xD)afI%BB1Q5$hs@s>6;92MMpc^L0Ovh6%h&xBvy75m-Y@-$k z;L7Se&_x9x$w|@`U;V+(97rz-(Pxn?y~O6V2Rp(x+5tm^4wIhI4n5xJ!!tx_&+)o&UPemKV6ylh)Y8?i&Ra}mTFp*G z;2(mbYIrn^$~GHI95A^c~9)MGt+v1kW!0m6{zrgen6|QLV zq6qB+_^xG%9PW^sj9zXAnKVO{sqe!^jKSRSK`tl1KNJar!hl>2RB7R)fkjX^$VYN; z5Zt~dz8U`iMeXhKbuHCMHj`%)Gi#6u3}}drGC*5<+mcyTse*q2lujm_hv+O~bXtep zx0@C4)Is(DfmhnfvM{YzCty$qu@_a+34x^T3?zUX(1lnqGLKieV~i|UQ`F2L+*D#G z`5l5KFI!oG#H<}Q#|9et~kj?lF5rAOPeiHgFb12;A&5vL9dMNdGfp$ym(Bxi?OG*fB7E!-AsKvR7O80ue<7%J$0sO%<qI3gVS0eV1$YvzlXw^&k_gdF05}hJNC;rUH&;$MG%5<{$4#o_zy56MV9k2yePA$rz^Cma z&EI_$a|gB$9hBbAjBoLYM!XA{3cPxH{=1ZK^OgKE>fSl(>bt@d(MYbD?YX%`1*Sj6 zV%O=VX`8y3ed1CllH#ZK!{F4VV=LO@xuFMWk-TbMSibEif=YZ*EgdmMQGM26BoZm} z+u02wJX0EOG<-I5gXhV=-s!qs8nVy}Z6NT6$c;$|Qajk?S$?+Q z(W>Sk8u}mbZu!08ITyEUAdcn;m>vV)*;D=Z`R#v$Rv!nBHRUtHqfCnK@&8l3hD?5w zZp>U|!Iv+a+)H5@{OM74bE8_|>9K>v&u_AmRX^a~n)acna2FoZjgn< zI(waF396_s`rJ@xI&Ia^A{(_r8c566Hj{k}gR0enc(M{ILsh`V{hv5h=6?m^O7kgZKH0xJHk!;^`Yr@M`_lm*)T?oYGEu{&OWj+IDs~| zFkXJqD**Xn_8}BGi^>;1Kdf;He!+MO00LnP>l^Qly%e#34$S|e4fgY}Z-h8bl6~J* z>j3KHWcfSZ!fqpd@ zO9{rIa`F%Kcs)fOIqClBRP3ny+CYK8{b$LG`uHKS0{LgsulRZ;RgUn6&xExg!R~SU z^<9erpU{1qME(FOLM)~TxQ164(X0g%ALcR~#-zJUWBG{Cnsu7ruVNx5qy;oXCq4t$s_kivkCO`Z%nJb3i}xN!0kHOc{8iU_bM6W;>iS zd%)wS4}bN4Ktyp2sS(|v8bH``?6mO6HOW^D*(^R5fAS||!C}M+M<4zbg(<4aD$p{u z=FZCgVXbk$I6fktxK$`BnVdG5%-Fq4-qlb`hu~w`6qx+}TcFABFC(SMdO@@XV6v$e z#D706=T5H#KaF2{_m6xQK3KExKy5Sg53&wR>hu`-l6TZgi;!ia5w%lJT)W8~LXi(V=($9Lk zN!hz2#z;M3g30bzr<%wct^3_S(>+Mlt>k@vW$5a;$vmMm)dwMMVL7DNyKouUs zULyoQ!$GueK+<;ft;UPMSSWXk%_%Pi=f3CLiEjiMw4KCbUo@LqH9(V-#LnTVm5JrN zYj&iqP2UM45E$ST$F*|=bF`h81yQYaPuKtEM}Ou(+e066RS}UN3AXLoc^0vE47k?( z{{ikzKyRvkmm+O9pTlh(7C032H+Xo<>gj6d#8C*;`KZQ2@Q>M6ZYF zUGMPbl^xaT=HCK3?AM)#ys-zWe78+RV;+E)$#xf zCn@s#8+BaZnb*BnF@@8ttp?kg_ovW%b9WCZroA)jaq$z@C_wWLTgbHBK2htoCas`X zfUQcKM@E1cgN2t_nn%~7)lMKzn!#L8bP38hOFU=B#n5;uoXqN~P!?ax zz)AOq!Wj868bra#9YIs~Sr2s~MtB{!rDy0sVa-z&ky+JQg_r%0D@4x|g4el!Z_fRm zr*~dr#?!`-GVH;mtCpy5&%xzdbLR_w$X|17xEOzi|5XnlQN73;6NK+X7m z{+R1hi!!uvx$&*HQ{q*l>1|?+6zcB8p7-yeQ^)ucQGI$?v|jMr#J}jencYr}Yf%&T zi#>VwUj>~j`S-5zb;E~Butk3X{+mRH&m)qxr|MU@58+N|$pFOwUSWPQt)XdVkyl+{ zhjFWz>^dKj`uU1+Lfe^xzakSsQ!TL|`A_M+qes3X5ucuRDuxH=s{|dFy}$YCmq+EE zN_wfRGq*d`7P=YLr^&X3T%gKI*b~92+gy}NMsvz%L}dj_WYo3yAFO4AnK|6Aox7PGJ+TpBcIw)0R&3(D7?~QrK+P`>qftbW4 zf*MBo;5XjAybudFqSaRLj$L8or|nCKCN!8=&OSC@?z4$XXG zaNgoYW~*kVgVVUKT3|=G+q&G4%+vRQyQMDaAt~Q^B_Kque^lkw8cOXwrLLH)D*#k} z`relwPDA>DvfZENkzeS5__;pKcDI|BBfhOC^E)C`>^8$#;L&F8c*3^wirKEy2-ZfH z5YQsy2K zDNa_TA2xR+9%RXG20@^leTQ%3J<^SDX2V1+m!lU2_w*dw8_C|3n{F@t7TWF`QO(^d zf6sl1=<=)6f39&+>|!9-#Je%!qOt#tOcl?`*Z1tRC8;s@&6^)BJ=I6dgl>~yWj%90 zKJ!vteAFjS=9C*0%(3m*x;~=zR<*D89q7%FIqtjc;nGtJRmLrfrg54&eo)lHHT>6X zPa&JyFrS@>;16v!17u=nnDXL-bdZyK)gd@eP<0G?wefeM&388L`Y*GMcaK*ToMB%Q zXx^-IcT}gQ!lwE}M8UvD@Gf^*EKJ!HnY=>t^PUrY{V8;MhZqHdni(3TAGt@E@Z^oZAZ{A;yB!eK6dtabwWd`5mBh$Xg zywW61GP%2sRYji9hfMAiI=6YezKHIT0NW(PN9$K#UnafLxIZO7&Su9t7k`T3 zr}O*^Jc^NjmN3>4#;n%cSh!9_!22}VS}KB-bFYde{JkcC0(z|b z49h${P2dzKWqJQEy!N`{*^H@M}!P?WAGvwt=340y@w z(0MO1d;J`=I&ECT?Whq(vt}Q@UBKs)}eREZpOmD?U(j_ZHuuo} zry)+m|JaeVy#KM_ zzSpD^$veRx&e%UavoR2R#7{xo+C(6>IMC*{Ntoe_N7AMuG#%*r+|_yt(Gs63AeBP7^nJ3z}yq8liTdw&pt!N(l@7JukSBS9DJk##l^gG~I&irH!N?lKP~R z92q}jOD>QEd5l#V37<~F1k#fD5!&V3?MCF$lm5QKXRe#T4<63nSim6Orz1O`W6~7( z3GBLGpwjfu=L2~ocFH3T&Ny&Nwtx9Z?%OWlrq6wA0rB1m7+3WRd)VUq2Xy!wQ3?{&JtP&cQeyb)QWVi#V$V>=v*0MRQ8GtO8(eETuzlg%WS49Yb& zXC)0I!dk3>7}kw}DL43j>_~Z`Y)&^$*3TaW-yylSD=OzZ&vXtKbrkJ9c<+qsOVMx~u*9YgQ0i69KKd5nK-Rrz z!tIHR&bT1JbRt?U$CFT#te9b-(>?8h+6id4`sVw2Qw7Bu4!QHJ z-(#&r{@ zd5i6p?>y5{h(eo8N7%Osn^$6!-NdemZO!6T&xxHsnE%wp$wLPSMw`f!io6MT-+)iZ z-<0aom@}+0CBJ@9N2X&y4Ac=?W`FpI$ghDl+X@&ol?CWd-8*+7dJao8upz3lBaQvH ztRO$Ew^vVmugcM+r+f{d%heBO&q-EUip0<^uhRVl`gK@4Q3hG;7pbST>UVignslQC z#Vs2&a|3dYtfk<%&2FTVStR+8Tr)_2(&j8za7C4SVfJsEpJs0SYgG_c+Z%YePLYr$ z1L9lD|G)4!iN5b!!cH~QkOrs62 z>)m(jn`JnXMi&TTVdr?1Vf*0T>Q7p%vavcee0!jz9Ix_kMQ>9FFw>lm@j|Z6#J$K; zf+)*SEr1U&g2rM6!`xKTp&nf?AxTQS&;MC;G`S|^#H-0a@ zv>TlMUhcP+kYp+w^d^?}ZL$akmncXk{CiTg%;5G+uO}Fv_h7vz!s^kB6R+X3J#WpI z&o*OcYDg->)wo*jyT4R^A!ucL^c^m8#hEfL(0?v!M&7K}^n>)X)Qu1Ia1zF#xXJcD zaJoJ)$O*=dQ`M}%r=NJC0#12#rtO4KWTmmOt-CcTe5bg`&k9q|JWuBioo8bXl(0G7 zfJM$go|U<^$&9IPKP1G?tbmKhw8;Fw5(J?Q)3$E0Nw+nk9)ds?1lsGB`0!`Z=GY{6 zPhL5c)Zouo#{J=vcHIz5&8tg&D$RiDIXR)uw>%HyV@DFK#T!mTiHXnRe-dOnnQI0^ zI4>}%XV#D=EyJ8)?}ru>Dv3BKOh$)ITg`vf*}NKDE&EH@&C;k13+2sAeHd-vphMk7 zgX2xysQ4SH?OgZ)P_$^oeK%?KXx8e{Hw=T(#Jm&e^&5P4w@>X|ZHP2nk*VHF_qygQ zSv_v-Z|o1OxA0aG=W`#vQvY$8N5F;xlGh*x+3)yY5lw-oNKYNKR$hLIgtpGMePHLp z`n)%-yZyLDWVQ_A3YMOXm0^RTWU%~+7f)P2_#dF5z3Nd7o;}g`dwH(39`Cyw`Ejvx zU4)9z&Hb@+rHuM#)~Wg%&%ck7qnqKNc_!y>6Y75Ke*dbGNbLsY{ufi5!NJuJIp@E+ zUiS$M5Bv7+NJ{xJd|Hn0v@d#hIBJr6;skYKU;m))PJ|QBy)!FePd>ehHSOy!INq?9 zmbA!uI$}=l#&j*bY9N8anfDH-NS6tPl~p2jkT&lV*^GvAq*?3>u~NG-&jyZ*!EwU^n4BXtO= zri&S3NzN60vmGWr@uT3InOb@=5k46nE*CHN18(82#0QjCsUgO;X`q0t4Y^n%GN`1( z9Er_nt69j%=dkbaMA}#(ziwJ5bDy0Y4VUf&3FD9|O^%O*UJw;F)d*}=<*hi}svg%) z)Mutq*|)M!C;$0+O0s})&PyLTbxpA63a`e({`>UH5%Ti|x(3y+#S8;Abf?Xz?DkMr zo7Stt&bRYNx`?dT^52Gwqq|Sd{5ulrw<+#p$}C|T5~M0c#?oGiJ)Cv>+Zf>2XSB4? zFX;fmX(msL-?sYfTo3K@uU~+qwY1wS-R}%VLD{#BW{)D`K2k@+MMcAHgHTM8_jQ5h z2=Qr82sC~hPx2N}CFVqkw`SsW*t1>&CN`Y>fSllbfh-`PdDc)kp-*=$S3o!1{^KGP z(e%pB!{xQf{WXxcl*Q@?$9q3Z;EOtNkB0LgVaDFIf{febdh(*nn($pfl67vL^N}>m z!KX{xIAs`69)J-V3SgV!K=NBA*y!UF8J>@Z7J<_M7IbjrSxQ|jc(b!vB4+j(Daz9Z z2*aK~6 zr4Qr4SWT~j&UAE;l1S%#t;~A9V0S!0+|RqNbc1@o$bt-BAP)~VTws8KSK+{iu9^k* zV6wfpPABO0{cC$zKLj>sBQ_?WOU#sc2$7$*15uln+3hB|gcl)@R6|LOAZV3Y9y1<| z3C^B$n)%&tn*$c#V7b64u2To@T+mv=NQ#BqHw72m=R`jQ^J-=5AkgHH60x6M9jX@$@T9uAc88GGTrkvl0dUBGsN^gm zni8|g*@LkJJZYdf^_k0ffqd3Q(zD@Na0|2=V|~^O5dUIg0YXnrjz^TEzqo`aT@deC ztiSh(=OX-IpRDJ04ZT-3lW-W+(Es}%Fr;GIC%xUFLp3-0G;2ovf6KCpCmtRMxVdbM zaoHE5#@b}fY<}$kD%U=yGUHPXmY|@h?d*N$AVYQWyM~}bR5C`~Q030#PPl{2vvNIq zmt38VUN1wWTA#6I9!SaYFt5Yq=VkM(Q;jgv)reaBunY@ef@(5zQqMP&i9s&IeisAo zsxouL(cN$?+rqUib~TlNML10?b4z%e^o%Su1m<@^YHGXqrn!rj7_}O$=dns=s!Hsr zu;3f*2jc7DaTDsgSfUUDl`m)tot`(gj1U`&$HPFne2%|%-khz5=-2q%Cxf|YL*XY+ zF@Lr8#u@;`eldYpGcPlZH2ME7_>I>=dW)|Qf zt-V}-8WD;veVDO|D~vV-19~4nx1T($Ad20~TkhrIofIDjN7n(1Gv+fm4XB^t&Y0?j zGlg!eR$%9(Ul>TC9O%v4Fexc?v1g|XuPQCSYOoZrLP5ZlCS3tr zBYn^Wtq>M`hrpz)1zU;tVp9I0XFH(5;NXu8syx=M`P|NrLwFvI)XX-6yTV*C!!22S zS-~#x0tAK@l9`2W4e&O=xVbf8u6C|T?^AeM-prQWnU-kG8I=BDEd(uFjK(i;N@$yX z0>(}|9-xjf<#~6GWb^vYzI|c9<|=t9U@6zo$O?(tP86pYo+gu}TE7X7Xz)<)_nZaX z``lpD2Q}*PV4g9*@?kjtooxAr{V0|9(*B6Y2m*=*ij|B0VyMDo!#fw}FcQ4d6k-@7 zkU1z<)t}UyphL6R*cqH4T>Bty6^;HPY^FW!C$GW)X?!qN^dHioYWTsZ20{_!KqfMW zAJ&ONG^mjM#8&YOOZ@|SK5%#h%g^L~H$j$g{Z1-lIUs{Weh_F=Q!4i|n8{AEkPs%l zoS`pW_;ec9tPdH&FMyojO)Bg-s7{z*gW+tSNLn_)bGyz@YqIc$jlFs5eG{ zdyT~Zq0UZx>e@-x3xu{@!A|feH^)+t`JnhY&ED7MdpK*Hfb{V(T!6cVi`x3~H?sP~ z2CR_s-LGmwTx8L@LF}u41FBNS%s^@197d?MQx?@0&|$V1BbGV1O3GeTV-J?gaW-{s zy%aO$1E;PYD_ED#9Xu$v`GFBt&^8{2#a-Z_=H^wLP@{tS$qYsWm_)r6G&hsHtS6@% zlVcYOvwG&GFK@NNOOQPg+6;hDJm|J<&0h%EQQ@wb=O3DZ#OHMeOHBnYTFg6c+iQR$ zUQLSRpFpY=_|EJ3e?peqjRulUK8N|mS^?oW%{iOs+Ybaj)DO}y%?U| zcP(HDV0WE#+&eDt8N0D zGT+wl9m_lFlHpm%!h4klpWzpJyz9G(szmGO%)YoA)#_TgW%*0&o^n$^aM7gC28t;$}}T-MN!vS zRj>`!&#>+DQA2IvCBBtGLvr{NAU^K!2hAFA5{9Ba`&_#&b1aiNGu9m+*VMCG=(^jK z^)lx5-a z>*{t(4_1i))dzd~hLTMEX+%RrlnMcd-^l|ta>ylS^{7V?Qccbh175B_o9a<2P)MS( zj!GN`5~qey;Q5r}8XmZBA2n_~VJ&Wvls4qr^k9X!Rs8W)HsU-s*&1@#6M=zHT+KBK z6RE1ERR1UyOP~dUepvqVWh;m(`}ZjgDwjR4rokJ`gc9oEf$K#KtjEO;uk-#wFluzp zAZGWiE(J1D1vvEhGL!#b=PFImpF(150$JmvtdHU95#le26DcT(C><9u6Og)&S>1JU znM$k3si9hWF(JIpku4A9^7dR!>+F*e&61=!jA$plMq4U~X}JH^GSud~KmajspzwFP z6!*RC;2?S61w*ApHqFw^uYfKE9Gk5pmxMKhK;f#mvsgAcKE4Wm z-VPL60{G_J0L;*8c^}jXVqevlAojDAN|+#{b+B6Z$UP~Zy?#T%^au*YCKPP=@ zc0ARP#VKB)C=f=2V0(t0rPr@i?6Z)uoixt5Y*Bi}AFE7a6gWNb#<{~k2tbRW2DzEd z*YWAlT?G~p9al(S17IJShT7tT%VnZpFSI;zxhWrk#&b)bj9H5JcJ_(Sn4793&)6YQ zGW(60WAD;(4IlVz%!^9_u{An|5yNykJ;`EP^*Fwv98zh=}D1AzZ^4<24ofAFx&EUGZLAf(D8LOlz2IkQqnMhk%Y zDp+JaHa2g=(?NehL9!dWZJU<<5(UCkFMM#KqiY}tPoA1i9sp891;Ktc##2QEhp`Ew z=>q2VlOL5^yZ!kec>c;7g0;7>)IY+td>*5mLR$m7VXwJ;2&W(?(;v0i(9oD!_we}d zM^NbC>HOV?|=i}EYTV<4OG9(F}mp-1*QaJ4ihuSzUOb_^u%M9 z^Pz4&j%e{1{Q9Dbte}JGs0hzm#P`j|D7oxSZfP?GSwe4Fs@pjNXjggQov{#*BCl$s zpSXUu#t{Zqykv!4yJkMoX-N>$)=fCpf~|20Vqb};BGXa}%235xIR{N3rLax5`AZWO ziiix=@6`%Mf?`>FXL&B^{lL6$d}>=hI7`24@y|%x0a7Wo0?{jSu;PT#Jiz$B>Jf8L z+n@dgT$^X}PUuB|4Z3})Jt|+gXhe?q%z{la=l1hiD^PXD4}}6ay+EY=K&sDpObrS; zNIU>TY|D+|jhLQutBehHJ8<3up4K18gbc)IAy9@Sgfi0$jzu@9#QZ|ohs;7j-F5Ca z&@XmN#h77m8|uSh?$}3s+Qd*T!fhWS|1@)0tIQDsXj%i)7|a$rAt!Qi&-qyL*|g7R zSu+Np9^f-@0=7<%9e5V3i$zi8_Ehp&u)n(2=fm-XvB`G{@G}OE3i8oa@OTPYKIN#P zil|lxG}4vZ1PXQ!6iwq`UiB_|1lYFq@?gPOSHFLkpWfuTB zlAX=+|G!wM7)C(S8^kG6%+Huxzvm5wU5vvIkRkbqPkT$N%CI(%*lvagm{3ri9=@;> zq>nB4v3|YsNd~!XhcOLvRX{l91eX@biXE0eZ8Mtm;Q_%?lMVq#hoc?M8m%>*Eez%_ zyT@nFUNlY;);?Ua@itGDOGbf5S6-24$43o5!D$ShptJ9M_mjJP$TuI+T)mb32*+;; zm9MlURZz{H3mqy3HiIa`wqY{cs>Ya+(CNImUE8v!X)V@btScIx^nWC>FCD*WMJ^vm zU2aYn@r592$Z)ZO+@Wu-!6|Q{2vq>DYKc#V??h+a@e_j4oIycY!&?u-qxv~w?`%Z5 z1u~%iY_%5Yht|B>5w?G5g3QM7KZAkkncmjG?Zd^EQQ+r;saJTlnQ6&E`&BrA3G3v7 zji@X&f!)$h1(d-K5IC}*iJ!MLk!y?}c$sI^1-cg! zm3gMuI&_7l4s5Y!!vhN;s5#Okr0BGwi`+yOpyGbq(!hrZ1?$_ER>GB|V6ui*CKA=s zg6y|-H&a5LARHLG5Kl?o1qG;jhyeC5{BDM9MNC7xI?6e+5N9>~88{1<*ybQ9+fwzu z5ZP*$=PdLye51v6NPcn8vr|4M&l}KY9tXA4&nm%2nuV`T3q+r}Taa{H+l7}0rWYQw z&Ng%EK15L>Si!A%Up1XB)}%TMYjcj@l#OL?3tuQSp+Hn|R+xZ2O|t}SO52RS7{MBn z4VRcpWVmpOdHR)YaczcAwPs}f1*G~Rk`$f*E)q0ySmu{Im$2EtY^Ng&8S9;p z;_!j+wAI|4K-7*cFFg;u-B%kcp z5q=tu2T4PaFdB?z5nKd$LjV~)H(Y^InGw@Y1JDj^x7f%a>f&vAx#XDjF>xz_GzO%W1Kk{{X8Z;PkV)xCZnN*icTmSSP9-NWGEv zQ4ETc;-OZns#wYr1pwM0F_TC5;1;$SzB0&7N=5u;X!=i)0y9|{uzve{5w`Zi_Lri|`TNXGjvm6O;W(eR5*C zNJ+;JL!DMueXqSnv*Kf*xcD^%OGe-=XZ-QR2Rrhu*})n* zyKS-C{QykKnIXoRQDD+zWBY9*`-I{C_}Nf4?X%%~QchOuCKCnzO99C)xNFT0i0n7m zRa=cTy4B3 zXpNHF&pN@FSeEmuIoPd@vx>xnHX>G$N{=7a!X?=Qe9a6WN86E%I-*JeMITjO76egx zvlMn}6{pp_6Qxq9B!3!V&ME>4^f|sdaQPzh=K$!Jp?B^F3GmoVc=37EaJVYWnnm!J z`Z}%AB0{>~vkkJd+j7Ieg32;V&t-!-k_pGkhpdABhXJ~n>1Y|7YS?enxyf1TJ$s;_ z+6soa45M{X^|2M80SwZ@YJ}?VsTc$Lk@fH$>ob;vouc-jQ6BVdr5@%BXwK*BI%yBK zr{HVr#VC}>aIO?FZ!bI`CX$sg+%IN$!ypN2kdqvu171|D-%NwqUAsfx_Kn(pemq^& zv$%F5uBJl|4;mWRsQ^#H`mEm0T>?Ku2IZrDo(HraOG*27hj#M0tklW(Bw;WIa_ciV z@||{O_VU_zuE7N8i%YF^7bXK5I`A}N+em6!YR%u9D;sic0~wx^_9`}9WCpG2vwH8h zcd=EAEPY0VwWsYvE30N)f#^?gpPOc14#vE>Kq}BrDERV4T)z+{}qF6S! zR79nDf61aBz;ud&=itvAA=exNE?_CiLviL25)F#i+tJRv!YiK|0NI<1YaQdi!F^vf z?MFlK!X3ZN0l+9Z(QmA2XDB7*z0vkVOHZEW<%kR_T9cl{)8|z2H|BwDR~HhEJEI#R z?8TQjs?n7}^2-FuTUP~j7E#TdV&1>+r8eLp8@xp!9X~If%--$`2SXaA?RlPdEc`XK z$g3M6oFbicCm0(28c>I{JePs%kIv zO-0oSuQw&9`L0M8X8#8~ySEcmj=-L9cs8SqUj@q>r_t&EfJJtm8u+0^)uPsCq=lR& zB|t)#HU7qZd>pG{ivy_tZ_2rQy=*iFqflf`T=cM`{ctrQ#4hPpAyz(nssY>Q*LLlE zHtYUvZ6XFzyS^b+l(?$W8QzeEt#G8YJs8V{vLI(Q)l0@B;fvwjs4q?nLjd#YECin%{3 z*_ZBQEbNG>9<<55%vW!e?G_%?MMc!0W_7LkLol}rF8Ifq=*OIlmTvqgWWD_#5Viab z1({(I8}M5Zj%O0^r`p`~_)pO;prPbd>2lupX;C?Z@;Has-C76&y>%9VrojX|`T@IU znB3Uk?bC>N@GMVo z=!@%-zh4S>ml&fBpCFoq6Q?}&-?wcZev5@b$vqAyzN}flcPSmwU8_?nGPbX1(R=79 zY}m&Ss8;GpSEn|ew#XZ zixTJ0Oq0m3H_CvALJws4D~VczbNw-@m2kX%5n^N7rGz~%1Tw50U9XW2^6Jls40>7X z;^!;__cll8a#T176k_Fi?A@QES9dGkocQ~eEYmy;%t!0(p$Fp4n1o~VY(9O==q+0xBXk11n-7-pAM2A!rvx) z2uJK+n|g|7u;h=OFSgW7M^`2V^1Icnz1eZi#HWFT4PoHpyH=)QLiwFl*rk};=(leyp7e%236g|Riu>xr z?cO}S@>stFD-_%H7fM;@EiHTZ?e)+DM^`GoR(7>K!{mz_yh)q`7(rpEqrdw13+0a_o(Z|!xx8NuUT$E?AZ{{iyMDqI{ zXq;?TVg3#HS=oFtKDqc}=|au=jxa|#Qkhx0A{6BF;nCr|lfJ6dIKv~|4P(+@%AW?y z9lo!yht|BM-f}WbFLt4SRacVu&s!} z-LIs#%`yCl!|f||8)lzuHVcO&Vh0nxusG6FF~YFVbye90F3x*Uk-dLM4USjD{65or zEpqOt=YN1q2+!7w75N7W1}|o_PaYdF@+L{hZQ$nj964R}7H*|; zW=idG$Oqkx>APQ=;A{Up)g$~em~^c55U$h{o7=xEwIM}nGT?bMvvulT&Gs$zSh*%G z$eo0kD!;*%6F$i@hl9}tU_ih@wauH1v$vgEUV0whx;$0>L8MlmCcWjfYhKQEe*W9Y zMy3Nz|yLun!5xt|2)!{MBHt992=!J*{eyjfB zftXKK*>N88>V5xb&dd!v>TOx{K)IKqWLHd|ZrM#aC`NvX?AZn`heE%u{|6*HY(+aQ z7O#;oZUPN!Q*klv?^o3IyfQ${@NNDTmB)KoT%JXkd`m)D_ATb$5T`AxEb4?y_@a&s z_uaQ>t+mNOsM1L@nqL;XH%(hy)aq2Oq3YV{l7(4Eu zR>dn0XMjW(-K5c)lnsV}8WnMv2yJkt2n*3`N+H03f*}^$T5um%n(l8og+h0r-wixY z-N3!1T)3$-Vkr#Hg@}5N8?OQmXMN6`epOPU17

z2{E`kf$Du!dMhCqPFabbGkiC zr^gp$%>Vd)D3{V2{IeVcsMbc+3E0Oyj9nNhu5}GK*U*&dsNg@VTaD8TZg(0i%N*IR zC_N}zp^!nu6VR#>)8odbcg9^UCpI2}f9r=droG7r=SwaXr+!?D)S)Wo3axW?9E}cr zR0~i+U2>OiXLIDTYVrTd-Y}A`Jf$M+zTIdmh0VJVrFJZgZegX7&J1nE)gItp-zdNE zyw6~u{ZfV*E}QzT;5B_-55l%H=PRkh)%ZOe9E`nwa7>pf{<6ODyq3q3#F<)z@q~GU zd*CzCzt`r4O%;M~lUJm8ezD)5_d(Mj{o#RSofKpG!{y`!$cKqpwY2Xn^{vaY5Rc#p zEZO4c`b__|`Wh*>s3mKy!C?V{;+N3AKN$HCRS7H-)uluhsC}M$_JzqwvW^7@GB^W( zx9)W3t5Unt+=d!@^VGY8l@i(|j@u7W)@aQRL*W6z1Y~K&ub*?VHCVrS4zuLxxTzydP4= zc=2cE)SHpMrM1Xr@n_{QPU(H0pFbzRPapgT{wA3T#8?$+)1&Gu<}WZJ3z;xSrXhLe zXVsqvWjlwDK30WbmjD!dVL!qy>Co9g-y`<)v){9O^3%`hy9!ZR3$vl`UbGe!UZ5#x zM>eC7BDBAzRQW6~+B>5|c^c0E9wa0u5YC|*X5n8vEjqr?8EAN{!w!dVLhEqYOODt8 z^(mQX`ca$J?(VUV;?+XzTT%ht#5nOx-xg#IJm7lVS)nf%`y(43T3H*?j2!c-u(P-dpVtv%<~^WiXd6d z+z`p^t*OjC@X@(;ZjCA|Bk+%!INIfWjz*5 znp&tY1YIRsCA*Dd=n}=?TK$9G0KFqkRbg)`mWEI*`uw%>wFB;(36dwmaWoibDeSC0 z;C~p@3psyFjUux1aqwi1WO#Vew*$YI%1=DF>)(RW-$cHCKc}Y^Q0pXLw_VFl+Yfi} z?WH`^3+;=shya!O6Yi;3h5`AzP}eQT;8Ta*cCKkC_>GM65Wb2T#N~gk&fRyjeO;ZF zZYh8tc%^l&{Z|?_GeeY1USxz1U!9zDOrLRRoe#+Jqe2G9UtD-fy|IHRd~*MgN_W0P zpI%@G3bx?vl%$lX@^b{#_D4+#n6i_@k1XD6eDQPj)c1wQMi~Y@ZBZ!pZ5!2wnXw;i z9P-rap?=nOaM{9Z+CRU|PZ|XrDLv}8EfP2)yE8=D$f(t`FG*g;{|fo@X00HJiPIsf z3qkb5sgri92~%*4Gv@_p&nd6HM2U?c~a01#UJkC*q0S{-~FgoOpkLs zm25=1W8OF9zNY>azm5So@_Ug(Zb0X+?&L#Tl2poP4PDCj_wG;nDEDNgOf@@IwqjJ7 zFW~wl?^@yOoeChj#*gR2ldD6)&ZcP@Gr+9^S1@LRX2dDGQaTxhPNy9df*kr3pUb0w zkEI$>i+umNh*EPC7wRzZNyS&ChwbbgxO0C(D#O5;aO|Mf0SeK?d3VRr_si9T+mZ)f zJLNfx?N2=Po_KIwm3oY{j)4#bsg(7%C;#-EOG~R!ivGUnkEa?XPvf^7tBa;!=Z@de zo^VU6=+pcWsulH{?jdqrW>^bgClv`+**Q7|cPD=B12W5N`F| zEBCa6ecYzOZJ7G_yI6KRZY2J94^I79>I%{jl8>$nDwE;Fe9X|wmpm$xZm=>pQ2X4i zI^A>1mkl=Y5a&tsO`~BZGsebSX$W3BShq))T4(H@Y8F(0XB5K zjOhX$h#oHsnXBdKs-W$zmf1JCDFonj9q$!}XcSfa#((wBuM;y~d=8I>b*Pq=7#WOp zYp1rMiMsOMKY#wAG*DtsHJ@DBPSQ-53S=c~8|wyw*&-5AIgbl1G_4I>n?Xll`Hr;! z?Kd*DBS*R`c;`^w%q_9H0O|HG^h-wkA-;VA2JuNPPkef%9)%vi7CQ#@5iW&$s>_|b zyEq^gb(kZc0O$)C#pVz($W+5GXq9D!Yt-&``)OwE|EJDnsFRzYWa#||>s=f(44(T! zZjMl^B#dJYE8Z5 zKd({K%q(C1Ky9-g>yXY-zC}1dRvJ{QId`dn_Fw<*q1K}b1(0McGVca!vARvaRg=O8 zri^xo&)kA0UTApoCFE|+Zjt#0hgc^J+aT}%sB%8n%< zu4N?4#YVtGIOIc>o2-*!JPP4>Fzl^JF(Og1I;CJ6CsG|i!!(pmpEkBTvcL%P8_n3q z-{84}=ZjkJ!$m}ie-8Mv3u7LS#U9*X{wvnJr}ldF$CrP)Y;|T0;y4P_{z~`NxCFE5 zKm?S{`Ovs+ekpltJ3@IB3<0_^eG+Tp`>SPEb3dx)+>Zc7Z|PmpO1Z{8P3p1A+?lpX z{lB}se{HH#1q1td+FZnEMyl`b(ew4+D)5zCLc_ZoZPfGa7HhWg1Ut_@13xw6gEj@k z%Odse*ZrMx#}d5y#mX-qmo9LPC#-x=$xo@YE(U%P~>dq-SO9zQ49UL|!XG7?Aug$Sk zGb`s#RAeO?${fl>Ma~+{a%Rql`}gj5{jT4?uCA+WpWdI>`}ul4A5ZpR%kaqU4?7N% zgazmJ3C5&ib)&D%pa)^Kmy|#04xmLvqt|i?S(7`uTjwR=_ftvWA zX)K(T%RPrtz*mtA!j!CbIKn_}r4{B<2_10UZmwKrhh%nQF58D)h@qrjNyxtk1y$;? z^i5ouPPE^*{>$)AhS1&=eNAM)g}&L%P6wVBd4Q@9B-9B~uh#AO6k3!M69OK(!v;6h9`u7%Ch1TnRvdxH z{^~7`yyUsEt~GJ}@!A8$cC6Lq#OujkOI0BJe$z~&FT>6}>T40~RESFpQw-@?xG7&jg6HkjZ zt7zzi{Cl>n%8UQHmDV^L5e~nEWY6ZEt1r1>_2|K!;~cli?OQ~wuPc?0pw%o!|KRnt z0<^n``L9qk|Hpq2U%JgWu}x?GnEScqdwo)krb`<@PqUq@&-pqQYUu4+>ioG(X}WpD zr)s#P`mEBf-mA1gL6B!nOf53|eGeA*O)o-?(9|Qb2BxfU&jyd}ONOoZnh?emXVcwW zLthc)+TRTtkXKSZqI`F06kl1}G8~4b(eCKM)k3Rdw!uUQYE(pH8&<356eo*)9DFH(EM!uWVcwc6JcMSIQtW#XnZ7)6c!++*j0pRMxaT=^nU9-gDnkX^e zx#cTNO>%+vOB41sfQ#t37kgg8E&zMyiidD&#LLA{?9`|U0mbgH2?v<5YzXGn0n zHl#_rBy}}5SBw5c8eiBvW*l3=S>Fn2Qvv7EbI+)TV)wGTyb8{FZch+u;`k-0SR{pC zRjHvq4>-y0ZIOO(NZ~X!4VB&rPld9{m#rtHr@nlVlwZJh6a;y)fkEpA6M{rM+ftVG zgmL6o9$?*$yUrN-n4YJiKCzV90!Bx^sV}H*;r#EQ-74Mq{5>ml82e*NiCHeu*eR_a zF>X`Ecta2tA8P0f!gl7(u;CAdG-TdzsyRe_+0{$3CC*mENp}hfoH0v%O^N@lRL_gY z?fJ?tX$q~1R6iye6e^|^8H`z{b-Kd9Q-6AD20%IPMWd5D)j*h?_pSnb*l z%?uv6DDloPTZl0biH?82Ekz$JW*6m0^Pu(Cc7}Zx=g*U&L%)O267lhKWn1Y6d`zkI zD9UXtcIg+XKJ8$WB669x>|DC?E|!!M-$6wi1wWGQBanpblDm1@md1YLJq5iipk!&-n6&dB~ z+4*3I7MqmQd^a1Q?5L zyY6OPutxFY8Y)c!kuW}By5`v)Pf4fa&pT+)zd*Hfo#Ao~D3uj9BlmDHLTwO31q;D2 zIs!^(2}R?!ws*d7YmmZkZN!;xqfp(a7EzO%NAbqlD(8o-U@4AKa6k@+#lJoi%-k_} zEv^Z0It|RsQJB~qu&c)A6e%SPU2jA@V3#+kBXhR&f-%;iPL{i3iLeX&giDO+=Cvly zqeB?r5AQf-6dd+U4==I~Bgpg_ky469)?=|gTyMb6L;Gy}3i>pv)m%>_8#_u+p?af_ zk$Kagve-D09#Y4vQ7(X{@C2@i2~MK@-(wM~A?=|UO<0{dTAspHs|94L!6{)Z&-*sk zK8ycWpTSuWzFt)Mk}BQ)s2lPd2L?&*1vQ=I*70Glvwe`OE^_=i8rU1_rA_t07vnMffs9uO5_j4$z58B zJ%vjepVAt^H7bgS@6Zu*1x;~p4zKC`peixbbL!Npiibt^E{Uz7Vo}}|W5K>;pO|werIOipqw8-DToQHKoD?^EB6p5W5 zNbfq()YRPQ@QRczFDqp&;(3HvEA$hD>H#XOfeHw%d$wE;_$Kq}?+MPA`+F^l#2<7g zXeE4g9}##l7a4t2F6B;gT{>qKp^nky4s!8xVZ6OxUv;nQUwFWcTlnI0$s>`wVuk8w zjA`{n7t(D;X6Yu561P{V^Sez)q{N8lMbGqJKngRHlfM^@&^k917(V1cJ3TYczMi^w z_r7(FXJAeCtyo_;sumcINp^5(NlbrRb=Z(GFD@qU(P?TNv~z^yX56H0C!qyYfk!;u z9ji;ctZ)=#uuM6QmxrN)BPk1qph*sdRybFmqkwpkmq~nXQ<3B$fRk<+>~~iyRU^&- z+rWQNnzn%C@?|drbk5}d2Mwt`P!!~4Es1DhW);|MJ{yu>z>A-7P3Y3N?8T)IdZm=C zm0kj`1Srogvs74pd>{CP7fQ`e)QyX(7^A15)bp?emU*+_d6BM>e${^K9^!MpV*V7B zt;!GK7u#3#7sg&tQbqfuev}%eE4Xptrsx^XzLb%zeC_;YGO>ojEu#KAFF`go#IZ~m z#db~=8H%j#M&qa`M@gN%eu=F}8!@R}E}{Xu6q4SFd32UK1iLi?b|k6hPx%)&_pQWw zI6{41xW1UkU4mEmAGg)*)`!RlH9B$Y|7^IXKE$~1z(1#Vpz@8M%AimY`evcTRj#_W z0HP3X*1UfB)DU=L46=F$ANzb+#5&j>c9l=h(6b?q!8oc+vNZ7x&`&=qhVr@wSDmQm zbc4;9g33dFm+ittv^bU~>JS{7-EucP197;kJn z!ok7AjDp|#u!cI95hG2#JkPkj?NETcE0Uu$ow+HI!`9E=VXnbw=*WJ3ym(Znxly*D zso7%==?*U*1%GYyu(Im55SpJ@od2`$RDDw0kD5(Sgvj=Tk?$)rPgaddyVbt0#~>sT zvGU=fLuj^I=~mjNRVsvpb)#np ziyttqljCiQVnN~2Y&k=D`Rw(L%Y82rA``62|EPeJymqPxRBCGFE-UM!1J1q;=}d*4 z&5?wjoWYpo6toRziuyu6K&WQI3HA9d_L$atrj%(s9oHS@5?;qALn?_g`9I|h{qO{S zA!N%@d(abC(`J@%H^I^!Bg3p+skDOps7ZLP#7L-CCyWZpBa zE#zW2KqQ-=z>Fjl9B`Y4F^UT+4h$XsBfqe-f)#<%~ar_#i zjQe>%;V8@;zQDU3Eny<;?1`^iQP2*@yz!a&L4C0&u-T9%y@<|hty*?IXc{w2i!MOA zkM|_VsyJcQ$laSh;A!UlB=xt2aGT(0g_2FzEm@bjs;t)|!ZLpai&P0e=yAv(_;8L( z9ovyO8kkrm5b+CjrHMp_*CnLW_x?O~&@*D`jl{K&$XFNAv89M1UnwQ_(2mD+J^bW7 zS;aUcKnO#VwxHy@4F2tYeCL%U@dDf1e)0*T3tav1a=lTo6~FSLnWK{NN#Zsu@8eA- zvI6q>pad0LOkvajE)@h|DZ*V1a%KBKysEjq5@$5a@I=N@Oi$yN#3Z1 z+CI7sG356lU7!}|woKg6dLOJ{j_;qGwqU31&jHryO~t~jp^_~$&4u4k$S?g*8tBTj zxI9}tAq?diH!$RQ(IgE{quPuihBp=OzX>pnV$2Vw+TH5S9}7$JWd2BePSw%B@g7@zluB@t*rFLS=yu5T)~6Y7 zU;jIlji9n2{aBCn{Mx5*GT9u1;}+sgeV*#g#qphbsOW;pUk;|AS0Sn+A=0O8_=AB) zHRbnXpId`3miB-*@rWb`e@6*JWAK7Qpm+<1xQVxiG=cNHvqp1>3ETI>P4SZ&LZMNar@IY~58i+TYXsOwn?7BdEdgEFS6Goy}7tYf^}3IFPN@ct@DF zl}PNYvN(RA9pr(rwlI_UAtYD97CQU==rTk71MEi}e3dq^N=#|+h8$J|nFI@*i?4#w%6A$b73E1Dl4d}=g`QWdOp zCJ&^-LX5wOxcoq30vuFuC0(G9hy9dZA!;;bWA6%*@1>rfXpfMbtd}ih|Q-MDdxt0j4~)nkp#SWPLq1m0&oZIVawA z<-mvF!@_scq*d_`yIUm%jbFL-BVyC-V)Tia@5=9l2&RCRCvyIq7bF)!jPesrx(WYW z!mRZt_eCn$|3)M~HR>D53yLg>ln!L&JeDu&JB#N6SI9V2}d?XjJCw^MEOLy8qr^^z70}Kb;&R+;WkFj z#b&klu8?$rx--5P^1Q_nZ0Rju{Bh4{w+tnNl7!w4Hmwg*Ai=0Zbc}IFfJJYhdDArb zFT|EQ;Th&N3HJZQ((gTTH17!Rr1+EGHrb$Bo)4p~VDL-n(6y~g5u4#`Ny)NSI(2&w z^T;mkU_597TvM>Ms9t8KSwToW;MvF6Tw80Ab!qouv*GNsxrlv~M6Ph~>A@vM6%HQ# z^B#w*8Z$x7fBIK2h;5)1imyN($!o8tnG1!z94}xhkuvv3xNa8VP!)mU`Byec^oKR9FrE1sSq0p6b<1#p7yfYQb3h)6rD_FX{T=kp0 zWreD_l5(;QsPOJ!#c>dx0QcqUfk+zB;)5@(-7q~pgQR`YohfbV#kg|)qdlU(8x?u} z-*}~wQ5)2+sJ)r2!D5QJhmR_ZHQ14*ZR=fqXXi19(He$zEh5w$?UuvU00klG_U%6Eh6PKj^(eekHV#Jhhx!528>A z0&sHw`AhF{C%Bjfa)rM@{rWw-FrMXx2@o#abo(;rGCRx4RurMauZ}$0i^(Qap!r|X zCtLH?N=j)L5)rU?RVJm~Ywt7UnLy)N+8jvlKp*Lmq3UZs^gicgmuzQ)Dm+Hd#3d&= z<|z$M&rQ+`ys+>20$|80P6RxN=#8)A=BsA%J$&ewB$>}0EhAy=a(kHm9(jwAaR4Jj z4@u+-FrqWOt(#fu=U&r2@2;TG;?_A2YWn2|Ig5&O&M;I+7XU1mU+d2~{d4SOP@x z=m2%6y5M@*PsEj5sd;wveuZIY9eDwK+UK5Kxkss>XiA`x1r6TKihaAtt~y*}keJ?+ zm83T6i72kof=F%nE%e+HSom=&xx@mjN5hKfi5m3Ub6%Pa0UkptCctn#+^}_>UhylHi>aP+xS zYNfo89@$xij${cUkSYF1hMh|4=CIma12*3zr{f>%qt*Dmcc}7D9i=dM7vT$+Y)h=U}fd zrvx=rno77UwJE4|vdk(~ycQydcur)oMiDmJ?_JpP+Qg4rKcNAd<6Z5dOuiHxVg#+UmKwbVGw&~4y}r}sQ_ z8SYAb*l1Lj4$9ZorOq08U0VNlxg~FwPzBNUD_fBM+06c-T@dkfqdz|{a>;=R< zV1xE-2~ZVYG8rvzul2uQ6DY5L+{uH*fL%>hGf0Z2&%I{M${kSr2Yy>EODZPV0RXS| z^x23K6TqPG@QseC8nsZZTfy;ZXYW1UnpQ%8PRp^E(ihdH;<>!q+QP`UJmzQle=@ci zN*i#YIMz?Ljv6f)^JRAZESGmBOXk#lp9}XnXuo$>URN%u*=Y2f{NqE#5c+Y9_RZ&i zb7x;QV$J%tLG^3Sb^C6`UsH#*3jp;h$}jcvyOppvD*A}lIyJN(O7eu?^j_RweIpw~ zdNq;Qz-$}(hg-&%esKQQnG5WWVt7QJSS;J|-md*l^V!cOYVd9(M^F=zr?%pabUU-< zmmVbnQ5KjTG40Da7Ek^aAzP*F+oMqB%`*Nf^FZ=n9qaIw!vdNvB06;4*!4+^E1k?8 zeiI1dI^Nx(k0A6gxh434l_SZa@yRRS+nU2CyrkQs@|?OA?0-ET#-f@CxzhfCrU_)2&X zP6WPY^<=L#h7;E*i8uV=%&WvUXLcg}B=)V$0%(4GR30OoRz#gZAc9Iug5Aj99kQf( zN@DCmTj<^o)RFj|nX05vF=`{``3YG@Ymd3kAVr{($a&PV>kj!q7kqX7D@C#8{vY*O z0&nayW5!d+Ty$GXPi_s^H%j+y*{6l?t2X!KDE*Sw-uYA0?LX*tYFIq|s3EHRjh2+G zk|z(*ORs?WH;))R(uKGnPKs^4_ZX*gu~P{~?XQ3komF#>pUTh;_TMTWwj%P6=da%@ z9eufb?u#EI3n?hWaM;q%nsVKz0twpo6Xy%Jybe27q5nV**R-@Qb+~o3bk3YOPs37D zv#HJ<=9boVJmMwT4XN`AUJ{Fwy|V?kdAw)=fTJGt#immbDAFDURbL;2;3W2sbk%s_0O zebyM}m5yYaUNJg!lKxelp}O|)sFJchY&~Vy-`PIrj}Z3d-oNBTmji2@irC8#J%<1V z^maVy%k8)=2gy62gg~o4wpUC30o>36L%^gAn{T%YZl$2xx5@j4qKzyPySw~~S{za< zTJI>w2E5hPS11l7KEC~`A|mk59B7-S_G?Hi1{x^I{?)hL$7*zim(OWCG$`>z_vWAL ze!^7vgvRXr5%vD=kPi>lBx=9*>}rH%3#$*tC1nSOr^%@FkwSl&j3B?#Y_}P0Z&J2E z)Y@nF9vQYe5OnkNeBK1dVx8dKF25+OG?ZTJ0JRHBHQ*ZmRbLi87kieYOsNRl(7`vg z(DZ5#Uc+4d+d_P2A`uxK@#x69C4STyx3TC!S#}@1_auMfZ^55+GO{R7Dz>GT6z8iI zwmk1dX>z>bgVxko{ZVUPX}bTY`3hh{&{OrU{+M?F2xN!f2;|y-NOM>AQg~Xy9A3bS zIBJ>f@}YuLb_jok293N9;I6giPdu!79_AVaHyhlL?7Fe80-uOpXwX`f#&75V%lRF@ z2Ro~0A8t%9OxDd0$id?fPoP+Ob#@^Pt z`$h(I2|ZO@{L5-gfvce~liX(i=y=y?&GU0fc@nua`pVZy8*ai)^DFrYE~&+5p~vONzG;-y-a+A1O)&2i_jWM%E8pD1!J70=kY6u#2 zz>{;+bhE`%4y^QA|GL0?psO>c@Q-%GaNrxu;QgcE_7YAxM~b$<&feTaIL2PqRpLzZ zCEkA2on0__yspuz*PN`hg)>hz7GaA}KllDh5 zT#@M?BQt;8HWaUQ|3BmLiFrH!9coLK-}nm!E1xX}%$0N)cNkZ!zmu(Q^E65^L>$jH z+xiYkYlZ4n{Ek%ZnPvCyiH-=rQTWdhzw~=!;DPl8YH zsCR``M!rM12>F|x_A4=am-8sh-m7Y3u<6V}7A_04(~WFqm&!YSlKdREO;t7ULr8nq z1Di`Bs2yrJ$B}KXgEE;r+ktnl=%ZQqO;wvDE@~v|+q>dGwaQdq*!?7UQ8>@y)V6&U zp_dVXgZ2XprRiOw32&$GA!0St6Ro-n4cn|&A~t~__IU2eapK$MB(7?f7`!WqjlB1Ys^dD)Lw+HO_eTpK($-?_{FaNu^mTFpk+YjDx}WBaSPpZinszZ4v* z2gkJcSY>zU%Q55A3|2tN56dx;|4I(MIpV9;Xy&v2_(A9BnSyf$Q>E(i3%t%ho~s&o zVE^Rq(E85V_y%2H`rz@;-)Cfo@I7oVXwRJJRQW%VE)|@S-OUYQ_6;-&Yqz%Wjq#Xa9rr zVc32p{J6WM7tm!XATRO9jZdMj*xQGCnK3^iz5avJ&36(X)er5bzT1@`?o)U^79m)1 z(Y;1cPxlQ}NAW>P9HyGi^buLmEi~!=`elyxWE`Iu&bv}tYVq&Q^|Z5;OrWC1XGDN* zI`>`YmA;nd&Ep0#Tr zjO74{C*4yk^!+o_%+)S8$wm3WJLf)})B8t#;x6BUH_v_4`TgfLA1+^~t7>K1`Gve@ zqm^V@)T&=^YJc*8R={a1@9I%iA?6K;qNZt{7HuQm<>#){7CbDV_Zp@> zaK{da;k6xi11Qz1zVgxCLej0XK?jT?{7=cWQnC?XkmXZkP#4i;T$d8OxT@pnF(o}E zi44y87qq)liQU-L`)f|j`1DOuZs6GHl+RV3hfJ2FbGYQ}^2JgE{g!6*=O*UU5AIu}_EycpYdl9#o z4}t$?7xCM@x>(yU@CkGl(nqb|=cKQR>hv=Bm5cJ7`;HN75RwLlK+|UKmMG%_>Zrq*-Ybr zNt~^)^4Qq3viD82lDhzCI)_A)GJ*SSHfk^XuKgXrFqiK4nke7Vz_uaqw++a}no z&ab-TpU^&6c)XaWtrxG)pZUWHP57QzzKs~ms$|Qje*gPdK9&F)SxpleWi?@$zw{sN z_umuZN5+JSdEiFP*;BjSL;6IWiLxr$7@1uq_3F<(JFQ#pGoGuJjauA&wdiP5nFq_e zj>m>FJR2WZr98;Kap|X2-I%^LBC#!k7kR^TPrBn!-55gj=8a$OQ>U{oOBXDazs6Ow z`c5SKu}<4a8mE@6HeHYKKe@R}wEIm=?RT@2xAo6biPng!cDcE=&zrdhXXG14c8U8} zRI+=^~#_>bMN5> z(LtL}CQ-b{fPMUO@#foy-V{R^-hSY2lR)J0>$rC;KOjhBwGb)9>V`~q%{-M2y=7(3 zN!1@zd-41dU)hoZrW={cn8RmsabM^5sx2YZ;U2r279~=otkqcx7^2y^!bro%SFc9N z9rC%_*y{_rD;(@|M5ng*UVf}dsqj8E(g+i>Oh8lWBD;O$JZrJPjN*EJY(M+gyo@%@vJW>&jk?B8 zQu}wFT`5=6=xKHW|JzzEI{2Y3_0N@FRkML`lEAg>Ne6OQaDKV4s!Ft>b$hm1G2y6v zD-9jmNLXBTJoUAquyt?CzKxZDLTi{c25BPq{@SIx8U9v{U24jAR8ndSZ7x$vj_(hf zX%Uc{8toAmmY$+2Ox8-HGe+q!FSEtY-gYF;BB$1$_QV!KnHv`Ox6I)Bz8LJkznHD_ z+z7}|Xa9FQWh*D(v!5gquNgVtJvDjepNDP#K^nK!&Q(`k8ZoM^!Qah^w9J-2Rek#p zBQHAM2^7`!iq6vS9x~eUv#5JX?`#3A3iB@aQSL%_WrohlBY`L2+46dbC9A-%DgP^c zpKf4Xe+Z$?4rrUUedsCt?=wIj;~BQs9NxarPwdtk3t3KWtkJEyuJ0?=_vCe;Yk&y6 z?btJ8{XW{**Zc41_`vb#4J2u=Ft8!!!N;c~)n1S2%0c~DBYP8{ryzs{n zMaBIAIwb**+Z+(EC^2uYD9Hn^GM{;;KfZe7^U4>V#PJqbK*`~lAF^m&D@SQ==E3qRs^ueeVMMgpS}+uTjBquuXb;a0Y7aA0rQ z;ey(r(+j!25AXPV#s%> zf<(tEB;7ojn@q=kYGagp_LuHu-lBN<#HQZzsmrqpcC^-#@B^(L0ZP|9gOKOaY5R|7 z<}E(=h?_tNPF;)H@}4F6HdFud;_W+z>E-)wy{Y)Omep$uycHK*cCG%e=yFfcKL^U* z;-3CpwR>-6)~o9{L2~L*ZL87Fj@n)Cwj7UG(~14IGhFS1yifU=*Xt(NO;gRIwiM0p z4>af2@2q5?bshZOA6o{7Vl>)6JvPZJ-(QXFi%&I=P)m?D6j0;jY9IIBkH}SWXyw}{ zyvT6Vz+PwAUu{05j!<+tEC_I#b7rC`d zFDw>%=^1ul+dI&KD^Z=lBm%jLDH3_}*E9J$4 zw0^1Yb<3>HgycWX0@3k{-Oq51%Jc>8Y!rr+{deoUca8GgLld@H(oFuHnK#$pUx@p& z?AGRf%YT0O1)to3=tob1titoM^0&&jXP%t;<%7L@^iwormKqWHZGDo27d+F$ZCs6e zrJIsDvAIX5xz9qNfk_6JCwX739uDFvgw&7C-aGX-3YI$aApRG~lb!OZ*?GCGJwjD$ zok(1Hdh_quJy&%Sl(YVMJthm+sPcR*tg>D2pWPe(WKeN3c${H>JT|LW_rSom*Yj@q zDs_zmSLd&P(0Td(Ue>w#mzf&|XYm2wZ(VqhU+m{+N1Gg{VatLFubFh3bDa)K-y zcB39u_;r^~@;Zt=9wFT&T+*I)nz1RpHE_!;U0K2CL>#|JXBebWOZL34qNH;#w2^u| z;x}|AZ!)HL@jO#ha?0qNMt|@5(5WrhD&dglk;rIyRS(L5Q9ojLvX+nBtUP`c_Tw1B zq7f+L>yL{zSlH%S+kK`*#d}n8fKTTw+u7RO}g^B z!W_UHSXQwiuPG)uR|W?5vEX?kplM&w-hIB9=95MkiPP@*()K$c-|9mI`{IQYvFI`|N4A7{0yu6lsd-{a$NVaxV8vX)f>ocD6r>!fsX?!8;#JpQ4WC>>LFP zv6v(R2ffWQGTt6*ByTlr(FQ}HKx?|p1@Bw=;ztEpYP31LXT!|n;|U)are4BAcXB@Q zg{Fkr^^r({2rya;qPHb>WoVm!2T}mZHfb~HJ{qZW1ot-PD<)h(gE>8~pTZ!DD@|t( z&*8Bnay}*az?^jj!2cDJ>jgztK64!z9Kp{C{N}li1RF0a&qT(2Z=uR39o(MaQtZK)1+BLS=D?_^SObcNwb3-(X67_Wx4a}FNV)yI8MS+m!Y5M<^x zR6_FMZ6vvDWr$(n6o&1%lbGJMk_tV~AS28np1HO+4gMF7)i>*Qv$v9=8upmbu+baq=+($dCUQQ!THvd;}h5!_hr*^)lq(3JznjEFCO7rY!@;*gcy-s&RwsI+n z?Q-`{x*fy$hr-c9#ZUR9gXW~XO33+OQmfw};IqR02~A2|jbht!SB3jstFGqzRO2(u zL`zS&H@89N3K$Z<&>FXtVjJ7Hy^}EAt0>Q0VoO&`DL13cYHG9(JW74qH=ACkRBAhA zmcOo50Az)su%A?=xeYx33#@nSO7{CJ&)f)-t4nHSE8?Xe<3r_J!4>$oU6Il9$hP{X z_OV?q>2yJ7Z_iUbgH&0EoO6MDF#Oi>4XxyZd6Hg?AmE`*cPZz8V$x;3$RXm*Y*|N2 z+k`+3EiBaAr(O8ENi-o1gqB@Ui#{~%V@ zzO#?85BMsaO;;*?NI#QagA-3W3<%oSIn8L;au{3Y-QomQ-;hR6EEgB3?t$iC?Q1jv z@JCxp8p`iMkFgK90$uDl7Z%AHVEqSKm~Ts7u|ePZuCaPC{T~FuG`d%I{W)XQ_HS>c z2sr~_g9$A*X06|L>cYgtX2G^&Iip`^wFrr zq;hK6!zCOuC&Y5RnsA*+ErvB3!FckQ?^^@D zCR{XWuk4XM1R12&7FR<5dtPxD!H@s4nJqnfg78a*i-|jU#AP!5WqK0PG9*6r=zC=_ zxgCxI+h*hntQ%-y z>PR!x8G_(rR*jY>KwGAQ=DMhrc zpvEc<`KWxMPMz4=pinbDX}&F!v%@|(cG^p`Z8~eCJvQgB0=#-q6FOFrX2iL;62e{A zl-Qxh6{-#ARo6rP? zdfTf3hvRP0?IU=V+U59@y;#PPUa%@2m90D}@eeaY!SnkETeGvzhF*0<`Q#V+w{G~m3rq=A?W&psx6-(D=dD65EqvzQ<|EGLX|Muo)VZ^A;~`XkwNpm z6vC!%F7ZvfUts4`5w9qG9Kgrwp0i^7zoSCz+kGwHu?w-pWo$BSKK(RIN4sXJ?VnK2C zce~8*&$%P1fnDRYXL$UELr2z}J3?JdN-~1S5(MQUG3hiEOQ<70uYM(UXsUVP7p@PP z*KwcOxZMgCj^UKr*@er$-Ar8nK~+O<&)YA*G1?5sxs0i6XygjdQy`+b%zT#!w`WR7L ztz|t0H4?d@HL?r)#<_dCTd+`)^R*x@dL zOe!1`6*75@@x}&$CId;+slqqd#w=(3c~8<&4;s;(Ze;hZJMxsh)*WLfAHj(>+i#c9HnEgF@oUWmG+L}?6q=< zcimYJNRO7j7yF(rs1X+Nyy4W3?cQ^9AJ)7=n^BV=EP2{W*A0zFymU!z+UM?*u30<9 z|FRmkJAWoLsY*KuY#ZXc9WUz2cr(27=6mivu)*qmkI!>x?O;-B1RC<;&BMV~^W(=< zDJ+FgbHb{>DkT2b2-}=p=Q*u9Ypt=9bnmA8RR%CMp-FwYB zcADHV1-m?3g_eRC5F%29XnP2J#On=BEY3qf88c(mb}$c53#a1a^PH^YVO;*&*_0KL zxy(nH>S}D3mV9e9dhrjYnWJJrTe#Ck&lcPeOTi)T%10UQij8-Cr(&_{NJ0o>PKz8n zg<}mQ+>;Iy5~7D99WQC25X&`;E5;#9q+CtOt!q{Cu@&tO8i5p0pK2m(nS%cuLs(3* z#5YAuVQv3(-i)}|E4rA#8(o%jvzN%OXWeZyFqanw+Q*)#6BkXQpA+#)>o3honx6m8 zmBM>F3Pv*a6j2gExA>W#_=%XPup%0Bo3gf|-*XUKU=BrYxAW#p4#lUD6o5~erXE22 z;ssfijXQ7jNm$?;Cql&~yw)zp;Ygoxhb>JWzJhR36RHho@c<>Mib=r=SDn42k(7}js8NpEj0Ths83F>|5EILE;kO0XkoNz$OC`E){4i07JPNP+#5X5v z!d#~a>n|s5s0bw`(Iz$to~=f&)r8NZL>Bx0y|z+L>|K?E$omav6n#u7$A1}sc_2+2 z*BT8fY2@%(?mj}l>0a|@Y1G`x~lbYj2Zb8S%6Q1QX>(cw_Oobf^-p|_K2STf1;=t$axHTaNuB8%PIt?fYCej&=K zg1pCcHgo+Je(2z*E)H1wSSpS41?`Tz5oBhtbg<0yv~AdV=amt5i%V!6SV19D-kqu*z_*X*@MT z)TNluGL|2rh&u9pUb0q{9qe(dZ+8Y^A$A+SLth@Zt z4+dMgs>oXHc4)FY6g2Coad`7=#5L0mnGG$oKwQFy>P2|`afreU_<%AoUz+?P2jSA3 ztQXA|_L*2t1e0a>g_ihnkkZrM7X zGDl6Q1y&JV9Tm0e)_U2L(;G%mj#C-Tc69~=ZIoKEedQl2hGp3Pr3FzJ$i8)^==;uc z>qs4s9V)D=2lpc=3i$I^*s2V1x&-=aTt4P24(6BgvLVi=T&e6&{p|dut4M z6N?4#Hn(F~PlIpw><6d`(uk0IM}Bb?<_Bl;)#d%@4dC#%guLg5y!<+{bNmpXu)){` zkehEeMus@>Kg|t6#y%_U5<8RIkcw2RXU4IL)I*n9dmgR{tA=gA<3+5I>x=6pBPwUu z0@L4tB3uQeUu^}f3sIdm@-TSS44~OwiNoVpLV7FZ<7!2~K)P*b{fu64Tp?;C7}lnz z$?KQbvr_3U;9{1+z(#N|o#(XxPqy7k0{qLAPI`O%kqefDHsdIlI|nip?4?a&0E$_l zB)mSuuvjlOb9^E@6q`jI3ay)ni76qTF^$egfn1?4|F+>!CiRAM28cI%45eP#VZpbf zo8`68W}3R|R_F<8NJ_gOJ?jbTHfaEbQcMJXl3$mtYKK#y^wj5Si1^i5^!c>8 zY8>c}a#onC8h}Doat)5%c6z&=^;#{Dy~vhk!dbayIT(^Q+`q2Leua-c=UPi}6L;jJk472ggUr7XuP4n@ibsG--Q zzIh$=0x^N!)IbB~&g!mWMX6t0A!1IkfL>gS(bt49ih&@jypO=Q=!UgBkK_*O9$r+b z?a19cd~B^7ES^_UG=413FC@x z)!>WhfOkt_*lR^4CJ-8lrIxa|4CLpoLg=smpd9*JWD54QX@RQ_xM7$s71lG}{Pvx9 z+SF&}RRgfDwR+4zq}TcTw;QA;YO_rwu{@&YWPF?n!}8gQ!-~AB$`svY{+3wLsZh{ zSShD+7?ndgr$S;5Wipi<$H;Mxa~_}H{eArYfn;;v*LA(G*X#KlTQG>)R#_P!UP;&r zSAh!RV|S)@vPX>J7h>bS%iT{lH?f9AWrdua^Is18@{(4{%0Insth_itGM2PKqx+Mp zQ5xt*1=?lduH4s!P^EfQzQQa7;nq|%@oLJ(fRrJ$Yh~xE3Is8?0ZwJ`MTq93cFcCI z{(f3_#zp-1krX1#7r_rN$}MsWIa-dCGz^+e zJa@$CZXTf(VaJks_X+jv_E7{l=qq009`7%kQ>`5R+P!|9lWJ(CseqHW0Kvpyxyk@k>+jL}my7q8?(V`K;x9qabf>g+~X)9kexb z!2oa(kZ&K>Poe~4-cN?B_9CE3U4bpPDV}BGu_O>14qvA~MTMdVqgormItBRcxm%)C zd8dR!IR-@KI!X| zYf{fZ?xdBzVVmwoi*b3%n;?MSqeJxjKDC79E)rv%>>{=zKg>w)WGclbIUi|Xuy9~Z-eFYkr^UwH zg48V;Ls2%Bt9sZ4+>7rXTTK#itxxp#w1Q28?@14t%2=Pp)1T+h{qh}s#mB^J zPSPsCttpD@QV}A2xo^<4JQT>8h??1nR4Z0j+usT)|78w%A-C^bzLK|LcR*6!%uF{r z_+R0`w{m1F+yvkt@u26^`O&R-c5ZWp1YSnGzkjAL_c}h|?Cx=#d?q&EBFU_CY402V z8o~~e#Hz1!e%_`e!hOCG8nK*kVuZ&Oc%kg$ZY84eHX$mi^FTe1k$+XUV>`L}mewK9 zB9uejLbK676`vk_?7a<>797GbH0$=xO|HE4y#{6kJtN!oH^rkR%X_|!lcmpD*uG=d zzW?dDyLkmeU$SWq)HJihOOIm>k!oCEKf^Wha_wD%{=KcBuNy85PF`$R$I+mV+_e+!pLrq=sO;XLtuzk!$G)RyOGBPP=WXda(s)_BQZBTG# zp4BR~@$k%S;|3U6;98`l0^hKY6+E{?z&}zhrLi+_O+r)foO5vWwPH zjoNu5n%L3%?ZUWer!fF%x(txxyI7-t_Zk30?m$%IrhJB2i^YraFK!6Dd;%aNOV81H3z-Ym8lGuR|2jkE9deLGaYf~$jbnESlQJK4~2 z`*_aZkCLYDb?@OD!LJoBVf7r(wSC@_FYhvnpUfNv8kY;|4b}ryr1jJQ|kmj zga>}_$0P!aPq~CB!(Q3LuqQU8cJ2456+!UhnM)J3OcQE`%d3H}i6u{DGoTw;Y5&g4 zb)1j08!v0M>ylob`9XeKeB}5^bMd8l{sVC0^Xa?WB#-z~rzh-EZEQ{FMM&(N8O+zJ zaj8$4`TZR*L5Eg%e;nS^C=+}{_3LYjf3$WkuSEa0V_B@9xdRhCjFSV5q=+u-)GYBL zBgSrn5L*jWzSEb-e(z)Je5bmzJ@%dYu#r6%H8r#DRIg$V6}6ZeaK0};z9siT5;=Wi z{p;5nhEG-GF|lot9`m^YUCRb$m7~kVgV`{1{?W}h8N4Tw$na6~otSH{UD%0RU)BIx zL!{dJC+7C3c{e*UX5WYP^ooe~_i?Se0{o{D7oL_v)=$!B6>V_HaCyOe2z zn$Rls{KeYumoND*3k<)GJM~=$A2@2};A>N1-y8p67*#%d0o?1_bZU&bsmNi+bEB@s z)mO|#j$9vpy(G95Zsa(W%PSq2|2sLs=02VK5tLn+RG%Lqv%_Ma`1bPo`;>o1;YJr$ zhVQRay|cf1-AC!PHQKdJ^x%1=`H^0CUmrhbBf2a#wkm^)4ePdg*f0Q@_MhthlDM7K zaIsQGiq0s%|j1udjMm0W+g89HhPYdWzz#RZc$bkKsHe08btCKx-ps6_Q8v^Dzs%g@ zZip@WCbUm9F2`YKkWkwE4U$_5u+?8CmfVpYq5dO6o1e8?p~_}98&~&YlN_2QRc&-3 zHr*jonM4g%Ad>ov&#O2mfP$rcQ`rQ*BXQ)C2S)+WVtPyXTmvSc3MtiDD}5(#_02|K zDA(u|qZ0Ku!_~cTiLhmS%Q$-Def7!|v%8E7&NcnRmyG5eTc>d#f@z`nyzGIx>m5(t zaAhKze2Fl-D=hR(?oXxKs%VP_t%v<@PcPhvgrhls7T(Q{dFAE1Fs8Gz2OI|uCc z$cwYL$_rr_za#CK`&v~$I-d0G9}ty6n-5T0MCAuM3@lCO)>H&0AE(9L5YtKEXL0D> zeGfWb+Uz~ux)`N`Xi&>=-@|3eh5Y&6|>TsoU&kV`Nhc$dG*y^@|8_u|mS1irM_ai&33Nmgg*t-q$x&Ne0(>GCK>vA^@( zFPc#{eqt#UxH%Y}#ElDA+tEIK!ax1t|3acllz4+<0BhIk^4f58KJC5uVHTyRPC<+J zqhc?{9u!Ja9)b$Ik*$_#d-wK2SN~#T30|>JC56QJqgV zs=Sbdk5h${GIO%?MMU)6(5TY&U%EoQoNA{d=mxAC=>Eq4+qb-@n!fcVef78BnsS(3=B7KAC^g6} zf=6eLG^X;CL!XSJykti;8VhoE4t{&glCrW=G_b)T+;XA3(V{^H@<5B?QsTyd4TR~g zMS+>Hx{I4m?q(pHlGE+;maw??%wtIduE&ziD^$cACWsTIu8KM8yxe!|%a0>(J}+U&878UZ43+J5&Yo9elm(-n|WZe2AUvm$SMV$gCc}=yzJM zN{2!u@A*y9ovjqTSywxRC{ivNaQEV?=U3kkk(mA_-RJ^Ml-x2}`O!>#R&(Cr`+YAY za#gM_)WzO&x8xDsWxzNW@FK1;(8Us)>7t=DJ%lH;0^A6EBs(4obh(zgocT5@YdBWl zQ{?iQoc$PmO4EEO$+6wCP1Y=8s#C-;(xwNZ=ABe0M4bGY5U4V2^;pz!mV4h)^Hn4r zn(ug_Ls3v@X9m8@`a`S?ei^VpbL2BspxD`HdoisG!zy|lYOnO2Eo?`>>dWuaD zHecC#6e}k>&#)oyoDx?}YBviMYHOY8ry6BASY+XW$)&@eBK$Re36=A(&$?e6P0c>0 znbLJnMh?PdA&R$#wcb5Nr;A%IC3b)Efd*I!`XKnY_jVtT0jAb*X_2qltcyM(k- z4Fc`^^*Qp`V}-%{;l-17qrqQ6lG2h| zM#<0Q^SiN3tI3o7nfiS$PyZeBJtx)>R?7f|Z?+Gb4mLMlIzD=>Ml5kKBD1zwWX|wh zLC0$7BMWzdH%4M_w!+nl|HS)pZvE~yMcSoARk%lW1+XKeox=$;mzD;;T^*75?&yvp zV82#C-6pPRUY34}7-&;5ttR@T{LBkM%}}}G)rIl{24SPSb&cki`TC(w!bzTu9#4ME z%=F$YZKxaHGq*KXg~4FIQdEjR&o=E18|8~V5F!6!J9~K`2(=wCl=ke@!jthON3=73nP}h+Uk5jjnYDXEsI>jfXxY#}B|dMp zr2Rjj>0tQhii4RIFA;YW&zeJAo{k}tG9WwW9Aa>H@A?ZM@||4?lP+?!MagkS@$H%Y z1zilmAOAugCqQGxx3OY^9c9zYdbgAgUHtSxE5QOi!=w+rTR!|wrRsY_=};SL#Gz?_ zrq7JgcZybRHWmBHDDCB2i|Q}dRbhK%1q%I_VyJ^UCPMU=R(Ic^NE2z;fN<5lEN)?& zqV5nD^YM{e?{bo8Q~3u#j7( z^a_*$6xL-sK;b3{iGI0Hh6Yv(Zj*0RJwZ+uUUr6@t_r++6q)sDqAI+m_$Bu6YfV=T zYn#T%gJ-We{MWq&Yy58CFb}=+{I7+ca{W*%H-X2Y{z?l<3DKAhpWU}Tq>r-ECtWt$ zzchr-bw6-xub0u6;W)Ld*AfTrp8Qn7@jt@+Sj)*?j-OCF5)g-Gg?a%|Q4FljuS2iQ z6yXzzkR{qjVWX@{H_rhn)xP!ta1jU3?va|l+G^~Qfz3p78%#s9&^{RP(Gq8kA^}g| zAn^)hf~qbN-}ue6cKR=6`|wr^1v{JkEpTg>a5(EN+pFi{-xAH+1Cx6>P(4omEy2B7 zXSe^cD1hD94&CZ)yuG?!gTzd&=v{f$7)F8-c0M&I)NUUolK)w$-zL|1^Ad zAxC)opH?s1JrITKele(E=x`YvNiK2K>j^R@N_0IQ2t>c~j@~)8{U?0btR;kp<~5T` z3V=sZXW&atQ5fS5b4&y3Nr>Brx5`7dGAgJ2yL8BbhQvFQnqazP^m>Gnx`pE0YH0*8 zzw_f>`+C`)#Pfp8U2z=h02QO2$})WDD|N1>i13_=vkqv!cUzUwt|@$4pMzY`St-mK zeegA8?zQ2|G$0ifOv(l=7(K?kR(@sfzyUEddc>lIyg-h$`q8u3q_C>xm{cr{bql!z z#ngYTDAxR`P6ei>rZ(~X_zK=Z{U<8_ejLad_>s~8Dm+WC1%<)FK3z2mMStD%w*bF` z;NM|ytIrwR1p8TKoBW~WhqD%-My|e%YBoQ+H18+pu57EfH_wr!Bun%dA4bdxsg$sO zGKt}j^LV-u;nDXpIja}c;jX(R60ZCt#Fo6jtEjA2bAqvug)NS_`ybF~6@lp3|F$6P zQpIC}uglrbHL+YV>khX*I??K|EgP&jk#Rrkp^T&%$}`bhUD{OaF@vCH!@?dRpU z!mZl)vl%K+n*yr7!){*kw3n>(jVtPK()O%CZK3&Q&qhld<|WtTHgQm{ND_k{ldq3u$vhA`w- z6pZd`wQZZVKW-!iN`T4pu3yi!>m~KNk2!kYHTtD6MeRrq|E!82xpEYn6yp zZfv(Sv69aejBsogdU)+}1j|~a*F9WSR3HP_j-DpjW#IE~3S?z~k%*@5m;Kb#;x%|U zx_Q@H&Faq8&u@)odhvx)0~}bTQY1MSU$Yeh(t8B5a7z7%SvAZXTM`bL-J}q%O25ry zMOn@YM4vu^m~wV}i;UdUipIRDmR(M8h)HaZyl*GhCBMN=$QC!xzVv`~8=Ucev0eYO zPowZ6Eor=$XrPt>_B}V>HdtS2s>69bTe*JcA2xw=@P3xZ#x(+Ko0WyzUgp0IT7;Pe zUmQ2NVMl=rUF`oC$WHKDXwm9>d;Jz(TrC;8x42O-uv5)fr3kTeOo-`o?~TqWMZG84 zY3fl7pGYhI$l})xH??06l-4!?cnn{iNBA@GRj#8Zaky(+C?b$=EM(~L=EAaYNCR}> z9x66qq+0uJ+2HZWpRSfIIF|f?%bmQk1Ky?-F(QPG|KEiIiH!a#gi=R+i>Um2`>)Hc z>RU2>!n%vY^fC3z1p!qCTNWO$ACDfwq6LyMMqe@)uU*{fe9*aYB4NZWGE`pDx0b<* z-?)6pQEM8mY3`9Q#)0zhOkev8)=Nj9FIJ#i!ivIc&6rCi2f-)&*RF*1bXiPbx#nhI zE7#$Sv?nB0UaMAzs_*HjWwu94p*_)R)6+50;_ua2W6^%FA^7@-O7ycfAUR~MH1Uhx zw?m5p7aD!cQOK}2pCT?bhX>uJu(Ll#nqE7?kHGQPJ9Rf6nqf49PyLGBIi&rKe>8)C zP+|QEz~&}B+u1;a+2VB-#?HQu2H2kIhjb9)d2noJcN$Lmtfbh_DB6YBA8D}(Raw|y zudo_i3kkAcgm0_Mxp4ZV|If*YydiqJ-gVMaf~S+}-@K%tz556-ckK4{3WCVS4Ue^* zNjb@C@X%IsudQ=j(1RSAsNRMVJo8QBw9Wb|UGe6c9H#I(0I6-A4xYMzfc=}*V@N-5 zGgl(6j3$-;B#N?8-hQ63LxT$>mbAF^@X{8EB?T0>89k7z*T0`ovM;GSuN8axpFXeP z{f1U6f^iaJ_t2fFsYT0oQCLhMJI>}uxP5|$dkcGHe%d$FM^W_XG?R2!{UHOpg>K-? z*q7q0ZHdCe*Ko_+%Mj>^A_lJ@V5+s~`SSEGGh>DawchHxu%GZ11lL#ziqbG}5H_zS z@p2D80Zx2}<;bw%Uw-NHr-LQ{unKg49|ON5ttANHK$|8!vKY|01yxA2K_AM6?rQyE z(c7ZMk|Xzcn4dBK(dA6Bf`jLXmIph?#hC1tSmO-xJzoAX;eB$8t)t}vO09$ahQC6R zs+NZK1L42TEaaU%?Ej1wsSqjja`lsyndqn#) zrSb&C%4VYGH^3N9>(rd8F=ibBl~etZ!dJ9dL*$859~6$+-UQ%zU--p8OzAL1Z5`G8IS6_Q;OX~TZ6G1D3k?Ghts=9bap zAeK9aS8@PFSj-9{SFpN+g$$gsGIDO^t0?0oH2;U*%^1TQ^~5{H?F{hbQ)jsf%Po3& z5}?HdR$Y8kP+Os8R`Mk)-@YRm-5>vvjHf-zcTBqEn3c=F1xa^!Lf__0F{D0A?Uykc zz;{1OkY1gTdw)UEbzih4UsDJ;T1dE0R2^=nnpYEUe@g8OZsnIZ>xkvhMo^(IfP}ZN z&S*v3kf!<<3S}j10^``xU|yOz;?NO`KqJ9BqNzISv9uYSWMTMLtNwbYkiGr&3kE`tzo3RKIJQ`}n6! zfz}>7lRn)zX2+jI6#-Szy&AR?w+tnhHyx_A8r*bC&uBGUSbBU~VMq{dFhVZZVE~^| zVg|Fxz6_A$-AoP{#V8d>TDf ztWPr*(l$1On~^1Vs`FJ2KLjLlm=3fC`zLu^pd=VJ$KIR(E4PAoL7)u8KPu6L9gevz zL8u)(YHYM-YSRMi+)$#DHRVK_Wt^s#4`9Mc{UAgSP{D#GS*09K-)kk1sl1E^+hIkd zNgaxC7aCeWalr>Lai&h(iv3EZm#%jk{YucC^$awG zya3)k1Sjbn8SFD$zJ`-1|+5erkWLvHw@lhZNjUE|VK;oOm3p>T#y9QCgj&U9Y{>pLLN110O8<^-KrCbGjwdCOw`>K` zfTx82&@;K+63B@c_QpP^<#*Emm)Mq;72`6|NFHddJK@%(w=EnfdCz=(cH#{svAClqHo2i|YDPy!mu)tuh2c~y=l~d9b zjoDswyZ#M_KWo9g!Y)*EC1?^)&VXfU$CQmGZXU^rzkki4#`^m=`o$9Jv}^zH=t>l4qo=!)1 zU6|d*^%S*+u?4t@Ts;$PWk62=?ir`$iaHt^Wn68qj5A>{B4aJQNc3;AR;N+SN#N^! z-R_3a)hY8WtEK`yBpJW3`);0LA6_Krla; zZ$%Dh1#1tI-nYdw*3hj?U+*qqK@*C$F@ndx)!*vk@O6S(KOwc8KpF^~iRs#rYH5iG z0-e~wjndCWT*NHeq#6$ubqeb|8OnZ;FX7+V0%t|B_=`B%i0dK}xgbHc!4`U8j`A%m z#|ujLu@`QiZ=6}*z71`m8 zFUZmjyC=|B^I-E})*prqSY~d>r&_#9mCwK%JuhtR?4pF5+hSBV6a++CWvS$FVRVj2 z5C4s(4%HwoZ)g9;NA|>4%_^NJ*_I&rxj$uUQZ?Sp|BtU-mKJ#T;~9uK&_TjNEQHo+j&q}c_;z9c3c;CPS_2F1v&NJ|OO*ueaCdIZ%o?RyHLaV8 z@A|PLog2p@l?sO{Eic9P~<(sh*aP|ApL`G zd5-*F#2h9v%`}O^_-B`a#7|Mk5z>be;lILEu{Npig12TZk@7k_3K40~r3JP}9j=#N zk4&@pR&=bRLXKWQwoeRh!C|x-SK4?5RqS=b>6Eymv_Dnq#?rKf-B-L0TW(__^&js_ zsYC1G2OkiIcAnGupQ_++J)8S$QcoHuj`|Wc$$?lfKBB0sdA$a?lWG1tMNFTEG53j( z3QKo(y$?;`NzJY`GPbawo!w987a3w%n^v8%>y4z%=bHQp!?Ds1R*AW9d$itKGjN2B z-P7gXb%wp$MAjVk1)GM_7|=CQPsYHkLK;wU|0_qFYw6BKz=E*t>DezKq$rvPk6t#= ziYbqpx^QDKsnbPifaVPl=E!gxvrw9Ev4)?G{zSbA>tbrub681Zvy+9OKx7SOfCC zO=ova6*V*L^IVhz^BT_E38g9C1kL=mA{VEcZXNYhFiX;V7wqWME52b9e-`ppdch!v z*-%F0N|AJp#J<4cxdrp}o_N6o=@6M#Fun@V_exxXHVjC1e_Nul5Bm$G77)qsVO!E=$w`iiKHf-9cViafA+BW&wzaNa3 z-}KX)4sI4A#ac@&uYfschm-_jO&(O%alrx2DF%>FIn-?(?u)Zu(a#V-(iEkMZ(vVw zf*y?){SQFp1F>T#WL6NxfJJ%P>lL|8Ps!zYkK^qp+R1V?{CcspINdpfL#v$D1$@%e zNu#v%=l2P|iOa3m8baYc&*#jBeJ|VBtD3{c$M6LtYb2KeQ0epulbqS{tvxN4QhSZA z)(NaANpUKTo$SG!_3}oj1MU0wU=X|v5f~3bW=J*xV5Px8LqvrSz>W&!iJ6QL$@1(S zxuP02jUWt}_yfl5bHdoVFw7gwD_has87VO-%?42!85||*>kQoq1!(qj=bN4q6nAQn zr$oR8IU+TECaM+(Q(78*hZcHyt5>*N)5zZ3+Z1t}(UB41_A6)iYtJCa`(b1}>B&W* zX)THYZ!}Ab5=a66%!&H;8M7PM#|FVIL~OorY*=K6_WfuZ5VIv6Czc@%f?{W}Vm>!@ z4$Ub~L^aBADrF(Ag$yXYL0 zb|K`ijC{VCR#%s%sKWbcy_IX;#&s6z4D30SmA9}#D)AF%Agc!$iS~aoOvS2^S7dBu z{Hc*v?pMe58>Msq48`?lHWjkTlHh#`te`t`lkHGGtIH_`hdgFK8|E{>;0{fBdCi6X zn}0QXpi-P}(7ge+}U zNraeIFR3r3XpGbhK%S8#f>-~?Xr6l`iMHz>&dFEsQagPY1W{Un4<&@4qH|C-CTf|p z0yZ;l5&_q+4%$ri*DO;nXtnwjD3Exf87srI`O=%yMRb?G2w;fhK!#kARkSXfYafCH zo$x%yj75k8Rf_?A&z>s`nmxm9GMY z)-=-bKw^Z?o~)Wz>FG`n5UwC`45~}j46l(>wV2hKJEs9_m-5_#R}5(a4Mu~75V%Dv zdsQG|cL>u*V)1+{!+MorWwx~HdC%|#aHiSMFiab#ztTlY{ZvV6k!e}T} zfo;*W4E~2D?yYh9e^XG)(oMTDk~TufEaOSx$o$iVXgNKjnj9~1x@^=W1!M~AuP7;f zM&E5aI>nGP==!uemYqr_S=N5YlWx)C{V%Dm$$)inmOv6DOfLM1sv!SMI%8yjMaqIO ztF5|Vks=s_$ju^?erA1Xe5BD>vf2XHT7Rg z1{1R+86^w`=3y+^IARX?9jH7#ueCv<)}ICr1{%3#q6PhS2@1CwQjB@vG4&{H1rrMf zb8q2mR&r8Ww4!mV z!HH-#)CATrje0&IlZ_Je-2?L!I9;oZl^p0lrGFDt)ta-7Hj+v_9{4lRW0GHA2+ywd z=?CUO7m%w+iEiP^F-QwYzgHdnVsGoY%EWmS1}326bCwOG<&dU7P|Phh5FX5_Jc0)u zd4RxXLa0NC5*kG120&TUDgx&;Ebi9I`UP&1B`>?#zzpHfxz@)M!w)QsQl*{DWoy9| z#1WV;r3h zHr|PDlac=q*!c)}Swb~YK~VXo&vGs)6}t`aQvAEe6R}PI0l&-@APw!Svnmig!acWe zjb3s9W8|!mZ65+#IQcc#=!&%K3FSZ~&@Z~C)z<`uk31tYx^7wSw9QXhRx1G#5&<(- zkhRTtTxvp6o01@D(-u;(*AXOm*!4Pk5oY5WkO4&|EmH7Lz-_pA*k^q)Ax}-XsXNW) z7FvdLn=x_$73v3uMOO=o)R!XRdh$CxLPDZX}fGqv|u2`NS#D5 zT4flxmJ>CggA_Oo*Wq4}L##B;V&N)^(R@ZK_S%xF@g!MwXWj}pQ?C@&0|e(Y<CI zv#pFtEGn6kas7o8xV^!FO*ScDR>;7yB>dxO6f3H8*eBF}3Fng#Fk`Ixrw~2W-~Yc) zRitSykU1%2bn0-5GI>X?utk%!7A#0&d_F=%x3$d-hyf(Q6S&onE2mK3-!*_DW*M+t zdoa}NpCDcguJZ#K2N%{!7#s5+qR28#Tg>!O9pJxe&)BLO7$}3v?3fO{-Z%sD*wLtG z$jDeUo+U&P2VF|V0938uv>rBiWs(f0?Zkk-?No`=mU8OMz)c!MxPJNHrm!s zQ2lxIw|9wtc{%~mxo$Z|f&PRc_&5fYl9n|SQ1cRw*7_#|L!#jN+bT{#Mh1I%hE|#{ z>+=0L<3~?SFT4k$GY2DqsL^vLGu#8NU7N83^c4&EXVJY5PHLL_Xn5>+jZ=IF^`f+xLA+s=@U zNWI}|$B2PN6SP-3u)44&0J#k27Jn&vP|P&-j`Bux3Dd%oL|8X1C1?7};3ULG>fV6l zV6z4N&WZFtU6Kn09}-^ylP1h53o9?^%siu;A}7CFVb(v}?tinHG2snk=5_SMfWyw5 zh@RQhv{thMqaFO3z{*rk%h8*XHjGlMI|)eDjbP;JTE3f0t+; zS3z$TTF!)FQ*UMF3_75rEqMIUpB3_d?e#&cogmU(SMzN@eca|+8Uz|m$_AeqnEgd6 z#S45DaLr|uGIj^cVa0$H1&Mus5;#%Wi?8IQ9|C(C@zkc;0>WHwDY!wwyt&mc=5YIl zM>Ht`0s2WBflR4lwQt&ibFJ(I3MQiBaT3#5uK~Ro;g)*;#2He8d#USh_ZxRO zT4wC<7Fd*%d+;3i1`^cseO7$w_lJN5+)xms=2XlL!^a;6b))lEr|-mnnQ%Hz{m`$& zeE1A5Olr}kU87e9mJdiTnAM9wditt_HMPyqCF<5sFV5w?&`S1D1EaoUp)RJF7DMPe z17zK|b?A1~i^61PD>I>E{PA9xUhqpf#;MV|v+3v5wCba{Sw?Ad!?KcdK1fJf?LDKd z*x+yPAMcyED-lbY&BYk~e`+}Ud*nk8rDJ~kWzz!}Fw-~LPwyQzZe^ObsKn!RM*<5@ zSKDa9Dviq{-}To)%Qpi{Z!L++i%Q(hD$!xZHhZ;4 zR>oFD+Os3Aon7p-7I3?~$H1ai&`1P9&_`X1%y%a4mG0R6cZ&i73ql<~u@(AT-Ly6w z_eQ>L!p|r7BD3-QH*L3m);_iLpbGb$AsBMx|H}6~)j4};sdsLe@m=!!Hy)?gVO}ba zR384<2mOYoN71-c#QC(^XQ^%SIBHRq*%~?iiekx!w`Hf6mU}+gh z{rV;LFgFMG54}+{iR-cRlvuK?@jAX#P0*M05$iIO>+E?VwOAP=ZS;UXexC5Mpv7oL z4Hdp^4CrpDu? zn4~OR&W=;EC1_WNLMfP{#iFGwA;o73vC#JuF*_Fo&s^(>JuM-DirBs-KpPnR8JI*d zIQXIaWWQg%rt-EH|4XKtZWU4H0n$%4gE0E;apd9Cx~N;zAWING#WmiuaY9w&iqK4i;HaC?cIaYydPfkHjhnSMkGtk8nTp((E6)4Vi#1!CFyu4?yhvGzZ?dP5i;O zQx4rs{wsbYP(na#rLm7l22|hu2P}OLd)wu;(%5qDYK`;K#RaDi2;l*unYN}Dmnm(z zPeNQj)=>TpgU8o#+I_J82x$%6@nvLX)4emA>!0T;-A1%-ki#+N-X$q!ITmxZlfo?O zaAENsk+V;?UPj}f^)eIkF?utO!cSgwyw3%p`GWg0c+>uke2g0G(jkXh^IdIjW?D?w zd*F;qEURU7F!v%b(6PK*56B8ZO-Nr4u0DHNQ<(H*a3?Fe{JjKS^vRK%+;O!XxktQ1 zui;1R1R0_kyqTDp{&i3cDND|!iMxJcUw0Pd7xo*=y^o*XQ53ivun-s* za!~*+cOZU3V?ZhmV3%44w2sDK*<-uKTn%VkKj+!Y`SJ1E);O3(vf`iIrvJh2ExF`^ z{S0oa8EX-*>q+%D|NRF%Ho19!yKRo~Z@j)ZLNS6h4f`gWrP(q!E;Ss#$N5AXozo@V7DNBPtQfR9irLR8)lNN@*L6L_a zb7&sd(Ca^Nd~H;mi2K`ry67E6RWRyC{qyqvkP!&WWgFR5{{s(FLlZ-v>NwZt4dnx~ zKY}*Rv4owpY27@$oH4p3gb!OTMXz_h84_=8k5~`Ojb_{i0t_X_w&1^byfwq4wM(A% zN@kh@TC*@^_^`FZub&ofvc3+JlGT;YF4r_p`ep!UbV*S|@8&PIdxkM%mEoAT?-?2uhdw+lXo{ruXIeY|W? zA7#Z{V1;KA(mB^^M1bgE%=Y5?^}->=q3)PrG}rat1Kd3wVVCqvd!Et#xiKc8B5ZLj zH)BPR-oGRL^oMfQt*dc(+ZxW?*5dEH%J6A?qClQICyuX=m(CGC)%>~b(RF$E1Z1>6 zyociF-zA}efvr0QkL`0qT*n=C1^Ul7q=dC;94 z{-v^5mv)kp)(3Jv!s@Sq*$b}?d&PVA07jzL(!?L?*k-6bBw953Q{rwV0vv{)n)-3) z_Uz9VCnCgWH@amgd!lmx(B*H`A6u2KY`mb@hf-+a(p4OS0~W;Sgrn_j0sR2(aP3<+ zSNrF~1Q#U!JvZCIPH8UgN|l)pns~N77XhSq2h%ydQv{yn#lYd_ckR+&m+Waw?vqx1xkrGI~zs9MT zf>hq~_4mG??5NeMkY$vWy7u^c)$P}ZT}ng^YNkMVc5}>?kCyK>JVnzEGi*a4tW!Tb zBo2^dU%K0{Vb56dwf_SoLDK?XjHjhn3E65J>|}bYcibTD&3=Xoh+#_mE$(fOc-MH{71kwujqe=?}1cucO-aB zJ21#nXAI-{)EJn<;gEs3$5o`um$R-I{O^Tvwllf6mHnnP7)1B zwte3;E`oxX#4As}ksVLJxc_0$=Dp{)`)^dytwuGR_#%lHPb$2ppvS_}TF}fHa|QpG zRe_IAHCZ3bz^! z762eJLhlFblc1lG(SEgMj-kKES zp^<%X#o(R{=ntr)6YiwHn7T>S^vmHgmUkQv3bCoG``U;>8VEd;FPVQ%y5CItPr&1} zl?E{7ovrml{+FDM$ULi>C4FM`QRPy)L$I9VZg9jRR$BP(!+YIvrw_HquF#j7z1mLt zm}Af=H;UMd(yxk*;@qd9XSA;<2MmBhI&0pWYL|o7Phal;k@gs=*72FC`1NdHTfK1yYLi^kz6PRxytXX_9{v&Q0U@mNYt~>w}h{b z?Y&~v&P}sRfF#8K`bofl_>k!KU#Ww)2c$V?cd&ZF+h_D#V3Qonw(GXE2?gDxpGe3 zu7pJH22mK@YPcDZsdB*f$V-LWks)fMn9NomQh&4x)a=en_5I0c_9ai+ypblumyj+P zfl*h}8+o#UodLl98LZObL;3kOPE~mS*i|v* z&W!deUL?2(F0V!4=1H5sWM?M#p1tL{cW-_3SI}Wd>ntZs$lSskRI3aQfQB5$zi0F_ zpJa(38d^c0@xX7&-TvXqZx27@v`Xj(>ao2rDRlfJG>vyg^#A}t^)<)^^IP$}>K;ZjfMWqPFc8b?Biq4_I z`5~Utu0eWeSz6_J`hUP{k;5N%j%BBY5BuV}oSVP@ex|GQVI)<0pr%p&N$-y1qv^>1 zSex@-nX7MaiY`6p(8d@);ut@=Bmy{DmDlY1x?yUOb$_4z!FCkV*HuCSnW~&0%AUzK zKdAt>D>R^B+8}Jz7Jku7Z15w#pKsuzXQzE$Aj?71iM{u)a?+#$#MWZV#hr*?Q$Hom za~;|jGZ#G^b6T`RLDA@;x3$!}puhbolb{1eghgu}^pavtmjW<4Sy~QPbdXFp6~EGA7jLs=We-FNu#U*2kxuHnntKN(|WE|!T@gIOtAs47eE&_o-~1& z?@#zG{PDd=F1iu-(ifw@%K01sKYO=&-pi0k46k$6sJSwG{@{mdW;GJ>ltH&roue%L z@M-f^=L$7hcAOA8A3hKvJ^rFeDts=;2YCY5G_~$hvi?E~nb)4XhQB^bm}1&!libXU zRfj96Z|gwQ0fgbbX@!Dtu0Q*9vo9{%(cN_4PaFXM#9^HRFTF+M93jYEojP%t=aP2R zwD!Ka5OGMHu^(au!J%^cKGv`g{Z&45x?{}}0SVsxeJbb>N_67I>zAPe=;Z?jG59;u z6E&E6D^{g?rD6FRr9Y*=8tayJ-cGjQ>E!;w8n299bnuEh>zAKGSlM$qfQ@IN9*kVr zCFe}-w@euMDCrP0t&fko=Ci{r=XW(uE=AbL^3_N0!fr`~%ZjHALs4M3^75CCb@zT#;W?`FcUtlK;}Pt)ddWL40w?Era)CW=$2`?PDe~*`2hbb2$6)TEyVW-( zKYuLmc@=Y!mFZdWCEDPjvT53_F&X?)A#;n^z3FmYPk3rCfO!8yj(DLeu@nUrPJ%&B08bwk5^Yhv+Nxqfxe?ZBD zjk2Az3pPfU_6H#aWkD_z&XL|qR_;-ehHC?F5W{Pv%y0{c` znN6MClDl+DQL9wPZOCPAL+JReAw)IIaqmW@kYp%xDTGSqGL1Bv>s-b-zt8y#_SpCP z`Fy_b&-?v)JzvkzHFc!Z{;j{H5HSrO?e;vBo$h-m(&9>V(YyU3E<#9q5pnMdf1#|k zFn+p8>`4sI={TZo91ZCMrsA2ypS>;hJ7gXE zYS0KQ$7#arVD|6RK^%o19+OaxWc$r=#+J*oOtOXOV~oxE0sY;Z z#<%z(gW7mu!YJP>JLmO{Ka!7d_jFj>D~s*Kwx%j;Ywqlv2Vn#w05f?e5ZIb%yi!V+ z#dC(coi4a(gw%u|g!|AHtvLKO`KDcerkLlzAH{p`kB*@~cn~uBLwfV*+lMtLpZ|`s zwpI-IYoa^t!twV{`6Pr+wWQU3>_gdQ) z`Cj+!FC>{M|2M;GHW^$rNz%!Nu<=W4Vdce`SCEA2szF^r(F%>EQn6!5pdcA zes)ud6{VvSTFKcomc!P8%b4f))^=g7(2jh&7YHilB&J!&dpd%&1E! z{QKW`OV7vC<)MHNn98q852$3M4M5CPjNGL9xUKMC&G0eKuqu5EKH;{$;V8F>%?b9XZD;$vwzgt>o|R)O&W@waN(xk_n0FbV-hq~`^jt- zZ)+s+-a{i9y_XKhR;z6J^w3fUOxkz9<(p7}W5&SkfkAiVdaTmtA<$MC=WPdJ&8*4N zqZ>9gy?HP1p;o&6*5$8EAfUxN2(hRbKwwFP*Uk_J7hXFEVr@;&hQatfJ4Z{7t&qAq z7jJM#*9KHTe9za6`;d*#@LX!xn8D~mab`9c$!IX+*|N0vS1z}bAlOEa88gbQb=!o> z=}CrE6-!QuxwCC{0c07a22H%mmo>!#`On8c9l68(I> zyUYjCf1||W)jX$cOyG=YB6(_D`$^2j>X_U`?>+i(ag&+~MYLSl9jMn>YQT^ywDI$k z2`*~HQUvd1I?}29agJ5yKwJ_ci#>U5y|Ih7bE4HwZ(+l!6mVR)P+~zY`NtaYf}L!+ z`;%izfLw-Rv&z&n=*Far2mlfNPY;aT)#OsW*oSkvepTk^Jk!@Q>r3a>$BKkBa*zBr zUwXo?s5zrlh-4DlTRNNnl0?GOS_ZT7JswPGz*5t);<>ml59nKK5n6Ph zU0J7Pi;F#YONjgsZtBUR4+|XC_NFNVMs6A8qG@~C%gjc9W@mB#@G{6oiTnwFr z$b%(tGC2TcwG!yfDo>cG@h!9jdl@o6!lT}3%BN04FS^R*gc=0UGU`Sy*$MG7UDH%c$s(`CPe}|Pz zzsXlf^xnkBHIao~WJL9~bs^3*m?Ogu_pZl=w#fYC+#Thex4%h{m~93*zJdk{h!l4X^ILP071J{ zp*mrzQ5nlr^gHE4dUVI0zMvmtV3$I?(HvuHiV5NFV~$QO6lYD@5;n7O1XQcFWv&{N zx(AY-(D=~?oa)={wEprx(1k*g1k=4tdE>Arl|mB*8?v zwC)o7aDl1ZBU&+%iVSO?J@L{;_d%kul5b|gT(K^+_wBhMpyXLY^+U-04^E?6z9I&h zmU)YPWte#z3rXj~GRM>8nW%gZDm8SDLHk zXY`d_zm?{fpMpUF{W%(MZq$)r3s*fZpBm(e_=*X_OLT0TH{;GnmiX9bPlT1LGg78! zN!wZz0$+c-Fhmi3f3R=vp(Kd_HLba?{~7d7(Wnq;s;>+hM%`e^@h?8tgEg-${m6Q? z$lcmH@=fWcpR47hIc2E=I)Anl(U~?u+NL&TPG?fs{|#szJylQZXjG_GKQ6ZZCbmWE zeN`#R(bHt9$+C+#w57@s=Bht_0V0E$dkOUs^tPq2!jhcP#2w6avHnR>Y0z*8#>p9t1h^bi!-yBgM;RalfyrUuC{_<*JgnWW39z_Z)`^I(8>L9l^DL+qZ5 z-){(9^7#q(!=UZd5YkpfHN#+IST!sifqQb~nD~F}%LuJ}13{m_bqAbp%5k)GjseD; zyKU;hBtG~wY@E{unqx_&_4?ZZrMmXtvbGQL(YW)&pzaUMSxxiv{gRQjF*;j${u{yc zp{<;ic-t#|S|&4bF^+g0BPC5Q(s~ADDwH*fYu*0gRoq=gEoGJS2JwwA)ZWZ<{N~-^ zQuOG=V8#?e{Qj`4*J2HW1P7yuX?MEG4yTVaxnY`RuJEIN+AO6X`!<=jr`*!2CV9W3 zwSkaP`Ll|myg)&chaP^0T}=bs%y0pi`8;*+0gIreVk1`F11=_ znOHTQrv=Pz9@mlCeJOD^h%(^Y*qisM_>#;92}nKE+b&EnYn+@~Mlux=t9-Nq%gTCl zW@ou=a5}?EEkBD%W_gv`p09>_8Z_F(;3kqg9zR+KWG4MLbyRN!pcH)~3S-v_@iP&E zS=VnT>D?-T+PF-#x9ZjsZRTfPx=HTSs$9t#q?0jGzuV9f9brAb&HTkm zlsweknMi}cQF!I>!n-iEW*Bi&>75IgPQEHylIR{wA8@#DoiBnb*p1rv{J)9_||$)JE}*s6wkd|k8)-D>`W{G zFjn%m+$)-yqg?Jt-e-Lt;ItRmA9bG#8n#9RPrG@_ov4v#E66An%xc?!_I%*!I(JK`YVYkF~Xn|y-qOGvXMg_rDVM!lT zQBCPg%p6UN+k9zC8h*J22)z=VYF=t#qzoyX3v{3P-h}9u%};1=;7SS;@?bNFd0&Z6 z!Ta{k9fre}E+WpviM-CG89cvn;v|9|E||8;ouSKG+rZ&9KHB`MK_iBZV69KTkkU0` z#HbZ+Qr+J9c}3F7EhxVX+5nm((W=pSh_C6Z0d_5racv{YUu~Os{WKgt6qlqk1bM1x zZo(O(_K<_DkWL1m5<7Z1EID#=$n|cE-h2}x?fM0U_}U;l%kdtmAfuXm4i>*$h8;pd zUKr<=>lrjhebb*hr~O;v5W|ztSaP)%iuF_Y3fTAxx)u01O8IHgY7|ayj#e-ocE=Dj z6=AU}a0pgUuvHtW4j3uYn9!6mgNP+2L0z_M>u$E}LDShUG)#n_4>J1go3K(?d^<3B zlt7sHR>Tr0K97dsJiL5?R;}g$Jyr#afZP(wH6KpoFjrKgw%h90dc`7?iYVfLp?Y>( z)36|oLQ-J+)Q8kd%;uL$eXsIaKNTlHrF^04p}$7HVqj~LKg*x`np@tXeb@TFC4J-UP2I@X5&bmx7yE%;7wL8Aigl9mLN4977QHGLLl^&Zo`7OP`e)C&!{N3 z7Yqo`iEXqx3Go#exvl0sP<>EHJY)F9NgfhOGpF`0NU1}Kt=AH-9`#JJAXnkKXt=y0 zaU9rAXHK@L494losnx-m&M4VABF?cNdKl4s$SGD^9HaP@G|A{6eFM|5@GUje4xp(u zG&HUaun?j(oVPumOH(8m*|A~almU>Sf+!?rL*{o3>)QD6!T7Imko=NrCc+O(k`CuT zs)-+EeWz)5MPgH&O7u~X#Uwzf;}sUv^5)s164j5Rw?nSG*HA^N znE`SNY@nx;rN0{9pl%oloW>J~InIQN1}AuYH?AW)d}rbUqwLxHtMJy48cg|5v;GJ+ zrwm{AN)D~AEc&H$6ACV7;ui0JkVa3OMNC+rzLjFXaepet2I-K*Bw-Ivw2Uuq+Qg9m z(@4Ud6Z!dI$vX26f4K!R}%$g%DA5VE`@sDt2?vtb2~4 z0QS^H<`%D4#_^+-har>TprAP1A}HK_aM`ET@~U)N^2O39_scfD86<9e+fTC_tbd^! zx4KD|Z~LKw->nTcznCiJHnn$!aC#HY{&2Qx=QxD2gckAfHA>KgytOSio(96`wWn7| zU9z79!jlBNg%3FKEGHRx27|QUP8PPeDfCIl9?h`)o?q`MSKidYQ?z2}eB&d)6%FRT zOEcfx_i4yrZV}8~O_mzv_SSn0Xaa4{aidm#;aQO3rEMRZCgJfmZEs!yOkd5IEneJU z9wwA4Nda(*gvnCur)K<)BsaRVsrOR-Ehv|AI2IQXt zp!UvZ0&eB8g6p?fE!&xV0fXX-A*+nNNQeUc+Wu#^*K2%n_K@2`V!Hb!lq{_9@5>{2 z-hw%p)10$yVjA}y-@$oZ)u@Zafl-;A!^fsVwI!_T;NmPMEldy+hK;49FXekRGcq(>=E zib|s!4WF&~_*^U~m^lRh`tq=UU=D>V`gK(*SaxGT*O(TY_$Bj>{(xWj^nJS8gV^(< zE>5aeYy=kZ5;B??eStWzaqS!5bQ~Gls%?Rc&!kxz+awXU7Tka^(B~J%u61w4r*bTW!T!mYGCnci<}ba zf1&Ca#A=V!)4oNS=1DXmZmmDpo3$ibR(iw#k{biDIU_8DksevZ(R5S6&CJs`iDyXq zwor7Zhy_dX(T50%ztfbIHT_f+m{EOiFP|%;=TjWy-S4nb%pcj$YNLVb`3ZM{bvN-& zSiV6+r|s}{rT3e8UZ_jr`grdt0^NgaIkmgJhEx$Oop7c{3^8vwnUy?*1n z2!ufFY!u&WGx2dRVa}=xV#(kl&oUz5V3Mt&)5dPy3fFw3Z+WkHuML>+dsnff$zrvF zlriwlOJMWUaz)Z{ORwFU)Gi9KZ6HT;!ft!(XErP?pz#b8ly0bIvZEyA=UZU<&o+`_ zG+Rr}l|;I5sMk);)+P(8$>1cA&xA$jx>JN7A)Wn>XXO!^{CEd$O*-jdRG8bS(k~1W z1Pe_AGyD&%8KwJQ=phYlz|=$5SQgyY#{dnG@PE8`RB){i4`l>8MQ4>pyb6)wCLiVAV9oyg1#fJReN@H%_Gkg|zdMj{EuWgCwlg ziZJzh>6goh5R@~jXdr5jGwz?D;dnO4F)GiQd5Xub?;Hpjq-lwzXo*3an0_r}qYefM zr^jVDZvAn{Ynwul@mQLl+km#nt)@^dYY%d-m3b7yiVrrsZG>vS(Ai+ga-?5!P(Hks z8eSGNd+3?VN@Fu^kMpG7LgrV6k$(b$Li#kOVy^LJlKI^hi6<6OXy5_v0V!FfoA;n} zYl3A~sNAE4WFDjXmx;U_AOF#&8VU+(a1Uo8CL(p2lT11v3sN+8Q0P3-`r9nP)F41G zY7}+7S9Z`AlL%6D_&+p5TOCc|jD+;?l1Zr8p`tIK*VSJ(vQt}5_ zGN+_SG&l!$jNAKo!s=j9fv)!fv(1!OV;rdB{VMKUo%lFBxthmojZNBLm7htXc*WJs{#MYY|&SB55~+Y9Ajc z_O{r)NRlwjM{Cfqc1;-#H*M>#T7F!i#BG1W$Zh&%G`&hW zd-Z2AVtg+$f?rVIEdu+tlA@i#XqH2o5@<`f9=`HSpGAd=Y7S*MbAgxHmp^*!MAE6n z2kJB%wLFBf|MEUM#%CK#5#)k9Zi`OTe*Yq|FP=O91Zi9BQmvx;Lp@+E*5l%ruffsp z>>8{t^uXFMn^G0sb&v+RDc)+5^Fl&n&Wwq9;@CV-D> z;G6URTl#<4|8dK`>hvmaEOPc_(5L6EP9Fe2(R=2ZXwA3e?CH-3+EmPKf8sTWeZ2_| zf^D~-%mk+}^_Q2Gcjzqs@1X2Vco-WCpo)ZFO>eEz-40~*$=+wUkImO5hh-$5ft3_* z^OecE{MLnGFm=8AR@|2g@o6Diz^R;c|L4uNeg7~Fns5h=e#Vs?EDX-k7hWEqBJ({l z<38am|^jSd4X$lfZdIS{%D5WmJodiLHj6 zH~bU63la@E;jsw6&Ft83O4_;qLTC;_7B6YkEp@LGN9vj-@tC|chYj6vet ztk(rJrukiYsDA2nv%TxF>VtM*-sKmk`?edi1*6UL*X;l&5p`Mn|IB*;rjK`{g(|Hxk&|3p_Fsd!npYii_Z`t& zM3q@6I-o{3AO85~a*m&Y(asfj86LTgQ})!{)8?;hlmo?o9W=;f=F8zW;;!F4abQR` zdH4;>o<8a8Y|y>>Wq(x91*4V!1t0{Y0?zHJcR!>D8*YM{*yHM>bkC?}ebzgt^ z7X`Cr;^42HG@Q!Xylc-cR`&mrF3Ot1B3khRr;Kp*?MxX9#-mM&>n~H!AP@1-8%n{r zuCa&d(Sa2Z)CY2?NIvo7p{F-}HHF<)y$wefOm{WEdu60r4o9~HMJy{%-u)`?v2$Wr z1xab@E?lnsqrdFVN!0HdyL1$8gEJ{Vdz{~WLN;bg#R;TYXt0UeC3{bJk{8lb;fGYS zW6~{PR8O5+I@`u|d`XwEj@5+W#U#Pf(@#N*vq0M>M^dZZjTdzX5x*b=jKG2Ju26WbDyKV%(*HQ@Fo#s+ihWKXt~1R>b}M zON4OoUw&>TdCX73&7@6uGEdoy^fMO!s%*~^ghZ={5tovk;A`{&pcbeENGF}yB+NPA=nzN&j;t8d)U6h z70$0O?vlOFb)k)=Z~W5m0zsuBX@L!qlP+2V1P`YuhpBI^$O!}{+5G@%J4Rgcoy9_Fx~7R(etvL z{RcEAzEm11yoqs~0;H>jckmw`5H@dp%`-3h^5EN@VLpGlUcSJ=JSFOi%&(|d`1zV5 zK>d0?aQ<)ORnxCwv6KP_T%i5ht$;MC(#f_qO}Sg1GaEfcjgSVzm=cJogz%6+BywqFMCLw9kRhN%2U z?8#Sg-<}3lwC!&?#xLiQXDJN5qF0@4rF7$hH~&J~-F;;NdjH(xcwZcey?iyr>yjEX z2LI$$jnfeYDX6I#=eJ-mz*l)3<$lThL8r4>;>ufq)V1d(qenc`uA!TgEf&ny6VrNM z3-bNlsRtg)WnaSBKKf+aoH$ZGa@X~FWrr$)!HhpE-*ecY_(7y5Nhc2r z^rgwGO)lL$-MjjuhsKFHmf4>=FKEW;a}?Te!%N*SFLzSl*^ZCjCN@?)LALF^b2h57 z+8>c%?lbe`kPfQfJYGFiF#FLZZ;vyix6M2}4rBoj_$i`6+$w0P?>zr!F-5b%EC(9j zVgAKycjhzf$uee`z=50Gk7M)L;9L(dKwtk@2tIO1uhXe@$Z4`VECI? z4)=HAolAWB4)ZiCF2)0E_auX2Sbm|+ybfM!P3%@~x#v5iO4(og3t>4rc4m2>ja&fN zpb+hV*wcGCZgQ`R%OjtX=sgj0jnv$}BN##PTB3#(m(*!=Od=F&)ivd&Kb zChrewiF4ms_ba4zk6yg0y}R#$iA5A6 z9QCLN2EzFo%Ljj4s&gOt;DILN6}l*Aws&2QI3n~LnL2`eqjq{pV|w-C!>RL{8RXD- z`4q9h+(e_Ad#8=Q>Wum4BOcrLv z%&Fn(Fu~M6jy4u3wxa!szwcv%yVqa&Ast$|yD%@^I=B7s;=ED4*M>5^+JYMMXv_0GK zY>1L&@ZLe$?dqYzc$M=6qu!T?F2CM2H~5F_z(62-oX;HZ z-*w-At#i+el+oK`nt##LmUAlLHE1RF#lhMC31u#3T#}KE7^B`$w!XCOxiu|%G!*z` zV5w7Y+x(mUr`kO#xGkO){<*t}f7|4#sfK3UL9-Zbcv)Y-fkVQbE1xuPMHi_C#d@>WyFTz==VcG^ z-~KgD6aLNsbKDw!&`CzK3D*`YRZ!k~eC+t%9Ts6-XgV{B+HWbfsCAQb5biK;7M}nK z`X*qcpEB2`gwLn0Oj*C<=NnpePxRJ(y!X*gWk+du?S?yYW40l!Gwq4fv(vw<7IZrJ zs&+q3acK+Xd1ome{*Rxw#pu5+NG}V>NbXBE#lBwZA`mULHJ$b0n#?OfA<9MN*~Y*-LUizV!RQ*%zraA7QrSA6t@v4ymv7&Jul$S`AE6v(yX8dU-k7HajO)PC91Dm=I$+N%stW^tP28Shv6m zHmIpG6|ABNf8Bod!($!qv9Qr<4dM`~qNo4tXjLBMw$81tz!_#Bm%{9ktIjWqS!HMJ zQ6XmhV2~`8iKKWw$=TRta^RiM;?nGF-^){9kd)EQ4M#^0JItYDsdtZ9I#6h2I?(!O zY|g$iNPBW-z{caBfZOmWVmm$IG^*f9Oy=C~P2$DT?%4||#L!ude4>W8>NUS7D&M-o z^$B?R9Pya9Pc(wOT%yqAx}s|ncCJXIQfZ=GH)_MP8T=z4q)T6H`bgfR&Z;4`PZ=^!uGw9AT@#)=U<@*JgaY5xc|x zb!w^XSGVnJIACYcM2wXQ?TUs5B3g$_FJy;K1w$?c)-aYKQJe$2Ncpr+Jb2RVWzo~ik zgY1`v=M8F&hZR*7Sp&6|_QhFM%fD%e_Bo!WyY8R}1a2P+y}58@MF-@KO3gx>q0)?n zKHB#OlJotrZ9_T{0B1+j$%5$SlS<7EFwj_udwF<$6L6*+_&@RG4+7DG`w@UxZAXtz&}rdB+*wA>Yacp~LZ7 zxgD@R5agG->c*E!nt%J$X$WYD?)jn|dQsEIPyI&2d+@Sd`bza)^;TW6K@@tSB0V-e-e0}v0Y_ZlAx8+~s}*F2 zQ6mTD?uu=m1~u8>mpQR||5zV>MUZW>=e7y^U-j4=RkUC8T|OXx|%I;zYT3Z96X0$>A?-Q||w*k-+{%6wi-OWz%vzg(zT*+T|%9?MG>Wp&x zK3HWoS4ecPwjg)3$aDYZY~>KMtzKqT`=V2AhDLZ9ZsWmD!+2@Y_qtDyhMu8;48_JV zk(nwkg21Q8`@=V7^S1~w8dJ@`(2)Yk?OgD>SG%{25X^DRh#@@v~GVrhsOBs4Uawd zsOJFYO!TEUip@4kkyyLtM8PQQ>0?KbzjZg~*b>&!Z~u?94X<>)9}jhtRGm5$4-1ix zR=pjv7ef5N1gKC_ae270EAI7fg?Ku-hJXH#O^sd+@!vy$r-|JJ{1erT%=qq3;PhFm z2$tIqbNO0O`BE>EDdb?S1n>W-hIy9GzKc0-@`|cB4Pvd`DfIiX`Xt?$+F4ttMaefrKZxIY!!G<9N>!ey@7RaZ8clm&^>6|Wl8f$q?OT} z5b**R<46TYkwR*ZyjYlTK5w^T#Wr_R5wRcbz%VGBAcC0(xv6=R*!u#)t_u5lv-T2o z;AH|khG7)NI-;#LhH(7MfQ-Uug+OqU4aQBdakna~NrXncUBVW%L~wbwQ~wPuZ_G#F z^7Nu&HJfD37b&%T zYcMOUHDZ?zny?6-PTdeXv=v_}>7un6;yKE;yd5k$x!^i<^Qqi8@cbCq zcD8HKiqgthWp~PM*PU;9YGCDc1N3UGtP0^2<|1Qhr_LZ;B*Jp4D$*LM|0}9scRQpB zNXia=m>D!83=;j+Wp=q(UPytXIhHL8PY^0o#bau zy|ZA9{G0NT$1VI7TIIR}D=SOP6Pt}yA)jU8i3Kf3D&Mk*9+#hOeL3dspY2mq5f(h( zhQm)6??#h<2*hr=yUg7eJK+NbR=;!_O(li~g;Otj(9Zj5s7y30No4b8XktH(bp_ z>?_urq4h)pm0!@OG$J+I4nP$g`%~?cSA(g>F)?w?w0-N7rDL~;5phnjBU$7thCz-Y zoU&5FLx=L81alwCPu(NZ24s=6T5O(~Go1QQI=&k%Wc-t(YGXl$gEtL2QmpMAm`Sa~ zR*Fbq+gT5@4rxW~jREuuYV+>qP!E-_EAUm6D9`joOS59;Y{5G2z! z{T?#H8QmTV6E?M4iHa!P@v7FD0wH+`<~NR^px`<@`5xTx$kJ_jI4p(~Rt zmhAYF$G{uK<03f5&1A;uP^qV>pl!J<|E;f=6pXwAVs{L#>{qm^PB+zKl7|gdF+C8CFsJy!kzl<{;nFItfb%l;QTQF)vuD3oX%ewRF3t=1P zuEvsd0P}#!6T2sDhq86jMsQE10Qnp4fAJa5UmP4$eTk8RZ~i1~X2Ik+>nw$JB$5~Q-XY0&m)a(6j@X>_Pj<_N zvv9Sd!J>VJg|BWGnd07=P&j-NQft<5?x$e{UoB-c^^^xa+fPWUWTZ$hirq#JY*x+q z`D^vV-&+q{G>o|LBG3Vq3sg0Vsx*MI3Sfo(cbk|9vili_q`J!L-7#WL1^|+2ww8K4 zT~>=8#zC_X$ue!6;q#_EMt>jhI_=F_jTi!o?3~ii=WD&zGe#cVDZWd5pCla$;IOLh zyQD+1S41C86aBfIP6o02iAhF*)#`UfQGCJ>6d~AD&Xu(_e{fY3kfQ*obhKW4bX%|~ zHlo-o8F7E2mDIa+7PzY1e+x}+F{K26(C&96O1HzMCww4dWHf+S-^MeQ4%wwy2ZTYkQ7K&ElFqZU{CQr6% z?J|0)6w*I^i554kRNLj1m}G%!O_1CBph7j4M(vS0^dqFkl#d&8)pj=9S{#bYQC17m zH^tiE`a~5<=9ok0>ek?-Ew?+4PG&Huir&3B$u4{D5K~OMaiuzmD)KFati%NoUsT+! z`hZDisx{_ZAjvz0WFP2(=TlBj>FeW#Y}OnMlcat_kRP|-g}x(Cj(5ptI|=0%OwyQ; z;LAtz9@?U33vvc&vNI{TZ0-FKr!dUWZhOdgKG3fb``kcOwBv2xZBDI#?v`vCoo{Vu zhIA!M@7N;ks{s^sJ^IddLyuW=2I9Wu(lBiZ;Nw5DxlPzK%PhJR1-w|u0wTfOO%Orj z6k7p3pw&7yW#nG%&Tg5wdN#{{d*W9n3h)x85<=3g;AzKBs;5KkD}Zfm?_Bgx2seLp zgL-v;+a+EAN5D;mwpdg-DB`Qt8{q?(Jq>4yz25PPq8zixzP|nMPpF1gx zyk{V&+Wdh`1iZ+1QBtvc0!>&a_r8GHR}oFTE`dRLiIGAk8gDwe=F|5a&l}$n#{UXf zu+lRsF7;^-dPGkknAjF>PK`VB7iWPdI~E+#3cO)Xmbv^PeieV@L9%9&wpVETESP|L zreP^xnYb?{mp$5A&3DwcFBh}dSxBA9;l|h1G+${RGxj2FTk_-;{fBr9H3Csy7DY*6 zqXS>ZRN)172@xRp0`$UQLxu>5Utnd$f+sFe)fybHIrc^(GU%v*Vhr;J!7xH)xfpQu zP=q?x2TyKeeoNq($3krn;0*6#+d!0FhD#T(OXP6fDu zKu%eQ&=yOjRjQbDcS@@neO^=qS2saGIIAJoay%UI1GCtNb($cdG=oPS$c>dsb@zbbsS7 zewIHlD-ab2z~oSPiDmX)I=OP)+a5})8gOeRf;@Jn33ANV@<|`OukY}KvxV$#ffF36 z+T3S0PhWX|6?T*DzBkBBjnkKAe^vadoGq?$3eXnxjYGWkOe=LdzV+875s&H&OKCcV z{)M7&$ikDcHXU-fzA~U4$np=o=e{)Vn=EQ8es}YQeygc29?l@<1js<<2#RZi>9Sf@ zfq}-`A${nE5X>h^jd#!LuuVZ6u{_G{hn$CvS5({~;P;2ddGxf9O^Us8B1&J;Z`1pX z59C8(4Dsj7q}#mt;Q8gE+rWoNO%%=A26PjUnnZE)B{5*EeioS?wk#?cY>;b>0WuV{ z{?W9$_;g}=v0L@lqOGG$o?D#`MhqhW z(7eXW&n-y%YW{E5Wmi?WvA`K5%b+EO!|3tbT`X$^}S2m+<*pGMWFuu6@x-eevC zApk+LVsC;tE=Pr<8LB5pg-$+nMh2mb`Xs4VwF?8#1PO~TO_#bmiJue#o~Ozy6!>CN^;MM!V6Mwm*jp~7g2=LfouA67QEYJ$&oi;RMcoKsm=$xL_oqvve7Cb8#X7hWI*H zs^8uvrB;im?9G`NR3V*j%vdf~_YDJF(X7?9C0+X$QIAC1cjqSVBy>3`5Fa3ohTH0@OO>PqzF%Es@|P zK{e2^=%qHsU;0wGTgJ&1j#WQn3mB|8!=o~5RI5xyXOvQ`3S1S-4mVJ`iMb-Msk(Nn z@IqM#Smui)(JWZMB`stsEo2~yvg(qbw;r#_CrOP)yyacYt5~ShgcGQ^F;be0x8bGCa-=(Y_;6k^tY{L|`aI}Hvw@)+%$5*Jjkc$cfd4aWdlj8J1Z{N;eX(0Ul!A z=m5B{Tf{0Qoet3YVAowdfjEp!I0|1_GXn<+Uq zleXCa;gLT4vg3Gxt2DPJjM#E`m^DjBLb1+fo1wqrL(kJaKee;!m3sAV4 zKx0%`>nE3lhm9%3BzySrD)}#n(|S=A$DZRIBcR>vP^7O5j_F=7s8ibc>XR776gV2%>^s9 zf+Y)|(8CK*TPq9$RDo){QBD{Bli%81^#)KatFc)hjJLExYWW2n#e_7c z8Ga@Iq&Uo<98cQXJU-K9%)^9UkW>t)0JG6sd|9$M64W|gqbAW9*GthIojuVhHSiKGZEGcHpnaCKL-v$H?QJ$+qV3$2OhOCNI%si&?JAtk zE`rgC>Wq~?pMz+Ro6_PiWg`p=k*81#z5u)~Zg-$o=8VODST1M-qp0JP7)rWZ- zy*55hgc!@}*=!mfZ{g1YUbaY$a8m(SntJj66Q;j7DA@3-X5{)%e0l_Sg}Mh7IYapf z|IJ#_sgP)YB}B*#JO*-1!XWJ8w7?Mw_k}<087Z*0%1B(Xy27u#ek#^*Rn@7?4;+Hz zfT56@axe|rgMgO>j7H5ZEA<=&5LSm9L)RVQGMGhr_~cW|tUX)y$*MZxTGA@1f6@J? zjQ@okbAji}t$=30h$|EGdyBM~A)F3EY$NCyWfIa{5p|rG*tH;QeVM~34_jSRX|=MU zKGUWHt5;~)#G1+~388}IhaEsWhX@@Op}pt;K`Z6G`D#dwY6Sd0Cxvt+Hm&T!W{iOi zMmW2=nbp#zfkmuPH{<%0>g%wC7hMM2d9Woo1X~R9kYi%iM}0{VV;F`jy=E;di}&JV z7oBeWFof+5ss9&xtZjr2>4PW9Kh(GDjwNPmX;kXPFRGbQmpLyFnQs%e9blM&xqb;8 z*>n~Y8+QiUjSCGjFISovY77a)g<~sNl80vg1kM>}lWkC|&Ded&C13G8w8VC4x6Jy? zamj8&Nc+b3@XG@F8=E1HUj4*0eNo8J=6sBotb?_5Rde$8yU-@i#7IUwf5KwUgiN$| zw$(_?{I7Tt6-z@wjVb@<>D=R){NF!*&oD{TftrsoMLCrmiaBm5Bsrfdl}ypWVMub= zhNOIELzHTba+pIo6d{#KnM0XSh`?_AQ=WD$N z7?*r>pLIY7Z5NlpSr=lCEXHYX?@0h)}LMpuYnj8;$X zBQM$E$l=(YT{H3(X7kP>7bJ}%C)}58lkl!=&R`(#f+KadY>XtC0U7T-{Wc5j(JkMT z%oO#3r55aj>p|nFYIe88LWletyt5n0j5D9e%vU(oc*`%x^soF&0ESS$j}Q|cF%(sl zX?!x?0d%PI)l&G04t6cAzwKSFcT1%Iy8S;frSp0HJ#|j9S4oglEj+LtT1wE4CY3=r z_orE*S`wB8^ncj|(em^uHdGzb^f2sW=J&dd-g==*q=y`CYlc1m&YjYXx-YsQS}{6= z(dDyww*4wFo}FU~Th=IL`abK-6_59M=`Cak_0yW1E2PcTA`g7ze-w?RFq^@+#>9;) zWaH>&&}J$8-`ijPAY2BeHG6*(=?c7fA@3f|wbVCHknbsWeQ`Eo96rFR^#w@T*6}WQB)XE? zzyEfbYCr``M(E?ah;lw!DS>YLV#kw=zTSBIs%~Ka#|$)Tq{2{*9roT-!i%pim`&ro zZ0NTSINj9W+S#&K8Q+_>jFGlGf66WpX`y^#x|dF`2V(lM73G@i!--+RXhsuZ?r$W@|z(L1C}RyU5Fe3zu@@VP7s|b_!JvmhTG{`R-L|@Un>PU6{5p zHf8^^v^NbMSO)9E_Prv?FeEP*{Fyg8$LvMtL~ZVLWq5TZ0_E+OUi_7dfs;0{Ykb@V)~ zTRJ{7PxtHPwMtw={E^;Irb-@M9 zpe+raYUJgN+x+POw&}=7fVOHVpu?)nw3x|@k zP9V6GzVhJ#QLSPwEy70oFRS*@yP_G7FJ7Z!%Qx$5syb&Re4T&$Ae#=F1m6E^Z!MTS zcH-Te?*UCW$*XRBk}xCZKdlSPp!S{a>DM%f z>To+}d&W_Efb7fA$;Hq%)9Eu)-8GlSW+XyF&4hx}zuYpnusaG+wmq*UhOaxt#nX2c zlr*FHf2C{>C?i!#WSpWT{PkIb>*4vOmenllo+8MT**eTeJZtqgY5$w>`h!e~$i{rd zpXdDkeW^E!+_ox-%9eMP3il}f2mSk_%7~2U#OCwHPTy3qdgqbUocmeQ=-I^XSf5AK z)mv0s*u3iEmPMhjXVX4?{n+q=BDdP!9`mTd^(qj1uu!g5WPu4gV6gsy@DAdpS8(-> zTkDs1$huINqfnpNVsEU@HG6V;ON}oRbhS^4tNm7f_D|mrH5J)|S6zni$U5Po(P#G45UqKMhEG@ajM9_kHj&+SIj5l@cr5v@#^F zeiDtqVMBSr%Ztm@HXrt=jN!p9`;Hg$`_|+Qs7sak@z?TJ1E2JQZAYkIW&Pf!EhkY+0p~_Z0#QHP>6c$<%W4ex%IfbPeO)FZ z4q}BTB&dtC=P4$uPMt8Z?IcDu|KV8i8$MO2ZU5)_hp73m*(O|=YSnH>Y z{khGvjgos*Fp%?iNix}5R>R@nneqPKs?rIpP-QY@EKw~^4tI1(-$H37{z3_qlT|R<)PAH3v^X!#bXY8{Pkl zIp}lTi2kbkZ+@0y&VfNw=D}EG>vyhicZPyJf;LZ;1ECj2v&N103rZY1fDh-&Z zzO#+~%Wqf7@s zp~A1(w%mW;n#V@zedjAp55BMnmiE<+Z_uEmjw%Xz2RILS<|hF~i6m7U`)o8qK;O(M zy>aOlT%bvn$q!W@CAnD4d*ZTuecRC2!+mcE)hIcF$AnT`{LVp#FN6TeHg%kd6Ov#% zSmSik7EJwq9+=Z$@A@tx+)}sZ_O0lqD|MT*dr4jPP{eYD!S4sHYjLObpZH#U!wFfF zBjoh|)PKzCK$+}y==#wWVbB+l@$cekztNcJbC(SkTEEJXaKRS1QHC?RY5B{bTv$A*N-Z&qw2) zMwZvlKgOIrjF%pZ?K;mEAS~5vNafaBGwNYa`X~w@{(hNL6T}-wnnOLm`wpM@Mn7zWwOTFrcwlsWK_sAB z_dLIabC9b}{)2>RB+NWo!{vihF47@eLtZjnK~6PSvGC!mQ|+1+km=;Tv9Jt0;>@B#*O zp?pVq#}kEeY2jvV{?1!g3GB>&c&SKE;`G;Rh$7Oln_L)RCy)MX#$WvX`o)%Afu)^t z49q8UBF)GCP?pFlp(VcU-Sc^>f3T5$(T1S0%xIvGmfx z@jA6vM0q8y@bkr!s{1p|K!8z(0uJ=Po{{@{gPpBnT$WjD(2C|)5{r%_W1Ji~(&nk> zeomOp3-=Yh3Eup??L+If9Xbj63FcgdXMpS3GCgT?crpm7KGKs_lIsVV+OnDBJ+^=Q z=D0DGAHxC6mp8ov3^l@@6h!tjP~)D>rwa|BDT5{vW^p*`V$W-+VV@QI{kL0OnAKBr z?;+np3B^ULIq!>gAif{po7wxgxY6A;1$)1nMvi1!tOYHWa^wPkty^EDKIt7|6l>{d zd6BoZXqu|`R>l^T3SL}qK3G(souV$EoOow5=ib`91}@+D#}~GXG|pO303H34a?5F5T06>DLZ` zUExqzWVCX1~o?ua$oO22+w(;PXrzP_4McqSKDh5FKb;z7vE$wJ}E)s@_H4IygB$rVk*9a zf6;G|o~&A6HSD3MH+W9=5PI8}?TS+Nk~d+K*d6wASHc;UUEvMwe2}@|*t^N@y!%wp-R80NfgGO7oNC-yihY-*-i)0wteG&Y5OaPe^&y8z!O6lL2F4 zJ7-?t(R>pbeh{DHE$7kM#W7w(5y99V{1yDIBinWabGLR$WBJ9ge;&lB*If$7M(?km zrM&Z+ebX*^-kp^`YO0$|iH-d1mHUu-HLc(E+yl%UoLGg1;oo=Gv3ouX`75c%Hn6=7ekr z_26ZJY%8Nf4*ng$g{i#t>O8l3vc|6d^Q@|*Fm#-`^)Dj#O!Z!`=1{(LhSRR3ozX7fM5<)Ij~h+Q`A$S9MxMlqm5 zM#DjX#jd-m3JgsT(Q}te-_`#(HUWe%tkN(H;ma+EHaBtch5Of#v1*w0L;FAGXcA5< z)h~2yg$z)`ij4&Bs4NY=lNO)$9Mm^OSn8t-4RSacSXfYXE65=@-WcPLpp7L$gAi?# zUAjhY=4$7r6yz3^Lt*ZwziafHZ%z+USkJkMo;N%%y}5A6R-9VrN63ZNT?OXehaFlb zF@GPoh(h?O#wCM_-MrJC@&|Rbt_MZ%5?M;>6;iP?uZp!V*&RfUd(4u@Gke}W@iydb zMj)#Pz}p>EbX3M|5g&!rOZ6p69FjE|Z&9d1KDi+XsH%@STsK#E8-|hjDK}&}-?7r21Rf*_q$pQmYO24)LiQ0rYoWh%_z30N>hTCh`Xs7@Wd!WC;Tq-UA3p<%F+ z15Z?EY~h9uZ0qwzX7&}v+&O{BYeSFsqEHS*RgC2W1Y*bgh6@n0|^?%KqbN-hc)6%+(`PIv< z*WFxKM6GQjq!D_&xBs=0@4eB0Gdxi>G~*}!5OZ!=F5GlkQM9-&Gw@XN_X>5&DelZ6 z3oH{~#R4(?e%Dr-i1oyVqBZAcu`-|N zz&KHd8jOZ!T$u)`W=5k``O;!W@|tV;Xny`17w30@v2InIq;25n6ow(qPCFpNz&vlT zyxOZ>obN?$XermlcapOTquI}jNy{#GG&fY|VRMc#;@$63x$kbJ=SI0>{J;}aEW2el zO3*1j+e)0x0Vm{(E)@LbefVMiro=yQO6PZc&(l?ZJ1%wLgva>Sc3GEr{O6;&Io^_T zW75As2L>AX#+M)Jg`bJ_IB%mEJ@<1Qj;F+}dF&_;sXcROHGq}JyRbbzlw`|2oAmBh z+kV!%AM`@V*~~u&pSDlfpJFM_=dp4;xVteQyW<&{5$2}fk5%H`dsDYQWDQu5lQ5|~ zZXNI3ayF(1t8}T^B4GxM@6=@rlNWE5Q?r3c7N2@%_Q>XCYl=ZVjn5Nud){i0OM`DN z_gp7eNjh-<$N`pX+)AhU3-+6x>kofle$lizWPg9b#$c_#%e(1)%A3IJt`Q?xl~&U= zpQg>u8IRw!zu#CtJn;ytX>mu1F9!dg)Qrw?7&`knsrPW-%{_u{>$3e>lbu3l^2w9-!aXS6Oy3oRVRZz}fMuiouqe2g#R z%-;Vj(-Rb&;UAlXKmRmxAs*MK_+dT;FUZ^jom2cnP#K`_t5Rps8#j!T@2~lkTpev# z{iRU3XL}Oty2y6za^uyR2oKDun(g*?qIfKcUxzoO8F~uFhAqV~;Kyo7|k$1eqHp0{Ke_V0r&H=iAxjg0Jx>~ESMDzH*KEHKr`g1+1urv5{G(n ztuAJ0<9jV|c^^p{cCFjf-(zx|Zb1=Tn*7zW`tzxEKZ-RX`(y!lG>0y4?KSW$G8y!a zi2|Og^TDJn(4Fg{lyMqc2VaT4J|U+QI~KO;LL3UnP|GHM2$wW^6R#9x&Bz8P+>`f zzpX~Go$VY`I0#kLSnOU|bM26jg5nX&ux?jix1ExPiEBMF;CZH%6CAy?ROA{t5Tc&g zt68U-9eQx{>(IQ8A;8<}qq@g#P~lCZ+5nU&~}G@b~Nfml_R=?2BE9BnMHlTiSQDw|NiIlPT}| zn)Vg1zUh!ZZzk_@an-{v=-lV%JDR;1>UCFOi*n-l{p2aDT2)V#pD1T0ioh3NS=DRs zAZ;0^gu}pZmyvttUn$}$Kz1a&tVzyHaw$R?h%${pEy(PNW{j~T-H#Y0R55qE|1n{h zo=gJoHZXpuBy+J`l9P{cv3SBY(AlQ4hjUmGCDXRK~!4BMK(>UqTKkpHsBVnG`M%BRul{iw~i zvVn4uECAGz8Iha<^?m`9LR8Mtj#41KfP5HK*ZwF_M+<0acOCT=F1nbqT|!4YNQ#cC zXEWX#fFIW7aBry_CBaB=N`oVfmW)Pet3Cn;dmdFMZ*alN0kZx61f`Ga8T8hHT0#)= z9>uC$D5fPR*^EcGgIfD+y;#n!M3xKd2n5iOYS#T<+88~%$w;C+@f{aT3zv1to?}t$ zRY$K(Q~<=GAyWhGK!{MK$uZ?@^wz^3%`4~Sd1=wT$+X?DLzFygVUa%?rsStL^Q#8< zmRU=kqo4htv$G%wn&+}O?V*6~oP#OHlB0{HZe?)rBx0UwAMi;R42~8HMs?65-2C#w&?vLy_gezBZe zRE)4Y=I_&t389uHIQm(hieh7=c*9^Yd*{|AWxFx3ZBkQ@o?{@|LG_mjGQv}QjKl9O~y+gsTR;)lw*v)sil0! zCr;uj{dl5q*!9Q>*}=|lENAOXfu^m>H*n2$zj z&&bz}VRxb$J1A&%%eRTEt`6>j-f}WZE39~;qes6Sgo7W<$a+ajII#p)Z0VcYEby-f zn^KU!&)ih~S)5Kv%@CKi12;4iA6wUipOwVZ!B=M=sK!BtO5KTMAvZ8NM!b>aEFY_S z_Er4mydQN8N|C=R@A|@l%iGF!en$}ky*V8xS6I%g;wuo32cgbpvD6}DPWtM=2AHEp z4rO&%3qgeYfDbY$;mXPI6D;(!zy&!Sh>SuebX#7j*VJ93QM7*x?{(&iOMI*cky;_|jBfiZDbeUF z?P_S$KX(K$JYcX_usS~^u=d;b>yt6niK`S(3Pu=-*T?Z9(F|bM2)ytpT(4tgb=XUig9EucTB4)A|6m-h&-T0l{w>Z?7 zX{}^R%$0X>9`4qU=13HDM}p$Q34;ghi)mkAHwH}4jYj32xeU<=l#Zl21w0JKFBIPb z*HzllcLGR3!(b?{65LV0O$qc{2^?P(J=C$2uLzbcic9=E66p|uUvUsl7@he?4ibCQ z0@tg+=%&O)Gg4sVmpJhwx7Grl)YIbY`N%b*Q-T(-99qb&#H1*vuGnNQaJWm$!eVg3 zhRbt)s%^MOj@xa}ifL2KmA{yoqBMcoI9Cd^TNt11P9ISHlU@&?o?!Hu9O_lKJEBy# z)|T$LZi!tB@wuYh9IKH#R@vbvhE~kiF6Y=Es*YWxx)f{qEuD|dvaA+c4ZA`mRMYTe zx_yzHjCv?x8KRnv3pwPWhvnt>n6+sH#7u#5V_S-F4qa3QOJyh($Oz#csu=D z?f)ZO=MEY)x1zzRE2VF{(P{{=B7W9X${+>0KLJEFg(nA#d~vWhT97AI6<@4o49()?d+43DYoVbKHfY@s z{n5#n^oJ)jt@WK)RB1s&XK_?(kv9pgi)vhT^GWhc>#F zWSyTJp2?-x0LU7G8%sSsInn8cDH-5wdj}`=rLUYc%o&d!P2wU~379>^b z!+C|L4Kw=YahGW_KPjflzQhZqh3dQjBPP_sKU27zKkb(xO=x0(BU}=)KtnYbi1Wv@ zU+Nx7gIwR1YC-V49nuv84c<1eshUlqm~1aVvz{%9<6HqNj|EWGq_Xi@ro2nu1}&g6 zR^2($vd+UaPH)wClx9Z$S{~?jQM1#R21Ir)ez85|pggQ)wJ6rZn)uibA%|y4R!y>E z_XIO1Ft>xiWR+S#OUaG$-aa(1&8;uA*=>#6lR;i2MShROV3Py6wy&v;fz4D^s7M#))R$SViK$`TqeViosHGmZv=NK~7Re z!;%`99k?eUfW`jLFfTHXWJn6$RCr=v-Knzv_7%LS7WPp0p*nH$Y3&2Ok?^X8<6x ze}Tcb;6mS<(8BGAj2}sM<5F_=wjzROeu*4>*3I5@3Ox=!>-A(l57q?o`{wM%MftneYao zkVQP>RHsZrIfJbTc(Q8aBI(jndgi!FJZSK^I#0`i_A}1-B{pklPr$H*8X(v7=QmOp zu~<8Tk=d>i2?|poOtm?f<&{^cFPmXDatQb)qxDjp zzt9c(dli63>H}c(28_2}0FrlmNG=^Qy4}<>dxBwA><&xI5=aF67E|>p=oSrT>XKl; znm-@!f?I;L8XX!9dDzC>Rho9FWd~V7C85#tp#|24;w%58U(tD_$JB@>cN3HzPnKTJ zJiRB{r;6p|eeXW*Fn@6iqSaL8eQ8;~7RzsZ9V!qq@;(e%3o^{{r#fakgd@G(zh7%z zX?9O&lD(Tu%_gQmt=zLBv#^%>+QShrbtGsWBG{RLqFq#{iuTs1t#q?x%(y$fzSZ-_ z{{+oaBP2XI-2Mpg@ykuSdNm+n{_|cO2bu|>sf`40(_;|hnFE|+?g z$1_&#(X-QbE9_A=xN)~@9e(3TZDCvm;Bly2e4e9i5^#8-q#2Y_JG*6!gFoW1x@^6Y z+6sv8M|0-(gs(q~Tu5|u(AYsH(e(S5jr4-c`Ze2KmBpW+!+$;!|D1iVW)H zlDlFFm=4+&kVq=Ga0@1Kjc^b&t&#+*uE0rXJL@7P@1>mG@Ge#ZXe0crSysx0V#cOV zc5v)dPc)$JeFa)mgF$S|9=?sy{e5hGvl_`Xdcb zf9fLoO~Z;}#^UY|%@seb-)pyrj0C4dKxQ5OkC6S9bya_QF)(T>29x^Iz!?UW8;x3% zu*4K8fseBqpOT#B;;#x!DC;CtpP&ImhV`bxx4NWv;*pI~+p2a+X^W9pL=*zoMgIYMG+7{kET<(hOUVc7558N5QsVH= zqHtvf(ny0C)0Ofg9@{Z+*E*Q z%b7=U60~K>96ku%mwpUGOD@vno#Nc%>p61{Eby0sI$74rU3Dv(2fH(?@UVq{_%@>o zPcV_;d<{)Le(h%d7JW=|;`C>&F098Q0D)#s5oIrL(d@0?%vLr0$-)}+$%7Z$jXFZv zLwzV1?zNMxFdiq%ZHz8lnK`+#jbd7;9zDhJmuG?)bw@)7Kmk+2?V*_X&$GlZ=#R(Y zUe!aev~W|WC|JD$0I9)&C|{_l`p`3_0vJ+mv3ICA*6r!LgJ&klqiOGQ1^rzi)vyJb#V;~Fbf6t)|H^2yJ2Aq4#<7tl8y z-ILy}wR0#2*Io@u#uGgS#zPUF|DlUB(7m)FSZRuKxk12b`nV z@YXm{#&%M8eLI(NHS=Hic4^oA5P`@uJ_F_l>5iVp4l>iZjIb~sR;IqopcT7h@y*y{ zcAn~dt0?T9w5c^6Mrb9czpKn;+#itZhWaQcwqsh@!hF5a?8Vjjlf6n);KU&X7LZ}i zwfJB2SQ8p59RWcS8|^!`$j0I5xrJ>Xr~gJ6I7?Q-7+6dZ0K*mNRG8h^1l>~8V1mef z^_!u|pmQ(QZ`!f}tN}>+dp63^H9wHD!9qX<4zc4Q%J#&?o+Nk#IMG1DLC1Wb*1nJA zDKGbWRMc7zY%p>``~oX(1g*h)suAXIaR^X-Ohj2zo`wf+g^$JPxU5DartMCkg>J1@ zVU@KektkNQzF~{l!2WBK&e&_}lTe9uxO7~k0IQ+(F-!4%{og&4PQNXX{67~$M_+0o zw~t6m%R|9wr?c$IASJiyzBPh^d^XErb_BY7N+3oaG1r~GAM{0-+6*RigHfMp18?&xR1~<@ zbuqN4=&hsep!`pPUGw5qgtR3XSp;yxVUd*gpj+u|sF@tD?#Pd=bwjIo_nUrlH~0v5 zgU5i&qoyeIkYK2HzAyl*>|&~xa0NLn2lF>`r$w@5V=TdE5n@I*Sw}N5BS&|1$$;6) zCCYQFNLA})A*<)Pp-zgH;faaS7K#vZz*_eXpN3+*MCS||tk}UARyo^6*3IK`baRh? zxBY}=CfQ-!Rza%;vZZdFg=x7D24xveLtHEpg{X1-$@ebB!{dAqA*ANsu#L1mNHuTs z8CKfi=7c4hEB>8x7N~a<+&_hG-9whc4Q6DL0q_Gcevl-L8hKLH6p#$+{=}elgpnh( zEcFWlAd5TNm;aR zh8pBGQohT`O}p+WX6qy`@PnrXlwI+I=>xc z)Cg1QjEQR?#MkRky7Hmi~f^j-UxT?Py7*EiO-qbs*HECw`Ed0R6x>^gDj@9+f8|kgx`X=%9 zYDohC#d30*ICubv8VQD^m{IJ(q^*H~4~I^%EP{xgEXyr?Vdbli54-qAsJrhn9{RT+ zw=3Y*3qGJ#VieE&N`}>Mx80T52ajYuPkW`2P+FZdJ#s&B6@aN&>eN)1rkht-hJ(pS zahlmS2yT~ch9Rhq=aK{N*}N@(*44{Cmyatp4=Qr(85(Y#hL1j+l{(h|wl6n62Q{aB zX)ry`RAPd)#d;uCw&uW;-Z`JJVUK|YeHXOA)?hd~qDT|S~fGHFT)?@>BimoGbb9}3rp%6bfDT;}5{L$mKTfWwzT+^eOeSR43@Zz4v zV^7(_s`Hi&OB1mC=SmiZU!*cFf^w0_zZhAdC(q5HQ_cK!J5#B7Ll^eN>uJHIk<2b` zySULKSIVX_8+T{G>O7(L?3a*rYXDq%fNyz=?;4V6ik@LSAFI<-F`GFWJB~2l+3Lt} z=0T^s+u*0(FMEBqHfbj2bqdaIo^Jy;>CW(9oY?j65OS3v?y?)}%jdUp%f+1^jsYA4 zP{d6c%?VMqTln*+ujC`iAj$4(`p4rtTQscgeptwd^_%9))sYLf4Uv$%RNTodrPqsx z8PC@|d$uh+jLZU^+kon*V+zT-O304?L2~$XV3#JPg^YLn5?%IYq|CwMrXcxLXX~-D z6QVhLwxo()v_1f zE{hwzPZNcQK1pfkAZCSPU82ivF$t3Dw1YYuB`)(-TG@FWWn%70D!ef?tO|21ga0`Z zt{4%0pLJb+j`1tf7|dwlgl#U&#Rx&+{LO*1v=jEt+)B+lg2Cf`mtC&t+IY3Q=U$5c z4~TpQYA9hFWmp(-v(7okt*_Oq z@KQTcij%xlR`H~}jUU<_|4#U#^X#^B*v~S$Rl2zFuqT=yEG^9lUe~{jc|A!S3Ui7^ zrHX!6NmjKU`}e^`=AfMkm^8{e8(k4ZvN6-DZSveTYZvOfFwo z@q3G+Fd{Rdc^`GzIs96pFZ&CT_e5VexgX^yR57srruSPmA`8~OVsW@Hx)P(msnmaa zm70H>5OnAFasCP}a{$j)Z2x+_t#O}ucBOTjX!nC6T=JXLhkw+`*cQyM~)Cp}!D!23dZ&TA-Skn>Vg2Jh0K*30-}x zpZ6GSqbC<7+w9e zXCt%H1GOO97n|_&wfMn@m{rStPcEmbU!BQ_Q~3#=tArQswPFGrnFhH_FxbF7ET;I{ zpQdETol2&grrXyqwQqX;?gJITnw2pVQq{fYgr!$zk+tC%WIr9m7QM~jDs9UYFe|O+ zIU~h_<5a6q`Rj^asF%0CFl%e>eXAnMeY3sjxk~Lu{d{gA)=b$lc`KF(i?A15_?KAg z?D5;KVDmc{o>2E6kWTnU_(I7NAE;e^+u*U}J$P;Y+VTq#LF4L9%*dXdCaQ&1iX$nT zd%t>cg1-6(>;tI_VRM!F#2~t|8+CnAOB{K@sxc(hA1wzb{+hgiC9ne@&9qO1DmKm1 zYbP$FJ_Z@fuigd47=d*yF59KnTbv)F{Nx1}OjjTN*`SDz)&wg5Xtf-#EU*ZGu0s9D z^PBhdt(Zmef(p`qKsD=5LS-Q4eui#aa~R6w+oyPxI!|k>9yh&XfN7~fTq{ppedW1o zIAQ-$3n%FImz~)+QUj;)sj*{(LwT#uLq+XsnM-cq>fUP?^KX1i)8BBo?P2uhw2Mg> z$&T#3kpZ&>{X3|l zFb8g#(Cn@<@1m-Yr3_MBFw|5hENZ^8k8F5fJp?potf(?$ajH21U5LS-#!oAsmeMOQ zcT21qrqBvImQU<-jj%t~O1R(@#a(?HRCLqBLPSp=3w9iQTWqxDk`f0GE+k)`+Q)Gk zW~?Mc4o$9loxJix_r$LQT7Cs`@wtdKLR89}?;GW3TWRWqrx@oPfyclizv0p)j~y1X z(E2GNTd_f<5B2j(pvcJPKVYPJf#QOgUF|;UXR7C+vX4}p3!ai2`?tRdMW{xzCKFy!Aq9>L54Qbb& z7Jp<&ffGe}#?eTZEZ>XNj`5j6YbZ$?oX3EoJ}Ki@4N1$kI!U*aZqG$iatfqVmvhfd z6)XA1H-f}3bb0J>-h0XomUeG9C0RA6s9@AFU;zn)E0cGS7Ydp_z=(d`(l&z2Tb`{C z_)$`65e;i7fnWM+<`QgikCfxeUxQVg;@^jNUmd&H)8E`-To0iyD`EWs7tqN^L!&QWv`(Vt5KRrt`nRS67 z_(Hz$W$-`IIxah_Mw9ZRxTsmY@Woe|Q2dcN8%{ElWt}H*Wg(~%*a79Y1lu~o_gftY zuQuJdH`Ml*$eujo{f}Q=wd4B77yewzi}$Hvj=<+yuRG%%G43EB0r}&#=A%!<7e+Z9V{3F44rq@s134_q;G+H;-TTUk!RX{(1Za1A>1kYI`;IUr zF0kA(fyr^%e)GB^xw0d&SEbCvDZOD47>jAe$jW`bveW*w8rkT&8vQ@u4zcLE;Bj~Z zZnpzCY4PNuE}UVK(SlZe`#O~b-OK$x#t#p2cB^TjCoB!DoxWdFmV$oq?>T0Q-qc$< zoo}3*c{b{t9omATYuMx6(AaR}5S_K&u%u#HHvXW_tu;&kvO7i&ZWjHg#z5l=+y@uZ zJSh;C9@gWX*mBcQR}M_cTKyh$It!!EfKeBPB_rNk-Z&TRpzX?U`R~<q^WW ze0WV=g}<7Lt;ZZz`P-Ly?({LqRrOG}*epiBqTPWv4M1iGh>9ec1=JWFoxZoQi|&Gq zjY7tHt#%`*7RU`dvjn5l-CtAy(6$wsxEWJkEuT|x5c5;@`=e(_gDPZ_VZQ(TXkD@P zPw%}a+Sr81&(38?ITNh$MuLu_R%xwgr1-sM$=;p$Ef-@~m=i7_N4MzU!|gU(qPNxo z{&IY<`j!>H0%qjuncVjgZ-3wA{~H|*!bbqB)VX~8aHIJiwb#YS^jz-!Zh1GiJ7I@c zg1_X?FNUCB9QZdDhJEG?;+WK*@hOIQN44v>@OSQE(JbqkgcSduJ((r!+ZqKDAl9s9 zVcLsh0%vb+UnrH7uN*<87I_*M?X*lOY(Xx9BmDATFXeVGN=tuZsTeo}UBn&n9z8nT z93xvmF&O6d=a>DuzJt}(=abQ-p=zmb`Mx~wqZ702f!hMOrKk;)I-AnwHPYOI@68Ll zct+`QX4Rq$M#sT;EEPTNmDLk$TX^!1|E$O?WZHJiu0MzgGuqhI{-Lo-sKOiI8pWjiYa~6gO;1f0QI<;>qBgZ&JSF&5;r3uj=HXjC13I1V5Gc zR`jQ6#mow)rVxWWHpe;|9meGnW>*rfMO_YdR5)1m1$tnLCjU?kh*|pqX9SMzcuDg1 zO?3)^)mhd5q18Dbex5=I9_FYfhqF=npU?M^V-wywHpS%WIW2-7)?%1m$cTd}a@!}9 zbDtu=M$=V9=T1Wgq_IniUj^Oij(?7Yz4M5=6boip={~E@6gEg3=vnVIlXABVHZtoZ zMQfAE8$AUT!|SoJK6^?;24N?FL+m!fEOafpJZtpeqNsXj*)CI9f&9hOuXgA@IJAg+ zz@e_nUwqsx`}mwtzx+uN+?cn;k`)%J{qU8I^+|+HLhG<8JKpVdp%Iflfxa9=lXHbx zG5nhsS3NVWLlkzj@8;=Q`NMBbWB>UPUOa2%FWWjG01@UL&)@c0OoATD9ZOq5iGHap zy0(L}t?Bb{;;_#F$;#Lk#LhYf7IsFitLvvlr=ia}=g)KcNS2*#`npXLc8JP&AJ7)) zup7GAnqE&oA+|3%->clUNRMR3SF;wZHYOlrkI!bxkpeT|ra+wcsXz3PGp7wt+waHI zHguZ%`f8H)Ylolx17o1h)4aeDQD1K6J-H&+=(fo;Tl@chtkp5y<*d~v6j*g6>6o@< zMWW}YhrZA(5wDZCZ_(7#kQNM?o&5{6*8GQuUol@cNey*h$anE07`V3q+nvU`$#Kc_?=W zCI2vQwfh9@=bwnF1vMX*b0^5OaS48~$F=Z!fHZN9`(FN^X>*DZ2@fJ4xr|!l;2&s+ zpB2(z3J{_}`c}UDflCKtL}=!Obu+&=?b!<%UJWvSD4R3))Vc-F!le7@Y2^Hbs7E`` z=qLQWQul->T;5VWm!3Cdh2=IB)wx0t|V7kk99}tNs*L zo}J%%-SAZNX@nGWz0v;HV1jP@jTa9C>`pFbSjLDae|;owQ?)uA`J`HhZNLdU++mM^ z)eFw0KYswiff1mRZO|ZjnjBSe26^P0UUy?!S)JQt+veeqZ_6d#%IritllE z!`RM>P;j^znTiD~?b)?A$kP##x?@s#DD5}XLC@_mO6W=y3Doc;$YuZ8ko1yoNn_Q{Z4RX?iKjO6<^#! zTjiamOCdTxhJNRzAKfs;CcE_>D%6NSToVj4{#w_V1ZlCQPI{J}x7yjY9GM*N#XaGey+U&uk0Cqkw6>Y@)XYjlkE|+ix zfv<@$`=^k3?|o?vS1f2M)**$tEDln81p<4)QenQ#J${%=zXJP_`JJU{YLSz3j1VLv z-r<5VG&+FiB?3$x{re#UT5RCF1;L9!PiVt|4J}B4uCM@vX|-yHW2LU75kZWRafH1^ zK(2E$8yO{_d2G(e@arnH8I@s+)7Whs{~$I0`Cp_4B#4+k=seq`tl+$ zDI^EV>-a!);hoZnsNY=CL~aoBdL9$b*Y4xhvsDrV`IbIo_r9#~1#2M{d$`2yLF-TM zZ5#(7Hd|rrk_77u&zPGzpT$w<-UfDIQciAyJB#!XkKZ7Px6R)n<)Ly8ZCXPJ18H#O z24A~#+CcXfs-yfjrl!I9MMORi&-$fO-A|D^-L?AY?93b%+}Deb8|)qv4WTp-LWC=y z<8RDQ`)uyin$NjZcNrNd@=v5Bluu4bi@KA{7VC-$ISYqb87^r75zn&Ddh2W%T8U9V z`T_M@@f`JFw>4Q;h5yAFgg6Vk(CS6eYccK$$ZbPDk{dG#sa8wOU|*-il#dcFBXTlK zPPofe;a04xZ5XR7K|$Vcg;g8X_7V2%tm96oYB)<1vA*7TxQxn6Oj~jJ`Thrn{2HtBqF_Qm}TzBLJ> zF7nwQmSpdF(^B`-$^U>||5m}o?;JnJ&9N5BqE|D3CNrwrXcGhJP5l?=Gq3s#;YTcN zW5A&6BUZ()_GX~6+!J#F8MY}W94*n{-Pzr9{64viUmjn-{;r=a#(ReBHWcyN{G!kk z7{_HV^;=G3cOXZ{G0JwcTTgcsgdT{-%qjlA0{F(*>&EkM?6`Dm@wHwHH+B2@h#n7W zmezjp?)`1z^3Ef9!;|X`?pVa^9n13X;sE3LGu7PGS7cO#y5DBbkVje;Lu!w zkg4(s2}7z&vk^+gteka~PC}BQ zHit5y$Z;CYV$SE&^?hESU%vkUd%d>T>-jj`@3;HcvrqAF%9>Fz{rcayhq+9TuIaVX z+D|q_{W{;2Zmg4i*)Dz=oJFInGqWt?j}J41VUnIqoAER{;>=+)And8t6 z1d&Wi)0!nVHnE4DDCZufQy3s)71_A_f_Z<(_74 z$Gu84U^@N_-D4*r7_RryQfdrC+2Zp5eP%tRH~dG$kWJ!R?t^gbNNHD3X^^-Z6ZT{; zaGc|wp0or48eN!Sr4FlMZK1dkKEVJ=vpzGdcxtgQ)#)i@Jn0J@R?Vzfus!J?9j(E) z$_EUWEL%72rfXE>-g^%&8MBptu%0~Zt+^z1Y$S-^g#IEHLv`-zH_u6q^&(W-j-r3r zI!zUAGwvvg9ZZ6DX@I)5^d7ce&sx%rWb;xrqlEuSP%OehZn(ZR8)fxXb0FC~q9~>I zK%k~B%&tjCqa64POKcMlbiyKwtzD=;p)e8hZSymRfA7)UZ2c7cX3=y41snbI?DaMEiiY^qPfy> zd~&rJ+3K*;?CY}sl$@pKDBIIB_}+-hMU`!heh$z2yp^93S#zazO7txZB&3u=ysEZ#Lo@#8HPX%Ye+*GMoIu`}-ZIigsjttuPdH1} z{ifJf zp_;E2=G(F20)Fd`2=Hqs76*L_DMiB?TaD9t=&&1RXy@K|X=N(u2>AjRo^lgTgfxEb zwo}dzO+5>Tql;wJbLfwUpP^jr_<$^7A;s?Xel9B}u43!6eweDc_r_P?;uED(>!4wZ z(stgU({zDvHDxork>bh2oBi_6Iw1&QcH>*mT!d93D_ZPWe?1V-D;&}oK@xl*x_Lx2m#lq(MNd3S02ED^_E7B zu8cF2c=ig`{%@l?1!Bx9INqSxDWn95@wX;lZ2Q6q^sj(&K^_3`%V=R3nD~xmm#hkT z2SANIVIQT=jCD3l9N|2}Jd^*j1a|D-I0{{CrvZ1KE#c$;@dDo@J%NMpheH_&$Zv}x!V1eCvR>cvx*c}3f`u1LI_+n$9s$}CJG~zrqPNA5ite0H8w=xw# zGCE^B-F)`WV28@ro?+nyvXE&^-gF0vLi83G*c`qo{ermGZfF@lBj$is(FKYOp% zKnpyFO##c$Ir(YV#c#Xmzo}yUAS97#fpX{!5dR+XgdKZjw!Lupu3K+{as5L6GB8eR zv4HN!sQ@|@4>D^RAvJnv%_AWnt_sgTaMSHpVRNHhpzBF2oW|SuIgVT(9KW%5j_)IF zr`LIGT10617XlfmrHOTq-DDfcCLnW8v{HaN|Ptn6r(*X6URb9*;P0X^FI9ccA) zwp$_%0hyOBJ9;)rpqUIbkJ_kAdDRL3H?bKSd1{yg=#8y*5oJ?}gG?ZFCvR@-y@!Dd zh$~c3s4*~X1wm0~_`+v6{>4~oqyP?BSoV=Ar*ewS(1JpXv`Hy>%l1@@q)DbcQKGKY zfV#InU{z}$)ng~nr}yr=naqt*(R@C<3 zrYeNwYgD(vjTvbyYkt8VihJ(<28Ku}Il=`6qfM_+ZFeP$%rp>3q~xs&-bS0ofbE89 z{8|@8Xg|@wOOGYw?c@8{d6cGc)x=!`boAC+_47P@d%FI|WRar$aeI$cH_Q$m%8RI% z+uwvfSHmA5t^1HS?>6KsN6?Wmhyue4@4YI=*yVfd{*Y9wtr;`i_I{8Nq-P3O*;yR9 zKwZlz+u(+^X*&;w@J{59hi&HcNJj+cpo!5Y4N8>`TP{H6PL)nEyrbx{&jqiuvOC4S z%uW;Qt?NGq4`|#3XK7-BOxdou-9UY-RPL_&SUkT%a{-IPY!>Z`nOKKGmD)!&Au4p3 z{Z9-v7H?^b5p;rDVP)&~$I@2niVIZz_3&_ROLFkxVjX%vG5|Ih`g>dzV^L7SQR$0+ z4H?<=gBVMyEPnY_7ai{~`kjZDY*5eqwi#zo2VV-&bK8UPq%EvjxKe6$G0ej3(^R?{ z$ee(Yk)9Xg{=OyQs>iK#!s|^3`W*3+pKQiJ|SODC-rM?BWZf z-{Cr4-|j^^ySu;Q5r8;Gp>p7~^*9J1|5_z3oZz}t;cx~Fk>=~HUUnUIS@S>CCogJ2 z!o07NeHH#_oK!%N@z}b?!AK=1hBaeou)%M1)e?cCytQB{+SOP64V}C>w?VU0Iy|(9 zx>sn6p3ApfAG*s&OITF$W<*Mnnoc&5n~I!BMwk^CpDF=HnfjsXh!XR3x=N6U_=LPw zaCoVah@iRi+D~QEjq;XVOtoecIKJzXGkTv}?xRzobJcy$vO(pk!%XrCcCNT5oATYc zR<};h(ForLteaZhDR)~`bTo7DD;?I(5s*hVkVRtTjWc zLftwwBE^{H3sPLH{uoZMeP$RF0CW73@>$ZwMg^XTpP5`fESei7mZ)Sa`;M%=v_M^^ zz!cZM&lBeVBe}ZaQxay5wi3y6^Xq!@UoWOXn_tDn_Lr;$VYV1WZB%|VzKqJe@vS$f z-&%Gf17MM#>x%L)BHW=Zz0VIk!V&Q<+1nmXnNxq6hZW)tT4ErpK}TR=`wO$p%G+4V zIujltd$mzpI4m9k5^Dd?bgpm?jxDe}KnO&dFtTAl%J<3mD>c2hqu^kLC4i*$t+-q{ zZ;MEK4MOo&TqqyJtSh6sun%((y$E}As3-MB{SEafp=O-EOyW!h8k=IF>}WF8f0G9J z^yTh%g=o$Um7I5Bq8FN#MScmkW>{Tuc1P@3uo+{00ATShetuWx^=`fh^Gca9-PJ=s zqAV(Vln-UkD{%e7v`~^c4tyfJ%#s30>}=d9Cad8EzlZxT*&;MMeKGTdWlH2?Ab22T zTTSs2M(#qWJ#xfzP6Ji2AOCt?z+=Li%&>HxF4Vts6C$pK5%wef2G&Gd=Z$Wk>3yp| z`PsgYMJm@bn+Wh=c>??()PcFYiQyeFzji54(SryDf4}b6YMIoR$bb^bOm(`Uxd(U7IGut=O;bcG47KZ_xbT`Io2kqH-^aim+=7t4O zvs=pKrOj&Mt+U$l_qSR2tF&*4uLSx`YZ%NKX(zJEC^bBS$wnHtfdW!BfNvQJ6xBje zi8d7^Uo<)+nu#%_mCmeDwNRFqE;RN^!(@i|k$@?b#}BgO1ojTkhofUvKzF1jxVDu+ z34j4F6d@nIAQv@EbA9=Nr>@hzadU0O^@Me6X!aJ{M`KBA#WGr|mvr>0lEwmfu*HmV zT3`4_(w+PyrQYee!U<{T2FF?EfOYm&{xa~Jui843b}nqh&VAu>h42TcMO*AmlK2~4 z1(x7}SUGWLlh68qsBIzNIp>7{bG2Z2%JFax2RpRLky|GJvN40pq|UM&ze}w}i9loa z9BWUkLBZeP$(u*Q69v$Zl!E8EH#-il4bKUgF>%Vy#(a!O1?mg(Huq<>ybow399b)_ zL(7K!h_6Guq1dkOrbAW|z7{q4&dvs@@L5M!x$*FL%*}E=pZWhJ<)>t~$y=}K{WvLi zOSm;LP2zrvUTbK!MqeutUls;wN6eumOKmRJsp@9EY4ISJ?-@U(rIj#OvM~I_m!NhI z%;tcm<^jI*#_)7kd&2c$`0IFqQ^NyQP{ZT9R`c5LkKExy6S$IvjmK7@Rb<;HIUAy zJb0B5d6QW3E6V$wug3BJ)mD$S()LH8=L$4TgcVwuMAkRD=10~54}q%~IqrpLCleMq zagpNml!nT=yp&23DR5y;SH=z`xSLI&l#X|2`;UlNPhr`wrox5ZVQa;|lZl%^w-NwT zoO8r4#@D+n4j2#2^cv8U#G5Jx8PcBZh*x>Rj@2LSUrWGjwFPq;(*JDruXaQ_&0$7dScUvMqj-Drt`}`!P1#6u6)eX0{DIHfq0M@@D~{Aohx61| z^EC7ndQ)x5=y141YHt?wFy_4%uylXR@Wme3<$+n`$S+9wpF247YkC}==Gq397YdwG z_8AG#>O0MTRja}F2lf;CC<>6xCwg-Or)&?xX8km8YUae~QM=(CjE)!oLVNkK1R}(d z>uqXWK>TM5xlXqO4b)hNp~s|*(=uP9glzFn;0T5h5Gunr!Ab1G&~>qOjLo^ZV@ut# z2ZKqR?gG16mjk%;OpV6Y09b!K`rK1=@X?K3jQEuwiCi2T;psADC+lD4n0pf(E4OFv zC|JgxDqfG2_GG;DrJ9LmHZs0mRent7OSnJi5c06e0ByQGE1MIXC5s7dr$<40C+^sq z@rzVobS#1))-dBBbVcE!MOut`dl@OhjHe!-9iwOJJsIq1Wi4S=7OqwDkdYQOqp%p3 zVx)v^JCiS#MV1oK4dn6+iO22ipRDZQE~vm%Z5Gfvy*=??YLGV3(;GCGoT`&> zwLm`_(%f~^E}Nl_wf_dr4=u$@Hxx88y!Cx8eOVtm{nFFY663RdQ}z0u-mG%)9AM9wg!Ubk9)%JP!Ms2a(Y?^?iQ(mQ4y?2*SL*I7$?=|?_*rJrya&0 zBD-n5WRm9v8gdwH2GEMH2f#ucl4x_5)X#|XUF-paI?`Re z$VR?n76-09gP0QGz)JVb!)$*YVx46OQ5TcK#Z*i&BQ@5GxoD;J38y0Pa>df4aD9F! z=&_z5>X2sE?sOTOeXNI+6Y-1Wjhf7h3BP8O_ZV|SbuK5V$K0~oO0}mT}j%*372sR?>3H?V-64bv%}}|doTweJVD%5JM!(GcZn)sZ0R$GBA12f=^03WT@ktv==A3Uy&a+&^4m&pR3m zplLxl$?W7_$_^Wg`Gw+Fm}pgGqAj{r|A2 zI?)}M1X<#FVzp+G27;)&zxoEqF2(gGJ3qo1eD(D9?JY3*L*VU5G5!ec5jObxT5cVU zLG0Kwo1UJ&%uu{#RP4b+XrZXb60^&oT*ur@$nMe0FU*$ew7NoN0zjR>x^nGRgL!}Q z;piS(;;}?J;m_JIMTjyQ{){XNA`C-++CQTyCQ)B{^OD{`&Jbxld`kbif@p{utV8TPKvf) z>Qc(70`V*Dl?MC1NL)ABYB8>k$CkI84K2OPdo}T0y*ii+zR(Kdlm7Rbus!)R@EfTH zpb#kzq3UutGC)46B&0dPe#&m%^b(uHKg{xowLLi2b7Xvf)GAhcErt z=l_LHen7RqSG)GVx>qeb1;7-{-?7M-{{AZB_8UF-Rln-(9e4g3I#&5r3)0nQ+>15L zzXQh5q~`ZP&Dhm&dz;NQQ6;z+mfj15k1_$xs7?Ug<~#RoK{-Yu*fsC%$6abTl<)lX!nB^%HLTOC1wr?$o$>8 z?Z(}Gd9<~HO5F5(iRkTpYa^4kzR>lUQ0J_Lq|-)N5MQxTv$yS$;*#f#I*8c>Q`6n_ zLk~}6K4O{8@Is*04yIMrx`FDxkz4%_&6*tXvti9F$o&1pHjgV&y6uolqc`#`RLm5p1R~hK6U>Q zj&wCI*wAJi35d6s%Qp3H>N}!;N4-O*V^oiSDJ#DGmYRgU^ppLZjC;iFBXuyH)^ zQsBii4)#`8GS8}?`WJd>s~-LB`qq2lysw)RLZV!V{2k1SOMmS>G1;FG32m1$R?e62 z&h*=)r4>vvVyePB-Qr8_@rFDjcPFPG`_?U1zis*Z`e+FgJrpgjm7I0GZj^VJI>Yex zUO7+%<}C#^H|=&#@4R}ph&PmNDq)q?K%q~s96bBdE;-J#6I=7`F--t0#xvd zPkMTc8oJee=l83uBCX*S-?Brr`niAh!TGg1Xwit~{W<>Ao$#Genn-N~b@?a{grWg| z+wn-5TO!J{h5()3G5TNO$Nca7SzzUXZjN6A&e7&h;qvZ)7jJjRdV-Fp^Hli@f%c`> z>?Pp=A7<3keMGmL*HQ0PhB0qcmwzixZBj@7tr$K92{upml!uLOJ)Lu7E9&GZl2CfL z;gEJJT6AQw4Nn1JW6ke4jQ7Tl?@LkVRu$(={=5yZWI9z6zrWEo^VpZxaniq7oC)I2bCS?rM~xt_Sx6Hhl8zty)@nm#$F@?9PI zq(b4Bd<<)dXYkmrb?=Jlg0}%!Jv&ArpfkO9h)2T_Gaq9Ue??#a9VXPDmLz#9uFb69 ziw8rDB7>_+m-AOsgmEdcH!lCr5dQ{2b}H7dZGUfy-!QgHhppk-Eba3))by9>{1v}e z+uDZ-B>m-Fp$Pl(-p1~sm9Q3!M>`t_>}D4X*4LtF`JxT@PwcNa`{gIXXI@`ivHQm- z#_FrE1(D@e+dKark0tdSe6sz^wV&9fU*HHya5{*D9HvOOK-ol7WueyW15K4-#{M1J zfWIof&?oOAe;U=%ldP^-^dUyHYJ4YGA+yu_c6GbzhTO)XrO&IUpxSN0KQ`t&lgW~q zgg;^h8=tP5))#libi_ro9$kw+cYCm0K-yXaPgvw*5C5|{!YA%lsN0g-tOGX-)xvXf z{9Z;|&ovf%9dH`(pD&ZWXyrv?%mEx#tbl&InvUqty|O;PvE%=Xf(LmzR&f|X?ocM&8Q_^QYI%Uk0entLg zV|u18+Jc=*@RSZ2)kM#-+TWMz#CI-D+v|_}lrM;|MLQxW852!CWDy+45qvAz-+m8Cw z$*G-UMoi!Sc6n6GS-OFp@s0ZR527NSZq((`zxkf*URs~wk*40~iM-I+(6K+Y@4!Po z%7<|G3o>6ZG!-<)H04iY&-+Bk#Cp{ryod%-n{tjkgZ7u!c66}~-e{oAZ8q-1n}R#G zdHNlw=$d&_R+YBHuD|-yJiJ&W`RI1z+^bz5e9oEmR_Elg3S*ww9s?m|3={cq46K53 z?#h|Dl5vVtXvv$3+oh$!!8}9$>5a=E4J-{;ts1k^1{Ad50n?bwz)RDBE zMrf0XIDSRBk<^87A*I8+`Q^V562f7U`|4fHPT@|HNCOV5=@p4x%O^is4h$S~@R!ZK zh8!698ZKxquV95Fb`UT{q7CY)3XeT|wpPN`cmoJADDw-?KD=<8uag}v^nFG|gr1~# zcMeCqwL@P}Su4WKkW!1E4n!Y6dFWzbdM4u0xPFFe_~2hIpX|X$>M95e-?_ct^Y#-# znm3OdIU1K%D4%Cbc^0~6xq5&kE^vvqxOeyG5M4L+cy8o`mUkJPX}jd%a9-~8DL=xn zZ}CP>>C=x*@SV6UZ5Om*0^NRu6v{SCsOi)$@4#0t zJ8Vu;Hftp;eEf5&GwxESJB~1bkLO#}C)__-_uHm#x>4H_{$__R#b*9W=uw#aS@HJo zQ>A`kUhi-Al=NPzeZS38_x)M;Yvs_M`_C@x1zi*({Vc2rV{IEUuknUg{g^RqFDtSQ zBm&`8#8L&$-@8*jc-ucoAAIonW!0%a|7`Jb8wwr#7b-hr*l%kL-#zY4aBW|Xz|Ov#dRto!%xRu7|<|Bl|Ghiz7qSKvEFEBY^Z zr3F#$ojA5PdSgOFr>;*1XFDTg818B0-fCu)x@}RxnewKG;btf9YP@K3KmBM^WW7Ur zCDQghK^PtOL=v=nctSCxO3}C@t&Y?7yy15{O9CY7UHMHx0n(!Kh@agv-@Q~0Ah%K) zFpK;OnSbh6c}HdCgy7T{leg_TrMyk8ihrg4<)PnMf(oPk!hcLeog0~@^r$RB|1uMC z=JQui+uc<-6uW4Rsi$ahe{`WvTjBoi$K*xn9cw>wk{GhRNs6Y%G+MNxTe55LDcjcv z$RVaN1j*@Hfzh*VmcyZ~@}zb5_;#nH*3hnr7X*uF6sK_Q$>^W&Jt-t?b3w}afNR`U zr(JGzl91%sX%lzLyh<259-2E6Pu{6z6L8lk{+PeI6DH!b9iL9q`$J9R7KrkFvpFlG zR7H!8(%#4^XbUmx8+8+dP5#v6BAEzSN)Ft0-&-A2zr$*${veQUVq zPd@G$p^4Nn_1L@l`h<{8p(fZ~xeVpn8~?FOU!nKrNexq^87P-)N*|USlFc;H_>vIX zEPhWRSpL@VI#IfJ2hv^`i)|?ntW&rvJUiry_~|K?@X>3}4eVMT?b~Y7*=y$WMs4d1 zqDZsPBdGM!SgGwH-b3w>sA=y5Q|S{ZCkN(r55n{=_czEb7Kzzm3p@+t*URM)DHIp zd5xxNS%*bhD6i`*Yv$JyUyXFqGGzU>sl%1J zsqVbI5j_{<$`E{N4ELYfL)QoO>G?5SBh-?j^5=l72Xv!M6RCUElzlmqX_7xfNUIY&MqbfXrB$koH9#Q{SX88qER?3eGL=->wz^p%&1y#Z9aa zUS09U#JR*MjRpY2#%S3V5JexN;s-=D?A7z#-JWEN>oiR*9|@Cek1& zJ2!lm!%li95#z<+Ppp+5OPxo?XTF(mt+*rqg)tm)NbS$8K0AD>I`)HVf&C|?%}?l7 zF6L|bw6L+BytMz-DdFAR^b!62y*Tzj<|FN0Cob$$_ofq|tMeZ{s@2N(DsY#pMsB{p z{PQA=(cRA{8}l_va~1``lAS0=LDxdm?{hav#IWradqBe9Xs~eN!&OP5>ZoSVu)z|~I zE^s}=hs85x_YYQhY7|XmSlEPo2=gM~o|n;=F4dFm7J+uvVb7hjoX9on%z6T3LXW`C_v8;{eU{yG1m zjYKEF+aCu$kp|ySjg)@BI0gq*1u4^V(WVGnvYIHKfG>3zk;_KxAi*# z(N4-1y`fac-gukavomt8>{hJmG&{RxxUZ(5-Z4k}R@`Aw3ykF{SwuMS9L28%nb%N- zdZoyyg&o@5*C~vvV^RmtMX=(Sex`JaV^9aw-934}k`9%rZdoLqO}u0u3?_{lfL7o^ z6{yfxR@@4pW!uX)5$&&`!U}upj|U)i`#9fTUT=h=_s}r_#(;b({ixO_=(ZzH!`Jeu zpG}n*;h!PnZg1}sz);klzic~l{J$whijDcANOF|tblA8jd#%{hJ1)r-Eq()FK=n>X zSoSG55Dx3+ZVaoqd(7Aj!BBS;yd1Kv3xsuwB}Z8`TrL5uLG)V6ne8?R@o}}2-qZy1 za1NZI9PM`^mm8=57X$3RaW1p~2_pR!-*7mr9M=HS(6wbdVnUV#WR4 z@{^w$jh}3rPx(F60w$_gP5BEQz4I5!dT^|##zUB&5;Xm!{-3^0d+u)OC(9eN zO85mK-|LsGWjf%m! z%q57*dKzk9-RQO)QW^)zg@n(U?olw>;`GRrOKW*v6P0yIlj}L_levcIN{diYM zQ%JfcxUx}>@zua`p8U3NW7aS)S0YBS7R z6*ybWZOkT_5Vug?x0#tWCUr7v1v*uDjDmD*?bmknm51R9>&G3e_kFZkLR>F2sE+e!`h>0|J>=~-rS6ZgOKzChN)LW;9pqjaQd8`yFmS=mk%B^ zeAf%B+$89D9U|N!TJeUn(Gg!#QMsN@QLX*$Uj*?3C}8;&-@3OwJplp25Q%y;%yb*e z=UCdJjXFS)_Sey_^@Yt9Vl$}C3}sQe%jO2lZB*7}#~cdE8*JUx$bWLgmdT1@hL{N? z$7;agqzh3TJs22T8%)BLepEx`dYNC9Ne{N^1Ie~|2ut?+oEPM6e#)>mMdzZ62q-Kc z!D>(`MdB-PmGc}~1yyCI6Rf8soH`Ae!1BgRdy_Aj1=Jmj&;rOAVBBY^@^|U`yi#&=1fjw zP-!R^J@*l}xxoivl|bKxBjE{kfdAC07f!dTlqS0 zO1;7^nm+>oPCijumK6;-rU!5Z1HvEz0if1Q!v`P6x5cr`Ia^W{ zeQIwHkF66+WkL#^e3Cw%P9NcubeAj7&9*;zb*=gq6o*(nOxL3Bs$)$svS~lqrU!pN z{k(vN8gtPfz9JVT9KM?O*LCzsEfYgq^gP&cZwV`%dW413Tq zW8`GS%);hw!e*c{F8zn?Owt*EraM<%?<;txB&ffS;#Y7u^1COGH(OcP2>=e#zZ(=ER`_BRKN=uhnGZT@*ygHU$2sO&b3~0*q^`Z$KTq$YE}ssON5NVY8ho+}aj> zk^UR9VbA_#aT9TaK-G=6MDyyE|ec|e? zDxr6VHN;7fwju(V{Wn0_;itjR7NIrb95WbciL=j_Y2NGO3q_h9dn@6!o?A!tDq#sy zD8T~u5jx~5`y?S|JLu-j&bGM0C@@@iuC?QE-nGHM$I|}8x7!Fc&XV?9Ia>?kLA3!> zC-k-|&KSy@yH+B8HWK8oyZZ?lv+S6d5_{<{;|`!8%-jiMs7|D%gC(zBf2)m|nrLm| zQ7&^e8q}pAOQ*A_8K?VQOs^gKgMP8i<1dk9vgbw}h*yGYmQ@nfk6o>UBc2{zv$%;*Znuw$tuIaM(C@9 zr)rN0I6yKD_fkw(Xv(fK%0c2(_5Zt+kC1U-FpLK*&=Q-@KIJM6bLZ7tic!2MDPIR% z>Cw)4c({V73~Z&@Q)FB(BZQus6SVs4r zqKZGr5LjLd(66rW4fY7=Q)W2Q&ng@YFwE^M$XjX_($ z+B=y1P_0$N7GqP6Ry=|ObPr*}tzK~s!_215k&>X@sU{idI-WWhuC(Wk+^9z#xq)C^ z&X5uyRf6olkg7_p(Ouz8&60$?1x$FMMUWOc#qmqz$(x7<*sy)SoS0!|0b$1y8^Jop%%)YQ+^v-W*)%TgRKIeb@EpG}t`1AYLs6RtJOh4(z<2Ifu- zBX7*Z!h`}u7vtI94Ie|SpXh-cV* zQE@N!+0P-{Wr@@-x4x8lmC6U~dQv0fREaj7LtGl&-L{M(joPf~!ud?4N(G-XzYS{{0ag8V(WGMASz>J26a%`K{y$FJBL5VRr%@}NFWHn|2LUm00FNc z95`v2RJ_2EP!#Vly@(&t>_E z*m8$zR<{_Tt`tC8W_@{TxbT6S$q1+ORgy;jQh0v<-Sg`2%|oc8msE_>S&nj$Meq;P zu$8bixr0OLm;Z&Ty9f&<@>VW{R~Eijp(a-oj-fhNNWqO^q6~tNcJ0Bzf0N z^faB?ll@@_*V~bx#y{gt3C~)fBWwU`G6Q;-Eq@|0iHDD84v2eFORQV`=46?1imU)P ztuO+#;@?~GEniz+KYzc>bXR;ga57XIsma?QZ3c2k=V-8#_q6?{8&`Z)29P#J(V{|- ze@wf3ayizO@0!LOj0ei(ZCqxQQe*Ia42G5_Io_Yc3GQXhCWoIwWr!m7Zd#5rXX$@b z+_mc^#XOqkD**xUNxZMJa0U_tB2Ad;KgVTnV9yw?DQ{(yrAq+B*s(}fo*$JbeuVbA zARwfWRiAc$Ye96XrS*V&Q5P z#J9@fFaOA`_~e?T^nwd1+xxc#nXt!7W5 zSf>tRG`2qehCX$%_BstYm}!jFQ;dy^wFa$X)G}R5&X;NK6YUJ6yCtsK);itGj`egg zx;E(5Z!^%zyqYwV9~skRxo<#eT)j#D%WF@mXqlfe0(JRJnXmsk^~G@NK?DLw2OU&z5;*gOO`dxg6y5a8!X<4RoecHnt8j z(dScxg-K@fAC)8UIwR^-@aA*PiS`qz!6NH{pqSjG71|dQqgP{N^=rOvBU7DqFPzGY znpe>nhL^_+l_NBkIGaw1AJv1pS?y8$UTZjh0Ww=OUb2xiWiEq_OXP&mR06;^sveK&w@eN*dTpAgWAC;MT1s0jC zOoP_|f9St9SJ0P739eEe$gxm_4x8u34rF|i`7SbO9G4%QD)RG(f+UMKTlm4|E<5FH z2>p$pAuU2rOE)$5NKeMAYmB(JElgo}VOa}vX|+mJWPjKVX^Z}~=8ruCok(jEbue=` zN>3!VNhM5zR>Vfe^&x9Dm+zREzGzf|1=UY(X%3hdwShzWCOol^HC1?^d7@j&9qUS_ zO%SyFM+CumP<5C!=|YHUoMmhnl$}IC*NfOBeYo84yd?X-gn%!MAd(49CJKATLCAj2zK2&a-lHQ^ND<&hS^7bdh{LjGGY?6ABktaTLF<$ zh)0gF#=6g@&q(*BHpU%Kl!3Dbij^Ngj%&u~l}747Vl;Z={5_5~#SnoBliJ9~RVRrh zl6elq&;<&*`TPdRoDudBw};w1#8g2YaU4FN@!Tr^D!3zXpZEzgepmA45=FA>D1k>T zmZRQP>*vMP6rVR?Fygs&oKNOVCCz?>lhb9#Gsla+OFJHzWY2^r)y>I2T)YX+IzD+b zWLf6S-BwG_=l8GpGVAFrue}p&(SR}CAKYf%h5vGhDu&S z9!6ZWYPFG(qngN!j?;%i#D!5-oj3oA84pqeMUKn0D*pV2rz-`msldZCMQZ^vjvQEd zrH&e5VZ~Kt$GD+U-#o~-@1JJq=Z=hhG=}4b(Hj_0AL&Ekk+R}=zDmx+^fZ7h#GFq> zejmku)}0e+`PdLRh&kR5XkAY=ThEsvUDL~!kyp?_+V08N{M`n@wCNB4mqJG;e1JOh}7A(3@@ggR_{AxSVNeTI3_Jwyz{b zVnk{S8oF9i*iCIelxq(i+b{!Cir+teVAKDPp_Qi#WE|hY&S714&Z_{ru`IrssJ6C1 zKfRkFHj^G@2-8?)PL~N9)VZMRu@aY}h24b!2Pd(3^HCMLI3hSpta7{hkpcG?>FFM$ zQ&)8~2=W=T{0gmTXA5}>#nE^pPLXVf-ks2(CLLtL+_^w;} zc{)q1jzR>dfOMlT7MmoW2=$>Z^tN`?i{6v0?M;S*{)O%aKpL;4cJ{&$Lm=ux>V25M z;=|(6A$d37S~bm1jKRpUjG~!^9 zrF^w7at^o{gQM!W0u8+*s>-1Wh))*203xqKvG4=^!w+^oY*kRr3uoE8d&iz9bgLHm zI0QYK!85sGKj_+`B_vtR411tU^L3k}IbEK#(h19EBD&gKtwol|T8DK5W9v1aH))Mv zjQ-RHp>PCi-IJ&FI@(&KHQk1~e9uS!3A)t+6duFd5C}9{w3h7r9mewXMja;B=w)NP z6XWT`l4YKwIjWtmO3=Qeipyq=9Oq4DhDtvYcASLcy5|d!d@)8;>i~GjxDY#M)gm}T z;@}S7B~Rc^F1eom8+$;Vb?(Yk!3qU5kYmqn2v2|TS-=Kg7tjx!=uGk@6JEGOWHqJ-Ld(2E2KzT0a6B^qY2?aP7VtGCFeie zh8XK{f*}`p+iau2vNMiaDg2Qw57VcBI3atPQHqEW_tN&VdpETaO<4P7z1#!V}l_4$(5-cu+?ClMLd(=zLa z{J#OFhtKnPb~M)7$xQL63mz~}V@j}ho46aNtU#06!X==K{IMON9Vt65n<&^7DH|rw zH1Z&#LX#o$ZK&p&8qyhBN*>bCHI>9yE3T7;@#XI^b2gzhYk{i{A7620rM3g)p9rbh zOd54LMo(HXxnLOvdehxZN|hFEUTO_I#t3I5wSysa&B$BO7R3W(h(y*em4u9D`SfJT zB&K)tGC^l_kH#p*P}}0{6|l}kg3iHWO0|t+-0esCf&qw*IQ*VHP=hBc-9aH<5Ekb0 zTiqbq6rS8TteKs}Ljm-(H)zlKph+&JV+H-ZQ_4&WP$=0dhDV1@9_R9Po|{c3NA~1z zPfzM0V~aU*+S{LRT)aPvR8M&a8&s)&*J>xKMH4uNN|kAJyd+&hM(j(IcD&aU{p5X- zem*GA?UqM5)7-SS^dH3mE&4V_FjvHA+m2g`&C!F)AW?6qD{k~8-h3-UD~uzbJt1NZ z2^`MnynXYvd9p@SIx$A?$-5i-X0q4vR$S>m<1RifGB~6 zlZgo=L4g)&e_t#HBI1v4o>5lL_C4nZDrpgnEzdW&3Yx*=( z2lil+vD$#u0-j~)XV{ouh;#x%}hp!)#Ds`>^VoWml+4pVEoat z(`=G`fai?c3?+(h?>Q{0C8NNd$WBiapovtn{DN{g;QgOb-ArE+R}=<_m7O%6n}^!N zLW+y7pqoIVGxSrPtdl*R?JX{{ciKw`#c9+5mTX7YH>SciT@BlowrS~@<7lL8P}4cD z0N8XTR-fXeIe3QZEl)uaJqqIr4yh~gHRpF1TW(F`tH5?N;NRTY#|d_UVLTL{|8sY8 zr&|#AP(=E!?(q-4m$ZE4tCX(1Vi~?%s5>$EK=eM&}4t(JI1lmt4YH_LDN74tC_hJI#mht3?i-FpT7x z{6C7$J)WumkK<>CNumoi857E_M2fl0P$3Dqc2U%n5;Ej6Y(r97bIG;l_H`L5m&z@- zA?8vhl*)-buu{nGFJ{`2tg;Bn55&-r}buh;AOB1>47PnKC78H&oxdZKkH^M?tH zN{4)_j6~g}4m1SkRSuY`8u`J#mXUxqBXEYMwAcfZHRNh0&`NuE z#a6g$;%%?S+v$fGf*X)op=(Z%pZB8KPcu4&mmP0%z)@i5yNVIZuWimyUqv!y%(c7R zFFWM8g>pm!d2`9eDb4I#p|T*NP#XN72agyP+B)p&eVs#1>(}9Jfh%+_!?K}U;2AhT z0*a}==4*Io^aE+%I{zg0-m`wjUFzY@dBqY*fVm+>Mc`X%x6>WgV&-It zki%`IX{qOYhP6Szg?vZ6KN#-b%-wM6tY}Or5@%|XSpMzwm29!^dL~m8e@ZZStMzOa z)w0QDg<(is-mu@I=dY0RvaGxr`DVHrzf2=XUgQCE(AWr^Rw#5FhLuiq>tBW^Cy$bb z(_m;byu);M994`B0RGD>?0o%GIznPP)hC!|DSF_L_OU?I>f`HY@$4*u`FiU`!>HTq zu=|2kvN&=!F0;B9O%fxe^FCJc;>6zEAt(sVVx69pN-sHxR!Lyw?fBVQI zx8QEoz&x&&C9C!f_AupZH0N)C+*tJSu6@nbN+(AdIjus6Q&JKxYG9dPvZXrK%XvGJ ztdABhLhUEIRKdi0=f-6ZH5IF{R)}k%Jk>b$=j)5s z@|ScLsOMDrWZ?$iRq44hD4_V@s6APwh=Uqfa4E0vcQg&A`}snV_Jf4ekSZBWN}Ob^ zF_(eBZ>voXXfhSFy?0C7C;w$wehvJ5Us~|OM=@~;L#*r`{j0=BamiBGZw;eH`GxM< zW>_(`?yJVovh@#xZjL7U7Wp5@Zr(n-#Ydd*TDO#jM!o>!ZU`}n&a7zE`YFI5cqcJG3zqTv(~SUr39cYfC+^m|V=7om&*fcf^d4@y z^Bj?tN>1PzOD8r-2RSArn?IV#GS#;mbw>E2BZcDn;VA`0kZ=UEai70Ys|;f&0FT*HWXY;#%J#Tcd5K8H4(?On%BQw&E8Wx zmvG_u)u&3{Mq|-IDIfBP5&>h1^6=zm|A2c^d%#8HqX@qgwS)<4uh&ILcnvr~2y?%$ zWIauT_nKZ5S`TDPGy3{38~T-ZPJuj#5j>WXd{?1S2fyO#5-5dQoFdj;{q)$dQfp9L z`((Ig*Nbb(tR3mIPD*>mhHc_8Gw+?h`~!prqkTW`DO=#5+&Led zjQqs3evOV{ocjl0uN1=ky93!hDy2rB47{hHN0RY!w5?b^Qf}`j9q@SdTkD|@j9-dL zH%}Vh*o($H+9H^Bph>t4GvV0WvQ}DhC485?D|q87UcFq<;0IA=cCS~T+0@!Rv8Pcq z+iXXMMGZftzEHbT@fj)k@O9x*n^A7ygPx`>52c-hVNK;>Po_g!LsRJoc3u`DuS)LK zcYbmz`Nd1BPdDt^>d7Jg-Am{AU#5woyf)C#NgYJ~Lf%@-N!{5S?ub54+csa{dh`3u z!ao4+ohP6_>Qc3Ho?e=_cH|#CaA27gyFTU=hb(V+ahS5_YbTNZqKU!Xdehk) zcJaF$MRCH&CgMu158E$dZ6S8t=wzXsU_EAp#b|iYldUK!Ik&SH9UbxyXdQ_Y^wf&z z>)INO-AD@dXiJDJ&q13C!L}!o75iR&P+`@i%|B1rVh+4|vi~6JTN!RKVb z1z;4HnO5?~Qp?8oMBDsZVUd}|6{#+>|17F1McTBpdg5Bn)aU;Cx$+bJ^V%E(mKhqC zk5BrA`?CD?bbZ0=5BHCopxU%v_EFI4PZs3z+^ZK){1)*oZr0SQek7Mny!Jg)rs`bQ zUE}Rxz9W>?TesCd;Eek#ACvlJ0`Inpw48ZtjlJ7E-m3QA%8^kdh7sjwsBMIjPdDnG zCDom*a-DKX-BPTKjlU>H&(aPQNEBrkn3T}Yrx?hj@us#%>^=x}{DI>gtmGZOpGeNf zMy*!4Ba>r#%bsfO>Ad2OmHYlmN_O^Qze#8Fizhud#06G-}wGtVt< zFZQUb3wQVWFRmE16<_~wu|dIPUov#f7>dRuKeT!O^<9a644KN2zO%gHbSLQsR`YLo zw(gObBjLeJj3vG1cIu>%>f!Ja{{c$P-wmh9uYeeKM*+oDGdILzhs*9H+>TH5W8v0p zp{{;YQ$m3Y)nqo>GxIyjwKfq)$tGrXek5F~whj`|Un&03sc35}jyWz0jK*Ayv+a!r z-?(3Y->M4QJ&5;scbDsIcYpY`g^~#lek3S-1RM*+Sn|S7OP#JvujC!~wOMmMTF81> zm*RWM>UGUHLcCwz;CZ++@A>Z!|4m7y6|sZ*Dj!IFuKM&G_VVfLD!mb{tDnN&e-V|p z^1uP%-^ilhqdMQmDRIy?UJ)C2tIUM0bG!^k7xu8;AA(9_ET6zRPYnd8%3{OKLXeiM zM2kC-r*8PAv*qgF7#>PsTq@Lc3t;4H9XwvjuChC3zoZ?2YFaHinmN>>>E;}nEgqO@ z;21J^ad%tZNoncn>lJP_2^SGwtPb@yVcaWV*u3fj;;-^ouO+MN$sMM-0Nxxh&^nu|sLpIxm;!yfocY!T-5GH5@7t#Cf z68_q$*i-rf#!b?*2BPQBbtX(c`FV5%8QeS`O0?|Cx+hbk1bI=v1ZL0+eg!xA(b-Cr z77%$6@zl*>@_mfa&$YMd#e+3>1V2%K4T~w&25C6U^R~+EcJDgq{4sUa-rWa2UTV|* z;a9?ssXI0B7!ua6IuRm;1pWC(eyz_XaxbXc5{noQ< zrf;=BKGZ|6?KtM7S4~_r@IHTZ={e~|U+S_r_=EvQDBjKb&%ZHkCJA`+Y$sTKNZCp?%GDEc(Skig+tlVw@l6ag2(+l^K?3P zHzvNlQU#DtA;MMv77L|cdN0f(nIJ={ILc^YuX6AiCci-AS*^i`zWW%OrAB1y-QEgm zssU@lxA=33#JI3Ff5U0&Z_LBPBfFjL3bzhUH{R5b{SnoA_)4-uO!9FU5@b4}l*qUn zN(XI;B^8&aRyc-`Zh&#DSnYQhv;6m=mB6ea(gpZc*5pr29jb`~i){ahWoBDta$CuF7$`EmUoE!W4B6Lkt*0} zo0;BH6U5Tz!lI8xHr6ooOm?W?hcBnHy}}siofnsPr;VG3I3K~Snn_%9k~W`}^UA7? zN|B*h3j^bu9=!$6EuElpx1XR?G(}L{R{^h{Y-Od%8+?*Tt<<{aWmsUUOuK4JAMYIcOY_&9&TY{* z2N7c9U?l4Ym&Kphk%hl@Z*QE@{|7XZ5A1}i*DUN``W^oJAK=^pdQO^4+pY~xu6Hx! z_XoRar7)^IWeBiNVM#G@JOy*vCb_{*axyA@^a&>894pUaDe`l&Gy+eK%jQm>zb5V0 zCKVYKEn6!dvVBhrqxg4r>OI{X9d{Y*gLZtVttJIEtKVJ2iZnQ!aoF_tgv=L*W-lQ8 zC((s(G${&1MTY&%p+IC&aIT|IbDeihkdR@->eXx>6jRBvZ zQr5<+tQ~w0?8RC%WK4R54`G_7?LQ@p3lMuBuilU>@0r>GBYnZTRY9Z%Ke zdK6$zcGnRdk5nNw1tck5R0(UUbH(E|33aI&#@Qy3+$g#kJ`ZIKWx#uU}q{b0%am$n2~z-Kw;p%L-YwXTJ zT&te7(j8IAVPbQ}{OnuZJ_{mvJOZyBI;KlE~9;JJp*1$0B~k1rjJ zl$FoMuoCC4rsZNxRR!(!{BFynlJkwR$9IF_Hp4MLDza;_7 z2O1y*^PYWKZS^V!y<}%I|E{wVDh!&=4l(aODt|LX)hMurgiBy z&<254SfKRKLS`4#Uy>gQkQ8SkxEsB`_}&#!Jxu58KQI(O8)tXzdqu0bdO%A-v(V5e*4p(qU&Zet~iAm1f=(*PRMeqd$m8 zOq$fGm#plWh@Ku;$oya51t>e`F=x48>%QyB3yJnydowZh$*kDaiDB?4U<_V3-3BC- zW7;e}zjDO{k+)&4y&q>`Ei=-?+!U3ouOpa7%>^)mrO>{T(UEvUHSh9&KApbs_VI{6 zRH)NIt&EYkFGvo4)yU7V3Qux}LT94$9A`J<%o2=u0J2F)SBv`WcXHgAzOBxk@#^~c zo_&HT$9}c`VI|t`A4n)NzA=}%MIk18$E-cgY7S%P?tjl$gK(6#$9zb?>P6dmIOS3A zHK%T)ELZN$pj_nG$2%nYh?(yN?#-Cnet)ccvd71lp_wq~nE{7R*njs;Bn?G14~brX za-$B5TBl&t_>IwiX${ANuQ@?IJ=Lq^#Tht%@fddOi{3k99)!Y~y$5!t=dWU%?-GyD+yytzTc%kw#oLN4t zKGYyzvQ0FpyNN%{wPiNsvZx~E(?8L*{3up{4&beR8~3*R2G)SuS` z)n9(G7e&ngnF9uI-A{!Xe7KeL`K89Uexof=c${^;Z#6%OAfXJMrRFm&^5%{8Sdu~D ztE0Ai*Y<;QAB+3uXIT{Ww$RMT!Lw5w#W(xnJa0xVfLdC771IB=;J(azcci<-ew>v( zAbb~&aphVE8ayGaW^-e`)F9YFhxa}P;PWL46bDOlU#{DBvCy@)A%3ul%>FoelQ!I# ztd_Bq%Zo|z=PW6QB4>8oW&6xs?W>BtIjratR7x93=`uw>kdqGyVXc}jstQjmJ)*av zRrUS36cw=2meGmcqx-;HnIa52qG^jVfgya!^kIqwZFHjtifUfyfL3|Bgw;O5dr;Jl zlS^=v=G@V&)OmjPu5N)jB@I2g;dhVY*58%{ITWFbnXjWQT~|FKxPKlPt0s4HD8_WA zWlX6LRl@S4nYb}9DehUTBGJSIJL7$>Llw6c)*K#0!ic{ZG*BnWg9$=dwDpw&_i+yp zSU3O{scM3D{N+&W)`Atf{2vh3*X1YaPcB2ltdr>C;abceB$=K{69BM5=IiJ=*f%1c@dQ>O?qyH+G? z1+FvBfyRh^|2K@piG49{Q3YYDuzKL!0vV`QLNXDzGvKDyJ2A2g5qO3|? z&)?WIxv4c!4YIQ!Y2%D7dFqBoDc9n%Z%D@+ky-XD(?sTd3nhHlKS18zXdX(*&Ea$7 zroa})>kwr%i*e52hTZ$BubKW#Ymr%1dO(=3ku4r~X*7u!X+35tu?BigvAaHc84XmfS7syqpPT(@beFx> zT8q8!C#*b0+6CEhQ#N;RLV0QZ8M9g3DY^qk^j)ycldIRswBWbunW`AS zhm!ECNSlSc-4zyG64+P#4~PNDGAfR0xd3~LE^CzZqZ6y4i5doz1ltbPBYzq-Y-}ZH ziv=g;$!_lxm=KF)&=H&;2*x@eBg8cHL4ocvTXc(3dn)uF;1U}W=(l(d8VDBQ#dXQ` z_XZlZs&$a8C;l(Q9qBfa7S)y8-pR6zHnU!(uYZ`<1dE@Na}B8qB?1dCU-H_*i^f8K zBRB)dY>c(K=H7kP!tG3}?a}%oVO`)wH&{JURS)(7CxRs`+hex|L+#%9X;X+`#;|JR z7wPb(F$y)wXFr@c`^J}!_kb-Ilp2#DDNXP{ySOjA?^m0=?2jUgr|~5r3Oq~znL|eO z>g@V|8Yy&(p96n*xqzmLl-ZY*CtL`~}{ZkB)D>$%s z8uHy5V#Hq&`cPp5hc#$}QHaCw@2X4mxI7BGYQpMBtVd&og~K>J4)q7st%@4nrPsub z1s=k3hU;+Oh@ztJr|@iPI%hFkMUTHMi@|vAV&4-?kp;(xwgO?*GM^4m#ll+3L6+WK zgB$(>ndw{lIBTTVCXHrhNG4hu*)OR!d5LA>_#nvm8GH^xqO;-Pgez}9A(u+b{H_e& zO(x;RkVy{b{0=~smRGVNe!11hwQJG$9kxf)P&bVlJIQ3iLM0`$8m;;|(hcN8XM$xa z#s|U}f#~u~?b_H#>&DRAnoZKoJ~-F>h#V&UbuRM!w3?&rA>S#7um)P$O14OC)=F^a zyyS8oMm-S)PS_@6MLM_%Tyg+=@z+ZOmYRv5RwgyhXT(;3oX~`b%QwA&ueP5i{lprm4RA2TvmwFg70$i=YLu7yvbCkv?4c? zm=BX~o1NEUvA8CODMAql;Z-Q|3A%{>Mia}hNd*L&5zQ^N4#nRl9e4nI2D_!2_+ZbsOGNE}QFAJJ!pxio)^{h3i;20} zLP^K9BH{)TteT^Kdow#>G;97;2SaB5lz~Gi3HrcCx*Ls-=_N^011A$0mt!BeMRjYo zP$GzJ8871<{mJ}-5`5uieFPXojJ7~A>@)S+RMX(&*m4HKAs?p49sB=~v*_LG?oEI2 z^$|8_750`f2;_nd_41|=yUX}eL@7-Gv~t%W5)+jYW4s zn5$3F?+rF@zv|2evJVVOEcGT>a_-ZCMUfeP{?TezyI{GPzMk8p!#CYD&9s_OlD=cX z0^w*NH!8CR5sK?grG1UW^@!_b3qpe27Y4;!e!gDPxU%o%+J1D=WZCvGR;-RQoObof ze*KfO7!4K3Bv#l^%-5gM`zlSk1AGhXi%3KDnkU)c?hE$@;Syos>Ins4cSIqmX+qM# z_HfE@Nwf*wfRKji&11qx08B7)%Bo{_m)vL^c3BdlC(an?P6>9QGWClDgIK-K^gNO=YXpU^;L`q$kbtGd2Bg#V-x<0=3( z9`qgoT^la3W~U)Jsf?BYcfCnal8s;vJlBCRR4_Oi3nytVGk4YtuA{MJ}=CY5S)^fXIAFbb^I>Dl4?-lV;^!=!N zO&tJU;{R4sf5z&kPzQH`n4^AlD3~)Tk}3o4tdp1+n&g+IGLo6KuRh^4&`VE2lUmU- zKF;z0TJKm|x`FX#OVkd}6sNH6DLPI?63-eRgt;UGd&MDKu7zgcJZctn73MTgh%h@? zuR?~S@Cy-{7^WrQ(>xZGF~$Z>)j&;iL=)No@-sbxnvhB5%;#8o+m2~0RLSEOUjZ)3 z_HB4fRd3QkdrHf1*+OMF9XteFU$;GUf6yG<5bG9TqK$c`31l^nP&q$;cLY;5u4-M9 zirZnj>225oCV-b9bt$5qpV$5q_f6PzJN$m$esTPYEfEAezW1vwGqMHHD%uBjf7C_n z<5@%Shyz*I9vbJq5z1fp!$*cN_}RjxtErH|rA$mJzX*j?Tii9R`Z%H+0$>$hqUb0f zqHk-#SVE7nJ4umdWpCXF?!+PzE>c9g#X-iexd90-Ya=TJ$a9nyqN3us7Fvr-)PQzw z?9KeZ@o*G8k4H)4zS;wY+f!h6Mjz!20^sdnII^J{A^wpb435YKOwyK-k5V%Y=F!!8 zZN|WIH#nVY4CQ7OT+&r6AI5?H1PQ@|!IRV*Pun0>ScOXS6Tthu|L?0*inV?w9|Bh-2cZ}~#C#Ps zBPT#*WgJfksAhI0&|$PvtQl+}fD_dX23RjZcQ>&M^dXnjYoW4QUoi#WvKk~%Y=zw0 zKuZ7$Zb;lH1bk@fB$NUfS^M1&!i&AZ&Nd(|k7t3$I9-@*8A^GWBuP4;C{ID5@3;E; z7MojV+)o20ag0e->nXV4I3G+@O2t#%laGf?kA6LUU}g(seg4Y4Ao29I&+LA*mbsH+ zL1-Hw?oLnrF(tmi@$5p)@ zhc_R~QIOYJYa+SwRbCR-xxGmqUqy2pl|XB7@@$ROKvOp*cWT1kFrp9iO=d?a1Pv_(DAL?in2(N|T~HDq{UbAY z%Ouzt3|>#U42vnXih%cr(AlO8`Y}kr-`ZUo8ei?Y>yOz za<0X~wAM79APLBlo*+&5r?X}wX3cw3x2cb&LnY?(5cAZCtyVyhCohKUL2@mH|JIVp z{;XKtTko9}BO>~cmiNWRPTE)zvn&CtxejIW^0X#e2m_;G*Zx2J(S=0~Y)L=`QsM1? zU|q~>fUQn6kDEz~yCyjq_Sigvyl=73zmL|}SgHCp=Mz~@&*&pWi;im1F`)d8s)G70 zfPZa1c*7nn4o5X9g|f-^&y*&DcUMhK!{FI4?>~bo`Wogo`KQ&7AUx0xtI%Pprm>(K zj^Ynis=P0juqm9OWT*%nGrFP-xKT2mfvW(XTB(T^0lzT1^-<_ys$pPL9*nA^&q4oz zIHT+iMZILY=Bw4%>W7X8@{gt0M(T+Zvnnno{jt_x<}o}0w=QpkDg>EL!KBEz)}Q##eZJl zXA6p%j&ta@n`aXfKDa!|b`JWcX5}4~eYu~RKrQIgbD#?})N*uoz zjT)$B_SUAY00=S*a)k4ERQqR06r5k+qj3rk9v(LBREP7RUDzo(a2%x6(U|~}N&Do9 zYNvdIgt}o}ao2pVCovF+RVb^%K&iY*y4##q0jNGaS)j+w?El`iMT0_fWWTDMAV=EV zmazE;*cPaG&5c&Y3#<&I4SEE}LRV=d3-GAnjz?Y#UXKurlu+Cpv7~U?s(C!4AYQLGKD!ncA zAouB{R$MyV?PQ^1Rh87=OjYLNgjPp}lxSk&&!jkbEjCkWAUu+3Yp~G!QTz1j_0yt98R}sB7Zt~iWh}`Z`F(!L z8yw_$3}iLu>`RLm2=U1p1!EL%=5sH~El?p#_yv<3CF@6bSf`z6f>+md}YcJ#M_pl z-UR8sQF}iwEQ+HBaHCuObAw55WQTxKlkO14yNjGD$vhSHO8ztTzt8iU0_nXXPLoS?-9y>{3%gaXu4Z}9z>E@v}jGf z%w&Uv9z5>y`IE`N_g@vU|Cms<2)3OBylW8l4JAs*mdD}u9;}Q1bA74_v2Bc0*>G(C z&&=V`c$vJI$HK-B+&zx%>t}bYQIpBwIUGCx=5o70*~^GNKdPTTwujyO@o0MDop}iZ zeAZy_(hMsr6fH8(o+i8O{X$6Nv->2Ys|bIUqarfX5q_`&6_xi@f93X> zMwMeHJ!oqij?z~;WTG;o&5Y*o4o?RG4khMK@c$?9@65fLuG&f&0ybb}QY^qcKWG^l zCSeRkM94UJ6XlN? zynd$h2w>|MEq6R>q(Y`qHC2ij~j1lfR4HNXOtP`U9Hwdhx(xGP_cLt7e90 z+kP+1sY~fx(R#AUU^uL?!dO&WBK0U?ZWn#aC`nL5T-;f39RIzY*HL)_-ZX5%TfHw5 z9pR#0wk-5SSjgo?WL*eGF`~*>TCSS;u(^1@=05QS(go&xCIhY7>#bGXQKj0vZ(!jx z$1~h&oZWbpgO!iOA-V>R z`ZLi0m>9Peer`5z^+#s)!7)8qKg{930hJQ@Bl`xSeEyDOD;Ob2l-Jakuo}2LQR!IT zpZ#aA#-WBQAccsayXFyi=$Fxpa@;>aMDBI6fncxsf!!H zOx(De_2AH!dKW4S9~QktCBAK9bK^KJvv(Ae6=3+s+&;`ULH!M6OX=40wOB9g1>v8N z=|ffEM@Mr}Rtx5??b|q?+Sy7o3;*K`1KL_AA$sV{}S z*cxtLdW?AIEAS0}H-g#};Zt6=$fwfR@@*&Xj3o8%agqfNyfIW2KrlME}+i^6ss;MSS`CQNl`eJnbWi0vYVgU8J3zkUIOi_qv9GX7URV})?^ z;TZt)e{KTm3hCb8N8hk`nZVrClg?KXRuc+Y}h-` z8bJi$YoE}ur5>|ZOjion}=XjXx zgJ~OKkIyMjt9P~gtV@FnPs5E@XV^yUh$c`Ex_g7kSU&J?GvX#esysKgzRHA1DoV z#k9}7_)a*d;B-0qMqS(rSRj9Hu~;rD?{ngCHHPTcC4h;`Hewg3=k|Zx4BZ`ik&n`% zdT)M?AOSm%8241ZBD!M?amj3Gfw@oe=mTG7PyuVVTh1X-YdmhlnRad>ojEe?I_zBP zD_J6`q1|?fyztemfLL+v2bcP3;=Q;TIEk3Cs%3dTgDM|2vZrq#yDI{Cl230n#7j`a zMyOBF<$bZdAq2w_3la<8tL}RuZWWGc%PcEbnRRq7hoR7)7HpL?&5FySn#S?lgrxO^ zZ&0mfpW$rZQ|4!$<>U}%aL=x``JNK@d!Y8f$*a1%=k*07yEmUQy5a-h$GO+kq$GM} z%IG3%p&|{%5wf8{B_R)6Qa%vx=R~K=`kpegfc4hf+c_rg{MaQKB$mf1gqI+j&nwi1 z6nH6l#mW@QL_Z?9H+nz#^Mp6l96pzpof2ofbl`}T39EfQvUo#C$v?~Ag*R(|ws803 z;e|Ujqmb=ZrS4oAZBj147yl@IOB|M9S3r#)iI?TXDu-JhUf+y3_Aq0!(W z1l0&X-g7Tf>dw+JnW1qlykx8r|e#7CAlXvZJTO@hhPr^5RrbyFV z@^zkA)Adz9cbvzkTalEy!ummzayQ1PV!vgt$69`!}7(FFvGM zm$Oy&`3QiEys*Q&fq5iDWfw9qsZzNQm6MO#MY9yBJ_rDlst|P+dm+}NFRzal*X5=& zzAC*e_ubAL!4P{NRkKffNgS6sDHiZ9L45lMlsdn zE7HRWSPXAx()@48l}Fw3%H9(@7L?PiwXObg@r%9c?8wH#4$eWil{TnQbr-BL)}kYl zmC3}+{;a!^qk(CaF-p<6#6yPAZeg|L_isNuWq!>h`4YiJwGrp}-t3&$E@e)T9@y+n zlt&8z*ij3?cRthAcA}A>RA-%mQIqmJTclWEa~rMom(}B#mV!L~x$rTSnt4HQ#-SiR zS!yo{c5C&+9D1SE18X8T7Wf;ZvMj5Wc?cP;=lI=Zv(`qYVFeb3cQE+vaNK-exJfRG zHgRe5TCrCWU)I4tiZ$N~ppJ}I$D3&<407U{|I;?w|F8_QSt4{L3Sx+6oSiuqm?&m#Rj7i$i0!&5y(I3m=-?PR+Wo83=X*iQX=!>LbXh5348+-cEDVW}i9z6^u3bat`CaQ0 z8`0`aL3r=k!8_KQiro5m^_KT0o>R6B6w5c07(RPiFi2m>04SJ5yTneL8@Kz*`Be+N zZ?Jt=6Qo{g`h%)us1hYxbK|WS9VMQIy7~g?E(N z>)aZ>+{F#>wnE%JU99uRwlweF>Z>w7f7b@_>qZqM3X9RLes?!{_~bEpsmf@kTWG(2 zeck7fv15~tFMJ8Bh^%)j5 z1|=@H892WVLnkBK)8oz459E}f9RaB#;9ec zO+QF>{Y5*s^qMeE4r!;W=;MQC@BcDI1bH`IciS9d9@n3*X;V}A>=o9)jHgi?0@;Na zaI~G^rs&ymk=Mi)oSh^2AzaCAOiQMAeiNR!=K>J+fr9p2XuTWPchy zG4xu!#*!ScO|-lxab)0*N?>tD?FRcuszK{E5z8(Eff z-b&cLzQWg~UD&=1n??1fW|~%cK4-JiBqpqIHusDvB(G`eQ&2bu=nVKbxmr4LuPEAIGI1JMLWGoQY%55ZK{HOD~PX7IhtnQ)%C#PTJtsoRe?rkNnN! zmls+u^OeD0d+iNRX%d|86@|bOnmA&bur+&Kq4g(w{QqOV!g#Bj5I1!__wz<74|iv1 ztq5GoT_0e&e$dHZ`5WQSrO7?Y%niI@ZhM2FytIYlxw`H2G{_mLZ)a`cCiqTE)|mrk zB)uhX>AS|5pR6j@nf1|4wV6}Q@xM~{Te>Xly!9X2EH|IOyY=1w<_n?C%1!Bh^FO6c zMJXVUQN^*L>(S|RrFtCV&exkc{R7XpAPLsb-!UjgeUh_qv1a58gndcN?p%y~=Nf0X$ZcKri-5zsFKLkE0hmtJO{)*xhXbK&Xiz-H%}a9`Jzo2W(bx90hj8_@Pz+z<5gtnGi&{yN!b)L+^f5L=SRc> zf02&dWwFN4uqme_oopW)!%eb-SK+jg3${Y%Qs;TX$IRLUsbh>P4B0qS4PB57T!G$+e>?{rgPwB<}P`$ zz>R=6X72HlMmJ4}Ua{+aD^H(KmU)RK=8-vB;Owq6R{>HWlQd;!=6eb)(OU;wA&-1= ze4GXpu3Lv3w-(ugS^kXqeBSl(I`;gCN8**v)DhMpavb47&um;u(=)j9o`mjMBGs9C z|47)nv_;Tuf$}!T&~XV%ey!2#vzflJe!>6;Rnl4DU_JNQTtWG-)R1f7w-*2YaP?2~ zSh$h$+Oxffae+_*Sjyw)@Vu=7L2U?oXF1}dh*Z=c zkUg7^bP2PM>smnBtLo7E_oIrJ!G?Mg+(NpxY&H|wTU`8^yKi---m$eOID<#j*B>lf+X&+G6ck$3mDOw-qw0xUgyyk>qsVvL@daorbWuKdK$ zG^<*Ru~CM}e9-Y|-wRtv`zakG8rAvDmWAjKxdXM``x<;g#l&~MPyhH6(qDx!CG7Pd z2eB_2`9`cObKUBnR00?MTGj)l=wWicKPBR^g1oKR?J-ZjltB$xa>Yjku9O}m?&F?# z!h<5%mBVJuG#7vfVys~3hL~6vANVpG7W*07wy!f$!aC{gZs8^dLiD*zgBKXb`<1_L zL1*`p6r2RNLmfRB{$sIJO5UD2Nb6aZ&bhy2(TXxDxElwfVekl?ZaG*PTYtt&aP8Z( zGq+aTv}2#eb&=f&4s@Si4&tU8hjD<)9*{2#D7kN}jzeq&J!oE{z zq1xGN10mLDK3`&PD7JB#avhq(s1yRkax>E~S^3UB4q!x5-(g(tdBRJw`1f5MdzkBz zkX_2km3s1c(dVV3vY~i~DMvF0H*aSBS+Z>XE|)kf@qP#roWPN>AXITpv0k~#6SxoS zAqN^|lwabIf;Tqo7x--=41y|>Jjoz}nAe|xU<}naQ z1GRWfU9pYB*5hKnD0U7F3kP|i0onWYqv+YfLb60lCqoebJ`eLzHECj#mnBJVR6sW{ zTV(A#!!yG_9$zS}kfyWDj@ZH3J=01?VQegcd-f5vMPS{meFPPu#ce$@l+glTp^33c zdRv8%;#kdkfKw`Ugi!!<1Ch8WTMH;CaaxbEl!(!Q@`BqY)HdFN&M;gU7$ivP_94XV zKszK<(U8K29C$IphOXaEUwyBs16I!3>wIhKjB~Y&ctV8mf04xY1BexVn`&M%?E90S zD0=RFRuok(ZBBL5gwZ1=3dGT16nda!jN8tB5jJIKS-!ic2F_k+MQEbrvE+^aadhtC zO!xmE|I9E+lj3e}W4gI-hum`L*5qyR| z!91Ef_JDWxgUr)gV=grj>>(^@hg6UuDp3eD-9*1-7q!AEN34!e4|TU6eqhauLB^ly zO#Ihu+`@#VAZ269nEvGNGEY~oIS;z~O^=v@^u!Gnb%Zrzq5pBI!QZ;0r@-Jf8go}y zN{Q+yKW~=ys_M(+KTZ!|holP_c$=kbi|e}ODWyUEo7;J#oODWi<;RwSXHihyyNqP z!>}4{qXE9mt9S)BdsKMG#@HNpltzLH;9|Rvs`x8l^jN3?4wy~`)Aur33R-h+zSX8i zln@HoKQ4;oZCT)IFR_X(s~faI2{1f*zBN&Sbh5@34xhAx6qmEe^f|-p@C_)v!T*XDZE^B*eyzez99D=1u&lp`3)vI}Av46P zs*9?6Cw$k4@wq-8{L6gFMhel^5@}8YAhZN|NN^n^1a?rklyT=8nHfq{2)K*;-hd9{ zNlG0f{1hnR8~Rs>+{K`zaeN^@`^@nNZM;T=@6VjwfK@yBD9xpkszLWaE;3$m(y^bk z9i7nwbg_$FivkS)r`&lpGdQ?@rN>1?Q_S*1GJBph=^5BKX@;T0q!LY2+}jf=Kooas zSH9lQm{rJR#wyD`2LQC~G4n>?9G^Bu}fYl>}&Cx~y&YKv#AM zc58Q{Ia1gA{i8xHbmA*=?|zWLyYKmqKJ+YBB$;waH;ZZ52d73~crae8{~kXlIJo+i z+6z7=jNXhyLjth`KK3xGNd1+fq_qEkp7+`dCZJI}u(J+%+z@}zGi1bT&hKI&K$Zp?^MK*B zReiuuDI-}Y2!R4)A!im+UWmE5s@$NMWweADog~U0-YF}kJ7_v}94(So>QP+i&ut0g zA~bRiyndX>8uL{R>VcHLM0`lfWQ=z!vvqnHhr3tZB5^#dIu<@(tZ5dS?_~qqAhe`H z&IrWxU93zz|G@j0@&=MURy|bg1WXRvyI>L(jm}zFO0-5pn3#w(u>H_67zQV#{b8E1 zK&CCB3PtByB8E7;;Nk;$8<`{D0WwkTbjTt4{mGeB7*2Kjyy(gz@2cYZIVwu0CcZ1@ zQ2CxKW3v{!F2iKW`Stu+`eriX(sW;Qn;6W#KC^cJA>e((3TR=HVtIUMI&w6D4zZ-+ za#1cxYuz?*FlhIV&akz9UJi+RDb9`ujet8pxF(diVQ@PV?g;R;Br&<}`l z>$IooYKV~yy;H&&vmdl1T1+8;zty?gi~?0jGH>>4IxU7*+9m`-zCY#%6=Ir-u^Vhu zhn2bFRfq;}!Z!$zShlV_-ql`&MU|KaVR^%l0>zCgEp}`H(ya=j?CxZqsC%IVA70k# z!*^QfzbCy{->7dq_6TAh4N0ckI_!{pr>h1G-dK=K>vPiLC?(EgpU*QSC=!+JZ(agS z9&$J98}NiMY3NE0R&e3rmP#PIvm*FiwV|DWEY5deXy#{C1ZO*frXLdCksC;$iO{gg zx7!y&;%|8yQt~~+i#Q#jDd=B-$Ta&V=8e^w3J7#JYPz07o`_tUJgz$C;{HftWOQw*Bez#RIb+H^;QTTo%_b79=HstM^c-KRbOZ(DHav2uIfv zf-aCpq^Jrp?FF?1Ok`|R_JO-P39UGFQwCf8kzkhSCc4=Nq zg|76w%ShME-XWPwlm!mU)>apU3;d%IF05kHPEfPg}AwLOgd86Rllq^F^%Hvtm z`}oC(Zx%)&j*$~adOsY^%D0Ds9b#9eGz1eB?hi7ThcJH84(ZmyZuK&1GM0!OHtnRi zrR@2}`!Ha+Q*Xf0VH%}Q*$-%Or*ECVr(Gsll&rb6XJ+&YncY0K`!4}hAuL+{YQjfH zMb2b3^;7S}uv$v9M-AcYL^1dM%o!k)Lf}<ub)TjOdHW`O z$v07{BiN4%h&6Yqp+{mOeQcfP4*a+nAFlWz=?fZ(H0{r#y^ux0c$MmD&>=ar zp`cbhdbi`DqMbGZ#UOJ^*H{+3!kRZni93|W!w!9^7!?DXm+p0z z62sMs{C2;pg~fG#@Pha_=DL&RvN~99LgEZM6I{4=Illv`QCC}MiLBjsr(>>nj^15w zyoC4kM~R6$`iq3snijX=Y&N@#PUgus$h+}jp?SvL3xJm>l-Zhq6hw^n`_<%h7JYD5 z-vdtg11ol^G$kYJtfW|U4S6Fz z4@gW@QC^N@2FbW5e(})}={siGzI4iU@rq(sCLFEHN9eGYgbW_gJi5^GgFVE&&t*m^ zGwAdWol1QEI-;&><>G@xJwmgUsh#Zo!vY;q_X4>^D zD}*vAd!_|okhxa7sdpdeDdkkbc7V2rL_qQNAUR+w%MT*1CU6!7*V%#ErNVDQjh3gj z)s=GJkt2?_prZZbe@SF7Yc$2bvSjX#TO7g%2!};uKJ^)Qc3?Bp`_^ka%oUual7By> zhe8R~-AHW4OLLgmZnd8`od@P+P7TJ1BphA>)kpZ(ylcjfj2;u}+pXTjf6`L86DiF1 zIo>)9Cz;WZ66pP=xUWr+3g21yPLs@;Oqg0M)CzrJ;TP?iP@6K;g9I0|>Y-WuETLj` z(r#maJH+9ScQejJXqECoRb$)(2$(cyxcd$cfQyZh6A4fC#(X8}SI+JYQPz`m80q1s zvX_AlB%+_Hn5pJS8WAar3vOv84fKZdUmYlwMuv7O%<)&^^}_{cq3a@gE|4r;i^&nN zbL{wCX&+kE_dF&uwi;vgo^}F=LobkDG+P>vA$y>&?r9U&m^Xzb$Bjl`{s+mL#Fh#K zm2L1Ua4Qz0Wo0M|Frr+zhRV$fv~Oy>+Ol8ZSi~ea9>r?6h3sLzFa7?S+jc!z?avb< z#S9kG!gPi+Ro4r()G2P25Ybm7yC6%M>Btv@E)YY5FoZ*sL`-2HYwx zFN?eN7h15Rc0w0cs5k#ZAj)jUq)F%AEdNOF5x}_kNfg1ln{m~;R`FQahWW1$<8qL7 ztJR@(H?so7UC0noR;D_47k&pP!6d7Sw(;4@kV5R}W;et4cpF#vWs-a4l%EWu0zG&1 zd3tkX>sRXTyExD5t;8Iss|)h{tyFu;@;>omQ2IYHSz2yLrqz)B*2WP!B|I19W0520Tos0dTYyRm^#v z+0B~J6^6Sr#_eCzf3lz5?#MH}XA#F)(OuqTMt$C8;F=DDjcBxV&$5w<+vk`6-(z=9 zG(9(gEkgTtTUnJ2Qpwz50KIdOl;rXrCNaNK)%ms^dvK!E!_ANcPQp{Wd>oZawb)+I zkqEe@x5gWa^CdLn9(%s<1@8Q@j}t4x>2={}`pG|6*E%oji88@R)UoG%_ShK4$4Rw$ zA9os2F@C750}+&TK*=~AI(h>4x3`XG}DBpjwTw%VKHJP;yK<+zWKS#uhuJfZaAfF@*~OG3i0{g z))^(5aAC5a3YjKPwQe+i<5j~ z=4jERWX;JR^ez+v@GMuab~J0=PVEpKoEOqkGk?-)4V}ULnHbY%^)fWUR&ASLZk6IJ zC5eAPWhrh|>pJ5d9{`6=SP5;>(@(u|(+Z!fE4*TWRlm)WQG2Nek=rKp>N929rkVjy zJ~1!ET^BS{8;>kWCK0+;RY32VGE~}YAZyKrZ-S)8aq+SB2DH#JFDaFz8K#xQwQ!d5 z+Yek@`G@(K?7fH?jW}kk9uF1wHU%NLf+Q)2@<9uHmBEC~um8G7t|&86F(@x9*M#^^ zv4wHQ$a;Y0?Y}Uy;(XZ>LX!@MZjl`k`<~Or6u}kqu3`*#;Ol!U92EA1bGVXOhS3#* zb!nJI6i*canhj>1m9=2H1F`z{piXxXPAe61#d|qgNM<(529s(odm*%H*Ww*6$vVXE zVJ#PH)u2I_3be0KU2o`fQBy$pgziutftta!a7B+%kwTj8%wg8{Jn)H8k^ez@>YPv{$Cl8FQ zUSMw14s8DJG}=#9+S4;zJH@q#3u~C;zn5#(00im5+Rjfj3fY8gLpcj$ zuEpFxL~JV%umZXG_4QgXx=|iJ?2YjP5~eIDw2p#i`WNe1=HVy)gQx;$`01+pV4$28 z_A^#5k!dBkwJ^4LZ~(Qdh-%8!Cp6s0Sv6^OD?@dv296M_1N%XzwcW;Ao1DRn1_r|E z)vA#hg)mDO=G_zO#2o{94bJfFLnd=T(yM<(-Cex}1p(o)0rR@H6nOUu$$HwdA{-Z_ zKk341-_1?nrdH&=s7VRU(!v8bb|TOc)a065io*0!qfB4gWee(*zZ8U3-xdWKuxZO-x&8yb0|}=E8XI1}a&I-8G?TLyBU>8BbV7 z4O!jRA!rHyFr!VBk?Q(;yC@jMZnFb^vZ$QXnvDfvZ~y52au+_Fo>4<;)#DtfYexHi zsrfC*NZ1Gxc+!;y6-1iX-)i!~fG?c=hsn)wBZ~9o{Up>*gtdJ}3n@JBCarrsv*2gC_fpz>}Q#^3mhRn zSFf3r{4A8=^Mb0HcXN7!m)AHvbmi2`!o8?Jx$$c~e|JbxDVUZ?@u6AH3pq^0)X$z4 zQ8Uc*l8pre5Pa7CfdRrBS#tBF*oI`xv1s(nvlizK={>=Ek(|(rEV*9f&4Kx1(Vf2W zcqcZiNGn+Tx>ZvyE>b8R=m{>V=TPyXMm23363ZW*&^xIgCCqP`1&uMbkFyrEF^TX= zA6!C#vDf%qWlY0C9rY`HZ382dKLdx3)6@m~trF1ACIwaV&zQ^wU|zFJ=m}jQcUS#< zVWW4B(o#5pq;l+prBeQx@W?R*WX=KDZ@Y(_)J=@}PfuOyPw2kmWL2y2>3k`C7AM|P z(X_DHIU7>Q+;WGZZ$$m>zBo?a9PO&py?xrR!}*ypR@i&;oS8%RcDk7WFpfiZm23O% zY4tcIEGLRRucwuz^Q*O}z8aSx;m_CSHB%xOI-MM_6DRIYoxLz}`K)h^{0(0;DYD|) z$8ndkL&=qId57uw!qc4Im8qp$RGnKfPO9U_GljDV%w3tdv;B&OpM2FCPjQ6bZLfbXT|qFi+zIIOUFn6YeyYfJ+w(w>?@}9>wzVX#)zXA_ex{nX-%8|J z+{Rv@&<7iFZsjC&=JY?&*5qXreNWJRc&TIhp#g{?1>kzquqVr;I$fg5s^52zj=8OT^L% zp)==JKRu;}1$Ydp+)Fo8>K-HyKi1bvZyiWLzxXtv-|THiG_BVr(_<0UCvxU`Xe0-w zA0<}rPI}sWvPF$Q!AQbW(Qv0u@TNxQ*}oVPB1iO8QK&YFus{D-Z~x5h0wM4)W!o#; zsOBE^Rjb5J41*WcvF)K$;XF5s49ydYUsNeF?w!OBqMS*Qe z7Q4eAW@+|qZW&Q%*M&Xt4!z0nvb&nrM|RLT$im9W?u~uS-?#6xVFm6DPe`EZ)ae3y@sf+#&S(Flj0TM2*adkqlof4wRhivQzu(tEoslCzm;lzQ)U2tv{cpX$>V?b-8u1_+?L8(_#-9% zwo^lg(Ei#nk0(>hA8BVaaNftR0M@~Z$LjbE+eE^rF(dvks6RS?E07ubcmCm+>E_3L zCwBEwnBi?mH4P`4QM7)0k~uw~?aiLe%xmygh<2Zyk;fABATgS1ReAtDwJnnm1@kMs z%we5mm(i@7@bRqB3;<>_8+$)HYrKIrTGWMs9p;hIk@)6C)J5Q`QD8tgOl)D?xQElwWtpB_(f18Oorjq zV|E949e=C@tZ!f^#m1IXKKJlV?CWQC+3~y@b1*6U3JteZ>HEkThO-fOWRX^YGgW#q z_xJ0`&O6JR@$3v>CwNgb0MAKPK-$f(s81XJqyW>52|9{*MK+(lJd#5XGGwFmM|OAJK|{v%B)u6!Zd2R0d)A z+|YB%TRZ=>dGs#1*&gS!9OYGu6|a%cslD-WSJF+hK38Xnv^wr{YT%Dhcm|K8`0l%D zXV};0Pr^-nrTr~Vu0(<_@{-icE9g^y|5eZwta>v*5IF6u0BCmqTsr?ekXT@2oCm@Y zhRO_djxq*Y-$*-$3#HSE9Ky|FTltxDV=~8w)EG`d*#q$R_eUb5AK*<;QVmEUtHSYu zo5O8x2;Q}@0A7A1ihr|E4~Eb`xbeh7(KDj_+u9g!>~LUR(vCit4V~_;S7){#=I6ih zo;vY0D!GrLo4SXLLr@QryIyX$`474svpsi!lKjKgsk_?kQ$YV&Y?op-LP0G_B7EgP z@xS1^yNUummGY<>H#e?@hb|t>xTnaMH|;K`_|B_bh)(*m=tS55N{&qTRwGClBgw#uQjrQp13Zs{m7v&x1XklNU zJ$;IQ=U?X@IA$)f^i^GkXFB~_bp#dptU-ggb-t_MxrKUqYSgv_`AXl{c~R;{As|Kf zQoP?$f0>y9rIt8J^|oAVwfL*#m`=E`-_1rzD*RQ$xM zElAwLHE;9VoNY!SEMY5d#6NY@NP`05s@os;Px$<5|H{^r`fjzS`1N2^LHJ{(dh|w1 ziPb*S!%y=f^LpPrIdf!tFLF$@mho*o~FNY`JQV^l7V#ub(j9N0b}43}iqWrtwA1bLt% z*_ZAAVqJ^6<9d*U^_T$Zz6)=!y_0XL{%yU2|Dj_~l?1(&owzshlV*HIcR9gO-)=19 zR2rweQ&Ih<`aYwB{rh}_pZ$K)4`Y#(TZa|~FUMM(#6$(+b4~vI{ORzWiot}<5w{NW zllJVVJ$J0f6L@nXw$*GX&4Yky|MBNnACwZp3)-^OpwL_T6Ce5o>f3dE_6i~Xb;9qw zfstjRxtr**`Bu{Uj!0z>_vC!I=(A;0R+VjhqkEh+smDG_gFzZV(gWr zm0mw`^`3+bt`q95M|ije9dgV8VJM>~JB<=fxYV7xjTHu?nl+ftGS@e!sFb{3@rToQ zhE==^;g&IlbkiO;7b1cLXZkm({98D|C{^#$>&tI69Vt1!4W^QJbLjzgCW|$cpEb4` zBiu2`nL5qb-J-`(YZL5>|FaNYQC4xO>UnCvZP$;FznC4)s3}LNEiw*YM*$b-vyLv`8nmqmip$>ivgSD|-H2gf z`;Irs`77}AMMgl;4HquOcVtq0vhY-qo@!dStOC>u^dh8dAqww~W`wFe@V}TA)r?Yq z33$biek@dfzOU_&6xHk$6H7Uf-*@CqB8pU*-++VGV;cSnz$N|1*_>)I5$EvH^ zrcZj$Z337aa(JXGJ%u=;x9V~KrLVdjf}Zc-pYuklh5ptA5BNq4si&49x3t1UYfM;J zsjB6Z$MR~XP0|^OQCh*iG<0~W-387#JgpwYm}5o)59*=k?aLeyrD%snMI}VeE}*j>Lj;eb9Ek z#PQMOcujjf5&z-Kq&p&QN^{%qI^pgirio_szR8u7=~smmr9@Uqh;X49@=smbzcXlu zfp?0w3{B!vU&|Z!I$r*$=xSBv^`vFLGJ;v`%ac_J6pbJQL9br=A=Wp?JvvNZLiTlv z3+W6R4XKgD37w*vuDV||58kIm`2m_$1NmHWf~U>g&hf2_o{Q>8gyX*QavnOu==yBA zhjCg#q`K*sgvE({$d=^`ZYa;(!i?Nr5n@24{z-oB-{S3?GcTL(rCU!xqVIsndqyXH zoBAm_dz=Si?<6W&J5JZIUrfEC<4?;*>HusCp`tiAu_M7DF9(57(gEEgm`8l!jgP;e z9emg7h5HXuIC)eLtYZC;M?yah76DkQ@Q3+gL(BN7@Iua-M-9~skZ}0w`N)vsGjHMxACIyonwJ4m< zea>fP<@7G|518ovK2U)Auy4UoEonH5=D+gFk&sP#usiGFJ8M2zq%TMF*RQ|bBqoZd!?Lr?Qmazs8h9e zcHPpkYcfvr*5+9B2}~-Qu`ubiwt+jd+OiY~F5moHf1R4I@`?)K=4KVDaPYlvV^PR$ zYYMSW!Q-CS3ulnO0c;jGzW5**$jXy8s!p3EO%cJU8lU(;yykjKZseH4b>-&#cU{Hc zW9oX){M~%b1GaN;Fl?C}I55Ao6&8XV7h<03wyi#xSBCBM^pk95-N5ix!M|E6p8R60$9ZM&Ry}ytoORDJQXdaZYHJ2fTITxGr}u_ z#;J$tK#=$~QH6n%`X>_PqMi~%bZF9LmZxr&Mga4d4+B<@@UjshKqWwC2J*rF{a(vKFi)XsIzkN%H028g(-wEUxMScl-VGs z+kZ-}XG&Zj*5{`Z%#t+437glvI5Ft>aB=;W-i`)(?FHQAakcxW^kfnc^2Q7wp3kJ~ z5DZ-&SN_*Z;iFO~KG>Hi14CX|RR z?%+<}Y(l+_?zx)!eK!ikA6Gbl^=1FA5&W+SbMq;BtMuxp`){kdubiI$C4Jmp2Oe>Z zezVi}AIX5B?`5H@vVQUaJ!i|{%l(Ny*Lu74SFfzDb^VEVA13zG_9Rd2satv*(bFp` zig@WG;`UkWBuMPZqD)eaxLONvlu zA;iG6pP&)`CG0j+KcL}-Ucz#CYvU_h!M@aj9!AZUA!g-q)>=Q05nIQpFj~E!nL)R8 z$yka0QWkTTv8D6*L-*#dMr0l)IqL7A(@85e}jm*fs@X1pe ze?gHKrcDqZlveGQ!K3aZ(WK>ykX~3TK863wIR+P!#J<}?@XCIQx#dPMuf`5~y&#Cn zVT2L&Yh8`MW$aIiIqzTFjaNqr9pP1?6s^pC z8};(dNakT1`ky&RG}Xe_CE&e~e`2RqLgtn0zoR1~C45hh5SvJWP_+bpN?`{JEL{&D z)?iBTSr=n1;#7W}4;QgfO9xdJmcn9F zvC2>0=wYFI}1kMzkQ|Q|M3>!OX;lAYUTX^tGts1t=Du zyJ*Q2)h(6!?dbGXr;s@;`N4UFm2TT~=*X;!X_-2pe#3-113=6Ngc~>E)y9>3w7rG1 zY^7}eC|`LHt(0f(3=eJ9mNK3f(p;ydnbC2|Ph{=I6MFbr36Pv{I04IV|Dxj%Op0(` z`J2_P)mVI%?gr$Vzi5*X z4(V&tq7wTbR%JwOnlDh<#ERJ!4rGBpz-@FopDeIK6dR7@50Qw?jbZRzosdOph zOU+`LQSTUxzLkH*V=}!K(NqKUToxgPmVV@8A-4OvD3M;Cxl(=V!@q=9u>?hjF5U380*#U4le*~D`{y2y6u3x~cM|c3e(m$lTJ);_Uz0`gD7a>9CpZ+HHri;;JIC=Y?+ z#vph{`neG%^?9fix zEgq@)QjA8r!PUd(62OKA2<9xu{8#AR{2F##tRCe_T4tvJLkXFy`s4tVAYnXJp=q*lHFQA!HFqc}4<0qYASUNhh6A3LJ$O*Fk9*KZsx3VBkgZkgyEFSP% z$z|Rflo|^Z=9lPw$Zyy^&CI{5>N|MQKM_CE4WOd$Wvvm|4qL>Oq;#WU<5jJ?l||fN zCJPI&B*0K~w2w0#Kqo8Fi`e>9QM|* zJO5AejHJjrN~>h3Av%I3*ED`V?qJ9v(6wGwKkaC|{sN70YU$7AtI1*4*{L^5SD%F# zC*?K#3}ZIVppin1C}2;0zFH@gw$UI(xHoE7wecVaoxqv-LD1hrm6yQDi(pj`kz4$u z#)SDXz6s7^1!fqUMv^7G&XY@iop|lBMn@EojYo^t{L#4 zKJ>3sVY?TZhC&FtI_YL{FLbA&-a2pCR(GmXV73o>m2Y;*My_3;V&+Y=E)YG2<`>u8533H{shvPL6S%p#(j^%ADjHC8aoO{}n3b147M zs^ssnmm!fBJTFIVSJ3&xzR|Z+X;n1oP>zxU2Xq=vw7$jjhlT977f%aZ8d?yP;-u>k*9u_#5R^OxoDg}s^CcH|wA2i0tstJ zsY%~z@!l>Og!*IXrJkRcw&^n?vdM5(5>sr4u#5nemnbq55D1K7M2RF_(-g`OJ)=ae) zoSqBQlr$fJY(na7)flQGO}E>tM4qGRj94rwDRrj!uYz@~t#pkKSJoodN{%Hn^gM2c zc^xH6rHTG*){mQ1HwKu@-LJFTsn|tK8eB%c4B!*{Vs#<@a#d1h%_OIkj^&cJ$;9_r zJ#zZ05Nky+)Po2yLiM;DmTVxdJ)?~y{we*D_c`9MACyEXCVl-zJN}}27!V+wG-C^3 zW5&6$FXgkcJp=fS(cR=u_!hbost*^g*x(4;kTyHqsQ<5Jrje1@TGKvvEPp#ga$q zY6XCdx!yR^o{`}s?fXm@t9BFZb{qY#N(W3Wa&sS1F)QRoeyIQxe=J^~_&xMp;wx)- ziSa;_gY$pT@I({{p81v@`-3hI)PuzB+(UkKfO;AVYJei0EAm(z9OE^TEWPvS8f*Yg zZ%Ts#{^aXSixP-P;=z4>Vnny<2g5yT`0sRlN+CLdsetkP$Fbh_9W~BFoYw;(?|b1m z&FtWQvm4Drc}?yASoh;y(n&;5h26lumC{a!aZuonpEpb7cUaJcT?H3%SKwVmV`+t! zVLxyse&SXvnheNumJM6t4r9&%Y5}1hprFciwf$8^*l+3T#rB*rz=j<*+ue$G3zup} z%3_z;m^iy2BkWtG3a3 zkhUV?j#Up*B+qN(YmWW4>U&h<#7JIEu>*)S;JbqOoBxeAydZ=rFycXoGf`TOgFviN zVvX&ry@^X&YZr2#2lW>f!t&}`@mpDgQq~aFNi_%oLZ_)xA;U!y-jvft-6t+KWGa{i z_CM5PRv?1n9l?eC4JgBWYPAN`Wf3mKZ5`bs+n1}RTI8|Z!8u-K^W;Fao~Gd#yykG{ zB2WXIVTNxr+pA4gR7X6$1Sd|k^`I3bk`kf%HZ=;Ft2Y37ChIWC-JkE_JlXFULHmem zG$k5yk$v$Q1OgruM~CLc0uAb%ODXsBby2SnkostiqpyX*-NjbeV>KVXpwx|zH*aU6 z6-zE(YG;;z;+;PO+3;`@RYb9AfOomTE{KiY(ACm)PB)2KbT%hjTMDa0?D2$tsw(H) z$WtRkSv$j*@A^Rx`0k0ej z|3-x;G1t+Q3uy&(v!uL~MAJ3|Yps*mkFcsD?if6kaL05jlASp85-6Xcyzg@Gyp@t< zH5;UrZ2|ab#(D2Y4gu4RD#_6up4O*>Db|(VWm4N=Gx}DVI;bEe8xD|#JK@bJ%Z0&B z#0$Of6#Ylrgmj9$?CW-xkky99#1RZ!lF?L0ES%-G!S70RRaT&p%m58+uXC+765{Gn z$7H>>1@j0FSy?*Lp&%>A`MtNqGIr$H(p!ZHl1MY{-D1&n^iGl$c5=15lEb*y;|tCa zOx0N#zM#YrzeTmRt=d|T02PA%5_+e}ap{-`h<7|78-$_5e3q#LeB6dU$YfuM#C<2o z=ghy!Sgv=ETqP&miMu(+k`|PyQGCI@U{&_vQ%(c~Sa(&&gKjcrL1Xyz=y$s@v|nB? z3o$n`j&U%XhoKox4wr|j&ym}v@{&r79i%e3#(a$&)_d#rae@M-{%G1573N0eq30Z> z)suj<8YM)P-duaG1tzVxz=*3U>zRyiGQR`C4hH&dUFmtw{&$%SC-Adnw$3;B0ovJg z(f|cHJm?IOB8){Ns;CJ>kE@|+QYV>7o;YGC`vZ#eqFLFx94C;B#=>?COcCXc`Rye0 zO2BFdm5XF?X|Y)Dy`3jgS6V4uZU~59<#<=4a!}}nHqk3pSc+}@u@JpT7#$|{Md-U+6D#ajskS%*u z?11RJzNv4V^8F-jzaureyV9u7rJ52A^mn$0oE)1D=~?})+b)=E<6m`_wLmh%nkB3; z2{+yln6Kc@KbxV)E(sqD2lu}>6EeyOUH8*k#;wf#hjV+zV#d(AT#^-Ri6t|ZpC#;j z85>(=XD09#(c>B)-ou@1+pv_3Q9xb>`xouqX-whl51?|*QHxY<1KkCC9BeY_v9V>L zy}oEgr`PuokwpA58BA^35Tv1Qc7TLUH3Q`HpvF(At$8z*wKYb7+rK^6$CM_FiHcZ` z=(SWN;=PTHad*LwD+A{*|JfVwBWHm6gQ=IJfvGG}81Sm*`>tn(%IzlfW>OnVgB z#gOl$dEu~=<+f!v?WWQR>|eF@Zsn1Z?-pTCdc#)4+h5w$X(6sOi;B;C`rTNX;yXYj zopC-QFE^p2ovd7^y_1cwoYjk#MN5&B2Ho4OH7)c!(Sp!asO4k%u@}RxR3j1QppMn! z%L%n`UQJ2lqhDS;{B-{w?S(L7;D!G3yINVzgJil0bljS-USsq^zO{8=p-x&Iho=Rq zpyQZ`?L1YErCS}w7`LSa&d?w;BsN+jE~!}aT&=UYt3N?kfb8Y0b(IP;I?N+j2$|OQ z(9RH>cz!iTUsRzU%5&@)dh&RIG~$@0@qm&Fh3;xHgtoP9T-K&<6Mm@z6>z`Njs0IL zy7PhKDw)5r{e@L2%uy9-LC&Xmf}SgWaots8+Q?pCb~N>HH%$5^5D-L?uYUEC| zx=q-!Ypx#jg)_-i!qWo^7tiKd%n`R|B)iZ{GN}i>XQSmkP|{5Qge_&7T?;(zl@(Af z_wLK+N#HwP4&@Fvf*Y~KSM_%?mnbQ2TQ8)|$7MnFjuu8dM`3!|m_52NtKsYI)$rzf1z zqH&$Me-rti6O;8akz@auz>QmRo`Ay0LZDxG+#GD?Enm6e8;-ACR@d7I+G{UT#Xrw^ z7iKvccM~KuWVg!IevilaxcdCN9OnaASFvSMjGS^sOo|>!Xo2@MGoIRt2csfdo;kT0 zOu?p*J-be2ruP!wu^q5#auy_#>7+zCv_^WaClCX4{O^WK@J^uWQd(J3{?rn9WT@35 zbOdbaDxBnu>{cBXm~#mOvqk;i<i{F*(1uy_it~nb1x7YP{PE{mbxC=I3LFFE=MQyuXoz!EVT0@%SYUvM_83g-4L(8 zaGS5~5D$f5;WfcmTW{q)8GcnyiP!ILOkchKcgT~Q2E`$^?5=-Xq!Jiv44|b@x#q2b z{2B$%o(Ro6{y@J~iYX&RBw8SIOV`_p9mu#@_5UEltZ(tg5ixa6bv^kpTPjyzaBSbV zGHpx?YHFpc!YSi+5Du7^Q;)wjS>?g=IAN1V<gL{a$KDk_DcXg=ooAMEjcm;2<+a}J z@(87aU)7LBKqr_s9s=|aE}09P8DJOt>)VqEAs%jtCirQ5Ehg>qBZKoMi3fe~KIyR? zg7%B(8`)Yd#eW9ha^LXPl!Lls zVW^GpZtW}QFPMFHw)r%$d<*SA30k}A-Ga2gtDbq7Z4|20!Kh0Andn_?a>TQkw@x@= zdF-Pb#Clx>%+X{}tdU(VNPh)$Jsmzr#o{Eg4+Yi+`T8$7ji>k@cskv)rGD1jcl z9rHq~D9M37-)!yq@s8JhUIK-fTHL$I-dR zGu{4w{4>LlLyDSgM%+229PXII9J`$=b4&+0G(`u8A%{6_PL*bJ?leQr%Bct;Lktye z6g8qoEKLq`9{2C_{r%nJp*^#vyL)pbB$DqC@@ zmmL@_)ss6>|4Ii6#+9ZOBA@FSokX7+`>KK-6tnUbfXRUnZsk&ct6h{>e(Q5eaElC> z^h?HfpExMlt`0|3OMNhk^Kf_n{+XgyO`O)HUoOSkuh#vK1J0LQ3rdMeUJ7{QT^@d2 zQ1U?rSW?hv-%PTj=y&MH$CT@>!PSJrB_%AZD=jAe{+N9VT1c zbAK7g&*-wsvNQWvWvv*J4u@$p0CU6pugGzlt6Tq( zoY31JZ{<~d_|{Lk&~b4CM_r+~(7i!!e(HWXZES9(9UKhn%Wj_vGsEluOMMvRDf(6O z$Eq3o6=!8?I&ZemYUg<5%k%J$@1`OD0ap(4Z_Q36kS=;CKm+-W?xQ=W^IuM-X4lvS z>iu>blU>R0xNiJZb?-v1V))kbu4Y%fIQ2YAl&fH<;-5=lg^bC^c^ZkWK6ZNN%YODc z)>!h}Cyu8nYFVWgKXir69to12%QAR;uti)v2XhyDbNFtjdVbhmKQ5^A&(6Io`F!v~ zuJTGZdu^~7r}9l|`!=|LS1@CH)l9vtc@NqJgo{GjGi0|UcCLe;b)UvoJg3^sh|>`- zGy6ZqZ*{*(>AqF-tMg)5#dQwZynC4)QaZ#TfrQo+(L@% zlfM+6zKp=F)L0?;heD?J^tb`n;(ug~u73Uar7hAy^XCiHCXQ=H&AvG@BNcx1ZPsUP z6RnC|Gxe7bqnO5)V;}GBfR1`Wzq!CV<%6tUKTBixtmH`oouYa@Cd(h2b7;-bv#8YA z{jX(h*`=ILqLq#kw$y!gaA?fu=A$c5Uv1))%T}sweq1=elrtXecG~yg8vE3mm+w+( z%tg3(?aE;>^qOi7=X`6alC#Xtdqxkik7;(PD)8(z=`nHn0_2-8&DgWUJeUW1fy4fO`}5!SnfE#3|`tMkYej_szeCX1c%Gre5Oy zku9wCNdAWH@7gJA1mT<@@hp|vP7#RvPbi3A*e{;C9IuP+1j0i}<8jDaUkaD#SFrcy zzFqmesdS+Npjwcje=dYOTz!*iY3r`&s{jwHI(gz3`mwKA+beKBdGmdPJPnc93*h!q z9pa7VwT-oe^_!b=f1qfLf^5%=uXoIb?onou8WYAb@k#41J{HN-vgy}o^ov)jh2_x;9Lgt$>vZ!I%3ddf zHsY%Ys0RV{eGd-FBM*Cv8Bq(6SZrtOuzWFT_HK?tr-Q)>2mDvkDO@pm!Y2G)QQ871 zsaoyWKHu=p{zFwR+PE=TZ;g32ygFPZs#YmI=d`>%>6h`Ykvp#VOW&#Lt;KODTq(;9(8!o#?lzcLZD} zel+^LbxPf5oAs!dVukkrTEyUo_#<;NT0>~#m?93PD7E%=fv@@iLGqD6Wg&A>*=?4@ zzp!K`_HMX)_WW9VcC(q3g6ab>tStsHc@Y6Wb6FZzS&NkiqxsQ?|&H!!0e0r{GH^y zp@`}4u~G_o_xP33G1evSh(xk?AUJIZ<5e#Arl~*BYz(xUqn1@v$me_oH(Q4jO!Mbt z>+a3vJboKTjy2>kKrA#M0N4Hmoryj9Qx5QXsv>}CTI0Q7`OiH$Ev=-aI}RTN!shZz z!qiH;Pq)CegU?jUBbP$EaPvZEpk>-$FWOc#xMo8xd=I50lBixB4};W_`X~OEL~-HQ zPngT6R;oK1L8xOCP3)!53bW_G;QQx5(lR}q-^`Df)Esy^kPBunYYTOwE5+mP{H5aG z9TJfD@P_KXA$-;dSRs7(+?n3lmIIHP4bS@hbXuT#j#vDYeO?b)R+wQD6eE1u}ui)liM?bbQ|7P zrcMY%I>%Ptnt$-&nz=R(5`BjqG2~i*$xrE26E%c;RqERMFAYU2pR3+FJ*Mt8I*Y4l3e2g}33fZL`l_yV!N(>Q``^E8*}+`y=J~1*!JcP=LKJkl zM;2LANJ+FwD4BY5KFRQ`*qhR}Q^l08abNVvO-iBlcQje;bxhe?=53?CZMm1fpwdgE z-@3XEI=1O8Ox5vTT(LT%rjj{yIEd{GksI`m6le&Ww7&cd@0XMoQ+z@@&g&=UO{}Js zGS+?Ar|rT_+ClQ7+gDLXux~St7@r(v$7R?#h`xZ6jj+HOlxTZcfWgJA~=kFoR#HWgv)y$$4@E?@Z7t5bAsCNXhL>EY{?g*m}gXhdva&dUn}0Hu*f_ z>$P_`Bu1yy47Y?Mq!#BIIc~ofFMSzSHTAW0G*>0+q%dag{C)pd{C^`GQ~}#d7dA4- za|r8m6#Ao@OJlCK_CRZCh={YKu<)(E7?FI=1C;V#UV`h)#^JUI*De9y88l~X39O9j zFMId?GQ#x76<2**1}2=eCV#U8u`=bUA1- z2i;@6V(7Hj&x5I~Z%0erV}Ff#l^_~0T+aBC862XM1KOU((r?;N_l>0EXY;dhfb8{7=9CiK=hr5F>YDOeM_@z|Lc8b&7SnO8#R z1=yrP9}jx2S+J3Bp!}-@SSe;fL-@t~3$qBdkjruyn27>N2x2q~&ntM!c#GqRn5B5J zpH->Fb!-u9>sV2CDyPTvV{=@fO+U=bGq3IO;E;8y!`iSB#y~a^0ML z8(kT5aVzd+VA1)fE;poW9?uN>9jhl^z-QiAXL|LQI=YiTX_?MoZ$H!yx=@_vg?wF$ z@Ea@fKe96O`*+yA{CEEWlc zwuFdw|8(5;cG!B+fwrZ46S!2hqLR>TXkqD{^)iL?S&QX=z7qGl5Mtx)gEhC}T!)LO zo}<8C_Eda-UTV;m4A2Q-qmc}7cjg>V$Ecg5?14EMU=p0g?~Gn0OC~lP8_@L^&?9}c zI0{2-JQws!bo#9Y9$x2a>r;#mTFl3{jBw~{K3Om%8btC|Nh4*m=HjaOg+2yn+{GwC zhw1QGW=|4O^h+hDgPJnQeDJTYDZ^(;J#mR;v(A-lGR{PZ(`|$5pFmK9%4Cmd-jzsq zRmk&)mM$gHz3ywtPt?r(Loj>SJ$QFf7`@WRf92`(9W*a|KDVG8fArR;y`#*Qu13@4 z+Fec0ds4(Z0+$xgE;lFQ89$zh7n?+?v>UtpjEmo13vv|DvJMlJZhTup*%_(o}?R`0{l`MuJjx>b(+8V_Ek-L;&tF334gx~#*Tm9LVIU%s+LE9g`))Dxn zMsc@5ALNZigAXbdM*6bGppi_@lg|&|kt<`4Zx-2IeQ0^|k?dcFsCUL!+w_O(Z!OG% z%7pyyY%eIrXNm&@*5rN~h-Emv(zOJW;Q_i`e&+Pe0r}x8|$viS|Nk z41YZH-&-8`_BQ)BnFRKob8O*|4se!Qb%C5IeuxFO+JQ(ByR7WHt%yeiTPC@g!Dfxf z3=13(pfeX7Q{Zr>topAg_-~9l`gp-KXi6B8ol(pr?A~lF3tD=9AdYL-1Mn*k$a@<{ zp-smt1(fMeqw#hFHumRxB#kJcyXs_9m+@dV0k5_m2%MpiJ*WzHeH7J0aT9(zG*P)>M z5cq{ZXLZWu5Qs3;;DWjIy-uQNPbA}y9o;}d6p4vdj}#?GlL<~V1$^Qtt^qKt#Z$Ug zx^)uf=)nc47Gu|S#=zKueN_r%Gz_{@AeI>%4C=$hm(O1Ql z!$c+CAJ#~gt`$DEJSkHzI?kN|i+ui5KWK zneWtx{&GE-3Y5ek_|+ML22MI?F4TyR0K{<$JjKZsvR~P(HTMguM zP>@ps|# zv2Ep$_7j*lw6M}Fnz1kFgb8ljM8vtFR7b|X5s!Ra;SM&!QWK3|jpInH)aYq8e9Hlo zY^fbhwS-*)BDZS0O7$s5BV+Ooz@FtJn6WjCClk{IT6X{BmjHjWgRICS+Tn}8nog-- zH@9WKj&0M>`XWzQ{2yGPCU8JM{Y#Iqu*R!|5BLUG_KmfprRgEn*5PZcvDE9_Vu3PL z3$$P3buW;?Azg@R=Fmy+vcO z8!ok_6MkY(Q?ST*jqJspvRO25&vl$VnIm_lY=r^JR0ck|c@_HxEv|k!6NXUQ9md*rton?y{+axT1^Zb1 zZI=i=wV9LNI=!%3z7QbiYiuna;SfrrylpC|o&iJi(;Ra}Akn8T1doImHhpPd)8f^fz_VP)-ez$kP`YGkQo+zQW=a1H=9Pjf)H zLaTGe?$o9TCl#nl`wu{SAiT@hi~IJiK>Cz3K3?$YlcvzfYs`kDnML6tumU!Cabbl< z(}^>nMQ2x?6bYnDq8UGm8BDk_i8Fo#Cp3PzG&cT3HU#cqr7fqjcj`dwkU&bgE`ESepp922 z8A2j^|L;Z;F?X15_E2N2bGF1R(et*jCEkzh!~{z=kpGas?Pwvs8{qinnP#HdW^MgpA z=Bjw6Bna_syO{T}3p$h=Q6(_JBsI5-7IV!C*+N~yKFx2`*16`=x$=5+T?d&^UWL?? zi!vE>Ns$idXg=pmeeYX~p38}(70M0Zx;1=q=U-Z0D~<~C9e}z^Ym(p!043wUrV9-Y z06f7^Fj8a->AUjaPor6mI;zu-Ghiq{RE9;R;}8M@^kUSCkg?pA0$~;zpVmItrY&eV z!N`B3Got)8ZPqO==wX@J2xu*PX$2JSf--dEd|=m578wLO(8op+fR1V2FC+XpKy8o1 zGr3CKuVI&S70|%$OQbx@ukWe5+pA&711V@Jd#p!jMy3>$IDD_t0EVT@6%8boKpyC!ZbMLnreXWH+52W(_)xY#Xt+`Gia1I2OdlNats?u{2b zS2WYv(i@VxDkOi{8$Mvn`>5o8zDKmT2crinQ+)>F_*TeM=9c0ARQypDU+Y5`h;jl;NG zj+G($T#dWNwu3jrAsSU_Mb(jTj%|}K4ppc;A(=o_)|{Odnh6~=0pXg_iNuw)0bK$f zeA0E>HEPk#5x90#iI9C}F(M=i11S)J8+_=3DT6C`OuL3|0e{l8c{)sH#R!*H6oe!$ znsw&5KqCd&wIGyCQ4=^m>tJ?2s<#&i&F{?mIaluVo=nNBqo`Y{t0EL;RzN7zUQYO% zX^{dkf(brkdo196P>|GP{hf3`*ZPcj4Vr`XwkP{EGYgo*$<74<@O=|F9=P*9G&}o} z5g^vYlUZ`>L+lTRRqPr$%L)o(?9fibiS095Q#A_t_J9RV9W4bCBAvt%;up}|JAC4Y zHCSs(N(WJ+WQVt&KSNWP79;+kd{F2POG&!?8_Y9&WXYDbit=H~kQ0SQ#l6{-*h;6S zLz6v*1tNfw^{~;}Jf1^cIM*eeBj`=a0_oCX!>__<*2u!%DJWM}lvXZ(*RhGa8SN+_ z^jBk;*5;nfZ#}7}q2chY8~w%mqYP+VKh_V&(-e&(f4sF&+@}VJc&?i9PVP*Qbm{GKI)OCwZ5MrKJXYM8@7{Yhe zn>>iYz#3>q6wa9#4+Lkm1pmeUw_WWH;}yA>2|DQ|Aq@5TS+94=UBUI~AptceKm#v5 zK#4$<6a|6m2;h$R+i#=AOIU=Y1Yo`SHA)Q2v1|Dmq$y`2K)_>n#wB(2DZqSmYN*fX zR^mgGlV`<%w3rEjCNT(({Nq*w4Nx82Gd=_?4N>5l7whSX8ISGtS3^BX%+IM z**7PLqzI7^XiVYqP(F6A0niI}HbjV1AF_rY9rj;m%PmkwSJ2Fj=D|R-T=n8ru-O{( zA5h{Cb@=$fV4AKQsY%6p?8z))`^S61^47-LEyoY|4j8^;5URM&C}#c<*7-vRSR8`He?QZ;$Ff;)z4^-JeW!Z>4KD8z!jWZF<5A}m&?!Y?M` zM<|%I6C)!m&>m;k!$4~^!wP^{qv7ox+MPM%n<1zuPchJp#PsJpmlDeO9f8>{O+A<8^UxAyPdvK!!Z}p zX-Tky(Wa$3DZ&RUR56Co*J?9XC&4jR^P@5I#8d=+e&0@;mM zW?H;)Lt;S#!B)O;?e>7vO2!C$U|8eSJOJ$1w(-HjCqx%UV5Jg&`vyAOvcZ*|A_GWb zmkkZ`=Fv>An>s6Z7}pK?gsWKv9_g5PF~CC>jennR!RyxE?F?;H+@t3lEm!6Lc$_!m z{T+)91;550IF%%iFoialOb^5P?oU-QFv6c-#=!=FWdFKZj7QU~+iFl_<)tX)wN_*`r^%lSu7q zY|xvgu%`1BUBHFr&VgZf_^J^^S^;8)<#R#UbOSt3{E<;h$tK@BrdD_D>P%{ zLL4GiE$ak+6bDFQy{ZnIpNfLYbtr%8{X`Uls9_@s@w8c^(S@V+*KMW1jk6x1=d zGeJ4=xTzAL4o4~u5$=)l>I&a&I8mVN*=Yg;;_VqgOP$B$L^R+y^j?a5jvDezc~VU zH39O%@!}`Xj#wXjYl8*5AnftLBGYOjtPI~mYNX+(IF3*ejEEd~BsV6Ll>cZAY10m_ zoAPQA0(vc^L<-ESRK3Z&RZ@pDf?U1?wCa5DM%?*oR-zVAl<$-3)oRVJ7Ixf;Qy3i; zS_&pWI3PqV-U|mz>3iA9crt0zX(AAz4i+guL-Y@367b+ZBh2SeC;rUZktxRUO7_h? zs02xjzqnBr4dERI1}zk0rt~ArLI~3mZD5eW+#14cGZ1TWf&ol3$F*aijC*_zPgeCOPC*Tq5 zWLJ2Buunn~^sUrt8E&>~e>1SmlKJ6cs3Gi1rX&t$RdlYqkft#Hz+W~W8L010IZk}d zHtZ1C>TxF9TNHj?u9U42L5%MtiX(i91>n#`hDJZ*hirKgC-Pf|-)&RRFEsB3YrV{2 zP!&m7Ncf(>qgKE6(T%cpODRwqQKA{T8iDvp6#A;&S`!M2O-1AkAySP{Ps%4P-k)o4g_Ov2`O2+BJw3oASLY z6>}l7gHGer!BX|2odTZXkiY>k-rQ7)+CT_q2|N>P5K9g2B0V|pu#0A%osQ42I0Wqt zUC824CSuhTc??G>)9K+xIZwSIv9ui9Eo=NdKHtauLgauYcXAw01r^K5JC)3R#L#ic zN8A6dqy|LpaD58={T{qi4cP#BE^yy%SBKsFLQqzu=EY82lqz zph=S)!1%3W4h?=s=}J5YX^dg2++p5?NMtY-r5=*3zf)|X+u;Qeu%2L!q7DR3aBr_I z*fqlcP{RKMBu)krB_?o`Jb#Fxhg8fDiZH>C-c}LG87cGpQe>w80S7Z}{u{VPg0C-_ zPrwQ5rk&~O9uN`>S>d9lt(Vg45heo^!Hzfc(M5%Wfj=JpxdSDQ|4aRj_}?Dii6XTB?LiW_30L~tPfN-vcLDMlH3yO~;8;7Z8P_iXu>Xc^{2?}OCMFZxJ z1hUjXv6dn%aZuxb&-3e+Bx)+$$)P=FG4FMvRG^7A%==`{sTIh#;&OzsHgr+7fSQ4 z8Za$s1X+blxIP|;$SbC3M~9b|t7@1t%g#EZJNfxh_xJ#~s#r-x>DvT$W(k7I#9C;6 zm7L%o=h**%E{?@taXw_60CB$(bPg66x2Wck@SGelxNr_VAQ}i-_mhz0)+*G%uEx(q z#Z`NUB14pe*~!~+uIyt!T@t|)PuSM96B(uB5Wjl?oTQk~CCd$#l{3G013-v7X==5? zVn8;|8{E$pxeR`)y&0&RmbH;eXW$yy<|0NygO<^_rLuHe@O=7R55W9(J66afG=VJ= zB8)Aw2d?bgn<57=p;ZQ<$krKQW`hBlUGN)5Kwgg11;C+`5#ZsCE0qEZJbG2zIreeC z*v3pC-`=U-Pf-U!i@&?+2+2e%uP$H*KlV6GIT)>X+Yq(&Xc?&)c5^De2ihOTuc!e+ z(FE`7>7l*zk-ez75_A}1KQKAcUX4*NGRY5`19QYu=L-B_Wijz|^{F?#Hr~%C6q*#W zzj*}5c{ejS-Nzsh3a~K`17~X5=5TM>m$5|7mZZ94xhB=);O@<1Os&L0Ii%fx0OU;1 zpM0>?CeWqdcLxH>P%5)#<*a~ygF;b4b#5EVg*ZW0$99ybzIWf+Z z>%nszsXKEDprTv;?uV|uEwC|4DOmfRxA+oaxdYVfqsj^x>+^aGw(sAZV~+2DmL-Yf zI6utYS#!zRMiQw-j+;1vx5b+2beMogY2WSo|`*-4NCY_C_d- z&0i)ZK-M_V z3#PSc#|i<&NXM2aIA?IBG`Ldl7d~T%aFwV)BX$YKpR5263p~dGfw*;}xcUi7n`v8Y zTg5DKXUimvU5YLc5;qr=dQT#KrQ4yQQ2In%j^yryw?HJj;0H~#$L8$ngm3)uXh*?( z_1lRpjh=d3yA?$i#bRv`%ytz`$X!o3~9KJr#HXFJS%x?eaJ0t<-r zO|6hu(<1fy%t!K@YW$YMGUWqwt^t7>O(wVqR0_s8tUA^XuCtg8ai90bGU^phQ9vJJ?i<&eReQg@!4>6ZPKEXR@=5FG zt19CII@CNSyykhofe9k6>yn|2b~Zj^q!e@GvviSHrT4)un;!QF!|qcVr0L}TnFz4v zrVcwI7VmGPEwn$Tb)|)BuE~-9{&eJGtN!gry{wh=U>ge$X6_O6j8`@(f2>e;>{m?p z8-18`x+o`$sN<2;l+7d`OpxKt+(ECG3LFTIe`|IZarMbDsfTbki=k!KSexYlxx{L} z14MQ6Zcu+d{OV5=Z|EAA^T+&MvIvXH# zZ*2}i3*%R0*wm^c#SpUKc2mTo+@)TBgry9oN9SN4I#=|5n>MJ4g#TU9AYW_t9$8tR z{58<>Btmc+^5^_(2;4VsV$mdjskHw1VKEqprYtxJ-QR*IL~;hVy5-%KUhfJMaI9|) z5NcMF)FXXi;Yj6e*OHgwxQ$o{_)1L0;Wb|6bs;yWchwn9Jp%_}lvb$)utAS1w_+Kn zMWU`p%^Mb}bRy%dNTklykuo3VaH+a~`iv~-VPRZdW>juEJRKumYMcOpcE0`g- zz#HUPkW)@>zmo2X`7#rLY+?oxUfer~fqBHg0VmjT+3Mj>-|w*QL)z{-bQU|cMaBp? z=(7#kBeeyYr@ZCET?5T@6ejDir&q@OgW7wcMDWE}0>@kcha$MLMwxV>$W0BSIcUas z*wI8QYxw7>kjL3oetT>ke z_KN%h>G+G+Lkge+{|*2c{K(LGZ}Y)7x>fha$}E^=DEly{qq5FTS9a_(y5?$4yfa2d zWHL&*Oyjq=_kSy*fx)dPZx7KN+u#msT`=6ZQXu(krtbQ93kA+q-j3ig8*bgWy_no% zy*6-|lptcrWx~5d8zsaOX9b0rn*8HN(v-E~8?2aStAjsVeQ9fbaPAmXwu|i5@;|Nc z8Z&_vk)YUU8U7E`+%$G!H?lfxF*m$#>oL_+^YVA(WGj6i)F^M@G}_ z{Nz`{Y11pAly>{sBvwb-z_+*!b4m2vkb4#MqiO1-eNcZ zqUzfYs^*s(pcXu3_Jj#xuQ4smR9K3VdDO-1{Ek}#XG^#U(6Ij>V72M~Y;%6D%Lx$@ z2rx^9qTb7{=&Kmz@gKnc^eJI;;8K2QIse8z2q|8lo^gL5z6H@q_905$T=yb*>6cZAhg>nu!}F5~=s(}}vLyIc z+>d7@zQ>-WLtf_CuJ8NbR5NBo82dZ?^>4G!HxJ^Fsdjs^yoR~K>D|-q0P7sJz-mu+ z75PAVN9jxR;QNXzASU=W6@2xX@xY`Shml8FD7}+htfy z^I%Ds%lP-I=0Ju{)5Qo`>6N&|27j%-D=YsbsZiSnq_);ylq;M%ze-3}5eMUTl0yD0 zpLbCvhXg@qJ+tA?h{>;eYi6PYN}0ybel4WEgiKAuYQAdz*iMu_mSDHf94nrsfKBv6p<2^r0C9T|yv1aCu2O=iPxA{WDS?Pi>(IZ zhgNB1NzK~2QE{;`@JBsv>Ny_RmA}gM5T@CG|744HHdnp@rN!rW)_+^Lb?BN$RwuQ| zv|%9VKxtXUq{r*cu4I(n-{!g*oV|Z=lT`Jy2P(uXTZDBMKxxI5z=xIp0oTt7EtqGS zM?~FEm+V7hBGG(|9))&oZQ>1W*keNQ%4~R2?@E>mZj8iO7_QQ>rLaEWb{>xFFgL=f zm;Uftz8rvm4hNf?hv{lC2n}oceN$87 z>_18=f#hHdL^>fBGp}ZMVmv1*I7y95k-`!LQ$t{8Ctw8D4yL~S@0(>=DS^QNuR8V# zda%Ci0@oh?QR4tBzokqOu7i+c6PZ60mSr4GJo-nsJq zfua8>-CAcaE~oPILKKwLzr4c!3H$n*d{$oV%i{oMeqhV6$LfZ)JFlX&k#hS?z>3OU zGPH||wQ%RXH@|&S3qEThtVEyTcfo%LtJOAMzE#Urepai)<;TW?9YKz%DKLqftGK6Ub&I$$e58cgbDpTmIH!DfTCmEUd(%GYIIb&&c8Q@Qr?eifyo@uy-S zH+AU4Lx-jvvp?|L=aNHrKkx?2x80ggdY(CU9#IkWNHUx{LdBkSJ#hMbcb~k?N?R52+XDw< zvD&nnlIoo+obf9aj5!XM<8-sG>cdr$_|NT#Fh>}kb&4cTx00yIBkFW6GnksY{*qSz z#`PqnE#$IT1s>keKTif;zb{Xb?j4w4rUCeI{FdAN_0-F@mposHI+rDBZYvPZTjz(~ zIoSWX|LG%r+XZ6mrr_rk-$pQW1@Bet3D%7@`%)$Hr|8L8uTMkgy`CtzXC8P=tyPk} zdLtm*;-d27oJZ0`J5>Jniys2AHt=t;=NRI+Z=`1ppJfk2qqN3qF=m&F|I%>P<9f4< z{9x_in}6l&nb4iCCg=)foVgKu%W~VKOGd#t$Lr|~)No_H`})QFV`kx%mDa+MYl}kv z%qqw=IgL`-uQj+it&|;m{tJaWMoUf#Q%1G?R2&1HYyvl8ehy>8a%mr}ZW z)-BEcqSo(c7xpawO;j@F%gSC<3JYj@=bg~ijx@_T7nz2?{nF-*oh-#I8p<8NO4OBG zQMwP@KmxEb;}lqJ75C^o=g7NTArO?&VPxIN5{D-{c)91iYhH?eEqdE+ftA#J@ewmi z`4Ef5V5>O7qUIQ4AFAO8vnbZzb~UokbEVPB`1!Y8jg7J&F8+FTkqOuEJcY~1=->7m zRnRPN9Q}RmpB6G#HRZf=2rAxF(|=Sq*x;ah?LY2coh>ULG2iD~{k}QzhWyvVjlQJm zc>3n4cON6J_kXzj(<{c_;tTX;DXZb3U! z1Yfr{M{&JZij?f!7%b8N8eBuI{aRxX(=%}Xx33vVkMY)j6kJ(O_HLHn3mE?j3duHp z3k;5W>;$vB&|PfHvzl&CHaNt8 z`CtESQ4HL1uxnB6k*YC4z{XGxgfCo5<|`-d81S8U_)XMmw>|^8aWeNot28l`JWWab z{LFYFCD475UEsC%TH{=~il)4B?F!qZX}6z zsf^_JAx5z}-I1?f=rfNNd?j^k;|kW;D>VVj+DG-}Z6AOI9D-@h9M0HCNo4iwf~|Yj zvTwa*z_m*>T7qhPDEJlfCE8Ix7i|(z-DsIu6C#jNPZ|hc z(k%OTS;0fr)y*rkafw$=b6{#6O?mBDXA5{2j-h_PiQ^^IP1Rn#$SfE8E+^2q><9To?@ycD-q1NR1Z(nUz%a#9n zv^-J^P2JdEYOu}>{nq-VZiDjgN=)TtUX9*vec(~Bf+Y4c-}Hz6jj%tj1qV>EFEVBP6DB~a&x!@InYWI5DzJwL^y?bf- z8*P_+dnNYlwI;rH=vvLNB`mN0d{e`Xq|-O?J!TMFYuL~e&Fp8|=)Y;w4vKTsOL+es z$;|?h(P?Q?;yGLv1EpR;MW`X8N3{mA!$hePMHr|D3MW}bhZl(K+IZbOoWgV=JJXy0 zocm)gffh_bgWqACHF%%lZ7pef5=~5wlcto_Z?CI>sOBZnJgj`SJKcM_40l+x=za4$S;feC-tV zy{AD*eDC${_7?qkt6j}6F_HS4;UIB^7u^<;eewDp3Ybb8yUo0*EUt(8BWV=<$vf>Q zNuKA~gftd=6$ic2o9P=6euZ|Y@6WdDiGu6{$SyQHkvYk$f*dN`@&aNC)Y)*5b*u9H zXZb_!5^`~sk4Ml#$|vHkwgsM=JeeI&B(dNFxBB0nQhUhQPP%96cHyBiT!#p!-ljBxMQy9+{*LLL6xnhg2`V83J~E4R(+)pj z;c2*W>RU*0#1njmR?%s}7K%PD2Xqv8jV?<(N90c?I7Ck4Ori;Rx3K)RTfx<3k_`3; zLQSFVZqRVe0`B9>N2s=$oWZ6!7+*89aERKncdT+3BziCO?hWpH)$FAu8H=ttA*C=~ zmJ(PH4qfRcP~WMWj(n#IPc9BVEwdV|vt8akvZ}NH`t_?;LaY|}bg1XGzZRbs_EtV` zk|r^+HQ0gYx4e-@yxa8xI@cM!6;=puHT7(}S7^DL+1HF9!I6UQn_yekPA zTo3ks->_ZvVM)k$?54{QVs1Rz*>qT+l4D1@EEn`tv)iia5o?qO8!r25RBaSuJY?#4 zfrpIbx(dlX&F$!8BP);ET`7!*@PB=lrrwq`ulx;8?KKwzrnCnOx=$Eltg(g__H#83 zqj#ZX1p>)@|1{CA19=xThCQ)h_4Z()Tdu|GJvRIHWV{b%He<{{m?Xll)RxODlQdn& z0A<;V0TN{WP)bjFIh$hho#qJ2J1Lk!*lSL;FuUF zcl8$EeH>?sQ4~u7)#M1vUIE_##miI+O||zx9yjanE+l;83~h z0}w^sJ!C}^SgMBy za*&KQ+IEDD&aLv*3&?YD2}T+2f4SPAz#?T5cnsCvKX-Ts|d)Y`f zA3Q}tU&RQUm8v`FBmmoDH`uGCb8w`v4%nD1^c7%m&LVF*hYo(HxoUAiAXrHmX~-q2 zw*-g&87VCB^WZWyM=(0)w08f^*j_dlG4(W87+ofx7#S=t<;|vucw#`L{_nJA1c?}z zLR2QA%Dy|=t@gN}Mo!@` z)3jktO#2$sj|`y+cnGL`6FR)};<7Ol%)Z4ZpZ>*MoV7sUXg{j-Eu%OJ83vgO5|Ysx1JVnMc}BMEoWP?X&fXjs1O4dh>NEd_KNoC zFylZ(%yME8{$7E=?)i3IzinEL0sMBxHkydi6^FLL?LxHal=nSTTeDF zjQf2q(TFtBM)*W_@Qoc^^+yLrGQTV^!Osb5iq9Mka&sCH$B&Fls$byGiG$p=?{t^| zz5C)y=m-%{zSFJDZ`U{V)W%c5*OPMGVdFE1Fa-2Z{>@0^%jFV$jVRNt;+bk;?J4S5 zeu+VlA>#IINc#X0VVSZ;Lk+F6#;+H4piWq*h$}FIMpnvtO2TIo={BBV$KEBpiblC| z1@!gEgkK{P)E}QT#=dW)-i}u~8w}?%q5S34>}lcCa&qzxI?PgavLx0)(yXsQ#KARF zG7^yFJ#Uwqu*0cEADAu$dc&wblU0L5%e|ynlwqiDFj>M~w zUrfI82-P*Q<9f}pqPJ%%E*>!?!2iI+Pne_1>~&~Bk=8un-vpbpq%ougyi9v$nP@Ev zhEIX}qv_J5J~U!4YFn&YZ;C#?2J&h3-}|*4&A}ehO|buBA|edhew#81Iq;oO9iAXe z5Dz!Aw~P;e$5tni{*R+`k7v4n|M+KyNtzDS+&0s_3hTh=)`rB&Q?lpvtGb=QQa=6PWWQd`{ZMw-JG@9kioDbjMyWc(OVQ&-K3E*Y$k8UIW-6 z2fSP{3TS7SfOXq`JUv93WR(qBlxcg-erQje>xflU@|;aWuefH6hXt_bcgX*x1kVp1 z=iOWbP}Felc}8<14BPR1`7bl0;2t1aN`c z6Kxv=GqpDa6SHCEi}&rn3tc!eEC}z_s=d>qhMpx;zA8Q!K%Rg3JThaghP!lqZz&)) z^^k^xvF$DlKpBJ-f`7p8Vt@#k3&M~`drMBg)&)?p41JN~viZ$c;2l5LHk&O8Qn%2p zPQAov5?*hIBZ;j607SP3s{dmZ4z2d>mOm4F%u{(O?DwpVV=Ld{$5CG1$s1PJU`mWT z@+yfS_@V}Dr|j^Mz%=Ie`CDZhed=8;@_+A@+!@W4)ew5vHn_5yGmv)$0IiE;Sz={X z=w=gtFnLY|%-mDwn%e+ZTFz^~64lH+Eha}(>PvnLNKE1yB2eO9} zpWK69HUd+r3|+*`#l&lk|P$6_+fK_5#cA54ZalUC}dbBi1Hj%{w&=sdMNf zd;(z}kn)$I*a~TK`zlff4I~Zb3=V=^@Wt%&XUV;6qLysC!K?JD>F^XF`A1APv%KHV~I`hDHs*0nO2m!ndciO@T&QX>h#>II+HZc4d=6`J!Q;V`BTB5Kn`YSYXco13+`%$bg~3I(dPP0}U(1i4cT zOFwQKMZBVL`}DiYin4mtpz_TzEF`z$Fwd_X1YW}K41hpU`WglAP11l5lu)3!d;IT> zWZ*p?a1-Up2^?1f)JIX>3Vq4dTl(pU&n|toqSeJMWaWo&ra`nEIC51HekgI5Y=WxN zTQ;@T(7@sRn;m}{=b$`xl)b}KA%G1e_j%7OJVQiWs=0$9P@w|?U3e#~lirh&l5!u0 zcb7^x7$+8Er}~pDGU+?GYV*SLx^g7kWyh@b5t#t(N;BNoC5Z)O(W%czi-l%!qXr7v z&G7wQFHA2pwS~KF`jbeT+rt8!l2fs|@&q)4d5xx~J5;o*;F=K^KIkQhVe7&Q%#U>j z2+80>b}BkQsAUo;?Rg=97eua8RI~T(f|y`^ZfXq=My!^vzRO@{dA!#3zzCthiIj|N zhtALlNU-6ioH^-SecKdR6n_zAVk_B9@z=*A<2}2$M4`QjsA=d#L|#=P&0$$;)Ab#5 zETT^aFXAcE7Hf$=h*`R*K{{$M=zErS-UIm?E{UmL0bf(|Cim>K)dKmesj!_LyR_G- zQVZdSsrw-tQ?`o6e6wUrRn(XWoS`=ah`m(Isq|5Y^NQgCV<%1T($wzPKg&Assgt(V zfKo|?Ik&hjtO+KTT>S4mCT^+sW~b6_cwpXRA7U5|3J)JlGy{jdzwv(Nr#$alZ=`Nl z8&=`mfP&_;NltTYD>4a)OR}}uo9gD5L$o@fJNwyuGg_2Km`lj@8#o1_k2tZugJZtn zZd&?4DC+(Cc#V9T<^4kOBxD_Rsd3Y)fIcQvyEn^>yB|`EO~cVO#zU|hd8ekh-C|5W z6<#@Ij5t}-k9G}dLybc4F3dga02ckq0jQNI?sxp0*D}wiHdS`(2;fl8H6kol6xc%@jGG!E-WwPuH{5q>JE&+ zY`diqTOfNWaEYn>Tr68B=JeRzk2%WmEdD`$tNdu%Mp|J7e_{1(%HraY+d|LS8h!B@ z7&3tQ2qlp4)gC*Q*FfS_se@qI20V>wgX-dw*zifFJypzdgvB(wwEnyw+B!REuXyu^ z5*QjD6m9hCsuR=DdXP>WK1DM^a7}`=28OIKa*J5WOlH9@Gg$Kl+eA^tPh-Sz=D+BI zKC~B5JP?j)9lO~)V%0AejWz5Zj_n?5!xVQ-OKmGuHmmwxUjZ(Et&n*?`G3&5tKltr znI8hZ;xhe5EM4Jt7%1j-o6dc4Nfz?O)J<_^h@4R}S+6SMeIPv6JZ-naqYCXq$JkoDA)97bFu|1jJl7qr1sd+6dHfg0oUlpk+ zcv(T1YXS_@NEG)Lkn!f5P?TXA&?(^UyjXq=q1{EM#+uH+eMKW1?Taz~{(Qe)DLa)X zyuG1=DA(tuv6 zy*O8BOX^KbMYF&GR0o7#3P*JZXgzmm-$hhcv?s+O)kjh?9DmY4{2= z6(nzAjR>k_PEjAbL$Y9g zneD*qjkDrnQx|K!C8cTd4k7kqAjGh^;NQHHd`9Q3~9Z}gT?$CX|yK& z=pS`qdN7Cwp%3+?ycrHx-n4lRGJhjS+CvLOWhwh-YM=wfzcP0~`f$|nMKIo*Ltnnf zJzgml1vH(u1t2wT^(gaqXQL&ig>%$gVsYjvwDP4)J0!)UaiOpyi@0RlkfBKmi&)-bb| zZ^I@;o#D>mGBL=tqQF_}x<=?MM&i>EA+OV=IG?NNVY&W4%e71Kof zZpcM0w^hqD(p%N(hFD14b+$d6^JXftSp+sq z*7PbXW#gvN_!Nbw(CuE9sx8D)goYtTMs!EgjRO_%#At~vbeV|pr{Epz3QTA~-U|5- zF5hVN59nP>a7xO)qYa|}>^zE^EaIES8uc0=&C}kj+IBwz)NpI z_ng(NB4A1QCA*ti>EevFAf{%gK`k_RLv~n4W6vP=A$OwNg+25E-V5s7NtiixpsshW z_X*^&t(GLDna~qX4hY|P`?!;dVzsHq8*b++?}`uiMGidjj9$Oc!Bly%&^tSm)<19< zMAoMyuQ-<-Y^U?&gRmWOT}x5vIWXc#Dnq38CTqw~fM3YMT|E#2PeNFL?)*hcqoFmL z^Yfd#P-S4*_nm9p`UJc0VhT&nlofDdHn&zjd_CM{ ztL_iPd0?svQEKeARLxKufi!Z(#Q_S7HUYtzLi2jyhD@a$kuwKiPkyK2%+IWmI5Tlq zO*FrRP%J>9fi)pd0YM>=#2ORhM1IViiWhc7=xe)~{@sz$u7H~r7U+()wYr6lC2o|d zKZ2Ss12+$Ir!M#ly(3!X==qJ&Y!ApdDKF9rr#8Sp8umX(iHFD!rIUu~1w^ekwX?IK z%6;o(DXbY5sx4c<@qC49}9%Tq(z zF^P4YN+ktSZwyBUYSnUWt+YMy+EHb!eY)xyb*8V!%0dHPe4tw<`O4JFLvdZfK_v6K^w(i&X4|2$4lsd)Lw@93^D#yW6+%zyl!+*|@r{b#Ouc9U6T+}Z z^4%{(QEUFDE|5yM8QR;|E(}Ihf1dnrsX={MWaN)QZMttkWDMGkvCV=hFc3(EIl0rJ zZC}-(n)mtZ<6?AxjnFg^V-OjS8{Y2~CmTihkgu*5ZQ3}<3t;!pP!*%j_00+2T_xc( zG^7nWAFI5%%Rk7>Ol5bVkL4eRCb|*6dsGxLzw7pG($N41lkzo*f)#oOn2P82E$s2` zVXCbll^~h$Fh?I=+}1+O-pkx;X+TI3V)RhnL^Po_{4x{6ifi-GujveTjn=~@vl)p# z8QJ)lZt+T_g04)qvDMrOgtju(|DGT9H|ph=?6W!_B+)6uIyhWIrD>P_Zk9KbERu`O zGTIGC0|DQD!0O`vE`iVkyVvAJbB5tD+%Z{~)n{mTgpivjMVU5*K$ntw&>R3S=^i7BzC>gbg50V4XuK(i2m4x|j(u$YKG z9UeMx!!<7`PqNw#PVgLXVp99m}^U#bI#8$4%NRI{D6a4y-@r7k7jsj}-ZOEAOch-H$VjFP_&L9Kp9Ao6F6bG3WLAjqka zI`3R4Oygwm7H*6gzfyU@t0sMLvpBRVe(OlgZe#he2PynvLL z0lBzx?-;n3uJBU3VbWugMUP4A66hK z15JB|NUfbQ%To0O15rWbzss-&ZQ_tcgg;?+VqwMQ?!{xl0M-2VG)BY;g66={2ix)XEPRtuk`%J2WOJB^8b0KV1riuHW2Kijrn5w-aH9KK{lUcz=|NBw&3toXCf z%A6T<#qT2}sgU0sY-Sc+ca)cNUH3})A{2$0u|d~dPQOICi8k(IThSN|+x~f^qEgv7 zSxsr%7n^6`cf?Pw5C?t?JNHgp?U9?CdoQ}xu76iv^vlu?({Zx;NQ>r-1G^E zH87tR7A@qy^mj{sH~bhi>V6n@&fiOCciEOq43M@z`N!)0)6ISc$7pe)1g6NwZQrjqOL|pqU6BPs!~4oW}7=H6{t&xgDprU6N5bOGikb6ghicH}$hZpc*WG z4P_Nep3CNC`DbCRqo*6J;`BBt zX*e;-z`u*9D|}M8sl}jI1W&kp{Le~UVGCKcz&uU&Ue!DF5#?O~Bv`)&|MeDOsEnI& zXO;(<+_%-mo2&yV?bCY$hH|!x^f?-PJziI1ONj#<$8Kb*f#j}MBM~bI%sNka!~OQ( z6GLS>{OFdK!hPfPu@;f6bZ5^ClEl;oC_ZeH$ra3CT-kub7 z;Srb5Yb)$1oOJOiE=8W!fs>{ZPV6m&Jud>o179q^8EW| z%}P=A+dwH5wQHMDE>y66AXw)f)RZ!;0 z{dzX0dq?LBDt1WddyS)0clEA8_T_j-pUYSw*Ip^lVwRl|>}&t$^YS-+kC(0Yc%uVB z-Ds{Vo&B7F&rY--H*tTqBPO$ta#_+pW8Pk-aW+7s+Pk(cf1I{^_$o; z>bDUk!dbMwGLN$;c^qyVbZ9WF++Lf3WnlY-8)# zdY^7wJmo9U>(9G?7623AOFk#?m7GDSJ{R@kpF7v(`ztjtFiZ_T7PH|9dEeJ$XBOvE zjFlLR1P+(L<^YP7U$iT5ba?KJMp+}<3hi&@DO4|@C!c#@99hLF(vT*6EYsYhT)%}W z2s+pv_^n_!mt5PpX_?vfY%TveSE%5f8>Mh*Boz#X)~!MG*L*?oVR~!QB;uYRehXLz z<9O1Ze2r&YzQ1pI&ye1$uBlIWGpE5UIj-I3IeQv{Nr;W14L3zr@~yM2m)V=cAH~qr zHo*{Av0r81URDo1(fR${Q$Joyp(Dl@2SV^l8s{~Eqr$(s&ZvI#i#s$c znil5O$J>`2_VM5UQTEwqH}mSE(b~%s+DUP7Yp-RmZv11s&mC5}MG(9Q&t^Q!^nG%! zjSa!ksvaw0?l$~}h0J%+56BhDR+`}|GDOc?mDc&du9Ek`h%1cLMspguINAEfwzM)i z<$@7J{4!|vZ9kNBYF)*ZK0Wm7$14^+L1E&7@&=!+2mkikZf}DP@x~xDh>HaQH;dCu zc6szZyEuMgLIc$XOi7X1mlU$4CXww=w%r<>ggs4(6U~lVNINP`!?SidzTN3qa74i) zB5Ng}b|p}~;hN2YO~C{q&8FoZe<@7F9$Yx|$MK^(^;rq>I@+-Chx zZ@d%1v@7j{^gFrbvYDQSpf&P;P@BcM9c>RhjQb`oEUCT@b8QR6TUi`9^(7vDUF)>C z0C7FqR#3gQ-t6*L8(c1Kx@p7hm3g;X)2&O4GIoVnrjA~CZjIhnrS13Lq(Yo(qc4Zz93;^)854Ev^O#T z5Mo&D5c574%<113sGK>#R}v=TSb;p1{igo}&ZkaXMqxq)lfQctlfO*5Ii!BHHqT%J z*NU>9|6o@a{DSb_@<+a!{|}NRoIQ&@)SkNR&REv0$<6jMeSF6CgI4zUB4QfUJg6W% zBbEE>Ad3m-9KnQ$6Fw3Mo;ywWA9_&}Xa805EM<|D7=nkLLHWnu1n9rqn`z*xbEOH# ze~HtKw+Mn{bf zKG4Um7_^SS(JHWYs(Q&)UG^pof0D8**aoBonlYM$cH_D@{6t-RN*iFls4fGaB{y}T3yU0)pi-LZPRW?D-0hdM7tI~|2#jsY3u z^9u*%rd?+VY=>nv!M@A0$C~GE499C@sudAH4P9_3JH35!PY#Iq!9APk>M8gDOLqTg zF;YyeCvN5*q0zX+F~K_d!}0Z}5%ia9TW59&@6O*iG+;IT!S4Q?3NQvhYF{8B+bSUZ9ih0nnwEVf`#eP3m0#xs6i98 zdn;vdjlx50?LGTrpSgQ~BvbIR8@?`YlC02Jg5Bii&x`>~e%oYLt^eb5Jfp4T=+-O0 z;4NR1-=E!OI7};y2xpuNx5D)u+dkxBT%X(pH&YhxoXNcO7^QgrMBr#-MML1Fj|mUa zJJOdB?C6Bo2P$z6z9ja+ic=sTnqsea@A@nu(0_9=jtrBDvt81wZtbvEox+9?nCrK+lOM5WBTw@Z?6yY(8g@8^s9=J7qUXOOGv3+Gh@~g8cv9W*#Wb z9Z6oC_O}dL*@!A>ed9RW`m$BijQbcJm8$W06)erE@RTw*GoW2LVI4;Yr0hrceirwZ*7BQC}rJ6!)Ov(=y=8kTtNPi-@NOe>Pu zv)}o%*2)gUiEa7g+L4n8V49Oqtd;ig?9HCu$A1%ubue}$!3rcN;x4nVh&~;K-`wNJ zj}evxy6-xr?^XI=_a2i%M0$P`{y-!ZK|FP$8 z5hP498n}7Q>uR5sLi)4riZn%Wa(nP68vaaUReWDS8P_0^aBd{4)bMP74=&E{;vSrs zx%AB<=>?+o^T_Ir5*?Jg=KAFEo(j`-ru4Lv z(H+11H^W}Wp~9njBg17%Udogr z@62K7c${{Q=|8Gy+1MwX^(T#O`w2c4(!`nCg_n&dG!DGdyhv=4pp&^m5xLmD?%BaP zynai5N+aUB%O<31%Z@7}Z&$o;S|8ipGTjmaM`R2Qf&usAyLIx=c=IY#>^HxnDs?Jb z;TRiyfoIG~U2I)#stOb>#4H-n3Y=1LtQfj&{x03r5%D18_HW4%Rm|EiLP{`k6l{+0 zGZTKE7e)jZ5ugMHh^k7hDdRO8=%m3L zLSn1KnADATu1uG=)_ceN7Qm6tR%#yl!@;7PwaUKsF2FB2nYobx++rlZS@mYTZp{AW zpT;kL96GW;?nhkW@c!|p?=}~;X!r);?-{>$m;6gXVtCc)y`C47Vo} zFWmmgbtkvj#*?r3|M)HNAj~L{hIa`n{rflWP^*4B9S3&OZ z`$*)#fA3bFDqeKYHgl<})9z!3t+=={ofC~jDEP+NMZcJT+P+n>jiCV3IIJnI@?EB*`EhezcqA!I3 zZ#R73DxLJr%2=j#NfPh?M0V=tDyLf$96kqv&s!E{88? zV(&JD-?=BAGcyfT4e5@OcfWI$dgzsx>e^ae%~SWPkRqRUzDySstBC(PmK?F%x5bp+ zUDO-sm$&9V-;w2sgFZV{b8=;PLR`9vMo3pve z-S3jN9FTF8D%)$|D!G4h=^9RxZBFdzR9p%^rM(8_*&dumt zViU$VeW2-7>Y~xZx(J0Ex1JcgVgmzPt#V0)RvqlR@c?FZD+K2|v{bbi@4HeCWmGqW zu^)+0bv5u0JvD*;rWx0!NdJ!h;yros_Flhit!@;WoQqZ<=@BvTMLY{*oDU2!ZQdI&3qq37DgZFPGXCk`D><^|hg;q- zl8B$I{3~C23rY7LVw9Zq@;+*A_i4L6m@%E}<+(t57&D7rjU}Ajosn*SDDgw}6Uy>% z(CT!^Zv$QHdsRhi42c|C^xLdz)Pd3cUjy&hXFJqSASLjE2rcWA=R5fUDox^N)s!@;+Wd+e}F z42o8GT^^GbCmH3p5NAIkXqRp^Cf0X8Y$1L}iU zT-<6*z5|3Ky}5Bvk~do3 zCXAlLr`jLUtydrKcEHx12IjLMm2C@4-$$&zOS$|!{uJg8c}|3lcfSY&HWmrcg@s-e z1~Hp8%+lBCNloTtG;O3FAzh~fOA8J7R9Kh`Tkd~QiSQHa=7fbn=%d*4r@A&$&O5kl zh`MbJxNch&c4Rp+Kqw7NdU9`=LZ&vHT~D0nZTdH0mYr_3yoNvGW4zT8d9BkH=LnYc z26^Mz9x`#pPe03})Yh-*>`44he3l`7wJI>*L3mKw+mXLh!7rU4697vGM|n@bu#7Wl zR;8vi<>O)$BHQ!|R$qq&j6&Vfk|%#<`YeI|oT6L;s5rhY>%G!tx&V^{H@9wup+$%? z2rORaT?_nzxaAVH_RKhtLuyb+8Z~h}t}-)#&9+I;Zx-hOM=v25Y6XUHhxZ1O)Z|x`C!Kq!YHJ&4Lxx=`11+R}c!&7>$3b85tiP z<)TpsdlRpD45EW&3t1lA_i<~|ka_7wH2$N4SXh2A+9c@3oQSBEI!}%n)s-{k z(YW;qo_p?9Q|ht=%2qHd@|=_RD!>vTzHa{m#B)E@e(@UqU87z_+XWwDzV{TO?E+Xk zzH-fq3if6pjf9v#sXLS@p9jG*x4Uh`DQ#i3K5mjyua3G=&d3nBzU;N?_lyxPOQ|r8 zmco{2VPekAz;sSGp0>M1wmNV#^2(NWq`yhfurq-OlN(;EfJ3U;5FS?9c>_b#4#V2| zYWjC8_eU}ZojJEJVg2q$_k(G#+s>i2bGwK#Or@h-sS;^0@vSNNJpQ0I?+x3Q=xgiO z?D$gAz>thT_ntHPGmJ$_RhPeDbOg;|O=sesTs_tJZ!@Mck+I~`<##?)Dm;VlMPJ(FQs>ysf!eK-Z#nc^|T{oR5V83Q5#$>hwBPa z<|Vl8_QuneBr^t8o$4WmkJQStmE7z{gk!=X=hBb^h?Yvme9nS`=24~z{V+^ZC87@o zR_oQ3qJa7>Yd2dd+15Mljgoe0NHoYb$_#4W=3tTle8?@>N6e}KP{6PtUzoZaUEOwl z#(BGDa4JEt+gh3cQbw*fBKjxBqwAQsx_I-;#xrde(u8Zp{+Xmh=AIj2j8EiKhDu6V z?DZ}B&$ZF_s!ewE0~VFfmQO2>RwdGja@!6>=7BkgumYe-K$i;+=3 z=A0bgq#?g39I`mLZAK)&O2B6@cO!pB=`u?Q5 zlijt>nGn6V=k{Lf3zLmT(kGB(c9H6ff6KUtj;FI_Eyn_7IR5g4wU=Ow={h%nky@C3 zUfj7~fDmEId5U-ix54dX({SgB2sqX>YSP3d_1CpZ_Abm@=!)IOIE|4}0JhLC-^XY; zJwPC^$qn+x-yF2oe;S6bbWWcxa#}mlTPAi|J~JqK*(#YD`yUY4S>;DNG%LlpT6Ox;5qWk3|7c!#1qMH=QCZ_54Mpb0J!)OQEZBwp}g z=s#2Y(=e9z!0d}$r(eC8YFbuso&WB|J!(5yy=!1iZ`^p8n?3{VhIf}+X5W>M{#9>> zr-$yyL$LhL{lh<4C9t-(R&8xZ*W?O2vxkXdFhk6F0Z!)Q5x0EJqF3?)-musef`u36 zVr~sCdL>8hE$h&~&5Z*eilq&NN7%FtmoCVQ-tm$pP7G+8+ED9DsyP%?hE@gkUlYVe zBvMHR@FCk@Q)0NgfH(b33*kSKcGs2-Z;+9^MrI^HKB)Uy##EhT;ZMJ<-Ht~%T!j6j zjoA2;6{i|ahPC+8G3UG^HwF$7CV+YFj?oa(0{OK)Ja2G#MFlGWs*lvwyZou`#Nja6 ziy_lPz*TdWTs;cwHoa{?NEAexr`GNAac5f19-iH_eD(!t;aR1s{QyY1{Y>2&f5>>l z{PQoRr&;ha(r+Y8_$?xexF)@CRb30$LBaVQ%wLqXvI@;+q|yoNkrQhbz83AEsOe?x ztk*SlI41j+bZOrU^i&B=?&u&6OKIxZx4z`qEMLVb1VO&lC6Emi|VG_0u`2 z^g`_@4@Y_CYem9rxK_Gpf&t&m43Q}@@*NUS{!$%Hf2>I& z%ND2{j|dAM4vWMaHdwcbGaRmk%6rNwwBfiwwk6O~=J*qvu)`fiP4$d&u@7J^TthQ- zdp1E@kd*TaO@$!9G=q#F9_%SF>vG`pqc}m?%1byOa`n4(it-V3;Ih49WVq8Cv}8XU zc{XwO3hb%D$Lc#&vU$25YKFs%)CkE%s!jVDT3HB3PF}FnTLUQu=5ab8!S&&@p0K#& zMx%y9CJzPh6!6p0=~N+6BNtYTGp|;AnPLP~LcMv$I3{BH&B(v<);X_U!0mjOrQlnrm^Qq7~;HysacIrtN~Q zpO7fQtf+p-hTvD|twhj8>Gl}xLTUUD`o(9QU2P+sI59^DO`xy@IADJVu+q?bNTOR?f5YzG#{x(Ee*RR+Y-<4~9wL=8gH_mHGqMj6 z;vGRCWeLb?xHbsu?wD!)8oH(n%c!5#@0Vz$VX1De0iy0-g4D|Z<2wNWLxU}gccK@r zz=mow9>(2Un zibfR&EQH`I#F^TRN5$1dnf`JW8)(z6qB7GSEL{G^=^lMQRIwb!Sl4?so1b@EGQizP zudZx|vt4qr`c8=-rY9_q9+6)wA4HmG{Pn`qEup~Pz4#M;k<6Tsf>(~GKys@~3KAy~ zYd6m6il1Ra{0GkWIn`3ML0|YRQWr!M46BdDtT@7JU{WFY`Nmu#jYRzHBe=XcQ2`~} z6ce<736o6c*(t_kq*+z0M3VJvAfL7}fM+nHrp)6K&x1U0#l5N)jaIK5m7*0X57llN zvW_s40ZIWUxJ|T&hXvS_tkuQE0i|No=CXJV>`zIXMbf|#XKQe*Hkfk!{7r+g=Np$^s- zdU$mhO@C#@HVkLjBUo{jE8kOyy)h~68)^_*B?%HVI!LXf|1K97I$qtR+^T#LIN&qwvJexu34&9xP`G2)kH zMf!p=yHAw7P+G|L@n;A}fNYPOuHv0yyXi+XxU(Eie27<6{d7B9*eVwrzNJ3K^7Lw= z2lJ}nh>kY>l_H(dgfq|V{fTT^O@laiOjr>AhDxQ?`D#X2*NRj67tbale0oYIaHbez7=J&{Wlp zl1+U`Arw`ui?=^Iy{kaAaFz$>YWA9Q!klTaH0UfixJb=^-;JO?ro+f)6$r^ zNj~~@La2GU%ajm%=4c%@_lc z_&2R+7Gz0;^RYwDDsh6A`$p0>&@R{?MH0BM7r8n#od;ravDChKbNN~;Kc?p)#8?SZ zgFfmCF1$rTner3g%{H#c#(K!jEelimnqb1Qq>d5I4;18CSUioSL%ZX9^?ZOoal z%^Fq{V-xB8M7RD zgTVqZ4x0wq8kOVcMBKQZxaU_;06);1nu5cn59lV5aJmu9t4GD_B%O23HX1 zr8TX-YdRu{$#*)V@r5jNrPi;cjZ`R8S=A|KDN=Xut`Vthkx%Ck z8co<=UTn$!CsAk@{L|5Sa;|%rCaSr6-x4NhJ43oolfb*4Ko=gnml44U?~b^yNJ##% z&Are6_M$V zMu)LOc#z+Fl?lw98dNrXb7JK>qvt6H9>_Fys#NkMiFq{Z~SMD)uVC}x8J ztw4&~7k{pgO%N4!q~3HisOL@0f&0fAA8SnL0@_qBXoseu1E_mXnb0&<(wi}zUAsA@ zF%(n0?0m_3*c)8*=ht%0kClLxkV>?@E==;wiwI{U`q%V6x`o2|^r`Of_HGn{)Fzr< zNw_Lzg7-iA4p$;lgZ|!8&`D3PmhRH_+Q1bZ?tAX1akpv8`HYcQ@$##a!Jj5VQMh-0t$ zr^pay6lR03R_Yh|o^fHDPDtAvF0`bi)qYh&T775}sU31(zhAW?ky1BjJmO6E4KoCM z`0OA$oSrNDbU4Ny93sA4nwt7KJs%hD?zzI>^msb+C4){;j!diEp7#W zJE1&)t6Fj*a_gp8OF6MdZ}<9D8{BF&g)*H5=i|^fvHTK}jT^2Y()2S_W8SWYruk^o z3u~4?ojEzf^jKS>=x(S>yV_j|=*;}tN9T>$cM^)X=ia4pYwnP%i>X^_&vXq87>U=0 z_AcL~@A-4_><N$by<{qO&cpV^tEc>2JkxZSI4d2Rm>|8s3S44076LBR#)H~3&gDbUdB&wVZD zW~JblS!m~nv>IVKj(VnigpX(kks}ie)q!Gv%Ke7)mCgHl+)kF;8?8D8Q-uNjFr=V~-jf&Tx@4IcX;&16n z;NP{FjQLL|lx>rIdfsn)6W2)Ilt1%rAmq5|)9(mO&`jHPx61Gfvgm`K-NJIPUl9c+ zj*52K)6Xs10Y*92p#Sv2={jzL^&r-#I^VK0)E{3_uQEYC9X((C$I9PP(;xRBE>859 zecxSE$JA?HEN(~7j8+pIt#9GA)Ju~r1AdOy-Fk0^|K*r>|8G_)kp$>Ay2-_}!+SWag?iPwwY)!Qw5_)(Rn$$yMyfa?YW@!m$9Rh-C^lqlop7f4 zu>X79!8Tt{SCx+kYLBQRMif>Qd)vhWUA=1a54G_G4=*O8k^Jd2kNj(E^Q zH$z%s?$Au#tbzlQi>VtD5Gk^Y5JeuZaH^a3m=Wf@Qmg!`I13F~U#JvDtp0bvx9oW` zn@B>D^JLEZ8h-zAws&M)X~p%8%^s#kT>c~iJI>Ln?_ECi{9Kjsr=7dx?7Zeg1py70 z`kpu5{b8;DnYr36Ym>`<6Z6qmr{z`|l$fgi19Z44guQ(Zk7F}6U9IBb?|>&e{!`lP zbBKc*|7gFgtf?MFl&c4O?d!C&+7q}r3H%xR$8EMxf7e@xJEXZRM`|NYxNZOU?)6*5 z%T6rL3VnrMO=h+38T z$X%IKu;P5(dH;Aadwi&L-nB(x6mfk$vN}(vM43;|s7`AQ0kHhKiED0vP85HSB&L^t zUTM%(bx(Yn1&YiNUQZ(QvfS>UPCB7x?|;_kY=%WlqUX7&$2UeA)u(?rmg8_4^=lhx zAKOMkw^_}a7#ly(pe(kJNza|U_nz_Pjl;fking3J9)~X7h|EviF`Z7l^3|#&V&Bn) zvSMS(fBRKwe>#so)}MT}EQX?k6JAX}z^vTpe57&pF=?WtJiqMA*~V^bospifh#Fgt z&M`a3C9g~CO`Ge6CpM;hUs>cByPcjtE?kOIcN}=$Tw>9ed9Qk|3v2seA^>SEVb`>= z=SPpvC3>xMTBrW{k2jODt*z|0mC)!4`qdqpPq(aGtRX~uUlP9WJ)*PZ&WZd}_Ik2w@aONwyjoJ8q` zb4!t6u;Z<&0mf%14{1ccyR?xuvsimuE5KyFwViBEKd)}j=R42`BEkk{PT<(jrGK`L zGU$5(WUVy#9qx);r%^tuXN`0kq7)IqE`A z;H0k=PH|NybN^(E#(#jXM-AV8fVpQPMGMgAZ36>aGi58fth>B=s6sm?F?_l8xct>d zLR)zvdW(L)Q^|b{98#va|7&@ z!uW#VtdAU|zVZKQ$d3`5Kk9ArL=?MLU3@Y_0r4q6Z9hqOH?oxAZg7`SvzPt=uvq-C z@%a|%Mds2g5CSa zZ_|?*U>q-Tm#c9kY(o&YCcBZz%*$?LKAps9(zM`*VAYuZT35I8de$t7!Ik|x1#*WB z>EV(hWy(HYP{9E6&>)dO7PJn{E7H`ghIL zgCS>gm0$wM%U`@M{460$@O2UjB-xW0Zz}KQ{+V$9g4PrK0jQkZOp9dvhbDQUXG0gy zOr+q&a7(0EX<^f>XC(&mo*FGnkbXfIa{0FT;+d=HBU%w5 zb9u(o@k^>1qq{k&d%`$6YqoD_ea_Nh@F(u?D^9+_!MD#4!O9yDrTh0EIR#ePc?~y= z@@GxdaCOp*yrlG_cZ~%i)|rY~!skdohDMZbYLor{x6P^~UP5Zzzb@#bxiR-S=tg_r zhYV%+yP^va+#3W7M$+bR+_r1AJ^W{~VW^gx1$9^7)L591r5mV!eb4PFeMWIzymeU5 zvge~dlozv8q2hE+qtTi+H?QfgMyjNsCuRSK4{N#j>}Zx%YPsLB9_z*Vwfz1cHFfHS zlw{WLP6!DtNc4z~&$UXe+vFh5Q=|Ycd)DxB1EXJ8aeP!*|%oPx+yL zD~n(PQ<4Oqq}Im6ZePpa#*@IsC5EYXiz}f; z%>{-2l%xy#uyV;WS3`Iy7fK=4EX|1!>dMZl+f3_I{2^iFTE0&Hnh+3t`RZ3kGM5f{ z!h(vLSA-mXospG{O$|cRjH1ArV~yiI2pWNcE#N9%<($3NyWmsILeS-_qDl{#z46VF zOhYo@xw3D+avG!jVwQS|P|cm1ADgLk1f_Jh7% zT{ND*GAUm)+&GGsTQFmw`re@iOua58iiLwElob~hmj~G0g6o6iFY&Kj2RwEyiq;F3 z3KDv!!dWHiMK!ODUigWCbrF-edhf=75UGsq21f1WEUhN;n6q-QiAi{njLcp0d-B5- zZ~fA+ws~ggP8JZ2aQ^({n0r=mwHzbn<^K6K>PP`e7ZE88WE+EUwwRSN(Tme0i20ym zPo;+3M zw!u*NUY1jT`%=439{(0$hzsqPbpZ19gr%VURd{Xefvx;)S4jd*p@GXu4tV4`031+^ zW1NhYE%F$5teQbRw2_3x&|hEKenJ1>mk=|RqH<$k(b%BuL+yT=_%bqu`OJx|r!<6H zlQJh6I?Lx|rCkxWW(WKSyp14bh0{mfu0Cr83m++3!Z7P6=6?q{U9VG9zBA_1EeIih zg0QP3{?;tid2R126v+Idod)WGgB9-k%B5aF56^C&0xN3Xa{0S180Am*(}6ElA|_o6QBmdhQq7WURJ-v} zj|^jSowZ&ad*&d9>u)K(`SZhH@v@BU!D_Qm+1@L0Lazz~Q!NMyWbd{*UWwN(&9c)3 z04troR|-ami2uAHf;>{1V13^I_+z>HQ&Kp7N*?>11-Zs!WeR@u@MOT^4eUsU;bL_V#!^wUIsO^vhNotR-9oi#l^xTZY?JZ(WqvSg^dQ##FAGhQAP`xFF587RljXd+px2 zj+`=E9Qtav-o`Tl?G)3kCDW5zR|vz)n77u}^~JNn~bHKn(ks1m|r-+Ntoafjg>*?w|KAgfm~E9mM$&oe)#(BlnVH(-C}6A0q{ zo;9G`cJp}k73}GcHG2IIyE*{#GS^WJ!!J!vsm`C4RZ4VSCGH!ZN_p^J#1dv;yeWHA zex$o0ni(MZZR8V}8R3@QiNEp#t^1g_E*Y3=y38_@^HqUlk%CwAZNG=%hEm^xp>GD# zGJ4cmKCT`VSkS`;;OoOQ%OA^|`WpAKEww^#87+~e4f0tub9L!Q}Fu5f7LCZpXE&~%9QR6Dd4{1Izv41IJu-=$t4?uIX5359P=65_~y-=}Y&Xb+#w zeklki#%M-ivLdd;wBdiT0>AwhFiKLbAenA?7zK_De?UrSrL|)8#RG?;qD(6CKDL=& z%li+|0u>^c^F>br*VHsdSNr>+wLw3Ieo-67LhjXjG)ib38MSZ$(GssU(&K)4(Qdfu zKPOW$j~B0#A4A2ol8EA@`GpIFI@*Et_e;)n%QVi5|@v^d7XV&05&GdGFD$FQ8s$D5wf80KHVcj=IqPnoh!@P0k3~Wk5Iyvx*YO)hvO3~in85-QCp)xj_a!)W?RTp|H^Yk zi)Vzt?Y}+q^#Btu6kQP-yt;AvP`_hT@|{O|D7jWvHXaY%yGj)KS1i6(8qg$uPsmP4J0fZr|W;Y zwhtL8=n;xo+TTD{<==jJ@A6gI_{9X2KGk-j7@bmhdL&luDM+V)Qb2`b{$^p|zp>MZKeFN$ z`wD;30Y2!E5aC&YBtdencp8^sofVFg+br=_PPO_Kd)z?IglymUN}Za>nvJo}PgoPZ zJ7fV;NdP|rzb5%EJ$&6N6j+h+4${_~(zJ!N%0L3XE)4igv`|vEXme< zRnP!(P2o7Pq%kjiR% z3KMQF?s9v-$EXSQBPhPE+tz30E0MCLpRMGl9&EDt+E=Cb53fg0u%Cl`6Zx&hQ7LyfYPCMbxDmczTnp^3BL7Ag=8i>_u+;_#RqXe;MO_`OxdWcASUiEawpPI`7cQ( zld^1~HzEpI)n$K+ueg=3s-%Ojx-`&!=)`Sn!JSAxvUVyAbP1!Xmgkb#2j;zH%NJcW{iQk*ZX(c++$4-rm{s+ zTZu8u)7^U-iJccRfTat&Ia~Aj#bE)^CR)90KW=bSG%_)V07|AQqBCm1`QEV+2+w~efZ9*enJ@BXFfx^mcr_ya2u z-jyq25%C)2?bvvvEtl}EpQX64qEWW8L!S_jw6bFU^nH~owKF?&DLgAC5z0)WGmBbo z{qTP`RJwRScn&kc+;$ms5$ry$PNIVDm6d7|=C%RtS)1qvD6a70$z&Q+n$e zOpxS887n_(X89!y0pjPKp5HNwW>@#Uq$%1qfJP*BK;AnRV>^%#5yC*vPk@F?3mqd? zVT`pKOE5-?s+d#^=#~lYEf(bCtf(r`8ODv=WXIG7`~KV@r4S~!@b2ZC;KEmXJodPU zc^fN%wgl^|vOx15#n3j(c~FsnC~XIe(M7jgLH}Evzf0MpkA`rO>IfZn+B17jD`;h; zL6^N0@~?W{FdxPn22H1#$@*cw6V5BmCb{eTKMVty?M7;;U)GV{_VReFdYsxs%myc2E;Zod{7+ zSlm7VE2yRk^NT9e(~O84kpbG{CIl&=i=0a%X(UjM+|O*$1Kfl;o$MKIu}0o!JcP|x z1r|Wo7jLte0q3KCWqT?GQbPH6c}dDFByr^{=2)%*kQt>odfzNroe2rPw9MGglO)d>?O4aJ%=k%gq^`+wL><3Hxlm>tvu7&o*`=8o*ft`%*9 zRgboW^^+J{^x1ZhwiMUsfu@gZ_hsLMhL{?AZ3S26Hzy?he?D5m7)~l2W z>v+!(W-hTG`OV%86x^h4)qZ{80SpGZf=RtjQ$TCa(R$lj!F0(#%tT2#W^-X3?r8=i zG{Hkw#;k!KejQ!G%B+`LV3*tFSf3XcJ5l$hclMp=;<^p7l7^s3#9;++3%cH@(7-vb z#4f~bTVmJL;#`cb5m?abIt=}vYhmK0mgbA!tV&UCUU*~HNUiRD-!;17Eokqi;+{9) z+%~N`V>x9{4^|}~Yx2Oiga2P_p+bkDM(_w+tQVarP^X8 zh)xJU7p|Wa;fZ(>Cov%47U^AvcGjuU%vWV`KJffwPY^vKY|*N>o{77P@mfZUls=X-F^- z)n?f9;LKRO_(-hTiKQ?qIRM<&G5+{aPR6UJB%Sl*Kf5p2AtQym*4t^mU%UcO`1cP_!ms&hAGJ3Meiw)nR?d)q0T zMT|1>&QKK(^*Ou_gfeSYJmjJEnJ+%wft8cSn#&L~YZdQ7!H_l=wNJ@>`mnR-Tnden zQ#b?j^dMRRhvVXQ904J-W6ehq;AQ>Zv3h-&i5W|oVCy#3(3ZxN-6}Rp@Pe7PgT{K$ zhMTG%jO@^wGG}6KKaD!Y)sS*bEQarlmlFXf*nIiJ109P@dO0bXhdE|GEW8NTex)(` zsWx_{-3_K__NaqYR>;{G0or>DinPnI7eDGxu;O|H7t|4DGo~Jrfuv0S+f|};7_-`+ z)+-hu(n`mJ3RTWQAWX6eV9fuWdQFf!tA+)Zpz0r=E$5q?3mxrN7XW!y=6)b3e4tvc zm9Y!D8Eyrx9Xd~8k&98(?k|&*UX+~uES*=X@-a!J9L81PwJmInW}L9s&mm*2!`zUs z1=5W?xWxiy6}?AhwdeOki@GGIYM9+W1GI_kUQyuQiMoo6_ry3#BMaf6*Hdii#)8jx zSV>Cu%E;cp`k@7#ZXt7m1xX)+kdF(5l(+^rg>_6|U@~M(yWwFMi2U92e)8hxA;VID zRKYF2dBnoD0fh+myDJc>e#q7LSP~%F!03l@{!ThoZg0+o{)U3f-JSB9o@hssIdbPg z$s+^NqgzDu0sz}65JchIh<;sAxjjr4#&4?8LUzR*5eOosQgbCm+=3Rc{%dMdQtuRGl!>~|ON(!XN>QzYDplB8 z;ke`b%N}E`izD0)`RM4P8nK3hoRQk&$CrS}myZC%>dvohD0sJF2ZLpH;PXcmAQpIh zdEV-0uqULC$ZMdR-V8^-E36xE!Fx;V4E#_+I^0=AaHMK@cWx_p~#3r2Imrf~z?966@{ z4FhoSs;4#i+oUiM1P((+qL>~b^&%mS!?P23V_Vqb?oRD{UYjYdo-u-P_q1-&*5GLQ7*#}z%IxWa^Qz=bcB=5?0cFMOpAve5%R2Fv@*f@`Ew{{N59^uUY&VcY#%_Z7 zx9LNb#5x@*^SHlL&4jF{mjnYrb+&|LJ;`sF$tF6m@A6vFTS)NFxA4&wh7pjBoZbir zO*Ah&E^XP?h(Mw=?7Jr_?G`u8>VhQxzF6Vmm*%tD+i~{K3`PTwQU#8sjndY){3 zk16!wjQJu+hr8zYZ*N>|V8_|xOFYSc`^o0kXjnKKAw~7R$4YNhNJs{31&I1`(7UYp zeD6yIZ)@DRBOG$E>jfU{iy0y|j0#WYKV2)cb0OkQz=IH2K0%=5uE3}<#mD0Qe&pYj z8y?J>w{K&Nkfo&pLmcE0 zF2Orn=d?g~*#3LS0h?EESaR%sljeKcd>~bX?gH{PQ~qw((s`h?6U4BV)*NFaBq4}Z zvx8fmh#-aS`Nd@H=7+!$s;t`2#0zk^u@`!zFO^?#HgDTBVMKuo5l{HN*2TkuJbr`1 z=&4?ACzMF`4nZrW2l9Ts`m&@_5+V6N%n|UH_NJX%l?c?|wsFxuAnZ##ta}0Go&A)+IOQq4w4Q86Ic{$OeY2b@JW^r8E*Vh5WH#>i7(PGidPEbfc=gm#x{{&cvL zjYV*sjwR|1__VfzLOc_VGt#5L5vm*8B%kpscy(FwkdQ0(j!(RSXO| zPWA~$HEezZoIRv&MBBkOih>+lpzH=D03J%cP~V#6#1Ls27T?F%!S7?14jfh#TDb zG7TA|w#Y0<;>7ByF*BEV0kSwj!p5&y=o)`Sl)W8g^vCrfo>SaV%v%DvFIAR_B-_#) zt#grM!jdr0|NZXZ1AHO`-P*}Xc0+^*L;2jIn2dDnoBdZAn%S990e=otDh^;_l7yt2#US*mAER35S zpkrn$4_cjRi&jPYWlCvlB$KisWkReu*ew!aU%%VDgE#vXD?xpx*h&Y(f2EyQj^6DA zOWxTv+zu1^x#dZP9OIZrYQn!g%3Z;w$VMWdG#ZoQSVM!E?hgd_NLqR_VR4rPeR^CP_YSPyrHNCI}j`fl=1|3mvY@L!MxzO|CtXtSePezw}NEk zi^PH%zx3!eHQooWxDC*^o5@dJK*Ki_YUN-+6r3w_X69ndYkWdQ~beN8BQ* zwHORTjPQ~|5(%~MQYz>Xz0kK`MBp%hyjp}dn2(nN`BC_u8MM;Yj;LYHnQbtpa1W!V ztPq$+?q894x~@9HfJ;zBcI=!Vi%Q*qgS~>ul=+HxVsm*yZezbGDubLrf}sQwPLW*94u>Fu5V zIiZI|2MdFOWPsV-Bhy|gBlZ2Ug@vpnM)NLGb}PW*s7WV>OP$U)i?ZAfE)Y(j z!1HfJMdzsjY{1Jn6@5HYK=|J+2)9)!q(C})8H!R05e6Gk&l_%ma+!Z)T?&r)7sDtd%Tow7t6p)qGD;~+0wkq*c)z-x;EScL`73hd1JsIdZt0tAS=JxV5I zFzf%H!fgwnVDY*fD-(c==>L!~$YZS(_@0yBEu@||15~Jlc-R`h6u2b?mSr=-k0ShN zJ?P`P0LbBR_Xn@dNV@iZOk2hbB7w%Rjn7o$yni+u!z?!PvWXSgVAz9He6HIq3W%w^ z2Uk8!iEt#3jSyrh=Oumpy@FoSK+|)AJ`8cNfEd@RRB?~s2Nr?Le4H_;yP66VxUI%onv9> z%j`E10{#?b1^0$*(703qEqt?9C<4bZ?+I%ip>3A#WMt$9fp-P~uQo6p2L=~M?VxKe zP?A&7=DaymY&2~>XgZkDmk@6V&Y!E|pLx-nQe|C};W!y#gOU0PI76{p1_3@qjH3w4 zW*Eb4l{lhQQ@^5nr`=t(VM|~VvC1zqqoHR%5EIaEIt^w)zAxU9iAvwu>g^J%)u3Ik;%ZM4=WizKW8-$(%a)`(`n55 znM=mtmS3ers@AA#vbpSlvCn+l?&|P6$hP3(ZnJ4l5f8g-A`>Cytrt6Hx~NZ$7B=8k z0)UG8Q3dvZL&{4KiB8}-Y6Z6b&j*t`TIvi%ou+_}dUbK+XMVFb$EFn#AXRUT7aB=O zHERVgU28=TRANn3ft$c7?Nq0oXs7(BdZN%AdOrCE=v#*laxC<5am->suaRq0123W^8O7r+#M;csR&2jtZUVQuQMZoyRi=Xb$e?w<;*kL7W+4Y(jMUpX&NAH1BnzghwP2^DK!?Nf%bopo_?_*)^?&AZ%WB5 z*i?~gHQf-+VnyJk{sSud@_t`PNTBd0qv7xZNH$0spC+5n_g7*>^%i$-IW`Cic0v2W ztGMZ}_y{i&SO{`=Uv^fT{CTTrR9Fm}CFk!$*zOB}2MO*!pC@~}PbuL=7?`hig150k zjbp^{UlgnZ=1D!S7bkN|8_p^y`Z>T-7;EV)fFSsR>53#VBDofn-gQ z7wa!Ta?IKV-LlwBHnN;2Bw2pyk1Bu*67^;n~E%L zMJcq5vE(Li{$uJnm`3*Zwof!=0|L5nW>Ol&0-lwe8(vM)0O_=5c_ZQrGrlTYu}ef{%e z!-G2j!5g}*?EcjPk#?ZL{iA%9jwH6)I}?W|q%`kgME$HF=MUyCwRVDM7BEdD(CETO z$v_HiY)w-*lxedCN-U0GW|zBRK)3W$@AiURq)nzrdy*!siJ5{0yf+Z|^dEqETda2O zG%?27zMqo|;n!RWmcx-g9^T;mBjVTur$MPc;3KgV^4UwJ)EL>`3}-;|U*zr?MX5EJ z(IP33P1A;==?BJJV*J{`JM6oQh(-*NDe zJ&}M2x6?Z+mX=U27^08~Y-*DmA_)2GJUgmiv>T~eyT93D#3Do?$-nwICGM!vcM=TE zA%c^isYMx*{}2&e_B7zUwD5Q|CH{GCY+-B|YMk;S^g<`9ao-8>fX2}=Nnk!iR6AE3 z7-RA{=av{>3^0k}0yB223~)Ci`W0po6SWrCgixrB)KFV8nhfgNESL6Q7bp<8)SzhY zQaJuF>BL*TI!jdj%=YD2LuVH$6fq-(_5jYRCA?LC{(D{Pvkq$ra-B3;c$W$Ff5`$B zZ8uVhxPC&4xa&M}I%_{gL91`%5pJ&fNX%u$;^>p1 zuaKXV2IA0nmk^TZxryoE>M_L;0p53`zu>_7aPG6A&Eb)NQC7dfe(vSkfzyXH|80uK zmRP{*-3!VC{;KfrIuVnE*fXu&IOrAsubkt|Ga!Lfu;vPiV4I9$ZhUglm46nqR?1RANO}X?(+ISqm5KrHjvIRh2I8V z@9P!|<)BJ9#MWyAxs{q2=7qVK&o@g3T#NeJ^UC1|^P9Pw{Bon3`f$_U2A+k9a16vO zIqimzV&mviWeOvuf-`HHc_~0y?wCCIWni01C;bL6+qR` z;}i)x`GDy+wi8UN*xbMRBtj#g$##^>apJ$SE^}@*Xk``ruKKGGL<<_BxYM^{a_!E` zX|_HS)X=no_e3>UoLzHWP0RI#(->>tyvyIxISQk=(~C_ly_a!e-a00F>x&B*(bCL1 z!E+4tFA$m%NypH6=&x8sG@cPRq*{If=@^uIOVTiCp4)LXLGdg&0u^XmeD%2GzF4+W zRTymy1hY?&9NU6^&dG6!upLYv?+T{!HagEX*WJ62h>b@tuXwC${+uc-9IW$+TXt;oQu(giBe9_}CF7;~$Jp*b#xua3ac|Tj()XJb=KQ;ZYNG)|w(U;vKf{PP1 zWV~u~W-{Og3^z&IkB2qCe>!C(!po-Xujz|5TB#th^Z#hZ!}S5V9_>XE-^CmKhY4;o zocBrDwZKFQ>k;T)GEBMfu|rGCWlagnuUMDg3{#G@dxI7{T#qyfbf<$_rv+cmi*;eN2$^Y?QJ)BDsU@g*PO+3B%MMug5#cWWE%oMiRL$;5{-*=qvAD8sa;M8o(qbKq ze;SEJE;+~KMVCc?xqwZ0V3stq-xnD?8RwprU)NsGKb2=6J3X4xvaD&jR()QKfBqSj z#!Sf&h3s?an9A@$+GiD)7I6!Q^NhEmYpV2rb+sAU?}@wra|_#`RwaH({UWDgF#EM3 zzrYi@2cfcha0>-|f;R-{$Gqy)p40n>H_}eT?WJv~<^mHVA?59(L3fIhJHwoWWR2l{zzZ^6=EN@u{k^RQM=wW;` zYEVqUHGe7N`stUgXdzeat!3iA^VdilCjVGAZ+1@Dl&CSs$v1MDGSzzTu9em!o-^q| z!erUFJraM2Xz7(`#_VidJ)$laI9P3-1{y&tt)0U)SJ&|{x8wzC&E3IwqCd0arNK>r z3)Pg8<^6AK?y1;1FbWdt*KFkMI`Hu?^~r<#m7%9BaW1Lw+v5)l6Jc<=?gan-RWBsY zBTX!&Fs{dn*Mr`&P5(FUD3@NWAx8oukp%I zrKASf$7Ph9iD8gJR{Z&@ z@nZAQ&wn%FrN9OkaK_n2gDpif-V? zsGBQT%b+c|ob9OaRflm#ogzkVGP`sCAZ_#an?Ij0=MEo`TGp~Kto|ae=-yZM@zC)z z8S-zXeqnQDJ^Smy*n8<1pME+Ke8`fbB7!QfS*E?j-$4J{<^CM+8pKwZDA90z-kEQe zzC`yqw|fp${FS8f!kFg8zmih|+!XUJ(wW(E^F(pUFot#ax}Z`H{LC(u7%mW{K2r$a z%w}rj2BBc2w%o+Swt^xH^LZWMGjC^4yEm~sgf(_P*v_te;djPe zfThf;?u~YSQuF6XS5Rr%!Gv|_JZ-nVfBenzWFDfcSC#>mz>%k}M^zSFr`%L9I~^Oy z3)ykzO~td9#NvNsWMKVo7l~#Op7nIFLsa?L`$`E~gPobPGAUnu&^+)a z#c#l-!A)twr2I9(qW(nW%Ynm-?*r?1-$S3*%YLz<+JMUb9=|Wr$!xL-(1dff$97EP5^#5bwu8|Pm zy)L`Stw_6b&f?-vBG^6QE}Me$@lqn0H1I3T&J@44cjb*L=&Q5guZNbat_KuBj!lvb znDBCKw}<$*n!g%E#e)Cr*G!Xb{-^tZLNIjU&aC009qcObQhamm>mQ-(GAe9nsyQoe zks*8E?!Fqz<=wEA3e|ojca!P&y@v_47{9C7WOvknjy0v^_f?ussBC#VKORdMg!1>_ z%cWyfz5Mmhgt&yFzT_FF@|zkyD}TON~9u=#6#t5I>v z{u|{Z$UsKTPTIEJ-3xkxiAPlu#lzXNrumiE|Mf__mFAYKCsXZTJ#g6xdp7AS2~i%{ z6vAUpUAN6{`gT1bAbZY$%bZFE%8c)*c(_j!rHNsmquz}q&+y;emVEdqSUx!&v*$K= zvGN?}!6~>%YP}6EfD)Zk6@AB!xEm5#bek|jm4WmQ%jMOVd`Cvx$w;-oEUQ*NF8k;% zU0&%E9`=&Klg++erW9*@Kg(H+shGA9W1SxH$UI#{aU9P0pGKx}J9&}E@GVUC%6{Y9 z>a(6OT%!F;8fO#N`KNkWvX0)O3D)?shZm|WJ5Z7k->d_+84ka9{Py#M@goM3Y>jel zlgZ?_ghmkdG;BKlu#h$H1i?~B!#xc%gON%LFPzLeq6ET(2IT)nS3W(jTvyGWMug+k zEsko(CMNuySV$5ae+^o?$ca~lp8Ik?5U7=G9F-$$q;d9i zuN+3fV3@PF%G3H`6Ak+}D>T=29->@ZQCwBIQF?)PbwfS|L# zroPUtXFX^zDeFSeI;kq3lGEC@hBu7P)A*;MzV`9?y3noqouQ-qu5|{yCUI86HEF1_ zW}ohBJpF*tBLhy{a&l?SS;Hs?y2e1=A!;s5UP?)7)+pK;IbNKm3_s=^rzva;yRbOO zt&SwKk`m4;{_Oso4;^f~7*RF%;iqAd36Lm{NNBNa& zK^uQ!l5i5GuN#=pbQ4-z;U(^u>bxurKwkK)RaIf`%P{;m!^dXMZn;&ibg6S zr_-rI7g4i9e?KVFLV41yHYP)45jEcsz=wAdV`j5PcM5t*`rSFJ4GH}%+XR=z#h*p~ z+O(1SIQq4koy)hXPvv_#{N>veFPJ5DW2HD=G)o%Q1{&VuTTo1`)jA$H)IBa^E zTE_Tl2Bur3xKw_eURol2egHy8FEUt{?l{wfrxyj&f%ae)$6_#5QDrL^w_;)l3YgGE z)ZO8BQXbiyY)x{gl+G6PH4w~QUvSBdAYjuj?k%r?&xFa`G6sy?&sT?CFJ$A=)~cfR zXVI+HQZu}Q#-+M|vrXbe(W(O`*hoTL-$$>{q9-yh$W2FnW}{&B=8WP9mt^?soSxn? zO44r_7YM4B8wh=p@b(dn>G^(_ki4no{}=g*#cOLxnWxGvn<+Ym< ziS@C0g!+tGu#pD86Xu8_lBf6#e~>I0GTfiw^VaK-UMNGsy&BJk$0JU$G9_iDTToyVmt>3#zjdNS`B{wd1aaC&Uz$Cyt7;dOcXVIPUAh z1dRRqVX|M=$>KMR=;a$ye6jz4>g3)0&FIxLIaldn(6bXtiVHLm1bM3^EArHfil3h( z?z;pJ&r=0tj!#l}JUcQqrmc}6{rmFSxEhwri>b1H2!&QD% zQHIUBAC4EcuIyzKC384=Q|jRjgLgknRpz6mYI8phM<*e_wdKy-xFUT9&G>Ra5XzA2 z2n%T|{JmXqrSU(Y1hsxo9#dLn?ZiV&r1kf1U0nV6A7FUr8mMF?i}HUmU^@=1Q@7&N={8Hhkyk^S5Bm!3G zq7I~xK-xH`A0wKWL~GywPF=(z!t#R?v*tn zTdad!6)=WXUn7YBGiDv^M3y~o9hOo8#q@NUxPHYfsHkBOI~nkV_Yg<}?Q83;O#jM@ z?Q5o2$=%G$potHnE0z6Buto(4E@7nQ?Y+5RXa*TYGpzlb6moWA63+_GjogW?hNtW9 z4E}qxA`gxVTC<2*{)b0Hj$xAS$#V0y{{xD$C*{{&W5#zeLE~2 z2EksX*?nnxWZ=n&$=qDLF7-sw|Ed3RR0VOhKjh`YeK^s=LbyYYov{<#abMyoTsr=< zLJG6WaMksbk;A^|z$;kx!vagBPVu{+ z289sktk$v>&p6(oz9RVGhwRMRrL5wxTkS{t7_&b?M_l-`T*2Tbv*EuZx938uIFTxc zwn^)kvTnvp9H*zn#_4D-KG%(~=eVN>?0qB!37xWi!H0ctEMRcRK0;*7HD)Vt(Kiq$~0 zdtX81!<&$t@+;u+Rj~xUtPGy^xcD~ z<*xVQYOh5?m@_+0l3KRmalFg1#~=A<$-x=@s}(2|bXHi3YF+ivA~=7l6^3yB4#bWS zx+W>u5>)|}>lNI|ec1z!^)OP-pM>PK}0ACS= z5lrGS<`}fufP^>n+PzrOCO?o8*#FQNHZ4%X|oeF~?Q;b)lbA6#d{=rvsNZ!{V zT4D2p4ctOX`^<8(X|o7xwTKtmi5U1t6n1_PM%{Ky>R(y>rccg()9GwK8lD_N1<`?5 z#XGHNo&VF;t(?-s7;>$X(uT=tpB(osr|b-%`F?w)XVu;GzgT>y&5lp7oZd7}h7%^@ z_~p}+GqzHGnBh%^ceNTr<#hcL5p=#%t!rzZ9}x5a3qX(td%Cu~=oKKubTqg~jGQHG z+Po4Tv%#6d8o=kmkWp%Ja+ifZNEG_pg2n-`BmuoPz(ycEwsycbZC#_!TYgcs{Q#Fy zd+sy8k`B3H1me>`EZ-*q{Ut_kc=)Of8u0LdtdYI5MWg*V?UG{=j_xTuK-CBA48edO zSw?u&ba@gBZUjTA#Ml#6oPCH z58fjFmyMM$A+Lh`BBYqb#ySZU$<+i(ZV+hU1izJ@k2t%O z4XZDP;O8b*Bx7vAFH7)30Pu8+19YjtC3P)AXS;qWdubP;HO1e@7c%wd6A%o8POuBix(rMzC>Y}E>k zN}8^+dkI!w8^=YEHFFoVjwzjip>NB9sHS$L+EwlNV*Miqiu$%_rg!%AZTWbrazI2r zn;fmK=jLZ#8*9TZ2?jS272vxhz119AUxunZ>nE3yH3XRO_-d01(b$5qcx`KG$%Af? z!F$N2-S1-%Noi=k^4_Q-c7BH10a;>0e0AVnH(>&?XQE~SVXTmHJ*0{u!Ksy7;e_${ zA=7I?5)I+8hIY{KyeFN|)AL*^A+Lee|07#s>pTubi!GHm6Jo&(fzC%nuIjK+;GQGqlSqCT}>tbZaLjjU~qQ+C5f>>7}v;;%)K6~ zV~ZBZNV7kxfPj>9$(bkxD5j!3ZN58~%Lx*B0LP~;Z4Ql>VV49G9*9|TT?J*7SPCnO{5*+bnWZn+q?xJ^WDGl?@47?jy2u@pv?+ z12w%kYO57Gaalo)SrED!;mGm{>W{mwbU2nce_eBg#4 zYJ!?T%tl%FW{;AjA|nRemvuc9l6Ly0 z|Bt0}4`;gn|M+Ky$zeK>xos%Qq3$x=%wgv6%_*5dCQ@TFDeBa z+dd6?qQPetBi6~ZysX0t3goFsURZQGUL(kKPt|4#J#cA&BAu0gRn^Oe3PFmu`jnnu#|C0-hTCZq=!MbR`0 z0H4m6oN$!gaO+8*nGKFThwC6noIJ@eZwhKGDU-O ztA$(Z9+%~XVO5SDN6pb#4#K7}o3Rn#qR>oeb#;(~yek^=m2AVhZ~-M%{1p0Cd82nz zD4+#Zp(;I8`A2$f_e$}vphqb+=u*X-B}Ci%Z0^mUSn9^5M^v6B_lHNpEN_0sR7#oq zeBLnT&BE7Ae~b%~(}$@ds<%zn`uBH4Zj6baY76FrymYSo29T;Tlhj~V_UwYAZlfuQrL){Vd%-rU9Pp8hB&0+blFkkq@e zlXP`8F8825c7z=C!GY%v@1Ja>6nQBv6SnFiz`-?dU=e zZP;7hC=}l&OB*Zy?+GYP*C?wW4jmAjPswl5|9_KqW4UHY1rshv_yF1%z<0$7Cz); z0_|o%Wam>zU%B%1M#w;c!s~#>l{q4MqO|oVcIN8?nTicS)3$EiaDdvzBtchG42b&j zvk~n`Ipa%(BX#QK(f+HD%ekx@yD^-arF_v~`^FwxZkgep>R>UI9{hG$=L@nq3xru4 zy2y)b<+|)!OM$Wvn87kPVRN=N;#%L9TiGD~>&{vxO^zBJ8~;Z%=Ph#5K%SKky@UB7 zZx&;xL;?T(Vr^PaDo*XCK_WD`8>utHIg3MQ5)8M8Ha5X?hz$3xD5-gS+`tu~P^(}C zdDj#fm}iN@k#CTe_;_)yv7+>!DAn8;P37Bj40riBYDM5`I^!& z+Ym^V3WqS)DG5WKaVV3WVU6=Au_p`+_=#p5W2K65GtD!p{VEk*Q9uv`i78>B3H=lN zmg4K{&m-6%HYhJ){TR9Dfsb&NxDHD)7?&@WtsJcL9~}8rVH1`UMCP*!{V1??x!0$n*fv@$ zu|@`Z(joj08%z5pD6Yh{CDEFC=2uGczQZLt!sz*e0+dlStsktz`|`zXOXn6BtbkpH z24jcy-tC#>Vl@A9upiA0VUQBi1}Kk2fFs@|g{)FF9 z4YtJTLLVk#uIpp0DgwKyBHk+D?MZzUqVH+7i|bZ)lA&9%{LV^Ceb0$W@{}PRF!d*c z5yqsEf)>(e$1om_L-YmoYfsN`zTKg7N2vZkr2%@WFJE+wjc5x-MqmhkkTGE-$dd

p^iO9D4~vnl(LCWTlZ=zw)=D_ftO=Zj4?X+ooc6as$ZoaS4iT3~}+in+~L z%%GJ=PBX%{L}gU%9bSX{HY>Z79jVktQCQ?w2#3&cfp5@ZO`ofaetrtJ=p zL};gnP8XSfN=0SuhIE(XsLw@K>yEqA%pk1*it?U+at`|3pZ8ivfLksyhG0+?4|8*| z;2i)(@c3q9v4-dnJJI~5V4DqK=Q+$UO4MTx31p-*R4-c8$S)V~VJ7{UU@$IGWM)vR z`fvuhSy-l1UOlqYF2%%7cGo=&@xsnaqaV)MD&Y+!f_z9iTX>mI`+mP(buYxNA->Pb zfpvEFYjNTE+ZsknB%r(iN5aqew;cw$l%RV1k2~hM_d14xkmr=L^c8{;h$7KTdlC4^ z8CF4Hdr}KqIn(f!tmO6JU}< zyIhzMu={q7n*yyDa~Q^N)^2W{g)L)fg!d0VW%O+M(8i9b#H96dWyU+C-RY}9udYKQ z2>x)UMPlmXnLY}|_F~_&%Le+@MjKv2%7YB)haej8xCKL!W>sty=aPTV!<73B|2j_Q zOC#D-+H7!y0?7y&7;xdBhs>!Q%VQ|MpT`Z9HDNnO98 zqs|FXY1{{9tPyPHlmjXe#&*faH?8_A?11687Cj#Y zRIyUCqB^t)4!HY!Gd6kfB8f(nus7A4si76Qwa^JLDljZ-;u@E4Ca=camul!>Udawg zNK2r_YG5h5T)7Kny}P1l_$bGv{hU^+ATZF@Tw9N!zQPrKSVI;YgC}$telCTa>Z3`t zy2hE4tZ?VW32NwI5>R(Lz&05qdiCejb_(O&-w<;-?Z8UwwOpVfgBjZjL44nl83sJ|hm#+rv23pY)JHk_cil_6>z zI;H-&^H4H@1TBd3X&295Csvo0qQ+);!YMd~16lxQ=;e?tcO&=SLw+*6y+&F2K< zFAHVBD*%!11*?d+a~4Us4mkPwqBE@rLT2TPj1WdaZJ1=!-8b=3Fc>dpY z1g#0+gUa{5IDqUB`=yO5YSO&Py-IKbD!in;H!wJ~vDBT18qlf*QQxxwV;sj*_6q%k zn&}5F(wR0t$0h6-^L@@4p1PPbjod>6x7A2=>BU5%M-!&u{lhwP274D5glSkRgc+G7&t@W6h>eGlN_UfpyC|XI$q$zA?PJ)HOYc$FK zikw2oTwkcUF+(p>S7dm1Q}$J&gCkZ}1TrKawb`)=v~y+fo7f+0?2V1@8Hq?_Jn<_< zs@aV5Zirc1oLDEn0TGN{%H6<#pin^D9m8TWIs5IK^ixT~%7XQT}DW^N!PZ+w~4ow{F%J(3$8CY0P?lVGYQ^ss=J5Bu7}JjV^fatT}3d8JF9jse}*?sTu5f ztGsjY4S3R%jnjJJ_ohw7zVT+q5*qo-g);)dPUct5_QfRN&N)WzJkOG4flG^|H*R_@ z&YYUBG~7BB**HVDC2DD)F-;9GapCJWvmpr%tcZ!R?f5_b5rW~xI?raj(qYhT!-h+6 ztpg$Sv!+hrS1%K1!ALA9`qC@6c=<`1DGt81;1cupV;%SE6f52^S3y`2q!lk4JcSM`J6*5(z|E)a z!YgYZe7^tPOC)D(j5c(7_HN1Se0pomW5c|dw4Q}+ldMa9KY9jLL*(vL;`l5Sr_0Tz zKs9i@XYbg7ktsrbQerK~%)Ls_TV>O6_^;*c>vQ)b{|Gkc(chFGSvbz=QeOxtZeN^b z90@h1oQmt&>FWNIbHfoL6HGH7|s~D`qv&g)<$ag3n%o@-9u3o zd@Yo(1@BjpDFR9`HzD_V#2U~w_{bH9%-f`#0^D20Lc?aUwyGB5>oB* zEI5;yx9uxwe>-1X->L@lA627#NNi>$Gc(;##F6@-PWSy)^Mh#M3&r67!L&(G)!@^k z-PLf$g;95`xgHlSAWXP?{A|4jjiuJXCw1F%jMKYgp3iW);uv2H3Zxjvh{oHauMtFF z*ujFbtckrULWRh8c_k*xK9lQrNR`6TdpckF9)@G9rdkL4y7OLwyfFdLgsb$t6iw8) zE9+dIz(J>jA8?|blqE|To?dxNecg?DMSEOY5`VuD2NacAlj0+MUM_ zEUc@3=sD*3tXs8}q+6Mrt(0%Na_)C2;z1!o!ObcyidsRY>+}i>Ym?9pnJnOI z7CUMl=ObS$!7^xE1zX8e`yxe&4T(k*Ap?c3r#4e3Q@FJ2F5wafVf#%SLXx@0q{V#k zi@DC?ID!TSY-x>8=Q3_(G;6sIr$Zjt{%G=<57iQs2$hn}^PrEeu2?KX!OIkLeyYPm z^6uvm^e-&v7F+kLrdT=>)hcYCC_GWwJH};PQ&xm@tMr5>sCyXPRM@|)+a&E@cG#f; zwMSc4i%;$awH)tlaEcBCcpJX6&+}c+nv^eD!a9vZx5~SZ&xw~`?{K_{Q!|zX528=M zc(}fe?sc|_%ea*v_mxTJ|JI@Fn{{yJE;e~xAb9e^yy^+H^x+Y3>atd*Vl}G`7FUsO zs{0)Qfbq)Z*wUh^o=Rhgye@4^)wr9WkaMGj10^fvsmzyUi!h{Ln>j%{S^G$y4&so# z^-m<;uuG(tw4~y&M$kJc836AmC*(!VRJSJthG5?KIoyCNFMF{14!~{ewX}gHex?Nu z$8-?3U2A-?;n3|k|8;Rj4LS%P6(`$xcMbW`=moxSyy?gq-65HxT+UPJOPP8Zq4Kit zTUD|bN--Ch;=ev4jqlA~kZsLKY?T)uNw~Fr#O_*m|^6vf<%#oWU+25#`hRDOL>^CNG?j)Vp)cO6uxwXtn#9RLuIgbHj>j-!MCDIz*`~%z5hxyJ_~V zX`WK?;AG`5?KhcjF%zVyORI}jU9eLA>W!sI`b6+9sX#J~Y{s+@i)p9y4&EQ?3 zPor_3cjv7-3KFB0e5Y^!aPhV%?3cLX>fd=i8xbg8Fr6}zZMWZ7jUHlY|MwtzPY-lD z?v}?ea=yVtPKqst59!ZqtG^X+x6E-r`?7@QUeO^Yhy?j-y1Qg{XsmSEz~C|sm&E(n zE`%t?0rmNG%uznszZ8(zWaaQtJe7f>z8iVhqE)}@{TLAY5(ZPc=Xz`XmOOq1NS(Yew?uc^^t2WuQHZBHB4qn@c!t1Tid5~!GW{o7HO?#CbPv6!e*uyXFD zk~_KlfrsOXiR0WLvZm~1ybc3)&af!c2bH7l{Kt4s5O#`?`pm7M>hnHosF`F*m^E;x z@0_{<?y6&nw;2K^BavgLd%~W(Hm+?A3kT z-=gOw(y}?M)3uWo%0sn4R3=xc?YU>r-FqIngbnUXzjNtG^8g&8nD`3BJ6b#Hj@>xi zWJ9UgIv->>A#K}#;?=85pP^szugQbBvybF8|F9PeXb#fh&!pVmYd-Nvg&9_Hp%m>Y zct*OY+a+>|rs2E(jGizyY8R_zPgk8jGL6!>HFyF^j|rz zTogUmZ?4aDzm{nKyLkJ3)d_Mvh~#NXlb*Impm9nV<0>}soIx3PJeV&)zA$G$g5 zUi)8Z*({{xm8`ir4BTW~YTN!Ik%fUaR-f4(@e$5=!?_yf?#Y`}+}UA%DNg?T|7<94X)DgfI;K;avSCu zS^=MK&&-5%`DPs52zmf|#?!1yM|Sgy;NSLhWxESsJ$-(r5g#4T%nIh5zNOh@9DihI zDs89lDQWo0dz#9+UZT!Ur-fi8UqavQ(-ED@CWAvmN=r1~$F<49L65A|jRy!Gb-8;`SCSh<-op)s&0R9mz8Je~= zFQxHi;z@=&4kg|kasKgZY*5$tzotyrU)0ZoP$%)KqmRE?Y`wD&5iFw$qq7HJYPm42 zF_uQX&bY?g!MnyL!j!rnjZO+Fue-!N1@FYKmpAPR(9MTYXWi@^WMnG>%~#gl4ZF-#?-YJ;ZJ^LKJ<3u_$@-5xTz=J(3V zm?_;*d?H}~8UL?V?$y_ie@fQ_LC{YzaJ$X0PW%g0#?_cBrS4|+-b19_0QvbJ0Pvhos+r`4lhw-Mm&}L z_|~>#Zi#om^y$^skLv^Dx|N3Y_WVx zDf3E!A5C0^lle5W7S3OyqTerZhS@e_UJEpX68#0umYBDXZbV*oUr{M3!pg+dZL*?B z%3(@v>F|VwsFIAJT6pNWa4%{cyrkspqSS?tONY)svS8PGY6DAr20zV%^ZnX@yz|}0 zL6y`3DgY9F9~f!AV$7}&8&ev7!MI47f^lq@gZw6%{UVdOTQhg-C1SWr*S6#G+G>93 z-9DINtnLH>Q_N=G*{0X$X*TZhNK(MXg|t!B9i!HCE?hh50!}zf-Xm zQgF+`^Q7$&Q@AQEXU5|nKRx^5xbto1)cpc@jV#|S`Bc^YZ^kcq>a~2nhyU)y!mw1& z8^q$;}(|fT2fT5>D%eyK2>70IsYJg0jInI;d zK+qgj{$KgGV?$ocjRu^q(|_5P)LA$jvUWHV01}f=8=18BC7Pj=hN7ZR7jX^zxrqfO zp7sm$3+KD~qPkxXj@CwO~Rt`OQ_xJXlSdB@0u{RhN%`H23=fL99t8JjfE z{F0otJ#PBs(EDT2xhbq2cei6ICv!vlwDIR#Ix*N3DhanzQu8ORzjTRqB9fiR>k8>+ z+H~SA4P7F*Y1a6Sg%l_?jivY!DQZ(PvHf|J4z$%Eqn=}CDvD)-wW97}Q+Sd^=r1H# zE@y6+8=|}5@kMZY(}O_bq?IoevO7xJ*JsDY3n;}r)i797v5>s80p!K8_+(>}im|xG zC`c3k4PD8WM}NOh)7BUhnBH88zIQF~^exii&jlAa31=Nsqw?-Y@(0R(wjpmv-88au+Q%_1`0M1Qzt`ijQcqf7 zlb2f+%W)MayWLNs&jiUudgQ&2+{yY8ZY%mU2$j&fIokbJ&Mf4)t{NJR9LAnsT(dv4 zpqN*5@18bM5*dUz`hpt4w6r`HC>%aCtjcynIOs#H&Uj9x#X7t6=LU*a`**EchW_j%A4@0}H@jj2Q~*LWOEs%ZTf3a{Mj}5%0O(3AW<^M4qVsm zi6XVi$k>MWkIB_z8`~paJdcY+C}g6^{jT~LnS1Moq^~7^*8CtG-+bfQtBTg*;66c? zKwrw*SzVS{6ld0TmU4Wrs6gt=aK--bMaI`U(a{S)8Puaz=0SGk7E9T50j@-xjHf4+ z#1w%n-O_8%zDAzm$iPKqiWmnB1!*bNCjK_@7X^df^x zyZ`H|Bob^S2S+loQ-E}`%;O+rR z`j)uwR8Po|iKmoE)v@(9{?u3xd%oEvZ1(q#y9iK9`V=T=h8FtgI9-T5|wrS6NNo*lR2-f0qpeDvhTMK>J=#{l*#I0(g{voA?}E z*x}gQr3}GLJ;l%^McPr&tTh7zcAh5nbnf)YnSyr%|PHL^IReBDX+m^$DUTx`~d z1;u&98b!Ih5{`f~JejrlvJyziHnJlgxt4#tv<#+Y`I*(q>jP3C^kb$p!8QT~M#V(M zOd(V5B+%LBi=vP1u@7TJA+IV#4w$N9P`zCW!65+@25)@%y^$Z41(gZ&`Rk!N3 zYNz{XMh?RMOIQ~{%M3%X1{$2Rz?_;QV`EY?E7FxL6i@yn`=3gb}jUqZb6U-cnVA*RT~dgz4??TE3k z()YE)oIfe1U||wJVif!?nONd$iaYc!Xo!nm=y!leZ{_AF`eHdT-bPg%#Nd3H-fw7E z8*KEE!IY-4==&$?i2T5}|GmV;KAz+C18yY^c21STi&hS9a7N0B^%V{G-9%!5*p|i` z3e{@#8i{|Rb-<4s#m%7Q;tAqZ9(s&Rg-vg328l|{wT|7bh4%<%PI;ks=HtT^f=thL ziCK+aGEk||m31(Q`_>3oYRkG|22J+WnBt0{@xRH{+>rfH)M-zP+;1FmV$`yr)0aFT zhhtmexTqc1!^78aZn8Y%pA)i`inJs#h2EG2CjP3B7EohB+d~U^o*I&#LNJV>V!D_2;a?Xd&sij5Ss=HI~8gmA!_vZ2k;wB zyIq#55&EC}#dDwgJ`hx;*!-F6{HUh)(iOw1co$GUSa? zmiCKw&WYc{LgC{(mx@~8hs;z-GWk2_H{&;&p#v>uou+u)7Wk%-)`GNg90GCDcF-bA zg;G!hD5gniy<}P~a7E+QVXnKTyYe2bY&dx_Cb;N%Lnl=G?4L_n{%?YaO5K?gTEd|- zzW~e%dT5%KauGQ+ffV~`Rr69OwNTjzDZUYdC`J@PT3e+u z0yxB@x8<&`;Wsy;Nh5`3fRQ_d`)_aV5|WUR)Y5@l&KE;P2TQkw^drGS$4++4e@fJF zLh*}%J;GvoFwf3OrtK!qseoQ_(R9yv@b1bnP~{dz3KX(TGf9(x^uNrlEZqDRwVV8Y z{uG{^SU4k0PU}+qHe+V9M?=KYx&d-*B$!alBwzU-;T5o9qW`m`=5cOYe3n>3P5|l?hI8fpArp7Bmtf0B`oIgYdWQ8he5EMdYMRt`QwdRQ z$S&5;&l?P_#aZcafCw0Xs zW`5WDXi2o7_wbvI=^02%H|1?2f3ZvWpK1+Pc*Ha_XQSIoRG!2T{M6{jnM+HwdThRp zoEDVr3)n7r%_~7Wh1*aLFu&4Ofr;GqK{e1)=0MN+y?9&_&jvJ0tgA0^n*Na$sf`a?A;8k3f=no*votd%c-z^d5K7hhP1Z><&v4;C(C4xM-SmKWp ze+%QGJyWjynrY$Yapv0kCs4zSB`LdxY~aEqoYI)jS{QxTR=u<9i$vg92fJ?8lgOA^2g0_?=UNj} zmhd9Bn-NldW5g85i7H70WL@%4==6IMN}?l*m**SsfuMg$%U~?tHj{L~5}O)Ds_3ENHJ~fQ8TD(HgwC_j z9R)Mx<8X%JFyFdS)5MR5UYSlwO;$mz6V-<3lS$TEcN;k$Bj%`N5S#ixSier=rML^e zvg{y8EtylSX)nV--VBoG3uf$s9yW!}O(7aebfLV^JxSXmwcit}nWE-*-(2I?7Dh?3a>;pftJJX6?g2zXw^-3j+<9qyvKGSb9}>z*?n|VP{B<+ zW#eDtUvG2)UM?KhiMi=3idtAD+KN9?!Bj1hKrYLX_@*WZ3!f3Q+HUVLic~7B4Q}kXeZDe%Y_o|mF6!Fu_k3OLeG3un z=Ro~3B-9w`sX?t1W5q*6p~XNMgf)0~)?a7KkQjTIahW>a37-L{HCgd(NDA>US$S=T zXI6I4i1CgoT5lxhhI0#p5oSQ9Dl@kC<~@v=0K?bT(uZ^Wt_kD|g;SxQa{0^O)1D*T z_pCk-mL50Vi%wn-X_>EJ{&6z zgfmI2OC2tLMpjDOz9#}71_WCv@1Z|4a-rzEd+s)50Ffd@A(7RnTsS7S%rfp`54?89 zel9(NlrUrF6z5nS24uR>fj9@4W{KM3_X4(+hXH(u#8f|E9~ZN)GoRm0Pn8{Bq~vpZ zjLE=tursAvfn&`^IlL>EQ{3rAA56&m4m^L}7pzL)XFH!*t&$Wl)08wAkcP6JON=Puq0{Cv#|(q;Wp`eh&tk|){TZeMW~*Z) z`A@jr4aXbIre|i%@_VR4zoF(K@+s#8hG(ckERbI1I4c|QD(sR5C~fV%yrk8rOO$=e z{;ozXYy0F1nr7 zwq5sN-iM-lPp>V(;)r%BZ*oriktswBwEWZwj!!>vp0O|(h<3dsI$uEl`igM{&AT~q zrOInP&R*N9D`BA6+WI!lS}kEzB~@KHRWt~^IBk7hui)Cwnj+)fAykmGZuWRzU%%u^ zAt`}MB>}?p*j{{@JMUhjr1=uxwAtuZzm2kF!j!K{1``nGuRDLU!NF;{5#O`u^Xa0W z2P=B!^Mz5kHtGt)7nP~zRg3Yf4t+DK*ym50$u1Is_T^ss9xn{Pskct89b;#KIj z7fCPK`l22sDL~n>XDecWbi%EeCUh8wIQciF zJ1PtXFF{Q+qPk@qkfWdp3M?}APLE(A=K0&|l20kp750V>Lh0nZ?5k)|)K)UytP@V_ zXTkfq>nS(ORC%hTJhMTWhi>%jgtbf6x~gL_g-b~-{AQ!1_w!al4^SJx1DTA&G$=Qs z(W{4F!0ON8csLB+B(s5FX^%}7C~Zd}YS7D=6AG4k3~KmlKK!V3F_yE=Hvb;(f|6~(p$csy> z_VnBg1D_(QYHVS&j_x&lEa#{tx33}~D@QEKpEVQ(?|I<9uZG;g zf^mY?xjSbSah&xHC&`Rjq-e-`d@^)6LNU)?%9wNmVUja#x4d5G$jm(<&r?BNMg-Og zfTXWNTqx1XFRVzi&CSS6ASi}p5~yiRGuD69aZ_bd4c}B+-25IyqL^}vj!V9K_r9P_ zbp74WbV7&5R!n(>3V{eFzz`xG#y&%DaX{+)RG=9;KL?Ld0b}EHhfTm1kUv53!ok|H z@f*Frp@&Ca#t%cwDmBDsQkJ_0tFQUdn>ONH50BMedZW%p40GxK{W()pcKoen2pz@U z5;PyIMf~7XkE4V)VtuT6KD^RaaB9Vidz^`;Pj+#)fID#_{kf0?tU7eHlv;45uayls z4la}##;mI@&|)bAMN3r?}i;= zBSq&tfY?Q5!9_&jBA>luZG5Ior878^F z0pL-Ip?%DFTdJ0*l}d3p)=6y_-2xcS#QH@ugs;he(mwjklr8rzzQ|raI@oNBpHhB@ z3O0+?umhJ3j`WO{0PIp)Py~xt;_I#INjq0k)18}%(hQfr_z5yn4MN&uS#xHMgKxa3 z0x;L`TxmqH3dk@QuZe^_Pzw+=xxw&@YmO{WOFVJ8B-&dgA7ki%aDt8&gy?^z>{Cea zu}fp^J5G2{9+zN zpIzu-0y{v7&nVSf6R`;Z&yxx#!;PaZWr3IY~{0NpUJ`QfHy52|e@0NsG?~ z0sLz@4;{0&GL0qJUL|NV^R(I(4Uw6@WTxAAAh%`NqaG=ZF~DdH+IQtI zZ)82za;@WTo-omo<)BcPASW>KZKSGLUXk>FCJcDW?I>XAMRVu*0-1b`0G-4_K)Cq2r7q+nlc`x^9I|%$@UwJM;K%?7 zkMe7|TaWevX+*ZIUwT&WB(b190+N(XjT{JnSClvwR6uNzJR|Im!wLz!r_6L19n{3iWYo4h__x> zeXFxz7i@pAC;s?{ubuln;{Ht*`Ezns*u+Bh1oCDL@APrqhCd}MpIqS+so zy59VZol?tA`J?D5<{{Eu-YkJ02wJO3r zBNufT>$I`bL;PDK@xS+E-A9SA^>_er{jAh%xGQaO^2Lsf>|TR2PwtkJS*-%j#gXFd z_S0%8F;VR(@=nCR^Rhp}9Gmuhev4z{HNP9eC$U4apcydf-EV#Juu7|g=or+<+n^UY zlNgVee+~sSKFRrTt`c$(weHx3YXz*W&rDV0Sz~o{d^*BcMCeolPHM5rkGedBN7yL} zmLi@I@fHFH)&)wKd(dokY`IVaIiP>+Sf+|!#L;_RaMedbx#eG5v2r`wD(dCvBbDNn*OC_aKX3o$AR6!X2U(` z$+vGcUwu{Y*1m_{jfgtcu53A26JIKr5#);>iar)S78~Db>lK`7^dbw6ECJ`k1-?BF zIT+!JYEk-tkDbD{D!b6tev1BMVG;19Q0GJqB2v5`B2&K?)jG=$${*cLLBudW^zJ7f zYf>C;ya}u7tC@6rGpWFMo@j4)jhpcc_U|86`}f%#KJq>QB{iL@Q-d-N5zL%>p%Ym~ zdA=VKOn~*?(;oEFnXip!fBe;IWU5L_!oOe}xwg*97u~X~zmVLrUd3MnCWgNm?QV@( z-If!8e2p^TCV^D--S$=g3#rci)a9*WGRl(~yi?|tNjloL1}qN9|4jDjA6ovfUUYq^ zDff=3)}0{xcShW@`M#^)k{EgJu->@Lo6*na!$QZFO}L}RF1OWbVW}6-i}BeAi{>*~ z_iWzG6kL@@e5MnZQlJ-?|7gGbLt{|&?)6S#|G62?1=}gzYZ;s7Lz>u+cUnAZc?3K7 z+G$n)z3k6y1V)R{&|#7!c=`~1?vun`mz%<#ydNCFGh;VaN4ZhKh>7AQC3#!ZZ>U7< z;M#+?a_o6dkPOZ4LW%8CAndlnhhRIz$nA6e8*Wb{(!Ti@(C;~we+)^~M!0Vqy4_Fo z*QuAuu)5c8vvRJi5kr#%}t`Wjmkf26|{@$w&u^mI*< zTF>JeS;5u$PLDOv!X6^nyVEX<_wVpqcd|BO<1^6RdN9w2v7(~!S#h2*V4Ifyu!x7- ztAVeT2fvUIy>#>z5*h>;A^ru-!`~2U!|uhJRY`>U{h>%}Z3}_s@cfHN>_Q z1zDY$_;0#TA}rhtc$*er7hBOzAB+)MyIrm!d}L^XwEZ|_`=8}~E4F~V`)9Dq)*ttk z*5+i_6E*`y2z#zMwylR#31bof$sK<2|JA=LuGovUuoF=gjrPV?LDo$MaN14Z4Em&p zqhi>_b@-O(kuN3^3s2p(J++}Gle*s!%!8)0COHmvnR}E%65}iXwz5n)v5In%irF5& zrZnHS@#S6I?91SiA$8QYX~iSu_3C`Y@S*}?{x6`0&V6$byQvic?hq+|hAqU;an-l6 z9(qdGe$qW&aX9z<* zUOQ|o8D8AAd z|B=_2elQ-}-{(Tqdu;Snv$yc12wT!ZV)k5rpHrgPXS)bjVFr)B^V0LI|0!()RKPVy zMHoarw_$g1mM}uDrc(FxY<`(_T-!6*yLJaj-Th3vJ}i;wPRlbpGf#iMUOb`>6z-c$)b_}kE3&sXS#p?_-BSm zniStAV~TPrIdp3dvq>Sz`BVutIy%kSoQ6>DwK*0wL(Y^#<&@J9LxoVuAv9u`;}FLE z`}F(Iqd(}eeGb=ky`R_f^>(Hgp+GGvTgXs7-5mgbp>rn+ED9tTvn7j;@3YdPx$G)m z{fy1B5&y&wC@HC;8$&(e%!miiBMk4CrxC^N^X;Gs0B>W z3n^%cfqP#T#2!C#QF?S|?*zZ=nSo_#75bYb)v*cX`XKiTb+SKq_F~|{?mpu;j{gBf zwEi2<**5lU$D8rCo~J0?mc}*-0!*yLvFq zM0)NgRovl;PEUqs{?|=B=Fx^YBNxnx4~UX(}i|7pY>W4_E)Ih4v|u?1=mw3>DVWBA@X;-pZ&Z_sND_)59b9w zN)e{ZGoBt2l=FfI?jZ>_FC4_)8drT4^c9qn*&ABWu{|1|I{CG3bzAd}P%hM4;x&9c zLr|LLT7d3k&Eq7=#j)rq6eDVWWLCNKgSpu$8>rr2c=lCas`Aj(6bbzKtGyNFbq!kB zF@WjPmVZ}3r8KiE&Mq=lG(A)VKm2-lZ|Y%7jNy;lnq>P5r@U~tq^ z+=W|byOGk_1PUVp^d0;@71fEv%OOQ%9)_!6b&WvVLli|&;A+CRi&q9}RT*?`28Uz1 z!pqA_GgA8jF3jzJS}7H$#+Q3k}t$Sgtq zOs9r6i)}0N)@d}O7FaeK?%Dchqm%gq+<2`&*sLfK4X7H2-m`E=z)zP9Y(vl@FN9{w@ zD13;G<13XpsL_0z3msT4H9WLZyHXVdp^<&Uo6>|Y)sw>oHKTQHzfImA5fiD5iIZ!t zk#3wpknXc^SrX^A#6Y#IAx^#$rhQ-&?+9QB|(wkG>R8%dTHOZo3D=_ z8_XQAJ?4FC2CC<}f%p%Q`RZ%za*7QMYh4p{Z61o{v0Peqc~eLD4N z{^Gq0rFF+OOR7IWr%oqg#}q2sk9X-j%<_#xwGzHdOI4JTFKnn@Ip-AhHpdxk3#%?7 zSE8a)YAWUAMZMYfS$97Q@ZCBmfFJly&s2WsSLFGzW2votVB7B62kAKSbsO5XOR-`H zrgf5aCctnthnK_cj|Q(BB^;l&ghRF+5`G0cOCIwq-wcB88DY~r*+*N{t*f-pcfooXI_alnSS^%(E%!x zHIr|ald>qrjss^!3;euRk`;s%Be*lDYcodevBTPX2Yp0w;myJo5+sqs6Th!$w{v6ybZB3&}v zJbVjDQ?nYSFxF=p?Gv1j*F4kZ&lHuMi-fD>rd&>t^45oW_Kd=Pnn4~*-M0D|>c1~s z>;c|;vaV5!c=w;KiHV@{LPW?lBdulg0mcS)_x{$uZ6vL-N|_YXBE}lY5;?cv7GB9^yiekIIKv=*iUwugTu|xU0hfEdC z8G8|J3F#?8X;8{V+Z&bZgqJDVebzmZDHoQ3D$me0EuEvKA%SP;(`?i*! z{&%I@QAAB|ZGNBtt9(_jDmY;(g!y|^eT`2LG}BJq7J~Og&ln*yDK!Hy|HMF<*e?U>zJ!Tkut`=2Xj%s#1 z;h1LL>IgzDv_x$dG9tMA&WhrHz=b6Hv+CQjQ^=L9jt1*hsTaXhDWA;L-318ApFgTI zB_$c#{^iDkzPBO{e=M6ZI7LaYdlUAG#%qe#^XE#uF2pW@3lC3EH;^oR!U^r}qmnV2 zs_G3Z6$D{CK z`4um}tUcdfmu|FL|LlQM>sp6OJ~|@m(an}^`+tlrd|x^4oTr~t1Ixtugof(>`IdND zyJWMd>0l*p=i00AEG%7D$T_}Rvjdy&|8!)p=dJQ|TCc@T&_7)Hk5ctB;r|8G$OlIp z-cT2_*f%yG`Hx5~#oGMwmHhO)I78%Av$A;7*B1miX+ix42W3*l?xejQm9gfaH)CEl zu830$h0|m}66<6&bZ}4bUhkw!{FD4EACl*TG?Y;dhNny$AWTEry2M6dTe|z3<>UE9M?h3 z1h9a_YxY6ry#)_0t#=-+m`t&Z)?$2xgld&!%{Uv(LE_Z4+9U-S>^qzPJKZ zDj9S(W_4#qeX%fK7dl1-9iF&`B9wpVKq~yc+B{DV%C->%@ZcNt$;naweAr1Ecqp4D z*&_3+K(0v%ghzTt`$KKsFYDR_>w!@)fD{RIJi-v0e;2+m}TA3h^jvC=ZIvNn1y9UeTw{K)j%RXOSUZ!HLM z_(C{;h~TJM@}ZH~G*kx%b_z>Pz$SN)1*wpM_FPoJ8=QC+Fi9^yxzc3}gE@Mvx z1nw_$qSPj?bIUdjQl{bw%;xX;A?!!Y3cf9acO`nU_asK|y){OvxlVRkaq4it z>fM*+9)}rMvaOAh&U)OaNv`WK1}E7Ieu%fmsbQp8VeLucN`C{(tT9=@A@+?F^fXU( zJU_sq2=V&Miy6CarS09N`_npK))iXzce(w!@=I5;`D7h*!> z%z5KAM48`4h{omRrH-xJ0Y{$x=~B2S#$#rATbTZ=qPWLwMs)~k9-Jz7R(Vo->G|n@ z#Y#711Kgq6FmiC8LiNO=K9rpImfWV)@duc9{2IB$67g%u>8N^62r@)Qk2*nGYGoi;r9#a*_ zieeY@dx=r>kVBaJ{IryE1|uc6@)!D7bH7uES_pKypNhE z8H4ZWd`LvhTHX$+Oi%~3#47fD833nu#&3B-X+L zVHY#-#x_4sp@Sp?dGhhdAYLX@`TLKyB5hd;F=%6>=!GnW1kZBG2kdU!&Kgg$t)@iq z&Cr2_>dsf{yUL|xEx(24gL#i68b&{w>z{u zSu%qFSqSg}=Cf?kpvFM zNjkSn&wS3zjn=_a-mShGHPYfR*5~(vb7Jo7SU#j4jp`>?)X;V zdcjJ}IJQiY?=X34Pfpxd$jOg0bTs6a(8e6*qLEdK(pD(A9OyU$i{r2@_Vs~gPHu4q z#F8+?hf&r;l7jbd{~{griy8TutFju3KVHzuUP{U$8jwOH|ANc7*?lO}Agh|Xg8u+f zGf|>hnHp>ox9>^AvicRLq~wO9DNt|pKS#-KkSNYo(hK60kM;(aeFa9C3Uv))nk#$I z6rEWz=|xAe>HIxJ@}BKcxIw*_zLQ%7>RKSCQ~zHxvL8*1YGGv!=OldxvAl<_e1wkR zMeMPD+F=2lo{VUtk_VK{;juH&$8cQmix(*&fS;30bF3O^AOH42i)(~w6KvZ+mGPPv zdV)m{T)|0rIfSMnWVHxM&kLX49#4efvcrFl>9Qm|H+Xr9NG>#G%kH3BP)%p|C(V&0 z&Na!0CFk!{bXkqsT-Wa2T?8ZKDeEd_{n;WFGb!Ie8P|(<(Byh!my7JBcEC>l0yMEu zRezR6sV#iD4?aCs)#Jw*j5sSY>4I>x)MAlD^=xRVt)%_ zkkLMBL+c!7fzo(e?UM;NHv+Q?5bA*kLvYT&NXVEI$nZ(fSFc{Pfz{S;R5!nFixk##pV$DqLx@JNW&(Me(q8I`|(6Jsva2~J{a?q>{o--t(GwobkjgRHs5_JU8+ zzt|PBTGTn7uDG9eXXghh9yTkW${*u}{%PQqzL9NoFlEy(vvgMxQakK;#^gJJ2^+HW zHA~`Ubj|6wfxR(y%vT$YqV|FHp(*u`&|)ws1t+1Nc9Z%17%q!ZOm@5GiL^9>5pvds z;Jw9!-pyzb#puAc4QCuzb2nzpAYcPS_O2&y*j@4|Q70L*nfaQ>h!QBRkU7Hcy-$UH zGW&o)Zcz^oz?X@ZuV(XOk8@HAn}nEu2Hhl}i4Z-TO7enqh5GRGpV!?xJHGZd0sQm+`z+ePErblEq?CCkV54&&zY`Oh)lWxv zIl1EXbF0)mClo%@jbKn@ggB7V1=CH4VIcBv)!Nx3V6u2QXw^w6gx_l~vN$~yxm`4;@4*MxV#P~8=JGw`p9pjc4Oa@bVU96BVNBLH#DP}n zxUsgUl1wOHtW(iQbZ%Da)N;78yOW4IjLPn_vGpyy*LkCf_7`y;RYHi^27uS)&GU6v z!6hm$!_ZrK-s{0&#{GF9!rO3{V8qBPmx(p@03R*NPE(NHpI$^Fs0P`01f^=0rDehy zXWI+Y4JQ^mf?F_^xE2P#OfJA3CQ!RcDpTkm%pysUU;PgVCK*T~DGvj4r zo%HeKw-%N%48hI2*%%S1tw4^TS@O4KrD^sSj(t9xqep^|8@y9h`og)0+$l5WPe?3q zfF+UfH7uOyqiJ959xTLE970BBEiRiBo@~ED^78Oxut4NV4iI3EU}pL1H3W`D7uk=H ziT=D|z^zA$FfmgAu6K23{aFoRC*IfMr@r7nhg?TZfUnHT$Ixj7Nv0pSz|$*SlN@F3 zxxdPUr5n7SFZ=_IkSmhbP~_v^l2TP?Vkhl|-`!D0GYe%2?faXY?(C;OJRx^K&us%h=%gfGQk%VL?5xOlj3VqW$4^9g z=c|O=kJz;71_mO3l59p_73x*_gOVlzjqURfg?JZh#PQtD8_jJCXdu#5 zV_;XE_#EZFD{9argvJx{(Md>$01 z_Q49B%GV2)EzDncuCoTg3n#0dPS`U5T}}DNuH?d=v_(u ziUz(ov0yrTo^*!nWQZizf1{m0<+0!bd2<(+H)(PkiR7#!K-FbNvy`#(An+Z0wrlgS zy;bMHwDVx+7z(y6U(&t9q;shzE4!ei4Cll`Pp#nK#5cfSK1Ya@Y0vn8XCA~-z}|2*Y=EiD}KUr@+genu~Vvq!YbEHT$;n06?Xp|_I6YNdLDkRn{R zN#H}q#3BQ|c+aBiphA{eL{{2AZ|UkZ^4|ygZ{_R2%+v@7ES(?w{+k~^z&3tvEKd;~ z!|cUZsjA2JYD*bc0VmA^>AHu9;Dh}_dxr-j|EFncEP}{-R#O(-{*Qx{0qZw7q6`B6 zBRJt4KQg2~mMQ-qV4j-guhl0AOl&}l@{VgJqHi!ML!2m_Lg;bP7igvp$l^c@FCSB3 zhT+A(N!Bb40`L6Y1lUtEVDnMGZ_7lKtqORIy2O6%5H z^=Ti^$W@)}6Ox=#L{iehwcL5?3k4dU%CKItHn=?o2A2G7L1My9FeKDD@pf1t5;9%^ z0=eMF{*;W;X6Vs1&B0%$tP|9(`PS>eVmQdjp!%Pxy*dY=5t0~e?|nd9PDJfG0+cWn zt%++Ht&TN039AKpdTjJU2L=i!FOd@k{l5Hd(4oIQ&KcHtX;SnHXh!{nSR@_<@~tY5 zk-T3}U;xp&M#xbsaEpPD z`F+-N1X=(=vsR1MlO;NALB?z-)Dp-O^oSa}S1SpmP_Uvo-26E(C?3J|2oi5T$uLlu z=M0k$-VrHHX_;D9s+;o_G)C(I0;bq_1xe}Vd?V41nYm~-bp{9f`0mUt!H7&INVp}s z8!I4LF@1sJ>cS5J&8Tja+B3Q@Xesm|u=?>~Elw!TP=Yz; z2z%X?zF6im)y4E-pvy0-p^d%tY*;{RQmiwREKH1*hDi#hkRdb(^Yt-n6Mi3KgC20J zoT+GhUVArO$L7(EUCkDZW|w#Z;8~*Cd!Epr0;@oDsKG(|GY@SCW8CF1z+=N>0i<6i z3v{Qm&linXfl8h;uN4)b>?n4-avTPJeh;v@4!H@jmXfZ(VcrXW+h3o4D~nWBJ&@NIxVK&Iu?~E`t2ED6Qx#a5WM@NI`{T&3jZG5KNw20po)DH(2 zhJ8T7$Acpc*ybZL5mq&zaP1;+Qk~JeqffJ5ha%6I#q@qljXv^QS`brt1ugH_L12Hr z4f$HT#GLL=@kX$@>-vMc9}^47$k1EQVNyf_4zTJ&uJG7}P3FN&BnTQ6PAmgc{u_C& z!Mz5Z&??}}`44Bj#Ft_HnRB(nfqX`2=AUg_Lw=SvCS(??s%}2xCxBso?9p$YPy}=% zAAt)PX!g9hp2#w~LvuLg59Q|+o&K&wJsAcg6L9;Ju@4Vvqhd9uM>T>$8@|oR&m_kU zIqj(+{jaiPUjR!YWe`LJT~%S`X!fNqQJtU)WAgH5dRV+dKiS{Oi)m31X$p|HJrN`0 zSwT1i}6usUmm>E6e(gw zk1sFG2mT?kI{{Vw)Y2YcQI}gl5#F#Q)Grs5?dBMRs?|djDYk(y93hhxUxknjfFaIq zG9&@FK(Mmk@0uprqZZ6DMiGp3@rBo%0+{mf=-BW)0Stj^1#-nLu|8Tvip%@y!!Dvu#IDzcUYJcvU2h}%pt;}IGyLfBWUgRokTQa zSBXJh)!E=sTa$coT&^CTZ9W6dmR9Fom5C!sG+DM0WT*DT7x!6Pm}8!tok$K88)z;x zwaA$xZi)koKDtOU)c8sxpQ?Ez{9TrkuoTqKr){Kg;A|eL?j{9%3*84SQV%EBO$fMb z)bHM7p>KCgGiD>}LAT&u$^FdiwbdyfLcPx~l2L?BoTMal+aDZe2r(F)(k8P?YIa&& zOue;RT1PNDQ5QUUTBAh=TRj=8#O=>Y-{?hi7~H&0$Rm`h@%QoNJY73;)@r$#%sm4A zgW?`)v5$X9*~H7P7P$&*G&;Ym3BIWv3no8$jXJvR63p#7J!Ae{a&Zy{@Jp-RKGKZ@8^>?lA|srO6J!G22deQ+K;SX#p4d1z+fO7R5@{3fC-CSkq?F9a6ptdQC z{_8z$6IJ8N)80#)CxzwizOozmgVSes%^;?>Z3s~e>CTPbDr}*YuTY216nwC)9`=Cf zpUrQ1ITR@pj!na8l0{;ctQNGr(@EMB5q7d3F_d&^W65lxUI-07O7vP9k$^r{ui%YT zj#GkxWKG)Flz~qZTIy@QY8Z@i>}qDt%TwbzB!^-EnPmo&9)7>2{oeV6SDG{=`>K-! z!<8hvE~KDzNkV|@;U2;jE0WOOaY3*{H8VHD7=zJAjpsyrL4tQ^3fFc(|6S(TWN=LdTf&zxqyKD)C`&1TLJDSsgG?|1a2s7 z*#yPxp~0cEu&<}*2YeX}1D=vOXVlzfAUC&(L`!Hd&RjH1hASdMiI5nJEZooZ(x~vp978|0Im4DWS&MXk<&=o>m4XG{eSd$ z!C%Xz@~xu$`vvY6fjwL{`$cDV;M9X;Hh5sltaNJd6U*ziqaj#BuXM;e4#pFTXYTat z56>JG$vxSfc0A6&n9M9yg^v zm-VRK+v&^;ym+IK5x!+k2af(-_vH2d#hy^r1-B{xvev6Wh0njBsb*y$n};rcW!!_b z9A5Pa6qIBZM5Gb1Z?_aQ0v3!Xv$~5FEZgmT^ld2G+eF)5nd9@rbsT!=E*SJt`*x7E~cu$Oo zh>@H(QHq`y{*(EuQ_GeHyR5@mAdRR?)+D852{L5B6q^_{NY$?!p2 zzC#f@vlVgMrbb$G_!Z*(ll&$Zs{uCC%=V<7Nv5f)16V?35&QPrPX~p>uoL~Lg};;u zjXjbTFlQaN(7<2Gh_60L=VT}RdqfASt~y+Rl0%a=4gSf0dTj*eh^+c38(^)>w12(qSIH8#CN4Gxnwd%jSUuH6@VQ}QcUfZ$<7edYv;jv zv*M(u)0OcKJzqv6x99GD)IDA@5v|G8HFoj#&NuIrzkTo0>fp+#*uXqF;vH94G)1G@ zV$4k&vBZ^206Ykfc05@sJrVSmHU8_jU1z443I#`?;Hr0J?d99Dl~RVX3w+B);fghZ zA@~%$?Cl>UV)0buc4?NFR7c04bY5t0jOs8}Ec#)YtF^9c64@d0S7@R8!y~uK1lN0E zP%Ow}geW|8q#k+wo)>k~312a?t1?jalJ^ECS*rOq#p2Zl@F7G?Hs>|>3hOP~j&symMzSd`Ii1Du{uN3GMi7pwjDnF2ME46ns6qN!TL_vOWSB}tL|-~qM8FJ z&P}hXRxDco8F>}1KETeJcfmLm&kqc3U+&;X2`eY7Ju^gaZV?@xsYuvP9B5A7_|>S{ zo(D>Ok6xet70hh9^f{#d4HCVElFM|l|>4gU_$-#IZ6eBBAVeyDd(drx93bI13? z;a|7QkKC!f`5zE2=8_-z27J{gT)!dnJPs@SU=6>qC=hYteqO-!qW=KP$o#;Yk&k=_ z|41&sbMxpzaQ;xL=Kcftd%`YPb?CMG%Z7sAR#%_IzutzMjiq1p54h`HR=4TqfGbZS zf{l6(%M_6_D`K0T3I72fp1SKjc?01xCDv*lQZsf=2fuxbIyg#;K<^nfJ$_8;D{y0O z7pi~=aydOr4&nXdMZ4azo*@=Wi4q4Bl$X_-k9?NtQJB=%f25PK&t*NBIi2v~PgFWj zqG&Z}E11{$x<2C7NW>1bCp4jbrSHyiV1DO+fI~+_w!?R8{fHYDk3DTYWceVsGz8Vb z;-{F;Be8B`Q5LdCv{Sh)AUHq^^)JH0_{g2M2q z%g3Bb@L(^SP<#h5axASf=1KN;;70omldzfL94m(uN^OUJTy+%FcI1#MT=4QTunwXf zG>40xK(~>jH`$LlCf5{R3h!4OJ0Fs8@Q_K%tPTo)y@KRJByLk(UI$!QEv%dUUzyk0 z!C>);y6Je>VCdR)`_mhCJ7+WC5zEM_@)djixR-uNlvZm?q6}JEP#0fR)^F0(vvMPf zJR>jG>%CW5?n`A*RSQ4h7ge*h_H~{x*gHH=?aod={<&dh^Pw7Nl`h08P*yzX{NT)q z=Iy$-G`u7dOt87u=ydr+<-~HG)#@%b|Ni;2+>ywWfs`vlndgjl);bZWw1DTdq!SIM z2@;Q_D#!0Ky}vJ)oiVLjD?82Id7U)UKE$h4pw~&OgmCOtFX`%d=`C9Il@~-lRe5e~ ztEDn0bg{&kn)!Hjw|RSP{(1GKS7$_GGCxNzAcBhZ!pvRtU4sNgo@*g3bq z6UwjF!#|DW)CD?vYLN%S!Poc)-Lo$$9H7tv5Mi6v(!Rdmwl39JSIJ>I?k7oj_Ux=) zX?xA}6DF&g#9;>i&nVi%h7r z{>!>>Q~ug0=kvzBahMgVbIcH2rSw6mThxy%l_l}GD}I`Pu~%|_Pns$bYTa0ydS>{;r_dl)Q8r_k>LR&gBatZHcAA~oQD>3C9v z6J;nr<-*{dE^GQ#JwhMl-Tw3}1OKPSk2h$lgs49MUoQ_`^gg?S=se}~3LeZru=|Tg za2rRi|HNGlB$II9hK5LBu`2R&v9I~3r>yE}umwCG?a1_9jo2)j!0%L9+u^w#~fFj5fM#bD(|*tY4C7AM=G-aQ|gVf69*3n?Cnr@GM{ z{or#tvcJs0`}e0q_C2GED1TNnYDOa51FzL@e9&B8RRax9g@to9(sHW#N6gJz{SreY znetg?_RT-!9#?#FL-b;dzg14ZiSlIGcLjMnH{hwJ)z2SRGOAe*-g#JMu3iRhJ30~K z5})oo*njxb>)egkJFf>IN*y@ZG%MeIv}DWE2VyJF=SLP6 z%($^!S}QXqx=9qSJUC<}Mc4NTkSzIh(R1j5QJhgOdea&U*1)grz4&80ZwugO z5GY0F=K-$7ZTJ0dW~V+xRv`SlioH%J2ROPR;CVz27Sv1LOnWLO132-)JR(hBl^;E5 z1h~|5uC6}wQ&kLm^6_h%>mfB0nU}AWC}M{_z0(-XD$`phF3-%&g@e1&U80}BiAL$^ z9-@RCD918s!e=L6I-O&(Df;X;dLqkQ=U2t`40$vpwA_qpM!oiyxMFeK^aW+;d?LCB zQ<8c|Ljt`OXS}?&sA8=eyK0pbB;tiONTG)-f2}+6bn0@=r^h{gf@8V;IcYU7MR*^X zXbF)+BOQGD#sY*snbE!@7Y8jrq3~+XT9NVj{+2fczIsjxTdFhB^VGht{8jWzFVEDF z(9TlQ@%?2&IU#m$_8;2{jNG?p_gZo2cg9HOp^h5^O^~FxX-gBE5nzYV?mDk?-q2n4 zNmy<5RMD1`+N^QDhg|R3iVOLdlj8QRW)98i`j_krexCnoCC+zwk>ZB$j@pc%5giOE zaVBd=5)^CXeFcZJlOa2B*%!?Z>KGvo3!EDGgf0fXw+ea;K)o3Lh za-wQxW^CaibPxH2tE4tO50>-wkw@5&eT-4mdAn|n`YZn%f2+zV(gr*k;3U1@Q267S zXRWNeGc>PRFeoAo!RIry^^D3OTrWRS^-i%R@V&Bc!_9qQPP!fW^S#r@D--rPMPIYL ztUbn%eovUcW@r=qt1jkPw~>6b(X_FwC#Qv#!)W(Aa^$xg#3?iOvX@@@P3G3`JbhnT z-LOx*=4bay?_S3K*Uv?Xs7PCDK_Ljfp_WlWZSF>S;jOKAALLcPF-TrAiN=4s+d9M6O!{BDV`$t%6M4#3--N);_P`VlsvR>HvzZa*80sM^hzskX{`X0W|k!CQP zvv-vdgS9_mlIviDLCA$IV|RJtHaEu}!T zR)Vv=Cucu2^=4{{2B7t*g{I4&UHoqos=gqfS@I4mxDtj~)uQYhL#KP399l!%7r!Rq zSmZsK@tK6LU%EeODYg0Qvxe-wiY~n<9|M%>J{a}kcm82uJ*zzkjkZWy6lc((=qLWxf;GOwHl<4z1U9g-A)%+v zvj?<|!={N7@GR4I-RGUN#}1^q!quc61pIn$IT7c4-oN)sgP&7_`!g@0R?dxAgc@m> z#Gpdj-)=mn#Z`S^;GayJYoWC1WtDKCQ`g~i4PC(BUeQ?<4wcdDulsELZ>g_vnT;g) z_Sv2<8t8N!(;UE3)VJ*APRIIoTc4WnEkQH*{f6lT2GZRKw6gTd44yx^+I_wQ!`fG$ zChr@}9%xcGEqOSlT&mV$CtxQ8d-)%5;PzdIJ4x5otAz#R@i9F(D9x4V=YThI@4PMS zM>8^L57olJ>>%i@infhez7}=x3D)M#SJyS}$MiBw+8*aE(_`B{nYwgl z6#1Oj`-K-&e(&wp(@hKU@{ZZnhoq2Bc8AIU7e)Cg*S{$8%=c0WZan;CKqqt4!fNYQ z#rE4pZ^?r2md)#T!BbC5BJV3}PwLOtN$DV=)fbXR2bl`8Vk1$^ttIF3JCTKR_N9Jz z0;F5jwwyKV>>4{?oq$Py9LVtu(Oxgc{u{+<$C-+V$vTNdh);Qfu^f=yx6Er+6wPlG zwA>0J8_LW%3lZZN;S1$vyAt7wod_?Bn)??gQd$s9kcgz6`_!m}2Ja=CYVb_BF#nvk zE{IGU#({F5!by_|HlBe>&+ix*$g;2?s&`^wv!Gn{NnD>=Agfwu#Z1qyFCvxa1{hg* zv(2`Q73ex3K@Ays(k55Ck-hsOAW|Z8^;pkEO5+ZgGF|Uf)gZ2y1Biyaft&O39R;Jl{iMx4*!rcNg3! zu(UN)&UECn{wBZOysG_=nvUOF>2UBjd6mIBZVpPXSrmu29H?4+~1FJ zX>Ar?NAb-*8y5UmLn_?bMQbwe$<=>7N0@RogP}H}?XMjgf9#H1cE(_@q)opugz73u z#XE`h{)2g^Mot!Lohe7JzZyH+kuk4h@nP(N-Jt8h%V!5v9&RQ62OP0rIN)Ce|J!bV zH9_}ZU(u@)5#9`uiEW4UFm(UZ&G!F&QRc<`RzSwgVpQIJ>)act7YI%;qEhsi{@i+Y zT%5|k0(%r7D&`FCIC+?q|C0id${AUu#6uecu&}6jtH#IXW=Xnd>Q;MEu_4i%&?ojD zynbz!g*tWuH!Egb>pfmxb=F-kuvIHEpLjX~BsypCJGz~xd1jTU_iv4|jK`nvstz9U zFB1h0T>>X9&1w-sUDJQcmTI=cE=F-BwnIy(+^1w;bvm}*`9{E!G`H!n_LjjkC?A^V zWVNPWho#A-eBZWVP5GMpMp#_)cy*3{R{RcF?`=6q7Cj2lttTVxs-+S&$OMvle+gdb zdbMWnKd#k%K>2tfS%V!WXU}}S&U7&YjB7rWx$tZ=u zTZJTHdf?gYfY7n1reph{6Jo;CwHYO&<}k_v%8pzY527`McZY3VKrAmu zbBm&Y4fK4{p2YF27rbAj)A5Rs7GPO@ID2bzf+dfi2cw6JSA8@z(Ck6m3(-TYl&t%G zLKKH-aObwyG+sW6O&=A`eCFY9A>E;zIER}iFbTLr{LD`P5UHFxRlthsKo7?jgaLnBqJm?cXaoZd=7wsU4A+OS6nNW~0%A`Z zkaQfYXxn-MPszk8-(^wFF-q;hE~zvm@+j~mn#QM}`QBz@t&72wW|!oxv*_Ta(XQl%uvrV;=^BX4@_>5{;3~?>#vOGvwwD$YrswjBjs) z$Mf687c$jp>-xV)(mZTmWb8k0(7OV9EL1+I1f>jR3*x~5FYquSkpj^Z4g_}Evie^{ z>#Tq*MuY1NMg8(l16)TW)Y`M9hj3|W{wis~brlWxbJmMGdmPGF3zKanI<1&9OJ=M> z^Piw0YRI;AW1cCVN7uReWkuW2Hd$F%+2j9M@^bW z+}np$rblG$-UslMKRb;je3+;W{WRUg!f6FCYb0A1PE?epI&EYNzaG|~*j@$+tCBLY z$F4`d2U!w2^wYcul&gNd{C?YZYEoD=7DkBa?Q*~GldZdVqT7P=B_|P(`>!u*ahIP8 zYpMl1$1FePu!p7KDa=Tr=}pNPd#N-RmatTVw0y7 zih9E*k1CJtu)k?g@L zlM6rTZ)oUeWD9zTlni;H*X8D~+^ivUX5{+zWClHl>PMwVDp!|*e5psSh7!(q0Yqn) zq_ZX&xZ7Pc64Q$$Fg*ebre-$7xM)s)D%ujhz?sqSAR%%3GSj!xv6#F zQ|l3ITmO@82@>_5bI9g;wje|@GNUpMWW5q&Z{a#+1EhZM{Z3_piU7e7R{3h_CSP_CBMSmDPPzpHEo5$>5<`=Np*-8Km?zeAKoZ% z)%Wrpj5ezR8JT4FBG)JcVr07a4*2HY<$Rv2py#@&UzhC(ySV}LcJb&ZYXU~Z@Sj;} zDkc$DiTb|v?+I5)G-O!Qhm`^La7OPK?2ECqfZns2m+QmXK?U5YiAaAC4ioMZp74@A zCuNR#yLVP%tHMX$3GUaQ6>lx%WfXa)HL2J0<7O~u$^QQNHq^vpku}HS7j1iuP&^kj ztdIXjj~5V64q^1V>{VURcm;~e_(+FuPBZ2#mOBNk4C=?#2huu)ZE4aVldq%|PLg z_?^0SFz=LD@a4NtuNQqV-CS+lst>H6F?T&#qhGA ze@Wg4{GgNe5CysD?lXi~1P`0WKjFceVj4uH3?Q;$>I>KY;SZ3GNZ;<$pSXbdcn4UE zMHPfAy$Y=G65JE*gGa)La*KxrCu^MnkGipB*0az=_ z?V~ri($n*Q)*k3vd*?5GuR&Sx=4v(3F9j#G3dS7f7#lLt`3fIBz#tE3jp-A=)rn}M zBZHv>%i7(GsAu!IebXESn=<}UJQg?MIpx1(?V;!4H5O-rnzTYsk+gZuA|MYPBogO! z{VoE^1CKur*2+@ALB7ccl}heTZei6)zDmH&)hBoc)C{`bwmLZ~6XC3%QRq1oD)Jw| zATdp!n3mzXWc|6tQd4Hj7#vaJo#LEhM$tYvGFT?vLeW!Ms z2U*|~N(S}c=N$LEZxMa4+1UauXv%L`Yr!I9Q~3wT=+WOX7N%0GjR1x)oBmXRsUv5E3XSrQzMbM=^5xe#CVi@3aOU5MIciGd- zP(w&_hQGZ$^0Fik{Fgp3rPK3VaniLuZs|uZQY*nEZS^;WX4Q$Eg>fS>X*T9X)U7iH zkx^>>@in>8?qeH^5ij3*VD#G6S<}Xn@=p8DfP7`QcxPoQ;$Fix0#qBQvC9t*ib_ye z>sI=XhCGH9QLG0uYrGfxVNDMV+Zv{4YTn&6phnvKmirdoNlnp%a+XSVK0gOQrZ5Mr z-$2=6*=C1v+#3*HQ~F9SqZzcRrtT%KPH zyv=7C`~&757`sdXgTBEmI7se?s=b-0dBe-TNj|KAnFe-oi4hm)6%s`C-MK4;)3a1U zzEFz0oPV97w_?z&v3QH}jB@H1O~`s86lbty-{kf#mC{QPrk~@N+^8wLw@)Xtgxi}t^@FGdxI#Z7>V|cQXM*4 z$7O?BF#>{0MFjN|Htnc)UC7aHqy=yuB0v0kH3jx%E^dU@pLw&**kzybEKT)up}~X2 zPVU$iulQ_d?iE6tkujvhE{w;ael6tRMvrc4XQkq zY#D+*X%L1Hz@Nq=_ZiXZgIWt&t?L)sKvk; zZxdD8?r)#ra#%ms;UKim@Fw{HcKg1UHxWuUxS1egzlU{>URiw-?zRv&J2y;SS3)*K z1R6*H*NY^%(`}kRzA4;Q(2aMS<}(lm3(O-iJrm|ZkFHgWoCb6d`$xARz4T($*+&ti z725p>2@{kx6p9tVuna}X3uV4(AidTzgG#A#PfZ26w8bA)72}VZsvLoaN50X?X6qzi z?;V)$jrsEva>%0%_)v)v?5KvRWeR&|u!KYA#!h8kk9Q&FLpY3$zO-+l{$5rFC%cS+ zww)~a9f2Ro5TGhelIf5;FqS4A$$nPkycz5s{HWiz*&9FT@9g|oKI&$Xh+nFs;7+wYR z58HbjQ4^lllpWh0==|o|v>|r zaww{<$oJUPo?5gjtaNcRN_A?*0^W_qHKhZ6(;ts#f+k21&}j$SKlZeR!B0`KAEXA6 zU(Tde9e70iu>m@(RX*gIWD^Y>Vok_i%FTx8k8+35QEyW_j7H-P{T0i}kwj1(l=Szf zy}O&pofsL5CparnEegm|JC^k}rsMIZ5!n2j{RdoQtdyh=ch-Hre^Al_e{s84$eYL% zUZr6tbFu}SKnRy&eAHa;$WR2$Z2FRTEf#~IKM@#6PlKo<1Z(t3eB|FsTG zANQHJgK*lX2(|1H8!_ngVuuUZx%{yKHUOHD%O8FTQ6FUnaOuTZwAE-SBB%A8lB84~ z=x3lr+g$#$yEtwBLUakcNco99Rj~DhJL4{DWP=^&CIz)A@Q_=QpsG(s705uh()6P) zVS}>yd}L$Ui)KCN->^{-Xa65i;!C2LAVERh^@4wHVEjkxqqHoI*57LwDa_EhXDl4GQYH?2cV3sCdH`KK{1G}Y_`eSdReuJI=2{50>2UZ zn7Ll?x=IUkYcs)MC(;0#a2>@eIz&DuxB# z?9dtc=}5K|w;k|r-_f_HY-TF%@Ps2Em(-dVO6zm1{Cr_vkRNhIKf<E7h#(O0egC>PVP01xMas8#q*``rHc0&uX1#d?7-jBtI%aACkZQ~LXv>!x zqB`-|Zv1;(`~kJ2H-BC+QD)0!vpxJKJjgL{zbnFa6m zFn>vJ&OEC+#Oib|#Yvxf$2F7^#qYSL=LAZ_@z#BDCWD;1?4VS>tiGRX;neJ0Upygi zHFZIiEGg?B!n+Hcfh$5gK>V~-KT$gh%N@=(ZvPyEQQw1KkQiv8Z z4iJgpArAPaYnZrhxLNuO0P|nk=7s)5M(IynvI>lD+w%&k0*nXM8pRcW9e;|(Sh~8Z z+cOxtSmPUB#j40_M^!Ii61KB2m=CRy>eG*-krpqcSbw1z{e)2?zU~e>a%L|IFZiC+ z8%NuNNafH-q~-w!`KqCeshby=nLlg-2uWWo|knn=OHGMen@# zrr_lV1@k)siV+~epV_7lM!R}Z9+_aaMCd^{?v@I1Z-)@ zx|X&m)ja+5VNr9gQB`^9J?^fM{>vlkl)3|N8MWWZBE$lFX<$gn)F9gse?Ii`8SU@q5^yczs2SN}YH&KWiT0 z4yw=RXH9YDdgIHq+olsBKb^$duo2=NwO%JRZ0$Pqd$kyIOxh7K@#f8nC#!hEwA*A~ zF`_08wB4jq;wT(sT@ehCT<&mpy;TiNpetjsUn+MrX%<`HOF%XE?1DDHmHm!EpE02& zqBDSn4r2u{Sm@+u;vq;-{C_}XuMIS)O^34nPQESd3w9y_tH{T)WWTb$^u}Hw)Tn-3 z;9=MdRD+F>KUzmuiqx%Xl>R$sN;0{K76lIduBK$5Kk4nFhG3O_DMVxW5hGU^X_iwB z7#J>Ru;56k+e3)?HW4UvS|WTr6m;n}pv*7~!@K#g8~?y!No}|9OCp&uC=S+_YkqIuh`AyX!IlJq5J|gpkOjpR{ zdsm$*Re7%PZm@Pj{1XILd^JM)s?$%{o{1Bx4bOh-Iu?p@Njjrf4DC- zB?H41K*Tz78T9bz(4s_i66|2|<6aT=gYIb@c|>r&NXYqNEhZNH0i4~#7UR-5{CPVp z%G>%A3AA~c^L#JXv0#F&UZ^t+k(MjIHg8#{J^*@X?L9vccnE4L-TI|@qZJlbg9X75 zz%+pzlE5O+jMB5@c|Q$SK^`&18AxG5+EI;le;CIfzS9QxzOS@4Y=Amn-ogS4hS-j@ zQ&IGj$M%?TdL#QuN2bbaKeJZmFObc)UzoW~8v|2>SBt$nszvU{AGW~ejJ;Zr%bXg0 zyR9!|pFDu^hAZD3cZze(IMb{|ag*)=8 zM2;71GZ>W-(^9*?eRVabR@Cho8`r4*U>4`ht#jM(K5^V#2K8?YFujRRj+PPlxNW>V ziXFbFqJaKkGvd6!V?Eiw+kNl=WW}t^l4uY(RuYsXP}%5*hqb#SG6ih{+VJ|Dn14{F zH@cqzib1vLtE~ZJ=e7%KyYPwliEB1z-<-p^NZl9F zW1$8s-gXWBbF~$=YFCTcneSA8wz%n1UhpfA!ew2_BZ@cOx7-Rtd~PLpl01SITrzQT`PU!$cK&k31xpPr@~78);b87d)0Ox6>d8MprO{2c zNOo7}Gy1=*s4KgWwejsGP^Ff$4)+-Hig%TBVbM_$PAbJ`&#o&=IpNlV`z)TSR2#LxTL(ShI>nwKz$EP$_*Q0l{aqC30mC0gS*r(%#2J}i8*q~D^ z|Je!;!x`+m6_ltF?P;nXY|930u2;SD!H$&Psv9}uK7QbrwOrv1;jsoqK-Qg3;Pe%- zUryhA7-D*;eL|F)z;B1s@XN4zoTw^JUkJtGCTYIUp;6zMwl#$KiT;d zPBV96$z%L*S5N=#UnD3Do!yY=-HX%LT@|Katc7mm}#G!t$a`|*jOUgUVLVWNd4_W6qPa)<~F}>yP8(wqN$cyZ#XL$H%{UQJ9lRj_~?}d*6HW*2NFw9##W-iaaO{|HLv-?CHKo z_ZTUKgIiBuDzs{@3_#H;a2B|^vkZ8&z=?EU?u|wSgE?1Dj|{x;Qzu-6ntANu7bDk{ zJkJ*WEo#n+St?KEXmwehdmDQQwsDBfh8GR5eA@I3Nd-4zp|rh#_>4If_)#7X19wR9 zb^c59gSOMwq*YlW1UgXr{h5bw5_G{>r;5P9>C9d|?!b7oY1^!LAnm7F-@E5s=OXs? z^Q9%gUt7FLqfycrrR7>%3N;Kob&bgIhv^AR`r(ViPsR>5C(DCwpl4J*7eW7+w5GsZ zX;Jd|4;bwZ2UlOeDmCbBq2D&F@dsy)ch&F7P3}S4Uj4o<)%)h{YXl_iQF8`3|9@J`wQw6gm7c9o#@EN`XKX4wPN5~%X)m2R`Mpf5fD zD8OW`IsZ=XNj$ywbMKaWv}iMUefxiN*vKjasrq;c{J4quZuOSIw$gtA}9=yQ*b{m^>u%<*W6nEZ-{lWqSmk@h{`zDWTC46W3^?Mk|D{Ck7@;7ML6 zzOUiUA$pfmaJTgY{ik}rkz~z1TaB2c)4ZP}(bc~^W9}0{jWxaAPkgtH!~7Ib7xOl0 zNm^9pKOn(xIsKN-^qnVR{{a*~)=Fjmi9^v@I+cPYB57y5dK?8MDF2@0s^WPijRw0) zP>|~^dT4U9aOjgjnWg(8|JW5%ndoQB2?E-kLo6%%4_6$! zG-n(+m*+2X3-hKhJdTLh1A@_P-1A$A)5$MS-iv7%wi-V)gAT>F#$5-_-`sR5fL~{N z>FgLpZae8dYMZ{Q9W-4Uos-xc!KtktYBHUYd3OeZWEG%xo>w5HkCpIBZy&yG;a;D- zBo`AV74EL*@jFWWRkK5#%zbysI}PKZf55qAOK*jfdT@O0A&>f*KeoMFq`r#H2RDV^ zR4fTCaP`pO8tA2KwNWCX`{>%k4+Tw5n{TOtFPxQ^_p6^?yRDILecDrAxfep+T1{d| zKK>7As5vkEv9Z>jt6XA4_N*Kp?byqBBExBtJ`UQPBX;lh2d&8YNKJV|oJh z-r{GUtFPBVZ)##$?qU`D2V`6}RXADoT*TcL*2ML+&z{Me#RX8w4X}c1%6a~@_ERu> zkTx^YE}Jkcl$9qzuIludDChi+p zv@Q>v`d9T}pl`*uI_5aYd_wOQTs!doNyZbAKr>_u(kLUP-a8#D^8G9t;O=EJR$kiG zd)SkUmWcSCQ|7j(6g@;5J_qJrCGA41@7%i5m}HZ9+iTch^{0-@qSRpx3wfiWU8IOB z+y5rJvqV;@sR0H4Po72n1Jt@54$2HRT<&wGa{s1NPZebQgQ-!Dx>LYWg)bSg%d1jF zQCcp4J{Gr*J@!IlSzw;$EgfxC&~Z*ka{kK4;@ek;J4i;ZMn@&I!xWw@j7NhX@j1`F zue#zlyKa4TxK`|Ox!kK(TEsH#e;WS$Dryt0DAqFm#?-BF6s0UM zY2de3lngu8)a84Cf9jYE;;e(pts^{Tsl$Rbl3jGn}(z0n8`h4Yv1kf z$>6n|XwX?>FqCK6Y8UOD_@sy#|Sg1{FvON@$IzinxQn9Q}nkXxihJC{t6C&Pd5 z!Eo~?m^fA$%ja>zjlwkFW4_XwsR@RVjc7-?5^BJVwn3>phuOK>7S^q)FYOZCY9}(y zxg(<>_uf4e)KCWN2Y>x|a476h8cB`nv-=DTm#D)NGnPc7i zrtAFZs2Y}(ooD&__>DE~CEg>kHJ01#C3B6@j4O_X=N`d~r9n_gxk{~f#E;OS17n@ z$c;>2ZBfhWijkQDU%-ey3wi&mR)s;t+)Vz9XPy`SejVINXF&1bYx>WLPcjQ9@?rui zr>{cx7CrO6G`e+wvow3{X=`;=NC!zw&m&e-)C76y=B&oicbeK$Tnyc0Y`E$)mKUk~ zw=>RsSX=J4rP7%F!z&p;vdIr(g)|axl@TGXIpUR?atJ;VQ(0^xaXbtcioUp;Q7D=| zc4Ia0KR`Wuezt`>d*vxE=~LCdELnfQk<|5YewmkqbB7w#zr$B@7ZqDk^!35Ly!V~; zL6n|iFRT-_pxrYZhZl<4b_{%EaZJw90Xev7Z5JbL+33wU`}^&P2YE_JpI14luA!WA zQ!n~P&$;ykkgFf*w3EH`;_JtpuexRkg6wZ-MdeYmL{Hzr5P&%PdMsD%QO}90rr^sV zClW_lJ+n>=tY_~7PVS>pRs)|kQw#jX}Rh5lY# z(ugkCACyMMSWYi4_#dyX|L2I;9*w^#2_~#_G)*&t4d>1o4(5HW{Of4z}DJ_vX-Yp0gHFdQM)>BNH40_%xgYbE~ln2a}qHbV6L?qlmbPvqSV1MNZ#5V3RT z*NMIONjt;W{ob5>P*`r1k^V)mf;8|DpXqc~9ID{p?mf7byPNQUa%e9weI?7R#sD0> zU4AFdOK|vMhW$B+SarOz`YzY#Wws{o);!B9rbkv0S>0rFD48{lY+t~=9!__^M=ss8 z+!61_pJVquavFrBO^eiet%1-Vd|$>|d7D^A*g7aSzqoa`6jJ1={Z6DNwOt@RrKVXR zri@qZ*nHRSHfP`Txy(vdaeRw6(3crF2nn>upX^^=eJ22c@>-@@q0lV`_H{jdFiRJqZ2o<=EO6l)}ANl5a;k9p}$t?I( z=&s|ed#E1CO?>*ycvL~pI-ZYV$`us3ix{NKwQ+|`xGUw(9a&jR5G81pdo5P@d+yU@ z1C{15=9T7Rj_c^OgEnEH7)T{?LUgS2GE^5UwP;6cuIYJ z8*dlQ`_g@_F?^Jr(eDL!_{1#r2T;`=&?|>EYrMIKLziUY}BOG;9*NqdKv)gYKXrbtR9IGfP{oygLUboa=im4ELL6QnmEK=*+EhJ6*Ac|gj)+JHu zIwsd`z0AL94+6YW?6}mJ%d&At=kFW-LG8TI%IV?MRizvI0*n0c!5Y#r7aa;@9tMi- zd5n3DDP@6yv5$wKN)QUz6Y=45Nwa+W6Zrn4|VC{O&wd6--=^iFj8 zcSjd;;WVggbaGdIvhpV0E#uiV7EhjKZUtGqi%2EIjCQN$%U@h}KRA~+o$VO)^+o27 zMzJj$2&vvD(;P$lk%7)pa?h}dQ}p$yHb(vN6>66VUMs%bb~&y3z0k;1l!1h(bM3pw zKM30Rv6KZ)uTUUq?s|7JH%8{R{bF_FBgO1|GxhAHGm_*mZuYik-D9alrAmzQG=ev_ zWsBab%yD-2XlJ>(Ry{pu_nN<+*nCS`#zeE`+d+j)dgqzHAJ%PauclF@Ow~C8{4%2@ zf~#~$=#qZurNJi(XT0Gf%{kFASLdZf&uLuH&P}8SmmNOKn3B%53gzaqny0T=-gj*+ zPyBT^XS#7^^L^Bp#t-1{cKo{67L=B?{#@aI%1HtH>pjwoTlVKq7j_&dQ0m%~p~vdH zi~vI$CDzd5yS+_{Z(~kgS@|Ot-q~4j4V7P^#V%2YB|bTK9-DVlV*rMPA#7yGBlxX9 z+^Yd?%_3vu_c<->8~&f=d!<7hnUz=A)e0w^zWGg^TqTfR$zMC zU^SU5L5zsBw~Ap*+y4bUHo)Y@E!y}iW^mELQd9ksvZ<|S!tAm#}+xZ)@K zzdw(RNaa_mY_tZg3wUdA+d>Yv;Elch>aYq906K46Z6P_bAS}0glK0_JPte*u|KvC`H7RY&1F=Tg-(I?XI5fM*Y!asx z;Ep~Xs$z6D|Bqz;K4~|G4>x#wkG0qw*P*YaI(BZ~o5Ywpz0J1*e2!0cB&7e^rbtX! z-6*9Vw;NZYHaJ{#ExF{_lqja`UZ#WIKqEzc6=V$j8zkOd$y#C~CJ)zQ)Yv`;!eBCG1U#jEGU)Y6@7{>PH zxee#u=GXDmi@S>NGGe$t+QQR!tj4C)d2}@A{VnY=Rcz9fR?pcNmj3}dmp^hnWA^rB zy<8#Wd7z0=V`~p8tu_psoF6(GX$EB19*JOm*_k<_s_*}zo7;~!CtDw>T`iv!NsmUuh5y)HCy)5Z&lsrMuKr3 z!`H5c)C2IK{UN;J)K{e0JnPlgz^9Ki^)RK|jo2;w7VJVOHI7PS@rzvkfYO^h zYoE`;sp*AUZ6RDJd$?>fd{}1;%K83M4~mt)UhUGJ)UXV)qh=sM0=i{si#W(YI_Z;_ zFcBl9hNH$2kCM6B5`d@$i?J%p?ZJQ;0*B8YVA>j&U5)kLfSm%6<>uWMOx~9L!IRIz z5V?c9)haijdgCcN7k6fiTutEfRFL@@4Q5-RbQUek10$)D5%xuCic(~$5$P2bi6G`U zIExf@cXSTHA|q#>OJUJDmSkUv=s2VFo+o-d=rjl&p05u&IG)P-UY-vnVtXz+)&L2L zH|VqTwkvUfmlP<0CBWN-cW?=6MD6E%c+vlGgxE4;xPn=9T-_-MO0NaZMK#llorw+z zuDl@Ta6Ngj9b`^Y*vsYXfb%lF>nRc$D__)vh22;Ca%f`1W(=H)Jd%`Z zETv}@S37OdyO%-r%)yj(fvhb|&WM zFa0#KU!mplv%ThB{E_eEt^$eEU4+?I2~8~!z#VDZZE9o(^TEP=avGQW51)eES0??` z)_2(Z={aQphb#ZO$d>1qjwLb|u)+?M3+{&Q$s;n7Nudnoa>pN*u!<)pV-oK;Bs z+(xiK?cdnf$1L{LmV$rib7QdLQKa3MjLVC$^tYrxL97I^lhPofeRU2kzM;xn_Lj&3 z^ERS5OHtaYpGmP=id-e@q&-Yt6+N= z1AVd2>(XIRH8UsHpOUwbRmckMY%Nx~1gB-21=l%#?kK4al8F>OKj2XYo_-H%`>R213a-`js2QK=Ik@Z-VOLsJ$!tq7LJ6^sc^a zpi88sO^**^hI^p~Je)r7`_l*J5<;nYlicOCGBIyh2w>>PNAYJkbzUi#rE;`-Z<6I# zN;2!(pK6c%cZn0S~}dDNY@aJff~zsDZrFTvnvz|-R%PNkWc9dPw% zyT}2yI86uCd^6_Nt>c##s3oD;#c!U|(B-$Rl@Q0&D!A=( znUV%p=ZMywIs=0{YKGd>gTj6vxMj?ize=#s+rkr322z=&WGA3}ULsIzZg(Cy{Z4^M zY>vFm6UrP5bC-o8XpPuE-0#IBqP!o63em0xq)nSM;qLx>a!p_jm&5gfSC>IF)gO|zyEDU1ceMowg@cT(#|p@L?n~*{J?+J2 z=N7?=xH#a+qMU)bJX8{b0Vi%Au%6WzqV(kYZaR=RGPPueq+t=;_GdD>5P_eTdj^&m ze#(+$KbZG`VB7u){-p3e26)Z`4+tqm`$+ZF+I)V?yw%imEyZBrxY)*xwco17!`R`# zd_I5CG7x$a5(W_HUG(LAv2@@H8#rmm2Q>iY83YBaav+G3j}}q233Hd0hst--z|pu= z|9$eP(1BkD(df=N6Rosr679!k!4)fJ*vOs(v!J(PGkP5f8(k|2>J)<0r{|5uyQAGr zwfdz%x5&+&beRzuP(ko^IIoQu4XXafw(O)bIX%lETaq@yx8ktBNK8~SZ>h{QX2`Db zNt}5d@3r1^bC0E|GH|aD&UD=i2t!s7gnaBAzeJOX*672T8G}5x^t*nawP>IC#eP4D znla-phl+6Pvv9qQY?NB1z zNDvXFid9O7gG}v4(DCTt)|3Q{yVLZ*6U7eUr7j6wS?2Vm?*qnB5g|sK3=c}OOu_*@ zv{e=G4c#!ZPvquiT{pm&Ly2KAkPE16Ai^_SGymkJ2FXYp2{7%j#C&eU1{!D|fLsC) z^q%ht4#*nXhEacfgm>WUdCn56Si|~kAxZ>;v&3Y=zSWORCtLFq8;p5#_c zs_c``^QuMa#P-B*K z^;ghdlqK)4C;z796c%hnuJ>?__xmg8`zdGBHrGKTP*2ZMW1~X0Kn-%t_(rJ;(z{^ni;=0Ej_wjN}^?Hky8xE|iQ0P;FW310kA;vH9$wM7YfZ(cZ@P|EVyA zFJ;f8BP*>k3o|(FhGgq|k#^aYpNG~kjK0)PzZsx4qM%$4JX($A zIu>Ka;FFo*p6@pQ;beQ~&(Cf+P-SntF=q1E1Ngp_N4n%s`%Iu4*Vs>iI6Xyw12W6i zD38~dR-T*>MiWJf~<6zlCzf;zu^!YP2_3=;mRuUU#u<;;_bqI&W$ zn%a4X5mFa9lt2gX=fwt$6FRiQphBMjx*d;rnkZ4d|Fjwee1?JiV^-hOYj8DF9Tu!u zk<&?C9t6YQz-8yY`oO?w+mQ%T-&0#lMaS`bpDp0B9-ulVZ#Bt|`KW9a5xjL*76PC6 zXGHwZY@U_sN4<$at<~UJ)0hKP?wlDM3#A5gF@5C2SIo{0l+Lqi`!Xl2h}v2yqx##y zWuf}x(9~RJwCwkzR+D;;!zz%=eqB-mve9C-)<5gO^5z*=5Y4gHL9)>s02^%m34fhZca z(W5=DO$(y&E8v76SlpabJiDWq=Z>`*(1rYJGuu1ry= z8HzF+4);@nsMIBC82y~Ne1fzK)%#Vxu!312EWk?N?%*!wV?;0_xZtv|L?jBf$5cUd+ums86fPPB4x$~T~5Z)_O+Oj z@kUcDb~l&*!?ETSD}TX=@#6^wuWP*flQ#n{(_ik1AC`@vN&xQXj_u~DBBcFuM^&%g zGDK+`xw6om$VdA(uv584D&VyUcf zi3(=-h(MX;yhmy_ZN%o<0NwGYYT^Rf^lJ)shAa>|s{j>r?MYdg`GbV{n0M=DwT&90EvrZt%|Jq2(f`*-@Jm1&Yh@1o zmu8e%gdha8huc35tdTW^C>wIA_SnH`+2zrlQlX0p!=P$u?{0L)A!w~n*hnFbi(v;? z-rR#Ml3s|AnKjP+5H%@=6^7>Z#VeeR%azjNm&pn}*c_*(4*HeEnlOI}a`mNRV}-95 zB|2_0ftX-P0_I1yvG9~vE~DoBU-OOtc=kifczk%iJNGseF;0Uaq&vw6{O9YRmFlt3 z87dt13=+(>0z@91zX?ckx9q@5`6Jk&!M=u#QbSoURa)TS&Nz(4kUM0{#?F-3!53U6 z%-BmMH9~j1#RDs=GTLxVTteo^a@uG;efj0HZ|+7mrXyg^mUO=pc6-PrjzR@ruAf=9>g^YT zMv^>$DGd@WDrh%K?WRW;G~2tzjBV&}8Gllqw+epFS?ip(thfA{>&Lz)!jGAHF7DYO z#R$nDO0Kn`eOQ}R7#uFUcTZk@DpLT%-Hy}^XMM?Y1TS2v&-eZ7n9w?YQMb7N<<#WH z=Jx#8K-XQt1~|mEksg)6BDQRqP($wY`WJacT`;q|70?5_c?7ah^L^WAg1y5>2JdHFW9!jb1Fh+Zlh09@@|jI|L(`VWAzH0vNmZ;W30qj%-m+Q z?EDuN6yRfssFJiMT=blD1RxY|Pp|LiE>I&RY^%moGg#IilZ>??ZVh2y4C6j(^N=uq zFd_g_S)UMX0;LyY{6XBZ#v&MSmD9eR6A2x(Bdto7&9i&}*TU?Sun&Atj$sV_Jeq-l z!)IA5g|(PcZcSKmJE!?RH`RDAT19zaWp+n(gBywfg8meZl%7Gs;JBU*Tc+|W*3>Ns zn5By4=79iW%kZ)8UWj~4Pw|=laWV|^8kLTkqls~mw;(vN&G0Weu`eQNB+k=NVMOqR z*~>Grqx2gr`Tu~M=u=6>i9|z)Ljdbta5Z$=h?$lNf<8u}NP1T_4B-X3tZ+MxrSvWZQ_VrvMKEPD9`Uyc zjEefvFAxYsM2x3S##jb?j=cA!WdYcVNIGv2*p=Ko(MOgg5TOWYuf5iKV4#g3uiyUO zhs#6=4Aj%F6?-yI-pgfG19;kfca6}X4sK=NlNsd`KlM?#vK%vc%m9|jQ28;qNmfL= zb(2wI<46XoutYx^+G~fZOUohWhWAX&Uh2St-J&n3!8iS3w2q8e24g9t;%H~OaJb6MDJQYlJJE43Z1tJhqVa8FyD0J+Lu$n9pdPyO>85Zwm8LUxYW_=V#?Xk= zzhucVAis-JAXuaU'!)zBjeUvs&0b})?Rn!nYU z)nIvFVEJcC_L3f#Hc39}kZdoJPhtga*suF~P|5lc4w@G}H0^9#W4XoV(RTI<#6T_1 z;8P%)U8_V;{wZES!N9wt-h-1z?GY4qt%G0Y1_!cJX)s1LU@j3`|CUo}17=Ac2!v}a zT%#}EOde|SiBWh63c|pYBazNWR%UR$xh?jaJqO}>75d!aXK||sYGJi@s-Kp`e;Uv< z_3a|TN_>hp-MQKej?Bp0h0vM#S$Z+Bu$VgpE#()&;TVj(>)1uleBtd;O|6lY+heLD z61&Uc*q=Bp)Bl;cUDzh>Lwtx??MvWdV7`BgFd^U`@9B9({1>WZ+6dhkfA|)&1+B68 zgfacp5pGgN#)2E-Mz^5Hx>VPK_5LH7Xt_^?+0J}~Ar^iyMjx9i9@ zL6CHvNz-eY0c zm`mk*w|>*v{ql%|SDp`qa^Sw;86_~-_#*En$9&^=bUvge?B}KE$$REG-aFYROTb1+ zOZD^;AoJBjjA7lYshDEbx5u>svy5-o;G0buYv!A8k9qFVSh}36)9XmS z-)7kS3^D%;yT+f)oH-*bvz{4?+qumOs$nMj8xXNbo!M4@YSOW@fq`f8T*YwUW{wm> z^*_!CH5x*9=DsGqKRqIjf!6vPRXt5EdjRcH!4g_FUsGu5U-o$P%Q3Oc7NpI%dlKan zVa6ufH4|rr^t#9_E%UEw^c` z?{)66)Fty4!_-;&GfvXCrc2K-MC`62gp<*}_3fly)2$>PmJ>HNw`fAVy02c8P?w%o zzC6ems5<*v#7ZQ8%xRGB%$G!tz6q*I0ElAalBj-*&NNyW9Nib25S}>(SMs3SZ+Ro6 zeOIqOjVi!qw7{|4g?Vt!Y-sQIoB8oZV0a7Yk&afkv^&A2DfwSm;L_9YuHh|v+wSTg zK`s9N+@2*Y^}J`|X~moH_Ib4mW4HiU{z`%3EKf*{`xy~^YU8!cxnA!ZH_bPdoE%|# zuDavF^Yn{$`B8(ZQaBUA>mvt~Pdjy{x7KvKfJ1Sgl{0r}gh0w0P#bw<=Kj zT(?n%jn^Bp@mQOclu_>o9Xcc~)L;#g3K^JDVu>w|}8 zCimQXJT*l<*`&8=E-2f-sAoF;?6?iRJ*lc ze?f$2obH49fu0+~dyWTm{EA*|yqyIQ(4yLB7clSOa2TU6OX8tPwbW!#n-;yGyz9W{ zUrHlI_gHL@!Ilr=3YC-GQbdMH@iur#&+@KtrMNo+j+N-QaTyM+!G30C#y`_@EOdk7 zYAw6-;IAvM8lc(1Fhg(DH*3!;xaytO@_S#BzpT*obH^-y^c}rZH_{9XAEN3))+?^J z+;z7C0I#4l4pRM&*`-(Ml4n$pL%`aaThYiaN&Ey-f+%as)FZbq&mWxHuhngRaXT=^ za$SK_%6oGy%=wP`(kK>_R}tYHyK#FhEO(F+pW(cOSZ<9HT|4;wJN^!DAeC8pn7%A+ zTIF}3`}Bi*^)FjY-DtS->grU<61Q}jwBbshlWSQ}K$bwi7-^T)Rf!dG4#35HXnKkk zpXi#zDUW|2+qio8Y&<7nFO7L3x@1iCk;SVqwej-p47p9`rQ4kXo3FKq$DVktIJa_V zkE`<9VubrWZ^-K0)tL3TS?!()RM}GL?~U`zFy)Z;naxOVk6E|9f}<`zsn9mA^7P}@ zsIH|#9|2~0PHX(dmkr<3OSK;!eY_HHc9|Qrk@KNJqF!g<-zfZK0<2{P4_j}?ACI}Z zszpEc*CC@ky4*2 z2w<;%j5(4dnB8e0^nAKxyW0L_8q+Vm+Zg>%bo;0O0MD@dF%c_z`k`t==;G+G-5=!2 zPuI_z8H^JDkE3&sXZro$_!uTc2WqkzO*xeuDsz}a2d6Y=I>>3tA*UgS$vG-9ryR-* zIgFH3jv;45LMSrFM$FmFd3=8F@9%#Phq>SH`@XN&bv-Ziv3|{jl24kQ-rr}OTI6-q zfqorM)`3+n3x?XbKu4?B{?e^iM(tY>Z@hRI_@)`T2iy-h@ye}o>Lyp8I|9}()&D>n z=Nm6st^c7!AD!1=mhCZD-l;shkb#(jyM&abg&|>d>q~jHf?LeDxDYRIn6pnzndNyWF%MyLdb{f-Jmv4AJwgB6YqG-5+hX zTSrl+6(M>)bx6FxLe+xRe4!stU`0kZV>hTo^B-{ySR^4+tK{R8uAkMRm;08hxsE~J zYK{z6=Xm7DC{_^Jaf#zWR;n4_OrU$O`Od=Ze1AM0JHPq|kv0Y2_e1p6i{UK8f4NxQ zIpOHSLt^HE?pChL9IOS8oVjfPWD!kW9J09ql4^Ue;yvb<`nlpMsAtr zyA<^5ork1|pIa zQx8tTZ}OdDlXQV3cHoja8O`6%ib*2}4nou&8e`Q=txy+nxZ78~Z>oSiF5s5GRTUa1 zQ+jYy`Bn$F9uEp@^K(sYo5vqDTGvGAXkZ-ydF{Z?N(`gEZ2Mw^4#M(6icU?tskHr{n`h$fKZN!9y#C!wzn6dPoR9m>bmhz8V-#vgpp zmQm?C+ScR`mZ87vr9anbUz8T?c)REE2hBA_f9Q|-@}pYA80(@Ao~$dD_U~eNYB=>m zLjVT41v4$IZh8Y?86Ca-c=ohM``Pz;16Z{i2g6?@zH{98^-4k@+cxyG?&ARW4;QR( z$vKki(0$X1o|;pENh&R1um3>KxUq_BQWV_Pp<)PB_)32bj#VTP7rAQM%+N+RHcH!T z!=m1ZcTrRKbTmj4oJ#$V_jsaE%fJ;w<1O3In*k$IoGt8+wFw&Q%;KM`{AVu8Xt(h> zZW7R(-fFWX;|r7?#oFnZEm_^@+qTz!StssFg2Vq;sdrlX-t3h%V+^u|=d9m#@YDcJ zNP~Kx)=~W0-2FL0Z+rRn?UMVwBbzTkmm5BTsF9IBD}o%d2S3Z5-}}?EDh%?{Y>m)= zGJgKHnn|*sJjx9y_J9#IIY07`!Z@pbkVMzG!uC|ZgU)wKTFOXq3w}k=eZQq9; z)3-j?zm3V}`}z9JW5zZ~o)Vw7G}Hty{_-_q?9P0|1<-9#zwoH>fCUu&_Y2M|0;57T zDf6$r*V+&b#RIViF{H&S67Fw4Y;OTa2#sG)MDjqlKG!&35c;yf<#PmJ%}e){$G*R9 z?w*Lt4+ZMIl`_Tac;vjz`FUtVWK24J&3fEV)0yqGilw-22!ve5QnSp9+kO+yLu1ne zSL3#}=q6o*_pOU57ll)_FLz_(Ln_6tU#(A1`t{*?&Q_;uf)Ap<4XiCayNG^7kc}pI-kcUsMs9#hXT5@Ut9s@sf$QG zyq7;%X>^BfEoc^{sYon#gfT!zDFgk5Jxj3Y8y(5cqA~bjSz|<@lcPsmo%!^9A|(gd zALrIAKCi*!$Da#H66XQ$HY1Jk9iAulKZEP9+oSbZk7X|no5My_Husp>Ndju`6rMoz zgJJ0p%cy^;rNQr({~)qUoC8ZQLhX0Ff&{$LvL&xC&(z#<;mCM3kw`%n+y+_39Ft2) zy(U}bvyv2=hLP?&Cw%U=T_OJD&_7U!*6??U-!-z;H@_g)u)>EL5pOCyJVS;<9yOn= z4MDtO7CCdA@d)d_xUBiy9)qJmmt}AKzC}0*Z#Gq8z`P(hK#H44{KG%LCnzmq1ZK=v zIZU)ybcns;aPSuNZZSN`P9(P>`BpbS|ZZV;_dQ+mTYr6A$ zWblVCL{HR#Pf3FIH~ifk;wop| zJ!h6ivM}hU#NU_y1AUQ;naO)a;sNqq4C$|!@@G%KA$hCH+~V40SyL}DnpZs1W~V-O ztzs6UXU^bK#sej`5C))s7hFzu$8Lt1hyM)1Z2^+GLG6|IPuh(ush+GJG z6pL2f=+`s=4G))G^0c$95Yq=E>gh+Jm#n~2o|SpG`+tN-!-e+4w^kl*FE}K$0zQX1 zk@H9Emi?1VF`jPcQ+Hn94-fD%C$dEX{e-GKx4!&0y!;$pUP5(FJd1V2$HHjiJEcV| zRF|*RIB`b)4~-PKU7FIM5jvQ-6E>=TmQDeVS-(VKnj2!VLeOXMz@pFVDW~5L%hyP~ zld_8bvs25YxLNpN8~+2nAl1^t)DC`q@0xx3I&F8aMFU8PGKFpn?gfnH$r(&IZKjr%7x z6k1ajwctuIAdI<(8x3_^{c(LV!1?48==1IkY@Ys~pWD!^*SOwjQX-0$y|WU2<0IP~ z>DUp>_bBCEPS4V(=%KG^ZthFeJwjG~fXzpZd%41VT`gGqXyCsa6+~)Et3vLYsq?Gi zVP3kQ13c=bogGap^eW1L9?R#xok6$}(W5tj zm@s$)*2}LSGB0id0Ud(9Ph1* zM#sBuK5QjhBxwU|Rm;_eSvEj_vB~%TaCH+RETI_2O`%is1D_Wkr65nnPo98)mW5kZ zcC93om7lcV&OOQZPb`<}fyWVk{cN}D<{lN^La7JQ@_qdBGhnO8B!TRbRB`D)f(B&o zXa^mj+}72VDU)au&>o>w7vKRvLM`50d8Y>z=hp~*EBY(5XyV$ZtY`Q6LtpM%0mI{a zYlSTleko)8eoTNO_`CcP^Vo%Ck1gpczj8Zt0Q4~AosdvN3|O#hs#A|1Gxu5YyjHZ& zoCY_@5%{m{TF##SS~An+;1|Bo82TVJ#_+dV*>w+7pZ;u56EnF7_b((zHyc9?#Z*{J zGH|UN_x56aAk(H>nva&V4@gw@CdwnB%|aK>Dg&PMljZ$1z-bS$>q2^OlG+$Tob3sp zZ0p?CM8Z*;^A{@yy?gzoX;AyFZa@NB;z0Vaio*ZpsFx9#Ts z8H$ir74^C!@V%uJ_WdRGdjRQ%oC5$8G5UgXzrk~z{A|-lwkc=WYGKPJl}skfrTbjPi7Wyxivlx4vN7}~ z2!aUP%|TN6iYfR0ERA(w8Kx)b@hF$P5&FObgP~D8fz8+ud%-(4TXd=~Gwi1PG}CaO ze=_0=2;2*$Oi;8BWh^E{*DhBlGpEgNo@l?_`t5qD7vRTPXP*W&r2~_QTm3RM8MU)= z;}J$ZjbDK!?5nE$s>&Vu=8YQV`DF-Svm7}+x zAV0q%D5WR=h`%&vRNWi#JOzrcX%d?~u==tPdamJkNk_)_WU|4-qX%-v3g|mmxFJP< zzX|Z2)s#C1CS|JPOgjxvU2h2+mDm@32dSC4|J7u{{a9s4<{#VpivU!ZY)zePlM-`Xyw}sw%Fr=LC*CRb>p1SI zan$IM-HGusc>9}#sh$37Z`%AG`(!=-a7fetGH>K3G^;8}v1MEA6L0b#eCS;u$w8@Q z3$tcN*HM4qf5rW(Vyu(s>~vL1jT@ZS33T zpw{b){He`Po3x8|u^Js6pV-HvCH^}n*LTJ@aL z0!7oArREji{2d+IJ2bI7Z1j%jhmI>k6t2_V`e*L%~M80)vcZe2zvvmg-V5CPtg$%q- zqo{bGaYTMKw*3H}UDG>DX3w6n)dmJSIcQ*)eOlnMOIc$zGb?E<@%_+vW?@Y~ZyR5P z98TPXB8=+P_0Xcd-(`GnxBBgOV|dk8Y4shye3PNY%$V=b++beOvm4id-QdbhQqSM% zd#jAq%XiYEa=XUsZM`=D1Ap|llHZpq8!dlRjjQ=n{SzryA7k`*W3ieO>Q-I*Id9^CLSMk`UunE9q7117rt z%HFrJe|f1E-q`T%BJ8FBc8NerSs)>(xa~lnda+a4r(3f&S8N1#rpCsY`_b%|R(tbc z%9!IpI^oJmscT7}%y`&mfd!@T@WjT%(f81rPqcL=-YHJzyh|>C_X+4d~xqwX&uy&}Eeb$-dwLA)yz;8aXZQ~OVe%StfBoM_! z3N7B*b&^n4%K~+8hrS;BE)#X!FTMZZ7MAg^$;b&&uQ$vuDE=SlF>ZuW+KYhX7{$~K z+=;TN<-Ld|DD62k8Bw1nd?E`w|H?T0jhNpoRjpeX8toZd1fM=AQ|Vfv$Anl^a8s%- zjY1G@1ZFRdz^#6~v2p1|`JX-QF5dm{H4KE8m^c#eF>WSOkw`JZyv?r;GpEG{<5sjz zURMH`dixfEXAdU#m{hZABHtFXaCA-$OT>pJYMm%+=0~IQ4yLXEfS)TOfDwXG@a@K9 z9d7#g0Q>PeHIz8sArBnOj*im}lMf}kCY-Jf2>=6q2_;?-bkU9SdFHm@B%WXO5GWe? zo$Jqmz@Tq~J-H)guwXh*jPm|pV*K{NwVvsHZeI&032XfMd10ZVDWUV z=W?n}NI@<>zwP8zp`fdP`S zS#4L@j*amPil)z#4dPKP7$0C*xn_1q9Y`yDLUR#+qK_Notcp3I9#aR%>$GUWxJ3fm~?Rc+0r}aS$kjyFe4T)@*W1 zXLPca!U+PlX`}n+KD8HnflnqJzvp+f_NYyApNDWar?zV`$O~d`&>1Dh5AO2L_Ayq5 zTA3^XeUzP&o;}J=G5z+8xC!X0NmegUu6%19-=daD+@F5Qe4S>pY3SsUg`|u@X>Yc- z+DTyj6|#+A7xSdAXmJNTYF@Rb4aeN9^Q*?yjN-Cf0q$3+$A6%Fc{TnUG}L~W6x)4_ ziU{5d)v5XUmd>(MtRL;O{`XamGhI-)Y7luI1u5naTuuBZpesZ0LW$}l6pG%D z93uksZAXFDT;Y{XkfO@;09a%m@{jH1gp3;S3Cb55qj=PU1O7Mc*e6PZ{3y?TS-~!~ zkJ-8@S^^OC{~{^Bzn9x-cv|~zEp_NdXzQ)#1aor;lwv;Q|EUKHLo#!tSkk!=@C7Y8 zWfrF;;6Uc|314Xe?-~Kqhiriq30x||Xpv6=G{b?tu1K0Z4`b*jR>&@w}@uO z4~B`n-SY`2gxSp_=3~712!i(UbMbTf3=gA}igs@=&6Hc$D~crJmi+(%?;c%CV4``k z9Z0hW4W@F;i}=J6nJeLYrtC&C3Z!DQ(4r=iZamf7Q}VxQ%V`xJl0pk`gU-tikqqdby`?duh;#FVJ~bjF*h!iB)hiGe0K|jk*N5(}uOBR8Ls6%7#`DZFmRu+zh_8SDY z2kr%8EF+!EJ}l)*9RgQ>in81D0?cRt=Xgu zE4uf;zh1?g%P%&LQZu(}?5qsKMoIYZ(3v?+Q9dM1fqXfB`P$Z4KEhjXT-5w36WRq} z-2!>M8%Xbf$)5kIhoa413Yfic=mBj6XuY}4&<6RoYyoKHS1(SG!*V74Zwqz{RiBPc z?SvQ#tQSEcY_GakNa_2gLfDAW*&P}^24tZlB~**tm<}4ijv2wE5Q)s(9G;Lhy8yDs zpJgMMAE0Y7*~E41hp`1d-Gx>lN1~i}aFm!yeHIzcsb?M~ncc~@tf0j=-oy28CHyE@ zdQnG9Qy!UrQR4}c%%%rdpkqvR*Sz^v6BK~0uR`e?T`7{j(D+fIc{~^|kmflwV4iO- z&D&FWp)6RT|F0B3ub27!2$=?au_uEn`VtY&JbH_*-3xsq=G)bh&vDV@l|x>Z7i8Bo z^b0|Wxzs1cjwCX&PpJ~p0j{t-F1%S|bj4^I>wP$0t(i70H3nRZAI5;#S7dVM_P*Kd z?jRmGU+PizR`#Ki2P5>_T@?}|C-d00lepnV@baO}Y_4Z&onE2+b9b3g+8!S0#fT+7 z1MeYbIdwZHvh4*#>apLX*xu3pNkaF$&|inD>uC_l*lCa+T=N{ig$Qqruu1r+Z^tza z`^{K+wdzFr0Pwcnqde-s5wY(*`*eE&*k^=l$fE_|08|JMU%`wSc}z*~WOHY^cyRN^ zI>K;9Z=T54@A!Q8-_A~=6etZr%9wNvq5(^3u&xw^Rs=YyD|xZ&YEI>} zJ!9}s?)fMf5uAi>l+F#bA7|U-L@4hG@uWa$Y{7W!&{byN)&dwDK2$jC7zDsOz35e{ zh^4`dzJZ6%&D|D2p;Go5HU6)yAwT-1!JC(0kQ0)0G#)g--qj>i&96kU@2?rms4`}? zh2aqkoNDNn&H!+=!nkSN$3M;1utPOt4uL9x9`(iscMme0uHjr!XPZ_6Q6H|@tM>*u z=-O(@R7MH0fncO2ZHgeW)_gw!9eiaA_PbQ#4yPG;Ul(_ zg<#Y^-;;N+DAW<`=qj5_ry5{Jz5;Yju=wyaQm*LR`ZQ3O)-sMNN_wlTVlySj6^t%q zzqnVXh-vlm0jTIDz}ZpYflrj!JV}vDvrpBS>z*SYp8_Nnd?d&w$`!cwJEgW6SEIfH zM>nZjM}tTzvraXx&du~GqMslrHn0z4{y+CKBPHTvl6h=6>E%X|h~NFJ__ut3s<~Bu zgW)&-56KIJOh(zK>gSP2G@9P@%p9QIbqc5xfE%`^r`lOQdHwC9tSDs;lzIv!WHJkY zbL-RlIRgRhfv3bDD=?yIkl1*FZRH4WCa{!d%0_vJwJ!|VI;Ax?he`q|_;^TJr|JetGY$9(+&Neo*l%2_OLRC`udBJ4 zzH*ln(i3UtW{=Ct7)vYVm=`4`gq{PrP>FcIqk!D%fl-Pz@o&O1WNtxWe}J2pA+$ym zXr%uDUHh^L+Z@X0AOg6hmo@eVm}4BzKY>JlotV_{c!3)#aAu>xd}%r8#-ci(x6t|3 z_)^0`hR&d(-mLFcDeylJMSiVAB`pD;h?}s)J|K4Uwv`KNmyl<-Pjm=R<%GtOVc7RL z07Z@T#JtRM1pyNgJ>WzdSV&0?VD^+|@0;z;`+?{{K0U~(@Nbwv0`_vhp)o!cn_^^S zGnK*?X5KoT2(V89Sh}Jz;&O;JA7FC4`R`euMg!np6td{|At@OsL{@#J!N0wIr=GQn zi@zboEQn0l0-9+8_G+Q?k{iH!Q!MM7d^o_bV7T~#77LUCfi!V;b2@B!oMB_M z5{-rKPN2WjoV{ssSqrY9KY~#9(8Xj*v5`L%gKPbdwu7D!=TekQAxJTw7|$D8JuC_c zDCiJ*1#HqWAj?aiysxh`Q((cWK8745Hp+oSd}}m{AG@b-U5<=gI}*%)^_(z`jXm-O zO>!fGN))sN!oHDV%#Mq?smGQv!7aejg2G!cR&dp4NCCkgZ-lnI9M!T3VO zk8Z1YIij1PU5JrJ-lR`jM`H4*=@<~$F^(+qB}~(ZJa-p};vG(s8iF+q?$%wf#!{iP z+pJo_X)=tB=q^g!$Z|6VTlk++KGP4T9|if5VGN++o%KKEOK?TQt2KP*?A`&k3NVQg zc(IzZKy2yomr3hp_^?UB!ziS>s2U!pbrADuS7jzB7?n5n@~2lVShF4QzH3=u*S%Ro zlBT9XJ2BpnD&?eNVo{$yMR58fHyFm>xVbC^vc@{A*y6_C2TJ%h&x?|)AoKlVr*s6K z11r7PiUXvl*%x*i+Kd!Kl%QQ+aPDEejE>aC&Gx~yY~ws$^Q3#RqQE6YPCqmQ=%lj! z9pNu;ii1vp;;p152>8$`4+co4LxHmER7h>ShSDr^=Rj?btm5WsV63$AEcdFbY_ zIv{f#;Gx(U!|Iz@@emV&e8}6-iqX{&;F15V&0Z=QIZ{*8cvY10ai7OJHi8uyn}ydV zN~upz9}Iw4n#k;CS-_>5jU^O!3S{TE@L0T>oma`HCdVq<_OEAyj*qSeLc!n|--miK z^THGk9DVGA)uytPSvMNBLbud`y4ld3-5|y}f15A^;w+HNByyHRnRq5H=7el<6XHhw*nK8WV#;IvI?)I#I# zqK-DKnfW|QHHdhCm5Z#{oIC7G2Oz&w9m$;&qthXRb0`sl0E$N7)MZ4lp-dHkhAxJh zpBTuN842cQCiqY1|j`B3kL;Jf6A#1>z!>G_u zz+@ARb_RKH;kuTXEBf^=lOb+iTFWkEPQOhmP{jaHH)UwxBsF7j81F);QELLLmgcPP z$h;aBpXOf*9zjd1$Ov_d7>NQmZ{Qh*Lzdz<3fBu?dTxYj8hN_vP;>xHiokk4jEUCK zlw*R{GDbdx3G6ucsmw!}OL|=Tasd!eTBl2S>Jcn>{3L1o8E^(;=uG-;v zDQ$iV#M=Vx&t4jQALYZ?B)qJaV$)WiiEn})y0l~zOzKF#aJ-J{gutcL^xYg!cd>x% zk-xo_?6?yHmFtRCGe6-Sn0I!AzJMuN zuKMBX*;2vudB}SZ8#sl-adR0hJ#B|0$U{DZ3hlEDCCll98H^Vb-BiZ@rWXIaaKGF1 zfqB^T@so*r;U?=9(x8q08uYiy<$PcHnc33i)bTJ&EEyiw)Cvj-%cY?h)cc1De6*!@$ zyXgSjN+6YcX#Pgbos29)%-lir+&rPR90XpY-#mlN%4jkaXafp&9AbpEX0iX&1^Ua# z<-%;?JVr=(YVzzP*<(2&FUXY7+e?3ffXA}|Ef)Mr3;NwaTZSa&WfOSdSCovfj*ilj zF}RDCfB{s!W6c`VSdtNK1w)e+ft|wpAq+ex%)%OQfZVEgZ$&oqAcLejZ47R?kK(|_ zxBn@QT%e$f5D?~=?t_5f)vbSsRUl?Awu?AB4Jr5KP&rI=Zgq7ek>@bZsj z94^N^xx)z(vUURb0vjU4D1GKjLbGo+WIa|FLQgvc;ORy7nVpmixMP@JDd2$6FUM_AHnne__ntXrOg>V-sVv)Hmw;6 zqa0j(UTXY6SG^})A-dsXOVG)ISU%q(u9X~O>})(nz*V@M!6LgxHqVcT z2(sPR(XcqEn+cY|#-%UR{s;ONbx~_o^>obL(MLUz!Zft@ey9w{s|AIuDUctQiO=i= zbxvYbO`;tPSj~L#W=FT>g!Y}tjBK!QizyF{BgiyN_xlt_kli+`P_k$Xk$-jd7=w?% zMxkqQ8^qOzNs4BD20hOYSzn$gKa`&LV@rq_)kwDm!TqEgC{kvqovrWU!zsrDdc>mfAe8& zum}Z;=U^tId>UJR6q=$2xj;n$Vr#bO#J5TiEAjgwE!Gap+BeUR7;Wx?5W=?U#!fIV z0K4d=i7?0vXp^4~?}my24@FA5>&G_OGs@_+Qm*BlCCX^))EwO{@6b{g2^0@6`onn1v-Ef>5fWz>hw8 z-D^H=^x3I38>?Q+8C*9_s0HzA$*F3$&+Vx1>nEqU8ceLRpeTB4w7FC|+(eJm1MRZs$aJ!M0>oVqaBV6*qT7Vxq1h zRhsoRH9&(K7CDpHtv zzG(3kV6@Ft_#zo!AZsSRT|C?IPcO%hsN_`TIB9fREnBOFu=cnME+bi+(0+NOU?7j6 zy#u@ke@xV#88gQ6;|ch4$Hf7A?&9n?#*YzDX}{tT zK%pBVy{{jWVC$5pdBA{azszeZth)rOksl4b zA0CtBA9){>L3K^roddmJ49vnBw6sR?)({kqaK^l`D$f=aNGjm5cMMPC;!U3Vr{F>>5V1C&rQZL^= zZxunbEj>6Xo%*?Ll`$My3r`2ILZ$giX2(6s*>TC?ByR!Ro=*?v;MTCXHgaiAZNbyr zxd>&6XKrP5QXL>q&M(@#&D6xtjB|@Ns`BwXyeE;3T`sLMh~knYYm8!ffl4}KTy+RD{3kU7&qe%T!7jB25m=GKLu8na78NaG~=Z|U?$H)JMmebf(m3vPPgT6yE7DA=Pu~hpMv?bgD3erW*y&M`s(|VyCF5Mef4h*?!T$Tr5^8^ zSV=sB7iILuw7@esKx*3*AQ=&-J8EHSn!}~tOw%09aJt+o?!1mtLD87ZLXw`GSa3U1 z_IMjfF=*q5ZTTF}i}68rjxbg(x_pXJf}c9}Q&(R!Cr4WKH_?tRW&zuh@Uht_eAHM~ z7H;d~28F*~316`}`Qang#%13B#|eN<1TS8ATKy$M#~kTHOEu}C6=1kz+jCghq4v<@ zu}0*P;x-w@qfD4ZpnGd)U>B&2`6C#1U0t&7H|wl9 zLa6eRxB8a)zSH}|`@_7RiK=#T0xS-zxhpNLxqtm4#TLGV+Q@D_HF?zUdlU|030ieO z`46-P`T01s6|FlH(;0Gxb^B)P8-I=i=#S@0>*P$=(a?S^^L;|qj#F#b&!aN|hXSms z7z>S_^Vin>ThkO>s~NryjUg}M=WRG2y<0ZXAZ;j2OlQQxV1@I<>oYcwMGzJ8h>5)l zg%)(E40BBo{*Av58}`9D^m5y^IjWDFG3g;VOB+LIE3N}*=Jr`v&@JgYX0mBEtT zT-s)WScb%nvYyxR!7o{|Op$Hf$4B2c&fyi!wCWz&OwG9Oh}K1hi>p8LVjt zUY|Otif?ZT_ExpZk2w-StxvV6ZRAu4WQhFI$nd|6A zBkfiXJ#5F>=pSdmmA2fhKl6XV`~usvd7)FDR-ZG!A!i<% zoY%P?3uEAZ+}B#1lA^i5>~PG&6Yx2|m3cL{}mZC`_% zmO*Sbm)=_cS68@jHp^wu!?9Y!to4ziK$<*bDtt%=qxm&hwrAQs9lPn)!vZQ!S1+|r zJUDhCq2V=yHM*D11kL&iPmdTPZnk$cGub)awvuqX`a0bW1l3F0t=jY6e7b%=xc^9?w8%L zCzihlujE4h1Bt>H?+x!zcB*6H-!fIM_4)GsD!u%>B{!_|@uf3&vt^ZYz=X_AYq!E0 z4SUGb7o9rtI2Of?XYtvU^SAAE{_zOP5PV`cn4hj(c%E658LL9sX+8`|@%v~Y?E&Az*{1;3caK&46X-}ulrru~?@8$cK7Z@0N{xAr{QTZVCh_=X->0=C z^;5}wGyc0%%%P(7d3x-#lGM8@C4&8@ z9aM6=E_k6R-{W29ma9}8qTC;#Hcmxx>RzTy%a#VaLYJQ}emw_yeX+;|0oX|`;ghm~^G|Wj%?mmK`@bGC>R*I!H{6XvLl6V|+a=Lz0niUz zE&MvF%4HOz&fN5?8z1!Qd%CCsURDH`&!FC)JQEY2f`U%{Ihw~;1;S3ao}`HCKFaxu z9huCu7Z_cAbY%RnAY{|2fcwZIu6SJk@^E5(Qp-ztO0buzMYhRS4^dC;nezP##qM>j4nd~&Sa0pLD=RlU3I1<@GK zvL4ilF$ugGabnI}(e*c5Y*J2If#zYb##`#+XYMf&8>MCrGj^%VH%~Ld`Z~11p5N*5 z*~RhaZ$>ZYg8Z8oP|OY^5s3iP(U!44M>`=^HqRWR98*FpgCpb95Ju~tnwwld%Scp| zc%wwKgDlkE2|s?EU?->e?ak;jIJ)@8?|)L_FH+?IzZ>idbH!55Xw3SCne(4Y5=tYN z5RlFN_iIc*Ll>I|E|O6_GraHc>C+vF3lkVf&qv)-Baf%CDaXG(l5pf1o$7a>~FCr$PGLO0pxRIikZzGD^T+?y&p)d5L`0^=mJDF{{c*O&ROGF@3msm`B^s#v%J zLH7FO6~%k$CrocxSo3ini8e-~O8)6r&PVftE8C09@A)C2`@g$7b;VKDmBb%qr&hw) z=fSWI^HSe8cWQU23Q>7B%1#lJx#h)Qf$>j%nu}I@MD2n`=BuL0?{|u5lVL0Wf$kk! zSvft(?Fx61K6tVCK{pVVtU?v&K z!H$(6 zhH^144KrLez1LHyq?!57TyXs|`0keiEw%$kT&zRg zL2F{SjQAyjw=y4&uuFp%^5%R+Cmj-|@6=w`w!`%;W8vE1D(l*6TM4E0Hw-7ZPb|Me ze7;3h$4_0!*jw+9Zd1;3{UxI6&aRe0Z7DjbnSvs zzMW?#$8#@1hncztZ00B(LpG`A$0j?WW3-POV`U!{ z#xR2qGiL;^-+R`Ncl>Bw~+t+ zTDr=9W<~g?Pue*5tWzwQx~S$QyEw(?@#r|Nvn3YqTbgq9aawQis2FR(iep+dcz2CD z_^oLDx8vY>>;FKXgzbs!?Hflz*S?+lU_Xf>Y=-DrKYy{K`4?i46R~XaHlh&%KtP*j z9w?W$E>GG)+kCqwYRVu@WFh_0vub_`6o{wr8na92^-UpTsZGT$mD`dK_%1xSu?TBi z-~8r6)#G;s1da<{n7C%_OhMDG-@rK_M1X zFKjltW8!Q3W$VA|_dA5D`eh(H0-_bq9)5BRvAFobA$tGb$f`8*I0fCz0t_82PWoQrjcEvsExeBte{1qd z=M#jlhppSzl8w9ffrnuLq*sN5*@+VR0q=`gcCV_5okLM>X!0!082{dgrhzKlHRU;W zO78UN+=i?rrlP$dLcg^uKN;q{`5LtiE&3=0Rh`8t-j3#J6I<=q$b~CW3})Yhic;oP zIKQ&j_GH;V@_%*uxs(A>yc-$ogver+D820)8g>_6Ryq>ub3LZseXe9$7y?~j(};x4 z=RZ7nHuOPOzqz{=2Exw+<9&11N;b#cWdXPnp%%KmcK6{c8xxqxUZAjK;dH3@SeUZ? z@4P69OBq>HP*kTpgp4IcRGt6*`TYf_u?$^6gFve+(XBszP+i^B?a>yG9@IQ^$i4^9 z856!S9Z4WB?cwwUv}+owGA*9BzF0q5@90~6qJzPDCw91IJwmGVPU0W8yYhpA8$o|` z_V5tDTa3id1Jm&b(n8k`A;K?vxes27er%maMj^V)l9SJh3)kD^w5Lzg znV&^MPu$S?W1rxsj=S?Vw@NYcqVnuUGXNLES-ze<0EM2CeS2p`@n(9SEJ@y#<&TUe z+?Mc(!2czugx4SQI3dS{Szgy(A-(;(#`rdlFtXLsY^|7S2vjUk=GIsQU<*tkb@xq= z&gZ=V!ay`E)F9#N(Y8;g9<9_Mh2}UW$gb31yN@$xt?%6ncP9@G?ODXuu|ZFFYQY=p zfd;~L0rCDHnN3$P==h1e+m?3RWBN3gm8r4x2anTSrrn#z<&}eihD$yutEJ7^XxLi& z3xeKMRxG1Y^OG5IAGze^b$k*O4qX;SBDk&jWU)x0^BAUm4i6beC9C?HXk(8(hE>!RwWWi*Fkwed6`hQVw0N z?C2?nLID4Qd|UQWinwP&5(MHM8-iU>v$WG`ld?K=SmTgIq@mR;zoit}I5Q}LdDc~5 zNS{U5(h6JV$z(*zlTd*kpP`LT)uG4Z09mK}@jiCX*!(eeLS6GfJAkH}irTV2^TjO} z(PVL-3$pXJsCgNs!E$IUy>XZwBI-)%8O}>KBqoMmy`@W_1@s*9Kb@f=g+PU9E`^w+ zE8>*i@%aQL0?`i7|BIiy%J}e3vc=#v1gGoQZ{eYy!HCg3y@s^o2P4)}%_`jzAwqk< zHtve{w~kz|$gw2+_70%@fC2%)&@oHF1Zwo_Fo;w;0E}IPRLlIUSJ<#5`ToHCbGAQO zDYbAD>!;KScsu(I#QCjo2X~6^u~!Szkdgh4w;7_WKEHZSvg)miWeB#B<4y&Nef6$GPNHqeR$+UhmCF{0F+< z|0+vDWl&YDG-pPGcXw@O1tUHqaLSgNQQJ8rawmn@3F%d}J3xfqeE5E=H1gTr&F_yn zHae9##gu4=B-N0rZOsl%-sgf(hX;VZwB*+6osxgI(_Jh#jF5cEwau^oAjelc0y_no zHDrEYz3|JXuT7_>;$FsgX^#ijXaie_Frn|qbjXcDSeLf9i;g4i>Iylbt!j>TLvC%? z=U~!Tx+zWC#F4&9wT;6n#&O9zU#&K^?z|S9F_2zRdT>fx=y2!Hzv?$K&0?I?cP zmtUGg!owMU)B&q>m#?p)A1BG1d4m0Ku4?8#UHnS?H)i*_25(15XYT(p2X7h87zZ>x zzVq7L&UO;$?uAu`!K}ic-_rYhRd`T8z0Z$>1{G;hkKeu>)bw)h+fRUlw8rTot@z1* zG|9P4MR!6TQ^!<^9t^Vb?#t0zU(13gQ0xP=6hJM;h-uUvF1$ohVzZ9z6W9>7} zb`&i8dDjaYPf-ohs{_>{so!1ays|vfkZ>&u3Q8Gbd~V{decAC_0=Ky?P|zu~7#tZP zLW9hI%46? z2xl)NCNP4Czmhejf^Fdg0E7_Rh&!Vu3@l;n)jCld1*(Ut8ES#8e`F|MT_E`o2#qrG zz}#IN{F-ty%DQ9hYzv^RqU|uUB!ReZCV-;Y5OIT*?73HZZ%l)-y;U7POl`7qN$ta{ z_3y%`aapa!LX_TbnX>YtiumB4Q&lqS{6XuW|9KUgu3XI3Tv8Z;?E@~@p0Lu|6WT4J z!!4D^djeoiV{zSabzl#4ZJwnC^m2l#L)ghc+hk3QjCt3y$8gnuA1>WH$wwfDZWW;g7Esxol0+FjuXJ2X85NMG9+{|xRL8;Y=kb?r&<$H3_rgf%#P=!w-5>p;n<;#g`MAv#xYV= zI&_TCAuB2ow1cSubH_qm2jFrW1G+nLjB@_n;mp7WAo&aaTWA1{3hxxad=EK6l47wN z3+N(L%Ys_yR$((}7FY%JOvn&m*BKhhm;AAkwO-(akP9*Chr4(;g=wZ|Lwpg1I|aZM zCz|FAROdaViOoa%AXQ>Ks$2c8p!6$Xpd#h&^s|)#hh#wAQB={4Q&OJ`y)?j1&|+ys zy!HNQ1;FbI7z)i0fFL(4;0ajQWy1LJ*pbh=3H*H%AGK6PXA?$V zZ>=?xO1BWpqe~$cb|uGJ=F5)$kD@biWcvT(_-BSmniMtJ%s0NdDp%jyFq``2O73nk zO{u=f+_xc=W(cKnm1B-_6qzKGn4?VQ8@V-_#hi1GexLpV_St9e&*%MmKc0`LvlEP# zMe61~y(^&!y}PcYWZDG-`busys3rpzQE zLw|$9urVVdKyJku{Xv=5Z9hX0!=uJz!C6mMy-I49mm_CB4=N+z6bslcK#Q(dxNJiX zW4kd(#?-#dhSnt5&GWl9#lbCn^!%pGL#345~24a+&KZoh#v=_|L3nX`uEHt3L@S)^Sk zcut^a-LCR5uwq0!kQLQI*{^gZ_CLaKjv*Jjyz=8Q43<02M(vnmHJq3 zU!-ZjCyr@NEN}+s5Yao!Y%~w~Y}zcABv3YTgR?3TUH+o2awz)-ml9 z{VedJ-`vdn>&+;tBzbWn%bgmw#}H{JaYuKz?WtT_p2N)0$y!f8Fsl>xxSycbCxFW#-s!LpV+Y&@zhxd+(>fz}dcGt_qpO=j8N?^lOc)npm|qx7Cek=8B> zUgGpT4bnimQ%M-;l!m6t`fkd1ZWSuQwj;VZX1z0XnOj+S=NywQ9(6hWb-KoW@ns=* z+Vp?MicmRD+Dyb2UOI4?G0cXQG_g3}?n`pEMg}ce&<_zMh@$W>&FW}f9)Ey>V0iDJ zWEy+W3ytn=uZ~ox@uxQ(M*os9 zKNXvpqI1y2*L--!2t?W!#bh00$XVAY2e0d-FdX1gf|+Wq6f^V3g3;;Ro|iMjpEGw2 z8iS|0eR&kPt+=lQaB4B5X(9kz*?v4FUCX(s=)|K0$6~KryR!4yHcM znml=29yRW3G2FWwSMT&*4CXj`$94Oy)^3dY9RxSS4e~`EH*XdK8G7D1% zQ(&G4c=`NXjHn(Sfx}6hm^9|99qopBHQaiE-h2ACLLtNSO-?v^4)kk3eS-6#fD9b};HNN8W2ivJNQgy}I0H|z2W`d2 zWCBo)TM?R)%GO>kNi;)JAt3WYSAM=uJ9oUOG@~^F!;KaSe-t_FRVIz;ZcK!M1v58~ zBz+QaQK7Pzft%9%d5(9vDA`Fg)ht)M>Gi!8=!BYsrF9cBUV?sU;GWoBQfiKTAbrPRiWy-n5VIY1*;@0VJ{=4k4d0UF z#F#j?LHocZZV@68|Fbo0xkbs|*RL58Pg;G$w&~|vvpUKijqRNZDU|)G-VtdRWd}mk z&`cz#s=7U^d^a@WR(_pZJ?%d|U}D|}9F6zt#IA8uuq(%aI_JF%L^-L7(M~6 z81;BZ9F73ivpHU*z;L$b=LVuz!#wc1rmRAvt+Y7aE%i!J=ct`jkUZ|9*&sjpSUg3H zO3W=(s%jqslmaWt@fjM3t9N;~l?_P)l)ce?vtt41Aetr}!S>A;-!{u-P*3=^j?U&< zk!57j6&T^hHOgO2J8EhA!_;ia8BS-HOPV7*sB&XB%~t+Z1LG) zHvgfVIzAT>@!ZdvpjfDqu}rIT&pR46F+b#ST__h1aN zKu|j$)7m%TwJUm&hX0r}NSo#67;b4m`k7!$MLvoQ=H_0V#l0g^DIao&xtw`ADCy~) z756d8EYe`PI&aGZd!z=ib{JF?_@8{s1FNhs(5fz+rnzd+X?{*-(U=CN?T?gpVh(4E zk@syd8w!&Sls)+}FNe``&~qDZxs4?L20*>>I=MPU)*j58f%tS9HMh-QaMrO#0cM)o zm+P%bp8!tStf6)R8bAPVzDv*A*dM6C$?^p@>nFLeoawDwccJYNOD;4^HnJBO)34h` zLi>JD6a1te$FQR^%)oNUXwI<&fq zj7&c`i{Rq)sDUk7Gb$Q9{DxGXWDGM!(qb0R&MQKaRAx~-1mId?ya=cxiON|~sTQ9! zG4>ovFe*Z0@9sEbava-s+V=eV#bp)Z2GPMo8=Qek+h)#g%dHYxph%njH(jKc*|qfB zx5j;J?eu8X1s<~#Tfw4|f(&Phh5;&0EqaYNKpU^(AXp%RPMq)>fZgdVG=i-2*(zXe zu~GL17bd#3dG*A>q(S&;^HmUza>RU%CO}7lsW4L2G+rSP7oAVB-J~*ym0vuFO649=UX(EDC>nr&V*mk10%(Eaqr%~|#z|_fxeKu1YxvJa? zj2Ka)V{_@ZZPtMZ12Z!pJ!WeJn8Nps;wD5_H;|WX1LF$mZb1v} z{8(XuY7)JKJ1;M2J}j$RPVSZlu9eBLq%ZXKWWAS>lra=Lje1Q0arp^{SgMyj8_}u( zIbQ1f-s=}*O9CV55IEt@gx2#nYta>I|Ho_ z^lt8Uv}`7IQ*b+QC4&iAoB@-26Vxfe0p~3Ym%irs&VyzYx^>%N$;~fygCqY|6sH0T ze**I)9P7~<{MNbjZTVQ~yz-&lK7O1&)duL~dF8u4!J?b%@q*D4Re3Pdkt+RQAW&p5 zl7{)qXQ#iYF+--_w|_llVNPI~6la$uvz_n?zy(E>&DiKA&qeujY>tci)yDk)lqXFG z6kL#dxb;ljo40E_6m6AKn%3oOu3m}fCIZRy$+Za0P_I@=xH)1=W5QdV4nVf>RwhIX zq(>fW3S3&H%de=@OMP{mdM@0X*^}L6eKEczRSWrk_kW@g_S(g7!Kp4v`*^bH;KC+koag*X#u0SfAu>?R=W@+#Gj z&5;}(=QiN}i`CCD+YdFqmiCaICoY%DGU*+1msuXz!Lls`jD`a2L6;${Ux?sQBjxw4 z|Hrbg#asL5!O2Z5<M{J7eH3lD)y1S=U^YT`HrtE|DX<4jCfxIzZ$2hP}xZ&8^ zv>2TVD$(UhI0An$jVaPxzsfM{(o3q@=i9-IQ`sPXeXpSwci1S|dUY9;`&hl-%a-<) ztrDy`QU=T}dLS@-I~v^7IDmbpBcn2M4oRkg%>kR4^QOY49|hM{_EI+&u`9(_$}L2U z6?&N$PaPF4L|XyYqWZPgP!QTZ17=nsZHO5Ogp%YHT0RXP#jb&-^`VStWKp9PaJJy# z@!0Kg@X_wLXodk~n=1;?Z!T;&ZWF>@r!H-5od&ehVQEa1-rzt=l-L_Ueu4x- z*o&r9S5WVG-I4O_566o)M>SUdBpB=;t>0I4o{)=e!KX-_YT~n^_!efqRu9cVMMXko z-opl8gFaM34RCb7)@NPWQx4un7u2Dt$+lK;Hioq*2ujz8lPO}jM~?^Mgk`* zF0;_0MfGP}hY@?ifL`$G`%Iu$Xrp;Tc`@@&D%Ec-Fb{xp`r#%ufDs+T?@sQadJV=o zbFqBzVW(%?SzkV)A7yF<9&!TZctgODC`V1^%ooCLvK&)P=(RS%@;`iH^H2Z_Gb6FH zUS<9SSUwshYb^}~8&$QnPjk>#L0|rJ%3#~_?4#iFL89bByrL&DwVNmW0%+wvRz;}B z3g*t|^KPMoP@A+2%QKJ$idt3{7^YZ0*Y0Oo6AaY zF6S`Z;Avxuoz*V}09oYb{3!eUjEJL+HV?eX{dg6BZ{i21=ZvD$n>}@4$_1r-=dk(D zy^lW1b`|VLI7kLbg5@qbHL8344y@yYd{cnciB0tFvE)wyZw8GcBu8U5e$d1^l9$JB zH13VmZD-tkofEBY4Z`eR#z8ty<{w?+A94NE9-gUsYNu;78Rjo6wX=Hu)_Xt=nlqYkn|3Lj54Y@x zhl-da^GX(X{MInr!W6 zQi_k>#`#!8{^X6WD?StCL3D;{kzH$aCXJHi*T2a{X>MOmI3M5=g22K!Q$`$uuf+{# za4d}EIJXF>!SwkvwFf;H&v--iTk6o z3+4?2UVbhRywLf(^vd3be5H+r9K)Dhc8si+WAVDj8BCRh)M*EH*w0U@(g|(=k{Ig1 zy7^+SzE>Mk_SBZvvx80IJyQ3e6K+h^=%MXnTjvAog70JO5u+4r>4;B%@q{KcZabm- zKleMCFYlI*$KXy|JUj?~RN0Ozd0jqQR~$|)<&Lkg=vFjqRb|-@u?=Ei+3u6N%n59v)#6rjU&3{?(fk41=!q~LFk@D=b zGKrgLUmgOB+={YR&Uj)R*IvD~2=h+{#{9Bm={;|F(cDobZt5bLrQDp@Q^UCP_ut`S z1ruZ@_`3-#d7dEX`1^iLocNyRI-yv#0rrKYZ$v0J`PCV*%Ikw&md)_~>8y>FAM}Rm zZu;C?(~_(tabxLtel!zDS%Kxf(hi>R zH`=Y&r3+j8?~K~+cTyKM9c1l6_fE1)M&ptH3W7?I7{$LYC8+qbeg^Z3V7H~*UEQy> zR6UfGa^|T7q70mL&UuYHLpf^8>j~CdI78`gVeu3LXl3iOw{`8v$a9_Bi{2$&!y?k8 z40zIfI8Z={&u`ZehhE?S=SP&F#tAmK0P+Yh1Vq?X$_f7-@=Hr z1LxZQbxX=Sbn$3l>Xw1vtW^u*TgTr?C-#(ZiYB?s>Lb;!^lF;I74Y~~+`Wy&GIzJd zjy=!sca6Ssd9805pntDd!467VtB-WGn*0=gDE)(KZMXZaiW$ZD{h#}Hpw2gZF#3M5 z_VJhIJ4ESxzO*6Z_khxRrYA90fjRP8bJVEx2eQm9_c>k^Z}$CDKw8r@wVb$;q(;%~lf`wdVU z|Cz@N<{4}EOG$W40^08Vw(|uS^jZS$?34Ai(()$`2JHjp4MC$jbbG}PaAWB&Q|qw#JR^2CDNY7TXD>eEq^i_fS*Ey1qM zKISva3ww^SMDa&SNl{~jrS%K7H;-(`D?Puir6;V|w?-@w?O039Y!%!%ZELOV=c2G{ z`{s&vxO$83wM#pO_U8f1+D|sEWd8acWCYCt`GkPu=2QS9txQC35?>oZPkI&!3j-LTi2X*K$+IXz;!DK3zj$_ zId!pC55odvAYG%khijb8NL+xo4HaChbgwPn@4@3QzpD3_OL|$S5;r^w>kedv&K3Bb zKWZvNSd&fi1{i}-nOUIYQp6{1A<&UHWsjJr9zGqzB zseH~7wicye?9c6a_afw<6_4_@Yk$8>3h%MnjWQordK0(W8Zy@B=YxE0_NB_v8?@th8?Rm{ja>qJ$VH~?RWP4uO8eKKNA8!PuCF01Vi7e6+{MR#Hrw2ZT zGt~R|8|Uw$6bdR(?dN{UL+f)NF9@#QZaUQaNT;(FCE;u6?B)IQQoO~wZ!?-^4uoAe z`Pkv39MBQbL+0Q+>VEz!b|xh?uc_0lA6mt}bEm?J6_%_ws9j~QEd+t*(&o0MhbF&r z$I(2I_8xMlacYhk7913T!K`AM*@tJoE+JO&(wl)RFlY%F+6xGE*N)b8&1UfOScT-v zKvebdNo7Zk=0I-mO8H`!S5>O_34tdMWxM9|*{A<~>&?G{Q}&7b=$?SgL}))fI^Lcx zW;!9nnBrghzDHklxT&4W@7gvwiOKkElbIBl>6dT#hw(*~5v*KUmSJao%|o z?59vj4Hh>|g&0{Hy_1o>{fh3Qgx9*cs7hLz2TeW~W?yI?Q2ZW!rvY?XxLOCSwc!f0#dGwkIob2kb07NLhlu*~hu>C6!yf!>)s1Xuak|iTP;CbHCZ{0| zaG{M|{;ZlrQ#2pnCbyN%U)8cm{s}0>wmQjpKO7nV+r&+4LIlc9pz$!XW+F|U2o4%N)d9mn>Za)F4D1L5v z(LuknUEGiAi#zSnrZ#eaNTdBX0MdVN|J{AvGBabE7Q67O9a-vpoV;qOP9-JVq*KFR z5|^3NtL7+JjsMcEm5(jgYaMo)*nA9ej@nk%F%Ll2n%pkZy8ig6Vx?Vp-U6$Vp9lPP-Ci5b$+e|)G?GS(?p zbHHGT3oSfFxbAA**K_#h@g}A5tc6FcJI%=dz8v_Z#Ptjc*+ZN(ab$#|BXc{-RIXiB zf=arC6cu1h*fHt*|dIP)trk*?2FAai{F<#)#! z?T2;38FpXdT`a`O(S0>Osd08nKfOCFCu(i*%?d$32Z}$n)EGs~8lJDZXQ}+D(c_`T zp$A%3CF=~8z5THpedZFM?VGFg(2oWc2(4WPi?oa%2hP*|Zhjq9y?%+&j+7KoNrj<* zr%NzXyO0(zx~`3vJD`V=$G<|c0wkszxf2eQ$Vr{4R<&GN&~&%_xa^qfiH z0J>%0LH(*Zr4pqcx=^xukP0bJTT>EX+ITL;6yA9bsHx5_%C zrROC>b-W|fA#_sMim$Pt2g6IP1!QE#KyAb0Rla{|N=qf>)V|i)VO&YdOKhqd=Ehe4 zY8w}QIo$5cPUvBYfxp#nV7!~@)&~HdyLEPALNV_xL2zn!^o5(}$0SryhFf}9^nWdO zLhc;I>+&StdEk5M_)^#E6U_f+^%WWA+D15zqE9ijCwVTht!ZH2e<;@0=9Qm(vNb8hV@%kl`RUg^$QIWRka)g;F z^3<(XImO2qm*%$`&?|N|m(&aju3wFDr)8F}npY+r8#~wj(13DL08<{ikU7W-UG=Hy zPvrz-K-nf&;n(ApLwcgHzS&UnAT+VK4%Ue_%NIO7(d=qKW~)Pp9@x!mTK59PL$1K+t+U^d1!RL zc{F4&YnVHEzT)-FwIuR=*-rkHDR&b8y!0*gV-T-nF+mZHX-8n@sG)stxA(TX$_;l` zw`BMLkT>1Rh7l4W*^7HaD*Y$#bzw|0ro5MMjFIxFdl^s(TfVdM^8-nznE^~2T<-?_ zKQ`*i1N#^vf)$`52UcSi2JExm^{^OY9L z5R@7bx&e9m^hLDe`PYfTF6NU?Y4Ot>#f_&Eg>OzHqz$Uw-mn@1-qrN#4G@#F?>U`A zrsd9;dk4Kv1>mMQquAUj?X2Ds1*-LKoeqUJsr-HrTbwWL8L*zNi{AXM62PV4jU&&! zuiAfpasId{Q+bpfZT0rknfe=&!=FQCHZnvS(5L@eN{s|&v`+ATVtMLYPlHmvQl1P* z^FW#|x8t3q=Z|Z)N8;7NYLhtocp=0eh;<)0E=V-&6ajU?b(flPV@?py7X@2!m-zb)a>X`X!3TWl{Cxe zld3-xTj(}4dn5pID9|b|di43LVEXV*d2vefY)*p0&qMuYCnv@NRI~GIZM(8jUp_1D zcn31%oF*U~k@W~9R5;>0`)GTM$@Z!8=2O6L(>dT4J>ewJf;ZRPxC;XsV-laQy7R7Urd+PIEZ@{zu`FC~KK_l&D{t>(o$;`( z^M5=0w{mDWM!9R#=&o@4d0y**JNLb2ReC-Br;8`OUb-;`WbG0rO}O~DupKgaU>zz1 zHb{XKG9O4(cFB%F>5Y}8yuit+eJ0gc26s8Od<)G;;xpdXt>9T5{fh&uM~VE!Hqs%+4!;?9wx_$&V=#Q$%ws@tD+s!yTwUza_cf0As@ zl4rg5EZ(wyZ4~}hQC2PYhxl8+K@LsQpWD`vRyS^Vx+M40Qd3Hi_~8@eEFX*@aVZLw zw)L*+#Oyry*tvV{LkZ^t`m|SBw(F+rzY5neH8-F^q8$->eTnpt`BURHqWD$UZ~s^x zg+qevRj)Qk%6qF^u&NOMn*7(Iwco*_@c&ZWWi+__3%tcAdG`m~EU(&suN!1UrwQ3s z8-}jYQ9JY3xeM^;RgIHrAM58~SHB}kitB!-Sxw*{PyYAs!ViVTM;4DxKDmFh4>6%( z?e0)=kNWnsZ*E9%Me}0tsqxVmV`ENBh}W)|XJN$`Gcxtd45)G3pIlnTLLZgBv|RD_ zWI+h|{cWXp6}8-+50q~o4)LGz5{$9*t0DQ@auHb1eA++KuS*Y>S@>9z0v=od4{sGznzqzpSl9tbWd`vzxV$@Zegk16GTn%bb`3cN?L?YEK-I9L#>18HIry0i+9d`xZ+rkYyD-IG9_^PxLm7Wh$owP3%0Dr^m6qY5W-p4bTFf z?FWWpcHR~DFWHY}kw7-u=UK4v#!89Zbu(DxF5otN5(XM5+(GMePF)SYnvdCf{-HR zv8s5Kj#Z_F8{3$KwknIIG$b^dUO1@TWoydmwF3$uOrq zo8dj?YZ61zP}bLr{+91x{u$GHYc|O3&ARYMejAAu2?}(AL1KCKWBQ(8eAw%+^@lOg zJ67K0NB9Y8z;~=P`@?(A&T&H--YW?j)?_H~3uyTMK|y>HO?M0CTFw(+;2uy(imhf5 zrS0w7Lpp^Qu;`r7&~EXYAs^@U%(zX^a%=%oO!l+ktu%bM@!j>F-xDu6JCm01q2UTicGukypUzo&2n!3^y9o1p4~16cO?e$dtT~ z!3Kxf#^&)8ogwW^lt#F}Nv4obkcJ1dZHAZ3)erMvg9G`^K>u_Ktg^(QHa1pN4B06I zp>AWi@{@iw7S1}RmW$CT7;*5;wgff;X5>Ni#i0(I6i++tk^8v)&mrB0cYa%X=iJ%i zO9Rg#E;iZ0(8W@ok-3fGhGXaKB{Ui|E?eEOEBPOi>YnS3Z!3d5gN@*IKE92G2T(13JM@~(%)nyxE2$z<`s*F*DF z3pOZF;q*|T%x&aCD|kbRWjaRg2LwW#9tgypGYbkDBMMaqQp7BbPR>m8ss1QXgv3G^ zN3%u-zdct06$Y4A!saJ6tffL=td5|r);5`o3p0cC(=4CgAN>h2jM14n=nsq z&7`&fx-)9XsNKfVZBW#$XYEjxw6yAlzG=Rr*HorzZrUCCw4ImF2cofi4*p#O285i> zkrvDMe%PPo(Z`W*W)FL@RCAuN5KvK~-V!nkj&(7Zn~KmJiV!>x;es=9_9Q{-j$J5d+hh_e=KlbhuK$&2VXjG1ZsKpu&rZ(bB7eLS~;y4ygAnu1v1Y!zqe$Uh&o9O3r<^OmGxnB!Xk zJ_sO+;R{ayaLK^rBH2RVSeY{G))*~++NyuL<~2sh<@0S8TLp!->ZyJ7A|t1=6sQno zxI~bn3_mma;K;gtJm2CsP(Mb|$F^#jzH!4SwnhLeg~QpO_4TMEP_U>J8OY7sWVD_l zuQ?Hce)8boQTH}wt`!)krZgL)>2Gf~fzkq_%9j^I1EDoH#8se_Nt?0#w0`~^s2YRcyYzaVngMpcVGGO_K>N743pfVf$h?hkI~?Jl@6qT>4T|(8jPai5h;92 za*>42sU@P0r%*gh`p*1|i~&||+9tUANS;?b3CE}+?HY9l@?%0o_zdm6jE7{_Fk4lg zf!(Z|3guGmpn7j@4IouR0V~hX93@P*;txpYA)o;534hKCa(I6Q7+^zbKni?1sk}z3 zfA!#ci{bgB@-HE5mx4$q^5XJlBY4`KlrDR9Ff26jVyA~1GRKcf?d_b3z~SNPrS(qb zKJv=u;R}R4twGRVSOhuQq?{-WQnvJobk=<$Jc0jc(;BQ?5@ zUfYwV0{D`dgUj^m8EZM_-b;9S#uzRuV~odzp3>$lH|Jl`sb zmvJbiSh`rj4YDGgfI8kJMm;Bl#cwropepQ)M`n5SI%MrLzHV!4TX5sHEczbLBx1_JJbnHGfC`WpC^ zw{dhO^=-#R4g4`uw;u-~Pn9NBveBmqyQ@_80bXq`xkXwA-Iy-RcHX3e7O7gj63asN zUXqgcSo337{PAF`B9Bgfda7@%l_fDok1 z$0X-N`sdh3$R(j$vQ;Lue!{_`%aRK|&+LlL?3cmKJ&+7jRj-7C|5vB{H$}Vr3UwM@ zy0TxpNs;|mSlEwzzt}|zY;wI@!ZUurE~r({O8&z)Ujj-JpN)B}hNOgUL4Lf@td_U| zGlq7{l9F9|AsPW{x{9;F$|~Q+i=qhZ=z_yO1Gr?Xjam9;EWN^wAj9g2dM8WJTRwK;uZupIF`-FgyrvH;HoKVu zvUPq6Dsuz*2q-cUD6jH5Qaf8UK}t=e#tz$Lf#P z`3rEG^*JB#8Y97Sdb2H$#BRPM|I!?OhLqt#>EE7)!SlUk6?p>`8RcOyYN*GDn=>{e z5e)QYH&97|X$4S#z)ayW6j`gX!UfSO%-_Bc{^(q&td(oJn>>;9^Ny8uT77gaPLI~0 zfyD(*fUGcJhuFIq<3!r5W6?dG+5b65dx%4YwuT5-=<2Gd zP$G%mLqYmrP`VJd1EFyJ!9JgU#q|gSa4=cqm;Csq;@GNumVTTnN(#%yvhLVg0V!|C zcC5$uL}0)pt7(U$oJFb(mAJBTfY4!P28S@A(wY`+gDLr2wT-~ zu~y{N?Dm^d84UR79*7JS?o66l;;MMKTT_iXW5x4O|7} zyD&`A6qBHEPeoY>c&K=(R9J(rtchP9X?@Z_lIZBTLp^0(Fd?eMuO5a)(ZF#jHV;aZ z3}M^%sn+OS^6?3og*3HoX%ePme4^_6d$wl0Rdg!kA&TCx&w*4>o_Q09TBHHJ zoyY7lM4#Svik(DKSEoV~gMe|VR$C0To0Mp$dmI|)@`V5N<~eKsHYD1+cbw`L++`qq zF{aYA%qE*orV|CGoSR&E*>`m!A49vS_og#L@Xtnp zu#6Rz=q)Cdfe#O`SwWIyBdZi56w)a{9@r^AnjYUGRwXRvN?+nNPo`tXZ{Q7Q0nD{F zNg+u;@fs`g{%tB_0RZ<{-a}Zqp@*^Ee$|_U@ghbZOg3cwlVq3%X|4ebWUQx0Q8&%a&+P;S~m@0b!#ku8|h<0zoP+HR3d7;gh-GW{* zP}BO~S6dQRVeSy&!D5W*W~0sf4UajA$_^8S@jc_zq9<_Pmc?lH=6Md)e1q$f8D=M-?759l-!H(L-`m z8dryonr?utFSue)@g~^f%0ysM90J?`?ent;L9k)UAF~Sf9Is@eDfz{4MUw{tV*er-jLIFm+VwTBW2Z@dt6R<*Nutt;TtsBC(Fm1A5 zR{j*Y;Y4}WcGzOT5Hh8);w)wsGQk_|p(0TXk>pK&*1V+tXa@xn)8v=>EyMOyy$P#O z#Rn_ywc!(`-0QC62==M#5#U@!6}U#LbT<8=t|?burW`=7U}ht5B~Xc}{ZLL_p7?Nl zd-L%S;g3woy`A1qhNo=56++%Y*0_m8KGh?(*ACJZqWr{_An_LqA;OVukupB`5n%xo zndKH5byylOXi|*>qT;mX`vDJh0!mYAgD3+Id`c`lWwUyOjT^OsT*V?)||h)1Ou zA@?b7_s-S7)in=avX6~Ufps+CK-yM*xBRxpTTM#L;5})hEluVg-N=NIXW8Gk|6&5& z(ED0Wy1YPwa_qoUa9S~@jNfv~)0hFzaeF8y4o!+viAWEVUZA-)!5Gj>8x(1s>hvDd zL>Pt23FV^=A#tEcJ$yw7?pNN5Mb{*I5&=UyXr=BTc98X@{YQ@Mm&L`XA}}mNrUnYq z{tULfdD0C=fnNaVW;69^P=^^t$ecQ@TRHgVgMm=Uw*@~W>yCFikZtp|3&Sq7R8)G5 zipMOsm`Q^H%Qh5qd4*kLd>oXgy3J~UEQ%I!16^Fo&`QWk@k=%pIGV6C;!Uy*>{kS_ ztj$I+%xHF4X_D*1u9!SCl>nRMC*B!uYvWQO)B|L}sx5*mS|CUgjG?I%TuEaSE!t9C z2L>BR4`3nT=_5X1F$Sx%FL^Q%xU-t#5d(msEG7^*cEDxl;jlODYH*YEyRn0fr-r~D z7YITFuTL8erE)6sZ=#Qycguhx-SUuuIyG53XR&aQZ67;I=YSbZGYI6FccdMoD?$Uy z&EnQVmD3+A?v0Ve?`63OOb0M3V>*hf%XzR0r4W=D_ceGo@^gbGkVM|rkUzcB6S+jw zg`Mi(c1oNz@zxuPUe1$f_RD~(=1p6ei;J`9QA@%+-NOxfT{sZ*9WYs)kB$}2Y5?l6 z90{c=#v2Lb-d1wUiJx|ul`;SP*cj}t)vE0;fYq~Px+0fzY=|q}*upA2p|&THp+-e7 z^*qMwF}-E!ig^;Buh(YS2Jrw&xl$Gpo+qx;sySL}+Mbhj7 z4J#S5UyYjd9v+O211tu&U84P{VUCd`N}jh{9S&n0yXJUtm4#(-aE)5dDxH!5Bn4(2 zN*bZ;*Ul1ab8-tQw0#zjN6*YiQ9{A`W=Slp6&rob|i<&3O+38te zK_UW7HCuU~Dy?ezJGlm1$2NYQV#K_VT09doWzdraKrY}U4XAsqFgQzCS~M5|7|GsYEf(r8 zMnR?aaj42S`SpQU#DOsBn_VFY6hT>-MKcTIPWPnsLr%PYUEWg~n6;d@%u=ZuOzqMe zvVZhFYk>;pYIDf-ND>2WML7@%BEpO@VT-h{t*SP48$V8f{)M&A3In4Q^5d3+BJ*U^ zemf`)s{;4gKlm*@Yw}$x`|a0$I~ell+ywrBLgK=o(~R6nuwTO4Has*m(XlxOqaMqT zJ-hkRNyy6uA^A9fI-Yx{LJ^!Wj>Uc7{^qn5CjHb{>d_%pmFsW%H^_FC=hrcUzQJ{; zGS(@!qN^>RurK`MwSYUbF;UD&v4@vn{fr@LcaIPF_9BT6N<;|QfMd;go4z-uIE-I~A?hU*= z`H=V5xgZ)Wbj;B9@jwL zg$ywygmMmzSef%_jQjVwzrXL}`~Uv1`FyVT`?{{z>-mDG(3Z|mrZXNeegb0!$kQXB zX#wL5z6iqLpDwKi*vf|FW(OzQx_AOcQ-Ue4W9ruBs=-DQJ;3`(%=VLbfP()hNOrj* zn-`Md5<9S7;%Q1!c5llLo;TZ5Ni4cQ$Xf|e=Zq#7ng4|_W~k}C@j!p@&>o=Gm=a#m z&2=bD_P}z9q?{?*#LQ)6Ml>(uHt)$0wb|$=(*eDfpCN(!vc3l*rreIwh}Q8 z$IStwnj8T?n)>d<=Pck;7E$H`PHM*}8gaIbmEv$^LnL`qXs}&pL5SkxplVC(0_fOJmvp?N*ao{N(>$A^P_rwI$ zECA^)fpSuDI=S8BcCr2j%(X zs9rqK0(ce!4S0+$XJn=HK2(g+Sz!UG<}Bl?@Y$N!)zqe0c?#{WY2YpIH$1?g1sHb+ zgtv_twvYlBAin$6w|Q5=nIjo9VQUu?^R`1_Gjb}ezi%q~;pwn|(KLrqK1-Qh+FA`d{uzG}^*MT8a zr}y8NE<5>quKW=@YkT>T8bagbq>86>vn!EO4v)LVr!jWSY!N14%qT zlu$iTkXFDS;Fr|4|Mehd>g91E1Z+lRb8Kv*M6vcoi19c99AjGE|Mpd4Lz==wwgw8l z8qxUolF5UMC+@t6n}N@<+Z+U6ueN3g4P?hDjpl>-Yx1)Ewc~nm?5hsROq{u!_~^WU z!Na2ZskNaNjNo-bSca$n&UKhlv}nF zUbE7g-C<%R4V5p8s2m$@P}zM~$vPe~{!5)5Uiagd+}C)yyo__Vvogc7HTeiZZ*8>R zT#^$oIVVSS5Ucv&ou%+(I+G*5?bH~b!^(B>O51n%2zO*{~{te4ts~Vf5OKt=%>}C{ixDf?=dgLN7`tnWM zR+@f&e+ZF|0(bXv4`7-93o3uUf>>HMc||CGDquIcB)k^!EEy_VpbI?MJ!<`DzxT$f zBe18J6!^k;)xKtsDj6q2Wc*FdmAQz__K2|EV{1}L2Oj7i5~D-lU7y7E8i6u+K<;1A zz!%Cg$0RBvVtN;WIks~C(h&QQ?)-RU^|CK}iSha1g{F_iO|c^Xr_NrEYlt63$rDZ8 z@h(FxOPr&^(aGQ9u%vh@RNIU z&2C956K6v~avi9t&f_hQ5Cr=X~%9mx6+BAUm;JJ(eoWdqq-2Z3f|jsxJSONNV1> zY~gp9KU^wK-iK-6xNOqwBRPEE_WDc7QX6Y!4o-cz8Oe|ZYPe&q+o|s{$(^x76b8kT z-!hGtv->5v+iGY4o)K(|QhlM>?i4yw`(0|nnjq>I)d%wYG*G~VN4R_K z3lZ_T9-o#EMKWmu)%S@<=&=fuvnXcXwkRg&Ua8Wv>$v(pkIcyBH;NoXX$aQxg^50H zUajn7$9VD@PmCMM4{L$H8Y!9E7RY&-wa~cc@QRX;A%L(W^j_q==Cz8^$1jLo;C7lK zE_NY+GgNzN+B5;1_!a7PJ~fdps-HmL)4V$WjiE0s*-YQz2jVXW*H|um)~LaMOyx@y zRe(^ryn*@1jMPw}_`Oj}*i>q+Svzu_b?xx|tFO*n^b@>rUu$+{8%Lu__Ps40mabEr zai5dliOlG^^W(27Czbb5`qDt-gBpCO{8Bh0r{2^kwOO{(dF_mLOlfy1##-p_U<7|a zt+;gAkF&Ec%3m_e(U^=u*LS5tDdAI3ur@dpeTG!z=bYH4L&$_w*G;R)IE18G%)@;?>haadZ4|c3cop3;4=B=nLg#k%9iYFr}Gc5H)VgR>(Hs20?E*RRM_*# z@U$=U<}z8MH4Ey9{V$iEp|Z3uWc&%*jZg+V{*tWqyDl%6DCTQkS$GoPdc5ijqg&$0 zBoKpE(ErHi@)hC@lQv zFnh_6|7+3<&kXSlGtdl9ky-0=_nx;p_PF#&3QY++v`ho^b=6_|u}_th19BziRyJRc zr7koS!nN?RLqHf8=sRy zo}t&yDU&Z6%J@qhY6vg}9hfc7?DpzxMzBU{4ZRt68XX!&Kr=xbuYi@{c~V`kG@$Fg z{z@p0IS0PI)Um!*mi6q3LBd+rax2o!S@<1-V~=MXuZ&($33_UwGCZM^3T)w$bWtWV z(YXTt`W`7qYxJH~d6&KU(VBUH6ulFr*X2oGvwnUB`@Q4OIqy-i$m}idAFku+lOE?e zv9kHT<^u!wm1+l%IoZVDXqJr+=*}{5!DF-}_~-c7h4zVsid=d$@Og2tBTW=FR;%OntI=tA(WdPPGQG zMIFZj_$GLv9x6i}$M5%O3!E*oIlkK zMXqEh#w#H=UrWh(+*ge=pF63!AGVg)@+t(}{`Y&wN1Kd?)fGDWlGeFRuy;31ZOVO5KHLzc z0aBL7MYp*=o%MQX0#Ws+;>qKE$2K;mDV;j~&@OJ_D`W>^aX0Dj!r5M}Hnw_)dV>$< zXWn#w!_GIy>xsA&T(=)cwn;eeN*s02lc=+9lw1%oF}?xq1cn)`)2Dyj3(DoG`f{$; zAh+&pukqKJP@fp5&WYT*1qiLbpgQM9^^DK-lOSeAna9t){02?)ZiA|{*IQA0hJn~PcRtbF|nQ6qM*`Sjy4_C+3{9!otY;HAiTVA0=NWZqBg zmaM6Taz4U>cdQ}k(yP}mxEs_QJAdmWz`gJPAauQxS4(udb`m117WwOU=y&ff8n|?& zc?N%#B9Z#t)IoAsw(I>o6z(T<8_gbKWW!gG_G0G892#5NMBH*!Lof!W*$IYZGqh*?!Kw zldl!jR%f=_^$6>46bBC7O>6e~Ko$il5jB@M!R6PC&$UD+fCQ9Mnyk#34d;aVeV^`( z$7E`2q8lU8lwr`XX9L<$*pM_j$s z{Gl1DpWu$xCOIYiMI5nGkcLTuKLI-|wVw|hus6j{9Kzk{1tv~;!~oU=_KLC5_afjwh|<6Y6@TwC6pbj{t%;1E;K~e($gE-u-@Gh$PZ6dBPgs|C z!Yv`^n<<`l5?>E|IB|Pf0tO?&aXSuI_$qxyhaDLRc_w$Gs53y(5Fy_xTQ=eMdS2y< zXuK?8{~ylyyCNYQM)h5#N3RSlpb(V7s=z(cZs4i?_sXtq5g#KnWG;Kvo^aUlg7|22 zS;&{;8)`28{qFUiF2l}V(gqLMNyGQv#aRwe8dK8;YHO=Q@LzmYN04;DNo_$O2v`48 z6@hEGe(}U2QpC>>1)YCVgO5uij426xkmw+8em-|St)MxrKhdG_2W)c8pOiG0HHvR@g+I4Q7Ep~ zsLkub>ya+|wqPM^f9k=4U1r7R>k|tdFAF>m*2`3w$}y`iJU(^5T|kG7-wrHva4;Ym z?ThzXYO`$~Wy;sjxbsAl(RUo}ajSJe8UubC2twD2$%0NBZvDz!oMHl67)IlXZuM^f z9bx@Ucg^_R@);g^#~|!t90NzblO5+VaS^qDg{u$0Vd#?)zy6KDh>fyE_uYgN}5?#uf8`&xG?z@Qf8%Rby|b8b&r8hR}*G zXm_n{`-I`?G_o!~gvVsuPwGbov30OP&AZt1%_>7)o;RSDFL-?c3z#_*;u@~s|MJfZ zyl`pw2Rykk6g0OY`S*HM{k9}?g?mT%e52DrGM4ezLR9PemxJi(+Quhmiz)g+%oG93 z03d4pS2zlPv-mC{?&~v*JrAgZA#x=I z-oCWXGy9Sa&xg%E+`B}!$-uH`&H?l`WIfOCA@3?XrC=8Ziu)-?HR6!!HqEMC=a~}^ zzy;VqFD8^|s9%ZAMXw~id^sNd>$-j%r^Q)a!w3cJv*DSAfotlQ zq?G~p_AkvQ=DE(FrnLryP>|C+U;ynXu8nqCAMNdJWQH|cWEx1WCeJaBKnJGv2b zWxM=a6y(rPzJBqK5u`x$YE*`w)3(i+Re;4pJH!W4Xxs`v6JaW=w`0EwF^Zoe3+Nps zo+QN8`C zy`Ak&K)mkd{dopF2c(ggGG`E(Vdah(CIh?i(lYJr`;at3bO%@UrIj){V13G(m#0=Z zA31NeO5H;;I1&JX%1SokkGvoh)f>4E`T);R_lqi&mSr7@mq`E?ayZEzBo{Dqj26Vc zDkA{ATeii6(T3AqjoP*&m1|D2f($?_sFUeOQUS%=&|xAwNuH0_B&SWZ*BOQ8v3{Kh z^e%wHzA`m8`kq%*Lna7xUyZOYDb>{>oH_)ql{}Lm7DFRq9@}^|m9J3+CxwAPzqQxm z(eJBZFajZnTklp^9^hr1VwtxE-ZSDz$ma8$eIJgF=1Y~FCA^LMzdYvW`XgO{Tj{FrpCe0{3{bfKF z^%VhZSoA}{qFA^OG9SsHwSgtb9L;|zd=S~=# z1rTNb;0I__Kom7L_V!Z5p@Uy^1d;ax+nf~H`U!x!{Omp1#CgKze^ZuwrcK8~5Tvjm zx$lNIpPuTR`LFoYN%w?I0hz&1&EmDR3Io=>)}W=Iy_=c-TWz4zA_m={$<{@F1?KSt zYvcx_NZ;14AX^NeP}iswcmvdeb%3#IBEg+*hdBFPl*=9b4Yihn%5ShK=6Gp7WwhpV z>sEct{Q5d{ohtm9-vPAI6EY|9j34}JN^EG9Hj(y*rxTmUkrcF0w~~$00|lfNoUnud zGdN0(YH^q9Q#yYgGkOu-W)MCX9S@yZ$-8FlCuwD|Mlk}uw;(t)_l802*Yk6Cz1=Zh z(unP-Li4uGBee!hOkRdO@>Fz1xvCx$Z8Zy60OILT1j*l0Y}*RNz(C&Io-$}GO(LfN-;Twoo^WuK^O{ICMATd`$2hbwpMs*t z2{tV+m0+;-y@Mbpr%vcZuiXNYeUTLY@E_zN-rQmHDH8lQ+v~p*nXzSRh`EsmKsP~& zA|D*2!C)Ggi!3THEw`LBuW=N z^*`q34ok>cY6Z=#%L1WomumeJCx@sDXv}-i)K$@CfBjAP9?m9fkaQ$xJest=De*h- zBnP4&{~fJ4DbX*SW+g1ag!$_S{vt|$4?ZMl;jQSN*OG07@Pq5_e_hlZO(|cFj_X<( z7xALGzUMt~2!&D%gS+M>NPt!+66AyB^5T%OBp6O9nhsrxwgGQd*7EzCE$vINnNS2E zZ0$7%Q4}RN+%h3`z(rR#yXM=P?u{`C4aW|dOhp~R=FI|sKL$DKvB5t02NCK7=JOV* zV@LyLLO#&~@oE#@06&%fwc^DgCb@f|Cm#oFW6}+kOOSD>76%!p_X(kp>RGl?L zAxE!3w_k@eLp6k4wvn|g$Bg3 z{!s}`Y$DF_Oj#Wmnrv=9dl)i`oQSoDKP*R zQ|cdz*b$3VJ&y2Ua!=|2X`tr8N;A`18bWN=Wp}UyN#qd5jxoJt&#P_%fqFPW{{z%#c34!Z(W&U{K!766`a<~y!<7LK#IaXMX#kSdxgSrIjo)-c(&ciJb&;d=MJ9wi zm_O6XQ#F9#2%~1=p&dO@J<2>d111v3Kr_~hW@8hd$QB$S5o|r#V7T&pj#fSmGsujW zb~Fgux93rfmGQA*^wXGkR0S4RDE9-4Q!jEjt^$1oFPeFjWftTWKm{8tF#!2c-L-$NsBOBIkP8TF-Bm@3m~1|u$?d^HVyP(7ku30XR_H?3mn$m z7IX7pU->Ng{UJkPy4OHOFHkN8p9$APx(yk9QRa_>rirwmV6j$d$rI+;Dm?LB%e{ zDGAhO1{L1%z2t!A>aZu^hGUYyI~X0mF5P^J)jWl(1|4{>yQP77Rsh86z`tw}JPG0h z5+78P7_)zC$;_dFGvqN-K6Q*oR3XTbK3R`FZB;b6U(HX1fj&K(kD&a>rZb_fH?9N& zC;l0Bvor577!L(X5sy^IXVrght}_Uc@StBB5+VVtAF=7ZFhW$eEmP21wn3~M+eH-Y zaLe2_m47f3EK$eVe78b=JlS6$4>G0EkaXzR3v1~e240`^fChob1m6oB)tfKz%>i-X z#oU1PqHN}5EuePSWHm1s%0{&iVFKNY*wd@)Uv+0&ijSKy$!`Ibq5vl-Hg5_12d$DV zLW`Px4hm42B7tDI+{yjY^7l)@8OCbaVlVVBqbp28p-`B6#0Aqq{CMEPWstGnzHweN z$FLVSmXzek5i_deVKn)+r0581iRb1vyal0}+b7S_8EZSX71FN5OYFAf)s=-X7Wk0B*f&O7%v50IAX3mYOR^Ll{B7W0>v>K+!g!QxDLh8KqX zS74Iv=!YWW7)qZa^zEb6`=Mo806U8xg!*JnSVE*mPjVr5qdOQAo#31X9uD3v?@4W! zcDpu1X#mQ$?y$rU%+Tfj+~(CH@XwL(M8Wmu^_Ky|fo^ja>HIZud_=vVMH7fyOSTTv zpFF%fIq*rD_X4Y8r9Bi118!d%*7j?;IU)0cn*}x`KTC+!ep4ZGCZ0YSyWUI%r)daw zf@f{a@}a8dcm~LK`~{?~WFb&_;XA5gZZtGj6=W$8g;AN{fr6IJ*y{zomWFd+^vdXS zqtReLARkSx=^7|ZB!*T5xNY5$D5X*obCF`H|2v1yslb!*Jt{U|m$I1sna2esaIHl}!lXdK&% zV;PD;ehUgU^CYfIWcg_}LFb_RM@>fkzovvDZvWBq#`eSrf_=n(`sBrHvYvwsQ4CN1 zy3Gx$*hJ!B_M9KRbIMPw{|QkmSVWw}!~UwjUEzPx+6WeL8#Gp35wzGY!Lxrs0ixEv zAe!@t>f>Pd6e2B*RD!$BTI?1q7|2EKOakTQwq< zwZTmKVD8VKd2t|lK*&@H*Ig@ux#Kc`kTNTI4ayKaKJrQ5L?uxO+Kb&UF9h-F3gvwM z7bKu37GTKl??Ax+LGBEs8cw_?O*qHdAG=2r*qX>z){4%_>U*T(W~c~AETij=Da6NWKsMpV<#{R8 z)G|;aqwO_CNhUv&$0;nEsbXt-Y)|OEeF3j#Y-gwRTp70GZaV)dw-E6p!m7^PM7t^CNA*Hb)=jZL8iEY?-rdi(v^i9-4<4u)4uOuvm>$^7lF#E&fN_03 z)qMZNDRPcLnETG28uZ<4#`O?a6Fr}GO!YTcMUwdS3{D+u%PHDAB6Ix*l-*Oz2PH)ysPV zw+vYay4QHdxw=ipT}v~$xf0nD!>(B#?i~}c3%&RM1qBfgg)^ZYvOH7!5+C?puY-t@ zF){v{6NIBs(%QTxrJsmUEbcuu1cp*^P#TRVXzDCen2NI4*KWtqASV6y%z**4j0ltrRmAa!Ahq&&A=M2ZFOy1a7F z0H4tJi!nfS6Id?48YFA@9~_b(MhMuLgE9NlrBBkHLVE}SM!N+hFQ~O9$r_}$L5DJB zqdKVSX2>2Z>>TT|NWBS)k911SGrYl*OzVqK=E)C|z$sCI#+*t68K+k*#)u7+TlJ?b z2YVIIqY07rE3LTgkGs~qnl0I+vOb`rc-ycEWpH+El`c=Nel^kjBeoq_#2(d;Y1Cf@ zGHnbC9}WBA*Nb9408!hE%xb=68F=8WXG79pqM!t5S!X&}6oO8eHiHsHCtLe7BNqaI z7PerVAri(!K&e7Hs{%i{K}GH-v}3C#KhPBHI;3xyYv_wSpbED0xDv#Et5DrZ%1pAp z9b+8vp=In+ ztbu_%mho&Nek1)Zevx@%yAD8tIJK%3zp}q z%n;EMl&u_Erg|I5jjs$RSwrW1J@oL|eZ0jJ?^Ed=Kw1HATyWeUImg|xP3;Be%^Gbf z=J^bQzE8h^!LkXqiw9Rrpa+1zv5*e8a$WxcN)eC(42B~;R{y1dm1d?%)JC;ZuK5-# zrL(hzFBp)M$#sAPc6+wzF|rp$ml&vBTxJ+}^*<5uo0@XJ5uw7fTae8x2ME#icqAm1LO;uhIYN~00^J9aO+%lY;HC{bGL?0*FmwtvkZwNeR5*={i0e@mW7&| z!8F=6(eHNcvuNPnJ4%#F(G>~*fEYqD3r)8&177pcrRg*cRYoN|OqOQ}Sb7yUpQ=Ke z7&73NK>J})D-WvxLtywxmMsubMU;rG3xrz)Sd2^E!6q(IEQEt)#SIz8$eBJ~q8YS( zqLBiK9MAZP1yG7qKC~Mtl0>uq8ucoe7=eQ$u}48s=h(oky8j6b^hQfp#C>bM0J|^+ zCPIqPcNPjmIM->GK(P}zlUO|5W4y9Wh){`kK6EqH&pxQ#blNtYaiBF|@V_xzn6(?x zNsbsz0SXQ1&&w2&Xu~q3P*o1%c(4ywzAY>W^3RXW-lTCy5J0AtYvM>eb15E|o6LO6Cz{o+VO5L$L4=cFhw!XiEi^y0M>i_? z+rU^!-BF2xJyLIt#uzv!N96e z$8KkIZH=a(pbjMyMqwnSX|HA1W@%hRvXYFVyV7*l(RZ&T7=(|=0G7bxur!{Db^7l( z<&>MvH%!ZX1&9Yeg2T7^KjKyRbl+X zuiX-(ps#k763(#yCTI4~Hir1Fl>a=4nPf-t8sKS%IUX z1J+qdPtS%-IGT$1naSFh>}OD=Boc*coPD9_ro9J;y~*}ooeHbw0Fu}Rcfl>w08pOv z*{4}#wN&vRs3YRHZu3x9(^XT9;L5JCFn9Qmm!#;5oeC5?eT;I=7zW}7^vVhv1a16n zI~ydbq{O%A@-y}aQ83;pav}^*&dWI&?Ei|7eqSyjrw-kC&p|<}>TveQIW!M^Nb*_O zonvh8Xi=m*ISPIkgvj%(OnaF6P6ISClp_JfuOssewiwuP1n2(^?X%``jsq=T0b#H0;>kzM_MfGv4{^A3> z7&mSG=h{F{Mn#DW^kr6R@>o0}MQAYt}6k4PA0861w#W?j1&>KFd@o$NcYXZ3PXbVmb?0xbpSRe#VFn;WItm-f$C zytNLqxMzGBv;o?eeD=a*B06=^ywbs456~HY(obbwcl`bR`r)Q5=iGpHr$xa0HtlS1 z8vXA61qj+iXJrEbn%=r>^!-(Osk+oW8jW11=Gx`gXLga^=V3$v6E32hMOHhe7L8Z9 zbztjb37rlT^KB_bH9R{X>Dys7!GISY^%3rnknITCq0F}3w($`(S<0Tn{@lmjkRX_?9(QlV6QLZK|63)mGjr7Ja-?(g!DQvSBlwG z?cT%TW1))6cx!6#V^QEFR9{$D-Avaq)vvUul1Bi(*E0Qm$(+l{3LmPdrn0o81y8qW zchG`RhvfQF;;~EjRQxqnGejaw(dgH|y(KMvD)bj5o1AETWJPVaBJA928xVVMHnl%r zcZwk`%pU^HBdzBzBa*7d6fH3;vREc_Hr#0i8cr=DAr?HswHt6c5jND-ZIsTDrCfZNXd;-A!} z@)ANWo2Um=m28S$h+r){^DXC5)^bnEP+px4ms(~?KZuJl8u|)fKFm&9zPo|$(udpJ z`y&>+ArF}lG#x^~3quPoy*Mw=c0LV{Blx_D`bDlk8SqS^ChB8jR8Hu_OOMaPw!pPM zDmKFpf-xWWQtkf*wK-bdVMnbW*_T{quvbezVLqP3{xB2&lPS30NB^|`3pz9xbpWf+wDxdY^4z~#Ha1PesM(Br!n^8H zKAY%l^ulw3{skQ*8(7ze-J}di0wn5~|4*WJBnDs83CoRm!qeYSJAEg8UsCsT*nQBu zzx~-f-=5j8tjkAMvwq6j9y`!`Ag(uG#3_@jeatPc>2Tpg3g;lFKA)FHn8cJ_lqUswaw)y?@r1B(=+cG0AyM zm-j!SHCK2a#&c@P+@F%+V&d)9y(n`;~!%{^9~dr|O$$59>13`0>1UZOA6kuC;H!7sENAkgcFp#?FF2_p=JnBbtJxyin~Xy5L(k6GcuaQUQv$|zM5~*i zHuq!WZ^W2@l$P07G`be*wMyT%9vl}Tczt;LS~2j^)ny4yIvT%mHp7@%d26*x`?hD4 zmH`k6oEv-W!%PS>rQt5f?PKWFI%{8Yuov~@AcQk4lN+ahm-(?h(W)!si^gtk>CoK4R z>;~}?yJKWc%$Ej?hesRcpZ*KFX)@PTtTf9oztWd=^aNZtvu~5l+ICcbe)FpBRr)Yt zg>+K4W`cB^`_-KmTk67)@YVz`BEd}L=0^&8-gOPxu{nY^haZmUeA3rLH ztT{m5&;5R;61g|Ol-#XHa**|QMaXuC1!-7-hY(|w9-`)NMvh|fu<=EJdO0vu?K5hA z6#C3WT2Ur?vC#gZtTJBf1-H%UZDHj~Bo6FT-CfJ>4s|h}q1jj^Jt<3~D=KfY5!8yo+z*PF% z8%O^6da>YQzJRr`JW^Jh{5|t{YY(pINs60X5`g`>*2-`zsw5vBe0}B0M^Tj zW!!N7`6B9{oHwS5rDIoh-Z5pWni+C?*u4k+ci8vNtewcKitQ`=AshmCwUTXoeNOwF z?fa@->~sG%OTVu>(Zfy$&%_Anp8x#Lla$>0^W(w0th8x%LeH1O2fOq)nT=W@Y5mCG z`iPTMAFRs6BDN58v$gmveYLl%EkWK>oJH2W{@lAEQ*or&G3{IjYk<1rq~NV(iVT&x zEx$Iv-BbJU?N(e`s8b2}3!*}9+?w~#&Yf@E$BEF3T3Yp#MQ>Ke9ws9$;=zMbmp45t zisK0J7B(8$*$e^jyK3m%O5eRa|DWc%;9VMPGS7T9$E17ouGTqmIeV>#(vaVOdyU%l ztRWX=#Nki1tB*kG2PrE>N(pIGnT}&bt&Rq!+$6=Pn(%vggheWC`)L8IeL1gbw;keU zs1yu}Yi}{dGIy-i5c1muwJWw)w#=y&y=XIruZ6?Jjj~e>XjGk|nY6g}IIajVf?St( z9=Gha(+}Yfap(;v{5YM2NcD&rb*Ya{E;Ip6MVa$>&I zF*{KEyK~=|*1uG?_clB?F!2)o?!M}eg`;DGoZT{{1*-uY08(-E@E0KHF zj-fjJh!jtbY)>VFm8ay4=rel}YBOIXjZ>6&znM2z_@g;XZgwG(U&d6LJ8ca&Vfcmr zkwYg~oBa$lwOP~ot+bt)O5c1_ZJnq8VKnkjF%VsUwyL;f*Et6JU<*SH;@p!rga4k0 zrH_!ftz-ct=6jmTfu=9XTabwp=W%kmpNMuDqN1Xj#4L1WUJ1+G4)G;fV`2!H@4hu5 zLp5v#Or2o_VZ($v%vAyad`mv%(mQ46^j`85ZMN)z4Z$+&$3s@f^3ds**jkI zPSS#6SV}~bFk_&JIX`m<3EeV?I_cEcG@XmsrWg~YP8_R`NgtqfpyWn;o|WtVz&SJ| zB95I2s{^JRfMMbJ`s?!;oL1^nj+p#x(E9!oll!{oZ1js?bnkH9a{=4n0chFnMW2hj zzb1l9IFBQK`U!2)e|>z5RC#|;HN#=b>p(i$AN~4C>|tfmhxcu^tfT=)0O9I^n^n>> z@uo_Civ{cJZK`qf_g()8A;twCAo6gj`w?onS)Q|Feo(d8)ii9zJvVpbt~WsfJm82a zOkP*Xsd|HB@*`_nngdI^z+SuZoLU)_l8IGD78yL6O{90IU*Xk{y`FF}#HtI`JSsFN zdEq@ku!~-6*D_vNQz__^em8urQ>o{LfR$!44MVH8-~T)S>@g-6fqm@9AszD%8XRK! zny*3@z<#>IR$?OMnc&oDmM!FzQop1i8E1u^8di>J9+|k)by+>3XI7GYS0l6_N5Fy9l~Gpdt; zqD1E3VaKSELQ;Bm+&qXb&Ds{0c9py855WLUiOVbPHwkT9(M|oSiu1xL03fBm+PmQ@ zE&UlT4U?d1#7E|oBah^ad0P1FFFEf-W!p!m#`i@UO(aZk)iCENA|AMYdPQ{!_`G@4!6iNY!PR=;IzRq^+(m3Ul z;}q#PsiTUf+$g0ro{KodX?W)cQi$$=3?PzfHxtLoVUhAdJ3~orzrGru`CJh?zTq^I zo9(AYO=!Co{^#m!+QHXp2?t5|Nwl_2$5&M9A0@>71b%$G{=k*{k7s+gDxDjj=1Z*n zK9J}_2ci;ctQq|Q22j1*WUeNst7@5^3}~~+m%fP`pt9EA zd zc*@5^Zfa#4Q&EsK2<-;2l$GuhknLTj^!_Xy9`@m0HpZyn!I7jmcPkBYzFsU?so%Jq4Oo#KgJ5rl|-*ffLfO~SxGFBFlhF|+(7wu zn8T%wF&`Mo9S4fcUk2V<)6Z2}+zb5=gtRW!Cclu~1gCOfk&-*;sR$Z<$My*QQP5nS z;#6c)VWjtVNzcddgN^d zzY1M`PHr#}&#;UFv|;7Wq5!f=FS_|;lrU50JU>ee^#YP2%NL`yGqV7Om%RJ8m5ada;JO!w~}|I9FHro`R$HKw?8 z>R^=SFq^tVDrePQ5>Yxh4I#ot((PVz?l`k;0Yo*=| zZbcZ(THABR{9U0wG((fRg~4?k?801Iz5d#|kvTJn8zpP_C*R^9E|tnkix7%59s>9j z7@I28C%yVhJ>+N|JQ<^*@t!#yD@pMlWOs39A4a^1&eNr4@XB9*ab>erT=i>!$d1+> zqW{=*CyGeCU|A6h)-&(eK`9yIM|g;F=QojkCCb*GE(G0N7{)N$=FD9NzRy-__k1r# zBr8U@9w6F8vsJ95laj;4D=SqVR-#&2DQ}7*`9#H}VpUxZ7{QC-;}SAbgr4LXiHT{I zwVc45gN)VKw~!(Hu^M$9ks$t*aVJrK;4aI)wN3O5SVT)<;e_>vW*I5E)lI%=0aAXsBreqV% z%LWjY@mWrhJ$TmIKEsvDz1WHquTa_<&G(ZtQuQm;b*kP%WUgU5iahzlyYTRgqR?9X&2(agrw+>^| zj>Bk0(NwoWGJ4d(%vJZFf2@Eo!Q92s&4zL)*~wdekT;S4q3WX30g@;+QVrpVTDJ)I3Hn7cSnzZu*C0TXn zu|XDo;Qn5Q!`RhNKoLl_R<3ePVZVFhtlQsT@)~)F#dai=4b!Mve^$#^S z`PhnhIv{;qL7LT`^TRV~U_Sosj&h;|=zvI>Y~`KD1N1KhQ$Vg^E)|)FP@G$gfTZ%C zr#}&Fe;}lCPL)G&?5;2#75)Ba&Lr!KRO)WGKHyiuUSGRBV@XO~O@=RNxpxCHXxwmo zORP>qslt83Q*~VV(7#ZuE<4^M#NanyJGa7>i&wY3%ec>INYf!Nl$hUq6OY7-42z*H zgb4(MRR6jBzkq}uXI4X<>V=k!yZg$x=y_b~7E!5~07ZjUs_4QGVm$a3M?KbYO{oYr zU;cCdrp%MJ8?K-i?0SbE>^GUY)up>OOj3pR21RVt0#4sxjvoL+)OH~L3KeLYl&|t^?e&{sVsB>yd#EMy+cEK#`s8(5V@ZR@b4=IDc z8b`@UY;Kd6_G^h`Dd_oL)aLE^R>aN`upGS1S!`?OS2yN_-1oYw1`GNO_E7jaC*Lr|cV+rR)1fho&$&B}7p1?~4>YCyj z2a;}loN6p0LPSS7BsfaQ8*&Gnr^XVu<+qLUV!(vO8)sgr2VZF|{F&VX*SBLX$Ge^1 zYvV8^WJc*wR;pZuI!gwu5oh;2*k9bHui3WhyO^eN@otbpMy^_&Nav<=incdROpoSD zj-0jm%bhlSz$5}_Q$&(FP?BI&eiF>;XB)_JV)u;5^qtr6d)H=2O?7m5+g0Qja} zV5toKooHf-)u%=JN+bJeWE4-ganUo&+ z#WA5UNT}WvSl;dM^>kDuGk&4OuS!io+1`?D4%`vb2Ax7YBfl&SnYb_&*E4S=jA{iO zql3wosr;d?QK^irIB+t8MX!|&x~n~KKnt(3S55XE573F*@ZX&|&%yQG2I|8ME`V9C zAv&nhV%wnIe4$^(I^70DsF6+5jW8%OrAG6elE=yz9T-m2`qH5*LGYI~is35!SuNdl z?dlCFvs1X!?FH=_dHWS?!mli>Ne}RPuEDcW+87@Iw1jPOeR)NVVbKTHiRZPo*Qfe_ zaCNP?5S~sAcb;{)B6_0R%lEBsyaNS&qN;T+_Z>wMC+P)L3B<|)r_nE;% zDK(rudajw4ab`{PI9LB8XG7WGR+5YdvT~2a(-zd>$Ua6(w-?JZh=>M*G}%H)_){fQ zmeqVQVQ$@J?qF9VkO=iqcj!lj)UIcx(9`KKj0pi6JD2+7+AKkMCci#A)zS8HXVR({ zR1TeD`mxkqas|w&ArxgPoKTElUVQ`!WzedzLFeZ4kOo2znF03O=9Yss5mW06IHhk* zE$3?V5v5{7i3>ej{dOKG`q8(?5w=tWypjO;pC%Fgy1C68EWO5QIz&WRb3Vgz)?upf z6SKaCTDaX}gn>8>Bze0xecE-~FqzVmLp8IBmd1hZZk(8P3%OGx|~&i3(lcU z_RdM2L`r{QWQg8)Q0d0)@NXz)>{B4f*oGNglgO zGP&W8X=fCc5fhSlOuGqRR05bj&L?_x6c z)`3DlEHiMS?3_{!d%z4aJdf)Ypqy+R-;n_)QkMndBNYAXti1FJd}G%N@+>q$py`t{ zy!gb^c{bQUr1Gg(sC68zPJ1AF1n4)fj2PR?2)k>ZiRUu(A_`f+0^qDr@%9{Mz-na) zH|pY_=VvKXC9fL6I0jRQP)GZ=HdzV78apEp3{dUI#)2T$O4PE4hKhl7Si(3D8;MdL zI);EY4$Z%HIBqmHCRVNK$p((e^Y$brvty>UlZORwZz@&^=?t{n0pVzO&QE{op z$bw0`X`vrO6D5P4x}ldpWDyAKV-%zwdj8a2i7W(xenfA_afu~-nBXLk6#c=lb?S^_>-@i%)T0_=>o!TXq zR46zxcOHJhc14Km_^*k*N1kwXsg;n`+)&X>1;?;)hqs8(a3?YAb${96cmaYy${2Tw zJ)=q`SdqjERCM?i+i-*&JQnZRGfZ*K1IVWbJ)`F`?Y@g}u7Z2`R0FzS(sHATXDth*?#XzBUp_-cBW$m}b5x9KEmC#zq{Ahh z=Y^r7o3(_6Nx26tnQVKtFvAn5SVZ+3ob*>@nhzNJ#0DtD?6>>1ew5bl#QGE$1Y~4` zEvOspc2n38zSX@6Bhs1h_43>4h~}Bafv5F}Qo4exk7$xVc_j0P>k+xU{uXu(+YNsq z^nY>_07|TT|J(wzt0gk<9>S33`R`;&m*%J7--cVU0f2+8FCnj+okEnL@N1eQqo?{w zzP&3EUMzA~m1a{Pv2`qp4}L?cuJ$+2%qzk;PbYm7ZpgXO$hNLHWqbEL)2x(FG+I7K zHC8$ZOdZZI7J_#zlI?P9Z8?WwJbc00b8Sc8V@qW0HwMuO&eq2)uvOaZYjmKo1yK)O zYPE`QQZCV6R039Rs!rO)jGsIIj029|2=yK+WT{ZD9AVC#KJUk=#7sB_yL}#@P!ZFs z#q1{Wn+5eSeH8ePF!N6y^OPgBtP*$4Ir-73?%M8M9^}2fKH=JwF%~usY z4yefVFzs~l%~}XV6D$agz!_yBb$XNC;MBB?q&PpYKZBSq=(z(!@5o?Yo>1?phG2k4 z|1z3TWE;(g52kB|5;{Nf4F`Le>sOlYo6_kEGBzBc%0a9jDT(*g)U6#-=Kw?f+2&38 z?6|0|u;yG7HCiXPAztIW#nvVSHoqUdp;}wj>W=X?!^giH+YeZA*E3^y7dGcSk2Orj zXYf~yAf8X+aV%u~7OXz0W~$)9UX0 z;;5tN|JhhS1@8r$==rWK2QC|KIr(HVUGmr$AEGyyY^9y>FzzJUVw>dd*^T+1b-;~4 zUT*#XzGK3gl4h!) z3i}PC-MKQ|JPeW(xtt22xL0c*>AqD9RONGOCXS49Xr;?jYf8- zI5EG+`(?egXVdLGTd{ztDV;CLx;|VT8t@FxaZc3Sc5ng@>VsgF83M$sX5tINfDC(C zq4r>R{MlO#VDO3$79)9`ETe+F-i5nU!Q^0+R5(u^Xl2 zpEb08l$s7pz_W1l-t{{0s0HoWvR*u*gJr*Nc8FPc!P_&5EG1#5Nx-jx1 zyv~<0>2O;6Adi3sLAU(^bFZ9{k->E6Fl-h(&zCQ7sN4;Z4Gp0K!wEFI>(JjV{k7ap5+oUa0E;E^9T(B+&{I0mQE6S%yWm=o{KfRAQ`9kcka#;&vrXvz1xuT}`~9 zDDaBEmOx1{`YXl?wR(N-NBWw;(X6UE~HcQ1BQ zhs1`ucb30WH~uxig~)vS$wSE}L0D-#MOGMeyJ_6fO6Qp~oF0xK8S4P(ap94+6vnrE zkLOnU4M!dTgW}t_v^gvSD zKml`$I-MmS6FmJfcsK3+;A>Lx?l=9w3DowL`o9JN#;{!0#)-l35Ywz!obx^}aaI@U zCa8E*Om%J&(@jCc&U208tXVpliqHp>)Q`^EjiEFLb5!M* z3z)m?0X;}EGI_8%@$}9MaRE$LA+d3}7h+y5nyJaOVC8A1T?&tF<#WKyv;_K%3+CTN z{hxiXH-~hYKxVscQ+Q-Ga*kEx)&AL*Qg1jbD{U@U($hW8XdpS~Y;QrfJaPN)%h^Ok zX!k`Yj2JcYa-I4yM571jOI)!SVO zcEd+-ma3d~N8R2BPY$JkPuZRP_KtX5_LG0{@YyHUw60$8#HDaJ4Q4`N09!gh#Wwua z>a!>-5tgYs!p9MP)5{(*IO+E6ZVhwC;Hb_k#70%7!%)1c1-Bk%tf(TXNo6r|LtO`Hzh!65aDe(`-eeik=pqAnAL) zGrS&QNQ8Lm7lTY5c!h{p(i6$Q{^lP}0WWJG7@n9ZEEFlOJc>2c7icHt8J-*dQK%E? z;&u=eZj7&Z1y4p!()goNSAq{o50%ta3{h1Z_|NWTZK@geG4Q4@n|7 z?zLSd-h_HjWKcCKA9OuSr${Uz9!4a3Eh%`dBl2jo--l%k~t;DGOp>;gTc*Q}X!eEhk4W)Eq=qNg&?_QP66 zRwo(`-#cQGl1soFg1#IYt=0VLKzx+{E)q_z@q)p2=aviHkA8SvMaJB`r_D$Zb}lEWUFhYLrnlOb0{bB`jMw)ZNwa^Skqf`UF_~ z|Lc}_Z*1);YU6s+jd�$B&zje9qDF((|7j_^0|~`qk3ZW_VY_0dYfXM>4&U+xL>tXi=XDay;T(W`yG1;9lPeel=h3PpLAy6iE!ILOS;rR_0Gm%JB?FU*4E7w zQ*G7u6m8QmK>VLUZ(cjzr!QeKH#J4=%KJSNgEL{&PX!(tL9D9=^aBbKG7yV`Z4+Vwcw_-r$SoZ;1mIOqB}a> z06l6?m`vtUGLm}!sdml(ldNL4?g#radhK}m+*JNOr%rf2TWEx~)y2y}O366~KW@Sg z>H0yqUQlo19<2YjY(35V$JvEgdR)@;ql!liWvj8IVfx-Ox@S)|WJ33r!02}8zp3c_SzRL4}hlyCSi5CA%Y@`2*UdD+7H_=il z2xg9rUcY+DMJ4lUN6iHx7`?eEnw@C)5$ObjA%=AtlC~Up-#wH&gJ+fFJyJhcGZnaT|2gj^e`cSEXO|*P)G_kLYe5;0?KQLNhWCzEQ!-pkdOvM; z*QwK{^rFh+pv1hOHm?JJ_~doEmg-C!DXiOfHN9v{26h?e%xXqn=`ui=q}@|AqOU|=q_f;Plrq=R2x;avVYc3hA)>`D+}GwxTYmkwBd}QjlhXSuqvvIaovZ%VozbI9i$9W7JF2T+M6Irz&C|Zg z(XnHGdRx9(sm6a3ryaI_$ScBaxmq@+)4SsbTO zxFJ@hC{dp@dOE8B)s(@%XBv?4yd=qbl~N1)FpFrv@j74g*t>84Nt*%J*`hCT{Z0T- zj-A+>Kq6i58$Jz-ReNVW6zp&~H1c04p>L#75zJ?=UE*Kt$bT8HKujhr^@+vFNn_Sk z0XY`aq|ecNgx=rdbEEAZ_T^?EF5;^uK9v3o(agFe>2v-YPXfGt;4YHC8S2$%h2#g6_ThnBk*oJ`Kn80oxzM;HqdzrX7ED^4lntJ<5i zfARuk1C2eeKdxqBj{bbRae235qSc<680jL~&W?$ixVz$Y>?m$2&1UIOd6P!=wE%1m zi;A4-sZUB%N*XozozRSAvC~CcwQGJO+8qvPwC}0k1rm+4(tL6t)wIME)ZmC$e`Bls4 zmgBFrSG?$R|3aJe)xYj7=+k-FRNOcezbA3i*F)RXYOgoxBoMx`XY771IqYhjyleN7 z_{4-Q8!8+ziQ^wo>^#~iei3w+6nAHQwqDiGWU zpUPI=y6yXI-_WL7I*MaZFn;Xo885XVg+thYQpu^_g>|&)zR$QX&>cxVqIt3KUDH|B@MuxxCNnd-Ui!?7rtEbRs!b%n_~MTDGhwD>hO`3Lxxtv-KGr{2RAOjz#-zZ%rpD<&roS)IFcjd0}dkh*KwJFoNEEtom}osPxG&bWEm;^Q5= z+jsmKo!yeck4S2MiM(l4jTHo zw((~w%3s~JHBv<7PbkzYls2jR*XXFbP*#=9g*P8F1L* zmj^spCnBn}4`21mbhIMn1(}PgFu%jK&_h?ctfaJiHNlhPIw@g?mDe^&z0c^McTjv7 z{qO~SV@lpo$~Z`CU%h1EU1y<$uh@)HjIa`=U;h^haLBCs)vh2E=_PF$C~;8Ox1?Xn zixez-_t6ZwfnpkW4rx0uJVayi1Y?TV86k57Le_ z#*~04`@b$M#Oj-FfkHdKVWC*W9@{6wt!=8jX7ei`!o|hWpL}oo@bHzYS7r&l;wOd( zI`Dx$wd?ry((c3s6_{7S?Tkv!=!q#U|B$qGHA#mPSp}oVvrg7KpUr>u(I+6RkBZRT zFm8_laj#1K&mPJx zcAwj(ona7^X`^6LO{u1A_L*B9&D8$%;M`5y5=y?5O6DTE@4bHX+lNl?8$MB>YFd79 zp8XjS&8qVaFQjL!l+RDTsz8^2#XpbE2rY0e_IOqoyx~=HVxTQ5sa`^Jsk{8A{f)Vg z8j_x&9)%724#)d zJ%4alqh4-*?9wLs#t)8#@#%E|wr<&vuKf$4M!Ek&+n$*j2+O>~!g8~gy&sZ~Km~S1uoZtKm~__>Mf>z=$9fM}0cF@q4(1 z%bJ_ZKCLZI{Kfi6GTL+4RrmK? zHEm7;LjcOD--}Ea{PpfW7~20-Iz-{FUfLD7ckjZdzU*?u-GI3pa?eEbD-(FZtmye4 z$dh}N4~NWMY2vnRzcOK$S7>)HdHCGn?e}SXD|vm4ZCv!*%bO%Gwesd#Hig~Nn6cPt zd5g4<%y$hwQy->lT-r>&*d8o?vK#2$7uh>ufg4TtQa-0 z#(Fxm;|&snq168@TdCsm(XtAU*?}MB9X4f0{mRqvw->Ym_V>DPx9iwF=z1q6D6{|P zcSH@Yy>j@}^Xd={^~}ugUtXb@(F<%Oy72fJ=Gc^5OW5J)CXxJTNwUuggAafxfH3Vk z{J-?Cp97CFExjt&RqN)@9F2<91j1622QdAi0vEjCIpqBG(C*39e*5;(*Qb+8T%CJk zHIvUB9m#BBpho6okH)eQ(f+ftv4EP{_dX^&3t^heiA1i{{x0Y0KA!^y1^6gFmIaN) zMLIn_SUZG=Hk7|X*{@Aq%B#(edimz!@jtv>9QJOMNcgjlTd)2qx^#Cl_Ua=|BP@M9aQ)!RC{GIU-s>8@r&3@NGr0h5_ikg zWFuwPuM~|lUXaSWvBd}PiwDsie>m!xyI9C$%CE_t(-6Hg?*dT?8P88%;~P9SxH*S! zPigIl>Le2D1!MRdZF6o;bT%X9o2{GMe$MZsFds`R!>Q0#F28TS{I=!SPu{bI2BsSz zaoF?Ab4M1!whIYX@D53;B!k1b_@(NSvFP*fulv_E*STF;+;b4aI%aooQNgV0>D*#u z>gl;!y#DR^XDXlT_;3bLW!d#sseH2e?Xp?p zr8|`BiV=|2gpH3sY6WiJ2f?gQatg&k+_lJ)ySlUPkb0^tOXV+QZuX>@3ajO>RR^|g zZu3x`L7OsGuK?UbrH82ox;!YprtJfDIcE8C=|8vM5g?_*3S=nJ?#@bCC;yU#(b=#& zB3!I&k?&0YOFMcL(-tLSjHw?EHzDn~`?O&1`#v^7#%YDPXUu=Na)Lo%)V*I?EwDVk zeYamU``pndUdNp|R{Dg>%^&;D-`c67`ua_lgx*&@vQKy5$RlM7ffc{edFE71q-}SI zd6@PYxJpdWY{jF!Gf0ykv7JvU1Qt-DgmioHA;|^){^p|p;J7DqCs8T*(#G8pFI*0p z8Y6UE1+VUqSfQ@&{#&wfLnw%PK6=~qH>$@A3E@7=$e z&pP##Fc7n=L$*@(^3uao`~Gg#V=hSg3Y<@Q)qv8y;f;|Mf1insU8w)1NLoEq5bT$@ z=dW|K`!~+%cTE)qM@mzc;=GdgAic8xynTxlKRyvjwca?`Q-C=-Qa|qP-{4qTDOxpt zr*SUYhjz1;n4u_)*1DtVgxntx8ZW9VySH0I(eNS-$ia$D_AC0}!zuMuWugu8db99w z&48t()<@i;tAo*BI-|XXmUPVAT96eZ_#pm$|UzI)#{+FP08W?iW{?LZ`Lhz$-h1X z@MaT&*^y_HDXW*tei@|ihjpDLTInPv7j8V%gfOiS6`I5Tg|KdjZOc2KhpZKM2m`Qw zFfYUZJ-=ZojqMy4 zt)xfAP)wg4{;?ObUa9SjU96ajkKYEv3|jW;`6lOhXYPArjD6-dN_V?y41HFv+nqGWF{0GKpOQ)9(v=xzs@(p3%n+M zW&Q;uir@*_Ac0T{Px_^eQ5ozib#GgIB(E+rBVD7j$P+~4GmW(lZavE0wj2O_sNHjP z4!`}tbUgoCr#=2a{673=CLzd%}1KG z0n2}r_#rX`ibe3xR{8q!uj)HBkmU@Il5DwZ@@Qb|SZW6{K!?DILRcDj z&hft4rM)(dPzyUoO)4B-?Z(e0tBc=zS=&}w%Z+EV+H>v|?kK8S`CEIFfN|%a))*U` zr2kzs+TeTgcdn1ZnJt*c6BEI&BH6c$Bf2i=TYmi0>j}SvT&XYbmHN4?Qw-EixbQze z%~1VcwM3G0;(N`KuELPZ@$os|{_N8F9@2cH6*-dTenL_z_c-?xf9q6X#Eg8Egfbob ztk9ek@gogq>fl6r@Ob@c%%y>S*Pix{tJK=;bi8-xCqMvD9}O$y?VmKN@XwFbR%p>b zKbh4Xy>c-y#~g#J!1EwD;4$M*@0E;fHgGib?#VTYVy!d#;h2zS<0yX{W9|5+0QnuI zVN>@gzjI`#WSGP{lv~+vz;P-^u72|kg^}E=Aq4XD(H&(X4 zpH04Um2#aVNI6|tpgwLMyS3NsboN2`#vx@}(NN@R=9by)tv?+CKVf)_nLKtG-R zM!emMRG*C;U`G9HHWGKYJuQ}pk?Ej zvILulCnps<5#QQGeFJ4(Ps-eBv}7;u(LtiCn@KUxYZEo;F%;hAH0g*IPriq?nc*d^CCtmV2}V2G5T$M3n0Owb%9%Op zkeUmJ$nAcpuO)h-40h=qGmKk;k%HQI7y9enrG+L=Rtn#a({pb#=Wq}WB;dw{p>>Od zXQ;6v!SvU=nGk=J3~Lwb-0-wVL=XAh3w!7%PEWL~8XnC03D(f!2Tj3ZJ0+(eV9ZJ)I^wvc7wl{UmvVnNqB6 zke+vt->Yfz&!bEvmci+H`1D~!3bDc3O=+L6t=g&_{UfQ<NPz2kXr77T`vi5zMa{ESuJ46Zc-D)=m+l3*NimFEiI<>I>9=&ycUbmd$>eNRdM19Zyc%xHCP}F4&m-}2T0!kFhmpkt^husQSv3(-WnCqdU z+lzi9rS)82UsGwi2=IuSMHT303I`#EV~5o7%sYEkd>-gCb78plH2w2kTjJw0rc1|E z{{l}0go~J;9F#|wIZQbL$pcu$40#$T&Av(v*AzyB#pvg_gUNhi+*$IPL!qCg)|#dm zKD#^kj3rXm^)c?u%?B^u(q~w)x-GiN)c*-fb6$Lc5-tRiJLBlIR`^_TM}+#909NdR z#Hrt4XZU6yE5Y%o7={xumUNnONCuB_AIQxgIUU;ad`lN%B6g9jEFHW>nCCgDnTkWT znnh@Y;I%PskwzO&&U_UuEpYzJ+fze`H4*~twsTIOwj&1GnBqQl6zviXC72;NT7FY{ z2}872j4-Y@q%Oia{}H~{P4VOlhB>}_8srtXEapNm9x$ewU6`u#LBb0<3*Y=b=Z6gc zGLi~G2|Zfm;SS`Q*WayTC?bL~`PSw&{5qV;z)QiHxg-xV-KA)TMUmOc&lp3xDu~8L z&5yyEwAYJz>Y)XxJI9B-E_W(h(*!tbNomsnhg3ntlVN_H?d|nc11Zt*zjg6qUjNXB zL|;dOBxAbhbMg)Ro;2f1}kVe2B6Fm-u7wcr57Vh_OFFZ%~x(x+|M@y$9gE zUlTJl8B6ajb-4@!B`6R*Yxdv_HfT5ch`y8Z_8(Os+*X}L56@K+)-;S;-@&(2$6qk> z_`^k{_*lNqbR3YmeaW4v7Gs&00nSD$J*q&=$<_S`k-~;#ITHb^GOm)B~ZNM4xB3DQ54^VM6NQ}K(gP9S`F`*tfs*{+WDnrh! z!u5PMXL{ICkqStXK-3pNw2|@UAQjrmok7rfZ;FI0dVzZ&iRyLTp{R>p^$BM zR?9N*uk0;ff7S(2Ya0Tz&4ZMTH$VuzHMLc;LTqS!3>jMe&UnYz8!angg`b>RR{v&l zVBnx5Zl}$166@mz*wdB^KQmnC(xLsWs;HjYHC*3piAKt}PgWm*mFS&u`9yTor8&A> z5Fuf$`j}1YWZiF-=_1-~NrkoFS}%LYxY1 z^U@My=7q?(M9q}#d(E>|R%jBJ9|xPnz*}f_6$GUZ_6ERvsM^1tk`<#so~YEtgc*X{ z_N8bpt3Rgb_YYo_W+_IR;S=egxq(X?%%W%8s6s)?<`J5?5<%nmk#-@|FH=P)0ukU* zI)b~*v)64dYzZKseOF`Ga-om>_73h@_$1j4MfqVK`*!ESvtGb$)rokHuO+mJsW86F zS}$zdCdG_b*2{^fN8RWqx8|EfRl2O)NAXio01f!yjvC`TVc$usK5lTZVtB&G@Dc;w zI@lvs4ZnqZ435leRz_(t1}e(+a8k!f|%G? zY&-7MipB_IfYjY#2pf?9It9DzY3EDEu8zb(p4Gw)g}Q0!XISO6@|X0L!buO^K%j~W zOduL_zBPxca0Ue{00dt%uG<(DmvCNnoeu!rNivPaFU$y5;G(1L2f_G@UXf%(*9xIc zCRWIbIEg?Tri^5`I-|_h(4MJ!e$%e|GXlsP^Vuoa6mzA#`cJZ3@_q&M`KLLhT8IOFR z?lYdG>Nc8OKG%w!B`yn!ZWe2YvqQhDCplL<4beB9t!bl+&i~9Ph76}#G~wf2*hpzl zCXKt;g_e%Y7R{kIn0ftLjbC8nBX9%+198|5(hTMe?R5IFIjn@d7FFc$4bVMg5Qu$8 zCUM$0R3Stm45nc}@L*(Va@63r;Vc?68o=ME`u^iLzsMn=LUrjcNrff)h1Y@Qa;fKZ z*&?5S0djNaBabuHOYj2p@&a3t9|=m_B{W<>I&o>|7Zu+WD;>$37lO{c6@+=6jOUKs zzoa5;w_*^f<+|R&{33gP@dtjeCoiqtejLuSH5j=+l2xYy{ zySPQ!*L#VFw@9frt0rW-&^vJU&#WWsuk%m4*#J?j1wD+|RohjpM^uo)&x^2Qae^wk zF8)8(R{D9#AmJ@!2F0K(S!T)*xRUI{Y7{N?1&c==sP8G-g3k62McT!08;Imb)OaO_^e3|Vd zYXveg^#*@@sT&@%>(;*fp;;ThOmhR!X$Hk9vrrA za2-;Lb}bk4Q|kV}L?MXK)+KoE?4V-zcR@*fqPMT*KD11KcICW+UqrOnVD{Lur_+{$ zey@iFP3;-?*?<+T+e;1LJchOmrldB@-Wq!SDhkr!Uko3@Va5`ML^vN0WP*TJ{To+) zg$)U_UEz!dLJ@K^?hTA^j_{Rs3wf+W+2%5E7HD`yNxGb&Fkg$B3bR7ArY;`jyC8HB zxSq_+hjXZ7*eLLGvU-dB8G;TH5YdNhC~g&TF*m1uQ!SHf zVn2KR0Nj*EVLV?SipGdJF2ki@_7VHj(AE#!#vIlQ!=TIPWkKW3D^kh64X;>K5hKn` zp~CK`9&9$*O1ZG9`8s4QWKx#A{$8;Sj_mRc2Z~Tg8HnTo+^83*vF#C|JUHvZ`fD&g zq${#2)^=)U#Yxw4^DQ$eoeow~vKr;?>(Fu=kR-LAPv8;DnxcPN@oymvbGn@U)#{vu z^x4;U*zij22t=r?);+sDJlu73ig-aBOR1hkY^8%0cJ4eEj#&noJ)CztvZ$q~p(sdz z-U(t@n9Lbjk+zc>3*6Z4eDNJfIC%roTpqj^L^GYs2kAI5o~$ng?q8Dc$KW!Vq1Yrf z;%x#?*%2cF-hL2lb}roOCRf>W4h8tj=8o%ca>uf=ZPXr0T?gJsd9bFg2NK$0__#jX zum&vy9v;mQG^Sm|_?ps!HI}mMPR~j0z5l=meH*G1_sy=9DSOG#68cQeT9PVsVQzD# zgQo!dt;jR2IiFt=ZXsyc9n#s`nOIPaP#u~98KHxHnoxRy9=x$qCM(*}{F4iNxz}o? z%*F9r1j0TewD;;~xfueEjbzlam9y)b2)>^uC<2{Qks)cPy4`14ach?kHCD6uy7|h~ zyziaI(BWWJ11kgnG zPLxB%eOQn-`7aY7Fx1Y~A#88qBa z_bNRNSH^=_yXCTexk7=@EJaofC%x?o2B6R^>b?~@m+wDm&uw!DS%doOxyj+NT^Bw3 z;0#E&V9ZUy51Y}zqjalZRDVce5ibzV@yzfU!Gfx41sl2+NWctrLW{A9Ue}Cu?0*V0 z8!e+3MKhd$J~*IZ!_@VH*jV+o=c@Qy*r1FS$)RLx8lSMX3%LEZDbKfwff4Hj^?!U= z{FsOc?jYZeB3%_3WMV2jixDUKlnI+1Qy8WIz2z*uY(m*WdT^G`aMedo0CQn^iMiuG zh>tFrV+MSi00REaH#vrx1bE}96TzlA?`i^NAeW&6}%& z1_d>mU+G0SUsBieEn>weA?%(Ht=@2I@jn|l3?<0sLHC< z#<5XWQtD5YO8Nvnxetwzlo2#=D=UvCGyVKvJ=jh>v7!wx0k0v>EOJw8lr2xQV^IfFuIXa8| zKVJw6(k6@OJ+MJrF~j;yo>TBfK^+^)sv+XLL}V@$w)kEt!b~0DVUg2LW2jp8x|pk< zg<$@)27Fxx;m45yrSBcvOgpDsoOEV}Jg-M(RHk>5D^*Kv!@YpS`P|bT)k9t$~<7}zual= z6$GLi)->ZvJ4p&g5Hvpk6KTg`lk6Saj}h8%eUgLCVmMj^mwSvMDa;u_z9pW1&fv24O;I( zrbzcStC?z9+NzWr3DTp8_5)7rsddklT`Q-1Hdv`z00*T34(kaptRE z602D)DcrWT*Tm!62M)G!dCE3mU<7AGSgtA?AEOA9R9bZ|ggbc@>KjhU#FI{s zR}>=!0#1by)UuKPg)qb}H6TANWZ&L!umd1VIzJ+%|rjy&lww3VIZh ztWR~t#v#Lv3@RYv((L`4VIJH)7Il zow6(5PzpbcV^7``n1>8Mw#vdUd0mm;&?i>)e`RjI&^p-50yV$lLMhX~9 zzn=h#A@@?do)f*U3B6(>Ff|_~qbCdOy#nu#XWcH(67>9&w2rbv@+tXhsy2D}x#Ovi zF5iZQ_1CwWRbo8)f1b2fYX0qy@T**Dw@gd<<@n{32U_)mtS0b27S>InCLeNlLRhMq$XA zLgiFWL(D0JB4-V=oX_X=dwssY+s)tm!}ff=9?$D>UH6Oi`ICK>?a@lj#@drHEyYKQ zPmg~)C%G|7&5Tt)rkY@u>(~y(MIxj7EIY<8kp6w@4#{pmB3cHI>fejQj|mmAFZ^y; z&upe76zciF_OIvK7BR>*rj)eN{-UJ~t@*Y^M_?>P(;Mq;BTk|28^xv~$dOqRJ3={% za~Go>{ZV5Fo51e;qcSr2rXE?o_%pLm>vtjjY_bN9TZvrfGxvTx|0m~Ez-u$ju-`?m zeRU1R;IZ}3w*Ys)qg|A+V7Hnxy^EU3&K@b$H!R^2HS~nKv+IrWb$uMW^)XzV7{W-A z?WsA;Q&M=S-ri0=I zgqv_nB=1GTbOa(ainG0Z{%S_rZ3#}upz5yq`ar;58W!hvf<#~4J}^) zE>imz|EiHbu6>}G)7MM%E24~q+EiVkYKZ&P80y0r6ICut8p648+S=^o&zI7&s;APu zhN{J=$>#3KuX#}a!GXSaf{|m-X~}r)&cmF6nCO|?+wB3)oaD?IQ$$qQ3p!j%w5R%!M?XBP0k)AZ|#Txc5Uh)k6SvF2XYlgO$ zoc=bK^GxKLI#oHiA^A1LP1M`4P~c3ub3uq+<-Z(U4{7&C=eAg8DvT%9LCh*8<0=bF zPP}aWhdnk&1sM9q_IUI|z254=Epfy0z5qhk#Zr|M)7C&yOQz9a=M=V@uRv3UHS%eB z+`<47G^vW6;Pl?U4DNd&S@S|MMy=iT*Fl}&W{KC`7WO;jFC2(P(OI(X_WI`PJ}c3J z2d#}UD9s5!*~aLLk>TqzL~oW&*eo>kb&pBa?4pJb+p^a2PbdDG=?l93HOgA?_7Y;Y zPui?l7aJ`W`Lnp$CWW`%y>_^dJN;kxbsKP#BMiT^Rd~PBSQFPz=hBvgy1XpSev=e{_#V(U8Q<>g>RNb@vnko zOC;LIe`puKD-$)S{nbEC{$|nty1;RA4gKL-2ti_;I+5;O7BIAZx%k_T^7}Bg8T_7g z_^1j}w{;a1aLVm_M_J$y;J>?gEO|bb%&lc>O>IzlTSkkyI*qrBEZF@~Xgb6FF9RVs zpcT14$n$~jK6mQ#;4&w_GZMY1RVk3E7B#Nc;uut~2k-@e`j#EX`oRE~l@O%-3i8o( z?S!t%%Fz1nMjL^-PiCIRNq|m0aV+w%WZigr15bZr=xfsw!rf?FTJu6E6mc^%zwgPc z7ljc-$?C*DBks`3(r&Dcxp>}bC9vo9zJ&zsO3khDJXl~F-41+E4lt9rcZI??GewmSsS=9A`oJX3i^R7_F4W49S<~X z)0cmRvwM+GzAq1}Mwb2{lt;P2&u0HW%O) zil||Y)B`$8vop6iLvNg@#621qyaGg!Q1*7KAG}rPS`qrbGnZYqB zQ_Fm`Ko7Z|20=O1hz7a4p@NOfqxbKo0C8+p#(hU@+>Y{MO1wVJZ5DZEUW1)%eiyVG zYBHuwy-o_fIM{K1ssWwcVBUvEizn-peJO}uVJv^IP7VF#P^UNRU@j2dd($^aflpBG z(^_WQyfVQmdFNDOlFmRjs(RY&N=4v|z%}N|so{-*iMQu$QY6*P+wUw#D#r%}q-#wT zgU&?*Bes}qSGJmfj>NJ#6&DD@$<`@dBzM!%^setAnQ_9!%~z7`tTnV-3g@ArUD#yr z0ky~aK9x1qw)jg+nW?@dy1yTyKH{^c2)&zycatEJ>C4b6rT%;iF^9B6I0{wmmOKgh zR#NnXRoLJBTu-S+{PhfBfa8nz9^9qrfn#SumAcoi^`)GX_jucmISMlXdnVD^L@>1t zEQ$lW5LR}buR0Ua@)FX z+yhGu;f;vTP(NIwac9Xy8#%T-sMc%qN}m%irs{z7=WaMTQdZ-~cZD82KSYtym+pHg zs}R>#8@I%#E;w1;pBFQs@iaiveDqi!L5CMMPMOqI)KwWk1P=Zi@HEY5Dv0LDp-KN4 z-xt<7a}sUjEsjfCu;N=xj2qQP`GVS6ty~Ge4*Q?R0WB)SjGynGsU`daI&6vqR!+>A zGEULS9`QQO=bT|f zo2*5mmr3_Qm)`=(x0hveHcsSfcQ;%bA-qH>xU=|v`eyFQ4G~G%eZJ}IGpZ8H@OJF< z-49<*ARLwXOI13=ae*dWX)Cf%l2B1EW%hiE^Wis|F5V=83Iq1)8~Fsj9wT}8@O1Px zKF;$w_Y~N_^Vfe2=9Y#Kav(~|vA^0)ltG*9imIs=(Q5@WO?Ras9nwbtgVVV0h$lk5l+6`!2xuYi9#{pWz7Y% z-RbkOUKtbVl;+}(xy3P4Axke9KxiY2@55MJ_U)j(P0m0Is!PH%W!+=^5k&l>DaORJ z)3m7vJew?=$;V{1ge&5h435KY==F7S^M@pc`17A9=5}w1radZM(h5z!C*6&$tC@ja zUopGu5_RW{-S=|);e!nHf_?NfHqt@((5*-z`Vi~0Z3a@Yz1DZ5x(ZJ61=vB`ORC$K zcGH4bTD66@Sy!1wzvgPttXM{4J~71ps?-b5eSv{OiWylirnrnJQ`{a@+UP8b?^$G0 zLID{;PniAlXmx|rkQ*ujv}Ip=*Lbh-cyR!+fTZB$wUfY;Ly;Pl*xa`&X16p72pXJa z7tATI_R0$W1qI2%SoU~EU7m(l2-L;j81b|HkUc16Rc%%rsA!^r&j#iSEBBsvMP3K> zjm{H zif+RXxPW71Z7HVO>AbzPu2|GOysPkZPfR@3Wr=<3KW$#P&IYWm9=IjksTcp632Knu zwa}Y;)Ng2mX|s59)zWqf`4=Ry=tbkG>F^HryA~_Ib?fTfqzHw1tKIq_t5ip-idT4f z`V$H1^G)}ybE1RXS2N#q+#R!tdr3ss883?A=yxBPlQ%vFXFDYVjjDkJ8~L7%8c-M= ze9Lj{^M7Z$5%F|fDm&S2st&KP zo}vbjrvQrJU8%d}bzw#(7rPJ3;P&YhbJlIYIU6@Mqe4jzs1yp@Rrv^ipOjes>H_6m z0PB1G;~;%lx|$lCu1#cL-u*2%$tl3C;X7C0)W zI4uWX{^;~y=5flG`VSPhAJ(^?cX-V;@^#}up#tCIna+TIz!tC!Q#|cym>;7RUg6=UX}%esD%v34sLcMN zl2oR2pKDW_7C?^j@%`v(T9dx|nD_V9RX4dGA6BYL$1W$Fd(^|jSOY{S^W}3@soF!F zJinnHzzb#Q4TvFs{>^{Ku8V?633U;nT9tN7l16P)7fD%D6#Mie?2+ZK?w?n`myGJ3 zPr7zn3uF8m=heU0Qh|D-oxsUh^`An|wQrOjh6@WwJqQ9VTdgY9CYR}}35%uRQ%tIdQ9 zt&%b`MT~hRz;bo{on~cg+Q)_!sVBwwtW8^*Z-@fSaAs?tM+Id9jJXA2GlG(ExYm8zcBF7jE}Ic^XTo z?$o$Oj>f)Mn^{+NmvFfsjpW_je)o*>w||`fou`59saLGcviv&Eyv3y!g}bi5+Oewl z_N=>}w=($nPPTH>KpF-#j)tsNzVLgzmRSFd$wyO=8+NhB?e18eRLM#7h=v+V-Lg^A6;YipBBwC>)Y`E2*O?f>-Ei;h;rJjAk z?;je+TLwIM2$_4(Yr04TCZzD9w@N3U2XF>Oqk$5umI8!@U`HGtnm8QF>!w5w94zMf z7sM@CK9=jV=4`=X)`}fn= zPxma}23QYMD%$5`$6g`=voYc+)a%Yj4SwsG1yQS`JOA|bjanDrau!zXTZqdXb)kV0 z&IoyJrZ7XD^>yfi)>Bt|e~}qRHS$Tx@ioL&$f=H?o1ebP=7sFFvx7DGXcZ=s086HT zu(EHp@?4j-qaLS*Mgo2{E3P;(BJ-cm9hn zy+Qvb@TO$s<;qb)Ubp&<__r2QVXf-h!@NOhU8MF30AVifuPNVC&V_w@oG+Ej$pJT(=|8N;&6rkkPl4?eGb(|tX8bR3O%gJ`LIX^mbt7b>M zzx?8#*Jn?dAEVYF{|B`*dJz%!M_@8F*vokDw804vP%n->ku-l>E|Cs-3{pP|-Tx8B zyRkQYijS8^17W^IBH1YJ9Yn(!?gjapGWgf$lg?ZVxs~p?v;!G5&;IX5(<$Xo<I;^ zK!g~}=QcE7e|L5hHM(AOHSQ}RPP@gsO~Zsk$m2DF3&a$Wqz>mN?>(1VCP(IgM=~O- zXAx_YLcc*xA-8=t0ZIG>*NDNf9>c#Nd1?M|a6E__GH7931U zA0Olojkg(?e|_t#Fq7o97b?5(>C+QZQ2J4z#mkhV5iu}O{WO3uK}5rjlFx&3ylcs7 zi2qw4cig*bdCd*ML>0XEW1TSLkNg!t+Y$;my&=PYHNhCy95#db{;ur2#A1jhw-;OZ z&ZGFZ{>#~8Jj+>Y_GL$}-R1m1Ty6gJQjH%Pu>xZ^8dTf-+!z?&ee)VmvFjHSbH^fr z;(!_;a_1qys_`skBPLruKCdUV-(`p& zHogZ~;KF`3^w}0bxwGyorM?8g#2t+M-lMl3f}RDBei05A2B)e+^Sh%)T;hMhOlRXHa(y|s zfLwB7ONb<}_lfMjfi#VVR^yI4r!5q+ZQjpvo*G^aTwA*F7HY9}w_{zvLQES;WMB>3 z0&n*lUxF|3M$r6rij^jt&pb)2Ma3!6wu+qUEZciUqdV(PQ5@cz2(7qc%Kw6V%4^qb zqn77?2rOTvj>9T_*6rUNbZ%?_cuc>6Ja@jT;I)q9$;Z~8m zm$b9Y&1Lz(qy>s*Cl`45oq*npK%_BQv$Sfzo z&}f$eEkhRHzkXG}P2IQnP@%I1K?Eqj@E>9EdKdk-0Z*l=V=~ln6L8f21;v|vcquDj z0gkgSHO^uuTRKfX6IbN-&=Y}>lfV)Wq`aLUzoJ0~kg|f6pN_C$^iU>mZ;=kK)n=c##bxi zjdE5N^zqaw5?Gt>HdhBL3|N-M7?EZ_x4{|$N&5ma6H_Fjm?Ab$chs2A6Ff%f6PtV{ z4LF23r0?3b>I%>Ziv0IrVK}M*k>t>^HJtB;2ncC z@q-Taj0VE?wEyIWXl({HDQd0l>1c-TkC_G44mu@-zR;Bhr)u3v;#1m7-fBIE2GhlI z%5X`!i4g&)G9xaebQ`ZAVS_`f2C%*O>|H->RFDKGz@|-^UI@|&h&a8^{Ff&U4ez)_ z#U9-!)!2ot8XJZ3{*R37lI{vfomBNei;K$davq^pLB2(N@jH!*O37k_&6YI`=mw(_ zBzI!b(k3tzhD|;vwOk@CH@1r2&Vnr~OkwFP(~}mTTxJmQRDjxaf;3YImqG+(W!e(^ z#f|Hf)%J;eW_d%hXie*U!e${wRH=eP)j2;n3h0HiD8J^R2bWZ+RDGO0CC~E*D)!@? zn(Z>(=p^xe8hIfhvJVD)At2RPbgYtWD8La<-P?gB8zX>8Emtn$`l@RDC>llSeBJhq zzM>$N30OG=fq{q=JfVJ1BgA6$gp<4;!g+Lb&usM_N&>I3wxW*^NF7}PSWb?T3EVTu zzz{A!+^Raq0J;4I0fmrz=ANW%4rEIaD-zIw(D@wN>qEOVLS$dyP9cXw>d`>ONdYiZ zWal@K!u@($ZHrEP;;P1wqSTKO`FKY(mgt~0U^%FHlads^o}fa4^_lzyNlHf+HUXRd z19N{%l$z#&H=u!at%JeAYC@;0PIW^E1ESTIDD(e`GHt0Or6D*+iia91i>{N|pH>6n zWm3^u_$HCjXAUVKijICKZC^oz{#c0gfDoBXzaL!m&eHe+pQ6g-Y8LcF))XnBwjHTN z1r;pOrKo$odn_|~J4~Gb&L0Exf{Kdi&+{-p0%!cDvKQI-LK@Yyhr^LMG@vzjVpMH5 zajpq)%Ykv8!rgXsOt3mI*}b*}8vf`;zMN)`id>deK=*oPOCGuiw!wr(W*YhCuOJ(& z=7-^Xfr2Ap=lN7>*1v|Y`-q5T6m{AN*e2+?z_N~{o2LX)do@*d$-mzy*7}d>EG+7B zKjP5h)}b+g9-nqc-HD7~z}MAmM`TKPW0N(WoG_(0qPJOWA<(vIPY@I~ z;fS4Fq^xZgi6%ePB#?X|^;e!5rhD~$*hE6}rNPi|y~pCij$dBFoZF*7KG6HAmd6|w zMVQ>-@tOH51DimU03tu80G$L%ed7ue8so&7EL{O%Pi_H4Jp|wh&1@*3PECaY4~7#u zGoer^G+gXiT7*!$b+xQ|pt<$z!;Uturg@!$bd>-Xe;h|7RT`X^MvM}@8(T2Sy7ka{ zwnl_gkR}=EBlPe2Ah7KodE;lgl7tP*ay%n+y^#)!54j5aNubqZ^AB!{+VjMFy>aeoyi_z~#` z`$GWS6xfqNzvw!jNRe~~>z0WMO)`N94)FSWanQ{o;Wi;3Hv*Zqby%YP4^HnQ2bo)gFBv=)xq}O_ zZ)6G!j#i)%U@GwdK{QKHsTN=%Akm??E(q-HBV)&6*mohrF2K4gm`Tn z)Tj?~JGLX012S(5_Fm8UVm9a(`RJhAIZw1NN#EH>-&lzfVI#} z0^LQ(>)3nf2J-nG%pl0hiZXS0F+d-!)rP6*Nr}q>>-1ShG4n47nZMG^bq=Q-d;{EI zVnGDc9o~b0Xe3Q?T>vW^TMk;Gg0?O%gJnNM#G^QckCDp0^l@IC);DrN>V3;}dyF{= zXQHY!%v*%xq!|Hf46PrqRek}l-bR-|6HX^EZAw68zF=Ts2`5nwc?3uE)pIZ^Wv+jY z=2V&@9BPIFjL_v@J)#BTGIYQqy12~o)@AA@TCmku|G=WXYd=f(nGYjH^!yohm* zkO*8WK!nc20+5rBSW-dwym1Hsx6`jHU8)fqm$AUl(hk3X7qodow$=Cw;#agsUme>6 zMvUtnYRt^O0rt*>g!I%YAmjzQ*EZ?ileR9NQZogrNGcf;o->CQO)L%;~@`MH^a203}d0lsZ)w?1TeTPrig5ES0th6p3jc7&A1 z3`F(8#BKDF83%3I_Eg_mpI>3Gtk)z}Qv;wegML1oHQoZhUZVZ~JKHg$Y;O^N(yn-iD- z_)uHHH?giYBCHtDF_|%o*)QQF0#0OxQ0ag8=Mu2wSclyk09K-LzP+YRkfJP*W8t~r zv;wT58}xT3uuin#AP#BGdkKBr53)3J&r zWW9eDB;!}dxv=p>ihFY^hbstARrUv@_u|YruV+xP`cV17Q|lyHU28~~2}J)=o6d-0 zaKP_)#8lJ+QBVDQiS&AzCdti-S~b=Zd1CNe-3cAX8aNunD9?gCQk&57Y+T-A+h@k= z+Xgj`SojKtOtPl8)-235QM#?u)d5<=5%Fs(6NRVZOcH$$%He|(k97=t-$I}dE$xy zseh-Wo~A>cZ3#M{S-o$=zP$%jl$!jVi1hC_dfoCHe8 zBf$(*!R2~bM-R-6=95cn8@uO44K75>e8FXU<4JuS;0jmM&Is^I_5S^MfgX;CVS4v) z`{sUsg!)M}yBv4JYt~F#M?rce2*KSM210=XiRMWHjFr<8f#izrX&wHnYw>-*)6s6+ z6SNs>!ywpU$1yp{2V6xVS|+JD`XWw?^a8PnkV-ju?w^`aga;46NawrJzL2@&pT+53 zr`^s1rg)tAxe!Gt8mY8dxLwLC1q>M81#Vb5M-Ws;`#3+Wr$FQ=xJXgJVy!2{e28U? zRgfUYR~Lwl7x9=F#*@{Z%Y;CViz18yG$h9Obvy+V896CFZK$nb>F?s`%@C66ygP{u zt}oF>mWy=Pd)E0vVqz^;g-(%c(41x!j)~`b`oG?Pqt09oABr8jABOCZjL;Vw^@O>Y zha>%`2;t-mt)!g6(^&hrIXI5OrF0Wc+7w<~K}0O`nQW&Din|vM0lYzwks^;evB<<- zwy;#{wJGYP(a|G8!lc>_tcnjK64)yAVENuM|NBL{%B@*1L&YoODP{NOwJOs5;wywv z>E6A2jMY3DTLT`@K}owNHsvwW0G62~b$!R4&Lg+k0vV70N z*-fdp@-p(X&Y@j>EN4Q1W|+w4W={CBQi8gmHjmyp0<|T^uBMF#&NA}=gAz9vWzwDF zhsac5Zy>^+=A;ya45o35YDRaFzYa!bEoiuvTyBE;i7drF^$ISS5ykN}z=V z%wimbxVy1my@0Fy4;){P0JJQmVGu~VCghMK%d_yi+E8G8*&mk%=b|@f;#5|a^ly42 zW;is%whtfckQnabiu7svdZBt0vMRO(s9zb%;zC8}V>VHRVvYT|UDEf}9r*>KNB7M< z6h(ocNn7GE621>44GwBdTc#2PQga>`E~I<6s=DLGHf{pfg)Fa8^#9b+uZnil9$0(- zJSHl>P3?E$@!0o~Z65kiF?t>pB{@Zg89Dcd!BRKcjNMv8VmRTkp%#pt1rNexI#eL?KtmJOHB&Sw*&?8E;H0PJ1Ii-Hgy$ z6GOFpUNzhCn_LaBci1%T(UaQzsY6@=18WXD^$18x?;L6+Ar#yi+3)Vh zMGiQdF7%TUM$@V#ytAN!6+W|}y?a8rP9z_PTJm5je1Eee@7A7~VU)dbVHSihCqBMI z^V5>?0*PM$ywa4t^M)MYo`olW51U>rn+!RZA$I7s#%^>|hcWq9A2 zytkDHiGPM53HAY1G5qnk?_(a&eApgK->dJiF5)<5YKACYJ0L{MLdYBv9ZfhQu1}Hp z87%#=A_uF(wc$6~?-P3_l#O>jwQ7VF#I~rZtpLAM6;z5_H1No%Z#nf#XQg*DE4E&R z#2*?iRC_l>BQn!X9SD7MXMWL#!2f{S^x(gf?g7`+ET5^FfvZ!HW>O+6CZI*5f#qmPPEvvs%BAXb1+^aR{^uS;dn@I$Lz~utyL;W12kdqry zdix+(anBeNXpSCj)9wXPfi4{g-M%FrnDfF2y%VO1tZyQSeg20jsJLIp%EhEXOFN$; zH)+7@=5fSrfTo%xSj*`PeFM$z34J-*AI3Ez6iLP50CzOHH~aF+^caZV2+wIW0&t=r zU%mvK%4i=S&RD7p;1=acL$S&O`o0to#NKPQMJSNy*49*fiYIyJij3g6y+~#Zs-m%r zcN6e?C=tjZs{(EuASjG2Rj5P8LN0=X8tTD4vLgS-S4OI~! z%W5AJ>vpbERvPM$4>8Fu_aF>ZYVf!E!EVqF>NjrnfaxY4Xu2T?_Yx>$*?)7RU9v1B zbyH|j0fP`6ewY~5rhm8!%>x;Hn#B)Mp~hV-?fV9x*j@3g{EW%aLi*~ex>=ZBXZ;5{ z5UErfU83EILxcnH_2kPCni;6=>KpSg-IX!~Am%`@I&lq^rw#Ukp#wsHK^dutQwywc zoqLCNlyMC3J9oh>_b8&pf95!58}z8rG2R8PlCGM@=scM=VVtK{IxzIx#2QS-&IGIb zep5@C?a=fvKsbsGZmc`|pM#3fkfBd40`Ep#Ck(*hSzI_BxpwhDvB;5Ja67Wif9rQf zdGfH%{yuEMq;zpvViqUhzeFDp0v)bVv~}`C!^i6NB*`BCfhB^5N9u7v+fiVDf_h>{ zo1W2GkRS9r;fJ1h%7@%GU6nxwS>61lr&sTE4|ad^`)qol2rE3@Bap8fS}GtM8ok#q zJ}s>*fP+@ot4OT-UGP*V!J1QMB@)y?{NNp+*6DMQ5_$(2Ye<5L%NygyA7eZMliR+N zk7&7Lc~FU?{~O)Hqy$tcmi9#U-!oj;e0aN@IdW1{s97F*^%!|WwCrg2M_a&N$?09k8$D-5k`8xGp z#hp~4Pb}H|Ty&lBhHxs`Dj@%3%LD`6y$6OBD0jdMZmXhkACUf*YWZACrW?5GmS#MJB3DxdvmGDzx*A(i|e`5#b9i&(GTAV@@>8NCK1dDJ?I~0aO(|^ zS}VXvPnRma%1>At$ZSrV(~l?P5J7uP2|%=HedKgIvujvnf7{mik!H$7QBbXJ|F5MQ z!czRm`wup#+ZIj**jnJBy#&-HUG2-kI0J#s0uyNt%A4lv5sENCraF2|x#tNdBcs1% z&h8Q|3n-n0v(r_Kd6gw2GOvveE8;Fv9TH=DQRZp*Yxjaarc2&M142 ztm9t+A(ds`f>DyO(b1am-P}5q&5pb5-ZW0tILqtU%_y)Eu}u#VH-7wj=3({vFH^no zcCp4gxwZjgjtCE(KcVu}AE60_*0qp7N)-D^!-{9|`fcUSzR0gfKOrC3wq~tgAD?kY z@RJ;g=@!*uHnLa4z(`N^U`^S?tr5k~m{7k=Q=^ApAKUoJ_n?{KnX83TQf@5^aV4FZ z3o%vURZ;(3cifo*Fij~cIVTwISQ*-$Uf#op%Ep(u8LK8R=>FjIk70R9a=~NLJ$lo0 z@w^*nR#Yf^kFJq+-tQ)$B?R+%?sI#31Z!_D^;cY~6}kj4xhC#wESlv&L_G} zN!RD|o>!yn>U{P>^EKtHI=v%wHcp#yd=d*2Xv}08gh*)Jy}lk`XW?11GL-MNG$3^1 z!P37PVf5_Fg=57GC`MrdrP<56<&avXWg1_hsxwlso*@j+C{`EVtM+?G6BL=*^XP`@ zVw@Y9`lTn$Yl3n&$mx7;JP+yFQY>KVd2jmJBDP#HN3Nq+tT9^H033w*Pm;et3eOKT z1qiam4NGK~9lo@Np63K7xK$`_7^c-m|HNgFFx(h zf7Rgpx;esk=iTNj&4Pew0neQ3>VZ6;Go!hcN>Nj7qEal|q>g{;UW)4amTBvC0`Ny| zQKHLoLR34LtnNe@$>)pjNP<4X`eDnaM~Yc#nAJ~5i%!1nsDVm@0J)28S7??91Rm%K z0NoIx-s*z0Jgd@5Z4`;(o+P;UX3vPZJBgZCrc6^?Rs|u$ z{=))44d8!44G!4;M$Dm1^4c-VzB>lb=IC|Eb^!hQNpI^CQ!S;6gii1Q{BQ?qh=^mu z`F6;KKcOvN4RUkEKAP<=!3Ke!F_%2OzS^5GqUb@^)Y*~#D`0KYjLAhtC6VjvLx*GI z*TDZI3qZ44J(M>1+%yfuqRF8DZ!6YYjEyYzPtaXKpa5I!m38q$Awj?0hACLxcfG$L zGH^}*Syl?fuE|&2PsseaXT%mD>|1v@RQEIK=HVmoBtVA!9)UGvwH!MC4~v{FX6WcR z<%XWJwq8ACwhA)ho5WMDv=@xKgh!!~HQZlTqBGYoXZ3>704Bc7zH#++Q}pil9awaE zIV0yJPJ=iES*3V~oZ8J+kv>|^xr|3%Z+(R=RkG^|o2;Suak`?!7yp7{Jtp}w^q#V% zTdPyIMC9T7l1~}yprP=ap*7oo7K3g&pLA8yy%wgl;SFy;q;Y%-`qwMpj{oG_Uw=XW zh#WrNVB7 z8oJmo#w^R$y7*3k@%U}p!FVIgJ@16R$jfEH#NiOs|KatmPTM$jIHb+cXXoV_E_hyc zH9Ozz#OX@!`W61WESvvZW~v)9@W4vl?xH@`ZGPXg1wsX0?wz@x>TemcE?yp<`I6i; zD)iU@Pxgmkz{6H+eY5GJL{x57wTr^?D+|_5E@S`*CMNI?<NU(;7T9pMjRy(uB%#a`=>3bC&U{1!X8f^gz)g;&>cse#q2 zm$MQ$foeOuVWd!I!Q;jAVSBQ*J+lY~r}OCQk=!xd)t4?>-PcYug@LH`dIPMHs`oSJ zbw!h0-BYT&#zJvVzPJ2*iTP7;cHZY~Fv;(Po@5VDscap_u@5*T2xm)&lPUsn%KCf3 z^ujBB!xajr%C}L_C?MsjWTXBRbQv~ulsH6LEB%3b(frjnp1p|CcAbZn0mbN5_oX6b z+7UtZA2oi+5oi!eCqXh=xHv3nJ|dB)H;28c%ThBOLt(G zJ)2*BFSXR0YyD|#*Nc=`58xUgg!wMg+&UqP-;!#{19cC1mGIH zMTxLG-#(iryr-i8T`g+()P^%0=&#uSfg!vaiBck;sbLltKKh~b;a}Yrm8J1R&2MgZ z=EhDi`3q*n$2dcyoFzHiO+)YiS^%ojM0cZz#opZFNv(!!%VFvg`-aywhb#ZKMxI7Xk$qRyJ)r%033eZE z$p1b!5-l-9CiI~HD7^vA&mELh9Ok`{2sO7kqbk^(Hy*Jwv&5w*RUo3NVhxl+V63VH z>o#y~yDtitP>R4xAG{YVx6&Ba_;D*E$=sj*JBj1>y1wv5?=4hU#fH}A`x;?o@8&5+ zqpfvRy7Q*;zU`LkJOwY?`4}(NC0sBQ)Uw*R{ctyB&8W2m2aT@7${gQLOFAEr@>2*+ zYihrb&BtEX5)0{d;0rlJi|B9lxuplX73lj`_o7Dlz}l51zca_!r9(5%@q7hf-$D=` z4*VgkvvKV5=8XYdMh(CO)V%w(^^&tn{++<8@$#MqGzh%JgKNzKOUo)K$cXUM{yjSM~axtU?{WC@k#YYMr14+ZaxtG%|&T4|Nh zD;IlTJbzZBHln8meF2(zHXbAx3AjTW#6|Bs{an=9=HpROEN_F_aA?is%&o3X zM%}L1L*ZwWNf~3_YM@YR@Bxe_Vq>$+Ppc0NbVr1T9vF?1CS$?(J_7oX8cfZa+dm%CIvpHE^+}*80n_9j`e@)BC&&AC z3Ce0|n&qgM;_HD9k84zwbr_&rCt_?b)z<`|0H91HWuw)aY^6G2$UXepG%hdOL%X z?A5e^guvOC#_aJ%5S{O5yuc(PzUqmnl}ejnIM;12y4M(WuAnAzhkXY*-&H-!7ItV6 zHzYeB2i>?Yte68-y|YH*zW*KQKiGJe_QmNL-3Uy%7pJywJs85}t=MK7VzD>$nbqH5 zU*%$`19B6EdzM z3KMTNNV+#iiV)H1UG*YWsQ{)fLxVQ+WYlA3%@#vQ`n>9k2HP!E{JJ0Afu&6ks*x2+ z8bc$(0h(`iv@40mT<-@i!ApzD&85DIEsWpFy_%Kxc-oP5iQm3?VDMA z>PdGQ%?~jVdP4)F9CbJC$HW5(gH?Q@9x#Zo^DIF4n>L5>tkW}>;0Yec;oO&79?thzb&ebH z5 z{qtDFKX7rw;aZRFY96?Z4~@^O=D_MfMoD!d_s^~dy;McQ8|J*tk44u;jWFWkveM`T zmBUTYF-l@{3O~fM&aIY1x!@uJ(Oz@@Cg4gdN%qu$&1jZ@|zFF)q&jwGxs zS!j*rY2kOY4^^zbeps~$ViQGq`a|fE#fwix*ES zLw86r%SV@3#!BZfB!oA}1Izb_`9y%EL>HkIM3%ExH(HL@(;q*5q|!B7;X@C3mTxOp zhyZt>Iq%1F!>TH|Zuj`?l0L-&f{2ax$VPlU_Rwgfvjk9?Lw*#Tm$xKD(cE;=tjT=~E=zl3 zncE0L?eZFHGmF1+!xQCezTqg}SC4(U2{42ZPehyGcIBT!zx-OTqKXLg`vp;IQJl&2 zg^^V29*xwa3E^lFe6O(!o;ytX`MqRBbIlD6-zuDJ`M^0g)b%s4zdV%F5z^&>KK>x- zoVA2|=y8lVv+Pj2DFh~sSUCH3pHv$eM(@yZ$u|$gW=(p&#%vpnMs(UITCKgi{^EB#t*{Nu6q^5KEy3LeNco$`dY`i8KWSuH)bN33 zczUp>VrG}?P`^hn$X$KyF&%I;@=Uxy_-%S%VyD70QMOch>yG6|&4uq*j5Ez|K7+(Q zr|0X>4=-ZRZrtK6bq&&aEI&A^tVBZuEz-m@-zjOwm|QNb&T>v6JAi4K$$b=62G zgj?s#_K0<6`_O~~S6c6GpvS3|D=kvf;*gE9$U0Amzj=$hO*5~wRd;nK~s3NwPrK^qFi!syte;l2AJk$OA z$3HVn4wK^B+%{8`QwN7`<}jx2oNhUn?oMcmx*axz#u!4m*PKf=n{rq>&_O84B%4Da zbd%#4Ax?Zp63mvPXCdCIy+&j%K@-^-S8!ksJ))i=zgsAbu z`9$<0PP3PWwz3)eH?M6Zx)YL18rPOKbUYf1oO}x4R573a3Z(U!LkG% z;_#BzC=)!5^7OcYxq4@Cs@SAsEIFO2PRtKG%do^nvC1y3U@gUZkS;IkhyTkeh-Z)) z6i=cod1`8l;`w6ihAR>e=EGFuEVo8aUB30{SOGzQfogH#!PVvr5kc9nIn9GBe*A}g zx+1FKTvcE=#>Lz5;jP=6>*cDch2c0A<-4u2bMf@f8-4Aw(VoFkf_V^GbCBe^kWA#r-71>r@|3#|8cFkmxxGxMR=Z06QEIDr#dnhFd0m2l z(!@U7*KWSv4kzGA<^ngSdY(S;FV1iCeQpKG&z^!?lS$Ww5A!P&-IykvEujc0m<`Fhd zdi7&r$wIC0@ve1Q=x<`M@oh-JV5d~*J%Ge$KVkpZL4o{E1_yUQgUmctyDc&L~ z!#v=9>2WSD6rzO5ZLERy9S*pjiqB?LjYAT~ZO*z$*EBREF)3h7H3k_aBSLCpA~ZMV zoX$fnw`x{I;-X$>L4M8;#dbEgmHBwq7r04oU2P#&f#My#3Ec~7$C1IiELc!gQbn>fUOR@pWF}Q zo{d|ZtRa!emC74$ngmSY9GW=)h@q%4t}xFAs4CsS2l7@P?VR%#zukNRB+^rDpMUDE zqI#WU^K|LnzDpZ*%24NrvF(uam&EQ#r>#S|VsvG(UeNfbru7C}r1e2v>}9P=q*)so z@Qq={}vrWD>N`hcH8nINYvh8*5twR4fkb`|N+O!F9 zqnM(Tb-nMD81ZjCmd0|!duvNDSN84xs$-SAYc@2 zhb@Xaisrvo`F7SiOXD_liw&0z;~DJwM3&X--0gHyUBukiYak(txveEF+fP>m>oQj) z!!N_6lz?m5)$FWjEuyVAfu{hVZlEk-+vW(8R7+{_Pwl{1d(3pqWYjI{s7NxQRHY`jt=74Xm>>{6~f6s z%*GQ5(p_AXzz2-;7E5~2cUtjwA#JIK)uj2{=GmlS@(y+ zm9_6=Te8n0sU-tDIiKETbYhcqxV@ffKIT*agOMllQO7$p5IA>h7GBqxi`LQDH@KNn zWD#upAw_bl9IX`JI&FPuk|4(ud}2~@s)g<@gBXiN`_@g@jNs(53p8kM{JUkY~<3_@aw{U&jX#o zd^4;8ycTS~3?Cr>x_DGRj@5Nv_F~vq>NSBY?55h~3kdI;E)^j*>GyL{+Mq-t>B=b3 z`fl>@wwF!G3+SLGVdWJlhk^F-31dbSv)|gPNs8fXae6oOgI8Tpt2Ie@j{qrK1CzvR z2GH0fL_p>Ob)j z%ui|w0`l`=M7;Qcj}jNDLd;QrK<|`{PNp8Y)q^qH@|@>l4^+fglY}LU#V>?_+^Kok*ZaP8CLe2y7S+}7{dt*cdThBPpC#x!;Tl}$eh}Pw6V-uB`QO$ z64S)Ir#7f5#^t91A6rhw3YODxzdDpXtX73LCwFrW6V)nN_FBY^xqHxMO_Dabu2r{D z+5E1el#Av=_Uwbd9CyHgiZ~kPmhk9Q(gqc<2V*a8%)+Kt;+XDe7`N5Psz5z^d*AFg zxTgBut#i8f9n>6Tzcsc6E;UX7t!T;o+gaFp&(d1>hHg_jd!Ny_CC$Nfso;ntwQHEF zNk=n+?T8G&rHKpl6}yTD3FqNtdUUkA(&mWKkjuiFhXDb0)Q8+R2k6Pl^6(}xPX|i3 z(8bzxJ_jumXHO$Zq0lMZkX?%E4)+ci?@%|ac^l`$D1v!c^FkA4Ip$Jy9k17NXjKH zyNE}!$Nz?42iTn*U_gMYTTOcas71mj3{xQw9uRiOGAH<0C;|ppNlF=zr;5!BJ$f#XTh9fgJaLC3+E^uDcDld63 z>17$ax(%&p<2tHToz}9UcS+Wq36f0MMTR#$7A{s2tzFIo!j+j|_S+=e#-Tk(10LVK zN_NP5^sx+(oN2%mVKjGV_tBU)m{5u=bj;cU?WbaPK2Jx>KvfmB8mcSQi08xA-e-U9 zqp8q-0xdN;r`67h4vvkG<}>=q0%8wUw+9RE&f~#GpQu$+1h~@I=hyvq&h+&u4-}Lv zt-tfw0@nwm1oF5GtPMdD5h*&&1xT;-{Q9q_Z^Jx~Wl}sA8oeZgJQ@si6<98+jo5ne za#66v-EC6I(nC`Oh-Ve!Tcx2M0O4dmZJS~u?J)QxQ@v`Y4~$2BHR(uZFx5!~=vd4n z$gOfeLL(MvNLurQWJx$-YV>y1o1^+@;`2TCq7Y`H)vP}CY?zD`|89FQ@aVt+s>Y9p z)$mK+AIl`+C!NhJKlczB}#OpurxO;AI zi1qev>wTz?LNn71X;Jx7`qiw$P{esfm)2Zmqa2K_w7L3~P?>%VDM|x~!S61}TzE%Z ziQ;$AG|cwaesf!n+R!^|DqFaIibUE+JP4QCf^#%jM6IMx9&I*^KseiibUM zH%5+#UPw(Z;cIMH44Er-fF!jE+!#uA@O9U4veFvXz&CnWW19nJ1QlJ zw20LalYN+~!ehQnf7Qu4D0)3E2?wJ+wzxW(9t~n(U?%9px5`!Em{*KiCyyxE6KTRp zhINj0vZfZCfol`Q>DjKoBN@mvww0{{U7TI|wu@$ZRw=)rQeA#PTVMwJ!J7LH+rR98 z8cyJ)EZUJ4@>i8%>JoX+mZ@(>SUof89018=yHFq>a%BJ?=ujM;7zKMB=Z(P!r`3pN z`cyce6A+HK`hP*(YX3E4*CK+me5Z^ka#9`7+{LK{57$r%^($J$JAFqRxM}#ao0r*p z(oGl?#>g$M{2brrM?nV-^L18GO6UcVz>h|K==7`NP2C==LTa?)m5_b`Fm`}Hwu^+_ zP3+V{c9~l10_x~O>J>pSP|35exECZu?RMB$cZGE$^3hO#2YEqW=fGD)<%;_}VTVG& zqc)07vMX0gvuX~m;Cs|cbQ*{SbD2kIKf`+&Rj_=kiy+GA?YU>KwW z^9WP%O}kS%I$~w#=EENBQlRH zbkbw9p<#e+hc001!{Yr57?n2if0wk;cY6vz0k^$ z++i2owb?TfB~~wos-63V>E;oIje|{$|4Q3UUC!=Ac&i23dDPF}BH8#q$qzxUOF&ou zmY-}@o1~Y>B<44unisfe#Uf}QAUlN7@BMwzD;C!(t%Hbf1H|C;mjYqc2jD(PaKTgN z(pqMVXRR)+7tUG;y8z|mUAkd=_>AK&a$t~}XL`YVYmkN@H>5$#G`4ABq9KbV)vfF~ z22!T66*0e|r&O*U#Ra*g=HMcU@bZ^cV;wsr?|2)XZsl8zsM^rk4})@W69o@udKu)j z*nU|+^hQ`!wGC)bI<%W2Xx5G--iWj!-onGS^Lk*ZnXm}5%;NQ9W4lVh?#3)cm8= zA1MbMg~L_;=rkwyycU|*tZ+VGw7;JO)k%Vl)vgjDf}pUrv#t`GpNrDoTg1<}pitvL zR-pU%gfpSlMYE)7F(32oYy!c|IR$tTwqS#X{pyApUG6*Hj3d6;B0BDo+Y{{h%{8yu zJ^Y%m1``%OFv1RE2wam+!7ij8DR_XATo5;yYN&A6X|9lDJkQpp0xaz!qx)&iHBmFY z5Bk_S(W#`#pP}YLaj{R^5seFpdE__SoDaMsavDm4fK2h2yW`b>T==sF^WfycO+9 zqfg5KXftIK1OzGB+bUOK4DdAwSE4Mz3MfFC|1>-lQhmk2&XKjpS+@DaQmh)eFIz^E}g050}PlOySoT- zRL)|0Soe;P3)OSQg=ZB+mAI)kW!kJF0<4aF$)I|SG!Fb{m=a`!e0<_^*k-`$k!can zuzeFxcIN%7A(o*1_DGJnPy}b7Fz>cg+E2v&gAzY#`_#kpuCO4kx=ON5wu#cXvc_HU zbQu4&jLO#vsv!_jv_DN+VC5lf8XyIF<+81A!%gq=7RWAkbRv@p+xo2A6xP@z9Heb8 z4Ly?t5iyFZYaY$FxgcgXBJB5Mm9*E}LvwmWDUq=>$ zyc#~~tg3O5r066MzJLH2p6_Z7Yb=Qj?kg7<@Ib|#Y76{;@Qg`&au(ZJs0`IFs59B; zIXxW}Bv(H;S43!PS`CY*yJZ?P?9aw;_CjYvvN#xN3reS2+CAeW9vnayM6E9|RVUYL z3{2vgn+m(n_0vOb#2df^m@NCViLco?HsgE&0=5@0N2q;m%0yEKuK`K4^92JV~=5k1QAwEQjR+=((D+qV+I%s#lE$Hx7swK@v)Eiw`Y-EJ{5g2>|!5PBjTkZPMmA zWcrR%(Ggp@`Q^u){DB`2^Oj7I8+!z^jbOP9Z$-QBXtPer2xK%}X=WCrqO!}xIM_K9i@SkWO;i|jevRPl< zH0&@;V{(2xvDI9DZpEGRd6{&kuZ*K2qlJ#O>Zf$w81|0D-~e^{tt(_|XX>O_J$3J{ zt()VE#z_!*@bpCA^t?T3*e?Y7cMg;sYcI}(~R@oUp z>GeOO0$&YwY!~MR*(gv+>-~HmvN|5rU|n;C_HUC4Pi+p}HcUHWU1U>a`%uJ$%{w8~ zb6yF%Y(hf9+4{Tr8N8~9ySW=#-hjp47X3Vj-Rs*}A-T4LWoW_xBVXJcn>b{b! zl_l)>GyBrX|8*E4yoc4OQbxn){4ZEJG2uUe>T18Q8fvKyuZEcu_5Qygo531&*%lO^ zEze9rkEnSs8qsMp@u!HTd-^i;3F{lu8 z*_yVMvpc=e@u_iqVpH?xG2{bR2Q^>2^W@boq~Oy}hez!K>0^e=cUH)qy$>07>wko@Y#JM<&HZ2W+G8HPK@=U#3R;>2h8t<2Re@SUtZ{v_Ofk+SmYVK7B)9T9{Yx9o{*= zp0k32gjh3n+Oc!kbG82mQ%wQCvefLL;N^0e{#j z?>fx2@^igDY;tNPB0sZS>D3?i?-;?D{)iBO`F(mg(+F#!nv&S#BN$IDJ!Is(OVURy z)Mg>BXlOUyiEp97CezNw>3x!Zmtn{Ly<*<#DF2FY=+97?T&E@q|00z&_UA`nbB3=} zK^b(#B2Rx9d{oSbV>!YGPeOI9B6-?=r=`sL&wJE3wxiRJ-GSf&;LQAON%3HGVb!} zBSTT6jKLgl(*6%e$8HO<8c&Eh+kZcKYWS+BMNwZJnj;oD7~j5I=$k3xtHLhd59*Is z8f0ua!_jYPFHL$S@Dhen$acMOCsUc zPTVh%Yu=+{yi;X=bn=8$=!yP+S@oA#rY0{Q#M~ABcWBb16+3F0TBrX0t4h}Ky@lYy zJ6ZB5zFIFwP7lUf9eJPB^}wL-<3HRZnml~U?+w@y&1=!^#=X9H$slV=Cs?KyFQoK{T_<6C~^#T`&itcC~llG}=+-6pQ3g@x7iul$0JKpQX5 zODGn_^3QLdcp0vK`q4NhS%2zEdc8Wc;=iukzNvCmKDDM;On#O(_( z)TLEtn8t#rXY0g-I($W6c<9!b-)~=M6FdLOEuAUmXKIonVF?9fQ6dOvU;C}4nEu>je$-2H z8uY7AW3Ymdm3`gZ5ajhYbHPO=Q=Lhg&DlV6htp2tS&;N6+43tTS)ukjv8FU;cS#xx;zpbb>9Z&a0}G9G|+{`)$zV1WU*^j1MG_-Nc+Iwp4PCJtd zl{#|-U3W|>%yXExO`jK5j3b(TOc?zDLvX6>Plb=U&1XJ+DE3OZx8l_wONhF^6jj|R z3ch+M zpkNVRQsyqV1KNVPK{ps+(JA%K^uAQ-MY!9BM*TFLIrFf&9lh<_TWHr<8-?`x%Ynws zuM$Ka{_4Im7x{XlGPygK08uI{2LH^I=Gmobfrhzv)dUc$KhEAb*pcu4w)Tc- z7*qYWT?v1;Zx>}oqs z&HA=~Lv8k9b3gUfM~|jGVusvbiT*eNvut=0`|IK&en9i}ZSThtD z9M6f%WandlRL{M!MSO13Oq*RQdtZC;7nF$YC1Gz2?msqv{!-fUO1;nvwtDkO!-dU3 zb7WrB>e*k=|DGQ{cO?g#iQiz$Ej~^)NC2GsFm4I@Zb7pN|dwB^CmAB z*a|LK{!fywF0rZq&D&|^OH}$lCFPBCUACAcY*u26?~(s8QnD1KV+hs0OQLIg5ScHgEu+zjV<&eF z)3b1Y*PQ>0zf7p(f+R`KsS8H969Xw3sTrLw8p0LT4E7fU3vfJJbNC7Eb5)G9 z`)tFOoy{-2sy_VE_~DE4*9Z1*t7@W;=Wy4AsjqhaLH|cxnRFzcYkkY}w)=Ho*NvXl z`A}WW$cRIkqz03+0SL6Z^NGJxBU%XMK}W~t9D<}ocRrqa*1L^J z>*?Qi=dz9oQZB-M8()|@aZ5_inR+Ap*+CD{?1>&7Eft<&7tDi$HNXiqh>~$fPk26Z zood~xul%=YFL{ByKn#hA_F@K~I-bfcHjdAjVK6;H+%CN~vMXo$X58qj|v8}bCvmHSO2u!i{(%1J_Kx#z8@oSJcgd{`Ve-TFoIBv1X;? zrz)4`z$&Ywvi&}ZefL(awp!=E6ux>>5%B%y z^OlUZGSr0r^1BrCB1RGCV_MTI`r|0a+mr40|NiLl$r^X;EHR%ybxb_|)BffcwpL{z z7_TRJWsYu(s0g)M7IOwnGv}@mEfO8tG>Cn#salG8ckigwd>;*H7Q7vPi!B>IcYNl? z?-u%bNm+XN^9JPjjgp1I$49qEow%=xkpUyFQ!gzmyGeIVbm^faBU|$eOj|4&F8y~Ka!=D(n*eitQH z2UL=i7Q<%+c33T>As z{fNs?)<4&S%G^1V$~boK?2CVh+JqwTD+199*SI5fx^O>O)CB2ih~w^^tbwfb6U( zE;`P6@m$FJo+-&k9<2aRRHDC3va5B3KCk=Vzfy9m>e3GR#7whsbmGu!W3}-e{ExY- zZ;7a9A$taKeJ!fmSwj|-xvAb)>XyeV4)e?z1=?k+BMBXPxRX$jY_qeSGafhc?5{rC ze|g@9_q-&pPvmc5TOT*w_+r0%O^C=BHC#S@W60%Zn{A_DIAO_pGtkxWZ7Bb$))QUT zRQw?OHeT=I@gIMY97FASE@kK0Nf-8iR%>~Y_G##Yvt!!$nS07CqQm!K{oTR{9N+mp zP?$}c{4ral+Fvgj4w@4s(Go{NxbWSk32CdmsfX{Ph*2j_oXbuxXpfFtoMPWL`@`0` zO5sgd78q_Hj{DWsb5rZ`soJJ_K}0YDdPdzjTT4o5@fgwoQ9h}w-}}_Q)+1d8HC5%h zFK_%kflWSCMXSx&npk=mFkylB$C_812;IdfL<+ntD*gycoGFn5zB2^4<=*B+J$_mp zyOwFs*G8bb&3j8cpEK-SPxNV&qz)Cy zw^d)j@y@{FJXY4+Mdxpr9<*zY>W#yCJ3^cYG@*@6<)Gj_(cO%wc-8L<(j=(KZ6QgW z7A{O(dXk^~E&I_`Yh9t782&73=w^;n|L{_d#sfU&;1}mW5Aw)^FL)Uq41Mt-i|87$EgE=i8)3QmJa?#{1K3o5h*4>>Hh7 zOnIz?0}6Sw`xgx@!uo^3?(xvH&c%GQaliP1p4dbM-*d>b&z)*BTs{6eL`sIqx>I0e~=`hz%hV)Pq z25#%bco+Lft9_J_(09AmMUs`L+MR{A-{s%$ns1T2fAL(M>Gp_pujlBInrl{i0XhPV z6?(2bd4N6THL_C6flgw~;j}-M;^)g^lR2Y^*56W6#_shOy`VdM-)8dZ$YzJtSt84f zuktAm{~$s~;?~E<6-To=q1aQvo+A!^A{@YaWLmG>?qj*=#j!lmYd-hJr!UR^JCckN z4m5cir@I^z)>f9OT-l_}9w0h)9lEf6Ur(gLfvQFR*rvX8_p$0D-}f>+z26DO;Z}Lh zWS%igf1-ZZ^4ksX>j( zqPh?CI5wZtQFJQABrnzDhcRPlTt$3V9X(r~Hum(>kvMr`_k^>xUd(&7*?8{*)9RLS z+ax3TPG5XkFpf>csByAef+U6aSij?-6?TeLp!o6y!Dg_4K?ODctI^rw zV&?t7ZuT*DSt@dVL1$7O;y*mbeUR+=q}XhSrchiHoSy&Ko`ZkI_?vUbzP8EX!tK4V zuz4X$FeiSxaG8u4yJH)N?tZo-fqM&2*xydH54GXuW|1P4UQo zwje-%$ppt$?|LfbJ)kPFBed2KQTw9E$Y+N+lH3Ch3HNfx`MY;uFKBUGN@sqBS95s_ zpu#iap8Zc^4@}cip`aqxd$zdxMz(~_cv;C$Xzj#JpS@(6%Z7CrKwa8%x|%&GsR0xB zTe$gP0#_S*oTqaqXT;BPT0VG(3%9p*`R`GXGg`rhOLBVDgF2n5+%BxtN(kBb1dqEuH=9LSjJHu3ZoTV++ z$-rHqb!*mCKHV1g3$pHDHrLq%imea)VOB4Xn4Di$&oLbTL=Q`QhX|V@NPk^G7fX++ zk?R05)B4&gc2)^^L})9IMR>sxL?s%eomOP1{N#2FRIA-c=0EsPl@!Z0oL{JpK%m6J zNp~pr%_wZDZ@#eEh`CV^du@u5_x94Auxk&tZS7CE#uYJ`5&7*mUOiVzMoulj7{^7HB@BWBD+q5OTyygGu*FT+nqY^JiyK9>qz*^_gs&Fg+TFaA%L|S zd$sN;d0|hsVg_xTF;K;Mc+u;-jCCTMeW&uu%clhyJaVh?O04HoebqbW7hnH-a?x_4 zQO#7Rzwj!G?^5J*ZUugvweNO+O?k$xA+v$)OZxGQ0dtC1*gN7FP^jSXh9WmdryEC^ zKB0zb9OdaRCO9@0yHa#GiDy~;KvtN4j$V|pZ->#!A(|HVI}GGGV0`aKOAx+?jFgJ!MHy0_-%&GxaPc-Iv8<8DnKM(GUjK$C?M zj`fCKvjXB2dKt%N&GYHw+Jj-I&7D(9{$4)dU$n=;$nN`yZO;RkTqe0YgMbg~rAC8Jav(-@RTa%~^h@N}EHF`Bk)E;sp5eo^Lh``k7sc(=1VBF=!DUpYr#u4jplc_13 zF^4M1T#*93v_HTSb{6aHsk6gN?P*kwXY@r)y8cfdWOSxofjHV$8O>+pfBnP>9b;*9xTxa^xqH%Mb8xk-$lw-73J|m;eMG|~@@IKx*)s6|f#ppQ z(K`*3^V^9!s*QCjJ4q4jmO+k&p9#M9Hv`z@nyZx05D$Eh_yyjTOLa|1IhcihZ=Wl!3aq0 zm0Fi8X(6admp-rq?#I((5uK@!vk|#{!QQ6#NLi6}yDm?c9wiX{w+(GT>!oIu?CA16 z+O2cKdbgNEOypZ7)0D3w)Vr#t`mBrgnJ^h%X*}jTb&GcRyp$=XrmFCVp{R4xW%?KN zGd_MXU*>+^J96h-p=CJsbR2xrVIH)6WT67hd5NtYB{M;?a8}ScN{6@NHuS8FGg!{J z@%en||9#jPnqEs}F+BrK4>i{_uANWmW7jLs4VAr_**dK0M;}+!TdBF7c_vXy(dN{u}7P$dA7JKefuU#4|R;a=cp8>&Qc|ie$B19s{ylKK-2v!-KdUN-6TiXQCj&;e_t?mz4|bct`;eHh)A=SVx7 z1!2-S0HhS{mh#e4&!ZxW!DPD>+5SZ-#|&OsRjjkyYq~THkT|y<$42nz~zm$f$tT$x192i+ppu-|d=T zD#9UH`9WfkNlg1jW-?NG$l_v&DCgL~o%E|k7KGu5@mldlz^cq{25ywtnXe2r_`bWY zwLfM@H0ztV_+mEc9l&pSAdl``Hf#g>QpZcXBsrf9tH7DI4M6!54p}mUUC~q>1nOda zOx`+}P(|o!YAAJEH$T)&up0nTTtM>F_*B_6s7igSD|mnwcQAL2szYrwYmH8G{sq~j z8tS5fqu3t(ug{(wN#X#*ZptZ8FL9AyOf_T-{BTM#!^zsgd#-x(S341RH$P>Xq5an4 zZb7>*s=fRa)`#LzQt;xbO*SJ=n;oW7{KUh;!azTI}&Y@P-*)|!&(V&aZ%rI z2{O|LmsLqN`#B*RYiTa0qmwkUaUf{C9)L?Dh{ZNSZ5(%bD?3~ZUbR?vZUA4hy^KI| z7*4hWO4D2U)c(?Kn7BO1@mp4e?T{%n$I5$gT+P#$lGv@D{lHNG8P%&|hf`gvZ`>j& zM{a=48GDiI%j&UIECQfpLUdOV%I6P0~%w?-7lJ0dV-<%5d=3 z%JHr8w}=`q!|N(Knc!U>z$bxZd0P#xr<%M10>HW-foRoO5S97U@Z6!~ci0i^Z-4$? znQ}mw_bkKd+5RUx9t8?#h!M#pYrCB$NBP`= z4{Z;!$Ad*5AHnHJykY7sezTSk0pD19a{FH3^2_Yk=cY?)`*ms4c6nEsfn{p!3>uvD#b*o~bRzX&Qz z;p&B?#y|QPy3wNE?eO@OcDO@7ofZWDPxx{9+~We;wQ<~M$Bl!_AY(gVM*PUZHR2V? zYy&?5qkmhq4eRbi2@gN0)AG0U&vdpcQ_q&H3&h?JK!J9M4$2*>L!l%EaT$ai<6+Z% zO+P4IL6zzCn}FO}ak&-Jg3l|>XVo1}AtQ-MGGHj+r7AnQ4Cvqjv2^6lmV@uNmB zAw1nsoR7fNBkiEIus%4uqW~>Wa-ec4p9hyIvl2wqQm`(=ck% z+QB4iG!dpjGxt zyp&Jed#%N1husvRm#b|V&lTfKWcm@7SpXoJrvt0kFMl{rw=$2-eu}g@*_)DXRdcPl zQu|Y;iI2<-m;d@8)SSfUboSDIYklByC!1#!m$wJbWV~aB3tuB;r-jq#a3QBiqj@$D ziG+YnV%xX(PT0V3k^MF^ml}pn`mMT~Ql43S51?x(IxAtEo>*#riKY^dM!G=J9*S7~ zixeTo_-MH55;xd5?F#yFiT(#66D%JfG&a}Wf*b|Q8`KgK4w1;p1AN)!MgS4d)l^SR zbG-C(-BaBCebqmeEudNU4sB!7#vm2gNE< zs?8an1Rbm1ZHECd3g-dh;^gotSXyj~@=p~A&V;Q}JkH<^$P7{qum?eRae7uBF$m_)gkm8Yws|$H+A+N|0I{7$e4AEUBo}Un^UVB}o-70_sVO=GVJh9#_jlnSVZaZ3KvfC8s|uH44JE zqTN`IjQ2x#loL#Pz5ezQYj)QlW`cnCk8=fr5cCa>CO(upNtE@I6wXi$@VZdnf&uTE zaLrwa)r9ipr_r~y-{ebYq&Lv&tgtTHQ=!<%;Q(m`bgoc{_K~OB6`|0H z^W$_khTI01wN?LmcaJne{aNSaiYwe=ZD(WK6`MEjeQAhU^>Q#v8#-U>=thf_msbz# zo(DlX%>V`$sN2Ld@1)hWO1mJy<3zVdAl;~qH{VkKx+61RV#qXbo{%pUDA_N#jbLKW zGd*lt{HQ}tVI6m1b}gMDxUKNu{zyYqZz#UzMSr^lv38k&J^Kq%F!ePXi-_;UP)l}w zU$%_SV6eJIodPWrYgL!>C3}BCIw$M;qb&VjLn^%yNn+H5f`!@YnF$w8(LTe(CVaI4 zf0Cf!yBd3bfT~;lT>02CnH&73&5UCJ!spfVUVz8^Z78R0Q;atzAS{*I)5+Z%o4Vi5 zt&W;p!<1At^(7b?cBZvvX=U-EeZupl;EBwuThtQDcz{s(pUkixiaY7VbB?4i6>>*7 z-<@GuV=3+sR%dUDPh1(cNZaQ>zW7zXxFEpdObD9Xeu=g{Q@X=*RtAdPi0(8ce(yIh zFT+@j6w2N9&0ur9n;#-nsqY6r&~`EMvHWyhQy>3QobdTl5nNN=4h~T~Xz}DYrU+3yavL1@Ao30`aAD*PZO&`!0F9uZL-AqB^B5dkI} zH5O{je^e0ADlx}G_~>qo*@p2HV-s=>Ad8AcnEeD|bp!;QXyFh(-uJsF8+3c^&ibXb zy|#RQY}G)9>t0_wEON*+UZ4(gLjJosh(@B(t7t`vVOAFquWrOKdpZ zTz6TK0=8eY#R z_N3ODj~LV$5s5YC>a3KsxndI|^Bo9j)_jn9OQUzu?=*`H!&?Q`M+w^+W6x;QN5ePb zKBN=X7P#E;jy#l^nWUj5aF@L{rEhOW35(-23@2v@vO}boezeF?3w2#J%`t4WHpkgc zT-@xba6JfzhO-wMEOs*#5hc@jGjObDhOupU2w=T2ZnZ3@M@)i)`cQQ628qA*mwaUk-=ZYLr2aQMt>YJBMsRFgJ1C64# z`FyE>dE+clQ2zUZytSns5zX=U84rT=ufzK>qkX=@1tw( zi)OsolzRbOlqwt$pchxYd*q25y3yMq6nE`HI>WKdf*@j2b@PF2lK~C`7IPl4+HiQj zc^9YDtOy5;8+Mhbr9!hGQOo&~XEA(cM4L3T)K-nQai~HOSMVTEEXQO6+Q`-Bxz=sM z4w|}stKkqRrGg_bzDTfgrPhAPhBFM4Cs|#r+JnL$R@2lPAaf;`t0PdDT0LY~(|F~u z-RIia2%@SezLzF5lgI$3MHmC(u61lS{LxkhdS`LfAg5wer+z#CGTI+CLQ~+b#~gV^5dKUV;p8dtCL4O5*K-&08j)fsPPIk;u)-LFc6De{9#U2I4sd07w!*_ zZ`fA;c-B)ekHfkYK^A>u!WHUeocz&?Hw9F@Vn-H68YWtG%W3Sr&M;qhl}yweYYim` zi}pp*V0BJ3M9EgR#Dj<`fjTGA;kLDj*-vvHSqL>6mJCN}_+V!Xhwb56X~ULb9k&W* zM9r*s3yyXuIhwT0q6BScUW2CsU(COtYdrvu?;OnI5x87%A6+^3m;)VxKl))vP!KQ- zYz+)q3G{>l+P76t@hG{w-6N$XlRQ6K_UQAT;NY-@Lr?@7G=L%DGEEgvL;HCUdLOLl zS*yPz&K}%tBiFs9Z@E#B2g_y@S-&j_` z;?3(OYMJ2ko>sIZGh(wl5U8`1@y<%+ucM=plamehvSkpN31O;#r(x0+H8)b-jp?Bl7w&g!YXaCpS5-argS{D^rrrhpf(B@&I_OcQ z2AJJO`GjI{!IXUgbkWX9e*Ur-`1pC&2jhw$!>UI9y60dnepW#fiPGug^&@)MLn@AQW>iD zWX@VZQAG$8F^A8o3<=gnUc*;$HM<`y6+-Esb|LyWtDsbKuTumfX6y&6>|w5~7s`68 zGyr20$k3(Dl`rE)XlVYGCutwQB$V+n=B(P3D^_k*B3XO>d4!lFP`m@h*NOU8T_t?u zd4?i!@y_}2l`uy3hT!F z_k8aA^L~xzN}^9WsZe#d7Hb1u8lD-u7}zW!>RKr2#NK*Q(#*6hVrUs5z3$y z_$aRGI4??q1%)aW0NKMlO_z06AvthyesyJ!Do)`1(e&XX2mNkaBk>OE-LaX64N>AP z>qTxF_#1gdRP76I=YU|@X%&IAE*SHqtk&@7!AmMwo2)u;YXQ(SZ4TBC0rU5gqYV-7n)tXPki~zp^oV zDOO&-Ld8{vRxHc-U5wD5-R7CYWcdETErAP3IOsz1{QcyXpoMr45-I01je6vD975Ff zW+6i$c)@I4kViu7{amsekye-xEtV(xvTa?BnjILNLhefQ?W@t(%Y$L4>L3|sA2J#E zx-~Z!F{;XRqdQ!R@GvkIgC6_Ji-*o*6XXcndATQl)d-q!-~?GLSKWZFiW8u=zulWS z0cs{Nz;EEx8m_+CH_q<5;HR4P_fIv_!XhVLQvDM+sk210pgyn0X~MyZu(Qk;mSKwkWO_7M;q`4m zQRQC~>^L9%xcGvsYx*gSOV58q^xwlA%$auQU8Qrs(jYICJi9>V@rtJUMWil8Ucrm+ z=WQ_8BCR~e#_;+(lOMmiPotvM6Akumy}kc)yS(6T&r5+{P!-R-F8_>S($njC62EtF z^ZWUg+lzk+Efzo!6o`^rbga)HRRzK}wQt^=P|AFnXpPd z_;vK~Zoco3@bDT(P))6VkJ-}V4-WOY7_eu6CUtxbl-<{=f_{~*61DXa*vgdGA_IYQ zU7GvB>CU>Mj5WhS&EdtJ^^E3AmD5mzmCGoOwv(`F|Fta4v_q zYcUdGJ7n2O!O>8+$rMwG?k*zO(;`ekhLSC#t_5spL;A3SRR#(TH4 zR>jV3m20+3y&ju%LG&NLBxyMI#q$>uUwc>~5E2t`g-jPPPs?$vtrh$mj(@A${V3>< zvKAaI@q(9^T_$1>xSCYw=H4=bM_qdmY1xqh;|6}D8%FU}wVg^xCm?3;3!Y0_`44pC zj6DfYeUMVoUyFsG$N=Ir6P~%pGWow(i9$QLckv4*3fdR5bAe+P_3~`>NF?g5;!$7A z$oF%24pmcuXj+NT;})`@m8QOa8jZJAT7rF7+1FWXVdcJ1!E^vP%E5&-KR~e&E!0&Hx(QDg0@+ zGa`L&$SoT4>)KQ?Rx+hNqbG=gU;n%!RRdd z+R1A<*~Zd?_U^f&JlN(;+QD8in>i>@S|EyjtL}tr-#=uxgy+akYzxGtxTFu?YC}Xm zjXRgw>Ibm!Mz~zcKP5$GO0B7%_4*Z#?-)GDi@6NsvR_HH*n|&?G{k60b5%vrS@|J! z^_2AWXE8ia#A%#Vm?FZr=Url-=-wL6gN# z=$txacvpWG--ZaAVZB~9yIJ$r$<0j=Ix}67soWoWh6h0Sa@cuRB>b%VekN+@QcKSv zM{9KHGron-XqH>(i4Ds8R{Q53`Mv^1^-rs&`Pp;AhOfVgY9}ypa9b7FA2FN`@4K@7 z8(eebJIo)x;EJBKtUH#oZb^Gm*41v<%8fs)R^t=4)`Q?3y5;)P(K19uNd1cS4KrM& z+5VM88ZTWJYm&bn4CA7UF0Ki{o^BO#XE*MgKj3`*@lOZ_;A&gJnxgtmF4!*EgvLyt zvqx+XhPIXk)3rkOeF}pe-94Tfp2Tk7{60|B-6V=CubVu-|N5n$@4$s`&BEK@dzoR+XU&`C1|*JgjXRD1dX$^BH>g(Al#Pir zf*=nr=;;sR@@Blme7Qwo`pFrBN${Q9EZi+|ETgV$x*(2+s>-rw}T-d$Fo{M0Q|9V3`wHlR>$ zH85$fr?P9KYIyer*E5>uE^G`l1tE7!3QxADoWSgNt-pUGw3FicmjWKi z3qCnrxg6Y*UMe?r4Zw7E`aAu4-XYZ=M*uk=<;)+=H7|#-tN0yj8PA61bt{RGZSRfT zL2aG-o2{y>|6m=2NFO{^(7@)PJr=MQV`jTzJQEzH= zB&N7CLZbDVPw-9lUX)D#^%cS)-vIWvY^iyBXHiT6pLu@wzug~2WHQIIMzLf2TWJkM zVhrx*&OUCHQ~Gt@rZFy!6i*cV zH08c8aRy&)nTL%6Y7Pv_-`|Y*r>MBwC_s36-lOVS;K`;7Id#A5tb=lp`G25qRrjHz zuY0duxmm@jrrm)#v0YiSE^3h3^oh7tr-I6P=;HFqF3jYackGOQc zIM(IdYrXUH+#iI;+dP#GA^f7a)&j>@GZ0mnxwtvdSF1fI_fK~nRmZS(VAj9L|E)_| z(cHUo<@q>7%gXYhWCg<4O7Qs~n->RBgUd=M=rrBWt>>DQX0BgUu0u#j6Z)q-%kI%b zHrJ)D46bgW7kj^*qi6Q2FPZD5W>hImJu+nN>R#`($ppTZPn^Iq+_ z#CD3ZGz1=8eWRt?!}n;eHu1p+esEYfav%J0DSm=7^}eLE%1%lK>$yfZwNAHKi+KZq z3Vzt2KjKxiI{5iYZ1ShlrcAe7*e{QU(de5o&^QK=UX?N zr}Ur8enYyYPWqGg2+rvh4YTVaS(kJ#?gt{(rq|cv+E9aRRj;7y#6&Mu|5rSK7cU)ap_(Y zi!3x&*A*?=HEXYt_vUxXm8ieZoEbDi8jlqbv%`E#O79~)^3S;b2a>%nxD%1Ug;yU8 zcvkOs%g_F!+zS@QaBCQ%qu}+Ik6}S$>sEISxZfUl1B$I_$!}V>w6zl#xfA0EKoH+# zq-MKKs>7C2j^r(AYmi4W0b`?d{&V7Ji3I%`2i>nx&lP0+Y;2HLzy^hU#}_WPeIuCRDoI4RCh6O>HlvLz%g zWi@Xa&o*y#&Ac5A=I?zd+j%C_Xu(X?!jca?lNb&D3K?p(%}+Wb={Z!@!*f=(@3Iq< zHb~n@#Sy%OesVCgXG?dUIjbrlmFokIHXE}GILhgd(mu6&3t_(_h9Tw!j8)HAPf}a$ z0~Sq=?l@s#ah;6*l!ILrGjfxChRO@MiLRr{!IOY!*@fti!qG1oNrZ(qe(IFJk=!}R za0N!2!-%0O(iFKeHvEx4#Y2ikiD7W8C;P5hMpL>4V8(V@iJ+QT@f0^V6@|7%-_0NynH) z#5X9}<0QVyY&GqfG)}lDqLL8oon~8Mu z{u!=q9&DUB;moDl{K} z0@7+QOa}JUWa_;aNQ`4*vZuq{dr4L)qRYOwkYrK5l8(u`cX_bEj-_qhJ}e_R^)pB8 zhlQu~X7q`LH&yLRJP$pNEVdwOI;sjjx)ZgN2<5~7LcJSURYOH~KpKLZU zdd%P`i3Ep}`{J*?oVTXV{!qif0{_xi(G>-O^;-h%n=kz%^b)JyfBW1r?~>p`1mTcN zz^2to(1nMYf7*ZPWvy(hV233O-sV$8f=z$9C|lfm2sQVyO@JLwZ;_6b+^}a}wBI$t z&JJSvs9(djPgvxvTDR@)x_Q#RtTGpUPR(z}CWj3DvdO4j1PBFkRP5C*)j znb{vb4--vNZOQtZ`eg1QN#krjM{;e%6NWUeD78p`Rkc%C{1g1`kyG>Moi9NUb{2tQ zse$F_ZvPz&?^5&)eY zTF^`<-}*411k}{3KWhFspMBRaAoWLU9C8=fbJ<<%a;5yt?C4YUHYDE3RwwZ?ENL0U zBA-PKFPdAviKe%v1&(r7Hd$zBGkjVwJ~kI}!=>JHzWTIcI%Y&u-!QB;EbQRpYV|9d zk;|_xiyu`P6lf_@+X)L#7>G}L5U_PcC;^!C2Mkr`Rz9!(kR|i4Yo|MS#fy@7T>8nJ zxoWHRPULiBE@>LJqlf0V&u7#1xbhx^t4$Iyn6|XJ*a!ONw-O zq!!e-cOt0m(9)fst&%ws`i6rw{+_fiAO2d@zHb~a*$z_T>I{(pMcwneaoidADL&hV zpFoXw1k=hamAvGW#QH@XRK6-wM>s!pnOJ;bM2?@O4-6*+1yO(hV->~nwId#^)4D)L z=5jld99i0M^;INX!cz5B%XGu-pbC;pj{w5!`+yr2JJ@^P^QfPCT`>VR+S4mTyYU?*F72^|?oQ$L$K4>6 z)kEAO-_IV8T8z>~f@t_6b%evrusnX|e1;r%?|KQ4-LR;?_qRXQfW>cxSgXJA7*tw0 zv9Iu+aM^9pi8?&=IZi{;D=-V{a~%b6!9w~j!_)1v)M$+9KmvH#+s_^)pMiIeRZ zj#Aqz|0s}XhUwlNuFJ}I6wp*UPouS$1L&DOC*)A#?`~P-q#bkKj&ycPexe@|4&T-ai09f z>%y)-?XT{HD#8P7FjQb%8|&(n`qktelh~tm0$v!8uLf|bj?<3rqpK}CH;BI)7Z3$r z{$P2FERfLg6vw~%mr%#EgZ^Q|hi;ZuG1;x1mQWvZSUmNq{_It_Q`vNLG3Rs6n8&oG zx?T!AwA2i7KJd1^$9z>{Q$k4yo5}H}f&Gg4rS$C^=D*WoX8s*g$|e6b-?1mHTYl9+ z>DPiuF!t_D<{Jd@$A>SEbvJ+YI|&*~&-2+HfDK#YX)$@6HxlcYh#7lr@Yjnsc!j4< zvhEor9jB8SvQ8umKMu4N4l+o%v+ogic&8;HGRtWQo~r68;jj;}lm#l$Rc36v#E`zu zy7y1yO!fzTmZo0Elm+)j?+iz%=+;{7$Fm?kU(+~O)?|RRwDc0|c#HVpKhT>aeW&pl zaT=5TfoE~+to-l&v%iFla-Ml1a$ zw7W%V=H}|#Kv=mEXP-zP-y7nqZ}}k2!qv-FpXUuI$!9*mMi+cZWi?wMba}A{i8qcMtM-=M~xdywIX4^1gFCFxabv88IOt;TSj;QtN@97aH z!O!~pL{{lvqJQ`Oradl^G-rPIVI;C`!0%XwmQT$s7W@zN*|%j1*bM00-U*DbalGb{ z)#~P!*w$8Ff;jJc#rCb`eN3r_7I<0N>=n6nV&`7#=Jk*3O-ZD`T4JV2qbnZFZC6<> z3NH#ft2*nW#D52}ZcdM_ui7_@(gS;eQM)v2xw!kj0uC=3AARxu!Y7iMV|?9X?zLam zwVO91Z=MF2r+6+M2iTZBMXZv(An3FYq2Msdir{e-lR7kzqU8xo^m-NE=v_qu5sRMm z{XTtm5IA6PEIgdOZh7;c%<=M@YzWl8uR#MoU>N{iWkn^vS(%p^%wW9AxOL zS8I4ScU9fUtA@2m+ESZ)m%X5p{XoWW>t$3#{m}N=m$W(bd~;e zPJM?#AcFLg|5URPGkY`cg5SL=otnM#_aY8<)T-!&S5@+9*F!x<5&avnq@n-68#>L6%vC95{30aH!_HVid_=@cXX` z(D@DQBu={GAa!fBst;G=Op!vUJ{s*3*^nvfxAt18*7e2bCfnsg`qzu5Lp378a5GO% zE{&e@1`}%=^iJ5#BGX0kR?XarVvx$6rcphl1n|b2t3$S&J63FtGaWr$(H9jF$yPn4 zb!)2DedfDa5WYlzBU}g;8u-x(4kMJw^&^+`%)&A#e0$A=)t#J&J5OK7V>xb492|S6 zLcahz?Dk9+w_7S*!ew@(eg^ZGL5Sz)P2PgpxPN#1E;5aL>CYVAY_B8rz|00ej8_y5FJz&!T?1hvj=tq^wo3a5hg9*0*)l6pT#kUJi5-hz3-=zB#sabLaK8dOa zGoIy2{#^Qf%@QtA4RPP1UomoRFf(Ch3SRV*A8K6SWYmer5N3Z}0LM&8>ma1N1>h*= z`}OWm>${aHqYZ2-w@bPU9>C>xBof?cUq*lLGQAKqc1DW6L<-J4xz2Ri@YGWxthGrg z_PtCM27Ba5E7nUaxw9SgQJn^6LKJAj`4R`o)-Rpm*6 z+eYp1F5h1C>SjTcXpjS)u&zNl>P8W0w>QCs1wOMkbQW+Avz@SQKO42u>AeIpbI`$& zie5$T-v%)gH;xkJgUDc)jzV!WtL4f9xk+s?wm@&_%0p^ao5x0MY6s0#02t{YA~n3l z2Ryo5doOV@z}Z%n7oo(W;?#HY0XXSau^%Ih4_iG!cs&0v{qu!#LQqluHG`KLt87=b zrvE=AE0GJ!*pwM$&wk0h2sNC-!hk(;BY>Yg;{bXim>-6di7gZQu~-bEpd2WeXBA-3 zi(;Lf#OztJ0i)OANU%wCsnzw1k}O2&?#32V$pKW%saK7H{h5uAJC;U%&+0#5{uZ&` z8MtHLTErLW_eB2o=jz+0+Y0WCYzi3RVV4IUgceC~r+?h)HmbTtqfPcAIt|>c<#1=J zGd7=xk`UlOrs##9lyd36sD6pOSk5rXu)7C{)}#n-)U2~nugg%kforny`&xl|r#^^P z&Us6-BkM)LF>jIfqcrzga@o>1^1%z`^d6duote?b(KhRNKKT;uRiG$vf%pn)gD(3L z)MIP%Q%E!@jZfcIB?|6F0LOmNQ6$h!qeKX0Qf{FDQY`OX9KThyUY-bEohFLICsti~4}|73B+og1({9KavAqwIf${DYdi11$TsnX7yZs*SeT+Jw&U_ z;<$rDMhNexv7>g6Wi7&X$m3ep&)fN{5PzVMm&{-KZ8-a$nnaGCL8rr(=N z_S?J+NaYl_HtJ+zux;`%q~P9OqkCgJ*^3f>PuOY_6l_Zk>wd}T>I;9%Uod}!`B=8s z=*lon*eMiP3H}tS`evV(A*XIYDU>sWGsRiNW`9{`vMA)`lb!$b0JerwH&#a&5fF5z zD*%Q5N^+}ng&00?No-aeKzEn&lL`F5ISxea&vn}~dd!L&Vb07Z+4G^65 zd|CYjaH>{7Z+swKG|GgZKqD?#Rz%KKjX8gzc_qC4Su&b*j&*LDFmAmaz9l|bv^#vul z_)Bn=Q2s>e+yni-nx~thE7p?H*+*JG_ZLpro6lyNiVHV<{L?Zz`AoADhYY@l&>eK&OmSdO?;tm*O?H|Y(6B@Tyby?Z!2JepC!7hvM$)}GP+$w9Oq#?m{ z8l_qe1Z+@SEaH&2K_gBqvd7sQz%JeB$c>3_>kLo=+~Y)yaYlc`V-QEDcHPwyXuv2k zmV~?{*`^>JZL-|LmXzJ@pX9v=J|GyBttz<4&J(AKggchhm`Mp{V-M?)I9kX+2JT$DmhH4_Awu z1KSjsr?Vg~KSJT{&(uz@=sO3sq}ZL~^Us2mLkjLXoA}w*`;l*E1Tq(U zC?E$h`lZe9n64;D7@Lg9*mfOn+oK`W#C9n0LR*QASR2ftk(frEU`CN}8R%9*XR&|> z?li^e?E3))j3Uf!D67KpOdth^(pr4@(>^j$@d#izUm~$E-mJ75`E1H=JK!#t;5Oi( z%06pnl@E-pq~_Uy^}QvrTOyK{bjQVm8PhMgcXb*)}aurUK$_?IFpnKy* zVj%ei-9LwUj(=)7;at2`7&-&TPtS9P|GFf zimF+J5;WH=5nbAqUdmXBbq+NU2X|bPN$UhjuX#x2_7}JwOHI~_(X;T7_nL1paUL|L zbLbAB1c>!k2oSt`Ipu7A!0s=<@p{WwgKIx-`qDqY{_yO*shQVnBP&@>c?wDy7%2W3 zYP{inx4!OazlM==qh}rAA>Ku}90G+2R{!%qs0-ho6W*2@y))ydNQ0Sq?&Q6^WU;uB zj=ig}4|zaa@E=ut?sJX&%WXuMw}9u9jLU~;3m%ysB(SZ2ti_KCQF=SU`9xl`!->fw zOPSKTTg;aXa^?qKSZPDe9=}8ce4K>mf%YQ3@Y}j!mO65A=yM;#2tr-|27eoMKxwNj zhb4K(u9Tzv4<$mE9|t;cqYlR!-x4W$1|(KbQA}yC1M(si927I0L0dJrBo<1&`_s-0HOjT`qjlkWycfDD*f1bUgfH&307`Y>S$jZ+1x*P;Y=S?Bo_}MC z#gW~{ALT?u*{F+zWy!?r`^P|2apro;iw8mCWQj0t@h_-rqgY%FSV*JJykg;~lWLH}SSa2VYWMv5mAl!}_aY+CgjDtQz}4 zN3mg>Rd!$0vv+j~d6maX#-<9Wcrb$83J`H77mYsL>KECOlA5-CtF@mVM);b;`A&PY zHn#eR&Fco@VO?Xm{B~!h({l=hzo(Zv^v&7HK1%0uCWovz+m${>S?N_R>;FJzx<{K! zmGt`^mqMZ)apPZ{l4Pni)@@{e20SNa_n38C^Hm|&D$>lgd+-0bVv`3_+GgwKe0pdG zCR`1YSGpYS?yUv$Y<&N7i7!zgNvU?$#9Lu%`_u(!Q|KR&?;-fj zBQE{Z+J~NT=Q-fx!T4OFO30I?TuYO<-x-_$s?psgh)e4TJY;e$cvu48fa+r_G{%IuysrR(+tI}q>&4dzrCqW1@ z7yMP8FxHzO*fI18h?Sk;By4vpbBci^k5wZ8%@evbp1|aD+?uHsDzkt{$SA=vUtZR- z0Z_i+_(edW#;LXtN+Y6A96UG{T?T*vU)Tc?8|V2D9vlO)naPfsRQvJ=?mtigh(r28 zV98w@f#%hF$Evw|LbLvBsH_&ka}{nfCsLUdqwhX|IRm9<@HvyT5)Wv29Bvd}Ww1=LF6#l3-i)EZ(zXMQ-9yCAP{i;; zAD451e{f1(2>^g*(TB^>4M4Ju`hUR{>Z6~=aT>dAi<4;*ZJ71s#6;o&?*{=LM_3jF z9S73N_}b3Ifu$W9m82bnLBYW1mh;u9X~EyK`>Z0%#s@#6VB2-T{1Z8esL_TO4ksPyu*!MEJsT)7_PLDDG}6>#W`mlpOBO3`qSWA3^i0-0UMXT*jn(CwB*0rspH0y>ArdE^%dPKHu7J4Y!kqY zGFa~~bp__?!ta5RZ7!u+>Sbi)>DK8i1^)dZW*`7JvWMkZWLNzc5b(&nTOd1~o8V~7 zU?6^-S1=R!^pV8}?yLnAY%wYdf{u1j$3-AjJOO2iz=Kd8&?=X$c4-~XSCK?QEKX)c zIDV?kT2=!z$3syPo%VPP4g_!g5h@UFERpXFh-1ko;!2AmAQq)v;sfK;WmO#{8T@}O zVwYC0MeRQn2oMzfIXgzmIOI~-)|!67f9MK~iBIOF1rT&9!Q(+288@}iNcoz>)Vt8K zjs#qX(D3`N?D4~s8Ln^Egq?rmGVH6B!%|j4<>w8+(vPsV(FR(^u@@!S4$QJsvRYFw zALt<`%@pC4W4z=%mmb+=HUR2tz{mud=hT_hIWvroDT=TWhZ@Kc5XCAl@Ft{-@1@PR zGK}RT!U(mRR1z=f_mc7^2rdpjCllWcyb+rrLt%~A%f>)!KqraAI7Lvw^Qc+*2&g>H z64bQr5N->An%w2qvYL^_dY~R^BiKj9-)NI7kjzbYiv>kP!2<%1BE}#%I=pyG@|?Ob z)(*2xCFoWzT!sY8`crBTXn3!A&aC4wwR7(cQz%ejz)T3~w{h2c;I_?A-iCoe}I<(N{!EvB>(a|38Ko z`1ziVJoY?wc=WRcC=Z)R1iWL5S2Md%0XZ@H@_rdoQ~N4JaG9Y7R(qIZsfHxQ7+nS8!~E z?K03?*x8ojR7m`fWSk!qCa$s>B%vYAK*Ca1V&BrixDS?je?u>Z4Q``+34k6YVyqAq zt!v*~U5V9(=ye4cf2zB&mP}OxtB(FH-B(H(FbB2OO|@<{7j0I|BC!6_iTgw7&zQl=MtXsiyfA26}5 zO95_Ub>KrId7UZu`wXOE;GS_%nMJ3dSYZYw!3M!Lc`6<~Yaj1yZwBnG=^X?+gZ*I;SA)c71ci0y!r*FA^}C@_32;s-rw_>c?IGPve8KpodMaKU~^)I2#e}aSz*t?4GjoqUEoI%PODVihwBYc8hm1lR0944jN*k z5I>asjXC8*eQth^_XjO!b0Okl=O-+T8(|HUiQ|*KqB*v7n4{=5{zfzj#oOVSi z8*OSIxcf75ioq)Sf!u(R91yo-Nn3z2ZD!9KgL=qrBwl>Pdl+X2026}vOi8$nrbsVq zALyZ&H3a3tr`6{@=TfFXev+w6vJhSnV3SZhqydl+?P+3*GJATJ@*P+$SOkNJt~SGP zTRmn-94EXnlB zVI~mj==4#9av04>hWZfYbM7LVz6*lK=&?eQ2T+<~2O7uuHaLCbF??;cI3*Mbb2@$G z)xM-nodIGTGx8QVRG&9Q3IsYK=#fuNg#A+G4$;3h*}Y8Wd|vl1osf@0yH?T zu8mOp1ms3pFx-w$IRS!BS_{<4H0X~-gs!cy8xavUO#7$)IYJhmacVT%(K|J=X`vHy-{T zys$CI^Ge5E2Wg~)A=Lo6CMB%+x~#`!q8=+s&n??_hIh7#;_m!he2=%vrByuM6v|?*hzazGt9OTeQQ)$!6VQ^55`uzjeC=uI3$X zs~|@r*L}@_5?`h7X0fUsQ*nuPob;72y3tOx`g6*93>`eS0~C4{0F!Oj)K`b=@Pnn6 zS27~g&H>F_)kywTIAdYn!12cQnJTKcJ5_Go+bD)(YWEKQ_E|CpZT((_2 z`@0Y{n_34M4pmJVGeszz0qWSv&#@-%tTviMa;yGsMpBvxBoNjJv(yA{veMd!V?%NH z4W}g}jkoN|p7k7ZF7mp96qiO&G!T!J($ciHLFrR<^%SjIqHAeI1Iq9czc#qrXqeDC zs%`ZiNZW11M^SMJ1(ejY+i`igX60eNW=J2ZzF=yijgkPt9~>H75Ufm7X6TTIa%L9U z_iPiGT~WWTL@I}gO76Q6gtN|aYYRk#YO+G90ECK{Ir{n5fENEsPr+hk&swa4lpdFr z@9CO&`?8vdYqNBS#QPtePj#5CaWZD-!e#UnnG(1hgH@iT?6gA$DXkSl$pD^)i+>3P zn#*T#g22vCF&q~kaQKL=M65)pKd8}%^25KqV!g_H@^^e~4PY~zt9^)P@^|}aT{l~~ zb91{OuHmxK$0&`bFgwcTTqrY`?r|8B-SHR16(+sG~N(sQ#eeaicDN6Dp_b*a*S)& z$g102v#7(~71!KRD9|+ytkgP_Kj9#^lHBp!apOmlTV(r^$BD98t^1N|kr4Nm*i=WO-+=;9Va_Q_Wu`J10sZm*9AX$ky2E@7Wpn)XJF(hy8@! z636SKU5p`Y!YPXU5D_00hOQvtTNRg)aL(Z@Jd8cJxraFYT(Mho3RCTVN1+1Z`@PW5 zlHWOy`#%sTZSzJFNi@mEs(!PsSE3K`NJ>huu>e`0Q>X9F0<*WVZWB-^; zHOq*?wP{TT#@5G9g=a4xX@Rhw1XN6U6mR(6blLP3J7)p^@WzM!&|vW{W1nQ?vK{p4 z%lO6pIj&XWTsG^Hn{VEa9jS^}7+b_%3j0L8U$@F=xCq2uOtcs#3QCSWND>!msO3&S zPJMnomu|yG+pAdG??yvt(?%2cO`74PRp8Gbu#%t3VbqA>p%yqj`v^_$Y+R_7 zH}mODUtLk2~WVq}AL8 z54ld8gUT*#mhy?AxRNTOQWf2Mp;1l*8|x+=8U?SK5?aAdVl0M4Bti5f#HL-%3rsk2 z!hNr0d}Hp`J+O&Smj=%LF~fvi33r9(Yz!Vmy^(oasf)QMG6p(V-ec-)DEz9KU8c#e zY*VE2;`LAtbC2%Z<{JGp%UHyott%b)Eg2W7ft=^8LrH|2I}Ayz4wthd8jlJmgOoi> z#S301@#(LU!p%Ze-b1##lymk264p3LpP_KKRb@&UGfT(9PPlii)$11>KZ2#QUz1*$ z-Pl>vw6DfWe-owmNMh2ntgtt(x&8pT248 z7mlAuqRS0V?Ov}=EI7DcLhnT~mFgxYr|Q)KrzeUzz|Q*nf1nt~XDgkjh-wi~$?$h) zf*XN`)*Y^;gL!%`91%>SM%DwNA*vBH~ zE;i3ZZ%01pOYzoUXSIbjt==F=H3Og}j5M#7bOpo>4c2iwnL|xFf@*>~v6JM=8 zwJJfY+&SQa`<;udi4zKr5r!h3v|@6C2^T-cmB0P0HFx&K;kG)ATi}C2ADws?N%j)q z%+_7Za$+srM%PW-SPnfD-PX1#(;&%JZc|<$S%CjsET4Km;93sR;9M zP-x{;5ze6wuNV?wX$oV+t8LY!_u-GHlAy5l?Sa2aJPd+=I1`WVSyU=q{0oalK{g%> z0UHJLb1h&LQPfJ07ymLFld@n~n1Y7~ad~GhiX0Fdi+Z4xVG?e=w>hVM03ev+1Tsx4egk#BM{b&!hqF<%IlvxhGrGw$2 zT@MjaceNaA^(fxb|3^)}h8&pk;5l)Ncb^OAnQKmyLMH>V2{4nHwZ^B9FZtb(^^qyM z8eoS5j4IGFatz^;xQT7p4v(430pNRjh=DKUZ=xYz~6CUjkZ_rqBHUOHQyJZ6s*&vA3C(`>nfZ$ zZ5(>BT-ozW4L7+3MYomEJ*7nW{it@YQY8S!#Vha$+7~h;V&#AzfC0uph=lr+PcBCrGP)o%1 zUyHh?dW280ZNtTart#e_=jr!nE5cMBv>>)Dj3zo+nNa{cF{KsZ1$3?!0<@jllo zW|2-8Olv+qwc-fI@b#c%mi6gogV}s7(1}2u&4Zx@9Q5{@B6iZNBkrBB7(qn~Bf`;$C81IsXVBKg7kdwSaQDpvn>R%wWByu-TFX~@~X zl%vw)(l>9UYYnE~e@-_^{SqW|B%*VL{=L&QpZU?(TK3XGF5tZ(aj>{|TAxn;@Ogzt z{S0O)9X-$zb&{-c6I;E_B4^8X7`)x$deV{#Tw=ucEzGW@cGqS@k8g0z9Za!gR}u7CI&M<6ZKd44X@ zaS;6^WvY4E+@B%C;{;jM?_&Hti_H1=?|8|Ih@%fUBLL8|j!@E`DR6|*R)(55jmK~L zwcT`@Vg|^`4=;ybkUXt`aqT%&CM(zTJ9<-&=OVZssX?27X~p`ShzMU zTLT3sVr_m2Jk|3)1T?mXTtIfadR^p^fJiqKr!-e-HFu?JSP|&$hYg2nJ+OzP#1_Ds zy=`LU{YhkQK!x0_zhcEr(T{qv7;~HSE>7jeHIJtEU}r5zh8va>puB$bYX z)*a0*cf=K~)Z2tOg8u$_MY6eFHgN+hpCpapxgOjZ366j8tU`tmo5ZzyPxx34Evj7{`|Rl zauhgR$&Car>C;{Z(2X||Ycsg|6D|IQcWo=phj+x)E#rreCEsn0MN-CYO-PX)E!7lQ z2qr)ueYdQLcGS7WH&8gx`aFx-#431?1xax9Udiq+e*1L6^i*2zzy^5mhBBrsf2WoQ z2LJ&nc~zm|@<8!9CY=_G4ru|qa6NV;+V`A4&Lm3fN(<|jLc~UsXlZ}mOjL{}Dc3Dp z3(GYNbXJfmIC{l6IyMWcZ5MC#)jH*cA_oTKmf%a^KlR%3>28Hc)z8-LlAv}0Ys$|Q zYh!waNsUZLrNo|2K?o>YJ$~5tP7M4~?32%y|uOZA4lgMPv!sq@x#GEqDYZ(6eS~};#lXSJc_k#)>tWMo7R83)HYR>wY0zx(_9+rv2S`+nco^}4Rt>p2Ql z5ZTMnPMPim24#f=fc*8`O;AL7K|3A-a|!h)j!m~YelU#vc^pLS-!#y8S4C=trvcdq z!b;)XJC`sK*uT>?yr$}ZikjkHo4AD(I9oYnC8B(XKo1zu$?p zf2-xba+XiV&T3vWBsU3!m;XTFmQ3BgI^;td-u9GVr_a-nwQ;ypK&0`Mm$%s=&M~_- zKi_3qbw`OPs-(`4U7Ip}H{tpw8V2FP5-UeZ{1sEIDL#RBjDGi4e7N}Gtss83e$PUE z_xDrSsjN`UwJ<8{S0waLkH+4b-A>8ha{Nw%eH@1_7PArw)pHmkyPZ<_<7@AX$JDUir$cTbZHM<2@_}2Rc_)l_(G||K*=*+V-F;}vlaCAB zNd9?yrffjL$}$_hX9PUHk(@`fCvTOd*HNZ!E-r>248KyQa^CJ~)1@xkN{olbVKB<iCvGFRc=-N4q~^C9Q3yq?hD%(|zzdXzn_U-WA?& zoWc1D!Xkoduz5QC_-TNN#sh~SMA@prxi6)H`#SG`+;BQh#*Z-VGlXa#-RV&@nT(*S z$z@)+-PD(Sz9SN^7gF%*%>C%wf_Fm=ZL&7j6g40_4>8)n;!A@NyAd55<*Tp1sTK>!*6mZ!?4g5-QG<&QR-p+xi4)7R z8FSs_u}hILaGod-yV{T%@KfGD5q3>tnF^ZK00QW~-gr_H%!6@746Hq)gV7s1LKtPj z3@-F*i8v+frSEPdBQMJ&Z#2Ee=IInQU$*o;$Y%X}_o3t+=~-r73@UDF;ATcGyS+!FIsS}UnS(gRoot5TMgn_+z&j4^cFF9s%OzO7%-)L&>v3B8Vr$B3lGj7PSMaSQ(Lao6TZRsu8R&dG4D z82>mCmt6PJ{2X)8|(iF<2C-;&j<+#KU=ocMv| zSRjo4e(I*h$ClLViKH89{UI$lpg}RcvAj(vZ=Q^`r92dl|F(QVPVKa@Qm8 zoZ)&Wp^W*+RpknJR;1rswn8f)V$3xZ%(gF3JcEXEv**SxMS_1r_*q5bBF1VvdxnNLT_dGiyjRM7U0gr@Ib= z*pUKlQW1Gxq0o;%W2)kfQSo<=?Q)ZN)vj-Kvdt5d#wcsX3lHMIM~Zm&cyv+v$Yj$U zo&+w`#ZImvZMxw?3QsnpO_^ga!&jHMPvC~a`l3t@2D(I#NPpj^AQzATvcA-sxx|OUGarI&5x3}Ep{r(9i~$k1 z?ATiccTttD`Wvl4hd9B<&;U&_b16m4QMc70qz28zM)7aR3AF#xO z$e@NCwMy;Fa6;47El%hRUI^?53YI%OSgfQJBdgUSdsd7vyO;ygh-rM{ANfAvop}$H z^QwHOs^{u??9>24?gtgj5Xm!Jy+@IsSYNB_@S}*_AifJsp|2r7t~}N}0YrK0U!h|D zI`10~*aWXkzFeaSrq~PGX&lPb+hw%K`*c69KVpA?O2+^*rTrpJrXITLniOl7gWP+; zr#nv;@~eq=z)y-Sjw)*w6ANF?zkPBj&yl7Slrsj^n^+sz!I~gbkyqF6g!Nsn6osk{ zdLXJS$tb7NBDw1pw`ta@&%}(~@H&634fK2!2zz@RYgQ)CuvYVoikQGm?KWnq{`fz4 z#x>oydUAXV)PYFQBbA2peSQ2A&q717!+Qskt_>KPk{Qh6O|-t16=VP=NPAo(Lf9sNiy@hZ|awk+<9< zGB1d56}~>EJb&EQkwm*R_m-KieE&yW=(<#hj#(i>6hVrynwpm{=gz9j@;ES1{tzC?A*EVG3wfiM2kh;gIOptfN~Q*8`uq| zA96Tyy|a#_T@6XNbN?~xB@$WaY^#fV6H$=&d=$=k6kPix@MW!v72{{s#;67T@`h_3 z%rJ7y`nhlzwFzxfnp-z$)qeOUJ>nlIh#&pmyCL1*6$dB@zte@=%W+?B97GcloWF&H zgIs+?W6i?ipUVs3+br!t7tr>jRQZsS^(!Z?<(M})zD~j-Rmi{ZxwR~}cvRH3Ddi(r zUJcUAyAJ{B@QQo={XMf#$M9| zwXgh^)}p)gjv|1*%*<+^<6&3-$j=^7J#hEYQlJBLPh#WNY|k%CdnG?eHn77XoTnvh zD@NEF%zMCuU+o?Tn60~aCy=POCkF)bVRUqUr=LXFLaI2pj|L0WH;Or# zMKXSaBbw5&?#NeS1QXjHdHBeVDb}|vcQSFke&?Pov!%q&pIj29T)%o}|M7L) z)#GHr7Ck0Ee4bs<)ra!YA{ich{_lLDO>6Ng#Z#_AiGE*S7&I(#f*9_&Wu|y&8Yvfa zD^cb1YySS3^;lFHb-DJ1G5LHkes&*M_P2v3@WJ$_>%K!L-rQmUwdd5iH*Mhdjd8 zR450UgFDCHeUVR7C({8BhV^@wVO?>J53YDdB+jsTjS$D`YhU)me{u;2kG5q7*iTni zUV%IBnswa{d@ym_`{0F9N5P0lwaNT?S5`LX%HBg#8x;@c1>7NC1OCD z@Z<7taN#4n>6Jg{2Go`Zz)aUrRAC@V6TiraMpF%MvzH4mJjz+N11(qgQC}%=`N&~P z;ua6PKTe{#+%ITvh{%@p)FsNiB{>ht^x}E&+6UN(fConr4<3hV@hPA4r0=(%jt!MH zij44PT$+bMcExm6P5CrAPmn9{R!_Ivp#+-r{88Z~aUn9;hZU8RM2LfY|P^Gy}T zA8)a1&+1NYoK-C{FTrTn?uJOE{I*mz_=vz$o+WL~3l05@q|Ba}UCJGd3wrF+!03}H zE1#&5r>x=sH&T`@tnr2=6;2}kiTVOi7HvG_xJyhE!Y6EtD27Ui0+3eWkt_hosyjtcs zUE~|mG(oushghZB=-?X2||$|`V6S(Tf9-o@~KB``L6S!!0Jm}9Kg@9}`n z=NT3j%^Z1|*!ADn2w`y^8mjRBT0hrmlEQdfjcV8fcMzq%3$0w?b<6i+Jm{~@w6YbRvylMSQhrQLCXfo5v`FTOwb0K1;HD1yXq)V8`G zzfM?HGW|&suB3`#{DtT+_Lt~l4_-G1?Ilg^>d94$4Lz}|Ihvv)>sf!?7ObI5y?wKf z?+6DhHZo@5`+eE(cE1X55C-4t@aI`mx+s@yZ`3y5Yolz*MGqUTM?O=$#n4}mwLf1@@_x(sk?K~NM~693TLVsn$ZHjPdO%Eotai=ns9NnS74&1-3=P>bYh4fuYmZ1s$fR3~`BLp9;I|ktMGphcS!I33kZL?tnFx%6_KnV0IN)I5B>a8%a{vz{ zGg(IY1n`a^H>EG83Pw+V+`K$+=o3c3OvE#(^7{~5AeEH)Q-F-afRdH2}(LxFjYyXNFBZ!ts}8)UE# z^^F1LdY_u;bF-G|se33C=7j@=?)5lTYu8#Ibw)jnu@Tl1JmOBl(k=S(6t^c5*Y`jo zY{u%prl{+UYna_IvZ>|`bqGM>%2C?OwO^*d@B+8!D{JffR6m`cIXDRz6I2Rr`~LX& zi!)(da0Yn#O5ZTbdTmenWGikGaJ+1D*0i=)APnJwEs#eJ4kME%q1OGi$|`=|A)LcPuWZ!b=<#T6%(3+NKr=2Jd5kb+0J>bc7>d)l{+aZUx7QXx>su-VM z^<&)HVI8s7+EK+sZj&F1bpHo3k$+8>daU<@;|n;eTpN@xDY>IZ$Dfj>17|t(1Pg6E1}C5@XbAJ+qgLsXN;?t{mL#F{AD-c*KEtql>wwW8D54`y7hTaqH zfHK&olJVnvaXOE7Hh*Fu$1qStV~ib|1M!Ba8|uY&cW^|QJUHI8VvGX(_T!?72A$zw?$ zTuEMw0p%U=c_sd4ATh{WA=GqF&wqT_?4%MLfHrx9wynu%_DVSR&I?NPWjA(Og-}Xx zgR~zJ77g$=b*^e=!)+o31hsV;c>^L>v24J!thY5P~j zDLK4ZOL)SaQjo@4ZL`CXudZma7b|?euXmv(z*xM=ryh(LsK{m}Jc*!7$#Tzkj?k@_ z!UtX!#Awjhd=}*|T=Mjq1Q!ss`u89ZKoi_mlo3(ZVbf20WhIg@b+4o^QVS? zAYa785!P`w5MPwJQ)c5yjMHH3O!^&u?*rgCxH4v|;i%yw%uiy7AnOCe&91@2v;zom z`Lvt0^RHCf*FV(6abYe%NccREK5g*%K(q>0+aO=v_#Y^@7e-RHD{o8IUJmd9mQD)y z{1t{DT;VyO4;9nM5l;H9Zlh)+@8KJ0tf8e7Az5-{G(@B-XKIlxcz9t}Y6fRxgR-iF zwQ!T(<0c9`1HlUFQ#2NK<`QU9>+k^u2VT@peU&AY(z`0NxBJWjcCJRCg^9_+nM}st z=jzFUiV0Qr-J7WkH=8MVIvsY|^j;He zyC&z3SOppR<){g(6H`uespHGZBHB`=`VlkF|>Gq+1`T3zYppttb)lEW9CzBerX>5X?YQz6P z=EiPl6V7n%0I!7ldiwYuawFD!sVk4c%fMSG(2#=zKHugNJd0GO+qU?Gv|%ApW%O9{ zWs9UCqI0963INrN#be_DFXBZThDS^%ow5Rv9ry(ofoAr*6!LSBOjwNvj|Yc#WX|sa zCm@RgWOtr(Gvk{#$3o97-RnC7b1!jfaap7Fbe%zXa2bl`pJ&IDo;1XS8VT7i1Vc`x zs2=ri19p!M1>{ZjS@rn9`3fub4;m3(nKSllG48XxMsXVB_7&M|)|+Gvgv#ii`ewNe z3_g_~@?t&alk7D}0-i0f_s!sCkZmApO#rI`U9=G`b_Uiwy0Mx3Q`X{Eh_+<~KSyUc01xVd68!%N8=9S!=fMWb?mRYHmuC;@Ev_Rv`$-5;v*@`qo1J~&_UW-}Y{!EeOy88k9lX+nii zHMV*h3f->vFo+MY!s6KHRbP3}75U>i6oL8%P^#&nM9qGab92g)xZBo_KUfI6L6}WARa%t0bG@*4_<_>B@ zsqj*rdN)MngwA(7p$G4p-rOadQ@QTC&0%$;X3fydGWDCuD;Cj{$TM_ zWuFl~i}yn9j*`d5*DU8l!SoQ@L9a#Y+j2kk&3xe4UGB4#UzKNH>K^%-Uf!$BV? z1x$ug&BrWGFMc&~rjIM&9k6kN&q_>Dk=!j`!xC;d^*xlRnC*eU1kU`{EH5{ROn3`u z@j3r?=~WQS0eQd<%F~OL9_<&Z|AIpr6H4Ex%sBFah4wBTQr6-m##*nfKht=7RU*TR z*c-FO{6o}UZUqlxWe>n={}p(OB$TOZz2VfFWW53b^OMriCI!2tx!=c>StL`p4h{oe z|2Gr?*X?=&Koa?qz2c}RWCrjl60D?CM7Tb1L?wp7!tlqYcB_SGk9q5 z6rXQ=`ZW2}seZp4+&uP1`n$tbz3g8og7!1B_wQbOl&DN*vUJ1GiqOr$%H3;PE5>tD zgW(3Sx#eCBlQ;VYac!X#?(JIpUQC&mcv2$B3Ze(>aI+bygxqm|g&O{tN`m@c8Yw}7 z6{xUpk_!5~YA_Hc(7RwWUdqE)dRX}lpx=1XGcEJ%XMddj8l}MhCYyPWyHzb><{MQe zhSv)}%R{0bnMrGxzL$gFtfdSp9VRk2XJn#(AfP z{BUzF40(gFlg&gPR^QGF(RNQYCeQDt{{!h5zjg3{^@OmGcbgb?dor&@oalpL^ZR(= z7$<~WKvJJF8a$oV`2JYS7;q83fsUORp;B&RuCxobMIW!JGRZ0&>jehtw*>BQsP*`Q z8UT*cx32;7q_`QM|CRRiKFZ`_DsA3la+->tgD>Y`BYGeLq5t1m&`0bQC9M8dMgjbun|d9&j$TwxiKq`kJX0!$Y)}Kq0%Tk5a=g{Q6KGu@sQ`%RGF>gjT0(S zYxq~T%S?!C+j1jE!3u{C??SpSzJJc8HzugCZ4hz!6U(sy>w-UCdG~A# zWA;aJT~hw%v7T+qQWp7gnMhgvOXvYwrg&o@mcu6=Gh-lge0p` z7>4sMu6-4vV=QY~TC?r!lP^Y2&rL}9%Veb>AkGy6VJ#5a#dyL~HZq;Pd|Ua?pO7vPjLs$-d>fDq^Oy-l zJv<+~7q%DKuCl9X(#tB%LLva}9c8cdrd=93c{#+8fXl94e)c$V=WPYh8V%Mh{9m0iySw z5^%rc@ynu!POV5&2%WJ5ht6kg??m|WgA0o1XYbDCJ+d7qF7-4FE0cVWSV3tnv!P7e zI)Bpx#yaX}!J%kN`B%YeFPg9tAb7o`wQ!pFD6VP7DnT(X0NnkDs|kL3*hO*Nr8s!^L7@IhSF^v zOo*$hW{I;(J}v=VYfmFg(l`L}g8-djvkzJ8tfVOGo(7}83ktuNecrF#4V9>9PZuIp zwY?pmBc^EOi+C2;(_{_Ltwx%ZDM_cu8TCz<=MpjU0y66Z;a7Y;-(PDEMa; z?C#6TuJ=pH+&;SlBLtCA={W35Q!az!yO2Sv$!op zn)kLt6b^;FDBLZmg^)`?>nyEe;LGOac;|oGfBOz{{vU`c^0yunWX-HA*WFuP*~Iv` z>u2J*{?btqM29-hJ~1NY)kp#R3uB?B%{abxYnJAxM05ML`18VA2@mtSzJ1q{Vg5FG>BkNpZ;S$DQ z?x&PJzw}?#Sq+<5w5%*h$=LnPHW}q`>ZX(xNl6Hf% z-{)V8gx9W2x0?X~A7;lZQDQ67>zd`>mFzMuJdLq>H!Ah#rh6@(mX`ySM>d9y2L$*~ zN?*R1@QE)7$39#>Jv}ce{qaHbm0xwqj=i-74Uk-px{ED1GJDiB`m%eu^5(R`o_r2_=bE+F+b;2h#+5~B+Tf~Le>P6x zPyn7hBErjp+lV5qQSRRv>huRoDnMeK^@~$i(fW$sWu3{$G=6ZqQgqvq5i*FQX;?6s z)C>{5rPCoTfNh=|Vy zP<5>S^R(ydszyJ1h4x|KUulDVOQdWbBDatYv*=fz84U(@U3Gs$MF)ofD4;5U_=7qL zFy&nWbV2iqGYR|k6mTu*^%#xYc;TPvEXC#s9B;j(S4L%qde6vU0!O7n;Hvzzd;D&0 z^JtJ!BY&o}-*7#^I=kYm6X&mtEf|eo4i!uf;GoqC$V3Xj(*puOBYgDCJn+Ks*-F)O z;Q{fUvJkysap|f4gJIz@!Eve>2;{ehFTDqhQ=xC#?(~FmF(j5os|KR7RGqJES3qSc zf(-&Fz0+KNn>#w*RIwsnh*}eDIOKnSyh5~)XTc0m5UM`3;Yh2u#pN<@7TAin0(X7+ zpxC*15O|DVAKa1n)J(-^f0dD;63^(9Za>1|mW&rZikpYb0+cNBz##y)Z-+63g3~!e zK2XDSO|7o*7Y>tXUYh7#NZ6qaIqtm1_q&~;^clHW>wlo^{gM`g3?re7PyU9U&1>E3js3VlS_dO{r~uulAPpLh2hH@*&XG<60n65?A!z zD&#xsC4H$<-tL65?$2GE{?O6$>xxItt0*3U0Vd+kV1RDhCeYWPrSp*umwuS7?D>du z4C=jJeG;W6rkSjs6PrWbQ2}CF)>`E6pfBU*4I! z)wmJMY6e8(2HKB7rkk%knMwwa@9r}eYsblQCwX;oqbEfRG7%fr;??wvNl>6P&v zSyDgtJQQ8GWGLN!v`^pawy$qQG=w!_m#M|89#co-8X4A13zf|U%3{DuTg}@yBq-6) z-vL~oPX}pz+0J>vLrp+t`2K3ThzlyUhlK~XpGSwv$nlZZQhBUdIZtA6<$v)h1qOy- z&i)s!@kNb1ClD-#x~iZ)if|0*RV0HOj|$KdK1=3EuyEo}R6>pM zev`RcMJ(6hA^=KFp8DWrc^NQfYq(%98xj_lN(2@M;NxlS9dV%37Uam-IUy0jG>Ax? z+ESpt08d1?7Enb3x{f}0?}FUeFb`G9Fp7cLNCd>z%oM?+;eKZ7F;zyhnxG!`#FGyO z&j4JnyMJ$;Ywzo2`iyS^fnfN81?_Tnv=<`{i;*|LSnn0v9LWs=+DflO<#z=EQ zE^M&5s%wX}Ar2k%{uQy*-yj|H4AAG<7bnZ>^ zdMXh3#FU@X!ZPVyEmFebPJwwxzSi@da$$NMIBG z9Z~avJQM0kY;Qv@6%5is`oClARMDFe*Z|)&2VRJ;iiVoCgqcj2v9D+S*Da%V!O%Nu$J`8Ve8_QfD@GDpo3(ok}D=`3|0ZS7iBj_fjP zdMG3*CmTP@N-6b8QEvN!@a46BRiu!5J#&;>hg)=nN}H@fa{E2~0T&%zsWDaJ3}On4 zySvv98&cvobujFPF`_bo4Fke->&b+qciRPX_@`3Ur0Kr&oi4Yfjcg<9_03nMBR}Yo}h(UUnNDAiwp$7nS!g%M$G!W9bVdVp1 z!0W5Z^4A9N9pi0dUaCY}+KreU~s%zWYa2kZI1rG!-@wlfLhb5}3K#mN*D)5uyS{ky!d+~}~$AB0Q8CpKs;h`foS8PB3MV%@a+F6cdG3} zvdv&TkgggDQp(q7*BBgAQ8Z$n7G_loN?L1Q+k})}Z=lnA5Q+p7_D_r|wBr>Z*r8A+ zP*og2PO8J}MsUp{<@zW84u30P&B&^9zM zvq^I6t<7Eg_(yf3wV7t{}g{W zdNb|@vrJQ51hoG@9g=&$mL-Mfpvd*s;}falV_gIezbV)S>AH@PF>PcY|@gx z;?)mVGsF1z@@4u2bA%$oz4lA2xsD_{X|Reog2{)01iC$`>o~t^{J;jKRP)P^NGTcXuj+ih~53)q9#kYAo&fnmk|y!A15J+d}+H9Iq6p;dqAorxUg`Y%1=? zgLF2mo9mwa!(y@kgv%gXC%YKQE*`m=pto#qGaYi4CdK zZBOo%Y&Fs0Iu`?fNdURNr{DC@OCBHbZlNX#i^`m(_C6SxLbNkOK$#~(dy~(g;W)V- z+{R!7JVLixvsPxsj!{zv-glFcoDZb0_Mfse zJR~_~{7d6pv<++6@rmKNZ;0<43x*Kjce1FbZVKxnp7t(`PlMD0caF)pg7SBi?)l%Z zMdMKiGI1*KfHm|_VaSZe00zVebrEk(19~2X699aY&HkFknQ;TYp9);t(2%nXB^qbT z1u5OSqQ-S}Uk_sY`x@tb+fL*Od+WrwpS|Yzn~hu>9n&H`b2cY8MQBfD>9cz|gTmUz zGs_O1SKZ%lUQbn;qCB_S(Wt-p<%-01KdBt5P1!zrF6#WU`F_!{{T8;O9~bBZU9f6% z!0Wvis_Ag$Qv(+YtlJh^?mVjE58ONwZyz2W#WFVWWJmcm?aG^c z=@Y3OH~7l4pCfK6OsLH9svy%iTkPfs>ON$1IBVIe(^t8Er$km8my=th)ia4%@=Blu zn!ITeyWSst1OLOX57;k`o;IW*yS9wi5w%BxmaR%n4Rj&ZZeKY%j^iufz+&%t(}RVo zUq=WrUf}|TVVAf}!t30oW=_>}OGV%?3>`&4MalHllMCyOwj-H;X4}L&a=#v!#0sNJ z8W|}iU_RI4ULFNyZyq4-#(W1E!_}o|p>5;Gs%K-PDIqk!jQ-Rk&Ya_N4bkL?1N@fb zPHPsIwfJ8(JbLRhB}bk0!WwN@j=nE>I`-isprD%ikge2JyiV+@n;$Q@-tGQuQ`2Pp z_a`z%G@Ak=Q@>UAAp5z}cU0O~$Llj_wuv67NF0t9t=VTzY3 zLp;aOGU~*ruM`8phK{IyCDNgpM{p&#O!N_8>RnwDInbhnYvDbk?KtE;RQSwU(BhkMHdM zZn|@4+Ym24aTmfHM2vW-OZ(5qoNQv1G8Asr7ub{jDwo~osv4(yf9wk3u#I)X>P4pD z`w1MdRp|g5He-!$8Z#z>J(jIZ1JrRhOJ}h($nnUim@2VbaNxS+iTrOJGv;j8WUjum zv?4dO{YN;c{4c6~wWAq3;4ExTII_Nfa=>Z4p{6IbdUW;3-{_-cjfyV(`b)qPjjxNn z8n77&LA?7GvheCG?Zu?7AK@(PwmSSPa+#3lZ&xM|)YEHvemKbF6LZLZb_%cU#{P-j z_ZEzvX-NQE+vQqt;&+ttykmUQKTzC+@GkOM(oz(Yp$C06m^>-aGUyT0CfX|-u#&0( zLWK>N?-y(?!Zi<+%#I=!dwL}*7&#Z4ubMNen_j23Q9XIU%(%Skf zZ>ZY{guyoIPfXNg{`e5j~hWutIgia`u|;+>t)!vx&=U7BB!@qC>o^1<*yepO|Z z#cu<15BbaUXUJzQ&hT&240AeaM8*OBQ-|G{+;1%g@ms77{PwWoY45Mkeb0V&_>fM< zma(?aZoo<#HfXRNRg><(VU@-oz|mikmL#)9E_Idfi@0UNC(Oh6epNBxP5ETVZ}5Rm z%~6PRevt8QvXxUz+1I#0rRz=hqr?>C$L4<^{$;%_rVI9o0YMh0*QqQMtx{Bt4_)6& zzrru>EcZY0y_eqo#ydxbaBX!?j<;b!+db(YS1?|*$LMGKzD~2mzU(r`crH;pK|Jg*aQ+Oz+HfyT zurqI6%-{8L4t)*kk9v~$?p|&T58J7O-FKKnpB3D+%=1_GJp%K+hB=SASUW=qgLtIi z5l`tm^Aej7=56zdS_;^ZH>k=2)sB!6{F6C>vZ$u*gj^7nh#*r+a^uAa>wZAhSVR?7 z*pBE4$@BV@$+ByY8?fiyWlF^q{sV;!;Pi?4y9AXcGdyrFxAJlbzI9~^3=}ZsW%|_s zaTsEvPt^hFWzf+!gXQ|#amgEFW#gKO)ZB{zYmMiq6G(pFaQLtAeSUw^&*%PDX&cmy zHCarLwjVcJicjTUgN6$fX$<9YT--qErZa;^`ZuzRf(P)nGChj3v%juS3Hzy>4Cu#hb3)S zkQbw4p9N#_l}AtYi`IHKmErBpW?#D+`kLPbu%5*sc8M;ww zog`-|HAbnC`2!WjK(oz~Gz&lEHSKR8?{+YT^|)l?sPIr0IEjaUuc%vJeBC*zlK{9W zU!xzRgChxxgxX$cYgj3Tg>paIIRvCT2TeYclynZKUb2CiweBWB+Iegvg_XQ#tm5C zojf@(>h~jAJp}rD13;aa?GD;K4WSRxMa6~uT!7HdFlHl&s)&$oR4I`bBy4nqfDSdE zJD{p6BR!CTFLQ+j!o{)6&l}t^-PAiH)T;373EG!DpLlQVC1pw!9EIe~ZTyj`9@)H9 z`(qYk(NB(R$~5?NghvlEv_z7d%sY zcLBPK+Oe6H{X1jns;q=4Yqjxm9txZ?N_ib}e)ZR9?gDz|u@FaR?Cqqvf1nbv@Wo#X zKMeXy=vW`5&sXeIgbQA^t~%a$Lh|dBgK_sc2hgvUZ8x2HhgKOc##S z-OvxJ>(Lwn;g8o0A&_FagbmvL&yMfE{6Glxha&l+(eMou}7l(^Xwsd ziu#Nn{KJgRj*Y_ohV@d$%=-m(t_kgFXJS}3A~FF|RgWrpg}wyt!ieX^*VmVNUj}n_ zIh=lN3Xq4K=tC^E-}W76MFM^4gqf|{52vw0qF@^m{n+lCL^3SIktPVkqs7N%tCVfA zeVGrv!uGf0CfLpw&Qx!i_9}bK%8<>#HBP>$DUV=@+c%uCqUEyy_gA|{SpU;13t>I@ zweUkb7FH_x@A(|z*sfEP2>CycI)GF)bnPRUv!dtJ+VHRZx%j(#q~(3cj9tFa6#-P*}?2s$4o&tG2I^G6mPoWO@R)a{bviwmXnmj7(yJbDupJWn?3fMJI| zvF&cJCQi%2O@)`)-o{QT&!;G%tiN2)b#vY2suM8z=s!@lrKx=9N0#>v(_{2T2X9W- zLU8(FRF+iMWWq6&bGi6@jAz{F9o6+b)p?ndP$YK%jMHRho=Kk&Xb)Tk9Si42ws{?W zRBech6MX8@k*^FNoeIuc`=oOP^Tki@`IGdEO{@V9<6O!EGD6Gh>MR7BI?60RI@zIP z+rIa-QKhw3=lW${eZO;mJ>Z$MVk)8E->{I(iLgD_W8q3DsXX5g;FgAfyk&qWf!3>4 zFBx1t|E@ELKCkC&`uh(Q%<+l}7>%mGZG3)#1v6evpjw%_fEDxLu@vrNJ9zmJu=*?&tah<=Icm5m2KaD4 z&2sJ)MRceRfoS~t7QR+;I~;%UEhdsBr}{QdJpA^PpFu8r=`QoWj3Ms=Y4gqRwk3KS_FR|$}u?a?{4G4d*9-@w6038Yy3GZl~Axu|6$w;QS$7>4v&6g^)_#B zs;LNQfD%T=!%CP&z<(#FLgFPJ$onlBB!)D_!?!0fyH9T|c`69!`-AI|e@Dx1cgTvl zW$!c$LDYr?7+<`69ZfqFfMgecZ1$bN^4MI6*N@?CL%yqarY$p4w*IrA{jbd}iiV5jmpnh0g@ z%US;@cem%!Z3!OhBcHmbdI8>mJ5QnNR7YCtv}&aHw<^SCm%>eH>zTb)PT@OmH@XnA z_*BBbFZ{RZxe6M?#oqQcYeb}RY#sNt69;Y{_#BD*4BGiS>sLkPm)VzS(M+4*s2klb z2DYc!f3i9gFh-wBiN{W!ywN-YGTPy4{`^k)sCW+B(ZU(fWOb-Cw=sAXWv%WPna1MS z<28J|W@hXv*i3|K_nN+-yQV_~d(JNr1%NYW!!-B5=kRe2?^qJZ^9oPjS|XxgH1ygh zfj(o8Jf*m3?6UEV@GCWmUbLqFBG)n%eTsY)Gx}@{ytvpjFb)m;4gn@Lw{OR6VPC8$ z;9d0TkC%ltuL zR#_Osa;$%Z$bxqU_X9smjo<y zn_9Nd8$f`8P-ZH?Yt3N#m3&>86~yuV-4q@Z)Qne8u=ra(`vgZCT@Qykw7>qpDDc&6 zR<1&QS>V~!eEDzkcW8r98M#Yd7~~LAh4@$-m=(%IIu14dJ;ELtJ&)jcwbSJNCS_E* zq;tig#{xPF!>?K4=UJ4Czxauq;z}^|@efWS?`f{8e0bjBuMI3ysc7t#S^CFp{X~d( z#Ra0Ct2gc~gjc+H-mqag#xQV8$i`l@V1TmL?G-wh_wM-1ijdnjkYk!LqM*#3lC~$S zekCrQRc8}?E>zF>;s}~Qn2}51HM4=$yDf1324Y zQ)|PhDW}4F!6!7NDQu0>BV!Oe3ScK3&_MBXW=t>92o-aQjUlMcVxteC9NE)w3|$Z zm`3CoHdPwSlqI;ej3Ze+ICiBtj@O?5YODB~f(l>OvO@CH#iihI?UvW&w+^VCbs9{q zaUVPUxZ%R1_n7qAl)j&zvhN#$K~DaUr1OquyMOchlZ#)a-~6p~I}b z+EOc&YK_=CM$u{{)Tp**ZECeA$jNZx~}K* z@vwx&V|z`%4(2J}{L@_Kqs89)&#|edaP`qj`o5)6JR^zj(CWNrgy7AqWY`8D|1(gB z>Jl7CXq3s-f_kY$FFpD2gZTU3HU|76p9b$3FtWGF%zdo51U6Oiy*51mrMKg&eMM1Z zB$*yA_~nJx&tZNAkJc4 zr41)iXPWTz$t9Qjv!3SQkt!rHtMK!$->DNDtL^rcCd)Pnq;rX{O~*95AXOFZubMQ) zlL##2p|o3}!dZ;mBRYrvIoW(KnCEew)HvIV2#-=e9R>{;)0LKJ`D@S0a+NsLtIaV7 z%iChF-(E~R$lKKx`dfWXR{r~{ZRVn!Mds3n(FKu4%^$#+cWY7ibBtQO84+5io|;*f zr(gK}(`rr^#V+j`hyTlve+yh!+E@Ph?xHNj9QfZg)8Jj$mk+<&DpbO6AHitxBDA(wr2Vt99k@2kc4w9%sb=Iigdny5Lj?(%}1b-l3$i z7mh~hRWqXgh~s;dS@T20M~bJ6bpU$`HW4LG2bO|AtHY~pe(NZEgKe;`Y`C#{)`yX^ zzArl)YIW=JrFZ@bl)2@NUQ?bsly+KbSY5y{&QEq&Ta|HmY}0V9}>ioV?gKTRVWFF ze(CIXQEb*!jmKW+EKe4Om6X@3XM_uYXbF32q8YfsM3C0Xc2sJ{P2ZrVrgGBzqlTVAB$#zSwc3)YlB&o=V&A^Iok9!an38(QAD>4I69 z^}tbiw4_wu(lDCp>?Ea|Ndi1VFF`7-QG99$%lP?3=$DFnFsdNk4!q{uaR-sG%VK6T z?ey+<2)Tb-lkb7*EycAFgD3fC@j@RchZklt>R*fd{09Qv${rS6REH46AiF^g|A7*n zAnTNCKxF9L`^l;7{rPE`kdOa?wy!ZUe2$8NFij}r=nOEG|Hc&`LtAj|JJYsDm{2~A-##2 zPV-RH6kqz+olNjUbse&Yr|$mfD~X!loUPP69zM~6QkTBnJsm=$J?()We0?w-)7%;N zKwgYnHcse%ruHExX>-?#1`vu>S7yW?UHPf*!13_9s)l&3B!A$@^JLuxn~Gcz760Z9mSxOzKZfl~;?$5<;};+zkh$Bh;y zV|*Hl_e&W=B;2m?i8&!pTZ~lcpGKzHDDqQS%Kd5ftArXY~# z^`&fw2}(~RGm<>rTu(W}?SB3u#{UTc5zzLkC9yAbd)QQ_KVt10NM%hMG7!)aG*TOc zY=Y(+EdD$&Oi<~#__Sw1>rc9E&M?jHqs^j7%Zm@$u1Wbd4TS5E8Yi71?xP_xwQy?i zE3WqKy+grDowz4^V3X>$IW@)zRInWpZ0?( z>GO};JAT-h7Z(o9H*RVYg$L*m^5{4GQncWf0GqB0B0l`Sxkz4}SKyNL-+Q@d>tw5e zz1Hb4j+0o5-u^9J-lKOAsV$d6gnJ5&T^Q?dHn$&ATRQeMk?Z=!1ns)0;A?Bow(2iIY{8kGW z>4?~v0~t+5pC#dbXyFW~cYPP*L8@8kk^n4X``DaXeglQM0@5Gx*)u&W(PBHP7pFYi zu)S}Z;e<`n;BEn88^Ql0$LlVe0O}@?SaU3LBrHs_2$Ge4*pNfWf=ciD74FQ5ri%nJ zHTaVvn||d<@Bm;mDQu@gzhsecb6hRR0$GNa{gcu;WdwWy+*6j`Pefy=dZfn(%^_mI z1xC%7O)X{_;C5&WSK%T@qbbm$!RWD^Bk5b3Wsx=Y((^FUA-+JkC>h8RFPe~NShlW+ zHGEu=Xl?pQ0*_x8bCiHv;gbyP#2dLiv3IHjZT5k{4)PGNsN(2e~C=N`)lIk0Lu#O-ZKB>Ss}H><$bD&K{oeS`yJ z`-L#Ta|phAk7rxr^0CkNutq{;Y$&y`eyNXd<=mkqT}uZbJTr zrYWlKb1kT0^G6>Cw_D$TuYEpz%bZ7ckOSQ$`sZgKo`0;q=)t<&NUK6=OT5J(zg-?SvJI0a=9^qR~Kq5;5V!_H3?t_dBjwSW6@1EDoj%(Jpmu%ykyxb1y3<-x97OiyIoV^JI2GK#sDOuK0 z59QmDkFiv-o){$fCG1^>KWlE>{4Kbj5dm$!!JD}7rqc_mOu-bnnIyNv0P75-{HiLO z^4>Y(;U<&h2D+1ce9$ijS4O`^ttdV7s20KW6Jl!lS zhv0uTdgxdjIGM4l-E1;S3--VIhTN%vrj~<{4&lbZ$LYl{lLt{T797T|7VI&R1%qQUuf?faHHyf4K_7t3ySzZk zNGJk}Mr{{{9;j@9MU+_u(yihM;2Fa8*w`ySN;tYxVb?$Br272qn$KA7e%82(bT|BK%9j!lNXHRYv`Y&&q#lEYsTbGcJq!SWX8&o^B=cA6C2 z{hfn<>(hh;<55oH2rnzKxf2oE^Vv~Z!mtzb3SEoIo+pj-Rv}%eC53wrj(RPJA1tau zM6nhR+u5pw7^5VfMJp9jbPZZhzHWBep-qb5ZbHO>2frN8)a8}heOm4v%$V}&VzDYY z3YV61NH5iqcV>5AS=WQ2Gl)6fc%VCb(uQNOZdU(wD7&&Vh_MEIe9VkL&lGE4FpF6n zVifp@vX6PO^(fJt%&-QI^< ziQ6jh)`g~t<|Xf1VnK%7pdtuF^v}?{pKrAM*ZYIPcRjzIX(M2Ta_abCsv2xr^xy-_ z2ub_)2t@SG0Z7&Ki2l&ae`cLI!etK!y3OG$ftckm$(F#SP$yD~uh5cqEl7Bea*GJw z&R>w%p4etwJ^IbYA0aHdTj<-x<_Bj1{vdd8)L162p7)Q{+h zt)l3f;3SfV0Z6AkR(hOgr_1)4`Q3JKy8mIHev5|&S%^&8xJrX#H~la2tjDr)I9q3) zUW$dn>Ffpl0e%v7KsqENjobhY4|j86m_-`=br zflEQ6(VNU&(^K@Qae{q32P*QwKxf2;KB9!0qA*b=U*m`w3hRagc~vUo{N}aO1|P8Zn2eW zi&oIPQ8{re))X1}N(F#QY5HvB?0tPC#HcS4+`+VpNE-kQ@81j8g(H4KNAv%9_x=a+ z`xF8FzM}=zP%oNN&8so!#|L!EgD56;`IB5r!}_~cId`OH9ciX6jKVc1@i3+MX^OrnZ8ezQ_UzP46nG7Y99kc@BcK?&%ai1*lO{q#Dl+2Y~0+90ZO1pr&!nDo|$T1;gN# zkmeo6Y}+d+4_Xn!wePzUI`JWdN7dOP(LV9|v5n(fc`^7Hd5)&u*61|khgSbbr1z4* znO9ooj+GA<{ddH|QgEHhm{iTu>-V+#@*qeeJ{7h0&Kxq%x5Y($f-LR){l8$};`ucB z-mxLxQrtWc8Rj8WLQsg%qI$ZjX-0JHk`l%3@j<>9hr$AE@cr0^y$i830&b{it1#Ju z%D?#W6m59Hd|Z}0+vFA?V72Z)bIhp_+tTw z*RxMSjf`rc>6q_;%K~v^#1c&b{c?|kkLxX8MEK@o{xKe5)|~kTWJhl}j0()Dv8IzW zxoZtMpCbGPKs+7~=OP*zv}WO3-Yu8s!2r0qh@Igv`5L8$&lo)Q4JxHHEY3(;W@?-~ zs8imiLid9qIu=?cktSV>Lqs}EPw1v{94^g1DoQyc;~pS}>oEo^vT z-s+hx`$Hm4*5mY77%2^vWhkQLkmGT$_lI6DAlJT0`d^@49A%$VhK+)<0U8oY7qXSC zHdjPLj=uHD2yKxw{sPwIUc$9f>x-r|z{f~RA9MfFTMd)6QH{>d^UTtvr!Cq~yC#tdrBH7q8jyb^n3nunU1XJmKoLHLtZb%;)Dq0D0f zs;P!ib&kWVF(J(#HK;<@jqkW(-MJ*@L59?UQ+QB`#Clvp1w;SdHB8m*8#i8KPg^I9 z5Pl9J>nP8#s|^duu$ualJQaPjkg%wv57UbKh+<|*b z-&`e!rng;IkBnf%@7X-G?wPCALlo1+AAL++o-vv{eR6rM?r{k!WhF_zofuY1c#v@; zxMQKXt+g721~789RcdjMER+aIHc$g1a=JdYzk15ER;w{>R5O<1vWKU-?Y6hS9oyCa z=Kpq5>Wai^y}T&LStk%6q!Eh=e`#xd%cn@+iJtC!GbY6TSa9$6^dgkD^{&C$H2aHZ za?VV0SH;^iJ4t#sEYYeI`5<-arfkmjKPe4S8j9y71>{@FTMS}t?~=uy{^hxnMeF)x z{nFhV8bjGTug}Jh`o@IF0L|kD!=uGaDgQ&p(Y*^_>tWKgyL*k4G{cKc{lbMDVJ-Z3 zFMVE5$YJac|-vjQfi~>-pL+pDW@44)m#6m#-Tu7KsS%`l#(ucKyLS;{LUT!7C!UGd!DoCWRt8R-R*K!jKO^`Fd}#Og zXUxuDwhgy=g;v2W>h%O?d4rgLB7|E}Z1nXAz~w2vN76ztaL4Af6bwqt5SU22StN9u zf&rV`+*^>vtcD3eG&;jPGRld+Uj@J;47A8{s^<*FXHSS8r<~`sy@P2Y;Se4Z-@!VM zJmn+~D0x0rc%$;GcckUbJHyZl$08*+efPA2`n{CJidZ?lnU@kJsALaC6y0~mJf6X( z!omAH<BQ@-i37kqhjUcuzF&Oe<>gplAzHA;$3KR#Rvo8nT&1OdLPg8Q+f zPaaLOZ}rtpv@HBhGSr~2wI8y|cqxD8Mswc$x*Bxx;7c~yybE?~_sJ8+@kN!!(<%`fi@o50k(n#*RD5O!CA zP4tre+F|uymz285OE1&eDeq)g5MnamD$c)n)7@1_;WOXz_a3c8mMgBV zUitU_yMTWAQ@I%5kiRY3kLv1wF7f6^s3}Q^v+VDL;}130X1<>PB~k6#e$m@mX~KHt z?UsBX#n4i@T0r2v{6n{y6LnKNd^t{UpBR*JjJh{!vFtYY%xc~-E3g|j?1AQrsdGh8 z;?_rzyY5Momvn(64_2$RMARvCSqG(`nr`>FnM!?1J^*w#2hIaF!oWP_YvBJjiJNsG z<*|`4Uipuu5k|n=STfOP<tl(eD(Pg)+5PY;+^JuZ*-E73^F7ALzQ1@JMz^D_2;F z`j6}3j+zUG%IYIIJaWrVz3Y0Ivs6Nf*!OzTt!9~~>Crhfht5Ig`#m3; z2M4D;m@yck$Wg@y>DbunS23-te#$X@at>rKi|MRA)_{Qo7dQnfhh;c?h#G3xVUc3U z$y(RYPSX!fyX|6caAN=?!}3h5y*8XJi-77>crfD~03MEx%q~L4dvSW3qV^c@Bb)}j z@5Al*q=P4opFw%m2{6-}+7p!QCY?z(KSnSK1`z85ABq95Tp0J4VL z5S|-M00vfi`0a0j{hgy>ofxU%O|e~#6=jN80T)Fzid|yJ3$F+2QK>Pd>mtf%kp$eX zd7g2Vi~Az3U!gXbpH((hC(EG~!ozjzV){ZW^v@U(Hmf0ccAK2$tUpmkPo)f$0rM;PR~Fn;gM;y%*Hv#@kR zQPhMOZv2~3&pkOW<#LHrSv}^aT0bR-J_!=B_;9G1e~4+86wY5$&n?Xll8&{MZ*(*( zT4Rvhw##o>?B=PK+U@$8Sa@A`yZ!+Ryj7lz7+*EP3Zo8kycB443LV~`J7(V1)$#r4 z7vO7&6I@UK&^|gph#tSrr|?rW2)xd(QJ?tEEX!&pg>Vo}Dli+8XttBI)UvnEz~%tJ z6h2j}TS`5EP6NoFd11PkHh)`6nQtE!G!8w|$EhuzR?0Xr=v9i^I*c{aw0#mr(v&{` zM9Hvcc>ovxB?nsqY^ba-XY8kZhKJ*SMs7#(1yPvy)ng0u7u|zAx1T)!(%}tp!Y$j0 zgxc%7~dQw~2lz9Y! z0CGkvW$?I=9x&U@z0zWR5~wk(C#<0>zj`*bPIqL>FxZbiQIPeuM*n8}mv^+4sEI03 zSRd>J=Icez|N2`W*3QGlf%->-4$EO$*QpSK6Y4Yn16>hVP6~rtjm(aunyOX$%qcW@ zx=5GDFBcg_oL^82amMRC9;^U13;K4YCCmp+jT6L)%m3(HihDx=t=lGj!)8hu3d+TD za11o4Z8769)ndnZu@?AT{0OWY1(l!yObITf`j%ml7+{IY%W1lEdrq8(e|gd1xb4}g z@L#}z&t8GmS{{2PY9bhDbVSAnaGiwGxHaJIItkte-x3Daq?~C3p@mlc^5`;~qX89? zQBk>8yFKO`%!Xv72g*H4PuLK8&g#lxnz&2!xwjXALM$UK2r>S2tcQFM@CY(%^w1DH z3I_G6Tq#pod25o|%1k0LM{|$6Y9BT^y=G$w{f~w(eJ=*J=fliczdL0Sf=z|AOlb)H z2l|~xWgbhG7Jh+rddaZ1#yS;TH*SL66LArad=}`nw zV{mCBXV*|W<(od6eQiDUS9$I(pV6BU|3fK?L9}<8XA1BH09?oY!hp%F7Qi}vk3NC! z-DQg~s+=`A?xO8TVjI8%bAUVM1#*>V$wP^vIVN~sF*GMB!--u0Y<3{0Ps+aXKP4Gh zE!=4sw>C#U6G;7bO8d#h?d`g|5}(tQ?|Z-5Ln7#Bk2s#BM*Uj7*YZ-IHt>bkmGr*S zG6;2|MKcsRWeww;x7;^)TN(k;zl`YJ-OD%%;cEwRZTj%oRloQVm%A*~Z4-KF*T*yS zZRlbPY4@-J6Oi*)FDDDUmii%KTc_}O$+Dk<#MtW!nt4>Q!pmMGr?EySo6!CbudIld6j*J*~{$>U%I(Yxc7i zoX50MNfho?m~-)@h^D3zliv;gI?zg3cFxetoyhBAAe?}t(v@1s#fuGlafVsVi+yTH zhBQp<@s0ESSzm4H0$@-4I50oEGAYGKwqQQ#kFf?HVcTJ-K7%NVWrQFKJ}$YlZ;{sI zxNn(ve*8gyF3(+#KxisDT{O1D`fkM=sCs*?YlOUUX3=2Aztbx(X4PT4nRHz>{<4zV ziJ80H6~}saTV4GYPjgY%x8vD4zlI!%c zBmhA96mVrj{&GfO)doeQt1teb`3KJUF5jf1qz=8B+SW@>=hJScD$D^I)<0ScrB;|((+#|Gc`3!DZ~ZVd~7{~aI%qE-hY znOcLT9~zEM9XI+?KE-Kn5)rsUFBY^NT9FJbKJkDAhAH5XKgcx}_WC)WATctR)r(5>5tl6SAC z9gdH${!X45Eo2ZW;TnLO+#>1znA7bu(Ve*eKns;cp}g;1McIE``02N8Qa(;;`~g4n z^d7#$zvbcGUmCkNbECbFQW$V?v4YHGce*vC~aDl88 zGm{BE9a!Y(m0san z66=1v5zs>R(7x#!ot->`kvaE6w7=2e-O75{3OU1frL$7IV8nVRp_fd&|3ZRDUw`mX zH$$8YTHzD_evZJ%08@=?Wq#b&oGnXf^8(Ek4Hw`Z7?ElWu;1!OIbI7CG7KCq1qrY_ zZ?fGzBT~;FJuhA4x#b+8n*S{jf}#p_Rc42uV-BZf^Iv<{B9jl}sp9C=Or~10!3@fl z4W!e;T(H*%%p){V$jTnoU)xB&_n<(rb{aIvW;PE|^01K%0d(U<1y62CvyTS~b*kd` z%T8VY8I|My^$jvIzNEtSm*@rBC7SGjqGIM3m&XW*-m9nvi3rS*h4Uk|fIaQ{tKt~7 zP_rrExe8qh{G`FHKflg5jQXsss;{F@Ye z{}p9sjW3|JekWyQ+!E)e@jW^+x(O~q(KPH*BgjJ##?m~-0x@b%hwX*oSwq`)3e_7G zD)bqcq3T;Ncyc5mBA7*S&~2&YrW)iWv9@y@9jrI$`~EpI+23#jEi3}jmcTs{zODpW?z!Xv8??VKwC=J7lXKv~W$67;0 zb_`gin&5iNDMm*EBN8+1<7;7D2a`~>f-4Lxf!x!Jxurj}o<&2&V zXNAhG9SB+5H5~U6$*s&4=d(P* zr$f`{hZ`}m%R9dH1?qAs$dHRWe}aH2(9#-HM#Pw z4rTOmQ(x{``JI|_{wIavm242Q@-i_y!84R|U8{T=!&dwEll)t2=@-kdZhcR=Yp<|M zpod96I?$_L|M!jT>tdd~Hft})ED}M?h*0&hJ{BIhO5%1cdGA`iXR@gbTsp5@^!zeM zYCZy$pV7PS>f%fIDDJmc1%T6!OEZ){yvtin99dE5l+LKjGWo~TMx=Rta&6gK-q47* z2MZ-)xaJ`Ke~iyL?1lBriCYP;bGN41%6&8w4)VE;xQz#}C_v5kj>n*UtFm#Rh@pCI zIa~PS%fF>Q6lG7T{iMAsQhk3(;3uhf^@Sbm>G6fY>j11G3(3KDKc=tdN5!SOrkCO< zsU^h6OyBL?-)Q`6Q^XfoPU?@buPBJ)-k(mhzfmmI50Dj#e&y6TH$Fu= zDIEMc3S^b1-*(ONZ3hQ>{HBWO9ck?9<|(Si+?ALZ+xaMuQF*yr^~U&~`?x~Vv7oTS z4mJbm_!5WCa;NZa`ghG0fO~9h4}f+bzKOM6eD_vjSv@3aby4?((^KdI)abZnu!tbJ z7b)dKRE;F>l!Kn-8msk#me9PS-a&drf5kyfKxPXwSn!4q{2dn~A<{w(eo`Ed|5O-U zx;?Lj*Sq`7=usRGur$1+v!(tguhynIp|8^-$RtA)-(8B+7Jr_cs3C*)k0yj)tA4T( z^UkeIKxnKDuwt7G=DgTD^S;Jx)mhn@H4mEpxOKxXCf}sqQAt!Ov8)N?3kPCCD;>7B zg5k%LPyYj=M40Go9zU@JyR%=et?dii*C#_;?7gZ+ixic1MnRMkC@}-)xF~gXe0E@% zTeshh^CjDndVl2Dlb04?PFvEE-+>`!veS}oWD&-Rp`H_LQGxCt^T2b*C z5N)3X;E%5sEH*asKsS1EO_5`QR3oq4Z#^f+73wRvHl${Me(w++1o2lZuLv9rDaBBvDXBgb}5VpQut?S{o0U2)`z4RRqGf}fMqY^?G8~}r{$=p zrX&i_)79Z&s}y*dY2SsLq0hg}NpFa|H!73opn|C$D;6)4zW6R_?C+G#2b@iGh8n`) zXcUmIfe1oor2_T8Deb;9ykTa2^kxbx?9(~Rf{Q(8h;Dt~-DztXyKZ{nS<(!6bHGC+ zt{~u-$(1jhXEnS|-?N*c4n*2z-Wav$Po5TT7B;QlkX`y$z6ZEW$r-Bn&W-&)vC_+Y zUODr}Q8@9_MS0cT@IyQzTyULA5#zYuohSC(ANS>L>c_Eml}@m(I9o}OSK}Us@>V4+ zQ2Y9}&-Ur?r527*{Ap)giP30>8;NVsJ?R?y2ITJz6Ir}$?f#}rj|>o~#A(|uluBjLbh8PVf_e zAN|RdRX7^xBMpA_5Bc;nl2w-xFdtAF!l8!On{^!BW-dol@NJ*nFa8Jm7PS@t)ag&a zHY#k#?CUkh?19ps&5$XAn%m<1RD!hi%!b6ecrgr48jfGf-o1P}WnI|jv_SbQ`y&m= zMy2;r+E=^h`^5+sBa>aH;g|n`S~Ue^8~M!TpE#qIG)x}WgeyVUT5fGP4&z7 zB7IrlQ|uB@K!O;Nzsgjv_Ndb5{!L$MKe?h9o;7JG1sdDC6$Rg%hZ(A8Shb2-$~-Fr zh43jHVvKr9y1uzA7=5Q0P8SBA-d<0cnlKw#^-*U5ncE<7EXRz^oR$BJk#8z1&&unXJfWpJBoLirFaolvUDCVE1Md zF8ETISUz<0XB@V&rq7@}JLFXH{XbK@olzCHPphf?IDk?JGK7Q|1K_aSmT#uf%eyOZj+9%`0;zs-i ztshNH7KFP8R<;I+a<13q=IS;5@G$7eh9Br?Y4*Pj&n;leXPN}&#VF>U-}-6n(blxMbj0B8Lf zb^k)@Ify5ma*^*&_}6f2Mctf@#Gt^gixDdL2*#eJLqbl%6hGp|gamx9rIE$zc=|9_ zXNP!mYrC}X!oPn*J(81ad?7`cRP*?F6>8K2vxSzkYQj%s?j$azEkW0^uQ+)YD&~o% z?(dYS@A1fT3~in$UaZQVvwMyI__N6^TjY!KV~CIE#bGz$oC{|mIZHaodcpk{B{4VZ zVW%TbCD;G-;=mM7x1475Yy^%BhQWRYno6Mzog8&vQ~O$=uN3M^^?EJhJc8G>XRU7R zg`CSQJCvvw8!YL%!2{IRVBcwbR_$V@E;{;4X8nJH8B7anWhi`XGN-w3y4&kTb` zOf`=Z`OLlmvo|WZlfcz`>R*tUJeh(dl`DAVE84q567hP0dpcfaBckCuyB7XD9jO8C z6B+gZpNi|u>01v|JZnWRb8VBFhRnACb~rOE33>fTog>s38F zwv-~H;F_kfSyDot7eIutp}TuL%&kJf$@4~7qExTmN!|-CK=&!E;Y0RS-BgF9c4D{< zAEkbeRaV_&=&U9uqC9h)sk~iWb$&o(0l|>|fkKdG6fEE4QzA6Q=_QMMmZkz%Xas<_ zzf<-@r>qs;wxN`?@k_%)TRzl2jFtthH8^v2?^Df8m^T`2RN!<=eWJGkMCSpV>B#!Q zTF_HA9>sJA(vGFYh9z8l}RmE69H47ux^ z7I>a5v#oZ9^b}U$@;eZ#UA>OTlB|DzWhtJ#jQuosFew3nvMSn?(=^W7HyJ7;XW{gj zZ9(76!Whdw*YKd-=v(K1B?J_G=e*sRkfeWV@Wh)=D@>c!aBZlx;t3IJ@2*#ZfsqGI zhA8*~OmN?4{hYzWGv7>$d8&=PXce5}_Yyvwt7P+?YYqc5A=Xnz(?@Q3wcV@A zzC5lNjH8%s{cUll^LQ$yLT7&LQH1OV2~V^KT5027dTo?ugGp1A&@I868yq1o{w2-u zai9PXT}_?UAA^B3{?7_yv|r^{mcJBgH(0)e#Q<+oYHfIaJ?6&cJI|7gcHU)qouuHu znYt+%1W3HWU3ew`#YS zm9HZ|UVtL5Co`9`XEn}WZ*htw5b=RJV>Rm;zMVLetJ6P`fz;lK$R1W#7q<1ouwy>b zC&NoM*l)GNGU?}6?^|;9noF*b;?pk=a6Yj&1H*kHnX6_GRum6+?azU6tyqdW-Rc_q zP}+wRo>JeO)n$3B8zCyMUi<02RAvXs>$wqxdmdf-AyKM0xu@Scnpi%zSyp_mZ;vPp zAB6%Jd%auQ{|(UUby^scY-Nz13||aoG2>BlGPzWA)}E9i6GXKk5W~>Ylq+{*om{9p zUd>vqSz&12;GGDi?G*Yxk<2($H9_X=h&*&OD>ofuh;HXuvn7 zYtbG%if%oUGU)xyc3Ml*;VA6#iR+FhlmPtl!U)0zO{$gD6b*1lPu&Z~4g>R8{m5#e zPd&uAqN3r=ywoJ4ZsLdtY1f!DO3Sfe#wH`5029Ks)FND+yub4=TJ z@`mB=`Js7e1%f{_!|L54y_1HBxa%YvZYiSz>-qofGU}4GAB@=8SMXHNX$ zmn_jUJX;_@>!G(AdYfP1M1Z{geRH~)X13er^k3`D9K=k7@NC-=`pG;qR3g%BTJ;Db zdb1P7pD@xHNST)^dLH-Y@5jpC9xw$|jR@nA+KEFbot>@Za5&~T5=9~Ho zPybNtdLjH;dB!0SLlfML{k%6+a5ISOMAA-mgciD*)RwBy_5IWI^d)6>9Pr;-{Lr~! z!%yMSZlFhwHVWg@Tz9hWg-$4uzpq4K=;ZiYph z|5SvjFfw|CQEQGe=Jz^>lo+dXTT)Ha+z@2*y1v5(Tv*@aY~NAlkv|846pkt!w8(i} zpUWEAx|$FL7V2KoM%K?7@-)Ll6s^Vx1MCn)1@EqU6Dk%%nDm$RrMc{^u#7KgV zG~&m@Q6k!U9+U6fX8mUv1)w`TXA_;il~X;m6b^}!vVwfGkm#tu1*l#P-;nr*+e!J> zk0((Gye!)F#N`WhCq)BQ<0hDshi<*@GgGjMM`Sp|leSSRFH;>igZ06Zaxm0_hXBU> zTx>r~0PLh91P1;yu_^})R>|N6WvSoYbQjWhQn}e}=?iDoyo(TiWdqXZ%sp1C==hVY z4}Y(Qy*m(b{pj}R+Rzqf!97Mzb-J#Qm{J}npHz69;VZavr#CR=ed2_CSeW+Sy!7WJ0Bn#aoy7_8sECrt zO^bB<45xJpFerOdOV~nBn=cK;-A%#m0w@M-7Z{PY^BGQ;N^%Tj6Gt0m+j#tI_`WAD@>V9O; z?vc)Jz_i5irK&{68nA)1n$}7^Up{k+5R;DG+-uk$UJ)ah^{>f2zhIUy8oB`c3Ftl# z(N#v$R-8)DqqSfMCJuN$cAuSVg<(?%>ea8vl_q};!z0#OawYv0xGVvQ^9aV;F5`fC@Hbsj)EsM)cS;#ehR@Ap!*ONMME zyZe0>X`7{yrgug|ws^;w59)D2SWn~NGo!gW>L!zuMYHz^n|9Bc@8E%As_*yzw`&pH z8(zmjw|l?M$%QC}gF;(k*~4E2E_r-<4)PYd6Yg{PnAH8tBNce5m<%3ptwJI-bCdEP z8O8j$n6mZa_3S>dCq-EOu=`lTbuqGq`0HUyG{Bk3cFtTl1=4x*j7>T=&20`~j%!lv4m_fC# zEK_;_OLS%ZcV%o=AY|=tgJFs;MM!;Ui7zg9@uq!=oyXAD$;L1%L>Rv96I_XyCngsh z4XIF}eZI^+aGG8I73ZiD)zc^#> zMZUewZh>XwY6Aa^sgX)cA z8wVr3(JaE>56!d+HkZGu5mX}_6Dx4(N8Un8#z-!{a8`23!oYU%LT~Tws6=jU+So%w0xs8eDx@ znP~PK7#6U~~y56$)g6m-A12!3`H`UXXYAV65Ub|JM$&YRe)h=3qgMs^@Y(mi$(YanO{q zCaLe4c;yEz)KmE3?7`T%ejxl6JGvKeH}$pg^M8a}$Il^7D<6R>i@)BG>Q*e|8`da# z44Gxk5v;ngs)gd=+ZRs2aB%oa+df9QAZW51o-bPK>ueutBG6bixPaJdpj zc6&}mXgZA@)YT97bzoA9@Om1tRZUciWn>ud{*J7PodZAsTp_&Q5Kim6Vd1Ig{;+Zc9BUMgm?P~I7=?GDf>!L$n zoambr&5?aGzFP>fl_%s72(=ODzKZN@-A4wQdG5M;mJ)ekk46sUfz z+^QHNP{I4_a=(3s-SLYNSLXa2YBRSh_KZk=to0WCvNP zYbXn~K5P!dXzJyr#;#ICFk*U%_`2L`8UjcwWTOC!tg0wR59II|QtB>jsP{_c_@N{{ zb5h>2A1YF9l1N|i=C)r(V-yU3*LrEA<8GpIILUk7e1UU^2WDih3GVp3C zd5uRRaWj~G7N~(9-A(aya~<{C?F`R@E@}XRL))m-#z&Zd!jnLfXEZ{nhK@xk(?d+M zZoX1Tsvp`9H=muT59&e^GeYeBbEBRbD;jaXLa8^X4}reT@f1l^gaL`(dpRJj&UxT1 z23clm8hjsv09^jqizk$7wR<>JGK?Wc$`hY>TLDDbxNjlDe<0j5+m*6oj$JFTw^IE- zj?O)t>Hq!XV;FL(s4Zh^%BdVn8)l@O5_0U|Op$UvpC_R-8#$yB%9(N~n)5N{6mrg) z(TtquFvjQi{{H@Tx#q(AaKG;Rc|RUy8su`M2&5{nWGay+d?_F=?onq z>c)evZuCSWPa7fdz@bjM@igX~j24Ceb;m=iH=0#4*ME_Is6-sBL~Yov$x-iv*;B%; zr}(f3!%JA9A0nn9TTlw&1-(>p!$&DFm1UdvLw(b@Jl1Bo`7L%jd#Js1DwOyja`;kG zx3?o1bRJE%3vtL`+7Agf9e!;F;gCa4Pg@8k!0lYz$7cgzk|HJO3y1U_Rir!7%C8f``T-0Bg>i4WGcAE&I0kju}M&G zNT$S4BnY~_+K@acMU@c84SE*)xJK{%7}?N>At(^oH#N%|yuD&*`UYx`gF*)0rQ4^S z-Y%V<1xd1SS9d^7xX3?L_^td4HstH@^d{gon?_)4STTvYlSZ6$^;O@qhnMU+?*8#DXUUY;~F7gocn z#FW5}rHslZ^U9#;*F1>p`%|8-y32vx9>NCW7~xJ1-u73joA}z#kzv zxp(pu1@5?rsoE8kGKXnyBWn0PfJGA$n=g`--+#^u&T1JodXyk#_#2lmhG+)ZGJX=+ z>-6IrxRVT?dXC?3R2}p6uctC%^Em&pU-wQ`Q}!C%_Xkkt$#2Faza*xs=q0R(CK|bdX5An@i zd}V9%4hep*^xQK%GnNCVu>L_lflsN$@o;8gly)5T=vwTHtMSst=2>N==pj#abGYT- zwdmYS_4D;$UH=yA&TJ1kjciU%mrDm5L6#OXY>(-y}jV~S>yg4TMe808`z&p0; zUqnl;YVtFT!rsG=)oYOYo3~}$Ceg-q1VMjLgxHhr4kXYjW4vTuenB_mBqKlcPJ+kVu4V?Z_hyc1jzO}xgc*%%y$t@Kf<`cdX+#dpr zCp;W9RWB85-1z;xEJeDZv6XCd%lD>aZ=0AW2gXSMPD$_&od}IvAjgL*4?<^T)O+X@ zVoQY~H1_55w8JJQKmjmJ`QVrRuqIWP`56Q0Ok&1_NuO}M@^R^V3cPuXcnv#DT-$(@ z!i_md(-%Li$6Pty3rc~)w>8k%pRPN9O;lhe;n7Vmk@G?E5zXL$@EAVO?ogH(|q|5W-alw7#x zY9#l#=VM!qS3l9nmFMvduNRMcb?F#MmNa+NQhlvy8MdBKg$2yRI7K;>U2&#?Ke=9w z^?r9dfm1 zE%XY35pyuu0r$cBuGL0qqH|GTXFBW})Zqut&OtJ9tZa$%a+7nqqfpGHqWn8Qo@m1d zbcTT$&^WX;v=tw6Zu_HKXl={c-@%^BMAv^#ta_YHP?4}U&*}3Q*M=KkdS%3VSk9RK5v ze7!5rR-$_>tID0kivxirTnVc%3WOIssN-Z%Ga(=T+-oJyl{Zbe2IocGj!Ot@(m6qRNCK!+ zX)AnHyzAI75@hB7|khQGQ1hiX#Tkv$WVLA^V>t?$O zzk%5;J&-bb)@$O2v=;6IMxJYR=NHEd-dcNr3&NZ3OEV4|ZkiR10v_zqcPhhe0_lic zMGJ&H5`_lw2(W{0hLvw^{*RvVpg&Yq0v~FW6R3Z(+)uS4E-W+fAu+>Zmql+cb++&t;@$rOB&o1+9pMh(84A5Unu`(eGo;|ss>49L}5#X z*7kf#CwuRuXUJp{$VM>_i-&IAFZmNn1-~5w!I<^Y$h-m7DM41K1C@+B7+*Xp>j0FFEh=oF7YG(20MtV{=C;ptDbj07v+|$NNZ$uDkZYn+0 zDhkr^Z;ya z+hUe9mmp*OWS7aXCmc9LIbTBguAQg)gHgpM$QDB`~VtX0?`)W7~tH2c}>? zvxRg&pkq4(T5SayI-n4ii4{$5jH*d zE!d%WmE5B!@4r2rZ*JH1uWo0h9aH$?y5=6q3GS1rsli#i&9XX(k$PvkSJnIvC9z_X zkoBfEmh@E#Shnb2n8(4&%XG|_g|E`tGCz<^r$12=gpVe<->!*rb^GkcfdVA@g(&%I z{@L7|Ez|%tUtk+-mYF?>k)*OYu><|LT+r1Lh5nN`(2~OFW?l?zIed?1CPU_{u9*MmZAEvV zoS~QenJj!Hk%6Md&0f>0vDzK?0hW!E-e8v0P0wi`3j~7UzNHzBE?S-keD8Q06@@Fd z5>?BgA`l3PVsmu9xzFm*hyDfg@XlZ*^4VVbE74y+%QM$HR8G>HkQ;Qt_`<%FNw>P@ zpKe3XV93l5@R9VJWgrD|Y2_oC$O;x*;0e>PT%LK^>qP(n^cQ~V%>2D9b=~gSqRsT{ zh(U?LxLSDb+0ber0u$FBV>sh`l0nq3gxRhOvF7SG1!CJ9IllI$9~`}Z$8)8kL`BYk zNQR6znE#ejZ!5^Hi#^%X%oogoQKDZvP%RjHxE$j@J-=~}EbQ{8nDR^T};XskIh>`RY;FNK}5EC315a4s(&H=Ee zC}W6^K_ZT~DA>sth#FnU0a1gNXY%tGr1(X`@8Vgdtysuqfan4w&(f<1F?b(7*okzF zd>#^RcAOUedSdX}xybf^Z$fr=vp72-ivUN*6XPOQ49~15WDLvMRUKvq5IloTt=P@S z>j1P+XBK;+E*mTQ?wfk7^vl&%TvfXcJj~T-+9w)=>O;Jp(`A;U#OTeo_5a&oDs5uu zOhKT>W<20js|0yezWgJ`TlKn(jN}p9w~%6=S}5cysA$>2fx|y^3|T#&wB87728)y% z+COiL@vds3K>xniQV?@=XA!N+;`pJuji*Clh>;IW^cqJP`oNUH-%V(gE)ARdPSZnj zZctNf$fa3KN$^Yq%f7?NGH@VlJ0%(9mj2*@HhE1+EXWqx?yp#sF>@`2C5R!<$(c)wOB>Ubp#d$O#tX%keLL`O8ampy2~@rrFr| zx%0)+R-v|@>k?PQL8}zY*fm;0Uvbl@vHI7d;5si{}O9StJa?ADpMBsQT`{zRC ztMeq|#CFh4un6WqP`;3&GRJC`0xd&>TxpQ#Z5g1#Da)z(T|D5=P`FjZ!E)R1-#j<# ziX|6HWX~3d{*kW zmiLXhCJT6E;#Lx#XeiUxfDTkO9Pvf$>pI%=?iA{FaAO0bs~Gi-HtfOULX)5T4+J0% z(zjm+`bjzs$_l7?6R-fwS9A4Yf6B+6Md9r2SfeWC>ulGdKMih&4POB=Guv^iaQURC z0K^tS%{ASRo_nW;E!7tcr!_qzLEd<$+ll1UGOC0`Q@r1fxUO%jgvMeFRS;bbWa*zi zvf6>LXyFGgb^n1BIw?MUss|=c&cc@cqAfWv3sX`w7=bH@)$Zj|qn6Qy{)yVntCV+0 zfJ>L2;G5(mV&KPubJ3m4I-0Z$`hX`FbP2tL%3^QlT*Bxcp>kRhny3gs{bQ^E=LyMZ zJT7|bT{X*xJwLON#Rgd%2h8pP&H1=2`!Xf6U^ReRVoIs+bwR4hxu8pe6s$D$y%)E) z4r~=q5ybnG4C@@r=!GdFANFonIHzKL9ZMHA1e_;{27dXiuR88E2LIYivBcC%50LYJ z&d^T5_~cLVS?2H6yDIr94+`ZUTx|TjeF;)5sxzm-J<@V*CPaEdc7QeG5nzcAT?yRW zMX{xU6|HKA*?lt)`sB|6|KEPASe>tsrs?rOQFF(*QyPop&-SOoa3F0>zV`1EIIkUy?DFACk! z@q~Yh+<*MM{HI0yIrp5Jv-%&>lkd_=(R5w4YjedIL6koU-Y^+N@Vrk9bry3biB$Cm zJ#VLif&q-}s_E2Zam(f#{O>$4AO9heX7+K5I93Lx*`|*aEZ_N+d0#(M+|1B>%M)H8 zY#xKf8tHdz$2k@BA*A|d+3$p1hsRHN2m3>hQ{L!4RuK5)vlRmFh15gzf-XW-xhRE5 zxH)DVZmubYcT@`*w&X z&lUEJDxXbsWee*Gf8V0U{k^jGG1sAA#J~_gbKOLRz^Ojm zcPnpsbN^!r^AF#<-LTK>4&Drknq$5RUs#R#*dyalAB5k=H`IUMABnGitf9V#M9uPh z1ZOFaB?;e(+~&h=01?Trwy;pwjWE5iB9r(C@K#TQJB~+=$-ZcX_tAKU&|)4U5(+I1K?Hr#DH4= zx~vv^2c+C8+-67?30XT}F$&F4h@=s`G|;Kh@Qzty3_^8%TiDP!Y?y8-eWK#~zWu9*6UW`^ zq%tvIM2d4+i*!^1S2G=QU|AS?b+B%Qu?`1)i9Gv5VJNN@W^R)8*CRH+?;2Z(_B%I` z_zH_3ze_q2Sw!}MQA?8RNh_;vmZX3;6fr)KOf$G2zujh|6z#A%TSSqbQW`sYdP&#K z;r)~I*2K#hj&5r+04i1l;>tX5>$U1Rgbv=-yHGJ0Ev9ouxY0HLul&oP7aq@c7K9L* zt8t@sQjn=kDH%j7d zIR)G_INc#y6HFzmuwq3LNC>2?JBxSRDtSJBV@8@s(O1MPlcsTQd6~7B;ywUs>YyKt z#25cn%!bV5`5euy-ZTDnIII_!OqBrq*8`RR7NQr7o!D52$(ySgJMTV`o>BYa&tmHn zLi0r+;=|UWcY>{L&8mkSohtQ`$A4%DtFM9j{6I%~f{AFOB>%rt1S7_LCAmw`E18y2 zsmS{DP$ulQ;oCdaL~nhCs_kumY;NeCFHc@)FYg_Q7DAtf5EZ3PlGmnTiZG*ch|q4G z_k!|0%U7W;{h_Unr4#dttXy%W)>%=Rec0$=bU5;j&b8nt?c`a@_Qu##q2l`~A)m<5 zunTi{c0b7Nea%I2rL)vrVh{G+Z3`;NzUrfeNF6h`!E8rm=7wj558Co0_g`()@2EnD zmNQ_F>q%yiOG6+DJRg(ie;riza0{XLW(XJ6DA08&QC#9bZBHG?_eaGS$Vbk6|AXfH zytfxRSL@O)(Zgq`2_<{DhZS}vc6$-hR*6)jdnvY%eIh7=Q$*^M?s#?#7>Pf=M%Uen zHf{z0YMirF=6@jR_mfIS!Z=Ue_BHBsmQSNQrPf89LM&Z0iqjn8&5;LXyujNH!QR_9 z1ccvoo+wyTFn`Q1U1-PJu7Nyktrl%B={bYSo}5UF8q7Bg_Uqd!GL3E;_o<5DnvEQy z(Azj3*H1bOi`jXXoZS*pFy~g3;_d6=z<7Fls)o6Se5kCB6Ggvbbwsog-x9qHw5U$* zzqmz zXP!|TMPnLe+}GT`uy#tUv(}W4p(ztI@-xdd>OaJ6btv-i8ZEe_)OGiL{>#eStCkYy z-%sBu$VivJ3s5BkN)zWNZND{F)GUSZ^UX0fWjYRe*R1G$zb48h@?_4F*rk=)&$`fU zAN6DK$?cnV?zK$S3Y!F|K$h}GMk?pU;8R|=lJVo_<6In(hq>v4P z)bVsZZ715|uGM_`qdv$J>l`=m!7%$T?DZav&h1P3krNj_Z<~oB_a5IcvJvFYy40>* zZ9diasBa+6Jy!K>x)ufcbvFpCs5@WRpG?agkHupNKgY z^uf5Z8!$fi%7qj3ewbt}D&tvMfXq-U-1jTz#e0(^Lw#JG9Er5`#YwKxaJ`mTj|+qz zx%T~HN@S6<4l-QNT@hjP4y}d@$n)Cj2oL9o75U)(cfXtnU9$Iv4khdFew(!X z{>J&z1#V9-XR5^5>~E$m-)lkQ^*^O=l&>I?y{8Nn1JUr&m8qO8n!giBgXqFkuzin! zT@9qKzp9bVXJu3QKHk{fexJKoVResyJvnAcGcQAo?MAA&tq@dwONYzHUXEnzR|IFz zKDp~#Y?$dd(!iRcE;k(O@vl>7R=4!ItbD_@Aq0B4t%QLU(Dyq zzUX%Ku(nP84V!fSveLmQ&8F~0ZNeLGg)06Vs8W1{1BSPxQttHr{F)l){B0Qr{!Nh< z4GhGnd%U4%=tJo8&&4>|`M?e^ez!DkKCUZpLiQDM*<0Ej6_TuXgl66{ON??B3kC%P zVzl%P%K-LR4RtFzv(0=G8`O^G-4+d`3eAdEn^>e`8f@pof{Mlnie|FI%h*4CA_vo!yvY1gI5d6x!=a|+a2asRZZg^9*0X5!um zw6Gz-+iMlfc4?+nxr0SwJzUG+-Y+CY6o_lH2gF=^E5m>qmi9F+C}q54ssnb9=YRC= zL578JPxhLfPlZnhQ+givF4w=Sm=Lu_Kz%(Doi|eDFq&KNzfhgrEywLGjF8jb``XO~ zyLh>{!m)HOEJFVrxc)@V#djNxk`@?mBl>Q!@-oPA*fZFx--|p@+*Hq9)@+sSwz6Yu zW!69IX(riBO?RfI>;mqg@X}aIoPL~4jr_{L62h_sI;}|?=&%zH72p=3x zFWx<@*1~}$d$EW?p=5(Eu~5*-PFPDu6`0{$@O$TE$ceKjcoJDbPzD)bOwVb+i9c7* zxM}G;r@B^@pRvbp;{6VGN{MPdIhiK|g)M(O_dLDI#y4l92)zFD)HC&uScX2oIlP_m zd$%IZ6lOn~rvu(#KBZXelm8uj`7!9saRanUDr5%IZ2sPUy-*DKlVPLy{G*g+X4mMKMo}t zYa(J~@EO;Xlm{o-$lf8NbPLf6*FjUlFGRdUK?oY99`ke0HVCTN?g_ZU^GS=k6LO!X zxF$$o-qp6dWu60=`lfBLqkEuKl4@{xMQQk)0d44KX&n1djs%MoKNHsp{nmf<5jHFBG7Ji5jkT< zeN;bwDu0nNPn#$!9Tc$_at<`M!-Kb&AB^oNgG5c+*v;X_O6=-T_}7-1wFsr&t9MTA zX;+@J{`oiJ;vbO(A8LpfK|7?~NrC z6*eo{X!?GC!q$f-xj)cYVOaEe+!{G z-ZGz2dI>8(TQh{Ko6K*TLm~-LM5DYXBckwOkB?d3xTz9e{Lyp?LR21yjLB`ZIAhvq zT5?VY3PzC|bAxAMd{0X@DD-!tf!&sRuecf3O{1*qLj~Xv)nU1ur@Hymhi&Tg_JfL zSzQ}B##^syQRm*)VeFp*3_3$YMwL8xM!at!MV4yK)PQW?zwmm9{<2$6{1C&r)Nq!4 zWiTHI{{6Lxl^Xfjd3~-N_NUhfiU9Obr8kcsgsxn`y2;bfUmkuxCbb-Qjnj)s}ESJ=&0qe*nJBFMHyW(3J4DHP2reNZ^1l;KHzu$ zDXia*3=?#e_zQ_{qGmj=xRAi|Tu9F&3GoxdKk&VM2rpyj#Ix5&TC}*bkq^Q_K>V~- z4Pn-6v?g+XgzFD6KLdd}?@tXhaj(JtVU*#{5tXHi3g>I7{Fw^@JHw?Zp1(kW{Ow=m zr?gzXbEkH{FMt{)DH3oyuXWpxKuY$D!M7(58dF1KQXd8&C#4`W;Ll}y+eE$z ztK`4q+K!`Z*FoWr8!^X9v=-agfGp+5<&v9;&6l?%9k6@~6GD4du-Cp`L*sPyr!P0A zMo5PZdu7h;>~!oE zH#`U(X#c|ly8ItVic%S&`IBk#lM@MwUL^kNq>;0BbJM$Ce*2Yd3FZTi_=ptiS4aoN zY)^y~7yt|#Jd&NC)_8Xp9}$B2ek^3?{Ikp|Z(%IrMMBp9r&36d)XLhrZ$hh*U^;zHfZ-#szZxm#shy+-+#Gb{xGVDczU1p=!JAjjs@Tx}%xa0Ln ztu48*D#o{9za#0&CVm-7s~1W5&{h!@Iu$tmn>)H}|J4q+PvSx50i1MD51w^(cGeG!iAbbbw6zbr%>M^UwNpT}M)rpb zY2SV+@-vhNPeH?&s9!Gk$B#aX^=*4A%K-}|r5eJ9Un?Jtqs_(n(#S#=zrS;G5qDdr zsuIncXoSoo*H^Ef3GB#hg|_}}i5w*9mwR|rvA3V_3#F6u=LVt_f2Bt_rCN}dJ1n99 z3!HN&A2Z&r-ui~)*{C9W=*Nxw5lx&DI5;`2oDp}AuZh(X<|&F|pdZsJn}Y;)ke%x< zpEEP)s2f&d6J3I0g18;!fxRILM82&g8}WWY2vbIy%zghlAOObju45yL&gx z1gg~m@wiOsFvp7VYO)CQs9&hY$x`^zeQh+1Euyj)STLMpIWKoL`sGi%4V?XVf?}9L z$EpSX8=t^4%r}lXLOv}n()zQBw|~@Lu+s)eH0r&9y{=V(%DDA@+zJTvEa>6qZ_lY+w{d8G3AO&mMTy+E z3pb~dsVO&jf1Uz~PVKMTM1K*Juxp3i1MK0!hetBKNIO%Bi+zy&z$KX_DW*iU={yFk zaU$BZw#Q>0;psR!o%9oaqlAo*!Sl&0j1uU5d@;(4-?RslqG;_LA!ZpDCa;{)9<$`B zH3OioKaZ8n%c*5B7PHHooeTm9S?Q;az+WEt5p+|+3oa?_8CGAM8lxS*L46#OayUG+ zw0x@t#{u(3O`^yiw1*~KIrb|KwA&8Hmd-Gwfcen1c3UyxA2@S`YXhIQm=VcvW}w#TmhNXFRNE^NuoGA$iF@J^(*=y?r7-D%iWuv;cZZ3Y z$>D-MtknLfHvl?ht_`ib!%IM6&|iL?Fb%-78bZYQ{sU13``$S<&jlnVE(JRzbeOT( z{Cs0%-7wU~C+t+5eD0w1d*jHRp zUfNS$X$L!iyYRocf^4N#+2no0Kr48--=mn;3Oo1N2(7zUpEB>E(cntZH7nknl+I;L z!^fI|=Nw1VX^4SO=I#MbvYJH? z;&tB@q-w|l&R?+*>+rJ^Oy>Zi%EjnVOM_~3+h zJG#@R&Uvsh-0QewE3HBDdmAipqL=7C2|6=H%6!JGJW!C~l1*a;IIM$2{cQ#8Db>Pf zH;a78i~0~Dq$90O>v;XE*E!Z~xnCJZqC@yE-t}+GbHqsS%{x;oG@?F82hpOw4r59q zt0D)HmAZ<2>plLv1^D8@(QVP4r*;>OHGsj}j+rd?oFgqEXose?ZrcqL++AR8NfQu~ zIPcZb%#@b>nuMR_|9ZOvz9V$fBwq{wTYm?shHOteVjumL<_dG;{2 zayVl5-noIdKXC__jslkWvP%=N38nmlWg>Aq9i>5ycaM_9j2M(7_P{e~O;&dhz{d2s z)$HoNhmN7r&snz#Dew|LNboyLFUBpMfX9P*>q^~Z8zpOJn3h%Ss_5wvx3@9x+kI_R zPQ?oC`?>WN8KSniq=Vhp*MKAHWcU8djor^*^rqaz=(C^Te8c-srT)xAq{FpT6(D#$ zF%C^Se*&i5>ZtdnOW5~Abu`aR=y_>NX`41#>G~C>-VlFvgAQ~RU zu*h8y&RMV2XlAMoJ8;M={cm6AmCm*K6JbASGJbZgfT&vO7=6=m_@dETpU)+oFYzhN z@3#3WhcY(`VLT>clfcvLuSYu_JMmUi^O2t5$A)O{I}$bEv<;V2fnaNYw5axEupo%Y z42;{${Nr%vKaic}+IR4JiUc-Krlsyg>W0zFc}U7DIKPcbcwp(1qtr>|?5D1oTfMOF z|HQS3Ll#2nzlXv9x^v_7HZL>;Gk|Gu2Y^$sxoLLzZi_7D$3(4Kxp;qd~aj_BYS5}Rq(#zc;9tJ~Qn!*}i+7;5J#=MAzDd4CK4y6uc z?!6?KaQP}>SQI^OWNVnrB7h=isSR+DyZ-})0_u>V`1SE@`>})h_u%$$xhh_lY}85j zgW@xND{+hiNBDOXh$5^3&iidMvzbA0|CIL=u&m!V=z(aZvgpimJZXHrHnaFbzC@ zkzOlj(oIsMgUf&ire=N?K?Ab+F+X6_8K*S%xJK$<^p#&yJUM7Xp_gntf{b9xh>gj| z^K&e0Kbr|?VO#85O&kBQOHYy$)PChS!g-u&eL_o(+;!C@mAC*IiKOpY41HfFXUR*Z zwqHa{@Q0um&d_lsBCvR3W%vDLpTvrV=0*QRk|>~n)41C_%k0KGg0GeTJ#{He)ghC# z$fyOTIeW2J_ZHNf8f5W<3~DpfR-DhP^HtX6{$22QLqmn7B*>9b}xy)|dS8l3l>!CM7B zwZttzio=Q*od*_+7ekD};nmp_8~NYPiW=-Ujh!OfGYb`Z!wOg$ zCc$?Tg3kp&lJp`+D?v(Zz`p>69RTX+gwZkDe50%%M1E$kc&m5@GM8tMjucV+WOtyKJ{ddEUf!XHXCp=f6tD^I_Pv$6$~o;^NYi?&lLTE*CPlicld7JU@ zL;|A&Udq}o?Kpzlc?0lHQwH9CoaOWOcLo+C8l&&QaS=Rx>>%ww?ID}TLgKKq3I9Oz z_cpNbNJiWfMkF$cFkOi$nOS}4GAjQ1rFR&KCC+4G;e@X*;+)X9Kh81aAz?~bg2A`5 zmF|6OH^#1utyb4W3E(Ln*BoS0Uitc-Ob`WH<>+xPV57*gt8?2X+bPF=!ZYiX@NW8$PkOBY7e>K8ryjb4p{)qK<9RIG`OB$< z*R*57CN4lXQAOS^^sI7BOke>Iig;sO(b$O&3XIlC+c#!OOl7l2tr9AV(o3$(&U)(z z#$rSEf$om0f#a1SIu!GAwx5-M-pF9!W3A6n27f-#THGl@K4-g~0TJQwI>Hpbu21QZ zSo>JDPF#QpvPjuiL?g4r|7SKc(~Oh1{?i_aOgwrrTO4slTZ3GptzclQkf*mqtL2N+g5!hmt zKdqW}I&xW+&r|C79@M^1M1wMzD{1(;89Y<4x^J>wL0ObOE7GXX%i-t(BGwW@Ov)}k zTts0aMV@%7XDof)jKiXptJ+GgqTWN%^Sx>?ZgTyOehaN5FreiaK`0 z1N-rxB7baJaLBNd0A;A;GV1S#y)tciy6GQJo+)M&qkz*h)VHVCR4}vaf?B>|NnDY#9 zqBN*@-B>f5^wfdvWPwh3Ema>3>RKP$UP-Qy#Sg{C1_OMydJeS^s7c z7nXo5yVjDK58wW#*)9UH&0f^3Bg0q&tL!cBMN9ejB>WL|-5)7ZYs`8wzN;?8p8~wC z@9?m6iPTX%93V!yk_v3kzzG}}LrD~jY!B3*8a#cdCUIY^;m{v-e?DC*y$$TrO4>Mx z$ZSb|aah$PQx#&&21Jr9@Sa(OC{^O8W7}wx6!x|qKtTE6ub}yAZSZXPHQ!6toD+E-t)`)#rB1Q%q3My?Dpj~S`|xVbH> zAx`h4@0OYmnSCM2qajES!{LQ9&t6~sZnq}a3?>+|haOoIwS|!j>v)CL5!ow4LUK}O zX}>`3C`K(3lA;m?>q)HG9pHS~Pi75Cd zHTI|vEFrA9L%uqbY$woFMTI0C3*uOPo(InQf-wakVPzgi30R*|t`sPIn=SgE>apOz z(}_5Fd8NH46MR}iVpI>v7LeSG3vAb(+@(YgZsnylLDDxAvp@X@3Lpt?K%IEA4l=d$ zs;D6QTG5$kkg`QLYarQiJe#*F-Od*(QMQ|lR5jyIKJbO+a6)de$pH@ukfPdaNm}khB-U?+SW6U0WqO^&hCCV9P9W6e5A=ab!wc zzuM-_E(Z_B5&Z?fp8}3dqLLsre8d@D;2!xCRX;WNn-7Ljtj2PF8c3|Tso%zVA2JTNm&r7^gl@~%`dKNz8wFm0gV zh-MK!Ou)SVo5!XLPhMX<-cYy22;{hisUKcvvNq7`me0Z_gGW0ezCT((wjF%UnOS-C zUC*&;_Of^}f9X18(bjs#?#?zL%V*-+JSDTyv6i=dUi5OxEqXa!m<1)8QTgkS!Pmpy z0Js9O-yfkrx@m=%a}GTni+n<-m&h1e5at9Hc#`%*EK}t0bg5^ddz*yOb2$S75BpvS zK+4F#u|<8~>u-1AWDf6QhuZ`%zR+AOY|<;rCUdjkrTg^;&nrz(TCYrRIF#M?)X}^9 zw}sKd;C`RmY^$b*RKp9`bNo&V;n|)&=iH;h!$p(($xmRt+5ku`UPX80PQ2J*+e>gh zi8NTLV%ic7=Tn*l)W|FMw=H0iqX3^1xcUwXU+gYy4${UyKG!yuRi*}LuHRWrv2xz{ z`$D&x-BVaX%{lAp2;3)~FJF!O`XlX0{?Z45WTaT>Xk=X3h48e=?!*bGXu4U@L`4x! z%kRLf$*r#|a4n)w==6o|bY;E>Q5P11k+DK*r$}LmrYUSG%MOg=cMZDFrHY%S5;&wU z>ngWA=YlWDxI0Fi5Bq|zd&N-Ne@->Dbrdm>qA9JMARl}XH5P6L zn)-?VmLagPCsG3_lfsrF4VYs)!87wmp0D+|sw*y-4?Ka9OYdR5oXNau-xAOdjc zd7K!5mLC1%M$oQ!B8@iwB8 zhg-X_UaKH3T56&nO-}502h#z6+(*7)<4iwoFB*-w*d}-Q2cgWh6tqj<%_Hq6t^y0F zlVi4fBp$y{udLi5FeIU2NKoC*xM~&{NF0Yru`+9u#Qa3*pv<<$ydWx5@;+Nct+58B zR3t(_d_C{dyxnBcyAxVJ+kYU)KF4)Cz_ z6MhAM0L^4)>W*AuE4#s1ReW_@u`p)$&QUn;;YtD}8)_)wU?( z%x{POP?4Oa#OrC7|JmVxC{(S&m`XN}9|Mma$5M`ZioVx2t_oZXEZH=kQobbdsU5&# zt?31Izy(-J(VM38b7p?c%v#IdPSHAkRBh79Pf&6doB}Oya}tiN5<^(|&KFJIQFs;F z+My-@v8NrF{YVnv;s*ON8{fh$)q0bCQ}IRN9*$OswpyK9seVXK+02bVwl*BL1(MZbCclI0;4 z7aoNbGC*wZ@h!w1#_d(KtKBB8F6PAjT}0H<0abZ zHrZsx%Qtc_a{x2f!*ees?`A~SoE{~N`|3(3`oM||m+&ERj;ypP-5wxd%pjhWAe;rmT znzOFjh(u&10eg{iqz zLz@pWa25tz#l>>m_jcDKi7oN>Gdt~~S+e{)q?i z=?F!7$Y{e%VUrwz@Nl6*7TarF&FE&4U<f6_DdruHm?l8D4%nx(N=Q?aHJ{=6UE-}-=fe)aDsfE_q?kpgof#% zY*%6$2lih`@Zj_KpV@psqzZfFJ5|*_jcTFPgD#yYL)LDbMdYeyeoRaO3y_n>`br%D2I@jGcZjzR^dKZoITe&OsYFnTV`-KEpXdduE|8+~ z2r@xohr%!s1TAcF9{ausEywe=Mv}@fg%3f3mxGU=Hz+HM4M+#^GpT3z9 zm?P$xNW$ZN^LgA?5+H;0RpYu^!H>;ma&sC8?c-m{<-g{6{SRGcJcMcr$Wufh@P7EK z;#g?sQ1=jqGRFoC*#Sq`s#3P2cfP72MzKEokz7ywYCD}K1J8?H5(8cj0gDHgb$YFj zxMDM;z=eoPD%Es15W_KDcSn`~^?yiL292MQ6s=N;0CxqX%iIVebSC}{$O?OQ@ zYdBT2JyO@&uiI9W1h(sd{s%${C4MZrE{aXDseKD^ft?tlexifN3!PS1=veB&_iMM5 zWH`cpCXt}vk}!;hkeB$4=JMZyVG4s=Un~-5xO2))Fu=O6^tZ>U%4q703!HdN3g&p0 z6B$G{oQimBV3F=t6X=M`%9ISy2F{{$Qz9f8b&! z09o3|?fV0z_P~RkL{SG`)}{Bl{TLcevzEzf15bj>P_5ej#8%Xi%<%aXE8dUR0X#=2 zq1`{ejKVR-Wc!)Ip4S((b$0+48<9r4UGaY$or^z{|Nq9vVv<9On#`ssIV4n?<475j z^QjUthjJcr%$!1LhEU`%a+pIxIp#EpIpmO4(7 z&ubldOb!h*V^i+x?K0I%Mudou8cy7`7b|fF~#;rt~)F)q%D3g49|2{ite! zQY{j|=YZ#+P~{a<)(e5Cq~wUB8}L8~TL2GcNt2Ju+%XfsA{NZA|H+U~W8F6Ux3XWy zZ?f(1GM13auNp-A1#B*Z2Y$TvlBML~s>bBn5>ji3_8j`d2nFb>di3@6hFF|;Xb}j! zSD{5NjOf>1()HGbVL(Sfhf}}M-1a9Np5r-Dqz4s4*cJEz!84nCEgd8NN#3N+SM9&r zL`^Rtq!^HGVWIvr-wtTPN2v^}<--rG_oP=7iW!*??z}mEp7SAu5W5BaWaAO$bj$Q% z#^b48RfK_I-}h4a(GIl1FI8QrnoC{2)l+LuSfU7$EOgc zky6|Tc|7>}(s}tdls8-*QahOc7A-B5aV-9?sOHX2$s3)s#HP(D>>*?@=kEoq7&t1P z1S^gl~!%8TJ#xxLKn4joU5=23cr>k z!v7ZH58w`DOpjxXueJ7z#-R5skNJEWC;QM6G(*t^j|e`H_g3oRfEz!DFYBUItxQs1 zAb8DuUDe5?0Yft6HwcwE_p|0xyR;$BEcanA6H5m=959`)t@~R0aSz5_3?EK zy4A1~mn>gkhYDt}x$l&z6}r2dDDhDa=ZmjIBnpNjl2=!3140H9-hqhkz=V_^$0j%W z)vzn(=gqh3HXp*^#Ap!wxCbS78M&+;eF?Z0lB-re0kmlODi=YiWS(+&7KInMkF>r{fT@H)vOU zjn2A?KYeH<8;2qM1ycnyecasm+kHT-wAFrH{tB_N4J^0~RfAztJ9D_- z5R=v+GL)S5P|SLRQElaV{w#YbBYt`Zt)n!1+mc?6$Z8F*GSzV zq`UB?7XWFbhd&gK-D{D-Qi-z^BUk2;SXs{vCcC$YO(0dd>+L9z4KBvU&Dtw*JJj(!`5 z3WM(zS0mZP#q8&6cs&+XS#uU6J~%tfa58;VsJCGS`KZx*HY~QHY~WP71l-|mH;?oV zpqHjwc>aBNS;GQ^NZD22(03j-)EmcNrf2R-1eEy7&$xI3_YpjWjZIh?(+Xy+Sgx$< z*-5?R2x8Vz_WoGccW!AcEI{tn33)0OsPztyLBK6cLAIaw`;VK#JzD~(s950Atu>zV zPx|&r1+(=@WBlhs3_I8!h_{!?ji>=>YP{gf!NB}`?`nFEPI5q@V9-3#mHKL(leO-a z&Hp8aLszr|OMkG@$p;(~S>5S;-p-f*qiyd9@09t~I7jCQ6!UNsqK&53?kfdt1A1Kp|HAQ%tSu;nG#?FkA*0 zHsj&2M=qM@^10PU9d2i7EQmJ6ZcjHW46eTIH~SIJ@fMYiHa60V+gB@WN}s_LO-Mcn zo6qpuRhLJ-tCj*kQ43xVJVd4PMh2YpU85E#M07Fel(A`m&#?p!GAX>Z4PsmS-$eUw z!I(&7&Xkrqx=A@oX@^W%-)*;YPh;8-8+d?8E!8%f-cU@Y$F?nF{UXy$%pQBMb*)2_ zHcAo_0|;)znIZgxF~_9qP$BBCws$D5XjyrPmth{=^w{}YKK^n>J9@UX_l@`QWob}N zL`qIr@ixrNfnM$HjZ66q=aPsy22L;vb7h;C+zTOOx4~0$1PsESU2f$OcL2dQ0HMMf z=wbVrmzOM$T~}J7Ce``v15Md{5xB8IRlh(bv=51jC@*HIx(JbCs(PGkK8Ry9hL0Ux zYUC3uc9oVXUUE9w^l;~@fzs@z3WqYl-s~bqT1E3V91F3mYUiE`pP#iyA|CYCi8#pC zeM?^Dc#dUs2!7_&fnHAQ2^OGiO;@toyGCd(wt?_e(s|yw=M8~vJV3}6Jo9~9QmeBS zOnM`VOo8khJFC^JAxybM(Kl?-s@hkjsuG$AT$Ig{mCIuw_lO<@Nk31vphB~C1^5n2 zD}&@D4Dhhe^H60kuO3E8QYXg#gr`I-q$b#9$=KkBBZp6ZVnc$~(0a)RaiS)W>;&>> zu+%xME{no|0`phy$O*)|dQrE+YVXP-yHMba9#vy&ww&^oyKfPE3BZ)<9^zh(Qvi%u zaOoo#Rh7L66y4uL2!19h?kJp;lN(*hfmSv)xX>ls#!hRXfR|0SUCr*eEHxo-)bve8*$s`4z^%y zoGrdxK~}mg*FvOoyS4mho!PlOt9N-Cb{gM&&E_8QzihS6m}C0Cxrvy86zJ%R=|w|w z)*{wSI|b#2GgfQ*>VX^E;)|mh?@@*Q>7-~$L?WY{N)w-waGZLH6S%dm3vbe76qkK? z3j6+1D0Vg>%vN=$^wNZG>hoE#9fRj}Fc+Y^9u?fNf5E2=vIq7asKMI$lzbhB(PuMw z4{f4Jbu0)oSSawIILT%*lC9rqDT1DCq71ipvez|@KpSP?KdCspk2d(S$~I-fLL=I zB3eMm${T(X{OIe*@Y5Zoot=RW4QrY?TcS%+lwIHM@^Iyy16`I z&C63EVbZ_9wzF3fDeP+4x;iiHYwm&eTFNfU`@`ULS6OlyBi*`4az`DS@6i{211 zrI?2Zp^pj<3J6g>t$^;!Q@u$>I6-VCGE7cJ-?VN=m{Q4{fIE1PN1v1sx##KxjC zKuS^!##0P|E*s^-fAjF3yEA7G_s2g&u9!-U8e{}`bWalGRe!OS;4k3W7DoeV34`VF zl!!$>Z)KJ$Mkv`!TGv08X}-y)&inK{M8r^!HX8S%=>3^hjQu1SKK`jrv?1X^bLkup z*YR2@fRVv3*`b3TA((@nKX44Zo>L&yI?l!AU#_{nGX=@ZG9jE001ra^J5^{y)$u z`D_ZAD8%r%X1&g`+WLNOS5HCD3n{5k;RNv-BK@!5uKihXVEEc$GK=W^vb^VSl6PQv zW}`OgwCkUD^1S z4r!we{-KrO3g*sfiMc^+@|@U&wx*!@AVI$k+!F`E0^yWl?p2GE>IW zNlGks5w<4t8BLJsdqX#_EFSOMYJg2XZ{kz1T3f|+Jr&n!#>^vW(p+HpcE{i030Gg# z-^3TNbY(6`4kfJM*{!Ufr;58xHawd`Fdx$Wb``oE)%Y_&z5t|X#%Od+l(7y z>Dkt`l{5gp-)^oU6mN(19!46gN-Y93a*AN++lQui>)azMzuNO}jiluytGfU1 zpAI$(8u={B1|a16%&vDyOD(BZ{WwDn=1^Y-pK^=}&Q6>3ry=6~WF*DD@aY%=E2aJ4 z6czuQ_)oSkr1{^iCUt}y!GF6dmS(lViASG)>ltz#@8Aa%v+?&tI$@{AFi})S(d=bv z4W>cNV?u$n~->w1L!JK!$&O63iw9ULJ->2(Honn z_zwqHUy+RUV=nfcE%pp7FSE3}I%~s5)%ag7JhN@ODaHSNYW3JlE1ZwkA{1Bm=?A#_ zHo>)YTtnOPIkXr zxxQI>-aGJZ+=+(!j>0dlh7Q9bwqaI%&VqEB>w)Wr)$p!&s$@*;mk-N?38R-^qvtr9 zJGG8rz9#>HyjeN0H`a(qC2W-jUDLZwWX-4R9w&|4X#IA)x;#g;h*QZQVX6 zFmjpxR{G0?P9@PadF~WE^x@`p>XiXR%Z$A}JZ-yw^P}Cr_AWE>lu>y(qfExF%kI#J zy&k$o!ChmThdy|}0RI!(i=4yrPsnwcbkV$KE$!d_v9VuPrf0IF3U0xrk{%dv@@UBn zxR9pIuEc!_=hIJY!fu6xm?QI^)Sp&wyv_QU_Xdsa*MHgWCwL;XAQoIXKk}|CixcVz zite0Apj%?XuHZbgl!3Rd+`5U^1l^N`8Vbk2DkVi#aTl80rtbAn!mgx8`lrM`7BdCbbY4R{&Mx(#Ix^ltZz*&lcPV?n(s>#xG(B}frJ6cGGYq;7NlR8WAzdas z2Y8dr~04TJf?EK~!3vKec5HDw+Gjgy5D-zsP%uflF9?gy{k4fb5#Ojb#d z+M#rNos$FEH@*OU{?(DiZE0ePBVU6r9^u+_oMT5>Tq6tO>3R-qdH%fh5RxnGL6d;X zB{B3w|Fr5KclQPhb)S~h2QNI5^2AOltxyUapZI2LM0h=y^43^PfdzW#Vb^t^?*^7Gj+23&@5qFrguj?XBwxDUIOU|071T7dg{Mw+8YdKQ^hL=ihw zwW2znu6Ff#)Gu<)?yFnpp8jfI_dN||_sS;0=b27=3;Y$VQqeXYtNy7V&`rdXM{BVT)YzfX76)WQv5KR_(>|_#{1Qj4xdI(?OKAW#nR>Jv;5eBq6_k2O>xECUypXK zrW+~|+lm=wb%|$nUi0N}g1oP33XT743nD>nU<51bb_v2Y?tCSiELlzkT<0%T9QGsw z?(;zD`D0ChtiHV@oM*wV+j=EY(4Ri$pK~17nXrZGiP)qSsW%Zq{#2*%y70*M#aFgU z@c5w$IV_|4>*ICrXo`=GZA7e$3Q6c)q&XmKpXWI7nFE4{CSS!Lx=b`;v!Bqk9#(L> z;6+Qr%nGGbftv6wx2fuD#gnwefX!U=iA6qj=`kbT?^1G{b0WGFlciBaG^g`Ka$ZK) zxhZGWcU;|^e1obui$VJSv2*^Oa)>~&3o$_c-|`)wVE631t7HFx*rJZ z{?X1!`L|e!|D+JnAiqC5JGI{)`gC``fsEokaAU!k1d{%gXL3)SPu_0O%zP%`P$&}_ z*S`I0OiNgyQ^OIZgdWV*%=Zme6Z+0Ks3ez7i>llaNRRka!c4yx zQ6qGyiv1_#Im2mTla$Ns{Bkd4-TD;|(Y&DJcB%Mg(|(y($T^6&Q^7WxDp=*bWp zLT#0JT^+E%5J3O8bDf1L37M^ZMnRrfiI5imsQ|v(!l3 zT4zuf%>GbnDnLKmP7H`tIPjy50#LGRQnH!hTy&z>VB^2 zMlrw}1W1w(rH5XE4mbz2#*BLK6_Dl-HVZZ7%E;2Br~%BIqtp=Fi)D5=MShzd_2$(7 zcYe%S5){c&&jl!-R1QI(GITxOnRK>SkX<0h1n5g~vmd`Ta86+B;u{^y8K27Uj?|ja zqLRZyPV$#SZ#3-bp`Azb$6#!4_|D=T;s48j$%go1!dVj}0gR*h%cl|m{NqaAGSSi*1qcYHdEHgF1f$*cqe z@)Q>@cl|NI_rIuZq%g2hV!IdrS+Om?Nfq;tZcvBi?-e^7R!cepR}?#(5Mv7`duCOj zh_0Z(#|;VZBwNDtGkPuDQO98Re8WZ4FZhX{XP%EE7qFHmDJ^24@oV%YrZGpDlB`F^ zT3V4tIG=*qCsFGf?g*-=dc^j}LS$$uwN?#lWz1nWzLku3DF!0ft)Q*_In!BniCm&c z%HW5@n`!CLD->H~iO=F)-p&Y`xY{{T!)6I>6o!qf^bqF$qA`S8B%|hmPrSuznUy=r zyae>)gu#4Gwcp$p7JPc!D|mAwhYz8z56*B=r?)<)%csZ}E#~)lD9j(O0NjkI#mjuT z@`ilV@}UrY7US@B<<$Q55H@Ral8xTKXPyqSe?Ddw-~j{a(e}B2aQ#b8ofj=ej`UKw zLsh0TgEZ3GZ?ycbS7+a0l#({YG}01F>1ylefN5IJP_L2!#b#4ub;lR@w=dc0=mb28 z0}ueRT&x(G`4g6qc7aPl%pruK%;$IQm~6Y_YSBfnOSnSw4<|9$XwyZjGRb zVylLx3abhcC&#+JD1Rl2!NSgp(}{zhUw?7l(5OGmet2}L6#RU`lSP=)SUVf>>xNr<8ywn*nSk`y!Yqs;z9V9bM6zmY#lrqs+^AuuYEQY8 z*szGGTA|Egumna3H}5UogcPl8w{YYX19&M(u(S9=w-d)bbEa4y%i*ysnXMk0130WP z>|D?b;_e;X>%9?)cZT+8b{LP}OdM--Z^-kfo%>?atpG=VcT2D7JDGNERaMQwrnWC>q@jm*Vq*?St}!mRp1+AU2y@^`=NGjpIcJ09R5Gpm+>4}&e9!!!dD1QyDI&2pj$zROEqoJ~ zZ-nfLkDLj_$RtcTEr<5sm=7@=&l4B+vW;cFUus5ZpC9^hJVE}JlNxsObGW+74VwUk z;_3tsape=cXvEd(Yfm~1U3&y2XPBA*ZbV^O>Wti>ov11(R3?9`6U3}ghSEj_b3`X1 z%di80LQG@g_emRIyACRs(CU=%P5Ab~5z*Fxx>D^`1F@|J%jtUNU;(O|m6$-LL!P@p z2SmNZBYzzNncIQ?E!23JLF}wT^&^xNvF%Vm3H7T(BkM97+E6|i5c|VIOy}_g*PEhf=$a-smt8OrEK}S_P^D@I z)1ulzs`%_WQSZyPI>F#>0eOV@fGIOT~0$#6OsUppNA5ka!nDjGb={FHlzD zp<&$4J`gr+A3stsT7T-5v5s#;oWG!>u3ox^ zR>d@uYY;qLBRl2X@s5csb&Vz|q+JReEsL&}1G}{R2eR8Y77<3pKs*4?$wwnG#8=J< zsT@GXA;X~Sk{>4&qErlcb}0`AewfvHD@2eVSPQ-$=5|CV%0mtehB@Eo2C0P(hH<|g z=C2uDoh;2e;?_Epk#c`hi`L%g=d_;1)4E?qEitXSE#v6kT=>f8@X-AbzSM0i%4M=& z!s^FFX4KI!U^uc_bt){MB77wU#zuu6y3z7Bh*s!5E`|}<=3RyvRmcCKibv;UeIIZL znz4^+gqpqfj@!Ud@L{35I#dt8Lyh5w`05TPWtv1n3NB432QYSKW_9OOPz(sejPi=M z|3JLrvx^PA_=%fB$5t)67@dWwvMrY>K3GCik(WYTa^y8?j&OmjMUeW2xn{>5o2*fD zd+^$lNv))46Z)|kOv&iO2GK4UzkGD6WEdncKm=YN|KzNC)KO^$p(?K?M_$aMZ*RC?4+31!nE6+^x2XR2I(;J`7bb zG%W~+B0C^}!s$WyxrrB%oLn?W1bx8Fx>;Zb$;D+UsszxXuCH1i&j?BmT_gSJFwcjyU4N9GNheb~g7Si`g< zKQ>`QEgJ9M0hTZknQ0J*=ls>xFD_1nUSIZ*y+ush};TT#KD#h}SYH`YvMF2*B`UUdLH9&L1sSM{8LVy1mmrVAlzAlUqpb{o(Zvw;2Y zZz&P)PQy?=0M3{*Rhir{O3+BL=GrMzn*m~q`^SsOUK8%pikwus=@e*XlfUeG(bi30 zf{Gu^KOgLPylNTRIw>&n{??hXv&vw}eFtLI>c61@f58$UCx$YwdA$1b-*1)BrF(QT zJqysJKb?Hu5WB&LKDhpDwjPNJXAc*%V76V=1Z0te9u~%Wf9YdetP)Qfo~<|Xs{Fz6 z8fGnPLJZ)pDIp~^DvTD$uB*;s2b|(eRuk8?PTS14ld$ zg>h1JQ~wx|dhDwB2rA3v;hy_fyHgr98*2D>*P!>k6$7`WY^_KSV{4>M0`E=wL3dfe zP*%&gS-9r%YyhnuIz!Z-zW%i4c55om9yKZcALzI3S?$5X=kXgEKRh0%8X~B*;nic!CRk(Jd?-+vGjyePY^yJ8rLO5DG zs1#+oo%Qn(naR))Kl+Luo<+(L@y-LICW=*g7?5y7WkwOCCsj;N#W}L|$gIlA$gq*P zwPKRAnKX3Fe`T02Ret2w&OCCvSK-yMk~2&`1p-kYWH0Iea5X6+=@)@>?SUImDzb~9 z9|P?52dNR39TR_nz~g`VUXMCS5?7%Il)q0v&uI=ZU8BFk&q67G5>J(NA)zaykj=SF zE@@$Jd6i&$b2*VUo|-;RGy*U*ZmVi8QK6z?hkgYi&z75`fU^Cbd*rQ5kAvoBVk#Tj zGkk>%Y%+}5v-1M`bm8fuEz)SQsLh!qJPllK6Jojo!Y1QGR`SI`5d$z^O}2ZPu*cXw zdA43TE_y3)C-h03^}1JoY?mHI*ZnT!5L^y>M%i-+KS_fChu5gKT8*6vB0vzdIEP4K zt$6^I-wVbxcTj4llRH6tuT3J^##6@{uZ4z6-E`u#BGiLr zH2Kf#tzN^2IDBy69OOcxLYVVZA?Zy;2nZ<5y7Q#vh5CEw1Ay(tz}s6#{easuNC&L? zibkiK`goTSAhvrznPaY<>Wq>LrU80haLV)1N~%P#a~?RUL5=@gL5CIv7UEyHiS8kr z5I+H)PK{lNgr5u^JGxy+JCO+5W*jpf9;QeDyQ1G((m40fL9T5zzno)E9KVVVzSGnp zhGF`TM=8qv+JuyH;Sq;^j$4Fba1v1;a?Jh!qs9lAR}@}>vc?rQCqq%G=<80}@PFew zCT5vFrFc&yt=wz=-ZKkrf)Sz&6pA^x_B7b&?>6rvcD=Ck3VP>FnlIB@Z;O&czY}fM zW#}ggTtXLco=W>T_U6Zj$sT_KHXgNsUxeJXR{=){c&f{{2{Fe141Zrjh#2(%wDv$~ zIexXxJy0?(|JB;sd2}0EN|?SIDkGv@Q~iD_KXbE0iPoey4gP#IYjo_#cWmZnSb_OZ zQrvO9=NLAhzz&%R7WzXoc)o=Y$1z#+de#(-r+p|C*|$o5u5jgS9L zL;0!II$Atq2bfVh;P)(V5ZwTRV-I;HbIr2;0!c+Q7Nfja!(E}j@Tld1A~uFb`tx2P znNUxrg!LC(mc$8ig3BG6Q+}pJt(|I&TG0+r^`FH2a;a7ixU8-;FELNrE?VbT=Z9|h zT62-huTlz8Z>98bs1Z8jfA)Vf;XJLnM8xLY=hYj!kJX#a=!dGt9P<{!I4yU~VJ0@} zUeI*B;ri*PEXb_&x1D|32`~8U%AR?w{@eL0CHG#?X6#z_ffu3fPhNZ_qz~JV3&tjR zb(aWlXDm|$Lr!{oqx2_gsmoJf2T%B+5#ZCU`wprM=j1e71U6vVzu5X8KIO0L2_Ah| z0b%~hJURLe^a|7ggz*(hKb4OYj^SL*E*sq>$sfIXOt)|VBLP}Eg$ZTS+q zyQ`XCd$fKfV$bZZ=Qk;t@Uu^$`#(E^ebhq`fXy+H)W4V~4Q!oKRePk3qdW{PJmJ8I8WQj9L{;MXxd?Q1P zzuQL;zX$)iSi$#mo0hE(9M(Nm?|RT1^)1~rk9x7A?BVH5k#Nm!7hwi_s-dQx4XswR zR9?g-ul!YYsA}8t+?eZ4@6ofXZ1xYqLr=)%zYh{iljPe?t;U*(S`Ppm5&L4u2=8iqm>-c(Z6{7wo5vEs* zf5vf>k88Tg5W7{eI6TQ0rVniXpt{eyeiJmscnF+Rwt5o@8i0nwDv8X)cbs;;=hOt| zEt07W&IMk!3+dSQN|+;CreER1({pUUXw>i!hkDY6sJF^%>s?k40kR1T(|`6uBQ)g? z5KAIpL}Efql63!FU?9hQ2WuZ!TU6N-g!4rbhFF&uuWf1H$G3)ghdXIKj!I}qj(QaK z;#1U_TFf6*ic2K}5pA)T^rXi2!dIqJOiB{H0v`cf1bEY#80*PaOPgB&a&Z)>{1!ihr>N?VhsoLH8Mha)ATR$F>1 zgcy>2{5DzHcolf2nW)9P#A^i5WSsde3DtVDe?zQYQnW~9#k@M&1_0M_zRtXa5$6&x$~T>xI&I#IMvHF1tYcMJr8#(X%uNki7<* zy>M^2YV1p?%UK_b)KP}Vgo6~%Ui7~zjr~WZ-%U{$q!mM#3`K&oUTlP;vZM~i{27zL zc3ua{Bbst27CUGc9)v%UHXd$CzP9hq7K>topdCSEi7R! z*}8~`QuLgy%H$a}oW*_09SSgeZh;D(JLw_j31sfEq(;#-obn;2Z*q7?6GT<*_i=)c zW5;3k;7gW<5d*ErQXCR7|UZ^lS~__Qb$Fmrcs=#h~vQgT#qGS`Zp)G!47_@nDb z%qdFTivKw&eAn4*4&E zz!yHO4e^!k0q0cfE!|JePj<%hZ+ zJiE#kqm(+HA)_bP9itEx4Q4OM( zG&+Ga`l3`BX;rc+A*MPn*ZF2K?oNd7|2Q^$#9%(` zPfWc7f%QTT&kFRS5wn%#eKOIzer-vUOKIlnIHXV=Rd5{~$-Rw~B!TzMiO5BHy-_M7 z&&^xqnIN0+V`4+KCZ&esnlOy7^M@}T?L})MQZWX7;cML3eg;Aux zk}$WdNh#0|P*>5Xi86HB&N29G+UKinPu z^XQO0Qn(Trq{7E6pFP0Ch_~pa4TzlP6N9vYMu86tulWD=mc5Xg&2&^6%Nkw{CI%0W zOE{+dPZEI-lijy?{ra_I-QA~p{8AbZ2p`Xu8>T@EyK^pl_G!9@3wvN_=Ho&&vy8k0 z5w#NT7n=K8d-jw|a@|oX-6wR%Zi>5(<<@)SlU#zw59NJJ=i&V?Mt$K9mc z?j(>rrFV@wQ9w+8=)!~U?(IMxrKUI@+!7Lt9n;Ze6jhc;+dMkqb;b8h(Bvds#if>R z=|0EL8>HtaC$L4zy#hdFJoLy56NDbp~?sHwN$9c5bV z4TrPiPc!;tq?JbQW0R67zDGhTMq3eh1sY;7e_%{I;i%ebLp0Ad8&O|vX_3rjCVr46 z;lIc!mE?3}X8>3ElNsdXn1KXmZc)mR8jo~mQEH7Ig}o%#FOSW3H)|x0&KRrgTMos} zE7I3H<&TBri4S9-Yj~?i8zi0D>R)dIGr}A39u|_BAY^;c{0ryj;}45uOFkHsTPVZq z{o6y8%wGN$@A)A$aaNV>AF=RVzSNnL7BLepOHSC<5B9$5{&8Ga4NC!-&L^s-pXA- z>*Z_cJff00Ux?DjD_OB=3gRj7_{`9Wl<19J?_mA{BuGm=E}=lm6ol+UlFLBOIwwv? zi>mwTRe2-HZ6TAtGIUf0vK5xb%ssw%J!fM&ghQ9Lgctu^g{Rtl-JgHL^j(yu^!_XE z&{{EG;f*n&?1kxro_1LXFOD`T=maR3tA0Hro_Syv%k3ZMZA)y6AeMn{|7%OI`_nwT zcfX)5HxO)?eE$6$M?+!~`PvRm9oQ7@8P3n&d#T}YD+lssh1`xydh#CT4;P_UJ?+!z zauZaIg?)&Iz<*E9Z&o9}Gd_3P=K72}#tDn~0N>q{(*75&W{42HLDR+bVBNvoCoh`q zyOcXnMs{S=@me+?<=xiuH{*F@NgZyx;vvmrYihis!QSf4)vdO=K7SW=ROZ)UTaRqZ z)QrxXbSUPDztLzuN+mxsXyBtowakhlMP1`hL7c_1V};dlVFtfdYyQsGc>Cz^yYqzY z)6Y35AYlACeW71rmhOYPt2%v}Waeiy{ZGzta*#9E!{XKx{dTT3xoQ=LHtUVv=sMKQ zxlVT;EHxsM-;fi{WUs=cUAK?;#rDg8GQsFu`1Ml`3dxB+{(vV@RAGhw@QjPVR8tKh z81bh9{e!v8DX$FT*8+fIhR3bcYk^rD5Ef%9c|P(sXc^s7KKp=vlbdTEInw+A$Z{#m z9+U4k%<5;9cKefTYFk9rOB};T?jynBP4XcLM(%M;ZJN?+52xT-f#O$p-%NxH{M!IR z?Emc=)q=%SJM{MV`BLW*XRoI;{QMD#xV9ULrGi_4@?lpUn0Df*pVZ1plo+&NV49x9*E%GWvZVxh|dlx>8+hDb*S_MYr>K_q$2MY!3UY zOwQ4bZSx&!5zwU>zu%YFOqf>&g9}j|r8@7YQM~yeM}oGd8w_6731hRf z>Ylkkk?|CN;=IdPiLg^8a5oD6apSQUl!AveAVynOUumoAm2AS|>vgN7bI; znO&^gG4wh_4}0Y&=elPa*5)JFHwqMzYxd@y%dd$|c$eDRp}{X%8IQ;NyY(2I+c{hU zaq~FEJQ$zvg7jhK_ndHfs2^QK;>t;$W+TmDaNOti{vX2-F~$rgZl2+DS0$Bc z#TyNZ$fm7-N}REOqY0uR=LgOm7^pFe^JXgrW{WzHjL~X`$dV&tL{Lx%h;H_^=J&fy z`7Y7eJ+lgYLyUC*#dYabpC$+)=@p#p)ot$QMW+25$%op}>AG#)y|uG8e#`t@xe+3& zp!+&P*d)9Q-Kay?p(UgUjAZ1A7`E-+xsF2Iv^m1m&Ke(U#9sxikVPqlxD;|}RB{w~ z3<(P{u1B>cFO78d7y6ig#HG>KhDsaIt{e9EP=iM(nN7Ut2Fbr~eV*iqD32AuWAUm~qOL*|DW;bM< zCRt#d${Zohl35U}<^9)=n50dD%GHVzp0lT%tWPzbCN!0PQ;*{F6Ml9jqCpLoMBwn* z>Q1Wa$@-yZvP#N5l=<-Wpfy&jN^u{9xBL|Tw)W38io{d#{InAZU-^P4Ek@m+GL^IN zi#LRP`&zZhYKd$VtpTuc7V+{y{iFaDMJ@2(kB!Wa`$IF|;xTSRq=`Rk^(29*2>mT$ zwfI9}jE+?N@B()>#Hg*{skEnx;(273t%R?WO$G4lU$sRuimaewzI6=S-?xGi((6BS ziC*iUA1TCt(fL?93?Pcrotr*kQtt;cJ2ZviseearzUyWK2+{BS-Qp_`M^`(Jn?x_V zReV-;=nH0j=L=ep5oVX;CAslD>k#y#7-p6Ha?&}ah#gg5LZX1}vlNX~ag-WNofTG_ z!3W!0UW&5I3pVgjMg3ji zc=ElE%l;Z3Gek(mNAG%~ZbB&q?rkv&G#Eb9zh6i!$g892(!)cxXIx6mxAQ+Vjr_@; zxNs|SOBMeMhYd=rsGC9L4G-DnXHCt-E6b_;XGbp1#cV8Z9eem% zE>K!WS!kn8>#6$kTPxQuTB<9S$q z>LqxPWQt*ARbE39T*{g~&PWs-(YkXeZnPxZ7|QI|wE zfBB8fw@I?jmTb2Tda7f)jSj>~s50E|Tdv-w=-I#*^se^!UzgC1@nDQsw_c|(Sd5UW zC-C|tH2NE!k3?r0S1JisxJUd;R4;k|uf0hqarWndVZ#{6tvupO)-$cZE%IG=Byt}VhnY*hNwqJ5z4`GKRpS$c2w%w4v)Z19+gbvO?Cu_MYG+yRQ$559iZaY^h;q)Q(6(djKBs*aS6`<@M(o zN5_>$H7c#y(flL%2HCZqg4%h_wRL*>y#!rZkyvRSt&`Yj)y=1RD)-R-CEmTu6} zE}oM01Pct<+aHO_hnC2g%~sH4vaFLqDK_OIA&54*kz*(CPaL2{eeglpiJzEeU&sks zA*j0szBKj@L>>zZsAMg%_q^4;%M)f0j(#u{r%gQna_IlZ2j`^fU-zmI7G`B2)bo@cKW1D7v0V-#_iDniF`AGu>l+E33{O$!2t* z#`yRT-*W01k?{4ijq5(_+`aJdhv;*C&Z%`0vlV&84oE0;DQ=-~dDRK?;qZOccEY6p zt7@*Nj@h@!*jJJmN{cY1DY$)P^%X%;Q3%%zG>LY|h5di8ST{aA3=GrydS)cFWjw)k zg=Z{@5LDbB$9i;$w|69|bC%O;%zhGQv59Q_P^Lea^@lX@*q6&RKi4C{QFUF@zU7;5 zyOly`aN2*M20TM(M!>b!C%*Qq8OMkb>`ZaZotsy#zo1EY(l$PxL0_%vBd%Ect1B0d zpw}$E90me7lHwb`YlV}%^%g?WBF20nn*n3)uqg zV#J6BT7Ne#=y6hbooFzIX%XaNJ?d2soPv=rr#8eTy*t>%o2LWGr7}St2~)?DHVoD{B`*@l+22ehX}Q= zyzX)uJANhcY$hgGcopLLdo<8?|HSJ9H(rOiCuKsZCnzu6?dOF%MZc~qFx|NICG_(= z=S=VS@_f9+v02B~Y#VlH0ecS{6pQ)mdqHm1h~BTiV+Uoay}RvIYuzQW6Owu?KE{!k zDggrZ0}17GvSs4;uX&eBGXurqzZ19iom1!wSD(7UJwA*%%$5xoNs4%5M>U#>Q;+bP z&zt^_qcabOx_kflj8Rj2Jc6j-?|#^;*!-;bQL zTvmuqCc&$(S`(xr7{Q{cQ(sF#&Hedz3tdzOIKOBpjH+MO!e7GgXg)LJ>pM@60oS2c zR$@#wqV|2)FX7pv`Kz5qs`T$smiHK*psCdB6pX@Pf|NNM^o8ca?2#m(;L%C|I%?HIX zhBZoTbP8k`2whzNm?ZCTA#)xDQJJOY2G0PpC7+-UOs)>=tjLC(`1U(NUWNFHO2%(f za3!MSes~GuV17^iUvDEX*_yW#fW-9q4Kmb*V zNOKXn{Vw*KJXHy&2p+6#n!fK-SNT4X_OHFj=Yx|W)~Y@SM`K=hb#ArD z+-ThbcVJIM6{v>4a?aSWKCoo9@uHOqzI`)Vp!a3+Ax4@mAadlY6c;#WJiCRz5}vE~ zALz+UxxmP2-^cY5Ya$31;8K{wt`2m$IG zU@R?5k8@ZS#06qM)H)Ap!mD!%pLpw~ZIpUwuq$Htw~O(=*b8r8RNuEb&gFA8Xn6_@ z4fQ%|{><8?4Xg{|ntj&8fT8JphV)^1iDM&QH<|gJ$XDLTE@_)h8jqfh=1|_5z#cNZ zhvOaaL3GA+Lv@P5WyouRbi~qiagu>7ZM+k@6-)9(cLsXpoebu$v@7s&rYLRGhx+;# z=GbE`S^u0f{|JeOF6jq`sO;slWQ(jLCApxkXm(K{@wOq5H+hxVQDLfgo3&IG!o3i8 zy&TshF4DeRg%V{h_L3hdCZkEuf;49Va1I zu1sy8>Nuzts6xV(QFrsNQXzmHm#izInrL3>U-7cQIOC!h2&AhJg6wX*Q6KGEtAODV z_pI0}`+l=i<3XYac$~5_?6pr`vSwe6UOPG&!hd=E_6iv#$bIy@f%G9L+4dOWBds*x z$Qatq`%+V*>aMf*BkNM<%w%)FvujaFVUIg(0_~><%5-~5C8#9l0+F)Fw|6gS6zZ~E|Oc4kbDG+;BUX>t~5){>c{I3mm-Fj&Jfv~|_tCYo%Yxu$J`*(L|<20GQ zC_6}9DMM}+t}&lyt{$_##3chIBQ6;RKj_GYl{&UluypC}_g1=qxPkGO-zuSTymTn8 zP`R9-^W&WX$>BIZzf$vNj?f$211bpiJyxy*Jx*6UF62)S4STf! zU;_eyq8I#p^a{5S&xO3l~D>ow&Z@NRKApFPpRz(QF;pg?^`E+&=^L z6w(1C|IienGt&0J=Xl1@6A-tIQikaIXJeCV|7Epb8kV$l0KDJBGEda(q}y3k_R(uc zMii!<3lbM6gR(IX=Rox`!oyob%kjZr=m8 zP}ITNKlMLlS0yiU$%tTa@_(VZFDK#c`#n+aJB>^vjIy+H!F6dLT|1P9F|+s-m5as@ zA>=ymZ(d7_H0=>Zgi2Y7wN>~DsZp!9GIs~d_aFjQ8(*Vt-jk;>#qs|)RLxUT`}T!U z?YJBzK@pMKvY~*1v+N<6h@wAFSMR)}U)J$Y|8(9y_=L$5@71B{D$fud41&vQ|FZvf zvzUbEBLmscpFb$Ta@`)hyr=+o<66agmtJ=6=(x##4g3Xrdf#V^U8Us;NZwc%-BGhL z;`{#EGS@U~$Z$ulg<-J#P@{xG1Eh zF@;(m8p`KwN`A1b;d91@{Q);J3?S2TF$&KGJ--VGPPoBU6r}^Q4J=pmQ*5zGctNM= zl)i=1M)M2+X*}OTF3V?n|Amot^%Rbu!;}F%^q_=u>^yjw+hC2vMHiFAjV+*3a|9%y zt#!Ky5Y_3O5}}4aX0HC>t0>b6Bl%|)b~f12s{HNC`%2d=h2qM5VsY%6Y8mVy$<)EM zYnN4&pCG9d4M+>o3!V6!_xwhL^nmNT?{_&$bM|bxUw2n?b5Zh3f;mDU?Pc5PzR`W- z-MdR)jDUE68l^#rU-B#yNB_sSBjjcT7fb~Jgbp4rTeulEBk?E9IZ_}3S zFEYv*lhy9tgs&`Ls!Dw@9VHvr4AUJi&3^PFMSr8Y+hN?hRClD&rI($lyuStoxKcC% zYiwEN96;5&fu?IoK60#FkrO^=71>oR5ihAtTpPzPZ1v;;Cz&*=EK3|?AJ3hdDao4^ z+*095)ZRjKmAaZJKAR-eK2;cu{&8h|arl$YH;GyVqBKjaz6MNV#?9wDf4`feAgG7w#6{MI86u%M3|AEE~ z*1RosIZINvq&nTG4^yTZpUivKs?LE)7-Z~o=jW@>?^l^qj;YH~oIF<{EmSf`!;t&E zya4+&dEQLiWpG)FBWrhkQ>XIVPE_k}{j=ax%p?=;F6h>G2PJR@+kK(mRgZ8pnL~i? z%t(U+Bfyrg7}}qo>oEQOeBYDVeENziM=qaC3aTxbGFqzfb7`rLm7o|n`jXs~5;qqH z4Ddw;tE{J!xkb#}cmsTaCZ#F88?eT89qkwM6pa7f|H_&SWycOyVVd0zB(XG3sn{pC za8q+O>}U&6`0X&9Bzcql5K^hba#?Eyj|f&thS*#z8K>+ZMwHlB`6kCuWD6t6ip1}i z22ni=`*>Hs2W7H+7k+>qrG`!xCQYT-jJkMkd{Ttiq3@DCZrBd&0Nwo zA^#i(qGK+7alqJNaA#$71eL#I2qN~D_PPqdMP>rqc(P2LVgXt8X;JyVC=25-qCgOE zYod=9q!7q=#!fQ$x&B9Ib(MU@h$t($XU3K|G??FP`57Kyq{q(zwzBWrOgakiT+w0v zJRd`$8y8Ku5Mv_VMjc2zt(83W-ZhL<(nthX)Y0vHz^MKObb2sPu8dr?t?TmTP^Gc{?Uh~2 zm%z?_bdD1LEkk96Oe>uboq2v`d_8sDM(9t@2QIsq_>KW7tJf4U!JlqkO|)jp4*%W5 z#|skEho6slyNmYgBB=vi- z{Sg&^!t?J@^nP&MKlx$lGqx(quSJQ&X44;8B8@s`q(ev{B(vsOu*di5B6Qbx-RXVa zoDfZPWboDxNdFdg&%o-=DKqBvVSM_+E3x^aVp!dU%og|1xZ);UZ^@iL!2bpSo!Prg z-+6sthxrl*zEyFjJUSjoCLRRmFhBpsU)I@(0(5s?HJv@Bwf|+>^Hx0W2=TwJx=DHR z1d3La!gV3z2gQBe6w;Y9nj!{$wR{B4+`A} zZ%EN-@awq6OkFYu7j(v9~Rsq zwjcNmc@%QUfL9x!a|&khYV}s)9O)aiphetSO(ixO4A z<^8~#m6ud2?N>{c&PUX_F((35L%Z{&{FU>+p$GDdn2(*vM`n+FZlx{XgD=9HAW9fW zW}fKxL+!A7Gf%+ru9xm1PZkDH_tf{xt%VnPMtVYLHHlkgT8G+A+ZL}3B}Ws>;GW<1 zRz6^*GMfX>S*ONPh}IZwkiO4$xE##TX|7uF^#R={<9`nnj!cIsZCTI;R9Q3^eg=aB z1Y~P6zF#31P!zgt$g=|v{nh}b-_;8^v#68T?`SUKj~z>0FBO7g2IU-(-*xY#&1OW=Zm?ifNkg zsb7JvY%;GVeE}z$?53NUEBAuohqOq`nnKVT0LoWKfU3%jMj}z%8w#NrLSQKx*Z;ni>|0-?Im0PFew}cz?sVJ(eqbt&?haQ; z(?e>rG2aH$kKyj9cB$8M8Gs;JxsdDuCMaMv67vwFm@c%xRqwKD#imlT(0?{tNBJpAVVDpf*Q}cyy zm-N8KA_Y)FR>nwS!R^fP3HCx)SqnYP)sa7w;lz5FDgZFL0eD%Y_8C(rP~M_70NV4v z$P*rZK4ETd!6t1>5R4DcgdN{!6fRb&J@w=HcA}Cr;@Y-ER>Ru`j$FQHnS|mWj9U}A z2EzH;dGY6osGeek)P}bQfpuM=goD2A)1nelNJ}j`v451}e=rVsA~}_Xd_&HsSs?V{QGk&jHEyy`8Hemn9|0}Gf&z>Z zr;usfDm5!=7|91y_4^F8Hg>XWx&@L2!ftAtx%IA{hqG&~%-#vgt+u&%*8NjhtfH!D zoI8L}vpU|&N#+79zdm_&2_Q@G*w6=)zS%gY;O#-2sNHsjXNHE~2`cYmh%*()1iG(N z9UkDS9FkF+{RyYaOc7HAyxO zo7ngRJ^Gy;J@7-!HRO&N?FI@EO z)17kHqo4gCMFRKvECpT%otuN76&&9CDPP{yV>`MHYtc@6pIezkQCJrEw8A;cuCJK~m94d|Q#q0Q$; ztzXMs!5+sVY%@12$|H^-Pv!aDC(qw*a~p6#0j9}s&0-X>hdovu%3`}j|7*w+%-G69)^*#rLxrsVVh*T+l>yNmK6>kEUts*qh;d$p zK(nMnr7H_h1dRoK*fk&RjvsqIeujSCpr`)7Xp@aZ)gS&5aqQgSRtlgPF5HQ3fiISo zBWAU0B~6oiI671e0|D6iV4uf$XzIta7NNZBOmyu6rA%2|5+DGxqjAM0g`(Ev*OtF(NF^&^WUbOWL zO1|!JDbt$B`C~GPxVxfGoK76L2oi9(Fq8O^4(>;bqbSJSGb$c%cBuqEq_#M-pFJN{ zcsw+7kW}|L#Oztr&LMXvs&hkGN6|TTSF)sX{|Kbg)H696Im^wD?c!TxmpTnimgKWB z-rzlJ99p4>86~EIGgBats-e*weio@6!mLIvT*`Dc{bvTCq++LmX6NWA%SGzgB!|O| zuUYOKE~lFfNLi)g;EhvCb@gCcJTcDQpPWx$69T(qOm2j6aWNEwg=;7;w`b9M7Kx5* zq+@oe%(6=L3W=V|#<%^tNuZKiY`BW84BlYQPcej6YpA7vRi)1A;|Vv-xCU2ci7|&*eNm zvy@7zG-f1$#7`q$kh%Y7^}T-2L^U>1fYk%t&oSC2F(;L&Hn5N+ipkK!0Dl+wb?y?m z5l|$j`7H{=L(r$64Rif~qIC7T0rCA4W;{XxFuSKF_)_B}&#jQ19^d28RB`_(#cXmz6OFur*t&k}+Q-6Ul8eWPu~KRi$cPU-T68kJwu zdWQ}%L9Wo=D$~_{!`U#w>iMU_bFsi6E1|t+XFv+^UY>%~-k*)-m-ES1s#k=4Ej1sD zK17~sq-ye!UcM~y926Xen2pwJP2I^B z?Y6`U%Oh~WaHCLpQTuUQ;bcW*e{QgoieiHTMV?JioWY~D{O!{AG_Jzk)v_*D+lpX&D z!i=p$DeX=I$Lpikhyiy6ua@-~kOEGof)GGK5@|W|6H>cNEjB32z<>b5hy*>JH`Ff& z2YHvs7rF!}glQnEO5war|1|v}@);qS%cc9Q+!>yLEoHPt5(pr3Iwezaeyb-U(vSj7 zXR`q8uYx}FzjF>G$jZuzh^hWH*Ru*|*FstF9+D-y;ABdS{`tu->l?~Y*E68ofk_y& z5X4dWTUS1(v28#Ap!mslS4Y3^`l|>BvUnat1VS&taj4?vNOyM6%2c3XR*AB&MKM#t zI>mJDySF3zf8r06rL^Kx6Gb~z88RytAbf;VoCYk{C~lvB92V;4)Tk|NS+K{?E0V_r zWVTv~N{SNF#)t-EVYJ*1jsoWm&@pBr<5%8{84yC|L&=qKZRU(tZ+C>q+R9Xb2~8(X z*c-U<^V1!UTmlq91mHcL^~^{ImZXt;oVXv_Un#z9MK0qFZV;A(Bs4&cI#k!&`IhA5 z1RxoyOdrAPP2U90g$O_77hm{b*{)~P9tWYb9FNY&o%{z%!6JQ2f*v0W7k@oW`!RT? z*WkryrthKMi(AdmlV2Z>6|C!;NNepu8!s3S5qZ~D)_dP9>&f(7SREtg`jPSGVx!Wk zrZ8G(dmw9F{h~y*AU7iQ?gHX&Qmjs`4R^QDN?d>$^tYlg$!Zmpvt@?gpa9Z_r_Nk#K*>2I>x;}qn&AhNr@NKN`-Q7hihrv*VmWa@P{z^f@5sHS-LpjuG_)p1rK&`>i$^IiaA3eflLIrP5H za-EXO%oRGPvaf)FGPZTR9$Wj_!t$$~+yNc8=j3RFTHA3^*XmI1M|B5C7Qjl?{8^K) z?AN>@d=B!Bm9)L83iFw+m zAc>VpGk}D#>FSdrpmQHC?}d_%$-&b z_(vrid+2T8-vQ};(4te4Ta;W55H!Zs78Xv3XX4~&DmHxDXE&mYL!4U`;_I1FdjLG6 zY*de@Q;9u8gGn}QZ&wraD%FP*8bI{m(~7miKB+bE-QKtk=1RwjIsdHa55%QR=FU0@s5rzPs#Ztiogeg1eLL3P#7 zpfAKVjc9S$8&vk%q573+Ud)wV<|v6evV7^oAJCICK%^I6#8Ax2bHiPEV6X;zDw;Ib zvfAD}NN-#X>0HZ-kID=|;y?>pevq+MCCD}xnf($JoRul~hP-l+f3aMw8J zw*TGuIvK+!*Yip&63&D!d7-Yjeyci=8g^)Ez0FCJ=L-NI%+XrD5f&Yc@_6 zOMXhN)*i$^(P8gW1&nFJygHs+_ySC%Scf7!ROEL>y!j&B_X0t45T~GFJ~Q~xe$M$E z;7>r`uugA8eLEJf_IDXj`YN;rLJpYy@j}-dRmW~`DeSKtnYA`?im_F{DQ&ToteF8* zL?wWLhbQ`nQSTyuBId>G#q!W+pO`Oy^XKqvdoFb-ruDN!X3|w{kuvyIiA})mqqT*6 z3t?GUV*u2~h{$ZM7<8eC#hrEc146k2y~-+DwP`~tM%Q?Z9sO@gYH~r4mWK0w9iRy` z>#kaJw>MaG014pgF6;*7=Rx&=-iC=c*K1D_q+@29UE~T0Cc{^a;zt#7AY3=h~vMt zO)$eFcaIG1>HVc=m0vso2Y-<|Jjh#L#6}F9U{zVn)3d5{1APFNz0*PH?{B(+{a2=} zyZFz!7#eUOn}={8^T_v%FMg^&e`+2O-pvks6ks-*`R$)Xcdz50R#jZa!Rd;Z1YTW3 z>T{T}W5g{LpO5>^eA4`7v~p{&PDd~OU2n5Q7SIg+@GI@aV(!~nq^!bnjt#^=-v_kF zQYZ?!(M3fHAx5_Hhi;N`g4_GMCH2bY*Pmj_sJ9su{!K5g^{2`Fc??1}iBPLDvOKYI zVF$`BIFwJzy7t4vNI@g-@i|5IfY6MW??3pB%1(IT);pm}yD=k8;x~ExP=7$2{nJ`G zmufpsP2Q|_pqL`EitXs*!Z*GLYYyc;u5go9iytERF_oJ-Gp53tZ+wrK%za_eeR)pM z(m^nPC_iT$V9dO5nC&`-;1=QU`J`=3 z!QK0x&Abt+Wf!v!Mq-mrEf*S`zxos&z-v-xpkLv;H2`Vt1|;taA)}%LcpcRslIBd3 z?Un4+u>*FVY8}e%QgNc|rsQsm32@)6=r6?pYNnGS91fUYS388w3h>wjjSUKcO~5Yb zSD8U`KNs(3^VC=Iz)f!x5W4sI3T~Vqt+yLf9$PP@j3wZVv_U{*C^9tnW>l64m{$>2 zB5%#jg3W9QTUpnZG=s$XcTpH&TG(OOyr3wf0PIt?Ei`8ntdcZTjqwpt$s{NjYQUzS zYC4790`MD{{ zj5bkZx6xlYDdcBcrh)}dJ3w!bR75ziWH!buE$(6f?HX%y$ zQ5zM2vtMI~&WA=^&2&A?%wuqUi^S0FLUfo=+o6@R~#UTx9Lto(_b2v$AUcM<8~B`?=bcqN}E=x+)FO2G1~l z8!(D_dmM-wG~1X0C%N?EH8g_`AhhB)aA~|lf>Fjfa>;Yl)w3hs_7FZ&AknG8O_G>( zJ6ph)JYagyl0#W#b7q=st>;vGW%Gtlb-`XIZ9RsKjdpu6>8}*tUB^mO2*d9)!q$J> zI1Q^3WtZlfD?Agj)rUUu4wy~vmA(faYnoqI<-MtG4g&OMfsE5+ms_^Aru$qMcq&WBA!QY@WX?Uh@e$(c3#2!XR3!LbdQ%|LdPzHHV~)g5 zju^^iefWjNEUS}O!Dsa$7kL_}1(_P!eh5!l_Bj2zU>UTUz{8wK$Iyx{DQe3IPj&m- zNRhla(+V#On0ojWbn-?4_e1HE#g;4VD)%W{rxjplR|7l|xN7A1)5*XtA`P%)q$?{J z9SPLX=CGqU(H?1ydk8t!m}GMhyL-Ld{9}u{J1;mkayy-<=F_&XC)qC#~xq9;QW6fKUAL2eOXvU_7tNtavI$C;C19(GeKqt;YA4HcWbXc^{LwmPRoOM1E(a?M zWg~lh3Cl3=I!(^vm<-A(Jv;vwedDp5bk|pVUgJ<0XQvW@u`qDuX4{E-MUkfttvn7JCA;rPS=R97Y59suqX6VSZj(MXX`i?pS%;KJZ5^r=`J87C(Tz`YrQkEpNclw6 zy|~bv6C})9LqXBXwB~sTZ6zqr0k65hg%1tqJI=2Hn#olHx;2hXQ3I;4Xbiz#7!z#T zVTknoe08Z$Py2NhkE>>Nl@OSdsEZ=g+qFCgCF=dp_#uEoHJZnG`1PD5Ga?I<7s@gK zvpqC%KqmSZK1h@`xq7eO1%7a%IoOckvZOY?c+8GQI_>sH7FD;EHEo`MT&rxHAzC#& zR~KKBOE7{<6}`ELZ2-`#sP-Us7jfr@D*0lkESFtQBp*!omrBL7)W?I(JLNZml|`Ks zG{xSX-yysT7QH+l#lcp~A`56lBmML9F_)KhKL5IEP=f*2lA8duRxIyyUyA3lMS8*7 zXA06Ets8oMj09pWik(CcP^xv zr^in^JD%&3Kdna&);}}(@$$-*o%YK9V-z5yD-4Ob)yucuy+JKdGF4g{<#-%*7}jA{ zAjp7n4lezyjT91c#GAc00StFSYyWdHTMRvLvH2SKK8Gcqtxt8y2w3Ezw0E9ZPu|GX zlfAaLe#gnI<4__%N%~IY4pJF&WuR4(KXsj1+@LBFQ)(op$zPO}KhH;dj29Z?Egq%m z47-#Cy9e-^XA;GSbsZ$ZN5SN$`87 zxV_xSkf+42TiwEUYn_QwC|t*556zUFT*Z59?ux}m3i1$@Jb|yPD88ygwaFJ$zJG9J z>h*}}D69ttFa=>G#PnIkBbXDF`x`tg{T>MyI5K?u!WsGjA$x2p!1QkY+a|Z(-nI<@ z-AdTY<(hI=zuFPteULTqyVCyh=c1r##qG_Eq@EHB9u9x2^2(8Gd_V%`bSG6XrsPVJ z?KBsKOC zhwgfo*QYOrXY+D65M~;hS{uiQoEgbcF#2-%Emx`|GDR2L9+bZ=r~A;#eyUWdTC`%H z* z;@e+f{sZl)04CWsCzlz&uJz7`VOx)rtb9d?{2i=r|&&_uVy(bZ~aVpbytpia#!QC z=JG;fyOEXt2)CCen^R_^nX@~Y%lJTOpZ@R38tW zOMB?0qT=-SYS8PTTOR+=I@1n9Un`65TN}Gc8ybA!0km)^WNwJ8~0_*++h%`I^tHS0gntBJs3x!(w92*W58GqaQo%oJ9j*bD6dggrEU0$e&5n7QV6N6`C{dv9=&-T*; z0sSAl6XM#o@6q|N^*t2D%!`%PDIZ@X{1>`47c5$JhyTn=__rSq8el40)G$m9sY~g7 zssgl zzrWzx--#t^j}mOw3eYEZM&2%0jz!#(!g$t1|FWZ1rrFG@-@m)>L*$W}1hfD_ds;OQ zlQSypK73c;aF|F#wQQ2B^&W+IyK*;rblwxTig_|i57q9f-j(%_WiVqJl|}EXPS)xU zj0>Es0ZPHn?E4O0-8h4!lNm-pV1Vf>!yC7F_~J7Hb|15vJBtmYdo}e!fyQqY_PcWS zrh9N`pU@ozt)Z;G|24w*7b@0o2`*85U8hX%e|(gn=hAriS6B4u0CS>11mLnvce;qY z%dn`3^d{GKTvDohuEc&VbF^O3v?BbamV?(>U4BJB$`Cp^n19=cZ?4vw!m9U6(}_;e zzaX2gus*$$Vr|rK3DaA$)=Ml45R4@rKJF=f@2V=fAZIkGWLu`@w(o9W{*36nIC?F` z+f7Ksqoxl#ZknF7o6y7e{8T)^Y~sFSP}`kY_JW>jKw4RvqD z=xn&!8^CD>+-iFxEqUrvHZ^P==akVbpy2QKMNSvv01plqqyS(Hl{|2~$z_?Ls_#GE z@I@qZ-+uA2J0yUR74r=_F@IbbWk!#-JoYVKbbK81qIg1m_o`mpHKog{)2~VsaBDo<=0Z`zFhu(Ib=vEc@VVs!620drTzmVcCPj{A@U&ZxfWg`Sz+1|q zqzR!;HcyunUjb332Y+SyT^q+&o|yXns2VlenPXRk2XDINdR-k*cb9eU;BjNVtiTRj zlv``MdB$R0)0uxkXe#GVnUDPPb`{<`zc1QtVHsBaRRN~KGx3~l662kgcpEQ7_IAng zpu=1DaoDrW-H8e@u@5RwK*=JtTpj4PT-%Wtl<81T7!Jjw2lW7*;*xk`73+r@Z}HPvZZF1 z&LmbPt1E)zY>o9SBO?r{e5Fln{!{Sv0vD3KUY@3n6hLBQ8Ncu19$&@H<(!xRMx@gA zO9KMaEvDbibo)BuCxgoShM%^{H@7<&27RXJ*C~Jf52QK%*7X*i{)qbxs#M_xhnAUA z6a~7GY0+8zeOUa>HRuiFul>}p_bU_CC0%@yUCa)=Qp82kG~%)*C>im*8U0-}Q124? z?DS-qq8gMGkf~-MDQn}oD-uzup*x5=0;*vw@=AYt79C%AkJVMc=CTR)C}smVsZF0v zc1+2YTZazTY`&2!*s70!T=qb<(9iYL+7+&A>0uUsu))y{%xsJ2IqYDoH1gn=<*}eE zcJto67D72)TvSL#H<&WDZFHDupmVL|!)S@rEwN&|8WVk3pKf#0!7l*Zx*Mt;HNXDq zJAOyk?h=p|zUu=NmrrL#j)-jb*dK$QiIv2t1y_S&Bf;oW*HrgdQTl_-;nU=8tNp!^a>vXXRL8Y!OnlfZVkWuz zY-EWQ_%tT?yuhWfsQ_YbaO~~3Fy6;I2|ri8G>1G-$3i4irQ7Gz?|Ph-Q>0F^)`$^R z&ji~aqYpo?E>yk#&{6B)X74rdRmrrs-8SRuajk2O(aP$&^@po7Y$Fr)3G>h1zOa^f zF>i^WOhV{p6aRs}ZhX(+YOLML?Tu6J`{-AFwPbl-8iTOu0{Iwa$p7?LdJvZT@Qh%z zMFv5Kko-tH){6MG)ay8qn-ePaeY+x5$ze=jJM7OH|E3?oCMhikOzl-@68I0enOABY zKlX8T!t&s|@u(dB#*3tnep}%-4nf=L{Zlt7X=R?U3mL*ZP{n>74o z-4pJQ7rK@~LU3b)2$J_jxuXJe)%MLqrJAYwlUB)^zmgzcDNAH@<1Ii3 zdVim1)uq;D`Mxt8gQDaQd#<-@mic`a^AJ@OqL{nPPqn`dn*3T9d~Z9kv-Hiviyal} zEhVMwyPn;fLEQ7xPhN}`CoJ113ZYoFfhwQfUGY@odyg;ib@r}%gyZest%MjK9BQ40 zNQS@Weia|CF#s)vp;PY4N*7hX;AIEikermN8ESd(r2xe!hf4tLvPF;-NU5|IkUE*+ zG`3?>pkyQ`UPKEiUknB)99|dyEy$|weXu$OaFB~tbGnTgQ<4I0;A~LN3vMh zddxSGB5IES%x&pW)bPV-w(88JOPRYdpvp^rEpGy%l)#xkLO8QoN;%}f0j%ztZmmTc zoWxF_9S&I)>(+`0PW^llC@8~SIrL~4YzucW5#jOY=Y}{DLq=L(B>2_)O*pzOIt(tj z{1UqVJ6txb1~kqunBiBZ8YvsH2cF1gWad7JeR88gl@a@#IpqM28NBtK*G!(q#p72N zUHRCc)b&Q(>5&F&lj+_4(Z-rBMo#R`EhdQ$IgY?_5{XE@VZ&qm}N z?CAFs0*4D?dOIdVA5V5;_GZzL{4`t2#>Hy|n zQ{-HAPi|PPF(F|4#6Rb{i26b18TVPKHAQT@;o#jDo4xU!i(2vF>X=(Z>`=_0+>HT& zn3n8ToD@DF*?4#pTJ{-sBPs(EXcNiB2+rg-w`( zL+4s2GbgPEHc0ev)*#XX@Er+2$*5`>o*X(K`BF!C$Jp{>tXDy(0Ak3rWY z$_@muyir>HXDa&TyE8+)vcyoJ--(&}$yak*w@s0EYD*1{o%|o_=#G<>)+bJGP?C~E zMm_e=%d@7wX+5^?T9XWQw=adUZK@_bQ9I3+;Oa66uW+N&#oRH7GBkf+pA$sEen2#GzyB5 z4V&WIB<_yp*n@=MNM@}I96%f z%zg%;oEO=$^UEktQx=%+H@2Q)Y&MkQzZ^ZU2L_`pb9pFb(LW!z5O+iIe`&H3EM!+Y z$SzNM5~h{`NQN?!%S(gaA)X?aY#vNV?VT{Wt*Xx8AeqeQkhC|QYJAv4!A%Qm$vuxh6$H8 zM`d-)Uj^HGxej33Ih=l;PI#;em$*v`xzUe#mBc6__o~>VwP~nMA;RAWt(i`{qqiT| zcHi$iN6Gcsx+eP>a#kRCX@&gk2_P<0OtG_FtNQ{wCv|9>ep;Mf198_^4BiN-Gz!Qt zdZYO>c^_S(Rrely@Qu$cB)CD8-}V$m*8|s(E6rnM_yiWg9WaZ}GQT|7bU0$;QoA|; ziq5L)RddFxFapW;tLt!FEkEmzz|lezv?2nBKp`KQ@~+zIY~tz>P(46Oms6Bv>(AAX zh@fN5vT&&bIQ2MonPz4zt@t?iQmKGIxcu)9eOhVEFT0q|^Nps4#2j-{7?TJa#GT zvV+q8(>kBE^sJ14gM)*zPV2C~tswn@A0Mq1l5s9=xNz^#Ay<`GW2^gB=1wvZLqC-W zjeAQN1>Piu_YK>#yem@VtW8>8)L$lQ#-|La0Xdb7s2bfcwHEpoEPpUN4ze_VX8Q=E7A{^Dyox zUgdxgjx$kRk@s?J{-*>qfqQi+MGz|XCfZnQP?Tzwq*rJ7UmRt+?v1>Cnc|_w9gM zA_~SZ+Rr|H5A1wG%#N0ZxBN-^H#*783ic*d5A#5;L`R63sgY!Sp9^t~&|0j49e`QydP)hRFLM@ zZJphhl9JF*0(f1OH;-Z4q0JW=CH@knBi~4wClHRxKT!c1GR~TLFLxvMb7RS|u6AlW zT6}K~J4U1yLvNdnmu$B+|60ED*2r5qs7^XGjpcBcVp^7axcRiPX(;w*Lqn@Z#QH_9 zaV0xXe4GY$VAN2@6}N5uD*9CLiYDWxoMN!MXx&N10lDn94cqL*o9e2;bEowocZqYc zU?p_H&j7cC`ybA8n%uB4nPmYUZvRKoc|St^_;LI=Ia|uiIDIIytkT&uoFscy_LaTP z-ZQgvhpfs>_Bh)Kp}4a`PS%legk*1yzVGiJaK9Y)e!pI?=kxh^Iv+uGf6jy`Mt2E7 ze)gPC#G_I}3q%~BPvIF3_*e-Y8s=kWEkEd8L%)akt6rV0HQq}iDPUEg929Lyxrp)L)*bi47r9ULq(DFokBo@OP}L<(6tq=ZZw!ZQLrr>FZfINijL z#3`*CFkDuB8^8H`b}FPx*cF)IBOBt@^YFQMonBH2hjzMa;Hj+U@|^#m@v`X{tt4px zmY19?zpYZyc5H_vR{;49kD!PNn<7+!^svf^+9-H``j~gACl^s?WKFK&G83HLY zow1M47TkW+Q){WvNf2p}#_<`1$)hlYo^We$%3ANy`e<3QxzDBw{i#{nw?zyWH`)Gj zMIGfBwU-+W8OL^21yuW*dSqqiUhf1G`CWWG>qlO@OoiXp;<_0dtMVoAh+j`2C9XS5EtHNdV7_Kh zf1Fa+x*6DYqEAI|PlL#;GSQRs*U?B5Qm*1*HTSngHypwXZehc^B+l75u@mbO5#&o9 z@mq=h!jO)q$I#V_ce#(>B}LI~=I^y*i&n((Cvll$pCZdEQ)bHz^sCQ4-5W$ z@lL`)M&Iw~+xS&tY6rQ9HHSS9PeZ#z992re2Gusu-5-zFCPuTGYoouh1XOnX zZSevsV+4txzV4`ByA|xn>%RNRuefoxmRkz_uAK3exaZ~5{ogT-Awd4-*Hk_ues{#z zUA2L?RSti^O)#2RGYPN1$#Y^-1AqSJOlB-}E_61o5#-2t_KG3?TQ00P=ROnjNvCqk zh>6pIHTbYd zF<>@(|E$d?AAF|CQjTmOLy0Bpj}LoCz+E6RT20&IFvJFF{<6+|&1v7wjYPB|^BNUrVD8QTZwG4%4g#^ zZi3F4-(P1jcpoavx(LK`!3UnnX5!c{P2j%X(sj_QptfY(&5Bd>p#X_Vrgt)Z+4~E6 zYNA`}RLLx8cI==AY%%$}b9om@2;1)|v(|G5-)g+AOSKk_vE9;$y-YXxiCPiG7Zmyk zBt7grke05Un}bn{Q4nd6NXx;xZbMFb1LB= zObm4yt`*nE)7zXvSXDFzepz3?*tPi^;kbpldAw9Wu)pFJ4_FReLv=%4K5l15AB11~ zb#hJnZxlV(aEt9()=rcermZJDPA%Qx?n`6N;!FYz1yqWxAYT}=AJ8Bu66AZAhncF9 z&7<-Hd;}T~<2I{UAA-`W>!c z#b(q6?ug^uX6B*#0m@_lK%dFWdLPyZ(0q5BJ!DXOeUsJ5pOetIPWLUnpI@(*V_Rer=kt(|4Q1B_?b z!((sbseE#7t&|QLG9Ce2DEred{mN(vM(R^Jj}bY<7rlLlz#|*jdi(}FoV6IK5w-kk z=l6@`O|y8SIQeT-)N-hLk!;RKWaok*5cFQb+WYXsFZuV~ZI9}kJNS^6%~P&*CbnSi zjbHg0_^I?}&BCNfaIOMW8=Oo=SA=H=rXc4$dBfV*)EYdRb`;(C3*BWXU!pmFJ}I7L z&B>4cy;_c2p&V_Qd`IVoEtjYBmGOY~PwgUivsb^g_f9FY9jrjc0G`X|ecQHUh%U2_ zwGHu2hB;hZL3Jz-K|JZE^E(SV+s}u?r0!mVu9LY}9}jCI+sD)i({?Z(9>!nIbGmg9 zY8riGkj%&^zm(nuZ@{oEfjVMInsb-3bC}h_Gw*#IWc2iRF&DEkjGLeW-}~+nZf`E_ zh!QPhMLQ7qqNOQ->38f!dFNv}|$UXC&Q~MGZNoYCR6qhTtEZ^8G3_k^H@PXCVUQ_i>;~UvJOM2%xM`Ks-X6RiY*!SjvE=dIT$WarMdrDL zhpW0n0(>BHJ#r)r3<@&*5bV{VEGW8U6LhG$&#c5gej!XAdgHRK>p82^QKYod^p{>1 z-X2OnEO7BtNW)_{g~^ui01pS8a9Ovi%>RMPbi#48YJ5KVwY0UxoiW8Zv_t^rvbJA2 zzQY>#^NUM^>cR`2Q$%9>jiUEaqv~zQBTbc#)31e`cd{Uekvh7s{n{SFaPg5tYVa4!MX^{xOZ~nw>+v;Zuv}HPijDv@&Tdd zF)HqfJN~e%5z@4D%B=m7l}z0+_XZE z5@>isMLDO>i=M!T;3-ojmehWI$}^8RM(TffAx-n;zMH5Tb*Om5bZ9NUH%^2IJ7llC z^h5GCNb|lqxbFb#e+=ezd_PoM_NR&){byXl{284j3O(4B=5_CtXDG&bo6fCjfp>@4 z9HzqReEMMiW_pne{F&TTce9@!-7_=4`MT@ivh{RjGO2_kRs`sS3eN3X481>eq|x@m z^cj>601250otk}^e)t)6NAd z0x0_s%K$IXIbI=p=*{m&)I9s0q=lQt+k+cW^WC}lL-6W&U}xL-_+s(S3l@JyGe&Z=o&JJX(d zcGKhtNJH7Rd!!zD*?z}@*y*=0zh68^sfKWDOY6tm4yq89S{>v3fsW^0fLC_!ZhZ>Wwi3Qqa7f& zCqtwpdhEE`pS2@X(33|T=sPEcN-@*&KcbZDQMob~0mV6rs~4L}4QjVF+0p4YW9!90 z6-+Um21Ef$kY9=BDhN`xp3=#E{s@sHzrS)WF27*TU)jQ>q68Ge2@<#V8v0X_(PPjO zcB%@JXyMX+XX$u=M(0_H!l7CwM^?r}H-6|x3KSHb3%n^8oJ!dmm8;1qUHQy{_hgG% z7f7orm+oD8N%q>r)5?>Z^|pW4T?~|0Z%Mm8%?~LlQ_WeUQN-}foCOLuAu&6Lz{gNM z#{WRH0RU^sI10j+lR)b5D6&r#S z4FxmlcZ9s%btf-xV4S}JlX(ZPTOX;HCK`h;B2|%ZfmX7YJRQNtP2)mHTY|6;l(_xL zJ&0CaC4jo__2@aUK76K?4t9_Ur}HsS%mng%pgCX>8YyT&Iq{X*b)GNjLQhm`NXVCq@+bbcsrrBi)Dpmc z{!_jF4G12nUA|Z`+EFbi{IxlK9T#_G4#vJO{ejx2%Fzt~7wP1QxRRp*tPuN~^YcyR0M6Z#yE`(>uW zqDp~X-;sx5g2yExztye=*zJCuaghD`W0(arzkzxOQugf$@HX>Txn?xdJuY_>t02V0 z-*tL5JJdN_J&pjz>>ZD4uN{`*HAmDv!epLY`{cHKs3Sw@aGpPdhlE}I7AEg7+`xyt z8v2XC4b8{0Z@X4O6Wp4Zfp*@ANP^(CLu?Z2YXG;XLedywOccwu?IYm#Ii+cN8fB7+ z`!0EJ2b~SyR)rVx%hP|_yY0;~e%nk~8t4@QM-qXuGN0v`GS$T(deA=kLzZ(QH}L-0+3#~NR!06DPe%0{t>To@@3ay4V0m6({k-( zG>K!Vsa4f`$<5VfAvjcw*CN|1<5Lq%m=6%TSmKjfAH!z!B#xYA<%lDI&MuIiaNdp_ z`$qhsE7n13^?u|1_J9Pyv8E(xy(&6k9(o?OkE46L@Cq~D1nhWScr&;6lJve?BhLhR zWiSB~7Kd?H(x+{?a)~$04&(~mJ~evhMZjc6(2oSU$H7082QqFS^5(rX*J^U-it?LpuVzCa?37#w*`sVIIdM$ghqmBv$Bqib1@hhL2)J)ifJ&(lILAE74aD`6f|Hp1S!2bJN+ zT0%B_FKQuCogr;OhT-m{Qm{)%K1NqU?t!+>TT~SMWJ3p(D;+NIGj+PW#om0%hT=REIA{6S2Z2c!|Ayu9BMw`cnEz?%Y75o+y`PZ6m#)iLMq(%#(V)~ah);jr5eS2t;vwffzNUcYM zD-g6N{DfZ&cUA%x+#9yWj#r#lPdy2l0+HS6z|j8e+f|_1lm;?N;8)tUtBB=kIt3V* zqEg=b%Yw`}vol`*e7DcI+d5bMBq&tOOursPV}F9{v_fj!;u;Rg)sH&9jyS)m{xSGW?!VQub^5n|FLd;=p&;do-e~6E(f_hbp4M zS1?2y%fb8`-^;w#wfB1)&_&uzm6-O7JjPG*BXD** z$KMHuA7iLqrxZZIBc_D`vG9|arced)0mqJceBYSs(drsa(zCfG*V+|q^N5*3_2p^5 z5&Da)(%X$EeyL3ho=O5#M~f|0PoA~8SWEQ|!3D3-LDO|?5nA;Tp9i$h8L+d%?cVq5 zq)qh8SuOU56d5}F!|%B6eu6|dJHa}?dvfIpX6RkD0 zxj!%Q-)MMUBe4&roJ%atq5YySuE-$K!b!BDwQCzG*2dG9`LkKD6F7s7=`TLVd+v6r z<3|5Lx7hM#;W`ZCSpo|4TMf!VNjcTu|K1v6VY$yaOnkpyVwiZD&?xOyg;x_wRgpk# z-&*p!wzQ?lh3X_bAE@A!PRGZZr?V$-P5>_Es!+e@|3F@t4})e~PyKBEj#BHAQEdHZ zNP`RogI1nZAP`BBxa;n#mi8uubEEk;ga{#3353;rN_#DeIPwHxACm9LhkTRRlyzeH z>Ydcuy3(=mEZ4mKzNgs^ zl$MLF<6Rl;>DXd=vpPFzxd_!lSia`EM9K9CLs;i<^MjtdS|aXVvs7SA$!JY@1Ge*I zV`+u^lGxnzgpNX^IOP6Se&DkCN|VbO4HrovAdc--ER907!GyefqFt#HIYT=k0C{rZ?9a>670xmuIk zV0J1A4goTWjLi%>VOG-W%9yb9!+)T^vs9Rc{Rz5w<@Ilo6Im0N;>ISv>XlE`P!%x_ zs~l4#Hs_+>7bg`S(+=TD`f>UmGQZzHF}#n>q7ny#v`pvyE=-nIt~4_82Z%VwwJ6MZ zdH&xRoO-WzHW$J@KOV5dp8)w!H%C{TYkYs)c7TcLE!OmXsiQFRh-1pY7SL{fN#ZVN#r zobPC{pn}tf?aLO>=!^qg9><32XxuJMcDI$mfn-+u4LsoAP-G2^N?RRsH^qjrBUiFq}4ywLd8WzQ@A zLb#=DB(XgxfIgU@Vp1?`P8m<(1L+|0sw`l3iS!DT_6muIejlDhD!@(x)Mm*Z%io)`vY@^;Htc!g^}3Vhh?b z^S)gqN<0?&gO^KAlbxCpZhi8VHLRUSIih4se`+Fv}yQTk9A=pzlW6( ziKl$UL4^Z^uiLI$bTe`SGAK%$1Brb|N4J~op{sbBm=bm${)+tj4}8qX6Wa>|k0Ag& zrtO~S&`+>z>B=(CI%$k0sv2b(uD#HA;05P(v1+y}0+n`I3w4_`Bds}+I# zR-EijR=jfcl#fb>hj(#&0vhv?Xwi9;07XEnoYug6R22MI|Q8CCMLqGc=dud76PSMh^XE zW(6hCIBX^CaD&V10Ia;zwkD1^@kniynkKQPtQ}I{)5N0%hm9+IE~?@i*mW8p0*q;BMNC zAJ!(&dSJWy@6BsQV=HCxs5`1*JKx)v=i-)Y8{T|R|3J@Yedl#EH^Fdfp31U1(qZwI z+{00~MipgJOyko$pOi+;nR!YHzZptE;!DH!_OsDFJzw9s&kBW>XL5LW$1c{d;fK$f zYhmK{onhfuy2G^UKCiiYq{_#iLJKIRbmF?Q`Y%!Y5J)tk$m+$(O`JnI ze2XDYF!TqC`AeKY8ssmFPNxvv!!5%g#5)u8@;XElAs(Md9Fy~;kLc}RZvAlclmBL z7m=7)%kg(DkU6I&)mrB9KTvVNkV+7%E&dYN@qQVpSgm#KIZ|duw&g^_6^SXaK#my8 zwmj{nLPZPCJP7IbyL0Y$=kthEJ~(hU_9wrt%=@C1zar6JS3Jt9(#)3|d{NO^btTQ} zNZritgm))D%QYpp98mHM{m5LI?|w~2C*%EpNX^(|u*Fv5#&e}9Hm=`$!FdCiqUS_k z2}UKyFB3=xt*cNuH!65zDB9?j+fo2e+8srXnOR!TR?mR^!sh;R7=Q4EFDm5mLRZ8@ zErO&RmiA`RgEd0N|FS@f0yI`)R%^$gwK4kg)TF}vQkc&mCDN1qDmoB2a+?YTlsvRD zo$tF?+=&DlR?DA~RhT`)gQiqCb@V#L_OochoCIBM3dd*@@9L( znZU>TAx1Qx0zK=QkiF349=-^V>_e;2&&CTT#_vFQ!0|S@D)APGX(f7Jln<+%*b+&Y zHQ)=T7bp_xZ8AWS`7j?y`NjE=@qZxZ-;aIhuTa$@UZMbnA__9z`le}jR+x08seMGK zR+=DO@ElhyS~EQ#zLZq;sn%ks?z0Yy24?w0tCI(U6GRmG#*xv@s>V)-DNTyhdJ8za zFKW=VMF%TGl#goMr8k8P+OiHKN0-dgK(Wd%&j7W#BD=lM&`^HaFXjL1Y)n80Mbd+7 zs3o$>_LrA@gm=mX$FnxG#fpppi&FblHZBMyk^Jm#SjoeB#V3gI8!?t#%u(%Mav(*B z-nvU3Z?{&kRe{qk*Ji&-XBhfXaAZEyG`C=%#MGh5g9~Vp6JNFdalHA#Ep+M=dl0)R z?8FEar5D~`fsNVny?%t!GM9SS3?tYk;(NMvZ$Ed^{;$05wr5y$O*P@`=b9$jyv7ED zj70_AFl&r z`rYSu8sSW!TV1e?EtJpQJ>B}^zJg;kS=&_;ZTiGhsXLezDEzo~n)%?TtNT_*-AY1F zw-!6oe5{JG4-bDm=@-sADU9tsqnlDUXMddvDv7-yXv21*7WUWWEia3+|6kwvKhq&4 zY2B56t>DkPfGv`4!>}~1F6U1oYd_p*-NemuM)WNWcA&3U*jMDlG~P_X-!%#u(+LKq zQESzpSKap3DK(e3do)>r1+?MT6xWT%wquB#PvPRdNljXbaHc>H4YNXDi(FaWvNeqY zEJ$H!bc({-XwkT*_Op1zI~%$;T1PgWsY-|N%K=Mld1F82dnh$XV$L;Q_PU580cb>Pi(XtteHVJ#3D-Bqy55!ufp#Oz z5X*Y(tDoWVZFkRes-_?KJ27>28^*kvY3KIz3`SbK!oL0@Fexq>#xuIdE2_}&U>K|b zSSwo+8?%4hzIWM+^+;o$T#Q_^KpA#?YP7T9goe%bYI{nEDA^ zfg>D>oN8p;l`8@!1afLEX=G2Je+)0fg=DbYYj_F9GsW4%&yjJPFg_!id&y$P)@j+u zHLH@gz_mbrW5wK0?`*h!uQ!75D&^kgzqG;whhW3A)uz98wSa0Gc-RUgajpp$J0IxU z8drwDB=jVZ^UHMVl}x1?IzEtduNHqTRal3=h(J0O(Z3e-S_tx1pI4$nIw`&1!)Qhi9({)7<{v<=q7)ZFKdAL5U1mVh6K@RGy5)5wO&b) zw^kjud-?~Li0*8+&U1-}kFGYUi{?nn0$9SA;o2^1w-sje4^%q9`-i2f-+g(`Nwiii z_$?q;B$23D^JuR2JMEFasy^2kTlQFr<##&q`(m4f3ZLdLfbokiS4~I)XdJ+LK!DEz19|9x>7c;r8(!3i=j%yjWE$dhE)S z8-yV3R@=q(L1XR*Ku+MNT9R-p8qzz!1Ijh*Q&|H&=E=`9uMpC~a(m zq<{e?GxZxft12Mn{i_GjLu3LEQ0*Zpv*mH?v#*+NN4k$+m-Ll$C> z4E9vv`ieFaqszC)YstUaMmo{78Lm`l%4yJe_jAEyTTT4F)oU|E0Yz!YA+eFpr;1TG z^+{4uR1F@ussj|}?9XG^HkHb!3+JXlJ@Uq~qkWP#n*hw?-Lpu+Af&ZjamefseMh+{ z`h>YAJ)v!m0tZ`FZSMXk>0gD!HLHYAs{r}TRphZ<{7v?)-o67eiNjP_w%dMgl@~0y z0b4RrNdB3~Ij+BaU7TxT9T4EEYzr#8VKr;VCz)VhFFE$ z??t%@ZQ`jFxdX&v74eb{|AiNi6 z8OLD;yRH`|M>cb>O(cg)PE1aWJOZboZx|-*F?m%15CSYzwr7CZZ0fNNAkzCWtxG~(6TfBq>D$MVZ1xJn8k`X z&JQUYnYXS+r>d?3yEXvq+gX11xZ+cg=fF^{kX zf=EXH%j8QZ(VX|WsTIUsmfuJ?#Clq4iOSw5^R}|)<3;ht%R;m*1%t@E?bNw%S zIkAi}_OmFC8*;6v&{5WjNUQj>2bo5@SBFbD)Yr!I+^%KCT-(vS0{;U!g6;R+EkN;= z3@WHbr+g1czv1sao>(VP^kMlAGFLH-!^x6oY=x@6mrTPj)MfH3QN2@{$$wSi{>^}A z598$sG)Rm`P;a5`v~--KDtTYGkS;Q_63z3*z^*8YAK z?BVM;gCnA?1<3C-2(6;HSP)r{KwjG1b3E%$jf0?=$fU&O3lWYtUtKljDZRLPTICq1 zg=urF&(#9SzprHJN&bT}OQrkD=!@w6YO_U3u34Ph$1bCldypw$dS)o~uu;8pT>cNV z<963APozJtW=(YQi)6jL^x81lOr2%-vU`Am4Kj1|+XMy3X*SiH*pAF0oPeRRxp0 zB3~V%Q8qhdDiJrW#XS^?JFGaBO1K+N=knSAjcc((YX7ps?nEKTtJ9x{XGnsDcg3xKZFEp=e}e$vTsB)ohf4Sm3|c^Ika7 z?ST6sfo~y?htKDvp7IAB^1UpIYM$jCI6~uZ@U;`J!)wP$oCP1(!x-!bNYELl=iv@WCfflvEOH8rOXz+l`AbUyJ{i z!MEMLphV^dPVhhCc{O!6^Yp@CRV@b3bp73dW)g=IZ5M4 z#V>{}sQu|A2-Onum(c0VJq3El2jSB0XZf#M)=*>x4lzuygG6Mqg2eF2+C#g5s4XL9 z`0)#c=^#Xj;L-ZAXTg1X-PUq7pxA?+r|!!bq0L?I zIp}y{l74g>r@?Ay@W#f5;dI4EO4d9X34v5v!%>f%Yv3tAi#)T>{mn>f zT<%}Kf9#&?W@N^7O-@3GI+Vf`XKxiJy($>&;xfuq;w`M?4hahK#WpT5Nj3Bk^<45) zy6@&F->I5B5z@M68Wj2&KUf0s!d?95MT!G(doN@)QR|J=mw3~BubUMN^9B2r*G}Oe z7tjBbF;u)qTa_XAfLj5^4KCsDNDsfSk%!X0Cr}}|n{LjXKBT_Hgua;Ec=7!9ltF%4 zc7;0%5hXL?M;>ixh;}$+e?KNq-v#T06jYiv1wVdR`YftN*()dT6#2Xu)uMf^7X74* z#}+CQf;;6iFkw@2+Wuo-M^Jd*P0cXEr2|id2#vC zwLZzpX3*Q*d(_}7-bd|m&Z~9_w^HB_r(vo&VL1Nssw7kKQ`smWPZo6fj1^on%RCKSRMg!wQrSTOyMjoRQl%0E0iwsmYBb0>H{?(F;8=H zNAwr8kio@}BBaLKK$9E(_Xf~e)x*5|Pg8b{nUE-qGuc5Cz8sg~3EFx)NuF-8T6&l+ z{R!)kWbCl@(jVL;#?h>>N6QfM;l(~f=+g&69PbK^QfYs|gjY_DCz&2fp;**(|A90{ zQ*d-kDQ$HNDrm0`-8RF&fbrEqkdlwWl(fsmnNI4m$nvU*oG0Q%ZZ%m~5Ch2+m6fzK>#^5`N1xTtDdi{kiE9l_zMAcbNvSj?-`T@`zhp_EJ~P=@?#aDTT@o8Beyd zQ?oN=4C`DxSU0~WbaBBw0nQneOQqu9p;Q!&rM&0qi1d_clnnri37nTQ@rIMTnVq;{ zi6|}=!U8GxXLC`=s0N$GZ}nDVFL-_>TwX2z1a4&q1I(Xg#EJTl?%d}7 zN;5!2c;pbrb8$ublg~<%%QL>-HVf=feomebRjQswp0n%QN@s?gjr95GuSchQqwkaY zMCF@Q*I-@cC4r{BOP7%ZZdmEE!3C8 z{z5C91~I((TPYoco{O`Ei}FjXb6)5TG)LlD`~429J@ngNWN)5zq)^IIrtf@@VA1FU zmqN9BJ7Ue7P7vMPI8=Kk07C<)0K!kz{Qqz5iP!tl1>dn9Q2xoeLC6`C%1_ zh0>8ix2XvFVSC}H6;lm43}k)V8|Ci8SDZT!(k8h=Io1O{Tr_|v33`T1AOTQ;j zMcfEJbpT-aW>4`s)Tx)_yI>l9+~l{!_YXpy+o*)|nW)>?hdp#9WD{kbcIcl)ZO(k- z*(a=hcX{rFq`3*V9rD8vfA8;?ZDOF+a8k|E$nM60T=?SgM}>2OL+lUK5C4~#Ay zsXMt=B%KoFGl#_L_bjP&-L8NfO1!TQyo||5Pf=pZde=5-$KCV({sSc$gJ8s#FE}yEpuL z;!##emT@4P2GsS@l@e%-_U)Vxjv{E-0q`v-EKmv$eZ#Z%NQ@Y+Kb!{6@@uZOFyYM; zD1+7lt8U&(k<_%ZruK(86O*MZq6qi?U6T7_Fzvi&i%MuP@rH3Kr_Q{zgke#2&#qI; z^y<;YP2f=OrBR@{`=ZieAk{HVyF+xIxicAZMl+Fg5+tqZD`2^{(RHUY6d;b4$2az%d5E+`M*&Tu!-veL_>B&;N3)(OgHrMB-v zI!X?wx5@hvp6+Fq%Xz#IA}{po@liBjux^q_TKZjd& z(n}ccCFC}dtTTMJbGIKwecN|&9-v8>T%_-fSCQvf1H7%;M?)SvUCOAZ+2Wgw8=CIh zO%^s$Am{+>jSfRe_5mSLn{VLX0?{?t9&3#D`cAZktjN2I+^raL*^`F#M}tJ*zxUii~l zHR?z3?W2XBe;`!Jm%NR`of~f@o&Ua0o>~YHLV@%4Fy;298U0$J>gSIFA)U1L(LGMw zXPNpo!3$mIj^0je+%s)qbi-_4|M<-Z!>?bs8N#={?2bbX=R8WLrf?fS*XN2*ZNWy- zt1`LidCQ--muUBae>?26y*do9UR1{JhE&;$4Xa4W!};@j?%>SA4ghb^Kfx)*vB%EiqmaLFa$CSp*QsI*XOgg1E1tH>$h&6R655SlkF$F-azA%8d1><2Z^U~~pygcR z{a9n*4NZ@1*RJF|Jsn^Emg;_oTb4s)xQn%nZN?pBMBv}Bb{tl3JEpc}CpX1GcI(Lp z+`Q!<`L}yl^Nv|uR!A-hw}le_h{>O%ieHKQm>amSQt@%Sqx-4#*Y{uY7U^!~cbsvI z;9dk~eQeRG2KxzL9g?tqHTfnl|0+M)AkE!$(o=O)ym=ZuTN;fOiX@!ubNmJbwT1Z( zek-j^kuxs+l=S!0{=D819m09Ok!spo)&@U_=YD1OZT~=geS2Z{RgVgDA2oTga0#*~ zo`#CoKh2dRHidu9IWNfnepY(m!iAtPDsoaHE2z8c;$ped^?1|iDYd%Y>8842g^nvV zW#f9f8l6H4S(@}aX%+mN@kLb_>%4fevDs^dvFDQ|^TN#BY zJ!@GkP(o9!w-OT@Y(h2+@2#w#;~@v*zmyQ`(!~ujsc(!hn)-^P$^sH zC+N1>rB&wOLBP3-0fY+5O@we4%f3pC0-c5{<{>!OiKyUUBBksFx5Xjl639f{tcKjN zUtEJXiX?5{^_-sBE`K+S*wB&phb^+Y3Zzlx!rc{*)_QK!@d+S_C_bcFQugMgL_`p) z4&W`;%#)Md_RbBsY5=g^GB^cPTVM8NZt*pVMz-ciha+bj<OLCPuft;!o?F53HRmv@LreiAX!az{h_+F_IakQ!OwxrMK=WYW{$%UH= zMJ7sx%yTV*{^Upt-wJP67xt7rwGE~Zg1b37Vb2LXpruIEKafQj$Bxfrs>WrMG+s3< zT7fW&ZB}zEv%$r9=(*iQj9 zjwkHeT)i<|Dv@{@f=5x{{*hPq3^e^kQeoM~M9ul7P*nj+{B}i`m}BUAor2flP@MqF zm_n!P9)aJfBAVrxI zD_h52IUM^q-{1T97dQ`x*L~mD>$;wo=gF`5>lTo2{~Cald8;^4&6E_zjsartS32z< zLmuUHOyZ_cN8t)5KBgO|*X z%dozf9(PEl3ehjra*3p7KX}}3>}_U|_i9V6pL%Qk`Y&WF&_&3Hfzlq5tk5#}+(`pA z9WGxerJMRiK^Y;+-o&eMwf&9rCjM@VEZ?(KxT_Zeg7%ItTg=M))OOW}mMQO=#rCEg zQ2iTl9zy#|``^g#C+@YnlLjZzJ>|O3*e8BbDFkDkMm~{1ge6Rq?k-{rR6Vqo6w^7E z{s&5!{Y5;H0qZ01r7&D;f9Stt4LT;37uXZYaJ`2nZM68SD!&{YR5>7#ClSir2`zu0 zCFC`1%L)i8l!D&J{J|0X()x$*oQLB8alTMoBX8(R5zRoHb6)WQPT&1<>G8)=ndJmS zP5bzz_4rVsUs(K$ZDHZfxR&-rcJnplJV6`7l=0Gfb=*8i98+LZkthCwY|)63I0p<| zz^-&6=Z>Djg}LK^N4@?{(8uiultY2hRqJhr3Cev%u41ff=7;CIx^z9~jkmZL_b`AX zX13fY$VWBJ(B=zuX_oTGvby7rs^evxO)FSq6x}k9((X+_%pu66O+4tsKaDBL#sn`fRyUKr+pj} zKQ`O6ti+}-^PRaKDU3OZJF&q5vIi<&6Yx0e|fD5^`C%O%u zX^QGewt@ROku`Q=K%qg^W9x=o3&b(}xHuu*InJBspI>o2%$)DaAqI9dF=rtZizdFh z_YZOV12dI>?hX|Vnhlb?7}Frdm`1F%l3tsTsmk6(JU>CuAf8d)8)LaT;3n2kaiCCs z3Mun(cn}qjPP#^%SBTF?*Ss!JeTYl9dfx9&`N+~J3%z=!m-|JoeDoe@`yZy*V)c06 z_*G%9eHQCCmA3@Mr9KA7_&<%snGFuKu_i2diIM#e z^n!cZN($C=r==T6snpSDZQT3sy~j&3@N@>z4;&QXkvzxAw1bQGY6FYs>8$!CGFs15MXfjm4s8N;H6-k4Zbbs?cXk3k}>(BBxpS=FE zISBShVs2aYDElrV&sHR!T~?6T4$1HDiRW4ZjQ?MFFw~2Cdhx6`rHNG0IU@ZFv0{L7?I(7p@aqaCAk`;}q;BfofHBS8n7fPE9YSkdmU&=QTe=etx4 zw7?tA?6OQIjNP88f2aD@zRtALB8~U|e?dYgyL$xHDu#QIC2+0RujxC~7t;~vd@-M9 z)PT{O>&p@xeQexp<|WnE`f-zZFZ+O_k7k?UOt&z^(v(GGD2&ia+GgTHf4NLJY7Lgc zFU3T*sAFK?9OjV0Mb}Tnq^}cjt#ZnJR3qV?%30#XgaB=*`RqiPZ$bn)WP@%OT@X0u zg5i7A;kr=Jy$1MMsnjHXOqzXRdHJ&XpZ*4Mcx=QJz{uJl-f{V5kNqZD%lw7-<2l-1 z*U8`^X{adk*DgYaUIZUf68IgT5MXB4wi&@m7LrbwxF%J(C`x`S6m&46 zY7>8m&gn0DHTqvo;A{Av^(xcuH~O^4JT8Cj#qfBK(fki9KY>b#MR`7`PYR!iE9K*I#34YCCO)hR%gv-qG6 zYXofGVP^4vNfBDWx~{H59wyJ0(BFx_{=jT#(P`arsX&mF@pE-@eOKBNf-`D}j0cbgy7&XSr?V{ti6l%JkTtTe*$h z)pMEF{`&W3E2y0MKuyOLmidCpcJ%Y=O8uFBzAe|C3?kI&LiVKyct6EHs?{LJNZtv_VSWkK z$W#~xLwUzx*s(!47rcQjE@tW7V94)#qQorUJz|qk$T96Dz$FTs2S;4a%+$jS=msYa zEf69=zqLigLK#OxVHLscWLW46m-$#c*+aVHpb%CK@ zFZ&D{F-03(@n2a^?t%CjZQs!nhv!sXHKNt(#>-pNon>C048Xg`S=y7lf}sB@58M1S8Y=J=oK^WJc`xpu)S}J=f2WCP5h}+L{jecbLEOf5eWe^SeY4jBQ4U;>FBC3CJ32a{!*0Eb)=t?z zn-&0#s%s9j+0r4rK%VdIQd_h`Vp;d>a&;ZdR8hMu%eK?Z7($gA!gYN)nRZI4D`gcx z%GJ*M&_5*MQp5Ub%sK4Ot(&RC<31Fq|G^MF&Kh;KouT_ZguabgS!eQmQxqD!d8JSB?ncZ$y4=m`uU%+2?Q7V5APPhaEXjr6^imO_u0p&I6X>jv z>Aoa1TILeZHrl%D(m}ZXi}Rx7QIVh}Ph15Z;gL`1iN49OdM!^#fmAU2CG*u|B+&8n zt-Gi}Sf6q{c^mns0|Tq=FmS!6nJ|G?e^0jAzHaWz9A?(guucbUR)tds(oCB*NQPTl z#YnA*&!oiV5Jz6Qi!!WjrL`vcaGih-!xoGFKfk7p{TB|g@p{kSvBiPjfoE|k;%(M; zDQ9M^93dt5ddPS>c6@4ZYL6FEm_jzQZ%-t2`LWQ*&bzNaw$odnH$MRKqRhG@$cx*f z;bt-V3hIFMAyAFPsJHJiQep!tx4gaUa$U#`5!!ymHx_+emuvo0wBM)i6 z06GSF5(UJp8X;aRSzUQoiQqwF5!ar{uZ~L=y#KMEbsqy$>D%Al@NDtt9S6%oXtkAT z#)Kn@wqvwY;|{zlk&~&aRrIMG(cv`t&=YLO5}b=9z?ZV9eKwT!IpI3{yE#iVE^o^c zb|is=JV~)CVSK6}NfTrH*k?{k9D8U;ME!B@QrnBf=@3_Ftf>0CkD8Z?3s?b3acMCf z!IKqoOKW~2KmXU{=!R?=7e_Reta7 z{5^^;ku^O;+(eN7{4!DIJO)d`WC=xy;)Y`9@4UV7M_af%N;@AWxX?plDN@eWBdXYjf`(%IKNuKiZBjXG!#zzH5t zAI9_#1RU%X_JK%rp0d5-L|6*>Nc?jDj)Y}p_p@V!yQ^5Qon!x>+x3%cB17t{PY?@N z26AY*`wyrTVcd1g=)S-y4==w2jhV1vjTObI%hgv{(is?Cuu2i}KahvN+bXNxh)&A!wfD(DdMI~D>)aq%Ft zUqB-zgVH(^IKtmK3nCfp#y?byzkNg!6o69iF3|a`5P6UQ6h3YO)9*}6`HuTUL{7~z#xxI5`>i=qKvYNU+43EKLkw2{*D#@qH0s||+FwVF2{WSlg6 zZ;)GNcN(KP)*B%ugIHW)>W24V+(uU36yQuYm=DjREqw?QsaIfbA1ipt+ilTD1&e@& zj!2lxk;IEF5*}`T$RDl@A z{hjYQc(IOu+u}Ror`7Xj?Ba3G-JwHc^WqLL%lA@itJ4#I??T6}NH!+^dzkjAy4Qjx zzXOZta~_G`&>zkRXlvxB81^MvBWWtUxJ5+|e_QV#@V~s%jUGF@`mI|O>15M{ZIApL z&s8#8{y>7d6z(g^IgTB%<94sk4=yp`|3Ge2zh)C8VDRSE$+z}^sn?Zkf0k^0oy}in zF`6jeQdqs8m97p*cNOTfhUoRG(Qd<{9&HNnGDHO}s>_P@!IihYtauCqW7JomzE(&# zfM$L6;PBBs_3ToE${SU#;%lwJ#pE~prx|ipfN;1xt{!I3nR-c_LvVim9u=4+w65OVktQ_lvmGH6@5n;v07au7ZOac}uW6=*XV~5(5B=NbJQ)Eg|0)c| znlv(WE`AV>xa33aL8o|Hjo#SvnB36u52F3YqRhniNhCL;(^De$JE zq4a%O??c9JIzn)g(T#$(g>wNzL_{*<|C29L4fV2v{G@^<2S>V7uY&icR@vh4)r(HT!U2N zsrm^*5Ld$@ZX9IPA0!seE-}LvnvG(~j^N-zn9 z#kk@3A$Wt!4@3|C#z~^&Y}s)1@@BEn2dQyc9JTm#pl;PhGsWu9R+#O+{L~QDa>Bt+ zhe+)6sKigsC#t_CDRP81T*X5rW}}+14jqQJY0uB13V+mMVA>+vDej_-Y++{Ndn;nu zMqW0-HtE0P)|ZU>>1b%oWf+aCrW4C=)f! z<5+HBH~NRz4netul+ayHBa)%GsUltS$S$gIfExY!T|bGKl$T90DXQj`@@3{$P>EM{ ztXSpe;`gWar%6DAQEJ=+y}g{dJL}66!K7F7)PF1$L2fbAVe%dB3R0u@dbPiLTW=(e zF}rfhF5e?kMp*{!$M49Omx`ziu9b!6gcwd~g)^0yu4I;pKhhy~7Q;+20GsED&%6)A z{Wkouos2*mV!l)FNaBJu9cv#3FqiHD36p1wjIuxIY*wPv{OEE0DA&%xJbo1FXUnDG(t)Yj-ZjcIs&bZG#eWXD z{ITKarTSQ5Vq~_2Sh2>KVfsHCG&2g2zqOq(l_XgdNsHMZ7O75qgZk)Ke!#S7uk3{y z#M=_9o@Q`J2qxUV+%5S8@Al0Uh-T-NBA5c{%*N-~qVUvH8~^BOmBlOV|ACH^F4=B= zB>(f)G7%BG8vRp=YY|Xs{4z#z4ecrjSbjrJ(W6fcibBJaTvh*8lCfAt;j`ui&TsAW zeDk_LV_kwSQ~w7l5)R)G*zTtgdi z#l)r+tdXH8#O33_>GO)*`AuCR+<8Gi%wr<5H(5FMOXFcPbTY%4r#)tq=z0!NPrI~= zKsx1oVP`P?lE*zi*i(le$0+2n3cG{FcKCd37`hY@R31NK54~^PBh_zO0Faa(l%+1W z>gttq!PvzX@Rg#sh`cy{FzKtPBp@ z!0lGN)5H-Z=XmbvpZHIuduiW>)Y1ouH(hD~PEr|H1$dnR6~>EQ&J^RNCX7^SCt2H1 zZJwKrp45lJj>gHZGs32JOwYzSB0C8W@Juodv_FIEYcSmV~QxIp8>mehv=3>^#`1lbJt-??Y~nT5rS zG>_zMhOh`P(LZy@x*qXCyO){UFw^M)9jRt-w3&T(``l}X&Bfw=1CPwoJYoa@{nxH- zt`#p&sy{=%v_nb?xzg8%3!t}6;=4p&DP9jIqcsaZJ}ImK1YRtEj7ZvcVrGvr=I$c1 zL0fy0W89Nfm3XJ78`*()qs%m|Q3VEAR;$16Sw(s7uHK}=PF?Dh6ZY-)-E+HqTv{+Jx!LJNRDns=84i@XvASWFk4q9sQ)%w8Xl9# z2rE2yRavvkE#|3vK>PfYU6ja&2wG7&-_W(V`E9W)?ylMS&~oyhr9lC~+A$|@GY^!Q zq;Zn78J{JxPF^!V7YzPG1g>Ceu>Z0z{@!oVGkSc(w#8J;$;>B{VW5u;Nnxbopt~-; z+zjlh3YN}lXKJUK2Q$?n=C}$qY_51py8TTat(CXiQ3%(T?m!AH5G3Gac$m=NFRLgh z=$6ol%lj^ddLL^v+4jMD!<#svPv}Sdelod7i(44l(YsO#`FBODI-U}=j~cASG}LF` z%G3YKu$w~OwH@d1>ej1v3~Pz!=a*7weJfJn^6aOyQY}@svmhIR$8NHzzP33!bM<8h z1cw0<%1d8dsljNt%>D<>vqy>8{Vs8v$nwwUPZEV`cmnd`yyHPoUV%A?9sPI%y7I0m ze@g$fb`FT@xx4@lXfwEiF_srDC}VDO!}RiMV&11)q0Ef+z8Z0MH<_Z#RG=Sdl%T5W z*z|69j!PcCjPs>ZZZelxk&IeHqq~R6WDXq(&aX0!wlEEvdU_f*SI_sPqz9>Kl8wjCYAPM&f$@;*Aad7Cx%NRLql)tJuMIstCeq2-9S!9Nashu zRp8A{31b?GBfCWdalKSK*TS)LQQpUe)LCb*VqAKG<~^N6D^c)2NH~LApUltvW+pig zVU+h}CPidX>?GvN>Ve9ZU9ROHVBt}r{8%;GXJ{(vdWL=WDK>qeM3p~n{Ih{j+yq^y zG+v#7p#xLy*iBK!oXUeiY;R)rLt2}RETy^3jdTk?qdA4pQS){*p{ z$7vS+#6N^<5RvRIdketF+XkL=X3ZeXI3cTnj3~LHkODZAe*o>7nnKPtU^M!yrz;B!z8kO>GyLUrVXMf z52f^X!KnTv#Ib3Q%vgES2*&5EV1)qFlZZi@|r4@FSZ}q_)f|#=w+W1 zoo(o~<84^X5Y8guFkfSu+rJUdT8zwmbw@?JK<~q%)IreJY~>sB7?m^@Uh7&rC{0+E zq3{QFBBLKuDk>bY?zd+ItQa9l->5KHhb2|3|KdNW=mXT?h1VV-;eaeWLJKmhXH?tdRSqaEGiZP39Hi&dBku9k83qsPwD&R{QF2Kr%V zTNB?{0~I$CSq5zcPbt}N|D^52GlpVe7i!=7ZcV~;_4GC^(PJHWTd&ed>XjI%+LV|LNd0V4-I8Nj3K#hGu^-6C=`>gUpykMP|Dw3$PcsG3 z|1AH!VQ1*)%V6oyON(*hW@hkrYn_-fJUaOyhaMSVTb(~IE0sM45Bl4!F4pOWI1?gAz~81VRc*xfu!|Ug$_hWWfvvzeFZ7ZbL9RrZZ)<$*y^! zK)vDLP!UT`a&@vi5R1d-%SxI=X``%Q?L{1vQ2NhOSDpXm{j9VNvcH5E#6S!_&m6R= z?94pk@|o~5&IuL2qPR)Rp88=za9xyP6l{8i&V2S)M2PQI*i=?)2t?1wjzNIBg`a^H zDUd<%n$iChY;`vfg7ks#?VIJ;nB70|i|+9|EcjWi9NW0&fqp-y7^v0T0 zo}0!o$~U&xghE{HWIFx_3ezt6w7&0ZOIVy7M0hp7?LS1!)me>*xg0P;?fc{zpx-Ig zfedvn3-tGu!TkrLYWxb$+3SYCFM7m}XEH0th+m9Kh6HP<-4nuBU z8_=C+)2K?Ev8et;wC51C^ORkz^(6JQ#>)>1HE7o!K`7SU#+m@W;LgDTtqoYr(j%*p ztqOffh6Uf&z-`9wiJu*LWV}KYLEpcCCOe31pReAgJ89g011M*$-`x{>i+)F(y^1l@ zDZ}UA==;FFrgXQ&mHJQ(Z{@0z`DWi5@y)hrPldRQk?yfPox(Z5$@kGLyCRJ3*jA8il6^mPtQZ(mcHuBZ1I>@uElvMx%vA17^LEqGe zI@iw1ZKqx6?z#)~DUx9773k^q-VEPg5oHu*Rw%yKdoWy*`GEM@NNY=#!lrqosTeSm zXAIB(+Y!)7RY1Hz6SWsQL}%??o~4DMK@j2}gK0-qMI)|@ZKmp)hX#^PB92ubq@1}a zYiLaZJjFwT@;mP9vl!YFZ#Wlg1G(I6oxX`hi^S#8hD>P zcTo!|8eih)zWPQIStOOhyzh79?3qZ>wW7|(&7lH0ZdEju0*$o>u4DDk3vn5Amu1Q) zwn1G|-*V?e&p>v&a}hsUf1U$C%_*B)AW>5pu%xTH{b*fyMV8wWZWVpv)wf5l-@c6<=JkJ z1_&PDRea32yk^uWJrQ_u4p&Oeim(XlXSZ7@Tw+2}nE*?gs+|Pde%|!p+$Auu}&v6W!>=nXXG^k{IUVM{VY_ZynneiG#^0~;!^ObYwLZa zW(G(d*c;CMES7#7mId26;MTd1ie!(786L(EINw6?&wzB%J(Ya-J_hdxaqYtdofBKc z0BK#(*Qx{;?N@Af&C+wP8X30QeqNTi(skDG3IY^QxUA5%-r#j`#_#09-2uwkcr|0yQbsa2XyyC!#hvj93rLGObP{g#qZR6#c!~@@D z*qk$^yL2MLuHbDx{`GjBXx7p7mY0o&Vw^vAOe*wRm!0Lo@zF?)@KOJE?v-)`da@$> zrH9o18Xp4xG&fL9Rb6-H(CL}T*aP9oNS%JsAqW@ZX7t*q*&R)-Ye!@ zy&DM^nTzayRNwJ=)vzS9wUBO?JD1UaosbEYyH*+v4t@m>*aFj})yOUw^3LZj1J*)7 zMxQRSC??h>x3caaolZ(AUCSGCB@{wrjAWMv`xJmd2}BX<0-;!k?u9(|SQkI{S&!d# zP`eCjk8!)Bi~u*Y!t02|qh#~^J{j;w$fn03ZcPs(8O)ERFIW&6Y7fwW^VBYNFTs%Ls3!+vP|yvBZ@h{SJl zx&15tmB*{^e2{EGuI$vqK7qxEsr_C*a2FrgH(DAC%PZZRrE+jO7rCR$%7cWm63qb* zx5tuhKciGEt(GvGYBHSHH#+xYzVQ#Mn^mqKnh7wzeoQ}oeV6T-MlKOr0<4B7n%dPo z1SdV?cLg){A7)*a-+#u_ll9s4&JEy@$*+DCi~4TGIfi{ zZGQnq*oBL3FOKVm#ZmtK9IkFPZ3RKj7t1w1g(d>wxm(lkCPbRbWi}yW?dy8A^94eE zj;U#Mf_6E>cJ9~%U(CFgA+#0A-@=j!FL3yD`qP*_K&DR-J=of@+pBGz*qBv{&UG;5 z2{IL(bn1F7DEb!pHeLE4@gbtH6vOG`q-Aw-ISaX;+>3qWI>ke(wP9aFg)`bEF|6S&eF$ zQ39UKMGpq8@hXrUgPEoFa4&fhDwCUxfxJ3cO|(*s`RPN)k!FfoO3*fdD^*_L7ZJ+- zd*!ycf2j##)I$+@BQrb?V`{c3U7NU<+^%A(c#qiWb~~Bj{Uw6>uJQs&2c%N1pUT=d z7}#k-1(0r9`MmDx6bOHF4U%}SpNct@`BWhVj-U3Mk`)Qw;G?kY;n_e<=37w>AdO?1 zROY~dav(nx+wEXD|7lH%XNyZCey)!ScIYJtt;oZM3d@ock_sJf#|;#Qu42v`|1N1* zTl21g-)4sZULLHP0bgB0*yqm_X}j$=b>-AB_S^r?NTc74<0f+#{;qGhWstMV?1Z#| z|2k~JU$LibZO(0CV_)krs39SI zUGmMZA@iGTBv#5s(xE{%Ks0#D;;9WMghN3yOWa?Vr@A&hQ|t0KO9s~DZcWl#&|n$w z>URuD$WvpWVXJg7t`q!`xxK3`;P&iG(68gfl^s5SI#^k1`kGAxhff1o5g z1EX|bCA;M;H{8Eolek%0kc67LjfG2e!-XYCjPyN55b5UeoOz4mOSw=@-Z#zrNmHDOOBNq(Ky$<`w#% z?wX;X`SSx__j)jFpAIviz#WHPU!HVM?!h9;c{Rzt*3V>#Rw3m0+D&JM_}e_A81W)9 zyWkVC;ODB-9iKZP{kxiXowiHO&#r@$inS~=tk(iU#4D@aPVj3PcY&p?Kh;oy9zXSe z#U##}qoSe`s1wrK@Sd`?r*>8|4dh3CZ>ZcBSJIy}M*#jyHsZ@@IBK@s&w;Tk0`R|c zu9j=)o7d@)YvRW)!Z&V%6wgZk1B3j+q(8_LWSIQjrn2To>?x{b(7f|c_1yrCSVslY z8TE%=`p6A=d%Jh1&(XDn;v{K_ziAstZ~(sf_|LIqc{?GE@FYY2-eewWHaIs`BD+-s zEIWy=yhm2_k6@btMcBzUGJ5yY`xr+IKKZANC zGeVTuWhyK0qumqf>>KIbHB(1n30w<&$D}C3)rp_{Kz^eBiIuXreg5e%k8p-eU|4n zQy(7fiAq5|w@1lX`!)jL!l*c{eT3(HcjU}Nyx9MA{cCy(? z&*pO5i-DTDZ^p$i%PO62A4lL!IP0kBRyY>c6a77>f_{A56YT(#@*UG$jhUL3G_%O< zywjJ)qiL900D3&8iJr_!I}S`dB?S?Pi#83g1J%$h9gi_) z`>wao@}1`wj_wb6RR5;x*SKS5s2pi3H*b8XBjtOJE8Zv}j5uA3AKXLLe_sIyySo!bOfn@h|RB zI4&}EtW^RF7$JHdf$X;zzPNpZ?DjO^M`}icODqUMpCUZJ3>t*J+Oi@hF1o@14$Ajk zsjTksSTU9*?;PTTBTd;1hGQaTD$`or2I7M7Z&~U(7&m*;wOv?GOfd~(>ruVL0L2q7F-s9z`)Ir{4{lg?Xr zE^ah%Mh(4W2ERvj{Wc@}DX{uTVW||Kcye(-N$Llb$<>NemA^W#PhzmD4K@ZOI}ydX zF&nqOqqO}-EIz;O_Xobob}H9Pvm(sBCCO1mEVtYVNAKjgquC^_ zT*1j>)qNhl($_JCN6EYXfx25W7$JHly@UeKQW|T5gj`KczU=;zH-#_C>XcEsO zu{P%~BDwK8L{LTpVw!52_qqlVGC${1{J4yS44(gh8NuM#3+e>DKT>%!E0@jlXY3CKP!8vxM9+n z$2$~PDotR47x-DXvl6)yhwDh+uc)x|oq52EK?=>SG_aa~V-GbCC%r#_sTU{P-LduF zw(t1znR!^2e8WNl<+5oi1X#9X6>2kTl31-iNdnXD56KrrR1(=kkXwdT5@xE^4;=SR zfMdC0-t!-zkAea9r8f`=#gDP`Jt3-f6~z#r5Oi8?bIlb@5i;9Z0c&L2&lNrDhVJ-w zySpKUfcIiqym3umxSB|43%M&SscFzt;7YNZGin35X#Xj&Au@?naM^AC$u`MwhLDg| zB!n((6(G4AY9Iifx?I0tn)!?ZWr%WH*_Xk!_D^c}#6pd2?YsO3Rf;UTil(Yd36V z^VJkXypzlJLS?)daD@^=z-`zRyuV~8g$D0W|o*Tq`JAoxt7^w^l_g`31@Wg0^7T8*Oz_|OFee1*nv*o z&Ziz?qP7@@?Qh_^57BB<_%7WC)|`a2P`~StEQgpj(^8401^O$UpTV0ec-2d%BK#cT zMHPyr@#jmJB%UmKGrP~<5^5TfQ`wtPw9t+IUX)ejhObe_mC$x7EJ@NW#thgvG=&(P zz-_4x!N&~Dd3}$*L8X!Hc_90i>{_#qV)&LrgXs1>pewe6qa6}F@G#_LKoK|QV$QX2 zub(W>oH=agCBX202m8g_e{0=zTSBtH9^XQ96Jq+OIS5INMeLwSei==wG#&u={On@g)g3P+>FaoQHAiRrypD5~LXWk%)*hP1I-`IJCF* zy_}vizaJ-Cy*PBVmcC`2UjLnUcxii2_rA*B_*dofv59O7!ZHiXuPKhY_T%XxNsAu~ z+yMpV?t&zf^!M6D-1S5mn3NzVd^hHXV?n$H|9{b%9ES99Zr%hUVWvS8fzQr&dpaTr z>xXCg0#|ZR;K_=k+Nk|~oqGl2W2raT5GQhk!rJ%-CM=MSag7S-h{+%ecUhD$UV!zk z>3=!gS~&t%y>|n-QhaFoK+cc1#Kbl{(S=+#?cZMCc}6Nhlhxw3I~nyAHet5-2F>`2 zDqOg>vy=M;uR&Gg0gR5m^?X$k+}pdGHEl5;?ssBJ*m zM&=@il!1uigPswzOLGz@>a8&<8YX^u)2;WoLHym553n4~t=0Sb9Uta9oNY-GyjoSSX+tft#MH8*Q3Czx)9oL=kPe8IpfqQHB zBPsuTo;TZ#Ozqvf#?Tl^hc`V;m;dl@*=ZFMlKux$Kv@#~OE?1fIbFeX&+s=xZ`y^= zTCU8X0icM?7M6LIq{J`GD+#%u3{|Ha&NZL6oXA>$nn}p!M-|uH4j1cST_cXXa)*e* z6>rb);^YuyG;=d8h3kV5S0b2sht$0tDs|=ghS~qLi4sXXF50X*c6Z-TygOgVdi=dp z4J1V3-whDG7l07$=zG#T!32EglPG)(t{QL5Y5FLCr|6zXyj+-GK^V7Olx(f z$$lGlZR+1e;|_amj*N5-6^;X`9*k+v$p`WQ z`z8|aQW&HfSZ>?Nj;-h3MQ=7#vn$(>i2B0|AphbC%qB~1Gv9Aber_hF5AZpQBK#qpQt z>Owu&5l5Yik0{~4WA33Vp{W&IV-$YW8@$Ku`~+&MBIsa!UAyS7y5m!*`&we$vfDrX z3I3hDdN^^f-;`liD`UXdN3Syt4j~KltPhD4N0;;Fb{xL8Hh<#|s)`%yTl4qmfZWWP zRje$?v&FDJQH-$AlcIub-_-Tm^XE1!^rUue=251`uQE`wF$ zR#7AB1*lJ_Mqt{fzrsu=ePGIrOYwAwmr8Z{cHe~e{$0|C5*F!_#Q@@_ACmWvgeh@2 z=qQw~aXn>qb4`!V&&?_`K68_);!W|{8V(JaQwrwz)gbtY*l)SHmE*iz*$g>fSKv4YQ1rn*i2%)9>}-H0b2XdI#IoW`Bh;Q+Tj#pDWQ}$G=ORx+X*kC*uI? zT_!iVcxHWUWvr!-*Oq!VmGc$~_14<7Ud-C!)mPi5bkrpxXrszoh+TeW!ZK4Aja6c=+$LTNSZE zywPmex(HKAEF^?y;d30$(XvsL@0D$=2lXIAX+b0rZ4B{})Sj={7UE~FqQdPOoa8j^?PDZr zQ#%el1(|(kJogBKd6IVFQv0$LvL6ZWOOq^4L++2MmvcX1>GHZTE=jC}WWm}e6A847 z-_4fWWu_oN*T%@xHcDtP+^1tqj+nXKaPskSl`Z6);Q*}K_B|A5jh)`7p$Mf12F$P@ zzCD@i5}WZp*je0_G9U zk!b)%k#b)~bWTyMEPS~2x3yb@-qX3BOPZs@adJ%irl~5|at~s*+nZDo!@#nVL@u7R zB>l}>(!$l>3XA)jQb+lAUhUUY6SS*_62ujBcCE26G8j(#-tHLJ$33E_&r_XZef2QB zsqY|R#FN^7TTqr(6&U_Mvfc( zPyNEp;=$K#tBE$}Y?%=+!#7{Nm_KZKK5YJ2?t)zW{@%T8jAYvdFsNKs9L;qE6Y+mt zncR4JVC&vW3Gd&1-*~(liThI2I`K4_yZS*+vK|kOzDF&KPzN)&cm(oXvK>Yb6)k>H(l{J`W1+HiVsNq0&&+Zghwba5U{g-zps$kJh*-HlSd9_H*M-Y&zx z-;mt@tiH^Zxea#RqhdHODwrNjXLwSQnmT@M`D~Z)YrjEM5}=nD5*y@kbp$q=cJC@T z5pM>sa!C0Sbad~#3vf!F!IGS;$YPNa6%x}wC~venN||Feyy9$aI|xG3$L zxW7cIj`hd}@Mk=Qu?`@mepaFm793-`BI{r>1FO4uSXNX%{~a|-ajTUY4OKe3t^OU4 zTPbek`-?*oSKCF>0@73>&H5k(_zJzH$b7o5DB+*|uZJw|NxFUh{#42#^Qj2B#y3T3 zuLsR8zT^#I*-I|l7w;BIsjac!A-KND!+BwsW4FbHefEMo;Y40gN7H$5t*1gc}P$VH%i$p zSQVz(l{v3J7vLfvO;tB3K;kriU9(~hS#6BDN%n@408kN?)D>M{IFX~yIBhq#jZ<0o zmgY3GBc}Z>{xhIbaskC5n!_^Z5l1qHGD*pd7`nKy36IVrykT~{%Sz>tFw;2RIN8RT zo5K3;rl4nL?ml#69NrdB>b1rXmtbaLcSDcW68!6DMg*1o02k%lL632Qit)8RmC4Kf zk+;yPJqGHc_oX=WV^c7Ao>s@y^K@^a3q!jUlMS!0uU|Lj={me8P3OWCGC?nONlgOG zvW3rem5|6s9mh~jK5nog-uZyA>@uHFzjec)VXoSj&|kNMm_zqxIddwT#d>$JtAMjh zKW0Y;ex3-xO}x$K_#Kxss8nojvP;fD^OXhPK`?)nS5m21*yZMbc03}7V6S6cu zc)Ia(+j+x;Ad`40YPUIMfgdEE(%Pt?|K|37P{}2od2P=7OI3_>#U*Br^!D7u@`Rb) zSWHBGLsy$|t*f7-d7O3hhyu_4fxrXM6K!#^#zpvC6M5F|X2>*d+ak`ZeBL{P>oPF0 z_9IIi_nIH1mllVTG87p7E-r&noe}zYPZ`Ruks;f0zXi3Y?vOX&#z-EWBk!at0BF;c z1$Zxm#rvk=;oa4Jp-5F~l3xCi+LC}e@jGvC^dd69_PAE(Kr<~F%*-4T9ETne6cnr-@V&UI%UE!{TE&bQI{U6i*OnY^gE zm=um8$;@M-Ps%NaEqG!Hw#I7Y9ge~Q|@#9xE zCks>vr}tni=S^psXI2_C{}CzC#_n7NBJ*u`zThTI@2>HFdtsu`&2p?Ii#Yt1@zpT z+!F1sh^1*a22LQ&7mYTY%Z^Y%T6XYJskFLdek>RsOES9v!+O{B zysnd1Z0wIf)JVi!i^`9>{?g_r-h!Ze>;Nirkhx_h9ZM+Ze6uT2Bkc-!@Hq zJ50%zp6_zw{*x)RP7k!~Z|+)UjP+=F_-6>y|KCfcZqwZ)rFLm$mmvdHNA5b?R+jzR zw$C-&j%v4Jf~(jHL@I2kF7{Efl@?Kuc~L9QzCUCh|My4@{R06R>gK)4+yciru@qm& z`Jz8=@d0h!hE4DHnALb#zbs!l3@1$N*pH5!JKz$Uw#TG`==8u>fD5S^;j!+m;`;rL zgBQb>W9gkGZNlzotXdo_u+GT%LB^Re;GG7AtWQWbwUQp>R4>OxPMCD*k%cuT*M{aOsr#R43a&voXO9HQd zyF|6W(Grj;q%Lze=tg~5D||K=v(}~D0PsPn+uneH@%i)#q?&x1v(2*bT93LhMb95Y z?s7vTCZT_ihLY`dMTDlWd*4RMQ+f|FCkdX(>WaITwx1@1XF@P}&mGr4Qp}1V17Jh^ z5;E9JuRHQAM}ual<*ON*ccf!1hUCl9Nis0(S?7K|JANeuN>bH=4+HMtx%D5bPW1@PF zwLZf|S5*R zwnf!zX^cnjPYC+R&{`iszA_oC4?^QX!GVZ%I#lF4*l1^-VHEwXGTG^X9(?_q*Giy<+yEBrBJ>Hs2m`m;EsN&Q;#n zf4JrbwcH-sSqowDo-v{1@ek+xZwpQqxhyK3>uSSrEMcvxGSAx0HvkuP< zGMZa$qYFWl+jxEC2h&qHORpM$Wg-v;)bA-$^bE@$&NiUJIs>I*>*~Dw1W{7%c0e}F zztN@mNds(^63?7>D)(+;IkKl@$z6MMt!5Fu(y6172On+^$qyqITk%|L zEX8FuE8Kj5DQM+r`EE@DS8U$bj27m4OU+u+{@q+pSy9;=GF^#+DOh0sp1!5dUcG;{ zJL9}x^eVMiT#!cE?fTglYHY`7B}xThXw{lU#f(;TA^EX$`}oOkx7&gjR2TCHNV+_*IH=Z39V>wciHVqt0=c8(u%A6Dd{Dh6TE1|lA_0rqR_`uM{#GAqzWDr?Fd`Pi14G+ao*1uQtqJZT zdW}%v0@)IXf!fD6=kmLYnE)5$Zg^h=A8VGT>R8qKqo4H&-CY}Aven~XRts({oF!0%LTSggpBQ}E7Fq*$pa_VVvUE8=~8@S4$YgBC%xojzs7Bo9+E)A!} zaRWD2M--;^W~TtL5K94gOD z?~{7y>D1ZloQ4;Pvo~#WcQYwq$!mP9pCv`p)XqPG%C$PHw4VtvbGoqHyoH1ekTiH; z1_wPXC`TfOs&7xE`4^f#lHA-|K)z}I<17l{#m+Z&uyg=F(Fu&?4<#%ry?ABS?Jn-J zWP}85()lLVQ1NB8toPEW-2hMYg4&}N`>|8;O z2&>QpCHfc*qt|?yog>$ZQXa-H-0ZR?!J~dxlEW!cDeNi|q*aesgw0XZ#zuS{tTwvq^r^I@@0mW8RIf zyjh~>W=z7c8Y47k53W?iyS&OW!+!_$TZzBOIcP{KaXI^i+d)lbQnaC52ROe8& z2sm$W zM!Mj~2ZVO;Sk3)RrW@)fxv{r|=S{_)j|$1s@L{8S&Z&w6v|wxcD)lH$`1Yw*HgIv! zdq{bYKdv6ktSk8}>(SkBzqN#`Hm~Bw@fu}t%-1OP>b})NWe=CHhHeqdG@ngIWthnN z+jS+u`GKL|M>6@-$P$GQ|AGADqFdvPu_gEEb7ib1-QMp`AM{G%II=ct4el(M#P-Eg zs369l{-9V<|8`l5?FID>OHzC>XGXCOq6?W_JgQOT!V6Ocw=%OV%|xzQW5;PF)T4~}KQR!yScIUbQUo%!L+ zq1W<(oQaCk_0#Kd{mchotfmVPC*5dSz2!`4@^etI)UN(A-%kG`VQIfSx~wKX=}&3Y z?FkyzISAk|zZuA~B`0<_>f|eso$LQ0hI!-(#bG%)RDk5=UfKID^V_ebwV2N8=DH1a zjJG~-;-#K%jlE3&o*+b()3%wKFFe1NWvz>^=8jA8d}^IhN7G?CVps?zHQxGZ-kbc^ zfz4h#>yi7S-UZvStZaoW|F5HMgBY$#fx%d^YG1UL=GPt{W~^&wCaa!9OmpGiAyw#R zbiH%SU6}ln_8q@KeUKjW!FcS=HGtV@up%(p2)>G?0COa+XMCKk<33D>7eEUp%N1{$ z7sytkHHK;joNf=iMINozj07yIn<2KF#;Tt_eXQhz3aFdH07sVRKaiu!mG|q5I7>UD zF22S?hC*C9&XS2}?0G$-JrCt))g;0403TiJ+#=-gt^KFtnB1-pw7cC~-88`Nx<1$)cSAmHscV&bI4x4Ueeg*#73DmZ`mGg~88MM~Ad7Y%HYGJck9gS=N zzXt!u^|d_-&|SF!N3W#{W}WRbeRcPf@LdBE!~B54io1cvD__>$a(p?8Uloaf2TL3H zyY^9s$Azjat14Uv@V{ZnNq#3`o&MigHK~YqxQ#!c%sZF9Q+d3Jrdqp0=C|zkS~G)s zIZHUC9=3BWkI*w2&Bn!K`=uH@eM(MFYU4`FLWCtM3OYT;V8{4Sq5*A*uN=ks*y`DD zcA|UhvmJaom?_hJsjv7zgSC@!6m#M8PtK5&YaFlookJSAg0%|H@%rCKpEr1Gf}Nc; ziUq#cB)GU$z&#}{Cf`I3%r(EeIY7G`m$m*X^pAI-q7h^h2oJ%56TO77K8|-zT%R?t zO)I)=;dQ*vRzf`4f^N~P(e!PEYHUToJefE z*}-IJ7pciyqb@mPFTw}t7vHiVs$U}m@5j7T;=C0aF5u@UJL^sf)=q~% z1@hMAcfOZP@a&?dA%{2CGg_KoxlnRRW4V}dS-q_jXCCxg%Y%Zq8p-CB-jnOntR%{B zZX5MM{=)|HZMm7fqx*B$OdT@xHE@)^_-Z-*XCP-_uwhhBQH*ZCbo)&oxFqJDDKk3^ z=B#m9V7#}`LP#r{WCb^3k14wUE#P?I0dPxk%*zJpA~a&5 z`ad`0B8pgw?zo7I{D+d741Z4PLeh&!%}>Gl+sU)@{ekc|QH#Z$-~BbxzyJNFzmR)( zP|1x$WH2Jck}Cb#+IPWuwW_zUu5>G)iZIB#N`xoe9##`pLqm5)3xPG!^yZ7Yo6S5P}A5DX+w$hD8`y~B|!USWkqId zfryw^%Y~l-QOaZ}JE@mOvRC#GEB}}E)y7Qf=SFmmuKacel+~;N4_{;4nTB3NL?={i zfBtn)MZP?%3)e>9kX-HOSl2HP#_v2gfiQ1x!T5e85pMo6B9BYoPyItbYd0S+3R(6K z14GAt((cUpwA!(S0!#E~Y%BeUld=26GO)HGVi}G%Nvb<>E0k8D(BcGoL~PHT*V=nU zeef6)h1{=M55>r7z~#8H#6hHb%?5fS+|I27wxSs-jn(MYwyKlh$Qt^2Y3e>xJ5?ap zFbqWK>c5RYUSJwn*>6$!Yc~F-kL`=`P1k0tqU%KNpL%X=s+Uz1Mi-X|bKa2|somb? z04dK>eusA*mbD1vt{EI}*4rEf#1P*sbn!gUq}{vP4QMi`(bb~uZ@&Q*l3U;(Ss54D zZH$*~iCnVxZ)JA%+ABiI!UTWE8A$v-DA49+MZ@t&`KEYLdnU!nNz#R^w~J;dNfu1~ z*w4z9G|X(QYKv!9GUQJn-MgoylI{!Y^oxcG95%QOgDo#BUp?%1)GduO^LMsAyZCih zmG(_gTxLrK=@8Y@GS zr9oKRYt1x_UkL#4AIBw`8oFm18YbIV5O@E3-It4n_+wLHVF zX6cxme+6aX0IdHRO z9gSZLmn(pl^gP2Da@+r~WD*?5f!!hejKJ}iy^I3l)(R;HXiS=Ot{s~|4g8G&K$fa@-+H#zGd1LBbAFim!J256}cC?8vmJ+Z7>BnCsV19W@ zlsNE)SbibsN*lh0e?K2xj?0)iy5cXp?yKqRHI(R;WQfE6ZCY>tKQ3r$QX}WkKa%R~ zjRKnIR)x64pWE_3sgs6~Qq=AeYlaAlt!ovG+3~PO!^3Lt&U5P%q}yMk!&FzcmX^}y zcQ%NO#?DNDHuZ{ecFXCLVMyGt^B%-W{Z0iPVB~p;$SN;2IJ6L3fa>%z<;(KA#TaRw zseC7ou>2Cz38>R1{&)2z+X=VPyUXa#vaTP4cY})l6Tvs!D5(GVz@wuMXam49G=AOv z>|*+}wU4w!jLF%&^}H&;O|ZU{XGKuk0JGl+n4uZo5*L|QDfs2(3AUL@ zOaouMHP{n8o66zUKo(=37fLNQ20*oskl? zX)b0eY4!#0(rqiTm~7fKj;QGVs13VY@nrtpmy?8WvwP%_>pR{ZPf6ZO%s2Z19;6jB zt?qF&EiW!o8snIaFyB#cM0$f;7mqh#5If3mvULiFl{J^7Pp%>Pw*&Wj>o5bUMrwJD zadoY98BDG6+_Xb&tjFeVtBj3BgNPzahyT=^3J${!b+NZf5~uY|sfuEk%#{&xZBaawvtIc?$x$+NQOl)~M*Z-iqnj z{LLUx4v&fIx(mGaG8ch4GEr!eOijN#K|Y3BUFCFU)Lq}zX;x0(Ht-yhTo~#Lbq~`w z+|#j+3>po5d^dMJuI#n5-nLHr@K{~80d{ti3RGiR8Kl-B zvhVNG0bZ|YGFeZ^`M=S*6^*#IO^HSiv^|r5KI+>#;+fv8cz40nErg zPyYB~s6B3lp5F?4sI_kJ7_c>#yQN)z(_;%>R~?5=mi+nM_SIsHryd_fA@HpQwJ~mz z;Ur)ey$)qY`wMVeeu+b=S~y&QM~~A84qd)-<*p%RLLaPrzAGGr-6w64IQOMPiC7LK z&Kp+uaO-Lb1o!@_tmNJ$Wc>q~2PwBzm4Ae-JiJOJg1H$h=P-8Pl?w95(?45~3F92( zylh&@kbA#*$B}Eh0jku$KNn8LP1;L26$ItjUpVF5|JxAM!l5}K%kY+s+C|zBy!;PD z`tJJ9&!p>~UAxAgA5~q(*m(M9`iqZ_j>_%7auv=2qBe)a-QCBz^b$9|;=Hm?%ZK46 z>PDBZA1|c1rUlBAXo|z9WUq=-;D@}N!h8}Z$Ar|B+>SRxBf`So5+@9OkVbI2JNcU& zF)l%!NG>p00nq-8maft_*Am0x?3^XuH$AK`lC7Ovvcm}`fIy{BrG5Z0Bs8!ngPE@+ zulOxya*!KxUpr=nhbXrK5a;?`cko0C4_@9}gUfEI)*Lp)-JR<{!ntoq9?f(3NcOl* zT{vYFy^qN^R~aPRbVX@N?0Cz( zq?sB$B2eo1^h)gZ{jO876E)p?_lC&aqQ89Lqy7Mm7a76f@!L8BjCkXP{cxzDBnW84 zJ1W3@#ob_b1doTpE;<`$ikuk0^pXMvFt2eUpzQpNlNPWWqWf8BwjAURl(9eVoncA0 zj-(jx==(ou<;NooB4C;K!Z!2kMUY9ZqS&W;e(^n2?x^qG)Q42<++W$Mg;|FF765&$ z3H2w*ZOD--vy6sIZ&jYi1W)P`p8(N~AYfqF? z<|S&q5>iu|L>M7E>Iryg2n{}{2ET(T{eguc3eWOvwfe`DWr9#ofL03WvzWMjXG@wi zM6p^{FzD_6wxyLn)JE+lfUj8ShI&kO= z%Jj4sig9*P9k(Vs2SCl|^rr7cP?VPIO%S1-T|Ix3ag^KI>|oZ}-JK$s^H+VsQ4$wf z+&>U13vbTQ%559?=&2z7DVK~$@6yXSG(bf81Kugc@%mft1 za&RaTPqZpn=S8_nGDGv+cFT5Vh9z|Uh_&Z^CwW|VZLK1}<&vNiY+*Qyr4WC+1pkPy zM+vlha4ylZpvCZVeG0`y=IjQPpBY#g-eP!ZM4Qsc{1+vxn*V;=nWv9qu-Kc`&rk1T z^t30w_of7xcn#sBecW8fg9=)}*aUS3-?J(-k)0lrtwuEv&h_(RydMPa{hjtjsHMN< zWXlYUsxMeEp;Mu@7Zs;XBby_hWRH~9GchKMn42<2J~z+9Nvi|c+QUK*>C4afUx$@n z>TfrJoup}=oQ-cVQ$i)IldPv^zd~FfB!8!haOucEeflq@)<%&M#vl8M-(6cyqDRqu zD&DM$rya-NAS8;tvfdom3&pd!D$I{0IYDh>)gLj>^E``b69IS_jOu5lbAk(7Z^5<> zhE+s6J7BcIUB=fSwKETb$k@hmENw!p=t>+dyxxN4GVFJBoOLNV(OAIp`t0EIhT8M@ z^lOKs(wif+miCQykMjs^Y45pR&;7i7R6WJr@!KdqqubGp%jG&97`#briHd%*{lv}m zwW|>|z&>cgXG!vnMPC8~RG!*Wd?~&+zL65Lv>rFS7aY{vsyMa#pl$!bcn~Xgp#j+U zZcj~I^S6k}u{1Q&xU~7Sh#UrG<@x)06qUwg=9JHG_J1-_v4VxgPG5Ll7#1XsZw3x} zR1SYC%%yyRJp-=}{rFjqu9YlJb{88{z57Md>?WP*G`!8q0l7fmza#-d98rlFrOMPB ziVQqhOGz8_v9*)9@#*oB49N3x8OVITvYBi13;@Xn-MvogwAQD(^X(^hAYF9nu*K`A zBQ`Q5!Ch^E{PY`id^j?8Szy|7we#ctL`f38O!{OPVT^=?<K3T8tX zGl@KUPe;LkK;?2|X$<8(0<_7;DefC94;~%C;O;Q!`^;y1gw~c^=7LLCXMIDkr*8zl z|CCi_{tm)iEQ7mx?)h8&`9Fh|fmUkAT;=t6%fu|Q>qlC9!#(d$lAgSiO1pV{Q`{Q9 z6wIT)LiUhiC8SYBniOV86y4Mtd97c6@au!|7ZtDU81(M7HPXp4jd^*`Vb9{x%4V{` zDN_UBP3AiOg%(E%W@L3oK|BfR9)@%Z+W|V6JMrI%|5u4rlc$F zn2*j=8RZZQNdg^6!|~%PQB*hK>~6AwPa7x-jY)eH-PUz;#k)lkw57Zn$TgB$&_vn`|!f#af zdJ`pfXf<4Kw@`qVNx^bUCO?tJUT>kDssMD`B$!{6b0(w)a?iCHZNsO)NN7?WNEj!s z{>X+;3xN}c5bEo^vm#S6G%&i^U{2mj#qLhwV33h5ZfP8E;28JPR`}kX{kVyXkimP% z$_`l<7i7T+(bVs)JXx^y;>ABj9nGi(UWNojg14rSXRTq-We!d2M zSeGZk(pHGGiKHEU?B_3>w&F^t2@+uIJ^AAvZ^ZDt(@m&FxWSuhMDD`e;`_UyDwWux zHcxE|U6D}93z8l$7tl2FoBEC+?CW*y_s4`K_a~+sa->D)p=c|=K#qy=3g|O$+LiK1 zcgs8VpFLQ=C*}xF_EQyu1LiV*+FB8F$ujx3GH!MIKDf?#m|*96_s_H2YYmiK52Zqu zwt*XY(N42;o@u`mXSk}1O`HOWA-GZkBZElI$vq?Mx{#}oQLvh_bb3duH%Jg6LEdRc z?&8QY!|>0G-F6@QW>l#Ra<;d#^pPWaRUsWjjs2&Atb60_B&H?bbRQaA#!TZ{VKj+b zsvqt_U7ml8=8VV`x3X!BdArI{`rycI)@Vjv z9tbid&y7^<3I~*&qM+@o6%!C%?zpoPkB#xqcpoJa2!gO!iB zr|?Ggi{_mI(t0Z`zJV6CDW0T~A{htHhYw&q&Hq5v;|;wM?ZvNO!QOHKEBFtbN&T21 zO>@eR-rU_Ey2@?>(1r+)SZ>3lk8G|5k9_?XFgUX#*B_NJ-L|oXh;(|%jWXlLC>Nbm z7hkudQtFpYO*}PUzX*Ize>;{E8|FZ&#g;Hxy9;@{wj4Gr6O{g%NwZN@X~Xf+ub#^O zkl7m2X6L)ee)*YUu23oc6oy3s3IPZ`jYK<9ws?(kghKd5Y=lOvG|6O%QbC8+V3mq3 z*IDC6@M8zSM?kTlNZJFoP;G=@2e`-Yls)N{LNrZ9k2J)kgoO*VNF5RJneOuIdh~$W zl?qB)TpU}Z6?GDKly4cc&XorSxL^T%%b$>LnhX4kTDaceW~@sMb)_JH`mPW zEC_oO`JN-g{{lb-LNq9ky*WWd&rB3)Wd%(u$TO>~`)H;zV>dmQww0R$%~MOJ!%W4r zt+{Pu7$#!A+bqY*?aOK$^+>rnz0Fx;`U%SKu8RsDiXB>aUZ;hezrEec*7 z_{1me3b87BzHgx#vGRYOuu$h5$g@__780ejNhzr}6zrqn(IT-85)0#*1?(O z{&-kp>vptEt6+K|xFv|iNGoWaXv)Hp_%p(|xul)2^C~V{kl*i2ISxdzdYl+`Z@`6B z{T`~bwbM3T+-k9dL1l)BB@c3E-U)Dc+x0zzUJ}ek7q%sr7~|h$Yd1tp z0%gvy3-f=uuWi}VLL)MyDS>M-68M$!hjxi&&B_CER|BF*&K?%zo;g3U4xgv+#KCyv z18brg$mO3Tv`h5LWk`?ve^YQrBrl`BUikUxWOQxvXa17lJbfBhr;w;{uGuastVIUh zWFUF*>l%9EnJ`B-e(*yUK^Ya?U^lRt&ooDj#^-$$nSPQ^Z@4{2+&8Lw?6cnWCEYLDQXR+?Cix2p>Ln7& z=ru{|_6S*ZHY*&P?_JCo;#Q$FIysU>21iz4#qawZL2j?wKkmVEusH>kN9BPhOdx zhg;3mGz;jl=4#B1SEInH^oKGGC9Lc_e}iK|zO(ZALZ&7y`&q9P$yoE}-e~{BSa9+^ zwje4TYW__%D!gy{@LNdh!3kG3ZZVzEG!ZOzw8h&1ij9h7C)wQAk}&%0>cfmtE(@b) z+Z}L2uYk+=Bw4eX5vZljJeVNKwZ+nvefhmE(S*)22PKghR5*e#mhHLF!NyTAtrvB} z3$WV}qC;kd<+8eV-jTND!wSYq->>AhptQZInf>VWzPn)7&7(ov+d8#l9Xvzxf>NH@ zw91o$z}{gDLAry zU|@rn%VZt!!K$D5_cWZW*_4I9YD}!sbYZHc`omfv8+@(Ds4J}A5G#REQY=tt#~Ci-Y4)6iEhkKYy+X~Ms0gy`P3I{<|Gh6Zjn#H(5AZGwr@li0;*dfiO!zCTK?QG%){y>< z_?|Zu_B~O<5*UTkhLZgvJ=&>?i`Q8F+aiQuruu?sTrmaq#Az~oG|0$~7fA!IHR5um z$z_IWl+pc`)0wN)OpxBM!IeuuQnH&2T^6-k1Mr~_*@z1w?H!o0A6A5Ew?s0ANb`T7 zpm-OiM&=*w#jRF6@2syOqWv?oDu_8EU(n+!nw#u$U&g`@!kBTH-+~{63o5uWA)~9S zJ;f5n!^WfY@B3Q^&rOw|Kl5Car0s8T(jrR*Ayq^YPW`N`f{vSBn^523lDzo8z7$Q< zCT!*?0RzrK-BEefbv+KhYX(Ta6<;9uxBbo&pBL5A!IGfEArYXs_SVyTtX9_8UKiE> z6B8X}^%FszmA$@4#MUoq6=M}C|8WAN|M1FqG{D`g?^j*G6adaFjXKBYe6(!Hu(`QB zwYt$*nP2R=94SZ8M7O@wltG#&LrQ{T02Sqac1ofdNycUwm_+`%cKn-Zu#yVR%CIb` z==F=}wZQF$KCOpB4m&WydA2YE%tu3Nue{R&LP2f_;~f9%MxR{NLiLx)ckL?MK@EfLNd_I6>g_(fSOx*l+ z#7n$!+mR(-f4JZD;P%{JS>P2n3c6Ut$FP36nJwcBhg7aUymOV+&-JTs!1KJ3`C9*% z*$bZ7Ki&SLo6`Xz+tITrarODLd>`s=C0c!_-XA|IwH;rLIbC*I1l?}Oe4vSJG6nZJLSyK4r3OG4pE_$ z@%ME?Z)_$^u^FTib08>%PAjmO$a+J@2?`)Z`QXnCg3TkjJXqkJaYrCe+=P2kYmdO^ z7JYBWTsHrfk3@UqhcV@eB+j+}2Udy&UnCqvY*Fpk6z+hn4CK&{8?t|WkA)^Gu96IloOnBCgR(l^^I_p)hBcgj=+n1NEc%WQXO zgh}lilro)!`IT!6MhkE5eBu&EsyLT{y{Tu5(2>g!(p~YR7F5Ta8CbpPt|au8D2gj6;E4Qj6)mq97PiDc&XHwO3r-_rly09xNeq{-%QLG!PbBFQ zf%-9HwzXRmpUA0M(V7=XkQHoOMA^66-%K*m2PI ztbKDlRWKBbi5z)Bn<`JuTm%kv;cc7Vbm}&r-d>V!;V-Hm7qZg%g8%IcN7arRP5+?~ zwpFNMI}8;;O&|T(jo8gJzxuMDD@9E#@FId!+aO=seH22@)sN2o_RkG}lt(Tu@4oXC zKCg(r>0Ah|H`9yis21G^$%X(ch6CwwDDUPYb2URM4Z#36B#nawKez3oJP#S@WV^?` z%3EWDeQ9ehge|i>fVc9!+cyT3@L)Q;T;o@DYQspF9h`YKo7x4T-5TY>AmD#bA!M;d z5%avoI-< zj|P45d#}dp^l`EvlcB~vr=ldP-1=WFOmmQo=naXlxpnVWb<4`+AEUZP0%c{3#@>s( z)cnomvTj&~ei@kfyJsasV^Kv*Xn=eV2=+{sZqrgP3D0i|o>?G9JTLV8L=HLZt|AHd zv>Fc%nxt%s%hI_0dC!Bn)=$d)(4F@tSj@P@D5S3S@1Nb}WvJ0ru5SG^)FopxJgof5 zt`p7~27rp~Z&yEh55A}7*wVs3meqd9w-XcQ^?(+F)yhtWISjxK3bh!F_^woxddjoBYW!0#opa>f(y03%U z&#Uh=&-yTL z0Xni-+F@mo&!;q#*GZ6-ygLTZ>ZVG>!LWxzZJXe2$LSTi*Rl zo-pNccRUk)kNs%6Yq1gSCepCiQ1?dqCxt_K673VB0|6bwL%3^@d4Obbq)T&#w%_(Q z(+()MIq&lzV@nsxE`JaN$x>H3ySdM9w-(i{*G)lv@75n{x;-mfl>Z;n%qFiQQ_xj7gHnKPlu-&;12T2w*pL;jqj! z9xk8)h6=!<$ByJ~Zhbfk#{nfBMmw$jh%obcj5u#E_syKTI3!4v^azMkezrZBj%z{; zD+1kYA6i-VR@22lf2b?hu29oj>9L=kJ~Q~`WXaH5GVVP6APHq{bVys7uQD+YX10LI zeI@eQe%uo$+bV!P_T7(acR0xKmVN{dn#mNNIchIVcy)%5%DCn_I8fV|nF+e5xk8}Z zP?HBy=z`5ig_Z4}bH!4_-vjNT<_F$E?Z3JP_GKH)(8)Wl=xZKGBSrEuwu*DgMsZ=0 zVh;TwE?SUdl*8!hLC|E8f%U;kP@>wbA78bwZ67&Bxp(BnNbyy&QANDWkw_d7U)|;4 z(j@3qgV7e5u=4dJXoJI5>0a_mkQ3P8p0JDGx#T^`8(@ylA@zX0_E_jl+5MB~>P9!? z=6!h;SOLUou8Yy2z@ud_)2)4x_Ix#1X8rMlpD&eeS^E-O+7dNW9}E=#N5<=_hnTpe zMp)FcnN;zTI0i!>d7n7)i~teb3$0c929IbJ%)qJK-|V^J6?u+Fv+f`Le?&Mdx{cTI z_Br$UM+bYgFB{fmh+QoIO`V+L$PTu*++pJX>3tuwa4vcEj%?^#&7pOqic;{|Wm~Bu zE!DOVU8c0820v{|GH9P*5$2p*#Y|Y9jbrc7(>fw*Nku~b)pKH;~eH5)x>c{G^$zNiGK4#_%I7CK$qvCLk5hqi;OgE2^ zhsw^rpJE(KzxM%2N7w;BtB14<>Az}}U=NY;Gpzq{*J!$GXK9HUe++Tt9G?$d)u+t- zN>Tk(CTYAg6;<*N#NjDgG5l*3*cixtN#>xKwCQJkqa{C3lldLj$W46>AuzuCuqFf< z`ye^b6f&%3Kh1Q?>!h=rYuEcEVo2^=UK7cot9RfAG`4&6B9c{g-Q*-S;6l8Q_N&^K z&k+AY{zQ$WaP=!Ez$WiTXfI^E?Cc4?w6(5|FX|nUI4UChML25uyc#P&{Y?dv#88AK zBW^}7IFs6!d7YCO?FWN7FvJjx)T*uVf1r}zT*tGfu`oIV>(ovTigF5(Q1KJuAMP@6 z^!yo@PVgI}P~huMLqWUJqwPq)N)~}-<4gA>3$fVuDL)JB7ZN*s9imOmMn7-sK}E^# zz}xJw%%k1vH?X}v`%?A#Gjv4D_#L_^ ze5O@&y>6Ct8m$dehWuHis~M?rO}@)Qd!uiF8!EvaHbK@4gc}o8O|i1&ae_@N-C;)K zdBKeH#-6wwcG?XGSdS;Kqodf$A$ti%USuNh*`)o?pO_L8<#iFdgf^tdQJF(ez2&=T zFKyMNY?7nRi%E%8mo-nZJjn%UO52?oQ-kK`3JsdUz9>;CuX4Kmt7g|T9coLV<4RwST>$;Ep$z?i%VELB9e`3Qswz5Hg*rIWhQ?CNU z2W`QWIV{jyl7u8){&&=F{eU!kHdx$!B4>=;r=k-!u|*8h}cInPs2iUA-FxC014l=e)R6rZ&Bl2O`iwC;m^PO5{ zK9F37JAC^d9HVp3rdXXRgiQU=1+gmcb!6^;J;+VD`9}ts`YSiV)WN)1W}1c;K928E znM82fj1^JMThYT3y{yjk<*cgWgYc0e7Y6B4Lt#_|h1ei`)B$jW7wJM|etiVLq~TYg zbcCEfXvgx`H$XQp40G!$b2LQOKY?>TQU~E`$?Q$URFmz!aqCF*)(sF`vF=nlB=(Mr z!jP2qg?Z6hvwT>?+c=C|;?LBw7)G)pbZnq|JF&g=**?d|2EIE4=JN!}6QH`RBOqz< zA+{;Jg7XN6HVZl~-no4zk@9Cu(=v5Xx}lSdX>K9ePNgJSR>D6}WfAQs85z9>)Kj_W z=4%Oyr3etb!#-K3MC=z`x)7Tm&6m?ruEZc0rhFh+G(GosvFuZ{$D9ukAuNp$Y~}%D=hH2=XMX z6S*yLIe0OyJ9(3{f zj0CHzFycagX~!tt$@^qEYj}@cmT!8WCRM@caf+&$PkPXnjBfcyI-`nuZ3-zlZ(^}* zT!Eyz|FbIPI5O^-MulDwX2MluJgc*$F2;kNS9!&!eaM^8;|zeLRR2fOd4{w7^TWZn#7R%z@tOUp7HR9xSZPQ1BE{xckj-ltXasA z&&}8{!44YbA}e@t_Ep!3I4zUzOLCuL3pR`QQI(a4cwx}RP7e*oKr8HbwzFFQ-K!*9IbU=}0CV zE)am{O2s{q`77m5!QBuU2&Y~>NJbr<7H7Cbs~;^Ac4|?sQa5u8?FJQpA@);s)ctPN zcsasaV+1T}eTR2un4TIK$qNJHKmxbV`5%#sMg|r)GZmdwbu8OC>3CcICE=Jvh4Mf?)BnK z*!os+;>WZ4(j!L~S|lUr%fiLzpn{o#dK!wxuL%lpp`$B#BvfCMXpD$d zvcz-f#F@k;PF_Wqal?>S0n#6$@^wIJ*70eKEKrP{?P5P$J71$sK7EVgW^%I6C#zz} z)$L{)xQd!eEdC zw)03&y0h=1SJhmD>au``kn1(GW37I?^-C<6r4shJv{+rRuJXby^p4|wMNL4%OkX|j zaf=Vb6X5BZ^+60(QP#b{OtkLF_I>zs6_>Qcy^p7j8T$Ebz;!&_jN-T2-)v_E0bk7c zTw`wQI6d(%NhfS5wECER?CGT#7yM7@AFc9V@lw+Bw`&}F0z7w1#APhg0Jnq9d&JY> z_Jk*E%kPt!t+Y6XGty9PfB=}LUv}=Hf$kJ8pI?2bS#5F4jNkdgI^xCTIjpPVJm8gP zpypNG@cz+b4(VWHq-~A+WqV!AB=g$BK2ph@lJVssh)KYITB^TcbNN1e720@Y`pGZ< zIWB-Frj#*DqnC0Z4H}pO^*lW=nNuotzPA^$%G8LBH`QGWc#lRAno4uC>%y2CE`n_= zrU_RL6GmtDIjzD-ik9M@?kmN7xp(a3cNRCv01ga+1`9Thj+BK)ZN-fF(&X=dqb#uZ zYUYX*+No=t=8{0Cw@Q*m^0GO58{LQ0i@m@*R}@~ydPi)qQU%Ga>rXAik`OK9KQ%&p z?!l7tgfSN{@JR%rrT0GGqtIkznZy_14k4xQZFXgVesDz@zg|1ADO;Gaa7fB!w!4UB z+boTBA#>1tN|Lz62Ich>`A%0t8#o}|p(e|T;@+c`UoS!3HW;SIpiyZs8Uo3jY3TA^`}1!?KMEe52-nfAjW^z-+CS-7}t*OEUAl{44aD) z3>yjC1O8^6ZG24WOi;@Jj3iufaY{+eQ|fU1%NK{qoA}%Dw-~N*Mf!%JZNFGd;(kg%oz(RsnCh)!*SY4mu-!Ij=zp@xw_+nKjO{2bV7FseK^B~ zF$_gxpcWquIePfd5P&K#Y@ws>C#sc~!d4{79Df8=If z_c*^hoXF$%;JvY6}7n)VT4zLKA zlY*!ID2&3BQ6OnZu8p0a=&5!8Gfl<^pC86dRU59o{YA;CCdXVNEnPg#I?B7%|MfLn zI1#{=QEq`DrWs#<&vlBNyC<`(_%p~b18jFXKF0KD`HkgI zZd$hebPVv`5GuwUE_{73mO>q@*%a5nz<{05-Laee)XU?_;7#auO@ES2UNVY-77l9h z;LwS89_)WVZi`*;wU`iHnwup6U(+4^f?E{1#Cw*K$EI(O(yD`*J}GjtFne6-ebpPY-pGze4^7W;GG zLpq6fn5JwyEJ=0sJFPTEf1=uxB3#v%4tNTobk_aL3FV4!>E7!&X$2cI3+g@@E!PRH z*s_}wS$_mtT~gmF%nc5s)p5TPL>z884TB%vR?#N3klanjv)3;eueHO}z1 z8K;`Sq6gAnb5I5m=0u@KG6g>8>?p$J*;AntL=Xg)=?WvexrDw(yZM103dJ4V1<*&> zw%f8@*}I(&CB0CBZ{ZOh$h%WbR@RPQKG7^925~S7f`J0Rj z2>XrB`4xYuVTD&%&xkm8{iEO61DRd=p$Di3J54hLhI~ca0;9kiJy(CiPIrJRT{7J& zd4I_h1;dJ5t^;%dwbM2}H*}VD z`VoB$97FS~d!rn5RiP5#JFqA&gFx;=!}vsN%abiiQwaG&XYN;4!N1zLi zMLcsuc>>Jo_d7?vPx)%OT&i zH@7j_qAsg%h={-r=vzBFmqW?h?FZ20b1rD!6NZux zpVMWqeQv@Ko?P0bP$Jh7$}Fj1+D#kEH%z|t(oU6i>mTms1Qt(MWbba#W9e~YB{@RE zwQIy-BLUjIa}r0FHqF`-Fo#Ec?j9AvzAM4H4fh|UW#l+w0QJMPz-WC>L&j7XvvjG~ z@+;-g?g}tY06bfS!l(G~KSaqZTeV`oQ&_@N2o3j_E)ld=5 zm#7OMA$?Meg~h$8G8Rzq3EUV`)cAvh4dmx~txlr+8#BmD6}M*TiA)AD`Se?Dfa3D2 z^!fR0ZJ+p@q-Eppn5oqzajQ6`o1^)#@3FhJ)UD+GAn^G!f0s#T4cn~kl+g+ZrY)?2hF7Tm!Q69x%Yrf{F_QcYxfa6Wv+lwVqm70W zl0j%y1aSH`!^o(k9ynpx?AR^qER!{~>y1>Ex20-u=aZE_#gXiDi~f|0MK|G9;FJjE z+EA+9ZrKhDQxLa56Tf2e`(uV+)9Crb{9k5D>X#%V!-K(ltnZdZ7Hh|m%#eXg4_Slw zW=@+K-+^Bl`V2#y`dweY?$Rl3iHkG2ol_*ai%w~P;s;5CwAl^;AtZTtik{RnjnXpZ zO3{9BtgCd7*D|P-CRN8g!4DqAZ7I#6R*!rDCOvyvshqZ_y=mnIf&D0cHl0nv@m0Y0 zLS4Nei#+7~b*cN3mWnUvb521=t_g`#+eG_I!az7gTuN^%JWz5igx+)@*RC&Tyx9D=5 zdqx^lzSz!k%#0aXx9<;2t(IZz@?p7l?CS7G%XTNei9Kv=b0+RGrdf)+q^se{Xgg%{ zG2aMO1zE_>aK`6#|C%0In6;u7 zd9hIfmI&6K(5Item^w#)?FY64SMa4XLJ>1nTdMJ)O=RifYR-h`jBVNqH-lSEDv08a z$v}^Q0=Jsj`CNP5$Z@9IwZoPv3ezg`94{{nZbAllm)hyxt+@37u!1#QPAWWZwd&*U zJ>7NN(<@z@>;4tOoEgO}@O&?7GWgD8e_QZXOjXHs8Sf+gam!;qJtc#uLJSa&4f>Ug zwp@1KdtJ{Em^cyaO1 zm%J?3iwNtmdsVe#1~k@}_>+vYragF+mZ{wx9K7=<&hn^n6(xOI2_}@A5sj>u9twG6 zFD^50=t>^1Bz91-hH|We8H^EN{)AXQ(HPOzOa$lwb>tJrY?W!6g1L3r!~TXZN0w zM|8|1!`^v(OTGV>ZeI>rfN`9F&xpA_^CD8y_XtjU`@%QElTq%k+U-l9LhQt<#h1t- z1t0P@vv+~Jow@Om7f}*~!u6m#Y_|3N%<}h3FIMyvfqI%MzS}G11!sB6 z-0Js=$mbJ7DK!FYXU2$keVA!l+{jx79fL?Uj?O9j%h}&~nmyNUxTMHy{@M{&mJ`!Y zQz*vh%YvS2p;<|9-)9Fm_}+rqgK(A;j=akbD*MIloo6S-@}`HE#7|Lry*pKfr)94S z|1F1|78qDWL+p0NN-jWWW|Y3nFdAH?ePdvK+%bNCL(w^6{QGv+x%+8|WPi4k@JeFX zm1K~^W0I_T@(xTt?z40QeYr-9Ugs`JER+^AD0tyj9^Zp4R>=Nf`tcIV_b9EfP#G#^ z`Y_Tpp%XhLp{ zkJX#<6>s~L@ID#Y*cd6zGLCpWrvM-J4~^xP4LlNt(BpuYmuVB4k%ZI%I>riL!i{dc z7xP-b!BzzUnEuPlblA2D|7gkP+#tKCUbkKZx~Y8~j6S>;^)w@$cX%kcykuI^kH!~? zbGVot63Qs{m(gidpy40GYMK3+dB0W16dl;u_v+r8=FePn=SA`7p!`#;o7Ib+2g!8( zQ(!$KW~+Z@>5W8y|L@!=!o-=Hz+bn#mC;>#%t;m_*Co&{6%=y!@Gbk|fDbLQ&PKGI zz3=NS^h>v!kjD%2HK(a=i0g=J7_Dd@0U%Odo*z{Cw+^@o9&Ui*2z2#fAIt<(n}F^8=z|+!zi9P zi13Fl+1x(S1w)R@wy+TbN4aAX`}oOwsFb+qUO@tD{U1_Myj7g5R5QYEYjf{he|p0N zkTiwPgR$>pzSNu!oOI~ zp1`-hXZUz+et(f#Tz>K>pz!Y_Js5vJ{h#+3gyVz924rMO^ux@{QzhlSF{!8pw=Wlz zE}h@aJ(-CoyrPa+MQ5El=G!Qr63vg_Gkdc=P@w*E!A!PzOYuS9{f;k<8qLoz(!R8K zV_`;zfq=@hpYdw@|2)2&lvh+YMK+J~mSxWswSRud=sE+B@-0tVqjw*AA;G+_epsI& zeWd+%;!64O^3NXcw}bmi)&dkF2QTkpD;dM_5VcAD)sX0#AaJ{cb9}k{snN#_Z$ZIz zQja=sN@H)_xqg*ONz7Q`{9{5nf;nkLp~$xG$p|K1HR~JTLmf&= z7ZOVNAV68;9fsLDxzxi&>JkSo;?*6!aXLA=P(Cr>Nm+^v$f5(LP8oMU)jPED3St}^ zAf(qd{BF@vb!D~EZ5}}a_wroLAU7+qG7Cz0=q?~1W>uollhMZJi1DdXm5%-(`NOT> z?>)#w8w32tlwu#0zb%X4kV)t6lTut;RM$CjIxTdd(v8!*?E`WhbsmzC}Vyf-{wpUF16;+@5>x5U9C9_K;a-8Z}o1yfc? z^of8YVm@hDy{FN&f2<*GcIDANcD0=PIhQSPP^bK0vi{6R94uXF_UWAtxeHmmu_C)Z zH5fWtFPWg!swLnr%0#JhopK(zcKeF$uCVMR&NpYWa(~{A*Abqs-bBDu-b@gqJGe zo0VP}&WEdC?1~k;Mb4D@fc#);DMjI{U*)NF*lY*e##-0U$C5KJ{R(;-r8p#7-9B8O zx@UKw+HE?`U%PHEElP|%{0;%5>P>5iuz>`(m-x^^|Gz|q#`rq`o$-G7A0?Q&b;(5)To))gt zCf299bIpB-CFEH2-?4t_F3YZSU$Ie;^(cd$-w}$y7poalu@8s{;(^H6Sh39cbeRa* z3Z>fQ4I^(D@d#AUE5B%@$Zfq`=qork<@g1+LS9Ufd*_ri`>oc;kn zqtCwh1e z=?DA>-F%I57s4Ad{k_fkM{Gv$p`_f&Y0(jqtc`LHw_~Kq8cu1t*mxII$QlBX%nbMU z#9iplKh*6{TX)R@7F6o)#Vzc6uoPi-J!VA`a$J(aiehRxrNnSNFD;-=f_N8 z4PVTdKMWv0(teGe==-u;SxJlc>D~l-6VD^lgAoPBuyzpSZ_SBIr*PfcS2Q%Fhe@%P zHX2`^6fArN(9EvnAJq+0@y(x1QqOw*>b?-f+q?<4p zg>}10nmd<}9ewrNie@OdzT5S4VC7&lQmy^Q_CjZD=BfWyyD0vKANM18r*k`mIv(g- zyl&Rv%lvU)Oh^fHsInDI904>nArxNkZ9do+fgP2lo*u%EIL6HyOJbyDeEUV$1%b%3 zu;?Z1V~;=`JFzIIH6WJW_bYz%_W1AI>9^8X(Zl2WbgK|GO{MmNb;)v*zIH7+X#x31 z2~&bkb1lchs)p{N+Bk>bonB||4+{p`?&f_fojWh?x(xZqqq4Std-jyTL*u;#{Wrl| z$5@GXVvspGK4_<;x<~e*@*;)DoAt7sK4mr zp#VBm>4D}yW5|2uc;)v3w}*`b5LatyG8#h{of(v7bEo}3C zlbRp=+8^{$_Fvx$8UA4yW~w~fi3G$#Ml_7W)V$E)f+cVEJqc=!pfAMgsky7GCIP(j zO}WsLhtd_|*r}qj)vupJ18lP{1EyNr-&k#Yq^I9O%PowqbAwSiuK8usf`(zxds}>y zPMK=<*2a7796rG(;@as20>BFf5vntzvK;2i?L{2=w7PEbY)Fzr$_*f;br#j@>9KfO zjMEn#Dnz!bC%ZWR4md52`9;e@Ufi?mg&EPXal4WF1Yaea7-4y4u`tV&lvH^UhQ6us z<=EZx@eXEn(0gj*AkH(m=d3)RGTbY>D<@sw>T-q1op@=m`CVTwa&@)rFsXuui!xlrLrjRkPd&b^Y-@C>rc4{x=9t zWE_~M3|yQ7H0$d|fgs>sT8@wPs}yNP$P9udSQnp(tf7BS8U5&F@juXITa}+i;kI>B z_%o2#(0)4i%#~AV-x_()T3nS21-0VgRu+8KjQVCQga2R9e&*r7SLtTErKf-7)?Auc z?rl6~&Vr_4p>AWX!yoW{mV#91w>OHPGO)U2!twZ|PfJf44BFohh{<)B2E^?CsM8JS zw7zSE{1+e7k5-K&vxjYd+)yu57e6VB{_}~Zed~$BE&>2P2cLnD`qK8UdmE^^vPkJJ zl7?@2Vwj@}ztO^jxC7EW(4D1!?tQyQVnZJ8eJB*f#hog>UARHvi&&n{`Zrs8TR2rO z>BgiB(xyt8Yg{qQ%EQ3q4)6TsQZhFZ1q%FqG#&qToG(pKcSr$FEEzL6GTQR}b!wlM z$n^pu53ceFr4L_d2j`D76>W5ve52@gH9#<*FyUce1#!z+Y!?9tj<^6u8ZH?2{QH_$7MhU4l}3yNaz2U%liz-%Rk)9@n{D z->$C`Kh|fYT(B0`(-LDLbO#fqTP3;Drm{6rAZj_d=g=wR<(Z39Eg0PXrENZm~PMy5uUGrnS}Ntromz<0V^^W0{< zKXT&D^S5D{--O#OC4yv;&9?v>J~stigFr|f7!nkZ^lISmE%cc=fhU$A~$Z?tm% z6YdJa?FSIbBP}Fq^EoG8i14zPZYsHj52|aPyNco3iQCLqGN2o^T#W>{TB2R#;<+RX^o2#eaZ96rD2xZ?~R*C8kgqGn3A3XB^CxE$2;%-16d)jnn94o zUN&$!Q`;l*lK205=334E00#&C0q~nu#@qF=Y79?!q%_7n-&e{73cyw^~>;tcQFs~am~d+6Svqd{BGu+xX@R&LeN3br<8 zUf3E-VPJC#MJ)P{vWUsLg)UOox#`%z2Unchka|I?ymeK)lzqM==Dv>fh2M>HYj z=QC}xg#wJ(K#V7yk?~C`&Z;Glx0CX zBb#IUj+TbGbNxFtcO%jl8>Cxy(h@ob%jt>kZ2kWz%!wK8oV{C)QFTKfciS!$lML4D zu=9b|r{aFUW$IE)2R=#7o9D@*uB|g0Na1G|O-MQnKO&Rm=mce*H_S`zdw(Hr=v*DuBAU|Y zC$*mp*~FxR1W$I}wat19Ni4h?%sGKDVAS9gosA9mg0A@8-&;)jE(AhZrplN83AVX@)dZ(`l&3+ZW8 zC;xn@pa2;%nr13aZe>Wy#w=KRY)4Erykx)MW9burd|bfg*3MBI+>EV};PC@yCmB7q z&5PuD`ZK~$0ao25(c+*bfucL>UfpkxSxGGZjj2FSxFnzfS|X2VU@5giO~d6AfWC59 z{h8mZ-uVxMO)n3HuYnRYHLz8%=@lY^a7hvJF0sn`r_!ZIQajY^D(IOo>#^$F8d7g? zrv0YZ2fo~>)s$Wa43L5HdP0?C-3|*t`dcK~QjDo$D8vdsukxc|ByDaz_et96%R)P;gC zKok7Q%Uz&+V{M0TSeev0M?OBxuomMM1m~@}{pB_ViSh|ghH(991n=>LQfD@eAP!5P z^*J>i-e!xWhX$vVCU?rs8J3+Y_cCe(iQPlzzr(jNiCBjmG?qzvot3}CPx1z)QRBaa z2i33ZfAQUhFGjahJeg4<%+9xsRib|z-#qxE%u?rgMqsPN*elmw+#-t5nKMn{M0!K+ zn=dpdL1K#$xTbLwL4mDjT4Mt(H||1@&8J~VVz)>#{;FyP?&1d`AQO&1qT!+dJPYW8 ztsjzeFyW6WQw=DWUmu?5A$9X*R180P;P>7X9T4R`miL9+*7xU z#avOmosG3D@l%qC8Z@llr=758=#6)I+3s-_T56Ew9oX*?u960Xfc3b!Lk^V^xQu#B8V^$aNVjJzN?Z!GvhY6h5M^qd;+~W7`I0#6h*G0r4T5t zF{5y0EB=fy#e9Fn@87!yshn|HkHwhR?~2D8XTLh;3pl}ouTFCZKZG0EVe-L9?VG*= zVaJ&Mz2mf7VSO-F&KLZriXTxSYi|ob+$~Y6P9{>9KXZj_XmaM5L^)khnl?vFXCzMA zsIT?{W!ko@{Im;c@;~ew-~xYgQZQ;wvMYLfb)5&yCj0nmqY^B<`D5W#Dg;lOKiBO{ zXM4L&)^%|>Sb)oJOMgQViy@RN!$^Xkh%uWc0?h>TSBD{T8p?+eYdZAz?W$-sJCM$> z^F8J%l7GU{|I{=JwPab`x>XJ7uOe>6Eu^jMYh;p3c{c!su1`+o4sL5+ey;((t<#vh z^Ja<}EFhSG*t z==ez!b2J3!F;dtsnU@ycQ>tuCOZrzjG}?hVDbIs+E<=n8 zB+6>Igk4|0y&HC^qked>8bfSxL{8u9>Gg`0bv7K49?y~=~f*Z<}VigWgesL?(l?zqE z{3zvisSx-=*4oh}kGr_({WrAt!j(b(2)2B=d3;vjR%&kSZ{me4i}Zd)^UEGoJ8^{9N8-}k0iDY;5ps5#2Wls_;YO6gO4ekWI_Nt43a04 z&V{%02+g*eyL~WihanWvWw893aDH8z?oRg0*3vuzb1OKB%RzPS(>R;^G_!dmV*aa* z=3IVa&Y$z$_3P#SJC0v96bI%(UVmj0kMiew!R&#M)x}mvlweq9B7%0&Fi_?QI>HX@ za{5)D6juIPsQQOc!Hw5ycdx)}V(f$8$*~3dXH@IK>ICc+x424AemoOfU=!7W_VmIH zTTF_t>%rY+Hs(9Kkf|0tC4~bO>wlnbJ~fHWZFX3OdkEJQT6tPYFr@RvEeF&uGd9XT zMMBBEkTzZ>Ft%%&VQBL5wCsCV*Nxj9?nvZ{EfVPkKs%HC&qtaS!#3#^G%ypE{wy(uMbdWTaCA;S?i_6Tfv6su==7*=&-kwc-c2N)V8pawX4+Tyh z*{YaO{tiJzPQ6AwNp)qEy-yJwF+SJqJ#%|=LE%puH$nVXFk6@@?x-n~*1CQE)W{8w zW;ggMU1+3%or%UCLM1E6BR4O$Lba=^34F51e&% z@1YkBT~cqMf>5f4Edcx7(NbpQJ1fQeD)n+gq-Kt_W*m?7w zdxdXSlksH7L_qwhAJ@5usppJmKnH&B|4A4{vvbN9rI4^dBi4xbS@v3-*!7y^y4tx* z#x7H;qch;G`1F*yJ=Qs30>?!dia68+B`#6~dQTn0F3>EzWP_Gun+!MAyZN zwS^njGy@+VWv$OBh_R6xoSEM|E#c^Fqwic&o%&k4%-P>EVfAJHM=vZgz^ailLWQd} zE{GK+o3!6nd~|M^$sD~}Bga%1^~7`AHz_J)MJD8Txj^6cg=x+Y zrns~rtJJo80?()Mfb?Q9ADr}L88yfI`H6H}gB7!SB)sy=qjpDY z$zM+JtI<>icwlzE11n&at{KcaHmhzvkhv|WogdBTFEO7#`kFg(wp(#E=mjv88Mo6w zsUjf9|9|G|TO|j(9`mWQu@#zi!LTOLS8TcZ1sI?kLgmXpBIFy`_Y~9gkk7=KLiegj z=UfN$aI^}H5J4~Fy`p5fWyLYV>Ol|EXMnZZo`Y(EV8R4H{T`4leVz%;SDU0EPNu=Tb-)vkF*(p+Q`CpFWzL z0bf%HQ98BTl*hfpf`=+Un!Ac_!9(dwejSy0_q1MxoD@cBSMM5wFCKyB-+I5=+U>2! zFzhLwURFWnt4}-10@vf4P?C4ctM|8%8W83GKzG>DBM9csA3^TG4%fRy67<@Ft{pr5 zU6&iRXh%FaH&y<4aZ5&xsAog~4pbWb2-J4;5TRUT5`dc>o|c3wLkTn+PT6cNBy2yH zJ=gE>NqVz~aQTzG%q?@3V_+PDzuWwP&QQ;@XPV`3g^K1s4-i6Cq{y)>ylS^i*vjlL z>irs{W}_AWO$*{qzboL+7xL&m+bvrrMcT|Nu;&HD*&6Mv+_lAU3A9OTt4}qP zCKo$^{HYIBqpY}PD=qP8t+wo$)rA^p#Ww!`Hic54&^yR5d&c21FN|k-zP2&4x(ofw z@EO2nno+DnpiVX(Wk$TP`RZ98gVRm6^NAhMQdf7L?DjS5kzqZwUY@Idue%a*Qv1cW z?{hHBt8z42{iP7)6f@O%^lCZdJY#?l-B|}D6CoqjElnY*)Ue+=+v8?@+_ji|XXYYg z?eh6Mx(v6kQIl-W{s{){25b37Ij?d zc&!r7?12hZ^O(@8JXfu>fcp9L(C}i(=!p(|aTEYG_?j~LXi5x<{(4>tjc4@IMccjJ zU+nA85D>ZCEPLM=5}x0Py6srgmj>!!6>M{PEiPr7C*g0?^atMYF8b38&xXvPQe?;u zqqArLe;fXqd+vEDOkso-kv+%T)V4oZ01v2ZHG&lG3Zf3Ti-@{KP>@XM-LQS=$pC;l zQxVUe5vP>;@;l=JFObZ)VUZar3*k-dDm&M+A)C{&LVc?)DVhP7pb3P-_)mj6(_HVt)twziJ`C#6hZz&@ zE(D9wtXa{^qZG$8`%$jzQdj6ZB0v_{8N{~v1+EhJbL8xP{9rwp&BOL-%k5v6uJCf_ zbgt?Kga1I@55=}vC?tbvJfa_Wq!0pEgGXA^GJ#McMe_LB;9~MpW7?On4~yIN+`uke zNVNj`;fq6kyBw>(Q1fRDaN}Dsi8<*zExfyGKo;5sQ}Znypwl<9JB{C7T&<}?fm@~P*@XHAz!&^w=lF+N{gx2)7 zYtJ?If4RvpA4XTm#Z{4-OwcUU9l|8N&EvE}x3{l&K?5Ru*$-ol7%}&1KOhw9trG8l zu5=coK6Dkt98-Y8vITF3S?T#O!I6M5X+f3sl0yK0uT_Vdf{%hm<{gfy=?ZfdHCVb$?pU~??P zu6Wj+{lK^7T;Y6d_m($6%s_GLzFB0Qo>LaCG4@^8y@hv1er3hg7k}vamSb(1ds<1G zWJi>16m$(J#LBC0m&xl^e*n2jE)L5DD35tJmxx8YUfNU{|ZFAwN_*| z)cE}7!3rg_Qk6Z=|SWDyYJ~F6pK#G@Ia+`U~(OOrw4E5 zeR@e4k(X#-lb$rnAPvPh1U+W)Yf{f6V#~zsb-P)|H}Cq-oZ0(G#BskGeI6_CkZWMX zWzKobcE1YIz?%^i3R4*|V>{2cE0Iq>c zsEz*f!d=f=^%;t7e1p0ij9>e1=-Dq=|AJ$wKyv;@(w zoZTc*H-352+=B(b-@$2ASoMaavZwLB9<3v~xSR?#^s_z-uQ-v(Z?r4 za20#Hxk`&nD6X3KGC$pSY@#%CuCfejQq*YLcTxebTjFvMH?H<@j8?oiXJE z9I^Y_h6G;OnUyuX6E7PhG%wU1*}F|jqN4v*t62a8r99qK48;0C-B9VpvRsS?L;65V z{C}YG7^#ow!JKvMmj#Lw@xJ-xw4-q*L0M>Ekz|>)v{)7~iB;lr$9|n73?87^m=rRa zG2r4&7{A3X{VuMx(WUT+15W6dNVgt`uutD82g3FM2c~|PIBWD8I`X?3*es<2!kEE8 zy!F?C;kVs2Xxfu;_A#Ih1&xvkiO9&fj2D!NcAO^U)$rEVS$$F1*7-&w6y72x4kc{1 z*zfha-u^48&rsOsK{22Dijwt95<6w`MF`i?<4=EwCe;@kHmGplz2j}&%|9s~SV_7s z>Y`zX)MG^$_uI1CjKk{A;#cT%op(v=b-z+>8O#qn74ADb#fV+mw-kx#+Fj z2)Lo`)?Tv>WC=7pdX?=PwJ&?m56OznOmbJ+!qY~tHWmJ?Yw?iPv@JI zoz%S=>gHx~6SlAYeE4Bkq4i#M~@h{BnGFYmtO(czl6d=Ugvj(9pAl{~Yz^wd$ zLN89xqUfs&!4t}?s3sV8F#%DZpoH0?k1R6#t2QR2bo1vcTI${;N`2$)50#GD6Fb4u z7Z0qxc@k(Zf;R|%NOa>CE-8d|J};^_aKL%g9*8Unsms+{1gQzeeDW-eUaXV5@VL|~ zc^8G2d>nJin&WnC6>&W#7{8|&^hTndn%TPcz?R3>jY4{<-r^Vf=PSj{@Zeq4c3M5gS+<-jmXlNR4(} z3ti{@^r8yi&x#noMTzSc9h{;8IOCyWk}t6_BPLz>E*5=E+Z@K}ABZr}!}kK~&r0U7 zGNUvWcW$V@!BV=__@rJw^b9s&3uVxzFYMXWBI?`gA!1HENR1z6K_EQ~C|*80p`>!P z3LjGS8dMR~esNl{0^9xfkRWE#mL%;X9JC(*(S2^7qzBs%=cVC?#C#N4g01W{X_Dw0v>05J;!aqC>sTNDq=598+#3#s8(>=bGb zy5>yx7pTv5IE)%JZjY8oM-7i*CC_ngt9Z-`qxU2<)eH}$0!|HsjJ z$5Z|IU;J`$3%L=wa<8kd5-O`~E-9kPen z3C)IDAJ1_Z^kl~=u}~>`cSC>onOT#>J`p{$pXT*6Xn8nke+$1z!b~>hk&kbAd{cO` zcb@&$|7@g0K>Ycv>083?>JTr>^h)d5u^KC@;{0N)_u5|N8k0hWN9h>ybcicTvAc)t zNrIJSRF>TRc@Kix#Z0zWKKYv#f2#50u9AQcV*vEKb&YA@7%^h1=|QF=*G<8Bbhe`+ z=a{yPzahigIJ%y$<(C!4$)#&MnE@CHj7DdI@;ln1Cf=n4_$=-FdrVCISmXiRN$;CA z;|NKZkQ5l@BdLaYHyUi-$e#$`4N9Hz0iPr>n>Ij`y7;5+zOXrK+aor5D(;fZE`16m zDfl>bwIsgJ@aK^pGvKpH!Bz$7>}S1W3zR8j%XP(^dlgwSkL+)`Jjv;O{%>@Y<;tox zn$dqw6eP+|><1sI0&~fQU*i`RgGJ{?G~}cMMS7ns$s+H2nkNgbU5|hsje%-+;${4U z1Y08hz^!)2b}rm%{SOqTCZHO1XohIIaxOV#lN9T-6Q-%D#03grfzZZV9jS5y-*us4 zVqsV$m>5Xy{0W6RT4h;W9mL+9X1tQ)n#i&lalb});Gq^ZL+6~TM{jfb4^o187WK7|JAb@o*u+kzwg z-6ezH#mumnMp;QC!d41`dPc-bd%8i;k8?I%4fm}5o`$(qJTi5evt6`L~eY(A-j+ce5I!+n4)3_36O^HU}R!qQFBB7@#zOhKyQQTLhdH?J4<)Xs*W zMC9`P1`UQi>?l7F?zIJQZEOX->Etvr5#c0cj^nq-epwgOME`{h)JSbG_y_jEp~GKb z*6mhyKzYQ4U#{9)$ppl-g9NXx((yXbFhEk-by+BTQM4gYA==Rz{!{J}Oy7@S{43g- zKs!%6CDj>Ghe1eCPVUe60-XsI|`$%CI?-q zNiK{2D7q=gDmO$yROEqtb9}HMbq7wjJPz6um3`5#n+5?7U%Wx@byClk1wen*ayH62`PjGP zR6NEf6RwuYtbut4?xZ1ZZk|hSPlAqtC8HL1cahP;fqKh#^)!rHn!f!? zK2@c;GNKkEVVc;%j*s^@`nsXT`AOs3zc;R+CF^hhey_mjJHBJ@oE^&*eP9E8+b3TE z*myeg9&5{!H9l&VQKZF})Oz`hf#L7&gHO^eTTOGRUCYniHIy!w&8XqywI=J1{%VJE zfk0O#8}1f-4_Ca%%K^#jA(}-E45zeTnP8?NaS#@-p$Qf!^#1g1%4MU9?+i+4B}xT` zD&9p=A3ipsgPsxeika{Vnm8E3z!=;kD7p93rdX&nMSTx?iLTWFyuG7)0Z%mho65c+ zlGv7JD~!!sGAb5BVFLen4}XnOL~4o>d9h-nV&^I7e(@gEJfZT_r8;2E+} zB5FtXhIH7ync%3rs&c*I=jR=)JBJo{bm&lOjjV5@*&0H2CgZuJrO@$CX0#=Db8?0A zP$jF+(6@Vr)BZuhb0LSNtjYH=2@2+`y?`1yGe=F6YRC~EC<}xrpAEoIZ617SYg~@f z$co+DKg9(bkXr@FpL0S4LB-dZq9pZXFQb3c{z3TF)OKjSt za?zi{I-LijE)vnc+kcr{xa}lAjF~L@S>6Q3O z!S=D{O6qk%Ds^}?Uc|Q3NM3aOvL~tgs93$kcd)|m$lvNeP$R)+N{WLh$-1qKi`d^Y zjzca&k2{1Q;bmf0tG-_*I~;A~?{~Dmz*ZzT6i{0(0DdeWfKzaScfB3{^(Yj*g%&g&o98 z6GP?ujhh^5Q7^(f60{Ct2$C|lZM|qx*`P3D%r6s-q;+?Nv@rGQJX`Os_YeTo1L)8o^I4Wpd5Z~xg8Ue31iIjK4n}96iX_o zn*neA!GzS<07}Tnxzl#7Xajp-qrgHwFJYT5XpSelnd_(|DlyCNT?8O^5ufq}z&%g& zq-Rgo5)LL?Sv+R5wZudK;PlV`KoU>0+U(^0W8O;6V|Z`Fz2~1{^UyhvRmCgsVYisx zU}#f3*V5(owshWr<^5Ko@W`i=G}Kp`PdK(VV|5vLw>F^Mb-zEoW&yf?f{?p~eJRZ> zS%lr&wC2-hhYGnP#F%%%0XYCoe&3fjNLJUiXJ|tfSl@1iUcn*z;x9oE&GM!EFf8}r zscwA18(wdu1`SWmuEx5F@8R{td$XTSPy-M;4(H(T&heB04V}b53<9z|+e9W>(gi-~ zi0{L+KHX2#cZij97Z>5Rn*dveNHF;Y_z;9>Md!RRj%4^@@FCB*@%g|@HS95sPP{t^ z=%nA$&q{u~>T?RB0jLP}nms;)`pJD<>(HiUlh-5zrNoQalc^a0zutojZDu?z|5%(7 zI?cZ_Kwbd;AQXLV)}RBs#la zqjsX>*(tQhgq3~QIJ$S0oci7U0>-6%iqj{@)NNYg^&bR_f3N}PJJ+ZWEB3;D)NO5- zRsOJdyfyN5Vdfdn=aO46(FIs0o=v~y9tT%jPQkqj+cKA~d-6`bfsad-D`(8@KV=uP zDT~1f58EOhkzw*$S|g2u*cjU=yw0t8N`Feg5>KS2Oh9aoP=c}kt@W%(gp|}8X>j0n z|4K{8U|K}qYt_t87X|xiP4i}w@?zw?Xc$2FrpYwb9o@$W1wCSS@k7mjY>Z2ui!;@4 z$Nxn%A<%$}EZ6Y>tCn-UISR$7wHm(|riiHP!w zc+ufRr=?5&H%?>YVb-eSvP)Meo7>pv%8}*d!M?SRBd9$B70j`_P}2B>e7*Z3cOrLK z7Ms&lx0kd~AoIqf+Q+Nk*XSQsbDz(onwOpBHEP)m-pKheE3q|E5qUQ@)`}(TTrkC< z@q4aNpmG+wo06p)G!iK!|0h^BF<4uIklog5g=hEsdRcnzHCk8$OC9;_b}B!v?C~Cg zilv(AzmhjGZk#6Q#jCC+94usBz)2;B4^}g|Gm?N_1f2&B`TXAPfqOWPoR3X9YJux! zy9MAnp0^=_nGdAQV_F!Y!=lGsj0_sTB^(l8fN>7I!5rMm?8c(535bKVe$6JZq<_RS(AUDZw4m;GM4fA1GNmdy!B8(UU2Iu)m;UQ;$i8$X$uu z>ks_4dth<-BzY32om6ySE5P+4rFoY@OXD=x_(w@wy;@%O7NsIVByD+^eqf>x$YJ3bvP#3?_c!oS(!t8jqC7hc*BjFG;Re#<1V+r2jz~jKUoL|W|?B|o%<3pps zU0Qv+Tl!i8Hag8>^Y2-sE$8JlWFn=>svfiX{d%mb2T@$s0}shNvph@sTRa9zymV%g zfx+l^08S`nWJ#rpxKi$7XY-4d4A?#ztjx6w+(p!G&fN)hDjKNe4Czxs5X14;SqJq zM9t?QX@uo5$ih5yX^pV}GMg}nb6!!)tzPg4Zc04r7#NKF+EGo9`3iTZ>q5k-KCg^a z`Yjlpf@sgCsYDF;hShcc1R^y^i0wAl#SzfOwF$8K-A~FLe1BT+OJg;&1@3+iMDJB^ z@tx#XKKl=JXXWy2U`}Fx#3{9*pE#2$o(XnAPhWWJQXQ*+UvGQz6(6(1Pe%i<)3@e=`tXZAbG9HkC1B7`oP8C zZ)xc*CBZ^r-&%}_T0HfY#kB0af z5rM~YXq|eWe&5VPs6$lix_{f2Q0v@&n=lZIkS zI1V@mOcQ5TmtxHS&0cYpr2})-l;1y8XACc}=Nb?2$M16NEhZ2+Tk99z&<*4F#yQDG zDjWfWnaDfT$$cfxZiL~CiDLTp{y4WWnf%uzZQ4KR7k0vEb(LW1Ix$BpxdpOGNVP&1 zi(2|nXRf9GFb`DN9et!~zv%YURY%nXWo#(lx7Yn2$iMSyN0#c1hl=ho%IH0bf4jh` z?T`vDCNASW52{hgIX6b~{Ss$;%hxVI<$S=vM_{bY1qv4}-^tm{l4`2L_P-yeuZ_PhWMSYe<7KR7$3#RjYx?_7Cd&Psx!Bzo z0Db;)w9~}+hoaP_6ddy0e_|q?Z$X)ValH=?5NN%kGv(^h5?kbrLVwmR;AZQXi5gZ= z@5QhCQaXe*7Pt8PdU`g>VOBxG^)#1uV;1&&E|rRgzU%TQ26La(1@i=I>@I#VH=8lu zFeLi6Oeff&pwh5|NI^e5+=$zK=uY=w@I!wRkw__5j3Q5ejpXKfXm!wRl@!aow2Qu% zHWu@xT-QD5+3sOb*3YE#XZ>Z$D|dNjjc}i&^O_$gT~kmNitEeW7ot^+{VUdHqNO|* z2zck{&Q2miNph zT8943xcI_Dw+M9@+s0O*t*0slU<+U_jD#T1oh_ZT3$q31erFAVORt`W8x{YrTrIm& z4S`wBE%L}Nc5((^imUX9$1D^X`Dwm}I)~vtweU$T*{p8(7T>tzG_>q-Tz9yo_Kb<$ zhW=rybdO%b$HihHr58T*K3fPGJQz8d|9Gybt{$G?d2;q^ub%b~v+8a{%GUGC`V!Nw zB5&v|w?qAdX)7|Kd8`bsE3*~a0FB3puG3$o$|{>e8Xds~1JcBlt?&@7o-k|a1NKCJ zaBOZK4>e6p@RsLnB>7=jC%CwHC{pTv;=1)>8yV!u8#@!SBIg}=hD zvR&s3EGWs_{B(f*Ao1D$$U{0G`?nD6Aa z-AP@g(e>Bn15Nk^j6bmmSPR}-S zQ6Hgss;49)qm7hDV^fHN^Ir5$ilwQplTM9WXx%S z+I`lzQ@<&p!@-xkn7=t70)-p(mueoZDkS8{{}6{PD2;gJmX)DkH$7tUCFGSB?%ekZ z3=Phvj(1;^mrO6s2T4`to|yPQtsHT98G^Doi)K(<^4=j;8D1+fu$FI^Q2i49QaHIN zq$4MTB8W-4HOf1_qa4xLz9na~!rjfOHJPonqab=pV~FqCn;#mvSqc7OLw>huat4`) z&Y-#i{1|S!`|0NUP|7_91T#IwU zaN9ADph>E4(t7PA$#gYyqTyH0YyP+}FoH~4DY%xFk?A3!aRm3oP3vD=4iZKGmYakF z7dZ$}&2fz-&iSe+Z5`&`KTW7j0?6(|M5s8Bvc~~dScGvJj%I1$BCaeKa zpqf+#KBsTK6&4;>5^85@qc^%i`avrYCE};WODqo4x;}C#1DwY*ArX`(HQi73rvHrG zekrwV)aW~(EV|Hj&r4oe+v)bUFsI~|*l$Az_diD&Bjuw`kRmhh2R((T&zv#J(VIy?k02Rw1{afPeR+8k~T zl8VQpZEm_lcaOkCQsp!^)g(vDV>0`#oyB6SEXK^%pdyL=Pdw`&OsEMQ-~09YG-{f2yV0ZRfD-r0Ug`^1`m;ZbV!;I^Ycqv@ zEDA?JrJh*4I7Y+zoryLxg<{LX;9JrrC@~?CD(i=F{ctitug2u!l}cM`$@=DzGp*`V z=s;(~$;C5mN8qh}1TYc9@w&UXuNd~Pube(S;F_(E$f6(6_XdaMbn%X%u7vHYz0Jl% zBt1{|yVLA5vk}UCTDr4iq2QD{F`(zQp-QD$UlKiZ$E_7(=Y#kScXwi(t$(+RmnoH+ zXtHDOJc6&~b#Fsf_0B(DO0e9tj16H97Co6=Hq1-5PdKV@c)57DBDq}gdfiY@_qYrk zpJZ9o#fWwQcy0fI*yY-oM*4p|7$9F8KfX|XLWP`FGRRl##csa!Fcy%WG@GC#;9ghr z^{w2Lj~8m_)~BbF(k{cY7%Od zRn4p|(h#|n9BOarh#gIH{E_cnLZ$*?^44FtO$0^Gh8J*lehw^|bghn&*sBF~!SH{< zAeM-QN_E#3w$kpMSeqO%dUe8pfj+a%UKyp>r<*uy56EJL>Lxd4Bp!ZD*iwhIEwbe{+yvPzIy@*ZFgun*5s>pYi+oJmelg2ppuH1f!#qStZc@4VY z_1_!P>owDZAyWU)Z4=rwU-ik{0I6+t^EvAyF2h?J{!pFYpC#@Vh?%L?CMuk{=Y@1k zTeo-hhg_+TyWTlcf}W|io$pvVO9~s9qHe3M%NRXlMm!(8jk@-Wh_g75bz}1_c(&V^ zaqnI{U(#ET?{97Qa=VRsx~_H#sTa-8J4srNyv7`h+C>a9ijs}4@4dnQY;5f#hPk-9 zx<9q^xe=W-ahr5{ur5^-ci7`sZT26?#YwDTwEz7`O8u4f0x-C#>8TNM?m@5EWKmE; z#P~_PK!D6mc|GH{y{l#SzExYByt2|{5vjn8U|gkEia)J?txUp$)7H?!I*AZ?fB{`x z+R@k0zM4Gt>w$I|eQ*AWVqA0PD-K)P^EDYS8>&$@Dp#dF)jHgqLfu|o56{lyf${*c z&bDQ@`@H{wMjn|#^YEpl%AyaeywboY(Mm8Va_LFel%mmpp*~ME<>I*1o|GoEU$*fs zO|YX@^suKW-aWp5%JWvRmH1mQ^7hdKnfmew|76p+axpR(N7OVmu>pyN8NtW|ts=MK3NAkvcDh97+?`-VhtTIB2|pWQ#`6Wt$veGJ*|V5m zlX?5s&)0@avXIL_q#v1ffywg{{(5jQw-i3NNdHxqa9X$|4LL-^v@JE+$hcO=ofE+l z(rv($Y1^DC^3g5*0w};E={Z+|_|Q?B2`9HDpD2E}>PcG}FT>wQ!xhY6%8k0jm&ej0 zaPOlsg&)^p5TWcgRcY6G-+qvJ@|MN*`(Ssh&BQ5?h%lfdNbk=&@ZbE&Okm0K`Z77` zmvpJ+gI7uH+A0=?FNQR@U6Rz|Uh;OCD1V1pw+AaM>iopFa*7U))iIv3Ja)#EDhKn$ z?^_{VMHJzuS>C7y!-PIo^S(R34;X+U7OOW)H1U}UF4X_l+XGRV#qv;pvW=H7A6~@A zKHUqA-&KfvIUPp?6iO0?~tCOUTwd}2sWQ2DQ_ zddAC7gj19Mstl;S@m5&WXu4Hl9cFDZ^Q=qIV_?qbD33)2=Jwn>?n_8lmI#$~iuGgJ!TnN zSQx|NvPJqrFB}saTeHy&M2!%r4o+$_EdH>iKB2r_{syLyLvJ+}k9;HB7T55h)Y+*K z&zdy74?1^p>Wi&#`z2!|t$glj_}|lNLT00^0aE1VL{p6p z>1azu4U#M`>q&y^U2bh;wjWnCEGn$~Ux;nTOJ@V=wuQf@Y+G6Xx!IZ0Pqg zk^(hjD`vm#B+D$MHpIUyr>zx_5Sn^081wO_ra?@oh*sIUhlPBZ&DK4ME#4^n)TvQh zWZcUC!pj|naB|hq{;3b9gdkLxSXr0E9hel+hDu55sg~8a`4W7RMQd6Nb=89LoA}=>+k648dkuR`JtE z9R9q$cX&$j2QFYs8fAY2>2kaL*}DBdwGv}P_{0mmB+^QI$pG=~{^{zwS{STG3s=PU z_%hyJ)(-}cUmR}7V5Ehm=-s72-mo2FLeUFkwBCug|J6OoOH`R#WDun`?3~S)>n!h*mfOR@)rw7ER~=D15Ov)@{?k*0TKo zocvmu*#>|>7X2&I$^=PK#;iu{pyEBpYBNJQ*{#>4BT@(KlhL0${eQdswt0l~YO_K9 zJ56x>>E-)gwzh8-Zu6$*KhX2C4-U6p+dMlndcDmnvMw!ufm9VsQ0Uh#xrF<)7!7v? zdPNm0({S4^MY7>J5{b|%r~Ye|N}qZE*LTZi-{&gVJ=!Hn=MRpLs(I8e+H4EXRU+N^ zw%ojoe|%GIZGxqt>{4FF7kFfMh~5VJ+~BiHY3tYW{JBDZP%{XL+pl7JWTJmrpB`Zv zUeGA>DqYu>SCaA#ylT0ORmufCxuJeB+ZP!_K02Qo2KJ{<4O`b%mcf$3BY3;94Z&$A zkfrnLswGS4MkDgF>(-@(Y`6PIKDE<3VVQohJ9A3|!I~b~9S|k*H;zpu_hhn;Sb^Ir z&5H!(*%HU|+q>uDs@YVG+K0@o&kE`R?egc%d7@Z<5(UdP(ZQUo@4(cSO3Qp{4rejG~A0=2T^ zz|?bnk2$$BsH}VQJYO=TQvZ(}C!VZ$aL;9zLBW(fRWgYtstQq^paic=yU69y+&k&5 zsU>GsWpkcnkz(O)XylJ2RRO~>nBWB{6om>f7M3K`?IrTZlx7Uhw}ijP?d={jkR)_f&Ck&l zB^`*Gy+83>S;-F^R46{R4v}w=vxEj}7%`YC4T!I`zdPtINc#_j?It4|;)$+#!OE(RCc)KQMLj2C;>A*&XVyEWZO4!MpUpX`g~I-h)bT+cQa zu@%-$m`V*a-p%~+fTOLc8Tw!(l6RoQo}2|hUVp-mZ#3mi$vj(sX{21UOMSOnK$^L`fB2C1xwT6CIU`iI>ac~i}pziUR`DfT>OhKY&d zSVQ2=CcJ4*8+Z-(Dw^}xy^G^wwTcW1c|O%--NK`^cuR+S(VP9)-jkQIwi6d&a6V~# z6L`M{D?H=cyK%7c1iJ+LEu?PMWFHqltsUNyn9$mC#|SYX8VW&r_3TEd8cBC{$?r2e z98wuiRFCpIe#%|MpHzBfKIwJN55LtyUflWUG4P{XAtx=itQXC6&1E}5de-1@-oIn5W@ zUMsZf%S`fETY9g_NY|dM>OqY-fVa0~a>!+KZ6MxkbrQ<3d-VRss;xCFumu8}lfvrs z`^P1OQP^n)QjptJ@0;1<0a@u7a=%~6TdyEmJRZDmbj_u{@e9*?N~31(JO;gGgAj4D z(-d&F;p%ik&AN6z@O{nO!`mh(+is8kY={c<+1->tHMYGDQ27Bq?c!KR?tVDYk(Bc{ zk6|Z9>*tRCWGW~QB^ zdu}`=cjL#BPa?-_1H8~TH(nkojN_S^>7PfBJbKs?l&*y;WN;iHw`6(lR{>EC6WdqB zglwPqg=R|WYWN?{F+!lhmlGc$7ay*CuY>mo5ARp(0|{h8&SNjpKZ3ps7j08mI0)15 zbQOJYw7Y~MSCn=#H zR}U2>E*1N7Egd{m7m}fL;=_^-ABchDFRlzJsMJS;r@yXLGNIX$nFMLpMU$vI9J6x& zVi=(ELmWDU6rXuaJYW_mlxDGYINn%n?+pe`g1pEg$i{sR2Lby3UqZ+RUsX;&ZeXb1I3?x_t}BZdLz# z67GdWu{0c{xNxBym!h;~?P3`Z?DoWe=Tq+c9LX4T9A@SaL=@hPMFCqCQd`F0l4;)< z-1W}5`9S|*pDl}cY^=vrkqc1+qiKs7hr34<2Pt%wXv|G(--$1bWX!7;%`NiMoBmXi z>1)|H%Vzh1m2I#p>9{fCI7E23gJG)gxpQ*&>6gNAlP_j?q>v<9nS|lE*-+_j79Q~) z76lG%S;8+aG-dgT6Mw(E!R5M@^idAEQ0%cTs=r~3Nj=rnV(?`fU!Uz;9=mhL_TCPP zUmnfa#uB!y#(6A*2wgkLzjXS$O@eIdKyL3f-B5A3^3pY>ZcO%i9kKPAAld(AvQ54* zCy}Vb?eut#ZGk5D)V6DFzx$|caNK{1%E2ln1&_5;AdOCwUMBEp&veb}#j^erbgRFr zcvVFezIX2U9%jfBN7n7*Vv6Ev-%E<2e=#}=LV^52()TOZK)D&)7+29Jy)U#jXJgc3 zF8ul|4c=YJfNkB$^uQs+1S^x(n`Wo|akJ@swgIfqX8O3+(8U7RE?tTw9dcas8ImTI znTFwtMGY2t@l6dNkv7&QX+&3V0gBh|lRJ!mAvHXk9;Bk8DdMRlg^;G|XJSfDbeC9T zKvr_pc6X^FA6=*v49xxmgOFZ{TJKv&3xZrddJx1+d=aFKZ{OcPNT851=MPrAgl+UC zPJZ5*-orS)L6tZv|8&`0m$#?MO*}j`u-ee10f)NFWW_H4kjZ8Oa{x|*VO=yOW!;`u z0>&L8_|%p7q(OxS0Z~$!koDM7WQ|yyiiwN?cOcCpl z$+&X)lY-Fv5Dn0qCLLVND|HAC4%YC+!1`|~0y85>`~;`9`s7s4o(2kf^~qyEM%SI4 z$A7DzOOAwZum_)j0iZvr6gw*QHw(`7|c15~=e^%8E5} zq`Z4+hXD@pNLZ;pu1;<9U(cvNIg^=ijpFS6nz5H$GspF`}I z24%f?^85ipeOBO)(z|IJA%B4DaxkFX8cJiiRYX+ePp=g}gf0jm#Iu5>FiQPT`K&2P zQz*Cxpzc=wvo{$|*$-{r5IqgkPFvhZ{E?C`CEWWBc6(N^qt`Vz&H#uZn?I~z`fFCs zM|69*-x>2Ee|Wk?fUoLh6|Ie3pj8 z<4IPfJ+2LBOL< zdc2R)aeIbKjr?uetEXrhG^i{7r_Cqtf+q&Wd+Ko#%)aySb=b#o2)~^7{ek5)kRY_l zU)!U}o?E>)3Aj88f;{ZUePUVKnHk;ac6dgb50P4q@EdiYtfL-)j89evGy5EnmSt5%(YA$%gY7~5c5cmNsNkIIbax=e4Hq%Rab(x) z!H2wf|3hf-OFdxlYmYn!B6SViso@vRsb(lOMY+HTDP&r3_=(YDEoO>HJryDjTh}G`qvkjlbayqY{C0y;2R&w^sRUObe=Om>4CQ*nROE zK$yD?2i&d8b_HE+Dk|p8KYAAn z0>?}VBmFo#~}@GuE9h*-%dP6kOjXk9sBz z>dLoigXhYlnBq2Cj(J*6_0ZnQjM{cB-Ig`l;hVQ*BY%&U}8dC??HK2h<4?;r++kS-|U4HXkp z+fwBv>|qeK4x$u3JNL7Kygd4|4+k}}Eu^B6OFI)4R;Opdv?)=H#%qY^Lhb2spKWQZ z+u#KFV$X~(oy{k`VZh`zRR{c_m*b$d60N=a$)fju#P>hffH zxb=dBuL52ACh*gBEk^{jrL&V@H#gLSZ>oDiB5Lu0IFa{W2N%FFwdFm?#Od|dvP*!) zR{l24`dMo1i`Ii4Odfjp(}#UZ`(;h}cPBq$)2^#CLvVn-t)Dvs*c?0ErLbV_TRC*wgR`R4qX z8hD~2Z-A~;n) z?o*I4`dR!Vuidm)4SFv)xOaMZiyVEp(rJ8neU}IAIX2qN7vO(bAu((rVa*+h|N5y$ zLVQhy+f^iwnUL^2LzDNb_)|}~{S%&Unwf8QW-`bNC%-83K7Y+;-;5+aJf5W@JakUv z{&o0b880g2z5%Q>dMD$;{Lj;+vhPI*i6klM7JZ9v5Adqsxmuh4r@foT^Y{#T0^OH0 z{PVoSQu!%XLjdubv_P@l!ge76gve*Y2=!>8YdpWTt)Vt_&O%D9z~%drXHMVm=4U`Y zMt4u4xdxf(RANHi+x0o0izI}wZp#XD9IB2ZW-HrbZC$`pR{mRX8=?+Dc)Rx?DJL5m zGMVLydg)-->)M0g#-AvnwcM!nPJVQlAr-nhLRdUn%lTB-wf|A>Y9ILc{ZP-ke4NtF zdT}96gOu18sqXS!f~lo0XL3!{klt7MK}Z2y>8N z(-GXq_>6f{ab8UqU|oZ;@iV>^xf6$dx~$n>a74?(aUe;}RP1tGMaYG}7mhD4L)g1CyZj0W&pc*~qUqzfKFOcNPJ& z0mgIZ;GAE6w;D6wrQLrN*s<#v@uzoam;ph=) z6k<~mQS4Wa(&q)z+SX18tM&*&yqRYfRD+F5y}P(SK`V{{oU_f`7rR}{N2Y#s2-3-l z=6*)O0rwADqxw^mlAJLDFoAg7bGg8!VDVaNjW%&0@rim5h(&z*lu`D09h&zyE8jTr zs{r;`ORL!4$s_|RprAY?_{NL0rO0Bz)r_4#Mt+y`KL$N?ZLyX znE1z!J?eKo!ab%aD-j~}(sW+qA~Hy#=5-btygTqn?zAweRmeu4lH&G(EDArQ1ken_ z|Ect(xMPNW{{tzUlxDb|UKv+NJ$iBca8-RRhZA>D`i6%wHmn(l-%-$MbQexE=Y2uU z!RF2E!lN`gvq?Dg+Dsaw^NiB_&*w}$6t${#eE?rikryl)Vl8_~PEs9Z3gN^}5&J<2Ki%FLCoCVovvK?QGF(_b zCM!6j-_;^*cD1By&8(z1Xl>atiZ5{$fL!C}H=FlEvc0CtX)A=~!lsG>`(HZL2S|m4 z5*lDnms}V}8;mqt7QZ-N^Lh-sMf~WhF2%)lNMQW)8SJw?A0!mtlr@X>!Mh1jI=Ze! zk6~w zSiCO*BC7;_1&)1bCvpr^c^0A#A9rb5I2I_HM$}o^69pY>`RQG!&|O{RR_HqVXRjsG zoSoZYb$i=Mv@dpvl3>t$@$db&gewEGzw{DXz6-3P~dZ>ZFqr?wqp~%6KffW`le!kUxHu-%dh{ca;!E!6x89YP9`ZIWt78$Z_*&p)XsG=_ zF2J%eq~7)IWr9#FixL2iK~H{Z?aDeauYYf#98`DfZkrDQoR8dL-u0hS@=?I$ic6`? z_7G?mbN$yEo_JwK!l*$NzQaR#I!4k$;g3S`tBOyM!6VNM<|Kvptd=}*WE!H@Cr+_& z8k)}Cf1>9=%xToF1;ulSK^5P$AD9wkVUY%UgwH#Nq}H4R1778cRMfqeNa?|7blBNn zc1Z}!Q9tBKqyK2F+y5|jX(}wx@gocIoL~`xvH%X=Ox$728?_ zGuDYB>fAjbn#P4_^`Z#oH{ZpwPfW>F-t@r1PXTo_)BTU!KJd_DT)r=t{TR-2k@pNd z+13OaiJ&O+%mM98F+UR^;vpRzK}ztrf;Xgo-rmp)f--nO_6Sl@A|?QK?0xA$2>SMe z1-~+;me!?^Z~qihKdXai8MJnB@01&&M8xn#{0PV>0|?{!9Mms-kVEYdyWLx@Xb!}G zmlfR$qQE)tD0`}7oe(rPL6=F#A_KfJ4v&iX&k9*ooqq*ZgKz13OaXr5>>RN?0XP6%2YqaNE#4dk zc=-hoel%b6H8p*?4)I0eLET(0A&c@s4D{D+K?fOTj#GlVMt>7=3a(L8`7Ih?|U zd@U|(T>I`1{Y3k%?+x6XY#!f7C7Z<@9B8;2`y~B{Oe;rimbeuBJvEf;^8E+=C&nIE z4gD~yWrhYn^WBMT4{}(^z2fwo?uCI@y`d`C4O_R5yjE6rD551xzRfzzqLia(&$TxuU}KBTV9_GTl;!v zqS9`UxZIMwbO2H$dk{l?k-(13)OB9f@JX`Ab3kRsa<4ju11@Ym=j!pMf||%O=SJ3) zzgl)9d{#7hUMAQw(#@j3y^ar2O@kr-6OsdfMt1>8hkm72#!BM0!9g3ZEsK1Iyx>|| z6pZYLH9LQ7eEHt|;_WRA$Zk5AHpvDXG8JQZ|LUKI1Et-RKLBXOpK;RAmW+}EDjfvd zwUa{K-})Z{#^=t+hnJyxC+AuXiZ{*+qkdg`(-)mq#PkoML=BkgN3tPGeobnvs5J(I zQqDar9US@i-@UYH=yVNoH>HF2b|UubXAd2qkiUYEGwIElrY{Xj!@9daS&ncLG_;Cs zAAtelH>|p3yU{4t1By2x!@`%fj=Gw%#y|8=}MP=7Y`VJ7n zlsm0x#o!t(_D+_o+6Wa|;S-p&Fu9q<&y$;~ADLYcrXchXSBQ5O$A&i&$+y2n+tZ zIiOC~^aW2AFv`=QnoDBu`Q&6f^qVB`!+3sz{*R*bex&OES`n#-nAd)!Z``> z$8-;nu>bPQHT`w)$DwU;DvPF{m7`eUygu3+Z3o~QlBs#i7HEBz;hfJ8f1Ipz_I7by z^IO+q2P*7JNxUeQwuSAte;a)C3tYmQ`c;}2eP(7-|8!UW_S7x5!{rr&vmT_^S>PG*?#uY?p)?mpO44_y}TXP%OEzvGnkm3to5r38Z zYWk-<8wt)@Q~fIPrdPjcXr_#TNAzd5e#p9!o~Q2pm@PMgc~{V*JbU?N3LjaIPWwp* z-CAD96=}xa?~ZeX-{H&H2E!_zB|6mw@_=t^aQC_LiN6T?ll||zSw|4`fLxeALhpC8 z!KW?NWA>v>;Bl(V|C=3akcnw*x|#=pGJ)VS9^_7c54<$TN?yFk7(HqTZ+|GZviI^i zsdH898QSS@1d?#%4O?bD7r$A7nnJSW-C-@44JAkoJkGn;P$m<|S!wR%|Cw`?4+>?} zu);}l`Wyn<_~CvZouH;Fj0=U_<}%a*l@3hTZX673@2~jnC>YB1LJ&GpwGtbs ze_pm&U#_ZUXsvA6!WnRg7Pkf`D6=O1UXNJBYSZ?k$2kQZ+4oB#`~sv7G4$cx4+j)t zrTzT$FYiR=4Z_Nfzg3U`33G<)>jz6S?%HtH74ga1Y{nO&y_)nss~84;4vO~Z&}7iI zF)42J#OjM4H%Ba)FW&7)Ue?9$-xm3eGM`?(i}F;4_IZV-t>00BkpJ>xrx$3 zy+mb1Rx4$*+M0Hf-5%Jts^@Y~XrT!J5x0e89HviOwH~nc!O1lGtIV0(0NY`Cjysz1 zTs2g)a@hUa+cK+kwguxyblo@D6+kCA9K9F#k5T`!v6IuQ8su2t`tFPb;1qUx<|3j3 zb>Dhb>9AYl->fl8Em6O7^QD9RDZI3oKH1w#+1Ev^P9e+Uoz>1c5Tc^l_WsS(wQTil zY%1~Tf?U2g-G>oEWk0rcc+Tz50ngC+nLf?k7fGZ4k^(ChN|Rtk~=Li3`tNIoXNBS!bE6_orWH7U1S50bX;n>OZPLfSu6k zC5y6Z5QK{2sP2%g6mBW&8lK={D2!%E-7kFZmwKz48bx^a)!) z!hs~A3^MmJCyB@O;%{(pEjT03;Nv`lyfsfK!7VHQNs`owTL_rm0#*hWAifO(jO$cf z(hO({<8(&jHzJ}#LlXr`6Tnwy^xJ*`Am)z4ief{V^Po(f%2!$s5Q!9S_B-|9b6*{L zbR#>J3hw443shX`L8JrkM~&y1rY2p723;ErdGuIRm(rV$+#X%3RtO|EmEc@>s$U`T zFwXqpZa5py_NA#o-*9rfO4HA0VNw6`*)~w8)+82#8{@hnx$%%1AXxp^`OA?k)orD5 zt!DpB)#bc*eQs;soy`B1;&A&2j!bbsAD46X+m0kJ5J@h~!-e`eGCE3g!;^gjUTL~m zc=HWC_UmT*A6r}v@nyZI4RvcO3@$@AO-Osj9(aHCP(KD zJ#X;p+4_H%9G#QnE_HgGKlHS)cWeCNlm6xaT(KGc!1#ebld66va3T?YD}ZVU18h=F%uQ&#ihsf!%3 zWuVE)i9*#N6y^t!6&eum&2*qW!}5t1eW$(NL;Moo^5rX)Ah~>xz2fK`X&2x90RRK! z_AzhOz$JjOGDk-Ds=*8&}I(ooyIWOBZiG3g@{xWjX5V5lL$ zdG&2m_J5$vf2v=a6B+w39xYs{MD%G<2+LIcN77kiEA&Eet(+f))u)sjP?xWzmnWFF zb0sqUHQI>lJ#kT|;m~PRSynp~leoayI(%4Q@C^R5U-BPF$b%zLUI8wuUf7d#d8^MK z&odN7D}Ljtb(Xd&`Bc9bL(3bs9J+e2sw<^e%h%gYM6$J<3-pHNIb{8m$bntN9Atmn z?)vcd$2Y1oi!&_l(%`Q0b6dN&AR_oqvr#5(kyj^8 zKmPibEVoX100J?nKy@qqDAukk+fn(wHqDp`DF{8{1MhDL%{O{1)Q-HJZCBNJhPgnipOzDjz*>Ll zMPrF`H5JQ3V^PP=UAHeHKFErG^`6xCK@8yEjWUJgIg1NFw@19?_*4Nn7FpI76QN7- zENX?VJ^OOv|AF33o9&q%ua>_0Et7X!!*e2_3KS+lX>) zJJKwEdLuN6yhR}C+Bw2EBJ_vZ`aHzb%I+og^*ksI_vGD+|D7zmkQoq}{f>SpwC_co z5gP;=Ac_f~4*VDLrD#ZdBhVf!uzF%j@PSs=!CPG|c1tJF;!LNA;~E=fyF z3HmF@|Kn3ofQoazL8fEh?!Hs>>`YbA^Bh*D*wS{t|F=YjA#pbV`Xu1q0Zb%Z(&&2_Ls|hyg&E911Dbmt6YMw1V(vK_$f(H zTJVxzvV1oDOd|gsO{sO@-?u)uwXPC_bi!32RMx&xm!>&2;R~`)9m8V9SXyOCFno1j z&wrp+IIuySF9(_W^X@=@of1BHmByq8`t0wj#l#rb=|W`bN0(*aCHg)8<~~9gcj>bJ za#^ak5RilNdhhH*{o{AJS94zr8wnaH1?T`|bAOp9EWSBeT@kW5?O`k7^)@&Of?f}> zkD9C$>35Nf^rIdCdI_OD4w!2mkVOCB8WHCTsVE@MKi9+$Blpgw4Z5OCgP1dA7=ONe zqL|1|FomHZniP8mjW__;CdjS=q__$8Inree zejz(t5WQJEt=*mjp092BWyr9uYvA_k5qh9n-s2kYwPuGPQcO~~Cc5p5quxuhBnfj^ zbm$=U<;`qp^%?S>uT5Fk!iKgguxfWv0dkGd)$V|VGdY42q!1K;-S8co7%zSTpEaG3!t@N{(q`v3a|$Hq5{0;fS*3Bo_(q5R+Y2Lr(4vwvGjHl-J;y ztCb_`z!GNEuJuyRpK;eajff?6E)Xu zW4f=#>I@s08l`<-Ipz;3gT*-HVD) zPI%0deb$dpQr+RgHZ~j`Vu;q^VumIhu;*qSJ%8bxy>glo{Y3mju(mvZ+&LPcvfLTPji*Zrw7$?EUQgSF_yO(&e9mri%S+F;v1lISD`JrupMcC z*}q>f0b@od34oD)&t|I&%~*E-=dg3tWJ$@Vp0t`&wKu;waZp`Ctieu28@Yr!P*YsznLJn1OjWtYDmALzVl7BR<2x8j?p z_Hcvl)upMAB>)(vFzx)2VF}BC-T)yzpLL1k;#rt4lG^a1UM(=@DuC$eJ*l$8zP(xP z!}7K6Z3ulOB_`KmMN5`GMhn$^rhX3CYQpf>uxW4SGF~W!k6Xt}9Tbj?Ck6E}1!pY+ zIXTUPKea;EZ=aiNlYdY~WG!5c+a+++EOz>$$#e9&-gM(v+JAjls*|S*k+vObe8;ZT zcq19V@Wr2R8~5yY^UhMlRdrY7p4W|p%$X!zt*icmLvM9wM62uUIE_ED;BFmCmftc7 z5PY#p`y*0~D+s!zT8x(OXiQ z+O^xo78cmt9fGD1d276ew0m6gLW|0K*W;6Z)qMY{UW~MGj{v+2VFdT(3PpH&Bpc`_ z^Dvy+V{!HD47Qp%`%Hj#YJ~XU*7X7@Q~vW3!>b%@Q7776xlppsG2OrV8d01uLTB>e ziP^&z5eI8zzQ62R&lb-rk`0i~Q+Q%fEp$?yPb`dt>iQY|>FERH)T?iY-HDmj8LA+0 zHojxNPif0`fimV;QH{IOBJ-(|!9@bY5T3xPT{HT}SGOctn-$E5g%^7)uz&${7TW&T zb1rqPh?ni+MqrluH|U-3+40iCzEFeId0o$>sYcZ1dwG-2+fUQF#~Y(|g3rIbrZ9Z0 zO~?jWgS#YI@~im4UcXePCn(szmh$LFXshW!ZV>&)ct(Ff;3WYtv1=Xt++ge&uv!%o z5V>8PGfYvHbYi^Ma!~qSQq4g`a-}pT;XKN*K{8NkOaww%$H;y>IMgoDHbcu&evens z;)i%#JoS6c(83K&X1Hxf4C~bw$S-5xFS36oQ(04Ky2|r}#+W5-KO!(j9m+Af=jOk= zMxVa<)g+hc;T-%`%I5wFFnfdx4L7_c!5Q0P?-!9w2Kc8#1#9l*@ocexV-k_r7A$q3 z<@=up1dP8@@p1en`iV`V&ke~bt4Lbo6kee8%hKyvYF3#;a2!^%*q2PJ^z1OW6zaKW zAK1|Q)Hla(9;jr4cV^TdU6pxi_ANf8Nx_1i-j`#JS{-iuiNky zV{?Z}Ej48mZ3S~Jx=`2v_?n^OVAB%uCN@x8+K)@{ag6{M;pF2AI)Z(FOa2xabq_}k zL$y4_Hfu1n6?|__o*~B>9leri-0AYO`YNMx7-S&db^+-lPp%p_snyoTmiVXks~k1| zM70z-*mXbkTe1$Vidb5635ZY>xapPjQ(127lyq)y7pGAmFE?`i%D^-!R$#BKkLd)J zJO=7LIAr_!g5&CzMoVcDITPnzxaBCqL+KZur`~&9H=EAq1FhzzSJxW;I_#AkeZYR8Kj457&(zMK>5aKCr$v z_Am~3^i)Y<{vG|2h9DBv!K#5f)kNjwxY^zNbBkdDv*3zLgETK&&S9Hpp%TQ&h`yNP zE32V~H8lF3+zF$jAa^D$H=prYp8UHdh_EvbL2E#fHTnJ{j%}|3#b;a=Q{4S(xwyM5OId`1IXu0+rrSGXF+lY>RN@(f;u*?(APifB#y>wC zNzogBzEOJj*&QWUnK|!)CZVFCKw*Ew?GBsS_8Fdr@X12Vw>#nk^w~fZ^^+ZsbLryG zhXywem?it8Vz%xSosFC-wJ&$~F-X%}M149F-h8k`&5a`x15L0(+f$c+VX#L?WBksG zF4o+Rd=9SVI|}FPf=Bbqot$RVUxpjB3a7#+zLtpSwq!zp0LY4n2=AJPzYVnmS6Mu6 z9;pWysSVDZ8C-0L5Fj(x?ov)Sx(c4Mv-5E`yze3!lfs_WS zOuv`zuPJzuyJl3wG&Ut7{!F$&*ArKEC>!^Ol>csG+~gu!!#?K@1<#dWPX-zV5?tD- zGGu!RbMJR##s%Y5)~S_9ybq6V)$wVtyhlWA;`D^PbDU zO5BQ}@S*@JgCsnNY8N7P< z!OTR_3mh-iFBc1>CJd?4px?e&F2Qe-Q*xGZzL)TIyK4yQj~u8Z7gXE{IOy8Lrg0=i zt<72xlI=oHx`?x00>9YX8*9Nr%H^6ypH2(@>T?}8!Sz*eFGe`0{K3xl7iNgCO(-R4 zmpHMXH9yUPqF+y6$(ChORc~e|6Ev19x`gCFuPSt<_@>@UlE#oxpw4jEo!g##Za-LI z+)}HTegsHIs7wmAuU^*oqB%DOa%JC46O?r>Yy zLU#5`UsdgS;CZI57jE#xK$r1AzIS#q;;P{e-{&VK+^W`0MO}+0QPbaj^_O`=qGlCnd*Qg96WWT}<_NeH~I8wD#bPl=}8UR*T)%o>0Cjo=Jp zME80_*<@UlrMm3El{F)88?mqWJ~+929h0O8UX4+&ySL_W5^TZvkc<`NQ2Uyou9iOQ z7eLgq(q#N0gjm|;`8XeA?Y)49AP9qT>2m)KHaoMuY4+fqYe7zaCtYL}mSw3JvV!s) zbP~20f3jt!9UhjsX-zL$-EFO5;lYHSt8luV7^xJr?U*{pHSK-%#t<={R(|PI6Dq@j zw_69d5n72fo9H{Qysn+BrKJI}$w9FNVf*;A|s6YM){sRruw@7A*rEsU6J=$_pc zP-uPopd@2vCYLKSwa}L;`frS!@Jt8e+}1Hl_czy~LOs7ouJg-Jqkv!t6S$rG^w;<) za)|w~Na7ximIyKa%GF&W6n#rfP$8(4O-^8C+Gs_Np(Om3#HyM|8 zWGBux)~YvJGs-E%@mh6;)hc(BA|WOPzb0h*W0;ByCjtYqX)}uF9)4!)6N>e7mAMd{ ztL3^jA3{H46L{1|=+%Uaq4T}-k9U{S&z{n~`d3HXTgOTp)rXGleltl}6?>Gye&SNwLZHHChYlNgxnLAOAU}3(JyeCDq`<@A ziP|?3PqQ3~#bGo0D+>%_6ePPRGa)H-jZ>X_NPOSu&X@8IxAr;N_BZj2hiG6tV4B))KcRS6W|f1>v)E_%N#*ZFEF0T^|_mCQamcz~DqATF|=t0ot58PT|S zAA#U{YBl50BybK1nkjwA^{>slmpdAm*S zdb{6LTNmr(H2?M2aExserfXo`qXu6%i!m(+*Q(L&=jn@Y**#YfRtU4>vd^jmo~e2TS1gL-cIPYil+*w+m659R|#HhhQidlP8q3HNNxBRU@I+qN{kUf`Vg=shQ^OB2Ea_h{ zO~{0#)g$?>&KD2&{bU=i{c64sKXWhrDEv->$zJcX!PS~OX`iJiybsQWDntl3uV~k7 z9#0b_yJ!MKCkl@Plo~&2sP5TtN^@xe3ahGIh}?a)GOtZD_F(R|J)%$(c`oP6<_Szv~gHG~tb7}n4h$Q;yx80y<=!0)zJY}yUSk7K- zH?6ESLmC7m&x-7{19-d?PU-eUO}GkRMCn^#_D&wIF)H8NW)Quhe0f@@I>{AkpYA^i zKHNK);XoH7L5Q4s0>&4u{;9-?2Uwy~L~}co%@H6&t16$X4o>w=e*928Z~Xm~gX6eD zTAOMC$?L@_c+X~_Z|ILMJKG%Vs;c-tPt0D_1Ih!KgybsW^~-@8sh-t%fvc9DScMBg zv5meJeoFL{$y(AMWWGqewlL+C zaffBV`*dW&`ML@1pW5A+UYTWRfMlt21XD@%z7I#c0JraT(4|2N=~Ia_xpq;!qlnqU z)@A(?^~Rl4Y`0uk#joJZiR040L1ji{0CHVf&`YY!j)Y!uEVUccaqhDq{<`J}NvM<5 z08x<;B0N_%bS;B+px>VKsLuu#zS19-K}QKaJIBgFgWLGvdy1 zfE?X65S0Hz&d!I2oA`Q4CF@X;#IsxKjo@3Yz$ZQ~`PW9ISgepcK13a`EKkTqBEKEy zvtrEJR@!Bs-msMCU1XSv0LNibCNg9F@keC=NhsG`(YoG4l3bE?rGP)U^#BmtCjQxdUj=73F&C;J9c;OS3vsjQYvv!yK(+{MVr^ zpWSCy4iOg4!`4Q&z-%T#g~)N=Y-*~bd5DG7%pQ36*sbgKlj?NQYKgrP$kcs~ADJW& zX(Az1kgvm#uXpFo_eHb^f;nqWCefx*M)yrK+X%gt6pxM6#$BLAZkF!-evG!6h*~rJ z+4m-_PAyNVlD|!y`%#Yrbqic*D0f?;ywrPMj%7kcrY89>furk|_>%C@UNXo6p!4MG zz9Wwf@{M0YJDQmP?i~dZxKQhW9i)`;Uh|6|0e03z0-& z`4f3INVZ(Qeavooqxc&)z*% zOPB-1OVt-0SphzW`$b??Yj9|~S1-kY`9P^PN2Cl7gW^SCV#vFrfKeb4nwdS5XQwoH z*uBA`O2SQm>lX<&(&S~qLY1~URmkyi1Cg{3=~B2%aForp^Rr#Zno|^Na|%R1T3p^G zV`Y%r<-+A1115~;kKKO?KE5(<;A9@gsg0%3y9l6mFJgLLtoanYd#gthDD4*>*V*2? ze#g6Q^KEOFQOsi0T8@qF%)-wS$H~k!DQ@H_8`r-ftz)Z_o%HKU>^3uAPW_vcZUavw z@Vf!&Z_oZtPki@U{>64m*RLa6bQ81qjFpoDoO`>Z=w8R+r9Mjim#1`Q^CpRN?^S$2 zW#xsiUCQxiI1nRQsyr7;1x{~|K8OrayRyre#6>2$PAYHs+2*S)zIQw-qd<)P_T{{> z)c8A%M+%aS$cV5noJ>;V0g~=nvL1$)_lRfUgS%H>ZQ;#p9*OecA=%6yoN@u-q37}_ z3;*IXR~olX$p3Xl?FCc2R2Py^?TIISbh@E{fULCY@sYKj)p1~V55 zPQZar3|;Nq7KAivd0_n9!%VA{x%8?uG&D2E*;jX8fBAb5_c@JeEBQ>_bAlBe$&T-)cMQ~G-_O2^a4>7o zW;Zzw4{Q{~k4roIpYFW8B?_BA4+Fii(K|v7G^>C5WhU*>X&~)ez~H^#`Rovh34)`B zm?^TYqr<)U!Oi)1>@K%aL2~NZKk{zwkqJ&+1-Fzce=2gYu>tq=n_kv(wtl+@B6P86 z^{`Tjgk%SzweL_vn5=Ew5Ho0gt&Se`XBVPQp?9RkyDtlCOMQ5EnF?FGDS4Q`d$+g9 zYHVTW5+%>Xujm=RI;P7cMHu32DY!`HipbgwB|w^)w?EPh(uiW*35}pXXz2*~1?0WUGHbJ*F#Z)Zi>5Oa< ziPmKxfbKe|s=>b%x6fHfafQIQdy0DLfXp%9LzO|CT@ZE1>T+$e3nq36cBxMGr!(eHyrY$IECqZ{2%oQ zM0W5P^87+DA|hM=2kR^9CHV-sHr8x{PZf0_n`?15AA{HNn0xTPJ zmv38jMI5Ziy#?4y-=Rw8cy*ap^CLNwO!PcH-F)z^>K(C-Th^JS>L)SnB< zpFCE{2kE?jGUfF`Fbs4Ahc{jbUQfNpWX4o}_IU<_m@yi~F(w;^J! zH{$=Mxq%n;pFVq^PwIZ+wfMgIX4WhAT44A)qdg!Rj$wa&GP@~Yy0KyK$0bzG?!>TN2vu%lt~%$6 z!lYF_cbi3pMrz3@mCQ8-t5@L=g-ZN>*|GvA`Zl~@v9}`xAI7=vpF98LH#*!YGIjFH zb;;%IHPP@|n4X#ydd3iTu$rN-|gsxeDw6iLI4G!G;q{$)XJYw=z=JbVh zpsBvq++^4l-z=@m=E1yccP4(_2p7j$1+iDr2Op5i5yQ+ex#e)_KO9?}wRCE2faVx6 zOiLmE_7g9c4*^D!r;!42`IyG!-yi&jBjMTBR@peL%A(IsL|j!46;%2cTJy}vckQ9rpDDN;hR$MvpFpdZIBDgcQisy zU6EnB-j^Zc1kjkju;nDU5Kg9wK2v!8UKr5_jO^D=%Xl;|uW%MWkiAusy)}rFF zj8<=6#@H4CrVdJoofV<>i$`qAwPnksdBePKU~xkkT1IazW4?rQieK1E2pdrZy0u#Q z%?EKO?rMsF*qEcE#}4S+u(Jxfs+Cj|pcW!{ieXCsS$`~4Ss67H1R|ekQ#So>2gRE> z$`c-dyt&ad)Ceh;1AQiYb6gb0IWK2-9*BOSwep6W_IdFl% zoU1OBiCqY@&}PlRDhrnn79Oi(bRf+DHJ(KfpqgZEd4}rQbdeqkngTr|I8os5YcvaH zr3R`4E+h~?#Xl3?O*Tj&q0tjf$BUJV%DnZt;0c(EF<`qVG|RENTZsyzI?;hcO|CJj zZ#CTG&O~su!!B?yemhtzB1^wv<(@t3*=yK|=Y+g)+wIK2XN`iMH-ELjf z-E%>$n#K8CYfv-^nKV;@E`vF#eaa&I}0=HFiwB}S2mDp+nN{8Ov z@r7a&-&YWBg?j#VQTjo(7TFa0p2qH_dzpAn0@A}%?>|&Xy0v6$! za=%RK?=MC(A+GK~OW+HovGs)A6+{HM`u(xP`S)Fkk684qNLvioin?3CM@BaQ#3L!k50E-n%~kz(lx4V0j^-l4Td?2X;cj|CCDDbVtpv@CX1YL= zA`TJHSjJ~tFJ+6~5_$5i>I+*Dpd^E3tzD$GdqHIK zGcZV(W;~JJ*e^3POE1bmmceay&2A-Cl8QddL7S3vHm&b@w533y z3XRP@AP18*T6%am0#4mmfwYFAhojH{L?VdP;3A#bp05--fE)#LzB_*;Mq*!+x#TQ< zvgo!xH1zmp@8e?T-94-%pg)W9LXABFV{ukr1t#dYy!;!*s1>RL+O&F6yO&w&;6#a> z7Hf`(Yvf=8P_yTrJ)qHkE z*ILk-g7QakB@S#Lq&<%Q5HU;|fGmNVi|sqi2QlUX}pY0!7;j=@#>^X6$F2IN@(UhW>vMXF2SmR8C{knl!u{}6po>jD%L zV_(X9!{JVzWt}%e>ZzMfg-oDsU#%xHrtd`eQAR`jq8^x2%i+R1`^rL1oEk?sqbV!} z+rH1-^rAhMWI@6U4GiH?g9$z=Jy%+mx9H;d#=E-M)+-h$$j67-bb0O=j4%mPCg0_I zwsWZ@;Gyu>=R~V!6pyE@N_J1YF5c5)Y71ZnUKgARYSJY^u8!t(1pu1VYEzSFW#s`A;8qwz8P^iOVopq({b^1O8hx3(p_! zPQGAJBVx|+*rYwHMa3=w}cilS#6>B9l?e?Pt|U;T`TbFUdw|*1D`&RNHuWb51L& zGVkX>|G*qAYv1KS@B4&pvBdg%he8ASh70oV{{yF*^XjwhnwFB5P>sccZO8{;JAH7TTQ1Lv5j4ZaUBq)wSj<*q`D0KnEPGe)ZB# z!{Vxoh#MfwEH6NKUx7=RTMo&o$EjXnMYR!G*w$ZKc~MG2vUWP3m=x(G5VBY0X*wsX zY%vGx1Pz$F_th2)5iwC5a_wCxh5RJJEGss@uO3}YWxEf(A=?r_-s*+%+ZxjuK+aEL|O8zQv4U`nTQ)Z@tyA7O4 z76@=*L#GYI*Luso8V3qUkwg(*FDuH+TlBn4wgKZKr%@ADB^etBh4 zpFdo@7$e4uV>|CzsLZ`KzwU2+$#}+*r>IqxY|uxh4i{;5#{qPt*>Q>gKx8?_@_j!n zhuS|I<5=Wf+F?~3y1_V*>))8a+I9f&G3QWrd_*JjQ1d2VuP0luZU-j3MQ9T4U5@E` z7XLMlJhzm8rNCE)nCEJl;@#8JFD8C!h``^Z_R+^Uk|=-H{75ne0qw`oNZoJc`y$Ld zE>4Yt)zt12|b*J0*#&2O6lxg_v+oU&m!O@*4{oc0CR?Zfiz!^*xSb^+{?`P{^+0i&9i6X6tH|2W~IgH11wTT#p2={q=L4F7fS z9{tPe!~37<>Z?f%yl40dZD~LO=Kpd>LQgJ|FYQ0jVre^O|3sS%OD&G*ii*)o_``#+ z#z&K}4YrdkgJQw)_(ef)C=uIMJ87EU8RVOzmB=jBoS{BeR8S1%om4 znUbq2GYbJjz|x0`-m}bQs1R{(Ej0J_Bf``0P3V;?<1zF^`sn@pi<}OmthS zhRULFPK9U)WZ2h8MA%{2QSFe3#6y^yovJQrjbLO3JKz_}ixv{GbByrtIkJKyQ0{^Y zr2Q_$S52D_F;pzNY6J^(#*2%*+}!Ij^jwLq5u$&}rf2!sq(~KHO-b;gW1a>5S?0g~ zXnoPMO%!HMM*mZBZ&u62&m55M;?>X7zVWDjQriW*SUk3t2hRtkH+*#1*~U5Z%1p8s z8bGc2bGlswq4w~Pqo&kh5&tL&9N#M<9%a|(2+nL25<0U|xpP|r1a-~oW4UX;SM+8( zp{Hw+pblzS>k^ZADhQFiWZ9Ul%pW#1XU>ba75UV7-?#? zSkgz)h(2f&(aN5B|JPq^q9CHMy?7QN8F&*7XW54h?{=$fXJr`tw5Z@Vl6Z9d^6sk4 zOYtq|n=!&|K(zJ06H+gtHJGO9-Ld)Hg=gRV(MJ!pjp(K{w*uwZ-aNL~rUjJ5o#0v| z7_WhZKWM&rz#2?F`oVUr-8HiMlO7wSU^YcA|Apg@t}&Y$Ftr~c5Vq|{Y!SGf^yBoz zlQ%Ir`6kL=ea~=<-4nH7Zg5tIk!XnnF)qeDrO{2)U#})9(DAnMu9S|S-2!l(fnVo) zk=A8!G!;J;U9K>_jys`!FDc+jWvAvO8V|v%_a?cxbTIg#!we97l_{l-vt_7Tayz3> zV2534d^mAfvlQ8y&Sw{bUQrD5kJ{s9Y2>Fb-lUEcwc9Dk3iX! zFop~t>^$`OGuaUxBA#fV2`PAgujtFf!bGBj>{BV|+%qiB(K2S;occKB=DPTethBLh zF`osa>CA_5RkL(vf~d3jxU))z=1d{t=ZL4bOH|WjX5Y~PM%_z~(GO;)AM?mG&hO5e z`k1b}QV5WZDo}N9-K$$OmA41<=s8idFo`QLb<3LJE`&o6ML+7qX!38w17@w5Qla0K zCKS&=v_vq$_dSiaT!zh8=@_jisyYdKH-ld+m@hM_M%F;BGZ}YFRUeNOkp|3DqAi(3iZcjI_tYg-;jvUk}dtHF*OJ_OAwXR|ApccoD{ZK~%d<#oaP zRH(tY;3+l|)jk}NbYD6+t2u7JlOl!Ng+dmY5Afu#SX0kK%4QF}7`NHVivlU^M^b#B z%zS!AGQu}oRU)vg!JL08|eG~{lswa2LM zRm#f!$ewo&FWFcVfW80BKVRz?BltKrOtCkcDL4DXXC9v-3Bh`Eibxi1Dt_%(hVTG9 z&BETXiKz?p0Lym7F!Me6znfh%WBb3|SW$xAEyX0NnAhuLjyCryL>Sc+8fr#h?Da7WvrB*Kdi_4q5zTV3Q0-1$7TV`u}%hp@10rQS-u$(J=vKsX2ZCnkn?Z<9H-xfA)zTQ3h zYRXx&LIO}Am2u3KN8q>1gZHQJpFen-Y5rLnN?Epy(%Zyi&Wt=ia1z)ATaf3#D`?BB zHZRA%C0l4VixZd}4NaU5&N35PYLxPv>Jn{ZJokwK+K)y&NjTf4`Gp5zK)@-0MG=6} z?_9teil)Z{4QYp(%`O1E(7qJ>k&pOqLjUmZKoM=1#>OIA!o6BH#LVy}W@?kO76>?4 zA9CwH5#d0GhiMDRq=oy_8gP)9znswtQtey6N!<(WDl8v2JQ?Co-}bxBT6vTVa>58ls6t~T768%N%8e0|p~ z!l++sUfh`J7_8avXiI=nO7&c34FaE3`;tk@T1`gwZZcU-KgG2X=Lh9GanDqKZ`E_8Xq&jR#p1C}5ZyU0RwiMET5)6QttwnE>!%iwySG-#q6km1 zae48zPU)#&ai?2Y%K&npD|A>tYr-?0K`i5B^-U5P<8_0vN-<{97F5WI8sI$hEVFTB zReyl?Tp1(ucFG^_7ca4c;-y#@xZ@$<;3yXh425av`k$rr30YGgarM-m$)k#<@zs|B z(qz=a)F%7ZC2BC|%aCwaX>Fyj+aHqLa{4z11d2=2c12#6V$4v(#k>Uozi!LRNr=ad z!t!Ov@z2uoYOL;Zj0Y_w5yJ>nXNtvZ#n&ey*T3a0;B+^9AJBb{NB9OJlIGDIPn?fa6!JcH zEx8iLGC`*nwof)kMpkwrhi_@Sc;Xy&)`0rkkJrb*|9e5fdNhkVG zWoVnF=~l*)tA5H))JWt)K?|t62i{Y9own=WWY$kn?G6Lx=fCPx78iC^?7#CGfXmjM(`Bb}P_v}EHfxpGD&w>Qqho0#~GCNt*x$R=> zP7m?Is>+zefoH7)<(w;&vh=pj8V8s7!O(aR6$Xi4)oK?Zu`g%szy|ZJc~K!EG;q{K zK#4r?A4R;LUun93eTwr(3aQ)5mzE>vLeyMci{ps8ah>G&J%_&V894RqyoE_s-*lGPuIpX#$S!E_ir|(^rKi>Qqr5oDL;lwu)u`kD~LAhx&iu_;I+BNGLK+C>fb$ z@5(GkW|AGU&vwSyW!)K>31ys-m8{5&Gvdt1=FE(oaSnIBzt8V)4-TLA`~7*p->>oX zzKZ$eu@IRa-fEI_qw#r5wr-gcLkfDZI3%Vh5czWSLXH$RvoidwVT$2kh|6tz&E2+z zzd`P7YRYi&jW_0|1U43bl|t+Mq;ys|Gilt%;~BoXQHe*cJn@T}q$Hn~gJMMgh7uwE z&$xS@&UNi6Djhp%%AQE_K4r3pSRCZ!rK0zS>JbXpfotRz85P@G8Fjnc<|Whn;T<@U zs@LT?zx~F)gp1q#?h0edTRd#&Hu;n4U(i`Stm%wwcam&}|A0da;VQxZ(MeBb-tR%? zaWP|isKl^>+3Z>UBC+Aii)p|BLN(>%hbyb@7f*z;keTtYxHD9Jxo)E=QSe-4&?TGI z;t{IKr+ee5pm09fX%6YQBuH zD4HB}?dPEcO=JOH4hv!LKdJ@}2hl*(kofmWQd-TE{)3$k-m{Rw>423_$an?+72feG zff*Hpr*Jx=NX^vN#6$~}R(i<&h+MOLMplJd$Mvuj&7okaahExDj$ z-=|1rUIsxjjH=(i&Utbnb`4FSD~@#{?k|JoCJ2WdmpRB!+z}s9FM)Hx{@cKTfUA_8 zZZJ4V9sU11VpB->zZ)a$Ee}&B1*DP9sl3O*zpat_96H%;u#TZiAx z(kjf!?jnb#;k0kKduMVQ!QlI&lb=x6e`wuV*hNMED-Jg_?DxBuIE(@xomHvkZ zf7Sc21?;>Ok+XgKRs+IwD)}-<^{HKN+ej*-1(R) z^&jYS$HK*ni^nTPX-{hpEa+nVDNAhrTtxYcbgYqRnT6Ox;V`*}HcQVNYvnR}H*4(3j1ji_E`rhEVRrg9=u&1E9y`Zq8-jGEAI z)3_is@!AUiYmNy}G%KC8_V@n5WpjE~!;#FPh2#sitw-Ksf$aSC`sEexRUZb5unCUx z{PZHcf~mmXen;33e^05=^qH9aMnV=w{LG$Ftny~^boqD9Bb20io4s!v=v(+KTmfWV z-`0Miw4Ub#v*$(zis&WSUYA+x9g(Pi9U_VODZz2jdYI^~O1~X>*O)4q^Z&Y*khY!v z6)#OX0D;a}@%K4~ZDbYucE@g;J{K8ycxrMqel*>o?i`N5doIV%9R%-UKM{}Ege|~P zP4Mxx6_m}I$P;(hx(nqg$GOBqT$M1XF?>a}uBQ)o1xQf|k3DKcQC_z5q(6{MiCz^7 zNx8rkJHB952-dyn;3B1wd!VK)cac8&!hGYtS2HIGa$aB)N~=ySd@v8DW^zLwSAcsL zgn`NIqn#=u#P&~eB01|S@G<*Q5sSr^ysJBj8!AStNPFY{-E>~(2PZFEi28?I?Dl}0`Y>6`@2I-=;VX^d!CgdE*#nt|l(Ywj zb+*?Z%9DSbo2~y#dN`}fN*c5#IA(Kpzb;*D{k_~fCG$6q^{Mf}6&eQMXbV2NxH=eA zE_Y}z&;8U*J;viRsBLM+rEd<4KNt!ck}8QAK(7orMY?$Lff<^r%Ddjs5{ zojt9M97+VqK!@a0tSt|#69|juQ7x-3!nNJYfB61bIc+(Ah#;+wSKZP%rS)91R=gM; zM58T!D`<}b5=|8dI>>ee>Bh_w6uS$5A3_?haOQ7WfzKa9No@*kfqYMR^Y^l**bb#A zOa%pqe-ZmN7Q0GRtx!wg9~#v=+mc-5@QnW+)-V;B9?(WDZ1**J9|VS~Te5yC{N5_S z++g=n!CMn)F_7)Yq(+jvOzK|#ET`g-uSTEjI@#{w2EFp8d8-+{#Ma*1idotTCtL21 ziSy3wUj6%7Ru#wgx4lvAKTy2WQ{-NpinYZy<~uN#`S(j6_pF|yG_(g`Pi;}cQnE1C zR~)m>Mzz`KP)(O`hF9GvT*PdySuK%CWEbi};$0u$-zEN@vO>+_Y#IrXEmf!fuZ>k#3#q{(eBQ*7Fow=}b@F;4qv(gml*j zShJ3+G9Me|hLOOV{?(^F@OLeo0fP~VZ~&>h*xjR>n%JOp>+5@mF_mr-%Q>86{ZoZ6 zZMpGh-;{2~6!XlYZU+a8+{{Z5cT`$#s>)mFC#g-sqPbW_k!6pc6a1I#jU9n_^&Ksw zftOY>QZ!64@(H2-tYq{@wp2I2D`3L--S(D}-|nUw-(EMr_{Y?mq}{42o{@Ru=5>~I z%~O9#+^^P{v-6zOTzqud1ZDlE*6gPv4*!6@_rm!j0)+m{4*aMlEW&*G`rYnPEo;lE z@DM)Aw|1w+#4_4U;@3bY^AM3gE)I9YtU?->&8g)fo>sDElW#ujiSlj0W`nNW`&lF5 zH`C2a7-1fNxG$H>=BCsvTmd!IVxzBJj~EW3zR{J;2s)#BUUdJPjEa?i+8Iz4)pq8a zaCb|+ANxxY`ZU-`DF$@U0|Uqb!0XRaOXJ3!Y4tFlh^S5BgG)2YU#LuJB@@ZtO2+J# zO?Fxek^%Wq?q8Xvmw7~Uw~yhv(oB($c=e73gym*JKWy0 zog6-2(fYZ_9AZwOLBuTFKN`F(IBoNU)0QUm-}9fP+qpIf$0kXSkPh9`Hyv9M*!mar zH`pgKco`Z(DFBf~7owMHEHj@y90Z1D(zWY#+kVo>DSqaRj`(SJ=ebAG{H*lHiN%5F z6B_PT9+mXb*?AaS)E}|m(#&^Zx3$R%D@`pC;8)W8-+P&Wy^eMF!-?54=jab@uL>I! zk;2>ZdbfhHZXKED&D^jB)$uda?gs&qmq$*+OxI}a{{`D8D~secgo_r4$uysa?@3Pm zaK*Wb%8XjoK%FwzECWP(nSlCo8dm^0>NS7vGdGbkSN^`q0N&2Qv#^jJYh{|9oYfly zhV#q^|DI7x?rt*-@0RBdB!53D@W1@(BwZ24%kw=A(;BCl#Y(YNe~s-$7Z0w-sS#W zt@GbF=AaBLdj9B|G?~AB1YwtD!fxYTOa2uI!k1y|t-@i>zX`eh*RGy;Lm(>YEb0Qx zSH~`2%dG(7R*-{==Bi=)G``Gfqj1nqzWlkx&PW=zI6#f#5Wp~?X_YfXx4oqI9yPwk6D?PO&mCHE>!rq zvPJs~1uQ0WLgTCCdr}(txkV@MCdMt^{!T+yr&O$ErVv@FjOzqCP(JXX#4|nJLG`wh z_%EL=BZ2tD!EeA1#;0$cPLxUAv=-#pZUh~j5qdyR)}C=eTW79INl%rY`2+3-znnSu zlrfouwNC3SKWv*K9BXSdXIUpSfG-$^Ko-%u4(<$Iyz)m zp-okeTP2s+^P>5^pnkbb#04V0Y&B@-*WfIYyA~Tp{o65811(+n7%Hkm8%%|@0`7}V zdi~L|=rbl^CUjJ?Fj_Fqnd-a8t0kK}rnZv`fBAb++9$?E6!Ry{h zZWkYGeQ7v2xTdh=5D|j~*WCSq`6*mgCC?#8RKb#o)m#(HS02RjnvniJN^R=o*dkF` z?OojrY?{AoKIULIySlp63-6dESJWjwb{8^p_Y4sJ%)E zQfzZHjFjh1xnTWE*1Sf7N&lXbJ@~#HZkPd`=*{lD$#!-bNww^g$ygO$ zwcNLjWgBrGF8?acI8P@Fr-)FS_+0|Tf{fkS`0=sTE365LH}ye%^2b}bX2xwS`DLS; zEJMr(#W=1b_J0;PzSJu2t$q*3aB6BH?Szw)_!SMk!z>xj{mv$ePfDm)6K%p&CgVO8 zv7TBB^}UA3uY4HZ3E;kJ_##X#+>42)>vIM^sjOEXh`W8_n|%-!)4SL*yBSy|Mr3(7 zp6DR%h6KO_wW4F?3_={L#g22f*R{}!SSuu>@Mk?Kf$KU#(L5Lr;6003(|cntJCi$D z8|~T{z?Fs@v1^fAI&ixmXKd!oS~iP@xfF7RWP z1}^Gp54yc;`aZRe=_uL2({|%a??{S#t%X%r+oJL<)~dw@7G|{zsmwzPd4rFz7N%+e z<6ryOrY>Ii03-+((A*dQ637ViEa9k37bp4WdR?lNgk%hU#1{}PUp)Z~6d4^F2j;$3 zA5|F_)77r&_;{hO5n{(RRZss1isT6(-)pDe?Wg=K!`j?I?pOEq?)Ol- zPG95Sp~zP;QAcF0v9_iC{N1Z7;+I2I$3nO=BV}pk?M=UK=Jz_ zU(02GIzW_F9B6}?hXU6#_hBm!2UtXJy-swnO-wsQ75oR_IPu$7L;L5;#n`Ajd4Erg z^v=snj0VlSKD)_7R52vOd!25#xCN}lQ+J$nM~)S7#8lo=b3Pq7zsIzd5TeW)`fIl(*?K1cY!a`JiH=e(U zd~E^lWo=1TNe5J(_)BwV>(Z0Ye@nHKP99FxddzX{hqhbTGX9X?U{l&*yyuKKivBk# z7y?h$2s1Z~N05AsaR0>SFTP#}L~$FnJ>mPf6w2gr@h>f*>LpLw7YkM}<)3?3Ym8!+ zGUTzAi44A2jE7L0(Edd>68TNcD?vIMBRAubsh<}z7jU2a1s}Cf8{FY)BTd7vsbPD zsh00-O{QOZmx8?;r0BdPM-XNUdZI0}VRKBnBoX2)jP#L&z(Wsqfs39+5%jjcMUf>e zN9iE}+Tl2*D?}`JiR}}pXSMXxBE5@o;kK=blK$dv?}w5w0T>W=f8f3jIku%jXP!~ zT6hH<_n55(-X$ zm}_D`^1Ax#R_SF|MIV&6`#6^$S7o5nE`+us(4sSSfgL*oB;wiR9A>AP3{-Cs;X&(- z!#+cSjo6UErIjLbao^U788?z{_QkUomR_Wk(_{NG7yq-}qOt(F$Ia&NApEwskz%eR zWF4PS=uda4$$w%YmG8bJh`9fWib}+Psur4Uu}Jd&3L-e=y_MSj31U+LbXcR-ZEH=a%wu_F8{3s zDNqJ9{_KL@=YjY}&%sKKzUJF%cre?W4}$H-<&}}%5aif5Dw!%tbOCD@FqSdXMsXWn zr!X5AsaEbE2rdKuE|rI$bzCt|$^SC@J1^GffZvS43@2M^2kaFVVLi8^}w%9l_vnKIqVf#8IH>)+pJV93A@IR;}M9k2mgVxB2vOZ1()00fd9ZsnI+rv z%lNTM0Ak6ev3ePP%&ll}=^fo|luWD=e5~Sov>+Ea@q$fwnMx3Fpylg++3oAYk40(R z?G4Aiog)|iRW4Ui@7zWK5w0r?j>%jMhng_<_0Iwke}4curAH1+h@+Bg1$!4_ z@8gj;T`ADUSU5OsGN{B4$MJxIj~M%m8>Bc>K`Ck2gI#SddjQgq2N-4LJrBo{85rPW z;deWE!MJ7h84$irRoHHoYId<+ylfYUHC+RpLC2Dhc!@>Z*kW>R+K=^<&(PHlOB-R=qUq1ua7EplYfm@Y&87pgR>K?rwhnc?rNiJ780q;r$HvR|X8^P!fd`DC&q^>)VTuyZjP(_XCfr>&Zd3R~x%$SsOhS9y~sMTPTj~ zZIhm0dA*oC{lea;wNdzyw+yPe8dY|&Pl1(n{Re6(96Rzo*kR*By)d_*^Cea~3-Cjw zDC^ityEjbh8iw!5HHD1x!J)1ev{xnXgmcp=oQGZw)r67^l^C=L>|31vOKQV(OeKoO zifw>Y;*&CxmsPf&SSAm)HBe(6$+eFNmp(YIN_&qMy`<8~sO72asi+$%C3ofMs4S$i zi1yWAcrF7JSSr;*eqytsf(76jVgW>&$IDBOj7FeugE%@sDci8uv+122hWgCSwkO8+ zG^>p1*#*P?0&dM#h2&=pENybVONw^6qdL$}m3Fk#e6{UVkT{p5CW~)O~b6=ReS(bKeCI!oX0WOh0$`ugW)k3nwgu5tzArw;B-{to+58R{*Y3_R8lWtM*{R~T3~Oh;)cSHQ`S$$>k}HoT zii@UJhl8MEa%cWWWTCJ>ZaUOL>gUs7?qI5mKvvK}KZk+-93_ZcR$3UgC?0U$?u$Se zUkSL<`&xUBs<8|_TdzYbHF8Pt@5VzVHk3waR%Nf80OY1%WBqd}Iuoj1I65o%f{oLf zL#DLR^S#a9Hh_OO8tUoTzBWL}YvyMKO$vR(rv@-pDV`bmFMZ;Ebiwn!M6=($aE%>U zS@B~z9(RT(4GI%Q{8bj-gK+7ATfK`PAdp5~!y9DL@bbi(6C&0Ep6YF$!Y+U?y74kU zy-<7K+sqF{#Tg@aJV1z=WsN~YqUs|$xCqa90u5vfW~96nR^BTjga3hZ8C3z?l zJWQVV462K`TAeB}UpE@sF6{IxOihQQpJ(x+JSIEY-6*NDV;k!NN@tP-B}+-qhrZj= z2+2L_>o^*cWvp`wGmHhEw;aYpDHg9P7994flse|fdv10hZpyY}6M@V%n{Q*C03@my z+fUq`4lflAG|ulq$M3drXRe+S0j&6OSUu4*%9k!`c`rTC(cw*@rcgLFOKufn-xYo9 z$4}2kK32iel8H@9wfF+Tcnrbk@-inzEzD7^z*it#m<9-{XdBy2cdlM-I-B%N7>jGY z$%PcNc=9N!bEar2;ib0pctJY?jpMfAw|pg>yRKo3+L#@mY1w_KvE`rg-Ho|yA(thC zTf17mJs@LmU310+SjB6Oh*f`;p}Ki9GT(1rucN(R-$&oH1QMyZM@kq9WA#vqFO`(K zrhtdAZ-pa5g+B~krx0NuQX%a4Mh_9$bAH{YH1DueA6JidbH}(vo~jSj&_t^Epz^I; z=al&H!kRp`Qt9j$ys}XHeBF0nF$0bXBIAR$y#Rn^^4T|c3BM>ViPf~(shOP1m|mhY$dfe_9Yv8ls#LBx6roC%?>fR(N|c&( zC~B*Ufrepj!StX(h4fVFqB^Qg8K6K-7vbVR=a$q~zypw;ORK2lucYt(PJwbLOGwUw z=gydPK|`{pKUcAL6?XpsQ(rY*cGo}QH%BJ;o4p`mQ^Z{NEju2gAy)!n_+xa)l1Ne2 z2T;6Dq2GnPuP>Mk2m7Q=ZRI$-dXy{}V@-OO;D23>2UHI7-Gaye3}C-`SEJWv!X-X7 zIlO#B4_Nk;RnxWB71C;SuQ5ge-b4DiL+-9T^Hex$`iNMXW9H2s$>o4gWEu#UjI&d_ zBFp8zg~n9!4Z;&Wy?-uIYj^H>DT^3p6Ay9R|ABr0EER=)ul7oi;r%)ng_@`K;M{zK zLy}js5r;u5P$pp^I_p!f>BSgqgG|yOU5V)YEB$}66@9`6qXQb`12{5^lI~&$y00^L z>>iz&5IQ8&GDHp{#vfqdt05I5RSLI2mFMHBIs)(x>@v)d?=ICr$L`|xbEiZMyK+ms zE1t%QeOK*Tdit4mCqP%@VQ9?Q?mc_*y~h52p9Y{h^!05;p^))4q+zp&SJvH*%;d+T z7?I}t*?ZP=kKf9j`JK_n=Yt<$nu)7<^pm0;D7}_9GD(=g_Ze7Zc9Qo@RU&cg$C`%D zY_Iypw$*Xz6M>k*rB9o3kfUk|f{T)!EWb;trUClB|F*R}|46j2(jhEnCh*Ve6m`7H z54n{O1P^U@CHVlZ=#1uYt|OX6U+xOsQH~--2}Ws@ygWrDl{BhKHhLoh!g%0H)bMPB zX3L5a+c|Hb*Iba>v+L)Jq&*;s^{B_AEwrsJ5PO=T-g$ouOXIupL-gafJ^PO$7rQ)<_Qx$1 zhATp84;nvQw`ETTslk()wp+LZ!F)g5nqJTId(Hw3%*6G&Z`MpCWcM5IoF~Jk_OK5aq6gMWeD;=&?{Q1gQI`mUh>Z>`nV;fQ|9}X%A7aZHeS*%rTWU;#yy4j!kVY8Hb4|A= za>FHkvqe*;X7kM#?M_Sh34GcfgMY@UMyoGBfX_v&8h~?GkC%?g<*I2ZjnN#YTZu&S z8}Cplt*1Qt3XY#0>{^ew@)Sov)585pg=_u8fbh>?{3B zyE{=_{~opTo}k(3-L%9#;h*+3T&DAH6I*pk@}*&|R3{}2DY5iaN;d9&@~gfN!-EV0 zxP0-orFlvv;|Go7`IVs1{(Xo=3n_EC^7((Dp4u+QuM>IwD#Hx-46n&}aVo7c=Ub(3 zO<6JQ6VfvlRK=&*Re#;uhyJ;{i~mM2&A4{z3a1^&Cng57+h2f0{))t~>@i>LS|&|% zT|hRKMb-(KNv4Pg*BdZdRw1h6QE41e%9?f?M@myHexF`lQ|U_PE1S6j&j+rcl*}5f zg);3|WiAgdBHuu^Uaa#BPlyRBxH(#){SE5 zTpX-=s8^)2HC*9s65Y*6`0O}a-u~0g3f71#T=pO@5q@7=1=j#g`Kupp#3b}~zcJY0 z_URxVRZSV>b}#>CDT{Z|6#LN#Mq`xhXG&rWp@YLiSKXXZgF32!7mEn4~j>QFFmNwE_uFSx68iO$sH>E@jUL1ij$ZC z(nd!qR9OTw(xCF8E)Pm$|7jS0R1Lcu^YK@mXKW9Wq~lKgwFV;B$wALF4kD1ASI4<$ zH#uXuVavNOom_=DjnKw4Tw!dtuwZJ(#yH&59WZz<0^QY?d^&!Q6x*YAr|{p%zLtwi zU}OiLR&Hw;er8(RSZBjlxzxd%G+MSrG6|@uy=SWDoW(uQ0v#L&7JetIy14kL7Vvoo zz46q}L6x>8gS}UUwcWQ4>S6ARMH>)!D&NKS>-YAA(S=oQ?@2#0Kd_VOdDA(F-Tr`elvV8-Z=x8&otsuI`o;3_sBjEX zd8_yDjnjlG_0G;cWLI+0Wo!yNaR(?uC@*W_yGL3ANnCYymYaKt#KAH#m`&lEIg_>Z zSfyiLqng%TE9nvRSnePX_3m0-uiTdorAf3w(W4iMsWbJt-tCiE;OMmRQ@bi{IYn7- zMQ_RHZk&mMA|v+7+C1;6jCRi&v>iM3BUtV8p8}8m$9l#qAd~%Ja<7P?+ zxKXbBd7#g8+vwJM$Yh}tnNGWEa+C(|F;tK?o&q#Q1A3-y1UOj@KU?!feh8+VraL)x z&ojlJvYU)1+%32mm_RR16sg45Qel@|zhul(?)=fH&fdxs=HTzTtaX34hyPLbGwzT3 zXVJU)%fl+I2$RB3t+rLy|E@26MyK@6=E6HFey8*kF-{3ffxZ`bu83!zx4PS6ZTL_UF6$wpsc) zh0k8sDEjtMn!4aAFQ<`cY=cxCtNssU z<2;IIR`@d=bc{>yfMZ2_LoD3i?*oc9_z3-o^I5Gb-b{oERH<`-1?sfkF z`GC1@|G{YS8@=%Rhp1T;Ri$WZyPzUUlTnrWDoDV7)kYnNm=wF?_!%FGoU7{1H||LK zp7fRV#D0Jd5*@gxdIL{@QEKuBWcw`wcnoBh>n*XIQ3rbfpg!d1!Sp+I2U+*X+mWi) zmAWZiYCk2N6n$!#)-?5lIE0azfQI;9Y_SQBqx$ZnZIi%=oWPRq0d)%ThKZ|}I%ZU( zkuie*E_FxMgtsyc9v9j6dP&_Bupi$Vi`b+=g_&U44+tYh0SNmIULFX??r{;8!*Ziq zUs}EIQhy^D60s1$IQNp5c^oy3t$)xT%Nw&j$Yg0mxA>li4nDqjMz7vP9msWf{7>!r zUgt0s@j(mWux5i@uA}F%RLfg1IA!};S7sMuH(Fio`srJUs+c^80X~zSKp9#L3>Cg^ z%)tEdhsw8=Pu_tzjSe^(Qx8}czT^uTrfknPDF1!mAh|>rbCZ`$S^{jJ%ocX{v9X5V z-~iP3pmdH-!#vj>B{!_BXlSGQ?BW(FWAP{Q>d`Zg(Z^Qq?`;aW%HCa?nO(-AX2)|PE%gCkA> ztl3RYSZeF%P`X=YkrI3Ey8?G*W9LtY8T2mLa0^=sn)E}qPP{V;U9C?0Rc$s>^wCNe zCJDZuGD$E_A8c59k59pJ)dOXE381}VO0MrV=psGsZbBh&*4F;2sSILJqllE{NHAqi zy}_zXW(x58A1qx{JU7jJJ-v2!ANMwSpVx4bU%B}5?4AEWX38_caX#c8e`&45 zMr8?=bOX^q=sUoJee*%>ud0OFb|0i~(=k7^pyEpL;-|TXcinu@_mGcXuBgau29;5l z%r|fUaaD1=AwM;KoEn!fC}hHkxXe3Phzx?+57WuBSu70y2fDa!F7EMyL7P>oJQdQX z2>l)mKXd#(@)@ST2n@CIDy;Jz_gS^2tJ8ml7!Ez-zhkDqO=CYCxOu_5x$(eaD@+<* z2>6!nLBE&0k7)2YBgCInCr$a3e3^MJdC<)}<25I0&yH2fA#lqMp1=4w2#J$fB@Du? zhRt*jpRWF#sF&d-&^80*X}y=^t?~`c3V(n3rDu?62rE_zUr(?#8to!(l2pegbsafSc#Fx6-OV zn5sr|^oW(JK|*fO4+3%+k27&E#FTNnGW$}Va99Xk%lq}k47~X!3K*bkYK+hpPIK;ZZ}>QOQwdj< zd1A`e8C-XCG2Na!2G3o1@xoZ;8Oi>8?;#g*5Uj@H1o2+lznR{@WK3){w3zRfAD*^U zIh*L zSc6ab*;^Kyn}|^Qo^7$Axu1~4E^v|@#E7U-AB-U9+i4^li{T(q1;^5 zarDDQ=ClI~K~eoh-n_iom?tegQx)H}H_UN%_EDH~`KvlV$3*8|zCt%gSbIbk+Ptec zbmxzymtb1nHGfkO82hMAFX9G_YHsih@TL6S34?l>?PiYkwf`)aL3gj?55AmUSr?}? zT)eRJsHtlQ$iUBW`52h(%NzSaT>0<8$#jya z`KFbEGXJkv~w(W7jLF9F#L*DVfqEJJlX*sx27yj$ZPyLzAP}V=#oac+vSP3 zMu(t4ZupS5*UPyl?1yIHfUO8r2lDvuBzgNzw{A-6m5k@GeIh7Swb-)LILR{Pmz-QR zX2AJd_4I*{LYa!OM$hGCwIcxjF4em1)5p=jgfRZ7F02KRwC_DDpq7HbTuyMjPkC~E zXS6U@p__6Wxk&{KXK0U!CC!Cw8f1PkgttZ|fwUoC@QlvPyVNZOr~jk$Uoz9eznOHs zYr)sN6`5S#Y~@}DZMf6K%Xi`TJ&iQ>R`b3rG@oiU*0bZG!DuXZyRe5BnbE%r_5-Ax zAY~I$+=4GVIx~B?q78}>gD@5W=-wZSW;)-}mu!xJ3-w7eW6g{%?ew4-dF-nno8auR zI33NMq;9D0wvnQ@Poh1cif5uV;K~S87r5Mvg77qP$AF|cHGf|n=R!*E2;V(T-cj0r z6pYqQzQzc9LjKWI%mEf0M|Fj(bdX-I$Q@H4{VD1H?x)zN34Q`G=3|y${o4BasB;#T zwecTl!gWnG8u1?C6eo74xix-FFpjRD5hoc3az6$@5j~*@>Yc;%uV1K)@-yF@R7Vf( zFJP~o`a6x=xEvbkWGf=-oE-NkL4XfxRXzo8+X(W~#-pao6?_q0Fker7*5Qz3FIakh zrrZ&}TE61k-#dt3m`T5Nz4aUFXvZWiQc9j{mm7;IC@n$Tg0H4ZPcV~AT5Uovd44L{ zF;${HPO!`@~CU)mIg7DR+M2slS?JGP(h5V?uX9kXs9$33Z z;In6*B)i`}wf@AqdGx_qENqfNGOo4yPHy;@VB*P1B~5)`L@#}^e2@DqUqu;y9H`ca zn28(~=~2kpw7A;S@8_88W?k^_%~=yKM+fKXoHmyPPJQ;E+K<$^@@{VrS!W|S zpw$&~Uaa*r7#UuD*_<2dlJI8?ZpTE% zWN09SrPjYgTLZU780o^^?=%evJ^?k#fe`d9h0+;^AsU$Vq!A($5B}_y%KXaX=QN__ zVOBPMs!wnI9nFGAMU8BrdvgUmPn}Y>BJX_%qi><#eGSmKtOT7)?<4Z*8ba3T zUC1^rgH@f_Q_vvG=9V`^j2 zU$E$@*+H*-g%??P>O})?<%h)vdZjg8C5x&yp2!wQQ=18jWE!jd>~6s7bF_O@C0>d9 zdY<(AhG4p2*PCuT{EO^Z`S}N9VJ&}GLhg^*fhgq~S__JoA^QSTB|-L|BelE$EU54Y z3HV3=`-O?BMcG`nBU&k8`683!6q6mn&P4;&7qJqDI7@~n5o0?#IB^!+ldOr%ovPsv zKKUeTUfPY<|8ky?DkznAYpihQxje|~l9T<2Z)XMExq&(LGZn71f1{u(R?%$6zvL2! zoV;ob)X}R+HS_~!tDm)FFtT_4MU?vWR86@ZRfdangxqf9J@e0U+@PhfbUQ`UL)bj0 zWbOeKcT?r16)!e>>#UT4q-M%JYQ=l@YrPXzkMPYr-DhSW$X0|)U&oMj%c|SDB2-h5 zy$fV9Vt!}e`OJ6bJ^EW$o8x>zNQcun7exdQWBEH3cJKEsM>~NWs~4bW?P4RK9Xg2a z-!7x|>?AXXpx+fMKlnSWcqWxzuDsxj6LlARaoy28@r3^EV3O=LM&fNPt9p{`8;`Cx zjwyw&cDVaCZuhDkZ8VYPsw|dc>Ms?e&NY z0sl*@L(`h>WRGgUZ<_OLk?(s*p&Xbhv_=)SX37jQHBfhBK&&G2k!#kPh4x+EuisVK z+p#gSQp5j(D3T`l?ovC5QpA+N@tNJ{s~!pKY3IK-cpdiT(Hp-@ zQ+`E@XNB)V*75xNUx@s-qi*sS@YGkS2FLL$rmOcu#WdyE%gvZE0|t!0G?4%Vn5{sq zibGbD_2VDaU3Zn0Jhr=ZeDie52n3v5#wESP)H0V6kyGbMU*?$1Koy1RN)IpdvcL1V zA{kTL2|`hUE6pA5veDM)1DE%zXOos+okAQ^^(Ex`pc6*Fm(`3KZ|mT=gVFmXFCR1O z)Q$%-NU70FjxRL+GeQ)WZh+r#!7un~@bteVqJ?HKp;Exz};dgjgk+X3cPuc-V|x_ z!_zSpEm1YAXn0b0BZQr2zWip5EP72l&*ktvRBVUAZ#Vw%P_!XKCaTZ`5ybr`Od(J= zZwzw$taOGm#8zF)VAG7|TG+M-<0a*HOQ>{x3FzumPdRp_Yp#b^hq0^D^@H#Z=)7P_(eAvsYFh^iz30yXQ{Qbum0RE#LV>sxP|#PH+T{9Ps|a% zSo_YNF#eo1HZK#)JB^QycIa$jEYEZWkdAp$j0<_OMI500C(pitBl@vxS_9hb8!FSp zYCdeivxCH_PTbb6UR^;4R02n$cZn>z(W@!krP*ob>B{nYy zfr!)<+d03}mi1&>e&hxf(V|56yn}6cvi|Qn@QOhqwPF=@2m1G6;`s%E#i(O>?DxnIDTdjZZ^pdq*eI`njCYU;Cwm zjK7t9LFfIdyEHa3LQ2EWo2@XkJ6a#Ty5sPNOQ?6Lbq&k0-nzan>FLtReo)90jbQ4{ zFVk&k98;@2h&_~Q-}UE-ENjsT?BQRQ!=50S_N%8P%*{ul?Vr7X=GoV({KmA}=yALa z3%c|2pck3Nc1GBbJKP`C!wpcEM@&=3fdFL6l+Bk&u8@K1reM2vi!kQZkb7fYM_1}$ zBN078mg=qgtshpLYRJk1WUUeNW7o}rV3sB*IpE<6^czN%=lHdydmP{F(KRukQD#ns z8!Ek$5ydGxNQ~kC(*Oh>Z=dU|h@*3GV2^3SrcQ*E$SQ_FMt?4D{tIQoohesyP_eZi zU3ZO3iCq8q;7IeeM0;kDrl!lCqgb4+H-xmtY{sz zB;M1`Fo3wff+aohMF0MgPuzId80EV~)jI_zaUo*@tGlSs@hV){{lzDZJhR(#svb=^ zvdF9^bTRXk{x62WpB z4{li6zFkA_SG(@;xRP-7t)Qm5ga9=V|91Rlh{T8XH{w@C{LX3G^HX<3^7dISyW5*w zC}Z})fGZo;NX*(_SL|5K{9{cP*(fGRFKnVy+U};dU#m~y?Yzm<*(uVr50n=bd%tV( zLA~W5Zp81j-7g8d^LLQ49mh_QxKwq!ZDkq#VX=nnx>eIoeads=cJMD!`wBxA;ng^o z$KluRqbk1 z@Vt+bRuIsg@t~R3W%y(;>SO4(u3U*~ixl+3>Q*FMsB&ppbo5aeuT0M}V6?r8vF4 zppPqig}&d)!d8sq3~6{VvU(!8F0fHhElPmx&Yo-hkEZi}r1Jm!_&L@QA|ia8<0#51 zvvG{$(6F*+MMjkDbL>5ml#U~_6bIR4mA&^d%CU+Z`&b9Z-VWW@_lNs0aB;cbi%lw^LAm#Cp1^_2YTl(0dZOe966$EkgDlo&%@=VE(7A%j%nk}ij2Xpm$#)>xO>hIAcCT%aGwSGRW=)9=A{Dl&p zGfO)+%y9FQzfG~fo-S(|PQzkRQMdZbQp^K55@*Bcm1Kvv_6jw1;~g(~OghDnYt`Mn zFNK*Ft-eKSsoF;$*+%d6xWK>gb+4*u>M!A{Qp|;~WhUw^vh`7Fv&R>PT6WJS9BdPw8nh8M;#>Pd4|_V8mK$^`Z{Jk*t>;jejgwnCCc-J^T6<6O&EeS0fIYb zct2%uz2UW&t>wk_gFEJ`F(3UAkfk0l|Xd7Y{sq+2~(x{73XI@ezWlW zJoZ9xa41KP-Lx`VS+iL=e;xrjd%UMWTt-O@UU>2Bksgn=WLRhef_h|hy|gx{Utx)) z9AX-BhlPacvyVM%-YqoeqAgn#Km^p)6`$2ze<63D3s&3$+akIpy^vqHtYfPWa=`wM z9Nc&wF8U6Dxlp{<}eJkZqn@p7Jm%RRS0xc{a6`7ROpLHB~Zq$Kmf|jqhB^`s%*GU)t)`d zFP@w5SrQyOWkk-$h?tu3_wMZGzOWYI-tOg=P83Cg2`YPF=@h2vG)zT7%h4v{K(Nxs zCl)Q3l25mB?=oS%djd5zgHgS3pHs=B9Y2Fl5v~F5i^XGV3l*#X#eZX(a0pLt-_Fm8 z^7->V3^9M~Lm0~8<$9cZ;e#G8&J*7daBRS|{>2^iI1#Ghk>TBH1{v{?x4dzv=Hug$ z1%G>H8DO?XU5H9i*Dh1OJzQG{-6g^#VcUPE{LI9jgD&w+2>j33!}qkIYaBe*7$pi* zG#QxC6-^PifK`>O&VZByexQs|E)o1Ahz~W>#P!$9PI`+hcP1Idr3|><2&mAv!|d+g zes+C+Yd{(aN%OoK+1JNTOa-Ycl4;`MTnn*@GX=1yBVbNK;6ji_b0G{TAirV|B{zAU zdg(6r(km0R?8KR1QX&~GJ*c^&j)I<;{VEa(ca7k&O)aPF3XXkyq&h99NiY6k#^)AW zlR>B$kHT{o2V5%K%%6t)-NFKXW}umU=pUCjgbB+XD&YU2P|Yvdx)e2w5K?V$!DwWR zqn?j!qOP*Uo9<^G>RK)I6eEkbpHb3_BAyAuxCmrTehG+u%KZ2{y#p;ZdZj_h;ki`G z)%FJh-M&(ba9>AB!ouf??wz9Mcz+qtM#QpHW&P{AolKkW>g=+q_EorOx8$kj(SaR+Z8zW`TMMlyO^mu;sZ?y}lx z|0fb*yFg{WNFsPc-*VJ>4yH0{T8q-~5Fha9D^xyKvv#XEyxQ^CD&cqpfdwA8IwIz;PP3}tYy28J-{9f+0O5ptq=bw4D}^U?dFU5S<8Dy3`@RQk!bPAPJG(o z1sKHUK1Dv&f*u9Q#Z3elCyKXpuZ^A5&`*8vu(d}qu$H^gkgbu-JO=Uv!gEjZ*M-~mmir0QJJ(}g3j-$afGu6k zII*?nm3=Z^VKw?7^um?k)Vu9WH%K328*$Uxn=y~(W=EBn==Ov#BRi{Bi;!96ppfOF zXH!o*EcDs#Ch>J4kwt@ln?3ZV(mv7)kKvdke--niCz8hHiJR3&dnNm$2XEOTA2Z$l z6lQ7f1rB!nJ+TzkhPJxK%C^#p`-|Y~0*fy46LRE~nRy}3>H$=hG{0k(^o}sC+XG>H zvbY-JBusWF^DXrOzk$lrUdZLTi-7CmP~G>l`#SY*=l7Pn!?Q*d)lXniBU;*Y}3fN_SH^_G>y{gl%3rom)e=1Z4(>NgC@g2p`$3lfrQd zzn-tz)Ve{SPK@2GYYw~A>{mwOYuq_rO zOFJ#hR@&}u^})%2QN=EI>8WNjZlX9mAO!J!(`6~5v+-U=l;~T1?6q~r=jEb<6{t^F zjwIg0ZE=7Z30Qiz|A8*vG@dTEPVf7>eS#kYtdQE5^I;Ft>WOyTr0=)!jeaW4F}LL| zJ>Bl5!=~aisTQAa+O2J>udst!33mUR`<2`F9m;514}z{w?x~FJmgu){Fh;#qC&$XKJFG7i z(ADV%gA%PIVyD1(`EEgc3VE~OCA-wZ4n0Zw>gI%J>fSfjFPFS6lE{!OuVobqeDJ*aGaU(ZtH<(+>N>lMsoZ;^jNNWLIwY<|7&iEzL1GG~{7m){b4qxcba<-!AAs5czMXx1+F(64d)7BLFA|_r+XEG!Ib+vu>w% zH4seGvb+E6=NtVQXHLKgW2I4HIsWIm?r=`KtLe}y2xo%ecA6_isZxPZ%!9UeR!?fG z%}hL_dd}gDLm5(^Jf12-oN5_YG2J~N6w985L&KDIG_OB0;xNXBYC9sj2E&Ix$5eL| z#kGf~zDQ-gAQOC4;PUfBIsHq10NJb)FT1R;5AYt}bAC|G4IhRnnS4G!vlTCU=C_+? z2St$Kk?Iy`(abIcnJ-6wlF%(8>TaeoG9cW1=tuHq9XUG|od7{t!CUs@LLoSqXX_qn06JDJEkJ^O$*YNIW}asC=;X?NWh=!-$E; zuTQ@r%Z(D3<=(y(IcD>kt7oU{@L*I@-6J#uYI76xv@(&uK|u`e|3d8_2;54TjXu$J z5c9Rm+awQH205QN?AXm75rtjb?BE#OaQ$v4qwt(HGpwJNua8Ovsz64Um%<&?X8RPf zTX@BH>}Sq5IP8}GA~OD9eS5{gqk~QsH+|}KdT#UeAe`fon&?YI-ZMrLPovDY0H2RO z^l*_)IaS*c_-3bn6h3s;`|yc(OJ4;G1p12~_#9Vfo6Iho$4u8#u;G+Wf1gZ`fuKj5 zjosuIS#%|c`8Q|5j3)bXS+#pz1(N4PVsp^~xWD_yW(uiqx`w;y@oCKx&-Z3eEV}$+ z9!lDg)=w49mIp9yfafF^*X zfCnXG**#`sAU?rUKz85Rz+TSTbnVEnTVzYO@=5Rgn%8EcBE0i#w);=eh}9Qvd$cx| zJ(SHn_wYBJ-@#pMY2UsxhIp?b{8X}cgYJEY&AAD`qxz+jrmjY7f{hlrm@xrz`-Aix zV8u@YAWtw8;=l%7%oKZt8QBgsJDpCrRlAUEud|gvt24hdqt!rU=`dfIpw=T_ZOZNn zE!J^HZHyuT6dmc-VxMO*CuhTltT8|bEZ_#RCrd0G8Qha8my`7QyZ=X|(MF$7n!)Gs z5i7MAzL5%r!(%EIFMDXX)slJOKYxt{+5o>G%e_P>4@_6R8`D_E4WC=*7|H=!s<1P5 zl+hgH&mLe^MQG53cW$(D{ajkbkLAHTn_Ualfngel=6y9>Jq?%!4-mgV;HjMa=i|{i zX6adrh%xVdKA`r2<;d*Onf|RGRX4jhw$>@fxR9j9xijIxR@$YTyOEPFe^2T^^6vv? zy>vFZYqchpf?ASY9+>D-TVWC7BMUulUKpKSrRAWM(bY7Q@RNSEb$JrST;HakcGyj9 zP^f=k41!}v(A9;qjeluWAG+A$U=^)cghoj$;4cAZapr46B{GP9=O3Hd?;vlz2ys;} zo=-tGPtu2q`F2%enqrVb?^LGIabCo@iNkQE5d)VRbSbk-;+yZw>^E`2vE@{~lc(wT zuDqEfm2!g>+K#@eMVPUmF2d?QcO6a8k{y=n2 z{_n)bT3^#CGqZ_+`4wKm`W+kVP9Y4}!5OT&cv`@-S3uvw*HLzT7Ju$mH0@eH zBgkr^hN7;9*e|4WZkRQ=z&sP3^t}EBeV?faa7p0Wm?S{q?a``_n=ccFzQSJ$U)2bK za5H>LGD(r{uSms;e@X+T=JW3X#!rK{;>bpwPOj+pqdvqv{%>tbNdNkcPum*<{66Jc)>`K7tjbMDbL7win0bsQl+2sObSnW1f+<8ugK) z@geveQ8z2E67?%6Jf2D7e5a<3CjE4EB}nH6Dbp&g;K`KQn3UhrvFWpo5xAa)lOFY~ z8zAeQdV%jG8`!-h>Q($I8B?)*w7OHNG2lwAY41wkbp3{}&_f<>lW9Q%4cG+v;Q8leW64(M+-STleF1XEb&6MBX(N zf2$SxTEZlM$Z|-08u_4Wsr?e$1UUXwCKM#O_SBy7(BGYlEvW267C!a!5r>J9n~yeR z%Y{&08dpT~307e}omlhwRM}1Uvw-7oiivzOLsf9ypV5^3ulc>+C$ylfV@#)#-u0XB z{YDopxyXFjYa<&0h=E6Bs^iS!VP!Of2nkKSn* zaKIX!j9y<_uKyGXxa$H;?zpG$d5=0YHSy2EHe6mLeVp!dj+H(DgqZpFN#xM`=fnS~>Z|1W~Z$>hBsPYK`t33$w{CQX4Y*XHm zQNdB2_dK~8Fzp}VxS>pBKss?t6VHgK@P4M`MW%^?fEb#qK;4WtFcs7WlPc)I^rg=@ zhMTpWQA&DRgvmX@sl*GtAb5M127*utx>a4`SpoRdhmykBx+j@9dKGS_24(EA;vqQ# z(fF2X2(HBde9by?$?+(R9I>j$_?DbR4@Dz(^MRIy$Kga!@RYb5$n}ukN5yIclw$8O zThjs)*E>fU1&D9kceBt2+Z?)0yD12pT2iXRP?&K0I#^XQB4Q#K5b)#g$l;Vu4sN=M zz#8SdkYdX-Qq1%S013ym&MijHRpi{zP-@iB*O`l`UZ08k6Y&ZOqR*?&0SQZdDv$k` zKGc+Xc(a3-ZGyqQyXTjoXgG2>$0sw3oc zn`{J@%@?#|6}XlC?Z2yux-{p@M}cU`j?zu}5g zPb!sg7@BHCpYRbfK*ohc@aG0iJ?R!;n^aIBA4T6iw1ND>huFputh>T4zU+c>hDVU_ ziS@!qs^Ghr4<3*lu^nR}oHki_kvNM(jT4xh!e3jppRTLA180FW=;6iXlnAr-~g zWD}LzV~m>c;PoC#` zh-*ef#PD#c@nd#%bVI-aP-;I_iW`l{$p4rSIk#^@ku=~m^`-W2}0DHg;8JP57$1hUw+EQA3kO~5$y{IceLKeE7jfxZ@X%nO`{!uVQul2>G86yX6c)H(8i zln%b;e07OZ0*RvAJ+7Y#<-`VyfwMk9KzP}wkZ>v2;-J9H#-8nt;mWVaymfChM?$CX zvn*A!VR2cg*c|=bE|D#E9GT77pvnu@4&l3%rW^fcY326`U=iNIfdCmqlPl7)^n6%u z<2CAcvM{c4aY~r+3m@E9dGu%Z?u^HvqLu_K%*Jjkylpg@=9KWC>o=j<$G#`$vpuaU z9l38@Ytch9`h|8COgg-pMqU}4Hca^3&bbL2<2h+xVs*uPcTnGK9|`_Nz@u_pw72Uc zDial#L|nRo#xVf9=7W#fr~FRjoX0ZG*p>wZ*dG*qKWeUj%&uva0T5!Auy&_FmuOzZyH^VH=S#UJg$qlQv_cIwyTTGk-5R+U6CKS71*l;wFZ%sx%b~A%vlIU6kWCZ~9uD5bT65mor=Vb#E zGzY9eFT^f&9igz&G+_Y3v_oGhVn%O*ct&tCG6?P{$x$fV*6?^DeLNH5tb!l=w?T}a z&q{OdO^?l*CfN}tqnHmvfY?#my5HohOJpGKr8^m*@OWOlC#4m5>n8T$JFb*rs2wF5z2nQ(lQu>M zloht-O)tVYbclHIvM4FzVb z5k%qItbFn!s{8aM{7$dRCX@vXD0QfQF?x#hUuT0rch19zhryXrv*CjQvZ3j|qpz2S zqfh8&bzDNn`Bo<|*6DCM=@&l^TeF!j$XPx>HoV503d*S+9JRpjI`2x&ob5(hhGQLS zOCjlLq_!jKo)opYHDX>+T>m`TxY}J|1+-tvd^ni@VE~Cr!U^1G-Bc7$%|14t0 z#{bikB_So7lR#*gKI>5u&u+@y0}lCH=}pFvg=g*bd<1}88P*XQ6g&Y^3fSGvIhoiZ z@GV0YD7v87k0qfx=DGfF4Z9SOOd9TbiTQ-kUtJ!2SQ{TeuK2(OL9}7*27DG1Q@N0! z7Qw~>wig5Dto;fg&)5uP{@*0#Y<7!EDb1r;sC{6FiL2>s6JYA~+6+lQbppv(&}yEg z$sls?F!<6}kCt*5YR*JdI3SKf5??2D&!m=CFB}^%_*s9kozNu0noqqp@hQ6o0eGY% zhr*4t29A$IpM1*LmJq#+NCYnJy^yp`0?gp3iE1)K8|O2p_GW4?gHNEJJ;nD;YW+u}%>)LlX)@_>OKCC#@_ zugz|I55k01Kda;YG}kQjQ2-{5ny8A zY;QhFDqJ;~QS-2E-pz3GfsEiC+*H)i=f}Pt6M}sNZgBm~`;Qfev9k{s;t@e6AO*o=uBg>m%&bINpkI+yhOAn@#| zpG5Y@Ixn>muHJ7MQcQPuTT6Lw0Y9UCrhiFMuV7n?RCiW(}r8>tw9d zeiY=ab{%ToHN=!WYj!uw_ooa%Y}y^|Qrg=|9z>&j_{7#Y=ut^QvkW?;*m-CP-3NfD zgxD{kHGM?t8P374(i@udlP3L;h=T&p@ML=2DzWnB9=+0!ZCXmTsj0OrfN<$IJz$k}}#Qa{qMgQ-V(s~-V1?AIun^52~c`%e#|%api8^qXK;!ZW%sMLR%C#YAl^O%U$yE?m5C%FnjXq9j<5UcP@%6w$ zTtX7V9HvW9e}91jtJlcIomq$LWbK+n=E@o_9-yl+>UtFYh?{laP}5}1J!qPY9I)g# z(F&`Y>IQGIA|3Qm6vf~UU*>GsH-jYxoDV(BJ(UzgJ#`cXOu1_Nmt zOlxTxQa+|3Lbi&1BH)ij$y7RCGAj)uAbVrDner&+pm&`f*H&>;9B?vcLFh*-OVZuUKb|i%7=}rW8m)gmA&EdL@#8!G90H7^MhW-2ocz*Fo&xOarzDw-! z!6J3G+`7PP|62oCetu>C@HOa^_@w^FTGd5MHzA?xAz6SK(Z#iBfsD@vR(9>2xs-+K z&BhV46Kp*IgOO2jUluEaLxb*(ycnVB2a5ds)+_w}>}avp@5(syN9Mn4il5&b#aq-L zt%H@alR`Ff{eUM-d!q5d&H;cgq7{K8@808ElIm+)KloR^zD?pqwdo5F@8-0Up@I>g z?^U~TlT*E@x|U=C{AyjFEmgj^-f;SO{kRGj2CJsvS;a4py0GN$e$dhk0fTy zWdRzO-!3^C-O_#16jcJmRYMej0{Ti2LiUUkUvmsxpkLb36ael3uhoQ%aQHEc(n+Zf zriH4?CCf!ew@x9_!*z^RnF+Rk2?BZ?+B)owAy$~v;nC$_3DwYzR9`Ym|9|~YE5hjL zMFYiPV3KGyYWDkgsCTf32`A1^Ip8;=5lAQ~szi@T4A|lr;yn~uK)=r>MnA4QnJZ($ zGb|*#)H9aRa-%Qy~EyMIM6X|D-pxeL}SeXDc1}wbwOly8kGtLifGtX(C zW38Pp3w({!oM$n7Z!adCD<6I01EX&@*OU_a{?7CtsE)Z6s9?h-9sR~|q;VQp_?ilV zqhRdLYa0<(G7%l)GG%pXm(Cc*HrJ1c$)G9T5`mbhf1o5kg|7b$ql@TAT1~9MlpC{+ zV6b~xm*#p09$C-w^W*)2fyEn&Bfv*VTz1a>Bc&df`zycB{X%{VCHWaQN3O2nRJGZl zl|)QJ*LNXQpfhl5m@xkp=b=kX^%hZ?lT_)L*e$Ya1L0;?;_}?h2_w zhrc;x`dw`vC#RS0mcCcUd{ZeZR#rPGu1jPHp3;KwjK0b97qJt!up*?1+%>KQxsdbz zM+zV1ShSdj&yB0iyn(W(m7DxdI1G*25S-W|Uby)D^mW}`r{0VmKKDv#iI zq6>&uiQ)-Ao!3fIPgKOv7(wgsp%j9D-2$heXPt^ZNYoUV}wEqK@8h(%cm@oQa z5;8nCYTJ89VP;d6JRG}~V`JjAg7&1~IA*nyNW{(ZR;U+@QK>+p0XJE@pFuBKbFJUR z0sp^GsaUKFir2KX%iv!N2C$~+d-nxI(7|%z#MDbqAbA7??T8gki*1+8G z3qE`{p?5OLBFpReplF=EAaM5A3#7CDQFgTi+x;2MG(LxAl=jXJ^uG?H zY7=i;4140nz{yq@B0pD6B-B?KxKtELwp$66ZRsVj7ujfO$$a}J)7#F^;6*D6$~t%rv`nc*vV5!<-LVcC5_=~istvs zcaR$6REP51L^3NOBp9OKR^n>*G{a+B3WAE!ScphV5zT`RF!^gSKa=0#3Iod5sK+KD z>ax{gS>pAhl-;>XZN_nqki-8KOWkNrsmTD+oNBb147O}+zJ!dSMVLPs1{o@T;JO{t zQtsY>Vwa_wDL0nf6Eh<>=O{zv)@KB3Ggw^1w+rKNdee>7O~{qz=t@5?B-7)++i(N| zP~ra;SA{9o<@Kf7k$ASNJ3}vN60Z-qm0lfj#BOAD9Cb`KHx%2oIzH@W*0gARRsRAplGeCFHL&h^9l}?f3 zV>7-4q2NGHU640g2KBLdxDs)ZvT^8>!8~Rs5(b6_U;~VQL@FF({(N5gDMTkQ;KP^a zumC~_aBOCPwD?8TF>!|>JTKi$&0rk6g(&$lp-rWcF+R`^c563dpb?xrRmczn|=h~L>8iT|6xh2s)=4RDp z=ZdX8;E9|>V0JLlo+SB-&W_=?#d*0=UF-uV?JQZle!t?IF~GP0jcJ8RxHx8XyiO>y ziJHeysKz25qCd%QLrQx@c#=L{mz?Y#s*hs!s^e}HW0$(gF0w9E`#TFW&l{6@c4p(D zT+ZkByvF_3&?-r?6`Fkyxu~aP8;d1yWLefe{#+ITi4Ib|&5{AQvZ&m&$ z<<{Msqi4)JH`<};eNLeLKUV+fb6QgJU5aTUYuqGUELJ4uZSNEGMqCP7p4?QCqOwr zFyE1m8Y9Hy^Ii_Iqg`$mR}rG=Y*lwQ3s@bl63m@%?TvrKw7T-W8vg^FUCbHIr6*nR z;!{}ZD8JSO5cK5E>1j8bu4gU$2%1!vN<#KKtX(47UL__s*&6sM+#uzt`WHIPyPzQl z8izhbAuhynErb;Wiv6uFKnm5_g*Clu*1+D#+`8yHqFda2U1f7}2OTU+jn$5WJ**bO z-Tols50f=?b+{tDtmhkuS(EUnMSmK<>qQwZUjod>nGE3Udw-3SW)5Jdj_p31g?T_< zSgf61!l@xk^tH+DSbZXCGe7Gnk)-Z;Gzo7UZoCZM#$PejkWC`B$ej8WaPPPZz3wRPYtJPEG9RzQ-cT$cC`K6A^^R9R8Phs z3ms=4U(tHxCNgsz9TV>2E`+by6)q#_NsQkrzw^1}bQqWF;j=$i+$sa{2+KkqQGg-q zpZv>M@Ec(t^}z{;>IEZG2D(Fv_$f@ag*CR1hheOQN=!~IQ^tBA6$%msUQCo&xa(kJ z36(|<+P+0biGs+=;=q;K1iRK!VCl=IPmc#+0auPRCYA5J{0DMnCp)&fnOcnb?9Ksu zllX~ckm;eCt9zzuXk`PEXTn!{NjgQDC3}PA=ihcIaMwAI>|~hadwbMKUAqaonYe#aX!)+mdcGV!X4;-4iwMS z-}V1C-TOgLWkWChtR!jAC-US)$iNwA<#4g9@)P$Py9-;RBKu+IH~v8egE{b)J*Q{c72mDk(68=LqurABa(NtGM{< zy>B$-;dQrXF_#`^)UgcNVH4ZoecN;;(lj0o^Xcs%g(wUkJ(ZQ#yR}QTMxNyXA%Y{p z?{iR5&%HUZ93vSO!zY|aW<_7#Y?IulPeYSJq@9{KjsJnLqnfq@$`^CSO8G(+?*Lz~ zrTIH&>#B5u^re;Zsnr9FOicS}^57-t<*o${qr2tw0!5F|FJx&x_ebWgUpI?dw|*ZY zGVaLqko6*qoM_7RQ3y-X*vwYC&Kb{9@s|63=Vn!c?^Rra!WMhcMTKkpygiV-mw7Fz8k5p`bie~4LA`Iy-!^=}=9Foo!2g2f zLYX^e6vh~AX4-a>QZ%9x2b3r(`OSqZ3#{@jp(A@qK5wJj&Bz2Z37_;Pc2QhU1Fn5gK;u+S)#x()^ey&Q`%de8fNSZW>4@S5+RdS_5`5P+Nug7n zA=*!`k+it3GjiS$%;P!k*?fKwBt4V|3Mw?-WUDDnBcAoF*pq&YDxXU{O!_Kwgb8{b zETgeqDtMZ&k+em41loC<66{xP`44p2s&fXJHRlkex}dvKI@jym-RvZvj;kw2`7l2- zJ>a0bNGtmP5D&$gLyxO7!1mdVbQg@}&G{G&1Dm|}DPTgTUF?!o_~xm}V+wWDBOhg0 zRTGH2WibQXI4a;2v`0*)o=O5S9Yhc@%B&r6HFx!F zC3e+{f3tiD9v#B{@zC6e^&cqsfe<{iH0ZQC5&otstM;=gT=#2T0Znt!n)C3YeAI6@ zmOXRv*u#r2vg4AnV{LmIBJ!ydA*N3NZS`H!45DvBvm+q23Z?B?W|71|ZQUcdy=p8i z^DiZp{*vD;p_0bF_?9LcnWzI}@h7MCUP+>>%bA8mq%%U*8vAl6#Z~B*WH9uk{ z=Z%MbhgVM}s}B44t=}njyrz3HPrs-6J1|%hTS=;rcCi!u+LV57Q#x+;&%|N<-2DeZ z)&YH|yORGvLF8j|!7plz{tRfv5btps;1Gzb+R_+}HMG<_=bj$Zs!AORjeEN4nG8SY zc!yC^s120idAMJ!Sys=GdYfI&Gj-?C%sJAmpM4M;-Xi!ry!L(p`G#xv*x1_9Vsj4OKpWL{9RB3bJeHkV~7KRU{w9(LZ_a zn~Eo=?(G-%Noqdssq=V5T~GrtAVCDnU{sp#(0Aot+}cEWLrn3+1_QZNKi66CobL~4 z2o+?cwmu2bn~0Vo*SuNy`o%r2*(33cGDC;DY%qSL_1a7*-q&@hw0y2g?#|7ZQVhR@ zW6G&5MA$Kheva1<%XFz*Z>i%fkubzu_8^tEsxEbo6ptZDNM2U(PoDKjBD>SOq2l&3 z2DsEsB+jv@u_$>?*yRnCPcoY!$k1@oPH|eqi`hQt^8ilMYnr&W3GAhDjoAb$^$CAc zMyhcV#PjtVHcnKw#;86@0am+qj-T>4*|1M+3N+rZjn-2Pc|OBpk;MH;TW$<)$lex2aRPsVbtp@;!}wQz*5WWU<7Vqhq~;vM`WT0P`Ubwa~% zT`^eFr2MnvmC=H@?&2&JL6^+{Ry}i@XzYBaDF64 z#w;;WhjD2EH5@%u*Wmoko{N?M^w_HHE@poH$~nR0b64fLjY-5AvT!2)v|PZwSB;)_ zViuUOO>4`C*lri16Qt-L{aWbgWpPCMr!b9B zim?T$v48Zz81s}#dQz0@WSLW>Y)PFFI3aNmlox*5$Ora-o#=)od3Q)a(n7QjT>R9Hd@a(y2@NPQ1jge-L^K3{L-3O7SSB^h5NV>;%Fi z7K9R+Ta7}a@KNQ(efj1ut1%}9+?z7DOQG}>y}`8*QvNs9gfLz#eZp|8n%Q3d&=A#? z-=YbQ<_BgEB^F?5>@6jvg(+`2=fZ@%VWREY2%E- zw^-ct)ZoYYj1w{qr5*b%k~iEC#uL_X_Smp`QOG`W9&;8f{>&EMCp4b1-UCze$}yMh z#Y9q8Aa<*UX+%yCtz{Ep?FMlwVz5WLU5UR7dTuz7epePJj=LZIGt23;pF?zb_n>gF zYwKap-?Qxl!KmmTh-+7UmY2%lZ$gu#3|y+YKPvH9@I5f4oDNTKmyqt)1-f3&iVHE0 zSaiVEy0Fa627h^cv=#yw(2Jj#n~$=-aLsyuLA0+{_Vr%Nik4``T$Q@n<%SVcY329N zZ}7dicTN3V*E*9QYq}n$)4VEyTFqG)R@+-nc!Hb0S6^2p%@8dk!^^)qx~;M&m2|!{ z^JU2=;U7gZ!U&a58`R-w<~ti7*K%)SV{e?fHcu)nLvmk+^(lVus2THJU&SHdIS-U` zs-9~Cyl4!;wFa*J>S4|9VMAMN%J-THnc|38{j+K((75woulE16E}k230L7*$UR;+< z{XBEqK3*;l2@=q9n`+A^`g;3ISe8A1Ib-3&;7u^bw~JsNx4n2~IJ`J}?_!st9i`LW zDfZv*CIaiLjG~!R=nf%tnDS)5$yoD?HA@DQAz@CVTDv#q?dent_-;qF2ssxi`D~2A zCoWM^lj+ai{x0?D#hV&KXAGX-6?(4P-4j%DBUtxV-g>&O$bDLE9 zwC$>r#xuWum89ZAj_IHl8KZWjT(D$xU?Nt>R#ke(!Ev7m0Ipi6lkUn7gMbuxLZ5=5 zneTDf9aq|6k$}I_S(YzQU3FZ@@}J02yE@qMscA&$C1h=<n zdTL~j*)^{uV0Y&1ZiFgjJHJKwIP`cWX8j=Y=l%6oJ_>0%+xIF1De9XC1JPtv9v=Vfu8Z0~u>DncO7e@Yg-2E%*-vpBAjOVHNAV zkR9T+%)VAD*1&`GKn6P#ucHFR)SufF#ZCofk#K5+oB+mf$K-1|Nv~b)`50_CPL_d$ z+DZ^W>C&UOB3<2jxfvMKo$S_aD zoL{eFJ{BV&ypC8B%?mj^*#DLzDWlA8cDf|&-kZe-?8ZYCyQ%(BVfT*F>Zl|KtxNr? ztUJ(G3bbISv(F1S+4vOtDps#f@6y*xD_%X~vOsNZN)Hqpc%0sr#yz8bNp;MgUNUvw zOF4igzdY@A%`6(pOn{$dnc2RpzAw_xlUQ!}!F(8Mb}cf!s#64c;L;y_-v8J4)7*t6 z%bnDvWWegiveik*Xw%Rr2!QHcHC--teI~x`Ccv8RHrAy7PQJD%eqiCjzCXI|C*@ z<=5ZGMYJgN2fr00M-MXp7;TMbnPrW#6*z^pP>CSX8(475 z>gn`W#yMXeVlsyw5&{G#zLC1{PpY&)9Jaf(^X8XvYF!Xeu+pi7=EBRviF3;58<9H{ zgO-MZx|bw|+`TD9CVsdWxmo++eFdrdL?~gZFE4%9&T9O{D&?cl(jz zuuFI*rcjlp-x8X*C=rBE85#GfbV&NIHc4lc##t2V*!AO9@&%650-(>hjqp(@_MEe_AlB9jb9U<8y!r0X4l|kCMu1sk zM9#csXZ4vQ{(*$vTONPVI`dvS+bAD&OjQaps+mmO3@O-nmnjk=@WV9wFvoA+WwRus z=8RSrJ8;qJZP2aR)($gSfLCv_bvOvvs79kWJ@>^(f49kio_j5Ja-U<$S9$R4>Pi}F z_ELl0+0TL4ff3YZ#Vx~sAi1=EAV}=)m(T^P&r<@M%TUMUEDB77qm*V#B)j8U`BP9pHbTq!VvO>p7$Qw>bYIZP>~uhP9X$X7k-++L3#+jjn~n-iaJ>k5M8t$&0Dn7lt|w(B;I-x}(unVENu>BC`Yh}IQ_5^@U{DYQ*(p_T2vT(@r|C^qO|wR#yX0gpD;zgEmx z7#A}bzP%K7PG!=1S8&hq?^n_CxpqR`7a90iL4WA)DffPra`q&NL!vR7EkNx-e<*oY z4|NOp%mU5Tq`ru?dyAlXRIMNZJIxpUHd>lkVul|znAN}~NL{Vdh#4C%nsbiM;`e1- zgN>2mEs$1!U}1d4bY$r zAyd<1mdZ<#f~_2_aJDCfr^&jOKhwRJK9Aqxr}RppwD*49ZnI#$T5$uOz&^;oqw=ij z#B+4j`U{>t?%4>PlGZ_)j0Mb(=&pU7p!w%3u2<%J&Chg+qKn%&#lSxwqNELf9t)q` zC5QBIGqzazry%%fKui2K2XE**Wv#sFZv&UBYH|0ag&-bKGQg*4Efj=rPGfK7;$~e^ zT&L4zd$3d@+zQ1(h+Y<$?QPGuaN>>k|Dkcy)>zqPS!;DWoN6(Jd`#@K8+L0jo^!l< z{l?nkhYmtbntQN<^27QLOd8eBsdhbcTcz@^n!|ro>l?m=RvT2*=+OUhbnbynfBzrf z3_~JCO~%xeTgfQqGDGFk1-V2KG9_}^kjq?0RGPVWbt{*la=+#_#9RuY+^@r$`(^Hz z&+q;H{pqjS-sgSJ>%3mi=kq~*GdA?+$e7ag$Lu0tZ`!{;-#&6pSw5XA;JFcvGnorU#g9iyEaO5WX;Z>aNo-I{b> z!`kat=#5Z)5Kda;kITu^niYSea~=%cGbq-V(!0ll*S`f)+L;K<5dV^D?JVVW;qTr( zG*`8P0P1k*DYhlR%y#8D_0t?Zs9-Bku>4!pY%_@3US{oN+>xH zi?>PWToY7df7{>gx!yHwQmn{_EHgpRTL!~o4@Cqe?LPR36Ud-by`R?~43JMA0m%>G z;DWYE4QlrW{^_T*XzDF+R+w@GAwj`OE*iJ3NZ*%SnfZ-^%n!@(uQ%GE?P?4d_Ns~0 zCq}1A7%I(p#;o&+XTY;C!xM(#3(DFL>|@5-&J)Qbay5xGUhWeh zR_ij!?n>9`h@TJp`%}R&WE}ODg=7VrOkd8YRad2QeV(cUW* zllQ|_XJ-dTcL!|I^ZI8Zz3(X*R$*1s=YkW%uY(Qztwvu`q4!=(QFTobm($ z-IM5>7L`J(F>|p<_UX#(d$db2Y~cGw?x01P{| zj}Cz#tlM2^s=ZL$a`WYUwS9s%H;OIX+hyAXH+x~^{0*>Dx`33700?+NL7Co&&zA6d zs-A#383^Y@Qq5S4+DBVwfgrfP>`u~%w@c9kVaFG9j%J3$Nqr1Vv#`j<5D*%A&oP#p;$D(BQggbw6Nz*|KviUe(|7w}bjQMQD>t_B}Ltf-nq zff97kdt>i@afp@ad6i0x9;V1$8Pc&;b;^OYE}AlsG47aL4sSSOC7s7mN<_}cYa3T4 zeYB-FVZ3;imfPt$vara`7U5j)h5NvS!FEtQ><|v`OMTcmJ3k_D$o{D^ITg=&u7czWKNqLPQo5qyHbsnv%46v|UHK z>EolqM4M}IjZyQo3mK_`$mEslff--*(p-Sl-KyK~=abn5@!$5H5!Zoo##ei((SJp%uMDvHZWzFX>}IuuqoKTt%cf z66?0jaXvu1E9rIb1MhEh5C}5Ei8uZx$tYj)JQAFiB%gXO1_nRSN_-&}Wq&Y28BFI6 zY&P;^6zJ@ldFCG}p3ylx5#~o_kjWC`X=SQjD<(^X79Q5N3FJob!u2f<%E-nBHB@-g z5(%LiPs{A+S@@6^{4?#F@q$xmcrYRYbcP2y23MFgRZ605{7VlAi9i`x3=JENy_>(m zO{b}WRu|MwIByMdYeTq@5Ck(zdAq2UAt@kd7Ek?&z4TZd#X6A9*PSVfNoQ#v6AHyt z&d0E#JoY4$IPsVeL6?wg{P+f84nZ4<%0qLBltOgF-T(%S3EAxfOY|Th`RdGBpx8f< z&EQK1Qw#v@2{Veol$y~NW&P7IRp?W@3uB};hMr~29I^ngxv%CYNf|Xp)oyQq+yQ~E zmN7FofE1_S0#HY{X_usV^u&Pa{rqh;=)otzy%}6OCGd;-1`g>vv`y?vszr6j%^wPb zUQ}RZMZ1EZsEx*@`Za4@p!seFioBep zxE75dS-db_>)#^4EDQQQkOU-i@_|sjh_`<;9F(h98mI-W2F$cB5rK{CWHdu6U{zbl z$RHwSPZ|*N*ad7KF-^O>ZI*2}V%@;`9|%`*X9oU>?6%g%c6ffuZqng;pb(yioSN>7 zn6z`=KSHtCzUaYU`Eb^jtCi8=oczBL0fC)=!GrdiTGidy3eTbcj1R6} z64n3bw-d74SZmw8KX`b~o){!guT!pjRCcvVPY^HzhTK>ooYvmNKizt{W7hWGJz`); zWKjQC2QHgCI22drjn&e@n=8z~rtQf%cAmzWH+~GdV5i}51uOjSAw%{~GAJ3)(d|YM zt8N_p`Khc*d?gb8u%!n|7zh%qRl8U27@bumksVF-{g7GfG7m&;B3mE)`$dGP&5A z&K+ywskelNkSK}b)q7zY477M%VqlZU8EsbT4l8XXvq250tlBMm$3nre+L8>k9q!KL z=EMY0&Wew#KK={K=T8cL;~tDtyQ zh$~^7d4RuTet>&{=9;#^kjiA0EwB&guya;mWUo&2BBgJpmDx|FZkrxWF62zJGj=uM zbX0)J?gY>Emc03=8j{+V2~_QFwu7wO9b^I-u)%;uD|hs@wJ(ni-|>oUfUpb%xs;3q zjS>mf7j$RvD%~8|Ez4y1>OTNBTF`MU)V(nw#>K2vVk|Yav?;t*>@68r1-v;=xJ;C^ zIT<;uev)yI&+yY-*Afm91&5HgIef%J@jN(bT@?s{2|pxCB;7Rejrz@e_2E<)Qei@k zTfuAhuGwIcc-LPsx{wI2o3u@^eVT7jfJz8UwqK2-d)#ug{Nz08!45c5U1;{REXwj~ z|Ao-SuJWf{W%Y7~oQksG;xBP_%E(^Qt4F*M`z;Ws+Zk!=J#~cbD(~}s4_axj_KV2G z$8~Q@^v#{`;p5`5LV$IvATH3a%|HLP>`1QElKBQ;?quh?-W-&OyqD9pR=yOT9PG!=&u()nTR9k=!)+z-N7!(rllq82`uKZrayg#c z2sJ*ue>;fVTHwC)$M=TnolQCjZ@m7_;-a4U1P=WV`cTKT-dDq`MPtttHv@sXt8dcF z(fR8?#alKV1PrEqIX+9vLD+JNgqYqsEMJ_lr}0({oG{#HQf=LVQ27ambfSi}l1-kR zhq=Q!KIx~o?e3ZUOe3_3{!`S}N>L{nuDwxs*O3~!A>N|yWpu7F8GdO?A5b?&fb@jJ zs_y&)F|`gG6H`?M)EY3#w_%+o{0umsjd;C+!I4n?M;lsf&^{jBI!!pZuF7wuWlMA- zk=O^a$x4qZ1VCm3IF^yzLc4INFoBdDEDXx3q-#_$vJDQG%TN@psp*s&+znwKhiE(PyrLiB5TU|Sci6h5&Afgij`vKmUr~K!{knm?+ z6XwxC5C(CJ<2|)SUSQitz`qct*1I&y2n|Cp1M2plV0%GLw+TW&AiWn%(ht_&OC76AY&;^tJ#ITd?@0--WU|?a$^Y$w ze~L4Dk@b_>BIPUoT$KQ1?SpoUo*tC>!H4#xg7fGAi#3+2AC$RD-UM7KI_5q!$?yYN zp6QdK@Jlnsa(c$DI7ngoqS#yLlLqMit_kFOAQdFkTW}+^?i688ZF4xvZ)deM=3}KjM_hsl2`+h-WX^K%lJ~9C2sC}UAXe(IBvbA*r8xRXnyrPH!XWLy49ZYb}CO3{q-1`qv{%M@o&-U*^%Q z;ZOC^k7g|SPmMTnSG-Srp8=ZeG@fL!?tOT?T)y+QUhcdqxW)KCP=3MZW7>c<$B(sb z`R7rQ3x)cM;`|4W*KmW*c^WAv{0*~&JUOFxD(i9(&0MInDK&A%<_%K%Dd-r12DkKY zL2b5tGIvK%g%_J7`Hv|o5A>+`x{K0*aSNGIDoKqkqAcj;L&HjJ;v!_3- zQ-E9D;q8*FO&IhR(M;q$T9W^ntwuMGSZ7cDrAci*deT2Fcja4liOT#E^_O-QO=ZBA z?jh9Pp-(cws}s-Y=>T1sbAD}|Zgki;gKbLw4^-n11hUz2F2awYk^7sOZJM#XdsQrL zzHwC;%m%ME(QW7z_eRDiu0;`@;f%Igt;7o&C7TI?iakZ}!anJoR-Jm_Ht_&K52DYS zlGOp=MBJ}sEs5}Sp&@A2HgGM1NZiw`7o}?lJpq$_9&R!;5xIvJVs2)nHX5T~(u|)} ztreQki(kI=GetRV5=hvHG#B_325yBF6k;FQ9c%EKT(oQGHGExr{&8jb>+Rq!{Ezq= zfKK<`6ncdIEieYg>E`jx*N$i7_oT<`V6l1y)A2iT?AOWmC0SDoWH_7Sp_n5sTix=! zN=)hJ-`{xGejze?E<4Lb=T*P;AxfZOU!$)>QU=ah&Tff*kvQ}8wamFnlJ8}iP90Gj znQ04xye&(m;uc3u9P(I=XA`<0@#)neeOceiwwJq#oQH6SA}7jKWrZ<|7m!ahhSod4 z_x9ZqOr#{em6FuZ#6i@s%;AbGgP&?9?j5o;6VDK8nJJl9dQBgo3zcJP=Y!W!Qlu!d z+yo=biN|j7-b?p$+}x<%ikW+fFCxZiASG`GBFkzRe#}t8fDimwbMpFis*O&Ndj-Ku z)H8Xt-FptaFPHZE%1wa5_;_uN`Q_4^@a(HNp!fal_7ix8GeUfO>JVf6qoV&FR|i_G zniIySh}y9{9&z^^`4YI;^Qu5_(if4;?}tU)DWVqfYb#f)bL>!I{~r?~G%)b*@J!$3 zZ|ZuL@c_B&_2o&+Q3^MDuzTYXT#e5l+bv&(l0cO=0cVaC*FMSh~dfgyklc7eR)aIoyAW$f!bg9Y&)k^RA zVAO40^dCqqJrNo zda^mf?sQ%C(>{DB`q8k4skb8x;4D$)QF%6pvU3goH70Z0vZ;96^R8GaOGQTWSjJMU z1_x@lzxktA7iVs#e9<;;s(i&M`tpIE)9_Q`xMLcUuL@i3L0bvg-JnyN_U_;IQElpq zcTUSZb-dvzJmF`v3Te0xaC6iTwGD(3mTBL_vM8JVKl%7QTX+!5fT4xo;z*L7#qH{A zxENb*l-&{ZTAdl|#P_O>2fFua>OVR&S?tZtudmFGCJRg-U|YT$TH=&A^y@3W*(=4# zPl$g_SKQsq6*Y5l>tO!pJl_|KIUmzqE<`-it9Y8{~k4* z94z8?)*(+D$h_Jn_T6#d)#{!oZfWvobw6u%(G^;JW955{;Tbtue`!sIqsD}JX0@Uo z(2Y0N1p_3Dy_kirLaVjsq7O3cZ$j4cfpm^k29;@d{lTp__gyP`UBM@O4Eext&)~A1 z|3FiVHy+qoCj{hL^>*CS;{LPu1@McGZTyL(`drIuCu_jvc0Q}fC|6`dc9V$$f3z4C zAd$lhdk&x944He)8YUr=Rq)uZtQ%m?v!n{~>p|rw)6Pl7d?+yc;P$G0tzOj#Y6lR} zHDa|d_5&vM54;Y79_uvWnv;w4odfxFCS1|TJk7YEw}}pwT7Rd)Mvq3goVg(;uQJBJ_bOa zbD?E2KDDCLW`Zmt53Zue#(c< z%Sj04k3546RdJx_*WGi@=}6v%qbGz0HW;g)zga>|8e}*Jmo;6f= zL^M2!?@jrOTHUXXrKqW^o&GJvsDcZ!VV08aaLRj$KgFy0!~hF52YYPwFhHh}hkQP- z6BDz1XB|fdABsFS7*58`&)?Z`wOm^76TEfzaRlLrk0=ApYBnrEsQ9rCMl712lgcV- z`?+Tf-gqdvz6%#n503)n$9l{P(Qobk%|ywSpVCUL%{3nU6E(!&JS_f#@yoRD(na>7 z`pu3WOAXHGn&%bpRf*CNG3-1#E~Pez_74?B zR#}3r(^#xUqq~!Di-`jCvY^Wrag$2ju|G%_4_XxQim3Sw_CGlR&;$sKbO)kcZr0=; zjE&N8(Cpw8Sx3n*eb-PF#f9A3!p-PKYW1c0E+_365tdoohl%O-p+=Y>)Ld|Vmh4al zmw-CqKn6rsRhxE4OGBfsn?+YL3OBQ8ovQZAT&&h?<)ic?G${zM-cvOIw1Z;R5UK}o z#v17XWR9#6MLc+mzB3gnEFiq1@i=<;WrIAa#UIUV?6bO)DBar(yHU_vg+ROJAkEvj@lYopyT;wg*S@ZFE6~LKQ%n?xLDF zAXA8j(Z+B?wVkVw!?PU8hN6&d10<^_^eht184`LqLQJEwb&JXj3#q|#ae{c8I0ONi z(~uvO?wiWfCv;P^bnwwA0pc_>y8o2ku0PMRb7J+Y+)w&Gck;xm#TihBEGKSddEPGV z0;#rTtZdBh$dp9J#H+u5t?CA|I%&5B@c%GoTB#{?xaI5jGkKXonJ1~A!dldWr^~fQ zMCHRy>|+X?wWNC!OnRg#=6jit_{s&~Qqb&r;cCaQ z+`(jT5p<|dFH6=euvovlG1IZ&ghbEm*dbPH@OfMz?9smv9dd9|kT#Oj)1STX?Dq9x z$;<2RC(*qT+KM&FD;nm*=ypokdq-V3!$Vtb(M(QB#_k;xC@Rx#JV+-{Gy=>*vEH8J zxA0Gt(e(mPPQQ6|Zh13npjy?^__C{Vk|{BH>*0X+#+5;-fNF-5xSaRv+(40khKoCv z6hFpPZFX#r^M{jC-*ruX?JF|6g`)Qf_sufoD8F^&-pB=7t+I(nE4xdbU)ChN7Zu^#FD_is6qUrULtcCb@JXt1OwxsnGr96I9FsS=_?NsI#RfOo#H z?&4Oc`MTa3{(!Cn)67kZZ*p!ErGo?;KU9adBGRZmVM0cNqo6I;61MRj-#fabQ-5zg za7jMpAzzBerfuZLqBwJyal_P}(62_u_JZlns_s0UXe?70jEiREKsml19lHxUJPYml zk}pQ;75()9LDKNZaTHrN)w^nV(ev8L+A>c*%yf-XRlMmd~wK&MOl7%K`z7 z#L@Z{>01>i{KBTzZ{afnPaP8ec?F9fwENxB!d1d8ikP3s`v$$7w1zfwHraw^t3zw2FUvOR${V9C_W z1)Ld}?JMHR9d4O(KD&{>XNE?u`QnMOMTa7*)E{=kFPbG#g_UJ1`H@AVtusBli(4-< z9?2)Y#2syvsC29MO~t?w0uFMQ=e{5*xuN*mJRdDF4w- zzX1uJqi0Oiy*g2gb_w-j^-n{D9=M#?wwok{^$4omG%QPUJ9MW7w!B7rft&+-@hDQ=;TUT0}IIf>KE9?7MVbA(W*GjSk z6li2c?S1_cnQI#O=ZgNXS<&ea)713g+3K{PReuyD)~0-X_Qug+kZ+HHd8f}0My$`~vfcmO6Eji8TDD$ZzHts5@4#9<%;k_5 zH~9D?$TQ~rC&&judUBUi9IwUVM|mdr1%H}u&0vgKVM7#2#ji-bLsVj}m|%^GB% zPl6Zpx6N=e;Z$D~9O3rnGoW=rkOeo4(eb#^8dW)JTKc!wc!a0EkcSDk zp*ZyZnTjwLZ~QGnH8LA&6TtVAf)l!9*&j!P3xssJmXwuc)F0Kw$2S)fzpYk*ZVMaoWyb612v}8>J3-T+lebI2@LqUtv z`0ctu23ibws*3>F=W7~>mNt1i@^`4!>Tq<%#+998Gh^pR3T58}Sp3~v_mYpFiS0WK#x&k6q|?Pl!GVPmF)j-L1( z$T=9+Y)O6Rh|nnwxiNLgXw>cwM)g5k`1Xf|8qn}Vz~2A(iu56;K09B59kX~_pB$2D z(1bO+bJOeoM`YGEVJ*;b*rsXw|fxwPdZ@ebq&SZ{orsIse< z8jI^CjBq`cZl`pD%bdyS^q``ln1U34!TJ;AUVUA44*Cs^g<0Q{0p z8uk3_&1O6*<4ufbk_Dq^e%|h8#P(S~SlY|&-YMdLpk{};re%-;-ScT=*H5!t+vh&# ztLtCo*)?wkI)R+}K>|rlvM7H~1yloW81lE4$K9)G^1?~3(^@L>IB1r$uBzPeaqs=g zxe!6tz14*gAS~QSoq@Pt50xgeZ9Fj;`TV$FCUv+P`^1V?-9}b@N8ICBf%N?G z$;GXwTD;sna6)pby0JJV>*J37Uy#N)%3D2)_8?|_Pag4?cRr; zYz6-KSP{BWCCHvRTxJ#S*m&kNXUEZW0g%YWW?=O=WiD}V*rj1!iVJ8}<*DEN+#xX~ zYA$Fmc%|FH&AH^I#b>>NtolF98Rq{~>nizQ@DCm3tIxffryIN8^-0k*vssGfkh$x6 z98DMfqU@P7F(I>K{hN50l-|9QVPXxPfrOzM{UW;lrxsSY=8VQW5)S01Ly)qQk^am) z0E9aqTVG=nn4XdcH5w)2HO#DEj{LrLD~3OuiG;-5AATBAGO!R*TVEfznXiBSjhVbi z18*1xy^)``SUlq4?+0>|#G{5jU%w`0h%8k)M#P7_?G-ut`muSZB^j@D+f~i_BY!%* zEu50GnU(3rRvEU_i!{R*Y{#)N*$6KJi?IADL zd{jq83NrD%Fv|TfvZM&taMwo3-6X)PYuikUlgz=l)B*;XzSo^NuG~*a1`5hyzgzW} z+P~TqN@oiqE}rDz_*JpAnw-prfCPX%is%SQ6_uo6(xDg2@}+^1l#Sv!pHzQDwp?`t zIr`I8wHAGyn3?O(V>3A4cB&*Z$RBJtMwP5*VHk{7T7<;~2RU;_EDCU^_7&acyD$uq zoQ~_NxV&)Q`JVFd;Ed;kVlXm{m(DaDl=3|}69tJJs+a)e8S|ILec)wEr(}|S0yH6i{Em#Zt8q{zX2%lr;TKq+CW}_wl z1C=Dqv$nmz{Ju=F^E%p2Xk6X3aDoy)iAo(T;FbH1VQ(ywFLe?dwP8xdZ>;3f=J=yns z?w_c7WjO>4wj<1Gd*R6`gP6M7-1Xx%v8Vd?+382{f%B=V-t^x6%`bn~6Uj?rMZFmP z!mk|$A3bFs47!8Gu>#npsHmI3m(0v9@yfT{%T%Pn`3WS0?xF&hH@$T6q*7z%C(hOb zZB0^dZUT{apwHhMNmdE2(wy+#m%CexYUyn;jHz%9M*RI|ZRH;3 zEaJjqN5J)M z9DOd~p;xWWDA`_MJj+zuy5eq7%avAbBceoY*Ua5`-dFtpfzI=2guGn*a@y$Ey42IE znqm|wJYFMMllk@^_PtnT547s3FEpStz&r=+~YB$J8l* zavuGJ#g3VxP+(O-Y-&W*jWYZg|dq!Dy-3Il&7itQ() zLdzVsKUj@h9@n$V?k1!HyqCvQ0oK*rS6_}?8d(Nz1XdDf3sc3O`cLh&8o%>}_DiJx zxuxLnLKXgbT7prI(I>_~$u7N{(7_L$2ssJbT(mmFJQfl0awOOtnCZ(cIDRLyt_N>4 zh!acd&71qm4_DuP{Y~k z=05Y&$Aq?uKj*7IJeB*+YN6*yEoEf!Xm!NV`M6$giivB+(du{Y?ZFOJ7IsGChxvc_ zw@mb%H~qCN_3n0}DC(4hqGpd~=L=Ol)pzvFG{dSI9*HWXIozyl@$91`s_85jdn^pI}mKRowJ-Elt!)Lzv+nm)d zjC&&`f(DfHY!QEtx?bU4o$xZH8w^rkVD0XqFi$<<+;<_(i!ZL07C2ZD_XrlBO2W*2 z#*Vv1p~wJbVhf#T(sW@pdgACD4<`=Uzw_)HY_YxRa%S2nDFVjq#nj3`PMAlI9jkvN zVJ0tOEIEw}_51p6!cf{EfvMo{u}QeUwbUPfD$&g#w4JEBC*AX@w@0un2_18U*2%l; zP#kbN78Z%QFwc5?K#Zx{x7R3sN|90#?>dJ7re5JseElR&oGg7k;-n z*W$gSlq?oSze`VNiu59{1&L0m#1%7%M8{?36PiJpt-W)5N1F8Wyd^q1j3>aNNE$>rjNdX+Kl8@)zlqcHX+y!?=%R8DyGq zpT(OY(G@H?ZUHskZQ)Gw>v#s*5a)KLd)}KILvq}bO-LNUpPFs>hkEd(~q0@nGrpfrkeS+Qm?1+C0nF9}>H5E4D1yv~94wXq%LUTbM31 z`AHy!hlX^OSvY!K#dXyfXjYkTdb~}C;(=TVz6|J6_ZedoZBgtCkCiWDXCD+x9ihKr zK&0$b)w)9LZghor#NEm{bT;df0=yUBmd8q|E93>XrQgNkcB_Z47(ifl46$qV8vl?t ziX*c{N#q5Pjp0qdLd^iGO#3HWC)*mikTKMa{Vy8Li1UdSMOD`54e8!qcz~tm7KHg_ zu@M)BK9CDie#(7UwChfqG4;lyMt$b7gI5=n$9uAWM|Q-A*8w$EPu+>M+@5R>s8kNf zU58Wwp_Xg2?%H3fYz0FRm)wELs$AYltfs+F)i1zSN(+M4&sdtDt$L7!n_k1-F@5rM z$+@uAynIYIa8P0d$B`$3sy>>*=@mzY`z#vuPD@yyLB_?r-N>%GFkc!f22d%+*F@g& zpNlH@15Cd=c;0=vlW}I{s8;ztVzBU6Pfbgg?c6f_OwsqfL4D=9A3R%*|G zpoWOn{dC9YISuWu&R%3id8I#0h*b#_I~YGK!*~v&rvYfmi+OV{C(a+p7L~Q}7a>{4 zR#4s3{F|G(@CszP#j z@zvs65-;UW3Q{+XbQ^xb z>61ON_z;K~(Ezob9gdVrLRMrcHk@_4xW-K1%ziMUFABlK8Yw}wa@F&Q^Jm50A&icm zN$Sp3e4(JqPO`q0TQ#`0TSMHAxlm!O7tD0EfD3s~*w&hWR_pANNa2bqu5aj+X0( zasOd_cIpLQ8(Zbv?e<>d@(2#Msy^-3CrnX-`cw%_RM}apAYVQtwz26uMDeQXT1o#3%WE3dIU7jiKLKp|oW3J;mKv%FovJ0S z86rypj+lb|XHCT%_6I3S5EXq$sQj`AI8eUV`^UPw$*A$ni*+#=&}52nPn?OLT6=ib zTJb$iE7U3V1+`F|i>MHTcRXdT%T0e%T5v=7xeoBD~(- zwa!;9jXIW^=_E#=yEOdWcXQ5;j6M`MPVMi zH~Z)pULeNSrcF^h{pnqv9h}rE6IFpETHv)ai~E-dyvrJA5MxR*he_UbiXptayeqlZ zhsUafs?KigYz}2wy2Q)aU^!EB@Ob&CZ3CT^=vJH9igz#s`NnAXo4w<=@mI2-p7GvlwGq-Aa#40N$5)pH;|{< zi}y%8?d*xZ3u<&-qWJ+aNKOSL^N@o62Kv<(Ylyq7B+Jv$m9vleGK(?d{Ztv(xwbG} zJ?%E4L9`F(@9TVNata^~cm%Q~{;WT);%g>c_)7LMTo>w=1p)|(mM7)ZvwbFQqhaMY zaFxd|ExoQ#VH==cIzi*n%k&#X*`2m{bH}(w@$W2vJsA|DQ^#!7*+ZOu2&1ys`~{cY9pMZJ zpq~`^XUD@9d%T*syVgQDcL2Nu78D_?`Yr*kK}BPkRG? z8l(?%O-;Fenc~A11@aV8$&|hcD!CqR0x@jeJWTv?j->hQf2X?fM802(|1KXM9Q0zl zo6~PG%4Usc@pjkc4Vx`M<45>~^dkFYziH6wTVO~eg1|}G*qqiDP(#=Kcl`Wp`i25H2_dWCuIhR8+g(U6ja>iR( z$^`UkYFF0XzqkoGM~+PCNlFYGPuktHarXHh5*c0g0TvGn%X7aVDDJN>PSC7dc%tF>g46=l}{Rn=r3`{tvmQqGZooTV088+%l4^M zX<^hsw`&Ubnwk%N)GU=2a-)l4V$G*Wgir*#KkUM#R{)CgAyP^X*T|4lU*E4q-BF6< zl*rQv=*h)%Ph^O~G>^-!9yEk<>j%GId?1ZFIR))#FeBX>6=&W1EZ{RF+RZpsQm8sw2 z@{X%m)4bYy5*eqNmz{v!Sis10Y1#V+ejkP7iwfp_U#mi&1W(a&SKghIff+H_=J&qPdB!~~)3fQ{X?<)FYUrK zz`G`1?P;~NeQZkt;P|3KsKTK7XGVGpl%}=pNi#XRCO>n$ySGZJ;D5}#*tnMUeQih# zOPe>2?p9mPr>)L_)LyQVUJk5ck{#Yg9tv$}g@uZf8RE)hrf7zbKc@H;JlOoj=bQ}y zzJpbefpVSzQf<8ji6Hm?`4N1{)4ueaL#y-@`WdfkG6kC=xAX9-eW+S1Q~YIi21k_H zwjZ7PDV;l6C}E8e%B9Mmk-%2Vtpr~!M*QQ_^#nsw>RU~?{DUnzQFQ4mTiAxpVg%oU zeedk?tKy%(zJST&VP8A8(ddH6Odw@2*;8>~Q)HuHVNXt#v{7yMe(=(0E&d#cESNtx z-Q2Qzy?1Qcie1LXEi_vhiiw?sON^Zbb9lT|Vp7pH-|~OA;mebKKGl%S*-oW}$*e z(O`$YBj-O*t_pMZ*5r)|xWJQ?k%IR~M@0}w%XO0@QEvKE8&cAj0sP?iYsvZWQezEq z`Mxuqy);I4fR_P2;2A_>*xB0i8i*M?0MOV_!5$x_*6Xhi|;<*ApCip{%M55WtgElxnz?VTB5P50;@U_(@9IBEORRx|ciIiOO zc2lsVx7ItVtY}kU6?jyd1@lV6v1frxQK&Z$WCIaDfo2fc4AM6PqQijpyNn=g!m9sqm0MuYTb!`w_EAD!uykm!R#56e=%N8C z67Cp7o!QR;bMr2MK)5R8Miv^zN%s8@blL=lS2VtJAY1cBBJ+PbVlo&=E3+X`vfomX zVc4s>k)4+P{pidFy&*Junvs*v**YD*arS*hJPfbKFFUUAs|JU?#4ti46qLgh157w? z#%p(p`FE`gXMkcW=XXsfiYDA$eHdBFYMiU7iZWo{E;+pMn50h*&6F;wC^*hCCDkuY zI7t%jtSFNs8SCQzz=Jhhy!6^%|yQYCSs?0xwY z6RBlx`TMBiu&!6$i+{~>VZ#^ePLci*;ufO@|01iD4Q0=m7t;5k>A?8)e%<5mTQR1o z{TE$MG@pE{)Le1#h;kBA)NXy-vhh&5vU%o5ToS)UIinmbvN8T@_Ng7;h)u<6@B*U` zFdbpOFpl0H@ z+xiG|ozt@_a@Sr^)S=($XW1sKa(GAeUhCF5m`SQ~Vz=@^5h?y3D)_&I@$LjCZM?H^ zxuZ{dFy@v3G6%Q#P*D96ecjyS_)*Y)p^T}RG#ZT8`W!3Nl?RO4{^p0D8HENilJ`R7 z)K{ZN7?jc;a}aF8Ynur$6?}ghosyuJpA6-?3(5o9K{~^`W;*}OkJjP=zt2eJt;0cG0n3e|Gx!FeD7N;g81vYF=TIKIcBQA{$BsJyqat#2e|uvN{0@9oUa9(U<9j z?3iyAFS#+oANZwjMjwFATxK^O!q}OC;6$2c!Q}D)JIgcJR5?OAXaApTUeI6r5e0Rp zUaGiSI`<2mR2cBVOjggkV4GwdMU{9b*4iblprZm1@yTLDV$^^pFrZ!$&KZ#!Tz}>f zLKHNrge2qYZvhPv9?je?i0{myaDR*FtGzs!pjX2_MFtF-SZYOzuQzKxYuupUcqk5k zSeL@PxMT8uxq229ggr0^eM_GBq}B=4bLi$P>+2{rh&UPwx9`2`&gE&0W>AIG=C&CU z2Ux)@&>6nqC4UV9dvV*eco8-Y?njL7n(2lb2Rc&liq}ZWf$4?R;09cy-W?m3p2F2G=$tGOZFMF&81%FZtDhukc zPB9`~Q^t`dtcsb;+HUFiMoZkACzkJQ()?Osn*|YwLx1W1^R?rfF00WDMRA|luMu3OQ<0GiS!J*u*ybYk zOA)^CD5lSuovfKtpEqag>~iO|nX_a!-6~hER&l>?(ONt+64os$1&YDZz4WqL$gBG`r!Ph1yYn8s*u--uxHf>m+U}=)U)%YRQ6-IB zcI0>L|N9?EJo}ZmyoS_!O?p+6q+})JXtjq8hx|0}{$SSQN>@i8vlh(v&1EyAk4e{s zokcxOT}z%;NgiK0!iE&H8>q*Ganf*mfe^tgLz%T4WdaUwC>gH}F0MIDol2Yuuuo0*?y?Cs_hIHR(_FY`1O(9#4?=mlqzywly1qjz zgWBD#flFq<@jSp*k^8acvkxguQG>A`lEtaetu6Y06rG79)BhjGH^WMf4r;QQTIDKd z$L1O;S8^YHO9(~oAvYUBX*Or6X81Zra#fB(u52VnC~`BJr8(ywzu)Kk58z|_d_M2j z^Ywf_o&qO?479PGZ=1vBCrwlPUq#;^)1?DkW>kOb6*mdH=4J+WN5~f}bt3Ql*scZ0 z!pCy(aOgT?%Zl>i0x2IQ-J1RJwP;ubg4b|12v&+qa((P zYU-q%3KP2?CNVCCe3e@S8x6*2xdS5+I|-y7dzs5z1qOmpM;Znk67C!&U;hI62`1mG z!*j*f#^rVZ{U%x#d;x~$4RNc5-oBbyykW(Cys5SQoaK>mAhA-bxAmQVIY6%m zgnTild*t1sX_W}|vDkog#^OJXnF-jb(!0Q*VH`f6489qA!>! zd5=h5W?hgj#AdfSY&=(ok4@@|WKVBX$ZILdSscb#_okJP@tk&fDNb#`D zvaW1SYuzR2!v}4uXHwAMcY!e!G1@)Hm&}@zBGjBIse9@CUicC$k6V{@-v%G5{0GEL zTD!|$J1w_uxV}+Q+BL5cw5|oe@AuHQBh$bhs}RGGl@xEuoTVtK#`FP2w|>?{c_xUN zOH=NcW7@X)2htTA=8h3T7=&S-Hncyk7AM94Nxx(`wdTBVzT(sQ2U@FV+6&tbCglc6 z(?&k1OOkE~gR&dz56k}&GQ;q@4@PIyL1&R6TTyi!j&X~{8jEgECe3w~U2N#B;!(di>5{szpww%pTiS3{><#RG_lVin~ygULAq6Izr0{1u6*O8|7^>^vh{{#J6aLRPK(Wvu# z(zd@K?a;0<|FQ<$JJZaD#GtAe9GGb`Zh)>FySbG)jb7h+_5{^G4 ztVVGr`|ECdGX*;K-d@&zD~Ng-pcDTwFJSiuf*8o4672|^Xo2PF%Pz$&RSXjkvbLVDfX>9Z!>8)7I^Uc8Ok?&hY5WyR ztYp^?T6pL_Ii*>XPR9UF8ZFx`RBI;Cyr>BV3Y0X^ww3BcD)UnEOz+X#q4tK)_f6IJ z1|jgzXnH7+uCUd=P=ESP6>}2KbGx{wBPMnSt?rO^|InZuQu(W)c;R!SOI=b#|K2>|3d1hr^yUI+mO{K>+`ti_r zY0y}mQ^w}DfvSnNlF$i zLNq}lgIv;sH311~%$7r)Jk7-Agu^zPFP-{D6+56hfWT%Oz*d%ep*t3Q;2zNUV9fA9 z4~zdeVmUXEV@f~R(aAt_^plgq;2;CwhxnRfdNf&891~+%C^cN@pb&$Y(u3Ps;~3W| zVHTRT)kHuF@9|=yhG$4wg)J~WhN%SHIU+chmt>O`9H0U~8PFocK+fa}@axjlDM9dv zDD4vT{yB87g|?i4%`RR><3SAhlhlrIAK%ntRG&LwkL*u*JbQR}-*M0t^4l>S$GJhM z^Jc=`D{}=<@JbjL4!6dwrs(+AX^YLsX&yfMOLj0o_2$${@_r&vO>_jo`JLotr`lj9 zEf1PE+~#WGoZKVNZ)Hr#_B$$WJ*ls>B|W;DnmMJyKkLgR-`?u_Ewb5y8Wq2N*YROM zJD&D!#X;X(X1NX17JT|6F4Sl!QSox#KLeTHckZ2LU67m#fc|`AcGjczoRqdY!(@B1 z?SG&Tc4QwvpNBKA6|?StRlLbpN(Un&;_4+gWRaOs;C!!7&?KMzq3LdYso@R5)$ep} z$6_|#Wb4m%)NQ4Ho!I!$n;!Qve%$+M^`mc(GFmPq`}NG9F=l`DM;T>@5Z}*@UOr_> zpU3=FIlXiL0Ny7GA0M?z-;3;8Tq^Dks-j~UmfdD9Q*S{2dKh+2p`?vBHF1dOnpA-= z9%XN|K6JA=TX`r1fKR4brIb7Ro#uOx9ecXiWxNuM={5VYy4kM$#JuE40sFkE7w;-{ zOS&zG(f@XLL5{Bmj*p&cU}*vAElg|BMgJkh#&{QZk0mep@NsnG+_@w00m zsLjs%5E!>I3uAISU#Ko#Ao#&sul(aDRBwokWOp5r(&G;#+=%?VUmbt$?rWi3Rn~=0 z*^leJo>d{m=EZll$7ktbl$ZvBO57qLA0+0hklH2eKY0Z@K!Ogewp6@r>$6PK39q(4 zCu`lY{XVCQZ6c*$5GI39H^G0T;MW^9`;TuMGjhxG!N6kQMu08`W3zA0isXMbG!0rW z93!OZ!9WrCb%1tx*etYVb4m9g!xv3Iz@3Q|Dxs?h1_&x#CHjqpLbgJCO$P#O_?O09 zDHag?GaN>q6jyd`OzZ__^Wsa%<`!l}Eii4q*fLfKz`$~$$9kls07u?>2}af#?y5tH zl2?s2@2Zsh6Y-t;H~=?PfoM_yS=|t6#%%&FOj6zxq*L2ZYI$!R!2pe5XF)6e2Xa~# z2c^k}Hp8@vxq_)+NF^&N8h#iCx|6%m|6(ykR0XQ9N-hK$+AQvZLKe z-dzbYv>cVrr{J8fZ{1-6tfImS;=RiO{}OwT{ys1LIOZ#GseSg{Cb@KTZ{P(7`I2@& zmPv{L2n?oXLYW>T9wW(N10hd$lxYhiN@e^ZCw=}NyDmHS$XQQ%m~$J~F6EX7MUL+_ z?RoNgy-xFS-1Qj{*CULna695jQmuCt<9JEbNjcDY>rc~$x+-HX4KMw9I$y~8n4F;K z%nNS}bX=?Mlp8t~2511U5#Fik&{|K8*s#RMPes{M($9t?C_-DOZ{Dy<{b^i%=-11z zwqBIGbi?oWeEFSczs(h7Zk_!^*%@TWIC)+Tqq#+anaas8M!q&aCz5F+xV0kTWNH|S zHtmR2%01gP`U1*-ziEVvsJit>R84epGZeB+lSj=$ABBHV`*Sh#Uy`w_=M7xX>apLo zPT_u8YEDIy-jG*ey(=I=;9;CRZj9S!N*xy0Usv+KySzAHtr|8@THZJ7l?sGc6hG&4F3)$QR4LZgqugV=J>gV~jJT%9S zO9CeypmGcX69B?25QO3OZ;}BlRz=4J5A?u}8K}nm#pV{d%V%wHF;1ofgg*yHQwIS- zf;?v^q#|gBUR3Q{2G%qhB+&`Va%lb$9#0SqH6sjU-WkBar*MEcARbpg^btyZ)v4nS+^GnF>;>Xbvvd;0`~6i6 zttSV5X1Hp_F@P~z$W%!u8>f4$R6-UfYzC!CxUE%k!JjQ{(**`e*xQw0R-W{a3w%nq z%V(kl^_I5nZKq#G*8fgny4|x!{@oe6;N4A zE6Yq63p4Zi)z-{wuAF7v=p*HQjW1=9xm96ly^86QVd^;!xEQB9v56X+WU*tK>UkfJ z7_okbjM3n(pp6#Vc0p>Vg@hi9{Nf`cyxX4T{kY}_W9oC}h0^-4_#KMamz`*dKi0Wq zjYmnxOv?gR<(d@^u%tkLp^?GGO1`M$<++h3vuW@P%!!PER<+WS=>m3_-KKY|Q2N@*V3|Ixjr0xduhM6&wz%+PGZ-8L%8)jiJ zVYpf%h0y1CZ!kf2OII&GITN)d1hh*^|>Dn!9yMuOT zoDUZOk8FUT^!Tai*H@=1i9VwwL$uBhzAo6=xS0AHjR@RGh3wKfx0`KgLd=1mC8rhD z4G!EJt*h;wzBXCuxTLpgYWCod>?MHZjCEBPX^J2|))K}i+dNknuQ(>` zTn?6mZ@f9Fc;eoN1m~tN>I1bB=hMWSy=Ub+m}zLfe2;xofu0Gdi{VzdmGc{3N4*oc ziiaH#KdC4Y_o1OPV=1OXc7me+MiEY=KBMdIUtP)56EMFzFZOkKX zf?8#V&Oh8_dk-AGaa{jd6OmQC0U62hQFXUPU=%>pf!%hh#CyXU)I+X0v}ul=&tXY> zFIRL2l4hoGTm9A3@`ITUfYNsJ4Q`l}$hIv%IKfBA-^z#~VHp!2GTZ~-QNz=ku@WFh2&Mh{$Ku9^sC8`}ZvZ|Gk;t>Yc(deM8&cW*Yg>iiO3CFgXMT*M#_xg? z%D66~Xa$Au-=bsjPm21Rn#)pjee;tRKSU6l2*CGNX9Z?ZqInR@&rGlN>--M)Xgss zoO0G`fU`)tz&F3V(g5)O!E>iEVLB00{gmDL{H|LEus<8RHp=bHldqUe zhTdu&O>8*CSa3|AKC8Ahs%y7Ye0Bd4YqEMI3@=5)_1`eUvB~c%Bv!4r_6_^KYxX8G z!f#RVWeQ?bU}QY5R#(Jj&+PJcIoA3vzO9M+v;7mte=BmhsFz4f0|sa?Z(We+25+TBIHKK3eER()OK}$k4U6bfthxFos!P z=8H?~SWXF})s@Yf+5>g&2|T(wV{j;N8;JYe{gmC$ghcpbCtMULU+;KQoTrF;qF9B& zALzkFweU{H08}CqL;v9rmy*BW_%|BT^_=y~NyM$^wV&)8R8dr=V!-C1-D{zI*8m0g zR@3H~8@caf+tvfaji58&$J@|K-~;~IxMddFg0_&NKM+Cd)e;Rqsb(1W>$->M$2p-uAUvqnj8~RT=ms zfC=YpFv~-GtHX;Z&)>Iiq={ooWFkLL{Aj;3`f2oxuSy46LD0OGdAp|Xrso_*p=wt2 z3p1~`M$Cj=gd5ZtWj(*CV|(k}+iYWA-NxGmxv%=Ndhvc)O1M^1=+4TWaJK-*`FEe! zPK_r6J3@i`zx2*`&QT?FoUQ_5IP2AdA=auf<4#5DzyAJaX4uDoBUbUzTb4!Ys)IX> z6?dx=n;QBZ&>#K9ezspyFTPCNEOQg?<)rxz2ZYDHS9o2#R*!8*OJGwZ?GtDuG_#9tgt|UsZCtZunaOH6x`mec3f`p&4VhRmm z42U>`#Q~G@+lDf}+EDZTYVXwUb3#w*^_kt^M2C>#SwgO8fs%Q2D3aArLoH5)aM^&h zw#fM7=f#7qjd`-It!cm?h@NL{THU4BY<@wVt|8TyDC@;$?eKk?Z zcVM~(iz;8^ziqL7*8eK;TB zW*Zf@Jx#%(rWtie7U{>&?m*w=xBhgkZ-}lo4P{+zbzZ#7Gu$Bs2hcxy560Krq8nUd zQ@>?MN!sV}OAjOD*=Ku(CoYYp#=eAL9Gn6BtN!As>j|i8ZweTVn#U@fXYFbnxIg+B z6=I6(gIid>r$yDZoK%mIY>k(X>1f`uclY=nzxw*$WEyE4V2EXVJ=2%4vX$Bzog5|o zsH^($q)>>pW$t_3;{k5d^2xd&*>@=mK_d$8_=DcyAI3$Wy((4A^aF<7w>B@L-PE+~ zbsGpA=WJ0;_r9QFnOB&7V~d2j4FJEjCkHY6I+yp-JznqBJ7_VIX?Lme@9nu%(?ri> z#Cxivh?chtflqBnm#5x{`Q~JLcfVW7bOTp5yG2d#h#{pWU(}Kd?l7Ymzis!GGuHn$ z<unqpM|!rWFmg(*;mT3{rPE5&M1lDT zXJ%b-nUMCMQFXBkB#pJLS7A=_-x}*6sI?uN;N$4isj!;Z^!?8G4~U{SBaSIWqwkp=u~7_K>7z#^kdexO?UDXl?H+g@OEsaY8o1SHs9V)Jt1Vw0_L}O z|7jh+37q{Xg>Pv_D=+WQ0`M5p zfB37Di8nv2u`)XJylh(-rgo1FIp#2;i;QlMHipyxL0$8LbVuidXrDsR0npU09e!Bp z6{qYAUe0Pukvhyw?FBf~jcPI^i@lCd8yp6*Ebz*wE`&NBb{^v;z==Kp5GH(I(M z=wJ63Fu5F2VUqvXM$_01L=0+X_-3)~Ka8tsifHH4A(su9sm)-sFz!Z$LfW?SnTLf2 zIK`mxT3>9N(_ zAfGljRd>SemcYyUMG%t!?YdPvGHV{N`UPfSrj^GqYa5WL_6jNmrJc4XzYfvj_CWD$ z-K3GitXLTzW=DFtCK71HEPa*ZqCYx7f~-tdGLVHK?w0a2z-Fh3W4K`04soNs>Lva{ z=-CY@o302r5eKmU8|trJoe(K$)+4&k?Qmy*cBei(dN}D0|Kfg99Ve;1%I(&y!AQhh zU@esPHMFes)Khv(hGY~Af&1@BxT%q)>S5g z5>jqGJt^S8^sM4{Es6qCLYElZdUN&84$ezZj#kxNC*_0l8?{v z^K*FAqg`(WbanZaW9J{KYC|fM-7KZ%cKXzkb6S#wYsqHz+#%`PULE`-bVs!(G*>$A7Dt{Sb&Q{Lem{ zJ50C#W}RuY@u{j=3$L-}=5XT}q`EeSfw&%i%^9r+>qVtDTR~6Pe&J%|D1J{+K$uhTe;WuYeJGP;ap@mmY$8vXt-_>ou zcsRwZl>WAiqn{#Z1`EXQAJ++aD;QEN!9gT#z&NOQrdGH9^b2@GbPp=TwhbW}x9bqzUJQx&OqK1F1j)WcUa2H%kR z8K19Jv(jM}3g2XL#lec8yP1IueyVQE##BVoh1KRKEV0l3SZl@ebVvuTVg=DfhI{KS|Y7|^Ef0I#;_)701SZOiEFpU zP$dE2NC?B*=7ZoHpkQ%se2verSYijfd;F^?dB!NGz_M9)N0mPs&>PmAXKrNuI|kMU zx*j6zCv&P2yC2S2QgfM*ZiK2@X8Rqt`V*K}F2JJN6k-@1dkM0x@Ll+79+PV549rM{ENp$UzE zg;{c8QD^kZhHb*%13sjgtsd)u4JLNX zH|2eF-0*(p%%{!vr6Zn-XB-h9$VN4?g1_&5b_jpN1Od8%OM}9~t^SMtL&`4;^l#J$ zm`#Ks37a!@7pxg4q*`JM#(s@Skj5ViM@}S?(6I9Ocq7L??w+f?UCQVBlFk6Y4{e?Yq7ac_IaZ6ZzM-tNLqg@Ox-xXj>-i&L zgTFx*xExv~+cwBtH1rw$WI?!c!o`I$V9|(4(nL25ZC7f5lXC&8#MGmi&zoBjyAo}R zSMe)YTknq!4`2Ce^`JG&rB30f!6-Me1~h7E0eLV~YT7=Y9yfLO@}!BVJ+2l8^n;%r zuhn$-fSwuD`2Osjatg0=S@!Rxna10p6*}@xhX3j}saDnEZ~<+Qg!`v2GUJF-JKTy| zEwSaU>E6~+bH(P7iqXAqm>8202oS_D`)te#zs@OjUmDzf@y$j_B})=$6&iZ6)%5k#k$jV+TPZd>6;3RU z!;2&x)zQ(!+5yqYjrx@>d%}XW=Ad$+ecILIuK4z$r9{0qCu_Eq_ZwqI zf9b-?!oHN0=NGJ1gg{fCV*_z$>HmSA6czhS%7Gr)LJ(LzUZcXTLGOb+%}>(U%sZef zkgC}nv#et8ABsoXPgY5Gc6P{8$cy{Z6x)uOYqkzdI1m*hW%3o%onA;T#W2{sH_r9? zv~jM(Jr0Dc^pRMBk5 zDDxSFcsm3(c7Vezq(ilV22;q~Gzk|2bPXF|=!y_M9=Olq7e5@)m@LmKX;&rd#Eq25 z$Y_y$>x#3cqP4MwM)s0B0Q~ZhYwes3zrf))MMe%ey>NT7=Wg1j#YoKK_#2`zp$uel zgm9e44z>EXqfE7zCf(oY4*6v$9ZIX?K_wW;!7)D`Z;^CIuf4Enz$*|wGD`l4(LjN0 zhy6U?pF`&doD;f^kU-L7kGSQ{hKG=OOwJr} z`WX=NT@sw!2vlzBkp!XEH_@z1stD~r#~6CLM=CXIR_JQxOi>M%N%x}Umf}yAN=)lM;w9ChZt-feBLhhpU z2`Z*|Ty1QHY*Ix|v2i0F6%)d1fb0}>tw;Ow&|0j0$V6(iL#m!+Z>>03QYVYKW0ksv z8v^uylhWA0Uh}miWI6O6iL&+&;hQh?Ay-0df(t_aERX+$)9f~W|4{8xR+-BrHEi|edoJ(?tqwOa)yG@$2UtaQY37RNle^FEtwILfD*>`> zLvlkrQodz2+%;)H#SrmoB|*~f-m9KeJ^}dOkpfncW|Zp0=Vu3bXF`EGfhTkchZo*c zDPgQKxwE5j>x{xnW;2pma(@hf7Y;%`?7nY4dM-gw@!xaTlGKTjw2H49aSJ9_s)U>Q z)QLGivp~Yp77ZZvi5HdZ)eT0Oupk=EsDka=iWePtc`8i*!xuS8$qq>d+fL2!Tite4 zXm{8*yy!*#p|S=$Wo6>e{)R3=-DiPEgX3yX>Fu-GLzh6otBMCzYhkj)oa4FVw(A=mHR+K0cA{*?Zy9 zu4OW4`UI$3If_>MI{+>2JEq6e2m$(YTKHYDmJA*41fIaB+q*4ZPvGa!&2{Q}&^uOv z^&VP)vKGY5DFj{pVHOcBm}a0yw*C&#sO+|H5eyF)^_upJS`&*=b?{vaK4G^K#8xkE z|N6CEb2Cj`_l*WQVX#~SZg0ub2y@m6M2&g^%&Q=>7W0QL3&KYvy2}8$VC0@(YtAVP z&>44rLZhhWNoTrQ^t=WB7j%H9sta`%J@jY+VV-{Wiy_DTuEasXJ+hp5jw zFE$sVu?In?Q0#YD`WmIfIuwwT?mt6Zk~`lIm3%<3M>)K?i3NzOg4K z^)A>|wmj;Sb;wlwc{EcS3~*ozyH?A{jiUe%&+uwt+_8MWVn z$@R5qD%cmm0EYbRui9&Vn=BP~*l>uw=Q$C5kCNT=wbW3|hf;Ebi zgF(0eU~RuA_-9;eV6Wuw->ZICP%xD$UF=!tN(C9Y^?G^c^NYQg>ra3C;M>-8wsKV` zuGJxBvsY^l{E>2IRtL^V%-q%P4O+P{7|gPKesQGZ&6Slke>H)~doy=Biw6CkUxMfO zqG$0YJM~{k$8G@KyiJ)b;3%-?xqZW;X8e(&w4H(Gry%amP-0T@9|PIHZOktD7Pcampw=5!CJ zK>PM}1{;nyg9H((BXJ3u!MxH=UP-+%WEhAI%Yn-cu1Je&Ygn62y_GsNAY=1*Zw?^N z5=9fTh9P0F`%FYA5c%?ce!qE~0o}1N{UsCctt`2yEr5M9g~11A}CzIWwc#Lu>M90PmQu9O(Yt$Ig2_ zxpSlm;4G_<7~f($T(If)sd*E+kQ4#h2Km6F06b{7$~r%}an0Rt3Mvj_rW{CFY?;%* zGsmM!@@2DWFhJlTeF+z`YWCq5rO^su0%Si&KzZJo2WtqP%HT)fdax(2cfzdy9+=`T z#F-2A(kGzSjN1<)7DsTC1GW7GsnyvM2R@AuG;6JRLxG&4(!Bd?3cph_-8ze(#5yL5 z&$$JSXzY-(0J7_QaF*5+GxY(~_Ji2FAGL5K12odal`q5>98kxcpx_43PRhhpbzKqE zLxulRTQ3km1{`T(raPj?F=;qbKZj_&IqgC^#Cpdzceg)Ul(;oP? z#Tp`SZ!?W*uYCG)@F<*dDzi~g6t9}J-t^=O-REYW53TEolJUF-Jlgi#mY>=4Hp3qc zHWDW_jY21aOOJ*j0dKHcw(`T52>WRV3(f)W4kEs2X8l9;xE-!EkQr%Rha=&I4lK$RT6KURBAbD^u zYK+_w3~aG%LchMf1^KkWAN-pD`_4R=To8mP(Un>CKOot{F~h2eP!5M~tQUgqV>Zn} zuC&Tr!DAm{h`tuuhR8in5BNQQL2V5o{MT}egl!P7UFue>E+{qAmcwobU73TXr~-G> zk$5zGgUc&nmGcPUxQTqZybWBFB(k3%ZGHy1xX!HbBtlZ_JO>%y{ei;)fnoDS_s>Gw2r%*t9%B`EszZ!l!O2)d=(~nVB3N(cJzmO zc0mgCo{>}+tS2~~1nm35E#qY&@fgb(#&-9WMYRwJ0h>r|09xlnXSa=KgLn_4;QmY$ z&{%a-%HTUOWw&vU9I$Qo78SPc{5&5=md4J-e|khpzlD(6cG?J9s_*V)KsdV9N5+fMH*gUPa@>? zD|;Q>%T>3m!<|*xy~Twx$7idUd06GS(Gh|K0fPt}REGCU<3E9=jN#VgozJgv#K50< zY=Y6$O6mjwNzRn`oUx~QyMDQ-nil%ztIDRv-PXG_(5$Rz9p~dg7Axx0wC}~f zHzx_dikfT_F*EIYQ1PhnsK4V_4g20gnybq#u|???FZPS-k^Lqmyw0S_ww5i@-HK6W z;PCz9w=s1;;Zpkdj?InYiJ)3SuY9xZ*sm!cB#W>5{sDhiEm6$61R$aukGvtBo}aAo zYx5@VTTJNbOY_)cgs9SsK@7XpwMp`$fj6E<&3&5!4ETlb$222NT`RnYUNrw&)45x> ztM98qf^HB*CuekkkBM!Lb`EP%Nr zf6W)7xbNK(uyF;l4!U5Nl9{NWJsh}=5j34^=pTWBy)0rCf{Y=!tgBF#$aT;_fk%gMedH-l$nIEjqE*SKdf+ zqz$L#>@T412a&DyZGO}Zl9!Z)wTv>}0Xr8**enaR+QHVfFt*Tf@P*WvZ?pBFo&;TQ zSK0qs&-}koL>W>M?z|)yf`P8ABx{*%HvhFv=FOC7c2l;>n_~Jw(4$^+KOpb*I-~}~ zs^EKFE5p|)w%v{qlo6{?i^P~A+EyO~M)YAq=Oo#$)VfndTRwcc&TH8y*YZ6vs^1mlmst9DZZ`V)`1Km=RC1xq#P##Fm1FhzH}*oMEk12IG*9=( zk*;~6YX)SS{_>;t3Wxr^qL@li`SVs=#MjtwEEpbq`mE-kcI6sirW}Ar9 z1D#GpI=*Il(Q?EWKU&^p}&@bFKaJL#Tg@rlETEnqe5}tlt1BiB3IVzf#7%8Lrbs zyOsRPmy&hlPVUsvrZ2PpxAp{~5`X8mqvm=q2F~Cjt2X>G)~IgO-5$=xHRo>iG)Ke5 zfG;a-qi^W*AGO8tTDvn;n`zgZ6CWW1mA&Hawzk`Po3MH8&iWEnch=#`H+5<_bG4`> zm40k}$s9=0qbjtEt!_m1sbO}279NqcAoK_tm|TX~rfeB@y#Qgo*OB^x)9$d|(b6Lb zf(LRIk{VD33$747o*9&o9uUpoK!>s}wg<#sJ|^fY`mCgcFlP zXhxH1|6$$H0U#o65^QF?K+tKhIzpdl;IaqzZF5Cr$Qi-_$k|FzBibe>h^ntL-SmvT zK2res&CfwZZ2tG2_IxdoCD$v$UZ=}}zr=6*A3!(H8v&c{_o#nK`=iDRu8%d7=*9^(D z-ij6%h+Jeq(#<-0RH<3qcA0NJb$b(8;-E$Fh`H25o%?|LEOu`ql_WluPH|l>h@_+i zfW$#dFQmlX((po>%yLzVMHv6#(uMUR$|G%1FR~D%P}0)8K-X}U9{f2d+d->!Q~r=V5yO&iVbjgPuiRn2a+ktUc0{ z^c5xhiBHcm&gU5-wxy|)Uz=1d7k%6lHqA3RzRo`1dyk2S4!iOnHoyvP_8#2-u5-5E z(nsqKt*8u+KlO?5R^2)1yoM@lf$qh^eN@~kj$)J~FoJ-=j99W;AQsL2_t#VV-QmC5 zP>H$YlOK?6URlCxj>h+Em(GqIy_mIexPY+#sME{ogKrim!mH@Esf@$fGOq4}`>?LR z&V`sBFiScc`uyED!&})+cM8Wg$^yUG-4;pi9*9r>n|ko<)#UF9Xe+~c#aZl;&;$TE zJEV4Z>_u$no!=p_WJ8crs3aY0_T#IUw7ieKb-L9{w~xV3losM*^?If3|0OP~g}(h~ zJ=x&*5ASlN+eVUI2QqEWjsI$CW(`YIGZ&`cmD?`C0~mB=m!J7zji0+7qNMH%C&!Uh zq|Ir_-sQKZApZi8hL}nCT6Gey>B=m=3>vH%)FNB1Y2Rq_>ajOjtoMOn(5~Vls(>P)NFQjaeNUro{v(vC(2qixgp^TSSyRjh`YarUkHNKnH~EboKy$ z?^^%sW+qWoC0zM`Ajen`9kZz3pW(9|LaeB$9TvUr|5Eg`l_qk+28`KGP?7>!Wx-*eFBV-Ung1E=3mEU0ipeF(5d9$6kR4s zgV=u@9Cta|k#Nt@e9oLDl3M*N8phDOk%??Q;qGV2))j7XNV$51a1-JIg~m}oyu7+w z-78JaC=dt#vuuRLw%t&J9|kx zgK-`T+x1EX?d?nwL&eIQ$d_J3cmC&=Q{C0ws=az-WGn4R#cgFi?*og2qN9YiaAD@; zr9a_#&avqWx7io4?<&gNGX9EOtWu!kM@DXdxxkY$^+XyhZgu^y=kX+2-^5dKtgV=h z_ONxePe((lhTxB`y^X@mn3F%GS_=gUt-X8JX}7_WA~`u)?zKO&(ERw11jiV*Euh48$?9_;VeIvZ{X+| zXZN~XL>)?!!^!c@_`SkOb{c9oYu>Id*Zhug{ehMy5}v{(AFf& z1D^ic@9An{=6-8C)@I?4JC+u7g{0>A&I`&)(*3pTtqq2IB1myHI@zCN3!KX>z^gm% zmHQbj&o^yZvSs|2T)^MHWt|mYUle!3tgdV-VQF zIOD$4cd8C53%oZN-c}$@v4%rO$Cfo+3S^XS9iyvrxka&Rdgw6~99?Q)HJ4w?2ofT) zH5<$mK&Pe&8cbvrKnQgL;qE}4B%n?F*Q^64)#dUxb1|0xWdN}zq9Lj>f)JwUL{2}& zUVgkX?5{ix`VEGXIc)A=!B-Qp4C+AD*2s4evnS;`EJ=7}Gr3vmEWUK|40_`<;YejU zNY)QBDm|FA8(`y1g4R6z;>r(@6M5XiGbAJoQ1OZ_AO}%!aO%K-_+QZjf3$Za`t+vB zkP>zbS?{JuMyIx+g0=_W)yX%zq8e6^H8~UnCds)`Z737m41CI#Bvqbb51>}5udWTd zi_dl39~}$)D__U&o=W`!w1tR*97Gx!rWPLHSV}FR4;}tbAF*s6L(}C6$2u1{I~GFO z1-M>)bnZ8&6iOb#82w+OUB|uy2tG;DASo(M>a3XmL`N&gsP8}@a9}1EpU3nZ1Wu>n zoB5(b@pN%t*iw$^z^@PyhG&JTDCVzxyus`P)bF#Q%=Nd;Y8sEm)VG0IMO#5kHQG6l zq-Kr+kQMK=zD?umLKtY?L+EB=7iS0tT#LUPxUi;1ojML=13XQi!>5F$p&*=PN&_o~ zf?MFyY8@y6a`LBQ)<~tzl3HTG0}Lbhy%+xiIeim7qdx4z@N*?wnp-Yx66VExGsHEE zZBfa;m~kAv`ww;-nD?NK%3VXGZ0I(}@)+r0^ZxlD-aMEo<6drtm2P93S=fGdB|iFZ zkS?>l@-;eIcj^fHuYzxTr9H4!;qwqR8*_HcX)Qtnx$nmy4fnA@qxxTlk;IL!WRv$F zYM4s{d#|4Ioj*6bn;$nE#5S!YcmGU44-=vdQH6)&mE-D{wWJ3*nn(WR)kfw&?A>iF z6&jVYQd$UJy8LgW84AWKvE1_--ADAeEwi3*2L}G$CvXU&hSQGPGf*StvSpA({d?*c zS7c%MQ0tTScG}YnME>qMGyFu4`IJDQ<<_$|(JGOT(BCaszRK{Z@TBeRnXxUsO$Z{t zsbay&G`dgq@%IATY1jH*_0`))dSR47;3RXanJA4XvGX} z(S_zKK1V_OE)W13#wJ&+7t7lD(`4nFWy{TrTd5?~QT9mX;@f9x-6vT%x&|^MNIOxY+;K)OAN*P%i3Mlvgj-vw{p3iMqlCtk z&GUBbQq(a1$=SJqRB1-Ko?#1s{Yg~LNiP|RkPPvkPj zdIAUFRtzbVZ*SE^!R$;{-v22&7k{SzKZ=iGNRuLy&D4}zdA-l;oaX@}o~hToESy!8 zw+&tect^_OcdkZSV6IS%fF;$Hvhae^M`JNl+f%k%Z4XS%9pX5w9@zF)nSURmxeUGz#I?jBK8m~jy+|3bwvenF5U)HJo-49mqHbG?A z9;jo3LTqwbr@VP|_;XwzM&Z0r9QLK)zL-UaaM=M<9K68ZO(}5_R^;yKza}?+Zc=#A z2UyvDEjL@$O1O~3Q!)|y?r)x_eLhOFuqy7O8nt+z;Xdxy4ztz-rC4Lw*gusy{vV4k zP~-+T^_-NE3H}Qc9%@t@$YF69W(i1xZ$cG4?&)yE^X@$>XO#3>@DNL>Yx?|iU-(~@ z>u0+wQ*Z$MDIz1*CHE^DO|Pjx`Wu#N>^+*=a-9A}7;jo(Vz}f6c`Gwn%>BU9#oQnG zqx{-E{%X(MDKt(3P==J6?V{}IjQ3a+JuwRXP7)sQy^?jC=a*{NO}TZ|UU?6%fh#|V zQEfIeno0knv}na#RnA)gV)l>r9tEzbyvQT8GUam+n&Vk3g~YUmTE8!A9ukyoUbbG7;t=qWy z?@ehIUJ$2?N2nO(M~6D~k2aI9%883<&mH1!;rM&XFB8t(J7zUVZ*TtZT0kWe`<~sp z0B)aB5`u_)BrW)9xAfS*aKdJ8e{OxBW!#L8%@zY5z!t6hP7j{`W;pFt25iv24+U)6 z*P>4gy-UGsr7utJ1yT1?*Zv3UE)N>nIEe_t{h7gazP-~fwV8FGBHQNQ)-ciJy}QyD z;J(6|6C(AD-`Dm0*6^%mb^{b^4VcB|c1K*!ezZ)E7=}`Ff-mw<5kD)z@0Jr2u{VT2 z&Wu2`cTvIUVi}HyroD>PlMg${*Wgnz5;ZO+BqPV)^PFi+Sc0@lNH{K*1ID7E;hQNJheq4}w`&WTq zKH*wBF4~qmvOPG.KUe4*_G=j+CQ;88Ch?%CJxJ6?7s*gT~7g4Mm`-`ndTj-^y*7BKr)9(;JykchSR4_@W=94rKl<NQ7o->;t&q>g3lNrZ2=U&oEG?U3DdTPmbv57`tIrBv>xDCoK=}xQ=R7CQT!G!qUktrY~ z{PX+5raShOcY9hu=KUKx=(X6lS52KLKt;Mf81k6-R;?WHS0x^QZE1(BaW7L9O?(7W zte1SYn)p_sYASt(U9XgKCttn$FS&`ktiTa!v2fiDI|izbX8r16vg_h4Q1Ppo_x<=q zrn3!m0U%Bm<0`J z)qA7?yp&=d*^kY>B5@7t`~>XaMaz4`s?~N8?RbhF4%qrCoXrd)W+FRG+{Nw)T8HfE zd4TfI{9Is6Ok4q6MlYS)&Kih5tN*bILy~mc!@0m$pyMV%>i?cH ze2k^7&h8Wx{T{z|%uIv$R_U1x+waPVtJ@GXJh=huCEnES%folw9UMP#!suh(^_-|F z|6f85<27f({%9#3hV6ULRJ^_GWGB^Lir?#OMu)l`Y~OkSRj_=^5q-I`5^L0see>?3 zpZF~Es20E9_VHrt=zC8Gpb>dnc$HR#{d0cJ<_C$1N;0?~M&Z!`C20GIB1~Lo?Sa$F zZsCNyq21oapV2)_BfK7=?e})tjWMnA6K*lUh=8B>)ohSw!K8Uc&6wuJ23RUU9 z`d&`sy!NUS*Y}!gtE8_609ZHHhex)pu1{mP_`1LS3T22SkfOwui0qI9I+ayYKss)5 z*I(5!j&vHe4@pfU#dwn@=d0Sd~ zWa+@tf^va2Z1A!@!|sptK%x!ZxII^PvR#dmC#DcA%Fyzn)6Kw|Hh^vUh+>E%;Q^M2 z2gG?OE9sVC&5PTDNubHP$&A|A!vJ%Pkmsngv}_(*&8aGjpR)goMWwpjk2qlt`kwB# zaDS0sv_sBB@tf$bVL!m(kMg#?>p7%Iaf<91|)_4ONY{cJwYW|b5Zy{>;wkBaJ26ss|^`Rwz4vDpH4{80+vKC_CG z^iL#lp$89zy7I&a{*~cQrul)|l#ptKGeM{5b7ie3Pf%&c)lh?+fE&9-w!d9>#5JX{ zPzKn2!1e+>MTRbJZ1FoPdcH`pe~r#S5{OH#L$0>BqE?q z7#bfr)VcI2^J2^IWj3K{+&CF1ctQz$@}nZW%q46qVs&m5L~C66)V(rBaxYXqQ}yn; z8iCw37JxsY?qo)!CAvqB#5;I18}vfD6Upc)4!l{z;Qv5RH)k++F8d>aBD4LRn(7Dh zT$MAHm>cO4N7bj#!A-lv@4~zYj7d2Rtr+&|NKVX z24WC|EwPLg1Bw6)8muCbJpdouO1u_A>N_(3@=V)IFNNyV zOijo1cyxQ2cy6Q}S5F01TNfO9qIdH5W_eb%Zk&du+yTtTM#;?!jRqFUXW}|~E~7ga zAW9~0m2dlr524(6i-A!meUZ08`EDhCr9bHcYp4il#G2c~BhZoHSucvhmD@&*YPW8N z-jsA=P%n_;qYj4ZlJXc!;0!}zDksnV?2-7f%=xeX7&bSWrxJhT|9t>=9P9ow+dX)b zva}G=coL#4POEqC-Xghvnfg|3HswB*yhBCp3WgtNt{m6-urjwaOiD4arY= zXzz%R@=A*j`>wvOTzw)A&_uQiH+_hWqpVW}DB|AFo%I~hLuK8{a7(+4)c zX`4UhY7YojQ5fG~mx>!+L5iLH8Hu2iE!rxdNQrBcym1(^d)8-S3kIPd$-8QQ9etx5 z$O5*U%3iBv8?ct^Sa^Yh@zD=V0xr!D{V{&j%0$%L*nh4Pd2dE&bGhtT;&N!NUw&ZN zR^-1kjYrZ*(f|-py!NqfV*N{8eQ6lcU{g%7?s~tlL29&1OzD^CX9Sr(@Be|I8GUAx z_O!+4ut&8rr5-#OG^ALiQ188XQ!98YRNW7Of0!@w{Gf6T+FgzxI2I$P*CX-D(Rufq z0I3C?cT2)To-$9GSb*ZkwhPbXYgCU>I(U5)AJ=r`IE}PQUPp!^b*rvVG1?2q+Q$<@ zbwQmQj9?ej<|Rr4h;MtF`{dF*<{P_Rgy5Noj>AhiUn%f}YGZBj&BNsF-4)aF{w3%y z&iBMtxFJis<(gopz*ZB!<(Q(^OVI8yR|cNPwVdH>D+Rb20GItwe)>(DCB)>2j7_`@oT?~ zBg87Fc(D5Bu*(5EJ4HzI4eNru)pOGA?>os%r|-eTkE`O&!27=iv}er}@~g)+P)fQ> zf)cA>2n-5AM&P%LB?g1sLw&}+MOfPD<~=zg`Bnke9qLc1TOa4#l_$S~9-8+_?kh6-CY_x*5Fz7gJY!|QVMKR?V!(-Z71H&oQi@A4bgX`E+`g1Fpd2|g%RI`Y&Rj0+3dpdm`| zEBk+4=WBB5N9R}V_~Fw!G;khxAd?nDOVM}jd1E}h=PJ?mS2Rz3%>E4rs9?k#C}J_6 zF^@YI&v{W(-2h^(`|~QqcdhA;5KSPxrQz0})2pzCM|@_C(q~(PcgPT1YcQw9rm}%) zb))~2^ce&6R->@+05+pPB?g=F_w*LqYqcz>saHaEkid&sMo09g^b;m;;Ra<+=Wpuh(NOO%CCweY?R^!5r)Mq zou*O#p`yTz_!Pl~Z}{@9J^T)dp==Ib95N1s`wXjLD+{bPn<5Oq->7&2_-&OOU8Y!{ z(otzPN{)7^=w-QZZWeaM41<82&;t4g)0)~pPq@g)o^TAB#;*9=R-))M)OQOvX9`4k ztVl6+fzxZOnw|cVA67gsj$Yv_Th&zEU9-l_ti_DZZ5xj{Wh`9WWITVbu}(1Hkkfrr z>G|bfQ8Q*+S6#}=o*!dVzCFd}2GM+H3=n?AwxZIGH3ujCiz1yy#NB$ooo|!S&lVHy zsK@O(AR$@_9LO15xuRxBTCG%FRp}_~5fQT)`x^W8hq-BjDB^F4-1yHf>|-4|0fsw# zT(8)^D70=K$=ZH;$wQc@JP*dkp5%@c#p_!_WIY;+_Efk!k# zBLfx-1RvGm&Jy!ZQ|1Q87cDuOQA4-vUKypQ*+SnOLkYOUV3B4rf)kmdO3ttf{%x4H z9uUC(E6F+SY!UghS4z{CfS?RxHIJD)HAO>J<=+lPZ&rUKaKgY3XoPk(!6`-uvB zuy_G$g`&Q(cZnY%b2e`Tur7anN}c+jCY6A_)jkmb1r<1!Z{!7OkqkErHCOK{K6#m- zt&dp_#%5R?LZ&}ZTL*MG4-ZUsP8T^&{fnWE16NYUhM?Z6Uep_x6KCNYw2k3*(IkGu0Dj7-nwEt?Fkr~T5CR*f(J&^8lvMB@3&0*rr}pc!xE_T;J@z!E}n?#rGS0a`aiHZ zG0F*y0OB^MipZhKLB|9UH~Lu|py-kdL1u5Jj^b0!IHHY+b7oihyJ(qI9vcv$m6QXz z)1+8)`abvM&*Ao=Nv-BGj(bFXn>;s4K%F8rj`Jrx1GY{S1|3O2@N~(fvtxTI7~%}_ zB^k5=l<)nq{trG=9HIId{Rvb=yAz}QG=7EN{~2H!z1g7b#_UxFs2h=ZntYQCKlF*yhv*i%cN-cfB+pTI`&V49Ef*-wE(2xEbF9)*u? zymz>rXBpWBlB6jI;Yoa{( zmUOl4OwPO@lx%MHI^Cg!*cFFz+Ra##fM8E6rYv?dB&8+w&v2|L#ZvR;0jZ}+>cPVx z*;2opvpheq_m{~tK0)J?`&g(Sw(hATWJ%1$f*|dm$K6SskJV1ZX&blr^Zl~_wEUTi zOr7U#xf^JIfl<{X?wT@-8fq-;f&1mho|=YdCy6cr?Ar#sH`BcXP0CY*9Nt|uY7P1# zfVHlhsT;el^v9%Ikh%0^GH^x2zt4!Pr;0WZT>x1`M43I6N-~7~ic`*}o z`dSPOvXLH>$=Ov!_d7sj34N~`eV~e&b!>PF;y01#30Ga|Jdx7oL{4DbQ=G=Ry&^$wD!L#&2hDN2 z9|0ks7O%OFuL_BMCR8tI@8*}5NDFrXDrSb;&N+0uDj&TT=&?y?c)~wBs;Q}P*bm|{ z=#t-NItnzFll#h;4Hp5<>l$V6G-B=i>4SY>eXOx1JEwKsp`pf=Rf zSb;X90pzqQ3y1-~7y4S6Vs}q4_%Fa=KQU<(^`@q``5|?=*EKv0V8B-}Fu;ZFkSh=} z$Mt#JDia;#98EuJ#!G^z>2D%#bWBnCcDO%gwTthG> zXB6KR%YrK2rsfFWQ7rAsD5lc28P9PR3x5FNJHgB*$q}akM%8xVTg@QcdiLCS7DhY` zKdI7BPz8e#21ww`KM0y&Qv%kX(|SrAiRlox=+Q4Ou~Sp_u87ioPqDK#xOlm65zxXn z4{eB>_ynMOKKmG`0(189bfgSk$DL#5ql}ECZk_y&YN7@RrppW2 zCr$rkmBlP_rr%rJDwn-kB|i?IOX|&XG+YfkZ>8n4?7cfXbg|bOe{$Q>mwjt zp7?e}c3X`y+xrz*hxxo;)-m~?G98KcKN#%t=v(G(--@lYAEA|ruLg9)>CiV~| zU+O^enp)-%^QW+;Ud+xOcXrWg>%h>ll&06qrgmvGeczDJ*DDTqNU1V#gc$qV^=$zO zhJLHGwYVCck_cktK% z?`>KBVCwlDL0c#W;Msuyk=BO~74M-{CM+5u=I>~IbtvFrv~_< zl)!z#K*xm8Z4qsVN3T}#ppU>CZ8<{rTR{&kXGu&)6XMOO&AS}Uwn4#OUI-u>op^&X z#Nxiy$=eMPbHwe;orAtWIXAQMvsZwE1V!9`(nI(;`|S0AV5eKKW_6lf`|knbFLqV^ zab_`}uvqV17GjF!6MWy3H@qASk55$CfBm|j+{@b045^U+Of5ni#h*6nDi7kS;7Q7n zm(?{VYY0Av3>FN0hTQ|najgQM!t$}|x>K>m0*%B9*{z5nCHxSRFA0%TnS8pjOWp)L zz1hOfoFDhw6{*CQkAqWlUdO_Kyy4ryV!%fDDnmvgo=T!;HwYLCV2@}BOs_^rwW)j$ z%g~E|eGlC}4qO=ApDM#ysUY9XvuhB)q_t-2>jQN<&SZP(RD;%G!=K}h9Tq1!=~rWtpXN$9!~l3#VWt)3A4sch%ywp_boM|-@qd*; zm&RhEo^v+0`-2eyKBTuUTuGUs-lyD@n!U=+&}amwK{wCk_Lbr0mGZp>>>Gx29W6;7 zpmy|ZsExB-JB!vY1$=yph!~q&LA+ltzP})07}?fqj_5qqh`$Gd%0soA(G)$v$W*W2 zI=HbPg4DH|o%XvonTo(`lLUdRyJ4`h2m`*EiAKnbCp_oj1^C<;YSHNXjRc)pkeCpB zb~b-|5d<*oKt7&wv4=#U9w|rBmpLFxIDRHs$uXlY>vgEw-B{!eeaVx0mBVdN8bf(- z9|QGx;~q5Uqb<3+9l}S7`12i%BihmLF>4xVj5&320_7`=g&j)Uxk1AeRm`#IPq$T2 zhrnRmyRljVi^?TX$gg5J)Ndzm5dW6F<~T}pAMr|%oyTKjRBlhY*gGFhZzLCTJ0opv>ncLiU zf81E8O)KL58KQ204CVLR?Ii22*L-t7Ho5<>aqx!gjW5Abmhae0aY}P9JC#6?LVreb z6sjwh8Bqh?S<*{F^SsEFecaRThl(|q*!5Q6zi#rDTm%3oM$MvgoU!cduI0WPHkPvW zyV){asW6Kqwtv>9rSaJ$d3{$PiKP3a62(a4Tw~;KUJs z7?~w)q*HH)hAKu*YeN~7o{w_xG_S0va@cJlmdZB(@D0h;*oT9|i$co$;u4WIRSBu; z9=>0eqz&efi5NR}Vw7wJ9Ui8IwOu~YIlBPqo;()SSKsWW6vH{ywADH()HV7}CbJt( zBsky@Iv7pkR|D-@4@V!v2q5sq_`$(U(mCO37Kuk0ZBpKkLoCiqq)CzHXW}~q% zvVj4a+t+kk2^j!-6+TULJEb<>Li2;pBtc-yz(jh?)1*uRd{R%D+&Y0l8+0OUIOzRI z?fIii^UuVq-=FLIl;N8@z4ss>oVD0+pyAf>-GLX`D}RSxUn%C*X46FYycrwxnPT63 zt2XSqjUn0TPBDyS&SVX|p5WoDUJh_rYb%C3t3MxfsH~2EV8L~9QtTFvm@(&)hRae` zR_M13GH4iZO+J!W{r&mJ*{yNLRh5+_d2yh55+m?u{{2n4(xzPQQFWP%-~=uBCF_=V zn<*;}v3)JlcUyGGFFVqKcDSgi5`_j6x`y4qm2WITMMGKTo1pqD0(feXtVrj zTJR$utXTM?4-5oMof2?@sd0FMmPn!+O z1|OPaJI6~iW_&CW0Qw_c3%4#d9o2yI5x{dNvsDC96>u2Hj$TR&pprIo=Vrl=kB5Om z5>fIT73u#YATZVt{7THDnjOMlGxLE3eZOlfoxD!shzCGIso_{F3FTlsU6sA?H(8+J zjfa-9fuO`ho5TcDT5|e(pbg~xG#iX>jlKfJokP;M!AS}@*lzZ9f2&{xTSGJ&_y||# zbdx_#NDcSnd+}jy=<_6BjmZk6U*1w0(ZvuPfGEON(}>Pks})txhK4sUg3`Rf5T*OC zglRBZY?vymKAYVh=M(A&{MnZ6jwxDyq~TAHfnGrW*VsALCK!_;qd0b|Uh%>hQCBZb z#EQUQ?EI*RS7J{~Rl$f5qN+}t6CfOh$iDxk6<;qkkfCeT0Xby^(PKi9%X7gBPd;wO z269mUmBUsahOf(zOR{2;TA%Lr%0#Z|#E&ekEYY=D{+<~Ef^P%?nI@wsvLLa0EawVM z5XyQA~k69rf z(6wv8VUt2>J|vc51OCm{NNU(9fiE%5F$H#LoJ{Ct`KN{>8aP`y^0^S|xH`xKqw$a+ zTm?w{8c1n27CLBW>Pdyo;z-kaxGkxrE%0)1eZJQ~W-}#ko&cAM4P{lpVr4z3FZlGQ(GLg$s3Nv+~?%?OCFs2nMfu9;laD|Jyqzjh~cS# zOHkkQt?+apHJ>i35qf@GdXC!1N$U!6VL?cxeX{Czk>fOvVkFJ0fD(TkR zv`bu_M5uvGj#8z$b~# zMr}bBL*-xd6r8xqvvl7Ay@?P;F z3vK*&83`T+$hFW&QT0X1h%_k#`c{7{Fzp=I1w1Bj9{ak3hhy-IQiFS^@0UgEzWIY2 z7?h@fq#0)1@OwDsK#Lpn1sdYQ0m?4CHXXJ$*5{oALHZJB#!k8GtGMD7E`e0p)7cLl zkB^LEGk!n}_Dli{BUTyO*Q`lPcbio;{g;)oZ$OzGQDc*Wa1%Sv>;eCoj1pWV6+?@8 z+Po+=76Z~-GZnIrXYt_OAVtoukd+YiEMh7jlL-x}yDKq1K53rlDMO|h)ddVVMy+WI zzjGo=RuagtPBYGUzdMT$o2&=PoIRNn^qzlLg@WxYh!R9WH~%RF5L?pyP_TAPW}hTv zVo`-MeRqL-D=CB!DrT#EIE90xi&EjD%@7o6GxL`|10M#Qt9bvrw&0WxxSpNiOzXMv zK;X0jzN!I-2d+ykse;eL0Gt8qsFq8jk)7&c$oo^1t#~y-uM96>91((Y_5hxT_fRrQ z`MW``2&KzrZh=#P&?ggVNAB6jYlAwQ408el`oNkHVP$C{vCr@c?eELY9 z5|wtg9%BsJ-p%YQsbgqoT`@kc^*_)Az^BDL{Bn{8hV@bjVtV-UDSX6&CYlep$A4#_ zph}r$QUJo|*(!KYcEl+U3a284*jHALdYTP-fo96ccVL1;@sr>G!S)-ppe$){RIopOxfkV~Vmu zVp=kVk#NJZ&UvYtO7K(+7DIO)na%R;?y9T;tDvBp8c;Ol0Q5ZX8%ORsdB`(m)*CW5 zTJy}sRlBrM`yqh%>uL@R{>LId9>T$;axBCp!13dL+y2(rM)BDV_m00Hd=-XFLQY%% zUdNisTh#UAPb0|pm_SX7%QE&pHC}(xaBFKcnoaW!&d6T9yz~M*U z{u=g5o#F}hLc4&>Ne232@+Y&;Hm3*}jb<{ekj=L}zVH~O#1XDTkD>gGa0VwgH7!wq z$5}b!Em*aWAXgcD!(>>jD=}}Ze99iE$n8&54X*B8{nS7>^fGwIg2;3yPeJk^qXe0i zp`J7Gav?7U66$On*S1jyT)Ho94Fn^$JPq=Auzzf4MSB&@2;w2P^u%??y0FbEfCtP#Nj^TSUwwX7|dGF`0vbe&(x!X~Tx2I0}V9!;e zb*sEzRL7o;Ar2`+^wXZ7D2tU#W+k1UJ^w$DD1}r-SG|Ln2(|D^-%}}{Sa`mxuvgqe;kCl%q zkCWi`hZ(wci7R410WmB}37lbLk*Z!6{YtAt3s}d?J~p~kxx;R9=tIVvXrMx`J~|`G zA3ZS^*>z-U_DOn7?U+RiJJ|Uu$*6XIyIoUM{^okysDs%m~BTwZs) z)afr*y{FCssS>mxenm~3%zLB(MuYnV>hTsOcimYxacH+;CK^IgX6P0lm$O^H?zc@g zeo#ECp#rYRxm;RD(CISsE{D%pdg|_%k6wE6UT;n%EXIG^8h$TjZ*@8_+@l>{IK>-J zB%HGlO82X(YZ5WZa?{qw_x}h5QQ#_EE?+Q)^2}~uf(n6>HPL0<+uI)m5FS7Y)q)B1~aW@o28E@)6j|{g+?Yi<*;>zmC19xDGFE@v<6%6aoVR zPs9h6jPSdK^7G88WqrPS0CNCQEc+J2Wm1Cugce8(7B7IT!}p0VL#As|1KxLn*iUYq zeEN>%8@uA;t6~Z*I1%4sx#mYgA&kNfffxU=0ruTxek$wVGJ~R~2%PX&nB)Co)Jtq9 zeNN@4a+SvAy8BsqLN1MA?}iS*lt#Ns`YB*Oxyk;W9^%b;^x`?9a1G31Y0~tU~2V z(f1jwm$Beqp?td%txEjjcicW-6<++)=l8}xl(zxl$ahcY0&&kkCB-X)eIi3UMiVJF z(GYQljEr>k%iq|rY)TGmwZ2o8u0c@Ay3&9@*4sO6QR3fy&C$pw>n{@_RItr|-%UkO zyu%eQCA?p44BA;EyD5tg12#R`i@?xc!DHIH2gRlvbJDG^o=?(df)g0vj){pjccTAm zV#sI<^1+(!*U9boKK|nQ5`?PkgV3!lFBNl52@sN-0p@yr!QTeyxO7=xL#*Fp)G1^1 z@hQ)oN2OM3TwPE@#gegwRXhKAwNk%VjHm!lX%%a+CTX^dw_3uRH3J=s`wPCG1EKh~ zWj(KAI8!KQR`5edqMAis>aU6mUPJS65IIkP+W%uAWmPVxlFil<4o)1(@s#p^XcgYr zMiF#uzAd-YL6tfQeVC5r@LKFb*qUn0pMYnrjEm4W}mr# zH+taD+BG3PL&~+@MVjP2uTGHzFM=nUT9sL>T~&9aoFK;YrlAi_cDEa&TSuNHNLen#KATUk^Fn?xZWGHB;w36ufy}9%kL6Uju={y#O$3vt z*vHE@Lc0{cqB8J<+aW()nuVX8S9ysi51L4IUiSlqmJKu-6v}lQ$ImR+POHayu)@8` zg*xSFKW4YmRVn-T8OP<>L=+EDnQdl&%!I#hWsm0Avq~+hh*i0|eZw%F4_VywU!og1 zU+m`jwyx{>l0joI>X36ii-Gbq;k#9*B0PDMMt>Ap*W>oFa+a%V127Cs<9r^>$o$?#;hPKD(=sMbHdV8sXZcqt9gY=7@Rx&3MO_UT19ZvT##T#M6XcZoCe5vr8i75rI*U%GXS`+onH?A{~thUH-i*E}zu|=PdHegq|0fXnF-*`NcuX*r#HLUR3x8hy;@~cd=>qZ?To$`kKHqQl z|FevR8ibPUOwV6hxGQ<~;zYzv1>YVoT!5ld{l2v}Qo`M!|A%j^>jd#<;EC9`xAT~o z2Dw_s09(KTZq|3rj@L}kqp`#6mz-xs5~Akbh*e-PhP;{oQX`@&#U)}KH&$;2WKj$| zl>$+EjIu+&`RWn`jU8+1W1g zWaF~GlOYBav1Ht*FNiSysb$Ua2h5`dXgCPHqr9X(UOK)H6D(Nm+T8n$sN_c_K$T7Z9 zR}?uWwaRY-g$8ob%|Fh2q}^16wp1=Wj>;Ol6=KtKMbZI0R@GmzwgahsQdJvi?(RU3 zI?5ic8MzrNomTWaHW+MkN1F4+>cIa3CzEKglEGa`yUz|elAOC6l5|4^2_T>B?G{=7*+D(1igbP%nqTmT)^ z-RtM~`Z+>9s*gq*J=)3r$Xr-!t(Ejp*Hzh5tGMyLD(9eUT>THs*=o1<3Gx@>KdBtH z{;l@;!yy%yRx+E3_^)wn>{)8DH+`iD5u%r8MRg*B0_`2wzwtjhe>y+1cI`G7tgdgQ zS!gS)osA4kx<7)CtIQS}EM3MTs=jUwjP)1ZGOLpLRBd`xm>6s82nXW!PbHo^Gm_oR zLjl0p=JD4!+S<*B;Rp9xdCsN>ZfBld3Vc9Hx73awt`t>Ov<2dZVmYYb4=7LwXIJ4^ z`X}*Qx1yfNjr2-}Jfb@Cb)2rj2iQ^uZeo`>rdFG`DHR4%RyqFD-MqNiqge?YdD2WHo>EP!2qwA-z8P?M<*90`JFeC%ZmbR+1u}sHU9UzksqF| z-PFM1-_8o74#2$&^A4oaW<-~d7d#CTib7lAn zRuFX+5V>{f>FqD~B%*(cgiDp*>3T!%iRk*&dQ^8f^yOLSE6vbIP5pm_UCPjC-N5uJ zA{(sOYZ|7Ak04Je;27%_&BgRhW~n$Z1=0A)g96y`KQ=rr7?@}BMg#yYeNXTNzE|xS zNCPmzHqk1n$ zj1+zfUW5DgDhx(mJ zsg_Cj0f7ney6<9-)sj0p4E6b|G>!{i2<5AYpuu9AldW{3^O|>Xt>8qg2*rw~(gLY? z{%4q)``EAix`%ew4_C#~Zlo$UrR%ojM#o127_YL76ZBf5Kk|LmS6B4uw}$vl^kLx8 zW!FT0Y65MoiXY#HbTQ5;=^eP^@J!DZTq``l#KB>bep&G8ogXDAK@S#S$vePfc{{P8 zdrm}fHo*^}N>5Nm^Ef^fq9;KFE8DCX2y*G@yth+9lRoSdimnq4j)tU4#S<}0<`FD% zUI;!lE3%AD{W2(jCR;$2{jR;lhHviAU*Gff2tNTe$*db_YWOfmWW-{|b;$RZw)1{{ zXEgWRSZM~1{)6iG)6K;xh_>5nQNv^}Tt+6{-1cU0-Z^VQt)m<9|Nh(>I&%dF7xeC&fz3$Bx1PDo^%!GHF;sZIJM)F*&3FiX!5=pBiD`o&URn~}hO3{c>iUMo(Ty(p z^7EK0E4P81?&6#IBZ7Y7DRk3|C!v1?Z>$lwK75$etw~_1cF_JGh?zniJmqP8n)|em z`FRzKrcv{p7E)C@kTVD5RWj@x5OJ*qcQ%&s%d}s!Yz_1^tD*4wUq7j=tPnIR__TY!j@`sqr0D6BCw5j7f6GXtx6O^;>xkYE zw2>5kYd|Mkql-``8?DV1*VA5*f2nhA?h0pzMDQeAwRc(73KaMkE`E67zS~{OEqwVW zT2*G%f49h(_H(yy`qlz!>k9a4X)U`Homl8s@vjj7Tt3yOUmiBD&!dG17JVfYE9VY& zqoHBcFf!b+!Z7Z>^WAOtqg-<#9 zyWx`Jy*kv`N~tCo&r$e4_$lTXxIfdVmOZZaubqk;k2zfUx zWDk26brut-`*Kmk7v`yr%33p0R%M05^eDuQUWwMwGfMo^nMpdxF*i+px}V9R#9pvW zPXN=qCsJ^q4VUQEBobF1eVbhG;C?~5GduYA&bRE6CLSO+9{fO+ zfo^l{C$_7le^aZ+s$w})J^abAV}-|M#cnRksI4dOo;3HRvuz8!mz~@Dck9O!snNu9 z7)Gt5?y5dGWAIBsb1vEOcQ>zo8uhnKc(jLGSBmup=Qwo849ZGe(jJLw)(>=Zjgu&M zgfN+>KeDQrVUx)4_pz&~8Lx)5Y%0r`Sgg9%wIgfXq8HFp>@m+?J((N}Adti2vWcgS za~A4sd|dUdKVR}nryQlNg5GvQ22^tH^XGPt%lV2lqnw(RpxBJa2k)4r2?-N^O;$J+ z+USSJE_vePd;I?3549W`C2u!dB6k^cHvdS*UQqVu%NdsHa#adD#m>YYw=u3bfcc|I zn|X|?U|TuMC#);WD##oT_6_oxs*Jf9tK=&y0uk~4JEZeQz6>?r{Z^WGGnqilok+nc zd7Ji>)f-cc4=2uFh1YsODm)J}Uagex3-J4HIl!6VRBZYm8t;dkm7@adE+)4S?L!uF zj`8cOov5!HoJ2FB4+E_Q^F475ow(N`A+;@sog<6{$KS5^q>J-u{dyI)dwBN zimHDoHmQjuUZo4|oWO9mxbqOo9Ykf&ny?DZ$Z>@UX-R$hrl^1;Cj6hHbB|}T|Nr7(JbaT zhdJH9>;C=Oqk6RIbA7J&;q`jH(hWr78s6N?Vws5K+k&n3sL;|`g^WAQ^N#o}!3LEm z+p-8wv#w^xUmkS!+{*4SD-Qs!JFLb+PXyZ4t`nvMSV&zS6FOWK@+w-%^y<+(vz`=T z9cF|O_+|ZA(XjWmGBCeN4+WWI@bCh9;@sDLXG!_Bb&pOeKl6`l(@KV=nRz@Lqr`nK zog2tCxZG4fr@~wU)Av3x2AI&}%Yec0o)MQiIaEz>NRl5)Lyrq;Y$>|RlUd%89o?eUBdv4JQ5K{r? zfwMcK;Di?+yFdN!@Tsnj*z6F`7LKXb$^YGUP=~5^TPg5=cSojFP!SKqGHN#nFE$ix z1tj12a61JHH6b)HV{H?A*<4`OE4;21y8@sumIvPO&Zr*o?ueS-DE;Qrwxnu9qT`6E z*eu?5ss;L5inv)hI=U-`9`2nI2ndmhraP@Ha4g|>7a$3W7YffmQ@-a{BX|k~ z$YxG!Qu|s2Lxsylx@=rK=ngh*je<*AH;`(gMAJ9JGQ^O)ivd{SSHK9ldDC#-4oc4@ zUNqt{12iP|Vghh2ygdq>Ni83G$*4JfuHsJ*uvClyWhETNTc|V3FInbTu0)PuXmdM`nUUr%dy@kLBiwbV zjT>W6KP9KVIzyQ^Lx7nmpUK)aydr&yivjx-cg^J&n7sz3r@Op&1b8XHeJP?2mY!#w zr30|bh_W|{(WvMcEmM7ZBjPt%IgulHn$-QqAN>XQ^`dt591y!_yQgS6mS!(?+wC(zOQh9E2AzCACdn z7m5VJVo#{m*CKsjj3(V^9;)OG*<$0?-$dL#T}hW#k|$TL5-=k(rQ zL65Gw+-q(kI(He+*8$3&D`ISF#~5Aw9!{oGGi`h8u#nFqNUo4tXVITU*QlX4A)v#n(FY8#+u8XA9!>p9>L43A&NmE5Tj6HoH#Ol4y_iJ0VYEHe zWJZ@uT7>la6e3OoRt5AY)1c7lkW~x7gZ_~^%(Cr9Mu!sKQoDh#>ZGG&Y_qVMsn{-! zol5gZUyK~l<0CVKHs0N&H1J?%RI83gG=m=q(tNb~H!rRIaeb>L4lmd`tvcAvJ7l$d z93a0L53*86%osV|AtP(14S0BPAf`_%9+C6u*ewuPMD1}8=}{W7mq2=}&#~5fi&RYJ z37^h=1ZA2N!9gY-d}3?DU`2wZolSIg0HIEGQkB!`w;Jy@kjviZ>X*E zn|*$d)We3pf-VmQ*40y<)ZT-+1Hm6jX*Qi@XIhKX)Z@7aGa*?sh(pn#Dp`Q`ty?U9 zx`_wAU^Hq+BaCS#wE8mPs;s9M!LEXiV^W{nO;mpZpXcLn;fm{o+6vp8fVIw$Vg&{Rcs+4~c9mWH?w(D)Mu78j(kLxNl0(2k%VEIX& zaPw8hJ;_)?aur}fP8$RhCJ;jNH#-ThaqNIP$A^Gv5R{Z2!tt__vj<&~17Efw z2J}ot|K-CLPQFHs@Afr5NxT=g>3p}$R8=cK zIHs0ltGqiz@rp-1U-8)~onM?;Y@$eDDkH2)0ZSmLLU&$>?IzDcfedEZ951#h{v5wK zL#U0OeKFq>ZDwxYSc(nv@BrCgl^C5&I?@ml!aoHEQ5u3 zSsr=cO*~8_QpxI&j&-PvUcrE1{{5J%%t_do2K0CTizw39lSZGMK;Za*(;JhUNQxF8 z2n`s11z6~{Eof~tQX{|X@WBZjw!{AH^}op`_HZI6O6f7kGL}P98$sr{shs!5vneaL z?DGVO=#S+dy#QR8QadTlcEI_6IzQ4z#YxhMmx59GD8s1T-*vXNkHmW95I@`Abi3c) z)daIG%C4v^$3Rm6?>!LfjBNi5@PD8nh_6hw^y*!=zoOL;R)P@pI!C{GK@J92Evq8N zHe4I2I}{aBbf<0yE3*k^mKGKF{YNkkHyK$(0p&-nR?Xn$paIF@sd_H63yn(J4aT0t zC)PsM=IN%>1kJ*pzpkN%KNC5MfUqF#aSvrJF6r=4aDB9RQV;K(|ohiG;^48xZk=`^p5qOhM z{m5lbAdK(imk|h`vXC1uNNjalIr`VL?p=6sJ!IOH0nBG@uS|z4*Q|x+C&H>t*fD4kh2)jVPxx~0J|t1vbnASis1u;rnP7Ka+}ox8rb!AbIkeFf=$!qg6*`516J!SDm|;Y z<_R!o#8b&FF@%$ZqGb`|_2BxaoB*09FU7O}{>$KPO02Dw1;!EMnZbJvTx#NrwW|s8 z->mQmRcKE<*%v2%SB*TjAh6R4{t~1-E{j9FY};@7?PaWhR~AjOl4Zshhm(y)zWK^S=O#Vu+Pjwx@{~ zwSKT@#_rjKu##>eg#!tXrotsrfzhWFyW;?5$ZcSd2+zd|t=p<^rhDB7NyQ=tQl}HI zzR33Tgw8Au08t@=elj|~!CgW|NzesqPy2JeB&?1vsnDXf6kl3O-9rSK3FEm7!gE1k zn*%B`Y>!xwo+x7sPfnZ$%XE*@7IMMKHaaLSVxsK|&yiCfiRbnW(|ZXojE_BP-Ysh; z7zSHuQw7fi35p1GXo}hBM_MixP@LEfMatW%I$gO@nAXC!@h-xO<1%cIk|#6rGrFjW z#y-qIJ3rubSO7Ua0tOrx7VV0Bs`JiU(fcwMG*HFK}3_AxINF z8PAs01w_ovA64;09m~}*vdWi(*%*3aU|h(mv%g+_-7qy7AWdrm2rijGkUo9P=u|4# zYGDneRm%ci4wO(B?PP0+@SJwyBlimX8V-yxmdg&(%`aalqVZ7RZTW({^O()y0dU3_ zJ-=MI{a|`4d82MwBJp+Vi?Gb@wGIQJoDA4p0_O^1QOT=O(N3=5+-?L7dUB7c?qE!~ z-FXilpDYE63Y?g};S0pn+~8&-_lF;PolNnWve*_T8@3bbDH?mmecd8#irc(g42Z)< zklw|{TUm)S)2xxOku-J{TEoMH9LlA3GmF&`#z7>SJ=9izB}hNM$ybThjvc1h+r~Q3 zlGRfrZLi$)Jh@{4d{IM!2nx zUOu@7Zj&y|1G}lIPnI{Tpu?mygOr;4K@FU@qR;b2RPuy&7Yx+Qm`X=Vrt6b+b!*V6 z2N3Q%zUIkF>*5JFaT9jlJ>k}2G6)s|*D(7O&^@U;oge5PvQfE8UOKVj(|+0(HlRP-~%0zN#CA@X-#R=WC9TN`tS>7$w+q(eF%ORSgaZo&$AN96Srbt2!x5 zdYk7Fl2-mo$Fvz*j(qBVPaGk(Y69hqK!Cx+lR+@1K+a@8sJR?QXL=yk{WYNg4LSEFhZ9LS#sv1WWg{Kj7u?)h6M&_7U(}@Z4MxXY;d{)XhI$U z-p`eI3v15*(>4$?cyc86i36uVaqA2Mn%9|^)Q(er&#qs!m-KvlZ8t5n9enK9ip6Uq zyPI$$@g0tLzM6VHi~vGax=jFn2ARn815VK&-e!;7gvr9gGJ3e3xrufB33ZApLM6{y z!t1`Ntuzi518SR z5bc#S)0SYKgX%RXJ$XyQQ1%@2fSu~@m6)5sa4Q~V6JSUYqUK<>iR$7mQ%+kYZMjL` zR#h6u_J^|VtbIpjXCN$OhXf_01`db<CRsuoKU=^TW5eAGjJtrQO~r9!yIQN5#~G zC&)7hHiW{St)x8sDC3Y~YH}URQ@u^l%vYf6Q)^~LTUo#arVH@={iOOe5Z}THj$7+4 zrPs7$GgdoS+Ht^ED6kh270RC%G04s(lTmrhD8t*x`6R{Miqt*?*L3@aS8sIQxc)h| zmVB%R|7cHqUeq@JOL=jV1xsKc7WhA}VxSL(n_(Vlfo zt$?-j&%yLB3TegQ9WT3#a>~n@XB&f2UE{3YFZZT{z<-*cp|;b+J6?Z>a_$JMS~B}2)I@*V~h&vo#*o!Q57IVR3TBgBH3*?f!Vu(;Hlr zhCc=DO#@e&HjnLKi@UN_4GL=Y$<1e1G2uQegU((hBu=wAP{TU65yaMK~wL`!r3%`z)qwn zr}t@#J`in>2NJLy0JigKAAfiPiZgbq;373ST>?`W0j3V_W}k*svGC0TYSx70w;+R& z{eQvw9^={pXg^s^ou~_{&Ew!h-QLR25S!AjpESm;qEPweccPpw-{aNrF|Qea1KO|U zsCc$}S26%;;nBhhngz}6KQe??QK2B2s(33)Dyczj+`B));;bj~U3&!6hmYTQ+ojmh zQGz}ou9VS_qQ1r_TJ>5^_EQI#3-uvu=4iGpk$2cVvhfYQ%*}u=^XZn1@$=X#rxQ44+O8*U=`jSl6ixhd2NEEnCarVNlI``| z2_-4vTC|x1mg@0oiyd7#x7B=@9&NqR_L9K?2i%sCU}Z~l24gPn5v7W|$4Q^pDF==)vXvv*K^o)5Bc5_wius2gz>q$Z zu<9z{BnIFqEkCy=>urNFn&J!tW?+w-@RN8EbI0WR<9~PyvlqxFUHdoKCH!uB-l(-p z&S-GW7O2vD<&atJd*#E)=-c@dNV*JfVJzWS%a ze$!iiJkDiKNd${!h7``LT;C@2+&s*oLDD0(j#f?QN%I#9ejd6Lus{0D zDh5u}`d#ps{YL6$e$blheHmU`eTFk!`lP}dJv!iY?m zQNXy@zd+2>)!VyOyfu{uxG_Ozwp^C`EIaTvFxidZ1ff|xAJ9Y7px6+fS z{K)6~)YX+x_?3SalT-HvbgRx_5I~%k&ciE}Z`m{zzH+Pw1f6t9u;BWw|65%m$FA}9 zE7R0hcN+PDfF>9)V*Mfn`AoeD<{+SleDwvRiK|{HtPIn5V5xQRt%VfvL zH?;<9Q90+?&sR{JZ=GcghK*KT5vt*9(cprWTv}q3b_Qj->c$kIuxqhM>C7n=*-#`MJM>)duyj}ZJoU@kyui$zk%!aJGr$T!$3OFyYwAkO zk}5CtV~~D|+fSFLssLYg_dVj6rufRyu#9#ySv>KIjlBb0Ptx=H+a@FW2Dk0hO%I&7b2}Y&0QuJW~i5+GEgD<81xx$;k{B4?Q?dlpTC`|1wr}r%YcpAjhlNa^9_}RBf2pf~dTT z+tOhY^j9go&P==(d!hH;?*pSH6kI zGw%K5%Q9j{V86&VpKB}6Mh-eyThy@r?3>iE`e9%D?!sD>e1P`V5zNf9F!Rw6>fhWw zX3r0qx&S`L@m&?XSJ2-|0V)>^{zs9vg%F5qL)|SomQ}g;PKs>|#^s`}zA`i3`EdU( zx70jMWi@EkV$uI$-ffVT@*;y)Wwcct8a7h2x6RXi~0{s zzqZrLEvgFH?jnKE^?#onjAvMqK8yyi*m#v9*Ak#uV)S{Vewwl+NfKTRs!YdWTi)sB zXOO{Q_V;VQ^anCmdQk(RJi;59S8jUJ%^#A+<-CjRP$jx2Mb92)xR>%)?^F@uKnXuR ze(MQOsAy4;NLo1Nv|!P<`B%#8;pL9Y?o@-twA$YF9`BK&vsdn4lp0`Y?0#peo}Vu# z-&%v!VV^!!vK04s<=emHLQZSjBsJTEtsVY5$pUh)TpbX$OdHO7JmKw}@8c%OH(vqo z`70cWy3fBOy(Nt0NK3DRcCEF9WZKqrl76+(9+BLlo}9@>bl&l9D7hu z#?SPnglu)nK}0Z7d3MQM-f6p#Q=>WF1s7(GXT-_RzlVHMyZlMLTNb_z3M(^TE=wHE z;1=~Iwl;l@Q%K?0Sr@E=kI1a_1{+-%?68`u<)88t!~fEc(S#Y^RbTiX^KsoB1hXeb z#d{zO#s3Qn>HLKHAshGkEaSzf^RVR-64^6^u5z{pRT(D;!wcUTfnRjL-frYs_$-#c z6y5^eqElFmfV0Qa{(44_B%iV+Q8tCY?6LT+Z+LFt%T})T(ZTTfKQNPA?ZGrwWSsx{ zzR~cF#D7$gx?b@e0m#^@j)*qD4Xf3#Z+fwVyW+Qgje^?w1mb?ys%uUErGxP6?#GIp z!P+};btHcN*k}VzbF(NJ(>2~igkHfPd$7T|6}Ll0bN%d&e*vW>3EMr^U~=$k#O96& zmpA(^_cq}X0``>&kBN1g{9|AL?!yheu(Sc=YT?>n8Ci-BO8sY0AE+BK+LO9*jSoi0 zObqUn%s(N|yPpQPH!A-Ey2ioM5RgzN^X%Z&8nJ!Y3`h(W3@hDD{xbgvjlC}i9*WJs zzJ&|_M%d^3s!^>}vZp)y5RF$GcQuv(V1IZ9Lo77e*WVsS2O3pI;I7;ga>S2DmnK+h z>7bO~`NgR2_%s1ar$H~~*mT72<6}MdHrU%C2+lFuue)@%zWWQ58m^z0ytbpITZJeW zyQhs?+;3cog7l+zWGt=q*m>=*Gz+=62say7ScNbBu=D1;oVoqsh)2lQe6SlsB!0{G zn_arQce&z4_Wy1SreiDN+LRxkpG`U*kwo0e$DN0!2&*(7M)%&5VOcc`2LeE`lc@NW zyv~j5um16q2s{z&AnT3dpoou8v>Fr|-fUs2MO)pNKr=j^%x-F5zare1Kh17EV0woK zI)g}VC--u7WOvkFDWynQnLObME?XQfOr3TxRXbucMQe&)3!S!HbuCm4PqI3opL$m= zeiiMvAQ{i2V=-ELo0V%JGx{ENZwk`6cym15*c7o7B4 z^y}V-$pGFxsQXK$i{>v?Zm1%8nAO;-th;C$m~q9=Tt!>&+`01~tA1U(tcE7oH`2iR zudmg#KNoGZLWXnM%sm!ede~Kojij%B#-! zQ_s7psTX4cKq(aXcPrGMUivHHb<>OOQa7e%hbjXOc~6vVxNV&R$ES`BSLt5wY4;FK zz!E`^P;0Li67FPmeaC0I!txS2S>XDu3USL^srt^{sene zJXY|lQv53LT~U}wz6V-$wAB3Z+3j$LD0)~%$EF6<4SQ7UgWRp=*kl}-N%mfH3h|(Z zV{QRH>k8wockN#?u1AVcn`>QOHx?CA$O@N8v)~pyZ132wGe7yB<_i%^sM2ROx2ZS# zWP+G}y2Qca{)M==3X<^`kh`1U9B_c?Bk3Yod^EKI7SJR&(RR)KXElC#eR&bSTPPG< z_;Il*;L-1$O7`(xY2~AxFK)g)^BeJQLOJtKj_6gS+B%{7DPBqH9jKlBllTE&P^F`- zarsZJtuFJ^0Kd?uMcrLT*G{EzBid=}=Wq509mNDiD!@T$)i-1M*?u~B&ba1BnF_s; z;;Y!2*vhsC-3`IY(5uJ%dEw%*Ql&)TWY8JO_}09|udYW9+Z~Bh4&hR1YaM>)kMaNc zhmQT6fD>(4jTPQ=efP(W#t$T=O=@xP^B~sOgMg7Bg0}4Rxt)vI?^N~)sNe|d_K!VdQ*aa~2aB?cv)6<#FvJsdQ@HUPOjkT?L6>#e0U zF=D1yA0-q8&QE~Q`Pl?Z*vbn$$DBAQ;7r-yb?dv7uuTcKwR@AGeQNq`OcqfoO!+=4 zZ3r;~5xtDm!5k@;adguV2Lpki_(1AjoalOrn>ZjfZB&?6c+Tti!O^6asjYI*P|TdL z`%vw6v_%g+NM`UVco^jEP3=PyN5X}@rWln$n3p;9?auMYzaQ#1{4rbNh{kfan_rXt zvzwwo31pv2;UE3>_WA$hR-3FdT1*&W!b=Kb#<83NPu`Ah9`hZcrYx!A@6$%zSB~q1 zP1{Cs^V=wbMFgSlhToZ%h6kmzar@7Z@en1i@?mI!6^-PdXQ}dFQw@7pnQo_;p*XM?SOeD!<+0R_iGUO|zk2AKX@cThzRj z{&$hOW;#O^2kTlKt38UpR$W>7=6Wl`s2cLQn2qTT(uO&oIn7-5+jSW^;|WIn1mQNc zj|P?>tVtPdIlMbPsRl&CMa$X4{&Dx)yWFU!eXH-`N31|J)iqRe=^j10srI^TYNa-4 zkNu;4R*3a`MLJq?-SZT9Z`PHztRdsH-oGfxvrD*OA9=q(AvFi^l>4s{whGfb{;}h- z_3-CruyHnaQgL~k&Z!PPnm!V@jUdneddBxX)j_@WYnC(t>-_t{-8bCkaJBqk6J5r6 zDQe~WcR3padnc72#?&`fl$`naV>Vn9TZ6W5<8qlumt*pR;ee06uB#T~m`{et=&O}w zrb6$e>&QOpvUvE z@tg-aiLy(%ezzVRhFrf|LIHnC%#N6Ctoqt;AYz~fe3vYKjn?^x1)zeJRnc**l#!D6 zFYpNwLHo4#Q{=}$1{CwviQ%ma@!1F5mW~iAxC_j!`Afk%BlTZd%}OKDPG(0e%!U3t zhw_rqqxNod;l=4Yp1q;yFG9Km|0CVGix+}(O-fW+=lvjyt_6Mx%97uoryymnf>3eo z@TP11Vx6w`-U)D5Dk$EVcUpU`dU-~#pWQQUGP+S@_i-3`ivu!Vti6GJWs?=rmNRQ% zc-P~-K6y_*GsMvrX6SKO4qa7Q<<2hCL)6i3AHv%%!Ie|1v_$0J=>~EcOW?O%a^-kn z+V_}VKTU9stFF|_mu_Il1;-(I^%Ac}JO7&uxEkkzc->{RV8xXy>OU9uurr?E9*a@Rqq?Fha4CDKi zRDEw|{PyBMhk_deA_P-HA-nKqs1f3~0M*`c;kAiVk4er&wRcbL&l;Gb3_)l1A7Vw( zxsv@-*o~Lic003-{_-6L*u6@RgXziKD$7dqalCd6Ay_U(zmlH#bf`K7;UKFju2Jt% z`T5V0tImfEFi3@AEhFy}%OS4fj5GrtK(Ui|wE}h*sX&8KFPwlhE-YtWaCUD&4#k>f20@@&!y zqnOEeh&KxkHeQpYDtp&lF1&H>`IC}&9OBad;i?P=Ha)mg;#Rpaj=wahR^;5b`5aq+rBy67RMcl)A~&x zJJWRW-1~8#)L!5=Ti|k1TLOB`C&(6drL9o!jP5SQX6Nw^sp=iCC*p1M4uVpHpNf}W zUywo1%z-DowD5Gob2d>A{x2}NQcBcEn!xemNYFC~=LaEf9P3J3(8OSyt*#oR1H#qV z<2zE5nhE!f!~Pg~LM*>YgOl^QdDaNH(5yAR?tx`#8G2XqQ@jGR9-0~@SKx#;>0;2h zo{XX9joJ*1mmjKV9wV!5B(KuDCwamD0w*mIAO?%`sdoSEx92pVf87pweQljrF5dIS z&*RWj;YIGbf&0Px9S!CPMn5f1?rCRV=y`cO=+{gtp~=L}o;L@^!h-Sf^Lr~^9&B=X z`HBtq{?pj8#1puM2VY{H{q_ah??xnIS1_-a#$E?jJ?XXbdJ=K?uxzb0C3=Ztt9=@Z zxBBt)cmHt6=|zKuGwEJ&#JRHA#q&cca`Ew!*qKk{sOVq+>(9!xzF+_GstLFlCNh7$ zY{(z_cGCUEF4#9Uah&bXj)zu>IB{q0YaY!jn!@X^d{xQ6vCAZQV0T)UH$o`96x4U9 zVw+i%zGf{D-+I5|E#NvntUr4vAD{U`-*vMZZg3O3t<$-f6_k^L%kGibxD;!Xw zrPaAa<+1_ErA|F^@4+ML2aiKtNo*h^6 z=^J(-LwQDPe$6}O{q?KwtQB>7t~}|tF?wi$Cjgsqa_8TDI{=5ll%wM^f4!eL{N2$? zE&HGQM^loV-Zx6KhT9<^2#MyJvzmL=L^7sWafg|F@nCH_v5)JKs-TLA1i zkL!Gcs5umrkBThL85s!^INdWc05dz*WK$piM)M`e2a#ol`|syvDfBSw_h>pKRxWlv zpGdO?z+K~RFjUnWhjg-P^xxF%Lw)c;XP*TonN=s=FDus3H%m;FE%%t7BuolcgEds4 zDZ29Lq#IB(o{FfeW=Cn-lpU1IEVnkJkU;VV;CscPKQ}dh&q1=Y_eb^D4Cys^UlFN0 zNXkeudR3kkzOJS%TJg*h~Ml*i~g3mAEwaO3!;^ z-hLX04&5l0*oB=mB%N)Kl3RBixyB>ZIJT1j5# zv+hoCTm(JEmNn|?9x47KfA|UQkxHYa6H8nnG`rT?s5F(=S=eCgL%I57frJXB3;RiL79!1Vu=@JcE&MUr&*XZzst`p2skj`TDFm}ZZCNqe?%TyBPtrTYO+Kp zoyk^*=0*AJAj3oq*%{nOY<*`bP6^FanmYfE7K*%Gj6{OL-rW#~pYO)WIk1Ou9KS@I zeMv9oSH&_=HyN9fpua z(3Lhx$azp@dbG-}49B)>e+x0i|IxLOj&|w^;#Sj*WGT1W-Y6t?3Al=z3{;&@SNDEE z7lznANr*9Ys)1Zl;wFlh7?5-`VLGfzgS%lIeVYNZ>NA(|itox>0A4t1ZF~*3Rg}Q1 z3#f)yUp|BdW?N!D4c(2w+6?T5X7e!N#`aQsEv)iZ{LSgMqijXL_dN{y zpET_}*Z1-ZX*IDGk^iftl_v2r7;-MLNS}uG1ALU)JVzv4De)ankX!k5^8}pubwr75 z(E!bp5(XN_`eK)73WGpMloDQ5?%H86o?COIO-c&EVD_k2Qx($aDvT8OUg2UVWFBli$% zDS$a3wy-Q_OGY~^j5@#pqvcJ_#(*WW)CTi(P$?5&amJ-d8ZQ7 zVTOq-51JsN!e%XG5SF4sUhnoIEdbbGWMrKV1cSWsxD=1tc?>tH2{d)u4Q@a{^@f-K z^=B$+lW`E!T?TfbKA8YMR5n8Q#Lx42i{B4->Oy2JFG>|B?SM5ZCp7 z)2IV_k1w8IF;n%17V0B_oiZX`hU0Ovx7tLc77mKGPR-Kwm*Oj9*-A}PfDsKjU;Q4n z!+bq2F303I9x3nlDB#LXlp%OyArB_CGIJsu1Sx>8@|oMv-%wuyX(-*>m%E`fqLBAF zm+rPZzP7qhy+~TWJ8rEQFlO+={g16W1^11R^Ph%0RBpUi-Dw2Y@Sm~{53){rM4&!` z=SQJUN8vq!+oTyT0l`aN8}AC=t2JBQ#k^v(sX5);05rJM<^AKdfCoJZ@Z^{Txu;^0xE>C4u1F&1Il4gz|bs7?G=JpF*WFlEj(J@3sf0ZQgI_B(F)_6 z;~8UgZAV<5pE+w6>=}K>0T>yo-?ABiq=9I9j4!8{tg>Rmmy3B zI2W^ooI>?Mhl-H)!TMjB>GH~na6RnSX~5{i!IQ1ybi#+&J<^xjjxd$fHnlXu)BAvjZ17iu1YSF$1COg`#X1v??qRv2{Rbsz9T*)sdwM#HP%+7TTTR z(37^=2M|zNaR4K%XiMm-W2@f*k7P&=H%bIaZ{tbwhpP^#BaxERfI6yPD>J_KhM8B3 z$7M|*P7Eez9`^6Uj}Jo zH4Rr9nG@%5N9=;JV4JzIW*>9uKL);<%IC-G0d7J9$e9Oht@ue`cHYx-42lNZKYA_t zD%B!(e#gVOK5%Y%@o88FC{iZFOk?Iv<&F7Z{2X|0tSPB|S0NK5YA`{{y3q^&r)DkI zdCy>N;_DcgZT%~wlty>Gt!X*F8ob_&o;6&zZeiJ48>|aa+-%>OtxAbc6bJ-XuF?K% z^I#)~pi_}E+m@Gj=v1S-9(EYSv?cOJ0^FGv4`Rl{J-|HK5AsAOEANPYFoU80ab}Vd zhVcDlnGD-z{woo!(PXe7e;nZ0+qD|X1}H19A+Mjd*3V^-s77N?INEvTRltci5$(7s zYVb{L0w_smW{XMf5o~wI3ddq^6pSafhr;B{h3eeu!UNk`ww7^s)}7Yy4QuFfKVNYW z*Giot{{iIu4f3ICJ_5m+j>SySMX)rI+P3nbbyL%MkBs5ofo-7pQAEk0@#r`2-eF>p z|34&fs8u>IuKiD>gnRx;fb@7AGk7^>e zYbLizN=iyy9*p}a+=_Ne9#DlYk}@{jrZ@}2jS`A=NekpPj>QYKiAw_hm!Dc_#$vIW zB||sP!7|b#TO@VNdBewN?xq_&#P(3)tZm?~MV8Qw7!8O)=0XYYH3l^3E53sd!3Gh0 z=C9mp-xVNq>G|6gTU%WcjkZ+@Ji!^ut*}_%rNU@L^^$2RNNk|(FwbIeptxxVaGw5QvX_{6gM+D!#29tiHBZz`#L~dS6**vu z#sWL#;{v_Uq_cgE%$G3r>uUDU-BDie%19k)i;0%4jR%665^Y3}TE9x(Eh`VKD>Mr_QyGe~mc_@X^XlqA zAu&iTF%+SK^NY>_2r!V>0>|4f$`6awu7;5bCCO?M`pq0Pzwj8uEI>Cbjh_PCI4Lc= zt-(H`z~e5nOuu)1J=z|3-v0X|46JB4jv+XkNCV8YDKX&tYpEDerycX^smb3g3^S4rqI5R$xwdTywl+Cq_VLl{sE_yZnhHO(}@j#OxSqc&kWt(x2Gcv2U zr@xmJfjJx!@D6DhuF(IXE;h|BFz_O9e|M|s{MOu`{0)sJnI$w|?1+90N*PAN8%(mM zrBGz3B<~||{GTK!EWk+CkrI|SH7pP@!dQPy1fqOp3mmtrA6%N?Z`H6{DBc-sSD#Kj zGM-VAgPo#9&7XZ|!HInyIc+4@N!PVfjuc0O2UU0CeX|ej~i|n6{s?>NR%I4KwmS{)c(>zVnNU-NXcn|oy@VPZv~ zeO16#4Oi**N^ZSi(V^U{@YT2k0;cI%m=fcQdja6Os9o16NCT3fpRTKC;*XxPZA2#2 zYw%}-Pph7mn@VEa@G0cK&Hcqcj-Ar;~HA|vhst%t%J{itKT0+ zs1Gx?Ji1?^)e#K{@II5jc*TO}W0paS@0GuJ!_0|tr;!@<{{wI7U2R&q^{TRZFc`FI zd!;V)_c)*8{3RF<4FEtV)mT0dxUe9R)Xd?32eeYtYGDaymYa*a$ffP3!ro0y=4JoqnIr-;5M+?KwXTaS zbZ3b!f(ego?}S@IcX0c2tL|Szo15fftzxGEz* zo`$>6X%X+<5-hBz*q43|g7qNQIwbgqPRf6duN;9BlQ;7|C)k?PVpS>!ym5TWElF=h zK*vf_lQm+Xfl0tY74vj@hHQUL#>f<65d8oP{Q%Sp59J7Jq1+TlizvS0tr=Vk+t~9* zdlZCfQeY2>r%8lRK|QNEaNR8T;~A48I$RzDc}pMg?tjw2&3LFgKmwoJteA;*{d8=H zqXwUvpB6ySY^x?LSp6|_+$oWS#~F7(?e3%n`q`w{Qe{v8=$C@}&Q8V^>Nr#J8@gD5 zDcl8v+FXxSByTXrV`hf37}Ppm*XuQ>XoV(ukQZH><}@X+X&Qdqv3u2N4n7?WL)$nO zv%lr8@VflYH?9oS$9tbqnCQ2drz-L|34x(K)j^X65+YduMlHqAkNg{lL$ zaqZD#nfLIx#!&D;QT`5dk(gk1$_fMQCvz}iS|#5=w##i@rRHfuTq>I4F9qtiY%S!h5)X0Tjn;Q^-~ z(K}&G#TT&Fk1`(E-e^a!GfhDZ{&65E5>>;o#~zT$+3mbeyzo`%2A(RNr7QQj{E^2ibFDAr20@9vRGM$Q4tj5GHe!bVw5 zaR-To$6CSPgS&Rovs4fzC~|vrik`t@w~Ae$zr3~VzU(8HV1cB8~%L#pG8(FxJ_(q^Zt13d)hIjkv(fpc%=<}I*SxN`FKE(nKNs)}9}*iyHHz-Mtz?|nwxFo= zAfqyqW5)Iinh2A-g$T&11Cv&uNzn4b4isd} zlMAR8GjN>Z@Z)kvX;N1(2ulY?T=E_R@n@-6vUHFPPf5U@IHznU7s=)J2vR(B^?+GW zf-^)`q5hqINveY4nPwCE`|S)wa%4mF+QaAGtM{il8uAbYs+$c9 z{OUjk^IBvQsQpc|C1x?EV)LMo> zXfEOH5gEdc&H7O-i5^vQ;a36bt-8uM;~Qk%RzPi;pk+&MBpAuscx?*`vL(?O_L7*? zFK|nna1Mew-CJm;MkNQ=fW&e`Euc?JzIxPlB1*+flA5@&%=mU*1JcJ$^HZK#{P}+* zorgb_{r|_Whg!9iOy;}J?QDH>oU?iBHd2ekDtCMna} zd}{vRz|$-U5GZVu0Ps0`QxTAxt+u}!5QJFR1Cy43;+RWX?e77fWa{gQqz$DrqIQ)h z5wU76$@Ucq2aQw7#yPhfT_jP5IGu-14d;ksekwGi%;84*3g$S%q6A1?QYn(v6@sz5 ztO@ZN^Rh)8qZ8CTyJ_YlK|=lfimAD#4_+L7{(RI4{H;Cvf<;q$o04^+=lDOM83^2~ z*<3WT@x>j z^U>i#Ae#2>d;ZoKqcg7D)dXS2`k_{)(j%v=Kce!6NX(Hm+YcevN7zW+Y32zFx63`Y)MX%5Ou=`It;dzk_YfP7LWhj4eK&uG+&up z;6B|qby*LZKTh8$d+{RQRYxpp_TuZ7z=+GGWoN2yLgAgTBk`>7 zq7aJ~c@{C}C4AW?xmf7q+Hx!NXZbIBSi8nc4#k{TE%qaMZ!>Kstn0%Z*h#6kP#yWg zyg2!+&!O}U)Gwb7);$Tj?(7RmY`>6WB`logH~DFOV<;b$GY&K2n!9-OtUlYGZXE1u zK^#5CL=NSE+1`8BG}qI{8o|xW4)#_wieaJ1FnGx=UvCOJWYuLi{49HNyVk`WjLqe- zz{9uBUF%|@XGJYnBX*D+Zd28#q^Xr6gaenKO-dS2%9mKviu#qYr3lFN4^O2Nxe5L`vk8d#bS znGje)(8XDT*eHVZ4#Mi-uY;a6?!{qG4f&QLyZR?r>$b!i5bFxylmIj=WPyvt5>8an z!`(epd8VJ|A6U#zFT)V-ph9!>0+y=XuN$^mwtNnfzsI>dJdm+fB~9cwkSw!$_s)AX41nr6T=pYa>=13%uGKAlE(zOY?Ay+-F10*9 z7P*e^4nyazD$!xbsMgU(RQ{VTif)I_n2&R zjS&0}f*)<3kAyuxR$MYoAl`hP@wAPnVc)s#Fw#0&Jd`JRiq9V17pS{u18Yy@>}UIw z&`!#S?*IG`AoX7UB9L^-ND)3c}o^ zqKvw_+4XP?#-;FwEHk-=^iW7fO^S-d5PL9f2E(#cvdFm3rRhIuq84M6@7d-y&Ogu@dc44_iy1wV^Xis# zlawFRG;ft7nHtUGzu8`u&er*a5<-ptpD=%@J^LGnDiG8&%g=CxE-o(HCr>+022y<{ z)BR{*-8rmEVc^XD%Aba|ylmA}-MFy*;rrfyjlJj-T3_WAgKtY!HB^}-wUe&6pYPBp z>g?dMm$x*8a2oeEqh{2DosnFpONc@r9CFjR)6xWv-^$xy& zD*h5n<@c+|DcB1vU(Dcbg9m{bkLlvi$Lx>ZxzAdiv0*2>pcC$2T|WC(;uIXP;*Ca| z-!6+&A~+(`I5zj5*D5?cm=gFJ25Xk#e;H19%2w|Go^uERQ_{*O1^4oc>|7GIk%?OS zTfKUn4id2dG?#U+IM-+R)^*0aDUUU3txkdLH(#HeyIC*m{@_x8;}6T$1<%gcj|y5V zGd1A*$EYp;MV?*>3of+GDt>iy`S!5F#pO@$z6$pcVrMcLbx~Tf?8IO!`#?3}xfV#W z5TKy*-d?e>K#sUi$Tx1bl|8r3F>!eoJ(xyo?CXk$d<#eeHi);u>0<#^F!F3 zo#|i3s0TIR&e=BdTc4+Fm3 zF{n;kRqhE(uyRwjrDG}G(o|h5CrP`gB>g(r!s2L865s z{3OZvLOgkMX=HJzPEMERm|QmF4esS?ltAyB-L+pH)x6pCY6K+d@3HLqOWgtaDcWZg?9qV5>6u$ev+}iQ~ysX{AXF#;Qb}-M^qw+jIG} zFq}Hh5QU9JJ$#w=cXrqvlaMQB#h4EWUWjdH`SWh&84pj(0l94s{f*z*<__d_Q$CU@ zi08V8-mj|g?UqjNvb9##Q0_p z7sa|OiF2@~*hB+H|6~Atw8m@s(iwx_4ed%4KMiV;?|sF}SH((A{NIv|0^9dJSR+J2qKI6Uau8jeYpYMZCp*`MeU@&D&>wPF3k6lZrkHxr>@;|a-zMmEvkgk`)r z9lrPeP%9Bb6{g8p(1~JNe}_X-S#;qu`eX^czx*NKr=zcU>B|dCa77a`#?8LUlo+we zDcER36kI3^USZLRa_V%`sD#Axta?zV;{|g5vm&3Huk%BeI#@Ow<1#Df8aAdSB~ry4 zU8*X)?8bln8haWB-}Az}ZahcDcG`X4v^;fG$-rqV%aT6Y;b=u>&9ztFi;f#k+}J;e zW=nPj~`AoE2 zHo@KL_LJ}~RPrhm916iveTU(d@wy|&NRNKmMldg-BBL`G!{ei875_ESpG{u-4}hF( z(u`D4<7CW=Z{)NvH>+HJ^c7-`#^1R&%C0;h`uH~2L;Ez6>a~onOP0DaVCc(^VA2sb zNdPHVn1Lf$i}0yuv&rdnkkx@2v$&8F9t2(4pW5Oie@TG!!{C79T0cmmNf_ZRMburH zasn@~c|X#YgGNrGBC6EG(Y~N~lN0xY_%zq|j#tyQP=A0q!aS7jP)d#nI%K&mJ@$iz z1M9x03%bhFyzgI`+Vb7yH?0kodYmDb)jC=sB1Y7JNenh0bUuX}npKOdI1vRX(V0`x z=OuGrt(2%Rr0VryL$%?dr~9a0IL}VAlX{pPm<^arhjXT;JD2Hoss#(1X>0U>Qmag6 zYFt0v@1SNUR%%YPRpaf)!AJhTuA{6N--)4HtbyTtTbJaQxxd}q>J;RcdsxFPyP_wM zD;#ukCKIc5|krc*N*?w?@H=)@t(G|wh%%uY_x#}9sXG`3YpRR`Xomg5#6mj4Y9WEq}Y;!kh^lm&T-8LTPc)ME}K~n5X z4HkkuIHgT*wOjky$bAXXB=@_v_dLz9a$?E63#$ ze*~$$+Pk~VYdfcw36BjR%7bXydD-j>mFl%fl`#eRPtbU(Qr+`mTOJGesC7WSANulM zr#D<0Z)14J5aKKr0;1lAi26opVpb`S2hobT8PM8@fY#%ND&4_ow1Yj{#+NJNykGwV z#GwO@APqrw^}{O1-8=81UYL$`_-I8C$HU-Ix>C`d6V588=WG6Kjd$JZNF5PeC#r>1 z_V%@Zwz_Hq0l`6JWI=uXwEZiQBztv3AxQALvLV@{rR9gsqdR=xEsCyA<(zb7j%C*o&&t@sVQ zZpW=r5x;9xEmfbc3Mzp6cP-iT`MUTIuPJaS;_!1zN~O)5p@&x=0n0s)Bf?r9JhT%R zYkxipEtbdbV840P4$Zp3QrXg$_CF64U-4fEbM(-RGd-@(y|xz8kPs3~|I zIHWo_K7IfkmzQBP-zQP;QPnxARqIq?@03zr6j^`FZ>wtvP<9u)tH!3blX(j z14?rEQz{R!!NTn|KzEMJ+LFWNui{Qb(?~P63y#u$T1oh&P|D%sD@@|kRMLZ+ouBQF zhMK_HuaR&)q=!Z3e>A|ZmSvCx6-8wgx(8jggxm3YG_vp(9uGY3tEbF>6MDJKe-CeP z=D;%E+=lY&pwEGaax>1ucjY(cXb05=y!}^`XZ{foD#Tp4b87?9BrR2JTdZj3J@GcG zRU|5$3*l5Ye*wJxcv5|=X2&8Np2c?(JTaH`R=VA5ueM%ZC}ic z_eAqii)`FPJHs+F`CN~9y${SJ+`Y~#5Zj|HQnTWiD=X95v%1{Mx@XLN5=+X`w7`ez zdkT&p#|1RM%qDuNw&v{QAC^yMMYpp&vuFpDYUb=$K<9z9xJa%_77zd z>270^L(whcc6{TG2pawT!-OV>s;&5x@PP&$GEg8Hm6sO4fA z5u%@Jl@=q%wBj~zYk^zVO3zN~r~t)?nchf|QN+&uW!Z3=q(l3ece^DbemGblQgGf> zsz{G+71)h%YwTGyPJL5{uUbX-+!DEDAQscZKxcBC`jn=Gzh_07X3UB%?z+_a+smc; zM4pHV5Zg=Xi#Y2V_(eT2Q=pu1(5f(smc=$n-j1}LE|5uFz=K|yl zq#nOqmfN#W94jB%g{H&0r%>&M{UQei=pszwP!9;P5`vuYJF7|F(u^zRl=asn;VO1KQv)kXrQj_nyPDAAV=fX&*kYL{;nwwXxiR*cmYx$4EA!DA07?%>qSR^!69ukn z8NGZL!xM||1YqRf(yae@q=yp17L&WDP)Mkuh&vVdZbWIj!4Q7W+8-xO2$br`c$A5X|HI4#EMrW819 zHySySy4YGWqk=`nI>(AnZXg8mmW`-$(Ycpo8jxJYX>3zFQ^|mhR>x$1@k(nOqgu;I z0HjnvST|45puWw3G4oj?wVLtw8-M>>A)RUxmEjw^KW@V${($9G3?7Qqzzn|a$smwj z6T39Z+WG@n6*sJ6W`=H3NgiE+GE9? z_1E0AXhxi4#3Z6}0I5B7J666ho+>dsNET2*#5FRJAI+f0&SAjLOmwEC>=>w_jz5wC z%Pb-zE;ZYfwFca7@b6f$rU#seSfk6k%cwEubP1exUy5R8>;7EM$z?%2o}iFQj`^Sw zwV*$y?S>$&>_CeE?Ju16+V&0$K&sJR zEPc<6-6wd3dKJqaRN`=s3-bPZ6ok5qvv|+pqd%pwkngxu7O}HTqOiboO; zDpOI415{J{C@!02?BN6I#XV3HFIn1rT|HW%036PcpljK0z7zL;=k|^hoJ_Jdh4M

Zp(W7qV~zU;K){m_@?AnT1_3(c7pgNt>o-40VyHgKs5sdmKsc@==GCh z!@=)-8&P1qkNGteqlq7w+ z%BY@;MdAreAFzC5Ej`+4k-w%L zWc?3@n89HS^P{JOw<^=Gy`N4UMnDK=Y~E62T#lBkSge1O)ml@FP{jwZI);E4b)X~E zgU}|P5U%k<_4pmraUoxcvK5PQSe*mHN=p$BqUl9$M^df1CZ?P>Q zvz9kS+s5((s2WF+VJg-4T}yZXl?oreW!XaDo0<3E4c^s&TMq=^F&mN0J`kdQ>}1czOEC?=^xEHlrgGy`Qbv8X%MAOQ-y$GwJ}FN+D_7Sn%7w; zi@xUfKdSnMp!K_!Kc)^FY&5u8opQj_1{sSmtcqPSZx{0O?NKgzf4HNitC)+MJ)5*z zR6q}dWg#olfy(MZ?lSPksQZvtK#pqEWK|Im8|VfwJy99oHxRiiyz%sw!Q5B_m=qjs zzPJ}yqP${}CH4v-0Q&M&{iKxupgjoWq6RDC38ajG5sR4_!S?@vGirjP8P6#3JzJ;@ z;H4D4Yc<1VG(N}rN*;lU?~l5FRcKJ!|C$u~YZ8C%z*504MxdaNz+MahFhy zJhi$4mIUA+m{JjuqsIRz+N$3ukhdlDIEq8f?_weo%IZW*Q$^dE&C3MegZ|B8Pb6Ser*>#eqh#gzSt}ZDtkO_)}%8V?Y;F0V!X0-uQ z^s|sB!WH(HH8TkEnrq@Yuslj2Rdf?I-Xd#Eh%%9eLB8e>i&1M z+ATzE2PMW>paM{0a9DYWG8#H%X158@;UQqqaW6tN?im$7?x~)N3g3o;PiKc_GVjGT#sIeWI(D&GdJpPDOmZ=0%Z5zQD%^o`?vWvq{#0pJ^Y6w*A zE#K_k(+iF>^g1w$Ua!(6<}!b#mq;yA!L|#A5H-ELxNOcf%$KR9tlLDHHPYtABphM% z#(1F#qoG@xn-D~9jQ>7~%0^bkwb~(0!hHV}%=tDFVij4tmWEdwCF-zBK(hkZ^j(+) zVH=h4x@H&=xIAF_0w7;H!G||BfuW0(E(bEJsZbL5Ct{|J0eRud)5%x4dVE3|8vdXc zJB!L*E$LEKbUw1zka1tawlC>w5M;p7n2JgrG$1yMeGVwQ;T+%a{TeI!$*15 zK%tk&_ZxtzzkGPK73fh=Oz1|9P#`&m{ZTdAY=lS(fXYn}2laDAJ}vyA3WCg^Re*$p zm9RRTHlOGWe=zYi2zW3jaA2jip+Hdk{!owP8902;0IAiXlx6<+R3UGJkpAk;iu-JAybfG22B0I4WlchyG+LX zI3X-@un?O*uAM>Lgq(V}y*Wc9Zx_J#%n;t^A{?#at0n3%x$UoLJO=&_bIzk6FAKycg{>;7E$jXuA5|8|JPL9&+!uLP6Q}F8XH4gic-E zgjPB9XFSrr13viiD;lhCHC8S;pTbEo59~u>X$4SZQgt3z15hdfUG-jxa2ZW67ORHS zD0|zbu*nm#P46@eK+4ToU$2vTs{CM8F{ubRKgBO>3I|p0sLjEG1B#?KVtYra>VpS) zIw};L;3i1qv_@M2KP`IAqr#{|l))@)*BIaD*Vs~{#0ACW&U2z(r(0JCVB`J<%|`AZ8IpvGy^RDaxV^#$$dV z>0)<5A+t?AmHPAbdcvqea~7ke=(3-@HdZ|dS#oLK3E)lR=KD9vlD?joNW-et z3{i?XF@}w?-XmSVPlSWJih^Ae{F7#iR3VOmq1bQd9IvL*YbXjw%lX!ZoAcP#;wgsu zrBEmmJaG8Yz7Y$d!}*(eml9JH69C9ajL}&ITQPstsWlU`yMTCqxJPv{l7fg*+&{MB z_%6s;`I~cq%gMyK1n%N%%)sY9u%X8lsMS!_JqDjhd=)=s#qfg`Kd9917+^{eJF@SU z+zJB4s2zjZ4PC%u*CZ?3{5eu}bAR8`fRn*fwBvfZ74&XE-oQ2dsi=R?iE)ap;0Zsx zH-M{q$uMZKW=5;0mv_g>=xqU($=;Re7o|*z=5wq#l`cghgc8>)<_9>k={hA1prj$a zg&T+JF6eHnTTF;Z4tD$4${T)(2b8hH)|XANOO2L?_e8+w$)Hw32$=v$B^5_l$j{Wk z=DJLcT?St#2qr)irSQx8YRTlB+}KV)9LaV`K0LU1KUQAjqiaxJNY5f^DEX=Y5Ukmd z$00SaIj>P_RmIoDF25Jk%(}_g^$+MlmQFur_nsHf=mapHLv*t+$bKv+Sn4Ubr$R2f5> zn?SxEK<^6E%pqIsgUKG9GWe<%xg49m5S=9<2D>!@T4LYJ$@__w~ zmC^wV4)-Y5YR`UJceNXA?1sS3MF@aD(^Q=wpn8E1tTARKmO+dk%?>lWx`N~ee|rkA zLOh;o-zwlxp`26b;-g5+%>-bj(77(osO!+&Vi*#euRTTBViIMv$A93LN6gs5`IF)| zg_^Q_`sHzWkhc3;1&al7l=nxVE#rBd{{h_NX)VvWiq5@H!0tuw#1u*28v&hoU~uR0 zoL{(ck%-gg-!uLCErGSVS&TYO2!bM6lhS*wOcuD8aEG`|=5?IOkp`yt@E~(nepyt8K;(>Ssle{9XnZ8*j9K_;&udFi9HT$9C`+ze@dhLV;mfqX zE>(g+AItE$TWdRm0AU$LZ*xYi(MQaXpI# z3JN;==IO7;Kv~hzsNRe)qehgm#@Mq+-{AY=q8=r%JD@!wZ^V0=W(OWdp;EpQJ}~uw z!6F;W9c}esM$t9gPPjkU7Bzo6kAoJhLM>7W*o*w%(xZ=n=Kok(z8}Lw7>CkI$Q;GR zk)S-lL?ZwceMT1M6r#@Lv?!Fo;8RD}fxo#`kn*ZQ&N3no(HVb2ceW`({a}> zC!lqkr46i@!rPgnIsTlcI?I@G0m}e9>NH}C*hH}O1T&Ea202FdK~fhdhB(Pg zw(OCBL91dmmi7Lf6@a6w9Hk+*1e*X?M;WE0RrD*O+7y`=nrt3l6V`_O$b*A9N%{Ek zKVszm zDHdqTgxjrSKrqXV0lrVXflR!~)X~bz!!Bu{U!XU9Q*tgfbTmE>*`W0ru?5{=ppA@! zfSJn@^mUf@iB{-tqGGKHj5$imyvt*NGvwC2#WvkK%xO zEpP?PO#Z3@etmNRM;D4sgj5Upb81`{2SbJ|X?vK{Xrfp!8zz1OHIfH~JG@GPfqudq zdOJS1A%-`w5Pm^lQkvHacN|*OuV8|Ujee6KJE2(3i^G$qzaawRn|#y)(WVc=7TES( zG)TTbth|=vguH>^V??;cxpNE^B&WdUW=WqossOq!w44{&pmsdp!^jShJsL` zcSC?5W)z3UV|u-BBdtQerKLC&6-V}O=$7z<=W(um;-7NEEy-5oycM4P`h20c(+@i} z#jMb&Q2Ndixd@T_o9&PSgAENfqM@UG&`DEitU@K6nWM6(je0DgbqVCjSj5NOh~b(F zMjH{8(jOrJMcRW5eycakAK++XXK~|fbSr#yHWtB{6)Fn}7(s-)=lpWo2wWuTu(Z#` zLvT5upRd*~es;V|U<|Fhd|3AG`It5p-9gBHFZPF9lzjy>LX_eXSP%d)Y`v>d`PAD>DB)teId3a83#C+MIMMMw5#_$%WG)$LIh!Z*xr6&>zaA} zMVUi`YkAq^N#qB2*V)Iw7A=3@YR>XJM*D^f!KKP1zKBibzKuK+7NXW@-$BH&EJlS)o?#S}vdc=eA^~&R-2ks&9L&tns|7iNPNDCM_X;Z&+LK z2VZ1cKl*s~zBTVGPoW+Dl-&E%0dUfDv!dBPuyF@8&5W6c^-kfy=J)U7lS_4RW)Uun z=3UBZxQ&?8r$_v>Ob5%~lP+H2Yn%@S?@xPXo>FXDpNw)ocNE=w7x<_qs^JY=Zj;_*5!I`*|ht?C6|tmucEDu%EZ}SH{yp6lMAgwI3=88 zxR-MsTx=}Pu-%(-l|ev=EydSu(}c4Xro5M~ZnSP!@WFINCn`<*dNkgH-_b-D-jcA< zEOuP3k8Ij!1|hhOL5NbbAf?AkfzB~ZPD9>_Xy??LXl>2tFm}@HW`(!H{l7L&3QGcX zQe>`C&rn5y-t~g}z2J{Hml-vl=e8tlt zA>`d)F~R@=R(2Z*z0|s^_1DcwFC);iws^|Qd5l4d@#9v+dU?U z1DARC1${~I&!pXk1Bb&Gmb>2-{0m0Qp70K7shoK%yzzzl`03X2%O~JbXrxbLR!k=Hk*8f`nUc9J@E9s4@_Te^YXzl~35Ua~nc zyjC%Faqo7YwpZGU-#MeXa5Z=6pLN2%>fPtj@KYDPo=D7EMXLptw+KN5l6`Sxt$q!N z1c*q9ywt(kE*Ieu!fkchtof(@e)95Tm}kt|=p1G3tknqfT>C<}OUXffN|glS>;ZH8 zwb(K5!nI&4Csr!KW3wvuBK+03yyIa#mq|nr_#bq{cJ!v;K)-caSA2H5p86y8?opw8 zjGF2(?D6HVx5e!~R)(s(+FU#25R2kkriPELVI=N-l+{-T#ReG3pNNH)Fg?XC4MqE9 zEj;R;>EnI+^l91q+kYLePB?0StTfH@m((q%R1l7r8o9uVpdGc{UWx95dEB@UCC%Pb z?u2pwu1Z?@4^Z;1q$`5bKE=bgZKa2L5iw3E+XHLinB*b+gxwW2`DdZ~F2WlNu13lp z1H92N;Z5abgU=3~C%!Ro#30dmXcd{@*3EXb?qsd~3*^-9$Y>9DgnA{BV zk=Fjdi3imPP~Q6a^U=bMXWpOezV&e?_+T=W)Z1iOiJDE#Sn69gHO^7_ zr_HmsdYp@4CmZN&syiU?r=r9+N3K93MG))@a>D8>Ld?TafxmD4yeRc-yTPmeYsW!e z0RE1Ms@=w~PX8oFhmW)rE5ZJ#hPSH`$o_T%-xr=#saz(@P?2_lQ_`-~Ueha@-S+y| zFcTfAb=UPQ?|yCzWof5F-AN>-GdOj$M>cFAUP}8acsipZcxK$B`mec_;QgDzSjC|ZiHVCWLYC($kwh6Iw|u0y1czw;9{3T{%jNRB=un^ynwp0LrLs~^{l4bcJ{ zxm2eM4rSC`d2}ToH(2`zH*`2Msvc}!<~iOrO`r2T-Wjg41lNVP-ll)}?!$XR<@$ZN ztIvYwXR>YnysDRtftzlk&+WwUDc68`4QVBnXEqy03fg&HS0W~xJ+L!t9$32XqAA!pzDewAOh&Z*OyS3XPuwza~jcAvv+K^Pepwew(fqe zQMm6xMjbUvvmq}tU;cXW)w{D^`Okj#{DpISSur6iKcBxYdfqDmi9MYXhRVquta1J^ zGkAG6?)OQ$U6oWU%w%LHN*ZeO=crEL(k%3R>LzpnTXu&svTPx?G;NJ*)DWQyUr;T| z+ze>*edIVUjQJqoVs~6uk6}%Cru)a&vj>6{r>|b4X^SG9%Z}4}!6h^MS0Wg~&k9>F z*K$7(=DN+>qQ(9kE9n?49Bry>6!$OU#py~z)(7Im_`~c|y=iQZ*a~CyVO0)!c>|lx z{0r^DQ9O%YMUrZFOGd+^u)^OKRFzbH-fWjMaOc2&2B%7ws-ultMds%7cMs~;M8&VR zy^Q`NQ403`=e_dp>Fsk%rqrAh!Aa(V21ECUXW2((rC&e7w}SVK-H$(QC$yA#qpHFB zc{x1I-Cwc0tgtMNhPi-;#qp~mjv+5oV z;G+BkT*I|TYOjl~zRkhJMO)^YZj8P>(KA;d-aa$Kh_wnh7B<8SJzuv^;%=8E=fu9- zWPA71`_YV3m)cscu6=6J=v_Pds$H&x}ShH8kgwzEJT(dsLd+)8N@?y_iQtQ}oZbVXo`}I~jqCnRXrS|PZJj5z&3kG z+tzk@+(hv3GXo#|-T43Ih=6QY4Id+YWD6kvc;V0YlKXYR&~W|G&$r*s<59ysK1aZI zr%I1s9tx)A;ANBO`rW9%wfe%iDif`9*r{#>b;%Z@f00dPOUq@WWu>Lk;Ji6Kui_uod@El7n73YO&UZZ9dvO zr74{HxTEUo|S${b@X=mSD?Pq zQ%SKRWJTG4&i@BP_tgfrD;dT$cN?tEe~93^e+$=2d%!5DyL|3iFvsZ>txp2R5w`ls z@vk<}%=AQcLPUm%ddyfoEsk-1K5Q2P5 zbNkJ3oap>Z?1?(~@t6yTd=c58DQ8f3T;|MR8Z8yTHQ!~**IOMqIy7GHevO(=-YYpt zY0;0s3`4dyq50Fm`<~~XBmk8h9{9V`PF>EY8a(Cj#@Q08e7kBgj2_Q-jN#5E0#RdY zBvx|$nGBX+jbUnPrthcRL{)3K6PXdIv(VV4T+eRdqQCZk%`F5;O1GZ)f%YxpJ{5H4 zzc7rUCPcwn(n0@&LAG4~5v@|VnV}&1z zVkIsTTP8XIo1p8Nf*ShKvEXVx*KIpDh%5kVaMW=osgRdvtw%ceTG7gs*+FtEuC;%; zg9ru^K$!1S+N#((eAz*3F?R0eWN5dZP@we@794Nv!#dB~Sf?3un^-qcCGz3NS3il| zHA_Rwyngyz;-F)VMevIlrr_1TdifA}^SfJnsC`3K)###-Y~4ps`1!S-gqNr=;hUAh z{~BWWxzGxmDxJaMTzsdlj2H4cadnMF90$!?k4)nQ9&>q;pWAE*mGA(x{LRY0fndig zSMXh9)ytj1Ip+v_-2A`+mCi~(k|V~ubMZC#PB`rZkO4)b7ww99gY_p!7~5d0H8MEe z``rvP#VEz9&BXV*G|Y3V2H1xbs+O;kG6G>g+?&MQ`rd?}bf~jc2Q>_G*_Cri1$S@# zx>#pFt*i-86pzwx@qIvzvX={mx0bI}n)a%Qs-sjPv|9h+dc9l!0g+`*jcVX#d{hg+ zT-uMIT{DHQJ3nOo{sSgJaDYSCI|Kgy1IzmCx%-vvUEizBeo0=ws^5$oZFz!eJl`${ zsU{|k*perA3urc0GrY)e{{a^dP+L z3~*=)t$ldeLntADw0=qbz1U%X&2uM$4APWB(aLnF{$6?cZ=JJ>i9D3qy~n8dO0IpL z{fA(00#b<_T>Mi1x2B4LraOHY@uwwj_|yCZ?0ev?#~(fr74on7D+DyD1*C&%=f15{ z4R@q;rR9t-f27n8pKGVbmxwAM*9t%GKOC+$68D&PJQs6 zs-&&w7gxg4b<%waEENuKTmDJ@$k*}WnYi^c#;vD#!X|_S7AsKyE?{;aEIyZ{;)z`S z{F<+^$5!|5jItJtnGY&Oa4KE`AA$0|nzrlH6`hg09eHE^u&+5C#2BNYT$6WK)sOPu zVUO=6p(uG}A74DFsBk*^D!IjedboOuUt`VwVd+C#TZO$eVt$JFv`fEy1Yw)%Fa#j& zDdoRzAOHS!E$x!FQ+xatgJfqbQZk`Q``fr~iodOuvGN?rvo>1#s-gJ8{I6iGoniQ) zBFkzn&G({SNZG8P-b&W$FuFJH&7-@ujehYG+&ft-ZT$d^wMZ(Gh-A&S2TN4JnZ6~5 z4}9OZ37z8%2@&nVQt#CA8u9<)G;Gr{>G+fPMjWaq@-en>NaO}IlY5|D;csIf^oH>}9OnhY^kJKrq@n@d7png1Bx z(Q2qeB+`Z|oIuOryO1Y_glefR_+svZuBIOaPVZL^A015`{|7t^7!E01j^t||!p_T^ zXy8Ua3QH0izeQABGmuO;-A9PMQnUAeJiU87)Bpef|D0ixrUNw@QqpB0+66)>aVN^2gj9T1T|xP!eTz zCHuyeXLF%(fWqHMb?x3MrrEMr$)#=lUdfJY+iyI$=@!+Fa3e7tBo|9c3f{iD&AQ`c z(8uS3xSVU>(?dUOqoobI{F}D6OHgfO)pz&8)zkIM-l)iLAyqe{wyD0^g-C$k%s3gg z=kJ@Hzva~9lPUioqW*9$e0}1!=`lxdn;4$tqRXRUk@D@5+I_qs)5I?bVdnI+3x^%K zg2*<5Rj=9QmO4kOj)jdd^$S6=;$0$nhWIVP`j^vRCq{myc1fcBqJ=Sede;++ry+N!6m zh~R^(Z~@v^8{rIEl9x$~^75I6QX&NONVCw(t@kmoE8sM%^)_@@uSgG>oOYz`pDCL0 z!MM#m>OQ}A&gd2%@tWab#Qg(qa@XFJq^Di2wYr%fS7MZ5d4&sDljo;6*ohB~QO|yn zD^?DK=~Owa-deg1rOohVKc6pE{GO}Ybvdj3H=>;trs;^lOw?3Hy}Vl-xHkHsfgU4= z;Vq9FNhXgkbcy$9dlkI#4^xh&r&fcxunGK>l@8e%VsUDZvN!I@`?#ky0Y3nkmaEMS z2i$l1j0nQcrbY$$t!X{6O#SPHzyQY;-hy9#bz0@>kIOg9?X8wWvt=Vq1-T0ODCZ3V zyC-AWd*Nb!VtRWJYUbc06bPLA)>K-z%xHE~v@LX+ok(!_r)CcqaE=gw{2z@0D}tJXx9bu^}kNUd-d>_IrE1Y;jL#VBYGy0@RhfHOTogTcylBw16 zMq*da2vRwy5@0`Mwc0dKG{h>aN9g@W_!%$48H!)Bwv;t_F7mHAM`5l1y^+3*7JMu1 zZ}%PQu99Ok8;N?@*Z%2HOjNk;l;O5Q{qvxm%L7n$tMfaaoNV;6Xl#&%%rdGa0#j$R z?xfNoxGWaT|1N$(?YsA=KY8m3XHtr%KRu-=3+4-Ai+EA(Tzh-#sQ2EONuy7Vcl$X) zBKeDh#4hoC|tk0@a@5L}F0NirL;eyzS`0Zh4XNC&CFn~awtmfT5QB<4nL zxwk&uRbzpr)X&6~Sky|o8A*$h)7ngCF3@TXIj!BsVr#RXA0}=BKy`%vN7}6FjpzFv zl5BJ9`Gkiis$kF^gdal6ERpw@dh}7b5&Ub%Qsg!~cW>8s-cUDEhnAIh;I&}tM$I2r zP|vR@RQ`r7x>l+!=*=b@QPeel8;(+WLU0Bgz3dPYUFN!(ULZLZZJR5oN~m9c`=9zW zg$O@kMq7zyzb5XWV=KFhqJeE0An7URw~=m7AJf$iY(^i;?u6~9?CSkV@o09L-|46m zEw!J@*EXA4H-L-=(h@jG58_EZ?WU?VqN~dnzzT}rmPOW%ka#^n^H|cp7hB{y;tG0i7--~;a@0$zRk??U$^kk|N zJ#K`}k`C4$Nb-W!hLE_17rzLj_2^*6Ds*;6w$cSO+}0EN3+Z+5t%EgSw!#He8m3_E zoG4h@m*>{5wx1ZmKM!Oj3}lu~ZQx3dq<@1RfasC>S3DN-4(vksz(FB&&d=5yN_aRz z=KDZ~{7KQMwd^gv3vlgme%GGtH9jmmOTeW9&)Bi+8pKWbHwo8Ye^PvM!Ye>iM8V1Qn&Z;UV2PqCH^V!W|luJz>1L zXV3^)v;BG@=T?7K@*(0?V1ULvr~DSbqU;-vgOhr+bBV-!WVoWOhojnSG#oJ_7~{QM zagz@UcK34qu^hqSy=2GeK{9Xnxwbx9#9w>{D(u#`Smd-EH6Mj1T?2_PDQXnF#xJzQ zKD-Dy$F=sLZc39k)Uy8hfZw6S*Me#2f^SC7Y^L9sql>BzZ5I3FTu3i1DXcNF-?7Cm z@>1h+dJv$E<2Xfo}9%i-W{PrvM5v9=Gg zm$p7YR9oEe($F6jCKOS-y5u6-z!ZZ4vz$&dI=Wx&F+>BZn}(3gvsUI|kkvv@ujSeS)501yzDlLe!J9;&<-lcB3RS}JY~n9H zqG&QfY_Hr^KxNkr2zf5kCAY`ud(b}DGt~A4+b=9s0Pk?op1)x7GYldc4++RKl-%L1 zEtY1P?^^9Y2X7XX7<}AuS1}$nx9k}dEy#tgHZ>nwbf^YUc0KI+VsXqze%S=`i}(x$ z8Z-`aWn0^+ITVkI z-4~b{}3>v`FY(099$qDqQvU<%Vdm5;B0e zxMhP!ti+^$a$-8*;Z~`jerMd;L&ILs7CMecnYh{d+E(pWP5d9wl4AC6Jt_}x_J~pb_2c-Aco^wbeA%3@ZOr;c@GXdQEgyJUTvA> zFGX-ouq&$FwD87Ake=sy4YG`K-Uayno?js-#oY_n@_A zq=AAEQQtc`>PY7YGf6$Or3D<)0GOnK-vWgmum}=R-@~#xTmbQ!;YG)R0!vXB+09eU zw(uipMS9X-mvrn~?kvn+Bw@HWeG@gG$@FcLxFpt%#m~`;pk*v2G_!bzpcKa+b^>e^ z7J0SJY_&DaK6|(&M)GjiRm;(2xNS4|uQXj@VLw{xINF8h!45Z8@z2Uykg3a=asein z>vic4Zs19!URS>igWy8I4eh}@HfCd7234cF>W~-!Y<_{A_+u05Ao`a>2`(5ejD&$J z%!wodIQd3^wty0c#RtbI7?iIq^Q*a(O%kd^74tmhwTjYsmMjJ3{{hA|iV=KPv5#T< zWW-XEnxO}UjS%Oo8{UG-M{yNT0FF=QvP>;vz$qv^PZL@j1FhuO3Z6Sf-wQ!C&L4iQ`pnr$OEe{u`sYS+(=kd#KgFz#s6CrC;GPKsqJdSOIqT0Q?^PK?9J&Ggv>_t!!R|)4oX?9;c}8^d4DFy`V;Q9LDz@K)ajCNv`nT|e%89O4nnO3sUhEV0ria?GIs;W zO?o3~c^f!1DCR1vF2<0fHmY?z(%d7McBRv!J6e8&eBuV~`?E6KsDR3~CmVneW#!TE za;#a48nGVAv?9lMK{r7`T=~1GakM=u%~B`fF&S=PTw}*rADH3(yB=)sHu;NG2x|Y$ z=7uw8B6u*+4ng@79?i^OHzaya6YWF-w!|3_ZfoJ$t%JDdVGq(Dv!e+OF3DE-Pfnry zkA-dhYV%4Z6b(03HOid_dT@JdP&anvU+&k|1#wSbvDcP55)-q*{Nj)1eImv$@SQzW z2g5m`{lD$60^CV32BLrZ@Xa9BfI|W~nwRX9=V{RA0E24qe;VH01B8kY+Px^yg0jl0 zijx=JaKRU=m}S#u6^EwTX~w)7tZlv&zc%wP`K8vni2>yKo!dJQT8X677@Hhg6spW7 zQpTP{2GW9V)L`E}QO+`P@Kw@6PvDhKa+bf4#kB&pPh<825C-8TJ8~RK`k`mHpCR}#DM>NsP-EQ(BKZqPFXu=R^paad{?E6^lqALE|%kzSZFw9^2oKC_-TfOn9V3%f83g2g^*ICVLZJkv+n z0evitUMqvL$E~6yuDpFNwv$R)SH~Pf#M-^fCjhg5(sUHLmRK-krS^Ilr#~yU)5=ZF zVYWi3`kztn)NHyn!1LJ+9Icb5W@nDAWE^cEqGeD)H^sbwT~T|(^&0VFp~1!Poes`~ zQmlcT2|nC(lZ^=}EAdvf4Pb&0YY4+*rH=Rk07|s7@5l+f<9--_YhI`XvL1tR%t5+&JZR7yi zN|Ks|uH~{fgFM23AXSH1vg(ChD|X!{RkN0_2u z(gA}hm1^Pr5(o@c`1#@*_ zR(*nMuVq((+c!%Al^kZZr5u#>tp{XWMMYW|nJtkvjvVYVX>JXVn8YUM>3=do1i`ZD zqsi$8a&@!{eNvPb{bais<&>m|(Fp>LeDj{vO?%vekO@t>KP(g_JvJmMctGk?{g@fD zsybn32{2T&UF|YXK#LMZRq=(>C4B>xv~uWNJOSJ}0^xO{IvWDkfV1p5Q{_H=iV=_> zZ3!f&DK|VgT9~_$uQp=57f=e2Fp%#50}@>Z^p(CJ8;$oL2yzUgmfR}$d++guUjzma* z3MrL2lx7Tow*_mUapfrSq;A?26~8&_ZCkFEtLCi|dyP-|T*0{QIN!y{tIswJ(A8Td zXV`ZNvg8WyqrOoz=%yHic%nO(HZMJ46Wc$#RQ)3LxqMz0xcZa*`tfLwKx17I)~lAc?=m)N3XffTvOY5e&AbNmGd)x3sR&R4 zJ8l0><3FG(`C;+t{aXQ3RgXD`Q4`qK;5#b^b$J@{Nx_>3$U?Ilyr%bhu7A>>SN>GIa(@{6 zO^82p4{6{6vx$_uzb9W?EvRzCH-!SNN@Wz1IQ+il1)nA*rm$SbziOlsDR( zY3+vJ$#t<55?H+FCpiPAN(lWMA*(CyiCvy>G!32#-UwIA_5p-SC`K3rnu!eL_CtVQ zs*A2V8;2kCdBt*UsGu`FcbKAb61bdbA56^{)zOI=Nwr(r^A|@1)&6p@Wj2osI>+}u zMayTo%120~F25Q$qFNCiniBrr^|3VDp+k*Ss}p$0W}#I3L5q~J;#pwplL#Z=Awsk< z4~qIm_kLj?%YTd=cWX$7H{GgZfy>RDN`&B{62V0-hl$RikKA%YS}ZmsLD_GO*SnR4 zBJKRr`|^y`y0u>L#+Jx!oi0gK0$){oeepms!@xIo0t9uR)ET7%m<8J^Dw*DYbRGAB z1)FAHo(7V3{EvDKx3>FD$H9R+643UN=WlFZdy7$Y1)SsFGSaP)D*A0+b9Ml4S($Mzwr(GBc=q~h$+CU1CM9`G3 zK~qs7Fs)VG{llOXIL;_L&YzViB!|Z?l!op*X#@))gT5(9>;X7Dh5%!C=PZ%h` zzPTHYeb%a_xRo#U@5&=m!BYTu7Mn(d!jL59NP#x-B;O|ztQvlmsxX<2!VSOs)!5oJ z?#UKOf94o|^J2QIZ7%T6l&J`7N>(oL}~_q93^?n`lT#PGQ5z`cn#geXY8mjPS;A+^xcn#}ok#fOWuQrBpBy zgNrpWv~|Pyl2%fWipB^O)~uBQ7^igKNL+_}IjmFRD&qs`4tC z1m0L*0XL54f?r4D;qI#1jSvT9;DT`e{ocE3F)f2KwsD9;b03tME2s9tQ>+6f0VSnB zD;+GUB|r;9z8HBLN!vH`my~P%PUj3aB&VI)y6Sf7MVA~M*3)F0XY<$nzl`qtGyJ_a$8W0Re|zoM*^G{b&MQt5;7DA$s+acrgRV~dZ*M6~!( zw;qJ+eYnHN9FTT@T=(AI_Y@Kn@;j;EI^JN76Za&=3M8pZzTJ9X{WANnf%WFTBbU5} zuIEAH#-H+BddD&I<@>zz9~o(a1i}@t3qCFv@G^p-B7^-DCV4r6bo-~_#iUv7?~>04 z*kKlm91KRv%-7D<@Q^dfhu+1tRvk7TmQSr2pv_URfL3{+W^Vo>S_evx11+#S&Ao6| zw8Hx^-K)|iuiMSUo79|UgiJdZ=xqxX-NVIdxBbTk$*TD`MH3QER_!PWx+JY!1?qJR zeN$^oJlYi7Dz6M+L@3v={AZtd7JQ1gr3lf25==kM>U?Q`s-WRZc%umy=fv81^t*GG zbz~n5+CTjipU8693HgDy<*~!&Svzz8Xw|CIX#XD&qs{*ErHjX;C|Y)sY1+B-4#(Gf zJGO6Z&qVyjoKSj5oJ)W=3g2CiHxUx zxwqpVgFEf+Co%KTp6UP}AKg3!MJKTy>Ag{z+g%<#Y0@frzU*aq!5{C?Mh)6&;b<;; zYQkq_W7vEeLI06naRO8ScbMp<(4346Ct}M>yFu2-$EmerHP&ZSbu$ZAZwn)lNk<IN1hC(BzIEc@Q z|E?Opu-OsIg3d8<-~Y6%NFCnqh|&irYEjE*zu1kATQ_bV6ouCBXfMotP+?}hvD-SF ze|s_hL(M?{Q@U3xp*N#m-Ql4dSBa@I%bbP&T2hY?u~1|XY)es zO=7*rrQ{uzia6jz0;6f)c%u3rpEA>u58e-XYnx;y$$Li3*O9|dDnGC`B?hj|nG$M&p79vo*THEI zH=~GGN~n$Hem|y#O2Wk1{{f{lv~|~#q`wjp)_Ynmx|_?RUhz;aw*c^`V2#4gpxbci zrO{WJ_pb0pE~uv+rh1BASfM^<49*yu#HReR5pFU~j0cC)0ltsVz0yoa2E9Q4|5ECq z;q8zT4xSIOl-Ynxx1ptyoQhbu8RcU|zrE|~!7~nXFCvCDI)OEea3s!ezEKVo4{WUU@WS&qt^Caf_0vly^ zK>>jq&|ld-d;G7)YOw|v!}sxiu@jUEDp1T+FW*1b5j_o%7U}9AF z+iUU2e|ukLKMVcoXgh_B(u`HCu39b#G^u>&f45*6Y@U5HHr|gx64kbSn4lqes2$k5ZZxc=2!7c zXq~~Zk}yi#LtlDP-VyV+Lg83I^@Vzm9$ZI58Shv|$S+y`zZGZYl8$%2|Bc)I?NNwn z)#mKlyNP(Pp;#Xaa@S6$xZJ7R!%aF|!;9>+1!R2BDUxAr&1{|jhgzF(Ymqu%tMcGad6Q9O%;G-} ziaSWzy3ZR!j>1hE{k02>U(r7uK--6pMQ{~-0864FOLsTIp0>?7AQPu^2uzp$KmF>8!8Td zI-xiF>Mm=v5(vlm#uJV2)MOtDIH}aL`Wg&Oz<5&qLIa?3%Vo(M)q9kK+kFVpLmVYT{fitS;Z=|gTcFRk_KM+ z6#fy^7KDmH20<%%CGInc3}?a@QOM<{g!nD2B#jNP)?d309bA4K68?0SkOr%qpcgtT z|EgdISGoRZ2b(Kr=!y>PW|v%MoBe^!3+8hHcDJ;acuQxCc7qyDz0&F*{Ok1~`8yUSgq7g?{+OtJetFx?*3a_ea<4>6yEG8<>bzn| zg-u<@;~!7&k2gk*y!lw%RCj0OLCm|SANo`I@~YhWRm}_3^1rVDStswj&J$ktWDZ*G zR>s1whT5S2IeA^}$93nEmoOhhAi4So3w-_h%-yLajKX$Ib zHDC4O;4UMxb5@C;TYZ*i?ENm?z;v2eZMC94RKi-nzi{La+mX&e>W>%`+4uH-U*ErK z4!v$4IuwxUB-y=Q!Oqa=opt|OEJe=3#+t5{z4RQOAypY9;>%-<618D)J`Owr-jv)`4mJ zqyT}Il_%Gr=HRzJ2g_0Lnjup6y|ww~gzPH)+Q%!(No^EGQ%5f?v)=}Cxi1f&nZkEk z?7Z}J;=lf~B*v)rRMd@>NUP7%K zFa?s!z>%5JMa%7-lbi1}oQVyKeIGi}7vf!8{9q?$n_5n-r9Rsw`H+)x7*7{9m3>)0 zX->a?`bhM)BVV#l7>C(MEM{ux_G>f9XV>qizaZSs%{~gVHZ_}_AFv#A4N<=3{&IKt z(FD$vaRN(4r7-!4+Lj|-txdJ7Hl;o)cm8T0`8VxnY#&z3WF|wzNQqsPg z9xpV)HK;oNV(o%v*Vb1f2l*O0C+?l$>7@2gY=j$VlsLdXETDM&Rk{kJA7OSlp%Xn5&P?Me3;u8-J^4pHw_72{d(?IO>pi;qy zxn_j_xo2)`)t~Dh!fp~~fV1zbtoaWtmoubpmLtVYFSqp{9>*XV5Tt9P%RjM6sZ*2!j1#R!*W=HQm6v(nFb-1-8|<_`&K_A$41uXOJUjfpOj-|?ZFt7`VnIQiecbv)J!r-p|`*`Q1o|_#QYXzL<wCwm%=1`i7)g;N@jh!T?kNA33^h! zo0l?7_WD=W=w)SBZB@?N}xdk^jA&D_Fvj|X-|^>lCGXqR$>2w zm**T^r}o#*?G1jbMeHZKTG#)ojlxCfQrIvCoU!5^|Dtl$xM}`2VN$*YRYD{#ho&Mf zE7gw*=Y^gghwUftqN5=#A3g+ZsDE`H5C3I5t{E*vm0r*7KDS=fNi)3c`#<2lG-D#+ zpSG*WTzDG|A}cEohISrVzg(18sY^pDxU7kvY%rong^OC#H zHyi)nrU#IiSeRB*^+4>67At189x-^Q`$dJ}0yhQy30k0c4|DsHdT}sMy8C8f=z|NY zv%`v=b@S@KE64wNuTaCxZb1d6d6_XE@Xm8f_l2Z&BzzslQL>J|#N8gd>oD-=aIHVf zutoVoupUY3J5v;E+TE%~@B4xHiYPN`*yJPA7a-QIznC4>bkNwm7_Yx1h<5rgraCg! z+k-5x3641Q`-zJ0xsBFK)*y4YF{*qJA3El z)=ja!+tmUiXi}SKsjuJDrL>aJ#n*YbR>&mmZQR)ZfDGEHBUNWUYC1uzqt}YF2DS}R zc_seEWM-xLhvI>Euzhu4#mi*o`A{Nbei)^aR&A25Cp5=bgx!K=)SUR-mYz0^RFreg zu?gJ1>xe=V^}5pgFPoZiF-zW8e}V4l?hD+?kh{A$r_0f^GqnH#mN_lWI172~6x4B9 zMM=50l@_TX5lp|oIsov({=JXTA(WxeUX$OYKUjB)-IDkXqnz(O%@v?;rUV7k5K zA*V`tu5HilSOU$e3`AI~{tr#3+8d<~XVw*r_YyQ`zps`%cy!|UAa5m0$9ee}q*LjG z;MpG9CCQ%y3fv#F?iQ(=|gKqIG5f7u`+E;^bK(M&XK} zH!U#zSS7=d8xIjk##x?K@*N-6hZvrhS#)#LgmTJiIe|iP3h^_k^s(b~0ws+u>TgF%X zMc(7kqOnET%NN%c&)y4DdwCGK))*wHu{!J5rye^B+v5`-FOVLVL~UA-0!T436t?Vr zG~@WSGea?^Z)P1}KW$P6L^ZB#*RkfH$3;qD018A;aL|rfA7juraTyrotW5&ebPbOlQq4G8y_F9 zta2L{`(t1uU+w|Y{m01~TLPHdhHWmfD?ffZRze!Hw`p69o>#99V117MOezbLe=&O8 z4bWa&CzCFa&t`_IAW}>(#vKrs5_hp-7-9VUNW*n&d5T`WJYDUOgTA0Q+3NGh#|fo> zFtZB}4i?RhxY^=~=)w^kADRIcG%<4r{0>~BnzN^A{%~uLy$3sfS%Hypm7xBXi#r%R zUTmNfaOU;A4k&T{_AJnC_BfbaBM&rWVxWk_3`*U2JxrgPaZ_tJcG&?b^YN$&SNHCn z`4T0ncHFZO^!asvO!N8b+atBtCm!tV`=H&{vDa&~9!un6 zBIYd5@Wb*aBz}jMGT*IYtDW?bbflL>ws)ktoa&rP|Z|yXpt1&zWrL~ z_t5%D>{MH_6CXbL@AKH=JbFCo0%p-POtUtjzGKDvX>9P{YsNi)t6QT!b3_J5=TXOe z&t-fj>`npomE5-ut>ycd2qWh{aJNxmtB=ER+as2}qfR%8GBgVvH#%Hw{*HaLbf6T7 zTpenxco8P|;AS8}hX8W=3OA|~B36x0{X7=tFm$z4w@VIe%6(2uv-B$X*P&CCI*#TV ze|(qVkYIlNly=)}c8e68_}G(Q^1B&+KRE!Y`wWn!eM))z_mH2rTg!N7 z+_{S3uEUZ)sZXwdBn;7w1X+od%U-7yjS~G4nKubs2l*cwu-nt{T zN?fV{T>elO1bRsO%7Z9YQR?BOxgG0PXX68R^peg4jobK`k*8bHG{UlKi7S&l^ZqQ~ zIig37vSTvyib$=P5m^k4Nn)U`1%a-nZ!E>vksDqpglxs_ySRVl%v66LMH7^$RX90s zo66Y4>vAV14;}_?>C>5oPMOi*7z<>mwPY@VLs{q4NyA5VYSMaM$QimNOEI%YZPF^L zSVugh7R3Qa=}CC9yMH3q5ROM3(wI2Kpri3!KVl`4CC@TaT}0j7vIqVHbasKA-GjTM zKu1i_RhQM)=H5JbO(!R(S&xl_>S|HS@T-3BvOWF=K#@F zha9nP*iPB{_hMxh))nMq9kBig9o2eW+dDtP=npi`=GUHgoEFN<`~NJMmAb|9NPU!- zof*4ukqmO?bZMxvdDMU-*!wEUG04~oSn@SAO3mZ^qeZ9!$faUdE##J<`F}uJveVP- zI%WyQ*P#aT{?BaEYvXji6cTr6Mmx`YijXQ1G>f{aTVKg|UYAszMOsGK^3;@FT4vyw zz2dA!wCEG&yWla1DJWIo#>&6ggl#^U3xQy`uB#66f${XVzD%RRrpuFwaW+X<1E2Nr zPD^O1qijX+XLKb<>6K}{w8|_24(m@Hi|hvt0~sfDbOHnzEjlbgFuh6nW<1>Fw24By zJ4e(+0&NXW30)2O{)8#0q<^M-)dftkvrW+cs-vd@sfwCltQ*2?9(Tfzj!^b0Kg~{^ zouPp~C#7DlqyF^N$)N*|mvGOK`hRRp;`k*1OsQeR3lL`ixWl+J09ne2_JH7FdZ4ex z{ovPt9;k6F1Ww$Y@G?Ci(D2rt-rNr1WQy7f~__SD*MO|sZqZpB80BwOKzj+q$ zl#M6z&%-@aK|G=d?ashG+#%8WRqh;ZwsCZ&Pym8|qs00|5vW_6Kl8hei_Ymsb*Jp2 znL|3K2=;K|F03W2pB7KV2KG(7sYbnBbEJd>9+f~e)Ead|OHx56} z`%cmHLf>tiJFR(i5~^Hos+xQ)Nsyh_>*^D^FhYG7NKr&=?n;7697%lVf@YJ6r8Bd$ zbsu+hCK}e+m}tR1;?WL%Y}DY-heTFFzH%J*KYd8sQeFgAF!S?KzdVhJ9Y1iaA+$9dfwbFoOTT846cW%#Okvqz|l-;wgw*P6!iS3=>U#9heK?FdYD$84n-$l2Erkt z0n*UgiYFaz*ABojQcy22|F&#=lck<&08O@Tu;X}q-hIl}9e0(4sa^gaj~+nQ!tHeY z3Cx0|s+*GotQQWV43pdS5qZA6Nrtvn$Ze@Sc@@wclj8W1u&FwuOe{d9*%zk}0r?!hbp(EM^|39i@Q9`4w8LZ54ftOW zc52UE%t~}I7yn~Z`#83tOa5~Dxy!dvx3C76A{vnNrZ24Y@!ockE>iV89Pr3q2Eo5d zH-?8e3rOXFJ|&FI2>dK?KUD_N>%oXc9~DELh5c1>xSTC-IbiZQDo?(Yf1k=5w|4Wg z|GN4^yprsMX22C=*WR4<-#ok4Vf9k8lB-&x1B+I5CeVXjJTo8t^o0?dhVt}X6oGMc ze>Vu#Rf47=k?`bo&zo0FtQlqmiWye{Gu5WxMhrIt)vmXaZ2j>p9kcLW z-zE9h4Ii>QTrSH>g}kls*Hy^TN`wv^R{t}*22f382WuBSIh+<}^Z*Lvag*f?KV$*= z>vxsrasMgI)4T%ar})bfXM?tVcFNHV)vys}v2Z%Pm=cR}&X%~ehW4*vIWlQC1#y9? zHXYua*`1dwlsC?tto7rp2yUZdEN$O%t-E*Jjn2-YsN%0eN_4sLOi^EHe}2OIjVUNw zm$l-7o~u#a+#CH~OAROvDkX2^LZCP72Z{g{u)=V%i<%vRoFjTuJyaWQ1HkADBHUH? zpLMJOE2b~x2*cRc;Mua<+3yd;W z0>QbY|1774_sN{*CV#=g1WUKWxx9;a&wOK{GDfwOxFgFfbtPY93njkl(KU*LpYZKa zEpQ*NM=~*sVnGeK)RbauGQ*5qNOzTGQ$1^D&OGZ65^7Ij2W7`qt+;k&*S9BbX`uzR zBoFgAEk%25QdO(#8QKb2^*nG}i*20cD7JxPL7A?tj}X9sk8mT*CrBRrb~n@tBg?}^ ziHcTka>NGDf}z&7>VukLR&p&cglNJM5Hq4-sQ0Ixvs^B)b&)D$H~FUn71MX#T4h|_ z+<=M+vjX*(PIq0Bd8bJcGCjYv70uxw8%uYwz+FB zf5e!U(`F_lr}vpt2ITCt)?d>V05g_$VT>+V!np^WTnYMhlEsC6^3+y^rtvDUh8OJy zifP-p*2#s}fQ!#`55B8l@o>Y=%XoKTAo?R=%W}s3h%F7b!Q2{4QTBxMiC*fa5baZj z|Gi4LQrklm`gwz#dE4CWkaoWY$qGc`{?xSM9!#r8jeB;FH!>WUz;99ZqS!zMH`Mk( zp{rt>$Q3u$MUxBK`Oq%+VSJx=4(Pp*L#jlNo8nwc4(k!p)*L*jPTpgD0tF9dNtr%7 z3YjBXMa;K@=7RoIL9~J9OY_yt`%j+47}bAI2U|i(O|AJ!=RPMI?ZlMQnBgf>(>W!1dwI2N;8>q&E5Zwk|f^ zvRF?MT3ZIzuX0-*niLL~=jl#smD^E{(nx}uO-K)Wyl&Pn(4e<_7@H!dc3sK|(yQ2# zJyebTngv(l1@!;OzJ)Ux#@lF*P;`e+`cqOY`E$jc-Vicfc?Aq8ZfVz>Yr$^R{WcUI zAS(6KaquB0z%DBsW?aA`AV8A9BZ?x%2zD)eR7I?HU*}S;A=2DB$+syN=%j$a-%mlv#W;u2$ z2m$SxaM2-9>s=9C!+fLgSTTf5#Vf_A=2gzFEUpE=ZP%-u;HmHLwzH!#UTU)?C)1Tp zG0-j2-_~7n3R<-hbTDD#rncScr^blXC1s_7XJE+3EhrP$djG43d|EpIo`tYwa=Nv~ zIjIesr95_mXTJNb!hE!Lu6B_o5#0ioh%--6nAV6nC`UT61WK5<6wCT)qS9cB4s=Uq zSgc}U)&GF)Le=|NlEe|vdpb{4T?VNaZgK|la4KntzU8pN0GPbvX4wfIvag#f>4_^` zaIIN#Zpd7pjfB-mt^tGyaR>I0Rh?P_VD{4&(mugd0?6?KOu&6h9q=gH z1`;I}e4f`+XQkg7mI5xI;s#X^Xs7@?< zyu1)>gBFUqh?pt-mUdKYJ(AGd71t+6+twfe4>>NqygaTdNw7CR7SZ21uocWiVnpd2 z^7|aDgb>wq+os&tP$0uGztJx8D#(yt(gd%`Ku(vT=C54&%X%fLs?iW6@hcoOXNs08 zrAzVMq?aU0tgg)nWp~H0T_?EYS4|yAm#2ZkK9ERaFc9lQn})fvhfm5xI#j*}cuBt_ z_@&lvWCCK4r)9YMrz0p_c3~ElSfmkZ$9T?Na^ajUb#@H;P?~O(Zr2Rm+MQx*hfL*2 zGu$vbEB@L8Zh%?JrsZU~p?PW=7g!KY7b5}+liye+9iCc@k0<$Ams`M9$_IMDt_B?{2Z7AluH49RRoNLmc8VjC>F)|!%bk< zaA}0!o8%t?ZkxPp&u9q!A(@@&1B!n4L@DG2>AHb(oqn|0?Eiq*JeOc^D&4XL6fPp1 zW(2lx>q|JJ7A`!D#6dHT2g87pM`gt|0==!q0K$pZpWr6%aa25~uKNNWPsOkDDmxWp z!MfOGuu<9vL5zd0R3l3b9YbrUMeV}wN9p=ET$Fg%v|N;}vIihNHMM z*UEsiy2`zX_7#<6qv%+7@=D=^qsdStEqZ0QGxZDMr4LvR@|0u6waXH_PJ3%{Ci|M& z8XJSy*fHhc8mbp==zBVHrSmgf;jT z_!kwePZ*sfs2U)L6hpU2`tpfW^O_M{3>$Tfw$+T<{jdWFXh;D!ouV+9b~)+&A$_`w z3%WZ?NDEzM0GQG4VQ?af3p2y3>WKnG7%fvk>e9O2lA^>fv5eh=x9r3q)Zplz&4nB{ zIYJghjAAc&xR?$^P&02l$B}@DG`;@;4bCdN4#Yw4+7^Jup*(2UM&Ww$bSZO_k>kM7 zAaD6+vHwR3(Gkf6LS$txIiq5R3Ybc+e6&3VPFfb#I$b@hi$R9!sJc3it}hbPXlC zj#!g3u6B;thGe?rOEPd58v#R}E=Hd!1DWx>W-4T&{^Y8$%RF;pugpj)vlLW((VC{l73A<>jWPD5f&L+CJ@W2u}o5qqMnQ5ZK z7~~g`{Zg7=LjzHEz|Csq|23eMOzLCWxr_?Q+Mw}y7TYi?Jv#$yvR_pJW;Ik=GR3nGwjp6A zIhP-Mikop8M80K4%}h%Tx7rK!0K3;;2ev5D=c#MWmtxe!C-CTb)}GsRdUZEpxTOBl zv~Q5~R_tA{sPls}+Jz-}LqX}_M_mAfJ!;$U2Acz-2xg`t)byGk`qv1ug zW?VIA{*SB)#0I3z?`h@D!DdHCKzi`D5aEqZq%Jw!|M5X8ODFZnuwknZZIRO|Mw>o| zb2!2Os`vmB#~YrZWLU*vE@$=F`$NGb&QR=0A1nFvZ0TGr>`T9!bBmiy&eE1S9*R7d{of>=Xu zbcPvW8u!Q_oc~c5&Q3E0cp^6SwM0z8#?SgCvt4Q;W1N~*aK+hw!dC<=W=c;$=+dCi z|J3s-*=JTGMRZQV^IiJ|h#~S2jx5N17mz`Gq}3po>Jl~H^H>a!xl@;TO$*$+N|1(X zaoQvOfeRwOft-A8FoPVlNw!{-_+&E4=uMhYTYza2cY{r%T-CZXK+u8eL&c^I#71k@ zL8wId7kF6Uk~Pd8;lfJ{m@2sP)m=&R(1>FIQrX(f`i!s2J}*_zyhr#6J6UPl2Lm!X z&tGgVc&{R^S{OUvh?JW$SmPOyY+_knc9jxd4RY}r;>T!G9%dA`ly`l$t3KKF+I{8l z@P*IaeLz^Ky!T`xJjBiUMbdtJ=K*d(d*LJb7!mKoo~6kiq3U5aB_>-TogpsHD~Vwt z#7D3M8(e-i6FamevSmY@ZER|}9jY_~POR0rv>}5fV|xyINKj?vAjO+iBsCYUt=< z0w*7-hn$a~&-VmdypQsycWjy%q3Wr&p@M&O5Yfa5g;9o)=wPqx;Dj8z8=Vl<>^{=` z&|7ph*~?35B=a5HrW?K2nQKk*0eMDZJJfusy*6oYY0#$0G%dd2D{!`q0b6BRi@mn+ zVPFG=6~mHet4z1Tw_O9fL&D|W^HP5HD#>LH9#F%RiG+Q^&07+dA3@_XKo}~izE(a; zck%NTVl{WyAFcI<`cyqw&_Hq4hs<r^dfjt;V1M?F2%|%>>9nt0pc;Ykp;?y{3QxAL{QLA#tAKS>M%_NDy=>9W zzf~OL$bX=PFuYu(Hk%l9rA2qyU-ZyWp?BF9lSt3R~AJ4`!-Q-)waTsnM&wYP`wRle{YVAH!-qvb7DYIdC z`xXy3RhA1s6T!M;xuGihJ@Kp9$`kCuauC9lPhc|W?E?w)GJFYaLh`(xo~?KJwNtmGPuckR z*!cLd?b)TmMcSKI)EQP9lcFX6?s*WcZv;Q*E9QyerM%YOdl+?eF`Fi`q=CA^swBDn zS{^|@n=Yvuh5o83a&tIvOG?p1y6m6>ZAt?Ee)&N{kof(**0_~EA^n4pfrB6(_~-0t zk&2i^N8A;rH;}^QJ}(s7&i47vNE!T`YgG7eQ>O9WtE%1xo$v=%*Fv=N^BCMv0_&ys z%w6c<(6{G>nL!c}l%V~T&8mg2$F3*IXmPvrCTjSML)fF`?1FP!RN~JQd;b8ylnzOY zz%6*V@oRLW`@l87m{K}4PXj;N_vd}ho=u9S6GN^0ojhZ***~-LyYE5jfw}12BkzO1 zuoe2M4&0Sih$AZhVR<=n6~+5JcZ1@30(go7e}_*MRX-(94QY>!%9VWk3^ru*r~0AP z&YvYGXF}}InNyWi)MoePZjqsYL_d$-n;W`)QgMsXn{lfKw6Al`fkAF+WZ} zs(e>gJ$aRo{J@U&jVXH6_g6;ajB{}u$GM2D0cGXITUR|+#>s-4Zd`#i_Yi|$nF8U{ z;%*ia#4e*sZ{Fu z5WRaSWQ@-sSN{Lu)r2k4+3||5Ut2H4hw0BOp?!i`VcEylZhl6oJr*viqSCFw2eo3- zX@v)S4wc9^8nIbM3covZSHW)L=IW{i$z*$HpvN&h`snxXT%+wIW*~Msei+%rkH}-S zN`tJ@z zPInZQgOPmShc{GDRkEEZ7gMV6vUe2%4ocRbUQOPXd+t~78~&8p*Ym6J_^N@JMX5lZ zdf7ayIiLyOR!~OlMWa)&1i#h2hcwD*8mS&;_CNF4$6MzXo*<+Ahye>qTh>=yeHnrD z7VNirbq&coj+866PbF!3NqlYtrQ%i283z~6;U&#R9t)8rU6goqL!zoTy*BS#=teP`i}jwVcirwM<&#!*EyoRuYZ5|*6u|| zK-{;;EIEZ-?Iq+P_wsi!t%Kx{EN~(0*ZC*n(6*|Ct|Qy`BJpJB!y7S8o+4yNNZPF@ zzH%zCAGJvdEnz7E17o%`ug&o*B5mW;Ndl6-x~3@bI7zj)J8H33`6W$$CYci#nn|#!FeLZ z_?N0sD)O>#J@my|438xUkz?gEjkQyoJ@UuB5>(kArnTv-3uExexxiW@V($=xSxokVMR+M$?h5XlOIWRHp3_YDfjtI zJ)RH8fMv1!SnS@4OK%+^H5fh#m%MFkw>$9n)NQAVvs)o}Xl|(54+8B`UH8RT!a>_U z5@_nTF9$P~7xwX$QwF^Ls7wcWIj4iUha)25v#T&Ifki@XmtW+SOg)YI{;+m;xD@7) z`thXJWagg4 z_|%-%EDzCp}OK$%qPSxJuGIlh2 z?Zd;>qaCYz!y_Av$(sPZ(9X5vlw|5CYuo%OUg~}&$+}YR@*9=C+1^xE8lF019Q0EM zfJQW)!E>MYbb7qZimFcky=WXpn{T$QSbb-z%Wc;-{_ZQ=_TtHrh%yoYzQ1gd9F=Pu z|9~dar8GPm5y8ni)N!z85mFic<*}pzT5|$rJG+?eHk!SNTO#!q zuA^R`hZ;|$x}S>noN+o`AQ~~>x+lX^oF9-lj3&#HJ<*H1_i8liH1B8c{sq7aZl`v@ z$(P+JqbMS^BMd4*17_h98p;_jGB9*jrk=HtP|Zus?~u$SD0=H!aiP88*}`C(!{c&7 zVWH~Qa*e`vC4X@{JGXv4%hPd^IRTZUoNXb1z_=n@@A0FCZG6=r-M2xmqRh$FHYAo> z6hVHKP&3+#S;!5A@#! zd7kgRdN8t)qJ!%A^>V)vU$J}lbFGK7A$&@4^h4m$za6h7G%xTI2@Izz2VVEx3}`ElS53%(5je#U@2+`e zQEo?FT$})BHuEAmUP0z!r}g?Gv->ptKr@R<<;E)&2g|(0tO-YzMQ`SZ%aI#V z{ocCnOXMB3_Xoe|>Nlv-Kyy%iCKbr+*^6J zZ&O+S&zPg893|>2Vds|N$pv)@^MB=WVgT$Q<5G^jw>5ko{5^NQa~?M4j-S(&VV(j& z4+|yT{a_K+lya1CCeRXnPO15!r;y2izj`ZApOXS~Kl1;(M86!S^lGU1-r)42mLK`( z!qxjW8Xn_P9T|#R1i_KsFv9j4Pq22IO9%Sw-2$Thvc79*wU*xXJ z{~3-|X4T@ib)%WkjKMZ!Sjw6~l>M2=^OLWpA31IMGUAn^7(PVnUc#}Ps_jWBP!x5W z_5W1r^QSNA$&)ZRc)}K5oLg)5da`S2UD}nGjMpOix=S7IbheKdgU~T-4y##16Ca@A zLdo27*PA`_d-FKfw?->eq%`N-DUD~F3{;%#pYTyF^-%1$Bw$qw&~EA_RV7HYyvNhEmo1^(!;@t>{>I?hHoh?wR1_NJ#n)c;$tGt%<;{5 zu&m!(D3PhN^_<0tn7vYn>kfZK(R%oALD_WQ1@~Hq#u}^)a3NHKUCcv&S?!boUj!0{ zD~Q6Mvg}d>jn^BIFv+Njp!#z12WEO!nYm)%f|i_=yT7d$?*Xhv=1 zj2wKVQ91bXs>Csa716(;>Oz7W2@i}2EoN4hJ|DC4Hn{R{moK^Py$srBN;xho8hCds zPt|(X?#_9SIy6KF{dA~2neg_c0YuVN;-`;@J<9f}{ypae%yt=7j}m@zpe9(uIf*Sk z!6PERE@4tt5fuAe^FF~fjPYLY^)u9^k9RB|EztM)eXxQ*1eO#^Jg1)2W$}^^(=P;a zj?E5etK1f4+KJ;O4w!#}MEu2pv~%~hmZ6QT!7oX^u^7RC3kJK|DL?+c*_&@M8j!T} zkVeCS;GM8zpR!JGu$qrBSb`DFfBDsI4IMZu$nIA zKI-+iGdCkjvrEv>G$C{DC)7E%6QeWzb6>`{_!a|RrKZY%&MYgZd39sxoFBIZbf+xh z;l~a#pm~feREj>MW19pieSEZkt~aA_>_4CmouM5?Gcx6kxHlw763oz2Tbv(ghHDQNU*G-i_oH%*;TysrIFTtZPHuMS^I6q(Eo1pJfqt=4 zho4Z=@WbOQ`{L|^G5aeBfTG}^J`o${wX zg^Jc_EfRZaV6`aQc=)w_Uwq@qrR3?CbfgV&IaL1inswY@kYM{e9|0)npAQYoZ2$D3 zcFiyV^rLtP@wI_ArP~VUTt_#d`-SWCX)X;Vz2%0dM5=2NHm?KpIkj#uywU2??SBOR zji{)Hc{Q=@ZrOTl-p@_>CLet_{i4Xs0FB6!Dm$KGE9dD3F=g-($N}Q;saKbu>hop9 z9eH2h=l$SsmgC2D?$crl;_5;Dr$F2dQr*#ndG_>dQnNn(zV>_Mt4*2EH3onOhw~0);UP{vRum*$>?LkOX-=U;USm)StPcMgMb$h&gWotA7y@X51 z@Dab0DjG2?nKHeZf%J}5AFK)KmKT?@i?20}R3iJ4soktMtT@|?#!4d&KfZH5J5{{- zaqvV+wgH|i2kVGnlLy{~pnkqzF8SUd?Ec!>Dep?r--7g}mEp|pW6WQ+ov+rsT$8Uw zDqizAY`rs}lYirKjos7N*@;8`Z)9N|<@tv)n?RA4&Bg9P6uC!0Q#bJn<_-3eqhn-) zyx&qp0_!<9Yby@+Ths2N?J@c|;zb$|GIEsNczLI0>g`sD+513iyGZBi#5; zQwMyUe(E7M#2Lr7U#&21#u~4rW@ypv^$_`gkcNjCVLZR!RuA5*Q&uz|nI61TYd9#- zr6K&VpNnKPbssIUI3r|i0)Kj(#c3^(w@)QbDD50EF=;yXH$#BImCE?XLHC7to0Pvq zAU1_~Ol6m1;}u-BkQF{H38$_<77X^cpte0+*v+!lWk9`Il<-q`kL~9=eYXJEXgLrGmpi(2C2q-qF zx)cR()+hmCqJMLtKM7=^9_V!dgEi{It+&9!`qy@LEqubChH9Ad(Ckrb&(n>^3`)G+ zNpn@mkCsi62Ao3rV7XMr2x^T}Fj_VM!^VPZ$d5z0O5Kwd>pT98h8$PE+v(RQP~VBW zM5_ZBduU{Mx~rya+w|jZ@2tY#gTk=8-ZMB+$Am}%MZ4m`IlMF_^_bIgaMXWX?tSOM1SfTN5W7l-IL+rhZ8sV8VSFUVz|FSWO52DLW&7phpa%k zn>!GtiSTb$ss=WG+@}A}+V3P)KotD}=v1BAm~gf{zk^@S2RB$teV31lyhT<<;ST2y zFAcrU>~Rce*4o8aD36hZ>)trRF>G%B_;oiZ3n!%AFem2EYH_0jVHwHwMB#E^gmBG7 z3o95fro_IfossN2TgK>>-(CHP!?uZ}G(R#dW0@EJVkdzgmpVb$z2Z7hCJafQ0!yWL(Ck#OQR`bq42n=YIaf;G5 zjdZ;}BT+V*P2|=L)`Fk?T zXicx(>=H90gy-)Jji_HS@W~h=A(Lgq!OSy^v0XC2E(oXNG8&Fa9^DGtG?HPP^Ucjl zqa(-)f83R$Tf1SoFwH#~;E{w0u6oE=jW<9td6X7=zr$eAbErM69#(YO%GB9K9F#+F zW#8UL^CtB9bgA!%f;wQUZ$kbXF!URENVCmh3m9r47-egG?aHKx^o)3mmh26e3$?mQ z-;!GAhe3rA8ug{NMV+!&W|kt;4tGug0>Ege(d>X zZrimS_H$huFIG&qG-WgoveiA#%w+tLP2+yFmzB!vMn!8ReGl})H0$e@4*$-B1bR;n z4^&AXlZ5f+v3oNUAG=T#!^#~Aa3p4KjC9n67u9K@+}){I7N+)tSEcW>k7lTB^EF3( z+&riwG=-`-J@;Z}u3kMIpS?WY7Xy)a+Nk;5{iRce*5`rcjV!`R+L=-`QkjyR2f=8D zs#|>V7$vFw(7(ZF06p}Z0IKo$Wp+y_VKfRRM-FCxT+`VH(30gz8B?wn!teC>@Hg9s z2P1lH#uOVqXQwO(M9AvI7rmm_W~Di)BZ*XaLyuYlbjt8>`B zuqXS0mwHu!jHvZF&UD|~3%IqTkk5Zcf<@FH(FaFzAqVt z#L%4aBCDbdhY#y?)b$gpNx<$L9>Pu8qXa0%?qLG%@3M$KO9!XFh_*J zzoy@ckJMfaoQtpp-USV(Il6Fnd)argq2kk1DS8MM99?UN*;gs2_5JW~lp+%iJ(eo) zcMy%>h->brf4o@#MRKezI4nhN+ei5`A~85j>|ciFq)b_wbvv^N}E-AeYi}%;859i zl{6udyJ0erw^lfzYf>3Cta<$taHcnnvtzbPAERY05{$dsKTy)YfEdaE=;ILbM$Y8d zyB2h0{@~7|CH;WN!O2hz>N=n@V;Om%TSH%&!lC>4r5xJ(_gChoF(G~w$1H*h4muz< z(IB4oq%b@oWu)P?c7IKq9O5WLCsN69l_Q;~XzYu%bt9BlhHBg6|97C;AFAiqxEIfy z9i{(;5zQ^ZVmFZa{2?R*XHWP6NTULgjBPMj{D|2_lYDH-1&O>r8kF){eF1ulE6)*o zfW|ANYUFo=tQjl*z>D9H6rLk5wCE8qSH+W_sO`r<3UJt9NSkYiQv_;(Db^)OqN{2~ zFhEn}2k5N091Ld}05)ie*OwgMsXDTm@O^*aKOp&N>w`s@Jq2r=a-xkyJJcOEM&pKq z8X;{D5-cEd2Jcw1>+1)1M6fY zMXZaZiX=-hU4d}9JHJ7W>OjJq6Y{H1#2LnEZvf|7q9==t&ucbVT?9&mh#6S9SK`}# zYmXZLYA64oFu+o%8MvAd^DTOPFN8^cYia;3t~TajxLe|7_|qihSb+nHR@TZYG=z@F2abf zAgu!Q!@+42me*|<)jnVtksyF^fc&N!SAz$+dCD{qypzF&ilC9C-|CD$_9ZCdJk$iA zh^QS0DV)&K-z`1@e_`O>|HE+A46w>G%|ss)H9tWS2G}i!F7y*1%fvfa+2F}3# zxi=sLDro|mjjd-bvC<9(S!}D{NqjLNUqr){H&xKD91n-1s9I$=&1zuw(<%E`ELs$E z!dRFbdtqhrBl`y+b+E(7m&p7d=`GcueHeo-K_rY{mW6rs66YRIUZYFW6`+*=fD`~7 zmENvDf(PYIUgG*AKrp@-_D9JaMh%d7$J&?tDLAPtNvI z`Gd5umewS8l6S%cV-*CgO!3Gn7L)y!9LXM{bWRDeVb9JcJ_dnWFhv640>72 z(R-Lw-AD(GZxaFMi1FapgvmPAO&E0Pd46Yv=L9StJ(OMzO!!lGD=#;g6cGCSe1hFV06oPVS|w5?p0J5S z&1EESn!VKY6cnivLrg;!2z{P_0f~^7g8dH5QBGR@7#F)nOR9)jig#I(Ozu5^=c;io z0eyp_kuaS>5qIMeNcVEoP@1Zw8fGG+fASkSA$^bwYNAzV5dKm^k`2>l5ox7N`23H5 zRQ-Zkhj3=wR~YryM$XOxgM((fEH;t2Q}5L08eOVtpHoDcGec4Y`E5pWU| zCX8zmg@5m-Nc?l4i|{9OJKu*kqXsMe04%m@I+L_WS^OcxWmFydaDqt(uV8cKCW}lB zXBoj6y1(I4kGOJIw-2yDCZ~51ARwlGe1gmb-8UA1kM{m|4D72x?+1(1%q^>!3CLUq z>7;9y1O~B^G$00yW-&2m;`zs7Q60TW5?}4-+{6JN80}ZA+H|GjZ{`dtMZqsF4YkPJ z4oe0aPp<0ujAf@ihHuc=rj{;e$m9)fy_-@kW_~2o>`!=(rUx`ku@k~1<3Yo~snP0M z9}K;lWiq%-Iakl}S3}>V# zhruq@NJo*BIdem#lK^}hRHWKF3VK<+^=XwLu%b-b#J7d-Mzl(0=I|;zM{oNo0$fly zEmeBX2MldBRi+yGZ;E}jC_9z1y$;$L#fTXn?rHkNkp+56Z}kH<=2mi~gSNLDTiH?j zV*ddfH;5~ZEm~k800!!IW*Pg9gtoe?keQa>f{mwzjJS|hwHaLCL!(9@)JaHfiS=Cn z{zZ)dG@9B)IytOJkE5qib+&qoNAk?T9yD5y54z_laa?6}Y`5n2{ebY1LW0fQlmaMZ~c8D$T!@U8T7b zd@nh41W?Yjw|EupL}_>w2>$_Gv4Faigy$$K9wO06N*T!;+r9?Uxxr>h>GeK=NC@b> zkyKPvcPV4c8$)o=S-^iIM`~SD^oJ@&b8|fl=9^6e*U#oc3Q)A;q8jg>tnlQ>VFP4C zmu#<3y5jX!@TnS8COf+fT*{Uc(GrnUH$N<17Kxh-ev~amXmp0ov;uE{0GP$MY1IiW zS<6K&ex)9Y0GoAF^GNv9Fx)QGuthLY2c5PF-g%R4rqxie4IgUO!DtyE%<&+RpJ7k5 zp#M3hC=si~G^PLf#3L&G7+1ra=yH8N??NH+CG&**>~pSc&Fz_jGp1$fN{rDt1bFyE7R5ZFoV*cF z4T~9OrrvWu_Yn*|UxqtO^#= z*ZW>mWdzy{0~@(R2eh}D6m5qIeE&vn23^vSQ8jbDDbE9FqMGd2pW4Q?Vr6+L>FTBr zWQFX`gpTk4f7FF6c-W@joxb!gjOiuFE;D-*Ea!4D=oK-cG#AN<$65Rk)G6vH1|XWR@7DSC?N~&v))Kx= z%#p(+`}-2JHNCry4{*Q^kH?WuE4Cdg)XO%%o|ZrTXg{ox=ZRNe&_ywO=9LeSwe!CaSP;0zrsno;hR;CR-3L2}Y2D z6&a2lolp(nktB4nmhz36ly7(pDg}T%4jDWHY1LY}$$NahCyXajST}91H!Te;5=s|b z0n<^K-}bIWztDSb!Jnp@yP#8chAnjMp6|7tu;dq!Su%9SbpUwOlqi&;RlQ&{8bLd>9Z9L1MU59~~EMs7QrAG$g zS1AqCrmjMI*RFK~B2H9y`=~O*=|tsWsyo2h{YoALF3Kt)>AC`>g zb&5HG9$)wKr?&z?`|ZYV12TWap1mv zUlI^EC})Dj$v~n=5_~ZRRY+MPGFvKdoy*cic!Gk!?kp{==#BE1Bi1D*ejv)4%m{zIT|AZ5(6kr)!$f6BeQ8@ zfFG(8CY`liodu&z?*&d}1CTy>GPAT>Y`VMM*e*X?q}wPFrYWhVRi6hqrG1Ks7|u1= zGABV$O+C@`&v7|5UREGGTg`$*h+fbD9~U6oZSGwgW`4(gYg<%vlay)7J9HW03n;vjic%Xgd(OX0M2|@nA-4P*c@hMgL z?3<+tYf{j?5x+a#By?9j&9MJq-sg-7-|!SCWZVa8680fShgr~S1AThOphtG9;f&A~ zrSlPWFV6%>P~_K_Haea*uAH2cx_2XFZb1HS!U-?dnRrf9t9F)>l=Z(pyL;372G7zI z2tq@ta3)!JdxvNy(JbL5cLNd;QLeOODcF0pDUAqWx43Gu zg#xeP$j`&tKY1HmV&x#fa?l*gWVr~V`Q%B^6Fy_%V9BX>DhZv=4}G6_F||O{!ThcF z7fC{5AEQw!kHM^x@Mwd>o~d!hAfpRuK>;SMMs1SF#CEx=$W@)KGh1}%@QdwVVS-&U)@gg)(D8`Ndhq-ImYiIpaHkH z;jBa$h-Th?8YSWE*R!*+F-tlxu9>@Sil=rGBAOB27j7IPAxdD6jn${JhJU_YX>DY& zhqBs8Jhc&6S)@U+(*7k#z9052p_+X7xlj1JjgL+ zV?Nld8Xcu$hWvCb_w3M!%G(1OJ;M2I=wC_dG8JV%1hJRny$mAmo zUq-mNjKGiw5J$4BDqQ(KRNRS;`|ixl@7}WHSNwO|DL`40u)4_U?(0pTebu4wW2GCh z-wjql4mqFpm_g@)IbJ>*rhK|30*+5U3xBw^LG}H#Sn;^?%AuNRS}CVEY|d9RHVbwT z?7Y19>)lv|r<0YBC=JZdFDl^Qk03pvk5gnpies;)R6Qy$xg_SE#cXmOYmtbi2Q7{D~3x zbCz}VM2+5Otr#sINV92s2U<-cKB+p2G6HC)nfkr?^{#iMwz#iK!slYaKGJ3Hs` zuGY8cEnoiN0LJw$gKHgE%j2zZ&?;YLc5iN@tF!AcL`OIH@Th@gnqxq*rja+aK!}ZA zJY;ozv+;|EtL-HL%5XS2US)0&s8{N({+CwVE&G^vDI;x1WVz_6OGLYNs^0J`!QnN(TH}p&es?Kw;zTno&3f zd~r{1sRZR#mtVZGY2)Rk&de$S+jD31OrZM?F6{B^XLE}Q{{Y1v?68@W_cOn1Xa2%j zQlUcX0Z6stl8s)=U=+0LKVWTPBp9AOzka%!Z4sbyv=t#)2Ry9U`}9lgQa4XIz9K8+`&c9}a$ZeMwcqv{Xg_I`Dp`h!3Ax>xR^>6*etXk? zg^pTIKA@YqwQeu+t(3NM%mN?#)qCAoVB0QXD_m|*a;uK84Bq5Dtd~scd+Rym#Q8+R zrd^dIrUVrIK0i3e6-iYZuDw|)y}xDq=k5_@yX@_MSKfQBoLi`ob54T&z3JzNTuFq1 zM6<{*CdUsCjYO>Vf1U_G>O$?Rv5U9TC#Fb4O9kaebC%IR@>fu|LXNBT7D>>$N$Sqb z%+`U2EAQT%T_*o~!B&g-P>78m10~R6VTqeq&vtDGY%Bxz3v%A(7?xfvK6#GB1XBG3}zm9*jbj zA3I3UCinuU1FwpU(_4|H{5mD~wnj2;Rd@^g)owo3;!WiZXQnWj&Ss%KiXR>^CLL0g z6E%)U+&%OC_0ZhR1_p`US=WAj^iJnpjK5YVpg+jvA+61;0gK@gTV* zC9#tj^R~BQAF}mGzwb8vs&y)x`?+=Vp~ac|U`po>fwONltm7XkWd%e1W8JXLwzuqI zh~>4dPC(b$&;JzmyiVlxZ08CKv|uxj{plH8B?t@!Npz7Fcte`iC~(r0&Fxe_+W^*zonDVe5+uX?3DW zNlP}OSI+AC^-o*~nEJAZHc_@yw3um&C>2d$-R|s#B2}^yhyfcLT-oVMKO{&H+%dyH z;a{}MY(;L>s{7T!XQJRR-vx;=A038(<>lqzXy!;Jjw8EJWJOFCvvvOw|C|A`GLhy_ngAhe-%_t z!+w;{(JJMgJYS!{XKcZlRNAl4m*l>$$jHh<0#Rn{EpvD6>$X>(q(74yN*@%?Uj0xP zH7hs5=K+(-P0)|B=`^KU0iD)P~#{MkKZf97(o-IY~kgETTv&MS;|2I%)6Q+fxn zM^gAl5dL#i;%rIL^zH8}`aGoqwE*+4*2BU`x6_tmH8P5-5Na;WSRQSi(f<31A*y?G zSvUa7Aog_5d7a{&V2^H^JOIM)y4QNUc^)a;hQXvDEsNg?&Gz1MEOe`cUm}jh&|A7C z37<-?oT9H=Y0;zFW>!bX;FQXEKxGteUHRb>y3=S;qD3`PD{kap^+|$me z&P%Jg=}7UCulZblIIbNJpL^Gh2(!xZR0F4w2Gu&00LRs84yrHbUUNXm@0>@BHwy;4 zQkl6Aot94BhnR|W{X$BVb-{G@uih7@m@1geo_S!d+4{ZVCU*tu9DhvKhRwCc`GL4d>Y7 zrawW%nN_sQ_vEkEiPTVAFPa$b$u;3(efNS1Nk*X9z;0Su9}PzYzj4I2y}tC*qxPH- z$h0Z(+SB7u1OXmf!#0itycbyzRXnQ&*N%IfI|MXGpeZ`@O$~vn&>AQf-@#jzkJv* zTjxIf{MqK)vtxh)++3+k%iYZ}CbVTjmZIFi>)&k@E;lRk?EDdH`J)+m^;87t_3bS? zlz#T-hpLPEe11|$)L2O@!g7#%=+(F0bFdIe=QAl~{(+%fnMTkBFY2ckB zb0p}ZT{9u@-nn+P2V#xRnUk_MxUc#%rl$xTE zTl2R&rKo=I#y=OU(ZLG_h|zd-W4&&5!2h*8)%MqksUzPm%Y4U&6N`KWASqQVB$$_6 zl)4Ya;jC5>6SPym6@HZ4|G8dm33-nKk@|pZecG4XxEo@MvwIguc?teTBZUD$lyA?$pUw zJ_6bK*qE@CXd2IH-!u2uAUB^l>40I^y%pKdm1I}<@2a|LSSRdvVUPvyAH-${8r@r3 zSVeq}drPcBUNq?a`t0r)tL@a^KxoM*i%}6WH>ou~loOEHldUpBQSO5ceWgGw^x|GE z@if>!=E`S0h()9CIh_Ix?cB}$O{qsVndkVgud8Y99kTYQYp8>%EgC@Q`?B7jeK7gc zQj+wD(J<5efH(eobCt3TPTkp`Ga;-c8|;mlCux}1(sYFls%EIHYegj8vZl}xGOBNk z1UgVl{rW+F>QyvO<-h z^?a0C)HsNHU&B@u4bz(xUeBme9nW4Tsm~#Zf;&g=hF?6gCx9|F*lrG4o5D5y@CfN@ zf{6nenRC3>G}0CoE54lZz^289h6eolDdYQv)+Rao3;Hi!N;|=PolbuR{cjQR}a?QeQwy`==jX# zzhCrk<@prlYf8GS}@D3^M%dq>{N?!W@*d+Q8!|HBX zrNl{v7EHSBx8=MO{7`qQl~>uv7zZ5;xU5nzg+HQLX)PG$3nKjR*m%_BT{X9T^jnj% zRnciBk6WIfe4Z@hp#7l&j2x%G8K>XOI8zK&uf`P~dq&4_w?Kd8RPs?`N;~mo6%+c! zGUIk*;Acd`1=Uli3w!cf~<}AGlJ?^msi|&KxE0lEWNQsONi?6wZ)lc+!&4 zN2>QX_?05ad-CcY7fxdp+Hc6Mj1SWg_zG>ynE0xlH{V`#7}j9$jpQ^um|5E}V{=4L zC9BvdGtk3+wMLs+TJ$rHw?VDDQzB zjobmP-YkgV6_YN-2npEZQLe_%=DX*PnM0jR=?oZG#=|?Ve*zjsy$-)HRqylIaUBXC zMW)b(pCsMsi90Y*$~# ztYd%G%*Ta|DMxFb0=B_CFx#f;{tFjwk4+TBSPd2WhFGnpTVti^JOR7rx z2yA>bUC@ty`=X%W)uS3my+`yRo;1-`c8gr}kFBc2OBI9mS=+IlfEI*9pZeVOe;l2A zJk$OA$3HWyq{$sM8B>(geV0RN4zsB{B+Z!)3QbYB(-3kTlG1F1sAg6Ub0~)rN*Kx< z3Yl-tjL}HM%z5>|jjI@t@c|hvq z;~=n-SWMnoabkqu+4;FgmJD6p`@^u+^xkW=cSrUN4Bu(iXaVNHNUvh`NZ+=d)l*Q; z^9>g>ruR-Y)2LbbC3Mrm$JJNSe@R>ZeeBqR-DT)wfM5v9W(d_vCCtjN?o~+^J{te|X+P9{pAlGdZ2(M8uR)jWl!d?ki}eW9>cY{#0n?0=#}C~&jX)74LD2&9 zt!Ci!k2%4G2<(UwD2^^WzSvyzNTC(;+NL`^$bPW@$`8oJw2u4k(dofpPmENK2Za%hj6TtG zslRz|!c>8O)*Dgt6k@I$3}Ca)C;aP>)O4|1Qj0l7?LZmHk|!y5;|Jfq`k$!0z4m${ zL)CAR)nY_UvVE572*4cr>UHOY%)$$tf-ot7HM1W4^4YuBxT1Y0Rn$x5Baz|4$!N!y zxqz=~}KLElW>tLePkB zxBdMY&tE;Yj^wNVg7i}D=A4ect;3#8^`KFYQ!|J;{`r7w`sJI8e+%AoLol%MIfpR& zp3P522_xf95fKhZyMt(D0=&(T#Bx{q%nc-=E7`%4cQnUgpX)GlXSEFEQC?+Hc#h<`%6# zAOG|i(-B5K@K2k%4??hm?MLe?yWA|%nZ5sM$h<96!4Q)kh0#u~;K&~H_gBC2<-|wI zPPV8rX68$1_vw|ep`RbwM?ceox~}QZY>U-;rm3fIuC5qX{Lk-$>_qLWOFJpq(xy(? z9|v|g9}n1PB6Kpo2Ls|~-SnfoSMcv!vO}qu!0ram!as=~6@4PI`t!#}W)6I%zw z9iz0a={0|0G-%%NX_Awtk+aj24Az$Rm zPd@23RH292!fq{NAyDjHlhgb3zxP`rVs1Odln}4lcym8aoIt5d!0fSIRx2|1bpL*j zeekLmvK{}oO6X>7;-t-q5f`pu(R_r=&#HmiH}-l46)cQY!47uKq58@9>Ya^#ZUx4W zZK4}2y5lcc@7x0LrHR+ax7A%EuDgtYiqYe>fs)@;F-Et`^!G06*V9{HvF1ovsQ?(X zDrRx;zq2)(Txj>EJ(zqs9Q~x!KGB^=zx9SX0kXz_5!LVSl1-()f zM~N?*v(~br=Zxd_WG6Cvs42gJWBDg+KA+|F&CH$al#Gbc0;tNguS1wO)O=%V2S>Dc zmXdw{MAlBxiCZUjlSPaa!{VAwNg`eA!fNCbcE_3!w3&Is$)@Aw?u7c7+QF1h)q#`9 z+n36G*a)SDu3M>DeEP7A$BeU>sR0;OT3&!P{B-Nw(LlK+&fx1|B8AH(-~I&Pm~fe? zOLp1){Qd*EZ|FAG?oO>?XqX)2W*X9qQ+HZtci;T#ioCmy2i-KQ5XqZ@k-H@wE1-`N z9Rd4_^++G#EMij4Bp;LBs}9>Z0F)Xz`h0*qO(8X$Ec#?_DgK?LeV$~nN&Mwhk(M?_ ziOIhh{cKZNOF96I7Y>GEJldBWPaihJD2CuH|jVf)pZdN1%)VQ=~6g zO8Y5+=2PxHzp)FHNdrr9JNQY~3p<2z^yg8ac{>|cb zl>qdQ2ncRp_vB_wvN1zgXiI{vf+MoJ3MaC5=c|g*^8RwF4V|+-7(oN=Q^^gQ%u7aoKmrqM|EKf zPKdHfq<-WQyNULDNuea%4;!4u@xL6pj}iNjQf2CGt4Z@h7)d7I(u`~{FD7^k>9@+5 z4pTs0BdMkk4q8eDVBoiCcNr}RGC@A*Q8Ri)?71T4f+rA@!uT8;yB^)3DctDA>Rs1u z<(F!86uXnqs!645ER_^TX>PZ;@4d}Bpp7+2ow06`utg8DVW3tsq)6R@^uJU#lQl|N-Lv2h)>Q6(^v|~^Ng;veWoSsI5cFd--c99pwTqg>hTV>;B z%`*uW6|uxmF{d0r^l4jpPl7(6q`7Sx5qsh*#ArzM#?A z8C7eGy<3PF>RrJ!fKJlMV^Bk2u_fv^02&Al9;+i7kvTR#wga728NlWcMj-9~5jvJ3=njpJ8JU zDhc#^VmaE>XUsKJxQl(r6pbytN6|(j@M@wSwaE$PF_#m zxTV72W9!nX=C6FfB@r=b3PvMU&yIt6YL{F11B=TrEFYSxL^dvtPhoH zKrFE_2xqo(`mi#evB|7E)_O7H0ak~rY%^}%At4oZn+N{)E!QdXVF*^?nnr1ZMwdd7 zp@RSpX~QJS(T*CVz6}qZh}$4z)@C@AGbifjxgS9iJlvsb!J)?YQ~isS7%*Wu`l1}n z&dT?ijv@QAA-DJ6>@tdFiI*FaSoTQr$oO1A~FGSq-{~OXc(qascdupZ? z1sRNpto%@9xV@Ja9&axB4b20ykyQ;RrK`+D=sfPD&5-9Uk~$&Od_&4k@s+MB%^l6u z>tAeap*5vDxy%06a0yLC%J3p75Tp6zAT;>zQ>EeLRVLR@3$vJWdP@sO7VI-^Ub6t* zXXEE*;wdCLJUrq65n?gwK#6~Td;(|KLQHNLpZg=m+*2dIxFnN_dWF`ow}he*N;~t0 zhLj+!%EDr>(C`5iHUK(2<1UlnA8e%xtH5wBk($Yw9i-`V5}Nlu!lo3&*QRwvQWqGK zkD3jKmX0Y;Jfk2|AB9u;HynEB5%bLBUul!Kr)5AK_yH%1`-8}oP<_3*gWs9LG$9v_ZThq(Cvto)GXzDPis$UD>sM0N{xFz zUl7ITq=#_57>pekeA}s6NaPkq^SO(75hg~aJr5JmR!!4X!W3Z}Xj1_?mOSN3pvmI1 zO96x*E6io8Qu@2BQgTfVf*MupVc}k_>|#0$k12!z&2wPjn*}4UE%}bElu-5g+_^_* zkz#s*-cI%ouf=y+;aiKHd_zLYlNkN-=+;)D6HLpr##wVMGOexCNtv))3i#;7b_QkoY90h?$p6Z z8iA-q@eXLI#RwQ{-l^!1v2k0-mpa=5w1Dtqf<`0SHF(+r8Ey+bG@Z9#!4c-(M5`^4 z35f4>$zdO~wCVgXL|DKV*II5NcGE&c-oUQf`x|7LTmBGIYs-8#9P}I7kq^3ZV`MRG zyk>YXcbT6W8{0!tMJvi7fp7?U<3{FMZBR=TRw}ervd`9-OrYL^jjZElmj6iUZgl5e ze{FH%1b?ThfqYw)H1uZ1byeGGTkt^jChMjZ& ze>uKG&DCtx6nv=T&^2$Lxq~`^I3YTB%62d5?0OM9 zKId1k5H)EFMI{#kP^jtm7m)>4ak?BRHo?+zrg0lE-j+wHh?)^-m2T+X4nB=%grLJ(m z31M%cLh}rsNDK1J@L+@Eb$uHSr+uRaxS~&%(-C$DAc#}!cnW%ggv1-y$fS1e5WA=K zQhwpGp$V5zzRGkL7>XA{P3wEREwNgYDf+Xxo%fuE&0P#vMl4TykPhRqi9Olr+j|A1 zK-evt@phU!F~@CzAwJCfj@fobZF!tmK%9POVX^{(n(4*qNM#G9-THZ1qNqDRLG(B% zB_zAk5eNVaC-;mkpi?kJ7op$5LWylno$ARnmb{!I1Eu1@XW9rUO+bhxC}vcFy5(hT zf(E3D{6ZT~h?jSCGlSGCG*8I$Ez=L0UH{{Z^o)K@T z+x9a5Z|s9GFu=<+eLUxb#mHtq4^c30sE%~$FN9I456UZT{ z?=gm-j`N`2o!Cs!LW|=QwTFFql9_4L^kCEzAye6j5yP8{*4DqSHNDS5E42y?zlv3QtbNkARc zDB84V`ss7Ni*zm9ZKUhWvHw4mq&~vs!PXC$+V`u*HJfbbB<#w`(wYQUW|6s3_ypDb zhwkug@JXkmkLulN7D0S%@N#Q_->P;01 z6Ocq*w*9D7qHI3;{GJZBDW?zm&O~x$!(OLj&q#QHE)8TzADK&@Djk*KtUI`D7Q2um zU&0K9>`O$qOgfKKU7&eaOvg}r6>nq<&7_g=y1j5saKhT{GtXPa3yRvhb@GT#V7N4) z`t8Z$NnU`D)@DREG;w}dcjU3S*Ua4L3#3ZxK-a18@A-rJG%t=S1*2J#+}MzqVu8;| zkh~V~;ZO>Z1~EN?2kL3$TW_Cszp>(&iCD)AU6Wt88@kY+I8kKZx^F94D^Va_CXXa*CBb1H1p*E*Jq~w8j8%&{U8o05A zAGjL0)2C1^I1halTx!6en!T~0{xv*QWm5ExCzb*y#x?wc_x{QVnOqT7fXjl0!YNa~ zFz_4fN=v4NtQ4SacWHFmOyS+1mmA&g0!6!)01sotk3Cf&(wN(dh>-H`*kjX7c>bocA>>)(Vra6xKonF9ehZ(kI}=9wby)aM#l#ErnVA3Z3$S zZp;KK1du79Eu+NC;}TD3fFiBOnbR!$EX)3IYg zhXgAO*zF%i(q4!yZv_>Np+>IP^SlmO!IX`{MhH9Kc#01j^HypAkI)Sf6re@-7x;k6 zG3tM=c7kr`QHtdzgA!IyrC+T=**irv9QXmx~wnjYvbw{oa^prC-4 zG;#;?k;E!ml^PDt;db*Bpk(39xnAk`(|kY03M56t{}GNsyEl&GZkzT3dZN4V-0ns5 zQwuU62tUh|ICu}&rVitn_Ih652~&-;P+-3WbO-zVlHskq-3&KkP9(ss~PH z82G2v=k`ioTc<@AXmLLC&sSnjbR2WXIb!QF5+ov;QWKDb>KHtx=yELBqU;7k1Y3Tk ztvOiT@BAN+6Z%#{?Zlf$J6lzu-%^gcF0;jn;05XXurVJLXNj~-jh3jK<8nv$uTf+O zY`L)@3R-~~y^Axo?MU<7V~9qECjt1A@`lPa1q4;t%rdw~>OMI9KAe)vnLYpU0{>j}9xmUoaXZJ#zWMtumN*5=e5vm6>2)FA!v5^4#U60&~v}Qo7z+W{sMT3wK2Y! zRE7iEeqgX*ZiM^R=<}$s{Hp=_EUs6Q>-E6!U~$2DT`=l^{)EvT0hoihKK7Db#j_l1 zxS?Erq5^+C`Z(#4UU6U;?6|^%>NxyP-VhWN!MC#2<6sD}?6?3K)dqxUdRWQ)TQf8s z9Cm3|Ntjg5Ef*F6Hv(M8EoauE9UBGgL{u=6*Kk6E;v=SWU!T)Z2b?f>6pAlW5~(v5 zDx`oXlYdH40gj+Ubrsyq@^!{T_nah>m2psz!9F0x)XYYlE7-(9?1o zcE5qYyWt@q`b2M{u#sNh!AjWWDG*upqL4tP0T>fiIa$QUH`wH(H&5cX)9ZA?i7m#_ zj$hfESL<_<0gTnWlRH{Cw-%g_yW>ObwDACWH}ApRSSo{08M6wQeH(4JN->fGh`Tsy z{2cbojM?;;wsm3`J{+#mp0*}Uv{pgYu13B0n!)|$rM@F%MTwQ?N;h5dT4aCAVR5hsGVVQNJ!-a6^diE{dBhO5{0oja3VT+NA!@^AN_BYO} zj`8|$AK>jlBCx?0WE7v}n^f~Tu!ukx$tWeDKQQ(!yZn*HAi}vi# zREZJ)$)Y?vYjUmrVd8J#;jvWS_c1X&v3-yXmTSOeN=&V=(7dgp6_=|P8&|^vHlnl~ z6tg?thGceq*&1yIr+gh04%)XnIm*26m~-=~GQD)#5f;5)@wJOO9hPrX&~d1K^qn}r z=NY`&;POogBC7?rW%?p(X3ARZ=vjorss#o;H)p-;j$1mrmtGehv>jHQrt;wFwf+B4 zGrJ=q9A8_dShj)lb+)r&g!s6)xY z6S+=5%;Ts z*Xon^>|lc~`eW@cD?dDrrA&yCgZa-lc!J^y&+5;km*PImxn(k|&E|SiTn< zB{~fH*7e5SQm$f;@7`j4pa+t^FD-ze*n@+&y7oLT$h|9WJ^@e!;aQ5FR^OOuo;6jYW{eB?5-Z_ZdA9;byvWhf+zO8_YPij_ikH%5^IRnFoDOfN8cs{dCBpAHW`P^ z9y1X&WR=+ddlhH3+=2*VZxOM&MsT|8(X>4}j$w~8eBDjsTiN3x6H3WGW7Q@oj{S7z} z_D1Vz9TUhe23|%vC{fOh`-@_8owy&eQ29647Ga{pS|#9YmJ8|(;$_2KhQSl5MS)e& zn(&pIvZ($@@|$lXyMvl1vMp@4SonUklkTFn0j^8HZ{5U;xUE}w1@7XRU_SfnifMD(G;es)h0 z1qI;*iat0T@W3}}tr;QXr(JY-Sk5;5oB3M!TM$gWZhMMe=)s{uL94<;t+4I;-DJN$>{3T$(~oX=v9 zIL%PMeYh|$TMTLWn!t`+ygITtb49&!JyFY1IY*C{)19=?G-T_!*uByz8K~Wt7uZ~M z-124auI=*iXG2Bc9pxKY>n}{9d|n9KgfJugY4kr0OTojXO7~zMB`4?YP4mx5S&i_M z?xb*1I5Cw>yh1emk=D{}JmeX5l`it5<-R`=rHg>`mdS}KJRjC96%TVe%WA?K9u zri$LoT;At<=!krqlWj5HhzEW)$MSEVCd8Gt&}8ay@8*r-DX^GGmn)tLnV+*Jj;(}^ zY@Z=M9wiw0?ap3fsg}Ou@@%yM}5Nuo22DjX0x_WnpRYf@amdnO+U>XjC7eY%#4}p`Y~p_rPN=hpHf42&}z0>OefjLNrf-m9>)acHdPS;Qu5fdDZV z(djuUMdpbnRr{r+8PpVbjsbD77PZ^;Vu$p%Olh%NZE)SOS$b*n_N>?S14sVXs&W#L z4rK@4x|hQ5atunNXTSTNqEwLM-Qaf)VJT=+RUgWQ&R&sj{C55o865fl-zVarXYxMA zOT;6v)LZ(*I_dkh0ni`qA$oK1sl5O2<#UsBN6R{b$jS{{{`pSlocf*WeX>6*A~xIu z3`;I0J-iQ|UnZ!3%LRa1K=nBM$XZzvRwMc3$%{GU z`9$9yVoE$Yn&#q0@D&da%T7DC`WkMu8Sav^D}x|K_IL(~X{p<5wM&M!WB7h96OWai`X03`2uH*j)MQ_Vimosn0{M~iLl+YhKQGC(r z(etI)sr$|?rgj%|Pb2ULVxC-i5eO#ld4c-6YZDih3@Wrfq{eiO39e!#Ft8bhO8}ILo7R7$0D!5#0%(Jg25dXL179=Uv< zNA+g0ra?-)UiDpVwRd#umjgvCM?^5*~%hqRMk(HzkgJ#7BPRKs`21TF2)*HxLY zb?2Z9W9{{k8rLBY&=@h{hI4(6MAbQbXb=g8DE(z^htRlRtJX5MG)O{gd^lfpX<&;o ze)g0UGPZrgtMJut0RH3a#mkj_Nv~rM4)m8|EQnX0O|OLJ%&JK9=pAhT?YGy*rge5o zX~^cqG{KNa;_``N+_kWWA7QPQFQ=~Gl)DEpb`KZMn`XF}abErMN%+DFbUvS@j!@23 zD)B?@zC3*IS(nc*ly(pc6;k#1t4H$lDyby6SSLM zKcMA&;i0ChAW<;0wxylHi8~*xqDwxhhT_az3c2(-G~|nif3>Fu!S)V;?B#F$?Vs9X zgEw?Uvp>)X@GZ^ScS4+^ko@Le%W$c2gp09B;A1`YkzE|}; znF9xP+jpkqqS6C&jAIfY(1bLHGh~ZN9iNyT5)IIqb;qg$i`8{{CD!hvdb+8Vw|QmC z|NB=HlD@l#FlCPk=Xl0G!u+h=*)-{;gf+!NEdPi4-Tj8y+L84+UOLc#3D7?Tv*kZ{ z_TTRT`Wt<&hlXtFKmGnHV;3ntknB6RBx8MBsics)bphaOnKv21Xyh?fV!&hrW+QJ7RHIp+tC|PGwH%{uJMJ-v)ezv9Gjnb_uV__ zuP16LKO@75k2k#X&GDxfS*|3s+A1<8^{l>SZs;hPT)eE3$_8^vikK08_WAO0 zazR@Mb?EMWy~yU92Wzl7HNTvZMcR*lgu)Zwo~q4f#AM+{bb;3V& zK}*5XMufM%(_=pJ(L=4XUT7a5E>ozxsNLr|*c3SBArSU7jTT1}vu(f*zer zPJ~jKQ&*EiE}e_{r~Fldxb6s>e09!%2(=g5Q=6ip0t{HoZB-Lp2O^UQ`TMh zNTCUxT>j#S^eZ|oAR>q*AJ+EzU+pE*$&vs)#RWDp{B~&|PjX_9Ba(3N{ehX2mLdDh zDuED6n~*2crZLPV!h|sI`CY-#B+sOQMwHgEU1Wl3hEbY9&&YvO`!O|KVv_smCX%VU zoKOMu43+-)%qIhkSPu45pt-}XmY^}!sn+dZ;||3j?q2$JNU3NIp-m=-2cO8=^V7La z{Q8|np1iwnrgmE8(O-3>sN#QWpGBXPAyAuWHsbFTZD8bWF%q&=3T)jLZi33bse2)F z+O+@|q?VvgA`UgX9Dirf)D55Ee3OtUqblC2une~Qq=51scYyh8575R19ruMpmn;$3 ztdJA~8n>)H=5N%;YvuFHasdx-u??Y{&(r#s5h9uV>-PzgXU`D=NkB|ig3=qa=f?-1 z*R1bP{><=2Xu(PY^dg+DmFJQK;tsUOAhF}+Jv-y1yrCU=$NL=heE@*sZ5g{56NC77 zYC9KYMl?Ad{4xjj)XXJ~y_y%ke)!+>(a$8&*pc~%v2(M+mkPfo(;zy3nWS8Z`nqq!XTEqcYnLXV;yQUUU(4cf$2ED?g0I6Hli|Gb61D$QKAW(hw^b->+{L*;CP(<- z7eYtnsNprRHQCB%dR*?FkxDIT{kZg4oDAktinK3C$f`1~cMaP{JF~&@+2VZfylyK*-^bG<2G=ZpXpm!3KNIb`Os z$qI}jV-03n878*lb34fE&lL6ov<2OZM>gm5qMma8GD@3$gDSZ7sVW<@BqEvXlHs!( zF4uE!#?ucZt?kZ6eCD)cxcJ9mB_JRZ9l2uHe9NB0A93rl zkrjMJyc}Tkdi95njMcw)-wkt<^Qy0YX)(=`E76u0TqKe#x97vyQ&v4F?I~Da8C3qE zd6P*jamZ`e_S`8?s5mXi-f&$He-2Vj`QOF#*LP>DGuW#MmVe!0$eivw@lQg@XlKd= z_Ti6D)YL3NyX@73h1Ky8CU0{!4m)z`BcqPBnbg(N&93+n0Ecn4=XMmG9C!$o@&H)BwbTKg3KxaG{bhtC7g#lWXrWeNgi z8VZP47Cav~gg|7O&|adbYklt99O6vg4Sf5Mp`q(f76N>b$4te3&}EEDUvXar{xDWd z_LDnj{2)v$`l0fY;GQ8%9h&-dLF0dy%sT_+FGT3J#8@%!_$qzGcb+2Y?X(^K4V=z7 zrA`0u$%RnUM{Ca)3UApq+!ML@EuMoOPaV#?K;28H|U@Lur^TaT6{ke z!@QK5a^>iiF+Mj3|6jII_v*Dxg7p)rR(x zPQ8EZbJomiI_Oc@>&B>VC#2RYhs1KAOmLuxh}~;E^E1hPpUU2@HHY|^edyJhb1dUT z<@6`(?S!{I$B+=eboS>v-N+Wj3K@M0sCO4Pao&L;bG$N&L!qD@Y zHCzATRH1@dd}F6RDcqibXq^nnZ{?9e?w~m~ZG&UT%Ev~i3-b|O$e2G`A!@BX9O7@b zAuMEVAIJ{d97zB!mj|%k@l+L~bcHi624xN$VR3h4e#O|U%ZIH5AWaDd;l7xb*{Fi$ zPvP zTyX=l&dNAEMkW33lUdyOo zF~_6XK1uqkwNxwjO$PNjL!yQXwbZEgFrYp8e5cEJ<+Yvv8FLp7S0Xqh3kWdp^Itf<#Xg?ldbWP`KSfgmp@ zWF)Z1$q}2jHx$jZ)5cIX;rcmGmX@xW8c}0fp0pTtiP3dICztPFbavtKJ+Di@H6nTH zy-xOG3j?ix*cYukQ3H@W1-heW?RQ}I4>3`ffV**$Kr3S6S$3m7Nsf>Bbgt!OfDBk} zaXNGNH{hHIW@r3?4{rSHaHol25PeNAf=~dnD(Cq;Q5WeZm5~o_La6EH7^AJ5J}Y` zMdvw@vV#YPXDu84#B;&qcpYN_7{RM`5b&&kA`l=il@Ifm9vB)^SJ@xsW)K)m~z>%5?Lq$M~0&5x+R7o=iy1 zmE2Hd@WwSd{w#V5-y_3O(h%G8ZaoZG!Fca#+0lpw;Fe;Wy<4nRQ zn1#}wyL*Fwcmt&UVCSl0#>@#C6s)unixRCoaC@17Rs9a;hi12gMfl52xV3$Hu-@KY4g*^*vIGNLaP#cuN9F z$(&9SB7`O_(bx(a;ESLP-r=)cnWlT4rjcZL#G*n(bOVI%%yeP%P#$8M3dft;&yzE(^*%T-e1<8geOURp~8Y&Fh%1H zvGrGp9I}IM8zH_L#6brO#KJGYq=Ji0n=Q+wm}~ zYlXXoNItm7hRjcgtnz6P(I<15Yv^Q^(PosUi2omNavr^XMN@6pW6b;1d2kpD@UtpP ziL4FSuLSDsRkZG}EJW}S%)nvYX?^x-N_x*(ZfqZ8mc@_&2!7E7kQ&TCqW28HqjmEG z*?w=WM4}l5Q>P(eGvey;I&4nJfI<*UoTbKIUQgNnRigwm?M)UG!TS$Cl)l}GZJo1GdqjqC zMMD7=ZVRXcb7S(JJ6&K^7E=fq;}uD#$f=#X5jRFurj2~Ln=;I|CdS%_xKZ}U=uvYO3y*1IfVXA# zXCq~7mmE!$yrvwq9V2y8{j*t17|QCZ4kHjZ)4ha~3=hEmElY_@kOokiEAuyX8bTMj z(KP!)7nTZ*0N6tHnDg;Mr8^)obQ6j;Tv=h#V{ODKFk;f_Y!)S)j~e|1=p;aIHZ8@n z?as#GB^5C+&a0!tk}0xmH5tG3;Dd?ye(;BZ8-O%;bwt^`vWRPz!sCY492TG+@44g< zxyD8XMROz2FlfJ%4@Qk)Oe^&k%tt=T)c!Qy(lQuCx3=K13}&tlT8)6<{y7ff(2Do{ zB+=}ir&f#9Om${;bv_6i`>uy1*Q~I^A+0Rl5U1Z(Y~Q3bS71}tlP&>0T*GEISQ+iP zFp*rdHMp4C2|JCGVu@<2;>?Ldat|maT`Ca{i8%ZYL6=#Qhl&K;2#mENK{96PU~^`} zo(G#Wgi^bDsCD<|0cF}#{7%+=c-q1<0_-=OqD|Pz2 zX4`euPz1RC{g0Dm*TjXJM|*UEM=~hn0+9kifCF_9#n0F9XH^sa$X$s`sR$OvNaiD) zW)~Y97bbdRCasfwie3jg%*@fQG%pIx{x-7I3=J)3_mHO?HK5QkchFyOH|{K%4@JX3 zp2M;eJccqu#5tdQV3Xsq_e==4H$ed*dB;KDVwv@DmUp+NhsCR zrJ%RYqkTYwdJQ=EyHRmt4Zrrgev}dQ@)A3A+!vScIt$`zZpJitwRHWq`Ea_ec+j-1hIWK?cs^yq7Rds zwqpAQOEom#5w?wuK$DSj8rtQ|wzmD~tKdqYQOse2Jl6T*{X^>A;ATyecBhsRmQN_K z(bM3ZT9Q%ePE^Xa*!3GICG9s6H7miyQg~{+*{Y?)s?6_A_e=-o=)IJe%^gaJAR#z6 zleiXrm9#f!aZ59w5^`)rJ?F~kn3eY+>kwS-C*}>kM*d>xPOH+uym(4rgsnsZRK=6e zxSEv*(F>XM4DKoe%S7prx;T1(@mDe_41rc=902@*qRwF=)lQfX>2MD)!%qGI12Je+ z@=0+<09*IccO()=N5gB}iZC$^wBIEvnG|1>I(m{EnBw1gAndTf*|O+0Ti#IY(+Qam=t1N?~sN=Tv_7^S@B&D~4c zF)sl&)>?(X*lXQl%FV`>EjB*zoD9UlP^3FO$I3R^9_|1RSKVh4UM#XOH42Q+1kcEJ z{n!?BO*kCzpnRkx4$>sQxdy|SeQyuZ)Z6vU10geO2Y^$_qSOApt8(3DT#t0Z^FKXV zd-vj)pt4cZY%P;Jx!zZrhpJ377(3PeYoOo|Qs9VAcQL-#t*}c)W)|<>4rv_BeXgV_ zb1{Ff7vDJkv(buKR z4okuOhQ7C`(W^#Y^gM89FFe?*R4UnxR%&R<<9|NAdXH-q3KHi4)mSPnN+*2lCNs=$ z$FKNl*egq&cWMc0?jStdka7GkNNZO|+|CxrhApJqvwHV%c$5Z9)x_7tJ;_=VB<1CP zdXT#QqC0hPRYj#o((qd+JkLE+dXJc*(cHZy~RY7pf|4< z0MgAw5G6H2n?!g`Eo0lC;u<|+hLbrqHqRM51HRBl>eIi(qo77+UF!%AeVppGG11 zQ1M4-rMjD-%)`&mG*4Dk!vM(Cze#vY#9R__6O0MCMb8kv=5iVkl=LF9v@?z ziI+M$FOq8>X1!o6CHH?6oqIgf-yg>}!-R~YCUYsut>jYLFr$lGzV4SU3QX@ z(rm7w*6?*1DVK6hG1Ml6Oyz!Qn5DVSWp3Z!=l7rgJRUorbI$v`-_O_U1#0A9R~VoQ zX4!w8^u{ta?I0FM^?BScrPS(y7 zh5%y6I2O{7f$F_a>gLPZbTD0yuEt*m5;NN?r%WUuLdn2Bqm0_8w1g>9HYXjldrSl~ z=ux*)J|CDk-5|eA11^If*1Xl3X8q<0w@$LClgBn)}n;mqid8wen3Mnt(Pzpv^| zyBv-K-{^SVU!S|GV9H_&7rCbrAPm({NZgD5ujSc0yu2v5;OTW3z43dv>!S!_^w zz;PK&h&}B~NLXWd^(UBytJ5U{gA5`a6q{ZZ1R@!}fwIc8baVKmxTEdZT#(JgbG%ei z*F@!+9)U6kYPz<86XjYuYW)mkW4#hiV_5e=3|HT;7Q=7hJQdMr79PjrN&*A&>K?$0ms% zBOQX|?uqq*)G#4&-y^*U!GM6s>CkW?QWOwaVzSKs2(a&>N%h4RfpAIKH(GBM*G2=R zp+}Ga>;c55sy@XgVc4}wh7B(EO(O`>wIHuYy&x=QJhOVCt-}1<%IY6LLJ}nT9*8ip zL6)rFXx9i7HjKnMpJR%VvMXm^2ygVn#2{IGJ3(3a@yDYI<{S4$B1B)?jOVdyQTqT? zbB4tJM>J4wq?BWtlQW#mcr=L}O^%)ToWvpKdpPWG2~(ayu z11P%j++TGG0slV&2|!V56^u9$ZbUSf{c==3Mkfsjd;k$GQOC7)OwNnQvRVM6^5;VD zfg)odIHkh?qy`e53_J(fDT|n~wNtlRiRi5`z*^4j>j927NgGr74=`UJxlpN&IR*u- zx8<;e3uU1VL%6o$I_WyVB8#X5?^u~ns>g;}_Go|I3f;Xc+FD<-PaX|y8onun zARfGEvTs0}c2j@bz9G8PicBiT1o*)i#F|I24}h?k4(O85aU|6QB3h5e=+8!YA=xFm zLde}k)2}xlVRv4mUm`c?#+2F|nCkup#4?kLEJiAxHVTTBvdS5uA zJY;?oYhMZ}iD2!|Xr*c>1fdk$2Vzq|NG;(}NrT8`pjM*dsrPsQ8sohk`g#DJ_2=L=ZrJ zsK8ImagkgQ?=X{|tTGCjYq5$q60`<3IOkW|aEUYGoi?0(4^TjYZhU@ls#R7wz1QzpuejE9gn9Pt_yg;~5t_9G zn!$0{yt=VTGRxhkDgPNrK zqPC+>Oek=uMxRO%A+sk>;WX!i6zgx48r5_+$X9)K<%V%rq{AyO<`9MI7PqH#+>?*I z`w#Sab~}*o;-ezbe)3Wb3<$Cj*}vs&?6AGLQ57VjJ+p?JBbM-tX2Q{ zC4Q@%s?kG^(}UvziMi2(f{ukd3H0E=eiT>kExk@gOmD{8n(%u18{ zH+>GKv`ntdH?BRosba{=7uAUeaW|cFpPxmND6+o<IjxL5de)L^J?v5U{`P{3D@S$i5 zf1ef_WalHm1YFjw9?#=#^iBZ@D&SeB2Ci3gh}J(>(f#6P%e{Wdg{RGUM=Y~0);}!kyn?OQkKgM4DXl(y4ID- z4+up{n%-Q-xJo2(?bc9XZs@_MaC|W^Xx>P&PT=LI#bZvU#nHf|AoG=-G7uP>227Vu zKB-&HDcnV?W29_SXoX zNkU~S#gRj3itJi_S!r#J&!8~ykoo43LfvQnDCL=UsTu`iyb~*!o+2g#G46x`wbonv zu`_<>)gY>d4T@R5oc4W5&e2jEA6O&(c%{08-m%8_RRR;I#bZ8w(!_m{&C&Xf@NLRr zuXJt?z^AI?vcEzb{u*c98X8v9l7%0ou@P**V|L5Y`ss^$|3%;G{cl$RO?sst%r~td zCEuBEZE9g>Ya9L3hB6z}9-tA_jq`}99$6~SK6gid#ZkEmY-&$zd-EiBsrSq|OX*4) ze1Z(Vaq8oWTYkrJvrwIF8UoBE;eLD>=}ytPDvd!6ny5|K6UVAFUBreQhAr^wvtFJT zHl*vcgXhqOk#?3RDuWJ+3?9eUDD0ET%y^Wp(-KtKMfOQ>_U{N44!Z7h9&q}P5po#a zu9p<<(;;dX)=Pt%``_Hh56MfQKgEj5ey-DFeMvD(?f}Y@QE#=~ zzHXz$c~PkN!T<1zSAx65hxhF{W?^_79_t>A>%{NZbF{~cH<|AUHC9A#Z=T3CUv4&M z8ho&I%$1{)4-smeHjEE!^&#`+V0k#>$pEs;~ZB^`uR*6tm9)G836?TiVO`Jf3jk zUc<$+{PNPkM`3oKV=m#c=G$XwNf#FjE|#yY{H!N^COl`aQkVBR8(ltXzahp$*S}x| zfV73|(<4}%Z=o%c9qy8rd&~|fobU9ir5LNbddS?Q#b$zaa}D-rb$-WZAWwK{*vU|* zPkVg?P?Z?~O|raj z0v~>R+Eu;AcJxMj)ibN!irvzc(tfS`St2mD?6n2EbJcjANtR*`SI~1vSot_bl6~G% zMX5rJUF-|&S$-} zc5f~X2srxlru_P&d;Gv+oExf_zh04BD<&goRYvRZPf)F502*|^djgrc2ekIJLggYQ zjkBoha!t=1Pw*~|G}UpN$+)bnuB`%$RXMS^vQ>QAhB(d4q0VnlzrpLA%IwlNEPASi)lINIH_^KnVG7P6-DoO(YL_8A`z0@9#VVFQ;> z>jj?D>DSs`(nAZqfM_F*lUaw7ME<0BU?hvlw-Z*W{P0g};PrI#)gATkC47^wz%YuS zX!U$T=j&`U3?c5bv=i*W_jm73(=Vq`Tbea5=+<D|b&gfvE-4#(-p{Z|XhnRMAzVBp`3zOOxfrgq-v@%r#^sB(zVwCLzA z%%0(gb(&2dD}ce|C@Q|mL@>~`ipII>+I+2G*kahU1Id3Fk0`wlVMK|`U*7I2}N~<4t2a+E!ly}x>ds$bl(@(#+fFONrpC`LKUR2$9mUM^z z5`wV?oM%?WQmf9Xc<5U?d`3)8wYa+%yIwkIWz-XB?4}5a*49d2Ms&4&Ya`|YJ(Tz2 z2V@TL23<*&evz>n7j#Ru7w~}~kT@BzRLr{QjGLP$z;Kk&Wk>0ZZ`k?;vg*`4skAiL zyepw99t5bic79j+(&rvOND#4*g(~-f=db?-RyoCVmG zR~xj!^|j6WuzOL?7adNlR@g2i%RPOJ~n|e1_V^N?tiMrkk(EbQc@8(9~4^ov;J+Z zIpsusn$=(HMVB61Q$`Ec`MS-C=&x~PE<+XaBEQq~Wv9tiFD&_B2l|=U%3CR@4N0p^ zY1K{Ra|5KpWRdG+SszthvrITNLSLP~)SFpdej&3byjPWpnYvbIH*(#qWbIe5M^-N! z0se9|Ep*%vHIR3D#!ONFJ1L+&`KS3%&^xos{&qUF$=D>{V!=A&`zLneobq1(c=BKWfR=FW_OeS&Tw3`rz6yP6UGBAFn=JHE|Oj@|$+RcQsx8zjgAG~g@ zBW1(cy9<-av}NmzE~=cG#Xb~2jV2wuy0vO&AV_s5nR9Bv`u4xB3XTW#HUeY7f6aX#30-dFp4Mvqe6IC` zXh>T^GCktkTNa1e(SI$zp<_Oc!IaT2iPvAXyc1zFs~T6I&tPu3sARl9EMQ%266W)7 zWwCIQC)Vh&!O8E#)!3Sf{)k>jH-A!o@A1*P5_@<$B4g}&{nXAp!tJtr{~13=r3Kk} zya=$`u8u`Fb`wHK+4u9CEdMk&=0m%RZw#8=yRVYmJyRbyTHpU{vv~-i--At5Z-S#+ z+Ncc!zsHiStM(Q>e2Z7xe(86K>8uO|6KQtBr1j%Z-fu68{ku%;HiY>WU;~62QoQ8s znJ7plYoz%8#E5z5+q-YP(gYfUd(5j|V}^Ry-OjvRSI3f5%17;lHOF>e{5kdq` z&XN6{!RUDgbf>LM!>v%5j%R`I4zec+IZZ&oz4Li$@n{ZYSfRzbLnjG}WyuVJv z*y_XNkY0K4U(MM?iM>VFNB;bOQ9Lw~Q5>UOq@ka4Oi3~-#=uLUs=V4>ha628_sD)w z@JpHaXipx=J8LuQk$ApEYe6S&RUxO>|A+5P@36c#{|fAbSzrT;Dv+NNtmOLD5Bilu zatqWHh|APcv8P`b`;|D!{Birzs(#MKX`DnXwf1DJmb;+W@pq9VKd%>$WK|x#P2cqY zBVEcSkgUbU!6pYE(4;2IdS#8GaKf*~D%Vc9Dd=qi|(}u%>AByKu!N{N|a# zg8`ie%Qv#0-+}2wi)(!wiwc64?AM4pXv_*2IeeE!XEoIsp5}iEsXqCS`004Dn9;nB z|3DN?frX>9kP{blxu6hZ0KY-LohwQM*bC5LE;vcK?mHlDNE98J*5Kb6=ASe{2CM^h zacA1As{(|&VDjo3i|=%47~GIi4++A?Q}cJW2KKIX2>%$wrb~MXu5ZOEUyT#TXyQd^ zM%X?;^FB*KdimSh&M-L~YsHg^H*5yLpIXl*z807~bmvaT28gqbK){|Z zkk8lWP}A~-T)=qHWWgmZRXEVshkqJni>c8@5}xw_!%@2%zUSVPw2oidp*eY>fHd6| zUfJFKj5mAxSR+JcL*nAsG&}Kw?DYA=wFlhmDn(q<_UMS-n zhEnk2)$Ah)d<6$TjFvX~Q)Hm;r<@}JF+$Z+r;)1iG>rWf*RXdTf0&r1Q~`olUa{S_ z#Yv9d4DA#X*wtQmjgJ{s8OrQQgoK5{czk*4vu8%%&KQ2DJJ+T0okPeLZ@M>c&%s0I z3?u?$Uf;j39su{etOS?kayVqy3qI75>rHw}5j61Sz$Uv8&A9(#Cr-i->WIx(C?4mt z<_y!gBWFJeRi}vCZd|W`8JcNp#}-?~rRfWGk`@8X(r2kG7y*5Liq^&^Y#>6){HhCQ zAYpQ?ZX2|{2FamyKE%lbP@ZfF<2IU!4EnA?G`Ht5N;D6i zZ~XAwY~?|a4KO($dDnkrtl#o_$fF7yl;a514VM*rxxW=)P!5YuUCm2~8^R9kWsO|t z{CwX3{E2q-f!?Ni1Tlxb^abQS#7X~GJy+J*O~HV?JL(+-WZv|7zCU8V@&Jy!nKNh0 z|6MeeGi|*?JDC;+n4d5_IcrF2j(sL1QB>D#A#`gQ7?Q^orqS0-#MpzBTy`4C=91?7 zl0IB09j!z5a6ICW&xj*{NuD;x1Fw`JyheDt1}=9J8V5UBi{fN&;C+@E-L4d~BAw93 z+VOpVwDVcCj*1Z5kmRo!X1YW#ue^ayB%f9(*t-o{!ifJaZUSeEp2>ZD<{r#M+GmN= zJLPT`ZLo=PyOcwyydb2SIP_KQ;*b`#Ph?EqZzv zX0;vlTd}PW!TR96ydpf|5g7#Xh4G*`KX1#%gJ|i|#{+? zHUF+{x-aqV&O}P<1Q{%z#1&#`8*dF21?MFHf!8okB?pP-06LA`g_;UL^xyU@AVwp= zIpAgUxd%IqM_4~&Q{`xWT z<~`WjeW*3s{x2>M#6A~4{-$LHcd(+|N?`bSbyWn=N>FyOBfdsI=TZk#pG3rQ>j&6yRAK zMTKrT1;;IKB=KT`w{i6QFTIK2lTqZI`J}GA|({J3M%89 zArAsI@s?Jz`ivmTbD-x9DujfJC?jTXl;j;Vo#tGJzD@P(f%<{w)fl*;@?*-Co|Hr@PpF`Tc z@AwakN_|tCXK;qo$g3NG4da}m8b3<3^+ghZUZC$0b@SQys8H(T+pKDC@{>Aa`~D|* zI=o{twB&al1JLW-2j_V@LA1@QOFVoiKTeEwtxz_1)Mzt6XuE;x*JM1tMQuK>?M(p# zzVq4y7?-2=GQm#5tnA47&y(q`D3#rXX(%_(>tMm!mnUR%p;!7+; zmNi^LJnqDgq-4GW*T6dQx_4OkeLF}QbD6hFY|d2xc;cAIEYl-{le6URvKnY5kaQ=H z2S6yMm!d9^$DNbGFbs?Uh*onMhb=w;*>(fL$taplc>g! z4d?{O5AZL=(`P7TrY-bEm~G}ZmX|NMi>tA}By<9Fs~AcMl{qZ%DucuP8K3lgOPwJd zOf)%`GF}w3Pu-a~Hu{2;LY!DTD4LY+^N;eP(%9nvif8gC93VH%)v0~G#p-4;{ za5LgIe(_49*i}fzO1>}~la1o^1}qhpTu&elmgtKNV-#1pW+s}02X{X73DtldDg6DE zw!&$}lM18aTmOMf?fFSYu!=}TzecHbnGvwwDyJCoSYUC2y}1i6q|`|twee8`#`2&Nt@>9 zk>8;5X2#BQF{QlWyWIESD=CGTuot4%Po&5^#>PFI7clSrqm4Ogam_?uUmGMAM>EdL zQnLTvyA-2q?kg$)l2t^?BUxvDjhbh&7N#DfeNAhGw5Wsw=B9Z8R_5p5?pzG+0|qto zc7mR+kbA22Gd~MGTW?QG(akx@sbmQ}C@Q2N>6SJ&VSdw2DE9a0E@)CQ(i1LA4?new z&efw5S^K~#~fbhgo(1W+p>!;`odTPS>wi3rE`R9Zc8!omHyR~)< z2>zt-ITW2_A8RRKiVXq0AOpIxgo12ML=;}Bf72AOUjiGk0snDM^4&ctN>I>0=lpU< zQjMc`!zXXy58oT9hXg=@&%Nx8PR4}N!^y2>+uMQ*kcAQ}cEMg|LZes{(Nr-T7||98 zECIhUCcE~`qc&xP1iQ{$@tT8-sa)`&6o63-@Cqr1@u54k5JX6RHxiWrsSM^YhYLGP z(X=%VkDAvYEMaR+1gz5`D0I7r_qN0UD5ouJRK&B5w7gar*!!&>2|-SSd5e~V%D`kf z!gx#_=EYP1La`A=B(i|s=I?*+h(=chhM#Fs(=buay9rowJy_7z;q1wmA}(Rn(v~?t zUzns2S*ipC8pm%B7 zXVeZ7c%Fcl(8gqGYLurkW=8r#;YFhQStihLaf@85&##7fbaOWe5Mb@)q5jWgqXU?o z0EpEX_h?4-C?oH<@q&kwiVe7%jtQitFYv7Cu~xWveoUm#(kx#51PGcprQBH57T56= ztuxP)*Z7C{5g{j^Fikz3zJL8y^vow|L^nQKshX*)TuWb^?eSPP@-cZ zj)anl3A;?L8CpJk4omRr&n^j{!$_#3&=Nt$Zdf2uT?A#cry|iZb(!8Td^ioTgw1Ri zwIa&cNT4`O>AW`h+Vmj?0DgP&;}9%CeV_~HMalHa%k;r$`Vi5vV9WFf!C)GV;oto4 zi_QqguQXZS|6PlN$gms<@f(YdcDn2>jYJLoWF$9>`z><^daaJXMU2doo7VNd{K zF*Vum7vUWUjr9No2tSMcvRGu6ii9va@iYXt?<)(rr(g(c%dzoN$s>F0DQ~fAL0YSg zc+@ShU}Ol8FWAU8?LhD#h%F~PfdvxxS4fb7gHDfgNjDAmGC?ztP?51TqOkcC*JRXH zv&MVcr^O#2O2|OZ9l*z_z8)cTJ?;YFqiiIR!u^Ay`agIC%dDoYF{~~Pa`3ulk+HSo ziBs9CfuPcWN&qC?uf)Ziv(3)qnDS$)f?~Eqs9MJMi5)EI97m!aAPpM+xa1UwetdVR zW~a$EmSg3rdc1mV#HA?4yrEsb{`G!o8kDlqPw+lBH4YleV|z(K=j* zP>me-sbQ$Xrx-wgBrLo!+~83-AS5GqdVCm#N#g&`k|a-xQz(P$>&2KbpoWv|VEBdR z3mTf?ZZIHu3&e@tNNF!${htiauZpBkXZPHed&Zl2MWrmouofGgFQ5~~E)%JpfUSR3 zQOw5zB%H^9&zq>Ve#PmnOahzqhvi1*At;u|C1!$NxdO6~Nw2qR?FyY#0&th`^55|~ z4k+j>?zFU}(DK}Z_hOneK|fUC&W4#335oHEVz_ME+TsYYeVFnIiJ&CZW2PO#h7Hyj zoG%~^vVZR-2Ba>=_qd?9k0NuT&w&7Ln&}B9?KKvPY9m|!qUXQ`M2kBefFd(S-GT;Z zXApImz@Id=hq5%ZO(gc8R=3G%2w;+7oC!h*fI8SSy|$*wHiaJWwceHDDYFQ6r93Ch z+iQDh3!oJv18qSHMUC>9oRUhe?>N^~2tusa)uG`Jb4(0*BoB>{g{n4_L8Y zDRc&76Kj?GcwBfq0#g68KvbqBYCxdy9xY#(B4MyF35$)iNg|pUJz&4kEmS2ac5%!R z;%PMsVw;JnhTEd?}g!-n6$Ez>+Vnp=Yy}rrd1m;SSxfAaBTA5?$>b z2jl6BC1^F39V+}r%X2k>qqVNSlxKOp$r%gNh^fG!7(>S}Afdnp#bDN+R$9=kS%*+w zm4daM4hVCB&I;Jp1KS?9-BR`i6#Zzc%6`*Pn?F|L8EGdlb$NBAa$EtJ^497>@42y1 zbTk_M+GbiygcCPhC}+|}_6M#Nu8CMpWj;%Gy=2PiN|tD$%>xGLUiV-AY26SNQmg)Tr}Z$c5TGnn6Md;%D`*e zz?#+gmNybq0fr(Mjb*mfg7$xF@DAp&f9A!1OHEJ$lcstrXDlN4@1RE8;4dJvtID$5 zZ}ED>1mH`x`ie)%U0Jf6&-24N2+F;)g#Uq_M{|g>d3l+s+6HlJ@`<3c4V^1cAaW%S z&>48_bGTj&l~v&Vl}I71z?2+=Oir5i+8C;Fl0o;qy{DhsC$dyx^NN)m3h&8^8b%I0 zd)1k%#FjIeLmS7ZKEB;f`Z(g8v&y+9fyP@Yo!eiY0c&PZ!~znJIlX)Bk634t_aY=qC-p9p2A0j}9C(|rPKZW52c z1V@q^d6oM!0|Nhx%*Th8vE@IhfidCW{fX!&e}vAYnjj=4L?F^j#UzjyXa2ij#4QIB-x5T6vrT}-*M+qpdp>Vb*obSX!fBG~BmKe8i+nJn{ zqJ+N&y}Mzf-C0nFkDMlAtom-fX&8pdV@&j}7IsIBnSqc>u$dPsLd+Vx^!_3rV*4Po z3OS5yrTxWp6e|b91tmvgn*dTw+oJ+FXY&ACmxGkT`haCX9cf5Lz;fT$U^n}HX63isgku9WH5ooD-Brxui~1(1c@O2x(i zjs$c^yGb|p6Qir%=oWcjyLQ`B1Q!s%{Od2qtbkph=vi3$WhsG2@)ff{Na0a!q;Ueg z1l%V@>+k}mwN!o3^irU9WH6U&pJitSXy!xEm^M7TVPD_!#yy(+rt=sfQe1+!ay2g$ zwReSwR?nd$LOWFFnSct(^XMO_a6BInV@6WAr^N z21Z)K+EDq&QLwj1`FLk}3Ia!0>j4 zS2(*rFZ&NB2?(17^ucn0@R<+fkYVJ`US@Pl`>Tds*k&?FlG;5!cP&6bJhy#su_sW{)0TKHfp#qRafT+5G?mIKfctRAnp|a_`I6H)fq+^%%yed zq=hU7fklE@2M&e@`?eEC=Ok{VW&Dh23=<5Bi11Z zL~%f}ZozP`@5zJ)=IOGOj#$TW>bDscLfS0UJZ%^%4VuJRmpal%Lw8DPlYmEf6$?_U zv7Z4S8*8MU`Q9l`MgY$%z+TfR9m(tMPpgWI4RI6(t7pxp!y>Qn;c!(dz~nNFSWCZO z;5=mU!@}qL{{z(oqCdRAi6A{kD8XMq7q@>w;EL^eOU00c2FXCE+A;%wsL6ppv5Fg_^I=?u8S|dyG^b%26FYVXP zdU0>J1Qe6qGG!vwlHYqvJ97D-Rt;gC`;;ta)3Il5a}`WDk!oO#$<2W32cl^7)3gO zd$6=Qw9cNimUdGhh)tSS$FA_`!M_N1@CO$vzwto07&W@?;mr>*kxOdIcRgqz1CY+I zpV`VPK9pP@?+j=KxdUa5zx?VU{U7MCVj{|E(&GWU-iX98r5Szz>2Wsg&VY6ZKx1~| z8eE>LjKF!sCaS>&ed2l!6Vn?1EUjes`iq@g{T&HP2RwX#p^pz(~G2SB;0 zfiP6-7O$kf(-aMJZzDUVn^SFo4?uMca#zkgP|rjZsXF_|_|XfUdZi7yaM{8pWV^UW z+OB%{K|^dG?hJ_81GELuUs*fqomO>N3W~=WCW;t=>BcQn{|IUs_%L^jYe0X^M4Un5 z5+7N^88ZxPoDt6HW92s{0rnO?Qjg_sC4+Di9}L9FUL-&vZ3a_R-)W%7sPhMdY{$40 zGKU3Mdq$<`LLd~L(G7yjZtyrXYVZ!6MFqyZRI9skHsfLd$pCzGuPB!z(*P0z(2xg) z_keiQ$)s0}UgSNvLaow+A{`GA-d_!40g!30HLElq>T?o=rcVU#3MsY1=MGL|u3fxC z(~!_1M>*1en+SSDc>!8RB`?A*p!jRp+sfEo2*iMGj1Us9M3fPcefd6U?eJcXsZpVb z#=qwSEotlwu8sOgiEgA%y=}2r>sY*A9J3^HFC_V+gastb)(VnoCa8t|^+}M5GPD76 z82uC+=TDSZf5t3Lh1;Wx$r2Js+vOIRLBh_oJTz6&irV;1@XW^T!<<$|=I28vsQmSO zVXmEPfPIg-dppO5v-ovgnX^_T8i%t%DtT1{07TRyS(@?;9d=7i;8aRARko5KONT|^nVOw8XxgjE8V`3a;n6HFv;fo-KG0XZunQq+14v9;a` zr;1ninEL@T3DWkb4}cKjm>L8yz1#X`ScTT>ke-wd0>wGkjHM7IqWT}**LoBF zQ63@E$tFrOVZ_`8Lx)E9tiuGr(%~3XJoFfzifs)hq>T($Chdlzp zFe=0>T6+?YNrK4x{z|$VvN$+f`5R_3Ux$CBKB@gb(EdlaNo8rao36j_ zl$PAMvm*(KNa;XKA0$KuYOXKti5?>U+C%LBdEElf0QrGdFk|0v%J+v7uC*wazA)Wd zb~jIpmDy6TxxaJfR+2c(kt~V+ViNl1TT5E1-kOX-dd^77AOrE^w)d$1#u{X2+5Pr@ zQtt7jlXhjQ{y~wrmJa8R^`;Z%-Bgn8Tl<6(#*HF{miFWt!J_@-q#YPv{&n}X3d65q zq(RG89<{aBTHaaxt;!qdcS4qam*#Yt6&+CAbPBSqFt_>P%k0*zsoE)r`6pHn909$L zIGiPBEC%IUA{1}ovhol!9>+Jl{gphti1@f`8(N2iMR#50%$4tL{gn98(`La!0rzYo z=-!~NTzcdpLgC{UPO z%qXiqe>Sc_>)adD^@B~smP9+vS~FLQ8Pu9cb1CkW65#T)<)T72UI(es+Zu;k+6NVo z>%B9kfk%~9%wC^Mg>}uv_F7HUyuTn2VV|DALwhxdgf&Q?bf5P~_+7zMDWsnLSEDhViqzWXjB8Dw8Z*UTyURYv->=8Ct z{t_@g`t*UqK`E3n#0bn}^08MAD9c!yUu3Ind&wj7b5cj8)(Hht6}pEjVD<|T>GbDM9SDH12F3jMO>yY`0+B^4;rXBJDR|zcRQHnM><^6Y% zBcR8EGCdZrnP9n{c8IJSHu)+|vcNdu_!Y|jyQY#u>_@ldJ}f{KA8Yy=rimEd>P2iv z;hY~eSxR8=lX3LJ9OC_mDX~M2ssK}Yqp*y(qjvPgxKn`WWmQocmI-Cbo7Z}epL+>X z14~V-BKB^!_dl)3y0wy!5x24q0ow4+53}(Mwqq-e$Epvoe)w;0TD3>}QOO4T9${f^ z6lZ>(?^M51eoSKrpKcIz9tir1(Ll@pOEbszg1n#{(x3ZgGw*dC@qO+9B#w`~Fchkg zbw5yN$cTPWTP)RpXk)NETr>L^^De-;Q(D3`ZZB5jU0q2uV6dw&x&}c++J`jMNTq&% zgmiI?N1II=?rPu5C6n1bnfm)6Sy1>6mha@7_Ynnj17XveH?OM|63s4+3QTJSMn$^Z zy(;KF3ZD)!!YO3kN!T21Ih_MGY($~!_Rjvedh^<|t4bsdgPnXJqhdzc%%cJ>Bk19c z!*uc9iU|eJo=-5!pqRL?CeK#F0z;^aif+*wp$(h3m5Zp=BAW5bq)k`DH~T0YdAXq1 zx*2hFU95|-_#gYqN0kq3yB%h%)L9xc_&ujF3%*{&1<&yrX|Mk3u8nhFqK|JMZL;0p z$MP47$=z1h-_>-m|8d8QbZfAZ;5S%YZSxZ2V0(5Q_Lp?xKM*%(TZgvZeg}9nPVUl& z%$KtZ)=redX@_NRB>~;FieKw*k2fC)KQv=dq%Mo*6Lnis_w&ACw-Uq`CRMN*y%ocM zF}{A4Z7?ANR*;6aa%I;6QVD80M)UVLgZX)~S<2(;(aEygZW6i%xGZM$dC?DJ?<$X; z`ei&7x98jyeJp?{l1rLUs@ztIO?ilsIu9Vg7j7RRB-Owb7mm!3==V;MFdsEaqvBHW zYjjOsuuE#*&`!0{s{_YbV@|OeJ7WVId|eqfao4rK#j?_KwOL^Ix$(QZY4ql9XOrFg z#nBdD7h(3gs5jyOZiWAtz%MiMO#K@)4i38RFzjI}6z(CvpNMS$r z9OO_%r*NpkE1l#GwH>w9Wkp%uuhtF4p}_i$aL9_xoFamhH96vfb3Utyqddaij9Btf z9Qy7fWI_YF9XFpY1J zt-JT9uMkzBsE*D&7n!wR+~B7bJ4gn&sJ~#0G-4Bh;a#~0C&bXuUyDX0pKNEt}81DVegw6R+8P0ia1A+m zs9m5zNTmz0V}|4~E&i`w#!4k>{wpGGMB#_;p_9%Qg9aYN{5|LAQ+DtCM_&h?ivhy# zoHvJF`cGDuD$9RGawvn`8&7)d&vx9XK1(GvfbBhF)CCUVv+NT0bx>f%AIXnBR{GFEvtt)^hwO1Z{r<~d_T4nA}7P^`5 zO$JVVjn7Q8qq>R5^E{QnlnDBS)u89e6)!{VqaHAunY_j^>sT)Dx_(3|!d2>$LYn|7 zhhhe!`X-+l3Es}`_KG)UDd%tf=zW*{M4wwdP4MuDi7j>%Rtt9$Jj5pO_G+tz-)KV9 zY5||Q)F`j~Ez$2ae3RH{ZQ$}=V_5qPzjIO>sh=5Q4&WZvdtWyAkn#l;%gJl+FD8n9 zp`KI*xBPg_H<7mj1P#ZEF(;qR5Z(McX#Cj!-&Qx9qoSU8K0cuPw7O;TMw81W*5&Q{6$?kENK0 zuI805*`DfJXq#!A_9pu@l=)>6$C(aK*Y028X4Y-2bU;d$<9_u4|1;!TPsvsY459up zt;!f%TLnlnW3#7jMg^#RcsQ-~S$}jopEsu)wZR$xbOv2g2F+Holm_Yb%`p5V3ITx6 zJo8=;7wN-)KQi#J;`#4G^)`aJNFyK0J>ij;E7 zJ*Dt4swH+&w+Tom@GUXn$C~!nEEZoqaoa=x%_9k&j=kDTF;JVq-*qbKk|L4~NVXs` z5~#WA?`g-I=e7o9Lv}Nmq;}pLp5=A+#XGVP<@~qhV*3`3x0ME=G(;SU&|04p!uSTu zH-#?))Ro*T#&->QuY;d{Y)Ms9Nr%8bq8ldxpNJ2acaIjnKX86iL{Fpg|1nm^KN6@X z|4~iT5wfqR_#RVc4*Yd^rKa46S#*Dm_hhGbHe?7uT7jcsagi`yThZ-i~Xv?Hxt79py z8WzaKQDV-X6Udqb;osg!=&>yTT)YmLm1yOvnWH!Nj=WhaG`k(v1$zmJA8U?(yT94t zvgB~XDdMJo?(3(y_r_&!Szas{ivZ=lRF?lF{k7Gh-?lZt0OxknC59jF%)Dz&)Kv%1 z)i(W7*{*}MlLkArw=6PpejGk-f0JYNr3i5c~AQ(lS(w-_TPD*b?m;2)Af*c;LDkL@%!OEp-fO)>@Tl? zD$H)=ThHS?KfS*?vj_2kvC8L<7cy0T_}y~o?~ox+!U7!UH1mE|zWGc#qH{}MO`%a% zMIr%|%r=@@&qtK+Z<2M*QrgQZ7PtQfd7!+wlOPX^Wv-MAop91MSNR=r^#ZH`q^v+0 zEDwE=X?i;t3-ZU0P8< z43Y$1^lwdNZL5Ncxdl;_T{2PW3+f(tn@^ni4Sht1MMpYIiI^WSgLv();i)!Md{`ew zIo&)gCmT8$!{ThZ9>=a+?8vV~0+Yz}>$zHm<7DXtn0saM)rLlkQ@_3*-y9qbk$=y1 zs;NmVIn?H4e2WcP4Ag-C$g};Y+vrPhD@I>0dB4Q1+1cymDc$ETN^?zV(7fKI(x2ff zpNNC6DuG#!wg`t&98i+YE^WBG?)j3ctX!v=$NX3Ees<*IU2Q#r0(F^VBJVnwe|lE+ zSG)!Cb<0pwb))>McEPgy||NIK)yHx%U|9()|~!bZ2yTna)Ad$0tSvFP?xz0j389FI2ASy%=d8qr$)#p|^M{b!-M@0g6D7x&N zf!ZYvc%9yNViY*pUBjrHPzRR?!ZKpr*5-uoMVPLn3hPg=c|^kK_#+)VlKS!I6a7U> zO9bN{)0t^=!Hx|_&H6wW`XrKe7pJMr z?z`EPzWtG@TPGX7O~WD7cIGD@vQNIlG`5zyA zK);)`N#m$$ckp!Bor^i;CnmJDq}TXP-Y&DLE|*_EWJR76H9kL)RDluw^1=ANv}elL z6FM3;@UtS#a8~A?G#{k}Y}ZIb1kHhxe&B*Li)Klw>zqsKO$WY{mps#M<;9PtSWdVeGo!NN)R{cmk@q~)8U zEeM^rm!U8genKe*ORbQs#iZ_Ab5eUnMY(Z^2mg6i7wM<(d~bq|YFc_?|B;gtnqCQ? z&^WHz2IuqFBcJ3)&UGdEN=;~LtVa`U;4INu^6yoH{^G%gH`c0J;^jwD#6v$#J);Q* zHmZbJAx@}Lh*w|+_cuY`5#EGE1!&DHJ4xxM66l&c*}F3y*c@h(`>@vb0fSG1I`y=74;tLQ@1iPaXcx9gTy?UnDeuB7)SKhPIf06QpVQTv`_8TgvT@OH1fP-n z`2*`j$|-G*4@BeMCE+5Yzfz3{9Zc{Ri&AY1NSMTD^BM?2KmVMOjk{w%nEGyar}JYy zlqM59x>ePi?DXR4!KgyxIcrtZMt~f#p7abL%~X^qlqy-tn^CH=#ejjOgR}jWrY;_5IFV2!L5>OOH9` zC&#Y6Ti6XSjO*@)CK`ucD(M;W;iHnT`KtYs+~Eyw!;6DPBWvi5mtDZ&o#Di?QaFzoRgemGLes8iQqB4J!>O+2u>RM0UyEAw znd^nS?%c}1t9t}yHs4r-7BJ&s->+Qw4ckEvjdg0RNjW=8FW+;EVRLNt+~tRi4`5Qzd_?@4Pp*mb7}5{Q|jT(uXstFr_*?#%^FIuzwyQE zG?!bjUxzw>2`V14uvkl9{3ZV4T8^&egLAX6_IEfwy2fYqUu471PuI5L4!?KGSXGIc z*c0_=N9?tbg#wr~a$*aEBA?1EtvH~2yycOESXs(43-F&4Zio13lk zs?~4b$-fW?+dGdKatvgGB#sTguReI9;oR2n3=;`A3z!4!i7#`H?HlTzR_ab>S=DwPu?hH5aw^t(Y>C0m~`;}h9yt*E$Po>JR-8nFy z2h!1E>FDaeci}E@NNPzb9I4dh8PjAh`VWH7GP&Vs+3FxH?M^L?M>Mhn_cWq{Xj;4) z{Gu)TS(4pk^XlWmF96u|zKJUx;__zDEb8}o)_hmup6{hT;~GGVc{hOQdNQKs&->ea z%br<3Pqih+86#MZThHIGrhoiMw?OJ5|BqUsF7c zAu-P9gvdSr@r{%79s}P7hVN0ynlnBp+1$lVUE-KX>wR14T$U|QB3&pte+@A7My;Dq zCRu(R|Cn{V$u5N*YKmMi>Dxa?t(-qNz2&qx|zHUO&o}7&u|*a)D`EQ_RTZE1SU6NQ^;SB zo9wM)))fUq5SH-4bSguXZdn>wA?hPk_!T^SYd3N6Z=@2UZ?0UA3)Hkltg!~oUos}N zFR+D$HCKL>xls@ya$>Vrz>H3jqfaHLMVNVV<~6%0nx> z&%0vH!n__990DY@vV3w=!6)vO5@WBe*&;0AhodY3)ojU@5##s+RBa}`q1q(Q-8^}1 z-TkTW&cd3$o)V7XD4gyL?><^LgYvTvhESIAm$)6IV?$E$*0?h0BqMQvr=ByEP>`#K zeU^R|bpt~tsbI2OrU$AXHoftd6N_l41GQ2Ecnw9%Rr#|8@$22tkW`Vd;NY(a$CynS zvx1182dgt!^Ls^dZHM{jaxhb!t2E}h&?#oG&g6v!SyQ)Usp5!DeUB4Crk9Xv#ach~PC|dIr7EivE)Q~GTMzY}le3!U z1UQSQOQiY7}t^62!~(Bwcdxwn&GMF_D!hN(-`UGXtG?Myb_MWEN1KE;JsiOo=6U=e@PG7~r5VQT96s<=GD55l0y9oa;SY1a_51~amQ z<_kSUqMt>voEWabc$k!)FtqqAt3RtJM;l(ChcM4CGuz1{IGVsL@{{*bzpSXYmRWZ& z?<6Y0Dv24LQ(SCq;(G7!?b;Xb+#y-iu|0~R_ojjV?E4i1c{O9L(IkET9BV93KxIJ* z%Cvj0FzU=@E=a3i$!Ig3pT18;_`M!O&KGt(31db7(tt_a{=x9F2fD3Q@pa_zy0eV6 zM{x0QCLWLJW@kUk$Pa+8doYv)Y`|{Ju=7)-C$|8IqP?>;G$DD!W!VMgO=ifbEs+UN2z9gt*)*g-w##J9RIKSY zPR|w;Ceg`Lj%yhojl~EslH-c3YifKJmyZ22S%-PpxV5v(K`K}_)(VZanf{6Bxo;4T zVH&}<@|V9RQK=RoMRO?oNRgF??M033K0c$rD059s6)fv<8(ZW(4s0z^J?ER2+2S)* z0V5&jQ@UMStEv87=_C5x+byC_L>a8zG#bGRUc_Ja2{oS`)d(|IUh02bBv5i%12Wkw zp#x_^f_JX&k!rivLGjgn_>v=wuv5E=(Yuys`c(g?iA((gCRDediSiR!K!SwvTJ>hC zxabhNWgzXcZbq^Ck~};xcx-HECPDEGH#mIv;cOb?Uv*FDksfH~E+rn6J(g+=vkbrl z5j%U5d5Qp-v`~}_rH+Mc;jV2xKcH7!*BYrl3dFPe;|)9XVEEaBQ9Fmun_%dpCwe2MvG5^WP;fp3UU!crd zjn^PD+!tRy;+Qi{>UPv;#*!XXxG}Qp;cu_IBh{g8Fajx z(a!^V<4^+w_YGkILB>Yj+d{n2`w^2}Kpq5-1EhvySBsP7$N}l2>#X!MSy3P61pA2uXApC4VXim)NbKwkAn7BM>wUJ|T9Ip9R%nE>T*P0o4Y$8l#%e>Kw zz!C?z3xfO5#ecfag~ppu++N+3rVE)70Q>P7e6i9^G5d!pI90-;7Niz=wHSZuwi#SB zpepmOT-`e|B;zo3}P)TmMY4gs?c0Gq$6J=G|Hejvm`kZq}XA>iP})o zcW_ohbuw-S@cDCP+I144^fLSFeRrgK{?=>{b&tGaldl$91BtqF+JAH}J0O?6!V2vS zRvr5f8uiX6RLTWVw^3O%2F2G|+8XKfF2&ZS>+!O@1GaC{Q15{V*7t7jwPu!T8K(#iA><6=`#w{Sc;u;hp*!c3pP-L&6 zJ!18dLEx>rKM3!2lai;g667fMKi(D(_lu(D*|Tt6V1DJ4BjPNp%*B5LBh{10+k#$v@jP&%l#5oArH zlnWzaS$u{e&2gepK=%dHnToZ##a#4^2~7mjFxp#MgXr7o8BTUd_Vnek5EXsA7nQ;c z*(BQinN&OU;Ee|-2K*mi#t(h{joW}PN^xsz8C-SEQ627MP{|orB6bh?94dm0fx3lR z!L?riA`-te=@4USDZDVF%@y^^om{Z_CMi>QM~PX@%G)wX7YbKn9!D$lxda0WWx2d? zHgZ<9x_X$CeA=gJ1L9de#eVOqUurb|Ktnq0s*)I09Vv9@G zs+$!8n|95~`!a%Lp|PD0h^ErxZfK7d)g>OWOqJ6G^6KLik0=*ZK_JT%Y;#>P7MyVX z-b`&NJx5D{jFZ&E7o-zMwW4e=WJllML)npB+*#G!aFdXqiDi)H1@y}<3svqFgTcQL zT7-BVJ!NUL>up#-Y$7kayp+%6axBU5{iQ8{ei3+i&Rki40rqe6sZ)_F%eZK10zPtS%=_`B# zS`K`PHmniN)?(tkK-38?x9!f(>t%a=5nKms+QPQY90M(D){uVPfktp|F#tLuG6ll@< zCM%<=3Sbwc7bxEzG#GmsjWY^zAZBRib$Ej_fI3e*0P)v@Sp1k!`RCTL*2&b4is`-@ zpqD}fPPe0ZmiTqDHAX;RxP(D2SS6y^6xTa?^1#K{9SxwT$HUK+LmZuECk#a5`6j+A z9W(OGDk!0Y$M#YfwcC6M1*CQ!xt(!LB$??RYNco4#SFl>rx&}#u>H}nZucN$KcocK zk*s1r$W6+yOH|b&Yyz&n&jb1dC7>KEf|kN@AqxMaMK~fU8z+wr$RD!jn zC3En~0W-8-VHP8aigs$-CKYBOR=bk&W;|@+*T^no(bmcH9kOapns0+${oL!ghgTW} z3)3HV-2N$5*p%At1IT=SW&yW5Vz{d2<)!E;#=Thw)pj0U@R_Q7qZGENWX*4InzY}9e-<(ND>8F` zL|=%DM1a@45usB6p*8suacO8Q*BH$!7V&#>|B4N+DyE{>T@9v#gJ|@i29`2}2^rd5 zZCyST=c;!YopFak9-Ojr{2W|4OrvEL&aq@%XH4c`LWvN>2t9nl21l<*WO?LYhoVdv z8rL_F2i<-fhf6ijIj;6{%y$ld3}Quvb5+sh$=$N9*1=&qRBlspr*B{+n1-502g_&` znfF57zxW=-i&+r)E?a=<3BbIVc`Ya^VZ;poQvnf204J_bnJ*z>=wQiy%}ov`wZSvZ zSBO2-Xk-b5g3tZbJ)!^D%2v!4)~@sQ-zB}=SHSdVvJJAH-{NAoa^Pvhnd|^8ja?+| zmBn~in`nX$USC(&c|`q-7m+mzU+-nokKjW+r#5xT>XbTUU9cLZV&wsD;nMQ5Q8AVcqZ%RyqAvW}+W)IuSv`ZBvhcTy1Q*d2E< zQ`=d;0B?Q|7z?!Fce(A^YjLiSJC!1(V__P>@9R#$jh_fRz8wTUleP^XXjll+(lu#aGpDVtMRe%B^em0sV{|q_*3_93Iy}Rr)Kd zo0)`{=$~pp@4G&hxGrk?*P{`G6xI-k3j1y&I(g~^^^j8d&9RJ}fRXIz`6#XwQ+~)u z&>)(&k@FZ!t}ndSIzZin=rCN|rUYsuw>xq_Dcc!@Du<$-{Xif2IkOT3LxJk{bCF!s zZRY0a@}(i%FAb_(CyObkAA@Pb_yN$3w{vKEaP|5$Nf7}zO$0xrWdLBJbyxx62o8kl z!K7T^z%(~Uv|$KUs6a5MUSFt<7SO}24F6ZFZPTZv7=OPkw;KF^!{; z+lv?x!22eZ_shFPl#2sIOETufV1b-z$yrKp$H^X^C9<;d3FfDbd}MAj7F3i2#5d;Q zJ!~_+2muPDsx9x{#@W7AD^u4S?47+C{O3eG9?eEzt{##RzN)Y#G(kMRuWj-XWV>QC6|6NjwrRtdp_+s_U>Bl2`)%59nE zn8dl_abS$B*?au5df>l6akP+jdQju<;0*DC4Yrqbzq6 zYo*h?8^HI4h5Ug$wXjl#6Ddeml7gnMQ3$(Ti0KI#k6EX< zjvF`{k(sHIr`nq!lJtnpvQUx^S+sD#JP1*Kc{nb+rL7b#eIy*EX49gnELM~Cu&cl} zZMXdicl_KXtA@*BX;}@R;Pl9Hsue_tbEhu(%8tIWws(g0IamW3t`v)8*(IPESJxTGEr zr29sSw{k#K(jXN@cZJ{a*C@5}Ze9ne-t8eFSyxh8(pc0>yOTtbhk_c3}4bT0YKg+)9Q&*2{Q5#B`F~aOAboeV+@06;HN9~*D zEANqMP6hHxXAf2Iu$S-K{s&qAIVa0ei;kZ5y7dy1C{aG}+ka4cXvo{Bb~(wTxz6{O zo_rAdTK*hlVTKJohnr^bW&>wV)+w|_lzy|YrqJvO6hJ|le{ z$vFM~T-&1Ip2SA$U4KM}ncQfmEPu_i3*o5Dvx(mSUfNf=6LfFh1Pfrc)BN;5-FJCv z&=_}`5Chpi~l!o`Zb$TM!da+FV*vD(#&K}L-F%k_Wn zwcXu66uoOgyl=5dqI>p0$kv&IR>vEFOjRWh!`tIWGVbbwm&e6W588YUckX;{WsH3$sp>_h4qfZ=h{|X+zQ!su`2KtP0r>19zkGt+X}5DPa#;g~@C9M*4woC%0;tQs8YX#Bt|OJ8q7oscw0L zMRcP_E9b4gj0Z{}R{1?s-i>3k*0gcol}(L!$iDqWsP*FDKCSF}fkuFO;kZTpufKbR zZjPEIJrYfE-}clWI`!D!?8pgRbGP~z_2GkP{Xe*Dw#bpB)qgFEHfXIPg+c>Lad2@^9=vJ`aL2{$*@gqjO$2h6NW6_ zk%w+K;|1#;wZ{WK`aYJGMa*q1KNdyQPPP&gT?$W}?lDyAZcl}f*_mJdr@w;^7$vo_ zpoyqM#DlrQ+~RG!$V^NfLcx?gkU4fL#pi+VM1edwO5I~UkM2kcw^>&j$=Sv|rIk}x z10!(=uM%_zZa*=|g;yisXf8aXY(GaOz^y*k7tojvx;uZ!uiQ(aambsqPcCWx%|AD> z`6cws?S7;lA+gM{?^d$(Qu_d_2#yvF;yyq6Bh5z1T9aW)9%M~Aed&~ORR$CY@Cc^j zDXvx*H*;=f-J3HH)miVP$R(j5~rF&f0#R zEKoU=;3XL4qo?gZetId>Vj3kCW;qrZIX(Eq09`^w1VU^6DwS*vsShmQ)h<_)8Ti0 z<5_3#=eVA?&hyJ@=Q$E|BgS&J4aF#|?ccbYmwltZ4JnCKXMe4@;$j=Jdv>=eO-7D0 z6#d($y!MD=A-9rU3_=?ASJHQ2DVxCbFo1hX(mC=p8NH)|_mvWVRe+YhQDKZhuHWA{ zwQNTez3M=QEE);;7q22WR*B?lPsxSv@t#%M`fU-M9>nDN!fA8lTf~i>8lvTJr>}J= zk=OP4(d}vp3pln|rEjYz5SN^Q;>qg9BxN{ThSvNQhjZG=GvAiTO;?ih0PeU=55B}o z?fEdCp1pj?mz;z;@RFE3@w_4;`8h*>knpH_er@EpLl zGtXbXB?zybf4y~m#%0w-_|@D{@w0^?N7CE>%RwISQpuAfM&?mi4A*G z?S!T1K^_ru_2mI-a4Nf$ZaAey-ZLXxGIG_GCOhGD+1bG|2MoQ9#D&*X z0>INH=O>NYU5IKc(*X6Q(EeM$2jH&j7YKnn>DA|nPkBELg$U>V7G!e{nZ~=)ck}m; zwEmJv4k$&V2jTr5cz)Zp$Mw6Q0)unI-y< zMVbjlX&=s7S$RxXx83M7eUNY_T4Tf0)OfAS3KFOT1fyJ{6`J zBK~|ay>_m+?S~T4uISLf`B-PdD-POJR|oqjv}>rIr-66JHlMrwoY${?5jpjc?jG`8 zuDY5dz3b^uSHuV>_UyeqDzm>K&(&*hl2oyqZx4Pm|5$wb%&MyEOF~$@PViV>;4>u; z44ne^eCYoEukQ&CB{Wx=Sp(gd25HfE&2Kj@B<86Ul7+S!8nKs(=DybZKQ|JD8a)%# zT(fWw-KS2@Qu5q*lP>@kWVGk0XEG%Jw>RLcVF$ll*j{N2>%-6X)Q27#`Mf=HzTxhq zCz)XW_tOz;FC+6gHK#eon6p&Eq~_v&O$8GGWU11=FxdG15#RxskL3Q5Qx^qY2Pogg zo|@mArj-M}xugu3ik~1q+@i;xPw-mgXDl3STeGXiHg-{zC_!uPr$6&|4=Kg)5RAmu z^aA^tOAo%uNv&UBTJM(mazG{{kBf_B3bDYA>e$fLbbM#ZJHT&|d#s!mcyk5tNyLxv z12o#i$`3>>F89&_M!D=A=f^$p#-JGnQT^ZS%CD%=;~yIbTiCq5=dLgEIS(k*(bR)K zZ!b3*oy5Ay^c95@jjc)E|*1mM(WH z%mcb9g6B>^UUEeduKT-3ynY|mjuG))_fnST<=57a%=FLx{Y~0cfxGbMwyI=3=k>PYNJ!GZPT4^)Y^lB%A(Nxq22{)3P*bwk@K4jj z0Z{;io!o$KTc-$cxlvgsRi^8aY^nLAjyNL(CNUZdGL;RDbx+;;dNnPF+S4K1B?My- z=9Wjvn@c{wA`P`Vewd&3`42j88(-WSdiwlN%cPI+5M#o#EtP+K&JA+QEdz4X?%q@E z_DhY`swPWxj_YLS=%2H;&F8 zzo(g{5T?)XYdHJkN%gO%a5Y)K(T@3#%-Faoep8Z7m`SWqiRgIfYcywboTxZx41)b&u2!~w&Uz!Q#e(#< z=7u}_hYuK^9|W*6usyjP(n<>mxHQ~Q=xn%l`uqm>x=u9Oje+`mY4g$^oy&K#+xWw0 z13op7I@iXw9#+YFcPE>C*1YY$1Cw4{QpYL^8d4MF9N+X%Ue_4 z6;*fYL2%Hf|2%E*bM0=&Q`h}MHrfMEM~5;4YHC#qep9~rbKh|^oY>J6bM(;lbMmJN zw@3=Z@FEGG3rW8Q!v2ZgMk$CD@w-niWweKT;bp9eM`lbSMqZU(io74_B>nMmllN)ZxmUuh z? zhEGzdZ${3IMtGxWr0y6>2Rc7qm#N}}z&XuJ4w3@T)5|Q7HUttvgRb5$E^oWw9Ij`Q zisvK_|9}L262&qKQ-A=$Hrmi$>Oy}&R@?V@Apf~tG!_&UgPmVj@QliRMs4P;O}iMs zi<2^V0|xZpo==4=Zv~#12xA$y<1rg_+@!bK*D~aQ54H7z#mL#<6-H{rG3?+IDS^Fmhv(Ehb99vL}y}|1;ubaBQPCZ$iD&_p7QDszsDKWXQle3wIRAu zo%cIl_3jQ!uE6Q7-+yrW;opPE-*@%~U?_r7f^OdEQ(sIddqP++d{sv3ukg-1uNz%) zzBk@HOg#AaS?#&5U6<9ORaJSb(81>6ADl2Ng-J`HG2!h&;e~r1bR;?0)72E*V{cqw-~n#M^~vKq!D*9%zn8@O9nPosYI{ETJH;PA zwhb>RyCV1gQtJM3M;o{7U7-T{c<4XWFKcKe@#L4!%qB-tYQZqEDAE z512I^dHPZ5UA(M&?|l{j^ciu;O~ocM4-;LTed-_I^rJ@PjV=X2O@pvMG3ycQoUM+| zFWTOoQUBa-)}Q@JRQT@uJiX^|Tk#)^9!sINNzkAuo#R@o5)zpgwR1?HbY^Rs^lmQ* z&|U>>?k~Vt{5a;9ZX;Qc3N`8R-f!=Po2eJ$--7`~T$G6BR)6mAGYcNQcLgGPJj9WM zr$3;se%)~DnE6M!-9Ir6BV`)!`PMy8g`w9s)lI_jK=NPps{TUsN%~U(LEr6nXyZL* zTbQn)#n~V-waK#JA$yrMX7*=O%5_YXdSRKRbbfYhTbFgw+2=ta1oki{c+du(kwXcR zXz$TI;)4P9=P`<>&v>Eyj}gt+4yJZgr|U3m?gWp~RrvUUXJ2hkug{+z z`4Afv{BXmGWP+RQdGq0)dIzo6&!d4o)AN>jw8y}Mx)#+5K@m^H2Eihk%;Ny)bL5k_@Mqt?@-I~glL zsu#T}6TL{kUsm}R=*}pXk|X(4?Me}%oCM@Yh}xQvxkTQ0lgm#ayP)Y`n@XQ2ZXIYY zVRN^1R%t)Gh(~m7g4^ybYJK?q+I0Rc_-1UEHOpyn)(bV9+h+D=NIYKWeQ(~|>}n@% zfnmMDWr-w@x-wNj|23l}~6pkYmd&6Y3`JL*0^=)e<$_t@ZB^bL3;h>IACu`K8qWlvxmBzXz$y z7$?YhSF&1PY_9oZUTf&M!42*fC3IkPr5&w2t4KF zD*DAxm5>#T^XYmO)4Tt5Sr=LbceImA0NJgcy1q9@9*^hfWf(xskbpSh>1crQIxtpR zq^jD*pW2G4K2fnu{PMAsEFm#0>o^Wox8I}Ie9r;NV8fpA@|5bmYsup|8BQWD>&n=h zUrz4-@E`Q2|ML@#f4^=Vlew-*#}2q45;!y?YTqPZ5sy?eFm z%}xX0Nwy6_%sa{jgS%wsf6#XCdmAULtXOc`qV+EjuqLZnWK3#_2yEp#j ze^B6!=c7)mT3DyASnHOjoi$TCvD0V)5#^ zd%a*yfZyRVGoe(F1KT#h&ES+AuHQK*Iq16QUJ^z8QybRapYa4gPgRt=*TMK-`f*j^ z^K&&P2B_F>0q(4${6IouQKZJANL);A3}S(C%5RVBc6m4=&~5_{4@7h)pSpIt>=oVD z^=`{|gG*93Z_>rWU+U+3o(<`#In7^R`ruPIc_@Z09C>!W)<{?YxV#V^jcu=lfM#ja z1JX2q{%f1l2nMw0e`$K!WVb2EV0+l2eW`Dl?qzShD8BO^fo8tQZW&c4yttxi7iOEG z>#5EJ^syEi4+!Bn(`n{k#HGTh*{HM6;nz1OEK%+$#ZFSH@_ z#%ppCKi-8Ul@O!9QM{G8~v=9KS zJm2Ti+N&Tm`h!)YS*FzVWTRlNY=Z??FkJuat6^#bygOG;nua}M%4*`yR{LOl?~v&? z8jnfIE0k^{mO=JmDHh*jR0U-k`~Pr~j%XQMsz|=07iMK0yr5Iy8&I%G17Qb{!=V)Y zlp*SMK+mRD_N_+4KsU8K)1aSt1cj~J)M5YFpS4Dkt z;0po)Qg7y1>czXid7Cb-Zlr?)g%Q)G_T1R==Xq{Y4DX7cac8K2+#vvmnnKt>Y>S|r zSX3liEvMV9jwrJX@X7>Cqp<+Zp2rzkR9~RT6<72cP@x~jE6RJ2fnK;wKMVYNPhjL} z1fBna37Ks3Bvd}CKQc72olz)EhwS0ZXyG?WolEW_OzlN2hC+732;ol|apZxFql(X| zLOLBtCXm13?^gxslRWLy^c8slK~m%qq^ks>zDaiIr?P%j{?gd&x}{xgFsH z6of5z)xFrtR?Qki7TJvIwS(A7AX)?h?hr^Ag#WH+ZBn^LrZeee+Q?&E{_WQcHhppA z{;L0RCBV}tD3El^Mva)e6ioep=yetLfjjogKzPLLhqL;Ul8n#RT_-=J=OH zrz@d&wHzgZdN1@DakzewVy&pNW_Q>7;F&PJ$x0BU5|32KyrjL zI~y~AVsNuEz36Eu#~=o)zZK^?XSLkM1B7M#vdG~_F$d-iQ!nU+{!D@y3mf=T4!&gx ze!QAs_Y_9-5yPP+UfoJ5T2&#eWHxRc45!i8*7{-mYvUr)X=3C;1n6tnMfI3$FZ2c- zB?JP(aR;9&EsQ$(a}*`dIE^{cObhZ#RLTtxhZoIVs9_784tsk zvGHrRtv7~1AR*-{J)?4X)N^Bd#eto~0BwE8{QRJMlm_U@DHjKJ zNllBGOP`L6=9Qb!wx*953`LIN{CcRG&Nc%q;l2v&CmYGgkuc9!mHTB4R9|I-cZWWy$=xBH0x5WGWsb zRxS%~4V$6|ywORR3dXmr)gmTsj>DSZ&|E!~k~U1Rh7T&=``(H$gRIs2*ZEZFuG8$r z%p3nfM&Wn`gcm~yj-^n8LY+ae=))0NtA7@i=)}y@(DV*H5+2*E6kl1a7Aq)h+h&Dd zR)&~IDB1)<8oy8ZrK(04cV-Kd4s&@2dl|E?L=}j7Zoigxb&P2EZjw+B{VP=L*9VXc zR&bXkJyoI)Xnwza2{Wpg42LlM+Cd{387f*;02D83fGrt@=7x@ryG-nmg&_?h*y;}n z2QA6(7PCQidpY(I6@tP|=6?{^-%T}!`TeNYW5o#0&u3Y`yu=#0(WFwNRJZFB5nfp!*uPcHu=MWFr%ej;j#TlUL8?qifq z9ri9#KMz9(Kj~9vR(-IDn;3dI3YD(|Jgfa~4N?10dB*IL&i4*k3riAf3gp_4Mz`ZX zS>JKb1eNSoyiSLazOk!QsDRPSVZYP)j{g9eZEt|Ys_GBo^&O189nWm%#HuQPjgldH zEq9r^7Ut_Bflv^(J-FhRw(kTT`IfQU+)L|>oQ0irYt}w*jr^b;=)@FKb2P`mG?-cN`_M$sM7I_cr9P)VPh#*Qv;BiUpd1KfwRB_#@MQlpl6x{jAHT1 zFFCgFqHsQCc=GK=0kF{^)l%VC77z_rPVVF8qJ_XP(vwGx(%Arxr;`>9ssk`H@xD!< z-W;GnC{wb;`{h>7$LaA~(peeBWdb+>TsZbvjrkrN&lsnXkQdFU!+0}6vdF;<%0 zTp2twJW;7R&N<$gCk=qKA%}`frhi2ANwlSx-mPDs$hc!CuhLk3RXKmm5!`9`sm%jdjr?BFE;gCAUc8AX*v zn1g(X-;2XpMP9jWf;m>i?ZJrLb}d|)2F#;2VSK>J&r$%ZTc`s(k5K6gvEu2rBB80% zSK_)jf8r=$ec)$-#;#c5fKjEWJGuz|jolSyV94NPN?r$G^$?Cacu3uv^+Yoa#qt5x z4wu3QT77+toT2MzV{G%m@J2Jn+v4)EEZ(r$_G!{~U~joT&2vo3#L$gQw^@TCB>VMF zYU%dESEjCX28C+OE|Q&Rw{X#jw`B)N(xDqe+Z|i2EXwafH}VJjou%&jH{vxLpol4l z!FmtuLInWYv#xw zYgFSghV>^0wJ?N&T-$Wk0Cii6hRiTqf-jlmZk&Pd6H6*>U```qJUDF2@Rk@K;PQD*Ju6Ok=wyYeb5wg7^qwcN1M4x=e3yC%a-Q zRc+SJCAaAI>!c$-#s910bxbJNeiUZ2m@ZXbZmqLrbC@K7`TE%ju{hT9-QVU@s!BN!Bl zdz`TXUITQ`OVsKZ9R{Qy*4RXQXV@J`+t_6lgvgzgajqV7v}nUNeg|OD$Ae+b^2Q+2 zIou?|Vkp5rzW2L{z)a9XRcqIHy7^Q5L*}?J)Mm}JV6{vm1S&9`qRMCwGo>ixOr;3$ z$f{8zL;Brh2h$f1xeOE>Evdj6DJKmDz>|oZ?u}YsDE~oOBw0ECqQp_n7sMkug*pS3 z$qb9{)}IRyyrv>mLAfmPpnq0FCtM@UG>np<3{{XY^M#I$$NqXx>>)(1W$9|Eum8t)yf~8=zu5 zzQD6uW(OWn4dR1mQ&>9$crbzr$smV~ss^#_QiY^=@V$7$S!GGpW6Ou$*7 zYPRUs*Juc%5pXdJ_Qk?$b12c!x{n6xUp7Ynr;V_0ZW<_kgOVmHG{S5^=v;}yw#3M7 z2*P(odSTA;cp^{vf#m`ot2aak|0KUvSG8UN8sfjgY?GZ4HuOA5+Fc!09l-}nkvjE^ z05eSkqYw}1Sc-NBBD6sKM6y4wriVUbCMm(Vk~1d35t?>QkpVsk$jUhD!sP=bz7(ZK zmWoX(PND~-hw5{`A-r5A#W!m8li6h(uUDWslL-)FLoikVQm`o&^aVQNXd36bU{r%O zq43?PMvL`}gHI$5Myu#~82rq=`vO}41|7 zG}6CAz)#s3(iRrCx==s|u0~gPseP->n~&SnQ4ZJ7cu+k3LA%v=1pzP6NtlO2fdYUF zcZS1cqEptafK@!YhY3SVONv0;TW?X2MyA3X{(C&N)F1Wny-|0#bugF!ra)?rQn}n> z4CsmGkdB97k$tK86rR*i+ETv2P}P4G?E;->nH3EjAtLG;0Yh9sSvI4QA3(< z5@s*LC5pCP3kZ0n>e$g5@K!;IyT6$Vz=7ouEOm}wgVt>LVd_TJ{6Ch?J)Wt@kN=xt zl2EA0n4(;hOKC2%QJExnQOTt#CAT4$2^&diHrGfd3b2G_rtFxkx387=+DrzU;BAriB}wip)3>VeodTfc zQ3rXp#6#`u{Gg7~6`O=p*6z#AO3xqAMKwaO=5u#c#e25OUZHc z#$H2V8#f$R^0VW_I6Hr`3ZU+|Rs*2iFILuZ_M&XScQihQs~`ZB@s3}RBDC=rQ96y9 zL$qRsnK2!*fCTm+>kC5=HoLr+gTZA9q)k{O!$jHnVXRZTJeMR;)UfORbX+(zZ#?m+ zF}o(tKhD~LIstBJ0iN}{mm7j*b)a8p>wJ_tXGMlYPK~n;-gFHCzh&Q?wK1^>q~pm5 z+%F`j(>{T+ggo3B2}~2u^83i(5(> zFA4A%c2GC05ej2U=4yn1Ri&Ph$zX;lKU)|Fc;=nUg*AAP6QgOAILUEqFY&6uLmzze zG=@e7{1%A;qlbjM@O$>P__Dg(=aCKbE<*Th*e7quN~>pw3nvWX4M z&r*iu=87*%)dYP^X*LKQX#3yLMVLt`D^RRE9m383K$Hqv8GfRaG%%z0ip-aRDypJ6;K(j}?6-_Gpdib8cu#L7VE_fh3eZRca9o-7 zF2NE5x1$H>;|imdklb^1b`Be{`H43`<+c*Z#;oPF(h6ip0F$j6mxwL}A$v4r>t>)H zz@wwj9waF_HB$uO7}&O(LjI=vjl2gp9RoU<=}-_36!)OaD|`~S2;5T(rl9bpw9o3@ z{FlZd(Y_o&DVigxVFkiHQ3L_>XJ~|44bZxAb}9Rgr@T!bA)(Osw!SY5i5gHu(ODqn zv7GYF2P1Y&2|O8uQRJLMLgnXTk_y&~vPPT4jWyPQKQSeY@bqXNND77qO#$IMMe%^t zk5^DQ!T>Re>fjFc6vmw#sFoaj^;;v=mf&PqeVz#NoSJpQ?Y_qXq-L5RTU|Gv;*J#y zon>Uv)wy%1*m`|+=LHo1k;L<)hGM~GSO>mUV?p#emZ7Xgh8vS(pejJtmh$j z&&TF~6%Mf}u!B48J54%yvmXVruAr!J>vuD|hLeErInRemDD^zG7FD7xjP*mpwGNm9 zwI~I83+AKNvzH1_A56u-Ov5H)J>HgleNdOf72fFq?xdW;DEx92GhU3w@BrlX>%m{! zjw?{0Dtv*TrFj)us-N#ox~&nbFT60-^4dO$&W;MVGz{OWS_Ci+!gxQq7WdH^H2HZ`SYJd z*11SJI!VqCr{673YA#p!aEHZl_Hj+ODhc`e?jlozOEsS{c0MI?xi6*rRRY5n-76Op zaOz3gL*-Mj83V5UjD1OchWd4r#YkoaV6M97c;g7;n{2@J2P?t)e;_yK=GueE>nWThxV~4d=!?i-lLv081gCSHADW$U9Qkv>k$- zJkb2k?ltVEOGtaemgEjfOQG99*<}JdD>y5f20N;=jcfNvfFn9M=Bno!bDI(N<_pj6 zn(BG?e5Z@*ai||(iR=plhnK6MZS{Bs4c%!8?80_72w4B!w)}go+Fl6HXjE*?x)Rj; zmZg8eMR@5m?)(;IXds#HEoNhmRLR#x^Hg?4*=wO`5jx|e^gCh+?~E_yV;w1n$kus zD9+T#PMp*QTPeH;x|~(VrknYJsDT;kByJ5vzE)|_KjWt4+OAw(_2TEY~!bsltb?^V070Ki#t}PpEAqs z6O8Bvvz(2K_i_(w$N63u>Q&3j0p3?t{;w-BZ#txh4eF`(_rk#^O^zNWF%EcX)>Y&7;Yq*V;q~6v{Z8!L!U9hZ5$e6WXH;D> z?);sKz-5dm{jNAkPkD7;F}Q@JHJ*n)dRbd&;!?p9)Hxyet?tWo2O@NSBU1!<-fWTA66LKE=$~&`cEbnS?YR& z{jE(q8M<5a*H1w{VQVMev@v&U3-ry}e=OHoi79XT;L5c6-}eq9sT)pzq%%WaW5qnZ zWCIc9)xIwOft(9zCO8~rOjqmmPN6-TW(NgktETax11W{rWx1tvvqAtE)t)A}$0}SQ z#KNk3|4PlT#-QqceGMJ;0kT157Q>+KbQ?zR4Spe^qB3an<}f|zzbBp{0_ zRYWup^wFv*<^Q7ddl8?NT|YlrtTud1RZ-m4slwlK%>!t#f6dh@d7Y4CUQn_hy6)Ztxx*@nqhRj+g0S+=JQn)+IrP9#rw)cr@hpvy+Bi| zi(RhK*f{ndNV#*MR299k*t_BSlJ5(;don%j^t-@AsZTcLrw0(69=LSBG(kTsdO zzX7A6_j^5zV{=?T#0&PB`a7;uMK@+nx0f9+4>k$WVn4{W1gZG(cwsMB6QboS!0AKkVpD|#J1OMnvZ za-jp`%ZEMfbSR|1W*B)^PsllEGB`vRt;s#(vT*^#6i!lQ1_Uycvaa>*)foLf_K^Y| zcvkq%EpVjMU&sW0aq6vBTDuoRnUWLn@BOX3>sKkyIzLkO8^Wfy4HD+!wtlv{U-<}R z;cQpNNO>-cgoIM*00eyiITFe(8`j zj)~rKd6jnJOat?ZNYk{GgjPq$io9WUB{{%*?>^^?=} z`g^e}f#Q=(S*9#BQLd}EqTltw{)RLKgb7I362nJUEdoBN)B|{d3T=eDaS?y^!9SVQ z;-kMxOj#VZyr!$(-YU#K-JjDZr7z0KF3E7qPH)<;YJYvgGN zSp}T?od}?_^0Kl;WfU6H#*s>SLzP{@X)>zBT1O-b0QMc0|M5lq;oZhPbmK4(MUeS; zR#@fszAwGisL*LmjX;mPt(Z|PiiYSZe^fr8p6JH<*B+P)FqK|OJY|aIK)TXcZ?>4w(lgE$Oe`HfkzlOD&CH#7>dCst1X>inFu-r5m)Vsoebn6gYuZs>$ zaPqW@7r#8JiY|Fjd)N$X|A{xtZ>o;{J7h7`WFtbyp6>OVYd(3h{?)6A4poPVWTkfy zdB`X@FY>d^Bg;F<+J-lj$ufn(M#u84d)g)CvRVUm$Eph6eEKC*U{T_uQ?Lk9E2y@W zIk95g8AUZ(o9%s9{NUu{EspiWUd><{I0v^oxk9z=<`b_T{VS>gNNh2Q1>bRH7&8|&+6Cw_%FK+3m zxmbWEy(q?bYJXJ}4(Wx3(M^DTFv#_${0p~UMJq*g@8vTOKPH;4^o6bSBVR>sJT&vN z1$C`1I7BUW-5bemNx~TW^a(NEOK9%-v<1>FI>9iZgipMgHjW;Ue=uWi4w!>WPOC0H z5ZFg#04^E8v)$qSMTGI?u>(Cy5oH|fVsca=s8nqCXG~Y{Yq38nh|?4!2(^6evul*E zR-GhYuZyOwYkY@3{*ib>HV}Q>g&m~WR59_St4Z7G8d>q(gcS;9RQd4G^13gZlm8y- z@2KU?a!-Q5l*T@Tj5kd`Y+j|f&;oN)+*>2}4VjwUrEkg^0s;cH#i~>1w+kHNTXl=- zl=3h4WKKDS@;M(gztAHEu|L3PqF$0;r@Z_cnr{=vt7xvUC}fh_RsR;JIYo5`9>OrW z^q9&>ix-Mdd&edzs4C24Yxzo`M=CO$Hb!)A5KSp_We@!6my$cywtwdd$d7U;r8u4uj)%$ zMk?=q2(P0rM=3;(Mw;a|y>k9Om#>ZR>hutuf)3O&8nAHJV=Uya^U+YK$m!!<%Ov3J>fGjp(hF?`E+Ko-2etmytT;l%qN%gW9&Y+{UKvjKf_f8a^QrSH+`!Phrwq@J38(i9w0ljht3Qqg9U+j0 zo>Bf_DPCX`D}*C~k{ims{LJBL(523(!|&}WjO`+oe7lbgqK|Is7)GTKKio$`Y9LCP z;774@%V$)MJW?cs)>h5p({^9>u>1<$^FgamaMHA4$#R3#SP+!i=z(3Se65|K!O|-W zM(gBO>_PnZBc>|*H_7ut0rfea$0Q3}TKq8CMWRsOZ!^UJyLd=)H9?%D<2rTqd9c;R zPDIC*#n!v!Y5Q%|eYHndX8XvJFB;N{d(ua|R;dt<~D zT-!!eN~YiFP|E(n3=k-{w?N4X!gm61$Xn@ zhC4UdO4+RbX9u9yQtiGF_1Qt3fvvx#Kn#E{LQl0El7|G)+vK3DjDM3#MKCA@z!Vg- zg0+o#?9>?a$Ly}0ve0<3E$XzU$3^YEnWoIUfNEZ<AwkQ-s1||S=7a<%dXuv%>CDuSp~lZ(awbQD2g2fPzFZ? z8ZX)PcbSB9M;Tswrj2?B6irDo8nU>8J)?`k#<3^@xcCqWj{-|fUTYk&stbo(8b zveXLsT8C_IyMK87couT3&i?-w1Rx>TH?P{zatCu!=J&(0F+!>Aev&lo3 z1bp@m657}8RvEzl2VG*A0{!Qip2mSAf1{p=7wjv>MRDE|l+3bp~(T zZUSwzHg4-;YwnB2FQIqeo&FA8kHKF(BOO(;Zx~fI>{#F(6Gg|!WlmiyQpj!?_6bjP z#Q&2XH}V*X4wL6xMOCN8_jebhl8PQszybuuYJuzO-MIVp**$F$su{h7!oZ~`XNtcM z2!m=&K>*Y@Ufia{8+_LNLMev*DP}_Zu16f>Y8i?3yvp;39=4O z;16GS3C)Q+bn%K$U;?!zKLp=}PBcGrC44?gZ$;7tJb`*c8gf3n9-j@i#g7jxaW0Bm z?6|&2oQYg3PX>3FLr4@N!O>q-LnKM7v2}db3Hu?v8R$jdJBt-AN>{^Eqr+Bf&M%@n zUO9a}g@1XzLI0dBsE6Q720;r>9y|t+c|*bvUjJ2e_=0GVzock(k?y zE6irX-E$Qig>n75;+F&WG=6s@)d!n^^F6J3`NENq^NRu1F8j~_Gm5g+PbxhyBnf5B zUTu|sz%v!J^}N&kYkX#S?`el?_3`RnE>?d*BIcw%3TSIUSM-1|Yp|x?_6yl}QBFzg z+4>1pFmby$g0E?)R;|G&<@-BJxJiJ2uoerT<)bLgL&V@QKMxaLu_+}JEKlRB%THf` zQhrDp^Een8iT%5IHJ*!ydLB{F0jnL0ldLa4FSkU~JeQ#=f@f`ld$<3m@ns_R7tyPa z7>)eXWZvnHN2ke6b&qXyaq^00w_IQGFWcWaR#f(k61VUeG2vm>cA|+DINA^mlz1z0 z4##8`n7#|RG)h)cpsF&Ltu#bOXI(!d3xu(cwOJ3W$_R<5&{+d<%yYKwi3AVdW?59iINjYpszUsHh zitb8%>cZXx($!h!=KrLgd4v>scB9dQX!WY>xY<3l9h3 z_h-!8KLUcUysZ91$H3Qz%YTn`PB{Y~|7_|EDrqgu{Ad+R)&K6VWVh&}wo&Xh>uLVS zYp#&nhH*PCy@GGrWuN}&Q4!1k0QD>h%-C+xdNHKZZQ!Go1&=r4=0P_uO0jPC`7z%K zr(-X)fL1Gt0)e!N)rxXf4jiCjc%K(N{TM}wDu#A@zSX5ydGT3uUpMBgl);;OH(gVJ zJj0Fdb~}sLRZ@1TYc;ob3YT@>ers{ubw#b>qL<#5Yw}$Kle^c;YS}vHP_1DmaUNQ& z`HPpjoHmji7Q0VFsr46o4|7O}v9Cn&ol~ujOE10Rg(PF&p}X7kTa|>Ve{WRFdV7Sx z;yxU;n*t(vN(b`CKDh@fIW9JPjo~q&&u(g- zyX%8!ZnITy-!6g$KIL%TMGNdeq)vukN*#p|uBjmyVyxTQqzx{X$!!9w-K`LX6JXEa z^(}&v!aPfM(L@KWX<;NB2GAR=`$X@U@}@OSDPvIU)Mew?tCe!>GPnR^FU(;$Bv8=3 z{dw4RLU@^)$E^_kBKSJ6BnE9hphxz~0#1c`>tebro1B*KM@<_+PTz!h^zKHeQSAuP zT1r?`r&o0cPn}LRnhWLH__Nh=fOsSz{PV{Wg|XE3ND!- z3nV0n=f%-8HY}xNi!!EB>dGKvsS?ncjugf#$1HOg9PZ_kWHJJW z^79#2m=j$S%RHrs(mWizO9fUS+ym-0@6R}5sWB=9py+CiMy7#qcRG@>DR7Q3oy3uy zntJ`Coxn!3YI4}5#cc8k>RKhHlBi^KRyzlcC`&ahsuB4a?d>%0z<9*i`-kqNH`cT@Hp z{pW0Ui6$IY&}Y?W`JgOq;WH9)$o`YBsoV^*oF44Hy1EtqSqm3ZwKvtE7nD~7ctZzd?~rNY+WIPTaE{4(CWAcN`kEY5qFEqC%xhhS<}>2rCM@$Ywe{0sy?Iy zh6e!Zb({=PrGNmk4t+AD=$J7F($-*dvD9neggpIh-FuT45x>W0fKlgM$}POrso zz?nXfSq^58Nrc><|3KO_apV1fc1TQW<$j+lmd(eQ@jZV zZxlVh6#p;9)mPaBnJ(EsjzJZHE^g%(G^D1jsdo}pbpAufJKB+QI=#Z zRvkSvd*46imrdvbH~A6t=13lZGrIhMe8?dceQ3j8I4K^9)G^um@qB@D7qQB3CC8&#qwoVc&NMVPDLjXC8IMXB69e-MGZ8f5x-z-FFCqI z?FF)cV=9f>h1v7Vdko$wWz*pBh=N_LzWhh z7d!=!Xyldifh1^gm**gG9^uZ%MbS9xn`%?tI|BoV{0U1l52Qpm3lSzc{wpV>IDy6_ z-}y_F_DUm%W-x5x^3=g~O~L3VjT7c9Kc>2eUFm}LS#f+uUK9gR&-*+`HDseg#sIt+ zknN*c6f?EyxzefDawTMQBhb>;b(rK<)m$YV>w(YvU9dAMGD5+YV(YE8 z#WR)3{BN8ztBx#>B(<~=MYN{SCtM)D3BOFnQ*Ey0V7dW5Wi*e+1z<@ECYHgm3n1<+ ziEF+oojD1|$x7Uq-z@?}FW@0Z%xNg8T3)fghC2(fv0!)E20!5)H&A%fz>_!@={01-}>A2YBsI?v7F@yn5j zQ)63UN`Q_(P~WJt$Czg}e%Tuu#ccuuAe?h*oraU%R?583P#sCjX#C(}f!G>z-?%yh zQploqXNY&L= z&(V?mTh{5@LR_lq(s+YL2Pxi|oj}2G0O;+yUABlC(zBv?({1ir8T`5>5M)g4FL4?L znRy|30LXfqWR(ky|6a*8(_@R9^n3FIIXPoeAj3C;{!imDykiB9 zOBw(ukKgHf!ZqrXK>Uyd{(R2?wIh}WL*IX6X3Vbr->-~4Wx~?n9_ZaT zO+#`8s)<$bSu21=E=TAAU{FDevj0?)cBEO-sFXQox5mtGMIc7A+N}OS*C-&1oA$F1 z4Gxakb~+D9QhYCE4tzwo?O&>U%Hj>ULt!OGa4SG)>@ovh1+KBcRg?ER?aM5A)h$Od zYYIi6#HfScd6PqXC7PyDZ98t|_YWwCEl@_662`ZjzbfqckucC8<-Z*(OMyK0_u+w7 zJq3+Zn7x51SICOZ6azrA_iEF=C`Zz?J%1tCcza;kR;FNtESa|x`R|24QQ>Alv$Q34 z6S7g{J<@EstZZ`UpHWa?POwHcd|#15NF4C3K7UUHkzZm-TSw~$Lu-L0 z@QK_Ex1V{SoGHT=Nyo&Spxi88o@hQ0dX9NyAsrvh>w^% z3{J7hGJ>-p;Q;#A{T_dE-#fWZ!2+G{wp}*lPd!*O1C#=W6X%RT-~`~U@XJ9xR_G`G zghdT$9|=idO-IRgSHcez@Ncn+=YyjYFngt;Y7nwh@0UJi1ag%pn^(c;zmG7)0wQrKu?1BHQa-gaEp$yj+d#2iu9^yv_Fz%pNtZ zJSYs(0QGz1w?mU0U6is5`uH-+*UOcyXg9_h_*2;Kotr|YG)tQRnr5~it97gi$#`WD zXilRkH7BPz2LWf?pi_BeI2$S9Sx#fL0X2u%=9@$Za=sI1*81Hr45$e*`4amq&59c9 zPuAtmw!8cA5Luuz2hf`Ti%Pe-Q)c)}HD{7U`c(}1H!stw3ue7K!Mtv3*=NN~!|bsa zom9lg!|}-%Mh4a3#F!-k!7&88m^wzHm2w%~kLLA822Ow`mMKOmwUYo=&2b8V5mZug z@dARwRPC{}_ztxk7UIjR!`xuAVB;9GOb|JI9-gjo4^VpHIlc98E?dH!Nx4G**Y3G+cP5L>0;7AquYwVi(!+jw*H zK8DA|>{<~*PEzo65oKCH*#_2QG`b%beyR?t2xj&ZX}&OMyp)GJI3!p!Qjy9ly;}*L z+KADxbS*V|8#CpY0NMPXwMbu`LkCL8U}!mx9#>Gpth2%Sv6ViO$QtX=nX{l%Q;His z_~DENaJ-aRZpDZN^FL4+Z|&P5lL#MjARUzgGEpw2!^~RB-2qSRzo$(GI=YfZkYBl} zh7EnPzQ_dz0p#0DwfzGKv`>hboMQ<~EvpBrI7Z%(FL805We5=uhG(P)kM7J{qJjU; z3WNcoGo?{qq3nC$ca%{!q~^* zC_64cPH~Mlu@}N=c5GnaK%9Kj=&4n^4w&BEmM;DSjoOvVTw;Pb>8WJZC!Yk`2HdHo9qAHSgVG@M2KGJahJ#n#- zcP43qsPbiqsQf4)X9*)zJ*8IANgws0C9?6Zg`mlmWKc-slPvM`zW-SDXGtpn zQFd|VN2sldm5LgSI~s$+T6?d$<2Iu6=|tHIt-kyY{=W>^_GswH;K0y#N<@vr58pyS zuV&%Z;EL>Z!iYnW?c0n}SwPuquKC<;v3TVfrqVDKHqV3mgcm{osVK<$D&<>)U_=I4 zL^(RzVZ~5C_Qs|aT^Dr)S8L$5)jJGr(9UtpmRs$l%mNRUn4>Y zMxB5_;0X)oQg`dpm>?-wf$03P3^I3SX!2UN`H^!Y3^{;KJMI7k`O(S&8mIzRe!W11 zF1ge@!I(IgxVvx8>Bq{3c!WZCV5dsR60KO73#~Q=G-uh`Ub)TDBPqu0;)?! zgQh9(S`>h=Eyq-)WC5((O7WCaSV1kLEG!%#1?oKUN%6vph z+-8h`qGL0QWm1M%FJjaUWVOJLwW#cK@pj5M01qoE*YNl^X_*Qzn`d5_Spy6<5+B zqqiNy|M2$_^75^r-A(R>(WE|tJ;(x_TLwge4REa6L*p$CW~o5^za2`J`ts-be;^wS z6L>t%a51|FBFs7(t#wWAK$F4ll5ybS3^Kl-c;K-=Yt~XfoRS381jy~O#^s`oSX@q= zCg>(Ep_WyP{*}LSMli(LbJb?4~nit0weoy7Ss+vZsuj3mu8Vd4BZz_tXfpU_p!$WjnR zQ5!V$I(bUD$h88ISxWKz%v*0)mGbF#^joM}y$s%8ioz{55FR5YDh5dy7)Z8l-W!iW zvw?EQ+VYRP1nHTrAw{p((+=21>WH-m*=FWC#{>9Y8z+IisHGmi{7AM)ucNEdpVl9s z04<=&+%P3?#aUZ~H;I$<#!)R$Ka09I8l1F7YS3aSQPl)A(gPj%MLfV3d6OPu=f1?X z>=T8l_ZY2l?GWfORMHrIVOoz@O4f6F%WsLCizx>`KTiIf<(}OKv+afsY%9GwUURP?%((=9%3}Z?t#izz_ zspQ~-Q(h(mLn*I*tU?Z_?h%NNO-Dld0o0-*6j}{!w7xLb>!sf!Vgh*)Ixx#C5PLY% zWv|y4UK|*qV+lq)+;XBUN4l@W0ogh5`bHnXeQb0jmFn9WRP+?&gwu_9=kNo0@S z{~VKIT;QjUI!&Bat{Q7Wecxf4SJVgvkj)>~Q%F}-P`buA*{W2qa5)M;^1pL$59im6 zr(!{be;M(+;8H7qJY8l_?UWTN7zOo<>M#K)i}JG!Kieeb$>2C!v^Dx38-BM;5&w%Q zhf%=RjI9Y}G>lH>N!ds^PGGuVY|}gPyw7T5tUe%A3*^zt)L(c&O8e*!$DI7~LF%+c6O8f|>w7+FFht=DO_AV4KNlq`fFCd$N{ zIi!70xU*IOa*HPruH|*43>|6BXUqEJ_;<1)z%PXQu;93*;*WWl?Xt4+l3|E%;3y9W z((TVsDx(epOk6vE-~U<4nJ6lRYM!je848=VrLkcC6xXuLATQ_M22l_bKQNq|GUH&7 zk=MfDjMSeZ=XixP>;$c-3T*GPVU$vC%Nt;U0mf4#jd3UuXv1HOu%y&7qy7*yNW_XM zX~d{kmxtEMj|~*8EnuKC3`+ilT|n3JJvG=gp4Ut8at~x7Ju)YkyTtikaHS?-=t{5$ zXToI!ztAN}w$Yvuq-+8y5kB9AirliN`67kyYyxQPuON{<8H^3!gLM(9YxW6a#teIT zr@ZRX>zYGV04_`D<4E^8hBe6L+7LW1Sd2q0ImCIpvJy}-l4nUEM64BqWWk|1lal{| zPGcllpgcgcaucl;MuW2kIaa}vqrqrR8;}7J!v&7ny{7hXRu>Y|*lHk8K2#mR=FCam9%DHy4PXl%F`lz~bNK^4bqY8zIO9lnm8+^Azu2)!i1*p~b z7!P2Oth5C4a943kk%S)9hC7~}jim6XM zhpPh?61htjau_Sv_HR>Sv`fKIFS183jY@x$Dx;&2w#<~)6A+wE%ItkJT#}$;5)K8z z&r-d1zBdAsy>q75Up*ycwD;Nx8tc!jX&zN=tn`O`9B+=$oA>~nw#2Y!2a7oEZS3?0 z@g=Ic8~&1N>oqZf8(klr6*R5PxIV>Fzxo>8TY@htoC6+E4JvQ{$SlVG2V%W$U-ObV zxly+yw`(b8(j7ciE%i6D=6BHWYop>tvxG2nJ=$~d`XPcV%lEVNwWVUR*<9Ko#x~~Q zn!eq7M$gy(K=Hv^b;9wOk}M*JL>+((*{kkL?caw_DMF~LG}iCZ$Pyjv4A#pLQEEb1 z+i91M|Iv|Mq64FX%dKm>PfwOLEz5SkyaHe8K}!Xd+&UzBAdr>FIJS|;C;SRizYco> z6;533LMK7%-BMWF*q-n?e^8Op*53yG>mzQh;hO+vXuEYh(fchqFLt*U8G!*$8?oiy z+m|Ap&R!U5>0Dst}lR(L&c24XJ4P&D}P{~%vu6kS(4K22YtR0M!-xD2;zA8O+h3a z-w0DGqU4tdHwc}4lFA_KDc^1K#9esuMe-%{a5X#}Ip_B_aE9900ESKG(UL8goo-~G z1Zv!AF6IwCFIO%5OA~eM@$64hiCaWeb&-(?o)S4D;@hr*l^4gb8*SKSyo#6qv<`*4 z&!;xXvKs9?)RphUJ{d#_;{uJQjW~n-Wy5EtbYoAqqx)Zt9@+$IoY244!Bb#Kq z3mr;)LZ8UK?&mHKl(OfG{zo@?S=q0tzcw1WZiSd|yn440)V0hX`eO`aCOcxDuI&Bd z6JW&2_}?kqmDXH#>68pYLVEaS`amQ1x`_y>fNL9EsH)Xdmv` zwDwE>&I^3QF&Yv!8UvUyFl7~ST>bOwjj;<0GPF&*|3EK)8nIL1ADgas1wBVX%H>(W z!CbkR#%N(Z%5rgpT|U$6iAy_J{AB&W1IDYK2u6iK;K^~O)w zuO#@ZC~#%$7{_Ma@BP>5qdhXj|HM-GAjm}-JN<6%NV-Ot?-C@8ESJYo#d8ygNO3Uz zwp(Ue-|y4x!)Mh;jC9`1~Su^^=}ZIW8W z1J$I|&mYQrq-(^0rJvM74Mo@X2+hLbeE>=Zm<_UI;IQ^|@I~l*x4fUA( z5iuGa+DRB8b z-uMLE`#-i?eMG)uM$gW(W;6D`n?M-x*1kc;o0-E=(2x5O*ZwdTPQ~G`j(;Mxu2?h4 zm*h~!_Yo8B(2p0TZqyl}b-s@PHE_9W)DjZWcnc$R3ai}C`}Y5c!8zT@lXTet269g9 zb1Zd316Yd_A5-{g#ocDvf1cfRktjmdVT1iwlgfU$R`PMf0^JYZ`MK?I++>%adGP7C z1M^l4z7esLQd1s^aev5P(W^=!o4XW+o%|J`F>gpb=l~uct*EqkiS+vW$QoK2?^}WYf@=zsy?}Ymzt>dUsIVpbDrEU zHka$izG=ht#~#@*;o!H1*iIoUl5_CBR>DXPd`c!rm}JkH}$YYYwmL&rhG_ zk9-!}BT0U3yR_D4_kqPQh4&yM-sjtwtW`e0IpZ2@D>fM{i9Owa4|+Q2#3EU!csX_& z6}RJAazRP{OX6t9f-bGyG+6U(+PyO_%;Qi*(lq+jS+EgV%c~Y`h^GcEYlYpoa%b;* z3%OVh9c$5I5*wS96$QH{P8nsbaIUy=lO6~;*qo-uO>r-+XoL+lT~v&g{7vKLcW3X{ zW}iD&l1P_7r^zZ%tP~-uB&mdB%WPbZ2pyH!1rJlo!tJxJ+&v*B-y7#wZLb)Gcv^n| zHm%p*S*4+Q_C!?g*TTp-?6ltr3O2=UFRdNm$1pGo00JHu$)p}_yIK9>oROv4(r6Kc z<8-UJWY|IlcNz+7=;1P5q=+L6fT6d3#^A+Ij4L8 z#OqWT@ZXR($r2 zgnVemNaMt_w(Iw)+M!w3)dtWzew{00*Uun5CR{>4XWV}!hS_R_C{-362Bwx^YbU>pucL2vGAMedNNO3sevmx7RK!j2ITDtb#^En(6r-WJRb0w!6r_7M2ybKxY3(LlyD zwuV=^tbS+rkC=rg@|)2>ak=A{fj5soFET^eXSc~OcUzv=fE;=NQI5-7Eqq#dr(AV= zpUbd{LR@ok`Ru?+4*=ZLZtm98_j{9qWF?o5oWiwXP*sVj$Z2UbiHI~pD`mAuDvD)wAsZ6D!1zaJ*IyN64?Dl@jg81q!9*AXgXp5g* z=y8#2LcJz9_&^TI9Q`re{f8(m#;;hqhrzic0`K8QU?r4a*C`jrzf?21A?RzbE}Z-K zC#8w>rk1|P*=F+Q@3{j}X#gU7J`Zf?MB6c5x?&gN@+N-d0mI*mlE)uJm7Ir%JMM?* zBhjZkGb&gEcl?}V;J-Am~c`W#B$#`FHZsaFg?c0w!WFLyn8UPM$By!LWvwd(3+ z3-r$}>eYfR-({98c(<0j-{8TF`0pk<-^o6#O-bZS`NH&=@Uy9UQu<6KmON8w=yTYc zQHz&p3#uZ}DS3wCPS8pEB_Lx3hxsUP0h>D6Wa4`qhPdQjT_o2z`(@jJNTese_!Wk+bb%m=(M%ZK8Iv({Iy!_#;XM;v;~!j z)>$T8b~g_Qz{B%G&@K!OLGN~J7XB3aF@G}EFz?$SJUM;qD)Msso^*LdjDDGs;{Ayc z#mZ>aN8cQO{|CAlyQCNcP^^Clr!|_|yL0{oij8Lqhii;*7ThTneut$OEK=V3GYV@g zU%&Bu6Z3GeC+WTf(mv(`>(85Jo5$-8R!e(ZL55juq@q-9K_}Dlr^CJ-!D-w;1FG`g zi`(z^yi+E|UM(tMDE+Lcleus2bA2<)bemOX-54YraI;c37dxiZqQ@~WJmGXA+;Hh7 zCLO=L^p@AoW0f3m=t4a=Rgb_v)?z3lR+1n0?E7vI__0V@a@@9PV5w@qW-nyyG|@Js zr2#^YJpt}|)BSylsBO?_8VebalRbcxsOb!r-UbUXW{xuUZ+T(wBBs3j2f z$r@Ty`pIL*4=I|anjeSR|Bn{C;reCR?)_{8iUa_C%d5IfIu@<`NI(!7{W8cm z%dY&Oa`*6*<(yDV%>LRFdok2o!B?hK{XRc#R>b&SHbvQ2>pL`OQ< zEmhYTE@jhq_}J`Jsy@Jx;V!JQ8m(P(WLLmF_yH1k^IC!EImMzB-KEF!DA5(-`1}^( z*V@yfU0y3CrhyPON^}^{^cqorqA_pFQwO~ocQ_r{j%r%qUOjR@^YQV2LAQ$OLcV=o zJQz)`FyO}Wl^19CT4hXS##dem65lo3K5cw)wf_Cb4~^1A^1a9)>u#H0dUY4o0Si{A zJXKu$?z>*|f!cp>ahO+GXGcZ9kKaP{3bXo)t@tmsqnOOQW$-YF;?l*z(7*c05tD{- z?`D7O&0p5i*zfXaZ#Bd#Js7_k>pAK2v82x`#Ff0o-P#I9mhR*od!C(Y5-__=wfm>8 z*_=`mxn00hL)=Gh0kKzfFR*PwI)=kF4-x8~j9o$g2l7SOqBIPZGi#9}v$KwsR9&UQ z;44s=QWG$wx)}FvXWSo1D)Sqtf1Q43xS+zc5D@-(d_SQz=En&L+wkB_`d4bq#B{Q2 z{I*tTZM$Cb%KQHVeF~-z)OwE9m^1FijF$m({@1x@Wp9hSnl?`S2Wro?bE6z{a=z18 zpYe}&`ms_Gkn~!L*4!Gm`X06*HT(#rub3>mXViBZf7uV0B8*pe`-yRZgSia2a};W` z#<;{)#pk6axnW=gKJaifk_`ym7B%8};m+iX;{S)FbB|}b|NsAchDk!DtI1}%=E|vq zLun4P$(2)@W9cB&l#Xo3`7k7F0`5E-KnBBHTqAlW7knOUlqQPXW4*aP_X~X<+|DD zXJ7s8dnfXY*V29CZ+Azf{s(bSRh^NW?V0HM&tg-A7mxTMSi8n>f)caUb63u8jm_mK zDSYB7)4y(GizkbPEA{-En4E#Ut_K2$^?13 zIh#w~yBKI7)Nj`oN7O0oaN8Yn?fTRxw5=n$#rek4okC+J`@sNnkV;lZeML5=_75s~LUkAH9v>7}jeJjKirR>3azgCSa4w-pnIrYK5HPOpJQ{=MkM1#D(+y{{5Xf>}gkn}rnkvM4@?g9t1wywYQ&%el^mNl#yUilEc zBbBwUbTlTsMmTNWQM2B1%i%bYeB(ooS60kUFEa@~S!vtJ8>r=?v`!e2HxoJN}mTJ91yHex6#1As&s+KJvxDJLskXlPy(aRAm^MLto!HhiE{xHZTOb_bxvHRld5B&RX3?L4(VeEqP&Ltg%*8hywtw14m*hS-f_$0H+72d}OpUDU96E>d#&IRuAW zWUXnN5cY8#^R?hz883@+tiXs8-|ShFU`WcIIg-}FLF?}FPp6aL0xGSq>Tq<%hK(&j zs0%EU;Z`3(fwt7cwMo2;Rk?VKVZ`?=Uq5!1W&+J|rPychsjByes`urrKY`5BmRH^U zv%LeEKmlME2MJY0&O)se;s$QhAoFqvuIH%!OgE0baE{uIE`-%YsPy=Fi|08Z7^_Jg z!1SyEY1Z837xci1B!{yvtC9$bzUa#91#5y*im5hUpTMI@g)`@p&dy7UY|Q_(;E2Cy zsy3w8L88OZ-!si#t??`2E6xeEC4H#Ci9WfzRG=t|lMyj# zE+)%w>HDt6|DbWBkn>^?X-$qCe;AIc#KyepPO|#QP>G}sMn4igFTLh;DD|g=Kl?Zk z(-^MJZ#$5sboSBLe*a$<>0bilOi=@h+R_=_@%6O}k|zhGHKga-7$0aV`ny$M#C76V zsY|Z6I#oA}%32dL46?SS2FUSAEOGBo+`9VDG2#}P<;;t^rqSD!l+=|6d@iJKP7X{E zEjy76tD+MzE$3*^vIiwR^@M;hx#F~|v)n72qRc8^_x!G=&M)qvnStTZs96{!+&DWY zIrBapnw!Jizm3309Y!fXi8uEXt+-uwH8X0Yo$jD;ZrUk}<<;<}7;rMBygZF>2LwEi z;t@py=j5*mSd#{L_gYTL)wbF3#tq%6ww~EZ5M}q%Ii=63j`=5`ZMs#lpJN#WjD69g z=lAM;hRKW^0ZHw&uhpAZ6U$WMRv#H}oD-+y@*#F)o;S-x0Ai(kHpmaK!jhm95(9rn87!Tn8TG6BnuQHVT`po$G|0ucas1QcN3Ii- z`t`@_=qqb_#>e{Q|AMv*GtW+~X-hqo;_r!XBH~{-C!dZBEN7U;%s)8~qZu%0bmpMA z0A!!n>l!SDgLq05yk4LY6Z9NASlWpA3WUgf`w+EY25c~}GbB$#N{K|!h3Lklxtn?& zEW&2{czAHAzn7zZut|5upXOD{I<$d*OvLw!Y*lfpIfy3NjGd&#-&S9ybBcb(dc|H_C zWmbyng(6!!YQp~@*EV&*1Ip-4eLHD-PUU(GjHKE;U`kPH>!SVLU{WtbsP2rQS}V?; z@Sd4)$uKV=7|tRJLJQX;CG1V{S}ndnvAH3(?26LoADI{Xt0=|;;X<$(*&n0uu^i8^ zfI(eXf4tD`FEbw87u8iH3CA*_{l#I+SbD zG&s9JXiIt#SK(q*5vo_F^+cF-0xZkg)BA^XNicGoH!^qy6YZMtAdY^#ZJ9h^8{Z zZ(v?siEy=NP}_n{kbF@0vH0FR*rK* zz;N+Hv@)pOj2uUMh=jK$P8zJZhW+lZqY)R@)5qgKlNI36LA~Ym{4vp*Htcz-RI-v+ zmFc2DbR>4sQZ&KC>ukL0pNZoshG7!l>+~A&tY!dC6S7~Sr#ww3llDJW*UE{$ygh|rkzvR2www$P6fI&svA4GhA` z2mn*=<2Nd?37Pf=cdLe#9KqmUhGe*PvJhSjVFV86&j*xqr32{zMm7!%BO_4;{1H;+#scYJ ziHt4jjG1z$STkm&kkE_xPslK3=sfS-dm0KJ12F>nQWJuIUhp~j*eI}$bFmh=Z}!@F zP?RtUy8>rR2L^!1C$N0jmyyLEIIK#h)64{Y>4BB_o4B!~AWKRu3P8Ec(8e?EK|>F6 z7bCdKnHIb>y$)ov#fM}QlrK+^(srU-BO<&l;K>a>ukAHPIA5eT0?oyCKtaGh)k9{Zc`@>i zht0PM8R_2`Nw{^l;pGz);xH8Y6*B0Y;2-UkHH%3wLn&Jvw|JkfJ>N8Swqr&_#OytR zB9~o;$l1j+ZIiKLK;UuykfEg^#&)ZWUxTBWD5|YJJae=<(IJ>EOOfpvU?jGQ)>VAc zYSA+jj*Y2q*L!QG&svkdwZzN=)Vh)yvyhM?<`kV5s0Fin*4>&;$nZ8a13QYtQ>p4i zS5Ro4gSbf9hcCi6uTPa=TJy+d_mCSHIP7)@jwWJ+DnkeL8sTw8RKxL3{-R^q4Y{TmS>#m6_|auMasy!`8!D_XXgO^VnR6`oF-9M`<}J z9UOmD$IBvZl%>jlZd;nQwDr>(v(Gg^9*^;ZlEF;T{loy879kkF z6hP7scoG$2-TAc%9@q#!<>>dWIGD;g7Rx2WR43uW|5y&{LI>!$RD#QKcm(_z~auG?w^bq8cf%8J+OAL6aK8FqrOo zI*|YR`Y5%JCS`F+)BG=8%c-virF|hPo#}Ns+Mt|~7e7W1cWzgvgpQ3Z$%Ccg7Ys<@ z1M4b3%oyWj6uHGkJUoq+&q z3z_^mUDVXdg3u(Lay14d%7%A{#JQKu^%o}^RIXp0tAf>vnmwGLk0t-il1NI0g`L)i zvZq6}P`)i~Ick9&{%5=KMK_ABmNg>xMZf4bOb`qs4etqg6!h{kNAk!T9Upyw(Rhn0Wgki5gzl?vW*hcar>rq?;y@7?h_CH1`w z;57wuaVf%Jt!Nz(D5=KCzfJ<3X-Y0-WaNcIM~TKGSQ!edOCm$>!PzL=rIC^J+xWdkBx{?Ney zF0}*A2fw66QAM#oxxj};3PZ)ZDCUlIvkW@J-RxHrv6`T1*h>3n??4*YJd%@t5PQY@ zrZk+AbAX3BR}FL%r;sHZ&o;0PplBw2rQ0k4Ie;P6dsd(SUtj zW8c3DB-qt}@Rc1Vsyy7nnvSWjpGsQWQs7Z@i2y-JbQ~dWoIAL2E_`Juw{fxy;n}Nr z*yLSumO>{ld`;HWMLn1jia!y=Z+#8H_f(Zw(0roZlpQOB7sR=U;1jT$%ZK5+)p{u9 z+xsN>oS+u6u4TA^NmLZPh5K zPK{*Y-2N+@xXaLX=mG2lwS3Y9AF2*kK59Vtf{$sWv-)V>^8`nG{ZJP<%|M1}>)Gh# zS~z=tKlFG(!i_B(kq;9cdCk~3i7#*V64{vWY|NEoR{HbzA*fggHbF!vP!ugC2BP`A zpV@KGLTfiN(z(>M*Fk8!S@fCT$9O}Ef&4+D!t#;yv$Wqv*>MQK9nPy0{A2rJg}iZT zJ^fqiQ*M`0N9Ug-HP0zm!BJDdsqrddf4U$Y`*u*#=%wfkCV}totkl7&%t4B;u)Z<0bxmp~!ROXhL>(sHfq)R=yBOmAj#(y+ee+Ozs zo&vw9tFMnQipQ!BI^rve3}g7}IfF!bIQh~rxeSxAlXqwx$uYPC2QF3<9wJh)KLIi- zs>M%JyI9E5jqSek3oFhyaoq`81S|21Yw|UbgzyN`qSj*j%UTmQ#Zk-9mq6lbO<;TL zY`u+RD-E5%t9wJOM;nk-YrPNph{X$qTqeWfYIMw+zkNtOKjl%)&5N*J3ork+H}HE4 zkgy+3TgZ3LezK`2Xp~q`B4@Y2SFduCD*0mTu~LGB$I>FA3|#h-KG6>ziYoJ6W=`jk z)D-OCWj}J{C6xh26AglRqLND6eEk8c{|k z+Yc0w+N^iiGMrTSY0OhOb!GZ*9%B6wRAE_o?F+Zm_Cv~d?<}3mv_Eb~lzH#n=^6ib zIl1E7uA{4@f19U6NR>@4IzPka)vnAq4&6~&vWw(a-lpYvR%}}hS#^9&kQ#rmIpYe5 zKGy%MW^?pEMQI;x-7oIBXfI?4ljdJuGqAazRnlYBw5Qfqz*M~&xDL`^OH#{g`G*mY z`PIr(PREe{8O|D-{2aAlrN1Z`$S;>$eW;bJ2ADhzBBw8I3agj_{Vo$DojXpew9w z;nI=pAa2ps;lN#oW-4C}upU)LZ+m=xKiqH0#`1e&femh`$V~gftpq`PupniO`}}X! zjp^KfZq@#_sqr&C9=LBxapo>x3-ckWLX<)z-b#nT1Ay{^Xs~`jlUgcMtHC&wQ~rVT z@7#Y^z3BoiRe1lht3jqWAC7DmtL)f5e%vhP{&&0Xju2x1`nxxU)(u8)Po}shn<^;2 zvHyh9^s8pkt^D1=~_tow)Yg|a8joICGH>psdYQbh%lURh$( zk3MXRQ!9o9{?89lvD=o9S%)j2O4tRO&tC4&+r&r3GSgSWoi5zx7(V+pSbOHa`Ch}$ z36Uu2*RQ0*@=q&no1nZSbG1gH=SvRma?#TWEaSfV_dU<6OYW)K8F|NcUs11$PFKl0 zU#Bsbdo(|;c>5ljO%Z?aQ*fzf08imW&xjow(GuH!Tau7J1uKhFHr%ttz zrZ((!OT}FsP)3Nv&zKfR?&jBerN>cwKzc%#9C@Jb=JB(tNF7F=I+Z1U{7ti0L(7~Y z30{kE+WuKYD;M+e2C?=OJ855bvty>H^$k46?udJAUfKv%L#tweWG4@M5(f^?MM08c87(UxZsz)k4`#GT*7#p z`-BMQ4%CDx+&j31JCKSh4v=e{>5g4K?#SK6dli{e_eN9l84%XSO&MvMK6Tg0si_EX zLe!ek{HL(2u)>DimsO|j`PsX}UKviBC)5i@{(fJ$mU{Z@%wKPFbN_=elAhRUfvWjO zNw&l?zxvVra%Qyb2Hnb6B9`8$<4=Xxr`{I$$oN!z*cGZ~eWaK$#rm$A*IsD0Q97sW z_Tpc8fq%`)8o#v}WR9Ha;N9G_dSLWOTTqd9atPddbp)ni)U zVXU@Js}0S*3~lr=znaqS`!4ZXmHYj&jqz<|IANQ(#C_>&tibHPJH6Mo8YjJ#rq_U8 zI!}nuLNiI<$6Nltc$U4s;r#w_=3tg!?pJl10NGr3WF9m3!#svtvvy1nBV8Zy7xS@^ zVXXMTct6r-({#5}q_;J|3s12K&qF~^oxbKs!qnNY)?2oOa5rFF1277YOyQj09=gRw8{A6oTsyOnS%M zV47{K80bgmtVy*x_++!Yc}A~0zW&~9ld4vtDaaPD>504;@jL#x=eVhom3X(N@x9;O z?-}in9tYSIo4Ipr$gy%qa%$r8W>{45!gDi1RqoV5!mdzt08$?+@Wj2t=VZ@QXH|qE&sx-X7t4m8OUyl=HgK4^Pi9I9WbBo zZK2`1*TdZpV=}kAw62Vg*?_0^y~DovbuoG}`)Kb6N|*+V;#h+^cQ5kO-VkyrJ`f;pleJ`SFXz_sy{hXi`o34h zsqHT9?KS(io7-U40Q*C)%zwF@EX7Gzg|n{)E(dRG$}iobXRGhTeAs~jrm^4qYqPv4 z&?MJSGK)_{Yu^w08WEVXV=g|e%;JqT#rt;BuKC_l*|kkaRYQLsv-v`&_CG)NNHU^p zKa*@Qv8IO%rEf3tINbLQ$-W?4Ai~^JL5RBzp$8neo;j!u-)f{ zRBn$Yf^$_+tQT#qfg_@5M!O;?)FA|>U(7e;j&@i4{4+Qfy}1b0Hki5!7S6sRQ{<-p(SdcZ|1-2#xc4dAT`#2@UXzc7a42m^{%e^*_g@;tK3Mo$1IDAfUUS=KE9FM30uTik zVV%y^Wt+Z%&d;16MfB-d?8N)l|F*k)F%1AvVt8L(8o8jujM~;2e(cEE9rYJ(+v!>g z?lzjzB79tL8=C%9KE=K>(quRgr>Nvd*nNC=psZT3&N=(y+HVm#BcD#bODVpfScST2 z!gEA^I@gzmD%oOi>=-5_&Q0N1s{dufL%Z*&@P?kKM3BY&%TM#I6;d;gHo8JNY{`q0 z-8Yh#UHnYyw#59Lnn-CmeltVAY!BQ!lNXaSc=ErWVaJAdD};e$>mWYxb>-dJ&5FG8 zoyst(El%CV*jdrsXk$6$c0w-qf(s?UC>wS3H)(? z6Xv}Q|AX$G4-XQ|ema@dp7X$ZwPN*s{2LeRb3L~2PXb~OET`kZ=QCI1Jnap)7_W%O zz6QHfc?LU*dw5DH?_U+m&(GfN2ru%hAQ>$Aclt4 zoh(Ow+VO7q)r3a$8?r-984ITJar<41bD89^`J9=c&3cQh4|CHaVrwbaJZA<%cdW;<~szq!F{aHcRT zRXr4hvGgA)KKrk`WVL9fc&C8i3Qh9z0^jlSv&_`mYVzH4My7Pokx~UGqsyhPY{UM% zf23YT^;T#x`hKE7n1kzB=8F@}+X~@dF7)Z+5r}?9#^aRT3sjFw?#5+z)DUW}amE#b zfMm;hLZYX^r_hm(oV?$gf4<*X=#WC==R~t(S&#I-UwadJU9bBDQ(nKM$;x+ydL+i5 zbn*M=-NAy7%U_ z!~gPha&_~TQ|*$uoBH>8QJ0SO8h;Yn{nK+RsoxM+muw@gp1pePNN7@NO6(@B-sZ^Q z1xcZ*u1=E6=+k${RAowK`#DaBuUuLrTuc6&^EJVVy|@4cNp$~teg19OOk7>EBXt?} zNnJg5-#@F?w&vS-vhr(kLq&!@!Ed+roGANw0J3h{PUu~)$vAuY)zEs_vxg&5tP{Pl zd`?O0JN&=!r(NS~U*)4oT&y35SM;TjTKaD`m=*TTCyNBs#sR+W%gEO}x1*rjz)T8#x~G?$=3Msj zhLt8q5eG*JID`aQUsmsh*%do1#(3>{6XofI`_bA~j@PTWZ^^k7jJDU%uUDQUd#W0+ z(nf!I56^3^2FuS1PsEy52eqflwbUH{dzq#`@~eN-g_myLpLjh6yifhLHa6mGLvL* z#^u0OQBbLQrzcVUfQEMThTgSbNNDx?0kK!Sd{j=L4oXr}wKH_J0=-m{9aQ+QyMl$M zvTcpd8BULTt2#pW$0|}5*&W{rR5s5~w08|1emH(#6UbVF1uU~k0ErK~N`tL(V%W_E zhc9~4&EgxR>15=3*0WmLM$-gt7e0MPTpV~Ps(5^|O6n=s1SeE)k26pk$qdzy>F#8n z@|bk7p2)X8jWYoT@Mx8#MeW_B!KF=kim-7o7t`r4Gtq$lz|x+%1_P!5{?g-@iY*k= zaH=?8RY)}tBCMSys-8-XSGZARSw@Rs2+*ePH$!uDwj>VwT*FOtVyyUoS2w$NFQ`g0 zh-VY{=3wwMgV{XNda?f3W`-@{Cc;4>>PiV>2HCNs1S?nj6- z)cy%&6_wSU|Hw&21~uu22a4>@uD>997<}}+!#`w0^|IVI$WrPy>qI_(t@A3NKDc~T zHiGIIQ8@5h=1eHzZ$>$P+vss_)P1cBo$Sc3*@9_Qpl4XozWYToBP7LdG~<+(2g9)~ z`{ODum<7`*1grIJKTl{J*+0v@uAxXsc+rgcQT{njpMPnY5;_vIGF16+%fHSxm40rN zTyPJG>NsGy1B~;OugMzgRZysaT&?&>FF9rUxWxv1v$(kCgx)Oyx%o>~h@fq{7-jQM z7lJMb@qXV|W7(Cr>xd@zy`s>Jq7tGtD`;Ol-RZHjbHbr zzm2z&hEs2^z8TG15Su3*+32&3u0?VOHcyo?zH{j3Es^kF`#P}mA`orjXPs>I(RfCI zN82{I;rAEQRaEd$2JcHcELoe(usFMPePQg#$hg0LP!m4F*Ib-yCQH`ph=2Pym*~2bvDX6Y^s3u6k7snkA%Ht+5 zmfJ!b@5z~Yt7pfyEQpqmeflTu7aEU)$RLr8dBysm1{al0wgBnQ-`j##D}Vk_vyE&v zf`Pz9oB&>ge?t84UYgl|hn`|h2JPgDaFZsbZK6Kur7KUCQs5MCm9(qdTO ze_Ozo4pIw|*Y{j7epA-xNqD%$p2&--E)5o?O?Wwq9-LuiUbwd-$ZpfSYzXnicG5A> z%Kyh@`r@J9_k z$+JrwA967HNbEAX#dVvUd5D0SPpt0`@FDM?Nk$C1pv&u&>@Vrjpihv#u*AVN3^$RK zmM~UdFq2(k4|$voTy`<=P;l|nP?<+XxcHFUk}5TnS$LgnZ9yTMb=e~3!yOHkIWZ^d z`>2sa1G>m{a&E~DdNYPmlHFff-0f#9D3jx?bfh12(raHwm0!^tFpYYa(}?R>Io_Td zRL|n4NBVe)?-RP@YnEm^ZhheLUxzay6oLt-7Gvnzo9de}mE@&31J4cWBW0TV+z^yM zYRUT-?>m>lc)-Py5&k_x&EG$h9{j|w|Lfl`jw{_KCU_qZ+WhSvETu6Px`>SJH}FBesuE z;Fv>yabVJ#U3h-SnvXa0!@G)a-VaXXJPXL`QOsq1|Fqtmh1vSc#@r$^AlKqyTG5L8 z^}@f=Byp)3Yh*R3%TfGHvsyU2f2XwUFf+4wlG@FDPLPhQi)a0rD4)vGKopaPtPnYz3r)}KdFysi(PSV&v~uj zHTuKih5^BCwdPAlqnA?m*O}{VxZgsTMRm-FYI)2DUv=zKV*aIsw4tWbXFZ>h3XUFE z6$pFv#CaBDN9+vZ7jTAVe%g8eg9xoP2fWQJj4s=nY#FH#8^o`Wx2+uU`Mt6$M{nPj zE~_-LlitH^H9h`EysajZLK}vXGvJJip5^eQfdiUn;?sD2to9!pvuTEecVpDf$Eqwjz7zmzIv@m$uDC+vWws;aXaBU%Ub&L z81tA3x&S?<0?Xar$l`O}VA173Jk<8QBhou$K%Oq%NsaFYDG4ruUmnVq@Y!eBZ1@V( zzCY)0Ll~;Kms3nw`F?j7eDg|_w$uU9%CRN4@!p9Cd7KwdzrE;w9S#E{W8M3Dgr>fx``_?Ln5wYv z_4z@{Q=p7;G7+^*ht5v{S=V`6B-%jaFye?-LW+x)>(`>5V4LxXn9C4tC7b-l9K=Oi z0KyEp2rjw2OB5?P0dlJMIr`iC!;^x|!d)-I@Zm#gtJNDY31*$HQE~u#BP;A@bgHoW z3pwg*E3Q$mKvE>E#`s&yJXpx$9O0A!r%*o#|yWdp987f>*@Xn=6EbbOF<`uppuH#Jr5u0FdN>X^`44 zff_Ur-%NH+i@%2(k6F8}u>t8^X69}p;NRv^V5}}QGIj!Jekcg2DbCzB1U~!}cYEk++zbQ9R6hrC+ zaZ90qCD6sw@;2VB7_q^*Cfm%43kc2eJ3quWQ)64;J+3weE94OX`T6Hoy(|g&UeTaE zWX0`iYz8I}y#Z$3SJ(33S%07s!(Aryw}DtFvYVYtNm;!0KPV7H-^n|?e73opK6$1N zO)%(;v410V+q@c-0JTj@9vDZF+gr$z?n6KLnTr{A&G=wi2|>~{!x)7ScJ6UY|3}}1 z@xUS`NWFbf8$wk-bxSYiJEQ-8wQO@xMm$_g$L%SKyF&F<&PQ(rGOz}ehS7p4Eb_lvY7Xv6$? zc+)?FF&WboRTO2AY6tLx=%Rx<%VAi~=k77$rmo=00ak#GSfZ^4AWxm70O+d@Nj4n5 z81>}u*vxaQ0pV04;+~3@>c$67-Q~Cy`836l^T7;33F+Zw<9c{$bIb^cp4F`^*M#vR z$ZcapFl!529AjRN?%`P?YmpYeQiuv_$OcKd_!-wt{Vew^T~gPY+g$&=U#rBQ-&G*T zz1C$)9mij~;eDRUUtZIOFni4uS-I#>JCP{y`sS&1l^~b8w+Qn<(zulXGXUnmBzI*|SUP$p`Z$l;-TGjdrc8UE)0#JMlczR35YeivvQ2vJ z+fqypfTX_d@OBa))Dry++VXdS$E40y@Ma~79EXLpyiIlJF!a4NRfK=EK|e>8k<+cWeH zI~zQLI6(q6O3bYwm1p|V=l3N1#tFJ;JBRO9BdD$My6{;$25pP1j6E{0(h_4FP44Ix zIU;+M$1gVEWg)hFUJ2fSVRNnDD<2+g7&@*EsdsYcCtv>5oBXxqg$L8KeOw2kNPE}TloL9fVVp4qboOnatuI&}RFC;|L;xRcae{MrampS{`j?T!0m*Y5rjk!8auHMYO= z934}YZws)Atso&94{mb!qWi~t9`SqYC))Pc>ktbg#+l=U`v$ zC{75pTx(OASVYTAwu|YLwe~Dr9l0&=TV26reWR3cGFv5UAhzkm zQ0{qHC9}j~0lWjQOSMAj97paSeRR20U3`y#kf71~{iU%$RYY3OqSF-Z;447<(L+rQ zM>$DHPQYW^1;AYm?Kb47qJjl0PWdO5)8-U$gydf-@#HH4=$cndBW=eM+w<_H+gwq+ zwS`B}Sa;hSGd#MRjqD!PF-VCA?j}GryeMNWYazlU>{UEwG8jORcaY=-|HdE1!kTcq zJGCCKv_M25W-2;5z3uL5_F5lpf#b88Wz@#nv@xS`X6`zuMV>G#X~f?;!ve;A@gyPN zfP1$z6uErUP#FhWl!^z4OE2no;4d3zFesDK*rNb6cumka|SiVQAkbu;=BC4&v9d zown;`OM091|HM}$sCr@`Uj$+)R0LT3>zlr|FzhBKmfXDG2h@Zrm6UR1pj3n=wJTYu zic&YkzfXq}soe9+HCTSNL98_JvM}>;=trl`!oXTQd!(_nmRoNw22aTxsARKmc17nx zR2KM+#)8G%7qx($-cz$Tz#=Cod??dj*QOwNT1BP2w5iM;N zej6s*7)JfrYE-E%O<@|*N>f2JEL&>PePuHOtBHgNx<0!4vavi#4vsf-T|%Lt@_O_i zR-go*6j_~0 zOQ(bgVM=#vy5f5;i^|G2*;xzkpI{pXz}PM7r}xk{aQQKgm+$B@0)Ly}ZNOKQGaEm9 z{TxLJ{>MyVE4__p#GD2NsI|>GquLd!U4};_Th@d8R_A|^{s#tRzA!}h@eMICqlBsV z119DMKSks0;iL--)X6wPQpzsslw=!s#fO-G~<1%wX|d#mYFi4a=vNv4IV+~(K)ch|6Xt993BJHw1 z;G<9H_n3d}4jzuWC}m!i&;wK-kK?7R?CuN}han|D$ zM-PEYyl#aPCA3yNab)pi;&dz{$}CzX%sy))%NkHCsYIw@=Zi9wV7YDMzG5~qVO^OyC zU`i|>hB4sQida>c==SfBGQ}!9n&u?sJ)l^QLjkb$>%_Rg>;)(~$I@QT2Q}N*DFS=Z zu#^Fp7m7}Rp!bGS*#cOltE`k1PKZ34!x_-2gJc@;H%*f~z2ZW#XtM~g5hW<==t=&K zywlTW_raHqDY!Hc`vFCM#4l@cvg>m5*=q^_lkHGSp+@0vP#NgLD%H{h#cP+oKFX6> zQJZ%Aa1c!L^#w~NDmjrcDH7#nxNvxx*o6<_MPRclp|F|-TNUj&O9}yvLnf1 zl2C=yf;N?}I46@}_?X=;1*)0m!qSOR@B-xQ9jrgouPxv#A5d1y3f3w(O4zhsNWW&D zE9?i(cCNJiCbZttk|Wh|$##)>qZi8o|zjy}|k3aAAYr5*L&dsw}0( zUZMueXkx;#7CX``LA=?opds9t)0jT{Y1>=2(`g3B{1YWaFXV}6@g`a&C?{BU zuz9pcutX=YjlMvzKRmge4qI^Mg{3H% zT~)l#mQgiVT(2&=zZ{|~`9j#+pMg>&3dQ_yuQ-K}d&SqgVLIH~tKvf5;#TU;<})F~y4w-bv$!EfdHDCk>dGw?CVc@6yY z7QLe0n4d^K{smtp4}D)eOzsyEhioMV*7bVv^#ja0c5X6-qlp65w!rrB+XV0$BFZ@m ze$q;VwZKm0^6g(f4N0bo`Z0HpEgz${#HZ$w<0pm zC|))uk(HBy4^YZga%Myo#pC4iKstp_%zRN@fsG~4aaqiUt5KdrkO^&F4{UpSCd^BI z>GZ@X8mv=~WJ@Zm5hO7TgP_Cc)b*$$AzfxNlnZWgN+#=WRkG4F1SEI`Bg#==dqD2( zrB9A>eCg{O+X#cU)>1dQNa1vz>h8W1^$1l|sy589lE@XLOyqcdVCh!|wkQk)eT7$& zkqZNEVcmDx!_jV#Bo4+4`=m4Mi!H%cAN(aRYsv!p;xoA%i*#u7qsNEMi%|3P5*>Xi zgZdk>|GUOno3nj1^>S>&K#=P2ugtqOmFm4w+9+#9Q{PtF&@vG5-xm* zU$n(_6Xo1|hqZF*!85B2y~d_4;z9REN!4rx1{{$jHS0blj}X4OJcN)*B!XkQKHmgS zF%y5?NS_V`i}bx&popmPWaZC@bVJ#&phQC{+><@o-J%!@==x2)6=OW5t1&xC=9H%l zoNRunvR3_)lgY+0fcS3B?y;zQR2j&eS#i!--Y0lS^kv8sA`kdoDUj#$o!!*QP ziNQqDCBM2Uc(M|-vL=J`*5OJEqyZv)`jdivve^su8%kU!cwo<>$nJI2;26zX-(bRJ zVA{edd}U47kRB=tkTqBW$72i(A?kV*hulJqKfQA3_yqY=6P+$T?PB;_| zc`JGNGWtHS?Bw$!!h;HYNBGVy*Er;n<**69V?MOEM?F41Ik0WEX!C#aA+Zf+HR}J5 zqH~XD>i^^TnPKIckjWTPZe1*;xy-1(Zpr=9MJ`b;h0XnLNEfZmwG_?zx|2&6w}?s1 zErcSMETdUWE^{B>-}(LL4;~)d&e?f?UhmiI`C5}*fQm?rR9Rd5SwF+-%15!FD^frs z1e{g;nMGf}oHBUB&fT#Od-F%nYbE};*sy55(^g_Gwwf~#Min@y&fbf)t}zf<%?(bN z6Hr93$T8xp?P^RQK5rGIek-fQhak4ayGaSv01sVgWz24fva5sTfF=P)Q5XA^I0 znqFim7R9X9=w8x!gDJbs|Ii_;&$LKSB=pPG=P~nw=e4R@ncNaV6A%=n(KI7>OlWkX zxY(laRfYD8I$!4H$CLjby65k-**tFO0v~ynZJ6>?iLaUPF&wPU@8hrM*;hXZ==$p8 z>4i9>A1~cFGBx1U;&^*rex;O2K>uzLi#vL~qggQ_n=gi7iV%@>`!I#PXSerdMPuc5 zj$)L+kroj{HJ!6P=l9uoXz1fKM|(orKQri6>tT^+ektoB)mZ3Gn|%z=vTqmO>xe|> z9vIK2!2BANVu|vdr*c<$*uK*GG2`QU!9(DAaj?ZW|IPBynZ(;VKdGtbg7l-1Z8Z*0 zED3OOoOI((EXw}6nb2u2eTlqC$~XL-t~7Dd!Ak+3w|;&*&tibEuk^TEM2I^A=*BE_ zJK40#7mHl9oQWxXgI-q{ym7EGL3RvBtJRf-w#XXhM%}C^!TVj{y}G_gbcc+m0EzZ2 zZS%ae)ePR|7cDr2q2zKA)*YN%*Brqf%%v^(I(Uo}!}-PXSnR6<*3I*|@}EhjRq^p{ z)S}cECnmaawaZnGi>Aoonc(kLqx|=O)C!8$2krA{RG=`2ilzJA%xle+8E5>&D}&h! z7{3Q&qn{1vLYOZ8WdaN%aMh_H>bJSDe#5Wqq-1{P630ZnW^m=M^LlFE95*6KDj$epdx;LaI%_ z4213_ChmVd-Yu%DX!76>E?Ve$SL)(pRO-3e2WTGpNV&dRCPn4Xv8?F>JCQ+B?r<<#Q#a+l#xuo9uyLnH&4=K=L_;f;TQ zY;G71@2iz}IvaB+IPWus7UelK_%3kviSom9%D;t7s~P0G-|pGHJ;|U|fn9VXP%5ZJ z+b{lG^Yq|otBrBLF1@%I959T62l@PAIZqb!837o5{MCB38#Xc74CJuWXbo@_kuBur$&i z=6ZPmt|0AY8xSQ9dZTm%UTU3ra^L`COY6KkK^mNcBh^McDn-wB2f*D zl&!FznveC9B#RgOg=k!!CcEWF82;4bz&c*l%>7pSjZqi-FCGHM-N&BCFM9@aCf(xG z&wH5Jxm7F63q*-`fK*)K)vwi;1RGNfNUa4b!ODx?E9ZOo={pPca_u14)y8Uzo~{* zSvt@C2Ym8P$0mkp|8u{+;7Q#SMRWC;6KsK1?byj>NpBxr!b3LI{SR;g4GnXdD-~0q z&-XFY1y7d!vyVQTvNZ!=lY5{rF+zIFCpOpdTX-*C$+c&>Wo9{DbLOY|$9vJQ?|6GbG;Rei~H z(JDF0622$jA~N!UcLTa7O{(aeRaRxEH9y<@t+N^S$;n2_ zTgm$iCENEW*L4T+-rt*KG)sH4L%jTb=J;CxDM454!(tpgTsZ2MGXyyfxY zHhzLz?sZa15UVDFCl94?OhUs?T{kO5L|iWBM`|M!HrFc(+CC@C2zS5&shEh@f+IbKDe>P*DOLhGIt2!KmXmQ%|i*HRsvMSxBH+n~9X?<8F(zpDgw&Fj|+DA^Z zZ`xc*qC|NXLEsgi-`1JAF1PMZ*;2$J5OI!F*_+>vDLDr%fp0Z>7w<@#_52zQ=v4*M z66}2K9t+)qk9I}24>mbrm6G&r@5&Yz@ ztIS;qW5h{IFSwcs*NZIaA7~*=zbs6WvUoQWd3V3~MCjiQ6<;-Ydfv^hHZX2FXciPstzUmNpN@Qt-Td`4+2XT%v6>d&_om^!S_qR# z#|KsqlGrbR#!xs>izbJ42`MwN(^*7D;4lxOyxz);x70%Dma+PF?#Cdka9|xwk-gVO ztTx$}G0G2WMT^_TT`}$7^r_l^ z<*VS-jo#q3IqdEYO=Vkh@2#I=-_x!Gp2w*Sr~9`ZTJvd|AYsIA4q!nV6~wJ)tuq@$ z&UvXRG6x*pp5491*)%=hzgTF>_hwIB(hM(d`-i`~8@`hz?Y5;;$| zh-HZ1xra`5XM{BuD=953YxLE766~I{KhxkeY6O6bH}R(lSCT z+_OJ^d;IkK@)dF_ku%R}ze1Vj&zdG8NN6b7gXMVBd~k7J#nVA}P#k;9NX|s}Sk3Vh zCyKwOe#pP1l=kQ^0cV&S?7|cgNor+P*$%B#XredBCyz_?MS?bv)qiP$!1@3|3f?zx z0O7x&g%x^N1jv+tWV(D~&&W4G-hsfPU1)w;&vl^-^4FrGNqd+s2sS{_zhqpe*~ zbEr#WH#=r@Vm#JJdHXx^;a|~3s>0b-C-l&9@$M_$Jk5BEI^ySt=>h(Qr$4@Fea*Q! zc_dN4ur2sqB*R@Ii5xXRu_JCAN~24*HYAn!+FIl1>38=WhsPdz6EFFh+=6$qJlx`b z{`}Sp;n(OJJ=hs3+owGui_8Q0j75hs%#RZ-ErZT;1KP;oUp+UMHB@S<-y5QQk1+Cl z=j$Zep%1)(&x*EM zsY;Wny%s-Fu`;8P%d^$DZq#==cBj$1VN2VC6Rn>7*N^Q~v^!vvFT9Q-e)mji#EZz3|EXFG@S(LSx5e&_jN_}<0wdvsNd#&MSrW#7UXaA@~!yA&ujqdwnn ze(|^JZ7Qv=3r^d@U(IxR`p=yNmB)KkGfv2phItPP9b1y_9{ge`<2zB7pO@*SAdbI= zSBs2kFml2-8i+89(DG$P@6F!0rxhORQDhrW0Uk4FaaIqN$0>vkAYa>KcmLDTKu@xviPFtbRR(VyZ%p)~)o+^f7-GZlv2Hz;D{8CmFQ~~=_QT_Rc z=cX-$ z8S|8vC1>Q{i4qFx?sDmy!x7L|>Kk1_7)?7k%lSWn}rZn3@-iwOtwmF`P#z! z?sfeGb=_`1OgF0ay%PpMXpLREaCmC}^tCkmpkI&o8+?46Hc;#~d-bXJX&j%o9L{2O zNYi;OQ&ivk>-kbet($19MFmtdZvB|*MxvIW;eUV?_Q#i4@lgY0ZMai+)lHph_ze;b z(wJw7!_4=s89grT-bqXAgXzP)m-Z0O1y}!)_Q!{Otu+x^fmsqa=rxh7hj4oIagx@T zu1@|LW_q;qQA}TAHmb9++2p2neZZEfJVbi(n#dTf)mY(5#{#q-pUY&s1Q#!U>t5QN z-;Mne8g(VK&NOG%1Z+Wzsf@40LL5=lrkcbxv**HEP>rc@!_E1jTFqmZE~q?`GL!xo z1)#aogS9a=KU!hoR-Z!v`xA<8@6Ryuo=b;Sxi$p$$ZN_yJzpEPso-^2OJ>%~lsJo>(tuLZChcPdV)U5Bexic8njV?{ z3~y|*(GBgIM$&`2sEl4FRCq{uBmo4zUEgzUQQL)pyfPi-exd!Hv{vO|k?_*2bG6b| zi%n76(aZMZKXU539v*aHB%Y2(&Ve*o$Wk*1wOx&U1rC;XpUV;GyQ}@h@YgIfJt$u; zSLZQf_kvSn3gpf)UZSL&TYy$@UcW+9wDX87WYgL^pLTMs;+nnoo3C*VoKTf3wKaIjeU3`k@xc`c+&m)+GchTn}2CSSA4jgzWZTn4u`>#u1p z_%Ht?T4TfVGRS^b#_L?_fVGy4E?6U#56!jX$Ziish0W7vjk629#MH}xBQFQ+jXV3n z&1l=HeyQAyFS;b3u_(}Dw_fz-M8AiXfy1qHq7CiWAopgrqwPpZ?Dk_uhV|2lT3Y%J zkW+ZqXG;sbXTEtKcJ*W95hK~<^1pzpOPj%MZpAwmQ`z7m=~iWmyg7xwfB9j|mg~O; zd)~%GC$tmVn3lygdNiMh-D7kJ5$CW*AZd$`fo@lmi( zk*m(zH@)NC#14k{%IkPIM)nP&`|D~o-_?oNWQCEB0}um7aPk_B<6@E}l(Qd^-SJeR)3G5Zs#@SskbD!oY`*&2e22!bioeXyjFv5Xnv z1S1J)#*Dj7dBS)Fzx$q4J-;WoE0<(pw%}~5zHf@2Agig;7>G_mFhKK>FKD$gZ`V6^ z^!_ZvlYr4U0_!0GXO9r9Rmpz9Sb{|dF3t`Yzx_>^&^(dXU0A1dU#?^ZGT;!D93%F! z1bRAtvMxJTKdemEM^%3Fi|=LR#zz$QHC+++9{8j?U2#!bP%i{s79)}yDt&X}l z1xcno<6Qn7dx8s;u8QEc3&CT`1jSI}XDa&992y6-Q9=rW8v_9VH8iJzX=$qiNpcp> zuvwbI$9MB7HbKUHhAvU7psfI+IQyncF|4EuRc+HGo-KqEPK*UHO}@qIzr~Ue;4geu z(|`EK#J9eCac2^XtojIt(^}C|2lIVte`259hRWJ!kQsE)G-e71I1Abf=ypJaFG0_6i%a(XKx`qif)vKxFd0fQ-|X;ciiY__CR) z>psMES^_(DzdU|?EF)L#k7<>s(Kt~Aw+Yf>>g5Qk5K~#EYAOA$*zm%=8}!+uarPri zbPFpysmXm;FNC^4 z1b!8okw$>bp^U_E*Ok)-M1o&LRriFz%_@&V++MSBxcO^-1FZ_Q=u( z6*eQVJEfV$6VRGj1j|F7b9U8!X+>8W-V0$Hxd8Np(NHO=Y#kR-%I0=doV3boYV{0< zGhz_J^L_locz#pTZ2y+IE*(DKMST?{wVFn0{yFu_%*x1iC6@(or6BA*c~Sl>6^49E z#JN|XZJ~|R>xpx9v_^!{wjDf=i{J93?|k%~QWr4M+g|5>IY($fGngchl6#x4N*T_p z-zeP&of+SZ2H}PB5H<(_Tl=V?D04?4?m-QJ{q3ZgHdO4vHUsE8%IVQwL-*xyG(`sj zkM0Bb%gPJ-UFSOki7;OpSJP>7Yxzg=ROh3J>vA^?Ky%_v8r zD35EmpF>t?UzWCbekMJ@Ntz%@YPZJy^vqVI|$knnZ7?{2NNW}Y|BBacgQ0rc;>k3=#X3naMD@_TYpiJ_lIcb2jp3sC^(-I2b2xsjgik`wTZIFvCKV7|UdST9 zmsoC;(DO_YC3&L%sg!1sP+f(*o@oYu<~v9A`s1I46OM=eSN#@?Frq6jp*frx8If(hK1h zPW%BxB6bq+b&BB%nIa03q?}lCjNQRj^Yen{0htilvCl*=C^3lu4tsXR%9JpY7=H6M zIa9DhtR4P0$y#5hNQyz)*I^a4L$ras4>DXyrX5EO)tJC)@d;V-#$1K>2nF*~r01Ny zc%e+0+bW)DUcA^aL`KLWFDKx@K|B|ZuuHaS5G4Tpx&<>*jx%cp-h#P&X)S*hvf0~0 zz++#V$nmtHd0uI6>$9XJBCBPVTj<{qwzpwCIxvZ+p||6tfb7W*bcdj6p_1!82sZ#+ zT3yS4!H}P^*0!KcuNaz8rwSUyR;q8XZ~*``U@9=m71l#}kSijwC$&c?Rj!P(LjX;S z@_NhQWxWKEvv$>;1Gt3{6b&|BC)Gswyqb7UEH~`ceOPSsWH>l%Y~8r0pceqm1Gi(a z@Sh7X_)ftfSxde^BvDJeWZS0bDF2#V1Jc$=f`X^VQRpcS%4mN4ljc@mN29xH$l#(_ zHub51NpPR3CrMBZV(#Di<|*cZ5NMZx1YOr`K`7vp*q8OqPmGekzm%mxOXmnnuqx1w zkxm05k>R^zPY41@Q11GAG5K!@91yyL(4y-{Ab%Mh!0Mu*6#V?C9ZQzRAGQ8PA2jnu zg|XRocek=7z&7s{s?hwZ8k(KVB>B>**hzWo3zt5eh6MDF^VC@UTC!wJvzs4aWU-`| zXKd{DtcRHkVuK|Y|6=-WLFJ+B`D(2x-0dkrfdM;;(+frKYM>}NA6taZ1M__V9r6Fi zmPK%%E{B~07_THc54Av7@?}%gjkmx~J3l+exGnJZtdZjjLe(#!=i32HP^0$OaChVd z-XDWhYJj^D%y$>Od6blYcQ_g&VtoL08bd6$1oFJkDz2G1&oSC^3B)Xq6k$6uv&JMh z-x_h(X6yp^QLfIab#8@#>JqCi?*ETbTha_d5W#BzUw0k6YlqSl$^kL3_iqZyJfTux zV7NojR0Ld`NKZlBiS;4k-Pd}43$ zYuc_lDrtpB1(z$BQoU2g6!co5a!}ehWzr0ELId|@74Aig4bvjl5wYr=9z^AY2qG%1 z-9$^!R2NMz1kO=`_&64?q1f|IqxE@h1; zkOMH-PZ_>&#>#2bIB(m2nE+Y%0d1*)BhS?tCY=F#{au}XJV(F})@m!2sJ23rXTub| zGeC^D)d1+i#-X=uphh-Y#j5Z#QFSV(nak^ioltB~iv7cmA<#bPN>Ek_+CKwGiC-h* zoK@$f&OrqW0<~2Xvgrz$?KUo+nqYntZ2qVR$JFA%e0P}_?G~(>2@yC}z*H3c9OdQzXXBHGps+Thb?|1TaHz`{g3b~K908T@6 z89PxTdsm9yC~NMq`v*vgsqRa~3GG4#t*ta@33yb2Km>w^SgLasoA@ulp{*mgFmJ}m z7E(`WQPClVHm|jepsCuUTx21D!ijx1$m+8OhY8C+G6n%~aH@hyEyQH2>OxDqIynn! zd&fiiP@pA+3RByvhS?8*;{T`TL`uYDDjcV-eSf^J1k@mkf#3v+DR#z&|IP!UI8d>` zCaXfzQ5~i&#UKROYABs=|noI3_rXbCtoT!+u8{QA@e_T`J_bR93To}2F>|( z)Gz0rc4_vZ=oazEVfX>at}iW!c3@xE_MQ~*<&~BFto(j1PyICw(#crowwo&jW*?9@ zMPEp=eK0ou09wK^f&d)(#$5rmtu1E8_;{f#TDK3iR)mxB`DGJ^R*4byOiNCVAlFarlhE<6f9Z?)ESg}Boqn7E#mM8Ia)=qh<237 zemHHt5WYS?QbMB&9NqC$-KFRj0YYiHd`4)79Z_;6?-hM%J-;l~R2gLMK%C?pScvE) z&{9pwd=0CrV_S%;23jUiTC8dI5nItQG*1xRTwx^E*{81#h5vEha&RYZqjYuG*4In1 zk10Xo7JlAv+b$5IYxsYsD#GhlthzC6CP+WpPPB>DtcOz{4TIC|2S{kDfaZIVb(%u{ zSkeHmfZS843VZc8*KRwbbM7BNsn19>)w+1AU3EEwAkH@ZXDp%<)6xk>P?~LE@@f!4 zDbE2el>Di{g(VO?^}Esh28bj zJueQ0@A^Q3oE3wL$vxZlIPE$rEMYKtJU2w)C2a7;zA@SR3*Jc97(piK$%K2n_?lF` z(zDG5Sc;XWfS_D;e+^O%O8E~^mj@qx^<$$q0a#tI^ZnpbgG__%QY%)ffRk2e_MWsTVM5x~L@R=O7Ll7+(IFU2 zwswaXJaz#AtA=1tz~X zz%kYFodp^b0kSF?X(Sl6fTnU1wxe9D4zXQ52?JR;{o<|6*pBVEq8BD^!bwT> zVa47-v+u|w^12+$qjfQKjKeNQ(?}tvHvm9*C6VrhvbIAD$Ds1vVW$w=;YDh)V-2!@ z_u{j#`=oCS-SH;T+`Z8tG1o_z{g*CZf)Q7;MzFA!b|hovV%ZJ(Qma9o77V8OUi1K8 znj%{By*IGle>ckB7-A~-)&#<<&tF_>8|O`D2Dse4>nR2J+vNucMk?fhBkIdX(0_>v zQ^oOM^@^a@{=H@7tG}0~sDQ%DxaZ(7O9kfBo|JD`SN(sI3p23-n2TH<%NY_Taw)JA#HJRV(~$WakG&hK-lDTRMJH)o&i9xL%k{#i0QU&e?>h7- z#nL*b_jhQW#%>b*DEJ!=Fg2lj<=`=af<-=^b9F9pzx9sA*E7~4b);u1E`HWCW5!lzpsc*4OW zo_#Lm2OJa;Fr~$4gO~ZgsktIcvZiP%!1PhhyC%ptgUqP|ujNbv#6B5})5m^I)C2M0 zV7nr1vT&R5LML}7BM<=UNPpn4KzJUYb78uD16NqsPw^Gn zi@B*f8`5g>$}~Vh92{tl5RTC1I>U&bFN>wM?1ESP0amU(egkKsO{QW8GdU)0?&+Y5 zR|CmDAiZC~$f!>m zpFqSlXG`t2e5RK$*4xhov6P!p<7De4s=&_Mx+hnvp0=wogtO&4d>nT3MHd zVqi?R{Q;p29(YJyd!jx2^R+Wt<(Mwmy8t;3R~8<|Ik!lASSy)M_FLsWEVF$jN0tRq zV--Hf`hVG>5@B%YSdr(&Vv&DQ^h*652gdJX$5}Hsekc>89ZUssmxmH2kW1xi_mpoX zfG0;T-@B4KlH#cI$P?+b66nv02=9G$S^+z`Wcu0XzA|GuU$86m%Ggz2+0=u)b27d8 ziD=|tz0>bOjN~-$;Elb$;JTkHm14b7_!m6w&9YaakLB}~JZ{2o=u9`NVAAUF?~GeYEstc zNHTEnWBq(?*n0Vh)hB7kzX|oA(M9B&$yj4O%|IHu)QKtQT9|e?OgKzPRf2K=2jqsT z`!5}X3gHZ0h|9a8XI|zwjwl{9E!`fzcYyg@tqj=4_kX;5+pmq!;+IU|#)|$r6WLek zdR;go>;OdmKF)#Lhm~;TJicyLQB(Vt{F4wxdA`oMUMCTozZvn%#2OJyrgF?>b3Z8^ z_<-u~X_bZ3-RLj+A4#7ynt*%7nf|Puz2L8PlCPwz(?Eo5&!)Xj-q%=Qg={GvTI$fW zIbHcYZUDbhLPN^}pza|)Se}{tp{v0Nk}cTv>jU^e*RXruQwm0Z(~ZzG;&+|eUu%3n z86Hz9HXUIA`lm5IXYEYS99~v=?r*=9ig&)AdK=X?Ub$P<-npUHOnu^#SEo9sA;lC@= zg)c0jpK4LVIMb@ZB1@92e zG(|dEb0~qlRPHo#;QaWv)%w5m$?g^XiZ8((7Fit0PP0Q7Zi>3!csh zI{yPx4Cm08OJy>PC(mbB!w-q(dRF)U;y7_P4x79}&>rwZ$evS4V?}QJ9X2rH(@!(} z1z&oUj7wjBTf0m)LM0^ZU5-4P`Q^mSosDXk1vl{U=EFZx(iJ3=xns8lKSar~#I z>DKTYw~fLM@rQNFn<8JD$eW+H^bV9%@q4!DUAu8e)te9zoQNdm%L>;yw zWYtt6BP7MzJ)6elYiP_q@Aj?|XQhSa42xymv6DTO{W>9ufNrJh8s_t+-|_EjoWKE$ zLpwj#b~T1RpG(w}7@8W6!fy&)oT&IDmiJkEs9Doi0yr@HAq4wuC7+*H_A!N7XFXUH zsND>(ZL?xW-7iE(i_vTdHHY6y9QVX4D}B^SnMiU<=RY=#cpL2=&7E$DEI3Y07yAX8 z+feLlI#Vh_&VO~RAPd-+-e>N}yy74sMTCe&^P_2!8;~Jv2+Cs@QuQWuTwlMjnr|f+ zkx++bl0Do+c!xD&e5k=JMG1m7;dK;r?JTz{CG>_#-@-1%n;ab=ii9aA5xMO#lkv=; z{O`qqw@J-A7wV$JAkxo=A<3;k82m4L+c|tkuWdJP`QUo5cXzttjC7} zMNfSufw==oSrdogle%DxuOh07rk@=ccXYxWP>SoB2(GU=e$6k#vgx$Nzi-wn{%V!c zpDYk7#=$%wM)SjFDm1RwNhogNSuiu)^J6ATIU$9y#wQcjmMhpHE(?NCxThZa4es?g z-7@VSYBHUjQwURG)uPq<@iGe@}hYEYTS|cIGMlrJvBzd#v9Yg3$+o-FS^%u}y^zCWAzQ zDAqJF(d-^)R!x^iZ@372leTvhK@6)Ja3fHWiB1+KjyD_N^46*e;QqQY(~JD+KY&yp zFF(bRbLJfMw;hP#_HUvk#bEW|CZ9a2@%d>Xk)?*}qA(mVRJ^L}YO>gVmd-F&Gw6j6n>4uGvxxj}i_Uq16p zpYWoI;=DSA?K1Ev=mwBjjb?-b642H;CQKj zgN?Z1UjArEl`BjlG^oDw6pbIJv49fKx}If)GwUBR{AMDpe<67cPxDAvqqDE!o64V* z^AwrH5f_p2Lpi%Q?{%~4sPcPRQRCgQuk`+ z_i=o`@B`b2f67rpZ#*fN5}L1Rc5Q%(X0a1EH`XcleTSLPlyZcH2BDc+hY({9 z7QJXsF-ViAtJLjWUBtH4_{=?RymmIOyb;$AgfWW^zW+XUH{I|zffe2x=bBYs)MV2~ zqG<`I26v%5`AR1)I<4_uqb6&r4VPRY{Vf(xl~l)0znMwaUC_eBYY06WzQzte?V9%9 z1g`0isb^n1_w-GB_ON>A4h^5Q>$mMraXPgSxz zgw{W7+S%S)w;o-QpWKu(I`%~P`j#Lxgr$P}Ov()bu|+k!#^*X6`GiSOI($h!v7+0_ zp-UTF36gxn#I*a|_W2=@_+zBIGegc|H8ooDN`)Vvz(XKhq%!KH{(665fXeUd5i3S? z{HVBN>512e7GsHRJuU$lGS@u6ZXpmq3M>}(R*1H{QsIY+}euTJNwGu-*S9S=8Q-QC=O6}qIVpY9`d;a?yMdg zD4)VF=;wVe9XIGQ{1$h;E2;T#kZ z@&`Tt;;icKfE64^_mvJh;3@pu-^9Hkki7{yq(5CO)sTE=kZNL>XFR8QKGN#;ZB67; zLhW)LNh^wpv}lyV?`GL1K8txK-2Zc9+tDYiXqUdY+S*@>?JO6(a9_Q@i)NpQJ+(y5 z@DP>@yHQX%AkKYVkovi=bRhM#X`lt$yN;x(tRiq7fRG&WEM^@CZfmFRRKskO2Fp}B z5zkb>_TUMTok4B2af+jf=|)6(xX!<$55&ZHfDS0Aeg9$~!J}1o6z1rT=`-tUY?Vd3 z7bcI~&v>;hmL*@{7t=ZAD+c2a&hr?OR-mso70H<~VHMWLiv|VLLE#(0Ex!)2yL8pb z5kTa+?}*!TE6iKoCZ{JGuRkf%?$pnL@_v^ZoQQ_ye53~He5g_;;Pcv2^6$vGeOh0D zJttm_|1k$+_yLqrNwvpv85GJ?k90HiT7Zuy#N|Gnp-1}mDDdw046Upr4g?0~^g(9i zgj?5oMK{qgOA0KT!o_7mTKuC=Kg`d*`$!@ShuY|$!C!-#rknjU?4Qb-vG3xxmLdHm z&p(~jMFh~=Abb6`?RSd`?}*r*58@;2!+tXE&^&)wyMj}r=?l$jL#tAf$cuZ9g71Q= zq(8pXSrpb0kDuLiHa+@T``D(WzzPJUv52_GKf%icw}nkL=nB=-;V^~w{I+JvmY3=v zdZc&}X6-+BDobmT@4fHsj5q%^2xC>;cA-V|BIeO zjmVeh4+Q)@`9ffRro%>UAu8@djfZvU@tX{ky zfA{_g*$%iAkovN?Orn)T{=d9Z|HO9U=Ou)yP*uI;{2FI44UheA;0+@3R;1w1mJok> z%QU(oVv(_9*y|rlFGU{XiDBN1z44z>>Aa;ncN6a_Poyy4U`>`!-O}tj*&Z zY6bk3m1+6qc9DnGO+NI`=f+M|jDv{!_;^Z(QOJt|kHT2yodf5Iqz7q3A3fwp?~=q_ z6!h`e4}Zvr23>hH?s1)6a`Hbp2e#&5~^_IVc{)#(tC+7IlM_c8GktH%gD-%JcuGhEl z?Os;}cFtQ`U02$ox#UgL7&qUCX0JcMMjV75jJUfa{)$_s)1=oNF5=%Y<@)V!Y*Oov zxBs1;`r4B#Pmay>S5>puDwRK%zYTJTTj+l}X3PYaH7z3vHzpgU-&~d5=Qx*7F_o{c zl)Gxw@#j>@<%%zo zL`}va$M}SZOem4GwIMC1$!K2Yg!8j#z zFfrq_Om9SPq_;3Rr%2qIzEsg8dhBZV8Hp~%<1)g}=0`yQ=Z^@_PuEB_(Nc$&>vB#G zJgVCiGz_%CtkS9~dFo3oW&@rzjju-QXuX^tHMhZ z$2c2o#5_m-pf6-U1RczdZ#06aw#cJWd|kw?J*>JJ;#S;VoV6bixYZ8DK3K`;?W(Im z%$S1zs*vs%07-PIp#KYm07zxS$t)MoB!^LAIMg6kbI=g6yYtsS zH%jbI?@q>ehHKW+-#x>>yCOL94lDdWK>CJM7lnRqISmznfMgsNuj|*VxeIGUyY_67YJ@<=p`!Pc5uGSh;d1+2_Jl^+{ z^XD;rqQIex%RK!8MbK-u^m2dV;(V@%r+$QR=h->?O^NpPe(L*T!7(%iL%BUOIfT?P z<93)B=B6y3V6Gn9hq}i?ezK0Y!9rYgGULq5j+niA@~)NtfS`GQG3bd5yB2IRHGf)g zn#S>{SGeb08~}!+Z}w#jHN&Lch=*?;3#-YR=8H9QiOc#!Q4|Qh{@(VKc~<6?<~(D|UX34Pe;^wAA=?gRQ%z3& zh(yDz1D!o6WQYJ403FO)dhUC9)=Nb`WXa8y;ysBHt9?r3k(bnXy-nt)9qWfD%(k+S zcx7_EbIQ&I<`3jj$}0qLJ@6aOdQNk?UnEb}DPe1?$adt7`<=m0@uIno&Duk25{=A* zVuPhng|APmzE1M9+CI2E0Y9BL%%Q;lfGc>noUsni&3ArXZRRq2_g?)Im+nJA3j123 zcj?bIJ84y?JIs~RcjL&gd^%bR=zo9l+!9^%+nO^AG*P;XU%pe!u>HU04nSE7EObpyN`)QQ42Cn$| z+}B;_*mx;4XCtB<%4zU^@aal87B1X|w1k*Mb}FCwzV(ow32liAVi7$-XG?L=J&?{! znF~kBC;MF<(q+kG%Fh-s@$&Jz4v>AF|KsS~ z&ZWB)HKn@6h8*TJRJt`AMX82$JB&_ra!44;=wPCQ95Rhqa-Q?Jf1iGT^6=PWuIu_- zpZDkee!ZSAU5${ue+Hr9qHH?**0}^KnKd)J%cm3}Nan5k*s- z5`#xZa)b-D5dW1!O@*M5YR*Zihl#dqwnW`EO2j|^H*Pgj;jF>~SPsbKmE5^61_=~o zD{A498{K@jh6k9%C3i&!{<~Jfn|*Kh%0@;Hqs&$?bPo-{r2>;PvzbM@Cp@ERHSCSW znN^-NLdJ}&$Z&ILr7+|u8vYH;=H@Qv0gj~f_4#5HsSCduDlBa@l z#N#+b2d~H^BaHou8sZnE8m3^zRm;zt;6btZp%QC<^@##K1e5FkRAg^tDku{Lg$rG;q^C!)`E(sd0BnKol;opS5!)Sw=S=b7 z+Ce)|@pFStH}xU={tg!EoO5odO|V%7K4tKrwg1zhU=vHA{H5YXpCT_CkY;{IjUH$k zb9HL9!}DefX=YhMgNi}}Z5?)>FH&B~Q?7vjn~|8VBGL3my`B`7<)77stR#t_R1YU) zmyMb1KLe-d#-Su#*$(fTn|r$faU>vJWx+dO1z%`2A6u)eJoZh*2SUGy_s=j4rX?yf zZwLKLR++_4U&-{S!$i831(3Y*l<67I!JAJ_USbo{*zx67xuX~(p3VQnKwXNt_=5>w zdeK*XY6#BGACb)zE%&9LKE!}^OS>N#{~n+YT5H*48gu>A3jATRQJItiR5iWmnI`(m zL4(QD@l)J2WOcvuHr_gbrrRsz6~>nR2Sq1Jz`ur3G|#D=@_yTRtZPJahm@UZ@b=yn z`!8=Lyv3i)4S#7q{<72;sTcXK1J_tuV>}vpBHuPTMb*TLMV;Do=Px_h`m>%4`qza! z7DOc&vETkbC?RATXpfF(D@1L4Nrh)P+)qw!Lew2SM>YY#c$J~D0_6L@+(>%3?{)1= zd^J&5t#ceqwHI#XJbLl0Z*W$cO80z)(qzPd!OwjYQ*UJKtN8E@Du3A-sM1?N_*KPJ zVVAj<*f0nmQV7KL=jun<2}k#&p*2hd2+mkuA+&1@?kHzfL1LfWXy9aPE2JAopumG!8lPXP7o$ZTTI)1e=??o_Mp)E5 z{#3~ghCgfaiX^u-uiwMj;u)kmHf+WPayB0j*FCtf_jJ_|xr6U!=jL<6U+sA=k9t|A z`Ea=VNXUYH4@!KocO{gJ1xQ&Q!JV^GIiFmU=3%ZxTSBYn#n5A|NHuLcY<|fZ<$=HqO!M5S; z^8D2t6A6Z9wuc3Ufw1`hpyNARs)KtU+J`Ooc`89l4sR{DqE=Ze?^E{pH64UYse)!Xl?Bw-Nog&;(*^K{BEWhMNKh|sEvJcfHiP&j2xf& z(>9g`*^Cz%)|1>V{aLfK!bi})N&$V&sb1|9FeEKRU~aTY%FiDj);UKUXXk#_(GnHw zA@T+RJv`S$1>{Lm6J3TK(VL?LVzJkvLdlhFj+n6Sy7t>QDuP2xE_adlL%I;xu!XE% zxa-MQE_JA@?`Rl|a~C~KZ_mlge0VitS@KQYC2ZMHfutZKw<6jSjs~`c%U^n?3;bEK zW-__B;l?w(ksg9)n+EL~U$Da)3i-ed!2fP*0;q!Ua&pNV8mbM1z5v8?h_iNvn}Kye zMXv#T5#Un&mHbI)fo}vZyGV-!=lfPrR7PF((BD~((1li_v|GO7{T?Y!s=3-Lr69Lf z4~`YAC5*IZWK#78yJ%?E3V@uH+M=?1P|HB5 zdE&5Do5Ne5Cm0P-b6%`~hk$Fgj)HK7W*3vY?u6bJNEc%OH*R2u*nE=t`p@9_t~{15 z1>TiQ!Bbh20-_uMFtYyXI+hOd<5ON3p%-*?jwJQg8Qb`Gcd~HFKnBNR6+xJ|b0gY{ zNOf0oTuHaKtH2)Nk{aCc$~?}n?p2S_y`9mlSa{}XoQZX@7&op4qtzc3qQ1h$MTS)tEmnK6V|qT_Vmhn?N$fy zp=(VeuDEJ3)(}4^nj+OMCC|tE^*dJ6Oo@A^cYb1c`cI@yV@}#h&XSjlVQ$$fn=4=< zG$xL0bS>?nio(JATRj=lmHkAP@=oLv+8}Goa-WJ`99Pw=f`*OASfNvpgLYYzX^RQBlO05i$A&UhhCh8~+?9y8F@Xul zZ?+J(DbriSMB=kB3hB@Zr-322wW#YiVjPPhA*%dR|3j{iLQjg@^y9}nS zD99bEGwdS52lb@i@7xynEWMWG^77oyryCtvi2E>{|8?Ob%eiWFM2Kr(t_dyF47JSd zoRd0IPQBL1VE1Jik%r2oYydOfpc%N$lrhCbkxkCRF8grV^YZFAqtHmqTIE$EQ!AQs z|A|U`$y`3#16VfwXL&00%ItWtNYv(s`D~GsK|c47(!4>x6pXp}y#^d8Kb;ZoiqTqy6TTy`Wu~ z|KOy<2NsK-dg!-9?QhUMg8Z$+T3Rh5WPj9`iOr$~`F*!-#Ty;9@%KASY^dFQ{w_!e zFCGZzou>J4WunuXV~+1GO87PQ-WUAcT;kzCVw_VK2LFUJIoC~}Gne$0_S+3s*6Sq4 zq#N22Y>j4{2QnxM5}jLo(7OQok8GYoA;M*-t>Yi8`ddf5(dfMDxut9=5Zb^BZ~Z%c zS=ycvKYii2cyW@$e`HG&>p}TrtneawZoy=00&kR}{Mi~dwYW~clG%2|$S`_Fh|k)& zgeewHG7@H_G!+O|fkn7AFxTaD|I@4}!5R)J`Q(BR$Dn`+h-?JueMPWy3}In6UMz(* zui($`4+{Gj6W|$GX5}3aLw#YSdvSrWPKHZjuKT+f?I{6IrGcvbm{1WJX!9y!(Y;{( z#aKNgEzZHMQEP+b%=f-VrjszFc;q{CJ;{KmL|*`r;!n7-1qw8JN3JD9)yDHREi_7z z$`4xfWV(-$1PIndLL<0l>6Wt5T&|~~u9>=T3{0AOXu&*7HU#94mtb54<%FZq`m-l< zO=7}rI`8>p++dkIHJRmR)*0$mB+y+vs}BUiAq56l5<;sZ^z?++9d}~_$`s@JC=R8X zABEcpEj?EFcX_S1ZZ(Zr1wN727{U-9o#MpY%qGPmJ7Ez~I&2&g|0~l4Y_YD%YsLQhqSo5aEw&{0|C9k1`u@+P7gexp(@&ZSUMW1kU%&%;LlR` zo%;Z784Js0hW|EtdtXIYjKsg5Es__6350qT;&Ud1U+S324xq8E4SJc(rI{tZ+3nQh zJpDW7j||PgjgV--ba3{h9BM_(FS*0ZXEAgjl%Z@CwmerLA-=GtG^ri%Hh1%Y3xa{f zT;eE2P5W?n#U<&OQNAupIV^9b#(8~FTj;AhSCemUGqIq`%_yt$URs)9Q%39+#1{o! z>ikD=_@FhabE)pKu9#6g1e{K_Cw|`~8r(Qg_cIz!0}iBSaHmp+Sg?*?=jb<@+M+;Q z*)Z(b)2B)Bb?gK}_m^~|3-{*hMg21Vx_3wxoU>9_Xm-B@u5WIIQi4nZ#)3u#L;3)~ zIfb&gh$tHeOS33bry|sHF}z?jF;N5uBHUfnez;AwTEVsIo; z@Z(OWC&fTlHtMQ9K)omJ0Ki|Z_+X}yHH1>vZ0|EOsXrv`o|-Gr9StTVHt(uD)JWa9 zUJnO~@lC6f1*gfR1-Eh|#!#fv%Rn}eg)0AWjrRb0(LNb3Q7}O7=DNeK7(3`yxYjKP zc?UjNYZWN%%C)EHT392O=pS~w;f>IqD7T=c1ZQaP^QXyztxN|+Y6+;n+J~%Kh8^I1 zH|M`|9eQ;bOEKyp=aqXnV?f{DG4Tl5LU=pq>Z)v|UbwGs#C$qSA1-xmA?a}5M@%}> zTs4hmldGUx60B>*2(D zxw(KdFF1~pn$2fk+$8 z9!#F^N;ssESjK|4j4yZz6q$W*1i&X3Owyi_pR?;P9}3h1kW^UX7O5rj%IJYA6(kYC z(vV6Ij+n3pwul#xaqoyR02E#fv9 zTRAS2MmB7+MB*Igy=o_W5McZ65aIlwt?3@9>A$c+T7PA!O&#pytU z?K8TSsK3)Kp-@MwOn;1#46-m(e>-RO#B)^%6;MQru*NFPV#h!+8KD?wlVfbXLo~*c zA$YvA#D%)?o9HGW=Rc9dk|@#zIA%maKa;Hd9r1#Eh)ooqNqXavYsGHJZ46$Q(JgiQ zWiyU{gckhjg(*LS{aSBDZ(zIC>?$X^t81eR`eW9b4|H7H@kZ62-tiSMrCaKSy^=>; zJ{{V2tsAp}Ch9@Y4i#B>5#$buT+m3tMzF3E*!OLn&-JK|fhbkaG(m*5Sd}vf5b^kT z;2o@*-U+v!5thz-nkgC3T01(}bw@KoZ)=Zmrsvx_7uX6{&|+jj5YcE8A)-V4FsK@27V3av)vg?6l2kg^Ik;{YbJG6-+Lpm34y=$0@?`o?;$ohRP5?` zfNj*)r`gANU!|>5d6$@^?o1j|W6co7U`;TwZzy7aDlcDga*7KmVn&^kVCAT0c=GtD z>$mI5a4M6&;11Vtwf8~maXU0a|B}GyZS1)Fr&8^ElB_1b+{)D^}_0fZqC8$&!KhP_?R|W@^wpUo?rVNg^YB<4KDE7UO&b{0tPde zK20MR!|d%ECaWe)@mW?|S*TYlIa^IOXwr_*^ZLOV zLp3kO-erh|35R#xTS^9D7`PO2iBoJ6BT{HLYzw2TZY4CSbkFGB6nTd;=2+Sy_g#tcs4`4-Psxw(cikU zmhOkjGq@{Q>3>iR_KC@d#@A=>C%K%rxrntCPYxSppAg>H zlB65E-RMCsVEFiiMI8mz!Cg zf|mASJQs)3U&+J~P3Iz*JdNp4w_pMV@iu>ObC?w5qjLSLB*~m<;h>{sKp1CaRO)ys zWWjEz!ZpVxiMgJ-<>)qiP#8zpo)v%crtn=ZWrgCkm!9&AuPAH5c;9W=%XWIp?(}P5 zVhZjj&c)G1=M`?SugNFBCyL6@P2>`X5*>R4yyH)1f%>g6*{me>_^Tw?EWE8f<7z!V zN`{RBA{JlFQwA*g&kMyL9@QXW+u<`F(E7dRs6RzOV!LtPTcy+LYpoe54`xd~jk$-~ zQ+U*u?$8HlDoq{n%$L$!_MQi0I=Xlbw)Y8Ike!`R&T zL)_V2|74ujH1F>JZf4lj@#{Q0C3Nz<#m7-(HK1(ajCTCE@gebFN${%R9^}XV&Q~Ao zFQ#K#P2+Q-9xGM7;`mLv$K-um^7ClXm0)YfwdTVn&mp>G!1ZHzlSFMLO71K-*Mf|7 zyw*`Z&ec)m>+jS5wMnb-f60I)E)cOarm1K2W+f}#Y6wB#2OlG@0`WeF-MO*GYhsz z`q^o{cavGmuzi9^dh|=A!m+sDz4R*{?7vylcdT5HYZ**}koqQk(RFR($&kFwWenDw zX2$jn7OOFB>0(rl!&_)Wa+UGH;Hx;Tke88X>=KhjN6W68b+zaz=!a}mEy2; zM;YcK0*y;5v6uWjwaQ+{oCVLLkF&{JDY}GlGF^n7p63jDtizdCZX*f(>p16YyGd}~ zQa5O~CbjsEiFF9FrTUV@i)-1XYQv?ugrmb^LJ)itR}SKDIfBL)#BmV+Z$F#TbQJE zYE&-w&-{iSo=e@7PR}BG5-8efmlr6A96{cRzM(?Dzi>xZTC2{`;{9qkJhXJdyREz6 z{sY5KupP8C1MzZ0g-j<#=kJ+wt-aYo>rm2AAHPt~HLUP+tW|XWe5lUQ=`=8?g~rJ$ z1|3rQ6W{90>jbp>aT61gr-O2}-`c3lyFY9X+CIDBUM@SyM$qiAZb5WWzwfaJZ#YJ7 zqMMyo@rdqJ?^n(D|E*nH`)!kUH;}82bm%5nd;3^yw`zD;ZH_boxLA@*bbd>iqU#=f zW@uDv7%TqY`|-1XXDHn3ZbGjJ`Y$h z6V7=Ans9Ny)?=o0P&>4t1x8B?2;A-sRZQV=-PGg>t>jm=?ttZwzK`n0{h;X-A%gu;SYFzb-Tef?&-r zwISESpIRqGp4H{>o#+08z6G?bfBm5FghdyN^I9_Vh%mC8lW}Fm*w!xONJ~(s?a2B_ zX>+L~aMmvwmcTjX@0mkO*Ps0d5l&nPr{y{g9&)6zxjuzaMF89OwD5;UhSorb`i0kt z3+w#!yu#zQx#g@N`wtJTyrhvS`Wt3SuU0LgI0kb^_t@}|Uo+&|_}X;b?Y~rJ2YgDS zCdSIzD=vQjHs`5!@;_+jAFgfWF~OMt0o!`Y(mxzO^dde<4xOq~8m$f1TaVW3&@L5S zd$oQe8?u{MPniB*yS$ux&7$6s>NTBEsB8NVT)s6RfYbON)TIcURG6o3Jf5#hZw~Ei z{_*P6;htQ-4=>6b;@zBQMP2LY^NGcdHA=sw88cf~w0>l(RGx4Y$bBBgphK9`Pw*O} zc}kd7!FE=4aT`jDoYVgvcKgTU=KQ%wMsT&iZ>)^@?4B0YZ(d$*G(u0)YHxe^ImS}l zZ2PZN!iIkD5O9LAZjqwZOz# z9{!|%K&8iN099#Fp~sUwF4jJ5fVwo9Ru@iZ(Ob9f`FKp>FU?D>{aKjBgqa6BiO2iG z)hl})KqqDN*cwvMMx89$I{44cj5zX0)E`alvCwuG{97ro%CbLqK6rn4`-8VixWBOU zj>1s$%cnB@=G6gZ9RZlkrBC&Lce(!cqzoBAm>o)$83sjPjNGj@)53Wd&^>G>kZI36 z`1otB#!?IIS0x%e)vAxnpJolIrs%T25B)O!ajfBeMw5b=n%E+E{OsoYs=qfsyh?p} zYcA;^GZ2n|ls=rTx=wtR_cC8GSt?kFdvNpYw59O%)k{>eonQRt;dSq{ehHp5+3oM1 zW+aYw@6uZ5)!4bx8ncNaQlckChJBS4b8f9Zv%8;=HC|DKs5!IkSyzV9$?K*(8X8qK zCv>ifpSHue+;yU@0*2fxd(Ulue*J&YLiII`xxMOcg*L1C&$C~B{NFYOP=GJceNJt) z)(EjVD(+87;H`{$EX5MIR70);*ybz-k6f;KSw9_Eijh3BL~i@nekd?x#6yZ&EC{_i z@dyW@S7vlwequW}*3cIY`@8W^?s)w1>!z59h*siIVVIx)>I>^{DpVfi|5C4badF4m z?+MSXVrx%)Oze~_`e^NzU(>1oh@E1o$S<$yY4@Dl7d~JLnqS!cd-9=-&t+!LZ@vy< zB*~+xPcCR&cLcUZQEJ=!uIS80O{X=iEoOpxU8=Qr`LpO?Hws;dzW@6%s<+y~?L4*T zs@}Ff^YKi0-xI9W;WJm#K78_AbD{Hs!IhPb-TV;Y#KVQG!}z<~tBE!e{@{_F^dZu9 zjWSN`r2B)10c%Z;1nOC-Ncb}{-fEwJwf{P-@eHwD+A%3BxzMu5oTWe%&3oIeM4W8Z z49E4Q6uP*&o-(v~d8 zt_btcPQ$RzZoyo34*lqjrc&yx=;dk}scHSxGU9v->lDF2tx}#`0T?~JRlBiHn_S9{ z^qpHU>zowMCtMEu!ni#R_=2wA`{~W3(a}EHqhrO_M}GR-Ycf^Pi}>j`0Uy-AnP(kZ zu#Aw5?ER#s9Iy>%lB#|Y6EG|C{q)3cNwj_aO`Vj-ZXuxAcY3RJV&3(tMfGXfW6r^9 z)WGirrdS+Xn>){2edWty*RBc;Q+qd8!i~|MN%xw6^*`RU%Q~6%O2HDdqE&kOK_r00&epR!a z{7<0&eh;P`(B#7nh$B8IFICTtZA`Dyp$K1?;4f|fl$#B9d9Ok6+`9|o4eVt6Kk(Gf ziYeUj8~7Ye|Di!q!k(x{$9;ZJWnc2>57ly}^0bBhZw@ktF1-Huz9A^=MHXl7s&u@g zFk)@@qXs*R_geY-lWpRQZ>YzDreEc!Wdutes|-#2e7X8sb(AC~CYC#ZnM{gde1_W} zfBy7{!!9${b#YN+(--kF;mGXagM^&zy$+ccQ$&(MB3n}Sprb15;}y!;m6P49)Xy(O z-`sVFf`3?X0jtw}6?%R7)U~Li1OMoGwVjR*emx7uCiBpf^g6#iR);n^A0{rF?XSxn`)kv+ zAkUYkh0g}ZT8mqD*U6+AIZ^%~`)<&)o?{Ay>=Xag+K*(Ur`TN)HJ)BhYpDk*z5g}6Fj`GugDN=u# zrTeflIuu?;g>G`ZbC6G>xEn9zxE{l>zMj0tFM8bm&&Jh*=^h+XOa1BvS!wM2#Vu;p z7KjhVl9$uWt@W~JFNaSUP)r1D%dor?Ia|Br5L4F)C5vn3od)KJH19L)xx;&Bn=&#J zE7SP=_ypYN%bPTeEeF<^)bgmxFUe<1Lf_Lq02>m=kAGgUZlBJ(c$+aoH-PsJTI`L2 zTTiCdJdIPI_hwc7bjyanWk&zF?02tOYIp2{T)F0|7>7M*oKLSov>zG<}KYQqU_u1If9r%W5#mPLrt@EU< z_SA`hN%!y5z`2rNi;zcNGAWhq98PWxH!iN^kGVSKL)> zs!8LsliN_AQxx{=;>~EQaDJG_5Xf};gQr~;8<>CY!?k^#^FgDMrJ9(@QQ2di*XUy+ zQ@cx{^>$dO$*f`uGnqQF{noOMX|?mZx$M0uzUsG%g$T9@qA>K1Xncq7&heu?ms??n zgJM^>VclI-Mq}Z6rYcwW^@LKfM4?{I#SKB82O-7Ne>oS6RNd$@t@llxht9aKA4yzc z_;?k-cW1i0nC`3G_|zn&hyXfNq(=s2A0tNVBHp{*vmO9aIEL46UL^APE&p#nV~kqW zvG*<9dMpV`m3vUAcH-j2lJL)IjgSA*?xrFqggqciPV4PoaXzHeYB)rX5MWq_A>sLi z&ED+%$3A%!#JpE}%X&T9DP?aQqRg)_JRaK~-y4bUT$;<#`6B{M`QUmXwYdE6K`#j@~+iNZc z@s_1~;;N_X1*3lUN58!Z*&qx-((H-u_wy4+*b@F@2>ak>&57fi{#Ld4R6p?_bY)i> zbYK>pZ+2j9zVo%|Ot+VXS6iU#biokI$3+i95xjn%)-D2JdsgiH_E&QTF*&NnjiR@O zgv%aZZVmRfsO1ttATU&gq|E37R+kb zq>(&lDE%TD`}fCq96d7DGX9s|f6zT2uF)7nRpyuSAGCc?EPY9=n?2ut+pM#BzCQ06 z#c{#Cbj3ES^yWz&cS*@Mw;y4Cp0R#94+H#;CEWU!eiJR=XWIjB`1s zO0;;G{@de;{K@>+hAu19Urw9k-AA4>!238sRaTY8=ts&R~O%K+#%$yZO4Mo&$(0uhe?YAo+j1X+wv&+7vnke2W%%UpL^4!a@cKN zbseX@ig0Y7wBTH<02xZ}q|1sjngLyHzwk0M*oEtNe+N z{vJ-NC4+jW#0WDDz9Mnl6`$e?8xb;668x>aQ%TD<|1vl0UzicvrFsA-3As`Wr|n>y zrL8S(qq38j8@Y2clBtK~+SV(39y@=NNm;2S)sGP;Y%L*wkKA0@_z6_+M;d;>k#2u1j#)l{!}J}EsgjdVAYA8#_0C{CFe!cvl-pUI3M%9YR}zw?Ao z2>?&AkOI5K@o4)L2%U6rt7a4Cy)TI`jCS3a7%C^9g;noK>0=VU@@# z(YUHXvKT(#E@5yn*P)@#Hbv*(dnAK!K2acB$$X7=nGnPlgxAlN^gi1(h2WnejJPzU z^);YY|4*nl!CND69Yit~Bj7J~J#PHUnOw;noWty(%VvuPT_Y8GAgJGwcTPECXwZsb zZl!+yJ9Vm;ZW%ZImSHYT$9cU+PV z-Ni=Bt-MV5gJ94%D3MZBUTf)J#L|b)b(ek9&(wx{Qsmzz)qkT@$ZGcIPTN5Luv zynoH7*|cL_oLdn+W8w_Y9jRe#!JeWSQ4iF{83Il0qq$Z) zkbNgNQnoC8HwtD^7H@fC@j6!CQPf8R5=6aY$36Y*Ii_90T9+|8E|pSNO=V246WXTj zK5(@Gvf0b!Oz@dut-wf?O01^}wS}%~&@P;vhsY&ddlT2jU13V4mAnYE@2#4vpZ#%n zr2F11kT97Bj$bw=N|MgP{k`>c17iGTZ+72>Gvnt+1SHMJDu|~y7J>5nke*cyLVGkd z7+UZ$2)PHm@y7N)?UL5>hLY5Sy!WFORH$rpOeFp&v`QC~$gIQ+1X|NaoV|x~c{Icm znXEu3BB{pmu>**h38dU-FiF^!-)EuW`tHl)d4BFjp>~H1nCgB%M0*dyBl{K@VhLwj zR>Xa{$6hIu8=IVNMeo}MRR#GYxe@)*qxSVvlP!`LTm8-cx0DRR#7b*+nHf(gM~yU* zpHS95h791UmZ;~ikVD$L*H2y|Hn-A0{meC+3v1xGxbHIB`oiL*UP}wsP6*f1_O$V8 zvZsGywU6nnfV8+~EWt@z{W=O|Z#R;$Y`E>#YH7m^uD2MbNhQ0gG=bNZF~bz0L+t*l z_w~i5YwWk}UaM0*K6}NR>j86G)DwzrBCGN2L zC7wjjCNu1-HffL%4py`;@?8T=lErvUOIUrQG<-ohf#D-3ey0WavSNy}Wc$fh>C zU|}yVVyHB}=G>l=)-QY!bisr;^sDucg{GfPx&nP)!as?o)w8)8r>3$y*YK3tWf@TqG-ft2 zH{y+-At7~bY@Dre3{t_HHMUK?wBpkSPai1QqnY#{q|P|!u0yOB*$7K`%2|!@xt9qU zY{EgDKfdwu=@z{*P%wUCDeGt-*1ur${d=CXzsLZsEwP>%p{S6yn2RAot|@t0$}c;a zR8wGpt(C^Mx?3L6&Wu1Hx>FDW$NlEKufg87d(w+;_F-_((CHNOExpG{faMe zIz^D)K>OBP!{!nQ;|Fao{@a@<(8kbP>7MBiVb-}^hL?H9RBEu-X;$whz=$ypV907+I;k$Z279U@p=Avpd@6mI5 zkoX2JVsF;FodCVeQ|wwdAgr~VJP5+T?;}o~8)@=}v=?N8nW77tw6ch}JWBXhUVQ6#bROWt4E-C(K^|w6 zshl!#!!STd`B_+9w9}yhY-9JXw$xR<&DazSj^JFd=EzPgA|zzcZS`9gd(}u!1fXq^ zu$;GH(l-Wg6|%^#Hn+zNwL|hsFn3%eh>eL>VH9Nrnh%0Z8SoAWZl=B+7~+9a`jKbY zjWS6fY0PmZUoBbqX|k^dg3`YIhA=oII5Mqw)eyXR7)0jQqfaI;Al3QjLwf5)7zrTy zo)@#Z8q;(jZhTEMliQ|9T!(ZkHo5{*b~{t0zoi+-*esUrU6tG$pGRe4a&0fWM&Wt+ zEJJ}{sS<1UC39v#t;PYX1lcFvx752jffiC@`6b%nZ~#V9Aiz<-ci z1D9}vZ9XZ(^*%c|XxC#x0hArEScp0_$5|mR$5wUym`n&jc-t6sPr|C)s0OCvFi|pD zoOz)O4ND&B>tf#Ywn9s~aEUC17F-(}*Ks+16PjP4ys-(Bs-d$p3QQDg z%25#+kT+4py;r|bDV8-CZgdt;fdw@K=KR6i?nj68>+wSNf(_bEF%WYREls^7lZ#Fy zEH)JAtiCA53?&{^{Qv^DO&xqAY?lF$7NMW#Rto5rBniaUWJxB+4>U`Aa_TO_*~;cO z{>1Js!bIi9Hqh(X2$F1;PoHB<_mvyHUQ78CW~_nF%;odj?>=AmT!ApH!Swn!B6jC3M3ES(o`_TO3)Mx_TX(qKD=oxHn;6G1FsK04sUFnj+C3Kz(}y?Fh9K z41Fd3$P717M4Fp{li=fl9VT`ST*k6tbIV~!w!|NlbQhPbPvX;H-hn;1x?AV3hQQB{ zE;x-WceMRvY6g>r87SMG4OiT%syAj1A?}I5(bGo}|I#*vZzr_}dTs{{zFNw81X&Df z`@PO+1xw~=W|CQM!j9!SW3;>=Fx_fWI5T@MMUQ4+Y@!71cKeXI$R-G1ID>3(U^EH; zk$vp!D4PUlxjP}!8HvImj-U;4UY5(NAdpNdUGxlOSCZHNzrUZNr%HJC1Qm*ki9>*Z z4fnorghxu4R`)v|hHOc`dfsIqm)}z!6c4j1;=@#_qQizW`Z-*O#CuA@q zj?DX_Y%i^&sC!IjVJRZX!BZwElV0NTerLiHM}cAzMTVO}&A{gZGd{V)Q@#sbz%;Qv zT}jZi9`|o10sTDN2N#BE8}t*{W1$8+QWY|;Jk>xKAl1`A$M zy6~y%^mHrrK?<^YU|pW?^o-n4h%|B1OP1HEo>B`?<5KPfiPdiEU~Pg(uA0jpX*+qm={Y0cAMjy z0)Num(m_gur)e%C_Btp=iJ?aVkf3L~d-i@1=P{r~-oR+EeXt~6Q(de=eiiVBm~C`@ zBhagq&Fofrw<$noYtd2B@3|&wFq)*3GF`;gwurD+2ReL)kuN)MsQm`!-in6MrtUH^ zKns!dZKUgNGUyVR!mJr9-Y{({3r89sj?Y4G>`o%voaAnJ(iC}t1QO>dl#^dcErQWp zLkLa-B9-4nkeFUmQlA>2{L92?wqWVDNLT$GcDcm5F4OS?iy8L@B3ujis?fDqkQHvM z*dh4Pp`X{^q_&f|z{JQqSH|0u8aLLdH`YM916e~M#2GBxP?=mk`NF3zXhri{;xts4 zPG#GQH1Ga1O?Xi*M)B|`Ea^ZxsNK?K6>3{5apaGi)FUeV8autN>Xd0h`4eELJNCjp zVq#AcfrVPdQx-pIn6jxMN*xpvKXG2#UYjn|mrQEUYW{CKE4G>uu?(^#NLbnj_9f6q zoADe#4Xl%n+Ue>15g~O^DlWbc2^9UU`o0DDYJd9Vlxg;Z9-8RKJZ=>+oG-Cu5#}1h#~!F?UsFlU*peuIwa+b$@5BBa_}fkxT1#j5(ZGP67AvTWeqD zgqe%*tq+2AI zb0X(GwC}$haL=K^#*&2t7z{fbKp~;!c9K-&78~P{_QuI~27@DwrfQbd!`b#|KwgBP z6PjTHc}ZMc%w%3u@^c#FOj6|%kEISaAH>EoGif_JTF@X4ptj$zo-%>DfH?lN&NUOn zS==Y+p)FHpoz{D?2E*J zhM^N$ho!;IcIOW8^g|L%Vm--{w-9X8@a9$6Wk$R0LGziPK>s zNfY`0<}_D2HwHf~C{(Jwbov=f{Vfy2*9%6JN~C+0ziaN)ZjJFzF!nrxdqo$`@QO49 z3p90HB~P)XkJ-%uRI{)LRBQiPEcl{;C+10JqVaFjFE!cOwkNfN@-(Z~Jqj!G1-rT@ zwbV8Sf$ObPbz#%2!V=qXnIPkhCB`=v9-!)n057+?Ks08CZD*gh6ZdWUy5|2wntL5F36)~NLNZVQLFuSoHh+-pWcwG5KM3hN@ z@KO48P-sxso-Y5k5M|3-bmuActiL(F5@$rOvrd4PmxlUAQG!U5Bp%ddtPfnZ%9PHkwjBwljcBZy&!`R64#Dzt#ySnAB2wYx! zl9T)T`(ii?<3;HL1J0*dsDd}wTtt21DVTjiRgR9%w`qIChiuKD&8tnLXExV3@EB-LnZwv@)X$? zxR1riS({5S9|Z-H`r#sOsWA3(93heDzsPT3ayY7WI&+%iJK%4FGV}Pb<2oXhk*m)jgbGYlT+TrovM)&Q|t;9v@m&~;amwj3O87omd zr2$aCM%K|Oep%kr%|yf<+8OxYJ0vp&tGM#Iok24^<$>!yJVgmPia#^d323lV$ASQu zd{g2a{a0TW1b_VAztq-iMCx=oIG;3x%S&;l8=UoMo0H*PlQn+_u<}ld_%)EdDih}E z9h2aEXuTIwhNHBm4jHYL~{zJWIt$2KlR6nh)*eEPZ5!y;+PZO(y_ zdUwOVq|Tk0r#W1vYDEbD%adJ6?;hDOjEET8)}Sq&&cNF-qixGCJSC+$-?^U~8X9w| zGJjG>ME(4D{mS;8Y3r@G>2unA`sd!f`B0m8WA22TJfbe#p#03d*N^Ob_+4Lq9~-VL zZQOb7-qEhlnf|Mes}CKo+&Nd7a2&PGZ$dvxab!qiL-Ng)9fFHZR^dN#k?Acz()j1g8t>An&|XAv<#@-0)b+x5r!>=SMc^e4V?``}9iHf1P`#UOoK)-UYIiDz zYU?-XMuam!)Y}D@LlPIl#xncf?sCb0&_gp1^t^_@TC%Nsg3DpKkmNXs3QWR`}?&)`jX*VlnR3fcm=%=eCXuo9REb{2#uu@EGslzwm+w z_n$Gkb>U;WI@U5!pW#Ec{@A>xd(?nNwi)lA(aJAA@In!}TBAPXd?ROdHErP-o550_ zexm`mcd|IzM8DBiPEUIkuTXMKlA#O1Td>J&(eRuN&*o( z?M$=mrhveA&Y`F=F5CFid#3r|cfU6O7}Y|;=`7}+`|m3y6$t|G@eBX_1s}jfNC2B; z#Qm&E)4ua60L5oF>a;1LAodkTxz%b3^4lExQxD@$azcbuE2(|n;yT&S9^r+eU1zg?yzlae?Gda zue^7^QvXI3f5MbF;|}Tl`+cvfhJqfjmEE-Y566h7%y7!8i?Sx$#ZM!5@z0L$e&C2U zg2U*Ed-dJ7)>_!tXwt%@Y%U`==l;KhQT02&2NnV_7|zK5k#z3yO#c7>zh;;mQ`BUP zRF36Tn!{}Bom1s3Dmg@vx6_=>X^2X*5mK2$IgI2~IfYEhP?=EV5E`+Z&u8!N>+}2l z+aGdsy{^~wJUkxv#~@w&R@9}2Td}FJIw;D2&^^MgQiI(W(-Vh1i$*7<`*G|m9}}*^ z<2ir*Bq_87VI2Q+k>0YC1D`*i3wdlMe(#b^0e+EHhM(yJHE zGE`6PAky4gJFDk~NoDjLDA5YwjoH<=m9k9{JNCmDqDaO$fFO~!- zR58Wg?C>!BEg3EG0Fc`hf5(mI01wYSN$TcbC98jiUXClG*kEP!Y7(nr+gZ;rJhs@G z*r%a#@z48NX3YJ5QuMDWp2(5#e2;hWZ|y3f=G4#q4LrlWu1J<6!6|#-#QbbM<~sdZ zPM}}Q_E0$gmZN0mtm3D)@p(o8vW6IR=qv*Px%P;U{zxj3E>#_~FL`xMa$g&{E>_Q| z>fRSILfi_jAlzx@t-(f8pq&a&>a6zO{Kk=`EK}E@TN!~vAGNOkkBhb0N8jrxu>O6c z%`f7O8$Z?3H+S_1vTE?3XI7Nx`6u}DehWS=-S^7?%thjeAKgXy&CQQvex zD6DiaI&Xi#I>hdZUX3RfmOTK&=enX(ywXc{Tffg!+eEtGpDUc&vd_`nk<=|aE{E_z zO#R!xCzJKekhak&Rh_u#8%xay3*}bCtb49S-AHMu)9HHTxmguZ2xu=}`ca7j^-+2<<}e%3WuP)+|R?~49e@csRPbBE_j zzmH1a^0+fuloc6ibTr z6{)E{+ZKY@w2Qra`8CS_Z*cZ-NqFOdJYhhRP9~;BCr~vP zKN?5hR)uTAGeaM&4JxMsO>*MqiN4^Yk@?ADYU#K8K>X;+N*kN<(?^@df&zcMEtrvrvoa0U7j1&S!o$^ z<36}wJBVo;_Rk7JIy%DNZUh|oRolPKY7L;oK0_ z8)$vmdjA~xew`9wJ#3di?S5B(2zgjApO3XTes*jy@sI4&>@#*;a|4#KFLt^Lm@2!7iP6`SRa{}l+v zZAoEB9~;-6^4=}m*Oh$Vp5xxjPsi`&CC(ekS_}M1kgcX^g~x5$S9^D!u9M zQV&DQVwW$Q+^l&R9yJ@h*!wKw{A->gUX$U3>7^gz)qbVjH%yH;{SJ0f(gY{U)K11e z=KfS)h++8_+&1_2J@I|${49oLZtyH&>yG@eH@~;;LoQx1%1|%msYT_j#;qlwuHC^N z?x$-_ceJUsY~8FmgLze2IxvAh0M7wrm?Lf7$xnKGHI!0&vO}f6o7)C0TRyGG-Ott@ zGcx_cd*fHwV|{1eCkx?Y<~=}uvb zpWpm0C!2JF(c;5219olkfvcBvH-)lBR3pNJj~1mbAG@(>X43C()J3$V`?pn6^5#UW zh!m_+URkTlBR?V~OBdbsgLFlmdmGG+U2HHg%2UP&8i^zI&g^xR*k5Z9>`m~h&%HK0q-9TZ}UF@iPf8on`4 z9l#bEMcJcm|L`8lX%u9R59kCu(mmK+b&cnk64^awt|~({v%cN7ZD=1mrv=pW_ydE3 z^@g9sTxtPMN8DfAl*{bL4U(op8)IetB|vf~1c3S#Et_(maN`tj_xiV1a1k#^(SVR)^O(sp1gVDzAUAG8zKpdg^vfX z6{E(V9@pJ-5Cu_V(%HR?tKaW0eRyPKrL(*ue&Vbb1s@%qX`*C+HSB9?o^E?#E;i`Vvl$SHNr0y9uM&eZE~g2uw`?ofHrs0ahZ zB}4_?y(5p7mspjGHf^VzTxvgrv2C6NfkP7MpWf)58{Ll0t67ge@@VLy*!w#}M6!Ds zuHdTu9|gJNc$ZiN#}auwOz$IFIU;|u>3^epRfz&2(o20yW)ZvUJh!@#fwP|$U70cz zxR>rTH!^cw^tFjK2@&*C>wxNDL@Pp2n_WmmPZ&I}T`=@+nCgt$1CUgyM&&~S@!Q&W zTgy-`^{5cm$|tX%j9JOI_dM&6=$V+ShhJb$9oheUziNlg5-gX8!Z~?1&PUR}T>sbi zlEV+@Pexs|6>ZI%VC#XZ+&^RR(o5?N8`qykbQi0OXWmvGNVFrnN+F_s3!p&sfN}`o z&ug-{-KL$#WLd!8nSvKn13`ZeKhirezVws53EQxfbPtlPt)?8c4tCXlBBi-nZdoBZ z$c)uG*iQ~z&FyqQQ}pv%zvF4ek1EeILOXSxMO<(2-ixSysC4j;GO76<4`G@!Yjeiq z)G@VT6)y|27Gl^E3{Z}RW3{>s|IUcsjsDcr=y5wZ_(gc8`)1dL6LxS_MO#zANfA>U8GW4jexAQC#i#}+jzn12P~AkxbCXWPH|SgcV{R_ zzwJKbIC!}+vs2b=sCbcM4Cx(dA!TU8_x6lu_BDK+B6)C1?)u7J zdiS-1!LLnYXpb?tnMsch>ZKKUQ+JBTf8ECCW^}Fn2o(#V^OR`S5AW-!8$djLYh}BNPa{*eN1bx|L*-<*q)Cz@Po-o=|-Ebt8$&~$Xu}F z($g4^sFmHA3TV{{eD%@`@nRYsR{0_N^Q92^GIKAY9fmgy#ja&AYs`l1E|)5H%<1A` z6?h3?gq?JgXtrF+&YmPgx^}X;Msdsj5>X5DEQ3ybzP11;%lKN&bLp~V1@pPRob-QE zKi-hTi~}N174O}bU|jE~1|Ah>)2gNRD7&u=wAGL(1B;78%8}ir(-d2WXd!GdiS$C5 zbM=%Z5nXe=C|mY>g&X(TPtP4Vj8^8=rz7R$rPL|PeRGG25^C?qshMbl#3i)o(N6jM z6~|HP!>!+D!hiIJ9PHnmv>%qNppuNflFmZ4ZJ6C<0q+d2L_Tp;XVNdZKASod zf2%&Up#MQ_N>0Oh0?P-p75EBiXkyUrn;|D@fZ8=`a&h`6Yc%xW2J4?n(OrrrRpsnr zw18+U-&T}F8Sa|hRq4otGneBvJI@9=8N>{hkKIVfK5<<(j&!|jxK)E!^FN3S6>cY2 zu5abmb{zSB6vz;L7${d74q_qOgp@l*$=s- z!(~$Yd_AY%Iv@F>ICab`zF7jg^19z6W8Z0XeXAN;CLnwB)8#_bJ+Bn{uUklq1^_jP zF@1iVa-I*Z&XDnotQ;s|64oRndXCqfkNXg->-y}EXxGCBC+lhhvJEgO*IYR`fIZnZ zjrodVAJ@^tbkEiChi=-TDA;8Rw&aUj`b2=%pWD6-(T$uR_Yp3tSHYJyzC~sw*%c+;PGCY1gEW2vRBZKZ zC}-ye=Wp6jHgfrvDI#n$L|+Xqo+qGfCVb0!A8RQWvG^-4t~;+2BbB6Z8uB{`4Bahp z&FFMQYAaSr90O<|0ju0raFdi3W+}#Bn+?z%Pdo3-C*@M|ZM@FKZ4xd^$N=G+h=qC$ zy_6_IqHaYpRv&=B3+ZtgPw3j2U!lm9mwMj6P}I)1g_qWpcdp^RUD!p8wXvoa@g=ug z!F9JfK$K>E(}(wU8?WnnY?-&%tKv(?c6JPd8j2KGe zW|Ox-9_L7f_{#jOMh@qh&3_QXd(bER0D~|e^EIORg`w>O*X=qn!Eva-Fbv)ce)3AO zGXBrs@IQAeKYKnniZYD4L7$gyG5|tRyAb;A#r$Wu;Z|Utba|A0H`;Mn$1ZzHIL9r{ zL;lVX*J3IIl`}CEsod0q_D7nXeUVy0j`-TO70DCuCVyt{P+R4WJEXl`0QAZKDkgpEt&uG&vRi+E`p{hgK z@1+>V3LKq`{D0ip$-enh_-6EEVwCPqL$p$PEeO%j(4R9pbNi63Lv#-D_WdPl62E!u zsiwPStz^ne1J)9U&-}!Lv$nemYXYlwfx=t(?0sb8NTb^G`kMA;tC>EJ+-DC z9nIi1=*PGZjVkhtP9;F@{rgKLUgTqvsEEMvyFwdrHD|U?j&iQ=?JtqgqGb)*eGl1> zYi-hraH`)s*tAa#FytRse*F2@Z~{!E`ld2sk!UVX*-uHmws!rZKmT76>k~1EKqo}a z%6canNE&T&F0K<-^@8#T!rFIqz=fReBj^7QnJF>?*+a!`j%?2`k!u0;~Ilg!ywUkKTKe0kE*Y zUcKcOh@oFT`^ASU`TLD~C!%;3ENI#VwH^gfv{s5?ZJV7UrsZucFG1HT<44d-V<~`9%dBxcyi}Cw z^8*@}e%rHLhCoiwUcRZmv_5LVt=hf`AklU+n$yhgSEvIZZ>=0CsbJyMQu(GTt&E*S z$Yr}BI@Js{Igm=iol0B4$n}ZAcvt16?jZ*5fxBOVlNgZ#Tla%`{eJGlYls-b3!$u} zFQ{JAvEX)arhFH@H7=Z0c|`<{^(>)`6Q&fn>a{{w3jONX67&Tai)bbyRm7#<-fCo) z);Thn7@!L1!oOo1f&Pt6KTR)RqK^u$VvC!G1pvwk>WPiAUOo$7D45TV`$hdNbq`a- zG%tYAPM55KpG-Gq{__9ilNQ_;VpCcP02zBTGg;q?(C=OZPD#&weGe<_0wCl5%2NiZ z>OH{35hbRs z=Sm5itN@hC<)mEEdRz+-{|oA@f*toY64Gzj&<`UOe+KV!PjAVn09%>Fd~Y=I>4XNJ zJ%L=~fHk&>;O0Xv5g)Owp2GpKlp37kj*hEX&;(JqFjXGO)5Q%^nI6|L|XMVr)w*z#2r~2CP=i4%Hc}IQp_upw0J5_>tS+-pUWdUVq3Qb(@T7h`RAENDQ`rcp}}$%wWqI zEH1Id!=m4HVnAU1;ce2KZU9qkRJe<8nju$)>jY=~Uw8Rf5sT~DX^HnQDjq{OsP_QO zVZ7>stTto!4yhceSJWb%6A#HcODcB~3Cx}apxJ`l*f=V93dw9p?Kp9ju@!#v@hvA6 z-wQ*UBiz*KXOQP|Gge#ARjengqXm{(G`|`A>2y*(sU3=o<4`}J{ts$=Y+XypCXKFr zg=EkevO>EQfSa&QOX`fSux>D)&l+pXUjM@#2oz>7&UM@k(&luD018UDqKx8=k3o(t zi-kS|_3y1Z%rKiq6DFYB1HZGX*x2qGJ3EVj@49!udA~_3WX+s5zjB3}?25fkA#^`E zI5+A{iR3Z;sH#e<{M$&9A`HZ~cbYrwv~c&joO>=MtQ&a;xSE9t41}H)X&(|EKwPAO zM=VGLc*S2pAcZMtyL^uv^B9mcWjl5f)mq5JoahfpOw{R8KCCdJA7Sr-Kv351oUx`Vlq> z97}aCv~?SL%xa7(ONYvCEKkwn$cKsqGk`UuPrg$)LbaAVXDnbfpgwjTp~ z$BbQ@Y~oMP#%u+HyP(4`Y%}_uaMb@UKrJvum8W24`>oYTbKWg3%~B?e*%dl%#-g?z zmph9eYZvqbvOF+|&*jBAho0B(jf(dQFHgBix&GMoA4kK1`WlHSb z7O-_mRJ?LePc=@-v)I-lmXDL#oq^paP1^(coo{(Yol{d=13;*|LYswuC<}qI37fLh zi(_tBQ{Zks9SaypKu?7dA-?TN!PyeNjkGmD$n3s;|@T%~EdIDY4GH+Lw7^FNL&k1g*q z2+q4$^KSAF)7)|O#6D((G!O?TdZo=YnZ)rG{o07HcmC_EmJaWemom1 z0<@gE#r?%G)OTU0Gl@ctya+&z^^?GFjROeVgmu=-y8lVQ;Sr1&>fEl;3SAA^-`E*- z4R7acaW=JvLff)NvUNit0;svw@dC>VRxw8YI%|0(f%r}~Ss1Z-8kO@-8%_mE(<44M zsc*As(jQlHc`NjLDyKRpxbS@19YW9R{_Ikn4i)6mbP9 zR%P5V=;E19?Tt32-qAI1S#qs0W5*biaz6*^(^mIv75FvZAUIv_jnL^?4hSg=7ygyz z1_EQXLEQ`V2X!}vc|{2oT{JYqq8c7P;Vm!6>>m-BA85-h|&Ii7{}k=N1jrefX$ z0pv;lm3*aryMK(Xa7*{E{UOOVJGYsCUiqX}sjYtxGo73gqO?zJBh1z-k z-lu8rC3N34cPdo>cZyv(h9&*0m)&ZpMhqNJ^b=ZN%*x}Ygn{SfM+6}RG-((XS}Pod z`sL=b%`hx3QYp<3(d8d481zZ#(F4|c1{l7@;01ry95;Z9tV;Sxxb%MvXY*mSK&*b1 zvM|y4kqG)rk1;MVcoqFw3>uQgNWI3X*__gSu*wmdRN2i7hK<5GpYDDw@TW;W;V)htaP68vqq4yk|uM@S-~ngk==TPyLz8 znEzLnlxA*!7S_JPq~y@ksstbx`Tamm}l|ENEA;RuBf4z{RUtS1i)pK>f^e znZ1m_+|)`L8M5G-6O1x{r<>hijTugauB-Wn&m^rFnNID{MAF;Gjn9SEAtw|H{3`6S0^34x|vUqqif%jXh z5zwQef3=z;XJ>)QR3N6WNjj?nTiifsDx5)ud^%yT2vlF3!Rc8%m-Z0InWxw0!{WTH z1cY;vPT4=Yo<8c@Cq4X9pD%)%LGO{m0UBO?Ms6Fk^u#YF8Q=q|glMpJmgVeTB#(Rr zg9WeY6N4JXD)@1*Y#~ijfdOV0+R^QyYCGG6A30A(kIhr!QocfGnhAF$P|j$dmHG5K zdAW@kc0b&Bq9f^(zwYmZxqa<>2Y4XO=ZwFI>6LspQ@zJyn%bHwYi1xZ z2`|Hf;Bp6-1r2q^jGBjH9SOlrF}Hwb6NAqx9`|bwLvR!DLk%=8qe68+T-Da62@;s_ z9gjA-V_X`C=?0hEWojG=tFwcJ3TzBZDWFHfk~57LAT=6{@4{BZhCfl3xRyb_vw}r_ zYU-n(lLeOo#NbxQCAsP5{5HvO1?-F&I6}%!^+h|)`HUC z3G{iSqbmOd0=3Ay=u$=Gu?nEk{dyMe!Eb{5s7c~6wxJ8+^|&;^p{%^@93a3J=AF=cgl}HkOUtr%b8}C<7;j-0s{1zBdB?7#Fg#mWv>1#&!NetQ)KrnOzskaUf87chFC? zfCJ_%)G=(#`r1=tUJ7YG*8b=AdFJQK(U*8w@P$vt=iSGT2lNW-2wG$K`H(C;aK5O8 zL2PiF-Avu6K4k!Dg`-wjg$iEo0$mFPQ}a$S2!UjshMrzprmez^kXt=|T1h|Uj_u{_ zy>ysZZo7by2|WFciLD3LVW^}g0JG_jt0(UV=l#C@^W>!3Ic&JIg*f#~?euyh1ish> zL#FyYOUqOz2Dq}gXvr|(>-bkVbixQzaLH@CmK{S|z!o{HS!)lIw}~+D-EfBdfXgb0 z>DaH$Mf-AhPBwuTA>+C*f7$&?r)D4bGsrB8!vG+Q{sIOz>hCJkX-N^A5CxpPU%m}Mg zvb6f(&bBq?m~)_B_Rf~|hLoRdI4n}W!;Hw zWSoX_TG}^_oH!=wUUSofxOC(w1tGJ{F;lrt6M5oV0CA5c7!j6$1zkY_Cb3x&09K5r z4(kR~+0oXRRq~D>g=_chb9s=q@Ih_4o&hp>oH8;gmWxW(jKw`H-m>Xh+btr*lYUo+iLHQ2i#G2f=m ztotAHcs9ugdKpxA*B|FAYG z5ElS>(Ok7z<_?xgb)ARB?h3~hpnN`ie-;enFj2r=fm8-TNYB|jiI)!SYi?C%B9>Og z#N{Q%M|VbMsFO^Tl^SBw^4>NxC1%qCGD0oVDnNo2hhv1l%EZPXF?$X~>*`gDm++vy zwd*y2K%SG9&grX>YD(vgyT?<@jHXX;F6$|!E~{awuH9+y4+oyFgqVv+Ck40oF11;{khISqWYd!}`AGv!ASR<+U#4QR12iW}EiH zm`){pG8a=y`;$B>m5EvVogH;sK4u3@2Hb&&6AHw1`e8j>mfYNKRk8rTn1*NuDT;A@ za!uV?vU=H1bt8%V(EW6n#X-uw9&jUHZng8T7>{y%vQiL{K3S*^vZ^j~vhT_4$tOY* z)*K39fOIx;k2bshNtZl_K`qX=LbX_bRjp$KkJfGClbQs1(Vv3JWnAoW@Ayc&cQ=nQx3(_9Qz z^heryGmRh$#B4$roQ~gvLRY8ufn2D^5)AYw{GPZJ5q-idv$6NDE;`M6VV}si&}NRtk<+$5Ef4R(2|9 zpMBwBG{bvVwk)&5=QtZ8dyR?={U_2{Ac=x{OB)r?e-cuaqCgm?SK@^sc8CLt@JSvY zK#uDYxfa&`VM%w(or8y@Y)Pz3=;dGJG5+M>l$r^#IJn#rs|t5=4@jgGj~Y<+G0Qy( zGq6^KblO-CchKnVXT~fHn+yggMrI@Fr;Ava(Y0O0v4{S=`dK`uw1GCu1J(e`?xpW- z!a~pm7*{{cR@CWlOB5On{C|R0p~G|d*?Ft7*_YwVZ^MZ_hDHW`iB6g16{n1yZ3`}v zB;q+IIh<&FD<{C)fFw4#Fn>iuBXksm9^pE%ioqo!PtOY@I@EN!;Mx)xB{7lDO`s>9 z(@lKL_Lx!&Fjfnm+l;Jd_blZP4Ze46lP3o{s)O+WesQttdO8v_6{&%JDf33fivb{C z;lOinZHh@FX=BDC2|fK*-tr0y}s`m>L0z zyoFsduP)K%3*WI_NDn2rvYLxXe)XkaCV{E9IEXCfg>(^%?pSbnlzBe)znDT1Ii(XR zWG;Hsz>iK_X$8Tm&g|pnPSFceii~PWACV$N!9P!LF<4;hnQknppmE-P0laRr=|I{% zzfw}7D8TZ0%ABxiQIp))iBr?BIt}(<9q)Ali^7EtyKdI5jJhU$cNP~7v7#wRUAAqz z010Q)_R>|ZU&^*eLhuzpFuZU%>8S4Ip!>fKYTYr6SHmY;rX$sEbczwJo^pF^M0PSJ z5->YT6slgF?fp}{+MPOyW0XHjAVdqF$#6V=S6c6>9j8WoLwE7+-9&u!@JOJ^SM_kw&ZK%}wM@dpcD@v538(Vy4_AP)NZx6nFCpE6GN zJ5y+cJ@KRe+}#KJK*G$DgNuwA196gJ5}m?C*SeA}cORrznLlG zgP$h=>W_tiFBFMKbnf%fmI3Ljl*`1m3N|OBA+YRpYv8&!<4aWS1$cQ|WHu9^FkziQ6|0`&8^iZn~kzj8wX1o;p z-0Y79!lj>R@#Ii2wT|qT%u8UJe<-_VmhC}B;te60C0?A|)zAoExE~Xo9`^!$T=HSG zqEu9qV;lh4P5lW>Q>sufK+C`>lj1-u+v2tPx>i9F7TLIbHRoSl+l#Zul1gS8|JJv4 zUV3HrEoGMKYYMrJw=erGK58JZvL%g7lapi8g@1rIAKv{uk?s3b$?Xu$0n~{cQbvrGKvsn9B$T zGowE*3;97uTYVfvY?Y?Y~@$b=8>Y}sjYFTJ-oU=BY?7Wwd4 z?p>hOr_^9HlBpMk+||7jk#PH=X3hLiR%eJ77OR<95T>zwB{}Y$k zml&*)LcWo6qGm&Un@bLdvr?*B@l`J7#2i;KV{J!GX_Lh8{|~zJ=;-+fCc%;%l|>BL z2&R9La~f{aeV5wCp%#XR+Z+z1nAm4aHIGnWa7t6U!y9WQauLd>ZN|tem}A5Hz4zba zwbkyt__mb}x6 zXaj9O8$nSw&^i!QRilg|OqOG#)75m(ap@HKXy~M4YgaxwcnokJCMO27v5lQE-F!<|bUiBDbVCX;SE$sKZfA9SM zF8;zLnaI_mxPmUY<@7W5Jib8_HV1K-o?pHp;^(g5#O}1m#^1KsHi8$i`_8Pg?$6BK zPB@el!u1@_a>iYvnr^J0A4Dgr9Fi6<{HIerR>Wz-$@d1bTt$FalI-f4`bff17$;)7 zNXVHN#hRj9+<6ppW(wu1v5izm%$b>yH*nYA)+sf6dLUeNy>h4IqWi9TLMO}^>0+ri{G}+1gm={1}r@X-Xi61t5-F*PyJnjY)($U z$Zio7S#tW((7k1}AH}9<_LD*C={K`!*3XdZ)eh*5Cl^6^{U&}d_PtiP+~3EOUz-q8 z2NVm?j68VlW)s7%ZpZMF$2;Q6p!)b4m{d;N-HkYMd-;YRF6`}|1nB$h8g~AX-#%#O zHMw4IMntE9e=5n`b3C-B_gc~Q(TUV|T-W8KO6KQ(-jDu7Pcq-x={!d@QwP{I(kX$r z|EsAUKZt8pCr2kmE^ezeWiFI-pydP}lGSGG=@ZviHH_HIS)=<6(M5uR_0LWYpWP>H zLv@WENs5@^TUztkY&!Tg^5C`=^9?h@@;@ke7O}&7S_y38GbMNJehvOlYw7r2auoA# zgwg8=$&Vp@ab?%kLETyqdG`0j@WT4_Ta(@oE5WY19NqE$=7t*Fv9pfZ8Q=Ioh&itO zH!@T%RKU?n4fn@KmKN4lOs@| zt>~?i8Ik>UzCYzYc;Rs}Myy*0)zMvcZHJ!ztjqXg1uQJoBdcn-7WbS78&utmhL^vD zGQt>k+%daDRE`t!Xyi;W?i7A)2B)-rk-d)@=W`MMM!8<<9l`1Fg-4`1IJKTiTq_R5 zyvyhdXnke#{8A9IQ^z?xxWwZY*0V0k%ES|O@}>|0-S|0$p)zUFb0T)r!*Z|4;SfUKp*4Ni zUWMOw)fcO{JS6-pyT9z&k4sTAC$v5{qXMQ7&Y_b9-taF)7xp<}1@Q~|79y}vjw7Y| z??S8rC*6_co(tNwu$lW0W5;ENvvOVaM~20xsx^=O_@=qvBG=LHT=vH(iOGTbg~=S7 z*Q$7#v)@}0c9C*Q&@YusW)x?|cO8nN=O0;&%l_UCBm=f?JwCO}CbN+R{ zxSXJ_D3BGFy+2x`uHs>EO07knOe6{`ow#%9@5;|PFXzPJeJVY23VNqn1}VzL@0O4D z#8v$2P_uU-X4e}{Ty_7V<#+nu?`mo~QPR6FxAh*}{;UR1R;M&9;xCN`9XP7X`Wn+W zN8445zt&$k_eddvT^LRzTsgsW!_~6BSdyf7<-%@@eviELwON6jjJ-|HCl5r}*n^~r zMux*axl}>P+EwZAaiuZ_Dz3h5`U|bvYxIq%;BL3avy9CQXG?11p16@s!?w%gb6k%a z8wpoqQY821^0xVmnA1zI)u>!Fj*g=PuiOQ{LV1U)Da)OdZ0&++pW@KRPBmO?D7fDw&K zqH(~XTgXoQ>gei<7{{i_Hg%&lnm@p~evXw^%Boaupzf&-f*w{j?;>+Jar!u8Sv(fp&ixUAF6f8(!K&!cF?osuP?xx1wk^R+mvujY`5pqO0P*A1~z9CndTVPyYqJ!jgrZ5)5}x z>m1@2yhr>b^kYfl{9q-FIy~3|=Fr#IDn1jA$PRHi2P_eKkh{vl$Bchw_<7%p&C?5- z?iqL&-;k6pujHW3@**|ObfuikkgYm3D^$^D@OBhBEIqt<`JFL-Y22z)48DgVMl0pr zD&?CyuKwm9df5WsaE_&&eC+L%`D+&<*#yRlc;$ny#t+*h`0n`-Ns*0v>B1`kZvZL! z2KVAW&c8;zjeZ$D=X6)j>5+b4^mQ~h6RBCs<*N!>K4E=GE6wWO^EOUTmAgvc$?aVA zRhg7l4Q%B#OT$+&nXxc__4a1g@RZ``@q<+rPUILCzh{uR|eQ-O%{(vJNyR`0+f-lE2TTNr(7QF85|^8 ztl`GmJ_QoLzeYY{`^P)xveT#d&<{TG-i}Oqp8dyod0FI_T*&4|Hb6jvcbYB@~t-e#AZ)tn$NSliIck|-TkgdFo0lsnz?rm5R)tA+sP zl77|HmF}=-k(Dm%dGJCV8^g1~sH}9>>4YC+?iLkUpO;mov#_@*$>Py@Fe@A;|bOKY_*nx>1(C9pz{=DqSKoq6QIt-dRL?;hCR3gphVAp1aWu1y`7SK-RYm5sf= z2pe_DWY;-`zn8DR4)az0G3h?{TLzx}@&aUz!N$ext87Qq%c88UCMcG$Yvi7%V8`A4nY9cS zdj`i6AOEF{Zum^^=niDxwM=Q7X7wblZa?0CEyGKutrG+1a5ex`{LyfJa=w*NBGNf& zXn*KdHnUopE?foFv&;5jLM`dLAI`j40^O0Kor=ggO^T7%N}205 zuH#WLX_Lw+OO&ieBQxcqirXHp)MKv~DMpuE5)9Ssy6c)m4HtP8YqXK0Xc{|aki2b& zv%XNt`oLFB^*v?`!jlnXqHE%G;L#UD)tU*MbrMf#8`BH5!f{A1Y=#B-Aud1NZpxKT z@AtU>=&Jd_118=rgB3>;%i8iiSkfo|Sm+2bj*^3Bu-auoKgT1+MN?=Xku^~8w~hLH z;eAxVz*57EUg0jd8GL>T5)&klv!Cu@mHGJYt1)K$u<9wZyUN#%%r)#S->*NV{2cgK zA)<2fe8wKM^MZl(j?BSgsnu zajERiEsVeLa<2dhndDVJ-5TEl zZ9pg+6^so3^ZfR3>RvQIlzQhF5&kPrfGLHoEf|iA>FV)UUpak55W_sZ@KHDp*Zt%= zoP2Osk$v1>JNL^SKz3ab6UkT*`!F=C{8gFe5{&|!ld1E8)_WIF;_SNd;KJ-RgCh5|O$OcGc95W&(|L=Pr+4l-Tcn&Is8WMR^FqG-GCE|J>&06E}su`9gITXSLkujrY3O*Mzoh z`b&0i_}VKx#Z$)P#c=;4ScQeVg3{x8u7^<i4(<(&l&6u)b4zm8<}8c+vamu8Z)I1qQt#| z89Rz*`xkU+E5l5Bfr&dU;-=F^eolze>%5%v6@lfkqe|}{sp{@@=F#P!m%raT3H=hN zQ|^=k;^vtBxbz4R$XFT|tM?(=5vMfInCVn8oLZ$y`8Xj%Z)7|;g#2l|dJ|z@8kMkt z0A1hRQ+!=>_D`$F*X950{=599wHvW`Hhzxv>mR<6u08QB*@e;6(KaKC6X~JSj32gp z+`gAMY6S9PZ|_qCq6@G&)gd=O^{sCI7P{lVcl*Nz264ZHLAdMXnantzlXS!3!C2)`!isMD>wDgQ2%z% z3}hEP>{S1RS?mlgGLVZgZ*PTxpY(Hf%Q|7-mW`fGOqz?)1pbKDSVLhHlip<;HqqLp zfehdzKFGT3rZ~H0YZRRstU+j1fZd2K(`FV}sc23`*5-#C+uq`j`?49S0Cfs`pj?Q- z=rPO5rZK#pYf}MavSUBnllZUnkVv`M{Ac=@Mdj?2`d$Mn&!nvZMirf;9UNz$mwU7 zwgLude!?Q2?g%)BNrcQAq@S|I0%Cf^2sBqL2ZK5Ssp-VxT3qH#n_?DI$+FdaT2JR?ny*@!-GTsLMP*H_~L6d6LBVa%_cp`4B1&+HR! zG--kFZV%_;BSX!%OKJ##xDl{(K4%~6ms^eSBJA9&f;8pk{PI9us`8UL3{-T2*6U%O zAzUq3qs`yXAvgmHSKsx3^eF5J$h9|EERNfCJFf`1Ch0zs59Dd?*)V3QAq-vLycs56 zjV*$ei5)1(z9*&AW2iOThT3v3Z}JQmbfc(`blJFV5tib>zT!6ttZ6+)BXuqB@%zy? z?!#+V3gco2Gf@$Fx!}_gD&s7z&eDTCxTNAd<2M`eduY?!2Jk3>tvD-hZLH2pC*OY% z%F5s9OD!_0yayV%Z*V120h1b$!YI?*laAFxUq z;OqaGz6uw+H@<1igKtNU$Mx>^bx^EwYd!gFRfqm_sy zbKZlL@7$^e&+ZK9hsY@etn2{z-(368_qWz?1*cv4KaTT`?}CJ98gRxug30%wuYu&= z1f5;10xU1~VDW(FpnfkS4}HpD+*L0Y^IViE&~o-Xhw^rUd1LS%V228}D|aGfa=e0z z_c=AR0KE3Hajjr(Krg#ug)}=6z!drw@3G|IHdITYS~lZo>P? zb~D1ID>}RC3Geq*@Exmb29QPm2d;vk|F!$b6>vAJ4Tp{U8A2TMW|jTb2#Gb!YW`-3rlLSi9A&qOAM%Cf z;LoN0gIK1w#oYhsWrtgh!m~ej0+Gz5$lHq1aX;d0F5iOzNP5S*e*q4u@BYeCwAYHd zL{k7W%MWR%Ang?iAg+P%wbLn-VV&T7*4G?|n^|oqQ|qPhKnR{EWiKuPj;C|*a?bKj zapQ8Q**@uBLYLp!pmnisB5hPUT4YKA#-H^3|2R7Lc&6L`kAG$|BvRbXZ8J3`beBW7 zHq59yr-V>CD5O#f8*)BuB;}rsP^uZ-4xy#* z$arJk7~*$UBc~dRO?*7Z~LhwR$Fjg#QkrO05Z})KDyBjf{$|&uwcbo+9?(*(TgDGe#Pw-#SRDmPvE=2_RSAyF9Eh02s@|KI+S4QM=QgK`qMw% z9?IbkFbek>%+V^!xJpciCAn4j9l?J_%yQGRbmIrj z71_xojA0(4TY?F%LA1K8j56`&L*C3@!-)SuFsJ2z4FK-Qmo-$9Yp_8HHcea^+6}{f zxzW}yCj(Nt7THl{=N^U8^&rh#s40j>POU3mw%ch(s1|0dql;nA)9s;6TI*6bo3Dm| zW%-D$px`N#Rk_z7{0XpkDAU2X7=Uk7w!<_b5Gc6gSl*$*#L54drsM&9p}rkBZ?FK1 zEF9C=AVrWgSVAGFu-&=$Mj{L_UJqxV|PWkR+F8+Gwa>7hn3 zXxbLEHhTJnvyp00N6xA<%;xYeWt=vvau<2t6hNY~&P)r7;dG9Rtd&SdXj#3c_n~@k z7qpOnMa)CnK0|scY28p_?Upfw#GN*Jt0c?g8d!L}vxL1@PAyGsM&;EN%=n(XI|}+v zM!+JZ>d1`!#O+$o9kp>XTM&5jgCnlPsa51Ddg8=U4r;}F9i3dYAA0D%c>z zRX9PnuLSqow6IAcnCHXGiU$RO0~EaFr`@ftL)Kzzjj{PE;vp;5X;=Hsrsf|w@zJrE zFWe5?q~1y8h*q3un6Pk{4QNr6;_~2EH0z>QHpf4MLjqr|+%7k-J-2BAWAnWuKosNz zPA|Wzxp$BaIhETGbZ%%jN6|e1VtfU!t2zyQWH@e#3aPEML24yxONM?&i^*f_os1T^ zl{VxG;3OyavX8m#Yq!3(kH~glm@|Ijc%W@6hlL zn-lf`HXy`cX2Qc~l^Ewnl8_p19H;#6<}Riz+qmQ+{=jS=1Z*0fqAKEa3gl#C@AYVc zS9pM$=CQquV0dK-@=h}(s=V*cp#U3}aeOko5Hg`j>&QI|$Rdygt?f5gs4XZ(PEegV zA~xGGP7NAg_B5ZLTO+m=XUSWaRq3L_*gvnOAyHauSMuNgXs#ESDME7VdFtScoS(3J zgV{e8Flf4FegOnI6hF3uf)ykjNr9~{35Q3=*5`be*(qCQ9`<74+?%-g!oAA!8%M%m zh1&X4(89tL!y#^vMRFQciVyEC^@sen(|Hdct)yF772GN_G~#Ih)9N`Uyam^S+mYJH z(1Ew1Bm+E07a3*zU-Q=q$)mP0Om8wBM|2>0rYCV7{f6)N_|Po_vnLoJdVzE>N=e1X zdayYNd4fwIPfWSSe7LzVNp!dhzsngdtC2|Sc0(}wWIO`7p!S(7OY^1>A}5?SCi84G z+R#*Sim{wru+>2B_sbBJ$arn;cH1SGqylzb@w)>MMUKqicc)D$S_z)xfj0a}D$AL(5@+%@@P-Zg81pGU%Vz@NyS1qc>zU+65dU#=gZ3Dm zJ1r7hA!bo~yM|Qa<1$B>d*6;{luvKc2&e&zil9fQKdS($4T?%eB#)p>&Kd4$F{pSX zX7tV!;yS10 zi01|QyS!PQ#(@T9X3ipfp4?cVEs7A1e~&~&Sp?Yr>AZ}a@Umra z)F_f&VXXlE7dp$T_)s8trTmlawO$ErxCzq@jICv?*I|BjDqu@xGS*Mcka@@{>-RKD zZAdSK$~|PI)Q97=5G9!JS3(A>hM@UgG_KJ6cA)7^v~5gSp=R8ShB=8qYz6YzGJ>#-}}6pMk%!S^-?J z?(7;1zb6m@@ru~Q{DSXPHdc9MPCj*KM|r;$WPm~)yQv%Q)zv*7uKyE?UgQNi_$Lf1 zk@}>EA-y*5Y)fgVqyPj6)?kq$3b83CqYax&{+toAx#2(=5MMb!CQOz*&r``)e55&4 zl!gb?NpD-nC}lJLP1}v)p3fBB_TW6hG{~?OCK#)+Bwsrqt~O~S=}I+T;Y)0k-vGcV zr)iWoB2dxCD*Q+bI^E@XBr36r5$}HjmHC_h3T@{sI|m|0?TnVg3Q5F!N1-t~av&I>>W3@+Y7P?VnyoQMs7*2lAkcS_$n7=z~RnrIRAL{O(L;_szyb zIKg=utLEqL5x)y;TF$6D^SY2t29>|lptn%$)H$i{V(ScI3gVDxLVd-YvNNDIex%Mz z7QhcE8uhRU2(bGFtTwX_6U|R5U6=(22uY5=j*fQq#Q}FxCgd%|eOJ+X)4c^+UyR!K zY?s^i`st7S&zT4=eoO?%0BFL#p_pQ%I~Tnqw(mq&3mj`oa@ZD$10m8uJ8Zc z*5CYGS>@WF9bIu@(gM_LAhnG5=~D_Igoq{Y{xMDBv@MglLLX{~hG;l*p~y zzFK3UGRoe4ScKUdjHoKy_3@32(O?wJO3?$O>pBQjw*JJ!twK1Qz5I^IjD`WRE1~3_ z;Wk+rk7*V&x=VJ`bPYky>|547VrXf{011zk8dvQT#+HDa`Nvi~yT{n}6+Y|X(>k_D17oKs)d?m`=+Jnq{HFC&__n~bn zee&==EDb1JxJxcFw4a+=qN6V*wR}TCCS8D0eZXI^?-~@+$g9Lhh?y90qQMo7AXb60 z5&d^b+CoBjO|xz&ddkF|!*K~E)`%jb!BC)Fd0qiyo0moTmT^y8en&f*#pf1oOo&*H z6lej)hF<^HdJ_Pmc7QxL#~q_5N|p5zWvlMZD|v4*Tlva7W3fX0|CQ&oQD5aA%ZN|x zq$o}AOhzdIoM}&hISJOrQzq&ohFUD$)K^Dfo3!!ULbAy^_ zorX_RyhnT5x$<1cEunKT*&{l_ z%3Ni(06YHI60qMZdXCdSwwV037HbQp(FkOTOxe%sUznlA;#pc5Uf+Zk#jnOUB7dBw zY-8*rnvS-Nc=`KqXN0(cM84R0{V$5pGP8#FmAG|X4W{HD#Y$uZ6*|5V20h0MrC$@& zNyk9JMVK8<7K~>z2NPvD_tzvtW@Tz zAd88+EMuXSH$${u)3Y7kqRK&mPfKBuP33C~SL;7%DN_1`8`N_Mj)`bR?Fc8+Af=5k`cHVs5O|C^}_>P<(z_}<9_GQL_ngPYSeYin!hrL#yw@i zmE?az{52u$nujE0-Hj}wvzd9pfdxzW{BQNZr=-7A%%e!}mZ;ww-6wd%JZyVl+%bpTY|8{{`EGoKqmX!82uQ;he+Z_u3x5WlN_?1+p! zGLU48SqsdHB2c8&Eha$AC2z^i=oCn!W$^pyRA*;vDs{$hzWA-OhW3;EP(8;rZAiuMKX8M&*$(wA8Io0gvGRk-KQ2ebYM zRkl+Z_YhU^fl5-x;EG$*cem!K9)IHvPaiU#AC6O%UZve^z=Z#qMsx&0XARMBwr;NO zx?cS-=kp89^FJCkTAH1q^wS~5-b4gnwl_>GzMlPq?*BiiF@0W^`|a#tDo3;i80oA} z`QO)}~W13TW6vqPu;@!yCkX$7FS>no@~lHYw=N^z`K=Adis zMeq`E47opwc?YRmz1=$)Cd?D(p1u*A}CYjS|i(K=M@b$(1;fjQHB90AU0e-45 z!1oW2ls^>iY6s|S8Y-WdqG$Q|wj=rDV%A!8O6f*afW@YP7ttcR|CrSUo3${(;oQKeyrYIq(V4z8Pn;;1{%%pDGehiCf8NxY`pt!1aR2v_6{_a1ENF(z zksdy}bx-uGG;7ZV;j?WCf17XB)*_joe}J?^VzL(?Y9fE`@vYE(kC*q7G@plQK|0s)BY)ErM@;aUEp~6cVwAXU!iIm76>yQ+)>g^{ZHm#cB}5h z#OKt)jV4NW5U*eYa(}74zC96s1>Vr%yyWug{l1Q&8W76LYVLk^?ezI8d0aE|5|`u# zUqD!U8n5`hbl0UOk+zRfRjDJu$`x3{u8pCTA4cf*-zV?VfZ%~<*MHzvB*oe#anzCb z1eiQbGD%eBi%*w-2twCvzZb0AZuzq#wi=H*VX&OumIl*5614h8l@`(>r#A#U*bz2Q zi!}qgR+qw!A6BP~p&uR^ixb`Kxh(tZs~-lHKx^LW?d%+zv;d-?zv&fuTxvaUT&VNOk{n;D{h429U>38tM!!0&{9thL%MS-f7g%FCn zPGl;Vd8_6uD@N&$jm`4erN~DLlR<^|FP91Z|1qk0J^uQ9#k2p;*4){7$ucnus4*5E z&m5I!MC>x<>f6ZK#)KBX>-jv}kWJ+wWuNlMug|-uGu&QX&bfX47 z-R)eBJnqBQ%3t|gIJ$qW*-5WHU1PTVyxqmht@h(RLX=LVh+E=o8?3#-$dA!|_KZ#>6>-;A zV_~&gYQWcCCSGb#eJekFFQ|gbA9wp7l*f$rV0m4e^N63_v9;<;>_pdpUI!LKX8(!( zd_@QMUFKHXnw-Jc$Dx)bficZ9LF<-K3v94~;&X0wR!L>@FTAp{NIyCtAkTv;MIBlz z{F7yZ(I(Hs&#ld>r%SG$YURwAAzX~vQUk>7-TJNX3q@B@Ux~cJ*n!o*UdA^)Wj>xZ z2q(F#n%14RukGMnYpLTzk)jXj$ z|McYzC|(X0ESwwg+V_6E3Mg^RYeNkf-wedL{WRl<{@C_^a{UAP1ilFPy!t%ewfGEF zisx$Dm-=p+LE%bofr=^NTHGg7+u@ouQz4MNmd+{@M`b^Q#@SKkf$_u@43OA?P2oEP%fXMNPlV=j zC$kP+7{%d*_=$5L_9dYR_NLPzx}RbE~Odu)4)uH17G`kK?f~w$7VI3~$WFEcb+bT^&J8^>XC2iFnzqzIo?!9RzN$0I;T1v~urt zvu`@@kVE&$xUroq6Xl9r`Bv`Xq93;G-Wm15V8_nXn^O;8sir=wN_f&GQ2JVH;0`@^ zg1NLeCuZ>T#HZraXBK$0H_jJFYY$?h+YB)lI%I>^vFOL!xpkorrf=&eU-#hex_GZ` z5U!0g8oS}cdS``wC9j@(YIpsKEAanbe%k!D%Uq^eDtUJG_J4n~vi_+>Uo`PeCA%+|lE{ z3HTkUU-1W($&HeqPIXm=J~gV<8jZh%^ekWdtQf}5UwdIK5rSNY!8=c;ZRdpegQin0 zrnKWGnAykUCz+~KpI_Tn*v2F^Ravi%w3h`sv;}LMQx4I5nJFC~l`C$%-}BD7-SoK% zv`%bivvwt36#>J9f~TKlZkC_iuKji|lY%`ik1^c%$Y&FmY3U5}EZ2h+IT)tY0eY5g z`TkFzkUQ4A_~yAH^T(tSJ!_8FsO7@-XKAe%%2o=&XaKEOm2u`wOR@U#aiZZOmhOcA z0GW37+08!hvTHUSd1Fne&zU%Ff9zKYI#{6v#)UHqea{TqURw{S8YWlFb0pevS=9sV zvg2?_`NEWiqrnaC?pF zYdDI17lop7o=!|CXxP(a=W-Imb+(RFUbau`cv`Kis{y(_M2F8*3gwJhvG;*!QPEY| zi(v_zs-<}5@mmE(p~BUIXqOEK5<43Hcyw!^kzlBz9eecJ7lVI_cE!K0=?rO!cRX(N zEt1+J!$nTo$QiiyZ~fRSAI&-d6Caf69z49M{(YX+Km$C3F`e`f~V@h zGG_dQkIT+wgbppEFZ9Fd6ooBgPp94(BIq}wQlK{am-L~kNdU!;Lxnx3_kP=f+D)5T zTaDL$%ep)ovPHFaIx#VoT|{`2SF!o%mi8xAOZMVwM$l=9XE?oYd`|UN`{(Iowct~2 zS4~LjfRIOt`n2;z#r@kIw{^EOT=LoIa@W=v=FAdNsmRVGm7q9yC{;$8PWYl74{F5RQ3knW??wWdDw4bC2+0 z7nM;^)1(QFUhf)I%{upi#)}!p6bpUQwsS~En-)( z`O7YHH{>_}i~&I{(yRXFC5Cq1ip==hrKmqezBv$D<6$wEu>LbJQG9yFpkkLD51g|z zadk_Jc^jSDzS#v&cD&j0cFs&B?mIEGvb!vtXMo&Z&Z@Iydi>c~?~ddwC$H*|m!doz zGqSZ6Vcza2BQd=X9sg(7-2?x8V(kbhx^9Gd4H2W+a<7+n9QpTDp0*E1lPeo6k134o zc^05V$H+J)3|ViQM4TRa`RSjO9qskjjhMYE*P@upA=VG~|Be6SOslV|bleHoDt)3g z*ArXPRo}RU;?5i|Up_u@_12E+Qw5oU9{rsnei2b|xS>0A_1)E5Bfp-jFX5Fzx8GlJ z2fyNb>SOPl7jVB8#V4<@kA}nuT~cQ#Y0a$M@G6-K%b}}9Z$EzqhMB+v^_JI4gB(u` z-F&oZ9i3zI385oo2Sq`n`y~8=%xkQZDvlRITP08a{A=Y*N4isZ^G#%6A}jmn*`o4I z&)NO~c^8Hn5^N!fg~x`gzSlSX$|`?wGWQB0A?1UCQPnhycIj39t#{YHStVcH(7u3D z6#m>9t+A8t?mH)^BW;F4r3SC~&+cqA(O}>M1j;JJQJ1zz*aIZ{_NDnVml5<_w!_de zQ|uoZF!lbuTu^gF>mI;bJ(IMF zj}`R3u&OWQ{nNXYgf(T?QU4HONzy7NJzZ{=Jt?;#{vjb&3z^-ZV zxwhA{8Jl)0ivD40`Fz2(GZ$Ta(yL|t*mK3(ebuO6cV2*B#x6*IRP@5e(~}8u!jFuD zv4}#fd;I@;YLq%q1vSkwNI&W%v>=GfdQ`NW_GH&W$l9l|bjF$jna@vYPrNdhe~jmr zNQ(`bI&(sHly$aHE}Wz;KdDSud%5i4t!Y?cv?o=wJeK9vL5S4gj-Puc;BMTrhyS0C z%b_>1qVuLSnovwrW_r;2-xeLiY3J`1C|jQRVdnd&)OY60|Dc$ufeMwlrKgW45ik6o zCEEz>tITUM`ea@PMr@j_W^JY1{8AxI;?$P$9v!sNi@@9{cv)RmjSg{BYJM za8bEVS*@3E{W1+>zZ&@&CPL$imV<6Y>a2bB({LHE1A(?NZaF%hlP3`Rv2x@t3241q zfB$|EM0kfgQ6v-AdEGZuv1vBbLv;kPKnMt6_-$C9mIHy@fRSmfDGW+DFx+9@&0?}_zRPib6W?ur4msh%P_8(gBr49OzeX*CJ zY022;D8<)j`kZ}5sj)tHbWe89<$vR13`p{5NQmiB6dv?ttM^?kc;4Fca+NVJ8B=?f{2$7}qDABfp*&C%ZS z@U<4gGgP$faW?NU;VET{MMF-*5WGz6Sx8;uX6Gn0dPXUVD-`av-!=9iPq376kDu0c z?US+OX&=q|V>$9C=z+W_)SY4lb{9}^jZy=0`D&B3mF@P}x+lz<6Dc+-^r+c1@^BeN z$v0Em$9}t&*Z7AhUCLDRd(ms@SLZ#^$~g^x&No?bYy%&Hs7H|YcTP0({KLM&D&B|n zv?rCeNVf{nLJ5m&gZWB46ne(%h4}Tw7aNWr+3iyL%lR(u*~x(`JLxJwxr*Dd&7}_x zK?Eb}5mq?$SH$U=@mZ5f#$d^S#e(j55kU0;(UeOc&yl6@j;Lu9zsLP9$TkP(_=L+w z!w>dJEkB!R0A}+HvZgX&oqFT5pD+t@kv zIj0AO7kS<>FL`1{XZ^di!nk-P@omOJI28!&)G?1NJh*1wK}Ln1m_1`Et^0`GwWBkr z`N3bC6p;^*^L#80Il++{RJ|C!cyqUh=%E1xJoMJWJdk5n{nv(aKc%bHTWV}joBKMA zrdX9<`W@?|_aa)cFk4`{xHeP61Ja_Dj-hMU&tWbGrPOaa7kvFp=y^o@p9djsAh$t% zA@}W$@`$2^T-@+uqjkY=LuR{~Ol!kt3&RhU2mN0qk55#3`py7uEcYw&e^3fbM2O%l z?2P0tPkB~a?sr$#aCTHFSpYpu#RofO%Xm)@(d3c!huYUfVR3F;9Imu0_jWc=xtcBWuy+7PEqA7rcQEG3 z+Wn^Ge5M}&289d4{Qkg(MkUiJ>--r$WBDrT5PU$RwCiWm^ou1-_|ccuT!D%7$$T$& z)i<}PyJ|>vpHp?K?sCfN>ZqIAjH=_>z<)#;#N5*-Qu*QggQ!1H0ugd51*Wl{*@YKY z?FW}U@U@nD?t1$sm|%3Q6=XxG&6tN-xYk4c@jwQse#-(~sR3xBJh5BgMQ-d6qR=MV zn><3#gl!CTiNM@DbQB3GXR{lSdOh*_{?jBFK(6L@&8E0NMj0srnruZVYZ&iSKcVE>9Ms2UEuG16Ia~#0`b#b-cZpNF#b_!F&XI2 z>5AuEfrQ~RtPQx3UK$ub&|zYpY_yw=tyZF1GQY~ldX+Uc%kYPe4od5;B(Jel3ioHQ zE(?)Atq|oxt<1qWYZ1zoMbWBM#Wn!09_~jzd)yj`fcV|nq$s|1E4+R;%u~YC4*OMn z%iJDkIh;9dc0OCMp{-K|^t^RmP#pdTWjN}H(1t|CNcg5cFiWzn!syAKr)(`>1mois z*I9bQ=uvH@o72B#vsVOJt$%B@aJg=2p8P6dz0P zn(ed|f=#INxP2p1SSobXQJ?~ugy1VKd z;}vP0QQ|tfL;>d9p?TRn+4)+W9Bs>wXRYg2i(popoB-1;?kB2<-|gE-k%vU#|37#~ z7)%?hSkuXg;s-kB@X*yt$SU^c(rxBCpxev# zj5a5nKoyK<@?QGUf%@zD$oxBKKW3lidPN6hn!!|QVv#tka7ZF@TeG`d&heLttobC?qYD@5mD(fJ9K`{wr{2 z_cjYHYL!V(WE>>!n@@pk`a@cw`2nJ{1C4GMP=kddETW>%7swW$gHQo*T9jzQzUnzS zgV8(#f=+#nro4i>AB4+#=lP{%&=M?tY5^fE;_MOvghKaIHr0|~tvt-VLWSI{+x;f| z)e*;IUAs5YM5qv!WI>^d9=QPcJ|4&NcI#egYl-qJ4f0Rl77~DOmE8@$j5!@l)tGkv zf2UmMG`|-K${F#BEwQ~yuQ-K+#BWdl6QW$jO<^`K!{1Qg?yjc z|Jp|2BH3lysU5)g6W=O%v^DHw7BA*{o_wFT{K{q%`ems5Q0LddV!_?4byYP*o_HQ!I!fueS; zM#bto8Io+A<^N=YWDYy;V7l3*vqhLjrIJ`Y1Ic07+he6aCR{5 z2B`G-LW9Jcu7gUb+~3L|OAp+FT6bT&wy@3|FDw%dKYYnl7Nu;GBRLay!;w=9g>!ug zCux2fAfc2{GU|?giqax;L6@_)D9NDm_Uap7t$J3bM(SUUb}eDF3&BR>2SG}OWM+b# zinF8JEei_HARUki4L>dld6vSeytv#~CVKoz{$5_o`hX1AR zfdlYrnlF|p5`O@{SRdtE5-4!9sB6AVSPeq}rr{X16;UiTSyyW+sbIp=g(bC8Fn}6+(U`wEbuah=7LHM&k5$Fmw97_DRwMNZL(1aL`4$l7jL zu3n(?Oet_T6CDiuEUSrWdGur|1&7|V6PF^25)@pm ze=h&E*Yx!rWm}+-F%V+H-@8%M+la})N;6J~x&YyIhgriXKEIEVdV?tO&l+dh6eFP0 zn91F1b7tjO1#>incP{f{RP}Z{glx#tvGj^N4y(c{z>*{iWC1(vh75$o5!MKLHjrX9 z0<{{a_SpD~5M)4Jdw4GoDT3l1Tutla);)Ub_6poF$C$p9-H=LVY&_7PHq$*z(I!19 zzME=11N32B&-K4|Pr8lkF4dVFmG#C?u|~3>f1cJxO|@A5^o&z`syvdN`dGomjL!++ zOf`y=glYmqQvSDJ-!IEpLId1uTe45TZ$XY;a*U1j&PWdGf9O9i^RL%}7_my_xB?uW*RZITbXDyyg0T56*xY zHmt==HFs>c%=QXBudgE1`AjA{KX-^8D|UJEhs~t%2MI`*c9Rm!LV&o=_XUh z;LOzffZO%Xjx=O@&A00Bt=>s095{PUY^8#>4AZdKJXj);NfUTq*GZ@H0pu{HHb4?UbH9Uz2YZJPE_ z*;=grQFd6Y6$d>Fs$!J#8}h_&$SNt4hY~R|!+3dla?cgVf?*b+@ELaS6N*uSCX3ax zxlWCy%D9(eY^ND146+EZlGn)gDW3v#^1J;ejnjyrIlZw1v!v(?QE{0Z)C?yop$-8; zt0H)g3FdCIwCiqN=QEfP9ug?UpFWrW?HUjw|7HPqM=sOdl~qoAT?1K#Q;fi-jPQ$G zPi3acOg>)G(2xMQkAo`3KS($((6%Ie`1PK&jbe-K1IopiH`D~m+?f@a!y{`Pf{Zrd zj)TXa6p02*eG~h&kBm$q@z|Q)L7I=+22{rPSiSr218{iFvKq*@o1#_kb+_B}kPO%o z$l~w%>O-7HZM`2xEw-cF(;J%uqndoNP0YoL{x}t&al}=lkw3xm?Hj<+j z%E6|AHLeB?-S7>97b5|t+z%DCq7<)x^a)+qv#RKsp8AG@!-DJ$$QwvNBY8d!X7P1h z(XPQ}zEHQ66Xf2yzQtAz>TQ<}S>xVW>`34+_3|Xch z${U2&+l1td@QN;PaK=l15cR{gg^4tvWcrwd3FwV=U9Fl%vo`3S`V)HIHufZhPCA=!M(=Li0Nk$=hdBa zbM=XM88cIq!3@A+!fEFzn`7Fo+JYQ~@DVjqqK4KQfN1#RMG(gMv~`6N>iKM6{GQOf z4RD|%?Yl1OW*SlQ0Kq-GaPUl#3F|Uy_a0MGnMUVs8RKKgn_9U_`Gts5&)h(x38zcC z^x7!8)J4t~v#QbUnt6Gs&D`AC7Z~mMep7D#0=z`hPqVj3nGCEb@sL*`)^c)Ze!X6mgx^WtHHQwz*fX=Tg4)<*1i_J2|iURTyifm^> z?KF-c7MlM=m08wcoX71OA=OW0hI1k8g3)~E$VE|4yte+qf?Pn@UQs>_F@s5O7rnye$%^ts=(?l> z@E}K3dZjkRyxD03p%0tfAv#@#jl4_3qVc~A?;=1d>6<@7ohLW@N(xb%)m&t@c!<7G z2h@g55|_T^eAjIFT@Dw`kqnjN9bI5)k%9It8}<$9T*ua%?Gmyi^6E4xjdmcm2*xlstZo}Zq+&5$Mf=cvGl13W@FrJgGV|uGUk-m z>gq1b*lOrQ6U*ddT9KXjf>unl!BSM1+T)1xc@(H^#Ral=K}z#AqrJhc9N)sb|B_yV zHjL`>$jR538dUVX!1;~{>T!_?Z&WlZg_mI3nUS7U&UbUSGB=!L5Ln54=hHjG<{8JV z6dmqvr;}UE++O)!2KmxlElFu56$~TV(-|F+lP1=A(+G1i9~Jd+5YD$)6u4RX`VF8eEG8%~He z594;T4(e&c6O0-suRuYgTt{-Rnm~ag1j0z*R+YD4!Z?klV4_t|0)B6H6xbxcY`9b8v7Rm}(P^qX|Gl z*Dc>j+#4yE!wu019rU}riO;7q*LGvkRHO(&*TZp;(Ep%q zY_&Pt;d43QvICg}JIwRC$cOyGtqc(k-i^ORRJy)%jCYhM1!6!lDmaU<4_e6yvBZ{4 zfiE0eju}1DcD5Y`%@CU^U^N4G-lTIRg@W>p-|>run%P1K{%#k1$_Dxc?GFUFXHYJl1+S&4GvZsO@EmG*YUsZk)q zIBzo+P(3F>kc^cQ&f6M@N94=NWYi5J9H%FuO- ziwb}OVTGDQc!DSRQ!6G06^=FuyB~i9q4r2l@q)KfETOo?xS4LmE7X7Pfw#=p-IxLqZcQ7p zZYVd=Fx+LBZBRDJ%(tpKAO1)z22SX?8Ix9N@o|7&kBAE4`MdS%Kqmc6pl;$~-h-5# z%L9xLarG5a!|xQ9v9b{m%-_`v-;Hf}z4(p@F9zEU^%nSMwxf!?biw4v!rb7<^NQzIx)yq^ z%c-FUgq?5hm{ilo68S{urs@yMVT^ZwX&_JRG!ip{nyT5eXvF6c6^z2uQfxrRtaM`5 zL|9in_xEA+^O35f1-W9cO3>}+ch>f}rTzK&cnjglY>4pjy?;H^ME|CKk(hVJJNzh= z`kyNT^RGm#@MF#Ru(M-KLlLxIX_oabQ_UU0y1x>q?zyG9Iq;uWgDwhAOEe&M%iC#e zufb_+^iNPaS_n(T!S>3RWDBu7tw+j(-AL9KlCHLWk;ZqgR;!x{;<*aBoM zpPzkrW#@ag*APFn18wL`@*rmR$+C=UjatC8p`7ixc!ww7E|wvjoT9u# zx$M8s+4{LvL0S-~sm+gd9X@mO#3k+6PjIblVBdQF%Gg?VAl?!A-BpQexK=Nnmv+hrN7stqWoNhw%_l0$_dNk`qpFV zK*AkXEN8Mot1#JDdhV0f)ScKzVdE})%@|y<>yf#w6&GtMIFY#Pc&N@rH|$?&DYQz zDRD4_c0RjoOPm``$<#_jZ(?WVdu65_K!xxTlCRl!nre*IHND>d;-DY@C*ObI#+kQn zcNORnh|BQO((cEv@h`9RiHQ316FqV6cR%hQlhsY<7a^`Kio0`*pG01j1>1&-<7gC& zezV|2S3Bo|L@`eR%f$czBJb6ZO=Y1 zB<@7`SC;Sm@>jp>Ki-cM>4aM49K8D3kH|o55c^dugvN_K*d(tcaZ($g6aGe5>nGse zj9r7?UL-YB#XlueE^?6`b8`jT2W^MOl76NyazIHg~K@kyAAU zAfG(_@}kEUEjHx6h+H8VS#2@NOg+7GXLNw@${IrQbjib?_LyOikVl?P%Z)!jl`@)Z7wYDvf>hJc~IGjg%y>V64rv>iQxj@@c?GPFX@VV zn7NWqnPreyVD$o5d_+-hw3m!W%aW(VP)Yza1v>C zX-OPs=pURO+{ZG;rkUd1||j=9UlLt zCjEFTnfV_C-@hPQ8?+h?Pf%8Id85J!=SZIa4_b_sA>RJ{g#W=2Hd(`ylpdJf&vH+* zsW!LTlaDqgT^8}F}oGS zsZYcb_3y9$yxriJyX{H1Ns&3Ml7w3<#rNpU=Rer@GnG>sXBMX}w)|sfJ#6X2Hr#v) z_2>BG2TPF>%fi5z@|l2>=X7X;0Z{t-;?)t0==r6nA&_IiKCYvNSwf5I7-k40iTLL)F49BRbvUg2?V-GNKzmw;?GsZrY0 z+xX$_#sR;$zIU;oR(GW~C5rgQiD_dCucro+IWM`5)bo@!fDG;_yJq@-_ib|KEQ0rFFR@ zM&;+;kd^cG)jiuRw|?@#=v8{h3yzQXuH(OdT>sM|@Yu^mhi;v~Cr|8>zn?g~e!kxB zrSsnX2d#}tJWFQ-baUUUFLYo#*3z>2^t`6F2w26APw%5hA>6J9%UXkv(~;XLvVm|U z-XbnbEFj(_owvl^SSo`rDJ}qtQWQ}^1RGOhmHLo%V{^4=Zv(`I%j{G|5jYB&b(Q&2L z-GO^`6MCJfO1G=`G&qkUaBwQO`^_h~GxFr()Q_z-E6U&M4mCfz3-&LhY)K06jPsByz>*8F1F8Ty>;d(Da=4En3-m>J0+4D~kBh;aMaNsS1(7g9*qvU68!A5o5TMYr=Lw(g+JNeREEtuzbUZk z*S+rhl^Pdb+lB>q2k7|y3`57h_EqorFPqsCH!DP*bx;s>7nFeQY?|Wa^ar zvEi09^-=O#DRo`;rQN&mlbx$23Ke zF7V|~Bah}UD=HqP&M7ZXq$GU2m5=k=KnmekfA{|}qNQpRp%b;mjLP*dx{zixe^XwF z0V$SWjj<;@Jd|ym5B(oU=N`{w|Nrr8hDmHGYHmB|rrW7+4s~Y^W9rT+IVN={IaDO4 zkwbGPDfeuIQq8O!h7KslkV#A`6N;QQn$aBRFh;+t-+y{|^zg9j^10sE=kt0!pQ7uE zkkG+N8-r92K*NX)I)9&&@&oQ_CIt<#AgP}?Z%j^S&W)waQ$GyShjIr0vQtPnPGkpZ zN(35zb;CWxr%5A%vx#Zn(!Fo(C9t3zhiu4j&nuBWyKer#4fBt2uC^hc_NVKwMeuqT z%B=5oJ+O1Kl1yv4bH>>U8?q?;@lyAuMg-#C(X3^3Jw9F)WB{sMG7HFcVx8e3XVZQJ z+1wb)m~qc+ctQ;(_}@`g*1zjUd4?x;yVQsiO4}XA@vp>X@6w(eFcQ^4(ajyjnKfe{ z+ih5EPfdxa|Ebe`kT}O1yu|7FLtn<)3eSBA#7uq2?C2t>ZJ>yJcWLU8x76|xfs{Q^Js_-6DmEdi8MUWEiV3R88W*T9ryQ@tF&hyrp(&ZLlnVC zdg=EDEhK8UncXVe$7xLK*6dp2b$_2@0_wr!Y0ZPz`9JFGGT~=IwO=F}h)WOv0<&OV?+4qJ?pe?1U@_}KdZqB)f8Tty+X7gSCV+1oeGA%Jja7j~7Gww&+|jJ$D7nUPbUJ2EBid{!b};$b;yJ5 zK$efr7}LJV4|;6y^StL7GV(Qg;B5_DzrRvgrsr_*#1kOnd;-pF%%NDv&91Lw2pIxQ zxB$Cg!Hlv!DA6lI12mHyAvSiDstYKNYFsjpfKSDl1vbVK2hOy<54<7gprZXMrViW+ zFgKh^JN1Wojb%WKgeo&KgxHUzl0G%P+Qe@@JE6aK9}J(0iu?QV!JfL$f8PDy8n&U% zCr4o^GLkJUJM(ql>zKCHAVU6rY_$5?+Vg0uw6kaSva&Vghn83I@@JMW-&1#=${tT_ zQJdxWBq?`X(j zoZb24P0#14`^mNQUa@*6-3IEpUC-X->sQ!^jWMydmCWH8|DNXzoa5o9C`@k2cl!T~ z9ja^;G@mE8_p|N7&in#u1qJskYty2PR5H^tK`Wo(kp_`~#*R_udgUNl=sQY1eyeX! ze!kJXcBzJ7TEPYq-K**KO#j0>&p5aBPU*IfIkCgeldO#cCQkp*l2OAG@OmW2FXXK5 z*%t?v0!JqI$5ge$nk_somn(ZK-2TgJ&zyHX`t@d-5Kri+5a`KL;wC5cvf$@S-sx$^O%r8dmF> z_0(O>dj?QRoHl838?E*7SwdNIODEM4#_XY;D+JQ()llHH++BD_)_VL>3P;1QYl4!D z$1$+lUqDx9fXFJ0ZJ*;cXSegF6J=i}P2ua)JFFZfyb}z}#EXMAvPwhMO6Qelti@07aYN~b zIzjSOHr1Wv=K7R2VA%;79*0s0s~uvnDEsw=m6v)&3lh2ElQwzzdCFBq@_Slr%lhIv z{px12;l1WVoY#3q<8a#6)z60aHV;7M)0;;S6d8^^j&YkMiW(AMfP*29v+cJiYE?BY zbqe&G6p%$_=kQ2I4;+f>#3rsOuxtA#kh`qB=y~S39Hvq7fYt8_yMq|I>Pf$e zqAPCq*Gr%1{{8mxF}KcH4w}RD$T0vKlE@prC9`SE!Ak%9tK|cInoMs@baVI)Vq3ZI zAdMA2^pluV=Fw^|OcLp>O~jylwU}Y0i%qkm4b6%XH>{4?-Ml`ORfQ-~YJDP4cUX)I z7b?DizI(ce-lly#xZk=TC|BMH>@qn6uS-{I&{0@M0sA%!`bVpU3GXbSKTmA7Zk9;v z?chJ`T>SHAN`Zo&d`HXnVYUX-{#vH^%I(Q#j!TS;f*iE8l{;9ycwp_etO&`8gK0qP zQJDgF8l*1(I+xk8Wp2zrl4_!C#7|yf2ix{A-%5X&fmi8tXJ@7j}2*>EYbG_T7qhlRpuw3{Wq8X@ObQDv6WF#Knr%-88 z`Kaw9a_#b&_|>Nc8;?5!ew{|HmNb{=oNo|j2uad3%d2pst#iX9b_nsH&@-@+^U+wE-zV)-^rgOuJ^ZZI8r~{v!hkY z;jOoGR__b;0A@2z1!F#B>@Hkhpu z|Div^00f|d&gEA}E$31XasKc#$m*Pl@FI4@a$riU*mqxszJGI#n@&H^zqofGZvLII z-G2#gF0WcJPc8u)aRj#^bH#nZX-xhAhA_@xy|^m2E}=)&quoHOBKts7S$xj1yaA5n zbv3m1YiYRIaW+%5rR{q8^hk2uRxjl{qabtrmSU9c0^++x?Mzr(T)1snux}#uQ@ta0 zjz;dEX1+TBeQS7QW}VkP8E-3|YXWBW?Jid-;x7C>lC*xV?e+-f>EeNpHKT~SaOE^j zSN0Xxa91q#-_7NTU~yWg?r79JdI)UYI*;9P03!UqrdO%log)78g zb&6OdyXC8StpkYVHvKLu)i_M{cwCSLyITL2gJ(Usx$X+I4(KwC1i})w`*mpA4bdGu z!Xdx~n`GT?j0Jf;Q7UFR`(ny1ob}&+e=sJUpbi5WMw6F8FN149%-h`G_FDuqC})=l zQEkJXvNNScpuix8r4gG^CSF@r@{u$|fp3oo^@c&6BqpC%E)rNpY?*U}1>)~%fS2i} zkX4Mey?(P?t$e9$;w4C^@CT6OFm_K0DzTrE9fZ@^qB)b3DY#XJlm-J2JJKC5Yab$m zb$1RS)>Z@7@L2r;7X*Qc!i;9uV`wfUUuIA?Ft$uxC>COMG2G`SwYK&H9#xRNqaVPC z*Ku;@m|{IPQW-bPx4wZ4I$xtHVe08s&r$q5yY78|PADL7f~tTf6BmR<0&YHysKGyl z`?&+mpr+i4yNTsgTaAqgOV2Zv6y9@!?Hr-f2x!Ud$xh*f)zrgd7s>R#(Pmp9*rFeG zy;upR9i`Sof9GQcCeYPB?8S3HjG@Xw8B;{Cza^h)PjndP!5DaanTEL`Y>o>i!;-s~ z$@ILdbwlaN*qTARJUREOAIov|*#|qu3xL za%o|G*d$il;OL9t7Z#$_CB;7w&JL(u(Uew9QzictPx(D3W;}kSzOeoKW``=-Gv4^h z*Fm`Pf;skIz*%M8O|lf^J02I-@;6zW=6LXy+|2AwEeObOtreDLh;ucNBHP3v)OALcZE_H9^X7Q$3H{XfwXmrTA9RWl zVY849Gq?CkKbDx>0s@AdV_`iB=jDkxjySgIBp0=4O*n|~Sxa4l^6f>^$}d}@Mkrf# zLgww;cCUgpig7ISclcTT%!#xNOB_!P3@Vra5^?i@kFq-)JbTo?dt+PIp*z1bBS!>X z{DBJ52eqvsiv{v<8Ab|KiHvmp-mE=tcv0tC4dZlRr3kB=2hT2G?CKxypoM&!WI>2h(=;&`)BdA z1itKsT0LvEzzCbzc8Ela-)EoQy)RMxKZ5*FFRTI;f6?}sbr*MN3aozoo0nX-Pno-u z0$DqfAjM_`7Q$Qm2b1;dmb}rL%oRSD2(Qm3g-yK(zYX%KTB@m@L^LOzn z(U8#s?aY^zA~!l|d62$CZD)URY}?<*UR*35H4F!@kiyoNgP@Or+IfF2WfU--<1TIV zCWTlUugsqUt3fgB#38gipf#un1%2d$1;KL(@Gkv+@4zqF)ocm z@-RYR7!3vzF?EG_gif!rDLmTc{wnIhj#S?YeK+o#m1Lb4ATAwfo@nrX`9b+wA^Dvk>|k=o(H{#5J9%l!J#3fC1K)_Vl9qmvBRrv}7l z4kjE;+O=TrwC-fd> zEu-QUQF|zy(B%MLzXZjEV|4v)>T)mNspHtx9ocauXf1xh_;jkuSs`+|m07Ky8vtnH zL`|ZDOSPYV@S^JGGN^j7i_;Su(%RFi7_%yU1HMS zfjrp?Gg{oOtOM)nncaK(aSUl{<59UX$_N;c(vZXyC`)H&=vVnLHe$8L!(HAAX175r zL0Q6|8u8B7uI;0_<`cF%L`kb?hhVR1tyUbz*%JIrG$OuqbP*Fl7J5&F06AS}R@L)O zbSycuTUfODi6#U*ubbP(MU;*ovRVuU7bj&}f~pgN(j*Y9F{vzNn#lx|^EbdV6k)OL^4pYJ+Nnk{VU93+T5IEg+@OV=N?1eoZj$Ujx z;qp(CQNDD1Q;AAt3O)+@cq3NR#B%&;2EYd!9Q_PQQxw*|pth$#HF=px4jUUfvb67o zOq<@;cOy(6&@Sm)0A~-os7#qq`eC6BPiLMx-J7mY@g0=fI~w;odWorEKAsf zM5_AuVIG+GE2d6qfFX-Tk_{*NM+a1S^F;74&{g}E z`|d`$Fm@-*&V}%PMMH)CSTTkzO%`^Cz_o_Rt?$hTNF#RjlirA}&)*Fq#*$!>ifL2gz7fpU{H5Tyi?lWcD6 zMebR;5uA&iKyPP5I=Q$J4j1g&3`Bv&t}LresLGl!<9TZybCEGWBK%X5d328ISs z_!eOD5@|{l2#Y2-b89}u2x#w8@rz@ZGX$nU6b@XMWM#BxX^%@gGk8VVOf8{vsu$1;441tl;7iv&zHBOF9Iouu21?$2A03$>O%s21g zY?`g}t(lQA@CRHNUccwQPG&|(QzV?8-MVI>li6+|Anf+dx0kj7J6f|YNUbi!x(|Oa zJ4n7FG=hxvIwgNM(i7n*1(^J=wfq=>L&L!JG!>dTzpgN}P%x#eJiD}|W%!rG90&&o zCc5+ruFk+pz>mr&=F=TZcxbeztbUz%*k?-AywUgQwrDH?hjo}G$P}HYlog1n3nhvC z_xu*KJOi_w{Tl1_n)bbvx@mpFOxo~xet>T^;HF)ccv2#6&YEqXJ%=%qcBOWbz%J9* zA{dM~IL$QL*mT|vtUy%(Bdi5M=AD*s8io{KZEo9a% zD27HFcTu0jkbJ1jYExfR+Tv_lN_Gk4(fp-k3K%y2I(@Pdij71?$5n~t{y8s6%gUdk z7NL#KOkU@BkX#%j0hxAOkOij+!11oQhOOPQ+BD}{hrJ&s3c)FV>nCPlRa{zhmU{n3 z%Qq_19n_$;2C|@`i}|xoSq;h}d!kU{*0epT1_G<&+fOb?#~x;FfOlTXEklf@{y+~` z7GN)##;0p@r&I&k*om~`y%`3fmSEk`2M-_4FE{5^>mIPXwv?~~#a&)yTuLDMFwy)} zzt4ugRk&XAs}7t}!`@C^ zVkUiEV0l_^jeX?MuE*_qhw1OYMObS%UsI#_I3{_Zo6O8nu|W~L`x3q5_iUdq zg^i>aDC6F@SFRY)Fe4hv7i`r*J2o7ClH(*x(8CDv9=DAU^uMUe9M&~F5;HH=nKHt)@rO8&_-rq|%NBA2! zx#mbmXBct2H=K9XZ%>P~95r(v_5BVgvv zT`C$UQ*hs@7Z|%?JWDv3y-@dbl(>!r%^nChtzjvYbJjiKP+z7UH@Mh74m2n1JP&VC z*1+`5S*=-bPtT?ic6hWtyfC25QN;`}d@fS&FMIWoh_=Jqf;COG#BT45@hGzt_Xet$^zPg4^U1Ipi*JTV@njl&+*|FaZNpWDFO0GTq=Hgo+ zo(ev)GVMpzQ=+sBlKC9lQ2M!Con3KjwM=30p6=a9&*=DkyEC3g5*~kmbSrQ)YOeAi zJ2Co8i@o{V)jRH56ATC*@f@b&MEyC3Q_rlNsK?W~yDv@*@GJ=nbBYGHWLjP6Z^?7xRH7rq&O8^1G4p17os@!?XMsM zB0b25-MHepw@c>#iJSq&Io=d+f$5puAzEj{9t;0WP(+V5MM3*VAD>naG?HA1;!|z& z{?n7HQ$;*Bx6l59hTz_Fdnse-fL?n2aAbh9m6xqz=?aodX)n}nBA|tZU8KP7l+R-8g?-eg^R*j5%kR<9-^v0E<3``^F*Fd2teL$O|<-Qyt zIKr3F2d+R8#^Yd$n8p_)10BV$N^w|&r|{U=5(x=Fys@&8W)FxgWfu(PeEIWMXc^q( zrTEBN?kT70JG1ix@tFh!be*lX)Mf}Cr2PUm`Xr9t4LvVhWfk(qru`szE4y$-gb#W9 zT+#S$EGhvU96TPnsfJI2o`!mUdL5rr>mS_NNEc(wZ6h76yx7H2MWR=*r9$MPo(-gz2y#pCCCTXNOtk>Nc7C(WDKBzSw{*8 zI}=Ms3}z^h;fL2M$1vHKrb5jw|Ab8uVE?==%V<>|`t+A+#j(tsc9Sb9 zD{N>ro-lbGEdn=e!-h~USShmruhc2I-7qAh&QUpzBtJRvquO|4+@seQ8 z6F>bR$F^F&5Xt&%Jg3~j|H5;Mt#0Lf1K17X+sQBv^+3RjwEZTjF!1q7PdSOGS#WZ? z0PM_Ncoa7dR!xNblYL&V_w>0~zfD}Cd~<4-*6(&4it~OaH4b9c7oNGYV|>k$9?_G_ zn~%jFp1B%gaUh!x14!5Tr_{nE3LdwB*GoWv!{`QeNPq-#-yN;_Y}2&gj`Y>|E=>_J zML=aA0iKy%NUnTu_T%9WHi}!V**>gmgr1&^(D36pfRqICVnfhxeC!SoZMy@fF-M2R zP=wa!0wz;?mQA z<){S`liJTeCAs@ps4>+G+&dT_r&v$xvnT9Fy5?kNOhU|yK*2zAZ8yo8S~f0RVSq2g zv)$aOHZ|V}7?SP4x2_w?q$7G4m_VVR!yS|72O(BRXadkId-w5-!?iFx|LDd&G8=Yd- zs31CBkuVvkrqT>%9cPMlJI7P_-I%TVpZaIK2h8Sf2*1C|eEeaoa*uL_rGuJUqWfG{ z(1-80i?gOi2Y$cVMhvDWx$hd#$yz3demKYX-97WfQm)Ra+Jy3@&B^~d_Jmmf;nBVz zg6Y;hJ8Fj;H=f;a@m2Y4Pp|DVK`kQi%f|9TvFmn!{W(ZS&1H?^P%EL5={bw-H=Fe%C-A>oa>9*vb6uvebmG5V|8x#T z?gqdVeweVV&BHS-!Ll^Nz(`}MH2H46D$AW$=S&i=K9}1W#-Jc@=y!nPi_>!9+`*E4 z3gsh6QyM*Wi0>BsSI)DX12`x&0~ER&dq(ir&m1=tBmP%Au%+Kqrh4SQMYAk9E|>sY zk7V8`*>7UgG7$@nr{}077z2^;uw|^B@8Gi!#qWbs-b<^#p$WJD7?54OM=sN1;G?Hb+#Y+35J~@cIR}ijL}3Z$oQZRZ$M3m0>eFbv z~ab+zjI{E;$^vonw<&9C6zzRPRGW{3hZ03c9S(pqw5vmUA{C+LOvZT|*m}+dCXG z;?P{nc&gzisBJ*RlQNDt%pVy1dE>pv^7tX+u%4HbX+~G{b@c53$aG-@sN1YX6(1lA zaGaP>d}@>P?uOb2P}TX~U=OhEslF&evb$v35iukZ#AXt9YBSn*YLeLd=aV<}&W)Z6 zHh|CXX3V+X7p4O>e}YSEh?R$U@n6`<2MxQj6k0ruhT35@{;ro@2STH`D2Rxsbny1B zvXpr?iWYs^zv#dqyc@A7#3?Gp%AZ6%I68+@zT!^N-*8x8`CT_U?55KQ# z_-3F?)b;|tl7*dc`>IE*w%E?MC!I;vOqaX4&}^hOWw!Onf*7!<(W#s(CtskMQJB9zJ&> z=T&bdxW{67c@GDNS7++ErPJGpG961EJ)%W>>MjTA*VjBQ$a=W`;3u`@7O(T7jQvP}evs^n5Jlx( zJRY?ev2H4tzrIP(`2jLuP_rfu&Y!R=+{N<3Mt?c_?lUom4#BXuU^CZrYp!-LJ!SlH zK!>cIwFGvC7B7ZvcVd?g_{Y#Kue3#8tmso_V%t%_QO7Fq-4Y9 zF5`G^b@1b?0dd7vMZy0T_c%px!}|)bcFPylpt-pivx^*Y+9qPP*)HaIpHtV=DA!zo z3ER@)X8({&%zMfS0v%i{3;8=*|69+Tjh8l`JRHh|X0YNLTFNWtB(Spng*5LjE8rJU zu><^1`N`i-UE$)bJ>G0R{h6g=errXuGH>;68TZW;-{Xqf`cI)|{0yeNx%O;t(sp7{3^gHnK|M4ut=F2$uzI*063 zNSr3lQp|E5iqwLlI*dA0teS(1E~t3DRaH5;rw{Q6ip}6(u>H$mpdUgVmcp43CKK@S zITsUdu{C~7`lK^3t^K2~p8ptIHiG0{k{^p&MH`_{pZP8&n*P zflD{Z8`5BXxti3K`|kX^#0aH>N1G2wa9`+W&Gt0jgY8z>C2A))nz?!mg9q^Crx%7j zf~M_ZEv~$#bFoj&kM)c{u3b!v=bp$&lwrn>UlhVHS z)tnzeMuy5J$q1+)s$I@I1#h--qtHwEX3lexZ~p(@-LtuJ`R?Bx_aPKZ2%pODRTk?! z?hTgiPycYZAyB?WmHQYeaOYpXm<9DuZmMKgpw6_BqdksrKEBfwc1%ZynCJh!XQ1TK zDNTbXzkp~Xc5rade*@x@WJETU4ju>S7X9ldd-q*>YZ8dJS}D!w263zIY>kng4>sD`88KYJXk9%d|)E0E-hg)h?oo*t68k+#}O zR-g}{uRZRW_|HXG-NZIqO|1l9Y4?#E$+pT$D0SxeE+tTb7l?`?1|Yl;pQiW zPf2q`UZ7{#uojnU0Y+`EO0?>qI}XiIVtX4W4*g!6rHU_9-AR9E`}9jiEW6msKIg0Z zzgCCV^ylV6@RhX4?VJ`Xd|TZ}hQV3=-^Vp>SD$oTsWJ1JZ24?uK`mzn3HPY0FGvkt z%aM|iuZn4ihR{i8qK`S<|7dbL3nb`~!_GVJ&*EwCqqi=w>*sKMVHrZPl4!h_91dlm z;}2=osQq!Sa;MTJV+j#1aJ9BH*sEgsIm1|!t3;Xu?sX+h<%SSjz(67KZR?1t%9RzJjo%(HuydK&q@SD>|WM{CjkA3vH5NjGK;?~*MUq6WK@&RiK&O-PgJ zYT-Dvzy2>WZLa&J_!0KX7&B~JDaY)QrrHOinXrCk{`!XOM_H{y!%s7!WfSjzyy8T$ z;(|r$d)DgJ4^Q6c=o-tZOmOf33;$2G26nh4w(E;XuIesVw(`Ebx;n4;ez_J%?0~L3 zQ)zk>H`i^|F#=g_JA3Od1977d*iJ|O`0tMQ(nBSw;UIe$Abh@CJ@pjOI4L=L6EhZW zrS$p1Uao)6R6&c*(BB-3kbQ9-?+Bj0rDk79gBz!2>n)+zJ&ZS_T_FxmnftwN9(3r8 z#qm#{4jNxFFt8_KzLb~Q1e^~wG`R)(OE=OwQeyorDm*Za~8O`6JhW@sz2$! z1X#cZr0rZkIF-Gs9rTJ{N!tO#Y6%j-L_tp8wZKDpp+UWgs-n;k&|KrN{Iw?i=lyQW zOFP>wt=u=RBawpB3>yF&CJ7vrLy z8%AcJJV_BqrO^KOXO#<29DEmWWzqn|g92<hGQ%`>;Q@ zEj;TuX6bYaTaI-3npdz|lur`Z;DznoRvZw?NbcCFD(d^mGuK`Cx}E>s!p~JV?$VA| zQ^Gm(t?;p(|1+L$B%Xhk(*9LV6#{lI%8l;Zzgs#`W$ha0h#MziUn6D-DRoWf+$QVH zF3Krc%8Yy_Zhx{;yU{)p|J68&Mu8)MO;_LEuS21oWm$*dhcmzhff9F2{-?vYhmkSdJM)rK*llRqCMUUn{uX}uG3)Tq`2?I zAlE#+kGR4={qxYFy~v)uBTHMu@zEtL2K>c$gZQ2uEHd0U+6|}i`fAZZ(=VzhObE<> z=z@F5eMhfz!0^+o-XCU-u9~g?v?a|^?<#I6^yBN=r2rqA{kx7d=p@jz3~Iy6U;e|z z_rO7h3FzWMAz4zt5bkJ6qqiTP?|Y62WAwFsj=BeRrYY%=BhbG6yEQa`%#6 z=g)+kk%T591%|HB^gWw>Bg!X_MM=Qqu9cn`%zgN0Dp6F+%h4FyICDbn*Vnw&!siFA z^#;7l3__#KMqWpMO}VT7h;AfzDX$Rao6NzmHol&=NPjnaR@>22M{b;Ai8tc^d-U35 z9sE(k301nD1qZhHqX8JRQ#bR8f95(s@-<__%-yliN%1MQsyne=b1-N91OQ#f{mu8h zip|--4C{Pfd&9$q_abV>h@~`xk#ap8kTsXOKdK#16gc4%*8b;6t$4>O5lOS`^{mju zEuFh=4hI!-R@7(;)Mfq!k0(d}{U;acQIGQ=$@S}%d}L9cMZ^@KLT$Em((m0a7_QVe zH@GCwX@RMch3t^{B69_1=a`OOJ102c5=qDj(z5Iy+tsqk;%een(3&4lRqskrviv-4 zrTAUH(*^3a`F;g_8*e3VW0*xOY5O$Ce-<`@mVukklYr3*o4un>=7VA_0ojy_+ z^T0T$LnFw_W1RElX3i^#kROR;@wr5RYor^6B@XuEr!czKFe(}hzVftoX&N7G<VQfT2}-vndTWCivBch`qEXZwJE&C*mL8p9 z8`ZdxZjy_IYM_RZB$3Ux$kova>s~8V)q2YKQ26N<$Zlb5zJ^sq81Fy=-GvGL;*oYVvQkgwv~}cOzvkk0UA)| zgw0?Uv<6>_0~vI_#e^blD+h-u>x&?1EPC;j-0&nB1bpe@RC{Pr(3QerxD6&xD}5fM z9Zg@g02YNM3!V6q5efnfP0R^Vk)R0cJT#J7bSReOegAR0fl0UIoln70=c&8S>aG=f zfffq=?Ho>Wk{(X@d>+BuBy}X61oG8Z9obQJx7vacj$o}x3+c7;A; z2`vR6GqB)*#dWt4j0tv8HDkm0`y1t)-8$b2Qr9oAx0bBcmY*Z{JH2rvbc|$D%mS{9 zwWAW{XJ@RI%50CWV&05s4?CBw@>|p@p0O5x0fT#fEd1%Sea@Y&%Jv>>*sfk!rRLY3 z)I#5y=nf?aRViKznv{FE8Ydv~0@vJA++18zeXm3{$}zPj6; zzlX$f@Rjz>pKk3>i)uo^Ut;f=ZtF`!9uh~OQ?=SgRe8;7jV^TNom25 z+7d4nMa&k@Yh=TX4FN3Ef3ttQ0Xp&gq*}^7iN;?5$$X*hclz|X?j3s8p^;XaLT~>= zS0fEPu|2lT5Imv3_4^2FH1}D{9W;T@Pn$6OpA_17+*t{!EY^yDe}qP)v=#x!z@Xq* z&yy>y3PTcwaW@ZvgV&^U!XAp1KX6TNcBtn;_YVqaT$T&sR1!v3qz??qy=fiC?vHBGig9iMMY0CX$N zbALP}c_*l4Na$&o=0E%feXd@FQu`aj zO=^taDEqKXxly)d1sYZKa9Spotra_U?D3dt_FAM)wk1K-nY+D2AdthH6$?=A=yT$(}{+ zWnT>DTO-u+T1}nE63>WqQ5*1&HLP0+UC&u}>I=cMR@g;`@#Y#F3L}D)+6X(wj(f*D4O(A<#>6R;G(XV6fdkUq#@A&%Q? z#F~zs_OOxfChvxUeEi$b{-GG*I828wP%PCe-f&89s0{(eNpYtGb#8i9SF$i5>j4z~ zB-f($^o3ZV^_`%b*+KOh2XV9PuZ0%N2?mC-V=*pI^GR%i2M`_ZF%Pv#? zLU5nDWe|U#vEj_U28RH|D$vS#AYyk>Qs(d*y;Ku4I>oJJ}_K=tp_NL-@875Lfh74;ziDFM2 zqG*9)(Zl^nZjrLH_4EzoPjgv6QCx5~_eF2ka{S6`M`$hP{JiG0w84{XFiowYLJfcj zi(hF-LN*lG&-XiZ6YnC>`V>tFE7ZY-Ozed+#9BD5A5!wHwtPYj;HR6L^)sQE`ZKin7uT> zqkyzbxJz<7XKn+meqYgFAC0v?%wB3c=9_V~8Pe8au&^o6o2lteXt`njmNPF@d(C zz6&Ce+gdJ*0HoPycoY{n-9#`IHyQEQ5&p+^nOT`GCiX6@Ai+;&KkNoTJBjv zZ@My02gU56z+<&5w1=6>GbAwN3{l*l8eut+q~DHz?Q-E&gGOQs+Wes7M`?!`E(P>H z!Va3vE!R>&wW3`7YZG5g_UHf$kRv803mnvV2bq$);IUGF+1oxPLn&6az<;$*C;&hC zBpK56orLN8?z$9zGX$hCHk?<}hO9u58=wPx*9}L69hFgB<9aieHNSSkJjH!g0|mdi zxPCfISN1~!C~dy&GdD@>S5szeghEszHeDdfIb|uifyHCE1PCpxU3Vc2EfZ;6bhB)3l8HjjFW|4-C`c}Z(!5VzZj-M{uM>1rt`Y~xJ|ZwES9*grgSa3BKI&uVGHmeR6IC|O8tG|EH{R&A z?f}Y1I=jP$ig8eo%L*n)jWDS_*^71g-yI3l=6}TF4^!Ca(gGEG_}dU8v{@BI1-N0B z2lLvx`s^&i5yxViUtC~jRt0(`z(zdi-;*0q7{o*yVEA~#L5*sAO|k_gE}%rAdS6;8 zbGOQ;PJ!)Xa3_)!?I;uvzD5<{l*6_`^}gTT!7qBdS=(>&vmZ79OY<1+E@{rS>H8?Fv`CL39v~ zmo3zF5w~MYkM5}|R=&SU+rkNKmXf|nhC_(miy-|_X7R2JkOT|CR}>81GNOje(!-K$ z_(O{G4T%&t(^YH^F5vWLJ>D$2eClh0GTT)YO61_dx;rX$(vz)nA4`?=E`&`%Yl-~K z4I%+;5DDmK3c!v+ph>%h8pLXXVAYNX{VB*Id`FAXd$xt;H$zg&_I@^aewJ!(_<^N? zQqS0f)Yt z((b~C;c&Aie!a8I9D-S-0=P8QyChO%ptW^H^6AMG5`g=EA+1mFniX=b@C!U&mL`1TUw$E+!h{*;ncw+5P^BNVp>3A&*4I0l+wlH2BxEa4wbNF;V zv-(JVhr90^1apbGIJ=Z&g=O-bP~y&SlJSw?oFa=G455)0ofZza$Kqp4*IRg3Su9l{ zyY>a>Ek2h+)nUQ-Y>;r!ztLhtk|CYE zUR1Y){?0B?F;Uy|=slcy7YOhsi_V8ajx||1wu*YjsSQbP%+DndWy;9=HB0!_XG|g+ z2dZx1ZuG~*28xAP%X;U4kLmId$ob_Mslt=TK=hp3JcN8#+62*=m7?kkm4ts|U+g3c zf=n{>nwpHeC6E8u9OgAw%-hfGQ`a;NXK}oxRL^K1&3i|;B=&<(WR;LHO)&G#0f*6) zv`m_>=zA{g-oA{`sdgL^nt19xR*R+LfVIyqv)`eias$MVLG%oyErw%pE;e5*xpWeO zZ$I4HeSJK z%K}#bWwRy|pPol#36+$!Ev?NcHRbKP!nYN}Zbn>i?+0S7W|9a4e6dA_vdApDNi3;% z+mlHH?T_ol^g34iZ@IY-Pg1XaJeJdwg;bud2Z5gh9H#*v%27&oo$~mkPjjs;VE0oe z5fs$*JnFkU>s z2;}ap3YyLZP)^lvmR2!fCXj<|?WJhdc`#9Hs6PNBwZ|^J zp-Va^@1910^DM{;OOel?U}Jt{3*Hk*aA1WGhIv~+(&-X52g+0@fjODsjFICQ1B9(J z;2p8jew04O>q*Rb;0`BvXc=EVobY^>+McjS)hpp3L6w^(qbj=jazVc?+;4vLFfDf8-|GxCG-(IBf7Zc;VzYuGvcL$L79oZe7ZC2l?(OS_ znk4qaX0*6|P#BbH-a~)%Afc0zX9+XQpZGtP&c&bU{{R2)874FxsL7a`a_ZpF#h4lT zgd}I_bUBxDT!cF!$P#~Wssn8BvUvuagpB|!A*J%g$KEot|0wBpa{VR=Fo!m}m z&yCxnsX^-Ea4&e-2I!`a$D5L?=V%u0>NlzWa3PHY5-MzXH$l+14d|eAD1RbGN!({S z;_e_%y}K`Qm4@r+dKCDdk?F2|8l^8GYcSaga_<#Kd|3%EK*zJ#9jHa7a!)27o7Mp* z6y>M5`=f{qHCXP~UG`T#{18CRtc%*{7HF(Wbkqf8F(z2oM{jC!?+^iM+A5Dj!^CWmomL6JpUK<4`~ zSFr!7KSFt580b#veBPM)XPi{(8)ZH^c@|IjM5%w;Pm>lD3r9BcycY9}vuv-x z6{BL*pr9t3n?s~*!Kwovo0{6`Lyc8bH>1PL66%e!^QCjc2E=XU`K9^LUnkxnP;g*( zU*m>7Yb^=1A*in>4Nks|KYM>r(>r7+9uN8eh#I)f$g7SyY;^+uz$M-=>g%8?Gg1p$ zgr=~A8=5Bjbd0A=+tp*oUAgmKqE_Odr ziWa`6@wxISK)IJ4(wXE8T=HIOJQUo5pn?CNQUXcv1Jg?DF$$~Cl^@3mv#s2I4R+Z7 z=(H0l2_CE?Xd!(4VXil@1yht5bz6D)X3@=S5e++nQ?zN%Df_~ACO4XFrHA_CHZ)GO z)Hf><_qn6CrDkVR7kN4k1);g2wKtZVdj!T^(B3Z&l z^a8(h_-<@hg9rMU(!$qyG$@JuKx75vYL#dgA+#MQyo)ECQ6Tm4savvrS?lLQiM71^XMd;L&lRQ&i)e|Cr_Cq(!S9O*^|Q z<2HNTWa?UeU{J1cPS~UgtS?AAJ}PEAK4n`y{9RP4wbWb)Agv|hN3rzeAR;pR0`xb_ zgBn=1=6C|$_W*DP+!BdW6r{KewvH=2W3WYhY&u!rctzxa?0m;Mc4Hw|^nO(n-V5rq zvHeUE_NA`aZG(>zfrTr~(7=O}!x_5P!#9#s)b66yBw^9~xJk>LHvxz#AeN+(0VFb4 z)E~v4%WK|6F~7lAO6q-tr4R>%G_|>I|FCAM1bPr6CkOG$rwy3$SjKfASUP$KM->6$ zNw^gAaCgOq|A>coW4~tCJRkx2p6gFAVeuEGX!pUVEkAcj&p?W?>3)680F|(@ShoqQ zPr>alc`TZS%aH^|A3}Ueuf3ccB=y9Y%GQG~=Bj|k+PVpi`4GKahdat+`S{c&@%lLOf-^bo~n?_9ot!fnJXA3#+_?JKd= zt>fw=g(yy`HTSiSUTVh)n!0%S9zltY41hg9I~^*(Vy5`X-&5bbWeGrp`)Mk@uw_}e z=0H#XxcM8c4yd~DQHSDhfi?;&*DRWCV-lV%0*8a5>41)o7ExyOH1{_rV3Y$)6ei93 zN-=nTjiPQfzWc09%2LpR-ST9(=-hcFq0!Dh)}xe9u+2= ziB5@JW{y<9cYWfz zR&!Hg_yaY^4T};jF`SR;CWAq7C}cbHm2&^H83f{t$PD#7U>0lGC}K~_tNJ5RYvjb^ zB|F0F4LWcOIby@O>yW9(in}L8D>n9C<8iUcM0lOm-^^>c(FoOb7XJz45F79mb;&D0 zc&4vvGzk=&Bk`w?^|u?>+4|D#p4-pyQSD-oZM%*PFxY?vkDb06;>A#)xVi#%lph4^ zhyhJsWbz|g=Bf>FDV%fP^_V?I%s-?>q9N74e8UGPw-p}}4{kOP(9)rooIr^JQK=vC z1B~=x>U|cV(07OA%lEy?^Cp4nks`Y+8eO9mxq0#sw-SMdEEJO#p9SGYl=8xJ0>P*) z+Xnm-mDAp%RU8k84OUa^%*I}>+%|WFZA1R4xs8_$X#6T{Mf%i;zU*uhsh+R8p-wOR zNP){VZ0bG zgP#wXY>OS?&n(GtzwBTLb`^SSSi!l3l@cpU*CXa?Dx9NX)UZFAv=V{ol-u@}ci(@* z1E!TVEQNEyZW-BcO=QACb7_a@$RPWO03*px4ASbdC2HW-7(_T6{;cUb~n}A zib7`BW1h(sV`#>O?RD%;nU3;#l_-%Zw72w7*d)-{`n3b{f4d&7wvW8{0{2?h&)wQb z6mybaX_GbXmPv{?8A9{@@e7k~1;b0m$kL`Ji9SF1CWycPHpfQ0@mk(#>Frnskdc-Q zJjP9S%)KaEz3wL2;2R&zg}ob!>i{D7SEsR7DRVi|^_IgiI6hdnhR8opU%xxbf<_9a zvvM*=U)MX;DSj8M!mdhmw!TWC)q_kVp$`a>n^cXP& zVX4Al{G;Ckl3O9`=WKq9?kG;=*T!gG9uauPVc=IR>lJGsH;P|zelU54nIVsk`~Eif z;qk;DfxT6&3{rItrc};unpYJI=0GDpRk9=Tr|OTigRrHM1z|5`2RXl7CGk=KZ*2Ff zbGY|xCAxV=MlUU9@mHNL2XO7_!)jprSjJ|d$jc@-<@vJ7 ziAEcrLY8u*dG)p278iwNctG1mxeXV4 zIgWh=duv=gh(yy~asKVJezZyQv^$-~*of@b%X#GpnTHi>ARJ`ibqmGt{98EBPt(_n znj-nVcd)eML46sEuAH1T=gb6U)wm73t*P^rQF+#vIeo{s-eDKE)jm9494uFL4ds6+ z-W;b`6umiC>)zDQY8lzo?u>LkVH9*!3Jq}Y?T8br_E~Lnuiu$-dq|tw7f@-BRbWp} z3dRgJHC|`ysufo%i;%LLN%l5z)ssddk=t{5t9E0}K_Ya>bS#$9L{Y6ugj1^i&XtEV z@SB7eT68(Ag1Ieo)Hd;F`}BZ^g`!pzIE203bH!L#3O+Xe4cvIs%w$|blR6aCw(**1 zr^z$k-xo;D9$@tmklHKcR9D>_(xv{R@!GBlMR0izvm*RoNa}ZBJFLA?RB3Po zsrjXG?CZEk#;>TqmVTetqbSI8SRHdE{2}Fkp?iDdZqntVk zu;0^_IvUtG%T=IR2;EMvv>`s;I_{WQMV0240a$8g?M~cQw@G9kzHZ1mV)Gwh+ui4{ zg!Gh9?MMc+&cKw{82 z4+;bs@=O0(O8WDFv$ZqkTFf!Bb6?%?*)@4W@)rzGY5(5)i>j_x{Wztzw8rRbl{-Z{ z&?Sh9n9}usUL>R4%p=aS8g_1d=Wmp|?O}LLJoqAvqmW!{cMs!8mFUgkiX-c4<1YucoBcv4WotE&k=a(O2fn5Zkse}>d9(;OH781? zWOSE2XGKZ$m%asOiC{JQqSoR~3rojKA@XPhT!n1?BcHN@DFUR_)Xy8%w{(XlPf0Xe zF2lHDmi(F0Tkd_S8;?IdAPLJ)0W_4)r@_@-iz<%y%l%X*l7(&(=XQ?xDGPYaXxOUD zo72MP6x6@i?G;A*~8~|76mz+R5%wDMGX(|rG5W)D*S<+R0=yK zkl0dc^|(RBkAoK3Ep^QCN7)xw?$_^5)0V1gW*%*5{$Of984v ztMPyLm{m;djf1aynvGzCWq-B1%D-zWG?<4igrFWt34_ielj{!j&rhuH3de1X8vqdrDv^w?AX>} zSVz~J!j3$$&DBNjU)FZ-p$Lv ztD|#yrKm#B|Je_A14*dc;)~zA&T6(T?=vDzu=%TJzu$>2|8yX=T)tTqewAb6`-1oA z_NfD-;P!D)2+&${3Id@4Wm9ca7$cU{PX52W*v=?>A&;&LXj zeQ`Z}=3gDx!gV#R^V=RffjpgYL#K`xe_w1-A!=%tbme(bq9QSD?g5VfL&MPDSpvNS ztotT^-#lswe_)*1c%!|X*>>$lO>D%wjl9qnj&TBDkT;&b@p5pFv(#QAy>D#xAM=Q{ z@TFpj(0~4UYI|tIuR$b_UJ|itjxXe|h7=s9*`IYY3gBOp4DL=9()zlDYxjRA2QS^O zy{s}qq6&b(p5EmVA@SOA_oTjOWwfxntbFuU?Ch`0&%P!d)rsTuJdW$&W zVzI&J)$O@aJDn*7kbf3sK|Hs+wD$XRhy@|dp+>I?_TweN5l>0BCqM7!Dj zr!d<$kNV|wjq#o<5B6M7V=+-3Ou1bjcWzzTpM-_03eO)4*Uk)%uWK9}1OlZMe>s%p zD!AT)fjjC2Y|AtA+~Lc5G$)`=Q*A?gl7}x(^J8%g2Rp-pQh_H7OX@wlr7Tr$F z@9CDcx6IQYqQTjbd%h+ODnx8w2^~87wQ^nALuz-YG(SEv#y79dH$;6j-euaKk4>P* zsKLrw_dv3WOjUF+4_7Raaoh8v+B352&8V{)HULOlji(rj8jVDK&pRADX3(xZB^#)w zd+3RYyvO>>pYzpNu8&IaKR%U_e2#;P^&PNz*7^+Ruz|3 z?pH_o^O=e=K-q9cW#Ce<(M`3FqZSK|PUY_yTljk!X>FG6a)#ygLo%k5&Wr!Me8*-w zmGv>MWo=EeD(5ANamYc=R>ggYPa~{_6hpTS;%s1jNvYiIe4pOcAA6(D|Kz*2eY+#% zGBjUVH{) za1k)}wp~ihl<1r^Nf=ol)FzZ)aC1Ln)@Qn-kDc|3G^bB$Cu&G2zk7QNpLsB`r2(Ou zqd~TsI9gmR@D%Rbtr{JUeO7X*KG+A9LOH8tAR4?C^U`Y2@pf|6T&PN@k=NbMX3qBo z%aTcti&rzQv|YZ_Yewsv5x20>OndXrQHST}jl(}>+Qep&tro)PN3QwH=lW5+y+*;h zCibt7>o77NvyK?*M zT@95-+7V@q_Nnq1VEUI#PAgC-@|NIx??mN)d>i>5YTe3%>X!*+0%;eVrmVv=^ z2I0R*y)S>YXmH#wPgE9g2bI22J?1lCQF7Mnl033~e>iz7>;>>BVX*(}+>)UNjMjP{ zH7rNM+F{kVtf?ni0=Iw~S(i-TQ8wx#dOx=t_JhgH_v8I7QY!0y-2c_H>Q#o|o!ANK zmxK>DDP{&eLqG)&143d%4{(z^QH#hksvAi_-x6$Npc9l`O^Yxek zTstv8SUNV^K;Am8!eE~dsWZIu~-LOAHCD=D&4wBXG_2cSa2Cvf15 zpOYp#y!|i58i|kw7rq2uc>VIm*O##P)BdaFn*$`y>O!e`pS=Ps(1{-DLZ668F^uMf zIYqZhCQm~Ex3w6uwI5@!k{I^T;_T&sj0nDQUl5|=#>k5;ucjJjik)qcuIrs&$Bw=9 zK9-TH;DtrNQK-KJe{$O9cLdLkkW;yGQ(t>#|Jks(k=K0tg>3Yz98Gs=gNgbDj+}+7 zBifYq%US%!>aBrqN7I{5I=6>OYdN#+BJ63|uIhi)KQ%~~-tiMRDU7?@GUd?2zn--% zxP4e&Bbc@cik!}?m-C;JuW$b}TMge>J1fS_l+{<2w~3VY$`81PKX+Q*04d?Yh~OM= z^4~si)&72;2*J1pVI??9PfKlfWH7RHWaPN)7oQ~#BfpK4-)m1kX=B|t>KgKEqsG^% zFQArRQ5I~Imh2U+c;xnfA(dm zUs4U9Md7c1DnrclA~hF$)oMEeWU(oCD*qb!6-KZkiX3vje7n+>xchYLMjnNL_q^Xq zVr-C1louyE$%`-V?30u%|44Orm+|%gHF(TA^mx)JT=sE80z+ohL;@7jyTt)Mf6-Bw z!%wqGIYdT#J{{f2xhvs`l$l!tb{k#b7+7%_wosi$G9Kr=Jcg)T-BjDrCsUwtSgaL{ z3+L61n(Sn-V`YcwBI4I_*SZqsy-AG_VzdBW`NS-r2IJ&w z$NFn`Q4V#OuF$!W0$$u*!h6A8TPAldM{Ii>MLp?vepBG~<1_=HQci^S^K;OkgS%M> zl8GmIy-yz)G+B^+A$@8}q`PM>!a$iC3A1T&H{&x^QB43l(U(W@#t2LhAk}ms#~=Tw zoLw+er^e$L|4M#}z)by@b!3_INGe`7oLHdgX5#sz|Dk!{r&#i)ZFie>ojc}{$1f3_{hWUR;&-sDz)VZ{v4I1i0dt&8Fjaau)k~a zKUsR zY8_`+%Lp`?{FraEnp?z>f-SxBo0Zq&xU(f1gR&;`m|s)c6jF-G1g-y?Ndr2Sx0oxb z(mvUE81Xno$L%RKoI%pY>9EqG4(xjgfOoSvDmQjf1$Y@NK5&YI?QA+ zHAZv6wz2JZ#6`QNKd+21g>tKdzeGH1v!1iHaadZ8%N42MeLNr?y)n0<+Hg#@-vtZL zxh`^QLvyMl?nA_d#cgf6z0KqyI~vf0uefpSi)O@=_8n_IiuKs~L-ARZ1DjX2&){%% zQ^z1(8w9dk=_E?;qua6#qZpN(0CMs1qXta~ukQu>P1^#4&p-giB0#&qx-{0}vYGi< z5ZkL`=wuDveC;*(z%v{KpXka93u(`Tw$|3P&z2HwE-QxI^T{sSIRn9}aDC`2!f9kTpK4OZ1ofbu%v z6-QysAPkpes;DM%h-1omr(W~MLEpCP`OuJHMiz?l5}uCN698v~Ri8i(g=IvB{-PXW z`&+n8*lB;<47O?4iK2CX%unCVUF(F~8t~4ri8L`wcJlnh8CPvuU#AF=-NaGwlFx_V zWH&HJ&z5P=(PTV?&OgI1iwBAC{Xr-csao&B-c5cnOkM-pC76RdQzQ!7^@Fr@{6x~f<;T~D;PA~k!^ zmlkD1Fs2L86NQ7Z!0WjP!Zw4cVyON&cB86k6R{)TC~1f;4YsL8A{4V3K%z8(wFk){ zn5f^Gxa+BDm1rn}sn{@jFnFw{s3z7EvhM_H99<0-Vj4+eWM9yJ6CX@@ul%0r&1++%xQzJ=h_VXG_nS2HEQRBDw(udD&^jv{6;mOaK z>O|sa?LjzTSj$2>(s9iWHefVG;orT7vu_`4VDam6gbr8!!Z%z#9Xy8TO6=F8-v6{Y zl@k>!mnrqI*#PW%Y}>k?vQmtm2Lg^Dmx0UsJ6n_33N!M;Elh05iddd)H(b25Bc{Ab z(`2`(8p@GlQkA=sgicMIq=x0O*K^#J#ASS4f6AlX(LT_3cU`ndtotS#@=V{J+Xiq? z!O30ppuBfBGQb+4j&Ns=3c&S(AV3D2+w~vzQQS);TBboq#q^u(SzKs5YI12Lx=zgz zSZCJ?MReqNxC!nX>8LIr1COSutVSZGxk~Ydg!Wq3(C?EyHhnPzh#@r*E!zP{Mgvb) z?BfP&YgcX0qU_MCry1!*Lw?4L+68HNbs{I23#e)T$ozuKuQvc=$MmCh=7?Z|vyk8O z5+x59Sq6EeO5;9sh`cQ9z%gv$Pg<5%)Rxnt6R&wS0z49@tHx*d$L%LIT8k{8z0l+k z0O{E-+D^O&9%7(>#0Vr#02)Uox156xA{6n$We%rEj9~16l_HK36l8+22ExuWtW_7~ zSt_Zr>~|i}?m_j6MOx1+>~JGtuh=K0s^2dn5O*V~LqpW9+#eh2Rea4#e}v5`WwM+l z>oPnLcu6{jO{B30T~xct9|*#s`MHI5a6o>4_MQ<0^2O5C(9-H?>4h~r7>gf7N8XF$ zFkQP7@0N{UM5m}HoQ~*Wt-Y`AV%%uwc{F<9Rl32q@uCl3E`4)0kBg0mwjI2o%6&&DTqV(%WfOM;6f7qeazuqIfw>j(P|RQ}P~pT)1GHGS zR-hrkX>#Lun52B=kr03!{4_H8kwIVnudXypsQd>Fqk+z0pYe+F3_Bhg)7VWx?Yv(* zNcmNO9Zk;Zv1|*6=l@k^y5OI;cz^o zsbhX};MrPM5+(%ML_su#uaUDq<^~1|`{Jl!MaFK`G}%q_OdQxc$mDD7@7rxiyQHgH8p@Jy$vmL2CejW7u4-7bOr- z(!=tGjz;oRV%B9o=Bdnlp#&14s2KHU?-Kjxrj%ja|IT*P7SjDZRa++6*P&k}T8R^o zkLF*kUoB5)Qsbpkv>fq)YA_Lq9rMj;l{9gx=gnRS4F-JQb9Oh77`54nswbPHeI8iM zeS!A(8iyMBOnVu4ZOMuos8V_mC_Z9N=q8y)}`j)Yl1@B#Td14`P^I zSse;wAYMqHAyNG%84GmjQ3`*Gabp8-C*ps$9fj;$TPpC9n%m&9ngD%~Ea|+zs+rw_ z2K$x?$1?4DNW^K4-(v?`e!cB7p~?8d6}wP_26$XkjBzG2Lrh#|Mlg8%H>w_BsNziI zI`Fr2`!a?+6Gn#>Z7%M=4K|prR!PF@DL#`aJmKf|VOx73^q*(bL^?p%pHF%DGon4x zk+w7Q*cYl#xG6aM^HDheFUxWK9!G?MqKT0b^EmXSiW4pE!`ir}T~(I*yxbqCT03HD zWQL#oPb1;;*8U8Hk)2q0pI!M9r+~^e`_N)uc(Ea>7c=tyBN{3DI|Y0B@Ws(p zj!+8Z%($i2J0339i<|<2ovo*?)ubGoqcy z%qNPD?2ti6A-li4(BYkcv`hqJY9jiVW@NX{DfP(yksBHsnj1{Ce6j9w|6fRrPpBEk z_C%s*X#iGofwC8V5QwT7hG2k7g;Nlvm_PhA$EEV&+aN3AjNP_@)#g#N*%e91bRL`7 z&K+Z6vJM5)-$f{z>xe;FgZoF5ZHEtJ(^f=71Wa(|rw8dx`hx(zNue3Nc0}yGbV&U| zK0a)t=ScRaSlJ&6Y3{2ogzBi+<4|s}UrK6f2LuHXjWv!vHod~ef;#I`&N2G^PbAu@ z!ZHY(V-zE?r2$=Ag=hQ`?;={6E`OvTzgBl<=Nr7=!&|i}@GJWU$&p74q zaWPD2?G-uAI)n4q?vu2W+I?#zlurXMB@)*Q7;N3Z z!Tk`Of`|8jAMR=c)YiGwAuEoK^3ed3O|ubqkoDo3-oUcp;Bfq|JR`^kX&5Wp=dFg5 zU*dxbH1T$`{2yFFiR{qqyw^-FC46^$onRri3Pn7I?R)|uE$b(iBg2;R1*+dD@@tV? zApR||a9ya<pbmBBkLQ&RXH^s`!$cL5_$_GB57qoLX zA`l3SV5VTN0$#o21V}(vQK80l1}bc*C%)qwu*ak9t4;)(azrCBzW!SMv$Tss6A@Sq ztiA6c95KhQ*pIJ=Zlc<|40j4`T=fKC0Eq#Q)&LXrP7Ug{?U(nAT_JWoZtB{$y~F=8 zGnKxZii8wr&%l9Btiy}V88(rs{*87Ak!{I9wPRq+Ua;o~Ed~%7YjLSh^yN4YgIu~J zJ4LicQ)^yFtvmQzPx%uF=JG(3&Qk+ENo};{Hjmv zu3RIh3T^6pbxbwzu(xpD#9c2r?E8#A1_vnnL>`~pU12CQhqtE&@_%2F28g1Fgm9hM@YI@#))0!==0Mq4PHw7ryWX48dQPoU8q6~u@vZDGn) zSaF5bYV=SD2aXw1mo0B6AaM&qs|fg!l!2at>`eEKhDu*Z2AH{mdZz6ef!W%v$sZXv zRIywP==F>=MFM4g@*%a8M52NP)5efwPmkdWJ0ruMQB+k?8iewRyO$OTHk~YC7e%hh z-w?^(%Ckd!MgV%p{wCYc+a`O{y~TJFKWZaMCenn{Uf2!1`m|AbSYw|@XVjmQ%VjCKopVG9!wNj}?bv?F-yxK7Dr|HpMN0w6dB)!e``YjAPA zO2qM`HaqL=5E3=AGor=c8F*iEL>2S{t;*$HLH#>g-{7ufOaUfc^;qxW@{Y^nx#)e# z4=KuC3fAmyQvxId<{&@0I|SohbH1YDy-V8geOg& z{&xHN-u})tNq?JY!f;Zx4cj+UGKE0s+7)+ zOQ6dvNB*LjD7$Z=L^3R0^|d)B2z2LF_3bnZ!nO|6GcfZ$b@>q=P-Qa0{p9(TuGw8r za2`B(9pVY(7=KzsZaR3tfe<@|-$&|yTaLmA@|AgWj4T$g zONndK%nf()l1Hty(>RK}F1q>GK0dcZ9W^=8q)j9IqlHz0fj|M_lp)FCz_2quxD6RR zDLj>&{t#4VQ4Uih$80$j5F90#qOpc%o74>CiA^};JY;r;QXY(!&^c?$@0^Weh-;qE zHV63B}cc#xB26Xs_>&U^YXB=r{Yqzl_&4 zdv&GU3MkxCGF-@8f&q2Djqc!FPPl>52wXU66+ACJvH&?m^8&^3RGMj_h)rH1t`}ys z#aQ?p-Y#RhkT19n^#s5MV|%$znD&_RKH zgm<7!TPu>?08D72m6n9Ok-&i1njSZX;Kr@k!C$j6HcTVxQjr0CwEg>;M%%)zj2#}G za~9+PtMFD}pG@|J0y|o@=@g6W?w_5*moq!8@w5&p2HHb$ZLzH&fZPEylvnFz34Xp>8v1%7vHZh?l{o z=zh%s4UBFvBmb7eI=Y=cm7R|F^nh~emTp|{^Hs}st&3EpK`SWr+scxnx%$22VIy#1 zS(7U|85`br#YasD;E*vv+DVr5(WPaY9x3Hex6oZmtq9xd?D>sC6`i1Puj#NHF<0}h zAYKeXJ>N;!GBUM(VkHKVFA6leT;_$aNI~*RFo^}{iuvAz4z*1c`fF%|Kuj5g89>0AzE*mwIkm4!qtXR zmZk}ET*64ia7nPSlwW^%TeFc5kUUN}xO>eQC{+np?dN8zrv#}cP%nIEXOP5@7kA>W zJxj~Z1id4+rbs7DKRP(M6opAVBp#NK$m;XK zkVB3v*lT>qbT$wG``>`5!8FkHY6Q`c!7Y3U%mAcQ6S$~)rVMFJTn(mMuXOHA0|XLi zzSFc`nP7xSi!$x^o1-hajUbTPsprt?yM~4QPCI++eJ~F*9)WX(lQYIC|#8u z8jJNsxWAmno`DM3-t+)~PDLnX;lPD+c;*v?bec_$)FRDM`B>2ACz^V$is$c z7>pqda%lQ$AdJD)5{1H2?Os?EAS&IM;GoJ;rOw2N;rtbeyTN2M@JMG@2?7ysp#&@@ zLE7~M;mGdFy6gY>90M>Jmf|AoTNTox%l8Z{75h#5v|qH0P5 zA5-=mI8j;DyfhS}v2gXv+)KYPEispSboJ|D@-NFpo1^_XkdNHsXTA_496l=dILc4T z?FjqQb)0>Z_TA2b7oT8MT0#lJR&Wlqy8k45nu*@k`V>RnJXdlmOPdhPwyK*+QMR+( zp(KO(1eQyyY3q)>%n#1La7__mBO!uP0cX@LAA>A)+u9Z7t%}5YHcU%0=&1BefQ^xMrkQm5&Y>jXUxqN!|WaTK}j%EQVZH0YzK?7EUAaWQfV^R z?e|GMLKqK`{zKhP9~by**}(wFH>dIX6_=xhI-lYuI=w@M-TTPt_jj~zj0d*`B7O*+ zdYXBa8i_XA)CYL!8HCW`77wMe^#`CWbYiCl8kkDoa&~1t))9&Rek$VqeFkg#{Xt_uEvz4^Z`X-{s^j zHm;pL+Dnlu8ID(+i5YcwQVRD%$7p}C&y>##cTAX^7a{LUJWmdB10QyD=)Vx!sq^?1 z(j52=AV877ofaR_49->QuuXL(9aDylCAfg+*@LL|8#(Pjf%! zsM4yV(m*M%;k>gFle(n8ZWM!G`pZ>cfz_+$K9be}m<&#-Dt@~&?5n4b+L&_6w?cP` zD3ogTHvj#h;(qMqCSBUkt>@JpiBI=Q-Ezxl8a000VM^cBq;$(aY!ItFPT9!w9ttte z=J!?;Zw776jh>5tCE<*TQYP!(ot^C%CRiW%n#Hpc9k`e_S8j*g3spouVjIM*l;*bz zUdF?=cHp<-KgySDL@!n7r~of7yleUYJ4&&OCTw^xU?SoEUv(hUBuf3!i-wo^6BM z{Aco>$}VBDrrP?=oxHyq?{2B{Zh?S%V!c-R<|89(80=QX5f)1Lrj@u(6uRv{r{QN# zL zpE5e)LwCs7)h#z)#xjQFBy@_R zX+U(^noEVrP}GygHJYqU#`@%1)Uuq;_Ay1%X1poqGwi>Km$TofroI6|Z^&IF0)VDl z-{z*sdL7zJ*LGaajFg4CLbLw; zVZI`a?Qh8MeRb`hI~UZoK9k-qw`^s&Eyp>DI&2Ggij$h8eG5_X_-<)+YiQ3{!x&!j z@gJvfL+y1|UeYM6Ec1`dO5|CmcR`0A2eQ#H;M2``lfT>WF-9zxP^R&1lk=q7w7=4T zgUA-1S6IM#tv9xDDomAWtri~B3&r^VDVZIRR_8OcpOgoq9eUrkrNH`3H)>wQ6Q?pb zWo&_X95xnzYQOm*Vs*WdKWM)qJxfkrEfyC_I4H=sOGt5hvmh7lSNg86<$Z>W#kS>b z=+j57rp6>%I3;Ru)pdoAtSgD-Z>QR#`}lC4NKTaF?!&=zRU;!nzTZ!Z6I!jMuf=ro z<}_xx6^FxRbf$nSx)jA;So5SPeOCD&YIR5SJ=(=eV#At~#C?^^J?@z2$+q*2`d^%2 z`tjjAX_=e_V&a8&={bR>Dv-;#ZCN99SaQFI3aWLgerAJdA|1k+7Yza4QG)|l zm(3=qjM^$inIX-;ymk&Jd32IE@9;jABbxqy-JSiP_vR;Qsa-PV8+8C%pK4uoZvIyC z;i{1s;!k$r2=S_nW}vt&9JRdmtzS>#!Dw!DITlTI_X2Ckp|BT07fxLZ8ZW)spTU2? zn!*Wq=&%=~a9q>GPHb9r%Ha2`jLT>7;sXg4p^jH8w=rX$-R|SrG%A#7W}m+5fAIRl z`(~qW#tAW+R#z^|zBj(2a#F-N!pLVs)5_24Q4U4z0lwR_)+ zaMH`EG#ZQZqw85j`lM?^`OC8hj~>+4#XL6erw4DHBz(n+ksf@AIU^D!Cwd)w84+gl zHLmv+@5Jxs{ch=L4^`(HC12>|PW>*u)>6BCZA#pfk6p7fm0fc9Ih9V$F~ISud?KjQ zE*vi8u{P@TY~NX22c64U>GbtqDLsAahn&IqNqG#B@8SEzqwCLwi{S&WVjXO>im5aL zf|T4vQGWYS{nEwVqoeVHQi9mkBQ;;>_t4KwF`+K1%}d7=(Ch3?BK1q;L(na zVR!9Q)FJ)#4>CVyN-Co3j9NdbZ!sDsx)O9dru+u#m%Xl{y`!0PO3zC^c3I~ga?;@+ z`61Um-b>EfGsbzGvEFc>wX{^?**qyd8SljBG6PyEDi&7@=7SpiMG}RTwK2XC1xjHX zL4n3Lj~CaRbdu&8lu`14BbR^jpZ8{8cV_D*5^cc}cI-E8;GDw=`Wo!V4_d;LwyF=O z1G_#B88ijiqn^GJXvuxSI6kTksz|KfBoR z$n~$yf57$j?B5MBP%BY)$s-F2}7tB$^q9^BETTVS(rKo1ZA$fBbVwa$Tt| zKWLs;kR5}L%HSgc$~cNLLRvR0)bDGL#+(aodfC^lyyC+kuH#u#Fb50fCKt}$ZtApt zb^{S!q7CGtjVjuwNJ^utcfGwZ+27wBH@H#4km}aXX|gZ?hPQ<;4wb<{G;ihA2W3g! z8Z+l&2`u5+ygRBN0Qc+XTv)chsqxRDZ% zm;$76g;?=3k4MeCFIQU*l=WpQ-1<`UhGT2(e15>`e#9z|5`)C$NNHUtyZk>0aXo?8 zhq1vG?c=oFwN)o&%yloxFTHB}=kfEJq)EgzM><`m{drCIlk@#pgPtG>cH6N^Gh(~C z)A0iGzn$qtSWiy8MRV*NI#f`}zi>9-_~qvj*}Ih62Q$5g&`LdoH{8Nkp=s?;rxH@j zUT^jxGYKy}+hxz^T2jP*TB!w$n$3dcD3F)9`m5?eHhBdAT?aSB|0%qGaoteIIW_RJj#dvpr^NM& z(+vw%smjqUW&AuyU5aD9-WAdN(!ZE5&7uh)n-^>5h)^?@kHy5E3K` zK#v3UH6aszIF}Y%Az-Midh|pVX-L3P#I}s-6_@8~s5VL&1~~*Q1K2t6FBnr)w$pV5I5@-zSwS@F)-mPa{BFj zTKecy`1(&F_xpz>PnTV!nm`l9d0u|h+c2XG|3W*zk6FL4E}mCgwYc08khuzbl zQ%5RpX=&5v5XKa*3YRXF^7-8%NxwgaA!-f7e--~@wM*m`OCiBWvAF|e82%?H9WI9J zc{(!S*}!~4xAx$afmSowdP`PX z_}qrdNnNfcb%su#f8=cul(&l*DbvD%X6vU6&rtce{PR|L4}s>-~DaUeCwlaeq8ZvvNpOib}7CJHnLr)WaE-PV1!f z^L14s)SGMb{H`&GsJ5;7vyt`$<;qKC8S>xM)|qV`KYu;3!?E#r$ZaqCC8b79Wukv~ zLYShz=&zzd*D@W$%e>QfT%t*iWR_*<3WfDgFQ3P%|tsWAexe{0T zq0derfZx12_8;gNB-aSz}?0 zV__a^g?GY4XbYQef;sFWaJt|)WPFvDW%J03A{>sO17XQC2;$mZ>v-9ey;54eYr5h8 zldH0`xPlPST?Tk8d1vJY94N+t;x^>~MEfQ_TH0WmFY`6z37Yni?1?zwT;RcQl5muE zoFduh8h7L?&ZOkAXS>Z;7Z(dW697u=fuW=lHH}V*uVB>p(Gto>FCcf{V^IJOiJD9Y zDUY7WvzQv(0W7z=J(oBsI6r(c|P znmLrsCkk*|cGCh*5o|=WWvt+bB_V1B*DGHJpoHg71Kw2R^FAL zqA3DGl0qD^eG_mK#75cCLWcG72kx@ELe-18^M(=e1&@Y#y=Nxv#;@Es)ktW)S6>=F zaHMqe)XQeo7H-hae53QHZF*aXQ+?Nex9sw@na6nADEiATEo%e2Xxl#rPaiRM8-5te zTjIg%Z+~vmYzvLq_U2PTy4`p!bDqxnSoGzXTYSg|&1*SF#3lEZp2gK1sLlUGCvGv? zC3)k$Io?1%O5ykT`|mxl>JnQUbj|(cYzGYa{XS7KQ1eWg+AR$KHMZsOpMPS8O+x_g zayiidpg7lPt2*r&tIOJ}e+CseWMa2}$MsL^PEgNJ{gLkVXdCeXC14oVicfuI5V<`$ z%@TnZWO@ytmeiqoL`)8LkNKmniPD^Dk|0 zBUszlyp4>zEdS$au*MO%6FcFDk90Zb2;nGq#m_P0kr!gd@I%&6`_m5j&dp!EE-AFa zR8Ii43Abkn!8^IKNkXB92JCC@a$r>d@d?}*H#i}sI(0Ui-4o?OjDEvK&eYmK&yE6B zc8*=aNWJ`(r`af)Ac&0EG-z)sHyP>5`-Aq>>laqjtg=Nj;Wg7_IQM)_FIPAJc6?vd zKBgF;GtFwuR{V@>A{f9n?U-f5o#(q(K3X>ihtc_YH(i`dB(wmt%Xj|z`JwpP;%?Xu zuVHeQ&Yn!v;!=6X>3~+R*$SCu^g*DC!r>Tmp1eZ8m2bG?ATL;*(p#JeAO!0vjQKnd z?G)eAXCKNKZQz6#OD8<@N3hg0Ufgf!7{o!J?>2PDw&MW}uby;eQsKAj_!pE3SLWI3 z_&vSuV=l+b9g0$?(9(C8;C3tHqc}5VxX)ChUPfU`vM=a!Gv~J;+3LySC#KSN!~%yY z^uh_GBw)xm44N0?1}#z+4MsA0sk(*l1sr&@#Y-q=D1|b3V?f2J5T>Oj^YlLJC2_lo zcuz%(oZe{+>6!f)>ig9uc9eHd$#uYohiG;-bPLF*pApqpb{i+194ug!IF%fLwjt2e z3NbV60Ul|@@4b=T3eI#YQAT61A#y!e=DlkJ;$Ojd-gV@Q>?bjv$!dtfTR9=n5W*Yb z^TXVt$swk|K`&jgs2wL=@&A4(G9(#*S=p*{206q}z^N(87xdo7d&aNdtLKq!xD!t2 zkM!OcIzwGACOGUgq54PmTaf8f+SW~4Pqz+-=^?i24=_CZ+}brp^%@z+ z;y)%$9{%c1cb3cYpeTfkOoTprA0N+I5Y?e_ThY{G9#=+QAUqPlS6a8JQvv+KGuD*u zT}h+fBn7=#UJ=J1v-wC}zx`0d;wYs1Zi;Z$+U}BB&66D@-GsDJoXFKIn`XA;l?-{N zpLkQILq#ALD;w1(^f=DGEJ#GRU*J{9B!s7{BLGukTl343YY=65^=yeX{_plQ7>A|~ zsn&GsN}pL4r0`k`m5(QtMFYdDu!wCA!__rC0F11m9!Qe`fX zk1`>3)lgZh{F{=yo3@{I+#cOR$`H6~7Okk%TJgmZ9XQ$SeNoI_P-i~KoX0rHeoIsVP4v?-WBV9pnkkaQyYz2^DjAiyfOOh zUX^_o-Cq0Kad+_XEDFQ3bnWgP-Y$*yHsMu#e7WorkViq^^4{3|o&_`sotyHU=_kT55TopZgK;tjizicbE?a{ZdwJe z!6%dZ{EBInV)_lIrU}Z2*sF=BdQy&rSQ<*k#q3wRnWgIwA} zBcD#-_0eIkochzM2OKvfUTE7svasT8qNb-y#N)3DQU5GkW5udtB{q}(+&eI) z07;<2vw-Sj6J*hWU=8V=pQ#8%>9l2ce{}E;*M`Hd!Ds8zESye8Hl;oGY6In1rJf+8 z^4f4TtR`Iz+LH;Vw*eyaH}M}(?zpDw%4e4A>#U0wCUwGbCYe(ONII@Vy0|fNO*#A; zYQs=0{YA-|y%C{B(O2SM&k4G~R@a|{T&w}gM7nV2v<)r)@2O--{U`U^@l@Q}H2!<< z=$JWz;RV_~N6~F8u062CKk$rTRzuQn3#%5J;}1eO>zImQh(G#w- z_U$BZp2t5qc`*G{e%q$e84do5!guO4_hbhd39y{|TTQdCQu@&u07Q6YY9lVHbbp`k zB~53oE^Tc&g67*5|F^wr)f6~nR)M2uuZFz{#OXqEc$3uUwEVRLw$jZ0^QSVU(`Tpf z64jkiV+obr)(KE7a2&JWAU7QB#K~A0ioTDCph&0EUS?B*<(M3a@}pc5kBiNO@LuYc z4nTz{L!4hRm~%QKQI&u5>h^Tg%Iwn&+p_O*nB(jq)tG8~@qCm6#r;DoZV{E?**D&S z=x2t?P3qnc*PAX%SU9%ENR(aWR~yz)tiqQCm}4xwX38V$EiM{ZRqftw>yDggj7cKA zg7!RYcnGd4ul8KO_6A_P2AQ^3*xB{@s}{HaY}2cG0=c*s^w7&@ci*uYMWw`lq3Lk> z=%mR!`yo5>Inap!T$k};1ahlN%SX@#624{eZzPJ20Oq5woDHBP^1#}@vI#eSNRk1R zi^Q$C41tPK2woRk&pCN6VIRqKaiI*3i2A6mivxUY`hGA_*XN1L4^EnPtNhIaf0wTs zpf@7V<03Y}^B#!A0aI<|Xw?hl%Xo;?Asl}CT||qokp>AUG#?0 zkBBdrxnMamK^V#$c1OQ>aUY2`XCWF=_qwv-< z?eR*^(06ZmU&&o(Z+2>PgM6tXpNb{ge7fW`ohI#wuQUzKr_t}p7w&|jP|B7UX&G(1 zA)eD|H@|#(v1zh*Lr_?Q8BR&mOu1V-sJ;uvlP}0CWWVs@LEYPDDppmk)ih(FQrbgf zyxvxBxx$GprG%F$ zqk$h*`JY`ry+loOU+#zYZ^dA9Qsm%^%-E1#p`K?UoPLNbhZBIuBWiERjJmp0seAa; zu-C@{HMeoebd6EFp21M{uIJSxlQQ5?Q0=DFv%9`4@(#eyZ6X=VTPGlsA@2Z^IlyYC zXh!Xezz(eui0)80mKbM>`aSTr!9~oTzvij-D6+zji%$f6773&4*43BujmU1Cqc@Cy zfPwcM7ByL5{!p`Q)b*tBk9pqxO&3`(O{hYK5$%MT{pFCg1eW`Ak`Y*9XMxkZ;-J}8 z*LokB*J*B76}mwVPBZ=?Hmf2NPa8%Quxf;HoRw7wOOjD=F~P;0XT^lqgEs}6Ot1xJ z3n-LbxaAdDRv9*>= zOA~uRWLWHiNr{x5%I{g=2RnE}n-hEwE_7RNPyK*pjOVTESf?aOLnuz=qz> zA~sIhzrw|QAn9h9Sn!!DHZ<0NbRhZkZEOsym8-aHeAPe^YD!Td_w2 z6GysFpGqPU1^BKJ_#fPm`2a^*pjwtvUM%9vaOTW|sonn;KM*EdW&hhl9Gd zb1WNA)oFm~=G;bC75`ith&&lAhd%%2)XHDZ@aQ{E+Ft&&!bWIzYRail8Kdqr0~Tar zoPu%~m03qcsEV&1hLA)4At8zw12W{Tn}|}fQPB{Z=#Co}M!`<;Pc#>1&#!ME z`s8}jW3epSs&Gu=c%fCkXi&ZPF#@H6TjHkz)1mRR1Tm5EA9OtL$j&QeU(g^%Y8vAu z_-ae9V`_(7n0!h_wPii0t&vvGlEyO~0VM*F3XGR7wyct;y;1NDqtory$-p?JuYCS} zf#_MhSbl;lhsZ=p`Ho@gl{O)kEqH+cr3b{cV0VhI9uQi?ZUgI=-gg zzxwSQ1bO2G$a29O$Z}{N1bU6SkDEDx1FVaYTB30-3iP*|#5UR!mPK-d&`n2zH{)8r zG3H+x4Q@J08J}+T=_Au^CX(M~skhsQ3@nPiT9J%OhHMZB<}9GCoWMz-S^mntN(V*bQs9j^S|8|)f+bD`F){+Y36^owtM8a^u zEz}+2jk_6rDLBU=xg`ITTz$}FKrU7Ix!6TXyAdk}MtPf2E8t0Ghf26+-&;wXP)PKMwB;bM?obV)evV}on=S#E$Ch@=2<9qh zhdr-jX*ADS;F&n8-);`!oBxB<3ZwCmLm#<+E5o^`V9ju+5K7SMy@`cGVOp;s%WEHe zUh589pfH|kiZ%axSsX_z2=_I7uybC`F>LNW&*MTwhT;__L4wA;&PW*0jDC?R8>z6+ zC9Sx)kJ5P(I;avcO&ijlT_8C4WVwMri0O}9@{UifTXi@%g`cN&j3-W+a++$e30nb1 z5iKtYG2Cn;Bc<)fg4=DeeDHE?(6pi33ZI(WqUY$@1UeB6EgHzQ9ngfWTzQsHrSzjx zQhW_@_A(j`_^u`cny#p4QXM3<(mayG-ryvD`406jL)HVs{2Dfhx5?WRF_$bMPlUF0 z3ahjnWAPPc#CP-_wvh{J%iH&jGF5gFLA+qQi!Dw6#Vp|ZnU2khRAG|`U3J*;0OM95fPlnE8sdiKd+W@aE=V8tF z1BU;yZ`Lk?YecfVENY!;0#T;-A z2sn+C&d1=x6n=VTDDt&3g?!StnKup-e_QX0V0iv>6H=vpj|JVx#UZ-@RZcgTP#J|g z4M{UagUnrt6N$1{$O%dTh^ZJ|<;C)pRb0MlD2+~`{Z#lZrUQW$a&`-s3NK(@F@lH9 zVVQwj8b);y`w!I@LD9*I&n0hT>#c?~&!W;kmHizt?7@{*S;beePD{2n6)QnMiN>q$R^nhQman^n;tiK{qdT4EFwD|@bK5c;O2ws!F>l!D?cuTwWc~{bs zb!`vvefqR#K`#|e58)`EvPf(lrh!E1xT}V905X_z=+cVo38mg5MF0?{7z=F@AJ`t; z;p;K5LTw7zfcy8&c8bx8*|ptQme!d?%i9fpSWzJq<9ajV_8qfqx{W|G2$)5L+^6BK zrk3&vr;Z+h0N!<~qBST#6ZG9N2jwSbM0QELW}xW~qi8iSLUn_l%t!Ta-K zE_DQdkSeRx?WV`Bh!Q_jH|oZ+Vh5Pfcws%fCkw%WUqFhZgTbnB*A=%DM{(fZ2L*d| zAk4CeioUQj!1e|(bnbXi%qSWeEJ}b29piZ*;cdBhgNtjm`J!W#H}M56L+^ZYe9Zo+ zZh-aeq8j(d(6c$C#G>6H=J2cm9y*cpDFL-}G&b+NDoC-RqKO!HDA=G%+732md3SP# zyU$V}VHw=>g$QD)GfAV9IeSq3i!t%C7$+`wywX}v8 z?#mQkwe9!|-8KxtV0k;p$9(CSlzEE!w|Iha!g+gvDu9WD$5vAvHfR_~r-tb9{2uZ> zBtITyUGqVktV9GAsF{!tI8$=jx(>56J*g|PCt2U^$;0K?2{p)~+eS37R=C(2aUN+J zlAx^0Mp?rsSHR5vd~rTKy$NEghQ!2QXm`qDMq7IY56CN+cB8s(i?Ty3We6GU0MO2^ zCI<;30XXN_PzWYNdU%i|ZZTOlDJ(lHsr2Eo)dnE`$#KuEap3)2$AZB*>MVc#T5Tw4 zk2a)sSj25bt9jfo@^!{|TH9AXuWR?+(;=xL;i}%c|2>?gF=fve3Riqp4;zQ&D&!I{ zY9v@4hsbcQ58dYI+em)*>*wTx5n#y)+|t!fTB)~l=I^<2+g6tc*_E~tSI_<1+?A7r zcH5u%6}MLLq<~@^M8?t`Zoce$nI1ve+oiQWaP_KMj8|-h*<+<$+ArmY7UtG^rt&ej zbTy2?eBeyWp8ue8KBlvmYP$~V!Clh1#EL(@>1pvEo;z|F`65e$*KYNBWbp0~!{A)4 ze(vvGqsiM6m9xj=PGaqAE|mVg6FNM>MVyan9!d_l-1=)*e#=?2@D9X}bBTAOm1isE zi3S8bdy3@Vb?#2+SfR0=S&x|G^iC0s8U1snsM!wZ?)rC=9%OPSMa+q^{H=JMa@=@{ z%(|8MD$H)*CiB2Ami{xiDg5G{^N!SnNNtfT5JIFh*a^^do_nQujPBh19^2xPlH!Lo zj@jiDB*DVLf9(}NG5zdTepFMAx1o|hfB7&Mm61pun043v z^pHYz^`_J-*9>me>RM;xqg^L#)(r9)b}rFQzyH`L0R?-*_59m5Gn*-5NH2saF!;Dv zg8`W7=_S&O?H}w>iVbc~&Dn;h)x2LGJd`FB+5-pSS`pjO`20;bqGicF*#y@yFD|C; zaQj>!jBgB}anbiA{*S>Ad z1u1Kj25?ohId=UjXFyyMkO{|oYh$X=_v}8bXS(r3tmoM*Fks*6y8Xj~_}qfH3S0sY zEjBgy<2A(jZy#n-llY(by~Pjc>_{*0;d{%>-;5+|O$9FzppUU(k47BK0sbhB!2Q=9 zzI|&!V;>ogRi69jVOU~qw7L*vN~K5E7ok+}1+5+J4xoo)d#u_5e`~UMCB>h0=8H$z zH*Nh9lNbN!V@_VPL|#rSS~=Zj5fMVaAyfDXO;6GN?D<}R$IjN$)VTgSz@m=)6)zsVmX7tuBoxrd zIElf5>mfDSbCRKujC|$YMA^*)Lw7>brsU!ZoN~g}_Jvq~tU7VXYis*2GcRhDUL5zFBN3lU&z~BK#JqpH{Q-^Y84AUHvn+c9IKcAY`J(PC5=GnwttY*aAjlX)hV8zAT?9OUJJOnG}-`74{?bMGe~~Fo$el5 z&{=TKfaWTQ2xB462U|T^_5*>s>XwurY-;RE5Da* z<3|TpZTjcFG?&e~1F|F9fw}QZjaXuX8%{0zcY5UMs&GeX||b3!EQ2JefKJL zds_tDQIWFoWc-@wvT-{NpPOHt@d&qPCUvVub82dKv`N|jbCsTau?su9N0B|ZVk7?W zxVL#iC{P}Xr)1@FxCnX8#pdieM~-3QC8aan!49rQXWn~ccs1Nyo`nU0 z+=h0_h3cWre%Ckmbk07qn5mm3uG{LV$F31@WBA$wB4j|vl9{1GO&oFP)1e-x(L8UP z325zv)%@JX#wD6H&Pi-vb1sv&wDaW%U#C}|!5RCHgI7`b_{-`;upGiV z1Vb`dyQN6K`9y2Iw#|1QV`i~B-;?)`7{6C#o#Qlmt?1psd5ZC-_0yI%-@9)hWzyix z5EykUXPRx-nMKG_v4@PJ(8SCU)3d_zHv4me%B%>WaEhR$S3l~ zGM86w-4v%|3Nm0NU^n>j`SV+{(i-6W%WAxl6rbsIr-P`zZ z{JDo+6}?VJ1ktc=;0hc%TKuySDokU_I$lAp00B*U1TyvCGRM%cntl@|`KEpe@^&v8xp2S-X4;PNBhDx@yTpzV18NEudEDAEj;VE_5BVR2K z)y_s@agc=^JBzfJS8dA+KeX%iR^5A=bz8T_{k5v5fv0me& zJG1oc4gF=twk`8=Wph!Z*3Yuyft(ZjvY%_OZ&RheagZzTmCU@M1e*y)}pD4{x&vFs{{{0Q~E35&v8WP>n->O`F~Orn!k&DSx24s9%`H9(P6b%!@?G zsx3wT3~x`ZuU|Shq@n+Q_ey<7gJ5Qid^79w`fZ6LRz{I!k*YdeQTmHRtoRC8HxA{u zQ&QSN|G4k5sfSubG{WfLU4B~;TJ>kUYF?KXCfsjO<-gv^J22R?^CTFxK!+k4Q_y8q z)6GmkxIA++@M-p&!QXxFbKAdoBSxDv_{rmIop^Ts@n4EolGR&L$@<4*Kc2r}61;bd zCL;K`w(#;sH=C}<^{{7()6Wj;`Pbcu`lY0;aphEc@V&Q;Pm0qGzsaJ0!hCGk2*Guy z_+9ItD&A6T*IhRLokPtiI(kF&(czc~=c$_KVi;{#Ix7oKQH@#m{ui#tv{|jFA3o9) zANl26vKvF&c5a$r`<2jSwb?_MeQCq^34@BEXq)%cZF4_25yPHZYC$luCjLvqLEh6w zyKAWrOq_>#?TLFnijK8~Pg*tjL;8)7J%3N?KmyF8KVpE8Z5-u^;s<3Ll1k<}aGr=$PN{c=KA?F7dxzg)bKPhFcyEHjw-O`F^DR z=dFFGlJc$_KO(JUIMcIkZn6;sJ(-X zx!nX95Ja_aUH*4bROi<%8(R=O%_xuCL<~Qka)CL$j{DRhwF&Y5_Agid+^n7MkAz31 zxh_1=O49qFEP8DxYkj;NHen9?-Rbl+Dadf;DPUM3Ko;rl?Ydr<$~({2CZfKtbciPD z%*DmUdw(yb`-hl~9Kk<=e2r^?zR=^_B%9x*y5i%uv)<^u2i@T`)%4o7`b<+xm1+py z6NB5MVY8BXeO)~Qe&xer)mr>MnnrrdF+u(&kBy+9mF!3cb-z$e)zNz$kHGXT#ua-O zDSQ7=@>IWlhs%s1NgGim?WdW1T&VruE{9E5X)_JqU&43*8Mqp7&yM+x6Op;slB_kv zx^buHZHJY`~FrT{ciKNEpNPzb$Nd2IYRvJtzkt@7On8qoNcwH1f6lc{QOaK z^N->D!Z+)%<0283D{aRg(T5s??Cn!c@OnKIdQn-$j?+N9O;Sv zoS=$3w4B%-`VTLuIW5|ofcbL!AEcDu6vm#GyRpVsQBkM4tz&eMr3`xBsNG`TiJos& z)g6kjzSd#Ti#+gJ=L4`TUXW%E1QO@?MOUd0awbbN+A!VR58>3ER`te3`_gQd)BQUg zqI~|wvQ0|6n7Rlf;t&B^a(cJL=V}9zXNkbic-$(q(*2E`pXF4V>;4xthVOVS zy@8|bYHi|46#ib<{6k<9#21x_@mg-@&zJejKYeoazGD{UHS8n(COh$TIzF@0QO{lc z+`Y6>gQMxz=_4AfE`5oW5cO#tZ|T=gU5a)#&2X56-8F2D>$IFbQwEv*a2Wdy)$4~8wU7}3VW{(p1Xoh_zpA|hof{Z<5SsK`$_rv$n zSKP-gMt&SIzn^mWLqRh6ji%@HhskA=cU2*FA5Ed+)h6yL;hu9z;gR0sIhWD0?H3JC z-U{neh>fH)AI`7;J`fq6%s2BYy0l*nOJ{~rEmW#gOOz_nE+hi%ehPGBmz#p_LGu(aW2ZW3yK4Rgt= z+v%s{X}4bFRYOTEx1$+SW+?zLdIXlO$u5uHoUN$tUXHM-2!%2mSHy#NwD0S6*`st{ z#w*WOx9kEXDI5;xlb5FPI7)9`apd%t0P}d8m5jFDQYye|2ZcrwTrtt#~#2l6^wGkcn4uta1IJftvTOSBG7JGdw6&e)F*Mj^<#?EPn$@P z@Rnu&L?cP2Up!n008?e{>E1Xn{6W0_cr&9(RE|F@L6dlkulCZ**r*=(!PjRBb?w&b zS`x+efH5IESuN9qp z`Q^(HE%h<4ZEX#9+-I4(#L%ZrJZ3CrT-0hv)p2Fnael`67m8HQ(ED??e{{JKkX`rbB2w z^rYPO^FvT_alS^s)$R^VdhMSU$6rJdIYs{0RFngJL`(mVQBm+E!-==F{^tzex2X@+ zLv=11b(pFjQOX;gOldXKiG)a8W~bc%NdJA=b{|~6UrX( z&uOWV?A2V~kccnzV7Z_Cy!&tOxQBmDj-jbAwik)|lIP_$&Cf#vl=x3ZL9iD0oZm2? z{`Yf-()Q%KuitN~Cq-+S4Yebq(}8Oy@B3fDE6R8}P! zThuNMM=~v5uCy45i)BWCd}k1fb^7+q%aeHBvuH=MD=k@EVWIu+EVMB(Ubd0wVCdAE zJ6F>^vhi{A1N)$`5O}>Ovwx!bQP$y~R&8_VFmR3!^^f_oSC+=XO|mCz0kRHgE#Uum zm`*?Unol*U&5z}tXur6s{$A-22w*;t-i=RFCM~Bg&dTN_@|wI0;Y+Dov$l_kKAM8) zPCXzesxZ!*pyy(c zkzcOV69V2S@R`OqYrEJm$T#U;pUKR8h5y@Y$Kk>!F5iQZgI?T2F0hjbPP+3+lz^i6)mr}f@s zbX$B_s34z@@P_qg^5u8NV5Nm(17#SN3%n^Bi@;4*m)_DDqL+HRp-ql2UZGfM0(h4`Eh?k2Y7Y#<-)TZ;`dCnPWJ*@@2tYCgfC4~j?roCJ7nj>c>wFWoISg1n?DK{Utq@VBoEvIO*B*s0_^7x&HsQJUJW0*%MYiUCwfLEVmA*_`y2+)|9P^AumVd_fp45&P zzlwhjOhBa@h)bSpZ@kjX^M<|q%e)n!IX)K*(32?x897_Lo;C2WbGz@gM2)O%N;yRVs^cMMFf^?Rra6snWF|8@77@F^!C7B`2&`q}4 z?$*?McJ`ymdLD1<46rz~9sRJ{gFojyV=tLXYRFPL_~?aKMJEnU*fK+Wp@h`CyFfs< ziKyw#p3_x#^6P&BUw>)vm4;-DPm$&oJ->gYI2aLC>V6)Moz4QvkKv_&So*FsE?W(s ze!9$PQh<1}&1Gum%)A_3#R)6!g3KWhD6zYmi)$sUa_{qkZ-HMzU*@i*9k+0@+B$rN z(ZR;JhvRcSW@!LYJYWAuOmp*E-^MK6VUDOp*h||PD)_$t38c)ql!M7(qpr~O$Ve@nW~3%?aH=sGCd+qtqwLX;WHLzOZsSR!g6s%5{(d?C zGqdYLms-EMLpqoE7_fuW zLbNmDVr4hOc`KW53#6--`)ro3FQ@qF+Hn7a^pK#T>ML8dQ;bq0?mXXJ&>XEkB|+;t zP@IXDEo9N^h`Xn);3G~tqO>8cyR=hY6DD5R^7gI@)T6~W@y5JpjYF=s68 z9WI1IAM#c`isVO8f1&}NNH)Q~sunj0bY2ipe1GR-e6et#q)9g=WRb0*IT{8(zm*X@ z^aI$3r8qK6$B1ot@w^~1(~^zx^vvisZymqY2c8cArrz-URLl?qAaJLxH)l$HW$k*0 zxj?Xe-99`7XD0uUkyW-+k#X4DQ~ntm?D1?ySX19d_xx0R@LaI~+iUWk<%90IC^to>!52cU`)*Q&11w_4QnK z>1VUsyDx(CV3J7Tw}L}T`!cC%MA%^*Ji9Lx_KlpM|2TiDKSI4u;K2nj#HFw?Oj-}AK-#mGNQf|%2nF(8El^Fksn&#>QOr}WtU=oBL zc2K~hkHt^%m~He^VUoCaLi}D~h?{?dd{t6wk`#w~GSkA8oFT^ir|7PEBA0lEdi-!N(+I zts{d0tzvS9%&Zvho4|uwP(LNHD{F%#xi4!=a)>1 zO!`PP&sin}y@E`=NqkeF`6w64qC4_4L(14VWe%?9%|6~*DeD&AyXg}8sx@A4UZs@9pL2*RolL(-V5sG3i*>? z)IM~WtU6G7{EBz%&%g445G%}F@yQy%vcTwQ*T%Y*cIi0j={wI4C zRARQ{R7#kU*yUJ;htMUtO0e9cick&JwP{CiBK)4I4-2XUbDT(?eAVW#rPHh&$<}yA zX%+Zpytvt7Jzi@s;)BrKjfW*{6ocbbgoJTh1139L*{Xt*iw~KLN(&Wbi#29jI(LtS zBdw_0f&M(hlD4yBV3f?3efvg&P!UmSRoQd{$hJ*C^Od8HKy)r80Toxt<)It+3$Gv? ztW}^hK*>9ENSkH55+?OE+#1GRJNe0jXt65{G6@tChz`&x-w$SY<$O?X9e9@^COqpa z-5RlOP1hwEO3N+ZHrx(Ium6yFWjNif%RoKtDe&Nq~|bdm&R zBG(OwKSkY2r7WfAmP3e3W6>#OVfk)I&(VCshF%KbZko@tO~+ST1j%RNu{-p%GFd>* z)r4$XE_HbP2W|F~<%Rgr19SMGfwZ}940gE{2}fe5ffMZ@+CA$zox_%6K9O_=Zdig# z50BxPA}Qa~07;n1i)gij)(%VG%b1i&sYk)-Fhl~rVGZyl-%`{4+DQscC!ZnIUKEH{ z)VYi%LcP~wX_=V-7lnRE(u8Nc#x^E^DS}y(b#;=rhPJJ{6Pe3;&Wz(pJu&7T-(JiM z3BV-Zz#|Kh7_a%kV&HhgLKjSiEl-qP43faVL}kz1aW3fW2v$!4?CcsWO7A-S$Gz*& z!1~06#qtp6Q_>EwBmJ)+1intlifsoGB9ybJ6^@(~-gNmc>Sy!O1Y!{`(kKe#lw{d_ zqWfRrh#hPh;E;k4_>Ph5bVRT#^0qU-gZpBwxsZz+ZnY8;8sjQXx%m$L&Ev@m`VF9{ z$rkXrrX$ElDoCmrao^G~UDka&UeAbdei#Kb6Y|WyKfz5p3OCeK?{SpLY zEFRVlJZrSVZBJ(Ue9d?cC-)?Kt9m*Lza*G6*?|3*b77cPz{hf=&H{UpCp>Cz+FQ^K z4vl=H(V}q`k>;dS72r$R_hn1HsezQ_^HWh!6xt0l7E99Vn(fiO*b{9hnUO1ex>VeB zNA9Y_*tdc!rs&$cmpvTuZ@tJ#Z`1 zbaBOXw8xA4dxVrNkvWG#=G389wptL)e2leLIJBc3l-}Yd>pAZ6hPjTPpt}gqWVNiGqkAoN9Vr+&?az zo9FL8xawkD(CXCOm(e1}0TtNqamoEeoJ{uB9QM2!^f>%Lf*w0^>gg^$`>$!P=QN)V zMe7n_@-nz7Reef@kY=tzXn+#P%q69o5lRi&z8U@xIfp#^@3`e{JiDt5_YWP7Ev^#uis{PffWtnX1b8vl|(0Lg~RS1D5qJ9Ht1qj2{I`9vl1xey1u-V6XO$Th*;j zgQBO~H4w?Aht;l4hf zmpU7r*24wcf6LRgE6C?beFxU9b*tlcy?ea#V(8QgGf7YXx}Z#eHM>-R7|G9he=iU3y}dF92F7 zhL`Wg+(IsiX=&ywO?>;$)XfZ!*?fV-MGMvsuf~;yk5;M1W=r>nq&8_KfcR)QGPtaO zp3Lkmz1{+8_Z3 z`m3&)soW12&Me+piJhYgq20B^nZYYZeo0E0X3RDFU31>)ydvyv9z!Y2If zc2E68v_0CX4q|U?Jd4JMv5{pEEvh}xtm+OfB9so{zR{u)Pb^fgVdw~FssjMLb9Nnk zS;~LN0~QH=Z4Mopb_IG#`tTT?EAF`&@;?&9$2zh~y~-i{S!~thdwMbrR1nph^p!~* z>7}pB@z+S6cVuvkV33M!(^Z-y#(CX1G5X_3J_VJ#FIWU zQTYy72q%lsz%PgPxLVa}m(KT=a&ydZM%^jG=xR5VI+h|=VI{`64BvNHXeX9H=AB)$ ze1jKuECic)h4}q`pwlqXQZt15;2J)S5U!#xgx9;LyP`r11n2DG=VyQL?D2o2OgP~C z)hT!R451(MN5f53@HOO#^g_$5+mEToIX%9c0zw+bpNT7%7TIdPE`iLjYyfU4w^Rgl;5+s`%{0E1C9JpSt+K)<0QQ$eSmx<&VzzUt?go;P`VymGi<}%!yb3DS{=$K>8Osn(U&_ph5?APJhPT#N4~-Y|H`^8G;rNN5*zBPAF~;slxJQ4 zozu;g!$lu&l0NV~OC?X-pEGx;yQ0KSeUQorEMTqD`z%^l)Lkjk)zP>CtVtUymEhFF%NvIkIdgh>CaGD!cBCu?T7Be)r*x z{}y}m&*R#sVaI=w_9ee7uEnH~;WTh~sGQI!MMl{5#x5NcD`)-8{Y;!KPZmL=QF5oE z4K5^8-Bkrx<#nenPZ8`ZQ*Ih4_oqiZ=xI+9Lni-+qjT|Ry8Zw7W-s{I}Od5A(X}(OOZop)HhNIISttyVnUHQHd-rlob%{+-M>GeJz{fR zpS|C&*Yg?Ws+Au`PYS&Iu&ZeEE5zq7B*@w3R71mO%j5XVPzbbF9KGYZ*DgQL?T33w zv#m-v2)B*!UpDl4h}p$|UpX>5+q5}@e<1^E?73n3frkv;M_>9*^qLvIj=Ve3D_M4{ zEWPNC%=UsjezD?7^uOUDO!BN7a>-{jdM=B(c9A)``Cv9m-{PKCugFvo{?9m?D(!XI zUir+EmJSAWP_8t`bJ)|U`9qJb+u=-9luO}W{4HVa!FZ2%tqT{kU;kR_r8~{?o?v9*B$0ITW8iZYs{Bw=}h;47@Y>@=k8^zF!V(zNf#h;y=9?`qQj#gBS+3UL(%CM2MHlPW*|Yz+3u;`%CI3PuyS2Zbdt}7Hs2ntR zVRPH8UO=nfrH{Af5@$3(u@rS;eEX=lBo;;i*Ryk$wMFzK)HzQw>e=tlNl$i|TX!$c zn@gi;<#bmON7SML6;##-9Erm_=`%!D2Je^G+B*XyBCu8JxJIgJYO8jUJvUz>IveY^ zvj)#9-solOY{togN#+oWSa4yeReSOI+t8dR9|>9D>od@zmilRR>F>beDgiPMJTtzZ zJyG9_U+i?3C^!x4EB#!Ub^dh3z7(L1)lj%rD<4t&r~eq}wo4y8k(!v?T8jJ&(Rs1w z9|0@DLq|UY@)X)9+oU%iS?E{}Dp>ZFf4#mtp$s6;lDl=_@u_lZ{$J zWG{19y*}&S?K+qYFjrl);c&5cM>6gAe$ko6++n_epu%iDJZdhpH?zkK{903R5?;;X z{#PVR50v-E77biHV_RUukKOMABMWNyOygNY)w)xk92iq(Cb{B)?JV+%pE@g2&>cOu zrngO#voUR~eD6)iV>>kt*v7herf6`h$8j&&=Oo^L(o*rT4aVo0FY?h@`+r&G4EPNh zp>xFpuqXdfG!9Doc1tBpm^NeK`qIXv}AA;ZcGtMt(O}_6mQ1~UD zc$lTgelc3bx$@AjXEM13(GiqE4y8Ng zOy?{_+y~{Ew*I3bae}PTF*%NEI~4oYSj3icL9oP)an=9)2PU#vYJ5?SMh^>feka(M zbng9$e~RU2!>x{E=}s$ypB;xbq$1AE58>M=O&LF#b)&$?U9xZ-e(!kp;-5p_8?hqM zs_S@~5oW(d2mQ|jG0OE0kpB#R;MjC;PC6{2DZ!%cy5arrGoicnt~>JG>Z7Wb6K4`v z^=)?k`N`5Aclw;Qc-u{T)JXnW4Tdw^Sh1BZ6E*lFxfZ#pT2Uj*SbD8!I<%It!n&vQ z@WeC1W(QDF%i+juw4FtS$k`{B1MsmS?NH zNAii0BmNCaY*{@T+DhI&gp-}zZ#a1*%`#>YR?U67nP~cxrSB5pS1REi{e_WSaL-Rqc5syVy9XSk-e62isY{JRNJTN1* z_%6E!5I1uUHSMU3p)nu`zmnTVw2CZsC{}eOuAV@tSSPlxr1BbrX)~5VaeqJqnXxUZ^OgU;_re?|LnQoAPY~K0l&Eyr< zPiI)cv^ffGsQMBSuR^Wjd_Sv9p-C&;s~0QjuWEB8x|y3;UQ$PO zwMTpo@rR^P4C{?h1?%dCgqy07kxhuc-2Y;y*D_7iceU%MpD*n(n~BQg*S;r?rl*;r!FMw9sbo+4%)S#uz<;0WSOCr5GFjSypRq5UR zc8Z#s^qL*P?(Umm8xG`{Z^-`VWN|VfrFNNV31OyLJpR>{@?9!sAJl>!Jca{OCmDOw zrC9nYT;z^js-52->d@@+vJE>)hbhw;JsJJ|`cqNw|3aGNGa93reeZ*KC*Ax+jg>`a zR^+s}gVgG2yWhKy)q6o?K<2KxDPr~Iv{H8Lw0~1@Ds~3D9rZOv-{jb9j97TIF_(A6 zVJ{2n9j`>S!edHIRo}NC9CDnUK;xP$bxgA<=jv+S)*Vpitp}!BYr?&j{XTT#vTLh5 zFQCkB^JxBtp)to5~AKWmz1tv&p&#)dudO{%B)(2=9Nyw6PaVFl9GK!@s7=Je>$UP@w{G1onoiN`&HD?9DfrABK%|$xc_mpx--&r<7oRl4$%El# zFjLOwf3j4w46*toDi(94qbA>W3f9nS< zgIZaJug1etrLy3;gc#Q1%asXh%ZV(Lx(4Dh(;zRapj$%EvSuJLkNEQ5B;jjy5W~g& zAN_|_^>;%aUNuY5&y^m5BY97M^EdDFc<4*aw|7a9XMUbm0Ajo4mANv^~6ozGPa71p22j%d7WN`kJ32!n@m zm+Z0GLh}V_j2&}*W8fb->9U<*rRqrX2crPjPkmB*J{)#E9lZ<2;QuVN0lMCI-g|e8 z=t2Q!yj%}^$nd5Tc0G}5*jFyBdF@np`r!`&a1%qO7h7QL6Yf*?#7Dq9Rx?}_uXvYH z$aB4av^mcI!c39B)8qrD*~)U;O@?rK=U8}pd#GW{cR3B-aFr(Z%)75u(&Y1X9!BxU zXtGVMAcgsl+fYa7{aavaB{oD%w(edV4&kE{p6Dbge@&h1Sg+lR%7n;VG&m<#JGCnK z=u~=qB27?Z?FfcA7uAkT<8LRmch+oXPeo^3Ja)p{2R=7^Y9m00%WuPez91K|zc68C zlTq!PWj2dR-6w!0H|YFXcak%7Ntj*siTH%RB^}C;CtNvT8rh>pZ|$4K|LvdJjkYEQ)bMf#HT<5GM|9XA*FU7uT;W1- zrq;v%UOG-y?R+T-Llg4GO)q|``zrJSp#-B+G4a>yy~s@Dn2UHEt$h|3FQ0A!IWw{u z!jSPWO~;^5j06GH_m9c%VxN+{!;IJ)OySagZ)Y`)UF>S z!!J2%A?Hso8svrpnN`xDO>H$NfwN}))y-88tXP$W$dBw0&n|7xBo~!2Uqq_D8#6m? zlCJD$%HwgJPbq4!-WI5Sra>B_a-DO=v(tavIZ)vO%b#ZbInx5SdzsHav%OUJYCCk> ziBo-H+G<=KCDG(|<@bB+g@HG%M~ztLvO4(axGIMWilfp=7hZO<2()(Isu_Ip()+t- zI5A`&`6V)bD?Re#jh7!W+UFdQe+Jws(P1;3FFfyWvi>>6oXz@Y##y)K%r1fl3+RWXHd7JatQxZeknJB5BsnqXhWAW;}J3OPMXGs_2(iO z)WveMbNF*#Wz;{5woIft>l3!4vOaag_qGSzQzeJ<(G6wB#7=KLkfRvET{szgRTvT; zi>0kdy;Zi=Y%Lg;G{CQII+5*a2aoll&0TegtEHdP+Urv1Yg+OAGKibXbBfaRkd%MO zwp(XmJn8;Rj_k_BvM>>#JRnb=>fcNNWnB{Hx=YXdCZ)}z_rPALGI#sbmzohVlwgD~ z%4RM+KW+M1Sj(uZ*elyAMQ5ixgPm%$LtNqCpof#Uu|pybN9I!C$8<&cX9p{bVbJL z_IU7UGd?%DX5E}Br;+siqtmsAjP~wBKDf%cak*CqOx92A2@`S4c>@Xs)oYRJ<)?2Z zl^ZGjac~GIs^olI3&z(adP{uAnSt05b?xHUg0>$g?2AZxG2rOf*FaTEmol#npUec; z*lpInmG|ojk^#=s4A|g0!DPtOdXs4W4imbH!uy(on@->P+T^a?Cx*}HwC^y}NY_KO z=C{;dI*7h{Xq&Czdv3GnFQnqXj7x>XTA*m-*O}OW=aVH0TcrQhY@5{l8=-U-$86Hq zfy5d0|JXxn`5w$}a&b0Zd^vHKm-PDPKMb)mlr(XT7v?fU1wlM#1>deEG%YteK4dX% zD8W~5{(}0m26(?gmb(2uh!DJ+QeheYa348{E&Ze*sqS&`FI_Q{zmPE*^mt#%M2g;g z^p<0GJJXm__=EIM;Ir1;6@Hu6Pj_96@s_epy(ys=qSqIT=&A_^9rc>u@WJ^PX!YVf z=VQn>GKM?{4fv2f?}OS-meS3=uKl(ix4h6aWeZJdt#EO?(=%-tB$k;9W#>xjIa-D7 z)g|x?c4(A=@#$G%&;DQVu-jhI^ZZptn5b84xVxjbEZMP0kp#bTOK)3B)G9#3uF?sD zaOq!4*>NiN4Q<2rwiXN>S0Sf-FzkfOGQiPXsKNAQ`p|X7!NOT48O&bI4fvk{lmW@^ zbyze+c=?U}8TBU&lf=arI(|ns^(ccoDJnl6n?59b_qS2oXS9ZSvuT1?b61;x-p*boVFba_^VA0`+V2cI)rV9KhhhIh z*ODSF66lr*M{8AWCF2TbRBv|}*+hf|F)ic5rnCGZ&GL5zFO8z|XE~){T4sCsbHq8F zd6BnM9=n_+fRDN@%Ku8{yo0jI+zb2{K2jK+>74Ca0P^^da6J9^70#KF7GdZOGv z^k@WC`sY)vb5ai8{)p_d#EGC^S}Bp{*Il2LyuU>sRS5a~uL=zb)&LZ+l#@RHpzwcI z>8#WPGN2Nvi>DL_{_vii70e~N?#!U(;KiaWK-hCZG8Mg}#<7<^Up;7aqjf6{ z9H14<{QXC|F9x;VTjf?)tb?|AS^1n&h6@U_g;==Napm} zOuN63aa^>m+EfRzy5%YZ9&@+`vecd$47B&BmQT#IH}gM@GB)=3>PA#luP5c&%rk5P zxn+AC2#TIE0@X^86P*Zi?BCzz4pwGzfc!2S`BO%5U;Yx$1#Y3t0ItO}EO-)JE`!q0 zBaW~8spx#m&th%XP>vjKhnXI5J>)vR)gI3luLc7mL`&ffbNzk%AMb?@Ax3eAs_x7v zgcpH<;^6KSks#99U{eP{I@ZWOr zl_`J(ZF~W+V`^!0vqFiotGXzNi;0wC*;UwxQLi%&0|QeL#bS`2G=GC!M;L_N_qr=x z!|DFSZmbmK3C7Y)f&AqU!!>hH8c1leDbsf8D!jagm&X&a1tJqEe1GhgiiVZqUG7te z{eLjQd=8ke_vL^L=nRMw%^35{2yx5Z7!D9IdQwq@3+^H|)n1t?Bu;+k^PbsyB6pZ1 z!@w5f7Pdyjf-AacKXOuVV7r5(ASYt%s;v#(Y)UN6^-)ooEh1xvCrTiu$wP2T-%~up ze#beIMxJic9k~wrfB840k6<(C#U@8*t_`~w%D~(&b~n?N1UoaXkp$8gF0+2e2pZy= z>#wS!BMQ+A_TVi`Yfe9y;25?7!>NC12JtR(Lz39{i0}!{KlK#&NjFgsiGOPFvu0e z;~p#gL~h4|bZOaar};F`PIbpw$<6!(>{O(x-J4XK1r(Xc5X$*Nn(M*xx8FlPPefvi zX-at``SVn0surE_6c3{r9v6XZ1OsU;)gPegc;}eiX=L|25I{`3(5}I7~O9;nB(dyYibNtXo=s) zPeJ&6dpH0X>dVvBE&eQT^p(m!6oUM2n%Ve~6?G9wQ&NbD;aO<2g-PKH;Qg|N?HP;; zfyWzUb1kG)RH-k(eUPDwKw^2lL4w}~B3iN5z-_xHtA*3+5PaMk-qGt>f$7Vm{+k*q z3P*Y7Tl#)mY`M$IFPFFl5w#cE_zxOt(JhPc`Cj3Kcd<`|PO zbD|mq8b`t%kU@6z5QCOn>ky_||A1t6frv*QblsSp6b1d96N}O4Nqq zMv6*EL)*wQ!O8@be7EDp>8=E}a4+mWF&P*_3WC^Gr;&ht(HmTrmBh$v(uP-ws3eTG z`uj!YWkR7q_}2<UcI=24Gi>1Y z|F>Td@o>#{wOkmdglW$z3PC_HX|W8URLZ5ToXiRL(U;7(Gunf4=fvs^V}CwbjE3lg zT3BCxtfrd|gUvNP;<(qQgH=7y3p0{WH{JmVR>I4SDkKf!A>@w(B%6r?pYN(#fBhZ8 z5vY{BDe~3D559(+O5yAIo6LV&;q%#j*=-iL^x4AVe<8=eD!V?>i$UdrUA@NeQ-7L> zYFv|?5jVz2d~4`wOLvto7C!-`OFe6q&Gg_#tlf*_Yz69 z?N|i?IJQvuIp`1(+(`~yf|AY*k`{m%wkZkwVxbLSZbsVkA(j>-rmial9v7cbbbhNN z%FU}(Mq`oSt}?@-vtOifW5XoJJ4r&uQz_~Y#`=#`3F>X%Xa#<^xbc*@_?}Os| z+q2WwAd}PKUW%o00P3|R+fqwi&O-2CzO2{IgSl!0p1N^&%4KYyg93>Xawg0nA>i~~ z9%ItRrv^FsR#bqy4JE^^#M#vt%L_>XfhoHA9|;za9)uz^Wjy}$ntvE&5zy}p1Rjzw z@iP7J-MCUibp}2rZ!A+FUdDYtYw%>{MFdU6RaQS3LM#y0p*gjy(Gf~uDr9-#VQ((a z6>;SvMB=_EQouzX_m_6gYitEosqVS}n{K)!!q3vF^>~|0+;Gfl+-a)-^D1nGBHs5Z zmI?2df_zDkHCIrg0y3YOq9>B$i_mFP@W{<82H^83<7?xi2H)8)ZbM~k*=p@gf`SgO8=`=w-E@j9D^MkiU`~u8dvK*{OTs&d`|6O* z>@_bV$sab?2S2a@fT@L8rq2kd#P$ec#0c6rn-DSY#}dE zt}zqRwjRQO=Y~fwmz4&mMEPY-^bcb7uKo+<0^yrotC}#)-k4p$Fy^h>3V}S!5B6GQ zbW3U(0NeVaHa0y#QpSB@TR&38Y{bW9Dlp~`1E^jP6Un9Pp~6AnPgXXyA&amkMx0WF z(ru8l(XCY)#Q9G`4Up|s5Hp++Tl~&|m9nV?rH{+lDP&##MED+ij-hsdzoDwH&_oz2 zd>cIgsZo%Dz&aFIRVT%l$U=lT3&^e!HrO-=g>N`q5@H!K_-zoFcq?%v2>BbRN$x!x zAQ>rZx*_fDE z$Zw%!q}5e}S4x7M_7w}`%W1r)fE(&ka;-g7DMdmF7f#aA$InyU(XvR0C+ZgIpYf&7 zDH=5X-1Y_ax0OB7ak&&%-GMlNdM{L8{MmOlD4E{#miNKRom=6?@WB1}OTRwe7UqE> zI}oGyPNeIWot%yOh4dw%u~ZMwDOnN{R|+jwQ&I3e01?M86*F-$3e|pA_Tu@Eq3`k< z%I={AHN%o2Abb+gy?S4mbf9AKMQlS&3pGq*~H=OwwjuP^POgR1m$BJy;^Y{CC8^|zB1lhs3#o3!;1R8@H1~Cal&$+mVOTI@T>Q)~hLBI1v zgnyK);pm)Ivw|0SGdc(n1_?EJ#qbXQkrB6u`5~yG%GEurSfFHXMyeF>T30#ww$Uws zf4939RoDzqGwZE!Es!h%u}3{ef9tFI;#(@F9yjlM6Srq?LtA4OCnos3?MRg;w@{Es z^C}BbCws&w6aBpC;1eQVToQ!T2(s4dMda3(cwz^f!ksB{^zy9)YyUS(UI~O!j3W8$?PBtMcKuz_Y=#!V;KV+ zeY@Jn(@vNfvL}+i(H|?V&sJkS|4G`t2$mFJ6esxc^y(WXyPZ}td`Uo)WPA|iKfmxD z6*)N+06gJ;KxCZ=Fy`2~wlhWtqw;MsmnZD&$>KsPvkX_HvWNVEk2`G zf^hl;pYIdyA3$0r2yk^v-aKR}^(zc#+n|Ez<6Y}FNC(ob)rlxXOHRytC=&^LBNt{* z$xYDTLkFN?khJX+*||LTUuy$4=dMf_ZDxYg&ul$RkjuuIgSYSL+9-&+7gZ@SYo-LP z@nY(P-{#Z?h~D8SB6^HealP%x1jy))-gZ*RSj_LOUM#`w+Q%FqfB^>J3CFChoZO-C z!rU8UNsdV|zfR**-E*gi!;Rpyg}~A!p_|1i&z~NkZk|u0aIL*d&t50_pT;b;ot#zl zR#n_WLWahf6M#;m#=#(tc|(9JUE| zTeFEDB*UU}9lnPJvj#COaAT{^(&qKrk(%|80(kk{V?BR8cEyW3HLR)z-Gw$_w1xJT z0hD@duE-b_EDZWV27iIPkRpPE@c1Ro!j*cBE-*fo=M5>?FVVi8AFuS{z+9vu;8Yex z!xg~w6R);I70QmIlyWWHyu6L8{Q`8s<@*dWdCs+H{b}#cVjr5uM6M^M^=W+6yf9vW zg3y;aD`QF~`!Y&YOUE>AgaeI)J@o=Y{@7(Ka)bj@4}c+@Jv3vH>@kJl@{3i+N7#ij z@TCILZG0;GsOS_J{y5y1k%uyD=rJTLMp>o^=@Q(|?FaV_A^-84Uw0&#A3-$C(t*rg zw~vTPlnVptHf#?9JOLMdvBpk>{Y(XtT0lva8<>d6#lykB6F|a(u0OQ`n8@6qf<2VS z6f6D)!RBC$`^ZhB_U+h`H^{(6=v;r3oU)QXoa_;u#xGblw8~!^ewK0o1pw1tMh4ew zIL}M5D{PSOL=npjd^Xk1z#Wc#f%xd0Mgh~w4Uqa5FE_88kW^QZ)i2c%)0NERl>`*Q zRkirwhxFGIzl+YxgwQmHt`DMMxeoWmHU2O@D4WJ*PElOVxt7RTEW>y;1oXorH5ilJ zbF?lZEO%qmJ`cX@kwdRI*v}++0Js)~59A~J;MY?m%nD}I#ua?^9JZI#?eYR? z+&_G&J-wbgLfO<08sO{?MQv&H4?h)UEus_qUxfE>;NgC#;No@4(Q~*44L;9E+^0xR z6p2Yj7c5w}q!i`%4`;wx!J7upNe58n2qa^jUxX53HzEpzV#C3<&E*G~kIuheutOhW zF$^M1{KRRbTnuB{d|}VvG<=>K(4;98ND^CO@C%?ib~W=xn^ckbi!x@k)m4U<&Esit zO}J4A(119QMgmi94C5gdIxyHAnKDn6XXD;F<7)WZjw5^ZpaWlgjcrNKia;G@y+;=n z6SKiDhNno5?AH%t_vL;TizxC1ZEd7PoWA(HL7Wuy+Pt}Sg9X>k+pI8PEBrEQ4wr&0eE_?21M0GeQL)~QT^1W!w=tYF+jW(TXF&;k**SV5j)1>0;yf=UGl|8GT# z<&uWS_owbYXD=zDQ5}5+!T5)*=6EDv>Y~aAKPQ+A5O{RxI2Zu9ed2`$0wnF>O zP~cV9?ed?*av;zcn$R=a!36CJ{S*4YY&%AWTZ6`qf*Y18M4Yu5X?5FubAmDy5^ z;;Rk#Y&YiGnyL&JrHV{~@ov;@=%wTAC0~YL*fm;!4iH@zjY!S@`4uT)sarl*!7&nV z*&tZU8tL!W$oKMhonYri8QNH0%m0M%TLhGC3GTq29>XoiCY4`1Vbm9qTikJ**8j#; z5k;j8(9oXr$8u`GuY}Ok64-1wWzT1mY;^ci5k*M)EC&t{wo$JBkeUCaHzoxTC}hf$ zyXN>r??Xm^qlzREPszy($AbrBNCkMJ0WzE&qdi#kcosH+siPE&-K^bG={yie_5|Z# zF^B>yb@wdb6Kyy+DtFLFi}H=mF)A!G#&rxbVe8?6+XN$tiNL%#Fc6rX@L7M?|6BLz zS-N_FGw7L#1qg~Bap?en{THpab-nN0d({fBWcdsOPU$>V5#wL z*-KSsCi$+6F_I(>`lo+(8)IqU;t7U`ICbSe1Ci_uy87)|8@WY`pCs8?fyex_8YB`_ zjW_IQIPJWN;ALiCCJEncLW>*$NygJ`#WKtk;lEEEIeC^8m|~DQ!?Ra!)!)5CnU4Lf zirOWFdDy>@Be^VVtBAbsNWgjS5v9oc%aYU9Y#~MY zi=xG zpDCndYHC%>?%NhnMp{o#qMuw_pub7I^ zSzTwu|5BH%Mq4>~W7*}uUOo5SY!DNV?2B%xxfbeiEA+r)VGY{0o3V>il)?+8&O6eIJo2pJ z-=6s%6!nZYV!@ka1b_GfrTL;?O$rlWF|{Z8siQXIx?w9_Gb*1`V*ayI5e21Wo_I6i zIUG~pI5dqp-KnnA!L!Pek#sWePBoXafx$MMO?1XuFWKlUxlFHcg8TcWZyoB57+S2B zJU7}K^z-43_DjMyXprx}q&7BsrDlENP|0O^QfPK{mF=gG2`7$*%3*3C35=*v&Tvs; zhea&k2^NfU-`G-xyHne*HM&m-KobWx{7B}??eE(2*qfMgWvELL@EqkA7`nZ-SEn_@ zD7x0|=lfMh6AjY6IhT9dE z-hJ=#Rj@7+qq-S?wxxaDj`iopywBzD_?V|E@kXV+rLv{c6^fmpSmRVPpgtm>Qr*>R z5560hkp)H(&E0Q0B}X|5esXmV*T_fA+v%p_c#ucHz5I0Z-jTCiYN_WXb#OHTRZ`Lq z^Cjyq@z)cv!ew^9uq$PvBn2}`f%ujYm%HY)BS{-{G%DVE4*o_ol~@j`OvlyfOLR5U zwltC;q)OtkFNn{YdY;r0ZcCv_$OGIh6=sJ<;kp^ruDO}p-{1F|b+s^6qcbgLX!5pE z(DN}YYuZc^#Q~4D1D}1p&1hLz*#w;#)jrKPPN|E!2;Z+)kYX0+wY3CFg&4Q_*Wz6l z7eddH6E!{MR|Hz?4)H_xL%r2?S|v5|LjN0Z-Se%xE$OD`XVc%A2YYa2Li`VEwhu^l91#ON=!!&N1*;gyk!@@;F;*K<(l&dGERsnDc-C$9;;Y`PTQ6aU z@ZKSSQ>u&qr7YCvcL|aC(iW|qYL1z7h&U;`{HjIpL+8lh$iVgui0WJ8ll$8oeqstR zlUG1P`fC2(5!PbVWj&7okhY(`72WJv5;L+Qn_WGvvE&I!*={h%qRuyHEtsA)LkV^F zU}<2cOF8N08G29w0)cGlT^w(Dv1`HnEJM|Wil)N&6^AspTFo85zEoJ*d!f;qb3>YK zMc^^{6&`ES8v7fMLlAjikO=!&V^_64(I=r2NO`dIgs%-&Mo8Ls{qT_cU+|v(IbZmq z^u$+OV`A$VG^1-FXr}(hk4O?=uSAzb-u<7%m`sz4piU}{2lk>F{?Xi%{I*UV z_c6}RWxRY2{@Xs~l95Q{D$sZC6qr@u+YkPQIL4Fcy_$_#%jPqwth>>>Tdbpl_XuDp z=S~9I%--Ofi}JEua-{R7l3;kYDJ6~7T=)ANrmy@=10~}x#CIrTdoQjV{3RYyTA<(} zA3Af69^0m*8a|ZMVYm!(F}#6$YmNRBGYG%^hU3*^(foe|gC9nG2K+C1c)pRrHM|;V z7QiL7*sh7;^CgcA4_MB$JsRt+f3nTRvX?6A->07aScGc)>c;emke#RD+h!z3PL^D37_3~SPM>c991xMS?YD?ZeF+!YdN}%jtGgdo4|L#Z0^W>aUKSF<> z_P{E=fY?~B^^F;Qd8Bh~(gJ)RwDG>tNMAF0rPMO_kSKpI-6vpDJT5)Wg$K!BH4`|~ zzqt`3%Kp&)L;06-uhrNjxeb~E&S~L~?^jNUjcexZ)mDO~zXU9=dV?zhfzkEQJv|X0 z7$`)J{*5MMfs0(dO6hsJz04*2i%GJ3*gm&>0y~X7hg=V3x<-qwaD()j?=Rh_ccj*r za?>vbD>O~ESv_o(7*ZrjYNv!PvHD&WnRPbaGJ?bpgQB|l#@APb#qD1{Lxi}YJdM05 z@hYN%&dk48N{v6LTewtqtXubh0mbVpskgL#nw|E8B_I{|&_w}Y`P;SUl%vV{YH#$y zWAdOYuO9|4<^Ov#Nx8UI_LX8*{J4t`5=hD#zqqFWJ{ONULB^( zLJDXl#D`8Dx~2DAKi%ALhGOGK^;&+diOsROG$4aLoHJXi2Dqo<8^nt9l9VGwzZ_#e zR&I_;<-y$lLX0m?`<-4bOO31flRq!*>Zi-zo9c*f1QYi+)bfaePrk4i$`1y=yePX; zV&GBCz`XfI)GWG{HC*L0Tk;^QS(c=K!ju6^Vki#=mx0HWv06@#Z0{w+rB zENDxvG6%In#U-Wud>^ca?U_acVt++x=VM_sb#`f_+H&aWj(E$rrFJRL+Fzbdm3KI# z+?i^`Mt@DKOh9zX!sH`p(eL`D3vcyg6uLeBV1r~@7P#Lq>nCr3$>yLPzWA)-Il|GL z0sjL9EgM_6VecPQ?hZ|m{F2q9dDdV+h3LHA3;{g&NLAcngCUCey>cB!({=Dg;k91K zH{9=R36d=CfSfuG_sU3pPBh#-C*k}}Q%yt zqxE4NuFK~6qc%q?^H221KpVE7XC3*vA zqQ&~E(n@xGs^99hp!qa}g*zTFQNDElrcqtVQW8Rb~Lv zgxDBhhSNh>ie#lEww%8B?b{NBW>Y7@bh~~{sI<&-eT^QtLAl}J5~*0QrEc-*2I?h ztG91ZfA&b~{JC@jo8*=w`h`@3iZosh! zl6Qg8gb~JbgWt-o{8s<;X{j9sq5@I%j+?J%6_SfHcF?wlWSR|o@qer%QRQOSpNNRU z{m|pqRfSI!2QNDBe+%jKaH5TgvGZzv)LzhbkF_WvC6D;YiJ}u@)e2G&n$gD+FSPy| z#nROt-Elp#UvLDOSHsr#94>kOSJA->=*6LhW+w|6%a#RzQ3Q<7a zC{;c7`6gmiRJL4$Rc(FeL!ZmgsOeG5x1pwbSM%!8dX8lNR=}V3zTqF@q0i-$Mnh-K z`4yV|ARnI7oo+TVZm`1H1y1}w+pJ@}wD5SN%EkJy6{Ui5>u=vK_%1Yd5}!3`FT+tA zWRHb!)n>;oRcpVMe=tS%ZD%L|JM=~G;CG{Y(h{}54)ix?`x>W+j%1Zti%XjnQk6K3F23P z3E$WF<%-U7p)GCqJu?!)Pa~HbzNL8FdFvR@xJ&5!@Zz(V$XN9YRFsW%XWlX$!KNKOz)=FsD2W za45XZk0oDSYwS!`*13p@766RPE8X+2E`7d9`OHAMr>#XNhV@4CYb@I>wX&KG)jj!G zjxd2=?!0-lBT)HI{G?Qt&WHL^1EVG!3s{#>CW+ckJ7Jb3zPP6`#<3RJ))E(>R3G=HP4%4 z$PrvB@Fo8YmozV4amkSXg>xi(QZ3oZ?<|g_pB|RmX+r2iSPnk6*P=Uk?PlzXV~r3l z-24l9;M?KG`+6HhIWx*AtCM-v3ms>`NeR z-L#aiHiG{8*-9he=TXeFTyGfJ-7|08Dm@eF)Z;YOZQ(!^g#Ri0r>`a^m|ag|JXW!u>$X|=&!G0SC+?&8o4I>ODSufQo&1wJTeD85nv z*8)1sR|H;nK;t1tjk;L70b%`2MYOsGnX<(H2+4C5dAS!?0&;^NfKCt zo7rUr=FBmbJNwO(LpMOLuB0z0coFl(W5#in?3HP0L>n@8ic)f=JtOW0m1F%@J#dd4~R zdfxSdbx&2yneN`H{|>E@ZthLsxtR)3eS&VY?^(#RD3+Q3RbOLoJPNJBD2doC`SEW} zS`N|U25}xDcL`*L+*|~r{nZE3dMh5+F62Eq_45X`Yv0>U??@*^*MaT<)Ta9qWxizS znJydfSEz3kQ4=C4A33dUsUHPr!o9&rf}z_^AKxrN~usL=nZN1ZiIb za4k$P5%ZdiRLF?t4y=YepC(wc#@7M}n+DH{m8EAvgM|0O4yY}2?W7pkiM;Gr-tE$X zt&(QCH=Z+qwY5h?)woB~9Qdw(AuPe;6(|ZrG|aGUir3i*KFT3sCx^ONG8x5#m<_$~ zh(2IgqF;T(P}O)Qs^J$j$4HOBC^`KT`}0{d)JULG%POK&%n97(FcDaFo#d-wsf0~?&gmX-+R0&CEjJ~nQ6r3!KHPRAJ%PU zq>RK2zm$#P-<*}qQj<*BN9kT79n?VVGM0Jm!~%Ab^y|N z=wpCpVKLqCJJztXY}SgXbC=$_4Q2A8&InchSv`LI zwMcvO!ib5VuvdH7L!I2ftu|~$ce~iLl92Tn-yzUc-a5K)Y44h;b8<9?epVp12prCDTq_S|MN%?MnP%VIj-yD;%4!Sy`SQ`hFCc% zQLfM6-8|Q8MWjk05n0$BdAz)Pte!6>D|iF9{3$)>)U}qwCNhn_A+|a^x)vR$`Z5dV z>71K$c}NL;nS+DKaNYd=m-H6`Z^ZCqiFX#_D61O%^A$-|dj38r%TK9^WPAdx;w}H) z9RsnD!>fqV?{rD)vHH6kaW1E{U5gSps@+vn6nQjpbA`5HFMh&mQQgKQ+)*W&Cy$iD z;udPBbdyH8R|Gdamh()J5?IEXSUp z^Rp|;fNNr3we@@Cjh*C-!^%qG#OQ5H?lz@`>fv|E>e=y8VXN(Kw6R<*@2z7i|H%QC5?s!@n5dnj|8z; z>!6w?cP1u~GKl2b>p$$5Tdw2yuN)f z4Oz_ewvX$@bdnD0Kwd=ubBB(=#9IqaV}ko$rqqMQS${7WAIsL@UItr{*@C18A2A^2 zlg*GRm=MsW>~i-)m{KFxLpOlVPf(+jk{K+srA(Jvq2j0I=)h7;q$3JXj;w4u&b?5n znbie`Ov%}?Tn7S6@FSmJP$31yxWoXaAiym{7}LW!c|$B7z>9zbn(SZ|%2=nBeOP6# zOXYehagBB(S5hP4^1&}>$QqPYuXP%%uw#yEm&IjR-wQ4f-*${4qhkoedBvPv@2B|s zp3(-NQP7lS8M_frDJZmK|d7Cxgpoerbaib8Rekb)Qx@KwPws{7|l+mSnJ*fAHehZ90vh1gVrUG6-g9Tf(S=m029&d{_s zDziTqE~c?qf$7X@ya-K+ZkS8S%pSgq3e1nbZnWpk_OI<(xOcSWX>kEq7PglmP%GDg zvKHElC*#qrAZhbyI@ldHLS#R^jjDjp0%345I|?Clbwfl@PkFHP8`yuAO6w{9PuWAghlrlFOw zC3WGBB=TaEYmK3`%7aeQJry_-cs?I3_nhOvkaF>-75CLC$Za|#j6OFBzRMB-=k0Wj zTu1?cY=u)5QdCN!90m~h*gK!%C-Sc|mQfBdsedb{csbL^!#AcmcrLLmE z@f~dl;oxX|!AqyD@q(L*i#k(yskz7b>YPSn=9SN)_=_Vo99#oL4m)R$S7Vy?{+IUa z{Y*${0E;V}>RFk?Hh|HYuz?-_}ZuXFqT z{`8NVo9+F6y`$})}i6VB*Pp01*=sBvbDzLD}E zO`rJrjaWd1}>b~~7#G2z?fq1c& zxKsk14)ElzPH=9orTGIovS{2L*&BZBNrKe9vM6;M z>11wU$&}ydRpK)t_*2zi=uJ$0DWJ6__AdMoog`mFqzIEGn=e0T$|pB!1rw?7pg-J$ z(K)Q!KZcowWWtYM3XZv9T2R#N%oL!@svbEV1SeBp{-OT7SIRK-W|KlVZX60}>C1PN$@OaiV8HD& z@^CG>lDF;1S-2TZz%cc4>1-v_kPh<1vVz@;kn|0bGJx9Uc%MlTzeiTJgXwBmyVlyvwZXq2%*N|TUYW!s`PUfx?3Ix5)ZX)$EL6$98P1Q<0%>cP+?CGG2^P3==wDQC+2J#`Q*rN;quWp}kdjw4Vg@ylvCKe>cQ& zmrIk%la-Q8A=6AdL*u;o28{uJHp_aH0!eQ;2I(8@YJIl;83xyMQD+{E1qIPxm=>O= zam#8Q{<0H~5uFY=Mm>PM9%Z%eRZm>c7yjxu96^2==`oZV$X9SM98w3P`B@ja;4gcX zDnW0><-oZ0v*iMm_9gM2tc`hGO(O&tf?Sq@A0re9{Z{`Tjh}%-z0x)qbpk)R2T;KM z-O+r~t!CRut3kA&p)_#-dlxSR&g!<-2`UGKos#f`j+mH42kzS;{zVfw2qbuAC)1T) z#66TU>Xd{S;5MoDTByDARy_#SgFZI%3wP)f@FaQjWJ@`YUnB-`;u8dfrOOYm4jZEb zHJWwRA<7mCHS?QJH@(wT8pSW;kAS!XbxCo15u}lE!%)xI%%=OzW+yk;(e4(bxZ)T` zizcJ_YJ#p9H|`*Y?E*OcBfetvB3^t*#+xQl%I6b-S+FGv{2#7bqLntAaYtk}mAMFP zsSfP%PW>$896|UiVXf?V(E8}sk@(y$xlyB`JdGiCScl^qCbb_dPRZ5NKyJQ@fu?y;jc~VG!K_OYuRchL7Z{hJ&{luIZgi7pV zsONp+h6?eH&jP>okX;!Qfh z>;p5;{o-E0rdc_z-ex#8j6G+_0zFz|c=5IN&Fb4{Ne6mKJtW0U@IA+qOb}=q9zw#j z2QJ=QN>$U+t~D@CuygA|;e!hhFD8Jt|& zLLp09&vLdtlocPOBshUf2_0t{FT?A=#+Zh1esa?p#|>hQXZ%^XzyVlaL0`6;E7>2t zF#8Tq!(M{&dZ?WL?(6Bg=6PK`Ht>QgE+OoI%q&ej*CQdt))HAB{Zp&tXhUW$34&HNlfb9CS#!wZi%}N_&+nfvgrH9sSD)Ih zluEe@@c1p9R@4llL@Tx$r~lI+gp|h0{T>)=d^(l))f7~JM{i>_#reZpcc+c2Aqd<_ zE0+;QBnH2koAzd}{!7(*(7^yv7x}^F)oW|6F=|hNhcZvR!kz-c-SPgKKgUfF*?{(W zZ0YkTqaglE3#YCa?9@auOT|_ z<}54!OTHE?X&VQ+10AXRikfLglofjwL4F%InoVNjbS-t-%&W}{0*ts6SQnt$X}fF) zoqSd#V%AO;30{z-zk*Eo*-Od>x>6~f5+v~?(d;X22mI2j$+keiw+H9hhbX(Qbdd72 z_c=t1&B;#)btxjQ=O=Ce=?A)2QmJof)OX=3&nv2C1iWSdZ1MDUbd<<+DR${BI_1A?MLjMKY zav9dL)=@miMctz0n`rGVb4tI!{tPu7N~f)|X!$!~ZR|GpR{=Gu80)hmJ+ z0|!F-7lXP6b8-M~2DZ#m;75Qj#Z8XzK3aw$P@#=P-p6PmEncY;%OnFo=*>+UC znu904hz5K55OsgTM8XSF2Yt>w>vO#Ta%L0*-X6WY7N?_`*}O=HFJs7Rw&uDR+x@_$9$5(Ez|p-@;MNV#L7){AOg((X_z6Wo9iG3d zo->VxC3eKk@L^T5e1<7?L_-XPxFQRg3tWqql%qL=g-4it^R+v-GE!W!)XRjK!Ju~h z^!Bbq-e6)oWI57uoe!SJsRTQ`b~sS$Fi2S>Eg5x6rFRaRaR9Q2dg==k3m} zsimQlOR8p_`ZGo7&4ekJL2vHcXu7iLu8h5>CJ&3SV;J6|q`nZM*5$2s;HPN*#uej@ z_nL_mi`>UUK@DCwuJ>}$bVnSq`W+(@=%5#R)!Up%ILAKiJ*o zO4F3U37uR+7!dd@9+3sV!`d)BdnrPb%KUiWomFYHHgs1&V4e*#A=D4XPT|Q~NbuFOSkPZ3 z25!pYBxJY%udTr=jz8Kc)s>9_)F2XA$YiiNGvm|+nR;IG+@(8%xG|>N(W|)3;LO^xiUcvxPCch z{=n657Bw2M!{F?q1RpLQR!oLx!7N58MxP&q$wZoOOSXi3TH}=9q=Q&H&oPrgVKyi% zX`SSi;-?1gBO`;@bn?(By%G zTSgXDpyb{}dRUK<^+(6tO1)@5ATQ_O)guK2uJFVw!Apcw3@{5xqX_T@AcLH=meZOS z{y0XjkTtYXX_9I&jz8~N&__cfNMT4EukM%gm0=6d&`> z>V|Mko9023S_ydQal#R7A8iN80KZzaK*Q%?SAO(K0vGHACF&K~1h;y3pr2fo;7E^yYq z(4?BCCJqpIRzmv;1}$6CPI^&|AWCK0{X=Lg7x7v=!T~U>bZbk&q6I5A#hsuKLvf%G z@nvY(z1a>kG1%jpyEGvD)jHS5f%H{7xN<5(vNT>_s?q$g%=YI!AN91(N6Yzh0*we z$j*Wavcgd3K-qKzwRf4FSVu?V*J7L}9tyiWoAE^o4xIHImya!(|nD)(g3eM1LPY--jqE|%R#g9E0Q zCIWWea!a#qQK(TOqQ=WFCbMVd?|bwou}I3MjL{&s1o{(NqV zChOChGaAA%HDql-pL`cX*77`;^}Gm8%`z&mN|zlQaRert-{ejddw~RfKlm+^Oetiq zV|R>;V|QzH=fu~0y_-#0?fl7gZ0lp<66?xoA*N0-g^*}s$8f>soA7Vo|2PYRti3QbK@LlXkmhm0(E)#G z!k}>L{TAMoj+e^HYBd)e;jYDv6~^yP(8~$#*@=yzvt$ttx&7bbj(O%5Jq!YXu|lEb zoi;+fdMMjLt>Z91QT#Oza#OIj{AP2gNb?8bC+DG;se{!}b4yx!R_yCl8-ISzkhuNS z{s>tvynofL>Y83f_=KdWHf}3si}qG*x6@9prOh8?%?Z9tj0t#6yB)6AL%|01j52$Q zuLtdyl_wQGjG=$9dWk7-%9F?v^;16NP2{xLOW8#K5G8y7BO5_o!@u^zZF|rmK z+0Y*4E~2DjQmG2`XA^vikgM-)#NWB+FK7S;Swr zJ99466&E&eZpL}TiRn8ABi=Yw>d!O1UT752{Swcm>D(VtXwzZ|03P- z=sUfRak~uw6SC%(LigB7Sgr0*vPa5sHm@>_>R(RTc=83p<@SIhBd!3R98_HOhX zGmDdraW&cRd2Y6&Ll3bKr>7r&L_O$=&KyjDzL=HqgLy+O5hcnQaDz$H=++7uPYQlU zibjSDnNj7{Vr^n|iddrWmW|vq()e{BPS}?p_G{`hOm`4&j$KNJ*cUY9v~o}u9BO6- zzN|D@mp0{BbigQakPU?nKYDKX*KyjX)1MspLrBNTI}cQU{_pcy|5+C0D74+aP9{6w zrYW?;;s*x*WXqZKKYh#`MwjS|psBHJ;uL9J>yn5bwt2qfigJ!9<8YB}V?ra%ERJ;V zl5A{1hQXGc%zCpJBx{_1w)USrN2eZ6cesjS2{7yE3X;wi@$#s_A@m%ulQxWx!SKPpZzS zJ7Ko2H(cX`{yVtET$Ac7&Du2azW`OvjyLqO#j%xnPgv_Y8hHvC^Ytg|61+@BV2}<%!?jj_xvz2{R=yy(e=YsPGpGL5q2K<1DodmN z`qKr+hMr74Jk>dju(Szk6IWFJ`8URdV0OD+EKD+HkW7{B8&;A^R2PqH5Kkiob*fh* zWEEw<{}hTJU(WmeQ2c3`T)NkM;ksMnNXg%?Ps)aOgAx(gAbj|_(LNvPM}t>_)T%oi zuSAneY^YH|d$(-yPSnZ_UTXIyzOLw@fAUB13mO?D&%6s195v%Ub?`nBN&Ig@6Zp0x z$|7{>fygULBK+9iH-&U)txuMC0O_D}$IM;#AKNKN0!L_{xe-oX%vFa?_}vFPiuGO7 zHaG8|-m%C+Ck`puJ-V!a)@G05Bire_y@CA1UmyR`+wE*<5Yn)W{i1hkCARe9;*hE~ zVRJSN+@|hJojh?rqiQ5{G5P0p@JjyREKzGdeh~F0IXM+i3Y89o)&hGjLl@2lZ2n|j zCwM6Ou~EXmNDBNjP3QHp^YV^ilF3Oe+3%vxu;re0b z6&gn7BFX)8u&Yw}PEo zbBpe5E6=WZ#lS(ypSZze+FFIH&pe6eudVE^UQoJLwAd8%9?b2yuOIGwAF*p~&}mF5 z`H$Gld`rYP{b`b-LGUiKi3374-oSS1`O^Vpiyh6xYf%>K3+Z1AUWdiyy!LUbt=0nx z^>fV~m%ojFQd{_f-C>=;7#^ej3jtA9ceai)kS=xOMc*!eJNSuE`>WFPdPYO-btUim zk2ef00yY})3n%zR36FibA9ZXNE8m^99+3@we!~HGXTxZtNzP(-Hg9*3F`q4|aul4u zeG@z_7C}TjNFkIZ|3cdPy>3R%PNqpRy3Z@DY*BMPF^Y8fu^1ttPOgoSAVPby|4mx$BAZE*w zVw{Qz*6!B>sSD%!tmCp?xZWl1?0KpLbBvc{@%w(o>Ni(oI}E6c-Fq&MiAUQqk5;B$ z!NlIYX%L=K-jWH9ca4;L4j$(ZJF27vD+Xv`4}Kc!P&z8D=q^Z?HxYGpA`(a)@;t|q z`0KxJU7CMc(iGx#B@}%7R^0`WP8ae9=)w4|4(k&!VJ|euqgDCY*{LRm=pC&*2iAv+ zd%B(Rv^KxspU*}r)&6k*naxGDLeUy9Y^v!8iI2$=;;=1tjF)hwV5$A;1MOu*_Y_k6zkQw3&UtXDyR!U*4@<79kaw|aESo_rZp=oJ$VRB$^#e}9v=ULRCo zuoiQ*qTBE8*|I+W>m8>Drk)u`Xi$fneOl9pu6HCLi)y0sa#ka7RU|!u#RuX4j)W<2 zGsesk`(Dh?Eb46`+|}&-beOb1#*J)Reryll%u4MWu0L~1@7=rFr57gZq0d?QqV(v$ zI^MjX6b+bwK0}g2-f-w0gR|z!aS!PkMVM;QIqlRuX(Lq6B-4vUq?J=1pR~F@q+Gx- zS{4aU9eQ%3Lsivdk%_D?{gD1Q`;SNGyvjJ8=!I0Q-RqaBw)-L%4IGdbKU!2r&T#h} zowjYzoZ8ku|2Xi(6;W2tzmO3@^MKKs>z&_177DMnLPim@tI-OL0lt^%4Q~R~&z!we z(f=og;5s&>K~i|OqrAH$d`iQpmA|TxYB)4du`Git`~wNw(NqYC_kD(HZxrN7QKr)cQ`rOS3PJOY7E4^gkDjA1J^%SRlLP2q~4+&%Q1`t{L;v?2 zu5|lOqJv}bt83je;Tr1Ky4dFQ0=+zi#^@jX7WU$kM=Q@wsehXJs!3Cmvn7r0+J0Zu zQ)<@tZabig3c{#|6S(Dksi*Jn7-p%-W7Y+1baeQW_Z@>xW^Q$#t_E>p9~Ub|>wLNM z{$|>?husTwkPR3-s+Oehor7&_De4edtFWrgSO$%P?(0|bH zdvmg@o{R8@m-wz;CcG^_lcpxdI^>06pGvaDni%dt7-;VenW?*A8tA1`X_=6B@mLEl zuV|kNb2{x@GezI&LFXGCHE#x(H$6OOx0jkJ6&Jp(LGSy`C*N#|qh+pv1J{xP*@fwI zh*9|qhdE?52~qbZ%r~#kds=QK1q3_B8EGxiA8!|Z(m$Z`Jcf%}jgI#m&@}(*G-~dv z1*^k4j8C4Gf%?g}VWYk$`>Xlb$ulEI>>mvnM{aIAl|(pKnDtMxsBysku+&?lW763t zRHUq3GSX-X+vq;cTF07GPhSkqL(!DfG8wQAA_@1)9idv7dAV9UBw6^ePF$pCW2n@q z?^odVvt9a_%IDFh$40ak9dza`bm))2UQlvROg{_ihR$L`3xe1Zz2(xJ-%8KqUgw%I znLEU2mRXFOI{spR2u=itlQ8FR#_zq)$_&s8CV7tCRR<5g{17DE`T208Y24?{f1z6eH(d`I{(f<> z;0kxzJO~^z_tZWqt!=7bbjcW7;7)EHCCgQHvQd;bTrv-}=6Y)Js7i*Ol;~c0{EQQ+ z03~wv*Qz^RvUSC_2QGyqcp#aeMWJK+O2qCnwSn;lW-Kkxjx zg4lqf`&h?-&W3FDdNej(e_&ZZ^FV9mOXv62T#PKAyI8rqZp+v19OiZt8^%;Ge!JDK zYx28SPvd-yo=?qF!G1m{Y`rluegtybvH!H6JfonXRNv3brHb~XRfD;%(4Q23cIUPS zH?NCwO%@WZ?nhWY@2eS6@pm@5x<|x2vdj?+lHIWm$Kwjf=f{Ba6FJTUdlL_tzjvJ~ zQtb{T9R#=F5|EkxFe6`H^0@#Vo_+82p~wyg2#(+MtK*;jv!nEy(UJX>S{wbvN|f4T z0_)iCArFyzheHsnqH{+Fl1}_?US{|UgpsbGLpStlYF<34wswOvhz224=VQl@-Ovxd z>G3fB8hsIuT5k8>;(F7DZn(S&P8S=OS*Rv;eopYMpO$Dvx4MC#CxJO{xrnKtv@vjk z_Ha40-RLy}Xh23-xW5vH>wFAusL-=n%nc&W?aK7Jt9M?V!E~H!C4w=Po=*H@>gw%8 z%2|b->uh%2$LB`akl}l;%|!3>(r-XB6F?Hnt*vR1|H{=w`U3gwXy%oVqoyemZ@$^# zj_|TAwAG1iLWjCUt=fIhM!uqEMd`N{v{^iv-kUBu`{!1*)uh)l1D;HM9<|9qtwzFk zhh_#9yO-R!{=bmI6xemQH!^DxYacE1F0!s1Fc@zXEovmAgl8NSI_4i<6z(!pKjV4& zZIJ9)1cEW1cfs>;RoC^=7sqnyf)p65V%3kWie>0b6+h6ikYqctEz_>>r(DC9x-hSu z+@*Ja-Z}J--@gMHL*8fPN9Eq^;AoL_0EKZ`_|54;Dj@0Pq1d)LdUS&6eZ8Bg$k&aO zGd`LTt-Q*rM<0FTo*E}KC__Qm2)dHsmro-!Qs;id&``RyE(j!D&B9fO{I|n*XGh}g z=i$gE>c-`)bnU?ONB6F&D9Fn8Az_&7%M}GjZ(eLvU%XGvnvikMRT0z>o(C42{H3g#U3a_x}>wZ}jmA>o-XWjGv#=*Qdfiw{3!BqA1wxAOe zzJ?h^x+Amp7h$%+KSDR-^oI3R6)o&@?$rx_#k=h|sH>)+&OjR41h=I_bfwj=<0o1+ z0={1Tm|dhx+oG?FUO{I%6xe;Ut2);m&SyrW*L@m9R3|-wT%qKt!JFMb<`Q;E$4-9P zxplYtraIv3cV+KX*P2Tn!JDURPEUSEe*sY#BYvO*$FA zEiq+$WLYGxeD8Rzy0EucD;2L@H*TL`w@77t_^--AKZRUx$1B;Hp1Qj= z5nZn;Egg@{+BT^1E6JYzebyjq(jC+9SaK*KVzpN~C2^7}>|b?}JJ(>5&ntlw9eY7Z zo-)B>3Q2lJ+qsuIK+gQjTRew*XJ@UNkdk0ZuOJTnCw2BidEWl-^0lCUB?mSP_5a#|T_mSA@}zrqTXLvz2_Xbj|IVt~R1Uk8W-!tCscu95Cc(Df|0 z#PhhAMPtKhHUW`pnm~D!-<1?o=>Zgiie3gsC~@V~pR^zw>3G#G+bujBrhIN?6_o*u zVFXwhI`Z9NkgTcL-8!UT%~mwJ9# zMbJol#EM}_ia4IqGe~Yd?~uTiN{Vu{zIrk>C|ULnd8D6tRV03_f8w&kK)h`TeZw{aefS|a;*GCRQl=4!w>=`9Gqw8ooJ<4PADq%FBV_^pZlQkzYuvWP3z62dk%4f zSUXA6GnfC(x1W4d*F8>|;H$1heA!*s7M*?|q_lM;B0S+7UW(sv?}${NP)I@qy=MGB&~7zjo9n3(VxYIR-%s4 zZ8<{EWVZb)eA;ANz8(_IA&g`TMU#oHpcxmv846#@5XvL$nrihiR;FvpH;cgZ}T^9y{#$?F8re zPm1MQj&tpwsei6FQlNz}GC=LZ;n~tl72&6Rmz z*>-DNR!&-+etxfIx~Aq8x%W51zfhvw$dWEF+%EbIJl`l@q=cTpjXVfjCFAvV{VsM z?{N6%L@WkIcOG(}gbMjHTT4jZXv08}zlA|K!6VgCZ)ntwiq zWanUIk%nJ$S>it2xFltWJJItQmwxNgdJ#RWl!aq}de`;Pc5R1(jevww|K|Eaxt^V@ zj=OcGALb{l=( zb`vW+;pAEt+yp@PHJ46-|3%2_rpCQ$;fZ}#dnZE&G?Z4sr^gvaf>g_JPC>&rB}Y4$ znsoHMZW|s=lb;0uWBr!R8LoqFOB5wdF9tbOxa~cl>JWv+Jh#qQVvWzaP`*0Q2ymOV z@pwEsT;w9hPFnt^6Kd5l4Y&MIFZ7=9c)Ks)> zJtTqZ5o#Su4sm*FhQ*ql=Z3J~d*SK2BfUDaBT_dkY`bYTF5h*ZBrer$ZCq6Oev_xo z+RQJMw;$4lZmKg}b!KGD=u)Ojo1jZh8)detU7En{%k@n% zAj(F^>6$JRrY6Y!Et4nAr!;=GLnM5xvb%X$=YN{?Qid`O*9k|9zsHpwLtXSbELK|< zrKekUqNk!yd6_r*;y8j|(desX2Cs~_W7zt25vOLkn6%1Cd#6?@l0L%#2QIc|UH{3r zD~kxe5*_0N53ju6iftD1{-Rvk8MFVd?5ouhHB9f0881l4)P z9Hs^`1PSb%qtIy))Pl8h3YV~hNt=(AUM1dmIE23lWuCM;k~&tN&99Iv#O71Ffo`_> z1YS$gfQUeWAb^no4P!Nf1%EGW#jrM9FsRb}!Rm^Dm5;RxNUo!UOjC(jD(HO5jD~{t zl9$L@Ep?M?t_{1bTKUs!nZlFebOFayq zlSBgc8(zq5Su7Fw?}cDah{B@acPYS*#g1qdSd8w1Jfq3IkZjC+g2MHR5Bf<4j*cf? zlmUk@JpuyLhhgzBP({s&D3q=5P^+K8tMuV=GU|!zD-$lfu?~|6Qi`@SRdR*{9MhQB z1-ZTy2*nWz+ZA4uxAwDR6D$VqTkT7gw`igYPh7!$+W5fJxJSaBp>@gY@!I?@IU|Jj zzN@M49x>#I&zv!jckZ{IH{ysSWy#x(4ePbVYff+ji0~6*)|Z@w<5?9@g+gl)TQ8Iw z?3uT1w@OYc8i;t1d!_dqM)+Qx6|bnY4M@c(lG)Qjhrmy(3|qnQ9fPrIo~DyjSYR{4 zv2fG1SDsJcIV(9PP({vx7f-=&cA@|;Sz@(kzI$h#V?tXqbWp3TYj51=qTbCzn0t#w z*@*+0(H=Tq4I!e`IyG5b8bYBQTLa=k#G3*ax-tQPnbVSvQKiOgXT_UpXzD;hmY&6* zwt_tAYK|lY`XiP9e9B~<_%Fm(-LWH;_a+3Rta^+;>Y9<$Kh`%Z!7s622EoiW7o}n6w4qMc-I2ylbXl!$(;UDiyFRGLX*lMYxHM-;)~xCg7v4uxnW|gY6hINnrHh6!WDL8VS;qU{l%X|dgK-hlh!i$Vgi0pAdP-Xl!xkv{ssqBBDirde^ z3Kx;cA8nEq_N3*^N!Jil-<1-LGin#`Vg$)P0T8oqx7Fk-{$>h3@TGng@0HTiUkugN zLrfSHe~utAI~(jb3rZ9Zm-X1Ft;WTr1p%SmQAGz^O%3b0B0xjj+39z#yg80xDO^=J znI>FZG+mUX$m*(ISM$P&dJy*HdEm};vVz0WariY?54oPNoG#6To%NCcYptkNrQdr@ zmE&{oR>{ikMNdWiTzLl>2x>oW-FTlw+I6yK)o~IOcdtgj&ywrxK7n+L`wr4cNe81&6QB9AEqLO{wrEkWCoH5A^jBa8u zmVCod#$;Nt)fApLw$`6J9g&5gW(KH#RS$up_K*Om(WQjSMxp)!7W|SYnbCH3=Jgz8IPg zZSg%st?Q25Iu3tW7#N}HbpQtphVxj8|9!)2^bq`t)+*If{co2gKNMoH1vupu{q$5s zM|+5&gYzm%`I)(je9%yfFCGmqU!(GU=MQeZB$2GnFp95GLq}yK*-NbX2!Omqg~ITAa*4t4U=M~nM5R7 z6G(O*1|A}fdz4GCZ{LlY-K9g5lX>KmGN3r`bD@&ea7J=n_1dNsV~At%c>t!Vb_JWu z`uwt`#QO1PrzLl^*jyP=t7{CeQPLlI1|N!XSzZ5x4kx_GHU-vP~J%QQ5uBtAMv)UR_@4 zFk4r!a9KK_5`z3(kOvurITeR|vUvVET={mZcBZ}S>xVu=T6odyi4h6N#T=5^I<~XF zt}p+H>Tvh#%J>hzS!&O7(au*#jTj+>37Dngbo`H#bg9T9_S+^u8c}HUi4xCrMiLNe zGnZhv#mARN9+IA5exbD3eBp6s#+Xt7e!a~cp2!5Ore;SpwLjBg0O~Hz9$9KXFc+yo zQ*=27k09Y!6F$MgdNm>HQK3*|j5HG)A9=;T9Pefhy}rwnvB8+SgtTX(FzZk}FopWB zCi32%=CfX9Eph=D9}ZXj4bsoDB6I+{pAt%ot8Rx(9_?T%8z;${Qn?lWpSazqtY(|} z%!i^A69R~)gsBHAW5M3(*rzQ94uCQ}@(xlADXE{OBXu`MF72h*6iRdpC+o6r5P-eK zgpOgGQ8OR(O4W{{7u6boE(&hT-ufJZO-HV?*Ieo~fhS?5lpsCVaryue$I361*51Ng z-W!9wLdk>4K7Pu5(ngDp|} z9}F0m<=J45e9+HL-0v{!Gn0T6p2%_LvEHO;J$7CK+ zS)vPgpciYKD#h1FQbhgZpYP;z$MD>4qEg{E@`*Gtz1NKAGY0zD5nHpFF<)+d z=$fR8(oHYC$f9PqN{d0r2znI&7 zi{Fs_Bf@qaVLwG$8G-KG(InF|(KG=(s%nZMr@gLfv8OF%VS#UrZ=!a`I47Af9$Str zG7{QUu3;V*l|g(`Vo7j5!@^Z0%>1iYHsuvv*);-vb$QJ>qrOv}XEhXRBb^jw9yjcA zQ#%uMaRVhfO3mpQ{6E<lLl5u_}yO^}GV#LXC&^sKm@3<=hO zl^ZylGO>v3?vS+_%vkc-WrV7C*mjMQa z*y5>6?Rd{2rd2MkA#-)H4v4BkS#QhPj>xr5*9mp?Dm*F7ISeFp4I_EyU)?HOeG$$F zc~fla}1wYGR;C4~h~B83lF-`wCn~2(AyL!`LGunE`Sj zaNnZ?v*PIwi7`5z9TdcTX2-2d2(~sWw?T~;90WjL+b*+))!GeQUzXxBAGB#0)g3UM zngGM0i;i1nLM;_+-lVjCdo4ytbced1U%^i>!`lzaT*q`!Onq28L*-VoTSqdjELGow z=5k>jS|estW!})z$FKo~Q7Su>Zmi4+?G2TbJvL5Ozv@{^Q%#*+vkI{)Sb_ROa2RXeTKH zElmx?v^~7eg58fPYw`;k1p`^oGf|2g!RWxoQlq#NRB^FrP$H{q8DxoxrqZ4H*HEop z-#`E#c&%((IfY7h*%o|yf}O!}oL1R42U4C+E6HT^TNJ?IWh<;)=o75?=l4{+_(Syc z9OM={vy9gCdXbQY=r1`in$3zs>cEcKs}Ss|!d0KFdmLCc zmvk#S+*VEcDtAnnDZJyqxox(?^eXuBc*L@SCYD!o2z|ra5bSX=n|TLgvyA#By3Gxo zsjwM*p=_$wZUds+f5VZY=`Mg@VqoltX#Rg>q$OO&2?3C-LYYyuTaxrhA5@4u1`?fc zdJFULww+K~YS;Nhn=xkO|0oE4MZ-K#Y_49+;U2z(`4?)W;Y(L9S%lbPl;Zu5hYI^= zWS|41^QKpMY!zl4u8$c$H;hYq&OsX8fe;D~2F84;TXUER3TV%`gKs6g!)JHQQHQ9O zQiUfOxL)uMX+x-~ZQ&7@P6)tb$De1LytTKh=T?U3z%aR!o!oimT7sP`h6ZVjMOui# z(BdcPlxLbEO+pa&;lnhQ5F-iEX3`Q05;ZazZ9=;ug4>!>VW}7oM@N7gFvua%HDY$8 z@~?yiGTvgWg;%1fCaB(v90J_!RgMJw4B0lzf3s2J#*aEr$msXj0!#mM-vn6$yqeI? zCZWkVZ+AV`DIpI+wIa+9Zq24|AZp+!zBXHf<{ZBMXn?{tcRH=nv>^UU!}2O9k)rlP zlh!Cn;nH#Lo5d79iikU&CC?cyQctt*h2vN)*TwJjlHkcSDt#N{p3uU}BDnJ^7g)ai zrtwHa933cKXXH3P>PA#D7TKjl#G&>n6;C2HbNVyg_MhsiPZQ)aP<%oA?tR@n3~S{8 z|MlOb@fwv&@~qJu%aiB&Smc?&Y#gF>%^|b?q$~){0J?nZcxM9t;jDAu@YDethXR3A zmXZhG?+q8IHx}9D3}dkxez_DK+om=gN9|;TzMF;K4O8qBi z6(yjP`|ir2NZ%Q!3Vu?QH;hD1Kh;VrWU6K?yUQ>X(yN9tdq&C>!Cvrng9JZ2^sZb+ zO##P{eAtqdo>?!er9kcf7aGt{uN9ow;n=3Q6hPVb-tRiU6ghX4(o%=siZ=bD$HF7a zF|IK*^R4^U$$g8{XUuN9!0)S{1yf#+pQ3?A@xA>FO5?z~`2PW@^08Lx8Q~jQ^v7>W z+cv3ZzE?Kp-=h#XqekO!VZZo^=n7Y(B^LX9s?w@Q|G=5zk=$%^6Pr`~Kl}35vHH z34)D}8|(8uRyAXMVbP%;Gi>)5I%rB1)ToWXy4 z3J+0sVt#G9745RA+p?HM7+DJ)t~R*PGx&`%gppcaTVmwxzuyM`RD~phYBEdP?mhKp z3pHBOBEFjFq|KpA?CvWqc&^qw@2|=|J8qg?$MZ<+T0IN7(eNxB4OEpBg5}Co?&Ie< zqpw!eb(*YDCVBC({#~2&?+>0n;9r7b8{qd>IFE)yQA6IfKQdvCfV~%GpBV5?SYGE~ zt%=Xx1q>&vyha-tTX?2jn(e2ryPb8qrs{)ta);9+Hlm$x z`1lPud`{aavbrA-B^_#z@ig9bn81xij-Co%0fo7e)_?v-H2mDQrV!tyM&<;j-LUEPJs~;Z5%KK<$tffLJU2^|W?`f2H>0#G=v1TitMi=k3+z%*wt@ z1E{>Al@BlN(~*)G-{{(*df{ry*`T&AtfeWnv;5Lak1LgluNIl>^ZIsbKL5L+qxUj+ zo*6Eobs+V!a&$a=_mgSV4zsm*6*YQoycq~DL29^B4^F&2Gw*t!$H9UrE>GJ-5ilih68r0{M1Lv&apv~>mp<$=^DrUr z$mhzl&m$M_W<|vn6(Z{Td);F9G8EG;Qlwa?1tW~M^uF7g>n3;Q+p@D!uzIn@XuLIT z_npYQ6)H%w{s6_ak{x};MT)PW%rZp6n-;MUMP=bKg+!XKPn7)Y9^V%nPQpi70uH)GQaF`lQ5+bUo~DPV3q0Ly7$~ zQ}@KwO_l8Ne@@*Xd3w{2v$eJ6l7FNQAB}F|+(euk%tLOOS<=)lB%mtwo-1u+Z<}jX zD0q-A{*ed|Z+Y@e>hYmIWWq?Sdxra@U**m3O$jy4980 zybJyvUwPxX{m})fMP>Zi*_88M#eA{qa_xOy>Rc<2CpA%Ux)*=$ z6SIR0|9TNV&XS4FC())mf|`-M$u}_mac#uhbmULjm+QUf>=O(yN4(-y=MT2kEK0nu zP{NtW= zVrAMDJC*HmAHt5*&9}!j&L?c~Ur0-Md+O8A9q;R+QWExHHEvh_y`Oxk2wc&&qfS4Y zYr+nIHq6S-ukGUB1_w8FXIHUv|AhMxZ>g>haIZYmh4S{x#y>eBjF5|ru(oxNV%@x79yYmfPS z544ScD~|d+^ZPU$5u$Zf5z(@pOc=iPMP28`L2n zFtFq7-}^6=BX`Ir)rB-m|4VZ8kuViL&F`8v*dSxxjkiAPCVnqLMYsprD?N5 zSJh^gi!(@ODW4w-jvK4`si&bjJZ%d!HInt+8#=0rSby;^rTT;-Z?;c?sRIyJ-7RwZ znAu8IliM(Y#bJm$Go|&n{QPr^MOvuyOh*HKz})IT`BHigF&Uo8j)`%o&TN}In?ltx zjQoRnZ!>qU^ZKcemJF2@r_rU2Z6y;)MA7fgVR}7mC4U-wj{1d+v<3t9 z54@LWFT6K#I&{F@TADG;`kDFa)A5oZ%5GWh-6MJ;!mYI!p%vr9yQKHl`Qq?Tc`A9` zsnSN!-xrwRwNt4}t>VI88gTvfU+}>t-;|ohv{}P4HQd5yq!ay@$P$~){^g_%yI;rk z9yT?hCRSHFJOf`o`M%$C3;mkI+LX+Q%+E|^E8|0OT*-D%_d9~a3;WX=cbT6SUw;h_ zuQkDPeCL3W9eq3mF+)c8?6^*;X@uy7js`GpM@!%7R?RSOhB+st%yU_%td#O^Ecdrb zdFA)*e*2Hwg4j}|o%39N%(R<;n00V-=$<>d_kZph*3GGQI!z7e*c>l*Y!LlCVT!b6 zE8^tfQGco=%WwE=2WXU>`F0mAGIDfO2*cc=+dFTk@joyA8h1lmUOA;%P;89*>g0Ey z@t*yb&uB-#Xe?@BT?WJKjc*Fg91^%}-rYB`$~))o>b4QzzWWe5@b_m6D4G0d>!Ow; zQS1x^$C@`+cn^nU-~5^o9SO=XZGr!@dA-NTo9R+?$|UNBPzNmRZ&1FjYoL1d*Gs5o z;?~80qgw`3hc>ltK6?-8)2AgPgwy#Tz6rHcM7ItV&trSEy>*<#no9m>r{8$X32rzN z)(g&N=Z{bOI-PZ3f@ybz2EK{o-MU21fsBRmBRI8m(pi-{*Q0$)g*`{CaQ zw5yz1M#L`v9!RA>PH&mBeErkW@(m*{(wZ9#$OdM>IHnwubs$VMy?Z?7g(~( z&AFhxa&E8q-?tEd3>~Snh%349WH`W}TWGLShl0P8P+4dB5GC)aTyyLP`RSzn>ILGN zaka7d<+CzcOD#LsW8H7G)Y%mLI*aZ1`eC^@CoH7{ql5g>YH(6hgB3&dC3aL?`cd)d z(c8*b6QAODE04lgxm?K-SiG()U9=(L8x;*=-WcV}x82XYcl-0dloi?;g*J){jXu4+ zW7qERdD3_(yf#kCsyvJ|7e>AKp*gooowln(PsYL#vHI#%wWfnsqtTL}Po4jKH`PVL z@U-&8BURUVWo9%yoC!t5YE9jEo66)5^NkQyv5?raXFK9)^vL|aZ?>tg!2jyWOBB*z z7-`n_Q1g^8;#<@&B8xLza@l;%|IvdC)jZ!OIoeQlq3XS>ZSBZL9K5RgRIdLWv@yT- zwboVzZJv5Bhj{SdliHw{#;;q(akxg=(WUO^Uuuk5f8>Tby;N9dyYed^I*Cr9YdBc| z*YN{gd?DjFa`G<&uMxULJP`RyF7`N-q;C}!MN{9j5@j1GsUuD2TW7+SE`Lh=UA&td zRs$d5*n6^*?n?z$4WI1|+OXvJGy3~_Ar~3UE*M6tbOp?7bsKi_f3>wx8hYa}J?$+4 z&r;{Ty#J*CGEI*E96F>$3ZCGtUr|@GR``#ha7yFDCx}T!%_{f+A#T!M(9PiT9-hHCE(r({GKL;rqx-tghrPS1!jg2-Lg2mhzW2}NM)pH5frKl$MH`v(UIi6b55H}*G+k9+kc^M7B*Fa3B_ z?371e#&6eNe0BWe|E!u6lk#WNl-tCrO8hUpE2fK^j$HbA?5dLQz>f#hQY`Zy&#Ua8 zlzP8#TE^WZDYDD1aM;~11|vHMHN?{w)ex(tw-m2z&A)h%SSX}GX*f``s=rFlnY%45 z_wSEXx=AL}q$>3765XF__sC`H^~KEr2ZC3*z%Ew) znJb5#3!Zv>Q^3`8!bQ~>Xj;u8)A|Jeh1$fvw7H1ZZd9(cZY4174PG4GHdSmCeYT?S zc<(g}jOnMv1H%U*|9s5^8RPxwQ_`iy>9$^9YbFXjq)(2*=d1k4h zyX}o47VKGQ*o`F9d4k&T2Wh;K&$M-8DKhd}AHtiIU{y(0?fw~HiN^gTp}%wdC* z?f0-5**UB)^Z=^?$%!g6kzehI3yfrovd-Rj8>MPd%kg=>euBP;R<2CN*cLU`8}beE z%Q@{C#MwC)b_siL`OQG?RTHl&-SAI}r~}ukJK#_iI8pZNDNbuVn@ z0_l0^lX0UF~?^m#S8vjeJi((_tg-Ej-|17(*)d$ z4m~QD^%K^?&w0r9fEN?{}3+v7se-B-K3oW14 zC(+V(u2q+Hj>Jmse5t>_V7@0pi;wWEtV49KZSc_{s;Y<3?u1ldi^=OR$h(l=v}R5( z3DI|UgBwlRKFOZB{Kc%I#~(JFbnX^7VXE0F<4Nlv0z~)wGw4X&@j7}4HvGj*wRWrU}s?F`EPrc$JC1RfFUZf)>e?Z2|L+RV!iJ+X1^e7Qfc zjWA*FkS*%~-30h+z+sb{Y~juud0k*Xou#*JSM?7po1etc!SDhAS6H47$0zxUlyK5LhUCUpi$e}`f z2nUcOTGl}l?&R^v#p$jrK_WO6m{9#jVhNL+L_b1D7v;btPfa)UqSl*#`aBYobas~h zg(h=0jal8xTNfX|6+jH}d;=Oxui;IrWg>S%ZSP+V=FPBVS7jr}Eyd4$;!Ed)Lk?;P z%A26F3t&5GT)vtasM*Ldz4WU6;**EP`=#|BlA2`E+hEJ3C`r9WU|E_}VhlB2PzDa4 z0O^q*{db;6EFJD3?JUZ9Yk=*QaswUA?%-=&^NioG>MPIHfD{R(y7>uyEvJu!KGfAE%;jBE=0@q$=yAR$q5 z?SAy^iMSGUK-f*6&vB=g>J$98D>Q=k)kgAGWg5IPSF! z^@Gv$b;gybUHQYthV!qppKgQ5#!A`OOh=9Plg*JX==Qhn;c+f`!80xcHrJ1xryL@wLaP``|n)*#_uVUqviig6nl17 zgw#5kFoRc_JAp|47kXC^PwE&rV!*vD#))!B3qAO0;_W|UO)ruR4Fv@eRizeP$tTh! zd~FNm;XiCa(D{uSe_e8TZM3T*8a$x5)qKmp=Dux%$sd$W75K|75=n3B9kXM@C71Th z|HyOFtPBx}L#JKrS0fAmZOJ~0@b1GteZ3~R`1DhN(yMDvQ^~BRg0C)<$4RU6*Mcn` zu*4TL#bQaPo3h2d9rcnnlOb$o*vMRIUwK8cL2cW8W17zR#l~$Me7Ow1=o8BVW#=l*e-3#tFK@+yNA-c+x%nn`%ovruejnUtl^F6X9R{B* z_uW)yO+*Ns`Acfxc5sX54Dq`bbmPsaq`m+ksuMZ*jCTn=o>q;=X-mXJ1L9uh3=Dky z-j(Y7phbvH{>;TG$S=C{)k3J%(Vf(41m!kM_jN>(zGLW40Mu-WJ0&w>vm-Hu4z(_1 zXJwT`0<7yT0Y!XUNYaLlp`eQ9 zVX)MJcS}&8Eq^(Jmj!rhM!^OSm6C)W*2Op@$yD!p0i9 z!_uXgTUZZs-1Lk2F8U{6i~N#*I;xxD0ZAuD=*C~ji&g_Q3}$ZSITXK}w`LdRa72zj z3w`4sQp&qT<%^br{#85=5u|~Xo(pJqhf7%J?9oP`*!k#1-!K4-jz@if{$ z88O6~f^R{`A3x zW(^&2T6V19y-WPjMgXF|S_nIn9Kw|iDAK+`VwHi=86DTiM#&BQj8W$+3lDQC@K9q- zj!MW3eNc9(T_{fK)eFc|{9v0k2-drewr*2Sn!Hn3R6oL^EnlS^Nj`Dqwy?$}!FiB? zh*Lli3{2WJgd|UVMZ)A=(m-Z%P_21#fELrMUk(j@r97_B{9oHI)oLzw%sLjOJ%iv6 z-Le8k3}0>VB&BONOt^6K{>SzRXZ@LCy|06|mebW3NH&IE?g-}AfeaT|&Gz)oHN>u?8fBPB# zG;SJR1%lwdvWvuiK^Vpaqn~!zTUqj>4eb*!YB)!EMODM`Z+6ZpMFydfgt!6TmZi1J zR@(YbfRd{I^$hf=h#SD=0#(?)?v*v3lI_CbGX}N<%6T=AkeKQ{Cwt)!7}ec@vRLm8l-Z`Yh(NMQoJq%epydUn636{$OI^ zU$J2#17vh0#vO(fREu<26ws6pBrG6H=FM*{nA-+yt)U8+e$XYg$HK_Kqj~MyimCq6 zw2#5OIj+f7k_E|Z7s3NAuJ|q(3R=kg^A4uI0tuQBg1Ys~V|PbIYciXIK}P>+>3rRq z&4@$}e2-{UR5Q4;;Z=xIkAF4mJ3<|VF*C=I>!~iw*sfTIAQ8=mX5CQRfy)n|iLCUA zNc|qDshr20_Th(}Po^wYPl&jjQaf8MIAg&1V|<@T5k$c0zP=z#cR~1mfRt7C(!L;~AT8U}qZ4pF5g7waaXrNQ7dnn`riyPXcjqJ-$FA-z#{%4ggS4F{Tq)M}29`P@w-U;$!PoUxq#LyH5= zh^(IZ?4!Gm#1*l@JJhn_KGfu^-UslMekd_>HN5Vvr27aW2o&i~4qnXy8;+nnZ9M@; zLG#csz=*c^s*$tSvYz_~p|>aqvGqp`%oP$X9GqMOB)Yr3!(`O^06tLQp6U60?TGb= zzrqjegWFmYsd)iBT~b$;2I0qDesE;oDTh#Xi7i8&{iphJeIVN{!-T0piRhdRG>lP7Z-~gu86uR}Zzc9BRa6L_L84X?ZX1>NwGfcx=lWSy; z6L@p>&YT@QG6w2{0HLoTaoL`exWRsk>JKdO^Nh9h0cu z4F|WC+mDi^35p6y11DEj4h{NBBz$>YXmG?7eO!OxKQcS1u@DB_vD&=bB2M8io`P?| zV!So!zQY)Jm343#Ub__xmY2h#Kpkc@YQ38G(T2O8&ql~elb@C-5>B_N55RM{@-{W- z>#_lB!&+7W5^v~N@54IB z-&TfJ4jdc7uvQrYBkOTr4=5nueUTC{acr$wb~$j~iP ze-f>eZ;{0E3~W|JSqJTfvFbbj`wkmf3QA<E7R;fBiTv&4gGgDh8PcG&H{{o6^=BuT5wT$5 zga9Vg#QV~LQS`05If7+&4m`#tIranw*N*G307YCe1>N-fphDJICikKl@ZmdQ%?;g? z?4?|agllNZKv2a=epNNW^IqR}zb>*^t7iVj7sC4Rq2xo^lNZ{N>Q7vvI($siqGJUN z^w@~1sxhlr-(5R$%b<2%2t)pC-vzJ>*llO?iQ|KJ!(C`iWnE7ZDoL$uti=`QRvh!@ zMNW6hOhhcCaPe&C+okM94xn!zDEw_Kg;nHk*}QJxJ293u9!-m_X{5V#CoJU%{jwK` z5Za8)V(`W(F(|_E)8V;kQd~fVzgB-@aXJW&-h<N8=|1OF&8D1 zQ7kurLPyGWH(+p$6oQz?u9oS?LmxEzDF=NuC&%o|^w6U>QsfGmEXUEX9lRn;<8ej5l&)T#4u3<51~;oz#A7^1BoGn~30TET25W&7e4Z^3pQA+~pzC0v1g zE{dq-E*JRbF1T*Vl=Hl&r6UaFa=6^jCn}BbR|$%UEfC>OGy1Y_%oa?PQ&Z0KXAv3^ z9##~nUndBgb_kr$Hg-T(zsnCf=u1R#3_BSUvcOB3tFS2X!te~6g4^oWs2==UJ9w^&LMBcJhgYoiIBXB#WtrpX?&V0zMF- zgD;74L!#8e5tqZyPKoNx4PRQ92(XQ#M+K_#OWkT7^u@C%vNYP zP>4{Eq4+lw^wabCSM~O7yI)U>vWiNfazT_?MdVdn*0=epuB708b-JrKh>uPh4hAX6 zjeH=W;WPSi@sKlf($`O-Y>c&1P{R+e(zaSb#{A4=HZVa7Q_^%@6;4KMSn~NjDyL#L z`$Oipg#BH^KZyAm-ll~2Sz1JfCX^70lk1#Dv1e%{E|{%wqDL$kWYb+8@*)fUO#|ov zhSy-=q6SX1n-J&Wv-k(c^3wsUoLa|lh=fJt!&JUj->`FD!SHi zFyJKA6$q})D|cC(&j?}P8i8tlUr`ml3JoLx<{)N;W zHPoQ_j?H<4zKezc;<*mQ2^wv<8S+8MT9D|O#M)e&N*~cT?5bBIJYef*D)COJGLi*x z?2lw&v%O!@g)kh?>TNrL``Ej3x2{U z!Xx1W;5bAS(NnV4z*n;i1Vp1RIeDFpWk<10efvMD$b8tvmg#Azhriq3fM<hTaB1_na2)=RApiHzJ(02utmKfM6(oCBPT@aW{eb{x9fKFvWSssmUd zD%tQ{N%Re%u^Q#oxgvX@y?n`9Jo=*gH(kg{na+N(;I5h<0{)=_kUh^>f7CNSoP!Rj zJZ{RiXrwBfUGbg}7W~Yd+}MKjQ*-XJ8Tx&|Fw)wJ_H@YFR{9&5Oo#zZ7s156k?DEO zoq^QQ1Q*^*HOasUx7cY}KzQ~E&mQL)Rp_G7{v(|DJFw{7>_!UOFm!2K5lkM-vUcd9 z!anQ%?JyBS+Hvv_0@X4LuUIZkGmD>N^VJ-FFS`YFD2(jI=zntPOZ|)}tV; z-K{{21Dth!+}-}B#{-d8QJ)ocX%gWhPtKjNdF_J8(sApeCN(gjCD!#EFgEoW`b}b4 znC+zJX}6r{=ESEgEYS#h+js#5m+HW6MOfS<95)ltfeC zuoQ@3Xlpa|0y)M9CVwN1r+-q4k$CmbIImG;`ouokIY{@Vn;fcHiLsk92!JSgl*d$wh`J zmsLV2VtMa6N5(|Jn<&eZB>>x5V|F1@L3l1n4-dDqpcN%wM16HznK!t#{)`v(oXC^v6u5? zVI3B~6<4?WP*5lvU~7zaN9P_QbyIgFpzi1(DkcXhsLg;5P)Q?8JGL=X(q}4dml8sQ z%%WQHq*Thu&F{XEsxg>eNs;M{(IHe6?| z#{crT4($Ry_%{NNpTWW9UF5@}6`{6;i_KaoQ467w5>E60HUeuJ_~Rm6O74XW*9o95 z42Yug?B3^rotGw`(&*g$O+%egE{>arYVtyX1Z_%1MyyTQ~u}R%=?Ed~X9Z?ZV=& z4z|T+Yjemn;ML+Su%E&GOaX*^?xRO-diMMa4cjz-@0H=E{{e)G^ie(?x?2S#EQ$Dk zMjcH0LoOovU%?bo)%&V89#Mz{L z`Wwu&%y~Twl(_8f4j(Ib=UodD41EL0xq7{tN6Ov1#KxK>0ywjP&Z5y9eiARf6#T>E zm8-9X-kml~9&@cAt1wkkml?v4!>V=kQ+=>7G*+RUdPsX5TikbEi7|j>*k8{>%B9tD~2493zBz97(q#sys z>IS#1uSwM zM;?rZGlX9<5#3!BjKqlBW^Gg~B5|7qa-aEnU*AFZyyX&yYu^LgnMYaLDkljt0=v0B+%nC+4}C5363`67aq1gN*|v zuqk<<55hHo5p-v+-hk0{t3Kqj4o0a*PnWzhX+?bjLSW-oim$dlZq*wVr?O)@Z&l5E zvTLI66q%12iRUokHK5O-seW&a?y7HJOk;0e{MFrfMoxY6CQ~&xv#F{;DpdTkCCmF8 z-Q_mQn;9UrwpMbk2j%rRz8Pw;Y9473@24oWNQpc7KB`p?)@ElhD$aXv%MCQ(Ht(aR zi$?w9lZSsDpEwj=C1iwH`HkantXuEIMchL$zeI;{*%Gj4zRtJRAcUNN(TtecPtT+} zr#A!TtFkWqp;24bwWxeGbw5T{W9o(bd$o3JnK!W<<7N$BsA`rUkVD*-yYX~JG$5%g zLpbFj64FC{toymgjDBc1Pb7i}F7oFun;D)PdM#tpqK)Gi(7)f1^lFQ=ob#{#7uwZs zL^KAOrmGpZj~#n%brg)`c9Vm86C70p1?_@Ax%xP1Xdn;tVtGfimwLp$27>1Ewl0+PE7m@y*l(BlW%l(dk$Q;E9{=w*Ch3c z9V0z1*4**ueJH9DtNC%G8Ko?qU57wqGh}*TDtm`7J&UrH-`8Epl40J+BR?k`s%`;d z9uOf8{M}}#J3Vtcfb~)RO4#m!`X?GjJGz5ZOF_(cL)y8-kGpm^vM1+1%LqDSA9a$0 zA*uR09a4YUHx=od5qYwMrv*{1|Cxlbjc@WCk5%0#hQImS$W9gvU0WTm;{`3|1vyn2 z_1HL+UraLkLPiR)Dm-RlpI+>G(EQyWglq%kqf{-)5ZCZ8XX<}hnJf(#<5eZHebVDM-*@Yqg;m3+2=__X4R_kg60pCW$?@Op z>W3WItCD#i_bJp&5~}iC{+_4btgF2KPchh@MB4olF{*l@;7uA)AjC$N>%2GZ~h?;_OEm(cxp2H%BuW1Jtavb&I&=MdqH-w+q;Z z*shNU7U9al?HxgIXhMt_ynSb(e)mLk#?HkAM(2%c(#U5WwfZL9iRhbGtvAZ}O4lB! zW<<{TUW|COv2tC=pi)~N#cF5G_;*a)S@;v3eB|T1CF_e5=P-5ieTmV2^(QJ?45My|ubpQtrX+?rg^^9)2&Z0)GH6gxkdC=41puKxdZ^QH7{Xq* z5xJ8X3sP@)G_FLkCpkX_5`lEGeF~JRx;x&+1F~?qUeXRW*29qTbwFCpn~xopwM{m& zx5JBRR8G}zEy{V-xkYuO=D{^Nuv69QvouZO=pf_=J~E`wq{`YWbFv-QyYx=T(SUZS zR{G2p)DMbCFiuL3G{AAJL@kr#lW?^EWwx7Z&VZuXK$~36-k7u*97`s>aENZ$cGca% zn~mRKEfefTr(E~!olD;Sxd_?U< z{iujF_vgo^Nw-);+rMy=y8+8)zo}OPI}K(&N07P~OK)SWbmsA=FU^~ysuU`9N!^k+ z76R^npJJb2Ny%m}zUuqwKGvu>L4jt}dB5{N?M1D>lZl%IyQ#iXx0=p-@4DGF-8ZXm zM>{`g9_ka;Wfu^+oXbBEE>anjvWX?XjTnyV=O_M1dB+6NB)H@Uj`+W zTA=s(*-!F5sH6{}Zp$mBsZ^J$(}MpaygYb3^*Be%{QE%C4r)B_N!O{zm*14HaalMX z>0Nl=wBix>va>?@_MXuScX zke%Jl2F58a!#GJuUK5rDU2j6md;$P(jig89La8%ntK78(8iqc*{c60C>=Yspd50BR%CF({f6V(JqbKvX7;BZVf6})o(Z}68h#b$1gzYJ!3Fy#Jd+rdI32*M^$ zzo{BZRB6xd1Q(`N&I91U;Gza$>qm~H%uq(GlbBurPvup&?3*XwoiDvVfmu8HmH8%N{8gL_d9L!Q+7}V`JOz1p_A!>#rQ5DQ?Fn_{ zWBC}Q80YeqXYy5t5O=LOgxkdKDDrG}n}7_eu#-vWBK z@;_80{5kCA@=y?|6Ht2i_w8e)k1N^Bqsw@5+J%TylU>cpZ|CgfCQ&)U$rp}%sjKe4 zDL?++cCnqoZ?ur3_-d{ihXO|e#!9L8Q11B$piEV44P(i}f8+0zE**GuSyJ&BP{FF8~<&Nq9d zBe1pL*1@`?2UImQI|B;;NKM6G4Mqkz+x3ikuXm75-|F9$L#wH5B=KV1?z_|Ge0E2N zC7f&ESi8HO^Ey&DU;hLO*raq6{kf=jpNf-O!5G4%`ZfEuu=(x-gf#3z#^eB~8?N(| z^e->m*sCUA#SZ|MTuCdIw&19Kt`eHgx=~J@!tuArr2g z49U^Le(bKbC=W?tn)Dm=4~`jmZid}i{s6ar*9et>v4hh&GEGHqs$sssmFPY3B%_IByCA|;jav}tpxqhOc(53 z!zrM0POweUzZF1M?RfZwhPQUt+e~UX~dY_Ue`NUI;N6DrZq%7 zhgjIS(3TI;V>eG9>T%+e@N3hV_{-%9*v7V1zc*~9P73;Ia=4|mfeU~Ar1Ux|Pgb-< zV%a&X{MfF-j?@Wn$(U#ZktSeDFTLaUC1C%s=gphRnu*ou{R?4K5#Z4(tT-QV^w7z0 z0dX4n0g&wcv%9?F){5j4g}>D-9Cv=1_D}vlkGtQL^sh$Vyq?zM8&S>8)8ixrB|XtK zU1QFgxPKpX_##rBtQn^WZfEg*?ZjYCJAFqe0%(;zk(NNA=<&6)@uT~E*+HR)n~^i#dE_f6)61uy z6AxWi?|JDp8^fWceernucJQ~xKAwE63Kf=Be!DsB>Zd11rJP&5Gc>#7TYg~w{rRl( zmGh;W2c(Ys`GvWFd6${pqw8v!aej0+Z|$@6`!appSFPYEd^+Oe`8@#6!Np-n8^ZPc zec2(pmklh^M`JpZjlA{K`Vhu3LK(((XA^4!7g#>t_?Oo$h;ycRXp+tGj-ou8#C+1g(-jE}3+?s>5|RPp)CQQYa+bO$3+rxp=~ld`J9;EOYVd)KHd z3dEt8n#krlH!??`X%Q{6a@6IyY|K`71*~$iDmxYZ*A2&9!|oJMJ}-Z?tfW!y^C6@a zq(OjJr~4{Q>r-5i!X#dZLtlzFd*W3p;SvjtM)7JSk6yy2()UQfXYgTmB9Y8mzuo(& zZa6(Kau>cAU2w{ilr-DR0LESD&$~B>o*>k`@fl1p>q*L!`4pxEB!y8cj&tKd-Y$lqhS7dJEuIUrIF_1?OGUub{v`OA?!oGBJd9y! ze9e~`6$O#mHy|gvfsNxXUA;GGX8lign&D`$0*@W#I5h5V<`+TVQ@iV0o=n6tY)0j? zk6Mbr?#TiZ=?&)r6vlY1g%!H?ny_nv9dvF;%S2|<*(+yXueYIn0gQ{;o_(2EbWaDu zF$qI*Wr*ccO$%Lx&Gfx}tbd~BLC&}zwc@gNkDt0Xw@5Y=d$w1y;@Vdw&ycyLmmVVD z5+CHOZ2z%v5;ZS-?>-fYha6m17RYIUj#h>`p-baq`+Qlzdo*o6_`aacmNxPX-QkO| z=_c-eY-4N!vX7QI(hXa$m^hoz0 z)Gp}9M~ytS-qEo3FGTcl(%d9D9zWzAD)Dh&KjK@tICbfK6{*iC>FT~dXU%behO|Ck7iT*`Q^{JsXam;wS z`%tY+AEsCmiiUHU4q`s0q|NLQgs`^2TO6}vl4E7ukqjHN*lDc#+uAE;HQFm1D`gm&N(X&&#V}A!yx4g7*Jkh&j`f{p9 zjaL^PuQz}*G(q*jo^4_aFE%W0?uFKoD6wx3kJtU96ETRLbUe1W{c!PqHEU|SFU7|% zaBWL?wf@(ox%b^acCKp#!N{Yc+XCh)Zol1(#`PyNp-iU3WJpI96q#o9Phn(UfZQfo z`CZ_Y(Y0)?k=m->t?_?YEyd)?ETc&lw+uIb&=|-DEb>%T!VamlM>?w0>TH$a#_Hyy*{0{D9b6W<5-^f}x_;^= z;fFsf|C}@%djg|)i}1OhqWDqGVlqBzr5EoJIGd<$Svg{nBLO>r(NAB?g-^~`vzHi7 z2|kOt3N%2&gmPrkB^@1yKj4cSx55I~3Nh6?s-ehKnC<@SL?crtJp@L_g|}7|%m&1; z>&xF*>ra6hPw+J$=PK3x_0{B@RTIsubAp*;?_R}dh(f3Nx!i(%Gs=z!82JjFmT&~4 z(w##OwMoD$!oe4fx>t{4HA2r|2EsDJ7 z7qVcm&i$-lMGcU3ftUF(;~{T7<_it=f$mdMzf0DGkZ~jZdH5z@BZh|=JPl>%UB7rd znj+mv^^%1UFHUAFd9Gu${sO(VX;AxTW2`?E4r+9>=ULK*(y!TNIXQytJA0YaD3lZ| z)GxTuRh3%$$=i}ID+Vv-V_}}=BE&z`KvJS@C35`r$ zwnr$pRoPT?p9&M>7w=5yir(cQ!+^)9NFm;! zq;fIpQ5`ZHIYRL+S%LrtW${%j3vmX2o3|OBlr$2rW}g-F2197c5qegI$(5SZ^*0_c z#@9~QcXRV~H$|99j~OV|ri9nU(SkqT^e{_UYY_J)3P>&7TaR2tKdxEN-@KHRL=`z* z)jb^Ba7#E8oar6HEZsE=kEMZy4Vcc(S|C%DuDWDdQ-1Ed+Fm%Pju7lqTP7UA>*jg>BbP*wle*93x8gwdyItA=@S7>FW zgB(MNDbbNZ&-SLntg{%h;VddLeaq${gg&mmk&*>))8e1PC+MT0wyv2qP!LLH)v3t2 z?LKpW?gtfSY#4A7KEVLH40b(rZ~ZWH74^d87Ym~angKO(0Uk`5T}(Cr_vVqiU#Dg?zPSTeL62JFBPjOtOIwv8JT~ZI!H5$%jqHT6lt=RC@^cCM9}DV;u!? zTb84IzFKQ6ASAU?+oWKK|1E=wLU3$q*phjQXl=rn6h_Aql2vRL;(b$_SH>wIrVy0> zh|jwLuXVx=#XhxPNL4+h8TQ$vMKmRgCuaHp9aRM$o-v}BrRD$w2>6JX4|w~EVJ#N( zW|yO~?$K9Pv8F=pf1XYH%0d>y$1IQsK)lO!iRr2}ET5e!N$i)yW1F~UTaocBHAAV;9YBDsjgnpuPhX$q zy(FT}NXm=s6`H0C`=_=#&*&g^EOS7HtZ<0ai|!#P!4t?k6}R~4R2lWnNZUb|$9WTC zO($g_WnFeDi3>UdnMXVI?Z!-iBS$|iM{w#yEUH=kAaKb(FK#O-U#?pk!A^H&M|HX; zMq14nm6a;hIh)Lo&vNE3Q@(XHiDwZNFtsic=tN5=CoZ-r>zPFDd9UBv6G%0k$bheW zsLYqqMsUcbz<8Fp>nZvsV24Dgk?4WB(du;nl##`pLInkQqHic&=3`@`w}^=x8dQ)J z`RvTxFu^>fXQKfq0&9dbZz^Wf-3{QDS&{#1*KEl_$Z9+4TZVxPphjPV6hE&X%nq+4 z*^0b&U`Nq3Ee;K&fqX{czaXyzeHOVoDeFW*Y;q-jqTlTm>Oid*2^#)6TZMTWaZVP7 zNq6#*L!pH6Ao7v%Hjf4XUHQ1hU8BjMXv0usiPJu&4kO?%aN09?9ZNn}Sk`HO=Gwdk z>+2aB_$18QdewVSA(M6^)MuRNSHRK<1njqI2j%tAgEq97DIRz$%Fb_+IwO?83zHT% z#qOubs_qtI%krB?2;w=&(=Q{&krBE9@Zs!bXcx0XHWWE>#YrjaS+iPL_6mn6a>mBn zScy8#(9h~Ch}HfV7%lP}WA$8XI=*zvRfsseOS<0*mzq&0ic|NLhHzOPXQ@wER#CMt zFr21^c|d6Nz?1a_#w?xlC{nUG;_B|)y zZ~`SqXz8A#@x*vWq95OUhZM`=3i+#02M`rxPuM&p1o&sA>xEhJI|pX{4W1#D2Nom_ z*rT1YaD+6yVjAN$KfD`*D})lNhk6;Cd7Ie!HYu+GM!)SMIK|N%$`?%%j)6TEOb0FfHSd6;hsxbsDGrQ=RWX7 z0s!09E<1fOOjerY+jivEL6A9E%{dNY9|bdk4TQ#=zI3)-lS&N$FjIexNQ44j1&j8o z5SsM3%62vPu3A#ur7t}-Fe_zQ&h+%$49%Ny5g7l+ zC<9>lR{!TetdVe~FNfO_&x|o%Q-tH1A52Qp!gpmpnPKM|DEn_|KzV^UWOTeLvm`Qj ze_SFot}C;YEBo$MWIhqdiR1BoO5=L}Rn-me-LyIBSYU>|X=b+Dgo@P=C}pQZgK_Gw z)iJARK*A%ZLTaJ)uzS)-li*MLb#$|77j;lzA4^$;1ZgwJ;Irbwq?;PfN_BNA10dZV z#yd4wj{%iE;ZXQIZHm>UQ3qtFG5`lBk(|uTs3HJpFTvyx6~*P*@Fq{GOU|W-V25o) z4pUQW4h8|0!2%9=uA0&#);trgXg5x_f~fBys|YFG-Ae0O5)t4wWxR#ckth?dUOF0S z*h`xAiSSCeFnX+j*X*c?i&ywss}`9h>dht|hYD4x!fMe^I;7y+JR8=7r;{5Vk?a5@ zII{k=rlcnKv}%D}=jQ^>13R{biCLwLU z&55H%iw^U2e0K*OnZ}5%F(X=Qrs1@*Z)tOTetp+MGjRYtHTdXh4hQG=)JAVhiO&!9`!(oP#U2Dp7XfctRLXUo$l<`3Jw z7#5b)nWjD_fQIUrE<|#Jm$KlfMs?g3VV(GW3Z1iM4S=}5(=D)v%ut@Cb)eA=xxD#l ztwY!V;>HI3!!9tUAE{g=OAf|l^a(B5skG!KI6RS9_@l?41kkvHgI!RUy-jPSN1H29 zHmdzmkF9A?aCcxY(_(8_gtm@sawKPErak;89UahQFCzlkAJ)3Cw#HB%v}00~t9r>| z9BD(Txtg|WA;}->*#n)7l~Gqsr}gGY7Ws091y{`^VXIHw4=-tkkTeJpJN_q&UQV>VkMnK<`3SjOK3QwV$mnH}^ zoXk{{!z~prM+#KHt08{7=0)Pl5$Nu`*ZRA-K2A>#2<$TTeQ;$Qq!`}dSO|#g5}N&9 zL>EDcYUVZQsvILx@QVN_h=hJ!zZ^(!sy8EjV^mF$9wg{U@-u8Oj}(D4cs=8=gN*iQ zg~(cNOQIgnH3}?L7dck6E3#?{glkk3v}`8`*xbM@*%dicW@MTnYBhk>^)9kgl=_+qGiPM4z$oM?Y9GtU7B+NM9j;z-Jto~gk$TB4m3Uq(%DNQo6C%e#U^lMG zpNTb9OHL00o(K=1!em^OALc2Cfm48tHY_B+)@@>ib$TUgU4qo-QThC*bUogC1R$4=T{aveOi_^P>V*UdjdZQdi|eQM{YSq%Gsl=} z>zvKI)O>jFn=xhpAneN49~Ke{}NZp1QPTFQdbr<@E0 zOu386nJJ9>>d>yc*n=i6`)=|M@Jov4Lb-@Hw?{oZ~eenk##vlShWW3T2{LgTM3Zybpm^b z>_kgB+|^2TSx6-|bAg%#(SGC22Jt<~>EU}IpIy-nhFe*9Ub|hbT-XeUT;KaZ*{^cK zqH$@{kv^sViy%@307~u{%YO?|Q+aDQGep75>u1*7jP=MIJB88ROP8Da^Kr#7;Uj!I zjM1kMbJ!*q`%&JXSH%a6)&cINFa($apQx9Rn9m6^RFk!}7}c{di>7w60HPIWTCAl< zxtQ9<{6AL711?_qf)kB^cdr6$i1|w6=Crs^kg|b$P~$jJOOKNqb(2tNty9&+Gi}2@ zIA&L*s5YV>HUipf-?QN4sDOLB3Bqo%#&Oi?wq{^43~N9*w88|$qT{V$jU@4Z`q_MF zNAj&PR)0jaBUIUkwPWeCi?paqz8(%4$;`}q7Wz7 zWg&X(mJu(k_0`?&qUFt$pOvdqrj zpt_pP_wKO(qGm1zAaCirpQ!HOf#wpYIs|sNr%olMU*)40oq*B&s8R`fmj6Npws2rH ziR+BxDP+I-%IH*3#2MFaH!7I21hfYhaU6E+5Wh+Qeurnw5kUa(9om=V8O?_BT7*+8 zw$kJuN+M9Uy;!k@v0c01^Kk=F_{MC_A6?YUT;ox-iVHO~aRCfEi5`wZg8txN(bJG> zI189aC_Pg=Ls8pFR#!$x^rd2>CRfjRJG9`UOG#|J`Aeg!5T(%D?N+|P%L zuO4L+E|`1__z zV125bGQ<~5fB%wI=U>0Vm8h~&ARXLevfYV|;>{OdYv^j(L{yzFm#x>viL)1YqrIj7 zLVpu(iT9n;E^W1CWG)4NYePg&fA88m76U|aSb8D&cNxb}-0@5QLihcL%?msh9C<6( zX)Ekc>^-rZzus?aFCvJPu){7+3uqX~10|Vm2>QEebK9@aUH|AAmasi)_mg7X@glQL zW(~rcXw1%yTC$#rzx8BpHR1K;i&{7CIvc+kp*84j(oXNVLEo?QjP+ydqcX{H>vo9( zS3je*IlC64JMllz^p_9{`JlJvAC;@Ssu7X|2Xq<&8?x~8MNOBz&l{VX(%FFxoohJ& zcF3rf9P^u*>Mi0`_Dk68m3Q_bh`=-AmFjKlk9VD?<>tg2h40TBDFrL2PLa+`v8`S` z=-uuoY@NwBU3Dyr;`iU>J!$C2+C;LiZIf$!5w=uQ_ZFyQ$MJ?U4>k60X|0>j7jfs;^j=adV4DEBTP-s`@pZ-^Nr7mzR5; zV3txR>*KKg!Nzm~QT6-=MVMD4$kOg^C#0fKgbwHBv9${Q#0A+hNV52>P(Mb?U zWFAgU-xqHiMi7~>Kjb`8dSa(}|IcAc)$i<0&GM`mRMgpywuusTtrXTF9Q|6VEWJRjWM4Mq}58aPa<^I<%)annW zkp>rUZI$WYtqe1+DeIw~v-G>Wr_B51Mt=dHH53n!CQFy@{?BX1fMPftg|KN&Pu$Md zj{aSsEW3yhHRbrGI%TT5qalQFNMRvjVR)__y^E2|iv&iqgJ%bnkEdu#&d6q?-Iut+ z(|a$cZfSCa-zS={oW3sCsE^;;sr;7K$J(~bcx$AOnwc3z30k8*`2=15vX!8AHw#^G zJ>GAyN0{&&^;RziIjAc4-@#epe9o)2t_9!NMsVoHRT0LuzPtkz}`kSz}jz<-C zh7Iij={nf`fewM_=mIea4ZWw4ShA>I8-2XFY+yk0#$2sqQO3 z1T73)IHA_#y7Kv~Z+%uHj+DA9^YGDOd1_;R29>QG;-idl0c*YDdsU6>X_9*U1J!A* zA82nlXepi^O?&@6skGWk#kd$@<0^H!{pXLL+NX7C_bg{NX)bA>LeB_4v<#A-9nC(; z91a+TqF*#|U!2luc-xSwyi?IfbsNjifF5JT>sWgJL27ecc4$VP@GSVV!^cPG^xRKH zDEx1c+pill^Jul-pfV>sHRSgC)?6r1`6PT{?*TFz*)A(;qh}hhN*q}`I|FZRWc0;+ zcvoSezPV%lwE9zT?5U?U27F_!mCa3k!cO5!iI@RUd*faIa?O9SEonZU+cy{Dv_Ntb z{iuj?jImnFv$whFjV_MODg=pFS@+aB!jigQi$XI0*uuDfyX zOTaS!c>3PTN!Ky>dX)L-1iq=i7ePv+WU(8&N1f8NP;9MkD*xn$OlwGSn&mN+2F+7gW2U{Y?Vv+9xbp_3}w)0tb-51*X>(Uz|` zn@LyR)K=arcD>3aO?-GiJKKD>ELF+4MK6NJa3TB){mekQ4Ra!91CxLH-r25z+}_D# zA(ij%-6!x9)>9d7^5?{_E*zS9JHER!9t^^}2Q%S$>&Uy&TKxc-?3}OkU~*R#ZcZ>? z63e&Iil_vtlV@pyjk=85tm5a@Q<1Dl*QQ+)*_(gvHr3lK*;{MpmeKk9@5v|Z)C=b8 zJ&1%2rP|eUVL(@y7wJa>SxY>z`oO-%l=(1SBEmg!Tf~ZW{=C}!=M|5w;uWi>xDnTgOg8=r^8|D-E^ z$;7qXc4?F!E{`{yNd^$G;)%N5jh4h?kY2MOjtd;o&yvdidG|j88*tkX(U?%pr@+}M z3r~%nvr6HNb~)!KroHA5ovxgp-#Ov9gS2&y5nDgIC@xZ7zr=F!dlGOjdWklK4q#j; zesBqs{rpL4+*7RwSY2u{WiwU%wrJ(hfqjn}%?2G_>GChdG5V>PGB9|?9keG9AGQc@ zdfr7gKielE8{}qvGJb&i29)}07WV#1U9fPQG?`Bt+he~!rQV8zXmGB}#O-7Q(m2cKR^;vP8 zA4F|w&pNXQ#)jC#kP82D)!Pi*o_$}7{UgfISgyR53L>SlRS-80>|xcg&dH8ngCeHzp0<4}4xw~SMtFu53|@z^26hw^7A=4FKJ zul=v3cItb?M}4MsvNAJHnfFxgxzACxc<~2Z{+ru_LuTj2QpXN_UoITAiidm(!jZE@ zCoYv)ro^==5y7A0(DznrL(E&y?hSA4i<%gH3m1?@|I1XBO^iBMMPix$g0GmU(? z2v1p_@}iMx`bQ3w zV&a6fy>~Rb7T3NplvJliLck=sBmMT3s2904&0&4AdT6b&7Bv0AyO!z3}=T}b;=f`Mue=U#bn`9V#-Unk1vl5Ju)_*(flAic}=Fm=r@_+(f zu%#0do%QqiF}1Hd+YQ~0L<+=9n@``~X*q9LZ5U+#yb`c+mM2}($~nD1Ek-Z7OHB2( zv&RO@;lZsFzZ=|l-m`nx>Wpf$4n;4a3i)04mo70-_i|n-UMNCND6>)@qg@04-lN&@ zd(6ahnKab$+AX1%NR0c0dr0ChkUYu*;jE2k6r})nkC=Wvft)iUUWM27{kfm8sInTP7mX~=M!lr?YZ81 z9fw$RTy6jMIWXXzAPs56CT4clzB zWommNe5}HJf_$)`kMIJze>CZ-mX2X#Tb9Z<$%LDK-N`76H6!<~+57g+n`Qs4;g-e% z!2R6+ozOs(xI*Lq<&o-l?=n;J`?{B~wQ1Z?xN&VDqw+c)tv<`b|2CI?xTn!Q`Ld%T z7l2U$#=j;){$Ume1j- zcQKgrs>$o`d6PX(M3-{CFjLc0H8zxR732R%eNvCg!$TbbnH+hLLGmV5^_a`|nXRANM!=PyFuzz$b`3cwrER`#@fKN7|97M=Wzd4Gxf z0qEY_rN5Q`ZScqOGh~p9C}!t}|9V~h@Y3Kkj(4ADZbP-sqjXAO0=nT;#J| zM?$n7!r_w0VMJH=R=-b&l?G31eI!k%XVxS@6$w8pE*l*-& zF&&~~C?eHb|9!2uuPwvXR=>Ejlc|#SoM?7fe=UNOmaHl-D1H7#?%9`1`6TlP`{-42 z$j^h7YvE3YGlRb@(jWvTdJar+JeKcE^=3a*MjRm)kv5_Mt-S zbDjCcI$B*;nA6)OrktDvhK&H^@LNwmQE6x3;rsJk1SEGDgUHj4u?hWH6fn4XJp9BZ*mft82JZt+u~#mbgV;5&)Lzx6DzR-p&q zNG7uvj{#?Xmde1jZ}X~euWU|~z|1M(8?>oMg~PzCKU* z(LYwnn-reW2ki7Kt8Ah&E3Vy6ihwAR*v^=ha!zx*^?& z2)BhKQhNeM`B3ySu4HxT`6;JVMTJD&9z?K=O8@Dx2jyYeSUk5u$C_A;6`twsg=#cHM9csG&LP58c;8}>;PDR0O?}h&p^kUQoYYopbx_>*ntByHWPpk^)kXfU`L8k#*q0R;{>Z z3H>ov*i6#Y)On}=hWoq>*JH@OkG8K?@%kYKl4Fu1Ku7k>UP>2MaV_(qb-1VdrdzJ# zJNE}KBYD0k_nhsd8*+`}%OUb1;hc9C6ypE&FCTuX-;ds5|Y!f)o0rq1UWJIxO0=x87&qGR7B7hJ`u?n*So z-X&oA=Z(Gc6$ZJnM0rE8@aR-a;4%<%Qe+~qrioHVSi~|A7Woi64aSD1%b~zf`Uk!n z6EmQFXL3AsmFdxQ+;ItPR~R}($~Cw+l1g?CMtg6N+WFGnI@#gZA*-O|~N0>*wcN^P?4> zz+8e<@AF<8_#%7>OdeV%Bmmqk z!O5dc_JiPI`$M(`{8%$$A&caD&|E<&>B)~q!N%{)9D&C|+1(oRlGi4?-O@bSA09TH zmnMfNVc$4>!-0A>a?VXneCl5)@i(Vvs*{~n^4vt_!zt-MQT&&*@ps5k zH!ZQ#>R-Rmf=FKHeVk(Z@_u6#j~gg%Z)28k>rs&P*ST=txO5Ae@4f@TtqK|>kQQxV z$S}#9&s93Q1@UsBJ993_&Xf1+TpRX+uw24;spNCa&P(r13o>UeRKYtBuSP4bMW~D< zIQKYjN%WIxEctv``Eb(D0ZaK^yV<|-b-dw66ZJv51;2ydM%Rj()J?H9E- zFMJaVxQx=fIhz-1Wr3h|*r#sY;6h`Sbf?q9vY8qOk@S20n|i*m(9ogStP%K-N=7wR zaWTK{9(F0ByL_>=F{qF%dGQ`{%r#ou(|ebM*^b+`C93yGEs?%_ICG!LJ5+ zT3=bwbWcd4Ah}(|KXgVYw6VPZSCD3_UZQyn^^@+c##U62JK{7pBtLv*=I70>Z#nkT zx^wq=%@^beYtG$Cgro;>h$%2c3D=w(Yj=^N!s6ypUcS%D)DtG^#AZ(V2P26C>Nj6k zIx=6pA`RIljfszkXa4?Vc)n5JYgzSkdXx}qK=8l)a+50EoDT?UvHA(3>(GS#^#%2{RX>F`Kqqs<5EE@d??|xJiR3*V zs7ANe)M&SsN1tVE)ZyuYB83}4SgQ!k`&;8zA6Eph-gm)v*nm9IK}w-AeEyTUPC8{s6 zn`<>D!o7q&2{&_MPL82ttu4QpbwPK!R~`OQdJ^tX4R~sy^nnB}BX6_q204Dzqp_Wu`S z?VCYI{+t2Oz4+U$p@NDP$3IJryjb|I4J}vXvGjnB$L%T+m+8vPMFA!z!}!(&!6aHD zS-D%Q2SFY-)9rChgZ`u9jbsWMCkRb>iSoL7tvbd(bNlG#!`w~BH1+(G-h$3I8n9|u zi*aQB-E8ri!_fj4TDg9VtP>YwyI(xLV`#`0+*-bsg}^Utu5 zC-Mo<)~shg5%NG-JgrhCZ6q3u6h5!P*^`!y?jzp)G8^~=|AGcR=A-Cn`=LX`br@wk zGv9ufLKaYK+xkTjHP=&RxPn@2^J9)Q9|p1_-=$0O?*+5c;A@?RuV^y82ZgUvV1$MH>4BC{Nn=p>f zD3Bm#&{wUYvBKpwdnrRZ4$&M#C?t?tSaF4IEB4;l2;Au83V5m5_gMQ`&>Atd`J$yf zcgA#&j}&zb)3E4ffa zL~t&=sI`7CoZIL4Wauecp-V? zTGDBA?@Gz-=Y?j$_*IHvMkNeutpT|J+-{a?i8VpU%T?`blVo&rVl!f;Db2~{Xey$| zk*mQ!tm@si?g*1bzO9Lq7teLXI)%WymS(=3!4M|3)1 z#eD5usRGq-cZPLKAP(_nxDjl`Gyg)pE^{mpJ{z07JskjT0sL@#SZinJq;*dY)X$`` zvN2jtOaRjJ(@Pbyx^^B%)2by%b{REB2EMI%7Af-1zt*#Xx6$gckGKTdxdj{`5p!l; zg)sB22s-H zdD@g+Eys~L8)1M_(naMzLJd?Ez zO(zTQ%n&l$I^6M>^jIR#M;@^{uKCMkSDmV$1of2b=!q`w58$C1Vsdrj|2#&`w<;HS ztiO|w>k2B+e>$&IcN>KJfe* zO`befvoCp1Kx~FIsdB04Hw1qZ9;FpIOqgM5?Ut0r6$s$zva&eu45|`=_e9dcda7Tf z&M}q^JxVb=ZC~jUOj?v5{nMh=Dha3$p!!<}xQl}M&6N5^p0%-kS>J@R2~{~X7nfAm zB$)}+{`*8c?1z><(uc=Ql7Tt=k+{AmQzA@($syAQqbNWY{)@rw4QGaXI$-HFI^iK3 zTK1I$kM42v;i(nJQ10;ii8-DXbP`(~i@Xl2H4ZtCV=JG={mGgED7tB#+;2o2`G7YQ3$JByV6_UnrX2S`Ny zVE!6Yw0UOJ@owB(ld-LBt73BMsmc`fXh7wpP1$+>8O(?^gD|8_0Y%mV*{RGT&5Q!& zLte~Fn7VPeH}AD&#)~Qn0$znR0Pnv?KYA^R(jaU}hjnA*KNY`Ym=o3@CQr-O$X|aU zsdHR2eS}#;&8Ugt+QLtGaU_iY$6rhGl zxBTjO1LA@|8ABXss*^R?#dnf6I^0>gG-di>7YhNhNi`(4JFnbQ3nIplg&nD-wTI+` zmp0R$P#QX}6!K~X z7Je4TjUS`a-Km|kN3sra6)l&D;0_3Dx;QXLN4$oP;xo7clvuORT+ZJa0R{2GNe?IR zqI`+${FA|(DbTkDbK8Jq;bw$A6UG3(o-)v?v`cOnd^qrFFR_#q2MC-0LVEyT3nO4x9QLWt%a7+Q?B=tj8gIn$TJ9o#s z>ANyrQyT2pkEav20NIgr0czC(O;xE9uG*KtCFKI*SSh!%sK97UEbM_G9xK0dRss5` zoldJ;?-}VNxv>15+ufKSzSTl!F+y|%+9sBE>+%wQ!s)oyKv1~dvUA+ZQrinX?RyFS@;c#* zSqMdl&u2-KQ*}m`)Wo0lGp$oLT3Uyy7X=F64^;hVrQHSVXR>{aX2KqeJBh_F5{c%D z#-35Xllr?35tJF^fxhk|Fa+eW5U;N4xhP;;$wGBD$|PIlvW+PZ?a+6%%?a&A;IlrY zMcb|l`$$6@z5vh$SM~S?LWhCL!S~wTS1gKst^Q}P5*y!Z0kGCl6OPzF!j9>e{T|;6 z1}VsEkSTjHa(g)NBt#~dwKX@Ig&;fM5DTVQmTe_&3&Ioa=`^rYlPPj7As72zF*)Y1 zadY=ox9bqE1^~g3e`wx_mtSKWIxtImTb1^1cwes0M!Pk!@n_EJN4mj9qi_dENwvad z)6EL9$#_5BA22U?qiHoV)c`ZuK)7_IHBPj|wg2Z;tkkY}g9s2(WO0+D1zI&0Gwj(s zAO7KyIH07k(k(+a%PI0E6Ha}UqcTO~eo@gWki4{&o6+78^K!*DY?8Y~K4%|oue00Njuq`I zv{O6{9w=6#4a6u#Uc0ePj*H#}thz$u;WSzkFIU?uxxs9AJ353smU~$9W6VD@Z8m@@ z*gBIk$KV)8I7mM4h@O_)(4z%lBc~n?_m9c zM-(%EohqJ>bKiGP5!|Prr_C6Ljpgc~#X0w!)gTR+nT#QP2p4zBnKWXxo1e#5V}4M-4$g_0h1OTkzRZJO_9- zB}NYAoC4xC{mkg_4dk^e&97j~(j5{4I^ZiB8w5=8T=A3Ur|pfH$OVw|u)|rB zR-UdoR&sqwK?*h5?!C%_rcdn;NS`%3kIf}tZTqaN&zIMbFd0kqNBR*2wZo?dS|JpI zg9q5+#lq1C2X6leN4i5KIv7nIuUlGFfZlm7uGb(SaJ5C1${R&pwMGuObNxZp;^lsVItn&% zX!yD<+)YgrO6FuX-yoRy_i%l~A!xt+G1o3+kr7IE%y8JJ|Ao5N=tdFaAxXJel8bvZu`rt&$b&eQIILBeBo&81GuYoB zjuwX+JGZk!r&etx{2YCZOAXtuFMT>}Q^U*8MR=V;?3Q~0ulxUTRQTPnzeMSM_8-V~b1wTLQfaJK&1d7YHxXXGJ z*g*9aVgxqau;FVTa1xC2m!~YMDSK_yyFsy7&lCySv$wOfWDjB~A5)SG z!6)#b_6{;ORVNx_8&bTwL_C*{!`QG!jCJeHxHiNn5&s{QJlbCOhluBX6{QK9rnOqh z2T0@S;K@#wW>u3UHD3YBl3OAO!1WVvpjxQZ)KB!on-1$hjjI*%AAz{ZdVo>KZJ?m% zufSwbKQd{X(XkI0Gl|h@GhmfQ6)U7Rp#}N*!`5|;JZwFX=-pvnirE)XH%(UQn!6YC zt~p1#joOcOyXN9!$98K`@aB83F@vxpwi52Y_l9E3B4oo>&xWmyJ;xWs6^482Yhp2E!_htEM2OX$7v)Kr4&2rFu?t>cL@1NcbxVNR>D2|8w{$NxIL+jenn+zoO*_kzuF+F@$evwhH|OAa&&aMz59bz|D&wT z?`d#I7dFFw0g{99^zgAxp*0$SSI6BJ6c}?bW}&)+G1&na#2Sd zg;0n&G$OAtwXkDl4qQt5@`Q$=6c(7;5;%EA z%eq3Q5RklQ%svu|d+YqqI2e4StB%L{5OGL1^% zqXKvMEZ}i;5W_rH-R%VkmV!v(w;utnUTd@YT77U;@htD;FFK6dKoD+56_R_=q6TBH z-n;MnZqgC~oU6|!Ee9f~(B)I0fgH_C#tlfom|$I5hcO4f?kf9_kUWKKbyH&VVxqUO zlSuyXphQ))nc|t50;@>RoU~|n(I;>*b)*!}KLX&7ytS#kZKx$22k735ELbsTQld`=|_n-6HccVRekXfKL+b~)y*?@ zlu<6)A?8|nTYby67wIPF9%fQ*$^Mz+@&fFxs*1 zFU^uloB6=%S@N!lJg|2>@}`&g^5y-s+b$B;P7!k9EHbPk$0?b1+}eCwW_25_?cA%; z|IwS2Cj4;AnD=P~e7Z$$&-7|3S-wBG0?sSoFS{qoqD53g@-JU^|AWhqsv$S_^ZC) zL%N4!l%SJsby3RF<F@>jg-=JDx0YA!4Pcp5d4wsUL)Zb<6SEIoFPsV6`rBEhfiu-U+AXx6 zkhKUWdV_kC(rSeVMfl}^PU4!f#CQH*I%k)k9iR2DYQj(uB{t2^T6Rgbyw^1d9H)#U z-2rk;+IiGv$JaL%D0l^CZsqii2mURRn&l<;D_be*Vgh`!qi_V>P)WgUo9Se%(i}hz zDMofAPz2cQ@$6LTZ>F&)+(la_dAa!Hy-Q zUFnkKoD!X&uMW?v25_K&gnNkX~Qm{qpv_K1yTsFAF-qC;$GPb9)N~ zYC^!G$VPGv4|=L?B>`-18CTGjdrG@}sqW2oWyuoz`Yi5Jemz`kC%44ic+T!X#Iie| zomw3gyk;wX1~PgXQ0fH&6#&$|rYY$ScNB9|KW2-#x-&thFQC-EB^|pI^*)1GRO-Ik zw3j~Fndu>Pd?Rt?^R2|OOu&C45|-fYr*GJ1-%tlNvq|#gqgK<`7Kzim&v057Rmi(m zB|q}e)SHKcqd7e)Lmlyzd+0vB&Ps@DV_96G2vhCAkG%WbQH69pkayACNAn`-{Ba*Y z%V1}8dLm&;Tv_ldMr-6lQS{gs1{YBRUbV8xdiFmK?$59v8*vF(@QAi+AOAD+~( z{s=gjr)b%tbuVm&r5n)QbNa}<;aMue54(?A0VD{DPqw~I|1{rF9g5*u+tij^cR0CK z|7*_u29rPf0#BPyY&XA*zCxka`5Qug?XO8|h!9qQ1(b3R^2VcOAEaInX*P21!4>Vx~3 zvQ`B6NmhS(_{JNtx2}4NXws#p?MC0$IjmJZ?r2idLNcl!VG0(Kn!)7@0X9CepJ*yW zrv}J-N)9A_yiGS#Fu>qfoKR}}*S?sy-0sAEjcL^$&6&atjP`6~cc``9{9V@8v;&?$ z%ib(ob1sV9>PRwq=($PMN#3(A5kK<9bG#dKZRDZkYf&+NlPeIF6uC3WH*+Opo-_KX8(G?; z?41&ssKr}-jc*55j96r?wO7`C8#i_(zm#^(98eNJjV7(_kL`?7P{*jmLZ(^-T2V=9Y?eMz%4`Y(ViKS^LPZP?{X9PzNh~} zsx&t!)b7s8tCN=}777U10m(h!&^#h+o~eTZA&l|IUVYj|2#|?)Kb>rG)iAzDa24Y>!S|75Fp%I{y*#zszS| z>`}L;0q~`>5mOgla0auS$L>y~y^cD1WW6PjM*>P&{{9-Vy2EFnSm{ozd#kIcS9z%2 z2F}S+Nzq8^)9Pt~^AH>vQJ&ypY7(<3Y{NQ{ zz8mDWfvlZ3gPMrb7v8;GSP5D??ewxj?oP@FD!>@5(9it}3kin#P)rwiX}lswi^wT+m#MUmo&!XZ}W--Q%cobY+vl(4tC z%H$6b?{(1E6}E0M&v#E);>QFg-;W~X^6XCE8{YH%ib3QU8s5cDp>ecjyPe*aV=rCF z?)j3QKBmGweL^F|BuFwHSz9?)R$__1Q~}HBtB+r`aCIgR3Tgt^j`&`M{91#E?O%yknN|?Xf@90_bLVR+a!wbNO;csN?CZ$6F}2 zl#SqvHdW{mr;DDQZIm_f*C)-a#Bfs2#QL07zL#~Kz{AwGUTZ9^G)$A%HEf94aN8{M zb(H?}_V!tQkq@Qe_m0!KZus54Us!ziO|w_!OH>tX@kRlqQN7kW_O+)i#c6XdJz(SS z+Zi&SNf!^nq3xOP^yo(5LwyP|+M{Ow*H`6S_TDXgNph%rl(Z2$*MD9-{N7<>W z?~9;t&BIq~f^TkJNa`jUi41|RrkFF*LbbTYob+SB)Vxu|x1O>SHGc z-28T8clYFxD z?Ox6Dq;wklWO!HJiMz~NQp6p1HNsu!!n2LPIfpC9X1vFG-+q5}|0gOoufLSrswV`u zr`D)XT{*`BCGpRC2yBYW`(F02Tx!o_^NMgEn1v@FxzLgSDD<2sOJ6C-fziVmqG(I_ zy|k7WA2>$9uvdQOyCsS%d(Ha8 zXGs%|tn6Kw-uYGL)XG*?v=8)QEuEbUo$~df1?%}_%k&Y+$j(Qey4SB)v;gTX0L;GC zXKXw!*mxYKlYWVXzh~q{jKYhHieC&HhrYP{_UL+2g_OE)OFFe%D0jx=ZiTny}d9yEpwVm%+|oq2_6+@BitR#xI2vrU9$xd-0$&o>Itu z=+Bjl>ZbyRM(ac0`Tkp5GhT2i(X<5N?bfRj2eW0Z zc<>Q4w!ZhJ?~faE4Ft(;J>$huF?>=g2qyX^u(|&u?eJ$fH4!YD9j7ll-;{j0&%#hn zdN5!pvwp2>HYIlHL_})qM)e7{@40NXQ{Jk#XztH=z^g`nq5m_i$;Lpcovw^h?*x;T z*HQWReg_v7JHgS4pleV=TR3-;{TBVe5JA_EUw-k>#Gw{n>JmQJ{RVlhHPhiu=<)jW zYFa64%M#COJIV(Cj{@Fr2hfYSf z#>^&nNOG1A3Qg(2Y~*|zLb+!MrE)6gR7ehmOtPUuC~_Rb$oYKM@B04!wui^|Ib7HE ze!pL@=j$K`YUE8XvS0hwm-6TN;I=hx&?P1$3GP-4>{nxUizQn;=TE+d!?aJaiwQV;ti4`DF{GZH6I|FPrH|up` zE7KPycX>S}j#O_8-_E0%_3}Y5HBs||jn@4>10B860ANxNdbs1Owj2N93y&sNr8zvD zoJ1J328Xx*d{I*VP4MfDq>gAy#yEFv-9n_{THI-d5qCm|9 zAzwF8rq&L>cDnFm{k3FPHXFg2c4%D>PvczQH%M(2)|?Kb2jGJ;MKei+sZ&3D*g_wN|&X-p60FYW`i(9acUiQr-Q$Z=?uIdnh@bROm#x z<*xLmULx(H3IX}4#4)}xD9M(cJX;-9trie@2XD!DDt#}D8t>13kQIlBJFI0U#1d6Y zZTn{-f(+?1mtSSwjQ!Jk<}Xdf&1dC8lA3Wa;S@BFy6vR_eKqdRHWZI%=)lHfN1|Qx zzEe;2JjUYSY5u^Pn{>kO;prCTm{r{=I1@1MTQ#+&T1knPLXS8+a|#z)S$q@OCF^cS zcn~*hh~o~X^>*qN#(fc*63-C4nY?Q`5ZY2o?J6-kVGyraabAMvFHpGK2jo4@CxYY# zRYg}($SPC6sdtheGl@FqbF$@vN{4N~WJ-0)**G3E%AJ3ej)>4a;<)hlG{3X-=I`vk z2R{wF9rX7?-`%|P)Ns^ldu4|l4LeFj2-Aq%wj`}&-LJ8MF7n~wt=2ZGUgt$Fz|yVA zQ%okLV*koTk+~~N!i$JBh|M-eo;GZ>7b2rTWYFfE@uz=!4dI7=@?4la=3PFkV`Qx; z)LT%apZ-S85Z54PD<`Qz*h8|n5WX&JV^|mwY}Z3%PZIAOw>H<|(7vT16~noUm;x)q z<0Un-i`=UuwdM}_6Xl8YQc>}uZK=+u&@4%+WX%;xeyQWd(Vn`hTyXp=xC!BDh;Kc! zGE>{C@)!1}Agkjt(|l!hhb6;Ng@1jNe2Z9s2+*$bkv^cdh#I{56EUdEyfK22(9li0 zws$0E6>UvP8qhrH*nK3Ki^9Vf3zemP zEV|YYwjWIbky!4xZxW2Y3`}oaOZl=e$O5VN(yv>NKrMsq<5w*^47c!>>A*a;YN1C> z=YJ!HEpVGM@s}tZX*bZ<`IrcCn#wdgr6*nX2Wi$H-lHRFK3;EBi^r&oK&omrIQDW5 ze@7U>3x49>)-;5H7BgtC!#f;^jmZK&j?9$1uaSyoS`n`{SeV@`(^ZAe}iQ5u6Bpby4`<5?nEE_NlN5DPObYZ;Gbj zTTZ}sOUfzZ;jyl5#UdKWImdMUaWe&X+2K8UiC^91=p4^z2)}k}R!5@Et;LL3yQS&? z9n%}rZA0&3(~PJL@TF1M$+WO!(Erp{EXDJ61MW_pyK1Nd>kr5Mvga*g{B6!9!TcrZ z(N@{4eGCFKM9tQ5SosYM57e;c!i*2%A)OaVS4-yy>KWJO;EDnK-osExcF-AKd}ZD2 z+m%P|-;+V$$TPkeb~f%6H^Z=Hhz;~Webc7iy75KQkI~|{kd?xq3!4+1_|m)yxxYdg z#K)5ZHeZL9V>ZOUz8H4>Xu#Qwv`3>u((WuA=Nh;(moU6T?jy~H{+vM9=t zzv?$sqp|4^?1DRN`C2D~-VU~4`@y3){VDn9nA?~_qVStG3mKPTO76tso4Rvs59tyu zNvt+{!+Sf4bJOVdTSil@j5z5Vm`|_UIXRm=vQbc{KC7r*Tzs8lLck9{ydaG@EvILu zEz2Flt=j$k1Hn5QXZO|b`Dn1~3e2*0?cY1GO&@h5&t5pn47P-6be)&4!wx=O7x2*0 z146o2pWv@t`4tp=Jti_lXJPJ6-$sn1=Zm3#{4{G9u2{c6S3T=X)ZEN}K(F-~mhdp@ zSMs)Io;Q_fpGGzPrRZ2Y?8VLf16_S3>dnHbZcUH&Yk?`^u*-N4rda>_Xxwu``OE3? zEucmEXtMfQ>!al77L#QA5z#iA7Nc(c3}mj zo8H;>VK!usM*eI<;1OpnogW{AU5bI}2Nn;e_cNp$x~XQ}`;(jkB+gBu;*6FGbyr;- z8h)mrC)>|HLQDGFz1VKPZulYL?v8@zisen=U|UTB#ly{J#MrUScUKz76U|7IoDA3k z_Ra0l=LvUDvCeRTHM+!$gJ%nR?H+kEH+pxU+b`ddsa=->2F4n8380wD5dWM8rox!5 zTaz%sVqV2>!gDZCnJQ11+Vex9TueQ zn?f@D*>9&iV@;l+?-E6heed8L&zL8Vpf=jx*-B&R~HVpm*JP6f3&Qwkne3f3HWp1CjKy~ z+9SD356K8J>%I&rX z>&7h;n3NnaN50P*=65Hc9YHRKxvmFdr0vNj_#wul&sf2U(;eNA{(9RiBjBlK1wRAY zJ~0_0ik|?g9CvDR7Mqj?@pOH>PT*#$)T@+I1mfre}(j}s*@VBt>BbR z0D9XwR#ziEZI?dS;K1Effh@HCqUOdAFe%cl$bKRVwp_1^mY5s=t)dr|FF3$B;8=y% zP17J&SC7|d(h44WwnxWJA5G(S7PhysMD6mp@Bxs*3A>|Om z)|%DWS8fW3J=aU-IcFt+3MR5yXOCygCE6FaT`@7e@`?YYRwxUjUDkj;2EEw@?4ong zxOef3!z|)`y^e}r93x28e1+g5ESU^6OecF)yx)33f>^e7?2#r>&qoq=q1^ebaTW^ z%EHbNqRLD0OhI@gS~5IZ^a7*Hf|l(MCrk8*93W8QW`xT4_hi_6 zOGZ=$sr?_Pug+^^v|~aFNOaEvjr-w0P|A71ujCw0CIvIAmLIM0S-P7@N`-y3#Ldm4 z;ajR%l<);nRK2}d?J(uHTBREb>r-By4g2cSfC7p?{HJZ~piRZjO@gmO;CVoHtrqnN z_+eGG;UE3=U6Y@|JlZLCZQVxLShI3kpu4^})oT0Gwh;~s1*#YE!g58Y--gIigVRYD z&#-~5z6{F{P|o zX-WnRJZmGm$S;prmV;vV%hPlBj#jtJ>!>aS)q1jc(yjmU_}6f`s{#xB%D_$b{y zdd|)L_qL@uN8qyftDk-FEra#=x1wJHD`3)qsC(N!$t_cY9y(?eOpJjH9*Wiv-j`ke zhNCCE+v86uBLvHwRD48DMLHrD^LjF{_2W}Osp*~WNPunAO*QhYbi(Ju$IY+zt!NdN zSDzT(FQyHGWz%XRphJeD5dS$w6)oJ`B_{^N$?M45-n+}c)MBGZ`X(@9g*{e3o-ARD zhmPZ0%&%7Y7}&cBtMy^Y=EfN$|CEYT-R%i{f8?i`{Q z)NFE>jb1*Hifp1Gf!M>pz~zp*yIIZFZ87(wDfD*~Dgrxfg-k3`;(5b$<&zhQ`NkFy z6?T5jKaF@3M&}?%Dq}!;Fr`nf@fA|v=|kG0s@6Ts{sY~kU~uu4g^4Ig&vTv^)D6XZ zmLxD49u@HD^V(d3p$Eb$BroeqkC8AGf}2{*LJ$%7T@zez;$rNUR@_R9l2$%whic%T zh`!AFFU%J%D?Jz{G;gRu0BE=$Uqn1NFYvsgF3#s(BT#he_TT|%X^a3igG`i}WAxf#h9t+unC_Q;|at9oN z=uYKIaJA9FXzR-nOPE^SZBPwFBMw%B7-+n#JXby~aftN3H8k|8ejSAC%pE81es__` z8uDApeJJ&SN2zho{h4VmfOl-m?B@)1VYR@iYzG!t?_ype%CCNUu_oI3p2yf%{?Gn8 zr}x847#b;CcsQ`am3Db8=%$c@O&qcTQV6LYH`xJsUELx`cI;&kBx?lyaWUz*HJT2* zn;~+r2>1ahv7eGP>UMReEN{Hy|DxG=V}6qoHTOAy`@m%%K9=*cXRD^kDL<3hm=r{b_%o zww!JcKLK2L1t_=mdCY3TLn}0nFeNA?)B8Z8S~AR-{ru+yZ+N^dABi1uw5ApiJG4WIiNVb9_dc zVVj~VR+%}tH2p1HH)Fs2B~e@S9+Xt=ALu}qoW^AdGeSUXO&!a-OjMhrorRF?OL1lp zYt}oUK`9~dWj52m6pC{BU7t~*$m4ho@JOX>O3|U zo((DVaQrxQ?)aH`{?Yd5OR~B9x{*!fWOKO*m4SILC}Nfesp@ESczy zyYfD8=ReyY!JKF5)#O8*$e_}`#1+RQ1l;IXp(w#?B(w}tg%93Yz<+>?BmGKM? zvX4JIaqe34FV{hUTm#5oMdjI(=D7=tIa-&W?_|oD;ea%aWhN$ohfbYy9#7jz5!boK z*jrW)yeU0%Gy1v($j3dcKI;}{9%~#VoEmb(%F*leA}Jtt0Yu^KiasUiOj{c_+4n{7 zDoSRicY0~vJIku_kt#xAkqco>66AtywUu}YQ?1~VIkhO?n2gC#HjTZc&)iyOB)!r#?To7foTJmu7+ceE3)oS__J44v<*_YwFEyc@OU3IMi@{2#%PVFpF?QC(_M#XUYCkC3mt41CF zTjao-$-)&s3qqTtggnCG4G@G^(JN>6t}~yTxL6ZUC?rXpr%nh64vB#9u=1U3`D%Z!%)_;itu&E&3ePP|Y<6bYD3TI`x;5YNT1j1oD>$`DJ znZwWVD3sDk`2qd$Hiq<(2McL(+Twi(jCtFWNJvPV(z!}E0V`Y5?^JFsv0i;jRvA7z z>;h^q-Dz%P9NYO1bSy05N@I8jP@apN96`DBlxJlWU~hGpQ~aEu1+tWY2uQT9q2LU= znXfY?|C%iyUXx8y4x_&trnH8nb@cKm-h;J@ML;rmAU-_2X^zQH0JiA?HE*271 z^w5spvyz|V=f9`NWjH*Biz9yncxskgU{EVfJzyxM;GtBwkl&JYL~-M_-s$zdT~@I? zKu96|2gC@_Zdw-QV3B4!X721pQLWD&9rUh>(WfX8K67vR_?GHqk4F&UDa4dUDWt3{ z52Y@s92urn<5nfs+gtRWK%TwrDE^E@iic*;dXNh2^3AQ@)ToJQyqbrGJYwIJ128z&pUS8e2%;vpJBjz#JdiVM?6hc}G*0avI%`GqDe z2xo$F*(&^SMi6^x=U>WrZ4{5bm_cpqs~us0FN##!#b z3DMBajh^5!;q*t38S2QsKaj5V8MUYsSj(50vvHR6K7aWt3wV)E;AhI5bj4cbQ0ysf zK1tsYCg+FYmO_Y}y`&_Ssgia^NF+ZG6^si|SRbSroXH9%)&gooTu0*~i*&MUMQ` z>YBg3MZIxquttTAfV6)p>MYKf zVNaUBSm=K&XY7c;h$twaXU0647LbMx5D2zL!!SF#Ma|(DRWkKn%rE7Ite*IYwfFE= zPqGk?H$2TzN6LTxxgG?3FXiC-+w^g!hB9ttq7Z}>G?dUDti>Wy- zEKic`m{<4C$I!XDRwAI(!RC&TcTAe3=bEW{cJU}l3Us5EKEqSPjv=6;dj6Xn;?7~n z#j%gIry(&9CZ^8D;nDHj4bt`p(XZ3it&VXZ*aayUIbfwCq|cT>j`VEaB=xbE1fU;r zDekV7{*_;By|j-VBa{BYL=nKqw<8qChqi>6ir)$BEfPHEW-Ngr&zbYhIBut6+vDO9 zqgg%%hRFkR-{xl6ulO;9d`(+6cmEDptilo~-Sy)c+KMAUbo`z_!Ywz?Jprj8=fh*k z#EPK^lzm0B4g)MiAjN(4KOs?|(sIw%*7pb=Q<}v!z(MW>LTaWR16+_8eB-CZZwCZ& zM$`bW^}E@Fc5e{goDdU;-f)<;GkxStD<2ao7Xrvozq7k{%80+*(M$&zd=K^93@RB2 zp|g<3M`Z<_Ay;>+2 ztan?%CRj1+=`NNU#c^Q>Hk$T4k{pr?Gqh+v4k>N#%Q zYOWqdDOXCX#>cx=oV$b>HGb>+%<0w!5CD{o2_o)$%R2Ei2}MaY7n{-j$Xf0bPJ^ zUp#5h1ET)&TUEZeO{|nmZ5FBREsDGbSq0l~O_P$0k@$wSNX;!GK4a(of|%hr%@oPi zZQBFkefQbIpw&p!OU_g59w{sD9S&Ge&o&W*hqq(BbI4|UPO==g{8gOpWID@X1?9tKYKzo(0J2owNept zH%V8ctQXii*X^F2dTG0m`m#!@cA!V7dgsumKT!Q?D!D=G?Qm+9SD_AafHeaka6JngzaNY}8Bv?zX zWqWr4V}}Cd4G(2OAa&Rggi6T~eHge<;8x2Q4iD)aM#FnT86>sG!)}@GO*<)RzWBUk zSXJKnoej#NTyW%3P<-eUR~V;}XRhDLlyGUwJ5y#F$r-pRNb~n8IN$QOk>aNc?OqLi zICil6S#eCAqRL&WhVK_jd7#9PfAbP^kd=kXj8jv?A&Swb?cL6!jgj&U8c2Pnp1S&v zIPwv`k*H~U;M~A|Va6HMG8hC+*hU1c?Z!P-6>?9<-p(8{SGtQY6nJ26 zyR#3HtXj8yGUzc@(6p$Wfts4Chg`hij(9{&e`a~xbClSB@-Wk|+>HVA5p$)ABkVLY z@wxU6i~5~1Y&ayqRF4VWT-np*c!8PF9y|BkN_Vqr-VT8f_L1&zPjqy24jP=_A_f(h z{oL~hs?twHi%wo<;l{~Q1$kH4jD4#{w4gsw-D~p_>K`asr%cj3P||ap^+VV!yNMZC z6LV3GC*msd`@&tto_5S(O&n#-Q{KbwVb$X1%Mygd-c`?eX2{aZk(5&|ps%&{eQ9|M zXX~84r681jYHu22fveX6yEJY<)krOfZ$?c44{Vf%7at=pXqrnjIWWf2z=k7-e37=qciBN^w z+HW)UJAa=m)@u`wz&9If1GX_PD*X$)8|njbI_2XRJsXFAdq2#pHMIH#^FvLno=>@m zObL81OYA5kl9Fx=7(7r+44+pQ6mQFe;2Ig0+R4!BeK&%RT*-sR>uVg z<>U94`LmhJ;U>U3 zIGt#e<{tt*R0U|W;Auc+$Xj2@WU+GZZtt~cMvkK9GBel`kGFy6BMmr5oh?XRs>``=)GBzsnxYJkTB1;;YCX>dS9KIfgZBCroJn}Vv!~f8hjAF)OtGL#6YE6H<{dI8Tc3;`=bscKMMJV>SER9C2DCA7Q?q_?i12M$dG%A&j{E_yB1<`n$b;mG#VWqD2 z{)HFV`cV<5F?CJ*_fd0_Of1_2D{7gwT0SS#&mY~O#;d(uA570%krn!g^2oHQyoIZ8 z_7Cwp1CKS?5DY>#s|)-tr4hGx4P@oasfC@piCmf4OEKl0z6}FjdNiVJ@f!O4D)zx9 zEAYnWHY%&{UT*Bs`|B=GH)lJ1cDY;H62v}uzW;z3VI5vH;q7p{j+jo_Pnvvqcp>xr zmx=YK#{*dDrs*RN`cb-#?puDl+}a#vu9`bokFRyiO$Ghp9kX+p-98ckjBFMI3o+yK zA`py&G-!W)i!3((!z49IwkIYn6I1VfI{6$%B;l3%D}1A33Tya$BJIX?yKW!KwAZJF z3wP9xJg6LXP)F*wcb6OM%D@8N4BVay zOjwGi9d7i5cln4E)T}a`t=occ1sY z5bX`%@!t)B)mDqnolJs3`bt>kJoV{i$5fWw3x6q zjifzs4KB(z7Y`5oBa#)-Av}ge&w}3B_cVM{@XDx_dMg#F&|qSAv5+mOT*4_aN1OfkhpN!h1gL;XBvpSU_6 zg?5?E(zN=nWi0cdi0>|lHFve0)ylK(T0xC-;n@b%w2Qwu-xnm7m9uZErD?HJg3OEZ z=_gEE667ya2LrqX*%wNx9&&yf%+Eshk~>-q7MJs`d^!#}mkaNzCVrrI|7YW=(>-EB zqD&HOJd!-^&PHFHiEDyuO~x5P%lx9{Hw9Kz?={ZI9(fR(7}P6-7}B)wJ$2>SyjF6` zNi{AQ4^Et~o_NJLgYA1ZIp{TRYsvV zT7Mx>o5aIU7~CUFCHj(JV?on(c`0kI5Bm)gGfvfp;ZWM<-x!BswHJx+ybl zE0T30RG*gkNnbvRObi1X$IHBzZyW4y)@;A3j ztFQar3E5jG7r6kNNndEIdf;>>I54~!k7v)+d+A|5T)y%zyxAn2OH^0OJZhzpO4z9T zXG&(WP`Xwdw#%UuQRAXR>+Sn zKqO8*Y&P2Zd(ZYpa_eSBxqM3DZ@r{Tzv~{|@M0Y#`7Xjyo1|>71167r4&4gVJ9Y9@ z2$>{4H8~SfBJdb_;v9Rc8$nbLId-`DmF;i^KB)GTXMF5-xv5>orL0TggJzXEnwxwYM)@Nx$xC6txs?bOW|NhX|@du(0IL-Hj5Y0q& z=IqlSXkD3j@OMhA!eQ^7oYRo!dQO+i(_gmcE%98KIlfsfTE!a&kYU@$HofJ;G9UJz z`b*nD+j?ck_LT?!0H5W(3JG;@#xD{M(6WT;i>0PmH!KKc#@dS*JbUYKMp21Ng~P$x z2EOuh`GKw5{ONN0JY&xHICh%&^3+66>9O>q-U}v;o4Opzw73T!+f}WQtKDjkLTVu-bhw&;KkMO2zFT5L)1N`z;FdD$MA)Tdvig!n|H`&kzXZRw+)-nzUV4 zQquAlFd>Aw!NoJ;rEKG-GDHo`pO0+|yZq0w6=GX&%8)d%WUqMJtQ*o2+1cot{BJ zhcEwRJFfTAk@*w1EAPXKnNG2nULPvEA zqZ>N|X>xM`4D8^O3*klBDp@NVDgEaKn9;1c=ke^AGM;x=5Vx?@%|PnF#uF*CFfL}bko>hT^61+md$dJ8q#1^G#Tbr%uuSQV>2h4n zzvrdOc-cvD^aNH^8E*YNF@^fj=|YN-h5((O9Q>kew~=7V{F(nEJPw9Pxr?5&X#Kv3 z47+sh=UgV_gMP6n!cZjDy<_;Iwhrg~+#^N}S0RLL#tR5+l&}vUHQxRHI2`l1>}?V3 ztiMYJo76Hp^r7#zM(1Tx)mM9ehA*5MT=7Pg=<3Q;a&CEKIP`UgEL_-2_d5qcO>V)O zZrkeY3TIU}PQpN31M%g7Q1nMyW$^6wOf?)U&+A2lBre@ux!tL88g0Af(5#f;cb|e! z|LewPCN*ng8M+pu#Hw{SV&q`YQ)stVzs&}EQLi-prP`}=J4KyTIfm+ZflukJ5d$X; z{6=mWaZBwU@9hCstABg$>xSXF{4Ee+tBJ;Ql`is^0s^_H-^8`eJD->Sk-Kk4Db=q< zH8dk9u8t4=dz1fAvAAfSd6y@@=@Jjbo_m8a9zuJ^PWW2>Q(#>db$2LW}A8G!r&EQi8kK|{ z3HaBT)b?>-tBua2@PRTmzP2yElJ#qOY3%S+dYI(jWHH4p+2vS+iajLBA45ZCzX@2A zn0wc^=Z>adl~ie5;^&sC^5WkuV?J0jj&xxV|BPS^$O^p|O~Qlw9+@Qj|8-Z% zO;ui#b*=5EUZk#a-E*Dlp_6d${!k->0U1;aLb<2wZ-)VTnEXp*V@z3^3x!i0Gwv1%MHuxDImsT<_;$zG4qX$Eq05^BiDW9S+Qh55upw z3f-M)$x*!k^g-P1@N=Bt^L%&hrR5CP6W%%qFgjU=P_P_8ZND1=7M6{Wh!ZsWD&Pd9 z@TFVqrPw@|*Z6s)a`%%@OPhKh6QPvnpO!I1)mK>A$&cY}DOI%I(DgPM*O8zg|B!gH zR0Mw(*gcX+U4h`U#_TbYB+iVjO(-TyTzSsWg*B@xO_X}zxTC5{1bQVrEtp~B$lUEa z9h_RD1~Emg-+yq4)+%hUNpW8pN)bRFa%*#^7Iw>LC2+(r`5D9kb`}=N$y~khY{?_! zb>OeLbk*R4T)Q2Uv?}Dnl!Ku!to&whdNq}_-$8fN`TkbbUs$hgheG%o{L<^MEq~qE z>E6KY!){Uiw?v5kGEVKXitR-w)K3qybSRh&N?Wq`j4U6u0*0k8g?i0Q^n?mL=#x5j zqmMsl-Q0A`GXU%fZb#SRVA0{l=jyu~=oLIV=$&Q<-`;c-!ru2UaaK9`R#7$}}&w(pcRl@d> zhkxscU|X`iX-(v{hQUbKFq9cSak=B5t5D~}hJ4`Ja^sh^N!XenR7Rg*F+$W@&e$QTA)#j!@kfl_h>8*k z9ob(WYV|8BBxyI(Sw^|`*Yb9@+3))8|3-5fZuc#H&$E3C>e^lJWoNzxOcHwmehgY=nkF)yuW+{u}HU){Qg+hFAC|tLT_I|L$r6&Gtc}_C9 zQfZFReQKxx*cVCGj<{#KGKx@;+FynUgC5n21k}~;&i`S1;GVJQ(R=ObYhQZL+YxB zD>KIb=L56#!MhgHxox@4`!*LzgSO9<#e1jl{Gt<3D`90Zo4v@z5c5D2l=Y5>Z;E02 zfHryZ`1sUW<{YaU>15cZt|Kx|=BWFv(*W!gnHa6->bUj2)rz4LqI1==0v4+e7RK3} zr+zuxV4c(K>A3c^WS?AJ&x(wb2vdQn`*;{FN@u8BM=VQI;pRIOZrb0@RbQa=yhVWnorY1?bId{Z9bl`ce^B%DVYKmlkVtdI8 z76OH-z6nd!V%`NIlG3Su@R1g(?};H__OxEAjtxa&4<11C;(ChP(O%7`aYb;K)e3HV zw(jD{+suS*x}g|J3);v8SM&9}pgmu~^Grk_q>Uc@z+bl-7CpTdPE`zL^E-3F1nF6l zLRk=^MnIP2?37?!F272!g0ay~bS5iA$D%?v810n_SHq&j4f|{E13kc32A|&D7~UfH zIB)%0=!)~SA2s#N_*695?Qz*sdA@)z)KY^l~i(D62gBFBF&JjEsb6HB}@P1+mN;-0Mw zU3_3#jCQ7^-}V@uRsv!vIO>1!B3G*3sT~tZ*lgqcg|&c0A&sc-Tf0mP!aGC5Jo~C| z^%B+QYbTB7Grm5s zWQx$aO)5&XePBvh>UNg~A-iZzTItR2mJNfyr#N(7xLezTp0j%WA5N{- z&gdMt z4FCDz{*imaZxDc`baA0)NKt*G=93Ye#YtC_ZT=#sLd0zyR=e;YO`SOLBI)GurB_cV zaCknqJ^JenRY87>tK<*(b2gi!39ujE6R|$Mv9GP;X6YB7%CQEnVhq>ATFsB^R=l=PcrZX+d0yu7&2Cf}vV1YWIL@Lv&FuaREjLno|+-_$s3V9;DvLVVsxn+uZE4as$y zctxLFr?pmL{QgiVPMaUPxTP8`M|q>8vZl}3k?%c-P?EeLL7B@*vr*mN-%Ln*0Tkid zPHBD+CE8Sk`KF&3P3%IKb>>P}MA%JH`V#f11A>hDLwzZEZ~$IGWFHb8Dttt&MUD3cSb6V^9h99` zfvDfuDC`4LQ)I7!)c8C2OqW&atD5~hraz@O+MT?UhEycAF;Klu4kBfO5gv1H&FZeA ztehVQKbra}pR#~qC$RdXfb2xyL4Tg%z5Wz(y;ZI-ugRjPh#RWuZO{l5Fx!;~%_rK!<4{fvPB`v1LP-rD@LhHWUR)4}tXk=a1c8H!Fb1?sUo` zTC$^A9h%_~i>+iFgRe@vpah`#bRcfIXJNOx2Cj2GSQ`2or{lcvPI6%If07E><~C7Z zVg+gYrNgr{GFy=1Ib|7>;no1xR`QJBYP|`oyFs4pl3iMsUTSRI{vGow71w&aA}5SH zYRS+M6Dr|K67qh_>#aMNM!d^3bb=5$s*)pcU!_NUBCab~`X_&sPd`{Oo}LX6 zJQzE8$011ut7|0}=V&*)(HC@o>YQREIoPerC+py|qo5AV_y!qkOf8&*7yX9ig~i=R zr2vmzN{~t~tYPf`Rrel{*bZ4fJTw~mZ`Xper=pN5y`cfk48}&_!$(|l6vSE?w5${CCGsGe$R$Lq%O@1=RhVA(Y{fnw?11QG1q*Z(5vNB@p|rLN?XG`oQ^ZGM0MWBt)^)cS$8)?Z_I7Yf|6jvuEQnt&gHp@A>-Ny7 zwN*GEQ4kiS?k_0Ajhn62R5B2z3vCG`b*lC>?q_@=zFSQDcQp*VbsM7g&dL>jX>Tty z(UCWs))B-~1FVvCkNw>A)oqi1BKLt0FVA%!Aw$H=ibOm*I5i~6j@@g7*N;QEhisRc zb#Y14TZmN~)847&akAv^%eS~+Vv`-)FDp^G8G_uwDYII%hmjc}__KYK0pU* zu;BjTo$YH@OS()SJeRtaFRG58Xz#KLGugXRK!*srm! zvA1uuuh8V+5zS)tkjlZ4KWR{ae*YyaP0$F14+7za_zVDQc1@bem?cs(M=EKg8e(n9X#gRYcwM> z^HODD5qi4mQ!K$uC%;9$Bf6KB>}~?x=-vG}p~auxJXOF#m^=7GO4J^v|Khh3E+Li? zirZ^w3!wmz;9U-uxMTW)3`}L)R(nEd{EE4)W!qC95je&W4=(J8U6>rg9T7(y_q9SE z@xaCF%dQov2S33IvZ43|mEYRy8x}&&Vcd`}4cdYe$>;zH>nuLJ?3NSfz5jF&;dBh=ypW%ZZTQ2n&V`1^ah9| z&y&=GrKTFWXXI?=PV@Y+AlQY@wilTgBdYQp**){=S5xlR0}H?5Pq=c9s7^@Cp_8Ix zT6sP36YXOm;`R?Kjos>srwJCdS-l?%*yFLTpxj3_4^;&tu;+5u+BSQ9RM~)#h)Ak7 z!`C(wme?|-TiqWg z)5MQY_rJyqO-MKE0w-(+n4!&axb(4pNUhS?HKD_5*g5?fAU#;X zjRhau%LJdBmM0Qth?<;X!aZSUsh} zx+N>h{pEV`uOa?uebZWI5gl)yq6?>8IG^77aocwFjHjk(<^maLY}cAZujfIbD+@}4 z9wbD`$MuSX%*^L_seblQ=$FYL`W>`K7~fvENkkFf_+jj#zX^D{0;)G^in#PCD}>Kj z#^wK4eZ{ZqFk<49W(FY5L{-IOVcswdlvH)5-;$#X_EDNhS?}ZY8|@iq(r`wWDf&UY zOPVfXWc)`CR|@iznH1i4|2lJkyxjLv38n&6Y?y2l8vazvBzL|a@^Mc-gq@ML=hj6E zvCoj;=I%6oMq5SzsBErud+SV}z4Hb5^7|oV zk!l=J#a+rkK3D9|ECL*O5iI$uM~n zG?RU9t;b)V@Dy!JgCpxe?L=6NY6prLB*s8`j%_SQ0uZ5X@qRC5Y=G7Uh(haLM`yd5 zKg^}fov+&jo2Mv16%Cd(?*5*U#-dDQNAF?bD^*$lD?G#kDl{6v$6Z z;l#W9{3lM|+lj1<->m(ELHZMuq~1Jskr$07v|}a#SkQ_eFFVO^*wEBMQoJXg1D})} zSkBk&wsMZEjvf+08uT~zxXrW5=NjP z&qt?2k+qf!|1;{f(>PYhZ(LDPWpWvRdwnCHKPoJE_mcfA4yOp1va+6c4q$GrFg?lc3-lC z23T`6S+!*3K%twV%~=As#EgTnD%J~o4)WR71}x-9Zk}Ok1$hNEvXmw&lW=_w zd5g-}g7XAV1PEgve4Iz&1kW+a)p`U_hG##};fva+01k$OtMk@YwR0B6mJixtztsMz zOU{sR9n)v{M_MYRhVqk;RcCy5igEJ&*^fskV-c!+lQ;b1{cWShpY5+fBg2WY7WRqHV^y{FB_cEPv{29o zI8&=%B)OVsJueutHlG?*`LLjOJrB)FJP$xtb~-mAjmg#8CjLNj9~i5+w&xOVGodyN zjPwFQJQz}KaC8@yG2WlEh$s~z0&7uk!iGPJ!FNI5+eK3!zrQ_P5+|Ay7({10+lx>$ zgUWXIqUct)`L)hT&=ToOMKUMr#zZFtF-kAwN%pw*vlN-~Swr2Ix}5_(UAQifF9MI{pt?-?Vb<+- zQ>iRo(*wY)l${k1p-WA&?l3oXxWC{05D#Z2VQ3sH+9ZT9Aw)WYBE@WmN#L!Z2{fYk zxSoy9P*@WoYvjH3FOZ)^1`@BE3jvY$K5GgUdpUVTV0W=e~E zwYz!*3uR9MFX+dj1BAH6i9DrN#8c_oX3nUMK+?tE?Z@F56$r(&3j0FPUvHhK_Px0M z@bS54V7`NaDN*!;f0LB|-m)m|qmw|oOw0QP-%Yw9Jh;vA!i^q4v6Lmy$l1n5igBuB??_eUmOl zIp6&F{hx$Gd}+&TG-c<|WxtKgeWfyF#arEmKkmjaMQh*PxID?n0Bbo7#@>mmTN5In zkcG}<{&?|RS0wY%1RM;>y@$J+K9^3sROqX(I`Bax{QnHi8?GOhUt>?(KGpdTa?%{K zb1=~LqS)>3?2f6AJ@9p~H*Z`7672g=Rxr85hx6ugp@|7yqNV;4=hWwYWE1*@uv(E4 zzHb_H`bwUQ#640(X3Bl!t`{9NaoDP5Dg>!Q{)3!%?VL_Y7&)w~ACnJ3T3LnJYmHn! zZG(N}P!M9TXk!hR1>Shci-+5-Goy`_WSL~({16+sZEkyFWyfe0k(?nsDW37`U(_+r zW9!@a5oAN`HCBlISTxzoixCWnmc`~L7?q|`Rn!GT99KRy`_-|QKGRi`ypB=G)MK|9 z8;ke6ubXPA!!fDDVF;qp-K)cY$J%@xMgAXEkS4wQ8F~l@9g%aHClgP-CvfKGBVsYZbW$@( z(U+$u+AB;gROY|<0G7q8OY9??T~zt@hz9$EQ5jIkJ6XK4w;HvQxcc;t&&|{1gP40^ z1jZar*sasQ6|1#xWgYvITBa!wVXQ3OgJFY;=xUOTWK6wp>tW;o2ylAZY(88PLwh(K zNN2K*v-gQ-@i#{w=$o9V1849qqV3Sp;s|xtS|9YRVUqKUP$k zBRs%4q!LCh?G*|GUEFnKk$UF1enm9l+2ZiWZ+mwZ6ccFTLL$EL=v|GR8eG!7025}k zb8_9Nc?(4ou7>HT782R>l{Os^?xe$cp9=zC7<7?NDWHb)D zuq46kdn9OP;^TI-LE^>NwQtnQ@qv%!A!KaNI9pJdgC}waVil9gAil2 zOqJXVHHA?0X~KvUsrbrS4fU0hl?;}A)6~_&?TTR>36e0}=|6~92K86rzt!KS-48&jdJQ?c-EREth>&_H}je<=R#0#-(lE)^0dq)9FQ#&H*18D4*3>4xFC7 z!MhXtcIBGVO!?)qZdCHzE_%Jh$lcr3?v>a-Eo8Bb@W{W!MB5s_RZ(wRuxeDA4CmA) zqaKf2nKK9E$6NF6xy1N4y6=qOL}e7oEJP6cE%D9Qk)xQYmsAi`QgGmihuIL$wj4RS z?)LD(wv%qzOzw;DB$C^4;?TSnS|Qe#*DcgyxDQyyA~X(Nu6l9F`eIGs-lyA1lF6+H zG(cJq-@E-i+1w%F_c4)^m*c0s6r-XpzkZ`NaBA2HHhgS^e!Z&k&x>Eu7^n!heuF@6(Su26h|F))V6c8tJF=mLxUX! zflBU@d%ZU@@9Z#IFD6$Q&71sX)36+M`M1L7vn@n1meC=c+Aq=YANQm^_rA*?C8IS?$6MmZbXn}5jdBgc!|SEi8po%G zGN){6;hg^9QZnrGu4IP()P>ldq3ilvzJs$S3`*+Ox8jkvuYYVse4lFf*N(i=(H2SZ z9r1-HHYk!aCOw^5l#h4h+K#-v%R74^uns{k1(bzx_{z>MN+YvR)L z_47esXkB%ee-vSeewQ|bmxqjQ?pr0)O5EupBcDq7qOn*sDZy^BNMSDfdS#-@!Gyb~^==QfP~F`#a{OuBzysT2($XsUM zhwQ|=I)!@&aIk2N;G@4ym7n=sZ_=E1UmaK}{pnFHS8y`z^;Cx+>V326Im2Q`&FcpR z`nYcW2&1OHqT$6jkvNfqo-kzeYLa2><);QZoeCONA@jtRe@&8gPqoZ<+UQdQlgR-Z zuKgnA$2%Qe)Ir0$a^MCCV`?C*yb0|re z4uYNm&V&6z&ifwk2Q4{XIMS2`%|aSRrgn8IB|%a8E(?CEd&E?qq$1xpj?OA-ly788 zQ#@E5y~7ifBu?M*w_f%SnQ>JiesVUp}N?pZNIF$NqSM9x2 zZM?4q;PteU`M8CuLj(8qPuUC`{wsA-E?^0_(hdQNdcMAtKBttCyC0Cn=dxun+u}cB zk0&J`IC1{;zS<>Nlf{t4{?ZJ*z>85Cjb>pj3^tydpZ@5(oXNP~msP|hba$~V4|n5o z&&#gl^daQ6k>O0uV=MHd&9fL4QJGbB8du^5XDxjVT_LAKEN4;~gZ#XBrw4`pJ zR)BV?$-?jXk+ZKJyGGu0vl22a@x2?Gacsd@Y(!{W%T#$=@{gd$7=1nbT=ez!^EE0U z)BJ)8O42P9U{PY8Li+kRH)<+hFPC3D!Ke=qH*z63{JL!uxh8ZDf*q#U81Jf2{|7md zk=zzl)p##3y#Xk-^N=4pupzpV2USla)*N*6k5nZ%Y8GIWk5%?6&0D`B4+?to!YP z_SHd;U-2(0l_MsBXZOh9*O&7;LptZWB)VX5u+{8!Dvb~K!|Q}jrcY>wM@nBQb7c$I zliw3%OqlxG>y=;|8{#T&VHXO7V=`c};jYB14lC*F98 zb@G1!R4ZUE3s`S4WAS6o`q^CO(m?K`nOLmjlOMm_J_XJbM*2#>D4#7o;ixo_(KxtX zIAi(`GdwZG(_J%qR9+aQq8 zJwHEn80bqn^WXbKCNq;qmfD28j-FH$7lC+c8UktEkI=Q_hYR~kzaKtOJ{!gtH4mI_ z+3Suv5sA?Yn>0HMR`xU>MURs4Jah2u(+_RBvq_XIGXB>a)99{aFt+gnq>q<$OPrW- zsKnTe#eWdXV1$!Ng=BRdS#2~oRisx4xvNK9D>3O?yO(>ot>Or$Bl5DELO8^I612D$ zd2iofE=FYFSB~Bkh+qQWF|q-L`})uG6uH|hjJ72m>Z=8F1FNmO=e3S&zuHFus;Gei z#?xiVZrtzb<%GUQc1KDon`B)Jsgoe{40jOOl$p20UvBr>{oW zzDR9IK09IbFf#p<$blT^FI zC#@JYzE-9iM2p3$Kn3cbc!XGHnOjT!Ml<$g_4L|}I^K?R)}0szTzTd_dfu3)@sue0 zUQ7C#=TmyX^R8t2y-2CTw}XKch%!VQ&6IlcDk-UeV3o%EVD|X@{&=J|rWr{7`s1vg z9F*O+f2N{VJRl}tg3Te@Yu!{fqX#~$HHd|k(-9=K;ZV8n~<&}w>6vP#<9 zL1$UF1y*7mPpL|2e(HHtR0=AUJ!p65@zv{5{IC2Q^nAFmQTu;CCm%LgrF>?VqPh9i z%8T`e*p%`Q&?=cw*a{O_=R7n4HQzCr>eQ;BvAbaksSoXQKL|<&6p9<8k0!10oUy49 znM+pInim7oe<>N&5i(h>x@uQhdFQ8$3Xhu~50m(9SQNmo1sD;9Pop%)0fs2EB5g95 z#;gievH4yTX{8g@QzkX<$v@uImD$QcLlsiB(z84dh;)D)GX;pW{Xp_aQJw&Tm0|sV z?T7Fjxlc?LhDMrBf%*T!q{JtbEp^Snenjy=h;s0P8nyfuA_;pGC)UA}K-|xN!BnB> zGe#&nQBea8XgUuKN1{fLK+5VwVVCL^?s1F4d~QrYf~D4M4*3Rl0~SN4Y@B`sh(p9D zS{2lssf&4-i_iY`LU;A7BnbvHST*}&GD_SAGFJ=;UHaQXSD?WwW2PS?p ziq2?N2*E3D1?MMb8Ek_%thkYpJ~E!96JuuW1cxb+)C{-9GC&@C{O!4sXhSufDoYYS z%(A~gzU8&BeXrK8AjHI?>1!4R#HvR6reR;GA)b-Ng;`QGn#{^g;NZE7udj zM;8FXUsz3uK;rxh=ni1U*8}1oI5JIPvCkWgUbzsN6M5lHt$RW2-LqK=OHz*5!ZNAN zo)4V;O$&<&*yUf=vjwZ~>?+^FqFB%y(+9ApSJX;AIwSD1kT6E(ZL#-{Lgf}Szhdlw?_@_Zy@KKoc4;4e(Gf+?&FBy*X(Ww+cL=g+w*KR>?# zh6x7FENeRC9rK%sm1yLYDYWo{&?o;U$=C?;*gK%Wzc)7{6lRT5zw0RbD7WiuSl>kR^w)SA z^AbZ876-fkVfZ0p&t^ab;UF>gVZheqb5ylcHNGK`{~(DC5w<&8-AYR`pEZK%+mGF# zl~a49U)_lM7|`})73Nka34s8xi7ea3j|OTl5WELgw` zC$5vqKrg6oZk(_)_}+0}Ut3%{kkKdtEiXEM`eaIF$x#k@5l`SCC^8A~Eg%EIimpgJmW+*!xu5J%!=w}Q{NnbGp-L*8C+Fjkk*d+;v>AE) zijeJ_d>9V3IpDKnprFw%6FfxoxhlyW=ClzMM6Su7_*|b1eeSlNDgoVtCSQ-Ic@U@m zs*CM`U5=WDW?zAq>abr=NXiAG?7Z0f_bz=2Pm#FiXb=@md_+8br>XF8YOcn{KOlW0 z=2J8fZp*x0vYK=>@Z8^6%bl}SM^)~Q-v5<`){nO_YrkL-<{r#l&l1hEwjvR16zU<{ zqLrb@(8AiWb|DEVKDpChV%ku+k*MU1AKoLX4wEcyaTK88+3>HDqbU6z)X!0sdk*!2 za|2I%1#RmJCq;=h=lhZaBz!NZAwY`u-`WrOI_Oh2Xa!tS=sEhPql@E{&~})yjkp$&+6srr=D|lS+1+YiwgD_j zDPf4iD=t|w!N%8EydT6``>NNcV}J_hCrJ@w5ah-N>FrYY;XPJrtYDFLA^l}bgF_ju z@{@eA4x-nf=@b1b)yEPJIZ#;QZ0bFOg-4_)~ zQJ3Hg5{7EKFh5Z9oX`#g?F}HfA}BG65kSq-$?8j*lqj&UBKco{oP~4fRcD`3nSe0D zmD`nRB1t}j4AAx=~lJJ5qhU2LXWUoskNL3?ZoC;|+rtOLRbRy4f`tY%Wo zPMR)pk?|G~h=>39D_Y^!f|dxg8a2nZW-f}45#=XhF%DaAWCjz@VYmDFB%7U@cP1V* z-VP99r>JQMqv-0^54{xn$m#X?kztaQr+}->-IQ1D!UjZj>EIPy3rj8{LhyuMjVwLi zj9!puUS--j`v6~UT~H1Z3Z*Btdh7^`!#T&D0|l8XMnikVzIQ$tgjYsu)E?0y@#UYh zlw9#aASvF8aBSeC`-k;=NhFMt#dnDrJXK>S$`e1gO{sM1A$jWGm9{G!OY{tLo z!SToFKNBD<*~WRK#zx{!5?|HF(WcMgfNl2fDu!S{uY|gJ_P|y6VPodRFpo`q>y=pHSUZy%$x7{6I-J zENZ35sQ3$bG1$W~=QOP(LnhrLh!##${DrbAWXgrp#x?m1&x0_m8QCm>_G=mx{lwM2 zjO2&Y&)OGY4XOgXm>Dr`VoTnz^*F5u@*wN0`@N(v2*#-D%*9pSE9LvhSj`sVt_#75 zX);H*8t;eDgk8kdgC0+Zi#n1aCfe2({n3JGX0@P;ZCaA?i(!D-Y`Qw@bLM5*!8~h7 zqRpM_+VpVWX8o|8fn4v`S8U*gv|0UMpS)?m-|6UEE$#U~l6V*V^R<*kog?At5aY}b zFucOSIZxTSk57ikrFep% zFD}QdN+zK;BQ$iv#gsOm-)HfcRG;@;9RZ=3#n-=mVC|G7uPnznj@7_Nbw|k$M}yXj zlG+aoh?^Sfi>n(Xp*_;D;bqWwNX!(WgPV_n`rRXgtY$$oK4pna@&?D&XVgL5ctM=- zG<3M6Aq@WlPfi|@Y6;$$1Ih?R)yrEnS>^;!4d(wX$rK8Q_PrF44`i?zHB;sZIk)A^ zWd*j^vV;S2eLJ98+rZ_IO`@fC3$yYAji+Dyf%_=Sk4L9HEU&Ame1M>a*+4#1KJKUR z_W1w(BhL8Xhv1G`I8v9J|6p6vhaTKliDFc%@}GY7M58jX1IoTwMMU+6^%ua7FVQ>$ z2+0|0ADb_2P6qD*NjekFjH;B!s$c(n(|DMlOb+B&e5rMx&U~2&WOt~S%9(pL7W;*o z_Qmu|loCa)$e4D0`Fn!qO zRXx7a7f8B01h%EKdfxSll#q_euv;-&$(tToi#xSO{XbpL;<1{e{f~5YYl!{!vJU+3 z{oAU^Vp9a;tgnJ}`AraaV5+1aScln8B<88uT|;nz5rC<9&}dbPjVEg|uxHe4t{!FoyRP0fM9EyBl$P2Q*A0+6R2F_HFwP35yR{3O{f zJgW`bAnE8-l^I1ovOl)vRf@=^L3VFMUwAlkr2zfsRW~03fv?6YSocMX2WO!tc{#AP zUmy4iQg2QB!qtTc?4GP5VYw$j`yDvC9qu6a4_}QOsU6kd5B%gy5GJ(Nm1)!uS%V$N zX)td4`LXv1R{C8WLkXnLM3I68>81y&sNMX=2&@|D!@3^ac)CDC+*jfe&*OyP`TpY9 z5_0^kbO!Au3?})}O8-(?_qNvathEY7Wkdl}a9i|3`;V7~alW)q?S1HvZ?1ki)M%tix;NP?i20UrXB~3G%+(|qY$a#JHOtfHddLSF86c)p~ zj%JNWL9}07>HxhBrIjHSk2(3zh=PT-u~^s!ZP8>t>uBUXYN9bt49@gMqVGip#o9x| z!o3VpR?1@Ukzi=-cIPYtlB)(o?2Z9O} zFT7g=!tfArS{NgKIo8Q)Cc+SF;f;aF#{>Ui>Bp_-_}d*DZ92X}@Fn6u7*KD#HM*Yb z1$!_soJ`RY*K^-H18G4eH4&`+x?VSYn7}YI)IjiMow-3!uARt2ZlnV4Hs4d6K~k>d zz)nHIjHTk_f(;)N+G}4fWZc}Wn9Pvp#*+vG@GK$8T8>Jo9sx{L&IEiJh+{_au)B9; z&9^$}UuYoyfS6&ZCcJ-#W6+8?LbpR*NW#uE2GWZ_^ zw6hZ}_2DEmB4hlAoFJQ>1hY~zzCO1~NKW1kTF=i`?QRO0Cbd?NXQo3?72OLDB%ked zFr}tCTOg)4Mk69()uq+DWa8;oG5ry$KJRGFHmKPDJ4^W&S`yQ=L`@9Mw;dh|j#L63 z7mC4Cw?@^r>lROniN_55Q4`j8P_w7el*$0TPK-8VgGhWM3*KckO)aXUr)*1Vtb0ON zr`I2~QD?Wi5ZEM(5VL`{u3Sm%$CJZE{r+!p(1LAv=e;)kXt3Odt`Vt8;!_zX9b?9j z6N#?Rr&ZA1jLert|3RiqAu}H`GD+*Xn3jJZjBO^mwUFT1wvW4Uf2`r$UDfHpXd@3@ zCZl)Tmg>{NS;bcy-fo{fkZGTI6#`9oQ?4Br26Tody}}2n1Pb?;b(d)tB)Cn0dcgUG zLI|N|1Y}<01~Ex-H#Q|KyuKvVOOg@(IwLE2g3BW?-kt-qCLcW=2$;q~KnMWM#(;Q- zf*qG&j+N50%~kF!8#uCJav>?5)$A?b6Cqoq3~BORSP0=RziteA`6{c~h}8Vu3cScv)p zn_N!YPvaF?p-(oOsTe@4&#B*D;#^vUM%#e9Cb+?s8ut2ma_!MD2OOBBKZI0 zzv48}YOO{(MabLb;8d!X)%mc8m7|^yziMN^p8|2KMWc~Tg@v8AE2SoSh$S7mZ%aO) zKF!o3w>ps(y#!me!8U-%B!`7X;ef2Jr?BU$%R$rSLv)4_S07qSh+~5tW44(>5YWQ) z^U3R^==&4coA!_AYZ1#)ulcD_QLzTwftO%+rYU@iU>MK~t;MhG-w9zBoN3Nz2-Cjt;)vjYB2e3`1SMfx;%=?9WHgxQ zt@f;B38#@npEbh@@-&4;8?(^7lWSyP0TrUnKoYD%u2k`4UdU^>~?5a=8&2#i7MxG)RrqM#u z1I+C?hoWa0XAy_!V<+_qxcyy4J58Y|D{U)Fi&9fO)?Bbd3r~c6_yn6Q0n$D7Ju*=h?^UtOmEE*@<}ypXIXKRJU*{ zbICYi>#w>iVf&l1@@KC7jy&t>RZ6fvSpb$`7~hb5RYkA~!tWcDSk8ihGnGXNCtf9} z2&~exnCz$CHmy-B)Zke);~QP%LLTsV+t-jKqdziBFZ@-#_H5R)e9`I)XEcPVxV~)% z2~M4DK!FznvYWVkZ>(m(P>rrHI{lCq2&`7IXBJLg^cU9?^RFzH35MB&P-g^31x4(Fa|)-QO!lH{}QbVcQIY+kED)tQA202f1tXT;Y=lw_VT1Y?>LZ zl~W@H$yJ@BGaA+AGN^b)l@3%at;4nso3CavFSc9*>E$OdGXLLCB=L(|p~whAXWsEo z(+i8UroIt{H(@hM^69e>w^V0CYXEY#e?TMm!hiz$!=y$DsePsVoiYBVru32UqhD*35|LVy-|^w4TdG+O?V z?Er)f9gKXQFj9_Krc23-z?*3bu@DVpy$`PzXs2gndj_08qrX zHIzV#iT6J41=jz+{yyDlykT9Tlp0MXF%3@{WaGpPwbEoK?Gv-1znM^O-X6l!hsNGQ zgxmJw)hCma6MfrB2M`q^--#!GQ~krpWNJ+oeMM@X)0NoDSjmq`Auu2WU@aDDhvL6q z(nQl)89IC6b}56Ap}=G$a@5Qw%m=(Yk35PCqHn_iHb9oPo_iyyD{FmZm#9Y=$^a)3 zXzB|2P|4KDGrxih72W0cDx+Thwi6lFThGRIJE!MpB+hVf`vpJLPwxO|{_VLrYooMj z?lyo_)^>`bdqDC7loC-C$)3Jx-G!PngDDlLfahQVq3uah71~LNL&4!?vaswknvTXu zK#}QtnG)b19s$hX0W!ZkwnBPpfnVfdRsgO|qIsCEs0q|_!uGY3_?UJxo|+V1G=Y2; zHW-{G07Y-0L7{1AvAETtWC)WVwNsq6M&IMIH*LgqIGL*)9RG6Mq&(SrsW1PsyS%Z| zEcP9|+g$#QF*}(%XA$XJAGSR5|7?(b{iP^shJNIkfDqe(d_6JX#AA_zIVL#TEy(IX zO#zT#^EG-1Ir@ii2Kh|CW#kmhu+1rCYYlLrc>}Bz_9ei8gLqlF)zz>-GYc}bnQncR z4?2tOP>5A>=f#woPCbPX;EE8Kuj*X1xttzeR>}*O5fjy8&}+UgkqxFn%e~TzZR*op zrIq|8-3=E1^PAN`{qH)I1%p-|MjVh(U@@u``J@UJBPLci8Brsn8N{Bx*B|Ky)L@Wd zk;^~wX-N-wa6@!d2no>{P#%3uo`d<3kg`)ppaz|G7 z4`I-7pvxv~5XJf-kn88?^Z}uybZ%3aJ;8 zL=3IDMRZHPOgv81=z8s39XUe%a#u9qETY+MIwfKRIoN-;7!k;xC5!+p*zs% zj(LeHbNOFZ;Y`IK^diUR2CjL|UJc$ZGLJpY#vSAsM2)%w;?{-tKEZZJjeI3K_CO-rSaCZWTzW)xpmDKwjT*bnpNWC)cnDL8 z?RFn1FzRxqSFyj!jXXSbND?qV{H%Ic+Yyd{X1fb_i!vUeel|tdCu#K=O(96K7icj;jb=|nHYt={jjC0Kn9SEqF{qK37wx`w)VZ?D~MofbogNq+PG z+ltd>s%{L8MeIdrX!^SNOp`3K6i(O5w%xvUrAA-z*6~J5&e||q&X`F70W`L5JtikH zIDzEd(To^hp@0a(JM)@7N6eaCGGbtftFL?ZzdX&ejQxmdAt!!ONPw7p6`C2#Fc~** z*O%zw&)=zU9}Vi*U}v%~%9(!DBca9W@xZ9bsFF!}jCXuu<0Wv~CAk+ke+!F$^FKp- z@6*!XKG<4_olne1SxvV~5rsQ>;b1D!u{Btv|5!0d?lEWE2-W!Pt6=(p3p-wMXG9$!7trW4s3??3!4)Dj%4 z7__~VPyt;z;&M@wHY>W~HZ( zpfR!?UEp^3g(VmxU}%b`3lIu-N=P@xC}v{TtMq)mBYlwDB0thQjqnEyF#;K|eD#Qq z-lF#2A-G#Zr8q$Mcg7?&eGb4NKTiG!p#}Dp9(K5t$G@C-FD6>Yq4)5yU?(>nL9|F+ zO*P<_^o`4(>U)^j#bl2xy+t4Q_7wl@1MfgAZ~jkj%5$YZ4jZ;;%#py!M&a6l;}y;`W*c zM}hM_TXuX|8f&Ko%exU`_~FKFCP914S6GQJq(^>@F;{Zr(F;Z6gLFoD2Vh-j%%HHc zi*}o~J4%zU#4`3*B*#l2tVFl*-U@LV{d2vr+oxP z(Y9&pL+>n=rFNMW=wGWn?P>o(e(l{|m@btcfg=u0$HdG+FxvyY;|TZHL1KfQ9q4Vo z#5=!V%+BtpF4bwtanw;!25AaQN}EAt?wgPiqto6>`A)V`i*iqwcMb%qZ>)w%Y&_mO z*AO_Vk+|uihnAH+L?+S{mfjs-N^79>tS{RcoQ9QLIP(-+k6+p3B}AS+*HoWWcEO-D zWTR}jX{3;EO5=*e#oNDM7T6SPW7T6>&=0Ra3u}J`aZn zK2b?=~K5WF7w>WEx*?sgM!GVZ_M-9POjDm!~MPgpp{O zzbN?Svh(*;S^}{9|4xql-gqpL&yg$e!XTJmu|PikTH;dKllz`4_e(y5(%@9uu68%k zV#j%^FDH_5^(`8#rKG0Ros;Bb^_zy2G}aV@%KrIlvbF8V=i=O)G0Rr=v#9HEg@kP- z1AM(rMP_o`)CMYW%DN3RN!F_8u=z)W0n5-vfsf! z@1DhdxO#fj1KDX=UX>w4nkm1WJtb114J5Fxg2adA-fgZ1P?IY|Z%!Q6Z1r2fLh{3hBPtB&(Bur<6A9 zycgp&sj?ICE>*eTRc#zYWDzV(Y4x~MQ_aE9G|FKF9}QYtW|F~rspI;2zGf!QoW9c> z@=h+;A)-`gRR}xQ(^Rca7XF^}&-2l1zvbg!XPogn{nb@ORz<#Q_^T8Be1xc}Z%uNU zNXixBrwHtjYw9bX_xCJ#I#J{Y>+cfO9J!sT)Ps|y)&Rom;^_C`P@>YgFFIScwA83VEHYyMzXO4<^=o_q8YVHT^-^3O0ENr^v(gy5wXUCPYs%MuZSEC913^-`;?RF`9tyT z!Bjl7Jl}HMA<~1_CWAJLE>hBN4UKi`Q#3=5(#z%ds*;P_A2utCn!CLWC_^u1-mu;Y z$_p;v8C~cxo;B2Q;&%LcRiVb|&meKJ7Fk+vB@_B6{HfT~+jq>A9w{N2iw8_EHTH9E za_0ToD)Ig+bi2@=fY9mn^|o8CqiG0}`dHxK5CF@?9&ID&6X6~!CbR$%W`DHqg@K9V z>d~%A{t(12r0wF0wJa+tR=mmoAi5{3__r2)rpFSC;G2N;M>=L91>RR`o)sDu{-cc| zFYo;&FgX-~NISWGGTNfS;LNAr8dhZvl+4dN5dQDBaV7orZ`|J> z%x~GXSm{!cjp>ATtZ13$(SQ%C!J-oCAxJc=5Q%=99e&?;P#oZn6u8Xc%F2n#@k@WT zYHpo75KQ%fb7!?9G|WC={wBV9CDkGOuu&Mfx@TDYZ^zA-k{3D=l_r7t&!h2gBf_K(~oxjqJpO3HISw{Jl<$>pvMwQ>#WA)hO%HQ~!N!`eBU zS5KL@5#jgO^IorCNzQ@7q9yVTi)r^qNvVU8lda-|8{C2m>Y-7uO!~A#y2Swl%_cj_ z7q;@3m#;|}3C)G)Ll>^!wE3r{tN^Z*Pt0>TV9|K}i{KV9w5A&7SH!V2GmX7?;S@uf(DtQbOKk z_x09@yLLb4aU7{))01!FZD(OskXt!P9D=O6Gi-Wt2VdnD`{mlFY$Gp$n8BJGBZ#M2 z!7`rYvKI}@6d1Q?ez5)K3PnayjE`h(Rh5Q3J&ZrFb@~Xah>iwGzu5~nUBbca|IP}i^d9JGT16{45=@&{(cW81$w4qjiZEQ>d{2kIW!kcWPl3+S=!u-&^cjNw20bMnVyjpg*9uO(N z81VxEF-jN7`pU|^_N3r$krL{WXhn)v4lIeVZD)SOQ^rMeoR6JZ2Hxs2>)$6Izt{XO zk5h`h*(0$2@0f>}%%VoQ!7eZgC)~R2^t88&l!JhT8mwS@q`!M7o4T_f`D z{dr+*n6CBoR2mePkem7Lmes=asdf{GSPv8p3^N!%vaUE@^Yr`ZAh7^AP?1xf3DUiX znVT49Z~v0!&gI{aOY~H}K4Q(-lR>87X72t!^)uDWq=-44^ClX%bpO3+SJHplA1l9x zJ9o%twSQg{b&T?=EhsPN@b^X#pS&sHbe*gI=Y9K|>X~cFG4v_!ujf-)Q%e6aeAl`~ zm`cwQlki1*8+QVDBy*mv783@?Ia;SC@b^hUQNpaS!UKaJ`@~Om@1`l^Z*R2{ z4-=Z_MiMRR6AZMs5>9mV^4H~vJrEO%2oH1UkO*E1ant^m8tE{JhksW$^6`2J?;*YkfoHs?D!e*J(KhF<7k{XaVJQUaJCxZ*4HybZOyT5_ zzjDV=r)0Yhm@J5Na;i(z|5EX&%yV@@zc|SV+(pg zdycG%8<$PQf8c3cb|?ML;+c9m$4~p~tF;ap;79s{xusnNr%q8coG!O+71Qpyyw7a- zW-K)G&zFbdXA|8`ExGLNA7g}I>x4Qp1K9O~-?O^gM2ns$PadJWNQ3JF;eC>0-baz| zbPKy?&b@yDiD_0O9~hGDq|v9`@DHV*-5kB=FJMz@NP!${)b6|f^jZh{meUw7HsXI2 zor@!r`ya=j8HO}<(rG(3Q=Hr?MzLW=7v#vjbdiWsom__8FB{28Ya^6uX5})vNhw6R z#ZV!u$X&xM=9b$Szu&h%z~lsL=RpZuXyJ5iZfV z)0sLA%xahgWg_<}ercXb2N~lnbw}Yz0}px#y-P=;5EuG|bb7Qq2AS!{+Lw1^hCRnKhYqSOJU^Z@jtbD zvF6@LU1+lM0|056`Km4|DUPV;=)Se;Z%qT1yKya3wyc`0NYO*HU8&y6T<-2V49;FG!oM=jQ_q(b!dS;Ov$Tuy=c{#nqF$s29w zw2vO??+z2dLB#Dg)+)s=awHLiRxPs5x9aN%{QelOO#M!4X4`_p4-FW6fu7e#9%UB7b!!(VhlUup=!^%Ql= z107JU^6MypW>V68{{FoOheKc1Ak_P7?4`e!2iRx+E5TMO>iIELFu2h(QJ+jqX`gK- z!L)(!Kc2WT=~n{K23BC zVFu5xtV7ieF$+SECb#|f()Qzit=Mxka?ENT3WOp(dw&8xq%I#l^aq7s;8)AA=$?VK z_X7>2XyI{({S(_m0}uf{gj|3wJeyJ6W&d~!sC4<9lD*5<;B`3_{$A10z!`q$+x>Dj z&BuBxA+*=wX z9?DN7qkmc(p)TFNxx6cPIKwlgekc6>OxfE%(ZDn`kbm|~dot9!{6EMYXL53WCt@wE zM`bj%=gr%$bVIVkmE8|#Q$9lBO$c8;2;MkK!kle2Qw%ZX=Ek;W@3{(L8`k-|Cb(oL8b~5YPU5?GZn!ZV}!0pJ%xN0 z#t|YHhQek475AsKCW2*_;`%t4bR~-_WE0rBHr4=bKMA7)afpV9oy2|4Wg`hYGj)EF z*W7cA?3$th5~zZNh=1jJPNEVUdJHV@MARdG+^4Jl<)c>UD9uF6ap|R_O$h9&+nJ2z zEv~k|C)t^>_CP%gy7#QZ*d2|T3o?D)0XS}FZa0YYNz}Yn2Z9H@*~GOA08cEX^gI%1 z!a-zC{8s%M%gjEN39F4fpIoO)PM2M0MG|Kt1crGDx(Vtgd+JD9^w}rs)xOfjNAIH- zISNdSTf%oR&defE$ys}+EM(*XiO5-2pT-I;PfgIqaaBK-1S+EUt|J0-bYLl(Qj!j$ zoI9c$WpQOaY%*d86;_vr`kA2T!kCZHW^{ApnT2wD=}0+q>>>5M%0|c-QE0xvVf?rQ zUBMFaPyo*&6S}^4z-&EiI@Xm6@g}S`2P+DQV-Eunnimm;QTx0f4XNW9DTR6fGsqv; zfmPPQ%a`2@W8&kAhdng4rMjH(MbJ$j99};&d_kYz2_@f^PlRpp}EUlTYA^;501oc9YNiPFX1mzZ4%4Y`43dCMn)mDo9k zx^|cy%(U5Q9*_oX-*7GH&4ZX=veM}Xra`S@FiD~uZb9)pnRjURC?VBEFbeM-pl)1t z4dq>)QG8%0+S#8XS&h?a5Rl@Gj59?4G+BCA&rpD9Zk3~Qzc311RS2NK)0z}_4ipWg|XMiXcx!;2QXI!DoO0a*0ITKt`pmnj5Do{34>U{m*Bm^NG36JeQ-B5<_ zQdq4JOq_cCx`84xpV^C(wlc3QI?|`xFQE=T z{<|>RcWYAo4_N|XZSf`xW;#rD9Fcfef z=AKlR^f&p`;T*HqkFvTP9<@C)#cQiqtS7#>g8Z+(X|z!|_1qEPwe_P@*yC&Hky*Ch z&9;Zt0S)1O@-V5sQp|cJX_haYJ>KfS|M0fJJ@gdqWou0=^kl;gx<93U545D+`MB?l zE>Bjz?ReM<yC<|e#{KUPy4y3A<7@>d?roNK|3X-^ zS$zE5@Jj}9dfB%#GjS6vYl!8~z2s$F`n(dP=m9hbOeVH5BreoNsI`#cet=yG)dlmYP)5Q&wC0;dlkA8;Fjo~7JELOn(PML%=cov{ z_Vy6ENi%hdOLN?r;D_Z@8`jW5O7|uT*l4? z1mudHjiIV*YK6lh=7EW0NI1p>05IQO!WPNPhqAn{png!{$)RX3Jm_GY8rK=gjFd>C zW7v3!%SZo`(spMv%9_r08#F-~KrXESR%C%AOYE%`5Nb&^1%~22;KH39itEYnKhodq zYzv<&eBFuJ6z}B@D#QEkFO<`(p2dx$ed*rp4G{t^_NMtL3aeVEs9K?Rz!%P0sO2cU z3$&{{CkVPkj=EVq_Y7aQ(lK}i{m$7MgUq!z!7e+>e+_bLgf{T?R9Y)nV%&mFmCJ!t z$1WUWqxN_X5v-%lX%)jQ!g$IzPD>om%|O z-_TjWtE7wnm6SDI3-lV4x;FPM9TB)SUr|qXZ!pXo-;2nNj<+!>+~jY`B@17fh9s3? zwlFBnInrapzY0PtZgNVFfo9CRiy@;nHo*!wVa0s$QFj#=y1{;mnC=TQw(|OKJxx;_ z&tGbScvf-Xh^4>{HHxCY5}aByqTsu%N0F5W5o$FcatjAh)ZE;LnrSE?&V0yb4%uG1RHu(R#JxTCpy0>PCQB}yc!f61pRkYIH@Frb%t{Somq z?;-tcb{o>s2omsT3UI~&>%07EU8*-aUjIf}RjAno+6=yBhpr#mZmwD}6i%w+hR%iZ zgUNh}n~mknIAO!Y#69TWE!5^JNT5NXC*0f*xwK=#v6s#_WNA_5Z84Ny9QDUN=d2IG z#Kqt0pi2O?vNk=PkTQA%vnMVJH59O(xo2Rl3xU1(&sOckIsz1~&Yp+i&c37K9DZc@ z{;8!a)ipxVrH^>jhV<0)-*iwJeAx$0wn3n^5g2#$@cQXubKv0_d`kSn5@_7Yv*aY4 zyee+kQH++ep2(@5=g8?1fF*z*vR_a!9^*Qt9GbyGB5(zJ6j!;u+H||B^p`7tZ*~xWhun7JYaMIUTL%_rw{4$YNygngM}}Ztn9|yA34!7>6)IY z4D~)YGz9J!=xQi~GOqi?=&Ei@t$9MjD+}G)z#LmIJqv7J2PRA;24BT{ZCfj@=`o_}z{8+)qihdx2}1=4LVZJJXqBf~y7HIT<4W7OY7780 z;_l!Kc2CdUgAQ#cwm{0UZ*|&WhsNK5Pyuc?@@s^!zi9~cHeTi+ygOJNW?{uTOx!E0K5Qt33l6$?8I}+5+tj`|Ku{m`? zfS#A?wtjr%th=#^0;pxqupv|U+)`fgQ7<89{Gy}XPsQr_{JSI{ctE0f$+L(kgul{|r5b|}qyy`R z^w-u(nuzMzfP-pOE&aeRo|rHAJ3DtO&DQ4=k*0lNWKrx;Yb3`z&@usJrv#4dxM>o9 z9xw#Bn`~4ulw0yd)Q=1Xl7Ouk3C~A0FK8oH^BLJZp!-2~S0|oYiqsDJJyE##xRk;} zq1uHjN>Obcj>n^Y%P%pfOlmp)r3=_`7~(@Z?m%z{d7{s;L9Yp_OOGx1n`5WW&(EOIrmMvM{W;U#nVr>p6+RNE!nQeJdKEBbY8 z5lTQZiaAT&-c#9Ji%9ydo^8|(tvhR6pUdrJsd5Nj-30NG-DOi+^R*bTDyO%7?q$sY zzwA}P?hfU@oQ-P2X4$Ou935}#9uJDQ8IrK@TgTYlX7WEM>_>)djGvg-)yc9`sSc&n zGkB6lT}`zvDiQk|*!#l5VROQNp*%9PfTW}$>n&i%i)0>XKK5pXnER6XJ@>xX?TUgh zYvyOE>RLy*K}537Pq~A3Ao{2&8kw8yU}{Vg@ew7XF6QZIhY+q_L(w7!fvqmF5R70g z-_3XOiXjS+1nu?z(E2~0s{=~vJK)v;!C2EJSqnC|wl zvvAPnTOkylHPAFOYX#v%Uw-c#JT*f0S{|K5cUb~F=z%JfyT?e0#!$1^bcys(utj z@Z-woY(CTYGx?YIIB9Zf$5mcIriF-^5^q8y(dt;MfyI?6l^{o5-iRwv&uV8H)hyf# z51t_o%w2eap!S-{b=g0SNwh*#v`bV+l~k-0c;u63)3%Yl-Z~9iDRy8hv?W{YBVdf+ zZ3L0MVH9Ofpp9`R!a`Jz4D#nVvZOEGL##iSFoJT&%ps?bAFY}QVxH6gAea1pR?eUS z?C_Ko2&;?@7au^zY$dGbbyBxhXe3RBws)qf4^&Ev`}|D`dS?dpQ(1#n_dWgW?iBP)w^D&{@sgo=_xVryY~ zdbyOLQ@fk)4U}{k6UR;`$q!mmQw)$_uefv(q==way0o%g&C%9j)fu9W2<6sD+n&!C z{M>dC^20qdcdP74N=9u2P@}thVYSd)yiX&9l}KhY_){Qeg7UJ&asA8Za&&V$f5nv* zqIAm)sP;2uEjB(v;OsYSX)r+7t~j3xZlILOX?8GDL`R68>J>v^4RxKU3WqfjKJBp~ z7hVjpu|EIkX$B`3djhn@|U&Xd|*EPw-`e8v?d38=M4MK<2udhKgJ}p%)t7F>ID~7cBO46!UqKer+nJ#>erGz} zKfQ`pOOo5OZM%o21=Ct=Bberc1TAR9QVlczKZx21P|9r3KBcN3{$06y7Gc!Qn7>i< zy6rRTa6a~uV}+o!N9(dB6r|D-SrNeKlz2Rw-8QIhBmnLQD+v~-?2 z3)glJHo<58qWeX6t_@bDi>IZlffPpky(3IZ=srwps!q2Xm^>`wHNaVt!cp z5~Wk}%BI6?3u_hU6qxyxn!Dp!w0{wzdo_$BCxGt>#xoOsO<0Y~TfF3t>sIJf?Erw{ z)gGYo0nL_9Dw0w+c86_f#Y44!)D0cnkR+M4nwLbP5$}4S3&hqWcEh0RuZ%WFl_9dy zes_aImPv(_Zs%>&VJK~;C>3&cM@EM=qDj%wp;oopWQUlQ&xzK0p(5IfGprp~kMbok zYo6~7xogv0D^2O*_hgI$=Mg4C@Y;M$*Lp)Us{JWs&G5YI5gcae&`QQX$hrP67U zqyxTXY&eu3feqG?oH&J+v}j^W`Kg|Xb(!8Q;cS6&<=@vnH}xUGy0u5#I=6*2WB@J& zPOTOc#>rudTv0012Hr98nE`~BX3ZL>20+ji1YO2?C8<7bQyB3@lk8Nl&Yi*nsn3K< z2Q`>5BzOxE|7-E(?L}JpbPOq(Wa+64Of<^Uftw%$yd8*NiO{%$c;H@C^I4!W+p9d1 zDBnRgsAox<9aJu-LN=>+p+EuJV%>dgqNuihIfA z2IdYoo_9ZNZ|rTb$^{uttEtZxL9Fnrec=bIV#0aF>+H;_pVj^)?~OD6=mt~g?t9tT71lAgYq5|h7-R? z{p(*EsGf=s%4?)|S$K!w{x_*m*csg>`BNbMUFu;NyEvgYMUd5(u^m2f*+ol(#;*{h zmi&vj9os!SMkWzfJa)%@{%qHB>$`8)-@0uJq&2zdZi^ zsVD3(g1LPOES>l#His8@PSI_r6C*ngo+;H#3vEO2zm-MACZW|37FQ4jG5^ilJGSND za-%CpFX9Rgp3Ca}L*I->PsaE&%-LV_%<@Y&y_Y}D)qz<=hflj>bFlFdXn{7QVr3hc zRh%uG`R8?aKdSY-RE1mMc1NjRr{TONYXSR`CYBs~X!iPZ88m*1KgEd8;}@K7gxgOZ z{d)BNV}p|C1e~?iHW?e4tKC)B%EX`&-0%s-o4ngW**^{uy==AMeWAUe<8{j>y~%#+ zkQX{q81Z0XN?$izaYHFwJ1ze7Q}H~A@51r4RPJso0$Lr}U&~>S=42W`bE$5vFI;-) zYUyx=OY3%CSS$ovFXtkp62Eg_V0}PVjWE z>^ZU}g>mtx<|@(aQ+cI!H)xl9o5Q?MNHjX^7;HRo%Q)4eE<{LAPkigaFe3dta#fl} zJsm&h1QKnIKCkpQlHqJw3T62+gF2~t{(3iVscvdjs8fqv@tx!Djk(*l#$8UGA&w&o zPOi$1%xp>?iU!5l_$nqfHsi~%6KC3L>krt8>uV$afuUbxAX0+;ojd42w6!*)DQEHG zLqVY80&i~psNtPwMw>PvFuz*b%T-~B&F}w);)Z(T03qJuo9>v=qjK{~DB3%0<;#8N z;-d|J*meNJrqV6t?Z38}TemcA3!(8Xb6yai)PDYwZ?ZUBr|xibE>>915wrDoUVQfz z<(+@aBbY>Jf-U}dX7S6*QQ^O7mx|=3U;+y9%D*pu%vRp;33Uq96Q9)k>Vj++K6^*A zh9>S#(1vA|`j;Jv6%#L6^Oir#_Kbz667FO-qa0+SDeVQ$(8B9NXPSl<5J)puE1ltbIo4}>+v48KwT_vqyx9yUMihv5zXXAM-Y`!MpG@#LjVX`mbHC9%QvD`rC%V$AJ_nf@y=$+Wb3+G@j#hYef1x? zdk)gGdWyKjCKc|b`mPUZx@gL)|Ezyn{nXDtydJ7S`e%G`Gw;@>%f9oA&q|KDECyDppY>%rc&H8SY`eKZ7k(>2c}D-; z*Ni`l%n*Ls48hj93gDbKT*Z~D!_QelpR?sI473gAUOAl~e??TIq?XXQakC@2>y2;e z$IJgVTW`k+L=WEy@V>}OOME#-o5Z(2?C3QAAs-JG+@XTI<1 z@Iv)2+N~BbWd*BMheF#Qycv%?_xMGN4t%4~6s&7vkypXY-$}7&XO?*bF}bz74E_hb z^tgS}zpaX=bY8I5@$uizb$Q|XHkFi`!R!TI|MlzA*^}+Qn%`;yUfIlC&Pe}djo~oQ zyD&ddOWyzEqmkw7)~Z{#@~2?7q|cz&fAg}v1)Uen@FP#wZ~agDA2~T*^WcM^Kzv(^ z5(k`GGuFsi;oc_3jcXZBR_#))X#b^+ohDAFIe)G4>#y!K_j?=@qUuo>ZSMO%e4|u% zJ9^3c-)R+PnSiGw*iM6wax$eKO%Dy55ED{dK}mawbZpPBNQ$?sd~{S`ocUkN4QCYI z>3@Boxq0o)kgmlh7_VdK?7OxZ)w51LoFkvN9gI>Vb+vBb1qxyd zW$_HEHBW&*4ZDXny4Z^(M-CeP4+^jJyKVhP1%!9G*;fiYB2T|xcP(nU+H}BMTRpMr z;#Aa2bJbm_C|{fxYyQ*ea)w=AgRak4fao*eJXy1}`S;4-enC?Vv+$?A`*!G}Khv7F z6&fbgS1Bv}2tN^g)o;YtB8gG67F7RQ{P1?v18sP5J9;R>;uo8e+Ip)Y>hLD!o$`Kd zW@kC4@Ai0JA|$){i!ZaY&?aryA?|SjcMPqk-j>7$a5`0g~=TC|6L_;5+!UugMu!#B9|7L?;TaQ`!=yM%X8BqJ54W~KWM z@||bO+QtqdWD~+n9dZM+jwbzC7cht?=N9TY8Rk3C6*qo8B!8~z;?N0$op-~*3IWDzzxmHOrhwC+^yLui;#5I(06;I4BQR>;s&xalz+PiuGjM+PAg2jsVr7v#16Z`0i7M$BU!0UXX z_%zGq3;ema812Jw{M_L?(fPEswEx#!R#0`GgffZ0r)Xm^mHl4JI@$a%COGnckY!f) zg+08wZqCFzN#^cc-G z#XTq9KCJlrMEoIHA-iGbiR$Mm^??XabnMeq^U%{zzukN3Xz{UWTbg;O_*mzKAK^zh zo0COr!#wq@PRcKJ5AKJz1*Mhew!4d!iEe|4R~Jt0>^-j;G*wF?^e#Ly>wjMMmHr)- zj%PZ6MD>Eh*!KzkSLz9RbydYu!dTLQ8{g6!zc^O^IkG}=xaCC9#J9{XPECLr;>o|N zWz7Evy=XQ~%a&CJyxXS-cPI8lC1st%?TI9a=2yOI$%k&tKBjgb`vy0sTeK=~j`Jcc z7Vq)7r%!z$cTCwtJRTiZ_$1ZI_a*2nbQURY(jQ(HrjY^GxYVFaEk%<6rw5z4?zDnY z#5~7~ifW2JNvzrS5gqs?9nI`1Pu>oyvng62D_Hr84^p{TtRSK)%p)=+sb5}rq;Fo7 zexN5-c%vv?<*)p*w$tj43AqTIll?~}(?4I>UfI?A0e-VmR1UII-fpdcjUfLq{aEz| z{>kR~uJ-MrWwL4>l>)+u>m8F>8(%E%E42j_mhBA4SUvp3Y`fEg#mE1-qQ3=HL7pZ6 zqXZ(My{=mCa;xlbR<^DO`hof)`-TunOl*PLyD7UiBQmVL^CcX3mF}o}cO&{WWcFYv)rD;9)rxB&QNk}Oj$iLz2}|2Qy{Ye6#Zg>L zy47Fd`pT~2utn_Z6(06q&y#sCx2YXZlULDS4wL?SBUSqG-PvpMMusZGgQ8RAOFs@D zOf#MGyK&hU)fXw|x%DLB_v!C2qJP}R{XkU!Y)vxf2~FvgYSyW6`yo7z9i5QuROIOQ zn&!H{!V0cVhKTK=)JDAJ_dvC=v$>IiqQ$LuA6#0IOC9>iu;7j>_HAJftKXeyH0o1) zV4%HAD!j?NFo~e_rk2RG*^FWcI$Vt_K$Z9+ZS%h`gFdGC)V3)|i)40}$Y`aE zU8q~%s-AhTgVOQ8FOMy!ElpRmw}S*d|L)gucsHF}{u}h+s!{RxZ3!p=rt@z8O)dOu z%ggFC21&QnSPwjVmfu!3AppQnPg+nZqS5^pT2?3$kHUX(_+!&q^eL~qqORB0C3|MJZ`8Ftef{bMep;_} zn^T~TdBVcmP>(Q^MnhAywM0!5)hz5AtMIRU;&?bEbNB@(S)=3_oNEoZ6na~BS7t$%;nB87N2*f~H~o{m7bY0cIp&|xI76XQL|%$d>~|WyfVXVU;0?$|hl$$X z#w?{O;NrG^NSb2}m2_ND|2k}`;at9jW3?^z(tR6*1GDq3=Vswq#<{*d-<%y)EJu)* ziB+GBWOiqb;&wJpi`pHt1qHzema_37im-}Wt?*|{2enTA=^CYEyA(;lM0W+8W?VXj zN%-&G+!Rk4Md3}fk@Rkf4e#_hSvA0WrKz2>yP}-m=d^-;BkcI+(16>{`8u#FHako8 zefYftrnm1qTKQ)2HneN4{W~$3h>8;D`S5be$JN+mJ;??ey^coOt(z4(>l&fd1of{A zyt*Aex4sCoD!)(nN@OBS$bT|ETJn0)A1o*R(c0ylBK)s%Cl_f2_izPW8++6C7ZNiv zJ5DH3o!;7uYOdXfmZWI-g0Mp406<<|`7&q1I_RG3&+>PdW$G`8c8j@|zyWF&w= zS0G_Y`c~J`%s@T&CLzt%B0Nu@O*ma04?4mZ(9MO8CD6&c(VPgN(eI%g*qvc9*qLJQ9JMk;Qqg2?e%mM7#Rku3bMa zvf9i(j7!13)g7X*f@z#MHR!<4g!Yq1iM1j&FvM9Yv_@H+i{b%+$;o>k+BKz%T%S`Z zQ-*lEk!@B%FK=E3(~aYkJb>}q zV$wK39CD9xMJ6RmjF!g^d{}(&bvm}@!Oh?V75f$QNibb4TORx3^{=_#b&GmbemkSP z8B%e(C)xHx`@j5I%#ITsyKaO{+6yiU5-Y?llL(*FsK|dq+4=LO?U4x~iuSku3FwO+ zwM9uEAI?5F(ozSMDQ$@I*ZSF?&-X)KPsc*r3}K5;C4Z;dzNc4Zu7rUAiN~dRsvqQs z(}=b8(#k~?oXIJ1S|&a^92E6L`);ZKf3{c8nqJ0WKpuN__)+?{9;=_WUVtHVnp@9J zi%cBb5Z5;M(E1OJ7Nf)I{O)hA%r~AV#ODO3Sba5jzS1nPPt1`6Sx^6boX5P=9vIHD zW!DG`oXCm$n*Hbcnx@qJ|L_hbpfxqzz~S%XN1O4jASbAF!xUkJ)>C=&Lrw4P*`k}< zE4*_SC-uyc(c;CDy|a@K7ymZdY~mOEOlhtXj+r4F%#{4YtULJvl{AS>vRSouky^|_ zSUl~-o061sFH`l;>yH`R)lxAa%|^J)Pa2K*Q>Zwz{_XUZqyKzgpBiPdd*2B7siJon zpLmU*_9aUO8yjZ78P!pFuXbNQ&))rc)AgNdfhNTkdq^(_9xR8{)zY{RN1^>2(bwBl;|FQUYYY^dMT(oz3ZpX0%wRkIqAy%;5g}$ilYln{Qw4*gI zjVB=cj^Z-aslS-Kw^7;@wQIF{#=V2soBAcK--R6u1W=7;=9yPfBr$G|3g;Kq8xZ9M z=VehshQfTIvJlNp&rh9#N!vU z{)Pyfr`f}Y%*&q|D$jE};I;!0Am%)J`puA>>zL(7wH;nLN_;KWJC%D0YEyezHt&+# zR^SOMe|0dg7_jD#S_JSqsWO%)gD$&g3sgTk%VnPH9glWX)Cxe*=U_$eYsgu(%_6ZK zZ2KKVMhkB*baReBRwjc{2IZK!@VUc|jjFKCwd-f>pY8-|u1hUVDsK;Zyn>De z+7>UYxT$#QUGxYd>A`s@j>0lPlx z*4LQD9C-m88&_-?9kIj>FD{1*vd(7e?An&g^<0Z_4NY!kA%T*Qx3rBNxtg0@+*gq0Q4rc*K#VdImc;3o@03l_jmfjx;HN@TFpc zTCfarblL578gdxazIxE1qgVhcbDazMG?DwDaELR(a{~?o7H%t9PK6FhEXOhP`AyL@rag(-1%E}fq@?o;F33KTx6&-16T4~X zR1h@;N-=-YHT_2gJD%C1h}fEw;X6iV4#N7G1s4udVQF^bp%Xn1=zc)+`?WYw(UVpu zN-ev7Io72qCHOR#N@@)J?x*9@%79J9z010NLwbN9I`wC(JcL>K_FwI|_*_p_=9ZVE zh^_qZ@9Y6&TLTb}#&&o4w>q6^eYGR!AzZmH{^*PITbTHPQ=Xa3rM%peiPOgvOiWB> zlkN%B=V_}gGK_9in|XBjlMSCv?_XP3fu+9E|DzcD_xht#AtTSsRz0@G6iHq{AQbEV zosQLGN80k|?w-xga$92hh(Plu{QR*r>U-sNtnrCAcT8^T|218NQtYwv;v#-M(a$;f ze7hn%Cr|U&`qA7gJ44>8u7m-9ttXR882YsUbO??>>LAR5EuUOM)(HF$uvuo9zm-WGZ{>aqfwk>{O%JapW!`KR%Ew7V?pR%3+! zlz{1|D``lgmCZ7U?FD;r)wSy6wKD~f;Txd1#e|S3b|3Au;yyDo0M`DWs*vH}K4s>C z`Fs-7`3SV{-7yWnu*D7YMavuJMyQ8JLP)y3O43T%rFM&OX>kK0_?U<;1cVqrX&qBG z&N8?4Zk00nIikPG{7d)W|9Kj&#Px-XT>?*YFX5X<5)8PV_m9EuXK$=dj7|i||5;Rz z8V8(+D~ipG9{XLZp9$ql_@?Dnc5*h60ywiiZKHYxh)XqN-J92G&1PCrqp#(!tQu^04G;M8eZOAr!WI5-%uJ+><8ue#8lz z7xb!Ub7XhP%=b5Y+gdYpD+L<#@b;6=#LHU%kF1M7kmaaARL}dVBcsuh-ewaL15887 z8j^QsL#)tR6p2#sv7YyvBGlh~vOnAuTHCA-9Ax1f`Kh6_NcgBA)n_Eo;ufAEDIl%R z0`lL7j-e|efIZuwF`Ou)0KhmGx>aRVky4pK`>0*+AgO6^FTY%^?swc1+?qp8gH7Me zkNC9L+hocEJsQ0p=Fjya9Wte&YpUqLTyeDLanjuC{LU(=COE*d*CMDTk-?kX}>V_CRXhX;zMtVBe^~ezkzQtRR``=jJvu~ zu+dv4uJhhemHi<`p>#2>Gb1C{DtsnJ>6okPY_e?Fc$5f4cf&qp2@_Skj3|;H50!aD zLW`(Z9U!0W?aQ5!s*u?hcK3YI+_pgDrNhGVcL;dFdB{qe({2qQH=z`|fMMo4hTVui z&V^A&HZ$Hy-8~WJj+6e=VI0Jq>d+M|ez08R7&PTu14oN^_CD!H(}pnVxj~L3ot|1K z3Ql9Bs6v&pBgz4!D%c>#cP=009!P+9F{0HY3w;wlpfPZ9Zfi#3(M1+Dv@b>piZ;gw zdnhy@aD_k|M`Jn-^V}Nu4yUr%^7dfT^00RddgM5{uEmUo$_7oR6*RWYCDq}q2hv^| zN?zDvKpQhpRtLK&thSlBcP78(S2%$O@EJ;waTQ0C(QjSITdIj@e*k3k7t&vrg~17H zDtkA6taARv61+xS?ttgK_nygTg^CvnR)=yk)!!#1AJ{Hg@+XKz%dXeF@hqL6Ak1Aw z%dWX7$}_QBKy$c^ZQxiGpBb^WcT0O~>BE=GX?ty@@Q7dxu#@_igy@blXoaVD#IwJg zLyZR4UDvD>6zmIrzujU;%8BLjHNW5j6SGeR{`hm>*$PRNuw+OF)|(dCo1UIAKaV?k z5nW%Z7sIBTyJ}7y>tS;2w@xCqC=&+(0g`UXTHro<#(4t~O26YJn;_n);Z)&(oNOtL6 z=|E0mf*qX%j>E){+2q2Dp(1W(+)4C0d?NF{Pdf2$5N(rdQhUxSn?*-A|iZdMf<7ro+2Z|8)7CP@#H{Z~?t_h<3M$v!3*D8-##e(d zo_+f(U4ujOWCrM!>8aOte?cO;=P!^jg%~Hf=m&EtF z+RQt$pr|_7BE;?Ko9#+9^`7>G0c{LZaHP);PE@4d(a>FotqFUOC&5J)WeeS~n zs4ot0pSts@p0ow2nd zEP(UM>Gzr5NQlscx4H}k%OiXSMPl2J5nEa`s0mknODr>ysSV0Th#$Y(L7yx90=3Eq z1civ8^;gg+rQ;8%9lT*rt=r@WWLTjquA@o*@XSG8ISL5uOp13;hHNXcK*q$YQpJ!j zBFJ1tYjM4dbF*fTiYzMvB*#wJy$^1zaK-Z^pdVurKMwgN4h+;6XyNWW6SPbj1JvDq z*cDQF29K-3&!G*|u!a?NC}3`wR1TBAw6!QAd#*;i`f881_cseWGq1RlmdPmv5Mgfh zg`(yw!~h37 z#(_cHOcP;_vEw>$)tfAfn)%WgELV>4g$TNY*SUW*E5ypu#|~L9W6`@(l#&>I53s`mGE^#VC$@W8`>eZM;v-xSh>SWmNq)CLY z%S~$VBhsC3cQ(-dO9Gcwp~=aix$bcSPAEFU!@Lf*bmX}LKcXn{@C1-*LGJ0Vhtb!2E^m7cQE$$+0 zaoqTDsgs`ZM0w8=quf_$0ihXCccsBFAUllHjrWdFPonWOSm9C~ z!g(#zVLn1NU*;;~iA@yG2_$P&wB8CGBo*y4avV|+2AZWF`^gL3pj<4~b%I$p@#&1W za**jRf)~_&`RtvWt%qx|3GKk)!-`k+Rr9dGy@_YVXF}{r;<{+U34;-E&xnqo5j2qe zks92jBrMqg@S)J(wzv}2r1ZAPpCr6hn>>LhbEk3&VC|8-gj!e+y;Sl7Io18+K0Al0 zwOQPgDP$qD;hMiKon~}@HhzA>s!axy#I{{_V<51I0{~!~zrKT1D&qZq;cQ(8o$Q%e zO)8&yEf$M==>m)|Xehc&j%>;3PDFx6>*geOMV$cgTy-{yPiKF*8uxWqOh$SWsnk(J zIdIt40odz-g|>phL4obu^UDld3q~e@*|!31xyX^I zU#=94&-!_2J0fJ3(G7ywm7G;K^+Oh>m!ONdScBO;ZDi|vNJUw1x!U;=U?H_?Ep`;( z43y%2%`X(dwYEqP(w3v6!3N}#(->WT)`(~^6yuWEHnqq`nBj zx2(#6Z6w${N|QTe4sLiLHVQ2e9q!g4RX}0?gEl*%T8mJ!TM~a$RyUR-dRbSR2&z!< zekm7ry}dIT-DK;b!)}e5? zRHrwq=lHy8mGe+`osiaXmbxk9`Ihn!!MbdMlG&!3l)Z1QdN}Ief0I6&m7FZ!<$(4_ zpN@bI=M94jP?jp6U~Sc82wLL(^IWJg-eqt%unG;WO%Dt9K2hD$5xu(VItLRlPg?T} z$tm}sgI0OvnBR^XD@pt~@3o>fLpR$~klbV}YPUDO=1IGDX6^!P4Wt)wDU7?Sw6DRf z$73s`qEoWIH6?{Q7I7U&{4)4+$W+fP0k$EjJ0Tfoio=txMGAUyx;ffGWCxhT&+1#m z_F>SCuQ-a9qY-$HI!9xD*=D!mbZr#%kOSo1Z)@}p)xjT1Ii{EWdpoJh!H5#sICEEc zN4a(H%2^ht{1YAdf0oX~8|wD`$-YLirc@Yv)-9P4P#`)rZxvkj z6VMn^5hO8gHik~OzlR+i0;?^8v7U$#KrQ6eMK!k{E(!qPdNoK>$MFWz(5tgmg2MAL z_Kg&xS9r4Ed7nkNslp6_Z;MwUw|{Kd7b8yblZXIcqbm3WFwOko%BMh4A5H$FxgQNx zLT0FW*iE{wVf3wBboHC(mYcqqDDq5)HyUf^3gCl`2Ejs03>qpf+1%% z9+WK=g+sFf5WJc_Oav$nx{eF10{@9s-Pp1&q9UtYxEP({;qr*&LE)t!_#@u525lIU ziJH?q6}1t|#C)}$k`IJt2OkP@Ukj!+R2K`_s~U3_gu~VdimG9LC*C(D^F%ewh@wj+ z7W#_xU@+`M({Xm*7hA;O2uG9q$^%`>9LGiD$thY;(4K#l^Kdb4?Wz6QjY*Ns3kvoZ zL#{5*b?ZF>-G=^a3%Rc-`@fO7GB4c@Qg2-BD@p8vPiQNg?Ca6~(UhLXoZ`nH$oU>r|a_jt3Z+gl`bf`hVQ=WeJf)1&Nw`xQjzZgFFAvDJT^wK*oY~DF< zv&m0wBf>wz1oL_HlzaXHK3*16s!`TYI{4h6Q8~GV?qi$5xxNB13Mb36)6x6nrbRhTff^@4 zw5#D5X|Qc{_$_(bln12@591EcEAD$%LCC($S%uz%8_J4X^~-D?f5!v($8MCCZZx_?EOxYlYkrCC^bZs(uDtn znIsVQEFzq4KAL!iZ}!?e;!Ki=Ad5Epn9prGzCMqW56R=ult@rLn0Ql=R+Z7m;oFX2 zgC%|HLqU+iNxcAygup8-=il*OSh#6+PH1Qw@<*cTQ2fk2FYmw!a9gIVcK*T3Cn?o; zTCWn}Z#8mnmoH?ZNu2xwNs1b6BXPiNoUSC_adw%1!j$hk%E-j>ocZaMB?v`&1rGk< zYKi#dxX5?p_elTcuiF32&7j8?m04E=uOgG6q&UN8yJMHM`P?!M3b?7fpjtoluejt0=nU`|18I*vv@9dfJ zRdj3r?6$GWKDB%x^SLw@q75RvfB<^pTA{<0E7;+?r2|7XwLu~IP>sVec3J!$E3+HJ z4IrQa$i0-H-2RC==F4%E@BAa9*Ug~|5{cm(a{nv@Ot%=by$1@)0!XXv~=idjO34@-{`5Nao&W?UnKY-GaylhYWCsFfIKrH!nG!=1q+3b@$8d5@Hx6-)746e9c8Mh4D4&od3-!Q z?$|zmYt`UHI!4Y>^@UcLypUtz9%$U#=F-GgLr{ISEB~cP?0ETuJLqUpE&6TCOz+96 z%=vu&*j+uQFvEHxo@Jvv|Gwd>q5odVA1*Elsr$3f6NW{8OS-KIo~|Q)e0Y*uAqD}8 z-d^b02Z8VF0aca-(G)2iZ6fJqmKDoRb_ukcc89V}9L*;(s1-7tp zCvkT)gcMNxbw0T)hr9!&WR{!Y@?E$d>NxW}G^6DPn@56Wl^P;920~x2ysF)3(G266 z`U}X*{rDsX&TOCl1+>IN{-fi!WM}(Y^jnQgMd5M>c>qf6-!8+W|GvGu%Xh?nXYPs4 z_?eCMnm1(BG&PEese&B59SiSZe@e}rAs^+Rl5~WlR^0?wH3Tdl3K|2w0YETADzT%9 zHnemH4zDwH$wvKh9{H|7-4I;DaUZ$+;*;2g##y=2J(giH^Xrp$$eHQms&_oVyqQl| z5U#zo^VeXk_qAs$N{qU0N?4=dyKO~m;`Ri!eXU;QLXG~*MU_ia_!VRo_3ktL=~H&m z)ZYsGr!sJbVe?@Vc(-=>-uNy{gK%mabZkni?Zd??!lP{EisDb<3ys@<#;V%b3TfsBemu6z z-4E3}e}TbS@b~0+jQXH2Q4jfsEPj;v>=Jw~b=QhKgOLomzAoUw9bV_+HLYO-h=mF&Q)0vgVw^=d^F=~Cp^@LC?fhky9XdoeG<8;mYT_9KJ6B@X{IPx3-C+ZkO?mYz{v@28!fjPH@>QD4LH($9XE zyy^N}LL`P;tB1@I9P`Pz_g(Pvac%F|coI|YyEC&gPIzJkr+7Jeqzvw<#bmIoL_Lx( ztHdoI7x`A*)b7tq@N!wl4dS6sC$Md!7C`q>J&fsnd7lZhx#tq?sJwR_)mi=7n zQ@c@b4wt%?ffoMN^xNblt4vt|3he&{V%;wm;Z^?wRD61<(1afsN-`@aWD4)rCK*E# zd?K;3|EZSWvr{^6P1z8c9Tm`1x_%pX8H%w`cOG(j{ZTC`r1L}UnO4}yC--|MZcii? zlYgVA%spz6oZe;Ei0hlW1(8R&s0;LwiPEnR)bUsHIIly&L64cBaY^gAtMDmhy;nnsH z#N1U5g~7Qy)fj%&fkB6vzkm|Wb7(*KN3%a%+&;IH=#v|MyEYWEZ-x-!Bdb|xD;&t~ zj5&_+*`3IV&Cp<4*F^kxrlmsygRt|)hH@D!>G24l0i8yEGRth`Mr&~RaDKSRr-3nHZSMuLjN#eX8YuK{Qh%3e1znG;B3s_rEW`$zQZe0p) zT^31H#0U`i^QwdgnU(p;$hK$6x7cFtC$*scb}k-Jl*%%*)r4r2)~oIZ>~DY%2I!@`AXop5$I;f`=&(v`1`~q#SLj%rFLNX z^)ze7>~G?UZjDE7NwRW&w(-v`baMrL}0!a%x-sxgb?Z#1Xq$#*qc?l*}=>x73%bHJ1I zwFbJ>w-IMw#mWt+=2jXR4d*N)SSKPxzp7s{92qpK5`a{_wX1IQQF9SIGDtUhAv2%) zXHl^;wIO*EmC5XuZLN06Qr04yMWjZ`*%_Uy7|IfIur3+z{z*;1a-Ao1Z4}uS#ko#6 zp_I{R#$l+eTGyo)31oGj(YR)xD=+;1{Zi(=UbYT$({$DfATBIWdE|lED&jPbtdDQT z>S7kP4$y+Bl4hRQdHkCuqeug2sma1eGwP>*dh+QTGze>2W&2{-I&`ZuNfjT35+(T( zLgA>)jXeHPYoVX~b&Pg(CAf&*$)#?&w$O zNr}~7MqDC8TkrjbJg3Vg1#%JBJ+8nBgx(AE6h5aoYw_@b^R<(y(GxsCc0xz(#V=Ql z{@qnT{bDrK%kFHCW>}(41Z2eB2smCK_+s<>il5Vc3eCk0EJ3|1`&tr@T_%SDDE?i> zjrTGvh%(}0O-yE4#jy@uo8-uh3I1SywlQ~c>bch~`Z&MFjaC5N&X%!(eVOyJ<6}^z zrp$v}KgXXPyOrT4`F2Tx9yhTeaa9Ysz5yZvf|eeboIa28i}}M}h6WyNb@drgpGcRhctjtC3HB>w&J zASpFL2$rNXD<%5T?`t-4z^M^={tI6Yp6H%E*t-z3zmOx8sMVohSx%~pA^ z8^t}F?G^8Z&`8t?%z(^ z^Alj6!92SBhzV^7x;~vLQQ9%Tb)gkrc)2JnbU6Wys&X`Vf5!8a!?A)>sdZb-J!fnw z{kWf##tyn2)!7|LzOBOfh*ZUH15BB8k1uODzN=C}(|Aw9MwlH@~9BebN`na37aIW85WBqV(u)*VD=hkulwfV;q z_wQ}9G`CPMt8Q{NwG+qY=Tbesd&9mq`iwMHQuQnk2XtRes4Ji+$D6j%m0TF(s?DIN z*@!)>Ck2?4=>~>0_aBsFL=?S;E%&jqhZ@s;`qNRa6oZh0m5ud=iE8uo4;r5R8zK1w ze8e5@wrAAPT>$lxIlnC!A%f2C=uaHi%a(N=FxY2L z;-lpbe==E{`F5HnLGymq?In*v#fKWLMJaDgKBWk!3hxm|`7ba!**cSb3~|sJxlPuh z8$!&(a}?;h{R=%~2w}O1TW0MZ+?Z~;PPNZ}f$+TT!Z|H6(s_?rc&8v@C_J|>OFt2x zyZKdIXjQ?U3T3;CX_DPj{qYT{gA(<@Bk}^te~y9lJLLMU#ilKGw3>M6x8Y28>apG6 zP-#e6a72zm)&ql0avw;>Dd@mAR2hcK*goVymeJM*=QNM=jLXN0S|2?4PkdM@bY>To zt~>B@d8FzsSwOUWbG;i44snme>d{3+KIa6i^!e9y+bj1WyH^P(kI=J-5o7q=fj5H^ z>in_aLuCMqMQMOJfToxsRw#aq#M}7oRnir%$s}EJ1t7uyrj|UM^(itrDm0MOl#iJ3 zio|Y}hVZ~-!OqqZ$raJPJ>OzSO|tr5!0`K2G`d^qD{!Sa>#fyjZt)z<_reBj4HUDpoy=7n0b#)y|o0M0*awv zSliO^!@k+mqnmgVZOrn1ZT*_ze^*{!cF8)Q`qg#30irz=lsd8o6Qs7ZrCAp!f zrbGqWdu`FDMnh}lmCc++3N=wbvHxE5{2ASL4~VfEphk46yLaTwRDqx?YmM7K+`o3~ zX8GgGH=DnE-gQwpbI)wdA6f!iD@Z=65wtt^>-smQ>)LePSnH=F+bIGe^#?IJQc@9Q zch;%TCVKGLnLpXjXx7KKq}1J*)FG??cFA|!M*UtVo}8Ag__6uyF~wBB;K5+{FIh!A z(I2ql`t{Rj_gao5;_T8{ZBPq*`0p&JZ1hea@1k3s<(x2QOgy2lW;JiGth}~bfPO!C zm=a^gAsOd=6qwDtoe{j9CjUaV^$5icY2|iC>V`77PRmGpye(BsziWHgr*SOt&qQq3 zMKAbSj99pGh;f8@T;)Xah=ZHr7dR0u_9Ubx~nPIljTkZGuOQSNLJag9{vJGaQ z<);K&Efe=VUe8?=GF&r!o<34na{3#TZ&jwhXY5efTTkrM53;?x>e*q;%@=sdL+6x@ z^I>?BIt@*6D!t_%@;zO?zne)`4{|OZ{xB@{oX;i2CV`#(CZCA({d#NuIS&w$zpD!E zR$ay5QdF;hkg2?gxNn=<8?DM=VE6O z$`kiSvmzaXOzcT?-xR5>8M{JN_bW)M90FLu-*bbD?PU-U@&|dj`1l=NQo(pT!_)!Z zl_-3X}*T#Kym>D;us%8AEn-F+1~d9_$A$pARU-{zbpL3# zuEv|vKI@G#|1j$-QBl3CWOta^Qm`?!cF!z`FK8r2o?oU3n(dp%Yjyt!OhO%=8Fl-# zi*A*K+ZoMnj8surI`jleQcY-b9x0Dgf=fF%>pr&hYeHl9HJEeWZVDsxfU@Nd(oG;8n&0LaW=Eq|Kdhh!=D{)@| z2)9r+yzsnyAc&65tj4YzV4rPKjGyD z=4%iVL6ny!7_#}44a!5e^0R%rxn=e5bsUkTKt{p1hLKj>wN+59b!C4D8r#4Uh=n4S z^|3M18dLuO#PVQXM<_9|c-OoDLXau&GgZ($A@(|WeWV_@_d|GcAW)-V&zzCeS)7Lf zD|cPeWWp1$jswnv?b>|OB2Q^GHuzfvT~lxn=|)g9MWP z94DQ}-LTmsFoX?;7|~Z`6zHQM(Z+Y5;OXYUa7(z8*+!~kJ2P?JX2#)yZdwd4o^PJ~lMa06r* z_v`4n*adbe%i_`I06^ZqGF>r6fg6D&C_o)qg*=c6N=^I%=3lo=sfQe2zbCvZq&z;* zTSOn$0k0r7`D^ESmgFroiinaJxDP5rz+{>2QVWaGL!2 zq7*gAEa;UImUOGU&uVZ1ywrxEA1@oLZ4SR-+n~Dv^mZXxD!~vpIGnCCeUYtB1-auY z2PsO4BjB_HMuCIz*lHoKtbJBz9L~ZTet#!RlMXu{@$5;J`1ZoAUJvsH~5z8Xc~4@FCJX(ZWj) zPfI<5kT2%Qde&VDSJtB)WBidNW~tnMBEhB9?7_Pqp6edJDvT_m*61!x<77L6JA|^c zk$hnmH!98F6gLPQO`;$BlX&$F~C*XlV?<^iO z4klQa6GK{pT=0n`lP{0*>@xiPCeY-=ew)qBoUom{oyoTp%lR%l&n5t6l~iFVkyw0} z>lZ8O_j+vsB3j*ex&?|53ieL0(zt-sNuqDbKR3qfe3x04kE5ST^1~f-Kbw2ln0Y95 z<4);~t$@i>`38U5p1F{VqSl*Ejo5@&P(iVgh=vDteiA7CJL6{ANotqv-A|nd$cE$l z-4O|o*^=4u1QC%@y(x{6K!H_x zg^q|Wr!qJ9$anvO4uTf?-bx^NQuv5V;Cs(xBK@{V1=JO=CFjh!&Vsv#O?fFQgY(-1 zg@kO7n0kjK!&yfAjpKzn%pfSCR+|m$XWf)6aIjR8(ovjSl2Od+Try~wl?bC|D3qz<_VppeOs{nn$ zOFj^G$TbNvlMMd?U7J4oyh%-i{gVxaXRuZ{8A`}FGE~)6*{BaKI$8{V&ksmy79ZK4 zigW37y=KnrM`lE~PiS>sJ0)Z(6YBXvzM7AhiXkIuSVA7)RT0TgZQO?pXHDu&%=%`p zllJfvX>R_%G!J85b=0dkP}WyLFeaaVEJ-Ahc6fs``V0@U7E}cv%u8vIM_wnyY|WM!I@1}+rIzh*iC?LqF^}gt;=-6P ztM)tJelTyWLJbRU62(|G?J0HxJp$xHg)wCwa^=Wu;-Z}VKZgGCv>I&b=M~Tfr+s`jyNsad_w0-6Q{iB0R+tYA1m-l9-@M5 zo2c>H_9cbge=5Bebg6-Rp%cLhn)uPGDzQ4B?_01E@-^^hGxm4eJ!m=#-jewq-0109 z&l&cCtfmAXXg!K=ea0;5aZr7X^-0bK&8rvMeAUk5qrTIsOW#j5?N1Nj_@~S<{JZLW zF5B$|@Fv08w@gN2As{^#6(fOR2~DK5!_|B7&V^P*BE!Qu4wmGVu;Sn>JX zt2&77EH8sJhYViD z(VTn)L`bWSgES;x_yWHcbtueyipyR|s$SKMgyGzR!9>dxxs_=m&-0*O}j4qJ6#IHRZiatj4dZ6lznrWw&mJ9;k zVb_Sh2=E(h=iDTsG-1Vada)*{bso1G2hr;II0x3iu)<_Q_Ii?`d+L?nzAF(&v0=J^g}yl4x&pWeYBI$^nma+DHF)Fm`q8WNzq znifM^;?@N_oiZpNjz$tf>}jwuO%0luDh?r_57V9=>%vDC5PaBwfer#+t((Zpd5T*E z_@NZZPepkMHNjTRqAm%3EDC=?m}%iP<(+SwgM(2i;9hS#S@g*A(v7R@^{X!(ClT1v z0VSfh5V}CzC@eRc3*V9Vc(y1Mwo&M(qgZUf1^6D`De;C1ASNTC4=;sELy8sBjX8*X(9t-9 zx$WeXd@${3`}1|A0)Ykd55#H8biL5~eHt8Az`&zl-b+7wGv%1d(?N*&#tlvo0xZgn z#g=r7+*{!#2GHJi0qFHX4APCg=L@pK&68^HJ48)1dO z@u;q>dA%xih!}48y-7T!fCH;~Xx?qFoZQG1N%Y+O3aCRPNhb!h1N%S)_)lDC(zsm! zon2bS^ZdElMvfB8DgC>2Khd{GR2rh<=lRh~Q3p>?bblzo>DV*K89g7SF)a0o&W9k*|lY$C*#}?e!7TrW5GZwhLed3 z`cLH3&brvAmY{#03;>)^1BrQ0%|Hp3^DqHvqqV40RRsc}FK4E}#Dl2x;VfQ1DlhEX z$l8?_*(XsC2K$ug%bL6h1xqN>Z5CPq04;7gPnZRd00GMJP=!QyJ4)_$%m_V7^9TW- zJULk;qo@Fuj9~&>6CxmFl{`|Y^7~?P$|r(b6^J7}u$CJNpcSetP~p+2BAELVR+xqT z?shj$_66+0V2|o%FLJ#LkjM}jNfHc%3QAd68f)0+Ij_<6M()pDCBXc}zIT~za$(vR zg7||DH9>v49sBD@a>8_sOw&0ddj*ncnK8I#guvE}aQ_$fI>w(y1TnbPgel+s{1mM8 z1s{Syib6x>lpiw46cCW5IUoj|j^YyyAk6#&Tjhm2Ux00Kup5*Hym-?LgCrcnHG|;c zbVHHnyw+YyU~B?36gZ3l-78>ncS$XRUD{6+v@2A3AXxiEIN-OremKwe7#m?{N%d_&yf&^-4NqbmK4C8oC?#)DC^Y0g=sj;b_vFx~*y~j{ zJdZ4vHp3kx*0}u@e7#PhGIxz3DM3EbV~j&j@n~^xya)Ed}Nk~(1t*ho%EnOa~1TD z13rVe%Z9s!lO1n5Q^}8l%|K2$6+!)(8LHHYI-W$P$PGvX5iP#S$!&Z2m^3lmI|M zpei2(b=K{A5(-!7e9f^Vyum&V}9>O&Rb;1-MOz(m9J44sYr(0oUB3%!f z5E0e zBY7$(?UF)rG@26eoi{+Z+Xr;Jc~=Hf{0ECc(>oxtAPRfLYuz)TNAbVXe)vvrM2hH? z9d8b{47uqUFgsM}DOuRn+Pe2PZcQ_uDS1ZUlq>{g_-nBSqXe!?Z7a@+4%= zo9C1W#?8ogMw+m@9%&qXyg6`A2P$t^9WZQO0tyijd#2Ea^gnvtxZ^U@lDvV?QFG4mW3hgpE5x%^+H@AR?jpR8X1UfEZSj^$P%c2w#*k|OZ|~vl-A^C9w#ag zEJyx87z|TL!YfXA<%6clXsHDVrAcMjE@e;^e3k|0h+UmVGeJXdzh|ZnC;ViWcZAE#t@8GuhBP3O< z4k(Ckezr!JAOm*XPf@-M3&F^k&)IvZ_gIt8W^gG&uy5DY&42n}d z?=xr;!5EI2Qc4|iE{193f*^U5I(SF?v|^BR?k3$(3Na9h-Y%kWbujioj{iFzr;4wa zv?P-|#d7ueSM9^K^utVbH01??eiKdvxavcQ$q{7F1)VeaBwivsuYkopT$LdOKn?B0 zu>6?qJP7uaN0{AT;07IhdqUx>NLpjDxArhcL{Cwf!W~i^fJUQXDLkd{AdWH`0*ct# zgS*==*rKFCNr;5pr20W%3CrFPj+0@mk_$043G(BVgxo^m34nZ!xDP%$(fh^8-7`}M zp{=UM^YuQRDEeWjOtVcIKL|hdkg3SdK#D`zxIHFB?XpM%Bo)Me2yBt2!j``y}o76!tghO!?FLu#Cmq@VXZ0J z{X8!A*smd5RW;$K&=M!!)G*j`i=F`ClW<#I;sS3oes?&3T}Wx2y8Y~i?y7P&u$V{7 zm+w6YtcrJbomzMEm^#FGbC&#^2xMQlXwAFYcTi45SjEMlV0vJX@ zdcuqO%m2gejJesAu z)LCT2QGTw`>Q0ZK|7m*4qz}2R!u_5qtG8ZvglC0RKbw~A|L(oSM%tMTYKRwzpc!gy z)H{3iZEXKe&5z)S1NWyMWy+NLE|TSbBNO@o9dSgneBsYF6dCLU*0;Zn^8qPjJq-Ux zwhx8zVk;&$5HG<{nZqRmwmxAD?w}Z)|GOjU*Q5Q3C+Lf6Zo`!xd^Rr}2u@yI3lt$DRuEsWFf2?u``qCL$=( zoX**_QjPD8C!(59@{oG4WTTOZm&HBW?UUK1J)K}c3zV?g?5tr83uxiR4tp5Q-?NhW;>KN)}k-?rxz1aWG*f|?Qd~7l@ut&KD6k$ zt4E{u8`tD#%QD$zBe1|vj~+wStV%^=KuvVM3n-9RY=u|vnF`DH)Ew{MC*?m-cW_G{ zbRYcGtTZ{Li?0_i5v-liB)J+G5(t`TiDSV)9zkeyqli-aEm? zH!j6`uBD|7k3&l)6%vbVKJ7qK08pis?O|6ZH6d}v{P7k#^9aT1K<7vA-`JhwoB@)!#e-W3+}rkQMZa&R)dyH z!F79L5B6`IpG^$P&VT1+Q%xm4f#QZ+2Rm+9&Txx90dweFcMn?ws~EECRS7$J$R`<= zEc@&yN9=p&xThUGc;*58*qR({JM`EqYVWhvO3I?dn|3tCAqBn=VIQ#;W|}M5f*siz z<%wrRU%*)i(sl=`N@NpRfwY5n_nK#;)y#h7#!8`o%^cbib2nZC+_g@&NW0ICND#_4WHtLqNNUHB#fl^zLRnU%?Zy6b zn~;_#iyCe7Rx^hJaxa}x9p-LJFu@qd_3I-?)@n1?>gO9diN`V3EBXa4z752dos;=?)Q9~o|6hvqh~z+lODfxz$Ya+H3& z#|6m1ihrs4R<(h=oWA+@jje-00!Id_gwG`1suia4eoAMeox97MzL3n1 zThG1s=2i?_NR(0T< zWE8v8A4B$h`v+U*S2OmlMaT1EYi-@J;z}Lt;KH3!r0J!;&wNZEVzhYf_BW3cF5vE( z&nW1E9LSK@JDN@o@kb3;jO(6%scnU%0ZfgY^q=*ZcweHS^2#20e92=|OUysDaRO5U-($L-UszNV4GJbqJz zU5eU)!RUi@tBNni(k`N5n*j*Mt_Aw1I-f5+Viqid%G>of5q<1pXtGuTZ>Fi_dq`U# z(_@^mdh3N)VE1q6?+KV%sKRX4_k<&EiZ}n4OQZfK7iy?^Yb;KLHomiYJN(XRY39DA zSrXtnfq^A)c~cFuRPHQqMlC17M#jv>S5CUR_N@x{t&c=lJu1|-p6ZESj|SEUuX5?0 z{y9*}?Tf@ez>ksw99CT)=(0Xv?#I}KI_vT&B?JKU~ zFWT%u_ky~`hh}qv5HdzeobngQ`El-~gqjhNCTt2bX-H^Qb1KZ56Ap7S?9gzW;-96( z<#T@WyT;|ut4J=+x`E}Jyn zZto+rL@(g*Q@ZxK^A54;4u9|ontMKGlf9BY!h%h*7zuSiiDe9XSfbeaGV2@Uen)&I zT205mhqN;LF8?%(7{q9r^G@KwA^K6!koM|-Hn z)ySkCv)g3UtWa9J`<5$jMC@;EKjCe`ADcfjh#@h% zap|1BW4aD0*E#NH;%1N(kYBh|p6gg2cM)8JU9919dx)>qW)D6RSqu-4?Z&bQ{@Zh{Tpqd;3s?irk7wUs$ z#{J3XQB&*!<{yQxj<@YDB()63kEqFOwEl1Ln{zv|V+mG|kj%dPziAh5f{0(-9Dq72 zZHf(c*dMug<*mrSv*(iL^Qg!mu-$z-;GfW8o)y~#Rs`TZ8GM)q@$+rP4ZtGK5-{k& z@BBGGQhku_`kb<*-BzX0Jo;BVm$>=C6#dGLq$e9-yitka^X^kMS|@Z~c&{Klp8WbRPBPt2%wOd@Kbnm# zg;+}GD_zJhn#=XnpZtFDx1^o;et+}*WmeEnuM;}2O`)PWWLqDa71%A!vG5TQakA^TirSNTNGg+&+wtK__{<&8XTUoQ;P=Rj8Sbk;X-E%7$B0j&aWZd9Re zp|F2GVOn=^3b~Dak4wimAAQNAc9rGO z!DQtN;G>C-rr%!CXO1LKAf{~}4Oredny9HT0!_5%mYebDc%wWXdo>O>aS@z}b+o|S z``Rz&KldKiFIx(a*0ye_{?)p&xs&Dc=!ioB0VWbSpoZ`AG6Ivbk+O;Z7LX9aJMB!y zM2;efTLLc%H#s=QJL^l(6kSu@2IbDl33{`=R94W)1)(3^N{0hOYX37Y)OcMau+lup z`_rv8w?gxM&SpG1*53@xc?Fx@D0rs!=35a5K{NqCGnU(#%b?3evs64uWg8}Oltf$m zl@f9#&}mFl|FO6qnQ9i5AOfY2h!t1_e-P8jOz;L(!3a@I9{itm9*fNY$5e=!l!z|% zH^pU}S#{*c&Ou%_>h;1{@w%|b_;yv;y0}_^_&J|VdD?w256ovZnAIlc2J|+Tj42U{ zOVvRP(*MU~e;YeS=}vAK)gReGrTg#6-#-Jd&iz-z6}D?d2==Ah-R7E5UV{~T>{12C zAH?N49~<@H{zjUd1SO;aKNj(w&ZsVtud%(~L%xV)OkvfWp&xvHzEci~1uA(##?uF1 zds+B4`txVRjv~9|IGQTj9BhTV_gSI?;3+4G1~|Aa_v~4kTv)y$quibUbS%Inq-pR` zsN7Oj)G*cjgXpK9Z**=<@ZbtVYV&l+Ja+SQI^q;4yPV$kl(ArMkayzKO=E1eZ2-N? z+i4&h_c?T!lri9Cs7!l12;$^BlCDMSE`j_Q&%zrGI}frq2vK8h4RfXpW9>idqia=s ztN(zosH9My6_~r%B)KnC=Pfhu(n=uGS5%{}gNo-x(^;k<0PqWfhO0O;;FADCK-jbh zmj8B>Z|d+RUW=@DB!4Lkmxa1U>8b_(&T$oy>Xz%pY~e5SRFr{yAe^B zlON}JXrBhe&JU;paObb`RE)SEeIyrL+rp-Lxo(juH-K(5u#M6Oo*@sY^qxY~ijkW0MEE?+lC79v{TV^1{-W;H&RTGV1mPDG?UK=Cbwh;x8|ld^mS=XM@94jMp9oR?|hF9s{IDW`YhBL2yVLBzKf zlZ_5YV@##~}@b@w!5!nM4mFK^oOZi1v>0fz-C+Cri^=TgtYV=NA)pQ+1R!bEBTmBCV zVquXMI`hV;5_dZv4^^8J@$gc0ju;D-tC#I*N0`tT&Ym|oEfI~AhE>@Y3vQCTS5Lio z&R|QqMoMz9%#6_Tug+kZY?13_0A%8M%f3fQOk za-?$#P@Zm1*l8PEo}1l1AO9}I{-=d=<#0GCfhjBCx8jWc@vTw+H7_ z<_~@_aZkYYvfPf34F5@^wXMR$s4F}f6P-8X+yLFMnqW27Z{ zqi{!hmr%n|zmh|`iZU-1B^Q7>v~y~BR3Rv-`;8O-AJZPH0f zMfnWi#)ri(+Xu|u&yW38RDqhl{K`65SyF1Ujc&U1k-VMw`It)Q_Dk1D-H?vhSpP{v z`1J4G0v_t_NSSS<^38{5v%`Jdn@}%N(GU7vovc154!ayX7hT@KRY7%5G?l%8eC)Y_ zEg?L~y7Szp_rp`_h^(~uW+OkpB4$ypf61Tkaui7vU0g$bfCb~Py!R<9w76h)e%u${ zKYBeV83E)P%rG)dOeyD$(#_w=e78En6L!$#1{L8fiAo3ygJcWN-Q@WxUMHv zuM`4>OJ=D9Q}~$zVM&*O6>KSbB9D*%)pp_P7C4|f>V+p^ zr73<3y1iFU7HqQB<1A?Z$I*EQB)R@={6S1i4YKrvM-WR-j+UbgTxi3Uxozhz%aa2& z_W;f8cnF+jg=jfYJEfk=kqfoNved+1niE4qQk=NQdGFr;UB&a<_jg>^=Nj11l=!rx z)ig^@4o=I1+1eq@KifgFiL^}E=^9*je!mN!>UtMWGU-$j7l&nJm~9`Ccvue4D@vRH z!HoJ&-aVWhWH-HO(x@HsJBS)z^DaDPY1;5V&x%|>PnEtrnZDI>gt3c1)yL&U(|=HS z${n8E(o&w}HFbq)t#=PZ1BJNTQF9v;10Z(^vV6^F`K3}dJ54kvB6&Y@2H=H|enYeq z&({QXDLkgk)++-{pn%gqfUx`-+axXo@whdGKq(B}EW-HCvEp#_z!%tJ7)w3fq=C^D z@@3YFgVjQklA4ZIYwOgdMgd+@qb83^U6}GasJM!79^m#D$x;J($e~h=y;pqK>wd|1 z^_JYt&t4PYzccFOj;LXl3u2J&TkwAJzF;F4C3P`|a9{(J)z!GkS(@ zcN&bebN%#16tnH0Re2;XSXjH;5J8%r)It+>Wg}LL1+rE}_SiYGWK_3D0%21VW|S0Q z!U?pwDM`NIT}f=FFj7aF<8|%CGs9%1=ETI;u%=}b-N`c@IuTQ*36w0=r7Qdt$kn+o zDhyE6CP)dxuX8M-WFqlbaHGTrT6jrP5)Z|y`byrJ$ne=2(V>H9{Rc(R-v-qKW`0Q` z6o#I(<9sS8)?fj)pOs`(?m~*P(Uq~7{FemNK5-$t6)kQ$$7!@V*&#jVP3b3N2&5f+i*m<9zpg9*1-Z zQqhtkRc)kXG(^Q3tvgbYc<>qBfQ}IDw0I%&AVl!P1S$$NZQ$FT`=aA;0s#4uq`bcS zBey(^FD?qM57P6y?cP!a@aV2Qm57qBdJ%2>Zbn{OCq#{B`+Y2KRR}_;WbS#i?7g9)Z)}03tZ_XoA^y?VW zPJ19yC@%8wRZE=s)6`>JJu)bf8~EbX1*$$~%$sFyix1pt^t*@Ic#%e1JS{V#E6||n ziX2tq+(hlp|3P(RMmWbUOF5=MO-k4iy>hTM;GFJ956MQ)3#toKYWg@~4wD)T+w!qz4XhSdjQL z;@|~f4+kh4a^rzuRN!oJtG(j@t>?E&sU}1qB9EUMtA&z81{00D2u}B@WkZ}>fHA~- zmSFjvv~?Q(yFL1rH=LPWB$9KuZ8`+@v;D!lXW~&xKgb-yxixARyr$ji8%QOa%eAp^ zlVD1BM2Pyc;I}v|xaoZWGM+K2$aQPM$er`B_=YyI!oyz@wW(w&XNr&!Zynh)qZ+JdD9^!yEoatXi|4?%2sUC?PzGu`T@YU^?@avgQV8Dh2nYb@L;R{6Kmd$Cc>#AtK9o}R3F@1Jda*@;Gk!U z9Fqg#T7VsIQ`J`rZtI=|^ZqlJ$$jW3CH->3NV3gMHrv1UN)jfj>taQcY?b7^kpr4}Wm?8e20s>_Cq<6)V5x?1 zaWD4Uu-cHrrTBfh>y_&q&vlNm%>BE_FRfp=#IIz@bFHN6+f7A^t3h~30AzX%nFcnr z%O=6P!`Vue{vB2X^b#QcoxpxN?zzUBOB;S%DkI3_iFvrPLaR>}!+jVU;_IV^^FfNn zc@e72Msi-)IRfDdMvjj)Sc`VjS$);P?OHN@^ZT9{q{8uWI}A;q?hZ09Rc8?x(&HPt za}QhhNP3GqU&wqkorMply&|XRrkiuB=JR0pjOUuz#TO}PC1p$3C60oA6vkgbBZ#bU z*yK+(3*fJMpE_-q7aT1YrqcWjaP1OYHR%AQiY(RY(63G9<1BwLvunbKYgwa$HYQE zP2QjS$iDv~`8@G>gmO5{JdC+>EdYg?|f9#x<8f^U&X#|$-H6M6c z)8XFS`C>@!qgt!ITfGrw;PJTu5Q)k(B&~3*oJ<1)7)Vo~ooLm#Iau4gIY`}!SSV~R zm+ROah;OwtNd~|@ZGDag9FB3;i~ROe`U9K_R1~HcgDmY3EP;(QUdgm5ZCNrP$Y$11 z?)pRHO!tSXxE2if3&&rPIn1F75Fk7@r5YFi@@DM-LnPa(+lE#c(flW|U3L&vf{}s3 z%tkGwTZt+|@i-fUR%q1FL(~n9{Xl!=E;Re0z|cju59A7ru;cEONV`~12IHky+Xo9%XJ;A-11QNQII2bC-LvbOMg|+ zkN`eaZ<|+IfpZi(N)64Answ+IIl#@;Gn$M;r!40c9`RxS>bC*1`D*uA&RkWh!AdlxTz&$8v!Bm<_$EAk8*c330O2|4e#52CQR@dVZ*$6W zqbVayA+J)G1{UPnrdMkdL&uOcrYj&8S5Ix7rA*>h32eyE_<8-ZzAxij-e{KsVEr9$ zT-LEfMWq%WIsQwOElA%kA!Rjrw%}%qJRkgVLbMPFow!s$K#ZH8m)m0fH);m;w4-sW?U8Xf)~ zQq^m+l_}r0fQK`41u0N~9Rdq(468Ngf6u3$j|(=(@Vl5j|7%kwbxh40MLS=Xj7dyO zY65kD4dh@6!nhU)1&(i;II13`Es}MDz4=77h}N9;B*9t?$}t{=8boM8K3a=U(vUn5 z>En413O{pW1`}j;(vpJ zz@C1QU5JbD=2FB34z*^^Ndh&liWuT2Y$SFVh6>(Tw19!q2l!7d9n)(XXtlXz7VeQ% z+btFSNifaLlgd|bdUFBR3=8+B<^6u6nJR~o^TqJLl7BxhKuT@L%(0h`zHD<1OMM4H z2&_@J3Ys2}xZ14}R3Mkw=dJ1htCnz$ypCqC*A%o)1xZB|#c!YN3;+$(q)VNS5(MK8 zfbuoLg}0-W#QvZ*X&w~W1g()co;D|;NKcx1=jd7Dkdwuy-P}e$NOwMQLoKljWfOo< zjvvpywVt-f+9fM>OP>B6UIq;3ciN2iLn3Am)TO+=RWC0n?pD-#6v>*A?tpVc7?W~~ zfPfP+8)LO|nbF=oj{9;xzQ|G!CQ$+1n~WsLAa#4W*pgDI6R`$!GlNbWEm=5&NKE|N zTPOdMNov8gk#;<2C#(+5Z&XjVN^e-MzE?Kb$Yb0F#qhmJGsOLBc&>BjC|B5@@eEnN zFtY+85Y40&3}S|pDV^i*kB>tkhouqN`;?V_atF2y^}PEOZ+6?#rqQ zZ5@6W#uguiyqU>i1Y-Mq5jFOIPS%9ZRiVwN%Xlyw7~N9v#vQi)MVmxLL3Vgf2o<>z zTG+%H!X>YYtk|WG437f#=`W1qWx3+I2bienEf<(d->Nw`aYejQd~1OkfWUyj3?~Nc zt^i(jd#O;Jx{O~V0TlL>{|1W-DN@ij!|#TaBG12rVoO#}+yRjJU6sgYliJr1y}9+CH=V4I^hW z4N1?+G%mMFVcLcEj_3WX{{c z+>BCDcn-!v(vRR_`Uw8U7@KX<>3%EpX^>&KfY}pMDn(>>!REzk#7pK3pSeWgRwV2A zIb$DWKDZJa4Nz*>>O2T(DT#bui(OB%?qYbL0*IZXXV^psV6HR@F_)?Ch~k0iBZPWF zXzBo%flKDOixC3c!%?A~j2+CGTUEG^DK%`3XRBmFeC`iK#S(CDES3zu3LuVJQ&m=# z5CbZ&M>FODaGetq6{`tNasnDhtrKY+3g~uNF-bai;MLcnH?{S4Qfk%8If3RNUVcSV zYZc#0%58r9Z7h@*hf6wwKA^O9sLzx|y?*!Otl3yvTIYVCia9VcE?RZ+zgk+)o-mAd zTK7dagNOdC3E1x0KpAw0>YtYO&G(yXaCuuUw|V|pDQ-Wt%&i*44J;0HKpk4a1*9sF zAG0lW-b^wPL{``Y-qHg0yrVExTLzrcdQE)Z;BeOo_7rb`Q z4VYQK{s)YY)BR^UPpyBNzc+?jv^La=;NQDnl9aEp#V1cKsu=h#sPkAUK&w`q1AZ04spl#0$`(8oKHL>1H-o((0A`af1~jahESbBS6U{tiRNv^YC0zv&_)CbP-}z~(`vWr~!!F=ph)4CJpq7>>bW%yfx z>HqMK9iMi^P5i?S&Z$xLrcl7o1etgA+E-<8Oq@bBS``D%=`~cKO*p^-*Tw~aqx1!3 z?HpO7v&zfBXo0e+r8|HYHZ=)mx3aWO5XYHwG=Mh)T5{V2f|4)qmeEbOR1rTl-|R!Tfz`<9Ae@S`H2^(_ z7^3Q~Z2}O}(8ykaB(Chueyi(FC&+m7E|=#Cuq!0sC%L1$ifUi`UeGM!`NF9oD=-@b zsq+@H`Js|016#MF&f^yr*c!>*$BVC}&%Ustz8h7Soi?521ROXP{!caJ<2o69DU^Sg z7p4JnRmV$j+Kw)+)YV@(KDUc?Y#Q8jdi}o@S!x8t^R7N;Z@6k~*m-i40Rke#-F)NN z>8(!<*n8*HR$aQo4o$^b#(mLzzj&%uV(=A(V`neyZqW9AtETEDHQMQ+RJq_Du=VA` zzr8Nk94V&5#GDx8zkhh{*}O3LPM*?aVqX|rbawXD_^ZIb6yHS*?ws}rqf+GnKr4&2 zqvGU3{9D~V-#p5N94r!4n`yr$(Q7oIr~B8Z(5j2kBo;BwC2SI~H@Q{(2cIb74(uuXmMmiI?% zRY3)um4{2d^yrehg^_7EE*yY;0XM8+#9-G?<5sotEm*GoY^l+hkr`j35spRKw<{LQ z(az7$Ua49(yW%@LljiVY0iqsX*1!V&$|a^bT)x_~k5&WL$c1V?)1k31YR5UYzmxRU z>EoH2t*${)awxy&c-17_VV=3k0I|F5j;r$CYafU)n^P+GM>%(lPlr?_hY=6!bJPki zD7{R1e*$;Ni?CY%_V))veT>+t#X%hwZfM}_{ZsL(O~D*y{sC^Krg}wx^$7x-9}qhs z(NcafhHci*N#hD_PcG!7geV8JqM)_#jh`0|eb;L1^sg=d(*`E(o^w83`WBDQ1!i~H zgYbC#H@Gd zSfU3nK0!cIqE!dU?W*eAb)N5BTLjt-?mihGgr6^VEn438nuE+k4ONc>)Tr>i@s65X z5;gtkCDYfiMio8zEOV?Geg};gy7BzjG%096$~~`b+7N^K5p~`^+^6DZu78t?!*E~g z9-u9J(O*+jc$V6ownypk?kq$vCbzvFvbbg>b6|7kVbJD@EoNeu>#n44d+^s+fwuB3 zerRx3Yew7j>y$3JF@m4iig0WzE;_04X`N4a zyH2>g$36A0))@cbHdO!IRGRfD`61=*2R82rx|KvZ|9G@LGN6DQ0q2@%QGDC4BO`(= zq=pF+MQ^C8k_O=vDk{@g;X(RuN&Tm#c`E1An2F5)VP7ACOP@@?ykc4WGp^>J4{0@j zJkokYLn0vp6o2>6gY13Z>VoV1y{lLOhF@7s;cH#u;fwT>^w#3Rt=Z@EO=d#l`Po3Ztb3QrNG|+Fr;Ayks=#!Vj3Uk7X&4>qzj|_0%(d%q6ApLx_)=K_ZJ(j1Y ztz&gb%6stJPQGed`C&VhiO|RX@F)4@2s0F`tn$xGYm$eR%)eD!3FEIfkRNx}#Lns% z$2`K>_5I^_BXWyF+`fCxu=Z`LJa=U_a-N zhk>T0e|8_UcKK#KcyAdtAVaj7d)#dq-~ZQI@2q)NgVN2A0|6?wuvoa{)sYNLoZ`kc7IDT6A-`P<9B zU(CKY-hBNZ^tT8f|D8KZw6&yfTBVGBA4^X2<-OIy7ch_XMz){6zC8S) zN;MdYl%15gc5lVe%cQaYx4MkVP*vJcqq%!jgtzJ`cFg-s*Z|&L=q_nF|MNF*W`Lrl zAZ2}^1!KOOzj;x(dXA9%ez&bgb4Pef-VxEsXU2`8H_<1Bj3fN74Gt^+CU5;FNZG!P z_}y2-;y=g}85%bF3%MRLr?eW|g!?ngJg{`PGpDyYWmZ|#>` zZ8hYeIU5M{GW^&}IN#^{mLw_F@?KBU`t);3hs@&@+3(Ogk$x-*qg7*!WWmb{s+S0mtnP|gLVf}vHcr&@f2S`9r=fz5BdLfW1iw_Y^<#5Y;U7)TOv z-t4XJzv~5cN}FvF|AQ`+24`0Ko+e;CwAjK;Z6(y>--fmiS_B#K5keR1S1ga(o%Yx` z78tN7c3DjwtjuD6Fvg8vi1N?B+_I4K^a*hklnH0oYY3}xz*;@C7FvA$i=L0ylenc% zJKx)XLMZXMvm1XpeK)A=H=OH`GIhWU8YK$u_G_u$$jmy_N?J|~TZ`8&Q0jNQVLwA~ zRpO6SRSB&K)-O8y)d@}q1!rN+#GD(cjtAZ73(kkCI z)>D+H#p`ujt_8L}x8b&TU3WJg#81-VK_7B4`~kAEWBnn#xFgmu-e#mc-TI`~SXAh$ zB}@EI^thf`+xU&Ovd>-qBg?;U{>6s-5tT>J-`;QhMxmIouavvxA@3G& zZ}ohv7EpH*R-a7xeL4@N3t-9WVAyDv^_8ZVDD9v3;Jd5#bKLBrc=gZD#XY%> z+<~bAEkRT*bmDjMM}5Dw153FwP+rw)a>1>y5;^c`%6b<;U8JA z9kR2Q60pijYAa!M!Pnf)g18U&|9zU8`aX(oKd=4c)pf;LmeC23+lp!sQG5K6ZKAS4 zq^~N5%0##!Bp#pFWJU(uCMbcL)Ioa>&)+T)UTC^)ua7I+BOe1rh)pxo{(~avpDbY0 z@h!6jlDBs1$T1YbhVQf5iMYR(k`BVImZBVDOT3lRya%6?Np%Z}y-;Y$K9ws0?{?%^ zZXn+5e|P@s4H}g&$WVyv8JRE12tcwBe(vwtprJ$CWwBk_t&xvLSQaw-tdSIK&`+cGd*CT;#1l`rlr ze_r)fe)P6Wh{Dq_L%vL3+c8Ay=kao{Qz_;nq9m*dA#X=}dv1k4b4Y$!3)1aJMsj*5 zFUqf^hsk2Tj*|uBY`#$BFtYtwxA%gnSB4$~47TTTowgBM3?4)c9@g-Bk&{-Ms$3>T z-d~;2`Qh&OZ%Tjb9(*wX;wqfK4b(UPWe~TZ{OGOEx% zZ+HSfc#jiz0!GD^Y`NO*);V^DBuPCUnT>Y$iqCRN;eBlTr{+{YDh4JRe&8_k(7QdR z&vSvdd@IU%Z_2UQ$pyWwD_;*OpQ;JExCF8vuqaHF*YkaC_iI;zrJ{Yg8*|QWW*%ye z^#e0{v--l60Nx%A+Au@r(=+C?@YP*9+uu~~!lQ|T7Y1K{eE&Li3fUED(IFM9FT5-v zYxGVzr1O)(>zg4xW(xx5|!LBqBUG4z`1A!arv?#)N}<4b?} zUencq9rxI#__aU5{~Izs%wl@TBHm`~%JmaLwON%^hMceXJ#^!}dfGd-@6@zzZp^&B zbAJx0bnr~zL1_bvPqpylvt&H+o>a+)=%e56?>n$7%)OplQ%cp-z00ZJoBv<$38tr) zl%&~V`&(g?{SRT3!0#Od0h-MgEf!&4?O4|zqb9JZW$GT{PQP@Wf6*UX4VZF~>i^Dl zwhP@Tk6!uzd5{_=uSC-$D6!p4sylT1E8{NkhcDoe#4Z!|(-i4oW1*ZU*EpjKY*TJ?2lV^iD`YFF zNy;G&dnplK4iDwmrW~TZebHO)f|TV{*IVB5Wa8gz@~d8TYiX~JS`xDGs|}}=I&=_~ z+K@X5sx+x!w-OB>-ncN*t{hwqtAUU`UkSklJ4+Fci9+tA*$(BqUOQTLFRF{3MNYN` z0}stE_8@cYA~s6*?$+6_n=p0+P9`E34MoJgfsAny*C^JcSW8dcBZNk3Gg*&MJEI-> z_jqCs2VQl_Z(l%veQz(7iI{I0$r`7HKJ;(QJz;%C1^-Sun>gpw3#~n4>rOydz1;btK@u{nqlt|rr$RDCwDzfkUzeP7ff8V?R z%3V#XCRILMjj&W!YN{xY8AZ8-5?=y!Y~$!eiX`+=Q9ef<{WZ`a@ zj+I@J*{b}l)fsW|mXr0B_}pC!~_PzM5eUo19ic^EbBPkHcKe7pFqb zp1uZ|MndcUFCh1tnOyho$ATdBxel%O7K6x!#Fr*FS+X7aW-tNJ!Wp~x-XLIgJ1YtZ z{RZNVk`pvA-$RSnx+Hef7lfNyI!0@Y6Wj3R2RLN{hgXo9D&5VfOCni`6OdV_DeUde zpo;nZkM{(+#W$0&RgJgi92dmz@k`iZHU~>1 zB+>Zh0{0e*jYJg~)_cIo_PvD%G+QCH%9~WlSi+1AE~0q}c;m@vkjA;@9IVU=Xx#L3 zqBBVyx+_k*!mrsyEtpBie<;d*syI)p zy?yv;N&5lp7mH^Kn$pVWdr&9YYv;rN8R^8|L7b_39y?HJMo ziIzink)v!AnLSkg&ZZPnqYD!sPw4OG{&Ppyzpt~iJuzWV%?8nCy=>{?toB6IZ>%}r zi}aY@t?N03Qa>M5R4g#U-lap0r#Zi#??7q4xWm7cu_8^F>5HI!2dR3g{19DUY>!jK z&(m?~5xMI`^Mv-M-(}GMh@bnsae>nh;Wz9t%s1^9A2(sP4SqJ68SokWT=Vbwm5^oo zm)eSV9w~p;9)uL+_LUV8Vef78+lMDsw!Pv65g!mQrE4~L)GgEoRvPBUoY(dKBD*WM zwYEGKr1s5Ey6Mj$F5hHD>Kj-gltB1*t5yNNb?WHE$;b@FKk$S1J2f`e&s&B^y}h0h61*}X zdHuA77>npVW^a4{jQ{Q7i9}qpo@IP<-N1L&y|IM(BXa#B<>n8XTL)om4KUolZ0>il zbH#9G-JbK{A+VCxF@ru?Hz6BCQ5?kyuKb?X`{x|zw|G0Z1N+#$om+3lwqQ~?`AfFD zj;3jlEp*$idBkT$ef_sKPJg6y$2Wj%i^#Dk*q04MrY`Hfaxt0-@3bT=P@aS9O>`uIhdaugB< z5IguH;9grRwS5UP8uJ239oufem5YTdE~>XKqN4cZ};4fH%XKg<$Q8RfdC zna3p0Exy&Ztj`ERiIIMqiVVNd~J zRmDp%bRexbGCY_FlI7dkc>8AZ?s0%c@;<#jh z9qgQ*w~owfw>jbA$A0H)q)q7$7or{e98R1n4T|FajS1f{l1U~gA!gqzwHk$Vlf9-t z{IpU~g51ryz2f4Fm762AwPkTyMQ3Xc!j#(JBU}Z9R*<1M4q<;Kg?d~GjlY^-sq2tT z_#+c(Z<<*C-Y87R3UsMRC+E(h;n-5Oy|@Dlx#o=6n;}52jhZcbg@GqhHiv-&VbS5@ z)uAV{)oY=`$7k6Bx?^v7QR;D(YGbc7JKat@!|P-ftJZEEd=o(bJ?S}&H|{z?DaTNn z`P>aZeNJF)|0`&n!+oRGpLi~VL`uTemmWLk=3K?4zkn=O0isD;3|62rp7uvPLGl)J6==c= zGy(_NCQ>6&5?KexiOjm$8!(1^rxLtU`#7Bz6d@L-R8bSQBQ~`4mCFw%{@~a#euwVW zcrP$OR@|?3nypABQp98+Puo-GHI?{@G;qcmyWnN4Ezoe5d$z+3qcD3cgjOgfMm(Jj zVZ1acsa6}mLZatK#kueZPKJq`GJvU4j8Jiq4A)2?%G^LZAR$R$O=4Lmz7`OVBe42g zB#SQ$ehF_`0fs~TknN=|uf;+Id(n#HmQ@HYF3C9YKj>e<;xWt|R2^{~OR$%KSy zbpT$-fzJxG?lP(=HKqKikF&s&eCy{)L_}Dbs0!{8LT7MddTurdQmiTuxpT% zewpgC<2B1~<7v4iPoMT0rlb~t3`W=inZ=qD0B$ZPdqgVbrH2*q@EQ}A{NeoZM1%LL z%+2JIysiwiY!}K|IH9GWiBMe}XpJ`xdw+OO>Wld@TRJC2zbi|FcwADPCr#@z!-X=3 zAcfG;FrER3yky0&!tgNKs8}SPJgcULcF*4Y(oI%MM@;tx=}3jFt-Dy>v?KkLB6iw@ zNb&>Gsr<41HK1 zmINb-vH0Q-&4P6f0bDcCOLJvADb!HwHjLIFeyMZ50Id;-J?{T=d(k2WS-*WL4_>a+ zBuaa%%ec*F5l3yJQu8r#-!pFwN?Bq%<5@+T5{FobHBzGZ>Dyg8a1`4?rgS$qK#x^r zQfjA23D)KIf-RhxJT+*y-Yqm6r$^Z|eO>LDgop!f0EjKjwQt9k)Hv=m22s%7h+ft8 zIG4o4`?WP#Fu4V4m**8a^|~EsIAua>vgU#Ux~WZ0yI2#Z%ctox`Q14S{s+I|;kof3 zE&E}o%0H%_z=}rGN_r@{ZT&^B5(d@&*r{H+HHsXa*4zJNK4t=a|9M6gW0NG@D28@z zn?T})K!ND&m0|;Qg|2I6QPOJ4a((;5f zoQXscx&8SjJ-bJg_(!4HJFh&bzTEm#1PwTb1bViQ42zcP_}^kJiAl$&sZp4_xNfqF zy&WloW8I_bqse4z=rnrFt zWZ}_yn1}|dBGaX*vROX!^5c_~gb2}l{h;gp^`_IK9HEVSDK#d4E>CJ{5cSdCKCn=0 zP{AlTnZX2TSKv$O2pZ-AV@hj=diF;ZR|D|T7l9;?1DVF+^$|O*x-pD*uS!1Xw*qeE zjOg)q^gl|dRuxSyM}iX12C^kvPY$ruCbZ%Lj(dl}#=K{X_+w45a1xC*X$c`ZPRuL( zQb0lh(;+lS2?zjV4IPg2_QNncP3tvrq+nUOFrIUKa(G+>wrwjL1lr#@v_a_5Lz6Nb zsdv#^@?u=pDQuYk;03B26rrff3%?S|{tp7$aQ(KQCtS4u1&aPcB{q6!=CXdu{d9yI(^Mc$7J&c42_VHGT=$r+ku9jl#U-iG1pmBvfZdd z&m3OP?+URcG|4i=xL%++lVVhI$*y-zlQ#fQGG!LVXRL>AYV|=3pHKuXyGRkY*POln zPZWHZtnS(p;9R#8=Ju%5TWC9K@q++=irq|}FTx!<9x#|+Ar#p)KTjhUkf?n6_>9^1 zgx!*&RxAF~qdcT2r*aH7IiXdJxJjH|+tku;e$a8;J1|b)OnQ*|Tt~D(`lU)$=#UBm zpbtwwNA6Rw{D*ZS)+lD`uwL0Nq#@}ubS&tvH<5(?0vP+KM5Ls*EXPZFT8mwNMa6!| zH19vi*>Sguf?P&dSZCR|*)G0hS;)W}i!gBAoAw~3WnfCH^_JaCco1PV*76c`GU0-p z+>)5H(&P3G3vswr-34tJIG4U`z7^V;ZQ$L8HR-GXRyE07Ti)Sluy37oik*3DCSr@l ztc?%L$+s4`eNKBhj$M>05F2r2Al$qjSTLBMowmdaJ3$J=*w}BX zAj@t|MO+}?wBAC_qf)j=Cl)C4jCfSl8+gLIS<-{TWi zJ9<2r`P%p&xotdbLtO}kmRUFUJfPDF0iHd`!o|lY-JFNKLmxlGv;LKnItF9WnL}{1Ns0 z%`0=Ah*aJG#dG?}DlVb7wyjrV;JIJ39OyIK1eD&ClU36JA2cw?%q8=CJv#gv0WleP zW72J={qy8}NE;;%^U`eS_5|^F0(G3wkN9YsbF<{GYNNIVMC6OicBqX*m6nb)JuM!! z%FcyCzv2XM_FWXw{p_=Mq7X^}ymgR1EtQIBs|)F3CRQ&OZREw&QP}We#r^#IEjRl^ zUL)&EOebI_A&jlp5USy0SQ39E*Y742cz}Jy=Q!!-*~6Dj3ts_$^wCW=@30g!`IW4u z245z_dTEXJe(tr?=hL=2x!sxGSp8aUD`TFRm}Fg1IX15+70vJYr7Jx2dOX>V&r*3t z)gN`fVWQ(_w!O_2I)Yg&{(v4^=40(w0O{0+c8AmipocF^>~vq#z*tIX8-NaW3H<<0 ztm;B1JDJ3)YR8S_aWk1Z4-E7YvuP-!kk|_ZdTyE9GN$DR!r@g<#il*6)AlFXMEh|t zJo|xd2(VPbIOUMZQWx!}a>vDrD)O%;hJvG2;$?y+f^?L}!PSA$ZLVhb6Wqbsi#2QF z11cT4&kRgCHM&#hpY&39&v!`#g?p2558=a%n${qT?ceh|ETFL*7FTgUsneF!G-)Oc zwMq*=%%q+0K0uit^M~hQSM$dQHs*lF7>(w@RT6;kGu2LNijOvJ&eQ_GRt8nrk-vG;6#dqj~(_vX&+|`fHX@}*}{|`SG{-?8cafKT#vwn z@qzbsG@4x z+FEaL&PnV3G}=;tVmr>$m>Wn#C-I^A4EkHNFFnxa1TJ8ZT!Ubhu?i1geKfxUW=;#B zB-Mo3tNp-*v$&um6{OgICkWKihfE@xc#aIc#H@kkkbypD{Z?;yRRao){m;xxeOR?r z!ZvE(RF0fsHoEo93`-5>KLxN#O{dZb4=Man=zm5QmbT%OHoD{zs&{cwzQ3tAIV9&l z=ss5QVUQYJGCJ%%MBIzE!h^PParaq7f~-V)C*%?B#b_Bfve46Aq4kN2v|$5j9PAAV z^ICucw6Jz$nz1{pfTZfl{ddSbl|hGm3I_uJuZTmPvTI%i%74p+3o{tplTcKgt428> zO&++znL{-ut~$vx6Nzqw0%+bj0ctf`mkII+wu2@U3}v9C|3zwMpWE7NE1M8bqJvBa zn^#G4wGsR+IBg@W*aE2#LTOsglU_v=I!0;-W^qZXurtVPA+rvtH5yW*{L*6BFn+Cs z>>=@-5ir| zAr0w%*Dt`T9uNZaOfyGc=R5~&^}T6lN6Qnb(E{)>*LkR7e1W^OBLV~Ah4yOU&Iz#< zX9q_NhLfq@{baeApR2NzTpK6AN_uGyh^D5uDyOSw24)NT^K$a8k-BPRkEL&zcjG9LiB;1`%a+@7Ex@viNi-0BdB# z)bYuNn+OG{F(QdmWLZ{d1ZT|S+pvv=M@$EAzu&7)-DUEMowuzMX0tFz!>jaop4rC3 zjp8mLt%cxlyt&=0fV!|89G?YYm%WP&$H2c%#zwh>XE0#Zo@-T9W??C zAk^-GVoIfjw8pV71D`ypx3}t|offaQw|TbWJ2X}Q<-hV~nP@_)n}a;QiDnzldCe&m zn;>Q{E>38ENYzpgY60#>NUhxmBj3e`&la@CE$PyL_L`}?X)gx)Wds$Z?h4IN7@nBW z-)PsjSafGKA(3Nd?@pR|Y{l&gS8>k29}2&M`HPcm#L6*VdVvoHllfoFt~6}-=p znrq9nYy=4h0TII1*d35jmVe1sh#lnbRTsE8q3f7{{4RANt+NnjfC+^_wO)gwE`f+y zF>BULU}OiN#y8mRsUiW;eFYgv8OI`q^0oot>VcIX4@*>IN{x_2?UP9oCkKk%kl@s> z5HNfkBz=|o5MA)E`M0ti*ihGHc!$|Ls7Vt{+p1NXgS_(URjK`G(ywV6*W?Z{xrkaR@5AYBg({6WEr zXCo#zO3pyl9Mz!nd7p`r5|%@8mXH~A`^t~3FbV;Z6ZsY zhme3Zt>;(#_(!S@UNIr1oxN&V@mxkPj0w^#FJO@oR~DRn5^Fl$0Vv9`Sd2kJfvovs zI-(D4{O8$&!}};WV%=5Nq;N%M&3?2!{^<~TBwA@rOCT;|8lU>D*OfNj zn6w<{RnHmC`5viX;=M4p3b=4unUzGH_?y`_J7R74e|EIY5!|~Qq$)Ce4*gJZF&H*l zNOOORd;QLCd05RXym-gHv@QW2M{X^3H3CjE`j5<}R4N$-75`lP9xKWz$ znyz+mZkIx8C6735f1;S@%VCCZda9#FbE&N-A*084WsjJy_Uel)#W zcb~=Tg{K5t$tYxN%0+mg%HmommtcR?ZQu7W)AO8ZNGk$Y=*!vt`ki*di)Awc7Q~Yc zhzJhh+t>q}(-AnkMVW!L;|>zb*z+lJoc8P=@;Of~TFDvu4i}%eKI|QzS)w$J0PkpF zb-aEsO{WE%Mkn=un5q~(-m?97XK+Ck`m_`SV~ zexn;4YSzF!Id5|~Hp!*$%r#SU%9K8XWVYwGa}Q3t#Fn-*n8aMaF5P=4Bt{O1RlNZ? zg$vdR7sJ+1s>OHeb7{FY-Irgm4-7La0a9auQ+b? zR{4@i?H=8#Hfcl}J-&7j6_C}k3j6NQR`mL(boP|XJZw%hh>po=G?qJe=V9njI%E3W-V-nyG!^#-JLQ+YYk&e* zKZ5u_j?TrAssI1uXNF0#E@VE9sVTS0tu$b-iw)(aWFWUixmTunY8JJjLF*{b2|1$jV36{l|9sGQ#Ytar`6+3 zK!h`;;O^yMsA@8R03FTR<#%qqx9j;c)*%DO8PK?ecU)ZKwJ~mW>%0DtpBDsdh^O7Pm6m7^D;_H9jsMPv zpq{>(S{i#4hw12q_9m(H*33Pstq!sy3p$u^NCYQ~rH@nOcZ4MAL#~n3^9MtA?hj(m zE2^8ETk3p~SH2(VU!fy$CUHb3i)%5^^lLfQ;_(g7Kr3F%Q5xH+VJdKie?RY*(ZwO? zuAnIRGh6;2@M~Uj^JY<`e=8{CeyOL;Io0N(RNA(blzl#tq&I}BC_ld_e_YWkMCEoy z44`*a^&>yO(3UE?4H{^FHtvb5`Opb{a6g9eL^RSAJlYI@!mBb58Z*4I-sbJR5|!dg zvYlWq!*+=>=KFUv@CnB%w-sk+gWI}MoH4Uv{9K?%CCHU{5F|w5pR^Fub`)xQ7T0@G zPV%`A;Wy3zv}ekbDBs}Sl4X<6B=zKid}_ybf5acAZJ5^B|I+aIg|7*LZ(a@T;LBIx zEgq&-P#?bkQiKmMR|_{lQ@WZW@b}I2q=c|;%T5D&)uPe$` zGwVLEbX4zFq$>@2d(_J~7YTObPB_iRNM~#&r91;>U*Iv`OFO9K@)rgxGl9gU$wh_F5h%C_f43m%wEh$zVQ#?=!$KJo>LG)Fnji*|KBL|>W9_$v0g>9 zn8h}i5xt@4?8NxYbkM56c6bvh^3|(Ld_R{u$Mbj>Xla~s^Oe^r$!nJ$w3)ggAGK_S z6X;X%i;Xg>!)X76c|C`REz8X`{rjYNEj8u3onH!n7AbB++peE1#CX|Cv(iuP*d*D^ z&p7QJm3PPo1NE`Fawo1{^rJ~5r`_$gZ=JmRL0am&tL6K|W=;YI>!Y06|IphnuA6hD z6U(oYZMyMh_@2z4uh(7}iUZKBh{d(?tT?=N+wh{53P}i`Hml>m>y&c!#E6fi@s%!I zr0Qy$}f9dD9BN%(!*-)vN8yk3fS%!ntr5=52TX>h0^52$JF&mCc~A?cC~9 z6@NXH@}YkRl>n<9Md=@ZHN5N8+x`AI5R=`AhkN$Nh@^ky$gQEi;zir4&7tOdZZpx3 z*PShPYaBgP6e$S(A}GSq_DYIm?yVQSqTsns^m zaEk}BwC+B$^>Dv)P_oBhjX&qwH9ou(|GqkCmrd^tb**Hj8ENF|Pl``;eLSNyR%8-Q zx-Snu7)x@mLqrFAfs!g0iJX_C?^md|>X?rTZcuW1r3h zZk!H&tr_4qo%i&0Upk zcAAG@KR=9^1rtPG>|>t*k{5t-1>r=u^4-n;t~4!8JzWQEy{im)_hT|bIsXHW71j+G z#51wUBcpe6X!H-{7}>1NlH2M3*vkKU9soTurjG+>GegCT%-X7;H{UpbOoy-ENOqB@ zzhC=D)a|iXcc{wh&0H??onPO{6|?4GAmQ4QuQ)!%lk|N(@gJIRQlH4DD60JO=0N%p z6A#GDs0l{bNFo%BW*lbdC>}zlU|Mz~%`wGOU+Od^S4G>Kf*>RoH)rqD*c*3GiyU{~ z+q8LY%_>7Ip#1rz==-79EmG~jxz&2#mI;*I%{FBfzV=GTnKM$5Tu_E1w1=!0b<6)1 zH2H=P0zK3+u_Di8KNJYRq2Hf=h%=e=$dO=owbc>}(!Glnkg9Bp-fzCcyyB6UzRpN5 z8Orvxx1T-F)g>LdtG^e0h@moAn?3WjIa>U)Ez+OKk7q4L+&SlR@JFc+ zhVHe`fB(>jgPav{5!T`%+lo_S7hB2?)B$iWLVSYpzMc19LRD0ru2|I;?`0I?MZ5c5 zpV?iPHtH#hzT`%weN?%@yb`LNiQv;dX9RF&o7NtwNKEqX#Ei> zuTOqH+n3)h-X~Ga#3~}e4wl@23TI3WRB)gIwzL6S4d}S#OnS(n z`ab-+F_mv(I_>k1VlVmuHo}k{E;4Aifzjb{3OigJe2TG2im@C(8xA~t+{T26$uGa|ORA1>d zGUPw1bB0GX=V8a=yw)7dg}+yl+``imL=^t%JGJcIUgm9)A6W@`eDsh1ny7eg*yx}+8sgnM5_9AH!P5cRKI*nkKS!quGP)wM`}1MG!dTk;G0g9lF=8s_==(-Bb60eIsln6omz@ZysEq25RB zI)v;0BH;V?%7=ys6eucXoiTJ?!FZuxi zHgua&NMHSq7D~I>HE0z%EkmD+Vvxi{$2Hum+adxssDMAWm;@4mL1&nYc_NHO&MMk zZ!G}WL=JC9SvY?4o?C(v^WMoZVPW;^(8#R@yT{j-V`}P0HAH%Zg_R_2HH92i3R}YQ z(8V_M{eq*D(HbyUAwa+E%grhx3_TPm@$*QU7ZeI*lV2AlCUuD@ZG4!caf>=&sgA|6 z<6{_^S?D+HHRk*xDg3uB1Qf=pvIDE*bq$52hbMC#WR}1dV=gSd`)p0C*dIByR))08XqtmYZ$1d@tq;( zFHrYO@-s#dh^QH!?ZFn)%}2MGIF;Ua@3DXHL_S6EE;6BoYp9lMkcETalrZa7sn8>F)qKLG^sMSuBb>S3ylMuJ8E#HL~9bd z=p!B#+|iXN8p9M^farRe5t3JCQ}71!v+cOgqcOo|Z?NdwMxUM?(5?LH?OE zv$6=e|1&xAm1(7Plk7Nm@i%fu=ydP2T6;LiUOqEp4zQrBIl_SU2vv|A9@&zfYOUwE zo!IVqer0FeaAUpjpkCvOjw?}&vdUO04wU4j_zGR2Hd_Z3W@zh4nNeoUGQ>l6lmd%SC9j06ol)xOY!?EIu-_iw zc(CQ)uh8XMkG33ToE3$~0M;0!!M^WI~zo~z1Yo7&be*CfdllJ_PZulY7oBv2l z9#=_q(e;q|+`-3{S+w?EEWB~K{APln=Y`-kR48Ai?Gesyt(*PmU|{}RyFh=DOd4}X z`QP$y%3Z@~)qt6+;{~Kla3or{&e@fHSuYY{c36gH7%A#9P9VQ#GZ1UEFx$VR`NXJ= zC&rAG^1NeT72p0{J&o=dwE(?Tv0>iJ4sB|i&mHcD@rT$+YKGzx@0Xno!t9p4`Nw1r zr#axa9uBA7f=aW%m&SC{@2lUXdtPVyU1x01)I0f(@2uRpm?>}7DwGt69-=j<*>vDEL>-g)bbj8ll zRBHTL7|#!`$e;Oz)n#QL-}~LyA}%&`0N(5#Ic*IDK`??~%rWEA0=C zFajI0F9`a1Mc1OTW+@%{zZ_Pyi244ldhQW!MlX}5OTZkA#d-9+&OuA!^=9Fz=aam{K-;KcK z+y^P)%u`WKF9k`c#mLwPL)2p?r_zrkv%;py@U^+CiTD0lN;`8(C*0nWhyG~v#ymuj zhGIxAm2JLWTRh}+|CP8{t#zuCU(L0BIRRjISw-khPUDR&^T%0;N*|Ab9@a>YoDF;7 zVpvJOzS(bG_aptjQuXr|1&^kfjoA!b72*eDnB1RYu==K z>Hje~BpbWV{2yS@=I121wETQt%U!Tb#bm5=Zg9@w&Ggg%0a7MrLTW0;oTvD&S08zl zanBa@?kM$w$d(qBB30x_2{USylp&hz=g;06xB@=GHl=(>rH_R_H3kSuke?? zkX<{JjVZhWr8;w|VP;k{L35aR2p5MpRTChAHb>fxTkPs}Y&hQ3+NYjo9y79(vsW=7 zV#&PC2TD2GhlGqFa9l4Wz)61JBDIf&Tf{81?;5v4t`Vu zt2pfS!0t@bl}P7zr~AN~DhVKt{L&vI;e(O$FH8b)$;ASF{MNv!E0}dufib+hxoDE| z3U>uKCymX3>;@IaBwZs!89USYzhABt7@I3XU}x(2CDpI#PKpBO$vCB^T-ucWUwnr| zPq+R)rMgG6k^hiyHWPR@=}F=Qv$3Wpe0%|Ll_txSXm8eAQ=%cz$?bWZvN<+G%ZWk}78f`fNs4AP%p49PTtvyG+s zO8Qh#sJ+HqC^^4l8uHK1*|yaepj64aG6U5FtS9k zjE-wUGFAQ|5*&Yl7D!~dFj!-_77Il$)XDjO$7USdQU7jCbu1ns*Pj89=TLFEXL1d* zEKc=+1?8%p^zN*SYGTC4%*x$$MF6YxpA9Gw{bvL`lf`)&)bu};_aKE>>LiGpu=LW_ zb6`lnM9Mn&0b9jL5)tgd@MaqcFTiDrnbK@>#=tKi2i1zmVJ(WQQ>dar5B81K6^WOA z-dbinJgkp9$3^2J_HkOP3WN!?YBxlIBN-&!Nr?zd6ZS77)#PMY4k zZ3&3(x>1&jJdhzoA7!;*WxW_wUv>s)4bY1w$|JNF0RER0X?fM3iRmajVtrmoBZ$qW zqo#XR_R#@mp;GX$i6enSY5Di0#TZq#sCLQ(5zBldTCXU7TVH!kW|d!p{hp(xBeoP- zVB~;XRv>iprXI}sr zYMn7X72)iCLj*yc1NZR<{wROAITvV`#x3EGTJbx?g~LTaAg`IhmS4&i%Jao5pSgq( zw-}I9ftVYF6(~}Xgb~D?b*#z?$*t}?3@u0mnx_d|$y30062c>@w#X%N$F@Zv3vZe! z;R8;?UW{`AEfQowS)X{qxm#J7YLN>YnY&a;NiiCXomX?QY zVfPSNR^fllGR;$Uf&eQAq;>UMAMWf*q3egbZ^hqtN$B7;Pr{eL{~h*Ea$#@WpLM!- zIj(eHa{$jw`W1u0?u|6PszfIANP$s@+R8!_@&Shwc`_m;P2@62Jzn3kajbM)=djzA zdb&yly!5^@8DwRJ;cHqVXoL)yO9W|8M>Z;RrXe8B_g=I%?}?f^O&&~s5jrNthiJFV zj<3e@0tr!r5kVJro-6~W*Q_*Y^TI< zK*xzduyex-%iH;9uH1nHLYC6Di8QCyYlh9+IMZS|W9yqE7PBh>ku?g!O46$EeR0G_&>f9?;i$!Gvd5 zha`pE$?J(QI(jawl#rDMvaUT7ht@jA5x3#aMKe|j`qWM!aSaN?zW|K#K>WJ3=8iI& zC}{zNKt2u{RTa#u%*%ko-GQCV0 zHSO+ zr4+LDm0+W{wW-r^vk=Q))H_b_u^hpDtFNHiP8wRwnllgf*62fVLYQ)MPQz2C_oj^q zc$9Nvb^J93U6JAA_F{XONU#~AI@(BwKML+#wXG6w zGnRGXX(+uGiu+Dl2Gyq2yFgtB1_!T@i7Sx9QI+ZvH&wv_2=P$TkpTm3oOmcm4L<@2 z0Q;05p#`6C=D~6dw6wKug8F|*nJY)19Qc?_%$o)Km;vgLyLi*F7fpe=`4oAV7j={H z)rr20Jy%6ySWY_>REJH9I5lJPgw)R4?OuU{V?J-oGBUD0t8eyssqB^*7V1DIK<&%r zj;ra?*QLBKx(5v8_<1CmBJ>)Fm-oyz^T&mNe@gxBQwk-R$u$}jRbZy(Zq+2s2G9Gi zTPi2_o9+NP!eSmXvl1>Vn5}>4Xa{750@m|K35jHjoE)L;0z$Sy^|INFUrp1v&B#&# zGCHk!?~ql>sAl_AXFDcGkZP&LLZHctqYc8NNS6a^g_UbChQv(AFoGzty2fb(H04ig zi@*`{p2r2fp@pL$a=@c6e}t5{!b}Pk^@e7@%7qFO|2eYvrLF~IAEn4MV#bnoZ`$XY z*rDCC((GCa!JL=)(nlk_7$W@J4nu!HAmbFfR^a=hsLZ0xK5xOyG042;$UD_@#4N5D z7^>GLue5q@i&wv%lo>N;&}PhfbbNvovUXdDw4?f%xx_&f;|%ayGZq`xNO1$R4yA7b zN_ZB6Bp0xc32QA3%fOrG4W}LPd~&lai}nt{sts$S%wN71&0Ca2E(L+lD)yZ3%+uK- zh{d+^6zB2?lufy%zo&=M%*RYyPah&ey2$X)M_Gvjdr+*tH+n8oU}Ml`&Yoa}<4w<@ zgZL@4Ngo(gT4qPx2*O;F-wLt0cAKnkl@UrYvjo&L%aUMDEid%|XfbD3VgRw1eCdJP z@H34gqA<*QJ3bT86{Y$Z} z5ayNY=GC**?5pyc6ryO@wStyfXwwlRe32&r!kwm7XQg7=jvjwqDPjjjEQDV?-AAJ| zny{PYBZ zOVFhpm>7TL(n(to%sXWQlP?~h@61d$Oe6Vr7fbzUN5hQzPWL$RZH7-|m}7 zV&Tp4Ew46fm9!l*vOk4ajR+*DuM9;cG?x5ljDPWmW2xgopvgRe{UkyunZ{lE)8T!_ zA9X`)!k073MdpRD8JDU9?5wgHKDTM6stj#_y%SFi0eqnAa`uchKdnRVP_s0fTb!x4 zUD0JY9U&7}qxhn+@thSsSGF1uOPtkPbc)VEP(EF{F|-%@ z9*$EtYbLD1&2jhqR!`$!VJ&k`Po6{m*A50a7Apj3#U$V#yH(~=$7x=ggZ0wvD3bt9 zL6yn?))`q}^I)3%vOe6^9)LDOeRiwI>v1Vnv@wAMnfR{I46>Tg(L2iD!qsfWL;>+1 zLy0j_QPlh%b009`;MITTb{e3KVAk?*igdw{5Pt!pSS&AHRBsW>-8~QbCC+;dOJpY! z@Fi;z~e-v35*%hu7%mEtx*AbU{-E+}VDx|tR`F1YH^qn76jwsC;e%k}l5kAIx(5v=T`-ItO*fMq0vUNH&sXBQ@kdX1pVPb)FH zOHGpws@F9uNp1RL^E$uZ1gv&2!3_IWKSXw{!B`b=a6>f{;hM7EHP$ByDf3B$n; zgcNFkBZQ5J1wTep(TrL1Br%9d&g!3canr`dF$x3~7im`dqHw$#&$vL@3rT|X3h0Db zLpmHis!OXm$vJ7f^{t z(81N6i1>QT?}_v0PAYQ?q*iWfgd~E_+sE$7U`HD>Dn6jkLYh@M`I{(d7JMXPu@>yF zPOh?9Szd(@2E_s!*26lwb3IjJJi7rq{eqfR_g9M7$D!mAhfLZZbN475<_ z4CQ>YOlV(*Kay2cCqvK|hnCQaoCXkMG&$i(@l2gN1?Y?oX7+Ba=X0b|ic?(f*KApscD+D+_$-^$M7tWuk}uu(6D4`0a#o~^Q*E)~jN}G@+YVdF5l#ZQa!9zTSy-m8;%s_o z#OwU9sB8tQ+@E~fDBk2X238G0Fc^DaCMFFz}cy~fL zOnNJ{Ph)q!SYB)m=?|_c<`K&eC^MUu0aNz(&;dbPKCmf$*!Y5)k75Upf+Py-T2Z|K z0CYf_I+m+Z#Y4rj!5kZpr;yo79y*f~HAtXGni^EcMA3`Ee8jf3c$BaSn->yd38i*G z@uucll}y;o2EW9}9I#3p8O|!VO;uJSzT|@E9@>3Y(siv#QiN@`zcQDp5^srQ2Gg4y zZA64N%I)v6x!m=fJpjUL5J}o*Y$5~+S>Zj(au^l^>r1$hZeIw1XzUiEL<(jku^rwA zUL_{vAYhoo2Am$wMX@cWUBvwuV6x5U(9B#0oL+OEwr7$obi(J{ zI<)8keD^b;)boRSB)n36JhOV`v&r9ZO@8rk*~>YyC>IX`SR)qqW+?(*zWO77VU{?h zJQ=NkNw*OYBIf&+38sEm5Z`qdp==r$j@Z*X`Cb7Lx%P$whGD zZ54gZ;e#bP!c~^)S;8WyZ?**iRYM`G+`@8tdhW0>tPpORupqdvaR8FPs3{NiAR<4+gN?MoQ2&16=| zAZ!sMLz`l6+Gs>r>o6&flvyR(zQ=m?9dilz0^yiWs*7G()ZhpXQ4J5vrZ%yz-5u?id7;yIF(jAfMYI%vPdY)6E=wXM z$K-c@B+u%A^*A66pa^AVo%~o_|Mmg~A=?i*C-X#magee)XK_(AK_6O&l$40iy|gci zfiC?2{;-DYXXk*%a{wxNjbq>ZSJID7-rRlUNk8Rd7g7l% zb|7R^y6xTmecilSKGL=4kD5zGR8&TLNJI)7#5%{NHdM6+fNh9+8Z|Ej6&4i{+A?aG z@`>h6hr3U)?@Rbgo=Q=?@5}rTH-i!mts0>OL*(#3n{-b75Ib;8ECq(*xFpB#$ZY>hWDo+Ad;pws@tdGa_7HBNdK@b8NPHI{)I3@b5VVuw&M^Vrl!pqGcM1 zs5BQv%!8u;6aG(&gfC^dxWFx1dH?u+;+I9grWHBs<8Ugo79s^$YZJ3u5u4NG*Rt7T zJ<0|;MtPx}t{4W|dn1_Jb|q{Xb;{1(>w9BNzdx7%_ccjOW5#6G&Q}{8Smp>FhmBrU z=S(uc_?dJbnevrFyU-jxNKw?Bshe`je!UMLJZ!T-oI(rVqP)z01#F2~3Ym1DP#^p= zMro)H-41B8i&VWk(z|3b={5mcT)(jSN~encGLG$c^+N%OSC;#e%5`%bL=+-rpU zNeeSIT2ZZ=J{w&w68S2zc?}HeS&0-ptvnt)3kN5&=cR20J??RK^uaZ?S1{#`p@`u~ zkWGfi62}UIZ`aapDUIokkYEjet;7((-6H;ln~;c{kk9!v5YQG_}D5?s%}hjG6nu21WiRfNnRvn~~Pcbpd2X7656 zd}GJkoy9e%gFvxK9Qy_qmT8kV~OEia{7fj=!t9ZR29{2VsJ;>3-QgA0GKlH>Fx>D!`=i3gG2Z`sap) zMCB`O$F2VXK@oPj-ZL6WaY`AvbhE8>=E&L9&YA&?=r8TLgwH``0S#`t*LRnB`pDJU zy8m}X`%reoRQ&zhgXh9@rT;E@~0HPxlWVris z6fMJ{BR--OgArlksgcEohp*i!M|`x$NHg_RX9L=%?W_HtzWfwzUb$8|tR@^Jw}RI> z^Ob~s{NjCBzOeKNc@j*_PFbXm|CX=~6r8R_gI7J#YHG5@U8awOmy8hul)8|}`2H-5 zH-@c$Y$wS?@P1U_Hj*)F)LrxOf4~8zG>XXP{p9)?5D;U}M0Y~L(S({Nsm<>3-L@2C zVX0YQSgZl{_z)_6^XXicy2)9!kQg2d%!I`zW=~mkz#ZHevSOY^rHU( z#p^lWa`YH?n(mUMtOl`4GVqy2`>CISoinWmXX>&1JhshvyBo1Hfm4YTY9GKC3f*qL z^Fx=l0Onw1bg#PT{8hR0QR5*(LDYt9;l{r9LxdkC${kCkDKK*Rr8E5ZSXY{uKu#dE z9;eQZj~7|enD(cR(EGQq63taTVnvQv*=kJsa{;mCwNk%Pr?hWv|Dqn*M`}ZB-(gJ? zO)NdgnU&c^D`j(jpM>M@4kX%Z&+D@nuXo;cJSVf1=ds?lu+!F~m4X%cMem-#-{9U1 zxDXmF!ZTEX(#NPY^FNKWsbsl<3JA~YrAb4mnk!Cau);t6`SU{rEqusc4Q4FB^a@#> zR}pzYQ~ixzb6EGg>K*ejW}(vEIcHS_RdjYvN7JosORdLZ{l!Q7!TTlX70KzQ54LZ? zqY=kIE+xZncdCU_h^cV+v1@_2Tf2{X#dNG`-zX)g;_4En(0RLabp>U(#`#nwfUvx9aPBO*(YxowDvk@@VvNGcrA+rqSL{$aD zcJ+EKI$N^dkLn-2v#cGLf~}41o(*jkyvRHyZqTm!yIt4itbIQqdvsub_=I-k^8E7E zFs1E9>CFfYACz^pUIw2EM!o)X;f^@hSYD5i8ZB;*@Jrt5%>Xk{d}uiBYBu;DUbFwJ zL2&McbJViDTeW{Yk^G&Akj?Y4a;A5*dTI(Id3`HEyPCAAo4@X*q9-pFoqV+)!@K+) zq1)ij!6#JIV^yldvragV(WpD>@tb#Mm9l{2`Q8ecDKbOa! z1>s)DL_#8mQPdyh!qX}AFdktVvU%rA@aCFaGE?>0Ybg{vR79q+dM`gVd~b0R`0Kk1 zk4t)pUtW5+{8#pv3abL7?zF=X`DJTbXZx^U)QRHdltCLVWoFl~4Jq_x;21g@`C>Y- zB3e(e4E{9m66KAWF>VzEdQ^O#U*|oAu)EzrYvknObI~9C^G%MBx)Q;yhlq;Y)~t)> zaqwF82Z(RC-os=zLhWLog;A~6wR+8e^d8vs=GQ9AO}?$TYmBE1_!fw53~y5O|A$bMGw49!u-xCsfBqMVN9bw=qrzPQN&V ziws_p~mKz%3wD$pfFc)R& zuW>;Vsd~|@=t{0Jy0^Ck-SzI++TO>pdKbuHFy1Iu3h4aEs~4U8jWyHc-QSt`R;1cGY-tn!`~@AdvI^l!-Tv| zzXVI=kdn?F00RqUS`KbPtt02Y&xAERrBc^9H&4fe3zb>?N&LqJOzio;yV!i_u5Wp@7og zS69P&VDuC!&0@w7nv-;R|DFQO#9wXZaAEK6P5s&~n>$Q0ZOB&LsbS=(ycQ#cZV7i% zdSj~D^%l?zzwX0@po!~b2?J?zZ^BT(8ba-e*opjm+lvTipUr(i%wTX#{nr`xl zZ1#2`dZ1UwyMFcfZVdfwx<;0rO*tZ$OyQ9rQm+N)VT6;b|lZ<3Er$_Nb= z>!%VfR8#Z*o54vfB%xLYOjpi6a=ZHu>8$fe6b}8F;klCb$^NYT&r>O{-MbneoEO@` zoBEDBj9$2oT#$bVfLZrO$j`>HJ4t_LNb}bYwQEJy)|!Q@1YSw9bd1%70ioj6M(@3- zv%e0%cx!*KYr`|3!CgpU@4`O6_taAh1nAC>j4GzyM67?H2t75162`?*ewIYu*14!s z)j5nnKH?jn&&n)w6*qEteORutN|Z>{oWM0uW-JBoEgl@*p#df#J}}1+7SHz8V+Z;S zDMb#+B1Oh(jZ(C<3^JnOm2)5-ack z&lDO*zQ$^;K@&4J*7z!3BiEa@@k#Ryrc6rY4BOz8%+H(`C!YUvDZ^WvCI^XG+!XzN zs+RqpS9RKWJQ2vI+v*t1xbKjEg|0iwmP}C0u0EKWwjUOIebl1K ziw|$btV`xT^V}Uc{Z266mUTSdR~sxClC9|+-{YQmP#>0B8dZmp(Trjw#t&ClfBF#n zjT9}f8~t$9M31+=qY^Q4d#p^Oy-?pUN6wFiV3uGfEn&iMY#h)1`u*sX9Ae*KzZkcZ zv!nQA+%6h(`&mMpDjK|hMw;2%+?M{>BpXuv>K?${v?$aG0HxB6)G4=Z!NiD)FP^bh@fz2lG8wga<~41+ z`?;g${V)WuqC@!arWw{YCaUeaD%8S@@CAL!RNW7oSKoW?|8!a8nPX(P);hCTD1SnBH%9~t5Zp4+bP&N>QKCIwBPwEFW~TG8XQ4b6kMyS zCy&x4CNwI$)?v_vfk(H!le5#wY5xskiu0TEmA9XW_kCW~Khk;9L-xFy+`h4<13bHM zBco8;4#Cvp*Dat7{Ep}MgPqD9?_wWr`{dmn8HxYW%DMWqR6EKh$ZjNNqN0zes+zQI zJvwQW4K_7QI7coOcK-8p!!ZS&`I(Sy6V;|q3M=WumgR`cgm@|N)$Oboj2{>L5=$E% zLas8FB@;{W|NBu4@A_BZGXGunmAo&ZF53ZR;-nw7$wc+!sMcv+$fPa>-U!GNcg%r;~L2=^zkLO}9x9 z=1`n!k#0%}K&2cvNgV z{riPfWpU2rVP-Q{oYy&NfA(StI4}N1@RP5oevv~I79d7g!YiDV7#txf?eI2VW7(!x zn4(h12Kdeuv*#lkZGE+Rf1Nxh{%fY`lW_@R*Dg)WIpsq$$T8UE>80G#7wrq{-oVfa zTW$>Ym2WZrw;*CUem^W6{r@VPOKXu9dM?Y_S!~N~9U_8bzeINvgLa3E$WXnVFE2Yy zT#A5sY5G`qWMEbrDiaK=wP2>1SQdDjbZK23g1;JJXmfK8u$+`A8&dnl#YXhU!2S`M zOc`q|)K#GK=l&vZ>302&tu6cB2zl$`7%!xI)y8b-e~NgJ@RzWXukT3cXg^Rs_{l9F z75;;0dc4~G@$QM0^wJllx{xS}=lmJUn9-5@X_fD2+8|hdZr9K80ee+KLC$@-H+fTZ zj(gQ!R61>cZUC#v+hAymiCAnWz%w7}KE#;eI1W`jX6M##ohnH1 zABsb`pQpc%e|=u&7dmDWRbbsG9YK4Du=;q}JwfU3xzm4}UsAuHCV6Z7?~$qXb6<$_^Yr^c_LS{a3a%$`n)`qtzUnKIa6w=?X9z ziEL^Kq@mdw?6xWv3gA3of=7cJY7kx&YEt>Xrbu)x^9C^Qa;s^-l9o)JUIv_P-qGC5 zF+;A>ooaN5eVE&bY5#nhTQaw(vXe@~{COiyl;a{J&UgabF!L`lHRp;!%8&(9TZNlH z<6~?Qk(Ot9Y+C%Dxyjh3Yd&>e?={;hoRQeE`_dDVk#uQR*QUzU^pT^V=WPrwvgDoZgh~5vMn7d?JBzV6co{W=WTi<{*DP|K^LMPB5Qv zun~?nbD>8w5o81i_#NYx4V!15co&xXLo70gGG%FGF{y%4kh?_H%Y=bnw_!+RsVMG5 zf6-B|3XpNX{35YDG7W6*RJ!(i_t@O?f6h;R*WH8k+za^?8lmtm_;F~WVeT+a$b5C@ z-{1FnUp!J8)`oRlQ=)H&cnw1wLGgK5xnnxHL5`4}UW^T~E+H!p-+ywT?O>{Fs3JcW zyIid><7B-2>Z{x3zC*2A)_>+~QJ+Ve$p<##eycOU;oST2Hd#0`TM~|#tG$s=VqX4e zgTzefllVn{$3j-rFf={2zI58_f(MOhqnGgh2gr>+D)~PvoMC3qh@>1!t~5OiLRSA- z-&d&Ok!1*>$YrHpnsh^yr(NjsQ2)JmR4K~gbyYKBSc0hyLVwebT#{}q+WD28v0=MG z)2H?2YFsIG++8L;Px!16P!T3xuTT?sLpHPK;#aBiXk$oG;CU#VzI}GnV)p=D2qP0q)N@3vU`O z(wr0+ScUwLovMF+`B<6v$4Dopqe*~CI|OS#%X+RyD;mDOdEfYjjXC33{J6YRl-m(- zeJ9@+{qSBZx@u-CcFx(%BYm;XDk~F*D}CII#!h{4T&feUzTNXjF-K6_GPpe?R5ZV1 zJm}6$5HxoyT*&XGo=6YB)^3~X&vCl7ta+U*f_*uyAMrpInShy$gnNaT^?Tg%cqrdz za_s13FNM2DjGMetR-8#SMFTa^IQ*ECk7jQ`X}l6TgK;de{4!@1bLYXD^xA@Pktz44 zy6b`TSF$D))uWTptUYV`s?U$KIcYZjJTDcmu#LqT@-9=E#j*nfVXD0c|IT|# z9bZOuc7T)|t1O~@+V$bLu~x#9tdn~d2QvnLX2bb{Z^zMaBp0FaCXPzzspuP=sZ-N=^(LrEj;kkjQ`k2g|JbSEGwsAukT|UX4#o z)AW)F-Esr{K>CttEGWrF-o+lL-n+J=Y(zhM0R8VY()|q(^^EtFn?LTON$E=anixeY zE)>f+s3;Jzr-S|9Z_`R{5^nx-adJc8RXM!r46w!v#_!xRCF~*!?37!P6}5y*oQaVr zZjNvOt9HtGC7-*_zh_aLBZRf}w^Rh^GD;d4UZk=W#S^qJ|Kp>Xr7sDUooiPf1op#B z|84t_%F!2AI)eF~`3Aq45pf10uDedt>kkdJ&D8N{^Q7yj-<=z(Yqv*2d$zEK}@yy(-I z-tAD(tqYeCR(h<+gi#`@ZvqoJw2fe9{5@9UkWE8`V}QV$iBRo%ytakk1TvHio4J(9IteuI9*B1YJx!z)0&4ANFWx%qsQqVE%VIqL5#HZ*2Vm_czX;*^50Iw=M&?HTSAr$z( zi84unByj`jHj~%0!2qBXgV_n!F50hNQ}4K}FOHFC#nhrwa6VG~ZYza;{p9|Ih}#(S zM@3+f2F2P87NM6oZ_EPFwJ590BMRiSoIU-A=QYY2hTmYO>W&pqL>q=&B`+e!fw(WAbj2>Asdr^AKB{1Ov_rbVAQoV4*C*OsUsC2U3r z5T)eQ0DqZ#q-LrhBnET<1k;?9n$C^cP0&06YkgM?kFasC9-2A}KlVl~M$Q8PR(MWw z=AtNIU9}NTe^ztLMnkiNc2DfLA&2>doJXp;O|dyat&u_B8@R7he0 zXBHJJJ5j1RzlrFP_C7#%qA#=h&m*bB;4J=5f=&?m9acnGfM`s=m_4@wt&lrrX)!{Ug8Oxz#Yq9jzSccJJOZL(t z**YR&kY#LxP@QRpP^vMeV;NMIvZff+3@RfOSuz@8V(j~Ne$V;+=elqipXGV(=f2VKQP8?&hqe5Nm&i87Tgt$y16!=m{ zlb?d-mv}V zs&uI;Cv*Z#*o)QLqJ93R3C4H0a|x1*Yamu=Pe$e4`$lS1Pi)aBzJ-q?#`FR`^Emsv z6;Qg^0wad78BiP53Qv0;mX(6lj+7WJDJXxaolx0B_DObFZ&;qn0|?5ZEmn{_(Gw^% zt5yEDk%Vt^Pkeu3Aw4ACD@hTf=e)Ok>ojXT4Po|0@l~;jwG<%ELcxxq_$9O9dj@0Q z7Bfhp*64|;!MS|t!k1xW=?%G-bi*MY3F?e*tOJrm)Di0Ivz1$%7e^oLNg2|8Lrt*P z`iAY8Gl$bQVtS*TR>KxTK>>DYfV8_U;)g-iZWGt2p$_@Qo-S|NiJd2~t9q>kMbQM^wW!nLt<*?ig9Dl588!O5RdZV?#xIEo%b1;YROqw@5BoA$ zH{Xj&`w+yUIqO2ZAZDZ&7swDlHGG@`@vGE@;@cj(OnK5_t0_hm4p)jCt_YkSEV(NI zo2uYFbTqG_p{yI4G@8~vc$jzP5J?}Auv1ae6yBU|LQbY6s5*J2?sC^0&=dA7KW7D8 zjnqUTW`Wp7nIUw#dfqdvuY7UCb$t)5W{5vN0hAfbrOL0L(QXjhF-_b;NVC~qm%yGC z*j>@b4JPqxtej(97CvP2e1HG~=CqrUnUt@_ES|zkhUit@Uuh%!cZtXyxrRCGfCAD77uQmL5kIfY z*u@(Ti;S4SRXXq~chCEQop#Mp^qLP#ie!a^qvbB1!`X}LB@QG-`YP4Uvfdx-!ANkx zeq4^1ZWFVVn3lh(vaxOA(v${AqLjA-yGKuJwzaXgnsQI(BAis))x*d!fPF7wIqipl z2yLM6XgN|F?Cw?BgJkl9?em|i^<}b(6dW6@_aw7s6Y-MU7Z7tYLvwP#KYa$vndwCM z49+pp!pn8v=q9xApZTixA)!Vaen5@T9B*V-!h)RlJQxtSz@#}WcK`F;(kTj2!q!{b zSSivwH9&1ZP~_xcp7X2GPJM%w;1;=DB3*DBXN$+L$gQmu{3VkX7^J3g_nPPy=jX{z zklLI%j)uf7djy=|;v!GFZ3zwnuJh&3UmAmKlu2BNf1%6ABGte`Gy&o@wNu*^NZmsH{l~oh0uc*l1=-BX^e}tr(RF(ht+E^AcsEqROXibtocQ|-c)@1Z??uu~5_LgL=W37WJQ z%q|b_8jAs&?`~bQ%eQXwcB*<_8QIAi^S6E!?5R|=#7;+{C1rWYie??Q(bgI096Y!~ z+=LGx>3yX)nss{U$y@%4<7ZlnM%q9avUViRGY$yp>Uq>sp6iWtahvuJ;gD~_VeQaR z4oR;MUNU?4&hh6N*_{?fn1!fzhWNs7hqf*eL&S;uWp_=a!_1Fhv|!(=QN1^C>m2!) zvCZ?%Tn`$7B@bzQY>E*DRDm@~r!AALy;0m)Ak1dWN%>*NU{o)wE1BvyX7SRnRgv#Z zrfPy*A*u!bCvLlWsSp-JiF@6x+EU^X8NLFflfJZ&n2e<#kCm^lH(rC76RelmzhOYLB{b%Ax~J|;+l(1r-RYd5_3Xj ziGwkgBuitMSa44zA(xi>(V|{y0TJ9sY_s63vS^&jd z{Ok#iqm03QW(IAEtDK^9*!#-y=;>1?6$6%C#&qaCggP7_uSf##h*PS4VQN$xri8!q zs7z#Or4UdICD_JFO%{0RVNio97n$5WK9t#@E=^luj{W{Ev5KF`>3-7Ab;?+Tug;m= zg^uTO+P`(0EDF{>r;1YG3LF5-?qV&xSjc3%J>^ssjZs8$`?+@D^G|ibHVe%z9O{>i zdau!uhW3L9eVC^Gb~|&s6Wh#NqT%KryJtHx?iB>J%~sHHP1=z2*49Xrr!)m-R<}}g zkL4@JnAYSM!!9X0R0x*~oVK}ngG}=d(!QD65h-Ebm4Iu5;|t$V1E6)pc#rkFSGO)} zSizavk-t|LA}fz3AsjdWC+oROwf1*!!!ip{id(=e5Nof2a!EBT)r37Q#!}ior9CRX zxOLt=P7@}pKN$7V^X9D3@-vxNp=`0%C1(=Wzt@BUgr2ixVPL!wc&>vS3HRzCWp<8a z&5v)Fn>44RR!SsABFd!_t0s(!a^|LQNB!EheF`$5F!OzymI}>y>2fX{`xcr(gJPXj z9;Z78@2oe~({~hFhzVDpz!*ntgy+Le9J*xx`{X_V6K*zJq=}Gf7gf$7V{*sC zGKB)6)65Xdu%~BcX{998O}XLh2d~7j`*97Dh}8jmLwB27X< zo;8H1@b+|PGT>!Vtf|BkqM$n+kqSh%z6&#T6BHa)V6!kLrtUd0nAanp?-~3M+i89z z0B*?A#bO7nmI1PMNOt<>i42MbH{iIqxb7P$tT#@Jb!<~xv8OiBMc)DiPX)+cd1z1O z*ewPdPAgpC#1P;zpClsV8^(wkcKzZel+2sMl5Q)xuu#TBc5}{|- zHH{qPv1XP`le9dsQx30N{m&$!h%8Y&PIoIFi#V#H&ip8!Sewx+7kp6>DU$@Dg2FPp zoKGu1u<|xK$MM7gH^KP0?fo`9YpNzodJZ8Pswc3Nm&fP-bac?5ekeRvFU)&rM$dv0 zZ@2&AdBO#PMB9kH)(7E~MtbXD^{%V~SP zj6ghnlqbTTo;9PNA7n_Q5q-L8V+vAT%Wc23@`DhJF(7c+D24&PEhbdlU|P$7Qt%te z*u}zwM~`<-zOQv&=wTKVC9`Gj9?pO?V;5=V9dee-@^$NKPTOAx=~t zRcR>+9yN^sW|8%rCKo_`i}SC$k@~*@Ns3%C)606m5)#yIbT3UZ66n29PZh0vj-)5F zS#2}RFYkUR!;K9!+$3(g+}X0=1GWhi90;btg;V$OD!a|MUB5G>nz_ohnNN8)W`U57 zA%+^ggY2~Gsn(dA0K7#0U5JeYj7Q8{t%NkRh>;_91iy=f71h#!R`}JL6X-eYm``2+ zem5BHu#{V5kS$aJID_0^se9G`|GC^A+QYR=$m>Y=O|MhR?{^Nxo4+4K&kF}gnAOf* z>=-dv%CiQFS9k_WbN2&TSRmG{PEzTc^~0*$^o1{xDC zl(58h`O(~_6Pz+l*bq5XR?gO6xqQ@uQwB(|okS&s2dHcyvrvXE9}54ZHAS6CP99O% zjRY;!Y^-oHERkg@*Fu6E$6#$3^B0Gu2)#ZvdfdXpmOQALqwFwl)6ThKKbWx53pGAM zO&ZVJEM%^drlWVVa;7LzfOKHK-z80{t?s}35znXnL#8S1THSC-qUbdwX3(R|3pIvU z_@?1o5HpZ3x{!=jZgUjbdY(pkUG7%#0d%fgO-C0`gxZHJ`lng|tRUqe;Kz)iu)JYKcc9N^mC5+1_MhSn{MkmZ31Fq&Q0?fW}7H2Rb4)hH$z% zS&Tr2@G}To{j&gMg5>6FDJe?`Wzv9}xECVnnJ#A3(4y54C{=y) zLKUx_=OIJCQEgokGdp8E=kX9W_^L*~2v%T^z)DRmx>$~HHs;9Bry8~H#qyC1@v9F} zys*R`!RbY`7rt#km#93)43RZl0-%5xr&VHP8|dWl7TNod;2^SFt9^m_@LscJ7{&jt zuH;03^Md8qVfs+~agsbp=YsFRIo%{#1ctR9v*DbWTsMbrR?69MX$e}-!ZgGgtuQ3G zI1}JU-RK^Vzua`#n9w6HZ1sMfm@>9!5LYR*Yv#fs`mH(Ovcv!@z?|T8Vz11*g*ds` z7<7DA2G+NOP{H%7#F@i(;VDAqd3aUC7Kk?~TSdKi$DRMOmM$IapiK%oo`7C+S)eGWxrh zN7&+6u%*g1^XOK1Vr>u3U;aU-K4JSaS($kG&8^YAN}S%5@XQdxs2#}rp}4pvTc@hc zbR+YQ+{8={oH=f7p&~x{4n_uXN)l_5ry*W~cEqPfU(eV|k}kqI`jg5g2hGPB$7em2 z-;4F2ZU5(cqEF1oJv7@Ux>)-(>kI~)`gN1jC6$;(#x9HF)26x(EJ?^QK0-1qakXL3 z4$+Z8jE{fYq)kn^e3!U_G1rd&p{&yh!Ob1O{^((3O0}SiVHT@=*8K{xB8sMvv0wc^ zde!y|y1HR~kD=#lF4X}Cx4)as7)L1mQ}9GaO#!!t=nDVwDAoOeXz(P0Q4%PIxE@=F z)8hbv8Oo_0Y2MrGw8-(D#DTE8qW(8xoue#VoUvg)Wsr~nUL9p3m~A%NeyD1z9eL0V>x5MTniU@ zG(vB^n}9z7GHL?ADr6QY9Wk3R<)DU@L=?j*R?P0l3a+vFjP?!ZVyD$KTv`BBK}zDl z6G7c(o??0*<$_77A%+PD70?Msj7If!u|Jr~I?2?Wf1z-|gmZ)|=OqHzJ%6brJa~CV zVlcHCfh$!J|LVK>am|$Ac&+R+nY$(Dl)l{lHu_21PxpnjxL2Su{Lye^ zSK3vHH`&^H|3V@P6W@)or^9B-mm#)SpkO z1amzE-DG|zAv;csx2I&J{;|9K~@D|M9f$4@9EVS*qGkrM$>V95}L-?{Up=mw9g)>4yPP+1*^#M`~e73Ly?R zxysCd{im|poFe|A#L4#bB?`I=2swk)9MboCPO%#DDNMT5NKKWvJKmWfptls8WC0I! zQ>5}?Ao09z>U~PZ`reirIS8{jE4bTfJ?4K}-w@ID+m6C%FWldAE%)|ojb>8_Y>S<2 zv6g5R%ft!`q#6Rz7$>8rzMje%WVf>Y$###fjG{Q$c8odf+-+^lj>lJa*YP7KSj$4P zQ+Duc@ESK_jX*Er{K9Q0TPAy$40PGHR?S1L{tk6@m|rZ#)XOsx9#Wvkhy3x6q=b41 zXfDiic~Q>}G(T29(Skk<)4*((`v385@ptK6!v2V(FngzlK%m|0p#dsS_%n%!wmpcT z*5vo%&}ZM>b>>GF;9CLLueIp?|)}Tz5;ROU&w9Ly{OnA z?0)G}*c4qqs%=%^_TsSbDJXfoEF!Uez%nHM?K8t2uh91^GaO~Du?=*BwzcHTC31!7 zc=UP{#$i<8Vj=gWN{5<5p#2M_W4FZ&Lfeh*^zBWoOVXFcvy=dX`OEu^hy%}3@bKuI zaXcFjw!-p(9C?Qg;k2u#5PfryGrHj$e|G;rjCa?oZ!5dUNUAGcP~;C-jY$!KjkqBH z{Z@d;o{VLLtgXv~Lnj63KA~$ePW|e3r6+jk1i50g&!9r+ zuOHv7m2N_IrDt(r)Q60Td0vd0{$Kh=()Hkxs>e92%TE?4g^-nuOnjRi<6z1i%&c8y zDi7Niud4st)54Sq(Gso#oD5vGi+Nss$d~$MzUByD<5wYa+M2jKB!3-d=45YT!qFG zBAaTJUC#bld;Q)g=>YGH&`~!}r@=lAbZ?cb9W^cQ*zE#KwCU#uoTnO*OXZ9sKi}<> zB$j{Z=?z7zf4pv z%zL@Yonxz!OFN?eh2m1pvt!O=T&w={zr5MPC4kH5nJeGFonu?xa=xI={A~y_;ng1r zw#)r_JAb}T_|*N&aO*rDq++tpd2E_>KWIx^d2`}lXcs&Au)We(&p5-EMI#*zvtrmd zW6lBBXGvy{oH$_mTxUM8U9;A6@<0~qpj5O^=}X}dVK4%()ZkDU(I_&w{p6}a=p$`& zTmGiz^kno-nc>>suD4ZxdUa587oDR*g!8E>)ipPI4-H11$pXC2bq8V5TC5v*+hRvGkg(gAOhDNTwlB#9qb})#k!?&^_^Iw zCt4SMOy_Ejlgc-zgdHh!c1jhk31lg|-=r*<1 z^9PvBz)X*Qn^p%;@Z(>pUsh5KTHh?**VIiHTj*UE*WsD6d;H^Q8|XadQhD;u(Zlg- zLnWdxv~BbZG_g?LP_-4E$mvk1-*9UgK`A)AyK$-?T|nUD%m_OQOXq_c)2MD6n^asv z&JX)rvETSgt^Z|NqzoAro1#alE`y*i>3CAz*Go`+mKHa1g|+gGZgUW>A^A>v4u)i# zcj`1EOa|Cls$XgjJ0PSQL=!SD{eI~0TYF?0QinFqiKRRKV)zBkHn0&D+s1CEn9px$ zeUCpI2w_ni`@Gx;=b=S{!-=w_eZz0pq$MA8;^AFH>6tGf zI2iAg4%!2jCa@i1pS7#$tu|Cv?t6Km>ZNjr`RBQ|Ulsi^{kOkVW^=q)okK#T;O=nX zi9`OytL2sWgBcIde2^}xQ&4^9)=$(!I6Qd=H$|J9y8Sbwup=oM@w6Z7E@wOZvW{}* zOwwV~?&IlkMmyCf-%b8tX)0&Q+HgaN;XF5gkygVz^k>qAV`6HQH(`{zGFQ@XqT!0V zMk` zD?grJ*LzcYSmE=2EgPtk4;X=Le5r);d0Fg4&k-cg zUV3c$G3a&(*3JjM_O>)NFQ}(^CDlaNaKWH$LaCbgMKsjFQr{MoK$ZONBK)1;&(k%v zq9(rK${t@H|4GMmT8=$b3x-7E^n^=gC6YOYZO4v0ki~Lv8wqLM^(FFcGA~C%qm+`T zmWq!aym-ldB<1f9p7K|%L+}_XYRlO5x8^X>?{-}|^GT2qZ|Cel)bU>!GvU_4UUMC! zMsh6!F6fUx`zh+dn0vs_n>YW3&XoX=NDMm04gJ?PQ}xRs59SB{6H2a&-=WRrS|*w}#JN&UNT`LFpG>TzwV zi)lbfM#$MV-hbVO(i>-Q&8xK|J7wjTAfI)&3m-$d`+<4Ds~tH-uPdk)JM=5qW!k>9oWv)vWc`gx@hGji}eo5>0N_$mes)i&M z%9}HF;f2>ea2%Q11^1r>#pAE{9xo}VtNP|9&5~*5IPUn`xy#+_k!6Dxj)S$bU=p(U zxH$c^`uOF!;$uqjLFPx83Xe4P>-+WhF^jZEMusj&YxHa_6)b$w*Q<>*;#^_&6o%vP zpkxo6)ceq)rM?&2EZo*PaXLp0B^!d3B=j&kqd67DhkwK+7F=$zlU8LLF6a{_ujUur z5<`me;gzdOJJsbDiW`JKJQ>n_^_UpRTEey3u&nmBNoJw9<@d8+E#uu2Xc5mc10Kp~ zUyYwIjng{$vG&HnBDXsWHmr%kM9UIGi5k3Z-8v=eeRxgAh11@B<+p!^A4 zFiKRZYS=6`jF4M_qQ1vjN$e5`laPH^tL)QrDK5^S(9@#0siGOPj&>qr(HyS}XF zpi2MH8d|R&_x;TEOTQfUDrea!S)e-YaXNJq#+zW{`exv68=)%opdFkEKSd9JbZQab zs@GYq7cC1xC{)J8-Hg$SNxNL2Ik;+N+tHZuru^lDz}@v{S)5{qbQ89{Z(Oh@n_K_> zG$i(DgT#cC9s$6R54OcfX7bV^7(clkQ;*)GDfX&oHfBj6#Q#2BcIJ8EYS5W9354^| z*J|=lDMU8gHmHTdso2R*3vBkveqHtvHWM}F{QidOJ8K)etCT3`_(}7bFB)B`_bx0~ zU-vHhJrFX;Xg9rTMf??Oa4b)PZknu^x2b>e@lG8L2Vn@pE3SecX#P%Bs48;uV0U4VHzSBS)Z`6DLqQo zSBNSH`*98PvrEsi#M#yx@-2o$SoT=?Wwi-UI3=iA*wtd}_f6TEvfp7;Of ze(ND&m<3VlUTll^4h*^c;A-f!VOeTcuc@@y|h-e0lBUUHq}ldjmaHGg5p^YY6|lQg%O*o7^(vi?oV6Kyf#F2ztuhWMX?%0_e%TTiMphbYbtx8S0 zj$Ow`q)<9qG;(E%VwPQaT~xoi^>SPK`n3_ABc1)2)a^O zIP-=b!iBvZQab$ zX(baSNI}p1`;*;mpX)OI#yrjR+tesBKTOa5qpkA6z~~(oMns>Nv7?+#6#t8!7p4w# zQG7Hu#M(pFClhAO54zdx)^E`;yKoSm^4DfD7D4q`6KuF06JH+KPx7|LB2{X_r%tf)07ROOHZd z`eFL&=P|_!gb^4vM#vA6DqcxTlk1SEI$r_AtA(N>q@RxB`J%9;EiHynu69kY&hHwc2EeJxE0w)OMGUeh zVd$;K-bu%lg)w(83De&-7KBc1=iNoj=9FXLG&!b%_UmVAGpuHIJlM6{1b8)WtbIdP zBE|8r@tl<-qP#G6@rS(jy+8HEkBR@fMf07g6kf5s&ay09@9dxNY2tIych_g%*&3Yk0(ngPZ`B0{6~zxMPIhWc+Q@4-&KlZq>E4iiKX;ya|QE1>w3CkN~{(i6XRp zzLB*;rFvfvF(mHf>bx(RKR-ihjg(&nF{j0@hN0ii?o3RM<5AsjoXnK5Z zG0c_+4O<0}C?TyP&!um090T^g?F4zIHbzUziSj?4sCF*)Hf{XDfhS3qBmu9q0^tx&U>5@XM*1?h2|M;%vS!(%O zZzX$X5I^)Og_p1g zZmr)n=4D21FW)%*?iER`b5dbv@}9oP4ro4S$MmuPh2(AI{drTrOC9R$xtaVKc++Ua z_?rtw#qBDWq;B3QHEb)@*EgHRRemj#x|FGPzAfG6(6`)$e7G_-uutp9rTbq6o@8RO zswhu;<$qtkJ6!id-)DB>$7-T5oTBTUox$qI+%!Xk^d`g4T|Ql#^OtpXA05h0UEkXm zsu|kQG_17!?CT3}JZ2F&_x?B^|?}$cvIl(ZE@^ZlK zuPc)M2M=Z3Zs(Ie8gImlG+Y;6`t;yx)Yq$Fw9MWOxR65Y^WsZAQPeyXYw(mae&O56 z2lJM>qE4D;w?g#j%RilK#-nzwc*8&#M7?|21-pC9Yl_KBLAT=N$EdPoOSn?b5>xxe zFL541qtICR^=o?>nDXs~DYrSpJK_&qZ@k=aUQPR!hwDTp^~2ruGCkaI=XuP?!6#~> z8T~%xS6W_k_h0{G;iqfokMlKsYGTHO{x29=10O}P<0Ij-EFQfcN1)^ee0~4o-sS)wf?Ut8yK3?^HX{F*$VWQ&{P;6XVzbHj_P)W@rq^2S~E+-bk&h$yvd2iszVfxNHv z-f3jd1*;$$Vamh5%X%LYv;EpJ|1Lf<_5%m)yglB&^&Uc~gc9eew#D<6NO%hBJ@6AW zFBQFl>evom|36@qMALyt_8e;hs8X(?2Dbp*e&8Ps^}L>H2*v-C`a)&-Xye4wDg0gr z$c`zL><@ZFRJKKEOabj#MkPJhJO@l`MuzP5SW6<$Ue*lxk;nFDl^MgSgu980_gYa( zZ_}zFXNl6Gu<0m;V;$ng#J?U7TP!n=414NLn>dQh*Tu-b)lxJ+Z1TC^`w4d#?N`B& zx&|R9{blq=)RGqy@-99sX`hS%ag=%jfunBo|MX0MFnqZ1LP!;-8#b+Zr3gDKIKu^j z)>*sd0BcP4Q8P0nT0S>=$jUs|gbC>8st|4etuo`@cRprcb^$ylv}JzL(b$K)(GAXM zDVVs*W-xJTpN??}F%B;QgKOa5j4<8s1;1AU?!|;51W|+jEQ7{9rwybC{ms53>vdOj2SIUS%l&#mEl!45|Qdq2pwy5T_ov|ca&3P z`VdX>^<0cz;&K6R@3+}R;SL~U*0*of<i(8~|--6>omT%Ry@UqhB$ue(Et~kMs@8Sa(f~Ap6xi6#n6N4bHUJ8jg2b z$Y6uV=D|js_K6IR2fnyzASf?9?ixlH;BH}>p3Goo&=);ZS&+hU$KhZ@loSx}_yr^j z@KV(7oYrM|#&UsAHwl%PI7Md;B(qpfTP0TRb1{Eqj`O-iZfr4SL>aKY-m)W>pRcX&L{z= zJFjK2c7Xx;Fpx-L&!GJ9qh{sz@9kk@)S@^|32})@aYPf4mv9eRJvHm~2}WeB??@ji(FY%Rs)1@Y8=ece1eqInUbX+u ztbDJ#Tb>rj!(wU@PMpyHbGVMrtQ0s-pxmk1p+>WUA=`YfxEu-Kfk0mSCSBYA}bw`nGmyQR`8fJO6w{lDC5hjV;K-Xk{ z*qvYfV|;j*q;p9wW6oHK|DT#!sIoIF`kR2RZSW@owx$8WSS2+NO*m5QotPc@k=OCg zu5hw4(0hKtBM{e`o$*ubF9>E|cSb~Va`r%I{rW5Wf%BfSCWLMO`V2F##8eZ9q9|@t zA*9jCyP?PL0jqU)a(yQP3!9Tb)3Mw_ucP6FyqHKYYxG7O_F^Sse@ zSNq+E-4<7noKc~rNV>dC!JgW(7|-~uSz7G#1`9_#zqSYHBASP@bhhgF!KjrDX;+QF zgs{+Ks}5?9A3nwM=BWVRe#-}hM!Hnjp;w->bX|8#xJM4sC&$BLJ}SA$1L$!*eMXc!$h&u=L4q|M5J=%<)q}e_ZI>`jdS^Ci zBt)CMvNP_jKuFawsQ_tj^_aIM(E7qNQokaR7r}t5ZPq~x2s?_5?$*}U?WPt4l(+bm zcEZzhJk5gUD>rq9gMsm>L7u*;a);F2oaJ}9#T)v|NAfDieX8+q)qbdA{ckzy8Ky4 zZzqZ&*8lO{zmQas9B_qamJf+0RQKI=&X<1jmKuLbkJ6>r#e-sEyh*!XLVH3?e45<- z777EC0L%M7PMR_$nEcL)yGtmC}DItW;aPOYY;GABF$4!f(DYkrIki^DppqU zfGZllb@}y%2uMi*RG;Vvz`t~J3nNEbpi|3a*9 zm5h}WlF2|6873|PYg{o}g8#QR$fR30^9P%%HMw&_oE~N5qF2k|kPs_$H>ohRPPIy9XCocG$qJhl4$#nI zSJ4_q2*4rc$T#)83HOT7(1lE^}sjAivy# z3nxbuRUU}H{3etB4L(u`nHZVa%TBBEk?^Mof#uJ0(;{RT8a+0#owp|O5^+#1dG`V!uxbih(HNvG&wa2t5jlTFq$v ziEQpi1A)DSd2b?Xf|5Tabhs*2Z%_;QP!kqGG(`(qQ=R5{BsM|&tgEOM*TZ1yj0(T9 zc|g~^CAWE04_pq`DsT$u<#xn{AOcSDVNo)a#zy)V6}2v!2%!fA%p?CPLwxw+K$ybI z!t%M^yO5ykqFWO9N27!jy+6M!-h(N#=Debqrom9kf}S7q%~qrNX7n(8&LCZAU|%H9 z+oTM*jbl3vw$Af<*rwm{gCNcO3D~_MgK-(uBrR;lgxF)G!U#UG%&EpnNk_mbCO>k- zT}ALt&B`6511hu`l=eGmLNiAJW$A1Z7ZZ0%)z#aLX*xeLsfm~Ym@*KTqtpwfT?3?l zMnn+_1|uYQO7ItVT>ph~=5G1M*Ubv;)FQ!*H0YfpT+(o8Nn?xLn;gP&+y^JX)A2=n z-@K+MDiSt!T$xZMupls&RvGZ*Dt=;Llet5HcamH5GKayMow8S3{nZqS+*owR%Bk|o z_=y}~4x3tGh?$swNe}67Qyx~L_mVeX&VZg`nH3y`EIcPE$q#Z<%DEU2n+Jv-d02UmKY?0u;#4e>cRzoY*))Yy6i$xxmPstiKmFmE8$>Oj`xZ z>ActUTttl+WTP}|KnqeUE^gseMNE;EyL#`C8a6@fRB6K>ExeoS4Lq=TR2a}EXcK5Z z=0z{?yB8xDp*EHVxE5pakOz213hp%o2?Q928xBZPR_b7QZhSAW5QB1J&Ka{)cnXCxB$7T7!$AafOTkiE)lKAod7N@<&hpMu z`rxZbCI(DH5g*gwPuDAVmjC?ir=uQiFP;y%bSxn!;MWifTUrGVkZ79p#v;IUi(g95 z;YA>~Wd7jE0Iy;UwNMKSPl7a>Tn3NcQWBT@M8R!#L7`DzZ7Q2_T6ie4+2}_mi5QL@ zn-e>X=+)$+9pQ2)KB8Wb;Y_G+^f2UkKWb(nBEo>lRJNCgZ5}e31lc-I?W5QPP-GZE zVXPf*l77r+bb;cD(6k;nT@%*NMWBq@FqQab)j4Q+Ht~$IE_^243b$SI-h#V{zt<1+ z>%0<2=s+0ft%+1-Mk*U;RM56@!#>w!DL>UQ%1DK$bP7^A)bP^`EIbsF(y+PYK1z<$ z;L)aV@*ELls6loi&}=4v4={Ttegb2f-mG;!64%U<&xeK9E9Rji})t7;(LU?8YE#p0qCzK^N3GpvLx4J4lKoTXx<0>soj3hlp>l_fRCZv<&jH${_CW zW+O*nX@5*Mh8TvI6rWLO3=ECKy)Ch{ZibXtp8P(u-ZZf+djFVQp8!9jI4f%d3hfTk zZ$H(LC?pgk8429G0eKg%Wcfg;tc-DZyD=g<}{!eXdce$XJ zhZGLxm0&49xh1_GrSY94Jr}X?mh)6zSXxkn<-pA&9!*h7jj)scA+o!cM8ifvD9g?| zkFUlo!};U6_Do0_uSI;Ik$*$bCYo?hYQ~Vqi}*o8Gn0rVQ z&bS83_oNJa#CL9xCS+p4MKsxeL9I8#DVAorQ3|Rks2l~0;m;M%fgwL1{A)7JR|mUl zr|w3ond@>FHe4doVSz+K{}1}UIw2QCEaftitHMA$wzUG)bBF|L@%zDjav*{t8F zcsYj`kX1E-yv3;CtcDGwPqQSWfvmGwwHb+@y zOQMJ_N%XyG>P^>cK#7JWoq{Zh%Nz^Na*0H9pwEVjtcB~9AL|Z`qvJ~&%yIm#R8wut zTdsxufQ4kUy%i*R>fQB<5>awyUXN1N4hTR&p#C%LI6Q$_s6e_P$j(H$?|Y^s;u8%v zvhI|GaE6S4E%@%~5c#eAanXqXJj-*#ZuA)E8}03zBOcdKqUgx?5SEZ+eZ>;4LQJ;$ zDEY^XOOG0$?RGUC2DT?op>=_oloufz_u3I|d<2d}sLO)nkV$NTXTFA_4X4My@KDp3 z2NXDM_MN%m`mB)hH~tYrjif9UQd`5fePJk%v?hbUnxRf-+W5 z=+M?ma!YK(v4q0A(76G|J%$jj>@l)UbVlw4GA8l{_)}GP#)X)~9TlAM&BCQ&&eKlN zBmtCgNBsH|%C(lgwrEN(%_q`MHm=0l(aB~#3>0$+FQ=1!(##4|U`IU8%gqP);h?Ai zgc&J)E^CG5P_&dbgjw=o3`WQR=_ zeaLr@KxmDXU;)jH={x}0YIX`aqP1`|72su5jVvvaBKYvFovg3l5l&eCKeXxM%wJ z_oVv}I0!5k*qF!DWnKM%`p(wVoo6H*D4?p0_8lB_GaH`NbWixblNdh6-z<7ETeXoM zhZC%M7>|a{QhK*^dErJwdKAzd5+U*#OZ@IEO#OPix2}ZXct*>rnqYudkoTnaL?UM# zFD=z&F6vY3HBh*ITTS^0LEto={@c1z*0i7GKKd@B$+%Mx?)Zdal<99hc>%<1Nf6^S zSG24eBTN5DGk-%!;bSym_STAn{xa-n;ULIK^iu|b&?8au7 zXsP};esZ(gpZdc?@=>e>)*#8CN~x7mdTH0RAL)7Pm?S5Euj^H!h}Jy& ze(57Q^wRRu(-UWCaSMc6fJCO9WjnlTU3@rz|7&v4Dn2hQpvuD5`p*SUb|)blj^0#C zR&d5=Jox)1^cL181TzzbApfyF;xbirY8bP;ylTJu{oYM_$U`&6u=nSsGV6W3_1z9w zbs&1E-K1vQv=3UN4#)RZ>$N<4V4A{$7o%pmg~!BPi-WU5qD156VIlVteGVli)54nh z>ya-+Yk!|br~T9jK_WnG<l2Cn@Pr?Lf?hgLkG{TYlxc3*(W180eJ7{ zya`Yg-sMsxIOxp{$%6TR+Ah?KKE!S|I|SP{L@FNYG1TvF@Ck+?dV1wLo^6$u{FL4; zp)>r7qdZZqt9_8%Eewn;7>}QIcx?{vev#jb#-18bXuJwmQSKP7RPi>8ZDA19EP4}D zNnLzzll#&1-MMq36Q*+}F?XS|<4GUyqU46#CLMx^&bo>eHw^@X<1}ywmFO9fac@Ye zX>^JCJoLl(J8~VEGtgw;{iuTc_jx)t*tBetuz%za8U6!B9dN7Q1ZCF-`-m2Q6d!JQ z7$I(BmP>m6r`5gKN|m;DVo$=~$})Fz{e)J1{Y$&4J=Y)=DH zLqx`;u6eHSy`-b}c2^EJn2;s}0^!9Q#@Q0jSz#&Y*zeyMl5>OBzN|>q#u?YJ%(m5) z7lfkrs*gE#vKBMOoE0NNya5$6wzovJ(58R?{t;uzz0en@f0tYg&hI6c=~T`g?#UmVv%Y|b z!hab6xya@BpY~uk$oF@cq|8330~!k!DpE0_t>3>e*L~Eu+Zfz4Pb+ zxw9^NPh1*hBhq~bW}_$k17?D)Z)!^Q-MD_ z8$S2LCx8`^e(2E6<--cMkuaQsQbmr)yRriGF;Th_ID?vrV%y%?d+K4y!;iDAOpRmm z9C`-tibGyUs(sv4+ddK)A@}w{VwVzZ2>oj#i>9-6BIjm9jj@wR{hs1n0Q$XF-REA# za_OM&g0xrHtU@GoTb!YJDE#+_FOY_a#ezff7gu>pob`T1xzZ062&G_kRiD2oxE62C zp@`PtQFF^E{0U1A9(iA?GW^ij+u>*hJ^wO6nr@lCC32R#mNKPTmXXs6Ywh*zOO z>yb&<4yKFsS20|R_QZ9dGZfAEOw3wf;R~wdk^Nx+RQv}#3-zz}Uip;p)kFe%gf;e+ zEE5Cv)Xc5SEge3T+g0sp=iG_asBc7hEEL{3{Cy6SCpx}s3fE%VMIz-^l)bNg$btT=8g`>TV4)*#(tkamFiAk-R+}%!xipF5aq6g zI-o=^O8M^OPRLv7$xL6Z)NGdBex#=~D6*CT;6c`&c^vJ<0878x?n0d*RwHN>5%ECr z&5Lhudo&L`O#g2vdj(1~MzSqHfdcl;9)I@ETsVI^ zv6dXj`x~xNXKsA*sBzE}c*HCiTxmsZUtptOVqy|fATdmK)uKoyaq_Hpay~4Xg>VYr zao+FrHcWJcTh}W#e$4*I?q;Pucy5AIzxnwjyTkucoaofirTin$Vj{#Kk2>M zx+^WZdee3L#hc+-pB?Sh!f}4#Z*+8CmsOR0+h<)KmMH@J*8;OY;;gn)IVnGhsO$eg z!DxBiLGRwY=B-NwDs%M+MR2*k4E~o#=TViP6S=k>sPSb^u_utFF(~bV*LXZCZD9yn zy3WDqV3P3lhF?P76LYX)I+F2>F5nKv$A5lQb+1}#C>$g-baz+wOOUEo+~MRZPEw0X zoXoy^nnr6Bd@%BD-FvY8q&hxjVovMJ8BdQSGh;^~tiMabZ6Y^*ii!syEWk-mEBFOjOh0K8di&B<73y z-Eme+wt67b(2B6`lvtWgFyp-I=HK2!(+>>=nZ1FDSr;Vi_5rAHe!Up}@b6fwPHWX( zkJ_GD8}TIP%LfIOBkB$GdOXcSy&>~Y?;zmgosR?65a>~3dU^q#rxH`lgMeyIKeTt0-?h0OQ3bEo5S zm594UiakD*mlS0u?EB`v;c&9;aW=!$oE+GN^OSiWQ+Pwvq&N?Boh@V%1y}ti+IL!w zOK}2%T6}O7pJfc%R-zLTq|H0hpDW`VZr)HB)b=}+_n zsCIkeV`U4&*vbWpp-^6n(T&=d7g~QWN=Y?o*8sjy6(V*@;{-z8t-|U}ET^wOIQ!4Z z??IZ6lCE67gelT>qoaFy-)rVwOPrioA!iK7Rb!iJ0In3wVS-%R&#n&{u*+w=fnmG) zR)cmCfBk-76hDwd?O$fo4s3o^Jra|!*e`efb<$-bR5{KyuM#JoeLV7iy+yR$3PHM` z&rX!KSK61BIGtmE2EeHtTUM*;=R?A?&x)NEj?w4&y%nI4 zx22BnR~zMUV<^uD>m;oGKw=|7u=MwkEXUOUifIbcdbUqeYvW0`0JCGhJViY zO8ytK3O7vc{#3L)6};w}J12j>v5R1$XaXYD{?zH#ISYR(`HK1l-Dm0W`W$-(jtOI4 zCZzT&JaBo1n|C?B8ewW{Mf!exze!`~9HEJV!xtUmdCOH^VPy-aGisSEZ2--ci?w;} z>a2C@y%DRM?Y|BO9{}6al|j*Z<1t&`1J?VVk$(Siu&#(S0uNqUDI(G=|L5Lg#%G{| zD(+;50}|WElc*t@z~);vV=gQXq}1 z%Z5yzGvfD-j~0>-%S7A)RLZcerGW8-KROsxe&Id95v8H}m zzA9WnHkeYh-Yx3!QHN?1C~p;Buy%UFvA04Q%U|slanDGP!?M)hB}F$J4LNa?)Tn4O z?)f$k>wNz%G&2*X{a*MnhNfPl6;loERjd)@)kU8b!>4{A@dw_tLK-I$^2~snTAg}e z=)3AfQ&MlS;-+EBZtF}spZ=4 zVY|^<-kGj`8kKo(2B*ll<%+v8C}|;B+ng6d7vFSWmCsNPD>P=U2#V7UkFS;t|M6Qj zWLZxPdf$1X2{j#tja|WDSSP+*2{&6nLIQUa%QpwOI7dPE|{37x- zE9m*Bx9=YRWDfRLSzrsFfAO%3li7RllyWQdiHVAU&t5350m}`9IC~5)>MS(w<6x}5 zpE=`EL(saC6+SlQ?$-4>fBMDR8RnKu!)h!iT&J;HN4YwszV8)5=E~Vq<|EhM#PZsp z^$`zOU$2#gc0DNsI6-`t{5&KmtIzG`lXe=h63d9dF&$wssSnsO0ZS*JMmSkD%&oPI!9`p6eZ2)AJhu(CUc^ z&od^R?~HApylCdD>dE&%S%h`I*Fto<))m$}WPaiNq4N8Tx~0uK{T~%?xA~%;^&CCD z|8*cMJTiw2@6PqdlTE5tO)j3Ru6+Dp#_PA83jB{I{^+5vJIdbIZF$V942gZce~nJ% zRvto}>HU&UwfR!Mvt{VbcmWPXD{2(SSNQ%Nfe)M4ro8cb{BpJ40;lC1UiA0wxl0Sj zWIP|gy#prf9A>HbYA8dL;c3j`v-2B7R)oT{8BoA8sPR9b^oe$4Y6#eM8`Z^Ojxj7O zeHdFGQ~xUAlviIiEhwG2bTyf=X0Z5|wCXT(@`(m)$|DM_QkxLB*ys%VJeAGl|T3_@r|P|U9n#FdBFv9K!gg6h1YtE@W9@Csd9W5fQ&b;1(c3}(I;Fh=Xp z$K7QZ`hh}xj@CoI4N<7BXc6HFykq-<{d;3j!IO6qlE2oam=B5S({ypwnzae_$`m-V%YQ1OxvA zl1xtD0_lU|x>(`jR!EEKNs4%9NNes~$n3A=T!c#wpf13mY%O3gni{_{k@G53Y^b^KGLEb6Io-2Q+zD zK`l`Up0ML9Ytqs{)_rV*GCOjsBg{K@s&s6DRe3AP2KEqZ>Q0~E;5)!8I~3A zwEhC?+eD=`QQ$+iAqMEhc&Fthp848?Gx5O1A6$W~_h1ViQ-sa0-og-ew8B75vMU11 zU9+w3{5QW(L}S9)dbIH zwf=i@U?68rmh>b1m$sf2G)@D0lZn5*iY#j|;p`b?PjZkG-w*|l_o(yE?y_0Wc z=O{yO`DBu97EX?OP&vmT2Y;i|H)oFVa0g z)ZOC1%auLJy)S@d@Uk7B(?w>8@nAve#rYeV9w~pq3;y!n!(gork2HEGG7Tf048NRGwRj z)3{!(OicvmrEldwT2mUhvO+RFXc8>(0*Uf0(39I~VpyLK(IoL+IO|O5SV~$dp2HDE z3;sYdq0}OM)Z!0G02i{B6$(x1tR7oRvJ2l}gF$NBeTB>{HHo14l6d(OJ8s0kW>1)5SM9Z=OR zGmsv;J;R6^+S|&+AYpkGXPc?Ve9Cug)q?keZLmibG=Y4lRf{x z4f`NfA1#4yr`kZ%Oo%)=p)$UJ~&PFAvjZFNpkGP1`UBLrqqA240 z)rgEMpG#Hr{WE1~d5VZJc8-bAEl%^^G!3WzH$$ViRKc^v4t><$#08XnMNAtT+E&f~ z6LY@4$??(p_JP!2VeX(JX~&g31L%?G^z4qLXB?8^AQfvkLNyV?5P+i*z;@%C`GJKB zdm)?I3M<~gtXWr6iBvjtP!^~^SwyCV{!Z&cYjZZ(6D++5*#`FX6EZ2@x1FLcj}B!R z{R>qG9$;qX6PyK~Jwz$tp~S%{HS|%f3^v#sh&_6mQQg`K?G>sW->ZF3MG77cfU&sZ ziUceh1MQ8sZERI`_hw-;Wf(vc9gNvDBJ9|ADge|twr<%~^BTEDWNHsho4`ROIDugm z-3oUQ^=xo~DeBvJ9JATmszD|i*xZQlS`U{fIIrphYi~9XAO)GqK;V?0!bdd`X<2wM z`q=@awUFh!(i>J^R{TtS&VzA$#a^f?P&wnAm1M~AK5zj{rG|pavBFG5J<42?itXaC zC(I>v#R&tS+!;N4{rGlkm(LvCf<+aM+6p!^>miM!@~V~TO6d)fcL4vZFjZBMCEhbx6v8>;JT`E|R!xSgrPikwOuL%}Y zRj4Hng2Z*XMw?51&4+v%ArGr zQzF`@si&-eM7mgdQlhhoNep0m6@0MlnBMjP8nVV>OyEXxQK!o|gQEqe|rfS8p z@@r3`j&wj1abB43Qoqpy*F8jIJkM@ru7&XEbGZ5`2(vJC3-KGRWi5~@zwho}2WeVX z{Fw5YLSJ6qvKw1qj3y3V0N@ptq-u=wKk0ordr z`x0?<6HJ7%cM$PqrBW(?Whpl!4X&-#t;FQu$1K{cf;HQg1R$s}bBX2ONM0U%0oJUy%j^jchzkHG`yru=E*%k_)I8S z5->l8#qt*eCsUx`2pAtRwT(fdTU#3}pObmKrFokLJqU~qRf9Bsw0eLKML*oKOP4?o zjY~!1J@;_ioTBLdp_@1jsfeYhR%o<|-1FU64KFL-1=OZsz1?>1`>eMg6-i2>LznpR zPb|=?n2k??qmfr0YBT<=H(P{m(fhkQzdN|`Hb=(Q-&%~qchM2Q@s?h;Qnwr@H}xaU z{G=qj%61ImM=!kt9;URd)fhk$7Qe@oc(-+aWrL301=F9+E2A5GiA2$4*tG@q_!@Dp+Gkwva*^vnIZO=&15gw6(P`v&ggw6%Ghwfvo7zZ8N%{ z^XSyL!c{D@t6i6y(32uPT^pn;8uepSf09Zn^)uGQwc@~oBjC!B9E=wJ#D^wrU6gNZ zpA%EYjO#fr-G@(5DOQdEyTbbCyrzGFb>a-LEMC(o!m;y4i>sY<&R0-lFKP9)CI`ulT& zGklNY`rgP+Qz^KQEfjE%>RTkhUDFPw$J~U6Z`hRi*hsV*c$Dx~`#fK{tL#IXj|!O{d1q{n z`e9tU1EvQk3Qy`4w%2B&!tok}&j`TVfWL*|n;Eq|it~H*2(;`j!TX>TaZxEB-Os9sIM>+U7+4kQVH%_35Qi+3mOe*q{dl7 zms8}@CNFD3w+rWAuLBB9HR^zq6!P7l@wXaXYRb7)=EVGU>u9++O`~ZLS{;7N(LAis z2qf39lM&#RzP@Y1V4HI|+moc={zI!4$<6F?BXpWL>+rgI*KERdVHqTlmYI|~+qg#g z=VrE%)>$~XrxZ4`3G*d~=<1>^&0JmIRimBe`?{gpbULIuNRgd`nnnL|)fz-@rS8uX zA*v8bEN~aFy{h17Fb*ehCo;tf^b@%%K6vw<=(-?)`@$xyNs@9^v08Tc6AG}b9OAbC zrZNrp-B0}zYub5awxsJ75vy%BBSGx;{V7q{roeoJFUWM40cg)A5*2CS+juD z;Ca>%aglGaXZyj+5sm~?7;1ym2z~?$!>M(tyIU#n4!Zw&FbPTPy<;L^fKsYn&gndV z1JBK~oXdpKOGY!&NsN(APs9_;FHN!A*~Rl7>$bs1B{*2cf80C!^D!%a+6Y{9LL~SH za5{i(Jf)3Kh4wQ@jnFx49;BMjGQz>Ct{6JIC=G>z;q8!U`A5GS+I3`co~5muw-J@ptu$hGXXmH!01Dm$q10Ck8Dy*i zh%=izfMeGYpD!rY*Q=u^ZNWSp(4?Y!1)&TQA|v$HJ_mTB&(q# z;d@5)Je>~L)I)^Xh`=m#eo;{Hk>_qS(i5!pG~3JqG0a}=36yt|>HSB}vT)6*`BNzN zZF;?11T|N$sguONFqjy^jrVBRN6D;$rU`vyCsx$e3d$T_gse0`m$IEL{Opt@)`PNc zG1>N`N?4H;dU5qQF$a*;%rX#ZUd&P^sz$M3Q=kHw8jRY+uYW_1kve}3fo7YU#^K}) zBMaZu_b{K^juG1W?g&;Q-wr{m1_jOpfZahSfn<11f^w)0U7elh=@bMWun$5uhIXxy zriJ+iNr?bTX7je8Jq(l7wc1kx4FdChBjF$_G*fgq+R}H7Ey5`L^XV>6&~k8ObS;E! z79@8Gg`#n*d{TgZNu$OoBTz+QnDTd@LAXh=0r7a(2MJ+>%ax!I$H(=IxBX^DTh-;EGmt6q9GsyrX*TL7pI+18}JvrE(cCJWbRe+%DjI z6hhj5N41VJbOoEY#lEIL=R*6@SDYoL>2Rr2?m@rL2S1#ao|g{ZnieiB=|Mr45@6eF$6 z!Y}*_atp;}X#D`?q7mZISAXz^BRP`DlRZD1z)VUV0vvhW-x9gr<8uH^k;v8a7^(7v z5t?IYxO~nkSqZ}avI?Gi{iYe35G9Z#b&IzNT~PqDP+XygY?0vj~mF4jun zws^>{-tW&yJbLmvs3mq~Dv(L6ZSrfD8~6uT04HIMAs1Sy9(DOSH)C8K2l!xUo@k_5G7PIYA#U@8y&2u%M~f3sq5mukxhjk3`ZiIpSG&h{tRgcoF}sbZ9uaP2D4PjTxfD&k_~f{zVkqQU@C7z!3Ts#jDJYT0YYDU{Rd+-OHIZ{h3HEkip7R*(sa5y9V&NyvP4GPy%4 zrd74L;@~$hyn}o*y;F-_1-5YJJ9Rc^>ant%^t=O+>m#uzOh9uFyu9HkK0_%5vY)y+ zvuXhT((P;35uAPg9}leY&9GrUC7*(?d~e9nckAq=4J}FDt2yD4q}SrS@y5n zQ8FVt_G{6JbD&@2Thi@Nss5X?ctd`z3I5?$__TR6BG1`m;xhRf{p22BWv^# zAL!MWKlHPjX%e*0U+z`^8@94>?q|m`&t3J_p$RtI;ZV}L<9N%L(mlcK4wRFY6FsbU zh?_T-z;h{$EEhUkWYV6G+2yZDo{F^WY}j{<{VXzak1D*4g|A}^iu2n(Vj90ZoB7I4 z5^85j?cfGmglnBq)qgLinWvf$1`#1T(5Y86iVVuJ2}p%ULnc5=fHzJi&gAMqYNzuSABuEnFIcA}cj+IjxX-M5X zCmCg%&YWKVSS#^nqAF5RYwMh294`Byku`Om78)8rkiPJx4XaY(*or$jrw1pk+MgFa z7j&;0`r2dri(2(_`<_ehDq;6V@h|tvXumIDOT?Y!F0eQ~%g=Wl8X87j%$ekV6<@?HJ&FTL6PhGjaZ5{#maco{zbSZ%0= zV=haK7&?sujlU;ieD{akC2)D|mT~ann=?)_J-4(*t(g<`6%R7RglCMz~?#A_O{0VR+x7Ii|XC2{pj z>tQa+9ns9YtlcWJqKQ=A26#+I36Sq_X4V>O8Cq(ZM(E&M+@;?o*HTA36`LoNm~c|Y zl^($K=5VQ;8Sy?$l-my##*?=eq+1Q0DMjK#SOfbTV8;13W9>Q-5DntV(3<#^BfBqo zwRS9kT?yu#l*na^bIE!IPLPE}T;rSXMpnC>cD2tZj)Dz4%UAj1yUIWMeij*Z=lEh8 z#(ur~$ttbvhfe4=PKhsVr7&N59Z{1CPEjrGQhLt6oFJ~&ZhF&47_)Wmmf6ktpb(0= zpYX2pH_MRg^3U~(b=j!p^{>)u$KmfPOcj_DwLznyc27)DW(57T5MUiK&j-2hk5lDQ zoRQw+$28YG6hc({F;#M}r0(5h+Ii8vVZhd1;_JdspNjP6K-olw83nK_#g!07Lqq2s z=-Th;BBGIjQXYMhqGwj(oMg&G$6d#R*X<&LpV!#gm_JDFOBS#_(;h}(m{z3Pg5~9w zbK^@hVteQ$hf2uY_*Feo$;;K8^sEZK+n2xY-UIbTg^$sG@K$X;co|KGQRcF+s!DxJ z#;O|$oxjCUkbd-EPQ9i^`TGyY&!F`oZ5wr4_f8b&UD!WZxXreTbQgCjDF4Xc-^oEs zXtixREW`ThcZc*zlOo04uIe1sHO>_F?WEXA>epkBy%L7Z8K&R_lFH!?d`zx;e$M?q z#V)S|+~}3+^`ycNO{OE;0)9`E_q(9p|OnITj7||iFGro;QzJHr^VXj5>aoLC4 zUDft!)5F<6Zc-{OyX4z&xI>GdUFJRhgo90rL*t$i1BXU+ogXMaDiQZ&VBe{|vm;E^lv zd&WZx1N#sa)+NH9cmV)bgMGBo&S(mcPy0x#9Sxba5WMP@h_jlmnXglydf z^}8M}qsHM)h2>^hw{JE=^W>ISq9`YyhMwO(am@K8MQ;8`+h9`S$ID$jmpiK}1tq=D z0N+?AkGx@&-6Y<LG{%ZRQiTc;^5Qms~z3{ zw7Z&dV?p$BDQ>3R+${Tm?L1J5U9{3cm@B)0D&s+6)%Hex6N4q5%TA%UHORSK3HbOE z6;T*z>^Cl>e7M=S2)q2oLCWco zIO5SMGSN4(IY(Dni`}bqB|6P81_vwhoJ`-ToP2u-u7KtEzUnHzB2dqY_8{Kyfal0B zJT(1kbU0>Pvpc7cxb)@3u5qzZqGwdh5YZqU_+m0Pl`!DJRMFE2|I4l6@UGGF?s$_t zPiJoa9L=8s(^DN!yDO0j&02pCJKggv^n;16C$v9pz1NFSTY;&*vS#-i^d93sx13bD zah++!jt_dNb49z=*zZR|U(}{X+oL}x4~a_DII8ebj0{W9#PTPwsoD}a8Njmpmfuca zh}BI0sen)d+r|}_Y=A-44$7&3p+Mmso$E!fwzGGp0-RY?Ag=WC+s0=^rNQtTj$Fk5 z0RMsNojPMo4o&YxyWQn$ZZL&LK+yGyM^N}4w7A8al(G_VllfPgME>rVcMfqOt@m7O zn!l$zAgw&eTi95deAgIEG{|`dWVX`-+4VQCoU8W!YCpask-{)Jjr((L$BSkCsC|-W zZ$t(G;3=<<8?Jph&g;Z8+oYJU_)&AL`Z74L&hKp$cqza{FNi0bsi|A4L3+;*goR#8qKU?HmiDVT9fsDHTsHm#0vCnPe7oB&6>g~#ceGBbc#gISO!wwh z+`c{W^c?kk1%x%?Lthr=AMx_KS~laGP1r!|T$-NTYIe-B4gY!&ZSl)*pOY z6IOy5iI+(;p4SYjG_p(qqhZz&X3;yP6Ct9mCDTd5Sg&hMWmhwv&A9!uRoux)n01Fg z07;T>a#dPu?)opV^2M6znqUBPE>`Y>LIx2o;MSp$r_sU1I zI?kUyzm<3IvhG?1&7LH0lAAZ`Ek|4{N~l`7?S_+ymxF4x#!LV9H0~tmSFMT+S=jfZ z=`3t8@zArBwHc2jqv2Je;u}rl7ag)W+1gp+jqUr|nEc+1rjireYi^wWyy{ZhTcqbo z>>tSRDSJeW>)vzS)JoIhR~;?-Rp0KAnU9^L?EU=VJqmqfDrs%6w7j-vwL&nTC9XK{ znDYp8|M*#T=q=}FrIcJH!?Q@=4=~bDgc$wFj^b)ApjdYob?QW>tm==i_r?fr`$VHM z>bGR$p|W$M(+SOzHIt_iwrp7cVj&iB?Ahb^!T1;xT@pZpElt5k{pZ`w5K7R7n=zq|FyHfzVE9cft56j)m!s5kU)$k!A z*eVxlBpb7cdxn6R>YWN1r}aE~Dsm~Tv$at}e`5(#Ci1YJ;@itC`?Nmp?b$x5>$wEG zvqM6u0!0|~&@|P)bw_#YLUPR=?mqtZ2#bLgjKix7w-bJ-1`!-FN!m@OlG?uZLd$AoT^z9gQ2nG)Ub%I~33jCJ5R41|pB15T}hCm9_27 zy~;~ys^F_$O5c~lAq_mhG+5|GGE%dfJKIeQB~NXSNlx&=3iy1ZC@%S}i(47vtL2L) zkeI3>eGbTg-JNqf7NiHmfKY_lGS2My)5f&QwHTz2Fw_s<{HyNQ|A33}64l$RIls2M z78|DP5$C^nsJ&z_zC{z}^| z;oIYPCK?EBsYAMaCVtbCUv#4?uA|L0Kri1W+|k!^?(G-a(RH^2U#(?S)Y`^fIeBL7 zspki>R7kaov0leLpX|gxysIkPW_3=x?Jp?MaG4jp{UX5$VqzO@uozJ}wql8?NX62@ zvikoX0m(a3J0)rK`RVmghn?&S`%aO$N!u7A&XFtA#(7dj*P}HQu#;R6|X`qiJJ>3ssib`wZ zA`y{2IdN*=zC}q&&s=+}lNf$)gH5A5X5PF#m?I^DxR-O zj3JyErI!i$K!DSb%I*b@t%8TfeG$3(gv=@Up@`kV7t5euP1^dCrdNr1S6GC*WN1Mj zCi%8HSf{e!u)I~rFMBVu-fcfB0l41hdp_pW?{;S-fAEL1DYBV`tAeLVqe?Y73e}KHWB%1enx)49J2=)eD*k{Ua5w}=;(_y!J^Cs0 zr6n-Si5Yd)3CT>q8s$MKfSIcmJTUQs8iS7-ZWyo`$-Vi{Ng&oiyZ1$5pp;( z?`msOqLS&iRs%?*A(L1^eE4Go9uXgMNPR3cFww*3(z=jc#l42aHo_(hQ#(WSkBtpF zDx&>_j{`%E6f8wPlB-z3Y&TvxJ!*+lA&C@09?K0c5Chsl{*zg-DnR0`I@}OHE!c#a zS-?+4uE(AV0>L${97PjZU?jig^i&3SFy}&2udFND695qvb9!5{|FvOoWIIcy;c&s_ z57Odbnz1BEwrpa2e2}YNC$(WS({*lol`eVu)koLJy?_zz=TeSSG4zceu7Jv(0SzS} z1TZF6QI}7UN@{ojs;nrGHS5I4U8eUvZVT@aRJKzK_&r&}-%NV*779Qo30X2W%4=DW z`T0@$)}+50c!nFy$Rj_v^JbKzxcOjBP?X&KLihV!EwAPkQ)s)1a8Upongb)?A$?QQ zgCPND!z0!%yFZtaW|_LU7}4)`YB?+951)VQjBA;k>_BN5{4*i;MC=cFz<1o9bt%2F zo06?DDuQK?4N@In91bORgw`>pF3@?33oIV{@?Hr?&xnW@z%}wt_e{p>;iU0h+&RjvJ*?1syr|l)re&x zg<4lni<;85y8}aIh>^dY5n%Ynov81{`xvu-yIuLJrR^CxL3>jNe_sB~4KV)`uc;L^ z?If4&eWIf+@Jn|Y5y|%2h@XzvyvcZ$cVeQQmHFhpj;jX-1p&8_e8S!Vi1#ja-3}>l zkZz+tIvQdB>=kd}%9RK10}C`Wx{q?OP>0WRemRQXc5QW$HQ*9^#DBNL<)a6nw@fi@ zL6}mea%g;~R~Cpy{K;*S7;_QxG{iL|crRB*5A+7xSDZE`Z4Cy@$ddbQ^PM^{zN!CJ z`iVDdvbijM$9um!YV~jNk1OKh8}lCiKC6NrK3gm6Cl&$)$E1rZv5IT0J2q$TFHc2E zazbCKU6wbeicO$K;rI_(G_`o?qz7T@cr|{srMZ2=k%u>&DV1RObkOgdm+kRiCxZq` zBUUhj(+;S-XJO|3$>)1NvLymtCA`4MjNobZm?xi9=g+$56*0;UAwV2ipVU`4@jLe44eI_2Nx2b6 z0A=oD@oUqZu16QX+#XXnHH2wt=|ZlRoGcz2oGT6s9rQkQq2}96<9_kaX}rIntX6K0 zR+ZoN?vCS?iXYb(T0bpy4$&p~%}q0tCvMzIx_b4|4Vp~)TY{^8TycTHft<}JYKP6F z<~m`n4Z(81l|;WjUe5bqv@poJTsDZ4T`tZK(-RFHQakWKD)NWoHj9Ii?wwR}y4_df z*J_p01+mH`%AGG^WX@mf*WTAY-cl)=P|7e9+~(5M4c11+&xwkh&+Gpt z+LV423{un})F3LTyFiU4MIl-tC`7UA z)pUzKc65;!uLl`4fP7DngM!hq)CgIii7@JSz6BLH3Qt#a>jr}oY*sKy6p6M@FkV@q z?42W(X+V)CHsaL{WzC2bAeVC33Y2yRuHenWoPN~o1%`-# zT>)U{f2Aj}A~haI*f-IDwiQrV_7@C7MLeg03%0QsDTzn>k8s>Oht6|?a+#_Biv;r&T;Tr%d>y}~2=?t=%oht}y#b(BW7xmU+e2|d= zDv&)!*nz>-(liJF(kW`-MJAU@lvCy?maW_pF`zw|Spk(6{=yN>QG}6=whxfR#IDIlmOIh|yFbCgl-(v%f+s4sv$pv8#5b(?xE~;$AF>tg`P;=%EE3#HKUCaxcMZbk0$qo!A<9~9_v7`AwV&Fu?l&TA+t^;VX997$7{!k@xo#LGXJZcgf526IXN=L`PWUgw z(-QInSu|Zi;YM1C{3G^fojxq7r!+6{N!KllWrN(B+3Ynrw zvd@;%DR+g(wZPc~|{fnC6e?iQ!ykb`|I9-3%$5{)t316h?1uB+y+nSu~T5HjdW^#fX zR=~L8y%JHBj;AOAM+&EQ;A)~cXQHbrLfu%xz>6(vk(N@BYdgI)n0>QQnfXGC`9 z!cm-`KbF1PySi3FMmO^=c79`W13Y*j{5-;$swwRX=^uF6x>gbbPME(Z2M}qSr^wbT zm-t+8@igoM;!WBuy_*?y(2YQ_4`7J5E%V}oE;suj=VOtRFG7#CD`XvWHZc!ZgXF;` zI2aUB84f}|?83rY0-hNE3IMsf1L^gK_U2LT<8%0aq`8Jhk+xJ9GGW}C zvWaHg6?bTFF3j^GD*iJx1W~ad zXKab`fc6UHl$Mn>kt(iQys9F6Yu3K2kx*s96vE7KiX|psa(hcT!g<1ugJfjU`#?&2>oOM(=g}TLt z9Okr4=q7WRMl-Bv7KET6j z>;xmMSHb%%-i7>aP6l11K7@&5VUQL90#2I!h0IPRAcNHl2CK~a7{X)5H)A4LHvspu zT65^?_YwZ9xm2^r6^dQyU}|9QUZ&tGJXZF%`TCp?T%BwO^3$qnaK z*PBa@o%=lkL4tP?t`z=b!X{E&Yazv2`UdE8c`!Zdrk}hIr2=l0L+PdE^*l;1`{X;9 z3`V(-cA(_P1M>4F$GV!pC!9jc;U@-cr%o!O=*Y~0+sK{0mLplJbys2Z{{fGTA*zd6 z9!>sjx-qoTZ0%;Pr%c|uJ8}Jc|HS2&G%#dT%5?k;;{i;y2Ho533^+z>X)!v?GG?vu zhF?~iLB*yqVl`=|nFvOK3}#7uk{mp(Qdli&0Z@65$Z(@+`Q95s839GLjOA z4s-aELb;rmUICP8d*%#JF7IP=jnKGOH&P8c!EQA6l%_K#)VQ(r4KH#9Ea)4Z+xq6< zxOQ3Ox?~7DlUH7(COx$GI#iE_z@R&ge<<$)jOyx-^kLjGdOz5z_Nfx$1x+kQMZTm~ z`Y8_W*R$OGmv6dzLO^Z9YDTZ7Z`rCw&x_;MH~FDu*~*no8ufwDjtaHB3_NOa!_92& zGgY5mbll}cu{b##*nkd#ptEXgmNzJYQ>vYGb>x$eipLQC_hHY`8wKJDAdD>17)n6aOACR4F7xJisA3H{3KK=l530p=ezR zkHNcnKsVThI>+X76ihUZCpAKGu%PYZWQkBLOs_xhqGhll{2UErnH6G}PwNjU?50NY z@``m#lF^^ox&VJC7(kpa*}6l1hh!{yb*1nu5ZA4MQUyZ>m^;*#*`Av*t}3)b{c-N@ z9A5<>KS#=HyG$Q_y$eYcvJ;B*V#m30JZhXyef0ger1;CAh}KzSxJpI?gPA{r+K>P> z`i^a9l`Hh)vwG^H$9?}L?^U{7=$jC7BU1V96#|HJOj-(-4Cu)WZmQT_O{M)NL$Wy8 zyv=%}7NfvxYV@K10py}7N9pf0cvx@MQQd|PtT+&&zhxN81YoGc`g@wyCQ>|CHW2xx zGMn^f;YOU!CpsgkjpeCoV4Yvom<%q&wWn}#Wkx8fTv+-J7wRrsg@tI9?Oa10YfeQT zw;k7zrF6fG<&Sz53+a6TYLplXRQo!~U}lnlo)f`KjgmLvE;bWKjl2Fy+={ck0R%uI z_}7tQM3D0|y+Apd52`yWJi+?IPfC!t++yW}@hV)9hN#%S22Qjp2l7x!lNhnK+6P5z zKCE|XRUx*S;Im6{$Qrfb^+z;p;%K(lrwSHwRoDX9zBi1m-GC(Gw{#4;hL%Ecpy|!B z@7L~%FTp1_Yo^mCbqYgkm9(8YuyT{yK>Jyy=q;l6K>7lwI+#m)!s`_{!Tk4cvT#Q1 z-uk~}IO$A6Gz+ExtSaMO@t$7rX3n&O?nUQhYCy>n+tHkaa-EfjYJ?yM zoyv>NNX}48myC(zw(UiJ?^1!Jwz=#Kl6?h+oOPTt&z@cnR|s{)9&EfF4l4ys0midU zjvR-CmU3%F?(*r{JdNw} zFk%;oO*VRtlm54Tno2WwC;LuZ0IPiSY6ntku$|N;CAYLk_rD}0n>p;$OjhE@n{Dh) z1t?E3Z^t7!R37ay>$Sz3c)YcafGNfa&bJQhD>8=~^6X(JmJ$ncK>6lEzRWuKXytLx zTi$r@2e1=#u)qbUnhRE_KYWAR4l^Z}3|OGwa+jAE!B!*hVzf`8K4t_Va8T0R`q6Q} zpxpjG+z!WM_rgF7zJhv_ECPcH7nkybl+?1%wqpgXB44LhhtBQ(Y14XmK)nMFT3|Lj z%wN9Du-H6);LbtYQH^|V#VUwKHPblu_IUvDk4llD$$e0*vnIIkZraRKrf%@~bmnGN z8#ok%vr;<_`Tg}E{E)2!SB(|M0cS$Vwzm}e?JV+T=BufcR;w*{Nbv7vkNd86AMTGv zlHUA4szlI8yy}T>=l6k-rig1Y8q%o}2(%g`G3Ts4Kl>3ipFz)o zXT7HGF)v5*^X!qjDW1#Ka_b->-qCuT*oEhAt7Z*l%eQ<)`9fhTcNq&NpkF5`5reuV zE-lSiPkJ9YJdc-qP#&ZnFS^z$HQ@va(woL8I)Yjx%YZab0UjEbM2+ByPb%Bq zNS8VUQee5%w9k+8Z>jl`6`e#|AisCO(&wB;&aJ{TUytt{pk#d0qg33qWUlZx8 zVO{2t;OB{IhU1Yd5^0|h&-YMe!s%9>PWI0Jw6C&(tp*t^B|!!r(Zn1cMPFU+ zq1_g0l?(H4GMlh`aq7v>>3B{KDAEQvUEew7W7Bq|dDJcpSaRLvONBzZ;w;~LWwwj% zS&)45!8_mJp@>9+_a(?cCAVK>-Vr&*&u=ZKdSC|`6F4IQDCa~t$deZPjd}DqJa1tY zl(l+ka;>1ChXxhke`>&>jh6}llH#^gDC#N$h#shm;%3^8G{JzR{tr5}Jc7~{X(vw- z1rHbXtJ@*}YbwDi5=AZ${ib~?$B5U9Gn=)X^HGRj-vF&(nI<)2|9^7`9xb1ma9^7( zOW1GKS+$#|zFF>N2L2HwlEcZZU!UCyObd~emnRW>bN)l9cmBk~(2xEV!nmZ}C4=Qu*P;&S9rZB_XsiG`>^NTQNK)oNe2y~|HmoG%PvI=z{{nQs z<(7q2tDN~$8Xm>rh+Iv6MbJ}#gb1?o!?-WTc*?dwJWMsK4v!w@Pk@OiL1A?f ziX>v%1Rf3z!3@Y!XnkH3GG^65PY@qjDwe0_o zWek{d4-gh04<3McmI#_QWX~|D^u|b)N?YF_3Gl4BD9vEYS{8^z#)2aA6CCi!-Z{%e zDuHWy3HrI6)LCUa!KnB;nGX~b%=jGeZ1RH*n6tF^`CeoCJH(E*0$aU1fc!F*nCf7_ zgVJF5y3+SWv`umfZFaZQ!ZK^C;2<$C#QV(DjEqne7sVi))1$_K!8pKCjN2#* zbXRqm@G4eI;SOnSd=;ml@Dkcg*b;=(JLC*qD{Fh*NBap5eva)8X>asax2ZVZ@!PXQIs{00`0=AbEXU}v_NgKw*A)F>oDOsyt`h5j-oKl#oSvh=vLkO?e z7{~`qRuoW`hxS`F+Z8U!pjN->ZX5xB709<;!%HFKx{cO1eV*EOjPR0#lQHhKA{-46 zYx7b>cxWaa1{!aa(J|Ooqr8yi!TWiJC7aEXAPgK=IdrGX5N4fc?}-|7u7Fk_AS->Z zo%$r?35zpn)?JQ6bfb0mf0D<5R!aeI+GW>}#*rwsuznoqq>&)_!q!j4g1KRAMa=d= zEl@;ap4pqXoLX8ZAF(%E40@s}Uf;eTXZn>8@9BpQ&VCGs1)qD~H3Wb1E2nH|LD8DI zCdTOidZRhMqd0A(7P@6?q-NGS{~8%$d)%oSmr`}e7YcUK$VFCTPj<92c`|CYcaVCG zKMVW3nhXeAYE1KWGd5McLQBs#S=V@`5c zCq7DF;X!M`iN{?TmIWdxY*Hs&;~R+_5{-fMsrL-7mO6n7Neus_B&4CT)G=-?yd@TkaUq;^{xqLKNgeM{cAXen4Ke zTwyy;GAbFrbZ$Q-we5h^G|iG>7t=mhS2V@Qn$5w7wAZ>o!Zo~n-z@GEnA;c`(IxY% zBr0x4qDKR{^I5@&K|QT5Mj3#d`KYPDcz!NkMFEcQ1_tQP%EL*4t{AaOu5|Y$AJ$gU|CZ%FA>X~jTTeqjs?yWvYY?=|4XAm7)O*&h7mtk;AcMj!2L!1< zH8Y;v&~dnSZAib7kWrV{tEgUki87(BYnJVn$!b*E@VMOEspYlx69z2z5{)YKlYNMvg~D-FSZ}@Y997(`4$dif^xTh-4UbKw{cOWaIleDVVm3;q zdl!VoHzIy1*Z%3bYtwNo8OWf)93qOP5LwyhTq!nDNWD4`X&ImW>G001;||-inUbo^ zWzI;2e97BH1@qWKZjLD8){5bdj^5=5=FYjZyONYpGP^&z?B+OpCU@edWdqw6T& z+Si-cgTMS5stK%tq*BQwQrN~>&$HB4D?P+Aw0dqiqiuGidS$oDr#mBZVN2XOBnCMH zChJDD*uiU}K2hLvVbyZ|upF;juzDY)#{J_h-^tu1Q0Z`9w($?Xp`j=U1ASxE%YcrQ z@-%G<0;$}iXSVZf6KYiut}Vr z<+4JCf1%X=z;+(dU_IN3NiuU+_0NVa^l>F8D0c&%u-RF2G)TVFktL$20 z6#y}r)5zy%tYB1hfyO@vveJK2eYLH}>YG>-GkQKPduOKHwXex5WaQS)4pw|H8mlP5 zilF>JR)P>aPukWo2j^uoh%A4R`LC{a?@br8TGKjde=* z!>(cjWF4ISorOuzNp2`%0x zV@o1kA`QavT(DX+co%ALuWwti{?`NBfBd}rX9Uyi&a@)$if=zkVR@F|SR<5pu|OgI zA90{_yy9i6Ev()VoQFGQ1LOmj=jnYh)u^N6YBl?XdW*L#MsKg_##~TWO&V7e3!~Du zZC;;B8{Ry9fWMAE_Jh3sBsYPg@TTjBc}lD=t|3=%)=Bc(`)|f?<{wJA8gWp>o`!=B zzoo~dZ98nQb~OB0z@mSW;)lkbr%flTW@FQS9);EEH|Us^r^Q0_fdDtW(~DB;wEooP z(ZS?%+xw5?mqcW}{~$@}yoQxbcxxc)k6zUI-f$pFR!#2hR5!98Wy(gfdKEu!_mRt6 zbI*k3nRI<$?thS#9R}mYoxgf{NeZ5aukehd6D0Uik&AS zGP-@`LorjBvbrqlgHu=2vysX-R^EL3?P!oUhWmEw3-4uR_u!!ELq=kGO(i-Ks#53G z@8%C*1Te_fU#6Dk0V>4xb5=ejZZW}2orq&8YB#%Pw)3)sY@QXm8rF_WSw#|gAc3T; zUe=|S=RP!bMDs4I^1R9MSzf6NHF6Tfk9{x+ZQpS#J2GGCc)g7kJUcyo2U+Trwkavx zJU$7k_%h$KP3d0?@=rbbXi9KiGReJ5C$}LP@#ry!Ao~2y7n0&=wdGMAT_R~d_Sj}X zdnot>?J@Gr6+O}6#xVW|lRM@F$DTM6)i-bA{Kq>52OR%hY>2IDnr&NYjaJQmo7{Hf z%4L13sKgO&9uCeO|1FtSbER^<=9Ec$Y0OB~?4$^`ndlKf%L^-xd4SW4ITd2E4_JDo zpqh*MX6O@qU34$i?sUNYB>Ic$zx=|~B{Rq%LR9s~X{R*rnD)mz$-ce4OUJIv`41gm z_}OK)t@xy3V!y#@?I-`_3mWJ0d`F8eC7s;Azn!?3{57;JAw}c)s$#Zc&;H$Dp6o9~ zZ_kIBE4Z(*-HwsEv{M*y$sgvve`|1%!GM?g(i$YuZa%5|oawE=?p^9iYz-)qr5NP- zj-Qi`)dK0BJsJMXqgKNXkb%6b`L8;4a1+B-#p;pXP3+hW52Kfz>YWEPB$!;^Bq7WG zDX$CK=>=${M~f2>H`)W4p72nF^#w|m#79gep=#0~S-ln-D6)g&4;fH|8$!Xwh;I`txzc7{ z7-|K#I0~|%&5k|z`;qJz8R`6q&@j?ibiJz5EBG))^A<}5_dfv9@!kl1E9$Mi(vr07 zEU%)SRbJ%MbKnxEX*Xs#iDtwK5^m|9>RO#nC)PpJuH=&X2&Xg+-&a(6^5pMVGaPtI zpmONQRK#4SkE5A{K^KBit7sppdC$*nX*-slmwdKw{ORPO9KKpo_kU{cGe-08@0!Tv zn05}pb1mlrCG6gWHduGTvB99pa$3>mZ)57ivxnKPp=Wl#+b@$3_NmtAxJ!OtH7EKq zF1Dn9XIDOy9A&G40;Gi-h3V~@<~~6mE8+a6(p$-+DEhCnHI)X@?i_Vv7c>$Upbt&uiU7nWx*Z%)dZcJBW=F0R=C zZ8WpuLrQXU%IDRANZ24*Nn_juBh@g;LvlTkU+)$~ZE_RM;}4V%>6JNR4n3BmoBeyr z`EC2(O6_+knNzk_toNU#C%6!>ZjoLmKY7&jbS$t_~@}SMzkX(fdALxBF64eH883nMOz5ZdLc#A5Jxd9j-D>$EEdcmD-B@*~2_Y*yPDu zPsQEu1OJkF!mYu{h2uV+(^8+p#ZL-Vbe?2tv2~EV%;k6`#?P$83BMqJLzCT8G8o4B zulwVp+XgW_fx}aS5cK03)(N&6T5u7fJE#0{Rfy?V_i0G~I$1>xXvOW97+H zJof53aeuW+T#WnCo6E)*uHY;|qjU!uEyex&agS4mqYcc}EG&(6?49vNqSxHB29M2@ zLlHchfx!J{BI7H?v1NL|)FExT=gs+_me0Mz!r$r2OdK$tUQwyQ@I>zKrR03(a2+znka^IBfxQRJ`DEwC)M&p7*?ChcX zJIIYx-k1~{uzj~41D!K-Z74Oy@+Pi8yg!422jIt#HO}b4#-S6c%N)x2Kif{X5r@K+Zrf9wlg;M6yN_|XnEzk`AH zMyk{loxS>OT`_ zCeqF1eJcbPcB23H5eGo`4fZ>NY**}3)6;?cQ zKB=brKtJiF)MVqma)yP*@@Y+b;`?28vm8N7EUQq;bed4~ma0(d3CA)udK#WAJh{1q zg&5{8=sWe+6T1%nmFV?(VpTrq=9~fT6KY%WxW)bCj{z(H36#zzuS$K*uqQ-53+v3!{w53{VTb1m@}UD^0#_HMkrK$wT61f)1be&NEjHYUmk_#P&D3?@wvdNIIm8+| zu)+?CR5Z{oB!#^{dIG$4L0}r9Z4FrvC_BG z-{tMIJq`ijn%Qw>dGubv664{?6Phxn>H6?q$~wXmp8fOA`m1Z_d^?VC)*6Dy`ver~ zt+rXg#laJ3%#5?i8?MzLhAGxlU6d^yY0A1OqUf_^GbBs^uS%=D$qm=tH+y!eU+o44g{Z4)K;4^2=h) z`j?6yTFinQvso4>XzI_GUcy?9yPay|h)Z+m=CV%D z&>#mPGkKzs-SaXyG#b<-CTNukdMgxFoosku@Z7p(bG=Q=Ddng(Fdwn`PH>V~SdtX( zdCMvraB74;O~VSNd!966*c0=1J9w(K;)E@ae7HB;URaljPP8~Q$GSN?I2UwF&>e?S z%;pa39GSo5{1N%#t!${Rv}1m}%9&70qkqTyZv~vE9qt`JIRmDK_aCr5&@$rm-v0GR zhlkK&gcGC4w6kfjp3IzQKYw}2Al)p;)v{`@AM{=3`@H54dPRDA$cpb9SNEOT* z^Iu0(Ut8=S`^kV@{CjlhQoi~*y(uQDwKZbV(%gJ}-&#{`3_xvMe9 zu6v{%e4IT$YGv&%vHOGL>rgqC3l@!shchA-y zdqyHvM|o%cY&u?y-ECq{FC$3z-DLNNjIrbCD-TTcUS!AL2D7jhq3L=li>ozHZzbUi z^?Vy(;J8_Fvd)J#OyytafqX5|)ZgQ2_b$$yi|9uXsQxt=51g#t%_fyNuuJiZYArH; z)IVbr?}L||?TQ}XT)Zqp$+8WG!Tgu|RLSwkH!%+6Pm9B?u}#Q>&N;bX@MYV9q6>h)juw8+QMm^Z!ZSi>qOx z9eh5BFTZZQTQ!~Qdfa|aZ~uEDH+)U_l8)->ckXkQLhGipslKu>Vp>O??;L(Sc&Tzm z71pzlecEoEn$l-c&xsEHB(;I~T;G29-(la>(eQi7-HFZe5d`bCExpWzZ!ZpgUbOtn z;8P%q7xA4ux?MJt^0e1BC}ZxynaX5TH7fqEens1e5Gmgm--W&}FP!;Z%0YP(Y+))5 zRm;CWz1V5yL-Mz4@Z4E!lxS$4boIJmLnH91PgSc$8`B)N26n@uUk#><*_qduZv1g+ zq5amO#~PBxDdtW>UXeoe;hE@?%ij}+c9Qdg;Drdm71kos@M4rl|DC+RE*wE&%ivqo z;r0>P{{ieSw{4N)D18SsAJ|U#_tV8^^u)n&WGjT*v*I?I z6LubfdO<8px>jiMcrA(rPa*0$nq~GS1cQCZD&#z3e!yMcrURtje#44O#W|QhwNh1Z~dZOny^3xuRtg~QEMt#s39TZRTLdJ>#VAEIYlj3%&5 zLCz*=ak_R9BW&$?|6LT=ql_w*atw6+ta8B*flvo1XOql)QotY zL3Ir$)!_|s+WzOHl=13TAjHwkr42cIijMmzdxh8~1O9taNb&ywsEvJE(NSlk{$d@H zAMHIb>g9xC6=6!C8?FS%42HY${f>ZE4@w5rKtYXC$`x|z71n@rDC0L6qqy^sBd*RT zgS3Pz#^R+-Vn2G#2eJ8)Yy!-RNMNz1f_7(7C zcR{vuwb8mqq=DHpk{^r&uD%o8aHVem$}7C-N*08v#D_A5nT%|Vx}DnUysIc`>!*-M z>jS>!%WoOEk`1WD?WiK2R0L3eUbtQ!#Lf)JWJRhN=R{sk3sc>R&~{t z`)~*dgu4w8KmRKF>oRMzMnRs!vq zig2T3g3&1c&^3AT5aJ5i-N)7A0wJu`pc~YT{MDl^;%HbtF8MT}Bu9@I1cid3$C9^8 zwg%MroV2$1#Ft66P%1h8N;Gf7=gEVi^7wpl4d`w`RcC!A&1jL$6D*tql|qga*`Pkk z)^iDa#o96@Y5mueth3Mxe)RY*+mPdk8~-HCwX5xX-cV1#lz73AJb*~EaZLF9+$xf~ z%Mnwm3`KtC1{8zN8~E{!a208DSBRrg5~VH3)X9;)0(YlfK2A?U^HsEcqz%|;gWzW* zFZaLpIjjs>wdG4)Yt!5lf5o61eG$2DGq-DhjXZYy@?=J3GlYhC6PE%ims7q*=0x9c zB=&K`L5Sxb3BO%VXII53uWhNpo@2IFj#j!V4T8(87ju&l8;Jh_&dlPlYRa2nxR{E_h04vS^EZ0W#5 z370+?aR$lA8kiQ925L^yvXgHqXh&kwmVwAj4gPyeEESVBGo^hK6 z5-Y2e-S-$u_qKzwyCzYD*SHr^VAo;KQ}de>gVJC35)5Zq+QPRwSO?~o!Fnt`k{hT5 zK6v2np}0D?JNA^NMNUH?CskZ{iY{%a zTprv9%tep^z|U(%l`(1Nrec4y-Sd_b+62Z3Qq9_Te5P5i+Y25IzF?~Oxl5>xekhR| zww<8+Ra(C@w%~c2{X&6@0qV$iO1Em?Z#nV#CM=NSt772j zCe}8C=bod9yP=Wrh?~F)ZhZzP_2-JbuTbymR=Hp`-u`M^R#I_;_A@&WZrMU94lh z?TL5PB#hFWuIRk2m@t@MjzF@<)}1A?!RYuX;iUPZjWzRX-SpZWSUq5r?A5I0j~8wr zicIr){a9XkZtu^1 zI7V1F;chx51BOYKhVE#!iQd97ELEOMM}j0KSSTn3Mn-zHqqShA~nP(Qb0yKTO>H+`(7HXl~4pwXbTwi@jqY` zhA26Utp2o%(Sz`QO}|^v%93?az57i;S`S&8)p4$54zulUs>fPP$cb^?>Mn$fSP4ry zhKi9PvIULt=Fa}G`FG)1F}c`}uSU3pRiPA#nDU)DC9P(0H!L7Y{VK$P4KP96)GvEb z$riJM6THsI9kvs4eKNP^Kw$H9?@}@Kh!Guw-I93?Xbz53-;zi%e>kIka=^rxu_>I+ zj@B3wt(Jj;)XF&P7nUb950WJ!RhzZ2t)Q01!rgDreo1brQ?Q3=~Mpl^2C?H}E-5Bm>)kLQX=d0~Q7nG?y9lK+`G>;$u5*P9TvA2z>tG?!5g zh9VaxW#%M_79G$>5SrSo30s#gTa846bzd-Gz%56yHJXjt_H->pTCc^~3D$eO39p=& z3p{D*Xxn>_V&swNZ5RR`u+fO5a9;GuS+6AJ&xbRj%EFq zjsVC)={5+dbUi_1;$LOF0R2ZDW;0_?K2ERLt52(Iv}$vtVK~fA=V3 z+}v$@p)K9FK+3|m_@u3HQXkidz9G*_bSt+YI5~hp?xsrkvY0*Ayre;D7OuvexXosa zIeva{TEd`Rt3-%=#XKG#Y~aD)6Eo{T6IF7Q7n?!8Wfj|C9;jde81o# zz;#s2(isw|t+usj4TDWK3OYN`BmUM;mPmV}12;7am-OP5gTUweYZTFmqZ*dE4Oz)1 zC3A%V-M)gE>n7tFt;*H$W^N`2$TgxGt`N=dA*-xm2QOV8M`ZaeivI8z?6N%TiT(&; zb$1r#K2fV4H+OD%bZCb%1$`Ghd(ILmOWkwkl+aVC_^hw;@ARIlC|l-jk%*qWUb?v;f8!PLk3pG@mUJmv~^V9!iu8mdAn< zBZ#X?&2^hoJk`(7Dt3WVfB-54FK>QsUOw%36mLWJN=){%`@J8 z^sr2m=)}(26_x-@S~rNGq?01L22ZNR_1+(l^v!J;$$EPSqej3(p>w|;5ym5Mp!*Ln zzwRZm1O}bJarL@?4*L0m$yVg2u_?Z{fDCrENb$n8tH!fRpVx5UG7MNIgXX;)%661k zS4oC;a4_2E{AL>IwcZP}SN8FaFeM~T*XvntrxLgm%M?nGH7*>;C5-B@tk)1X$hMXa z*K;WBVyn+Z`#y;8e*GtdsydSRTGKUqDN~n`LkDn^P>YKpgDQCCG)rF5`M}*N8uU}V zhsVsmK!U)96DV1gDLo#2!F5!}BCLn3y_GjFEjfqQZ#jQw*MQ4XvWOI3`nb^%hY=Q- z6KSalFA`QREW-OifEElHG64U&Htx$=EE2hM`5H;{dBJ@U)!)}dcRe`$jW9)x zo5O!J?9)HZ7xZLAxh5$)$>LJhdxSfy$%a2I8~T72hlEboM#mo-y5QOk&{n~)JbPt% z$_-aSt%VAEu<|BU-%KVuL4b!~*k2VNQ7AdTvL4i01OpFXYOX7?uZZnZacSjMT2Fou z)4@#FJTLG&Q-&Aa1JazPbnfOuT5+3UJ-MoQ=lxpB39=402GvO&m279sSRkY=l}VwZ zLwcS@aNF>J7oVX?1WR(>_+VWYe`1v(aXx*@kbtnvHNeZU9C(yoM(?z}NqSvcXFKQ2 z(AVhk(k{F47_@y9_Do7J%oA>am;d>&%S@$4D86ozd)vzo4sH^++(XMc^iS`?t`-2- zq@fZ7#9AQa;xV^YJ0@SHlxh_f_BowkPVC8hV3bpW>_S-Pz#kW0(`%K6O=Qf1_-b z^WA!BRu9cx5%VjSN&Wd7&JxLzUP&1vkIZX%QyAl5zIyGN3Lq>V2L;mxTi@|J_3Ci< zT4fksN56)`MAN4zO(Bj+gGqg}({x-3gzFbZ`-Cn+C4-w+Tc^4y;=1cj4wxhg592^n z!Ea{u`f+fn3BtuG^a74$-&`%QqGHf$08VZ%v#8u{FzUcGAgN1+)suc}s9BSb;m^A# zY4VDRVD)k4>KUe2xLYP(cE8#N9gLJvNI{`OKc$f(hUCMQn3mgpx23vzg{%3{$}9El z(7Ylwi(pNCFuGydX=(^v@1Ufc@0$twboMKuwOb9+tZg4v1FEFd1YJjSqCG*jWFD-* zy_T6l+gZQ8>mofS4K{u~wscm`nd7jn9igS3yD+S8@!Le8vKMH zlZryzaOn?CN79_U2b`hNx`qZBxvV!}+h^g*pWIF2)wWu}b!KKlcX{v6_fE>Yc)e9N z7^c)^o)9~Y|Ec=|#uHl9Ya+{E}eDOe&*1Ezry;ALc#_!=P^y%N;e z=jOZD!%nvkA+Tx$gPtT>sGZ7Yw*=yoX@J!gqvP4rqnvzJiNJAN4X$r>2yGusTBKR2 zX+sL=1Sc$i!;K)rA%}@^R_#Sls{RJr38Wvmw8E{M+JXPL#08nuo3m+n9os8Ewd#*r z@L_q)c|}$s0G-%|na9J9<2QI!%8mf{=%!Unp5Szym&nFWFk@A$lY(s3x7AQ7fgGnU zaz^tR&}yiEWH?{JE3Ae9!y1QLTSXm(PW&RnpC{bi6E+h#gzZ9jZXv)$%aI-oYnZ8W z?^n8?Hgq2J^Nx^rhf45^zty70?Bhkp5l9esstBl|{PwbgT&0+rZ+?KsG!TNlCJDmy zSLPkJRfa>&XgLYV=G4R}7#ZNkxbCLB&k4|CFuVnLX$aWzsMLqq9~VL+F)ZRBHTKh3 zR;bKOOj?n)=2(ns?mO`K%m;Z1p|CXjh+lTNW#)_y#3~A&U@+@A8SeuP$XU&o_9h+0 zf$h5Ge8&Kjx#7~iM_)R$@gg8g?4!kJ0bj{Z-;!oQ_jg$#2BW$Kz66r1HtgXhgJvFg zeVVdHGZ2A!FOTJtH=jpi=3-orel188O~Gyu)NOvrSf=#$WG&!_;tMvw5HHEvA-n0E z-ThE%??TNWF&%?#bqcQ6q1Y&Uvyr?W`pdcrZUWq?dfhqDoUaw>P0QTG=cN2mNqh_teCf^riZ_l4lT$ySpQRG=Uv_{uxgH_)4LN z%3aRqS(q`M3Hv=}>BfY7+|r3Z<=*Pam9WKh#l*-GdA{f|@uGOW(44UQ5dpM}pxhy6 znw-*e=+PiuUZ}9n@jlOv1xB}m;@t%bh6^|YPQZwX)=y$*qLxzB z7JE_UORGg+@2@%4VB5Gp&)Xc8U#wd4dUA+~i1J{w?m+D}<|K1FTBxAa0bGfJe{pFw zpruslK#^)Z(5xXfWb$?!D%Kg=o3{MaAKUKIhK1&JWxtgfBra`36(HI?vcBzbThXLJ zZ$67~y#ND-c=^-o34nPF$R9fi9D#T1W9Doy3?G-+|$aw^quyi3YS7 zkdR%~sVcLXBZ1RJ!tYKbW@P+`r)NLBwDt_cT`J&+^=xpQ+l&be6XlBvV@3woXq`UGu-ilRU zTp9rD=~y^!T1HXh_STETuF98A!SS0$)Cegn_ObPqUw@)GPpPqp(MnN`=vgFmq5S9k zU@&KGp93(kx)eiD4C|e~`j6$|dzmd4AC!zuoO7cgI@!I04Ucrz`=9^vKRskv%uyP6 z_P9FeT74HO>_YAR6j|;XJ685Bm)~igq$zOG5YC>+rYI%9$cl6=IZ7Q^G zHQic`g_cV(Hp#AhZ!jc)GTb`^b!!UbL>f|5EiVsDl6(&dsh!;#N(SK)7D6TJOVL0_nNGZUg4#&Rdgjb zpA?3SeLh0Kvp^)%N2Pn?X4;1+;ZHNSOYwN&|D6Kr#M@$9$RoS1W8$M!?; zp989=J@)=S zuf{bJ77dRVZ03Xg_%!jnORImZ#7`B4+);*T_4U@S0M`>qIiQiD_<9Ycy7bjKz(YZ54CVV^`|5G1JU1MOIeWk6OGsrBV0!fCD^RzmoBhJL zD?i68=cbCS16uIys;r{l<)O0N={|2qeW!Asvy|-)^P0h;=m&U4jxUU%#CsYWrlj=5 z2_|3P;4&+4e7dL>mwtD=BXP!7-ELBb*Yoc1uhAp24al1qtF(!WY9tRy4CG-% z8|!EeDu7`uy!yoL+o03I;}NQNawiTXIwyW>wVM_tm_4Ju=}kK~&E!D`-y0onYvGxv z3}1bQa{Je0hcZY3)dwBxZe#a(<65S|fTGnS zvZ0YfJ{ZqM_L#e`?yC;VYe8_b{882HxE;BlKJg~n*lwd4F2>hj*>%@JwG^UPym$r} z@HKSQP@8MD#hAx!hQHqVZI2XHC4W^3dj({64whZ`q<8Dxb@i-S-2MpM{x>l6#Uaja z&UoxyuHo8X3~zMg4h)Ru{e0p2M2`AkLA891aIO4R!uy_`28#W_CEe^UB1l>Ja<0QP zrQ_e%{%o%uSEgsLo|@W^>}m6u%AkPP(f!dkfA75WVfeloXjwR~6kAK=CKC6wb~cM;?bHoX+T zg*nxX3@QrvZxA(t)G2WQGGzbW?yaXsV^KuUul%h8FkyPAng9DqulNkHyEe$_E!6#_ ztX(5?-mez#Azq6r$y&TNr5YchnUT@Ax(b{VDlMvl-{0hOdI_@UkHlHd>4{bsL!;x5 z_L(Mhnoe1H#)Q9lh4|9`T5Rk$OgRwZX<`#9ZNB&Era5yc@GPKekv*OePSg9vnfNKI z-6W40jOxPj7RswEq{9jYe>1I-4y1J0x+^PI`xV0N(R%vQ#aQbF72)+KhpYbf_wc2p zcall)DDlh3TV=eH>#XKIivl7d3);1+*NQ`u&Uq}}bpAVjPxL9}W6%6UVPE$WuE10v zZ_cg0whj5Gw*hK3@ES7vCD0wbQa&?wh|k~A8w;SkC=R39^Z@9HhQsS?d&{Y=b_}*k)@mtAjXKk9U3@zp$9DEPFGw7x6y(5YO!&U{U6_=g$JvWlJx(iA+`u!Yr>r|@# zu{BbHXoFi&hze*LckmF;UOjeR!Un_v@9x4+x3%giX`Q_bK9xH*xL^wU%ZG+Ch0ALa z6UyZ4#q{$h)G0u=z76m#w@Qy5QT;!P&ODIm|BvGzhDmZ1HMOBASBKG; zIp*kaCAXx+LWvl2--e{LHfQI|$}y=N-<%<5o1+jN&WzD4=A3(cf1lsK`bYEG=ks~L zUXSPV@prlu5kv^0E5EwhJN3a%NZVU9`k}8WR@rUr2-uv)iLaj6^MU`O zCgUyKjGKx-`&{zf?v(#$^Fo?TI3vODXH{dh9+8W1QB3uE%xGe2U>S2$b#(z9HeP#) z=7nA%Z{Wup|9u+QWyMBlqLB+}Khu8AjW-ZtpK(BY8n!B8U-kCw$2ncM&?_9`kHXjI zd_F|g`Kz{q9`S1?%KrEE6?n6N7@S4VF}Lb)O5+kSFDDd?{JU6xK34&jvM5#g`01qB zzMw|=4~~Eu$q*B1#D|M@8;UoH$c-!ez8sT-OE@kBAzOA(@4K&@B)%ut=oz&ZyQyn+ z*q9B_^<%=APL%?Mvbw67kH2*;FH2||Y+q^UJ6@1CGo+UC|Dq1|GS}HZ_vlXNw0E=8 z(kzAPJah_N`dxwy21!mkh&Z>`nycXEkPD+f3xb~q>~|c(Won{W%kMUi?$>(SvX=p> z7~iISIQfo=1&?Eyk;aZAJo8o9$@S1Ns%Pzt5EW}bD zW=o;JWG8Lx*#3H;ASOW*O?ay z|9*Vjq$p;<-Nie7&N?_6k-jcc%&6$!#SF?me*L4ceXW+CJ^b>L#gwK@OlGd0o_@Lr-o>gCh$r3?ACs zsO9jaub5rUKcv4fZ>pwspc>afo5sKOw@9ssYiS`KaA5J;pHvRUG z@4PvHZiXri(;};zpI#yx&7II*w=t^h7rgY$KHnVSN}o5r_kY^3=Y5d4L$~yid`P&c zApz_G623^~WO_VZ8M-f%W8VkIZNhOJj@{oUdES@bwY1^p?%ox!FW7dO&&h5d+#c6N z*dP}^hxpd9P963^5RK*|J#Hr6xYP{mUW;7YlRsF?kdR_?h#D{NP;_!`L^ZqXfiGkI z_Xv#S+5iO&q6J(6Wf-4hV6^zn$moxV{{Q`>MeQS3Lt6>_M!nV5$*NPQKK)Wt6nxYH zg+^?nwEZ*fhuKU}dKa6u+f7M7=-j-g`%E$l{!paGcFRtCM`S@Zl+0g2G zch;LgT20~ANPC+}QJYs40|PI<>^pMf+%Us7Z4%=MJg)m|*{rZzX4Uy4@ZITvD>63* zu%oG%7G{Dp<47FID%CON#Sa;^Sa`h1bDEneZR}JdE1ruFeCB=B&>P2?0J{g|o?J_z z=fu`P)W6jQs>XJC`Fj&{gV1PHX`btM>W?|;{E>mL8Z}Tw7HTu0_u4;*gC{6wtC&Kn z^-YhI40WxOXWe>S-FS?p<%Cp%EQi2jz@0jV#S8BuQ=VG}-1C-_fGSHepoPcVr!KKg z+B2II6BC(ll3*|hiD*P910Uq2oKOU<70R%s*WuKeSSF^{ih6=^#N*V{{F zAKbK&K>v&6UR@r%@%-9v8H4j!i8#^D7Svb2#!7tb7k#|ovi6`)p({T5@OL&!}HhKh5~>XFmLqgbp({uU=ywt?xC^|GvGV^7@Bd>Ot&(fGSvIFd*wNCe4M_ zDJMlS7MTFpVzHFyNRKeEGKV>{=T{ihq>f+I+iw3l*l}<0_ot4}uW)b39}GTp+;M8u zV%X$d#D3$Pkm}=}&+q>f%c!={8?-G(33(MOq=X(Ex_d|W^ypJNvj~5NwHGBiPTd=N zzDV;>cU3s;nKhpDGJ_6qo6BDFPt5+Ym;E7+o;g~ffb7LWVe1GD z7w46W{m;77o3^CEg)H2&*zl%#&!F89u#Db#_vrjJk1>|KkNc%^^JdNnT;@5>-F#h*sFzK4v1r>aG+`FVx;ZE5m6h|>0n6*s1gl*_jg#( zHRS$jV$h+DP9@_r*c_0T5bN(qqhV2VU}DSW(4;x~21)L_OBbe2++^PXG0rIGuG#H# z%c=m=r&fb#&h$fEMfu)H_<`hg$f4D5XcRlHpPLV43=B6ucJ|ri!s$A%71@qXHnq&64mwv-IKLDZz&;8WLoRaZcoy^V*CmO_Nrlac=ZN z%Ctr4yD#`>?GOJDQ|}o54BLgc>9A)!+72dcm`|Bc9nE-(j%J>j=D+>a6XpJc-6TOg z8*^_Ck?_=Np-<91H%LE0eRFGsLbzzSnqO_%V|=F2;QprN)cVM!7R;jog)>;P{9wnf zbK?16+iMS)s|$E^iQ_W(vmJFKJbQfcD`0qGD#;YaS2MmBjTOTEe)g7-(YobycLlP7 zBY5KF!&%b{iJNvI--1AOqS+qhwar?Y-5?utH#?!rcq6it$$i7$b;W+l0moVET$F%ChN3I^P|EK}CTV~9&NbW!StZh$i)KBJ5 zlz|O+K7+bj;ROgUNJ**wt`BG&*(jR%=iZ6m$73rtw@a{eTZO`iaVf*A6pf|xf9Ky- zKk3(RIjXmJ|1GBgrBC`8m*-zkX5Bd6cB|$<&A#PNXoj4)##OV9uKb@JH!nJ`$n`$K zi>qyF8rd0(t>j)Yjfj!~ZXF94m9WI-qTjw-68_8Ca!WV6^y!O+#Pk-AS86moWYXFD z%nn1IhljC#*J$Z0NRC`O{@uQd@cPTsvG1kxF3V-MSAUA`A9^-tBRbaw&a{u*b~CKVP&ko?Jm@|Gc%WUPcd&{bqlzg|Go4?9eK03(6o#7ajj=xgwd%_Rkj)z z2EOeVmG)Y0ZY?<@RtxuR*u@RK{6jYuaEl!seyMu3FsBWvM9R+M@ZL(%6txzO7K$0B z_J*eSClU$5#-BHTByJbqcyv=H0>-Ek9b6&7BNKVWLe-y5B|DgcNJ_%tjT(>d3a&p6 z$NcNvvI*0KvzKSxKQFnoPx?e=LzIcqaZkUmm5Ej1FUj|5ufQ>wH)vAv`$@vrkqetL zg3a1Q6FZ~YEf?9P>mD~Ct;<)>F-LFQ0uZsEXe%J_ZQY*VgKG#yLv69+JARwSlO7L9 z4`S{0uj`x&_VVe3Ivs?aOyhX&Ysp zW0Vk6M-a1Jl?HnP12O+5@7xUYL7Qp!!a$cAU$?Lo>o8jK;C<4>w#1l*-+XsAJ@aqG zR>0FCF6MzaH`%vE;dGof_u9u3uMTFFy8hM0+L=c{;RmX&mre6Z4j`ih9H;MZiZY7< zDM?$lo6XxdmyiFwIzoP5>uKS30B;i=DnD52SiG&_CNYc;duEj-X{_|eE?1jUK-7fV zU$(0qM~lta;$40`IN3FA*~u90lk`1igFW){?>lmOZxrWVlDel?06= z!Cj4dj+H)!%NlK;bZeh15C75rBONd`FaK!Wd?L&7qH7MC^l}Xnh&LIX9jF%Fz269m z?7eIk2_?`@q_M4Lv0#Ir?jJ=RmLjROF@c`uy;yUz=Ctv=#xa7o*s*kV%qxB6V zrwz|#RGaj^?Uq@BSxQ1~G}26BG)zHtRX(3rhTKpeTKw}taYDgfSxtf0sb!R_(Vs{# z+8Ng^Uo(u;Xn#{TerUenC^KE3_D*hz?Cah4}z#W{O zP%gmfe+pw09L?RLLBLW*Kn}cHp|jk|wTsmeG$tsvHcpvU7na zY`sZFyy=2|-LMnjY=lmxAV>;Uc2QHF+56vjcAOPB8+*poA*oAWp{-CsmFehKLPQ&% zv=h2I0~AdSJPOtWe;MsrGO?*2e@JNMg+l~1KX__otMu8j*a%8zc**mdMpaWEyrK83NW=Y*L za{_$=JQ!6ZC`bfcC8F3#Xx}(=V}-dPxPoW`Q6p<9kVGcnz)qtDYx@BegeownA7V)l zq4;X*vtWfRc<5)~gt3*6|93Kr&nsZeg3M6|WUD_TafDz`6rB-<9We=fLlsuJt7Cqi zt_H?*1G@;!P(i}lY%(a!4VZ@-7a9=Y;iw`4`&e$rf{FC9t$SY1>6mmA#J2t5HW4UL zl$VH{0`Nfl$s*G8#2wW>L`G%prs72kGGJXa;J=g)uA$idtj@)KZRlfO2jy5p`y?dspCI@l09u; zu3>V(yu4UhoTtL+r`ed{7-d!kl6u%^pK{jE_ix1|{eWzN!O3*W@3GoqLuTBJmUk$4 zIhAzx#Mw?*c{8AdAN~X`_VMr6zNXH*>w4hkeUJ4$a)M;xg(F2shE=I|GYC_EPH=B3 z1gtzL1_}Cvnx8LvkRv3v-2#7~$UVYz%qrLJ5VPbl4c2?p9zIp31mAXy5cokyy5jl! z9p_0CDvP_>^c=1Hvbe#i@S?LNHUL=TM4RARpBq7q)b5uo0x$i;LeICmTi_7>F=`wu zL}pkszea(@qmi>J_qSX+9rAc+M?_spL=tTly=1b#y6;jbhtXvH{d8?a@6EqZ>-hWW zQ@UTGhC%3mPC({c`KML^WiPT0Sl>Z#(h;b~9YMk1(F(hbN4-+%64Nd6&;CzUAN%~; zQ%@<+P15SH8Q^uKeo>$k+@?4Pv~xB3mN>l|P66p}hEyEUL#P*{GgXY7vs%e8^tFfV7&bM?+Nl zsee1y@ zG2VyI6AlnJY(gkw>Zb+97o^LV=z!oWlpcmkPF@K&wzW#n%c+SQpC|6F?&Y`Nm)ne* zL!(|ZwRc|idSwj^%yKQJ@#0JYzUyYWq$m2X+X>b2y;Jg-9ykMoxCojTWbhMQ-sHEb5e|*N4$i&uU9=LdWblHM*65vAZibg z0`0APWGiw4>g4kkSSFAIwd}lDuT952Qxs5Hw@3r1xQt3JMCQxA8+dM~3fiQXR^tZ* z=cok9K?b%YcdL%&J)Qo0s3<1JA!|h{y3E8NUPg;2PD4Ck`kVzy3+)u@cfK{Vi$b_t z-;bEs=};0JccXE(sDOLHnocz~xs9nSMNHCD2sRiV4lY-kai-Khr{G{ccz-FN0{PP^ zH=BG}IquJ?rTLbpjr{%{&eu?1W5R8-nx26c( z+P`!X&lwzduU(@iHaAcC42oezP|WaN9te}wInL=Pb7xdLl|ocIxs;@*J7nB=c@eoB ziUk>nazVTxt`a_B0$v{dvi@F0XmgKN3N^X%li;GU*g3O3h+60@NL(ufdcreDs^oF=Yl|uSr72rN_x|wq7$>RQOZa%zK+Ej|ZVSnQtj{ z7lTN6I4#OQe#XAmOCAiSiZP%l2Z0efn1nCIi|_w*bs}ksHBzM7ij7bXppQ`>A~Y}_>~`8rWE}Thl2!3xdWP{}P$_S{8g*T5;s6l4> z{m6@oJ6}Rs>9*xX-bB4#c&Opps|X435NSad29#t~$4~$9pDGhDnb&rZf42R$EoA4n zLG)UY#3iGkcsocOZmTa^nvhq|@K0EMt0@EMs5J|%&k{%Dov1p^&&Tc??*#cag_0xW zzZ6{!rW4!+Y&wbUF%H2R#IVtS4f)Si45E7dS!B@k zDw3SYz^0*nhg$r>cDlmT;auaGTt+pNSEMGV80KkaMERW!^90n*LgByFhjssgp{$*(#gh9VH^jv7O3P>&e|{oP}%j_tEgDxM0RHxU2-OL^8G zG0musy@Lw7`b%!dJJEo zI98XI9+VGyxD84UZ^Z zPkMXQ5d1heU=e#emn6MQE1&Z_*>I~mK*D^Hh~!$tn}Y~@kY#hA>1Ck+6Fzc^X(v=W zY~;9Zp@hEv^O+95Js4N>D|z<3c!Zo@uP4Bxa=mhn#=yb!j$HX3o*sM9GYLjGt&4@P zaV~Yh5Z7r-xXS|9gDK=7@Op{oghN981eB=Mbh&2-zJd2`qwn0o(K(rUro^Dky%b3I zW?Vf;fJ!m39ESB)bpQSmtMb37EnXqY_>8S77qn0g!liT%ki$51Re{(qQeO(nRiJXS z12S)G#E^ZVXyo8w=|$I|IOGi4cVx)M5`phxEAyyA-2v_+9|ne>*K9Wg7(elicUB!u z{z39+<8L`uEDM`4S<0&|t5lKu>X9(cK(XBJIZ7K&uelRZr(nC1MhfimwEv~J#_4n1 z(9@XBi_HLyAy**`6uS(}PyM)bZ!-?px$AsFVh-aoEwtKPbkkPI>sK1!6z`g9`rXkC zx9*ZLxsuNymo$5vdPuvuTXM3 z!p6y&l6uV}3&Sr57H);$Bf%J}s7%v$@$G&lzC(|3oE2l`^`;8Jn> z0F`aywo0Gn{8x0)nDq3M(Hd$p_i&1E`~o7L+$S(+X6t98o#$a|hf3d`AzyEoiU$45E?i6hj{XMk#RxgO-~X8^=Gu=AQx z;Aax9CF|r>hEdB8pLA3v?wImpCdsBs@L*HD&w!az07C_aF-RO=q=g?b-TW9+yz4Y4 z-3uw_HqXAe++_ULs~BuIwsA?)G+!>HODZo4ASy`U9thTH)V_RKvE^@2Ty!5K73J9D z3k6|o2M~rwp!e;|Z8~kLL;x)rU-s1*H5xc>pqio3#DPU>m@rrk^^>N>R&_P8eI9cV zS_3+DPKIaEuZoM^O=)4c;TThw4UAQl*(9*mnQS`oF9^bdjJD>^q$LW)K#R^Y8V&BO z=&Eg2Z2C|O)gzg!%)_S3%i75;&}w}KksGVY+%wZQ0jmap51U~?5joB*%4>a>WN!4mKP-K_?2W`rFL zQE{1BDid@BYy3p58J{rJ1FevirvJQAfbl*sPN@XyV4&j?8gJm3MBsL8CKx>f;jxHg zmz(8rnIIPaEw>?nh3a6g{lOnb)@LL!(%c6T%jjB~1Qe$mhihW@HLmHZ2h`^8riiI&U`WmQmxfcar9n*>{$pONFhubFsC_Hv^Ol;oap zGTIR};gVzM17@_L`v!|UX^WzJS3>D%^ks$LV+7ej5rgO@D_a-@0>r5bG>|4ixqUvw zaN4$}P!$Me(*oI-@LC2E&!~XN#LHa9r6r-_}tD#SM8;Cj)5(gHD>u-1_ekmtqC z&x3RRLx8vh)T6ub%-0qu8H3|m>4N2qzxlmYXC+=no+3!PkAXxrE^!3KHhvErP?TGf zoBMxSB+5j@w#+*1;@`$)0c8o1m>4_3M85h^r;1E|8BB>b@RM-M6s=8qT2o9-ZzF>* z);1^^pn#p&N3NF82Ir7|=ggk~tTI0bo6#B=Yv2yTSl@I-c5jMO1yi9Fk6`R=b{}i% zQ3YSvGH;Ye^46)W@&$_#+!K@rn8#HVIMF9?8$#Uu{XMm|V^n_&XA^iv&rO`b{

#)K8>Xa@rY?l-~<ob8wK5~A!f4=X@Z`w5JJLQ8HqBuMm0;0CrF zAKFP?Vc~t>!6l#Z>q98e36kGF=#;ijBoqctLd34fDYKyneXvy^P^p9<?lVGz@o0<r zs9~#B74VU^3f3wC^V}YNoP*$zluiI#s|nY#X;#={{+bgunsJPpDn<3Q6p?<D@qxVz z1?&D8fDc*T>DLcn%ReuM1*B*7NSMx`|2lUbNwps!P|#{(^A6GT2BzR;Zz9d7CH5sm z@R#f>FgipUc(+sC4Czy`AD2B5v9AG=2Zp4+ylDXdlV0!}`Lv&W1graGig{3v#kmYN zj*htp39e)?Jghv`pbN31GJ3mip7_&(_0QySqoMNS*UXMSy+hX*2OYkz9dxE$riAc^ zO8-7p)_tQy5ElcmW3K?1KY~%EiZIhAJEk7NjnvroQ%c5gHI(~!@hRz~=IH3dZU=G@ zsa6pvqsAQz<B7`}%dA>|?@(~kBUpjaYbBa;=TuMT2TLTE!B`{xS$7=vt|}!NcvY); z_`PzdYnclDgFimBGO^LR+WTG)irQ`tEnW*y!7=1yRga?a_IdAtOY&30$jtot?P%wx zL(`9Q4MMi!Wr0l#hS3k>(^hziAe>#ZuaFfS?#(7)vnw*sc)7p)(8pxSG1w0L)Ef7} z)sh<I!E6>ZFg{n`<)8Cc{XLe<u3s3gH3+FE2Y?T#!ySu-^&?*c^}Q#4yo69y6n0C# z|BTRid@}ey;GGzaRJ@yWC>3sUYLxUem}Il(^KIAe_<;<`4fFTMuMD^7BpGN3<o%M} z0D02<&+D6;=Z*P7s<7R#ZP#t<(+gtPEjuw?c_e6Fv&&>tyUft!+gItXcy3D%&cia3 zpP<z7_0T*~Cw4RS&UR_Ry2=MHzFI6Tr1qe5V0}$717bvW_90qy4!3&=2M0%jb5Oru zwPF<}-^x#3|074YL8FD^$l*pd-YyY)RBKX9cZQl(2qlZ4U|F3Ow0!w+o8sS)af5^$ zjW)%XUuq1ht7XDBKYqtOJhe=!%rP)=n{V08K6<SC*lQvI-22g^y^L*JsiMm|BC@Ql zB;&#h!e5#iFy|7N=Z-{>*uxZ|-|mCIrs<Xo^}n_p1sjsIKHX)0ZDuP+OOPeh_qXdu z<r~y{`FWMv__YNbbv1(l4L(#Jq9lj$^+SxXL3m=#z^d%4=W@>iwK5XFV}g-$aU~5O z3@mhtwE~<OpAxKG)9Ve>6AnVeS&#}ILpHbvHgYoP7AvsJ0`vig!lVCG3YHCFgQ@cl z3}`J|zJXM#eutTHzMz|8irV}@1koZ0@keP%SAINlzz~C3#BKcW{p7IRRvTMbQ)9f| zfzU($zd`Kse?a6lLyY>)Knsh?5|Yq&<|0SFq@l7ecy}lRxa42p?}j59Y@PQkR<>*N zBa1+2h@SsHBj4JMyl+T4&p&!qcX5@jg%;LG{AEz~Y+(Ohe(h`xQQxPgX~OMZX8xGP zT#LP=yC@>{W(IHa{qgVjiXTa6o(~xf<JZm@Ri%0R=J-fU#OWF1W$-bbie|`_nrS7% zK{s(yJWJ-46zR9t!<Ucih9$pCa-6lq-f9FKzgnyqFxwYrF<Ex)EK&y)L>VSX99fyH z6tr;c#x!%G_#ry-vsL-y#0VkPLB#n3gRI{)4Vjv~<wCbqz6|9U+w<O9O1U~mI-g3; zvtKvie@glQG2$(Kz(%!n&{3<h`|`4Py)}~Rn&H#6prh)u(Zn^AJ>5t>fyj~310%}e z?{8?)oe369wJ0O^DAVzp1iu7tvCQGKYINPW9}89H&J5gw>$2)Se3W{ETR6Dlq^#Xh z1lliAbZIx<{uO1<=#~2Yb-nsz2AOh24jlP`aKQuV-8r2|mNEgC%mCLOZ!KOD2b+bY z*CQeF<5o&hn&$|Tb$^57>SLUrWkuS7*ajyF_k_1KS)+YY?oeVbxXOUD5j!Q$BTX@J zKMZW<^%UlL#RO}oX~8p!i5<NYS1xFe+)Fv|CyZfhJDUbHIGCkrS+T?a1G0U9@U1I` zrG~9nW2ci(%tvxI1RP(IG(xQ;q8#)wnk@O8Cl9wrF`cy{2y^*Vqg+i@h}pib>H2hF z4)k!g(fV^Tk~2HYH3u6&$<K^$hN0i?HSDO3en`!BZLi<=9Q#gdkv7&KGf0#N`YkZG zQ4giliaL#dP^RL*<<mQJ_*{w$Iv7CF(Q)X%l^-s`sVIYAisjpdsq)WJJ8IlW_oFf< z-riwMaWKvy1sks0TWqQnwju-9L`!mbWrZr$V}&D6gX;+L<ePYObXeJwf7HYystIz5 zE)LIFLM(-xxU09deXq>1U?#9oxnX?)Jb=c3zNzhg{pxn=nxVZya#;;o#3$pys^vI8 z!D`EICVs|CY3dYS(`bRZwi~t*I7cv^%xXMm;^cb>jocnOVz{Hh@!h?OpMl9TO3k!4 zU0OWj^%PuFcMtQ-owwcJWVQYVu!r`BY!+xHZv9kfZOIi=W<IS|^eOtS;k8zA>p$S0 z<HUAn(kpC@^uRGy=*l~f6ou2ITOHf&UNd)7_^RBK8)IS{uW-#V-iFbMX_L7_Cz8%- zS3ARr%`O2fHgcmxfYgY6WwEwaDzUT72<%>Y13|pCh!x5!*gcz?&{`+OyL*5%*<&ZL z^<p>P@T$d9%KW7EpG|LF>sJh8Hy0j)b*v&*Sxe>WyGeq?j*MqhULahEMAyHEiOq70 z>ZI7vXA%s5U4c&C{-^0aK`+DAb#3416zlcmr>>3giOM+L%n${I``R9d$21KWWfsll zbJkSaCOcpI`p2BMkOy@+W(E@%G11RFU<J2+8lG_C|Lcd8(2p&XhR5e5ZeJy7upojF zk`)X>f>h9To>$sTyw-)@k`2RGJ!4l8pSIINNTnKk*FM~SI@#{9rhmcAFsyq&Zu3t* zh(D7Kd@zcs+!flqKT#!V9m0RhvL(Iw6WP;YrbRzc>jPwSxC63l=;xl!4~7{)9IA}? z$ymxTKt#zSbLdF&4s(dH$@REs9@6oqg0(+8%sde<UFX#!5;;qbkgw9QTz)RLpdyEr z7>!xFygc-DsuiomUUd^+oiW+EO@mIk1qA0G-((^5<dggBU*o<WIUJlcB6#*;Upior zy3E>48>=;KEBy(D?QI^`FIK8H?)788i~V<21KR^5OV%^iqnSM5XT2M`P1U~2M2y0e z7(-3g&-^9ny!)qbpz6uFah0vtgRx8jN}dUA@t=O*U%Gp7Q?`l%0{|<i#~`%S{mZ1> zb(l~v)rS<zlg}COee(5W$$>kgqfodi-CV(Rgf?-bGQx1{B|^3^x4q}vb)pyK$bFlH zp*6Jn)Rp}ggF8dz!jqqP)!bx2<#RPk{;fQygDs{uA)-Tf&(LHq_jx2LrL2&~REi8v z8;iT(=w4m&BN}zKb|}`k(LLwwyQwwz+Ee3qMV2Go!arX**xwSd-BxE~Lf9W)$EXTh z`xy7=%<z7xlygg?Vn;4s2uoby)?7+ejr8|gY+)x}+is|JGQEd_+3)m6eKs(yuHLp@ ztc-ES&y4P<_vHIM=~uJdE2wv6*W`+>xdUqF%FQU{>jDmMR}R8g=JY*3_U=1<vU@7I z7eb@iMo*t^PP1mI4Q3FHTR)<;9qxAr>sR+f&x6ykLJNdkn&r)vtUu1MDQC5VzQM}= zpq<8t%IL2-+i+vB>)V^F*Q`}}pY7V>XmcBo!1q8%g~ssL=}Y7jBJ+%6nM<DA1~A4K za*#fW7B76c_~5AKD34txvu&OJxp`O=w$9kF6M@@wwfri6uXo$$u>vK=Yd(w1<(KR^ zn)$VZ^*sOvUm;OB4pC`WNiS)_k)1q#vA|+^*u|U4q>0@e<;;7g^|0-xM9vn@`NtDA zJ<O}R78Z@hdvjaiqpOsl3)ZFBfFyI^z$Kd(XH>dACS)Vp$m>&wm2=O_rX(xUe<Hvj zTXt8+%lxU88kAy)!}Z_y>`o)s%?&K!5oh<`_06iv>C8Dqke+5EqC+^laV4*j+LjvP zI?)ncF_L~2@O>xWeozV;bz*^qFzV#@|N1<5TxcVy*C~s+aXq&3U1qTUYR?2;IrOuO z_qn0rh-wi7@$lmHin!!6e-Q5kwm*^Wx?a9G3mYN5H26?6fY@gu#(!ML^x<(Yw{Du? za)%&@;=N?4NJH{U%Z{3yL~zNV0!jAuiF5S-fY6S6ECQPl{uTzNAj0Q&c1nOfrj<T& zpn$NO_<Zec)&;NX(MF>yD0s%T{pa3d8A8hpFx|WA`Jptzt^OLL#fuOW<w5h0ch<6c zq}kHO1Bl24qT08pD}URG79c%kx&;^O`|{;>=q+=Td~Cbh{6w_#w!zcn5SoytQSu5} z_>Q|Py{|0&0%6Z~L#W)li*Xs9jmFkX<3zHZNYUey3U{8liFSmY7InY3v=J{GZ0Xhd z=E&2M<X(^It5#lD_P=F8GVA=o;a}Nj+*DW5jZ#2dY<p4C1~;SrTI9LzPa4v4nhmfh zP=BxjEYsq2)}@mmS?iW{ui4o@oY&i57_(9ENFy~<yWSTOWI)D<hk($<iMMYV#|sWF zQbVfj?;8cQ3)%)2q3?Ps6Y8&XZq;m~OzZCNaW55US?gHfI2%@H&e7*Rd#>Z!Sa;Y) zV-jj>C}h>ArKT_b#LcZx2xM`x@X4O{3-719o~<Nv8G7z4{+8X*r_rHLF0c6(+-MgO z5*O%^<h?o86sIqqa=JJnTqm&xy%pz2f2H(Q&$W&L2>ieiKmE{o8Ho7XeSm#azy`O0 z<C-AQYwv?z9Ir0)w?YonP|!S%8#07_EB%&D|JPr<^#%7VT9ne|>#hUHvd+}4DQU`T z?*_@X#)-H!`1%BwNDVjo{rzQybaV!1tC5>q@-8?pm!wjRK=R&%Dj2a{(gHRky*uD> zZ9m_%XSCdTIWpz0Jz|vOW%KdH&xxeOBp5rfP5v3zc~6GwOpNT84)ggIWfmEi?5dlw z$A)gwMnoG`<?hgwuXOJJx9e}5c8j58Yt6jieell7H`viATG#W(*>kRFx_wR%&D4|n zARhM<x+Rus|7AoxAjRGE)a<Xt(kiMYzbc_t<d9Ec$hArh;VvE6_1a+?K?97GT^3h@ zm-R#hY!4!kH{|o8M60Cn5vQY?n|TFQX_tI+UIsp4zEzpva$KbYiOf<h?LNu28tS{| zZ%He?Iqi?O3;g9{%G|bns!o1X)_-TcjClxdE)I%;e?1nAHg<jU3cF0%hjZi1ll1nN zkq)mOt}!5sRPhS$^kZjBFI_y?)71KD>Iu{9O^?Rc-66Q|(Uz>cu~dHj&Q2}o#Zbbb zhmSHufVf)!kjka34IIa<;n5#6Pqvn2W{?PgMy)l!$*4Mey(Vq!x%a(vLKDR{I@#%u zXuot_&Ol)Np&GaEnrFkQ9pKZ=z?+rmSok$RL&ooGrdc#R{^~m`olsxTOOGBrPmij# z??u6Rbajn==C{6cVIrz6!!SHeC2`K!^y<HRF4(oy2VKGF8J78z?1#zlYj1p)BXmTJ zA0c#4BN?<B8G#?ZFZliL#v_W4Z$48|WQjNGFA>5gi~m~soOyn#UiWE34v<S5hba^~ zCVA)D3GYo_kpOtT0|@o?CrOIU>DtTu@iX9JQvs_6mNEaz7kwyma!&uPQT&bPz@h;W zcg6LVMT9NUOhyd>9ovkKm(3O5G^qCG*=#aAz;D!fX<0joRsoEjK@0`&4RXz{Y3H*u z?yq*GiUyq{E#IY8KT&xQu<waVq<vMRjZt2yMqbs!iUX&=9qQV)*nFu69nq7os_=u+ zH$B1H@`(XGhHdw7k%>R&)f0<7hI7I)tQ>3`aU>|A$0%cw-12_?_2x5D&>C2mm^c{r zIraz5;`g1apR6B`;!P6jv*p_sIUeUDmEt?j3qn5WhPUw6xNaXVUf_f&Yecv7cDXiG zb;tn{D9*1&?=R<A2|ew_D8(=izsc(757L%dpQ(GiJwtKPa)Gh@E;m0uQi+J;t896G zP*qw<JM*I6L+@xUoChS-JD3^PoSZ6^!GsA*+JL3;yrRI-^QC$qKSBG1M%wPlOFyj@ z1??jm<$<oh{wKk;Fa&aZ091`Ue@xYffAlU*Xe4-nBLFoW{yf}UM43Q=USxvQ79_De z9XCJ(#r9P3eK#_X%VYFZFWiz4w~id6pxA^2t3`za^!}*Qp4ip6l8Q26mqY?!3OR1l zY?QMw+|}Bllr=3Orr@9t=51RH&)q1<v>S9(yqAJ)0FMh$8kj<KxgzW5_0OxR7nKC? zd@XSflt|S&w!l_pJ<N}}uI)$epJ!NS?aH1mwvNzJXWbQGU@q#Kw?~NCb~lybD2*D! z2?Fde{p}x?0rr-g(bKpr9*pZA7qqa(5D%gW`M_CxqDG%eR(Hy8WcnU)r(o*R@|L$t z?q5-*@2&}{kP+Ieh2gr1I{zkr(+t;@a;fkw-YTmw`U!sH1^u+H1T189D#j)Ijge=C zy9f-z-3l$c)E}{Tj2c{MwR;|(VAa*s>T4bvPvV2|qIAP{>DrD#w+Q<kji&SU;XV9c zxv|Kbr?Y~{-d67lwrPK$%VlPR2MnU<`eB{xlb_;0u?wX~!ZXc<K-<<=CA00sleX4A z<!|=vO|FTl7;4!x)4%=dq3H2vkNK-J8iFb8R|RZv6RYp7)?-`<gJyv|yWl}juu<!> zU9csJ14?TRWeseQMC7mO_2RX4tVldKxmF5eddYEY(<MEj(Vm*?%`BRqb1&8$3j3=n zcu-(jdmt~N^{wTKluHfGDtB#*&rq4>^jbUZBb?Shu)&nH0v=ThpIu6}{H5psnFagY zqWAxQ(SeQk?_BW?5W*20JEtw#72uD8)emm!-RzLh?w5Z5+E?rEuTI}Xdw=w<+qpQi z#;zHJrJ8=2@S-mok;O*7aVHn^QoX;I-aqZ*&;r7H|2F+>u$i2^TVHp^r`u8k>lt&U z@1exCs|6ER=k`=a@V+WuQBw4QDg7FL=RX?v@IOFlIsZ5^k&(c;p`s_F{+Z}P#IMUv z<{ja?g}y&=X5WyW_KjO?jqfTnmitgtf=C9<?QewP@rIa+g+4L<&XUUm_OI3Jxwofu z`oA)^(IQ4U_7{G4G&e4@aKMzJ{R-ipvY;*eO5Cq`l{=Q=R!NV@a0!5Klw)Aa<}+YH z#WG=gXSCfG9#rWhjVk*S=E4=#wW!2kTjTfGjECKSf7y?Zr=)Z%t2<|dbv7ty@&L(i zroq_zwD*f;J8>NMu@jS|xmAV%b|N`$GnFQ@8Yh-bk9@MT<ZgjD+K<2P3jLQG-}z*I z`Q&v5b_Vo%gKb@UR?Ys`OOTKLjC}YL938-G=6}k)yWlZ2(u&;Boml<#xC*xBad-A* zEa7apnC(-dzz%1#w|Io(p~6QkTK`5bg{9tilD!}DXS~5p^d0Mu4X!2dV}lo}tdDf? z_jTnA-)qsEcGu_?%6CM5T!1;tzcgXGpe+vx;UYo|vno?SE%p&Y9Fptw?<;;Y;I6-@ zy@TXfD)~gfdF)cOx}>JkoU<HMh2+=%J?h+^W)_MMc7WGO%HP%WJ#3um1|_EhyuEpC zv;^x25L*^eb$3me&ilP-QkD^~8Ch6**kZpmbo4=qIf}Ii87@(bG=K09<n1_CC3xT9 z7K`MMb9t{6@H`{>H6d<-t|2jINDp#*_ATMwl$sK$FidJ#-y&^8tUewS&EpKZTrioA z#l2@t*owP-kzAPC`EI^b1eV-bZ4Aj3cq#{egx$K2>h-|6mn|i?-z~k%y#>{I5j32? zy}&mI`TQ^M-Z%WYv$kK($Xk94xua1^2slFip>QF(3168svZ{v{BAe4=K(b-h<=bII z*&z3ZY@)9V1=+cKbo>P?_DrGZsk1L(BX=%%XtJ`7mG#z-M!Q71o_pgKyK$5p!Wa;# z^Rrq$d(S_m;p4&d?qG)h!}Vazz2RVK#2L?#;mGbia_gn~3%v?C*o`h;^1<gvmYWPP z(G(G5G4{J#gICPi2yOZwqvT=g_w7S1M#q2sa|U4eMg<QH`>yY;vgo|bCngLjFItu< zY&7{C@5xx>=`CN?&gem*!B}^K`ht<vhhAo`X_~qjHpc~F<et#+t_-34u_+Zh*Bbi< zULRaHVY<4$<+J?en$|}J_*KMDzlFAg9MZ>6pmbs_P!`COY*1t+H+IKxRlo@3Wcbk+ zviR8MC+_->!Ll8(wLIBc5XQYb5sno){Y_q9n#4}yzV8G1Oa-ASMoL-gdV%X9V{YP( z#&;`nR9Y$)$M|Pj0pgn1rt8bMZ#a@5!%WD#w)))pX2K`uLj$WU(4ey9$2a%4c)(VH zzzhc--Dif<&CtF&H}P;D|BYs(;|S{ABe`Zr4%tzzTvtA?zrYY4WN<rQPu&c~A&#fq z5mLF2_`tE|EQ8-I^?1!Aw3@~X%^7s#-e}<F-%FujOD3Eg&WQHa7-&2bLSYpGC`^KS z{7*(#0m<(X?5)y{JI`p)P@(t_UZVm$naXio33?EPNQIutQSl)CMGbv-Q5DK~4&ZcB zZ)Ak1etuy9GI;nAJT^aX`Vxg~C&;Evr=8PX<m2@vzEfCuVdElLuxM{T{-mm1K89mq zVPHDv+huf<A>>u4zKr^-$KjaB*4;*H>dTKh_KtN-B~Y?|Y7l?_P9p1}X3*dg_}TiF z;{yksnxhpa0w1?A(e~c}h7wrPKXfz6QqPcA+@UxX+Ym~V-Wj(dLCcmxO!k3#)$goX zTM%;w*7yc?!a;S8yS>ZB9X+;S6j|MWUrNF~ma(b5k<mhIe9mh@dF05V491IA2y??M ztDzV)mdPIbylK!<c$5xaMuoaysi7zuw;5WrzI!g4)dY?-iFi-^;b?G%hk~!kG)U|i zID}J$IL&NQR~FhgCORgfV1XfsKlFyVBdiOB6|Q|g0ZihhRx*ACCiv;~^0?-WaD_#x zNYY-6;{(P3LhYG}8PwEPr4*NE1sGAXn?P$E*y{|V3S**yIH+~Bqw+2&L5_%?qyUNs zHXJBz#u3X@k=%Rx8e_f<M#pE9!ytn!aKT7K3H1piCG^^Yw@^howCS%ZY<mQkJpPKW zx@m4(41#~aZ&NuKqOn*h$wm1LN}>NLB>86+O>QQVDm-c;(A-<Rx?04hK(X;n6IK!^ z7%e0RSpS1RvJt0-CKam9w!p)-9B_TfI}3h*Juzx(e{?9X5C(&<$`2NFQ4D~{LIurL zux1&lRBjljHgYvc6SrWc*%FL`z`^dM<YkspQOvfTU;vsfx=IURSP8&!iD^MX;z^Q$ zUHAjw0n#hY?I5JMnKjV=ltL?;zKqi2&Y{t9#R57YI3l0N<~ZE6g&C7pi*j=<8DMS+ zE$JVCFb1zLc!?GOYi7%8LKi{a9#gBN@cy*<GRP8b*o};n3Bl3Pi>lkyye}C8^4ZwI zVEsiG;`e8epoLwq^b*LLZXUziNGz;uI_23X&qNkKJe3)RNRYI`&VgvfPy9)&+e%{P z`i!p}3*rkKwgHL_ylUbH3&k4*NF39HC!iE0W7ZT*dfT=kj6wWaX`X0nYKO%{q8|%* zw(RD04^vl+8uhmv_eSGp{IrG^Mr003L?Oy05pQyxFn}qqcnDP7qgcf3{N%(QWd8>N z*HkdZ_khR$3-vFC8N7VO-Eep=+0A2vvGS7FD|>DaN1Qmfjp=hvM-H2r+l=`ZTcI4F zPx&8at=i2TjKKUg^i8pCSWrZmF?$&QueA3q(~f4QPqFciU;HJbBWQgIsO_{}UW285 zav$Z{n#|9@mvtznr0wFnF1YK6|2@_K8p&O_tSFw?JMbxbH+$N%X%^a*PYQ~0@{d3~ zgGPv%ABmy@vO-c~%%#l)b<9Z_AGwpRE`46KavFSzuBEreO$$^~76wZ76Y{L>gd%S_ zchY~?^8S%F%virKFh-2x?Fj2Vn0~34(#zuRs2^(%ZZB30`D-kZ4P<H`+=Rm9#OoOE zg(yLe$|+DopWm<1B9eV;d{yN$9o<Cc5*aLCKdvl}A=dT=b~p+sDX-97AdvoC3ZWrb zw3#!)E6RLdqcW{bAkBlNk`QHgqRB{Zv*fIG7sVV7-lG`)PA^^W?^)xt6qOkGbhoGk zlh+t>TXuJp1UK0R<w5!mw=7s2iL(Qscv=~Y0`I1&Bx~->9lOye%)Uk(J#NWF6x7m^ zeZV(BCvg!mQ6BqjBWmvlN*%|{TwKB+?v4OdMR}!}vHV#+*QE|JOk}{=@Cf;51qx@- zM<_w&X91>hU9;TS0BxnXFN-JwJ)e<oYZZC!`d&h*QNtP)o*B-jG}(Ly`tXbT6j7Tz z+h~dTXH0Pn#*<>Y*39Nu&el-nIAHx8p}dt&Qw9P3QJr0Z<uw7$S2TVY3Kw7u)b!_f z%{O<>0qD1y($9)9ZFoKRhCJ(SM_s{o47s!)6mD;T5Xrx^|Mvx`U+!wx=bg_WcHIG# zbq*SJ6B}bfi$`Sx3O^9M(7@LBN6X|oF_)9tJ?3EIFXAt#fg*r+UJz<q!h`X^9jL#9 zcpzBq4xyPQTL;T+5isJ!=U`*;y?T`|LCq^*MH|ipBEkT?L(u@^ytT5%W17kv7O*|A zMndM;7wlb5=@BuA^E>WoBf0f;To;@K*a`ZJL17F)dYDpT*v_K<kD@aVWcvT(_-BSm zLZxrp&t`n5Tpf<SHOFjJ$hX{55o$^YGUS+Rh_0C{r4q_9RHVa^FvJ{X!Z%`=Ml9x> zdwhTI@BfC+w)gw}dcR)J=i{kSKn34a&-LIe*Am1@hYM+HVJ0bYtUqZ|XdzlIqVDL1 zR-U*r@zK@EY#`ex+pUiM2wwjBpqv?tH;pSJT0@qqieI}igpHcweLOF8IGDfRyRyG3 zdrwB@_C5ePqMT-Du;Y5d6~;(gYTi}gDDaeK%HmR9$JyKG8*34(SZfRaGe%i1Zv-)Y z@UACEv6Z$s)App<97JlqBVw%I5*sor{TL_dPOsTA{v7Bf3(>UQG*cl)<}wF8ud5GE zGw!oo<m5mi^G!}*OwSsep6#dgL-G&1Gv0fWqVtb`{EK9rYUDXydIN0WkPbZYHp7-` z=bz(^rZBQc9eicY`RLI#ptN~4VCCk`cxGtY^FJA8O3UioJSsnjZ5{6v9}wC6Z5U8; z9bgaKRNX5PjL2*Hp{r%nyT!zO>5J*O0)NsHP#F%LKu6^G=dO0YbxO<JCAt3d2{i`b zCUG(BvY9Cz-JKeSbUu;BSyjr6ma$LPTg($Q%rRclvu!kI#>m@xlE$7uj>*9a54Lln z2%0EW$biB8{)EEDvsD5Ak704-QaFfmr);WqGYmR62?G6UT?I)wV7A&aIUOzMkV;AX zVQ2cdNjg@q6(K8+*BL&<^?p9e+s4%b3r5S(&k9ZHgKcOwlSoGbQzkTFR`|wUCL4M) zr#kH5Jv@J7*(<=OSo)lgoJq32n&PTaAk%Ez3E#ZQHB&BQP`76<G~v9b^)%W?so~`Q zWFC;e$>2=7NrFnhrR7a<$hvUtR<jR2pVG8geRKndQkRp?TeVaVk@U_1vH@uu2su6Y zcCbzsvY{-<Qz-*oxtw<3R#ddC(SfDvB?viC_<9$g0?&;OFNXv`xvl7t?ypyNc<onO zH&N?CsuLLrD&}smX^g{F<9e~@4y&B7)1#M1=U=(3)(k%o%(x|Q0Q8QBz9fSRD@6z< z&`Zn+9<NN2!l_ZVcQI@ejq*h~GRT5Z$yt2_{=Xk!Dm=Dwqf5cN1pqR2(;`4ok))Er z&;Rq?VPpk<iI;REAF_hf`D69<D3S21#S!0SFE%f_A+F^@;&`bE&ynNCuK<G{8mf1X z<yL{XMiV(@z{tS=%#O7|AX#ibBZ_^d_9G;#dFC3T?U2+|lmot%w`tm=@bs4k;<;+H zt#wqB4&4j;{aFiA)f>fU7)LoFv=sZlD2Xda=Z2Na=%dNfM%mV+7&lMeQY-Ib;`0Yd zBOQp6$aka!?_b7`vXAp(rZhWtUj+#7&9EW@s+p(owJ+9)EY_B37aGrVv%+IYJ4D7x zium>1RlBqAIz0niD<OX?p^(&Z#%d5^m-0oRtiQ5qE#znMc>LKMDbCkwq}mqNWZD4H z_S)s>koR!<_5s6b&GBhHAjIg##vg3+XTQKc#Q}}e+N7>>R@5Zsc_5>PQ2iuIH~0Wd z&Z@P;6^#We$`?QXEwExjq1?1C-?FUDSISj$i)!FP(0^`u*m_w-d%JcV8^x|$am2gB zM!lj`1OMKOdtjX9kH;1s+8*z;tQxf|M;>>hz5cWy>4v~6N4h^ekTuDuT+Ew%Hhj=H zP$Y=yPy8&dzaJ!+aY&X(hpW@&VtzwQ1&c^%hcTHEov+rfG>gtmV|=2n+wl&=BjTyM zOlxZ!@}&7OG&9H-)ymE(h<D)o`Tsyij$|!r*6YyxEx~Nd$qSQjV;S8*lZ#+(t?(|T zLM<{ww+AF1Wzw_jXh(whtB(3Pg)RIz#sg^fZ@HBBBG&J#kKO2{I8fGESbj04-jqn& z|32G2zB=X{RC!X9vfy2}99cAl^b#st;cyJC=3{|7-*7FFGjaA7F(6qcl_C(5V4i*S z+2T);$5C$6g87YMCUeZ9_Y%JVukroX7g{>}vLU=^DMt$7hZpviE6fW{!hJ%abOf+h z-tt8d8-VxxO7QlF>s60%c=iZMw$B0KwmmbzfZcu~S=tf~n4%yDp!;zW_cVeSKGw{i z+>}VmqO|((vNFSiUa@SGlLOP(jw=-FVA#V8ts7cj+=RxY!8kLP;iZ;#jf%n+K-3($ zFJ|p9WbsQq##Wtt?03hT$WsI}3@IyaX4`m)KBYMvY)SXyv06*@Jn}FYa4Nx+R~aUs z8~mJGRfcbSSX+^=bQW@kMyb(@HN}A5d_{wyH_xC(5^B>?b}Pm*lbfCRO-m3HqwyTO zaY=+M7`@cVgAg}7W|{J#T$4|kNk@hE?98BXZR2G)$VvVF9;PrOy@gOWNVIkyPu@ks ziPxgzk#McbUBsYeTzAqWN#l0(qm3*Oy#3*_q^lVmC|^__<Ru5TWm9@FTJ<4u4A_Lh zT31AM3j)sk3d|Ul&9X<@sG0DEXl)sX5M8$NoffD&R@{a_fn^r%SoTR5?mul5d3gPQ z5E-6e)^oE3wCNY)wL~qL+PckR8}tpG*iS;7RGGM}TPgp6pAXq&VPHUlhMF&ppmg_V z{vd^TV>AcEsM9T&GN9);mlB+c+{_FI7cG3^-*~lP#wPeRr!TL@QGtI;7tv00_1DnA zWj%<Tzv!FiT>*B%*CaW$1PDDo2k*UiTu_f4c@l;$A2NucQ-SoyzP0U*Jp(Tg-h*z; zDdDghrh`QxQ_6P*EcNKDo>{&25)#62kpQWPTIyvX-%OB26Ax+g<4?=wr3Mb;vh%mH z+80@3X(PwG<AfszY)6_9y~<{W%itkpA+zM1n1+Z()1e3CYr(1_j<rLszhMjHZNe8= z`~!df+frqy2U6pFO*U&Lp*OVJ;OOz*?4v-doX4qi3r2MitsNJ%vxMnrs+}Y`zD2p# zC(6BNsXr$clKcZbk6aRK$v7rwl9@fx+WsbJ(M(F_`bC;_TVgI<^&*8cb_$9`(|14) z)W9zK#;8YHm7zEu!Y;jW^2g^O^jnZ)38cwPZ$JU6>TmStAXg(JwJ&MDlK*+aH2bx= z>lYshz!^v&=0k+D^Qa_sU(6fCYgoYHigvb24==+!YF1@9U$?*|=~EbRH1DcfJrhG0 zu0<L-KDdQFSovEoNwDhR>%2;0qX9${X!PLGZjg=4j3@_+xLc6}FZH{^9=;Gup)Vb} zJ^e=IX;?nzXtS-^8gPG}+*au)ZO9TsAOT=}4jhS&4FOU1-3%=tgvX!8qm-$35^A1( z&TDfFV}6xb3ZGrmqMd_jBU-!fPH8-1VKO)QpYrE<KePZtMkF0g+N^=BkhCwvTmD9K z8(Jqk5%$9xVo-A;=_%bIXoqPoOwt>(4N?P+fTRl|@b%89cTAdP$}O(5Qo7NOR%+&> zzN1T=IwdH_JK5<V(_fPX@w*EJB4+%eq{0a6w-(;HJ#e6pN+HQ<+bAUoY<Wwop#zgv z`qGx}FOqk2Zny>KASe@dnoVd$>F5JLA5Al!Mc*EJFqZ}U7rGMMY-|U&MeC<DBa|xb z3=waLX4aO2lDt2}SJ+1xaehS3YX}#l_F((K_a{o^bmZ?XDs|r<Ny4jXN>M5geqlfN zL1aX?5;XWaGt+kyJ@-C12eN_}VUvJC7;&^yg+=`)=wk$mD}lrx-YKO@_A}G~=Az=? zrV%_{urIvQdTxd!1%gYlL>?-rJ*ai^N7MsoV$(4(50J`|&Rqd1T$LfHvCw?O@nBmU z#DAE{XEihpcqtHcWA*yja6^!Sv~vRAtmkm>c*|gQ;gYDJ<+a!{Wj<x|D`c>3KpSC} zrPVlwgyvQpJZHbAO>$u(CEED4r4EYN5_qE3k$40{+~Zk>l0mE=U1a(R`e5G@fYszM zznl-y*>Z|7uFVKL|4`%?Z`n|O4XW9oLtalfp%seKrqHO2D=?@9x)j)rK(9H@?WJ_a z#Bq*p9{M7E>VCp%AZt-*9h?bZs1te}(dp2iZ&gtM-pY{#OLSr)=Xh#lxWZ<QaiFJA zEr9FgO#wiU$UI8Bd?ns(trM1&PpL;BO0JjyaMM0Je+7@ObSrc`&pWOM0v(veLYV*S z4_g{ifz<X2iv<j(@H(Y{n&4-R>M4^0eU6MHG8{thz${3o8jT;UAXs9m9S5`;gOOW@ zF~mlOX8X;KV1DK()%(feShH413M~vLShbTFWi(=KvSL&2$NRgkknHK8dPv;6WNbEV z;Uu5CQLLmzh^);4sY}<rr<0>R#%<dJboFzYC+AN6sK$?TMNJ2!r%FL&NvA|CQZ6F5 zaC1iKW#vf5c&y&=Y++A;@e+$iv9+HE6l2gV(S&!?w5SIH>zRt*`2MOvDz_Xxlx^Mn zmU0k_^++~GTBcwmS+bd+#inujbgI*(d4K*G<jY}Fq3AaKV4fUY;2<8fYF4n#KXy2A z_;YD2By{jxysXh5M;gbskcTT(8Zw*?I!GfZUrn^L9>ba4O82Mr5ks4EIq(3jRkJqw zLT5LLYYQ;PWKj-w-vPa>43W~@a+1b=nj!n#7fC$Qa=c;$WF#ajvaiF$=V?oz#vd$} zO?jWT5|rE7Vieg)FtP*RV|qELLzqh6x4ze!%;p@L*4<(pqcraVqx9C<)INYI@AEWB zsesdiab214-KxuMqRr5QdRm_$y4<DQ_-As&<3W0<s%A4mR})HkLz|u)E<fdBdXau` zoM9CFGSp4Z8;)<;e9&+!c9@GzhmK)GzIJ+QlDoMMpL~<s%$mc4a=rb-6$w!u*8<AB z=mrb^;AlP+aZ4A{6|AiP%+8c&s#FS+t|?#NmdnVL=MOO6$IG<1zrwp)cF*NVwY?pM zApGh_P^#Gsd<)&0rQnbgj9M&&pQuQc4;@(cA6$?8o$2eT1aN>W;wutvnG*U+$wom+ zRjnu!IVnuDaisPk6JH3pKm{974`!udxUr7FUf>)IB{BWCW~xL+Wo*8m*UR!Jz6NHF zjDMl)sLk_5jp(}Lz;o0lV+<krTYnRNQ+m*JQGab*t@dAj&`f8fg4y4630ZN*IxUh* zA?+w|?fvtWg%U5K5xHL3<ZQRA*BiYw9(UShS~2s0KZRqRAX&H-^9nzZ70pp<<{n^C zI$-<?wBv&ycP>vQqxg#(H-{KT>bEt-P)|Gd{iEFf`GRQG3ZV>xmkF|n*1v*IeE)U4 z!eYHd2BQZ^27@p2zuy*HAMiU9(V!|V4>OU^O0U0i<y_?F8RKMfH=3sNM4J9#{TP;5 z|K^JfCo^aL@V9~4(xw}CIx{}G=;9^_wHJxj8<i{k9S38cSd7C^k@B)T>hhy>BJB6o z{>7J)^)-nM-oXE?y|2EhZJClWc_MR1eY0LFC8jgxdv1!?f|GX1W+R4hSM+lEWcio} zBAfw2p0po4x^_#uc!4XI6@Ia{1JU-SbXTJ$gc%4yK=*c>&pWIi2zv9{xBa(P3J<Vp zxd=j&Iz7rGy*YH1TKXXfJvvbF=jN*AKIs|TYZbpp`<waM59-`Qg5Y@8tFF>FJGfq2 zY<2Rgv+d(ho$3;4Lvb|lRh*o9TmH*Ql^!o#B<P(ybKh^l;tPC!k+sY&y_Tj{aAnp= z0^cwHjYatAAbgD5lR!wGCt{mv>isBlA@+!K$50%o6teU%9}R?d&+Y?51keylJ^cAH zZn;qrufY)gQ2t`3Hhx88%Qss;g-OyM{Il4N(_5OOmbSttjJ=2N<r|<_$CRzqoAuT< zkzxbKCitq^UE>q&1rV8GL3npB<)Vo}L?iAO`(!Yi*+tV<zht217dIoHOMIyPM`*=` zkVKlqkLjo-m~c30_GMR7*Ktq#4ETh!5g?hOw@-WWW_%mf3>p}t!Emvr#FMv0QZ8dC z9-TgybTWwlyg)rXfJK8%gs)|@<mMc|yhK0U&A6Xcxg`GBh51zJP!BU?5B3{mM`d8N zJGXCe59@oOFvy+Y@(S<I{n5HgVQ=M_345aA)=o9Fyf{8kz3&M9fGa%+kK`yVo?f7l z%*>Sz1c3IwSX2Nfr=B^x=dSZ3D4qkaC~MhOed%rZtv%_M+fqrUu5z%X>ZEy{orVi3 zcUq9V$f3ppqn>2;4Ry)4A~}~ZUPVPk{$5&74MWL$-RMqiq3VI7RP^}0Z||P{nRszv z>?K*=6%QOp3Kz~E-d^BvR=Gevuu)E4Z$bf6%pDlA*fI~*n6-{qV3{YKV5i5BWi<Jf zt;-<_jsw}(E`7bPe*9SYoe6_1e}Z1utFQuTXAK-ZHfja|MO%l~p5EYAp8C2RJWCR6 z9zP_d<Er!OH78X`7mi4~HE}IGd-&)tH8c9VgDBi=arf^+#pbQY+!BY*u-IjyS0Rrr z+f`h*aZu-Lf0bK!J2M|LTEgP30z!6#v4H>9#Gw`c^cOKGUF9?Rb>MC944h}w64x7r zs72fm*!&AUd|FrC5YzmRu=|6qM)jqKH}ov`Kg6t{K|d=f_0Nu{)ObvLusiWqNMUf< zd@s?a&t9<j-0P0z7)0sIX4;sh=lt<VR`Q<dM8|aA>02S&O$?JSpXxI-@na*4iC4_q zNc~)i8l^cp6)@;g*ijH?!>P5zb85UKG4ccthzVj@s9u{7#78oWgHYJ+Ri~3VNk^tf zCE^TQ1f5Y%6PaF9IL&a8Mv|cay(f9HWymd14|<M66zpb>eXo5)FM9i)`(vYPyJ%*E z;$awiXU6r)&w=-&D#V&$m2?q$$K#;(E#E>Sigwqvv&2mlm%kpitn-%+RD}iYKVzkv zJk*vQ6DA}6=+fh|s%B2Ub}4DpA5oDX@p2t?RQ=o^%!4?i_>Ph8JKQ)n^RLBIEvV!) zmbn?m)GqqbuG#cWL#*rVmF?Y|-}MY42(za;hSWn62@Gy_=l(#zWe&mo5105QRm(22 z*3NJWDrsDL6`VG5koL>Y0G;2Kz4Y^B)KTJ{lD|jJ%!^#jT@2k)W~$+$Cd!QRv*UHx z12el^RqJ*94zEG&ZUk;<hUU}{74GF~j!GdAP?sxGw>m)^u&@3uO^+~Tv}oSZUHL?s z!nfgFb^WHY(o?>^e@9)-jM}xL$G>x1tnt5CUskMzS@!C<7`q~jTAuvl=Z)Ab%Tr6i zzwv_DxHT7EDUjST7Psh|UVn%f+^H4{XpXx;a5%jfQ0>QVY?pnhz(a{at1U8ocC7B_ zi9D^5i0r4Lrii#8yXHRp9_#64IJ2v^dd2r&=+Ezr6@<^<DHGadb#h0yRO?6S>K8D1 zKQ?C`z5J|<qrGyGi%O4QcPaF^`{X)0@uSJnEYr!>&A+PVUL4vwQqj7-srVSS7l9pV zx)jwL)BW>wMoHB$Gw+^}r-9xD5&vF0LVPBo{j+%AYKcTUkVaM~6M*m611pZAoBeDL z<Lr5%DNSH>uk5%!<$9((aXxwrhbWYfUi)XRm;LqSPvc`It5+G~SzFts0G)|KztDed zcjA>V1lV*{_J_hJ^y2P)*m2n0CNGYg5;L5#K`OQjyHdP+6uCa08N>@-`{%(1m((mh zCTDAC;%`}CC>U5MHPb<-9xM=@ERLy6hq+u2tmmx<{rWI<Vd3%N2kK>5d<(xDv+<GQ z6nxjI*$JIfFN}+o@yn1X7qtwX&rpBw?a!4+Ky+i7*QWCPPkX!M4_NMm@BM7zsqz_^ z+l?vbk7t(8a>J4zkYh8PN0RJpZJwT@2m{_cHvQ6MrBfZVP+GQ(AzY7c+?T+6xIKIS z;}Gpw+bHnB6I~{4%xH}Gt+rL0v=WBKXWG7Y{#cPZ_VDJJf9loa$1B=}L$B*MlUK%R zGP2TOe3kmsOzEZEJ+A5=5{hk>-S+WY%f%LzU0%V$y3(4P{gK?jb4?QE%DD$I(Xyil zhl3Ju$!5cE_{x!?(~-sB6Au0nTy^^zi-FJ^yDO-qBpXxL9g=^Bd>8HqcDMlQG>ALG zT9+0Mod_P@7mgTeG1)1!y&j{kn9un#6&$A_r`O$`ME&|v*)nau*783M0smea`LLz8 zir2F@GI(+E=N<bVv)f4ZAQkwmNz;8jh$=^Q3=;H8<zcJ$x!_8shvOmYACJOJ_G-RW zf>rMG)^^4GzV0159r1(m=%P&|@b>FD;j(^QT7YZ6cmrRtu=P3pp{+C{|E$%8_r9w0 zr!HS1yY;uLr5^uv=;Eg!K7G^T-SZHJd3&ZDojkDXTfxQC^l>?Exq|x7x8t8fItBtt zIi{5?;@u|6mWY(H`+;=OiK4bS@7KDY>@vsx;QQ6T*j!ao7vKZH!xV>Mf@g;^V}xdV zyd=eWa<HuMaM?Gx(XyXtVI30F;MQ#QM%var6jR9oU6VY<nHQ2L9?CKQdo9S4H`)2X zn5Ng%i}vE<W(!Xb9(yU@U73}YArzc`{?Nj497KHg8++%NRyMiP<1=ape+c5bhiHc` z(l70PX|X%|<jq&c3uD~YIwrzIZmv&uQquJqq#Of@1_0~w;LgU;uSzse%#Q&UBoB1F zp?BEjN5y8Y_<C%*6FPtz%yz?$xm=8FgPrDq5t>M>?WnlwR#<PM5{KW=bCAME2u!c^ zeraXFv!BjR=sdqSD1OxvuUv+UCys1}{<V#n=6SF6LkR5GO~e4!Ce!8Up@)tdkB|#k z?~bYtE<-x}pU(;Y^PkE(+I~wM{+p7?&)MbOp<<c3tGr^czS+RGy2|Wg%={jcQsiIv zip?%6xDRCrT=R}zN<n!!56>43BqRKWdN%H--%@NOtk!QBoO*9@QYPwhi>kjqq9pp6 zt?sFg4%ulioL?JCKbH8uDy?Hn>bJN?tblFP@XAQa&{??}9e}vzL$Qdtti?Ei-79a2 z5={!9qzYmi(RcC|9<onTy?fW}q>nZqi$nGU(_uqAA;8GFT>2RI#GbhoehwTdQOrfB zTa377#?S&6354HPDA_O%y#X#+Qa(!rqyD%&PxFzXG{Csn$?jc#${wj6d-a>DSU{4{ zvRPB?3Lm}k2!5sILdOX{O2}T_^{(ItNAgtY<Ofr}H2z;Gh75A8T#r3QEtT7!`t^tB zTLk+_Zn}Hcpb~6CXUCj!hq?NVeVGTuUgV^IAs74e`%79-sfI_7wc*_#v;C=_)L^08 z;%dWfXURtb;f7JT><gd23wK0RTpk36ja~~T@}tv}h=G4zQ<k}!;}!pnlN?id?K`B8 z0s>a>%Qdfu$%oZf&r}8s)yDPH2<YNN9^O#~F{}>4X1c9i_t3oBh0Iqmk6ke`m`H>~ z(fMn^m-zGf+p6A9F|XF6VdrZSKkdBw^br`6-)^tR-pOe!`dP-kbz^_R@cuWjMFd0^ zoa^E&1*Jd2(Mz#*kob4Pb7k&tTd7Rrr@^wvYV=M|zo_|;X!CsMpGl7>kgs51;IGFO zM??Ppe(#FGQT^h!9NJ`3Mp*|UDn0M!*-Ibj5Bp!>+CsKX&bVLkvpzAd#;xNLyJt)4 zwnSe4)f^m8($%Ar>&mb3akB4|j+R|sKXg!4J$-WK<Uc;==3AE}yiUvI1jrk~okcD? z`^=+n#l>*!`%WiLwxzr%<qFsuH-k3PG8b0-+?#Fx6xcN3O^bD+x(1zA%XWG8sWKXe z3eQ{CnxFAp{}+1KyzThX<hta*2MLYA^PjRyN6tRM9M4~^O8o9~<e{s2BsZ8P+U0U4 z<-&(BY4cmE$y5>WvvMX}5^;y__XaoQF$^}gT^agN@#9AXN1x>1Mvcgm!@h<n!4Glm zDQzW)_6{S!4_k5ConraXz&B=oWPzm~0*rNkel*;v%ou_-%Kso1SPI-8w7or1Rk>xp z)I3stWK!UW3;G*vZ?G#ZrP&e;NeJ39Jm&}r5{8Xf<ApnYep}ZOSdrAuBzz?tH7Q{x zeX=0zhBL>`(BotMw535ePJGWlhDo1kv}|_D#Bx5I(58E0;-fAs3IXdsLt5KXIh62p z9s$yiQXf9jGu^4IYv`VxZGT=uyLK=KdhTzbPt-2RfL|s#BZ1#OT06+)jJLTtk72nS z?(mo8znv{H`b|!lu`|;G_E=0-w)Lm@$BM171NX$AGAV0o;m&_srQ+M5!*5X0tK;!A z+2n!zb3^w+bXlGVkMxAYOW-){F>KeV^xW%ob3CoL#E87BE0>t6&iezaE3AmwFp?do z4IKD}+-q`)!jQ%zdZ;cZe7y9+-kG=MTQng#y}hZ%r}uS!>kj$Qc~(D9Y9OY$Ti7SN z91XAKZ@J_Y$)_*E8I|Jr&|`t`<xVPB_S;6#EU}v<4K)MxBge|}EWe=SN<IY(pNtnf z+3?T$ob>8A41MO0u}MVOnS(W#oZNGJC`ls-f$I~NrSb6e!*PKi$v#GK_V$&}O~IoP z?2Rni#WKz7rrl!?&%~_fC+LR<@uIV|=8z$8hLp#+3dLE{gm>(}cIdgAy!k?s8$1f@ zzTu-ts1lw`j{1F4L6e`pBm~wtCD=vY$PY)P!zc3dz0WVU--Wfb9Cy#w<IgHtL2^$S z+_i|xO`4;6vs~_NG{1x-6y?YzMtt%QOTiQv9vSaW8teb0bM9ZrRp)a6Y&CEh#xap2 zn|_%7`1a7llO*m$iDRY&HIUKQ6zXwD<<BI4ltuS@9nTx&dh9`zh~NLwzixZx_uKb| zSF=11;JGXnHd3(S81zF~c%2@z9CA}uPc+m2`kH-9)<x@DyM6_qOxfqx-*?ay<0~~v z+u4xp(q`*uWbVhuxM%WHe_l8ft3TA3Gy>0*U5K=M^C@lRaZ(F_614v{T<+_8;nM2p zWn$>YX!919U}KyA$JWcWJJ5bnrXJPvYvHov%&O}B=lElG`0d4IeE0{d#%)Ye%3-r; zq6Tipchz#l{nFSjMeo>Zr-gW;M{~`=##G<R*nQ|#Rwh4jgQ)!kAZuQ4`?j`c_7mSG z-6&zzc4MK5dXMgP6WAt7byiMC3?3E)=-1k<U9h?SeU}-xkKLv-e$9`n$F<<bX(Awz zP$VjBc(*f?lKtA+7U7RFL3g{Vi~D%VdR<j*sQI-Wgqo`)5k5!40*?+6K2bpH^VU1z z*4r24rNflEUU9K3hui9k#*`CTbf>Jq`E{UEGvb$xI=nL~s^=4GiceBi!sY*ko|)k; zgm3?PMbe8-P3p=RbFI`UAr#Sh2Xq4&gW7))-Gcb}mnF(t35W|x*RBV^;LH*Fx6B=S z-P!Y6-x51uD7O0#QO=fEQ(m=cQ=QN9#_leuWNoHTu3-~iyIKC#quIWr@FYE;X5|$Y zan-_O_~QmB!MoMWMn$ag7?G&-@16s>-9mlcN~BqzXSCV*2P0k=$08LDuOy6e{O<ff z)`O7u)!x+i6ki`{jwu*%0phoFse5~LK*#xeXv-BZo{RSGc4v>$e<Am0kIYF-<^LuF zcfRGb(1G>HpG>;M08BDu*W;h3E)O*R@8nwMdN5nX=?FZ;Z}7Ip{7bc$Sks8Gxv<L> zvzMP9=sfc^@C`kCy41(z3-wch%<HM1h;Prnn6=vZ<As^0r=J(u77lVshm;l${<@*P zSN%d5j*&Z8Vt!#?nqR=-^r70kH8eF^yI;Gd;f5<L;m{r9GMiV*v^*_A1vj|VsP6I2 zQx+DK_dZ+a=eif!6FP-+QWLRgrJ+5_A+Yze(7<N6iym1iR(GuKdx~O1Y*Z#MTJ2o^ zMVqH)Z?0E;ziQ;FSgAE%w1@y5eZwXyp;$WAGDy|(A&RHz4q;Yj&PJiXy|_1Y<yrY1 z=kt7XGxd#Vn-5cU+aj<bbBLyo9`Tzu-v^FgL(ApAS2sZOS6H%yNz}Wezh{1|H=N#- zn<cR6i#N3*e_|J5&6s`Nx7axsLw0t9Y#g%?%2L&66*+eJFr~xT<@(RC*GC$!Dq8tY zb+;v8Ki(^rph1}3=pbb2;fLqDeb?&~U>tj4=H;q;clSaFKhh>TD;GmCH<M9IFgA@O z-2Ong?*-Kb1q($*eESxkSwmdGb#sPC^OMpgKTyjf7Z$%pNb%1*f513ym+Y(ixO$h5 z0MehX+Pf=_KL_v4HB%~<J>`Og6Gnj^I%oR_Z7G|tKHC`w_B`}KhyQ#Z3qRewC${fS znyOc=<(HIknx)N)g1G}_*xM0AO0m_j?ibx66O;mp@H_lUoG<=p_f?&TNS28w)g?aS z+8o^N_u);I55zq=JK9{Bk5yU7e<80(s_19=z3MXkU>B3a;YA0hFIQdk0D!cIh}Tqw zxc83_9LySP6PDi%k-!gy*<DYlNJ^=JB{II-H`^AKM$eX~jb5D{n6m4YQ#lzOg533w zqt%&TF~9qzid-pw?zoThf=t~)R0gYFHwRe1lault#}R`lqQVymLv2!T9n<L&XH>S} zn3#{A-w%|9e*Yuz{PCR<VQRxGmI#5+J*-<PY}ZiUS^_gHaL3;|Gcbwg#$*ox`-4ZB z?}=gRj}toSEN62n719wg-Dc}<ADWQ~H9k}JCPDe>#(}L>Unqq;P8_;6P!`u>GRLU1 z{`D^uY<k?`<?l0@dJ|@X7`r_C1<MBZT*h}?*S5I&f<v~y)F;Po`GE9sXcUylW$t%N z&b@xTuAXXa{Q1Pq_MFq`EI{`GtFY$uANu<76Z)?j|0^;_+ynU&`6qn6Hn)wEa~js< z8}2^}&;7Z@$HPVf0i_&D6?W)9eUl;9=`nHm!z2D2E}HYVILXI9aK%N9zi0l#cR5*x z6P4U4J9U$nJ7W6qm9APfF+qMy$?qZ2MX~~YJ&uRlIWn;1*mw$to!J+<LGoy;iOhI6 zgKg}dbU!#Nm9Y|N#~F0oqQZHD?IbUhUTjrQtvn56*7HCT?R6sMQ30h{%S?w$UUkqq z6=P;+*6Lu?ZFR}6u?{{vb^XsaVKpNlu<KEH&_vBfZMrIQEm(<eFdqYOfFSYkfIJD< zHi}(|x_pGF=xit^66mb}tOcIbM#CvHEbVp^&20KlX~%V#-WJ$2h}hPUyJ_t|`tsUn zEK|gk*Ob^h9jP$pq=Cqc?21PJvnsut@sG8;W3XP9Ue;z0%+h~r2h}ky2rak7hMbOR z8dGB?ZBPRoV9A3*PD(_#GGjy8-SY+f(s3L2oP*|?5?$j}M4Ny1BFyC#{Qi+mS^h|I z@Y+yV%#k@8tOqio@j`n#Pi3&^{M!M<FJihbUmKx;1p%?i{?fxX(egdqm>$42?#{dj zl2Hno`tzZHAPMpGqvAgNRcR8!whjmypP<<2B<rnQq^at}qzhJiLdW~_gDliO`VzG0 z_dERq!QaY=G>y%P%9ER0i(V{lX_irW7WpsK@SHNGohDH$?;rj@Pn<Fsvt{)xK@Zvf zc#!Stui!?Gak{Lr`t`_U(ltkVV2miwWF2tT^aPv8oaHH^<EF%;@~L3HV8#+aYy!J; zfTrq$z$&tC!wEF*0j{WW(__CX7~KM1?$J{sc7djr9&je-qg4#LKyFZwcmgP8V&f*+ zZ}R?Yc_v+;-^^X5{tr4Lp`;R12C{V17>(ry1M>xIaUu;2!pA<XmkG82`N#<aEL}ga zhu<fAk(QG%j!QCQR5G{6+!EKm&(>T<1D*Re$RARg$yal;lmAA739?)<AEQ%jS5Kfe zj2vBMgBNk&UsbpUo7kN_Mv|r^sG@i14dwP*w$p)YC)?V85gpuw{0+v`?1-e<f-%x> z{G`BUpXDm=+rqyP5=g<JE_6AbpE6_C!CjL#eb3vrSDJVZy5g7&(w?T5nNlXnh5&A! zr$$LYVaj@ym<2GlPbb{Qs+F}YVCP#IUi7!b7+riSYL?aoeA@JJ#OeZRt3bp8vQajA z9<Z0UTu7l&NNhM7{Xd8lMeZ<y2!wdNqSAN;GJnm%JKF;c+VR<srpeuhnA%_8D>Qa9 z$4<74qrH<jUC)wr0WX8JLt+pC-Y!{><+_as$3M=rjbd3rzY<%V#*$jas(}M4u{8CT zlLsxfW?6Qx*?;nyb!BkL-AQIAT3MXcLxZ1ZDJ{eVO^HjOcb`&GaU)+#lQhr~#*cYY z0w8DX=NgFlHHRC0B-@cqY#?dJ__$=2K2grD<kt2q#I+JvIKG}oy_fiG8OhmCPowXL z&U%~Y$;Gj|64IqD40^9_{*Pv*-l%aw0919}0ESy_Y}xgKX9bi&8@4CIo%YX9%TZ{$ z#)?-Tr_C(kR<2eVdY-^fPU#(Io#*lB@tYPeq?FS~*UBbW9RAo(d;P3tE~!ze!723! zWCPgB2d-F8)rI4K!_c!pmTc{r_G}z_mXl2x%GJ2Oy;)bD$n46!tOHn;@T<SIpoP}; z0n6Eip~tN)Zgi?Y6D-E63%%$?L{33E>@FagPm0gvY(ZHX8tdyS8!FvOWGCAIGIzK` z<<@F!IGi|@Aarhz4%(PHSfB?4>i<Go$2xc{UXpcuh@5xDjndaA($Ck#!Dz;gHi}1l z<Tk=yvB(my%P0&GKV}^)O=7!mK=6Fc#5>!W+r)-^$>72Yc(d7M1b%Aw8c;Jl>JKi0 zQkIi&T~9O7BA^8nn2{M~f=sG>cK&fSc$lAfTWy`~0$>0(`J0WG3b-4_P9~lVgvzIz zOjBiAD85Oz0&%q-=x$C*ykbS%BQV147vyLPCpW%ju2C;$ow;;k^{o<`tQ>ECLL=<5 zDmrMw=rT=RM->+>>JJpyV;@V5B8KbzOq~}O^Hinv$r`1l#BovX#!sWb_;IYw1Eu7# zOY4m#(Xgaw>J3@INo`jdr3U?q=jLiFZQ}X)hhiI%CSbvl2rD_yqmDQ5ZnlUxr5LTp zhHY^ZRLY8-bs<|)e;I|2)cmctF$8A0svJZDyy9ed7h0YVNAp#~=hhra8U^37^rM7Y z`^<pkn0A6c%l~j$f|s)QEAz@K1%#)O`_oZvv9`$3sTOePoqGanv`l$8l7v)_diG!R zdZn?wG|4>xPfP%mG<d6THLD(O+#3VZi*2T(E|15>0O<4a<&PtGMU(e}$J*k4(4g#d zP!y6cmw~ZbUOH4A9T&$g(KUTmBr$)cc(nW<1hSt{6l&rN-rEit(IKdzCD%`v)WW%G z`awmP8G@gTiCO&lU~2X0j478Kt7lI`*=kJl$YP+RR=H(ic&S-trt8`Jv|E@J#29M{ zYfTyMRTV)Z)t*b;l4U-HY&?*uOZttbqwtv88sh)%GJ3ekX?0I8^4Qv%9jE$=-0m^X zS2oao2Vh*gl^?C$gYIMJJ4`NojQJ|dI?$M1Gn|r20SXdLyA$wquAXR0OGY`cwb>9y zw}Xe;i%k>}c+hUhbMByIMft$!8>Z=ss^!YR*wJI6{Pq}bAmcrVpB$S;3~C#yMGD}) z#uhvq8$He;sJPk@Ibk4HYMiGBO@tClyJ(P;g<i5=GZi~)+LL`)AqS7={Y>*8hsTDQ zR)QwQRaeOf?xp+Kv0fn0;ECH#z)0*j;7n5ioEZhm=AobK^VApo1RS%7BRF-ca3IXN zIV!L@oYEC%_WHoAsaaYU;kNC()@Lod$|2Yy+tw{w`(jZGqSISt^I1(%ik?sAI*$@# zmN73|dA=?1NAxW+uur(h^lWEj%6STfKpl5DPI;Gdj7ioP1T){{{e^c({u=^O7ScDX zR}1YJ%D#g!>JBrBSvK3cd8n#^zB5&i#j)v$lj?=XurVuaC8cB<!VX7l1e11;hGZc& zXrnXg#>w^IpAVKVQVT5bVC=c)4v&9@gTnwSpAumpV9A()7yX583tO)uf+oS=mB~h$ zk_rm~R$d|^<K#8nmzi18w&uirr#=7r$DGzEtBg=bGgrLx|EefLbqELUOdJ;R!JYeo z6>mzWx^lA;{)RnY=+>&}MwiE{qk&)!%2<_<x0vPz{R<H{s3AqCO&B(T6)NM*t_Qv+ zWBF;rC0FHj&6`iK?Lu3Y{xgS2SZ60IEY}!V1dD%g+zIRta-=mygwGSdDN`%l+pJub z%A7CBf7A;^Y`DMz5Anbpl4yM`;xnZuAl&}h%XtQI--hNPiAwcK&KDyFQQJX(tk*<$ zyhlDmrH89%?hF4<=2Hl>E!srK#emkgSQEn0{hEJG(no=e#F}RR2&=n+u(udnf1O!0 z4##LUp=R;?B%o%8{FI_)cylSq212XB!QeG2r9almD*=wd|9ZA?YlJ4FYc&=+L0kh6 znn6Gpmw}gm6Ky{DGQ-7TLpE2}99uBuB}Sgn*4`26EFWyqVveLSyHJ=lJg(F<I)iub z1NsY0%}2*gA8E(=*w97flomohM+Mry0^0=A9-E9&SllXT`DtH<IVf&SC8*w1T10E0 z)8($}4v-AjM*+=o*Yk|(I4!3!Y5*ZpdvAxnwDBKP;S562kA1qviEN~BD5c(q47fnx zxP>kUa?a<$gh`<AQM_$j<FChkVm`W!yF=F~NCQYDtrXN;(IxtpLu@KUQK$5I>P<4F z^#+s@WAh|{F~~y8;`{2EG5=kmdCK&wm7|LsxC$%$A`SDvMaqdmBP0LY+R|$EQt0S4 z`?PwrcZn6AEx30B>EoH)*Ctx#e}Gr!Cd>Qlt?&g_|3U{z7I;3;GM_-T;z2yZ#dPz< zWO8-`t@3NN1>}(y$B|rjC?Cb4{aAY}SARb6)WAJwuda2)+T!*zZljZ~N&dM5`SPZn z!GvYunqw#+62weIYo9FLpXEwtu!2~dK~<;EkJC)uBE!kOopuu2KC4RdS3=u7gO~Eh zrEa&!H;{X}mJu2Zyvf{2^g&54zkwCeE0&$K{-?5fjfxz0z8ndK_X)y_SA?Yc{@uAj z@Sbpo;MKqdFNy%DGleAiRdqnajO%3#^X+L?4u@5&#K!)*Qp6SKbn2*z>C({c$t+RV zx4G0aFfKW3(Jf~$_9_Z3g3sr#QicnZykq*)wpPIIpQxbEYVi}$!IF9cp#$8CIRBOA z7f0aO=4-CPv<=?x?9MXwW=f~|PcWkaCb4&(iT0I~R$!JcM|tE!dKEm;!2C2nEBf^j z4fr*3A!Y^JmN!tXY}wA(0@exs*MkzT?Qze3sLB&T+H&&t3RtGfv%8|DJU>p-$Zt!O z%8Rrs*hY4DT~0o4A#NdMnMx!6n9?TEeVt)Oj1$DJM=%m8XBz#7Snzq9up(z1_4C<# zF_Tc1#aah=(YgaXJI`bz$BIj4Hvu3#a+&~K$`u#ky}j6!!oDeu8`y)`bDao(rAjzT zwx+1?+t^)>N=+az{pddvFI1pR>u!ILulsCs1U67Yh=-sDYPsigGp9!#jVf$w5?H^9 zAQ~>cnY*(`zAuNah8EZ5L;J3C<eing(gcF3Q+xj|QGzH{k?*?FJIkRFD=6ul+sJK< z-X@R+U#e&0Wdk|XYua<~h#?x8OEW^7W_^7t6FGX|e@@W=<tt+ryWe1Le}5+-rvk1V zH5<kX4S7T@TxO~=rj`~RZ!O+Y*^ZW@KDn`fnIt(^-Q5cS`E9pygSHLl3~nOx6VH=& zTnLs6<Q^0isCi6pblP-tgE%AIA2ix{TLKKyHi6O*U&z}SL-R4=0Q~E>RazkI6>mO> zTcO4_Lh_BZQmP}TkA6P?FSL?E+Saaj6^F4^<tZYrMfL1|lTs!>28YP2Xa~i*umBbV zHWSAUZc@(hI+8OEcCqg{Fou7%1%k3cD3W%*d!Z+YZQGoQ%=DJzEo4R^g{ORqADxUg z;R9?SNls&5-^faHs94KCm|QT%85_W8xvE+Gl(A>GCp7{vv-v^dL7jTIU;wDOk&MUc zm>OGzU|1=UPE$Zh#&wbl2vVweN$)W94#Qn)Qci`f?jV<k@X-#AkeA?NNaQExeJIMe zYI#KWEb~%q$>E}wJtRH`an53}<+twPxq(`6=Ss><A7SX~v9Y(UNo@m3!&0QRH@xV0 zwWz=0Y@1Nx?GJm8z+)lI8I{K~B>DY`CErGzy#9qI2nrwe{zKF>83j!G6Z9griunMA zii+=f+BxD%NlX=dfbq#r(xZ_BkLTAK1@rGw<M$aP=dOWGGf>}`OSiW~nsR?W2^PW> zh6vT`K>*>v&^44&*d%O9WbS&LZXSDLyjF9ZsON60PMMEkk2L+2Y?U7(ywDA=o8<#< zn?K4;J~u537=D7SZahjh>f#gi55jX0^d}bX_wcITz~5QCqUx#HL0O&GYI&KCBZihM zoO5u!tmuz8>FDYy3!+?)9G#FscS0>k-btCvTUg$(wn)=@qlGktKZk+~(i9zbn^40U zng^_W>-0>3ZI2Z(VB}Z7_CI$8JWsx|KuQy!1*g0>QnkYHEh=?)au8%$58NAUylVX_ z2`*k*%!kh`@n`Fqn%mMNZf#{v;B#d9N`mJP7yLYRRQXV*)?_n+M7VaAqQ3QiDIE$W zi0Fpr3{z&XA(D+9rI2>go=H;#opa)%=zdRIOgKGQC6*BY@kX=l|5KquejGwiAPAS* ztN*k^*AQO1Le5u(BXCzRGDzI4C?74MA4$+hfL;!RPY*%goFQ#Z?9(<1vR@+$td4AZ z9$g*xTdyl^<<5`n2lL_MmHDUQVZgc}n{&fGxXABp(SWS*e5LFOTt)Xrzphn3qQtVS zpvW`(03KzU33TG~<_S*7i5jAUwVv2b#5d{U#W!qcKW7W9{n;U<7y6>DA&;kpIMpnz zN){ZY>X59!)aXvTXB3c|1MC+N{iZf?ZRi1A+SIR+dE-XDF|yth@!WK?=Zl0cWY`Lt z8DTyZhLTb(`Fuj9@aTmVexLkRQ*f(|g7?`;W-h}^Q3Z#QsUV6fZp}f(Mw-_r;vXvB z!a4@=CC5?Vv$uiifEErVPH4s=|K=(ZsyiikLbgW<aU&=WF+G~T{-1}-@mb|0$E*n{ zMM7uA0d1k@B8s;bGoh(wiC~y*+u+*4=sUBXt^B^)*S_mFHH#apRA->L%MhK!?#exX zTh(t!S|6Z(fI|ftylOeOea!(q?kPy=u03u7;oZhf$TjfwN}$u_lVlOc5#Y?vl!l$g zgo2{SK~7G$9^y}ExxmtsE_2?f^gub}E9b@DDE5d={YYg4fYvL_rp49;rEu+&5zrf; z;@_Q?Jsp#h<k9^Bw@&AIC*3$IVlMN?T4p+_j#fz6in=FVq*ApBw6s#F$=KXkrRU_x z5@Zac5t-Mb@Qjtkr8+=|g)<$*|80|$d@)Z|v0QQVKx_Rr3U?fkqGbPU`Sa;~iAxpW zqR6pgA;^!dF$^%+wuAMUo>_{SEYL8^$;&hyP)auJ2t5RS(LxF<fuNmSaFvg0-eS03 z6Ph=UDA<Cu?*wl{Cgb+J>Jun{p<mYkI&+|3jQtX+b;dJu@3$Vt4|cvP<Q2n#7>`ZC zb9*Y*REOjn&+0qDJM=PB00?04gY|qa7tj+9o@9{l^`Lo@BhM9yrBDu)A_!m~n)WIs zzNAG13*rJ@TJn*bAC5j=0pi3CKGe(!2qjJ}tzP{cQ8ORLiAahTSXr3u!wcDJmN$I9 zF)Vv=Z%p|W611J`F^qo0k*7H(a{`;yN>nQj&=6ELW+I2}=|I!<J4X^TtJguoNa0j$ z5$b_S*3PY<p=3w2wol6>BLRzR_z=|f2}bAfg83gz5{K0!mslYF0}&y2(AY9!y*ozj zOoHmHrQd&725;<qJ2JWy$&}yf%S*2ODj6^M7D#tc_;eKQNm=>NgZu!_jy@OQTR+Hx z$oD|#8%`Wq=-&4mI1fJ3UyN6@=>}RD9~qLIRhZ9Fm@Y%&S$LchPezhXN%|gVRvpYo zOp6Gid2B=ca?#Uk;-SfA>Or#o+ikCyZ&1V$(hj+Ccu_N=d)3hqg+nlb8qn6-ZY$mg zlHLOEF4xL=2rv;LD9*Jn2;XMs&UxeTV5P5Ic^TxCv16rjIbFYSG{p45Y_TDG>j0pu zLAgv^QuSseIAk)*^#eI&Os^tPr=hnC1}4RY?ofZQ^f)#YM%sox{11<)8mUzsLf+Q0 zYFm0Py>@9HayF3*f(z{Mo~F?s16xdFp=6;>Z>rWSq}B~v_pD4uI;|o@0gf2HQV=z> zdCnLLAc2`N6djS$(h3Gzg|&VzgkqnP5Ius?vY<a_AmImB#L0({Hy$kFSt8E&0^~kg z_D@7GQO$xilrdpiQzz?jQvTMidQ7A#SQ$`Tqv{AFkd11-TCXd4w43P@sZBaO8*@iv zI)&}l1&g&*UqpOd2T2f4D!Van{Pm-M{H59$z{(t_^8j}o86>#_fq^*gY;c}Nyu8({ z<S9htfZfI-YC4=3$X*pOr~C070CNLPrXW@SEgM=+dN_ZnRrQoUJBg(9v$uJ+C#gx) z#|a8<LBF2hkv^J%GzAh-{vR#m9xLSpQzsB#SMs+a%^L&#Ea+Df5-gy8{9uxq;3SKj z(lNqX##$%u;`(nrf+zsFG|u~B`#iA@H5+)*F69H467SS^3^$f&+s}`jt-|W^fp#Zv zUVpHOvCE)`(jr<rZP51*<}efKd%)?&N5Kl33<?bQ>(31u13|y2C68Pl*hF>DfnRO= zJgO@Y#(>T{C9h<isX%{TFKo8a$&zaM9d%eW8kUZGm36MP!1?+d_U9vU;yu=EeVtx1 z@!UqmN^ABCDYrl1WHDGn(5{t7bME_V)t%wA#P{od#P2oS?2Qo>n+xK-{sFnx)h!yG z@?qfqlRGBPP?h3<Fu$vG8u|k0b4E(pr-*+XE&@_2s&8p|LBy*T^;7pNE(dUTcAMr7 zWu;gb{X&j5WQqq3j=nLroTUZxQ&y=x!`HRxd*IM~rX&kv0DwqOhJVv2^@bw!+U73! zp=)q<`weAEuVALht#V@l<vB5d93@NM^q4K$C)^SFNWFNU&kqcKty4PUnDER`wY+Hv z*>9xK_PQf+cT1J3Cy$IX%@95b0*soSFGgw-BI~qE7K{(+SxGxHrsV%SPRjl~@+h8! z6kQ&d6xA<pXus0q?2DCw9sI{^Le~(rD0;d5c-?_lRRb$ROsJ6cqWSk<&-MnP9L(wB zA0CdYo_3PkkN?^FKMAK02TIDuwT8AMuWS7WDQlF;m7q0Qr8qjQdQT-EM1^!Z@4j<1 zo&27EL*@1xLd}Fk_u)|=^61FDB^)A70K{{<CHnuo|Hi`g7lOXSc+DGg^#$^0`TTt; zt}*!mAHSLYSosDDb41Z>JSMRUGh0`B2zrN{-m@dN+UA7)WK1WS5tr2V#ER=R<P>x# zjvgZvo~UY8MrTEl5O7h;*R66L%(h$4UY!y3=WU+lzY!O|fK|!p{I6_(S}Y+Ppq;z# zUF~nOQ;HlgPtNlU!ShuzDNP#tWErw@Rd7i%FoOzD2Paqz(@Ju26})KqbkZN~I@TS~ zk2l4Ys3nXMAKUeual&)YHwx#AOuIKWrXVj#7gt<yfrWTJ0QTmk0`n1@FO27ZC)=1! z5w)Qzl?81!qX?wUbjOIxnyv~J)gv~?s>`kT0y?>?NV0<SFw6#^3W6~SdJd7r;}0L6 z$=>?j*9}|LVX)fMC)wkN(|=)^&86#*3E^b;s<X^omGfPh*O@&3s88hCmuo?!_o<a! z=5(rV2$&WTUgEul7RPW`Oc-HopVLK<Ky90T;yOQA@`&dazCX`<zT~5_4ovdO@1(3s zG?D285e!QXwd9TLL@!JSE?ZvXzSVz!UvD*7w-p^gyv4|j)Ot++zTf`RzA9(v((akP z#*FMcuV@W~fj$Ua6t~U`*ODB&vFSdoN^8$P-<45Ui6X}&nK^bio=B7)e%4bwmns3g z#w^aYt9^1_w_1Lvxp;Z;X3c{H{m=e)Vb%;Dm&u2KqNHKu+p-Y1?fqWML6JsRLD^u? z%$WC$Wy-)C<`;>LEPK@I-<qn0@FG+GT92Q8U%crtHl`AVrrxWP>L;B$XrYFRx~RvX zQQ{_@kT*_`19<tyly_FPZ9^WyR@-g+C@n|#vR~W)u0$b6;PU4Om+~K4aBXN?y>gP< z2EOSu{m-<Nij;W73w{OPVY^mHOM@SrK;xx?*&F_O%-x?9Y`W67W+fC$@+J!@emN90 zetPzwf_bBxi1kn2bEU|+GLN?dVR%_o8Dli2Gg9|>I5B?dca+lm2%gjxwu$&wu*!#4 z53<W!)1{3>zhh5Mzhu0)`eQ}#;U1kDU@P!&`uJ`@cw_Y^X!HFGb@sMm%dQ`K*#GGa z7Ozj2|7DKE`sqymu$D|is7AcZ%4J+1xgHT<TCFgPE7&LqIWhaF{=neqU1hEh63baA zA&<Dx`^~AAWtRN&9>RT3O}B+&!`7E&<NAb>QM66x7O{rb#v|k+3*L($wpI4Bf}Ro; z6HHD)*ihG(2N!p-ejE02qeGY%&M$x7^)GbqNvq82!(o%?_f-;=e`hKUS+*(s^`FeU zYrRW-#k>q$D-Xc@33imVUf#i^2jEWZOHrGwz}`y}PcHZG(T_lziKBn~5ZlO<vP$n7 z+9J6$quMVD&V%gvl1zoqmt0o7^^EFNvw|yIN6FX`4_C2~TEr1g;$6=>Qli1H5lK4I zci&bv=rvOqdiT~EN6LS728|?su1DH;|8-_KLG2dz<y`4~!v8rs_jsn?_m974Scyqd zQ*(-P>Jy`w<LKa&oTY=DrGvxfd}f4Cnhg=vjB-vnlw(elY@$pka-2r9oSF0C^Lu}P z|MPh4aPPkF_jSFl=Tm8PmvN@hXF67gjMabr{y)I`5z$gAG~CSsQ}tSfJ7g@${8Qbc zZ8>#&Gkn=X@Wfl2$W|`H50kX=#<}MG$IXfM<zqIS*K)azU6cO-h8>>q`)Bn%e@7pS zWca>+PjAh1gD^HMW2TcgXITr2n`ZA0X+G;p;uYL|#s6pT;oK7+e3q<y0xymRIFfMA z(vi{5Dxa55#R~tz#$!H<F6<tVm0aW6Y3e>`lssB>5t`XHX?$&HmR?b4io~5S>~#-_ zeAfedg||hv+{(%t{p-=_lhm`%*?N1RAhPkno44sa`ujf@7YDf80$jLPRsMlU>?QK? zAzZb>Wblq4cwD}_eXK6ss8n(>Q`8$V(_Xx{IudVperUJmXsua#fnXGvAJC>~yG!+@ ztDTrqJsJFQVT8&>MvyFi{4!sCC|g*gYU*D}MIm1$vQ~Y)y%wfeFwULD1XkkhFR~ej z5rXan9~K86zi&XNaNf&l9+Ht*F+rxyZaPFvZb2G?Qyxp)wDQ2m_ik*%GiR*BDM6kK zl+=Ib-wvHW+lOG>nNXC^V_0?<o82*870}Xhp41Z_2#<)k?ml~Ly>~I}i0ObU`d6ZC z3yK_mJ*Z=NLc6;$cm)eApy*q_8!cqjHn7shiCa&|YgAbzdo$);&`0=d(u)2JW2r>z z%Wfl>1hDttDDR~P;~V_L#OV@x>Q)@uyzdc@?tDQmP*E%{mCX`OI@<fIw=#&gNC3hG z3BDa??WU9=D;saBs^=wdLxys_{{yHGuaEy=zXZZOu||`0sYxqelgdwhb3x+Pb!c6Z zWp}fA@2AR=%MimZJ_G>Q!PzXHGf0<NK_Z1$JMN8*7@jW9@om*6NP=DS?dvYKHE~*p zj2h0xG(p+}Sv3z5(iPoT`8y89Q}jK>kvqX}mBYrI)S_1=!9aDyzGP-i1WsuDi|k3& zR<);Tl-%MP;6_U@>e4j(j~0uFrk=m`IlVmE1?K1i8ANaq9g<f%)>^Y436V)yel)Ze zcXP=UMRL=W*ka2QK~gZ3R{5b+ZeE|#l>FlBV^5}wiVfVjvMl)7(jCJKU&(i^WMmV! zBKEX?7vFn*vCtCCqQfLGGDBAUHX~h3#Vypp4&HA1`o(aeVq^qX*}GEivjbKxeilDm zHLgiINfS$w>euH2ozwTl#Z)B@xIvgPYt(lygU4_P5-ims=A-t0X6{{)=auzeM(WpD zt*(?G!3U;q{`AQ`>v1?>Kym=m*LKFkD`SoW^10qNJ4fbkbZ^u<o7-RI9GgGJ%jd!9 z4Dk`rVT)ZhjeK5{(`^)cxXE2^{em?_ghx?}#&3b{xb=daaFM6NqMrA6eiRAmy(!qf zD*CzRzS|?C0(JI71s2G^EjV<qQtQtAK#;_7DR$xg`y#YHi;x`l!kd)Oq}6$=?8%S+ zD%bvU_m(t3OE#Bj<&Pw2*}%g(F~tvhd6z}c(Czno>K(%%rX!4TfS5g>{24CM{9&ZV z58UJY0tdXLyR08Qhr*4)=in)Hhkq<(qR{84_z`eCJ1X<vD`yWcgO=p-Zk3l+R#RA2 z_!VoLMEf!7oGEy+Y};q&DHs~{L@!Kq#_8A}dFUysHW|!9U_x?TO+yY}l_Kx;<I^_$ zwbnX7Q2iY_mDp%|duALiElw5o?%_+%9i6hnv4VoTO#~}`^uOQyWaqn>P-2t2Xy;1o z@rzCK41@#`R%dQ28>6t;Mx}$n*-iM5^8$Bc{#gQm)izcoXY&Ox+&?C1lGd96Z$P^2 z1q?TedmiyT*!7Cq2Dz9vDBJ4oki$vz%#=9Jt3UpnxrW{j{9W-)Z@c6sh{w|>2e19E zep313f{JUL&dpPgNjZZR=-D`aorvp~v1Tp`qP0EI_A~jh0sSDYtkK)0!S?XU!pql@ zQ=mVR`e}*(LG_8JzZ^~14c=eL$z$s!nxLmcIsJWaUy6y`vV;2dpp}|l1W=g-8TpTU z+EL1`GPc;ka~jIaC)}Z7i^NZqb&m2DFP|@t@>~Mem-pe+&^*@tbQm(Q9oh!o&Id#C zH}Tb-MR8N5Tk%3$JD<G>4#xvL^$M2Hb5>f5{q>qlT~zc29=2~4@P47GQ#lNdVXk7` z<o(kpQpT7-=kXXMOP+HlB>A*y;A5XZK0CxH<9^xJW^9&l$xK#<!#yY@+4Tt_ocj*w zKJ~b2qw*U<KBSw=;pS;sTwFcmYkg2q6y8vtb?ui}{xyB6$WU(&Nu3j)>m5|Tru&cl zA{reS4WKByjmG3Fu@BWDgWB}??9Bhl_H$o835-8hwo)~U8`@s)xG|u4)tib`ZL`rX zmCQ^ksD5}?w~3Gr{6%vMTN~3=(nyDTgXRa3USdDiEz}VYE=HJqe)Rm3j}}Y$?|qMk z#E788ORMZdlr3)ION%sjXGMRc9|Ey6KA!nvWKynvGMq)se4aNFq^P*k>A1_9@DtN# z$;bfbez`QOlcxJC9=vM}OmuYD0%AUF+G#qU7u>0wc?9VVpkcPhX3lG${BY`iaC*is z-R~3>!>52`Bjm5yc{7E|0(=3N01m#dEau*wt!P_p*(Wm71>Rm9?wxg+PDDt8YP0?s z%)3kfNE4ELy3~#n!1C)_Y2uIPyF;C${9z2hE_eq|-Ip1_9vA!gv&AfrSr$3rl>Ii* zOHg%>eVrK<1@rDxCLhUhAV`k?K&3tEqTEornX|R?jntIKrRUA|m0r^gk<xvbX&woN znWGeV2JVYiy~$^a#BT}|MbFHbP$kJBZ@M+a-C?N_K^;2ZWdF?Yc|0Kf_x($aq8zq! zzDBHZn;09c-@v(kDx=!<Zct>^<Y1~EY5}%suM;#T&}A}GeaurLDrt*z-Q{eX+mN*u zu)rp@kJN-GX$8xBQl+DMHAUjuYf;1}9f4Jq8q*n%LPmOw#`0fD=6rB$@_tn%JzAxd zHL_95go528Zuv)_7Mo9>0V^ReVZe3t(%p`>Pq}vJ_Oag+a_I{8DH;9;C*K=sZG#dc z$sY?X{DOFooe|q<@DdSvS>(ffvO%;XDJwVa;*!B)Dw>tNVF?kL4l|!UQN|2*toi~@ z4}P;Mp*$|*shzE!cZ0A8dm-Q4P*lfPxDDc{%Q@`;;wHVu_rc~#=h&kF5^IWJS4uhY zxp)?c+t!DN2kurXpQ6jCA)&FtwmrtO$SCb((*0kn@OW{(sy!vA!?kc#G&E%_c2BV| z%Uui!*qdx)Q3eNYsOg*N>|fbt@BYs2p$m#?B6#7sw<7W1@6>8jEc6$&)_32i@gF<S z6e`#ej#hxGI|w}c)(FLK#`kYIB!<R^pRZ+UIo6GDU6mxC*wDMKxBkH4k^IJE`q!KW z*I4zz<fZ=r5oOcU)QMHKc{ToSBSRL599kmzD(4F=i`X)Cjdp2`AAQ^ax`j?4)BfQF zVa)UNi?yoS;Irr6oAsiYsFgSG$qE9ht@4o(Kdu^?o}ouIx2%JxoVlo{-8;rEaG#NH zd!zAy3IGmAd5usWCjA)P`{y#@jai`kmyz+tQ1`kBZzW)JxWVn>e?TB|gYKmK=w}c6 z-*Vis<;1^`8R5D~+avTVnUB1np)_Es!k0qH<b)pxUF1dW?r5Z?LL*18YGFVS?cujq zBS&aF_*fl+`ytMte$C9S!&gM^=x?E!UcBxEk2Q%TF|n4Tw{-HkCnwK7y2%i6x)V>K z3!t2SG`bN|BfRpc94FXP@EuOQB6P019l3&YVk>Tqz;vQ#=-_DTzoT6DdM1^?8VY2I zE`TTSr+oV~2j0m11uoNO7c}UGd*SKt0y5BXM&l;BF>9?S9=E^uVT^%~qV7wjb*bUt zS6}RB=ASwGi|I~Y21#EU`$#xBz`BYqPGuqORwBv5g%?KyrT>>Hqxs}Zy|a_^3IVy+ zzUyNAmS%v!F{&=l{rH79%PGHTO7`~uJd?S|{GDwHmj7ogB}yPk#n58VwRCE0%yuD5 zT9{+{2})^hR<<<lAKzX$iKcmEw#xjki6!i^^m)0hK>T8CS~<+u|MTh^x?JV6{wdA( z2V`AlLerk+Sr5*@wz%({k4;>9#i`;PBTF=;jY#|lsJ~b_9ek+z2!<jQ+%|@Me=AEa zH%!0;`!YKwWa~OM2zwMM=#9|o(F^D>>zgLou8^_=R=tRd$@muAc=G!Gjl8s_GGDZ; zcze{tsYT*A%E#fl<-s8>lwtL^4}|%7O1u2FL+`%E@`bubx+=IgT@%g2HoW`Xcb`fm zVm`HE7SEmZ{+Pph?CX2??p^mEFL%0$Ip6M}|DKske({$6?dokSyUPWsxD66gq&MoJ z`XRp77a`KL!JgxS&Gn1i(i5YdFWb7ipsHX7p!Rl607d=>Z(4x{Lq3~zM4^rDS3G@3 z5rG`z7F!K?Wbc-k43`Z)U<yB&<))}9mlE!26n+$RSqtH5*gGeB@k#t2lOZsKx+$>s zkK|9~8_%;&_Ilgo|Iyl+$ntxTr}0VZoSc;|oiEo9NNK8)q8^t(SF}d+Y+eqvq-yFb zwwgb1I!#bL$CEv;C8C0+EjE+PBOJcu3hMHykeY56h5CY%lSYDrx8h5uZg#{OBZXBb z`6G@d??IP+=9JYq>;K9op1%<%Gb|?R0-&f+MEU&_$UEQKno`YsZord@YxOh9UwRhi zsW7rT=~JOMGj9gP;h5CZt?^re+mb(|jgjWC&EQ>SozH{I_rn8;J))gWJGeWdW-o70 zFrQldHk*IPx!2d$Z6(WC*EL$%czxa1`T<5dD;`CVx@DgkcDjT@m&Bg9^U!!x#CZ?T z)@Q<y9_x%kt8*J6ojVRH)f=|4I^fW_!=<UxgGW@vx3F50jYi6WZy*0N_TbpZ>$$kH z(a5Udi>qWVhzQshTUsxU(5QIh__yx%^FMx?a;(J3hvWMfHk0OlYV3>G>Nrj6ehH&5 z3>H0P2mNy@79yuqQ2`Q#bEof!x(_7x%><2$^~tsjyuSVK4SL*^q$yO&#@Mo}C3k7> z<<_UadM$RY7k&P=BP55!rp6Ce6K*j=MUq~WA}_D5ER)^y^im?8y?jtxS#S^Y(}lg0 z=fbqR9&%4n`S_W~pIj8C1ttxU4w}DjM-89;dXsuPEGr<OTg6E^`s$2Nz&id6gxZOi z38Qix*PGwo-w5|!q6XJxj0Wjckv@IU#27Xi9q~(Sg|lVT@`i~p^Gk>dO`qg;9PHy% zxI@9Lfb*nR`#AHS#^d^!K~eT@^6I?-(-Tc;fm?P@2Lk1Hlc!0a^v55iDM@ORfl%;B z>)M>{S_$NY9{8Xt`-=8`YtRugR)t24qSt8AHJza&PY|8cHdm-fcub}hDY+@)kB}RS zycJMsK?ino^TdWj@pij1iO$c{bqemXrDlx{M-rj$0`zsEJGW;1N4f;(nOhHFhIjM} zpO7A<h+Dq+=c2UnhjS6(B4E$l?F_ch3yjcwXd({tS3o7L=L=aC47hqO_H}b}B1(3z zf5U*aklPzvacD2+WOQbbGIDEu=_vO~nz2NEM?|;TRS#&RFIG?6;pxo?x;OuHh}gai zqgZm_D1qcxAq(~~@R92@TtAsO#Ib|{B2@hx<x`zE*q}L^TZH85O8IJkZ*TAf1zE5{ z-UQn()H!Xh8o-D{h*-`owDli}zI);R)Lk|LTFJU_Cu^q}1A^FqD^nggGc<cK!UoQ- z9ZW4mE}=nVaVecQItax+)L;2K8w-=Taz;CVYz6fXlkIzBJ|-Gm=IH*Sq<a<2ivwPg zmlUKau@M99kR~d>D!;Z%A0H;5zvdh&o=m`w0qehG1tAkF1yX_WL;EcQOw?eJPJn5f zHI)&G`v&Ox4hcK2a%|5CBwP@{wJ~bUg`r>`0mAzR(#e{rDpELWNDG}q_1ZrrL}`H$ zyw}v8akL)5Ts9DD$La)QSQc&6HOBd3BI*luJwJB5>%ev|bbw@tzxq9ZlvlFaKhnQa z?D7J*$&;H2)2|U8b0y&VidlIa`zeND+f=kD<l1e)p(*J0cUeu}y*))s-X$JlwgjhG z;^8GV$bRVW*Gw!}s>gH{`&}9--r|--L}`bEqSoiTr45oy+e*tZ(NU2N5XHQ59glCD zwP0%@rB;-5iI(P8kiBc?gXniz!<10w`d>Z8Y(N-9*A|x>7J#>S)}OU`VjR973MTPW z=+3{X9h&#V0Wcraa({?Jh!)KTRQgv%fn2AY5*iM_5dp@+5+O)Fx+_DXv=~$Dn*l<d zM$$}1gE`5LKKs!FN%3@~6^{#^w3_VHF8hjy;Nlvi1lN|#?c5d+0(Q$7(c>BQZQC(s z<^hBt7JsZ=!-xSeOP9bPt@vRuFl=Ixou3DtSj)!`f^`8!I&?xyk5iB`B?Xo~6xa#* zMgFK{z?HM@)kiTwuG9PR##)MlTQ)(baj`nRfHwbJSRVJwOt`R_uz7fIOMLOxi~_)b zfvXyTg94!OSXDHOvR4XOThPk;8s<C+CE!LlSJOj;lBU7ard(0u8Au}wx8Xs{5+L-I zyk6&wRBV(3g->S;XO0X(w9SriEP8r1*|~<adyvuiI@#i>`}qi98-7nHHw#YzWAUAs zb85x8OQH~I7zIc0nw`BSh|NnQHNAnW)59;?X)+Qp9UQKh6ha5L0%pA)0GVbBR)9EC zFt~W(q=3Rmodi6LV_)au%j$&;f=`rIbX^fn|8fUl*(e))0Eyd=5P)WCQ4!7?iTxvD z@MuS99jSd~U9_-48Uzq4aP_N!CC7x(h+uAkcqd<_g{q~Ku-~neXcvOk*=CGoS1L1Y zf1yu5Cr02aA3C)Gsf+}xWiPs7cUj1#f@Lae1XHN`g#zPUXXr+R+XtNKfYeL7EQ;H5 zNUjD)OjSosJ$uCPTC@A%b_rkZDjWct{e#7@X1mVGs|il|{c9!NCRW?s@dU8RFljJ% z=hND-T@Yg<0ylfjt-HqfQfJ##OoBl=AxWH<>|RkPQF31(^Y0^g1fGPOHMkM_$AFbm z+`s!flh)hzp_;-E>)sqVJE9t0zg{x%RMKkF$bq78HkD#V=4sXxw&3RQP)^Dhm&*3n zD7q6Qn$8`hJ7EfqzOCf6-}lDlf_Jf0b^tWaPN-}@N-<djZ9k`K>AhC;!Sh3^1HlE? z_j;HR?Qcq5B%(mYwcbnIUBLYwnnQo!hyD~fk*H|u{CuPoK{t0F;h4ydn#G~;PZw{- zHkwTnE_=nXconvzK<)#aIsKa61(TctnTC3bTgvi)_efkoN<FJQVkfwu&6`Qe5TSBF z-S!`2pRN&$A3fR|$Z(t$?ePAR!asyW$uTvU+0$~3fI+!HSgVxT{gXy>OkAw75HSn{ zzn#!1o7-t3lHEbzN1lu16;BXCh>?1b)|F*pR?3>WW|$G=^Ho%RId>r$Fm|n18Pn7D z;&6*3CeDU(r^AH{q2wwAy&KOkLy=i&_%*OxU<K$q;d;I=UX!aufjsclUB%#1syKvS z<LSQW(Uk6#CR`f0Z<&6IGcw+h)k!k6@C4?~*Jnam<<S|GyB()*_wF_Y<_BmTiflsi zF$H_?8E1C7c2XriZb$T+(1p@te(gJ(1*>)OgP7RO0FwxRH679efF!^l?TGK;$C!l( z7+sp$n*gc#;YSI9!;m?}XwE#TSRDMV@r}%OT5lNcwB902ehlYs@7R9%^$c=VMGk~u zk0qd|iHD=c)r|ex#j<&F$wx<~(VR8<YRTYz16;MF`mS+*vK3?w4s(n}f#teJ`%L6+ zSG3iE#aV*`Ak<cF`O6+|t50fd_mQXSMG6?~Do0tOD&1~cs2P{+-IJ18bx22lnbF%^ z%Y#-TOQkD7hb;YpMY;G#a)gJ9HQn3F6y|58zbs+dU#oO%tY3NVc7@cQ?*OnIo3Er6 z?Uw<X;w-e?`|_q%wpdW<?Io;UiV6RUZdKb>xQma3Iw*H@WR?zxxH2r-j4O&G1M~QL zupT<=;cMdip+&wuhYtIX8FVsnX;!<xI;A}=ge$>&VDfQkHdJeISK8kI#HD`VIilCD zgCB_}1cEzac-BZNR#mta#w|E1<E$dn%bsS(^kwk+wbH@>(&UCzA#foPnBr-l2EbJ2 zwb9aNW4)QsBCMAD&zI6VY4*`fG?V}x{um{HG48fTLw(wEeF-m?AGg3C%HkLx%aq98 zhsZp^WU20ArecbmqWm+uP;VmA!8*Xx_l80STwn<s_1+G&-w+&>&&PO$4&pLJeOzFY z84$%`y(D?5_Kx$uo~yPAe*^kws<)iR-hFklrjLE1T(OCL^e?Tnn&6IO>nZSjal1%i z%zihRzoymh?%NyoPya4PK!fX)>pTg5<_>8z;IHs4z!esJqjYS@|A1u1w=w&VasI+v z92-9IvzUMRIHd03>}c1gtAhTxIMh6-K8%IK4B%)fc8#JgFIRkI|GW!`z)#PekOwnK zcfUlvG9CE>17(N;Lj3P{Cl8)<*5VGsr1o4C_>3&zCw)h`R2Dc<M%GMsxbFr|OoO9D z$Rj7zd**f^qcLPF5UVcI#_7>3)o}4~P3za=Lu`pX7HXQr_2q*^%iN|=_rd=WRgd_K z@?gsbbzOo>rl`a2|4<sJ(7p`NOxw1`S}DSOEe;T>*K1aQU>y|@ycFENXu+|wJK-gW zQDez?iPDCRsU=}BG5p%&Iur}_TiQU+8wl(Cs1+3431Af0Xa?TX_dcRSY>>?PXtTiU z4bH9vSsH>*j0N(3hd#0HOSLa<g0U6NrSz5|`qp|$ZQ>$b+;4&8_u%P5?13$i{cQoh zyk9fIQf$u6*iRieMlXc)N>rqmM<)>JHTVKMwJ2Sx>+<_W`@s>c)-EQK-@PU3)$L{O z`SF4%X7r+y`ko?IeHJtj%rr0q$m@(|{`jnl1sWV{6fQaNouP}AM1A>EaF9^!+W<xO zXTbg%=pLo<--GZA5P)B@E!u&F-7!2|ge_^-WJngf74P9yYiXflWhsS%QW}`SGdjJH zRhK+ALOMuyP1L`~L%CZKCYlXJ%NN@Y_7NNG_%^Asd3sxU{AoK)lJTVC>0yG2rT8#R zE}S?p$B*_^AHdIc82NW+>BKR4^cRay#U4+jS&pGuB}LN>N@WDNdgpe8&APtTN#i=% z;aE{71p@HTQ{rNey1C0vgZG12JC}2YHW1lX1X~Y-DKw#C56B`RZ97fw%X<o-JGUH_ z^J|?=0&%9pX713UfL;Y~7Owxse?S0C+5_|#m|a&VC(^O`c#?CWv`RIo7MM{Dcb7=u z_wZP5NCbNv>Kv2c3d^h_%kYq|ST$9B*WK1z7xP}DSUW8(*?F*v?N71zI-!*f@Y_Zi z*=XoO>vz`jAy*-IqU!zjSFS7bEK)ci4sWmb5$cET{>~s0>;pzgzMFZ9Z8p)~aB}=S zIBxE#!D>0~SHZdkBp7<@c=huTN|3@X+5upwXw%y)e%jATfBpiLh1eMd4F~_r<0@mi z{K1;cN{9ScGY|I==!{;{17DhL)|@ITE=J(49k1-419WK*AK3T@fOgPHl<Be)rPwuM zHpk#)?KH?%h~^*AciOFp>9iHa#kYaKK)|>Ts|2yqcMHd27-G^rlOy`MlV;2ex)r~F z3%hvo+OX;AkGNdiJjVd=+{y`s=|1Jm?v@hrjtJ+;mwv%?6&^~}1ST{s;?dvK*#hb- zWcNDd0ZDBuz~uVy=P7tIxV#JGHrk*?22A&OO0#10s*9_Y2fJT?z!xzEB{kR2w}A!Z z4uIbzSE)EtYK%LZ>pNckbL%nucJ3rszQ4`_WqDUkP`l)cw7N_ubeX*jUKB!nUB1*! ze?hbAY|!U{Z;cjT!7(UT8_km$f*>D2d!1TB6fru$-PkAFzWVx4qPT9I#CsH}9R!o6 zzcsbjAvp$$7rM1Y8^+D1qdMu~4^qkx3+))GHKX@4Uh?cVQPdf_!jpNtr$f$Qz*^Z> zgsp|crlI==4jdAAQ*ipyie<?ROs`b9E82F26`z({{4@3hmEQw1HmYd@7a)MSV+r+P za&WBeYa%!zbwn|ni6e&#cP9h>1P^%OV?Cmtx(QPSirnTFi7-w+)^&kj(KSKxbgFkM zHD!+cRe;0`L{$+&{4Be&RiP~!BLCa4Y!uE;t!;&~i*#(@jRwOy?23Ml!NKoeXi@6@ zqVF1#8^E1Dc1`LQdX!&Sw{%@1K{5x%OW4jWE(Bye??M=Edg}Y4=hUmYk~x5Ao=cfR zPdIeQn(`>FG0Bxt*B1*e-0;H|Ebypf34qH`C#gtrOKZ~Kg8u-sUlnq4mFQ3r<JVmX zNX?~U!;b{eK{5tTS|)gv*c7<inkh}F6W5&zh#x6D1FhWq<xULa%)vMY2O94XuU?^! zZT6~Ffv{78SC#dCSmD$u4d$C-qS}=Uaq(@e{)y&$&<(z{O96;G4YO(eOJXNF8Xx%B zbazUS-YF3lkP4h!Kj%Va7pBi}>Ck@tdLAz<Onl4IT=oC$LW;1=Lv_UH+*_#{Yr~)C z1^g{9alnnXh~4c;7li9!F<Iv!N0vXu3QO+sVg3NfX=B$;ry<_H|4oj-%mr;$E~Xp7 z<n=7VK_QAPRHzZT#*T$O5I5vQxFgUD!rrz$hgA47utq5E?>IFRP7M|{9DA6rhw9%Q z*W^>QWZK0{jdt`P73!exv_rk5Bc#mqCs9*@;&jIdD=03uxe*)6F{LkU`zu<EN7l%m zw5$RL_gHZ_T6nk>RAaXw7CjFR-Mo+dmPTd^7)v>KkzvwayisFgVA-%_48O-7qn<Qn zrYk^H)m~{SsT$9q_Hh<6R-MK5JI!1B8EQbIDRf#eZ)eraLKChHZVl%FWw9wrQd+K` zd9+07apl#(+5Ww>-R7Adu_Qmsl6kXf6YBqbKciqw$APdNg%R*wcp3b(M-`6RKhHFk zm3<~H@>fv@j<wH5hQoiyiYnELB|6;mTt7n`(!=lG(+Oil53wbx%=j4~Op?yj*;9b1 z!6A-JCTqwxwB219Pj>I4=+?OYflnB|AcbprN9HZ*UF-#>du{~N$JPrl*ebL<IH$A| z?Qh4%cZ0&J$PNt+VR4CVoWa43ONS#sQEpBgHmL}TqruFuunL&e7{^44J*u8Y9{{ya zyeDsXC|GYt*e2>!vWmj!lO_eh>~uZ!8aNrH;^_bA>8t_V{#rf|_1(I>@2W^+FNDTt zVzHEe&k6SRe@REwd;J+S3kvK+Sn*27MN(C%@UfDfQP)I`oTfmGnH56O5zj#EXRP)s z!1VS|;M<FDIf$N72O~)SS3Lq})J<0shd(O_V$R~gg;uKm>}=QZ5F}*)=s?a(sX*^x zDz>=!x_q<bz>T?>LcxPP7dYhT=z&)x;Aq-xKeQGW4xrIWs!fFNo#L4G9&Hcn4<TQ5 z1k)pIZ{IVzs3j4wXmEtDdrlV_B%79O&|C@AU8Wfq%1bi?p@$|`3p)k0c!@8;VhS?$ z_F@8eN|5_a$M>KUT7ner8_++^cz~rZ5t&}PR={zzjInvF<@DyBB2V`qf>m6IIYa|G z*?rj#f>we@wAR6i$=z4jWYi+~J_@A+2uv0Nd_pQUg^A0`F0psFZO8$sVGDc!`fy~W zHu-;#Px={2I&oat#z4^tKZ`dYO>EQlakrOToNB}TRxi(PcS^o1r%u9vGpE3kl~)GO z>#J}}HZi)oUYa`tN_qIh<0e#oX1+Hz_ej`{5x(VQ*`3m5Afakp6m`F>mqjM8f>Uca zG{6LN*j6DTi^Q?VvzzWKdBCNkv~V()CzT)K0K@)84S;5lTYwEN*H=%`bmy&wz=~Ff z#CnBud5n@8D*k&j7-P%h8xHYt^dR%;>F3_M;?mejA3GU^Gcq0e*5;VT>C18p20>u` zy9y^xBkN?vt#E@Y+qPL1-Gk!m>jh5!&7dq`KjV+mFHdgUd_OoXT%}Pact+KPAtohL z#UU&wKd(v;WmtEpu2@WdTGP)>_{ZS!<6)Dn@Cdhz)Y~LS;o_R}KCaaS_5{W(*x#^6 z+g-N#MC>@2vJ4L_?Cch^<?dJae;@~AobJ=p0S+M@^C_Dro`RzJN7(weYAln9CUc4= z^TcM<whbFev>d}&?t|62&`vI0@>A9{lU;6PSr>3Mm0;?e4Z#2O7<1``=QN%<9ya~L z;E6}++dyDQ;ZHBXzPzT3i*1kT?2I-@Ay5)Uxe`(F#MVMUzB>-MF71V85pWi~xI`DD z0}NRZK4Vg%c7RFToQo<o{`$7NN8iR453Y?oKKcICP+sD|S1t(dVLZ65WBUg&+$6jN zt`P8*vN&{b`W`r+s%C6Ymq6uOt`6ta6Xs|Tsfc2W+$1w2M@0fL)X%wb|9s%-jAfcd zIJ+49janEP$lseEq-fiq9EG!Y+w%$?kMP4odBbsrdLKpz>)TdPqkbw4m9~Ec?WJ4| zrA{rUMrTZrYZtS?LubD=Q$e^*E<8j}0m9mJx23^h*V?yi+@UTQM|fO@WF8t?e~8#Z z893S~U=f`|&ErLSGAi2^6xKSSV9he8X}O;W;`u2?>UChk*FgBoPJ@Ix9kc%i7#6@& z+3^O5wz&y*+HT1wCZ3`V9a+k&scdjuouxO3<{?*L#WheQIk$VI1Hi)d4ZzP<Ul~Po z!iJ(}4lr$S8y3-iox+8RTcLNYLG<=K!FqrP6;G9IoxBB5^4Jt`nALwm%gM61q>#4+ z@%shOUatYW@Gft**3`U!Iz7^w3JU{$L^T5XRt?~Uw^9hOKm~U<z^@I>(xRc)iw~<h zEF3{YiE$a_mRVy&?Il2h)7sQVh0TI@oXWf6PVN7Y%pQ082gf=TjZ?PPONWj$b_!S` ztbas+Rk<7R8-cQbWH>iZ;HK+_g|T&Gjc%q-UaaU*x?}%Mp2Ul4YG$nAr^<wQ0$HRN z)bnUs1+(xpJtgTpLGa!p5AGuaQ)!#F`!?D^dcyx(Ok|a>aA6D82#5uB><coGMbRrQ zm_(2=D!TMkl_F2I{6I4OwP*@F(!zIUSA)ROoWWv#Jws&RK4rki`n$d9#{N0*f&Yie zRnJg>qJ?PNw*#SQHyO^&6tpBI!+Y5Owj3eA#H?y$P%2_+-qOl&D~!q92Dxu~4uE75 zfTL2u!U=rfhX?jJ5}Imh4VE^q6}HKa)B{A21rVN!$b@=Xz)nUb6#|yzR}AyjnV~(! zQ9)KLu9H=4Mm%G?8Y65$7PO-(h%3FL&UVu4z;EMmJOQq~u#W`4U9;#x*Yr_%J`5_m zyQi3a`s#aDF9oh6>}uA4IUjih_Khs51O63|$#17bX0>i{-)wm6ZpQD{&k|8wF|Dlz zCu$~ZTiC2Dkm9kdzi`k_E(Bze^hCgQa^8IvI`_;Pm6Hb+czK%2F8O4=ug<<QeJ~)_ zbf@{lwnLe@P|H)fM^&mFgA!`SQi%^~r|O@~Qyg8=&p1!Fi9NdhOjF15i7mVB@W?!S zN{fM2UXJ)ZfL=Be*;T9?`SUIM>#j>e-jd~W#N<t+u*GpwSF41+TI7p~?%sqp4z(x7 zY~7!<ku4dm6+KO{lsVd1;R!vo;h(>&RH~$rF&Ax3q!X3s*+xGDQl7J0F_ZQb+kx6B z2px0DIl_E%8?PRx`o?gi$AG%g;g$Uve`w)=dQLkOj3B>r(6@hDq^cSbw4Zrf-6XQI zE$e;Vh0-1kt;;TFV>G`1HNKT&ae4(ZYBGa)(vR;j6>2W~)c0Or72EzwnM1r{R%Lu_ z@Nzp5V2tG*3aN}rpGde12tT(3C~Fs${daQA$m@FkAk;U&Dx)*`V3!D8A~^VWrEL1O zvYG+DsiRcxu0rgQy;tu=w7|d_3%pqV&N;H++LYl`kN|R)u{Dk#WtBfBki5Puw0{Kq zFcwE?d795hu`!!zw}3yXMV20a^8%s3s(JVGW9FWZ$jl%Z5&YT9=3cmIMu5X%T8o_V z+!LK9ZW_y}!kCb%-4duxNa90`yjME=fQfh~V%xKxGh7w-;mb7fwp{AohdJ%*?Z9Yf zo|LgS-(nht|KZuT0M(nxBF#pllCL7RJ+_0zvf;L}z~6%mi=-I~y*Fbu&ofV4_O#OX zq|V@o6D4mJ=H+tF{yPMen0rw$d+s$?jz8xSKFwRU>I=)16YeGX*5nBvHs*={5PLOX zpe)c0)n6N7XYx*<e5U6Q+6o0qB0q<$zf+XIxt>Lm_npXWO_JCS{2%PFI;|p0H2NkL z6B-NzeFJO+{yirBwx<}e&H#4sn{MR#sF^Y{PrZb`V-TIYZF9g^v>@RZ6m?NGfDY`i zIlcBX&kzIOlu7^(jq#f#R~lIVFN$+%8<El4Y8Q+)-rcr;bRDj-N+}57?t)blk3PAI z>>+jdMB6SNj9Hb5h8&K2YrB~$7^OZQt744FC{K&8KQa<(y+(J_wzFnHX_r8L6frMo zo|qStX6>eahBg$ht62^ca}2YNpPujG?^BO6zLZ=*?M+0N`&x_gn0RA@x1%p(F@=Fi zmTDs%e5Jq}mejbE^8<FEc+QltY^^DEMtdogyKnzvxaD-{6Umd)yxZW$b>Z>_x4pNA zM?UK|`O?R&Q1n|JA1yN;Uj*YW5lebnv)r=dx1Og+o_DO0*P1l$b&)b-3zlC!U#^e6 zK};~!&E2oeyR3Fw<QQA_&(@RR+0M0Zmc^ovi-KjL(@@YTu%DYCrz2=|R!~bGJ85so z&dn?J@$#&%m&d1S5Q3bvC5J>IHa#l(ws4Iii{0IN<i>o*y@_9Mj~dHe68Lp}>oGv2 z_hS-HH`s+t!L2|!V>|=&q7SUJ%&a5o&Jt8jc^4!gYe*Jx0Fnl_E`&$jG>LQSBdyc3 zw|;JW6x}?jbFp4TZI#MoKkY}XEhwR19n`fsjJ+f>IOS%7prN;a&b^cw!N=*ZkAhbB zZ*&CR%+keJ>i1?<QO6P0ub2Kfio`|<Tly7-)7xk3g%e_}LZt5tOa<wJMRMh@yO+i0 z&KN0I9=4Tz9SiP<jUB-lq0tzZMVh2-<?`qe3+1H4TW*228*ihNqiH9vkJzSZb&OW| zEF4CX23~Cc;SzKbI|VMX_sTO@ROWnj<KGG%tr?LHPq#GN;lEP`&HD05V<L;30HT36 zU;GDr_WEJ7c?w*>)z!(-LZKHvzKrOgMVZAU;BpUG#dv;x#CBijBHcbRhX28D9-p+p z+N@9Dpz?qCggK5$pP+SS_K{Ol>|(8bds+*$WMuQv=CUrNDyuq$RL2{g+3rLdHH-h4 zYBHZjRIXa)#w=Ui&}~(G7>RRC8A5@PT)6~RYx8|eCY1ZJ&2m=>5xjKmU(3$`Y(L&P z_CMgLUCbw3Q1#mLA*r3&t-Gz!=YReOJTXQvc0Veg)59Y6Yc@re&yzOI?*gvT-=$%D zu`#bMlpp%7Ub>5!t@`Suxo|aVzUxvnPfNw--G-(8jP~~>uq}r#A>>Qdkt23X%Ci-T zxhwzN*P1Ia*baJE)hOdqrw|$9yqV4s(cG<VO$iA`l9t{~)ciC~(bd5i1U>_sqvHXC z{X9jRE9MlbzJ{HTk1TVGj&GevT5ofgdJ=hBE?z_<<8J}!cjjJHtqS`F6MVtK&kJMl zxoVec2sfm~HB_K{M(VlK&XW7Rg0SR3R%R#B&0jrd2aFrdoM~yUHB^UEjK;$&BtmzU zr*enI?H-2vj9?Mx{f30{ApZfc?zSWeElXaojNRIbY@WiWNBg`ZKht#)gb+YPma+jK zBNJ}e$wwON<o=B^{`sLl)N#rS5@i9}!~QPN6s7+IZsJ!0s@eJSk}bKJ;rFJV(fXWx z>pqj4V$=c5zquCVaDhM>-7#jINIbsXi%5<L=Gf0aI(pj+<}wOVCU}tnOlK)89((ao z<*)u%fUq|<<`xJ4$8MBUUBWtk+e5BI0+o6x5XPOK=PpKS30heynMobtv*SZmgZ3?& zc3`>Y<yvvmsest9(+2X;Vi+h4;@k;(Sy`_`bieb;&}Smz6?;2SY^HaUcw*vUSqWd= zQ>=Ij>9j>C7qnDemFQ?0Al+XfqUvzqn>mIldeBq!z2k(&ZJGC*+c-|gr9WZ++FRTV zMX=Ev1~QtbS@x02X)h7_^waN_p4<`6rv1*r-?eF&AaR<Bv`{;diUqiDo}SqW#E#$w zk@I77s%UPBi;7s6qapcHyH~7<1Zwf7+GNA<$6VF3t;+mB<^QfpnT_rzI+R`$h_OU1 z?zV%DNGjubwwBVN<&{|DF>usu<}4!%D@7u^1k)m-uDAr6RK<8te@>;Sq9w;@N<V6u zubgH5zJ_~9eX7oTT#&Lmk@5N|eO%i95J%%J%1D3ny6Ya_J;R)-v;Ml@%b~T*12jx~ za_imXGG$3aY4~X1nc{#Qya-|_OoG(E%PoD&5<0MuhxAG{gn?aqfv@~GWAeY9>ANW* zZXf|FtSfQfJfj9>h!O{Pn&Dd1?e%w_x>JIQG+_2AWBNwck!lCnJ!DYl%oV`Nl;!gX zdou*94RSxze!sN{dF!m<uNKv;zAyRXWxLz?lef%Ox~c6!9gZ>Tr!c<_>xkO8P0)s> zXLeRgFzj#mlJ>H_N7_|C6bs9{r)@_N)wkU=`Z;r49O?F^Qw=Sp$bfEJ@y!}YYL2a( z<HyZXVEtk>MMCLcJ+?9e()Dv-9LJm{#!25b#JcqLJ#y*vW6`PFP^nK*7<e`0F1p)% z1)nlc4rXm%kE}a<i1ZTnloTYU15+?sX&+*ZSAHvOdtS*uNh}uKJ}7(L=tz&(kjE1& z!Z&4KtW4Hu1N-FCiV}*BIcIG4s^H+2-jpRVJOiU3TducRI{#xq#Ut&g$SWX#FvUhM z5;L(E-TO{!-WR7KpSg~tac&6}8%vOt{vJxu(le3!5pXZ^KR}1q$0dwKGOLSG*!$W| z?`HJ(i@nliD@P^N%N)nbN`k-!_ojoSF-kxu7&e%_-crypb)6)h8Z}`aQX+c!wmYO6 zi=%$KbzNQIwa^Gw*qjjE^69Pbv_1cEDHXq$yNZ1mMHP}{oEJp~Idh84!w>`h$yHw@ zo)BX(Ku!FmTQuIjK-uDud^77S-!=!&qe0_jo!*05@}aGNUpBWnX|P6y-_lPCb><5s zqrIaRVkP$!coKe6@K2s=J_8%N%Q!su_nS`+J*KC&QYCV23AlaSE!EC$of7k^yUKH9 zpYlla+SN3|nh-_*`iwfq;KWY{{yvQ6L(k`rW&1Hd3nN&lbJQt!Sz^u28`=`Fkh)YH z4MplNME?hrwMi*SS`OyzUIBC-9#ExkJkrphB-P2DUp@BYB(Bq*t`}9+_nImbq77Gt zRjlkO**|wrdbl*9F&cBcD0D{IK;{0t`nUBU8%w!7W`*R~$H3B>tF?6>FI#t)*b-Y+ z#NRm|I#AF+yo0|{>ZC0gK;0hv=j{=dvC~}{UhUyK?ns=0P_8Xy|F=TnoknbHmc#?< zsufT1!>H-`I#|_P>l%3}RnM~;%z%#{<(Y`(+{rZ%MWn(Ay`Yyc@LUA=XOy)aLs3F6 zc-3agrWq#b!e@!O?BSBz)PFTPx+M`rH9bAP2e-4+J58z2Jy4ab%-LLO;M?A#j<-+F z=gS~GZ#FlE+l<hbI*@XHK`eakYI4nq;*7-}gZYhynFyR2o+r^MxI%BqQhfK}z3i_u z+}VO1<ud~p3s#yytw34Mv#_A6Po<sz;Ym=yr4fsXVP!v8F4Se6cMldtSvv36_=I7N z-v3R#cr#u1{W{IReT8!y*|EpJevsR7J@6kXh~_zq2v*7ZTg$_A-*YkFpWk%WsiL94 zBf+9RPNbx(<(3${igNo86tOYog-?Eh^Y25ReF$nWlOK5~ii4ewJaO)uX^3N;76!Z@ zXjiw(Ps>aA$CwdvpBtev5xQQ)vgEJ5ZJo(~w1kyz=bFbjY5ydDL53LCE)|dgbmyMd zo2(HJ#VP~kOuB*k0IAdN-xRs~I+A8$j0)FH@Lzk0UzO%E{qscdd*Az$vDV0*?hUJy zyb#2G=B>`Fa-YVpsL`^Ag#rBHgam51+VAxZ_mosID~;6Xg#a=eES`_FrU||YqmRuT z*#7BRzA71<2uo?;kXHNNO^Drl>}1LTN0EJUewloY(B}Z|+>(3sY3H`YGGAi!QTv^o z>+`=?J%|@rda(N9mu{9>QeALu{}_QGB2C93t<G-@RD}6)OyBWtVE*gtjNiDAe5-G= z@BWM{3FcyzJKsjT-JTj()#q?1`k6>+6Z|K!G0MpbQ0ScIppoFR%$Gv6(?Bt*c0;!v zN&-l620h7QO+VP7G!#AovD20`edpTy4!N6n4W3c20YVzFT{3&OEUS*!to+ol-LXlm z4j*Sm$KhJh$FH|8X!*iQ7y<aLqc_cKsy-BFUKfn5xYC6Ob7m{bLrwh4r<)F)Acr+N zQj#I8IEY-p5O}*ho?_4MZ<(Pf2#@~{7*HP8MW#$s9oO0+Yl!`u<u~VS^d8<|e+d>J z1$+Y*9jhsh@5_gJn75S<uw`qN%LY`x7Oo5(T3Hu&#5tDXcW7uOwPI)*T{pS2s@>yJ zl?#6a(K^X_np@<T>Wi$MSW}{hbVXTmHm%NJ#cvmjU!em8vJ|*jGJKvyv;a0YSX_ED zaOD)4jhn2>4Hyt!9e(lXqT~C$aX9RB1Q;&WwcAZS-aSmacmsn*uSpe)NkWx9rY!<! zuu4(L%h30TrjFD_%jXU!@gx1vVzEhzoOO~y)te>)9S>T%gnf%wD<Ymw#e2ubYBBN< zm@FxChosO9@8`Wq%722zuSl|XiT{g`i~rcP6#k*M)bz@9biS@-^~N*B#L?r6qEJ6! z!iwnig`!5mQLlRknv?4Fz>?9YIs;<<G|hO*0$t%gNAVigSqo0*y$|6%7Y<lQxPuPX zu;2AQL9$ozRh4E7vbC)EZFcg4^h)h{FIhJqalL;#_nrIdbG*(t_>Y*(k`}#QJes>{ zGb(C=m+?PY#XzquV3fGd!YQ3qF!_+K!(8jMUbtGso-)JzWH9Mtv@4O-s<k+HVa5sh zk6_YCe^H;aU|B$q$gdiv8(31py-?V&k=2%;QSW>;aAfOUM6Y9Iq)X{=bWRF*FfF-E z8`_d@7wrq|%}G9j=U}qLxZ?7~eh-$Eca1~Iwc*?zlu0}09Ee`fAC1oF(?){W0sj++ z(iTwE{4}bZUD(>9u@k7Ne$233-Lkdd=U0%;eQ=3ma2T95#wr~HTyk%PtDdu4M}HHl zTOfjs)$6!SG;-h(F~58?qSv9K&einG9ts5Yy*a7l@On@AN0W>z{CTl{bEs+`P7;>} zCfz*y>SKiN%ikEtkBxal`jblR28&vpJ6^;K3I7@w{Bq$%vhwEZmP7|vo|E}MM4hXO zI6eAqr}-<-Hh{Y^BCKOstIjBN{54IVp7Qx32Uk<DY7XEcIK&@6Bnaa0AApyil;XT? z`vKoD>VD=4`k$vy!J+PQ;onJ5WR`N1&PmF5eEan15i~v>^`icj6nfWfIWF|&XRDdo zL4n%q>a{4^ADa3$$P#}%>TDdK-hoUJCn?q%0Q&W^_|5fq%H7>%2>I)N+~-+X8Wbik z2R3y23j-8hUJuJh^1*P-W8NOZ)Sbc0_Gt;mrDvZi9S<IUjo#3(^c^32_)XHGzL9eA z*7-=V-;`@MG<Z&O*sn@<H6dVrZ5|wd!nau2s_~8H;p(4Kx7}(kYU`b}e0JYFo&M}` zu(Bi@8c%^0H;2DHH3U_#e5L^L@V)UqH#=B-mJpMul_O<-<J}NmDJ~{__GwOjIe?}c zI(=EHpk`6f%Xf3~I&Z$qKJ?^^de?2^L0xyU0-Iy2ctf}x<Hb0r62A+>{r+ZwIk)4y zw{XM%8IIkBBx?GPVvU9eo1d4Tz8`j)Oaa^S^G)_8?N#Sr@*VUOIC~MjTw{;62i?BV zVpm5+hsTw;-avMRp<|lnl=KSC07{%lP^=T~WmT3YdwA7@*_XN_LjM8gQuG?D1`EH> z+Q~D+=IKupU280~-C8j%(huWpTGB_ac13Qo<tRC@v9*fQ{WA|2b<=+tuD%s%dIZJC zV$A;oWSkF=_V_J&K8sZ8PH>C@X~LlQ!s_y~c^B0C{CZr1ED@iGf%MhcgwFrgd^%6m z@jPcD0b357QC9H1f9Y`HOF)oC1oYQBB5i*TUS9eSSa-uLUVzqV(L`Bj`mM2ZE<;-r z9pUYv@lFi`#WL|<YENT6#TP00!8uPKXcII(D<`^S)5oNk%DGrMnOAdw`^fa1@~;*o z=U!EJ$;Ts8h#y0Nom*vZqUS6^clz`&M*Y8sejfHQyqovxP6r8u#fVL`cEetN5ipjY zo~0Y!7?ybZ?7FG$%XHJ`<mDmv=6kyDpJNklX`K9*u`2Pw@!jaGSzD0Qi#G-7?s9&5 ztHTZRSIz65SY#<3XjgGEio%?jaWrvTJsdQ}CJu>N+I+efV)1Kl;M_0XaF6Kf#HgYC zc??uvvMYk4u>@D|I`e%C@92Fgcv5=YxK7T)eMM|!h-N&uw!|eho%J!9?{r=&zj!!5 z%n5=Fk;?J!+q|(8E_C@oyVL@Hgh+M}V*NYHxwnJ+IBmBLng}W`i_Cj?{%#;0yDj&^ zV7yr1m-EI>!2In4o3`}Qoa^>7i7Uc+tP<Ilhi^aX>>sH%n0GJrl1My?UhhFUGDt_Y ztKWugS<_ecFRhfnP;Z^Q!zvmpTHLr)GWw=5c^~QEJY<C1WR%C;r91R3@DTX=C!-s- zXvWi^q%z<GWv;a_a$-kif1UQnXH+AN2miODCq`-82rD(M9Ba_V0i*w!w}0!nR*8>D zbHP#ZLaoQn8IkoRBa1FE6Q?rL+x^UAv_HQ;Lv`_o%$k@$;)7>rXU&H63>aol2>+|^ zDL@{Dhj2^`54F+zGBTkAL0ku@nB4=zU0{9dAc&t1DinpBneV0-jc5FE!Y4ul*+eDj zFgn|&!gqE!R#pZ#zh%cqG|~ctEJY~gr|~^=I0oBpii*%pqqF7>L_e`}!$XnoH8Apr zfW`Uw;g{7snq+wPVt<Ra0AK;3N*O5jgzAEQEQ^6Qs)SCo9kz_RWhn$+=Woyq7>1mA zTd<=EL?!tZ8pWT*^&^8>y>?Ifp$iny;@eK1*G1a$2d^@?=T~k>S@$m$LGa0djp`^D z%ngflGQShnr)(6q!a(qv7E*FdKcj&qp=}c=l_gbpE*!KK07hVfnAAC7ZX(~GoCPhK z>krKnm~vqbn3HifJ^(pHs|bZa=st~A>V11%rt#gC4znoEBLNQ~d7tyUZw<A$zcWj# zftJkUt=_*2K-A>m@C)O8Z7}%GFO}_rwdCf@m2`5h5=4lxLFZo@D-VW9Xj?(zSK?rp zcOby2f6FF@qGKiO%J97h5q(-s8D;f71)zif>q|ISpnqq9pkJV!-p&1{D4z~93pSud zCviCDj=>;g#R@`|qlD(`w-1hph7?EZ26h1FC$F6mKF`8~An_QLzIcN+q52p&juf+B zbI$01#Kqh$Jl*n^xo{)pbu2tSEmdp#gf-c#u2A|*r(||M=_zgjOl2IRi;MT@Rhgk# zyfGo?d)UKSl-(DAZU0|Iy=IPj+=1-?)4e}h)F~?nO}I{fAP`|qUgsE}41w>mY7o+V z|4?)S^I(wlhMl}Xq%{FLzgya>wAQ1&{7okyvRGW22ti2ZujKI#BV4e!EgN5izyS$V z+BX%aMu)my>(LNk9c-!lV-09J!qx_?iYXnpR3J<*s+3yCn=`}#i!31cOfuYSYkNDm z2wPUI$aMd!NJpF`ss+q5YNX}jtC0jK9g|fEK&2vbs2=b<JFj?r=U+td0}Y-~hP1!V zpR_ti=dT_<K=Th&jxC>upy|b&?eFJJu*gO;{My0LO?;)l2}}<?+n0##rgkEU6S<pK zyezp?<IZ}m?eOqEIQAguH(7Xa+@}#cBtQ=4<^Fjwy<*2wj6?k|T#^Utnlm%v$7+LA z^S*qBbU7}5g~ZtX{j$DZ4!@hEE8u4|JYpo8#sEMlXRxVzN;47Fzg)B^3ni$vN)GKQ z=`qWhRC4ePpK7{x$Soi|hp7njl8WdJ{C0UHqwL5b9tRLDDVlh#_&)763@rQDIXy%Y zkeaxSM7?|GrJDApmGQj+gY~DfGMyYwzBl2}!8_+dtV@+tEVNE^Kb8;b%FEnsI1?)g zAJmDq#Sf-&MStE^a6hY2g>)}&R%K1QHIb;GiJcW2tPG)IRN3;}-?2#bO3y@Xui5@& zzj5B!12cM2ATjA+NSm}T1EV;39}ea3xhfdYyF5Sqe<YoIAk*#t|KBrA$U3Mdo2j{T zDjD5u7^6>4$yw@74o#6;Y{)S)BzNxF2vN<U+gXK<NSMS>ArzToqgf*7GxzVhzrX)w z+1|UZ*WvkmJQ+tII8$Kc(-pH`>m0Qr*F-;nNUp!P-WxS?RmuQUV_ZLCYA5%h;3?NV zxC-3%)=*UPhr}{rT0f-m`?2}dmJdqVqI|}qer0hXs<psT@7dy@VGxP%m>Y4tR_Xw1 zl3rI|Q&K-W?zw_ZRx{EJS^xBAK0d_&v<B@A`L_1~3IRKKqQy}sN$Ck!uu#a+&^u(+ zI$qL3;8ztz&#~Jx{=TO9gODegIsBfJQmk5x74~&!@e;iicsAw1Ie5FHUzK-}Q8=Y+ zlP%|-INKdgshm+{lL$ytZw5&0G9CtRBYgPYcXNfX8%Y*{fxjFRMsny5Txex_O`04b z4$Hx_1Ls7hdBw`&w9WI%ayePcg&jLQgSb>u!+Nj8Fn70TL2mf7)b+2`<K8qbB7oKb zw$yL3#$$GnVh)=7&ddGW&7?f^DAXoW5**mNf#uH95du~j0RR#6#GB9|$}AFNxhO|| z_9he#uMt@>O!<AQmC@>!{Jwt{dccl%c5iZ?M4N}r^>6tbBX5JM$7zd&*F6(1D4q@z z$F_4Am1+eyvVeM&jL@i=gmF6|pVeg4fQ`>@;X7ly@7>jS;2~Z*HJovQw#U2x`#N|f ze0qD|QE`<2WzzxOMp1w2fBQSfP40}!p8Pb?G$=g_TIlwA<xnR|@FhiC4QV<PDPWiw zq#SlDB8xaab6_i!T`<Qowtvs<3<TmZNSEU|4$AZ{3V*)f=s9h(djZ)ji~mFn7^_BX zh@9;X@a@jq;)|PT?HKjJ)T}!$G=Zm}Kzl3-7TYshvLb=ic1NgI0ka|la|ridW@{*Z zDEycGt6#ZAk~+3Qc6p;K1%r^Qc!nFLHz(WB>72jn>qV8wb=gIEFyuwtYokAk?E}KO z&n~%sk~h`G1+&ZR&L0!7I3G9*&z^&CYG5-UC^nwCI|;ga@xd)q7n9g+PRKX*>u@7k zAddy{M8z@JEmg7MEbem2-|!|i9=NBb$*`dJ&&6xe36K}<Lg+yD$H!*!hIfoZUrC9F zDXl$D-_bgd$GP#oC8qHA5B^kFlb^AjUl_k%=~WtQYOnpPZOs|_x-{KPX@56!DO$%6 z>3KDwz`0+~lNro6=}wIUb0<dv7zf3iB*Wf<@p}|Oa6jNn8)YGKuKTv)1dN3&rbl)) z+lS(=Vr}GL@=)jy!+b<&32W7;<(-^rK3qk{$M(;L7fB2de+;jR_}vUS(|+wJAB>ut z&=*l82{5{+YeSupnMG3L(d2LU-oJ9aqfMA%10Rn@MKI$XJ-)a{bVijhaL-JKAk#@k zb~&vQarsKwvkmR}ZI{~xI^Ld0YbbPLS(z5w2euMfMt~t)M;0Yn;8yE7vXm;}NjPI~ ziZ1(!WL%I@6%T*QAKCsu*?yP4t);M{q=?uulp7JQVGeP5lfIenFBZ}oN^yV<cT>QD z-pIwgO-aB;F{uQ>5B2k(2jhF0uz|EYD9;eCkZlcJY|!J56r28ta*P5!n-=+fo*=nj z^g?db>74g9915&*NQvEyT|x|u-@`Hm;#OViMn1tPh^lL=AxD^$vxsSrb3?k*c!4(d zVmD<U*C+$j>~{K>wff0U0;ClF%Pd7o+2^JHgbU8=+Ry^Oa$WiZJjf?dJw7dUB`a#V zSWK$*uyJrF5!;?}U}yX$fk;Z$@*oIE&j=qSy*N9YWJ%Q!+r!$SMO(TY)}h<1?<c&9 z)%2<!^;vT=VF!e={?7FPr^Z<0PvU4!`q;|fU_)1q@DL?kF*TAU{Irl^i%dPfIplmr zSFCnHmQI<TH43;Q5<&iPK2+J{dHuh;r$AshYhe?B!FR=PsZ0H6&OKx*L`y?4BP3Tu zPNb8htqd~5T(6YR24<|C?F*~IINd>{pVI=~<4uA0@^{8TQ<ni~u!*$|Fy3_v=3&?1 ze^M|O^UYde6vS1P6+ur$cRs&{Zlk5hu%I)L3rUc@T%=cBCs40Xm9(|bvE&ZmCU^}m zP3UwlhE!W8E@zYWQPn8rO~?vR$6f&UzG3hJCO=Mb?NXYdV(<|;;v%R()y;KTf{9MD zou}ISyp0+~dNt1tX!XUgnI#&A^ou5MA9U#9AvJzq$s&((I=RHOLzhG02#QFh(v?FT zE$x0I4xn3HY3vxjImd^Cv&mWxd2i)DzOfUVp-D?=y0uZ?yT_6Uq8mA$Vg{EOsJt<I zhJMh9ZB40m5P7n{(WHrO&5m85+Er8l4R0Lyj~fB*h8nEjMS;Ro&e`m`=LTDVbaVae z(zOSuQedn4sGFTGcolw>M8cCFCk)!{jOPbvBMMI}bkJ78m6M)8r?B!-aL$%-x-4EI z63#M@Sj;;buN<UJm_!u+S8@%2#X)e3=``C~Uky!5p&~9t^_U+}t$^t68TZ6^FVN`C z8U>}?Ex(JL8~uD%-BY&pfpL%2YNr(*{KPwVsa9aN4<<{~zg15fA_Gj0TL*lq4d$e- zSb;5xjCN}<N4As~V;yx^Gs7!|)&`;`jdRkWzfqoKd!4AT#bwBeezwgkZMuaFe*Rwi z@nL#|0AqM5D;yFYm6IIigaO$abVBWt^EDJtg?@7VpqsANRvuc(&eN7^f^E;T2}h5I zwf-ca)*at95d%WkSvpaI5%4iM=4IE~bwJQUoQYg-pu&Lj7(U0Cl51;#e4E9P>N4)K zwKKZJx$z7H-#%RQn8~&NAYl*J#_9t+IlWF@@7f?O&I(b}d`Lm1EQKfnH_aFICSL*^ z#d9aDhk>(TN2|w5W$4PLx}_kj_`mxDtv0BGnijDDr}sjkTECTx|6QIxm9!p`C$1vd zVo$ka2$G^zKRi~r718-0$ld*36TwC++G53`{3>~HZKEv4hz$a1@GryL035oZP<cn% z57J*w>_~?NWG2hlAGCm$l7KoEG9H52DuLD#Kk_v2IWaKH)1LK$TLRxHUN<MEc2E{f zne>Y!yO0xPIfw%7u7c;<xj88YP@5V~@&_1YDDQC?!(epXv5d315so5m|0>xe<ca%B z48F<1*H-m(#~DZ0h&n7T=099_6w~weE;68`vS$l1v-!bH{3K}`_zLL1s3h_Ljg?rn zwp_ILYyBljy3^D^`cD}KzDtOnGykTSmKuMDmX_KRJHSwU9--bKL@o0$?3ah1-33*^ zIJ^fDZ#Q&z>stbxU#Hw*xR<HK1@;`jgd1u=MoeS#X7i3ROWz2>jsXoFa8+6fd=W4^ zlyQUbrLqfJGbo%tMV1WSe!lvA6?yWEtQ(aoNq>W!u$2Q$L-bzJeY4xiwUJSCY}4sK zpswms<}w5#3qrLE65L=Z^}~y3C{?JGSnS^0(|h-Az1UBlM<HaCF)a0iNHhUQ_!Uc& zM7oK_*;bfG4~Yn@6C~$fP`L~(9yC)S{&%dPtyB8nogEJtQt>_CjdOa(mCHE$S~u#} z*SkHn=i@dX#`1vCwZJpBr@}Ty`b<Km*BDX(D-hX@UvcVtWdWZpxV)`pjxY-sW8ggV zHQtCtM#8LZgM0jzKmpX9>Kr?tr$A`K!N1&cns~}30y%vJ&@E!#X%lx;^#t0|`0Tg& zCK{RxaU&WV#{<C$YE<!&FKsTyN?eab_rxs)Si-5AT|QMy-xvpB5`Pg|qJnu<#j8$O zotF63tdvL~i!V)6p+;7SFKkDbis8|r*v<ybzYsv(J5ztf(PvS@3BhI(ByH8Y(cifO z65~}-s)4jNljFrCJikyJ9f)`(#RFG+J_%s3+ov7U0FJ^Gc*78_Fc8q^GqUDfmi3!c zX{!+(H-Uz+GEj8I2_Y3AIVeexj?Ufyd=8*CC0d6XF7zYwl+uqxzhdXIZlzO<Zkc%e z0g*4L0Qo0(oE=zre51Ih*bHp0istDq&>g~(!t%6rL`=E>tL8KU5|)AH)9Hxuq&-Y| zZkt@v>p8B4Vppum?<yCr_#8D@M6El`8v9>wL3oj6A@!pNjQa&_k(1WG6{Uw{6!v(9 zJXepy$+;QKew)U=m?c`XhgECI?~)6ieDO1P?6SL|tY;5nG^e^z#4=9jMJHHIUg$B3 z`2$is#;}8EgXkEo-onuM7x6D-BR8B(rGp+ZWut>gY8`_Hm@;SCrHSxSd-&kAN{S@8 z6<jXOy0IG#V=ZLke+pnO`k98NxXt_i_cZLU!-*I*SVCNGdcc5AbUg_6vQ8enriuu> z_)`CaPAfGZCBPOJ>T5||GR4Gz?>40Mb2`8vK-5oFmxnApz@qMlIvLez14bxepstbY zS4Ic-V@0uKsRl!&JA+l<yDgoza&9lri@#J5)NnLh_R(7EQsL2#CX?_GlHLZ$6Z;So zg)!((&051TqiOf$z5OxK)k2Y@XTaMM<)|(=TI~wAEg-SPWX#qh<<Z={o^(a=%OhR1 z7t^TmIWm9KZCNDh?}GYeO;OmW*tnYYusllggWE=1S9ymj4M(>n*(W*IzcFBKRLN-o zP{MjyD70Oyt0W4#S^8oH<%1!lIzj=Y##6C}b-)4yCHa^zw489wF-7h`-f{tVsD)Hl zB4%{Qc#=19I<|9&yV60=NuNLPy>%?YcrjjlclB<5G1eNQsw{~w^D4$HO*aYzRqpCd ztZX3WGKf^_FBnD7hhvB*powc`mbgRIy2?|^EkQc4&6tC3d*?HzJE9y?SsQf#gzpQ> z^P&ef<?uGYapbgvS0K?EY)jn<y<hkp*CYSe4u{^VhelEMVo-am)z}3Ev?D9Qq9_6o zg0G27B2b<4;FZe5-5V19KETo^^m40%StG)I%44^}#X;7ZcA31+Ji#a_sAi0y08-7> z4ys5KT9-sy8YkzIn}hpVo6go!8psMLtf&l|Npz}CF+qw<y+?J$>}=1aPLkB0%)g4s z>U8g|@oc66V7Jx_FK?N&pMEdIuvtF1Ns{P6{4QcA>6GRBr)jTH0)D@vn0-Lw_%wki zGH1Y{Ky)yJ*3~WRGg473kM^YG34lm6eC+i@v}bUxb>3dYFIXxo|DSHo^b~k42=w5^ zRSyeLV}O>=gWtj-N}5ju(F0%Gj=1;Em`j=?G5CZcrO?t1fr+p?9^b@DhfIf9awc}O z;NP4>?*=2DNN4WOcn;X~6ISvh-U>kEhd?xC-Jp$E!-g>=jkDGr;*81KR6H*ry&ID5 z@90V8c?9}FE?%2Qt2YF!#JtW`dmUHKo%~SJR-*OUwb;v3sjF;jDd}(m4+q>#k`rz> z%BVD!xf)jA#+x&ZS=frQ4`bJ*@en<jt5VmB{o*I{f{^mi(@`}9JV%JY+KFsCp*;|W z9XM~`7`69pY@hhX;?~t5ss)NGP~iPH2<eJ&O3}Roat!RLWtd7lBf1oFyJI+)+N0FF z#qSBwjwa!|U%&{^Zl+RBmi+Z)rC!fCQ;$H?&iOpd;HVFCQQCx;1f3kJi^(8Rr7^Xx zh}e~@nBF5zJtmm~+qEz%Q0}1Tz)gIhD74%HM3qRGpId@Ay!;>k_8^ephknbH2;Lfw zShxS9KPdOL-TOA<-kE~EKzj5?;IKxv4t-hMq=ln1I4ZB8oI`q~g9ysg8KtBxKFoZy zA2GiD#y){C>J4Mt6=F3iMYTmpvf7E=3^X>KLz}h*y6x%J-Qd{FN6g%jnqmsYVl&pX z!Ov5T>wBRZm3>C6>Jx&OlEJOh?DjOUH<u)p29dO-SvfgFB`}-tcEL={aX*`~a;pvl z!7s<9OT6qn+3PI?`J0a^M?vZBQ_2G#IoWX8psar(WycJjECP{;sZ(#hXVo?knG&HA zlb}B{A8xdT?>`8c$)_Mq`+HBJf-DGICerEHT7H$0U{Y=1gVDn_;OPgrB$(<1hMxV@ zsbw$`&dOT+{k(Hg7fj+A(jM{BQvMMr-^1Z~c{>g;gU-QovVV|m1#yInJltYQ3d4NV zOt`b^{>8~4=LtLUXoF}qF`M#Xmxv`H=(TNzn4=&}r|SK*t!fn<jivgEYsylvIY`i7 zLX@K6!fH{cb$ZaC_pF?StwE0q@i!-xP|(%<C>+-s-U8lp$l=9oTNOtsQgSIjI~Ix2 z!2{Vsp=E8-2AG$QiEN;0iA48c@?Llg*+_Pd3t}~L+jHpddMT2+shssI|7_G}YZIrP zpfHL`%(1!#>km8fuW>7igZY7eF&7&~aLOeDmYknF^iXqEO^Ji8*k?>Q8vu0xJwCJv z&mB_^oiuLf&iZj711A%oFum@CtI^PhKZka5;c1S6$q!6u1@ArQ;>b(WsXc|K&Lpvf zr@sIGnX_?vSKA7WL7sNUqQYNhoNYNkRG10wuIp%&=U+S4?zzh(BSNCN%<8da>gA*l z<j(8RVmXD<y{$3;I>5xRBU(2S9O-#-8LM-1$hTpU%f-w6^3|_8-}f(lq<{3Qsa}n~ zuCkd1$HSkZn&}p+58l0^ALyM)7O9-p&#da95z0Rtvud$w3cg=(>02-R-gOM}k7&z^ zyVFWA1Us`Ie(pOWVf=t%(3@S+i1`Z7x#PDFWu15>;S^!`l;QGc`|pZ3z3${amoto= z3I0+)b^M8=!^)@m@b(bFtggEELONQ>7NG#gBq(22o%k6Q%CnnryzwdJfQjA?FrerP zE%9zYMC9k>#LrH<KmES{nm0=ZQ-CfFFueZD;(_vSmt@#(!T<wMIwqNN5?u%zb+>3E zd5a|%5<AAa;%F<cmcb-lCN{gWbm3?WK}F1zgrB<q`0n)4)H8ZUl|k+1L&N!?-xE1Z z?~&uXe)nPqn2c@H&i<CExqK}bFY`Hw^g3iy4esE8398l@^g$^iyr$hgkA6LJc}<on zmXinxDgeIC3N87zYX?f#hlWVqp4=ps)5m2pt#<1?tPvO{Qdn<aF!n@fJvbe3@tqeC z<;Dn|N|P_h+I}Bb8Y3_N;>rJQJo&*=L6R`8Cd0$A62X&x#!#l>uD+z9JiNmhtQhL~ zZ_UFlw+edW5VGob8t&I$v2x+%4Gif#+A{nscHWNqlkPU^sRpv(E<60jcz6jZ+drN2 zfFS??3H7$yzj3i)6CPuic%{b0UkVPrEgSV@>FXmf(UAxDtM7XzkT92=L5?}O)t;=> zh_9Ui0G8}YF%uoT;nq#{0qy8&!uF-2yUwZf5MaUV`u=?7O^<gR!W=a!V0S;}Yv|~3 zg4@6mVp43Ivj{t3t|$F0<!L$M<79pI>qzH7)G;CcH&<0Sz`^hf%_cs#ShN!z4Jc2r zS1;|j4YJRRH|_eWKmprJluB?7gCH67Vkb8H{OL=R$NFa#aX5u()?n0fS;-xv*1r$e zZ@&ov4cLXkYybO^cdg0aUBEyD?7${K4zFL{KQ#X?9%5Wz8J<1;NMdlhR<qUNqGajr zd!J#_F3zdILUgHpBmZ3EKy4Buw*~o9o_kBN?U=;_IhVRfJ%iEIzNu!vem`-`KZL&L zwGV_!IrLR3K8rc-{<*WYq2~D4h0Qe#LG%YTLhN^D@t}kSYRxW&a^Zx{-$%wqH2T|F z)(i2S1YVWxNIUM(MhEXtOus!u98GOp9H(t*yg^8vX-aq3Mtkq(D;0z-H~XS)I{ft) zj>_#Yb_;FM9WJ=@#!)qFV23AuezSOqw@=IJ<a16X`o@3wIfudhfip~W$V46Q<@wmK zJ(AOp7}lF*inDo=7T<l|dsPKXoEgNc=B-C9KALUsQ?&W8Z(pawr`KY{j!z>mPm8M` z=Ar+5flIE9sq3G|$BTYkHU99awpm?cj6btbjqkvN0V^6z-CmE~pQc~@$IhPtZIT}S z5$aYx_eRNJbg@yyXDzlmeSBAFCXPJ}AcWJLSt&txx#c0M{<K_vRX`$(R098d?!qi( zBdJWvU1~gZ6QA_c_(03NuWxedvy%-t6tP_Kou*Nj?z2n@)=(bxVI)n&0>Q*qvr`Tc zC%!0eK7D%0WO#HtH#uVU<xIBxzQ^>tbl%f@56;2k7E*K1G{4Gi+PAdC^*O&|955!z zH3fG4U!pSyJ`nlyx8<X>Hn+{{+iMIlDM8x(#yRmz6-iI#p8uHKloFZvI#i8XB#f;7 zu|`z->n0Fujn(fepEi6?*GoYBKD-&3T)35Eq&>7>F<s$TO?n?<HsS6W%w?1LPYW|- zf=LFgf-z}va!$c|%77k;az(7h@`?*-Veuc%`uoUa{5O;Oqc-<8(V!*E3f<Ch>%i|^ z082Ce#DFUqqJ#f%T9u@y`|2DWkv`<z<|O&qxSzLB(dcno!>MJD4K*g($lqktZu8NK z&)dg#jYCH9ohhYh+g~K;dpBJqj3{AB+U&3+(Du~jhLeAc*5fo9b~F!iPHO58%W#$A z;cKp7{tUDN<FI0j*q8Ze)^NtWM9<#6@$7ri2F#eHM^ngK&uUjGHYv#0Wd<=}Y|(`) zhX2!!O4|&P9!7PKPc~d*Q+b;U|3bU`DyHLQ3Oi%N<}^ebzhQJjAJG&1{)Kpw%+;_n ze=#3tc4-;j_yF9S8iCW)f1#_Hjf$=31CIVSD5q1Hw)v+lcFt?zM8&M`IA1;A{^4KZ zsW}F6x9T0X@>3qv8L2rvU{d;IVply~Kiji8fAM!$dbHQOY~?G+<x`MzURJ1|F0TMb z#KYp&D*IqD_r`jyn}FrflLM^FMdm6S0tz&ut~^@h9?#-9wd<(M5=gI^ivmoChFNVl zzNJfUC<{?Fk+kIS*6-mJre~r<FE$e->i*YX|9K=>VZhw-YYNnf;ROuR&fWDkglzRW zNSj$aOF)W#R2(k&-_3eGACi;;HY(6R3{{?Fk$v&pmmWX`gt3RwlmLA#y8s4~(*630 z&i<;}a|JN@IH{S?#l|I4jabbYJ^ayj=I&nfzM=QXnQe|(wC3xl{R@GqC#@PC!=cD) zqEz<;iBh56(}%R9m;Z@Z_}W3(sLxHXuU40Lzj0pC>TTNmw#EI5(tDo&f|jtZcD&Qx z!X%|6=lss+7Sw%}@8;Sdxz%rV;z5~$pz-8x6<P@v-*P%;fAo*0yyV7YSMeGD+&Y#( zbgt6cD6w&aE31EfQ}YV;nA7*mgOa;)EaBDYZ?`k|7QXyiV?LU-I6Y}dyQtzPo?2sX zCmR(qqsi$Bvy3lkL1GdqolE6+KK<Q!FpfMaN9*aQxh2}XG9+Bf$a5@oZUb&q_rWj5 z`Qr+A_pKQfD-g#ya*1;o{PaM@kma#^4r`hTT;gbOu796lFwRO-!5}Sl>4|LDRHDi? zX52X+rF+vCPbE}jTvOVV><`L+CAdG4&%Wx~@-4Dtdu}?{-}P$IM}N=#A4UzT=-YA6 z;aX9FBMO%S2I2hzg?$|(<WFkiu;)bvt`Bb}P&Z6lEJ(1W?Tq(-UfUH`Ws8z9SD~ej z48%Fr#2N8pmcrXm7y_Zickc_Z1(Maa+z#oX9lXmrWwg5$d&}f#$Rj1|gtMI=-rcBv zB8^iim5S7uwWt7+(W4)qDM$x3T6GvET}*HmN1)ciH-@U$?N6il0lI8kgsrbws;BD* z{}2SO*cSQHE>K&cX?J5QkFfkG-Zo+S^Ux~xZJle+;Zkzk`K)mrUQ_6FEC?_EJwNM( z-!1{hwP9l5t_3U}{yy%)2pU<aBW`uXGRfxyR}h~YIQ!@T_3=?0r6&DOKM&qBKkdkk zYjHU*P^|pR_B-h|3RNE0ap?OApSZm{cn;_G&&_CzCfGN{v&f74`oFFPU!gF_s+yc{ z<wt_{$g7L9^`)ydr&+q^Gxbw%yrm^zLymitYn~;F^WJOhwzFMRy6K89HKWvCp!6PZ zkGi(}$o#VJ!`pA$C#uwxcZF`rnG~wT>gz5OhU|QWZsKM_6rUOL>r9f4cbhoaBG?WF zgNpizBiuMbfo_?3EUiT++5(<)>gqAphQ|vD6IG)e8n|qIhWQ<L-j7!<7@tXIND&l> zJe!#H(z(6<Vz-VGTU7)VrlO>SmHYiC?swgzI8;|Uu>=)%-8n~sE>@bVs#am|lFFXp zHKJRwHjBbyzdL`%VxFJy+^^X)+Y)0<{_V}&MGGS~!+{!Yxw2(k_xh|QQ{veBeTdv& zK0Q5%`!|$dHrz$F+x~jDw5hRGvqw|)Zb6ZOCs9~cvLqt!6@6*>b^t}5O{*S_=h3tM znhIFMCq3`LuZ@9d7hX)E-_<kXSM`2nX4mIwk)-}R;~$7qtuzNMxtYpK@C4CXm*j8F z8LeY--ASg0g6CPhe%j*WrR_Q1*u~#6n%q8~2rd`@v=#x+n|9vQv{G`&O~}ZvFd5os zxnnW;V#qw@hLC992`4pR+aG>W*{}_0+gZbFn6j<=H1l{!DdgQ{D>>sC1d6octb+pz zg%+H+9Fj!bB$Y8beGj8`Ho2GGLP-r8HOPBm^VTPQWJEm;bv|wAVNZwoBUD8!SPr<o zJUr~#@zr*_g<<f%<X9e)LC*C(>+wb*+VW>OX8r6T-~6B_30{4xi9N57-A_E~KUSJc zqLnN>9N2#BpVWfX+d5~@wS?`>v9QITj}6-KW_*x{5(I)>g)0SSI$(-Y0@IP?D_@ph zHUA^gdM^bEu4UC#ub-`Ze1@8xCVOCZ5w-Z_(uXU5IDQB|P()Z%O5ZZP_TuC6y@Cr7 z#uv+M<taUt)7&Q*V?*Efy3HB5087Cp(COQ*f4wnrhxC>xDW`2dw*7le`}Kpj@~;_Z zY{Xe!2Be?t$WWg3_ZO4j-h?t|ce}>+3R$1CPte`|x@CJ{<IOb^RC>(&u52km1LEJ& zH#aE?$Cl)kw0v_rIc}_N9nXXIJ8XxSS^PrJ0*$%cNTH?oP9??LyM(H%&-+B&efOWf zT9)OTe;dhNeEiW-&CgC=cMQ;-^~C7QGYyH>&e=n|aRe9QU>$AK$VGGOW9TOce^@9k zn<6O*rVMM5F7n4-G~ZPaz#GQS-_M-ZLJ!J5O_5aD-2#LT<==lk{(|@arMM4Q?wa)N zv48R4o!2|x-6$LU5Asm{a^xpJ-ydhLEgyneUH=|Wy!Za#;Y<_}P?P>Nke?sdmDRKy zGbiwK{ho(@=&T}9!-?=PuxMh~(np0T5>@?N_5E41IWq;e!VgIull9L>)ymI5_};H0 z2U3K=dgkNRa#>TET{VWZ9?<NpI{o8%Z&?+yL+N|kA3J7Z{_Sb(Ni)337{8{)W2z(a zM0{*<x8Sw^<(p&B&gV-VNSu+<%Us{sd{3#Mb59XWNwjR#T=xs?4U)MqNT;rK6gH{Z zOKcN-pjrMnDK5<w9J__uWR&0Uj67i$dbIsPC%QZ`WId$Z*Ya=*cjU*ovVIwB#9DOB zn<D1+{Bj0NHO>|(!!zYMowvI*@w6zZJ-1%GHB4P$&6)*xmq@?mKv-pr#*u3u82I(w z{h^qr18+i4EQCF(_DX<|ndt3{hB4MlCh*e}?-c?w-plvf+7AESDau*u_`<k1-S_7< zd&l;=kWH5~c@o5r2$EF%Q^|l*yzk4!U6m*IBWLE6TeMB5)?BsX{h)rE8{4rbLD0*e zaK|HmMNjjHV{F3WrX)To^4VIufT?O5fgJ&`y5bXs^dDN<H1O0@?Wz`vBN9U)C?%Xf zDdiqBYJ{{+hsi$pkmdCJmFXJ&&H9{`%m>qRts3%A*McDQ+){DOqk+v*!f=6i$r7mb zkrwRQP*kVgCB!QO$QP#7`yli({JU}xjc0=lc0cg#=+<is*@&G7pSpRoB2b%n_eEzb zzfUaF-`Lek+n+}VM)zEN#vFZhU?Xp@Xlgo1l=qY3M0vNwk})r)2lFdR6jmM+a39+C zj4B}4I>#;ybiHF|{0p50vz)nel@*y`vL91$*NH!YtZGQJuXr}+Mm_FD<<M_T$5-?K zH(FXJYO!4N-5%?JxBCW)iG~qFT>^CQ#iE?%>HQ~gD^ZcK&vh}<<D2HwN{6o%%YOBs zt=LTrJU3@{UNLt4xRUvwJHzC7cbyE`-%`mmeE?({vdG3Szqi%=Gj$h-mZe~LRZqhH z(8U!EZ=}J|G~Srgg)y|TO7z&QqZRJ((ArfmH(>Q-A;w}oEVTu=BK%^-efrMq^%sun zV`G=$Jw9L|SD)LjN8<s~!i6r^SdVX{JuJQKe!)xG3yK$%`oaE208!A3zbiBvEsEA$ z59Ku~8@?*VjSR2|xMHs@^=7K2k(16|!d7$%tXgFqDCchGeD<Bqf_&<nLYu~XVVu3y zAiK%n6^(~26klHNu`4pp&45nOnt#{V3s+S|%jNW9)3Jf?2Wr`plV_sCwaQ&rw6CQh zP)8%+;0yQp46OT{dHwEL{>9S?wKe0+Ai`+WHSCj!lh4~Hz7u@{-$V-QuDj#=So!qj zPuRhM3{2(enDs}ge`WJCOFBmUzod(nt{hv$rLLs7qR=tPaOGt|cM9N&X(9U9k&&gc zt_pk>exOR_F79ALgonRx*xpG*<Z9Hn<A47)=aF=|8n<=u{fZ@G$i_Q(ibWKpdYIn0 zF!xWmkC}nX^VH~=tXm^*ZV%2)^ZZsHIlkV%|LtM^Wx97`CsCBs|LfNUM^>ipgQscN zmG1|H>a=JVn!}?_n)aD3Z;zb5Wi@!jsNqcnQGkwFD*K?a%g02&-FBD*?<@X8aO0Hr zotUR)^8XVve8v>w7}4vqnon?<rFY=NLq^X^?^xZletvx;zbX&lE#m8EC(?u5ei^+> z^u1cMTTqIc;@NVRztxcRZLhi&zW!_6DQmUm0OPb!d@s-T&)yfOy<eUiz5Rzd;=S@L zO0F3GP*Au>ZBTaV_?@p8qJLa4c}EuDfNXinb@Dj3LJErrmk!)Ba%AY_1y~<$C#DQ6 z;Ne}wwYrub58Mr{+2439BTAvKIQ#h{-H{Bp)Id2xVCbma*OiK{T=^fnHMO$+E}iyu zK6TI{!NpmiG~7Sxy7P+LZk|Ve+s2yI;02Cc{^s)IZxyW?b})+~kehIKz+>W4dw3hk zTus95CL|kVYv_D1<$uQh^o)Do3_G7*O?&;+#-e5T@jJ$&)$gyx+tEs5%yHT6jBg|R zH%*mtDJs%DfAzF~p^J)nn-Dm{KY{$7cOP$9F7!j6YOXH?jU3Np#cyi9zvks*zp1&a zHi&+$j$oWKoFVt*y78khLryC~^?OGI4{P1y%<{NvW`De0a#$Ndrq^j+&%1y8)WMeN z@8}lB{$ukjgG=>iS5v>?zF~K_?jc`$9DEQmC!_J$Kh_Z~k?oW9sOs$c^W_$4`^~k5 z@vKehHL3j>{0VN@+VkYE+vm#5WJ;5rPFhxOxIJC7J|MogBWBBG@$TOREncs>hb+=1 zg~DHbcf+x#&le9`v>m*qsx-8vIf;=(YN-bnDw~bDgttY%{Cy(qk}vNhJt{#rAohQL zGzQ7wI(M<m=_95_$;+~T8NDZ3CvrO@T3#<`L>Y6EHqW90Ghc(>!lRF7Bs(X^_cbT? zHFhYN%Y`>W-kfMnc)_nH-}DtJx2wIFD+p{Dh9Ft^<?!Dd(ox=xS}06@A0&G=<JOd~ z#G6C;p1OxLSuw-F+)+HW`~6nxq5d7a4a@OqoK${K(vGyJ%Q1<Y?>oO1bM+CwWG-^U z_;+2lB!d2mHB+DA2LBoWaEBe7?GNq}PQ3NQ7P)r!nuD@Z)KXiOk?DI`^z2oUXrQL_ z`l-eL@l**8eZ>Kq*>eu+g%LNmc-Z3(%^@1Hes%Snvj><s9bZSNj<){gALCtfvtMs; zLWc3H_eIALn}3|{?@j)wH9?v;Ug=?J=By?)h(11NYn?<bdFA$ed5zKCb3^S*C0sE= zuefAEFKKE+szdd&$Fr%j{uIgGFWx#Mm%VxOZ58={d4>!7_zM+TCRY@0Qcp_z_;zQZ z7dys!7ECgt4G*1n`)9Mi#gYX5`nCH1CE=AEIoSBzQnRXqXo_WG=SLf-bd6Igx*x1q zK#a(h#>b~|okS9>r0*g3TY-usmt=l53)N{9nkR*4r*Fj=1W4!3iX1CD;Ztktj-Jwx zmx5p*W%FZ>B;e$dwMPJ{tYk4yqTkRFtwey<9h&4!G|a~;&5<H9l1J6$!`TzgGm>xf zuJee^=T%;bW#^4Yxj@#!u#Z)_w%H|O5-LKYV33B24*PWmH;XA<6Xm-5!fK|f3Q>wR z0;Z!?UtnL_>0g`$(6Hp~0Q`M}+>SzL<E-thl1u{c%#g%|%W5zTA^>bDp9{b#wA33- zGzsgG?+YTEWOf&#__bZ5QFCND)QZZw69~aYM@8C8If&w8fARbrCP82DnG8eI*5^*Q zp}T!#YDbc22na-+LOp$`O-YTzO(q=$%D~pVSn_%sj!1(3gtIgrM7b2<&<7uXb^te? zCu8U7dCL8SSn-9Pr7~Dz1$s*j8}6v|1{rA!=+}kN5lgK0W{EO0DeMLeXmL(*5wijy zm^Vtx;m|~ur?DwpBOcZf=+VXRDWwDQfbOf54jq;-<vE(J_e5am%d|;#5VaO2Un3lp zh61z=#4L;=5AIMNh2^AsdirqYRwJX;){*TDg%;ghYk)~K%&A79&<>rIyeE+Ia)BVQ zJF|)es3fRHp!AG+o7OXs<Wb??pC{fb5_MdaG@!qr)IqS$;>ewFQJ1H~I_s*zwox}2 z6F~+uXqIm4cKRT=+WDJFW{tNHN?Y@Wml%5${v#N7%GZXgDo7cGphLc~^r_mUh9|gv zB$U!HxL1##U8`yBkOHgsC8uYS)|>T1l_ZjJ`rB2mayi1Z7eo@PUvgEE;K7xE1?$XU z@EvLI(B>1*vOh4WI)IBPIWaI2rFb<FrEti!(c>hmAD~kw?1p6Zfv)RI@h$_;9IzDe zEC0x7G7=Cv=bUb{zeA&**c+kXkcH9+9TAP-%nbM*lTnSB<rV51&9UfSTUTq=GKc8k z^>XD#qPFrNLT90VGQV>rv=Y;4BYk_|_YS9Hz2mdBG+u9y(bo9mlPFORXpyq^j6!mD zLoz)7(2~uU3q(}gXe!sp{$jZO8wxr`!y_Zhzr~{ThXL5Ja~1P7Q^*P+jBd?Q^G-pE zq_(*s^5m-HuCQr`yGEsOc6&;eeHiy=aSy)^($rQ(VAX#buJ?MD-8w4{o9gvhKbU%6 zW#i34DtO_9vuVfM$C=2IydCi+XD`;SKn3cJ<`{$Jl93`V;jM7COn_r@a>xO78vh%7 z2Lk<+08l@>o=k)@clSpLUYh;<So^(|?TZ@qUeC48xQ$jjJJdF)gWuBFZ=;TFN};i~ z!DG0ulGwSk#lre8#^7<KYzCr`lvV!S6N#o&oVd64?2Q;C%mpJj$@mM1?@*<~d~C}g zZM`S9gKl%jFhnqr50y+(^A;C@Dk-H5Ax=qtL-mE}gn5qAS}YL!6BAl+qbw4{3+%|| z+9Q=i0FTdbqDn7(bQG|1q5R~(WA9Ll`=bq<P9x5eXk9G)YUGvF+heBVd)e++Wr%H* zjHMPlD`yefW&6Ky@nzii&Wfs+iqgTgae8rf0Rlii?sdG?io#{!M7a~EGk!FwmPaS< z%aS4ta-(9xUYgs!wNS7(+>#6z^*TQY_pek1%;PbOSpbxZ&#iq)o}dE$$a?K12JEi8 zwv`|!C~D=0A)qX;y}Gv1|1*ll#eT`axMmU>+eVpmOtKj&Ep@)sNG?kr+D9N<ymyG! z2hH6#quqi+xZ=B0x1$`lr(<mx)aXisEe+kll;9D-2!(gq`$`8H`->q@0gJ&81-LPV z)+oxU|E%ip1EJL0e1?JjhPV&eXb-rG6W{?6SUW#^Q~w~Ot;wPL&ZinXq->C6^~a|< z(Op0t`JExhk_U3I%;W-AFGoYg7n0$2I$o7mhoT2(-}uadhu_!a-EeL*?<FLW=_#BT zVj1cOa(kYpy`ba}N1e|9kEt*8B^wt+_L!Tu&Jr$n(n--JVxH#u0fUP0SXSIW%Po4N z9FPm-D0N%0U+~>CztS#}3X9d`DAoL*N66SQ?D)q8cy2Kmr`%G_=#;e!?3?}POp|X5 zz=)9&pXkSqe8<!QA;;QUrdOxG_7v;uwhNY^ymc;;!gQ(%!ZS?pR@v{=mA$Fa_^B;T z?Y$_t!hfR=ghUEnktzmEIEB(EurJBYWkx1RI-I5u(87v7Knc}l(m29UL!aXAM3dp6 zrd`ODNP2XGv{QB?q=16=6qk%{pXheJoSw_ki0@AUlk!5yyx&b$t#c(D0WUY8yC_k0 zs3Y2~B%SciiPcD_M&onRv==k5+NjVXLxb#^HB&xwXFhQCA7&i9Ohq3-$uX#UKs1i^ zQ%n?2D4v9(lyWo7gB}OBm`6;1jWO;osds8@^wi;@0J01SLMKDxM;O|miM=}CzJG;F zngd4OHK)BhlSjQwaaC)Z1`aKQvT=w$oQMqT93e}oPy+L&`Rqb{1?A%(nczKNFEis; z21#uuzC0O+4aDjzr>;bkG0l)k@zBLltp7G{<fZORT>U0;yYBafaJUv#SZo9PPl9ii zp!s4q!_??T(;N`iIzK~)%H(cW**IPs&jdMoRbzH?w%)iB!U_mbQmj6{piOW`*iDd; zH^f<{pDj*wmwl|7P+nLISuWJ#-;xwtp47lqU7cnS;ix=uXzM%b*y?DgLb19AcN$S| z(NlP0hRbJqg_{&=eR0(&X3C=Nea&{b^5dN2Gr%-#&dyUVl<~%MoFaDL`}*H8iqDyB z>r@tkH1~oP4g!fJcgduX3_`JgoNAMXT2FEv7*Z=mAmJLioQ^kQMmdfiFI8wkn(|G? zOx1U41r<<K<EO}ja){O_*nd5kCDdM`7(42d6SeL9`RJ#+mtfeis+STwQp(<WQVhcf zb$O_5=Ur5zH)6(@sylR9KsRewlfFg<n@uJ<crC^{@Rv-SKHg=ZmMS?CylQ{Nj6Sou zz*YLJJX|e67*UGtCeB=zD>TIovaXJAwuhtFe0~@Lkh;v~Z<btA6g#jx>vYCt*wf^E zpt?!@TVkpzbvtIg_sbwcd3?Ntlzc_(uHmf?0_0PE_3xf5#;4eX8Oz0DJy+BZJ9r<d z%s34DU;?fjA`ep)pEY)ypjn{A8N{~5Z}(F2b2FL2UA^&n0USA!MNfC^D=3XuwWjo< zr&`$zKRp8ecvB+|<-6mX<sv35K|qkG<-}M^rfkw$K5f507<BFWZ<ZQ$AcH4Az@E@J zK;z99^oRMkoMV~OdP+9c)Pf~ck8}AigblQ$K(a>yYV<#Ena;g6>lspTkMYQt`xhWi z^sg*$8Ve|{M_0t-YUF>tu6D<-F8w53EfA`rg(G!_&wxb<JaE%w$)AL+(O;~0F^M8e z-g}%(6*FWSAeU`-V8p86xQ&J$`J5}G_l&?PQL?}XB*kD!E|dZ-iY7^=wWj_)U;qu} zaP9RLJIG_SF7J>+bb?na!9_Y80e(AK`eVoW$^-EusukD_^REPPj#6}DULhUg_s%ir zST&moM=T^F+PE0P^72Za<Q=N(As5DG9eyDFj&;??+>38$TM}rw0|=~ERPaxeOh4_K zp@mR)JEKrRUY_LcD%F(!sV#LbkR^~3U#Vf=Jz-P}yAFD){PVN}zfv1Xk%tzz3M~j4 z4^^Z#P;&)Z`AGmIP?-5NM=pGEJ<?G-J^m&U6KQ`%S@Uy?IT0kCB>Z0ExK{|x(?OEC zhMCmpmM#nV67^f~bLoCS#FjL@*4Dc1o<2BMPnCnludhoxdJwTx7$0Nkh<S`8+f`kk zBFn_N{>i)+kk8s_MkT9?n+GSLxQnId!?e!DQKd-QQBLP_^wJmz;S?F-;#fNf`7060 zr-M0EQi+MWhV5_=3Ap)9x*4l$=CIb_>gB@>h522Hit&5oLj?mFEZZ=aL4~MU3hY!2 z1jWi>50PixO+P|MT&&aP<KzguiB+fbpPgWDJ{GG?7pLr_2d1bC(Mx&NE!s}h#i^f$ zXBoe@=+x(9fg{-(>5(q$soJ~lbX)NN>i`RB?ekmxOjkp3wLBDfsn(K2GC+F@UXk#& zAZ^fftP)Y7)bJ&RK}IQi`|$gIKV+DcfM7C}Bn|B0QbD!OrNZhC;}>!awZSLr*NnH+ zAJ<5m`j4~l9i-Zx(>U3zKDa^)?I(VFUzRk__jryoK$69S$e8$-a#-+&BfX|=HMx#D zJ6aTrNcGvJupbY5cQbQMf#s|Oa??n@7hpVvU1-)vNI1`6?|$mZEA%`)VNY#nTru6w zwLVjJAfVeq8PdJA#Pfq_(9WjAwz<a@uv>v|8J{xO>>L}^1i6K}zE@y#)pPTpEH|-s z968<^T4@-8@{h?agb;CG$K=jtNq*ukw*F#qVAFP98H!ZInYvpBQ90^_Rx}z^qa@9f zrf;wrwzLjJ@oG1w`PJ;#wWmzlQoiBWpr$bQ-0|*36)I_t-?J}k=T?8<gQ}G}gf&^W zC+90}VzJbG4j8Trg6Q!tb$vA}y*<Z${&Tw~p+L=RBiFx}S5Cc9v$-9|uA65dRJX+~ zR=X^qk~Ymn)jpuel+(6SIMy;;EU)L9v5eYYR_8~?uQ<bMM>f^t%YRZp(D`_@Nd`pB zdZouOwn>R-QGe|67X51qaCM^`)ulskaow)}vg6rPtJk89GaiBu<L*>!c5xqi;dFKB znq(LVx0k<px1E)|dCQmEsC*+ILlg`=hdc|OUmx`Z1GuG9g2E&a{`Ec%-T4k3Zxfw2 zZAO5`YNkx{W_8FvV{i_mqrnpb#7=H!aW_XytX*55GKr|FQ$@L@-mzS(0s398|2?rK z9HRT-n!;%%vw2Cv_w4v4HDx(D;x~?7Ibdrn7^f>FNB`9R@Mdo;U$iaHz`iE7wwQF< zIKEcf5GXIi_RTLAw60ZqaY4e<j%_|#i4i5&)Fc0`!}4to0>u-2ls01^AlXQ8|Ca9Z zV&-z~20Km0$U9<dvLpAtMGJ7TRyS3=%*hyJ@t54YxWM7Yma*ZK+&&sm)V+YXl0-yW zR}N9M=I{dlHgJH}hGT{l!(XKQaJ~+BJ~7rPt!|7hRcg{8C)dLdvMKSzbxa)nm_vo} z)|yZJ{F-oV!Dr?btP{>I4(R<Up=dD<E%FwzV`sR?7ih{vXC6G(WfyuQ=mIQAN@2_b zJI1p{i5WGsuY5BdTA+wlo#>8s5`ciEXh$cBs0kh2AR(!7+l8zVsQAFBsy%9PyIN%S z*XPjE0ozc)tKo*iL*6K*0@=O2boqHxkE1LQXd(~8cE-h4OIsl@HPb(QA)gZAHhhUU zVaru6TS$>KWI9q*-)kUFZqt_X#0AW>R3L;CB$<!zqQ!R#*SqUO9}*yarykT|0pW-3 z4$^CEA*6;K;u@0k7UolHSwnRqe1mc*TF8ETU-GS_EetcO3!-_Tuwe*_CUK{mj{}f) z;6u#LLyf2oIb%;qyf>D7Suy;-J}yvNhC+0~IsiL$Ua7ctliW=uJS)8bEpZ8Nim}|r z#nzVNn<4#U3cQg4{ogGgW5Sf+)O={W?y18r={rxVdVP|dUJzPQgwYT&2DZvqLBM`M z(j7?6L<=XD)-R=VK$c`F7xhB|Z-0c=>7p>>3ya(nPc#9Pjwfdzr31`y_=s5UimkSs z97$aV2~q9P%c3O6bRoEpFf|yHj8J~M7B3gRB!69iXt0~jOHFwvz}`9qVdN?N3Y_S4 zuje{Cnx4)%!0!pO<87+H&mK1s4}sSMuYH{bIs{kTQ)nG;5)9!9tsSRy{Q}{dIXcek zJ*<&?t=vvGN<6qdcB1BQLz@M#{uB~DyYvFhDVD=P_(ygJ-(^>v<h?`(VCukJoj;q0 z*j4+g6b^;9o}dJ_N5=9BRZq2O?`Ree?zyQT_`-l{gx{BC7%v2U=%>bmj@Q9yG-h2O zt7I#ueV_z<WXJ9MjVQh(;x8MMw{`OLm~5@?TFOSh3Qc6qcfNxd+D21|z-*x862;DJ z5aZAWy%)uU<A17~F@Ah)q7={bx^s$sf9Td0;dAHJVAcFitlIV=o=uRt4&Q8<N7;&2 zcZP!;-^Zq^^}(Wb`(nkkuy&qbRgp;^INJ5f!yyR;Xd7eL!_`p4hC!ZCjI6zm6g9#v z(g(VfqHim&v>6#q`V$<bo}+VjB7gx$05=NVPXFlxGw?x2In2+v(fI!jitVqcwrlqz za!4Dr#iFGj7DgbI+)&|)r)2n~34HB)9E0(wt%WF<-M90cghm3{wybX34LLS7ZI=9y zypbnVZNRAg;3t|r%D}B!tW8;J<2f6<d$7re?_j!E52B3$bUtmO63vm74I|N}>{>o$ zbAzIQ^xvdVxg|2VSpu@xE~7hfm*l(Yzib<#Ff>Omusq^~l`vF~T0j{@fGlqLFKc@c zof~NFsa}_cB3T6NG(ousMaf1+t0%s9ZG)#W*CXx4S@#^ncHueKrjky+v{UunMzeCQ z(>;}U-XcsbmNbt4B)XqdT7*7v)Odz$_`{D{T_aH_45H|&Ira4Q&aRN671;l|71X4; zbMrZQj-kS%V5T+tj>+^f3|}m033o@(fv7k_77`FZJ(_=avQ~`q%6M{W_1k@@Q6|SO z#&kHj-#x~3AP#jziagF#Zv_So4l=Z{u=68lXEoROv-0Avu2CBKujkAl$?$Qf-n|R3 zo^hVXzmR<)I}g*VO%$Es_6KuuAbk(|vXPJYwP$c%SF~6nNbS(i=_f8>)Vr^1zKAne zXBQrB(bw4TVluP{sP+uSc;+JD%G-<0p!dO9*@(cxBZDk+L8G8zt=SMx<g=SdVDbe0 z-L9l<@xH2?qsO|}=(fRjINgG1SmV7s@kj!<8btx8kc*>yXlsj3%t5DGUp{9M4u|*U z^w!#Lee7D?ENS%j-WstTw1;Oh#Hs@Fgz$m19i4Zjlk?f&!I}6=uv!Q7zO{YC$tFHL zS4fsJH(sFhVSN27-lxSGE=(tdQg<k0uP8nhStZxj|FQu|Mb<JGkO(+U0FO<Q(!5hW z)D^a+W@x!l+{<dh781Oujh0jKImAiiOE~5(F+j&yXcVn3>71M;>?tzQ2#^#5@@dSi zXpy<1w4o;*%pZShY9ZRKCLz%mmNwOPxQV1|s-at($0csAHlz1po*95TT}*d=fv3<8 ztZCLoZkzFWL(_I{aRqwjc9_JmGiRRWXj=>`U`k+ChEe)NtnJr)L)&ozXmL#vG;V27 z@q-&z7=#XDC-|_*lGfuw6YbyXK$T*z+aWC=f=0?;0nQY%?TTL_HXa)&WdUEaq4^jK zNisOdKGYQ#WT2!SE=qc!$hgunvRro5OR7~>K@<;S!mhTd)b3x41h-3+6WQL_X0A<8 zNRaHX4}jn0VG~F)$c7YM^6vQ>A#-U_p0fh4fcHi@r<QouW*&<4VVpX2R=t6lIv+<^ zmxka0li`~U(vg;7=v_e&pFdm3@1rWfRpI>ZtOHj;jMHM?jy~95ZcI<41J5MGkP`r( zSy^{JbTJ73M&HCHhEZBWn#+kUB{9;(_k@LZ7%-0qsB!J}DKksIcwVcHTDoZ+u57BG zLvjJ7YxlIh*k+!9Zxn`T=#FJZ3l>78v$%zjFqRRn#E|yw7!2kOO~->Tf_Uq$N1g#K zV(U>Myu$McItZAL;CYe=WwV;d2Vl0u7CL$|LIXPKy|Dd*Hv|eMYP>1u<45MLM>%OZ z27;>Y7uF!%&>#wMgM2=s1IE5St-KCyrst_IZ2Rm|{JoI7GZavQs-bo1dG7^WeN75O zuhrII`{JYC7Y%og_;9&vwMcgp>4nqDk7Cq_Z}AuN!61KMhr^G7RMoN1f(nT-3cHoE zSkc_c6vJOX@-OsSt3Hs6cKvz%>7Q(=!C#cOdV~K$Qc7Pdc*m2U#u^pec=-MJs%+At z&SKq*-5+l!ms;f@kAAr4JXXiEbGLIRmDQG{?t9*T>%9`;CxWu(7;%sJ9KH9>!<erp z<|`&rkfhs+ks;&sjCG6*?pvAhB`NN^Ac9KDzmOS%Y*Bcsx~&ay)MOV)K6IZ7<)dnV zOO|IUyBPP%&^f%#HmpQJ7SE}`rj)0pd$XS^kWq(dagpnkqEqIkt^s7+FYQJYZlnIC zR#Vl^_|A4AbNk|)eOzc2J!i!3EkiYV+h46EQVGvPt$(?j_4n^%ie_u%{hgjM#Q}fr z$K1xJ6+~NCwl0p!A_M*`NIEI2)!fk(-&2t%#@Ksa^4qXw7xoxK2*FtK#n#_@1Cvj_ zZ*zlj4e9l7&L;nS@>@gZ(>UhcPHIfXWg#LMHqYGi*+H!R@Tdfg!Lv8fxDY}A@GqpN zqEcmN`!4s%DMjp2c_Zy@rMgH^GEik+*$%29Rx5!y<8TSWjd<tc-27wxYj9M+%>^(W zz1e(t{AWv~T;d3ZQTB7+P=-sTxwafNN-+1R`B|gAE?R=Lzz;0)6;qc<pxQ3N)A~xs zqi7=Ma<jw^yP3BPtL@1r=?snHT&9g)r3f4|W6p(7Q?C6#iq6E5>Hm-8o5>_+sL5uE z5;`2k95a+7$t@jnP3dsWG3RXV(rnIBG0IJ@E{Zb59EDKsb2M@@#~8og=ld7%+2`|l ze_qG)`FM`Z$I@lj*8{r#GjWWx7>3svTK*t*6<(A`@p?S-K6!1ESEdjB_2<XpZ0R?M zn-=~wwFiIb>Wl9G{uR;;UxHHGi1I%bm4Jb1cn%xB%J^t^hOa@kYmQ9N?l%eyIQDyD z4Ei&xh6SmVY5Ba3bz7)AWzwrxBlF=U#Q2xE>rkOoTdK7B%U^Lw<q-43`f`zNbJTnX zeYwlSF%1IXt<5q?2eefr)q0qs1bR)B7K9!W(`vhpQjppEs{HcB)f5d<SXQnq)v1Q@ zO}V@-b;g!lEsF#uhuYMKtZywP<ws>JLFYnU{49Gu6!2N@^vHWAuL~0h*Yh1gd{cli zIS97{#}_6o2rycpV=|+_OrfMu)m%bdNzvzXWOC{vFoL_IsV*0vNv*T<=J>(FScL{d zg~FG-JiJK-!Dmbkr7p9JK9eD>N_sB*a1ZuePkwtGCuy?J3largVIfo#^sgQBB#!w` z@Qe*pWnJJzy0NlP(<d88^$|64fYd}%Ve$f@mZ)^(s;t1jgrCo3u%RN$a9`EomGY<8 z@Co+5Af}WRG{eMPm;rQssV208QjINGzuTE);cXzvVD^rj;8Mn21_~ja1B4`?4_Imx zZaz6~Kl4KR;pBgf%2!|2p45mx_mVBvTP6pX>p)F<?&8UJRM&}Aa%`tC)M8Y~L%R0% z`b>-Y<!=anP<DY1!E&wC_}9{%o{I{hshL~I3KUPaPr<A3PS@{39|{&cDr}%~!*lwu z{j(qA`pwDw@2k-wK24RSL_w_cLI=61F}X`Y=P{h1_)R6@YL@Qfs;t5XkWBFKP{Fo` zc5~sV`nleu91&|8?RT@oRMl@0(w^wvf4Np4Hv&*7FlEd{s-n8w;Ox2I&gs5k_<3iM z{T6{=|6aDrFFU_NfB9rG`Es{lv0KVQTCmv!84ujCZ|d+e`|ms9$dxyNNEv+f!sHuI zM@3pU_EXS;8wTG0f_v<HsHa$^9PeuH_UDRA+f$5vsisRNx{UB56AMkfU;hIU9BARE zi0sp(eLfe0Z>WR7zSN(<da>u;#RZ2|bPFK$uyTR<y~{6PKfEY}((e5eIjL5?B=6)T zRM)Nb-Q3;hM)2v#$T@ovlE|;~yxj2v3+{4?o8o)ML~X9>HbdNmx!WpL;~>a@LrzVN zS4i#_PFz+CKhoPRBlEj=_z8^KQ!k`<;ruJ+SA#UKbr00$&;mxOuAb>`w=Ht<n^iX} zD@P{!6RM(A?})dL;Ef7{k4KUE`g;e$OEp*&V_qx_Qf+>0r*IPJe-hjpT0)HITjoqo zzp>7QVZ+8buJ6bgqB0&ZdK3=(?*XUzPD%ZumtSuMX~bkEwa`dAx<zwkJ`<eYn7u9O zygik$FZFRB$<Dy2JUYLbpI$z-B2RPruC1RUYiVeINN`7zQK;-VaGrU&Uu@+DCr+&9 z0PN&r>qt5ffxSjt6nMQ+%crFb<1_cgmrO)RVTvl=mKjzi_V0Oy-H>UjLewyOzFF?Q zLG@qo%h})kk&dHIw9GJ&V~!CQ*)_z+tB=kHaCVm54uU1C)++)JwP@p76l*M1l!`}> zcj^z*xZ-m_Q!eOn_DFZ`48w__<ATk<{LO19^KQH$m}5bp0&(p{6q&dW7L`})bB#!k zjWN#tcP{%!KdAB@J$irQJmx%t3OK3rahnZ)74VlyaR3(~`+0Qc>E%0tpBCR396J>Z zxxYJt8}9j{C==-KVfqxrqw=Z-cKswZd>6}Ay@URse&x88gEBcZx)+%Z&G-9*YZd!t zSl*RM((@i@(*>kFh20W_JY{iN&+Lr2j)>1l>ZDUTLPV)VGcQ4L^6vR9fypP0%T6NG zs`ekk4k^#wyIJjNanzO3O9g7;&0?Pjw_o2xMNQ?y+xfJ?`#@YcVK=<P5NvZaxD~bB zuS-;#SAoQ)=MYCTwxwV?Ca|5~rM@<oQ_dkv1*xC+W@eSe1)9R&4$3bz>>ux^8DH}n z3K4>ZFP{wcz!*d>|4Hk3GB6;fD;+gKc{|X?q7cx^g}q*FUt;s%0rH`n$b7f$2sybB zlupe_3pHp23TdHSQgzrUs46YZVJL^FJ0U=yd)AV<s&&#^^mNx011`37z}4CCQ-hOk zrB;hSow2^z9Pl#c?@9LoGi7)ZlvjBFcVkER7WBtHXaGu5&m_h_?EZO7BjrS@n3JVa zh;45*fX|<0`#l%RXd~2ImJejo#>;Tlxh&;G`U?0TE|Z|z1L!V<e^e?<ne6;tTctyQ zt_bumjy=lN2l&x|`60T`T?l{I#xg_C>uc+dgTo^Lu;Ol|0WX>Gg;oPG>LMS;jX5Aw zvri-7@#@}e2Icf|sifQA^R&I?;YBEBLS;fqd)&1j;1=QFPK?r(UuDZ=xfIZl!(PSA z%QWg(c>LckbE_L2QQ=+hGF{I5__&(8m`;L$H1By1HsRfEUvM0LLnb%h*p?i0w~Y<$ z9U>hWx|s|&tFit4EeplovA-K@<4Mv`<pA6oH%$8NjLHvE3~4;^lXj+X--WwwmyUwt zZHM~^Ks?xK1M?;Fj0Ir3esk~aafJux`)FW>Az}8(r_3M-d_#isM&#&=Ofle5SYFiU zf0tcT-$?9Kb})aY{!J=d?0jbk3p2WN{g|SfGDaYeY#-w<Y}(egNU_|ug4((g4*c#< zKAbkxU`LCQ$=I<UH9PePdxH7`1>K2|{LXosf0ue%4J4oj_|vyG7w<TRragZkcvQ^I zNZzNlNtg>JgRj3J=VJ9joc-G4g{p-^$$Q#@VfK>xKffLYVb9Jdq)h3{d4QraakCF! z5#DH?G~nkSG11y8o4Rsgpk*?87TxUr^LWGB`bYaGvN*=Wp+Hx0QS~)IwfbnNk~t!O zGF~~Wu$O9<tL|-5{key^Cg1irWjJhgANfr6rnNCPASTNC>-%L+=<h`B;h%B0@$#Ty z(k04B<gnCYLT2N$B}u)xJ0ly2FWnBRR)$B;<`xb2ehZDXI{2+iLGHfOXw}>;BZ-#n zPG619lEaJ1Ae5&}JlVxR;ot?AzNs6xl_Cf=bJ5XVbIo@mU)R-MeSX|!+GV93#FPcr z0Bg<ew`K1?vryk6sF>(ugwqTC?-$1zqz?)I>h>r*;4j_~@a;<aQ8({<ywgc_6M`Fh zUrTCgYvL|HBD^(`bs;)slx)`C%rkL2ih#~=aNOcwS-CJYA3r?I%IXWHG$`bl@n3cF zbg?ew`{vv4XAd3DJ#+Ngd;`1G@6=xdfv7UBtjm!-od~;xlou(o^}#N{K;D%s+y|OG zq$Na_$y?E@xhS7}+z)<)irQbow3LPaFb$7h-h)28nIDN&q%U__(=bY)Le^1hnI(va zELI5<&y%O_Xr@~oAs)mWu)nwWcSSW8FbNe-CIp<J-7tar(wUS;DrXv#-%WUNEETG! zl=C8|22QqugbD8*f85qkxztU4p3JECez;NAmlI+`f!13Ayl&Hk`|MpW^}y$ye&sRA z<MJ*pSTY__DznyZx@bLgX^pi+_GT6+-|Dzk_44E=a>k6iY<xotYC`O%P2ck2Nvzmg z58tsnep(3Nok#ss_J7jCIIH$~phV@$ZZ5)M4S-8r8~MC0eZW^Nm_3Wx*;8D58>d*8 z^TW~#Q%mhi?f<5f_00Xw+hBPO)pb!l=Wc2RqU6w%Gd<tSf0ZJB@PW2=@KeRho_q%H zQL-v6mX<li1#M@2gYULXKqI2ZS4tdo#&k6<siNc}o9}s((U+Sq_Q1Y0{5H`8>Xbor z$?vRM<-Cc*3}|XsPeH;T%&X-it)m~9Qk$h>Cm83}w=OC2u1Alve}Zm&l)2kjyD>@F z_eODbHp@!W68@cDa`DAFmiMS8g+(Ar(le89F9*3CLAU3u_t#rwT=*$znQ5_NkBRoi z8K@~gzVn85bfjG4)L+=dMv=Yq!&1P=Ek^bSWUZG7vVp->A5yNc;Oz2{@Q>+!R}f$y z=k};8+<{NA)FnzpM$z@TKX;l0UWe{scG!b%Yx`b<^foB+xukTiQe=nsESe~if4qSB zzrMzgfVKaS7w6y&VG(oxhQ(}v8~)}%gC8FJ@$o;<LNIE++5XeZ;}T}MswJlbcSo<Z zGxP6ATUYCs%*49_Lj7hFKOKC9Rm;hmO9yWnizek{x`?catd-5<8!tAA-nv$T%Y5!M z?F&VezNn^lx`i~kAhwy5@o5KF_ro4;)|Vf_tZSdS>1+ZReBv{E4L(cv9|vOv-ntxy zoU>Dvb*GIx{r)E-n$<HSNA*}nNNy5-JI*|2gtHN)KPG(6`Kb1LhDVFSY!dtB#><s| zaSugbs6Jp|m)7_i6aAnQ1WYl~{l7*jbld(lO(-;i!63Rsnn}K&k-E-187Z?!3Pd<V zW;8Z%S7Z3N_2*4^3TSaHx;KG&Q&YpfU6RpG)~2Bl!Hh}jL;663YR#m{HSS$sK!}&7 zz91L$LtB`O$HXaN&S!S)&NwCb`cpDD3rns}bEsVk=gC;a3TE#{&cX01m_W2bf&cKz z9$HC^d#LtasGx^zz+6wZVuHRVrd5?b5xN&@(*iSd_>w~`h_K%G*B66V9*-N%WG;~` z_0g6+br@&kwK3}~);6h?Hw;Xx^T^qfTyzNYyRp*#nFW;@1j09{!Rcam-DdM8c%bzg zWe>bB|A~*8$9ZQgc0Ds*&-CfkYMtu~EWfX*=j?HZgs0DO0?VJ@xcTy=k=`Rt*|YzF z+=F&N+72pe?iPGEKb5QYbKJg`5D)&fWa{jxhZ&YkgNob#+pMND=D$7qysmbq()x+@ z2iDSR1EV58F!bE`dzAZei<xoSM8MX?)_Is9`5<fz=Bx7cao59``#&BTC0hY3{8`NB zz46A{p9tEK7?Y?*gHyfS8w+S-9S8A3Ri!<A!RXsiK^n2KR!B5j>GQQljYd2K*^yu$ zA!ZUl_`P!D^t0X$=7T_Dg$>5q*{YS%88|`VQw5HJjWtX9=8ag=Moo(GjtXN<s^aY_ zibwLM*8!2AoqAcNEZpH*^yLdAy{u+UUwGhhf?fm{C=$ZLzba?E)3B+d9ZljhkSY>i zUUI6>zjls;Cr|K=Xm1qqj;WJ{0mYP`Qn91>hY34w%JC&A3hoj#_1YWApyQzst{M9G zc~HH7>tI2lwm3!yg_Z_B`S!4rx!jW=pP|~Y)NY58f2jtOS)vdAOdlM@1c$Au5F6id z#q;y7oU08`d9wChq_P3Er~Gu4uOJX@cwK&BLd4Mnp_IFP|DJ!M+{G?h)8BwY3^*10 zvJ%y$ZwjY;w?38{x&I3i*`ghaFE)kpibZx+Oz5RoWehMM+@5B`ZJgR)dc7Tr{Uz-t zrSlcEXmfhL8m$4$=q8=yR_j};ZqC&Y{K>0(KY7!N8Qo7C1X7TCv}?iZ)#Px4^G|f` z14|sKYD44GmKiI+254h(+u`|`S-++@FchT4D2b&&!<iI}(r|s!(9O5<UVf%$d^=Ut zml^r~*dNJ|6i1B+$E|(QJa)wuqgxE2D<c8#o3ZX&<%zp><@Dh%Y(|BvQ_#cu`&s4g zK4Y3N#wheNvv92}%bVGib@px75At<mndl`lyDMM*s-m;JT(qJXcN-Z%%-pq0382Ay z>zWT67ltR!n9%g?SwWD3;0pbZ)y|*tYkb>FUq}Xn0yZ|^?%p=NFn?N7pXWgP;y(+0 zEoPw~U?y<hww$=h#ZJ8<97>P7Db&mbpb2Nnu)B0@>{&W8*2v`k%iQ_wNGC~WzTm?? zl1`V!tyiHxVM?OS4|-Jiz|yPrkSLAN>sigcj*fTZ1<lA<2p3R5&WB$uGGG}M3>sGr zH@-Q|O!O^z5)0O!1(jcnD&S|dUXiI|1I`EED<k7Ma+4!6!Hqla$Nbe_kHQ#hEI=_S zWuLAOgA_5$UYuYFHx1yqC8T((uNruDM=iQhCoa>Wfp~;#FSs>k@<L81HlJg_p~4n> zBc1KJ*H(E$2|4dAG?SBb99Z>FDsEf-KKIPTQ5o*P6}LbcjrF+#wzQ0$O1dT&gK{!k zUqF`@QjUa3w1A8Spe2;Sx23R#6cl~PxLah)7hrqxyk6xie|ak2zoetey#)*1-Gf>P zJ-ipJ*-RDPt9RIMtCnr@_~1_HJ*72-)`<vYeF-@0|5w(^*yK4)3$;uJpl3?y-+S&j zqDN-J2O~ToDWMbDp^LiG1&4MAwl1a54DzFouC;_Yyl!iQ(6&5EgFUXM=o|`DX+2q| zg<=Zm2m%Y?(*DKCH5=5?rD<P26@p2=KTZ0*2*Kw<(mNwhC%u7@rkR#7;Vk9+mnNWh zpnOwvWG~We!pF8ip!F~JN|BJ}mGpG_I==ac&S4;z!1QLyMB-;5m=P$@JDT&0d3E{2 z!zX~^qyq@Q{?(njXmcCny|~%_S+Km07{Eg2-}LC7JIuL1t(lf##9E#-nfb7@W7qF{ z=99(iY7f77-Mt0ktgc7G8Hc-X9K9gZQf`ARNX}N-ai6Dd^jhBCf5v*RaC5f|VCw&z z50HQ?!1J;7kB!b$l@kt6-9>ifyTR;T?4iP7&h28>+^un;j4QipvnpSv8~j80=TpuV zAkgm<ewdE5&8PwWpZ>I<Akl2Sm{4&&Ai(JUHz$GQ|AF59!8~Q2og5rAIT+1=q_!Lg z6gRX3mP>&2Al83Oc|9&tt)=$GrUyboaUO6Bb4v}7{M@TC#77+`6bGdoDbr*b6sl|P zR;ZlFw*CI`bc@k`(T)8rsXaiuysunpQlgfk(VACi&;hR5*})BeJRdhqY#bK@oKj8| zRDap7*#m)}Z>5<}5yW@TR4>KpO%1gJkT1fb+={%zA9GBw<s06u=J4d*Gt*B4Y}X#2 z>qM*k!|n9<Yl1>LtM-XNDECbNHf4w?)M_E@-(}g8^}&mmjYji5h{+VarVEHQxAAYU zo{)`#<^b|YS`AQTx!u$Nu1_E`Zt}e@_6^kx<SmRFUvDVdw*Q+IRs3Gp#yt>FGHTNJ z6kq8}F=YCd(<VGJS^sTky^TX%fV~nR_h(70WpKV0=Ps@2IY0au>*+N|In9&H^i`%K zjuxOFp{b7HrNd+8S}uCHYABoyxKw`MAoDn|=k+BmWyQDrqX8G&Q{G}JV0q|P;DTR4 zIpy|bfaQF?0V|k>%$<l2t9@Qz(`D1I&`M76?Lu@IK*~!J)fZ6jDLB_DVu9ASzuzg0 z{$ktrj<6J+!_MJV&dS5jC)n?>{{aSUt5K-jIATAIZeW$W?2eU51Iz9+0}$Ya2crbV z+X_W<1`BoW)ER(C3g<Cs;MNpkXTZcWwwGjLs6A;K_z7T}A^=zu5ZboBri_{9t1bG7 zuMaVeq~l2ktO$Cyx>E0_Qev2pkN0Z?)oYV`O0|o%5MS&s|0sEo`8#gk9z1Wy>&_k2 z-JD7ar045KT#)&y3M}96vnYE-^5E?CW+?<(QKTM00(Lt}bwm-*9*_G#R*8*JO(!ZR zG8>>lnNN#&?tjR_Ox!@GpJ(UIF>ZkXR`l4b{!jiEtdE+7^=2T8@50-Rf&)VHbNX_x zcl-?|vcn<s`uq{`)b{7EC-Avd&g~SC0<iSvgX$9$f%GKCT5j^bMA#-KAEdcQYoz23 zY`&pnYvKUih8X~2m$rllvI|&$WpZekxaa<|ENCA<BJFvVj<Qk#9q`{Ox*$G|0tD^I zbVYAJeW68$nX6EgXzIR9n!3y6E)!T>fw<~ygmx5eyH~hr3t;)j_yHRFnxr^$VSs;{ z!9^?j9X>m12yi76Ku&`*@hg$NGHHLkI;vrgJm^@>PgCQUvU??77}Hy&Ulp3;$ZjNw zX&GFLu(k-@ju>#jk>@LBRF9oN7u4o>bg%aA*gm#0I7G)d?f{&lQ*LS|Hc;<zvs7Oz zO+j}-Chfp+m)qqk>Wka9ad?2gq}op5L(i)m6R187Kpthj)tgzTPY^6~fEwc}N%|q@ z5m{7=2?Iz9LzK&CQY)aj(jzDqx=5`bz0BYhNu&DgS4;GEN$V>&Rss+637RSN&>A=Q z3>1a<TB7!S(P*e<R>VTJA&-ZA_@=3}2^`lekv|Q+Z>3k?V4c$bHADdpymF|5BB{wp zSc4X~h{tMSz;m-`dOcH94)F@c09f?J3?ojB9J;tr(2f`er3^0W3)HJB(Ur1Wam^Qs zFe*??KpHdKl5Sf`iXPaS2gY0Wn!bnrVr4#~cHBsECsi4^-}Pr~d~aH=6rj3bg&OXS zCsItIkdLygtbE*H&D^5C&~+=j9Hc=PPm(%(#h?0$2K|$iIIe<1SN$Up6e&c!FM~HZ z`4_dK+X@iP2k*GsO1lVJVl+k|)Sg##0Zp;w>VAowSev&aWKEymKhgR&^wJr>h&y%E z*UU0Ah|&IA9!OxbL#ro~LL2BZf9Wq?ujT;)lR~jo8#$o3bJiqBP(;0@tEuS_KQ9}G zL~YKEy$s$P|1lxnJ6^eXnY=7drudHX!=^)zfg&axmIZNLo}oYt{lar+RgEH|m5QqU zU{);%9S`s%;g#2?#fN(l=qi2jRMNq_w$G5KTR@ypJU6(24*|vmVBrD49Yy1ot@j$L z61chZj7q>5mo|g)%IMUBp;$G{-lAD$m4nD1P3OcMmY79d-;Bd3jZugdM{3=T$Vgza zg^btxEm&W7dB}q9OYF)i$Ye!0$d!lgfh53px0GGuLhn)!F)Y`cjo+3f7NRDw{j&t6 z^Vu-{0TxAlLw6sR8$2Sx6Em^Kv84e;@4n~Zkcl{Y7lac45dPKz<pliq#vfkF6eEju znJ4&%e@8w~rb88wJ<$fae<8?oI`CtOxQ&M44TibRYGV9!lSg^*qNz%){&c7n55|~N z`PSe>az+qbad(uoXmNL1Mu0^IH>+Oh9A6eyou54o&Q=9^PImfd0-1Y;drKiw@&uvd zEwHvWZ}h=o_G`*Q9ES*Z4GYNO1MKisNKKy^YQCb-))%-}i;nO%d(l!ljrBxJiiylA zTB}jIViTGYbT~I>iX_jg0fNC8^)(loqCz;kE;te<|ML4dSrUNZPDswux_;6y4)Daz zegGYi_p+bwg}bF4rmM>G$&#SBYf_v`s@N<>wJdJi_Ptbla$*OWYO$Sj0CFh0Gx&_Q z2=G{|#+k99RdU-AY0J;$(ERkRJo!(eSZ~nW+=8;oF^$KBXwidc-!L0V5UI{%8C$S? zE9CA_>4%gYau~kI;7qQM+%lYazMUj<N2>ESs0cd0hqE@VYHbMe0LZXP;y#7-{rTq> z-#t#H>8<Q%o7;siLbmOen1%3TApAnn{jDXTwQN=|ceCim;*=bPql@FX`0v;b+-+nF zg!*YQp_KH4^RX;s5@QXP!*AM@{apHU8yz~{lV`3hrxAkKS>01C&m~%Cu0d_LZG=YN zi<;V~ZUOGmJ`gkhE*?ZX2w*8efz208HAuoBxuV5oi@?PX;iZh-4<n!HkHgNxvGc<c zAeR;Xx&EA1M6=2P;oH&G4|rF1Y_O3e{ke6))eZQuV3t5M$_nZY1puw(BVPafjDPRj z{ZUwo?0}zU%k?8-b^Y7C`G@!!z3hU|obXS{j~QbV;31OO<8`xX7Z-L5x}l&*C_Q{% z=1pSW;YhoM&ZEiXE#P~MFG$koG=%|krg?oK-e+_`ZLw!`0o$u{MRx<af&>_2aFBlM ztN|1Psh4<7b%JM}_C{fVj612BN+$`v9X6ugLh;=>VeuJWUt*TRN>(A|v$sFBFkc4& zg@*<~KJvv7zo3TG;qHKSChUkDLTehRQqA}*jD>yulNr4Uz~LK&PziE1Xayc&1Jp?g zKLK(8ik;`22JZ9KVs9dfHOcNmqng+q?2dKKk`m^KE><@a091<oibtoh8w$995(<h_ zsF2A0%PW#WgXS<ei&ja)eS&KM7n7X><q3aZPu?51d{xa^G=Q&ZhksR_=TH<)_qqk^ z&l?Z#jqg`Kq)OZJ`?t~O69ik53<k7DI{_I|ER6HM_KXQGa+{#|9c1bl@J|O@uB0|_ z8axuBH%zz>^0hxCwq-C(b)LJjWy%PIB5<_61xZ;&j)?`vEK%F_i};6t3E|%v0$|%J zTr2c13y?`lfu1`-9fhT56>o#qJ53JYTG`E~L^X{4FtH|w0P)}WhYw*4`1B@Q^2EYD zu-^5q2n$QkP&<olDC;q9i%{PZ)0o_fJQWm}lNY~qPuf(fQ;VGs5>L`|!A19?zu*fL zbtB0h+a^MmE&eSg*S^vEBs8}zMgo~+LF+9%8Ji@Gf-UK#iPcuL*BAE0PWU)Zs@=$* zL`{SB54JgJ)6o1#7CZlp*^-i-;CWppPzIW;C{>Rk!1IeeWJ%ToSSLYs`#)g#-N*N& z?Lcrcuq!pUVV>QJ@95s40sfT@D@|dMjuyk6P42f3zeoq=3XaavvM2RL97#MXpuGiu zYDcyH1IJH`)I<g*AWFR#+Kb#Txi*STjfRahAwaq=|DgnP!FDpQY6*bWmPf{~Hg0(e zg0cz)Q-oD5WY;sjx$#U>!&r!{@b@qQEjs{6iRacgMyn3v7e|8iz5)pRrHsU!><o$) z`Y|xUGV=#rRhb10V>6Kco!(%Epa_gZ%;BECAPdE&2hL}G1sx9!#U{KGO0H2s@3IiV zY<NIk<4jNze#LZ=mPMc!U830&$ChIdrrfY@Uix8t5vvz2xcO642{daV0-MHG_hfy% zIU-2015B0xL-R*=hS)kex@#N2V!LA+RR%|L`+z*bG}oKAy$$9l-$SXlcr<_1KJn&f zX(9HCDU-MVcA*-8LSuf{3WTzbWLR%+7Gr`%rwL6_n4QtNS2qx~pEvjIxTRh<tv-pY zObfmQIpqZb<AhT$dH(wfsXQq3ZeTZhM4^ipup_VO?x?vI{v1BUSHFX^pv^p#mXjG1 zNt#OtTEznPIre6OOhj&P;iSIcjD2#%d_b2Q5lADbJ_9nsGHl5<6i@>kzr24<;014h zk{TN50NhLB_P4y5+|9f;In46{^sFo?;(DtTdi7<<aIY-L<mX1tv&Wn1Zm*5;QNoH? zzvb%8YCu;*c%VUn{0~G4X3F$|7B0z3L8aeEGK$I$!eGfwF2d0W)n?^&iau-!h=C|L zr((8RyCOAb<2m0Z8?Xgb#a2IlCfPqnDTRjFxld;m{-GHzwJmm8yb7JLj^#aXo+-lU zA%Xk7jV0WZFlKmDW)xH&yb~dj0H*Kkrv(b|lq6}a55xbsTu`)E6053TCIDDdjulfU z>Rn=;pH>%JqF%*~5#7K>I_X$bN(LsjAmp9R96q74^>dfNK-f;6(%{f-v?@iUpL^P^ zUeTVlm%6sPACcxaE%HSaaLBUQ%#R?&n^zNuZ>Tmf1P!<3ssKsvHR*KIU4|}`jI0O^ zlL^vl0L*okGds2#-ni=Q8w_ut9+z|V1-Tf|84|VCgl_+84nB8A*FVY^w>V&vS|jsA zd)Ml|!U25cZe0>uF(*?nuqz@OGijy<S7}2{GeN?fW*9UbumPhwPlN0^ttUStb^w&M z?_zz$=nmkF>J%BnOzGgKD0IFKu`XTkoIcNtv9YmlE(xRb!0}uUV>u4Ab!e6_*Q8@_ zFpD|9r&xckJBOm>?6VJC&S)mZ^iCbHQ`!)?HXyX+t0lE@A*0<D`m;~O=b?!Fg04uG ziR-`9;44<9kf7_(!a4mjevUI&MZN=BLP+(jqOW`gOGdmionr%fBZA%cj>9k*9jfjA zPbn=!dlQ?iIBl`HmmpbJfBG~fgq=5pFXDCm%=rp<%s>x@>Jle#O?bvf6f35yU2k?% zLPKQCMuVG^gt{<t045L8cK;vf{4F6~DOnF*O_AY*2w~vxG0GqK8XBnkUl2f##uoH7 zFCI{|c?e2=*%+kcZE=guCc^8)x`lz4<yaVDv6K!0q>g)~S^3Z5wCHtq&JQP!JP&j= zFi-ce>M{d&ZLl#GHrh=yVO=GA5gOL=Ai!%0DC9gqa7q(*$JSWS9z-ULx8&JI!6-0M z6yT7u5!2G*T?gg|0Ab!q;}bqJIeP9IMv3~oVvMWp5?H7J=D(AhIlaNywyGJ?s9GM5 zYzCdkVt{-L{m6kE65};>;d_Q#E|%5#dMXn<rBQmb=#V`n6)BUBf0lA=HfHZ(H#Cx* z-g%TaI-2TJv6e@_^g*a>9CQT4rn8&RFYQkPtW`c@(}jLFzOXHN3vPIrlAa+TjMj&9 z8ConFG5w-px~Jf2Ad+i8W6?(UVNMGOqu8Pyy&r00I^Z(jUJ2=rb)L}|%T^77i>wrD zlOstc9W?wt@Rz+MeRI<>=ay=T0yf%#UDCdODBw7_lKg>Iu{N=y9hfH{S`x=xV#>{% z6JL-lo_09`6K+`@zxIQN*487Jfk2neLvZ0tkN%!ih?GK-ws2qfNMx^11rP#hrQa|u z;}5t|uak~@N367yLnCCZPI$N;+w085w5P=@DAfhfbraIC$sfq8{e{5)S56$2P4}dr z7A@xJTF~smo>yICjy{-Vu1@c(AV-=dx@HrQVG4J~7lfd}Te*K5D_(cOZODg%nT37$ z3vZ!gSVqngU?c-|dDnRXF4<lI#$KlPj=)3hbN0Y@A`Hg-sP32E)g87vV8t8#NH7ID z`SOx9%E@5=TSoKg5lm25M}q<zZk3Az0}Vb*@+er+z;i-u7P?lLSg6%$8Sy<d0(cw@ zON34IMPzNCD@dCdP(trLCG`lS(Dka<?lvZt_#NcvcVZgzq)nM5lhv?*{P|AY@JuPV zXuR$Y2ZY7ka>^Joj&QNG0xg<c_JC_VxM@fx1`TfjMc;VMz;G{GSP>IXJQ)uNath7t zc1L#HL;ZAs2m=ZcGDMP~P7D!+bAU;fQW6T{E0;AkZYBcJ@nvM!wx}l9)T>(gNgmDg zLrsy6B5bA5ggIf*In^W}Su8E~3KX)2#$An0Y|thE0C|1z;y?5ko4XVcU2hL#7G(2t z>zO_jkkV@&A_GB}BxvC+kZNX99=JQm+SvF~AQZI)oMu5)_JI7OZv7?R0ul(65jlJ$ zwc#fVDq+|iD<~Q_Jb#t!XN>+Ym`RYP3M8q4;*Xn6xW;u8M67@6K%}fRh=6R$x7{L) zf@#fbOm0uDE)~wY&vUI#T`b!%0Le-)h};sWLPMQ<6OL#|t3<5(9*qWg1%<A!&SnOo zAQZr7qZ;C7rQ-MuHpjuw^}N(N9*>fXQq2q%?vvmp4Z3a_TVVDAYTsvVV^}YZqcRue zA{*w$hpA=<?+jX~0JH0dXb`7nuA6YbD-f`YnD>F!_|YvBs4gfXzEEN^`B`VEOCS(J z#OdnjMC;f_O{ZJ48PG!4Arhiy?@t4QpIyjPbNox_4l-Z!^?VYDD-w$DQG3yaA^ilM z|4GB_H0F-3J!VQrwzW-o^yD!{4^)ETKrwu&&F9s91k?h3ng`=g5f(DmsC3bX!H~9= za#Ahe`Q)J&T-S&@h5c1I(3zEk|Fri`H?&~HD2=aL^ekUJ0M6=tyCXKjxa8<XfDzH= zE#VT_RbTy4%b1^+Rl}%<ah24FUqXey77xtRnZ@vXB+)42KXez|0%&u`X7A5giq1}U zzNUA?y`A0lUWtj<5Uc|4d5au>ZV^b={R%_smi<7C<n*Q%L+iE0!3Gu^GB=bI#q)*) zQqV%4&WY23xgcRqFPN!AsW9jBCAjh49$Ks65~@Qy+ZBkU`>YQV2y?~#<T-jgM2^P% zs6~S4ri`rjW}8uSlu*o?<^Ny<h!I6uFr!`q)Z&`;vlTL){0|VcMoIhL`7V3~wWoBC z8q`6}pgykznA=u7rjwC?FeMY15#l^W(r_(dzM;0?+#)uQ7WQrJDMp`^-<W)8p_YT4 zX+>1&^IPERB5Rj2agoC-c~?%HC51S#Ugyz=P*888v(K&2YU$@eQZV#^1A{__PqWB{ zh+XPxu?ll~fB6RxlGvjb>IE6b#P>WWdz6dlZswdJ34;|LZt7xJU;C*f#trvFA^}VE z(Wn8Cs2?8+jVfI2<IzXg?wvk#{FN_kY2=5#=WakV=0S^DMRz8Un3I!pCVZM(=NsBX zdEx9R;+&J?N}cK|mL&t>Oq5_yN-%8kPbMytEMARRUEZ<5C4Qcs2%zUcl0O^k)pP=< z*IwR+?JpBvQB~k)D<G3Y+;N#vm@{@UBAJ?w6QU@F571GAPA!?zEnm$rs`)Z+XM4v3 zW;DK~$51GFH8Y@D*1>tw8+9NIn6rS02M5VGfQ?#avC(1)$MqydH$H><0M-}g!zEqz z1fGj70vl@ygt_3ltwgjGKyZ)Vd5a-PVv|qDHK?HWk+z0?Bx8(pOdi(0no3Js95fHy z58li>x!NTkY8|%=kU0R?3}2E!EL1Ce-z_yeNz_<dd_UAKmxO2etq@e%d21`VZ>9qm zff1|=FYSs`jwWZ(@Ql}%)?fpq3O!d7h%y9OIjj^gVk79H7(syKHgClnf2fI%AN5mL zEIV_pU7+tri3EIkt`~?Xip5Gfx`XNS+rX4N;vk)IVf^`a@T|b@uB|<#8$uWZ$V1K7 zV!(y~)&gjDG0!cCBJ)=$!l9a@ya94^J!z8;(bdqPPpSZ7Uw}E|gi9WlNu$xP0Eu%S z0y!pQTS&8`XFvEI<!-Wb{0;#WQ^Tz2UpEdrU{;O+&L;ssb?RIX4aM0rEn1I^!Y9>C zYyiLHyQI2jZpPiv(K&_$SUd6C4-xZFyGZ9$3R-7%EZ4q8PPY;+Gl*opd|^qP8U{>y zBm_B<7UQRv%}OX!Q+_Q+j>xU<PN=S)9>^pMiZ5EX=JEKAqM#oS8(p6D#LAu~v#oop zYbuocf(%MVzJqLj;JQAB{>`}K;<VtfO*jy8{xQibB;P`VOoO79IS$eqXyGH|V7JZF zjpg%r9XnjtLoQ*P<L%YVfKI2$a{V(M7BF$xqfYR?pzwwhCylkmfG4e@wPHw#_sa4K z`~QKgF;eWd6Sb8XMr54w_F=Z(O|p-pZxbkRNRK3(enIU*$?9GUV-!vnDKp}UO6XXl zz1C;07N)@!Ve7*F<o_m_5l_vxABf4^(2+cYV!cLMC`Ou<9(DV%_|<HE7@>B+yglE~ z;XX1TxfQtIcHR0XW3)9wHs;upJ@@Vj0;Di09slt)AkB&7r7NLJq~C^gi*$ZCmnJIj z397^Ot?saficha~9^}NY$t4IjTdjN#QjtwU!TnT-BDdc2{=KL_us8I{U>S%6^}qJf zu|1KrSD6c>Fl98`)+GLVH$kRJnYMfAV!O94=75u=%-%2UAJ&^?vgrjHH&wIfiFJXX zfV~GDv4bblnzCvb9gJ;!=^0@Y^Y{3P%nka!om2`VrNr_)g^{x(tZnl>cluJxdZ!4M z!LodkdzbH|(&sK;OIYjTwmqopuh%7DB-;m6uh25S*u*D)AE)`(1FVLe{j|2+HRBO( z$rWA-->=2-i-lg^4tVb3ZU-%718LUQ7v7R}-L7%5)8OA&z4e^_QD^I$S@Hp#n<Rz} zKcaRj!`nUS@d|#rT$P&Ix7Eg+vvWS9+ZpfOJIAoKNqjcIkpCnhtY<wADZdXs=Y6yz z%y^_oMS%8}xWl048-0B9q~(wEnfQA$^*u4)pG&V@aWaK1c2ixn?PKxB9q`{}_kR7Z zB_@Jwjr^{%PFXjw6+S)aUcSPAzg0&AF-qN#JaftYt@|Xk!qSn+ReYVEcS55v_KeoQ zaX?CI=5<5p{Gvp#Yl2EiLzILQqriXc!_kf#pK41UuLE~nZmrz2xG{=SUw4>CwJ+>? z*4uZeHQ$4lSvSCB8J1r9Suo+17*7ZFOPC9lQ6E~~-O}CO;1?o?(eMp{T|{{m{%lCj zQxe(DgY;JCU*$bs_Sa=#IGt4x7Eo}{Pqic~KaC5F4x@s1et!yYwe^8epM%&N01%!> z{)t>G!%t=SGbMBfq)rQUE8ELX0XOo9STw=I-~nZ};5Q1vtp`kfo>$4@f&5aAogZQ0 znfpDEe|LrDOxGvE14Ey?Pa-=u;lAqJIHdzN!>PRBwP-nSTMEfPGTSMtSVhy*Nj{dG za(Y5|#sW3psfDPrV+AF}DACKo1HmJzv!UQQ`zeJPYQ*s~BiU&rlX{S_e?PM0(!+z2 z06X9rqQ%70C3rr8q!7t#dJ<H6xmga`M8+a5Egp{M&-8jpA2z6tA93J<^+s#22fRC6 zegce(j^Yy@tJ}eH6MBA$IzHqvNxY1sBm^(_7S7G-BV+?i1Zp0q4GD*`U^{H?!#}wy zYtg(v@*UtLeG9+_0U;F3-d?awb2ZCMit(6XZWB-?w_Y{jBvcuSh6j~v0*&C=-kDYh zybPz5Gj<Lfw@?d)Kq$(G=ni~CYq!N))@v&6)S#v+9`_9;w}Fn(nF8pq%4sXgr~AwE zIPa**T}E0zao3md*4t7$S-a8|&rAM2ZaU8W!RnTQUfg_J-dZ8fl-Bf6NWoYrPmT}r z+<o=^Seoe-gJZQG)jx<y6*U)6|9(vMXdhV}5Tmw#(?ssCo+8NH;mYHYQercEFW#~| zy?4FdQ%kO{N7UzsWH(yA6sP?VL0ST*P$;!I$$c+l!Go@MZ8DXjL7FBitu4nW@Hff6 zmd+3(lP3Z;%MWnXKP-Qf(-_V=cWLYt!^dFX-zm^<xceNiGK}Xi6WErIYiVAmjHIiL zBW5|Z4w;TTRqxifu1sJHLyN*e5l@2;Tb`dNOAQ?KIVZAPTeUB_9lP3yQJ#`qaAC2G zftAJmXU!3l;aXxN;qcx`*R_kaMTjtQZgYez*JE#);%y#tc)b<O7E^_+!Ad&zHH<7t zYdx>A10$|sJ2D?PL>hZcVm#ev?UOC56)-s!8Rx#;Xa`IetMkc`&Nkua2Xs{*);Ikv zFtNZ3?td=N45CLLs6EfcDr?4+-F$U_*E57Z0cygKB(HAfCSxk~;0nga9KD<Nl0^?u z%dg$q?lg~pl0ELtw=yxtvhaPrqKLjTj7uw`5mFy&?^@}2#)s@#D8D+$y}|9MSb6^! zC8<(>P9+56G;YSx*-Vges>-!&9rjWx*W$#DP+Q5n4u6iA;G5xFpxr&pp8eYRqQvn# zSItuOZbnvU&^R;{!%76=0RZ*PkYdc=+m^H}HHb3zweh%*1^VA%*moe?M+?Vr%F=dA zFYx#23=%~lzXvn>ec5^Tf*R3V@iN=fWuZkAv-bxv?T&9Iq0SYSIrOp)g}XG(A>BHe z5vm~|iNFr)-iFJ?!vu^`GGiOBeb&u#RE;|)n)<07k<9@%y8l=Y;A$<$7Ucxq=04lO zBFzD<m&N^<*5q&UlXikwasbHfGvUPF8;m5oHdw0vVKv`SihuKiL4%pG>a^17H~}?Z zI~i_Zh1rY0<^zA+@0Ullm~r!pWJrO9!$0tRxDTQSVXYv+h!cs1mU?%MjFdpKfv(kw zC4@aCDbZoSY4|yiT#_XRk}$9JCAkx_zY*6!#+F;=z;Uz6_xJ@CsJ@*VpAohH1Et;| zzX_(xGRfE+#Cw|m?dvYNa+py^Wu+)PR)Gnk_^5b!cUyw#cW;ObBDW-R-zex<de2iA zuOJ_CskiRk=apRLC)M{7?1NVX_D1UjWoE(%Iu5oa3vq*|?n&?8DXuxvsg3MS?#b!9 zx_5mn*uzNYM$*+Ph8`{bN8Ydem+6NZWFf6PQ^i+9YTBecWKW}pf0O=8ktxABN;$L> z&%y;o{n?EE)g0l?-|yYcd`)y}+9?OQ>h#hfJN)X%e<B7w+lJOo!q?dq@}GX8&5+GX z#ol*|fc)V1)#BkSjP>_mPtjSri}<Wg5IaX`%Px}J`prq5lUT#(`TRtHlZ#_jdpcb6 z2@(9%a<lTS)q6Q$T(crFbK{T3e2}U@@Ej#GbbYZ)0&KucEV!<9rp{v|U~7tYRD`xY z(OYqr`}D>2QARtiUy51ZlNWd3Bp6rapA?LOi}a9AIA?qdW3wQrB8dwWIrw}0Z16^x zS(UCisf6`FmjE>JacADV@UP+0#Yu+ju9^j)d*l0feVWMMAXhkP!#6B=-(i_cPhQ(W zw!CGwaoQ$LfqP<+E^d75NT!D7BJmY`@t-fic{}}6S}wZwghBRe$(zi3UO(5FIl#to zT@^2viLv;88YqEmmIt^*e#TleNEP{BQtxY=Qm?FGj!Xy_qf}yb>2S3z7bQc>>CMZ; zbk+=6BHD5ezVUpQlnKc$p4)c&5_VGUl>Zjkdk|?E%JMp7%G1{8UJ2uB2b8)kx~6W) zMNB|&Ys~REdvVns?Q1&zYn715-xd$`gv}<-dozIMz)IEV*>&q`+$eoQCYbxMx23gY zJo~>sBj9o;_TA$e5QL%ujLFdR+J0B7l&cG%yL#iSkLEX5G&URbnkr`O2QSfr&kVNC z>ZKcFPY5`Rr0~N7q~P`+sNT|1CQ@ufNkZIM()sr0syRl4UV4%0=THCT?*=b6gVZKa zWR<y83Z{Zxl04)y()3peNJZW!D7ys*Ddm1C=j&E~);8;_G@kn4fi%hn(YT@2AQMH> z`r~LS5WTj_!AgG3Yre?-^`O-rtRQF%;zFJCZIWXK-Bc@Gn1wQFpB7eCQik*sX?s<@ zRDjp?rT1mO)w5Q$swct0+eUbZ?rJX@IHq1n^Y@jwCan0kb#Wx#j{<(*G0Xb>_xC}X zfUf6t^}38k`jg|n7KHzST62n?%lZ2a8}Rc)L7o1ab<C%mo}l>U!Sb%N<;8o7Z<|+L zJ7$&;R0*vbB0itAax(8VpE`OjIV-_`xbI$6Vn$xV!i%Fb6R8wnwozuDB9))CL_G)~ z_Bj+(SIuV0^#gp8pIt_^-5re7O7u>2@=TiCskgiZYEe}_?E!;)1GOQ0KdR)cOS?=& z)CH84n!fG}A4PqWF@1VDxIKB`kNl?=zDEvP?i>r%u8Bt~h&b|vGVxs0Kv^{jP^!*f z=f2mydj6Sy7qrl4{iiKWW3BPsw?8a|7Ld5-;PdF9o^-67mGAKQHx*xuc1;WgYgw~) zF6hpeiM{^Tlcsa*vS(q%U6~Pg9l?~cVc%x|6!TL_6sULf5_|E^^~W)8DzQN-E-Kox zbHj+L#oOOoF1>z$P2D0Y+D7qDBh8O>#kE|$>E5w?`0$`&b?Wy2K$eYP6nQPW6lWK+ zmvK98@5?35yoGv$_u*S@E!u8*DOaTfA>nixn9CZ!><Y2VY-Z!=o$k+$N@T2#|8O-= z?d?acG0G3yHR01lVW_Uh&}V0zAM3m{rwN#=zATfb#@}rI^vO#EX#_}M`V!Ev+!cW; zow@U?U^v|kz@`mzLUA`z+NQx(5l)$V3!!1Zccp&uyCFzgR?@H85P(Zv@x?j@b+B9T zzwM1cHTL+^CG44zO~xd<aD=12zb-Ec!GYk(`;wU_12N~+dw~!?!43th^z^BdIB6AL zY7-e}CvT~$Zw^peIQV>*=7Fs)^w)o3A$~!=+YE!Q9N-l|Wwa(sDvK&;If9^nGL0Rg z1XxkI5CB#1zFwNU!2R6dos0fDH+HLypSAU%|Nh2K&qb5}{cd<K?JV@YM0g~C&Rm@; zhc9F6iiK---T{MZfqYN?0KfWhK@GlN3@hNFO?PyXGxu=&G=<*rxcE=%>=ReN(kg?* zq&O!I15Sy~yuMh<I8?;nt2t`d0kRXWnLW7q_O^a<7UK{Z`6@GV;QHP><EkerdEm6W z@{$WC)!rY;v2yopUgzo)@vXV#s?lw()TTM7#0j2)k?+l_rz{n~7NPqHKEPZpzwYr2 zQwQca_%UVi3LJce=}N(*|0ko?r^}Mk_Nv+Dc&_?Smrefc%Z^h7ElZ^!{zxmngImaS zKaGFgMTV^nH>iR8D`@31<CbT)%)xzp0I)5LUG8)N(A32lR99Vx4EIY$RvpWl)o^!7 zAwv3ynKoa%4@9g^Y6?T45K6SHVB|H`0M*jdo3q3&i8c4@Nt&Yq>XgJ;+%U+Ebkvo9 znq({j_aDwK^t98xQ2RxA^nW18zORzc#k+hL<*~~iQUVe(F&@MD4h}Xo&}X}O0n9?D z=mgMha_l`rV{TTC2h~~s5u?sp>XV_><31LC|8uARoD;)uQV#pe#K@ZVEe5DMEhQS? z@NsbK(@Pwx1+8i5L++|LnhIIvH*Cna5ff&1yYCXu=lhv2{7BK$yDkWtOW%*d-HG^e zD5c|b#tf-*0b35#)rtR_4IJ6l`zA9^qsW*w)@s(?)2jzknyYco)eeX7CU4zFR1)fy z{sw*=Jf*j;R^J{nTn)PS<&J8#@;N<IhJp(q_<z5lwWs{@_wUPo<{G8Qr6_0(q#FHD zyzl*~F-@b+;Nw;kg5h6vLUDJl$Ju&j;@xt>m{Mpy<&<jtTBRjqX?4rLTjbVUfTYr# zH1>g?JLJphE=&JrrF#Cezc%X|L~$-L+(nHaVJh^BvcWZ2w)H+yX?ttpRpE<*Sk(7v z)-dn?K+HOa{(tJC?2{S$Xl0hNcbBzL>oC<(q&@u$HV0ib^x^{x$&vuP1vOITe&5ds zuyT;u`3D?|=P1%c8B(_)g`QiCe8rRRlUw(Z02y{0Kvb&f;4<yxy|ok~*~Q|*cpy+3 z6AM=P&Xg6_7R3mE0N;7+bnQ;h+mpY~%e^Cuy34xb5kR9_dLk<JRbuq1uMP&4)hkPs zz_8T6*G>p!bn?)Q)wG$kEIy?_kDpzds@?uD3}fHcIJg$etgKK@9`=_+!R+VhbJUzt zhyLX--+pz!1qRa6xuVc4-!So$yseb}tH(N2S2|(`XWg>9bFN#O+*_SO0Ks_j?St+? zW`@+0(2s1@&pY%T?_uvgZ5!{neSa%EkhRhU<CaeB`P`~m)hpAe4%{!fV)`_3*xH{0 z?RKaQ$FE*aB{rWdK=ibIFcU|BrjhI1(!Ymxi_ez#T(CW8&<OAd?Eit5X)j>qUqn9@ zqHnT|FOJgdzod8SElE>&Dr_m7=6g<~O|G6jpYK;!EVZa<%48diebj50B~-e%FheI? z)5NzTG9<sxr+(Z6EIrYSb{y4TH-!HO>iJ?}M-H=3xN`k=iecqhItm4d2A6cT3d?>@ zSuEfS%o6LhWIn%@mcH~|H6=w45<rLTXDR;)7&!jE+BC=cjI5UOGr+PG<`#W9@#^U) z$M!8FkYlaLlsyA@<J?!IFK#_=5D~11(S>S0IiK3mSEqm2$dVcN%YQ~#Uk=B~aA+SF z)D=@m{5XG>=PDto(`IVQ2r~1*!WoAgn{+^L?-16f9z6{*swBOAAn<s~U{JyZx9Awi z>K=Qk6;>SaOG#C0cq9m2uatA60{I<t9;k0_x}8w)aGDk-0ZSr!Xtf1%sLJ%6Z0-^h zZs(AiA6x2pW$mp?mBLV=3)a^^lT6Z?s#~7AUis`+*v;=FizCe4no?7dS9%KDW#!&4 zALLmfUfAK1#+$YUI4z@hv;FITym$a3`vI3HFuwY%^i*lsw3qV+qYx^YEO8Gcz<jt` zE!Dcb-EVW<(DSPg%=zV+(#j_AuMp5gD7!*pyP-__X(>^tNmlv6b8mX9i3M81;eA)g zk*q?;hnflp1zu=_+h9Phz4Ek>gZ1<4eRsb;SNM6)6KS!%<6y+^WP&!i`}+DH<VOji zwI#@0<ovP|Yobi$lFQcHh!A|b!tPg6g-Z9C#NS-i?;52lC^^jeNoV8x*TqPhzC~)U zc2*ez=y=KU6Soe)*g9t~hCe;c3~n#2(xcV|v^+FQIsN*k!uLx!x_<*2U1dSB={VWs znfwHlnl84JSco*Z8T7?(JpYaAh}U%DkKh?5HafXiHh@VZ3ajU>Ap*36<EF0Bk0kMg zLIxtz>+k*#gw!bE6HO{FgdW#I#`k>A7Beq&s7X59P;MA7TW?twaOC9mV1266jk^s} zLTol8|2}EQOhV)VkAxsTN}oBaKJPGb;$+H|;CA8L$>T^8yJS<KOtLr}H5lEg0-8u& zWS7lhP2Y~`Ys`oMAtY&jWnHho9f_)cKYgUAVgF~**kl~Pd&=aXDeyrg6zg@Gjv`wH zlC!%*@sh+zN0WUC!sNZt_t$H?Ec60V6E5IP>?c*LY74zppe}yYLH3;a7s$Ts1wCWM z^cL0za55#KKgsWAw^Uw((kCd}i`xNZmtFGIDcWqNEDy0U@5_m+SBwR60hAWiNolN+ zAkv9R7`xF|_ddE>YEy{1(tK;Bpm#zjsDnOKdbC~^IIEn=Rv9198l_F<W=2wmEs?RB z4GP3aT?^GVvbi2faH{%$py&5vS7pX`6>HHy%<2QZ6!bV_qCm{suFUSkFX`k8cr}tW zoFDGGd-}(*zsUbnbms9)_<tPV43jh}zRlNWL|<25Ir?V9Z1l}lxx3{^rF?}U$6Q0I zukYFjQO&HcV{|x*kZV$g%7h~4G@9jRZub3se*g7Xk7WB?@8|3JdPDfEtz}h55zPPA z*j|Ha(0_M%p176Z?6_2cdFOxeP@+OdwPQj&T=~6aFU5G$s;c9f7HN?6o;dnOhF)a6 zT#_rdPKPDBGJl#!ZW#~_ggQu|rdDZg6VbB#e0J7t(F6Xm%5&0{+PlcKSV)Bu#_a91 z)uXw}3u#1xBP3X#;!j(fRtzXtn^2II9Wiw^!VWa%C(gLdA#IG5nb=7g$kh)IaH?25 z{(7kqd{K0I{6u?=pH8FsmmN?qxs3=(IP{kbI2_kglB<`D9WYKJ_sr){;7Rn3TnY~U z8a^f>Dsc2e5DDg33~uJV1$O<ZX>TzId=cf1ncpTYJcctBE;FvOW@^Md6_a#8IFpES z&Bn}zS5p$@`0>5zZ9?#eRv3VRQoT$<u_EFgfB4q*7!v)Rdo*h^oFyaEvC>Lvn>xM} zdPa34KGPT{EV6Rl9u3u9KN>p>_at`#I(9qO#rzVjfBL$okO>ZA5F#fJsGf^W@C5m4 zE*6P=`jS-FMWSW7N~szFy|{ZuGA&E58BAN>0wZIHsmE1Qw2XS@EH)o412HON70sZ= z$HNBldT<3oj2?IOwk{OET~m~x2vfy8(A&1k?BTkD=3eeX5U0~PRS|91Cpu2eYiKoh z4@<AZ%@E<1h<}q8Y5V#=Q=%scFAiBMfO-GNUpz67Vaj273Ed3i)fjgiBm?w_bBE{b z?LH*wUBGW+S6GYdFj~`g0K~?+)!Yx0g=v}Vn=fc@!|OGLFO5)?!)(FPg3#r*J4L)I z-ZEF$)iLpB!(c#Md48wk+Yk?gVgg|1s1y%F9DIT+O_nEVlLnRV<<<sL`3Nk__a}$c ztUl8F);Mn#G1An*I2Xx$=-LTa=A{{*#wV(8xxnu7x~QQ9@NWJ%6JjiB=jmXEf24;h zc9=n$-gEoZ?+j3>VA#vVzP}2=agl-|^MqxQ3Ht|5o3Yj43}`TE(*1-t#y`!&3oI(C zHK?KaWtbij5i!s*YuB3;&1=M$Fmk6D)g5Qb*GXykJ5^fwen0$Scqm6$&RcV*Tsn#w z8>%BK)kyrnr(J7l=bpF5lv=Qu<15@|ul)1ZqHQ#+98LK3PTG^ZF7IHBFmBkaUhVG` zI~!Bl<2$NWl1j)}jm&9|LW48Lduia&JEd<sD`Volh7%m!Ha*LSM*d+ynR={cZs#}L z&P5?LY!LF*2iJD+f>xs}wwb@JXG*abP}7GZwyv8rM=<ulwaNY?w=YEtugN2#robqE z-Wlf=?@LWcCl0s8v5K3KGhnR4^8dZ94VCZ)uXk$}ImPhX(uIy1LFR3{aY8LXdqG&- z4kOtx?*9Ct!ZSfTu3Gw`pnda2*@{%Yi9lmf%_<YJ{nJH&)n-Jti}O>Ofzzo1Y-aQW zXBa-DwS+r`mO)6@MgF$k1X1Cjm0RlWJ2uXulSudn=^6mIzsBn!WR-5>R$B2TW;3K$ zyJ$_4H;{`%S8%^`W>T-W5ssVz+08U1Wm%1z+(O$=$UulqVr7Jei`&tod*2*e_Yfqv z2~yoCS)yu&yyw4|%w09jFm~0SANS2gu%3+N`*?)F<>TU_@^{urBW~rg!e&yh`MmR4 zB=2sOLCv;}C+7usQ1(r<fq!9QMwd@`zE%+YBqu$wHA?+$#_v>h;vB7p<qy4(q^N@q zTeYgn*>!cu`bPZ%1$*8lKeR+U;SGt~N3+Tt&1TlX4lxCTTi?^RIMBS`Z_nEEoP(V^ zD5zVQtdP1!k=AW4Y)LuQgNFDs`C4G4c;$OWTFsbLZcDN7N#RwW*&`+6do#8+LD^Cv zMCwHBwi<X)a%r$)E4QR~Y}G)n#KF5WgqF!v1=@_0hs3a9jf?4-XLTLTt<ge-)U?LP z2-aPHHodJ8wI=AFeD~B;$+TCXz78xmw<Oc%B^FN8H?<B!KDX|$D34JeZrb)Jcm<;r z+_%GuB!}PHRJbzAumY=plK`_};6vKJ20ea6u2uF3$ngeYdA?k$(e8(}D%Hk1*Re-M zUHsly{WLiX+cRh)AgUla{{NP2fpy(q(^d`(N6T>mN?X!$W4)qs_5E*KiA;8x@4AcB z-Zv&tP?Z7v$}gOkb{9aibx<p)h=TQhl#G*D!Y+B@ag{5RvVfmbbI4%Y9uX!d_q*o# zaX`DkDc*sFO22Dj@oEu`QeyRxm#_ph<z@+T>lHPMPW@Jy1}T@?m%!<h?&v;rXnvWu zc(`lo6@)b8M=!i8RVw+{#8GTfjup`ZLOS>gN)64eibeRR#!C=oVYRo=ag;<e!D`WJ zR;NLEcA)br!m-SEYRx_Br#YsL{D^eypA;Xb2w^`pPTw%Zx>KuNtV4I|h1BJgs!#^$ zFLXK_g=sAs2vb@Ep{@9=aZ891Vq`p#K5_EuK;e9-+z#4E6ELAcpN|@7{A8<tTS3b> zBvz-VNS9iz?6M{EBmSSV5*MVUnHj;TSE2+Pk02KZYmQ-Em(=r4BruI#nNh(x>0JC~ zyz+OXN}GD3!)E<W?8;V&lAc=jW`A4jh;bVjMau>az%c2NQuaUL&Rk{XkXF;mGEe_m z!A8%})AZyF@vQzq2CRA3*{KpDJ9xh-9aCK7sO*!`X+cVjNT|ndveYw2AHUu)spxsA zNEgz2Argtxrrr6P$xlKcNZg)6E!it=sE&}Q7BfHNAVpa+<)Peip6`asHQ@ZsKl!{V ziYDp(jvZ2);J{H33wMW|m8E9<+vtTg7sS`?QC{K}K~Df8TQ-AoSKCEg%Z=_CO(OAG zr9j9JpK&eoR63rZh~kHf*_SJ{QIVbIfSbn-MDuWjKWr`E6Rlwhn)c%fUYSx)6aTgd z%i~V!r79b>NyGA-Cjh2Z7!{oLQg$CoK`cPUEZBZI?V@(w%Oo1NQk0vsIr>q`B3`-R z)<se6rXDIqrxD-e1T=}?s83|hAltUuSBm?M2buAg%>Apa=>ZX2hF<`q2E?BLpn}ro z(vqg=ei=Pzb6R626r-I`aqp>}H(NQjMK{u9fnrD4CaX!m6oj~^;0iqVKyWwe?1Ks- zo4L*>T%@w5S&Im$09ibKivI)$>j6ai_q=LQUY;dl@Z*eU{=8P|=m)i7EUS+&8$mnE zFB)befUSTh(t`_O!JnvE@(8lJxx9C_wqdBOaeA_t75g}nztzuu@*hOOMf&pPB=Rr2 z5_^<~cDK!G60+Ak*lJO{PtC(300s?HYSD3~gUZl7OqLSi!8H&YAs;#sK^Sw={N~}K z$NNN8&=qy38D*%&?4@z!Kgwn5r*Sv?;V<)i9kJ`7(24T6ge<I)cBtHBW9CQQ6R0C< z<)Ud_NPlR*D?`eI%4hzds;tL*=lDQ-U=5ascn!4O`QMng_V!DZzo^ZZ^r{Qi$S%-~ z)!nv>QC_)v{CoX_$u$rF#6ht)-Qr#Btk<B9PF>H>N&zb-NU(j*tEt};r4a^jT+K`U z6ISzqFs>?hneB)E`)3@bs3uUL&jKG53E2hmL7%UoN~c|b+6BhA`S~TWAygrTc?{JE zx4L7=?=G?R>og(*4i#F1(WktiL@<+som)oo=nO>t^nk5tB1590P8{FGWzEp7>5gQB zq(~BzwG8&WlxmYVx$hKNFgAYD!r4aAvSiXCTr9~<wcQ)i>A)vb6Ey7}J`5$o(-#HL z{tv$^Brci1q1eHC3iT$4csq>X{bBwQkrmOXmdhreoJzVd;S$!yPaaH#$o6anAjrGd zW87DFy-Td2XKT$qkYsjoQZ%G$MO^Vp!3ay-krdCufbc`;`!kUH_!=%d0H&X3+~{R4 z(AdrC#1-g6-roBNp2FN;XLlH@wuaVPjRMQM;TUfx4H0#*$!VmQE&U)kleXihY>eA| z2S|!v5B4YFojaMK*DhMj<ATP5f#OuTnfn$Du~fmCP^TS8$tt`0>%R(n74o6v@p$h- zgV=l~aa_<%*{cDq*=qQtcE`0ZIb#De&!*Q)P0+fXjIdU{948R(B=iivfWXF~%9}K+ zx#}v+`$`7ie{eB>5TyW~)_my8(Sp}RK*EOPqricdRoH3f7(I~BM!DZs-g*Z?Kv%i! z;^J1cJK-h`yOjdblyNfVV2rh>G4aZA{ElcXOS;$SxZ7f=X>GDE9g>h2;C4Zc`>}y8 zkH@iO&Gdy>!<+&05Uix~$G|(pgh$>BEm=^}_b%FJVOf$>FkGo>M80Azp4NqSJdH-~ zqK!0|M-)LquAbU_dOmaOp{K0EVA!ba<0_Np+fgV4mWOhIE#x&+&W)o&zNnjEWwM;) zHWY)qbD3v8sCk5Qj|s{P1VV`xEo^Zf4`F@0_|c^H3UZkK0kt8I>)eOyH>TBt^Kkh< zyr+`6-vGl&d$-1V4q_`lK8Mu>A>5>Iv<iYxKpmLMStDjXiM>5!!y}~=qT`%hsA!(c zzTTBBT~n2R3{SO1bVh9WSM92{d~LTD<Ce~J@k6b2UOTN8R!O}Ho|ZRVPNhNHxbu?y z?nmG4<j-6mOcWD7sAo!YaC}V5d=c{X*jX|kL6w1C))`*+h;13ADmsh)AFZk7#{ky# zF4!W*(8in%x64=ZaEf`CteBO`24*rjvuHc3CSld#%X#0msM}!H5kBD=n?K}F09r|G zp%&yysNw`s&dLL1h!Q8EVk_~diei_?7o;Jb&g>IpvPVjUk00)!$M%pyg8n_)_|DdN zH*S$&dk93<(s{18{eWR6#0=UM-ihU|i`jwPjv6SL8m^v&98ea9fO{*@%M;}sxL5oZ z$5+(z?h#Zip@Zxb0E$fc%_t(pa}!aQ(5Yt@;=Bd7O74wE&JYz~te<?PBYe^_8&fYg z1TeqG&m+0F+pWKFxYd^Qj+`S|Tx{#K9uV#1WyxNGr7zw;66zcu^@HwZhlOpWlBD@* zERzuEID#v(m35>(aZOH4zfZ`5`Z{4h(2Q4YO_|KzR7f){nfs{^Uo+#}c2H{81-D+q z718t_s*aEm2?Xat8EwO_8iKq)0ek&>n&QLwD>~alkKB}xyx$z=b*J089m$Ziwc=A` zc2kfO6^YC|VbyQ(C&bb|KN#|n3PgztT1LwNVnXrjS$Ba^4un28SJ>O5++>msNl(kK z_6`mR;#WMxS*&rLa=&J!OaG(3loo}Yj?*<&ruyL<u<Bosi(ewj@RSv{$xH}qp$Co4 zx3~kkfUzw2>#zrayqf1#*)c-xv?D~K4f%@|f{;m4E|=vc{F-ff1Nk<|0i_sRbWApx zOf^&ul|!2j5^^opj+*+1`S3Rq4E0{zkCYzs0H>&>4S8A4NbpC~)dq0KgJwC~v_yW$ zTk7dfI|Ld;+~D)nh}FYeiM+05-ukD*Y0=)GBNJ2Qe$|giFuCmW8y|1CmWmwna>5~l zT@>Rj9+43H)Y2o8l*B7r6^=mZNnHFG^lUMio)bn1AX4v*PMIJ>cZiNgb{?Tgz-==8 zPE2L0#i9ji+xP^M>q(-K6+kD1_FdWG5AEEq*+oN)G-D>hg5Ht*q1=5jv1@~t@T*&) zneMpE<|z12+y#-HEPzDwZ*C>LrKe^2Pc)@OZ#5TPsTLYA5F>dHbftZ^I1Im#sZ>aa zOZ>%@EE<WUqn->nLW(ub#5u@%#_3WW9exRH<z?c+-4zN2h=-C%Nv<vwNxD}v)L@#J z=iQkVA9#ZUS8Wr_vo8B<3$99%LFlYdP3n$LBF(B1=%4ExTKpFU%8-59O6E&*AngB> zohApLl`{7)Tl4UXII97_)@gV0PEp*Xl#A{Aww7=$%nPj>t#Gefit&2;Z*Vp1#JrDj zCAKY^Eizo<s8Fg>N=NI!>&-AQgLTZ=RkFxbew9!+v(_!8mROB%GQ4h7qbdmDvC+?r z_T|+V=(*QPHs)qhZH(X=Od>bf(Gyc|R2Wgl{+=LzRW?$it&<1@F#Rm}WgiD>AWm8g zA00>!TNFOw1q04Hq+O#%nmV&<h$fNr_SA5z-rQ^_=x?~d+HVvc3#3^@!pdhJUEeyY zPDGcG+FRk?Y)s+)ipBV_du>FmK1(Q3ksm+FSg6B%P`;N;Au$D@FU@!#%m<+K$Z<v} zL7&vQLfw52z=YWoL`1|nWM-!vDh~ftD-F?Y%0VwCaNJ+kh2|N}&`eCs<MiGWEf3+Q z`V|yAD9TFO5FfuT&~9JCJ^(p*w(P_<$%e5C4T%ZW8*Qob)^{QfHiLo&8|14SUNPjJ zH5>ViEEh$Td+1IddVLtxZI)+YJ-8Y@L)=L<9DyJ^;Q?ysMmI7!{$fe0i?O`Jay#3n zY*?Bh6p7wLenVISXCfcPPn0OD45nAlud;pA<*<Yzz2mxsBXKws3gi(NeeK<xa8vfp zs!qmY9VFP(E@kF6d2tECDvaS+7ScyiiyZ(78uAGjvj2mW(sS-Ly>*7Hh<WTPosUQN zf_X1MaS^?>&8lsx>kZhMREYa9rG<8{H_=f$R@UNZg50zRHGEYxlBTCo`bD@dT$jH_ z`XQrf`7)YExZ~T2MPpH?JY|y^%xJ8_^{FMj%Utl)9u+x4H8PlWjk%NZs#&)c%f#>Z zKxNPF?oC|BNUEz2eMn5?TF<Px=}Cu}@)ELXqmrl5aHK(BF$N5`pBBJES|wIa@GgM7 zwy-*f(g$fRMG2N}6K9ia7FMIsO@(HmFCR?rSmwSatH*p#`mDRFW<02Evjs?=^!J=H zv3EOl2L*DQW*wmB3;^Z27EWQ?7A_{%41UNvXkPpp2&38Kqc~gm5{`eclhqu`!ygj` z>y&|*{dGCLPjx4Qbi$`bKMFaCzh)sngU8>&t*o$vG_5h&FCb>uP?}TitKiAOYVJgM zr=Gn>JGRx<bP6cW@lmbV_YgRI%|n>MRi-R)Ed6j|Rx%ZWSFBkn6co)e{{JD`TVuJm zUzdk2iJ0~D8M|whOxO-c(Dnxh13~I_2-V6FWCka6wsaxd^T`>hCtqqpkD&Xtv}W@P z<*g?Xrk&ubz|@QPu8&mkXMk)H8Av*&SG+&WZ@8=N=#3C!zGku?D3=7PKXrz6XIq5U zu7VCX*@MhWnX`(xX~La_{BgDFJq{u<TWRO*)(hhAS@x~`C}}=94@9vrCX_LUEpt%f zrl8c%k0JH+j8HG<3RUsoT}4%O2z6NiA@#g~7@}>vNwd*~o2+uo>{4>7b@la~6g$sw z?h9SQp%dft*C3Gj=V5g<sH<5v<15&yxf#bu6@?*{AZG7w25FY{E5tfedfv#Ikb=Ee zbCGkS)z*AF;q9Xjxy>~u2*su`r-RR<`4!D*D2FA(XZXRoACZLzC}LEq+zBa%tp;qN zC5iW;|0WAY3&pywZ@AvKvxIU%pSy!3T9V2C7&^QYqBbvHVL=q<po_FxFdBErWnI4F zFc85clbq-%zj6Vn3S#;71ji2n9X%|m17Q?BwMKSZBu&g5loJ$@oPXEUh`odUme2|B zsruvP-Vj$R!@s9`4AexboUt%Y!M~vgNZne84pLF8z&2BG!~6F)p~{;s&r6n6I_-Q% zC@QBMruV6Go%Ei(QMUXKVtn$Z-z|fh>R|9|N+$K+5MZ{+kP}NODB4q5Q}GO_;>gQ9 zM6|<hq(<y$3%V6vB&~|wtR25f*;m#xNPkNuah<y}(iuJrDH=BmwP<*XmvC@^vNzmk z;;vTT>$nt4YWZYjNEoj>GcPCTCxa@00h-BG7?6^-&&M<^1{AKiQWagNc*Wx4*Lr~! zt#Y62kLt{J8gI|}Il<*&J~20U(Yq;HHXpcb&&c2MGV<mWXT?9Lu($KZJ*8Gz$U#O@ z2mwmmb2)t~oq-`ANwT4kF+GK*IzBoUWSG;{Kc!zg&(mALB3+|K_p(S7ZQBK;6ED@y zS}5EQNIk3~RpiWcDx#gm>^teX$79RHZQ2Qr&OVUH+}xFI^OdbPy^mdt{nD!_u%ZyS z$Q2>y#qhg6jc-EeyC}&HrnJwR<^@ocW1rPX8Mkv!Jjw=Hx+f6H&0o{Agw&ah43RT5 z>%u_~svi1IH$|JX$)05@Vmb<3o>UvpeX^~8ZMvAuh>2hesZH*^h>;|U&L&H7c9Xoi z^4?I^^s{xVGbF*$*GC(-JmcDdx?e8{#);??e{%Pd2mE9znP(?tcXW>6?co1G%Dil< z@5Maz+@Z*;yN;eW_!4MxX&`#tBy6UqD(Y%++4b+2y>8VKR=@sr?{S`O)PBXa^x>mF z=^&8$Xe)JXiG4CM`sptr|DsE|Xj^*_ZY}FefDEm_xw1K<ZMcQNLc+W=Mk~V)`NutN zQRQwljBxgDZEPD<g8_BiUIpj*E0eKNCAW5$qpfmdQp4VE9yJot3PR)RE_)bp^}Kaw zeh!8u5z&7?lj(pU%#1i~v*x5Jk@vqn{cG1BmQr5naZZbp!J=W9RqY=*aw1wYG4KKG zhXq;6S^T^!)ibAW2R%cF-4x$+zP=~+Zu-C9jhSJ+8)k)pS6v&c)(Z#fPFbJroAXD< zEj@bvKoVoC-PWHU&1vUZ#2^g32qPF%63;0IMkCF*dJg{H@G#9MP)B1G2^w)ASEGL$ z{_YcUKw657T2_k#lZG<$gFjLCzpcy75?ke3@lXA;zG+3RR3zgLBw7%+;jCgmw?s9` zIcg|Wn=}gRN&TXlW`{84?P}Qr@uhM5SBu{N*e|rKMS&2BlR5cIt%6^G?!ox)RM6n& z>~uQ^dHX~V7Aws6?+XgS>vQZg>&N^w(#&E%CGu{f13FZ0P3%5*7k*9a8aLifHs573 zy#_{V3#*<r^BOh=J|5$fmHxXUIjEaFLXobN>W9D2AJu6ydWbScM@hV`T?daDL(}s$ zcPMzX&i5{!t+8<GvYKy(F!LxSnzuUC4%R6SW9LRE+CVI{;}LvZ(*k6nW>9<SM6$>I zLzy)<MhR+mL{s|Ffij1k&wkjt_Qwt_0c<e*dCZG>l{DG2d73Kpk-=WjrMaGH-Qz2e zW*$3pA?fV?aZ1zxzD|PIQ?2jvp!!n+Ox1K{WpJ(7N#kBjSwPpvhF=}h217@UU>0{J z%>HM;d<s@DP@ar^yQ2e?bB(5)xpzr^+RPxXhZc%2K6|!ian(<=6_4LM?c=#<`CYnR zL-=Eg+0yUVQ)qo19K#-%?dGWM%;F2!O@KKo9qxP~O?vw+w)`fKh>!aZlIwBm-npY; z)I(#U8S5v{$5o|{t<v3lQS=6}Rpx!O?BI#yC8?;+Bk5e&klXqF!M4Xbim|6q+oo$@ zzTJ>1tbS;)j}XgW>RXqG2v0tzT7F7-1(e%ELbS~J<5fy2S@BmoBaFn~*|(~imy~wp z%8PY^z09GX&Nf!*)AsNDaf~-SxG3mhBcDK%{t;RfeTRWg+no$`e1*H*c=jc|PSTPO zJs&EfnJe^4`TkmQvjuzsbnwyAWa#M!m!(WTp80^q{e0H%C!%|Peg3gj>j2JEliTIr zGgwxQeBo_m5#*cY`(Q*C34w?)-H$vUXw0BZ(~Q%5NsPs?Q!1&ssZnm^?I_-Bf?+1b z^-AcejwBvvthD?^u(YE7rNr;`w-qJX@6T?p19v16Lz#03cwvHm?BOqjki*|nJ&xR# z;E8RbA2$Y7-|}@Q5uwrBI2NLTMN_*wYIQl#gu_Ua6D88N^?LsK>+kQ;W^#Rr)X3$z zR&#pyle_i{CCw;COo)XfYcKmz>ABZ_NS#><9{)E>rgwjJWktH+Mki;M3tn(MZ?;-U zR3=7b(|x~|9SD4F3-Qie#<vMD&V}Ut9eqc#1J(~!6AoF@C+J;g7;F2k^%<sT5f?in zs3B22e%!MRrG}o;J8yYC&ixsyZzLtU?Pt7o8N$+;`pxOG#^qggZLzwovgYBEto6Cg zJ+=S5dsBIG_0O0Z5hJZW{*R3v&ti++-_Vj8O;xv!ii`-&cBF;lq46DEX&uFf&Z$Mp z<PUxOHmH#(hV-Sy{`TR|W;@Up8BrFnmh+4AH=9$WRYNqle6NsR+_v@CJFA^-uLdpY zTRwyiQi=e{J?cf4s1A_NygR-7AEhWPBp!<_!==qU@K7VGGjmqTh-=xEXidAV%8yLO z?;&n4kps@zkyer~9ug(OpN-0GYWxu<my(X%f`5=;vf{O4V~*ZfP#3|SO>U}F=5RXm z-<tv(cSCiWH|6L=+9(A`+P`yWAT?`$lMJ@Mo%bYP@s`GPN&Yx{=x%Brbi8lJKc3^c z`377zD!i;n^2^KWl;5S&YdSmY=$-;gvO?d->I=8zw**<<g>lyNnXs{IyUX`QwazA& zk_MRu&oJ|>=AiaQ^P)LfVn@zk!d@fz(-}f<eC6l>>-PL=%eVUXX@&o$ab%V(dsQ_Z z1QV*<C(ja8_kNlWVEw#$3#{vnID)%td~evn5%|2yVo~!%^iyW)C8#a_r9n2J<zxR( z%TN4sbztWn3qR!eeS&3QM^mNquZ52~pf>Vld_rNI`{hJ=lrY#L&Mw|yqG`ZFuSE1R zP3oxw$bQ~Io#}R2qwjCzcK&v1w<av)?(M6-NzP92KzSn5LEUHb-B@;`Ez*zmw0OEy zqq&`nMLmlUq}E+h%B$S<?DYu~fi~h3FJO6p^kV<Fm$$!btXoqr-+;j)ot#WT&Rzei zw?-r1+EakWwwgz(XDPf%;$-an?VQ^6^$SG^9IPwsy;esM=F?`aOVm^w7Ym%ae<JiN zx`kJY>X2T45-&hzgYtnkw5)s9mu5c{Hzs+NM82uc*y!6)<a-)t@(moSXN#f)TLy&{ zaeea5l!3ES>`WN_Ys0S>74`q^oxRs$7|W8Hfoq}i0#EN+xOp{=FwEh8Exi5bK*#fQ zNr|+6aq-0NIk$W=buWz|KaDH6e*S6UGlN!M@A@5-V#4{qQI=2nezd%4Kt^2nC35&P z;h$i)7d`BNI!xx-Pa4qn<{Lxk`b#<AgU_lOzAkV)=UoID6!Dr=s^gdBj6S}Umaj8X zRIdRyiw|8L1&QBQZg`>+qQrnMFFSwc{=rTc?0Sfmi*Z}?%JWZ7zpi^<kIKlMxNBpL zUIO>~7r)D&Et19mZCRSXR&J8#{T;k>rF$UPeUs7kObWu33rqddGjprrt-pMJM4XjS zs|fPFGNOVJ?td;g@atpmj@>>F24?EuEL4oR1Ua7LJPIQC@0jFG52@4FwbB9yck_f> z3&*BEKeTpIK}6|b%-}sL54&!@ZF|9-wrG_#T`bWK-?FpzI2cr)?el5zfs3^&8cge| z{))Zee9HQbrBSRfqc#3kxXQioC;p>t3UYkmBJ1N&-7Wr*)V}x~e)K+!u<&%{jeCoJ ze+mBD-4ASG;s0K}Z$EpsDd*N4{x|}-$Q57fM~NF={A%0WKg*SIfDKlkhtNEa-R2ln zRr~jEAilW$aGfY6s#+eZP&p^m`?2d|;o11cFK*|eY~UY&hmlqZWtGZxD4EoJ2<QHP zNBg7W)+3$u#<>TI7NE~|{&~&c9qcW+NC8@Za$WPPv@kTug6f9^Ho2>9EA#LZ5DP?J z;Zf~tPmz?+5bWUK;<Ml*-*(IYa@Eq8{QckFu}1??Ap*R|mxusH?q+}9!^B9_Vcai+ zKDz-rM)q99;?|oQ#NXfK%#6KxrMAN#c3r5W#Uk(xWCv8wfA^|GCzXcC?QH%|(R@u! zgEp(`fK{wy>n&BKq8hicqWrb`@?+IjWBPpYZ#8m*<SlMutFhz{SJQ)94irC(5mvyU zI|Y1sS97QBZ}Pobt-S2+SHH6#*j;Hm71a1`PNIU-#^{?|z_$Bk@O)`GrFS2G%zb4z zamqV;CsQ~$kIB;F?k`Snh(=CAp59x09o?qNr)O_nP$?FEvZG4XK=|_sj+NAo3Y7y% zD;K|^qXk>~mtElTwpRb%qWcEhm}8umQc3;BmCG|U%Be)dMfqcuR^3O0qZlTkP`l4) z`0!=_V2cLZ&mxba?CB{r^+<cr+$v~lVpp9zr}g@8&&9|fs9iB!_7&`m%d7I+U%USd zy?;1bvRDS|`C9u77rXxb6momkEFAO{j&{BYes%Em*#6B$-^LU>5RCyo(lg*!eD<BJ zzC|)uK-^WcNqDGjQSM%W>2mLzsQ#u33r!+T4UVQ>JdM2a=C9&6GcYs`*0fl1c;fZJ zrhraPzWlIkjNd@g_tV~gG`cBc;*J0RY-XuSsD;eKXt(mb9f#_ZG_#3eT$}*3aCz1~ zd|=a}wF}6D6~0s_8O62@$!cGwi_ROrs$?y4V5@cuh@9uoqSZg4tri~G-b5nR?@R_H z7<D8|-ySU&l+TG-JG1iwdW!ZL>74_2`bd~)Tc2TeKkh~8ffn2pa|aq*`c&lhAEc#g z#%=ZZA|*ffX-H_oi!j~a$B}J51+9*;^<`pl!Qpd%)fAm9gq&@awF4JT^Eg^bM9T9U z<LlaEM?vuI6|ZOh`QIKk1;=uqbD8x(vElvxILc;(P$dJFQ$;v9sr?T9dGSrEg+Y(f z`rEN>wI66jr>2g|{JPK+Pyd5xuH!_NRLp#-r-PC2-zv%Xxgnj-O=tqo`n>CjKLhVE z!e}k%g`ebv^z*8RZz?$-{)V|3Qo|32A>oT0UU%8WvqL$z7K(4~Ty5qK3z}f;7ygq8 zlkfk{`*ALB4)dXpmeqH`{y}-=L9-y7MFl0k$?>W`v(4|Jk(^<Z5v(aN?xg=?)z|CM zTn&ZG{-oxOjhHj1!mesOOuDhFwt8>t(a=Ut+1R<g&u{%{A6PEXVwZIn9s84eze6TL zm;S~n;x$nWrY6;k&^@~A@w0P1DtgtSj^(YgTV@uo28;Acv=6jS2UCC9HQ2Mo_sGQG z_p8z0?n$QM*PebtJt%wQ5+5Jc{B|1-o@l;QXC3!1wrZ^Wkn^j}<yJNH|9j+AAAb6E zP9feCQ`h(ZPFMx^u|JcBKBX`6{nQ)G!%Jo!2X@Rgqv#>#5<-dzb}_c5{p=!mx~N>N zSFhY9f5(tj^u58(Ga=<5siO1yJH{0<jFwb&snX!Di4@Imw{1hus5e&ai6$LEfJt0@ z=Dpqjef<GuP%1}eJ6liO^c{|CcxG#3b0W27>5exSx55*h3(36?t4pT7hG-;mo$|V? zzTV8sIuV_-vz;G4DMQXMF52!wE`C;_a86x;TxKLPHkV5u_1v`_@{7F_ARbUwAc+#` z0TW;BKDtmmRoYSXLl7T&T~_J+*0UAzMB2ihu=E;+LR!LJy0c?jJ~3zDnA}qY+}l;; zmCmo&GtzM?*`VgYn{malE%P&ZXZ4ZaMzyZmQ^QY)+qVr$=PSa$sA#RnUm410iLtAt z(R=rb9w!)!$02E98Xv%vZX<#lL_R~%96Y3z7HT|;$8E${eIdGvS!aV#W8@p$o!zzP za%|qWd+w7rZG~D@C6*6Ae-5;WgAt$!IgFNjhkW|}A6VZy?L&=W9Kpb|8$R(}-FqvI zIoc5GRy(KsB{p-Xz93YP&KTbwN?_`m9@uO*{GwKo$Qe%VUl>Ho*eS=yFKgep(b8Ld zAOwdJZ|QsMVGL{5*E!3}JY@0bm4j5H;c6+<K}^|UNG}x07vefcOYsKn^-j>e`)_`H zF_YM%GG&qYE{9Js0@hQ-rPM|5Jx^JWeuMZ$8uSMJQHZ(wFfhvSMNmA~^0Hh%8`K2% z$!nb*AK>S-%TI~9s>@||U%rGYkZMJV>0Ke@K3K@}`?B)!^FmZYn!#ZHJi~pB)_0O% z^>OiAE8!NYy71Bzv2@&E>(9KSb>%DXZ}jgl+PBs(tD!JqjePp+#)F%&ae~Ete00;M zp@G%ExR^gadbw#Rm>gFR1$xCPs<<@!SWe5K9F?pmUUwKmYFwN_R+Y?;ha}E=oOuL# ztu)&KQt+79_FkF!@E}n-&u<{LNlp|LcW<85$UD%qZF*pzL~3V(iNSRJC2Zeknb_m= zH2&RN`S2eCt9sbhvzZcm@62$B!e&BVcfEpJg~)wBhY&*QT41;zy@3sO27)rBGu0nB zSdncvR$Aducg-i_k)C?7NOTg5G@dtI?3Nuc!(<|A1;`nY6~MvQ?vNp6=EfSwsIT{l zMpD$ECRgsZaRh^fW<UI@z!ZC}H~nuz$7B0G&ZS_yGNGT>ylo`?z0l16Ao&-{BgHq^ ziEFDb6j6W02Yz64oZ51dtEnqn&x&iKVztIT@1X=~BgO0VwKM-z7X1t}#c63IUU<9D zl<{0&5M+J`31>TvWcH*z+z1;jir)HplEp1opstF6)oZxGz`qAJ5Bly6j;qojCA@O0 ztcRt4ot9v_gZ{914!Ikl9>$0PGWj}a<659!7nC>Vjfu5ipp|{!@#*iy7r(C_(L6K6 zhtVIitwy&4YFfwJ`xifXZCCyE;hwjPf+Uu<b<=NIREaQ1S(=$UKK=OP<xVF#ON5Ct z64^>H{8IL8R9&-D^U`T4<IW>1qE3Tfk?)i$E;i?1{HCoG4ZVvL4Akwftl;XDsIy~M zj+4x@PVdfiGxzU3BXcFl(92;|H7F7_1GDtm_)+#(w$SwrG^~R7cIB;rIrQb9Yby0G zj{MS=A-uYg*HINCWp`@q*#YLUx}5#C+=H`bvCmd-55?OyNDsUZatu%XQ^Y*s&pOX8 z7}#lH`C6eyuwx6!h1}$km+2{93g8HMpu4i&I-K$_$U8{I*9l<mZ*Bj^oQ+kQFWcI0 zwJYP@uc^{aUw2=S_IXhstIuDenJWfNvacH+NN0p!HArlO_aMK&`4s<S1o{46qnpJQ z`_JyP(@1coF2z6OcEm>#bTPuJ=$DaKzm~UJ1G?T1nEvwjS0)(o)=rJ5!FZrcmGJ9d zWtM{L-;3o}O>H00!$TU+s==LmMpM@Yzpwr+xbG@uii=i!q@4Tlsg*0Q45lLXe-{_C zY2bK&L___$mW(@g7=UV9+iS_sUOy>5dFe@idqpobP%v8l{-*m~)V*hRVWa~shaNA^ zayP+qnv=n~!Yek3rZu6~p!rMv%dSl4K*ZPK%B==-bvq}{!ufq+?_RgAzg5%?%TmSA zzrLZ;e_N|4<zBgdW9%7mr{|^Xl0X&oov-z>9opx1JFK6}+4YSpx(NTf%I@nQgOA&- zd}dx6DGtLZQ3X9OXdZd>L;J<5Se0*bi|?AJ4AlST4<9xt93Qj0-+Y$OnB9o!s}{MK z_+~}uj=jp|BN7fdj#r-C{X47bmEY}mffMn8)vBM!M^C8SdMc;3vcyBnaW)jrs5mT{ z7Re8!Km5fk^3kcY`QFBVYhB+6=d>C;nEz3Q{?Qck+GalRG?A_8rqwSf8t_&L2yHGn zz_4fDXg`$>Q60d}3}PO{88GH&3LcmboOh^`ed{7Sva^OWX&$zA^AF3yi>T6?kt^Rn z^sJ8W!CD~B9VPR@X=b?k&x_|l*})sjPouZ>>8XO4zaHy;*i-bIv`o9&k!9{to+ERg zD+!^7Jt2i%C%r$LQM(+J{ma_-E3T4sB};Xi^gh@kYWaP*J8ICpX@17b7T=WRd;LPj z@k$#reVc+b(}@Sm_@zmM8~Z<1meH)-nK|69h18LQ&8^(e1bD&VJi*NdOZV>Ghn(&< zIP~M!eECkcwjZ0Xh#7NQGx;GL!`$^1hEC0?DPFdpPv8@;7SUvhsoc^?4Dm1C)FJP# zpBFSsIE!mKOt9nVWnXj3jT$56&_B%0oDuAL1)I?JgFVseW;gzA)jBPU)P;nPN4|H} z5qiJxGw~d@xBd^}5E3Q%2_fXVtVQ3RFRD+q-LvCg!P-9>zTB#7u@|gmR?{35(n|bB zvjZi*0e4zhexLtXBi+}y|0fJ(_0}l<mi)H_nY2c&FaJTV?0S3SkL)@x%~dKloy!W6 ziK`BAx!4v0KXK+A=H*}ie)8X!U>L6Tx!ij_L4Px1=Bop#<L;X9iO!Y*?_Gk@bm9Dd zY<i}DwPOYr&5?wEaZ^SufMOP1=^NVyFq_{5w<n#aCiRlHX+!~F44o|E6g$WX`tdt} z6nc7}HmsX<QySyMxcN-&jt1!ta?9dWWV?<Il?hn1MyrdI*k}J2uk<oj569N>X;Iv! zLj7c>9SE833-KZ41qTO2x+WQ?K{nhF<|L+7=3+w|MwcT+(In^%)hl72zLaYWy!ZYU zEnrXyZh6Wfes=m2MNeIM6)Sp_2Ftjgj})Q<6rKcyC4zh3c}A@ZmeU3XwV7o^f&$q? zrwrx$>g4ZB3Jk-9J0jxLy?#Jpd+xCd?#@)V@CZ1|f)!mGr~SXSHd|v)Eeb_)^6n9x z`s}O_-ToowQQmBb)fGJPJ%k_{0N%;NhC4R8OO14)=6j5J4HnF;^dXYdH;R<FNW1~s zpP+rc;I!{3hd-Z<QgJdOwMjhKsv05Y0I|Elb+S|Oaveq2O0q85sF(~lWw}PEImIXd zG6iy!dMMyJBqU+`lpdej>lvyzHg{e%9hlsW2XcEN67-F!{tFu}(mpG&?%VLI)>A2k zn%4_p+|_87jAq@uvFlbtlY;n@#WhtghPyLi8z7>l954>Q*{W-KADXWU>bS0RZMBL* zbfNKcqmzUzEuX|b<p$2-o(!?2i&Ro=GpffyT8N@0QND4VY6{Vzh&Yf<h;u%%uoh7u z*{_FH)!KSwx&(<cChihGX^qbuqS8ZU3`eZI-bup!e{_gBTkjznxOJn@C@*Y2gK3Un ziuJ|gH>P8j?BUKUz?5Be_3Y#FC=E=|=p8a0=c%$Pn%XLPH_P8+zwV3#BRu9y{~}`$ zvN4Y5@235m5wQ<W>sL{qFm%vZ7_1N%u2VQ_YJIQqzfhFKx|}TZ8@FHjP4Xf07KV7N z$f+Ic6@_%A<&BfwF8}f|ZYj3`y2|r1FhaiAY<XK6Iuvf{xA-J}@=7OI=;Jd#cg0QL z5US^Wm@jJj@EUQ8!B>!xfbD(R1@_Q(iy0b5BT3@)YBjU-ylPdsOYaR3T;N&$58~hC z#1$7e-I4`1UpT<LBv+&l!TZ+T?__fi0vQ+z$ojql+4o?xr-B$*IF{XQ6{XcX$UX@v z5a>73;$p)(S3Q5-Z@xh0c*r|Gz{10LPPy0D+Nb*W;JNBakMn*nw+;%cWP~+O&4A$m zcev`d5pk|h+C7K)G=Bo;9Z2;Eu<jhI9TjSXZzwvdCgMZz*_NQCuJg<X4ibk}bOs5t z{g<;`6Nl2f5L@oYlfsa=HdiW%ndca-aeF-?@xE~~2Wi;_gARX?Z5~g-!`G**J7NCX zaXmj9n)HJe5YD{<u%m|DXe&-dV3!3$T~hkgdPoW^`x4$f{-PdRi1pb=7~&^8O;v^T zA7%JaH+~I1y(sbRv~uSOwsobfqF`a_JGAF_+1jnfr(7pf%+%{6U_bTF{DmqP^#2E8 zTuQpHn$;SOmIa7+!Tj^weU>pEQP9Z$Aispsk|zovWq9YNb%C<7rnJ97igx%6cd>YN z_Ox0}s}cN!1g)n^;n~Q_kIw^b*$_W=c!|d@I}E)ni`|mNH(b9}N~&gKMLc$wM-Zax zlv58yv52f#xPKwbr7<U{zDqhekx8P#oidXrT<lIPjb6k4)Uz9w7Ha#?qvU;!bDK2u zAr^GP2hrMT9~^C{WWYGhP7E?41qfN}X1!vM`bZ`()BhR|Nyvi@(DwZph<7{ghqmzR zQ-&n}Mac9>=N_dh057uppfCtGRSlL)>X9qiYiBFe-}!a<tEh%Fy%`s41v^D=HXQ|D z=20{0MfmT_faIlFtsKd#YhQPsSc^aWsg0}QkJLgR5yL<lsHdD!Y)KMt#C!a5%ZCG{ z=Do3v_cB+~%UAnQv0f*9fwOmgTf8iYoLF=BNPA)nS8Gh}PNWRf8}6&!pElh*)xP{* z;mlu~2q+R+*nYr0pqQhLpjiOK+hXr3D$bah+sG7mhxQ|_rlSTd{MKDJIq@Qng&CR7 zR+ch(Z+B{DN&@D~w$Yycui@-Kw*{(y6W{{_Kfg^tN|!^_|L@topQ@%=aIxPD?%wMH ztx+lnZ+CHK`@PpvvR43Eh%rhVVa!gm{@>92zSkCReAEQQB2@selwMuvvpb$;!PzA7 zwB9i3m9#(pO?bgj`#yQO5%c&w@4~~1-(gx^;ahbsQvX5fx|T-g67HEH$3yHstS6j5 zHOSMDdN)swabeLj_t<%El27|+wEu*+_in`L*}QH?B5Ynh73d(_bY5TU+~LDU#f@O+ z-1a!WRLrVK?*|#WuPnLjgZY+5keVqfDeptot_+SuD|wdCqP(1D*mvy5pHq|e+xiga z*$lPE1Y=9`9LALhjop2_*?o!ZN7Fx`NXbVwzbzTx)<3bAp*zSRbzRDrd3by;(^<n0 zK!v;R9S`JwRD;%`NBO!CpElVj4tLegogS1~<60L@2-o$>bIL8buf%IKz6We6Jf!4k z^*Tq2+BV79V+W_%qkl>zL|hhIDxhmXi%-c?@Afp`R54q<zlaei(7KdlgdJZ<UvrVV zaiyacHuzLxl~aHn+A(f+A{_kus=SXw3iEMB*AeC+a2VJLuenV>>&@V)zSj(XEWe`} z0^|O1Xw`$1&Ou=$RYnhX)iY=wd%3`E2*DT+w^QdWV!t4<>lWc$b~p2>O%8{<$!%(| zHN%cG=<x*kT{1$X_Zz}3M5VfwJIA1hZIzT(atV&K+)M(YA!KZai7j~n?6C@=vh&5c zp%&`!?tE!VN6l~@OO>OZ!}oanI-PmSp+%AG&#RXE)@f_E;8zB8tg~&WJLqFG3_xf& z4IEt&6xm5jl=De%??<)D{Uo&J!1k_UBr>3e0^&~$9emXZM{Xd<?rOhpzIA}aEym9Q zc6yzL8@K?2fj7w`r^EZ7L{cB%CXN3eR;o)8Egf>IN6kA=th@VynJR4D6Ew8o)W5Z2 zx9U7-D)SJTio}#bF=jg`^C8ss<MDF-IEj{97atC}wL8tqEd)C=<kw^+{u<7o9_r_y zW#MeHTg?CznzbS5PV)(c>(`F^{0@=#c#~Um&>mJS9cSS#+jr_-T{s*(*5p3*oOZ1) zwHtG3Qp;9#sYR-R&#SIJ@nF7|=4~TL{tu!Fc6y|-{|OB`LSmSq?M3U|ez$GmTJTLy z9?1RduJ$RlwUzrreP-Ax&Ld{QF}j)W6KB``=-oU#Av2BusGWVKMmr-nYiCYe9ty3$ z1hBs9F=tDEc~4j?KJGe8&$9w&DF%{#b*pnnnb6R%uCSSI)}K4?jf~xy&l5QdFo)EW z%N(5$5oz$FqIGhYltK_U!8>55^ucGJGyN??0aA$MIXh+U%KxA@^m=A!;u>^c+CHQU z9;cw^M21o~<vpcBt#Xu~7CMh`=fyxgk437YNPUU4UgLJ~JEcKc#<)PlyYwkrD=*~* z5oicGyPL6sL<%qh#~m6$90A2vne56ChD;@PXQ{z`PHsymVLi1h7!y7OqX7>*q5F~1 zxFHUhdRbufU_^v=PG5e4hIillROd5bi->B)ud(2Y*%pePDe8?$Y3dg<5<zOsRXk<4 zQ?hs;ikFQe&4^Cu*K|}IB;1YrNOvEUqA2-opB3V9Z5xV(x~&cZT4CdC3|P;nQ!wdM zy}t%bd-|jZ70v*~+?^_*SiY;4atajL`}LuVKiE~Th17y>S*w4u<(!6}an-_T%w7go z-kfQ^K!hSKlUR$jt)H2-`?C`lh1aKJK<`oEX)G^$3!)fA{{ARz)z!hZ2d~&v&XUE% z+Xcq;OwBmKBHT<=Ok|B@_kkm}{j=X}6vx`(s9$Xqt?%c(Pw%nHAD|$1EWxj|S{M?} z2O;mRcOrI3`vn&oev`kv)iLDjY}4d5dfpAT)m?(+fJ8+rMYY`YFbT3_XQg7MqUXlK zahiixkoh)Tz4xI{U9SKKwBj)lg#$Lz%@%db060vO?T#{->b^aoEM<|*>5NN3wq5bs zF?+pUiOeYGRfCmG<EZ3SwT2*BT=e}9mv@wBopxbN8H-tAkVT9nVeF)*ezar6jP!lu z`-(vQed*8VL|GdX6R3PXmHZ<uQzYu?>84KD6cJkm=^R*7Q`MnEDXmUe%pEp}(KJ`4 znNp(At#d6KpYL(3K7C>~Me3U?kma$hXY$5LtymUIah0zA4R#pPZHz$$9Wd=ue9JiZ z53H{D7cP8o9<6ukRJrNUIH21#!iyiSDELrpr~f|*Iu8m*%sOt7I_-I0dS<Y;D|pkj zn3&!?L)&Oz)#uanw63+Fba};7V)0?f$BBm-j1{ivBsBgsEbonR-~37eF(R=K!jA!e zQ@SG}#;+$C*g$<;YPG7pz}a2TfQpckI<q|&5aQJ!zwFl)r}x;Vc-b@W30D~cr7Eb* zn)VU+0VivYImHL%E}Vd2PpJm(PK(J4$WHopr9XZO<9(79t_)QT94{BG-dW^UX<#^w zEJpYSSYI|-Tb#5VtJ6k$wWm<A?DWJ*^LP))STBRN9rgWj9||P+HlW?v6Q2Im1)JI7 zOixmmdhH7cv2G<H{QeF+u|VPC!*c6!KP(Kr>o+C4j`8Fnzu&S05+BShp<=)i1UVu$ zSd>f&m$fk2-8rGgKX&uf-iRlSQ%||s?v(myniSn8+UQwiTU?~W%VAbS;8MVO6}G4z z#$}6(q#*J}1*jRZ<;{(r@^^_p?F*zsuv)!`*cdjb|B^Q!7ZdstPx3m>B4lxrndA5E zKG8Gzv^(?4T{{EYI%o(0fWs7=GYcl71T3r&P(${-2L*yO2Xs<;E2%q4`N}!luj@5J zI2f8P$LR?|R4s#f@UmWc2o)|LTaMVb^HqifJBu%w%c0EFWen;d`OE5W^EbB>;p^)8 zA}9Ul^}!h3fwRKIJ|s(40Rq)dyp5d^Z@48_%R9wYw94pBMx)IY{OA*@0bA?ZTNQk< zkU5gW+F`upoBac$s{`VAI8-tI&C;C6p3{0Hy`Pr3)Yl(E+#Eu@rD$z_b8nq(Vdj=d z=j`Ntsu82#_(ZTNLwX&>{KP)`#3Lfay&8*REMvBPi3+>84~o}NDscJ|t(Wx*;{1up z&X3vcwB98InGyE7+mSA-K<MW<0;Z)9Vhdfb4#$k3?bv{p&6L^~43B`|%VVH)NtL<# zZ?Ii8T1f3#4!B_8i-kLzTa6OfV`A2W#JfT&jRL(_5K+KU#Y2Hzp5j(L^Z{Xw##*i@ z4=HUrOQ(QF*Oo$=U1NWPf=8W+@61}ftdSIhmW+LG@HD+nBlc4Y_e8`-cX_+K$vdj> zD+OtdgWX?qA>Tlk*oWXiTY)5+bvb#0{s!i=A!J-i`)%&cH`OVcv31Tbn%3NnmukpX zTVqLFiD{qz#|zin#^udf+FLE4EJs=iP)2MBl&G+NK`SEE0#P#qK4V55@t3ed`iG4r zd+xY(GoFZwSI=QT-MGw0zyrIaOk(>X6z((i038?dORe4a8jMqOD4}vf0!u{e{m5td zJ~&D}LI9fopLU)Kd(5TCpL^4X6rE~T*gi+T+}%roc4A?J8*aa-nNnm)qIHEXDWO(l zcZ(IDOm^+V-qe`q_+!~1yM?rf*bwv$<o3qqYbL6q!dJm@p)6}Umq(%(VqecZHD5@k z5ikKj1tbI}y00KhKN#+I17mg-2H>&F7awx5?OL$^4~UjME}D@R({{kB4&lZsXr{Cy z8(p={1NOd&okqqWDG!;R-f!D#I>U_51@YT!yRurOOu<FdX~?gb=MI?e?nky~kOU(h z(aIMTa-l*=YPy<h(ku8FvP9YZh6bxy3(JFS0LwC4OQxfQC&B-$DWXVU2}@JN2_Xwa zd3(N+T~LUgX$_*Et3KMze0E!U*QPbk2H)feoA~GEBxz=nfXIY&DJNDN^r$X-`;KJ) zbz`VSwP+!uGO@i?78FN>Bsj`xYDcvl0M9UrsDzDTsDh87M=2Z+wh5QbBfE3iPe4BO zMsNm<gye_|72?`8{QJWNBBH!aa(X%~Y|c*ORS?(4z7<b!^aSx(gh`!!LEF(Rm&lck zn=I+Uj3tIr%&M5+=!I}VuJ8&m!|r+3nw<8j^$6u4K|Ib9(T@h0DNQ!SmXz3PU3BCJ zafgOKKCw^-_U&xgRH}=dOg1{&(goNsg0XDbQ+z6H(v(+dCi7|#3yH()J$aSXbla{F zLQqh)lKs)9(^QQv$%h`HvDp*0vRLbx)M&SS1t}_NDi83`ngV&Eg?;mk)6r_Us)F;n zdS=&!5a|%vxOuW0%70=KE1<;{L+yt72y>ucmowipOu!U6Mh9nxw;K1P`r_VF<KVz6 zq1uulsLY*b&mWcyEpO2*fJFec&}q>H!K#9xXjygj371)g>u(op#Q;@KJ=-hLYQmy> zHzSIE9PlzyxtJAd0$-P8{)+Ha-}eAeKKB3P=sf(AdjB>KqGD#?EKD4w<!U&}aIbP@ z?$IzuST<a!IdFix3~@IRDRY;jrDhgpfur1|<wDWO+=?6hKKJkW2k>}a=bZa9uIqil zNLx-i#`kKNw!nvW>o<wI@tHT8>J!f^8_kjXbPALw(q!e(1UoIhGDG;-;7PI8j_)M{ z1rM?PXu?XlQ@HO_?xdwXNOG`f&_d{kqgekVi8)-iUfxJj9ZrG|Z1!FK=>3pCdefQw zt->foSNgA^YUom8CT00CBvVARBq4f}UEA{@p&n(h2IMOCNAu_tf+!BS{1S)`8&-+o z6ik`y&iv5eM})uC+;QLC56W$o0l~4>sYJkDQc~dHT4oFzYetBQO>OavT@xUY_2%B7 zYw|isP<UuP6RABAEteGSY*umGF%!>GLfX@4@G=7y`}!ErdOFE|HP5tGq_Kn}oFI@g zc8~}8PiBHvq=6s6>e7r&O?FMb;?=jns%#zO8`k1J>^Cc~S1yj^Bw9r>OYC1l)FHbM zV@#QZ4x(u@LYfShM#&}i<iux(+-p!acpNHQghuT4)d2q(NH&C>`c_t(uxpmNAz6qy z#5Wt{XrcLMPov;jzk-`Vpgl0+oB(5=2f6kQU3d;p;8<{^d_*z6rxf~`L?j@F2rFgq zp`+w2%b*UT+@s+oQD&7~o_OVq8hcNRVO^P!gBcM;ZmgNLu=2nvqk!-N+)W4wc0se3 zi;2PTc5<R2KnW1x4w}@y#*j<Gn#nXcXWf2bMfQ`h&PuCdMl-BPdv_}9xQXGOvmKT) zv2c%AfP_34^6>+9P_Az*_o}~l)wpUqF_^Zzz9aelxv!|8-s*f05wee{xzt++CTvCp zHcsa$@u_Iex)q2KQmfRYpt-XEEP|D>LkKbKG}HVrLxM>2#Hmf^Iv7>shLC@tVqy<b za+78dPt=Fnm_zfElBcsZZtU7fjBi1qrmUn)u6pj1?sQOrZUqw}Lnfe1GviK4AMFQ* z+P$@t)0T%?l_!J+^??H+B4*OEM1E}Egs;2?YQ>g!1LnM&IDT4Sl0@%2Rm4!XE((Gr z-;fE?+Cz)a8X_%%_#G(=2-B7_v56STSN+E~u?mauj}4tYr|Trl;sBi;Degp%4x%*9 zlOvz{30&s!BNi5Pg!NpkVc9zDopu*>1#SMvmZUbBf+XCGY=No4PN9HMX*&$ud$7C8 zZ*UUF5%JK@Kw}#qYFdIDaEnkdG<L991<Dtvtjo}}khaO88wzzga!VFl0wvi`XH8W0 z_2wkYz6OSVg}Mz59d->zQvLX&<yWN)%^B70YK_QkJts=Q?9!?{$OGlTg6UjYO>+?t zM)MbZ11Dli{6Go>DXTBE18(>65p9<aHdLY&g~sv`rA>@OheCU(`Xr8A!b2(dcxvMo znC5*?S!I_5wLKeLuC#(vjS4qhzD9!b%u`iElX83KGG>h?w6KdQV+Tja8mrm49D~T3 zq8K;rq?&{gdSFfz?^5qiC8Qc`VK;lCp=!15y-E>qX+_#oFIZOZGhh!@5EUj<aMPnp z#j~y$=S)pt()^TXg4ok&#-`E7i!K*LWqj|jU!oT;lPZCeHt)a%DgGo99!rT;;rof6 z%&aQD(Ve}~1g2CqrF4~g4?cVVaCVkFy*_Z_5lp^hi3Y!_>oUcZ@1Jt=c{jTw2kbwt z&4-=UsTH+Zu0cK5y^l&{y$Rg<kk)qX&TvW)_wc(UpO$}k?C%esF257|*WE^sx{K<V z<P6H2UjCT&5_g@sp2(V;+4uI!`ujuoPdwPUcvzBM9IFm9@BS!v#L|w6PN;0Ooc6l^ z=?%}*v#8vc6A9VIevf++qjg-0(p@|3YWzgP>oMUiUk!D80G)Gq-1t|=tttWD`G@0# z#N*~;e<R-L*M<)zE$Ei*K5}Pw!7z8@Q!3ie(7N2MXJ*&_<vJgGpZH!`wcokFArtJ6 z+AFdZ-1pJ)0-E&>E-6Qdti51MYrfuR`}Gb=CMy`^`xWb9`SOay{S|kmGZl-CC<MJL zPp`?y8^m^ZX!gQ4U4?p+M{HBJ@@tkw>%fD#QvQ6+KJ3r$eb6Y*>o{5CqJypPP)~Ka zbeOIpI%0a=MLyi}4Ag3OZ7&Zj%^<~AS$UEPOCc6Lh2$T{`kbDajp0i>^bmz5j%N?| zyLoGr3-VD|oEk7g?xqAA`4ffY>R`Q6<=PVI72+}FA@(u&44j>CL<OM#4)Ws(DXPh4 zvpx;M-f?HPUSJdlr_8N9D!Y?9Vh0eKowBiN^la<rr<GRHBLwC!I~T@Fn-65Y;<PtI z6PI|6TJ=n$x-vf_59JQ&*1?_CC=e4Xt9}x7)pd}v)cmY`6WXh|;UKt4d~^>kqNPKP z0*Aq|+z+3N9&4g@ztsvEOkFAsaBuZ)di6Znts`>2^XY1tZDM4)y*m&Cu~soJ==Z`9 ziw!Z)Gff?{@{AH62iEHiv6Kcxs~}`;Cgz_Zrf3LpDasst2}%e%Z!Hh1G;2M8!Aoox zDM))CI|W|`i6$Oe#|O8s`d=UTNT3%`5x|uWq-FiIZq2&;AEX%DD~o)q+<_CDY+G)C z$UmJ=8~XNocePnLEM=>;H>am^aO0kImhNsaQv*42Meeodd9M)G?&{P>M$NRBVjnD| zUcG3ZM73^W(Qe+S@BcCJ%Y_J9%+GJe>XsChJ(kLqTi+1WDVY9#>CUP95dxE+?u7o0 zdpQ2!hO29bBo>2Wz(F6>Ra2zYtsV8@th~yF6bN|RmntHT&DmI|(53xx8TP$tX(O8A znx9{bEcf1|ng)3V>$&RA`JRmu*5Wlp$+oaR5o{ojTTTQiIm~W^;7Ac%*_yLjd+!$B zQ3z#Rnp-mRp~mW#FSc|mW4ulVYZ%`NLx+tQk|(mQyc=|KI_<a$8om&l*2yF$3ShZc z3{|t91$k-sioL=9Q6Lwza4Syj{dzTG;K0!6;a#qfFk{Zb_<aqlJ*~=c>b+TJ(amqn zXH^Tgm5qE*?Q$*%f<fO*Td5+tg2>9mH0iF$QNs8h^WQ+MIEA)*`$}vJc&0F{e|$TQ zVh3XW+52oq3!Av~COx}cpd%frCW!pBj=MB^HLTtvLGQkTH`UnuujbF!R};=gnf`jO zq@d!7T<<pzJo8OnJs`)RA}q)b&z+q%5o?QS560>mesrc#KakZh17?*uH9n*O1r51} zK~ooTYDWS@h<l#Pj)q}tCuc82IJ`Dj&YmV(n4(%|<L6W$wO4hrZwE&lHbv2AJ&q@^ zT^0rC7<dkO0`@gxZSU-!I<nZ?=m6M#wEG^``jf4=DG%}H38O^#!Fu(o;HhUb8Qt;& zZ`318+#KopyJS<pXS97XKWUi})>M;S&*_KreKI0kS*IfR-URgJ@aqvNvS#or1n&NA z{vYi0Yd5r)1JpAdJGmzpA9jux*vIdP>mR?<@gHQNt>Qn(xnskq%>&^+8FudS>5)}U z2Wrm-W7Nt8jei4vbF}*xh3{KOFApAv`YOWvJKc=!;M1PR7jBxaUMP^!xN;TN^)jlH zRWsB*Wi0M4KhT}{`9*o;zvo~A9>bQR4^3QZtNZ&L*hi&Cd8h4<hUK&80Peqzwe$A# z<x}m)=AP-WZnLnPKdO>)<5FS{`SWCYZM~Lf)g&^;X90M=dFu@F__zdgNvts=(0A-p zrqq`1LX<gA`c=B+(A`C{k<a(IlRMqswO{UT?;Wz)CB4-#6qk42i<HXKiOgZdl$>8) zs<PYo8mqmK{vTvK*UVm}&E!AGjpfH1pzANcy?YP>&G`B8-uhX!uVW_^#D#|Y3m#zT z{|}wt-Eb;StK<QT@ud8-b5?(u;-*{BtbS*FoZOdtE!F9F<?aa+jrR|%cM-;u8eo%$ zF@w|sRq(ZS^O{xb`V`ND<3vH2-=YETKM2n40COjC!(B&Wy?Wz;*O=cooh@mLpIitf zl&Bxw52UAWvJUxsq32|Abbe&d$4764V&1~w3W;7?aXo<z0a`=6FJVovfLK}C?g^K5 z`^Qp`4LfMOPpTaKgeA@Gp|tLJSaY5DDJsPqz`TqO!L&6F=m5HC0jGAU!mZy7W7OH9 z$C0K7e(Gs-3ATEBa8GLbz@bxNiUUae<I!s~0rVZwMg*W+IA88m`+__W0bNTdQ(O>y z<87Yu8y2VxQ<81eocenE%OsW2QGl^F>R_ukp;=&q+I<0r9;7!b47cO^b+40kTB{Ym zK=<^C_3oLTzHEDLKbj@mtR6pvcfYOORvH!_m~!ZLXGbu;Aoup4s$cxKvLw>~3MrL# z_MXhT>2?FlpSdqH!W-oFO=b5GP8Ov{=q)BscLw9#uYhc(H%5f^rIvl+mUY1F^yA<u z5C1Xq%pyD)?vH(3dqk;SCT~}}x+<6X_WXIQ8A_I15)$7TWN&VJ_51Oe?$a5mZoyX2 zcp1FN8V3!#*tU58cs~wO5W20dZ+GTKo((qa9@Ut*8LN3YM(15d=&G)Z{Cf?3c2);G zQ1``mq<-EhYb7s0AX|BTNiXbU$denvY4;k6wd`x{Z3Y(+851^Z?^<ijdCf54B1;HD zL!Xd(vU$7Ef3Q%v#bS&xB+(1xdN$A1W!++`!^!%v!M?bIFD=HZAuy_?Co;%C?9XfV zLyS4^7z747^eg%V(~DM8#!36=Tccms@%U@cuWi5icW`Oo_I&S+8F(Nyp<<|7jE&o{ z;x>V}@A7gfSNJ;NPMA^3-K*CwH>0>9$*#e>^G_byTU@sZ#g^Nyc+s6C;i0be$o+<A zXcAg3zak|)3t^5W^9aY(3%iv`!{sS5KQ3M8mnbOlhTGdfUXBaR?)*C9wwSl|;gh@$ zA$1T|RpeK0`DP-J-sD-g87K8~oh-YG8&Z#XVek!MVFF=oZDEUWi`JY4K|}3rLWc^U zpV|Qdj1Y#+FSc{iS9GyCCEy`kT3N*Cp+eeAk*vEYjn;c`c+G6aa+*|i2t;Iv`T-n) zpNTprvi^feoXk&=scvEctO!qS?cTwy(;5n>>swG_blA(wf*rb!F<Hy%v2y_STdb~r zvEIFLZ}%JD#DvRWHlPB1FX`C2%S}I=JzDY!pZp@c{U8H+dFWX5Z6&<x1=>>KD4K~T zA@;#GgbSs9v{jT_L5#oPNqD(LxfJ4IfklH?@p+T+|32n7>i?Aa;)_#IyvELsuDSx} zRv@D$D@1aZymLmCNf1nh*u|kC#)W;?dQQO@(5c=*z@*ofX;=Bwz{YsnX#-?<&x^gw z8h_ae<TUp{_|w@z$yE_)*VhTVLlAQay>NyqpOvYt?|+b^!_&Tp?^P>5xgKbt^`u&p zl+_;(6yz1^!7=$??eAmkL&-ad2EyMG#;=+jxV`i)*+J6#IAN#pQc7@ge3B$~8C$&> z#vYU}x*_P>9kZM)8=4V>4^?44Y+vGpYxW86Lm-++!McA#6YXs4+ep-r|BbO%+_IJ8 zuWY!2ZZA04G6uh`%0Oah%pnh?9bUeT@-(6n>^&uzoB|t)Hvjd{QBPVnTxQqc)B^jP z-*(MDC+{hCev|P4EF=a8xs?RLo-sx^E8A)!z+guKNCFxI!G|{TS1~j+<3W5To?sKO z#N?#J3GXTCCjJ$g8X;<44btE>E}3kGe?Nb>Xesqk;{Acf#e#*3u1itxdQOz<s0{6z z%KH5(bJ7gygxd_Gfhfjz7hAIHSob@kK==H^Lf_PggOb739SgA!RDFU|l#{jbMtq_g zs{Tz;P}1E^7Di(MqQHc|eDs=k^V}!?#pJ24Ksq{d&|^Xb0iSa6XbXNJW9UFG%-U8f z-Bm3{@=39${jZB2?G5DA=3g7K`D}Xq?r#mtm~g4QhzR6rQtzM$Q!!{TJxNEy0&eU4 z^iwm08NQ$qyNS>jrq%43{Bz)5%z&rhImq?A==eA9972%8!X^x4@9)YF0a~x-TrPjo zU^>UQcFI;5njA2nNcPm8rf|sWwl5qGSfA&$;WA9gM$}xW+3z27qRHMLFMzQf?d$b> zj@ACUBU-?$v#sj$D@bjKK3FL7V$8lBSi7rUdOh%Ge@jJYj|>|c=egMWx+C5_DU2O7 z54K#W8te1~{n0cbX6cMhltan&{~-4tHW^0lL``{|?6GZ<SSQZ@jWo8)s}cC|1xFWU zx22o3OyUNpT9zezr8%@8M?LLFzm%*!*Rg{K=5^>&Piv~k#5rm5FcW{?Uq0?Eu6Su! zlknah;w=(lU*z8RCQIPM1GkxAx_8Znsj^}TAR2^Zw=~^-L=OZShhYdB_uU2g{`B?g zw(vxz=_obf#ibx$-!n=pfL_y;_}CYsp{c=%^o(@X<zQZX7uds?;71LVPlQixx+P_2 z#$)#o3#AP$$2!NHl%golR@_-@tFtc0b{{F;t8k}|KiDdWS!>rPo%1ElSMJ8=9oPZ@ zkY4e!+VM&CcFg{T7Doo=-?BT})>dw&IXA>-sCnUq_@%q@!bwy|K{%`*GO?|)Uz`1S zP9|^5Ae$4SDr{%P<yLkLUCjrvRnm~lGz8CG_YUzl4P=k^%hip)p_#S58!?r0@q22- z5=&$@DxN0%*FQP?;n!tr7u^XtT@>re+kX7m0Vu*+0oe$aD?eSIJ;=do90A^Y-12e% zRkqaAw>;K|nCAhlOv7bQ%C|D!p?kO!7s6!Nt}Po0ehY>fC1aQNwgxvP;o|1MAAw&9 z)~6aJ;TL;e?fY)a9|%y7#%AhQzMTboamZHc_xvvmEuB&}IQXStCui@wIv-_V7@`r1 zlL|Wq?l;Dg;cm^)`y_RCK?AQMtJdVuX*KH*h#Wg>c76X$jP_1yrFtGh7BO5d93)3$ z8^rg%^*MAk*yv&J`FE59O)h6P?#_G6v`Ug}pXS-^6OKhX>F&68{cTXH7FS^!96k%C zfjh3>8$!OV|Ef!wrgsJv;r2_7jA*sBukFkUF~)lN5f7PCTJHwa)4OpAfN!>e>!H}q zR`69KZEs7njqTKQ(QmR&kQ%IwZ`(y;=(4G{<8QR(%3bxf_o4#B*@HEP0%wrl4|q(l zb?IooAlQP`k+hoo12I((1NbL`F`I}LShL(XU=#VSwCo&TcnUpnqoyTJf)d&(&F(Kb zIT@$y`g?JyGvEVdsSyJ@<JY~v8(o7PTiL=^@TZ=Jx>ZN}BW!%pn5?w>9YT<3JhH8_ z;0rwQR;5i~dibQ&9hjnG^-f-s&DeQOIwu?-KVvNS_Ah=0eoX4!omKVVkh=NxG}hsC zQ{SAN#Qz}Bs=(CGQ7dtZPkUSw7_URgQmG5%Va>F-x(cO+?kD;d-*h5nH)g>uuzUB( zkA2da`3?5)UDGp!BIEO+`;&&3p$V>$Xe_)~hqF|)N}QN^otj1b4`Q|Tfi-cvGRGpg zC&~Oxt^s%YuVKZbw`nJ-ChcFMAY@|I&A)Fh{|C8g=^azI;I+FuHd&SYXvOPu>*W3O z0n1r|<7Ra1k#)Lp8n>z*?W->EyZEGnIC7G#K4zbkB$MD33R%=XwRI#I&Ju`idyYB~ z+5uQY6?6vAGFF50be>m+93Er{sEa^=%fWdUU5>WQtyH9WHr8w++tM3}ohOoN9j9!U zZMq;W+H{T*D5>TX!h&=r{?#f(>F_Lv!1j6O4DNR<<#F;ix9)@(hFW8Fto^H%ZS~%m zv$62hFqN63aqd1fn*Gx|ggp17q~c&XwI7JGGVA@z;(P9`yC12<nu0}&VO@pFKK~~j z){3%a4u^HvgH-&_e}{EcD-^LXkrJ{lJ7dzVbMwP0I;?0*W6o%;9cV-ix|N&`yJXYF zFHuBP*vh>pujqR1Und{m6B$0fo+}}_G!BV>V1U3QU&bI~%b5qiN2#eaG#EE8>u9%5 zW!T%_T+JZK9eVKPqhf$y=Z)9Z4yobcssFyP*vci<okcNVul`-}vbB)@!FxBZ$=^1G z1j9GJhIOaseJkEXWn;9e{ZVTPaOEmmX;qL@+qYC1T?V_`8YZ87Sre6MH36|W1#24a zsh71N)Q%o~CZIu)_^Xovykqp2ev%}S8J!9aX@WcDnK)J<G@Lxq&8r*?(fv)s(Wd}2 z`g)E>vp=6dYRG*qV79;bR`;7NzjQOS`pi`nNWqbo%eB2eYCn2EM)30lgf0fOroFW{ zw>nu>N&i8{_ATU675fxbV=MR>_~*OVEGxnOPi?~;<Vy}R<dk0Z9(K5rU>+KJP~7G7 z2P}W^d6xT#-tfPQ!}&Kg`K`)oB2gJMo}pnys@TZ|+1wvli8$qlS2I~Df!e?DTyD8^ zJ8MOuGPb67z_sx0t6g;2PMB=@2S*kEj3?B_U_;|hn<jOkB=fza$7?oH`xf9mMLGWA zFP3!pJ^q7?8vmq<7E)A3DH*0|6TC~MFYiBIV6GLj|LWz~A|LM@jm#^`8_`ZUc%A-N zkj*gM>TijD{;5wcV8CGrMomqKV#`)^@uDiN%WfK-4ivf|Yo++<%<5{TUdwG^YlQ&E z3_BVpZN5a#D~x)j>%u{y6s_uy=0=#KU84B-ub|BMa@ps^u&TcpV=Dp7{b2=9jf?OG zR;Sap$ltCGP&MbdQcIoWx34Rvmkk6SkBpql!ot+2r#k(^zuxXip8R`yIIrV~)nM%_ z2%TLV#ocr-iacw(=QcV!LHt`#@X%Pn+ztq*;{42fQ)%#Y?Fm)GWR{3wzKn&9eOG<q zKlUbF>{?z#)YA;F?I+|t0iG98z53q|ilx@yR+rvzDd<)1dAEjoenDPbzZ#j?;uJYG zn08*^gPWM?noVN;Zm|wLyU{x`$MN!RyShdP^K9`0|Gq55QS-iJ{pgygJegCze%}g9 zudU5#Pv2P$4vu0j#-0C)PaJsS7wa}AbqqHdtf8|PwE=wE(vZ#mr1hKU-amMP!HhlF z;fuSuroP)b<izmFC+++Cbu^?5>%H2iTz(|)3+*&gV<;@Pf0aJ}doN2)!#CZUhfv@D zOQwS;;PfxKZVK#kZWo|Mn-?uFy}OFK!1h2yrXAu(w)AWBTfL6@bZkt{9ep*Dv%r_F zwE5c1rQmFWKWwtpW0Ox%z3iRKr3*d`MnDPB?KsEx)TJZl1Cwtq1Ud%msdP+2U`<T9 ze1OAmYpK0Yy@fnMRASbet|PQZ-iuK>W7qjmJj~+RTIdJU!!G#UktP)}lA7$-BAa}X z<zBBBmB*N*OmuR;y&OZxUaGp}sLTNl4n7zpMgOQOQx(sTf}=?gP%H%ruw$0vvyJlq zz3@(a8#O$=j!>H+GH<D}70_(nqP1vTI4@v$yC%kW@^m7KJ!wP<uOy5OmUXQ#Y*m+R zh`JmUf2?}hI?KVUZF}AL;Y6GiGv?Uvc7ElV=^*{$QC$3n+vw6{D)uMg+J%_(Yb_b? zYXgN=cFU+pt)2XwTbG3#_RL!#%nTkr`NYNU)2$<gKOTZY*R-m!a<!<L+Po1a_4VF5 zxkd7wWky5)LYd|i^XHTPT6osu%P)fA(&KgMg7T}8tFv~>WPKOHPI)*6HkZ~wQ#5=Z zYp90ylZi`|(ln|&_*99g&Fr~H6P@rggnmDz@E=4}{^H$-1rOdH-bZ1>WXs}J2wxCy z=C#R8a&h5cd=q=hX?Y0AARfdhl62JGq+T}&G1S0R(AYG#F6OIaU2DrM<quIsOCaWU zrxN0G{t^c^Wsj}x3g7IFWLEzL^4>($c%e_c6G<+%45f+z>_j>Uw!;eMH*NMsPT<L^ zc&;Q=XDq``(;0B^jX#&e2BOodQ%f))FHJ?jYCz4EVZxn>EIziQ4FK_pr95LBNH~&P zDE<6`X6sW50<2U0-m%a2!XJAil0=P#1BVtt5@dLmm%bkE_fvmJETlrly?l*3?K08s zjV0sO-BPgjiW!VY>o^-1YA9(ZcSwwapmgzHXkrHbp`OQwffL2qMk+9RmAmPHVG#E3 z;cuBA+;CbwV#?4mB+j1ez!=N|Iqq+Al6WXNSDF+KHr>wyWvCA&3+w&?t<7gbaymp_ zmCm$_%YE1)%^lC>jcQC6bU9y2#uDxHz=j;cu$Q;rd8>$Bk6x~Qd-8R|gsu~m@5x}V zZ0QNvY%T3KtSh-oP{nvMq3B@21Ii}e*+R1qta-MBjcvRQw>KRbf&^_|nPpw)5)Fb6 z{eF0ES0~=<{dqZB7*}#6RTk<g06FZkjVwAa)ft#OldYEk_qurvHwquDra@QVXKQGa zsiR{KI{Q-Cy|QPlyNMVPg7HG>Zek=0sH$TtG?a{wx#uZ_|1~Uoq{f%k+goH&Ql^|< zWU{$=CAZo!!M;7Y^9o@Tpt9z7_pw%5{%JZs7$#9pp%hri_F@5b3TZD!Hny>>$YQji ze^Ox;D3{}*Fa;GBc__nYuvfAqTGd5Cz}wQk3XPTBy#4je+N<rs#5s4lJ{=Z{ukiXN zA!~5jL_8*&c6V(ecEnVP`iK=VJL@3Z5Rv~C3;>ifZicqX9HXOE*B}UEG@0A8aV{y8 z&J2bJj%LyXHJH-+DZPMCwQY`ePMnqYZUC}Rz(M3rA;#fK*=3#Pn=ZzxZJb*nx<>hc zxqV+ZcP@soS7-UJ9#&T103^V>iO}goj4dOzya0}8m8-Hy98dXo-lg?-@q@7V6<F`o zZz9^xh9ixx*$n%7SOWo>?k|D=PkZxZNvvZgD-(lpv}q`yd3oTsHi0aE(vUA_sj67D z@Xm*i%_OQ`pCzuXc7)}J>fAs(5nhi{8!<G2a1UI=B&y}_!1It_N4pjZQ9y=PUU<Ce z8hbbrY~!8Ed}{Fv7WUXg6Cq!JBH_s5SLMz(Hdcyx?2OLe4_^_RAQ(qRR8vt4lC&55 zD^gYuL>|E5WpJvNzS!@Aocub*h}uye@}b|nhH@ny+mox|HUX=xG_<$b1C3Xx5Rt2& zF&4f@G#6U|o*ExBc7$@`{JEob33#*$pc5zZtKEhh$bVFQnZNGcydDybv$3h%*fmJT z$MI3i-CP}8%yt>#GeDv>w0H7IOP%5$_7qW1Sai<oNfk-~X6xW0F0+W9W14a$XXf}b zh2uLgC^QQ^(}T77-#%%P8-W|8J2MiSjA@;VElbKfx84Mw+l*%zCFIuqsx8&UfINcN z(54S>Efg|CP|@M2%~0zHE?KSEH(?#Ymczz2XV9f~8v1cwc_(H9+U!vbcMSX;<R6F< zh}PvyLResU{j)HHbqvR_4}{w|4c6ZG)@BaR;KPcg!}T~wk{^1<GZ(U4&`34;Yk`qW zRT9;3H^7l^RJ?hfzRWj(rcB_4GuEOuE``s(htQ3C`G|5&3BDYPvK_U4cEcgk>j`iq z`~C0b(<$%*ZdH9ibw+1|%L3^$Jn*WwE0G;fPI-KxFF`+smf>uLmWHtsndVD5BY7sU z>mu-&f<O8WF#8AhW#TOyz!U<XvG5!iwCYi^x}2JEO32_N3-iNJ&w&-Wy3!W?ee*tq zdxM}bH9;IPk#F!2AM)NI%=BouH_=hRRnO4FN_Ghf&MXYHP65Ou)0NqtZ8EVP3*<ym z=h9nA2!Q=-=8Zp@tjoZPTFkQHPp3AV@BC_jfp!atn_YJnghH}vrI|rHAJsJ^Zc?ft z9BD{M2~Tx^Gr=L}{!vglQUYZ5aV`as^0=%FK#5m@l1w&CU?ukBp6tOiH!a_dI(Sa< zU;UNhO@Hnb(<XB0Wx<E97NLnPtT+r!&~NJdsVc=eKLtenY=IB2EFx$l!<n3~7d~t1 zB=JXDAikB}G7C2QBFBe@DF-~LU*uHF&8lrVTkBIhXB1Qh&yKzBr9NaY6m!(ye*Cx6 z`ahvmGfKvVd*zgTRZvfgZ~Lx8?Go`zE3guq(3q#G@aj&J68Us#pC#oZkw<$`t2Cin znj@7`1p;D2h+kCZaNO}H4`ga;t4a<2gKU-_2>vu2xXZCu)>sb`IfQKg{S2c_wTtAS zBsuLqz8+b>@WR*3vzD?7ZbF<X$#kx;Az*MKq(h7&KLBZ(vz=Cx1>EtUrma3!MkCHK ze&8DMP`d~kOE&zN+r*IMD9-gnCExLvgKS(Ew`zg#E}<}+;WYlEiBwcAY95RTiwiRM z{S(wMOa%+bC)rSs+fy0Sj`!8{MEB{UxZ9d0;vAG?lcx=pLZ)pxU4_8Q!9JN4tExwY zF94i5cXiWgE+mHWZ{H+4|KrEL{lXQLStT~v1O^)|I;l0=Sl`+NzAcxEPTd4$sdSU9 zVW|C?5uPt2F&rMW^Qk20b3F9w=PZi&FXtwnnu1<6TmBA+5J_Dwi?FWs&qw+L930jU zXCMNlaGAFF=q@c)of-AM#lbED^>gwW?;#FmnqdVf&3oF;^6ySjt_lTy6(UMd#$4)h zAvKY=tpdUD>u4r+%4+CiE7i2xNdf#=ib&W5RyN&$iQ3@f{o-c>om5bfh^2>sl6Rm| zz@`H<iR}Z!4O7Ba*Pge!dYhsgS6FOdv>CAokNKu$Z3wSoZ#b<ux9Uo>@T)LD$hklq zhlRCtfE3k9hs?o?y2y5>m+6%AT*rBmXg!<6at+6*<VUuVCOA?wA+rFdhYFxocfv7% zWLM4o=<=SgnPGxt63v$rAJ4dX(#go~JV}CS3K;a>gr8CnEOj*Rpr%3%urmCley4jZ z_9HOgPcpv37h2@oUPGV9fK}8jWkXFXTt7Nsy36??<d+fxV!(kfj6WfvDa02VXzY?~ zDO9uN4ATUp@_2HjH>{_u*DlG}?|GvsU#uF!CL*HIIKZsr??8l?4TXatQSOMPx9}np zShg<f^9Nk@M4<4%3Aj>5OE%+WVw8UqCH*ER5Nvr`(KY`F=kz*50_#L-#0bi{_c{l% zR%qCVTeHI>@em<29zk<jq;r&kaG$K_q@(4+Vu@g<>{yUpEy|#><s-`Ed_YiEXPL{- zJ9Q_`78}-M1q{%0aCv3jS@P!`OouKS#?Sy???;1MuPoc+{{dO33iAMdF|iH|g`G1C z6{-wPI6QWmt#6*|kuRe4f04z}KnTo7@kUc|GpeInzz*Vs0T*9j<K~W_i7c2E#C=Nb zc^q0TsF<lcTM*g{sP!)C&1i2Yd8!uVDCPE4fvI^6ajz1tbIM{!6z|86cmxt|(;&NM z1VbsOq&rK-dLB2}8`>M2#O^u1kWZt)Hhb$@U|n)i8yP_MBTD*`RVzo!nl^uAvSH<I zI^97q%6+(jqw7xhEB6ANhk5O@t2lBU&?O4FJS+E8L=BT)MA5mhrNWP&k>7ijWgD(M zw*1})&3H&DVC26wIi^`Vmjeiyd%8qeVY;k14`;Hp<#$pX+G!%pg3i>pm+M1(3cG4Q z3^P8a0xeOO3#LPfkwE5b%%Qs~QC7I@qGLbZTsdG!rAZy?^E3WjGN1`8eMCVSlM$qW z1W!F<@nGIv)G!079H_hcU9DQgZbD)EPZK%}wf5X_#{**8>6pc<qd|Ce^KVFNUoFf7 z^mpcPEloz0)gsW|)z6)c%P%7&w!`*NwZZMY=7Pn^cwotJ`L-f{iKT$wni*qUrrk(N z;Q_k{@3J{Vd)wu~m)1)`Lx|91{rBG3tl57md<T|_CFYQE&)K{`)L=yD5^OC+f02ZD zTyr^W*Zo%`n2=}2hD|W$3LX%!CWujm5V~)`2HuG#GMH8&(P6nUr&{Q(#NG5JAt!%Q z9}dCLkO*(wUpR=pGSqx?dx}aBM!*6<#7nVmNyx__=;{g%2pjnn!QsDxnJ%y|g2==V zzhOZKGfKJ~nik9^vNCA@D~7gb<``x>xxrFaGVT<SC16r544jc08UA_-owIgIj<-DP zq<J)9y2gw<BVa+jq{;~XfRCf*Lb%OA3cj>9GHdf%7Gm~!elvJajdB|v)DM$R!Jf`q znNE||*adAw8B&!|eG9mcF7>c%J@%%9kb-!y(L9aUSSqa;;qPY<CkY|){o>X9PH#xj zPH0{*wt-?~tUN^RgXj*-c~uSt*F)T|C()P6<pk<E#>dx9M6Al&;0!My+t>CPuqBiH zb$3z5Oo68GFVwz6X6>d4!|>~gS4(#ItAtJNr(@yoY{C@q;m;WeWd9@w1W2NMsx=uH zbgZh8ZJ=r2+BV*KA?_hdzUnRPhC+&gNU(l507S=~`@%-YgNU0Sj@63W=N%i3wL#re z#E_h$`@>p!WtU)TUl|rAhMGgzE(d69<}>Klr`#0dQyk#$JtcokSGjC6Z0CH5*axY= zg6KqgP_dRi%Q<{bm=?w<2r?gt26pA)N5Xn+2!58kCdqm(E~s75@V`H25Aj<|(>bNf zHQp%)xlCUmo_btG5G;}lsR?YQ>zl368I~n)PX^Ocr1{f7;FuoKz41eI>%K5{g0V2} zK()}M30-a&LK6(wolud9m@}F)dXpqFBNI--W^_5_xsK&7Q{>jUJk?-~GF-WyE!PK? zn@fJ5)3^9or?|&83LQ30%?GDt%yoJ;!!`mU@;~dv5eMO{tUPokE+-Luw^b}Ge#j6R zmIR-(jF1XSGHPc|e_KFN)ggSX39@7?(L-r6QC~CV7-|`6o9w~n`5Z=7LS{m4EP211 z-}>{UiD7iPPS=oNY~w1s5ZYDBfgnM#>#$qpXe-80(C|jnU5{|bt`#n`C(G4DS^8;s zFcBSRKF$3K(O`vkiCY++gRDX-k+{K4;hd)|IiyU~p=jYd)#`NRjQ5txk`R_;R>lJ~ zcLK*NON2xIgNRcm!Z*Wts$VVJc25MyJu2o7CBC1f|L<{yJc&>^GO!VAocc~xhtCSN zqNeA(IBXHs><38Lsv<NIWHU&*H4&}qT+)<f2>rdm3lw5f{EFdY>kgK!1)h;Bt3?j+ zYp<>nn>d>e*Mv~{_gW3@jMYrvsA-2zw!X>4(B<+~{Hu-pzL_vAZ`$c3J7#rB^e)k0 zFqGTwKOzBe+W*ARC#<XI4O2{J^utQT(u;`mt)3XbWI@5<zlq`ov)7a$U!NGh{!1v* z<*VTjbJ;^*nYC_FgMS0XZNbZf{KHFGOO^X%UxO08Ep(u~AlI+7sEx;b>R@fSzRE3$ zvZvHHG40xIJ0Ho>QN9x-w({s8Fo3<AV+iMATI4~?<F0=;G~3b;UaUGaaV&g7E|Gr| z_xte^6Q|Gy`P60byP<XdEi%#60y{$i{rES?aep~ncJ$)Zxg%!cnu!BpEnxNkuY~0f zSMsX@zl`?{Fg`B($p**xwoD#CtrpT+CoN?fEx}Wj_nLHn10*Ow<ZU3fBI&;vf`Z1K zy^?A<sYf)k0gs={Wa&AvOE88zg<zhbB^6M&H8cw&##%mQ5-vinv$0ydp>R&Y!ifSk zPG-psrxH*p<^DOW{UJffw3-Vehwh-eptb>w?jJQ>n^167G(n4BhcbQ96mJA%iu-&} zUJ)hTL3l7}m-%r98;Hxsb&grVyi;3&4B#+Pl4|WK1OoTCo6aAnAk~{HonwwfAs9y4 zfZN$ay>umo6lM_ZOHhMcm$ACqVF@>UJvEgEn;lA|8E!e()a!s}jZ_mfHE)(8Tse#k zGM_RL{0X};)vx$e@{!laeS<l?(tys-s_3z(t(QAeN>8(`CFGCG#MXh+!T5b!o8Z`d zFK9(9f~7Jb9QDBy$*JGgp)RwXE0Xh1-i3}3_Z1_o*?*XJ(a56RTa87yr4^=+$&ky$ z?X6E47afpdB`{gI^cwhhX=z0WEePTt8~tq$#yIo-wp@X-{B-|n!0kIg7Qj3Feuxn^ zy&gWAW}aT}F~O_ju9c*3F9=%pKem4;(W^!f!GoyeK>dh$lh0Wx%7FyCzM;dBx|q!! zmk)A<G<Ge1kAPD}g3({#(QM2Bj^_epyYqf&UJsW{+9+iG@IrF<lC`p20kG}CCoey3 z;1~e|;j~lmrQL}w^qmW3a0hLsEr{&%?%}f`siMJ)y(j6=5-vWG#GX1gPhvqwDGp|{ z`VQ$2=LZ|5*+j@}K@V}Cf~ZAY-RyLlr=7L3E`8OgZqtz%8xjrcm93ewF*({Wzd8Hw zI&{n(YJJH4k1nrn)<&{YVs3_8C=j`V0&!GO@^EA1IB`GUyFUI>rq`6Ij0vC)<$n^+ z6<O(&#Q{#Tj>TWZC8JMji6&yCf-;mpSFwi4Ek?w-C@M`ryVyMTZ|ZsP03I^N0fXaC zk%_Bc0o7h=xDNt14imoN5EqV3&}^uTt(!eNIUB6|IfwZY6Z6eNvm>01Vv}<rJ(vLv zdsxYtRS<E2mNWV*TeIN=l;IPh1&*`RXX~y4R_9RM3CL)U^5hoLTkb!|PC3Sz`aH4I zb_?&6q5Ws5FekI&RkP7ZZp;UQ1_o4G5H}f11s+YbZVn$OnKXONA;c}0uOS%sSG!lf zCoen+R@Pym0xkNK6h1rURO{y0ggN+xNqCZpp=EX2Q3@^s=;AM9`!79Px0_f!xY7QF zuRx-83)Sh!oHT(t_shb^fmKE(WVkO5;=IveZS47|IRB}YE4vrCL|V35xt(aoWpo0( zO>YbD5NzLKF*2IE?u^Tu0HcwDKrV!3Ej<${TlQt;F9NqNd`(Mx2WN@?L)=4Sac938 zgxK>V0fVGn<#wl`r5(i?w-m#XiC#Ma**TAZG8K*63gaZ}TG<&>n=VP%KNHC)&hJM{ z9K{kl<2(qm_FLSO^T$T?#B7_Cm309fB5|cip`OmbbBZl*x<bU_yZGW#!La4u_l7?P zRO-N{^TL2%3#4-2N6pPEnWYNi5cou=$@Kx`um@}?Y@EpFYI?+k=`%WI7lW<VH<uuP z>?5*b3af6qL6#{L+{*tu7J?He1yUf82v8xP<5w9Sj$)Ik!{wI?<+WC1Q#4nKNg$wi z1;jicWfB30tAC+nyC>>*(nP{3IpZQ2<_L^Waw!&Ri+2vsSz@kL>&XLj0VPQp2HfjA zo_PnFy!EQkZ22Mu1qz>#a(}_{hVw#m&eE!^3KYuEMnP+sf8%l+?rf5QON|1pD>aTJ zAXK%scR`{F;Y8V55d<F<3_5JQ^@0A;7C_`eNPeINSM#)CEg3h==sEBouMHf>Wdvem z)eLlWols=Tl^3GWLv=iap;4YgVs^exf#+z8FobeSScir8TPPtQABNOp<a>E)qHrZd zXdMXPIbHr@0EXrmCH^Fy6hpmhV(4#PdA28S80Z<}nXnCKY;IKAEHRq2pgFYqG_?)a z(c51`6KLJ@h6-u@|AfjS<wK!O3Mng+U3L1o;j-{CUb)E&gcXCm@`8?oKrX#gnZRCy zf{-j02@%RLoWfDH-^d9W3P6s-ONJFss!RlgHnGI|z&!uuxk;?E9A*`W?{RPK4e(*K zU5+7waM=`G&x1h0e!E0!+?<-moeer_TT9I}TSym;fZH>OqT=Tzeprsjy}A5U=LJ#R zurapG#qZ|A$fFsx3#R9v!2awet(8$3$(_hA=P2Fy<&2lX7bm~XDkgV+6V4h;OyeHk zL;3Z+x6)XRbuuO8xORA)pPI4W<O$1&1#VQA$1`$K<myG<+II2FHrcZZ6@rgHneOZt z;|!NCFR2rwRSf!@3*HLQqE5Ez%wI2x@uTs($4QK9R4r&Pt52SG(z*a|aq&Jj_aWk? zpF`Sy<&8Mc#7yJOojgbQrv8cZ8*m5wwxQ}=cf$+pfzQ0Jb`ZmL?#WGA<D~VA1!8KY zOL4c&*aj3nL?ox6t)gV@JnvB}ySJxEOVZ?t8TFJ1E@SPCQq&b;@w6}4NrpZ|{iz}( zb5^Y;bg)<t>Dar`hpU=<^#M!+>St#nd68wz?`i^yhtH)&qZbQou|4^EhL0Teay>B0 z(#?oTdnXVc>vXdTt2JgJvrR2j4hH@yFkcl;({*z&(@?k_kVKAN+;BeH7I3`T3c<$- zvMZR&C^Fow7(8cf{Gr22dipP9w&%sJv#QQ-?!yi^EM^wU-vy1Vi)PBLBnPd*RJ4!# zM|c+@*;>IHb-K~M1s?PiERfQAYL@s<TTMwa4G6-d;9VVpmg^3Jho<hk4WLDW+ew+R zg1S>1ZjtBv#I?S<OcGKv7AqcLANZzc>%eZwnes1$;Qe}@T~%G$p2NW2Z@JY-9R2;y z+hr!nN_z;fLg7UhO}0GE-$E7VNf1D|rBv1^9`HutvPL)9OD}DY@kbr~Oo<<@UMckv z@4Mfi(58M0%fQTL>P}tgd6blv##3=X1Zxor`rrD$m|M_Pv-U_~T5v%UcAo1-QuOL% z_+lqNh+5;8N$2VDe+gokcx7hP>4_SumHaaG4PywN#g@tn>hHMLpSY!TW?%^-gK6>l zQ_q!h`4WHHR0xHF_ktr>Zspb$Y0uVg2oDIIs@=o}@90F(vTFFQWpTSGFu-wDQVk#` z#WbEpXWJVjGSnhD17ar4#tYdxqM@?|pC4U){m~bC$p@}pn@FGdG5-0`_NLBHyF$2f zE#GT^JIlMGnPKlmgT1x8&$#N?Xh!nG?aadz<g`upU9_wdE~__AEY<@?Z$nij-?TkF z<nWonf?N`tTM>TugtqL4FpY$r7i(dbp!lk9t2&*|!;aLDkqY7_b4VbaWNPaNUb{>) z(v-h~0k9Wpj<)@gqK1ib&U+Gar<Q%b*yVhizjqzmyS0tG={kJ$TGHOZw|7~kZJdwu zQx~P5oN|8TV-mMXyVCdyGZ7sjTcPcHQ;S~8LM^9%r2c}0@zgfkQm%*w1tVYtM2M09 zDvJv$Z0ZFBU)8+kvO?2;ki$gv7q*L3;YtW>y=Hp;`^8IlXGISh4XN6yv~03}QY-#g zMHqek4RJb!#+IzRJdlYv{ZRR4{`x$5;Hh-p$oSZS<syDt7gaiI70$aEaP)_gkbR4m zonD-*{*SX|9b*YYB6_Q6?<@H?+Mm*=3he#6PK59M{)h345s4=3y(vAOrt;Wf;$i17 zthVIjlN$!p?@?rZaUpm~AmwNJLgb9p)s5c{CM`@(#?3R2?yt=)+Af83FoPBYI#J~# z@Y+*yT91$ITl3}&+~!rBwv@bj&_t0jVreIEEpo59eERdqk4u7U8?oxU9;_m}y?)`L zMLg5`YUVMq%y1cVU);Z2bFn_=mUZ5>2Bg@ZQ(lO;4u1~waNLsz5!`KUuVBw=e^oC} zgx+zxyrrnB2Cs?O!>&BZ+aC=DK3#2e^0uFwGga(gOG}D-_Q9DoaQyn%>x3uvrRpU2 z`t@Hfac%p@;zEH{Z`NLZ-90&GAJ7WB%U-(Pi6*(<bzb*h`N=HfSxWDB8#z@d*Qm3| ztB7y#XS5;3Rm}(>a*hjV@9loYtQ6G)rUR6;<-xb-*;f)X>*+>?o6ac=%fF|Z%t~0p zPkp*<f}>;TaR~sIdp+sbqUc7HQklhUTgw*VK-zZty1E!(1L*q-O6OlA(5`)r)7|MB zRsM487e0w_0?m?AA{ry7+>>?`LAkSss$=4?`zmIo1EJ|<%2Vp(DRw1!H7Y9n2O;j= zDd_kZegm16yMfEr?BbMgtDYMnAs^*Z`|Q|;M*am;Y5%?%Cy}ZP#9lAH{w~K?uNk}i z>LjxUF5mNDH7BJn=H!C;CE4!ZmI3_7EJw`c;fv679_t^-1`;O<A`k2UJgpxu?zH@_ zkNY2tzMWkfkp21|v{GG|N{_>fdL^%o+!B;GtlPkG+G|X!dI%Jwn7vlxS0LV}4iiK& zY&IYN$~=+8fnjFpm`(R@qi;UXzOB~nd^liO=Ybu-yLUURckVA+nh42!Di~T5%>p0| z8-Ou-5Hyce2w(kb=z1vK$dgv*Nr{vHYO`3Tc(lc_TC8`wz_z~zmV961k3{lz>u)V1 zuLdBxx^d~<y76sdQewdzC5#zp0ko8F&b{nZ5)suuh4x+?e0y1=5oC4r_NftfOJq!5 zcEprF7V}og#VXDR7>MfapYiXxad9XFRXs=v(eq1Vb6c{cj}A*yEo?XC0R8+j;}I&l z)ImToxEYqI&8v9zX!7TY!|%=quBuTWdI%c#&-?F2;TakXlY0@v=#}}L`ST+OQmhV> z>V^H9WMWh8Z-$+lypcU@A+3~Rw`&H%ol|d&fg^wWS)b_sHW;pz7nHZHxr29$>!}r- zj5AYeTiiA-y7<c2pNRQq!v0Aqe}%q{g2$U$tQN@6XPXIUN9|z@iM)dc-U_+&WnX}j zb&Zfrr;{m6kvm>}bm+3x-JNpFfI6c>40AH=-^t7RGtN<mEpC{&86{>siJ$FxeL_zr zO2VOb8Llt$2Tp|(Y~3H-x_>LERAPHvbMPh!$9;KzF8hZZOFJN)IPd`vo&E0n&)L4z zOQwYJxp5N#U!n<JLC*(<CNtwc$bXA-{rJrxz+=zL^ii*!+NtwDaZ;LrTc1>0I3$9R zx~F8?pUDhYGp$BlCeB1gCw{M(VmcF2x+ALlzs2XPN{(1Ye(JY+C9>WE1~WC~{^6JM z4aF_yeGy$Y0IwZ>9oW?}E2adOR*&xr^L&I-%(xjt+v}56eJOD%W9l*@v$Wxlf*_=F zPP=tw<%K@(Fk9^Mi&7yEZ{*I~>!$AxEkR*7X7qbt*H$+jZz?{BL_ya=3+(h=f>l$# z7Y$S_aUDs57_{(1%l8V;MUDrBem#<TZZ+6A9wLjQ>=*gw^;(DCEuUY_QB*|jxYU?@ zSF2G+DgF@%!A(uA|EPCqR?WyS1X+E<btM-oZ0Bf6basT@^%Ey%s*Wj=efEi!IW@qQ zmNS~Ao}kkoMC^Vf1e5#4T`dzy=}~n>i3{$7_!;WEDjlLgiDvPCjov^5F2oB*!b^ex z(Y$<r?)W~dfWoT+ucGMi-l^G(EuVEfxbz_$9k$7-p7I!GZEso8<0&lMS{>+#M4OL9 zU9eY57-drjT3&wFcfS<nOUl#K+<35_2<;Hm?JSv`^4PSHZqG_q7J(0U=mTnmUDg+g z$;%`tB;$chiXJjB7phaPEOE4H==s7(GuVp>m%JHjm3l3IJdRI}C^xaWC0rYNBHQ8} z2X_RH!qC}rsY@?zpr5DJUoHy2-E>A)kB|z&XnH9!mV5u5)uP}SkgbwI1M+zJ{Vb_` zyAiGSf%vI;r*ZY9kyijqHcG<YFxa1VMz}mxF}-fM!?<<oBDCbH{)Y?0%c@f(D6ouw zcopnI-8D7%`17l}>%1NZRL8`fFeQ>Nwu_+G_3ojE%8-=xR7&U6@AAV}TYVi0+vS=+ znQpqaRI_0b23J#I{nYgru`dg9o>58aSK4eZJ@o2Z97z1`_=vJ_C-ZZmpOQDu)WOmN z`j2q2yZ&6OBCpPejuy3)RU_VZ*|_5km5mxtH0yg+_a-_ZmE$oH%`T~Gyt19&qnWjo z0@6>oJFaD%jjZh<f0l}TGhK2u*-k^NIhzV};Ff;v@dYo>3LnpO5&uphZ4U|8NM4<Q z@r#1JPQ_B$pK7b{6Bz}%cOBqRe7uSDKJ}zFupMdWSA1*q%k8Xa>efS;?7vH&)Z3sy z)N5hy(EQTzm8EwLjE=_E5`Gd7)g_(wfs_djyUV4X_!a;Yg36D~80B3#{YzUZEedvR zE(tjP1+O9=`p;q4y~AEYVzeZd(7XW_*}mvP{`vBW__yI%)c+uyw+EGiq5@wCjV_DG z4S!M#%h>ASdn76GnZ$iTuMrm-7u1r<O!5Jaw@O1xo33~EZ)!SGQ*%hvYKN*)w*H+i z8?#qAq}z&e%~NTweQFK`9f!K7I=A|?3{wYak0gc%Ek-=j_+BBb{<+HvZT2cATyDP) zo12H{4Pg|hzvR<zbsSB2em%sCidXc;!vCooS)RGGp&Z!)Cu@v+te3ax`ck<6t0L;x zt4nir`VR>HSsP*FZ}&%4`u8wykE;fw2=aj51g|6rx9YoT*Fq3hFu741>e)vkao4)5 zLva0M;}Sli`p`gQQuzV>=8&eyS*oF+zBATV1GT&1oepc2ck5=jWi@$R&dW!BE~mq| zQ!0J$=s`?wR&Ta3+Bb~0JNWK_gI9<%24XD}q3=qE4;$USBKCd_)=&OX1kF_RyXB8T zDPuPGznDB^;p*zK_!i^~8efDICLWxFV`MW9mv5X)r(>rtX(@$3gaw#wAFvSok8=eP z?M{M7SwO4$Cc;fS`YXgDl8)&F;PL2tZdOWRl=5dBnUG7oom_L3TM1vyDflI$f(J#$ z_zy^d&jN1fJzJN8u$xXNE&uD9n6Xh8Af?kndohOgA8+Bqlhk<66W3g@<n0Qi-7qKQ zscV#O(}oE<!{)D(#cAQYi4?e}kTTg&&%H$ZalvPcA{&3d0T)E0r2&vc8U1+a>!w@y zs|_zf6#`1BLaChh0Z&n?8zzqN3BRP3G91_4^6FJi4~C1ScV|2aLWjvEE|i|svl{lf zmSe1`pHPZvVdwmQZ;z;nURUbSv3%=7f>`Lujn{Xh>MkgRzI{%2vYPHoZ=8O%@cH!n z@@JxE0>SN{$q<YbX-CwE(!H8~48yz)r`CCDpYPAo$hj%dq&$!OhGe`86KOBGlQ1j& zThF@y&@6pNiIXW2l2=k;kQ4=+M`>4Sa^i-WEymm9|42IbKqmkH{ogYTIiz?unN3YO zm5gEzv+3YeIfQhOLnGDOY0fzgQE6?CQ8}y}h7O2A&cqzbgd%4~vzYVw^#0zT-|t`j zL-&2Z4$tel9#>>0p?(eP+52(u-PMFkm85?NV9C$+_Sj;xF{M!WP$Jmpo50=KvTmP3 zUw<%QYRk0RV@2Fn(nM17DKf3L29;x5-nd}f+wD~)WI$9GDS_I1eHGG}Sf`4C-klU1 z85Tpg<PLh;y@|{e9Ld~x4MbfGxSX$n$y$E7T(`gBBk?%kbP)trFU|h@<D=ky@rT5v ziR$gIO>>-h2o~W&{B#TdSR(68#(Tt&$7X3p|JAk`&~c7?+nMKz7C$FAHa14ZwHQ1C z^KtpFUcVf$p2{wLo$6^vnlk3D6sbHZKZl43FnffR=TJutsW7v({2j$Cy9qrp#OEW= z5QXG}ku2z4mbp1z_fENjnS=T}X;Qo$L~3=%gqxJv&zMd$DO500SoL7&Z6dVk>u(Qt z#FTGtxM$SOBI|OGRUj@D44ij5n9iFeWj;Fd<L*pqvL^iJ5gjH1wIIzJbawSRLcRcf zvlRZ~{qTuRYbs<}5EBXN6*E87V>!JMLPHl%e!Z*SxZgXd&AK`4hb)@A@J8&lleu0L zT{L3r?O0K?v1?~UOt$X|*U|rX#xHf9P8nP9SEi<n5yR14j1u?s<(`2gs=(>iLX8L& zZE-eu5gE5PCS+*t1?BY1{IL6Tii|5crw!KEFk{Qw&YUD1pK@W79LKGG6&zH)HXnK< z&)Cg<>s^!Q_(RmJIAiflW6*Q%>N7%VSZhWU`+q}h2iio)YDwuW-M*<4U~zqnv7y5) znYFE5mGPag@RmdUK`UIIiDbz#sryqv!RF)UGuc-vTf%015AX+Uo}*@9$Lz!w@y#V0 zj*Uz06oH?txp8EU9~a!N<}>umMtDn^VX>+cr{WxxkP3?`3jDbD(O*;w#?$y7Exmo{ ziSC$3UcCE9<3ZwO?@rLrAA5E4k)mwP?o84#*G$)hfD<vYi%bH{er@gjzrP2r-@Mmu zWZ2=`<&7)hURQ8GeycveiO)M5U5xPCv+e(^lXK^9Im+#^S-0x~fPC9?4@&97dBCqu znH`d)m9Ma|49AYOsv?ael~9*p@Z$07ea%0k-)k?l+88ZsBbi0$9?I=c@?1YXCA_a{ zYlBP20(JnuwK~mra^utG5~H_OA#O1<DeLdTG=wH>N`!0?4_?ColHzwV%y6K_Yn&17 z8R|B18E^6;P(J>m0Zf@M^Tig)e)X7#c^s+A;N1ploVIZx^q(`sm(M!>ovAUxeEc0g z2Yc(LxbWdkNNnQO1l_<j>6!@{SO-zCfBdn~4_jkd018Frk|uQOWgi0)wR#ZV-_h>s z^_uTLh<dCM+g+Hn{6pRWbR=&N20lyM&lS6UV$6u(;^PBnX%&L7`+}FrP*l~@|6K6@ zPOzSKLsVnovUG}X##cA&)+vYR+z?Kje_2Vln_lB{OF9+va%X)bYeKNL_rezw;<Ys1 zzBW;qTu}X9_0_WMd6|y$4~hm5wdkvA4b+Q128BkxH{zSu)p?bjn&tdkF38dL;@Li; z?306;m0SvlU{cMG1YTkvS%$m&Tk0_LA{xJZ>%7=9F!T~1s~Erc_urhmHVj$Azoc2! zsRMhyn{hQ#e9fhadf;g3ZBO{InWcXZ7xlmP8XAm}5`Qu8@ZhkfzI(m~1Fy2qM1a=! zzlV?e^kxiGvl|D9w{D%y_02Sa!l86<0{nIw$M;S4@mc1d6L4s{cu3^5Dy#a)-L+!$ z`K+2wa|<u#PTbmCA)^$x+N%<O@)e=?E^V*8Q)wM|sfbNsYn-om8qjRmQ8Ff)NhhA+ z)SlcnDD_>tgS|$Zmo{vfql<3ct~z=4x_sQfkxNYR*;68eQ42wPwvz*Q@2Op%BBH;I z{o|=|v!`Et_4E&V@j!=HLDM~{aBD9c=x44FRFPq}UMEo4!KMlIOU8WZn`PhjZkp0z zeFlmo`&{nsTsW?|)FJH3a)RC8QXS98u|r9PDx^6kZkg8e(s)BrdVtWId~5wzYY%Dd z8#QlB59}K%8>2SVI_^HN_+-lexpFflAr(K%lb((!i#oXIF#bs9$;~`$Xx8q_>Q(k` z`vDW>GC<D{(H$WI1&0bZv+o8Rv(bJI)|X49R_;{!f0+2HQ|>Wm{JjG?!&{kmup7T+ zZ;*OV$}q#K7Q~y44u1Hzw#RMT_|-n$uZgZNd=tHcIB(e0jJMZ5Duf-`*8i9V+h{*h zpJW|9#r?Ds!&;Jl@97JQBxf5+sImqld6lETb31|@TUx&<{0{U|sz?7>N{={%+i!O% z?R@+s`KyP{UkkjsD%J68!p99OXKm3P<{+{$rxG>oqe}b()AyxV??;RN1EQxKFwKYH z+b0TT%R4e_l=p{+hkA+%UjoiMxUtjiFbl;-$9mb;>+dbb=%~dHb!_ai+R=EI@Tt<Q z^~ZZDEjua`dt(Rd%Utn1&^+}^x^Abbc-v$?!p$^M?*8zTrgQm6CEjHz6?Ngx>f4(l zeG{UzC=v`$)#d+D1D}4CywTCKeZSX)FiB>@_foc$!|jJmBBt{Gpq_b8)S^G8HpYcK z^<M$DyEJLZ+cx*L5~2rk0MR*K&q!qgeaLC~Vl*{+s~fZcS`%adQBtN7pPJ@seulAU z)H{rd24>dc{=07$BTjeu#25_zm9^$epq@vUMiR!tqf$Qs_$Xh>?Igx9D&~kkx6@b- zuVTd_t<nXxtQkG1_QL85osbhj&@;Zk>W=A5r0pwOHHJ1tkU}9qrYY&y8#ZF^c8*gv zr8HQCOa(dZzdOS&Xk)?H#aWFCaC6J90W{HdH^gD~-OF7f4#sDdAWdilAFj}3oBcnh zMZsSfn`ixDWHbXXOLy|YU$P|NYQ4;R3->{@dInObgDs(?c<D$uuBIS>9WNo68JFW) z$}}?<G~5AEbeA~&ap#sY4IJB}nU`EvSxedUX(LS2eo(J<hWMD{nr)MkqA=9Pcj@98 z5xLg43C{JK!CRb9ckdXd@3(L;uo}o#jjCU`*C{O1;-gE9J2xE$@LTfj7bK<kx=VeA zOc{yc9_t^_^_Tj#3i~Sog6h(tWys(y(q4#l2w88jS@&gAy59<2sP$x<jGP$1THq-F zz^u^Oa4zfqr3eWbrW7D3r)ip5TaCmio31gTxffQ}>9B*lvy;@`hf7%I%4^?cUoI8% z{WOvCQcR$80?YfA?8ew^R>W!6XK$D&khs6dvi)10`d2{SeYZDW<qBy%LXsd7u^W_! z)XZ$6Eiew2NhY-B=*;v`AOx}Y=>GI1F8SW*5x88TAg7>>!xtZ~ixdJ~L(udBe(wh} zec<|T6%S><#;h_Ch=8@++igi%<5=jD^g*Hwga&HT6jV{}9Z2h~(Nw8lDhBrIr?OHA z;9TKGf};*ZoL7T?G>S~_MnH<Gf??{zc%%|!Q>Vo`GcW|wouu-c^O;9y$4uUSee9ZC z<%vTeTLsJ_=SvFK3p?o^fT7FFr6B)?c)B%7Iq5DG>SpTg3BK{abGeGzZ8+wXz@;WP z-c&#&3YvE6<hBYJ4%0l}_Vg7DQo+~8y9I($8>t*aS=`W!>D1=Iptu@tAyJIkmXwf? z2{324mTEuNAJp?2pnU`6lVPkcjHxkBdC4xW@PxBgu;|<xFPdutQTU)y^<YTnWKYp1 z_maD^iiWVv7-=I63wq|geY28%g4p0DC$cZ}Rq;1ts~M(6mrcZRXh0`>wt~5wR|!SB z-I2prhlB%`{N&=)J5pdN{Co1g2z)N)vB#iK02x*U*3}*Njn~ZBPQ~|>G@lvv4wR%U z!LEco$^~$>i;9#LHr=WjLtDpGgf{8>^Gq`XDC1cDZWqbO9x|3LENqxHmyj7`DKzoM z+l(g~5Ty=_Xh}Cg?`y+$2D@0_q(;N?p|6<^xVsQ>%?hH|B`RYeTT!+AS^MvO7Hps5 z7R|23%a(+u{dGJ)F34$ldSJ>9+4KjBEZek-7l!Y=ZGl}P_6>HYzVVIEq40QdPm)91 zeaxbxbQ*Zf8o{Wj^N(Rz9W2xADM^tutHXpEq-|NzQl!0elwfFD_}w-*Ti&l>R|!(@ zLZoFuvsk(EBEdW0W*PWd5N~!zx<Y0EJn6CUX7|&_`=)$?xJ*ynzv_qHyoK~&*K)k9 zdH^!a=yXi2JCUD_nm?&-V2Fj@F$WPsme8M%&sET>T5uT974`l~V!Qcxx@e*x0C<~& zJ9)yT&Fnqo(DL4c{Er4ixJt!zNM`h3K_9R<45D+J*x|eVF+x{(a~rUm!j2_SB4RXk zpaG7b$JEtplq)Y4%s$-7rqhKTqhlIl`T1(<8ecp=k)vh@wts*d?myRDpByV?(iI1H z;?&_93G0}is$fx2B$jx7#=$4hX}M>qU|)nc=VK(((JW?DwAm~QQ$`_<WS{uXf)7{{ zH(vs!@!r~^;bB$19!HuyaE~{GP$&1bhwe%N5(F$quE1N1hY&<&<td#;%xxPYIQ;AE z?w8lU`oMICw8${<s`4vu?urjXAly0=BJY<MC2?tmB`1i_1@!XkJE44hQA6R$FVJd3 zl#J>H2ya%Io~XrhFCXEQujJIL0egR7q)kg`)R+KVW~yd4Mn2^QFe}8=U$iPM+*^jq zOE4Il6IqFGGe9GKb$A)jGScM9`~5$uv2S5l<*Hg8KD=IhuP(;8m?umD4Z5H8#FZvd z$;<KKnJ?be`=}3p((_;4+O~NbHIxor+Cuo{TgHfG25N<8lp6Y=5H9I%8$q)MnZ1CQ z07L~0wNFb(4ds~*x0rIXy!w9S=-7%HTpse!Cx?Ls@!sfgA;hGpnmT3{2Av^@p1@S^ zH=}}r{X|OaoNx6uX=yv$@sasY(I=hXE1bSgm9&sHh;a`FvQJVLuyVS=mOzMDnuwm3 zFsB?Wos3VpqR~Fug?zzu%!SK)u44C5n|g}#q6&Smtzavd-_A7T8buTNip1^9gLMVu z=iG@`k>0czK@T#fn)TMn9!4vZ|F7PinsR7F-(XHqd<fx2g-sD)G8&<8soBsvnH+w} z==GaR>|ar5#lD6<iq0~l`6f!0TM|TodBOof%gCF0-r?)_pB65&5E5P%xq4!qf?!pO zYz@HB(oU#HJ`6-xf?LF(3`$4dUk+n@a+EY@VU8;h2bB69NE<XT@9<<G+%m{g?|+Go zK#kbWk(e*u0)*JJuV?}#S=<fK0G+K6-D&YjO)8;<y<_i0EFUL8HjO&>iDwVIZ2p}h z9qa^JZ!H;9kU-x|#z3m)<lvwV`gJS4i%`u&Pbn6-69>|NdnNBKVF3j4f7m#`M=+|k z{|eU-%k)m$nbtfQFsnXpfgMgX$a~apbUo5Cyt+q-UBXWKt2dDmnOxtVRLr5*x3V|8 zu7Qk}+HC4j$oB0dy>REwsTPBD@KWH6F5L3Nvv=~bopY6l0O$gp2p6zC>RdA@`z0Oa z4DKG+tRK_zU5C?2J(=lSw_hbtkOGRfEUdnZL~;a~4)a~NS*X*3@HXzyChUPgpRhjg z@m{kk)3W$XYI33OVtS6I1;$!+YKTjKX}NrG6Q!jx7TB4Y!v%3QSYG+gw&jDyH*Nvv zKpg)=^0ODba)V)G(7LR2TPmQH!$2krHbCIuYdU$@@zoT?gXvC99ub+G`n<v{2fq!n zOanjX5A;|tr{9|NgY8aPU12T6FftFJf=*d1a>~17MU5|UqFZpa^Y8CKA4~;+aN^$X zaHoC6_7G})MCNY6H!Zc*hEA=WVZ6jbu1d#JQeu!Z75~3^IsbX@1DG<=(B@(jWLnN` zl(;y4WRgaZ2o{%e!!n^g_!zw-HA1_frRDH9K&x92Ok$tH?)=>^V^8jEOZTg<FMucp z=<UZ0axcp(54HC1Nzy<^vM1!u9J6v-b7h60)c!$7-kn1xb@gCoS{2b<62bALp1bJY z1p*kyv*ZJ0|DYo`#M5#`z4zzW&y5D8=``q*GIia$Gujm8ohV9pKjKywl&ZC)Nox&} zxNi<zwG948pBhciQ*x@;>S4BL4^Xt9S3+ZW{r-D4fQv@VSzr+CGRRfFGY!CsQRX8n z&t`Rrkv&kxxW%QpVdNp4@8~dyFEj|?)c#@Rh2cdse5qzB(-B}6UTLHfT5P@-z09Z% zyBG$bVh!@hGUW;>jZuP{zhkv%mx#Gan?_?=r3kHHj}@jF!N5|&Y6n-ccbZqZ`FWWP z3&*mhfM%}~Jh@G1zWySMo_oYBN@KWV3u5*vrDx-sn&uuW&!DVfiTr&qg$aEL*iX7d zNi9cSu173kdV^`s=4b`BB0hDq`P3rc*(h(p5m+t&op*+e5pi~aAGnP5Bv3%ojSF~t zEHRgtYY%dGxOU@`^xlDLwtN><Jxf&^N@t$ixH7f>p}o7D;XLjB*_}x?-r+x>J2kNZ z)?UvBQT!`({(+)(9~<Ay<Yw%VAs5lm`o+jAsJhItv1QuwhP6z2=+|*O#VI*W5DzLL zQaHwEvc9*tmx7#o9Xoo8{1voOw27sYA^IU6bKx}wLJk_u8bPdbE(qZqH(hlId(<62 z88$>A)x#Bb@6~AhW>eF>A53KIz=0HQ-+SP6c{VB)b>Vb2yw#n@(P?9vCp$k@pu`8& zPvfTD|8epjd;%I$r2v+~!%KWprT#76#`G2R5<^NvyBM*^qXdVkXp(a~g{`8%pXZ{* zb~=4@cm#<7Z8aku&{~QE(>OoM=RV+cI5e;Dl`$P?Q87ER`z2L^f3csI4035DESv<a zmb{=v<6CPvPK7pZ<v<`aSCyPYbKan=uT8w5#TUq-0_(U0;ZK2y{Zj#RgWyy9r05?p zUO%%J+!KhDU_D1G>~<?{M(xx<u=5mAA0<c*q&&*Ehif6Cqvu=Z1kyLZzt%X2S09VW zj7lNn)qH?K>Tf!~r;ZG?u4hO2`WJ;q`jh+dkEGs~x#|f3;1kVM7Mxx3_SOY&2&8En zqz0xx{Pe?O>}<qiP(D5__ZTK(T=e>Npr*$iMT6mdh>&RE?<rG-Q+zKg+?XR`tcrbG z)-6BcP3p18G@Pb!`vYh~r*8}F24E??nRY-JKpBB&M_T?Z#>w&p#evKi^P6A5dfO=@ z-&l~i;YHBvf(ri9UtU_mm=9b-rRrGGxGTBN&j(~hOssfj){uamuaLo{`8g0eYsOJ< zqGm^$W(u0NX!OIG434#m(&iKWU=qbYPhhhTJ;k!r%fzbyo{gsaK$pP+ct{K<K8M%W z^XfqWvB(uNhLV{M=rju$LD2av#-N4nOrk!rsdt&>kk$F@wWW{Im_f8bUB|S5%A-v} zJxhnp_;lPpNrf$=Pc^o1ybp*>#_ue73&OyU`ts(*N1S+d%m%7GmiaA&)W-nprB6i0 z?mv!ysu;Ov4B}kR77fcg`+&2fn+th~oq(m0k$Mw)X{On<?6ahh=&;Tj$SlnppL7zL z4@DGg2CRW0hLc^NFZ#8~Mj-X9%?vKG<6$!MRJ=$6Ukl$(jkwVeRXJbqPAby56-^qD zx=j{qNZq*p3J?wUhf$Lm@~&wf!{z&?^&(<~Br9fhDYWGO0LS~DKR&%M)S31M)l}I2 zkmZf=b8-Sk-uX9|zhBakK^vqYx&@}Mjfq#TfS;$UN@%UHrG&XUzVW5dc4513ABD8h zJx)+<<V{PwX2kziF=3*VxV%V$<bqKEXDGmN5!qWIZ`w0Q%(URQ^bwSeuPG&mgxhG# z#>F>SqGo9A<U=R^1F9!o4zkQ)OL<eT?jrm+fAxYzeAQ)Pc&w|AT*(0a1pPI@lUE~= z??V2HciURv{Wx$e8<`xLk~WLQG9A0qBWft>@Fo}bC!LQWV@`;zFwolXe9>dD>fWTb z1!Ke7z)3uu7)ezJomVp?a{(O?E(Jo&aeHO2A-4+65N>%Sf?)H^(Qy+!Lxd-iZtc@R zPAJVX?Acjk1iPtJA~GX7?^O|G(|D7Mvmi<sXp#wySBI#AWT-6>dpGL)-LW7z9G*9M z@DDhE-BGy|!@g?`X0_v>Y_jjHavDIboQVo|Y)|Ghku6PMz$r&Of}<AHz-Z!Hi}pWG z;=#UL?m565!tMR6uKZhUy|~a2il8b#9OIy4cXTcJLMwDu8rUDgl#Q;1zN<vIA&3Jn z4FPR5csD#<t-;}kvg9-gfSruKfo_QmuT$4sd8%AWXUOrx2!<QE!<B_A<{9^f+aS~e z;?s%zcgRwqIVtQse99RgqaPGLb<(=;Na~c1EmIM`mt}V7&uV?^8hHG;`3aEGIaW%m z`U_cM#|6lgd&sDgHK_thn-5sPHdW91!PGU-|FJ?B5Uo(HB!D8))-aYn9`2wmiU<)8 z%8S)GNs&TxdscJDC7z2P^29yBMYPfdbxr;QyyFAIx^eh4sfl-!ZAU+54%a%Qtw}NN z4pia-c8xuit1wHbY64tri#S3?O;LrcyE21A+?H}gD(dkV+0q``@<6)8yp*TRkRddh zXQJ*MydC%-fDk200WsvWRbjPRzv7+B6%)O2v|It(UPik{z=BTW_LcttnE<#VUd=a> z=Fkg~`CS=EW9U1Hvx^xjs@}fo{?jl<&p>kOvw%sL#dTxuU!_4=%n5@HeoDH8Ck{Nb z0YYPMfoyrv1uR2a_K7ehY$!12ipk`2)iw^Jyqhv%SWG#kD7X6zkZ&Q?ukcvq-RT9- zw<~awdn#u)TNP1FO!$tn@xn)~i6GWlOn>klGCZG9-y}Fg&5FTe8(@oc*N+{sSi}lg zNLJC>DP#}E=NwFj6PUOl8OC^;-Vvr;Sa@<5c&Hs(2)PoP6PnJZxD`*|g>(+NhCm~` zcKTcCh4CGIP~_OwL~=r1bX1P`1;Fjdmm&q4`G3G;I{#Q`xA>v-$lV_ll$nA1RIxaO z9m#@cmxINVtXw%`nO2;h_Am0msc}0QD{hyBMPsVmBQz>97fQ{barRi<@dAUxH8|M? zdY6o;HO;XzrFMz)heZfp!sp5wsbl3d!4q7rUOc<9r5pcy6+9#P#?0!4DPQzpgN;Tx zEj?XOu8A<hO&+Xe1CnIZiWVfJGaFyhV}AGD<5V(NCTOqt#}H0pBgvxP{m2(wN=O&q zTUU4{COtTkYYx>gjtB6uV#iIkhtzyXd%@Psp=r`CE*}C|1|J9}2ZvZU$Z+P}lIHiM z#@-q3>t`z#=kW97_X~qZMSKjP=B<qx^Jk(aEp5DRXWx$odwwnITdtGmG#gmupVX(; zqSUo$soR5Lmx1%Y^%pk+k!3yWABUoJgC|m{7Jw%-%W8#ZVNtEML|P7}f!FWzA${>* z!9=sn4n9Rw2J5XGIA?r6O*CCwfUFSsoiOA<i(Yn#<`TqOH%l8V;cjI0VCYWO6*dk0 z4wvSXp&Bv6nHJ+9xw#n&WKZ$0qI<Fycm%%X=V&+r!n)xQEjEkOy+Yo%WHHR~(wFFd ziGP^BpdJLS#R527Dbs6;U?Z|mOTvp$qj$u|Xauu@x^c;AkGOCectr2S8B4Lt12lAi z?U2L49C-<_8f2rCJEt617%`@Z0%t3V!{a5L#@!j@cQRG}TLHP#qk&k(nb!Q4`V38$ zK|ftMoV2u@?rmXcTmzlsbq0&;Li#Or`9_u2>4Fr>QZ#k<Zb#DdCInx=8nV}88n*!6 ze8{G)+to3MJ7n3Vg=>gy@t|BbTn-i-?+HtHlYxCw54??urhpX>yI;RVrV~|+4KJ=h zr{uVG7+FIkSl4hwi!&G5$`77fm@*@WC=i<SWmlJz2|s+(SF<y%y{yu=!lnFBO3Zdp z+7<#k#WABrUX7{H_(EAkG<Rn6N~W;wU)?os50}uXfJIetvd;CA2*AD?D3$SyDNo{> zR(yu&pqfB0YInL$3!z0LsA15wx{w3Y4+~g34e&tv>C~KVnDVxFN5iIx>rRE#BS;*N zGxI;S&b(!6aIgqjn+yz-_cIeRm8FB0HVpcAaV1y8y@O_En$^b&Y_SdOz6H8~+CItl zsR+X%t5_XHnfiLB*##aMvu*(g^9Yu3(zFTq0Qr3?z=4IB5-gzwB2dER&0oe2*nBXQ zVLH<y?mw`sk%j7mBcmYs)y*gM^KsTKaJB$xuxNaMY|%b0j)#CFw`YjN_9n1^z*8Kj z3HG_wpD;@S7kV@AewbV*hMG}e!um$)gk6$wznwIt66DTC4k7#LLc;_-u$|n?%F1bh z;pNyd@Q$b;na~27DlW-^m(-~6HJrqK;L)A2|A3|h+6UzibTylUER<P1r1gryi`{z_ zBIbq;P3Ug&(Gzc%py?dO<{t(>LQn?8CxE$WBWt)0lb~VYDRJK-_08^Ac}hsSKV4X} zY<~ySa1K|Sa%#99bsXG=4PvupTCFQ)Z^Q7z;Mpr)so!2QW;)nsw7V2Qq>D#yT9fw> z2OH`;?@6gE6gddO6cvkeZw*GJY>y1rO!GBP5*1(1jPAr;;xmspMNm1`DXe&(gAf;2 zvHbSF9c+IPku+2U{HIl%W2P%QF>wUJ32zhNaB6(uNdU)3XX};zqJP1Db}?*&!Pg2b zH6pnbPQJ8U``#ovx)mMwV)kBdIbGw%;H|f$>YciI3A5$PVZ$HnJ?#~zk{q(ewbV)l zC)LrgpAjkE1}CT^1Aot#TS})(%Pj@>DZl<5B>XKfN~uL5adf$D(ykR%=3-JF+<UK4 zjYH&>?)*Dr0nOS-GgikP#cuVrkCyql4BvOfY_}?GhG{WS?*qre(ITJ{zv=uhP2LDL zvZ>h_0D7b@4HBKc(<am&{56=)cb`~BTg;W)5$l`p>4*P|z*s&wLYT&W505@KX57@b z5m!{kiGb@Dk3k2~JIZK5jd$00)>VvKwN1Io7fb`5p9uD3*@LuC?&S_uPq|Icp~KTU z&s6m$<5oRg4X2`nrs0rb$d<@V=!N(9wi4V*ZH;ITpem570}ynniyOmitmIRJD^?D^ zWbo<6gYs{)G_n>L?63td<j+4<hVEU^F$$P%P}AMQ*6Y)Vn<B*rIZKf;?kdG#2xT{` zhnm$^*eMy8IEY!IV)bc7p<CUBUl`EI!4!8-VrCGRir@ABa-I^lkZ2P{=$uf8-PQ;~ zjay&%tQywrBS)YGz;sx3hNBFQ4f4)Q%PJFFMZHQzoVm*Hgm@2mC4zyY6MzWNk4U%t z`S4so8%Fih=Si^n+t{9Dd;S2q;{fb(_TBIbxma9bho&eh4|WNa&y==jM!jM^?;MSw z?;BixfAqL!q6R<+>cr_q{`%B)ZqkKR#tG&KgcWAg)XfVTE=zo4$`f%G2x6CQ^99Mx zqb^Rtg&E%|yTJEzLP=-4jTXx<eICkW_uzlU>cO64mL`E<QUA6EuEpnP2isq?UA0q$ zx9>UBrZ~09&QU%-8_HKe><<D^6KBvm-QP+RmKLK+X!2pY>@J(`6CY3cTa3#_f;F<% ze`{}^ForyKs`KSc`WgHOT>2@N_#it(BE?8syza+^8~w2+wbnO5%+fyj;hEMJEKUi; z$UGX}H2%V#YGB^T6w;1XNRt7<%UU5JD_mQd1bdLRM6;q$K$u9!nZv)|T)3`tM0+fl z$dKEex$)cf{n6*@P+}hT@4wQnUy?YqL{g_Nw1;u&*U()q)NS5m$b&t%gxR#@V=mVR zMpr)Z=TVSa)T}Wvr~4980Uz7HT`Mgt)V6MAT_U2|%QO8<`is#=(!__CH~c=hS!G-* z5E?iiVSs-OjZVQori(reG)l<1E^Vu$Kue2`7sO$A2_IrRabPlXsZjKDu)6ciApFDK zx5m&(1^3RIl!IlIaNDly8VbY%v2gk5MnJ;3SCV20J$3TW&F05Z0qu14Iju=D4nw;? zY-8XatAH~(VI=KK@#WgQx%NRJ{*mSWSi>&%XW00S1Lh~$N2ID+MbdZ3ZZq88tFd<+ z#(HwU#KZk$T0&N~MEXBJKPYIg_D4r=!!zs)ByMU%M~0H9)Ye)*eRgeE!2MpX+<N=# zhR(4%KS&R>izp>8d$QudKgT|odbX(7Mx(5(&%aK|juAYhh$d%`;?1tJM&;)=!_E7L zxhuSjcl#ZcpNt;YT>&M&cS;9bwr)aCyt;`60gkb23VzLZO#;==+hgQ}x4#DW>iU^I zQ~dTmexH_Z819*)=-S|mh1}w^{{cZF7mlB9?7Dtgts7w+$wX-*`ZO21XCoRt9qi{j zM*sj2f<e2#45l_}ojcXBjG%&JMLX#+8H4X^kT<>L6x~B~V~k%jDf-9)4{v`+{{j1? zEyJ2Vg<&Iz-L=y-5hEs+JbTh$dEKW_y9K1sBbrBJp26j>+e+=rD@CPeQ0kh>99R*` zyhb22&tu1ztC2N^u3HTC(4NhDuNRQ+2`%0}AJJaDZ>;V5$w|&eRpyRgQLg@_0^jZ9 zGYQZ~j%At=rJr5BRsUo~DV#o)N!=eVFTr(?yRco_cN5861ZcD0&(N;X3^wgi9nzdb zk_pK5R!<mMDx|VPdz^mlUUcG}5p%)tKUnBU_1<4x|A6U<U~T(V{V)OSNy&sQ;f0g+ z8+aGTXHWdzjr^Y3uwyfL2>q-l)-6on?b`r&3Kh(2_}R_E>fJO#Rm&Xcrn>QA5(;+U zGvO)pZ@eO@KKq+w_Bsgcs;*XCl(E=wU*NquS)JEHN{HT_Unt6{l}Pyyc<6IL@4KQo zc!ByEx7l%T|Fb5Mrn#*sy)ad-#KUuLv3;l}@88hR^LwBC@1PouuHEX)VoUvA5PZ`b z{?{d7(~f_S{PWa+FlOQDc=fx=rLq~{EJFoAa%1OVMAg+jRhni)DrwF0!KAcG(3Wik zEz>u2|3=8(a4zM(g#Erd;GL982|v>uJECa67XGMxe~RmPWQ&c{e}K?@m&j(%+Kcmt z&%Ap9$@XuF7#L%N<|m``heBHDM>*)-fz7_P7k(bdj*eN7d8DiZ-?IDB-EI8Hwtv%L z0P`8!AdgBG-_TFQHamPSPdZ@qed^(6OSpA(%bfA00O=P3jqePt-N}{5$kQZh8s8^$ zrVK>DP~Hu(Ul7y4_Uf)FbmO19M&LV8ztaDH_zQ7o%eFrIj#1x*F%kudY5P+!xHqeU zG!=*!z%$&h?&iMHy47-UE(MWDSOpVJpjrODr$ec6+>lVt5L_vsRX@;*X_4zb?R=r@ zLMtY{&;#p`q4VzU1oimn;2Uz?(SWv2RbR6p<a)3x+OYhDw?(ZnbooQOTgJ6n{~E(H z!cNQ1{U;weSimUZ*9w2I4i2<QMGM)JsGu1&<$6+E)l2yCF}l0&Uu+)ssK;ZY{S<`X z3VZNV;Ct$+vW~60|19c@gc~{NMi^k<E__D>>X}L`@myiBz7^*9HJUfE@uB<y9cWfZ zdG{y3pkMY0O~5{sjWby{1l*Rae)WHq40P+zktN{5RGL?Z$`ww2eU-jnX76calFfmz zn1A%02_j9Iu$pVvq|Os`8lR83Ep3smzm)F&b+gRtbnFqc6uGsnFcsAxm*KUmmr8CI zeo)t>P4TWA8@$<g$NB3c84$jkhuyNxUw?6RbE|;GY7^Dn559r~t+^GSlec|dJ66Ks zOu4EnH}fNHiQCzDwV-v*$eWM7NSkfZhH!J~x<?#*_j|tc@3OP~zzFa8_y^_+=1(`k zaUeeBT3z|)e;=sn)(*wCp-vf^0I*)aW;YAcAI9@mLm=B_6?B}86X3r@XMET4)-6Mp zd&BT%qj7%^p0?DTN`}Pj?S~;&INcw^8<d^P@3F8rJcMU8WVHAlepSSDm=^vO1QB+V zb?3{FT3SB`Ftgdx+2Uo-f5i&3ue_?gWAzjJSM?}7an5AW+wz<ybO)z_*Dd*A;qHDi zuUPTOV^u1KEQBt)@$K91=cjA$9ivIg_g71_dh1@j!Sw$(F(G5;1GuvF<@<T9_#S<m z?B-v8huHx_nhRa+BBP4!-JEUPkSkIzm?~l$=()9(f^cH$I;)3fX7cXYmn`ja2#I1d zs`S+5dK>g#H%5_^l&;)ty^m(Y>ZIE;dga~BWB9z0gS5|0L`cXs>Bb!`Bh%#N=wx_3 z7TWWArI10|+)kR=3R8k&-Om#U*73qy;w$qfAb$?zUWc9g5mDVli7<=f?y-=&gZ4hU z6e4#otZ@3p9hv$BO#G1B9av9Y5t|@=n^@-2X1xTS(P`!>S0)DZKF}WmyW<&k1cS7< z)WS$I;uHbX1^(+&o`H>9B1K1aIy?j4SQh!>(SfpncyRFd-1WsGH5w6qS|(?iC|h3X zoPt-=3mlWU@#DgAlB6n2M@}7AGOZG{(swcMrR_-c{gwvf6G4OJ1q#R^k**g9zHdJl zMs+j{#zPz(QxTkjH}Wbx$JCB7kG}#pUmVN2uR(MIjye&!n_(&k(!`Xv=`Lfw+;oX1 zuI&Mn!)F=uNGvmgF`?>pQTgyvHJ|Y|mN)<F<JkF(ZSUaBY|8Qq_ZDAs$svjOCQymB zxKEe${>Ghh^6d<kT;UCrKL3$@O4I22*(`GmYw7K`jELXs@Auh8-8_EiI%a-z$s4<O zAb1y8*-?V-Q!2b((!cT--}sR4!anqD>oC(2#--gi_2@mc)X!5?65`pa3EqY#P-uJQ zJp<$u*M~m6TWr^iY4HV1cepnXS1$|=-!$bLJAvL!cUpzB6YRN=_A<w#yp|FC)<(h6 zq{366<Hu=?5_}MplQ~T$x0rK7;NMxWm)u_>&~L9!%*YMr!e@AwP1Zq*UF=^~^B-<6 zy~bQ!w;7ocjb(ggB~M7@^KS!jB`jQJvvo!6wI!El*($;5exR6gHFxZvZg?)%cJh>A zWEZi58PQnkRm7>O(P|g0?^yG<TBgwc80mIFe>PlDWkOP^<V9<RhVZL!*1Dh$Z}aD! zC*yh!=z|ALSyvUe0_qtT6dqqX$1lbHVVu8p)#=vV$%Kg~AnjshZywJ6<o7ZlD^NiU z-?lsl^+JFo=F*kiEEaXvLnNmFou`L-{o!*9Ea~zx5pklDw?wVn5*6ucdHu>wbfW+C zPKm6M4pxS<b@kS_cF8rd^a6lgj>-tI(<0pKJJhB1)1*9-5;kw)tr}-lqh4h)nDy%Q zB*_qcGW&Vp*$f446(xFfq51wh^(IwSt*-5FPAl9f(7~Wmmt!H8d|B!->}9|cLGf?f zP79=&>#0hKg~KiQ-qs()yof5=ec<~`$KxX=%(GRbL0H}Rz}tJ@3MJCQr{U{N|Glyq zh6mZSMQS0~4TsI2mC^cRky?ktOyf#_k+r3ze`XslwHnyF!9BB5Y-mWsW%H3KGOPT| zjZSZQS-bcL2!w>gkac)>JE{C0T$Z-5EkGC3doU4uJUw5j38gN!9xTCJDC{Fe>LP6` z+TGA62Lmvy&m_y!@y1nmhkSQ%1XTNnGYy~!8v;hckXb2!O<l23(6Pu%;Z`a({tjvN zJe$1hitXoOY|icI+-a4w=<ELcuHE8P@+@|s@LNcxifn~JoA-j;M`4&=FogQzT`cXt zAAe3LUVhqQV6R1LT^Zb|QT0d2FSU5LYa^B^B<j!3d(A&{6w*C_bQffpDqTMIa`wGD z=i&92*i_xV|8KT$k!SupA3ud<&-CPa{BCjWSpIBlmH0s42@Kh@zEDig@<4H+Jpx%h zQU3nn<Hau(D&nMa)z*1#eZEZ9-LtGOw{w5k2^jg@oPq`R_MIDlK<F)}C7Y6MD5BzT zd6YgKB&&ok+~rsr!*KT}bTCiV*EGrNx7LDfGO6nkE^N7(cqaF$ac?cs$z$SH)f4x~ z9)=A5(bV<w*VSx<%YMWp5k|sm?5azg32c1(=j+@|d=A4Px~S)6cF=_BP15v+&rO;G z9*G&KG`doez}`-nS2Rd#<8Inae?)jWHS36xbCPDLQHe&b<FdCo9L1hUY6dsjY2Q)? z#pJ{zPn|KEeYnlxgG6r^S56POxIguI8&TEo+x^aX>Z1%~K-+s5a6AiHU6Z?C*_I>% zxxj(-uVFzh6Tfkgyo-M;yhY*@$pC$xAbT(6rhL-i6mO$1+>RvnY|uBd2fNDT+G{^y zZ_2{lP^aYj-rJwP<HmZ~Ik_BH+-hlo1-x~^=489n&S_7V-|Z%Xn7^c~o~5E&z2L4i zd_L`*yc{5UNUnn0&(3{tVdY<`j-!c)M5fpvw?B*P@Ll5J_`6TKIJy3B=LZSN?w;S7 z;DJ0e#Fi$hy88k>_4R@}W(UWF|JD6@Qc3q>CE52MZQp105fWVHX3K{!@5{g09+Qa} z=AZ)6uk%csLce1ITR`qTw{J();Ty%^o1m?1pbMm@XRy134*GLjs}923SL)y6u#a1B zeG~uwS94A&vq6rPS9{n3ap>k79qQ@HQ`t^?8LIRD3jAgaGGs3ajXni}_s(o`7E0KA zzY;V;D<?VvIYpqJU@(%hC7q-FDtDmn()o-q0J>!t`D}w`l-l_8#N*&hAfFaq&5q<+ zyNG)3spV{eb7606!#c|RXQQWvdgv$Yd`k!qr`lhA#u@oE=hNyy%yakFQS%Oaw}*Za z<s%Q45QBrCXOR!L>@H5!Sl|~=MbqUm4kLA!td}%`OKCNk7dIy>eE<5+aC^E-lgZv; zG_&NChr|t<NNoxqo1at8y_x^}+C{qLClmH)Ei4x%#30p!8eFsTSPZNOL9((pmVDUZ zLpsbiN>EZ*KJ^r-_Oz+?aN5mQfv@caaA?(b7~bBlsV{KGO*n8^RWCI@)0Blp{^X8I z>KmS-=o?KOc+=9>K{WU(3Zby&LJlv=dG76d+XFxK5mMPOYi?l0yH)0#+xeh2)@8qb zNkKxCjK-v>2f@O^+V+fx@ofD2nl$nEOSQ(f`iQN=#h$Y6i6#MPsv%t8Pr73WQ(2+* zz-F8j8M(?`dH>Btx3m4sQ@>%0eS7U$o~zSe{z;L#x^PSK#YIoiXG;gL{ifq4Gpsz- z<l-{z^?Rb#%C6hd@djifBR5#DAnNOYN@0#6ZSFtdY2dl?a`vurTmR8#9=ez_-9jbh zZ^g1S0`IKJtfNxG))&q-sRx~FObm*)q#b%$^er0h|2S-vj!xeLspgGE0*)J{_8*H~ z4eT3r?!-eLkIU7R6B&qriQ4JDhnTe4lj`ve@FzCneB#mE$Y$@p5Om?;^Bga=+8%!e z_FNQc<EM2i(-I_poKx~cM<?_EM7{*Ml%~3|5YgaY0_W42NmZXQyep5>jM14@1p8pW zGyM9|nXg&M;o6jpqQ9u$U))RG4yZU2*7M@@H78P^#AfhUS$F<3G^+@qy@q}cVoNV{ zGURKkG?bK2JQy8(4$4S>YO*FG9$)yr*PpAPJYeaK*rrw>M^YyKv9dq?>`#;{ASu87 zKFfE@&IRq_to{CJN%)@$X~(ouJ_~p8Pl9!Y#<~5hf+co`FLIXenrOh=uAIno;*wj$ z^k^o^Y|%09aOF4M!y2&{mhUi&TqnNJKO6{nGFg5=bI6o~%8K>cIHU+po8x|Wy;G>J zql%8-YVe)K=c#5;uMIfeGK-@B(;yF70pH6ahXtc_OWDm{?SvSMvte)Z9A?e0y)Ert zQ9YV!bv9biBA%U5h$HZ3ZjBFpD-^ndb--bn$oi{D+Fg(LUwQxBaAu+NblAmU{dcoF zw!aBBwf%P1;7!Hvu7r%RyFK^5V;mEb-|~6edEH+c)}H(&`2ZI9eHznc_haBs+?R-$ zUv8+{3X2R0f}C-Ly&datXh`)1K2f0;YkHa_vToS@0)N3%aVZvYimDW${YiuJenokE zV#b_M*Dkcr*}-eKhKc#8FJKg8c6C`Iu2k(yTf=p<oDS4ehc)haBUGSlIsC-F?+mRi zu|FXms4q;Z!kuH*`WM%dD5yAXkpH@qQ$I7+LZ&qdR!=>?d-Y`945ri#@&LMNm%rD2 zKYHSAt<d%Nyh&h9mc$&xIM^}gmL5<dL53h`e|)|0h83}J<N1%|u|H=9$bJp_V8}k- z<Lt-)k9eh|Wa_~*Cf&DwUAlGS`hYApQKLDVAMCFLH6-U-axqauyV<;(wm+qq@epYI z&7);TZoT-@OWS32a+T8`ubaI64{*<s?!J_VKOxwv!Ypp$3y~n&vu4`^e+T^$Kr{<x zX2WIb(^hu=%^7RS*qq`1FGl8baU)SG;N)P`ITsfUdn7l*^kdfT#15IkxrnWw<|CK$ zZ9i&J_T);gJ}1-{E|{^;TtJUoP(hfM3rXVc?Iz@?_V=BQBHazU=AHSLsgHq<Ow@SX zss*jB>PjW$KS1td<lZ`%bFR)Bhny^^-TQTA4%x(4Mq7aAF3K_L^K2L4sOIDE?+DLC zbNqJ<nd6Sxy772-9|McD)jiwIngzqCpq~If(5^&-wr14<*;wAR<H~Iqgi?%;4Vdf7 zG0!xCxcGqxKF!Xdsqpn4$`xR+v?5F|A}bgBPv;N`>_exAMxzyrQJlDm6Xsb#oXlZm zJWCE^;R!I!9&+&QWk6`UI41MLm53Lw(5UYB#f=f^y$ARzu5v(Y@{y}dhtY8hIYA3| zO7L1fEA?3oD0!GW9iotWasg~)6I)Ig#yF$Z%h|NSb_#PxX=cIC=sqAbM+`Uu(}zUb z-huJ2{CQU!9#vq`zQd4$n8Y{9sjE~d>igkTT-WEV;w4}daV20dc93TTAh#n#yG*u+ z^Yu*Vf{WC>-ip({oe`*DbKEo^0asIKiD}qX*&ifVWz*3Da|Cf6$yXMe<$0jOdKids ztm;l;I4BwHSewEpT`Zv{DrW2~=eS#gH)-wJCm4Vjqifj;WK!c<;{*xCa_P%VOU(Dn z-0nAiZc`yw$%ZZG0*=4*F=flC_~?Ja>a(*NUx)IB@X_-TW`HwC-p^oFMur2n?`GCJ zO^OSsFBsW8V<={E4b!5r?47u?f^cX{5a5T}D-;*hFlE_aIoN<o1?TRomUrQDT*}4Q z!@b&4>=uyco>2l41-;s-L!{li2D?=u-2qHSFo0olSMrjw!bi;v>T=JRI5Q_z)#Wl7 za>_6$zz)1&8SYS1kpo+yLr)lu|F|Gysae0HtU2(a(_H6h8Kfx>uK~M3luTGAf(Bj) zvZloN?AP>6Ue8P5S;_hrAH2v}Qq14iPp~U|DYU=d5h_n=Jqo%&MU#7-OiOsq;wMoJ zqF$|&(O6{0F1Nzoh1OIwWtxHzWm9n&?hT+@UHqo!ED_}Gnmmi$G&SPRP$ITU%|=OS zW05_PnITtvV|=tIV!KqZ2R0>565m;2PM9o~3n7A(=qYJn()U-=F(&#RT2T($5|oYL zix!D^xR(sP;P>zrQXysK9?i_KfXd8lZd;lxt7CeQnf-as#%*mvxe3(W5`y^T&i7?) ze(`LsVW?|KhnCqIdvqX)vwUr`mG0s;w-uh*`|u-AtYN^w>or|)@?g4)4xD8vaLQ=k zaA{8#Yc+=rlOL}V$LvYHuULnoWzY=xY2ei|ZEmsHpS%7gU?n>cD;JCi5X@MHp`*zF zEJ{%43@U9Bu}H1!njp(o76)Wit(&wE)=vMjJR7r32OHYV;HYFUuu<j*<x;T);+B&h z3N(jDbzlkIevRjCvfd!|l(k`P^N&b{p4|ywCJw`kyU<pT3kK_`>9o{8)BWrUWFuKF z@q2%ky*CV8A>Md^NLBc>Mcw;TX@_t^s6db$oWGVCpxp4cqIH6-F!VG&8{#AKIox?K zyzE>4n!dL#_`my9!PW7PqL)?c#H%Vma@{xGO|PalD?>0QtuL}d&3K5(cz?d55}do} z?}EU_?B#=c;$uy8G{U-d^Gm+DkX3IM_;%l_S|%I8<hQr2elAth92t)7X~PDg>_pgE z++U4~BfUNn4x=EVRr!uAS*3#_KE}y3NFIU5PbG)al{N`HW>5Dk$`pi+$T~M;+G!J+ z0va!brPD-AUEDJTB@EJ-%M6ari1#~j!WszocUKFoj;{0tv#0_l?Qf5qCCr8VAs<u` z?(d+i!XhJMaz-L;vQl;6D@++=?^r8CJ~W3I*`>61`vsYJE%wm887hfzKxUs3|030F zRbJx0gZe88v91-=DRUgm%o(xrmyh!+$(!Tdi37cocv55ff$(*?h+W6-1VRT)&O)U& z13>nwp5kBTQO$$cpD<c6mSbMSGf{%rtq{w*;wB0h_;$bioTY^kuUVa4(ixuKg}vnG zWIEU@9?s2i$WkMfr~AqK(*@)wb)X;j?0rF=GGd1wZ<sfyPimO&w_X?3k^uamAj^8G zFuq!p7?~b?1rgQ_(g>@9yZ5VWiBiHH(yb+A%+mvys2D(byl(6oGlKa^JE=m=$Ok*w zW9m_r-8x7?_*-+YAP;?pk%mjAu~I;^w=4LJLbHJghn2`!h^_4^jsPmS7sT7O3S6N} zr@Ncru59eSRwkPuffF20%1YY~S>cRC8BN^$<GunOTxLW(?J}B;%t?DBqs11jCHxqk zX8y0bL>3*E)blw)!c3#K8D{~-J1*qy#04NF(1X+_up9hACyXJdZmbB7S(dxV?}AqJ z#UIHjdAycTL@eoY(B;xd;mZ^l>hCUXoP1eXF~XjmC=Tlw)eiwZ;+)Awl?52Eg4pVH zZ*G9PeUCDBk5CJ-cHAXOHWpY)ky<na4U(0vVqF#cSMiU`!RXJvs9GZ1hv7}Q1=7#p z(T%h6T9BEn9@O~dYfXan*w(R~(T;p%2HuQh{fA%vBY-Ifl-JilXGA)sZYD~PNOO*~ z($pNcT;tpW7R^0sYQ0Scmsb_ZgjKm|SN6X|P+qL33m&*~^+ceb)t=Pwh_h;|Q;n|w z#EYdd0lmtxkX_}f^>R43oC;Fm?fJY5_wCmPg(W)kzJo8>(3zGrTK?-LA2k@%<)`_2 zwBtw7N?4u2de9e<q#)}2nT&^C##b3sjD>JM0WK8LD6Gsh?33mkB|QqezL^hrl<dvx ztEuCB2huu8=>c4@nd<%n#XpvVHv6TJ5h_N*Dd>D|=14EFex*(oDJu_lM@uxmX3wRF z7!$v%$-dsSqqEL2rMhj>qwC1RR@4lzN`$G}Lo**8Hz!8Md*1{mk(sr<BcwkRWF-eA z>3%($Q1$%e=x1Eb^nre_;T0^n{2{Z<o~2F!%8lBJG>fS#60c%)+Qx|8ugD+$6v^V? z{Kq_5lt3@GUr3(={1BEJM#l0ePfhNI4IxWaRB-MZ%`9NNTrXCgk3vk~f}Y@^vl+Ru zLHwe7HUjp?P0&G#Air3GUyvUGDmXuRX2Fx8{ha?1A<y^kllJ~592z09S<f9v0F^VC zBIQ~C`pQ}^^ln=VAoqp%*&s#Ib(<3C0WwdEP$_`2?4IRoBhz&*bNpQB4}eth>>)@B zqSM8gQ}WWYIKA*>H&5}QU6_}byCt7sTbukOGB{ukwAcmw2S`GTnPvf)%&(IHI~zQ% zNxi&+KaAd@GaH@^7-!09C3VHlhV%r%IRfTJ78`y!n=g#hFwa}T`WIzGUv71TIEL0) z3X!o{XaXn*(m6>o0luA$Ank=GKjiVJXLM{z4lZTKI_Ww?IF&q`esTMJr7UHbzIbN; zY4Wr7rTt&EJ6hB)7y)DJFmCk4^bbQwsa>sJ@{i6b&wbC=_H1$vRGCb&1Nq&M$rGEy zQQ}=#){@{$b17snF|+Ol;0f3g-dA3u!YmeZj#vOu74;{VcIr~4#y@G%^$|qw;38;u zj;;xaPFMA%ErSeCir{r)Jzp{|R=_xVDjU<*=803D`~a1hu%dtty)=GyWah{t@QOna zY}j#<>@9Z>04q+ohBBMx=H@1H$_BSZ<_B9q#}<xjqsoRcWR1aG!ws^OlMClQ6_Z)p zn0+MNd{B0y4rB;>L+4fp%r!wIsN~?iW5wzcMIbV_WK*G@$#8tLCzZ~=r_&Ol_8*W7 z#}45iLYP)7D-)o_S4F~}#spPsQes7?5VQLkIX>iIOK|Y*q!eJM67kYX1`)lC`eF*Y z=3g8Gc)f1hWlsMAFti+qd07zNG&sj&<(?^}V&VbNvMy~YUO6e@bt6zVz)xWz3}a#= zElNORt$P&wca#ZG@k#&9So{e~z9``V4d`CQ8qW+xXAaBhSz{>jvZmYpyE=JGP5-)t z89|uqcL5PhEP{vz4><FePt@-)MPY_L(9M^&ESygelxyq-I=;l+qx-zBi0jgta*Zjc zblg{9h=g6`dUsJfl>p-6Ye(!fg)p{)WtW=)vhm?Y(<aEQU9bCBk9ZH4Bv6eakfSjI z;xa#j`2+<t@7gOV{*GiX%oD_AQzu<zSRI48@@)<e8d_j-_!LE<eF0XiPin#fX8%Xi zxyLiz|Nnn8Owy#Nxs0i~LI)Y8In3zbR5>3yC~8V4hZ%EbxKOS&gs2==4pVaI;FQx) z=1?Y-Gt+2>In2Ts*Z2MT-EP0X?RLX^@7MeNJUkxv$CLe(Rkdv)s8z7smrc#$UG&Jf z3MjdRIPQqj;gs&3l$eh<<DGYY%ub(UB7k@fa`aBQSP&rgNYXpKwzEat0DRqV(kZ+1 zCI5%bwvm9S4}<V2&<g<8+)HO&a7sxO+KjDHZA|}ituPg%9^@1QEK3d+7<!V*JB|48 zW6Y=wq?|ONj)EZO^+}KwcQNlOt76y1MozXrai^5$y3w<Dc)9Qgyxfm(l+$DZ3m#IN ziRYW`++;LM+nLWu<YqgCZZAfp;B*e#J@db$#MRXBp3%-Sn@|Thjib?kq?g-0dYFq! z_G_W&?*<{*M5gJl7wx`b{=hQo!^jEA1E*=nJ}%BtNZetvQd>{(Zmf(l(){8i`2h&S zeaR_TJQ3pg?AjO;xR<LHIdxp<_67$|llBC+1K#_(z7;x*z<{DO!t9AD<_nlPOZABQ zEvzvfu-ouwq@{_~6JqVe-x>f9P?9kB1$T!_;3zXEFZg5!Gc*ku00)}Xf0J}$Fx6Th z=i3f>ElJ=#kFx8WH%M#W$-n5A;jbVAQKy?Hdt3pXuAK>%_pl)WqJ3$J1!U_);i36` zst_Od^0AKXbpD{|AwYjMem7%mFG2o%BZQs0J#f#@kZH)vB_p>hvFRM&@!V{#Y5#bc zAtGS>AK1iWkUsd7lzJov5&oTOj#F<oA+gr&F_WPT-XGriu0RnLEm$?}2gUt1XNWQZ zuV#O^W8>va%%oAdD%Lc;H{b7DC6OYxoSQE!)Z|*U^;pXKhtMR|X$um$joTk@o%(|@ zA&e#iJ@5gQs0SyqDM&lN-t2bkjv4)w|Ah*n7@{)~-^AC*fM~40<l#t>8^#lGn>l<S z1)Rc52Ck~5ulkqQR^<UW#zK%;>y$UX9n(B}I9M|Z)-x!nFpxZb@j#=a>4Jrkf7Hj_ zWnfvC1pjbkE5OTVRDT`x9b9O#ag5=BA{z5NZ0>ZZG$l7i|3l)P{-iVdU@k7L8>mYI z46Gfkn9is)q42c~7h0mz6Xq!&mMnES-`=8EcKK(viWfPxdUTm;1e6+0%xNHmh)k~@ zs8)?XBv8!oY_<S3vk<p)TGg;w_$s5Qbk?|bXOl9j9I$*zGBncL<jrj^M^-Q;(e2-~ zKq+tC^0Ek&&E?*-1P5w1N!5~GzHSexXXx&ju|>~ogEwiO+3aL<+jHkM7pT(E{^c(x zL2_nTTs;nubRPQA87(0vPZP2PMah|ee-d_wZAK{_>Lue1RUb{QFcq68NCBZdiY&;k z{>4KM2BQr3n6|Od-CwTh=f3F(qL_Kw03f|I^U*oxw*lX<Wd==Zq+SwK7N*4kk(f5p zKf41$0rt6CY?jzxT0f>HTS^R_c2sJ<LGgqEg{}q3D>ff8f>>ov+R!o`+MAi!?eqr4 zT;2Q{;k@?#1eF9kgxY6nKZxP(dsH6bwXt{5@dofB&1urbnnS7%UwjMe%boJB?oD)a zG)Q|)_XV`Qy4I?)sZYZ2gR-|llbL?e1Y6HJ!68HQx?uC%mV8-4w}q`f(Eiq?AX3u? z)cSw41KXS#9IF)f`{;h^Ga+2D@1JSGRXBqK1+4o(hgrj=Nu;Lg+H)`+*mr~Bq~b2m zeOy@sd{yKwY%~e#4=8eS$@o6SzhK?AtH#w!=s}<m(b8c16LSF*B9>PS{#!OLb0jT! z={5Msid-ZPh(&`Swb~`CZ-}A~%Ny>Zc$T3@5P>f(zv`JTX>1ZKh#!z&$kIkg4|=8a z&0UX~XKIKeroVD31e{}O?NF={o_9K%&ED7UuD}{t0nClNC5GVbQZ*2@tUoj$%-uIp zGS4jB9um=h5H&qn(`5iuMzGO9#Y7B7-2lxRbN7r+v~h&}iTwPkVh$*<v09*Ooo}rq z<@UJ;&l+v0^&^6?4<~Z9d_Jp=Hy9K8=4?h{jt)V<)!;Tuzc#YmZbAwWkK<Q}wp1bX z3B*!5Ju%jd!PdbI`;gm?BM;m9wt@57rn@`h8v{6l=?!}IU=|7@&MO3I&6u$+0Nm$4 zj`4Hx%+uz8zWh|vIJ^y=4Df}a$X4<HCYd(6()*imQzS()-cM7GwE3H?aZ9G49OXNW z6%_*}=(s;q1Qz0E-g{dP1cO;E+J?XvH;90qb(5dXMQrp)yLf4u{0EXpZ1%E!5dhzF zb+u4Emr0=r*?~0an9(5Ufp>W;JX_3WgDx?*)inJVE*S!iqna^obIgjUqj)$1mS+Rf zWu>6o;m4BcNSi3O&8N+{k<_-kr73h0XpOf`uv^HFg;x<`QhVdf$%?avE(j76cxUBQ zOKM_RH-=w49+D!%O$U)S4i!rliez~piiN@0KCpqW!j)P@`Fs|H0CWY3MgxV;V%|pd zAD#u8)yGQ)l;0h!4na=M%`kkm+A9h`uqU!ad|Qw|431_~$<ev}WdEzxCY#<#px{w8 z@0Xlq#U4|a`M)x1+1r=$X&NhJoDIl*S1Y{Da{3};Dp2LoMsI2d>telQ^nMzg1}*Dh zYy`4|v{>oIPhhrMY+5!Io#)4M<b1EzVs?!nIc7VU7C?MZ4(o<3<49%qDYaHQUGaN| zeHIH~Y$u|Q^dkT$G<0w7=j6KNGj>e4q<2%L8N3`E<>4+oc?bVg)foX30l`OLm({ci zZ}las;w*qXjqsx8ne$v>oK2=E@6LwvE!&Wt3)aod=p`DY!ih=b3s={QaARD8VVexX zTfFJS@Km;lgcj}6T!v(Ol2!pMgn@m6=4<sZVc~QX9sscYjI~DUU>x$=GN%#RhH9g7 zVfGSxlbH*fTiT`(e90w$z^5QwwAC~mMJH&)F*K1GP`Kl097SzAkzNQoX~~+{DcHD~ zyFXXuKn3{Vb441DY=x&{Oh5jSqyyQz-Zb2ly+p7fz-^?9R_T7SosS1FBLECf5Brdp zbmy@2Z&5AFcPt*HWeB)$|EMMwY5PxT?OM_1plISdAPGy*Zv8DS<`Q0cMxI6kQG~~m z&rMp2g!u$mu+AC0p|H@r3HS&T&?=mYY#}WXbK`)AT-|_H=Vu+e3bnzaVs^II;~I@A z;H>bR)j-VZ!Xw$S436rCy@a^wh%Upa19)WJvwsggXj>W!%<LWbw;rVpAl;qmPth?e zU}^}fSX>NNyp_Oe7|w>xlUT~kG1FIRHG_-_?#{lY6Oj|2>>>yg)rz3qUu00wk-q8^ zKb0{Y6NN8u%y5Gh)1)u?c&?d7Ts1HXJV;i^mg53zBd#i1<dks+fmji&YyfrH9oJzu z-(QC92n6tFzPZ>QFi+xA)S^31fPS=DMtH%dlx8eB=RZmx{*3#UMg`CXVIN3hbW++s zJl+5R-~fTij@=gEHf&R?VpFgNERO~>7d?8?(pJrCqAhI+&wo0wroJV>+w2h>98kYZ z&2w^;2=@LDq=s$U_yPN#_OylKwK_$ji@z}~9OAch?|^MD-Jr^Y6#8(J=4_uC%bQ`j zi9GWT2>n>xa87(jGbmV-K54cSxIV^!x&d$UT760i+4{wzw)?8UG=0h^tDR+t<o1#w zEf3lZ<g+MXVZO@tnIC2c8l(`?H`Y#9S#y#LF<ZZyLUd&K&q2QWf~k}SB6Yl<U00{T z7!EMn!rslFYCSZ+244vGDco#$ugHl5RQY!2Fb{HN(||HFvC=Bv(_I2)A#IGW0LUyC zFp&E&<JB$g=*Lt-b**q7DpUl;8n~c<0EX;M`%d(VoZ`0H;1`{>ops6}PY(4XT_pen z+6E>tXQpFn<Wt^rO#Cg^`$M7><zfc$<%RAd%dZyvrl)tUlBaONCd<8K?T$+4gf&rP z6UWga*Z}=efr5`=(koG~;6G0TVV>TNA<Y}4;vtZWJ)yeHVh0nMckk<tfj7i#3P4q0 zpNNSJz;<qKtNoCC@SfteTaU0c;dd|9jUqtvW`KuHR<XS<tRDk#ZF(~-jl;tKdU#6n z`=>CkRq?$G)?y5InkyFa&Gx*p{te~#mD>@V4zW*j(*^<S4J5J$W-~?XTYBy9wy52W z1x|w^sPBZ=<2Ys13Xrw=U4cDa)2^x=6$D54tZt_d1cmH4%kld*W5&P4!rK;3$Rt>M zS<LKU3Cm9{x71&0oDmp0Z1WHUuhyM*1?$DN?FMeqU)$;<Nd6v%nwjQk>CHQVraOGT z?QnP^jae&y{vYU$allE{n+KZ&49WjMp=rOjgM^l?JXK%3T4~I@rQK4w`qs<0sDB;n zZ%&{ep6Y*q<Xo%SznC?!ZpYl|NSbF^242`iBYVqJ>*K1U`o1_kl5}#X@sz%jBhNhl zRI_WXq49c7)8Q@oolB_6Iq`*X8&s{1q8=os+sw?6yQCVGvGXjcp!A0=HnYim;Bd6; zbN328b+C%8V!1$VER^o!axTb!N81nR6Xr;@NNMn<bCR=~=d7NL>bpVMI`6_$t+YVj z)9>1(Lv{`b_-6;H4!RKEZ56DYN6V|HxD(`O{`*t%O^(}Q5Z)X1cIX?Wsa~#<DfDDp zXX1=qm^C;=;F0?MKhOb&YMqmVMvc8jL~>oWaFx+!S87c(YN2a*gLSRou9z94+;v(S zBL48gKkW>zD%iAk!Ls_^`{t;d;^hq0fblrQ^6)dnRre988{&(D?2T}Uo8#YSvUd%^ zJJcW7M;Zmb@$|0sx;B5hJYu(*>EJB(^<?t%j$FNHIe>6zYStLw4|ZkC1)>DMUVMBi z5)@3@qF3ajr@z=M#J-DP_^Q`Xg9zfe>Q=P*>yaXcIBGfX1`5xi&U(4*O0;+8i=yR$ zW<cZH!?Z4SA!->2a0gx8%aq0Y!oVhosi3(wyGaL&%>9oarpcB5KJ``l2ZyrU9e(re zu}@Z%QLiWPsU^@Xh{^2<1cGICZ%rQkIwy87!xH%RKgb1(s-J5K@hI*CHVC^Bb?uEr zQh_L`r24lCR8AhUEfM+VYj#Vo6<F~86lZbMXH^kCed$Ne3u2iWLuAdyS8%HC(tBiH z>hx^&?nb6sNy;<JBC$t&cb<Im_ecUhw%g4gX})b&==i>m>sbsradC}Ag$TLIsHB;) z1G`0py&r%&)-#A{{$)=FnN>*{b|=KB=t>5G<n2C3sg|5~jCdgE_s(hE><ss&V_rX1 zJg&kdzksP|cnMjxKsj>d!|@?m{^gzVlExsnJ9Eq`tdZ;8nCqvnLx)EsUaI3|W%zaC z?Tps+LsGZl%(4(HIyVfK(dWKnd;+vPktoOctx040*>vVyAD`epVjPb0#k3oL=%<i= zRY7*yGdEj?G^9G$=EK5aKYVw^dVX738ZqCjVcOm^4yph4WnK1VH2XRu-2d>`QaSC6 z$&}UYJ=o+XiMTT*)yZA(;ab1C`5K;G&K^RIrNF|>n99KF=Z=|XtrfqW-h1Rx%*8ru z<*7iVd2-=(uP549_59iX`4zKvzBpFl9Z&rG3rRa5)9osepO$B^vtzFw5)d&CYmj$1 z;AXHd>9d^PmkbS#kXvL$``IMld^PVp(pP>$rX=8dYCXO`ZLNw6x=AC+@O_#Q@-MOL zrEt!%JZ<=AnKh;=s6+x(tai)uk~av?%jHt+rLNxpAXluZ;><1!aS*xw>#p+1YN&Ge zZd(ilM2(zNBe}{FKjdZNT8siqsstq?RekNZIP?l`A?W<;YhU(dfA&ffNU55uMjxJz z_^aK-Tec&;MSIk8f}v>=<x&#hYF(f)?N$`E&^)kQ7Tl8P{rDj2<xS~vX@e!S`;Sv6 zs%wv*`GaCB#)v~7e2Lj}6@dtbx0hEfzKiYU5W0;4bRT<hsNt(A=EFnr2!FzF6T2&N zy13vOPJLKnDh61NA9(>-ra#QQPhJZQJ2zLd{Wa>STr}yGXJeke)|ZIyOD@sh{q0mT zp>tm%4+JLI4W)fKV0rnFeUmki7t?re-E7-koBFkOBciDO@C&uh!PWAIgBK5fq3XQ{ z8Rt%I$JYP;ee1HKC%fd-b%TnwsG9Qg>r`|BueEnN84>7o{niPe=^gExZwaGZYE(u+ z)LvyI4F}2xq$0L2!V)r(?ru|d{1Y#tG>REshML~H8cf}{qke2GFUfCP-x--ZBL7)# zU@DW3i(eK>f&xCY*B~R6E98F-y=f_N0Z{XDqV<DW`4kC>g*8TZNO^wLp7++1wJ9tA zK5lxlvf;*(QFeMl9HB&_J<P=FIuVAZJCtjOG2Jq7zur$o`N{mFI^0{!mPaNHsWLpI zE&3ziP=13{RW4XpVoMMOgTs>Cd?`RAPfO}wuK+K(Fr2Cn8*E0y?qxEi&n)eqobHT$ z`Kt2a7XD!zAfI)EAw$A)h(jAl&9l9=!T(N!V&b+q6G+>Pl>xp6I{(rkHjE2q!CQO* z&0mbiX~qSw_qVD|PgiSF^X%>|$q$<z+c@{o5yzQ!IvOICf7`DM;nwT0o;vAjYFfFH zWvTW<;@l`~6le?uCGB7Llfrhru)`%b-g}&~>#qy%I60i$!syJ(yH{m$T|xYm*T$CJ zm^s#kjUb7J!BUvAKJlz}oz$aoU8rrIoh`#N%<W9|4VTm(jkdVN1Cd+z)83C~g1kf8 z8M6%-4LJmLtmMtpvA8cM$P%<Cbs?_UW!?mktLC@2yR=sOw1$FprP;WpqZtzzzG08# z_vVgk>h1o!4a_;<M#ol|W_-hCYCXWThDl%_F`MY?uD|~&`TaIP3mtm%z{t_);aT}= z^J^cIjf%K-*bnYsTlT&`Q+Efxlj5&03Y>GDS06i`p|uAT)8Vjoi7@g`_~!jt-d7ug zmkbz?m=>N#S3G;=M`O>+f0bIEa-RfPuDb;cPJ8SY?m6{rPn9z4H$P?zedYPt=IduI zew{q9Dl`<9-F5m}uctMhc*iqjXX@w%TQ1t>NAK-B*R6@<20c?e6^x?Nk<>fKP_?nc z$^@0F9}e3PWa&|MtDpKK>vmc6NZvHluH{*g&A`4E_ZxX|RdgG+Aw+!m%a_{Z-?+dh z9=X|o813?_ulI|6BNA8kKd`(DdE7ZFmkoqIqk~l9&r*CCEyeSujRmgrha?{+oD0M_ z)(1J|YQJjhTs@(nE^QI8j`QcPCpv5^z07#rWvuvgq}yGAA_cfI+m!+R4*d{Ewz03q zQ;wQ15|)JBN$RLiWN2No5Ot^nrCJk!=T6FW_z!em%SRv^lVCcYw-vTaVUIP!fBQdB zf)i^6zWVl&-j@l#>x4hAbFKAC)d3UwEmdg4;eR~!Xa+=Pxsc{{f4Za?-ZB+nD2^^P zKe(e{qNRGwp<fN1{J@EL@LT0J&%_H4St`9$n(*t4&(7qAMIPTw2IZaD35Tm6_iwCu zBlx^WUcDla)x}zN&1iY3ih_VBdHB)4ULVw=JW$8EEPzy_W#!tRJyjf$AC;|pIHezc zyGmGBEqFe*Lp^3~^EkcK%N%3~(;eEZ75QWB1f_Gkj#}(HPi_~$K%VAI+iWjVv8Q{@ zBf8v>h)`4UM^*X=_>$k?;4n-Y1OKyHMh&Q1&RTxjyy_R>hCOlN<t31L_tm++B(wXo zr+zM~4T5m~zHmcHl8~F!mBBVRXw~^4lPA7}wU{V=^Ee~nbY2Uv->g|vy4?TifkKIo zJzHyp;u$Dz&^n>MiFq!i(zezvx#@32VwPUMgnE3|%KDsU0++D5;dEBz_buq$D4QC0 z^7c>6cKZk4?#r2J6e*!vzw%>+x~DfoJol?*anu15o{OaY`v;C!$@&yuVf$)nd;W^F zeUPetJ2R}k-a;APyi17Hi!_$E>5*I2Ge)1bbe4)fzO>=`^WVVR8GKtvR?FwGgPdY@ zLJbE3#ab<1<|9(CZoRDlZ<}46Mj-;Qww9(j#x9R#$LKZ2s%JC+*qBfVv`k~dLza%L z-@7}N!m`2DP`aH%Qg=iAU-E~{qQm?N16Yg5H=WNe{HtuC>{IuF;+?BM554zxzHIra zp@@oOyN89jWc@q2DD*kqrvD7=L)WC7TK}syV%(*xeLp6J3}WNy67PF2AJcK1MI0$} zR?E-x^ZikJKp@Q@IvQZb(b$Z<8}n>6PCZMlW>>QBGvws($G|r2`$5t>)EqF|3PPpS zJ<5NFUWFfN4P5L?7Tmu*vBS@V@!Q0w8>88$_VF)euH30r2sY7tyyV2b6@&RbvMKv1 zCE*-Im`g`}QKb{p)r=O5qWrMDE90T-)27>67R|B&UCO^yQ9Je#FHXw;X&ut`lW~L3 zyJFs-GPKxFjGKX8$v+acJk{K4U454$xzQu>Ciy6v>j&8yE?Kc!cQkju@o=^^mGL_N zmf8)7acbI3xYG}mi~C+d3^gp=Ui$H9Z|4iIR$mGwMyx@?M!k9uECFgN!Jls+@A`RS z<!!Q`3_*>JJOO@0Z+@LiTIbDxLIbKr$Tn&{h_(ysID1I&{KBoYfG4{C&@F+!%dt`$ zpPYg=TT(G%S3~5=Wj<`Eer)LAF&gsvvr^2<TZvzvZJX6{KvM`$dvb3dzaV$~>YXT| z<r5>R&58IUcCQQHj6~839Eo$u%ZksBG1CYqa(1R0%P)g4yJmrh^plaz3n=x$Gq)n) z!9c3FE5Pot(R_Ms-}sMfacyrdJLRW@vhZ{6-->TbV|wD!;_<A?psEM6y^OE_rbLf9 z_14Y}UAuL9^K!Kk9Ij#ptmb>9!@g<n+85>AreL80EKP?iy(uTFhw@v<7rrer%`Xqf ze%ASQH-zf!rVLjH^z2zBD<WfOtNhzv<)URd$z6)zc>NP(?^o3QKrq7a-nJ8>1OG_f z24BU#4|{^WZ?pi77d$5KpB*ysbUGMx`IM=>r|<vzb0i}5O$MfO*IRln)aG)1MKh4M z!j@m*yC^yCeDta5n_#*BuR}M15JnIOt}H=58b5B)V>kmi|H9S!7Z1E*Q_{C^$9*$S z7HL#jD+IJoV+CL~cpiH=K*Lixia2Am4Q;qB9azwsU~;NRe;qIWRn{_b$NMT>&>5go z_jLNxa?Fge19A1y?bIjZX94hYihQPO2(<9Vg}#xF_$jSj)G>4)6>W9rzg|wM0g6MA zk83kEGhQ%l&6c;BS%Y(uLV9ez8fp<^C|<$M(4{ZLo`ipno|Q(YQptoqk?W6-u{Tr# zOjv2rXIMfw?|OFky=a*=kFigdX*o&sb^ii<UhhYrkifBjybRk#E)7i}EcVU67MDR$ zZ@>6M$A+3!BR{wut?JP099)qZr7y(qWOic12qW3fa<ji!<LR01x1>YI`joNKhB)&t z4=z#MTgse|I!b)&D;8N6p?hmLEneIYWlrx*0Ww?GW{x;nJww$4?aRkAT3gD}SkoNb z;Yah%cE#d@zfL|NzdpEtO#sk9Eaa7|Gec!lu=)qeOqCc8M1Z?eGI?3~ALR#6_6K*O zD--Q9A%Jl2q@LrHC!&o1jcPb)W+F5R{8ck#acHnpk{sH2`9VTEl*aN+$f-#WRYA5U z|5Co5nCD=NBIuYp%6I?ct^Nmi6`J%GpwS*Dcfd?4^edCuIFwb7e>c1JC5TgH9Cf)U zW9Wb*I)?I^KX^0#?u8nWJ<J(0vRTrmmtVf_{Lh||Y`IeixuBVIk}G={j(Qi!d$`JK zIVF#moo_gO^|aX&uzzCiS~$Adnb`&C6EeE)k6b@W4&g2_o0J^J_C)+C|Ll6B>8|Hx z5;g8|E3}wVuF*KOT4}G+C96o0&<ou@gR}Xw6?%D1xj*kX7h-sm3Ayv9{J@XW)gxY0 zZS#~!=@4<a+lMogn7IXC-b>GGL!`(35lLj>%qj1h#j9?qN6p>t>!1_7KYLZME86tr zmCJ%{B)=Yjs`MBA?ARpBrw4Wuu5M5sZC8#EhALxox-uAWw&&jA*U!%72FYB`Nzod8 z1|-W%SC{5^J_{LdCPOid)h{=WhI`-QqEwBDBS|Aw*9K6(xtok=o98c-R9UobHNR^P zKN@}Vi^0SZ8k^uj%T;?Yvs64&{O|hBCTyeXxBozU?>>SLDf=|dCxD`YHg--fW?KH+ z&rbF=a!aIG=Bqw7Q0`ow>z2mOMjDKjl}UOE*_#_tLDvuN;PJnO9gh_j{@$=XolOOB zx@DNMLRCE(F*g6Lm;A{@4Cgm$q%Y>WAJOos1<B-{=1S>=!tCweGiT{L6i_?+5cs*R zBPlmk6NpRzV)0jT*<0&7xCHRkT%h<eNv`eFl%_^hxD_oNzHQI;3gXaDdMSu(9qg9X z(8BV4>jNB_6Iiuldkn>|{qpXo<~=>o&z2wnG|+P2x=)FA@1L$t#ulJ7vC*<(@p5im z(66RF?z1Z;e^)IY)RUJbb9lMX=_^k0Lm8I%e}A6bSNRdG-KwNAR&%V5w#F><f8=L+ zxm5`x=@n~AAFir&-Fxi_x;>_O4zRr^+jM4rt+qyajm2-P<&W9jxHiM+>|fk&mqeAp ztY=FGqjR%e&a3#kM!`E`X(<wv@MRXye)RBY=fB#cbhtZbT2*h5D_AW{wu&_#`4M}L z1p+cEfl)co*<X(73yEq$YAa3pEFL<WG|2EJ<0*Mp=6vR-a&O$#hzoD}`o{E^P?FP# z`F0fj_v6Oj2b8lU87<^UsW5tTIkY;d{-U4v4pMy9`5;tT&$|O%@}IYr_I`JlFKv_$ zamC55yZVqO4aV-N1Kg36;seg%(RnsA<r<r3OAUxW!tj79An?lclx`?#AHM5+;NVMh zkX&Hd#X{Tjz`Bf%ssd6Wd<7494u|W{F8m$B^vzJNnm2@x#q=F~%TGHR;2e|6i*t-; z%l!`t4c+tP<)aWxH%M$WkQiY<@UxHjrAA}d6Y%2o@1@sD6LK^@2kegLC#_rl;y(Oa zYZj5=c%go6{)ml3-GMq(%byn?UVA*dxnk;iY~>w@Td4Q9S?={_6__H|B-c1l$wuj* zw{e`p${!O1kvd`17w>gWl$_3`aR_Q+!nMuaiSE}*3+cnZecp}aE2JnUFzt$PS48qx z`wM<l-aV-oMM{l*Jy+p>WVBK1zD0NEfO(Z>MC}v5TeH&VA~vSIv$G$UlkJMo?PYII z1nQUSBqZd()||~w=j7kz{5Fwu>j~4zed_xCbDa7l^?P33*8OiLszuGmI@?FGzf>#$ zj41l__36Tq=3{M3=hgpC^Jj=H>4k@Tf3_6v&Hw89{Y!0<ILY8mc2tc-mC1pkuDACO zA96hKaKT}4gFrp9$MS1<*D9l(g`xzmmS0^`%dNWNG<&$w`H490rB71SO?_ZT&GEh< zwVrVBnug--7rs2_KoQ;+iton3j0W2MLBqW}tZ(0SSz!RG0!(>XeIyqte<E(}@*(xy zXAGPz0ALZQ*0z;GGX#npP3Td16H@7&2IZ4V|8Af7*HqI^-3RG?q?s+nb{hg@52H84 z=U?AH-~6wwm6GL+L*tRSgvJxg9Vj>JQ^aEx3}h>X!1K7b%_=xoyiP{esWyDT!-wH1 zmb`Nw|Clzfl=Cr(+xyC<l+RXFKgQ{~0T}v|(`d7`Js%GBN-Rh;_^rN*+dh(xdSu$X z6A`SE1rdR-JM780H0lEm0R?kXMZJkFN!a|>{q}|RYWMMXTtsd~cEky#VM}c7)63LL zRxfs|MFF<^HOumbP}V;MSHlD5V+mxEP#~IHUtKFd`%mU+_CGo=PxD8r2lG}-&fW&N zKKhe>CINBClV#b21(V6GBZay4FpPaRe$ZQdByB4T`3=BLvoR_kN0gW66TEPxL5|F4 z`u*)zvqpd!Mz+P{bIL3C$3!v+j!ab2<3^1eE^eQ6G_<}}mnrd<DKLdz2>Ny~bvct+ zyyh|bHF`SMbCaYrg_G{jQ{?mie*0Q@RPV@;sd2@VU&7;K^^cu+(_}kAxzf7XeD2?W zM=e)f*i@R^_^T#*N80g+yhb^zcOg}i`A&KK`&fF#?k;Nd;+rjWzs**mI6E|)HIV(Q zNk2*{(_{av!75#DZRw-RC+L1elrpX`D(fEflum$>QKUhPJG|-P0(}XE!36PGC}1IL zcRehXYU~n(HGKv+#QO+4ssDj;2v1Lv@hpH3{0ghTD1OrlZbQe32rhXL_-yo1SMs^) z@{0}Kq21WSD3&2q>432<A=^m>N=8?gD>F6#{u3C?Jkp!?l2wJaMS&Zfy_brjD@A}r z7GG^wXdUm-RsF!pjGN0rIEmEL+E?d|?In*A*OPnSOa+9?*0d7Fc+`6ZWJs)0kJLT{ zA2MAG2<4n=W<kYa#N=X{O!F`)T7hppdYoq~0)Wv#=GsaU$X}E!poPg^m`)abITU$E z!W>|`U#ZYTr>2B&xLjI;f?VFU{~eYDGK#z_Qsz{lFZw1T6ey8*-;m<ALlwaXvk?^& z{1Kqawfah|@p?S!U49}?^_)Hl19aVUG${=#7W>KB3zpl|8<V=$guDln|0a?J-C($T zLwcXB`$I)a2UcfgILOYDw2W3DZaUQrj0+*K{BGDQ)Y=k(c(q5|=|!G{LOZgYRw~zK z0FUeIcOriDQ8o_qPSL&;8&b5H1hUnYrG6wI7{)Z4a2j-rF&!+NU00=+aabTf7f9l* z3IQes#bM$G>lx!^o+ENG`iieh67$f{(?phC&o;6*hJHhr6wm2Gp)jJx^jy&&lm3g; zET%HQhQ#fq{ww$c;`E)62~~Sc#c(PLZyTRSGZ4VE=<p$oe{%vU9tFT#Yvl6R-wl$) zS|>mO=pOKw1BS*SaAmq@&`cPz<vGBLy09$jk(i47xmm-qNiKdMG=b#VTv*Oq5JHPj zcvJH1ev;K-(lFS5S*S$X!qyMeohfSiM7>Ep2UUvNTbId%-^i8)C7t_Q+E#uP&?o#M zT-4M%g3R;;hyIyk^%lTKn=5MUb?u@HPqRKOO1J4#<UfT#uqC=G8OKs{YFQ}Nrb1<Q zHV_rH%pcC?E*wCV+p@!w9xCZL`QiHs9ZX;x0P>UcPNNd~kTw>P-*W#6z|j@sOr$U) zfcNEkI;~`@Z!y`nAC&mIg^kDjDSi*x6KTN3>hpxJcP@zBrst(j!;~@}b_ZZ_?X(?) zMwe?ZU)%<4JV^>R^SmcJ)>@-et(&yS((QB9^wGy}CO(6iYV;%!><dF(4hYx=eu>F< z@(z%vocD&TLu?mCf%O2)Pf8@&zlq?MUx>o>lK<A&>LJu6uPpMd*J>j;v<E&1^I_ou z^2^azNbZ8}OOfMY3TD#gEoD8Xc_GvsW5{^^gHQQ3HIkkR0DUyEdis3b?-kP<Ohnv> z(moD+&=4H8IIbEZz61VT>_`cL^C_fe{u$^XBN&2P*zm4UL?B{vL)410F1x%RlW%v4 zwre3HE?;qUYJ^S#x!v7_I3Wj_bI95rfQJh`9>{v$Xf`4CQ1v(bwZKu1dd@;#--)-U z_RkV1q@7G;#;GU%7!xj4Sg_yO;}?Ph%v)H6(s3$;n^sdf4Z2dNl%)b_{vo_C+8%i& zIpR1g>(&yrl5SmsnY`nd3Xrl1saspOj+9Ea?PcJb1Vw&hUC3gDr*quVNrqIG7qJcC z9fM#2;i-KiIBua!sHrQo+F{XYPXWvyth|9w@|@LgL)TF#uxB*s#{WRi6eHP6mJw8< z!)x&Q<Mz?JT3@OS@ojOzvZ_{^*k+bp7xr~QNnZM!y@LP%OPusoa#+3tIX<Okd`fuY zmz%Gk#$H+%v!&%z<6nE!UxuxQ>5fE?49Dv|Sh-xa=d%Px%3s$^_ywdrQW4RljX}|S zBDF>i{j!(#l(#h$3cu-!r-<2Lk^B{y|NfZj-y2{+K&k344~O1Ge!gqbmoplzgKMo+ z-<7dzBCq!ukfiZ$yGN`AQf6p`<Nqg!ImJIbp=0}fgmOElGI%A$Y!{RM^I7Gm8%tJ_ zdF}RhbQRVJsT2vQvf_g67fCR`FDatf!tEa>B6+EJ0`9^IJ_}h`nMeZJ!y~?Rs3YXf z?RFj_3Sz_dGJoS*UJ;&H&!Z_MWM^t?Hh`{o2Gto5JL4941JK@>7BcPlSC#%q>|ONt zFlu7cP9ERF?#uwy8kqV8SmS~<Q+vW4nd9dWZ&LEBe`bl=#$VJTR_Vc-{kyRM*|D7l zc_XdqyZnR*WV)NCPpeB|aT&U*WNkJX%qrD7U=d(Y4Djy&KykY=1B929LjZxaS6{+c zk(oA>jA50zkCC`m#l9K|*e@$)Pat#hGMPO}<D{~HOv@Z2j%+wV-0<4sJGo5SNIrV$ z+W|)q#3XnlkOL5$K~d%dbYLW^_>$_Jz*KI-{S#^U`?(bZAv7uXD>AmXwAa(kU!uvh zu?rAlhJhV$W`2c5N*R8L)nLNg*C5%BV(w8rkqU7{EjGWCt4^3e4gkUqk&0|-o^5z^ zf^n2{uenR0Ix*JY)Pcd9n^62M0+@G^onhpOOafI;n|$0j#HDS2bzix!{7>><>r>#2 zDZB~3;b0tD=|lJa;37kMY8_yWfZ~pKQK46E7<<k8gH_)Fo^C({gn3|*b%2<l)<lOF zOY5gnfEcs#>Pg4UBWcwt|N981?<5>`?<JxTWL^7G?WRvVO8xm=%bS;N88RlTNIMU^ zE2mpCj&yVfL>hy~DOwPc|F?D%Nb(93NIQ@UMyC4$a&qlDT?3dd)U+sF!c2Ks1}iF> zQV=q)|L;pPw*4(~2xVT+>wG3yiM8wMpiAszE09MC%|*8=pf7o2kxjCo+w#kTFnm*W z@AGF)Jf_+py^K(?G{jG~eU+x&4V4SnUo`O_=$bUyq~36(dncZD@{rwEC+HnHpr+h+ z%ijF7OUNpBJVguM(Nd<1fz!_42o+_(h%3>6IQg;)L6y*l000bs3K%0FIk~vM?rR_J zh|5rGN}=Ib1U^hHDDrxiSi8|Z+{Vfpm?bju^O#9aiGRO~1>j;9VQltRv=PY6Vn5xk zUDj-36e~Z5mEqg9@m~&7xODfh9}y`#?nbay{~x^v5X)Z0hJpyp-ncbWci=AL1KBf! zyA4vHwpbRRL#eZpvqVV}$>BsZu!See9s~$b0EJ(FQcXMNzz5cP^x+g~dk?=(Y2pa3 zJ0;ZfxQXHRH9(JsQpi4KhO=8L@^R#<PXWO0zer+V))>#?ms`;(xp2>LS5Mtn%K~3G zkGJ?AXf~gk)I3DU4j|YP;%^<O@VCHhX}=A9pk<u!ecMtI1g0Fnko_Ns^tj+t2|hQm zC(KFtjJkb*rMbnA?xlQxxEgI^(;ie8;3k=3gjX@+UA$Nz5sHwbN=KJsZQCS0_l_V_ zHyi`qD|jM#043Wa@#zW0f2W*In7{nA1B^|fnvcyn?N;0e(P0)DCC?m2B&Q<`I8-Qo zg+Y_td;>kVvrm;}em=HiV0x~vL32z+Kww_4QN<bgnmTqS-kpk@7!j}1pkApRE*MU3 zTwiZ;=Coc!KITYvTyA=tuhKIM{bWDij}7{H^=LsZ8K7|7QPG1()HI{SOWJU$7Ns_5 zr*`XINh&1b%^j!8R!#x~ko23_gUpQ+^kh0#QAr?`uH^dtw0Uhzw|*Tm9IzMm4QDF? z0EyA#lK3Y8r~97H?NP$V<o`f!z3~jqkpv7~DplUR8nFf!Zl}vFfh1#?Yi1`vJy9eK zQ(2iO+;IA^QWhp5v!*E)7V*_nTVj~~oAxw0AEa)#o&6mNbmbYjoFOspFM^6ROoa-< z72=G)_rqwqGloUtd~Vwg{y?gkoZ+roQVEQd%Msrt?tL&Ag`XI;m&S;q9M;}_(-}oG zv0G@fT@NVUaHipw_8{8_$kiPsSbz5qX;#H*;a4Q|!o%$){MYBmA)vK_VQ4i(*~D?{ z=ZN@PWODVi1^aU@$R39M-+?>ZddSY~s|-^l#?baw$5q3XIXkKS<0SG9RIMr$2*7BZ z_lF{26UY5*KuXyuNu&~gV!OD`ey7wpvg(wM5e#?S=Cm2cq=cf{U=hjkXvsVT2PU=R zT1nU`SYABn1Wi=mN{y+D)V@kG!-dB-jRNYkY^N$C?Lg6o{y**<O<+HI0mRngu4mS) zstx@nBPI;+$68mR)zwu}vSzkM)s74Rro$@KR7o(K8x+EsI6DB?ZT!%rDx@2*?SlM_ zlfU(FsbsaBNbPwx|0c|wF(h2$D2~caT6(<DEVH|D(QvRe7*f#<tp<j?PfWLWs5W4= z3w5WwGZEf1(YPD75b*}#e2tHBvl{&m2VmbScs-ax&*;(N$i5AG2d|FVtJ5M|4AVW3 zHTg|hs#=asL8gPkf04~UKhZVTGlx(DnHVH+^TB<MS>4diOA!s&Vm5mhGZ=~-GyRyS zjS!q(-~tC_r32xstYQU3XqtgUwgw!+2sI1R)TG$!vZNx`gO-|<O{D9wVfiTq|GP$U zw=(@SD;$_yAPy*(Omc*S`>0ubyQ!F5uBIB097d7yn%$ua2=?xkU6L5w4*ByxmmPbG zQ^CA$EPHoYF#$lp_XBu*OyIa;cJ^^(_j9vZ>4h-T7m#(0Khy;R9l%PRt9dsX7DKg! z@NBwRlBsEZMNoQg9Oc7tkiZNs3q4~d=W&b_?+R%&+;H0Pir&LX(S=rN>)MFl!fegw zBa5%wioN(8YT^k{Q!va~&I@0$R&c%WG-sq%Eg|-*vRLbu!-oo#Ax+YC*dWLdzH?wg zK!>yo4Yx4c>Cdk3+%4hzKaqA>0cPq|iaC?ZykREO>|CYKI&4=h`jsgc0*vu|ClWbd zbQI$q!H%P+mX`Z(rj%VuaL?GxUpJf4k}x!MFOz{_m?o<meIp<rY~nBQd?e4%hp}a= zZKnxQt1<luN?tKAhP75o`f_$Lx{bF_<oE}};+6_`J@w5dtoKMD-gU{L9mp2ic3mr! z-Jo`1Q7n`C);YKh*IsBGtad8dwpFzlTn0`?DZ^WUXEd%zTjZgefXW8tkBq1A9iz!< z$<dvevO7dkGpd$;b7s<CKS<9=n<IQw(MflKA3-%DwY#Xbpv^#gY+WCD*H<rg@kZRX zBKR*d5+bRq%n%mknj;hjpectvveeMcY^^p-G4(T}ZQgqdV4`f;L!xf0fMq4p>@*D9 zp~?W)Tn|^OKC%54ed|WN2420#;!<u6vx3L!D+Q@Wt_ZjzSoAQ(^p`{QLpin@6u14! z@4)3un!9iqv(cAyIAzCh0cC{}jw}To4*06O9}zPMX4<%b;e59-Y8KnsSMMdrkVlD5 z>=P%2i(8?_mM%OdfcM^!ENf*l86dB$iV>=P%+qlem@ke5EZNmyi=iat<w|#5wm%fU z#z_i3QyFrmT{RIAw8}S=Td=eZSzP-h-}#)Fm%^9C$Ba6WU08t4=gUbdOuxOECh1e4 z2k!SS)4O+J@j)?AvMm+m##d2DEE|{MXDTr)(@xWLP;0gqXIg_eqfKmgqAZzTZykSr z23$+%F9raC+b3v7yJ9TAjZ|~Z_8gwtgJ~n!n7ZRlyf_VK_M~68keO0z&>l37a+o+e z7P6QGa)lmCF(At@p^A(*wuVfPu1e#3;!@?#WLqLX`HG)UeoQV9ud1m0@Wmy+n-Wjl zAbmhRVoC3!DgreF%%%#|JeAy%y}p^9;E=|I1FfVzxMLbL%EYju|7Rcp#i}G{L1xhB zDGHU*5Ahq@=`Y{!Kn5zrTHf0Q3HX=|fL;Z!4I&E4W%CDPqqm%ULWV!fw^AIp=Do<L zm#Y`DgPG-ke^2QTLsc&X5q-uAc2y(R9I8zFgQ8*$`F%6m;T+jP43{Pydj;J08yPGa z7QOMhEA@~#fhDOR;G6c3K44(OpUzm?<`iR+>E?oL!lJoZ#5<tymXialfPb9)3$*{I z_}}OUcKkFGf_Uq7K`=YdV+C+9koUk0XY|66XQ&?+&LDL3%mJz8wsRcTtSy`(=cqee z9@94s{}pG3$Qz4oNHlB(Mz|NyQ0NF2I?1=44XBr%QkoBsxhS$gll?>3Fyl@8+v*Uc zfuXQ15=hfpX_Fow4I`dk3Bw}{pngmFkl3&Ly-!Qu0bd4mU<f>}JxtbL<eoF+&ES@+ zCDIfbO<IK1^=-xZ+vW)nvLS*CIByMNDAQToBFs*HU#Zr#Ih-x$U1S##)_a3;%W^pg zGPpq%vV*4wVshm#q;7}VgPRXzA_75EdG2X_yo(}RQY@jFQ;2Ds43=;+t>0}VOAxe~ zwKKYjJse=Ix3{=?fm!bUJx_GU@Mg{G%V0%!eB3~#+*SC4h<ZXVd4HEHycrb8#8aaW z`=a}>hHL^))cc7o>DMr$vXDogHb43;1^9OSih1U=m)87P3+d<vpb{%YnPekYft=d( zQ7;5lW(1f*^>v$6yB(<W+Eu?5Sq#oi#OkwzU%<A2arP-kbAj8NLA?~%v02i$jGMf0 zt@Z-UcrW7w=(h$Wl^V*JnV96+6sYFYFo1JqV3nq?<+4+3C>ey|i5$6vQFLWECvH{? zY~2-Lc}B2g<fx^2XC!+Ycg4dgE^j5tmEt3JX*Yq&2-|iB@56xP{_yOS?V$*HfwpSm zSARfB?pa7|f;#{$Wp|rwSQUB>_z!44F0(3k+nr8V;ItnkU;mx!mQq5YlI_8pt!w0N zfBimWZ>~Ay{$zM8c1t@hK@~`<>32%_HaHvr$2ZE*pd3WhWn|&5K4c*ANqC-(E|}%c z_5lJ(bP&@WfYS#R&#B-&2R%wQ>{dj0!qQuiJ!)v`;Od6s6LZZfgJk-8UzlKY3Hy$p z1ai4HsKF+*8E>d%0sfHT5~k22nrE&deI3Kp_zx78J&WP^GgZk<585hVf0Og3F$W}K zLvIcukM|X7L#9m-L7W)=b09|Ab~Gxw5CnbMjw%Yr(;z3_bB;WLD!0QWVPv&zSpT!O z-p|WD$2~Gf1a#ObEfh2t+SP50Y_|v33r=$hvsh!fNNsdp*6Z2uAP$nNNK<HsBjmdP z(~2TrWGxDX&~TYRWQin52C&&3sR={`7Ba4fRj~R@`@a>y<S`;!^oM@JKvI;2Ui?F~ zd>TOT2N^?6fT;32j^>x4PAn6cv7-;84GNjT84;#b3pn7!o7gZCO;YPB#e&EiFda`% z)#GkH<K*4DKI4`a*Ni%tHF*7VyorQ<A29EcJ&&i&8b_yI*zD>oV_5t$O3j<(pE=Os z#u)35)E4i#ItYULwN`?RELcag9Dy_G_{8Qh!(VrB@%i26kvKlE(JBP_Fhn*}uh(c& z5V#DQWrogc%L*?0Ir797@ae3s(yM-|*yI`kyV^NNLt`uAQzzyoUAdVCSS#%~v(X#< z3Vkt8{1xrPs^pge|BM;-PFpAf9G5$B1$5onr`sH$J)WUrkVhi&H^-W6t^=t~wF?*w z9p)VL72k*BDuQ>n&A&D#HlzM$-%eA*LQTBI%NM($NFB=yUihY-{z3cZbhg}52x<wC zbAw(cK8q8)nXDM~3XgJT0bWgNZ5z}yeL0IY)(u?mhZ~W1>zpIMPc-?pkRcx*urTmu zpt4LhS>*@{4cR)jP)%g1F$EFR(aaRhnSrh~4taFuH1lH7ae0fdbz#9_XGkm|k1kS7 zLZ>DF@8J&wbpie%Z=eks$}fY`eRH%yk+sMRF(W)%`;m|t4Bt#zF^w#bDmS;Wjau&R z>j{MPzDNn<jBMq#kSQZIBW)5~EOzS-n2`DrwqwT9X$vYSP-cvXQE(xaXEwEpqUPKU zaW6rnn7Xe5@E-s@q52`k$h%yTJ)7^3JU(W)byo#c(I!u{{<t4nZ6B848wWUd&1C6v z{`K-*id&-z!|>f;j>-0kycTOFg3qGUCx_z%loh}rWvd0Qk#Cw%#r+c&m7!@&prRSP zb;3pUBcC|G&%|1y;DF8ji@)MZT;B*4BR-;g0Q@<IWjpeaGa79Z;*wF(u4);@{xkP8 zHFy_2ZZ3IJwaG|YKdqmT5&}3mHj2TnS}{X|LCg!$Hjg<{);D(_zZvBUSU-x?36&(W z>4jXw*~o@B<|^_p)I@9{O?FQ0_b8d%s-D}wmH(0(>^nr~<Zvk)tE;a;+Lh^hTI1pD zzd+<YG(L|}m}GbKwWkDoGTBL3q6&XQMz=%6s|7pS4_NHa76N7@X&t6$P5e0sDjBKG z-!5~x2_ET|pN_eR)*Y4w0)=Cq2QWzO3w4bS6w=7$_MW;)4Z-5y<Mb_8f9$#2Awu=` z;q&;fT<Q<{<f+gg!`<08fY5i@w&l+);UACWym{dtI+l6~WuCiRv)he%u@1WtZ6oj) zK2h9w8@ICXb$xE_eqV%&VbX?{{3z)(*d)Fjz4hwVi%t6!{j4-NGDHU|D9b*+Y<sV1 z$GYI5)R$rF?`6LuHvI6+Ig92FRsYCZ6T*c?sgqZ0mTbG8eF`hd&Fg(Z26dC-+sB%( zhi|*P%?x_PAXOf%XRUgC+>@#n7ZB6zsD0Ty*f>mXWxyZt<6lhufU@Ho=ajI}5H7v9 z=&97>|3E=c0*uyJ_G6!-Dtn0V0iEJHY7e^B5)S8V2*qzsc!A2V&6q}oI1MEGl3^LN zC5__pgOAXC!MCt>eNBQlcCt+ioXzap=Gh8c6U;^<fKQ&2e`XqrJB->r(Iq}2VfQ5T ziUAY^MBUOW%97xh9bU%N0|O1V{wpCa7sGc?l73?8`6cUJ$MzY4SWDuZ+_+<xSo4|u zc$<DQV+lLkyP_B#73d|hdx?$K*@8ZBzOX+^<G~)VG71oA9L#0jmZ*MOEPrP34+n60 z8d4DD-^2hw_??}Kg<A|m1cWSo-^XJvR6TX+q>zMS-fwt6^RL5i-{^)Vzuu7Tk@Zo& zE4{5`37?DM4VUiGlrg+LO}%=jowIHUq$rcg`!3e727Ut%Dc_I3ot{eWt$)1OLXkJ$ z8Vyne`(FJl7m@R=0=~{cjZ6p%W33U0vMF~Z&FN!#bX@YuJYuy!A%Tethrm~7h<!@; zhJ(_y>puV}@3I|?X>;Miy(<#^@6kKSSy9H3-^Ez;K<~?y={y|=vkMXV#n37Yl;@c8 z%D`XI=US)b+C#Q?`J{_X2ugX-h3u}t7cDzVu`h(AsL?=fDqB=z**Zc%uhKISiY$Y` z4`jQ#b@FR;1d0;-liTsBt_(Y^cRua9AZ2^>0JiZXxNfUb<#hhEb#T;5Hec4%2}lg` zB#?K^+|RBTOrbLk9}^j@Zp$Xx{Nc}Kg(G>-k~q-23^sw^SG?g8I%TC)pw*<M>1V-M zo5jo<J0)4|@H%^5=DF+5t~HBjQq!15Fd{0W%ep7=fVoBU8q3oTaz}Z!?6L2j-$U%Q zHFcd|r9EMrziLH)->hX^>e|)FUKaAU!(5)^w4-wH@iN*y3r_PPs<ppqDB=QovW`Pp zSmiy}OomeqOSmKucuY9UuO+XjrPt$gefC-#Y~n)D%#kzr;&*yOmdGp^`{g^Ph!?|D zD!unXPedUnjJ_o@dE2V@b~r=~c;@#}jR@Q4tX03dR&5jI>+){IbUTxP`Gu#udfvEo zHXnYx--j>Ua6a|7>)=@A4_P?%86SuR2)O3>>$c|?H9g{*oozmS+TJ=C)%usa)(Fg> zwz9IyskZHxnR(0Ib5U*8dDtc|B8+&Y`u$M~C6R>D2s>pr?e5qqQpr#l^fkRH&WH1; zP{23w>ECls_jDUzFk8Y_R66(tNzL(EMTxqyhL^Y@j8yXcLDP|voJ7(*2?a0ejKw3~ z@T&<ky3hzGPLR44P0mZZO@<W)di~Hj^vn|=93Y7+)cSh;SXD~UXq_2y+}+LmkTkzQ ziYZm+C){u){iC?v_-%|N=^0PR9aQ?}M6?piZ7FQ!UQYge-@>Co(S`<00-|EZHIK&O zwAwW*BX(}$UjEBe;C|AEs)qh*{L>U6aQm&zy21PZQvZNxK<aN&P(DBLD>wQ_mwuJi z)IK{8U-U#}#FwSe%eVIlwA~)+utPU#a^6edBAup==6%R~jK7hBuW@0WGgd5#W?Y5N z9+~!t<=ja=R=0LpeLLva`P<>>!L{gziKJxDA*rX)y3|ldT`2cDQD>C%TQ!*2rovly zD~K?cyfaKxSb?gLg>B*Czv_nu-y@F^a!Ll)!=Kkg93qZxF0KZv{V#<FBwEvIS`aFU zPHoyVKm0l@7{79`t;uYvY31Zb$EJZ6Fc7&u>i@wOxA^3~fWG>{4#n(Xc6RqH_l1g@ zUcO3Ph8~Z#{FZI0#>q|e8}M5n=!u4&(M%|kGxhk`-Zk>{U}J<%>F%)}39PX^&*O9i z(zqV2p<_r5@@xK3Epl@`wQkk5vvx>)S<QpIU^w!S6uEOZc(u4uj|_+zg2|RdMfmEC z)QuIp_2LV8uuACW_$4Pm<gc||X~)sl-R^FZf3>}v76n0s<DXBqE+U;m=eOk3_#XPZ z{r``mbB|~0|Ks>!m?TovWHX}N`pTu4%ZwC~+%H|Exl}5*xtlwowB|0A>({l5YjR04 zVH*mWa+&)ubHB{}^8KCPfBy2YIp_0vUtX{0%RjRWj3cs(I_!-&AMMx$8-1;@`4ZFH zI5!}&_eQLp?f}`le!bSPW+>>k=<BZsJ($wabAm6#O}bMS@~oqAZn6kns<tm>oA0yR zQk*Mr(IS$l2?tkG^53MKq|O3r2Y-<*vtdof*#q1U<j0Q{JhMnvJs92sB?p_%l}zh_ zfg3^Elg&pX#^g_K;krUA?^XfLA$irwO_-ax8zL`@uioA=P@Z1oHvogF4ir3Y6(+b6 z91E=0*s#sZ{a4qD>mT-tS{i6oX1+fc1cZ);uAnZLy4v;{f%@HsWUbvWWQ+@a*toJf zuu~3#;#xpIp9`ERyMwH*SwWUK*jQ(70&Ma9P=&8=+AsO5#JXV3#!RNf4fiy_Tl$L7 zjKRMb7%@`s!TN<>{3H_D`A|!{>Gk6an(MUM`=xhkUPq_;caP306C<)G8*C{umbP#5 zYX_8wS#cU5=#Ta4`xJI+#ncD_o2Ni$pQIx=pj)n92DpCOtn!^9d2*XE2az*E#n7ie z6ZiMUYed)H&D!IwE+NlkyvswfjT{DGAK#6hK3F+A14lY!VXQ3ZT+gH}PzEUbM_w|~ zyM0x6+b+EszOv?(52cH;Zod;NLTIq};?B7wAO9F@(U1&)yn=B%?Oy$238AvTp{>VN z1VR6+PTHr$Por3GT|WphUpyzVOoio9@aJ2a(~rwC@;C~u@Q$kMtkj4$S3>H>)Ebzu zdAAei=4_*%tsI4-F78@$4hdFC8C+T3qtr~HC<x{2p2)#lzf@9z%#*`x(Zf{IgSNV% za~Kqbwm+G7_t9-$=)X&lK7Y<?<cXmc^$zXU3t%T(gO-c$Qf|nqgC>|Ubwz*Ytpg6A zqky$-I~36*OU8#Z>ZDyc$sai=<)Hy*uq>|oC{9KQ@6<8sK(-J^VUTe0(7OV$ZxI35 z@f^on?PoPZG642JJ;An(X)R`l1k6j^gDq|5+paqElpV#GU^$03lqdXTvd?*1=0zOQ zthl%Kg3G#g0W@!%nMC|iA%&Z{23SeD(}N(zm_lFw<JIm}I?8{@D5P;LglU(NnhItb zF#BsU#@+Qq_dy9C+VHN=tU}QZ*ZWVuJ^QRQY&6thMGP-|_@sw&rX+@_pBmb-b|A;m zT{Yzvp2{X2T1Ub{KDMYN^~1x^P!Vq_{%g@CP9$u0L;zTWJeTAhIGU&@P@JdVziV#O zVU(CbJ4PU=Y@$AX_1_D85L0h%&_>p^Lz>3X=50E7W7$srnNbE_(A))R;oVFuxdnpV zx#h(ZT2DqXXe+rXmp!-wa33nY37`CrjRoxQ+CH<;55P%%zL*^OP(a7cL(7N)BH!5m zY8fq+Tc51Z;JZQ?&yFk7WURawyP<~r&?e`!my*y>3ulAGXS-88|MU*u^xS;fT%$UC zJaD%bN*A#+_N<uGFtw?(WI`VKBuvLI6dnKmwv$6pYWkK)J4F{aR5yL^Q%LjrDOmy4 z?k~P)UHp}Y^J@K^t{hiO>El>{vTpU>sek1l{gBTKmf(Pz!dp2t4rs@T-I4{jR=lu9 zkQF||a|B+=S6Yp1><39qMNayjkK85P(kHcJkpa;O-P+u&UE7kXXR)zvv4bFeh{PyH z&sEF6@UC?-xR=Y*8m_?XUuQ;|)urF{@&s&Om`nL|qm_6U$5JSTkZU*YUJ7<f8ovn} zt2-D02`Mcic0ZBMcj3rU6XgUeIwFo~EN*e;dCjZ&SktjZwO~O~pMUy?k5%?+KDFZP zQ}#c@Zq@Dt5EdC_s6~>t&Bc)pwRDSY0NtHi+!gsdwc_V3c}-beO+0fq;M3m-Dj01C zA~ySaF9e5VtN=q{_U`-FY_s*JU};7&Gu?H|Z)tTu)0_R@Q;!k9B@{laO&_n$_aNbM zkwoYvjysq5KSpOoB(#jxiYUV5t0H6fz>RUK`JEXHDJ2b=qmh01UH^}qwxsLA5gIV2 z7^e6MQ16zsbK%zb*OZhW>lBfD&KJ*6$8hFsR5QYC+Tywj*Fdy(%7RKTp3hfZ+|nqS z;1ZG-JG{go^l&|Z<sK!$`By0**jfaCSzxs#sa9f5MU_@8a#d&H<PSEJ1}ckeu@4T< z!?eA<ltM$%t`G|eSLf6GoUv(knf&+zC5$nf4og1kGVm?a86svX*r8>Ia4Z@f{(+S| zb=keNA#LCAzVSemR_)8Py75G42TByhT5NOmx&HbNIrvSq(Db;^Jp0h5drr;VM1Vu< zt6JE+bIC^}{dG;%mwalKd)Lg|5r^Oe6JPcR*2k7`pDC;q)pWFzzz+xUQBQd6`rH}m z+;z`5rb`l%G9$o0=U4SB#S0y>JNa(zD2-pf=eUx-@pGyHIs@9l0&<R3w;n#@d@kTa z{!MuTOqbpNX?0TWigI!=Bkz~BN&&GFIjR;OeKct{EUjGgZnKX>WUcJ9ijwjoyJX_? zeNA=XYH24f8uYK*PdE=3yf`X*Mb9FIHHQvG%bO>C<b3mkEk0IwCYuteUm|J50KZ!6 zXAK2OVJrt>AKf$Q?r_WVeY}GD6xiaT-J5^aIkkmH#(;~E8ijW-C(#vMMiLpb`v?88 z&V`qWuu~v0kTExOAEW0KEiY^Je=t&8C8FkSzI|5ZNivuK8)<y-pKz`AuSuC;N*Xf{ zj$_@Kh!2_jAXujH>n2Fpr%fzms4DKOK<ZKsdX)^tGfMlClCBs}DUK9`S2b!1jFn<p z`99;1TsxLo8;~9b_@LdXu{d+XUj@FfL)44_!TRwVw>yu$I{7lqdZbd%=^SWw<+cHn zzbEdT8g($g``Oq(A|G}?x7#E%@DqY6=7`nRutYVx`RzK_{{MHmAFuXO(%_?iJx+h# zrHSt|$}g#jlJu0el(-N#ldv5d<X~92c;}R|Tm1p`!a(z@?@oo!5qMvb7{R48=d~j2 zQxS$HepbV_BOlb4gfk&$*Ycmf%HPg_!~H)!sz@mOcHzVCYkfQv8lPae#of2Lww@Ua zf;kh-j(wrrJ`TJDCt2zsuX}y7R_bd1P_1XL(efRIbYP<$&Yul!>g=uiHA(3AQul<p zje8#%$K{wLG_*-tDZAdgu>eRcMya%*8-h1QIB&#q5ng3mr5%cZM<nb(e)f5;IbUjf z2!WvHLtO&K%~i@IwGfpAtYYw@)H=0T)@fgHRLM*`*d|(Za7)j6nDTu|6|^Yo&Yy?W zQSAx70J0e06B*|DE@1-nIscrWy{h$n*Pyf>y2{=OWNj?oleLip3m`AU;<BgNt9-5Q zJw``N5{*|3L6h2XaqjZ+L1yR0-Phc&bKBvHcz-5Bf$Hg`1e5`O7dr6CN60D|Y8!s^ zTi2QjwXLSIE2twfG7+i)w@ZB@8$ZoCVZgh%^*wFAXJE3tKA?rU^)AgDOw35i^h1{G z-Q8`<aK8#dK1Clm)oE{T!KjzJT|YdZb{ak+N?NQ1+b+8sA1*xPe{VCSuI3XVM%eRh zvr>ugS%0n3XoDl6uyu$=a4KK=R9oNgq^hu0A}<3RabXIbj0A@enK*(P)Wo*x#Gb}j z4?zHPU|n44y5$LooN0Vvf_-tyULf~9A4W-mt*R%n9oC1;NJHu$-VE~(L8rymz3QTv z1C$X7yV-=8<2i!2%SVNZJ3^nfkV6dfk0tf7{7;Mw7k&#o_Z;F04z&N4+xJb!UHjek z$==<pC;Zi;Kr>_F-@Z9Jz{8g@7#e<t={KUctT<&hK_`JNHhW*UOiLI$d~E5ic6w{{ zzFeUgJaP_2fmBjhRu5k6m}+_j&7@Wgej}<9g86!WmaZ*{I%G17<oyEtWOG+gjExc= zY1Ay<IlA}#ye8p{+Plm9rPWu|*YHW8=n6vCQ4efmZ=da1=nq+UH{Aa!u4PBnY;2}2 zU_OtBPTT2VNnDvJYs?x=yL*%W;5M@Sm+#hvr>pKYQV7{c5OoU}@jp|V&l28uO21q; zC?~k^NcfF|EZ=*+d3l8A(M1gT@}Ig7`Gc5E{q!#n97c6p4dFWh7{wj~B_(wgHnX-! z!E_>B;Xx`erev~2CHqh*umubs(?arV@^yHP3dNDbi$^o&Fs;|=c5L^9CaO9<wi(=@ zmf{5x9&ZL7SMNTn2zYoG_XXqaF!^^+p4Eytb-`!0r6{yf;d`Xwaoz&*!V-#!^8{5H z$L=Y1X?-j?mna1HhGY4YwchUSjhDw5#%jx{KlkIPTDR#uHsTz;jnUay>;I7ey)o$? zMl(CQ7p32!yH|N}6tkij^?j+oEWKB#h%O-{&$WYFD}jL_3*u+--uZZ3&&-!2{QWm2 zr~Dbx&inE&CsJi$3()($MU00kJoxNkYZ-<1W+nsyK)(3ACE7fk+Jq3+-&Pq39d9W% zeFBT*zdpyKyln0FuJY;Q3vnEFkkKfI=c~&vzDuvUJ*uq@f#s$3@w?PHfSmNW!Z5$5 z0sR5J-Iu3cU5Ej>B-T7(5ebtVhEH~_CUfEuM=!ZSGkzWRcc4Gc*wCe`s72^cdkpGO z-U}vT57f)u8wk7&TelApy81~Sn6Fl5ThK*<q=}=L>h^l4h!Z~aB5t+I{35BGqIUk8 z$MG)CU;q^5EA8>yqx8I=uYs%4Ys^}`yLWTNk4(Co&*Q86O@0O(E{3^beJxc7IBt9C zi~7CNTZi!<ich{@y8Y07#3tmMbGc5_E5A`#Z}tqfP=#ltHGnT{F@T;7RsA!tfjl;F zo#!1<n;xULMv!N>;X?~Q*;Y;n3YB-y*0T~i>VL_d2^y?nP<5kJ$&<W`tb2E=ljvVJ zENBo84m5hc+w%rO?)E9)P_4Zi=0=D?{qLubCe4!;+d{=2yQZiAHYoXUN=c=-)&m{- zwEY`Lagx{N>((%5=Mx{<P9x|@$QS&&kn|qs(s<PeZxnowd-KzqYTLMzs~oq#p#$|S z-CI3=s_y*|P8O^+>-esQQT*tpU&jA30y^3aMp_pe@0pPun<fx-L?sAs=OXA=0SC}G zL+&dn&!soXUcFK15dO6o&H*+Cb?$FO@CZRdkNOJ{*aNBOl4wH-pZmANy6toxkjs4j z1CXZ@Ka1}qOy6hTmkMlen#`qWC?|qy8CdxT%%dgGWeBd}Mr2<wXD$e9`Ow5C=@yi* zc<t1f*yGRTXPKtgL>H&ikzL;`p~FcPQhfPS<Y9M&!btcN_g|Bxl4KwX@eJ(MtCcB} zPn&bY*+%csu}cTI-c%i7i+S-A57WCNb0i?!$oYH2mRHx$Z<@Edw=bFD9DF9s&KkWH zJ*p&@6|0sa{+rb;3VM}h{atx|KJ(e&*BAF2Y@ds=n-;1&LL4VccGG`5wd*9A4DN5) zIZ9mMdf=_zq%$>BXEqqP06x%?R$Kd+hGL}jKKL1y%Dhs(MW~NyMW8hkdh4fGjh@FR z^DkY{bWXU_D4d_^JS_^YA>)5qti5Ww?>KK)Y6Z<!?#GO56vT!EtcHp|J?WSA)4>5P zqI;NA7+CxxmJ+|B8i_=0!TGi@FI^pe%=LL`cP5Xvc&LG+<>(NF;gI_ebJlx=(Lo^L zqW4Pzi6T2hdA!nY9iso|kHOgI>mI9nu$kfQ4YUHg(-xp!A$~hhSeGG{^@LpiLzm}L zKcNcQ@+#)niH5`<s5N;wCx&+#{U!&F$FEmvWm$)vlqJ5|wPrn&*h0ulMddY|2?<#z zMvG9NC<qj6bWhk6h-K7jB_IM}%eJPPN#-DpRQyk_NC!~t<9j$uDoKkQNts?=qm3PH zCxH@YWUEp47eE5l71)L0w{%%-2Jb9mOK){Aqs^kkyVHwQFtC|Ja>wjDCd(+RlC`~R z@%b#%!>d?)j45)FOAb=T15yLeD+PT>i4qi#Dnoi?$sdiOBGMyNZp1K%2Z4<Fd5h%J z?-@fGYf94UsEx&K%cMpFvtm;fS>Pgt^ItcPLy_~!7UO)tOE0Jl`#pLOXEFXT_0h^D z4$W8?Wx`e@RRFE=p#;#z+r*H-&C@wpm!`nCUPb_Vh1;NRITF0_z#uM3Q0b9|45Lv% zb*NjEwV?Ccn<c`6ZyK*D)ELUlFvJ<75og7-zJ{g7<%EDfv^MQEUJ_N~Fiki^`a6y; zo{`J@!k{Z~2v@za|DK4l=-b-Z%<Fs&lZ?|RD{1-Y`~H*Z&mhX>o(U8m{hr$LM|ZD) z7%JDgxBF-)A5DS_?O1XEBsK+BvTBSYWJA|MSecS3C==W{kpCAVFx}l>`$f4PL=T&G zfL$NGORg{w@ZXv&;HlLLWPV2#$W)S=moy6I7YxfiO=!X;_Ss>L;RiOk$J#N0-p5dn zn)K*9H0cK@{phi$zLYO=Vy4Putsc(kS|Y$^7f2N?eILe|?!*oUNa;ja2dAVYqSr~3 zFAq7@bY&`~WD4bgkZ)cpf}VxvaZzLP2g(hg5VZ8>2o-UF`4Pd1KYMHtAmA;MvIS^8 z&i%dbzD-2h2Rrv!s&||gOlgJ?`#2;eQc~6q7J~l+G+!dm4||AG5PiL;NzDG-0u9gC z|88i2pxt9*OVM3V&VEcE?Dpo-Lv0BEaj?}c0lW-FcY6kGJF=~PC}Ne-y1Zf+045rW z#q1uuSBs$VjVZIcMNU3?Dxdrbv<z7L{*qaV%;sp3z~qd(0s?gw4QMh-dQ%uHPvk{; zHqfTgj}3ZNBU%4<Ay{!HbJ)1okyVMRnNAUKv#syu1~{S@=0`qRY$`R%AnZYxAzOHX z_#sd`dZWM}c8v1tcPP{tu+%*#sErtH5iJ_`Aqds(XUlys#r4E{z%D|j5=6zDrpzH< za~(THfYpA?gs%IqxT$f$@Z#Qlk0W|?Fdm}!U7Ch-2Lp;wovjAyhM=inh%i|4ml1NU zCA}G$>_X^Fmo6BJ2>P3Q-w^$=F8tzsz_NoL1b{5|4-wYtE&Vs7_R%rQKHV(VHs4cG zzHuIN13mIlAc(SU&Q-9uQ!hP5z-0#q^SM5R=tRdJUdi{<kY3V0No6GzDpl;<h8@?u zsIMy!%9t_X7s&Z(c>-Ug1p(iK+>eVAS>H|!jtf3{_2-Yj%A!_S9c8<RE9(alKqq*N z8Jmo&BkIAk@khq=ionKfz1=d);D$>|_8`2+6-tBxVZz;$<^a8VYHB<IWL9Mwk?a5- z1ZXZY-1=^+(N5-3-3E!jZ-lB&abz5fdMWQlF35+}i;<?_U>*`$s}GyG0DX)VEK=JG z69ywBN1r`{E-?Vc_fU|ldgNRLOss-uRD%`&g1*e}FG^)du`JV$thvkct=3Hmv}lLR z^Fn2o%CrPB771Yp1tqx`b{t1gu)VAZP~OWFE|?~{fAd+;S~cN)bK!RdLs~rC>_5O( zu3_8WOSM@h7tyra2b{7j2873PDPYr~g&OTJ<s)2lWcBY@i#vHJPl-79gbuUYjH+Bx zl0X7BC<PS|^g0IIOm8;T1(4;m-n2L_tV@JH1KgdH=6*GgD_(~a*u^1{Mq+{FKr)Rk z3@{RXGBf$b-+;RL%c@zq*w9hI-1+NuxVlFb-A!xxT+`mro-l;#KW?gg!xHkk%OuD? zyEw8T_CgCvO8b#;fs1c9?ftGf9#G*0sR5y~un}r5z@t^`co-@-^{N%?hcMKqi->k! z1X2iL_bN?C+q_Rt%VhHyf`{x(v*0>EgXX8M&^6OOAGxf*qT($u4y`CWc4CFZt)asP zdeN0@y-+b;DQzsLoS+P_!ofg4);p&MCn_kN@dosEvIp3O6B!XIVO!$SUoNS`;EcS@ zU*Zo<`%Q!*#8{w0C&oPgXwK^yW+7s8Nt9{{bi-KjCb7+A9{eWfTb`+I(FMK5WnB(> z6UOffi2l^7+%<=N<VXyF@4A4m<k@Hv48<t&;zi@w!X6lZ%o_mo;@Ssb?iT{bqWFZG zwdMC40>PoUKX01NU8rdLlz_5DW<;@u1wlN640Sl{D|k?0bU|~Ak_)~H5W((ri_T2` zJz~y;8FlQusp)d6Pz*hC0C&CaQ}F9;;-4x0M@<t(z3${0cu0ic>*8=wsxPVkfQN@c zoyE<fp|p6N!*M_=7bKiwx-vy>g!}r#$e_aJW2}ViMi*WV0fjpY1Fz0AsO|PdL*(nV z0%^F5e9T;ac}cN{fxLE&Jpm*w#y`DO8M1%Amv>f45E>6~2wagI`Uwp=4DWqA<;jOa zS5jp5<+?cRbm!OI2M0pFXJ=ZU05KumAjGy5P@jgu#l6&4DfNX8u(Q!?JV0;`>qas~ zS{4G<87xp6RB+*zvVdqX!Mm|eYR6pbNFDpws}WK=I7|(&f(=7Md?H!d->jaCds*sf zG%shP7+;j8c+Bx$x-bd6`6+J6cB$ep4H&Bp>_S4=qN0mAreiTOV{C-xMtAR9laO)) zM7KvOcMMYFs#ty3D1NmcJp3(|9ud_-;5AD5IkX+Vlr)lQ5ET;3EH~}*(6V%apTKV{ zY2t%>PDwhhyOX+sw8NYj#k>4Gx(qZGJZMTyNsH+t;7}072Gd@saG|wqF=BKN-_hfz z*H)IdVwDF3pJ0d8Dzyc2aou^vY1$k)_C(N-I&bCE0F6wl6B_srNYXtLOYX^smY3JE zZfdx8Dr#a0K5MIgvpNpfB`TO8P=4`1F3)*nE0QYaL$O-yjW{W)b^3zx`f*T&jw<G7 z;$RZqnwC|HBk{Uu<(rIUStlsmm*UwQAz*Wz!tWib*KM(QQ|$Aab5F^*V4;Thz4nd? zRbo>D?TcJD(sY>3&IMjkq&;9Vt6(@dfO3eFDX(>=7oI)U4oSzzGiv0@{<W8#<+%<f z5W%|iw6ir=KqK(kN^WaHi3VvCJl_5xalhummRKYa`=T`@E9<bqJ_k?ka%4cFp#LOg z57Rhf;Qr$Rf6nt5?#YyF7D$LgWmN_a(<IcTAWfBAPLb*EjiwlmfkWZ_<m)ng!@(gV z@A;NUx&h))6!;j!Fp2`o1U7{+lo;}>N+){leCkpQXW(*e!kX)apSd-<U>;x_ASvOK zle#C~q-WHj=gV*N{T>}hDV|^#BS>y=4-%Ej??7G+4rua7AB1NCQpndcGXBF4;vfig zrP)IbOTO`A!~U3wE34Tca1SmJUR-!>Ei)<M8YFTX)KFqj14qaK$5p#&utVQ(h<u!c zVU$l2#Y1-B$P^EWtQBq8G2r2iYbJA$d2pb}-v+o80Y1Z8K9O{Ic(z<?vYzNXMU;z8 z(rH=CpB_G4Hrlj|Y^f;xnMqX2Uj>i!IMDn8TTpH&(sW<Ikn;ilU0i=T?NYtDcRjRT zJE1k8aNyeq_(32Sv86}w@CzUojeU=loec)vu4!_6bqTKqB`%gD3t>*zNzQ~&5awFM z$d!Rcs1e6H;bE!3qZut9vW`a`g$B1gTo5riSQr-&zUbNd)>7ogdDIn@Hh|_nKN+b? zV)ckf6@zXvPUT1vMQXL68z~3z+$hu#rGp|{f?!94;Ro<rW$8k@pf+8af~=b`DWYy6 z{TZ2OqAPfHz^XE<j>Mp?<?=+=N@JP1EWMG$`aMc*F1ygOTiiH`mtqPk_QaNI<+VTt zbRg+gg{j6b33!@wpO+71!c6R?v!_mU?Y0%-mYikACY5aXf2Mr%;+!Eu6SsV09eb)9 z&VZlsH<*FQ7hsb$Ij(1(%vSTaqDbwW0Uk+|!IrvZYLrPjMVXun@}~aDL2R%j>|PCU z7-{0W!nq&uAcCqBm(UR*qGRvo9HHsFV}0{WG&ZqrnT9koPOL!^#rkXJ9@|RrG-JTM zP4odbfL8gvpnpb0I;&9`lv;k*N&UlN{Y(pAW~i&_jY;EU3gjyCHq(EAni%7!kfgdY z<wzFDfshA+<fX*?vz4fg*5WD{<P$Lt6-_TqC&C(!H8b|;ET;I&rI25hhV7YPzF`}n z*rQSpV-yRAPBNol?r>-JX1<5m%-+}!GZXM9oh^rYC`6nMycq{u*1wSc-nTxT7cXcE z8mHif)EF}uCCc=+m3_rh?xRe>b<p&ot>!IY7+!1w>i7p^rD(-0mMPY53WbRSd<z)f zK8Yx8MiLkgERw-K)>xUX$qgxPR1%V%h(4jqcHDN(-7FkdB1N3u_QIbDgiIw-n;8Km zEYLHHh=`y<i@C&Qxt8IHX0{t(_=wH}69qr*lbPI$Ce$feX`;6#?*GiKcTpt|paCV# z$iuHz>C?jL&}kM~3;9G?-CU(^oLKjNi61cK;#IfgMcI!BQkbK<Q%mHYK=a3irlNsx ztn48++}MCO%nXa>fDENo5}d&Wg9oCLoy(nSu%<}+W6(t+K7N+S|I>&ZAk^cJjFIRF zdbbz#kwr^cq&!Ih$iG#2)_K(a9}~aL23-%{bubO7$H);1jlN^<B}~?g84urR$}&35 zaV7bKl7N{bZC~!ROoEdgTDJ|*=Kd$)^>3q1*0vSr=SMK@N0$~f97xVIS~)n%epBo3 z(@&2FL@I*u%2EmIZ|`RWE8=oYHJy7C-f?FvHp8GrV`fEir{Bv!eZ;fSalH|UFaB$R zs3~tAx#AdZqCdj}wMm)Q9hEXyrodR>TBX!TKnyzFjnvcSgYZl-r)N^iJL=Fd+<u9~ zq8tHq#VKB4KBjsofs?4+65t%su)}crdbLtBpn(iz0~Q45Ckux!mzPZ$QvAi3i{+s5 znD1z2Q~{@o1|!mFY;M3M3W^}!gpbF<Ag>xtWs&9Z1dmhz8w-*6Kn#ofo064$y!BBY zqD{8>VYduqdRCdnE?^)P_24JzoDs)GY<GelLTh39Vp8TRx>y6eK)9(aBT8=r@%iwY z%r&xT#6o^kkt@etsEjDZvBy$f{)kLc7gYR5PS>=XJ8xJ-HiL*NA?r8<;D*P;zNZ2k z)7$N`0O=4!lACqq>lS+$>UV|BZn7!8IkAq@L=MuAUBUIgDJ4TKk44AVskvO{-(tDm z!$577+nHd+MS7?Y!FP9aA5_aaXgY(}_aEcaxB;M@MK3oi1<sFuOV*o1&C>~fpnCn| zi8^im#6W0&w&0Yi8J7!H^P*F}0#S35HE)t+@O!TpuQt+{P;45+(iPZA3mF7DBFSiZ z^#tv+D@_4lfvYx%#5qlkgQXDMN-5V}zdE{hrhAGTK#dcewUf~eVCcrMyKHpkF$x?< z5k0hiNs?GXQ>7wJ_<1!Z;%wmNT>0lJP6uF27=-BSDd}(lwQSU`rH&Drmm~$v6+UI_ zw#>zVk)hxPqf*&%oM$wAkn+U#a2#dNFGOSAh)hW3XN!Fm%tbsF1l%QD*c8z8-E%vV zG*~+gXC#1-`0<KnHhj<0(VN4b0cr}wt7T11y-rW-<ivrGYJ}L<*VT0&qU?{Db3usD zJ$$Dh!R~vF7$Q3oBWsbe3&B|M%mN(LJ}_3`J}d)uMB@QEhU>G-YW0fpB1=ypSw$!N zM}!zzI8nK83*PHDoG;BRUs;Vj6h7{s=HRmyc^LY>AbFbt7ZBuH1##XWd>i9iA|9>N z7dHc9^(H7=xW5Iku3HcS5pNZU46O08#*KkDhoF6wz<4n{vWKI`Ds1V>gy9Hk9P}HS zt3%uG<=LGxYr=-g8SPYMG>dkFJ57JJOaXKLJ@K)_53VqdyE7Y%b>Tdy6f~3n5sXe^ z^b)<lg+f93sghxrYMl#!_W`YakcVDc{$Nq^)xbbNE8MK`5`;unQCpvr1?+J%I?&!% z`Ho`E=<r5Tan83UU+1D=LA;^Zm9$wj21K$Yh(#vrr9n|(1wU_Y5N3{NABt?kmgD_< zjNIQaJd2=UU?A+;e8PM1_~R$-Pc5^0B9xQSasrGl9y>@v=bG^TCNu_i7?p~xe7FQi z^&=;Ag%+p81H@D7u%A}ThF1x=gu^e~_EYLyKHb{j|9~?<{`v+3Jly<9>jG+-*znWB zz8H14<73R8-x9KI6?_x8`J6&US~>xeLNseaqh&b?uuJx<TU7ym+Lnoe&cs~7u+gZL z_d}YMLjhh#SX2;6e}bekU4>gKFRo;P8rB@=S}zD3+2ad)&sV8X;eTJR_tme8hpG|Y z0ifQV;8&z(&6aQ`K6BZej6n3uEMsxRA8EQWVs+qk3PrU^n(J&$;&&|xIj<o_|7Y0R z37>&>HivLiv8ojDCX1Vl6mg#hDQ!QNDVK+K%=od^kh%i-s*q+=LD9vHOF%EL^d25Z zd18;!>sWNq-QD~pK~F<zeNI+pEm|IL0BfT~f;q$*8>OPL;4SAZ*p!>Ml8a}PM0Y}2 zcl+}e2ROj=8_>lRrAjFj<0MRZJe)P;vZ!6cI5#6!w0d2r_@vJq|HmZ&mI49zV|A1# zr(r1e@?o%LW=cCNiJdFk4Z3cimw<u_-Mdh!4fbT#`5r#?ax*;>-7AqaPtlF{{u)fN z>mKO9!&G3{Q%>{{4(cK_v&SPr@|!D3D>Ia~U&2);5atXTpus3gJ^M^QH{VMH1l45m zgrbdZ7qsbbs)sF{DU*~vX7<E#yPYxJL0~uM^6j`68tAOf54xHIe2q=r(`IB?+g5~q z1Ze1~?afdD7V5~sf?#AC@Ui}ul0$yp5~h$lmV-{f<v7xXiSKmL!HhBbP&C<UuZ2Ja zi9BZjc+r{xo~S#H8;TiX%G4Y=+5<jLd;kT0aTXV!@K2?2QYITi`x_zMJU}IRo1w_6 zi+U2r?b2XS3=@2c1)w(v0X)syu78EahWw4-AIB<bJ3|vOh3fJxQv5#6tY|a%BkyPQ zu^pVL#CQB7NO31Sm$!Sj<xEuYaV@JipZn9<$WHVuWrTk$O-|H?Ic>j6gXKaL>Z27G z!jCX=S%%j}60WHGgDDN|*!y*8JhB6H>zZ*Gs1oB?y1YU5F%s&d(8zAwb)xZ<99b70 zCVbE~C7oy-Nks%wKqf~D;KEH$06)PTAg}Z-#~yq~1feo(8~O5gy-+Yw@v#Gs)NIG; zoY+k!4CL3>(Iv#ZecFsOaNVY6U(RkRGoP#|&zs3wV1k<AL?22ipcK>oz~O+1f>h)R zW|k=vkY(Xns6>Mv99;r5Nb=chNcf6pfK3oD<=8=w*?qjt&nKbq%nyedo4Euy=t@La zp$cL0DynoEWOp(`bX~U7=MYk;om9P(<I6#-ELx<74h|bYakWFK*~Oxag!`tcfO9d7 z@_yb7dbE1A4$lS^<(ZYD6lYq(N-;7+G1S`(4?HOsy`L(Mj%$>KL@BeP2k^ZcP`*IX zU31k}pLn2fyg3kd|Ftv@3_8knY^FkxIiAJFHuMIc_iTzAyNKVNmBs|GKiv}{!%Ixq zkQUaGpZ`&0lq%@5Iw<_k;x+;V^=?8uM?uB&pex6IGCElB$z$;kroYFAa$Xfn_(aB= zaAD3HEeSfva`2jP1{~`op(e8;8Vpgw5g{!#rndsb`!2ZAKPO~N`wW<K8vUxBLMmh0 zXtYS$deQrCY4%ihF^$c-@_Off$&#VYz^rCpv<!GL<`g^X@{GNfiux6OxX7ngc@WAX zF^dFlBL1I-2zUs;2VGn`nZcoQgZ$fYX32bS;^LLN7&TBJ!y<ug?wAq?xt_v<pWc*b z+)Egj4V@TDt2vlhD`651wFws6A)gEp%G<%_zZ%jtm>!{^u4w%e>B*XELv(*qn~^oA zPqyKdoS;I*ZgfhIGgw}kadgYXicYP9T7Cd4F39DABUrww>rAPJe9_&QkH<<xWbEAH ztOs%0Ry<OK2Y4akNC}6Cu2kk~Pa<vuZq*@&R6-rX!*hCHYmj?PbsUr_edgYE!>0a= zLt4m|c)lv}yf@E5(M3`um@ceN^~Nh|p!O@YLb+}D>Ml%y`2a4~G1iW0x?Fw>=nC1R zXWhtUC4v&;5G$#}1<k4S(CEFoPi@%bMMaLTz`3WUJdzCgz;+aSU(428)-$gEVVS9N z`ViDqceBis+;i#m?>hbIq$tC!2D_WNZud;c&#+MpxKrM$KXv*=pmY&qK_RneG6W-& z^ohkvX^AL?UG6&kZLB8wD#)k;#Z**McxoC*yYo3qz%H;Ix|Bj;-3}KweDfHh-f>5< zZq_cskP$!I5-t*c4^-dgyu35XXvKFBK9sVCv;;Vig-SDeGhfq3&XmCB$JR=7P8PqO zJa}@!_v;Y!H*lEtI>J9;5-B0R4UV-A#Ez|8-TwL?ASPYY>Nt2MLfFlIN+>6c1V*q< zi%p#nOa$@#n*NXhoA)mzA(Bebxu5~>AgIW&Q&Y)4x0Bz!J9oF=qQju;mb*54c$>5n z2N!tq_3G_(^M)%c0w93a%XREnoh(*)HkVmmrfHSEb~o^a>)O>I6QNkNAtDZ(nRyl( zm1eYeXXHpRz!5Yg8=Rbqbhb5Qk-YMCNUOi>lUYmFQ5lb<g&NSx#9;56%J4QtYDW~~ zF*HJ8RK7j2l{+=)X-c<;l5%G7Zm@Np#X$R3UMJE7G^NBC(I_=)qQ^2b1siGFxE`Eo z{3*G{{?3G~rYpGGzVMhkSCe(M!Cv@;xE)$8A#5^H_17C=Y@N>B_qt7C+Ue!Ux*d~1 zz1pG$zsm|$<<w^!hy8q`lO>!FYj?Q9<zOVo#Fjn~kVa&9t!;8N#E8mp2eS_z8zZGt zyZ$uGgLK`ZVBBusMM>`Oy#Wd(kZ^zr3U!Tt@~NK?N%1%s*MPy{U;x`%>D^mGf|=9J z1b2{xa~eJcN`*M~`mQyDatB)#UKlu{hiF?u<<7`|e%AeSoZZdEf1s0=E2jL5zy61K zqz`>%_fL`3^vIU*62MpiCpcN27lQcWJ}!v`GYF7Oo7mfm@GH@=Vqsv(M7x~9RoR;K zf?;!kk?3`Lf2K&ewS79z`Rursb5wX4)Hv&t^JtZpW9k}@aTGe#3$4ul_~P^~EU~Cx zz$@GYTsEDin%CA2{7~!K#A*@^X_=u~f5i3zzP$DXH`>QFTEcF-9cbAZx^M-=^eX)< zfKpa`Uj5N``24L>4&5r&Ym}{5PaH>kqYbnkjg`uFTA*efuL{2~0%Jh)?l)}3m76xj zIJfhzwXRLQdKVxGKe@($?RW))x2Ju|&mn`gBMutF0vIaGyu|K5;HvfXbN8+wXcN+G zeW*tDg~3%V<BomAhhQv64+y3tJH0;Y7omomwUbKt>6G+V=Za%&5Q!Wr2HCMONc2)$ z1cmfI2_}bWd4{gto6oLsNy4}SqyPaetBXRk8?H#PH}@Y?u2H)oMERq4{l6I808?ym zT|TtrV4oeE`H0?T#TD;y_ap6;5L>MGsp)(={X_2Dz$SX`&`#VL8#+=L=xmf;_8ipg zCEi*C2@I%W)0fYOv?IJ5@Lri~vcQFZWv8WnhGgZvm|`<3CmZ0GtFh1_FVS@>hhcHZ zF76iIL+v0huKS3GXn5mTHb%bxM&0I)yO_)PBdK*!=E`KW#&e>FwNZ=5@&p>KIv^l_ zUb2g&3tI#|VSibccdE?1{*EVPcw8Cr!kDHGj{BymzR{0fzX(B-b<(i5Y45g)8$&2Q zj4`F^F?JRGvg6y%^Iz1R%I5txH{-IGF*~10Iw0+gdGFLQf3hWSYZB5_HDTKR%dgYU z?3Dkf2{^hMig9>49ANnS$KFOcoek9bBM^!?2rBPJ4t~cTY7>ViluxZR=^tDRdojk0 z@!%jJ_oke_Td8b)MBYdXuC_L_{v2}H^<9k+{Zm~RM;a7Z$SD?CGi;{4wDFu&V|9ad z`Tg6htH=lkwJTv3+<zy{Aj<NQ+m#|~p3O`;_czN#8>tjTl}!a^^|yn<96o8=EM)r` z$yFb&(k_UxXh)hW{F>oZX)_wE08|$b6n-B{$NUF8yTi{sVXvD&2bi#3y9~+4PTrJh zs8mAZfM9Q#7T-O=o{NLEn3Yn8%ZGAB$Q8wnoqKzCfkU;7s4H#weko!rR<N&s&TwI9 z@4MJf-R8Y(WawVg0e=7c!KXe!F}-RJ)k|fgIrS*YoZQ5JK>Wp>0I8XqO|$c&Q!4)f z7s0t>C}ibn7T>Jz!I~h+1DShyJZZloC}SegeG^96wrdCxL-lw{Y5W*5U_vvEFhvT* zV*8gK#0@Wfmz5U;=C1w+bf1?&?>D{M<uKoWI5hUztYruHqxJO(pCPGQjDF6v)xPyB z!InkK^QiMfCJ9@ynxRJTbuMVsA7mUNJ7o_TxAl3g*26z?;1<L>e&Hsz65fB?42z?f zBN}{Yk1|e{JLr~YV;<`z92;sUoJxJrGzeSVz!Zj_<`B2!rjAkApn_ZhJewY0MXtQO zI-DftE*)xs;UBl_HQ!E}HrYWu0Co%&Rb#q4t2xFXxrb@kak{YfC2Spvtm!|8k^lLH z>(0mauH{tx>h53C1LbkYJ4()yks1!l3HITccApUmYDMIj)MR~uD~Bt`TJhy<@q?$v z3gvH<jB#mf=?zQ~)cDtD%ZjXViCOiFG?>FE$@im0`;5_1!OZN!xXx@wPnZquX7;^X zS^s1;y(8-L<JUj$H74k!mAXn^kIVG7=y;E!vq^j3|D-ue96u673jN?LX;!4#1ufRQ zQ<CjM;#9$W#l+Qw?&0pSyN;ZJ-HlZwElx!V9?Q;=10~~0GQrPaLzG;q1_&8~l&TF1 zZAV7x9)Vl{H%y9lLoe)AU)o40DjA?g=)Db-*xRaa(gOGm+7tCU5(RjIInk<Zo{vpG zES|ax#)~kEFgjT}Y0=t>{Fe1%={h0?N*v>Yxux$oSKUJEhdb+2y>nMIoe?F;e8Jh# zMMf_5$qx<4rXbgtg8ob^He=dpw;(fcYmB@dpXEg&<%{jBH=@!8Sf73k>4c&{@wgq^ zm`#>5A-5w{o+%NEU%^m65u^TO4H-o+n8)fHm2*};dJneD1ZCgZ$@3Bo<QJ<iGk3;( zz1O6u#*v)`braY6L%m#&dbWsEDUoo&i{})xKN>t-{N%~iTx@@J@3y{kG>uE(03(0T z;aa-xS!W8At}T>s=cDw(R821tx6bb^2s=PwsFtw7iUU1>S-W1umDKgS1rFo;NMdIC z?SELT(34rlivwUczhP_t{=2q7v<z+kKz=bQzqzq}cyM<GT&+eq`rE*oCB!K#mgN)V zw;R}RCsfdtH?*<hc=clFth^&%N99zabz(zsf-&$g$M0B7r^)P^qCoGrq=fZtoA(=a zif(UtYJUzVnx0-|?C;uK*Kgh4Co1pSC<_OA_%AV7l#Nn;>OUN(ab}W3N!bZ~r$CE3 z>z=hq6-qf1(X0pUZ}jm7mQ#1GOB&LObkcfml>~pW_kk^vRY`@|OOlUWsI?L*;@3e- zp)uuKeO*0$2D4QKkTrwtuGUmtVfsVgsx1N`bzt;gd~=|bo#(lIGGs}pmTR>cW1Rkp z$E}|4=ioySgLQbN+W71>p*bZ1D8Q`Tf2wJqIHm-7+zg>tel(il9yu>8zox|xDjO=~ zj8hbDs!sfCc?3G$kxkmOeHAl&?Cegf_>EJz2t6bS7`U+VX;sMq!Y}ecAW68jMG7MR zohd$=`W9k25sw+dI`MYR=r=>Ak;TTTM&%xrc}PV;`_!YOm8Apn3eqoN-6K#G7jApE zx1p_RdIx}c6(fVo*NV6u{UqNM=s$nHW2#D{*G~7A(l4lUm69ecUX3VcH^s3_Y*L>I zz2ABB9BDds@Z?kNg*U+B&;XSIJHSBN+)t{swH`MF8CV0>*R%r|-|;@%wlVMOzu3I; zF7Ia0L@auhejkAdB}sWfE$E<sxmK$BdC>)D%tp5qmpYV43YCBMTic?I|A`LE&BJDD zCda2?VGg*s{wR{B&18!taK4n|bDs_B<_beJ%HJ*<omv=|bz7u5>On?qD(*{3M72a` z5Bpf|P~$p=1kGN@K+wCkkAB`uZCXVXoLb&TQD=(0PI{;9q;g|hJ-{OQ7|_{riYuRA zev>{Q?{clyL&9r-vH~g|EbY}8d!PFR>bnuUzV96g8T|3@Qv7>bvFQ{fxGQoQz7ZhC zdqw_Qls-SF1_ND5hlyA|o(@mS;DW*E2`Qj+dojK~R6(UA#g(2Wg`l`0jf>JBD+w*r zWyY8}-3VwQpgFb`E-U7ZiQ6{J`*p8tq?E8S5-e!kUcFvmOXWypL(9Kw?b_yfm<0V( z?MFgrg<ax+<J`%;gV28i&^%h~McXguT^HR88Ov_kKDD_NhwKe5?;umuoH7lyxp}EQ zliF2`x>rDe^ZTMTbW%AkH+~$u(&?Eh8^pB|j`TFKQWWC4^`eSbBACG%eWhtF?g~uk zcHw;%L6BuWxEK%YCUprJ{z?wdo!3n;Te)-a0dVn5>z_d@gMi@FL6?_CC+~Vq4`?nS zK1c3<T{T;AZ=eqiAI)fy-3imxRP<5`>M|4E+Wdrea!H>qbK!qcZSbmAgHmg9lC)7O zVC!Ud(!TY9UgF)E{|nylH$H6b=Kk?9bpI6i1y-+i_kO*nxHdFub3);QTcOXs1mmN> zc=n&yAMesHcMQ`{=vb;Txebf+Hgl^if;0`!HH&5IB2(5@z}ywkv*tZIqjCI*T3wRi zD7a_UMSM(;H&`1~;-QhyP;i1cnf3@GZ&Sa|*#kB7D;n6j#dR7R`g}Jy*ar96yZl(% z(Ue8jp~#EPSG^Zp(vI~ovlVW1+JQ~Kn{O_ks=L<YY%!sBgi-M!`CslXU94b7a5O!> z-sj9e-?FVDKSPP3mGK{v%)S{ced3*kdV=s4PT^}*(nuog{cP)In|<Vww<s!>gWm8S zQiHqk*rUH;6Y<VkC}9GU@VB%DtNRvpt2#M?2Sq0~WdTkj6seJn)yf(|StyFlx}&rc zJ!SUB>?(o-4j0rne<#;_9SJa{(x+eNUM|>NZCw^0p^}1qH7E$xHp%?|`qsD43E4mQ zFM~0>7|@zA{hm-9>z)brlaq&k1^@o;Iz4yMzWM|OE}I1T+_z#7B!#1BgCW1PyWfpa zObNMezALNbBV;p?xzFihd~@$rC164^q%E0DaL4wydggLR1#e#J#&B_z>b|r<+MB&1 zaMO!G*5*R{#E-e&>E^=yyWn2J@qi)<))Z%x4D}vVPIQ!w$)2)k$Q1tul7WVMNm;b; zQ5D4=L4c7*sl6QS@%h@R9n&+m8uUK**(SX^{#EvO>^oo4qac(kt!ujCqiN4JPwHf> zBt5K&y#_lM^8F3@n#Wv{=z|jm>ME_!a)2$;v8`~N!nw2d&JXL9AjJpsYSi*&)QbEa zYpZO@_plL_S#p~*lmb6^vRZNFFN5ah%!+1MI|JIp94ZscP&n0&+Ics_s5P<HRa7%j zf`{`mj?JQPDsCLz*N%*(Dx?fBV9Y|J7ybzuCK-|eDnuS=9(&Qk<K@hi(rQ16aY56j zLM{ItTU+c$ajRrp1DsLuuf-V!XV`?#JTbckA^$H|e1?__w}BGcu;!Z2*A=@jfs_$# zeq0pPtkhS()8?O^7<=OP;b2?w&%X-Ry(nVWwGZ#bSVEYdLa|EKv&i7A41NwQkC+TH zpvXX@{6f>Mx8u@;xm)}Pc;^JuKXXH)y&naCfr-WxP%g#4LFPSB=-A->LB%TU70Wyo z_cCk}neW*))!a*-of3UmtN-~4E+tXqP(O*D>2vSqzUx0*WWqv|qH<q=r51Q^e<W7v z3(w67pZ<Xx5VV-TmpXp^@yTQ!TwU!-&R0SEbxOsqm8xN8SH{->DtEI_&TGK;Xnd{P zgv_v>j4MoM*yr}vqtj(jF){dl3!;gyr^ZQ<Lq-EQFuXL{VptJ^@qcN>KV07a<v(DQ zdY~Dq0M-f<VaY>f@1BZro+Ws^8|g3E4OLiIp9sz9`*!_lQH6|m^_%Y7C|PAzQg4%U zh){krSc`+PwvIoYY&A&DqI2PzE32kI*^X5*tLOi{;LfOt30t*@9N<sH7_Zm$WCA>9 z)KGkQ_MiOlpw0Od9ewTq3E~cG8$hu?G%cR<X?C@^>&k~CYV6k)3<%gsq%lR*1o((= z$eJ|p+9p00O`@Dytt|p?|6ljvArDV>_xNtvQ_ftIV~GBLK}@0bHg2`<PB+C}QphsZ z{}LsH+#4Y6Hx-6(zklLc;&AWDmg3nH8s~;jX_@J<Xd9)DC(l$>lIK%`)Z7bdAXLcG zkf!n!u9>rb`5*1tf5iCt9nD6~l?lFu^<RVO?H>LvF&z3{?_n&9Vf&+jCLeT`{wnl5 z!%R3l6G@6z+E93NRhb?k9ne`x5i>sc0bT#MW8fu@yquV*m2g;FXr)o#nC`apiWjQ~ zibTc#{AJ+-8$(NTE<_28DxsSSZ=XMmD{SBN3F7#t{<{lVG?oYGro}H^n)m$DL6&G# z;)*LaZDF<9#!A<G;m%RHdVHS=@z-=7YJ56j7oBr|^;qLe$CwuB&#6dx!_#+ucvoFA z+HD$V#yYQ1Vhj4qt&hH2jgbf)Ff`kntJydb*6;oBAyhkf^`7Y$?Nh%MvphHpES^Wq z0uI1FH?9gb76->AYdIGN(HpWJKgLo-`MjE#@$ol1qndoP(JcO4S*Ip76r^rn{#Hgu zJz14f%ZLY(>^fiOfQv;pyQKZA{kFf8Ta_jP+Pjpq(^y~A)^3y4y-`pa5yxJ<e>~)N zqgvIISBOrNt(2X33YgT)kg0$GzNAt)@)UKYN$kmuU_XiL@2Ga<<>f@Yz;@YFUR;ze zsTrwuMWChZNr6vjJ)sLmNY4Ean6>vUJ-H=>U&4x1Ms|M*$Uk9pj((zzk{%SkWd*{W z?yGIj+q>J@zH{7h|17MJrf@~h4>fkSy{($vwU5Njbc7T%cj57P27CXzW!8Z6&zrpp zN~}(J3VmnS&Q|<%Uq`;;ZF0<AfBlOZn=G=zV2G%T(~G5?tp|NxVOGTGjdJDRzU?l` zKR$>uy>fz!@F^^Zg9o1c1`2^#U32+yKYz$*S#@>grTjkDCyp2k)pe9@A{+C{)&2SD zM{cdcp<O6wq4Ztj1wzbK$S;a?ws2@rS?!NIcjnJbiMw%>O8Q7e|IqnOeA<=L$GVX> zcPQ4oP(5;@@ALtKEWNhLNcoM&!^4yA@$I~pe4WHAkp_1Lz>4t_C6w9m?CggS1}KJ& zOz>R88K<~CzpBE?Bt%Dz;E0ii>m_QavD3zw3J>GV2_dgRt`pw)gQtw6)Xu=j`%=sd z^**p9jtR}59H#~PFHBL%=-iY0_IBg|w^IlAy8a;5P4>jo8jle^u+_D_4L7F=NrWSg z{DB~4XWot${`qI#7d6l2S-R1d0T{IheRcchVTQBQ9Wm)q%vUqi!BZA;aMS#20l1xA zD57T<?B{)8t{kt?C?9$u>gRgiDsuBy{1iUA0cpH5*ZxyUM(dBYFN{uBV0jM3g!lSd z5pRB(^r1bY?th%Qaq>Ul#C8JA!AK`RdK-7UcTgA~5L;wc{ms0poiC<&YDFh)?u=jS z`SU@w+&6#KO2H6HsQr)B{Zmp;!QxQw+5?1&E`zgS4>n|QFsl;haazneslQ0mx6O0Y zWDs;5)Sh3C|2nLY)wDuT6}0*~Vd$Y{mp3-mwffya8nrnT#3(jizd!ga<NH4jxCHep z*^<PZuSqb$zm2Lkuab8|Go755Df*H2os)@-75?W-50C*zX|>{M{wH|ty{?mx_wW3C zR#kDVoq}T7oiJ39C$<JmCX237$h`hy{qL5R6LHPV;`#g9`<GAL-TwR2O`$#j!0#8R zVOEFjdXZus)#}#|rnUF-4!^9&wUACyhI}(1{ATv+)r=j6$iHC>dBb}XJ$93xFLEvU zgtM=0?L>g*WrAQw)6I>Gqr9s7N(Rs#zWuh9PL5SAi_pDOu0@X+NkSOZ0e9G&uCA54 zS*1UflUTK`i|jIf+muS0;e>oTbrYg({rgq-VYq;Nt*$1=g1ogGd~?@M^D;u|R<l%b zqs=f3$Fefg_nn0n>Kgnem~-(%)Wi^ho0KQlhMJUN<iN!p>!0x>6}nX5k+grwl_@xT znJCK<lUieF=J~{nQM-Nc_)28-ej_Wc47CW-IXV3peK<=tfafa{5D3+@iKOyGoZPNI zTsFhUdT~DZ>POjOzaNlmUnYPRWl&Y%CV+p`2s|`0Sg707_FuF>ZW@}VU8>_l@BT5w z<&*+iwd@iz(L);v8PNl|(*G0Mcmr9caDqAM(T-)XKe8+0y!qJ5nKv3@^}9BHT!=rK zHE3mUk-tkYzg<<}e>Q(O%#9)Af#I{?17tZ(#$7_{7vxlTH;ULY@LqiS0xB0MaTCNR zz~B>~le(vk2P_f=cNVw#o{b}BQOk?qYa$GMBW4-0^I<!NX5bJ@o!C?eCbci_m~$CI zR*SGc%lgNacdc$kpu0tKg_u!V>qb`7n}yxKNb|(#oHe<;SaoJOGyZ=poqIgf{r~^p zGYqj&)Lb@GbUAf!=);B?DW~LIDlQQvavGX5L%4FS&9O_hW?c@W6N-?^P$tS;D00?_ z#T@21r+)A2d;9(8&tdQP>-BoR9*_GSu&OKPQLfwr)#?epZ%y4yr>lOvgs@;KAdlF7 zFMOM93V*Y{>1;b37tbpTY%jIsxV0s7gSw@9kLDcYTq*93+H|WX+wXK6=JjXgv^@R= zSh}Dnq3FiVL@hugTyZnf;fg=!%IJuMtj!4KZ>NrIgM70nSlaIY3gvU1KKEh=O{h8t zw#eZI#2n70!kldI<`RMBiRE}6>39QOH=HpAn->SqyQ%x845fA1sK1JLe`p{z8BYQa zg4Y%bsT<Q<11li8uT{${p!WwFKLZ*1Q*Eh>NY&9Z|AR%RBya8nex{Ezq<&(D&T23s zvtdXc7z=yQAWrAOvTh{2nS|3((Jb1-SJUOF#UR<2lX}Wt<s2ZgOAFF8;?gflQbNv4 zHE$*}bR5Gkm&3$)X@mF3f8>!Ok{62p%PdN~&fx&O=hFO5XSP^92Sds((1J&&hcdx? zv@cnKzU!|^Kzv*`v~YbGZ=GCV?S%D4Oj9>FU-NUjn7r%a0Vw}XS3{kgW&z{9Lcb#L zcz8M+?!nJWaV~5Z-)<F$gA<HZw=b#FF|Ho{+vc_M`crjcMt24-caSyBy}La~?jbxD z3a+C*;IG8*tza^86;j_!*O@`iEZ_8!x7HuJ4><7hQtF1X9OiW%$8Ld}`j<V$YRCM# zF8D>G{G-0#Pq(_Qcc89w6O7*E)Y@TZlDR}jP?B?OG3%|=c&%Y{$D_i%Cdb3g-#*4~ z{fX73y>{|)7JCA~*+WEn9QffXO8(3*KxeAc`bDmjAdS1uF_3VJE&zOrEG?iVz6}m3 z+~<+AXWP!mQj6}!A;6RqiC&=&ofSAFym$pcI>#;uEMz{FobZWkgW#0cK5N`UJ=PcG zt!}zWzfZX>f^`^f6Ic^x3UJ@pL$ozZu5g{%?QC4_>`}Q+OtCg-Y|2D2uw{&&!{u{0 zz>ng7!HXih6AuPBdEL(?amoweGS2TQYMkam1C>|9g6_QFY*=t`{Gu?&d}iwCMP)y3 zCx18I8FKe*gQj|&H{NFDQDpw*#xLP---gF;xmKM2qupe$KE<ymFRaehu(5v5G=&zI zArV5pyXVeBb7vc;X9m`X^bfXFJL1nEK(WSXi{mHNdTIVD_c<acW$C?!kyQX|aVw5g zA|7N5?EuE1%d)GplqAJZJe@gYlx5wm>AFfJ%RiyHs<;fEypud(iAOFHGBsJOI`Bd+ zUmk&qYDVK&aK}&EPfe5Q?wa$HsJ+me*!H!}KC<6b@YN(&F!QP5eIX##F&uB0YM!5x zA{*z61#ggn6448n`0aYI_+j{oc18Fo{J_9(dp!42ikj9*i>;u`eXZC`Qteo*HxIn_ zJ*zCdotM6g+Lt|MkC1o~PTH-JMGDa1>*aDOs$g7<kRx_KCcJecACCQztpvMnMwVK~ z>;wTZgHjry;*nHab<wrdAv<W9KKIfc59FNm<hps^J$Ju)L}37W_nqh|+k1kPYGIb# zXweQOLHHbD$rWi8TT#7g{Rtz5Q~}NmLN(-D?CHg-!xqIJtbe(f{8viR8VE8>Gqn&! z((Vz9IEopTLTwrjibWxqOjuO2xI{1}iBPI$me%E-!?BvpI@zjOCJA#|&eDtEJ?dB_ zys-%aT$YW#Y_a~~J(}H&bJa)d*{xa%8ItDtjS*PiWdP>84Bn;noq`kUS!!?y9?OJ< zE0S$Bk#e-<9{L=Kj0rUnw8gHJZ*UeQ<G$02WsP{y;x#B5<QxA2im3G>ZZ9;YxlH59 z)O6}6tDVuLhw&~yLPVQJ28LjEWY*>Po|(!t;fri6$|p+>hHf<W59ntl1=iyY02Fip zvQnn2lgcZAspH@3Ggelukw-j^m_#Af>sFbcEVn+iOwn{fj?Z=lhxFZOJf)z04!b(* z@=`e_7+q4%-cu(OIE3AE{Fh!ZR9D4O?*jt^C!O>2!lC`FIuZMk-LN~FO%!f!CDYw5 z<j!v#=8UM*Ws~l$eE9tkqCu){j3WfepD|Dry#6PlkZ%vgDYr_f`IY{U6e1Bj4!6eb zy7zdP<)oz#OX`h|j+CD`pyDSgpn>>I+&aGEJ=tANEkJd8FsC#!)B`C_Ox16m(PoM{ zi3d<&Xb?avhGt23Q}@8r1{tiNd1#<7g;Cu9%n*z6r&(^gPG@-ELv6)%14(C@xiBQ> z@^c%%vwqF6vSqO94@OvGx}?3PJWS2sfj^&WlhL0YtMVd&Skc7E<IQtUEHEm{u!@N1 z;q@u;aqh^A5Se5k`BG%Ts3Kv{MjDl9Azh=89(=V*GQ1VLd!Zz>+0MdojAhQK$vkX+ zzTG?h_0o<6bi->r_uDkJ2Kc5SW5kPX$D3j<k$wyfqzK89xRS}->I!Gp!PgXOY)P{V zL+nMW3Le3l*mMTon}VWtSW3TQPwBgJ00SJLJ}yxnhmSM{)SmD=>?HCVT4Vydf=?84 z=SMI!aYwuO3NH}p-DDpsn^o=zaLm(~r85@Tl_9<br0t8@&OD>9>Da;>q}Dh*CDYG^ zPH7rNVkVu9{CxtVS>ak@R*e9o5H=ulQZlBQ<FE#DBXkaH*f0vWnCCJiPZ(sIq=>%y zoGJ!hNdtoM=!Fe8s$_I14E5V}m6Yk!$RZzn`LPd3))5aMu)+(5;qAVVrja=Q(54$) z*>3te2$}s_dVWtgpcn<Etd|U1LfT?E>P<qXxK0V#a9I{Shsy-2s~~z=Vx@Z;uLt{j zYWUUvOv>*=8C3Z-d~{)RnI|Af%beweZ-QRr3|>3@WW~(4>4r7&-UtIo8wt)}6kWOz z(R54^ZWEr|LRQ^M8JBw+0hjEy5q&S5vb?I9jq6wv^s>-8mdn}{%0V<$FR)?Ix`#*> zTjM?h6rNvzi!jqmWnvoVuBmHgAo+DH)nXxQT${IHJI(S29rD((7a=O-kl`rI;&FSx zt>fXh!K5or(B5sD{b~H3n=s{_Wc%#-QK#pSHS8|{uVWBCVmD2W9bW_YHxLeVA&wS0 z+BbKnv=Ew>1}+ZYN<@E}U%-J&X?(JM=$v3^c`q1Ekej;>nZ7PsB1>}sDjiW-D+LL; z(`9`jr5z+j<rf}_7+%E9z)f7zw;Bd_lH9oXdZuL5Nd@WTyjSjm-HVF;Ftx<5>bl$x z8@}zQw1v9R1IpXgj=m|cEb4brzW^7ISc^G++39N@Q}_|c%hk6Z&yD6G1!of~EwddB zY=Fe;5bNO#@p&|2!&Sni0ITvkrI(Sfjk-Gyzqhc$dYpP7`5+ty@@K{L_-V83GBpWX zbqROyE!C1qVd4!QBUqy=o38Kroh$FQAr;z)vjPh_)Sb7+@Zl(dJt2L0VOR01X=F_j zw71kWyD>%sz|Mh<M@Mu2$f5Zje_;&z)!JHVXMhf@!xSFaWCTtYcQ5Zg2CxPO1<-=# zmG%<lwuvu9%A$dsc+RpaJ)j%n=vSNKgK$`9n~z8UMyIUT*=hnp6eDwmCHGey8irJV z1vZ8PV6>|$PIc4P;iQVLSUJHE#sbHbY>VMc&@TH84I~B*r@BX3HbVghSPxG>^fDZN z04(gmkZa|w=8Fejs+#!qC84#%EXI9^Y>AXvZe1Oi=KVXL6N>X2>fPQ|92u&bmb<HE z%S-7FP$W|!T@h9R4N$Pvun&vnp(3|WOw>GlGktx0O_ItxS_O()3c0*9&7zmRkVHU` z#<!3(|DM4yO~i79%qbfrT4=K5;H4!KqcHj7ew?zW22WkR4h*ASJL2R3x8qjU8cxIR zLa}VsF_wL#7Si-(s-DwTd_}_mi`5agK22@12V$Gq6nX%|B;c)@jKO<I9`zn7x;Pw- z^s6-UcP^nwgnjB3(>`e+Z5EDj0DoiCV;}q^tcNH4)TTGxZleOqe~ti~-wScgZp#p| z7Np%`Dvst2Q|%iz&<=Cz99n#2U-x-x!piT+zz)9rV@S1Ni+4Sg9Z=cr3?&xj7x^+6 z1Dr~}6R@1e#%jQc1HG0l<*+00?hbuW!4WRy(&|SC13L^b*ePLpFQ&@?4y^D8^9?4& zAcKgJIeeq*R6R7+#u3CckEVt5i2QHixDUXdt_xJ7HNgkjJ=WpHWgeJxbqTcwGruO~ zO;@_C>^NBWn;)0GLY6PA6T7FLmc!<h5oFA7As#53O`G?nOF56-eBtO6o>*aF8V+uL z0B5NAxpT)c>T+ql-JmE6Fr$@W6%DA-+6jVoSeeA{h8gPpdwQXxWHI>gO^xMM7G!x} z&P!msm1*WG_gH$g>A32{<js|DR*;v<R|sjnrNBXnSbRKX(LBEdW7Vs+QX>3P_}rS; z4YCmIlb3WW)OeKN0NWvY*hlkkZTLV1=kKS{acP1X9mj_SPD%QoHLV&|UM;0?%=;j} z?R2}(<2N{B51X%8cF<bxW1Sne&1<$vx@`38rEX_HS~E0hjYtda>n%XuTt_X_<J|xH zL?+xEUq{Zm9CUka+lN{zauM(?#EL`#;AH-|pU9<akKUE{bKF-ZNs>8LN+e#~zU(;E zQt#m30q~|dvR?dsz;Tc71{+!w<jB19paZqs4eed6upDNW%hfemNP|3NP<VUD{qTmF zDxI`F185Q&c|=afyN8)f7Q&D;|IIYBC-2z%uyOkFe`rog+U}7bxj3xZHL@(#Shmu4 z1|P!=z+zW;v{H?rNA^{l$;WEd+=O8t=OTyD1Q~z^E8syQsfDXMTI}}hogQ3QeAKpf zIdp%QlxEs+5sTGSYc^hC5ax;tUgxrU$cLPtmY{g6Z4tm`?*n{fFBWf8Rf@IH-#$CM zB%s8}oRmTaM_6OWNnqP#C9(^_@`67MoO}g2Ok{slZU$q!$o-U1!m&98x_mP8gDJpN zX8)8ne^?GFNoM~78aXJ}7u#<=!mR4ZQnP1L9VaN2etjgxbjgtcB=o<?&72l69sUt1 ze(ga@Jp*nH6A2u@)mE7p&t_eNh(qV3&{_~<Jr$2^3y~+?uj<2z&|r$zpyhZJw@jM@ zmZ|_mE1`#;w8o>xXe>$qhLg%*>~lad&HPebJ9NdZmH5F{62*9|hv=k*{dfMJOfc#W zhl8#J=x{s;35OE&+6g!FsR)NCfrAEpn_20$&?aYA)pbDj8zjSsY@>GNzKQ(j><a;S zV77<6-@@QS`|*_CZs*dNf!Uu1*w40>fRAPs$I0Gz<_Wa~v4Qx%egd}=HBQ2<ZU??E z(8@ZwT>|}S1NN+0cSm}UruEK(i@t!F)2KYH2)uVcc0et|8@60VRlg`bPK}&(YCiXk zErkQoSIMgtw%#Y@nIWyJihkSRlEc<mn4((83-!6ZwOY_AIfjAs+M#?*p+TrAS;kfX z7UOhGc&GptVOq!pjJij_3sBVeBH9B?e4W|%v^NE2yjP>QvQD!Bss}33DXbJQBp6`4 zs=0i7)^)E*%xnFz-YkS;V`M)b*7Hy(XiHk_hQ$Hbw~CCtV^&Ioclw~_5C7cJYTsh} z$89BIi}Ce9)OK=#<dsn8>g`9iJci}Uk4#a$S>0&?xK?Y|L@t9?i8!G_Yd;FnmS$-> zKZ77RxGv&ktZh(4yOcM&VxTMDGUZHN;5Q0AoXGj_Pba_9r2>FgVA6OCyaA#gJno#F zEQjUL98_aU){eyR7FV{lAhtS<DYz?^9M$2txN8ra#Ubr8`XX==lGBV_RRbpzm7))@ zgGOn6JKyz1;F~NTI|#R1;8d|$2RhQBDL*9uebd`)KF1=tjgpr83(!I@<@6&#5eF2e zN}dz~ET#6A70w^^+lhhZ!4j}}(#qzJgf?dss|jT#J77uyb;SW2oa#e>`Fz-1pUR`~ zsyRVcHL~;Sb?SA=rKaMO51YtLaTRjMQX7FQWTBaWBQUus1N#(Ljy77~u5gd+g(6o! z0D9VJo6{&N=pS<eCxA6!n=}h;efp|bxE`T#h;L(gr&KSl(jl4A2au_rIl|?ii4`6j zw)kc~Nb4X=ObSg9k&e?T?JFza$@^e|gwexws*-pKtqD;(_~>Dom80&M%pmYiUVgDO zEq)qQ+p#%^sf3&v^ZXDCtADaR)bkiNL4OQI45fsf12G2q+Q-Dkr@;YTY^X=J$*$t= zz)WN+g7r*qU%kK3gjZ%0L?TkHkvG9+I9nYAabsA$inrvRN`^E2!SJ`9LiupAYNO4w zQ=Qdmp)P!eBLQ&<a6kAiY{H9-rzLZ$%CvO5X~Mu$<?fHycr2Eg+fvO^S|0euKT$Pf z$pL`@mdi?(q8C_oGCp!e;G`)d?Z!w03-_#0ZP;*PD;?TT^KypNl(VPO{Ccr`M`%!5 z(Q9G~hcIy#tG3o9y<KtYD*g4trs##6U~1pgI%XC8Gt9aQ)S2pGCyR56EbX#eBPjmV zG|99+{W&7IZXN^BDf}HnOXaQid-V?dmpO-p^75#7Y>9@^t_8#bp!o4e$r`N^NH#uG zky^O(4ZXw(I%%ScTcE70mPj#Qv2oL&6%SYoO^QISt8ad%8(8e27@r*h(CPn^Iu9ek zoGe8>bC=(UBB?S$7^ujTr=%KKw}8i^d@z%2$gzmz+x1-~E@SeSI1`)h^nEpz-X_zk zy8}$|Y0c{sF`GRC<%2YbozYA_KkM}6M$R4%O4TG_umnYgCuRl#C+85Kq&e$};Lch_ z&oP`uh56vM$4R?OoVvPM`$rde$Ppo}d=@NX0me!`5cW=DAZ5yfC{B+6eS`yKBPoTH zT!b<gJQn4=7<%}(_%C4YZ9P~_9#*`?aY-9v`6Nn!0R5Fo(0iOFEZ+DNknpR{ykwa% zya$mqrn3T${h+rTHbEN&WOcptFj<`eR!0@*L0Lc_Xi-WS;Mb*rTURVDwElycSdw!j zeK(&K3$d7tS}UEZ_uiLAivxh*5FVazY|P$~w9QP;&_0)(Wnj?YrHVseXG7@-2NE~f z8Txl#LFhw%EU?6|6D0;J9@hk6jV44J0A!Rn1p#_b)>E(?XeG~{X^s@)#+S}y=(r!V zARJ31lxiO#E!FjplEnkg55|Rb5k(ODa0@hKmcuI5JQ&W=pd;+hb~L&hgI)>jM8wGq zj+z#m<J6OeIfy$-KY#{n=(BDG4tJ{do&@Vn8~2r7wuj<ypkoUZbwV2R3NZ6j!<EuW zM5QX-J$T5y>f>aDwH;q1bG~anv%-lrVIhM=JeZ$mp{wn|LhHD(XxF`!TF=&`to<lz zP>Lw^iWKrH!10_jV9geT&?o(9?5!(*hiO!_hg$5;U^*2);lzpc@{%U;NpD=!avh~) zm`j|a7Kp6@anxqiWc0Q+GeeX)%0u!_e18hw7$mUpz*=e8Lj>|X2Q7t}?s*BBu}v5c z;p&(O1RHJ#!apw1bB179f%&q4DIBDUHR+B2*Ao+7hmcUmk%LmRv-XNQlRS#Tc7^#l zUaomjb_GOa3zAbmOQzHxi!h<=1%nsb7W|ZguE5fBY;j}rOv+YwJ>=ZUHUp>1DT}?w zehjmNu{;*fHDsvK7o(@TovcFv*^4(&zK@;2-NYO-iU~uhUvV%<Av66^q|X=9>k?)Q z4kyv6U!-LQT)Ij4<d&x`6j(=Vs39$=%fhYO&Rp#_!l^JW+@|#SoxdYB{}EH^4=mp{ z^V~|bbt(vtfLU<D%!j`-mjuJ-sYA^|Zf9?q>F&9%>k+^C>vNK?zDanLuh6@_`gGxr zXG!hLvF;Bac@2j%%pdEY7c4lGjXJ~4*fzmg=KnkWx~=od&P>wf^-Sz@it&=iYIj?* z^u|k`Vcmz<U+2-!JN@cp2#jR=E*q}}w|^nS*7|uln?z5BQHn>~>q0+rzeJl2=9r>v z{FRp%ejlMov7tB+!^yJWQQ7nVD+4;UEpW80ni5#740?+^CVMc#|GZ|jV{-dr&sTX3 z1{M>s5SzMwr6jFTbr)q(omeZfW6|6dY~jA9x~Y<KvD^X>>7FdR#9rarKZ#l(mF5s4 zYl6|B`i43j^~6Kxl)aT-_&B2;tP6j75X5;2REwJNDL*AmR#47j5eA>{8RfONkO?w( zE*Z6kvBx9Ahe2*vdW4<IhA14Xxj5^{DO5gL;IBNQ8EQ&xd92Y+J@>mqr5sg%7+juv zE?Qa2H17Ri%TH?rm*$JZoya3ra!lE9YZFY|%Le&S%}E`c`P&Tq>=nC7brm`w8n$sx zG{Ap2Z?JG4Y*fpJXclY+)YW>*O{cN<J`p>~cr1zK^e}C=XWeeDhkqK-B!kkpL(8v@ zeev>1<Bo7xz4)Mqqw6=Nq-2U>lNO#^%t?6pZ#@OwHREoZekam-xssv?YZuU3i9&?p zm@->^2~RREzaDC&eo?i^ww89OyM|a#E<HGCnLtkKEovu~s_T<{^z6J@13$=`&fgv6 zp5AGpjvaTzKe_giVPuyl&RWcAnSSQK{m$RM#19iq{Zfi5Z<cHo=H6Raj*mYdDYlro z?l}Mc`FA@9KfE4}zrgogbj%&p9#jv`^~meyX?9Qgp>N0!E2Ww`lO<Ff(%#|BNaH?V zACe6{&E{K9WXm<SMMP4TDDkqYZ7;4>>3$owk(lv8KWdLXdHk?VSnDJ7(%0JmeRl1? zbQkMtB+Lmfp%sm(g?ms7kvqD3Kf4+&Lww-2$(4JGyuO!7?)j@dDOh_Bs}XP)i~Oli z>&ZWLB}k$4jeh4|(F;EkVr0N1haM4+2rb~YEj{%Ux3*p=_%j$fkZ9uJ`#s!MU2VYK zXMDLnxkk@~#HlNdeD(GCk$*GqoWc$dD<L^y#D0{A`%MpnZv!3vD_0&rNp-qnBJ->^ zTKd5BIkQ!MFDla0Lp$WRy#1a(kXSxF0PKkMJbsZeWr4Xozm>fC#FBcZt$<|mZllXx zCqR?pUljW8OSI$b<+3|~?(4IZruTFRzlBU38Z4Jqf?x1`a9t#=%<+m#)OG!ESztiO zSJb@~;0S3;avN&GYXfx*zjg(si!W<@!hspXo^nCGPXaj{uCSp-;t;cDN~)LhKI@lB zZ#`M|S@-J$Bupk1LS%{BrUz0Lc~ktf-uq<3;FLP+v#pF2%a5xvk`b_=feWt=+5ZA` z8TwytqpLaC`JnXbouBQF!#AgqYb#0>Czj4iT@VQ<%XtI8mFH=AydVUCarLaF^mZ4H z_lS8xjaw($8lgYwH?_(|KaozpnIZQQqpQH@Q&&sH)5m3I{(y~)kxA70dEkGia)119 zWN-GT13%8SVFe<OgO#6Ak%Qk2E}T_p-~AuRp7`VNo2y<=67GO1VwFt~{qF{@!q2Z> zgkW80V0JujUv(}1-}R=s5w);CUs1xHzEPc?$ODx<4|oOVIH%P7L0N(S?&pi(93t&1 z#s6f9al`kfvzmDcE<!t(E*sd?k9SUbyNAFC{5W3ojPiyYuh3FdmdXb>Dz|hjIWI#h z^UM_u?LY0vtav3baT>dS=*~7FB=W{9|7yujD4ZW-C97W>TjpOrxQ$i`8A#h%T@zgx z-#yh&J6;p7u;CQDk)ru<qEjsfK~z>-8UJlL<yO>?@CixaeTUbTa8$ey>H37a_1{k8 z&HRN9B?=<Hva5A~gei3=DZa*#c0WIRIT7Cgjx+j0iE}m^9zT)=H{>s4AYB8uI*Uj? z$t_K1egW6$$t^GSc~2Zt;=`bu{Xb}e@ITBhq6Rwm%S4W3ocjf2vod$Jnx=+nh1UB4 zL=+N?Dqxl7lVK^l&3)=KV>ixiOWIb-ib%(L^xy<Ip){V>-1<;VKm^bBH$*Sx2?bHS z<P5MjutK=~Eje@ZMb)?!g=89@Y_46T=*az+Ht}OO<sW6`c9n}S2&zdL&$b=Tg^2}a zrxVQn*pwXyi6~zlE?r#S(%Z)7RM$m*;CNY=y6@U~Mg3P7*xbaZ+w8mg52@Aqa~C#P zwYWEr;*qiYudPRm6k_y7b|Geddefs}=;`xnQSt7kiW6^FY2tFtjrzr|+f&ac@BX+B zjxWi%nf#&h*~@k|-)#yEdF|>hu>46_UID~@oLBd?^3SiP;d*}^lk}g{OHM=U=*Fa3 zv-~nn@1gUi2qP7Bvf?TyS3=mBbq}$(SF3;Y9rZMCbKW@4@HDLpV7d&DzSn-meYM;h z?zEVeSHyYr!T-{d=7P~{)m!7jVeoPOCr~}7-}lF%G>t^TySJGWf7H-SDth>BMi<W+ z=ovv$Xch)oZe3i3lvr@SsX=joR{*uRn^tNheae>Ns6f*(SsG9n8hhr+&W$=HGXDKb zGt6v>w)`R5&FtH6t-1%H^Qtyba_pS;jPK<pqz-5qB**#xH{kjO<iA2j{#LF*Tu)+T z(%lv{XxGeY+;S01h_Fr|Ddzc1;ekVz#J%-<YV;<F^i@u2(1|SNXu#Ewjq)2Tgxzhl z7f6KbQ^aE1@YvFvKm3MmWQ={H)WJ2(0{!k`0Y%@(pvwj&OB{NBBVb|v6l!x{5$k^) zf%}3LPR)J{`+Jr)nS8wEb-l*@qn(q?laf7%i7{YlsMgBpwtbiM)z<~SXa6w|AJak# zz?N+&JyG}JE8*zRLl%Q5BRkFM>0Ts?ihq56dyujwyDavYTgblIvAnU5Gd1f)@jtB= zXs<VNSB1C?e}nKF%6f^j=M=X+!5%u|M^a3+J(#q(_5uIrg*PuiZ8X3Ji_(ris-Ge~ z8;6BMc9fh}kV?41_v|>`brn3=Cp=4|g<`i&x=(bd<Xv~_$0NLWXq}idCp%Tf*T!#_ zs7GZuOq)fqRr?GWQtez2Zxx?-`kG$;{=fH7!MH`ChSUR$=8s*4yF>1iGxY$mnP24a zJ>T(m2De|xl*8b>j3rz$4p58`p+RrfW<!g^OmAy2nDF6qq#;$MLWIN3$GuK}u1B;t z3=^~Eu3t0#;c+;L&r{DuD0RnNZ$DlVaCM80ScsDau|OSF0?g;=o5(-t+C0r)z*C(w zIE~uAjB)Qn^*DC0!o~_(3tDsk=00EUu_2oZ!BA!G)f%hh2bvv12(6WgT>EhT?#<WH zH?C~CYg6*l=tSDd*d5&`wY9Z<zktY`eUAe=k@Ju_6CRQYH`-7#byTF?Bmaz!`+Dus zYdf*@!AI_3JN|8O5F}~Tk7nw34ka|e2NiQr??QJgQW3s0a@U|oO9%l}Yn)$B%3KWQ zuJ&!8UYwaOir7mlb+4``hCk69QQHe<iD$sHqSp(XfN<~c221Io<WLy2h^gcv_SER^ zzfWwcOlbMls4z5nWu-hc#JBz7KB*^nD!MVOCgj?)5Ico?39ON+s~3(tsNVV#A9L=< zr!*Z-&TLk(A+7G{Z%;!z#NH9<0<PnTO|4y=dek|B0X+w-z0c{KJ#D-96m$C}9pk&< z?$Y*IL6fe)=F`HSg~+SNm#SC-rbeSC+1P2m$2Q@n%neodI~jxS0W8NaU1xq1wdNY; zwssde#eI7*TxV`+A!X4@D<qDMmc#$)?JRQLyI7w9a5Sa|mPKEao<Zs!YSdzk@1H7c zR!LSRm^20|FaOKiUDU#kC+b}6_?+-5E&N+u&UOHJNug}Z9M;`#n9URNFl9QceX$g~ zzB0mP`)3E;^Ew@2>v8^H>T{+ku|b}%u;4vPI^bNFehl?|LKXj7W^VVBT2J~dt3a1! zgH^)BriWobm_}~<A-6ZO#F0eHXOB*h%kyC&#kh9x6m2GSUeGn%3saj%+dNNV)NCCR zZ#?&UWm*GH-@N&3<mBk+ncN3P^Ua(`oLAVVO)r}RqPW3NrJI4G2{YAV@X8iu0Cw8W zOF}r0rw715J~(koFT8uD1n9DC=fZlM(68Nlj6Y|HSB(=v*6M9hbvthlIII*{?0xmG zF4?ig_S<Y50j~4EI|$SKP}d@(3yhI>be9aaTF$_hYr)OS`i>(k2$7z6-SBtMo3G9* zY>!2~`?r_kmm3sf!q44MlFQIRRJpilODIViZAB1{eK}mH9iEf@gjN{x)5(%fq_3#b zong`FFCQqx&Kufx2nnL_g^-jZ5Pdm&j<S|D@BHVOS*pp7)OaGH;Hq}iVfVZ|dXd{H z1F6b0XKG(*6O2ELpl!*eLH}I6^7(Dai?%KUP8c97o3;xbd^|kleMtGY-v{5~P&*Pg z|2=#7J#i1tD8p<HuhPG?d)a=D+57BsQ(nC4I7F^WpvL>rEGU|?IuC6tPI*2a$iw^u zG3Yk^82it;-(x1H!OL;Bnau39Z-M_Csj>Jg@$*Yf>`D9$TEl3^i_^KWAcah7Wiu&1 z!>faiA`_cep2eT{Z2x*#&C90CRAE*i@Nyc=E3Rr;Osp1c&xYz<xgN@#C0oI7#bfN{ z<Zk>$s`m-$J!Zbxj^v007ji%RE_k8sY;82H@`U;Fu4$(JO7fd}eCEnO-@h6s>nYu7 zIG)nH_CYd$5NNjc>=nA%PQV}fU(aAi=OHfzZij`p;p(>TQGqMAaK1e!{w8wvl6*~d zGlp*NyY8r`52{dMAz^_xPWWkA+aAqH9hgDX^)#df$RAh3+qDbQIM`<k2$Nyyz2BWy zPsulI4b`{r=-ilj-y!mnf0Hw|y=42hF6P&l<r^o3j<P<AXNT*C_YC2lmnk$r4~}I= zSk4i4&T%hg{y~KtKiFoXK!vG(>6W~F&~G~TeYiEEf-9`N^r%zrcAY^1q<Vz3=)Teg z^CsATN#|YL`+M)YotH0cJf6659vLE-e5H}#XO?Wp?^UXR>IGMMn;5&y)*(Lx?4@R& z&9W|R>9AfC{iX1x90cHSg1%ZFxuaM@Kafo1bZ*3*C(*~1ij>*li+=AgDB{L~{}Lwy zyB8L=eN&{JmT*f@J;%S;j!0bmYa#1HLF`|-w^l(jsagMxXVrzd2W}{}DNYliMUMDt z@0;TlUL}wVA>uk||C-2gSV1cz9{8i}HrWZHg%lcd`$_J#{59MME%+6e8e#nmmX`+J zpgF5&Sr6L6zjdsLs}hS`#`x6y)BAg}I*>wzR(hxlo4tlwt8kW<O#}|7son}%NOKmC zzb&T+^TDYkAGZ%q@iZl-aWQkdMbjtNkC^)(&1=`~1s4>W{j*faUZ4HD`!Pn4&G_@= zOXqdk_0H^-baK=!`kEIk;qgz^dCmxS)^o=F-Bj1SJLs(g1Q&mMe58Yky5=C%?=l4$ zxZ@^$r{@t6^J`sBGR3GxLTRkrmPU_Z$zkQHgts6ld<5*8R>!0seR6DxJkgTZWhzhH zRpPCeo6o2e`@6!ds63^g6C`Z4`2NGPquvVz7Q?1hGe$+vq9yDHZvlxduumnb1fAts zwT!De`pY5X{^;Uu-6kRL2C`J<k-seVvLij}nX-ae2fz9zPRHmB+po=Nspt9NvDrT@ zRXp~jt;a=mnZ|uh{PAy8={uhPKa=#F^(2>F;w91p%A<QSMfn0ek%D1XNHi>9B+CAB zT6%Twra8p(wwo4qv{<^oh{>+(dv@Uc<)JwLEXBDyw@#@_0^<lD{1ah7v)f!>@W_RX zz<-6<flg{-)8>~=zs0G0+xYOyx!l}DGH10?Q%S{kCGahLrVQ{3*~1MwZznyJZn2?G z5vYFgfuvI?`$5@F@q>8G14=TZ;QgTn^J@qwjvL%7C32h)3btdO*#0>ZNo9aoz?J9f zZSM}IwVI$m@O+iij`+Q^*>JNpGEdy#eXr|VRa~4(+ntA_)<!7V;igfQ4{kmw$?SNk zQA4DS$`iSv`rHcDf}Wti1>uzyUKO#wla5(M)~sPzPWHlY$5dS2-L<@%aoF{*9ejNM zRV3Z5;G0a?!0aAnRPLGM9f+&QHYxOuuKDiIQ?G_hGH$Aen(m*sn3RqC`hLpccWZWw zkOg8RbJzk}OT(WNTW9}ec!|`uDNok#67qdE6K_1toi7Ue>*gICWv@-SCX!SCznRUm zFD@No9Jn%(wfKqq&4M?z!poYf@wC+FR6d`hIQ8Jsb|P3A@hJ85EIfGNctQ9xvPD}@ ztm<2nL><rHte+RKxc?iLBkd>AV7ioG7=@BtWWU84=cXTA?9Ukc<DuBu^6e_xd<((b zNw`vZ-~2#~!R-4>Q+Lw)lFgeBHwR-@i0!B-If}>dU|;v(X}R=Q-8qLI(|mN(6wLqR zm#VT1Bem=AMu*y{#795<205HTfNr|yzWOefN98e(p56Ln!CrL%!Sa&DY%QaQOn+Y+ zCpM|#`)yy>E1fuK23~*RT)`exHJ1BvgH&Fd=*YFLzAs$8Mf_(4s<9;lOqj(!Ia>Sl z-)*KmR>0lxn69L)ijF=1ovw?`VVn?Ez43_vrhCC+`l$q~rI@ByukU`<CdBS-<4#S8 zL35U)K60lv6H;OXkrkrY^G>;zwWPZk0mel@H81G5{tekMeCyDAu_to3uExoY5RUge zFZulAvAlWcqu3U;*$maU`dL}SHv6jhP3p+@%dIS@pwE4^h^hfDQOo-5t*AM|`+oaV z467wm?=ufps{Z;Rm6p@orC${6QNWS>1^hkV*UL3}6nl7wv)4WrP4<=~KrR{WUod-C z8{yc!uYv2}@d#uq{FrXUV_J+99?PBPa22!|ndXezpLeT|1ivi$dm8hn5|@8Jn6zl6 zYJ9>}Nr?T(=AjLTFg=Z)G4FNjAa~6QI3b_!Jex^0XMFk4H<R_^fAWugH9sBwLb!bq zGQ;Yh_3j+U>j$4mz4|eBAdmA&kzqJv$oKvqYsjhMvL}D7gtY*fOa(CUE0v|sco&M= zz2@#H$;*n3POg1#czmBjyj7ehuZf!1ECW`Mk|hNPI#gX(K&Igq?YWMn;*E%09f1^6 zK2eG%au3s7FgBKPav6Y|GYW2ZN1E%{?7kQF2Q6GXiEt@cRb>=bW-Yua>jS)T&FjrO zu&VFxzAoX0N{2(m#g)D2%Q+y5P-!Wttg!K++tm4l%3d={|9Lchwcu$`%rio=&j$;G zN2k>{GV}-sFP}~j)7pHNTlwi=?{w%0+pFk(KUejr@7f(@qEJJPPE4Z`9wtH-A%A}P zCp&fTS^bG%isYxqF`F`9S?qStJ3CMO&i&@~)SM?*l8g{Hg1wVSXbmQLiX3DT>c{=S z({mrD7H7bZ3u*pY%-U)imrLOI<p7bnifJ4R8>@?M8_r*+11Go!Mz${2P9yEW#A`{c zfC_U8S{c&4<th2rD}l9cvr#|>)@FzzkHWycFV2Ksxbv@8BGbpW+MC7lY(*sp{EY}Z zxQv{X=!`h9xTE_h_*4On*>uhM*;1C3O2BW2`^d-lG-~OK6ue8HX#QO>R;E~xpH}2N z+@H7m`Sav<Q0@71Vm#Y7TW^i575zjW&o=HnOgLT6smpjB94GI1<F8%sCM(-*$r!B9 zqxvV=VxBQLP!{SEy<a1e7Pibk?-P8?#%&1G@#GQgQ}TYI0XL6+V0^hh<uWe8+@IFA z8N<KlLQuUiQ*?XcmT}jC6g96MVjcK~NYD}>C`TQvBCW!osU`+ZY#X^#e*xC!mp|ao zOQKXRx=(L4z&1Vj{;|7VwUMKPM%Z<i%lCu!6aK1O;w`-I<h-Wz^N*&*4yxWezCOpq z{Aqy@K0k7D{hiHO%q=hVJ7c%YQo4G_gvB^ZQHbihl{d$gJ_Vg1fq4|2z=>Ee_w7bT zpu6-1wm7stpK(J^OwUB1TAb(NH%7Qb)Ij{Lq^#M1Nxv>89|IbcEqFtUyqd_b_ia%S zaGTAP5_XcqokD*BowXPDkcs`m@;=S5G8+-!6~iqB^t*5<zvpr81{K&V*otLx%=bsx z&%f>%t*tR-@BJN_B4De2xtJMBk5VF?=6K_mKA#I-WlGt7>jf|PET@%AeYu@yIjCgN zzHHcy=<InQf(L$^?RE>-r~X4$JcdIDIZW)-D<O9eisFc_h_%KP@P73Ok#_0Yf&&Q4 zRAdu-=te8!@mYWyyZywlm_9>4>v|UiS~TCYh-gv-n2SzT<I&~I!YPZk_+FZW8v-Ub zR0n?Sm$}K@Qp4*gRZ|&KtU48oENNd+geWM_4n#ekW;AJ`f09-(4(@XOY5|m8C6L*r zMq)Rk-!<JiQPnJpUtMSU;TvV+-2E_QOb1!a#yh`-xIook5jcj%QNTq1S)OW<{U-^L zN(!5;-gDnmt3fTN&n*@T>nFoXt=Md3K+iX2?A;BEBLR?$x4R6v*s@#;Sq}!RVYAP7 zDcgP(>+*3&>ssqPSHkq>Q+B-UUKw6iC7p!h9BxFkfO#V*S-&k&I}=F6t)RMr)*oEC zwz$Y%R*(<$V>9o^7$2;i+j`~+sUx5(OuKP;y^APZ;`GHiL*IGJj4#*GoRX)`epHK- zWOJ;*uVPP1-6sc%@5>Z6x0`4ixehTO7L$xy;#)}51JrS5DSdvMuKOeO`?D=(lIT&z zYQTjF%eKfa8^-~5`A3x`2MVna-Um!wZS$boObpR3p|poV`tId~s1G*TvFLgqQ$#7e z18jbSw|yQcL@A(`JKHA1!W`cNekER>9Vijm^+jCX_>U%g<zBsDF0$(YrN}GJc}z>? zUC~ac7UWFWACKx}!-;i-^b-mL{tCG^=b&h<V?Qm`S>xtS6As)@5ud-sY}JE#1jpg4 z4}6u?ww4?chz%W#dmL{QdM`~PwqtsAeK&vjF=eVs&(;SqWg!K<8SGmqhHd+TY%km2 zDj|KBtv)vRFts&sW_Se+nFgXhtK*#iEjXIOhOr)Pc0*rf;MgDe;9aF5@j|hM-kX)_ z`$(VkE{l&YLm2Lf4<e6GLp6|WebLe&h_xljz4yatvT99Dt?i^BlO#0AK$TEmwx8f2 zS1>N4c{h%Drc#U-sWF08MWC_n;9r3!cZ(~~F9mkA9A{(HU2*@-n{(Q{%+m=EId=tl zLwIaCsZx$snCrxZRx_dE<CP<Xn60%FnKvGt?}{9_LJ4&x3iH@#xr3dm4IHqqu~g+C zMhPS633^Md-V|CUKQN2C!iWo*j`5l%6sWy_aF1JO21o#U<MOPk85>6}-+Ym$8bI<V zL7!{Ck$_MwG4Er=lQ%2ANu>GtDtkp?*}O$&x1Ye7^MZncTN8GoR8{02w)V1^o30N# zjD2=dyBN#OUK`-C(mF8t4kiKvzXu3W(CUcDlx+R`v6qi`%5{Y5*eC-@`0CH6!bu%4 z%SJQ-@&Ws>uvwg8gGO$_w;^`qZIqH*oBn`Uq9g$&6Fqu3X^D`H>3oh4H2z&_%rqX- zhG;Om@<=nmhXB2c1yft)kY@G(u?6#88Ho35Dm~|`zD<GK=e_JEeYXGH0NpQhZ&11o z8ULT2`{2iK`fl07aELDdD_LwH@7nNQ1N|-lB}>{ahyIw(wiu5BVSI{hrmqAl@D?f5 z)#OaphAXbks2pm>L(u~&!$49f;AKF2kP34ou%jx@wPdqUR4jUH>;CPMb85cpD8s0U zc!tT9dp}ZPS79`7({9g!TxUlaeU1ZMuTP}z&D_pJ`JrfQjeR%X7<WjGP~RHPndgTd zGUv!q35~NKfLFiY`3sU7?Kh<fTNXHUDx|I7=AtFF50K`=BY(zkb-&k{1AK@@LeN9C zcfboc@H`RGi%B=u^3;hYQh4PHv>?hv>N-zt)7eW8lC{ENfyi>(`jLX!n(u|i$1&RC z$%x8+mTJCHwC-`8@Om)St8MEQK+EPqX>Bhd4TDmIQGWMsez6AcE*=PNvbPeJ!A8O0 z__Jf*FGiD^k%Sg4$dmO9Tx;~MHTjX{NDDY#DzgFnzNXcOa#Y^FTW9fXFW*R3P?NtE zM@1+Cf+^9T;;<>R(CKGrOyJZzF9kjr?mGU78Gwm(5{Eb06J?FkYUF`Ucnet~lD<9} zvJ+|72{&*AcRZVJ#=!ecS=#0ITkh9R=4ua0!?0+lUa)ratr^tn?U;Z8eLIV9ns}_Y zp@VgoBuO6O{f5}vEklYZ{^1J7FU+D9A!^@G%fQYSPOGDKaOEEfMlq^?bth_Xbs30c z;5I(`y=ajl<#Sr^57<vb5GW29HP_JSJ}Lbqo4Tecm#Mz&ZC>t^4w{Rjj@VVZK^xNs z9TWFhb&M8hE2QQF)%#8RHA&rZaKiDRTjQD-UAp{ZDNb;rj&-oztzcu-`pZs1PI(zu zjIB+Mdoi?5{5GD@Nm)u?B~16^9Vreac2o7O-=7qL+-mSN?eyT4=fE;OzFUkD4c;ja z!azg3>$DkZ1T=s&p1a_mdI9q{7Q0@~ZO4i7;jk4Z>?$bE1#(t5U1)zJYT)MdZVm9L z8-WwWCn=5{QG`b5EE4;`KuqI>$N9LQ##(GO63aJ|K~7=wKncTG(WkxP1AmkRJSu}y zUKFeV#8r^5n{@7>;}@+M^Iw41QvXu1n%<!P7_E0k`@oNzkkmV4TIz((DuJ!^$K9E^ zSj_=29}f5~>siVA+<Dhp<kWM&{@frZeKTr}@2abXH=jpb=AyM9gzM*CNc@*Fxv7e8 zI^qne4+$=gAT3jP-7+5SUEv~(&UoHt6mx=D1Dzs&NJKaymP<AMp`e0)LWVe(Tgb@f z<+?{sj^HuX-lZKoXl?F7Ny@mdgw=RF2}eM?6)aV<WhwK#Ci6D(KBlP3Zo&f7@ppq} z)tqU!^pPwTzkPScyiHv72TG~NFkP~K`+|iGAte)r!=!5h+pLYIho)E^#9^vY9I-D^ z`>n0Z*i<`q^5*soB%Nx0iyB81*wyK#vRC+ycq46P4zOOVU8lQ^1;M<4%%r%uFm6Q| zeMbT!ae;STlW}hjSSfuUKnYN<EQ@y|3hz9r-}(i>b@c!#l>rGhn=|rRJ>;BB47SZi zl78;Oq%6an-0S)L->&)Ap<2K+UpZLS++}t!JJnJgx?`T775&`W7zFQ5Iqn{*MuFWk zkS{?-!c^>lfIvZStsd#>*bMN~rmlx^KwQk&k73#y9!=RI8+P+*fkRT?UZqBM!HIc& zE2ZKu!`kMHF;1*f$UEoya|8Nx9+*xJFwF>899N*~bDb^$*UvXAYvMMe+MMbzrLbse z@>>J_{yyr)ZYo6{RtcqMZiCxN3!{cRMiO4xCcJ(S_<Q%@1Dxo>V(jH#zy*Q8(dXpt z!@fgJPS3IYEDOD2LX;m8Dx1tz3~>+E+8Pc(zs+PS0uL-ef-e@TjxXna8odlFGfgEp zb<m2!*Fzh)uMF*R;q{Y%6rr1T3AmGzWA?V*3^%q7UeLy^u#A1%*`~yn>=?;>N-FCy z^&yD(J(0!CnWDf%sgQLWs})eIb;|xZ2=U~hu>>c+V`sVA)E@X7zbto1i6|QE&$MB; zwUu7+!cgQ$>RUNLS!BQt#d1L*R=nHW2)Nw;$T(N!i<WpY7y^oO0Ua{R|AlAMXxS-3 z$}O{F$vf_1PcK=Vi2xu}Yz4eUFC6%3+WqZ_B4w{0{yHQ}*?)M*vJGao6|lI%dej=) zmZ)d$O<%IH`PfEm;Z>+MrE4T8)J1nhGQctStg{&W*3JY6x=9N%upVBTDQ5lG*~_cb zfiJa9@j0Q`vhe!b88Sj*@6YQHd)bNCh;Gu4bhhZ#Qk`ZKNKY3J3r^hDMQ}vK!IX}g zczYp&1+4|d$$Hz6ok6qup};mPS$`5?_i>=9qqV_XCtv&4P+RfHoEf;jh3v5Y)|YmT z(B1jbqMf*iYUc~DtGf^@yv5?{EyvZc%?ltR^=YG}b5rc=<7TolK>jpdnlQ~=Eh~Ck zl?}bA%3^NMsD<)5X3-jPiP{H%TMKQ5U0RTFd3L7P`sY)MYNBM5-;BDxw3#n*p+#Xq zh|U5ee~kGVz#0+0jeN6)*@p_~H|O+s0$U^U7-YXdKG(sy@tqB)!)_B5#RT>?_<)B) z7v2<4^HCQT><e4UhCdT7I>uZsJ*H2g_~c3^f#11vfT4`#5TlUeC13^k2#YGzXR!R0 z(lOeqmk-=Y#6R1tmP*|H1>jBq#i3^uYJ|XMT)dkH4B6?MwK`rDM+6c4*;v>{4Bw9I zITb8#9MuKV-4ESeLxK(-!G_D-J$F~y@lD)XEv^~~r#?HFj`TV>STYUTftg}vnO2?h zxakdIilYpP4%ztc(afHdj~F`!YXZ|b1=Z>aB5`Qn_;DsrjQrat^q;Ws_RU0X4x@<W zRpexEVFX+V<#bYS#rFyyPmrqTFB7yd)3ty#k)pVa-BZL8mY!~gMUPCg5{UPmEt<jM zCR`6zX5yAQy%10~2fkB=11hV(lhyTenrG^#d(oiav}ZumchXO|O8A<O+hP?!k)bA0 zYrF0xkYPX%WQPv%7kbE${Esdzc{LP2*k-)jCF9-w>Y6_^65dn5r8MQ^I9b2j56VA7 zMReGgk3;G(V4e?kXN#;1#m>hgI*Jn%Xdos#K<QA1DBn-*m<69v)Iq+dejUu*T3X1p zpoeq1!T05YC54yPz0A)!LkC^JcX{e76^M>4#GX4HPXC$B_B>6{R$oYZyW}YP*RCB% zsW0c9$c)!LktWUq@yNx2&Di#NSQ!?R4jlX`Mh~4hxh9tH<F|l{TKn+(Vm(sE0*P)Y zJ&gqPb=#4OKz9cVN?%$gu@u+?#>D<dfZMy^JHr#N{mNoWhTb4=^B%FmnKr<2PJ^cE z>4D9uBC<6?Es{fADHWkA@51Aki&|ClGvi;ZU5O#s1E-ZCts%imtt7=F&CeM}oXj&% z%)_lFz;Z<>PqE8>5$25tK*Fztm#jSY<8E?hDO7EnC7jK%`D84+GiKSmwk>A{jA>$` z(&oT70$J5+uQ7F}(ajDw{3a*cDeM>Uht_$Q8uEqBX!TO<+1~j@n_lqD0uUO-i7n(f zw|#|OlHImirU7N<HS;FR4Y6JEB;-ml^ar16LgF4G%Vz|r=TOs_V1qobk+r3<GQ?*6 zzHkDy^Z9+sFr=s0o&Ama);LPW6u~M5Z1sR;?5d85AD@4+qAL#C3w=zbcRyumm5_^* zU@+)LQq5z#*2+&25vD*>S-i8jXHLGL>${$L%~zEa4*G3fT#<b|V5n;MaXT}tgQ6?h zWe0_VH-&i?au*6L!E;nha1=<iEpeS*zx7C~yr~7kTUssE1bBq#Ch;qDgi3y>hS<qf zEZ9E0QyQ-5qYAUM4Y%!rj|I#2t{)qwi#Y*t$vQOCcec&IFJSBtS#eTdJYfKQ;x=0f zRpjX9A4gJp?<aTCQ}SwU6v@W~#ZxWQ45t|_Nb#QDpvmann!*s)^-u(spU0>6?b6B8 zZQw&tuTBPa+gN2V(H$I`1#kdH-(PRn-amxwXunVRR1!{F>Yo2EiEPx`W>aSPk+TX` zm42MG3V}%T8pIy7@KF9d^sD<Mqit5551~s-^yV{Nfx2@VK=0APOrR^8=BjZE+bP^B zM}ig>9Zzkt51jD}J`TFiKQbkTxKP4~I0=<#;zl*U>Lrhz-rjNz*K3Tsrr#BdCKRae zOBcV1j`vSA2h|v|0FhG8o6i}f+o>HVH7hHl;(DTFOKxJf1CxRQy<3qquO(2i7!3z? z1Xn<#1Mij12r8gfTO;AyT3AaqfIvwq@7Y}l0<3a6;(<v1fK2>Vc$=X2>%Hy6w+9V} zD$PgpS;>p^0C6a{R?;^ca~&0Kortf1OU*QZu3X{@OQ@IpHk<GbT<qKcRJpPX1FWDN zm;!sPt^ZeUWJQT=Ec8K8!wCa@Sw*lI4+>sN1eoZemekze?53==%pgOwuuGwm!xTS2 z;irv#1icKoA5uT3f40>}S5|=$e<d}g3IZEQl)%}j0ifM7)e?z^IjsdMSz_H%u^c}O zIhR^JLm>mVI-@->XvdR@#bevR?y_w8;4okb#w&D4`WbvdGeBZWwMeK$)^8>2B#kxJ z(I2+fdEfi*bAM5`5cfH5MgqgN59CL;@<I(rDPvGp9jY68a#~F`w9ORUHze*znJt<` zgLw32%rWW7l^L)<%nO6q;;rYc@i1__;287KRR!?z={aTuCr7C=*EnUcILUBj>)zBP z7cv~%X1e4UQg*U_S0480Dy9<+avC^A`I3UhAG_|ov~lqO;b$!!xQBSM6lkz%wBUF} zaZ#K10bqu=5z`jSt3BSq+?Q>#G$aHW(xX0-usUHeD#SGrAJ;9m_YX317{_DOFmG~> z_G7$P?xFRm1E9c;@fTfoM<0v>3|@ry4w*q`seLTso|oA%nkeFosauSWV~pnfP9X0& zxCJJHODu3*G$0{s3LOeDB~B=T{dWA0{+yOLY|z$g`^_S-!V1xx3RTL$XMosVt7x}8 zFgk(K?_}7vjowPsHec3ZgvV~<E5cczn-!ehK{J$t8Qbm+Fw+BQDd;>%zeqznX(V}V z_TK)Z$$0U2D7_nMr+J(*otM%L@1r;ltZg%e|Bs?`k7u&|<M=(pkS0Y<HWWRM#nO*C z%;<pRaX$4VsVSwfQO;}#rJ3`gVwAJWp~&Pk#2gBt$e9shjw53{zx(;KSG`_d*1h|> zuJ85vyx(F)Y_4saM6q=bXcZU*$XhzF1(2Mdw|-#qPn(7={v4Sm3nY&e=tBRi&MNxM zxFZm(9MnRg^m8X-g6R?jv>wa`Q6DERWWT$#{umI2bnDsWgbcY3Vdi>wY;HDe5RA{B zMQ>X{628_^>BxuOnz612zhpgG0S_n>0dFd#<N3w=kz#!b>Z_ZK{p<4(p;L}h(!Qze zE6J4t3s-tNEuC31DUb1>R!tv2Oh(o=Ch!Ch<CcIMQ0Y0N%<o3r=H$NW_^;N|Ddc+S zjqkq6whexkf7Jwhb31xCqoT-@zTsS3zwjq}n&1Zr{3SLH^`K^f{{?n0qn$`_U3dm6 z%A{WrjP5_l7s)`J@WH777n`iX@Q<I&z<Ld~ZNkMDq@PqG&xqaZmn!tMPQbLceKS1# zz{V^=2#}cs-D9#Tv@i=3*?g?U=+ca=ORnUxuMrvunnuu}Fj@*kdo(OkUP^J>w|7rj z*u3&?&8XnC7!;R}5mlYJdEF0>lCZlHE`=nZnMO3QtFokgJ&v=4>i{F~{*Tmzys|2& zxO9m+)*J)K46}O)mO^Qm6{dH;1P~rL!^@2ak^dA8<|zwe{2-@T+6V8A;8KI#CmPSa ztZ1@#$<lRO|8J)&!3W`fq>Y7T_J0Ix=bM}CzGMu7!~KxG!L_bNVBrDN<WnL-W0}Y; z_TLC8IaXx6;k|qleolvi>_0Z3)k2g)iWUHrtcbr<PISy`gw^#`o8xD<_H_NfD#Gr~ zKEJ%nRLu4^gYYl&f7A$+NdcBXtdjZzYRYm<VfEl@0bKCdD}(xbOp2dkg5EUwcnd1j zcm8e<6#Ge>Z7eZ|(6g)9$`?82?L%PpgK&gY5zCtc{-{qjGev5C2|;H@lfqI~2?pls zB-`-6k+);yYZhVwbI;lG1Euis?DW1&;T^4UJ5hK>-duouA@D~qrKo+Z-=DP@3*d=M zWJ%U`aM-zeSwAEk9of#2jXS4!{qqCW^>S4FdhvS$2Yt{v7AQ5Z>&MDo%~=}|SbF_} z5Xk&ySuMe?OI;!w3XU<}xcPFYQ%;PuT>-+pIKd$;px_<cfu(MD;|eaF=Tn&e-{}qo zNo3leU-^1Qw{jClA7Vf}klyP}aMoBh$I077Ig$kftOVqw=t;#qEEZO6X%_Hk243im z;X2B)&a0}5PHL0P@rf2vW4jf!Fy|mYR$qAjtG^@-d^hm@)XJPCh5~+~yr`|W5UTJ; zA8O$sGMgDeFo@}kNK$CO!@U{^R`)ZIleX`r6HMe>AIh4!_N2XGBIDB$JvYrXj1Ps= zYS`OrhD?@15wLqaS#}IzrMWHkPn_9|=SqLIS)!$0ErcRA4Ff?$;jD$sqr15}yo$cU zCvpi)ondLI1B|UE*{=KxQq7*sE}nehpv>#+gq&oGKL~5}<EiREdhW)Z4X8ivh#CDX zc84G07$$%1bn_DIgaj>fW~=ze#PQ+w+GtZRu?Kj`V-zWx_M;|lnC--Z^DOOl-kYWw zJ?hz4hS-?us)vooau4P@U5{*D>rX(FNxH3fzul^e%=JyeoM?O!hIIHBXcgGt9lMni zuffZqVF_Zh*AbyAxhl`ba8e<}BVxxrL~|hq4+s$Eb}TD5u}Meo`^YI{jZh<l?_)e8 z=YU0rvGy;niqO{^;Y+HqcbT0gU5VkDuI{`b$N3EHU3#{3oI_Fj^XIS5mPC&w)jeXa z{YQX#b5n8bZZ$#xB|K8=ZGnD~hxb-H-$Ej#+^pFH15hX5S&I6t3T@2kSYV(SorOX9 z!u~2h<Q=Gxh}P8`QC5kx7?fu3?$(}4<jM9R*C;@6e;z~~rM_Cvdd*yuO?lXAAhcGI z=$~ZZ?HU9hfP^0JJ%4N#MvZ*+yKWcoNZcr(6ijOK-Xum=b3<BiX3_rbPBYiTefMCp z@v}DS-IDuW@a53Zn0&j7->%x*X!dkQRxIP%G9MT4p_pET98u`VYJP%1>g(>k$nb?l zW{_1eAl}a4J#R<4a&W2ETC&IhO2p{qXqffF;KK0BjR)&Z(zf&&PtHz%)AjJDlO?oZ z+E78;H(pOTqocjYVn9fGrX_W@jUlwMxE*AF`%;$Ek&*cWexQ`n#&qfP@)#X#f`uwI zxf{Mp$brIo{Za3g`0Bb&ep<dXOy>slU<oip{xg29AF!Hs70Y*~AEz3we>P!u>&Vl< z5%FwXZkkhrXRPrk3wXqXEc^q^_hVE(C;3M07NMDnebtqmkEYPZs}R_CXHfQR)t7Vc zYW6D|#vfVrGS0hGcPnZdpQ+%+Idcff!;okxQ5v4#?zeaVqg!uZYR94O;>ojYAUsW< z_j8g&E)hR9nC8ODttM^==*y;m6ojjc_6I(YPZ#(|2L2mZvtP9LQanye(5~ufpesco zD}DL#R+g1Q;f@=ygEV7YeRxmb`$ETi!|ub7m43uliB|0K1+565K-&?2`fkgP73@mU zNL+lqh7dH<mGW?9$3ep5+eQ0w!^!s?C^lwc$kFmmj@t#k*_3RwBSw(|CP85%y^gAZ z5+66btcZ!T5kdP0m<9~{mI}2pU$5J@UB8t4lr}kGgg`){(B409o)vt0eV~2IOaDlG zeYbCXf3-)={lB*DTFJtq!J<39yppV~yj#gj(~=3wTuJ(a1RXh0O&3w6@a9amY(~+0 zX4TM#m3D>jG>&zA(YtN?qbFvfekL_N9d7B@X~X>1bv(V5Gv#lryIzPupfrb)slj2A zz0LTfpV!GvQ>=Eb;bJe}UC7B#bfE=!@3(TBoZDtWzIz9;Emw|TG`zG-Fop+<wUp(b z2zGt%cIa$Az3mupi&NNiqKR0w4kv`UVD<b^su#{aR#xwRb$LE>y+)>CGwh0EwaQsy z^(>}sbjN--xV3s1|CswANEA-&8T=ji)}hY##Q3Wi-Uk#Mdsf#5@}nv3Vwy2>jT(s+ z#EHzGu#dvb3(j?)HONxsGru^$T>Q~lw0QK|U?~CCSNiqglboa6j}a~2?EyS;0rbRk zcR%5Hjnb=)k<<w@#+utLy;|&N&#TZN4rm$>nLm9b(9KS~*a1lFX)r;^q;>{SZ`1ZW zqL);S;cFnOrqtYmdFk}GKZQ&EPwMWw*P&LtK8v}FFygyb%ld+cK3^uA>KU=VliB^@ zOb_0Vy_XFn<UgxnPELir>R)*q+l~ufRY&+x*G`(gPDX56Zxe5*#^0zjsZak8lPV@w z&AXb7;OAbfxc*V^;M!#NkA@4|7mv*xpx(L}57vI)-MF@GzOs#C`53v!DwADW&9Cn1 z?n|!y3pDe|r3q2t?U{#hPgH4*Spo5Ena^4Vk!xSv_r<TB$Be1D_Zwul$4-_ao+m`L zA4n>E#ge}NjrZ_zz&~Svf{DJ<CbwF)uWmN|Rt}yr^#see`PEtLA~qhpg}CD^7TsU& zoS~l0@9(sASal<LtK~_{^t@r)iL}s`0W)9O*{@--`(F-AZio65_w3*g74~m8n(;V$ z<^B6AT@R4Y|GLdADP1P<38>s?GXg30Ga<><;!zkmmAS#*L3)U+)VKdh%Br3kJsWCt zij*H9=Of3hkC}D(vl^qCKcNEN+2*N;nX9W_r}s=fzqzmZ%|IUZvgt);iI5RA@a88P zx_|9|scRmlgIjj18kAJ3Y6fal%dGb3Ej0VZ@b=U7fCCN~wSSJu7nZE;smf2kHvvEF z=abi{$CXRj<}r~Q8cn?CrlrS&nFI6LwzGOx#j0RYe`B!J@~=AeElMOQrjo1RS@G9v zZ9LAuOMdf~>e$<6rm~-n#$|w2cERPu?v)QlQ$inSFQ;hBWUIu_{nt6rfALaQ%5XzM z>4^B@^MW&=ZIb?`1aj$mSp=?jL$<htNVdLkJ3>#%0h+)plHWuI*)5*+Zjy1jK0=;T z3z#ICZN3hyI#_%D^dEDP1dAW-9qmgR8Y<SR@@<!et6BhEh<)!Z4Z6IX@{%v_gUvqz z8;>uFrIU4if{^}_BNsRBqtafiwp3jn&n(rY$UI+(9pzI^h!gRY_X?>~hvp!OU#%)D zub#T*W?e;w8v=MK`4L=K?C<EbA8QW|yF${!gl}0QkOW=d;d)(b(+!z|5TfS(X2#*6 z9wRn;`0cgVU*#1GVaQ1_!_ZxOhgipvIRPsn470HB-Djy&4t7IdlV(;4<5{{vj{g`N zC%^ydTk|nm+6b<Jz{6%YQ4O>#^^%Scq%^{l(JhAT)QIFu!nD)*w#VGS8I4JQZ18~i z+XuDCRHRH^gf6}u%tNm6<%t>h+2G_3=0|ERvF$l1ot;OMp{n=tVxk1>ln{!M`#@N9 z#S-eU?EgAu4%WCJLUCs{KSnhFl2V{u-*=k(h@k5F?<t)#(Fw`EpFZ1$(Sgm%d@-m> za=4^=I5NELyHxw!j(y+Br?E`>dkQG0kzQ>5`v`JQXNK$;zHge7;_^{Xem#gsJ_4G3 zyyhM6@vo1Vis!n%>G5VtM)HA=sM`Gq%R&qfYmjmcb3a{q13i;nIL3SciA^iD9`?{W zIq2Ce=jKb+6^~zZTKnRbVltv5lb!A{kZgNoM9oIo@gn!xq0v8>rTf}{Ze4WMV^Qh2 zR8!&5znW&-$ZH^H%HaEx^((YvQJ~ZZoc5<a@X%tbbxy`7_*T`DRJx;wbOfza^aV!x zWnMoPsG=-E2J!d;jX>G%Pk$Rsy}gy1f4#Fk2VSCqi!G5p8jv=rA;Mkhhw|1eWIx4s zc3_w;#-yA))sv!?8gj#Modw29cr5u-`KXl_%5-L9NG$)_-|N8B_^i(OjXjmI?no@< ze4vx0ypC=E2$&Z6TObidHZ3(?nO0DL#ZU0qCpY&v(Eis>c`XUsCW2qk!hEaBs|snS zoYv8gQ6^nY*oKu5qP6r-wW_0am*CJdhVxCq4v(Fy%8a%`4Gm03Bfm6l&WLkLe6PI> zm`V4Vv<s%pg~xjg4VwG=7^%6zLf=$og3?|)ub;1<eR(uS-OC6E-8642B;z6e(cLQ- z2EdI3yyql>xg!2AP`@|Dko$g(d*abe5l?l*$nuy8E~EHefqLOJT?oBQem+zgLgc?` zp8{Ov3m*_Ag0{-p#Me)+A5+eB=YDtfi-a(M+W~)mrMj829@=xSA?KuhoAh_=FMjzF zeW_-AJv;{di7SqhCwrE`ffBLD@+SLgoU}3m<y6E%!k_<nr*|)d`O!RHElIkuf4p)Q z$``B&FM4{$tfQ)eLeSy8$-8pRe6Qq;g8ZC9lGwJxqka?Ys7?FC=VLTpP*}=)(|0L% z+AO`sbHNqh5;>cVIdN>(llO>;@`(NLGJFm*@3>26HZC}LvNlTdoK|DHPFPxD&tmUu zK8UyhrZFuHLg1l$aaW%YTo*u}`VtZq2fhH`3>Q?>_Zaqw&R_4}&TO~_Uu(t>X|{I& ztGYq9lb26K;irb6qxjWU;K5acGxgfVQVSq?@ZDcz{b!Nu34w@?kp(9k^CQ1-%1cJb z2()$0DX2WzF~NvyJk?80k$4_<-{GE{`)z~|7}#QO<MVI#9J%K5Oi*v6^Q<5TJcjxG z%ByOiIe6<trXZxYmMux(mB9sUUwhlMZT(<DKu`IWgoIt4fKk$s?n#YYXgtZ%tioON z@a5UBoe3Hc=GP@%zpZ@wxRu&v8d>vU$4;o8y-pW5LeD4ULnIw}gc^VZi%1cHPoPWm zharNZgpLhmoMpag=}e`YtEhm&&Q{5LLpQ%Hp;N|NY+BG3iqWcL_y{Ur#J$Xz`>3Sw z@|Re2r%a}(?1SSKVh4YD*<cXXf56+zt&)n$B+qzg!M8{@b7B15&*l$Dke}s5b0S7R zVgdH=U@O6QX<Yw6sh*t0?f4d?%@w#bR)nh4)KfictIGAgAX$0{qXM!6e7A39V>Vc4 z)q(Io^q%S|ibJ&94~OB3vH!)Eb=rL>A7*SW856HNBv0Rex}4U@jqN(&?B#rrx#EKX zlGl0lFvSA7{+lnCJT(u;4#{~9`-}b4@ZxNbnzm?r(&tW}#<n_9_nPTS&F9%=KU<(- zEU%?(jb+SMcYrLpO#5Nd0RQjzt}}^)*xE#wno~(GS2Pk$I(LmY&;%XMTax6xw0Kdi zd3u`KWHE|)q4mmzyq=SvD3uiZfLkN!2v)VeL-Y%Ct#20^z0TT+Q)yYB>~^*8sOAIE zw4QOyyom?p<onfZCGS)sWtYWM`MW!|O}!#q@1x)9t6<efU++6>F(U6KNd9g-dsx>~ zp6jSAMLcP?Co#FU9eO|aa;Dg6L1|ePjvVc`?ybnPU*k%89wud;y=c^g>FHlsxW>1y zSNn?p>H6on`z!zqNLe=5<RTMwg8haJXO1*+rn4pIRt}peu;NpEK>Q-=0S#&YIqkXP z@+8s|F<Atr%B(|Ajpb*3F7x`#zGMY-%<<Now2m*A_Z!_lVRgV&5}^RXdvE*wTAo-c z5mw_RQ>YWPds4ao{@B<YsXo}_gEd{Ca!aYBV)X+WDti0+J3)?`Nbo?&6ECwzV64z> z=;Vdr>W5oN*9hMze40Im(q&T|u(8l_@Yy$1E}l$I@)0!j$}-4~vOI1|&gizdz@*>& zPwo>OTYBN`&45QP3vD_p!<Fn0N7<A6ONrDR3Xy5<`_=vM*IlWj-YJuw)+wx;24o@w zWF*;d`<-qMX;eM@Rzd)Z1@Y<G|Gc_uFSt5ip?ug=QU8!*b;Es!N$u3sF>$E+`YajR zpQFPbS$#VLs|ol^v{hl-!7@diz<^Ig1^tyT-8S!>gMkQ5LKfLBo|D%KgD+KCk&TZ8 zi-j@#${Yr^j)^DbT#7lc|Gy5+OBEd@=Mr<PzjnDwcAFw)Kiek0K7)?wP*BI9YC)*Q z<2Z@=t{9AUVs)d@B2C3uQ+KI*^1bJ23ROcFK3)X~t7O02&X{^H#19{3t#0L|+9OIt z<vm>?;E7YO@4Z%kR-Oh3mWxES&sAFny_nXVeE>_*5e*_`H&^m~gh(4MjFkG?J-Xxz zMK4gtg2X=Q%*FOQB@QYP>axa2md!=K^O)|LY`1X&<~Pg&^9nL)Ab;LXz-}2nDic$| z6Z@swu09}q@rsnAMZGZ75Iuq@yS1jEjLJQ-5Et{BgK1jUbxiaqxwKR|M@YW65SK$8 z|NeVw{|L1r+>IjZ6+lS?czJVF+}@-4D__acu2)}A)XFx|>IGq_#fVCqKOXSUXM_Yk zDIvh#NGW&?|I<fP=lXAX(JW(~$$x>w*dNAd{XuK#J53@Q0T2Gb;tOS?uEv~zFxxxf zdXWn&J!X-PPCsTPBD6&T9V8);v%vlSEJRGL%vBfkc*(|?y$+%!PQK0Z=~i1^PiT1F z8up5(<NA=Knpk7Rw7!w<B26(Vy86<`AEuVo9Z=Ta7_G?+EC_t_$NU=j*tp9%CdQ3& zig>W%YDFj@iXVbw{sVYCua2uhg{3@>Fm=J8K;>!o_t6&29BwW@@N<IHVN4e!?sbFC z_Sfmi;@_69oIYj0XOgAJ2NfQ>inY*G=O>;RC_gj&cKg$$exrhi*e{ctgV4gi8iZ@> z#7G8jf;v7;|2>lK8^YLRkzruH`D6ZpWE%$uot{JEVoLwKo>Au)OP6ny$#hhEc_idn zb2*gypR`Hj{a1zc(Bhs9C|Zu7mCT&+Xn5VGXF@$EL=n-ecGbZpF1S3lPkb6xG`5`H z@m`O?uhrJxLgaFG>~<bi#0plc*k5?#`7aP$F8}eq!5BW}vR>&DA<L1@U@%y+`)?h6 z^L|R5lDaLFcl4H_bi@v8+k?{m;c~y{&FW~UTmz5n)A62#$+gwsT>Ra2fz({B)6=8A zT^OnBqoU#aEAuLkEe}0SgN;&3YSS^3BwS7ze*4ChPM!6;dq3QX6x>U#{n%$bSk5A6 z(m^v_&C3%px|0po6^^tt$RuBTftzsIKzM0=#>g677vQmpzQ4qm#Jp7B{g{1bS$XBa z&5szCaQw|)N3maPgDL^?;8ttY@p(g`nS;a0M6D2pUk5m^vUklZhnAvOzB(tGKL#aB zko}Z_3+guvVP#e5#7b)39HnRuY*pNUvW8t<Up~FU_txO55SG*v#4a>9>4DyrCGV$h zxPSf^kmOpssF@=IZ%M55)a*YZ{CVR3m2^b^Z-wN``Auh^P#Hu9Yrx+n0QH7BS$#XB zHZd!MdwE_1y-nmuYLyWUazh5gH56_+F`IMMq4yT!%Yq&?3ivme%6pk8;1jvT>uV0i z7Z+t1qEU}?JmnrqEl}{`;BCWn9f>*IzV6APclR<M=J`gsM6TgF>m99L=phdO3KW)O zn=1ppnPJF%`we(?G4}gXwfaE&z7s3Tb{%AfFJ9}5(LCwZKIeGyG-FN*ifxqHTyQzm zFI-P`1S@!9!Gln5gqPT<5rWl!&$uH!!0)q(Hw=+<my4K@8TBtMer{`W&;5wj`kVC+ zx4}q<G@&JYJ9gsb(bab?IYW*~V%O{8Fac`tmdy8q<-$^rJ-KiU0*1Uv=fT$VQ=Yx9 z_?qq*8vE9A`~iH3*;gYIV}|vfV#b754}@GWzy%_ef$k+x%Dp)m?CVlwrkO5fC2R%A z&&>OnE-WlKoPM}_?VzBlsr5~#{u#xLu}@@HI5pd>`^Gs|;5Z`m$0_<e7J}iaQvYa~ zweWt}NLgrm+R|7#;IFc(EF}?me|?e^K#W}6Q+}VSesq9g6-4X~4vO#2<Vv*<2k`|# zMo_*BS1F7&k-!(&NiM-U6}`7K*g6a%>C95ZdFFIZYiQy0!8ZjRbpCi0%o+Tv^-A3o z7PbRtK4>BBcPT7-Fg7JH=s{N#+E|!{7>RWGxr)m8J#5w%G-57gV(GDFDY=n<m${to z;G*{c82k_-jF&0St(Cdx4-4nX(NsOMp_<pS#Ml>WABHNE^{W_6q@)pZy)1=uy`aOu zSy&{QS#7pcyOnoPF^2PK<@CT4Y=afan)hb*x+v+@F*V~KB6U;tL2!fD?+f1_A6=*v z8+X2l-~fk1u{e>f(`st{2QKaA@mk7z4EahS%dng>)apu?|9uWPKQ^dZ(k1@XX8|~r zAp9E{cVl(y-HtGAb``3+_Td7Cxg(e>j9_+^lZ;%trt_WZE*GKaLPp_aQBtCd@+zY8 zhIAcHihD6_@V72!-4y9p=C}4w<g}-u*r#e~phq=4vS-Sfw7$6`DNAP9IT!2G#=q;b zk~3{jQVJvuL!eppbRfu%YZU{A67|2I6nojAZusnW$a(e#O<UoSAUdinwN4Af-wRij zHUpZfq>2A+R<}-_h$R>}vz=*~j_oe84{t~f9qdFCD|cPpH{ay1UY6LAd8sF~uVJ=5 zHCB!rM!Rz)ceG!7dc*I14(-1U4PUZy{Iyl?q8_V#xD6NJde3%mHHzfyIKLHpG3;oc zy)Ma}QS&e0CdXWG#!zW7w^7f8<6Hdh9ROzF15?e!kyx+qFmIXcC}N6oCvPHJMbpf; zf3?7ks+=RrO5Ia|XR3ftPDV0F&1=hTVmcGa2b~Tj4%tvi$BEE*kGnlG0{~~2aafaW zAzkj5m9ts&2{kZPnfXyC2R2EGj4Lcq$!Za}NzG`}Z2!}W&Gzm@Gl}-MeY%*iK@bBa zX?Z?xuHG@pP{<0`)0dhNpIXD=d)}iLBS%~`Jm@M(y1-$Z-vV0o!?O)9ol9H<heKw7 zcNgVR&kYZANMFLo(D=R=SS3E^KgGvpok=?-Kv2*?&Rk(33j}e~XoWmZAs&k8)&*l_ zHaE|6^fx(75Bs*M4wUbrA#5!Q->n;T+<ddCdz8<lN?ZPJ^CbLir~qaLKKe%j=x+<% zVT~tCKVdBHSOxnP&@6Sp^1&_w<iV)RekSPRxi(spgg||KY+Qy|dh~%FFf??RPorIb zD#qI@^|~EzzeF#1%>jNM6bi^%q(W0ftf@a_qk$zQh;%i!V%yFHL=p}cc<)!Utg0<^ zd-;y6&-m#XV}nI5fznoeP|9a)kZB_WD+qIb_?B^hZje7X?1ovq-;W2SQo()Iod)=1 zszEMKnZjV{ry>;mnGb@j_@Em=V=HrT1f*M==EUWQt%7#&!820N35{}4@WY$HMroF! z*3Xw(-oh3^sI%qQUQ^&hTRS$Yq{9?(W|?ds#Wi^lY}xJC|8G#y`-JHn%ChP%V8?3# zlZj<hi+?Lb>4(=QnKUBKO?73SO|pYyn%c0+Q8mqUc_`8c*aY)kFo6Il<>5@<ZJ>Ew z7hJGD`TpG_HB+RIFSO9v%2OK^a2d_^UU>0EI1q%W8n{e?w{60*%EP{GdVFH#oQ1!; z+ywN)6T-64)XFa#<r-~18i7(EP!kXWv!VI`FhfJLtuYBnurEXk#a%H+ju?OA9muLd z!*p1<{ZjA&A!ov0`3_PIv2=DH8CpIA>GbS2SaEhG?Nt1|!W6kyNP6Htf>NeR-(zs2 zHLMO{u;_^bQmWi8^RBd!La><kYL4)Ex_p8(U1#opGDv^^hpgcjR-RHA1r918my+ZI z1G5u-WYN-zm(WIBXM9ncDPwDM=lFdu&j}@r;@y?)SckE?V&tlYZWtJgV$8s`@%(U; zQt-O>c~5(xT*yeUD3}@xUEu9JnxkggBG`_L369~+8y<kO;wlo-hVI7}YhTnkm^SP; zw?})vV^h<jf4{pWyiF+gi)W`lAEZf61i1Gg`=yQuLUhX@cQ|9n<iV;DYYin<p0lEI zVdlS}N!J3~#!b_G5V3zF3OL{55fbB%0v7irmLBK{`oLLWz&$gva#K#c7f-#{s1DEw zARshHpgBov>KeG-acu#Z-enbC(9oHyCS?gwHs^TLxfhab4^VTc|4k+g#ngsGhZdq( zWmN~Wx@bpmE&Zr%iC)vW{#PgyFcl?kPdGv~o(!7wH5BX6KdF{6!=f+t4@YyIS>A}b z6*NcY`|*flL2>yOQwy9|85f7<br7(^5b&o&8eQYVK0YjFLEOx{bINpHD{9hTwl9@f z#}~{}EFkqPSVfCU2_b-ZL(?6<6~iM(Z9+;d74IU0|LiG4M(dj(j`BRJ64&q|?5>=f zdLe72FY#K^S&RPa{&-vVRq|4JM2(6uW=?;D^Hn=_mjP!{K&gF$b`GjzxZc<xyRcD$ z;TGcE327Gz$Pt<eNwphZV!{sWla4>$>+k6b{}ae;)MpifAPaw-!ZJ8q#V=azeeZDD z*7qT@hgcX1;M)fONMv1-DH8dpEpSgja}Emg`2eP_-3|70!tA`c{_*LVe4_*logJIv zg%66Er2&h*Yano)e{!uldQwI=2;cW&+`8S>4m7dGllrKVev@hQMu<7^W#*n+)ErLJ zjoec@y@a(Q+rxzwrSt(X_*oRvn4-K;o!A!iNTT^m$+c}K$RKjJukCH5H$Q$ka^Gau z@bohw@}#B`hTR|U1zrw0VvuNVdJ(fP(Tt5Oov<CGrqH<+ZN^#@cd)W>_J3+MOl8Vc zu$V<k5qL4%UjfZ2hCnLTKaR58Ma9;6%2CN){T=*7FsUy9EXxV>j9X8j-Yc_fRp0|Q zS~EVvfBuu4xanaXSNX+e7p^4MDz2iiZ#0hE6O1RaixlI_P-qK<J=TXz;8^*eJTCd* zSO5%6WorLLm|Nj97PJ6^S$P~0y{X_inUpbxOq~Fmc`j1tXL8nrDufmkcHjzSnOF@g z6$H-~ZzKSjLg?K|S9nan#J4WD2)Gt`R8(yB+)?KQp%cXTu;$1Jzc=2pE!i8bz?l{~ zdt@ZT2s{@B^h@M06g~#=FD?^@h!$<Y!aDdbq$85%ea5h2GBjpBpg49L=}z_?g8$4z zX1zToYSLMUB&j&_8kJ6eSdk&q>g>*HDq7^>p}jAFbQMUT_MvN8WBVxt1Dngl0ep^p z4o^8IlQ^_S{W&RC_|Hp%0<p(D8w^xmwTsai#%wY3jVEfQeg6n8_G9Zm*|wC4MCP)G zO>7sf5?%+&TbYg}V6gS`e3ls@Zw8KlSm)ZB;jVUW0GORFwYd6(hmLQNSmL$F|3aD0 zH)N*@k_*G5ntJ4d{R&A3@Y{4}IGEt-$vmN;>AGiW&`im6o5O-LlEdnqUCb$F{yAkK z#F@DpoA|}WC8ciZvN5Qv*-bZ`L73I$$^8^Syz+f<k9T_bO03j*GGuZsab*6U@ByZR zC}F55g?(OY&igA!6o+-pX4d*>CPz}hzS29i=~4~Ts<3dNKY?s-Av{*w50f}!1!35H zMjJGM2~~-NSC$Xvs>52=^Ato&D2FtAz%RXQD*9O{yN(UkESL+esvXit(XI*gp%&nB zHdX)SK7}@7$z=~GS{Nz*iIMi>z_12%FlE>b4Q&Qb-|J)l{UL|-@fb$&eJ>w}A42{- zM_F57o*T=_POoSiT_sY{`$UT_#c_TP;MEeAGVwfYPL-DJpUmC{iyN>m)y)nBxI+q6 zu3^o3>Fk8>pL^-ID%>t*ML;iX|H}LfrFi`ugcV`w(`3YNj9ilJYYuyGHAi%BRl%BE z8!)oCW4)n#edvzPFoa>vp2$}^DKQc^W(*o6te^;TZ4jpk74Kn7h6m1_6HOgy0>O}A zDWqo7brM9X!g6x>rED`JeESE2gKWSQ3so};f#DPiF{YjhH2fI|61k*iV6Q(XPgvX! zRf2@mH;&0_Oa=${(@(GOjY79~Y-?P9I+KK$X7}Vok5KT5BQl#A2ivCkcqPUX;_*K+ z6UEXA3rr~BS5WR53yA93B)!M`N-%HffY@7CZE^CePxu;e(Lbi(OVhB>z;ON)Wc@@v zQv&zW5F@J=_kJmm6a-b!mZOR!fFDqtwUwu8^exNkn-{d^FAozyeDn$_O4&vO^h7jF z<O3jn`9{hHb85ukXVHLIEmafTa?r^Ar0<C`lbSr84iR0~t->_SrdJ+uaUW>~HTw(A zLrw-khI0ju6=<nr<SB_ZP<pg%>xP@(rfk$-tU>8S2v3`{2VywMwdcb#;ej2p`F|}@ z@K^|f!ADV9|6*A*FQ`k3()m!CZetw4L|_{lEzN+tdj5s_%ykfg`{PAXjt`xnvlxNB zXW9bolEgOHT+St)u8HmqV9{`Uq<lb*0WHw!h8e<S{|QRt2D$Q~v;QM34}-OdlqT=l zY!55Ks2_H(qIYY*5{Og~b^ir~N%ZOx0#OFE0p0^H>66w*TPU5A`|BVj*azJTXqUTc zXaF3EaP&s%X|AuK65=A<lC(txYb4MF^f%+n9L`)mAYi<5=KNVeUj`>`spzYWk!gwA zYCUOQq5E88+qPpe+v4y4X#=%X^!BQr8{sYhU7`4czF!82RZY5bq@zv4akYR0^9zs< zZ^H`SYqfXOSpdfai&nrPtv&-UU)qFa(1p&8w1Wwbub4TwzL!x>JL|c`Iiy{TLiz59 zhT+m>ur?y&^d3(Wn{9<k$A`$tqYQ2=nEf1WA4Q7p+E&Ycs<or|F=hM6$7hz9@?Q{g zp!8B(^f8%$LF`|&*&Ed&)<)<?nqUqLM7Gak8%04pe|2PU;y86A=#iXqTd089d4b(+ z1<G0?_*miHl{6<#cf&k@ctyF5c2*5yvoL=ANTzZV5WFvuISG)St;E|Xamja7&SIK5 zIYMpgMhJ(wLRS@|rkioCJ^cVlct1t*sd4XOISmvES+&e`Cgf11tGk$Uh6jO%*4;oJ z?6<Kc$W_Cv0(a)MMIWB)CgfK{_^q+W$&&9sYl@SDAeoRorA<(DGD^y{@sn@R0des9 zzQ0@U@j%Wkv=mmjaCx2g)&ep~i&b6%9XirP^WDNE1M5u5X|kj#{LLAH*ci0B3@jC- zq;fwd$I)f?Kqr%<iloJ8c7aLJX0c@0sxUaIT?k)XFcfMbw6o+_S>-Y*8GkqaMf@)k zjZCD`aS0N8`A^!pvAn#{e#3+K^<B}!x+F%iu@1C|OVxD+H~wdx*!=D_>{h*B7$Cm3 zX=DThhlf)*z#i<}cV!u89#cN?4{^b)E@+j`42iWr0}nt628BHYT9?Rtphl`F7kUpU z?@;jX@fxeOO<*ZXAuvt*;;rXGN?J}l{qx)KzwQ#UMV;b?oN*2E+p)FFU3Po03{}%@ zqtCF`*d{hWr}7*PA-;!IawUANOv6ltn#fKW3Nua_!4S&T1)!xh`AQ{gfXqiG;A95) zCo?Ioo=jU>252L}ei)1#N;DLCEYxwj%HI=OAz!%N7sXOcrfK#i5^Gg_7<fgb(&mzK zZkN1A$Vd>RTaYAg2yZhbrZvIjm#0W(u0vt2+VFY;cyCpjuU{_PI!c1$Qvdqpc<WtO z-kdxYTt^Ug0(kn--=XLs+kG3`yUnh<er$_4c|+qbvxXoIQ0#&=s?Z}>6kkXHdlN?O z)^egjtbUn+ya+>ul+*1<C1`;%BPt|{yB7Yp6?!&8vsXP#31EJ?g3R6ukeL1)GD$cF zz`<tVeNo~dHTNBIMxZSe2X;jO-;!5)K4H#yFnqsLayqXf&SI7u=Dm#XqX|wDG;-;4 z>sy7MqsGR)^;p<DK;t8B<N<zdXUA67^-M{y8>Fd+<YCkyYKfS9$eLKNA$6TJ9*Y5p zObH<J=8Ws47vSGsa0uxxmsKAWh75XGEOvph+vpGKL9q9RT72W^0)D%};5tB86d9eP z`15{iNy$l08Jlix?bvqza?#PjfK&ml&6ID2uu8xj7$qH@jM&zZLbbyv_<A_bpBf$j z#r>dR+Dxqiuoe4~vK^KF)@@=91l&6SM&Jf-tqfKvb~-_lBz!qoW=a2dK>#Si>M*;O z^zJ<AR<JO*bULa{Yfc{y`b`AEK@`Oc7KI{i7MA4l`Bqs7;vR!tv;qOCAp_SMCMtfj zP+K*6Ibe*66Eg$6*k2<=9z%zG|2AYw<68d8$7~#^)@e@AFfyq8LJGAA)dW+(;8r!f z*56@qyPq$RT&8qczEluf<oW7+wKD~3@u)d;Iv7m)qN&G-(jT)L({DVm9>lO*yV3ot z;9k>z{8r8~QxVtIm%zt3s=u~Sz0e9MOD#~dV5mlwJEEijw*)@_Nx$ioC%o#@5eybB z12i&1E*h%|wLzfa`(PTB@c1L#)OLhx!#Y4iK%zML`kvVBow<qOgrf(@=<uB&PzyNE z@OMt`#x`11Mm@J$1shNgW&Q>BJOYO`2zuf35}T4zqVR9+vfBDY-X|+QPit^FXHjb~ zi-u#h_b{yZo9tL;g7NoICM|G;8kh?JIYq1l-9w=IkB$U#QK8&IaRfiTy$v47_q>jm ztJ5@xlzmx^K;p|R&G;UVj_I_6&7?D8X~*PJPZ?VxR$lOBdYYGe1-ZKKkp2;r^4nyp z1t)_=0p0>cG|%e}%2Xf91U+o&dX4~GsFQ=y_cd8vp2TMc$qePUh&~+pDUYh?i}I`u zW+Am3g8-}A6eTF|NTPook}0sjCB8T>k2#-{pcnEwh2rj|MH6elf$OD^^VFVp5XFXl zvzEvMDYcoVo-KEToRPt6%)X4AqTSZ`^G?L5t(-5KaiyJtq{j~#g&VtHTcUJ$^Ya8< ze^w+XANT-9+S)l>FrW)a2hSYF{p1z5kk8iiNEu9Yrhl~1Q2-|gjUqN$g&4?nQ_fex z$BH-ihDK|4f3|7d%UK?i5yPp!PXy5w@61efRP5gqeEY)(`gpa^%I6}`{b0>#iYBas zk+p0~yx=tqN>6|qF8M$$jbY<f5<MR*J~6ZpRtGNB_!usudyzplf5xbdXY_8R&oU0Q z2_EaC!ijt1I^g;!V8rMSWXuEL!Ww&bxP^9}H!-cuMQ{x<QkXW&-o9)QkQTsN2g@O* z&N`1ytY7hGcx6vn2snlO3p7#dkNKDC_JvGiKl7N4y9VPe!_nR2#se<)hEk}Q>XT$? z`Xlee^u+zpTHE~#`?U&ga3R$VVyn`qMtzWvu53O;0xuU#1i!}L_0nfuvEWumlaqU* z94Cgi5EwXQjIHR+HZx}*q-L;2K4L*32q1jQ_$)>y#j~RW3h;^a(H=(_EMvoNypv@( zt;L7smgfj4LgOvS9E0(JTAxlP6@maUXf{{dU||8^ZwRU);-{qprR#wm5r8NihEE&o z-2;7@hKFWDb#{XKa-3SkImm~&&P;;`@(FgLMc6Cq-psWe!T03{==fgf2-miK`1~5( zm(yy}T;U9_VQ|YWFXcORvaOCq_9u`;fb`RuB^%wx28VNJ1sTTLAZ3Im<yX2ndKoj) zH2pIDHa{L@euErC03p{TYwiy|0(OxRFHOYv8}~f!pm*H-^8ryDqAk=gM;P5Z6VkFS z=WEU~$Y={ib2!CN9|_g~$?T5N$RJ`EJhlRDP}Rins_-q2glv6vshw76y^^AcAK8~# zlc#^?2$j`9WE;Xqew>rrQW4`$+B~$$H-Yiv>3NuuN;rD3(53Mof0w`>*(t6S)FPxl z3Y{GWIuU^4HVv&+EcV_pg(yY-O;)}fP8p02Mn-_sX@Ka|zE~a4usLkh<2(s~&r_QI zUibFm5>DjKcZOooV(nlRAlnRTFJ-W#J$t#4&aE5ZB){?O`-gM=pv+L(L`|sMN6(5c z)wp9=x{xcAQX4;xGt}Et8tH}`o)Z)?E9al1>{>xJdpEb{HO<}*sYX^0$4_B&WJV#z zLfp^*urATUk4MOmUEve?X3se1x_#+*5H3fww9&xA^zn`0j1cM=U`+$38!*^<;o2X| znM;~o=ANkYldfx5s!T#S;IkeDD9@T-k5>o{4z?AUEk_aRl;stNv${=in(FhK##2={ za$x-8k?YfBB>cOcZ`UCJEFq#uM-~=Luy}d-h-*c%T?poap-72sCO$$ha_8YID}XB( zjYPu5dUy7eAP3evA3tpKWqdtJt^>JP>Mr-Vce>Z&U!qK0=sB*{`W#k+62xdyHI+-B z8&6)|YQw4d^)$|!<-AWm!LQvFK7qpZNVu`cM#x<vdzdWYrRXOp)~=j;pTHcHNA^LZ z0eqDlqDv9OZQL1v=tjV;R_%>opzvve2;L;+>0LN#L6Lx?`>XU8MmgY7x7TnqSFu#A zurEbcJyTRrs?cBd47wY(0e&fL#4{r&8ZGkym8{l;@FYulI(WwB-<RS@^!~gfo>&zT zxyW?3I>hW28)s2gm4KPG#D&Yu3%&UG{4)XkzRX!pPJ+&oh8Xw~ekwmZe^!{;7m;^p z6p|RfU@kA~&ktql<NH?&mtAX#-^=N{bv}Y%sScqR3?KDnU#W%O<zJqRHK#1^cACr> z?x#$){DKh?EL7v39ng1dVE4#CP~YkvX!vY9iw!Nh17xn&pT%I64?jq4hvjfan7`46 zhrLEe{Af*%C_x>b^1p!A^(UaqYC__bS#o88kJj#gS8{tQ*k|<HFMnZm)j_z4p-y!< z1OqL`egNG$3GEW^$+@c4yFUy4ed%7d>xsNZGphy{QjDKL3faqW*zkdPltD%@EJx1} zd__+3(HB63<HY)FT*d<=D5uag%Gno^iOB>HvPiF;hxuGTkh5i=`TJOvitdN^yv8os z{Sv`MMF9c~(}pGTDlBi^a3_dan*Gfxo~n@!#Tr!BWwcunsY-`dUP{}pBX%46C2}FA zlkn_4{N`33;}$`15Fmh@1(5_*);*i1K(0v{h%sHpH5cA=iG2Oyx&7rPe#*LvCRauf zS8KxrO>Vi8hmG%C>+X8jCS8^R<G~PZSe3>&g`=N>&AvqscLLykCA&)NPInoEa~rdT zuMP)=fd2xA0{U-F@XQ|%>huQIQ$Ab~Paq@QUV%5(I{zCFF|HP#ysmq5{O48QrLH{- z)i39EW3HZ;rJI%YigI|W!wsj5lX%)6RUqik;-)<G-og7<%$_{uDNd7G5xlY|pE8AM zfDgK9LvunFynJ7*JRPqt`lL?G7<~Sydv6Bz(Q+}<XI?3@G>pX>v_&C1dyujd^n{|T znr*&Jr1<*2Q)^gcI!Ra-1*VH{m!Y3=P4jO1oVD<s$1+`10$GO;sV`S<r#j&=$awQ$ zjs#ox@YUO)Er{FJJ$su?Oin@f^u1GAg2W?52<{UF*}nQCJsP(u*DX3{(n<9{qd`C| zK~IEsX?^vj@i@%f4W4ZlfqqgxriWbD+NXmP(C@htKK!h&I^C1Tp>+LT0n5|3Tmv9Z zvR#8~65GEJ(#NEq-Xex`LzUJ$oQB-*+4fh+y3}J;v~BV}sPjG?2&XoD&pCQo<=t!% z*Azr2s~6y!iyrT-a~H`&?MBH_n_F*I$5o6g=;Jql$&fem^sS}4pNxICGMW%bWn6%m zhiF^-TGz?W8Lz1T&oP1XYi+fRVS-OyCMlV174dRF)TgFfZ%^-5{!N69a2seA>!EQV zmq*`bL{Wd;D4TU;x1V6>tB)!UO4@0yRr`O`MFt=L)}Jpvs-C{#+r1A#%!6BblUeus z=6+s!_F*euDWVR3x6+Bpzb<;GoCyTM7?o94Pu9MSN_M8n$FaeAgh+0N#M#S_bv!>m zgpCXY+gh|#+>?GFvgV!y_4*Afh5Zw78TAcuR3ReZw*igpS2%pJ@AGAc=BV{i^>KDj zuU$n6Q;vTfaain6(4o+F&VsdEMU}t)eev_gET%rvpVe1f(EQ3jY03E7VEJ7Bsct`R zp5Sl}(#MZ8mK|c3MtE-2BB)XiYpl9_`=F723Y?K3464z>sf&vXSIf=UzZfjKvh|Gl zIIY(Q+`Oy#lBgwgs{npt_A5y<8;6+@dBU68u(3u>J}r>+(MQ%>`M{jbHDxSQ!Xy5( zUjG3cbqLfee7^GPa;(fp(0<f?m-{o+A5b}!cSqSZZAbzE3zXiP{%wtplf34^W9ERg z`8VW}_$YIKq`Qcb6lWo}v-ZR<&#rF`x4woi^!HUw8*6+JmBcj%45K#}>?oo$jfm$# zn<6G5`1N<@BH<}tXAJC_3VaxpiO1s7dIGm%&J91?J`>pnd*E;?^@ZuSNJR#^GJJ9L zPU*WT(U4gMBs^$xPe7=*=tnDk6m$>DSeq_;{GwG@%phAUsajDzy?^#o9nZFp2ulCr ze)0vkHE(`Y3ky>K{<uaj^mj{RemAkUN==1eWA*Y+<w!4iDd<kW3;)x)_Eo>k$G8Aw zSi#%QagXOna7BOu?wdvH-A)Nk5t`vlC>3@NBJGux2sfMDn;Q7jsuD#xkK}u|9%11q zpTqRXCzyTehTQGBq@Oim6#padUiH{D@8J<ts^LNvnb(j4DZINC`GrbKeJ}a+I&%X_ zbdGsCW9|Q74_%$4A!d;Ers(MUYj)fddkkVR-g33n_A{m6*SMRB?|P|%Y~l2MP>AsD z%EQo!UH!(NA-8isYc|-K_B8k<?+|Yk9DkWsJucMz`qA%W{i|hNWk0vMG=p9_QQvj9 z;`ZygFZK)@N4C(T>=rMiI}k>`({KgFyD-u9FA&{hy^5AyE!6jmAt%=KlyEOuF5Ezc zC`_?`T*!LTX=z@tF}PY*Q3pei9ye%@bhj5irUbRFXMb^IW()mM+fD|S!}LO!;Vyc+ zChsh#3{uuUlh!P5ljbTP2!^f7$}uO6%FfXqHS<fU<%Ag`Auj2xTg>K!kEA#|V*h<N z$FwgciC)MMve>o|a@W4a?aI(@^48TJo}6RI!47}z{$JoS!sG5$v`t9<L!UZ)@8rSX z78a_UBU?957$7~QgR(B|*Qu=CfP@X5a9ewLsUq6uH|$U9b5i<x{*~=^94JPJPm)W> zL8zG?*q*sl-!u6yz>7SySGqOF`QOx9`Fd_MZ^EA@G?yRj-^7YjS%oB=iN9g2@93qu zeaDGJ;oOk9T_;(jjz2(}P_c{et7tfp<NXuL*!tSJ_Yuv+w0`a;S*ZFl1#nXm->=f+ zZc5>nlHTmxc^~2{O=?lx7I5DkzlBB_OU=lw{eI_sZY#dH-l8F<Q={-pKHcW>&fL&L zN!E?Z_s>J5p?~i2xfcLGsiCSrZ>o&`rR|M73$9K*MkA6eTxGOar2JE%J(d7?V|p{$ z;5#QJOunmlRaUaC-S+O8*q3A`zw#z#374v?b<H<(#fFg8j)h1bJ$%t!ZynqgAVq1B zp!_ILPr^}Q6$@;j`*D5$2@$^Z#S{LL@QP{t61HO9t;4>i>qfvXY03#=+WwKxPN!<V zn4_Jv^Hv$5tJNsr3&w}u#VNZ}149_Mt>dTVkzmaZq$HM@WM7-q{eI+PSYO#MP4M&d z*6G$9g7!M*&i{#6M$8a|<U|kQCUJ?SA{gFEgMHYg2ihWHIa`utc^-T}md~lQ>bIV* zghV0n^OvP~^fI%=>FPUv;zJ{2m^j%?Xl76tnV^)^JUo$-7^^g8+QGl$UUjc~vSaSr zl6Sh7?izc+{tWbQ#pOtWQ3%ts&YcRHGuh%PK-y9M;#;~}uxaqcEXgN#=|;v;eRYgn zc0s^9rs$1d7xf=9%gW5CN{|$ZCqk^z8rbZpv8loM9t=7JJfa=DuFUqrRUHdD2}N{_ zTAm;eo9OSX{Z`2;sjAhwc*lyqzdDL$?7Os8y;JiX>;fyNb)p25oJHRDyZga+yJ~KN z{08ltg9f?K*n@EEpEIAy2S?pu)we8xFr>}MNFe32OuZ$nurS~9tnpIM5ds{7>Y;;k zXSUpE3t<pq^wbz`3N?sa<XYXiT7Kc&?T@T`@~_@_y5&jPBMY535h$uIzWRSBe>s^y zd8JJ-n~LsVsOG8qT2#fV`bA7N_-JLi3s`zH9PT_m9$M)$gk{8#zB0>Enu}aJFF;m_ zsndD`wtMd7-*JeWNrFO6J?6XLuS6>>TN&KxL4mV?lZwNq$AyJhNLm24anJs;tH?_? z`I+6q1jdex%79wu$cI6SItsTl5MI{<HUy;PhjzpV3-j-gKioT)jZafPHXAQMTxm5b zI?GfzDZX2gj!&Kk3G!F2CJD`HBb*+S0^o%s<Hd%p@6ht3w@76jz>l?HT5998oc9a? zsTqr3Wxp6}9PEB`U$W*|*Q4&`mjtjGMr$E}fcvdhakaQa&jE^T{y9}teAMvakf=+D z^S67x(zODR#GXPUr}eM5+#jmeCZ_dR!F3@`(>c*5mABjcOD1J&o8|@eZWWg&{>)33 z`i*8<VBXnLo@rNS_-=V8YScb$GaT70S$F9;sdiRL1=0n73}WH!uN*^)D$QhaU=*8T z`Lc1aLB@_Xbj%tyjH@IIG1@TL-+Qlad^q4mp%~810vp!twb|YJZa(1pD1<1=5oZQU zDIEHV0HvcWC};Yk>9ZHVzZI-?)>yYM%;%6)A|5eR2wya$QMF*&!P-N74lOWW;+Jj9 zW?KudK0CgNJkpQb|CC2rzR=0!C^pV+`@IoAm+_NEs}sBM;tf6YM;r7AJKiiw&>_k4 z9Hcg>(Q@`hZ+V)IHouBU5=3zYLTfaOVqM65bKA0P{hhZG`s!J&Ol5;qi^VRIMhRQK zx~v}1>MB?#m<|Wc&2S|BuK1q&7r1-9HoA{*EqN2GlKM6r|5F*tpUoI}Z}2DHAI+x? z&z@T_dR|3RL9j9}GTNUL046r>&XJlA#{@KRE7|=r-y0O7B@S7H+gzyjhE^l}_f*qr z?m3=`@jW_1u@Z>3w^I%uL9B2%sK!*s#21~HVzpGvK-T7{|6Bvwp7rAD$=E=E8+k@U z5Y6b3`TojR*X)VBkt#R%3a)EC8^0czpaY)ozQ=`BoDEjq5#Jf`nc~wj_7Re4$lw)k zP467Qp;^ku%VP*g_lg}qb}UW#$gR%^WdLNi*0G?p2(rSJCU>OuSFz{xn_LllI%t~N zH_3Oq`2LD|5}m-9DKm%bx{CK$sC>==N5b&F8koF5ZMIoPrBS9bNV@VPV^|}Zq7N4g zkF0#84j4s2G0at303JLyEZRkP+a4WsaCQv`2}dB;`l-G4QwdM``vAJhB@35&{b|Fk zMuz><8)Y|#tOV~qX?|%0N3t;73JQLe9UI3QMjw^nlQy8UR^NPR?=(D+FlKTKTaW$y zDWlJD>0P;&lbBZuL@8NajR;65pcAuK+;<+fI#>S-JdLZk#K_*w=n}AvuTAW)ceww= z!RX{NIMaU&H$kp(IB$-AsE_+r|NeHWADalK1uS&^-k3+feP}fjnr49us3;{SM`30- zr61TDBg1WvA4wm0G>2MqzWwoI=Qq(aO?324O61Q_zwaGqW?Mgt&en(kkN^dDuwHrZ z`DN)V4=;8R@~shMC(>bRZnd}BFa0Ye&+4x%wRg*3x}l~m)q`N~{CIpUF+)G$xsul8 z!NRgelG&WM)UQuhN)J2HrK5$Jh>qzZLcy_r!qRIlZg{5O9j=*^opS1#$^G?Lci(wh z{r@RC_jsoFKaOvPNf<?uU6f94U5sKbyXfLpxtA_-iHO{WT;?_;rP*9d<<^l~iX<Vo ziOek%%4IIoh~*aMGRE)sJ^%Gj4-b3H_w)U{->=v6*|5BMHDjlA?7VNY_z~N5rbvRX zAaVNmA{cY&Zv(&^hxJwJo^j1gnffFZs#xmY6WVoN)ADk8FVKKV8>vkIKZHd+=K$eb z(@LiI@@F*orb@Z|8t-?^>5%=#Wn*nv*rjOoe4o3r{I@z8_z;T3I<!~3_FkAIk7%B& zQNt(8L;6uSepbd#ARS6m16iODQ24J{i7|eQC^*s-7*)^p`BOi<+G!CHzqyHS(*Tl< z5koIV7o;pK9Y>uby)K`GscV$IeI049#Ez(K3#X>XyZ&!*^<@bEAshB>gUplbWqpb5 z!4#+$9vzO=4BWEE`_^3(?ZG&?F3`(T$DUiO=&gZhxAmaB^4lf|M29PZgHoU08B$o( z<FMqS_EmHiH|RkTn>;Qnk@?s>27b+eW<<%u#r-UcXf1wrw9-f9EVYH^)!jRLLj2Mj zMDzm*DU;4nM3V32f0}6#^XL5SA@H?@!G^%~3du)%Ps&1>?(>o8{sJ$f#$N}jF0^JU z2M14i00QwgLO3l(T>ewa?uW~7u{vZUK|JYq@vY-VelHi}5qlJ7hd7JB>uHm}5zpI| z%;+}gYJ}dJ$`Fh@M|!eUnWTAeleto6_TmK9{W$%so2qckT(!d7U}C~InFQ0c@DHn% z<b1g6D9P@Fp7sZ=q;?W`p(ZLe#r)~ekXpv}Xyjsaku}h02rJn8F)qg#Get=@aWt?? z`h6<1KL4;GEq!$!p!t*}iAL1=Pn@(sr!2jAI{7qm69_J*Frj1v;>bs#;*4ZJ8;f4( zw~1=#5bR6IA7A&FhdS%c%^YA?6m6m2Nhxmcn702kk;i3{-bLjxp0@8zHpQ@F2uS5$ zV%haW!P#{cHD!9c(k6d*3}hTN-u!Z&Pc=yziqff;AHmWW64#lsL=7BtvFn2xywX{X zE5IoDV&~e{E(WX9Ql{gT!*=28+`b0GlZ<}?#eZU6{1p{0J*HhFK}t0(`z`zYZ2`?Q z;dWL$6bfHo<2tD1%syfrbiv$VIA(F)Lxt+zVW%%zj-y%qT|DO8rv3Tv4=k}iZg!`b zBj~7%bmvHIOUlXKufgOjkiLzVj9d+?T_zPx%^50qBzpF>8W5Xj@K1MOmCwD5TzC@} zHzn4a(LBSO65mnX)MC#L&E6Ojb24J_4+)z7uI{|_Y4w7f1Sw1bl?SJyTxj-<-g$YM z8z#Bl0MI-P^EH@s+Nmbo`D%wFI{=&XPj~4)=^3CpF*&eoe*mu*@pCqKX7(NfcPzAc zGyL4sYpk7PGXY;3G<sr>^Jji7J^5$wOb2hyb~own0Zs7aqiwqDrvS_xHG_>*%KX?j z!a@%z+i}PsPHxw``}X_aqN}C{7!b*tXc;V#I|xJ($YqkW7vG3#{M_T@Xr}gtkv#Wn zh|R-<(+ne22K=slnNGO^Z;Lomn|*fjSjgVhht61#HGN%SN5g&Vw?Sxdz7GZx1uG&L zM4SJ9_bbe>Rv`q@%Ap4K?%wascy#Ipi*~%VC8|GrbOsPFS(@|S9r&96apeir`P>Km zSO)^?9n)8P>)3Gpw1+U50w>nEu9mG}USKO!$G_7)iyj;!j&2l+Qd91&cdf&we`^Wp z$88Kyqt&-J*o=qyy%G464FQRj4(yZu`F_!Zyz-~JheB`rgj-eir)c(ft!`)>%DEi* zqxhRh(nr#r7r!vB*M7(foh_cMaEwxqc0mOFa{e<I;Mi`dcoTJQw}T-s(D+Bm4g5s3 zD*!YZ$f&wL%}@L9IJ3JziaJM|x|a>0OZ*)qBv3`GUk&%cs^Pp}St$#&VE+JrteU1` zNoVm4A|4cgJ2}wyvLH3or?ni@DIJaS#fu9zHlP0zt#OaBYrI7bq%{o2P{2;M5w^?f z)j91$R4r?vEhPp-pux@#_&e6sXxvr8$<f14-ok{gX=lB?a}Ksd6D+fRxlNQA0Oa!S z-W~DZ_TWaFJ-i+uPkNX_v^w^q+UfYb&v0A!(z*b&W!KkJF~lE)s9X85+Ca+4mLl^x zZNpW@=hwkcE&aa#fPvrZ>JmgEHa9bFb}JBvoP%aH-Y&bp9{H3{#DT9-ZCQT6AiJB@ zrt;j$iyCr&ZsKp*h|EXdzyZ?GT)jrY<8n@_?QeNnW`O9A3+s%{pmN{uz0bRDU#h@e zONxcPEHlR6U>lzDPG)sz7xU@jCZJc0Xur+|{ecs;7nC#u8loQ{akg!kvg=*ry?v=4 zbRvrQu5I*Tyta>?p+B)huHxV8Bcr!o#({?=?wHNCrVRpo2K=R~-YIQXU*3kO@lE-U z+Xc9cQBN7M<9%m5R!vXTz;^alBTCg2m1mz%JI(La6vKbM#Q?y$yffX#r5{VlP2;|F zq!FXq=;o)BNB?HL9a1ng=@@dQMBdAx?D1KD1;w`r&JE^dLJ9(2?lmZ`fsjK0)*d4w z__aZ&jGCU6dCqedeZ6SxuvrApJ8m_Q3N1L>`L-yB(6wPmLM8zDrzGc7!<o|8yl;mt zP+{hqgN|2jJ{QjPINOqv6WyaRpLD<RyQ|g~cvEJ;o{@80;&W2#<L_N%qmjK$A<(}( zj$Hr4vFCQPx0cOL{p%@(pU!%zzu~g0P=0$;bwRYUFpsU#QxLx3&!D-)IO2Z=jZN+t zAQJHi)+^?Fxj82hg_lnK;qGCY=w>Ju`yOZ=fMtL;m=Q0~h$tnDB{}f*kus$XBq*Ia zp-^#m`w<;72z{}wxSk9aNF_iv0v`=RHb>(GPaE-l((`v;VjN;?xwHaT%SnxY^)E|` z-)a>DZ%APoUh8+slm~huZk^<?F>18<a<0_Ey+`#Ep9QETnH`Ovw^Qn8M~oG%WUBF6 zvHCy1czhDTQWDxM#hxl2@?5&LDX;#s-#IF_F@E{=J=Bx6a~oFeiqx7BT(-88jsR72 zt?|U>$tayF4xxs-dhW=t#*F2W_sdcFGCejISnY~&F|>A9xh~tyrX&9brpR@Qs02g3 z1N%`w3wlBgrCuX<n=;NJzqV%M67m*9OW&}PD-@0AooUOjjo7(|7-{ZDK|X#bj5d0r z#Q{LW4wLe)Yj&>Z=vf|Pb8r-|_)ahZbn%XuT{q0)bxP#E`Wk_DZ`lqWai_Qb$K?wN zIn#i6abli!V}Ob~-S&=L>X!wNhDV&l2Ih7)ovS}nvuSB!GWFydqgL1-4~}ulYSi$_ zm7D*aq4z>7<{7O{L0Nflu(~QLag$KFdFp)dbgt#&)maDM|A82mD06mekp8UT*fUEY zd3|cLf4yiU+UbVxgptD?N!RK)>n*#t4GcW6_0x{&d$Ct$e+<*Quk@Lgb|E@0@xu@U zt1fz2?1aE#uWO@zl+atqk_2_s)@}ozp{o3Mz3`+QEiVrWiu$<oddpwidNt>VRvd5* zE&yG*Bd<iX($YO^5VT-_&BYYqg)Nfj?WjUzHiPFb-5$-+cYk;JquFl9?^4ta(7D`} zK^FICK4uofs9q@{?nZhwhPCN&7YH(`VBjz{4UqtJ#iyGVoWntCIBzgN5Lj)oJ<@C> z4m~&^--EUg7BU4{3BP(cjvp(cq@q(UNf6pp!Ie3dKx`5@1Eis8OCp%Sxn9_6uN69} zhT*98T$yO;7`!t<ze-kM%8rL}6y}U%CjcC{J`vEg7IP`ib`-B8_W&O|22pcHVbsLQ zH~p7hGmu|gv-5gm+QCo&B;`udFxy;<H5q!x!aNWSUT9XqTl#$|ZD-tbmY{|K*P%Mv zUkZ@hKE0sg$^1s=Zdun&E6@!B0ta)=0dF)`Z$m*AbQ0QapSRROFJ`K05xSyt3)DEF z+rvyOY5g_-kvN(ha2G5#HPa-N*5nKG@@H6pk5E=bLwSJKTs{A&5U~e(+_Dg>UK{-^ zH#sd8D}P^3qdng{JXC&4B5)-CHp^HKlnPM8^+9_vzQa7mrM2QG!c$Z`k-32=RA&~0 z61T!;!|DNgh<Kv$5bn07v8a9wb;8N<N2Zk0^d5PoDbym+Q8>3kVNlRY6e3j*Wodp^ zN@$@?J65cjvlX1DDRM21K9ke3b(O4+(#$}qy7a=`Na9|y_^-9W>i}N$5-WX##0jZE zMC(h*8Jlzh(v>2h^;iDY9rFAO^`^f@GT@HR0wQnP(~|XNA#Npz9V|di_PE=o1=VXK z!TJ#iRU$WEaYxxw4bcGZ_;mclZ;9B*JqpZCk}Wa*s-tl~8DkL1r57n0F9CwLnbV`m zawc6>XDI+ySHwv*i%N3isU$uSdMn{mJ<V!|#_fidTs*dr=`+;9V@Ks=Aa9CPQuT@L zSUq4(y{een>KxoAij6*e`9xOQgaB<Z9engbj#elg7q?O<WODQXt2b?eJ3@w?)N#~9 z4p1N(s&qCSk`}WocZi1={A8c^`i}S;^OHZAPSHRH`0{%p{|3?iIeySr=ybcXL{m7j zg%WN{IG%IExs*elLGBbog{cqL#(E<4zJZhu6Kgzzjpi*8jp^hJhoD)g{I6u0?AMEI ze^SiO-F06wkpMluUD?j1O%bi18c6-%o3mXjzNwAc{u4SSD%l21fDoKTL7v1ia~k;R z<~>HXLo-Uw!Nt^TH7Hdj@PF<r^Q2*dN+`hleG!FH-z%Brk{(DQ8s!xitWIaNiN`Nl zf6NkPQ6%%$0i&b2uO6#eV`p3v(gj<|Zu$~BmNrNOn3<pB(&+|ad<(p}Z4Jnr;sF2| zc<Y6N{3RsT0I<2wisCNC43<HO0AD?@#{d*I4_dI^U->{uSLu{HgtFY<ms=OJdIu;Z zZLQ$4By1M!Y&VRQe0=g~EkFvu?5ZBXrHI)eTK+@m44fqh04(O&=(yVLmXVBrrb}Ro z73j~kXO!t+DHCCKpPW)g@Q?wR$>A+nUgDF5z<)5nwI6RDGw2;NI#toJ&gkze$dk<z zj?2-)`RWFaMn<aFF)G2<W_p;hP3J4I1c&`?Fv$B|vN)MDW1&Sjv1>@Q5eWu|NJRmH z0a}@=a|294#Dqu*4_YrVYcmCMHOv)(x`gCt#B=#}2n5v^`?IB)AXH8OAuzwP<JE8a z^8?USpbmB@Ny<v*`xb1PwxSNyp@70Uq`xmF(E?{<+P**$e}cQAGrG)&t*Et12arhM zzBG5a74m|277-W{S8iGf7j+p!e1AhSK>Kr-BGq0dYRzL9SiLO(rdso*OmvT7+A3Op zef{;-!(uk{Q;L;YQlr6n!jw<+<dk@osOdj20thvEu}!BC3d~asZTGl-L^X!a6m8l* z3?#pSv7^6`CBO5OwuG{GD$H9&_#d<a=}fNmGfLF_9aJ7dJY|<;!%=%K`(Xu5-C_1x zK{B=O*hSQiJ=|tYU`3A9$w^5~OIG?>G#CUGjCR8e5>OV=1xIr1J*_aD7-myb9~o%| z^)(wY?!|BgB?(Ir`8YBO=4WJ)6hNlxEYr?5(EbN<e05!OLIv1LYY$EoxI>1oA?lHO z45w9w`BkQ3f(5Q|vv3jyaxJ&m<kH?jK+y+&Sy<j-Is>r<RAlJz-~_fL|I=4!ZaNb4 zTBUT}0D#9~Lj`KLZketg{N0XcW0OG2zN4rmSB-dfdC{~{r-!FY&d%~KhHD=E)A?{$ z>X>o#R!fy$b;KJnaqg&8{yUIy)Lho2JsiBVh$%4W%n|JqV*6uD#2h}98?%-uB-=;K z_R<bTf7R3Sf=d4hwOwS5oXpCGwx;~jkjJQadIm6-Ef&27^bhP@V;*jW&-_>7k?1iR zg(2iAHp_K`&{PAP+)S6poYF|O`Z7KQoGivbJp__zAnymXqo2;EhW<)-@i(1ly9pOT z4sZ^e$$UyRaadE}a1*^A3nfpq{4gQT12H7Uj3G0@f5oqo8R2Je-XAQs7*yO!j>l}U z`=u*mt%)^)ME&JC!XB#Swo|J?AM&lHe`CgxsK0XZinI<!k)y$tAmRNh@5j<MBUQn6 z$!$jM>Y}i`g@v<)=<ohG>y)-d;QnDeAAn(v<kEwo{)VEi6ygHkO2~O$geDxb2rcKD zvpzU!JpD2ygjo~LHMbsIT)M+iV8zfZEvGL99X@nCtFypF9+X26+y$HRn;8~p?yfAe z7OArjCJgQXV%{?y;NIvDuAHPAE-ybyT0j8`)Yax7f_-o+9*ui&n`{PhRrdQ!4PygM zF7qqOuD*vG9p;69zo=WElG?-FB?9r^?roiiZId5Uao*vi9TB|yS56Ft9h^^uP|-tc zvSc@6JBYo0bhVERoZd(Dki)1k1Q5oU3o6+wv$8ORfpWQ~rC*kmr&N^7JHx@3CzCUj z#q|{0fL-)yp*Y2;S%XM$QP4U>fkWG^(g0_HjPPHGEB(ZW(1B%w*jo^|r%#&!e2-t4 z149peSH1Nj$)bNO7HS1BFVF61-N`h;F*2gwx6Q(&6AVP87FhOEQ=Ah#+&~P={p;Zx zW@BWa5k`*=qRzmBMS&L(eVO5a`un)_@3BMf&3cDTHfSpahSVtUDA&^yF9Bk&CZ`4o zWPZdHEEjuYBQ;GdN&ZuktrC(2QQ2Xys`poK?qQbzNeZw$!)cNYyo>4nQ`0V-LqJrF z+DNy6NUna)29auuEy5l}_)}H7l5J?Fli%tH`Ow+ZQI4YBzF#PTYinOmCx?v|!B@n% zbgrcY*`-I8T^87ksL2C&<|K|L>jSwp-+sV5x4WOVNCocvF_&i`8XJ~lh)PPh6-zdL z$~Zcqn!jFfxb7kI5{%detpec{O&$IRI-s|)w*J+4+QA#q@EN=`k{<D3gHPzen>%IL zhe7B1mjU3n%S%HghDC0?Qu8Pj9;CchAg-A|jn5OJJakU@y@6!{j05ta)*~EG`qDfJ z2;G@|d9Si*a_K&BWKPtJg0P>7D;w)u$n^Zcg<yCNDJV~L0e2(A(F~#eg~yp2r$u=9 zId0~Aw7)usX1D__FMNxvPmkr^9(^{E^`F0m?9vQXtX;_M?hiw0+-abS{|}UF?uf1- z){ybToUOii#+V3!{bo6f1UziP+TTO}pjm(EuP37xq1AlO>DSbQ5J>;~1!Ji`QLQ(y zF;TKG$d_~YY&^=z%i_7nUt5iu`wVAE)e{XEjo6k!>OiX_Iu6j^_(E}6L4dxCoIgDh zEX*L_(jQ3HU^xBMdfNwj!H+(T<NS<bQh2g2uZK9VC>HMqfqHfJB^nz;`^R&nPdEB5 zG(0vuDIIh=_Y|DkpatU#)ZV@>xxf~}0r3oin7?kZav@ef(sR?$Sqhyj3dP3!jxByO zc@u(x7{)9u@ORTQt%5&cX7;i^S?29J08v(yT919&rWA11EsV#2Kj`PanuT(>mUB-b zzCSonnoCY*aaSbUM1I7QfFIkk5@M(1j+HnH?R-z6MB#X@{^}rM1U)YHV3V(<yuedI zYnuR2VYvOhk)H2bgw;*(%J-GA_-E#z(5V9y$!<+ig8;SC_z?nkZIaAeFKDUMFn$&M zNpBX2MtIp7JXR-6RXR_3G))pDTHP>KFpF$G9`EZZWwL0mDDZzE6@{qh=Ft;MGD$@# ze5<h0xEj<$eITkYKr0$CCs}<j3LY7}w~jR6RB6byCokuwQ^{M0ET2J&S-n!3c_P5n zm{a7XWdxZ>1KK05N41d#+rP5H4nLYHMgqzKzRsf|3DhrUprFKUPxiZs!JPE@19Zpd zba~zqVFaw4kILf$9|5u(#D`+$4;IM+I<R5(jFOw%cS>?X^4Qrm&S0+%c!g57_$Gf2 zczYKo*#4Ia?FWn&mxbZkd5g+vgNepGlrDnUFW@BlxAS8<n146g^T6*zoO$&2-Qz*P zrR!FC1~Ne<S&W;qVBDV*PmtFGiTg&^#Z~4l0MBsH@#%}I?410<XdFgh08pG~pgC`# zE_Bq)NcQRhDE`zXDG^0`U`U>u2jmy^MOn$%$~NF(FrgDMeRZr?L>^8-MrSAz*wQ)( z76Bd?vxdyweIsX``_T2HkZ~w|WA`liQ2T38UfFmi2idgyh6vA^CWwo|<kwMy1?r0s z(1B)^STt=;P=Z^6=9U-n@<g1C#huqzm{uenf;jSW<=Ie~e5G%j&H{v17zw1kbRimp zR80#L?&XoLr)TG7oqagU-2W7OqB6}hN+Dc6pv!<L$5HEn@-oe_p@vaZ?W>lb*2|V0 zLXZKIlPZYc0gvd>6yp7Q0sB_RrMH>zex-B_E1nE(!{sJ;+0>{#9ix2~W9OQKq-@2b zZ1m>wXu?<)QZc7#ra%dED}U3(3InZfz+}00A5K`_BKGz|{7Yj+!OC$gWI8eJ<CMle z7~p!b{T$GQRu+#$17eOTxZue^4xc9rYX0#-v$R)AGcwxzQff@#Z$LNzr-p6WE;F8e zKj#KBw``!~TuJD}pPD8}GP{kY(Hn$CsFB6q3N6!#TnALqq<Mo8DwMcsdnJ_7DK@jZ zo(J+aMAmd}(@4P##YZ!Rdk__-1o_<qSW$hTv6~c=sUa0InUDtodMY2MOb=pwUXxT& zefdyGx!*7Dl6ga@9#qMryg>bdp^hfDqK^#M;ru@Qh>qb>+%xI#_oO}Le=rE|-;I17 zvta@SxZrN-D(afX<BXa-Q9%;<<%im>UD+bNj;s8r*@cv)B?|+f|D?^T()Qgcen&;e z%@JhYgM>mAFpwgZA~?|omG1I6_nAss;sx-ER)hZi=Ji*>GvbP#ipG|pjXdz#jj2T* z+&Os5X8+1QV@xwsmMlSqcA9bo8wKnv-rl(hM1v|=vqk}~DlZ&_Pdb`ZZ2%N&=lI{d z5Pt~5u5p$f>-^fi)I9<qzHW*xy4-9`FpR=1ZQf2h{z%vP0ROWs-QA$#DPznq8Tcz8 zj3KYzES{m7^dnTk;Lh@ljcOjJsK_xr{`y0>a~j}i4iC3pfhBYF4B5fFBB2&f+tmQ{ zBHkh$j2dTN@+fyT*O@5?!8z4^x$#cvE+Hp-u~83`4_LvB3B*~Tw^qJsB_tsz@`bG- z+cKm4Tw_uwQ_*YO&`u%#l#oTJa=D-Rm8k<x{st1!uxeRQx2jT>vjo{7=gYIhVsvGh zMq><gS<uAXJN<r#!%hPPChZHCSXEI@^mR^Cp(>cHY5kERQw`zvcy1FvzB%Bm2|zUZ zo-?dO4WcjE#gI>|9{9pr0LrqUGJ;-*VfgK5$6I{?10ep?yCYOk$8>^Y7saL!?jcN^ z$ODEgV0@e;MFoz!Atvk+ri{Rrbcze+>ZWHt&|cDhW*E6tE=KR+%?x>P2|_Me$CY9O zqKFIxzDMnizHg@>2e^^v_N6b5RqeWd1ObW!!4BH2?R#9ca*>NsrbI$g=1L%|KhY?g z;a9?WpRa<_cDuix5B=>_*MAqWY!q^K0qT{z%6ko*76@hu6K>T>;G6u{=Mpm3^#_!d zgj?b|J6}f$sE3|!L$cqsL#oXklJ`p1M_cGyfrVoPHMn$%vjHK_Q-I~ja<>W+S7oZm z04H=}OGNz-rVJ1#fVXN3#l~IJX2yHK{G>g7f*K$8h2t9;4}>4Bh7Bx1Qne-G-iH%G zH-V$vO7(Dc33L3Y@A`kj8IyF55<6!+JNlf_A8{n88C9SGVHyGo%kgAq4QawW7`Sg{ zfYdrU!cyT9uucl<v;FT`o#ovNdSTvbj>g8}oPsl^N()y3(sK4^D@dp^k%LO!y8SXk zI3RQ>i|lol<S~sETcFr^i~aLivH@CcaTm-G7sEYgOQpX?&v5(uN7B@2$r>s28UBu1 z*wK`M|2o_tDO0f`ahUPc?`O$+jx})JOoOnLnY@)2;E3!?2Db<q&B6tF|2gAOCvPsY zXCMNg0cEg)yE3cqiv04tGAK7R=s(+)>S$LSMG6DA68Z%66NA?|?~cI;nx<2*>BJ1F zy>3+FK6D(-%S$J?+-VXJ7)8wi^iqE{40~S1Uzs{qxt8zcIwQXbMosOgU5ld-Q(~bg z!21=2yriDgn!=2JM#=s1JS90KH>28h2xtz>*(?~kD$-mTsCe@p#6@W>G35AjIxxCh z?2M@kczD#Krm&*@c9eB9<5HB}LIWTXKuuZcO)92!Fi(S!fdb|7cbA}h+rIbbWCdW~ zpi|PB)&mi*h@0WIadIv_-)S@btOC%*m}Ju#hzc^}5ZRwBy=QA1{7r#vMr%q&_a{2M zArDUij+IcLU_(|O5nZmoqv#8BdPe*CJQm^{U22$&mxzv6mvdEW`!V^0NNuPzwP3do ziBx{fiR&ZFH9h`d9;-vm7foOA`MTML=36mxKkIQ2mHjJ)3+%X_{unBNYmm~FZ6C$C zq|iDuYgP6Rg7z5z!?<>ZW{gOkEs+AW+_Pxki3Bhsx;va?HA>C8&&-p}&p}gGfGb`c z^JoY%X8=^1DrW-7n)0a=yLqY#&?$uuCX$!uyuh^lNj@mT`aKJR6Ju!RA&UbinUjVP z)=08y;40E=p-n9xTjR^0kq3@b>rL=S*Fqqc)TE~1N`~>jBEs1@YDQ2ciCtMxQ%E%e zI$+(-mblNU+4u^P81j~2-_FsTQO;UpI*5brE(RO~s=Y=_TeeT64PR}*x}~%TOW$+> z#SMoFTqLt>)_~p{2a(_fauG?-3hWJL00J+w)zp72CQg!iM~{8)C4+k~TT!xEYQiT? zL1aCKJii!hRif8pc2pV*J;y7UWWaN@^2@Nrqj_vW=|IZd?vZEyZSt{tN<5SW5MvT{ ziE=carv$a3x2&eG>bMIk<}P-w&XJ>l&qr?8f!Drhf-(nrTGt%Fg4)}_%C#G>XPyeX z!U0@>8PoPV*)Ui*2)M;jqM=7M+n_~WAYV&mXkqC38t@0?7>VftF=Xo@A5rOmXlu!= z%~)RdFK2E680&T5TY6V5*njmPefi*8ejrfJv5CdNMSvmgJK7?z8Om)_3tV|Kqvu>e z1pd`vI*Xa>%O=+<(D%mAYTgCE-P0qcz&B#x&85ck)y>*;-H5$AB8Ec5I=Hl&eq1Wf zG4zi~e;-+TXOa9#kH=j7s>Za~qY}Rrd|HCXCJ_gL$CYJ=BXL!;$G~-*EYs+^N{nkq z%_RESl=6wdoW+MDnGACX!41quWKsgtK7xB)WkIT7f_xW%wr7@C=?;i;-mJ?PITLHL z<K!8@RTejpdsx^kR=bU~+(#A?nt{vW@7L|Wv~u&?I58)ayNWajw@ck;@12#SX$*q) zbB&ls<8q1yqPJ$jLhA^F5Qsqi*8f03Da@C&zRVCIQB9adWHH|#`-r{)R1-|cR<ooD zU}FrI-ydVV6$j*P{}xgY&TvqVzu`SGbd6;FzoD<es|S0+hU4jM)M{VC?Kpq_HI6bo zqQO(~cejW9QMaIW)TB)*pbdr?<;8=9V?N$T#&NG)4`6681LsMHKBK3T=LX>(e7k*o z&+LjB3^XSYcyK^)^a}PV|Dk3_eUjb3GycjYzL~R4Q+9Wv+*e^^%^bds^tUXKEDr=+ zZf~7B5VF5Tx|HU`y{hc&G~=BU2c=NQ*D_K|t4t5qDCbGq<i~Uv(8|v-iuy;$XU_SI zK#zJ*1wfJgS{c-MW(9b*^<4FPb{7r@il$BCQM=a(6B&&0-G&NVr3-te%>0~fW_9np z*TXoPKyn&BN1GW2;rfe=zXP+ptew!^E2+nypOK&88&-Lz*7i&gw}ML|?2q?d@JjVh zMP*90Q0&ot%+rZKdXK-fxacO;9KH2pp;6EFRLiwJYm~S(%Iz9O7s<ALIKXgK)Tz<9 z{3Lht>Kt-%yO3ZyUx(lN@eZFPf6;Y0jze%?ZlzjGd^~&~Kq%w`X0URk%3kHKEi%le zOHmn%ctz>xFMhtWZy+XmkO8<4*HPw!9p4SwiPDx^%E5nWGU{r2NK5L*KkA8P1>QK| z6cD_@FlXij9`M&P<@*PGV*q1Y^WG#0otVrFckhHti`Wk)@a?N-Rw{MA$b5?Un$T4p zU1U);o8<<SF;g|;41)waYE}_nH-an@ikqRi>!!t@vi}_6UxQDQh-6ric~FsG`}T9N z0`B?x|3Js$(97QH;<}Jem=1=e*S!*GkZVdBg>;{lqrR^>t~(LKHv#5bH?I=uN{<o7 zY^@<wGN%9(Sk|2hop#psR`MTfviRYD`IzB5K64rMEN&2(OwTUbU?zQDS=Eey8JM{( zd(6H)$_#O+NC0VFxj(VD`}?h9CP??-3QXHL5rFK<y*zDuvtwFX=##4+0=%(%OMNFv z@N@zl9Icvc3&ep#JGKT6Wvnuf&Ayf@@=CRHU1od8f?ouuyS1|;^0{9vJ&;HhN28YF zZ)e{M%pRyD2d}36Q8#@qqxI;#D>)RyQ1CM%d>?RN$bPE1|G2rmgPSr8wYZm?s^{_a zpW}NNU3(DdEn;H)Vm}z3R$bD}QdmfADAcwj9<3Dhc@CvDeDuF?^6a<i7}u(CP1M~k zQp&=PhLYN;hMMsQQ|qi<xjSVS=S@V+DS#qDrN947_WnIb!?c<|d}jwT5V-UgLbr)= z%CSOh)Vc+FClE;3wN}44G3aX?n0ti@g)a{Uzug{M*S`P{yOZ>+KM+;q9lT(}_5Jco zH-v8l@;7p!K4-||v#k!keyF!tpdKukik%pDq4f(iMDLo3A2}Q%L`S#bKSx!4A3M81 zoN6nOv0u^+9Hcp7-ul>j+rRqP!Nt_z860T@=?%`4R3vYpp-}NWGCHm*Y8|V6{iO^w zL<qC4v>l!}^xX}n*pa1y19+&_)T-w}!5R)=a*+!}-X*souJ6UM^KaU$Y_xP{go7Zo zS@pgVt%%**OJX3udPoqCK~;Yc=%D6w!d@mGKgKC9f>t>^x$!Z@V%mTf03C;H{YXw8 zNXi?3H{dM78le5+l_n2YE@Xcw8~zeGj^++0nR%54r5yO@3ET&ojL-IAxP8}t>f8+d z))NY$J*$G~m3Ccw=Ze2W>ssqEg21odJ~f<UbmU=DvmWzuJwObo3(>6WF=Jd+zDs8m z86}pzkv+nw>$2caaadJ0ZXcD+PQS{hT8>QyKU9EH*g37iTeq_mZr=v`@0WOGSzb-L zG<CpPCkH~^%|{NLjuR`+@3y6{ZJ}IjH1^**9bk6QDo!|yxQV)P^GwVL>Z6~d=~*dQ z5oRac4(Z<8X%yP7Xr$NdRJ3UqS7@)1Qx}Q-ED<!*N3KeGd{QU7E9tfD;&AgERezg3 zsPd~QR&9RDaYczWo5|f8ba-83*RE1_5EMf@H(_|Y26e#j-%y3b$va|afmcoL9Pex3 z;7A*<8aKR?#folyhxn|NfY~aR+bSvc@1Cc#i4)YAdn?iFz5#|IdF>3Zh;ICtn8q4u z^Hl2VR4sHrd8m0uV+!5Wik+{U^vDlYK<pmaT#<gT^y&Fy9-8r6X^mgubXcHvKgV?H z$?K$)6jmzQ>9zpp4%8s;bBg5oM}h?hj?{4GoDK<4VBdewM|M%ch9{e2s)rI+a!0Tv z;IhI@60d%sJVK8yFs_$yJ~kicc&SIR#HLuA-puK1aB8F8q<^{Oz0cto$r<=&x+Jcg zpts(B<h;;EXa@xZ+9Mu^qweo^Q5bYxA{=yTBW|?rFMS*IZ==x8d)r<0i$VuOo?$x| z3}eysEjLt8<L1t@&RmEWZKsPm{&*L2=C9L2%F5=$@1GYx*E~U>-+R!?Q5ly}oFh%s zqYW_Xil}sev3SOAW7c3@1oCiD>93aDGxmtj$r`QFh)4251q77=l=*togA>&k1`hg) zPlzhlSkqAj_c{27cOLE@<|5B13KZX%P)b=JasWWhj(YWzyi~v8Q(yKq{?<4a8O*5p zH#HnwWfw`{l?d(*{e4)-Nj))U-+xjkCbvYWVA&z%f1s8ln|3iD+Yjm8gk;=&{0NmP z9ElhI^`u&*q~S_F&Y%(ylzwg2SXrh6Z&CH<))P+vk?6NN^x}!2c$fpc1i!g>Z^V0O z(E+@AN@Z8X@x=CpvIs>r<->RA3>SKNVg9mm2T*fREaZsaRKndpImVy_GH{twz+H5H z4mmAZ*S)(BBOHXQzw%MytE-9vWk0nZ?o4uBDda@BWr=RnCH_V(?|uuHF`?<cdk}0T zk+hLsHUOMYUulk^kiJhrKdILboJu(#x?S&kXNlGeBXwJzkn0(Js3Z{(im04`a&H{? zLnUj{86d=KaBq0Z0{2#O@6?-*`q{eQZdN_2?zABI)&pe4ck$=9gIs~-vOPSU3<bL5 zKTC#GSXbOG>~JGKQ$-^g+w~-S6A5D2`}UT@@}k_18H$vq5qr!2zII!Qq{WLd!Ee)i zQB8EZw=aXFl6+V!YJL81)a*R2p7*9_`xe5#2j?;$Mn}?Z#?5vgO#i562Mn=uExqRV zoj#JICjBA1^*+O8kjJ$t4NIz!6^a7|fslG~8SWoi59v0$f1$>h&ehOfp>EXq$Uk!V zVa_`X%(L*%yj)G93)|lbIhQYXD#1O946lxT*>hqTOi-+V7DZ+Bcvkp6nlZ3_Fvfi` zyZ3FT<t0}Yl_ICED);LhPA2PnQf%)XDG~X+JcKfTC-v|7m?L)9xtTIGD8T$V@Op;} zi&a+N!TsHm%E`zT*U;`#x-M!7P>TNtvcA#U>0!I`>Yq;O8e!)<2mLq<^IFmTqXE8* zZ?h)ja*vDN)utX*4p?e|bM7)CNcK+0p7|zy#)aPrhxxWuJTJ*T!C|VV-tQ6Bg>*1{ zFZiDA2zRN<x9UcxPJ{?F#4m=#yr0lq16a!}fOGV~O?PsW_qJET)3=qK>VT+)gCb#3 zBA11UCcjn2u6FLzpQ*NZaP?2KA9}UjxtSXF2bg5lj^W0CU3U*Sce>!cc8}dM1MZsW zta-BxPwHmQ2S5$8km~D3K4W-mhIw&9jz78?0h_dcdP+~MU4b7M!;l5<({}s7=C!d2 z^ey6z8$PWlL!X08O}e4<8w{6mgF*S2C;7mK(OC<0^oQQv(t?H;j@F24Spe`y#$XX< zy~GsiaB8^FW?m~C$aY0#3gsJBS%d|y?oT|U<M&B0hO=Iokw=&ytCT2@rk;W12SXqT zk`$o_RO&^yay!v~6n&JFJziVb`Wk(_*3Gc`Jtu}m)wnUJs0)wClvfgI@yEzLQ+U!7 znIDQc2&4dkIu7x0Ug{ZlC8^*zo>1P(j{+OZt+!dr{fIxd8Gad=>v~havc(r$!_SFM zJ`80H&fO9{ckH-b_V8h;KK&ew9HDj`_#5D0=K6uFN8<OKA7YflLtO%_5es-1Dm3k? zo3=8BVi<$dZyrAve)PCehwUxz_|gn9*BiBe)9(vTdGm3><~;_f@9yW|Jh$$Z?x)Lf z@Bl;NbGI)V=IzQ3oa29F575i?!mil0>CI(0))tQaQ=g<Va^+5EOhOk3hFSQ!&;Chb zujkO{@`b|OywJ+)-#^|gZ0Pg3ug0#djo5!&%=D_TzcHr$tyXKrC`rPu??&X)Qzzh` zetapzIY`AJpp&M_$?-JXP1u)5r5BD#{z31#F3KKabRKvc3oNIrk$hCP#hZ?OWSsBo z^{wzLaD7pJlyxULGW?2I-@y~dO>b3JG}ay^^1j-=nC+;DWyk7o!&Vbt30*uh>a4ww zq>2sYEs8jXc7roMtDN{lWSWD#y(}TI7<oEiO%D2(6?hSTKAU1Eu}a|;#QePWn%T7i z3=20GY|ia_o3tu&*xm!*s_*(YPwIhB&JS;C!E(iTJ^~xafb`Wgt0do17?XEKQzB~r zKpnH|?9HK11<ALFOvf=i?C1NFliqa_(-S$7#Mr2hptS}{+m#mcu@9ugY9G{#e@zES zsZx5_sHzLf6v;Xxl}$T;Jz(v1<I_9W6`$4*st8&?zPtc*?Xj!%bR)<SY#4-^q}W-H z7W$uqOr&HmY)IimtA>)Nx?$o|(%OKyy&s{jz3&Y?wUr0i+YhvUKWd*~9vjP3<JVEi zQXKxT{Ihj(*FQXPOKbCwa$*))sGlAOK_wM<hl4qVr29OkY*H;op8w&T>#L<%yt?FG z%gPSc0T>~S38^NP!OzFS-6V4A1G%)-k@D*!FH2l0IN7v@%BKb<W1L1j)4U+`_Wsm3 z#m5HWs_V+{K$jBxzZ}wJECuN)BjbQ?=Pi-COTn+>_Icz4GD?7pd~;RSS0(hrwqBe? z3v14TW^)%(%a2Y-)sIyDC%@S8*x0dJhkc@^OboQR%v~cba{bBkgIy6K;BX0ItX|3S zQ%7svuOufQX+G*KvAyv|hpT=(=NdoY8V3RjDX!^L`t*5K*EhmVCZ~4n5B473`TQ7C zsN4luu~g*~_p$IV<;A}Zsz@@N)l<*QYwCd?Gpn)c?Z@lQC2KN0x;xw!;&$aMyMicC zctBBzGMD#m?@p=bUf+=&V137_x}!NN`g@zdhx#CQ?gqG|=+>E}6*Gfh*cy(Ccuqd| z)_6&v>lxsqN`p$+WlY^ijj<C~AHSwX&I45>CD&>T4fm1rq2$h|Bd_YFq!`MWjgq@k z6Bk#b=!;Q4&oxF%Nm4^^K81AccQ~pJihg-?rJh8B*fp|Fd_KvJXc&!OW32o;J}FN7 zC+bpQ4VW=G^4`_tf4!?0{yCe4%ya&0%0uQ(-a=I1-Kajp^2%Hmkmj19dpif9$uRhg zT%G6L4(VrD0>lrr+#%2xUq4E;9{s$xcm$q+&=-OhO<qlYYfIO8qx-VS?{5tGV6KJw zXXypyt_>r_;J+=^&^cQZmCRk&DK+`4J*EtWukKz!R`E}Ns=6M2nT)14ua#D4wSMoe zP+5`|PNE9UFY)AF3cv9=qIcyvqT1)yn^BG)_vYTGXA$S`m_|ghx8LJ|p9%lz?ok%H zZ?d}MbiBi-ZZa9vpeainT$NkYHHcy=%CrHLboRK=om68iJf5I0ajJ_ySidk<SoTYA ztQ{nA3h0Ok*30x?W{XYBndW|b=6NYq?lYS<o%np?a?%_Bm;ZGpKSAM%ZshXLTl)|- z6O@fvG$0o4s=QmXD`Y-Db2PXA?%Q4owfEj9(j`C2P*xd;ur($s!%UfKaRtq|l)?gN z>D4aQV)nj}()Zl=9)5as*G10_3C$q|+%<10J2DW`lV7+277}sRGTjjatu0xPAHI)q zh|A*9u?^aZ!J9vISk;SJe@PxS3*T_gH{jLs?3pZIZY+8t5%hOyf4X~@X7Km|+5cd) zVkCynO<exwa>e1}lU{$j-OSy5gnn?j_wwl|2i26n4jJujVz?Y&H(D<HleUHVBG+;F zdLws<Q78tqrZoD#WL5RJ%Tx{f<HO=X<$BDb_v>Yox{;ach|brN6N`zzGU_`nO2PcU z(c45tf@RL9oqr{lBG$Ih;;c+rcvsXr^O)hq==97|f<`L?<Ns2xm^N8C739=*_?59R z1tjMrN^<4XxZ(=?s)LO_p)Tr<Jn9_xYNElrgEKFFB4dP8Whi&v>(Kg|F5&i?{pQ}C zSpA_a&$LZyD%4mtXnEkbTBni1Lso5>{5^W$JNuJih7Fr^awR$=>{>y|_luJ_YSZV$ z@zIAz#ol*w$S(o5%U{dZ2|2U!(8q_N-ZBO)Rc+G5teKJ-L+9Y~{3xB!_Sw&NKXuB^ z56asZNc_bEW$J@oB0kEZx}M4>n!1&em~(0U4T07L1zl-+mv5LIOF5x?SVpjNM?YsY z68k1j*{9X}Rnrro77E{T{aYA=PU{Zdcl!0y6De8#dRY3e5=XsHG{|(2LkVgexBG)7 zKP+FVajo`LkdozE_?4Grg^SWKE^F&bsh#pP<+iTE2x%J_wPr(+8Bc^SV_O^?<@n5= zgUU;=XDq)<yH{AA!HwR-DK|YCV-7halJgZY?&&&P=rc{EOUIQ<uCSry4#o=VnNL1< z(a)|YsV43H4EQlW6mK+lEt%kBn(^<-iV=Q(hB}7Jn2VMWsNDbc&d2IYA$F4THe5nv zy<I`cb<=Y4KVQN<d6aF$zQ3Qjq>GzWzHq>(n&}69rLq>Qn$>bQ#@XQa++3quqWROF zBSEBFnOCSsul*pj32l^Jco^l<)@NDXSMTY?r@lV>CxwjjOJBn>nyNI}s1v6DB{}NH z8)rtc9C5m;KsCS$y84>%_mCrjf5nt(^woKjX0v_Z#iW0rf;X)1vu1J3l!~WAwE)6( zIwNpfKGEm7QQ_$~ZTfUVLmIcb3=kJ#lQ;V9k6E<yw}0h6IthN*rnx8SPR4-lrI>2} zHWP*NmkV)~^_7fASrR@7@YMR-_1NVy@jtqO%-@|zn{G383lj$(K;z)ZHNJU}$JV_7 z_QyF*GQ4=NEHmKWMjPd>qGvq9lXay0v7*>g+OkEF-@l##VNIG*0YwU|SUm>!*4b9K zT51@znG!P~sCSKV!i8>MNwaR;R=4<YPJ+Vl14UQ%2GJ23H>`dK!?UTvl@?-Y!HS-1 zxZHO>o(E9(KAYOD+`NY~+rW*2cQh0tn#P3{IDrem9Bl2>9?!R{VKg!b=@=%`J_U^4 zk@YzmAAH-JHFBO5-MoE19y;d0QG8!YZ-2+}x~_1gH4F6;qpX}0iB)gR^_a@7((v;H z+tjEljv4U&gue4UO7q{|hqM=IZ)aX2xsf)?v<oy2>3i+%8luGK+xzd8RkYl0N|^i_ z^0FzoGr=I=Ta_QOoCRSG5aasl=g!wv({4WOO?G?fVvu0nyMt$pH0XUlKW=LZMuo&> z!7ll0D9G&}e(M035fS$eO7sm=l-SQu;gTDnGeBtnw@;3W^6@N?)c2VF<+5icD-&OS z&YNzRmBysvGP?7U35@vmqcb)00S3Dud$o$NF0|4w3)nb3AQW1tss53M?8}3YWphN) zJJ>f3!*-U(E49I!9)?jss4#Vk^IKgzr59z{B9|w-)Eusufma)*y-XHU&RclFhqQqr z8wsHXE7*JU2BV6RNt8R4)Hq1Zl9N(sh1uttq?P!KFnW0S&l*?t?7fGU{|8FE-O;>z zqG*}H1CoU&r$S#E$FHu8o9s)*&=r(-`S|2=&7T$#|40XKQ{qEWA%F1ZJioX=?`54d zRRy8lW4N#BYEFgyG{#6(>0g=sBlx>D^-QtTo*z}4j2&A*K&jFF%(8Fl@Vx|YR2r1_ z3)<H>w(~E*`#oZ+@Wjeko-^&-f_iu%;&OpM^ZlYk76`*c^;N#AuyoDuNBBH<hpLLp z;YZgD?W=B@s{E7wa5xFbUPs4QEcDfTT&8E-PLrqeuajp06nOcS_n%_>L>^vl6}{D( zEM@7mJry}Jls2%tPxslf#ut&qr?>7Oq}`(CQ_*yKd1>PjAa(Je-)b*cnnQ6BMQ<MB zU!<!)&E02sQ29vS6Q?SV5lu~NI%ii{GSX*RO3TnA>KZ#cH{?S+$|6pVX}g(w<QFlS z@g*%glW`_O@6OC`hWr`Zu9@w+=%uV3^#RXh3urgyZCe=XYpYf$@zw5Obx@>1^o`8} zNAg=0L43otgg-{i)$&H%sc-)S?TZ6#vr=+*fNk!r2r$4`0CXu)nj*}s{MmaX(7MUn z(B!mb$hjBiYTGTfsoQ#(E&Eyf7^vXpjx3tFW%y)Gd|?L<C^45SR_a4u_vGH^SOUrb z1p<`yF6vPP&S4XB5t>}0KGQEXyz7+V|MLdIE~$e2Qb$@8_fZ<aJ`R=K$}g9@31kY9 z8jprZD^lMV_ya063~QQs82rF2I`KhD+{d7WpC7dkqIO7cLZ_(NxGI<TIL9B5AP7S0 zt`I!eui#kZ2Ys8IP-S@_f`SBcCIQI-F!>VeXV7D>rtUn{wqRPQf&*SdxRe23maW1} zqWt#l(lwWyxB`%UI*C?b#{!zbJ$8Tf*57m&DOdvw5MN%8K@3aoR{K$QB&Q#4_W&8? zC@&#FvUBtJ3rG#JfKA0`TPf)63z+f^3;ka&6g@`U4LvC2$YO9L%+J?zyeQGnJmgZ` zkOu%$us@O(Y~R_VliM)ySC&FhP8lNg-RFB&Ijea18vg+3f2Yio9uk^CFvomkI(bbQ z5@PA7Ru6ktw0VU*Ik*Fe5ikf(BZEdqe8IWodN5-(PuMk<v<$c_;P>0HH3hcRIHl<D zkr&#uEMR#f0T5YtNwzRJnvN)$T3&kbxC5@M6p|-;z~-8+ZwpmDXR%iP=zS-z=YP90 zfZ9pIJ+eQ}g;52POv+n?LJgyH(qBCfG1x*za=Sr(&w4>>nmRM@4QEnlH$c7-RU%<r zK`|YR!QvbrrcC(~nW(3jf-f0tGNB#VG5}0oZK}TonpX&gD8*v_L}E*De50H^RC%FV zo^JO!AC+lgPElT-h`Us$>|cK^sQJ5;np0y2qER=}QyDW@Qw3Ck@pa9ndIW&tEC3w_ z2*jRa{l(4eyh0&SS!Zd@V2Tu0MD<Uw%*ryA*BAW=grR>Gbq%K$m@%ez|0Cl0k~0)$ zSTT%#zE!BD%Wi1i6s&HSiT$tP>&u4MC$W}X8x5jleTQ}(gQr54`ul;P+eufXJ4PPl zp}@FAwA!D*R|uXGZQq6S6z1;{jxxZH>Fh1y=K9z3V)!}>fJq_0uqiW=l%EzW3Om;} z|M#G5|I`OjmA%c9F$4G6R>FxFWvZf_wLokc-WJIwphy|7Hfz8u<QHE#Z<0b^poDA< z7;W}|nW*x27YU{j4Ndj@i$UH&KzYCD=^WGYY;*zU{aJz%&~UvpO7K8zhesONkrTQh z5X0O_LsC%TYVtYo5Rxu6aPpiS9EAJ3luL4ECCduRh^zhw2Rs@;YV8<E#T?gIF5PG5 zo~ugH<Ry(-izxrlcD`p#3g|cs1IaZah&AtF9pT_D`%(bZDWhAA0i;3Q|IK1l1`(cm zOIa+`%*Fi7l3!GSDE&u``z_WE^^R7znGJrgEJ5rCWOdfLY>I?4P<}O+4`jiea}q|# zNP7HqbuedoZsGDwmpr{)-ENJ?8BFvLBYuC3x?vsv4|7cMF}{a<5cqxQ`!t7vEw|;f z#Whx3P9}$9iwj`UzO~`V9HHc<qi#s@j)`A^Xk4|6#cB_ULpG_&(~OY49XP9r*|i&; zhq?^Cq9JF1)!~Jd9{&(+@IU|_i0@c%nia4xd}t7(TJ{_LtUo%n6a42O+?C5UH*JG< z>d>}lv%s{U$%5uYiJ8qv0D2A-;dhtzWWSE<CpY~<zc|}2UuK`thV?pJo8hP(M+ITv zA-m}s@&j5jtNZd<06bpEJK5AVhH8u^14%ym_{}1txWorK`|;ta*id;?hWSCsjZHc~ zcm_Y;3#rz;4OJ=wA!PfFnr+N_Fn)`Rb8E6Q_uU!GZV@$Xl*RC`m)k9Mp1@Xk2$}m( z6*R(_x*{y$%c8qnsXQWCQWY?4+Yjj<3N9J8d*uNSfO^m5amru?gtMgr_7aG)OxeX{ zWXdFU3_dhW#rfj0Mb7IUS%ltYc1G{m?J7`B+u<p!<-)Wo<Gn%?p)qu8LF2~*pX7qo z_%g<(>;TjC1;HEFTK}--cF=Y(Ko88FGW=vQ8nk6qb86+^q<6GuDn))@V$zVAjJ=ok z*05I&X1NM}y`;c-@MVf?Klfsm+#kqE``lG}9u#*D+|G?Ph+b<b7Ow70C|9Ng%|<@` zS808ow7lsmP#fAkU}IA4$0h7t)%*hnMUHPrMt_MPWrcv_npuO8JjSLiq3v6Xr(;0a z47V>`TCZo%9}}k*fhyQm#K`Fxhzu%_c-1W5!LMAH)n=Xk+L@avy+=5ixVe8vE%%f# z+y|prkrfH(aV|8oM)zq!omLktwucy;+&O@Ywntua6Z{RMMawXfpPEU^$8g8V@Zgn$ ze@Ge3CgEOv$afN_mm~DD<F=7P`;?9>b!d)Nr8ZRF&M3rUBTF@9CEnv7(erecK5J?- zygh!t%#c^>XrDE{w!9fs6qqWi8-1|)EEL~IhOL|LEb{3}r0=Vc_o(O8Yg<5(%G?vL z=9;yi{MuOtfV<zEqD^;T=sX@Er6G~^)p|71v8ov6b2?_BH+rq4;L#mOMl*7FA=m3H z&Pq1GzFJ9!uqVqoqMirXl>WS``I5z!0J1Hcwi(r`%7uNPwy2uoHXULM4>k5bkdoEi zQ)i_?F)&b&zzc698k~dP4J+uGM*;`^pTYp;<64&IUFZ-1BN^A9B}MYbCh6`?%7j4Q zH~TS0Ub`I18!9IcEsUfcb&bg_It}8ix<xiq&6c<?DCBe6s4U{dk?bn5AY}HII0ZNQ z>Yq&N_yB0*PG_6|vHX()U$BtU9NGamH~flOoP(Oe62I^1-qoUIN-h^TlW%p^lfP<_ zeA=Y+x9z-j0S;YxnFY3(4$rAw>hT<E<|inrVHR@Q$OnuSgEN}x9c_3ith&~<WrhPN z63D8Qr-r14f(d>tMgQmM+~b+-|37}sWRfOD&DZ7-<y3O$)*NP|JLHzLbdW<+IyenE zABIp`8=+J)3XKj9MMyH#=1?XSnZq=ir8&-N4)^c6fB$<t>~U?M&-FgMUeDJxn-)!O z&gN%6jD8LXt5;GQat~*LIB1uRPJ?Dc$pF)}gw2d53t5t4C+PuZo?OW9eJboMEJ7wv zU4e`p8R<5#lI)SYgz+NUTJ_bMx@Ro(lM3I*;XzjGMTDf9UxVZ_t4s`X*Cp@;^Qj9@ zH%CWP!BzX07Ug;_w|Z8<@;jxsp+<~mS*VO135KcKd*kp~FPM|e7?dH%P{qNgT0SgB zpx(h-pRPG=i^fP9uJLN^y8-2%jrRnm?qBA(q33qIJ`w@EeO7kw$j&N=obMAjgcOiX z{7I>xcs179dZV$<pUTC9Y%5HeTrw%l96neClWiU~U!6#0p&H%L8k0dkkR(uaW0|L} zoUSo$Ju|9YB;rxwc`CgMpb=?M1ZLd8Uf&&*{AFOK+WT<fUaZuhG>TvY$TVj_m6o62 z0(Z8g8<K5R24`_HlgUFH@y+~9>oX?Dv=22V!1iZV&dbVfVZg1v+nKwh=Kv1|?JK=3 zQ9ytGIt$h%COB%wkL=LHLwku*i9U`^a%&1-YYVUHf)bYeBIwLayIMeU-}EW-xA#H` zWb>b?H@$64#NeLsDB&)>4*e(T6@b=utG04W9(a}{7Jc7Ilyc7@-9W`99&P$2r|gms zB<b!mWq9l$8eqU$O9T+dQ#MK<b##?sH*#dn)!BQ|7TFz$vU(tI%}%wDJ}I!5(BbYZ zA-#=V{zX)A{F4n@cOrS>K8;SpV9&_#I$A>WD}8f+ULR+UZrg3r(U|0HJ4gAgEup4q z>ejDvyC*^SR4J>|c3~nmF0u%6&-U<t@z4D_H}!n$Mv(Af86Z5=!0`_aMj(qao}DKh zNi3va^HzMf(I8Gf*+(CR>5+}-&p@8-CFN@gU<3*(E{WDJVPzi8&$67cy{5>F<7L^z zXmI{Z>C*6pM3S_Fu}5No%O=%oL1;b-t8T+!{Zc0bpqD7tt@#d=;>WVLx(9`dz|k;K zp4_Wk1|mbvV-uzBz9KD|S_G&Tz#_K~S<8bT^3@ROZ+1hBX2Psf#T7seo{!jSE<Fl_ zIqr)DL}+?a6xk+5AWkrI1sV~}YAQI9cpeAw^eT5tC7V0DPk?eVmKuI+{+TWl8DBIG zhoRXZcDS5#T<ruJF(H!1s>TB0#puCKvl|vc|7o83lotO!<J^K%6Y=Ux<Vi7(Cdkdt z0bsJmHVGpMZp5E(P=y~)@A7TnCR0Lu=ym6!FAbW7H#Vctuz|Uj5@j1@3x9(RBLfU! z)m3;&P!psT4C@;h01?y`itg$o4K}mKIdd$~;CQ7qhqhhDks!kI6;eq7s3f_rT3s?^ zz1h$rlASaK3XIXRZQIBCLi#vExqA^-eVX9{&Yajy^2CqhV5(_s5RyQ?YPyA~fb2+{ z9!p*Vm9+peYImr?@Rm=y_WDbRCM7siCp5AuP@WBf=>sYDZaqmi>Y0R3fOSJe%OM*( zfOoe>(mJ$$?Sq?W)^$mPcJm&l942WjODfE>aRgECmq+SRi*+21sI<eUF`GPQuP9OG zjcX57v0I@l1{e9yOb=cp?txl9M=Ok4^XouQA;huU{xz3UpP*BZ(8_Z18wL+H6b&OQ zZ~UU-Seo*EnNl`xs%<@yqM|gJvSz1XZ3vi6VXj++p6wf=nxf4O%!H~B6!b?{L+JIN zbdXY7x@JM3zHTS~e(M~@jMkb5gM647Wi5$aQs~uf{y;RMv}605V2=;W=A<5p@Lb-9 zI8eVg?ZT4GdGkvNxeLtAc^t}}IphvtV4~6)_pm{18gL9rG}8rpbctV7Imj}vA1ZK! zyWd7@8@z;7=s>rbdp>FDHvI%BM|;WTPTKZ^#xNrz*e}A^#=O1tF$98XSlE-G<79d$ zc2_i-aTMsGe-5nJ5sDp|N^;EguiJ4`G-L?+A+uNAs?)i`!vnO<`enhX)0dUcU)}@k zGL?*7z+k|R&2X`BtFDf}>Ncl5+0wG*-TIVu!g7^o3fs_0iYT+FVwIU<45z_<<mf(R z7=#7m3_UJ<Z(JA6s$O2E!?#1hH7q6k6jHtqEHKx4E+4JaLgE2Jk4WHXW3~PPV2;M( zzh@x#-_RmO{AX#((plR)BP-7uDFXb69+-5+deu_IMT0Q|+3jdPhvLJ$@1#>_^cGmN zeU@N2m00t{Cvu-DhavcXv&4AR(h!cT(!Y}>S>ZIF6m@kY?TFH_abGii+}0Y$LrF#R zD#wL5z>D@VAO*cq_S;Nq_+%S0=##pvP3ZYP8i@5S-po$1bz+qjNeWg%6P%jYz~Faf z*hn`P8|$j1u-7G(X|>FDioNP`&pdemy#XS<cS;(l!L6`Is>C2K7{7x(g5V1r*D`75 zJhFi;`shsw>2`DbKPa;sMX<LmDmX0*xg<~y`#3{#5rKvdrF7NeOj|eT^ghb9U6zh9 z(5%=SMUpLQDKY4^cfbjA`G7Q*shD4(ZT`W9w1DG6KnrP%rm?VvfnE|MgXh)ncALqp z)huVRq}`>l4AoS|kDPtaxRf7iBHkpNEX=JN5ihoY9*u$Z+u8Nx`YA*3Nzo$$Q$?sX z#76lbH#<#jXFcD-KSJno=}osB$`JIxDIn)*pRw$})S2!x+=3GMKGmK+)ViXOQT|Xt z9|7)OTd?*(DqkbU`7xT+TsZ(bS_+=S!w4&}0Ruy{JM7t55@3$6)&FN_gGPuNudliY z@ZUSav>7$eW{925@K-knH3LXFgCGH32o0Sj?yKwjUU*+F<p-;amJ9SgX_AAg(b7{h z5TYq_SE_>hOogd1^R$|9gt(6k(^?Q_0zPY(n~o(#Wq;B_OYW>!DPX}e9p-Q?Yp;{? z5HRWDEF0TIvmR)cUkW8>C%XvR;~pT3lzSjo1HxnF26|~ffNt)>RsjtE=~#%lRSSm= zCJ_?lU&Cf?@ETVTU5S<%y$=wAo_NNQ?W;0ynKXQzrYQ^vppO@J65*jzbCy0%fl228 zmp8%Rka`4)V=dh1ZetEvY8W_SXQQCQQkskwfHsd|lh_F$lrRX!@_p7<bWar8I*8qf z;aN=*pfdevDkhS*8k(SEUpC5uBD~hY@11)eN+oa8hy0dPDbR^5pkIy&wlOeOJTe+= zGy1Sd+71Y)kV={@6xe(J-JwE^Zz>NnxhLna4WZ`01fD?6cMS~8oE%!!(O8Is?v_*4 zLT&kCTS-AHEEq;`CIFjVIzwnnd<gcE>~W8a`;?R{D1pvr!kk=~+dr9;spN;SWH34^ zwINwFELR6wCeh|^lC#&`&f@SYkyOwu3K5kX@GUM8S^|A9XDdtk-gA_)+fpAQDie!S zNulT|>?;_}jMjPO!ZX8k$%yXIeLWXxCX;90Lcq8iTasU1RdEB@myU;i-1)c;9QoM6 zpobS1S#!zODM%IKF5H%ic_u)i6i|+^JBOi#i<voLCQ4Dk7`7Jl1IAICKN|`NsIgSu zpxc?0<Ay_FPCapn?m#0>vhE3wbM)~)ipV1lTkf)ZZM+9Jz|rjE4f6&x8ztsSXhS~E zs{UCQsoE1-VAU@7RlN&0uenOiKCmFsM5&gS87=1l9YG_Caxp<0B1K4Ja^bKw(X)+~ zx4UKhb$I=uS8*5Wz0n+T->tPm?8q8e4UP6glu^Z3gG!L#O0QHcp^t352<gq;SwhuE z2jT}xcO(~{_+8IO-363w2z?sCatQIdYc>L{Ol+TBn4i*lk=;E!Pd42UM60CIFiGv8 z6>g8(WOBz8Yy=#JK*P69Y+cZSc;R7-pY)}^@RPH4T_!?^p@aqksW+8@Fcoeb{e{(i z0a;iui2ao{qtqcOOHBZSzJOu<NNSc@)E5{qk<}m^5YYicYN5*@Ve^FY>+LWYv^fck zMKf37VT^^R+IeGjWpoJ{K3ehyCb8N6I4Lj^fD8<S{>w?1z8AX?0YxRQ7ot9x6h5d6 zak`fH9jLxQC;#9VX>f+}ae)5{nzfpg2B38U^<iG})3dDJ2Zxl=vYY8>@G3v!W;0{t zVaMWvw#O@{J-VRDt0eq1PEIolsV5s3&^MG^4^Q-VG>5FZC7w{#88&1_Z<LvP>b>_3 zZy&+IcQoWh?UkevT7KroUb4m5nu?cZbh;g*f)PxKGNyTAE~7ZLKVf(U1gE&~T-2Qa z3k{l1!!S{HVnxs${RG%%>*sh0@HgDijhg_!RYQ^(RHV7%(=e=6cTy3l%3^0R1~%!i zUK}Zr0v=`Tt!*gKc`A0cv0ZiH`~oSGGW9ZJTh9U0Kz}ffPkRk$QTl&N6cOJ0B{jYD z_XS6YFHB{msSHr797FpFKtCr7ItgZJs)!zTORGlXL;5n&4D)n_@GS|Vf&tQi3%;PG zV30S-V^wtjiUEvF!dP(s*J=a9?0$T69caODG-A;T({-YE)RVB*Cy+$vKTP9Ch;bs@ z8m-a~G%csV6E8HhAW#X_Rx)Sa%E1N@m^q99U~p6DXx{z@d>|M)2Q3o{a8mP>TpC;& zLs@lhfNCtD=6eek3$v&y(#zt$EY!&BXkZz9Y7UF-ux5<*h3B6jAxEHT!X+@4m57rb zHo-L8XZe<~CCenit_|e72x;%}D!IccKEGV5pi9fp?*)C=eapPx6Y5X|$B{ZMy+Qnc zx_+FrTteF~^vEEO-lve-D2wDm`Zwj)vG$g;9W641I?ANIk<^(e9;W&?*mj>sTkw#e zK|oY8F(*OsZA=l<`s=}UJKJRd`}Jy?N3q_(mG&V6^nb-J!~(xNxSP8VJa@Xj+?dqa zaB?&@<J!KIdZ@%-Vp(z0UC9X{mrwr}@amDEnPh)`Cx!}aw!_H#z$U%c(EjyAC}gdf z-GqYqZGI(>)<D$x6C1YB%n(Vf`*3@n7CCOy@E^{#_%?Dvvy62jzB`)zq)1XL#JdQu zF;HvwRjAYzKO84>Gqgct(kD1$Y(qCu&ZTco1HAaC62czeL@+cHOg&R&gNY>UU_rr$ zA6R~-ySeHio8evCl|T_Ta0LN_qFt4Ta#QdV@go_&u*$c(1{Iz#Xs|)-womrBkcSPD zzGYK{FTk;@t|esZ9QxBiSm*mRJV{Jo(BBSkmu}mOjDV@64pF6`K@<0#M<1U6{?5?Q z#TXc}O0`w@>tKwqJ_1*hs9n6|Y?i`TB7_NZxPdOiVUrh4j%i_!*q=Zjg6Po*)NE1F z3;ZBnl@b`|vU27v49lM{0c<;6&<AWkUp+Y-J#j+>+W61q%oJ%Gg_9CM^Z{o$!YWzp ze8s`&#o{hBqMaUQ^xQbh(z`HEU2QTyVLZh=&W&su{62^Unv$cPb85o3zMZHc5|U|# znN<$?Y9g=rXF0(h$%t-<0_1$&S?thI2{{#Ybu5M~*Ts}Z5_%wlX}3VHs&>CRO*yOI zI+0JX(W<8kGMZOq09)O*)RZI{&q1guAOw>8D1K8qXKkEv(KxsrTZ?F!yO6b6P)PBW zvN6jB>jL&YJF5$<nH;eAb?SW+f2DbTe_igLTB{^buTvXu$&Nu@i-FQBm5^~BV@l^) zT4@#?w|*L~(QFmlS4`qmLdHj|58P?b^m@Igo|YOl{k_TQBcx&rH6pq^nD30~#+uEA zz!O%ygx#KE&#!NGet<Q2#aDl7N?0Zp4rKOHK9VM@SK0HQK6)SQJIGiYzr+p=D+XIw zz1AO5HMbnC;;9KUat^WLi%nz8x13&IA36?AUhlEY$Vzz8k`+VHAuPN>?qS*v3{3mP z-3NoaRh9FPj2gS>pF5*e0{i9nzimvZP^`rbf#_wV?84iy#06WX@--?PV~$5A=&s-G z&`bp&oYZWAVClK-H3{Af{cugfpLKrrn&(TxZLRh@s(^voTjS*4FmPyV?dtEHbVEsL z#{*L_4Gq>C6ECSu8R73&{ZJuC^}+WS_St)xu&*{|Jer}vDu3teKYy=fBgd=z6Lb!Q zR68N?3*5KLsf;N&`mf8(!`&BNgL)Z+q!<jveql5s1#fl8a)uj>V6X*Ow%xvb?|MXx zwa~r&aK|!q<7$(lft@6@Z_;b)y=&3JPk6)OR_dGt8LhCCT8J6eQq^`zNuUHL=0ZFt zPb>nayZs&$qo?~2Vh_qe&ATd`nXE*7zackBWkmN)C{B|UW&_7!?bD3pB`=+q+{a15 z2}wM<gY)H6@>*S^QAnZzz(AR9UR^+JT_iyRR$~)wNgnYTh|>p>$K4kaHp@NkUBbV) z%KYVPV?uG_X9BnK$#NQp??Lz&O6j%1gGd{Ce93OS_f|>d%kLq_Rx<4<4LtK`WU|{? zp9|-PQ^7zwQhE!+QUobJ@NVtP4!|q^W@;N!+#ho#w*$eUR-+h#f$E>>4K9n?BpM6I z6IoJKmM#wU{#v#rAArMT&nGvRvBy`P&t0<BQAk4^eG}}K1)!?gPiALyKi%Zy-}(>$ z1b0qQ36A|o*GG(IyFOgFXEF?BdTxkHYIEDd4gjk70S>*n7J5{&@1e_q@hrdODbTW6 zYW4Hx^($@hEpHZheQ)F95_EqH??=z1lxeASttMLZPQSkG=LrqtPby9KI7>ww%Q-)2 zb!Do#ahfKj5XInrLnv639=KT9tbxGB7VYY6*O2)r&y2>zZ7C9-oN1RyCL6Y}mWn=q zJ0Hl9IA|>rtb(&8f1jZ{+Ha2xXN9<{;bE1{l5y_)_U${rT=4a7qi2Yh%9^16v_k8z z89zcK=iFa1h)7lY62?pf+9T*aS5bP+F%G|W`XhhkP<=-hScCm4|8Y{`^ty8L-Y9iG zbpE;4nNcPAWm!LK-@=yWQfH+eoQjk9@^*iyUQdKZr9!2K`Ac&P`rw)DE&~eyqjS;c zL6|Hxh>Z+*q;LN&hA6=Zg3%pWDzv<ONf*1wfF0GhfG`{@aH|&8n6rX|`avfd!*N^@ zH|oWyiPCqv$G%W`U_;I;S3Kc!AV&%<)<+{F+2de`)Tdi6KkN2C?gW4#s?gtF<+E)@ z`k4?_?Jjkwrd)_)UO-3Z`%7q-`n2EY(JD>PqddvzWy`txJ3s_y2F-hBqlepH^IqQZ zp5?J)Bg&S`U%SmuYmqp@z10^aFY$9oi7;e<V&sLsD*c;G)s<^z_nM<s7xW&_D;Y5} zKWiT7yMpv<q&(BRUtS_t11{O;Uh%MU4cwS$&eohVHZQU2+98XlQVLWlm14!U6YFLT zcbJcM_@+DXFz6kbn-|_$A0}F4gJfHc!fBracem7MFO5N_lXfVoj{ghX?IQjix$wd1 zRF?HW3E@;va2LI8>*Rj6$JtQj^~PIJPWqRG+PQoXnaX>~yL0~5V!y;!WTE{kW!yTu z{QSp3kA)wO=KlhYhTd-L0hM6*!lU^_+vK;6y0ZoQz4YO>;26AUAouqFE?+2~@JkQz zHJ!pt55#-_m@|z;AtQhr4ECh==}cGDXZt*6B&gPMLZEbcuMhl5s9ry8prYJAj@s+M zdlS68%$oLrCH|Ptok!&!cr&q9BAi+E(3(e7HexUNQQ*Jd<aCZ0h#}z6y)q*yFbkHc zmRAM6a1uU?+m$26FO=G@wpXr29XZasRdv|Ic8-twkoO0?a<LOi&x6Jts+uk78w78a zlE?l^gM$+)Hs+oU@oE>u7nY^LylcV;uHwDV+~=yXkC-D&dl+$PFGAAVN##pn@6-7d zyCi>AxXlkqFB>aw+{x11#nnA-s~?YSsJ+W1?)!qf!x}lw<^Q!W^G@9#pQ0|+&eL`- z9sE*WnP3o^sMv-Y|4qIf$fo$R?pLl<NqZ5fd-~(31DT0m?RhQsU8IE4<2qXg(csWA zVONsO@-35(E{%v)C^h_3G)uVOB-*S$VrK*dJ96m#Zp__;zf^CloN!7j+{?+kr>Kp# zsyocGEaZ9q>@c6pv~#wo01Y_xg3PYI3$n^3ArGj#jhd}y|43awsoI&47MW#~ObK33 zK%?}2q_eXB!aKUD$RmO|Oaru#?HKE^YW=nYt`G`At3@(iem&%nX;>S+Msb;)KDXEC z7TtqA+Tj%!!Cq;4QE|J?c`8u<*BiaS$e+edao|wv_oiOW`bpa7Q}W8oe4?q}0HuB2 z%P`RX%v(P6s#fI(V}^+Fs`0Puag<!+8AQ<FnjHd#)ws~lHhEtCRnU^T)_A*fBJ~GF z^5UxziyXz%UH}?QLg_0#P!py}*p<BFpiR;(mDpv*ix&%qmn?#G>$i{t=MrS?UPU^| z-4A<N5E@Cdn--Gf0#Cn`x2P-Hlchj*mv1zMCWBt;4c&eJ0(K8($T80K-uuefu_JwX zLCPzP4`$Ncb|9(pzxc-|#fe?=CnhL)C2O}ew~+rEQnqq7Wa9-M>L)TsN+-XC?zrKr zOetz9`<YOG5~h_EJ{Y(Bvdf^>PT}pZuwq)%VxQm)q0FYWDv)$fDoJMSo8NHM(*<0& z8NX`d#qI--KkxS+ij~dg)Qy9tgv(7O=IZ;*Q+Eyy8JThkgO3D<W@x*=$~A%^-4G#5 z=}S07`tP00806f}2m)@tZSfgoyvd5CNc!^6D<j9wm&LLCtR(iN$B0F_WJlYkA!|+e z5A+WNvHMj@34zjEq3Jqm#<9H#y_b~cxpDm{^y|Y{iMDzTrbuL>Y7~7<s`{}0#M^)a z#}c@P%(28JqYeuPw<j$Z=tz${+Pke8+9A2zsAXoj!;b9y$=46AO?()&^)@X_$xmla z!KKhbq4N*x?`3g(>60oM8@gA$c<NRfT9VFCq5l5#aG*_32kl3*F%(C>TAfHARmI@e zGP>I;MqBIoH<fl<wP`cs{`c(+J^qr@=b}U?@@I{)$r1Im?hff3wJZbU)kMXdyPw)6 zvn&HuB1w45`sV|?(eKxtA#(s?3Ww032+rN>t~%d_L<(J+pHtVjlG3)7TyB+e#BQFC z`T3^TSVJl>Z918O5Uk2gp61#xRT07P*`F4)q;>_#yHbqfdr}NH&i=viG<t99NK2G; zg@I%|;Yo#S{)~2(!wn#!#N2B8;6#An`wO<t-Q$p)9@TThADc|Lif8BOmLsv5&os2c z<`@<GID_uaA9`GNNih5iUHT+mJ`J|^EJK;k_mz4%eE!kerETMd#u`Ig0Kyd3o;DP& zej|V5YjRDMa$T&)>_MGNCm|3gS;Gx*6VqD$fy$wI0Z(4P;Glpn&bx~a95Vn7rEksq z@zketWewP^%GjRd67p5`h;5#dA22pa_LaM1E-k-xSyvftB}%tkdHXz=C3sYEQ8w&- z9#SskT2FPhU%$rP^kZ7644z}-!fEb%N6EO?8I_n-R2g*t;qN(`Q$??jb<LRZhF-p8 zp6a!Gv1q6!&y>4%qpiY#KC5CbUpVc-8=fF-eq-~t6d<yPri8)gH?IS5lZ_AGVhohE zssz(yYM;g>%@qqkE-*@E@YxJ6I5fNkx=^%(M!0yPI+eAy^gK+@-*hdiZ0C=#CIjq~ zXHwb8U4G|jQqs_8pyCACXgIO(IR?`V@)|VU3JC*KN$hdYpD}*e{ZhO-hl|f~ZJ!4d z1r~7zuMjP2aADst2=C~;DS3ZDcaT-YU^;r%p$t#o-}d-$L1Up7olg;*mAB>*tlBLS z%q~}G=HMcOqB^?&5ZKU4d*J2_MZKCBX0_e~AG*!+OTQ=$qHr)ta`yLaAH_)D3<Ds9 z``ifZt*1`hBcKJdNc!Fht6HM8oEDma-qg{T%jMXd?^!}%pOngf_Bpag|G2DtYR!%1 zPkS_RM;_Gw(U^j;)(}O~?r%0;BeNW(%mTn`XW35jm>xM_^_8YGAzRdKnAw|dO+o<f z{t2+kI^H>@hs!#OO<m<9Z>La?!y0i@22D+d?xJZy?`ckIGl>$67GAjY(dF!)!B45} zCij)}n1(c74<WPbq;N>krr#g@aLtfK_q_tuU2VuamOW|Tm><MU+7-Jld;0LVFC#T) zYPaR<{I>MxY;|MIe76+K%jIfDagXPuWmxp_v1E}rGx^o`{ddBm@UJ8MRU`I%0zx)v zHjf6_w_8uWx%VExS*VPZ|21;ZL;8DrrGgg?=U3RK+FMifUH#qpGwQ>yb#KkB0=dxC zfw`Y={Ttpm+<Cui5TP+UPx7CG39O-A{%P5v?kP574>oBvStBvpXG6mba4WM@31ZLV zWt>)F?hb@zkkSZM9J`g*-uX)_<jAkUKinHyWl;L~Imkd#(1}B)9qJD>uKY1iFpntr zYfj%Co|Coj3L4DA`Nq`Y8U!QodJ9BzA`EpcN!zq7r-mN|`Z5$6q$vM>T}<L0kTL)X z0TOku<R|`C%W6roSm6(l^Vo%l&32jj>tki64z)NMHy8^Tpsum<Q=Ad{>G_L4KI22~ zKRHjM5feQwZ<hu;*!g;W;~F?^<b<o7wsIfYr0$)_dz%x&dCGt7f#!HL%Q2cyv2TAC zvDZBER*7HT%mxpuZvIBVYPLF`{jS`~Xzh}tT)mL8D0+#q`1>=>u6>yEc7B07&k@XK zj!53rwfw2yW7}y>c?S|SI^W0(MkO9@TbL!>KDd@{V0}c%k|<iLEOJ+^E(^&chWHxy z{Q7WX?pl3Agcd<f9c2pLxIUG8BjLb>v;M=6qtWY4*YCgmH8pw8$NYL*UR%MiuL_l4 zwM>V3uJP6$Z=UT?)m>zlBL2Shvh2Ui$&m?>n%uPt_RYP&^9KzQQ<ch;LJrN4ek)&& znR;%%3l?t2UT@avzv*j(o2F607=bkX3OeOM7P?&$zhF6{QxS$2Q2on<1BDK5ke*xM zl-962oVb0K;?p-&TrayHxlufJeUB*EkTdYeKTgA(@+H+V7hFQw7s*zP#U-Kz9Ha~| zKei`i-D=VLMTt{YohCdv2I(J47<#XF79<-bwA=Z5$e3(Lue~8<Gb}utqDu;EYmO6( zR|@rUvgoNq5Z5)g8AMQ)NY2mcKyPQwk>bKH)SpBS-X&uc%7>dH6xqBB1;ncwL!S8g zJPlZsmDg3Ax6!_6U22jv6E1~eRP;IIM4WijsO$8)Fl2G##asIEM_TF?<M$nMh+%`{ z?y->RO+A%vi;V0JR;Pq$7#ww~cD}X1J^xbUmmXe|&;xSf*!IOC_cOXK%T9!iP<oPR zI!_&6wB<Z)?-2%jnkO}lHd}qzbN##7={vG3vTa?pr-ZGQU)bK!JTg{yW1&~=u%7*a zGvAG#{}Tl><%=pW^(}QZ1buq-s{3Q;3*B;aud>!`wn{$Nv(Wq4<@wk%OS7ox+Ksan zV;8P+?v2RJ#E&A<*6FmHpuWV<`@oA)wsFEe(;aFqSsN3oA%UJQM?15g?|G<shku+? z*i`615LM{A@x9g@@-LfP-)F)q9Wzv)>8dLSUb$U-?~2V2WP2lITLyZX(-a>2{_9AW zvWBe6nS@b{p5ub;%{fMySHY`AStOor-%cudd5OBSct%WgG(5NK<n@q3Zcrgehw?vy z!x&RaW4$wWpDnxZKT<Qf#z6W*$Y_vadi~DpJMr@sPPwK31Sz2fj7o<$b@$I`q?}mz zb$f1}7+($uYMZ@d<DA`3Kl@htZp2I4axOc(MMwfcE(0UjZShC;-YNc2YvebHtA_T& z`GsJ-+<?!K4U@T#@4D$bU)wG^b{h8U7A85sYgbBta;C(AW<hTyP9P{y&c>;j)khC% zT)s(De-+0a9Z+spKFN91by0P!x%cHUhdL#p$8y;Oxd{-Gw}o+Vig<Jf(~RK8VcxtM z2wAy36;oyudh!o}_Duu0W!It>?s~=ly5|ezZfP)ZyT`C6>2AFG{P~Y#fic26u$#8~ zP5MZ04a_6XiBo^t-YV{USxPqIEbm3k;CL31Vo&}9(qE_F-M7%6$ZpqVDOY#=YP{lR z`n)5M?5Ku2pLXHN!i!%ipB3WxL@B3n&(k^wTm28cSX66YYeq&e1lD$!&OG*WQ6GK| zGByF+AL-KDGz$k3e3(m_`)kzd@lVVNQIr0}lWp@v;{j+DnD#KE|G%@N33q-uY>=qC zqd&zqf7}@y@|UQ+#BY-5A4pgPHNFc6lmY^@BCXbo0XUYe_%-8h-sgi|;)LgH%`47w zhj#uziIdD$5_W%mrBRy(Vs5OH^YMp88`r<QH@^1TY2k_9|MUzI%sHE50U}mu?94+I zt;-Hj$(wYmlwq<oZ)3Ui^a(4}{+i!=ht*`>hch;Hp?ZH$lrcd@58?dRw_Nw4{m|Uu zB0hq5<#&=rqGDRbh_n#ywT~JIt>!Qj=JcSh57LgD8u<9n1-kq_#O`Qih(PSwqr6dN z+3g;4^DZBpE)%yr7LO%ovUu2$Io{?O4SI#1fU`1mUbn)&+-riIY5_0M(|NFG(89oO z&i?@VV>pRSg0NzL{Y2MAK!06X_Jz~drq^VC%)Ni+B+X&{FQw!p!aT;UpWlZ)_vtq3 z=ONgz>JhpU+kWD&{W*}Q*||cLQ49k0FQBhu)DER32JX&C6}sAox5=&*rP4+V^NzQq zxk$}boT1)87fE@=FZUkls?88>-5hA&GB{AHbda=5#fB1WD;XNYl;)B1mR>%-n}c|F zmt%#%Q>=UrMn9fxxRkR^%1(oJQus*F7JSL=3H(*<`+e6{!sJsLP*q`iJ&AJF$KD=O zHkeM>Wwptb`B{JXpNYBsPec9dPpDd5NNSZ@h_|}>Kh=?himwlTpFR2NTHpzNdS7A9 zA-gRJ{lV?;V-jBT>Lwqp2G|b^!h=_L(?@@7juuXMj{FO#7DLD1SF}m!rTGnp=V9;v zUNyFjd{{BOt8tKz$u+rdrmX0OFY9~g*O=+C1yhZPe=mj?|Mh2Ywt}Qy5GSRS%vAsx zmh95#k+S`vEgdp$S9cWrSQdJZ0nx>`^NtlcEcRVlS`y0)=G4tSjF_)XKhV<tJz}#& zq(0#h49fi0HGYB}S|)Q&9TA#3=K%%r1&8N~@gF}ZX4SV&@3lL#1bj}G!jO%9u5UO< zt}-1^jZY~W16RO~j$giUV#>>L{~^64Eoh2OoO^F))yI=+vV;u_IVVTmzh>m>91Sz? z{k_||V{3rE@RAvA`$;MOy9a6Fq|8KYnU-o<W%`Z%7r&kVc2f1YPw0kI%>!ZA{`voL zq(9s=6pH?u*RNN+QNC~H?hn>@=4i%8Ise!P<UBc2y#Ah<n!VtwaLgjnV`a8&`=gMI z@0#}_yCUSq^&o4>K82%4bH2>OQlH^#Iwn$A(^N|nX6IfUo|}>NmB;k*H#^RFqJqee zY_AtI7uXcvEy7bDMIM7YIV9$$&L)^$tl!D1>q>T+r=iOcZ-;L@gQO|ny&|az4+D)L zV)s*xAAl_nUy3#Qd1W0En%#}P3EEdvjrL;m%aqfX>3i-GTnZm2gKEV(%WwN>3D0+# zmcwA2CcyX*qgst()q@{;VW<mD81_hC|AGAVqEqREw;^tqwyuFu5~Eke9Y~0cbzNpX zv#eoaJO!(91l+E|;BU&lp=RzS8%2aPp-b3k0Z5RQ3gSVh*IXl3Fisz?CVKE!twe(C zzPFh2B1Hs$8Ye>_n)B;a>Gm$kL>nm^<7vv|DFg!c3KKp32~dYv=@x;|Fe{j#CtyHe zFMS%sVEz~e<0Sz!xW8IjF2xxC(UF;75Pg!op*54t+0X_Ka}<@1zVw_HZ`HJkcNuQY zPoE}Q8!}`2%&4He?G5p2T77p6OMzi6jm*3bkK_{}3J+Ng&rE+0BH>sW;Er0g#gS{I zR6!yATvqlJ8kKewkA_jM0k@)*L(Rb__;{-w-Of@e>~YKI(V@Yhy;3)L^m(*eu$I^v zdOTDah2{-C4V?&dj;y02-O}y4qJ#pc-NiebWI#=a@Ik2B&SBYg{40Z;dkDZ&5>JiW z@;GP*CA7Eb2&WQLiUWzj62fw%OyZ!vBgDCW3S>~9VlaD(wsDik=IN-Sf>kst_IiBr zFWJaBC(t8ptZ{@IMn~|n1*clT9gBbkEutTT(pDKrJcm<MmY=rvE><ETsiO!|uM`Ys zT$PuwMq66{TzDB9&^&o+3ARco{7+)@#7PbRA=GplTxoe3YIK>Zkw=@JYqFKC-0JB5 zJ~mrPe1+#v@*JTlMx%V_lnJ?iU`HCBX4{v#vATgSf(2S=s|l6VV|aD{0_VY%q08j0 z9qB_bkmfA6ReMnV@cV%EmzGVYC8vW1z2fhXZ!RQdZMg&S53N+BoGVod`xKRi$@IHa z!^8cN!qL1B7e?}-*>%d%o7>EllfG?^H8D*=>E3By!%(_x46g!XhICyd7aAbv`^E&B zUdRbB+{NmX@v~UcRuZ__4bQb(h+*rR$%0Mdxm$0)NiLzcIn4*GUCbrj9n?a`fkaEQ zq#ejPJBxWxG7O9sP24TmJ}np+O>NBMa`C8UU5M|KACb*ZwrZGLzbC_coPjaz0O;Z5 z9zNxjP5p(kVy$X6P#BzFnm|5D5TSIWqV;Y4$oW22IJon8hFaAhK;ki}q9^gRg@om7 z6Wk`uJPJu!Ty@=TLe(FJ-~CoSM3hi?0Z2*k2q;zvGkci|WovFlWT?k-d6UcFD@5EM z0{x`~DiSXe|M&bwgS(=d_RbF8P{G|hbtHIf7?uU9!{=$y?Hg#;`1i-;NFi6muP?e{ zKs$dV3=Y1q6<82O@+jC6f?knQZq-9Fg0L29+nf93U%(Tb0w-DK?mZsbW*K@33G-lj zyaqEt)a0G`nn4RpX_o<tmssu^p8dZ0zU>GT=Cc44O%gh~BemHhKm_(2;ACJb97q{4 zKr7MH7W$=HoIm=KQ?tKl@MfxaWY=kdhtz_%Ef*Q}pRr+M?ki1dA3)xwd@GRLMjqp5 z`aEH%c0Q^H>MF60;PO6cu){->Z2B|Z=iPH7&lvzD#e$RJ?GuqI>5rZp;FQ{h;1AOB zgg4Gc3lyzr^l?Uu1ATWD?I8u!RlrK^|Ex^}WJPAPrhA{Lag#UBfP<UmUvDJ#yF*zB zQz-drVWX!Z?Us~rw@xqqGJi@640jY+j*4!XpsKfF=4@Rki$bgGzDUDvX+hmvm_z3E z&}8!XJuBfVp*P$8Xp-&*k*`$&t16EQxauKbutr=4v!`)wzZO~-?7V!J7^N1z+CME+ z(B0TP=skmf_B7JLRn5`OVc8S{DUwC61qW62YYUEU{Sn-GJBJ`zC~^VT{5>ahjj$NR zSLF+=tDX00Tw%jRs-?h@PGF&b+sgWvSrD?~6>3{%*@h{Hd-6RFNrjmOEp3#4^cN!k z1>RYqmo~uPk5YEc#vdCTRzGGc$x_!O*wi8g?L9i?H0>IqSGy;Y8=FnZ1?>XQP1c{> zZg*jhvMl!C;H1mAu|FiPXoY?sdlaACBTJg6I8C}#t&ziU=7gmwthhDnR`E9M`%03p z?0iq==k4%FdZ*DSHO`+DsXFek_TfUk`dpaZG#TWFs^Hbu!b-HAow+1Pw(yG%r{3m$ z?l>3_Xb(6o&#z>BA){3XFgl%K4G2V_3J=QZ%{S7xu*M%C@x*TRn!63_K=34(+TaX0 zp-;3=5Y6WMrgV>G?Scy#RQ>4bX;E=#o1c9Vaw2~8VT;hw=Rt6of?pWAMGU@D?pw$; zHkSKX^#s&^LQlMH=}w$lLTx@j{IXd2!|C;=`B|qfBOZWXfQscxw`m@k%T=9CDr}|X zR$>Na$tjPCmfSTWS8h>YV~Zp~*}Tmw+62=>!&~mHC8SC{CKe*F9iX(;{{3YknJGPs z+dV;GAg0NnvdH<9)0cJ^_CW8Wv&j7Zf{&qSP9M5tI5mxX%qtQ-E5N~9T>s7}+Li*o z6i9gU2L<m%<x(~<y<{*|x%QYTgXL{V>EkE>ipr7U)I9^M2_TZXqT6~QfnskBg8@<& z@?Y(E3S5NH({%e<QuYvWm%&H@9awbmh`(tuGh>FT5%RBGj1)(KDFcTX`idZQ+74YL zVKZ#$vf{2{ww|c)*yFZpt0_AqR<1KLE9n8OR{emLh6>1s1vm_?N!hdE|2^~n1)tg3 zvf#K+6Rtcbbi_65+K_CV2;}Gu@x|O(AbEjTwgTdk3qwP1@`8@?VaN%xdD(Jl`<hj| z>lodSb=(#}<{dI7!9lL4awD+ZB{9t3aY{2ow`kA3$S4)+rVa>Sk_u0yCZd}EC$+VG z$Rw5oN=<u-|AWdi?L}awpW#5JTbA_pMlD)Wsmd@^@Ecp84-15n$Bw8_djLQaI6s`A zBi+&>xksFEwIz?@l!(FR$sog9yr|jVk{HfVgNCkT23Mu9E7RMlYk?a^U_kpwE<dtu zeiGP$i8qvjL!TczVuLl=2AE&pQ%w%rjzDt3H?@l$XO#)V7?SXUjcVJSEA`9WwgU<a zk8RopQ(Ksp55Zy)xVal(+n5d;rZ@>cSuBJN^C(X?%$>(Z@zo6)T69c?gKI$a#Qhd- z*`}Vsp0L+5n!fiuIddD;C#&q+w8lb?Q_h*~kL6hqwvuE{A9A`6!`KGfPJ<f6$Ep1Q zLv~4vBgnj>{x9&}u0sP_!~>O@HlA1g?w0tSr-Ry(s4rP-r<J(ydM#+7calADrBz}a zT)D}G#mNgEnF)o3j!kB+5vQTQn4aLO#WHu3eifm1ED@$TU+Ca08CXI!6!E5Xq&qCc z2~x0Y7Y2tlJpG6pzCk;fpb)ufkwgULomZiS4^Re}X7Q3v$m5;;{sb_LBvaw%sdWTN z1*XO&xIDiHXei0pY0YE{a58OLp<BDKx*?sGC#Kop9~!+Pkz^CLZ|Jbp6Hj3E4GeqY zdL&ZL{GmYAat2*@{~hCfHq>)~_B1<RTi;5+m@V`v)oS0qjXAl+A6fnc=*Z88JRr&b z@2bV0?lb(#*d*9h^yNU&lx6O~h38=g+o70w9Mk}D2+lPWmG~`6PQ{Ys1TObId~cH5 zpzF12*l6(eFzJ|-2cU&4t!onji2t}Tj~quqm&QaVKWaeiZ1GxA8k1lOMi&vo=BtN3 z!!!=0n>#}(oy|v(qJM$w8#+&-^zGmB?zK3Y5!PIJ_Ysg=NcczBC#sHy_rPa<G4Igx zeb=(bUKuN`fekkqR`=>u_jp6P;R*;UuC<Bv&HhcVVu7U>x*hvnCCtD?WU;62TP!G# zu(-?NOga)H*>r(x1rBlHNmyh6v=5;=v6XvM=qnY*Dj21K9M~}rFJnkgs2nJY&P&M} zjxPyK*ev5Lq-%-+^b|-+Rf}(q4j6Qn&>5i;2LUl0lx-Qf7c{WKr?=PxkBlB$SuNCE zM8kSXvO%V2IvBpO{{uX>h1w!TsHP12YdIZizMEXwN-SaepFALCM4ST_ui4JpE_v*p zxL-th_v~(oMQU7<z115ahdPIWOlMy4$qhqfGcoINZvFRhi5D8{j?_(pXS-fDhY3Ll z3!Us;eI_B%)2k}Olu0n$#^BFMCTwyrLP1+yadCzD$@>TBl-ZwLqLI@HK46&>mS;P4 zCc<g_{;&5S!&YisFq0S#`y3m=n9)|%{<bF9v0}wl+t9&vhcndlF@~dgi0p;8faG{A zk3N3N6v0B7@J5M~NUyw3Qg#+Y1iDplFT?93=cK)9t?7D=*9qkH=%0_<sD_(kL9|VX z*cn+&IqmwMR$mm>;AI>#+XLlb&t;*C{WK5Soz|*)R<#B}h+0=va$(wIR^3h(s1M-v z!r)5KO`UCnF<2RI1w$^cTI^=$f|!tda0S#rg8#i?<R)h^JazMGy%%0m*uwHEoLhd< zdS6vd>C{U(1h0Bi=cNRZN-i{+0nzn6GSJ*u5@E%2k_l6#jDJ#XtF1CHf;~}?f6z)Y z;?9M)fQ-<ru=aYUnHa2yx4|6^=xEc48{mf{;U$x#gLOPFE9-{B-Qi>06PV1IMHwpZ zDjWZusB{mG8yTwu8*ohdXM?s$#HIFNs_MBD`X&S-gi8R|t)+*Xa2jX}d@6+ws<c|x z3IPSaMs_ku*10RaO&{IPBlpXq+RDIigb3lEtH!NqN}!AnOfk8vClN|a-^r>!%6ouW z_Yasv7v)*o;8;FBtts{DxHZDGRS{Ft;GRn>t*K$_%rg?uy)Og}s2C)%uSFw+X3%=G zf|Hboq0+->l$>gpg1q1PE6%1ZER0#?hPIkK_{(xM2Avz7)t#v<!BUAJ!)s#UBs4{P z2h8c`PR=A>;h`4~6}v33E19PiI=1E_{q}9*BcM>ahUK6@RAe1$3wh}D7UW+W)<~)q zyywQ(gRu)A4V5V#-UVhZE6F>+6M^a2a{r&S^`Dj&O}`90x$psaq|#-|Vs}{q6st_H zDoLU>fEM4_sJ2p;n5QK5p^NUPLM3U$0F5UueRQ5Z?m|i4X#yw(F^h|QRwXN8?|zW$ zlsFv0b<fYU8eRuw{tjYzzk=<-o*&1-6&$_?^krrSC;Ecyu0*W7eY2q!Ck4Gs-ze^a z&1P`n@8u?O@;Pae*#qV5#PpQ%nmlKav<Sv$b3K!@DjLk?Ua4#CAX)w+#UbyA_|MKQ z5&!;XqO@KgsN)r6y5hUH%Sss#Mhga%^TSMel3+HOfg&)0ENf?K8zTU$5kLL6EdrCS z9j=1L*fFI{SH!OW0?||*4FoFVoWgE<P%Z|<fo1pS%A|3Pog$&A1Pbsak65gW-R5Eq zSeWKkaw6X+yyquzmmIF14K4l4FsDW+X)t{CPxH+9I~A&H7Nj)*N=|6fh7_qGMrvpf z%>39;n(uk}EQz`I{)q~_Nq;>xD3vcN8J)N^xXWn-2;eLfNsbc{EzFs?O^{#9R7;pd zNi!^xb}DUaobk}Wl$-nu>_PoNh{1B7!LL(!92?h%LqIh!?Lx9>&eC@uF<QhgwRx4? zn35Q5CUFHa=zCoM7@U^-@B%9U!A+hX&Ar>KjSUBQRnWD_XK&&kjx<(c{_6*wq3IqC z;L+4Vi}AGvmqKq3l<`t&ZGz)+5A^zlSe)7B)m8@(*eW1%n)85zZWo0X+caQMx?|0k z<`f>9{#>FndZk^Gl#rx*l|!8*kW)ctOOYgJLo&Pv%7U)B>H{*2@C7jqBVd|bL_^Yr z^vb&9pCorSYj+tk31r|mMjIl*BNOKfdqQ=_i9lf^*|;CSA$nHD)6kHS=F>%=Y}_T4 zt<>LDj(}m0d*NJYkWVhqR@L$I@%_NPe?p59&?@ZKyKC`x)BRQ=$?y4K=jCkWiiU=m zqU4;-oF&q*q4Q%f`l{=Vpy%Lol(V>)<!=M5HFQf)ZxZY~Ps&%fvsE5q$8p>1tAHS0 zmh||Wjq+ns*!|ohMn|_fZ$l^4%mAC!TKEbZZf4>rL4(Ie{xNq3f#XK$(AjW?Y-~WS zHfLed5r&2$;r{}g*HGz>Hj>wj$08FF3(CXmKlC+UtAu6(z6{yOr#T=)Y)@aZYsH_W z7wsZM>%Rakmz{I5L1`k(*2&=_74J8IXy>XFIZM3W`tt#Y0OT(Jxk`sb-QWXwkxD-| z24jZj3s|epW-MA}tXKyOLM)T`i)n2$7B@f#neWLDg1NTda=uCJr67}s(H$**l!#(m zkz}*`DE5FKu+X_L>c+CDMB{@g>w}rw`UF3ZhcUve6YMxvYj9i5d13<WgEj<)i<OlH ze{L3JcN&9=Owj4dv*3Mj@)J-5wt$3LIVvd&oWy7yVM@%eMiwX6I{p*P?ty>+aVw%v z6${lY?k~I%|4}W=Sfurz`WdP}v%MV?Y8Fd4p3qAG1HA*`I*}Fgb%{=iPn^Izw*%N^ zqnzE7MD2k-R(_qYv4D&$E-Y}Cc-0;23!>z2<~et@@4N>KxfV#w8_FnWp^R~GbBbi- zRz$ygGJ^?&jSbPb#!GxP2<3hbHD!<yNWj6@NhVz1-P`$=Pw(E8<?e!o2u?}LJ%sQz zCV$d)C88j1poMSGJqRUxc-e>D``{Prvn?{th4?S%LgW%e3dPVJ-B6ekKN}|vjj*6K z5lAwY7YiB?Te;tcfJlT(Pn_7Tm3otB0R@p3s)tfjSKx*m)y-gCs~TS<o@fk)9sI47 zl#1?-jna6gdnHSS7mS_F>HDw6*`aEF66w3tqG18AnIdE_0@iuk8s$oD8K%fW$Bj+1 zi_`{9eKQeb1}ruG4r(b$!r^e^DPz_GUH$a%ixom)ZiL38XkU9%{<XJBZ2RL2@nB{( z+ztS2UjZ81Mj;kQur8vdvJ4Fw%i!&n#C1@pyfC+}Fjrg%GF0^Vp_)Q*+|nmte=2(b z99;c=a$I-9V7gC@h%G&qI(V0kupmW#(sltu+IgsE8Q`k&>mt5NF#^_`o6>k*L*uO} z%RcH$2h${b5g8$L@RhmG){fyN;~<((E+OYdFu|$z^{zU!fa*@6@>er_w(4rFzbvFV zTV4Zlf>CE=XLu_43YjFFa~Nb=XxnwqIOV;*&eyVzMe;wpior;V1t|zaAUyd-)ubnm zXsa+%y}{sxk!ktUV)vpVVZ&qd7_Kw)zyS~c#E)ewD&N$h(PyeUn-c1IYi^Ez0w+ML zh3(E-GaWV%D+8!%23bC2%>Fl?D;+Yd0VjyO>S=MG+W{LX99Pa~tJeIgOLjXjQRxMG z&iAcmIK+}4J|h_iF(sDS2(Vz#8Dx0LRye7C&$&FCQz1Q^)Jjx=snS8Z8$D1B+7Dh& zC5Z71<kFPw+E22Rsc<Y6CuMs>OOuA4h}^i+?MYB3Y{e`W7u0(ZE%C!YOIT=NJVP_$ zDDbskAy9q{)Wkbt+^JN2Grblo+u+`|ySUEjm9jKe9}YhWBdLZ=;-rSPN9rQY;e=U7 zQ<N9J9P=S{^znUYY(+Rz4pBN}dtxp2evuS4JEvWfu&J#U-}u3$9Xs;Le*JI1bYqT& z!Z+72n37TpwgP+~1#3la4{0RlqjVY=zYTv7S(XJxJI!?l7hrlMGRDcl_4R8T?qwsV zhfC0^qrgm5W59i9y5(q%Z+6YjVzL6E@0DrdR13S){KgkG=w~g{A>8^%^wx2(GppiC zg-VcV1!Zf;{qj;skUt+p^uwSh3X>ql3mmziNgDoDOa?zfazmbtQkX%EM*UVUgXJ3* zrj&sqkF&s(m<@Y_2DVCOT%yOpW5KKu#tBgiIMdPZDSaSGsDb|gTeX^<!#8<#6_%+a zR|!Q^-m^%s2ER!1Zxph?c2qW$FeZA*2<3eB-25tZ6p(HVMT=Bw*bmTK$Qy!HHx58p zpvuaDWzjZ|&%|m-v`gbEVahE0pVWE{gK262#i#V(pZMpH4oPH^y?d*$lgLn^{db!K zZdDsa5v);UlK3~~p;}Uu1zfb4oO92P8Rr)2E+yHFnP(LB;M`GkQx?~-w}8rJ^;3^1 zj5^;Wfmx$r+q4DA$*jcuA^@N6ozJc?oOYFhnPSg@u1%yoxyjJc`ytOf3@7*mph57O zm%PBy*|@!>+p^F;VB?KINY2yczCKbugsH}DUzBR+hw|qHYwoG|OVwkl=kA6RRcDX+ z{RTY-b$duWRF(N7;4aT||EUHKm*l=*VDWPM>|7C-JWAVI(g8L;OGC$qx+j!vQH|mr z$@Bk!P31Hd%nDd?YcsKR;7N+m<ym_Mnn8;0Xn&3$E{VafR>?1d<Im!k2Q?AOkAp4q zzDCy^+1MZE8vyc>TdQt7_U&ykSs)NiXN8{e7Yr>G7Q=v60%cs_Wi-rr@^fn+>C_FQ z^6_*hj45x;vzK#@$MB>uBLle+$bru^RKwoxGe@+WFu0!|N~`ri$~0;LZr`H8rQkEa zKkiR&>YKl_{D`t|$cu5~k-K<*B}|ax4GU5_^rA*6s9DHBGnSVsi<7SAXFM#SMQvB5 zJ7`aMvQ1vcxV$M`D!Kc9BRN)9eEGx5p`>@V9lv(0ynGQ6-#naMn;rIJmS*{oeJwS3 zqrxFZ)r$`%D~MiPdw5wH7)e2Ql7Fx&7oPXMRX4OHW!KU2Rq|)OTYl~OERh$Wt_rL$ z|1&#&&xhszj?CI~ufUl0m>_U{rg-+Gs*cjgV3yP{nJ+4TrG7iVTI&ig#L--ql31g3 zOFqw<DXn?;BQjz-b>n$T$zu-2m??!u8B=`DjpZMKuJcogXjP})>Pb>bulAbfYV$MQ z9EgWo*JZ=|>ea0io7ci#ngkG8rl{m;MwxB?3zFQ7Xr!+}DE4@K)>AJy)8iJ_AufsP zvFr24+n*PnYEvkW3GHhM*wz<s^yi!e1Jjgi-|qkAzUUt1_A8q;fJs)gajo;0?~^?q zA#;-D7;2!sYen*7J?JyHN*;Q8T20$A@&+)^s#EP!^ppFnF-#ym;7Kk^g4kG>YA0%4 zg%oW5h6XsG1U&)Q4uvfwdPnVH_K{({Ro6fWnQIUWq56x2YaX1Ko7YAI5D=V&pA*KM z_OK*m!~mqvG+z?-RsA1F=N`{w|Nrr8CKGZfYO<N4+o{{J*f7U3BxmU$(MaU5A?L%8 z4w}t5l^jAuQ8|aqaiWl^<TyqwhaBcSzQ61K{aud-u|C)5dcR+<=acpouuD!Kvc>hp z#$mBLQOf;|r<X@Y3zr%M{s}=G%3p;HqYYju$7vsJxWL;b1E7b0b-|<`bLX%4Jxs{X zyX4UV<lsOw%hk;CHx3>*JDW?szMbdWj*T@uN0tuN3+_ZqzNvP<wd9n&7EiVC__%FZ z5{3NL^%*q({%e3gAw|JQ8woOGmsUpYEk2*ny8SZYoRTCC5DLbsKf8bBs3hOQ;*BTD zBR}KM!FufE(59#mtR{QQVH7qTrbxGpGAL3%dLc5ebV<eH9d<A}k@zD!GiBS8XrOkQ z#&iv4FS4(wcmH1G)7s9yOY55NxZ{0H9Vcaa?_H;4Q!pi7I_ozHa}e=mTXJ=9=Gbj0 zRtdfhU@)E52o~47k)R8yJQ0#SPP)r>N`9%}g6pfDXVbm=4~gkm3-+b0X}q?HiXtxB z;O+p!5;cos*&)dHoD$z@BdMEXpMycchcuRkEFGyxAF_XRQ`a;iencGNkps_=bsUDl zzI{-9SEW>5EJ^=T=!&B6IGP@|;AXgO@(Vag&Y7_<;i=wgw??N4b)Dntx!skJSSXhy zBfn+FnFZyp7i7<+l?nNh2|VtBAgsQsXM-T;G`9NQuMM^TM&M1#8;hH+p)R<5Z-5au zh0Yf?MNlNRSj8-=#S6XqPgiW-TPirn-nRV}K@IO7J*c7Ui`jM#>@#U$ksUoWFgFzZ zv4P#Q&{%GzAyWLukFP$Cn@QVH*EXRTE9I}%PX)h9m6q}j|7p^9+zFa$IC{!$b@&$l zL0?*s95a4Um~cK&dtS2cq|;45_&q6oM`*1JK{K(tyrX?rb0aDX$3mVQ+43`fnS1VZ zF4t6f{ka{p+2$nqAL1_}qu869yqD|rWhM7P_H@;qj2nO9U2FzO8XYT{GIY_KEVz+Q zbz|R<{jU=+Ga-nzo+OPiRZ$e{9k~b6b>xjrTE(O2W7=FRl>gWFfU|HyEL37sq@}Tk z`4^6>J$d_z1Eu(85WTJ<VgE?7>L|3!OMS5_gFda?{pA1M1?#xS#|^ej#wB16&eLnO zsDn=F8f9_UlG@NNd``nn{v9OkgzVZ;;Rlp#g{j6zawkR2T3O)ONTAN=!qBe&h7)02 z{D<Vub5eV_$HhpKU5{3epA2fV+`||30>UvXqfR5aAIdyipLHV;7a7ZESL7FS$j`oi z(p=Mhr4!i$y6^I)UOib6yRo|D@}T{j+Af*^2x$j)g6fzXeE$PjKb>G16Qc5?w;Ht& zg6<=o$Dml_#7&X-P_6I}Ih$f7bU(DjugCjGG{Bb{QO?A1BD0L~V*GlgeyH3Tca*hv z_0&k1(}u$G6hPeAI+ad=rJZ5;?2xV)Ai|0EoylhV0)u#JobLpDp6-(KJ*ItAKV;!T z0r0lwTBTnSd4VGMO1W->20-UyN1epA<JYuvTO+S|B~6YX4mBsf=V|oZNO@Qr>mbBU zD-$MmjSMt>MCE?zwRmq3il4~as5rV;z=F~&+a%Y(gk0gFv8XckZ7wduY0|U(YV^?` z$VP6KK-ixsJ`7KlqsXNLPEyZvpMNuyj(dHzv)Szd!Bc+b`s+beOCe}iS(x25;=%i9 z`%ckie(62s?-V-K_L*7fH{Y9P2*3IGq1jj1PZ{3ubN2Z@;_ED-a6~w(w#c@6XvWk@ z5~a`!>;$n8&pvL-x~i)x5vy_dK@n@)>l~}&4=#AB4i`JP)tipuCFgL~E->)^J&~%N z>i)>gaa8Z^J$1$Tj==D99#7q$2H)Q{>NIof2NQay75)eKn?4V2QG}sJp>WhdgDc_U z=sd#5vecJy_QVr1vPn2%Fj=Dt9}V@Jo~7tUu#k$+Po}IWEr}5%Li?c0G*+U}#>V@D zSM|hEN{T3L_>OSKAm!$QW_1<$+?~dxI#4sp?$4R9_{H!`>CxqhEQIED$xl>BJo4Iz zcz$_Q=c##{uk&GZHbqC^+q;CE$(N6}euc2|-ttju#`kq2E>$aB$s$WE_N|H!2DJGJ zYsT(Ji4<97s#zR7QfBes6wb1QQ-Zf`#K|l^p}WGI!!LQHxTx6hNupcOOFGexy%*Jo zyZ;A-nT_i=sVDx(SuVfnFt$w=<_dJyJv!8ri3xFs(`ya{(eW6+yT>iXT+Dv?HcG1h ziV+E)^LYBqnMdCW<oaIG@l92XNT&DLR`*@}0z-2oyiVUrG&mdW*2Q8>jMsbCzdX5i z&b}xQm`zx>!9{=f{^~F5MufPadm@OGQAfRpGgo#?Xe<MZhC^R`2~ub$Jv;(m!Zmx- zf9zJK;8^i=tAa}wivee$GS15`7)jKslDS!3(v2XAmB0M(tyM?sFV<foSi?2<jQL@` zf#kI~K2Xz6`&wO<YIZ?i^uCl4Lg>FS@S89ZNRPNrQoa2uNr(8y`*No3nyP@cZU6Bm zz{{vw%G?!{4I1=S+nuWk97uZe<&CKmrcb{y96wN%W+Ui7(-`WTHHv1g%y%j+E|E`C zppqK*yFUcE)xMUbZxNIQe#3-EDB_ud6u|Z;SHJq)Go6ctR})5qQ`M*eDQSz@;G0Tr zsnNy-YNev;yOgxia)S(y)`4GoM?NgA?iSmU)Ied=MqyL^$7eS*4^*CT6(Ak-E1rQO z`foon^m5>%*(MjH<mluQ*|v?D?0Su-MoIV5C}>%Vh(*cj#oVzB;Kde<WDUy=k5ogY zf6cVbDb9{baIkd0aAXSTHi=%QT8$~|-@0NM8QBKK-ZyCD6b26y6{Zh6tr!dx#c6zv z(;#j>WI-#=zCV@qFM^68xoU1&=gseg+vj^YNZUgDS==b)tDR%xeFqE!%xsz?`Ux=> zpYMd!1PVsd5JEfQ|9!R3l9DwGZHlrP@D@7T=GaqDsf-%Vf(EY1Dyi|F%i_qykD{P4 zl0%LmoBN04HBzfUlV;UKINl2QQergvn7j$!C`+MPHf!VSe_{-Zy}zVtQ<xS8)TP?u zA0$=2zqMG3h`)7_@y2$tRhDgbZt0%7oou1cYki5!o9qsA-8a_LuVH98>0_`O>>O0< z=07RH$;K~+I!(jZMxJHV#hf7puDXgut|Ypq9QCiPJFV?uOip?`LbZ@hadB-IdS#-W z&*rp<Lr#`9ebMUHSO}*$xW*)0e%8T#B#tDBfgdCN?;@Gnrn7l|!e|)$tq3-ECM^fU z$rCbtcs?Oz6Z8y=Sa~^6RnB(xcw#p8Z&>6k6jD+sM^9vLOb5hdoKHTLc=mH|fZ4RG zCuK|lQVd!yTI>kwpMmHb3Ff|`En5cv812@})`FhdnaB=`UiQqp0?9r}@IGidlj1J( zQEf5?+$)umw1h4#Y-xz?{eYdS{5w*lSHM#GGx^g?Y4osndZnD*whye^5cy8?M{!ti z$s>W4!3wJ;umb<S=Y4!^1L8=Z^kCQ25rbZb(wrlRS|m0>HS3(~0m<G_q_<Q=QQ~g{ zb>xQ$HKq{A{fpOp^D$WKlN~pfrbi&Q>}P!KDhR)C(7~lk{Mq;);E_6je0NVnsrav2 zdmI{-5SCMtV_Koqn!h1^Og2tUlR9%1D8rvgkhQOrrwlEEbk~}_t|RC_A?0e04-l6! zpF|wZmpozo(e)FST5O~AJnVEOZsx=2!2m=Qqi)CM!2P>}&y>B)*2H6DliH)5Z)QfI z<uYE@cAdjWva<u%-_#AGuN*h2y~Fwqt7HCnG5T2ghf$+h0+`6lbl3Lbd<6oYq`YD5 zFBaO>Ik5O%8_gaIy+`Vd4^<`4qUYJyATp1RUl9W-Q<dQ&#S(oMpT$Wkb{fI4EyGbC zqpvGK{eHM7UY_t9RnvWdq2uW$i;Urq+Kq8j=M#U+JK)!R{ebmOLj#j5m)`LvpX0L$ z`AeHcDhI5NfAh6clR};Fkl!JK^RP2_eKmA-(Z3|DyNXiJce_2fNY55>^~@$ZS9d-+ zFctPeJCi1qT)*4&PEG5l2R_t)G3N)q{u@s=M+t*8*b92ux9GhLskvTcgq}rXO)-mx z(w6Uxs-HT@`#+&Rho8M&ROx#u`J8%!ZnSd=y>`pt<J*kR7fQpu4aZQ5vJ@T2)}?db zEC|{jl~o6@>Vtul^h2os4XoK_+)b%V35;t}ixK{m@$r?}x2x*3eIStj){Pr`L5&N8 zp;6P9#!@Ru`KzNV43OsfuHqI>`~r+(oLbi=HX>_4lDKtj717mBQiHjXbg8W+DBVSA z3)OByv|q@9b-K}4@AGZ4F+rdBfL;PX-wJ+{c&nqbyvs=_O~~Je)A9#<(VreKe|=g4 zr6nGqf1~Rs*0&Z_-<>xRXKD@zM>VNmKk(5n>0DyBFpSuR-3Lpw)N{-6FUQW{?&F*F zV=MdEH_p%8xagu$+9ivDLy^s@-rMo5hfa<sZ==ai<m=_B1D}!^ntMq;v)M}sAy@g= zo8XJN(^+?43H(3A4Ns3tH~w8E#@?q(Md##XSlE0^S8w!^-q>x{a=^zA?P)ss=kRxB zn;O3#spn&YGe<mnF|j}jP*14>$6HV^r_OkL%hsc{l4s4dz{^n}0q8}8Vn^Zh<>F1T z1>JoQR^G_B_ml@evZzX9aw>Tw;l(yTCK?4=NOPvo<rhj_o)sF?(uzW(y0gSinte{? z@3W#)y@L`S3d(@Gb`d*JJ{``O)*~6->Lf(zx(Y!j_@2t15d5tu7x{_1j(YGG2-8k9 zyz(r7&s|2CU?DarP2`rf-(_Afb4od~4AaBU9f+t%G`w9~dVlq4EL|@|9>F}m{KDg2 z@{$kYZ~;t?f_(sIx;x#HygXA*bh#?N+EdphfQ<0`@$u`aht)UEs7Tb*M9)V{XY}a8 zr<I_*mabx-JMQYZ-wM@gZ_C!?!L+c7--bBM1-8$gefi@{e0a};ZGyp*flA}QF;8aj z-=fg0<+m|nYgugyx)Q-92q1iy)hv<XTW|G422XVrA?|@agePXhjs&eus~5WD@Q9xU zUIaR_;GqZ1QzZ7=12h;qQ>mT}zi<)N$Nz6U*bbO?iT4cDefeI!gDb`BX3hqCeEq>4 z0gj`?r|OrUF@3yD%6w0A<LUW}+Yav*6D+^+k1mX@-9<B9Hzcl(-K=?f1u`btBZ~3& z3;l`<Jk@w{_2W6DR^GqVyxEcJTei<5VrI2d#0`1nf1gG^r7{rsXK@PcrS($pg!wVD zBhYHkk*bTwtK2nH!-=`ptqoBpJ2BTSV;?Tq5bKDGv4&C~`KUtX2d0;z9lHbqXdGLr zW#IL*MIS6JQ*zg7bdho^O}bU1gUaDwmddHY>Bc=tV*pwje34$yec*EJ$(0}ZHU8rz zcj+%*Bh{313Ky=QeZ7urG2kzM`s#mxk7ZWMO9yI*zf1Ehy!@xbp#C@FC!<YkAcXUF zw{CKvsw-$nt-&;u8Sfm`<$0>_>%`gFrt7`E@r9w4t8S|?LcwfX3<L+K=W$-0Jn{gk zIb4K37^l(Dti&&O|KDznXq#xa3HY0@#_W^E)02*2T%Akg4!e_W_d7K?6{;&6AD-QP z+|nd5g4i?lDuneI9M!YewAe~J+#`Fyc5e_&#UoZ0Z=81dyz#i8`f1(vlY4e!dv$D@ z#GJJLkMuvOombq&j=C$D24>GP(sE*y*6LVE1Gt3Gm!vk`SD&`<N++1@-RUouI@dDv zo?nPUTD)FoXDYy)F2@=?kvPOD^D3^*vK2k*{GO(~x(9S&|J-gl@%Vt)tI-6QESd#< z8}_$7$;zy1uBs<y{muO82at3n*Fg5inuk=GpLZpzb=j(~oYmc0(8I@OP(_z2$$bRA z{$R*vU>Cddj@FgKw}Ky^GBuZ{yhynF>FE2+KO1M^y&)Mbb2y6y@6WOse&M);#Y36T zHy)i-fBr;B8zDx5$qqF1C}b+k%(?q$L**#hKccG1y94m$n@ORxz8*T~?L*7V5BLL5 zU=$|xe}E&={7=yND@VzA3Q46cWA0k>Sz73;5bfnKlCM=P&}lyZjHB>U4V~#BMe4;l zOJiIze&_siGRkDr!`!xOte@(aaY~%4;a<DalzcDK?c{sO`NeI|q9|OMxGtWYfI!k_ z??~6JcSOD|w79wQDpxrqM?-V31CFkEeOJP^VMgrrP0g0wF@rIQvx1KnT!d{R4_~p` z6zWKfk29aczIWbf(BQ`V+}Rt=k$MjX;4byWUzu5^i7h!LM&f32KjQF1iCsxI|2=so z7BAeMr?<YoV2}}r3$*=0yO(;}Eg%dr`wD!DIv;tF$DFOL$U`RRFLWN(W65WG`b%=_ zB=|y1o|+wqWm44H?6l!zVf!Zd9wVs~Te%<Z)V;5vG@Q=P;0J*!n`LZT<V$|^urU*C z)I>Y3p^~Q5U9O{huWaqy`bZe5RB8~fz&&RY_&e!y)~_(-1(T8^6<0p#FOHQ#mKtMs zoYene>q!K(poO&3wusjz1T{XAFaj=1UtY^E&1~=At#(`zvksj9OBFryKR{^x;m^NH z1r^Nhi_y`yJ$U)9H!CBVIoT0WcR2nmvoR(z+Kfft!6@)A(%3h$uiA=s9zIeH4jA7C z+6>imbU+#FIA7X~onbGQI26v2_#1rN?qWy4w^#i{a%^m}a_gCL)r_YhD(il*=tB|z z=4+0<ebbO!`ubn8yD0J5pOZL~f+cEuxa`HG58lDL*+kki{Xlj{)X2&e{uP%MYUY6e z{leHSA*YsN!Bg2Sl%evxG|7cjMK<_%c2{hj_77k1O5EF0BWS4UMkxz4BQ8ApZ5ok4 z2WGQl*-r7gYUd?;b(YnXK9-EU3*zj2C)dt1MuVq5NKT`~@n#E4`Zu1^Za?}XE_{c1 z<FMlXcm`A`!;(1hHab4?GIdj6FLSJJ^JKHWo-zE+g0QhW9}pl;xZ^EM3wKJA+S6{S z*!y*oxbU`i$7#YqV9cIoOOLbYIZYx`$LoEfdG|AxMX0CvBh>?(_Uvdw$Zr5MMrrrw zq~61E(c$L1*Vbd6Z|C+%e70xeF3Ns_Dg~&G8MLOM?kir)z8M#htT|98cr5M5GjK_0 zpYuZh#cOO}pLZcGwv*30E$6&*mg~*esXC4jG5r^RWC+B8LJ#^tes8!9Z*#@Ki~I7y znz>dPaHgo0*X~ca3wZlYqBE5m9NM2f>VHR@A}JGu`N7M8gO53eE@|-Aj4n^v-cwT9 zw%-RiN58PTg!AXQdQpnkC@>RC8i4;vZ6$#t6~>N3jEYXquOj)CbuRd)ZZ6_r^PBV6 z)LK&fg-+0%qTxPbSpit2wiO{iRoyN4gniF81mt*h@rhnaz$L^~I==c$N=_6A<Io=! znZb=s2QFUh9o^ZrT^#AR;Q_Qoo7fL#Wc&Bi8-tcY#c2d}dQS(Sma4;H+teDy7!+Z5 zQnsdEGX3Bz-hMz^^$U?|ac4<V35`aqx2)&CU)S|26q?1z0wR_+(93{DvKf-}N)r%< z0`2Z8L-t)QazO~zK!LDLvL+?>(Z+fn-vS~z+GXr@S*@SbPhU)Ii}Ng09$5!gr5On6 z(V#ruV5u6_^V>$?#Yx~&n|sM=G$2Cf6w(bf%%&AUc=l@i!`{$soUx`M{}t0IhZ-Ze z3kkoSNHPB8GPx=;+10xc#H#hXed}N8Q6_>QViTpP(Z&yMX;h>6VEU~jc=%B{*O~<p zJIs!QrM?YX23dfuwA1fDsK=3{-(Z{BK2Ko5Wf`#`o3$N}T@4(OM>gp=;7^6Hq&|#> zhdVqs{-hhSq@H;GK)s%8WZnK>1gM4ME9cpySEI(1TUe4Hwt35*Dv*#~q9-&Mxdhg) zHsPSp9mot5Jko#}7Fmw(|8H3{aM$Pc=Q)9uMMjOnwlRs%sAV=sCmc*fX=CQo`@Tfc z<^sV&%EIaL;@O>GPKTy$&Hd}2o`)iWr3bU6!-Zzi^cz<%QhMl25$ouTEU1R4b+gqA zuK>YR^-iAJBJD#nZVwF@^A}RvXE6Xi?|%S#BacrM?hA#LpgYei>N;zwnI7a~m8|qv zfv^^IOJ8k~0Q@r<)GHDi!}k<;ioYhqXZI@hYm0;k2~TDKVonSqxJX6|E-WQOnV7bh z3hr%I(Z4IBJu|YL2U~S`03lMCtTXX4py}!Wk^4H{n;9oTLP$q7D_Jhmf7bf@gxf$n zr=&u7-Djn@rc%;pi~tqu9yZ;=GYezokPIw@Z-}?O_*0zc7vU)m$hs@Sa>nWGL;@m} zk0)tp|1_8q(jOc@HlvrYO@daqf+ck;TsP8ut}z5WQDbrxAhS||$prPq#T`3Qt=W_Y zYPu)5)zu(<X(s{foY`2~zC)t>r7M?(t@`;#;weOsA=h8Bl9X>Gpj*3Zg2XE32Ic6u zvWl&q(%mc&l{}$L_X_Lh)&F3a{w=*=_2ZSP!s%eX)h~gq;7mjq{J8#cB%q-nt?YT7 zA9_}{*vfpj>Wiqza;~-IilJaar)F(7Ub2_S7%0Tp9q}8`Nn^8fG7fjYUlJGzLx_Q# zWJQ~#$7_dmrd?fwyEgI;R#FUUYzk|6-+>%D3&PQ6hpAa=k}!XR*!}cel63ZpA<s0S z6g|DTo+p72;^QD;#gj(hHV<G)N)HYk<2}iW)+Igz&{F2$yZGHDkdR-h5#|Vs(XEA$ zA^o1U14TWadsiUupwdsJ$HE;hW-ptL`a(jX(yf({dl{pX7a-XzlIC!JUpHW!Cxi%s z&#u0<071?7?K`o5)TCtnLKncgqQbvE|42H3@f!ppNIHG0-AvdN17!TcVl^$%h>B6k z=^*%2n*0(=$#5z*HEAY71w`LUPgvTO156GwD#n6LyuZH!%2O>uX=u#;97lT8hG!iL zN5W%H+l=2>;c3Ci`kSzEUH0(p{UtL_$!EKRoCW@A>Kb^aZ7+w(B0mbPqY^L=X<Y~7 zAcAx()hgRw;yJ*K>gNmNHrVi=KP(J#z}rQ9?t;hfAG6`>?=I;_eLWkC1OPk`>?7<o zA}tDGWe3J-<$R@DuXU)ETz{xe_Gl7Dv$%<Xmur36jDK_%z1GMAuM~abUwvn30`9+5 zt?<BQg3ggn1+kaOg$h{1PU~jmyc!~MpafJE9#*GUU=z+EpU+4I(j${$=egKQ3yWkS zoP6CJAC8qhm}Nh60`;e5Y$60K)bvA7bUKB6B@>&e(~1FKO7j*!)AK=s!9`<JVPkLt z;%3I#cva$YeF*Ajs^3)kqw>r#nNKVAad8dd(|8INcGb0OI0-aWlz>IwoWTXZ?PisU zBGqp5zA-cm_VblG7*sap(xtC)cLrRSwkd&qdE5kTLHPB1D&t@uMn_xG6*bcqU{JD= zcfdg7FtL_GWSfnwP7aFEk%1ig+r!BD%#p?jVeEVJ6cYb1NLdF5nWO`!a6NH((lK?o zwGLtaOH@?r!9E*n%MJ1DBXPy`y`kW>F#bZ_{X?6V@iHRmCG4$4fOwbK*?%kpS}rnB zU~rc-LeY#J$hfQura3X}6fnoJXnG8&@|~Hz-&axF1SrQ9|Ar%Bk@$hEk>JV$!={8N zx`nfLJ^hArl%mvbUu*6Yu;zBSs}QB48OtE!;nOTmNzXgbXDF6Uu!4yX=qLq*AKgc- zD%N*%n6BYsh5~3elw_wNQb8WWSzJ1FF2Do<Y0wMiDu(&^K*<Oj=%(K`{_o)4pNk73 zOM5WCMncr5^dAnsd6A`UycFR;a!iU{>b5QU$e^lqE9tm4dI+*K9<RTr2+<WUVTH_F zXuXz6N))l2d4RO8mK-gGSD>_TtK1TRnP~?VW)cjF&k!lZAvaSr_#m6NjU(va3?zF} z*Ao3O&U@cd7}bD~mDWm1C%9FxtwkJ}sP*5kR$X2iJ%)(?Q<X$6lMV>o+_3?~Q|glW z45!i+hvOkn&0)<woUbQypSwzq(2?r<5q1(rG*kLG=f8|g2_z9_N4wv}DpG}*!{L%# zMN=sSH2defVrBQ$5vnDm|35_Up#mf@KN@8XXR!_0m46jyi1gL`52oCjDS|*UWRZgI z)KB;AWyBdgNMr9@a{Y%^SU#%ig0t?uuMp~!@pmE~4D%nm4aPELcK!p8kTsxn*`hi` zYEKbx=474#Mh1Mgd9KWbN7x-IbvRPB0jp(9%v-Y%qF|j80U_J@4?lq8Hw^{3H+o4& zc0Uh>3pWNF`ycS#LVcAYh2D<o3-^+8)ccY`k;;Q@_Y-UH_rm<>Kf$OtNVr=cZioIk zfKu>@>RaB42r6*Xb;uts<qM?G>?sb-;PDB_gL8olke3f!91V{NWi^lWRm+Tifhy`Q zn}`_gi$8DCeWzA@3TIuhWtSnx(!+GoBX|0twqt2BA7+2If@}EI0@=T@LlHo9`u^Lh zKx#u5-I{H@P0nv_)Et2$bwIh1*gRbpJ`Mh#5%+x05f`zPwjzjF5-;q(iDQ9?bzLyK z1Mq3_{o~9c|4tS))U87V?FW%$p~>yxsk%{$U)M?uiJb;2=|C(&-^$u53JbidTXlTk z4)5C2&rrnAl&P4S8SHs`MFvu?>4Ehga<*7(28?>u_;bA#Zmf;iKUjB)v>olz(}`u* z%X+b1@7VAPUFmGcEUBrJ?N>1^(<;Ffpom$!NhnM+gZl-h^y<5CfP0G=EGX4R=V>BD zC)!qb;uo!%!Y{Dzw~zblK6FL1DX>{XfnzZ5a&cgYb23@fA#jr#t){4N2aydiFpAxa zdTpYLn~rH12c0@*pSMkg!8`)>sR?2xeOlGf8XONNd)};&l=JH=lIi<*;vF4jy<ZI| zOlRK6z0FR_^Q=}D%idZ0S;43kFKhPyg7(uE4iyKpZu2edA<vNkl4xlu<#Af4&dLOL z>IKDOdM1os9;MLodH)EB552(*4`-Oqv5Nf+9v6!Pg&9NEU4`7eohUThJdWSgwnd&1 z%P8LNP(GB@{~^B*L77m&q6^n2>-8wyJzenDVIIt+*r(8xYZ;7cgFruJc_*3oE`UpJ zZuQwv8BecKCxI{~@tMABhi0l~pCvOU3E*AqWFGUk6h?CvF3NXjmqRs=(Cu>r8RE;A zr4wRVVo9{AEHtm*Oa#gn>@V_T!(?A+t+B!0>98~DQCdy`GUk<%<G)Q>v3=v<R^n$7 zj(h6SM4u521cN)AXQ~aGtsBg)zFIBO5e*%QC4Xbc%u=i)g*i<|Ck$bAbGV8haS10z zF!Y{5X*h9l_?e-Agh?QKKeQM=Ihln}^<RqJJESTrWpV(NsgFy48p;E<8w_<F9}NR^ z*&k`~UA@G<eEsxz?<6`U44Ot=F7~}XV#or+o=+?Q!!}@LkP=EO#A13Op!wv}P%$bU z7%lOMfU>vjf<_xIOTW!w{U9Bf=HcrnQs`dnK2F|@KvL|W*ng#ufsB+MJW53^!gYh* zqz(){?o@B-RR>LFUj*vUclLuCBM}R6cQ;c8s0l1)CtC6$lEv}tl!=u>e82j(CiTgd zwKotdkKyH+P=`<BYX{P1H55Ae#)&k#U)4h9%tIfP>K|(kc=h)Ol+t1;Pnqt!V768P za2sO5;;HtW!W&I>kl5DQ{@`K-p^#wP2C8!eu>;-<B9{E*K{JzC&w=S_)J@ncMQx$j z(VS7RLwPa*vhUYI%$+mHQ0TJDbIl=1lcLjs4pvC??EJoX*0y=y7k;KY{>=W+WGE}v z1WIO+im8_W1B?tI!`ePA2g$_wf#-e3YPf9)P27WC?Xt-L^&!yz@p5~)AntS9e_iQ2 zJf>3<YA8h*d1ES@mb2{v^+S)$e^r&2WX2>Y3uW{1D$sjAZ*WT>4IiuOR(tjRvN(nO zJsHdt@;+Aa+alG|`JWiE3AUwx!97l&9yo=t0ZdZ0K2{zX%%Oz`7r7eB2*)e6{cJkJ z=_~#sj$h^~2G$xV$OVmkiwZ@SKupynOlM@v!9!8XYO-a7iw&?c!X}+?lpG3VKvA>e zizW0L;wse=jEgFc3Tmp~l5s~p!M;z#hY<rN6zK@!wr9Mx62Kc-zrX3vsD_x0H}Z1W z@r?ZG=raKMx&<qLo)M6$lRIO5sy8^0fuzw`+~|xWC4%p};PzD^U7U?#ErHi)7_!cJ z4;$`TqW}rTn6yCU6z6kZCB5A=V_|hcpwM@d$oc^OaZHOONWl(%XBkk(lASj^q`N$! z64R9HKVuQVkBB4@B7_GM93Hl2lcK`FYjQ9-K%_Pg{5KLD4iz3Yge{jm;zdY@LZL8F zgHhAiCCWngGUjxm&pL=Cmn;;^1<M!lxkj%@KW>pOs6IKv2kMH!pG=hEXyhA_FQ#a4 zBXsMhJZ9}!IUkr=$AF>Z(!m6RzK;qp`Z7zS<AdR6+9f8nWYMC4)RPt;3ubiyt6i&u zl6l}!gnGcX5Ehm~F6%JCZ|sd)J=fYV!UiZ<%HG+({`%U?{v1uRAb&cxujrzbg0wAA zb{8v*z0Fhp_hTL&+gx;rG}Ng^TVtf`*mpO23WVnz1mPCaJbR2(4FOhdqz%s|3wC?Q z?Sa2fP*LZ?YZiz;g-Qy>*7@iK=%@2QbggB*S{ATi5F5~q$tsp9K>{r7$0%=&qRp_Z z8&3|=(d(QY#;53GK#ny+jLK#k4HE(&&LYnlpoZ$Ww!~_zP=Fb-S)}b5=5t@K2)Yx! z2u>|ryQQWLT4A+DTVR;|Fkk~HSzC&LW%`?ntc3pxK?Pp4o$|1a#r0xdrboyDU4lU$ zSbx2oVJtwV=>J8zXy&8?@Dc9}LoLtzKjG5hjO8(c&ax(hf!Z(i8ystbbpxNJn|nzO z#7c5t&Nj*dFk$pSsn4k<jNEpjk)4?r-x7HCgTD;j%X}kbt!vHO;$If|oR9qcq_ff@ z4lHXC+;xFjGAMU4T~a%;6^>smwEaae4W(BUv#ewf#%Trq{6@8IL)ZWgAYQ#|$b7c| z0gmx3Oh}dqfz3Gw?NjJ*)^ZVMK_}aFB|AL01NxPmuoNZ}v(p5A02~g;>fNQI>3Hx; z`ifh|kWw?m9)$gP;wI(frCZm+nKuc`e@fxuKq<N)hu`<K7863!iYF2G#edKYd(ka) z@H1g9-%aTG`3h`ozo&oEw<O?<w!j!Qs(n-x;0=O}Akl>$2V(VDFiPEK5!#jS@_QEu zy%?3i%k)D;>59>33<b)_CptxdyX*^9*#|(eeO1oWjzbyAyxlCSZK{s_CmZf^AcL#G z^Y7oPxQ3@N?EC%mx`GW*sR$7t0f~@9Z-DCyrV%;uaCTytVCo+cOIAJDQy?QMGMfTo z#%7zF#fzFBr=)<OYlUrdSF_zbvao?jXF8z?Dhyc&%L9}&BoNFvTuHt|R(t(!N9@?I zC@(bBb^D6Z*n)x&Z>N)&9;A!4BLLW037cY@8pJN5yGDz1TGNw<{#?_8fV<t&mTN@G zC72{Q*RX*eyEjSEu+oVZZ+d40I)7ZEyzZ$u2^c{$ZZzcjw-yc?ZEw-I>Yzx501#_` zFAx-+ye8H1iDa@THs*x+oQ<C>nj<rio4zRL3&(11+wed>OT9z4fOPAC_)KT+FBT%u zj37MT5uF7V=j4Q37d!buWtE01Z_QFMqX{m*f_9mh70*8WwHIdJ?~r9@BuhYITfne6 z2=P2r44z&Us23+md`u0)Q7n4VBGkz_bC?g?2TpB1roN6d{M%`;=KwIOfN5&Fn@QB@ z23N7H+R%njK)vxAHIR)^gHwy;^_wlu&(uH~DDky5w;|nE&r0W!eGC1r36y4Upk`4P zlDzJ`GUWrI>^kB|ZIjZHZ0t{H2#W&VWBVO+wJ;m361s#^o{R7l6ht!wr7W6f=Y;#w zhILRz7TKjq^>AL-*%_?$_L2gGl?=Pvt1Gf!3$how=u-|s(o@+1=3?v8Lj_PtXJp<= zKV>M7-`r-ACL^2!!u*p$d=EUwnyL>M2KG!JYV@4&{~vH8G0AZ9$voW%bQ$R|Q)j{Z z4a|CN;8{`*E|Aj!J}dfz7yF7a>{yFBkFofK?O<WBaI-k8(8vK8P(G-)Z_9R6vp~T8 zK74J3p0HxpXx&nbYFjm+2qg{+LnQkue%u#sSk<3H5_7z!{boMd0P>W;;gk=CeUhL% z#zU_ZfnNiEjHZske5W3PrDIcbjDR}zl_FgxXp|Tm3%+>U75GJIh*+<&tzceyz9^;v z*a9Ex>qo71AZfizFFv~3fc2nYNo!1B{!{`6<PXwWi)>p$G@g--XAC(cT;Mb0Bd+e9 z2ma9(>*O;dU|;vF@l15xwKeomY1>WIz%jsM)2^H+u6-%emrVzgFu)n}cgO<4qylV= zfS`LOG49330OD7L?N2TRl=N?XU;91%t=bZSnCLxX=B)licS`-X`AEvo3JdFey`0;y z;6ZkM2_)nnje8KXFPp}UPA^`H?IsgzV`DF50<~SnK`?Ue3f<_Uf&6K6d@V`GGdt=c zU}oeR2vQ`1=ARkY+a`cCONTI-wD`54v7c;v9|7a{r_D!x!t;2y2k&k-tG<F+;7@Yj z#y7|BgQT<d*L)6@2wxiz?yPVsY@~I)g#$_puL)f{paBwQ=oJI8ag!NR7#4%E+;QTw z4?>7!)~TjDl@4uy$s#c<?ye2=k(@-!G^OBYlS)8LQ`ek2-NHNhb6sQs#u@eej9Gv< zCI8dP6zN#76dIZh7FDfqCKJWQoTBYmv~2C9X|yxzcMI#~zC_l+-o>6w+Cmuj>seHW zP%&I~i9?f|1wV$f_t0~iIrYf<inJNC-7JhS|7WcF*1n@x?D6_Y9?i-$`YNlq$U;3O zl`s4?y3>F*75`g8NCz*u4jcLLyg%DhCWXe?D1p#Y^_}_*+WtGN(J6I)b^(L}fTBYN zwS|rEx)AS>R-p1kG5RLqjiHRRu-0t+`fSl{sQ7G9D3t7asBVL+WdCG37^$9U%fJAT zE^PCj!vn$W3d=w;YM>IrXF@>hQHzvoD|}*hUaR-0A_?OKNW~HJ$&V}4{n`r7TR;k< zWH{0<;&y>TXzqxMS{X?5#1De>c!HCZuvUDpt^nwG6<1je7=OC&u#n-Owf>j(o8)LH zpq<9Jy`aO0o)-eMDB$$fP^5d2h6<XV9VfK~Gy3opKwRWWTw(l31@uRHQeHrwGzn~3 zhw6!H(yj3q=tlEqCD$t4;;B}HW51X}5W~ZWJ@YPcrW4^0&ZrhtKa@U$_4M5=WO2l2 z^bYg))mnjN?sqzVZ6YqYBu;Vp!IsH`b5XAg1nR+s`gq}i+<USiRuOyP^)&e~F>Rz- z-17@L4{Q2uYcNtedyO6*Q6g4Z(cSWZk?Re#43cjtkhU$<TlBw2Ty^vp&LBu07wbfK z-cfaMn=W4v8Ruig#$O$7RbOr}jZYPb;?o?i^H`DM=;4eLe;6{|B#0S(mYj-Lk?Q+T znNc=%eNTiEoth<iKHd4oGh$IQ2hqO<(=W`9-@f@NYgt8hx$`y3#?4a}Ar8#0pS=*^ zUS%L-;LQ)eezoNopHxvw=sq{pp9Z<1DQRMCOp)s~L_{_jWJF!xwRuC#lHZ@{QHdha zKpa(?o!o5_%|7*@WJOaqYAI#)S7NoP;X-f16?g!jHI(vrN!Rv>YE~hSdbT@-pF@XB zNSo|0?+yBv*6)_hQ|-r#AdxLnl_{iXOV_}b3ZIqsn)~PM++_+5e`)(IJ28KW`FPsH zbXcm{7>f~~rszSAjarsN{zUA@6saXYf2{1=JJ1HG)(G<{Xe!)K`{E=-m*bU(rOa<R zW<2^H*^1d;*1ham9@92Z_H=SB7()FkF{|ILBl6a}KqC*|eV?=a4ptF3Zz!3nU^~0m zX$=Gc#5Kp@u^P{rgPoUyX!{7_kE(|OR--4iqSr*Gc0{@>U*X8gzR(<KAhoT@&RruY z!`(IdW+Fh_eE{8U(%C3g$$zy?c;Ohk{aD*-46WZ<u8f>>K9s0geGH1+&*HpVe3V5; zbxXxFfRr5F=qsgSmkaA}vrKC9pn1rSlco*&%Z}37%zfB!A=M{uq)Ust-L`B9t=n-Z zeKTkEO?t*H<+Dt%)eyZ{9CEyMb-{8;Zn*>ptQ#cAb}cPQZMvBW(6`<*0AiIi_j{Qr zGUvRZx|GU*CV3rVjr?e5e#E4tjDF%2V}^IeA=vpY3;N%h8n}L4Rcy&iZP$2JlePr2 zF1pr`gzBM8@V|e}D~*=T31eTpB6a(;6Xr8~?jU`J^VjO~lK$5-c}XMYmJskNyKs<A zj#7ZWxL|%#s+EO-=4j#LDFxslg;B@vez-kJ^8Bz#ZgK@u7bI@1mzL30vr2af7R6mg zofF;}PtELx(7XA~klf;Mpi1zcFU%zvwgp;)^*(5v+bHPD^CpUaw{D}1|5%Uj(>6$U zFt%Bs?8NPC6(hh^`WGm)#;E-R-$ymjkfv(ZKPpv@Iyh3i0Jm>AsGs`J35k~<c$F?o z2ob^9?Q5d0l^z`?CQS1%r?FP^Aw~k4k8lttI3h}M`lvDmo~q-Sv0rUI6*SJ1>4-YN zzMt`J$h1h}T>ycWLAT}3K`#xoeCpgvh9&#SA}@zWT*CY4UhM53cQw#n-r?*iU&S09 zHc@uVcn@mSkasjzO*1d<YGlVnfOR|thc@|c{isH6;|6*`QA|*4+5BciFo(YS`pU8H zG3tw-@%^IM(uTgn$rUoPW%52ji~ZnisSp4hyHEsa<67(P=Q9;q;-a62ctZF%sEl*& z=M#qFo?~q2r?HTo4e|BSzcb(o6*FZ&NKhXsS2%NY;LlldSYPewjz`Y-4^glUMEmH; zv4L^h-|9jR1alS~H75JkF5=ekDYTHe0B&=eUK85280*k(8S}k{KAkY96T;~LZnu2A zOln;aGM@GutCFsxOZ09fy7?kYg-)l`7*p!7F+7@J=HX>Th*`1a$<CoU)1^HFvBk^U zVns{&w}W34F~Z|FaZvKcR}ZI~Q&F#%{l+-WQd<NJw8ytub$L5}$Mxs@*{;wpE5(9> zN+c_5L2g||_XOn3#T9wugwQL+HJ9dsBcG#+ojr$}9sG}9naS=d2sWK${8rL|(6M{! z|6e0moS8T{KLPzd(H5;S630Hej>NdT8l+UjM<4UMA!<IXsqFec;KSFxnK<RYsMrti zDg$`@Fh5=Tef-{`$P>#Wn>vj%z)9`8;c!%{#cI(8)g`wz%56%lp(RBARi}MifWC8# z#mcV&L0>6?ps5+%Cvb=8(lK?|U{d5G!F1sLJK4IMkP7Kc=hHG|pjdv016wV--`+&6 z2IG>5+6UD%K8vpaI3vFMXwOu6s$#^IzuHa3YT`_t{&O0t>*l9{y_Bxw!j<&#Cc&)( z=>1!twDxLmP6VHn|9e3^jJs-}^z26a`Iw&iaFp<fsH-F$@C69^)r-xrLAu*(^Ix}2 zcWV6^5>r|ipS#HtbF$WF&n|*&63jq#XxA=PD#j8&@?WDsEE8;I7H>U|jFxN|#eJ0= z8H(IOWgO3TiCHjz`5}MAzvQCSbnL_F`qT8E_Z<)p`ll|A3lA2+g?vB5;Rv!&@VwJq z%t`B^XMztP2Re3!aew8sak9lLO0x{I(*c7-<*!Hy{UfY8Ee#c$nWkn@<<9>Bx524{ zxNOFyzNeByYFgwHG<SZ8X=5%4F>$?%o_9IBYg#J8+Y=xRKy>b6oTIBbgUt`a&PE@N z)by3P7K%GRW3nUUnMYq;f6HI%cNyisTrwQNisy6~`K%N*s^vHwHuND5QnQw$lxS`< zZxXebDgaz?KY}>W6z-X1(+p3!(U%bT4$?y7Fs0Sm*Dm_J|1hntRChY>?t0f8%=>F> zrs-uC@6k>h*33Frq?Uc{q0rP(896_ml$@?;JZJIxpw;oBvRk4ZQaYN(#Sns;5u7(b z{km92>J8b`H-bgeT3i})UG5+s2^W?FFt0AR*wGl(qB|pWi7(1(7>`kFM1<!E#X!Vj zp7J19v;0xU6Y{zYbWX=XW$Pa+ej7qtN^|w)YUfU*+09akJ|FOO{L|F^AvLi$IGUj2 z`E#YbEAk)SVc+81&~jw#P&+bDC?+ZB=mq&<{ocZ*6hrAU&_Yukc=XAKYi7-!O3nx_ zmx-D?5Tf%h{i%1Yg~atup$HXFDg2f%Y2?hVh7v-J{>5-laci;=etJR;0K*mekjy)U zs;#x-vbzO4KiV69*e469ppnG=vrp^0UAlS4T~T^(AmW{4x&+Ot4FoypcZIhMPC>X? zBh`r##&+Ul<=;wG>^eQ^aAc7^lE_%dI##uL=Z-5dy|D;JfipKhgaw)cZ4$Ha;TLP` ziw=4vi_HWe$cd$g-?>>{{k`^=g|UM=;x%(R*kGXY^jGC-0SVu+dH|dUe78BH^rzsr zZ{q=7Vs`M3!^<UpnGDJ1(9f|gbW7KWsW)CVNrB$(FjvE4Uf^>j0XXlknmRJb)3X`% zeh*t#JaE*!{O10E;LQ8!Y$Ybuo<012y6Rkdds3Zm3ukOW=jO}ih)l<tbn({sb-{@_ zrK`~L`dsUpkGp3M1J4Il^yelhd+JtND*RpuWs()p#jPt>(miOheT?7Y-I!zxDl`DA zq3nHO+jqL=LSup>N~OQv*$wA>{Pz7f-fDO?r!PL@3ZLfy7M%4K7wBHZx0E${Ow!e` zZ=k%=MEwf>)RlKR1tX}WW3AWjWW*8b6sYv_@aUlSu<u{FDbDF>egk>IU9465?A32o zAzG7k=Zq6Ly^vnmmT(4g;iRJ!bG%TZ&+-tRq7%Y)ToA;G>K7zzaJb<y7Ka3R_-;Cg zWe2mVYhW+E?B7j7z8NC2ku|cH3$9#0swpGR2YwIC7Qrv>pT89L{E3FB0JGMnBS6h5 z8)P~CDSbqaGouTYn!Ah&T)uY4zeN@;Ln)|hVVy<TTk#9O2(!Z>@DyDUi&X7#i)p{l zNC2)Ue89*2*JZ2Blmt7mCpF>w@<s0RkRtsci^OX)Jo>Z9^l(U;<C`CM5|ohFW~N0N z3zlY~wa$0nO6^*DVV?YsQO$$vNoQ?>yH|4WCBa9L9k`(*zx(Rf`%oFa-jF<p$GVy4 z?96GM!cjT`pW}}Bgwb%|v?Hiuw!>@G<8ADd-v_M5=t6-*;R5e8Ion5fFi0mNc~Ky$ z;rAO~N6A^)_?*VO^df_cwbwk7)ko!+qH05nbno6qO}X)_>&OQ(`&b2@TPRI~aij)F z=W4k0vhK<YC_n~TImE@)AK{P0f{$VrqLil3tAK($01wLswa*ZjjgCyhpWs>nf>zwI za>FtOF}W{LKLP=0q0xEXbPia<<viV#>%zgkuNZz@&T&{mOEk0vd607kB5-bv$Eh4% zg6u-Rzx40q6>;fZbEVOMDE7CKl(^a3v$+;;S}*^;eQc}Vc7*D0Zzwh%W>z75!I#!e z24LR#Jh;=}$TQ}B#YUG3NAZVifYY|5UE1cpqb<Q>)Kr7-2%DBC$arJxtDuqRD{Iik zrR#ssdKfvOP%N{--G5az{QcYE^PO7pbod)D6A83|Rwz~jd=>iD6nE*xL%55&WAm^5 zzqOpVV>+01B-ZnhQ0hM>A`PUv`9;SZn-7b1<giB>w{vqNUqe5EuQz>4UlPNHHMBUW z*|Wk214g2K@H>~<YgV3EtBMs&I)&hW=FomW^DPYi#XnXZyvQ+_w&4}^4%u+I8umQ% zpYCF#+IQfN*50!*b2a3nhoc4{P(lO39h0oh8yQoS-;;cuF{+Z=m9@b{hX1F~QZZ_p zryfNl#{Saz$3L7ZZcf~e*L~RLHz}-Ke0#v-T8SwHQ3h#|&S=*)D<CRY-DUmwh@SNv zkfofoeEu%_L6Q2AJ^_t;BUL=^NZi-?%K_MqH$|cgsd^H6ZiAGm+JV~-uVgb1EMc)_ zJR8=@U#p*lK%A$ea7BQI+@lZTQD1lt(uPA3`_kWUb?c)2W1=Af@sbA~MGtYLUl^Qr z&>;l=Mgy|sY*up9{X513@Y%XBV^#(NN>V4mW<Y=3{Z029XB%FOsX4ve==)^QntQfs zuqN3er9m;+o-QXO3cBiYj?L4rGHR<X)!k&Fx8r6(<=N?QhcxHC<d>#!Wpz0rx5|-P z3*d9*;4!QE!}U?yf?zUrWn-%5uGEiT$Z6h(-&?>;j9*9;1YB!U-~K8K6FKa=c2J6r z*w}Ft4D-9x9U=L`MH}uY`&%e{@)7t=&37#2R<H?C&70IGK9DtBY?V;#KG8YC%hssY zC-&Zm)c`RLCpR4~@Wi4zB6Y=h1{le3DXv9X7hSLUR#9<E?ES&xOwh%?3!wKM?o<EA zSW~D~SsWqIT!Xgv9<iz3KWkdkdmjD@*Y?2|GY}D%%+KHcE)nfw0)`$~oVU+$DTAVX z#Q4}j$lrmc_`ZK-8%Eda)0sekTB+vhF5o@o-X(ilpmfomQe0u})?u8NcbV4vtrI50 z8tEr?SUh#)4KUv(4(_ash(ErDJe1n`wZ=dNe0_kv62xzXf%~kX$9-`;;Sc1dd8`bV zFw^@y^}7<QJ<k5>hZ{oKbg<_mFz54&tSp7GyQisdkU;P00w2aJmruO#Oo&Um$j9xn zc{h6>LF|aa=4b4GJ~xtFQIB(LY2hmWHV`a``XpymZGy3Z$;07OpPqh$BGohaKy=-o zPX)_wl!LTi1#T|Cd2(_hZ6<S<yE@hj{1@ubn6@Y~H8M3JBk&-UwI?xX;mucBv*^v9 zIBRS0@%KkU$`Tp3a9XMqyu0G;B5uByJjo(%C%$x5?8I%FwSXJUo=nQ=Lo>A=X5G?l z1`ov>Heyev2FI?}=-;q<5ypA7QiE<?X8PJRPP^xz*@>>oZZi<4+byk}&M2%w5ue%v z0zxb{rI!$X{9;?M?BWnPkbUvrC#Rl+HXVu)QUTiCcnN=$p&$IP53^wQcVA-iS!-nC zoJJ?|^8@J2k~L#QdQ5qOYl)=%Ldi)tfInn+5pWmn7;0MYkIHma(&BdUh0-wW?Yrfp z`m@;Eb72b&aM1_B#9qwjsfHKYo33R@a;#eYOzeh4>sO3T;F<&)fP9P28PE9Xb@Gg( zdWr5eg@C~9z#S(Ks|QNzTvKw&yYs)+lG-74kX{(;@};H4rssYZ<oG|uCFSw$wqGJ! zNF^TK2-XaO87<Lg$m1^4og4uA6!yF`TRpG5TH1DBoo0$;xeJ3UH!J1Js_RSA#wOF; zdn=R)lf<brl|1I}H}eG=f?qW5?3*^|9*bA1^Ylqc>z-xol^a-0m({<ySa*|zIZUSH z%>u&P?EauPSPQcye5e%9S?7Spiu`FJqxS0H$7lR*c>S-1QLSOJ42izO37LwQ>Geb! zyI(2x=PPB6q>EbZy5_RdBN7gQDgQB5%0U&>1GgcX5HvMx*g)X-nZYpk^S5M0Gfp=m zCrEUOaW94Zb5f5radk&XM$SS1ae3Qby7~<d3(gn%zldYjf(9k)w^41&_N|X!{krhh z8Fydrd=9ACd^_;TYb$W_^}6EXh9dYy(#4H+f~NPB|AtP+pBu<$Fzr`m?7`2zo>T6_ zl<yXZk6Ga_K0lkJx`uM^sHwSLGDNeAq2t+B=1OSk<|1Q@MU>k9{d$4p4(_6agG}f| zvG^AAi2l@wJzPfYN5U{}vk62)S%gxhYFBY+GzfZ|s)8Cgr1-qeG3}H%*doKq7T88j z6+g1m%G4O`A=T?mgVTpAXaDM>L8Fpf?3LhqlAIml4M-$z1@ZIe#ZzVNTk^MWF*E!0 z0!d|q1oYcE+;#KxH(}@7lS=<+TIF2%k`M+$MqvyjX`UWlEq4H|a@FOzAu4DCTBCgY z*RPcRlIwe7rlTlY$ogBO-=|laL+{VB4m2BF{d-I9r_@55{vwH-+Dr$jC6Pa;UR;{m z-!ZqnFFe!dj2~!<=)C%o{frRztF>zncm31%wKZPhK1J4R+WLZWxLSkeYvq&5x8ud} zFADN@oGQ02SZi&}2TaBvn=6p@LcI;ENxFkvm>NH0plvvcxciw?5%@0Atl*(3Npzw? zAiP|iF<jnAeqC_0SMg98rt2^w4;u%bIA!KHQL0~h&0wd;8mNAX@2*;l1OE&f>ep|K z^qoa=%kDsXPM{Rv7u&!#%8--fK!D4spW{b11PwmrDe9Aie5L;fyi$HvQ|a}u^Wx`+ zQBxQ>@Ynk(FmaZ3=W)X?mBP`|S=ri|iCk~a!NvU^Na8=;+mYx$3%bz~&Na|nMk`ff z7%yoqYiHi)g61m!xz;~(T<>sifdBw7$<Y~We3{?0AA#|J=ZdGkD0~^34C|W)DqdYj zw%?|sJ>;>$K?bq3H+PO5`N2IL*>s3YrYg<OB2Crr!~c(>bB||w|Ks>~h9N9P%`uzK z{Ek}}mkx88(ZwytUAic0N-CEj_sbBKGaI2)Gn2atm0Ut@*<1>lBG=W3#a!nyjr05V zCwn|RHv4`)pZELydA**m=Xp9a;TTBnvf!iFl8)5`s^M<lL6)h0_P6wOm@2W2d^%uB zL7#LW*a^}vFX<4MN2&;MuKnNF6HQholvIP^@RFQC>zX6EXN_5)-0W5M*S%J8S0~EH zD7Puu&W23PN(-XpDhTHX!?NPbJH;vEIiZ!08iP9zE75$zX18m#W>)6B>;k`H#9G9r zD)jm;dHo&1%i|jWD!Vjt3L&i;d3{Bov)AC+%VWCn-{851G^<zsV{X$a`-6W`ZdiZ& z_u#{6aUZ*Z^Tw?zx(EVvXyWxjv*yi{m3s^}jEoUH`d1#S$Z@GFxk)fTvwhA&+G}Cv zK7L&FS)@M!Yp_WD7qI2{$JC89`-q(N-+_xn)VH+iZ_(l}>ESflK7{n(^>tuZmnJ>U zE<JygH++S->G31%5z4SlU#vkFJx}LS&rKIBy*|4@>9fB_xcX3q93Xx1-(CP2ruuB` z5W{jm%~B_UGHPXQzLVIfbE+rpdAO+wrEv;EidLZ97-uxqys1eMbKs?NG4~-zWLQO= zRD<zHG8uw8OZDsAb^E|ws51X!Tw;v9`PG7warpPzV;;k$tkufCx##f&&!e)huAu3Y zSSInOF087u`Q4vzA;j+dc5LEJRD-kQ+H;*4XGKS2D8fun71lpk9=E_Ag5r~pr!^wQ z9Qxz`$N(a<EzyUe@QXSJX#3xTkc2(`lNveBqiFm1w76TF#rn5uZmOmjx>$RXeNnWb z*&`i)^<J_Zz))wlbvS|h)&6*2o*dS>yIdfn$Hq)<ovyBhKHp6F4_N+d3H)Pw+Z38D z9KU^ex3y_rx&v#l5uT~AIlaj20JX`{9y1$MtN(yq5y2J?f|Jr2{YZG{T4m!qm`QVD zrAO&0ev@w4b0T%{@sAfOmMX_X2A?4I#11&<;>r)dn>-gnSV%|^l{Fv1pziQ4Mh@JW zq2#QUt|+Hc3_42|dTmwZj?zN8=2@R4{Nfg{AQ9g5a#_`mJMm`&1tdW{6RS5Pd|~i} zVb2cL7VEix1d!e?iG~Th5wbUwuEmiJ-C#&{I(IIPJZf8s?66^=7$6w;QmZn!d7p8T z5NjZIs#A8d%*~x(0eN5Um~j(v<;})DVF=YaQ1tV>$uV&HAN&NWdd;{M>Fs)6d|?aJ zi}V_RGDq{vQVu|ialsH66p&7=k8kQ)R|M(-IyrVzREC3N>I!EqU?rs=Rpm`Uv1YKz zo_KjpPSgsv0K48RVPqP;ZCp%JnQr0Do4B62bSfMHxKebD!B9VYoWWy@WAZqINkzi1 zCQW0ctaIzsI=Cf(;RZ*XV)5C>NfFGGc6^e)C1GWm=UhWf3^MrxxGnEs$#gInj*52k zl_?a12euX81ocI^AoDe0G@Y2yH?GVo0lCbM&@jD?2yUL;rB3I(W47z6W%C}&X7EM% zB=9tI)*91o*-Hu5{e45cPmbj1aHp3051}s7hd6|2?Zw;OL8ruPha2PSM`FRW9x(u> z;*pT3*NLJFTI@u_;!{CU#L?8q8T{dXe2(B~o7IE^>>@7O3Hnf3yIxK6Dq*9pwC7n& zha<uml_dI}MH<T>Lo!7vT4YufUEWQWphg8{mNSV#UzNET8KW!3=|PG?C3*H+ac;Y< zIffh}HOkM}EF=SDAnw!Xk5dj@5-W&p+ynIqDiJL^YJ@8b9hG?*J5es?VcvwqGs~M! z;@$xkw#GPz>xTYQH&w)BsqDP=fm~7$1c479MNJIeu7TW?m7S6o03Ulh-g%q&Q1ljs zuI39K|4TZo(4@z@9x0f0jCVX2(64U|4QiABx&{g=LzK}Io=eg6yxxSVsoQ4qLBSS^ zw`VAuvpB6dH@U=!)=mLV0<bFYA}8?3YZpKNspm-u+YjbmU-y&BGd<$ikDmUg#p`WI z-w$wb1%!PMlANa(5;JX#Vt+8L17LREE%?LGu=Nt=ndZkmREsE3*E+4PK%qDH9cA8f z*BUh1Xu{!2_Z&7XPv|ELw(>09>Gp<F=AckcJoASP3qcqf3k9}Zd^bZ_!l|o|^1k)% zuZiT2kom%Uy;%MzC|(MoX#~SDPZPk}sIa?A+qGnz*G-u`7r-fi8u#_|#XGiT<p{?U zs!?|^sL3y{Ay%I!tH0SG)R*bGu?=o9+bds%U{W1OmmQ!f>mqak-O>7p&UFEU;riMb zKs&q}1g1IuuDK<QH5|bIha=Z)h%dPrR_J1-WHVy!EL^oz`>R(*R<o~c&O$7`e3aM> z6>t%}fz0dMUsPWYnV#Ry8%Pt0nvFmz6*vdDqg|M>VLdY{VD!U2*aVoh>`xfQXIqO* zLpI`%Q&&vgnj>yu)ckoFkFTzLqG@re9HQkxkeO=bn+P><5Px*Qy_@cVMT4FkBfzqg z8B!nRi%QI#nN()=H1vD-15ky8)gx<2g5r~uPgz>@aj;i$fC#JfdiCbIu#EJ$+~7D+ zs4#ih0T93C49*sd?wIY(_9T$r$fOTXW#c;*e`;A`31C<mZ>3+nfh4?#egJ=CTBS~) z!LL(8xYM5dJRwY6xdjmg$}J@OoQS`*E(W#XW>ek-Mu+YZ@sppU<UebihN@9GQ7(iZ zJF}_={E^pU``kHNEoi;1LF5*V18*xf%>tr)kYO$J+D6-uJ`TPu@yq+04azkI5*PIg zK&G+Ta@rV#zpV+P<Tz`}obQiqadEDqWT-}`@l`NNKFB<WZ}Xy>&re`^UVc&wCX19O z;-o}=wyn$vL?0WBUx@RdDO7K5q34c?K0qK1-=gCb$L?Dh+z*l@_Dv5IJnXqCc}y1% z1)my*G(;UpYvF==NU$S0((T}Qd~1M~Z~8J_GO}w_z)$rvHAplzlXv8T4qmt~hwL9S z9nsg1Vx>xH++|J7u}gV7h(cLQbrLMD?UDM8ja~A9dD1MXnvrN~hxR&vKfFPV{h@ET z&#ab6nGm_!NgS^yrdyyp`hL$cWWuC`SWZHnz$-`-qOV_fu--G-Ibo4X7#+xMOX_k5 ze1CoAgQD5*S*i`$7IK{j<1Q+4YcZ+U#l*6|Q6~cGw{Gz)q#CS`!G9UI;vW{-)<Q#X zgDTsJzFNBzhZ4_b?Pb5SU0?i1`Dddpm(sj_{R1F<DqUVQmC#QV<iB$s-H70Dp?F6- zpp6^~GI@z(GXKhu5^DXRl=?n<r)!RX&SUZ6=ngQm<WhUa9~FiaZ1?KCpW>16(dwj4 zuIjdy%RkR|5t8W9slW}RoO%}vvmlf2WU-Da`5oY=8)PS<n4$H@^G6T^*7)2`lxvp$ zw>pVP>_rv49bi8l%t}fi2k8k4QYIRruH3;9ThMm!p4>8Omj6XYoZB7rU&K!177z-| zfbB8j;)s0?jqB?L2xB#PB~<mb{R~4{Rnb@da&BF+OMzPEP`)#m%>%F|#Qy^h2oxa? zdgK+C*~o#|K^zR&sorDA*(OdN1(H-E5q%cesnvgonM32&%}ww(lD1|<YDv*yv-XA( zc0CA&h9H>IswUCVuJvGDK%^Vb)V?_!cRBtpgk{M~0DVg^%n!`l?XeB?15F^XPB9%a zBOb4?XxX!`?=%xwoAr~{s8i+;*di^-GboY*7_yTveqYyE#f=PtzS45mKot|V6aA&| zfE9v(SnLNg5SXKN+_(OqoL6<HYmp@q4=e1H+gPs^@Y($?oa9~P#5)@7rFEXwe1$?( z*sK-4jkGtJDl<wY42s2;O@@<9G|h-ff?_U=;YpH=B7RBVUGE*|G-|;R|MhXzmq(Mq zJtQN!wZaa~15W@lSDk&{jINi!iti?=Hi(;sP+(<SF6#G`)oQ+%T!Rjzjaul?Lc!MN zNwZ#}JjbEGkh2pC_>>B*OD;Or#FjCNgJB;N4S#Lpw5%=bVkX8-qMX26UwPfQ%b;`( zvJ2XZ*TwK^c>|;mmdR94|8-+7CF@QZLM`;KtZXL7YJXlFmLVbcz`P{gglqn&s4XM2 zI)env<-L$OLx2)p*>nlD78RgHd|BkR^Y#OD+8z|TSL+-OOBjze{++)ezxb%{7Zwov zT5v!yrV-I<7N9N<@JDCOvv+aXa`z24wxU8AfC9}(UDWQkxaCGta))>f`At{hOk6?| z9(HkPhbK&8^-c|uDUP1OrbJNM>b9C#8le{FMSb%Z6#nFEP9lKe%}12bN>#&9yJh2# z#IZ^l+dK7_S}<gVFQh+SY}nDf6YbVn3}m!RP5-gHY_~ly`&d1`{r^&+-h^pb$+@65 z{z!>3Gj_Y_E<=(6cuF9^U?c}8$YIH`r6?Z)dms}#Lk5U~!Yf#$_wpPlIW`9LE;NR5 z6He8~@uuG%{xtgXBSiU3so7p0jWU^S93`u(zND)uhMPQ$za3M@7Y;rev4&Et2OeK| z1VK!NnuQi!0%t$y@r{qbu0%$h+GC4`&3WSH)xy|T8s!+bq*-x*;ZGJ72#FR7;xGtR zHWK!V^0f%-4mF;lI0jZ;zwqJb?hvvMw^X&vMuP?!4nTvI)^kZuBjZlVq}F!22wvHI zJ^TY}Gq~v&yzTMr*U*HOUqQs32!^;Ok(`9KVo5aViOO0Z1u=r7I6m6cfXQzbLI_em zI5r;L_SjOU`|CKR*$!|QFFUa|0xt!N!9V<Ve%LaDqe)S*T9XmU?(P^`=nv|{0GI{< z$&1TN2ITJibB8SVqF=xRD*<obs!>mEO{`y}vAty9I2g5o?UWnJ3uv+cW3*&K*y4~* z(8UA4?wXhNYDJo9azv2trfiov8Uz|1TDSr5ljdpn4Zx8Z0}_GP=w^h^RMvt5rJMX2 z2C99TpI}R};SGn__>2&+Ef))hP&>Jr5EY`+aatL~;#VE3Kg8xEP0Wsx0E*SO%B_S! zj+N7bt!P*9w%$NDFvtRJCkK0_1PSS<RW6nCI;@T*B@2Ys0oCxg$7lh(1Q4h{=US85 zhu}oVA;2uDcDB~9{t}J;s9S5riH*0NYssZk<n@vz8!BQQAHKvWJ78_)x{~qR17&+N zrV;5w%*+@ap&LH9(&x@qHCQVyI~nsA$J$I#5{zm0rogeS3~_ON2KNVdiG|@=j{XrD z*>-<FrdGI?pNCs9$e`zJZAH73g0}s+9!(y#o1{p4&^vyc<3F=n*xChR88e0nB|}@T zgHr*AR<`6P23z}mVYFLqNft86R>AT{A+v@X#ol~#0)J}Cw`!y40AxfcTaXOeZsXi^ z)Vfruu4Hsc6+^s7|LIHf;TG;28NGggn40`1SWd=KnT{HxOU3u=p(U!06=42WsdhUB zjJPeH$m@NaG)T?F;1}qA5uMCqrNYQrU3}X^*i+8Jm?da`JB>P*nU{rXytQMMZkyC( z4RT-cFAPe_z7)UXvLw@B+>)-I1zbic%-<VSUY5k9hQ$1eBBQv<=G<Xdk5d29?5#X7 ztnEMG9~%s@lb2TnKu&oZ$UOpM27p$jIu6Jb1IbZF*G1E=&`dh$YzEBTK}t~G1JI)< zb=u<2wQkvfwZ2Uk(vxsKSv`^|ye++U**DQ7DK&zNZnNnL!-7QWGo-F7%x_GS$L4W` zG%hVD;y=K+2&pjkAFw}8!jybCB(E~i*+PM=rVJaJ{!z5Dyb%FQmw<#P&}C*S*A!Ew zoz)qf<rdb=wkD*JRKZABVeqXVbXZ=j7g{%Ox>lXYnevwV$^yl043s1c*U&F^Q+>hn z6}^RnTo%p3e#i}0s>#!cLiQ({834kJ25{zCnm@6ujhF1Bz-P!YZn2|KF|YmZ&Sm4? zV8t*+lBlSw=Ou5LFjA;ub0Eqe3Hd^jl-W!Jtt3M{+jQLyNAWy+0t1z`+@M~*z-O~- zV0H=-x9i59vtVWrmijLz@#rwpaZ)Aq8(#qW2;n~3`d}n)Y;2QOPrBi1`g<Zcu>8p~ z&&v7ph>rGgUkWX(l{fT-Bn`zxmg6XZDRC!O^FWp;sae9&F1&{vE4fH)Ezas&$`qZL zfj$QG^9KQ7Oc$8)t^77paB{9u_9gydV2fKWQ$Hw*LUT?8CJflfxcYesu+h58t__I4 z8@`SnN;NFCB<)8cg8)@M%hqpp^$P$`P`u=E31d8K?X|>^Fust#+6Qd+gPq~Glwb9x z4HT~Gb#NGY+KrYB#m*=f1+G1*zmT-67eKHA@Y+CN$bD<5I5(eXe<0mE7!LT7@D+YP zu{RHxM#BSWTTV7Gar6&O14V&M2`MNX6~FDa^M}Ens>`u(yR;NGNj~C#P02t-$lA0; zuO=jwa9Kvo7zy&hg_!B%lvCbY(WwEBYD<n7GIt_<p<U^s9k*E0oSp^I(SMtC9}Gkd z<vqTeZn%Ic!Hhc?I7|VO=Qq4T&BoQo$Ec6=$0bd<;0A4}KE;=^vaWm~j`T&$u@^%e zFqc&0BigAJ@oiuW4h?NFi*gdn{?!4fssyrM0AfXn3*xJkXBmB8$o?&uG6XJu`z&Mk zg*Z<dl4@bvF9u1d7L1r*8V(2Nj4r;@2y~D?(wo4Wv%?Da0)|p8oh=+V^RdyTDhp^i zJ^sig3%F(nQ?#MY;P?#eM~5C}lera+c8)of*{q(tVyPB<@{#Um)hmWux3o=TuR&yJ z=!a19_w?NM4;(?uyrZDQ^au2MZe#33ZuHeO#tI++yulq7tRzZgq&yQ#Y8~Qb0>;}f zSHv2lr`%Wv3j$8jNulUugC9=$iHttB0IUyh9(>P9YmT5BQ0;sHA73_fAd7MExc`{> zr6jQF_FlWhPK1GeLsuqj7muQEN)FApgEXV5s@BNM56l8&-i=3Jr98Sw3CV_%DS38) ze%WB`fXSMu<F5fyT7lMv?a>*gF6)`>6o9uoEk_~F)nd795GN4(q0S6M0&rK4qEw9z z?EEALISP4}J4#&#98U_v7Ir|FI6O<Y3s+@wKYnB}6}WUoN|8XZ<n_I<u`&nqDigM~ z>LKs09vRJZ7=$Fcdr%$n!0id2mq%3dO#tEleCvEq`sS>IW-Brj@C7SVv2qz`y5#(p z(eXU{C?`m^+EXNfVRj2Fid;13n<L}p>bK&xL+IOKg3gv1a1!FUYef&Owf>!SK)vEj zEd~muB?!G;yl=}|8>_@m@*PH*N)|K7(6z#^52RqKLGnguNBe%U+z$pC;zV{SpE5Y6 z82AuU>%F{51vU2T_RlmoxFSl{H@ZP0tQLrl)r3fSuBciE2o>c`rsVS;+Fhqh^;$CH zQu5w}MG?&Z19E|*gtQz}huD|A<Fdp=+gm!BqrczRu(7yzkkoqdo&vg&78ErI{7@t3 zw%3};x_K{C?C9fFIIZ!ZF?3lA`kd}D&N@~i3JD$sFmhQJVX_pJMJV59*J36|QZT=I zS``WRrO^`%3E5O#{d#DnW!_TJw1p={5=1s0)tye|Le=RwQrR&{WJp6XwuNUQI}&{a zn#8l$&>^Fb&#eeb_89F(%=F*l4!ig^|1^;STxpzUbupMjqiexIm8rJ1ne7paLOxfT z^+p1&Ikv9)a?V2DzoRwdtzfi&x0Y)-1~FT}5XNr_CZ9;8$SeADmHDDlWO{?GG3W>g zybf5jNGQ-M;Hn`zsBEmqXnkKZqBp)_M`_PeM6U@5k!Dx5-!O{#4XBXb`?TcHtmOi} zgk7YaJ9<WUO3Xxnx3jSKiHvzAO9U0bQf+s)ZaXPvl57MlMc`xm0)sclgbn2H{I9QB zwb?w|EXkN<MwnEBIld)k2q6|ySohgs<c=y{+y3w=ln2@ni!M0_I6=U9wrYeLnEDp> znRowL63grlz)A=ills~+V`emM4NF$umBbb;pQ=qhjW`$^!u~>oDIYkm468zA0psOS zYhDf$gJO0Zt{S~*mG6M<;?hZw$Cs|O1~deDAP|@(2Bf*MafZrRFXZ-nQ>4uZOGWC- z8GY=;Sij9*jQF=wb9u)f1JvM(aas~Bi9g4qeAZ^>+Rk89q6xo!h34MU%-AZuMSB-y z1@>adJPafYsBLppM4*C4b8PIev>A1$$vQ8)DzcST;TT`CQihP!2;Vh&ZIK*&4Y*J~ z#RQQDf)+43PATl0yCaUuqfXlx@>M{U*J>D;m?01-BUCp*FU152{zT;=etz59PF|5) zI=4cZsr+V}kPcTTAc~YBSw6^lQS^=?Ah<GvxI_;!W_`&t^CzruGsY^fFf#I<6i0>f zPVH1B{JA^IJ9Lc!L)o<PZ{1wx4~;6yKCrO(-;<CyoYvhq=Xpoy0Nou7w5EWWR`BeE zS;ybrn?@95zDelmawP|4C27#_9ql|VdmsKo6JR00@H-G55`R6|&>AKlx+N2M#i7N= zhp?oidFxl*2uKe^Sbzkdgv~A2+ji&g!)w`Zj^5@53q;s5*rd#EY9*K;L6UDidPieH zR05)+U1ADo_oEcZ3;cns?Un+FC6dtem#qe<X*Em*T*ML!XrUmK!+FquRx!@ar{R*- z0(PdPVgx)J<z>k6TctoJ49f)gEiLm}CZgP5$-ncRzJAETa)MzNT5u;40cKX|tqJU^ z&I7$>!nuzJ<N@Pv)Hw6SO^VhD?;z`&{xH$9^)D~%K}i#k;NCAkrbmt)yA&OZm$~NO za9KvW5BC}@8TfWV<p}wx5SB(QW9>)Ux5zN%DFw=T3a-8!5>)5ktlNs(Y0FFx5247z zrju+b4iIrtkagfX@fa6M1mq3KKH#MZkhK8IsKv+-X@nuw2%f#Tq&&DP)<th)wd$~A z#};rTE||RTh}Tn#O6cSdfx3Fnn>T4G0BwC{AWQ8+x8!&8SuPkcoyC-Jdq=EG1ZLy= zitv}@UCqSgRfc~1?TIf#28l`A6NCBIFW2S<LH2|<q8*wJM~42c@;_U)l~*YngZW(m zC&<bmQI8U0;q`q!zVGP2)uPtd38YBw=t_P_EfGUE<dU7P*=CXth|icsgWplD>XJc+ z=FMA9klE<O_+m}vlN?aP4&V<^f?D{jUcC<O<zC58gD7dF>#>z`FKpjM1DE26jHqzX zTP1ptXnh4m&)QB1lcfdR3_yQ~%ihfz7d`=dxyywkBu<b;SHLhBM=7D)+R_S&^vrg$ zb@-R6l4>cIAotg8Ocv5F>72oGetgn1VK%tVJa5VgW?ZIZD#H<t21U$>zQ2{K+7kan z)|38A@29oWy(p#pgTsd-faue&^h;8TXu<AM;&I2R#X2eHp9std$H|V*cZd80W+OUc zHJ0Z04g9^!cP7SBW~QHlHxYjCI6ZMI6F{!@Il;jHUsHSQP)>ivbkYNxyM4tFj8f28 z?|IBh!8#3Ym=gr=if`T#LmXLAS~>sv-DfI^q>w<4o|)B|$B#T!PikNFWEv(!mE#^* zccD{ma7P1=GR-~35*(s{;&)ul9fj3LmCMo}6po&+sr+m;fy3do`y$Ui3S&`{Up1oI zN0n;tW|jVGQEdgK;el=W8B%WdkBl3jA9<CihJgVd&qmFTjlZbPRXp{^$u_-Eb@a^E z%p3QHD~aFoT~42gJBEy19i=?+`|_MXz{VeeL2{PlP36bj4>|A_0vfl!`q+cn^5B)v ztb#jt*Q+zZ$<i=nvPSJd?ZIa5cvxcLOP3P%J6w~AyAF1&VlL&fyb4K-zp?e@e)h2X z;oUx>mSnRiR5k<ixXyj`>-QPxHCcTt`~iph+{S9XPDUjrX)v7E*%#RUIMGEtyD)7% zv4whx60EfXTRFr<A6|V!^)Czxf_quAzdW{*eQ*}zQeJXnPXPw-XL-l|2eg$wRc)}4 z|7sd+kg&Z7wr397qlMQST7-HD4fjn+QryWhTseHrU!|;FvW>$Xo~beMEjmMjsHy6A z?yZ6FhlJs!qzonJyFO4=n?8mBGn!g+R`%}4x@7<PjEb|W*7%b+>&i=~&mKfsN%6HT zAB@QNo32QjhB9OnOx2Ta=w20HvcO-o8XMd?*P+;2Aw%#R9$#g}JCo%nDO#`0@N?#u z#rQBJ&^{cs?4VE`xDt-QvI71C`ukyiPiOa^D_gZhS%8cP?(_^<t_8$b@7m;^%<Ktz zFV|J;`;lGJLngrb*I)P>cs8*8r%&D5W7qj9C7p{tW)ko4=0p2SH|R$3>8m%nL}O+Y zn7(RD)pOV%+ajJ>UqgcB!&J2@F*cB(@G>qta|b$7xT-#0$IYbZv4zBe$M4P>=j60y z)LTq#5qXv;yAGrFsUNmM(gbEv#Fo-HL4C-^zo;k(b?$WX+mCOr6>5jvFUU;dQ5*%u z6C;Jh#B!%}rALwIhv#Iwr#f`zfg=DZEL)=neA!DHW1lU3pzni-Alk`RH=L*LZsU*F z*KD(Sj$gQ853CgyToWCOKQXNX=Z+oK+Y|UC`_S~IoXnL4{sk?CmW=NA!24Uq<1Dn@ zk5?&Hh(6ak0XRE@y4pqs>{Aaed>=w;TxH_n*JVGRXm|)DjEQ~aY%TL_)$jD&R}z9N znrfG(Mzi|sN_Y879d>{z7{F?5nf?`;kzV+_o0i+PKhEuLe*9+=u;8|Jx%55x{ytgD zUiqjfnJ3*bVh)la)p1^T2JT!)mGwRNo;V5>$^en_4SNfWl>>Aqhf)I{Y0%WW?;-eC zwZqCBSuc*VWXkot-Ugou>fYH@HI?y$_N+wCMw<EJx1)gC^%Qh8JqYA|ve!np$3l(g z+|V~-%8joE1{l!a+#rlu|3$cZm-Gm&H^<wIQ#zCL<iMsfmaFWIZ`hh4_d};1+Zx*L z9xEql^@c5C&3=WhFQ)cXB@}*nUR(KRDAsI63W1#u5yt9VJ#y#}-F|y|jL<1;<!}VO zCe$La`TqdFuNNZkC>TQK;ei2pckGzWOJAMFe(h>`Fua-YErC|OVbjn$*E&UwdA#jj zpBcwPP#+}-W<Vi7I9V4pFPT}Pl_P?k7<Z>@$<e;)*3;CYxW``q0j&0V1arS?cRAUk zlS_!iOt$c#LpxG;Of=Gh^t<*n;}`aBONn&8Ri;E={rt+rY)Br@ahMT$fCV(vmTI?r zpJ9IE%x;5?h|{C2n)q{@(cd~Ls<-@y!Ulomp&3Ft4yV)Ob#2X0r19BgmX%NmU%rel z9cfQpIZOEF{%#hU)bCLdQ7F}@6l4;tvUFMRqJ7$oRUt78c*)~=$lZ-bUybWJ1>V5t zhM-$bbpHbq0$9_jLg@N;;YH~JGvRnt3<vyWWhLI{RrA-!b9>WX{TVCeyK`&Bn*Yv7 zC0GPKY{PG;Tq(V?>|AXw9fg)Y$DMzY5*It{339C~{Wedqe&NryjJ0>8J!zqp`>MOY zYU8otJx409uTzu8&d;4#u5RhZt=wo(7X20CwApuhSuZU{Cnk0LP%n0b$Q)Z0x`A_^ z_<7Uf8sfVDm5SH%L&ausfq9JLh}_R+df^yJ)2E)_tT*lq<d)jLURPs(bKQ6okAW6k z4Nr&8OYudgco#!ei}wGZ+!JYZo`!um-nez&fORk`PKk@J_ION}kOT|lxlghBDt;j9 zq2Xc&V15RvDHEiZ(5{fW5<jwc$F^S`zPafR9TYX;Ie!bP<J2Ru)Z{$b^XC4K688W< z<K_(G)=f?~ntS!hjx`)$84ovwPzhxDoacv7#`}&=1l?9h;Vz*51qarG7d@Jc$U<e7 zxYp&c$lLTLi(VMgCsyy`2TVTqpRdDjcKw+7xX`t7*ig`i13Q6%x4U9L$r`y>^|ymJ zm?h@Ss;oOXMi5rF5&#wV=7I!Yooo6nxWr@?NrN?2y$e~r+NED=YxRAE*A;#JlzU+e zbc)1vb>81~6jWM|#LaIFJ_4kCo|j#3vdzD`H8IVN*5%--W;_RK65d{9N=^n#PE@F1 zd!xgc(H@=-%DL-V&R5U->4x)F9+IO06S6mv=Q#Ln<pJRbaJR8x=9)PzoS#|(hLHw> zK-BXHV-bGq^SgL9N9V|`S(q|nMzy{p9FxN}o6NGodd3tI0xW(t+b@}TI6obEbv|c3 zD8f6|ZH7W`{H=D%OjJp^QtM5^dt-&s-o(DDN{fMtN$Z*$r}7Rp@~rr*Dn7*uq*d!! zSi7{wlwR>Xl2dQCuKHFcQfRwsvS!R*bQ)plq!lJi`$C#;M}vOV=LM2x>F>!jz((-= z<6FeWFXhQV(|0#%tKc60^wgv8F^0@pn70AX<L_PJXX5%Bld*FfHaoX6p?|l(dVAPH z7_wpcB5)xm*T>-B2f|mLWRR!^M!7h5He3P70lykS_3{gqQxS~U|H2kEr#7y;?(sBS z8e@_9T&iP{Z}115*?kdA1A36P^BfCE)Op%(c|JPX+c3QlNt`SZ2+EC|?;2Si_|@(= zI*Of*FEX;rI%^}wS&4HAs$1VElzdUR*Q~|vw!}CM#c)4#DPwq7*pd36+o;=NBAwuY z73}o>y>fTk6*j<{_ZfXf^!4y%=eM|qCOuG$&i*=n9`V6t0SgFN&VBvs&ztvuc({Kb zdvy7SmD_GzOGkp|o6NBnAL3lGp7TNG3wr4|Y~_gu6Q8&?g&#;h2{gX=<p)!t#tk}i zw-Y6?<I1je>#R2yhHe=RYP`ACrk`6`y#~!U&()rK8xtMV>EVahQRqWEuBQGlJ85|M z0L@!-B;hUS`m5qOdRt{Q=~X^(*hS2XzbQ}O)~4M#&`k;R9m?P@j+A%bzi{%}-Tg$N z;YO>djy3K4V(?zD0{ce(j7Aj~oh$KRkK^Al@1(G!6c%U^d1-Z-9MNYX8ElOB=yR$b zw3ME;6By6yoi_<qZh7pkm++oYu@K~dD@~xa4$ecEpYj^=mdf9qxhuTAJ)jReDL|gi zn(Z^tmOXJ-m&j^z37YFfj3y<G9Vr!5B<a<3`xiXSrQZnYH9BG+O{Qa&%121L{K>j< ziI(2}{eq9j{f-_9lKk8SjoPBc>QU_;EET<?KD-TVEf11#4ObH*?e^`-dn5FYn+LUa z=<PteW}>><%{1dxBQ6;kPyc)mbDXI80H1BQOnr!YNBfeTe*T`_Zo8+z3z|Q==O|38 zNadzCD9mXQ;SA0^JaeN=eNE^fiACOeVX*gUI+7lDQLj(9{+yTPt8<$Z5ZLfw*0N9a zn!L+PQ%fuYG?!EgN+d^G2UlrE0h5f<DKIJfp(q89{`O2ujB)xh+@ifE?p=2N|LO+S zqcazL_SUKc5q;=^hj9Zz`i^FtN;du7pw-!sKXS_>W<Wj@<+HjBM7ykhI3r_N9=|03 zTA7_^Q(vmjAVWsSz?fklS=sg<UT-I8@lyPqxNIErvxjUxMJ8>ckbw7!N*v<vwRzCn zSf`GHqw3cgGS3_K&hz_JGN`7tv5VJ}da};HvTCt;4zQlitYJH@+bY{mCvUEd-j9+6 z;_aUOS+Vr;ZOs`m*L1j7F_<L}Ir25k{tPYsT@nbH9@+|jzLeT|2@?`19>%l)d74Fa z4;RkXUv~1J@<$)}4>&KvX|avEaahD6zl$ONr0pE}fzf5N`&e01e_X_~$GOkLJ%Zmn za0~oZAWq~7D!h(A>3nzhC0<WO5gfAtIxh!f=40~}ZU?VK$x6)SmAnzRZ}~@?Q<V;M zs({7}e9^5xE>zbHs9L#5TO2E8sV_TSd;Qe$P}ckGI_>>DN&#Due~fpTa)yw(L6UIY z>B7R6o+&uKe@x#0a#ZU4_5mYP*>EJ1J5ry0+UHNbp>%^*Q1A30^jhIwP-t%4yZDfT zEeiVbX&Nq<2l_X+T<$%^Jf849dCjo4CMr6q<Jz@>*e6pld3q6YpB<ae75ugMr@n4- z-VZO!(bQW_ZLNksuBveiVO~)T!^4cR-S0=8XrPb1V07fwEvHYdNdJ^eT`UIA15;<D zQ2Q|b{DN;Os$}c5D*uy_&GR<P+T2_VzU89<yVDaLa`k3vR|CI;Id(`l6W4;t6R9nc zBmg_df6RhSOCg`xW{`cS1xlC4zZ<-Ff0gl;A7^{<`|G2o8qUhH=3AV-^U(x$v5v_P zk4N9#f4)efV;471(+*$F^V>CT^TTl7Lr54Y8a&83d8+QXFJ6}$sQPk}B6sbo(-+BY z^}~R-2to~9<$HeT4Y_pQQQKp!3`^RM_Eq}ySBdO9pA&MU!B)Et-*{y3Q|_HjcmDV% zMXk1-N1%UUxGF)=a}RS^R}@on!*`e~=m>ipasDm}wA4LUQCe<;FK|a1f4~(+08IV8 zo|kSJtGzH~o&Jzn9WU!ax8s;yY3b6+^?+)93vByazsn!^{{~m(Dio`J4eaZ?xkcok zcix#pXcq(?+90uTO;M-!*d826+q{wqEe4pz-)k6pZ<FH?!Q-t;^Qg#|NysE$1aB4> zuWi#MX5>&l?UumC3Iyx<XOM&pR^`RXG&`j>f9J&WL@r`RP<U>5;K~^h>!J^m-y7$U z+th5w6TT<5ck4R8dAaH<9*4>+3SM8f@$_tyXz$eR6#4pMQFVX5jZjMLNd{P*2ld@I zd*QXKKVGHxHnh9^8=XT{d*<&<*N?cEEnucsslaMkdiwLA6<)O|#Ou(t;G-T1R*-Nm zV)k7#Mdzm+?1-{|^W1(YK0M5LOWxE&l@N8+ZS>Df--p#O<lan5yrW(5?mdc~pI*z# zmP+?V(F8bHk>AfJmuc2n%CjGW&eu+ho*i=RwZL3M_}tvPv!M6sAB(Ps8zK1I-u{M7 z=70qPI+1+PA|_bMhh<5}uA66-=1Z>q8V15tEPvv#W!;@$cCH#hS8x6df?IC;C0H5i zbydrPw4$c#XP8Tp{Q8+N3H@WQ@SfmYot<|~Yk3MKF9n3o!tCKuz-laUYE{GMKuE)- zUPEsFR1`spGcqvxqUYdolzlX*%PfOO)<y8yIGxGHQ&I-++*E&BS^rZ&j*hom$_=Vd z`FYv=g!sNu5@H>}37eM)yEIW_P~ODuJ*;p2z`>oEFiX5(NO?griYcExA81DXR&j+H z7XrH7b)F9Fk~}jyJq(pAP#&MV@Ot?BiKyX8@iMe&4l)!fN}bM^M;&8<lsJ|>MW<>R zh(zRj$Go4~o^XpD;re4UUKt8W%U@60DG%_Te>6MO8?kF}d*aRTs2-r@m3{u{lI2>3 zhCT3sQ8SkIu7@s3ybyEq*<T`s?S8DXIXyeg<-3Wsfk|h%0zyRdd4RJOh*kO-I($+J ze%YC)E1TD-!LD`q{Lp`or*PmDsl0o?TsOr;{&r|ZHxn*MKI<BW*xim5l3?sn-dWj+ zPdA+}`~EMLwEuc~lcS4i1{0^#z~-cS9hN$N(yX8doVGq-tQ$|sn|epBR|KQAH9yuq zKv*aCj1?1eyYY8;{EHu#8rm~|jxh29bCkkP@IRl&V%YRpljzg#s@dHsGlTK4nEy#+ z9V*kmq$d2c^XGWq^u@I26S3u&&F5nQ?y6w!+&$T-egDem1tz;$VCNc|f(HUHeiwS^ z=gGf@9)1i9Gk+hW+sbQY1;D^NVr3ASsE;iquzJ?GO~w%jD0Dci*k&5>r<vUNsnC`V z_jmPY_*V`jQnuf@J=>F~z2`#-Qm~lN5efVE&5fRj_t*5FC=XL}mMu`$%LeZespoCZ z|K$n76d!;m0si6ivd6sz)Xx09%Q6aGd%TZ;l5g-4F0uD`COWyS{O;W&S+wu2>c5!y zj?dKk^-B1a{T@fO{Cm#>Rb5z+lAJy6u+K`~!>1;{KpP>86m|7l*Rm1MqHh!Th2$NI z3?vN4YQH+st#mAxL{1p3{dN}hzt0%<O<TDvuWb0moEPsS`pCB)y^*uMbPGXM)8v*M z-}FGVhj;3#B!bHAwKCs2BbUYnqkW(}%OSqV_J)jUgH2&(8e<8TU-6Sz?cmq&x_K$( z@vEPx8<%aoU0&5-4-%=Bbz2@U{ko7ZAMH+8P?E;{YP?!6xAz~zFwFvZ(EHd4$wkj7 z`A4{CRn=nbwER27A+STDrB0PE_)DGL?|$r#<}Q5(7PE`jih9qvT<4{FLu|-#UlrNb zls~s&&29=?>eNN%HXjL)H<c02b)4(=+DtuGanba`%Z|}Qlz0$%=~}dl;_`CP&*s8e z<Vu_2L2K<Zx12Xa5px%sSRcL1x||!rkz{)A%cM=2siVQ^EPoweNwvZ?=0p-Iw^?TH ze^+nGjQ0@+<=bm<+K+e9VyhE}&Q*;mWN5hlS*oT8_7dOUJ<oZrms9wy?ZJX&3pejl zN6Zt={{Y7m|FkU1;9yXp$LH{n#`L4=NL?Y^Ar)I;$E>DsThcIoTd(A06Hzn?<5`2D z)X;_7nhs*Vro@H{34F@}{p5hp1H^cvJpHrM`-r#ce^S-O@L>fSHLx<!pfIFzTlZkS z>%O=R<1LWbQ-0s)wZEEXUvX?%+dn^(ZPa4>qo~Zx@Qrsja|<>dVs}95p&#^UQuBv@ zDUTMta1lGYTba*qB!f}lP%6*sn0^0B1F0484t~cPY25o=#whpi9<joGuzm^t1w`zJ zpEpBB9KM<v1V2d_R$ix`1kw88?O#L6>=rjJN)277^d)S$oiq0R6nHG*&5PA+)PF!W z{@ZMClcKMff#iHLSBpJb`u(kPmgA>9m2<3kPV9My^!SQ_n!Iw&c%Ik8t@G6zdX{zB zx|J76NdwK!e<uz^IPk6YRk2!qW#>foY(?vsQ;D$0n<5jBL#Wc>`J)f6RZJZStMZnb z%b@6tA3P*po@s70-?q1nmC=e?<D83&S(~u+ZeKKlvJsU}4_!_#v=X0)qFe2~zWn9w zWlX@9l!s;g?gL(bN?WVReb`M~9(w$X%A74Yu~efHRs0CWrZ&3otsQuW8a%P<8{g_o z3jFH@SJk0_2=twR&+A_r&jm_v9(LSHYR@Z6#V<X-0eTP|;D_Ch3zRRBiIiyfYD>(% z(cXxKAlT;TJ*SV3G&#}Z``-9P-b0)o(S<n=o<43?`Q0oMVz{#sF*RaB(D@i6&GnIf zmhJ8K{JKi*uQyv-+~}iE{yF~;oMS81>>cz5({@(-z5{Zl-7JYBDh6ky#l+ivdB{Zj z@EU!Fmuiwh6;jXN&>bPTWy<^t;e>a6^LIhse?~+Z%)JZ-6LP%Zo8>1nTTJXb>mn8~ z|As|i)57DFw?Zpx;(do!8*ycUQ;#sR(N|oN9=Q11BN`P8J92fcbApnjq`qRm1ZZX^ zNxH8;u3F695uX;xY!i4fpYVB(0oaSz4d?o<1LU<*m0+3zCFS`(v8R&_Mb{*bC&t^o zcrYeu`uQo|)d>~nZ9=q=Ig^<RFVbD!bWP|DnG`Ks$dt%RvjDCzUOUl4Lw(JR$QxZz z(vdBl*M=>!nrAGOd=MN|w)-pWmU}JIcXX+|(I+l$%n52fi$UFX_2j!az)A$@?Wi2l z*YW}MVm!@BEbu$cl+avcm2drV(?#?wF#<LC2V4z)JrJCq;j~m%6#u2u;@3(I&>d(y zdDB0P7vSh@;K0;spToNedbWxzGD>zukIxpRhW)(v?;gk4I{wBrNQIQJY0J&`zA1>| zN7=05v|g~fqbN5l_998mhoipJY=N@>y{rDhB--DcQ3kWf<ys6yvYb@XeFlGuTWpZm zo*Ipm*9HTl<p4dgboVC+k?yz_JV)2u$#5!r2Fv?s10o?fQ&3(X7^f)3XX3Eyd<$u& zA^j0c^~s=%mh);I%fGG*RrmWdSR7Qk<MnoIiMSK(iXbF!aEF(FW4=NX$o`$30_Yd= zly80UVmFyk0cRs!gAKV@<qkkRv&+=lLHlnY8#dk5ivvr2x7*@a^=R&|Ixt*eRrew| zkTTDiWAQ!$x>Mm}@x5AlEtkXOX=|v#x(n@?!QD71Uh0jQF(VyTz#Xu-1;fC-C2-B! zm*(;o#TwVaF6d)gktHvQ@(59^2g%vX4g`}F8IsdM4Xn;+kl1;tT@!MwPQ^2{7jEYi zE6EnjMmg6#81G_2j1>WPmv_!-<Pl^v`+NYmnow+61Pi$z?4~)jlT*B)vZT8oAb{Gb zQ73*j#0=^C1KRJZUnDu*x<#Pc-RlHi183;(?u<MP+Cdpm+fjoMEK|Dkdw#e6eHH9< z3OtVH`tOlltuV%7>b-jhl^)8p(<9oz9Pz+~oj3to)7tcmEV&e{*Vn+yYqI&bh6khc zDA};Sl5hWv-8Y2e45+`M#->;%pA2cm2&0zmGqYuE|D;JNA2dwIB6i%-+DyX*BTW!6 z`av>9c>DTSt$uk2a~iz+$tv^82)t)Cc{FpC$Yz%e&}>H&-K{H|1B+C?UKwNMer46@ zvGc#b&{b;exGd>`LDh3txJ7@ai0_H)GK~gZ2t$lc`Weesq?n}M7}41@=E>{YeC}i= zxGONEZKorVbSp{YwG9!eSZ!5hdbFC3T>u%=UpNAeZ2VTTbXu$Ae5b7nwr^(m*7}YG zoKyJ32GA!t#!zTc@rSj-_3#aA2v>^r@xIz~cNYHoa)D73ImZfYFKLo*nMNm@p-kmV z{sSs0S%9cq0!i|iUPl*M*Hd@VeD9lhhZesK#9h8J{`P+;jw}h}LO-?|F6aTyEYl%d z9G}Yx?{m-aTYeQ}kg#jprf&8TtwJKJ3g1JI%lhGTMj`F?>MEgRIm*@i2ewmuDH4Ih zGA!UdFD;BYTi(>bB21-o-#;M9*_=L@e@{bQkL7GRx)C{Rv3{{-Tl1(`J5m9Z>$QV# z&iVCjU^>`Qb(1gn+n~lq?tyHyFJh4#FZcJ$*U0~XXi5vMUo6{Q8Q0gdgSPY1%PAc* zZV@_O_Z|1NUU|tMN*H<UWkx0=;X5_jhb7X!nqRas^&Jc=^7K~fwMEWQSG523<{*iA zyf1~nZ|>&nTAy+bI{}U*Y|&%aDzch-A_S9<=h`)Vt_{N9L2w2GX}6J(E{z&f7cp~7 zAxYN3cn&-s)eQ%vdn0C2pOj*M#vf^WW;eDw*vLE2o-(MIXW6VNM<WElzT}v%m|O7D zO<Ys=-U-{)$$g_DrZ-Mj7@bJGr@z8kt=_?!PYiyT4(m3&uRjd#^D3q)wLJ-aB}GR% zZ_A<|SwTSi5}+&d>X$ENr&`?SiVjO$t|_8eLtP#kY_Z0=o*mAm){~dnpkBiw*r9hu zqaQl(=ri#XC?D<Yuu1t_=z+nGvX;@`k0wcL_z%yG;@%~a_LApAHsBvALGW2?2dzn6 zS#|N<W2L`JKnXv&W_bM>D%Fq<umU%T9Y-_3e6Ux^E+Ly&Ng5ubBrLRQ;WJ`dO#IMa zhO5j;$2RiJ0zDW4O{<@Ul_?H*`62x|MrHgY3weaERDP!B{vTUmN`Fi-yiMh;$NL00 zt>IhanJ<rt7$L3m*rJ<(&`X3jVXLglRR$!Ll%F*fEE$WF(@uJTQ42%#1xy}yVCq7; zsWF6p-+_XzJwEba^AI6QmP`@~t&C-Cx%cC@20s)Z+xq~6LB85S>K5S)^~R|e4fq{8 z=HE$6@2^+~;4RORXp}I)40{<fkx^5+Yt={@bq0Klw#uNz#FUM`tBZU)G&EU`4Iur& zF95hCjJ!08KC+BzAIUZ<lU1@^z{1c2nb#1;7aao%KwXlZQtE!b=r{t4cNhfzeIHHC zW!1X)nOl9cnTO!uY|;0}qi*}uR-|C)l1--uTcC3MLP4?h8vv*KUayTqmfez#bL(Jb zIVG`9f=tOC!ZdVxhK?;${&)A8*dIISlY9$FPJ`icbtX9^_3Hdhfd(@E+(j#0+y8*@ zH-B?I6KXZEz^z`BnGq7IQBUHDDjv<VAG@vE7?Nn}3$7kZkV>m`JeMW%BS1fBr#gJ1 zg-sDH<Y&amD*$NUjf!)t8?(0yOKU#TTwhADllwZwohTBX4aS<0n#>ok1HR*JQ?w`n zC!Ve)4QK|0P-yYAep{Ddi!PRV9nTR6u2aS!!N7pEQZYjp#is&e9M1ZB*k=thQbg-U z0kCkX6`X8iQl$~Hd79&?09GR)jGL6_7{WWn?057Gg5M<Cvf`{A+eKRPQqwO7WkDpk z1b{4`SwZ}~ri>|1>W}7%z9;VTK|-nR6hWJNT@d&pW?Hm83lVX{AZx8G$Lq)70V4Rh zz>oKd;1kJKoc8FImqO7(8It!?!zI*HjKOlX`$^plF;t=fH7F!}+lOyxMGepKow)>J zUn$e}x4dCQ=-*^1j>^09MlZ)_xerre@Kf8F)KaQ;i&cD5?@mv4@098<s0DBg_OMzE z7Vtfjq=M8cqSo}oddM5#oDHXCb2*AYzf-9Qe4<#Gl?lN*r@3UM7##9z;C{n$aAjjb zh*0IP?4jlXa%DHrDNgfen%tTp>FCOqr<){zWu32xYIg#7hHgiZVl_=&$y{V5yZ`dT z`?onqj>W#Tkn4prxL97FW68j6;V}9eF9~FAKRjr)KbV}s8v6Yx23uowdL8uGC0y|E zgWiZ?fSL1A1Zt51=JKL8K)sxfhl9a8;XNBKSGLxQ(<a6(#?vEN;O#pQi9T>Q6l*>f zPtVGcxMQq(EP)9Z@{VQ0eByWBx~tkz+QARjfk|OX&D7wvPb!Z<dXPI=Kl)<pF!^&G znqyWn36yp))=Gg$JA4YgKp*VyHijXW3O3`ibR_(_>I$8z#7Qc_LCA$ff$Peb5<3fw zS1&MQmxaU;TAY35KRG?VUkbc+gY|J`E#&)g%Uo>drQdcdNEli77voz<%T}tdW_t-T zdN0r6s@27Y=00V`IyY^Lk@qnL74SEJ)w71zkS-TTd*@72d{g#K8b|(ilv5t&ieq<F zDTs2m!MWGLNGAc)BV!!-1Z&==ll4vS8EPqbUFT#qkrWWoIk)Nj2(H{05HW+ESz*A$ zni_)Y`4m5zW+$SvjT9n`a!rvIhd(SPW{h1<2BBXG2`u|tTTa)kh-pm^O9UlB6k4!X zkhvhX|6O2Qw0u@9(;XT-V|J_M=QRU~i)SzrgzPv2@~y&)$3yM6CvyGFUcn!HkeOKw zS6k!RIV^;&oKN6`xm^biVNRG_lJv-L`Dvc3=~Z`vbhtluDf$nW?)|dw|6Ho${*22? zjt`$+5Zcbot(lK&LW}}}Z7%fcDhfKel`F;Iss{SHW5p=+u~^N~j8@E{B+4)Xw$for zvc#x1psYbt4{$&jcjdHrS^>CnY0e4c%DAStp#`M*oEdb2KrB0zoG9%FvnPP{w2YiM zQ+`@JBZ1c+(t+_tXZEA*UGL&=QOrG~#2g3Gy}9(^EpCY-5JGB_*Tw1kmA@>7`HeNE zN70DY(JuFkg6DN@z)Qm9!vI)qpaj5`L5VSg!Ag*>{;WzcCCf#iCbN$??N0_4%tG=m zEm{S259qlRsDyxGSqUeL;jt8rgq9!Vj8+(a<_)yAhkA3_$}oYNg~Fp(H=V@Dd=4M; zs{|&}IukF=(bLdagQANNT>|yY22e@MRLhsJT6CDBg5}-O-7PbT?UW=aa)ymiYzVJ( z_?Mh&4_TqyDM1LYLEe48-|#lxF`ycti63m7uJXW9EAw}<=22EaD{mIxSxf>GlN7bF z>+|s@y8@WzF2lkgQ}Ea*g#_1kalA8G;FIY}do{HOjF-veS$?esj+G&4q82z0q?29R z@>$TpxoySjSt!KzgSk$ZYHQ!%jSrj`r$>OGETd@vLQ{gF>Pq~lDuS$}R9hB7<svX| zb)FWTYCdZ`gQBO<^H&rB9Iouqu?7z$cQnC5CIZ2fLbNQv-e7&e<PTEb!^&^}^r=)C zu>1cwzLL_GTc;j{{te(XKx=E$k}?L0j2Fon{~*y<(BbTfY}eACh701MM}dZW2yDwj z6Uc0qz5;@S#btuTx4*D{I}OvUyBg|yO@lPWZoV^*Q(RtQD?_#i?}*FF*P-al40juD zr6;&uYg<Tp5~lC^$N*OU!x~8VLulQ?H5S4_uOB^U-C0lq1i^%SI}0o?;j`m8;9g>i z@|dLv0Bag7GST7uODMZYYs3kx<Em7#>w@nz;s$AF)@zlQ3S1q7P;95I?Fk|+P7OrE zys54@UH2ILqE-+~S%tL`M{mvs{(`;D?3c$MapXB%am^m>e#r?v8cfUAA*rbPS)QEI zfHGWnB0%R%zfv93poJCa*iHTw+|(2ej#M5d-&E>sn@XB&F20T{@!nCry&d~Dlp(dD zIb!?2U<j@(Qewk59RdhYkG9+fRP(~GlO>?}>nsq3`Bd4Hi<CF!gHrkkwfNl#9-I9* zxD*$a2^z4I+hhs-Wy-uACDi!Gs?eV$0%LGEbLDFc6G)G^m{Wo_NEBWPDuDu!S*-*& zjsPcbigtEjuE1QGao}C+ZnR+wgPXuK0X2!HhG8=aD>R63+0KrP7_6GNegWH+@@<{& z_)iI#*YZsAa$%4p7I2G6(a9hYS&TBNU-My8>GD{woj2l|!!|fQO0H@D)&FyJ?(t0a z{~zBBLrg?XHd9kh-R01&&1rOSx`iB4kwa5DIBW<xZY1TN&9PK-=)h2sQYL3&qD)lI zOrsg*IOlQyuJ7;vJ?t@$>-v1&hu7=*I(-6<56v*+gJoOw^G{LmA8eGXo!v8t0Kf^p ztHPG|yb5p;QVpwAtH62F*4}nOPSo1P-k~K?shig{78)eKAmk4z?_bg*xTE<s$WKmU zF?Z?2G=pd!uJG6hMzG;b%hT&3+i(I!4YJN+O>y2&uXj0m!mfilisgpNyQx27d;gSo zUGP!MDZE^`CwRmMX2u6j2MR1!&sexp0Nz75U^6AXDwg}!H0}zlHq9hzapi@6g_=*N zc1LuStc;Y#)@HZZ)etF+_wN-9fH_d_Z^|aJ97c0qz+IRj#(sEOK)g;+Wb;bnd|m<x zQZ4qt5@T}5l#_y)R3dIJ565a-ZYb@k6>c!m{IiEX@#vx!Ac0Sr2UN-f@!8l%xg8kp zb+h_P-+v(KAN2??MxWS$I~Iq2kx+SeQJy|rcri=n+ccJ?X;vZ%Vre2{iy<atl@1cr zLIR|#?XCc>gz=Q_#tbEQU|40^KxB0Yytt87{1U69d{4CSGMxPebU0d34~qp1nWAKT zw~(bGu(B2}Kea5`*cRnnJi|N+Vk54Q#4ubsK0Fc%5DHs0+e5}~cj>oTSqqQX`o-@G z6Ax42f67Gc<_P&zEs%O*lf;8T`QFVa=a^a&3<Oo9|E61Ryej}Fvb>DbVsEfek<@6g zs8~#|8k!(OZ9ydi4=()#%o;(YgmWAI19{P1Is>?K%XH$5sKiLpDYfqze5+buAyaag z6FI@n3$ezvyIkCj@W<)Q26axo4C8G?Ie(n$4{XEugYe{TfZ1)uk+fRE83G7J;;a@( zw`wxGM!;T3Fo{n(c+g5zj{eiM0b)D0yHvEvchZS;@V2(3R5SH%S$r+D2r!rc2)RZd zBC7$35!gS7TkncxEzlV2t_5;6_1?dOFq)|CpoEuAPDFMHNX67i!dJn&hFYzb#qjlh zWZqmP<GMGFv=?o<b6Ll{^Z-;`Gz`eSw7~rrHvMTq@u-`Wve56Ljrd-G6?`ISqp97@ z{rQ$_iWG30ZLW#p?La{wnbP>XNLC$)@SWSsfTPCG4t?>W3+F&W#>D%>krMhqKmo|p zk4)hls|rZ5kj(+=NCH8>cYy&6M>f`~a7Uphak+YT2l48m6dw+G`?{DxBbZ#30meo2 zzQMtVWyYC6(tyPO1m%xjzP7%?<WNTef6XouY<S{*TmlLCBYB40i`c_o2L>fo&P>$9 z`1S(Xiu2RBBfy{nbk*dkjA4~Ve8dpr?;I&)chH7BG`;EfBMFO>(F9}4_ca$qZSLHr z0#!I`ZhOQQ84Df11R9;muwG)&)f_`b(+0TkuX)Lgo1uY+T=!&vd2>r9amPWg!5Hic zJ8EBIf&sB<rk%g7#nJ4DPkx5H!$l>T1o&=OtdoqLAg+O)$Dg(t=C-8wl0~KVd(yft z98>+lK{<97TB{m$Go8bEMX?Jww(`+lCbt_8DT*xyf2-sYo2Fp^uH?dQ2Tr&UsI8p$ z+`EeLO6CiNg-&zeGp0*ecr)MxJNv$9mJ>b|t78D#>Thq0)rpXAJYef7&~4_dZtGO| zG@d|K0M(zs0){cui`Z@M(j{^H?XV?g7o8KfT7XcKp#!K62V8R=nONx`ya7-J3?fg; zo6?CSDZts{n$#tYtmvhhX_KA6<P0pI&84`cR9sFhw`8dZ3jm+!Rm7Hm51A6sHXA~) zKqHO2Eu2H|LBwV88qv<kQkKqz!-mwCD8Psjfi_!i|I&n-AU3{0-~nSdbG2|oN*qtX zt<T#zOPSpJ-BM4G4<cH~YJjQq+dHmrGE>)O;*Yr4_%^YDGCUgut4*hM0uh8EbPOA( z&w9)6eJd<PMNGD{;6m2AtA7M?U48ROgoXYOE*vl>L4v>9C05Zn0{*sT$-kl+DwYFS zn=r+R%^Mq=MnsB#H}FzphN^-rxPSFU#MR-lL8h6*gveEPRZsfK#q=c}cEw!CIF!8R zp2|R$l-dIB|D~M^1<=sSy(-t(ND`87%khD<bH_wlsufdGjcho2s3*S)Ofax^`5xN_ z{Jj(NdwKMj2Hpn@6C%sFC+L5IMLf^2_@b7Tx*U_k*$QPf00|LJwR&Gx`81-X40d9X z4GgU4(xzm#2CwWp-x|Gr5wQ@fC8o!EhO}^7EgT-fc#U0BD)#-ciDG;>JS+FQcJsCp zNThCJd&GS{?sCc33xU|?Rpd={hO%2V1dZ}^ZKxSY(=!SEUZ(|i2PbNYLui0n%=YaP z*pzBzK4n%M+Zd+$02}P+*pu!SLZtgYWZQ?gf=s!p*6RMI&K!^)Mg`KxDAd%63k5=n zV!;e>JBSwq^oPB_NbuJPj;t6+d<`PfwjNQ@RDmoP4m(&}g*<CjIcntRv&doqIfrht zbyndC7X0-dxuGf}_}Z>^G+Z_IMnfwL&ZYCzlE((=Vu_EMnl~3&OMsbpQ0XChVx^tk zxdJ@vV&V3R)sP980dOeM_%=rGU=!u`#C3T)B77r9ejZ=`+k|W(r*1IcHoP*za?syV z@=5QOfE3J{vBqsai(aU()%sC|;A)I!1JXDi2p3Vy1tPZ8xMRI)S+cTtxEamGf(4)6 zhh^E_INRaq{RxOT1Wl?7Mv__--5VIa%7-QA_3wky!nx_x9Kp%w)W;aM8Y%o)4kfXY z4jdF0NwX5jMuBkCS&g12Z#g5dlh>SRBH-+(XIdtX9f|bzjM@)Mw>bw7*bQ|N9f{&r zC~ZH5exXKZZfn25sD2c%O+}SQ?tD%ioBLn10$^i~DKN-nBh>VubtXsHcaemsc;l0$ zV<z%hdC?2zSu4cjFGVlV6bK!5w_8l~QqnVKw4o>OL~cp*E95J3ugLJ6>_&8?#HVA7 zh6+aZumvP_fXiop0NJiRy0KMffcf@Mg5#L#Vn0lu6=Y02S7Jht4DE(&aGZJSucK|z zQvi&kl%&y-ytJG;f@2rmJX^Ln2bybAOVoAyWuy@-QH57)*!FciV7)8B)^yXK0!*6` zE9+LUb2~1H`88Cc2UhN-Y4APJ5)?$a^8SMX<xTohWh{n;kd1O(U1~m#4TjH3XQQit zZJMXS@Yu6So3gTlUb~D8`^Hk%jwN^h2l`w(ZT_;vW&J308V~@e%DE6^OKM=|Ym?rV zF_^%`;gSG}li}Q9{DR7x1J(48)_;x(tb>l4>c;QGp3u?X>CV~%81dFW+4##OroOy- z2gxk2!QB|T_V4K*Cx~0y{j7zAP;VJa?WI1QLS?&zSgNjIi8hYHKKT!{`|-~>XDi9Z zml1Hr_%89#N*#ab))+_PeENc<dB|r8O`ri(%T`ZHv-xU_svY~xD~2?@iT1z$524sc z;Xs%7(L3s>OE2FxdcM8@pA7BrBW_%&EYLovb*j>TUZ2AOxW8<7=}>)qC2EdbDIW|3 zk|;hKlqCv6Ope5$`aT@VJRV7z<*HhENk*?QT2Hi>h3pbSH+rzPk2(S#`nF;CJAVU7 zOZBcnqrqQGmiFZ3ck-QsQf%#Pw)EFvMp-H|<Tm}Dyv5f!<FvJd?6qjlW|XVn+j9p@ z5*Gp3$Fw1Tu+k89(8xRZ2y+*0PR$^Eas7wB|55Yv=$nGA7V#BG-9Mxkgn{AscZR~9 z{SQt_!(RnliAuxlqSlY~kTi5#K-HcU1Z6TbF^`EfPbf?{^R>K5W8$MBTU8o(muYrl zk1nU`#B#)n^&c*6a?S2V!#<$zYou7ETXEc;LMUtKg>N9&5xr!5)o36i!bv|pzk@+H z++9n{BKIc(2~{6X|L=0Mg{acNmK^_I8AoiK{UE_38zG=3(P9cHrlM2l1<23I=p&|! z*iB^hd??Vf4y=&A#)9u0&2Q}opyKcUYKWTYC9oV>6qxzcOzQ<(Sr>%1(?0|P_{+?? zytf_bn#zM~ErgT7f)$K_s<SWk$`JX$Flf{mkFx8z0I$8u?9_u&p>X~*xYcdYuc^`E zF-S2477g?sGvT}ToMgz=K+Nt>7i`5}%5Cx+9=NI=)OH8*j18FFf0efX`{DViAKTwa z)riTOpHquQZvDIUlMs?n2D%XB4*OSIvp|Lgyyghk2&0T|71r3eaQR1Q(N5M-iD`xp z)yP0+^5S9*DtY7g`=U?jX$9HYC@5+~g+~b$7D%7XeHozqXXC{o1ckgz6<g&y4W2@l zYZ_>86@Jp1CyS=jJFt=Fgt}c~P&AO5^{3pUN~cG}5Koh8BT{pkR^bJ(vd_?e@ooE} ze89a^v9y~B9v8>f{td3egR77j7ME=GsJQv9hIK#?T-&U!!Te|Fmh;c0(pgKB$gPHn zD~YGjvmyV;u+vQISaRtsJj)^5?hy9&HNe6BY?a5T2N=q^mutfGZOH9Yp?TrFIbJVQ z(CQ?4$VGA1NeYqYjjUj)ZA*YOA1Rjoku<Pq1N>|8c{rI+;1ctp=1j!us3%x3WgT}V zwhx2a%<dUS|IB%FOv5#H>r^?B>cqj1)u|t<tbeE!eXa@wBQ8<s{%S88>aN+}e{WOK zX7eC{hr5&6AANq~ZH5HZX7$VRzU_fItXb@*^LvGk`iXwLuje6<wOjyF!E*qiuBPc4 zar(J5xA_gC>(wFNOAnw~@JqmQm4jTivia#V!;3x72V~HCaOeTc=~$r6#^2vj)ye-H zJ2sxIFr&6VZ3&+ziK7y9g<O|_w;Pf%h3M|N#`3SnWbzGn6rR2r`r6z4tj-#ZD~!vV z);WLZ3wlkT(H*Gr_fq6oie^LNy1eJQoQ&O$CWZEBHZX5k$p=_`$H*^qm-KZKzp^Qt zp*sib*Vm=>q<@!G<Cy3?$zH_2JGgA%BSUMK2Jopfx~P`8_=0lH4cd8Cl;?WEy@k;D zcNO)qUm)=E!<IYu>1j4{wX5dYGhXWdfztP1ao}u;ZONuAoe%uAO>ITl%UsW#MGYL; zQ+R9qlWI01R(`2GGd^%^^m1e3B<_ZR{1y+AvdLa`^t`cuCsHl!EcL}76i0WWeCXC% z1Y!Xla7+Zv6t(JjfBrkU>Da09>nR_KM~NA{VEf&nJ#~-9CF43@@pc~b7IEF~)YH2@ z%Xj=U_eBUq4Yx+4n)=);f7->fFZ|#Z?fZKubw~Q!DXy9I=PAvF)EWGB1#tS<4S3<Q z+kYTm#b+PidD$LA5|w9gJ72Y9PP6wVe2@_LIrRtMZvZs+d)82I1<!qn#8UQk7E|no zckgy~xpCgiPvo9;$Fw&Zs_s`P%15n6H+akCs@u;1y@m9<p={}r0|Bxm(~liH07tb? zaJsmn3^opTsiE?)<p;M5R#_a|M}#HOgg$kgyzz8rWBV4rIL2mK9|bYjOnq^oqXc;B z;k*0c8hMc`e5%f%y>H;#aY@0DO^ZLASA`_9#$Av6n{~zfd;n8j7LnPqhcDRHnTYI1 zq4b9>;%sNZ$aTK3JV^djQ+i=A>BI>Y=YcMZwasw&w_EKUg_5wQ{Ui*#%!cE)ErD-^ zoIH=?4Ae}T)oq3fE=m2isSgOUkP4br?FIQn!N%;Si-=#x-lev_ZyWpkwWFm#8wicP zy~Y~9WbBk%W-EWVx#_KymB&~wHTM;4@a&h$D`vF}RfqTiKKXJW9d<EDgR9$SeSR(y z0vFY14>*RV`2TbDxbNDY_IN!pNsMRsn=MVnlX1?aFjxHC+@`yxjIDZz6!=_n#YSxO zd6B!AmJ981R*=v<-)=qyYvU}%VctqInXoVaTB{gM3Ax$I@hIMXdf!($<}v$4b`O2= z@$bLZq`f~$!6BR1o>$!6xC#WaV=<<@{5bt}H}LRam-#oux3#O6%RtCa#37OHWs5E2 zdV?lCnFZpQa@+kit7kc-)TfbnKKt+Csc^%w0sD#$NdsnEw0xZY#{SlSJXD1S36<YX zFM_U~Or%67@?8(~<f-g;x~s#>z_8cDm3wXsdRCl0vhS)xh-s}t2CmVi-2cqSr9Rd7 zOXV0=aL0#Fllofk|BR6FNo`HNYSpa5Q+|JXCIYq!9p*yQjO7E)-Q?@$WS`KRQo4Nv zvw7u(%;GS7vboC2Jm2AG?)R%(%+JYPw`DHBEwny)=9=Q}pbe`zSTrm@TX*)1f?%so z$`pi4EA4z6H&fhp2LT&UYV6$=bhk!t&^ThNesrYdx3`Yb?$EYh|A9zcRH|iQz@fx% z5Gg5E1D@9Tgg&D37v~=*gQN#Cn3*3=Voj5;XVVhO6-EHr$KsnAt$|@3Oh-%&O&vfT zKjAz}7Yx*QDH*Fl;v;$&ka7{mZnF*kBW=6%O=Y(L5YrXoeJlS|1pA3uKN3F*wQ8K$ zOrQ6(?^E>BMN>7<K-n-X-}dRt`F{itetd*>hlwg&<KG4Om`qTzHl9wPud^0*;0z`j zQ(UF6;j;&|YraV}wz_yuVb0&<d1E~&=yP^65Q1GO<M9Zq-5rj*zf$t-jFht>Gczy0 z8N&glo>@|nf5~>BKo~eg1BBU*cI~l0bZm0ra}djZ&yVdhw#TxZtY+Ocvqz}$&BY!@ z$1V*$2j@ix2-a5%WS@3EF7Wxj4~rSdeP$g1o)OrJXViNI_?P|Qz@Xl~?#G^I@V!Q$ zgk8lWm7$4LIsc2N6>pzQQlR52)__W?9Pt<I%X5_Zf~uK3Q3w~<|I$dGJg>5R2q2KG zLi*ii3St%_rAqanBco<@L`R}VMGkG`sw#6jTIOZrxAzZExNV)=byyxs*$lyayLc=2 zd(}Y1G3<sCIGuI4^rU1T%s{H;C<eOW7pwj6-gfsg_c_Yuwn?-b*!0A{C5&qTq)8K^ z5xrXIp0&4%u4t53cW3QS-aiscK(umam3r6+3(HRdI4{(BCIL1Uq@QWA@A(6c%!PXt zQY{^US8G&o)(FuS_wh;MrB}-Lrri6zgn7d`b21bN`98-7{M@g=cYz46#PFYO@^D~% z#kb7)5t#AXnNaglHx{NdpSCM!HJ_M(LCV+Pd}p`UTNA!<3J;gCnE|@#Xt$r&M&F~U zguC%I{nUKggie`cY}@)Z{jfoU>iHpH6r_IP*&`E=uUAwx5}+Srbz1q7&IWsS<@Rqe z{yy0gqVUd`Bk6LF6SfJa6*?gu3ir;O`Gh;38RTp+B{isLmUO2k_W9tUbeM|Ak8oTx ziidDN7xBt-#N*7hCYLYbbRu($Dgslp9d6~=X5)V9o$MIcu*GoUYb+!XVkNcx{G#&C zwKj*jI^$o|0b`IsXXBiC&I-fB;P`8b#eqn+ICzNSx?E!IDH}~=z+X3(=-8Rh29zhn z*8oDuPe<QKOny2&f#JoMMfn4kzBiuiLBy<+!9ZIiCqk6uR{gg6EpwUs)$SWJa7v!r z&7((Md9ugkPNndlLW>u8QPXxsf~1aiScFdyM1X1QHf%)fZ>nfuhM#?>*mB^)CQwSw z9`Ag6_1sZC_diw>djalnfMvUvzmKiCbBhYgcSz|c>tWibIT>?OG|?;R)s2TI&cC~C z?jB(O0%_jRQ~S-*U+?fp%1Oc04fN?tPCdH*hg@T3^$0pYlW2oMXFqbLv5Kqe%e{Td zuqWm>uHbYrp2S{cyw1<ct0~qP@JG<A)M}*Tq_f!NGpo0&?;X~iJg6VKmhvBHubH7| z!pZ6>H_$K!xuxJSIN6kX{;!E3b;DQ=!Q5#q*{*Tvs`R_Paz6swWD@7cfU18ld^G&@ zeSvQxSp?}DQZ{)|wYx*9d@+nW`1GcE7ym$~L52q<2wK%sR{3#h@0USqJR4bIv3Jio zW;;Pifuv_93FTj6mz}*6Qcfra)B}2Y@wJBQM9<D~kMah-y<*%N9hnO)w|lv%_<eAs z-&$Sqv=qlUy(<DnidyUrQ(CX&Wwd-%c%WpCg3QsLHEs6r&#!$6R?2)E7LdbI@mw*( z2t~JUHobgsSL*ZY!Uu8*ulu|7qN9E)68awQ#?#W5o3I;c;Vj6(r)p0XkEg0o?vuJW zlCwhA+Svf_)0b`pzIo9Ilf9Mqc#6p@yq3G^*)*r{u4CVIFBq;yR3eA^@8`1Nk=J5H zp`=rg1S!-b2i;3w)^?}7p4?d!;vAkvzTS1ud6KjdUe-f^I>hfEsPe2WuE?j00fLhs zadoc-uP=YY;G#9N|ETdo!nl0^Q=Ik5;Q2|9P`n(wcbJ!wc*uI&5Fzk>lvJWgziVKS zVF@h)?83Ng+gtdM1L{rfp5ULS<}ti-i>Up>WOmlO)QXb9f%CWn{BC03lco<#9U8tl z`s!3;UIw(cF0eU&YRj;q(Z|*k;L6=>J7pw%n!G23dmypIE0rp5As1^so_OfnWA(U2 zKd1`#Izj=EPBj7I#;i(|-t@UN&<-E@kqc<uAbfAvNY~cwd|0>RlM{Lt`;r=6y8Y?V zi=IEvRi3cPJP!+kTFC&D46EKBYNIQ69f-#;Ba|XBH4(LbxbM^}tFlX)vdSSE8>BX@ zr+;4Lw<|+OUad91w4e*SeiK{$JkHcn?yDfJ2$trFy=FRlbFX|%E7u@NT7|Mvc2^Rf zeWqN}Cxy-t;+u=4Z%rcKko50qEcPLz!wb&%PV&0`#jHRl*+jtYWg0Y+$As+4YXI1< zSI?V{|0K4#s})4KkkchcNlS%MA<@z2eF*hvmF=}_9p%fc4ZwWxdq*&!^gisANHaVV z%>XFsW2P3x3Wc(gE#$lb1klGsp13btAt@U-_1WLYQ>`B$VbVHk^oG)LcbAV8DV0bh z%Qh~uEh)DJ9#Ob`TDFt#YV!lgDXpJ$A1;I7pxgpkS>f->%C?Pq`#Bm9-eyz|=l6Yx zI)+c$cRPW(Jn%CmHP?72zNcC>^5H>Sr_dxs7`F<*_HeE}IPH^<b$KN}#{+h)M3TeO zxVc3`OHG2Y>$9iEx3bc+qtqmAgxj}X)56lx64NKSW%|>`amuU#<^EiQkkB=Pbyd`C z0MhyJvitp^5^nM8>(b}XZ&i8(Dk`0yko38G^<6)FI&#y!fG-natH)c5bYW`{qSlnZ z@d+Qkb$F88gN(SKV{jp_s;B0xc|U8bxZV8X1w4fS<@Kd}e&KHaF7MCO>ATl_lmY$u z8kbS^A$DxRyV+>fNISBF@Tx7c^Mqs2&!x5IG5K5<Cyz?!#m`1bti>wu831>1D-e|| zyb#bG(@xU&g3a*;nfh*Flg8SoN^)Oc-ssg64}dPe_Kc8q??p}<8m*b&F>ICNZIjeF z;*@T-F1jE`7YlfFi9=76sEjdO@&@1SN*a1^*Pa5_8}B5@3CA=F@1yqP>^VeXO?smb zpoxjs*?94Lr~Y71@Hu_NYw|$|wN_>=U-9yrhxvr@1Ob?8GV!~9_xgw5a(}K@l@S{E zOxMa6>DryEeUSOi^jPbqyH)$zv{BzOle!|?CwTmxw-3!hLF?kt`HqE_p_4W$Ygcn7 z5{&VQ?0}V$zrLi}9ULdQ<lFZZT+zYkmpHIgH{}L?*Sh>RdZ+nmZyM^M`S!aIP`UTd z;QH2^0<@0u7tkUd4?)>&Fx;89I*Z1tBM|pk9e0GQWt8JbHz=hwXw64*%klDWqM-MV z_}&qNFV`M<_F(I&jj4c}5jkbtCntOD_vLiPSJvE?%xdiZ?>$Cd^4b()9vCC&`@8Or zN{_qAH-o)+)lwbFp=5Lc3k_P~B4-@5K3Ac2UWNh<!6-n_tb9;W(GO`F>cc`&k2pF% zWSfI*zDzTB>a!ce9-C{_C)@YVA(YQI4hS_VfX9_LaJ)|udD1gGy{cko&Ji+N=h&KQ z^dj=pnTqYf;%njn7`b};e3wb!(L+re`A6*pja*Q8S?SI122t<Y9$wJVeQ|(`ZB#WO zUasw^xS&xWkg`PAe;;KA9x`p&J6=ofifl7+k1+Y8SLc?d4e7~LX|A@6-)Htu?2gn5 zsxbDS<KI0!-uyT<an(~SG))OFEYF^MuunhR<YR~>92k%Z-#q$K*eIw32kwDQR+aJ= zpeaDUl#S3EWFzY?wN$FtJds+PxwH@}RLh!awKlMQf8C%0j?-R)P=BIY1P^YPST*3D zD#DDFu_FC8d4`g}QQz}UTD$mAZM7;&Tc*}OqM!|@!!<gb`Axsf^^v%cPXXd|D_v$i z-#yZ=kRH?6+}1YlZac8-{}tdHk_B#PNXM6U1cHZH6V<q#-eq6>F8I;)FRE<c{GAVx z!L)md<0ru%&o@mofxx5>(IIxWTTMR-yrPJ}C^RWD|ML-JPy3e&4cAO~AOx)?<&#Ic z8P%gD-{?_XY16+$+{sz_OSDE_=VM3zN<ZO_PG*Z{Z1yth>Es~6i1u{w`9dE0)2_t3 zA44$nOh5P2l;?2|&ps9%TTT2A^p~)mhw?rahf6E(ynxo5UfWCL?e08iRj@Mn8NXEi z^YYOHM9x!L3eP4<de%_!PlLAYg_X{d2jbgB&UN+6`a9X#=0(Zpc7I+($j!EwvqvCR z<K8y>il<MH>*OE5kv2?t0RUnCMDJm~*BZIY^4dV)2kUdcpD4WReN4@HGS<51jd*7j z!DiLq^w7tw_>p!!3pCVxV9NMP{XoN`Z|kv~Eo#p9H`d$Bie%9%?u`gXpU;16C0%V^ z`eweJjpX;#H-0?G9d}P0E4B3%zZu_eq3rlu!vFHX=Nx*7j+j$o3pk~E?=Lq85h9uj zI4#^%J&5ow2RToYM4ROZnf6Rrto0|xe|c)3Vpx+-?KUn?cR7>gZ%j^8pu7{b$wU9% zG~u##-#EYeMTMx*dSBcx3lT!xo^NizieeS^?KurrbHVbUCZD)8Kp%4BA1-R(?+<Cv zmO#wg_J2zH6Nf28@9S}0_AM=g^sCidW|gA@gcj=dE3TZ&t(c>|a|d~`pI^c-*SmTE zt)cgoovu`X_+T;{V*cfpTC|@eZv4Wp^^30~%)UJU`D0dE4`W&0H`BNz-2ULD^5guI zMi2?}$099pS%3+O5i&a7WUD8NF#OaHuAFpQ(XEqU4>H}z<i}AWoybx?(9~rC7s5*g z>GSIV1iic>I|^7pm?;T&KA`=CBK}?3*jSS*By^U_ZanqQYO5(8F4BHxF^pxS-W)(E zbcYo{{S(Y|j68dj>!2SbuVVMU!Xjj9`-AFq%|3ODxoTWvsLT5Nc@cyykl_w37x5DF zMy4%lIT1yId0;aN2CzQ`MN~sO;*XUb*V;HGu=)XliA&_p8nX1SVSh8s@2n7Ff9Sf? zb!|WmX+J?xgBGd`&<aneh*J&w`rYa%ZF}0jvpQ2~AWD8wT-FkERk-OAVl%N|91H!R zw;v!R0cd;>qz%i7Xw~l0lZRBi#A(Sjva5hKoK+(imygu0U8YJLK+{h3@$I>EVJMk( z6J+Is4l;<G!WEvWwwYP-lQ^7PO~d!i^ez>DVVl{snGlS*N+4;ls+b-)yxbnfC6E1j zaczVy9HQ3Otrwo5WDJ<98OyUM5ykxl?Ojm|@x=w;`Y9Nu{ao8{ps)zW1_Xk|YmjnO zN506MF5%|VW_BF|y|tq<!v|3Gk~$!QZCl(G6GS{3ko=`Ehv>V_0d>8+Lq6l9_E(t9 zGN2v`ivWJ8VS*|J+zs%p%!<L`1zl#6lA+|@@;4`txKB2lsD;*pX`rj~fbq^eD;ev{ z%)2W;j$Qzmhi9ufK5|U2Se=H=Z>;L+_#;GTLjt=IUm0uI4|XzsFRl0D4+~0799j@n zSjaab5&@S4RwM7F@?;dp*`#>TE&dbJES%h?4c~1uWyw|dM*~1@m63af6#6C}S-PjG zNktRc(4{T%DL_XcqPR2mfkhUdMXZNrX7|jqKz~#OORG=@!o|!4Wv9HmLN&sVo2REu z&eHPaftKmqJa7SYf}tKJupj=s35wNzZLK?$m=;C5sTT#yX{Hbp0rXqaf`Per=*-yw zdOnNhxI9R|*eHp6Oat8p4%y2iu16h=gyMj>c+_qI)Mo6Wha;sjCu^J`-SswXuOAIH zT;%2i2S25&2Rd>1r^KoJ?3$SREJX&Sg2UmVhn8Mm*#-ZiR*fKTLzQ}rwKs`v&~d(n zqz6uK6OVwkEEI`ao=xM}J?W1>26K0j*>EoP21aI=8bTJbxdZ7TAuLrLH7NNDh|qNz zN5cajKg!2B2HS^ko}*>GlU)^$USz)&*k67_GIxrO*8w?*pLz7>)KW;es8pZrU@KgG zxltEsnP$VM2+bB-4I{&6BVg7ptR*!eB1l~RlYT<f6%u?bOec?EOn?ErWz-1!q<n9o z$*Y*;;Fv|q9?F&r^{c+;bBt+3(@fO|$pl3^!IvxUlPoVF;BB@{&yY;_i9*E1eb@(z z9o`<@S4u07FT{j&X0ADOM|Q=UeUrpjdmiO@l<8AVLg)E*09X>VMFjR3#eFwA5oOXx zR5L5XxI>H22ukFKn|Td@Ks*JY8izw2gM)9T6P~>bU8XNmE%-u_j+zvV;p5VW)b3n* zm8E&KR)Lx*TKxtxO@a=Gz^+gCqyJ2q?0DUKn*JeldHj^$?gB8&#c|-rF_2oFRXjWD ztGJAOR}^u5ixx!>-JX9+p*bWTe9?)>{}gNOxUlI=b>+!Xq2{>&?sreZi~5i|nh8>? z#i)sP%%P2Ds*M?ONExG^&O}HYV#8HyVgVTW{CzbUqlMkD5PjODg)EwWLLw3rq3kL9 zanHjbeaeDPOrXZw&1=t~sH4R6sy>y1Zi;w>8>Z_HP?3eN{(kbN&ejJLut+BJQyvjO z+Tf1~$q2c+Pi{Wp&x;791%Y#pKrl!@;=LY31+XNWl|YoeA~B*Ue_AuW1HIwc*(AQX zqxPdWqec9Lcr?{`0$AV3f4dv9F9LNbcvLqt_bUb{8={;;n4@AGFx!-7AGYI)Olf4G zp^QmD7<Y-J6f=Ba*mIF}#MoI2BO8SX7vZ{e43h>eQIQG)#~43z<J6I4juz;QZW<Pn zNp0!n+c>IP2&&X}e*9u}Fd(Qq)*FBrwo7T7oBJZSj#(hS5iW2WtlNiTKXEftU;;#J z(ssNITu0Ef5!wV{eAF6F1T^D1Lck>XKjfVQ0*@P+h~F$BDWB~}>4u|8#<3Cy(^TG5 z4c9EW3&KJ#3SAaRPe3?<F8+J?HwX#={Z8NUQMPQ<pcTrrXjED3qb#%xX8wVqKY9S- z{Y1+a+PHYsF~=pX1Ib-?u=9O<Ve!)&fAk1ZoAQ?)ef%?Rd}3YZE7+z9v?U81bStir z0X~7IE1K|DJId3?pL~dUO8$MDu2!cerOhxXL44zNa6bluv@&<F+;p*U`bSNQ1$+&? z|Ky(SG*DNxu(4<&N;VAg%#+wdLN@0+y^LWzUu-Pmq~B8s;uZn2rjs3eG)X3ExFarO zkXtq{ki;}waeN^N#G?~MQ-iyYsWi0%fN@J7+c_(cT3&Oe$^A`gA_hn$aDsf1k(wYk z34W{!g+=BIL&LPJqo8RI;5Aftp5p{+B$$wU7hWE^qKhuOXayTh1R$>h3pr5wtbTU_ zQB>T%)l{7ty0p_!c=Wd_5otorDJorfNmWh2n1+7?9rw{<k7)S#S0G$|=9K9bI)XO! zXKd5HJXCd6pb=uVTjnx4KtWLMundUEo#Y0e)c<DP*cLycRyoH6DTdR&p1X^MrV%U( zB-%jmE)1)|Aur)c2wbfWfL`$(#C1WTjoc{{7h8xp)!5&Zhs4Q%Jh`FAeCf_1Ql=6z zhGXS7?bGv!=?TXBrF@zml`gJxH)TMQ#`4*&e))hhMDuHBJAh?nGJ@jtq89!KCVX;% zU|~Xh4`BduXzlR?F|a0?4#bwInt30xqwb?_<Mum%&bv@xb?aP4Pi7F2-I>ZXPkg2X z3UpGHbsTLjZZoUT8pS~FNy&4q3@fz}gps!rrUn^MU?&;WOoC%^T9Z>6j4tL8EU)+1 zqr6jBqmqQ&!o$+4eR1Cf|0Cf0K#+`VwPF7!@}pnSX_f%l*lf{GX}4;ylRhBKD38yY zyyFRTya|HlC><qO!&&An{BsY7_4Jny|74e!BfvJ#8h$d{_65!2>G57a=B$9&7W(R} ze#%#ITr~MD2@Bb(CGx*PAVrd3=yz*JA8n&Dz1a9<Adg{}|NJrNIx#QW&k3Ze1)3;E zte}B`ii1oG>?G+9d<FLq^ZN-ZT2ZQrHQBv=edB_LB~v^}tp+gIfbRObN}8}$t;?T@ zFbuyXEBVWHZ?#q4Nlis>@_HAFjJj)g8#rLN`I8p%UE`G}#C;I{e9F1pF<ryJtLk}V zn-$3yAV91U;7=y6F@=nb2*C_FJ<~#luv=Gg76_5uyj>t>$AgAD>|=~ubp0+MMJKW* zdlH7?lHUSCyi1^4CWL8=4I8$DyeEKB-TKfWCI;LYz;;?`_QdF}Zs96pZ_ET9)yxFc z>jz2bCdeOkqDYgm-Xjd^Aod;ya_bVLkZsmtPgRZ#`yi`lfR5r9P}C?PCJ0d=49YI# z?FK&nw?=drK&5fNvDAd{jhx5_3gx2&#L?N?W(}9*B*rp!l}Yh87Srw9z6-J31jB7@ zR>mpv23NBepniw08O84k{SjUuu6h!jho7lpd>ee(c49AATu+Veg33t<Wcv<nILq}9 z-f8;6f>LCG`x15Unhd-Qa36n=Y3j>=WE$FdZYCv2S_LFuw@#(UxpKgRubT6C4M4mC zl5|&gmbD?$ZitzTr8OX&rO|^?2`|uS2;lxd-!%RJ5d!rt1Q{Npb+Xs2Hv~IMy-5m6 zTTdJIhnnP8bLmO5btNjU6M1#_=ge9`nj<kVNrQbeKjd%1!>;kEIa~cZt|2hukC-t# zN$}D#N%9UblmAs9zH=<c@9iLX)^Mih1^A>|ajh)4>x_+Eehr1HI;G9*nx$*a@O$&L zKtWP$$a8K1gi&`?O5Cp;LW)~7uRPJPYrx{mYEjkZYe|)n^n80Kv4jH3Dl%4TwIJqI zB^_21zGyK6kjS6_qVNMWguJZWWqkYpuatev4GZLU<dj*7-U<I;6#(74?(Az}A}PI1 zv;h>K!-9?W4MIF%zS^;bBVm@_0M))ZivSnH^74|G=56*7`!_)O>>iRM>S*Zq=tZEY zcf33?i-;yqLEjvWspwjW1T>!PDq)dmSZNv_Gn&H#$7;8iKfK<YFhT>xCj*8ay1_>S zCLmohMzN6EsycD_K1%u*2%zQ7<$<Fp3z)*To>M-u@=yCr<(o;WT_J$0NhlO)Bj4K7 zQfrKsd;gl%I<hPE<=v|zjbFqGL~`rj@0Zn0jSQ=X`o@$%>&q%v2ZupQ7&wQ3nX%Zg zkRUd;fq|P2SE$v_I!6Js9EM#m&ULP^&s+bi$KnHw6PLkN-Ka}9#5uG_6h*5D;L2!K zA2xSA*+@|vOSNghoX4oBK>DM$oWxGZ_o^ma=&xC;jV0eSpE{I%A+d(R(T<X1gc~*@ z^#`-++rSnp>WOJu;Gu8<MGegDdAfuUsFz{PqN1ERz6mAhEDm1jahJI_Q*0?jPYX2J z4Ng!kKrV_(Y@6I%`rfY2Z|k4rV$M+=&GRZ7T|gjP;Z(c=3m|k?x64t2Ih%-h9Va)8 z3V+?N_rchQr*O@Q)uFzHf|x|LdH@mydhCf0k}`8AJ7}$c*$59Dj7l@(*8$-5$W3R` z-H(J8(<>xoi()nCSRqs+@Cw1gg|__dsOpiguAG>H@Rj4FQo)sBqtLv50PGJ6M1*x2 z4#TpI4`Nk^ZXocC4#`LX-yWpZqyn~*+1yVHlF96fR$~f<Q$T#uh^07Q#+@491Vo9< z6^1}v*1)sZo#Nb}lU^ZrfGuCD4mZJkj&SEUNzs1a(2`()vet-%)~UOr6Ki%YQFAfe zv7T(JZt0B+bU&E>ObP)S)aLbo4*B5^94K;6Gdt(TNNV{szy)@fD}Kxq*06muPJSUh zwZ#;#GDDlRgs3ZuRUpb6R0_lgYw_xNxeKxJjGnX*rurrx&^4Ec(ldWx2cvgmK<5DD z7k&FWn4%{=)ah>)0(csBo3EPB@9IU|7HP9E9SIIN@8Xw(N})>$lF+!=x?-^-WJ<9v zHE#r`<5c!t#7T3I9L3qCK{6kT%LlmFbitQ)(}4^&%Ith&n`HbzAzJ60LpWs*J?!NH zf)V#mBZ!#4%(o+4OojvpCHAWU&vlDJLd3Buml^Wt6TOx^PJ#tD-@DLs&#)K^iB;J| zI4c^my%@-1Fr-+0;SQQQjp3gg_q@$P5F*)CAB|myo`Tcvy7ZZ<$uGT(?WB}le23e1 zRZ0KYXmAI}_a%~tFbw0p;ziNgUj%{_sD>;-N+K5M++FB_fCFC(&@ug1e(bUSsVsVN z)A_{6d9((YvYGb+I1nv6_cUrk`+AWL*%Ef5XSQB2!`w<x@^v4F@jeJvUchp=?%ZlQ zkr013UK)vequsGkt!at};Va+(t^Te+gQso;Jk^86r~PHoPA{WZj~9r=`52}FhLzq0 z{<^aSm=Fqd<|?b)LK78D1W6z8Cjhy0_lG5$;%w9xsU{Jv)~Ur$EzLq{Esz=K3coW~ z^g@*4fhdHZXMIj&JES<C>I3AzKK)5v8Ubyra^lYMy9dV|F4|5-&I~Oum^wpF#I`Yq z__n7HRW>ZpRaNUw5DySS@d93DMX;{m2qgw*i9~?*oX58zKIDd|Mec-gUR(W~mRFB} zRslMG(tfOJWc!9=wUB{;H5}^`En0a;oTK<ff%%R|h}N+FhlWCsx=FHABhaItIy;o5 zu2?-y_xt_GObM0?n!c{{jI6PzH?JT*6{Oio34|k)gP*+w6zEG|MFY)=HV)?Jr?A}m z8)f=NJ>WSTA@E)syx4ngS@)QiDE@#m0bl_4jy|!J?!FDyiv}v-BwI?wIU#&?#zIQZ zsyhnS0tX@|AV$Oak0@Yj!>?=yYjN`bXf|dg(mGZ!X~dS_0$7l4AqW4`Chrw}C4VjJ zZkIfCaa()Bmw=s_1#gCJlK-hWmhTXIPfN@cEyr5ospXao==RG!b1;TsxmCQL^qrk3 zpp>6sjXPLdfSsg<Lx{Z$R0nCl9^fnLW5g8mMA~`~Ni8LP4&A?x3`C_RUHDm%mLC}( z9TB|q!KS0g@yNt;dMPb9NC+Ag69gp|W7}C9GnSw~XCN{uEvQGh?1Qw-33S15{oT+F zmt^~5*Yo4~rs>@Zw0MRc=v2F@Z$*0kDZ6Lj4WRGO!f&QTm9#abliTL7{5I|I315eZ z&~#w6tpxhDk^KYqVs0}k&P~QDG>PNmS8g8#)A===@q*Nn*#-UKbmIQ<@Uh^zRlbEX z(>n{HkU4K>?L?3Ssc`(lzg<X&sH>AR<ROXVlUiwW;+#q15c(HMS8X2_!39zCejadA zg*UOjMniUDwcCu&QBO#A;K})RaozA06<qqx?VR0#Jjugj@8`pjpQ3slEM-0`aq!Gn zP;?0=47BqBr5?D8t!l%C&R8f=ZCBV14UW%>nNtJkGK<FFMa}bQQp800vo;-#10H4L zO^CJmb+^;t@XWV9S6g5=o_b_hO>X6QG1an<o!bIJ9rVnDfx=0jhDH}4F)Eub_oa;9 zA0?c-&;P-zF7V5JlRE-N>X|sJF)`3Ne3h4kDKFzckd`L3pS4mX#)FlOJZLlKJww?$ z%QbzRYl3^C9QuXN!V|M#CW!RLmBNh&UsQsaW-v1|Rw3ww%3!Rq+87T2_N0|Ti(*~5 zAGHnBmleZ#<-R>xgb;HeGL&Q;1v0Rin50>DQvmiD0U`sl9U@u(BHd|pshZ2AFW{PU zE3-Ed<lad>&=edAVTlXBaQS2_=_^(yYEbkCU3pI*kommIJdN*gIT@&{5#eGaX_#~q zYyC<IwH8H?$GkEq@R7&PnWPjuqOlqa`oBmTD{@px$8kp%R2-P%iBkS0NGs}@Iikx^ zJ%xjJ#AS*3r&2({9at4X{x~pBQkFhIQ*~6?zInFBR>kcLkD4_siPG+hR<Mw5mod)6 z3Y8cU!!G$ji9?$*CyrHBH9ULi1KO&2WU2}0HPnGjjlyS9M#L(n8BiPv102UyJt6D) zzWv`TCwSCZeKrD;Z)cfi?wzx;E0@7=9w`RDc@L5tE{$Ge1>LZ8q6~=ZkUZ3KYn)~8 z#Mg+I!{IIRjV?{+QeVc@mPuj(D;?QUUZrc6WTs~p9qoJ%6x;~+Onp&!+#iMkvrMDn z^Uh-L%dyTDbc2wOOk92F|A8v?Z3uBwTP#$OA+6_$<pj<lRK#S+Qi9sRv&P`=Zh+K% zZvrOI=yt}#N77W)VfS)VJ16n;d;SB(JjpTYU6RkPNFNSF0Kcc!Nn92>>_ccIyyz(k znIH`eD+9*D6pL1?MzM$)roxaCr*k>5iCYCYH+&k0sH7d&*IRf5>J*J<EnbX8=}G7h zDb+65FtFS*Ae{9A$y%Mldt*u_*SrW5nU(BrtG-eS)C<DGiI~qxphYS}q;DYuPZAfH zSMOM5>i%54*B1NE7zpz;@K}3{1m@b7UsJQ2nc}?Mmri0C|B$QJf%9%`@TKb+l}ri; zCW^X}rYOTh(2j70-&Fj-Pv;>+d0OCgPhT*HFv9xvq{b1$>TJ?ve9%6pfNgK@>T1YV z@gcMTaUuVISQG$6j%f?^<@A|#7Xs7AL9EJ`ncf{0UL*<f?Q-k@VHgwsP!&;Kg#}DK z2<%~EB4`Irx?K_1*l{2v^d=NOUxhoxg12HFF(6nX8OU|Q-@J#<AZD{od&7m|1dFCA zX;U9(9r}W$Z-#{+Z-C+JantAR{6HLYTMN{ZmyhvfkMn^J;=Uz^m_3v~$E~VTs@7N} zMWZ~UWls1h<R#~q7XyuKZ31czNPRH34`;2rct~t$Vh~)FO`5}x!isFRT1#)irn5@D z#fu6AHJsK)k}V#T;pM*g5f|U_WS2Fm#gwZi)D`P`RVCAch<6x{V7!oUslu{j)S$me zYD#qOA!-DEj{DI}`&me+NMng8`qWdpnEH|^I(3lF)Y?-@jm60qUIWR0Rfv=$FNbgT zRs{yk4OP;`YEx8`HV6e#)V$HGXF2zd=-G{j_T}kY-tsw{<6O6A`8fF?#%UO<zJLKj zi#^jM=PcT+;lLhj@v|KWydpXSQS!+oPgw_KbB}|&9I;*UJ=rJqO=@I`EWZ6RdL)Sx zHpF(s{~{gslx<L9O|BH48Ze)l@Gr(CscX&^qmG(aGG$>Gv*ed>?FG^i`e8o$R0alk zj_r4pOmaBs36tmKzhXoZhrts`Xo{aN0oSG7Q?O-HMr>13BY2SZspV&bTq-icQ(SX) zTTVMV==cv+d|Ds^D|WYDbcWd|Q5}$*DdT>X*+4?X1iWx#u#38t>%%wL+fcX)YYm7} zd6R4C@b*WHS?DbS#aFH~k(ML7C<OkMy5=V(rLY>AK)nwU`*c=pk5PJ9dY)`){Xm)R zE5o2<_UdAjY(`@5Hy{Hm{#PA$JiimMwOHL!;@j;<+;mU5+<4_vnhzLAzbqG)yRFBD zeEqG|^$Qo#O}+W7dd~m~8u#Nm&+6BSkZ!}btlN!^B3*#Kw7h@x@NjtUo3|92cTa<D z{EaR3z`v&ooht<RKDf9$50;xF2z>LeJm$3Yu5BRhqP*(M*c?0Wn|uA`-G;tJs+ri} zmbYuK_VvhX`?_u@*Mzuk?zkC$Rt~RLfrQWX7fbC^ysCP$ty+W1xee(ZtZQj`I2j%C zN)NitrP`w3viNTE5Nln84m~rGIznS84SD1|oDVy-rknBFBrku$EiliIs^N3`PBUaV zQ*=4<IQs93=eyyx-^L<iM~z`)JvmE9MJK~W1^zGOgYoANoH;FPn8f{o-+saf)gbJ> zhk8sKlZ`r`rg1OisRe<Z0dG)!^cLXiWX_|Gm!QL=eAc)X!1b{As=kC=Hndj-n60?n zxqz!q4X4PGfuPlnlUAt~mg()@UUImI&SZ#5!cx>0$_w;OJCQI#A&cy4DbX-d=(#2I z0msopfG8%Hym=)@=A3Ovqu6{6MArN&h`cg)qm!wwU}LRnGc1jxExl3zB4RhXjJ8Lu zi+{h;*&x1pcg3asGE;5{4%8xtPgovq`_jx!B)1s~9DVn*mX=<%EBg5V&@K$HxA*rw z*L-)w20GMxFl!@2w>Dn?Tqd2{D`Qq+fz-VBS}<3(|Kf1KK<$ywvZX6>dHQ2~;p@6H zzE#!Q0ah%mg_Rx-H6f{|v&%*H*pX0yj!TjkJa8v3`{Ja$aXTQg0-4qP2l}Mn9j_x3 zeEMG*$J=bg1Q@`5fZPfxyntuP4qUiMCprJYI*#~>o6QC6iHIfr^Dytu(eR21su4hu znBh3tyo*Ua$oQ(1`V!!wAhA4Ze$ow(ziQ9lIK1RhCM|JC2p84-vMYjrozt5Lz^C^z zfSrj>bl7r3B<b$3B~mihI=F{~eq5CO<Ts|jlxmEJG8mBV^Ork(9-#D>GgMXGqQZG9 zD{rJn|E6RI8{V0=kce+tP`-5DxpilCyy}l9$$G-9u|Q_}Wr2DzNH%w<o({vl(w2Gq znfitf;pewJDZj38Pr#M6B*=G|kycB(Thp4t^`XJ&G!tS9DEG*pyU7|bdFVqKD2NNt z(tKrQ;0wcQjvdB{K&@Alu4EWriyJ`dS$mo3WRywWCRTE?gPuAfqZeBx6Nl#SP)_nR zf>4i?OwV;d-V0D+dx51O?7R)L{puI-gwXW0$ls5T8>D|c9b2s;L6FT^6#@~fCuW7q z8d~qkRVI4Ug09eBC<DIvbBK8flfpb;0j!*%>*vwa`$^4nE&vFAv|&4j$iI9!cWJco zo%ZMZdJ(cq=H3ghFP=;7fZqu${A-DlgzyQ$6_jHi({fE--6<u74)vn4qY5X7V)M?l zn~;%ANWE^SrESD2*y9jURR6*0@KyS7X=zIr+^DA@%|x)u&+k<}!+LaEoUJna9@Oh^ zW-J>vLyaO{QfPmUI<|A^1>S66k*$`v>86@AOfWD?W0gfhv4SoG9o_OU?YY>xg`J&S zPv>PW*%Yt-s?wkHdb+wyH72IF#=RcR{VrxbdPWW?C8)6*aQ25dzo}c|MqY>|t~7c> z^<rep+2t@q?DxKpnCV->U-&<lEE};8Lf88`xIdqmCxemu&D=RhtZYQ?SGKQKU|9BV zZ||J$YeLBz>>RLwimD!=$m%qncY*i&x7N%>y^)SVYxTw*cz>d3hJ#C%RrQQ$2MmA@ zXpk*nS^nmZZBW!dr)C13%0&nE0rnUzTuXw9dzS674ls5z%DrTUoSbk>Qqq(z|J6NH zyC032Xse60C^==`ww>W|`(A?rNBW8jEB@(*pL+-D<G^@i+fneQ*5wAa^2)K<hhGE# z?#7x&VbzBFzM?+<u*<uM7_Sd5BGP`Pcz?F)UiXVZE5<)h9dM~!%#Q&?8d3j&n%<qM zFK4T!?WpJTy$pkz0+kk-{x}}rt97BEwB;54Zt62MYJM|TF8p`=-H>zZw2O<H-#FV2 ze|PQgD=>R!;#%+hcuUTJ6ZG%J^zOW&a{KsAd1dd<{%U)EXv|L-kcX}}?wtDj<_{H| zukD4~C*GUK{u2EMvfOmfhvgMdPsI?gH!`^>tS25a8Q`A2(~XWGAANZh-SOADU$OG^ zDh0B@co-rdSd9@?csVWtTje~78Y}h6`!Ib9Q$JDAy^}4>2~JhJ98b>Q-I%VS@Bn7O zghOQt=>G7oI|70G!QIDOWb6)1b0ZtMh%nxhl7PJz67bhJu5^yC<HppP%l!|Qn7&mH z-7q-slZG^+*N9<bIzv^bXr+TRE*sxmXWQr%n!e$>N|V)|m}8^#;4}RpI>iH%+*{h` zwGY0K;J1rR!dKsTcvqhIrgPO#rq#eG2;mdqdAo5=w{$-u^LRmu?=FM)dN{*9Z5|o~ zc@UVg+8U;3<A#@ctxtY$2GfhJVBO@scx;ayNKIC?vhL9Dj(9U;Bb5Q~R;Xs15~MU_ z!}vRA!h0}(Zl7<xDmVF-<7+z!kQJfI0TQ0OPw4?{<$Z9$PSpAEr+aseNHljY@gTr( zzHg{E@8|QTD^<3nL6X49AvC|Bku{SdRA3$Sz)s5UDXrG>z8*kqge-_kw}oc|I``*Y z$R5n!4qkYT*Lskr8JL4QW=~^Pt-IOGO)eX4(7y2Vz%2M07r=EWQQz9l?Bz`YvA_UP zPezz8XRERIh}Eda`aMbLrR8lkrJ6X4VP?DXAoAfV8;nVP%YYzKx=fz7=dF1>b^4fl z#Py6$ho_pV3?nn&+abHNvFDpOO&6D=w=2XIRemL2X6hH_wfe1WrxGo+?}S=E>n7_x zdiIgRQ6teS_6Xc8HvUpS&-k*~=>Kta?(t0i?;pQsn4~#GO*Yh&Q{@<Qn2pLQIVC#C zp%Kby$oVWO%|?i7PRXegN)9;<F^57Za@J@Kb3V=K^Si&l|9d=2oBMvhuj~1GJw+cz za&e-KD2tGm2qV_@?X=_fVV3&Cxsq|q;L2OQ_P3K_tOi`!H!zOQVJ6m>wAKEa!tX6& z{ri!3UbQ{se!Jo|AKVgZ<DI~dHPnn@v20CdCnh+Ni$G!kQA$2RyxWE#l`egJ^+3|( z$#kqX0N3WP6<wlnk5q9*TGmH8Xhd?o(RI%A$n<KPcLR6Il-{c*;y2FmgJ;tyLJT-{ zmOD+nNg}0<wdn{2OPS8<>N4l&g^mcPRt0fbiC@FCB<`Th&Eey;p!f9<$rC$E%I3HX zW+E`+tf;E0TG(G*K4m1;`EoD!y?ElE+kIz6z5Wq5jU|7c7&Z8mW-EZPW6oGd<@7ya z%bjk~l5{$0nv+f`8U*u_T7KQv(zz9LYDWoNm7XV#Wer~^{Rg~N)gkEEDr*V>%qr&P zr=vV>58{OjZ3sKB3VxitblLV`Tw6;j8RHoX8wh+yt1TIhzff`CMLw%$s>v~<cx{bk z|306)hNL;(4WaA(`GWQPd!^*!xtg(q=T`(`Y0K12sjj}_-}xqQ@R5s)esJ6qQOFOY zL!Up_SS586S(K>A^zJPAq^?f>9F^*Wi#G>l#IH*{*eM~uET6}|G0uxQ<)~*k^hkyi zRf<gP6|m*SC2!2@L|&D=;Bt2CZB^>T^4jj*OC@?O#g~0#yX_h<IyL{BBQ^2#ErxR$ zb0T!yBpXfn%DGGL-d=Ow{M6p#>13<>G&4~N8f>S#vG}VfUGsEGE-fihWnFQ%M7nCn zVxjvWWMIuw$2L~xqV%&XWDISZyxW_s@KFB;*?9A<2>qk&`4z86Uy?&O!BDIM@cY(p z5Jkd^{jrsHiWr9>CIc7~_2BPwwq=0TN><$lx?l3)$F!umx_C3!P;yky-A}6Cr22-V z{4i)~KQ^M6>t^+ImhR-1H0hIX4L704V#ex5&9w$so?vliF{=LJMIS#G0;;EDW_iqS zOs|HHVA=kF9xnHz!Fj=cAaD^GqpoOnt?cT!c-c{kMHebc(6saZj{5bh4i+-xgb`Hq zJVxxU`0L|OAhjeyjCp(7B0?toweY41O1@D4`H7IPrpkz<)*6Nnht0ZNTV;406nx%0 zMXc~AM?@&zkdRrG=!%*;E%YB?KBhy+x!YNnbOZmO3Xrmgwt<!rXU>(skjFxHUAy$< z#r54c?=mz6b+n-Tz|b5StPyFwn|n~|_ZHt#>N4o4{~2}W=TFMS^wY?H;MEY5pV>PY zyJM6rZ@1z|qAV(zs|GX4dx{?4>~d5;_$S*1`e}ouJd>^u+7ag~)ROYPNIQU@6WiQu z<2<2@HLn(EVxGy`8#sM~3#wBOSp7~;ysVT8=)Txnw>O9&MMI4$2XOcpf9KrCE`ITx zJ$8*Wd1#~Hrlynf)r_}t$Y||=H^PIL-!E3Ipt}?r=1XXbWEdJD)oUla^H_#UZvT#R zQXQ4z@O;msm-c6JSWW7*Gk?lpgG!rTMOW9$n+J1_r%;U^N)uxS$<K3*Q-buRlViJj zqzU4aiN~h$>{F91u52cF3f`?M?%JmabOy;h$w`~OUF>M$CF~w|=)+MDT~c<1KtXZ0 zgI}4zn%)ztzZu7B-z+OXsg5BvWkx=itkF^@m{zHhN?A>GaUOh@JS_>+PuUlR2&X*r z`UH<l>4$=s@27M>(QmhP;YHCfCmlbW>A(J#-cCnLlM9{n<D$NB-l!WMzh!tQ+>b{k z{3yG4J|*w5kBknNh|S@L?bC<p(+U;}>QQ4;dY+4OD~xP~I-R`q-x^Q##s6`UqmcXQ z_cJ;<aIR8(SeV<=JNwKZWB)$2Xk?ewwPrz6Q`(wUU$3>Pj1oTIJ<CE~@`Ql@gXd%D zQ)CR={#3Te+_&ool5YCI9<V61$k^JO7cT{^<a>Hvr6a>fBT<TPRKF;vdD?!l_-L-& z*oYxep*_`LQ^(aq7xxEaTM99B&%pO*44nT;`vTUyVX6NvyN!nbNR<qvSa=VK8Q}i= zwbD_Qp_BG1wI*Mxh1?m&|Fc}~wW2XsJU3)EG*WN<sZ5%}<WxrLKjMg&&$VyU2|bxV zN`dHFeS{X9?(8td%y>2YE`|A5*H0PpR(0haxTV*<%5ylS{!?~d{i^jsO1{^qP}s(~ z=Xt%u+6K2Xq)B?;zmHCWOtSdyy-38>{Ijp!Am$cb6#cD16;Dl$g;WpC@2D1|TvnP; zg;Ff*uT=eGb~N)oUZb&)k0C~i&bUN57M~yAbvh9-36|j(L|mV`J$~a=PIawa4DH;? zuN<NMpQI@G&mmgeY9K~3KXE&#S#_V$g$^9(TtA;OpbVNsLhIp)E?<%l`Wlb@J<{$u znKJ5DG-DHTFgD(BG`uS&XX)+shr!#nR-~kngyn#yZQJliHD|>>PRELW>Q9OJchN8X z`0R+i5JV@W=lnmdZaLwXG0C~!(|Mjt^)V%}H<gd7?EMMMnviRs4`vjJSrFBZBwccH zHZ3iLA^s^E;59Sau_ibb@s7#0dHFI0KFnB63~)GGeg)OHo7r57K!TjjoapT%x3$1m zi=f#r5OzUx*tZg6{;C#_S}bjHE(S|IM(?fAp@%pTQ;&UU%tEy`ZM)vkZSgY?B3^3A zFkmF9mcF{f*W8a8v=nm)$c5Wcg*<^%DOpCYgs##D$r@vw50WNhl7?ta+x+!KBt2j2 z6L0qXXI8Wc13$g+bwOtVetRaUupS)Y*gj0Vo`M#6lz;JbpKzN6Vt2<bZ^Hst5@z>U z@|UcQLRURZpR}$UW+!}P0-GWsjcVy%{V;buI!SNLcW&o5Na(ZaNchm4{e_cO6EY$3 zMp%GZ2ug{p^4=3VTHu2GMrHqa?k9uwtw1vm76YrMM>W@Ysq<8i`|=a+9qz~aYWu&K zuV}q~EWp<Jgi!v@?1AazVD|8*l5#67+K}v?eCnqm2T$1{8!3^uKKvbroGw!^d0wa^ z1gUaIXEj<SGS~h|UJ4e$SEq^(!_9w?Vg895r4Pp?_WK)dJ{w&&2rBmFq7-4_A-jst z{AQBAJ4@tT+7(~&)V`A=+ICt7EGkI;-?6^!y`O95*CK!rv~_h)?-%y4QR0M@GBjwX zt;S>Z`0ejywW#0h#1+@GA@*~3+ntABLt^%cmR`1=a)&y$Zx^IU$Z(lBPRp0KHE#C! zga*pE1Wt2(P(9FNwTIgtQwW(^VVuzQUc>e8?u%|Zop2kePjiEkbHF0=H#Kb2`5XE& z(c$#JR~OsCqaqMu^!0tDqH#m_Nr<C#+S~(X(V!S-hH>WRj)hgqfm7-{qVV8##+>7& z@Ee0CpU%_J2a&-UV;L}%_W!6Z&XFLG#X{OaafN9nplIjC=l7LaqWI4?TIc|vDG`Va zKz(8lmlmTM?8LDcv+cF-Dz{Up7)v3^2Lw_is#^4^t}y-c-~tuAip1l(tDs$VL2pl6 zT`Z!fX6U(LMjSB8l<5T-5)W+ri<F4tUX|6epq3CyPM+k?o)J0O(*|ln+Cl6Xha|Zb z8l&WlXTUzH?5LVo)3{?Yu694T^j@M^)dimO#Zb8-1f4h=)l-P^;rHlkMScIq`ZRN} zojLJ8bfVP!la;dVGu5xLEmCrVqf+<?Me@6sZkN^5E?MUPIq563_tzSjj7qxX`{VWL zk%Wc8L9}8v*lykl7s&MWI|@wR{&>IR_z_+nLcdR8D3@NYt^21({YB3%JA_r~rbEGW zwMO6857(OlY$y1H7mZ?0wb{OVI%ruz;D}c>R2*F-8eErJ(2>-Hm(2mAzIQap{~8QP zRIUje9(0;66iR(DWYxkD^A|%l5?b`B;2b5prLUfUDyHh&%Pm>(eV6l4!C}%j<F2hM zE9+bJ#xxi99xD@lUH!?aHlXqmv47fX7Z)G?qh!X%*W#PXfS(Sy1bq9iUg6)Rf}yv& z1$q0M5IZvQy6w<#%GlO1x9{B&V6f*ENJ2>Bp@UTg*MCX`6kfHvwH3gW(O&P^PtTd` zK;N5t^hyEp=wl4+44L|iT&(e(KUX4CxaUwb7Sv4$m-BN-Vp|GNI#8;H#4T%uBYa&c zv7kf5*W%Z!Fp^<PaeKRW=FV8c2YGI{+exjp%CN@VZ7{^(F{34tOv+CmNntyvE%P9Z zPB8pU!EO8kLwrrV)agmE0vd3Q83tNIq$nE;DOrXDd#BaTwYLQ|hld!t%8*ZW#Ll!~ zlZErX*f&)VZasWcp8BJR0cJM$!6VZZqF3wz$CtSA?$C%s)=PcbbNU8l<Ex;|T7`z) zw!2WJ`gl8i%2hS^SldaC-Hy89O{sYTCvi8Y=JuDpHluH;T_bs?#~S(fZZ2JD@QGD# z)lc5A`VTk_;SA11mLF?kpv;y(>U2PGhMxSLsLO{iW0CzLC6W#cEw6T~VS}S~{lnMv z3!1M6K33MdG7ycC%%qF0a=W>dQ^Wt!A)#<8_y^$VA5-90CR55ARwVYC%gwy~eZlzG zo9@rJ(BTokyp?evtkrAxD^$I~r^)evJ%*m)iKihXZ+?v72=+BtR#raQ!S3Hyl}U-s zuAa>4YbaY<c^t_XOmLSlQzdCyJad!kEdRRq^tNBQ(wWo6zo#Lab|Xcf@7-wD!`C!9 z_LptE*_f5sJe@y{CdU=H8;U9WVsyP2YbA11b;0~MX!Cm4{*G|S_f`l0WGtNh8}-K| zDe}qIwt9w%9ZcF(u&)ubuh=lRVFFjJ18Yu;Qoy2`yxj|W53`y}wv0RwxLNPlDZ%>( zc>nI6m+EY&-UG{Vrg_5u16KQn`!1KzZ9JoHaAYZ4SN#%Tdtov3gU!q})*RJtpz+h` znfGT;I9L1!+__mS`9tLSzGD`_@y<O|&#PXMKWhKqu3Ou%6SOP;+PQ}?g0x=4G5hNJ z3*g~ZR`k22aTA}-_#6fvK=$OM-+hfA&QFZ_L}^(%r%OjFeYPb`fct-Euv)&FwP<V@ zjKY>od;K#Sh)h3>K`^u?6MK7&Xr77A(*l8o&)Q{IL`jCQqPxJYv8eY(waM}lALQS; z3;migmQ1&*mY__nmvqogqe<Wy8~@cISQfMUMiV(1X~U*PEby_-WP?z}YUm!b`|QiJ zSo&RiDtw4-1$NMQtfPlhe?+*?b+Esy?=}Wez(yI(0NnnYsPHvtqO&Cq@<LFNw8j)Y zCb+)<Qbzg%3@X2O$Qt8?@65+w4BK`?O@NfLr+r1GzZ_bCSrV*QtCli#QeJ1J42nJw zSY=(-J<<l=_!J2KgV9<bZ?Dq1-6#fMIuHFJXi*fJ8l@$UVUnA3ZyT`3I#}ImY&=ww zz4A<pk&7v$mI!FW`FeO?=q)R5;(<v*(Os*GHYifa9Kxb3<?;fWxubfU=mASo5YlNu zr~F?;eJiYYlG(^%8#jf}F>~}8iZlL@uZ6?&HgEwMTs)MyB@HFxelynoR|fasgPx(( ze6$)Ud~kWgeO*Leuc3hywu~2kZgr^~(={DcOPSfSrljrGEAxR*#H0r6V}_$}WtAqx z!XZ%GIK=iQW`ki}If(yeEGWsqE)UtrZn|WLx}@}HPnf1Hfb~>0-O3@ayLc47vWH<v zf+*y$i|_AgC~a~0#hV~kzX_$#kOiiMX<W>HNO6}K)PoNj_CF9<Bi+7q6e_bRe(tb~ zN&vTu6C;)Uy9D{vKnq6Nm;4FmV2M=5&`yLL<iS#HMlw8Xb@)}#MMOsvdqQdtyybZ& zXfaC7u_Z;x`m#g4Pys4X%?ZXVvidSVJmN3LejEpDMhqp)vB8oLBE=5y^Lg&$ZhSka z(w?)@>xs@O?O)1!ZbyXq&T>)zN6(8L`2(@{Q(2@G$j{aaB6ii*-UGhaGD8dR>djW^ zmG<Eglj&HGr1*}x?AL+Y+gIY)Gk6v`OAbItYwz`s3ihQ+OI>U;G_+_?F>6kl*|ZG& zlb&#>V$z8~d`H8$UTdQJ<Q6h>Eixg|u&TTEGky~qMoZgDq4r)t@&hhEm@JsT7U;Oz z4eQkO?`5E{EUDY3L%1=o*X$<mmZ~E4HmAc{Qt|*O#m1IAh^r0!<7Y<(<1~MwPoe!$ zGnoNUBy^3zu?cRjh|&NU*fQMq(5~EgH4U}x_KFd=um1W&pMRBmF0YD&gT_v^IJ7q^ zS;e?TxNLTo4+@fZ7Bj8Kq0VC~3_!pQv9Wd{HvaXvkpvzf^n(~GWb}f&7Q_h097%Ks zn5oU1y8q86rpHc_)_T0<1;=~FfhEEIm0TW1Ty_q{XQ?p#(Fb3+_(O@m+yThI0+_;i z$&jYWvp`!P%=B{S+X@gUG$=i@WeKTBse(L&al7TP^bwO3i_*UIjb~TGH4cpC_k#E; zR{jAS=01aIn(lQsuAcO=giHr;!pJ(7s^3?#M%}WN>qFNIaMJvB(DrSq^WZ6t^Lkq7 zC^Z(ttjcAu@P|eGg6$<6ncKG?P29tT@8)^}ZlzJ?SozmE8AQeEDGOXW&etJ{dY_T4 zs4P{t#0NuDk&${o<wU$E<4FE<*_cg~!VwOj6xV}T!<G<sI$~8@1mL)Ccdl@1{2bWN z0FpQ}u@o7w4Jw92jZ%0lc)U!xQLe{-MAZ4G231WklNw4+J0=uu;7vb`cf{+Zwej2x z#Gs*l8M;YL{sV5kp<(@jG1U(znb<}ZywI~A@iyF94~<IYMtNO9BAaFX)TpbjNID$~ zzB-D_d;y&NB)KtQ$*9mB(rwdGtpY`KAowF#5(1H)NP%g1McrBPP`5ysc;WO^=;128 z(PMzE>rU;CT+e1>dtSA4O0pJ)iCD`OfnBbf)(EXSpVLyHmTqnLYWG|28Xf$gMFgMQ z0bV|J5X4&XARizt0-uc7gK_@E8k9A0Mh^7=+s9OG2-47Q?LDx=UzaHvHz>tqnbs?V zoVo?by2ykyaeT2liB7JHH4hO2Zo|<>r2@}Q#|(~I#TL!9_n@&xeJ{S%8W?x#gMepX zR&}lBX1y9+6d2Sgvw&gFBpz_?y1&8VSeHmo60r0w>ve7c%0^?ZSmyD#as+feclle$ z`N8bq&0KIi;5~Loy5-Q@m3{G3ad;V0X*(V&rPS3^fPr={$HjpX$dnq?CsF`E99wG@ zx2e)ULTULGrxIFehekR_fVc0!)cqUqm>#4P8#A|$dF{AahQsy6T3t~o{U&H1-jLH7 zr;k317O1<Auo^7e^N3tltmOw=7ZVtloy#=-ibJtsJJuLi3`B(n_*$Uqiy`_lv2=dD zOkJld49gZiBQ#<%YW<;nA|FoSY0EQl5N<YU8)Yt{^2vHd!_f%H@IeuKWM~{%m&jwf z-Yw{mPbpA%c+!&K#Hf;9FI0R$JPNp>Q6Pa~6Wi$v_Y-xK98<u?eegSi5A`F06jtW} zDgTA(P|1pD!G^D4k|0xtP6QlsRJw!Qie^DsalC{jz-uhtW3D!|kGgwt7Y_3=&?>Hm zA~2gwuxS%EDQE8%i|;AzFHk>}k4iv`a@CCLWbaW5ltjW4BNvgI>{c+lnvQYaS}&Lt zjA(2n`RPQ8@!5Mr!GyxbT1m*6foTCU2=XIR5&u+8_HByd`T<{{_4t_zx4%w)z@MaC z4PGo{auv^Ke2de;&uff?E*gC&mFh;oaOraG%@65S1hc6$Q-r|oJ8ddRCY$ire(}cW z4HQx8THGbdFuNu28754YjP>Aan;D4>BM;?5GP&W}D$K!EP@D4zg>T;gdG{{=xF#r9 z>X*YLNtN;F!*Yg4rL*e-MHld1`R?G*2TLQ8AajF~16p3WXH8_q_lWp|q@*HBTF%QN z(S?R-9+dBaMbmsZDHky8tEX4>Wxf^>@>R((k7|w<W!txl&XiM~B7CuOSKA%cVvDd} zh}+gk9U)%P65U9Yd`V79<_e8S=H&q}u@LJCuugU}WdC-i3FhKVc|S_t7#%-js1MT2 zQ|28y`tus`3owiKcL0q~PA&pVMp)iZn|n!bx>lC_VD@o)9^bRx%g_4~X^21h{w*iq z)stlNkbe<80Iu3TXnh7`b10?<_%+hGHDRzB8OeMUtdDy0@95B#%}^qkOFqSG7M{&O zuYeS4jpyX#k|8WV)cSBrS?X@|Zpj#yYn`6QNOXb*9>u`^GNmK*Du9IthvTjKkpbJ* zuKL#IhM|!5eVh6QOG9%_P=!#VE7q(;7{pEC0fhMPigI1XV4>ROcEzf|AOWE;LVtn6 z?#Lr8T8}KptpMehzZqA9SY*vnZUBTOi*FDF-KVIZ1rl+;o95MeB(u|&E6Sad3jB0l zz{YvD?_(JMYpn(RzL{KX;|<YT%X?`4$Dm4gjnymMPq}NU!GHk-V97+UVIVrY$U{NU zaW#&G7nEplYdbJoPxqErhW|vPWzoIxQA>_Pt2yL90J3FW!t>(`p$dPQH#Ul&ed}vB z3=r&jp?dRaO%n~Zx=0>)Nrn(QWZa6(n`04NYNUuJ@_2S`BH(+u#Sd<z&$1$^k~Vt= z)i)ps+~HgHk-0g2(Z&bJypgWx{?g9?CKLk3u13%!L$|Y5l8tx1da>vBqxc_%7hmP$ z*9;Yaj^N^TbRG|%cX5$N{0nAIa4fk^iM1!m!BSJ!{@qjYvc60bqrhktFz<V}&tc7( zOUHi00ABRQ++3J<=ggNSWxZJjXW2NAl9M|L)<s{hJRS}vSq!mQ9<B7`YNpH-k%bp% zu3F~lR@S*<jJsd2=Z)2gke@7(NX05+CjTVI<P>*+Ah;$Bo#!1lC@K^xh6Kq3RJm!V zs5WKc=tip{->3!>tep|1IE-3yEg_$^4}-IL_0jE_sDz<NQAP|6tGA#%eMN9=Q%VKf zcnk=(&x+n13ju2)G060dojS&Ndd%1-T^>kdfu^*;I_)3sJ#g@0=UF~zQC05RYi^*X zIo>;t%J{5<O^(j*&qaS$_YwE0Z8Kh12O#N;Je_3{JnWdGS2f*1pV@nb4<+$%)|l0w z7}VLCHmQWehq|c)Q_bRh(vXo-@Ns<UL<!9^T5VtlY7EGJLwMframN39n|xTpcms@~ z`i#ZCzVGPRGXA0(4<Ci}Ko<qgLc^|<uR1?Mpo^}K^^X*2BCPEJRk#jUDA=K%-|Q#e zzLQ^?i@aaJo!c>bJ(xzL=jsit&zi30oKKmvN~O_J+VH)aT;54B8S)lw-*N9Qv3vfA zeNLM2;0TC4&Vse0so-Kzzb&F9kKB!EXN~OUbVdt@0Z{158d69*QgUs2r%{EQL?{B5 z2X{T{#At15$v6S)vPl=E<ALdp;DZPv-85XRTqE9dJbF*=<P*QwZo1o%*y=*zhq5{^ zu||>uZ+tc4R#G=D3_!buz!8Z@R-4;``}Oi16k~_xBu`)Zd?Gg5Yqn-qtqQd~XRdRJ z$XX@jbVmcVgRrN>ept-DXnc7>w;uIxMsRrP63NZS(WjYOo7MQhWgQyF28+FmZ2(CO zhd82__9*@d@(m@j(G=oX2UnvbV;jcP+-B_8^v38bxd*H=x>^K3g!OAg8;*z2%Te*t zGDwl5tlbiecGb*o!=pRZ8=}B|HH^9htc!9r=|f`%z$_ybI*7o+ytTxOxHQA*QoTXB z+y(+(XD4bYMMdUA1;f|3n(lPt;QIqf2~yH7<G#f9^&T)j`I<j4Y3EY1Re9SFys#5h zbuytXvYw1BX+a7o&l88p6P?sZ!Y4{iGK|2Ye?Cr{Bu#NG4<(02D7!=Iy!dHx*~(fp z)>eO_3QSjFI}CK-aT7>vx<oO;79IzAsJ#zn5pn^xSGB|y1a04@rl$cI77KL>0O{xn z>CW|OrN;AXYxycqFX=?UP;vmrfbC#(+z3>Go(inW<Riqi;T{n$eVXBfrsntx;-mN- z%mt!?39I`XI+omogDdfL9{+3xCqjNgZ=4Ym7c&rgg(AHYf~}VLBGt222o`Mz+ampY z1%34KyoYCov?r0-=^_FG5r0fZx|KntaZsnk%&bI8hctMusLJe0nPL8jkp-WHfD;D{ z{UM|*`to7Y4C1Ud(*vZHa$W*U$_;A?zSxi^77OgE0?=N=1(i(fwo8<$jy!#QZIaM? zrJpp9{5Z{w?=epo8hMC6s1#A}4*BXItr`){9cE)B&aXGS2K}&T5bAwS;~Lq-r&KD4 z)v7LZz&buCRAt{roFqFCMGIY?mmeC-dcGL<kJzNw(w8aN9<12IS}y{`L&K{XOStZ6 zgj#Z<oz7!du-&JsYRVij)^xmzF#=`)END{F`$B?fur&V7%gty@Khc<Y6f9RA_~|&M z9}RN2{^UK(_AyAOmqXxkcAmj{?qua(7@yzoedHR0EFZbFl3+f>q~O6@ATNR;%~dbx z88LC!**RfGrQdyhZJSVVI#aPtxn^w0<x2aVsdkWi=&uLF`M0igOxZQSqQE=j%I`Fg z_?)tsSyNy6cFkAwP^<AjKb_58g%i9suNcvGND*KIG{@xfm_75HssF-5hv7{1Sfe`0 zDuck4C#J5}{{d=Ffs<iY6;I8lNXsK&()OH9EKKJiZhLgwdNNxjJHOup3}P(AJBpJ& z{IuHhfapK4S_DUl*=fLnP59U3y2*gN%H@;+2ssX9B4N|4mFY-zA?RW9P|wPr=)*|V zq=q(O5jyWNTHGYw2A>-3BZ+Wr&b6KrZyN`Hjs8YMl4~=P=!m%&coQhXb`6U!@YP%5 zzRxI7|Hz(R*WJT{r%z!!8Mqxeu4GMgG4o>v?RZ<1(o+5mCh4PY9YZ&ey(c%F4C!7F zEuSX#41x!QNaq+?Zjr#0!Ty}PR+Ja&GgR;&{3*xchJH*;QtcN~=#@{q0x+z~AgGGS z_A{|GkAM{j##MRq&g_=&>karkI&x*86d+O8^ahrW79qG#Y%hZo2EbWDx!YF)8I#&S zQsitVt%&+f<M{dlpp05mb!mv1R1M~e5<V-$ol-WG*bK&2ue18W(Sq{Z%`^zb!aT<` zby0H2-V;i7t3Mb6hJKO6QDWaadKrpFQo<m2zy=D-Jn2Veykphv;^?Zil4ly>YT@~a zHXT79@1OVXAOw{}T%3<0U{$@Kv$FOe&y2Z6e^621C$6Ix-9JqPhA`24)KDAuyaof6 zj!jV8H*+lyUXAiI6kIDT7uOP~gI9|lJLK{&cR`7)(m!`uq5LD4YK@%1#_nCGrZOAm zPCjx^j(c8lS7r(f#{HDgZwIrw2=KDBku)OY1SY!Iar~Y69!O|R#s6Z@-q%zf!wz;Y z{sA|@a$HC4mv~k7#^Xj3(-fDkMe8hs(aXUCC$x=a(rn<G`pde?)2i9OyQ8!LlF;{T z|NWk-D4!xzjDu)u##{=xd>FVChxTp~NCcZN6bS6!<$;wUIy#Vk%6ncHJFSr>m{b_* zvVjWKg$uJmD^Zc$J^Kq8u~0{0T?S%SKKNp>QRy~#{lBE}Mn&Py4axnqmj1>{?3dfw zhJE?|XZ!q&kdi#d>H1BRNHU$$O~t!emL$;v#%6<ei;q`k(Od{%9K1Q2GxF3=h2BTD zJJ~!r=|rR~eOH#*Vcv7`0gz4sl4(E3XyMbL0k5S6$~q9u+4(*`gJ5h(AjTr9rD)~_ z0P)I2M$GRx2@qJUOZ&gzMh5x*PDC&T-xwqjm{iBCx*KGErEJy$i_^#R0sC{sFbsO| zvzBiZe4y4?D!2wUFpacS8Q4>sjmi}TrdDz`ZdR?7XiU!-Cw-A$`>s4aLtK@g+y>no z=4$EmZ@yScU$o><o6U4QkTM~4qqv28MU?Q_-kY-j4|yNB|7IHbAuQk>Elxor9)q+7 zTghE_A9@(__5#3)MINXr2wv@=SK|14VY~ti89z+NS|RvJE-q~DH>9~b=1vmcD>Hm_ z$(i6$M7TQgLZ7n+SLB9;skL4L3VfmZI1Hg0_iTVAI|yD{>HFY%ZV(;m_1fBmQyv}o zhwLl<B_%t*=sj?JSZ@`m<~~bgo5ClRwb<>ta7LABz{@HmxKUKui<nheRXQH(<~~R9 zX^uvkx|--@V8O96^HQ3`D<(<{wt}ku^MdZL07^S0J}r_W6fSogUsZTtE57-^w}LvO z=AZU@s|ugbb7MyCEO=Oy?W`l4u4pk>#tSw_p;5@y3IQUX@8uJAdy|7Qk&a}HzrIq2 z)4}T)Z$~NJeR4Owd%n~fW*KUeIc3tOK@N=&JqD!iJq2`8uUCQ##wclCSY<)8eK7>L z_o&Wt6$rbNBUv~(dKX^sWMxVtcL0XAZJlm5bxn+4`M~;ogoh4WN=f|8u6kVTH6^b% zhRSjfeVAW#%~fdvr8z5xl9AhHaXUgDKKU9jS)>M_N)EV=#KitDiMm&JBy|P>M0hBZ zzLv_YqcGe3V!^KAerjvzGPX66P=#(Z1+-Bm-FSyXO1Rc+BitC`HKPgz$AT%5Y33+F za(n>DeH9N(XT#ReeaXlgdpCFfh?x9jQ}AyEiP}gTz=jdiPD96mni92tT15hE9so2T zI2($7m?s3OQyE%2`A~8NFi)6~MYQp%Y+0@MSagB!Ib&@BIqpDY-_8cD8=Me<KN67I zbZ5^)74A=sp-EOeA0APC2XM1>Bjm4T)d~FX0)8OGs{b!tH|&aU?f$<mB#Gp-FZx0G z+W`i4n<4oVp>q=h#+*`mIAEC4*<ezPCfSfim%FyYRXiIk6M-|WC=l24<%;P??7q=x z+WR$bM+RM>mRyFyM-{t}ZYbh#HoUb(xEI2@JQ9CZmOP#t;qkkDosI!}LVKaSM&Euj zdl`vknv9rdZNV(dl~FlxB6F{Q`%3gb!yhD&M%iw?!wpWmATj~W+-<l#IB=&iI9EW1 z^+yIZbWg>c!v8K|QIc10BdR&}SBv<F#NpTjJ4NrY*->9479}woU{Mh|7Qn2x!O9D? z+O3<6Ee~|VKz&27Lakw><=d^)!J^Qs7><6o$@Ds6?ZnHZTwgJ}II?dTxK@W{Y?>Pi z`dG~1McnS@oJlAuY2V|)xXlPm$NCzfV3ASX3c760O?N%UNKyY<k&s#i0}R>|z|xny zK>1E38ePU?Og}#{^7#b!q4sfvFQg5|L3~&Lr0R!<qH~HY=xarvCI!>++`eJLEH-;M z`V@?~((}D(q>6g~KS275Zkb?DGB6TbeI+F^>5;(?MP=^;iqYDBQKq&$ae~i>LaAi! zNP}p#h2deo%^GJ)n(*c$Hr<SPixN9MK_J$v{B0*6Ed$R#gC7k4jE)-IMrTME68A3# zWFs>5xyu^PpC-(#IqwI5&{`zibPqXOEp+#&@EdtOLJB#TnYwKkwN$BEHK~b5<P?N_ zC`Z11`_cR0Ou6jp-+CPF-i8<6DQ0CsuT%feBmSrZ%L#0AE9YgogDE?`S8Ek08LOq= zBh=i682%N>FI6!kUm7iO9($Nabrvelt0P}$5q_-+`W(Bz@Mq{tI)2j{qW33Vh&_D` zU8f@FjN)FDh8(kwO#<Q;_3)bvv8yh^oM;eoEc;EBgvkzyo%>1Wsf;xQWJz!;|78>6 zk$G;Vs=uz&av+HI_8%qZ*<b!t0pXF48kbyOR!a1}mwxPDarDqni`y`(Vd~W^1L1Bx zt5LW5>z|Wch_(DWLcWID5o!i%H;?=fJ^RO8VrNW^MV{y@n{h_<t6cQzX_6th|5LfC z);?}KZ4F_<`blIRJFK3F-_U4*CIBWp*HGm*@K2}naq16TrdRiSES8GS6aOlHohvII zdm0vY<wE=6Z_%s$#m!9dNyg`!e9b4JXAj5*ITT@fIIY(+V~mnr<`HtUg4Np*3i)py zU#cAI>Oe))KWpnBe-H(48;ff*stgNQE52jflgafAe)RV8NF2E(w~)Ievs2l?ujn>| z$cbjI>|d3%f>J#(EgJBkFgIzznby;O2gF=l!;9PSJL9!riDLTYjg%89pBpY5jMW;} zW)A$%a8#JmcKs?^xHLbIfz|#Mlk_|#Io8TZapf5lG?&^qxSYDKKb}A1t1?&!d7T*c z=!LTQOOM}WWN{wA<WOhYs%chxV9e~;OH{YETfqh2b{FAS?0<9#kZVrqd-dp|K**E7 zcs)GL_dvHrNsp-a=wHkhozTARw4W&o{F%7}=N&zi56+@LEX1v}DX{D2`=F-@1JV9* zv#?@z4_8T=t`Y`t%2^=SWm73%g5O$Y&OAG32NUNQ9qR9e>(#5^kGKUHx3;9jMB9Bh zAHXa$iZVTM^ZaA;=_|?kx|MnxM)%j~H?o5rZW3pZDW8)CbEM&QQG$gE2Svt%MON^# z1IM@FJb=dZ<7iu{TAA?bCT?PmXCQOw-D5Lf9bO&rty?A3NF+Qv-EZaknJm{Do`waL zSVROsLl>F0)!YdTNiWkB%oMRfhwiH%I)O)`k6Vq((|Ihs<8tRcHlk`>tl@TnE51T* zh5jpRC`>N;<};z`X*T3j8KGv*)=5PgbDN$t9UE!3_hXJqY`t@@(>>&S8Cv90-oZ9y zBON1Wuu{CB;@ZLm;v3J?FkCBn2n_x4v4+cr?^i#?od$}cBA>JV!6sq#-X7Zp1?jOm z$#+)v7houC4V~+4rq-n&ZIy)@QuT68jn$d~405{P!Aez83^y?yB!}n)E>Z47oxM<M zYHGG=3duFWrv-U6IYpnSa7k{6{*X4g$?C_-{e@pKn&(|0&X7vRdsZg}kdgJZHXUv< z0wO2GH2rfjpV2YkrZ3Ai$?Ax{0PGGpIbMKP!b(A!%vFu=*+s2!KIlRmX%+N7CO&<9 zC;r2knI}noU$5RQg;E*0%&LNrKDwx}rBF{*vbK;hqQ`6}Dn8UKC6APD-!@licBloV z4O-LtNp=v0(h-@ghmqma>wJ2P_5zGj<^^?^%kFk$=>szJ=Iv1@EI!<my`HUqxan&+ zBw5S3H`3u}$<wF86_p3Yz_wHHg8$j-*O}KU?@D7urwlZ;KoP5KS;;~~-V*(*(jTl; zi{=F{m-|V)fJ}3EnO@wf#v2Q~o`y8Tp%ZMH3><f3_vY5o75go3$ws&56SHOsxNn1O zv*%$Ugjr2ykt~Ll<4xTcTd660YP>B_X=lxmtl80#-|=~Ld#%igIG0+*d9k~*71`kU z<Sg#Nx&9hQi{~G4Dvsbg|5N$z;w^9#?DeP_KK+<asvt5V_~6Vkvc9vnyr)(p>c(<y zcHVkh`RdkLw%vXRGR!#vyvo*v*oO$=08zR*PuSTqp<vbZ*tJTFj&cXNy!~%45v84? z;7*a;hmUx^bAo--QFuvJmckv-Cb(Xj5#_bK)7~riQf|W9Mj%pbU2{IO=JPT?b-fC! zv-=+~<){`pdVV^lku?Qjue_lwzsgt^uFw;g0t_-gU5tGGA3*naXjyu&_{7c?bMneT z%G9CO;5EfB{mux4r<DH4da29SDSFpW7w=fP!I8xm?63a;eAD^Ml11<TIttvnS;^Rm z%N_+|KnpKZcMjZ&pFPVo4-3ht?y=Z-^Q;CzY0-RhFnnXa@td#S=eI>4qMS|m%LLCB zsGt9r0fvlD?kV;pSlHYT&{O#IK>V=m%tdL!oP)_St9)r=`|8}vJVV#pz#K~}b?6&4 zebY7iv|%(gam8X-1h-YS=~^E1SfYymM^gS=Ys4uDhEay&lw0$U<Hl7Vh)>^ktE95% zYwsmIG;{$bAAUP^ZVzYLUFr82;rI5)^#f70VDNo+JIZwUg}H8VK5gnDARR*+##Xm! z!+$R5OA2(k8ZtD;JT*eSbjTs?V7%nlYb(`~Yd_P9`SqvwY~a;<ids{9&0fPay<gIj z#%psldf#U+Yw_j_*E2u*@*YhYBvT`_?Jk&WW#n15Yl@7dWkZ}`KR&Uy?9Laxe0)SF zaJVDZCXVvl++2+e`|RBOR`k(pDkVLZw5P019Iy1WANewUYJnH?uW`@El>OSzM%(6b z=2O*r8)LX89J{)8_2Kyw=~rsKl@BmVbFn2ePu^axfFxHlxWjH2#ER^EG$YPSTq}ic z`_DNfVqRakz2nj+x=7hD4~1hv-3tC``%$0E6OR5dF?L6A<?7kjC-!>tM+$$K6dJxS zajwK%9ql3sP%dI*_C;S?>v&0a|M{gNZmB`Zm;kHNZ}|-6DZj7d^l($x-)y@l1|4d; zgHw?lgMnkWs>`{mM>??B^42?9-(BX3$3CYwKd4doi>r?MqSmG|qW)c1>^QzXwKO7L z+l>r)&o&i5c35Nuj@k9M^_EU_Ig81Z?e}9WI0x^}5kz8#+wz3Ph*cN|t?g}_s?Nq! zzc{9=6Fv;{$|Pe~?*t&VZ8S7O;eAhL`TM4CnWxp7fWXbxJMM1w$Pq-&qbAOhHi#~N zKT~NL(<|4FVejs}dCyR+Fnz6IGc8Hi8_!&{R3E>TQeRe$_R-yr&`X2758!DgEL0t& zG8#cH;PtN+zGGS~S=CH&o1Q{#W^{x?v+Au20^u<e1qw3pm4-J##W;&3K->yk#0!2J zleS4WNH7Rlx76BwGZ2*gJMPqhljbTTJ}@-rDqzT6M<T|I3bL$Q&rYu_NklmSn^Nh3 zZGvTGO3t^=qq@*GI3CvDe{SUR+mTCzL+{#Uo?`Zcx>cv|+rybGj@?mzS7FN&b4}>c zDAQw`F3pNrKfe0c$%(Vcb%BLh4}QpJUD~a|VEjSHhtXvfvl4*|5epdlmF)5K8xiN; zzq*+z@h#R~REvpVarpDa=+BnhNs&f9C_Tr!7f|XOp7!EGViYZ{b=EqgucYndLz^s7 zpMUwi**WLw4nKQagLwXCJSWy2qQ#Iyp`1`#9(pI#?Kq#7IeTPe+cx^v7vlZ5uSPJI zJBAC<m0GM3$)C5w3{pkj!Iows-ew17Yl*nuF&<V8VO8wky342Z;c}bIjA_|0EV5n@ z6?Ghc?8Q5)(r3$`LdZ?m@f=^6;|Gsl8K;ChUzH)~P9W}*bKXY0;Q6Y&II6LhZT#}i zEt;1Lqx8)BcP@8BuUGgw4kaaqlZ`F6JF|{pB-t1sQ=%Er4+oXZgC&R9#@hiu3{G`u zbqMgP(8axh{q(0@id}Vkf0<YqR7&6WIrqo!8}H0C!LSMvLf%4%$s9aAUzRIk?7M{w zFDe0buwL(eUz6kXmdhetkiPfIepC#3ZFC7K>5{}gk>fsK%gx~0M@<f1@NZD7D4CDS z5c50J;1ug5;P$gj8Tj9E7I(wLb@1$+P9Hm~FSv|ch>4Ur%mH{EI|Y{X1(NlrL3eay z1?0^B@!E*Iu1XoOVl%r1AX*KN^|*6fJgzp@f)$J9eII&+p0)ZX5Fc6>Eie})vC#;& zC9B-%{^?jka*Q(2HS>i)3XswVg?r&1h@P~d*dXF&=rX0{{iWkVt;z8Dhmf#mvRaba zAliEUDdx<(Z%vhxOThF_RFYG{YI)1ER4KVpFc}-RyrvE*xTpKE`k6B1qI6Wyp*fRt zyXB?NtPHvG8M*fBVDUkBe$_aiik~SpHZ=4wDc*Y|>}uG9)6lpTsu)7*q0w3{_iAF* zD93~$`MgJ;x(`kKP$lxpbEPUm!h2$sofuYztAp_yiUxJCC^J^=r4sU(tKPhP;McXc z7Xr<E)mf4}O^oG=*^0bhLpYabsOELu91k2GAPzYBU+d)_AL+Jxg&J!}kFb>Mxvd>a znA<1bfE0PY#Uu;xf|?v8l1Q6`fC}OF-;T^S1oAbx0#gZ%m7$RFH#fLslbRIX_z|;t zwOu1Tl%C1MUObpF(qdAqL1pN-#-K1S?U3@eptC{BbiL<XH8+dyl?+>C`iib*XQ@~l z=@PwlDoIWyXx^veYI?305KwXpSi!|puWA%Es@3+hIeW)Q-{u2)_0bm@NH<Q`ZRNe7 z!toii$Eyr#6d!v;EWe2F@4eR}N$q(my)L`sV=8^0peNeYt4t1R1PLfr>SfixX>LKj z90J6(fE6ti-<lX?)oJ3`WXF(TB&P7fY6#DD<M!csa3u<U%ujWmytE?-B*liUCWAdj zBY{27@|Ch-l|S|_%cyi|zN~&)T=xvI4IyWLCd}6gkYD1Z6+)xsul0ttJ?*@1^o<st z3-AJqeQ!f_G|w`cMpZh_y;?$xSn{0IA0cP;^ov<F%OdFd)uH!$rmp`!bnJ%o^{0R3 zk19r&tmBx8kwx<Tx{dN5?Va8(|Ia)F!m76FM=d;b{Y41&vA(J}g}D#xyq})C19WP> zM8pnZXg^B<bZTooI(P5UBKl@-Ji<l5pR<OVD?Dm^#l?-}tG`Y+r`jDoQ~$l%eKb55 zn*CLfFd9g|JGwM_$v-%`tJ}923;Fv-Oj}J0{omk9ZG1r5SFU6*!P<e^zW@Ha&cO`J z<w~yjc9|XaEcWfOKR8vx=t-oL9IOPI4TFi5diaa>8osN&sv@i#(W^b}-*a~p&h5#e z7OvBDN!0yYbZ>>D?!5;>Nz77A4=d46#fh6HwU9!iF{CIr0$#dQj>(C0^XMLqq0bC| zI$dAz&adiOyQ5;+M<huJb+nXl>+<I&lM_MX1|`8Y-ToaN&h20rpo2Brth)5}-Sd&O zS)*RbtO&(-@y}%3CzG}rR8hxG;&^%TG2cT~%7n#`H)6H($kM7xBHPh?%hxnR5t8oA z(cpMKCs3D@{Ti=KK*d((Z~kQeXt-l?H29yWByA^Z{Vl79zbdm{^EpBu@Gs+vIv%a} zxyLT=huQCe)sxc-2W&~s2058=bjKF5wyph2$otHXHcm!lLs37-noMNuXP;j6gm2uu z&4x57(7zzO-^(EXeA+5}1o3mA(EM7qQ8|J;6r}k-SXJ7o)Oe<TUXDd<?!IxcKJnG@ zIIubFmrD)>2Zaq2St94Yxkc|m7+S0x!dl6z;BT#{0oi9qSJ?Cdt`qG7SIwv5hdM)p z&dInM9>w%52Ygop^lW15H+Dk%+P3su;-ZZlVk@9ogSJ}M9-?a80#;YvDocch2K}jn z+8N%fjsEDyj}V=N#?ZiG`ZeB~<K$D%jFf8MMSG!3&F+i0hI8I4w5`0WdzG#r%HRgs zBzk?o)T0-@tCuZbKdq=n``TCyru=&6VLg>^ix8Jc51I6*ZU2nGt9vGn0n?N#TT!Ng z*~?EJWSqozi$^Y@cR@$OhVDX<NqDVuI0k=M{>YE`dEZdM=DPi%2jTN=a73)Kn#1D~ zuS9vV$Ci_t2sAf1mI>LFrb|n;X3+?-MU`OU;j_~P#j`fl4=Vl9hM{(ZqK+9p2kTmx zLQ%2(CY@z}KO^J#aInkiT`4msx8d3|=dO9%U4DFGw?<rmUcGI5pZ`@@PQsbjDSr~j zET?P$j;@qB6|}<5Zk?N4b|XN$>tq)l_vV*ydXZGSjvT%U`Oi;c!8Ey0EA+^}OQ^4< zl26Eu>5&xHkpp=w6?~>(1(CAa8iJ{bNbM~+cvt`Z_&&$!Jnc^nEwJ1L3zPcwZmjC1 ztdzy_yOpPCQ1rOGXfJ=AJF`wnL5Dyda7}=gnx+1V2YmCzv_C}tRoQ*>$3*7i=|EDJ z1X5C~2^sJopqKtfQe*I|%H`AVXS}Rc{=KTVv&mNR{x$}KR-s4ccHjP)NNhNnh;fMt zerBsuxY0JLg?aDMHve1)&745pD~SqHHIaAAK5{;VB!|Y}%oV?*@uMakD!eoXf3DZY zbRbhK$oBq=NwZT%<co6SSG>D@LjwV)$aH?Rz$c~Tx8y)3h~ln^^v;|T4>zfPD`e8t z(~sU=wl^Z(C%6`M37I`N-j#p~0DFp`d2Bw#JjFel6u~AGy${xW^11cPmk{UVM*~wv z)f*u1YP(eQ{dl*nk+6!=sUO`3fVJ;;JvR0|$+vY@awi46esB8^e?;rVY%pYZmv1p2 zR#esal5}$vJ)bhf+i`MI&mv#dDuk75IhCUO175nuS$uwI_U0og+3*^<DCL%W02%S4 zcee!+>W2DGm{&DHUi2p^kX$G<+x@l2x(^Wwky~vu+xO9ltFOEJAQUAeJSH@10{5%B z-u6F$ZHIH4n<**>a+cV)4D<Xd1HGrYxZEnSjfMBR)?SU997;X)XI`62jSim5KR<q6 zdi%kp8S0|dQ&<-%;GECbWzH{=X_qg&dU0HDuNNxabdyd>@WD8|DxJIQXd*qMoOf6^ zmi~b_aQh+b@M|r;(pUp3X$^CZWh%~IJ-#!BHR|WsWqNe#Rx_B3Du^}MTB+rzWCy+p z!H^u|6j=)DHp=8wNZR?!Np|$FimjbWK6RP5`AP)@J|lBq08$G174#R&uGOM@u1R&) zGh0+sr@};CSC5@@()0s*q>|4id8K?te_0Cn_GRuh)w?1i65lq7+x}S|dYvf}u`XN! zIB`w+S`5H39|+A7QJ+s*m6N}f*mhs7#wCBqu~ytjyTHke1*}%0VUAsW)k%pvx1s{K z+C-&5ve2@S{`myITD&(L97wE}%x5OmeTqr0H3GM9#lOr5P>E2kPze68x|PP%ac@lX zf51l!y-=++M2W(s_9bHStD*oYu4iVwH8hxdi0*-O0pp(E^`u3=8mhE&D3wN01^0~p zoCrhW9t=gfk3oO_@vbk!ylXtDnf^zvcIt1?x<vZJdlt=Z$KI7k^`i&;f*C8VE-a=0 zfWv>ra1kda!wT-#KToq5SWGbO+mg`F3OUt1;STL(mv&hQL!>B5`RzWc`>PUmIHk-X z@DVi|)a?2n@WdzYO-|P7-vo5Ist9bVukoy|r>)YXpdCXld+lg#UYzFo2h*@m`YS?H zLWg4?aACZO!wuO#?AXU#+*S3ihQs~%pcM1;Rn_J;Ji>_+Ru#BD=V;}wO4%}c^+M$f z{!yZ~uP^3LRkYchS6xLV8u86L;R9@HL~LE^!Hh^aY^g<aiBrj5zfRSh<tt6kC!b6o zN9UYSJLR9mK;b5FJtIW}<J=E4X_qzKxkqL-Gi?|5Q{@zh>wAhw3xnG(9SvL)O5>BD zPUlAAN4cxq@D_3u<ocD7OTvLweiB-n^p!t(pBkPT2!EW>I<)JUZekckN*OVTcyrUG z_?lb?U7XHzq~?fDDHh*qd)wGi9j?4n?VY*7ax4zgC<!6R>-x0yY*J8)D}#R&76zCm zf;XQ%QQRByr}WxZWMu}NX_dIN^k<#U@0O^tzr+o$m1i6+BfnW6IFp-pKSFHvKftrl z#(7KFQRUzJ#;L4jaIl{dpZXtwqHo#tIez^3pgi%U_(;*EocwR^qSUV0{eEe!SCR(o zQZkB)rY>W~k}(Vn+eC{X59XR!i3UwK`}+qGrRuXX{F?r2+kL{V+;K-*5&te47Stl| zgS4?w2SV1TX!)w9LB2rPuehZAgX5p1WGUtqKQf=|)v(Dw4?@464P67SaFqdWsHMB# zp(%YYdwk3X7A(~JQ^DoSoaG(0L_^7}L*l;&s}RKnp5TWC<`fJJ@#lnxVTe|=GO|)* z`^t5-l^qw#hC7!e2BeP`jYJtaMOA(IGA{cz5OG$b57-SY@hguIFB6yxTPqAy&j%NB znx)=pzyl)Xu9;vb6^p$H1H}ah6aAD+)RoZfehOxzFk&=&?9jDC-KzeeQX5)~DA3Eg zsF}A>2*n_yBh$riYj5rpfx<XL@DaOi<FYY)^F;J<`8J6eRL^Hab8|iGqeYTw`$;4y zIg6DbKH36p&;bj^Bm_*nwYDV{^bovShemvSic5qZqJR!vNvbtcZrYXDA~=KR6J0)5 zIT^=~In)mljD}ln`rwyud#oX?pJKM6g=4BGZCX^SV%mGmdZAlW#6fS1vNbVroctM5 zr48x+8mOAl(n2svprO_c*yN<wH$DN0nMd)6k<XQ=A~HRW(oBN$OO88QOyL~dJBEq? z!I|0@whBqfYU%tT>^ZtWUVsoorcJ_IWV01S4Edy%q>B3cvh}R_)>v(-ScNlh@@Hlq z-lVKxa(T1fAT*_pbHWlKJ>PgE47Hs?1GoFUtzr#%gPFsbW8zVDH9fb6{%Pg%$WCK3 zNL(sbOe!2;<*c@9wU1SkCW$P1?%GCi`A!)}I@?@Xk7~)~6ml0&!(~V@6YsGFEBuHg zQk41HJkOn-+KAvbB5U|9)kTtb^eK!R3~cBiACO$6GNgU0*F;OEW69m{ZwuSmnW9er z0Y`TaR)XKsdl)E_V*{a<%J$xlKFXp-_+RD@Y-*o|W7uZX_ixo806(?SE00lE%V-2| zW#aYd-AXuL6ZRpD)2it)W%NP*67L=Hw!?ui-Ovb+d>#X`P6}o222js8YQ!D1TXFyu zEx-9c5JXn-vz3jXmhKCW`#u>|Vp5$y8_$1jvW)x49L0RpDuqPOq(M10E`-xV7!Z%h z`<R=oRwed-9G!bS)9wGqKQm0yMy4iX#GO-V=w=SHsXOGBv(%kLDjkF&hdB+QG;=O$ zShvGaIdnj&oU%ET$y72jjhOS9IemYh`}d!}JRa=&e0E*e`}KN0bK%jC&mR30ab%|* z?dlO|*gnIX-*DVKsN3G}4%cr|J}D*N<#u(bjxL~wiBa|kq9xD}s*5G4Bo{Q+OlXHi z{jiL~d;-R+Fd5t0??Akq4;ox#HdhDG0u+0Mo91n=)mp{}1xa=5F5yEBv7dYBa$JxR z)vx6qW}f<vDnGoyfF-ev_&MrTPdG5pO?|C>Sap_lp=brOQxRN=)<)|ju2~GHm+g2N z@u~Cs-@q6u$y2=vmgib(zpw*M!Jh9*qTZN}9SvI)Z%U2q`wOBr>K!ha<%cj6>amc( zuB86~Xh$*S&d2fr_EO7hLLT=|UGMXnYSvXIgr6$?8?MCs_2au|njOuYDJ8WvqU=!+ z<6owngx7*hx*Bn27YRe)iy(xtheD#(!tC?)K~%j$8h$D3y9&EDlG}mm4nz9Qpt=Wd zvr8j;pbx`!F_w)w4qUoRU!`k8I`-qHYg7^j)O`o9KMK@TWJ|X~!B~j3vM%<J+1ol8 zx0cY7WB<(^R^%l}3+T+t(HtA!vtAjF4gm$()ea`32+tucF-v-II>KsgOIr|+3|i;M zCjM0vRF$`ulXh{w<aCLGdt8<%+S(TIiBpuevhct{^BXS;-A3KIIY-5P2Q$s!>rcgz z_itpX4~FBskjsMi$A5HTAtXxVQNDwp<F%7%84n1v1rC_P5lc^N)vcmY^ulzc%$Lk3 z_C$-VL@>pU{2XUFXtJ4TZSF%-2h&0S0}RA*no`yljib(bl5(&Pj(z9?JtkWFW2Vu< zBE@i!y5Ll$9>ZNyF=5x)0v;Jlr+7;4R0&OP|4#NGwmHy}B{}TPap=uPLxf*GWakoe zWnHyf`17Y&v1+{(q;ffDhzAnXK^cSMfP-@E#?QXlK=^K%B^oJ(1SuI}f9_F9fHr=k z92_uS-DJ$ia*ipt7$Ae($1t9`TiTA9#oOFe%F)V*(n_pRfj--uVs?pw%y=Vv^z%z` zpDOgWc5zZuN3(L8f4(+5bk`+=2$gp|SOb{GO4Bk(l>B926y0Op135+K(-f=*qocJY zN%4|>Fo68Xz^xuS82V?f+OFFoA|S`D#B1A6^Dp~Cl{-qQRYRNalSwIdTMQ@#gg+Ey zACM+{2U#!pqKfD`+T92cg{?=#7+LtA2U}z^Ij)@Uz|iGYh6I`}0fkcVu`TIzdIFUS z1#fdw>`i|3%v*!qm~t#*VY~PF3|JkTaulzCk7-#czG<_j>dmmTXml`A*$#aIPAND- zo4{f?6QhL$f*uFcwGZ2%sWQ@ls?QU^D{{l-4GZD$5Fm$@MiohPBTlfN12#~xXN6kR z;myk!TN}aIj+{3*7VN)`ozQ6oULooBb_2qja*#pATfvUwVKMm=5R);NBtadHP-3WV zGJ#Vx-)ZcmH%9CCRJ*Ym-S(yjoL!;6qn<bQ7ok)>Fy|TK()`S>)FLLv9;~9oXiK`! zdKp1LptqzXNbOfpA5{w9flr%yg_?tZ!)>?F3ypdtE?2nT17NXZ+34{x;WBd%dycOc z88y6pgZkvkfKlb#`@)`u?dz^rn$^dl)IdCh0eDjYLBP;ZGaDsXMm8R`O#3f?eNt8J z`0UhgpHZ(^rf?wF;90mLo`t9b(YgSE3Lh>x^yTY^zu4e6VPtQ@8ZF$3e!C3|rxpdO z#|I)rNZ`!?1T7nz%zS;Q+qDS5>d#FQq%XAM?DKf*8!mAkt56)9S<L`mOq;LpXP{$9 zZZ##Ph{hK{zay8WPic7NG%s&BDtxu{s`wc6W&+krQOqBd7(~hV(9C)uFe;?o#C!)i z_xA6_-GQh6D;Ii;9F4FgIj-cZ6f|zEhR2w*Gf<esftomEahdtj1Kva|2ig3<SKLTa ztj->`-Xr!votoaXygX<3htW*HI(*o^Z)-+XMnE{jv9v>vSPddL6VbX@*|D(8<KBuE zl(jb9y$wl5UNanSIU`|=FWJG0l#!NBw?VMYW8)amIr#(NOp4&CEo$`&vfMb@`|lN> z9=QV7FpI_q+Rb&PN=jrBFR=YHV1_>rJ8UE<8+ER=I$$|%yRx=bUwV|FQ>U&>C{ewv z{pvEUpr0Wz8dV(9vc`6(y0JT?{fc)pFU8JR#dE&~+yPu*ZZ^}3-$BNlCUv!al_B-r ztep?#3QsM`)kBw5^543=F!rkEKr3;|CyhTqeegA0ZVGTyTgmA1=-yU*>|5;-YnPdI z=&8(8?1dFYw!{3BIsghHcMW?fO6jK#8>N$)VHsdoZKb@G5DN(e^ZV2lG<hfcOJ67( zuYVd^+N*GHD>=5cm!g3QvEFW`7jluq4@<+R*rFNxE`KF^q5#81e%(wqX&P6l2d#TZ z5K@}KhGNF+dLN=N*v@e<GjoV&jlz>xKObc9ULzEhBCk?pgDk9|p=Sl@hW+5U-)fo? z2tiZB)Kj2y{=v<vdSsWD`5=(jPlWv=Z5JSByt^AoK?Jz0lpM)=P1Y%Q>35b~71hw{ z&6j_r`$4-nfB-jZTJ<eHnZIn(4Ko?v+R6T=6xu$hvx@c|MoVA!x?g{bV`nT5Zzgj) z(@%MV5kR-5QOJz&8wKS61tF~i;o$iauRRtt{#$8&w+{uMT+PO7GiAj5CBgz@-@cdH zsu6Y+?Ov?V+C}&M&n#BrKs>I6-iw<8RS@NaXI0?AX}72Tj-zXvC<;{a!LVb~j{muJ zrw&x}mP3i;<;QndCk@jsTF&+6GGNXIfO_2xyFHE5Wh(;p+DK<X<Sa*tC?2Zv3Mf52 z{c*&~b`-JHn^nWH_?3=^mrzjRE8>n=GTCQq``R(MB@PgKf++JG7dnWGuAWqtTb##A zg3aDF_t{x6W3|E}`wjF<ljZtTfM@Pqr)%~+3xrHcDX0UJVmXTZ@o)JpRhpC0Wj=2b z2r3E6uu=&?cW-ZIZgVsAO%qG|aZ-$DUb6<tIcDk8k$yxrhN*P&WX@c7>>W50>;*Sp zJ<`sBLT3v}LYw_@Ia}IrYfV@{*J7Hj6y&aW0uK{{n79U@oN-OiWrh#64z+XPq-Lk& z2$*yFnVpDgZ&tR*WkABPU0!_uCO$s|oOro)-SYo9uKhJy8xR4SaKw@C$VM%tHz!$O z4L<hu91%G3paWwBX&R@Qen|?*_TiaRiZZ@slepWSI1c%`D0s^}^uIos{|UNx+-8MY zs5+xfaUepi+F@Pp?}R0t84UqSpjcW)7~<gA;6@36br$*00;n|(deb?cUXiiQjr$%@ z1>RZ2rGDhg;!LJ?P^Bt_uy~vaPB;Y`JMy0{@kvc=Ojn5+<g7pIH^BkKK;MhG@T6M* z0aUn^%uUG&gQP#HU7qQf5)!3@8zN_>T1JB+5jRfmd9~LR9JCbLUTY~lI_Kr13fYOt z{$*rENfKpe0^MLaE|f-a;U0suRM~kUSc&boy1tMXXt65U^No{zD}IHo^S>x4xfAkK z`L%`+raxPo-RPI*u=CnP;bmR<MSGK-oC9+b5uz;f1rZoAU-+mV)NI)2L&#Vaq)5&q zFJGQF^8wR+8(eYc;P|t*W;ph(bqd;pkRhHTOi^)lBDMrL7*)jl%yQ>)=a~|RN!0@8 z8<j#^EU>!(Zdg!%Y!UEoBv{Vzgv33{M)RSCK51Y?Nv2v9grOewipBi%*J8U8SUk1h z2Wrb-bA$cX2&UN+?tt6c)hf$wOWyig(eEZ0<^&67=VCjGjw{S@R8blvOOrP1V{>H+ z$O5oA<Tt2*Mb+@?(GW@?K~LMD<Q{k+qx;scmRy(=-3?U%EopZzj{giS=b;XpJ^Cbp zGWkiOFHP(BCgeZ1C-TxhhLmnSEui8i2~2KE7Rt<w<|_X^1-PnUZ@Sf}jbGX!*-6>X zK!awNm#43PME=zbR9ZQJE60;8s6?QpffFwSuL!~24ZfVH>dy+MrrF&_{`RO*z3hc$ zNuhpaVcLd;>%l~b#|(^iiW7XgRi;`Er~Co@dNfOI)cjoco4=!=7y{fgm0R4lUO@uh zEF?6?ghk#2->PN$Bd34@LpF--!OfKcWivnj^-6Ifs^eq)rPh!DL!JW4=~?<t`HZ7| z@vt(`S+F?e0-lGS`@P8cW}zfZa}YY^E-hwc&>=hE*vdip4{%4!hM)}<_r)CTBc-_a zZ>E4#fUzb{H5l`(j%MOwBtvOd!=CTBF+0X^11nPyln(feyg+oGvpO~EVjnxCP7P^V zZZm1A>dG%-D1(}awqsepeHE`dwS)ikx{J1eCn+7`Nj00-mhLPu3ejDG%@<F07BA&L zGhGDVYZ6dgyLZ$7pY}Dv+cnb}6_vqUQ8b}MhZ1uFOq5Poyn51Kh^-g}Bjj|r<fQ*d zvdOqwr~pll+i(P$X0!{GmXB4OeYsUX@P_TPqpaOJCu<d<O3PDk6wIY~yKBNKjcB~^ zoowJs(;yuF72`0^s06M~*kfZB1j|Be%f&_0eJfj9n$U2?Ce?98%m{Ip)*r_O<KkD6 z=Rv^r>qEOgpz_~0;~N=FG0Bh4p_qoku@wKG5OXg&WUH}-A{XN|no8mOl#61!wQaXr zzxUi0d$?|GX3~Lwas8P=g?=9z<frAAK_Zl6Jju@cbk4a-b{m*EGH!{iu%>WpWFEU- zl^P3{rc{icj+ux8^*PWjZ4?#Sn89}FO0f@}cOTnY;3=0Ygm({aBLZxJ3{QN#v3VBF z!Xwg&I(l@dU8$xS+K9}Xz?*^T_KwsboYEU;87Mr^=u&8E7Bn)!S5fXMGm4ix3IKlu zg<JObJ7;IXeITn{ss5@zBa#eX2KWwnSxeZ>qEd^3z6uD0)HGUEX(oNrDFegw0F&(X zP$|(K9v-4>3Q9D~^mFWsN$e<aMK(BlmHDdrXlMzlPH^i=wA`VE4~KCb6EXQ(($e!} zK1c?nI706S0+$#xNi!E~nd9kL1Kjqt!w@|O%l1{zZ13!`4?>jcY8zl;KTJPlW%Xs} z3+N|vu9$(?K(fb3pjd5xj0a89a&0_=IA|kn>`SHfuQ7HR#<5RMnk~$1Rm{A*5j1;$ zQB}L4X9G0V%IZr5N}jU(k45?Aj%?#mJUnv4N9fq}crJ9>bWNo&(LE<&)M_}ghP_mt ztqXU+FM$26v)GQA?_N$Io^_@7m{w>16^sGG^G8{;m0HF;lE2b@gUcL-HG(pXx{|+& zAmB;9)cV3JVCGI#CjzEH%bPnb<&M(4ZdUWXYEmaE+oi5vDKNafSjrw*exxs?Rlrrg z20<F_LdztoZ@xmEeL)?iS^S$7aX2uD(7=TXXI9D;?nW~+=pf4*I1>U3+8gc%-zJp& zC1Q;<K^qy<d(Ot@g<3D^2<nCuM?)*tm!zCOu5@(cltB^&=yus}(rsN8V{Iu4DK!-j zYPyY5*{R?8x70J{vblU6B!W|7b&;TlEy96O&VOFl<jE;YnlBbLqBmkfzMsM9n}GSs z<4l>jS2S21=3&fo6T=@9@-o1wKgPAm&Wj(D9}YgAE*4g2Sca7T38OT-NRq<<+CT*u zPjm1Y7TSrw06*C@A|5Q^f2QHO;RsAzskUm8+fcIrJR0dlX8k^DCu@Wm&zQ1nZ-P-A zlwT47-LF=XFwc*xt0hf}<_~yVgoi?#a3vd5_beIAJI4g)?KAf#;`rdXaRm;ad&n(g zV%gH~GBRP8%v|8Edefy}I+m5oT`8k=L;eo_gO?~8i+$->D_|si5RWfA{p7x^sqgP; z9jpyHof)rVwI~vwacXbh$!`NBK3IXiM58ihy3!c?lUYWObF94Ks4QuP9pwzoVdKpZ z4mW`Ct6qxtG?oD$R9U?M-{A5B805#e?SmeDm{5=hK3QO8^za)Fo*Zj?bHCyxt653V zoW#$;u?A<H`c(>dD!epi+=P>n(m=4F>;e-{7J$)bJJI90%Nqg)s$`VJW0n;uHlckO z;O|1&j^7wHB(bZidg<8UhI9*`86NU|jDPM5Yb3>S_dd<1KK{|5vjsZ}@^h?C&2bpa z9EqgXoOY##syg9mSe?CzXY1C6OR@&!J3bmFQr3b{_YqyIoWlueBBTr=Th_1{wJKPg zv+h#G1(}gplBB=eHSu6@x0sX$-h)m*PzvgYro}Eic@Y{<O2}Y)zzh14XUB2i!*Gy} zth)`vu}B+^V!i>enxXYa*r#;5m!x^1bzksli8xYS4_rX_R@j0))3kz_egt^B=ifn^ zV3K=N1><P>j@5vcbeJbP>(!`lPi#T9#89SDEoTHKNm0QXhbY+#;%G2i6FvRRewaEY zWV2VUF(@IvUpx#cSdz8svFt|`9H*`G9mUv<v6t#cL%~;*j*4tPv*gg(s00{2>b-?$ zVIt1gVmyn-3?Kuf3wONVfIIYFiX>U$Q0~Fq54%x5(0-R%EsT+kN%!y#AO?bufQf^0 z*3g!~&}mSnMHOtgdS|>q`0aJ4%2^3iLZhc|9VUB&?{)NgCrv*qPH2agk&WON3jZEt zUeu-fl&`FotTpY-{`ZNX+DC7%;7MEM!$$CLf4ogw6563mh;S>ZX<VD0Jyy~Nh&Bsd zW=KFEXpEg##+9l^s_4f}=(iDc!he#<|1ES%=}1FAcmjur25it^*ZUX6;tEP-7~GH@ zjB5vx3i$WhP0QorGBF{5SAdzlrQf{1?T3UkAK|Gj9r?@{A70@NsY3?qEQBp^p?}bH zx%p7mp45L63i2s@rzSOUI1b)#3>pvtFQ1J5z&$XNtNu8}E%0EHt0B8p3$zOzMDx4h zuvqY|qxYrV3xbvtg1XIf_XN0661VqJP)tz`gSxi}8V7d5gD#q2z#!jMlHysm3#U$K z8(G#(xU03y9Hsm6m{E>UkIK*|I`6z_rnjHibn*jD<%RYSeY3Ba%X3v;4Zr=2In4;B z${YZ~){=#^Jm%4#16X^U=Qy&ve`f*)-gWrr@+*96txjJBDmE=WPobb_vB+phi6}z7 z45}ztnz0$7-1-6iAQ@=7G$U*~=oM8Fh@{q_MjE^pHXN`0-Q$flh6|W=qBbp*bE~*d zsaZ&|M2@RzeuK@e_xe4T=#rrciHA*nm<(`h4>Si+((I(k1r!6u#_h7sS*0LTUw<jd zf?be2vDz;=g1S;uNAZdDr($to^6}QFEzkl{BG=^~@SY+o16VsoUd^k!DbYUNB%sB% z(3?=J=|(T*g&gJx=;>fc8=riaczHDGh$!SaX3ybgnoUDo|A@J5UCHg$fBxnjc_p6? z6A90&>}_<;I+>{~Ycw|g`=U?5>o()cqz-gt`Ch%}f$I=zDjV(Pet|DFym?;b2iR*; zU=8ik_@-B)iJpUQ&yrH+q9hlL%9ZMrvY>V5{{u|RGI!+190q(NKR?agaT!abt_&O( zl*G85)d;v&hNQSw>K8uNJhJXS2@YNj_s_o0Q^(x4feuycU(7NhwW}M1?zJhHMims= zZVYB!4L?^pk!!`ZZMYcPyX$B>n_K<#pW=HOHBD9Z^A2y<ELw`ZKr#DUG2ASyjQ!kA zADegAsV;rjq;+*w$y<ximV~j)A}*|t9CM=g`Nx!+dq_!pCiM5RVp*t#`jyS1F_j`b zqUX$=Q)7iAhpqVXIIzyLi&5ijt!8iGrpUsRV{($QoFnP_OX;{Ri=1+cb9wHtf`spl zy)Ttt+>w;H+l1lFKli#~@H{=x9<>j3so-f(Aeok1nQL%zZ{@1U-jM1`=vu4{^DDO? zQJ=V}EAOX3Hhx#?XE0m`WFE)N^N;p@OS)WH>Frz*I4UEcfasc!DffdZUuwT#2i^zq zBKhF_j6C!@e)oMfeF-GvTAyqKi8qYtrH7QY|Ioi^2*khh`L2Aoj2Ltyv*q8b8TU=p z6}ty%KUbdI;GOD>SNEoUj9p1)loi*Rt$iFRrsn5~Y%UV<6&S;gF{?g{#_%e;jDCcJ z%NdE%6RFP(V4tMWvgdIe=3>Pn6kVRAW3;Duiw!mz5Vm%l+LK=6R0H4CBFsbOhMqg@ zebRefjh)&x75Qu6*9RioxSg?gmyiybAmp6dce*~zKgMr7j`s6IV{*yCqUd!NX)&I@ z7go32rq&tn75j6Z_#=bu)O`&?oXY@b3yf)8`H>bg4Juqi=AdS&wQ^$%gZ4*u?%%gi z1bwsWCJ=2V{Kx9V%?D8y{IaMTs@7)3QzFtQ_k4VwYk&VOCjP&>)~`2uql|O!vj!pb zeJZWu=-bcgl!}8s9<)Hsc=#wA&JE<FKls#+T}UK4WD6|vmX#MQ8B?utq37JacJ@s( z(Z*;wUWw~Dw;axct~y^}WhZw_CxTk_GMu<y$!LvTaz>YitsiPsFI-2I-o&D19-p;s zHteJU7{T(4OVby=-gKp<W#Qx9+rzEk@zm`KwOb#hskwUs)>uL=Y(XULjj~^GtG$1$ zbl|f_;#C=AFMSi$Ql;Ir!N`=(=V!TT$5OT1I)12}TkUdw@$s?}ny&zqE%O&~Q?{(V zQz|RGA7Ns194ONP^hp{I*EqD4bw$)#Tst}V8J($Ty#>3DA)bt4Zd%857f7s!JsFtX zK@JBT&U2F9AB)p7tT$=DqTz#HN*JiW_S=yzIvnO8q4o6TsGX`n=KQs0O%#sr6W9Fw z@0>bXj{&edR+@h6HrnU=ghfsk(xrv9n=kjvtz|_mZS#UOZ95rC%ke*(xB9Y1kgdsB z6JU~Umz7NR)+jf2O2>7e2CS9qF)rt2KL;Pagx0qC;Ad<Cjwq){XVV8y`KJ(D;^HYj zw7iaO82L-eU!aTN?%gBQK*Dj;;NJYUPJf=pzis}PFJ#0|H(QYlu*}*>AC&UVq}nqN z&e=V=A5|196D|lCYua$Xxo7;L+$on_Yb6*=y?O%nA<}*C?<)_ll%CKv^s4&Q*5E~Y z75UX=u)Fes@$7TeTB7XB&k1a|es`S9@^Yn%+daYQ%z7_UJ#=v-+{}6{x#ZgYc!hhn zsJR|5#!f*gFi+F3H>Zvo40oqzs15EmUds(tHo)&Wd0MQ1*)uF=yIuEJm`2*MDnDRm zX1QwM@0NMYg|fKh`3Fq`uzR#VH{W>r){%E6>XqWp{T;j$zKh~6R=>T=DLiU-5W^S+ z-Oy32o6r8`MCyP-gCB&eiJ=RUjqiMS{t#IdMkEVU*5#X$4{UQm=4j=^u4U0>^5)X2 z-=O))Uzk(J*1tph_I-|0;J1ZG{q=2*a%S=xr)KG&cmCsL(Z0`7-<$WJW39PK69&>G z-vvvTW6(20GvEK5KCn1Df4lqB6;h!;vFgyhoJ=EVnA0-yPW0_f4UfG$YIU69#X*dn zFLZ^F6D8avrS3Sgu%ohOIuyv(=V-Z24U*<Pcc>CW7v#F=>5C4C##cu~euc_c@>F4^ zfLnmj_TfUtYl{!b<IfAX$f-k$cQq$K2;2Lj5y_Ju-X%~YZi(7s8C8mP(%%wmGIs;- zO*j`@-aqF5*yh~bZz84zk3N-7jY(drIw8Mh_$Zl0PQH8ge?W^dNo`bgbGS70>*k^V z0aQfw<7=WV%di8{GB1~wVJStwTz8M`rY_YOFYtb2dd@t*$DYQJAeZ89E0s*b3?|_s zjAgp+XRsj=@;-0DKWDGb@e2EIspq8d_XH_Rh%{&H{1NU8F(1VY#POOJ<4aSXk4pnK zk7-c-o$j!(W{B33hyXU*bv?Swzh%yfNb1|FuPSbhy0)mhb$DGxVo}wRo#-LgKXUi^ z&Fe);x2dHcyMl`U1K9|u8A74!^Oj>L(lPXe9<Ms_9YV?3Yp(2j@+w<C_-fMvaH_F( zFq~^8+^caXzvPX5i9N9cstK)r{`aYGvU5fXHh7pSJ;<S209D9QbP;<v)^VY$0A-AC zv~`sI)H#~Vh2mMWSQED3f*j8GP2c$smt8H_=F8LGLYF@K{ji!N{f>J2x<#+o;O`i7 z-+A<}H)l&|#&_){`>tN7=MZ6a4r3Q?J(8Nuu4qjjMPyUR5O&?jh3q=qWP|#1ucA?D ze4ts3a?P1%?Q%$8L97D(Zid9wAh3xKw>Lxh-@K%Bo)_>l;yig)6bSmmqsf7~z1GM( zCk$|*i@Y0j-|Creg5HO(&P{|u$#Gu`Z>6_r?5t^g>GQ!^_`$mpw~DkmozZX{w700Y zXed@m=fOxCbgXG=CtBy+wPmRjhx!*=e=8D)wV}#Mu-?k;Qm^9*B6jT3wl224^Dn)k zFw45PR3A*Lhg^GW2;E=VEHa2tayd1RtT=ncr%~p9hch4!k1tq^IDK&LkK)}Aq%CG~ z76tuf%e&McYz=e<WghL~(&2$pPyYv8p$@RR-#jqSN}vbFwXZ(^a#wJuqna6}XeMc0 zU16HIPBoV+8w^F0V_)g)zL{op#j(WJpTiv<9w;BS)yV&)saH?Lb5s$2p{3{S&xOUG zbB(reT3;=D@bmf)Ij8E6he&iWGnJgHJG}z?htuEx9?MK=Rj(+lT8rHL)@z}DIyGB; zOcji-M{7YJ)jqP(ld)x}qG?ZiWCYyGn<2K|x1Edp#|DGjVU>ek^iYeO{Mef{Z5_DO zdOuPDJ=P-(edguIH93t+=?BfAe6eOOgBH8(W*`>!N|se4F%<WT?h}UTdhK4YC-cZh zpY5~#>wH<l#>&4L?ac}i;H9=G?S^;eA67$el57Q~)^%ek=~|U+u>Di-CC?r^d!Tm2 zLagS}2+}8kMv2_K^vZvfnj2rLPt5|=5)1a%3P$YiEdEe>4}-?>;)p5<#pjDR{!+W! zwNO_HtU#A5EjCZQdG-D-OMjP!*)lo|T34<7^lGc)%?KI0<LYItDklnO(}d@L{o*<9 zx}5sf%3M`ZlR|)hbxLioX&bP8@Z#8c8$d<BKZNt`S^K`TLmC7V&tm>~ov`0+>i(%) zl@DN)qJ);2X1`@tboBKA*=L_Ri=>a2fdR^u<0jWnS<CSs4D4EF_ZDR;fBt>)OR|h% z^Tf?Flgi_xg!flfwqhw2r<9VeZHOXV654>%`}0OqKR(q~3!iMX&#kDP85>0WY4D<Y zPr^iSO7&v;aSM!c8b~5HbGhvHBO|SWTQxRERJQxAJ#Ep2(dfjIsPbFZb@tk7+$V8g zfB$&ZXf+wm_pPota|Bc9m$^@^#3^nvLOkVVrKh!WbDh`z>l*rsEz29hXRe;9e-p0B z^Y^*d7s56V<plh5`oPNb6{GB${>jjU9@6*cA*NU3uHR-p7OwrW7O8vM>d?Zx1O;HM zy?uy%bI)MSKaCqN-v@Vp-71eWdUMsH@3vO%t(<HFg!lJ>YTINTEK!+8fS<fEXvbl) zHGTc&O?4Kwb&o+3y@Ko=l#Q18Jz^iZf1SM&!LsmJ(JUBT*!bEdf521y&5GlDID-50 zY0i%Py6av^>oe4xkO@*DQ)KQ4b29ql;f>NDYo{3s3<VC)&hEcalVK2uP^aMt;|foh zCK)ARUd9$NPSijwGL$*|Zq4bHUBNk`h10;F;yWjl-;;<ky$jp)g=9Hc=#{G?YZz*U z9S~suHPimLuZF(Y#V0P`VSm<K>tPi*wjak1@)2C~jU5I1Ym$zbobwq|v>$5>X&`AJ zHI542=tM`lv1&szEdMA{+<k{vr)-5F%<JVy4JifLuuCnMe?8kSwF5RkT-qN*rOOoH zw<p9}PN3DsOw4>Vt3emxRKIjGC$)I-Ys7%*sz#V{&FSzp)}gb*zo|?43<;d-s6d7O z`)S*agL^v;NK(BjErREGnbEq(&ma4>$ls-giKNmKVLi)j1~$%G{|IDU8Ute*d!JpG z|Jc5|xAo0=QWsw=n5%Gg<HzjugY#bWV6M``+TopAEsc^=;dkRRnYmwsT(JS~o0{1U z{y&~QJ#^@hUHoUwA(w_)^1Oaq$iS`6^Agsb$Zkt?aCi93jEA7VRlN5T?ffTy11Xdy zK~2e8WjhhTrwev%{e@VX`R768ue$6}zbGI`G3ec1i^3dl-F<0cB(C|w&*GbPn+FCM z8c7}PO7@5$Jl3MnmUwPypB399$ztnF-+^22zG=)JA?Zx(Sq=cK9vD>d_lsBeN#l>p z`|d2xOW_r3`bj+kZd%FNx9=Zuf}4sfs529QBd~P?c$VHFW}Yb{ml#6GK$E_goYT)9 z*;r|s*5}Sw7!G~D9XQhvVz>VqAJM=Ttv<hdPLI*wRQU}PK3+#83l@czjPz&FNROj% z`7Y^b6Lp@dG$;SLUY+fJ^yQ;Zz$o#y&iThmwPr;gW$GlA<i;MK`3eX5^IMr(qNZE# z*?x`^#y{5FD`+r=u+8t<(yLpoOKVBixM#gBC#Ut}+Gkw;`BdAhaMvqm;CYYsjU<Zj zO62)}k6ckYb@78_=%QhogYBnkhZi@U{yLlfLh8rEF-|3T-BYz#HM_2PIFybK+14S{ zcHP1?_?cEr|IviQBxytb*Rwc3J^Nidm9ae&7w#9j!m$MXMfE@LDm*w8YNGQ->2Y7= zvarqB;H`1zhky8pBX3l;lY$HCpZ3hDoZFcNR3RV*vnyo{Vg41Z{H)$XS62VEgF|23 zih_4~gzqIm9G5xfcnbYTP7`aSA#lv025EIJund50zJrrhZW^ArX?s%ZewRg{nU@Mv znUpe6d(K!qsD?UbtkMtiEqiNTQG7lnD0PZ4z|)H|d+dTj-hP8hD_gz*H2|Jdp7++I z@25sQK%Q>7He^qpRUJo1k}leX9}gI`d>wHl9i|jacmMR|)SHaEUA|+x>2oM3uOwQH zPkPIOq9#n(q;+@v#YAOf_lwn|hZ706?F9w4l?FB&(FEx>NJ3liLBS`-=d)r33Cw`` z=lLEnlYb06&+0Ij*ot)!dh}N1c4^EWPc6DsIekaS@n^<)Fl_Yqb0&?aF~RsG)2I)x z_3x?d@;dRR&?KYU5|nPOZn!$hdY~5XEA5%s!U}o4_ruc1=0nRbmFQE0dq4*^LgV-c zTfW@jtO>GhQa@{oWsTQ9V4@KGiek+`lV_CmImmfepj`83b0_Gj*7+A^{0rvoHyGlQ z%Dj#aT|>Lyy~)3G$7|MaFIkygC+OB4Tq*neV})sen@@*1?H&B)M{`T4#;4}62=9?( z(rCuunrevf(PXRqku<Gu#V-08X+tK?;X*F1?68mI$Rb1p#-V?rNiM_BKAbPE^fXvE z52g)O<IryBH9~x}Mecx4*&k$d7`uc_xV%Ju9A@F$zi8ppaGlTw>cK*H+*mJF-?}t= z*U?Ec89y7&4{HnDl_h)WzQAUPU~wizF#73jLXxQ1dyzyj+I0PwYxHVtkIB7w8nMIt z*3QIC@7vG24jJ#9NRBx7*NvxZR;GyOffI^LQc5z9t%6&?{`*X!ly}la#p`wZiGPb- zIJBa>IOFLs(iZ&7$hftzs8Gxt`RLXimCHVBq{Eew0eBc+cVf>O{(iZWEoJ=Btq(bQ zBY)O$Llhhp{yBbXBjjRl#h}6GAYQvfWN4LSkiYefljmd?EoKo@Q%-(3je^!J9$~~e zV{!-&UMjfuJ8WLaUO|l?yQ@x<@aYRQoQ`x!o6X6y9-N{f?E5B`zP>QbSllGJX+DsW zH!u{_Pfg&01n4D)1CxzD)tB$`UwE4>M(^Z^HW$=CQvI*okvG%xxp%iyY}CIAs@Mem zp0eTci+Qitpy#i#y}a;FK@Ld38R5=XCH)!M_x7!E#bxv9)QcH$!z#%e?)Llgs6Pr( zz8SxdV;u&0>_&yChC$`VK!hign<jL#?ntP%nlJ%I<)%O{)ETvd@QW&5f)CO4zZ*KR zQRm9{7@v3$)Ec}qi*1Z8oB7YNkY9CZ$zLPqaagY8uXiCk7jww&skg)4z1Q)GkOLqB zbtqF=A_7^-x*E>usLS{+*>KJ3i^<Ku&mVYn<^E9D*9VwiJc>i9;l}sZ*NpUk@cxoj zxQ-2UP`WF<YeRae3USWiH*a=#bw2G!Gv16G%26gSSKZ`3PcpKX-GIZ1vmg3bEB*d@ z9D1xoJm>T7YmC}EtYJehe-mid#L%Rju7z9>a-}<1=-jGgS}_u_a#3hAQKNnucSUZY zouxl%>TYU;8{U6`qR#z3*B-o>4gg`8i@k4-=p66TsdxNa{4m~e;g#EI+r{$@j~}y4 zJZ8>r%To{vdTHawcp8u=#Nc$p0;#DBQlEr}|FMk8gePc(!Jtg^nacM|*Pp9M?fF6G zr`>4fl2+FfqTZO#tZth;pCKvEX!IMDCwZ)FkNe|w&Z<N(%?{t+TO*2bBsPnySdV!= z@r&wj(Hi7^aE{#5`0d@>FM;Fv|7t5DaO|Fq??rz}^C*y(RGzh`B+T|UF!GxFdUry8 zCBM*ay9XzHv{ooxdu;bPL}w*9hzBcRw49MgEfT@>9Kn%kYej{bpRn!mq%R2uBcCoK zViFdg>0_jgibH?O-rIl1ZP(6wjkFm16SAZks&Cz*0{2rxifNfdOBM@t)Gk`z!#=?{ ztD;qrojEsV2J#K3qr*4gU%w3wvCetL*~JC^4edZdRVa{w`p@@%<I?1|5{<^q_dGLU z_m<CyMHvrm7BY{GnC(-e%Z640f(aZOS~cSMkZQ9_!$@pqXI|ZWCj@fg>dz*thKOc8 zQ`&HT;Eu7~fVOIl%t65*;#-4D;%%VT2gSmfOc106Ti$uz7shA(kHpciMhW0rY`bM0 zq*?R30ChXf`KlhQ-HjHm@-@F0akLH2+`aij>VH7v<&=hz#Or?^d2tj$r4jBd-c&;$ zP0?hxTlC9k(f8C>GGBtK2<E(1fZ0e=av%|+mft?Ba5cEM(IDoa<*LIy<JxYQu{Y`H zkdEe^`Yqk%I(~-SmNAGL-N939X9@3QO2F`cRK`U*M$yM8cHixK6k@RZ#pOkV)^v+I zk4Bjd#|#I84xLd~za~0mW+_;%DqX&PcFXKK@|jrfR|*;wZ+`>T5i*J5YA=&r&p<aT z$m4zP+?YMQLwQOTHa4yT+Pa$SfuGO<_63Q~PtC{2h~u#Bvn-2b&6Ew@<{cew2q$45 zSij7@^3b(W$H#;J{8OqZ_}d5HTGh`=JhWAX+j_@117H8=N?Oa@%SnuQKpjKp?dL^p z9FC_cPQJZ;6K#F`pik-ZeMLz%Nq+gvV5+vt&#!;h$G(p0%EX}oM3p)^h0D&{`z}fr z9Cko5I>5PT*@#U$M{|_rV7aXD$G)QhmtGQU%8$M|yP@Nod2>nrR}M4lb~I+&V(=|y z6>3b#sH)!48@}<4bp4e0V%sWj1W8N28DYyz^Y8z2ahx@EIeyhecA(t9hS{_7l!ES# zuW4+JwgKMY17p178-h%u2?sVXt7jh?KRX|%mu9f3y<fUDZSBm5sQG{W*JGbW4>umz zfj(Nh_~X*m&C~Uxn*Fn3g{yx(cA0PAdV2Wy7qD#6lI<-LQeFLUQ{3gJ#y7-^e1W55 zZtbIq%V5g_t)xCI>ZN@2ePf<B8#nMU4W!cGYiw|6U+&h1qj-=C)@<HXnyISD5h+~X zxloV?238MLd^95RX*Q+zu9by?nfNKE8d0)G^;E%Y?}vdn@K(?*>@Wmst_Smr-AFvA zZWZRMsJ`{<5plrPM;RXRtC&}(>btw!p@aw@;U1)*BAg8iO#2SwV2e*BpLV)W2B!db zZjT0P`A0uA2Z1V#qO8+5fct~KDl3Y&M?th2ZcE3?U*A#gl~;&*#stVm$8I{yr?;jc zJY0}q;;of|Jm6^3c5DlD)Vu-^LaMX8jl;3lDXuz*0)s-nmlz*<%o92BXwkYvF|wen z%o@3qoOOCCgNp=OOw0MkVASiH$>^RUhGhEE_Yy39hOJ(C60laE*2vjWX{D}~Np3U5 zT;t+zToru~im#U4<J8rF<FKn;OC7MW9gl6DKb_urEjxirk9G1-8nS-$XaF%b-&}9x z<xN>gI~wha2IsfQbCTUAY*?*DHe+lZdX%dCrWt(O7k4A0XZNep5`#G^43~AkI4-V> zlvV;*XSO9MH{|*%<H3Q9!&~=jm<B5k_>ccmVu+u!Y<i5s{z@tJDJn=mJg!ii)csMM z)V=4#Pa@_pFA%neO-NHFoi?~)gEvjHTxP-nvmEOoMS(OqBW+TjxMwOq0mkDsf(edC z=ZDpcWTJ|A!qXbSx?0LDMPaK<LYwYU4M=+IeH;i2l+82<LJ-4L3LjqV%&5tyr*_5^ z#x1uINaD3t*5c$ySDhFz?*V2sAPFcKuS}T)21zlwDk7GCKjKDiSqHvh>2#CH8A3cY zD-Epj6zp<@D^VfCQ;vcUz1Z-J%o6j&t4Gsv)>*L)r<>6+9{=H+QtM%86;|%Y@eFE+ z>hgx`owT<Na0%<la3U<GF%i%k8d~Uvtd;6!Emh1Y<JZA>h9P@X6CLS1+k9nba{MO+ z{W*t)#qr_s|N7DAa2k9PyO+MJ$)t%L^Rs@n)GH#-C2@Ifjwl(XYw^iP$#R7-LR7y4 z1MmB1tYJEz2O+fUhKX<+rN-^EZ2&fhHSCZrLk@Yu=2Y)RIGc?wx9RRuNC*+sVH~<M zI%m^qkpBVawh3zID0E499$U4l9KVwz*SWxknSiYwedqjo$EHf_PHQ55yZmw9hbXV; zVM|KH76MFJX*EHW=HYmYg6uD>!GzTHfD%X_LO=5M??=*J6?6y>9G2JI`sC^r;`Fmf z>2JlDh0PzUTRJBN4_fF^AF^d6onBF}mMiT-kYtDUUR{Xe#DcznZ*w+oHtO_|aPtBJ z=QX}>*LgIg>Ax;2hSUIxqr{E@6f0Qg50ts~1k6u`6`!%a1y6vYN<Lj7&zpJ$>DyXE zHRCuAOHGU(WYov`Q;x-;598SV0vnF`>UJd8pi57EG-L7dWi**gI?a1yR4b*Z;REuA zuZh|8B<kFcXO}Ir{gd($pGMPL)zQApSpS&pp}W>6n*_TTcP?^M$nr@*oqc21F^J}n zTTuN58g2@4uE;F0(JU8o3-aHT6?Kk@LJ6vKbL_ejy9y?`vE9{p!D}2`TTiij8o(?G z8jXcjErN}s_7M;AgH5I~T)(#{&FhYK|2k31Z9J{~_Z_vIK;X(H9#~kk1?XZ*n6Tkt zray(d?h&ezJ4@gk`<iY*A2CcE+KIm2CKo<=N<(`YJa}Gn&4mHLDIm4A)B(5lpX4Px z`d#^EJ-9mynJMfoy>&M<|8o|L^PYtOz-c{AdcGe$x)_crG$VrqRmH=3AzDUMuf>ls z^bKbf)KN!r9G5hU;DY7N!gmd{&~$pj^4d<e(W*vZKL<C!1Y&i7o53GT@{&UYs-Xf# z@g@E!c7Oy1mivB*Eek>otj*$<i`D<V5{|xnd&6gdBH28&B%>vy#t=%>q+PW}%QO?( zmCGzVEn>5Me2W0W$6i6AeFDg8W`kh?aS0vxn7FL9OB>`oAuNmTQwcl9U9&eZl~^u8 zb*sa}RdbXZr2#8vr}IU#I>8gym9DWQPYKd2ZH>Lg@o#C?^~ZiDOB+4x_(hSac#*{V z$*x02Z_RKjHiEee$l|CkEGdBr;U5ER6JR4cPL7)+LU5Z!Ow_?FS{lnnJPb@gIcLI5 za4g(-iX%jV*u=T<N%oUuCk+CUAd3$tXzecp7SeJ<*d>}6)p7HLZGukZEg;*3*m`7m z0n?d4Y-fE{zX?8Ekku0RiJ|*plXx&`My=fC&a&Y{c;K<uCJ;Wor-{^UVCvgTIgsq@ zkYlL>H%)VBd5F8v&@^D8yj^1t(u&8RWs}zLvD>}%itL{to5p0K6{N38;<X|D&w4N6 z88j1dvZFl!RUAMHYF3NGMCWYNOM>gr(a~=m#Y}ClYGXRZ5@`7`jU}304FS0@4|G(K z$~bZ+?*hXMU=;L&Jv5=s=>Cg`=bt9w-_8f>Z-5LJnZXA4t|lj{%5mrnS5rCIUhPDI zRdl!egcRGM#4IHIDu1CcYj&K#`ALyd-Zhw@T4`P7sRhZkIG-7&CZYxDgZc{bqrj}o zlFE4D(z*+z`+M`@a2^QVt%a4C>zn*x<tm_H0VvptGEzK#d3(DakK4JJq`mV`g{}{U zM--F^xgT`&vlTt&!NY2KXzFMd1#aC%!B0S#{({2XaXhYsw3rbe4#3}=I$t4W20C<o zuPO~^=>KsSsup2Zlfa2`ge<}warkhYBL01OzZ*ZJXJOE{2d@1h$Ln~_(th!Uf>^k= zn-v!EdC<#;U<(BLp(}&Pfd2XyiqXGRXghD_`{J~AqeU<UBBH?~ltnX6a>H>Ch6=&< z0AQO~J1!0{_JJu*{avp!Vky1`hF&HyjZ7z7xM}DV82<!xeXjP{c!e#@^yX)`qf90p z*153I6;zvQ=R#UQ5QzxA9Afcq1w$!b{7CWgU;eK`>DapNUI`IAQNCd$!K2S~n=WPT zAc1#f&4j>h%QiED5h*^#yD-2uJ->hOjq-MEd)dW6oub)gXH%+-quA&JP0UdrVH!x_ zujIxp`OZ(6l&Dc8?0*vd7SfnEBn|e*lTx38pz!`PUg`^Syze3(a2dAg{jwU|djEc& z03vFYpim%C$y|RL5Pr*52yXXkHBlz$FEgOmJx*=ek*FJ?Z02(vijAEZ496C2X^Boe zJdyS=z=U5%vOkfK>_6nti8Vn2^vipVQX8zI@gR8<i;BwiSVn<K7iUQ;sN8VjlE_&t z@C0_M@Zo>Oxg;$}vA-E9$tSg5m_`m=#F+cyfQ`s#9W2%!HYAPB6V=XJ<RY)ol%Ui_ zGkKmc1#o7nTtqM8wNF6?>_0+Sgu>@i7OTOW`En2yC~}R}7b)0`q7m~9D1=8As29AG zb}XsG<QZ;&CfzfncPwD$)pGM(#z01AgRTYOZxq*k5)jv!RYz+<X+s2^fI%~i@_vil zX#(O#m?tc1c81IJ%&u%W`!srt^|=*TXb0EIHFc>biCqPzD_e;+>O-4Vxe|P@Ad6RA z3WA`v^&vi^Sz6R2Er|me-3OEihVuxg?EwP>(JFdf@LvkGuui&Fu^qK)QScQNo@)dT zB;0Srv^$DDFneRdHb=DNy7H^+Aj4GnbpgP~RN~7k>K!4{fs%&t_=#hG=q&K%I|Ov! z#bVJra6;6zSU4*f2HD+z81It8*W=V_Sp9yoOSE``ui{pk`ur48>YZ_Cqh)`Z@c6WA ziy$7{1HYe}*2eK(Re%Nu;hepIJUbE2`9OFs>0@2wwXbD#BT}GTeroWCc{Pq7{e`#T z67-Q;-6UzBH(p{BgqrnkKf^vTN8DpFx~kYAC@=+ckTUMqh*;z;%ug^YSJWvnPO&nm zM@L64Sp9;-wqA~B)I9=7YUkCjd3eG5OO;!7DeqRnFLOw_u}(g7y&gABXvwP^WBZY4 zT9EUUcaUz<aGVVklP$9uh()aT7!|$^&Y1cZ|C9zfEQ!N`H?%b$#SF3In;$67IS*BH z%<PXZ^Wi`HD0}J^rQIQxb32hPl7>r{3<te>pl>Fuf1<X^n~>5j8ggkK&PRva|Ks;B z$ZtUG9Q7&s|8HH}iZiCm)5Fx~nMtiWA%dzW#TSaM?`oRpUs*nuyyra;I26J82MADd zr&$h42~+Ih`_(L?_D0M&UtZgMW=O+X{OsfKp_}ibPcg)mBfJyaRY~*^#;yLVe@M>R zN53iQcY#va>)~v$0{}VsF)p0rD2X>r0UWV0_H;C@|G(V#lVG+pA^C|)?p&MFx#I~m zCC1!Ln@*jzPd64(v#kZN2C*GYXgQX(1EZu%<t!c2JdJp=lbx@m8P;f?j#K9%DZqOY zjS{lTc@C(PSo+)ywr1UHJ)lF0=xG`p$K}0N9RPOsR8AwhwzjnnQ)FgThQO{Z5`gmo z1R70_acw+me}_cBj9?Wk;B=K{E)-?j<KHfizdn}Gewo)K?n{HAz~1FY+2imcD(#8I zhwLw}{PrYXGNmOe<C7H*Su7>C19i%r=T=2s((m!aaZOAK0LxKZdd00HbiOM{L52!= zC7PBU!mSV4V`j$-sAQk-)yIHoBdog#s#AqvdqXTW(NSt;f>1SLD@TjCm>U!sjVq;! z8Pi7>*i0c&N}7TgG7;4lW~&TcCtelB2%F6XsFf}4m|KkviaKN!@ZrkN$w;wbkEt|R z66`>bsFjH;yp5>(R3#|7#$H&h$2S;O!{aRyj-}XJYl_Pp9YU#4TvHf)9jdYTB?`K; z2#_hqzX!L|o*9;cthhP0a;!A*u01l)x{KC7mttCp8dn!`i2D7G;wi|W66-F|Q(QV@ zGH`z^T{4^>86x<WIKTs$;7529!C70ACkGAR+?A+@RrU0U$GA={flb}$Swz*CgVM{F zyR!<SVGiR1kDeHy<iW~)6tgt)b{jq~U2T(1Y61^lVB9e|uvJD^@0-U`p#$f&xJ-e5 z=6UgrWo88_K9qbVX0CDFc@Gu0{d3NxCxr9*s@RNFE<xSPDX~LU{*Bcf6CIOdYOQwb zlcWLGfwZHN{a$u7X*|?4ok3~?j`t)waiB+*ZVT#0degM$jq;0@Mnh23I^VOy{CwI$ z+84NkbgsVe?CcE7z^obxaqkqLfx*CQQN(Li@jXLQ-K3$4j=Iq~7)%qYh<0o@XboKD zn9GE$9fO>+)!v<u&<7cKv{|IiK(Whp&pa@?yJ$5VXeOxZefqXuv{YvvNe4YRVZIuv zeYs{!iQ~X%5Hi*_HxOHLHn?dgM+wpcKF$9F4pG$26FHyU?(XKQ3vJw!94$Fj3}%aY zo8CCo%)w6}w9`>i>|7oVX#@VU_2;z<zN1PM+cgTamzBHqf6{{>?dD<1kZ#kyYrxc! zOmyF5WXN;iIKo89jiX*l&>JeRpK6D4%Wl2;g}hwn7tp-<M!51T`zhe+mDSB67&AQ! zmLV!c&t0laPh%4Mf51hN^URu3c*l^ixkSdW)wjku$O=yeC6!wYiS|ML#bptx@QDCp zyDOb8Q>)LKR%!HrH#veVIh{^PhZx+J$xLr?^PbcX>m1Et@Ou9>@wohAy!8+cZ|w(R z;Ts%nmg?fI^m9m4;86&v68y@mFkA4I9FvV6i7<N$`IZsCHyk&L<jbY8DCj3aNUES` zY28;@;?Lu?#9Q@ESNsj?XK|eOwo*9pt<>)SYJe+^wuxuVQQVBoMq^E7QX26ZWY9+$ z*FKl#Ed<?o50rMlNOEfuj5YZOcUvTE>0FU!U`+%8op`cKXd)(9e2Z!(*AGsI0N+l@ z4oNFeA93tHYqxw{W@I6AY~W!ynjYFt$Y|5@SfEEP<B$L+E8r)fsoO`ghD0Vb33@5+ z`MGGsd){j^r6dFhBLGO!2E^`NlRDU<@Z;euqbfhz^-qDj%xO(3NePSTuu`H*YXR92 zD)~(jrLh;wNc+@Rtia1i9mK37deeqp!kht&_Dmu3hJugiTtqi<ynbzs0sWk&T5H0u z^6=TZE;f^qgl&ES?4WzcJ_J5Ze-h4i@N>GO>fJ13@t*Jx;PCKwH#}V3B7f3O<`yPo zdzeWMh}yXmCbaIVx#tN{r3XfW@FQseTR}wgL;kx+XGRtKo2WT#FVVI_n01F0q|EFC zBib!q<sG&}5o0_MT}U9;nHk%~a)@1O)6sJ;(?r3(BYkdEep%Ae37^$&y%yw7;?p-m zIAb$J$-zUR53Dd@%*JJ=j&6Ok&I!o@N!W;k+aFj!>FuUqxZm}u>Y@NQW@X65j3Xgx zBA;yz^x^oT`jpT`SKmtFEWn_W`eJPZ@7+B)2$+*NFyTM@zLldse$sD3bqI$4l!2)J zR5%~xKLJy6{~yq&)5UAK`{68zwMZvTI{3vX9IT*66VTCGJUY$(`T<4fmQE?Rj&6hK zh8?k|2HNf3RJeXxZ|xsxRJo)pP#OqTf69A`>o)@3ZQUd;5^`2uYlP^%$X{JUdUyXG z*QAAWO2I70&Gro9@xg?i|K7ouJFOMFv9Sk$GFJuN)G`YXpSTsKchD{YT5_gvzSMTK zoTisII2tR5w}fuEIH31=CYUcIun5~B5cInsD;ydQqOnh^12|Qg5OvfHZ<(3;6w{Gk z8Ee1u6%r;=47BGD8-p^-hp$0Rf(S;}<DY64Q0H~TD$L*QbE+TR#|J@<>#o$$%lgFD zq;_-$XM0KLxL-#yV$ky9iGtR_*szq>HMxTCI)iF#b!OeS$4OG>YXk9wjbU5=(IAYt zY)k-=v7#DQ;(J$57HoNkmO=rK@*SZGrYr3Rd28GsZ2epol;TNF@VJ@`j(s?^>a{l1 z|9oMeqj>Dw2+1BB|6wOubmH#1G0y+-bngF5{{J7pW|)Mfct^(6lv4+XVh*!WIVI=Q zyHtd9aM;kC&!IG%V^l(K$8<nBA99L0WisV7$I&cj=6vXTeSZ1=0d8~KuIu%B9v+YT zL(3GN4Gu7V%64U@E5=uG);DuoJY2Yetj=&inInGZok-PbeLE8K@Xm@+xls!lF9a9Q zMXD`)U-P4yfR?|X2GU24lad#%kpvLaq{JP<^;@r1rrmqs#S?Nk8C2oECfG#b23ZA8 z+Xtdr9*%j|jypR$Zhh(MZf*rIl4Bp~O`ct-3j8e?C3<wNEF#H&Vej2rd=sH#796k1 zIYf6HENX^YM=g?Ey_I0~fXq|<n_vr$G>(;~_|TDE!}-CPq3-0aUYpQZ#55lCHp(w0 z7_7ER;Q2Qlj&V3s8M+<kNOIz=UoRt~epEG%{0uDv>hNZr*kX>T6tB`KZYq=bMHODt zMQ8ZtPcU~G&T)Vr!W)K+mupTUj395^pA45qzP^vq+_CD6gdn5_H?n!F#bwc>`|{KJ zhSw*iBN9jGtND?+dj(qI7W44(ll(#k2ol&_|H|eWZ#bWm<(X?`bIp&NcQk5KFKdnr z2BX<+1yPz`HF7BtUjR(R?{KlVglhlWhO@+7FriLIU&~02Pn%+jP0Uy29{c89q~kD= z5ePaE7#76yZRh6Z7H~&{iwISsOp4XMoL7n{2K%HKVY%3qOp+I8(?xo_nivopF-e#R zuuu>4Nl*!Sh|~EK(Of*Lz0QuXC>Zl-IPcA;y?&4q7d0~)ZoeE=@jt^Dhrc0w35<%3 zWt*aiT7l})j=qvB`b$-Z+DF?RNXX)H{#vqDraEz_m-{6kJOI<G5!erkd-z#knsh+} zN?GINOXk32p0t^2^;L))XVph6-iKVC)W^9CM-1*b_oYcho$-gs4#HXb0o!;kNI&90 zDm|Bq6I%Qoj?7pD^<8k#*dRi*$^g({2#C@InJ^+X9$RUwgzyj`I{%i68r(I94n=76 zaHqRNqPBj}s^<MWsM#XU;+`<jT{A-NC#jL#xI-O?**ue9Z)YT_&Mgh+j&`sj)gmbM zuO848t30Mz?72)iJ!^PcDoYaN81y!hb6GRynE!=4N+(7w%{3M_HG)oz8E7wZnQeH@ zcMl82{i7VIPKE;q<x)iQ*Oxj`ac)xICVU1b2-n(t%G?$Ykf0gK`!Dce!WYrEAO-|k zdRsFKBr&rSA&Ue$v@jbMl$o(|oydPz*&E=ej-}0*)q_LTPx6IT5|~)#|6+=FS8slm zxX-=9c}qyb)UH&#UQ^d-M8M7d0=F(kC&cF{QhLHqw;4xom#ByGh9BWl&3H4&Zq?)Z z3mno8Z-~YgbdiGsOR^88Bqm1mx`BS9-<=a1BlI|DygIoECP@yF_dBD;T-;>Sygtc6 z_!qa2{kKlFc$IdRNQP&FbMWSu<uNkOFJvX^?MBMaIulWiK*r+YeSqY0oLx1sSFIQx zKy|RLmXB@(Z>s}@mCDD3YW%oafpJ)S92L(k2Q3B5v0skzr(;x}6q}{Q!EM$6g>TDn z2OF<4$9KV#lu9JUI4v@w1c%D-<^c>L`ydflOJ9{bV;THXnuDUR6dLj9n_19D#D3?= z2r`)b%9)u_dvX_LM#UU+#HA4%fbUzOA8WxmXz|Shy;v<f4URStQfleAq-A7ow?&BL zn{WX=BVq7&o+2v)4Q8JGo(?*^x=duV;W{+$lwsG}nSRjxKNz^PV&?wD9L=DH>o(pg z0Eg2jX2d`C^t?~NQ7=7e!cX~KD3hlNDQ7Jg)NCi#{6qc3dy^ekKN;l1x;C?LTM5cq z=X_H0Bp-Ijyy+2o?S4Cqh$N%gl;(QbrWKhRbruzTgKxfcu;SJlj_T!n^O6lvV(C2b zE!JNy5#Ea7qb-+oAV;}U48snsxh-fM`FH)W2_V2lWU}uh{S$uWqe%FKNf3lo+8Ww; z&^L?xx8D>U<j9MyF0*5<a(Q`rqmBMGkecS-=}w%b9lkj0pkv$IsU+~)8_jLw`&9c= zIIkF0vXoBodYBq|#p8Qq;HR;W_t(r^EACwSYGCf~x>tI~*q=90URpD?CEReHKsC1S zeEL%P#mpwWHfvcb)$v=QICEPUtCBok4Hg*@R^C{XhR*EWAoK9nyNj*F^ri{lx%E7? z1*O#lxnwX^VK&4Yqp+r1zNs|)eogsueC`J8<2`YE2bqr5&zTZPg~T?4Lag!dnWHj^ z4oc4|_?ka8QPLKfks63T56}3ej0}N5%4NF?vX$yQcTx9#GwSg^9XnZG56QpIRI>uz z0kXfwM9{B{Z{E*0@ZB<_zh&N+#{{ZRatiWZO7<{#V6qYHdF7q{3xYrE6n104Eb^>0 z@bY^Ls}!}b%}@px!XCr^=vk~;bCOK$d1uPzL-icjt?deCR3)4AOC!O<oySVTOEClH zM4#nVU4I`jj3%)V#W=kG%+n3A-|w5FJbw)z;2kbFK<PSJ`wvS_>fG&YQ{wf*n`${8 z+&L%;R(_XKa+kR2sU8?P)<vy+`0w!e!>jHiIkvmhjLf<n7N<bQ-Mmx`_qqz(GC~RK z3%}6a>v5!@2SrgX><Pp}IHGTU8~+8)x*r;%z13k@O(%DG^by*J0dY&1R=vWDDZVS* zN*Xp)-8m95`>@f`H+ep5%rKN7&A3z|2Ye2d)a7OYNuAUa;V2$nQE#}nvJFFT<umTk z<7p`^FxBvcAiuGA`eTo8BuB^&(!_cr!|>^G1s`fQM$qP%O52YQDi;Hol4xxTc+!|1 zGDu8=c`YB&WR`#^Rp53|NK@*uim}%X3a$9wk}`)E?bD!$%fJ0oMDWjUODu}VNSgpU zc;|kK+PAi!7Yo11PMjS=f}G)t=||NPhrVQv`!oBGgx)Fq7<Oo@_}ds{<)5snFd+ux z?5|Dv)8Fuwi!&rHaj~O0JVp-F&XpJ?TgHXOA3Bp-Ilek~qZ%d2ghA^(SIW%YV+S=- z1hQs`f-7Ig4Z|9r89##ozpM)NZ#Vm^Pjz@4^pZ=m%C-v#OH~n!dtZH4u+Qsmt?=(i z`~}1w9=oMMzVgiMFb7cyJqsR~iL_=)g@%jQn1ZA5rn&EJw74{9&bs|U-r%J3os>us zo_5;lSX5kd=FtqvKF!n5GB_8#M4u@BRz;sJy7OuLGMhZcAXv8bai7rvXziw<i?G}K z4`Bhh!Xt*`DkYBl-UhqU0*H-i+j-3!DY2|WD3>yKw53l%wh-pajRebGv6m^CLkUVU z!Sy==K5^vHlSU`t-`t8ZUwXqRqVxwxZ&I}rXfbotkb;8S7|mmx54-OTv1R8`F{(4l z4&HpgYOR^omie8Nw?4T>t{vqbOuua)@pQr^6r)g)NBEul=;%|*=`WH0206tj)1`9A zWxLN(JnYkgAW_jH0~KLALq+NdZ<@oZMdZ>MLO1;!^#cPrdqopY7w;_+le@2Ua(Dun zP;sw^)d6CU&d6;!osp=pXTtgg{J1hBRSel;Ea^}QFemJN;ldbqux5Ob7#_E<wD9k* z+w6-!DWy7+(sh-~AHkKFt>@k6VzhRD<O`tqXV>f|s~eS-AQk2H7qCAN-Bw&CuXQa` zV_2>z^~Cqil(g?mWM9LLe1>^l)TYN#wV<pNw?X)?uV#`Pp>Dmd4Tmu~8~DRgl~XDj zBM)761TyTJLdC6+amA-(f0I`yUt_Spl#A>B0&YiQzkNMru1|O6njkvpgrx=xPM)Is zciG12OV|Hw-WOtyEElU+vypal$ko$-&N3zL+U=PRuRec(^)7g@TRk!&l{$Cgz1K2k zv*r{DgeDZ93K#Z3gp)E1)~DgUmcr|s^GN{Zwv2NMic)i=WZ!4Uj)tr}7DlaeUhKeU z5E19$tkw|t?x`x*73<5|m<H_TAatcQcy8Bg()k(Lkn-?A!))gNeITPRu4loxy%-_- zVU2br!HBf3gF)oDaKnTcDO7a&AEzXS95c(zYM&<v*|hv&xKi8WY7cfqW*}5{%it26 z#90#V4x5y$djg5_>}s41`t?CNtcAaMS|H3zMO{*l(X|)tx|I^vdcjwDQ<|_YL%8wd z+M)dzcT0e1H1%vsW8Ng0wR-6{b$;i~g?qtw?zZCGgWuN?29{R-mw$26)eMqq(e0y} zJT8U^Mc929Y^(h*UbRf#)t2>@z_~QtP^Rz~Xst^!IbvceG&VxI{A$M?+eSIn&`gUt z+xoRR+Dx%iezaYN<W>&?u1+3R-%KcU@cA;rHmf9E%1R{#1YJuAT<qAZwSEX66Kj%A zfqIGm!3rskJY(hrQe8~(f$K7kU@wbwuo+iTcU4?-dz6XU355<+ibnI^z=;Z(DWo^* zeA{4V{VG3s?}53C=RKOqvKC=3^XHFa<g&+VAExjNknPJ{Hik@KuaQVCe|*CwKWL>a z(j5L(t%j-XEY_pEWh+^&A1|CB{*T@_=O;Sj(H;*Zf(J()Tqu7gdGj3yvGHj~D>KA{ z9Aj7zXKkZ(xk6oFkvfoxc~n_jOV<AP$=L}7XY_8i?~dJ}!?gVz?xc4%=7v2!<aF%h zj_t>tmtDp;oih*=6Aw0B>=TD@C_q(Foar%>?jlrcAkJjp2sAD`FP^eEd>GJ#4wB1B z@4n9Kw><4VqO<94m(3<_3@BDuH48!JG6!3)4fdsP3$fE+@wNV#gP5FW_^pIe7>EZ% zva;VT+MLTZO!W^LA!Hmh^u3u;`1T>xc6boAxYsbb;LtXGT(PtzIR<r~+gA*{+86eu z?pD$Bjb1*zH)u3>q8NjLvmHb>?@gU-I8^@Cb%7LSMenN&Mim)36MMgEKTFxpY}Gfo z^uyHFRwc##{_SCh2b(-UtR6{rmAULdwxAB{Y=U=$1fjWtuxa*HCw08tazQlDsnl9+ zeXcxcK;!-M`=6X+8a=yRGrR-9f>Zd0Kx1un?bo`b4ffEqpA5=3-f&XH_b_>o_3pjV zg{7%cvXQ}G!1=x`<=fBu(-tbt<7cx>@R;4uRF_Z6)p!u{tkc-b`=;sg5mLhR3dzNd z-uERp$;I%XC)83&xSB<0bMg(xYr2+;{Fwulzbel;ntcg~5PfNt^Z4+<wskwd-!X?9 zJe1hWl=Lv4LCUJaoA2|nvHZuwxss{*I#FvM4=2{wRmXJ4XI<ci^ypL-t?89Kxd;3+ z5k-d<Y`2;V&r&4nK38@>#kB<~Ls#FGE6%F8e$fhV{_Gsy5<zkQ-!$&Vmvgk_$EQc| zXK+e7>^)3Fd(r0de2JD{lFU5_$k3RZ$F}G4wx%-t4xyC!K!dn0dppQ>AhuZITK{n? zn=XS&X_t`2@`(SmZFk?qSb0ectc<L4J_d1H`1x>0=tU+uvQSa<IX&BB2Dg}pt6ue; zvsN?DlEq7k*1+?eN3V-l#Ms*hcn9Zh&ce3$6dK~f2-(zvs8m1he=wSae{bmgN{G?G zMbxbHgD&?3_YO~@2lpAAB}fPRbk(Q!ijPWW^@Q&P;g%J8*Wh&UXI`Ih0Gdc%zs`Bu zzuj?0LIxyfZy=+AyE1a0fgG={2y$k10k@#oXaw!@A1zzfV0JRWw$Ww+epT{4LOCUP z)C^XFUIO#Qf4Pnse)FiXKX@z~kvP6uxc)kxz5tM+lQD--k($1X3XPHy07!y!w2~3J z8KB`z)uue`?WUFgDqgrabQX2be)@HoNfIAx7BW@D{^jAFtTwNpe+|lr%8acPEe#-e zAuL8bhSJyQ(^i?Wd+UW4y&JsZ#Q{ri-4+3<9FRqI*xhnNAO@*G)DD^mw6)ecBH}vN zCZt-)Ua))d^X%d`wWZyB@#pw9Ys&2mzwf%zj^pQP>A|&jXwwYvR|W1aAkX&^&tsl) z{dYa-pZJ~@lG|?C9y6eE+g~QkI1$E=a8zpFgWUkgBO!I)>7IttJ`~+8n|E%(JXWiv z!|>1$ts^0DQSKk9FKbm5_Q#$?P-ufT$ny7zh}<-H(L0k)8N!)SV*fSX!Zp=>AIoKF zU~kv|=~+TgJ1Z_FVKt4IhCLH1FI(ggS$c#4sZ>O4d#3dFT6s3fV_*4za5dbBAT`#Y ze7d^Jt#pIQDKecm&R342KCJ59CKtDLt0@Kj1>$vQTDeOvzT`eKavZA!Cf!3ms2Ln; z+D-w(;$|D@qLx8<mE`*x$^JI(!F7prr18zx7ZSx^^z!fe&`b#1VG7@qkTPmF6)E)` zse`QO`_Kiq)5jfGXLNgnR4}D+LuFO||Jggwc6Mq~>KVv~znLM?m_yodugf>^Dj{!f z;?L)@9?)R<A+6kHk3PJvPz+hRLztWU*W1+d2D<4AQt7BOD$BEF9GNFq^8($jycqmK zuyJS|1BhmM1kH4aC*)eZ1+(5`v)Q_5-j!vJjjlfVtn#)qK_@hQhrh@vF){D(n+DmL z0ny42w?}S$*8lh>-P086B1C9fx+x`DQTgc6%RHM0B9zxlQdkq>o*Y!Cx$RGo)47K3 zys+3At*;qJ)m9Y~>mye?S8pm-I>&#E`QrxyFD1drQs7?V=N3r@_M&@tER;u$)4r#9 zx9TtO&rqume51Z{FIczS&6asGbP@(KO;^}fj_B5!M*-U9FodiBWLhP{_hWQ5FHcp) zHUc36#iN(zm4{29=NsdA>AhqaIKqe4KO7A1jhPJ);F|;IS84J_Z*I(~Yy-^+DXuM< zuZ=z&e*OHxa%ZUf9`*A|qts6+y2Qn(w{sL$Utvfr%`FN3vRcNOo&#?wKlR)V@Lgz< zR0ab|{%f-n?;%jl*5W=MNeGUu6azDi<!PENr;=3rk;~bFx75teEE@in`1XwQc7a;3 zy>nf`K-=f$)%lU9iy>G@>t*NZk5k$`rPMa>5#^;GSaDx@*0s!4R!D?CdYhQx66jX2 zI+gI_?~gTJ+~<WxZI<{SxUSu~-sGkZ#6HF}XzD-4DL<o7JlgK64RfE78Ixaj_B2^< zJm_SJt{4g-G}Iato9V7l6rR1bP44ptGtD0)zuDyqrj}BJ_c8J(9Ys%BwD`Q3P9%rK z8rvT@EYOevgbt~6WapQQmp(H7<6HYGa&9RJPuN1(>F2}ME;$N>o!O^GwLz%vzM`Fj z$b>eLLpGI!aWF9GhyIvrQQ3oJe%EKH3@I~H>gop<-dvRzr+lK0P7s<#_aWLYk3~7L zE!%hIi9ZquJ!)hP1pMK41z)bjjRByeL&k$aosp#jtJvoH@h0KX(l18mp_7F183ma1 z8pUbLRy6dOe`h;q)WVRTY-l~rddn1R<a~M{(IxZ#u{Z;tEyeKJYkhnoW<PGO%oAd+ z&Rw$0U~*NvK6epVL!OHY>4_y*ai*$ym9$jfN4*F|lJWX#fjpdd(yJSv<+W5GOU)b9 zf=ke2a;NPJrFj@iW(WZRBHLD7=0g2tCv%|y7(f`8)G~*jPMki>QgZo|yI0f{yC$lT zL`&{iqIQjt`r4nqBu$d1CWNWC!>xFE0U(Qo6F(8LKOA4}NIhH&fSZN&foT8N^Rt)F zx*{5SI(Jt^@mLj*A=Fk+v+jtwoVX?=r0KXuVYm8Io*nN@eG=YA8q%`6tMd3xN?=&D z*JW?l(&@lgd>e1=Zh!J=@A73;PFjEH3Rn!^8-ij!k7sk0UGl}T`4o^^DG9Cr)}~q{ zfO#G_XkX$dT%VAtuubEA^>;o8)SJHA?EL4CGr}9K?Gomvz2?B(r=QmSo!S*?uzS0{ zzUtFK*o%`06rr)Rpk0^4+OdNYPpO;6&ai7KulLY}PmeF;u8w<W$U%~!_#L~?dzWhe z89Pf)`z@$ST_y9XsE4L9l|IYlu4D*+(Zz%0pMQ|>*HWkG_e|}LRyUe}gY*UayK0&x zta(_p*NwUB{NGatzk}ictGF@lfGF?e%yQOWK*%$?E&2GZW=7cfzb$qFXSkmT4YvAM zXvGxGgyoq4vY?QKZN8RFawh*&NtIIul_k;l?w#E4cOjRvZlC)(*3+q*Bm~fY)xKtZ zbFZHGr0Gi=h}#aEqC7o)#Nn{F{nh=k48l!4^)sf_uD^h&w(hys(bg1$X<zF1!6@pD z<>v$`n}~%URoHmnQ2DRw1D2AL$;9R=c3k6AvE{|w3L)m64#O^w&pSO$@GCFwGyo>| zM$C<@eh9g-;8-c6HVqYQgMWp2Dtfu!{2F{P$MciYX*7%e^XPl<qxVJBiZd-&QC<i~ z&{Y%Y!?;^^GuI@~xuZPb{NfoM(_dt;PM?s9>U(#yc^-$~1D6R(@+1?or`WWVQuQ#l zxs3DN=MuF&cE<H84Xf&mypZP?EH{I>&~hUzB|gMw4Q3&5zh19U9KAl8)wQ~GHs^ku zsWOSfl3q4zxb(6>kK541Md6)!-Fd9EG6%4o*Kw$3pU{IQSDt*vOwzRDF(5v^`tLs} z`Z%KHkhV|U_krKS_S?j!Od}yBA!eDM&S?GD)b~g3#pfM<`WKjaxf2v<_j)Um+4I%E zPk-phq18&5pSk~r6vN`WgUr0QAE8TZO`I%)^!r5I*|iy!i(gGaaf8|42cn`aTBihC zrYD?m+o5k_^Ney3qurVRj(!P~jQ34{UGYSsP-vpcvml#_-m9^*`G8;_y)L`cI{eKS z1lSgAvmH`SUj6pq6d)d1qK)+WRrAq8?Sa)5(;JV6R!Is7!V-J<OQMA~-4y=Yl&rgk zBuG2DJZ>z$TIT&D{4XFcd5DD)yTr1kdN8A!K%t=<Fp$k|+%_IWp&5ouOq;y5+)R0b zvcmcC(W029iLmv#pL>V3u1?NCDt=FA2q%DhIk1I$F(+puUXylGBqAbuee)7q3UV*` zsw2eJsAYks-vzEL$PxB;b+|nY7dh`_ULDA*oCa$3U)rD-13ooR%%CLn1NNw%=uf;| z-4v^c-^_afVw|a3kCBPz(-*)Zf!i^-A&>AHzWZachf&fvU%jvCTlg{;>p!u|q|cxz z1$l-Y2PK8z&=qx<`ble-pX@A_bXB6qAp?@w>%yA50Xg1HCPp@^jU)xGw1r?46IR?E zaVYzte$Nhs0AYOY){P`Sr-;?W0Sz(smhY#Vt#7}7)`R1|KVc`51Z*z*UfIz8(&8d` ztJCcv*aMd-XXV`+1uiw)812u8nZ*70aZS($>HFxn8h>$qpv|>J@Kr)2IR2JD7D1O( zy=8XK^%#dWk$k8Q@(*+M<61GSNYo_sT5B+L<+t$h)&)CaFHPsp{)YIzo#<xRJZtwa z5W@;vez>W;8v5tIHlASY?&U=aQ@>Codd);7g!g+xA&m3s^xGosRgco<&pg|=Vhkz* zHm1J5S-ui^2Tna9>P7-~?bX0tL_|+OaeA_I)M`|zITxW(2C?H3x4smkE_^=6C%?M! z$Ui(ZTiDFpSdFv>YFL_lX_c7YcGT&!MvrPD71*)+iR869IQt^|*nf{I<F`LodVLK3 z_WBi{`kU-y1MjGvVYgM6IK>5_5GCv(?dx9Zd$o`J{H1yl8V-64ChZ4?r>}ew<`brj zkJJVF7(bJM_N((NgWc29r|4nBLtA$<a_;FOm00AKa+inrhGQ3h)-LC6TAgQAq@I2v zH?2u%U*zjC==&<aH8pnczlr#2vNpMERS2uO%WUmDy}aN3;LS{gxyD%|NnR{Jcsgvg z3!j^*3eG8S4F9CF2ss-jSoKl9A>hc5?^|lu4+MVY;M6|-@>$Fw1s%B_WH8^pB)J~x zJX2kf*+20Yz`w-aidri^0_G4MTM-COOHf4o1s-ee1P)Y&c7KZhXfMA_r1^G!O^+Vf z>HD_${Q>g9DB@b?5O+U%7_^V?@V^S%+H!UGkX?n+$KGlP=>s&~h1*X3ay?)~i;1Pc z1+zPOa?H1&JbBJsXc4x>9F9`aPy^#+x8jQSGI5974o!VbFwo6Zj{AU{5wgzM5ZiGs zn9+5019e|Eucr|L%x#+jF>bfSf7b{D4I;;!cGH|ape(T>=HYN9c%EF3GQAv&J+Czt zUed!_7v&D;cz*qf-buhsWfRC%s1nR0U17Jlh>X$&(%n2KdRFKAc~l0uDjWJ$UJP+J zqftPpEjz46--s##IWDdM2Pt|MjnMLwC?b!Bss4CdxKP&Q^@6YrD-eba44c=}#yA|2 zlu&dwHw~jq#`1d}XK&HL>Plx+bLutOtRA>X5_;KsF|o2Q^)rv2Sy$Ac%^7a*)dJZF z>f1e7-&?WEW%1dRl)#`M>p|N#oJ^?b(Y@C`S+BFf0Ut&oT;C(xG2xmAvu5gj=}9uP zip4e*|BUkV#xW}}3Pz~mZa#)YA`Mi1ZkcmC6aJ|76F8h5s~dXi^Q@U6Dz}tokVT|T zQ`?=yKk$MH<?Gx63M_7Ca+FS1JOG<%q>6#eWtoMgszh2}M9Yz(Nduix_Ragv_^jJ6 zIo|<;lbuOA4w8c#$j+kb?rfFE6OjHOB-_?u5l}irzduLMH0b+JR<PPW%Tm(^C#b+T zXecfn0v6csv;Wf{Rc5zK+)Of%<YTufsF3X*1=BJvpcNS*VR=H|RNvIEMB>3f4CmG3 zGQaiE2uGo@tQYcx${EEs>0+>Q{c(A(MxS<2@jB}2F|<M52504ZW<+;ztTOEkZvS3r zOEDlLNE6>2ZiEK{ujD_K<C%`rUB4Zsj1#T|=9{K@Z(|{B!*56IClbPhL5D%10P=kl zm@DaM^{;Wsd;s>&98S2jDR=@5oH5Bv=M;7&u999b$$R^n*3|p9qqU2Ko+T&h!zg46 zSs#>D+*xDe4##+hdK&U;dK-jgiyrCNjg|eRCDoSKTs3F})0Wa&#{4-xI4BV_Nk{q} z?p>iy;tsDy)(L<(c`(Jp`&!wgDI=<##T}NJdLq8o93SXhLJfqYJjZLmZTYg!twJRn zRK|C`NB+q1+k>81<jimmK7cR_6Q_EamW6KmgY#bH#mjD>%L!Wf!eM<+bA?3UwCb@X z&WkOpQcN}J2f>k{Zn99FtQa0ufv%+N3n&cmKOy~}?(s4AEYJRksG}Xpl@j*Ln61s+ zd)t1W&*Qb$FNrIdN@S?Z?vLO3cn|t)+XlXZ2$ISOvO2_*p4iwE`n)fpgcZ|+R?uXM z<u3_J;kNybVC=yN0l=ubBF#J0x?S2iqD^(ZaPQZ7j0SprDs4$;u_%x*{OT6vYd4eR zi~=Qq@=jF(j(D@GR;9DgQ)le*7x#Qw<+3F--SIq)1N)YLmZBJ;*1$pdKH>YBDIzKH zphuI^{JL{*h#LCFkhywE{A^JOp<gKL@~qssdF=#ew1a4q*z{T}x<=Y_f&7vk7j6H+ zxnHp0YZ(81Mz$<^E`q&fu3~cD3@B+jT{Xfs1+jLkftll}S8l!0tN0$@1FNhzsybql zPIF!SN~I5nOKEhT2mZui41#y#l9gj-uDK;w7J!ej<e$?Dyds|Np;`u3Y}2v1>KHrZ zg?u~uo-$6zid?Vmq{{>dz1Dw>mF+yTS6i!PCBJYAQ8bB?BdhA(K6I#LA>$j51?6@5 zJ)UekiMv$H0BNPya@xygIMk6>)7o%oyHT=Da|NVNDsq!lk|UKcWKDj-!_fO}J$N-% z1-!T(n`AxVe1EtRl>fD5m<o;Kv>bgvhUTn%)pp&NvLom_UUxuf;T2>6ua0OHb2q1i zLz`^XgS}`xgE}2+Max&)2{Q{U>1;LnV<tg?W%Z@6ibAZN{B8F%eRo173%Ncqj)Z%) zC{a=4lChpKFJnE`igqs`0wD|Z<##78Sv(7SF3XR;W7e`<IDD?ac~T#bn>5JB@&l)2 zPQ{ox4k2&9DRgklw%GI@8)UQh3a{EUB9#{gxP`!Iy1opX@EJ2$RU@@@9#aUZS8gLv zwI8$Nlnk5)qBsQ}j=9bfwPamnXU;IxNwo}F+Ybu%7o=JEc6K5y4Aj`eGmoFk<i(np z>!Xpr;NQ~4+nBYLBEZUOa+<5f+(Do@M7(L+n3XuNCtq|EDhAP&2s{Wg*0az(YyaN) z5c!}kH1Z3?91pq)A&Z(;erJ>}UnmBg<F4YVcc%r28}kpm?S6w(ckqp>W<eK2Q=$L? zAyZXdfod=~MjL-sY;43Q`Y?MqTvGb#u=VO+Ku(Oa{&uYm<Zy)5$w$?tcO2*?Qaa&l zOKcomE5Kasos6evRziOA-j(T0W>n)`oNlzXV9ReN2OF*a0Ptv=QZiy8Cl_?Hr*IBx z&NQjo2zFlrb1P7(6^%@vUf*kI&lfma*l>O^U>5ws47!bM8bPR0iM)CtD}N;%d%5)_ zFoB3}@6ZO64@3kz37Y}ZQ48ZM;HS&@R7K5E3-T_`T$6oSZ4X|8;Psl@CEYZ#<_reG z?_0ZuGqOFQP|AQ#KkzXID?bztX0ZCu*(P282=N+7*nukY&Bi<$|GR`Id;6VHy$2$b zF(>H~x?0<kwYyLptUFt9R4b7_B2sI&<jaJzjb=XoKBWY=G^DY&!LuTEd961iap6F! zA8?ySHXCT^2OwGX=V!RNsDjNTmt@dYZ|KxGZwPiSgL&Ic5~TwuNuR<0{pUbbl7{3C zUd!4E-MCAgLA~{IKF~Hlp<>v9W@WP2BNu;5)a!c9fSh!RLucQJdlyvvXmSW7S*7pQ z`cTD0{t>vvzc`)P*qGZT+73kz{cl&w58z<v9{Sw)o;)AoD6bkb6TP0-1~j=(9Muwd zti6$qZVSCNy)sT_5J87pwT@ox0uJ;ae<d_E7VPyfoh%KT7tk^x3Mk42l=$sN=VA+E zbCMq8TYy%msTSlFfZ%aZR*XcWJvA+B-%69X#hV0amE1!A<(MDZA4ExqXA>$bROuq~ zN!GqhFH>C*xt$x1t&QYEarU(=-;7kQl)Y)BG(@ovL|$iQD9W$T6R!Wc>33U$gZ|Jc znj<Fhld_9x=#kIP^n=uDpI16G3!AirZHI%Dq>*F}r?B19teek0vz}^NF9+E=fN$!; zGP4E{R)K#3UdHqqbrK}+-Q21nM2t{8nIaj*GSfm3NxscJIpFSbZjvK;5UXoygC44n z0T3LiapU{4A40y+96~VY0-?9DUF0`w>)E`XJeMno$t2&lz`L>B?`++fGfkZJ{Iszg zkWbafqUf46$LKiC^D47J;}S6{dGqyKkOa&r0GQGfN{C}%%KB=y+Aq(^Gy%;JIdOAd zB?DPH6nxD9BJfEq!<Wew10`50!BD&7u@A2o=4SFvMlkxqMX9cfJOIqox^TPZ4fW#m z>3?4yJ6(ll#_11jhU~7hcKCIxT$5)2K$VRXVx2B&kreXh<U&a#=J?Wq2m=A|M=Iep zerMRTG;BE|a|;VN!3jqXOSm`Tz{hNmIFCFNDBMm3VRnh|?_w+ke|9g0ZDLU~e%GZY zApk7~yLbY=`wb+F9_|f_b6Y;D!bj^a;J)DXQJd-HvOoeg?re2lL2ABo6KyrSn+t?k z4T}(w@n;iBF&eU5>7B+>EJRXJP{h96<<*0^8At;bjA!B5UW=Th-mMpLek-YL6j2%c zD1`yOOe`d;Trfr;sCX50LHx=WjybOxy)=NHhZzI@ysD%Lp*n#B=-4YXskC`xyN0=( zEpII=NGa9^{eXJkla5S>3o%?0L7^Fr%fqSK^q|E}5(Z3%p!1l}t-w&ES#WRE%r;ps zv448Pw__vcr0!X`tfaq#ZxgDx9ykw0!&6AYnN-ifpg0}fvTvdQPkV=Sfr%STdm}$0 zN$GNyXJD8@;%eeEU^{R|Upb<mxov)5VkHt>Fg7+JM=_-fCd2x=J=a_y2mU)&%l?hG zz6Cc`ON8Y=)RyaLA3iP%d%F||SXBwxBbN2Yl(gbZ7Az`3MQrhmJ|1wU{vydeohCs+ z6_z<PDw0o(>b2Rxuda}R_Xbm&H;FhE&9Jll<_Jieayx6J98ezgp_-Znhpm52`DFK? z$-RS)fzx{}1r*QRY>*3i_e0sz6oMI$gq1AdU_B7Uh_X<$RA#@br$lp7SiXEM7v*fl zyx>7}*6!EzY*9>1Sap_X6zC-At|cz;c=O#RiDiNCb#t8`3B2~lc3do?g_X{g@DA5K zrhd{q5cz#?Rw+x4`2}=Wxe!ie5}L5>eWDUL0Gja$Jsq@b)sA{FY&Z*HE>Gn&qJT(4 zF)^A{3Lu&N;<jeu){3ca$51#ia!`z)(3{zxr340z$|SS(4Nr=!BxVuT!QxEJoa?;$ zh3>}HK`?mB#448C^G|)45SEsA>8t&qqv*NRrZ(O%v*rx%Q+L%!0u%?39S!_MBtfW7 zSuG+HhKFX4fI#bO%^9l(V=a!zmbF4^w-AI6XVtqPHWe;PVTkYM%1h;d*?%~^#KUm) z;Ff*}eO6vI0@T|1w5c9&rD?&_$4xahz_OAnJm(=<E!<ctYoB20D(s!*PecJwHeK4< zap8{qf$xOlW7_t@mId9*98^n^1NI6b|5^*#bJfF_*Jd#f_@lLIC%D3f^B}38mADWt zK@{Wbg@<5O69R4wiZMX&1l>Pk+?*Xt0g{xC6FKaoJj2S9mQ2YAnJ_S+<RM)Ck(M%p zf-M0*yj{ng`5WOjmNKI!NYY^7rk!`J)ZPK%%8X(J`Q^fv6&WJe0>lr(ws+0BQhOvk z!K`V?*uFPi-m&3YQVlnB;~U9!$hAzlMu$iP*fMJms{mMrniZH37U+Fx_d7U%uTFg- zG*x_Fm+EBZ(B64i0KC#>K{Wl28g5=mMU%ChjZB+C!?OR3G0eX@0}>Bh+V5PT6y{k= z#b(v^Xc58RxM2VG_@p$ir3QBpe@4N}_*x@Z4O%CrhHf<@>nXyF|2p~yU;Ft;Dsx80 z4;r!b3V86uUGd~}f@w=8Or*6P9}fBQaB)%fK<s_)aV_Fr6=FBD3Y3ewLz4_;ffxj{ z{IZaDdb}Ok)D%;XJ4jVd#CMw-f6^6WR)D^nd1sJ@;*92OZ0svA@B$*YRU>iWt9koi zw8)d&2)QICppYtn9Rg1o!+*{ey0-1NfLTOY4}Zi-KQ9UHF1ndnPE>TH&8;d5fRa%9 zSV1~Hq3xUJlS&vwKZyBOhZFL$v<jK>7<2IaM(7oZ(y~D4A6P-XgT43RiOfcFxaDu5 z%dcPj6Q1#DGJ~wIQ|6(4g^zm&Zu<3SZ^+9VChE>jjqQ@93l<%BGmf<4U;Bh>hTZTx zE>A%SZGmzy_LB9m5;`nPFe0jht71y-_`^vv9OjS4!jyu`C<!dGE*^6hyzD6>T(!RL zm8Wm<Ez;1m7r+JCK1qPI6RPld1JhLdNc@wXAgQbtJIO<?<|863ScU3l1bF%PTLMEJ z01I%&nm!C0b1KOk(sm4-O2;+I_{`BG#zk-OsuE--SSZA1;b8^l{ib$FO*i_usB>hf z#cCooKO}rz)U2yRqOB1=wzL&!^@sb<2p%6?LP!ckgq92Atzppq4V^(uk=}%wuK2`x z7%uQ`T2eq8j@4jh?1*E`;7pKSrf=jYUMS>J(jva}5;?8PuYU)B>IHPNI>{yvjSeN? z;U<59ox(Gh!=8x1!UTi}J%K^|{IcyG88Xqth&6%7unhR}{_!0`B0bK*(J3&wpTmNV zlyk>#n=u@9r(Fo-=2sziGDEZEH>sY@nctjYSoMw`RhpNvmjV&+7CC=twxt|Ez3n=g z@&)Pc9TLy|L{@kS<q1b42$_MFM|G|u6?t?R7bbtD9L*7cgGH|ybBmbG8y;#iQQ!o^ zFAFU}3TG&6o7$JMu=}lYLL-;Cl)<DggHw2rlmJyiq1))q5n0Wzpzg@?g!r6K2EFF( z4S3?*9PJ^YZNhprDq=h_4$yII@^>>gvY<^aaq?5Q(|&V9quRzWa^emZ45?W1zKTH} zbY>zWu|0V5I9Oy$5#n<R&FhMDugr}lTO<rhdX8648mfGNN*&h*{TS#1fiPY%2<0ss zC(JxoD-omb(?MN*r>@BI^au0f@|Ob>+X9KL+F1#TD;d*K9n3gDw?f-3Im@(QKq^HD z<%l<gd3_Dc#HOMVcopSHgSQ}$^5kLqK%qq+NHZ5<WdqE0os@~Ul_D@ox?|XJa1EW{ z=oo2ZAPyZE>B~wvDh*5;I<sl(-+@zAr}6rPru7Y}ls!JiqJ$w-ToU8InV&5yy}&J; z0p<p*gTBoKHA8XQsqhnTpP9$LYr?2*Sw|>S(N;0@3Wn``hwh|FVp=sc`JDfE<b#+D zz_LLHhB>&c3>v`mEIM0jHU6mWfJo{4@-pP^g+?epuM(Jl`sW)^&|TfZlm%suR~odq z5g|XQfk~<jP|0cqJPtc)lS~A9AWXmF$>HK{Jz4X?)sE&wn&g~Hk_;s6cN3P$2;sqa zhu)((Obd;rP#GD3PloRVzpjGf$&jIgBNz-pH^(KHH53$dqCnxzWYr%{0pE8fMaN}N zm-YtrTSk?ENj?dx^ySU$B;;$*0*nI=Kmqw`ewvBkh#fgMxC-R0VB{krwk2ZNRI^nD z4L<v!z|^K;*qw*mKW-cTL_?wCb978mt(q{QQL^TDZk2@nq(7X*g60!!s(L1XivoI~ z-lHlS(;y*OzG~Vas(D>1D^@H&f)v)J_ZRT>MGy;I&bm0lmz*ixnc;!9;ri3kW7Mti zS$~i%0UItYOS*vcFPat{Z`om9Qq)TA3fDc@)TKOp7A`?54#%;0Qi!zm?Cz^a1@lc@ z5X(Nau;qLYLe=@>IU(a|Ak7w@FYnSuQ|8rZ>@iwx>IwA<O)1d1Y5eVr5OIgIBLMFS zKf#Oty4?uAOh$tosc(2JJnxKXrH7>w1Xa|lTp5u_ng*5rt_@&54!vZd_2h8qokk*z zWDb`ov3DZ}f<zadQj+kj#xy@*&JZAH1g)_buJ>rj=4%E8^7E>}O{wDSk;;b_FS<0D z<S5erx^(yVE=TKOU`~waF%MIgAFNoU?NHlsu{IwXsEbc1v506~7zE@Xd`3EKF<9lP zJO@{6scJU$A;q)LPQqtkkRG>qE2rV|AQ**Birxmr)Qj>t|D9Lr$}})Jq35SI4~@vI zueq0~Nz~Z~c*8|w+x5IPUBKu6*}?W>)Zy@<r4dTr_1c-{632qmcB^ydl_yJSI91%C zE`v4a``h*4U^muSUn0~a7Co<g?fgBVxH=JNaRFLn$o?OOQFCVa4nOcf#u*Cufq7zF zYDt93stGAg0n19kwZ~%EEMwyD&a_!94J^v4n^-fn0oab^gj|awFB+B)ccxBWA2!7+ z*-2d0I=tzVOgae7iUxSn1?T!%(rcN`q(V~41PI0iIXSX^l9<}N38$EnfY@9dKvZ6J zq<9tPdY#+qflCWhQ7~-mLno~iaBrL0aK}>~(sqF3cJxD4PQC)nFFU1As~00eCGVT1 zAE{b2oX7A!$P1L_hz&o~hsh}0$|m62?n6}D2<=D~+X{8kg5;ddBr8a%b}*$0Z1%N` z;tOR!=%0;j7^TL#vJfq@t|1kzyxs4pHid3?m=*{PiAEnw;1lO8;Diuw{un^dwO(*o z7oRh#(cT+8SPWf4ni*fwR^wxb8-N;n@0YW>3j<)Ng-Bv52BRDf%g(=GYY`69Cg#b= zQ)M&J;Ou$A1{C})t{SZF71?a3%Z@tJf)lVG^~vpj>>fDsX(N30qWQQ=gGGAa4y3Rf zfS-(`%d);1h-1{YbW#1xToM2pOjE{`6O=);E2TM=(ovQGuoz%)*dcH6W=JK;hc+GZ zZUkbg!SI8OU|D%rY2C-ArK(uqVCPLQP=}lW!33@$yx?3C8!gX7ZxiU08Fu1epPzt^ zLs$lpJ)H379SCxL%t4p~rW&p&KizpbbG+*8p``;KLx0Ah#_7Pml?*k|pg$OB&Xx5- zmBiHm<{gVn8FcgF>)d+j7N1qBI#|fjJ#6YF{UI0I8HYeW@O0q^2yIIGrXgrCuz_ZV zkA^K}@}Vcfj2*e7+w?%N#@;Jaed;jpQtD@A`dGM>kdkV@z^gkoZy+aeb8Yf(fWwR< z07ejHbmS_Zw?EPtNN`->_xbg5Pg`A^i4uAJh3cqeD7GgL@-WF7R20daYZB7Tk%XCq z$Zbct>I<QznqMXX;=2vMQsl<x+H^8{p@*?r`etFKAsBfo#0UyS`W17Ll8mWc%Aoo2 zZB_L({H-m}tTHA`2V;g)_^XlrA#}0^NNF$>(s<mCh(!qToI2v{kPqRWILI=-r#C^o z9Znp@9b4o-j7Z=O-9TSD7Q;W(2F&ZYzw$Rr%fI}XLj^UyHnO~!*Pq2Qb5@zd$vDjc zC$HBU05kLDB1X_&h^*u<oq&d}ZWdbIm$1vGmastADvvdCvIo6h$kk>ili*E==qFPn zMoQk=JxNH_b~zIiM>*TF>E=cM6iCUFvmwg32(ZXQEO2~l`a0$5lpN6124Y%i#d#PZ zu$J_V1Q3Coc1~e<lV#W3ns2K%k9IgQ<1sP_{7PR2Kr|FWP3v|-Qw(iYrJo#4M_$Mg zf{DUA$K@xEYRrMwvY@PsO1JSkn*eki#90UmOZjC8y%}J0S|9qm&-cHcH7KQ79Ehf; ztDs0pW?{*z8}DyuA<Jo%FX9{dGX4S?exe=bvj&H!yvLVQPFJWS60kz4WByLe=XTGK z5VHAu-x2cQCu}P(y3PsOAg<^C2d`*`tGh`#Hq7l+H>jY&Of;0Dz6_-+*9AuDD7|+t zVh|O<(2`>6y^w*lYxR|9dx((%XQ^@f8T)xB;X2H4o%YwUUTHJ?iYr84mtPlp-KJ|? znGvfmzK56^^e?O4i9VtC{mE^&bTL`zOwXU9)ocIky6{`@xv%mv2iH3Ga2xM84{Zcp zi9ZfW1^`^g=Ayym`iE`6E=g}Ly;qVNt@E91gn7@l(&mlZ_2ZqMpD792m}6LHXDQ=H zyonWodv$AbhEnq8+wSO2k^nEWGSB|`X8c#}fRB6V#T+r#@<x%0dk{t8mj@&5v3XF$ zf!GIc)OhM#PoMwDeqRv(KthyG$LA3t6@PK6#h~rYEM^T$dNKrieqZr%>1z=^h^~0& zlUa15)A-zu^++7<nY-TNRYjy%Xt^|Qvg?bt$Px6m8JbzO`ChIhFY{l`_#APjr&{v< zc%HJ@cTCe`^Y1fUgFSp6R49s0Kb3#IPswkBXIg3&J;C8dvMjih)TF_joF~ClshmpB z$P{osX(bGuIS@|L4}|Akyr(j6IG=eVzY*STaK~pp=%+aGDNTzwkG(M3#GyJ3mu>or zZ<{e08*ON9TYunG@o607OJlnRl?9GZ-b4Q5n@W(sJ5S3x>%2$WA=pL8*;GPKdcE#N z;Nf&~Duh&)X))}RFru&HM7z_LrTX+`#eeOI+_E6@7qn5!-DL(0k2%TA1i3Y^2Cd#c zyOV!Ix7}d@V^Dl~Umk+m{Q4KT;D}qghDeq_+N?Chb5oj!1}iRp2xQLOBkNyv1vdtS z{(YFmY|zhE<?FG|gS>aMk5L?KZi*fJz*o!@N=>JfxX3Nz?7m8u=df<!XU9?Eo8VOP zchu#q{*M(k+B~=X1hb{oC>Hcn1r;R;-IA4JXU0>hn_;?{srRO2BW+?8YqXWnf8g8m z@?H4P45c37l#{gEL4anU?>qPI{+o}4k9wMX@u~G3GjJMNFMOqV$@i$f=x1+<C8a%H z<^6~M-8#N4G?~1{<+DnLzzUc)pJa5LRV5j6v<mdTvgLh;<c=rX=AZC>7bNVD4XXG0 zm{ZT?@NN^I9f!p5uOBR8LLOa`Y+PHte6*;l4I)Vny8Gc~>xCCi4pp-sa%LpVFd!1; zOPMJiun_Ap?3`XlBSEUcMMA2lSfqNGZ}IxHWs~xnc0PkqAp}E%IYHF&8%D-u#_0@F zi!8cjRSC424VB9!-W<GEe=A4{c~YoxH<?~Q|5es)Rr9Tg)F?<ry=_D#le0crl%JF0 z?b8irWxKMo+R``u<X^5OcQk7IjO^`%C|o<wV5hC#j1He4uMJcD5d$*521vf|e7~O{ zemSmO_NXjNHIhJCoXCWk&DgrHpSkD1gfk=pwD>C2ulKDXa%&TC8KnwwI)YUVMJi<Y zwDM%EcyVIwkTU)qw>#^@buveFQtz%#(6}aq$xY$1`9kxLb;5)A%Ozun@7*;z_cMV6 z%`(%aQy#uQUG)tAa=5AuqnbIoRrKujv&-FvJ-=kdK;~~9uM*remACwODp%3;ml-P* zACjCkN}aPClN-IIcK4FZ8Wps1qYC=ItbdM20K(N0-HHuMgtj0&k7kV9Pb~km;G`rZ zEKV!kkZLyi6`L1YSF`=<>ic!qO56lzw_0?IzWj-(iHvo&-PY-^h8B!}5ACUOGkK2E zav}+HY(!VZ7HC1|hcX*>FTVW?JSn&tzMj+pY?#yT09!^Tp%-i1r;S1`=oAD$-<kS) zu>aa7Z1ViCTy5b368ydJjvZ?$`iJw%o8hQL$(gnv2XkuJ%tzg~%#2|JCkpnSzDkE} z*-@_N+9kG8J4iz5Fv$|df#P<r*v*``kHSp-Pu0c2&ip!ya1olgo97N2xKp~Ku|hN( zf5nKP^JzEThU^lq+%$O-QT=MI%VK|8T6ypNc$ka6SJ~DxGor(RK$!6|cI2t*{a>9~ ziXZ#XUaj8PrC0ca3k(}f-fU>#h|Zwex{cr(WC=VPF3pX@Xp8H%GW*|9l{{eA{ge5k zp{~@j2q!BUVhV0lf?&-mZGs+lg@-#PAQ{Mma=*J@q5Md3_E$O3$7EnN)U=Dr`X==A z$DnJ2<EZIr8TE~_Rx_^`3wj41t~)(?U)!`<n;!pbK6CJK+oS9sHy4m4QR$sU9mNi9 zBQ;r^NJgmii8bfC5R0D}3hAu!xw;FHhR-{j+Cs29Kc~aWPJrf)>i!JG#FZ$zxL#O7 zu^k;zpK;W^1(Jk4w*RQJ;r?l><<&hdVr}-$QFA78`NYmctnjq$*1ya3bwBdnk*}UI z0MBIyWie?EAoL*VtcH}8x4jZf!eAGhY5+NDJl}5TVzrf(wpvj8*`V&c(e~3nYGhuW z)Ws_+FIsE8%}e?7D#D>I`~K`3#6C@<<m$w@Cj$EV*cSmG;;UR;dki`O?ATNVN;g8D zar8o}omh{*Bzod^<+Jbhe-^Z>nE_0mof;AzZW={TjG~JExL+MNt6e&IOGq_>(iCW? zT%f^lZoenkp)ChEGC3c2@7d>Gb#z(XhAt*&Ht2Fb4a>f^pF^dRKwu2qTj-F*$l!?@ z>!YI8UM2_j)V!-65o=0}n+>KI<r}nz;zW@qbd#jPmK~wfvNA^fd=u}y<3w=5^7|iO zu6!0wZU3VX-*URls6}Bq<H8-VLUPbI%F*X}?Y)-+_=-fr%v~NVd}KrxbWO8<Gs!>I zxn!*NKwJ=GItYKCUJ$j*mzx)1+w6f=Gm{LON_TA>!CNbdp~OIy=I&H!X|KgF3Z1x< zgfWG0b8;({-&*?2aPH9xj5F`Q()}V~s?XeS^e;SBiH1amYes;(&ee}o&)gX$4e7b~ zZYD~hGjLuu5-TLXcIAeC>Yd+&k!;D>Pl^{FhJTb0!3RJ=c>N=@uufAQbDg`G8j_Gs z`o}|ZpN;Cu0vb;SG=Uvq)*9!%)02(+MFooq)ZMD3Er<<&e4d)zIVw!HlvO!nD@wd_ zO8R{aLl==avWF?;YL6MlJFpzv?8Ind?KH2R%894X#dG=JpNKECPfk+e1*G1r{VKIF z{)W1G?;O29C`9qzgS_$>Ef?u1>5YW}(64a=n)Q=e*R3eUr&~!jLl)2MSoaBERG#M1 zvFFazw<a#of`t?oexIS7#WN^H5rdYwcc+l!o_5MlB$QMn7PA~N$~)%a&6Rgl%_B!k zORY;r_iomJ8@hGd=fk89;k)ha04r*ImBt>+p)dS%&Q{&z2o(NlEbEPX$Nj+<x*dvH zugO6^bif8;%*T|F9@dPn!}BpOg?0{mEwJuM_$j=Qgh4X}?_JX{N_4g~M7c@YbHv_j zR^(}ZKdhG#l_7K)Y>x#x_Uz6c=PUWIL^zc;IT&R75BV>ks)<s9dO^`NZ8$4#{Augi z1DnCgC@5u;vse4m-}i^BXbZLBZiRt31NN2!a%GQ44@K9IMR+%9e}SU3g+)=TCE*ba zw*9?QVUTO>+?mzvBgz!x=$xlOLUA|sT-I8zIYf|o9HVb1hKX2&mE+#JNZ3USXdEnY z-sM!@Pd#xb4ZlaoaK^mXKaBrn)t-H<%A>teoJrZdpMOkVKUZsd5gf%ugX_{%M4Iqr zh=ReJIsyZ_z~&U5s=sRW=0}5cY2)vr()g_JPv4EQ=Wd86WT}h0(Ik9E9<bKF-zljG z@@LkD>W^mTXkZg&d90Epi2ujYxi~WQ|9^ZlnIuxwWJ684buo&$%t#^0C7~kJNXc!; z{W3(-%)KbLa*f=|HDt)<QYMr;W0>X6T&D5;ozL%2*x5Pn_v`X}J|AofKg|TnE=3~_ z7u6=-k=xvd!}n9bz2(DYl0B;TOOiTlau7n8ui@;X%~y{dnrlhpUY`|(pzy#W*dCW4 z*xRjParGq8hXztXJE+B=KR*uP4<7Qh{vqu~cRawh4S5Xdx#(sGc%UL~^w<7euyRzq z*wtMZ-w<zaeqSvn{PF3O88;bU@;JLpK=Gq=a;PQ2tC8)FrZRL+4hk4Wx$~<-dbir0 zR}cDIUO%5C+*fmR#`;s`hvJ%P8<HXAgvVx)Q-tEPYY7MRl1#8|r67$v+|fgirxcq` zFne^j%Ph9FgATusNWvIM-D5djcSEWumgsj=aZA){FHd(=L*kG4ZJXtNQE;WRG{IBb zjEV$w)#nH7QF`l@?!x9-O(FQ3FGEfsJxom${$921u)h$`J-lsDpi4tmgPccA0}g%e zAXEG2W@?*fb$sJc6ew#qG&S_^z|{_!?=Joe#68W2@2g(W>eh9}G*ghEz&`|iao)lQ z7U9VRJ{6X!g;)dOcJ!uJlBPqTrM%WZU;mV7g&}?&B)+5%{YEYi3V}aE_OA62q-I{a zsTryrJ?JXP){+X<#NRy+2k$=v6-kBFZNnJ|ltnkvT~0ZNF$-jLPhLLr3H4PgZ&9x4 z3&kIs3R0ky9{;nDg?XWa?NNNcx}6S6XIy(&`P|WU22k4-y6yuiaz&0y4l_qP6LsG? z+E35#rB1y6q1PaMr#Lg5f=y%TD&MnRa?2w<#y##Ad>(DNkla5<5w1O5{|YCuTvPWy z(CuL>Ot{v@j$kOP)P^|v<I}P2YvDdU<`G%e{bI-K59DVy4sMmyX)ydfQkaDN&?P=4 z=d|&WkfiI<!O?NCtNgrS!WB|8R#CCiQjKoUGjJX{{=n!(A#<$nM!>0%AEO-#0b~Xw zYY332$S){=6H$Z9W0f#`a+fp?E$EZv=pc_f-(2BLO!y{^)Becj<#BVVo8MElgd1qm zfm__->&rh!8!mQ>b8ZU>O{AA*9=lb|@8(!@v??rUw%ff2O_l|MEZ$yHFPRUna7_QB zOiqC(wFk+uSnORZe6&rGM7JDF@W6ReR^}Iubw$drYB^O<v|NkM2?g`P)oq&5Mt<a? zpSPaKsjDx%YSe)gP-CBuE@VgDxhfle+oIORe+1!jyVQm!MJ~s!dMTk-Hk>@QU45Xt zu}OGd<*N=lG2{4NTuy1}l^b`bZ)p1Nt$`Fpw(o!k3+?;GkOu$j+jyEbb-u2MvX~B@ z4cf2TD>=>4ylPm?lLgF)voEcSX<Ks)&R47(ZOvmo9$_$hbl?~5sS9>f%y&kWhQ(uf zj<fu5$HSj62FCr*y%F<bx*Xq1bem8iDbS~A$?5Ub-6Kf8hj)Z>wL(<djn|!dc}@%j z*HJ^U3O{=5olmdJ#05})0_^GzNMWguDv!!haP-UkWME80`w@ao_5SJ-@HzgCm#TL- znfg(z-zKK_`Ov!~apa8z1J_te(XmuvH)(ubltVg34crr!8noRu-lymCD=AwpSZG`s zy~VN<V5kIKkbuq#&kK)BrIiQnxc{r#bOP}uKPE3iJ-RANR^OJ!n|<?nSa*|Hp0T_M z1KtIcZAzz19jXW^l*2csdhy!!ZjiOjN6nb$iATOCfQEp6@-KCx?6JWGtLej^`FP=F zz0J&#`a_C~ce<!@dy6(Y4klyIq*Adn^Vp+-7s67Zq5MhLLQ%CC5Nk9i|7Npi0bEc{ zs}}NclQBY&x<KzcK2rp<4R!P@(9aG1qiGG|(G1J(`_M3c4An6nNeQ4D@2PNZ_kMDT z%Io1_fY`DXIf8NKy04TEHwjAtw3Z`-{T(SCLgJ7kZDpplM%(vqVR|)<McsJUSiKJ$ zP1~g}UE_&YJ=?<wuY)@XIwS}M?&ro%M9*~NDAi8l^4pdKY3D)?n_GGN+;HQBa)VAA z57=T4HB$Xd_v<Y$8;CSk8du}b#57o4X;j@<Ni=qT+zG<*3Kl^i8|CI$pN+SbgJTAV zM&x+o<s8bPg21aI`I|gexsll;nvqBe&D?4CTR3`77s;ti($!L81JR3FzsdJONj29` zfjOqe``KMNS8L{@bt4S4fQ{35Ngr2qiLbWcltcMkJJEaFaD23){BoP8%4=gK=}jh^ zk?%Vpl4<?@t#{cXa>*gksX}FG<?h4dFK!CIlq$6se5dh*caQ!nl9eR9UVhW{`YC+t z-edu~{QQpNXw|lShs@_aKG2@x0CJB`b<+Bm^`X%yTVw(aCITEGmcD>j9gMjUTXDpd zUmxGG`O~`b&Yz3#6g0PF{y2Dr$`3?EXR3pkU9##cS$vB0i?RF2jSFSxPECHjbaT}I z*3a$cQ}*V;H`k=AtLq>4_)-iP)o=oURC;;MB>&9#OczHvsU!g~!@$qE){~50Xno%M z;P>{bv=U5z`NZnBY-}w|;JT+O@jr@uEr&HytSCK_bba=Di_9~)uXG@gr@3jF!{;aa z6YhL&nA)X5z=UX8-%T{xH{EoCM>OP5*a+kzlsr+?dz{JdgX^{v2k2tw`x6IenTS2W z-sIfA+jzXj`iPR1P0{cnXQueR807tSyT9>gahVCK=dKT#a=`71##n2~yg(%Kr^K5b zf^BwNU&ExpaKK>0o4Ix0j0_K%y-8y?ihr5u&FAS_TMm^uGD&Fmp5kzoMA(-*qo=Ns zu7?IlKq4khFfS@fT^dg5S$rU2-w6Msbm~%|`A?{)ULN8(g?zlbwCIv&&X|>!H@mUL zBDY_k)1boQq8~xCZ#FY*q4&=3Z(R71<8Im*K&_y<Okb|Ma@V%reluT<F68;NpuQnd z_gd?cd2<b5j<x$RelN}Tp>lp?Z8tISPmDNu98!t950p9;T8UgO-}bW!I*ra9W;g{f zqueB-;A`v^UlV*S3EItxFPt);XEGB<Uj$1Ij|47BHk+h=MX5zx%z76+JEm>FF=TzW z$o-9}vVNXBj<}W~q?pppcR%;QOR|;{gmwQg<I~r39<r;1E)31I>&xres~d)QBs#Nm zd_ly$F$Q+Vx?rgI)%}ixBL}$z^7hYww{9o&QLxdB*Vw||hfNYU9=h?4DwWF$hGt>{ zh2(!YUo4BV`QUZvlcRHmEL<p!>cTdCk(0?YeTHL{ngI6#(-2M2UhAx<)T2hIBpoO1 ztXwWev3DO{vv+dtGVILDu{&HcZWb6`eNrsPiy1C{ni+lO-lL~a>(k51UJ5hyXl;0r zpz8vQf0GymqZS(bmBC{ozr&6aIlQW^FZ$7}9c$~<L`%mfzsyA9{#_p>O%&D|O>4Y7 zom%1MDDY25hB@aM1pcdl>B3D)h}6ZEW;P1XDY^V^%zotH)b&9c`~vEYr<Gd0>ykw= z<{osgSn)sRsz3*{on4>z=&-iGX1CVUL^~qJ^_+~HQ(7xK$jG5TYi7RX((G0?l@0oH z@#RtM=k(A=+RZ+Zzwnlb&Ma!&{J&F!jPX`JTS5?U=bpdk@x>)QB<{3Er2-mkNTyXA z<X6VqjnBHfkwIJ^s-F2y8qT6=M7K-+fIqeGtFiem?w@9PGQFW2)$4MOyY(dXpj1?_ z=|3aNui%Fb0nw8ha;IVYi#H;72ZzHzj*nKI*m2#M9j!2bN+c(iqqy}c-mm?!OpKez z=$l<maUuJ3z4mZ#ywqz4gXFW`)%X=scIq?jlVATKe*cIXWb&WzfDRFT#o9;fp8jgu z*N-9bnVRH^EliwToqMO9a``aT>!QPna2o?pOutUb{kHuS%b4|Ek>skx{)Ge;z}unC z<HQwbpgol@^LK++PLeQn<;hy8OEoncA0PjSpH2Fi*<c+`1wC6B`BuG`eHXXNjQi5R zq)HDlk_>~G+t8KuONTa2$63tsG67619UpJ>@$rpiYl%C81U}R#Um;fJp;7>_M(&ZX zNmwF}QgK7s`_&F{*RxcVVK(CPbxX0_wH?->cGXG;B|&RcPrB5^ga3g(56%Z2-*~mE zWMHb>9vT)L9CM@mZ&zBko_lDNH5X-lW2fk&q!ax_Ph#oJ()<u>-QlAYNyEBq|7Tx} zmh}VobdmhuV^15RM`cU`;5b24yvw?2w8z}Nry|SPy3cn*P#bQ*q1^l^7clZXN()`# z-kiiPi@Jt3cV)@Di^exye0O3)c<Krip&T@TgPw|687Z|B3o5YO<W`Oa?F!_1mDhe| zm!D%92flYz*z9P(94nma56TK_+6lTH6Z)`weQk8T$Yg+1H$D*oVpCkSaL|Il{&&6j zWNNkkI2t%v&3MmOEyIaxZ)wTm6oWry$yJQLk7#O_b`|(eVsZzo_ZFQI8T)vD#mJul zMH~RZINIhtVW&pL>?|qJ(tG&X!xOo)+r@oKPV}G<l#ZAL#(>4TiBXbY^g=KFdAD*8 zEJ6!&A+lKw+Ntu4csrE2LzWfcG<_DoW9DzW3N;E9s4?hY&4~i?Z$-f(yrB?w9_EGX zt>ux>6$Ey7;0OH~3()!tQQe1@t`o-Pbs2|Ra(zR$wE#s0V5=bFHu87zS#rBuqTpkj zTSeZ{?ZyD2+l3F%b#>(MtJ`wxneh+IQ(NRK4oEwIiIIJuj%ecd6jZ`{#+G3W?p7(N z?AL7CvXuM?AF8U{C2E+~5fr~)eRrxt6!))ful!zA>vEgmn;xiZU@XW1a;CC#20V$t zvy3S^59?)|`^A@*+U0HyF%m#jK+;~Eu&TBx!vFz=q!CCT#=DI~@A|aEXLaCPqMx1c zRa@?3_`bJS;@V^%X#i1hzKF>SHXpLvR=ElQmS_AR@rVwZq6tJURa#zY+rcLZ>v9Ip zwO(Zrf^h71(An|k3!oKXc4_Vj0!>}hVszhz-E30nf9q~NOXd)y9i{<Fw;<cTP_!+= zQy)YZW?4k@9`FV2ij0)Z;J)?uX4P#|O<6j8OSztmLdg&Bq&bm6Yb-zzkpNsF!lBw0 z?4q?=KTi}OrW%eo!Z%9Nd&a2P$~!+m(&y8DQ7Bn8ZB8~bv|S?=^1MISGfE15urOo> z8B#+u>+M=TI#(zSsS0i@xE*@ube?N=YT$av#zMB;#6VKCoVoTB0ea1t<30i-2mZV? zqT3o?8#zkCG!=jS0Q4JSX&>(_pDPCGO9yu^#j~<qY#-gx42UObfJy*Vm5!jm7)b)g zmTX(y67?a&0kA!rR_=mSlolL=XXXi|{r4JMzn8j*W(<}~rGn0`^*|8^G0lL=uZKR& z@#Dz@+^W}`@j$o^1OaG3QYKL;yMXuy<W6qBU>~Ha2MN!<q6s#u>7A4fjs)%pFtEpc zR->w8K~jdAcEvHDSj&}+ts6dq?Z&&BLHyLZ+VwV}Pg+ThVfP3cb&R>&kn{bKEYmK& zuFurxpvb)`GICH<^=`M5p@OI?W=AUX5kxpEuTpzPt+2L6J{Of`csNSHR2QhJ;kS-{ zn!=$um399}`j|>xEJ`slnGygj`RtBC3MZhW+;Ag)**O|Vv`;srk)#Gt8rXR<MSqo= z{RUyQOCX%PhFAxE7jmQ8cIKkh=%R*?n53z$q$!NX^9D`v6b(}XHV3{fRb}2RDg?pG zi+0cm&W`?j#Q^SHNws_O?v>yHtf|FF#6(-#OEKM$=C;Is+2$#ux;TRE42qh678_nM zjA$@Z6Kjp56N8IAp{0-`f}p}88g|M^SQAfDx-K2I*(`7nN<brk5|}o1(|bK<G@}AY zztz<dwt7%^Rvk7IJZYkNJBHtu0nNeSN&BhLjxOus*EGbnJC;`ka>NiSlW#!*UfuPS zUkN$20R1zQP%yLC+vugeQfRumbc68yqHRsD5{eTRg|Xe+q3AGzNXnYGtN4?N4q>0L z7baee_QO63<j%$_CGtevaL%HNFO6;#MNUDIV5B^_B-goCDpj)qsS0sOQ0L9?<yPK$ zZ1Uri-lg>W#f3;X-EaS5u*JUBgCx*H^s>z$Df58EL+zEDrCGpr5mE<;T~i;O^|){y zQz5W=9oC~1(!6&Yd=`~J1au3m&Eg+I*Wrwh?&@4ki|qqsNI7zFG!};_hOLoQ;+h`w zpw?>`+X<3rvUcim0lg}R1LETukt<e5oV=*AQrk3y@Sj{EH3#oRqC21z0#^Qiv>ZZK z1AThJGS3eD`;n8pp2f(5R<K5h#Ql{LH}v2CHy)rnE!{el3}A>a9DE<)ggY8hNelKV z+USvzF1NS66>k^%VD!=e^RbC<Tmt~FC***>Mla`^Xs7Mo5*ZLu|Jx=ld{51NMD6Hx zAYMLX4-=)IgPUV$i2#x62Vtse$C*P8A%_Kil|;8lsbR+@Q!<2XWFOCjA=!C!RU6)! zXKd`$T>^Z@odNf0=Qow9w1SyaXYjh6=pp_dC6mLK6CpewlZ5n+)3gC4FsOC;P(mGm z{;1!|MKj8vy1fEWbxI&x8$e@&VSt4xaYg4)X8s*~RVdF}ZTpms$hxdyxP!&IiBWud zo%s;1e<b-Aisn%YlJ$6p@CuO^hNM0im2q$g)9Ux~^roPPLPA*N?1tpH-1V*PoL&i! zQ{OzcO#yhqOwoAn@<AYA_lan#D^U>9SdO(X72s#eNbifZ0C(T?WAMR4>)-s5q^2MX z&iYywK{7Dgqczv|)X}5I2)PS;O7b???-Ch45H1rT2WBSj_^!NtOk0)om-gvc()E@Q zGMVb^pt?h+ZZZ#bP2Cow+66j~5KbVa<QAw>Y10{imR%jAN-_z}WaU%F)(^>=05A<6 z(IpD@mE?0D^`&+Y2y|jb@>|+HzUh#IR62;>7fC#-)EJqiomRkSQCImF%^+zy{~;h! zZ}U!tW3;oG`Iq2`(u^SduJ5kJORztAUmCi)%izk9X+8cJXqXE~!_x+$MfU}$Rmy5^ zH0`Wcqp{b}Adr6O-)s+C^M4i4&JD+C%(rGB@KY%lCQj4s*Rmk|`%dy@?){22QAeZa zZ=O;J%*+u&jhXSN@#hJl^?=joMY*l~$|N_|H&D#2F+tR)fDzrbMU(xAC<5zpRI_w7 zuR};dTX|y^XZVcbUdTMmd_7j0!3!!AeWn%E&)=1{jm!LA@o%zF7l3>n9P-S`Qkh&U zsOf8n*V~)=sUCB_@j*OnA&$Dv+P&ornPYk~vkva|f+sT=wPlk<j8W0Z<rlQ>u8qMm z_03CTNko5`EnN@@`$iYy1Y-47GuGA_NYW%T7UZ&yAGjb~%K>yOc3w78r^Km6yFnI~ z6%f>|kL!dc^}nG_AIWYoGk>jpIQ}jnm=>P>AbyRVk5EbrRn}b;1prgVhlkEtlT-#W z*4`Rln9z1&B6B)e*$;Gt&%^>+Oj#Gtdc;qp(%%5PNOzU2nfO^9naq0lDvIptN8T*R zoFBE_=0vM|m>dAXf!kbM99cNEbIZNQ@RpDX|9;j$$wn<LLs~k#cLsmcPMtL*JgajU zD#Dy)#<yn16@M2@q(E)6B3U;nvkHx39fu|-@>(z4M~^l5GCqoeVPs0+Ge(nqa`%-6 zh`UtI=B55-j|bsgJ=m_<A-68cCY9}LAawRc#d-rR4|e;Z0UWRJSAdH1f*0p8=(pb` zAB1T3tJF>bg%f~B11F6?+0o)SxIs3wQ^lP_8e+D0g$C#l*D;Ok93H}H?}}U>@fIqy z`kw2t1T==+eia>atnJjPmVJ@Yvza|xW&mv+3Q#RT$Rj7-v;bFblWDcM8+oaP5kBNI z9dSq=X1fLefb+@ZWcV}bZARggjv#E-1Pqmyaxsv7dK?)=HBqOaOn5K+Mj{h?l<^Df z>2wN6I&u5@{P$yh1kqWnU*wBZ25fGT8&@6dX&}yA&7C898o>El_Ci#2#E~u{^AcJj zdvaj1I|rmr|HqWvld~G}UCqjQ#++mqfSZIoLzhiZfUAcm>pI21^PzArfLbBs;2w8s z(f98Z?6r@Du9MK5FD!Px_@O56jAu(!^LX7WQ(z}`#U$8Te?PR3AVQjttbl0(A<@>O z^I?0ox5~S`PCW8Tr`fw$?oGdDv$E>p`=YP*^Fdhu>~|F_{XiLbFQVn0_u)2>u<f&L zguJ?-mr8acssqB6|DKWMiRwTC5Wtl2E*((3yM_Rt^q97jrlB~5z`tb3(S1$P;q^{1 z2z}BnMq!Tkf(AA!^!X(!@U_d!h;I>u(>=e>zy;}E%AS~Z%^9d>=sY8fC%!<vAb~s; zdZmu)nOkc&pu}`H&|*{|dwp|wA3YpZLo|6_<Bf})`|FuofCU@r8(i^SH}M|uS=zY; z>d14a1F^|%@h+g0&wFi&+`7dl&)<t{;mRR`1|F;L{q5>)9V98y2Z4CpRyvME$i4^S zTZ%GT<(p^>wTph6mkQ&R<O{OshV^$#JA{W1*6J>q=U7gg)OA3Ylb7aoSSvb05X8Ev z-V(bYF~NeMqy~um_FTM{sXr5pUNbWulKf?uo)*jALuTL>ho3#aNNAeJtPW$A!pDai zd&WJW2KhjY>=A}=V|f5)3!N9j`-~d|&>=vS@gj{#!y>IOaYO1%7zJano<DNpHRP1O zC=hJ0`4Pad-2Z0dMp;I2LQ}xDUwDce)lS_O0>Eq9tr_M*Jd*yDKyGe){sqxfW>?C) zTQ&iFp6)k2A`jo9P+TN6bO7Ytizg%h1`6nWca%KHi(?r9$x2%5D%5@e2B*`}34;!W z$bpB|54^!H)6HN1CF62v?1EX{1M$HQzEl@9^oiC?hHnlOKL`>s1gxihQMMwPEfsh& z`Leiu(+V*2@2^(xbrblj%8>EB2THm<viP&Z9ZFYcvCOAJSI}hi{%yBzHyJ*NxE;ux zTWq^53wLe;UH($#bPPYQ47Jm|mHcH^Ix`2CCER~$tT;kd5KIh=w>Q#uvVh5kCqPa2 zt3m3&JX`da>NtjsONio}BdW{-Az?OG-nTfy%mG(!2b>Pg{tl$HjxFjvkZRO5{v5vT z8L7~5`JHo~{xl%-<EEMNkr_5c<6$0IW|`HG90jtT=MS2JM!$rQW^sK#ikTIS6QwEM zqkSK4i5`;%xN<YMI}_^08X^(okQMXnd=OCcQJd+QYd21G=nMY}35hSvX-DNcbw99v z4969?jG32rOE5Fmh7#FDb%MNW;T_A3M8Jquzx8Z=NX#Q;-+zfs%{LV^M0TyduLG@z zgbDq2(G0s3{h&6oKRIzo%I^2!A$0+k>u1eNPpjWSkm_*UB#ZRB_iW<lNpESh=GMZG zKnuuPGOn#!|6|}l*X|<+(HWy~@B2r`MnAbr%ve(BxxN^T<{#}BSLHK4+;ekswBmql z8O_1}1S$cT9oyAoG%Hd|*kvIKPzA(ixIOr7G8VSGpg*c-Q@f!H@w9~FG+oq})=mbU z4d4jNojDOTa}g2b{2w;p*2;ROqz+G#YARBFUbsKfuEb;NmPp!zLD(jcMQ|bCU0U*H zW6+hNPTHD}`o68F;+dB(^sYrG&h$S?&Lil@uLq}N)~rtVb<YGx)e0U}Hzzfd6#Ex_ zA}=TXRBxFjVQ3qd;UmF#c_(w}7S<p#XH)ds=NFrg0xth~{;M)9g<ybQ#-=)jL>La= z-eYMyv1y)9|2!I1`u?&T+$*&CV`4b+Ac~SxM1R|tX_Ic0&OEAL9@pS0k)`R!EskuL z?P{cJ(}NPQsXoc~l%pX~aXpH#-Ty%5cRj#nClH!J)(?l6DS}7q1>5kqnPcUgxx|#B zo~aE05_`JLIPDQ99xK1}_El|{zEKo(G~ZrNIk(kvy-vW?4j7W7EVpX3cb5+no!Q*K zTtWyLRm~HDZLGenKQvs+TPc$OMbAU?5jqdZU5Z482c-5tZ=t6V69!}fZWe;XbV0SB zNhxkE`$v9~gb^VM1VX{-Rw57GA&}HuX!OK3Ua@$2UXzh;<aJC-i~)KkHKjjJcqYwL zXCkzma_qF=k>^b2;)x2NR<PK<y~NRh99l3vPwk}Ofj}K`ZWAl6{|SqjH4IwQmA-4< zDVxfO4{M9hmk0ZMis`h-W@U)57d7MiUSreT5#rx)B!Te$>{5eh=>+ed{@TiI7PTJ$ zFDfs}cEg-tu7I}>fbtN-zu_`Jg{U()!n(H*pKP)kaR|V)yJ-=<QR}tD2nWoKK*vCL zF5sIGhJ^R`r3uZ#u<9ID#vHSMQgr33wrz<L1EFo#9Hk=7B|lQqp@X-Z?Eo>t{k&u0 z72v4Fo3cM!8Ka;zb5R{nKRA(|l>=zUU3^1t)_41gGqr~Rc{DiG)<M-&$D8VK^KARW zlI&@q;<%k<w~T)QXRJtO%Kzg@wE#?5C`wr3HcLmWyP$QL!snaZ-<ML+X$$zMcKgTF z#=Y{xhT##K7Lem0rOgf?CI7p##EUK^R6na7+*$_r^aM%u_hl(H|7{aw_W)PNg1`f) z7t>ui&<iA41=<A1gFa{Q$*=*ps7?N%DE%h}`kV@NW`TAJ*~{|!R2}yOP!46OGw|X- zG93XvEJI>q_(0I++3T!fQ>b?HetB1h_e%&pxDHck6hO!E;*kG2>==+Ie}xWWsIGeo zH)BSP%1qI>)I0Kxi<rEC!3ArSLHuTjwuB2cM}aP#T~>yzj3!e6CWTR^d5r>dR!eHd z8z7w?czv_M8^FumS@$&fVUdwIDOvRnoCAuuE^LLAO#2uiX&K!@3<}MvD~xRXqA+E8 z4N|-FyU5_R-{HERF(Do522xDz(wW*A1r+Uv(4+%?;*(%@=GSoIE`%zX68YYin+J(C zCa6h$^#=@)VTp!(pBK$QE87j(fS^W)j6XS3J9kZ?L-i#;4c#)G#^-$W_`EQT>JEtV zks91@=FoCG%KJxqD`=S1#Ufg%?3>S+j~V5%g@AG)?*LwM**XdP+__S_>c~*J{GsEf zYf~>7`PQ;?j@0ftCfrf#p10dGer0fSn08K>!h;#+<Ia7lS=|TOX^Z9&d|?f=QcF+s zLl;i)CR5RylC5QuX$t)NOw(@GNKt3iXMpa^g#IG{2qwa*!zWc|6-M#>k^MD*{hg|) z;$*1#($)9pxfkxbW_N=BC5QLdOLYj|eo$M&oYS5hF9kV1cVo&(V*Ur(vyZx@{)nc~ z7P%?amoIg}z!LqhNq|v}6iyD(=Alo8E~Da$0IS}Sp`Sn6n@B+5aRmZh;7q)@<~xr9 zW`Rcdu7p5FZ}7L@LR<FlA}Kml@tmufcL|^j=T*cDPWxH)Q!izTB);@aH0R472wh$* z&QJ~c!u^;5&i)p4n~_5c-u2l}0nN(3*_;7%Kv0%ZX%|~S!<i&(+Ld+%U*Tq(Bno&c z_8uerfuhweYXI<lgI#@q4}R^Z6m`<mzHP05e){#YXI6%QPh>;}JaL`Wy#L7z@)E2M zf)j2Ep$6dq57Y?%utyh+??9lJ$OUp;j^2rp^Uwl0@Mz^<?}1|k)BNlIK8HG3BP+V% zORpNy!vr$c_E*;PePx&{ZZO(IjItaLkSwF&yUF0P^KRxmqn@t-*kuOgx^+Sr)M%`~ zxFmIXo3Q{?zll*T_nSPugdx2a;CUNFz}CkYXf*6l1Tgz~zBhoDXb8OMo;eR13rx)L zCIMy<TQ4M$xTlUR6LwMQ(do*5BmURGzANqE&<XdjU0@1s#!D=W9D>8QfbZ5q+cm|j zQ8FtfTiPr)2L|EnU6Ya%$0{(&fuCY6u^j<SHpsp?Zt5HZj6n{v`ZAecyaMJY8TluL zTNdbM2@eU|yA7&?N~X<+98hwTQGBKdbiV*;LO$>y#6gUM9~J$hxM7%^JXru*`j618 za(c!)>)Xx}=N7ODlIlsB@&;&^dV+#(%vtn&ND;UZQlaF0IC%&RFzBKgJt~p$RIYq( z0iRKz@GPK6Ec8@&T>%KEQ)~dB>zLtV?>?~1(Q=^oqaW0H0a+cko{=lgwPC==2Eyhr zqL*rcS?`7EMtLecK9o6<PS)!YLIFV!+R9)+e=P^rUl!P2G<dLJ>YA0ak!4!AbNl*! zQ9w3%6y37D)P7-69*RaZ^g?JI`ER6Fz$ERg6fp%5v%ugX;4v0$_XVN;>Z`Na?boBp zw-06O0hBqfyUHQpF}{NyCQp9k$NyXpAA}4R_NBMb(2)3)wVn8T#;YQH69?_LUhMQj z){)N+D8qc`p$rqwwxn{?8yG$C7PvLLiPERC8}cOGe)B0n?Ck+F3$alk!wmY?tlqKY zhJn7Ku8%!lDvO7eaOM5rH`ug72X!6tMd=LZLXSe7|7_tT)Q0M>1m)0g>~x`n_SqGT zLmbJ>BFL$TxH2@rz!CZ$<Xm`3yMK((V8|%Y5EP2+BZx=4Ch#pf3e~g1v*IS#mu?-0 zJee}wD#%V_WH8`?<`p?Z*ht9%(2?sS0Kt`n;#hoX40y8rb)#2`LUh277P<i8<g)5y zQP7LD!G8qzPKFeaBHkuI-)_TkcW)hq)i$rjUg4+m(n*c@Q9gpCiC4)W5$?EQ{xz=M z^e55rqZE)##-z)WF;K|rd!q_oT(5AU3+Q1P1;&X8kGB;W6qDyzBO~<n13C)NS_2X1 zjowDZQ;`)wYsf5^^e}y(BXYF90~;mB2@@c`;g_-Zc%5fwLYrO;a`e3fnk+<4ynov> zvUFU&mNE=4(DbDm3#7k7nboz@JvAZ+rHsTrx6PvA43^H(ByrJ;*JLN7=oTpI@(?Ms z5E5(0bRi9y`E#Ez_il8OGWj$~O`1U73PE^A)0x$mp~llFyu2Tpl8;KvY!nR3cERzD z1F>etLMe-o!RQH3RK{-bw{cdC7$^Y{0BzODt}dAXIr9=EJm~<|S?a8)a6@x}=DwIJ z=zi(8&8c`T2l(x-E5yx}L2R}Q5e>f0t>2fdhb>)C;xpm%#L`@G`8r1_p>A}Bv}d4j zSpJRF1D0OC>}6ASyZ*sey8G@L5M&_Qd;wLrOF~hB!xroSKLSQ`LA$<1@0PzfgdA+$ z+-}z==~ATyH|O#dWV!@{$1AV?JTh>l-&q>Y^jsqC6midAxO{hZM*gAiructFjN9*b zKYoN9a}N@}mu%=1!OdRbeljp-RD1bpi1Y+sF$>l`-WENSwhwpkQV8Q$rcNs&kK>!? ztXia^F;9<Czi2EZ1UEl}m4)z6*J@peKs-7)37Lh_Ai&pJoDUgd?qd~bzDNhYe^yp@ z{{r_@cc?{IEZX0u+}u9C@<f|{%)SbHQuf&2xT9j4=daYL&j4M70@r!))#y&4g{<cu z2MFd;m+Jafg8b_*Uf%jDD!8UA{9-z7g84-9Mfe>r@R9ZI<-`zO+rXd@i~_gsobm;6 ze=@S4$N<7GEth3tui^$hId>$#RkL489#X!a4w8=6tjVE;0+Ta~mk&t}<Qi|vZ<;II znR6Q(%yjovmvvw`K;Uo?R-oE*=<8jcGVm<}uc3LJm8JfXS|tfB@;8&&v4bst4P4n= zh4;hTclCn1RCoWKY|yAmx)f7)D{q%OPS{<GpS>-q6KiLOO5&HWLDQwKpnCWe{(M(4 znns>}owg*s%)xi=O9ndN-umSKPWhVL`bLq2pOpNav90}N%El$iKFwKus|SO!a!5}( z;F|O*st0;#bd@@5tmo&ZV{?F`CG?$3MXpbORO#duRwiz;dENJ=!=#LYlhLde<Monl z0{3HCdxu<mr0~?tg+A0yn9-3V#}kh}F^aeytvD7<g+WO!a;`U|M-`S@pvcT2E{evo z%GJDc{d9)vzB*?hjGv-}iF>R_(CPV=pybQO>`Ygw$e+!gg&YKStQaM1qd$DBsBC6E zFIKwlZ@Vc7H{i#}KXFX`%@5E8TIwiP9)W#hEbsw-WAe;SCsR}7*$N3G2QK<lx$0$K zroIJ4r5nr3B%dk#Q5<?pXTC`nYm|EDOJu}{bI0Mp;zM`GA~q`R>{LvTKH8%Y<DYXF zC+J&q<&2p!nWW@R(FbIP;%oIaY&fI`3UDclY;F0JI=~za(q9dcSjS{o&W7-XHjyo8 z?dA0MMgbGkvyU=xUfibG)W6Wdi4^(<5$;E3Op?-y8{S?%qy2DaJTXbr!f`_^vlbq8 zAlkbPAAzO|8}%Nx*L(y&{Ov9WJI*5RT3#>co~ekb9S2ZNFxq=;*ZXUV8(Qzi+<MS3 z>_t=EiIN*VbI-N!fQj5!v{e$dzmFjE@^?iNK~$B08&VEb7}g^?^IE0z24k{deasd1 zbj6HB=q<GierrAatmOU$i(*cQSDCiGPI|}6AA%b0Ys{S1hrI#fM?hk3qLNK1J(MPM z23E2P(LW&%3|?&;BMdYj85^`-^hgNXEwSoiEdCA7x!Wb=%cknFfLrp$wQEDa>Kfz> zmbY?RXgYx)V9DuRv4<|Qnmb~$c?O?Mip@;`;_ZVh7p}yg-FuZ;-_4^Rh~ud}^Xqg& zB=+k8PgCH3tk4v8kFL}Zb@!^gKWCrrl_aJEI~K2F5LTe*LhFuwa4tSR#mS)SP`u8! z!XgH*kdRC2pX@Dlaix-|^K){V(dxyj+g|!HL)KK8&r4cc3@sqB;}9-KdGEu*5?JUD zMSV0v!}2=r<-xYu51@;#j9P@ZWn71Z<4fNp=!yhU@;PpGy7=cs9yvqL9big4vb($1 z&g(7o$XnbsVDxjnof3-T-<s`GT3m8Dn|JZ{h^WwCjcnIYxTRIS>W%O$e!%Ej4n$gK z7IkG0KXkUp(EjtU!G9mVQMJ}0=4Ev?Yi-q+UYZ>p;dn_S@3Cpl;d;D%RnpO#CrAEK zw8IWabzj~oU3J6uvTHiVJf>ZPB1f8C$_1{(@XT=Jse>LH?ZKg%4Ckisq0Q#upDk;4 zbzNlFe!@(kYX9zFi#GgJsPse&WxiS>Vbb&+WECd1{bq5jz0vYxrF1||^jVN^w<=ak zVCR^Qm)4UIUv=l^H`%tYt;*F(FmlhdzkT!Ad4GWhA9d%Vnd{|<8tm67|F*07rVP90 zBDlX0Ct9hd!FygA%`KtkI#hgr6;~XavwOSrc}UPd<ogq$G7oyIPT|K8+)%Np=9<4N zRnf;?6}luKy{8j*-)@%=A37>50yNXFJ)Y8Xv>o<SHzt?9wI9C>c<kSJ9QTfUe;UT! zitow5zS=%%F}y34wKZ%Q&5wShfFdzDkD7v}j-I%Q_c9rXS>AN}&So#!T@%vo5Jo<c zmNIWhzzS@xM2=rxaf*bo&kgNcj>ql@1!F0Jq}tkjk*8#(Z%z$}%<!dsvC8+@)c=8a z{|5@#KGJr-{wo<F_%+g?c2%#x*Ge|#VA!GY(`(gt@Ph|QSwokr9Rxzj`N`UM)-XRv zP{)6IWx^G%*6$FEzod`BvXsCp*=H}cU|u3Neg+s&|2$Zon>MhoSE!V_*}NCHsd;gH zv|RwGzmkGHuS3}77j||;LZxge`oEp7fH1J7>2GgI%tV_h=a#K&-{ovW`m3@F3|ta> zl{tyaw=@Jjbr-_f#b#d;9vZaq?7(rexQtx~tDMN-cQG8BS@@A0Ty;>QmQzKAo6mS- zQWFpTC>q99e0VP4#<BI6>m*NMAU`kst}0>aaf~tY*`W=GZLty|Uqt$$y*_nhjdsL; z7Lv)DGh`=+!UF4z4Ki9vZoBNub)U@F7SZz60^8!O{c8^--aY<wLgDJDh7eIB_<M-r zm%f}hSGQZUoljEKUW*F7c#ll(-P2ATy}I%Aq;I0J!~v6EowB?RL8R)2z4BQDI3PxJ zh5^^to_wd%Y|>hUUO8x2>cL3Gy*pPI+(UOE<Qeag29iZy=FuD8+CL{R;Lej<_AP(f z^r#g_jDCrF<PMy-HmrMi@zN99*A5w~8%Pj%cZK|m%|BeZXQD&<Q4&Wu2J8|Dn)i84 zL%ZSX4vmn0NWnyCYQ48Z;<0nF5FfkmH~{`r9`(z0W+Ge8HC0@li=M9DG*>hde<NMS zplF0V(dqqu8`XZk0<1@O+%ogtwKzp=h_MI15>D}x!P7hztj<0X5QqL47N^$E-Zto3 zTcrJ9Bo9h&><au+1Q%+ZK*`;XdyOKcNp=7E&>`sEnn(<?4iFW&QFw!YM0^*Hd%Mv@ zLHt5%CM?llTOI5I-ePOiO^M*huMDq^M5=ol&Gk=$$X^xjnC_6p+G}=X5_<d7WHRUj z!82fM-sJ}@hMO0GwzPw4XAOWqK2FSAfPb$b(k1H<6$c@g8v+E?R15x|Mmj;%J1wc_ z*-I?j&95uM{f{MLv!GfyMBwijttL{jl17F2A=2<-pbxi*XE{#P&)UwWICH*xBkbS< zmdV#j5f9o5Li<XPARbtnJ+X+n49gFDgA}LBks1G)z6%3HU*Z!CYu_4gbT4tg0F6}6 z%Oiv}Y__{j!iC9qSsD9cj}13k^W!ZxNMpYrIgNCEU-e#AxDlY=ssY(H1vVbxLXHO_ zQzYILK-IUF*u}~#%FDjzPAne<kQAipn(3IapX>Uc&}?-eMunEf`SRISv8zbaH#`d! z$y(A8W&DUOrTF&<16jCPPe1nO>J|KaJW0tn)y~>aedF<ThN<;cG6=t9?eo)ULh*Nm zwdLXUb<c))2klHbp3*ARCms-5e+(1HH$5!n0keOj#huh!vQc}Tbvu4W@xp$neG_eG zP}8Tfc{xEu<_-tnBg~>Uf$VD13twM~Ryj=xeLzwQd)0sWYj43FZcD^QEyxY%eXY)B z9%v`sZ2k5J8=%hz?W>ZRMC2OQkLc@%XnM&(x}Qheyn4w$m63|zGi6!#J`jCIXVluc zd<wt$Bg)i*R#<!Qcl7vqB#hI^`K$>K@+}43jJbc^w!ohT@B}alRYtus9ib1e3zQ6o zXHLG6B9w$_s|hc!{TD9yw=k*Uo8`GkQWJi1BvR#L-^Eggs=FDhi&6NoEKpgLoy1E< zg7<nYz!5FK@cQlr{H((#uaEI?ZdMv**ZWU=)mUpkY*y3JmHV6so)5%HP3cHX$T#bG z)%2FzDmrW-!{hV4d->B4CACBxCcaw#U~mWZhuhTPI+-hf6^G0^c=&4-&){pZlt>cx zV!qM*#uBlf;~j4j(o~$`)eW*r)YfMLH3-LY^<RQXE}kMD_BE`Ppg7U>>)z$hK>RzS z5U8Z;^AhzwxwH`#JvBGh2My472OQm7W_-jk!t76Tm9hGVVJ*IJq30xkjtX|ejqJb) z0UZFr+{Rj;1L8C!ppq?kIjV+WX(p@%M)xVon~YnFoW0nkzMyl|6nWiM+3Vp__+)%* zehuo{oCkzyhDM-n=bl<`OH5E-0iIz=C-0YBg(%K3OjC#)L~Q@bK?u@Qo%&y-r|C(> zjRbM+`$P0dHr3Q6miZ&bNe8e(vshN=QmU?soh!pP?C45nMgu{Sf?hxJ&Ur{9KM*Ul zn@#%?WNNw_%f%gZHxUN4Q}@h_R!y0o9E&6DdGS;bB;4BlY;9c>w_rR~>Vgt}3^yP+ zM^MS>H|=&eP~2NK_a24x(s7sj{M`@sn{|I!ylxh4zMkZr)wGMhlVsPGs8C~sG6OHL zC9|jQGb4@dabL5{yDF%rTtBHnj+t@I`7xU_<PIP7L+{~qV4ZDh{B~yZ-S_&6*AvRB zSBFQ&c&t|r>;?u|?iu}EZ*85M8&6S6fGHCgL5`tDCc^hNa9eTcVtJK-MXnnez;8qZ zhThrE={oY))kV|ld&k3T{^?g{ybc00HCJ55A7$5P63MeYFyU$H0>$O$PqHfO3n;Ep zk{|gE+s5%JRA_Xbf%>7z48=*QzDTb{lSc5+8r71EsViL(;3)q!aVOm!K#h(bCh%zn zzGe0qpiuJv+A<t);#yMOoZG6kUPBWGc;Uk*;n`auhe1AXqsTU#(Dt+6J(`nLE5-lv zGbTzVT0|8-H%6HV1dpvlJv<7<bkC^i$SBL5Gfl7Zl3;T}6iT^CA*ILNx-%|f3DExa zyaTn_Jp#5&2uP$~>``Z8-tqO2cI<^;{Y{RBQ=txej9K#b_EuiR6D!@*#NsV@px?Z9 zb=t50^>1_&^C)MafdAR#IyWpIV~Cv9ay5&@9NcU-&~*PQtg6z;@t3ffWdJ`wOziV= znzZ^kWhIRROj$0<Zo~>Lp`qw?UpT$Nt2hb7%I=-Z+S%a2!q{-3FojZ{NOwPPm|1=k z(CqB~mODQSnrs2c@RH0Nno-K4#kCThkH{Kzk2DZ^1{e;^yGhP>!ig`dz3$mXnP@Pv zFO01*0@b}?Drs$U-48tZS>eRw`^K+3x5Cb$Av2QqR{0SIn4dVaJo~%dpMvxUpLHV8 zn_4(2qpfmK_Y4PL75<Q-zj}rFQF;&a^!xjSlp$;&kt&`2H4vm3#mEoBMu>j8siL$Y zmX6qs25}>S$NbY`>H@UdR;N#g*vRM2)lvunMz;ct)7Ec(WJe!Gltea2`)Ut~jTv=p zIUZ@iH(CESEux?n`dPNOpUh^GBzSpl;7Mo%R&Y@My?u9hFojq)nYtCZFd(eEWa1Wq z>5+JdE1!_e_~#>bmgPjt2#bjx<p>4|hF<C`m2nbM6X_>FfivVDK|&>9<M^13v$&QV z?O{+j`{QXl{UFI4FVtw^tVyPo@h2C7JVzcSgOBid7e^<dVI7WlM+?meR2p=&n>Smn zhi|;C5QE*boc?yoKt=O<?NKKJq=MB0EeN%+>n?`A{W)Ay)!@5D#c23RF=N+C1Mi+m z7!&JO#eo9pJW86`8!Ve&fr*%S$=^So!rb;B{cLk#TdYtEr|ul-{AxG~73@+TN3(XV z4N5;fr%GL1Ut;hBE1jp6$dUSSVu1|g!6O0u<m%R*Vjqc`dA{d!_jaHcMHE4f*$Vz- z9`sLetL)^z?Kk4mYUxAX8MyUb>-VFFx9~5;3DPCY5Ow%7c!*-ew>yk_X&-8L)<N0G zI$&u~a5{A9IEFK#E?WU(-9JlEb*VWDq&Kav!DI`&Pz~%d7vVIeH**x#C``lLR|IzN z=$!m*X6LL|AVca6)`%uj=^qBzMu0!mUc>4aH5G*I24);~R8hy^+;9SZ9zW7}W9otA zjg2-kl06Uc;g*bveGB>4#<6~3J&i$i<w$J>?j82p-OoE^z>GqKEEJ|KUdh|q)3lEE z2P!%nO(-v2NedXiq?I&?t2qXjtc87Fw;lcIoTS~WT8Ge)on>lyVpD?)@lDHiVlZ^q zYeuNXdI-wy6=U3E$@&&KiI7*BNY%Vcf*RvIb_6zp&?nVXzu~0gGqR^$3H+BATD2+- z=aMBW^-a{yz2_g#f@1IWzSi{+=x9NxbmJZ)c7>YIMIT}mV?ZtYTD~;tph4txlW9lw zI#R+<&D0LPi??c;Ha)*~;UjNt&#%|B8i}N)rwMu+j0l|`4d(@`i|KP0RRcg5#<uLz z3+}f0UEFPY5eE9aH?~>UQGz5rwW#>DWEF5KCRaIo;<)hvg}O}!qSCIqP*39%s>)eF zJ6LeW7rj;H(N<&C`S|RsAL|fTk~*sHz*G#G(igPNhLx@N1vo*^5X_pD*TVZ*dx~$p z8!CU9s9yc9SgGDc^rIMj(+m;_j#eG2VLp!Y6_c7WQ%r97ne3Hha)l7`)i*yq_FBEr z*fwA(U4Z1YrQ6fAolQ_Z*DkB>_1bv+H{f=Ii2fpUM)vz+&sq8Yu}G8@_Rx*(6*{{= z;gp%k0C-U{Qr-%UzN|aGpFP%NXHXJ#c3v20Uqh3tBAHLfD7i{#r#s9z+*Us;{k7_3 zZOv4RJ<G;k?>H&?*^gH(yjf^EzF(|AI{Dwlz$xFdF<b$(dx@m@)-o*Jadh1m(u@Oa z2!>~rS&6w6=$nS8k&z4iu*+v8U55YRZw`S&7laCdHzd(6F2AGsVXZC5Vpaj$KnW@7 zks061S=Q|;u5b;?div{9J|9m#xr+`IhLc8Tp(<sXP2ZnK<ibY6A`vAGJB}8MgPz^n z7EGySCXBJLYb{=Ux>M$bdXI^Ba`@6{fkE{%tnlZ`vD3%WbwEtmh`}u7>B&iOzDjSN z!l-W8J6{bqM%i*mUAxa$_t6qlCBqJ7(PhAgia=2mpEq$FPXVRy1%D_q-h64|tJ_iM z<EQWHYMOWhBEPt{!HRazOunxrbi?%X+fC}s1Yupn#auZ)&5R8K#&Bim_R&ts@s6%x zk9QI8V*aY^Dg2yPcQOE#kE0jy`<HV>$l;=#3=s~aUo3U{^vRZC%NExIWXi98AjI6c zP|R1F{}x9E1aV%@3KL%a^wV$dOTvnD1Z;W6dq6nY^4XQw)cCtO@%AIHh%qyx^8qmI zy^`sWS4Add_&E@1Y!_@Q9p@z*24oQSKL<Ya<n{-o62%OjUp{~~G1Z5SGMFD+oO-FH zSUgIcT1m2`twy~J49!jr-uQR*?wGxQ8RNT|{+Dae<@D=Pa*tm~(^m^gnI)6|13jWz z_deq@Q9I-)*(~GMu%Q*oQ-4u(;kBLU{>YkDPDAORKYvHis|^Kj&2X0B=&{3NTU4?3 zpDPl%^vu%|4Ue_{g-0E%hKuyv3=yNR&9T<5+B_Mp4>>61+sHF47<jGGo&33d$Wu8m zRBU-4T6g!-Ot=}n6}P_1555B@vX@37u_K^BMC{iqqM4scYjkovmH8J&v+wQJ($Q*? zC)eB>U4sYeYoDmbHD64*0}ray3bO9l>X#|4&VZ$Itk7EPz~)uAycn2XNz~M1kKo%b zWEb9u52+1lGSuAx8`YAHkpT#WW&Zqn8Yn}Mu{-c_ZUdm%BGBwlK>@X+pOS0(Ovq^n zs8Q2vVF{zqRa!Zq@w;>SRkQN0Al<vAb2resMM`2C`TgxX_%VoM(O+NUMON&;iZLNo zX4VTB&7-Y4*kG;R%FV)ZU{Ddhezhb*UF3B6-^Yb(;OS-oAP9YQb=_{R<rXS_%HSN} zBoJd|e@Xdf9k+-aZ*wuqUXDMX1_;^%R$763X4=o6Prbij1l11@Z5;GoJ^YQvD7mxo z{JzO#_Ex%4?Y@RiX-RpYUS4RleZ|Ijat7QXC~UVlG1+fIBD7j-`0kx!ooK3e>?@bO zkf)t$XN<S!<>NMj$#{~269sF8<JOs)RDmr&3teZ5Qpq4j;;pPS_<$(^HOetN;3r#- zQ26wGCYsexYK}6YW~c>*lLE6{KxM;A;RM~y+(g2d&w`1=LB?u<GB+1V+`j}CM<(`W zcZ=DdlOQ#{sJ??~VGZ4uEkLnP6HXzEB<rc{qJN~{7s8&0rb2)`kp&&(3?!0WkmV2c zVCVI$;yY;Qf}=X;2ZR7b0E>9bsewrvaP(54ek?eO?xX=bNew?nwOaU2n1XE>*$d6i ziBQG@NqS^=72?ATV0$B(;+-W7BNs3LX_Jls=3{!kj8s^m=)2bhB*sOVPvw@X!R13o z<a175hn7ob))mFb64~NE(Nmv`!7y=1-F~VBxFR{}eW*QdB;m*xd1E1Ns6AZ)dgspJ zzrx}$%zyLaEGYDw?w<U05K$gS1^I~Oh>^|Pz^#$Ajhq<<{}qBKcI5AqJAxp_97I8r z(Z67%%s)yk5JF>tu<x9UWrn<46wO=C14K6pek3Kb8S2+jPaSLmMFnq4@B?c87ifmF znT7={nf5T?bc&Y}wxL}mf`7h#DI*c+S#!WaN0fCT7$BZxW5sg_^bA<taz*Kqfom*t zA2V_U@Q{FrYTqSyA@2wStSo0bp#mID&v9^;dLxxD?%<UxsJ#aH@IR2B=m-6OKf6T+ zNe0^?MLb7`iLWJ8SE1_#sMaMA&-j|f1%4!<SS8-r(l@lQ0Q!djZ@+OMAu;iHNR!5N zjul6F2r}SHy#g3`puC?M1b-wkeqr|(5!Y>($B?owgq!hRb@!8<rP%`SH_KRhQL$sC z>KXT=u0GsZa)0b$YS;U7|I(Z*ICYyj{6n6H@HFrK__q9u<8}s+IXF<*dOuSz1O^uv z7tFAo((P>BJwS<P{etHT--H+NRcH^iY=~KPO0)OrD;a&72PC|dJcU;DMtS1jq??F0 zU8jSoY+&aFcdhrO(3{`0^EJ1k>CCTLsFBnb^~oVz;t-w$2t$aA`XfVT3q+xz1qzUH zY}NA{US6OPmT~fFaDFa@?}QevupscCh4;D}T%_ee$H@5J9y*`msnde1bs>7zfrRR) z9xfo9>Y`(yPeFwMxMMuLmXuky%`QBelTbo6HD)te`UdAP93ai{a@vtB8-K|>AMO)i zgSyaM0aX3{)pA<&tVzED!zDvC<w$}aBVKpm-bn#iWR+^bIFZfB%6ORD)2FsU#8m() zZY${n(hwqv(HEt)>Id$}c!iWG!MuryR9zZ+i=C@!RwAh(IhiWR^M53ri$Bx-|Nq}J znH;7AHJ2GRC6r8EjG0XbBsoh5Nv5dFX~_Ao5z4hTLUA=r&Z#5{36q#Z;W9<e8fh`d zIgD|A-=E*_FWBvU+xzu;KM#+`<L<8Z;oM|Mv6r{<wGoC$$O15!vTAF1PWsdBfRYob zeJi|bMPJe4Qtn(1Ww(IOx9X<Gg-m*Gf)o)hyCYV*sl}-AJ-8;$FG2UFL9TlHK)Ryk z)g1r_c+4Uw5(!FMx0851Zf<@~WT`rE*N7#M1OtTsx%LUX^vzCYLYzXUK@p+LoG(_} z2s-rIl;zak>8qK_HGvK|d7=M$FOXk?fhV<ZdmPi&jv5A!x@_Ai@|wl<?Rrb1Xs=0p zcPWq2DRMOQ9WG}s_A?3(GE<MRu>?ai4)pL7yE8+|HecDUD13KBn6jio`dyfElWM>n zJbRDXB(Hdc$M4NX$x*FN>`r6)y25!PhhN_M#M6hDDOd3|yfN-lnHBV7jT#Z({nET* zwxdR_;Ni>deq>Bsk%JylbjC-qTE>`Un)9(hdf`-D@h>T(FB)0spD@X3|HdV8DFBnh z^zj(WGgf+dn}G1&L@fB8?T#G<$gg#v-PW;GFlo1>e|n;(`*Z$lbVAdL#0wu!XuzOh zj)kiiSNMZ<^HQJOGINK3J`8V6VM#rxg`vIHEU*WkQY^Z=j5v<;Y%HG4cQCZBL9AZ4 zT^2dXuQ9qH*eP3^k%~cz(kdFH<#s8$)8NrNR|QtH_IuT1-vs?zM+a3p&kI{WiR_Ts z18is`s25sd4$H~q@}Pvou}SdnhybI<Mg~lIzhP<_m@rKQ+h<yp@m6xj@ad>wiJf@7 z)~DdXKnqu9E=bBb0_lwJnn>t2ad%WsN7DbM<`x&ilw}jx2%W7Xu8EtOvhf+e%=nk7 z2h^Ij{(ZdWHc;d@oE!WoTryTyD?Z?p58NpRozq8sW6^ICs|{q?z@XsDvJcXm#f8vS z2rXN~5sQ}Rw4Iij!KUdCX$HJHSqg>?CU^P|8n{;oH}er3k>b<)Xc&mnasPKI!S4GF zvD=4@NUmc5uKEZs4rDcq;cMoJknN*lPRP}2JfnEsemS6Q?fpJgDI78+f8CiL>W52; zqEUcVfyI}arJX|L-4#^6kkxacxIeI>)#4Rqtd|x%L{oS&u*(R%QPQ(I7UQz!!2+oN zg3-_tayh$xA)-gZ;FQm>l!fMCLCA3CB&taPk|YwBvILti`{T&V$4kTs$iSu=<#vue z-B!qw{`YzUlF3VB!ry97!&L6w3HT5rzfQiO(<fnpjC~*Bkz+O9*6@A0@qbcznR}9x zt19oojAGsN<vO(mB<StqHQ=@CDydXXN5L{<Nz3KYr5kkEXM7_|5g=(qXdR-iv;tx+ zg)fO3i&f0vwwYZ1X`uPmDR>gB+W$_-`1ydn9&<n_Ko;3SFTHE-8ur3YC!5Zn?t#Zw z`xhRtuYA18MutoerX;$XspuJlNQN>!<fR0;df3eTxuw$1JujKd9cf$IX6^3l6S3+M z9{ERW<*PO0V4yh>pPT?IML>(V0*0-X?GqE)E`^b;SZ&!IxTmtzobM;2^3Hq7uGMUQ z-vHxC=`r4-jg8|rS`UZiP_?SY+=?2?_YU4Yj>>!Bc6JSd4THWq3z+E0Kgs}sxUODQ z(0bwlsha{k$;?Unw`cxNG2dpzB+>hT)0p35q1-~?h{Mwu*Ob%xAns%~A8BXB@-UYQ zqVtAO>Fz<*x8}mzfV3g-6L>s5u;5`w{uD=t4v$uNdlEV(H<TLyMfdy1e#{5NbyN*N z#bk1|%XpCut`&Tke!ub`!IV*>=`E1^tpPEsMt~QiwNwvjC>ObRo^JY!KeSY2*xAH? zWWewf&Y1>41_}ag$zyMkx}nEM(1*-nJ;5cQ;UToC&EIjXT%^eKtRP%BGizcy+ePC~ za5uaL=}+IUV(t4PBf)dv$(b574(5o2r7m7OYPI!(`WbxtInjF(v<RdU{Vvqb8V6l2 z+;>MH`Pj|~IvJ#K5<WiBfL2kfw<V>bZ|h6?s&_sI8GKu?;)oE~+;=+c6#GU<j@fjd z9aIHtm#fd1kF|1L!qB#`1x+efZzIP&NrZ%h2?$Z>?wKx-J7go_IaRIjbPG(_-h5tT zBDZUp+~W`mK1WpWM(Vbrr_!;9zlTdU?rucN0QxS8zN48Sw`%;|C|0%Go^fNtPQz(X zIYPcz6;?!esf9NX$A{=O!@%;GPlTNn!e}}F0Z$5#ONu#EDz#g)-rQCt-QSn3G`p|B zHtV#e(KtY+5IAoEb<Y5n_|r7S)D5p?*-Z?z#dl9whDLvD{g-wlWO5_k*3HyU(F>s( zh71A^thf767-ED%Zk66%vrcw(=gBfdgart1@tXil{A^^TgJx8!7?&(WF+*8hA15$x zBQ&ub3C2_JY40_x+E#>hd;)Ucxcf4DKKWW>C-N?+x(7xLawj~R=^qqkS}|5bA(a5E z<HKHNj9OB??yO#F(kPhV0p+hdsh7%`Ij_LVK|R|xU?*8fQDM9jgPp2Ye%_6?>zSmI z?(5A9rMR^H*3*-}V$z3$mg2gK15}r6Oyi3S0SNp*0N3#EcF%tR1uR<SAASy0etlvH zykfpO%vxs!b^B~gbE)<M^<4qP?h4JGNIM|BN%ID5$~9<dlZ58mayo~X8E$V;lV^_Q zK0!lGCPA^Uu#mm1#FlN1aXZIZh>Pg)){;acmz+v?Vw^{M>8^(#)b0D=<bH<V$F%&( z|A9Mi)~@n<)Bds^PF)f=qZ^6RU;un=;HN|xy4j8f4<{j%kr55Mb6HmM7mP5CVmi>K zkHxp1LwfN!YBuR}waZdt&B#^ohMegE2BwnGNUz@b-ygh&%HJAl!a%<tmNR8#ISy&Z zw#H`Mx+P2bloB)}xZqIJtwGNuv_;sRhX2haT)E?=Y+pyv9rnuQCinED989#^FUgb( zR9xk8`+6y#Kkt2?p}us&?uZO9UNaTWgO#G56`*6x(2_J%Eei&Hm_)77IuL#={v*RS z$kG@}8(-$Ugw*<Fu~lraU@<G!nl74?g+nx9piCHQrh_m`6C2^FGnSTEbtHrlLwKo6 z<}R*6H@Fs^ZNCwZ@R%(OQ9)Ab%pB~?xwkegG(ay97C`9I>TrsgW!)TF_9~ygaJ10U zWbZooP80&V;os{_r;Fceb>7TG;ZU4@{)GeZ5Tqg?C+7}+i>yu$Xirz;IlUCsVTB+3 zZY#8{UIuLK=4DtAV|g$RA<<!=Kb1I|^W(|S(Kkp5X&7t#e`fQJPx&xO_gE{FFU4E; z+SvRS!{FNqFdE1+Ag?<-lD>%x=LvcL0AWq{<1=6xs<>FDo!Lzp?6IocW|3oUD|bl_ zvaN)&o4UkA%Gb;uft&-m3!woZh{zqVFoJ?-vEvB{!vI&<y2P1nM1i{Rrif=GO9yd% zFW9b?A)9Qu&1kK7SguXhxWdP5TJ)%a5dBha!pJ9x%0)&j5+T>xTvAhW2;Ebs{dc@J zn1j-@)Ofb7PNcaUUU4B(@X<3>(29$+gMJj(OprnMUccf!_X!*6)&OtM5rnF=MryzE zmcoP?@24^ltALaN9Q4b6dOe=xso7{-$0te#TJk}Mc>QgvVpMqw_Hf4iU*^UE_#+Z# zOTKe1bF^U7fmObZV~50v_{Y%x9$uljbd#tqsu&;BIGr3Z8T}D&f!{zz+U+RBRetb1 zZbDm%h86d|3m!;$4%-?yYJtY`XcyHvS~(K5@u)^dbx*WTURBt$GhK$M)xe{xD2kBB zC<N%qvQA8Sim!YXZwVPuK6UME&I84O2fOtfC$^OyOpG56J^QQ12cB;_mJlI#x)XIt zJt!wy!8J1Z2XnS-@FaKmqjBhy+7QtV*S$G`cbpgMYKJFVR2DExkiG!I@jG+DZ!aGn zm{}W26caFAIx&}$UmuZzhywJ8pzoODvS*^erqFtMMor;)P+W(dwpJH#oqz3GMkY_T zmbjw!7_Vcm9&^=y6pVMj^EG+Q+fKUm1SQtCFsP$y@-M_vMv63BRf3-3c0O!!Tz6t% z^I|G7h|SCG%DV(~q8_xu>fOC>e%aTZK}5{qVTF#T*vbbbb8K(?Qy)Aetro1-$-i8# znc5>~*csns`t`+Sxu&`|I?F9>gj{ry&aNi)lrjlD4C5~US}Q5%Xpx=`QB?|d=jR;n zl!&&Q`frl5;F{tH?U1|;^vatwg`<~;)}EGM`El#>O%6hXOoOJnm6y&X!gvq!Y>U5e z?u@U<D&2T@qE1rb$tK&S(8>k-{H4v!kF!UyuD+b89N4%H&g=028=V0wwrR}pJ?{s? znVLjIeAq9YqxlloDi33kp~6@3+0XVpw3?`7P8h7*Buv=7K`Fk9rcSE|qrRTdbKPZQ zHI1gp30DiEyK2Z)<I@Xk&rfOTEt|S=B&j`+c5&%Tx@X&g+^Ll&sL1J)pQPu30I8U4 z?e|9<q=wVPrs?WZa{2UWRBZ_z0KBHUFvH22fb`H~^y~Rtv%!DDqU2B?6k-?44xhP6 zab?c6hU23viLRv1L#I(&7%o*@x=Rb9nCM23Y7JXmE!ve=gCtdp1ZD>-hI285<4AXh z<6QyCfwrex!E(T!u7FUd-EGC+&LaW_Qp3CQnYm^}ITsjK6E%#1GP(zun;$A^y9REw zYxu3G!jAwF99WOQWVxTt3@Iw_0MIc~rf&HtA>gZxNE*HeH%_Uq6{Oj}p(Y&bSJRC^ zH80KBdOC<vHLVc_#=`BYeuv_mKoAQh<h=!O!O2ElI33b5cJfyG5;YM5m5br8PM0gT zKn$K&e>Pq|-y|1Ui<UIBF($nPfajJLX9tzSrU_dSDYTNV(8GrMOZb}qfP)F5uv_f2 zfT0<Ke~LMaP=P~aTcb~mQV<aa0R>D@p_!9Deos!9hz3KQ>a{EbLlh<mx?~D|t5kxP z=xSi|m7}Z(sH?a@HQ-V~xpz(}SU=jj1m_HGaN~Bk?joANVKBaB8I@wX4XZ}o>ybbv z3`&_98G+Ju!h}_l%DY{skHGTqk&fHf)2Yi65Z8_9*zUrUX;o?9iXV%l;NX40ifb{> zDiM8qoED-vRQ>kc&Z7bqFslXI-W37Q_#+Og1yyIH-<@XIj7=v;MLM^B-sfge&ee$h zpS4XzCnbPQk_<$6(PWq@nMP>zln%!<E^Ci`!5M?>V#$DW*O$MQpWeS%ja<085u*s% z)fK{;4rjx#Ys$rC`%Q1@*`5j$C-E;n(tB}__bTjvbdOEDiS!`m|16BpmGfk*HSAjr z?y~<k>bM*A<X(x4ji9-@5nPO=XZNQ2?R51;qQF4~sNIFQ6e~-v73`Su*_v~~qN^3p zw`pk>=|wmPyD3MObgMr2!EAZ@u$ekk0n(Lr=Qw$(O5KLutmwARiBC4~VE7IE?<e*J zzJOrm*$8FDT}j5R5HC@t!jv<U`WTw`1^XDyl9N(!x2V|8u(o^!1}HDBvMR<YnH%vd zAhL|;p8@Kii(o><v6R<<KrJLM<dKQgrkHNTUOfrXIbRtAM#TL~&-@QS7rNYXFL<YC zp%VSOE-21CnxJsy49@aUKxe-g(_5;(Kfo~o%R_?o_hF5L&$S#|1(}^kir*{@nY$=M z!qJ0|-1knkDI>?psr{(0L`<%#UJV<Ssj7$b$lspvysHvE-@jBUwc>6QfNA2OvT?Ci ze@|Xo+b3;yj8lDMUC8<z-YRQ(&JVkaH&|`a+goD^hH!I-RASP(l{hMr2KkK#6CTVP zNH-SW9bFvQR>ctI*;w}&S6(15*X9TgBw<3)uL5kBP&JBQ_4VftnQ@Q-MgqRTMv`=U z7Q?Z@|AK7(y(hr7pD~rpNbDL$j>}O+3d=3W-2yQ^TX@i+qB~sNIk0^_1AtMY&56q0 z*X?cGSjR`3rXqO!(SM>L)Bc@&{<=qYKQhI_<~!<VCHUW(_##Q!RoatLb+$FgnA3#^ z4#l{Zv`^To|Kk|ny~q=;aS$&7ztg_ctZ^?wA+Coh0iXs}IT5A~*iDuk<Cj)M^^JHT zU<c`j{(|*5#%;|p$tgxBdmz&Au-}+|yiuXTTT|P4&?#$Nb6FaVK*+Z@nKslsf25ip z6h!^@Qo{0MN<NZAgE&vBRBMj#j1VRfGJtp2rKK}031TamPmfoGHVwjwzZ)m4)h99) z-7riZ5aGB)nSLg;9~<5}0VY)(g7?%J&0(jxit;Say&My{amQMn*LsA~?i=TF;M_K~ zBvb<k(5zO8n-jM2`h`k+-z<%UEV5@nQk-vHC^)($EyrZ2glmT3&kJ}o86ari(V$;& z3-<^+E2bA+kIWqs7GqSN%C>QAiI@vm=kNbJN4Zu299AmC-(MALVKVU29IUDqo8nyY z%T^4dMLNQzzJ&nCPj7+kk1Ovl+O#IRy2IFmnW*1Ha)ZT;ZNI<2OaU3;!jt1Lvvwn8 zd<8fHV8Iebo1Ung4p|i>2VtOo+^P_KCEt1?H58DztGe^f_4oVBi$U@&q#6XE+Hdt* zDubS#w>V9*W1pNS9jpi$Df#|{kLDo1QQ~^;l>h11awL9oL^+XQ(r47x#;*>E$(^u~ zl)wnlgA`58fKOILq!6ZNHkdzx=nB_{sS@1!zKPmeP2GNDw$ECg=nrV;XvjtX?-8OW z`te&^+vzJIsS<L#@DXHAPe{r6SLUJfZBRPCbdny_#KH24-vX$6a`fECM{sb&a+A^O z3L!(;#2_d|FS?YbkLdv{M8C<zJ+p&#b<^mcX>dE-n;tVGSJQQBV=q{~UrOZlBlz^B z89KHIrs@duGq>~QiRi{ZDX0J>`tIqzC5TWHsVA^hm1|Kr3d0g~=WU}LFHt1Ktc1-1 z=p*C3TUryXD-WgFCRC11{7c}^z6^EuI4R53VoS3SjY+R5G#WPaEt6`Xy~vDw_#I!W zRGFP5=?Ug~_W|3CX8P0fh9rTN8Tv1BU2&ma#&?RD=yf#1=EN5*ZI3Sfd>VXx7Sl^X zk!xP*>+6F#bI<h)D=JN@zc7|tEDh&|*mnAs<3ZMrIXS!q0a3R0YJw!M7BoMGY73z5 zJ|RetH1DIe?JK5Zz5ghi6sj~_oI;2jL%~b}Qi_5qnZ^v=aC|rM+V}|PB`(J0FL%#r z)YpBds0qrN2vj5Zo*$KRKG)P50j{_YTQ)=H>2c|g31Aj0kKXqbgcb+U4T4)ie-Q8? zC3Gre$si)<BNM|!#m~j}gWpfm4RX`Sngys?pG!3lQ~QXW3|313v@=AP+yz2G@?M<` z4}<B@Vh}BQV<*yKH+4ze5TBEqaN*!wVBI;WUlX_7o+#TDq&}SzlLPWjq=_fQ>M<wd zap7I(echuif8&$x*uNc`Qp*LyLQ+VfYR!+LiE7iy0Yg=Ogh)Kj37Cvu+wj_k_HQ_p z>4-P0kq?_$Krn(OtI^qdb&d`|X>xbh6n|K%*nZ)XdB<j9ED$`xT5aMp>9HGq6KkNN zO)Y7HxK~0sC=RhG;3ypqO@JXJ$+OxghfmQh=PU}PH@hG(Whk9s45S?j!@4fA+t`H{ z&*GBjWNLZb*TMp~VG5q`_rhvXhhhGK%@<faATGna?2!4)y1#wxyRs?-U)fv4H9Qyi z+*6lBIoE#O0pq|)l-#?-n(haawElE;JL(x!6DUOhp>S6wa~)sdkky|up(pptu4R0T zWm}@+m0sp`{#3cu?$S2>(mm|QoP9(ph(+kw1*mU3J2pp9Wc{adYjq8RW`_P`p8I9C zs6>8gb833+XpMMB%&GNy$(ZBcScB4gV2;Cn^1Y27F^8@q=JxR8wH_aPncCDr|7&r% zmEFRNzF=x+c6Pw_M$N5;vV&U+Dks->)2!z2C%`I<@V0o7c+;uDRr^0cf0@Q3cU>*F zT~02!^}y1xN}xRGG#>Kf?LNyM%BM*^oFzbyhpP29<lxi{+W)-j{nFzh$!w`L^6nbJ zjNAL#oiQnbZ8X%8Q!srS<1WsjQ|G+@&C2f#3`xzkvEVkY2X(Xm{-Z6_2-h(IXb6yZ zO=xf_f>p1EW$SLvYl*HgBfl`8YHJ>iaV2u!>8aFZog2G$o!E{9*Yma)XiEQn82NtN z@D-%nPfE&c9G-sPK)*e}Ih$zNHTE6{*OMZ2D-~G(Q*jY{_+ItgTE0YA1j@9Att>2? zNY#V<-q|#*8Y{O!N~V%RfD3P_zHDCDP^)6-baezX`?o>HQ1ww`t?4}8Ll)WTpjmO& zvrzegUDCfJA$;d!9+%DTO^5V4yCiV#3i=DLJeume+2r;crv*lNTgA00pSi~vjT-32 z%Eni#E_nmKAAMVZ&@R}uy8Ws(%3XLZjclt~#yWizM=JNz>JL(;Upk;`4z|~VIXF%z zF2fI4q(kD{neM)9R8GUl^Jmt{WY_TJa}{J|lY^<P#;NlT2Ip^H4#c+2uRER#QO923 z#|^N%H%BvPY|W5xnhnXr0!?_ZaaZZgW0Qi*@f_3?Z-7c?Zg6=If_@?`4S~x~utF>t zvr+X+O}8$~g|>7h)eF&4;xJU5+T#m~GJ8ZCdJ1|asSM3fGN;<_?YZ2~X+c4pvuf(s zZK7{q3n4yKCQ%d7xhbGb3Nj@7!a8KmBo&lE+w!eilDexWJt7yu%v7F3tq1)LM#Tal z$oW41&to-A!4i9@DuB!;Y(GEyF6ywQBvT(8gW!!+OKNsk9BF<uWV=Yh;-#XscX~ws zwD1@rFS|o$0Ws#vse@dDRUqm^4p9_<p*Qws9c(?c^n>5$2tDpoES-!6mb+oERkt{I zQqMfY)XD}p{%k*Fp-vV>USu5oom}IRhRl60-M;N?-KO#G=!X)=xLQ$wjl#qrW%txl zQb%D0o82Z$^BNm`$<ew9H+YeHTs;^_f$)lAt)4}-3~$NMZZhn<2x=dT-i7hBuVpS* z-r=QKVEL^Pb}(DX9+P<WW!fXGBW)=%@?t$x{A@3~T~mF<1T|7$miqQ-Cxps*ygwp! z9hH-lllab~(P;Ev-m#icQ8cC1q81!c$^B9B;j+{V$z`e3EGNo|M`qpDufmk<?UW_0 z;g(3fRzwJ=oOea)w%-Gj@JEZ>1ZV}1`=?^%r@&V-a~iL2{07*os|ET@xw>4m>_?ta zYZ#Q9oOf6I&*s)FOlt^}4siu*PPHpJk!Lgv#2<-H{y#(()vPwv=T#M~q&3^k&v6wA zXo~T1n~|$SNav=#2UG%~n5bQoJJ5-8xJdfe^SQj@PI&s2yPIrdIuG>f$_4W;pUp`B zsPeO^32*UwgOuj>@MT-So0<#k_EIW^hm0!DUDDBhGo`w>bRAQ2=I??*)498n|D4J% zh@=w*AbE3>8k6YF_18T>+uOBM2Bw;XXo=Y^Mr0Izt7=25w11#u{-Dhr9d?IL_cjLk z*CbqLtat}1Jfp6=bdWNNBEyb#leV6!9$4Ie{}N>nPRWNJ0DTlIMCpwC%ZqbPG{9~< zmW;^f&(Y@4V2yA+YWs7SOUru}IpLpfIgD7_1}i3C&uvgUYH~g1%i52x8Zd64k>f`4 zazte>b!F~(N29_DjkMDT5p#!-T8^YT4OtAWS;4B6X0Nc8#InyHcHH~8Ywt`GXHtiA z@T_G91Tk2nTEUodcn6*JAK+*2{Z!#KMZWVNK$NQ|7%$ikWuN93qgCb>nL%qVX+ovB z#y2~U1^w7(zw~1F0em&=&LUwb{-L&eae5{tdhkzVv~;n;kFA#f`BAd94sL-%xh}l4 z(YEu<7%WtKJz+yZ_p8hHriKFF?HqzJ8+jEi$r5~Iy1W*n4m|6ZhN>JKC$C+r;EETo z)ih2p*JEkIdh)#-WP{nmilMqWq`UUg7?EIh_3_Kxfj!>$MTLuUizUdYG2cBX!mwIW z&qb+Mb0&XAd=ZCqBXj5Un#6#~HY%g<_M*bNdzmmbocrfrwT5s*qxU*>+v^^zXuM9> zb;W3VP|J4pjFh6!yvSgVWA}pG5`JAE@kO)w@4Ulbb?xr5H#=Z6$t%&uC*%vX4omep zn~Iq-OA3RA-s?dDK~*NDoSqW2+PugAH>li-I#%RYYp$Jq&g*yBjv6QwOv}4-IU~I) z9Arr4G={1^^|w&~RrLL)=I(<9pha$hxrtmGCttbP<W5ElbZ6M)d(*j@u_-!34<^t3 zl~?Gy|DPN?`Nz1d_q)*%6fA6sZ*w1C=hrbF^|Jcspap0~z4h~)Ni7ri-oI(HF3AUu z-4IF?*4%5~{|^FGP64oLvtO92T<q`JJ43$FFDcIN_x?7HU8%>u`VTmJTUUdEt5iB5 zkxD5DX8$_j7VAG%g*6|w6s6MxYIv$J)v}(Goezx-wx&Lo9DPw2d%wL084+`;t|TYg zGt_0Tg?wGDxu@%yvK&YM(rNLc>z7X#<OfF;R+4!-j1T$rjIYYQmn`EIlnEHs`!5WS z{d`P`YVV1!D@TCsu};n8$y@Jym(TA!s-i+f^6Fg@`_3QmgAd<Ou%-^jTGi<8)6uwP zel1=u=B*8P&5xBm#lYEwaU!JXt=|HkqVLTQuqNR-qm+J!-m@jQKYC|4Kj<u-PT%J9 zT@R-sQsti3qBHE5cr!ECzEbzCzVuPq(Qs2eFn%yyHmmz)fh21%Ud3!Cx4H1*-!ZcS zUI=mRWn=<fC(8(Ox%J;M&38Lar9O^M&YzbE9Kp{x`1!8~h99U64qMY;?-~k&8^<P` zyX))s`H&XPKtXwsy}>J<zB+iJYTMG1g1FXE+tfZsuqs^rt3)HL=#~%40!mf|(=oK6 znY@DCD}XMTM=y%r+9|NUAO4&rU$7!%{|b9q_wv{)Ka;k$%?~v9m~4Vf=Pt`Q%T=a8 zxU$N6X8R}0fo9RodC$DdDLgsStauR99*AL_!q@#%cF<QlVvmL9COcRvd&jeGgZ8Uw z9Ik2Z6Gi1mhx5}iMe4q6Bt?62PnIIaCvg(q@b%Osbal{PxP?li*}4<R?KwkUq>qyj zzr7`9>3I>LI%GNd`T9d?+Jfng96gMS`UBMf%27{JBW$yk`OQA98#@@(`q9G9qUeak zTv8yYEh;d4@~{A>TGBb}9&9RfD<}(^Zdv{`Uwhf2122VhBwasz^G4jKJ^6_1wx1#| zR;MdT?e_+ZoX7Vv`s}14o@J$K3>)rl192-dUmF&-pPm#%O0=sm%sXlUxWf7(pMTjf zP||%rwtFJCoV)b$>M^rx5}$)!1I7~OSiX=Y`#3c6;HJrX2NE5uLyxQN-hI^3wUF&$ z(E57ux6v@cl<EBN;?h<3v_Wy3?PonWFu4&@SnvHO-uT-k1gzC6;n#_(X)r{Nxc_K5 zsW$G2jPGEfdF1MspoYVJJDM1lNn5V!I=mr-S|Koe*$A_8>!Xk(LdNFksGnL;)9RZ` z4YUa~CH-$4Ga~~OA~9l)j=Hj_vd$mDDI)j2-F5OisPxmDhOWmJY3F?D%^aAWN%);t z2kDWi_Umo^89+as-^%d|Zw*tUaIAV@`-u;6sx0|YFcS>veECqbJGgu8S>AvfJ@;9% z^`G+eOM`j;+HbNYWkE>rzDm3qKVL@D0au30BD-4#y}a41%Pwmq&0$Y+d~(H2Z@=|> z;!M#4#98IZRM38=Y+0FANr$Ngllyq@A}_W)^9k2$QBF@({>WTY|9|a$Vx;uTd|fj< z+tmv?@J$<8AzesjWF(o5R{8r|KROz=HNYOO)pnw@w*LClnH0PS+SYdCHzC_aPa#v3 z2{(21MSv#lkEKKH8Vc`h9MMW)@|};BWjU$}y-%l(wkaptnB!s^3+?{MQ-2Zy--U$I z2cBbEE1sWh4BOL8b6T~W{qAlBuMu+0geA@zu4M{!t(HG1YKJ{{n9GvTJzLs}v0CRL znG5@@b6i4^(b^xXB`3&?%#=tvR_WFuM`h&dMb#QGy-@BrV)wL!iJ;ptCnj6Rzq#_9 zdQJ5K8{QxEOc9-M<(i>o<loAg4=HCg1ix(};Te6uBKCh5#0+e^dERLB1O5H0s~`b3 z%c>QXf7>sm@_j<|ka>)QX?z1-N1m)G1=QK)W+W=^Guaxm7r2!fWbMn}dse^vF$@{( z_bGZuP(L_^yYlIU<u9}UfZ)5`6=<X|KP4yV!PWGOvY;l4i{|#`Z{AIJv~<M!v4Xm* z*PS1RAgV<Buw7<QECK+jbEK+@Ea!AZ9zS)k^5~2@cV4sdM5ok^&LaT<dQu7_u>J<E z)&13f9DWj3f+%C8*T7U_ZT-^!34JhE^#xzm#&S6am#y^GE&xu^NMm@5`k>JL9X=Pk zv`$NPXIeIiFqB9h_oWlD`fge6={t;CsgHGfCk`8De^>1yH{r{2>&RqvecH)rgIu?o z@tAC5hpp`N4H}6G?i8zfy&e<GltoXp^$p!aH)~MMGkhm~I>h-Q1>KM24K0;^jW<WE zAm!kr&t8svKlUOHO^-M6D(RlGGnILi8^<fs(L1>LM&F%00B6I&Mz@`~HKq(KG}B^J zXZSAiFVbwdpPH3HmsdAW{QSkj>yf=nbx<8IAO|K%ZUHV{YnvtF%w{oZbPU+U2W8#F z4U}TUR4Q-sw?zzYaox$!6Nf$}Eedp*56b<a3PZ&e&~y?Io&G+$g3k&8W$ad%n+{RK zyH%RDn?Ba!Ft@{;XrfR&#lI*MD+|YOuYnl}tiZO;)VPSfy>I>?{MWbqbbfvF3D&n* zi;m^wK}C)psZOt}MU&m1pW`hMtBBI$>-DL!I~;IKKh#^dJ-ybuaz~Djd>8zRE*rVS zVP@6)<=qHU(L&{gD-11cJ0CIsE2vrx!|x%t?i^2vpliKu%QN!`tiiI~Yu0|9=zU?K z`0JkFfWgX9g@%8JA(yI2o`1h19CbSf2}AjPJ*w)`4^F_47wcafxOOZwl^!#Xn6)71 zcGRvbpJ_F0vX(*@&61D{I{9x>M6XPL8}!PQj8OZ@+hCh%{sxR8>&UC<+1syXL+-5) zWmn=j2QA|#Z;s+3j)SY9Fmc^}nzEX=vg;AvYe8GN!-8T-3eFPlqEazHfy4ZEwgfq? zpQj2TqJtkNw(aT7I^2cTSD<k{HT*&ovHMW?uZRe*0hhmw&#x*y#`eebgf!Y=M4m2t zGBfuvB9A};uh00P6&=vpQbb+K&3JGb7X!viV~FFqC*;A9!ntfP78x`0k8;RF$|5t+ zki^}5R`|%Z?V|p3`v4Bho)*lK%s`*ATRK7S99~7`yxlVouHDHw*jAYJ-BQ2M6LF>0 z$Q;UCiE)Yi5Iu~&#<2s%jDJd-RR&9jGZj^hLw|hG{Pf#>G)cz#`RCeh1=={{%GzH= z7JqyHyiiQ$F|38i5X6?wrzi)g|9B-jibY-~F=C992h;kpX2T6WP&8)Q(mgwlerVIv zW37t+V%(N!dx!=Gy3PSX9Q^v~tGbIf)27-<J-$t@^n8|h=5ce|VhvIgN)H-aD7V3( zg4c{YFLpei(s)P#;xokW`*ljUmwsE*?@^ls*PM&zf5_?C`rkrjS0qopy?Mz`FQCH) z(yk2qg>z6j@XnQvl^o|W{Jz$E|9-?d9Q##o7}Jaz>!|Hcy}D=m&hk9tKj2#MMXL)n zca_`PpcSWcVr9A-TGOiu7fpA6`Ke`EV!&8^Pg*HweKpc7S9^?YiTb*5;q$xO>XS<E zbhd@}Pl(I-4`5HITo#P`=fu}_#yR9_b=WcYto8{Pk<9v&AO8W#Kb9{J>fF<e*u{E; z0NJ%z-nWK-7QdA%y<|SB^uW}fU<Ut=2o_w=9@}-d^Y6`sT04Xep|f=Yq=&nh@5$cc zJ*pDqP5pC^>vpZOTBi5i@S-}ZA@@oWjrOkhg9IKXEJ=E*a;~2c`E#>b{7<$;rlMti zCb<=laie}dTKS1|LpR_Yzfa-%LOE*jRl&B$r-!wi5m>cftjx+a^M%XAEr`=0a(@x| zy2+jDV?ia|I)pK8OR=%cH`=+hH~Jy(oZjh4sq|J?c^702N^^aR?=*LJrfqk>ZeN8C zzL7go(h>No7?m{(BB^>m=oCt(&Rbs%NG_3{>VlB^*Uil>N+qgGb#$^?T<4DEZQ`r! z->Z!r9)^MdqDh@QBiCHR85P(akyvydGFH1x@=lD$FsCWXD|KG@qw4U8&Vwu)b6{|w z75B5omEKl%!2Zddoc)ozqzH9O+fa$JHqX7xI3l2MBe~-Kb_n`sdLV|TF!ycoJg&_8 zKLBa<?DSd~-{IVsvj@@4fP&yPG5#;Z%VD$cs-`_Efm)<o5DnbBC-z6>B|=0UkFZ^) zuKfhwG2`1OH^U*r6<#s_wvvZ={Y%f!=IaYC^qsBFt<6w{VflQp>2j557<%2P9mNJ- z0Nr3XQ@`!a=O&L!8m`owg$BtXLsxkVuVOsL{!+*uYMuYb#21>!2G0ozr!sv<@6qv^ zUjY%&ZvQL%S^K9KbTct!8R|Js5eysbtGks`1%c_Zdu{~iE2st-%LTOrUrc2O*Wd4$ zY4WQz62e4(NQLLPY+mlKfl?oVC7#=Z0>8&255}Wd$oOBzA*<!MKC=tg=uQU(t=Q|f z>9N}LC(SQb?~HqyJxqVbT!k9Cc-*|Dc^eCzQo}&i9_z3cpaS|TJYfG(TRTJO7WT!p zOWP~^4t|(?GfDCr2A6%c<I0jx91pa??EoBYS;)Wib^U@?_Sa3dW0SWgO%=;wKUZHd ztUuYS`)Am;gCPuR6RxAIgujcg&&#=wlazYa!{!q&-e6Q_|2BSQq1I9JZ(j9s%dYqi zk>NheRhpJ+bhl8@a!&u;!JW!he$$9{jt^W*Z~v~2ybmw@j}nrUU1PPwLOky$a7L$* zfzkClPMAqzcMy_P&CNk}<fXyhf_IHxE1DE?hfu6@nUj{Qd7~S?6J5$f2$J(&9BkE) zPo1L0e<h;JtvBr`i}<OxQ=yYPG<!%zn0ebpBdv%xA;CgH6GyF(=z(^&T%COaiB#j5 zuKd*!`C*_VS9B{mI>x@~$NLS$T>_DC^T8kT$6ekITYUdfJqRP1)D7hpt7U{87hK-m z`!-s^_Cb5~(#@1SHQj0V(=lgaoM*4UnVn7gq!1_h?|_XtVJhbkaw8BZKe_e#SW}-+ zHZ{Is^e&H@!d_fKv;>s@s0@y3^eNlQmPW>LB!xO|`Qy`Ro2K4oL-ik{8b^?SERC2t z8%SePnMhq}fm_<RNb($^z244ua0HR_wuiFvx5b$Rp3%)TzkXm&yB<JjF7T9A6lQA) zVkgrRmHzbxPj2cGhHv-88jE)NY1}%dQarahWz<F9B42mhZbt>@99`5hnfsTeO5j&L zB@2I6mg=-N*#^CRI_bPeZ6z?F+h^$x`_W0*=b=aB91efo8JAsNn{=RHbbkZBQ6~9( zP(U*E{!%--pDB0IJW2M)JZj)}<m`Ch(s*%a8>~p75sa^WdEGe5>50HtqB~>Q4yM!A zF~0qFMPi+BK|emQ{P5+cL2|r+Cg>1SM%2v<-hHM1Yj)K^TnJt7dE@LZ+h0JjYJ2Jr zHJRa}Ivl)=q`i&(@qR2`4!urMj=*naB36bw2-##cxuT&TNveejJ-lKg`)lPN53I(b z8e*q%-rkB=o2SKO)cZe3PTjzil<t?*HJWjz-n1siui4hSHLCa_QC}`6F^{i3rSjd( zYRR6{(D)g9Lj=D4WJ2W%(!o=!+tE_G3+7*VYEmfNcGlUQu(1?dc+rDAPgLrX3hTn; z=9P?Ce2(p&a4;P8u(eOV#|#W(|DY(d@!_qvrH73dhfJ$Jc3|6zULUdqHTpKDA3zTb zE-`GwsUaDw1d1SfDQFEpHmJS@xA0Q>7O`gB!6F}b`iO$kH3mZ9l({=&TmsX2f}4C} zJU%XLeD&mR5C@Tye$U-^3$IQ28yAfgB%5AeEJE$XZ;%R=c|HG2U88^K_0o{zsos_v zEfe)dAjw>M74ZB!58Ovqh@2v6!j_ZcAh|T3iP+F$No7gzASbFt=H%Mi+gJKdSSao~ zw^<Jk{1v<6l?9weFcC;G*KKTCN%n|(#te-X!dWWxgGkbeJ`De<3rCHbOai5U1sK~w z$xndecCfxpM*s$^Hrj}_3g=w=4rOta=j}0P=NUmg5!6x2fdRBi))Ng-?J|!>lKJPh z)g~RIK553magMTr&zbz!a+@pNFTEjJ(g`s>;`s6i?@2H;iheP*-Nj22hA?ruo%Yro zyTT((gL1gp_PTi#%yig3rCHKX(+FCuHeucF8WIo@jTM(BgF`{nM9SWuzMmciC`R_` z=?qb@{;}4Mh*s5tL+@r?m-~@W8y~IPhMpKs`AOg_Jb8Cuz~o}T>T{DvSpO#!<KWez zMpD;L{;X+S{`jlU<0Me!CCR*dqir(x4kKiEZx4NhAE+-4w#+AUu}1SlJ$4d_+w<DZ zFr)(Li*$j~ir2{w`_$h|GC=_u7M+@cRV|S?I1)Gjo2yl+px1mcx3O)z8tO`oBglm7 zs{OUg0y;H~5N?1hN(vV1&(akCprG4-!LHmU92m}v3q}SD3klk~fpyf@NJa#4OusdI z%Q&(Jm{kY_o1SVeW9C99%5)Kr7|&&G#D=8oetSvDXjVE(3#7oMq*y4M#Gpfiw$Ut> z)Q6hu>5~F=QV&-#|KQ{9jt>G=c*HI}Satc-1?{9z)yNezs4v|pttHH0MRBxh1iGKj z6S8(f_ke<zqd{?4C|z4!g4GHo$?XIe1I2ejKkMI9YT}_8H*(TPIBI(1aZ&)Nqo0&0 zJ8-QoLgB+sAynf(;HcASnZis@xHK<G)#Y1(<O6*xn$nF{0uU(|a7Vw+&>YZKu9&qg z1mJ?iV|@$z=Mq4rhfU3P`oDDnIvK|}U*>RRFx~FeHS!~v52_$Ck{ej!<fTGvwJ-@; z1HB%BhzURvg%4F&?u~o-H4)-xT9gL6#ii>9^~Bvi^{lgI_fl*0(qDRLlUKGttm)UI z_jc*ko4UbI2!tgISW;^wDhr&m(DcSBHYex=D|wi@T}%Ize=XBp!6(u|oYzpWojz)e z%BK#f-EsD4Y)a)0ff3`tDG5;IZpvRf>GgBCS$*7{l!F!5mwvYND2U1n<M&q-QU9%9 z<i~;9xgN=pDo<t*BQr?Qa(u4s(o!?*k@2I5z2|%8++u^BQU^j#(k>aSPEzSo5(}8i zlojQ`*n6G^bJG>5zOQY{w(}C~2uJgP0`hB5cv*`P-PF6gD_*n#Y9H;?qm0^!me9GM zOi&g*q7ptw6wuT8h!fdtT`8%s=~2pe>@6q9+{~alJ{?RYZJ&&bnfo!I3={7##y$hP zeYT*DKg4f2%oZfJjpU{;vnT1sjtrU5J)afam=3?CQ;wtZH*$7p$yehj!1C5ycAa}K z219w(tWIY5<z^f)x$!=AsGm!(5f=9JWSB#90A0OkO8)Mx7ByW6^lRhB*MlX#`GE^B zFk>(#l`~^01sS1MmG{jFat2mQCH^$RqSdp<wx35xP$Nl3;+jHr2@Q1;@`$Qw?!+1I zihT1HSJD*z#FjVYkHg!$H{W*IK(shm;g6>}+7!hUCOi|p%<;D(J3F^p4(de)3;3hY zj!5m-r0)k;@qiin;1=9qxz*SKB|Uk#X>6=FUF2gh?fpx^CpITT*XhVj961Hj4ns92 zSphFDFLc@JH2or2sktBJsjqBI7po;0{S8-;)4Q~?As1TGbtZ~_qKDCmilfMRk=<-y zNca(7kw*<M?xohx;uOM9y><v`fJl<50(w>QD}+YmDf&ys6FR4ViM8WX=7DtGZ^|QM zJ)WCRK6!60p&F_7J)}YAkePa1sDVvT9EQ7)_ipm8EccigyL~rPV!`tIdomaIhES;E z>pHK@&*;L6wO9)><DrP|JFdl-zFI{`N5`ZCnFAr}CX3yG!WDyYb57Y~`7SeXQY0*v z<G~PJF;{Fe1#J`Is*6N<(bIL?VvP`Cu`$IUl}6&H_NXmW%|urDo_>7Me*n`?BB)L^ zz})sTrXT!-4^kB6LMKz;Dlp+{QQF(kgl<VX1-#(w@}cV%Hbl1?aAIA0?m$J4pV)}s z#OeuyNW*@rdzpT4KC4yb#V9VktYRhd!g6|K5<;E}d>ZuhVN0x?u&xm160oWon{hxy z|0p%(BS+35&bMNV@(%25YE`)Y+cbSXb74~HSS=VhpbZ54f<Am$vtZPX^vL%!^>G(E zM0oLSeLtl<O~i_#airdVjOA;Pv#2jb_+f`@#AynGoHmwh{&9C*e9s@JtAE0(5d!`N z$mIsJwZzfd?&7II3aU8cA;8PYzN+~3&}jn$8hkivBv!_dJjG0jad3&>zJP5!L;({P zxKyIt5F-QNkM%e({UAfR<=~mOmVjfJb10Fp5O&1$S|MXG;-dRWEoTjKPBHe!6BWJ4 zB?y5#_~cHC3lr(JLFN+?+7ep<VW64<up{D<_qKHzvBhBpuspNZan8|~LfTdeesx#8 z^JyaW8N_~Me$b0rU@_Ok(ItTB$ss9Q5KLvT#<B7rb#nrYQB{AZd@%Sn{gYGd&*9tP zVA?WBIBbLsh7JF{*_}n_aqw6*TdNR*gFICmFtI~4f4<Z51m|?>ciY})b~T3-Mo4k+ zKwR_=02j!}H6g7>rjF6m`#JhbK*d!0q9`JQ`*pxzs+HH&1q>3b+!4r!wML>u%>UAw zVDmouD;IB6Z9q2|#do|X-rrc;uku<7>_v)b^kQ7S5oo$xD!kTmYTDbo^ClyTF-4TY z9hnHp%|zAAS={kIilNcG`j?=Mg}9PAq6tZ}_~oC8Qr}>bi}BTxp)9FNi?oOAxh8ZD z0S#8|_|ncN(G(>ZLH~6#i5BBjj5C|3H@`BLi||No{F<n-%hD|z9CAy|G5kB&$BW6_ z-iIUMFhApvwS4s>b~PT&KY7K)y&$%Ma2)i7`LB9IieJt8;lsAmzqN0EHv*zKbK^Z2 z=H7Ob*p1S#LFC>(U1RqiXtmKH3(YYWC)VDchjpl(li04Be*#0BxG#$$?ZUf^uwp6v z`yL5#SB>v?Rj`>j3<T_!HbTY^eS7jVWEg^si}AB8{8-v4w^2H6Duf_p=BsydoY7Lu zmZ;Bd1*oiU`=O<LWR?^>+QN@=i**@|Xm4_3dYy#mM(Dp9sqa3W>~f<n^o;7&el%n0 zh>b*U{Ua+{%ylc3`FU445-N9^Pn4zqos*?vno~8OE*=Ua=)%;lPg(oO<<8#~*j}sa zAwO1+<SG6kPY4^=awT($-x|fAt8K8u3b^3As~DjA8sX_DNcOMTkdfo;>kz;sQz$}h z7(RLttUYLJU6w*V=mRPZVS*$GQZbY(ERy&Sh^3$7RiI!0ukbqQbtuAbj=b&(PyY}2 z5V$Edhv9V6u^Zg|0FToAShgqHR@9;u!}R0ekDP=*51Qc)u?X2m1}<MYyIIEWGW`&Z zE#4*D7*wTZ9U>skyfy3Uu`##pv%4i7Gm-MJW|B;!a=6Lf2pN4FTLh2F=bsl}B|rXU zTVAYYbqWT>8^eWvD7Zv<oOlh*2^W_dOtdQapiY3GMe`wzjuhMf-ALL*3t6te?OYGk z<lX2HJ+KD00sW=rbpDTpAw4~#Y16Di$M_`$c7%haOgSX!LP2giYG928JAl~n<n|El zo!$`#RfWZz^?AnJmN#zXU0u{?JqX9Y@MIQ(#>8x^75jgr$mgkqIVN7qi`a!<98DZW zVzu+gYc-}xF#fv35!pI*uu{IhUClpFrM;5I%fd7H#9bLOU#bx<STUibV5UiOA~`+< zTbj9N8oh%g6Ws&`IG_5`ghWD8XXZis$fsAKQtCo9R4r9ltodc>-K7Pm=&_QLfEv+L zn2}ussT!3&-dXjiF%n$1gM6ewn!d$I$9OPE7a<zdF>|Oy^uuB<cQ8j*v-9T;_8{c? z(;?H*^s)~}<N^n_bw5Od9`7@*af)QF>Q<vM8TVwG-30SrlDan#SOZE)*Id1Fc>Rn! zL_2*^R+r73o^%uVH3GGyP-?wX+%V`9o8c!1Y!2<sFoF)ObgvXWZ0AnNF1`E7<0soU z@!Psj4<Q6Z=~qd`pJhrAh)K1XvEJO8k{u1dC(~%WoZQ|l3S@}V&<q4QddV|a+4lUc zBal3#uUxJkavYS*naF?tPG?O}g%as<@+>L`^&|UpIHyDLKfoC9W-I)WVqcLnfND%Q zNGbW0+C2j1AF1_bFC!<BPyr1TJ|<|w7&aq;xR`^KgK5DJ=vjPzi_K8w5|0IIyyK4p zA%^a1r7Q`^UHc`~{9iDT7uAs_woryt_7BqNIa_p0vg=gR8T<ZsCoD~gPyk<VQKDJ` z$Q0xrO;ITSvQ4%{IGkhime@1vy?48=4wKmciF!&;^ENVQHd3Jw&>BWW_gtOJP>n7f zzWK&Xc_Ri<B%ZKJlra$cMK{XWw@KSfp~2kH;Fenw;qE)^X^HLA%m}hgGun5k>AJhc zW?ypnXv{^Z-zZ0wZ!UG-OEUTghIx0o;RxjFykAWGyRa|nXkg9+m0v8{cB%{6;?*b_ ztzC)qHv;=QgrktP<HGOL<Gv#_&^0sRcznktIaEC^Sgb91>8rEFm&ZfhwqS!|6@S~l z&QC#7C>eoDhj<)VvzoZ>4;GUbKd4BU*DD3MsEwi;8HJuhiQx?%h9m?m&rKZs6031h zH86S10B?&GbIcsr{9xId7rOrzT%4ZtawF5@m!^|fIz65MmPy&!vGp9K9|2J6iGb&0 z!3rOu!^C9`3oCtZd_1}oZyl`dwkClQLKT}9*LGeW5S}**xn@qThN>Uoe+fCB=!dD+ zROY+IJOU{NiL!}0Gt`-De`a&7lFg?k-Sx&72R~$$<uEVY#05B^^tDF~&n7%i&G2f2 zsWkr4<77{Pp*3HgO;%R)eaL}T5WW>&vL@?by8>;CU$-3ZFm*QJ87Z-n8!ojW)MY-y zuWU#Sdm_n0Ot6K%;o77T?~cGl$_Zx)%}cN5Ce9?E^7K`e+PSt7ZJJ@OVpmZ9*!gnE zBx8B|tV70wiu)%Qz5KhiXSm3?NUy=#p})g>Jj>jfBq;Vv#12k6$!W6=T*WS}y^3`v zzMJZHQm2nZTujYqdI?9{ze)5q_*{QZBZBlFQ0^8T<PlPpOs3J`aEl0`n&Fqrp{rf` z(Hj@fpQ#W(d`-ba{v5Hoi2cp&S&lx1uRJ)Xa@|{DyWgrc?17z19Z6~Qj#h(jrs~x- z62C9z&z81CP37^p(E-jCp;lc!^;M$jr2zPT!UN&f5#L%FxZ*1(H9yXV)AE@@^IdaB zUEzcH`Y(<_acnsy)q3)_QrSS9VJn1mZ#LStk^A<Pi;wTW7Q|@IpSsA@UClmh0VQ(# z+VeljuMJf~RSQ;yEz;7}$E8lx?4});R0H3xlXL^Rex$;3a>^twkv$Bsx9_UixJ-!{ zuyR$fqI=_cI(y7`Jec2aI=WtP)6<tF0r2Q#{z~Ea?zc6_Y0zdEWSRe$JSV5PKY8bF zOAn{`{=XnYphcFNxHMVjOQKINn5Jh+=EQhNce8lFmaWy!Upv)~OTzUcd!R(uDE6Gt z1Zwp>B*6wU8EbDdkz`HXi15f-s=8Uw`m?+G#}Nn(vDF*G!&OpS3_pW_uG}ZNt7Hem z11f+v16<a|(e`QrzQ8WbT9Eh`#8~@19g9`$&AXcVu(&9k-_v6TlUDe$1){sE-(qPy zhB{v3>ap`6A_7LOk;^eA6)QHqGtkYCqzRxy!oq2qggFjn+xxT`ZZs?t|Gz|uBal-W zXPY$O1!PVU>`ov(Sr6zwO|h`4N}5s^piOvr!s17}@3~g$b(=h_uiRE*0j`q)krH|z zsJ~Bu%J969^y4|euSf>}3+92*4Qj@e1q&P^Ipk)4co999RI{pT4A;H{@A~HP$qT`6 z7h}P-DKb<1CXmGoF^(5-jq*(v*9<0+j5==lw;~zUZw6op%uWz8SfsB_WPHAsm)bPo z)SwSHR>)Ju&a6AP{kSWidY^kV`@#5sz&=8E@3XU(m#NC~6m|rBjB&~|vy9}ff}UZ6 zns3&|aZpKoLE%_h3K+a8&3P>>BX!vAnuHml>H0?e9*DEYa@Zb2G#5%0mL(e!GNpPO zKMgAs^Li^KZBl3k0iQd-wOtpu19Td7vf8cpNi8$Dd)<LZ8%R?-90p}>@YKE)d#W_p z40}d0Y|{Tw)VM!cIj%Yu<|$CK`Fgph@p{T5i(=cUD>nnr7k3a#uIidwj2vK~;z5zZ z|M7J0k4*Rf8{Z5=B1KI$BT5dHLpO7np>j&*m=1D?Qp#bYIWvUPYz`@v9ByaIp$H*E zZB9`}WDe74EobID?(h5a%lA*%_TKCLd_Ax0dR%6udPio-#tlXE<(#qjc}vZAQ!s(% zwAq{(HMheSH+3t=#6SYZR4Z6lKd;pPeAG>hKFt)V$}T||*Lk}8KJ2$``p6!AzgR>d zfe4TdLUy!poRsj)ZHMqOm{J~aA*%ZEZ|-ev=$IFyq4cAWNVt4b)zrLANJpUUKwwM< z*VMb@)Jo--KCKaob+TQ})Z_iN>l?E+_;Vm!gZ!9yu=MwbG(y}MrDLGhL;??nmZ1%S zJxoKX?#z>%@P&SlnB4HEod8yy94gNN#)U$XxlWt}Mq=V;Uhky_iE>TCGzrKgtvP-6 z+noqi)9Gi0I|=4^Bjm_Ya%5lgo!(?iIcW;uO+lC3B;A*@fRrFq_f?vkEr7flI@gQT z^7oZ=hg3z6aBVv7k5l_?zh*CQ0$%_9pEDJ**$`4p&X5@BNo`awc$mQ$VbI6r^gD0r zOd`9p%uUtn)hy7DfICP7C|E2C=mIzy8JlBj1Rnekl%gh2#ypBXPsrC6n5VfETR@ic zgy$*GX_5{RLGyo9uM+@~2y<q0+tJeYr#QAM;N0l*{I32yP|!;dVP^VFcOIDJr8HR0 zz1T*D$we<tS;;!+^166y+${$Uf0-?$-fyj4Lx(#;;H=jrXpugQJ=Q@+A{w9{M=jD) z*+dK}vSfFn4hBlaJCT7P+45SkU~7{6Yi<+8&;kvuQ<y$P3^bI8A0?L%McE4^Z#%&( zP>y*NG+^dpd%EO=n}{qMV>@)%To;5|Q0;W`460AZ8~P-Jo(A9#cx+2_@b{cW)B-0v zM!bqFn;x4(5zAu|gJU2(kXM;IlJ^y4Cc>F^lLWtyrQ;mpzIIm*xh{x>{jc&EWrx3b zlDo*{6=zPL)Tft7gH~n?!L_;fqwY2uXSw?En_f~x<G!ZlK=b8!!COg2(<GM1Mt>1V z(FD|~0y7?SY_9v$v54dK%NCv#*2ZI3=1$I&B%k^KKmxEL;*bhN7Oit>3s+y-Z#p?z zpkZql^{qg<+{F;IRYOGsp%9y-4jmr_Z=j6CM74snuw@DHQPNl1!dcO@o!-swV-%}O z%0iz73?t}33XMQ2kJFQ%Ecu|CHI_yH@f-m{oV=Z4@onV}_~-aD{Ka}?Ql2!U7S~Co z_7|ai#QsXU_aL|rmn`q6d<M^(fR%m+WPQ-*P>KvmGAxo0uv@Uy8Cf2QQia0PfIR`o zDs`E2$4zTxThbToB-=ONq0GKZ2UMw4KP6@OA!hZLlRdGkxlJ2UxIZVsdsl8c<54?} za@b<kYr1W1woD6NabzJlRoWvOmgleNV3Xde>jDqA6MR^9sgVE1oD~KVgQ#Qd0484! z2JWb>%Rz>q*bHW?FRn{T83~jb7z6`lE;1e#C^k^Mz3qViJY{Q1NByw~7mPQ|3Y^F$ zYW2^U+){gEAOK|;Ph{UD9-us3fKjOc;)}Ud1~fj~<pDWM?2m#em(!5xRR+aXJUXYP zZ0Ch*4TuFqwEZC|pC&m2!~^>Fb((L2dV(17z@54v0E(l+V?y{DCZPSK5wU_|eKc2h zUV($p&BQtqgG?k`{Q;H&&Cm--JY8BKzK^4CIswQA8%A78lj*1h3@s}EG)u_!!EI*k zlGbc8DB68SsY>w?9R?(4cw<%jiJF#F%&GnDrLu<M>z)65Nz4FF_S)cup!s<dF_fKX z=N$H}x#jH%VIT#`UjCvV_ij2zbXvY3z;ynLCcTYatc~i!WP&vAhj@e2F_}hwqXN4_ zf)WNh4t_U2gR}#6mnZXi#ffK->Yd6S!CyhvV9$oAF)uRJ@j9*z)^FUwEYe9~CUu7g zPv3q%Lz7-JilCHOgIwh$&rw)FFL)8kfb)sXsOd9|Qq?`E-%ZYWI`#>lwSfj+bbs?e zUB6GyzdAyIR+;VBC)+M*8$>I_sF_4_?X+Y&RR$U4Aq|Uh=C@#aILQA;-xzBN?Q5r3 z-=zxFl8kHZh5q^%a>t_tE)g!ZXTik^VU-lTl-WRq&oQD5zM~i9ZxlH(Ic1fu36Lox zdDGz$4nB7c`-DMUCNPnipOYeaEK|<yNrO-8vMRN;$m5uzfAnY|!uYB;j&W9;O^7D0 zu}M)vvbGi`+UBS{QR(FxEXLLf_?8_LN2se30_4Jw(pW8k2CJ_$3mA$a^<=^lN>&=I zXqhOO2FVsbtl#gS?ew?5F8W*-eP6;pr;bK|e3Q53V-!p+OD;QpQF}plR07Ng+SdYm z`o6cnE|4ED^~ZmyezMU-^2#fuKZn_OR~ctY1>!@G$F2jtqO(_1{Ld#K#MGteVlHc? zysm-_C&z66P6fP6JtNn*S_&q9rZ*n7O-?NP^L_5q`HY8zKljq3Y#ZkAZWxQBeNq<# z9)sqL>td%^6Ty&t?L)Es;RBnohV);l<>p5JqD{))D3V1_&Dh>36eM@Ve(^czM!&io z-u3EYtrj>zES$gu9y0p9<q-N`rOl*@B=w{YvY~(pe|DYut6gfULj6&fhL?vZ2Yv>S z)HZ9DahD|#wo5EJ$*V*)HKt_79h=sIRXXeb5nDsMZDsr`p}(gV%os)vygfg49q0a0 zQ|A53bOi68%h28FfcQoi!dURWLC%(BdvVT;$z;<VjGn6mW_!HiZ$Ztf#@n(<%M*M3 zDeemCIy4j7b)X~Yi&LE0cf$og>H|A4j3)~i2_3YWi*LvY>V(j-c#OvSyuDQ*At4E3 z7_^cgA-D4>9`W@~+AFv<ZNd@$&_hoZo;i)<u}9y$Zh9QmohOz1(L4&hOhxQCY3V4% zR2Y6Z=~?T6%k5a1xAwa_q@4QnPTxQhV<<-a0dKv+_H(VO^AoW`VH@JlzhTp{8wB3s zK*=)`+nK-Dp}<M(0huL5OAiTl;u<pK=Oh|7e9P1tA3SjE+9H$+5;bw1EQuGKfj7_I z+z_cOH>E0u(Y=OGyiG~1+MjbJwK*^_9H0rzTt1t7d|ux>wL;q)cw+%Yb=$$E3(ck7 z$Mz@BuFP}kF#64KF~QqzXG8YGV?#drkHw=r7b)jR;Xfio3Y~7>f^GuZeiq&L`zjlJ zT^1P;6xBwtpLl2Yv7**vA+1MyZD(B6Fq9`yu5eIfqh{s%W53t>4$#tdWWvRxv{p5a zxG{IZ0st>v@LvH!GKb*o(YnK^eA4HFd+Ors5&%kq9VqPuded}loSjz(@oyQi{n9io zeteoDh~E;nAc^fOdf=Q9?5bes1oZ6T><lweDSB496L2pT`PVw8`G+D$o?sq0dD=Ry z(*s_e{lkoQm$NlXBkJbl#~iKx@Y&J}BA58vs}1%CSTs?klspou<#6;MlF#zIHA`dP zNs<A-+}OTBV%(zo?Zqo^l@yE94t%iJ&HmqUj8J>}?#tnk@1|6YB5U{hkMcy9)Jo(3 zK>O>7AfEJ<{qf4i-lQUPfikF|AHtelg}882|MKZCZ9?R)RL);CNILaBrsrs!^#{;8 zTZIX~S#<9<u2HjwrR8C8T3b_cMVeYXFjji(@W`gf=cuu8(ne`_jMVPznuB4zJ76!c zbxxW*{=|#0(28x(zblA~vmFqn!w-BKPXgpOXC;rN_s_dVCMMW_#`c0|>H|mY;MK=( zn1j(6778<EnI9AvYbtWUZ-EY7<?_Dh^u4_8LYX-qtpxSgr&(^y0m04h$&<&~P(1RL zkvwj2eH6ES`HlTn=w-vseRXIoTz&-kqx4Gr`rU9m#Lxa`12Rb_ALdb08(9ih53kxB zKKu1wztIc#N1V0*@jlLyC6P1oN3F8pPL;Bw(#h_JsSntc?(#2cOiX`M4_iZIHH^NW z$GskuL^yX?_uT{ktWsT_<MjzxCBkm*0s!5b=qU0WXBIv@uV;~TS1%|rh>AeLX0N-5 zGb4K((>0|JpvEi!v`yu8yOtfJ>K7B1@kav9W<n%T`fSSm%QfC-&mGG;$J)xqV{aQz zB-V3=#P0ar0f~F5;NVkO6LhOJr?{7NMN<PGHKMBpFua)`qaJ}O+bm`n`bw=UWu=v< zI}cig&c(FfD7p?_mD{8$Yy)>QvE4t7)I?2l=(D#JuXujNk`L<+W~n;((Tq|6^H-mK zpB1Jkdc_s`$~Ms)6D_C$sa%Zl&s=Gw&>~=m{%2_R)()+|YEPRL0WftjLGC$w$gO6t za-lyDRI{S=bi{VWc3%omj{2J5UV*oPnc_=y#AYD)*Q+0x)eXhnD>0^S?w7;ujA>0B zp=a#7V45o!@R!in^<RBtJy(b*erVOrrsI*4;ig;0o!61i;Vxv8!gCVeSI*v}6hx_A zrbdPA$R}RRJyhVO^$3fc*TM0qRnohSGATr7j^0%6ZU<~v;_n7_WaD@47l$gZJ0kyq zTJxl~g4e4Ack2sJOaxl=oaKtFYk@nrSz>{EXU3e-x%peOHy<CbP1=n7u`fqc620S6 z6$xD9vzAaD*UdV<?JbekS-+d35A6{hjf_YZ{{MldU8?v9kJMRh35m|f0DGgqXFLA? z(<>>s^-#jnp@!p4-r^pdVRD{}V~M`|$muziuj^lZw~!;pJ1o&PJI&EbT-Ux2rJvv* zl`wzfG8V#z&v{(^59DDrb2H>ZsqH*jyR5Vpg}Ff87F&I`yk_Cr|75P_QDjY>S)g3T z>#xJZZ^KmP4@XudY~UrE>qU<Iu|5MRBWtt5rvyE*2Zdm0lWC%QC+4nVZeq?=#Squk zrhNJ{stdzzlXC1s@22fRMU6CJtukeAGWNbi3(#!!%<1QS`vXrg`sm%L{utl5@$=OR zuBt)wo;GxnjHi^8E@Tz5$y$Q~Khm9*tM9#y>NG0SVtaFgkqp_2YMuV9=RFrj3+sbz z@i;2K9Omcwp>|xsna0njaRjGKORn)-TWIst)FWzn@q9F~GTBGw208YH)p+(gHgBGL z+3V$%cDcZ^GnHrn?|zyh+nAQ_GZu#)A%U46^eb?8M>_8BG#7~T+44!>T%wfX@<;9( zl)MsO&PeqV2eT+KHc=<*8ptZ?m-{Sa``GpMn5nCyH}c~m5uZJxXJw6I>KG8Ty6M}i z{zd+nP*b}Cm^zic?Q&Cp{}aSzoipj+OH4u;$`N>f*!nWAcBa?95PO>l8R1ph{uMpt zaA0;OT^MR6SwHZxLcc(ldRXIc#S4*H@?<6uE45mc5e!ADw#gU#XmWU>Aw`=;&ZJS1 z&x>$}@4eqBzf!YBSnn?){8%~lwK|k0A&}Fd1Vk-@pS-wy?*^$*e3`^4@^(`s-}GK+ z{3`+C@xBHh`rK=wKWc!aMx)i$U1}1?_SK}sW`slwgONq|zrPsS^xu3Va4(~lHovbv zkSH-;Vg1|vgKOCL$^+A9%G_7fN%h(L&tKbmk?h$(#Pw-nimvK(%~U=6qnqBG+rl(n zdn9M|`}6Knhd<U$J*WB8Porh&jzm?m*2?Peaz)_eMR<H<xeT)unDgc1Yvx`3%aa47 z*!$9(R>BWR=B?4x&z*DaJgS$n+~`zqs~M<`rcZsjOup+CV@UW_4uY1zgUhwge!`uU zH03fF{B1|iMvY3{si))-6qjPZX?G#T`O%o<SvKxeCj<h}-`d1~U3MAO2L7wFxz;r| zzsxTc3_~dld7ib=n3<-s5<L41%kZ0$+b~kYV|9KP(_SnR`86J*0?!uD8SH_*)J6<r z+BKmV(}7B(Fy+?E0l<)nDFT@Wl0Z=8$8Hi~8whP!38phO0^#C9Hi6hmD*zU*cAZG3 z*?34;^_fSt7Fo$~(tP`bt#<MxQkXyjVBgD!C-kLYxMMt{6##wjo^Z>}>fNd8(_GEK z7ATTaq~rX<0hV@A-P-dwbvo&P6ZNob>5%eMjjS$kSpT>ZKgPP0#=4Kn?cT4zYz#v_ zz+>c%6AR-e{+|60WRc;sES0Wr+>yV1S<Ur^{?DcjuZ&cQ7=z)sl{?RS9+)bnYTFLA z(X^p4-KApp&@(N=uTBiz*7rv0AYFHcxR`-ypCrYbW(^vU@TC}y!M3Sf&HJ3Yr$@l= znf@58Z%;7UkeqxZ^b#E`mKNWDi!}i&$13+~@(=SobBGU+)0cTd35^aAsc)q;@NBMI zTuqf#m{~_k`DBnji6n`2|MsIWK(XfTV`oSMu&Y|j6Tc;>k*grcf74<q7#JgVL5tov zX?*!x2YPcpJBS1{@4apQJLbK|oAyCgwfa7rR?3gNKP^t)G~T1<p-XknFf){;(wjtK zZLA0+tz>ZO#em$s$dt#=+S>Yrbr>aB-&4=$kH}xk94%0Rdq`wQFn-@l^6NhGA!x%y zrK&nlSe>ryT6R#4DEdcRpFXYjUevZXr91D|e<18zS5n2+tD7*#4j@x7nQ3wQ{B0-1 z`!#Ov08!;#!bPZx0!w_E;_6s;5%b<v%S_it3^eUOy(eAmwvY%XNzq}`6rh*wfzrhQ z_#-`3OtZy=d}f|3t_Dt{D+ePa>#m5u%?|z(#H7q#!Smk;H7cI-s4v@#tM$x?P@s-Z zh9dp%fWOV9Y)GYT0Mdn!6~sc&`_f?9UxVA_*4+c*uOHE8jGxRqRQ^1XI2owOymQk) zb!{66;ucPvAH7o}E=c~`M*a11{zTZ#50-5jk27x>31JvA-EBn|JokOYoT&xRm6X}f zaveXF1^J-rA8aw6c|<Sm$s70}?wqhFGzEW5Jt>O-P%lA1IoCPv>ZysJLk)cc?06c$ zdP=Qd-alXH`60c7l=!!Sj<H@0PH|(p)bH3lvSErUe;85>Y>sEh<Y!V)%eJ|=69xNw z|LV@G*92{N!R67dYW0T`Zf{35cUo)NypO2`Hcq0DV)e!$`L0@qat&fOQxK5z$XH+2 z+p1&r<iDfX7Y;}*sH=B^`Zl>mUG?7#6z+7-k9tsf8M0@h$jSWjD`*I4I;ekwy}<jU z<utujvU(&tRUa<C6P>B7(lw^k-_KwI&Xa6A-+R|+HMYmon)^>Rjugx|GBEv+Ef*I* z!9<L)fLOK%kBu;ZhkGTn{!RH|9?-NZ6JYZI#p}04eYrE@-hbas=Y{l#83!Q3oQ>lq zd)&Qu@G+EdO9f}-X~ONtP<WM*{KEL5FqPT=xj2*GN8sx-!u~W7VzbvhQ1q%2+o8*0 zvOir3NS$DtR0D9fM6QEcn8{0hUEyFu>nddT`<$ye7o2W;F^qF~#g?myYK?3E)7U|G zMmpcTc@?x0+h1Sre{x1Zw7>)JYywsM#5HE|*aMk3wJirobNV?+TM*LJ0egDQzHewA zn95~rPxQX<ToIr4+mjlL*mI)(d1#ZS-c>8({;|2z&||36#;2saFc`($-YAx{$WnY1 zY(m)B$GlTIggBw*MAXXcMCP`5&?x^6tyTaqDE8N%bj5JE*N+$blpVJodX?S>CjnmM zoV6H-q+PAg9;d&sa-@+#BbOr$^F}T5FW>jMy9QevUaAVWczwwC=aVU`nFde<@H|C0 zkLi4}K<%Sk8sUr}+u!@0>S%X8DNDVS1eFKw@n|*PZD%=c)189NnvBUB<JO{}hL`^i zeOPNasO%Yg4hDtF%0hE;r>@tOEK2<g`G(68;gr~BRYw0jE${Ky3O*gnfVBRopMuUv zrIQS*A|Ldj%hmQDeXQi_niN8k={V-~4X9cMFS@;8-Ph>y>+?qj=__zlPQ}iTHh(x- zZ_uQkBO<ub$xiEB=b?VJ$hFD7a(t>iuSrEfp})tZcSBWL@PnI|lp1-T_4mGNd&Ca1 za7{$q{6vFKKyK_x`{#-WR3opkhzOTFs&no9_nd2*Un0P3|8#s5*cuJI4r2qv8p?kl z7q07<%!vz<GwrXz>fi0N#DjM=F}v1AuPeQRG|nkJyT5B;8oOYyY>)V2+^_a}=bc1Q z_BMePlY8MRjJA+3O?q=H3QQB>GGKsbu$mH(rRSlR{XuUHy{l^M$__zT$tM+Ed}peB z!>AXmNP|KklZ?@SEyUyX;WN+WY`;?xP0;{+C-^ZPDwyc%;SqikHP5f;G%|k?#<t&( zm?Fzw&tIG0jLw|>_n)WYiT-UC-P&joD%0)KFVvoSv#S8ubTE3^b|PECfX9kW{uq&b zT^?C(=CxlQU;c9<`cJ<?^o@I2&Y;R07oWFx8vmuZhO?7r*B&+3{C-D*0}PW%L|CO( zmKw@4ZQ}!v9tp_L;opD4b;h{C&+nj8{U4n+rA<!g*)N!Daj#tKIOeLnIkr!WxhdIG z6nq)d6PtE~FoviMiEZ%4ab17E<*Qx28t!*e(_|WH3e=dHnfoq8<8^k`3u>M!F>AM^ z=nA(HIt}2?HPEldETuzgCUU=Fvg_<t7!`hbzP_g=F|_U0pAiQr*1us+U9IWJ{{BJi z&mH`q!<Q>3x#Ckv#RK@<^kK%)y3d!pR$6<yxQp%@k>X9NLT|iTVOk$^?E&lK`r@N& zxj#KEy)wG5nx%|P;Tx;O$~VY;NxiKy%?>sW7i4c<ojCb{wNfIEt)^RVR=9oo@Nw{p z_QBGAm}rJl@L!!+((7i4pkX39<JXbL{GBvJjpKATOGV7)?#jY^7YB&{aPr72LYGfl zsz7UQkMG|5Q6vK^4D7$^Yi%alUg56-4SGN`kpC(0=6v{xz$$=AN8Za#Fnc^bokohS zBQEG8a|d$f@7DJ@&b&GQY`kqNB0}t&MNVk0lW0KQtKav@Od>jzuk~`dcVVozK_l8d zYHSZyS@C(aaM)$B+T4*NU@VGgG)}6+6PBN~uS~e1=8SWbV3i+zJG%q&s|wp!RnnbD zv>>7VT}&9a-*^3#zM$@hZ;~%VSDSa>UU|qK{=I~yp=6!%ce!U~yaqkajDsjR`ap~S z#8>gVY8vI`a<YK_EvuvtG+AdRT%9z_dpy6Ma7-8b0yL3Fl(1q0bKGhm^NDwA0cL#9 zXKcuGr&PwtGN@Ys#i^#(VQV=V?EpGfNfvXBWALw$%_En0IifTIXKTj=dvE>DTer)u zF+J!cP)>Mm_?JYQ)d%Sb(XHn*d(mt85B9Z}{Jw3J9@CV@I2M~~{-fq%s<uvAea4(V zd$jOlee!klxC?&GpT3!gAwZSx*cgL=_XRSuOfk*S${dA*Mw$2Tt4Y5U?-xle&WK#^ z>-K`q*z>Lb1NBI!AM{t+9~a_t8>P&vWPIK}Os&@-s)Jr_jz$@0A=Hz!nh$<Cr0Qem zB=t99PvGOfJV-%^=t2G)SyA|dQ2>)`c=Mwl`lsJ|#%g>#9SXu*l&!zH*U%amYpX>2 zB?r&wlzCfp)?8EfSzw`B?&7-auA0eel-=3z-lfy#Utihc!A5{~yb$cHrOiCtci<V? zN<nhQRp?J&g_dXC&o)SiEMQ#vQ8|0@!q$r`2cSK(-|U0}q|(2aIb09IQS2Q<rPh7l zWx|-XGF(R8iTAx?B5l;^Z3(SQONN3!ZUkkH=B@Xs8?=fR>3m=4yv3u!<Fm;a(;s!s z=o7}nM-Oz{N=#&v?;T#h^meE32?<O_V*z=hmVb7_@AL8pCj_|w9S9BJy526GwP*J1 z+jq-!G}^8Wx3{=N9=iJ>DhJWi$x7fDv-2RxOtZH~UEwKjX_}gvB}{n6z?%XgbJ1E4 ze`x6_79FEuch#oazoZJHCJiKyzx^P*BV2p`!P47vi-2_GS6~$mn)C&N|5x93<>geb z#`P4yXgnV~Z+k34UhhHHnauSSDiWI=LHPA{Gxr2a&M+2QGTv|fbx1F)iK#$iMT_Hr zI`|LG*8Aus$5@Z;$eO||pnvZ{u$IM0?mK={<ywXR!@CD`qP$+jQRtW=&%F`fxAF-F zxtTI-%;JHP?dVLExvzol&P}i7_MJ$ERN=q(mP;5v{J!IHi??4nmZ-BfNne4iRU)^- zADp64&eo0lh#gC7W=ZWX4^qmiOuly~U3hdW8)T6$KY4A6mv`O9!cLbq2kM6t1YKN; z3^c4xm}sk&AJj=i?KHgYM4t?J5_H~VRW=M_Sgl1uR#|U1ty?s%7%Of*u@b5`j+cJ* zfh~WdLn3!cZA)JNw)Yr*M>oA^PM?N(BtOKX%%!OR2Wp=g`hBVyJGF5kAoTa6w9VV^ zK1XWUp>?}R>&Zxzm9k^*qUy0)+SE*{g?JG8H5y%^+i`fQyHfb_FE`01<ciw2RP!9q zTXRwUCR*IZD;K>S293H_gV|~BXCetBjpKu=_T(1|;BA*dk?+bv&q0bB(ZuC#7eH8$ zj~8x8FomtakfqWlk}sl<@F#Q<1-_<NS^~5j6-EmoSK=poxw4d_X7p!fG$tWc@9VbL zQYCV#YM~kDpWiU49Xw~Mu$NW&s$=Czz|jfoq~F?f|LF7@C^_3}Y5qp$rxO>H)}XFT z1bew%ZDD&!T?4#Qt<T0J`40aO(Q^P<9z64v_eWi66Sv0s(VW!S@TuW%D8F3P*u?N= z2^~%%1#dfFecvsSebnTi<ONO%toWc7zf7wi9<x?%6nz%dC5kz1(c+v*9`i~3^#%hi zag#7`4gr|<KZt6X;^sh~kEL8-p<x7J?`fmkm>sBt<n`8Ua|~-cq-#DQtR_5bav+Uw zvL^!}3&$u9I(_CD2J!x=9Sq~tofQm4d>phv``%yYqyHW@Zc(E?34pU4b!x$M#N8Q- z=w07qFZz8!1QTEk{L3pa@=gI{Fe<_Vagxf4HIdvy)V_LTwCxXH-*d`M(cECa1)(?~ ziFjV=z7WnQKs--#T#ySiyqUkJU@LLtj}YiQ@jh&RaOZ#Nh5`sVOBT^8c6ndi$Y@M% zG^XF$g8sZIK);I$m$cbywFaGIkim3&I)mK7D__y<8zXkRlziQCN=S^pETYSqVOJsF zo}Y~R36i7OY%gyCXmzvx6PGW;xTzoopRK|3&GBN5ZCe%)7<YIe8>mi*C#^#nf7On7 zII&Z)_DuOf5Vs)hIKJCVT&hVvn>VLczOchqf>Ht_fM$<(y)vQpkM>-{SLyOYqL4)& zRKM-ke;|nSfup!=auySi&}_9s#49n@U~q`MaZbT#!RZEl1n!I7ew6()P_~~E+^fza z$<C;tR+X((93iz<lG+-aE%7M}@G-hP-J6Ru_BRYa3Zi&&RD!~Hk_jP@oIH7~jbk4} zQGbd!VzI=oyo*VK#u9->zRo=1XPsLX{t<zyBDa(RFdV+BsG=#|Cfe!k%7<YnY^p^R zki6_beKjnpwmvNyXx9EkH5O<E*PpXEcL~=>b0QwfwaH+vlprR9vpH3WPdQJ)a#Jf` z>q6k9V0QfnRaY57Z$cmNgRPb8{j6)y-(I#iHfd|0Ugy!RL9$0S!yFkarTvglM-qVz z?C>PM{e>MO8@px4td%wN{c3EJ!yB?&Kq!U(Ku#jAc<WXAeaUNBt;W;P-onUcFq1cL zqY-EevdfE-Y$!uKO|S%vmR^n9c0zdUvSia_B?uuAg}wuZaaMU<i+kZ>jvb!nU<D~E zd>!dN@G7I0@;ve)DTnm{@Q`To3rQ7H^d7o`_(4qnCW^#Kp{Hu%zJ)t{8e}7b!~+eH zJ)mf(AKe@R^jYW{4SNmbwiz9MFz*n>U-)jTrdg>OT!3lFnaCha(PoTfl;U$ufn66V zK`BIm4Mm`_h(=%x)>9Dfb7?irX$g~_%e3)I{3EG^Zi+F$j^}2s@5<$&zX+bhsAA68 zjYXYAB*wv0UK@BXXIK`34#D(khKKeph=+s)w4J2iSu0HSXMGS3iXZ!?7?OGXxh(hV z+3es`bXf#9+9O0Vi)=mzIC|7Pp#D}Yat;r~Urjf5MHJ$Ie_Qbp^+eZ76r_Y}DtqBF zUB92rH8;^8L$x83>TciJ-;mR&EYTcv38N#Nq39e2pq;nv!qas!{af=(_(e$&*+1w8 z{sqwf*9C~qet5)7nCg~GCMS1M{skXx;Goq>KgR$OwjClWL-ptBQ}oq5AuVFQV@a!- z%eG??ixk<`BsCU-bocei>RBPa(Q0!;Eza|bS7g1RB~_+CwFFIDhpOyNfH3&JfrO8x z?y14(e%|kjX-c!msg39LQ;zgbfG?^5h_{&W>9zS<FR~85jK1NKWZVek)1dOTrTI_u zcZ%MX45M3!rNq%#3^CAZVLaA2uCVa2sM#w=@pJyuF`^v4nz#7Xi|~g4M-(^7E6obH zB@rsy#X5t=U}vm9*-bH%;K(V&haIWWv<q?PZhgoYhHVr%$dCf4vh3D<g9PqCn#*Z0 z8zkQhf+{%1CCCMWct*)4=Rr`MVZ-#HoN%ewd7IH=?x#ekV!Ho<YD2kWjQ$BVDyYL# zoq=vZEL($&gu5UNe-j?yP&Tk=Rs(R@ASjbb&UDIw5%DO$5#!13H(IDOWZ->*Nih3$ z0&q4!e$)Qv6U!5M{UM_!Y|7k{3IT5N=M-*pYyCJ#&dW=Wf_Ca4WT1mIO6`~v+*nv& z5pNqIZU@;{A*t#0?mis8y(j&4=9!Wl<$*F=iEHVk1rZ7&tqvpf3#z)o)BKhckfDkk z5(WkAwkF0;iQ>qoUKQzqd6G6kTTU@5u7o|O`Jea8)bdT-etrR+FtJHDMR*y(<tN%R zpFVK^sPFt&+aL;*e>KUC!2S^9UZe->LepVJloi8o0z_PwGh0PXRC#-yU-t8Obs&qx zuOJ=b6{p5?ZlBa*Zr{w_!Gkd&_4@L;*LuH6%oiwosUY2QvWod5LV=o=oV*h8s@{@# z=7+o4nO#%p2Em*`*(cA^O{EZ2<+YubsE>}q!&^(%>3B<I67om(XCcMR#=niMG$waf zwLoM<qfq#`6HycZ!h!OjX$j6sH8iYX{GRmq8|}h$UDhhOwL3xesK=SewN5r!)yc0- zFk7Be`oApLT{Q=Ds#ry8L!X5SG%tVroTh%;4iNrX+BL*kw@sWm1rSU!__4e_r#DWO zOPXS_-Aj46;mJCo^LJSSV`L&_(IK1QvAbg6QzbpDjOgjIvux*3xLj<8d=gR}$H>uI z>--|LzkSL&2bQWcnz}p3&&wSzL%*uG<$rU%^(2EP*>ef)T3$Me+FRQG2D<2VPx4g* zr1<U^yiBzL|7{wjJE6@`q|HGBqvrKOb6kpYj;QAasM$nm{#!;o|6KmILp4k+6cGVL zI;uTn>IJ0t(E95|3P@Edd;zrv$>SvV3V~hyyOgtoemsp4HGQ@N`0YJH=)R)RAQE^Z z&|vo@b7jT+3I~XS84rTS%R>&JJY%sSmR`xGBd(nkyi>rnKS&QceGc4TA`M1?4(yX? z!I5#7+Gs3EBk|z=BKg~z7B)OO^cdw8%#*5+#FGXkhqh<4{QJ-G3Ig|MCu|4hwm*&h z>2JlsbOsl%0`((+uu0IZxsip5ASW%I{UOC0Z3Z!$_S~l(ZduYoRHwZRlcx4A=%4e~ zfXEwf?DYT<IL|(_1cgW{5a?MdY;$jlU-1lGD}otu?m{YXbore2e?wBt=b(MU!se4P zc>rc-L+@R6P}~0c*g13%z;dN-1&(<KWem@LIbl0CKeZ+6%HwasgQb66sWE5IAWg25 z2%Q`ACi@o~ycXuy=|xE0ITE3(Yg!Ummkd0gZW}TBU=*9S5$=%sLLn~tzPQ&`Oqz*= zV0KujtJlKnR<w*1h@$0uMFp=Zr^0Np)Rt5BQBtYj+IGAWz)5Ki-swQ-^YR4MW=2i} zG(a@>waLz>7XklU)|oPMgvUQ0z}TMjxz%k!p-&DF1tve!KNxte@QS>5Izd#=J_GM) zr?K1x5(^{=@Oag9hBu$XL3h9-$Em1x@nuFbDQG35o`9Q-9dvj<#|bp~4>Zm}W-1*l z`gpKKYj-j-!cKs)7D{C|{JHB0L4luAY#VsR6^a^gR%w6FBCkj={mrI&PExiMk9HDl zy%0E`desCbOWpXRrUxD&A5jjb;jHmgVGmQ~2(jpatEntw;ULBx;PWU27saZH$WDW~ zZPNH??=2#VO1I4pmX0i$<{1%`fCJ5xbyD`YTnHp~YugS~QYDL`1?A*S7M)%J-E@NI z069(a2%l?vPS`{$2?B}3ZaSI|!Mz}Y&(_zakAlFq(SMjL%gmZ0s!-a;1h`M*Ty()i z7A)){xsg36GzUbloL+xTg-w~;0s@9K2rsDwg@?y%*IYuXcJN%QT)~UBKjSQ_<tMR4 zXREK;;`)uV@_OB~ND|j8u{%nm*_O8y8&AbHpJY#D6_O5w-Y=v3>Tg-xc+ts6@lUFk zK0JJ95R&mQ(uZic=hUcB^)=n1VLQSrSwv+<u^Oak{D~*fFk)-c#z&t#V(LPw{!8bu zdGhVA`4?%{Wc}iJA|6MERv~|+eKHaLVLuFsL(}Vo$lYo|@x!2~fhbjT%W-WMJCB9~ zqIx7h!PDU+`;~uZs<p$~`lr_Npm_5@AWerv#2mdVE?tV*=(kUHGEF1-plEnu3%HZV zGZRfnz_y2Ej5R2xQ+R@q!Q`tZgeo!f5jfjEiQikHFb?IdB0SSo)hOLIM#^O0@M549 zz1L9EpGIQ;X77|B=<G{7ttix=^2rIzl!bi)Ylpm+wJ)vS2X(4pH#+msf<_H1VGOnn z$Hg*@fM)N`H)c5|oiu=Z{Z)=oIRO-@EvExbCfP4*snOR}#0(B2P>`B=GOzt2@rYm! zVQt#sz97X;5<)4b%wjz^oFC}}Ax@|%H<<|f0!oQ1g@k}08P+)drFs->0kpXGMM12f z$2DcL*rIC6`t!d~!k&y!#Og4kdiKXl&}d7CF5WyUVlewTJFX}G+f)?vJ~I4{w;4R$ zLJ+>aG0!BoKNNC(CU;Q=6oTx2-Ar^oF5AvC3=GPS$h~<N1S;zrw9_GTK56kv;1;bj zI}Zso0NIrFH+~h#;5rD%Y(@LyHoypI0Ijfl(c7^fL|`MpdryauXR@HC058`*Cpi!b zVt)%7Ai~cl=x)WF7I^lH@>D8S5>8l$Nq4||FP<<<HMKKk?MB?pl>AB-;2C}tmw*ls z#qnmj>jVkhyqPD1Oy5sth2)*4h7hJ|7`zhiv_8W2|6tB?(F=1P!CRq4DCHwtS}SEd zD6>dGR-LSeqYJzm6xFt!j21zB`j-f|YFC%cAe#QcR)&A4iF6`&1Hwi11>wRff|RCB z$1v9<K}eet9{|p8LD7~*IQq;c<7usbP+UZ~K$Jz1Ca5nt<`H2IiuDaZs)B;D)0p+Z z)n>-7>?uo#!`%yaN@+MK;#e<BhvpU`wOG@YAW#UsNZ+)JNfe<%w(LN{ZE0iE2V)F; z8#<lo)m%yk*LKV0IPMuss{ia5;!8a~5Gwz=r4&44R=kKW2$<b=N>Wbwlx%JxyO$+% z)aYK^kyEeB$n;N9D6VyDi1L93ls<Rlo4~(n?^<Q;`xfT8{kGXokBo18YTSwvK~Cdr z1lKydwi3hOA$)_Ig`>aDUh0Yeqm7+nN`pPGe!qBLY!P8DN8akkE>&m->Xv8w?-UeI zEi(B+&ZN$60&%2GC7<)MaUbTz>aE8#N!$NG97;IoXDv7_riEzwR|abm@gGQW{)YT> zyh20h@h&KbJzN}x=`RX0h(6$Vn_fJ@o?WYW<&3z64aOu{ciVqT{6;{(Jbc&dxc<uX zMji~9;!=Wtq;D1L>yW(kl~);6En%NxBYoaG=toA*^3XV-yQ%8NS(g}}RH&ip{0Ir> zcEJ+gBwwiJ%0uZ|D2@+$!Ho9)3F+O>AdfA(zHV8*^T|viA~xP--aqmuy;s{X3VrYO z-2LE_539$_zcaa`B^KH#h0~Hx30&tVol?x=@8mkX6j7O84N0boieHgSa@+<x-%7QB zbZ(6_hd=oBmIK{s1d69)uBH7eMVHf_vSP9MJK@d>IwgaTvopmWiDk~yw8-kF>FPW9 z^pnbD9foit@3GrIophTt`ac9(fcm}$?WU;7j(^Ht^j#{6O7sC6FDrX3{17gT(|>Z( z?NF|*)<BDeW1<StPcVSJQe`;gry_2Aqr=}2a{YT*kZM6n6KTd9#0px;`7~+jir{?J z!H3I07!CZ2!5n6AB)dcfp-vo}Tkj1N9`YBS2TW#euVvvfo@M>D(1#8q@N7T_TC<_I zyx$1%DFMFnwWC9$E>%X$PRcjZ{pf-cnT()UPrrt)H>jMNVabnG;dpST`yeTL?z4ZC zN-(JviDxqK;?ul2(45s?re*ds>KOhCJ0CEX0%cw4BM{le>}Y36NV+caV<-)^xag?8 zNFrq)kVNK2XFH0>Jr0Zx)Z#%tq04(aAKjqJ(1Z<~?$w@v$IfO<6nZN{-2ihI*Lm`e zIw^LnI!{o@=3c6MV4J(6t>L3K1-3$VVAOui4|qBZ<?1yE=na;5=?zZy1FnhSL%(*P zAbb#WsW|P~SVcNYiL~Pw@2A)=CW+~E@RGd>-f7VS4CEJ%dH4lP!PiwrA{fz*buTd) z`3Mnek+YoB1I194omOklv3&w^%3eQ+@<(n~{vQ3w&cSRC<|%Nwxj^*0xXiKP&^K?* zSw{VoHMnokLGQFQkH4#Ka@2CNDWzK&%!aL(6+%2l&5~sOQJu4Kp~y^yiJ(WF{`7cy z9qQ&k%D+&{?bRIzp(r|JDNk58EbWTFdb;5}k0%{3YY&5hD3?0ov|}cCB`Fnc?PQ&i zZK8!Kz388~v^H3uW-TaX<3*@P1HjbTQ<6R#qbb@i82ddj$}qxf+ldaCk5cirT3pI1 z*G9I@;YiPZD&)7%UV;UHhlUf&6XarSA|CKCnP}bm?rdCawm&ddR9%`@@J!itQAyX@ z9%ROfvDQ0pLiK@sK?G=IMA)TMJbD2iL`HqN_R#1}iITPt&<nD>R!&tAN2z_5H$VpX zHi4~_#cVrb`DjBg<DpjqZ5I;U6f7OANfJO#4(Ag8aJ1C+IuX?g(dU&q9J#Xf7t=HX z=~UsX-h6C&I-G0;3bcsE>{=|99@P-Gn-vC@?FWh4TEh#Zo0X6RjcJb%LGaeH6I+rb zI1O}>uI*hZ`|%6qz3NnPM!}yhNNGmp)vS0OTup6Wpue?<I|Q3gHCY6j<IdeYVuFh$ z)!+D(yTH&3ZtIUm!KA@%teS@1?^~A0*hM>|`NI-cHzT5Y9Shx1T^^q~KeCvhkx;jh z{|&EqnI1PLH#!j_9QjP^yVsn}Bj*G`d3f1yF{1%)!)ZN4%{GMjR{gN~R#rWv{@lbv zV!|gUsn-Bh0MUn*P}7OKKC@-62_6;kHw-TOJyBKjYMM5OYvX=#rXCOKM3|!#!Wou{ zinzY@=?4gXM2qp${3o9Kgi&L{`m!5q|C-^ycOKfGEgl}R<0w}u+b=5^v9XtV6V?W{ zGhY!!(YLtv^;s~H?QBw<7M05@2^azPslWRyXNeKfPFfC=f4dw|AYhoeK@_y{wB{Kd z?5N2LcAc_vD=FKTz4yAwAwkRnit6mIYHh{7y^I>UNDlFW0`|6<FCgoXat_fc*ez>* z%Td|svgM|%Ekr_RM6z_=97cl24nq2lF!-urV?}2Cl4!YV8pd`I)SH{7sYE(}$vo2? z0{JfB8SaDWk(O#wQsyAF)~BQ6D9sXqdH_KYV-3<7auOhJ6e+eo+Wp?ZCLJ0`O$eIF zR%4@}V4ymI+jt}2Qsh%XHpL5Qk2V!HZq7+sU^C&2Ox+df9e+63rVXkr)1N;F+$kH~ zKU!_{bAha_+~(uyGsYAD7QwJhD{P=^;bs~3x%_LbNv^G6J+_Ig9k%g{DD`MO6_@L_ z$t!Ko&atv59U?{FC>z;NB8Q8I14~isyMhuH<Cu_Efb&R1bbuQoTR_|4_NTpUkHnck zzYQ2peJK4KCWs>uHi~g4j-*2M(V=Wup6H(2u4KU8CsnO)WXv;+*bz<}Tb5?%LD;s- zk8NLLBY<7193Igf0uY^}gY|ldqH<w$#!@k|iNyBF@8{Y^vC7p06xP=Iu>o8YkdLw- z4fO{FfiK%g4kO4A<SNDY619<;(f|YGRY$!z6sMlejotbN`Q$f~`7xH>T4#9jh*;C3 z*^%%dW^#bCuCdoj{2(4h&3iU#4a7EzO=d}Ukat)YH*@^B6+f&vo|384ifco5(8F!f z+ClVs_Qh5FXQCt;XrG!jfymsN_^j$S!LHwQ*qvUXjs`U#%`Bu}*p)Zw1*P_C#WN|^ zcNc*46s{l8e~8K&RkX1<Yf@k+Z@p-LV<;;&&M+2Wsr(Z^FD~ebrWiRKmU{<=AWMM} zJg9zWDltq6B|kA(A~*C(Fx#hOiUN#Kf!GTi^5m|sAtb&DnUx1!(ZdbP0t5nHF)MiP zf`YOKCy-0OW`~6d69vY^y^vG<vPo5OToVxV8TunFo*rX6_+(YUr9_b&4mOeOE;-d? zJdQ#L{qq9hlB3H}DqV-xx1h8X6n3&43Mr<{zrH#fw&5IL-(hly^+E|A)zN73r=aMJ zG7*!Y7es?%SLf{^S)(S=_YW9K^*K3iLDY21w$^vHrA#EJ0!?WXiLV;qXVl6i-L!!U z5i1X2OPT>8@8ETW6$ZE{f@~=>HLUCse@&r(lD;-ZPq_+lS9bQ!4#`gAa*kj)1DTJ0 z+uRbHr_NzbH@^u;K9vZB!schU9P&GbMD_o=3}H;a{F8K{Ul5)hpBm0!3YqEC<^rMa z)*yp_GZ(+b<n|2Y=+58xlm(+%6rI=8bF4?6VGK%IU%2TK0KtS*v$pL7pOE|^z-G$+ zl2Tf1qhlqi3o~U!AD5L~2;-N|Jom@ds{lC)aJLxgQFeF+@B|e>Q}X*X8`-1?Z^s}i z^i*0OJGX=(eRxc=-oF9(x=X=MMB`hEO`KN74-%~bMA{~6+0XU&<Us8V#A6clu{{Y2 zhuI|{JApFsD+@3&^!v4bOs2TiRw2C?DxVh>;ZR<#rT#k4t8|Mp@DwcT5EwKBctG!f zMPRh(b%Xyv?|)<`RO?piFqV1SP8Y7;BxK0N#c66=Y^|5nPf!8Ag6US+dY;gDYGL+T z=e$*yUr8BvEM~2t0677pFD->{uS-j2eUPk{Z^(nfYx)6fL-LW|K;<VV*Ub27wuB@i z0i*ohPkqJH*q#Bvovc9~Z8sX%#|&@``N8swC!H4><m08|?{;zw6AjtG9>H2qJk!qh zS0IYrdJROF@0LQbB=_pnGH<jI1+(Yry}E0ChPd6kM1k&DT|GCfihLH}O>{_542<@0 zAq4}=#$gjlIbrF@kwr$XyKgGuZBra32d&z;Mb>8p&0C<8R4P%hJR#XmpXt&zbj`)M zvWA=%4DF=}?Fx@O7VT8FND4-}7lAA>6DZkEpc=WBKb55-qKTWGGtQK^R8jUrb<&Fr z<=%~Ofi-^0o2bMXai{YSZgebUOU(kIGO*Ai>gW-SBk*33#x!YVOj59Wb?2WEFW;7v z&I#ife`-xQmG&R#ajkcy4jl*t{U{%ZToL-C7nnP4oHY6tbj0DRDaxY|6e{?D!x(Km z@!&1RU^5xIK8M$n`<KdB^D|)eeYb>;gOiGoQXV0#v2+i)Rq1iGjqa1Qx}WEw)Q^9= zA?dVPnzt!)+92z<7+RC?t5xQc?q?UeqlS;i%6K5!Hs)>g_sDa`0UaVo&t>`~VY2$U z$$an45y)n9XLzsdQq%!2zWSdPfCoT1qvhV{lW|Sw^!3D1?WXq~XRw{luQHDMr%8wk zlCs%>yb8N(ZysKd>cEeYqqKm28d2wi9?GQ1g5RBMd-9mmn?}PUNVQw>zf)@xE==g* zMWI0F4;97*vVLjluX?r~s=9*mm)it!0JXH}x>m~MF+oM^`Pu3q;91#qCbW+O@mS~e z()Re227MU!f3duZtQ-e)qEvOFoD0Fik!-ve;K_B$dGK`Ug_yQPIK^gt4%7a2?DLhd zf$S6EIau2c?r6mm*RY5e4@pqB+><o$_WJLv6i31I=-=N8mfrN1+>;`|=-TNh0Y&^c zTl(;gMw1tT71D2u#TH8z-MONey!zWs`Iw$r-n18j3|--?P1Miqrj7VH{It7Hi~=FR z+mbU*kMGbfSzErz89h~T>|^GwztZxAbwtuY>2&W-wgen+z@MblX&<O)15u{NH=biU zayH96Jr#w|%BrjYwQc<J&SNizzmi3^SgU;fIm!F~yWAyQC7*pfD4#+$ZC@UX*a<G# zx~lPgce=Afs&8+M6tVXdyH80{&!6T@?SvqfjO*?|uMzEUY8+ct#$S2Rx#tde1e}jN zta>g#P+DRbenh22AGmCYB^0LX9XrzuJz>sig_J^;%5FY<cXGPf<MmhC)sGzcEH<=G zNBjKy!0QCrchX=Q%TVGq`fhZO^bOMve;)<jBE4a)<oJLIvbW<_7ubBjipM1l`h~-O zqj!jgpKKzQ|6C9{am7+k@`O}13If{wzF;tPx0`l8M4Xv{o6wZ_PGv)sWE`&VWJcBS z-+cD>B5AYpSY)VhS#z(|%fN!3OXW8a5P6-9|3&c9nSCoBWnhB?m}0aVxW-#>VQi!= zAS*%w?R)-Q{jp=Oo_ahOl{AYgmks$$JN9ro(6UVt>%MVE07tU1wwlQovYkq!ugIVW z8P>7apI@G63foYkSidPhdJCq}K^VfEW*GyuI9ATxf+-!<0Z&Ou5QOnlu;u&n%p3SG z<_r8BtZ{2kol<A)`FD|Xtq-pFO|v4$g1_87^*HNHmh+*4a8gXhwp0Bz{bbBPfq(x9 zI~}0vIat_uB@2_nQr}6dU5|s23p`o7<~SGW!>5i#zF_9G1!`>qhv2Ioe;9}kTWOo6 zqc8)x_k7=fzC5;&cEhQ1%#ZpPaM_O(jz2lg-2dg6@<RtiCtG%YGc9?z-c`wz__)t7 zRdmK;pqzQ_ER0k<K-KEUapwmrPe?B~=w`N;vU0MvV-h?bTsX4#MZ^UEGZoZPJOB;w zWgJlbd58^zOXLyWJh}Mr?&S#=J4ZxQxX;SltLKv^u2VjOS<|>lvbo{q+sicxr5(q# zG$v1C+EL06#0}$Jhjw2*yGT+t#hcgy2l+mx4C6*$dQxrnT%c1K94N;0?aC0OJbhQ% zc7OT+N-!qD$;S7}=Zolckz9Cc*v?OMn0#GS(G?!&nQ86g=BnqEe0J-M(}MR(*9cnV z{+>H0`FrwEF{3bJf2~#qa6F!ZI>rKzKt&D>rxz{WHO)6=xT~l~>=R!S3vzE+p($0z zH;L5rZ{W4ui5Mv2)i3!p@N^fxhHMZwUa<{6S%2+DOV`c(rxa{MU`%FY4rVi{{^2Ip zWA|0Yp4#|@tOMUi-*4}4rZA3u5?ESi{Nf&1d-nG(EF$tVAWH5`u0J@2JbHs>?6;18 z2CWu{Zn{vz4Z4nyIcCj8V>Jg2C9{sMdM#V>%I-&n;3fI$DUPGxm!c$LRWh~Db-(8! zRb#Ig1K<--)%_Mwq`}Yu+`E5N20=Xl#d_Fxl(swKwS<|nM`S(Y05^x4x!Zcnc2Lq) zsm-mCU7=8)`7T<{B3Y?LYscU2P0Z_vn7L^09iPXPCADh>;kS-nYR&&=YO-E+e5xlt z`%uh@s4O)OuSk-;`-Sl{H|KDc=CQR4r-)&FqI;RM7?GacSFX2b>#pxK?*7K`j;@5R zKS7$@cxSQ0DVcJsU&?({*So*%;EDcsoj-Tgn~v~xasmEON+moL&(#ilOtxh9eT%^k zd_?@iZyk}}Q<**S9$&_d4S!e7in7Hr1{z!Zy!^!Or^f_$eDh$JY{~q%D^aosi1NX* z?MXwNq@Wy3MCm+->AUA{y_){RxO6s${>4D~{<4XPGODYS-i=B7XL_>M`tW8<U97Nf zx}D@k(lZPBA?`=p3$JU%F*DCxA@uIC;63Nxm|CTnFJfPy`+rx+Q}3T+)Q@xBFC}fJ zO<(?*D|Ur`%;J##?l<ur6RKQHuIo^qbb1k94h3tIr+>g?YT(TLSbY~8fXr$_0FY&T zy;o;o#!NmhP;lB-Ulu`K%t29Q=H;!F@!fu38uYsipTpN_zrwvfs9O&oGd5~{l|uAb z!bfMm5V>>uvZ}1@%=mj4YI;qE(0zq){*BemqZWw9Ig8ffd;jL1ds#`xP4UkW5+nDs zZyWk4F^fW0?$T6W3c}Yx%bW4c<X=43v1@eYY>ylRki~LT1o%eQ(Ef^wtjNz7+_PTy z<}LRF1?mDVN3}j0jV7ow!`>=6Xw_Ypf2dcfZZ6k&nv=Bex2`GdFK!n#d$rz$8`&h2 zoyv^UgFy1W2EX)ASr1LWNP2(pxa(T~7RLIo_5V?HF8)mYe;hwEOzw)B%%!H>y0{c` zzkPE{F1c0|rl?#tm$~FJB;`AsOQIT6XeifQbDPvA3Zcl{N3-1Tm+<|a-yh&Hdz^jF z=lywoUa#kip<!C)w-_LL$leu7UQ5jfDIv0b1#!GODa|nI|9xaHv2_raJO2S0FrrTA z`o-%g6E$g5G+YuqG49{<MtThjaKFrEzkX(@hO7zQz47VU6)prK;n4=?bC5n4YY82% z)*XAjfjj-&j|q<q+Fb6B=MAO7!J$%0wX`!B*WFmkjAN+M3*Vo=h7vP}Dv%2NhTUo| z0q4>@oaD;JrzXfT(mDs3*<UWCGz=u9k+Psf9^ZmH-_NEuX&pK#OUCnt%brL4_?#&` zf%mslqhl%HkWo3=mDgs(XWx&SdXpR)&*CvXri}N&+s^e|fSBFUcbN{;cCt?+MXeuX z{_|ma=a=xYK%2(cQvZ>mF8Qsibk*d>L1NRoY@*$Vn)IJadeerOh1poK^{G-wWgxfK zQS1oU@tej>JTFRS#NqV&Bg~xavnfRnVhmZ%>&57!|N3i2#wP(>^;3l>6~AaRK_~UL zgNDl8UR5U_up!$sT3L5{uNZB=cCI&=(kpVW4!Y=-UnCngUcZ}sj;rU8@qn<1jUgR> z{`w#1Z#9w;H^DJn!q@b|={o{6gC_KF!-Mb_$G*Na*Ylq$eaCcNd1l)10KJk28~cQ; zXN(C#paVo6qq6Ux!hla57Q!ed0iBC=(3_klXad|GM3H*r^1J;TzP2iuKy@=T!#ein zeIxamq=kEHHn{j}66RfTME&|*rwgX=A#7S3!_@sL?yf=hWkEmx8RT3lZ-heLyDuKe zmt6}IrPLLrMBwPXe|A9xe;)tl6rbalMjS7S9XPpHdF64E*+1^=LA`ycvGR6m*KhMx z4PMs%(=8;t=T#AysjEHb=`jgRASw-QD2aeM;Cb?sFeJcIUk#Lze<ar_c8tpmaC^uk z4aMukNH`y2es$ZJ*pxQ3O0}%Npxq`v5g;l3kvNu<2p}JYdqqiituEbBz{>15Y<#|! zX*lJ2`&Jra-JzYl8yTzYMOd)p)mWWoL5apPWbB-6PVNn}TKPAlCB?boO7qQ?dx=0W z*C~(SYJY|eb#K@4Zvmgxk)g1+LV<OQ<Od<rmj3~e1*d|i;>z`RxdQB@<j`eC4Aj1& zhGx2{->X4=UTj*bE_OSl^y2fIJdgfS9BP{u)fmkE(edkwe3t0*Wh9UqJdWyN&#MGs zsy3pOgVRQn07`icZ(_EW3|8e?O6u17hO|h39oD*G2dA(+F>o{D(MYyte4<USVUoW2 z##C|JnMX$IxRrxH{{fGDHO}U(_WN=}i3T|(o#%78F9nJFv`#CFzO%T=DyHpXoiV*t z{ySS-W=r-xtEB)N*M&&xLU0W+cfkgmk-gDFtQ4w>i|y0ZMQ+uzjkz^)%IJ@A11m<7 z4g0HHpI+yhhHzHFaqtg2tJX17`}VBy1gqCMD53Vwt!xt)Lo<EY8`$;lj~tEM7Iva- zk#$x;U&BwYoP%#cOlu=WeG=Q=GIaAf@5s?v8&wMgWS-~tWpRIG2NPG@Pntr+rifNP z^2X`nWyq{Cyv}{glOJx^X5u|?=_7&%ncrP``h09pyVI~8ZT|Z$nV*{9eoav(hfD~= z{IGNGycA5`Xa6$w;}>b#f6U7f{9KINQ|u=fo}80lsE~!#fjJ^Mq+D9DpRq;yMp*eW z9aRuHco{o&x$&i0|EXbr$_Yz5TI_p@@!nfXy2cTDC#}q2>D8^31*7yzDKn|O2^m{7 zv(D7M$n?ZD3;vvNCOOvFd9S(kLevVW-;iQew%oDs`{d#|&A$XR_wIV0_X<idNO+7T zn<_r!d0P^P*n1p7-@|ftLJDw0VI6#K6H1d=fv}T>!+#2sGkIccbONB|ujUn@>N5q_ z7BE0moSexhM_b+tV)@FG5kyB~K54o1P{CN9N1%OAv7H(zYN}Wh?d38Z3QatawF0VV z%qBYC9onfAoCt&Vvig&W&TGOuE?-B-M<YY#?`~;4Ohg{q1KuCmbBj>`5lQNk4UbiK zKrzWMiCR8sB%WiXsUusej~@HpV!<D)9NM95>4(umL`MGP^m~x3FK?d~u5a@k$j#AR zS!anug8Ht>octz9l5{&iIvgpxcp!dxO*HqO23b*H5IG1Y{hn=!G434>8FAS*cQQz# zO7z^*Nl-C-mTW3Y#R=;-!1u0rPh5!o@8@JWD}{h3<kUm+dg`KnSG{(0aYQq)@w~dM zjnb4z>8v0VRu@=r9}fX9D=H=W{4|1$5Ml|L8~VVmOLdQqg1LWd(2mbt*#~*7Z6ld# zj$W_0GQwk87>?ch;PfE2T19#JZT&euHtGvqdwpNUVFvYNN1^PHETyRU;;BTIMIAjt z*|wn#EYRz#JG<Gm-{K?~A$<d{@_e{W4Yntux3VwNpF9UfG_p_r+c^x(ghfw`9-<)# z!m+}cPic+ZR%h`^7))aqigwEhx#QK?3VC+pmpq9l@1c^)mL)pw0JUBwwovFTHGW_4 znfB7bQh=fIVv_)+mUr%hjU(Z3%Qi!z=c)mx#2~XKSq)u@6RV#POT8R?5UrBYlKL5g zPI+Egt)@f}`M^K1dI+@Dw%WMw-m6mWl!+l2QVWB!R*~IRN<&DmroC@#!nO!j1@vcw zfXXL+YUb0?6Yzt@8~=A8zf@OD*Ax1rxN}3wWEG<?WMXucigWW=VYb4U9Gj89KiWEa z<k!-+NgweDV{C&BE>vVIa!aP^htWgn{29FjIsnTcj*#wEVy^v?5C$NRkr+3Oa4di6 zanGtS9JlcQBQ33oH*mVO4U>_?=Ew)aKc;V<xYE5Awc`?Msmn;WRDhQ|PWuE{+C}_7 zB1M1Tk{zDKpPuPJ*$NuLae6L>Y>C(E>AI#k^Tu(#BJAZ;5y2#zvHe7By7_-Vw9A7j zz8tGY|D9#H!e~&ldL(wZo+=`rr%DfQ9SvX9@fmIo_aiC=guD=s@y|C!ib~)f!2(Tp zSKNM9O8NLoQBL7l<$BSm(o!7{RVP;o!^g0~+jF#Y-hLUWHuKQ5MHJ_%m6~W(V^z?r zA8kPBx<s9S=8Fps4cP!K)CrNR<6<brjW;k!P#8LFm>KfZ@>!N|kF?s>Bba!}yrY)E z?)Ir-x6>4{lmlN}QS7Cgcv<SI#9)-uO3J{`s&`c%5FtEaT!2hH<CXON-yqKEbe5&& zX1w~*t9;mA?D%T20SF)YYx2ie-jh6&Q7i5NCA(zIm+R)Z?aEx7(%pIUL5d$G*&Yww z8x=1)SPHyHJMrfBcq+h$!S-{8vo$TBB&RUWk}06_Wc4(qezj%Cy+9^gA63R8I}bk} zb}ff-PjfwRIW<*kWa`(8Ieuy6pv?w0WxHBdoatqBLtsrLz@TO-SH9`);`Ed7F7J#U zBVJgZOlHA}U>zdkMA(VUs2PX!Kc=zo*WVtkShjH6VJyi8kcCn2X!)m3-ISHo1`U*0 zj=N^Yy}|RFE}b2&Cm1MbF|^-5bWf434{OK8d3Cst1^h(dpm7J$_diq;c+eR2>v|_( zueVrlBAs;Mp6~0N?nu3lZ^qMkfz8jiEJnTlRd^_WzL!V_>7NrBI>ipXM=&J6XrqoT zg$kLWw`uW5<e<ImGVGkwM<SoR_qt(s`6Xxv$Q%E{wDY^!|0@-2ss(SR*m>&`v91H$ zxT+CrCyJNZOB++MbnGneJu)5cA(gFa!)ge8381-SoHE~a+<EW%`fs040PhSpMq8FT zV<9XvcHomab1Oq&l`xUs0^;KfBQK@5V?B93J^%XHrZ=czW9jA%9UV77Es-e+)jPiN zsjuwzcmI~IiVHvziSqpA8x#=2sL_tgDdJm_^OdnK@QJKz6bbmXaMSI=gT_)<u4|GM zI5a+~f2>(p;qHkYY&BN|i+fXc@@Cxf(no;@VKU8Xo`Ltf1ieG(hC13irl~8V&SN*6 ziG9A=iVVqiZhOwc;H;Wufpyx)BT`N8+b0Bte+-5n@R_|vEAyLaqshXNEU;sCy-fEC zclTxKcs;JB02u0z&U&fGqN%eU+rj>5xqJ{-JpBj*NH@D*^Zl}Xf}u`o44NL!;LN#Y zJ>ea-vW|NA2xWNFP;K}_^U2%UcQn#PPe8#y;bUBNy~SX<LExv~McbDK?rEg!#MN<f z@4L8K^qr;3Mx9)nSHFMkBkkNfFB)5Rkn4Rc7*`nx<wHNxlvGgGp-iGS7p`tQFQhM! z744rIr}8;%ARIyw**Ro?!xP<RCPnK-O$K})PJ~OExwoSv=ScTh7tLR*$NcSd%aWIA z@(x8U4CWO-eVlMY(oiYGU}tF%?Ebj=(dSc=uRuqK!T6I4i<%Xw_1rAdBn{OgowOqk zUjOkq;&H4;Eb2zdV6xt`<kLLnvYLlLk?;n`0o9@Q2qA}J*m@pZyv`B|RI=Y<bXrV^ z(NW*{M2-xazQhmd;-<la>dFW@ZQHr^ab4H#Hyu_>s?QLR=Me4(!iH8IKP3b^Yz4%V z>!(39B>}xsIxc$WvdSR~seGvs0!vC&T$qv=T1wENSjKccjP-Xj{0j6JKn=&&0O;zM zJr&!{dT`X`dqxU}@orj+Y~|mYalKWwPanOTKMkw$i*0ViKskh%i-R#gRaL?TY;0bu z5ch|#w08NHgWh-epBu7AhpHI)UuNPVFTEBGDRmcr_;$N%rhOO38_7u^WWuNFbCf4c z-|S$^R&p2$ILrfF*|=>zVfc~lMjK4fz)h^b?}Mf9;+fx;nT5lU6jMA*JHSv*Wp?S8 z{#RM}=X}}it>saU!jIf=i*+_viw7|@l`bqAxB8Ech#ee#vL${0sjDnel@4)=KD_N8 zKv7B>>`!KhEk`|xTiktj3q5eUM!~@G<u#+lnrvH&BDgQh3peXTtK9euhEN|SI82{A z-3Be%l8BSyk=tUfp{Wubn-?#J<vE|dg^CI|{a_mxfB6k|@brZP)6!_5-x6dw$H2?E zwyPV<7MxmEFTAsTFYh6;7xJ@ut3vi%l!0=~#rMEOQs|bRPh5Xt$g}JuMp$J9En*@d zA%*78sy$R@*cMz6bD=-G!u9o-YXcxR>{x4yfV!7fYeA><zEtSF9&;X!)Sxx4Y_FGn zNweP99`HWpnPnIWU)x|@e9_>{PWS_=$JSl)nvXQkN>)E<#}4}T^utJn4m5Nf4pn~o z#!I5}Rc+SLI-{<}Y)Gz-YHQn>^F<Oq-1?cYvS96jv9GW&3`Y|}zzA6ad^)n<>^r4= z#zqcGSyjqLD%1e~j0(AUj=hNrnddRt?is)uNgP@o42N>8gh5}?LLV77k*-w0uCun| z0<R$r+2U&i$A8wP69JR<O4#xONEiQgv%N*f5scLJ6Ys$~5O`w_m{dq=J^38G`jAax zU3IkPT2+3{4QF)q&s{OtvqyUT4Vy|mlJaex<H!{<Mb0Z8(V0m0*S0a<6bHVFDry5P zGS-YYavwBWWJ|8Y+w!<s+6*Te6ND9MiZKz6&*hFzD=u+{Q;CO+Ae^36amW#Wn%uhX zAn~OQ4D@zgh<`i;i1I?%)W8_!tExJX9%#Q|rgL=rjPdF;Vx<=c3JHC9x$|`>c7Qq9 z;d7}Ia)1GSNfM{6$m_$XF9)%`j&5QpO~Sqq$(Op>EA-&~o_mS;+))%I8jCCwt$gS4 z1X#}s>Jg|nWfE~50s&0ekkEa270L(M`U&V(oXh}2Qs0prAQwyNEcjcJ2nZgl<E9jv z#kfIIn#2F-ALLd8bV(Q-OzHjED<+iI)E{v6P=&I3ttWsWQG%u>t4#NJV&UmivwVn6 z#-!09&GDDzU8CXfE%6_^*<lRbB$c#%C091?dwe^OR2n1JkDs6|6*(ClE#%AP15{2> znqXF*hL~bHHiMZv!0I+e5CWv{O1jqaXAmC})#i5WxGLQwW}AYUutFoFOKyk10;Avb z-UzD=Qv7g5yG3-h-j)6fz|s9*dPnD5T8$U1J0HRQnJ%DOyRld7dQRQYu+YS2{N*dX zm=Iu9oo`;1_W_uZI?W%B%$i{Lf=Xkd0#OIjD_qUEm6O5k$GG|T!~f3`=!~JLmV_Gf z)m%gXqxI5;%!b;PPkRM|p|El|XTkoA=Z&u}LJ4?~8MT(j4U<GCFvD)b0(ceMN!fT+ z^~TD<ik`lV2yGr405-$&oCBHNx(>Eq)$KG^)@76G#DRw%7!kJ;0-`QPDcwh&e(iY} z`d1_ub_ge-j8M-6gr75PRAHrBckPgq);=n<9U=<4JZB_yC+OO>M<S9Ok^_lKy?%{P zS-czsS>p{7`W{)gh`<p_hy!%Iu7e>}fw`K;J6Yk<i{*UbtY6Sjx-vwQpD|`rjm_+; zGNnjcE-g9-s63Cd2}uy<zHhWdx+esy6#fs;M7b@@#eFu3@j7;Q(umW~j3ewGhs>f` zsBTL()3Ez#!_M;94Q0xPkFw=Pj}eH)oo;|(-17)L2yneYGojQvw7CtW4S+1hJblQc z3-aJ$RFHpPPsz$-p#B5&`mq(UG)tN1(mK0+qMCc-AqQYO1rg>1UTtx}ZU9)+^Bq2Z zM@U*i#+(@+!=`BquwP4H0CALCgUQyy!F#PA-$N`q7?KO=I09HGgHq(RIkfX{>>*H; zvRsR6l%&n-n{V^q2`ks`8T(`KJP#lvi9xMlwYIid!<l%8etdp;7>JCzGs@7d8g2C0 zjn*&z8{{tPnM@WNB981HJcWo2;UT?y<JOz38pXh@Gx{yJ0<HJ&x~gI6ZFP0ayQJ=n zOlBI51#<l_0DI+ME!|6gp%DAZU#(~*Q6tNkNS|G&!zo(~gp7HtRc#pZwhdBFP>h+d zN-_qg{sp5WwLj#Kq#6=JX4OC!3A2Z<Qx$Y?b*cU>qTvp5idi7TW3Mq{@rrTY9@n^m zXp6AnL!4~qyQubj^K>I+onXfHoxEZD{(8eOy_``#aAAuVwWrm~un-W=tP&(V`v;__ zGhc>`D;S~51y_5psR&TWKiP4Oh+(!NiQ6=ZlV;yjOK|H57HWNc*NzJ&$w%`y`(lvr zif(w_r1D+EDWbY?3>mWRct4>M?$<qol!g_`o(VeHFp<($6&Wc)Ed{jhnshp#6%jtv zI*B9uU*H%u#?FD0XRijzp|N!uRkC`tU6nNhj^c)$_`^;q#%DXHy`jBm($A9oy(Yn0 z)iJO*rsA5*GxrHXBpPODRo<;t=9rd29Ds<)38G_kK}&Js3I9gD=I2ta=hynkF<uhp zoskgGF8||-e8tt6RY7G6o2X_aEX~_(hD{aW%|HTSZe`~7FDwl(FT>E`+(*Dhf>)c= zis5f$vfvR)BZp%oG*%RjVv@jWtU_&9f0Xu!T4S9phjYa_>cTz8HzT0^Ag9sc&_`vZ ziC}VU+BJN`h^XND#=+D1GTNu*aA{lHJdW9n`>V?O!#D_SU2@@yyfUH8B&uB>I~@NS zHEH3cnTx*)q8dle-!yO&`IvcNzS_lQ)R`$2Nn+F>{fF(qY+`SWqqy#U31*}0I7?o{ zW~?3jMm8?Pzjh7@tqBIH_2!0y6)>O8$CU=94R=S-HOd_rDYyx4+5<||0rLj@vpW9D zumFHjrW2&EWZNlW3$8cmR%NfR$9(PA*?D@=+OJhLB^<qk`!ss}x3<KAm$-5pUQ2e# z?h5_VX(;Hhp=nPxKVC033SRR;Qf)ifR4dZ7*>sgA#wM8g6Mqb)C!G&HqxPeoGbCL7 zk!v*~;25ggh?9IX_|Xac#BJO<EBQ*JB`ol&5nb&d`mL%&^B_`|Ek05doVifF(LKJ_ z7dK8d$cBnP+<Q0^=?}(uf0hD9;kqwTvggZqbfrwl%OXbM6CwFX9+ChV%8<3Ureh9q zhmQBkfCVQO7I0?juZg(S*pH;F-yheuo=C^?dq{;3^G3>EcZ=)iZ{Kd@2g2mvz|Wi3 zuaF`&arB?ebe(0T5`N4v%2yCb5{5sd8=KTm{P-SFh>S~kgg9?yrtg@R_W#*dypguF zhvMWKRL7-7-1?v&c?U1<vm}zG5cnVPcDZn<E2m!h7=Lu!EZA!3&};;#u_(s-!-RRT zzf-z3OQssAr)ve%{6P9X6)StrlJf}3^#U-77*>y%Ys=RisFdCe<{aoN0zw@rk0s%A z9kT2iwFLCcPVlTPv==wW>?50v2-nLhvJkt`YFA;y1rtF*`UVthJ8lm@QgCj4PfR$d z@TBf#hx#R~{>3s|L<$vsAjx>BsL>zPn~AiU(?7Y>H3s9pR}O+oqS29tl<OB+GlX*K z=9Zev;X<vM-RkYHxDyCCAXfRgQ|rGlu&5d@&I1}SjTBl-0lnx6D!;3TPsIU(->zQ1 zfxnojgJn`m&ARYk8ntQqkJ+nqr6T(XJ1^!IUJqUOe@huxqd~+mp0+(OKyBrfim^Q# zAIooy1WQ~4xb~W&KAYzicp&*-g5YG-mkrMUJ=_(eWMPX=Fo>Xd$|PQ$Dw7~U)a}Kk zPUm!xr}sh5?H~tSHi6UrY}DvLBo6e)>@>BGa=|>X10nnRN;d>jTD7~U0JhA8qt9J+ z7-N}m4zw92fuZ_r*~MpYSZ^fQoz>tW5w4KgJpu~LpSAG(uap@?U4B(9Q5MF2#6!f| z!BjQCQ4l)|K$+m{jU5&f-h<ec8AyPHqhu$oTD6o$$V7^bt{v|N3R18CzzYxAyIj3C zAi_33(~$8SiDJR`nu~;0%Pi;Oqrnt<8Y%#g+gkrWfmXKh_w6M*ZXLi{2~SDs8`(1i z=FOWGkdHc`%OkOk9LolqKGeb^J;BI*#S2G5Ji)TLZkLMPzklt%imPSfr7)TsjQ$aR zgFkhi)xn&$KjyCrnd!n7tXy-jc*F{@)&P$E=Jp}2%~@Esi(-eS!OAC9=fJZzVrIC6 zkCaj^rS9=hT77ugbebGeo7RIs*DBWwy2p5RjtCOR+Nt83!}-`dE>5r+-~iM##q)Jj z&!6E+g_-8o=a~R*-cVBGD#d2cK9k!(RU<yS*vv7Njfe*CP;!;5C~ks~I>ZWH@tFNF z{&7`$bU4_eC@bgw5D<}Plfl^MwCsm4EQvZfXEmf!UuLP$0?Bjd#fvBUZRzdyXZh-8 zOV9P@=7Z0Dp<NA90huOsKJ|IT0Piehtptv1bZN;4MXQ-q5&{$+wXyQVTUBn0r;LKu zvgDven!sx0fjB@ngUSgNHim-gx<ioW1Y2M?MkZ77Z`1jxRdCO#F)LwKjbQN>f1*<W z1Z!p%Cbt{;_iFSsRE`UyMq?hFd`Yf6ySgBSJ$T@NO(0`XJ@wLj;5-rCCm^b-%7>B! z8{9fEBDzGBOtlg;z$%Tfmat<tW-oOu&UqdpkuBW*d9{eAtz*~_G)!O5cO2&9u@E$i zSf{G5Rl-aOK5`zB-w7T;S{_6yr4&#Cq+eme4Vps5xkNf$!cam){aCAesSW?Yp_1Bw zN1unkvML<RmuC!kDAI9+VB)WZ1M&X9)y!k3Z(=#j^1$UnFI(HE?8TK16q{o~6QiKh zwYkyE9Xsy0p_vZtX;1tgVS{X5O6DbIuE=DrHWGBI&pAQ?Wx0v-oIw=0EiJd1EPxJ{ za}BciJeYUz_izRR3_e{>Xp<8L{f@Taa>d0DaeD}ctaogn=8V@z9+GAKwmt*8;lnn3 zqhHpM%hafX5Z2;KkL>=vyMI5iQIkdpGy*&1Q2&KtAGavJk;fay__o#4Y4QI_p)dpG zJ}LkJ(@<MJh8!Nk;&74!&+xVFgv;c`hy%33LkyW;f0X96&e=VKGmx*h-jJs?BMxM3 zbSd{zAIf=4=fsYKh17Z6e~FDQo=zP-;7ix(B94V>ht^|vqZOrG7KyfSJ@A8s|4rHR zX$3bG0R7u;#)x}DxIw?=>32pZK}owqx{_n7@?KxnO#4r?NX47Q9ZP9dH6jE&k(InO zVN03Y+OOxcjox+sqMNLI+@yx2X7q|Wl0JZ_0Lc%E@)FZCSO!>-DMd+hT5Z(|bXXeB z{31Y}25H?Bp`2mLxT01-_sD-h_%3k(P;U;pA(V^JN9FOD-*wVB{%Ag!K;gVFdy*iS z@=hIw-L-=k3(<|+dZv|J_*)g;V8;#c4~XkP0h--e+zrqpL#Xd(9DyT&QK4t|m0B@E z<Emg5XJ=l?O#C+SJ9!@hYB3xmzMlAk|3LGaVdKK$-9JoB{bYgigTt^_>jgVmD{SKS zY)q!2LtU@dEii{@Jcd8@q;?`VETvw$r{>1hSsN`u5O~^pJg@QcbKq|imaZEk;b*ZJ zmo(OG&SHo|B2}H5Iy&shheyrzmQfwjJpPx?*c>vq6P+ODM9|iyRVY`FU?c_V1kE`+ z&Y87?9x2^sysC%RVc(<Q9!)vf&2A4e=Qf53JwoU1Y?kfkxg_2o`1f=%WHM(WgQfgB zDB(HzD+@0c=NI1#m}_-fJ!HJPKK1rUE$_GdFQO-+F|Zhw(td9orkxOsht0SpwlLCo zaRlLgtouev0rrMjcvo6q{hQ|gGTteC@miR)Zp_7?3#>cg&~j>_W1APB%ttD6dPg@l z_da3vu=X|Tuu-?ct@biyA+xVm!Q=4Fsdv8~3a?sdMdby^c2d(P;r?`0*sV1VXe(nK z?{=;CJKy(GDE}=NS?uEk*8NV$ujoebRnvb@t>1tgyzLa6fj&Liv-ktMx>naZX+Qew zlAc~%8*o?~M1b6z`BCZJ=`+Kri=(vft+-~nsMB6KX4BeeY;wr@)I$~cdtczKdTLx2 zesm~^SBI$bttLlPucPT*TB{&Th=5J#C^t@@F2YSZRk;dVZqDI_B1YFbx74i`uep`@ zE6jp>{hUk8@v8w09@lH+%ug0c9efz-wBPy!mh`dmqQtOCB9r*id<U958|ZTQu!yuN z4i5f_v(Oi3QhI@=#t@*^0pG=ai^Q6rA(Vdp_#bd+v`xRq^Rt70{^1kDYMkW0bcNbm z=k>HYE&hnq)v7t&7ECl*zm=U1=zc&$YwjOK-xrTBzAF&b@jynE0q@vl@xBhED7G0- z^UQHbKi{M-BDtejFqzTTbD2lmdP8Tavee1z&(qXNAA&lY;)RVD82vT>xJdKI<xmF= zKE7)ieYMsGyMqF)q(73&x>`T%jWR%b{&8^;GRAe~4=}gz!jn63n#ZrWW3Qz~385<3 zdRn!4d+LP|<OaX0Is{C)*8nFbafaLyg2Acn%;AJ|Cs~wTgaM^5{R)*Z)4(dj?iKA+ z9Ki+uXv`hT<Eusgwx^5iY`rOnRd1Mp3{rPKTi~Yg!j92nLmWo4iVrumo)vtQMZ|mI zk;<COnhOd9uUwb1d5;Z7dEly2?7!c$DiIVTU5D1Ngr|OB#nkm)ZV2YpWf|%;YxTl8 zn|WR!v|BxxIqSP~8Ih7N6|H^=3Ap4GRB8{aZJFQd#7p2PAB1gfe!-|R1E1}}0b&G$ z>gUMbzt3ecatzw{!hsm$CH%9;8tkFHA4eP^q;2f|vGz1oX5lp{S!w-++Q5O@Dto(S ztINSa8uyGXCn$)C49(-ek-tMgBaSrobJiu^oMj=W^%hW4ah!e$GZhz{dshv_BU-&V zcvfxb=j%%{Q@}_GggM?Db8{e<rqu;8``&?^VZj5`i2KU(c8QKK-`TuW?6xo&-K--o zbb74Jav}_f6{)A+`{Z$kkR&K!slfbM<)L+#JN=c8s?5IjrgWs^V|C3v8YDNnr+7<R z?XyK^fxmt*!&*Y0Z(Zhx-~-LaD~(V|!%=<IUgg!R|2#~Txi6!}K%n0|2rY;bH_{kH z(baWHo@ox$%uhiH@!IV2{{Cf-li6<`;h#=d!zPxSlLBo9#38*Z{`?pn)gJxUjyJjJ zn{e-mgdQ6f$Kj(Ckp2ogD0cuaSvnz5Q(?>P?Ju(qfeIeRughb1a3$&K1~)0^uNvA0 zD1YtfBvWl)Viyhh6Gs*`utZfIR^24WNTR@5ISeBnU(Zqi4|)6JW8DuH|G#_CH6O2r z36GG&Zr*#ZQ;T*QKBlbJ4_4--Lih3&$2ECjI~*rlJua7AwKh;E$V~9A0I}r3r0dBc zyyrKAI~Fb0-=6qa5<&#nIn+3cRotqSP<OC-Cm925960i|qlEbvk-nUa{<H;BXB?y( zWAgwF=k&cO<BLxGSMl%Lff$+Rg`vzLE|ISdjJc)Z7bA+2PIlw!#Dv+%^*pHD1Q*7} z0(4WZdgG9&Sy*3OBdiGdcPtmY)-nOUj1t61n~fqL@e;M~0j|th^OLDuEC`k?2>Q{< zAbG0r1U-D3MV&Hatmi2qB|Er9Vb;lj*|4xhw@$!8$iMi8fFyxAGp$Usj}sw!2_)N( zFAOk^26o%fKRO<EP?BzhP;R|UjuLM;Q~?ovx3S8#By(fk&<g7(ln-i4(&peqbxw@* zyax^*NODTdw5R_HKdm2bkPXZ05ub{x>_OJ*D{{%R%fZ96ZEx}e&lbP6HBErCWSZ!o zmsY*fIH<3xB<UzU&yU#9TSWGQaT%+0D`CgYb!5ex^CjsP4Dg9MBNqQQFrekoyj{o3 z9o&L(gM=7p4FI2JlUayRY7h-V`=e&TC(yK<7d$kTvA?KGv5ws>;_~`4Kdve2;m;Ys zEs=i&1;yb}(&i4NgStX1oh|TT>N(hGE_oHiHvYsP!FD5}Xqa%C3>l+#RrajK*=jAY zf`}>JmeSh9^91ho|3={JcAYl@e)I&iQ^5%dNO`{&nfsOqs}qm@y3#KRrq)b{pBC}d zA;>Yv3f5TutqTbmWP%ph7uT)G1)i^1q{g10$f@V?22LLd-Z9d}UwM~a-t~al1_rP% zsOK779o_Z7f^mBz=V{Fm!t{pZUX?+n=<UBd0@cwYp3Q1jCS+k@k${7Nw+*X&-L_-M z7Q>JDW79L@6Oi;43cKcXf4qhC`w`0Wn@`??Ln>QFhDpWZ&pnlTBxwx47_ecGDRDy% zUD2&W;n)&1)$3)lL6OgT8m~#**}bYbnlifm1@V9%xGMF={1sho+YZ&uYiqlz^xTej zeqz!_Sj|TJR?*(d!n`7cF#|QETJzskHiwqM`cmhON_3!P$lO&`<l+K+V`*XAj!Qjm z2(JU8ec(Qe=TtR7hs^bxW+G9mE#v$5Ot)aKkW|S$03!m2!r7<|gMnp~UA=T<uF)Hh zs81{aL_4*fpRoZn&<3NbYDWB{VOnDdZ;;bv!#!heJsq&FAL*chKL!)31B4CG<I7Z{ zJOh@~unwvl1ym_1(yjKsR8{%Y7Rte(p#P8Gy6G3Xx;|J<0`*R5ho!B<^Po7FFuR7~ z$e0T&&%Q>m0_E3PufzwOz3Nc_kKZP;P}>2cGI}lbum6IP@R_2Ze?i;X0T|P9LlX`+ zuou(S_LT}B5=^5f0GSqW6&kNr{#%Qscz|U*-Ybk5TWw{djhzRe(ekK;<gLcsL!T|{ z!a6kCCfIoJc^&^Hsnp}yb5+-iQsWxj(?y|>W~_~@y)+2tsfC7jWmUwgvBY}to0NQs zKRK&0p0H$3%F(OhwVclQqh$MyfFD92ya=(eb+*fSFqvaGY&{PUz0^LOG4rL(PFE&j z^*7m~!*D<Lpg!*aAX$sFCj*Yigq%_ALA1fs!(UMW;T*;!$iVSfP!<r@V6KYyxe|jc z|JI}S!1D@#Jrx6@NRf4wdC`ju%*RbSSa}^_7S-Mn2*!4Oem;fJu?JA;eI9N%?4-cN zd4wQ)l}eC-ueDu`jE_VQ=ff7+h+KXB;&ClGf9p4W&Ab|)Ay__IC{!vVj)`Qh(h5;e zXaYp=3FEco$^&oFUxXclbWi1RjS7#|?<v|pvU^udD#Nj<6?swZtGvACGUOE^*)gG9 zHbfLA$tZerZj^P`{okB+?!Os~sE{{heWIbm!D&mhZ;-EsCz6le`d}=}?oT#yL`+PR zA3(OlUWLiEv1(zZa(?G@5E=2>d9Q8qAR9e(uc$tE>E>Mte?;_)oOXD7RW&F@n{S>C z4e3YvEKi_o0K<FcH7@yr2~5iMv}@8877QER2mR<@TaTdxL8792gMVW9!BQRA)9Cd$ z0X|t_em&|R3tXsv`1+eyP$>%#D#PH|H(ma{)0GJapx;Tac6)hxi9vuQC>zZ6Y5wL> ztCne)n@26!@6kk5pP?9e4Dj6+Kr=K{92Sud(iI*m*yMUbG*&+>E(uTR1kVE3`9F1u z`=pH{v}F5=l?+cfopHp7bRN5SH(#OChjq6L{Wqx;`*rRHBIy&1fBA~m3P^&GJ;!5L z`Sinc$Qj|I7Y{-USJd?S?{mAJ3SK2<(>{C8hX2*OQGclMVE3DM!mGh3yO!0K<Ho+( z=h=$JB#g$+omOOww&{C%YWXG2)snS-*o*z^+i$+=$@&{!$v~o+)Prxgp2f=K%Pyyz z^u(<hi2MlOcO2}UrX1HJ$1Xpgs-1Ejr3hlI2!wTMn^<eC&C4vIbO&vD>2?&GNiw#n zC7%4KeQf{M?za&M!}f&)j%n?p7ff0e_S;BeQ{f9=xl~6bDg6>uq_G@Hh@7H+q=Dt3 z9}uKTIE<;VI<KOkrpk8>w~mzl8v|W^YZ=9iYKTx&Yp`IE*Ox$<F)vIZ?YeJIHuK*o zCR1jFI5xDW<kZq#(CX0Ux%GGgWB5kbQ3ca?_<2uPBVMCXPpD;J&ilxFp`n|HMz=C; zTR96(Vn<8ku08C;)`aT?0d(`g<)Vu!Mfqv|zkv#%sAHyCyBk$92(hm<*|{T$VCVfo z(R$__Z>Pzp{Z7sDlW_8+FFxNh$b2W*0h;0O2dceLO;XmHR@IMyzClgn=A83I4xO2~ zg)hul%#=iOqhUMA&J8rdlkT*rdOL%B)P!^Jx#iDr^~Ig!2_9rd9d!~9yEh;-7l5`i z1ADP)jLC7TxLapp)T76E2!cpi+~UltpdRtJ+;NaJPU{vAV<U*>;&iW9`Fp%KUQ;$7 zIC~f%kM38Zq7*uf-18AE1<8`SEU$%Um&5n!i5Bw=F!cqnUvZrD(%YU)@@YdWSifb) zHdHM|zP6#AmEYDC$t2{pl?r~;zHK(T8Yf1VjtOIBELHDbEp7kSrN)O39?H!ndmlKd zy4F>_PQA5l%p^ynWE0)u2i#s4T!|Cg$qFzPZesQJUO<a3;4McJY9a~cH*-WL9bQJ< zL3VMAntyGIk->Y1l%<q9dEr!u)W~U1k{h~i@|tF_N=j*>OiJ$dG&!`VhU-lG?{vY3 zYD^kBt#w4uJ2EoTQNvY#_?*<^?XFmnnK^J!E`>j|O?N0$&BNEr?6<U#o%16eYCpG3 z0fuitXIOHHdb<hWucY|tI~aUUIcCv$#BQ3MDR)>rjyT@6TKcc+$)|@c$DTA!>l*cd zY&tBhRQpWUSvkRydMQm-d96+?<z9KH#OD|BMViX1I-<bRC0hB(VzGyC=EsZ<8kB^! z9y+j0*XFlsmkbadH{KurNPUJp+D|x>5NJsIY(Det<nZq+eVvu8%n8+nbRG+FIfsDn z=|PUEt??{UsjqLYV{n&>r}5u!<CNvO%TW})Ad|2ipZkJ95D2HRO7H3v-T5P64Kd;6 z4~pDZlKQ7L)XxF==#Lu#t%nYrOpfEnBW<(sfPB=@=H?uu@OoYU^fSpj>{C|s#de@f z)gVd#E(v|M!5~K4owh*-i59NXb{9&|xO}thtxD7$0qEn@X8+5A?=5Zw4A|FA%lXrm z=01CK2Dz;(XmOb@Tcxmbe^l~MT$3mLHXcZnJAk%YedVMOZSDK7T^`HZK?AL28l;)N zhQUN<^}|=<)W5nA80+)*>wUQH`kQy2vQq^&-fz1u$Y^=r`IRy*<+$z5i}q^8=&Vp8 zc-#(6#bu5Xr8v3UZ+qu7Zd|``!s#i&6M)~GPWbs8qmjC;me6>&8{o7d;vCCN%q530 zYW3nf*FZXsbxdewT<h|K^D71ea{T_&F82LABx@Y~{w_aR%3pb$4?C^GvxSo1-QwKp zNoq@|n>tlVhksD8#(7<eHOa!)q*TkX{F^K@er1Yly}=llXMO!qGPGF{3zi7H5BSv- zT%>9ETgC#~ANjjgZyo#zNo4+v7!5t4U^voox)uBf?)ZIXrI_o-bXFWR{s+7&?-3FR z+&eXxpU$(;NdUiD?v>U&i5c^$G|ttbzsg%k+VLl|cj`hJ0RV6iI#rRE&PQ7~svifo zH!uSY0+Z@&8hE8N8gmQ$0w_7*)jnOdNdZCMAML@}JC5dePBm;W=A+<l;g7>Y9v=LY zyu8Fr`2Br@Xa4-1y+bLOSheIW+g}2K%qR<6_~lUhg=g#?{$&y~1$Xz@z3?M$RulVN zVtXlyv9gQja=-3v#bN!ba!MQ}=xW^&dviZy4j+~q+!D1ARVL!!`XsEEpCV|`Z)|@# z7r}xM%@J6J@y(j$tgid#MRlHuC=ygz@DYG{^V#`r9|KvIzQ`wN=kjMx)a2Rj2f^<C zE%N(u3MTbJA*(CBmeO14t^X<*mIl4(JTj@WExpAX_td9cIVgCqS(PWm?hB}F#K+o{ zSyhk8{Y829`n6s|$QsYQb)oRomFSGI>BoJAeEbz9c?>*rHTs#Q5rzu_Yuj8C(DZZ_ zXiEDub6@4hg`{uIA3~(edxNmME*UZ3VLo^Tg&C0xXr@$Fzx3N#-^B=tTAxpEDQ9es ziRMD|5L%u+I}$n<?mg5#@&B|dlsYQOUgmmx1Et2Db>jKIqOh|Z0#0VX#0NEeh>gby z9##h!uvM<+A{ixlrqQtQGW)*ZqP_-RRcB@6E$)p0+Jl?Q-?J4lZ-ioT_A2d8SUkaK z@pO2NRDgx<)=!joZi_$S#_iz#x?Ix#dT%~5;Awm(9sV10Dz))+jO#Xoz2I(><JmHi zwc`M&Wjyj2HAjHV`r(Fhp+9!+A76xiG%2w$w{J*#4aW0@KQ_KqJQ=rKe<)rv3|Za} z-oX`y^$o4fG{j++1t=%r1=tKc%$Nynl^9?Yzf0;iA4@JN$qTN000JOtB0}dKY;mjd zgtW!(?;SE515CGzbsfSe_xdkF2V0e!Wf{5VdDlA6Np(Gy?n+lTGu#h<`^A5)ME0r7 zgb(;hL6Poz9S2^;nV46PG@lwgYP@ktCtl?JUV)b6{3Tx>QQxMb*S?O~{{hW($kL1G zN(Y^M&!EW2+#kh4Bci{$1T7@Kw}#xx+^O#g?5s3$VoQlEKR{D2KCf(!zL%QQ3F~Y} z1gZ5KrkK>7<~);mnJqnnh+Ehw=%0x=nXB^VnuI+DOgr`Wy`?^V*Z0W~mxm7~v&s}r zeBYmHAQbpc(3=dFnp|@qpaHbZ4``db`NElpGE%a(w`?~0&!v`oW${$d&uhT+b%5B3 zla>C@Tu$7X<kPK+;0%{m2?-?nHZ?e#95$2jDS4xg-GJ{UI%rKjpz^mi7!?Vi^+arT zO66ai1%aZSBHTVi;H@3!yL*<H&|i~uD!>)n6Oj218LZUx>bdkw_YV<4Pc!S=;QYGi zvBLDBGxVW~tS)|mGAu|zEpbiktjf;VT9M73rZnV^)wl%nK3#-<o!*?|To-loEj8I$ zO1uNVs>^DXFyqudvokiu!$~tvZ*n%@f<={BuxVh&QKaQc{l|%k_#iXo>q=_rBVFQ; zUEofDcgRKgx+?~sjgAF6gLhw!$KI`43M!E{qSDm}SUU^(D~~G^S(4qbuB-N?{;e@A zg#a)#yfJ66@K4suE^gCaB8W4g-4nY|86ZaHg`*_;IGgs*AdkJwW{`Pqp_?$OtyKX} zY;AMlJKpmjcCL<x?6r=Sr1r=kiJ%=7$*8m$U=tIP-xr(N`7=7fNLvdD6qN2g{8R{4 z<I5u^>7yj%?zI=2)$yO+AGvhnjO7W<EgIr4)+My@?B*hW<2=cC#LU1C9k<ZeaMvqV zZeiz|Bk5)D;O+faJY$)MR)4t)M*bh?Dk<HJpTeUcexBUy2j<-_pgy+aRK#s>l@G1c z<Kk5VNAK6sBt>S2ppoQoJHlg^|4Bh;*6%iMURbY;Ds1v+HP_D7PYv4a8ENyK^&<D2 z*f9KMG!Px$Q$bZZI{Yr?PKV@#w^RA4=jPe1AUw-sH*yNE5tS4^Ewrlj3?9Ow9MpI} zj_MfJlAIPjM4Jx1sc&vIyS<vLw)OZnt7VKT-P*&|&{&%4<}aV<PA$K6Ga+LK0s<VA zKh*nZV^AAgoW4?1g=c@=ZhHp=_X8m%b88d3kX@X_*`{K}lbSe(LDZryKT!2ICP1T+ zj3#vrzZA)=7hD-)Ni{c@j1unZ_o<Y3n##DGsBDwT<eG4+>JaBSb1W7R#<O0128<P- zn?`+Y{7@7KRwdv*`wm-Vyq(^V!hqW?YT=s8^Xk-p+8)hI_<7p)*UdPG{7lpexGj0G z!W?Y2@~*b_kNGNE8!lC42I&a|`NL9QhDBf%OY5bv>5FE9Y)>gIUM8bbBE7c<fIR&` z)H;u87Liu*y7cQ8MnKpWid-(*q?hK@2LO3Jyh~YU-epgCc=xHCACU$o)_d6f;((qF zR~1ekF@YUAkT})y<!K2)Y+!d2zFsW+3tkSlZybL2Pf>@s4|K+!n9ZR?0uSBYuc@4o z4=_{`ngz?W@(Zt@{dC(s(<Fx(2e$a_{&Y=YpTIAXvRA5Ouh&TF(49pxExv5f=412n z1U@9ToXlpQ6qQvdcA%{7{UQ6@S5bm_A`RN{BIP^cEmuaKqbXxigpqT05W2o{<58lK zE-0w=2%?bSvD@-*!r(p2&RxNE=>ID%>9Z@jl=G5|LJfh76?cyX)j88m@EC)qX=dZ9 zIC`%U!v>>fbSxbsk)JA5_ENyZ8%szV2S?iXcdIT196uzy^i;ZgA3LCQ!rUf%s#;7i zKvP&er(r&}$LjfsXD+K>PTAg!J<>mh*FKf4Fy7;krC&Kt=`3TuJNMO2tQ*75X=PV( zuGiso9&|$7KMPyQKxHVlGtLg?|8@o=VV`^wJM_(jA4~`<N8s6k!jRzz6tmi=ywpD8 zm9^qSLUgaKWRKoT@^F2B;WP6a?u|)CF%EbXwCHp21BCFQl;Aay#s7fEC0x_<{3Y?~ z!Y~^x?6^eCu<y@LH;&Yst7v}jk^B$vnJFnt{S>C+ofb!IfP!T*rONVEbeuw`TCRy_ zb93zZLcn14z=_-Bt(Ix8s>7fpd|w51dGqnFmzWdD8`AnBR=sDBgM8}PBmhe)x4l;^ zGehWXDnqrwWN&_3Nd5=;-{9m%T-B9l49S}gpb^rm>h*2z(uyx`GU_fek3O7@HT3rg zVn#w%iTb#|&fIFBye%znf1!&`RLsH<2$vdU_mg~I8BIQXi}8tgR@@Nfp!sfKD0lu_ z0wS~Rvr$zC>Tz^`r|i@%_KS+D8S6A&nmh_62)Y*cRgPTsMAH9snihQ&ZDND6-|WIk zF{Aj4^7UY;1bG9Dz@)zIG`K4E1WVlK3HiBj{8NM9j>lqK+vZ-P@?+nhw?_|8=OoR* zmZDLJ!H9{i;TinxyRP|~kkw5VH)Mcfj8}PhXN+=}AaWi<hej{PPzpoG1fS>s;J3t2 zt9Zyh^$5~Lms@X6Rp!zk@0NY!KKQC@bjJLd2`Ll5$?1;VEHkugx5?*+zDLLH>7fZR zPCtK%Y-hf+3eN0-OA7T!u9rF3-CF;aFCZ{!ri;$aJ!pRWxGF983O>N?nV|t#8gKvk zqFo~bDgy&Fd-)D-Wl10-3ZCB{<_ft93i$t*D;%OeMR$J^ZAy8|kWMNEOj;~|tJT*5 z&^i={(Z5<OH?dQKdD|WWqIg;(F{yC_e2%FYUKjmC3*$9ruj=MK$sU^w>dtx|->+kx z77lXWi^#f*Y?)JCUz%ML-V;LgTb3d><Q`jjVgM*I??2%9nxPokpNwso{+C~5d4(q7 z7zX{cXHqFtLZiP;bxirhYH=xy`1>d@gWI#=Hsh;^wM*>V_L<_<<bxTj;y=RCiJ0J$ zC%<oB;+w<~v$2FSoxx&hBLAbs%vvo(AagbNOWRz30=Sn{ZOra|qAA_^V|l_11>IXO zb=U5@IP4P4R(UiWzTOisZq@TMKg_6}KBXCCa|6X(V%91@48~2Neybcg8hZw;F;V5L z_Y{UiI=+Qw)F~-Kwb^e(D$4GSf7R-%*Hueolq1&HOXpxdzN{z4elrel)aJtr?L=&P zLlw`+)vd{|+C4vpEMh0hvYevKgD=$aUh0bfb=v6Ax-^PzsND9<*@Bb}5onLrf4pS( z85eLeHF~umh#Hs1xK$Vwbe!84zHsFoZ;Ts@YW=|ByW5xQb;FOm%5eP9EyOvn9<8R? zUZ6$22{IlS*jEju{47tbd0)3|248FU#_&Y#MCf)n3Ct8KeA{3Y?YdCI`<?d3hh9Uh z$zuInO_{VaVS-})7k`*3Tp0bO`q28HEAcmq^<h-~=C}P(=L5<^0!}ffX_s2szYn2t z57ueWT^EUb*Xk^DT^s?L`!A<|x%~R~_0}p{ab3utR|Quid{_!$QAd)UhB)-!)Atc! z#;*vFTv*^ijqkj(|JW_qj6wjf(Lv@-{cNwdTf%@*Br$*a?crca5;r+aE_zDC&D=BK ztK_+e$>j%8O@Ptvi~0F8@4mfDuYSpO8!E@0q>o(~8cZAe!`tI~#t~Z2mQJ$KJ-!*6 z^h~pESUlYd0Yz$p4SOuOY_`N<es4Qh<~KF>vjz2jZx0tYEn}-eJBeTHN3kh^A-?*) z#gn(1w9IRgYGJm1A>{=z62Go7+k&xyJWaN6ryWsVgzVH@kM_n=uZw%s)=@Smy&zg8 z-Ra$YNRX`T=jE49O}wZxnKPLfJ(__@f%MR1Qeo&(L;gLt)U%lb74lYbn#6}_nD+bw zNN-qqp59E9L2Sg{nI^>6zEYLhD;%jM!f!2O$bKRF!G-V{N}GU$m_hM{tC~wMJI*AV z=>U-!mG9$5)io6fHhr&&il1IxMXe?$o6n7qHxx?mFA^%n;?2y=jr0?(#ia}XJx3qi zA;iQd>XM#r`!GIPMytfts(-DYJ;Z<``}>-<E_tkID+JKAHzbk1(u~OU*vA;XW5*;3 zanfD?*m_9)HlD}c3@#9ZdU!nh$g0&1;iRj4FRbiBCa<W{%ec?*4duU?mwB+xaX<I3 zVx|P2lVW2PXkYJj(Vimh2qJY@xFG$kQa@jh+?Gz5jqcA@?*tzwIePGFPP;b3pRNK0 zP2iu^+D?2r_2UU5Dx1BRJR2&$cBBZ>nkW7CW$)$Kk7iuL=904*NRMpNJyO*-rQG-7 zbfX1T$RWLu9)0}2;&(<`<VpsCkyf`|yU4L=IU`;|K9W$qxfoG0eE0MUzywb&aDB$M zi&!7Y<O{^xb!D}9G?9V&Y<u$3@dj=SxHl^mw?fzzS>`zQvV!Oacj!w-N8(6D;7n9J znc6Zj4J8J*F#?)lHC!i8{5q-{rXB>5ioJEO@Z7H>Vzt^|+z4FZtYPXjO56SWGHFEC zbk6K+NfA^MbbIVZ+QA-glOVOJrb>Eg)g&+d#C!J(Wlj3qQ{@$<6lzflr0YE^lII33 zw0W($BE4k~YE^EzwDp~Z=hO!(xvmh<{{dwxm3{=BT-M(UHt3bJ>2%YWWj4ZFHJCJW zv*E9eiPR(wJ{fp9NMlR&6Nqhk9P=%UCkpLV+FA3J`Th%Y#u9IcaA}O`S3>Sx$U#F@ zyV$ZG*uDC4%}8hStJ}757hGh2eM_UXo*v(fL=1Yq0V><%&sd_s(Nf~`>|*P$J`GV= zRyB5L!!QSY&lUO)<cm7hW)O!K-2ag-efZ>M_K(!_+-3+RJAD+x;K#bpeErAs#N$UU z_1#d}-VaKFVE+U1_;&^^WzfpqrbkVy>jYN!zh^G&FRF~T-nr4?vCW!%kMuwM@?{8& zkl~}Yi=JT(SC%iU<#Q;K61K<geWsfayTzDG^f1&IoxFXGme9pr=cP|Z=ERG>NDh0! zF4}7PMSIFm)e>4tavo(#%&q!B+!fg}A4eodLT)Oo_{MCUvhVH#ZybEVYo)hLQzU{Q zD4hGc>Bdx@+OKJ$uRETzJnn{1AS<njQ?}dI{tJb6vuhD&3cL~Qc<^x4Qxkc#RHOXU zuiq)P@AFTpPQ;)5Md=vKoxQRdD@E_aR_zQB8NH;Q<+8u-j{h=V<!FitsI>=l`N{tW zoFSpzH_&L5Y$14np1mHmBd1R`?T2~&&ff`FAgz5qmyxwRmLmzM*8O|1JEU=COhj&_ z9`rv`IXCs{ba;BY{>Ra|2Qu~lfBeiaNiIcg*-X*LwQ}jhTxL_B+>*O=QDI6KmkqgJ zhR{bdgi^7oFjOujmn0;cD1;(&ZJ5Pe=RQ8a^Zotr503YFpV#I2d_3ctirYD)W<k>` zgOmCSTartSzJ>QhNt4d1D3`y(p;9f_l~rpXPXJV9AWpPYQ8ry(w=p&MEm0=+@$hnb z@%5#9BO_hPT8vom;-yFueh(9yWb7i<0z*0v&@>N2<)%#>ppY*A_>9Hsj3gO!;faOV zPvk?qeukh}vA2g|O6NHkLP7Gih#rw45Nc4)D8)F4A&@=^JiLHELf-qd3e5PD#$t6X zqDy|{@1hy~(Fy0L-MTWglS>l3P+{~IqPo^X7HPUWrvZx)YC(j|l7_SbQFm#{5>M)( z*RFENdNPiDhYEI<iYnkX5ZNv2Z*O9>A^;*?19upnOvoy#^*kqVLP>lSgrvNz77vx( zWwg~G1J4(2^L_K?5g?T|w}x3k@04EGUxH9U@*PqpBFJxPRZTNL?vL>u{@{~8g=8p3 zF$r9462|}WKs8MO#;LV4X&3M3(gQl;YyhY46dhZCEwW-SKst*Vf`*_zI_ba|?*NN% zd?``C)xx#bi?Ykzn+B|wG~U&cT5N(MWo%teA5iS`42Lyd5kU53AAJzU)C=3WTv~Zm zTS~;zmYV7;&@>U_stJl3K|nM+zZLjr_OK`iiax#~EX7W`>3Z7wG6MPtjpixV@%pm} z)wEcf<gbL@c^#Ok2ZR-~lE2ToqS`s3ADTJ8bNcU7n&E^gz+2|`)bsYzfO8WBDGVc( zGs&El^1fr11?0dI;c9VbP1OnAccA(5`_d&BObGA(&IwE?N5KDp3;6vHRkA$>uJQZ8 zX!>+qM?I7`y6IHjE@I(=<i_=zRh5k%I@M0en3>hZOAS3%T)$GV8NymBFbO5<((8q_ z1s1HYb}ged)3@{=o@9qw_ZR7oQb2}0Jxex%P=n?wDCrEX&g90ptPLofTr!ch#LU<p zIi&}wjcf9-xB)RAUV2G<p-RQ@*PW$5&BoqclG#`(xDlV;HgK{)2dB#|US*m8bAR$B z^jFL&P_Ttgi*1kZ*$3Oor;n`(3J-<CoD<gmC1ePMx+ynt$6SOTVsc}RDL#sr<}apq zfSoL<bkq<eQBz*VKA_N|V~GmkD*p$_p~v}WYK5;7jE;oVl>Y~ucP74=90Itvr9buo zpUxxG8rLi^CiO}h58|d!O|orf0jsPi$qaL;eMKgryk;2V1ergX^m9xaj{{NM9jQ&o zV#KP_z)n_k)g4YPt|!S|7B5PT9E;Tk5%sE>EBU)x_LPRaR4{_65|k2f8QYr5mgiKt zbJV!dK+?>HvuoD&*Yx%n2R-}>BbbF#pB+gU?Fao#6M*HBhK7$>D8}SSlM)81ps4O& z>kFLB%vfO|duxpRzV(CcA|9eRp~nzC_7mPIPbkEku)JM;NtuYb5)HE8O(N(SmqJaW zM(ufL6?N0|wdi*GJK(>E5?coEjMzjoYHk_xomy@q(=Cjb`+_%}E9_>4&F>*B+||NE zCUMP8U%1Ga7#5fd(K&U+W#6)Hmq$#lhx0!fo?i&ny6xo_u<F<@rEE=MLI`k<>Dt+C zHHXy|mdZ6qG2p(liedf(W@HCwCT35r@Z|;#&!y&Rq=*}&jkmRJF?tb#)fXlo8VXP^ zZY{;o={1GcxyL|#-k#cty;$9W2nP}J`8N!6794U`0`rOfsG8KQl=VVe2Lj)?=lCv} zaUwr=&X*=WX^JebnKXZ9e6MNzjiqRW^g62cg=nBm$CoZU<6uG2p8IgG-GEN3r3#zp z^gJ7*DmTCt3j)=Y_)k!3elf0<HWXZvV4^!TfC~j*!V0j@NV~yKZ2lr?W$F<`FGP4& zN@EZ(WVAWT{8dx9*P$a;Fy*}_v73LuD>4ZQ=(98jRs=;S%fV$gblnoFB|sVR&#}JI zbPSPl+m>9s!l?~<sJ8eI?h6taC=p`yi_Nt90}c)7Hq~VHc2DbOrZFu6ZIjprh4Xt+ zo033jo3v@S!KU;8ueayfbwKtK_3<CG>}&52!5T*#nGrDx@S{}8mjoYN2w7`LUt>sI z?}el>M~U`h7dt(b3NwwhsTjX>OSf(2%SNN|-K^#zVo<G)QWj*NCt>5Vp-)*jg2TAw z?g!-_feac-+jDqleSRT`P}x8X>%^+-GP1Vw2ORb0G@$bzAfuL$kq~Ej`si|`LNoM4 zKHsm&Bd#0N9j5qqSH>F+e^GW2Nqw9u4Thmh@Y{qXdb73M>S)E@#-##;wrtsCn;KT$ zfsNm|HzrUHUJ-eFLO!}@RF5b#3{!c|K}tGFa-c@-oR1dvS1`ZReN&Tma<&SHz<gTg zlYF|~VLhw%F)-R9A3Bxl&U8?R6>}5XO3bc(c?v}aLvgkdF0on|U>`k;GC?oIRJ532 z#wex7q0=|?Mc7u#A?=_u=r~$4?So0Ap<`T6`hIQWjpOOxa!J&WRU;x)V=3`ftg*ul z>s{XV8E!|{V-)uDTSD~CkKe;M^3t*E0!CEBB@-)ES{?ezP3y4!Nw}D$8YK}9Ujq#y z7s;YhR6Sy-e-p2FH037IQdCN6j9`QwKNFvLiZYMP1Y<@93QTir)J!4$Gz$`29$0XL z)Oc{a7loC=QXRZlohgVB0u#y<(wAyg@62?EaC<8lBB95^|3utD)q;+^90iq(c-<KR zD)}A4bWXV#(RRfS8<VXxHQ)>yFRw1hBkwwQ!4d{QmqUeNFj$j-Iu?ub!mr}74Ed(~ z5YaTdJ(%#@UsJ0}wB5?bQvkgt4*{wZ#+yG=XQQCH1sRHv>&YQR`Kb`(GP)CHy718@ zmvW<;U5>kh=zPhqVrnWKDvA~ddQl}hBJ`(oV;U;Uzn@q^DSqw|Ynx6rqUxykV8oci zr2zMI6KQ&{2rYT9n3v-BxUB+dv#QpiSMtZYKV;-`yB$8K<t524So5hv4$!^cdUA4i zys$dh#WRgxL)2&u@6&kHAF550b{BRXV#eOhVA=nCa#E^|v3o5L(+qyV=*MQMzyy6R zEjA+E-}{{Zhpj#N!Nu#HQ<&z#$i;c~yAyMnhpv_%3R)TiJtDiTo3+6xLh7&C(<i{k zY+<khM;Z6T=imz<y`#vOs@|oSNaP&IsulcCww>cY;6#cOfcbJSCN~_A9%Ps8IeNC? zZI1tMOII*6G#eLG!UeXdIf6A2vf`h1Fpi{-5r}9WBQmhq_s*6;P<H}#<HXB%c+8;8 zNS7VV1_0j_%THVeYAezys^jYmT4J<Sp)dLa9?6FbHX|KtUqxn#semi2gFw(eipm|P zgi^NLHFsh(W+v^Flfh*x!b6k<aw|5&dO7cI)aL~v);OjL_|$lK4sQOVdJb3>jn?>j z20Znw!~Cw32Wmy0+)w=U<_&FIml`X1MdFKl9FHjz`x=0Oy7D1BhX@|kmuMSX-L4oG z1!_Lz<{v7z=CTZ$<6c`n+$UwMM9%E}gOLZKn#A^0QKhBzH$#LPPd|Iw;aSLpGzQZ7 zec8@qj`D;|dtAKucoRZ&Y;21#NS1MRI6$E#FQ6KY?H@gZJVFSxYI>;}7tSwOLF$wk z&=eQaQags9&?)gJ`o;+vI$6)s;u;eR3UW(1*R7A4$l$T}im2jWDTFDN5gM?2&D^;k zjM69s)ZF*weQW?T>57uX%rRcL`~3@ryW6<9mK{*GQI^OYyBi7{*p60*JWZCevqT>+ z&&Tlp_crF$2Ia;ZXEcGuJS}TTVIzxZgy77a@>eQg;A|J9W!xnJhjzCNGN>&UJMrFN z_JJ{lK)-eN4Jk9Db|NyE5i>pEqb6oyOae_%b4Tt0K1c$b-5n#}Z$ye)nrrGpoM7DW zfJ-;p{cpi;z9wNxSu*xxk?_)kuVm25F!q$Z_|ncg28weQ7K`S6mDpXiuN7{o$+j?? zp4)RB`j%#4E~zV6Dg0tu25D=a)-#bgWmRx3tm}yVmL|;B*-p2DmY^I89U&vFEtI*Y zfh>Siq>*T6u}j6Ik_zUI6vh_^jC<D59;0ACv-nz5GILxSXyO50)^bf_BXM81oIkE} z0v{s1H$zv8Xjh@gzZ7v}8tm^`e6dU5VT(kO@KW9raY-zsly}d{7)=_3U1t~=lt8bK zKI%`i@sDN-W%?Nt>cAcMahJtrFo`HZs6z2Tn-3;=btIbJX%eh}<36W7pFLtFz=Q#e zf3ug)=l#3~5MIiSV;Bq!N!?(9g28INT~0<5%V5NZypEbwzGv9jao=tc(p%H<m}@AO z=elFI*i+?dBbMaBM_4P-+}HzH6R*67%&FPBW|j!~@L+*N%Q1V^kft4%xlr-8ju1}9 zU?!sL&d!=Yu1l$Jhjf@buds`D7p&#%BY=Pr$4(<i?MB_&$}{3;g)78RISO)(!vNL8 zHWuBxbvUr@lAWt*x7>>{7*+DeCZz!|;Lj8~rJ^yW{AuerTu_|wir|0YBY_#j3h4iz zUsQc8KHn!F99o+?X-c1p9s(@aqroo7971kUZ$h1trqeXswy((TQmlv$=csH*o|@eI zeQrc{Pklr*PSW2%n4@}EyP*wb>>!#Tm1D%RGhQ&u;+f60;*N=*NB&QgYo}*v2Zd&= ze@~@Y7>vbS0LK6#Uy?ea`y4PTmEZ~g!_eJuIKBvdfCZJstro@4a*rWup}E1JIo2lo z8thgZ)DO{SN??OpSP9WvEybn;Q#A8wq9oAaGdICqSbcT|^8a>^L!B-<7#<J&F=^?v z>}I88>Ia$S!6$aQZORjSEo~!GLL|_~zm^(!2sp3xGtx1R?Uc|>@D>CnMS%vmN6@H{ znk8j844pJR?n`@4!yk%qs!zUxD?HRuy}IF&OT=jco*|tB1F0W8h-Nwbl&hFJrd6jj z&`FvH4N9{cIfk}Mc{kbd6+@C7%uoc4!^7_tI|oO>+!xem)~t~WB$nC7ku0CU5<-*O zH2CoJ3_a_Zy6h)FU>-xFL0*m-^H@++=AadSpj&-g9Y?fy5!W4S<IeS;r7VRBI1FD0 z(Ys<HojMAaZmp;;ZaN#R45!ugHzG+q{NOG{a~IPf${KXT`GrGk%;ozJUg^^x{f}8K z-8R|f&wx@Ed*Tpy^CLvia)`3*Ej<162n+yus8OptrxTBztU7|&<>LbmVj0<L#FnHn z0)<dqxb)>R{qw8y-lT-V7bXjG)@lL0<?paEVwcDgEU^2?-z}$?mXV}5?~k>fKS#*= zhht<SO>D5@wVvBJpGzr0dWZ7o&-s118I{qjGRLK6K?Zm=XAhn4lQk56CV%$n=kYFk zL6(gxuOZI)lMQ2icNCh;Whp1@m$IRduufbH*htm*L{8qdK4s){q>ZUd;VKQ3T~I0A zhZS$<tfh1z5bjcIYgps{=j<zOPCBxFuFYLF3*c%t(k=Uv?VI;jm)2{Q>iAcZi|n4m z_I~+fFuN5}cCf<aX4{PKp!L5YD!bElFmMGo*PpLn?Y>m=?eH^SA4C)H$-|wwGbm(- zuYRIhfbAMc1Z(HiMy_e5zV}hCoPE5*n~r5HO{A)>83tBH{<HYk>z7x*)<~*QbrY&Q zgLvIB7s_^eV}|@yGdk^VE86y+EiAqdRns0`8g8`v@%_}2=3+d~`N9uU<9oT|MPZ@> zLCNFFr4@y}+q(8lH=fmV!dC4i6x>fR<No7Y?T~{Yh#Jl``MGhl4f}_(xRH@LjWv#R zfbEMdvPK3rR7y$m*Pt~Qm$&Y_nAd$G+mGNrMMU<O&+e@CFPXZDl?*mM>1w{3BV?f> zR?1TLz14ZSuVeo3(wx!>MN*Aa%rqD51TWTY<a-lTj^l<^RMEei1l)!4Q%_p27!vv? z9b}H+!PWOq>`1PYe&&bFB?=KQP%3IT?}90WQo`0OWC7Tzr8WMAH<nd=)|H))+2tl& zEqacuZa-#i)Agq7sW(X~QxH;r%G+FK-UYkPkPKQa?@uJ*9X@=+JvVyJWRc%fg}StE zHE^j0kRs)Vtd=6qIq0*ZWNfD69>dz}`w=RWY+8N<ntRq`o*Eak`dh~`ziZ<+!)rhd zv>+h+_FhYSltB;3*$fg^UPNS&$Qx4TOp9H(RJ1yCeEOAf@GQ<I)Q>#rB7Fd5c@cz_ zwG$(vM$47*)FF*V{zQpp7&L=@qDjFmM5cp@-EweANM}fzM1W##J;P%}as4OV;w9%< z7N4Xz+jD)Tb(a(1DE%MNCG{?tlS4X8OW$CIT&<jPdj(U!6ZaWx`v?R$YnbIO6}(y? zf-jx$NZ@xbrbGq=<fudLjZulPnjVTMf+;RN5+)ky0LXt?qI@)h;}T6w=&^94ww*(1 zS9xa!>P%cT(`7(U_J(s(&$swpa4fD6_(!qBNJU-oYtu{@Txq0AUUKBBrZvl-KD@@d z^*9NVii9RCanhFgXT5@Ir92P#gM*=1Nx+tYlrmha#Vs6stf+=CduoqRqT6_ThLlod zhoTr5kU8S>Bu9NXeiyoRh*LAB3Ey|B+Vq%&;(bCtXmLL8nk}hI{nj~BJD<RNLdC3d zatVzN1;H;<_xDME`;grX1*8PZPU*5-5*H1kdLM|xDt^CWO=?&z4doW^9A;7N{f9_S zXMD*l8B^g00dE7{D_<WQVr`o5Oo<5Y>hF1bLL`?E@^kFX9Zn^qxWm5_9z~{p2q`M{ zerBKJgJ9WGGT0O+P$?#-?AHtjO?ybj{@Fix54_5=;hl)!V$g;IJ#<O&-+Af}t+|<0 zcDOkeTcKG$0Sv{BBK_5b;5`NWBkwCl4?Pl*KW!Z8dOdy4+ttH<ErP@Dd0ZDV>y<Ap z<Jez=`tu=i|L}jn{k@ZJSeH!*&suBOtjfMzAAb|HeW6=M9x3UHWuu)?((teI<(gog zmK(aw#Tzw~>o=enAI{p~xnuz6KT2!>5JXU$2Cvn;9+)878OPFY_F8dFIYw|643+4H z>4XNOU`5!{rl7fHJ5IJEkBP+==O7fkaP#PezY!i7RZ%usmqssNDl*WmPc00hgF^Hx z<V9-uYVjNWrF0As86w0maCN7rrAL>kSwopZJcX9)gVM)Ku<b(Sm?nV(VC~QsSA$_% zE8^kP!?ob-K7XzayWCCFF*)uVt9h3FF@#OMJHbU&@-y(#+hcxr{fxBIu_SiSiy;Z^ zd<|tF`anOMF==5SVmV~$Gs*yS*=_9lnl}OiVb8$+_!i*q@z7M~P#6bQf=FQ&@X;D- zSo@wl%?C#8Ds}Ckv{=x)ihoV{cwm4t$H`~i0*K2Y6eVnIy&xY|yV|BSYGVKdF@ff_ zoh(Xy=rNt9G&^+wjM>hG#HB41N=^v#xk#B+dwJOe)jdriE39?r#*mGp?d2c!aCDS9 zBsDFo1i2T)3T^l3PnoKlk5Z<dG#tQeU{J*-Y3*#HNkj@DnWW71?@ia`Z#olOhB%Vo z4oG*9K9w1dS9-yIXW^PQw;>ONLc&A|N=aEh7z)jZvs9q=zXl6tKYar$&1vfF?d}G` z)Ak~{MbY)n%R-MR5J-SaF48EhTx&9#p+>|eYI%=Q{I1sH#i0qc(e`T~?A5HVJ~yLQ zI8eaCH~@C3LKW(NK+n?$?FwPA8ZbJpTZCSpdk2a12-=Ax*=?ZA9TV0LfOFx6{K}yE z$z9}98Q%z*<(?da?H^6p<d_>G|LAgZg&=r=#~yrPJ9o`p139OHY2(=(Sh$WgAt0l{ z=!hSh1;GK?mD75G>X7fH@hzA^Lmy@7Tn|FZ=|joV11qz3CLTnM!l)Li$Qv?#E;2Hx zOTLt&tWPv|-AIDfp=oCUwbNgi2a*ue5SD+{c-w@y<}TCKO)Bo{LXlRPnJqF@X%x)i zgSogTo&y7{(L3*fbBY#2QH`@>(xY77Sz!MVV-i{|Go}$Ti>H`f+jzRjstK?$PjB*x zYt!1sFmFIk(cj0oQ|b2IPU4-22m*>V-jkX0<)kj{Qa4vn0J|~63<MD=^1zrKC?lfM zdlI{B`5Y*PGs-(VaoiE)d7ExISR$j15WE@uUJ=-^W-a=hNkngw`K|}>@miiO)X3u{ zRX=VNBvl%14axN8=L7m$vMeGL2;Ow^zowkQ#3@HOQaeD1XPltWgc|a|BptIIT?|NF zu7OUATYxYjEGeDzCrq$XF!9hqN1?J)<0*YEBlY9(+n;3lycajdDjdOt@(?#stw>q~ zVZdqc0c~TYpdI;V<mg|Qhh-SHGVNsfha2Y?Af{A?Db(gMC$x77_2-C26ZD8>I}APH zLRZHfKN&>7Y6Cb7D6XGVQ5xuseI(CMF<>5;3-0n9c`=rLiSFpM7vszZ8Jno(U;r#t zr&x^c@8EedsiY;m*1hMV9jPF+w83vtb(!6I7$znkmiJ<E+6{^gXNXy{_lM9yab<?1 z*l-0hbQHAv$i~;9*3pT86~HOplMCV7nY3pQVSqqgVF^7naWf5EIV-DMw!xP2PqkfF zrM`fpFFK~<|LBlt^thsgHf2E}Do%M*osZvDzbB48$4OuXxI4uc2v~nKUJ=>nJwn0N zeCnE9&DOBA!S8r*Rt4vE<qL6=j!TIF4W0TFujj+Ng7z+e;jzDIk}K|hUEDMq@qvWt z7L*~;9>rQ>pr6L$yUGJ5t>1ljy%1=9h_nVePT<oRv%WnqCjBjam9WcveDXv5*RT2B zer(Xfr|BPlB<u^9#_H{re_DOVGp-lbo8KlVN|GAYU|}~&>=YpL_BA$I%{Ld?1kd+F ztIy;DLn6k`@1sYIGw12cf)jKD$;<~rVJ(}M!^Ca70D*-uOJh<yDhzb8d@u79DKoFp zZpaD!&_Y=-Ly^^;zNsg@-{RUIfEfrgC4smO(HvYjqM?#MnD<D9gaEUf>^%j=!Zy1B zj<Sd6CDFaxU|<^qRaQWHmlTHFRtJtA)==e80*xaG3q=n$E`Qb|<=$a$y7(rCbUi}q zK>H%2HQkf_h7x$)1YRp}{2_Z)cWYFq3rKm0eHN(OCIEVqbRSN<j5!b9P(~_ZS;TO@ zdFUzTaJ`*G*GXfSIO<BXIU23TX#Dv?%<iNQR^0Ncow~=@hMGuHD<s&eaJBMum%9(8 zruW_7Zvf|RYD@e`pVHF`fHe#)!4`8hYBhFc_Jeic%bp^9wc_1tIB?x#7q<F*GRJp- zSZg%j%RrCY+0`e1qi}GHcg9nD(tM9>5E+w9_`#_M#>y+EGp&ZHNBaJ{5`(ue=EgbQ z)K^c!Y;uiu_4c0#do!X|m&kAPfQol{ky5Td^;51M;#4A-y3~>El)sIS|Lgc~lneqI zSa99>KLAik`+QJXu?~LhLC#+a3;Ak`)vcM@Say3Qv=#K+kFRuX>(!{n+@^PIx=kjt z<iWg~vd0;z;PhlzN_U+rD33j|{(b5?`je^Ftl?9dzXKn`LYd9oD)siW#i`pPz3*^l zsM*6UH~Jl-YK_#mm<cYt%*Uas_D$_l9zm?>+8~R_5#5xE)!Y(|qHqWrpC23=%#%#l zrRMAe_ukkEpgBv*ob&h~m(f%H@AnprOZvX5T>cPjh*ih4y`6I%4rs}D_C7G@B@8Ht z6vvlm#{F7ci*es;SsiPPA1_4uYZDv9NdsF>)OMZoL`%j;nZKppJn~3^jSSj*t`oHQ z7a{Ux>;bDY5+Gy&zhW8#gs^O^o<D`aOdk#nsQTgz8`o1ry&Na^I!>G=*BO0ECxM&O zn?o#Qi1M3<ZelsXM=7!v;k-@P$2l}l>q{Mgici26{tmBKP%>71zQrcBia#VVMyO+< z8n-Q8zUn+@UICOd%@#4OHr^6BQ4j8?e)iD>t02ifiP1yCPKHrxP;-}i>}I263PRyu z++ktz<bMG6W45+VcxUNET&^Aiy4ZU8$=94~0lB^#?+HX<Ej<5givFbk@uaKo6)elA zA^en6YV>>EVgoNi%SM_)e;3pBJeUUB`n>=L1%^16{8WBgowr><>Z%-z*3wbCulrWa z>8p_uEA|TWos%QB@zK(=A^36h@yYY)Ty11=8z%r4+E0;k`QFO)o^!BQi|r8BN09J} z1@*rw{qdMFAJync$tixQI&u4rp*pVy_H2`Maj(1LKmMV~l6NbcRAuaWt`~f$ho=0m zld2+oYWifu4(H+<pW9B&a8G_O(MD1pzzL$;BZks2m7eN=(XVmm_sT}CH>1_ZB8ZWM zg|eu-1K*l<lUvjP8Fx~K({|~(08O2pi)BLuxTuFmCCc6bC+Tz#<z%rg)`3iywzGrT z<*XFl3Ti$usQNUZ?dcOUGY@ftg)lE7E*r;R{rMgC;Ettcd8I4`%x|1;CAy*Yp}E>D z(w<-T!={^r{QRO<ewKP|9W^AiBvT*NK>fa0nkM`11N^rdlv_Rvg_E3W>^Tq5BAfZ% zh0+%UFEa{W#d(Rg<+ytvnps)^;kezI;XjmchP#*dBdN6*(X`*_(3H-2qr)bRKVWD* z&JEFEp@hQiu9`RT+7*h+lpr<(A&kjJ)Lkl`kSkiM4N+4DFf%j#P=&{@&K~EV88{R_ zq*-<Pq@U|-WDGjnz3$1m06iz^A7Ah<;O;>?3aL|ViB?P~U-|ejG_Gc5q{c~=hR*mA z#@qQmZI+#t@qNEjZ*xtK)%=49hTX0&;BlMrsJ(PQkFKkJh6_hhb=OJfWpCQ0a)&S* zS$x>m$jGmkA#OUKza2P4UGX=BPRAtlR2Yw)4wtA)ug|+{*e*{n1*f35AHTOITnE)< z6=!QZA=CD+L&{p82QZE`27@tZ$o``z{v3!5f7-80CSS9j`C0nc9VzQWy8KZ}(XO@$ z93D%4)pg8#S!ZaMVs%;$`l<)4@TNOm^V;%N$<kMWI#}Ja=bw50^=(Vx(X;lk{{Z_! z-=Ie^d$k>-9D7~uzZ}_wGjab0T7hzI^YZD#+p$Ed;hsOc;GE}EjdYnrrd5pk`ZZ+U zw}_>EY!k&z$(^LXKOU-vQkv6PY22&FpTxpfE3UR+omYMK7*dW8L^G4XxKOdh&FhV( zLbLd*h+F5!_MH2z0~`L-p)Bgvc&hQblV$30W#sjNHp`+<ZX4K`uyx0Tu(I*w#anx8 zH+LOr4Zj)rRZub;{co)H?J<)+xDt`G-CO0B@fmu-Qh#i($YQhV1CWsZ@|IO{)04X; zbiw(njQqit4X+OoU!I%^TiYIPFji0%2-We?v0Eq<>+=NleA5B!hw5}4;o_CuTR{&_ z_@vV}!qXwsB4VwP^Rp3_Pk+1MK7Vg(v^=__u*~Iu9f?V5i`cFvu%4I3uFSw=73VY+ z^_N#wx0!uANB;vfP(-`iKVxK>GmP6>Rb1U2^Ty2|6RY2Hq=%vk*ReGRSGw*_>EC|& zKwn$w5_I}PWp52asMXv0A0YK9nHgdB?r{{(*v!sz@KSFai*xC%Z`#hT^{4RU0J$qV z?$O)>&L~Fjq(iKf8}_y53B_b|sE25zOaSveiZZ%jzjf)kUdeBh5+u=h*zP_nHYcuW zep)LYi*@W-Gc$VQeIq@#SI14M#ndf5rhDA2$=Z)H|L|{HQeL|vz4>;3us{ya2r($b zOj}=Ek{LYvHCCE^6MFk_jPmPfG4yYxvwn{kTC+$U0g8UVZD}S_kw02P?un~~KH~Q& zNh|VLw~qQ*X2`agSd2u7qb&V7KVR!L?qe^*GeRv)5<XR6P+NrFcahQdhfh6E9S`|+ zclJz;>ncCv;{N&?YuVx2z|XR=_E&v>xMm}=9vwc73#wS_3W&Yfc(6iyY}_HJFJO&B zy?q0DC&b{jiUH@Ft;R+Wm_#Ai?0?=B;_vs+`!Ayp9}JI#j0FqD!e5tejA{y7#Yr^$ zYS*nluT<}Zp3ZRa6@5t^d4bx={v}TOau9v(GpUpz*%4R6FkPhEJVY&>xcB)%S?maB zNa|c!9;1VFeaZmg)C{%-`8#)<-~}foYlsF909akwpwEd^g*sW*5(gDhj&N>rrs@^F zFW+-jkyv7!`PjPoQ+W)`PK%=PPVwf5w1if_+SW*RWs&lh&b>g#h1Urg^$2Fr%tZw2 zH}=Y@ebx=)dN38*usG%wIgM-=h`0wvq!wwNJ$xzB^;cVygKjs6P0hZH6g!kQ%$>w= zOn+YgOq}03anEIYh-wU+_TH<~7A5c6p36Z9`0OQx?iOvw1Ej8wDsIs(?EBc2#Gps9 zA40sv9vKaO04%|bpo)Cy+L^t3G_^~X4{C!D5BmudS1sJ=5c5^O+}hh-C3^bHn_g=V zi3(~{mp`&W(p<eC<KC41K7`phKt=Hq56rRC&#F7~{>aD2C!Aidi^ZA9ue$pH+mXTG zQZf#ae!97N&^WjM@6yLrynia9zA9J_V@>Emn=!6O-+lW!zmqBJL<gru(G4$4CEF%5 z>&jz`3nFeY)At>6-^e54234MPysO^wZu|E5@bwM?nM7@nnY>sR@2$)6Uu@&?`7Tcg zjO+ky`6lM~_yG>0!13tzE3d-~Ot*lJDy1J?>gVh%ReImuXju8&`Lcpp$P!(w>HfLR zq<btzm&!Z$-nd#X_)RuC|6M6;LKF8M3trXlN-k)!cggEWtZTv~HQ^q&(+B?OHA#>B zh`7N`kyF%F-kyt$a1htLxi{zT@*xRQ6?Kfd{r1vNxzl1P_X<?=S?v)TD=cN1*OxE6 zSbET144?4lrV$2yp0L#}AJIFoS86gErUL5=&EMsdT780IKD>sXh`hsh{dwBSU46q6 zfkE59zHPhs#d}6tT!_3g1l!=dzv|ha*`aCXerL=(ZK32w!8eH~CXYV`JW`{Zr#a7D ze2I{H{x?Q6-lPoERp@CE=a>|TYKF3r+gdMrCjR}zJpWRBD5(3mZOQ{`s7rO?#1Y7E z9Ryibx|YM}dHXq%Ajz0?U1gclBHa9b@6p|_&V8pQ$x!8p7LUbXUq1AUi$9Z^s|%kV zwRZ<Kim%V==--{LcPZlJdcI8~Y}|RBfnyt3e0X5yA<@+8W0Q(}>>HH#DhwkK8auIV zzIRL=UZ`DD!8WYVxIj)UT{@#ml)dnt;x8K4rO?@4^Ov(~8yh|0REmM-L#tsn0~>`I zc~*+<Z}xRd32V`IKhAAB&BZBXH@B4O#Q4i|s-t=2my<0>hNzfF`^P4k93Pt5yPoNX zArV>oD*mOs2z|I~uyi=t*LzzBtCgc$m!>V5-n6etD`9CzG0~TI;G_H2IsER4_sBSq z0M{1`pCYSOJNs6i4IBuUuY{~p(y|^x8~xv9Mjrlq`o<Seaw{2TDqSahY4iJnTFxZi zIRSJ4P*Wl}O4)hZyY~Om0YQcArp+-2=sU#4g-b*EyDAK31y_jr(~9rB<EOt=?0JAx zn6<Re+B)~?7|#i_<8?s$12DF^jWNqs`1Y3huaa5aEVcpr@`TtAd$SX}giuAx;nmg6 z-Z?0|LR!RAG8lPhETkB9!GoAUHH7^CHuUDb*^szgLrF~6_+{~H0sl)QrC<E#4icKd z{}x<r?WtMX*^$Hvh|vYF;kV`M5u<0$A3K_LZ;GO?j_4#>5{)A_y~sLiQpX^>nGhsL z;qce)vTpH_$1L2v()Q^;k^l?=W!UxoK2O)qh->zLW`W7yJ>B8`S!XgS9ISWKE|wng za!u|?s~@1^KD{v9tK;G!g`Y#rGjUg{Ob{{;<voIy7Fp#dAX*)&_bUAlIm|Vi`t-S4 zt@4LIZOX8EUTcDUC+drj*pl?as%^7%p56Nf$$x7*ye|KB?dr$R6{w0peX4QH)xrx8 z;G9E;&uvh}tyqjD&S3sc=g?u5P&=bd!iIAc=a_esR(n)~eG#suhkWFmWUKuZ3D|2L zo3<UldXI#av6Y=W=0&OA=lhmF?H$&$I0aqdEEPR|kz$Zu?b;-1H60D`dj-X{2ki}9 zI)oll38NI!#f-0yXbu{cZ*)pAMq^%epKH&?^>R(+z%SFqkQY*J3+`v@4!iDF32~l- zG33c9SM`3bX+L#*V<;klv%4)ae#-r=W+mjkbPAX}aldsi*z>`1;CmBPeatj;8fVko z>v6ocTvTwyBK9B<Z#6Ke{T~n>^({F7Bf#|*-n!W{YfTs|gG;GMQ9o?DMwV-9TFSD& zlLP{V2-TLCH6vSN(zPtij%z+*`I5zdz+X^tF0k|Qhuz7oMY<<dC%X2f-|@$H>Wjw! zV<(%G$0Vi@nUMOTS0qE?zwXJu`Q_m%a&hEZsF*mWtGuUf3gKBVWs?YFfGeQlAHVg6 z&MM98cX-veu}8@f*X!;zOR?KSud)`)Z&~J9b;lJ_l8&Zw0a=Wu?zz5ZrQeMP;zm2i zf(COkUOsOex(;XmX-R9L9DGAJ^?1YA#2E3?3av|yiGEN+Y%%7@r-Q3?pPzg+Fnn+Y zYmL=27DJu(IJu?r^=_HbiW+YRd5%UmsUiWjE@xSzH2V_4D<<{fE*eJJRz&5<J<m}} zOrBQ$!fcY_cU{G##rgp-I?R2g;K(CQDGy+uifRInHqaVud~oBDmw|b5Fi;K+aHkF% z_nTIqu>5h+#qo7wV@^SO9n4f}xu<Tc`ai(>P@v?}5SJqS;CA}O8N}O@9}IIGN{pDs z1R&~TGH`Bx(R1q&`}c+mUzk%^T^3%8@&-&&J^6aheqoh^+D_Cn&HIB3&ntlD)om(? z{r&Gb&ou{`2HJtqnR5pLxs&1>abB;&*=&YwFfXm0j7-12PdP|}qZVT3+GQIw3sX3U zG&)2gTf)cGd9_3mbu{ndLm2_7%R()V8osi!3g_FV-D(fv&Z%?y9H6S(zk&hrUrW;C z)dCJB_Tn;K_TB?@Zi&lH88x(lZj-=0i1qh$FZ4t48j_Uep*vW6T(0fAdw|>&`e>%7 z%2bB<<Td6c#CRH%U3eMWv~bzFkyz^{x}uFy>5GuYYQ^QjawV4^sV?>w8B=LLM*dhu zy-XUdv-aVxH!xx4=tN?TkqiRfQLY?_rN-od29p0dY<^TvGn%-!gabRt@7(%zC$Y_{ zdZiRn6@d(k5uDd}{Cx1)*O-Ptm}f8hiGNxA`C+Jr`rVo~a}-8&VUGjV>{rI6HJ`bq zleq*Qn2PyJGq>986jQf<k>|cj`)bWjZSr27=^d;Q{6b!~$d@H2nSyxe>pRve_a}+< zE;5f2Sm<mYo|~fD($j2z2?STISa@r$nAP^#a%zZZC`F;^^Djh%{|B5I!f#j&Q)9J5 zUN!NL67=_DuIdD~z{uDJ`*+TbG_h(!w2q`%o{87HCk7pM=Gx+On6@2sKnvqtczNnO zwd$IbPJ@j?zaDRNt+7n!-5cT8U+WK#nw&^gmJ-SQ1&-axzl-m!S=~k5&GiQb4OT;y zq8!thldmo^AJ`<a#fU_=NwXh6t1MNF`7-uyv2W5r>D2OC__QLmaZKyGU-NQE+f#SX z7n)WMZtLXDkogN{N>v7{mF~43*ZwkJ3zO1G2<=UoURQK|I<;a-+4Olw>?;Wgc0PBS zu8IC|fB8<Qv~&z3?begOO+c;>2OGY+QtWtSsol;+)}q^pwWWrNE?KsUO07&CN@!a7 z{l*Z(C%$ezJ?JVvyBOCy$$A&9xbQB1`W(o!GTf`-$P}N?q^>L{&e;YTFE8c#pd*#? zDzBc7`s;dtG;6XXT=MNPCJKTifSU@Ne-ApRb}@DoYYh$W*Gjb>ECaS$%9qO87Y}7* zPq5lYkE0@ETw8=E?sqg0BgT?cW-kAj$$$L4no~_mpxfVCE{(D@r>=gl94dYG#u7@A z<ITIIBsvKL@gBze1e@n56h+NML?si0!8Sr%(O##UV7qy2Oupn?$QPzL24VK1oOk-u z6wD$(d%GDNsjZY)<^;}y=#@7b>wZtOpzCWW&F8Sz#sg1`{(j6xYn=Z@Mowa2)a=Pk zFM5^f)7T&659rT9S6(h!sBJ|eIa=?M?P$M0Jhdet-|kmDqr>L0P+C6<h5A&V1HY?c z`SMa^Cak>!?Dm8AyIwth<Fk)+P;NCwnCP?q89o_*MQ@BXzYdwz>`bw;&(%SykLcDC zGQp-qq5PM=;k=g|{*81>Zgg}^PAe%w+4HwVF3qI`RZpl<7`$aua{c>Q1*jQa?ZioP zs+LrKs*Em`1zO=ilEscI3Q?#(u(CIVIi~JjhM#y4TfYNK>8eaG9C7jR&Y%q~w%#0W zeCqe{SgN$RPK?Jh3oXg-{{&%TO7Hg;x6Sk2S?0WZ2PSr{RY+gTn8PM&LLY`T4TSrR zaj?vocb6{^Y_DaJA*QSRF8k%yE8<ptFN!x}$pTizeE;&RrhiXzNh(wGU3M*4aZPB$ zg?opM3?_Bie`Mr^B}i0zm@9U1Wz6MB_3<_<u{W+nOC?$rWK!vf_9MMyRWcw6Zi)Ca zDbYKGg}kC}_KQ1Fcesb1E)*=@JoZ}4kGagRfx_X8QBcWo*LctlD&i2wE)22s_Usd& z$$>c^E_+w{1i7c?kL4x08*Prc{k&QwdOK*L-}#Zh0dpKA@VyB5BNp}Vf;q*^u%|sC zA$+gQ`u<5@P$F?QI&$&3u3F3RxgW4E^+>73s@!d{@OO<V)EuGORA<7m=_77!=W}W~ zGjW%d{w4nYVTgWO!im@4)^)E*qI-urTEzGkiwYd1{}*+2<eyU^5>n7oB|I{ww(Pmx zT<cU;n#$cPkeRheTF%a8tzSE$?kxwHqtG+^qRL-(pv_);1_Rr-KfmtyvQy<hnE#AV zHA^-llde2n@S2$&-Tx5{I!?l<fB6Es+!j;o-pcFHrB_-)sT*6)zb)K;@2{h0p9`zr zwzbZ6(?-^m|JG&oyf05l@mkz@V<q;XZ8)e25pNa?+`bPM!&9`&3-)j@F{(ANW&HFb za|e9^6zu7voGo-))D^4CI<dEZz6l%i_W1pQ@jK#WG)-lR^;S7;{#@3M>W!$YV2+RX z1vqX{w!HT?xkXTZX3+<|H&pIk=ZabGsill{kN%ut{ZqdSp2F7LZvO?=vGLZcY9bA% zn733GYfZ-wXu{TP0ND1@?f2!=K~3BH7I>LEvft$B+qciR)-|kBV?VuWZ~wBl*dzo0 z<xeaN>Gd{BMeXSrR<36MZfLRER*6>Wjt%hIU=NuEAPG;Fj?{Ha8stXCJkM#l0l9|^ zvUB=4$~o&xfG(CmK>d}yeT0mC@6rp?u?QcYW9}VvHh>@6S8w*?GSxyF1FF1Sy80H` zDMc(5S|8AZVMS0DDWSiM#7N6vhxMz1o}VxA6oW0P14t}*A=9`|Z7Yc^&V`OVSL-h> zRD4g<A=#?P1E0co-pQHz@^i1J3KulW0<8fbHrX<ONru}Q2~Z}n8IDSTXfDBoyshyI zBsu;64z#P>m#Pj4dI*de=nNnaip$vPVK$uu&5}Q=8>xzexMbc%U|-dqTGr`R`TB@u z>Sv#KP>P}RK!|*F=gGyvw-CfH@%flAw0ZA_3oMBTvWn0>v{6G;M2xFk^U+@sL7QGx z5VL7GV$Q;-I44az(QB6qZ9uSEaz3x<1k{wUIAa^7-qa-uW&x$$0+LOog3;!=TQLes zk`D*W8s3vONKWWSbIa7^L=~{9LJaA48WXX_BD!@3oFW)}jI`+z7L)L>8Nth#!+oMJ zC8{V|BBeh){c)G<&nClcx!}%Dky5N_Okgm^9qXJL`RHXq;T73%kK(NlaSnBDzw(4J zSF?e?@2|{cP;(|?vc+Avo}Vapwr}#&bjr{DVHBPminnZk+*J-`gRKE_zQ$`-T#wig z3K?DEyL^#Gxh4>{8jMy2t?n7(DtG=IpoxzQ|CAit=X;mb3k8cPrB0*a<yZ+UC^^tT zBn3*3+N3?OI1tCgFipHNNlroS*(}dATi3rtsb`Y*(4QjH%pG!*VK_s@n2%ZGwVd2a z45uizP(S>O%f_2X>1@1~LF;vRmv7{ji}h5!23%+am7h&iwBqLT1;xK0xX=eW(f<L* zZGiB}U)92AVLk|8t{I(pI5XZc>RUs2Gn+lbx<yfT)lF>j$BdD>(AmczU$6&u^D;rP zA|3*pQd129UHuVWwM{S#7u^$Yuq1Ae;Z|_|172yW`J%qMWOj$Byc3V-D{Gc7q8irW zMcH`94U<Q^)3F#H`$Q+<j_>?6l}1OZS=Q9`<7y*vV(2iRLcl1C@_EQJOnEVF=bfQg zJH7T}!yA(wmoa&wZoIf|_cl)QIuSI^8F6Mt!3>yqM5x9_+eSmOuM?QfgB*)#Opfs1 zy?0`TQ)A;0s&mfie|(OhZU>QgHmCWDxSl0^R#UHp{wR-ON_v1ng>O36g~T(IiDC16 zK><s1*m5_koP(D>5|8BM?qhABAK9Ed001G>*Ayi6Ze)a$l1dm@^m4LU4%lypc2;3) z(w4(l{f9vm`s0F-t%-Ph(O~qWrP8gZB+?qGGi*E3$so)zp-VK-0vkl>nRBX}wZk31 z(g#ce8B3fS^UZ7do*@ZM>{_MAtlmNki6I6~-*0eqmVPzj^2bXU095!sV}@@Vdyx+u zikVgkAPlB91q50TQ!-h02}r_>)zy$Gbg&1fmt7$&3B>Q&)~ByVv%rlv(%XZqpD_wL z{9S@KWEKQU<gNdJV>zvsQ;VNaLR425F4>+@sMa3g;lHEO0u@YSv5D733m$|ZrSb|w zL}TPfKUn-=t$lm}?&dW=K+?u>EgR0uRJ>+m6U-6h1j2y>ZDJA9VJl6%Gu@;g6`zCQ zgBTbC-TtH&p$Q5@Swh%5@VeRsn@iIsk?nmQP9)E%0Fg0S<9YRQMt|fvjGxanp}r1w zMt%crtbk9nmM}%>19d7;Xtq#YJEYrr5*zNWlphfczWzD5W3kefo&p6$0whdX%A3S0 zJSKPVRGV56sBEUGLpqi$8~t6zQioC=?mA*6;%f&UufCEZb(f<x6R;$_PX4OdFQu%M zz~6^st{9mHMx;eNB!9nfvLs4DHTwHBIFCD4Z=_nU3r8R8!D`mD=NXJ~GBa!b7;kHS z@|y}i%{190)bgIBOZ>7CnJb{(rwx+@UrHe9M$PAjsV@=)LQLtbc|iKHZo3h1?%_qd z1Sn|QHx4Te<U^&*B@MV4Y0HBzJKOR%%FNvNy!@h8ZZ}XuhUH!Z+R#@%y*%4Ki+vMB zwXgX}J~-f8JjOwWfIQ2)E=TXGP|)=oJ&S4Yp-K}<*l>PIGV!`ejQ?ZU+#(q4^~gkg zG?V&rRH^T$q@izT5A0O8OhC_LTHO{1t3_}(9Sp{W)dA_DV1b6;ov8?3Jyu1sIUZ)t zLS-6u*$#s-k4GX2eU8n|zQ@A3n=+I5U71}-B?&=+l+3q2P{+ey^rl=1*^5htWppuM zJ=rzm)S)pS6*y<}=k)~iB;2<cRI9VuJ+uNj%A9*HWd%i^)-d!9$nyMnxuts(GJ4|M zm&upl+9_iOFLRxetoVp*mfTBYC_Sgw-vUe^Rht}gtR&W1xeTKiGdDN#Lq0iBmrWjM z>spIVU&;R(L~PsGXb8%^PN6>yaL|kNk^iCRo!Mjr`V`2*lH#!?mLdeYP6oO3g8c4S zRWZ#AXMD;aU0%inp@!n#2huM3o<tLH0?w|GS3h#Wg+lP3G(u-E784;Bp+T&xtQt_r zvAfQfi>eThaoo&xz69y*5I0hs8Zz^xa7Dd6f>(H_&`-748-gbAv+MX}qfV^CXd+r- zrwS+&ty?~?o>pef9g+rxl?Hf4GIBgJ#UOWWEXi@_uT0W)AAc6e8SVr2ONx)zZi1*W z&?<PwPn0aNa|Fr9&GwY_t|iSygD=S8C#8ioMor+rQ~-hyfaB6RyBi{;2h5Tl;`61! zITd^m9wFVJA@h{0<1V*7mOn=5r)K@uftJnIL{Y;8p!~V((fZbxcv$a7%GqathqNJN zUDA<B8gc?!prT0r7i`y6&>tW^N#>La6fJK#bks~L=G^gIT3IbZifi$hAZtdMU6&9c z1p;AOuZ!X>9>d4qOOHu9U2wJHOgUYufC_%+#)i1v>}r>(EXtk58R$=kujRx1pb_ey z;)%v!ezL9nP;G}dl|$7a9CLK=^IZ+FqbJ8`C^)N`%DfMs&;TEw10XqmKPn+Uk{r7o z+<E?(m05CMtWD@SkH%x&uuA2zXbnBLAj|}Zme9MD4?Di4Vq_X4?@8S)lM_AE8xEVo z1ydjc;0FPUEHhF|=vP5Hh-_x`8-bP-afPUN7^Mbc<Iek=Ok&Q41*S_0Ogr&jg@RR! z4G^%fS<@@rkze?_OB;g%V-oJiUNC|J3@i?ECU;MZs?W0t4zGudWNBr_)gU~<(4W|Y za&}*po<-1T1K=<29OGC2FV_eRMPt?UWCD98a+kXo*Sn!R9?$B~-6?u?@GnpXqt5~M zRdz9VWp!5UbiF1#T_$P~zt<NM>4$A=m3o!&>Zvs>A1WMk3B*v3NadFxcobUJQb_9k zbcH~@n7N49OgyBWJL$>N{)$1{2^~@orVlj101r|Im6lT!RX3s|-KpPBjg<8N;kkxa z_6Y%XwzKLYCl#y!B?+c+^i53Lku%5Ue|H8=!)zfI5gQ&JQh?c&Xwb=A+$Logve*np zy{H4e&?*8zgK&gf&ep1rj_J?*GUxYhIQerRkI*18({~d}fzWOIFW^OmwHyCVn>BLq zG829$3&gh?K`@Gr&iOLKJEHs{%YL3MEHImt+F*`_dG;f)4L8)$CTS`F{nQ-J*5SNQ z_}Cr97>HU~A;^0w7U{-4WCG~zn5-#HJ5HBhLwt&YZR$hj=zHBJbRtwni+&vb1+~ud z$Clh{52<9W#g1vQ%-KI_^{4zFsm=|Ck4c5F8vgne8t!S0P!0xz-)1h5d&z*QtW5u? zaLZ{=DfmECCb5CIPP44v_3&eJMBR-4MH>93&9<H40J0J)WyW%#eN^<8%P~u31KE{9 z3En*aXHLh)1CV8;c|{xol+Cr!J^5!nPEM{LGpOV((Lg3Am?u>2ZcI*4mT|7B6et{| z87w5aKZrmvOv~SCjE6#Mv$?&r<e9VXlwe;-pEor(QnFiYZ&ZDS6*qTfHdb0=vJZ8? z>iEbYri;rv$sbhM@napON^r}2vSQ|?P6>a3J3xRptqcA&KXxzgd+3JbHg-#T45+Za z#fJ!o8zFXq_tlWgy%?<&PY>t*n{8bvbrB1%15;Sc<=nsjvKnRDP`7~>5r)dLFlFg* zlo;mPzXSMAJsH9f7*|sNXm^!QT)p^<VS0|z`9PS1<|)>QyQ~Ssc1*)dd@g}P0u^D} z=B8r{>R!!(I<F3BH|#WS-*U2YuLr(On?yuwAS`|=MoR6VLDIZ**Suu;9r)F9Oi^mH zT_mdUxGkuz4pr;ujMl>%J9%vPHL;G4&Vm2%VhFLm0;4=07_rDIJT%<$*O=p)&K$OZ z_c@cd>~Xw0y5XkyNC>AY3f)hw0$zT!^a3Dmq@8g#zng$g#2f;k36!zp0F;&o&O|;v zaoMlgqS^S@NDH_=u}F?N5SP0{_5j^2BK)NtkH_wJpwJqdt1G_y4M2a%X0*nDw2Pl# zgH75p?^M*?Y|XpdKS-VG5R3Wr2YN4*(e^DUjk}qOay4QV`ZQ8MH02iA%*8`oe25DN z4Jn1Gjw)WIyRL6o&G6|qK%9ZMcC5N*x(wdZlQ-{l2NompeyJe|!|=0O9g}4wnXOOD zjN3X%3^vJ>d-geqJeWGlRg(&|bb#5}J3B#=hg`-0>G2)n&6ER>WGDuPHOrcfKgCt^ z{~h}a&H+PI7*j*@OA}z%${EZJs>wYT-U+_O`3mfV6<_#tR*kuxC@1Pxs5;zv2F!Re zI1pr@2kte1>DYso=bQ&b5i8BJy7N{i1=oPs;AL}Be>vnMsDC)`8=&6IJ}AJEhpBzN ziCrEr5)=2S;5udUUVDY43Q}&AZhltt8@fF#AZu@ogGms7kbFQjR{;R2V2#<zIGs;4 z%xVEssO$8M3NiKRj+?$|zBMr0_z+wh+5jG!-#RU$Yq<-pSiMp`-THMabTYa<z4BDo zTn&V_Z7iZby5;~j3K4+&v$kQXHOsM!F>Z4P`JhFV2&Sol4Icwo-)6^UGwq~7dUx;g zUrmqOI(xv_yPKd2@{`V=26v7rpxZ2;972pJMiPubT@3DCrMsEg)u*PxP5DSAGj}90 zGC}wjzgKVajf`_Ml8ch5*3e&$4ul|sdJA<@i!FxhYoXhJ(idVw^e*6)hTq~vvJRgB z00}-gMsh0M$Z3P~GPbdrQVDB~31~aBEEtfJ!&j5U?lSvGb`ZOJ=iK$q1MoKP|50@A z@l5@H96vKm(#WMIo2gZ9U5wIPM;Es=ce=<Wr24uIA=e?7G@EPmZJ}I-<Py0gxy9T< zbdkACqgl-Te*6B;@A2?wj|Xk%d_M2X>-BmL9f{b!KK!w8rLRy*+|xdgUo;2wl38af zO|tp4$<UDybAik!(zrWfiu^t}-llaj_H6vx8?{5ype0pw;7zdr{?WTpKqpLt-tt)% zca$psb8wiXNtE+3GYu^f1*mI8t}V&;qf;IJ3^57Dy>Zg0*#@dHzdEavc%KP9r(eNb zY+{2c5S$B|*RangU6bZ)n<poNc+?25?|-YsF*lu;N<f8K<dTyUc`G6&D6HVs>9<{# z<kv1>o}BW~X>Vt-;(4w310-J<($D^S)-z46N1%a4AoL>Z+;yPz0+CGI5H50arVoFp zHP0h1Ey07G*4lOIZSTGekj{1W@bYl^hJG+TNrE(pqFYyV{z-m$qJvGI<wk|9q7!dl zkv{=BpZ%cC8v9pNH|qV-)b4AwGlNpS53ZJb$bVAAY{m^H>`zj<2V6NxQs(I_Q@xaq zk)j$Ze$d@#@tQI5E;V#71-`rrC2$EVPf6Se4pV+!S9zlsbGsGMJi}uI&j_c=9PNdf zbOm*!Zp5+x-A3vI0hjLiw<2(#+^h)rOXWk?*|byF67zlPSW%jLQe%G)S#*hzl8W0v zugdSzw_}2^Btc>%_*|RJzd93l`kJUl!+WC>Y8NGQC*{F#$t+r!@=1&Bwo`|FU*=bg zBX)yIQ_XEv<J?*dmjFTB4EVH`hU=gF1G!j+GAwH>dmn6}z4`iaM=nWnO_vTfux%DW zI}DM}SpgChaCc|=qa^>aN0*>Ji~aMxo0Og&2U<YT(Aj%mWx8q9<54k(_JQku`fgKE zgH{*BIqdy;tFEqs4lGr(d47qMONT*`A+}Fa`hRrQ*~jz-IS+zc=#^p)apIE&Dfbib z|FKU~DZo-CL&(Y8HiSsCOaX3deGC1-RgCAPPS@xa)I?fG)O(1JA0v|kK-;5mD*Www zfCSBJRkB^U(4}dX5KIde?ich-l00#7&0?h}=yYvjo$T{I5Q3K}96cx?q`lZ3VUl$8 z)N_q?KME;pY{VQwF7LIb;B*>vt6tsubDQB6)VE%2AbdS4$Z;nimB0N9MUNGp-9>`Z zj2oc=lKyBb!WMZIR>9b?e3^KP=A)uE5)K~fhv3(p$Rfd84|9aRTNfh0>>)GIvXsit z^N0}+mTi^7u-NHJ1X1S>(21`;k-!#K(LuQ5%OrtXWf|G$$X!EpS84OQ_K548()cW! z5?zST$I3ZyrhIDqz)6kWG3o;a`(q$Ydj-_B#|mt;RBY#pV9ARcgMX|~$24K+NGxNe zz(DBA>A4FB*B=;;6+LU-TG@(RDM=I_5XxmfTWXQz{8?|u3;UUH0vAY{QvAtWb5*{B zE}R3|g9-6c#+djBY5A;Nq<i+%FzHl`-NoW}Qc&vL)}Hq6eb(cnqL*#F9x=8@@gmlj z*5jGKo=c({>QLZ_)_VL=4g5x|b~THtzq*nmsCouLi#2;O^*6V?@HVZ~4p7`Qo(&=L ztTepOLLY<JJ?HuCn{TE>S1o-T^!OuJbA;?8+hu+ZYKPd|cNI~Of!OhHaSD{~`*g+v z*&hVqAXnYy_~|-3Ey*&u6*g!<4}r6jMg*jpO$eUN5nsX-V{}*#-x8*yn3%*oe1NRd zhxq>)b~$PG79`Uzxvv`EQW9k?@KgzzRM#p0v(dZ#)zN)cReTNg?mIdMw0aLJ3xt&b zPO4ZCm|RjHs5oLQ-RHQxVa`u7W@=eOxqW5Y-%gd}O{jcXhR02L!F7sSY?|R8Wl4cs z{>L(JM5l~sIO%z{=Co^?1CHKblJZd5vkN#x-?XBNVfP4R%PL|js|Qurv7Z#YXvD1e zwqQci1lv$?*Rwsf8Zh)gCWO&dJJcAfcq2_2y2RqcabP<M<dpC*_LKl2Xl5@c2Zoev zS1}_FGFS4nfM(FK0f*y-_4H<%w(~%E8Jiz8LH-p0v>qH<y%PZlU^C&gUBjC}zasa> zl|(H;7s&;Z>Z5jDxBmk^6gMwHtKfo~li8q6RS=lm1xEnXGLxs;$@20@UOR5jx=wBj z4O&7Ee5pYm>OEY}Xe=-AwCmJPQHhprTBT!Qh@CAszCE+J39h=2<-VM=?-Asw57SO| zuZpaJ()X^PRt$_>a_3)>uPD&H4RrFa&+1G=>dfY{R6dQzAT~eIEYEz0MQ|tw&N{?l zz_G8453w&_QAZyN{_Y+kC7Uxqd!gUCX*fWF)J*nCe^H!Nu=kqDYC=D_H)ihlp31$t zp7}}D2k4W=fL2Wj+VY5qKM3Xf9Z=-;nMNG(KbMnq36iwW0SCVGH&eCez-ZFFFa<Rf zNdp>-fHvxcDOj5CG%4~1r%>-eTgt(|w_YLPn(U%2>r5pdaKSAE%{h03kH<X7o=l3H zRl)sEB+-`4EW;v%5idW>^1-tm6jh8yBH|Ezl7K|a$mXVB&CkHq-|5wg=-HiZJ%l_; zKp8MbjF<rrS(NC0E5aN}5JqMX?kE7A+Rl2%w?#tO3HDN+^m+LB?0{Q_ICgaTp|(#L zk%3YY8+!5t@D}h5Q{cM`oBG?t#%(PcsTkhz33ps9ct@&j9zKlQu3Pz?{4T^x9t<BY zRFnA|w$DKju2Yd<4?>5?6qwbjc0j(sjm=Hs5_xqmy9<mQ5!Z47Cs~f^pK3WdY_5@d zWGt#vd%};~L|5JP_50p5jjaUFVH1^)3J4Az2I8sliYG7ctI2Wj6~N2HVk770uSUNt zZaiD6$$2kx6%vb#5)5n5DLi*zs@7{n6vVU<_AuxI^{xMaWYeRuBkyRDO|p#x|Ej7M zH>zuf+$9}<qEZs`jk=q;o^O$|U)FdC%cV5N7^qjAQ2D&BqXB+-tN_-6QM+L+7$$PC zupMrM*8eHVYldh)a$5XL<gV<cHQ8Y6({=31aC=qrXY^hLOeQz2;O4>qRdStDpa8*4 zFL(v5Ptdb5)N74iT`7eBIPL;XjUx7K3`Uc5y{AU{uXKh9@6a&|DC{+cUNPWJU<_o! zd9}^3tdK~MedX0|1a1i{hDo)&H>9>Y7Iec`q4RjDK9hTG*x=#{vQ&%mZPIF4%#ZB8 zu$FV?e6`eMwGLH!g<f&0kta(pZ^O)8U+&@*z%GGC@mH}w-5j2h{KiPNAARB<JGqLi zGMp__@}2>%?CL8jsN8PC_~%C)bUqLWEoTfi@EuN(4iLjOw<|&cK`sA03^W`OyuB4J zIiRN%c(yAf0Kpz69lt||{iEoS<k!Rqb~$u9Ru0gjE`KpVltU`B2(ZurQXY>nI<57C zgeSJMDH`Ycb9dR_I5NZy%P5t6BMk&%R);Z=bhb++9OUoPy<12k)jeT<?sBLWg!ytZ zddGkFe%|Y-faIl#C){l3d4hwi`a@m1Y->UffVKDZV8t|}_UROvD1CUNaCB&K=LW8m zQ2^u1HG2s?xcpEjc6Rj@WsDG#1U3M`f_0#h*_RHP>W7<z2u&=a)2byxR3E&ziVfC! z`4kykaD;1k+?|riiUj#|q$903AT%dsAEzu|(IUo)SaX`YvSnE<=6fl4xl=ZiXA<{E z$-n@{@4q4m%<jz5Vf)fMSQ0yNlJ$)4NOJN9aZomEB@S6h*8)wetG}s9cL{mEDxiiN z1BM}-<TbYo{WbJ>xPu+e@*F`{D#{mt;}pC}+?{uu55gVb!Qcp;n-I)1H-eae4+y?H zA27kDc0iHt0~x!|P&znJddjUx*?Dz)RE=lp*9jD^IMcvMC+XnERIC=6x;&5ugxdqy z|BJ(&oNKg*?Pl~Jv`0?5FL62hEDWp*d*?RR@(|bxdF@G7U}50Z`sgM9oi-!k$p8ev zuH_CFTzMN;`i->=QsB10qUuNjuKZSkV~VN-jsuEgOc8zh4aSg27TW83_)^5iGog;L zHiNHZp8OkIRfBJ1)w=&|L<bh%*G#X!3`W-#Uwq?R8}^n)?7b39h(33<fcfb0T&5T7 zcxf;(EB(ukWsPy(;Pb`!xGU{Gc+uAU2SIny?|)s9_I)Gf#-*qY*L~@`_U*Um!W^%E z-Y&rvw#%?^O#2T&MkdVl-qAP5P<5wdwtmj&Brz8_=GC61cPJO1uM-{9@u=4_=l&#x z))7S4KY33%{ITZQ$OdSHPcPj#<6Kd7*_$T6C;$T>*#ouA&c{Db`#j$)7o!}80+Yf1 zZ-Ucjtq#4fvHA6^o1@im-KAQ<P3@BG7tZ9c&*z8WSh?#{mx`|LC4P$%_v4<pPVTq= zfTJedDVQps-f$#ol9RPVY|0He#o1swDVK+Wfe+ZR7s~U(zK6X`#Qf5A_RYc`3_VuD zC3z>Sex)#w{+t!=jMWv7O4TAu6?G3}6wJ(-lJ?oah2&RPNr54_jLqNq3A2%t`Yj8k znrC4&bTE)#c<P_M$4{4vAe)`?{qAFLzW5AA{!w`d2#f`AYPwWlD7DDT8+TLmL<t|W zLabGdu0L|!X|^$#^{XfU|AYh$-?74tysJx*SvdA!;j0b@Y!dxGJDMq*w&^@{otm5q zMfGjs({;zxmE{idklr0^w7rW|&Y_Zb@dGCO+AgpdxvjmI0w+edM)luaIVI^98@{IL z57s$0wuT|`6Hu=<=F|lO{#6rx_km2nnC><bgh4RO^aS|s`5X{e7|9(+04^KBRz?RC zOQrNXK)5ZuR_dtJlf<}MZE&+XLsC*tGkc$qbhu6$Z7)jCzpGa-3E0#-xp-gtE5zkm zG&DUKl(`+OP8g(QqFdWE)^c2jFQIDZf;eyWir%~S>PCEk{MBjH)w##FSW9tg5jRGd zHwUV@R|nsDJ91U~TKteP=>i5qhUW)|jhoQ<iJwJw#8^VTDh6;-RBaLJWXnFWG;bCH z9ajVLY8RgDRlHu-JTUI>E;kvWyGrz8iM;-E1DhN@#TJ3t2O~x9R7@?)_(O;tGAcPV zT9zU7biY3`>;Yb*+Uu!Ka3lpH{r_pU4O353ru$nK@OO&6O@`~A%Ixdzf5=%ty`jCd zkEF%AnYt3QqPd%vv#G8T_k6D-<>UiL@fqdPZK~YzI!_+MKtsCYIAlmP*cg(h-B|gE zy0q3O^f7o(H*Nc$_Owi%HTCyq+^NIVkB?YR>>qEgTu6CgGT-Oldh%<Z?9lJ{#E;>( z41{O9<~Tm+j!6k?=$YIXZ?s(QYokAi+M_ScDmz}g{yXZ5Xo}v&Ux;B%7xb%=H<>lO zF1K5*4+sWW9+NuvyX=ymSJJ6Nv-#aottew@P=%g(UiFM%mF=}4L`ks(Nnc)mkU3mh zVsSIw`1tAaIt^*hS~hg0<Z)e4K%S8=_~SQ77TCQ<R3>M1O!UG>M^;LP&plxl<a=u) z4^*TvVDi~sLsF)vu!c#TFJ9637A>NEBxNE{>_!G1+>i_f|EZ~(dggZe<c<BFrlkCU z)xN<kTO{57uH!XhagC$TO$00tQ*vuerfARa-hC<`NcY&{B#gc^^*yJ$Q`8~7cLGm% zUPAoG=l0~&2XZntW?jH)G1-XL75q`D8j=~+1A^Y`|30XR>v(oPGQLaxo9e#-1t#Yn zX+>X&vLm|;7fmnA9LE|&A4k6^lU;Q^0{Xfa<=Y)aKC9&Ns0dUf7Khw&T`ilovb~!@ zD1W#o<2Jr({(fg6RFn2)@gKcR_Ji9_#6f?rIz|mTCgRe~$60r?J;{FFGO3go8T6@y z&CtOO#`~x}>A&NZ_YSbH*?KE~!E${;pZlEuiQvFr)b>xn!p8NThhcnTmO3UAlG{g< zAYj{E*5CIlzIcOaNv*$ea{P4#zE5hCnR|ILh+&zaUv0E1{XAoCqQ*EmvS|m`_ULIq zuytR>+#<U5rA;PVotj;S{wc+-esN^%B+BH>{CfSa^3U_JzZQPpAmo><Q`@hA*U94c z;R7yw_^vPF{{iEU1CL=p8!Pq>j3-F0THKG`TTD(2o!R#C-0MtQ+cxcrm`}%deTv^r zGJo+OAfY~=F8<4Cb!0#+VsUu0e(k5P|DC|F?V{SXqqgO7i=QT1?}i@suJfqL;mFVY zXz-gj6PoCgWY=>&yfN%e$DQHR@t|=!3icDFJfth>c{S|1#8P2AEj*q3yD`?~5?g2g z&F&zFX%~^NWWTJ~57p@sd;2&t@4zbZr<b~jdp1u)rUr11Ftw8}@zRuHQh=wJei}JU zka+tvXBhmqs|Cgf<xl~OG?&EeVF{=31J$*d!S5*5p^cv=qiaTN$GN#C&Ipm`ptWtR zSw=e1w|G^?1wEIrc3UMT-eWsjP9!2^_~WHDsukD}V^oljo+j`88J}^O68(+&^0rb} ztwyvicLgdeI3=u8E8CRteE59gpr9(@w^+KiKSCP`uPs)Wb$v3`1-E<Iv3+YjuI3K7 zqZ0lker~Dl)6ff-!_vKiLExO%uD@wvQdLk<vV2zLxK^YCVVOHa4&dHuQf5f%KY>DG zHH+8S6u4h@%R8H&@x*=8x)xR09zSSa6|s6LWD!0vNss2P&6bv`3e-^gckRoWHZ?JL zuaW&rI`yL;s0GqeSWgc;x=0TFWuv6^5N)6EM{<_BUhgv8c(mgzl~Akw(~2%;fMT~C z^JI2S)#Bz?OKWK<nokd0yybp<eervUYw}m>>YG<qJrSo4kT(#U^&vEyEAd|hJ=43$ zkyVo~8+RiJ-{}t$Pt-kpD37q}FgGh3sF(BY(6cV{0-78@0JGTP()&)6#iW>cCsBaC zqgS$eWiyvyx<mrBd~`&ARQXTa8_S$Q5)Ac(1Pr_T7HAK736+w;6!Jh<qJ&>`WE0Yb zlKvc=dK#z6LGfq$gPPu6lTj_XdulmJln|Y5Y8#L*`K(51L*A!}xg?UnDC+lD*Syl$ zb9H`1a6mIeVpo}5SF<F4uRWaGPB28pK_j=^2i~7+xZJ}-_qBjwaj1==GFbL0A}568 zH$rONfl1wiSGHojvTiyYye<Zsplg3;-3e&6A~ngr6b-fha3}wLW@1{p%d%2pErY&c zSrr}dOC?9dEr_`nrd$j=mEO~0bNAFZK9w9j5~lb?HGFXpeQc5s+sQ60wtI~|@(2oi zTH2h3m6aDe4%=3wAN|<Y+&iw{j2SM>x+TT=F$adoOHsWoVd!K|Ldl0tdH+0;!RXs{ z(T$K0BG-EIUf!K1PurOkBy={2Ep?<|3ImNI>dpFBZzYy|l{)SP#mFrM+YEWRM8m#p zTDt=)r3x)ghc)ygX|g)+Lac5o5{{j69i{AUE$X`m{HpP;Qc5O^1Die(gmka_18hP~ z3y*n}QzP3L<9Ep6cy(3HlJ_QA8AAPtA46few;f(Qba}*Ab>^KO*z$wwqZ#u{7cY6? zv@R)1-_^}6FF{?iDK)v3tv0ii^%9ozmdVt3RpX|l62yPOd*Gc%)dmZF|Bu})oi4jO zEf#t9-xD{kmq8KW0>bP2MJ<gJA8Zmw$t3{G1&pD{9{6z1b18I0%_-q-O6XhjdN7Tx zxmSH|PY#qL#l8~OKf4xcVwNFin^|qFv%zcHvXOofPF%`L2yvfT<=M@XE*JzzpBle_ zJDm(3r^WAFqT<9Q`Z-=g(_z@nA9rKo&z9~qz8kH*msvX2sJKOW#Jyf)vQU(q;q}J} zn+0(9_)5cmG&`s0ax6Mn?mtRjxP`b<yfc)L;!U2;?c=86SUp614;URa6$?ER<e;PJ zx>_Ku-U0gIBdDmLy{NRd6BR-mED@e|Fk5G@p~&sB>i&3!kc=0sua@OLj=~NX>5|MO z2}MhbjWXBa@Zf_R)~ZeKM91rs%hOQSS<zE+(Ytu18-MQQ4ZU4@{dgGrb7^w$atYx^ zplg&6KRXAruu{zTH22s(A0bmgSRv!~`wJ>wOSSIMK$M{er9tQKjqB&Mu#Yibq8?jd zV(EuDdrvMI2-!pHf!_U!&STGnbMI>_yTndMn3cVEP|A(&gP0YBxD31kr>j9{RHW0+ zzM3ux+Bu+Ybo`l7NAJi(BzaYuy^yot);y!uXi&y4>p92+%KyiHc<$~sW-P9kZ=0CV zRk_Tnv$aZdZAKvBi~_wa+vriV_v(o`FYB8`40BK_q76blt&afjvr0l<`jf;Ba6q-j zeC}$1R_Ij)`1c;YEqwj7m!cZ4*4%-jmN#PxJDLhh+29-e!cPt-Vt9$t8add1rwXbo z^qJm?Rz8bBN-&}2Z5}c+^&O|HxULVczsr?VVN!%vaI$;fFWtML>Qmb*gxpnxC?8ZZ zuuEf;DdQ7*{A&l9-H%h1nYisCHl~K~Q8>zoZ7z{W?<Z!h-j_doGy~z(cx@D$U7%E} zssQ;(@zEmo;t2|T=u;pt#?sKlSAEL4Y4ajvTzOaVvjW3>vpvLf7EDq2LA}rNk_9un z&L8Hxdl3p4%sTmlQm$``U&N!@WQ1WS^iCusB%HUPXn+QCUD25Vy76PTyijMe?s4vw zCJ$`4_LzMlneBs=rHOWz6)4^~UY*LBGP@nkPh8IcuPjpq3`wFcVdvEccMOca^d`AY zG0n^N**Sd-eZfh@Cj`<C3$^gObm9(TfA$q5hweQ5`YbwapRH1zJW@nreCcg{;<?b4 zeGq8Q-my<lhu^u_QT)6W(DEW7BJleV(agWB0?wEwMbtFHBx|G-`>({y4FR*ViZ(-? zN=7{iZqPhGttiJ#PmdKXob=eynN~Yd=WcXJIzMpl#Ap|p;)9QUeX+O+rWNAHWe(XS zPrdWB-x=+k-!;s))w|$&fDMDz>8?P2-oDLkbj9|N@B)P3;AjS7t@Nrj<=#Wcku2@> zVQZwPSEHH9z?I6Zkta87?*lO1+^F}L?3Rz*@;%I<;FVKTx?nJ_%|X@pw07%igd%G3 z=8xq|$9P)O@g7R6!(lV3K}qbpd~5P#mujW>2*so`eA!-l1t$3azD|W+%nGqTwCR9- z+1b>wzKb2M%T(`FI5=szN2J-A6+Ld&Q)!Kkl0;_FcfypjBOhB;&W_SVqWj?^J`qZ5 zd5>1s)SbW(>F)IHhE_f;YZ9%d$1gke6-b#1D;E0Ws`U-n0o^ycV=ehwe;m^U{JJ1K z-puuXkEl;pR@h(yAofl!3v7JXd#8W3!(N(e7M-Y*BYmm`H?Xbk%|}Yrq*2@Jf2vQb z$M;xaRb}7S1ZuD`1z5&=z{}u|wVbZCAd4)U1KE@Mwh`EUxWb?~uvB|sX#1ll0FT~T zw4a#`xX#v>d=VaT_V`(h>~q8<{CmYKlLNEKP9@R1PX7VVJa>OsFmx983?zoWqHj(= zt?pNL_fj#u%?3psOC`76*pxeu74GQjjULwV>xWWet9MkWCzIYSZoiWZyXN#j;Koi* z^dB{hm^#NBGYw%6<`dN}KKCbQh={nNPk*90MRLDcK3;nIh`Jt&%rg5jxX^d(-`0Ek zqw7Lken#Py98b53*FTRn5JhJcD4aW0_-p?g-yD`KZeIsxXWPd0*|`i4m#82wKzeN@ z|MJ0>X~rMWYXhagxaOxIt`11{A8zOI1);rpexlyL$aq1nQ0M<+*Xa}X=qLSE^3Z?M z9wIm*hAU<I&3Bq)M-I)7{FL}ja*3q)MUttOnl^^MCxaY{p8s}^RcJi`@;Ijfw$#+p zglpQ-K70swBtmIrJI6($5R}82vQj}&YSa4fk1fAVwWH2!y+{davJcq#=UaY7v-waZ z5mf;b+ODh<1;@a=2&M4iFGnGe%VZx|=oZ9!CC_zamKgt?LEyj^F!?vWf0z{WTb9J6 zvkQXQ+`;@?wg)?IY8sw<B_vD;Sh?fJm>QRADBwx34ssbQC1TM$cj=K^g*?Xjde>V# z;rw!qW`;SQF`WF$&jQoMpW{J!331$e@3$42a%=PrI+Fs5Gez?sUNE{+I)y9+lT7Wa z4mQ$+KtW>&MF06{Cvoi|wt~%!<$j}@EKsHXatp^Lq+7_PAw0*uhG6;l^XfGf%aD`C zk_I2iS$I*7!)c!{r%Fcv!S6a-zG`54BK?|##hOyOOvf0ue~<6OTfyF2PYW#ojaCqH z(#BzeT43;oE!pqZ6SLUmuBx~hB;79Rpb3`qpJd)qPR6nr%XQl`w8UH`9lTO;>bnY> z#n3G=Yrr(pPKo5dy7MXh;oFR<WrG20r$DnpURJs-!oH3Vk2R8?>f&wre{oD6?@sM< zI`}Q=76(Ilw5vr)Zwk2VqI#}{Ut}q@(r4nSi0|Pg&O*_71qUs|3<ThGVcm$$ANV%x zjKb5VYA^~hkBrEM&byFCJ652~h5Fy!Zj|p*R?feo)ROc7%16%6b4Ls=Xn*2#Zy%bw zP%fvgj@9;umTLXGj*p%@_AYD0&0v6OD2HMMnk>{;Gohs;@^aM%!jz}8I=bn+Y*_i} z()~(N5@;+lvF9UX-U3e=kpCV5FZ+G%_CA?Q8RD16g9KPEHRrj9%e6C9HJqD}PVUU} zY+2DN<A>K}CEXtDj;lahv;G70l$rBcHW3-p<Lg`QP*T{N_@R~;Q$9DW*;6=+et%B2 z@=4EWveB5N3t2Ry;_V@kxY#j4!o?N&Z!Y<I{T*HEuP_Dw*Ezp#vM|j~f8yXr&A-{P z)aeD+Tx*&Ey)?yk{2krPq8U30X^BmYq`)a5jE<p>LOB`{dhLYw)ERn6g|u_0^)z1O zXX^bB*EECYOq%<U-{6*Ad8oa&@(m+b+=S~XU5jN`7Z}&!61{@LR!wTnVbUgj)Hd!k z{Oibv`{Ng`s`W9pU0v(!@7$Gwjj+M)4uZx+9DQ@fY_Y_>vpO+$x7S!3ZnQRIvvN`^ zwjYtx!ED!%ZR{$Weg4um2kTWAdckIx*eBJlClZ|Jx@y~rQm+4S`)hm2F03zkr5!s^ zd!pl;vn@x}#m6g)^dn5#N9WlzRG_jNDkVF#(ylBHTw76W8pQ}6&#tdpZSz-tUe*0@ zwgf8PP#=+P!g(wG(`xf8X_-%g<`1J!*|*c*-0H}(_es~f95mWrswd4J%c*fZHUW|e z)M?o-5WJN(L$NO(Mg>2IE<Dl}aanA;itg#EC(P2294LZ~zuD6tYkK%zosu4d*k>-9 ze?_e__ju;T67@3unpe$8vULio^pejIluG!uqgXPb$Lwfs4+-JZxpzdn^0RX0f*!<p zgihBchf6NUEp%htyQw-KI0$zBjm2YiS0k&umb%3Z<+ejsitooQyy#Mkv3FUTWG|G~ zdXQx~?h8@QXv(=KW=GEpscQP_oBjD`HalUmEOPZ-cCgf`?1UJ6(u0lc34LYuX<TC$ zrm-q;3wA0ZJ?!hE(mBvf19EA7I>M&)S8#iwcG->_6`DsE&>2}s^OUhmKjljG_v9iv zN;Ax!SsGDwopeB%(f^y)(>Z&8|ME_>U)b70n{YjzD9b-nY5vAuDor6woXHiiX-XhS zrTLF&u$kvaLsi_opX>?WZqoR<QpIHM^T`8O0d|?sozx7c%7-Nd`s^v=>4CB$&$LA2 z9YpGgJ;7tNFO>Q#UGDz@sM7my-W<tYF=UIUFHUVB@8V>JeoKOkxL&zq+L23T3zJ0Z zf57cvdiyl~_xlk@_br1yO6~qgYS+i2pw6x(L#w5n*?%Znhi<~AF#TR$<EI~Gf6i(A zWsH?cQ14mkowdu={7_(gJ5MaEX`cHtVR<~hHJpmpGeDM2RlkS+zJ2qAqr{he+bQC? zgZ$vtP$rGqQy4rU|0e~P{HZ`ixhK@1=R7xH^`bf@?vE5VOPziD>*Ph1@b2t(Y<8>E z^!IJuIBn5>GYJ00!m<IsuX9F?jrb>J&rbo9PN|en(FvSAS>%q!KpuJd$QQA-&t<m( z`^)*YaxTzscF8)ukvUmS{&~IqdXgko^6sF%+)B~8BP#cW{=au5v&mL)&HlT3Ln6ec z-#MY4h@wnZxD=#WyZ?~#h5WPK)CUI)hL|8-?N+`)P?4zVomXD3Nk;;Gubg9*bwzA_ zlNetpNTn$76<Vso74w533@K%F%kvqse~vIGrirT$VuT04OJ!nw_}?%*xQXl+RABU& zImF5SewIo{I>8xW1X+x=o_%pOtRP~mC2i6#X&*nJNQ(r!-m=w#WeU)Q=qt-Nf&*|Z z5(vdMDgEd_^K(CwGE`)&pCm(<o;9l($OR6R0B$gv|69Ph8OfqW(7t)xDpiH_4WfV| zl`d5yjkRVdNZcGXOUvX>@eM*!qQ^+es-Yzp)}V_kJH=*cV%!!g;U#W`YaB^U^M_{7 zAKW{~&}J=3vSo*+HU0DsY)a|Q;bxi&6vYKRR@spho%@@HPXl}rPG#>e7wc)M0H_eq z6L8`~8G&7a(zFQ(jT#{`>0B$_CGuBsVRj?hq=Yr^`T4BrL>QI{Mvq=RxPEJ@*&|>F z-;xw{$&K*czE(a*HY<1dWz^qVSDZYI-{m}Vvb^JHD%$_ydXDgnGR~IUNOLdHO+RE^ zx(6`i_HGw;2CW17(<Wpw9Rc~S7oh{9b)0<Q{ELkzz!4|qcEKrmur<IBynJSZL+g|G zK7AYg?3G;G4qo!dNQk^BlnPkl1S21UIe`OhG95nJ?{Hp2sGwQD0m}YjL1q@=KcK$P zZN0#i^p%6Eya~|Wh>P0(HM>MHoU$OPQ-610%FHfm5zQtX@3z(gzW8|AMpMfqnvX=_ zhRd`7aKW!yZ?nD>q@|nsSWDSwVOJS9ujMJUkB(4#9u}z=)7pQbDrfez&F@_v+E3$n zBLf&4gU<sx%mDvUl234!PEqaHTiNj2EZOJ4!=0jVYhAkq>d!@xM<mn-Jl@oAmTXOV z4C#ty<ZCY<_0ewzr~3J7DZ0)nqNc&-fQqr*q`)+eB@&+Iwie2(FM~--7bHa!uYf)p zO2NNI_SL~oBwXJQ5^|*McxcWFLUQ8SQ6V;8?8TxFgu`0_1*((_)EA{a|4-KzWNAru z;1xRC*?WAMYJ;UC)xTA6yNWY0n{{}HR<41|FvbBQ4Mm3O6hbuRhHIr~{_2DksYn4R zZ1b#Pums>aT2<*G%_V7BUl$UzhJOT205kpk(epfc`Hi5a9hireP%ARDg#fT+GBzOu zsJ#64bI0{vrSsdFw!*cOF4TNLS$yAVk~-_z{7QR-iRnAir<>XJNye~o`sSWBc6_PE zu!U;&z#K)vrVfIv!5kP&D-ttZ2bBhU!!+7iQ#QRuHf`)ixCe5jU5!zIR|-I^+H=YX zS+rnVr?W5&_~C=PVU1T$TC!xMZ_~+Gkc)&vx&$#BNszru<%JnB0!CdDH9Bw|EGQI> zeD}Eef?tXT|DJV@1W7Yp#wSGdl8KLt4YRVlV-k$!BT^Ug;2pK2KcV~!0C$iMQjmg_ zvxpQyT`>5caJ#)fNU2BFnoV`yj4&0b*<mh7^7`nt;HNTZ@P!$#lv`lO+;l0=DNGSW zjKO(3DX^MwlGQg|A!<zzwx6N}svjR?hX^Wl(6X^UQwg3WE6u(}16jxbwb~Z=UNEu{ zE<@gW2t=5qDQFOS!Sq)Xr-R}p>=W=yvU!jZNW!C39~~mq3skN`(#-$ja2V~>86K68 zR{zAM63Bw-1<h%NTYnkxh9X%0$Y9~1X0MO_0Qjxxe$Nz#PeR8_0mtCr7%#X1{CA*F zP~r3Iia2B-22>tee2!H-bQgm_9OxCAX#%5ilf^f<DLw|c-iW?)b;9|+syKGm{g}GV zPacyy4Qbm%%QqM&cg$QCmH`H>i@i%}T4$|rhI8TO>G+3w^Wbi1_1_EuD`eF8*$E4G z9bzS2+n)`xqinQ<*~iZq&or-L8VoUK$2`OV$Bf1e;TKx5EWzM2f;dz|ZQ+yS6SyXR z%6~vcKA^PIw9fn$1`3WxNe81PrfWM_a-#?ca%e5mpGW!q62U5Dbm15ldy+?ld?Ds_ zfJ>H2>p;dS0zs$)imJ_HGNaoe=pUK;Lrd}weEQYrJwQ6X2U&WTebe@Cw1B}?bu7~h zR}h*bwy#yuBDD`cX;~=5@EO)*7aY#{T?zS|ot}vV8FlOTAAj&*kF4zIroA8{#*F0u z=zd~>H-OTq7(<*nv38rv9VYP+lL(>+k5w3Y!bm!a7TNAAG_1kFo7@d{f!@=x%UR9E zow%j3a<|XS@hzZL(R&p_b{WiB10NsjOHryS>?GX<Os)1p$nU(Ci6<l2C^OS+I<C(n zpfG*VtGT79_XjFG?g#1Q=<e)p2%4U+p}$R=oMXIVJh<Dj*}F2ctkSX!`e<TXs7dpN z_M!Ab*#_*c0v`boF&HqD=5jZ!R85lX<Vz1H`RzR_c(^%Q*#vq5brk;t{CTK)P^?Vm znN7%5G_MSYSmimzygq7O2*osRuFzjGvtkU0sY%$urGmREuXT!5_9MxQJ9}vWo1}-r z#;{8@_pF;hgHLLfBKr?V<5cc}vGmLCrDC9BWgmm9C*qRshPj9HW_;U|QW&BuMMoz` zGPL~*8`R<ZW|-)kju|438-@sQ8@G_dk8vJvHYLs(I_u4rv`NLzX+n)u4+cgRt7!Vw z25#LUi}>}Y_y)W5n*;TdMYkJ#i92<9EoTgGGw6=5bZT?SJ~@%!LP9JR99K;=PB*Qh z3>{5+U?czqN_ZG6Yx%YcSAFsD|A4`SYxFWpJRC$rovxX8_g$5*LlTEc;`)umUJzxt zzCtIzd=+Uf2ry(~j%vh5)@b>LMRG7B=8bZ_`uvbSlmKutU}CugZNCLq7#1?m6rl?R z;lLqe`R_cLcl8E_^zEvadcd-znXnHP-grsxK)0vfXK`JJpm_$Dp#RL~DP1Q#D?9Fi z7q8?3+jn;ao(qMciY}JBoiJ8T_uA}0<Oo*Swt_-`*x)xd$<NZuB1_kzJxo!EeIKI? zmOoVbKyuybUxox#K^zy<_%+*#SQqL@_%QpdR_G6t;93%ql<~J`yCXl!8hH)j<`bxL zSdNYXmdVu<oi_8!l0g}IcV)K48cBPAg$d=p(M1Dfl$Hw_Jfm)BvQT;JTLC%1(k~@D z?@#mefz;9k<8GgzX?#lt;I2(}p^V>DTLPkW>4Wb9X_%9CWYzK}JdH$c$l9kn#CU(! z_VoHKs7x3>UHB1VcL+(@1_Q|9gX@&u$PjeCTraCcwU&eY`aP}ot`|WIGy&)?#kMT@ zK=z{Z1)~<%D?lX=hkp&7l>5d59uq%V#E=VK&&}m~gn`PJ;|mnH={8o`>DS?~2vBB& z%B%TOyU3frHm#EPMj~-&Qh_a5qGwTy<h)+&H~*5QCyY(;>ks}H$WVgMrej&WUP&@5 zBJqsmNwxR-!~3Se<6FYQ>u(^Io2{SiILARLw)IXt+sr^2$(WVp15o4}xS*(8`@EOg zhCkg4nB{-vvE1AY3Nu9q-<}g!-)Wss*O*x%N1Sc4jDXM2(NdXI&=Cn}^IKI0c6VBh zXX`1}Uqa6reB?nJOYdJ#k<$9~^(O*6AT5!ou{iR2(^iB@4}a6hEv<_yI5bCcu_pLH z4zXR6y=mnu3G=>P5-h8=d;c>`+UqlMTFaJ%rSxyg$%Z@OkM0Fq#(#?l_3|hJh*=-k z_R<b*=Sj4}i9^Bvs*^L=izqNgQv~Z=C5UL2m&<x-I1nprC8w@>DVVxf^B#TF^Gi!A zC8AG~lmwfKp2oM6_=ZNS=41>8bS<?Y8^IQ&1{?;6*eaZ8;-82BcMjdVvwWZiHV5$H zPZPT26X;`BQ&AuVu|bdo^_@FlHK<y;%A^)j0f!RBfl=cHF8ADyi#RvJzX8+bVlkZz z7-h6kH~{UXfpm!`Z=)>?_8U3iYZuv=?G|!qt{g3tfdnmvh)wk*Rn1u4Z`fby6CXU~ zhhzNvx|f_tb<%sc6>+CQRpIXP&Zjisk!Q_@PeUXJns1Qjsr$UotRca2LmBC)sO=Vp z|0T=$k)Af+JZxYLtjW{OOu@p+CwyI+O}6CC;@BwS{54*^a)(SK%idfF3~{0mdE9>i zdsi<;S2rzSbXRd#S|3SL0dw*|QPg*vX=+N=5Zc5agRpAy{)GJ|nhzk^$?ute+O_<5 z)Jz(WW%Q0czXP&9y$5n-stes$H$N<bNTOuQzK%_T-iWGMe>i9~1GB))dPTeYlXn&Q z%J*l%)jE6sLgbRnbUJWox=A>n=;=6VHnI$V6S&Kgc~B0ksSaKq<V$_Ec_Z9FCOng! z-HprdcH-HS4uj8R;10veV)4C=;TZmT&OXUwrOn^X!WAVcFYUk*PWp*{{S=NR+juiM zUe<xQ3>bQW_$htq&FXU0CE{jCzfbQk_RvE<&>)l@sDWrVUfZ&Wf*y}97zDXcp6!}@ zy5n86t1fqT*<>VmhHE}pLx;fTWx<jS&PmLinFohmIWUQ6@LNM^iB1{QD2}kN;SO3M z;r^~1aX?k04=TBINi^L6C(X_F=;sd;UMBT~xPVhd99<Hw7xqg_uWzt?8h_-Xy&qWw z&=Cy#4`@je7?nFttkKa-W)72Nf29fsvH2siP0cS%7!befsEBGqxTfusHeUPP^tZys zmlW-J6F(twmTIdE(3a>elJ7We@5(9AX;?JLZ=R_cqJmKwZxajxfJ1+~m&nAG9lYj0 z0-KRqH!`9`&FDFxWOgE|`n!e`PI^aF@=Tx`fu+%bk>Al#%&QZy$N)HVJGmoPLoa#D z?mp5WlyGJC0B~$duL&J8h1d*qK{Y7;{gUo`afhRuo$=rv`vGrLAF&s-RuKCuaa>Va zdAw}p4+$yrL4?n!FGnW^pO_y%EM?50=b$G{9fVV()M)T%u34|mjSQ_PmSLaLAaa&h z1?R9JnDdJQX!Lrf8Ezl3`uAvJ@#bU-y*~`Lly`#o2c2=B<x<WD1*C^0;SE$E8_Z}= ztos{BM-k02Nu)`dKf@&1poJhbjblqf6r6lIVCb<~B{v~39ommkwqXrq*_S?=#rNeK z#m!ZQ-_{I}gybYHrH|Jj5U58hZ*Sdrq9xr(0zfBc+@WwMAq{)JAl>oAdrYGa1HF;| zhy4Wi6u$61rdq71)gQ*vwc;`IgU{1m-@;ABPZ1*-bo8WMdfwwIk2umVHhF6joEYc` zyWKu#z@SxzOKb1Fu2ae_ezta@iuc;_Y|yn#kALT!znPdgrPXxDKp~Mkh7W$P6j>a% zoQ*gGrm8L}J4_54LovzEMr+1*{z)KexxAWQ<p0M<qMU2R%mwRCZCm&YpFPXE6@Y>l z9-`Rr)~T3<8GCWtyB!1e7rHdq-~*d}e2M>x^<R+dFz{x0`Dh;$8Ik?q*6aPGkDRhi zo{^jL$^U@VF`D2Ac`xmA+&|A|5;DBZCT;=&#er9=@!;|9tG?Q~m;T5qsj6LJ#GU^R z3Agkj@YI_@>6uMC#o~*PQ{Oi}jhTf(v&N|_rT+mI`m(MFnTAICpj78S(LOGf&KT*@ zm#sgSc--5P=mwV~$^A>Gea};_2nUoTz`hJor|icrgf=0A!AQZdw?mJ<9yY}e<?O-; zc%|PaLc>>_uDa6_b6g5wQw}sU^}8M&(^AHL@^TSb$_IbCcSmUe#9L|_W1;2xEv!TA zY|af|`R6I4c9f4!A$F!BU8b+lQvjI^`H7z}o{YMBkV!Y2q9_?!NNYXmuy?D4aVaZ| z8)#r_75@ybX<OJ+VvNyty3jMugFlyioRUA-XbHpAK!5xjn)BxrEq5YAo6~RgnRzS7 zBguzI9n`jYo*ux;+yXwI`O}Fv4ajFMpAl3wVmXn6!B}F`N^LW_=J1ao0^nx!y$+Y| zfVI`Pz<w+;bcguY(6M`%4#SA3BeQ5;g|;Wy$9XQDE9jfa0W5=kZq4m@d@l+0%@cYw z0xq*cXQ{L-g7Fodvad<|HV?ya2p%W`maL$^M5xe^Y*Zx5kfi|e=_<yY5WL`pgl>R{ z&$&&+!Ef+PNBRH_0s{g&_s@)jjH|2P)87eMs+z%Mvtt0Im{VXXj~<)a8aZPkh8n=K z)J;}!Ym#lA2~wYOwsv(Iim!j2#9^|Yd*MY}NT-!DbKz#ag4Uqf1)cQ9sP%wk5J9ki zysb@G%;g>{vT1EEs^rWnkb)(<NONywh;=>F=#(J{Y5*c(cqMfsJD(&^bfAtIXi<)n z0nr@O4E}@6;k+x&%11GQeY8o5EQ9dO9M`Kdm8!g9y^anB+A-J%P;XI-uBZEAo7Ucl zez!1&!l+Z`Vpe|Qg4U6}!2vlv{|NPj7`KCkp%L`GF(xfEH40e9j-zyG){k1AS=Byr zk<r|9G>P>;A(gw?4E@u=Koa+)v~!d{RPyeEC&7dbQ`Y$aO%b8ns6S(!m-Nbi%%oZs z|8(%}l|Nqib2;S@z4?uhuU!I99L`9s6Mw>}J>gQ>+LNzegTp6`hV0N<9&PjTDSO(2 z4vd~}ml5&-dPuwS<>#dl|0ec8q2Q;Uq+Y=VU<EvV{PULa0X7){1B5~5&Yu@bMI#4W zVz-+XtJZh4f~}5Rs;%rWLdDfIBEtj#TuI0+5+i<d&TwIyxKcoYC<)HJ4Bl1Dxh!>q zib-K)FY}BLJl%WD-LIqfK&=>l#6cgex`221rd6&jcKDBZm>MPRr8zqp>`DhrtaZoD zg;1L)kU^ItSVhwEWVyN{n${-$`%GL8X*XhUP3#))mROsPPV@!6U_N~7`*UOwiXO;G zq_l4J^Cyxh#VVwzSM@P78^Rafl+EkjZuk(|*hUU_+$;9daN{ye19Rt%Zukh{`2G5< z2B}{6Afau2I7_XEU`xDFo4;8}0nID0FTAnb<2)t6Lp0;hu;GT~GvssOa{kFJC|HoM z<09<W9KB84ad<^XaL7oqtX2UL2W8Gx4^f5A%N}kxL?@Up$B_hj7Cu5omj`tkkEqqG zhY`R+3qL?!?N!?qIEuM9DN7D(_z&3n1~?U(*UgiKZ%5AwU~nTLR@E_X$I;gsgtrIv zHuVr9`<iqVAcP;iJ-~P-!#iKTM{m;yhVm7FIw^Jb;V%$P+Xt7j4CM!>??G6Lk0)iZ zduS7weIW}8VsNOOiyYjh-7Af~wC5e025lO^`WHaNqEjnqTCM#G{#Vede0GzSaVL^2 zJC-Iv$>R%>1jcA9BLS>6z9gjo<ZkdCn&F8!FR;<L7`(F6P^cz}5m#&BEUmsWU=hd5 z`UBVULyMDC0pzxOBikZ<C_kRtf!bgZx%xRfT4BGhy9Ac=5(rRnY!e3=rg+^~AO8s8 zY*}CDS5OM5*{>(gDm-2~GU<YOf6{RO9thyxAIgjqNcF}CEgHSnX--&9f<UA7GhZc% z@c9JadGRub>>hQPb|<E(i|wVsE^E-nHUS5@$z+g4dw(J!Nd<-s4s64rKM)qbxvuDd zDmFpCirByfP0=68(ISGk>4T*T=Oi@HA7>jh2PDMXz%pNsNE6%&v1CP=UCSkJ1q)k6 zcTrzNSHa`PqOsP<WZA2ptMZg_6LKN5-2FHJD*D$uM`oJtTnGe-V)<&(?}1(db~Y@c zBL^0Beam0=qcC9A(N1JcTx*$|bV>5jf@}?h)=4YngpT-NnUWB>E?P>np>{CUdr84n zD_yUJJ+-&~WdrQ0AeQ6DXzTJD#^7IlPaFpv{OAh>Wkpe`=w+<-oacC3O$?V7VyTGp zK#fdh4}z{J7Fkt=^KO!8C3xWFJ0r7;aDb_QZ1Rxp-8F`Xf1ds8Nb(_^8>)f9Qq(N5 z59>c1`90V*3~Ojr?i9*`?|_DJ;;(XiOTMwLOZ}-v|CC_ax;1ofE;?`$XA=&~VJ$Kj zc>1tE9j72*0w7Q-C^(?1&x*(n#%WkF2v}34>-=l1WQwT8YCg;ll`Bxo9|jtH0WlNT zvx~%)c{AugpqaO_T{ms)I!AkPFdrullO3Nl=c|B0sDwt&rn%nH3~2@j+^9fblgZJ& zhW0D}7ifXeR%hU%#BYP;@V<X@#E6j_AWO-Kf2YBZ%a|erm>XL}>1c|!ke#Ni%jg3o z`yc>G1<NzAdL`#64N{g0<4~2;I`_>k;%<K$>4&bn|LG08q8246q@e@5(x&4JW`c0a zoD<@*GlJSjIMjY~{*OC<$D$*_GWl;ojkH%ikyi!(_H-#RcW#jcjwV*LmutzC5%^x# zHy|{>{;b|(qEYy?*HrbkitNjxK*abI14%8rNqtbvGmUBI%Zk<^&feoAShJ!ogyyj+ z3eZ1Ld5nA(c<!xQhW^#HZAQUtB%^8T?R;CbRXpJUfGg@GJe~e50zxtJp+~I%cw-rU zAa|&)RV;}6|HS<Kh!lM^gh-3r0PhCCVZVW6ophfxVrJt`23m<cr7!QpBL%ZTgXno* z)GaU$F-pA<{2WQ3Q%d7(BJ&dZ($LxpJHZyxRLJraB-A1AX6%b5r;-5ZAGDcCDKuux z%%^qmU;mI?sNCwb4v{gCp>POee^C1GFC_yrbVy@^f*k1vTz@y@NGab3rOC6ISEGL- z*y!}D-;x-+v#zdi!LVXdDtWF`KZ{X>V&tFO4DpLjsW<%6hoNh`3@s?WS$65^;DD-- z4XY-nRvOR*#x(q+f^<vLL?=_m^sL%-1kNnQ*D*oF!DPsmwZ2WD`y6`SpFNhglUF1? zPjv*}6uy9^bp?ctjYwVZBamd#cELXg7O?xVx)*D}Vb+39W+7?Ddn4%~XUY%z&{4fU zQ!q6IK=6y_PO^&j7IdqOru42;kI#YDbfb@Rqs>-bi=Eud(P+g@B1!b3?t9hK9)>bX zv<rGyv%AYo>U<`ZNa~cFh(JmZh&?Xp%86x;q+If=p+ig6%tyPnFF!i4?A1~o#Ma<~ z4VOv#-HIn1yx58HQ({I2ZONH?!h!;}3!cB03KCBC{sN8av&aaOfsL4dGHu;V-Rd8< z!&XY&o9B+Hbx67dyH9J`;fFOvL*5B`?|Xoy{*E%**m@go7aA`2Yq(tdiX8eCdcv_- zbN`cbAw#LJ#Ib8Iur_jh=7^H~4{$$xhp#P`v%3><46n4hG|s-vVnpoAK4su~gF1Tj zRus%eo*W$bM)jR%OJR%b%Qz30C2)_LF1@ZE;2aV#Ygigo#5*y}dRg17?GG;Mia*WC zw@Kv?_-K&c*$83IMp&Y{fEhNetm~1U2BYR@?c4d2^24<wd9I6zP2@<5mQB9VF|8>x zMF0@fHGc`&OV=Y`&A)Z;V~JZnLta=Z@)yGV0zejG{@mGBHndFoxKM@Zz8wcF5$ANY z!lm@ZjqmO|ENoyP3CRMbc?SS@$zx|vFI}&c>~@J}j?1R;tM&%$w)uChY#vS}`~NAu zDtt6((*8h^oWst78R{>-vR6%^(-pPYu?8KeQacBtge^!Ab{R@*<*iJ_Np%hBSXG#V zX2hu<Veig;P0wUGdC7&w!I+H$Z&aT>7VI3~a@xxsCMnr>O4vV2I@;OW-hn}FAj$s4 zo0lkjDWeb_fJ6E9=Izoc&#o9J;T&Pm?0fiNm8DWm4{urY)XwLCHsIpGyztkQING{w zCVqfcIG<V>)u;r%>+i4@qUZZE^~G7dE=qB*52&@<%(qBNxc)`}{t+E28zFjAq)jIF z7vDUy-H?DoV8{XaMy=W}B(u}Rh*TQdVLXm|O|7^2able{^kvS$tP$eR=sn2<1J-fn zBQ-L_rLrZ)QqF$$bwSLOQ4maS6;s|kTf54s363c}QD;vsXs#y-8W?DT8QNXc(|66K zzNaG7(LN_NoWF7U!$PbxuyfX?N^A-NA-96kYnr*pml{_~tvh9s_$Enx{r@RCaqmre zPx$ZgrFrP~eaI6Dtz#^0S@B}Z{*`btZ%AULU>U~)q1g|vzHH|ncD5Uh65=ucMu-r( zHz7w90$mkpUcy3~;ogp=3QBLlxDA2%PVfP9gwjotb*;Oz#{%~=y$O#{^)~f)Dael> zsS_A{AcBEl45S9|(Ta)j6-zNKS;D;e$Tp08MiODSSi4t$bSQaNRO;24cK1X+&nJ*} zNeGvj9sV7vnxX<RV4cA+DXPF~eh>ft=jfhRSrua6{@np0s0S(#@T>ztBVr7g56GY( zTF#EWk=5mPMKU9qlu<3q3ax}sc8I$OlpvPozoT?bP+D57i<ZXN`pz4qH#ppSj`3Xb zTpD2sKp&7FqWT8jR2d!P{}|J2NMHq^;-)Om3@+Cl7tQEj1RI^1oCAo-6B&MIW_|Q} z4RFUP(F3{W26yhu(2ahgLMY!2@D~m|vl^KshhxCJ!A2S>eoD*!V0zQ>h=+zgI>8nl zvi+m)Pu;dP^r&aa-_9)vYbYLjwOw{P_VBz?<oEc!Q)_)b{|Jt0wH~)>5A8Hi?T#{u zFtvGW^4I$e$SJ6ZcB|+O0+Vhw&F}ZR_U7kJhK)og{Ewz@ac8>!|9>-?!`c$cGDZ}k z7~RZahVGn_vsC0XrQ|f^e3p`X=3J_Ua#oRY%xMyHD1?whXvAWUa~PxF`}4i7-#@^0 zz4tmiUyoyXW$hPB-UWx8{5npVhgJHtf1(X6U?*K+zxw$bH<PC!mfXc(__x~ujhU4v zzH1H!n(R|`fqlN4X3#n3{;Zje$Gm&bnU>5BzrEvR(AU9P3ppedB^MI1eq{2oWtgi~ z9q09~R1W@JuY8W4dy-CP+w$WGA5J3Y_1uT6V=tFoq9CI!w|J)31g+gv-ra#pbX<2o zh-=Y~z;En~ExTc#*rbB=d>}g)Y%u+%{3ADPXVC$Z@?=liHoECIH~wNp-&t5_lv+a- zdcDW$883D_V^_$@HrS(3c(F+@y1ilef;Y0-Yd1z+{vbCiWHRIZ*eCw^9`VYh=r*=} z<<ICYtzrJzS4!8m+~Qf-3h|mRk3D;+_XM<w&oYmW?xDBz>^5}F>Co_Ty2SmP9r(3B z?3Aq`*q9j)K{0B2i+)>XQ*`tAQdj^;k9ggOJ@W3wY54Zd$2y;jnt=AKZf6(c*D%I? zB@?fcdUMyFbPneXuyjR9K2-wQi*+epEY9Na!7-t&vv=O9SRaX=K6ke>t;RtVIQMmO zXBLDYoZhZ}=JF^rgzi=f6Q^L&9ZfI`s_Ug++D(BI(Vx^Jh4W?jo^}|DB(%~78V-AO zqgO3(T6gesDTyy$At9PWlq0wR@mloKp8c6$a({s&&y9@7)sIz->bO5P*+aK@zMbW9 zd2^t6yB^ss_^3eE1Ivy@pVKB&>;--*eid(~(T;^*J#ydcr=YjkO46G1nDJkrolB97 zoaEJFvNLlBnx0=$s#&Z517Zj^2Ny%;nUX!nV;s{S+)ZxLz)s}Z*Bk9TeBp2_;+h9s z+CoV^h;!eiVh~!)u<pc%o;degF!h9T))2XvK~~7B)4lQGF<!}of3ikWH+%E7Y4>NW zmz0mW8k=6MbE|0~NA|yXzEG|pNl{H%_>Y54PX~vtV5D7-*pPo1j55C}YUdoNI9J9t zlKHr-xeFt*UOx+vw^6Zb2{Om>g~^XkY(Yf_C3+R!{1Nj0AuXiUB~OrKwx|(@<`4NR zY(2}pceV8XO$+f56kUcA2D!qz{EzalXq9uFw?3uOv;$(GzMTT!LSKci`ErZRK183< zlqIaw`bXT&`A?{)$R3ern>GX1xxu?k#`V8|_tiMD`Ww&rW|<Q2aj%u{hQ|GyBI~lQ zwe=^=Mix_&%4v?(9}8JbT8t$nCpsx6rev$or6`9w(dLR*I=-HrJ9X8s+wl1E+7M_H zcid02IvO!<CpN3$MeK#*O($b8b}*!Rt^Rrz;Kv1_1Yuu?3kf$@UyJDc?ENlI)z+^b zJ00n#==o>D>Edi$=}Glj0!NPZX5l8=zUz>Qo@EW(s95s*TY}&7EKIsF6@<TY;y0Ps z3cUPkx7_$4@cQWr!6hT}>gbC$r(cQ;)U%J@?pk==FXUh!b@6kp0N{Q{PyuX8oyj4N zvdT`M`d}h?-m!LaYZ{JIRl8n-tbcK6Vok}(Ut-;dPfIw(ij3EqZyqFWRCl)SwIt%o z6y@g}Jnm>$dO=oLi{@Fmx6kE?P7^Zf!UORMw{O`sHm7#D%5+D}5VwO!TM~Vy9oO=c z2@8Ax`Gppt-;Uiao^pmQ8$f~+e>ANn(N0bIVX^}0C{#d9GhO5aoP3S@5FvKkWb44N zR)-_n3Y|mmdxZ}hByJz;lX%!d9~8a!)Iw@4hM3auKj{1LbMf&|$FVO)il0E7(__@` zQPo!R#jni+rQeOr{sQLTzdEZ}$hUv^GNwj$&>dyoIR0?+%ykp*S=<9IiG2*~E$oYL zWxK)~|H!$Bbf`YV>c^DhLPjx2?I@M$F07Ek?Qez_3nr+R-H&#y-C#P-q|Bvj3L~mw zEc8IJj`mr6dr%zyOlqTaXBUt=QupRV@Cn(Hmuc6?{lxD1l%9clF(B#Y5@A;OyG2QP zQ$E>F_%);@J~kG--XAB+e{K4FX3kW64kZcZ#nfDM`j+?L()Qu*H+T#RwI!job`Vm2 z&%cZtJexXcqG7%3^X9qCD{s`Bxy}_Fglx*Z<#~3Z{E5Pf{2S?O8sMTpC%9HAy^h0< zlcFs?)eK(G`SpD!M*b(s7^|&^AFQ@g_}a4;yMAn5Hy`v&euX_Eg#7k8yx3vaY{_=? zGbF}%&eR=0O7l56mUtiTZ>Z(Mk_!C&ss*@+q$)S~?lo6G)t;rz&4xw?53Y%D1#QV1 zTVIq8)&({@7x3`7yt_A#JhD)(^{3B`L7^PaCuwK9LoaU_7Aw+_K3ZF>w?9OvjM$E- zE$pY&klmELJh-3htlN@_*NZw_lbS^~>_VJvN@KY4g~8$SueavRYG^_5frd~Nr+6JK zbLaUtRs7U@d-CykP8s!;eE@fUP{=+wWjYb&#veQX>OfRGt^ZVg(;iNWiS9FfHT}TO zz@)F+s7dAgS?K7LC)2=IF^96Lb71F0#AFo&G#QU^{G#_AZMWEWEz={ny!<hBXSO&W zE|eIkbl2nMaSsOv*Yfz@=62c|vlWK`BOb6t^Q+f&^8t(5k0~D=hCJT2zWLnkPT`sC z%aedgZW3*M>}_iMw>lX#3r}DeW2E`-EuIX@mTV-p#P{S)QoB%(zrN&CcKxoMtNepQ zzBk(S7#+}l+w@~su8AJ3Sh#`@)VHwCYql`Bai=DZR(Mg~l|Rc6@FGlshlpt-66OT@ z2bIB7yja$QfNr9MAK(*!3%8d~Wqh%7gbBr_gZV`<+IElldk$^=VA5vBi#)OUl6Nue z7y&IfG|KaG_nXd%ygtRWSVnvjkh0X9AUl=ZCaym(_p%p5igL8;oC*1H3BsTdSNbA? zOW#U8iRw2vstSdvG09lg%8h>>W|VkWXZg7T^5b#cArttYg1dpGa}aWx{-;;WsBt5- znIFFBOqb`NY^96PheMU?rKoiy)4`USkn-l<L?Gh*yFYeeWECy2qWA3gS<5?CW&5)~ z3j$klDK+5-S?b(FyEpC+KO_cbxQqsK7v#}nnU4D}me!;bbr%j+a9gui0_`_i9?N#| z%Sb}qR8@%w#IeFFT&nRg=7ynQarpW3|JGaEu4?Ut+ui+IUU>}dw}s;>8M_GO@7M&U zJsuaLF=GI(Z@rz@_1;~XF$mw4M}#qZv<k4^Ry#5%Y9M9iKzwjfOt&lqj16j;!)Kgo zs9BgG_=I+Zh-Mri$)&5Mb@2B|G?j1<luQ77Wo@gR23x8(p>Z{!Za0iDQ1BrJ+%RC% z-><ZpyZ+@p>mRr^f@uUjm>|-S9V#aQ3XYTn$a7!Y@;|0OqOQc@9c|yM_5QgE82@R) zcb3gQdSvK(?%!UuZzF??_JKUUb>r?Yz4oFJ8$3ZJvo9jDf4L))>tsrR=mgk_e|4?I zj{^^MVh=<rJ1`r{kUSYM4zv70%HM(C)kA`9+%Xs<rADT+ffl`qnDzvVL*HhHO2z+C ztXfm0?dNOpvL&Dw>4V@)^FZ`-Y;LOP#Qg{w$*rj-MGM}!@DeE&Wg|0>Z_BC2>HVrw z`PS2MLM7c;5QtiV=Jpg}%Z@nE6p&!fqih`f8?A`gIUW3ZTI8k_9V$g3{sCxUQ(fX` zX2$>mCE4_GnEBMh&U;#QOX3MB>SU$*QB3XcfPQ#D>w#U9H$of|6ZHqNWvCUqXbsgD zWXF_R%UboJ&=w>AyexQMu+W}=>yD@)*H0DQ74XK(5O3*eaO+&z8@3FA#6Z1Vt~6(z zjI5MVh<MjJr$|a*(8T&?*jK!-*0qG9okOmom%6w~sofz<dW$JVipMQ2&T{=1z6>u& zTQBEhJJjI7m)!kZ_#f7?I}u;2M+1GIyjx^EdtGAq^-O$}dhT=Au`-;I=f=(Y0T)u@ z;BBWjUw;IH2GAYWYd+WBg~qRCS}1=Lu~uY<=iwrg;r6YfZ*l5?iDb_G-J#V0Da%ua zV6HAD2npCBlhr8o6B=;amlE$)j7+1%@K5DV8R;B|(OlcH>Gw@kHJ*J2{M2i>1iM$Y z))kI_!c3--f~Lu;U`h~|*l5z#`P*G?6Y1K~=k8{#ogV&|RQ}y7xqH$eHYWP0Zg%<i zq0@720<jweu=s3Vv?C;$c;ZW4#{>%T<WE$7@j#jO{R81o|CmsN!ylVm6YlJhwwz4q z#<0GI-kkLheFF)N@vCQ~=qZlelfT%QOhjt)|1|y-*Y={Ny_J#kea_ywDfN9sp|Rb; zO0&s9)*tK9>5?0Rj`CCQ(sk`G(nt61Ehv2b2|HD2qCWRdg&&IY*&U9Iwf+JU7?nB4 zi_OA^6Lvy|3aMfw?yI#@L5GY2#;Q`uy0W%GFuqeE=S;zT5ythcYe$z+bTV=Gic_D$ z0uXXGJ|_hC+G)}l;wLk)-B(;~e4-YqlD*4mYB94vmx3akn^M84ZG>x7-`mCr9YY+_ z2P9P$dsgOa9Xn<C{uqnNYBX`F$$kDvdZJy(HU$}B$a-HPF~{>Ll@1VmTXwD_><<TU zPcNgGG_f-EG}+pmYuZ<f{BTXLLvFi&`*7D+{8JjfbD;6=pmeb0&x7xa!-BJIN9CoG zpF&E<2RXm$Zg7vCQFgsHWAf@^&{(&H84$wSrn4#xlcZ0+(W93-lA9+2%fnvVn0j`k zmt52DA&v}r)IiPL@*kyNdo0ol>M@@HHy;+ySSx=;`tR{#!SthT=5Qfio<H@E5m!j> za&DnZV1C8w1e)P|I|Ei0`v8i6*iVX1v)<`BEMomplue$Fd=k6!zuc#`#I=hp($7<y zzaXM;*nI`%V~<YNq+jXLG;bs*6r<o-Pe1DT?8=6m>NENoLMKY_YQgXRXoj0r@T4EX zhe~!q_b!M>vreq@)0XE_VTUw9@tJN;79(1~p-a`*;Dp?xAdjHydOHl-j_sxC({jU- z0uhV&hRoyBX&E%nt;_nF_E)$KHIt3|BwsZWKAl^9`)I<o{}4_~(#Uj+X(cXXJgUqm zM-Irr?AQy{f1OaPRS;8jj|<z^&ARbkIDMYv7lH!id%AOe{sk|ojy}Cpj)=CT<l_l? zehpDgYMcd#x}7h^Hn$<2pC%ApsE(?7*rRjWJbX6X?k%;P`A|C`9t3!I0!vR?s@lRR z1RWwn4=u)VsXe;*ezJ(e4~Q)TOWOAT{pbZz*prpYt<V*@`psSY`UqR=f1VeRP?BIf z(ET45w!-(nb#xp3T-J!xwts6eZG`HUJg?_1WCG-KUWQK-R^Naq*89#S6$w2FKKd%U zx2DnIFCb~6s4TC47z`I&EDvr=7&?Z%!T!-PU@I9GMksXtp{CsxRG^vYQK8x8Vif(U zamz4CyyTo<U;r%-G#XZzVE)}|m;++&lfzKNUHj}Cskah+E>vf7$CGi9Ygehax3NJ@ zN&l+6Rq~kcJuU^P?bxgQiMMr?)ECp6AaMC%%O8v`zpHia)e59Z1#uLgiyOYO0*NRO zBwYfR;Np{FQw>vk<^1veIy8Ws+w+f`lG;t<>1~M=QNvSTlRvz^Nw>GNqjgUZg8Myi zmF*V7C?lP^o~7~F+V~|cL^R{tvtx4mi-%jHK?j6X5O=8x?2W)QEGN5bv$R!+0&nP) z3SzbEr(xw#pgT5Iy&rn$m+ITQO+E5<3S8jS2kA#_w0n$!vc~)84%8?e2ibptD@OV; zQLYY7(*NCStmIaICqrcGNo_AF9__Zkw_PvzmwColws?P*xwBPXf)jdv{h1_?^>Sq9 z9#7O30IiAs)N<iK+VIqB)VsRL_fweYrnGox$`t%l&)e&rvvD0qBkNEj3tP<{m$|-? zFPwbPR|KHn`q>{SU4FTW&aAmqYt`~d>rH)6WdB2*D-%Lb-6Kc4T!`dsYA3xZ;4#6c zqJ&o6&0azMH>H@C^Fqzx%KI)gM_`uor+|=0oee+1kX>BL^*5496LXwyaSRk4U~K<~ zNMs?ql)N`zLuG^bwT`2+{4o*zWpzm7np}fm$<WeU_38oo(aPQZeXu-uyw`v6yH^Y! zE;`frx_3T8m$wu~p?l@ik=P2cuCdt&FovH6CM#DjM@t?-939m#*b<XlSaA|dXiQIc zQFA#5y+9FSG8~0=E(`M2vuG|_=;ED`7aV=B>+psf7GLi63-#b1=LR3JcSmv}Oj0kp zN>H9RcEvA^LOYM6RxK<;m^9BS>Q1iHr@I5aA@XHC%fys9r-WbW*4u3#G`h<lU;NOk zniRg(wXYbrmh>0++#M<^0C3aeY(?4n9Yzo`LUcUjmt{>D?$=TLJ>Oah74_JZo+Q>E zrf|;F?UhfDf;reEwZ5!i|Kin*SkRIFY%#XgrHNOu?*Oj*7vR1DZ}0^HA!?#yO6N$P z%Kp!}SzfR}mX`aux9Ys`B8%BI9a!ks7)@`}L3BT@%R{nO4no?Ea=M{4YJ-D=|Hz<d zxHFCPLT%mAk{^i-Q1Gk?3m7HZfw{Yp3ibz^7Y@GVeIbGWVY94W6I&_<R*|ljq?CaN z4Crd8EcuT-^eepjLMzyI!4hffpHB)>OVy56NEr8>)MU4q9_FhJy3Q{+!YaDwyZVc~ zlgIZ}y}(D|C{aJVU^>OqJe$MNA}$(-%#X7zxvE(B;`Lo?N(Ge6PtV&bTIK-|)==Hd zd{T@G@9_nkJojlSL%t4RlC@RfR=fi9pb*BMKn|rih6NR&*4r{j5Eg@SCB{B7d%gQF z(8OXU8Q$#ZHSRU4K+jl5A8*!_8G9CG`>8?>2<PgLI?r{?0$Of3U{t6to8#z3<?hCG zK{99zYvC5S@lP%qB=;|1XMb}{1kUdAIZpmL1pL07fr|U0jj$rAYZ3n3;W{_k>FWsd z*!4KCCGWCe@P0aD3A4UtrHMr<{PZx_ybdIOkSY4w7&s9YMhX-wY94|>WaoikQJI6) zOe%6-tVBGEt<OV{0Kl^jq!)+XjzF~?kQa4kHFj)$#uI~)ROSe%^s+f}|D7C#z~g>^ zEU8I-*<I<Zrxm*_&s`&^TJ^NG_uF<1Eovfc&@Ml4QcSF`he8~0F-y7bRn`z!BN4J! zpbTx<87y9Bx83aPp|a??)GINzFLF;2+(J<3dP)H6psplt8jac3FbJB4C8Zk}My+}0 z5&H=*nVh<UA5}+9B>eMv`njJ#AGRV<_xjijvsV3H5wdztz#ux|j8_~l*X(T2SEZzm zf4Uazp)D>%F#Xa4W}F<0Wk0m(b7dZc+aN!Bykri>vi1+184F@RynSUlc70=!obxkN zzWY7pv74bjV>Dna<_P?`g&AFfribZ}pH77@<3aL}tx&9UE*MY;Q<D_k6DI5Zf_6!; z&Afge1LY?iMM@g&e^dA6i6rjjEe2Swm~q=HwjX|<CAerdDJS%@BLsr}naB6OIIovp zn?V8>afzIE9K{cs*Ef(ueeLbX<%mL|B!9FU(q#QYefX$I=Q+K@a1jqAzHNnZX$ov& zc*?kZaQY(qom#t`_(!lThwI22PxW~+E*V>@^u`{|gwSMisn(C-#r-Ua!)gM2SWxCL zK8~LU<=*G6#VM@Qzyvgj1>1kUr%7b2&QPd$=DaxK!XIthr+@sQnh?~!Jl7i?Ds_Xz zT7uRV%3uO0<ainISHJB0Obu@EfZDy*=QYsz#aQ-cWt?tKCLlRwX*8Tl2}tYe;p*T6 z!~J#j^w<x;`anY?Q`fyhgc&Lv(r?K%G6x~~wu@Q%nGZV=DX=hin`XyDUKz>tR=rR! zLSBAe$ColfN_62Rmvc6nI<QqOE>PMVX8HN$?QG85(VKq(bWd@i$}3VS6$J-qa|5Zm z<`W<(;8WKJdTdL%9V@UB=IZkqjGZXkeqy~*k=m$7>F%=>9!Wib-Xf;s9}c#X_!+xR zFzJxJHWHDsV+lb_h!5TC+^h3~NopTj;?>QJ7f*%LNPGTTi0<6&=R3sIFj%zdMV{Gm z{#Kr~F0^CxIe9LMf6KkZ%|7S9fF+V?9&~1V92S(Lg;<4%6nj0lB`M>TT~peM7cT>< z>$)x~xaMpoQ%}G#qn=D3hk#BiY$?Gz-=kcccyQSeVhD$JL)Rps^u;j>V96yOLhVDr zN4N6&YszDTa-hDBXjALpBYNX~GrP9Y=Y+C1`b$utoY>UXO|^dJiI_~$ZSH$}Ey1!R zX0O)vZlt_r)QxOQP2_YOru`p&sj|2)evKM=f5L5Ic$PKUe&SM*YAmoVVw7$8Z4ia_ z%v?EKtAog%CJ0XDS`^wkpV5$R6`RM0uPz+E^z<6xGF2335wTWV2wbXv*bTTKkoaIo zF?}qj*Znu<@gmK+NH;DOlAK%>h?aAHl9SEB7E7K`(HH*^qX(cJgYx(Ujncny##6cx z*UP)<{%N(O4;m6$gldP(i&d#Mp&k6Q->)ciTyBVy0u%|mYkERy4L-Vdx-I>-;fd_O z0GyIis1uueJ)ze1xU|0SlhH6s2=T{<w2gofQSoyu#Xh+aB=g{+X}jtCo$2}2O%B5^ z^hQohswUpT^e|NT1gA2-%H@A`^eU0xssg(Ajai#Tb?Zakv-CmA;JQSX<(y5io7y<I zS@jMZy6qXjHSx}-hP21JR%ug%ix%!4Xb_^?h*8_IL4d9<9Cj~%1pm<V%OS5$V~bz& zqr}0nxJyzt9q_5{On!+Zn9DSbg7CwbS+_*XmagQO|6gEhj7Yj)TaH16oBUo3ruUM! z)cy=@gK5-l>fP%f5c>yXMtB!yI-$(rf$Xw)V}!O}GqKK3#G7bXRy$8Xs)4$0J;&3) zQh^*q^3X~6M_9o}6?2w69@1B<p9F-=&b;5*)ExU?m@_EA-|mTM1gGEK68bwi$*QL^ z%j*G);N2-O7v&OGG94{*z@7Hdr(<SGOY()bjXTm(WXaAoofqG$U~jAGxQtjK5n4om zB*?B$hkfn&+=fxOUMIc2xEvC(l$SuI4-WR*hydnaQbTof=f`3sx@1yclX6tRq}jhf zg-HfUa_vQN-h3YG{84k!S{IP10@YJ7Otu3mCwCGIx@=_Lc)cz!-b5|hpSBYBv9NHq zD8y|;1)7c{TN&V8Q+V`{?~~t1T(eg$=-ueT%FXM{eHi5I+C(i_vmr<%*u(Np^+HNR zFTzw4kHxD2M&?G<z&|Y?>-x+fE92FuY0#2S2wNkcQ75aln$i3Bz-a)9<x_hnG*S-r zeDDTB6O%WOT9M#RN<1{xx;LqCrO!Odjc*J3>_Ytp$tCjVMD%XE6kLCzQBo~urx3Q- zpPYwo7{vD_!Q6|cIz8l)!g&u_`0*Nv0mNL;r(kGD+-u7qtFPj@^k9t@*kxY)?r5R7 z{vpG#RIxA{eJ<eO2&M|Of@#C6fXVS-h4g$#8o1Wp4AqI(=I||J<wTfeK@IMKt<KB; zqj=-6(|&O1_9IYW_5wIP5mBZ_Tfq0qPY7)t<)Z1Q^DzcT1B<=b?`-2HRYGLywhA#z z+Rs$AazV*ujErFYzu7Y%Jy3*{PHRfmSQxQ$7L+4hqmJ?+XN5-4S!#UddOb%qC3CX# zfSzjjfJM)Ev8h4ni3A>|&(nGI%%%D)BY<83DekwKJ(ZT9K}pri<J*cDPeD!-hx&uz z`K|{_gkn}cTB{*o)FTEnSa?!Ko*f>C76FPg;$v_hxtNAxsi?@A(T&Gjc`p|9GzCeq zhJx>7sOKr%@?0;+!)BB7g6PA!4^w0O%%d)lMZ$=tg5G2HV%Tk0rd7?-x}L935)PxE zhiFE&g1`RW=>8c@pG4S^$d-=6UaO$pgJyc|%mtSi{)K>s{wQ2i3D?s;SpvytC6*j{ zCO<$Wi`M-)@K2Nzo6ci1B<=mBo`oKc5e$zXy4QhAL9yOYNxZ&I@qI;D{NQRS{9B_3 z9)q5Z&dG%H0kL!IhEYBg50p@Dr?vZg)CPsLEBQT-YXYUt|A|*A6w88?_MVXud{@~e z9{0eiEz-y=@{q2HU^y`MnY-X#_g)Z~1bgJrSiZs~4{X<8ARPVB^9wJhC&lcZMA&Z5 z9etc3T-UW005dE86iU0_lS_A~b?)3MdacURP9cn=K{4%xle4;3F>*N|*`LG84Gy(h zA=fcMTMMhG++ONteV<I+&wBJQB_9^-0uSvK^I!+&@ywRoVCFVr#`iO(&L7SHP3vr& zM%5Vku-ZGmV>>j*hjzIwL|97Y;tED)?#uhojXdbN{iJ0PfcLl<0ESz)A3AVvJET*l zewB-9F8KRszJie~ID}XXWGaQn&N6k-^!ZBKYCj<GWW8@K;)k4ACyQZx+~+sMGlhyS z1|f+|RP$0qf-&0Jg22!NK0y!->0H>c;ubJ5y*7Hqo%rk;sH;=aBA~#P_+yg=PQRN6 zRW3*Upk@d&LUH|89*<nu`!q@{Gkza)Im5sBavMahCV;_MF$?0C+-!@RKBv7lC{bz7 zejuhSQ-V|H`kz^1C07;?km5V+*9#!9;~6;x6r#Cw7~LoGFOV3FPtaJYB&~vpwcv|j z(-MgIq}eBir2>Rqo7{9`lybDyWpoIJ2dp~eaiOD4&9Hj~Dm1Y_7_cct(qiSN7wH^k z{Ox%jCxqPXPG(=Bs+9Ar8|KIUp1b5_JaMATV$!)W1Ym)~(VuLZw(&ePr^)0c>^VYO z*Ls{trJ3s4MO{dFE3YFeATD)}9daG;<cE}We4i$uVwyq<oLds61FaS??Pu(${AsQ8 zVB6fw{|@(Yq+;|~I2xE_UP8a)NX9arU5z8DTbNA;v-YtCzQ6SJAwW2Rv!<tWBt#6k z#LYs_R|7c1C2#5H8H~)W?V`tt+^Qn?#^0?m*!_HRp^D_E$U`w(D@nmmrO=9y+%_@L zlYijW<|j3+^<Wm$p#~CarMiE}N&1r+g9{3n7d^e->VzltAdrpXitZK__QNmwb9&%` zYzdKwWs>zfx3@Nnv&4Tm2vS@&Ii>X;H~tiC(28f6m-@9zr^x}JB*X#yeqO>G=Tvxc zeWtp%#6Q&KJ}JV)k3G{H^VgIi?W+yMSI26OVZnEw9+#YU*g<A~rXu-1VK|PO;ua$E zLhKywLqAau4#9oMwM2j`i=qKo)H&q_5+IVFvRf2^alPJOm~qheYLlMlE48URfdHjp znw99uUOl!xsH!e5RKNTe2)d@LKQ0cIZGzB<ZsscYS{oc3yufxqg9g=r+$hW+On<Z~ z5TM!_3+J8S`V+Fqb|aCwfVF<sE{n-9{H{byzk0~hLh9b+fmqSe5a6agsif~@4D9f} zeHdMnF16hSx|qv<S;fUzIA0j#Y!yp1ILnma$(ppHXt=!WY%~IUV^WjJwgf;3f1J5E z8hPe|Dp=0N9048GnyuiWU^$UI0k1#E1ZL-bb<zXI(GS;)o+w;<F2FZEPXcAwoP07u ze{*|Z{!?Q2t5w_iqEIl?p3k=-E*iXt9=<iZ;4OfV-d<OWCDRA;{g%ZcXek;HK?g?_ z*$>LvCVh(I5+&T0d#kpvJ@<q2dF5fut}(SKu-Z>WJYyekN+KKv^{0KstUUgjEUz4k z07~FNmi%}XI7LqfA^%rC5ieUm5#|>T3p-KSVb60E^x}ctgYw*X#ot#n!Q7VOA>#ET zEm@87XVb`G#KA&q@Jd&d?_x~s*?#-rK95>^%r*i~U3J$?Q))37WgX;fx)>Oq*O^94 zHC{~XvuGQuyE;XwTnHm)(~1jyuJ+YFGW-sIoz`(UVCYe`=2cchcviAqPfCX8Y`_NM zpeeBCiO@tTiQ6oa+6gl<{iT2Dd9>1t=N~9Ag167@!GoD!0hMV(#~6>>iM=Nz(w;KZ zC7sg?#dQK1q@cHn{pyh)5n*#xcaGgLc+h#K4pG4t{Z5i|g05GbdsX!&=;DH7&4!R( zs%z87q=5OdZC2?oi&V%^*oi0z_=qoun%=j%5oISqEgMn&XjFFu9>!v}`&<-QSzlKP zlSD|AHMOU93@ZdnBKkq@?w#ffyw%6LkL&YiYH<&1#dNb8SEn;<>EDJGW3eunjtK(8 z!CTTc9MNydD>`8!`>)DeC^~`o>}~m4y*g*{-E7W85(~+EY&V<Mfo=B}X20)%@<3uH zK*)K1_4WPwtIz6NJJWTX+ur$&hZAb?h5jer#v5&r9xrQ-1q=#ADh{dBj#<UUCb#RM zYCUKFIW;BIvA6-lXd?T3ixit**d#Tn(QZC))r?Oq0amIc8-u2amLeIUi7^HK{=~ZI z53KTMTR&u;=Ats{ra8@1Z>__fQy*fZjLPwoTjdMJzh;dv3UU6&<8)mxx#c081Y0ja zBA|6|AKITZSa)OG(hra}8mt&7sp)U{u&t+ni+p$YB{I{|`;fgri?UQ8c%TfKUtLSZ z|L7p5%z6exzWBGO0N$I7r2C45dFSUcqeR;JTi64Sa@}o55Hs0EXKDC^M5#2lR19Q2 z2ROyh_*5-~1&Dr#>ri9-%G5I`Xun9j%ypopL2N_S96}h>9b!$!uCuU=gGkUZog_fN z>n&y$2B+A3*9U5gLC0p(0=Kzex$&V;<gQz>9j{k>>^mOZ(>@zop~0KCoz%k}#=j^? zlZiLHe(HfV5#Rtz6Y~ie@~HR=lt1g$QjyG6ndREQGm6BrYtM<qGe*O$Hufj{b(eJ) zCF?jP+(&F<KaoQv@V$yrpF)z-7hll%{#*IhT%97?097?Ej6t%vQfyKRy&UvDNeRpv zJ?W$)cZ1u3O9EaVz0f??KQd4Ft`QrMSZ3@P<>hGlXbP_KAhck8Xc=%J$kb@hi#{ca z*;zrjO%B(kP2ukFn9E+%D%1Gi7NyuFnE4t0Ov3bU7p(~J?UktwzP*Jxoo3Z*VQoya zgub=&VoKY_sE%7~U$#|Swx|B#LyCRX=`MyXO>D{CmKh(lyk&CCl&qG{4=Kevjh6Y> z!`fcy27|sLnSTeFqYZJTof8~x9QW>U;D_WLLW3`gIKok2>)CrJs=jD-(OP0Akxf2T z3UTFVkqEw<C6`{@mxcxdc4l+I4KTWH9fbUo<sa*632?8E{;>!c$6vR^KT7f1B~C%A z^-L5K#4Ppu_9T*}wZ{XZk5}kOW>S5ZH|9z{%_hiI(5*Dj3Z$w@n$Tm}ERNRTM~^5t zkwT=hN<{ll|3GMep!gN+5lNOjQzzGPPzm<tt|j{AWCj(T{Eq=4Cdvs|iQl!kaK!kO zQN*TBa2`LGV6VBBpQ>)IvuQ%^*(%JmHxKDW^FvhltpY^KQ#gNbWDN_P9)^S-q{ugh z6aLrI1mKT)v)u*qTy7QI>XN=;aS;pl=8o*z*vyGJavx{)jZ~kcQ({MO0Ll^&H5v1_ zq|l2nBXSJWT+G<$;T%ZhiWm4u`fe4|s1To%trHbpsHJMMKMM7bOEJgj@diAgDaQAi zYgw;I(UDZz2nSmP(}0b3B3Ho6^{P!$r>a=o)j*bHE@-<0{MdRjsZd2TOMGyA>Ruu! z6W<FGS(=S(txBQhZj3#v*g)7}Z6*+|WO+4oa!mZ7;Q!3Wr~T{X9^jgyKRw?Lim_GJ zjtnWpsc5bBy##><$Beeaqhfum0_50BO(!CYRX`wHTrAYK^`iSiC0RgS7m8^o;~C%2 zWdNIQk8RKajWWLC4!7W#jbP1u2`;p<wqJA>p#3869aRT>LQ;Gn@Am3+h(?ZK2=lm9 zO0g7dKE(pOv9+UAu-hdYAI+4_|Jy$^o0jEcsH&n>t~IdkIKLvr90%PR1rY~R=lC{P z$P-po39db1?!mgbGsZ@{oxNNDc<MdeD3+L`;x;<`)pnvXPYCc^sGF^D*-o#jL^hSy zS;a2#Z%a;@-i5?xJn0ySJYJ3~z4`&29ZkK>^$>{zYgsBviUBq8Qm_zL<Ot0t5<?r# z1k}k->Eq7;FnJ>^sxc@}g<e}s*N2;2XkBEqu9!kAAhA1^w=hqXjIf#=k&$Q2gYbKG zy9mz^YjCTC$21v9V61_#S}_!8J_cQ&Xp8y;DL=h^peUlj5)>Xv1boHv9<D8d3g!S3 zXLRqmfrZzLEU@^LOTXzVIx}D~rSN2W*x{ECc*9amiBuQ+2X?bT1+vR__`r>2wOz|w z=Mm3uJBhdm(JZcG`o6|!p?1M)7;&GUm_PL$@@&jrvx+KWGml3>7+9+!#*d|zLwt~v zq<#Des~0U&+tRnE{rCa&2&fzYmS!nOiB%e2X*8!Mh0}Ic>vOg!xY`DMVjZ($?EzEg zl;wl65Z6A7PtQzfiv2zeQf)=l5U?s3$2B@*<a8Xg;&jB#qT;(z9z{4Ka7@crP+|Ou zR`xY>qnKcF^fvKkV4L!B=-mp452oL`9C0DnET|~=`ENNH6uquMNnCloEF96W6U>q4 z+HqWVof>>AZuR7DI6?AY5@VzgR3RRN3lB^2<l=ef6a&W9mE=J)KFzvpZOK%h7jB3r z2{BsFH$o`9P;zviCvQJ@a+4;Fh3}3*)c0Mkr_Jln$Hs%TVQNNZ!H`-fc@zxg(M+UO z--a|K^kJui>6|q~W7qXrI4H^%vo;{n-yx+=@L~l!m!NXD!2#A%58X4CAOp-7S9tz! zg2bKKk=7gEZfWV~(u4Le(#Vsg`8tH#Q1GoDE>Ze2d%Ea2dXlkYQxECE9nS$h7cr>u zFq33j9%JCypPmgrdouXV^C3B$$Q9FDPyumYNBBeCY^EM!0ze{ZP+w2|v`m}rk1554 zC`jxeh?P)|G{vCcFK%-cl&i0X!|$-A*VT5&c=!-W|Dqk0#~tM#H0W<0G=J9x;p=4y zc_Q9A*#IRG`(7So=G9vVq!#<O43Pcd6CUw2sX+A1<%qw)aowlWARv?gz&dB9@?+z0 z;X$SL@Ho4LhoxA6Yms5R9E|er6gZypOQfCuL}yv36y#5&ULN$Qm8qe5TP)2CZwZRt z{{oqs0tlagRMGI1VpCT~;ORn$gqEcd444j_6;1*KvLJWekLdMTF~^fCv!>7Vb=S!i zchPzVMFD`q+xnv}Ra0g#$<c+=s1Xq`*aTqXf-`nku_$?wr>z3U$PV0lEujf(cW<fE zaZ0WiIL9YM(q4)ifh<FX-cgx|q-(?sR_87}vw_%ofQoAVS!Fmn6HCRVT;PCBlXYVJ zgL?(!&1^UgiPP{Fe|Uvv20sK{o-?46z|~Nyk-oS;&0V@cMfhat&Uue6WcT&67WIz2 zAqeChZK$NJZ<VT4G>G-USO+U$td9vUiC#*F3}k@-Nf9rWC-OFT?*tPJ5g-Y7(TcqW zugbvuMSw65iA22VZ9ByT>82*N%TrIq4%g#@gCTRjVou)kZhDs|+>mO#YiDBV!yi|g z+HHKusD#R7+8`|zO+yd<R6yqFgE0!?rCD|oa1FTeUj8bx-M=T`US--EKc;X@bv1>O zTZC~6$n(51M$oZ`2(4c+z?&<6Z}g01T?&$!<Efq2s}QdHaOtc1^4b7?)2oCFXH#MN znXxDLVF%PhoLUOrHQV0Wn>BK`q`zSE5EqC^oQ?gLXAjy7r;2UKzb@IzmD(%D??fsx zl;frl)i>Ad4qBpw+>B)|m!_>RPXr87+?s>;U-4{5ooHbb{kGFB8k&iXE~r(Tv8IUH zok}cb>Qma<SXKOCv|+0vgOO`~*eo3=RrWCVi*hAT6*^rKzsg#vzL2^NmDZPm;6yfJ z5R7ZjdG5~3k4>avr93L;Mi|b)!oS>ukF{ZF3PLTn(aN<Kat%>#mG`=Sr{Df;M!0F9 zQ$1(ARJW{n!MuU2Xqfo!C|BEb?sLXO_^^YFPHQ5pIUD_CpyYP9W*2fs+y}9<>%q3+ zbljgY<nv0KB4Z9B6|NnVy?K>-%0?TLk|~K8;hY&@jNCy#PtA9ADOWXNK?l*@r6(Pv z-q-A1>U^1%DMA0>zBclaPTH`c-JU5RMKOmsU8ER<nZ`?2*_DKZU&g>8o4d-6Aa@a- z)T~^zA>_VCldA>$#TGmtDNTqZh^Wh`y30ewsLXM1w@df<ClVfv4#j>zg&*8V(At{r zd%As#ua3I+wIOx~GAJ4^;;$|)zE$(H@qc^NhZ^zSjuZp!cFZYonO`kigFY}3SVe%h ztu!fmvrN8-%(qeZ`W|wxc$GV`Agiat{MdzBoF>S-2>|}*-*@hHLGa21M*GFn64!>L zQ-f(>E07HLoA<wk)KKn{$JfP{aSVf=7A05&oVv}_f9f=?E@y{?%dGFxb*B=Jia@2J z`K-V^yVg$7dk4FCgRp@ltLpUvy;?!s>9-rJAc9hC{rP;!_}i=%J>jwsrj>!H=<1$` zmr?gwEXnUR!_%K+{!_BSt!?<}dIbvLvjU!%ySech%*Ll}aARAoI`kMR9px8;*2Xh? zhoFb&;t)Pfxcw5Ybn2Sq@!&6hT0XjzjlT7w-mfA_AJCMOtAH3xcSVA>{`z@;GYZ<F z`v<n!ff<KXUr9R#%Al97^t@=hBU8DLoiFwT{)?zg-3$1QsxXM2#^F!cf5tqO)6CFW za`FqAuSCW62NgTC{?m4z%*m+4PSbG@cPziTqvW+!4A38gR*g9=0>IU|<foIF>H3NZ z3Jt_hIg`Xbi?Gm%Z|wrpyneAQ3B=wBc<~h4wAwSrouBvD{n^8d4+JcFawFitBCEhY zRzu-^cHh_Z(Afh36lj6>@yp|?oYWWfG_No?*r#Y0UL7L#I@Q`xmbocfbgSmc(*iw$ zQe7v_3*4O7R8`W*q7QL=Q=6>|VNtdN3cp@?OIKD2SAiVLui{U2Zr~?8CWj(7l1DiT znlh6Kuqhc2C2cM$M?tAPqT=j-gq@JdoaQFHLPVi(rc!{yTKtRrT$h#^5bJq$@|3@b zYbHTP+%OVzAbPbV%`{yP>E6oKq$#tQbd9!*LS!4&`p?dmP+L0`NWDpu^!Pbd)W>OJ zhtWC~bw%|1Y_iyGnHw=#@@=p%f?T2Q*yK?z@dhLD*ty3NVfQ5JemxEBFYt>AvA%$E z@gRBp(XvFl_l6cdQ@2ODjr*zST8-mP7naJshugY>*1yA1snP!x{cPObwbwYWq!FiD zru6_?VU9bqH~+%#zx5KEjdR}-xlyA9{frNnr~@(_qtzL`i9ZUOOUSE7qNSa`T|Bs$ zX)*EnEvt7TmTkY$IxWTlJrk10FN&dkc(}$rHFY8}&i!*ezE!pIDmrgqTiQmRY{&7P zhu>V(afGc~6F+so3scTzj<+B!5rf!@USF8$SNhpo_C3OHZ@iOiQA=Ss=R3dORS4O$ z?>iM(mr6MJNC7vYGo|?msPrGEql5RZ%<JA~r)TWCH6||inalmy#*{^9d_U=vdo#0g z+q&^Ulpe&G)AwoM6(9vHa8=xFVMj^)N#YxyJ@2?%X~A&P5H|MyX1YI0!>Q=gMCDIa zZb6qq`#7h{zGgfJdDh6#9|s1_H}~tWHpePFfCjx1_aqA*vZ5_IUpk<LM@)%a>J9qA zgbr@kb1I!N2NO!)#!<;V-qB6?G4BRba5C#fcR0&jcevEQqY8EYK%$F3$LskijzkG_ zhPAp}RC7JdcDd(IH->#T{xGTv{hIO_d_&q-aOBv5%m|^@^~^{keE0u1vGg5{(>W7i zkUP;%A$DiP+^rmraUK;m`0vHk`2E+fUD^*`5cjC6YTI#y;;)WR{=0IuQ6l^uLgn8J zWSS3xRX)|;Eq=hiQFyj;F%+BxK7-K<fvs@<zCE3AqS3FE(uS4MosUDMjvjM73A&T- z6kDV3Oirynpwd#N9(07KD7k<#5|fIMs*JG5<8$Rv7wL0b9L2W3z#YfvPlv^*a?HwU z^s=bv@?dhA<h|&GTrs1Q{}CHj=1;--kO#|}i>A$1sTaXpfW(w#dWD0C;Io{OzzDgY zxSb9zro}_WK=C^hA)C9ipftx{?xC8~<OONf=5{CUx?Vv)%s_F~ov~<zb7I@1X+Vpz zS=OL44gOUwYA3A*WN|UnUlF2bNM71}o3r+p&-UrQ9Ct9?S~LD}=6AwPfuLoZ2}%4p zh4zY-)7QRu!H4xUz*)W((!yIJeMctA#CS~Nv0hVG>jLQeAE<fjk~A%rKYs4&>B)wm zZAZy?wtXP{&I{cqvcm22yi{#l_#(L){iH|DPh|E;eaGN;3p1C%!m3(9<;N<p7f(_e zrtUDVoEs04();0e!8L?!<hn@nT+r;<y>~yY)1wn}QqoWL^+@dE3OQO~(e!$iQpxyM zIh}^nf|2n>irH013LBPT!m*E$Eax7^z}rs-8jo{T{DZhMXfB6rM63o|15$pL3v?Rw zO$gaEwu<W0Wnt(>=*Ym!+RBFY)Ad(3gkhIRuK$M2fnJ^3YRm&>=MORTOFCy?0r}Fu zcU^sdyl7ZXu&>y8B=-8Rf1fFN5vU!8TwqS*1H}}7X}r2W@7#Q9<lXDTzE~Y%C!!P6 z<)+5LLdUA^?;^WTe@`>MVeREjNXO*h;6~0~wyGWEV6U;ll*b6-c+$DN9v%bLk^(6J zwLM>Xkaa?%yG5g$Uw58ERwSqi+P2qIFSovf8-}oU?e41T4k2~DcaU;&#e*D0pIKh7 zJob~kjsTjTqRj6&tCoGAFoKkagn9TDNMuZX{;Cp)s)5qSUhtTUgH66EU<|sh&2LlD z)B{E>R>!+<mD3uIC=3kRI->J=y$KUfNimNsQTTl(PSbqbQH5$9LVLGW+;+l9$Hu75 zFv{_NK-l-vw}c>#BR!euHu9$`W>s6T=S?0zsMI>H^19d)>6Y}nfr+AXkLd4r5oS?Y z{^23YHp@$1_mDjFTDs%J@cZ%KCwXV5)B3+J-ldJ6jLMG*j{%cK^pNjIJ7uy8#$F#` z2S+qC=k~DjFSIx~tejr>rFo>In+9lz$uV{W7GL6T>t)YW?zrCrwJO7b>W-6!g0B4h zWDALC0YS6+^Oxou)oFecDpM<n>raC|<v7k^=^OZ-YS*#Jg4OH?MlQq@^Y6C|g3g(A zIqrg%B+|(7V<p8r!kt*gU>d8`g>4|F8?pn@fkh|#`(Svy1toglicfopF;lKT9{zO+ zdX#q~O(ke{i_s4FPUeNMrz^aol}0rDD^475)otsiqjNo3ElWE-XQhd?#GVQ<Xs{HT zI8g3c$=JGnXyVErpiYmp)AdOR6oABukcG|DPm{$Qke^CulWqlc{Ny~_?uGGV=d=8$ z>}n77Nd>Yv7p>k4JYOwPU0MheWyCW`Zn+=tK8kp}!2FV^YFd3L&FK8|>!(j;KwT}d zI2BA%X?0!3?Z1G#TuZU}-6%!9lSj_+s_>(o5W|(eZ_Lzs&PQvhSm%SWz82u%@oX|J z-&*arN1PTRudmoVGgN&Al`1x<9TdQkt7VHC9JQP=24czKk_xwz@<nesm*m0NOJC4R z*Yuv78+q+gq70tQ-?~w9V=6XB3tlk%X3*iESCzz#^m^v{JqB~2bi5}4HLZcS2&>{z z)H#BYJz^oC66H$;A($WU?Q{754RxAQVWHqEhur%f>9XYJu&3%F3t)0fs?yrW{j3`4 zd$31T7wxp4+2T)v?jEi>jeE1>*ZQGKgl0}3_+a(oc{rye&)11wHyus6a-YiN6L~iu zgxif){`6jke0ji^ZK4wcIKs1O)wU*SL~g>Y+%3Pnl=Z{L{$)QpKt<BZf)?pOWMSmR zglp(xf8_0qTee3`A9U$yrCjL$Rgz(VKaI^#7D{|kKT)8XiZ{S=v}}K)cOEw`v@|A0 z+>hqt;aVcv!rssWR&4?CU<EDWO1~W@;Cv+|mCNy{k?!Og$oX*<dZo3CIXAZDPy$&8 zPMP|CYt6rVH@&2FxQ+B#D5BlWNj--;28pb9U{DzHr91JV7fG9*-d4KR$&u&gFCXs} zci&$J`}=14tYQy{c0Q->w1iycr8y;CGqOe$+SgS+>#+0SvWnG&$Q8S2?PI6~<at#- zM_wsVfg(U3$)Pi>`(ZT}r^vqymk`9HLF4PTx6HE{v5#q<#j^e@mmjXEuqiM^RGVaV z$>UnTl=B^W6QV{uwdGp2$=b-TvYOuX-%h}Szjl;FX<mhRSn#$a$QZm;<41?E<L`|R z2G=$nV?X`mo}4#LRwKv7oVSN*D4U1vf<m3VWOt%K)>&F}q*3ABG8L{Y+fWxyDV4ra zQqJtWI*HjJ+`acds`KP!E%%AxQH87XoM-i_iL*lQ=jvn_qmg$NhAlp*f4#pVZHR#C zzGhx`={kQGGZB=YmzL7N06}XZzSNm8kF(?CdC8wyAm)F1ZknfZOl7pgf>oZQ%|Dyi zUEuMWYkzogu<p&7YYDB79{p6o=h4b90``x8j!m$W{(boRnAj;I3Bb0iN1rWD&L68h zT#gv5RxD?98@GblD0yO{hrc$QF-rC$)hEX;g>Vi@=l>mSTjLX$ChI$iP=v@FVrK=; z7C6*-(&9o|{NiRgC`i5hL|`iP>Ps9Ki~2_~E)h{>e1F}-h86`K+5+Y1eOmI9@72U_ z%%%CM#U!c4a;`E*!-wN2Dwm)8oBsr-G#0JUV|+$LeKosvzIJY8{cWz2Y<{ngpI|LS zAROT|HJ{XNSn&9M^N*W1Vf7F{Y5yokw2PwKxVw1Tqp_Y$u2>lvo)kB&Fng@JI5llL zHu+(V#h}F9S08S~_gI6z=Oh~$nF`106S1Q|23-PtI$TC?iE9v0K{zU|j>&Wg^SRg^ zs&6HG@5)8z?3n1J53WWeFNHE<$4_1hBrtnW9W?<75KoY8fce{!h!i-5Rhsq2RztUP z^_|`azUc3-BZ^0=^~-$KJ}yfoh-a@u^Be=WLE+d#>eApiPsgvev!j74_W%47*m8BF z&)_py6a-;as9v%uE`20*?S%Vu!{^r-BZ_3q4m{jSCNvKFT+-3Yzjy?Nut|Edf>1v- zhH`Nal>9l>ow)VsYC#ME-4HNDfIwT=3|mr1@-pQ33|H$?{j{ILtEW=Y%Bc>UzD_R` z)~>urGHS(QbzA_@OhS&tpGbU!97Otv>;9Yo6Nxa5?STCB#*)b<7>)7y>W_B{85*5z z`nF4;7_C{idQ{<q^u-0u-4k=w&xt47mAfNql=QLCIVq1-rrptk5Xp)LRfkEpf2`+m zSq>wTIh1hw$7a`YT~!{z-A3J9tZ`O_&4|OkeD~|xs9;4ur14DT1Fdj-iYM~%8gRK7 zt>U`A*1t!Lbt)7Mp{QL?WAqBO8RyOWAZ{YTo87|7RrxU=Y`pTfN|$UPtyVPo?irhU zVh_+rq<HXL`Th&SmAHMOs=`N&%F<js5VbH+A{tW?w<9K&k&6tb!!iC3XHuTmL`D(^ zMgOb57T02vAg2?fwHLVgw!t7hx~vr?ao-<TdMLR_*E{EH!Mjczl>^EmoRoj@3%KeF z$k2GAgFyv$Z_m2?O?)hKxbf2Gv%<Zd=G^X>1L62q$$C+%cSU5gj|#ar>KqXk8||Kq zBhaT2)e}FUaygOE;$qRPy&_js^!D)G#&1jG{)eAGwe^9_jfD%R=rhb2Cy#2qkkqKT z!xO?IWk&!0h^9}2)O!9I_;J%<!Bk$SVcif{x6+~T_6^2FFk{`N++in%){WU$ynN-9 zUS+E0pMV|V@ub!-WAcga>_ibTU1zmC%5neVHAhjo1OYv(WgOH@Aca3xIp0eXl)@Gl z8vZZ=`nv63F7Utk>J}7+R{m({b}cg^drUPvmWobrUV}y1<v$`eTVxDsTkHh2-&*K? zrRi@tSnEFzk!WtNdz&l7a|2iYQEDtd2&#vP(c*p6dq1R!75d=fwsyegLDp1+a+=ff zMNkcs;ZU~68SR_vn{f&+5uH-9NT#~iEPol58E8N!JQS|o6L!c1A=wag&-udD*sbFa zOeO3JU=BU0K8HKPiA##(n`gudYUn%wi9+`Y#nqz=Lp&bLL9agGX+0JH4z;-ew#F<! zdnO%y9wqt+Do1{?7*~AZ!n0e+-(N{_if=1v3QmE-SH|V6QH3&2dq+R$usHbm%;xva z?CB%WasXM@AtxTuR_8(>0midYSyI+Qp}up*s%2PUllApF&uQX_43wNRq<S<UEr(vD zw`h9pl#;EBycm-<@CK1_pz!Kq`NY?81uDW2{Z9z@r_)1D)-x*CQbqp{xQ$d>iyPHf zols3q|F^4kR)yh=f&BNrpzKIxxkIrjs}v_hyM{baPWd{(=?OZmx@QqtN3$A)<}v%P zz>|2~YrbP?O1wt6hrT7E-*+elA8kintdH_3@IuYAnPYYP;)iPCToz`+*V#gZ`l*_4 z?(_V)1gFq4(L47aP10%^PN~=$SW|2(m_H>!9BW+pe{{VGJXGKRKRyg5L!{8iS`>z2 z2xA#TvKC|Pm8_K|+aQTB5=vvnT9WL$Y-P<h5+jPTM3&HyhU{Y>`d__2%lG?#e1GRL zn%h11oO|!w=Y4JGwODRno2B}ZhSK&??&6se!DovsD+uMi)!I}dg1A?bMhkAySofoN z7c_a%KIeXIFg$&~f=_$eg(1WC!{-gcLx9cdGC>3y9zGf~t71SOWji`jw$SF-RVacF zW7ojDkBPye*nUlKBld@28k4_a3yjE{wD=cKTo?6B#=EjwBI}kG)h%<HZa{okVJsjY z#STb+-<$KYNY-!J9en{=fYrVzCOX&v!ZItouRS{F#&P&P{c^gx3ZRg1bZ~Gd?>LLT zL&N})9=dCKHf0Lz*w_}hb8S)YeQT9m_)CbjOq4LUF!&&G>ble048G9)cP<xlx(J5J z)C6Ez;Y@uK>-(?AH*~iVK59&)0!&A3{@^2568UbqW6)Z`$Bm5{GWxf_s0qS8_iFZ= zty@1?Bx-@E<C7YUC6T3B`&5x5V<V4ieL$<%G+4=w{Un@y{#V-UuP>wVn^nIuAsTEv z;XBr6P6pF*4DL(L$S9OQzH>C~USf&M+q9c+an`bqNp>G3!sbXEwfV;jgoG@m2Wp=z zUG(6&@yvIHd{YcZgapk|Z#abAedwhQ4(~08l`e{F^Ig;iOs=%nSN443Bd*Vy?E(o3 zB;)GDA0^+Mu3daoX_$Kw4+DYN1n1+4V<$d0-}7R~1t#omO?o!rYQ47^#V5`xZd{@o zPmH3cPPBAbQ7_*MZD_2a%-ivui1vKtQ!gC4=|?IkFxo&rYL{Ft#~1YOeBv<)(T<t` z)4n$PGJ`9HJh$JvlzV$Us5|<3pvLB2?m2k~cA}QHV0Uxn(C@0p9YgRL>ono_zTtHX zJJvaRxsx3iCcOlD&_Y4hhp8dTqu4(F`x#@M`N|ipS;FJ=eFAqJoSQ88fifi21|82b zL+`X#k6xFld7@|e`U0mKd%1qSK#sCV<qUD<Z2Q@WXo^_=0X@evMLx&v4Iq&leAQHC zN|e9b04bwu_N#*F14sdKXDGAhBB?nPQt)E=56E0qV1F=K6)Ad3ubzRki<Qt8M~IPo zxK&j@-E$!~L_TX(Yibl*s2NOqaPRETQ(<DPL5S_pu%?8GynB|K%6Dx8?uNbkz(D8? z_Dlgjhm@(lR0Khew+@_Pl0NVXd}uoL5s=X<W%3-(v|<|;PonAK%f_4F^%Tuy8GhI# z4{5DksYCsQEUN;$=C?ig@mBI4oFcw$ake9*E}M+lvV-)Mh^UHG%ck9-7p{GO0vhj$ zIO(fCAX^~#c<g%{SR`e$h{EbOQEfT(ya})qqVxDc6nAghdO>K?#M&o*vFHd2kfk{w z-xnlwBm5E>NoRi1eQr^KdrB8i_yh9GqVs-NJGPq6Dh0jf$CVZ*J$j)g2xwTRHlf)} z;Yyk@*p-G?&e*S3SEUgx?yS@E6Y(ZNe*M*M4m_)uq$nVs7-t7Du_AZ~%H0qwJwj&I z;>;mYmJ21s{J|#!g}G~IbRY3_oph%4_tPw=_kM=jhg9VoCopUJa)B25i*_t7Uzzv_ z{z+ZQCabf4SRylu6_gz<AA8KY!N{U{$i=g*V9~qV{)MkiIyyaknws7QeQ^+X>~@&s zG7w*7xT~PvGS}1km)Fn#@LS_z0v6Ismh)OqRzA@B&`JLJ1jxvtDfkjF>qQ>!Kgv^g z=M#|I(mi6$S3w`d#F!IcpNjGs7p)X0y?esMOW+mVU?0uU`MetnjuD;SZF93r+u0FG ziblHjijh19<mAS+lXY4lklIp^t~Bd$moAVveGWq}yry~OisA!AEp2pJWKcZljABAl zC7}KbITcS9*daPF9#&78kH>9@quBJPSq%=2H|*Aded9l5zVT9THfN}|Icp{vO(o+e z%WdT$!pLkgNR1dFTq|e3H<2&hcs}y+Z2C3450Y9S1oaxU0t*I&N2I3(^lC|YmakTR z@Z#RA>jhwC{xS#e+Ypl;!=_3Zq8AP<Y##$jb<#g9ZE=B$IEu^+!3ocW^+K1X=*7P~ znLM*pxQ1IL!uv;_FexCQCR}~;kh$QMR71^eUHj*W-V6@(REIm-^rg1=JPim}dHwJm z-I3t2LGNXI!jH)A?fTY9UC&j&<O2w`T=F51e0A(9(`v|PLoj2<Os&WaIvJ6UY|SR0 zVT#T7ehxT|d>Ao7b4h2MwBOKL0Gy)-F(XYji-MJOk?58D9U)xWjtCpKNP2pb4Vw$j zbB_B0#K`N%<65zb`G^iTZS|0f<Ey#1PLsj$9e#0I8`)%ow*9NplrDA7$pNi=rdh!^ zksG<&0sFrnF!cl}?DN)3_^5b_W@eKW1yfX2ReLXk(4{gJBcL8O0~BO_BrfqwB>@NI zfcl!>40A5;-r4!_1Qfcqe}yhyP92)Z^c(_l1v!NDw<9jFji`<^a#4n0d(vZ4r<0t= zs2ct(F4g=@Osdl>z1_dv&&4RtKgbDhsGOw%-nH_F!;^&orQM><QPACC5e0a%$f$$H zUbaSAtc$C5AodVi_k}j-8q>i{l)mSYaj{fy(O5x&&y#e4)(v_Vo_bPawf^0tLn7rq zy<Jig&S$9)SKHGU%|mld$WYTBAg4LaL;Y6cLYRc3fs3H}XqiCMoX7T1Memh=PbU&^ z6!7-I<!{}0C`^wSL7_?Gl{JAQ=(hfTkt7>PB~;UX3jJ(*qrjVme~A#pjG4KNg!pt| zkYKQQ^~s*SF>Y_nYFHjWv+WuoiVE957ZNy0q^CvBwSl-B(ot^DkrEDmiJibAEf82R z`ry;Iw}8<$h-<v%-4nheBY6QuyWceYH6w(J2;ZD4<I{7g$s!TUMQq3m@)+;77-*De zBWu#6G^C)KU&?o3n0;wAJS}kvpe<-0Ax%ZXW-Ix(uA;az3rB<MIW`p_uXZt_Rwx~} zHzoosaji2MKnnB(U?{(VN$w=eN7j-*nF0ur!jL~8+fbY06ph((FiJkm$QBLpll4&E z8*dY7#9<xICfPolMUn+5lZbf}U_lRrep0u=XPO=h8{-D2hllv}z3S-fe#TjlPbGvX z0OXUIEDHa<ZO}6@uNCr~=jI_4BI76g&E-O!La~U|mC-y^TSg<D%sCdOS!Kg6@!h#q z;s()&U1B!?pxg~_*{nR^q-Sob@2D|;p7R+$WZ9>00K`XYW&@E3i5M06mQ6nYfQ?;a z(hJ=!YIMu@)z++VNVJ2xd9tCZFpdx~qQ-NX)#yg#ZtfbRumZ~6m3hBT6<k5jKlTAe zS<g%SC<RS003-8NH%=Qsz}5Wcg*2TMdr?8$Yc%5y?C|0QUUf3aS@=-_Qx9~#bEDTJ ziI_>??#~apTjao%Bj8h@5x$_~?@ArZf%=3lp{ESEmY&UkPwU@;<iS0T;=#@nyEy=t zG9jNkh7(-nUF1Y<Q9c81)v!V!<4>gtc6EO_twes?IyR@aKjx4>l+YNkxwK<Z1;)Ug z)|BP3pQ+)Cs7jrX!O?h%fIx2xQ2#<30$h@RJMvB0mC)tuIo^e+z=d!l^7-8Q?az3S zsF}3k>1H#9khdbwg$6=xew@Dr1D-b8=mj`IzWC*?OCCSdD{iJh@p@$bB=sj1FxXK- zDot1oPX?tMPP+&f1>8c#Xs%G~SoxWiCa1ZA!q@2qo7?ZALro?YcXrI;CW3vagh?)S z&VXF?AO&i@NCw8c?+Iw>x$j4{W1|UbH-gP;9h-d&WKj*F;QqdB&}1fs<w!2$Z*1R% zV(?SQSVb3U4pmse4ecclE3dNoZQ(|q*N0j{!qd~7m+1u{eNMnzhu?0@lzlhiX>Y-@ z$b%=K45TU3EK<YASn%!c3dKup<$H3S(A`OrcU#{1MX-=WXas?p1<)t2$#E4BhY(*U zaL<@L!OwVW%_l@OQwAnqdg5Mf<l#sW#zvm(6`$#}^$$x6G<r6f6QT<92wx1_vw(Ok znEJ{G?twO_%Q>o^6fkbL=?{o!-k8<Obs)CD+Y28-9R74U?kGCdg46TD-2@8QcLVkt zGdl{)?fH5}i=s+nh!e*tm|5e)rw+f;;pEPO41MO#)9_W{x2>g8JoYc-lhsr}j8}&o zFtd!JT+SOe%_V=@ch_RNqHc=k!0S0*`E2bF+qTVd848MPtdo9tTn9UgKMN54j&(RT z{T(lDsgafz9F|eaI;b2=C5GCyM7yiRWma-TK~2<mxIIiw;WbD&;#U~pjr0Wc&f;E7 z$~OTB+D>hK-h^ywC{#J3FP=E^>?s-9N)di6%mg^5+qXnaNRaH;7Ig8x<sY-^y)e|V zAe;f{4pRg1L2MU$SfgSZ(HD}Z!BjglEfNjU+zSfjwPEA*o*<LOoU?Kv<tUH_Cr}~n zq=y$=zYEkZy)6#E2gj2rnSf`stgEOz3>vbhUyV%Qxx~2=F(2NSid(zWp(=cc;_ZHU zlGy<HJ2>>b4a<dA#J9J>{T*P|9>_L>29anEqKhQmAEvFQIg8H5$lf|t44(?!Q0xU~ z*t=g)Rp<Ji39NBp_jQkod&s`D@PP!~o4u`5drN!TndQ!&R3-Kl`i|u)1ttVoWsUqC z6|ibjs$_}?{kNk{$akMyQZx6K8E4|^QLSnJS%87+#z-*T<?Dp2if!%;X!-wU#HS-S z^DfJ=e<tet0aa&u0*Dd)fQYwVSi!|pFBQAGowf)t*ug{ZV{%{~$s3&9VLBw5{&UH3 zk~ms=Lo~X8hM966B}R*9iAG|i4r#gejAu$s5}7tM>xGLb4)%=&l0@Wqj3ek}>1H&L zetp4Y_M=%?WR$*15ciC+*okizon#gvg0qlwwX{raCK(LX3s{*4D&P7w9MyRm8*L@d zir>w|#sQu{CP7DxrNwxfbslpt2X=M<ab^YX+O4x`>p-0eR_Lf!tIP+<tWT^r;GA|Z z^o1$Hs5uYjvd_59u%_P-dj8YB;beowXksQ;^fE8?-84{CBTx4+x8QSas>p=NfDJpW z7%$)Ar@GJ!13`~0P2=JT;S`{hZ(p)u507CdwHC;pN-Vr22_$qO(5bL?eozNv%2zq# z*=IUSh8e0Zdu-`uYmeIG8Zkv2{mk9H!Wpk~GhntrlZsBh;H!QAWt(^zQn)$EhCMo^ zOUD_GsWnLvGNYchv@T@vLbe4_%jx;?2@Q`O<_-yCOsI?)#it^UoNCSmV1SlQKkd;H z2BMlV_k%(djk}0fDxUNUhj9)39J>p|{vB2K`|Q7O@pX)CArJRq9lQTwKjc>hH*0de z9V|+9cPuPpx$rr2zVN*flizDYE#B?{LTQ|FpzUDJFxgPv=54C?8X!hPGtcWt=^3S` z6jlnJxyEJqi%XFRI4tg0qiR7P5p`v3s9=!vaSw!AItJFcK8HRb3${phOfXq`7V(9M zh`F$O(Z1^!w@?UzWXsu)e>5!<*$Vs669%>YZDt@2lc9z8)A|8IbSTmpw1bN$Zhum> zmDCW<j8A6=Tq3Gv6jn_`CBo!P;ip=VS2TU(t%cd=d$+I-eAgTEwl7ROrxCfw(UI`; z9-&SqW6Ob(kWrutvzEAkc_bLDN;B+avd<FZ1d4Y7lCXLlyK@6f(!1!lbi=;sFfB?W z)M6P?3tAZ+&4a<(Tp%cjyDYQN(&}ImBX7B_04ON=-GY%Ke61i1Q&26Krk8;1`BH@= zYPLk43)oxS!qOsi@g`hGabsy*`rqli`}nkDwFLj%!}tq6*A^e3P*R5q^Ct2Ydu?N6 z!9#E2duxqcw`&$o2N3rZ={shK-FkJ%^7KIjg@B5K^G_kBG^i}I_t~e;ACMw#qkU;@ z-R2L1xij+BaP(ZalPAs2h)Lde+5Yj8@G3s`r7sXzFj30SY+6hrHXy|UL<?xfUA!lI zz5s!1eJOosOn&%o{ZjlK%DeY1z=sVaAaO$kK?ndympq(pl6_qmy+aO*Hxw}(O<M=J zt8h^$b}St!DPFK;PCUek0V=#GZUIGwDwrQ1fk)jq+yeolXRA+@c#ftmptTHvuuAAO zbEEQI_#aS}+9a?r5otuLxIdv{3)aP7j;+HyPg~fo7d;omCEXAXJytHr5xf)76YSr9 zYH!9iqKBK>M{2%)Ni^l0;=~ZCo7V;;{GJUaSqS_Tnn{@z4qZOnUEfpev^VI&vCs)s z?lfm2<*tWFMs%s@-KG1PD_vCav0$tNuV_*kyVbU}>+IKb9ht=*E(Io4abXh_j$DXs zwbO#Oxv5TqcPz3(bz#HD)bCQ$*7k9_csHaT6)@-ve?s5=_yVyGR7cU<>OrBCRf*KK z8%&?mhp9ALJ3o^?NSxCH`C&8f!x))Rrr<Xh<jj!1P&v!0Beb#>FiX=1FFG3hzL!lF zHllv!KfexD{Cp}M>{mz33n@Og7jUe17afUi(U}Llhc~myC_TQKBU(Z#^!&Ikyh;~0 zRI`eBDTJ|eE{H0Oz>IW}<vZ3#AV6riB|p<}063rzG*#IX<djP&rqq^+N)D|S4smoK ze=z|*=Fqr=*tmLy*rp(7KvDB)eW$6fnGr9Nv^Kvtk+e9EEozk{f<&VMdG}XtoFV1T z#&6)IKkk`B-rhlT%&hfSmf((GABLF$aSDzLmQDf&L$Yi$ZO&eh+S!=T;^DO#vjx>I zPW^ftF9O2joGV*<B}HdpWj*iyfV#FN?a%2=-|b3g-~hwA(woDFj)pU?CCUG4P7?~{ z%VVX*DC=(PsW8Lvhv<yAVUd0Vkv%DwbjHpLHn`5}Z0gzU%xVPR{R7gl_G<<f9qmg4 zHD8pRGcmXWjzTd3r5|UNzP1*QogVPukQc*q11ZkZtY26?tS64#;UigJVdSc6FaZnY zgF%vGk@ceax8u{LPje_7Er3yD2Kukwc*K6lOA#OVqh45D@QmlHD0GqtKGah6Ss-Xb z!%{?Waph87>J!el8PYp3ajHT)F=YyR#z&QrrLy2&4I)xpRNJ=Y+e46^-lB>RI?tag zK~5~9BXAZ3IF6k8X{ApVe!BrU_(EkNs>QVLH=BRy2`=F#MwiQujC2V+`8{&ak%+S^ zuV@U`>YcLn9FP%OI6_6=724-(f<8TiGt*C;^GQm#S2F1Rcw8t`^lnDjXPk|><}k*$ zB;uDJP<E!Hso<^cy(gPpcog89)>nUAl<Y@X=%fG%1n1f;{qMbwmi}NjCC`g5^a<P- z?;ncEd|^N9#iwVY%D9ceUX;+oboy#*gd&$nMp?;T=3p3&;`Pwl0{clERV(e-f7?O0 zajhQ|AM=DwL2*c+wI{UYYPClAyCk8V**a>0QFhvyX(Xnh&YvYHj8y8zd-LS$h5I!D zQS%uzEF-0t6JjS1q$xh}ycruCy_g;hLKUOhIbMS<6fb%>to74NtR<eQ3Na%-&k_Tv z1yhFA5{RNHEh>aHU=yhBXvGwiku=SDKT~uqMj+*8Ad}WY=WHq99Cjn%upB6&1N~Ip zJZ;8^`4yMEcDHl?vgV+T8XMdqo+9B~UV2r}+5-s57FJ-_SkES31L4B)@@To0qMDA9 zXu)eheci3%#|?|q@l8paC^l3D+#<1Cl}dUh9Lvu<;L?ei+U`&Y@+>uYWC_{JY@FR~ zn&()k&?BrmIFh<2P-;LdZ-RTpg$cQxw%TE-4t=kneM<!`uZWCLhA&#pYjQq$5%Al$ zZ{zEIdCm8sE$e>RGv2l$LsiU6t<J-wIA(}=CC%J1->VAG8QWP$rXz*Yf@89jx)iH$ zH4B~bnH`#&>t`zMRxLQ&M-RNfs~}pM$(PideWnw8f>bI1!Pe{NtA6;BDU{VIXPKJe z?wD%EWZsyrpyq&Uzv;yzncOqz*&ggkad&g^WtVh=wNh8<Kb{<_l*sDlmkmx^W*13M z=IH`**xEJr^F2sAMqY>ge1?Oo;|O7q{LHOsG7ySJFegx{$^BJ4-Zr95MFLloBP-FN z4Ue8>G@*N>ODYoDc-|aN+hl$MTHThZBXIplws)_+9wDfYBN@5LmR7}Q02N&=ByrNK zB*($ZC0+b&0~H@G?w^1e9slhYc{cSz8_bsp<;S31Q}ti~PVPZWWJ!ip1$)MnNlO7L z3~KjLPx~-2WisrlzK5ii*1o9KW`3u#gC;B@P92boHfiy?c-z<(W#vik?0wje7jb}p zk3L3cVI*nNztbUj6}e<AwDbr(^c1|tYXfn7_j*Ar9aX>QgDyQ4>@N(|f>ASdhRm>P znQsT|xqX>reqZ4LV&STv76lA($JCjzf%7DX<^cpXu}9NZC^)>o2u7jly}#uGiJS!Y z_|ZGy7Z!dVgIU@xX9B4s0oj60rmjI*n}V6L#ccuR7pKRZy00~DRh|Y-uBtBLMumZ} z&9Xr#H;V{*hha*dtY?YD)-iR8H%nD;3FdBNz#8CIbabuzZFL6?7gw>O?Xc$y3kGet z)Ab7!AazjO%|P>o2MWjyfPDMmqF6w@OiM9wv(Q5Vj%mRbI<B2&S}Z<oEZ|XLn*P`b z<a@8ML3W1|1E1splz7<LQ->ZYSgDxwYXIz9#iNhp25|#me2~Z()WPex&m=fK>=|Z8 zHx@E|q^FT<Y(4*2e<o08hh%H2(AHAfb8jOTNtOf!0BatFmCse43eJd8Gby6e7Vh11 z+`d)J(Ah<?X=cA|z|(*owBW_%BM-<;Qb^cn+6rx`FE))=vR?p*5@BPvlwgGnG3Y;1 znP0PYggU3|X$f%~$)1;1HxW$3#Sai0aKm9&xw}_2l@~h6vw*5qcxRONq0m#IG>0D< zYtux9P;c81?mT|kTg-)Btkc{{)1n@Ca#g49@&mPx68CwJb@Yae-N~QzUHiP&zsx}B z5-4}J@l;|HAm@S>r&n`ifcM0MKIyPQWvJ$X)eRT=YxDt$`1qkq2#t+ibh3umn7*Z$ z=fb`*;)fXLN`r8Vk=+wouW6_=pz7JaY|v*>!FZTI<M@D99wTA$<Uu*E8sW6ho4l(A zhtol(Kn{#{{`1GBd&R|Jy|7REv6cHmJd8O#$C)Ar-{{f!C2T?gh*9hZBp~EJ-D%?Y z0I|ybvA<6-Iw>*D!3)*W%iCbGK*=ZP>=qnkz?oU@@vGav7{rxi6JK_`XbQ;RqP=Zy z4HGGkuPwmPF2%7?BSkWC7+dCOQNL}h!wJwds~Aw$8!wXdsRchdyL61!mr=DUK-2~n zet%1Usu0edTnBL;31$V%muHwbR;h$gf1$*obafwy5mGw6i3#;V{0w2)LIm|T40yXV zy{CkCB1mmtUnCtSFh#_F0HZ*xfYWe;f$=a5@Db233wwhv=@bv&UK{oYp14@aIcwj^ zG(g-yN1mf=Wr5yJuB<uiYnc0uzZJn0f|sYE_Agj`6o-R=F#SUOLfuGauv5<2%{Tj- z1J0sGxa~I;E<)>V4nchj+m?9s=DE$0oCmlG8YYSDLGkmG72~+iToZflKG!3>aa%Yb z!$CeN`OO=j-jjN2{u*@6s-TtH0!RWkbx6sIS*zvT4=v&2^P}Mx-t6_|;Pt5sJ5a9) zVEy)PR&Tiw)O}I(Zrm&gNa^D^hmxw`76j4*aWHJ1McVp#m$k;2b|<=N*Z`*R3BoyU z%gu$DI36+__c_hM=?Q4B6*E2;6!7y|@-Ji$2(_Qlm(`=HQBL2W@J4{-g&e@W1>Wwm zEU|U;4!_n8c81&54MNp(yR-`O&us71^n9HNA>#19(6W9g0A(f)ghY8LDpHDPyAveo zrrvT+T2V|@BVxy)pUBfWd2C2zz=p*vuoG0&IV;fX6jFqUbRBT)&}IbP$raT4r6ZDq z6uo-c%TGie<_BQZY#WN{oYM1|kOrdlcA$2F0A0Y6DKj+V*#~2lUG(_~25qI7-;UO` zrv*?Fuy3@aATdNQI5a6nkIQh{QCk$?!@C{dE6V|49Plmf-!bPbJ|5jEi~@2;XOj(A z*Ba6x{iGQ)f-{JScP63~P2==_gqo#*y{*iFR8*yAo-k83P_MoDz!wMZ<iJHx>w$Q_ zQl%mhpourPp3xA2prm;{=SfKp>GgnV0PDb18=K?%2Xv?d+3RjR$#qPCI$Ewn=R2cN zFEG08<CX)7T-uwHWg0tjuY(D&+fjIZ)b5~AkST-FX9Ou-&;pj$E-vqoub@g_U)cWQ zAhG>uytlk2$iE;VSE@HuIn9LuSH9e=ITs#3hg;YWDVj_OPvj}nY8B8N+t^QjiFfy9 zI5<!Tf}s_nA3<uKj)TF<NFag>yZQ|pbLq}#vLteTeWOU(fDlL)hQ=XcWLX>^k{bGF zrh$CVmh$5G5dA_5u;erHf}!s0SS!rox5YW>GLmcMIw~DU4hDkS0U7uSXhYC2KCuk4 ziJS8S(tT#XOv#Ktq{RgRCDJLieR-?~whwXyWKDwnyMW?RQMW|QS>e9OPDZdlb%@u7 zvuM)kg>?iFV4n~OhLs#=KcnIT1=7!a|GpOjH()%wUYhYNJdJZFEM5AR^(yh>(rIm$ z_20NHYl)}%^N!!ebu-%bAl=+uAqYEE=7rw#g^bwlR-tn?^qn6~*Q^?Ee(|+o5`g1< z{W{pxaQl2eubzBAts<*;Na!w-QIc*jPkI+T+cxj&3<Q8PcNWYf62EndCWpE*0;^I5 z1&4(^5w_qzpfI*W<^9~OH*dYvMyjjd9pBdt4GitW>*n50a8a=NC^S_16!WxLgJIuf zWTknuwjtiLMj+JSTb~l;GHwqItq|-X>iq(l@`f|6w42r1<UDpJ-`xJj{XMLSu<A!z zE^%*l=0bdCvz<MJG1?t|^J9cH!Bjp%&_uiUI}o+!N`7ZEoVX^W(k0Kk0SdBYpC&3F zW@kB)*Q6!-HCsPvDlwAuQzAeZGeom+amYC91ACdW&Akr!UNvFLV`JzM>J@G+h=+*I z@)4)IID4O(jS|&P+{fKZSsm&&&W+d{DrIs~cYJ(W-xjv90Qa%*r!tp)zfi`{JJNs| zchIvS4*!D7IO&}<Pq;V!d2M0d+Uo|Q<HcvdPWAW$d9#$cLnuLf60tWdLs;fQ73apu z7`<~L+XaM23ebA<WiBi^*B#+36BH1zCx^(W={n_r9Ae+6Ymd_Qc?E{`T?M;q3C_4y zNlAhI=#g@em13m{83pm4(@ajkaXavmc(Q;xm%3HY(^82y8Oh=aO3wS;{*=$3-JHaa za<Xn4UXLce+y<}yC{Zi}buxjV%#&Pgk~Qu#3r{H*@&NkbANx{uPtB5}@S=NV7)Lrp ze_LO3;w4+aIbN68KxSQ8;owz$lQFY4&!!D2CLZ4cuq03>g+{x)ds$k5kk%FM+uZ}K zD^`nl`}w>ZugH3_7+x#pFG1?(Jz-P)QQ#0uNtzV42Nq8d8An)sm3TUMX-ZLi`u8Go z27?I;Dh%lS%tn5g=2(vnkI29+T|N4VH>dN-VkQuTAd7f#SHxHC^W}J+*FN!YMG+>x z_gIdo?Klf)whddjPYqU{^fDYLtb8V!pwF!jjr^{EBUSnow+0^azATag+o0L{c6`yR zzrcGEi6yJHZey4qc-+=Mn?pW+>(T>!VQVMl{xTZK?p}IyOoQy<FzX8IMD3C1+vOSQ zmv5AxgP35%A=?&D*SIr+7RSk85FRbN@dIC3dYi@kb@w@XZ0npdVWql$$I7<Z)|v^i zo3AmO*iwrLb8oogpQyXr;eFQH8(X(Br}bf-X7hC=^W{x~2y-$v?bxVBV((XcWzKoF z>%~C4M=uz*{fJUfjeX(Ar^jAFiaUq<Ew9*F^l9V+C{E}>PagRf%-6g|%_-qLLCeZ1 z2K3>ESMIU`l159d;ujEMNn^c1`Ix&x0!rq%yMdC&_Fa|~6NiI<`f6vOi+&Y_hsmN( zQ6cc&#JZz?b*mt8ft{7U6q`~hj#D**;$BQ0THqpz4)%?Kqox^~;9H^rOOU9&(eul? zFK>XSTR%|OnF~Kj+ibL)hN*&lAPyLhJt>Y8JY!D+KyU8dQ?F|sB}M?5k>HK1ui8GE zM;k_Wy?1fvGN534GYel{X?)p`fs_yfrx&<wP=a1Acn&Am__l}7qQCE9G}kk2N)ts> z$PR!rHEdyLC8pM+9QRH%k)+hX{j9%y%JTb1U8cAOgaGIB-Qh(@Ev~<>jP~kld+l$j zIoSPS2rBmCD+_Gar1)u4dkcr&dv5wyyEM<h=iI--3f%V}uDf2e`rO)cbi%tC1O-aN z%tp8Fa<}(#z7_i2L_%#a9>#AoE!cliE?*rj?jFoKOxo}PZPJ$PPp5_**%5+nVodi^ zNDS+%iIO3znEi{ug1Ysr%EM55zDvHEzu#65JYPROjT9Lsmw(Cl=1E~l2E7d%kUj)( zUgL;Ape*ZI%)@7D{goYqEpHQ-*CZ&vWV$bX2MW>r9><82)w1@Ppq+L5b4im!gsTaj z;u5p&R8buY&F;gibD_fSw;9H_&<aNzL%+*Etz=Uduuh&sq`9ErM+G+S{*HRovYd2o z;`!lh?)-Vee)VeDLR)l2!a4TaEyyr(P5G*5X^8pm$@fv{Beu+=5qfzT@GX;ml5JEu zAOLxi(nrHTB#i9`U*kJsx1&_>Mw7ed`&q3`^eoM;X}M8yBkWNM=)*~TftQ{>j9xBQ z6MxyH4SCCBEl$y{ewnhbwNrzRGHAI<N1&Oyb$2O#KhV$G65o$`Ka5yMwg-HdOZ>1G zsd3V^kz>zj`3SnMHnC;xRGl|}^91*Gwfo&dH$nozJ43grA9Z&*0uK*NYnI>+k$by_ z%+dRuY9TUFXx<Q$XO$~=vfhVYWe#9uCVt?cXwLFc?W=r<_N*Bx(z~_@y`Br@J;3_+ zXX~nO+Q%d!Tgj5{vlW^x-7zcPBT8w3l9-2*sYA!ze&s-w*M1pDjx_C9&0b!+eP4F# z>%;?PA8Ufc^o~o-;j4Nh#Q|ma%zM5!Rno5b)UZV9tR4vn7_ZF~`9?4KaORt1j|pRH zt+jKO<i6q1%kSEUhwsgdMhlWXrmi)kSY1g9DwfcC(qaveoa1GrMXZ*v&Z;&jhzQx$ zvYfxeHRBAAiSSLR<E$582`DSRmL77^lg(RJdc5OHj{?Rc1f6{6gqUl%^O=op{c&2= zGNu3!{jb*l@=Tt+=KSy>^&~_qm}HV7@=_-2P3&Z|eD<`$BCHoXr-r-!+2yolR==)X zJTk+(o8QETy>*Ta_kk^C^Yi7$(qjoy4tQ$04#7e_$8Uz~o(6cdEHr|Tz4qwhlkPR< zhciBh4ksuB$>2);VP{{tQi3Wz5?*KLByZbG7It8!C^HnkZ&$A9s_tHrMqJ1|O6D62 zmIALYY^}UA((LJGkq|CA!9zeSq^ku}N8Y};AX`zCJPs6`EYt5MMgYpV5O#j!=+!fX zvxe+~$LbP}t1>_U>FBH59T4Xh`BF*b8jA?0n2cHQhf93$m{dNF`-KFSTv5e_Edc@{ zifJ$L@n+qX`lhQ_$2C8Wz9@+&j}nd`$)l|ueqW2Pov*1yXb4_;Q`vBXi{Z?O32>;Z zvw37@Gs7f#5<v{{8?D<h6R<V@`NoG}K<m%OBNqs}rpb}cxv}{Hat%K>R44sAREw^8 zpVmV~57DW8FE~R@ot`7-DMA}NF%3!$V(M%LfT?@%bE<sh%Ll`(5AdoecfxCp9_0>7 zcPGdt5L_=FGlY0H{G|7SezT0SxVUYl-weyi8rAK`;94U`r{a-M=Q{$_pCHeM;{yoJ zqJ3`*(=HaBDl;*nhR1xur~9or*8w%pt)IEVz;%=67lL@psTg(N>3evUZgMNSul9UX z$*t8h3e#YU*Vy10o9jLk!FWUm2uLs$vvf1AcJ?E8ot)P3`E>WrN?(Hn6TzQAZ5Yhe zvN#s?&z#O+(!6=c$4AgRJq8OgRnE7d&MbILEiY@-H<J>P?|GPy`rZY#c^=A?)52lg z8`prfsH+t~!V7n^IzaE}IJ95=x~KHy{lmi@>R}n~%oM>Q+J%m(yeCfrIt(--h~sL| zPcI2h%G@(=BNMwIu2Sqv{pl%X>zOgD0@=I64%#StR{`_zt>B?__l+Tgt}-^8IAyvp zl1|OLREcF?-G1>ywtlSrO&e}?r9YlbFFE0V>*v_TfM{}nHia{g(l10DvpONb?7Zcd z(eYM}%Xqq1YP8lBvNMp1w4pz`amABQd)v}y7|2Q9zp^JIe)Vl#!UvBTE=;OMTYMK! zJR^F>TK1OVPtTNAlDKfRPsmEl>FU(=-UL1iuz-_d6*1!(FKqbdSx(=_;<tty4GfUe zK5Xb-_rAVTla9my#>*U%7Z+;BDp=yNWa6m>4<?e=MC8@fRY3_NU#s(nUV+t~dt_RV z)cH!^CDWQJjM&u6W^BYJrs!4Wy|<!DdcBIL*9f>)7+saQ!n7*$+4gG+1SY9L^04Y+ zmOYL$uUp(U@!|FgCQ5M#Y?@|aCB!)ob$lW9x9~X|r0u<uC`svZ25}yKDXonB=u+UM z=KKqu$X|1x2nFIMP5C9CGrpbnMa*jcfC!_LwGTlr6WKZ`I=yxoT5z422E9I&Zh#%H zJ9V(RX?)iP=51IQ+8KN=Yt7YQf%pTm?)V-VqM0Ln7{gM?%Lq4wj7K49!$8P)%;knW z!W~IjjG0?;w@~r>jFbf$IiFwo^6QI${rYLRPiS*?k>Y*8_!+WSd^?zw^b`h1dQD)o zNnNFwTg^7ZnLfzN1WwL~rKJTen~+zbj%x;jr#$$?9~`2Q+^sP(lCJMKsY^b%R!BcF z>FHDjgeir-FGPn?YQGlEDI`bf?u#A5QeX?oC6}Wf-Kx8#etc05B&W*2(2ViV*$rA9 z5DC01b+~>d(k<a5$5j<VB?E5X`dIf?y~Bp{cqd5C-g{;w<(18)x=CgQ6+WabE_uQH zO3(ea{y^d22PSI%`7C<k1$Ge=+ZOM>UA07bepkWOo+bB+6o8wUoP_nUD(>m-Qi<v+ z4tVAr>VS|xpUL2qp+cxHlnPv;WIw$udr2#q9&x`t!a1Oy@NkFoNXYRf-<p*hUIgZx zeB|Lyn8^MBYwVpjijAi%&vH~qg!e$xLRdYvV$3~n3fvU}5-|2aM5o$ybH`uhJ;#4* zaX+G&agJLnmwUh3|HQ)!YX%7)@t1fa!dHpS<GU`rtRzKyiTva4H(dI~Nnw4juE|IX zHqQyacTV%~N*_nRt7O{^fcrFXaX6E-Ow_IF%t<fsfn(fV+Co9NzPw@C+aV=g?_c;T zhX2Ctq2^T?Kl%{y4;p6rHG)NggK_lI`;_z7Y?*oVLVN-tLu_vZG@Xt|{zjpSFSHrI znvQL``#>HMKTOhDxLSMkX^pSFLfIgC_G{s2uLPFyB1N22uF#vtC|=WUQ6%P7))sW3 zSecy7+t#)b#uC)&IHs=2P`+npUw$0=Y2z`*SgDnX<DHhgfcPB$N#?S{6JPEmp7?bA zzPD#3&1%JezsVnOx4uUfe9J^};zI8Xuo6Y~zyGp*Pz?FhpdM<zL`NZF#v7t$u{`J9 zOHSR1)dx8*?mGDM)fSGjxSiS-7bJfAHkz?48YPqQIJdHHO`=ovgD^X#!1)u92J_pW z;XhN%xvu{HK5BAuUVi5sZ+JW1Jm>7~DHrJIBZoLAF9*^HR15U<@x1BpC>H4H;pL|m zh&uK6Fg0NNV7J^UvA>7--$tFXF*X&`@%FtbrhHERoct+GsF;|ThVPAAYGxPp{xux< zAL`V<&Up9k-E(&p&w2a0$RPkXKsk8@IR%BYz!7Kt?s@q;2A=iu6aQzDf6sIArk}H~ zn~%Snx0l$#ypB%Zcl=SOP92=+Kkc9Ebo9C5_MbBy+?$V&$3OSx;}&?+<A$TZqnp<) z@4t8Xe~mY|Xr>PwVeIJhf6wyY{(q+Ud$a#sgT}$R)wJ&fx_P)c`rb42bac6CanI+b z<{e)zHQ?7(`+F^FKCa&W-f9Z+K=LKWJArDhH+)@y6M8!OXvqD)Ciw4t{&Nm<f8f`? zq37-E>FBSCP*6cCC@7x?LWBO9;D7c0|A(45`nv_({C^GoU%mfh=zs58?Z2B=H+}tp zC!(pWq@<{<A@|>o|Kpf{&7~oC@c916<NOCJfA<1l(S&Nq{ReoO&_6#wvc{%*AY)?? z90UR#0x?&BKoDSyMIIq9U%>=o0k)ZdKW5+$^k)>L17iByn3<TE!OYCeU=}dYSXfyO z8Y>&?-^TW@2Kn0#9W?g;v_Ip(q>Mjg5XT|bUyw;ACLYkA_n<!DG_3zjeQ>6O2Alwx z5pswf%5en5%mfBAvw&HF69GLTKp%*OhxO=5gf`nTtRv(Uj#nW(KI@S9h00bwvoFgM zicY={*rEK#VFD*kpOKW3hM!kbRza$&>0H#+(>E|QGPkg_vbMQ$)%nKFTQ06{?tcDv z0`3Oh3yOFc85RBLaZEyDQu5PhDbG{0b8_?Y3kr*hU%#oUuBol7fBUZOeR~I`^Fvo( z|G?naq2X^MQ$MKFGe2j4(dJfG*XZjTn_JsEe?~xun1Ejn4cd3jD7`p#*7Dijl^yGt zz}je~)^95az`nUBu9RQ8|AbyFuktCC-g3BRD<E~@t6~+mQP&DI?0r4{w+vv%oT)Db zR(7agic#GA7arTqWce%g1>|G)%a_YD8VvzGKCGi2z5U3F>vetek90gM->I_OzV96> zHi|reVZ(dwp9+k2jJo$Po<;9%yb{pwlIc>i?5MZbXYf-ob)pN_Ri6e1-Qn!&gU9DB zUo2S$><)~SjnC!K3yYh0zlxsK(bWp-vwY!c;u>}rdGviCJUB#ph+kSEr1<@!{bG<6 zIJN*%dNIg?*TQ=wr|{a6xm)R``w6Lhv{6iqRCY`Ri^Y#5PI?JX+ts)W3W#epZ?B|9 z5Qe<-0+nxngr8){G*xX~4|x;zG|0*>Yx3HYo9g|rjWR&)(76`S2Aw%4HX2W}IY#M$ zKR&6)YLPfn^u{^H;XbE1Fg2WQ-cXm9Lc?Np`8Y!6Jb8g{rh{D;vhr?KSY2MrAmAve zTofF7@C|$lC#v;zfx~z^Jbd7AsqB=!gMVY-O$Ymc(Skb`{=k>r--C<kSl#nA$U=90 z3U49elcD7ItEBy_Csw?Vhf#KicvX2R3)nAzhl%!@0i%xAAkXJTyN^Vl^-i?>R*8Y6 z)^f3QVoF26Ie$QuMtkimG$6r$!XHrM?ffq-)H%_@a`aXT;s<2MN-{c(M7#2qvI8i} zL3P5IYG;zs8-nGdx^_Feq;&ygL8sQFIhEW2p8~t)bz);)wKW4NO50`KFZp4-lP0mc zI`xGk19S&AX}a0s=qDskE$>Grqq^SnYY#QdkUt*^4OE$bPW$odhUciM>VoB1dh(yo z`z|Syx3VNsqrBJk8n3mt%pdkqj@axd1fokRpX|ZPgI433-tKfccEjC;sHU^lKSBPl z#slR2X`0Dv-7CKOP5xMJ`mG(y5FlyD`!Bc0{Sm9ju5(vQwD>KTgH}!fJHOU*1Gqd> z4%~GW-8S5uDg^ynx%-J;<cX#Z{0o<zVePDd?%6z;2w#@@Q0*A&mp(|hZoS!&;e#G2 zcYRS*JYaG3Zn50g5|!`83!6pNHuU080KV|dL1qi5UYPPk#2De%^V5?Jo7asGkB%yD z^&GzP{A4o*6>2T4>nu+`Rq_Sf;!e!+ZZgiV9WQkK_cNFNooSYPuf&i$&wX^%tBhpQ zH=P{K_ge(EoK<&+Q)X@g9C+%TaICV-*LA_O{O`tCILPH3E5?gYJ4a2S+d1$1u2w}m z@KLREy*#XCfRzMg)*Ek}N`Mb?$uu$i5`YVA-4cKg#EyjpR`<e0(2E180Iw2&w1+pG zvf;YQ0Ln7O*%A)Grqh@C4??qJVs{TP$ZK(VJW>JZijUI!3*UcZ^dypx`>GKzr2JsM zzYtH|YCl!jt`{@_sB!tVSc3_fAwnSK$(pU2h_vXx0B;U;X_B%JGJcSud$F6S3vK%3 zuS^bkMzhERR|`oMyq{>i95nPL)u6pmRQt*b;kyxfM5)hB=z8lq-@E&!u%VP)YxGnP zX@9}xw&<Ms-rVFJ%|VhC>-ERlB@zpKr|ZVQCU>03BY@l|uQ#SX#!HUmn&!D9U}w!) z)L+BTsAJBX6FP)6LUgU$GE!qd8QfDkrHm{%7LMgVlP478L!LJ@i)e^25f|r`BDbIA zJGT<!jOOD4bVQCanLl6lZ)KD!WWU(Mmh-LLolqiQsa@(Uw$4~tX?HDR<}~+Y^OY%C z{+({Q&l*G*N4jT~gU%nIG^u4}YvL;H<R1`8x%jFaBhsvCNyoP1cEICM+KzSjR#Mpe z(Umfl{A^t(_Z*esA}5%(8L_VPnrO3rb-)C7qr&|wA?HYfEPjHoUFz*{+tz50JQxKi zOWc=gHcM8P?7Q`<F9)SQMA#xY+mYAHvzj@=D5bq$n`%On&0-#ytn2O!-r60!-n@Qs z7R<*^Gqns&!|GmaW6Kc}sfL)q`C;cr3cJTFY%*`&vx7s+g8Ke15}F4}Pg;n|7sJJ* zp0sv0y{A;|VTrpQ^&%jiny(vV691#>4LA;QeWA8pVBy)OH(o}@a;xQz)JU%_Th0pm zqTkw`a`k~bYkukX$`pRkQW9>Tx&nrNa;{ynVELJ<rw8W@I6xlB9WbCI#5mIn3$tS) zo7WG(8G~QXJ?KjTt`Wen9<}K&@jOX01%P+(!J@C;JlOb(<U4%uZDAtsmh>O`nVlVG zbkO}j$SER9pSM_ES{d($$&Y`^{1~z%)6wXG2(djyU@{IJ6h4>)tE=MM_ki2zs#JFM zl*8GU6NR7B0heWh#YWrallAf(|8&pN{Rf2|=>8e-ZpYiha!(4wzVo%;H-im@!GGRY z**x*4I%8|oeuri&QuMX5xcyp<#^9_8+#poDoxA^hrJQQX!x@~3!6sA!`bc@eA%WFE zqBuI$^u0yq1L?dDWMM1i{Hq4HYH@jS=A0ty$e-z|G+nfM5T|*BO9Uo6Mw$!sGmCou zt7#bYPv8E{Uxh9}HL%<5jn~>z*LIbdo!~E*b{LlJ=wG`b@JpPtd@Xs5XPGe@^N#z( z=#e)Xx)~LkD4AK+4mp|Z=zWcmBG;Bxer<a#R~?=c--LB#)2ttC#f7~eqS*qxJud!L z$Yt)DpShSi&E!*Dw@oN}ZadZ`_xW0C`tRR%!QI&}?}1YC!S@Tc`v4(9TT@`AEGLh8 z=(KFg{=6?@>%@A~A@C%J{m$>fbn_MufGou0%ALOh&hnEjjNtK*+oO^+OQ}MMB@6pf zEAJ-D(Iv~P04XX2UbmRrAtO=QxK9_TF)<~Bp;hk+DhrFjUlVeG$8<o=jJ+F7|4rRY za=^S*_y@=mof(=HUqeh);*T=jkQurXVvq~zPPlDGRI$8QeRj|IRy9>*-Eaw(`f7+} zKrr^=0sAecKj*CiUW+}qBy-U`T>wRAH;aHBycUqs(*PQHEj*gq0pR`R^SoFCK+^b& z5?%|;*XIXt(c3Fl1Hk%k=5G1xFC~TZ19A+o`(fpR@jp8bn7oQlkF-H&`zZpadF9$! zP26s)ohmi_Nxxm#<wW9NSwJc~4j-8Rn>S0V0D!LVSfck<p9iW)nK9}<a8b5oy*!&v z+FGyCd{+eIXgVp~oL}qTyR{R&H)ZS6j*InMF0*g5pBs6z{=Xo2y%yGPcQ!u8Uq^{| z+p1knxtA|M$pu-$opinWdMo><^J@Kfg&g|eKa&%MrC+L<F~#@@Oj?v|-peec@Ez&6 zmp2!B)u;Qcnu7k68OShKb;(4REq4-kNf#)qnv(I>E$J(*J?u~a{>`~21x(%TP7TY= z*n5M|cGfKA!l<(%>vzzDgN3}#F`r|?;1`pi8=lOJ>sKOCy6E@ztA`UcGy0luhiz>u z^#Mi0DbIJTyyAgdvzh;8&mHo$l-ifvyfkHx4lLN$5sk(9g>_<9UX|M1ntL>`z+B3e z_O+C>19;Vq@O57`kkpAK3a%>A^*hvYcS~sdV%XI={vydApk8|E;lmh)SitatV!uV` zFY70Ph0gE6e2b#2nBzI$n|kcm12>D?7E>SXtz3S#bRu)ly@AWmwBkpxd~5yyi^Go` zT!%Ycs_=PmOeBSmT>w@HKh|b(lv5d=Cud|eZyAKUjBD4$B7Z*r2bW3|A&c`^T`8oJ zyjb5C^F{3U7e7y*|5(+l_F`5^zTw1^!2Bt0B>_ueX?c{C*a<=w@0h5Okym?;Q=bQK z`gM7NnYqmki}U{iq_7(RBx%C%<N+BxK-{NcfJYmQ|07rCiiuRcOHcaf^p}&vCFd{y zC7NyGF@FVMIJ58H;h8Q=P&bT`Bg>t?L^ZBZi4~ZNkAqXl-1T5U$(Mtvd55T;S5mCw zwti^Xxr{VUhjc~RRrB$hsZx~$Jj$e#HXQV%dE?tJ4{P{mSrfPhu)4z1;Xd%+EWAJR zDek0OFw2x@2V^pv9=5eyvjZ*8Sos5z+a0V1ge=N{{SuVAFHN`|u{SbvKq(97CRTuG zKu?*7ujmJr5UlxNXOtG7Z$Z>^Dcfl?-Sn5mJCy{_t8sFE#xH&f4LUtE4?2--4Zb78 z$j*WYOVQfT9TF%i%uX>+iy;kLR0>%ZU-sgS2}kng-g=ty-kCXvg_z``WJ|F4bzErZ z&%pnM&lc+BU|iUjZp%x8zq`z8Emxt`(z_x@2R{04%YAQ{II@;+pkF{QPo3D;Jn{CL z_I^}o^2=P#x%i>a>7u()wHPBq?#|n@e?Z6nfI6?Olqov`o9K==cTVmn$K1CqWX{L- z9Co{gJ1H`-r@oKMEiYi`92^nxmcLB(wu>uwjqk*OW$)qp-@%XmfcjmE$)d8*6?;DC z{i8=v^P`&3+E0O~`SBaOb-W)Pai%<-g}HO?5kz->p%dZF3swi91H`=D15KkOexzhT zR^I)%@LXehHIsI#zVIBs1Q%R+KGoa9GUzrDe&ROw(<}f<&<JeOsTUD6KvglDJ`f0T zBQfPBhum6GZlnCEA1HjnyylIKJ7)LJ_aEWyJ(towJiv-GE_@jrbMr5;%U7lH@g0EY zA4R3`TLYB%Uj$)Id5F>gV5R<&abN>4<X`Z5+6$QVKSQ!JHOBy*g%|smTIN@D7XHOx z_D#xPmd$HnMi;eTE=gDgl}oQoo|+cjxcw0_-mV1@X{^D4(BK>+l_z8|#$#e$8*XSU z%c|elchnelt+GTp%%2nl#K`Fh!)<zCA-W-a*+R6932n<9^oo2^SoO8kz&{|vCjh;S zZV!8Ai{0-m!?cCriixE_71D`~zB-iimdueme5h*?FuohApKNpt{(ux$%qWrb=0%Xa ztJvBlbHT*{9dN0Btt6^g_oTbD;F%P*K)!QeKmEg$JT>6HV;pX!y@Z>6gB9g$<5D>e z4@~@EPW{UzQnb91{|x?b9JUwi^qT_y?5~QZ)JtL35~PjbnzA1~j_2KVZ)+oJpWig1 z=Qr=#MNOs;PMMc^T|v#~z83xU3RR-64;wU}x4#e=ws)oUO<#5*AXEls>|gi;iuFAT zz|rW95_*fFBq0vhO!l-U<->#R*D16;_$BUjv!MYyK5^{U;lit%RrQ8waQpS;0>&da zWy{Ne(Jmz_X|&t|JJ)+u#`?|uW9a5a?EIe0glN&ufJ;6c8l~N;WK8Kc<>`R)3l~=k z7c(Q;&l3n12XH7%^RrBG7&r&#7d>n3xH@ni(BQT7`HnB|Nmp}lp75@|(8l)S^3BD6 z@w!Ctf#M;}PX2Vk#LdFb9FH-Ib}UNbV!eE7qhRkDN>6H6r7m|@YMoE=8>w35cPS9G zYQt~qU-0B6n9uG~NaKlITGfxD79-$g(81O(U<Uvr03bjTjsFUe|L7?HQpf+%%@06# z`7bdC^zMJr$^)6=fc9Zc<0Jku>r_2moxjwu!|q4+0ddT7{HG)PRxk5krq9RH)LiW| z^n7a@0sjMPurvNg7Bz++*3pI0i_DP)Uo3x794`@Y2JrP1@t8V&C7zy1X`V+oK!l`= zZbPnx@?A$yOUwTOxxYQEzULpd1f6a^OStVu=c8<SFDhXNTd1S^Bi4{tVXRJE*##w7 za7}@bW%AF6)#}Ue_dMINpRNvbIBXP3XiNgei0n`k*TbDf!o}xN#dkpIu8tAy$}xlr zao&M>Yd$UBxd@G)xhD6{Gl1X1N4g42SkX_k|MPYKCXLY4Zk@PzVwIaOgldO#+pii> z0apBROIAO$Dnj|%C(fLauqu0UuWI}9?KgyITdVcbm6-M{B{G^3iYQC?==7~Q`6Xaq z=(N<Vrb|XgFQ(QMvx&-0*+G7UZFB4^bzTBkIsD@QU<z6-cz7SbYgr**eYWEL``|F6 zkm#MF+qB*Y(G~e+$Yc7~>5w$^OzM~Aj<6|?U9>kEomtfKa40&E7I52O!f1Wzf&I#6 z@OpWOccYsc&ax<hJ8tmIZcC(=JKOFc2XXy6C5V`fi!gmnxB>7<fFE1ozGndtRI(Q? zRxyS1Pg*D)5lYUt@KPV}|0)1z4F7((acR(p34eLy3s$2TwIItX5~}#Um3m#fyH1Xx zKc9~)K^?o7VnNT{|Fn^J!V$%Km1O9v)qd@S;$6P0!KWhPZPv<qs$VGLB5c+)kxGU{ zW4(!htU~q=x&KJALeMAxLov>2od06rhz|X}16=)^LLLxFg3tj$G#BveJWzrDElvKL zL}n*~o3#HYB>zn_53EE0cC{tf`EG^{4*h?Oy$Lwf{r5gjLdlXRlO;^0!g$Ia2}3=W zWE(SM3Ynyoku^!eB%#J$M99938BB{M*|LjN7?fnEkSvkGn0~MK(DV8HzyI&=x_;N? z%9xEf?{n^R-}gDMG+%~)YXG(Ry-g6*M9D{azRuwtZ$D{d607B%$MaQWzE@;<2HSex z^Mv5y0%sN>s@tuXv*lMI4;Ku3`<;9m;wdf5ANiYOZyP?Hyo+_>MSu&@3>-lux>i?? z53iT#C+gd|hq6YohcWOMaA$=(8<pES=Hfb{6&soMC4Y2iBxRJebDs1<Bv-Xj@N1xf z7Rk<aB!*eCYrfIYSEQ3MX~FxFDx5Ns6BrMJ+2>)J)e#zmo0=jWkx%3^=9Ec(DRkGK zWCOA92(Uf6=65ga;`kc<eovN;!W(Ve@^t%5*es=FZpUFeizV1w{Ojg;*nN>g{@2kt zegbi8A5?mZubN2ImPg)w46C@P>{j3RVzFjrhY<iJ-f+e*zt7r-t>IG^oz=v7JTn9- zF**hso!b<fnBN?xHl_Cr5dl^5bHwKN!v@j)kE)Z_pQL%OHs(2B{pdJJ`ZCvlW-cOp z{nO;qurBy5#WWB@{Gw}}eWq}yrrQG~{Q#5sY!aL3iT!vH>twfp`1|68^h?b=RH(Dg zOa#45Ohg3M39y>jRZo;~C^_+>rzIUU8hU<R@E>$FP{+yUMk0^Z;(Elzpawv&DQDX) zdht*;-D_Wy{2f)2zw*q;D>L1}w=$$fDFwr_M+W@deoe_kGrGpXj%hj8bf&87wmQ-f zP3>Ohq4NBvVWbczj&4TY))Csxd)(*ocDcSqy1yJ!6?Pk~_$^YrO0ZD*4vFGE`Cl#2 zzjb<pyM%sjD1gBSLWBGbip~_rq)Q;|4sniTDv(^+$#aujveGcQ13go|g8Ls|O@KA! zmERE#0jdGqcRy4B;*>}zI!2X9WjYT5B+fO@Z4od0iw6G&C?<^2EWJeB!X%3H*toef zvaK`nH9BEp(zu_`V68a1^R6V8ieIV;xl;CpiKvp}@}OmE9|y7enV8un>1dsDt7j%` zwWT_<JT3e;$AW11dWW4w=qrt$jBdR(wY1sZCob^XGr?r)eXH~_dS;<wf1`;<W+vBR zYin&q5ytI91>bGVC<p}NDF@~*GabWuEZ<nB@Jx7Ai84U^LT#o()21@KFr`ToK><@k z1GRuweI};vnx6O&I`NkX-7baidH5X>dWMp&4d6HbXVBL4Vs8yDb$hAaL)63^vcpLQ zxH%-w*HTvx_Vh0FRlF1vCXq(=-lSS*?R@&Hpiq@{Qh43v8&Rm#wcmPv@fT%u{d9oB zYwfd5)M&p^rx6C`#x(0ui328r@7dFNvoMw}k?)+2`N3wBRmESPUjDW^H0I(R{ofo> zNk10FUeC4n5xqw89ZP(}8iZE(4Rzxu@jS#aMbAZeYjva!p#%n)&96D2`*sMnR2hv$ z#cZSKXp+-Pl=4O50AZNXq?t`VbH4k6a^s27q=*PQ%sySm86hj#r9-JP2VFGE>{3fE z<!Ac_!95pNr7b5i_1Li`y}l9G_t&cc>3>>yss`(KTi*><hD~Pv<~aQ#Y}+X5XVt9+ z<rlDfq@T7kPKNJX9z9r-g$ea>8@m6JMijrQkK(>$L4L7R@VH3hIwfL7y8G<sLs?GW z5nA`(Yv!UX%La1U{3<&(p$_{`hYs6uL~En5A^ocbD93^{>j_XV$^gfXW;yZ(mx%xf z<{<Q9%wdpsAb`*ahyavvy$p;Sx;u+Zc3MkZrf#cwX)_YIS9VpKXfn5=sR=SQAa>E1 zOY8EIH$++!<+fx&g*V&qvw5w8(H9#PF;qN?^umQzHdnZNm{27*rSL5p(26Zb2fr0R zAhy^L3$FrFe%f)B^i@}p*kY}?Y~U#^@oms194u6dc18};j&0^w&PJQ)Li2i_+~}@J zw1&ymlM~d(uQNP!XOK6iqvE$e)X87O`pM&h&Ao(79_85^U>_ukq{bC4Q&6uP<;1}e z-ZNq%vL;ZxDmQYB=4_9Ow34Fe+6aG2;j4aqZ?4J((47Ajv1gax=}fnO2W9&!4|NJT z-Grd~E)Z<b3%V%ciu<#J?EF-1-@$Wk*j#`8U~m1T?VB+4VqTr{E+ImF*UKK6)!q+* z(pMWsUKx^cfHvirCrUgmIznWyMAo{ISM0FG5h<A0lAPF)t>+@>rFs`E6~5s=)q0Lb z2(66DvTnO{dV|$;B%(Eb^(OM&i#us1bA$KVUfA4c#eYlV-6jEkE`28T+t;Cq^uUrG zi)6c<mEG66VB5t;GCj2DMzI(Ro1jpEf7(*xeq?6INLpFJc+$!J*vpdiBbq=~0u*Sv z=Rj8O(-ne*<B^*%@vYa%Cc>TUjtC|}ZdU8D!zAyH3^xS*c-L*N9N2zND@-hX@JL^l z+-vgpAAO=lJ@pL<D1P2XTX*697UjyGfBG6~pSPbCwMlMKQqcUOE1x+z-}sN)8M?(G zziy*A=}_u%l7*56Y*&mQ8o*sLfRsQH$ozvmH<Y5xm__ga$gZt^Yz`hoUe8*I02F~} zaW6Jx{zJq6>D!?T5PAs!fW@ug27;?sBo3tST@f4ilfhCPtq!r>(@DerM9|@MtSi)w z4^#f0PqLAZP*F8Mz-fsN-=$~ehxx*7u$+|Lr-RT5&B>KE?~4Fe3T}pXmdFQ<UHfa$ zmn!b2PWo3|=NMaF#UkMhck>U@>cvRq1Mqs-L_L|7!31VDC>3|MAV*x0JtYO^2cxGH zQW<6M3We4(UlIk@CvpjcUijtdcO{++`33vv*xM?exP5C&s!Mszy$e*81<hO|tBa#s zo(R|Op`ON6K99@$=(s?a+j^_#+!;F!lQ=|F38$s=Q9e>OR_sl_+>EKf%h3|uFnhXV zXX+E@w<?->!m*@C^R8gyhFy(E6C_bls^(>$6^Du*KUKv8y7a#y90z83w0_=G{uO}@ zFxsJu@C~{$)%{#0HC}CgyG)~p&6E7d_fpP%I=u<9aovM;jOZ;zvfIFL;G`WZEo~+a zM7Xr%xFilO+ZHizDJb)`vvNn14C~P7v>mpY8CYmj0iWDXdU^W}CzVrkgdC-~`=JF= zyRJHFJ-LgeFvQE8fB2h2PkqvF@4HB<9IzxlWKOF^;O_cc>`@%?o7ENCsjUz0zDPu@ zT92kTS_hWw;*XM-ytIviX#%+7@iDddQ%#a|Qx${+LRO>|kooF+gdR~fM>1q&VB4*< z=zz7<tKXk46M+%&X~bnF)$h-Mm~`~E+T0FfJsF7e6hWEy6Wro%HYmb&-%xDFZ0lQ6 zOnXsflE78u{Gh$kgAlCBWvU|FC>Jx6`&hon3sE$l`=knxqn6L!<aV&@{T~Yc{~N%6 z$RyO~KNP`ZPl%P;1gj!!atnNaz>;C09|LURhWG@LFO?ICZBcQpa@o8xYTz$<2LyK9 zb@D+m@n*lWighUi&%omxeN7fQzS>_?FeiVYdw+cJLnH5GWu{<AT*93>;QucAMP2S# z4mt6sagAT-8eQ&9q0Zk5_(MNLgp<}(mPbTGy>$?pT%jJfw?=r6RO9B4Qm#j$W;xGC zE@OTb`Co@EYJ?%j_P8&?)BuLq<xD-%68H;AE)WVoDN%s@K^kUiEGH#Xxt@bCet+F_ zEhb?42^AHcHb+IxHDIdD%xiAU<=X}Y83!jN9x-$-;Y6nrd<RR+MHEe<Z|3E<WIF~m zs`IKJ-uvztd9X-6eKbc?SBswhgL)b+@|J%hHi}nd3X<S3RB?QjW%ad%F7%jZQhC#t zZoscX;j4kK14xxZlbd%(1I`_>z(9^pWL1N0ObS_Z6HnH2ydR}se72=Zqe+^(e2%$Y z*^~!mf1YFVj8;i{tO~cs5s88Gqa`<9UFv+lt+pt1zvRWm$+HW#1)^In4n@Ux+PEb6 zjLJ0xD3~bjp4wCGtfC`uiZ^m_hG%=ESL%UsQH^|rBx%geV)a5&*OP0W@XlhBp>_F& zYe8qh3OKk4;xLk>dytk_<K#U!T626Y2K0aF5;Oj4Ym4n?YbJAv^HW)UmB&ZIm;nZh zMP<Xh%!s`8TD%n!`mYokB3{fXpB?igg=LUGfkuduRcL_ymaC~lLEMh8LRmhoC7-=T zD&T#Cdccjl#QDOqRBQ-jMrF&CD1@LqLS>T$o!Jy8t^VR5Cr)Jl&8>PfBUzj8j(InR z<cU1OZDgS86$C20s_zV>-S5$G075C79#9W8>I4iKNTk*>6jIU64XSh_D}x5^4@JMJ z*h8=gR2L|MH(7r|s+qwIM5}3-T=eeQPym4IU_-D{4{NjRfKvG_(uLAK0GiEWZr%@S zMDQ3JPK_}=9(To7QEO8i?vX8TWN5bJAtAMxguuErrEs4J{Dr_kr2ySkXjkl71`qMM zW<NQTw{lu^wx-JNbHD&WVpXOdxxiNnj?=Sw$U3pWg5?o(!4526YuP5@@Nj>k2kwb4 ze%&*FDP8-1%>Yfan@I0HszoY(LU?=rQT{>gk=)xi^3ys~^7f}7T&ZSqr^uC0i+@;% z#A~kLcrw}#YL^<y$9ZR_n44Mbx;Rq6(Hw+&nR{1f$}C-0-7=^;&vW3e)YQ4rAM{&3 zX#}?+n)N+y1;DxfUt>0tj_l!Eq}}~iI1+A<;&Bm$r`Cw;?yw~Ua+Gwt?%dKLzpk+0 zj_*9!d42m~C%daxt@%6tj*T(6Iq~cw>dlt?Nm0WAclnnzgFE^!c6^{eu&robq<9RY z1<q>hx?mC4eTi!Vcu5#V(yo-|JQG>?B*DcY;d;Y$^8E1p=@*^P4~SJ-BC2lx<}gmg zbq_vg-kd+od<op5&Ooqjc5$rxi}yo`;nF46h2+@MO5{kOZtrd#g+c~E)H3qFIXrOm zNEWh{in27;>bW_M(wxP<K@hZP*r_TJE8$pd;t-(k0f(=S7aO5I|D`TcrHcJ<Bm2^4 z>?faYuWTz03lkIh5MF{?y;+mId_+0qA`!8=$mc*bak_TO^vH25DwnaHV7$$VQ@Ld} zu9AHBlb_~V{lyJ<GN{Z$P?s&{Lwp*DKVT`@q^d}cik{GWfx!L`1m1uR5QxwQIs<rv zO=j%Wri2x@8LJ2lsVPXzk}vS=%xe1KTnyetBvDE}4p>oQH1nVHi>bFV-f(vAuKdeh zP-lt{p`nw%lMB3wxgLPZFpwJD`X5>hL+sh&w6(+Vf&%u;ZTU!GnE3xkr|a^=_2DyV zV#Lvr!S!1E>%+vQro5it9CS0*(#<9+E4Ta^9kb-alYh~kaB;=c;_$~V472-UQ1OKV zy>jYbayuHa<OR+Hm_YjSF?F~<Dn{PZgm?0kdEYe>Msi(#3SMP$z~OcF-*w54kbbFN z80qfaT@`8*ZWAGHBdMZ7NuCZ7s1hT!o`*75Xn>Rb-{SP=He_#7xFt9w60}Ri9W`T@ zpMkSVsm$rs<8uSi&NP3W=g+Dvzs+&B2kNl8@Z0m|s>{_nnw$Ja%Lt4|mL1RTS6EBu z6Ap!Yz`j1*7it=%e6BRyNBW?2e7DT3xYYEM${Y9ZNm}zSJj8Whb4?@UIOAx@(Io}9 zkHqW-1s~seb=C973U&mAcT-AFiay}PI|Q~ryJ>^JuWmSW^5Q7+T+J}nANFYO7de>L zLPT8QF;-G&VC^?_c%;(Z!#tole?igxZ(R4w&+p4wSQ`?_K3*S?WK`i)fQ?J3&u4O_ z<GBxYm@PCDA|fQQm+j_JSJgtcWj7)Ix{JLbN%#G#ZjO2w)EWD5oWdX!eNwAaZB%tp zG&y%C$?{h&&`hCPtpvpul>Uka70sQ)UoPd*K@(->7!?n)mE=Y!LJuQ=cnjhR;1v*G z|BCvc_Ww%;XUR`)8k#nAg-zCVBX&_{*jjSk15JQCM9`x7xf-DH13_*GlB**-1!Im! z9={?Pg@D3$!_IPPMb!%7)E{eC6W;4{PbkNiKYoYCH8a`q7P9jsh}mPhO9H^rqf*4Z zSH?5Pp%DZvCU$*w06x`tG|5t8b;tkAr~eNT+h~gD-%_Mu={z0Ole$jUx56g2aLtjK zo!fchqpTj6jkT+gw9p=6nEc>{B)2P4o@hF6aHCCRf*4G33#Dc7sDWbA83zN^uWlv# z^SMZJ`G#Nmtu#3>0rD@!TWEl>{U2e9f4_oD)Mr)FZNgS-7ilI88zbhy-S(ZdpR{kk zIfiqlh;_U2!n9XT+Z(MJ`5zB%l9ssjahLbAB0(L6x%bV1;>r5m7fY`<b=h&rt>tAD ziJpD_>5yJQmF`%dMX-J3C9RjdJ&%5Tayp?mX?K@g?Nn=fHOQ5>^O*yuhtAaaATv;Q z*!EG{{F3PKIrX}kG;ob+^{RR+2bNehvyc~Q&saN&4Ov5=ms3YItv?IA30jH5xfL$w zqzA<3+$OuuH~N+}ZhP*yzmz4ytX7I3b}8e}o@zM1mNt%QHbETI9Y<4&OeE3Dv9YLF z(7i`BQOm>uiUgvUrOKEmYG{=$l&aep%%Dy$<iRk9rtbaFzHlc3v0IP8wO!<@O(;nT z;DUH57_YhfMx<uTZpnND=qSqKhJugTdLB4WHU!WO%^%<lc5oT&8^ZA4DulA@e~0Py zAM7Ce7tONCWRNJ?Q7g{@HFqR=UNmYmME@99fHt6(mjlrw8y*6A<UX5cyv$oOOGWrb z;=)#>&B}radEN6AQv`5jDQOUTJx^2LpF+Q?bmdDEVC|uZb*HUnoH7XD98O!|whchm z6#|>azMDk8uF|zPthoYwgv|1<-yA>qex~gJsY+e9jFsuWOns-0Us7+!WUY3$U3-U^ zA0pX2Gvt^wkUQX=qde~1;A)CKxg~DwwK#bdWAI$r+&nR#S0uPIXB#K^=R4=|V<Yj7 zZY6SU{>37?akFxAE#%&bA$05WF1h@UlLBoPb~h+q!ZlLlyF4QhTkDi7nRE}F3@Y^2 zmv(60W<1KJ4Mae6uxZVRzJ18tYdGUn;aTF>OrjPmTvx2`=^Xaq4P|gR_tghKc9+Cm zI&&V>{j6V9hGyS&W>RDdUgl?v!cXfTpMdx4CJ$eV_2KpO)cwlsHyg)aoETeFu+_p& zetw}H72j{uU(g|RvhiA3=>WEANV9N9$MY7>NxSZ6lQ?&t&o4iNnJo_K2}N?z^95}? zKFXW5cbY|b%X6>p^js$q^R#+D?nchbtfyVDk0hU4T-uKEKVJK+#$iA`FXcPZX2IhA z$z^41T1XfR(MDYTinp`)5U6er`BaKtUwARTHR&E#UvTP@ec&DP&TE!&i}@S8(}{Gt zsS@F@L`m$8(Fsb}a&9&%h;)z4lNtDujL!k^ma>RGGjt&X^h}o00K|f93K<5WW(lOv zBtX0ZP3_<2smYG*kOKQy*-QbTR1?_M8N}#5OM=Q>G&{NetD{~>e&(DkL~z^22C`Xz z^!QH~W~irKsE%XvvYX-q@Cjm~;z00`?k>=wPl)|@y+NKgtmjhqQ)K)qy3r8+L}2>s zDP&I)S)}v3S}TatCj>&cL!LWZ5Efyu7=@!BEdBVLC-Hg=N0uIlMUzzGir}e57}d2q zF!On}icnG)ydO3Z2m>(@T~{zo^l@LVDcq>|l-R&|YAF*Nl}Cy<<TmN&DDDQ_)zm+W z`2Zs2VC9rak%L@f<Q*w!-YVn787p+#<(y*)ItavzC{-&t?4)snw@9~Z@!g3BBrCvk z?drT;p_#vJE1=`yujEIgAls?a_}WLZYOooxyt%XTMPq<V8^C)|aDpnY(4i};8Qxf` z|4RJfO7CL+&>o=|jQw@~{)IqKMNG$fw)Q?@TFn_GMEYwS&LXS0YSL=)5v;AR=JM`+ zE%R;tenHD;#(qy!_nYZQ@P#kDu*QF8Ts@=WzuBA&MSbfo^xV=8Fr+H_s-9?Hd5h*m zv0|@k^I{S0^q$N2)=1yoIaIq(sP0vNLl`Pt#VT;WE3mFEVWb$w58?S4H#K!_P3zZx z#N&qRFEm?PPdy_dip?$8UETy9B<4pI_#XzxvJ`!0mG}0lF2W<xnHiT?{IC~JO<UI3 zIB^5rzBo$(^B!>X^4qpv$dWSv4l90A=!@K|%*^D!uI8HzIZ@xdhjA^jgL1OK1MmvF zkE!(`s$e?=ol78Tmu+5#6pFK+KqZCz1RzA%KvEg{695j%A(-twA+a+qJ8c@Mk=4bm zpxgx<r7tHpAKw49gslT8_dR~<1Ib-?^P!vvm|DtAw#+L!20Xnpoqnbn;<7f-1&DZ< zg#0^a_8pcQyd;y@ZIT$TC?&)#H&?1m!#2VD2mL=OHDqH>B%R^Amy%>6M-^)}ks~Vw zu+0d0vI9WjAI{F!QTPVuC$>lrPFl;t=Z_Q93s1XImte{B;j?FdbG%e|3;iPDvXj>8 zH5D3bgFTg_fQm)ibsN|CcE9wce$&j0jS^5CP#d?Cc#x9Elbc7m=#-H%<ey7XYzLmo z$Bjr2>BX7p6QzVc4&0$6M?U9MuXB$Mcc!RDIXi3cd5CLf=j4x~P6aJH!#O<=FL`~O zyCI9|MY1_UB@k_oA9=Sl4m$ki+FU%b5Ooe7cIiRSs(hwvLH16g5~6<1v$DoycS(kh z_MRdW-44FnA+OeO-J(8)mt|~gP)tgcBevd4;pcCTU*!w~X=+~0{i`x7&wifAjrvgY zPUqpZ|Kb-u^Rq$rZWEF3r<7GkMoffvVF1sXOe-?vhQl)1bKq$S=4v1;$bH#!7B|ay zq&joX=`pJsPA-~Q54<kZN#6G6I5nbYLHz(zUhTlo%2WKvflKffTnBNF`wrg)DM|Q) zrXI1|i^mNKU+YtCE$s&^7~Q|tnkvgia7;fV)-5_*;NSw&?BW2Gw8jA}o)n0*+E0Bd zC6TV}O-_8+m;Nwhgd%Z2;brdmRTSv^QNV<SHvYPwVm_kQx<v5=%SE10ti^|XavwJJ zQ2_-NvWmglr)TFLdkwmJP>1iYb|JWG0j1BD-Jos>v}7dUFeS<T0_fpSsov<i_When zA!7_||3*6nTr9xa4duW?c2Eu!0dSWMdch5LrB9dP-H6T&Eg{o$V8a-&i(ldrc#d*H zmGZMxDDVMQE8!|PZSn9&*Y{A@mV)*hEIl-?T@{pP_d@K|+klP`LC0M~qfoQIvWOdg zX;A3Bx8I5DJK0$sJoofntotIX#OpfzvzL$q&b4}B-N2Gjr{by;gG=<a4X;B4xU+1D zRra2g-yHcxgaTQc)WO-FNSM+d1G!@&(%c+lP6>G?&n0DT3T|d?NgTTnD{?(OFK36i zEKiZ)y-Lj3{-0P-imVNfcUqknCONfQj!JgLje(A8{*8%+gPE+3bMosv9N<r#4!{rp zV~9ZfM8e40xJUJ3qFd35UCVb$yt}WoBy?7nF=XZy(Q}41F4QyS_`{)ki!|Wp=VLst zA3+8W%^yjv&HkvtxkwgV8lIMI@Kdk3SA49vEr(y+Llqx3Sd6Uu#Dvo<_C@pA%1q)9 zw1h~M2l%x4-TbByT;@|!zDPUW<z{`QS%<LR&o_U$@8w;dqcS=6^kWZHzbh1V8XnoZ zN?KI-7$l>9+CefZzK#(bc>-CN?=1RYa$qlswJS6vSnzm+@Hz7g+MsWEgV(e~@a!YU zM>;ip%ka?lgev^3zKz9l%QEdSBOY+&o@qaO$V@GeR--Leai6{xT4z#~MyL;ik|;x| z1jGqV3ayj+{A(-<W#$lT*#Z4S7dX<;=1ozSf4uCIzfIUfZulnUyKf6+YzT8;A`w{f zLaE(;8;(5c#tZ&F2B7AKg)|FvLRxaUnzNvN-)QSMSykX_NV>E+O#+hSf8+t>W^uMz zV3Tj%K%i_~3fn{XW(O@>=mMhihHLeYqGePWeDcUm8_2aqij3ooMbQgXwt-P}gbRo6 zyMgZL!m)4H_*RO{FJ7~BEYUL*1SvE}zj1qKQW*F_p!YSms5-|_oXQWL<uv|S+ZeEY z7{9_*3!>C#lyx$C5#}~Ht4PNxM##Vc1?7QD@Wr!`W@mbuv}c#8?Mo0C#fIc(taaxY zoXJ()>8vl%sLAhv7<(k@^CSP-9;25R-M~D(nmwL3iE4n$i^y*@7fA}-!rz(yUTvhU zD+f$9U^U0AI?wY7$%uTp^YDixI`QI#kaNY#pHYtvTnG_YSBLzlPM6l2vK(5n15<Db zjBFp;-_b1HD^Q^?$;rE8Y%{xP+xy((iNfOOF9XKRdJx5EIMT*q@pN=TYQsD}*RR0j z;I4nXqBP{C;~yRIyM=4V7l+j=Aouv%pKg)i@$J<XGGXe?TL&G9B)45wiT?;J`nwM3 z)9aQdUX90=CB{o)`lLpA7ux+K4`^+1Nu?K-o{G_=Xx-m)f$J&k^A(25>i{uaE?)7S z^5ofuz**SWKtL?T+&%NF0Q@b+_5$cM&_x`bsJ_EEKRB7d)$@hw;KxD^gF{_ZS^CBS z?HB$31ZQ6t)(=sI1)gXSUe7>6LsXrp2N0f|otbiqko!Hq=Y{!N!lJ%){D}xKQ3ale z{rsZ~UZ?`XF(g#r=!V4}`;E+tIt5Ys?9Sev9?x!R5J%nW0B!_H6)Mr2C4ZB5GLsW9 z#B3M<*lg%VN(A@*qtCwiFDrFBLITRBazI1wx{^s!?#s9Y97^mr+{~mKk}P{F0o;8z zUy6+yP^WGawte2)U2$~FZksIXp&0~<wDRCmV|@UjP?C>kqSc8BQaP3pDk{<lAw>wX zfLH6}x6u!Kd&KM%BHU-8gRo(KtMEGf!q(7IMP8=);5THv1@G$c5)3!GcfI}oZ;tc0 zc!mp0_w#yR`H0|F22H6ONf$~l^0*FDo<!F#Q;j?(EwJroz~Gy=ePQ0pw$=6Psb29D z+uoPBOzZBWmrM_qO(~YY=2KE$2)eBR>o0$ki!#-3JkE72-x4ik!`W=&d%Q^=&ZpcL zYd95`av@dkb)$ybbI(rp1cW2$v6f|9EK2S|x}T-Kl=C+of(c+woi4#E!90zr8%}*f zSB|Ctg11KEH0uB?Bd2r{gUdPh@q5YXyJCg2+orpm%R1ggU}Nqe`POUJlUWM3{-@_I zd`nmmD*HrhOD*8`n`ui-2?pm+KX1IT%eK8$sYziW`Bxsps?VHyh<ZtSf8wL9d`wnF zP}YSACF`f^r@1Ribu%m5gFjik7o!<<9BG*6IaEBG@z;p}>iz1gCeK!J0qM*pnQwJf zR!h2<R;@iP9>TurA}kfNm<ms#fwi97)%mL^Y<7@8nrWJ2aYmxFH#nL&ZSOfR>DGyx zFS<6&Ojd8#0mWhM`U-XxIHYbbQQ8NnU4R{r-ik4=YD7~Ofj;C&&dz<|Dxx;Tj}?t> zKQ@C#gn;u7ahX&=U7h$+9oI+0PC}&82|dc}!<HPVixSLy0I8u6?>;JtzBTfQZEZGn zYTg1oSARTzn-u<L?=FJo6YLh>%BJ#zP;ra7=h?MiE>}c~f&lUKhg02{se;OT^M(U< zkF4h=XSFA4N$S67f?UlJwsUa9Rt*!2b|RcsUJy2|KG%0~w8Le5?b-drwQki$oUB?L z${Mldnz?y#ay$EqkT*h|<Chs1n<Ryve29`x1SS{Rrtocr;WaA)HEUTbm^q;V8XfB% zL7e)#W;&53KiA6)C|fJJ)}V7l;jOyG64y6{6e$B!Kg`_vR7aoINNOHTUQ=8|&`4dy zn_Vw*5PI##iJwtR+L#Iswa3^=s}TN5`uX$pf^@!1>P@4Kno)GLNw5hIkGwMnSB~<U zRh~(_p}7K}Nu6?jbDTxhxYs@IR(Q+ADBEM<On;VIyU{FIYn+ic8&4g$ihKY3pGHr= zkgUnFm*ygi;BUMtJ49?)H+nsApp-rXzhceVOj)M&DY#y!Z}JnUxnJxgAlbUZ@rAWj zf_1%5k?aUA_;04;aCt$Ii0F=mB&G?2HdI05pT1^mob2;VN}(lT!cGD}Tw&)Xjh`4# zOtHdG{_0bc_6a-g@01u@x}~^SQjTi$(Un^7zrRGYt+FUzq;Tun{6y}S6OA41E5AO9 zLIMMUQ`>lX<E@(dqfI3*dPIwE!=F^=t@LuvbGUVK7M-lsWc79>m(EV(uW>G`euMZ+ zP>8Yp*RaL_S}Lz%ReOL}2BoqLgPq8lXgrz`XfB^9k`)z)^`jYBgQ3rmiU9c%dk~Pw zHtd`BgP?#TIOz~y6#!|rK)V$}^~HIyP5drWnUL)CuOAQssX!$K8UnkBizG_NL574= zPa(Z@Gf~Ql9fNQwBqu@ctfcyJ@)dS|{^M~`PI$S24*rz?Kgl>Iiv3LyNA0}XZZ6<E z$SGMXJbex5_bb0Sz92iRZRyC-8CHqu5*h6HH!u#aI)#e+O7h^`^u?lI55fHg!tN0` zXa8|b`jcCa7%?p*iO&(Yh?TmT6y_zdvgZKgI<DXzFhKc7@^$ytj89bNS%H4ra}o9~ z3b<N#3c8%gj^OGkEU<IR0NyI?lO8$X6Bjg<kPi^^iJe!xw9v#mA$u{D!Fbiny7Y>B z#|h{1#Pe-|3H!rhjzU!20JCe)UQZK21KvE5@RV!jWZOdHG@l$(F392PB)hiwiC1Lc zBW$7?VO}!!P5FAXpIgRqqsuq#)^Ph}2k|@aR1npL&Qjygn(YU=o1Dv@Pj<xxZX2mF zt+|MgRGwUh&xK8UIrWW(ym!P0xLCKj$oZCAf1N7`je#}iEzrV%g%=(YJGFYvW!1}n zO7|*mTzx6)Q-5N%STih=Y!e>tRiN;uDD&3o!nS7hZ+_~GB;je>8^VX{Ty-d{FzHKN zomFmg0q=9H_Fl6;H!>VvEIm>V>@P9VLkjkv!)uzVx`t`e`%%E2X#Yxb#E?mR;=$5} z&&w7m)cT6{D6&4Xt}k07eU#Tbu)r`P4m%fWfMwfTS|~<^%Ap1)v6G1_QwV694j4>8 zLvK%|gV`mZRKe^mlINgU!)2yR860GrN}QuRGqc$vcHS_~V-RnYs{&zMr~}#nn19^W zATP>gKIEVufcR5WArmDX`J;U936rLKql)9$Hhn(u6nWq<hRjru1^~W{1Of!~`On>u zRRwC8OuvLS@^3uTU;}V&_G%DaYSp*ilT!|UCH{cgOq;|Xo`TN<X2~YkkM0hPwDGo5 z@}Juejiz*}&a>TJB3VUp((&b@!nYBsJ=xJgq*c*6z_5mvy48$n0`CwSoP<??r*z{Z zM%SfVz}y9L(%xv8$Y3%RaQ2he?a}$5|9-j3_tglDq_jEUZe2(TPF2vyZ^<|>q^=F7 zze^(~(&Gtyh)Zk5T<_$gd$JA(1)Fne^F6PZL~rktr+lWIFcwpr7`tfsc3WPaIbpvS zBb)MdJm2zRPfEX_{Kt`W!0#{Si@N&(zVx!}+DJOGGnkG`_RY(=2}YNj-{jDF-<Evv zH4>tn6bWX8{iIb_8qL*a&PA5pTkP&H2=-B^Jrv&R6{V>ipb*}xHdFYu=@`7V*dIQ! zClYQM<!kGFVq5c7+>Avn^1k)pF8}RPIrYKhvt;S-nH9%06kysHo|d#99X!)@@mb;) zDPvmmY*dYa(_D3hs$t>@uacjH1wN(8MvsBLUF9l4cC2Who}V*rye3NuXLp~e#+&qX zg|@{;6P6T8j_-E_BL&YLQ+gjUK3tgDwp666A8EStIA3>gIO*45XmnXa%vu&{DtF{E z7rj?_^t!B(=8QdY*zogp$LN(Q<dcAD;kTaayo=;)@)gRGJ&A1e7V&uc6c$|HYKi-5 z`0gol!SK%S<hM18#EY9RN#V%&!lR_1FhY@`Cb)S5%<zE$Y#2|bj0niQ8{Im)cZX(4 zvk?M@mLw2f?9e4A3Y%?R%+5X_SX>O+dC=s7K>PzZ!A-fWAk%^4n;z|ro-DB~)c}g# z&4vsVMU*2O*g}ND9Vn3hAX>R>hs}Fj?%X6_0T1Mga)I0l=v+WwK$nkMljxQ-XXc5N z`rX%L@o~LveXmAVn$2B~=fU={SzWoju%&F-L&?zhlk$ZXXYC9!g(=SAKBVphu`hxx z1M<l}5cl5b5s*TImPBgAk)w4DAb!<Z*wJcH@TA+T)~Qv?MG9}PyD#l8SEXY!nqfZu z^VW^0gzK$uU;i9|y?T*8rKe4Q?T5XL?&{2#JY_vJb|E9?eCNJq7~I55G5|qTljc^7 zm^Td%9VvW1hB-Eoz~v*~st1!Yk_8>(wWGr%>_MZF<L+<F^xMs%bf|z-{og}acY!p? zl<s(9v(;^zC;lZ;z}rRY+Hk*?_mucqWR5>_KKS)6hS9nB6RhEPm|rx(B=|9Y(_^sL z_Mb~anv6IWY1x5W{4tet7WZa;oQ##$bNEPFcXLS&a5o8S@H-{M-5M%3liGd1yrMVQ z{~9AeG@Plq9AotO0&hC4rDoTa&MU97YWFq?DnwS7i3*D~-n7oS`YQn`H+jw}IR7S@ zQ+=?{WGkh6svXgPw$3P>QWRnvZ0|6t<llJc<w~ex<}wUSul)qe|N6|T58jprhZ!P% zI02u{AleQei5wFgjJ!z;u@$v8VkJd?#rrihw?+JV&5D}@)x8P;RL59M;)P^vqJN2? z@~JoK_78)4!12Cutw5ZlEJ0`ywucmyu%A)`(N`F#HfL?gyu_8G!e;LwR?0I<9-^e4 zkLDN}`jQ{}fW`@o?TMd|kJ|tNxgi{5R`EQPS1BWDAZ9?5zts`Ktx&x;Fy4@`L@<}; zU+1!cEi@=C#*R$#W6u^gcG%Eot#%5WFl4i&o81|ZXE!b12;kgqg{~4=4z>sZ0b*@v z((vDCmn+_rjX-!IuOrqZR>Eve2}iWNTqOP&8`))J-{fgqVL(lZ<R-|t0jDP~v4uyX zzY>J&8u69<JhA!pDhVHvwjczl>n==cv%ew;bk4;>om;bZxWuW!DFd&|WU5Tg*}Fs7 zv9;pZ7j9JUesrhfhwh-Ci&V-{MRgnV?%f?IM_E#eRF(X5etry?*EQugIIEvZ=;Y_8 zpXH!8ofqZFYWb36dX046Jwfdm^NX`_3#fe-7qs{ig~w-dn~r0nIKUWd$N!9G6_Aj> zNJP)|e7#E?QxICKU&Z~HtwpZ<Rao-{-df;~Vg$I3y7HVk8m+4wufB4PcBRZlF#pgK z?+SZxz-74r-r{tNFRaPA*Xqo<tJ*MHSM(>`2-6Cb_-#kaWq&w{-7T9-TJ5q5{*JS7 z`*Pg+WJ~U$Q2jWEI|703tWNlj$oSEzU!JU)m62*`UmI~gB+4$gCa)lNr6b5bz{T@m z&LC{c&zt2hleB2YxA=YS@4U%#`&#x?kbb(0|K{NK6ot>Ph<>oH#7|Fmvn10P6jw*q zFPEBE`;MFo5bKp1`K}w&5Bgt^q0f%RgFV&Erz^$4jnxl3$Yud(fE5t3q2RP7B3HY8 z)-tK_YOVL@QxQTnGls2EQ6I_MngLw%&SmFA0FtRdLsbto&}ZxVhT<@8D3Xl<liw^g zg^(A!h=JBmY}%$m^vTAM@!Asbyup)(LOEgpSSM(coSL!$h8VY7%2(nwxt{>rbz~z6 z12I8(qe(L`M8C}4$i%=1V{QiC1SkxDS2!1gRL=>m5|GP`@Y#UTn<fMU7|*c{mpAwU zHr8E)gbK15+U)`ZP|`(d)&hB6E;E7C4|VaHLI8q}pUPf^kK<K*fuqV|N&P*2D|=oN zh32+#ysgC++h%~$WYZz^h3{6tl*3+JhqMrgYkq9`|B|c6;Eo`D^seBd03JTUHE9dx zooz`A0Tw@SDv-TP`^-B9V-8-C7O-w+-XcN$uRQJUoRwqh88se_7%yei^>o0InYvCq z2DW#~ccm-XeotJTtBvPDG$~5`^0Za4tVpuJabL3375!rLE55su{OBurh_R7W(n;5R zN4ulkT6!lh)Bqayf28X_0p4pilz2C(>ecE~+Q9oz8?&DKL(|IM6(`g8SG+lb5lWyf z(xQHIToDRAX=%YQUL>=KBaQyY4;X4F8!Pz<+ad3%b?pc!Qtm2r_SI-8)6&fnnbYmO z3)8)en;xv6y=Pq`>@P0xS##|=g*)zsOb<<$oZ&SX>1nUgb(M)rZ_j<3UOE`pJGR_F z<g*xFw?AVN!>LJARJ!ko_#$xAzUq8W!U4f2RD6BeN}a@Fh4UPSX0xbpwrAv{NoDHN z*8w#amz@sq-Wn{zXrimDi|;w#j4?9b{O0Iu^s^^#A*d>5NsMWmayhHu9$wKDg0HEN z*49kFnnkbIGASk?X9GvT;bqFRX%vzWw2HX|d|FDLC_wOHTbFIz>>q=s->(S3jgVJe zANZXz!BtUcDP1D?({lITk%u?QA5$~42At#AqHRnR<oSbeEYK}s(jc&P<Kh5K40%jI zpaPICQRG~u3Au9P`1!3mA$1}TggKPiK^(>{ZuDgld``7}Y#JdEZ17-PWKqDo%N|Pj zvkqgU8~j(n)qo!*97$p4`#<5#7WzoeTVtc>QwW(F5h$PkF(pQHeu_D8J^;~AoEnEB zU6}zQU2#eMt-I`a-u~bXdl;|@WI`7d32)L{B6bg*!u&{1yc~o#U?5p~DC;j@nPH#T zJ1oLky1aCBwMsN2;S8}Cf+VS%kff)kXQVO>y%zr#livkXBl=pWPo5?{^~0R%$%~$# zZm$JEj`OuxzT-?%e8T<=u*C^;RYeXJgx-DpniciVOZ9!%;3jw9&UEIXV^QQcjXJld zQQlyA4X?;ZqIizM)@v61oQ-EV9M%6Sg~N^*-lPHU_sUmz73{2^M8qQP_`FRND}D^W zuwt0AOm(TZdc(b_@{h+!+~UbKB?hT}M7Hjm_P!#moSEXYWib(#rD}w&2qxZ<hNl%W zLL-2qdmu~wNn`e-E{={CWfJojqh{!szYe8jox&QiH_Gd*)HUuIk=YuoJ|Pj3{R+s1 zk7~RZ6uyChMPWDX!$tK+e~$mP+u*xZjfuNj#kmu$haJsadzKZ-x3RFXyB}OwdBMQF zt$_!M>yw?$sC}~Ucr|J7cC;D3c<JJ7sN`uET9zA5wt%bjCTHn{yiccDbr#+Ipb%9u z_-*-?q~5Jw<Y@3(d^2Gv4?j@52z!|}-TVQU;R~p>k&GAcnch6Y;KE;N>p$(%?h(ge z2X7t;TTWoTBCP>>8Dy%9#HF`HL=qT`kti}0I3!=OJKZyc0vrpnl31%_YORPWJut-u z{Y6}Xi;u=8zF?d~Bjg$zieD#sPX;+Zx-+R^;<14`7{P_O381!Nu6_w&&jD>x6_BR^ zEU|dm3~dhjBb@zVBLM8q(eR?H{UJ6sw!Y-nu<fs4LWftxkqdBSU~LgsPx6zjjmuy| z8Oa8I?_Jjc(1A(6PfECaEEgc{4nT>p_jo{dVer+yNh?{Hz|(`Dr)}hv3aSS?t1r&m zgw#09+T}o(;-3#!eO7^0jm@Qi9YZxMTMU+pAln}spR}<m*A0-P8q7Q1v#S#|t(EvX zFkJQ*Q^5tl){8V*aJ5)ByC#!!TFNxduXuE=c(k)1>M;zCTg8;9EaujjMDWice4F~w z{Wo&U#k0wulzj8#cC;h*ezD#XVvpdhzfSHpCOkG5(B}V(u=~vz+NiZ;FWA0ewoszY ztjp}fB?U5LNih$cMUPkI4+jzeG3<QAmq4i!P^nyNd<jfn;7qxMR&~WHn`$^{3tm>2 ztoF{~vDIDL$1dM;kWKjeGQvnYe!1jbn(MqmJ&KWF+WdJY!L?4v4d~(a$JHs+MEo7i z{V!+5d{2CCNK$*{T6gDTE64>;QV-27HHR&o`up;^3PEm9t%0~#k@*+lN|SbiX*YEf zd_*F4x-91Xy22<Fq+SAOM({b)Sk<lhg&(eC+4B9?8F$1Gjpu2}VKG9f*I82y1%BKF zyxAhmi-E^IFh-9##y0wYj)+jdIe1@f_Arw!iPlynKDUrx<y-uGc5cMxGHLK_X=Igw z=d$l#wbA-E*%v%?LVQ@l{=THQ#4`JOiYM8OHD81VOGLIONXL)%DRZnJge||jJ>V3* z!$+A^4mq!IkmrT^7LgT&IPwwdFK;iA_Y@w5X4lH4DEt>5Kww!D^p;#6W|o_Dp7JXR zQsO$Wt>zb_p*9o>Hn7I)g%5j$0pRgKD%@O{5rk54j0LWSKePr!6bC&dJv`55-X<+~ z0UyGqVzN1ZzPUgK^S3S`COQEo03r~!E7fz;8nNliy*we#t^k`X^5!zT4N#u*op9VS zImJ43c;b1~NcGiu(hNOYdZ`Hn{-0nLu`bD5ef0!vDw)Ke^i^c(#Rj+lyY-mv;1815 zZw?v~Wx;3%WZ#qHta91{O?0k?dAEkIua~v-zOynJ4f!2fCas#SWyA@cz^#PtEEMFC zPrvXePfGsQg~vN53b%@n+~?swSvLMAUzpP_>E67Fs7K>gj&9{)1fSQaHr?Q<r`63Y zu^j#iPt%rn@;A82$rIX`bk{A9_l?3NmSB#K7}C)N=ipf!pp>utSnbBnF6M&a<-$OF zm*%Lz-Xx#AzG7$$8LrHNzpKIM{`C;VR~+2po5CbMELF35&iZA-hthBO@z~=q8eyIl z;_4IY`$A8=q~csZar+M>-%qjSHtDYAN0p+Zy!H2(`nlEl7ZP7acyari93B{ODot^S znQ>SwQfSnbz69?(Iy!AShr6e!cFufHvNNCdRlc+n3QKFR2UNRQGQL_;guiq@xn&*? znSDKtv;J<#P#^uxA)yU(85P)aN=AR8sq#Y2LH|=(?U{rJXWv%%JhThVA{=pTU51UT zhCQw9*PN)*FsME|#6xrWyYth7%9)~bpAJ3{>M8xa?z_tOy%KT4<=53)rX@34W4ErK z&GKYo-%NL?C0%O>X57LheGA+}zf|Tdp_2v<WucXN-^&d%D80w5*y&w}kdN-9)|ik; zQTmNm4o!e_4i&(GT?OR+8)V2lwlShPk;SDzx(nvHj4=|Caf&8XM1&{Sm?vYh(K=V- zBnqTUWoTF&+PDP#JnT3%1Ut99p>W!y?Vz|c+VW@p0sGEem1U7HAn%KyI@tr6AkHE4 z8pKF%&aiL5?`<m~y8o5)vveQ>yBwKWV-gJ+G5{4AHg2~;y0G83ar1jaWTPY+`&>-O zg!CTi(s<<`RWIx6!1+oC^|QQHH`o6Y?I;5m8zPm;uWM7Jm9)C27Qe8?<l8KeP<4@C zV9vzeG;$sjH109xPd4Cp7zDrZA+FOk(?=9qmMj>{go!nJtT)wz)WJnUwC~-U!slzR zN9FcVHOtB~sepeWA5<6HN&;s=!W84n37iWa@(80C*Ic8Y=*ONX>lc2InMIn}A1%ka z&RmW)X|>p&^n~!EpH_m6_cXK2EsToawdD)KzyR)70~l#%w~B6cDBQV6x>wA6M?w3m z8=8O`=Dy-fWa&CGkxv5i{13{ogf(^3KH%~%0}YLbdBf4cYXCM6Z+E!aj9h515I#qY z^xr=qPJbcPzBMIFFtJF`cO(%eQ@V{7TCL&Bb8Z((cW+nLTNQXRY+OPo&Zd}0oCgzu zd&~%~Teu<-w8x{cHECJ#HaH5(O<RiAeBgWF`$K<SpLx+!b3*;J@zH}{9=e4(yiz$H zd{)vpR0AB9jH?|iCf3Uh#g|lw&Fy(eVtDpCCVsx7aDQGpPRewiR6n;qUzXhBx1^aQ zUwAZisjltnucZ57&nD0Dd$g-%wVrF>P_|DPjus^3p-Rgae%+qxpVOo{(Pz@N?mqZZ ztp$$7d`IvLDJ(2VyBIBY@(oQay5Uu6`azXyWx3(Nl3!(E2YfyhMx-@_GpVLa*<hI> z*vCkaKpb8B_={4YM0h5qncJePN1#ST=NLdcVuT2wb<KU*I+8(7K|@~5T)z!KzYH@; z{32jr8W`6ECUoQrp?3k81zPv@M@-qAkAO0L=D;m9J7U?<>`g99?cU=yC4c4548?y} z1Ix0FVT?cPK>st8@uxnxkY!0=8AR?6abQ$9mS5qtp$~3IH5pDo0F)Op$#NTS8!70M zU$a?Pus`^l!;Hqk2u-zrwwI<36`nsIg$jxlxa1#LaOO&N*c^^|`@t(P48I~2y=-8E zU-~))%mm^!W4rR$SbUfTVey1vTfgPiw&=RbXbiv#K1J?Tr$kLEcu_W2l{j)Sh0DIV zd0=v}y|=^^GOLiDh=t?|Jtlv=7G(IPFxaHib;ZD7R)6ae=Vuv#C07leISVSI9t-wM z{G*fq!uvHD7fiZ&9<guvcA**=q+wu>MH7O=^{LK3BhW1$m7FycO#t0}rKo!SA0wE6 z2TS2M2gao-4U)CZjDFCDaf^q*SU8v&T@oFd{#y5pm|9nLbt&KVjS+u}FutJXh2r;_ zQFx#25b<86KEX1Y@AbjI!GKdJFCP-YxN)xI$D-K@+dXvo1E#2;??!}C|C8CDre9%_ z&UM~-z%ThreeOtE#(=L-qrfFEp-*3`(Vt;6FPJ*P%>$zAA9ya=)p_FO-=`C#;oTCQ zlP20mTX6%#t^QWp2E)HO7zQP~-^TF24&azMxBkK9Y=jj}hBTplHtUS<!+#PiUU7{3 zwg;Ls&F8{>9qk_Rh>4F*+T;G-GQktEOgljTKHf#suKn1X;d=vROFofWS6q_JrFLOr z-_Jti>6%wvDHeiU!chj-CERK#{Zpvog%nYHUM@22;{0}5RLq(pE7-0&Tj=8fK>haK zbFMt)Q5}iD$vDP*&)>Iey~Eb1@E`!+IA|lDnal)FzA)*25U&U2`z_GULa`0{P@wgZ zNJ-FE61|mYXbf*K>HZp6wOf+1?i|14dM?=6ko23w2WXIxJhU;ZA(tD^Ce?xemt71{ zvNn$rdBi@fD+4hIO3wdT)X1(J(AU690^R>Fr_R1+Hi12R;2C;!1LOQr-hutT6Dl;8 z&qtD>eG-q@W1_}-I)wcd&K&Qz#J?Kt%yNitG;-e-Vw^ui-yT#bmn<qq<79*?7aDg@ ze4bO<u;b^~ZpFAA%RwT|>2DoLsq9(m;_qQ?R<ZGohPo#ixDI<>;N=R`ngs0Pm;-*9 z+XBAYwFE;pMT3Ea!5>27_ON016~5>kZ|S{j%V5@X!3@XJY4^%3FzSLi9T8N}H#bms zT%k;K@;LMIsyp0lLf|G*@Z?~#t+FC>DunARS{UQk{AevtR5aM^>)re%@ANhs<N3}) zjw%CO8ZRkQ@8T+&6L#%Ffh{FjpnG>yPOZ($6i)LP`3Z_Ey8RgXW%kvQ{c=(+fKhio z5(tLxEmPyS!y0^P>!((65lCi0pxT$yKMtS$@J?|T`zjeFHXa7rfDZR9n3?<X^z!Fl z*BMz3YubUYfiviytI@-J7qk+(qZ)NrY;kC$=BTzl^$Zg;w=!>@nxVc8IXcN}EtLWe zSyMU?ybw#rJ!GDmD@?oZUE1=tMfc<xJO@+n>U9f-!FBrs=)3K=mYd<9x=YrDwQmi7 zyrv>FxIZeh+MIDoJ5^-<#NUI6-ObvLebvQ`=-k1{M^C4B7JZwreBFB+?^33$87ss~ zEAd~Rzf~W@NUfy}!>jc1LUx~Z;wA?4?^NRCM|70k&i{-Ha0%-;0=KAGkeoB~TQ8t$ z?@iScQ;!e0>fnL?(cLazYS$DXMl@O7W50)%w%+}l<AcF9tp{Ml^bKp0w*BeI$hgao z=q<|b+xx)Au$)W~@Kk8&ZbotpHx|e<VN#Uj2!4zZ&<v?`H?WozFfNHR*hwX=PWs=+ z$o>8$XPev3b_ykvq96weZ3C+VF2Cc?23<pLrF6FSgB`B_JR#U1G@v!i|NHge2-PAG z+y9w#{x3N7=PfsvMuTf=4`?2`K6!QmOvT<(1YU>rQ)Z`o=t2@}X;jC#?lVoHW2hA} zYT>L(PV2al#lyY{4Zvh~zZjeWf79ok<_2|?`h;+TGdJK}+`Hn8dn0kBzJTwCP*T2_ z>!juLakBu}5OGCxv<Uq2ScWj*(ZkGxgA9=<H1i6m6GxL-LoDpD{cdoZyo%Ew5vsYy z`bIm@O&sm-MI6UWb`~Ak4$FSVEGGFRJw2t?_q0aQ#A;>Qlvk|@u729kOP=IWV<OWg zN&k#BP?O5jjaPE*-s7l^uAi}q*fIf5J>^#Bc-LXgGyBpHt#k|~O=!`3lT=`LS){Y^ z9k*#)>EjeW`2r738erp{-2#{N{Lr4w!*+@!Vz<QnO~WHMvn=tkM81-&qem>)Nb9-` z_1_%(DNwz5RK+{|^|rPV0O&hEU(wxD@?dJ@CKe`R_f>rvH*=#1@4I6-ER41N^gXx3 zxPVSY$=e+7r(A}R+Zc6gb*q{7wi<06z0af*7Yp5`-b*IzD4dkEwexyS+;IaQMp!6U zZ@cRn-R>z7LjCNb?6QjbtajO>xg>BXuvx1ntom<XZG%AA1oo4*84I?+JCn7hV&e~= zzw5_}{W<w6TzqFxokrd;liE*oq6zrA|GLXKOPnh^8!u{IV%GD1eO6E5r{johu)5+F z-$%1`eQ%wP6&|>f0(T6uzkDRY^$@mpqWU<aZ0NCfp+4<AK6XWnw*BM5lRKg+agP|G zwKHz2Vw0V(+y$mmuR820<Ehv~eso6V3F67~5d*FWiRCIR{yl#)!}^)KICt{cFZJO^ z2Ln4iNo&EwKY8Zji*ytUHkMRx;40Yz!lZnYk38vdTgqW(p+>OX%BQfC|KabkUeL~z zCMg8ZTFE)q4BA5#O8}Pww9JT20zqYDa|i0CL>d8TcNvj*$?FGUyOuyW{_od}-0MH} z11Jk@sTJ)*icD~27naRwgH2z{pRH^p`5gU>FsPL_gI3Og%LZ-OVcg)jVbR)MCm#oD zSo=F}4Novd6&7S_v_AC^cjh-ouKbotmk}$lD!h?FlN}5S0vEFJbd&*P$gUT*V6(MW zQJL|#))j2tub*NfjAl^M@r%eHP(ScdufS;giWqLa7TwG$UN^9q&tmEIxvvGU;6i+D zStqh4&+*>VU4OrpS@{r9g3;IPXgTIj5Dn*C2r>%+1d($z^dgLhMd)EEpHTEma}p)p z_RmX-+39DsU$U$8H;16S>Ue2~RoPx))JTqbTwONWx%D$aUh=EDh}+4F-8D*%r09vm zv7ISdygb=4aVB{^xsfMQlAiP{kxlM^DYQl;@<>1A*>?UBxIB)HHW4xz*2W-jkmkc_ z3<lHLJ#?RR_o1-2ZKQQAhWty0gHdNy(}BPH`B;g>p)mZGN*y=W{`Cx|`<8&P`krjP z&LZ@?>-`qm{?rxR$orYvd3$&Sycl_piM!PJ!rnNR^TYlW&#3PCo}NP$0z#HAuGBnR z+I25)biL<0@jYRPc{;QIO0Uy)9*(uVQiY`0*XQc06W5b<<)_m4{q0_j2Ps_bx0Ai< z*IUi{NGu*m7>VXPJ$!m@&$z%Y_>ksM^v@YQNL2zvLfUSBS#U)?idCr9skrDESy!Dh zUpB*=>+j!#ET#G6X6zsP%~585W53GLZMCo#-!{Eqe5d`V*I%OJdcQ8;TfATFYJK{w zsF-Gvg-w_BuMaW09ty3lmlDisK5D|ISFtTG@5+-)MAr_9Sr=F9RHj6>eR4UazH&tE zmy>;ZZ`zr14N>0pq_wc&$Ad#_M2B;cB49_$Ilz7DE#}6*0auE^fh@!}3K*c_gZ2f` zfC`|QovYN+j)gX~P&z#jytA0JLabYHGtk;4piu?THA7=y|L(KiT#vDjgLEe`n6$l~ z(_+II1{HyS*AuguDeyJ)!S<g+Y!{n!-8eM?Jg~vO{_!quE;WK)0X@KeGqiXB0s-7q z?C~)6<pdV2h~;40`IS74Cz}wZ%6qAAKVL#G()KbUkX<jPGArY=Ag@9m0GrSc)9QuT zuLP}B$|C3314g;$#cvKPB46wp#waI1XrshDViFtmYJTt~A(!%|5Y0{C^7+eE1Bfov zI%w8rA8N5Etbyw*n7#ML#ZINo|8R+4%<sxM6JB`LXqj8R+By%p!_rWN&@x?G==xgZ zS*R4ja7Pq@gJbe^iXg&%Pi$X?jI7#^czI6Xb?VBo_<(ilH|I9IAt;~#A70EwKb*Br zkxTdQ=4aR&{PROfk1P&+w>x$PS#!J>iM*?+c00H;t%M3B0|E`%(~Z*q26|d#zxoK! zP3IZ(guyAIR$%bLyO&F}F4`Rx4d(voppRfJ%PxbUoQg<KI*FCeI_PgV*Ze*HH^<ih z!`PcZL*2h`z)DiGw3w1ar6(Dc$YeKC*6e0X2~$)Uge=K6A!M?K7W+1KCPkDr8nnt@ zc0;mc%`zC%`}xj{e$Vqi?>X;#PUm?_rY7$1y<GQoUH6BtbU~{A^go?6G+&ZOOO*Nk zdvbCOrzKYK9i$_#D<2Ieefo4M#r4u7gYWRlKs=)7+j~yJ!oV-b^CET+{KlJIz}(<+ z?dU!p`{VV88zeAluM>2tFP6}G^S?#vETu$Zw@>+r(gY(L`gvET7pTi6){i~!jrba_ zxvgR-k1M$Q?<BNzt(ukvR$lQYVl_`V28V@V#z;Xwg=J<xDg3zias4~L$B~knp}p1R z!?53^hMN0j>1}H_`*-83{J(ZJNb*O^2N(rgN?Bf^grDeX{@Eahu&#TPg?;bZT2Zm4 zUinf^h(Ou=wCAI8IY}-4^VEXCbvhkSbm?}*XX#dVES1$g+di9!9^2x@bpxz^^F{zK zfBYg?l&OPA&j%hhr0zW6+Ql1?nx3i@uM<Me+Xp(9RF@b+QGE{c&_b4WKf?o@ncpGa zdEUBQdIpne%jlq>;DubkK`{TTqhfk5GoA=0--pRH|GRQvG*~Ur1E8wG^AGfStl=Hn ze&~QtV?t9K#`7C&%<#Oe6Y!C2-mJ<H3Sf_2#4fAf6$7dW1;*TBpkMM6(3Al$#*_bp z_y=b@*T?)*<w~Y;PgY~7sPL~S8|XnWSlJgdX<<qP;SRhoosD^qHdbM&Uy+ogHe@es z&<`5U(=jF_d_fBELO7p;Z+wY4+NZ7q3WkkHkbO_o$C5TnwGjUP^k)M3Em>xy2eVT8 zq9dajwKIkXtMX13G!RvH!m{ph>NqRvt8W>7l)0lbgWZ1gnfUw98W^rK`sk)KgU|7A zl=G_ipB;o>h!m>Q%3z1>aki`OfEV#0z*gb^MnC&9Fp|CKP0vfpI2e=Nju~IB4F$ZT z`<Gq6@%_M>P?h!QHI5wR6B9@yi-CsbP{ByTqJW!}bE}!%2T`MxC!!IYLs*q~yFp{# zyD(f|zxduu`dyaiU<(JI)P>tqFd+xX3OpGyOR0B1a2ib@;Uj5OMM~~1-HW)lAr6?A zRFff_hDhGAva_qF5?t=sE9|!3^@>wyxX|wy&2DyKl`njzaQdY1`)-ZC9pM#Pla06R ze@@=Fzf7a9-XZllQIGgj#pd{yV%q%n(41pFwv-M!`k&z6o_O$?ShlE$vBa858*=c$ zAGQ~TMHx%aepEb`T=@weV6G*OKWqVNe((0!n%F9kg8jb599C-<Wp8eaY^@1!qMj6? z?E&A#t25mSKh<ZyKF0FkYWwYCv})$xM@l`e<;YMH@_0KeM|#(%)1WwM8X6);sk}ys z(XRd(Vc#Wl@yF{>U#ZJxrIFFTKaa0iRvZ|Rmw9UajM_8bl{D@M84m5~(DTim4SzeE z={aSY!eCK=vHIMyS+aoOgGKOw0J=5+eNX=+MC7;1?l3em6fSws37Q{hWZ;%QbD7kc zpHicHYta(o-~cAZc`#TIA{evze~x)T?H6<}$94m^Wjspa1u8%@52keJ2lSXh^bJBZ z!xopNA5PzpZft;B@ZFg#t3BpNSgv}<nI32VB9I!%dIh~9luFKa#rSB5jB^eABFqai z3?x7SA*2MrH#2I<kNt9~;aSNCj=d_#_;iwLf(^>?3gcQ8sZE)e6zhCbWk5flOCQYo z!}bx|P~s=U?db|yF=xy@AUIabwa~Akzi?XSxXYUcG+dv}pJitg^|MRut~}pyo~JSX z$*rxn=RVukr3w~{P7R`Odf;{&49RrI$?eZ#+n>w3i7Yi=p1rS@KTic$OvpXFLd`;& zi4=*Ow8nFO_Qx3dqyPo&O_Rba5$dA$3%NJg1Pg|%w#k95Hdti*>j~2AMGWt|>YJY6 z!5PbQ>>0gOvz*i#c`xMC>}Z`gW(*m$@U-&4;C`B;&*omewfu9_nqsrC-zC45rY%-Z zxEk$>;J7d>3gbP!#^3eQM|M_ZsSR&$uY34K*-BEgF4r1n>C$?p(!tr~rNFQ09aE1C zcDz*}yB_d=rPcG}MEzGA#Co<Ta>;f*(#J9LJI!>qF+^sq;!0DeXBPScOtcLgRjz8( zot>#m;l1K8yBsnUu4!=WtMzX(UT|R6<>xQQp{CL##ieJ|J43l{`F35u-jonvhtJGg zM`>h;-VPA>xqrvkWPF6LMw@+A1+ONIH2bkp;b*-Qtb1}*>GPJQ7X=SKxP)ibkOsa@ z(s>V4zoc+?4cSDfeDuw`T>qlk@R_RwJdER7%Y((DMzCfL7^k;;D1<fN$W<MBv$c#v z^Xtu;e`*HP|FFHXArJHfY8Stzrg)V-8l#+Z$QMvoj|!;WG+E+@rYgGM>U^SiYj`>l zP-j1C{5F{~iiisx(!26&em!2l7gJDaIB@P|@t7~1$K$HU6_QpLtlsWCU5sx5`JuXr z3ieA!>elT$ZF9E0C10TAm*<S-g}ojDT2cm52HJyrSFHfYpHKvd9Dv#cL1ch96acW# z<aONZwS|Tm^aM2iGd9hP*#mV8uE2_7W@Y++uT(%D%9>%obH;#x8F&KVIs@RE3wrb# zG=M23L}uO?X^b=!Q35PMH0xu~A5z=Q@bmdA9SCh;r~*)W{rMle3qJU%BYxm_NmXfq z>0Jc;O+dGI9y(Qp%JC#iy_V@NhE+5l4;I$Dcrw2S8H40(O&>1PiO>gbyJaQKU@vk# zj>mV`pybNFwn+=i9I2v4@Z9;Y_4-PjA2y&pe1lzgg$)V|fZ~<MC|(JFi`Ox`_nlb> z)p2T4grsrQ4e_}mp34W-C446$qrMRbT~!Y)WCy5{5$D3%Ld4=D&L@|=4ev$ggdiko zFA*0-l;uM<N9D-03m}fM<)ZI_^^h^FnV+MFtkdhPfO0>r(ExYbAuIv5DSw~22XmUM zFC-cy&n!iV1A%ZmK~HiWx32D2;MZiiC#B&S&k<hP)4kpt)Ao}FVabvu9SDI+snmmS zJmRZSSMj^12f{t$7m0{HLKvGN1Flz9?mx}_Mmta4jGARD91!&UZu0`m?dh}P<)gG& zZXjZ`vb%FsOGqK*DQ1%N%MQ@&oT<xe64X2Nod>itz`3jC!*49;M#^n%<E>?Wa`?A4 zf7l#+ozRc^>)(m#y}~bQd_bsfTAil5uO!T+ED@=VbB(&M+f<HHBi2mIUdv0F>wc;U z_-RYapO>X@h8%4{*o14K=Cj-Ji}_6m8JkGA^W3Gao?_%DW+!Q~&!w~vUp==#_Iqfn za^~fnN3?LU!+;c<PD-ECtV~&%?J!>((I;@urq1OO_EpC9@(6>32;iyt@Ig>V#g*rz zJspMDTM;5sU`=UIA0Kbg!|RO>x7?5J9K2n%tq7|NzP()s-;!Ra@D9^=#Y8kznY;0q z?uo!1V|ly-!3%o)0P&n*c7ImerR!*$gJg9;QOlet&ucd_B;kpw>-Ng49j?pc2f%?B zh?mW9ug>VsZ-JcuV0$9$VmIIbFyRB#I=5uw*UUNPU-m1kB_l*41eUbmNy$mP+6Fx_ znTK`(D<EhbVzq?-5iII8$TN2BEJ-+E2SR8B<Q#N-(&!J{UU*4g-er6T;Wys{(I99N ziD*HO0n>mq<}IRF?m4q~w?Aw*%J(U&weMTbnxFk7$72|=6~KR5N%r30YZU2`rA<DM zy+GZ9Co6^Yzv(lfpSJ@rS{!&hELH#n5RRNbWe4asn0uc8?}bXt?5R7fDA6j*slr%I zj;wbNI4Ft0>t!gLvY)g28{Iz8O|;ZIl7IK<l)f7qN=c%vRUfDJj;PuQ+OW^?M1nj2 zU`aRpY8p7(ato)`q2p>4w5#+`ENN@OJJ@R+SiSsxSi<L|>0|M8SDLBR%r{_S6OYHP z{#Yff2d+P*Ib9o!4Blrn&aRL&zhZe!U_K^nctWly;Igpxj;7n%Svk{oe8(z8xTwaC zIHwZxlw;keEHws?7aHuP)*X0gG*rV)ioUjQ%W`bQl%<t|Ro;)6{$%8_GV5ezT<us_ zZ&Tpu*OQI2f7pWV?oB^+@>YE3)pPpF5??BB3@y%agho2e?DUD7*U!)XXyZKhrThk9 zrhNSM{e$q~`IOeG`XOY*mGkX;#e0@_(~2Y}<$r3bj@>Sj&hCDF(%T^LN?U)cxs8w@ z^`~XqKP~REudaOsqym!0m5<nxck-LdMR*3PQ@oe#%8l)NWdG?aY6B7n)8kfM?;NDU zy1HsOuJ@%~+?R&<1qDf-T!Y=yI;*to8nbjj`h&1wU00*2pGVR%mADFexq_kT1=^Mi zAa*PkEKj1F2Qr<i48b)HK<0y%?a-7>VzQ!GVp*225M$_Iu1LTRoyliH=`v1NK{E+6 zd~=>Mqng#BK@b|)kAU9?Bt%H=6?M<6jmyhKis?}Ro$`X7fpO3bLXXncUT(&40+o~9 zj54B*87G5RpH)BPitc-9F#m<)Zu7h2a{?+Il)#ANpa5oOi@(j?H_G2&&UFKPqMhB7 zkJb`r4msBgAav9}?iGpK-U_CA_nIu<Pu{58xdW{kekpOjdj>^7ZCIa}Tr^nWRYQ(H z%>ga77ERrj26AHb70{PK`mbg>AR<S-0EZGRG@$Nml_JpumN3H|`7yWB0aATqLc&ZX zAW`!Jyc?X=TY0G#R&{Y%kNdXWgr7NYhk#sWh9a+*NgTl~)8p2naEBP;)af|EX`ILB z`f;OUy{J-^%_P`%;UqZf3taH=;TZj><4SEXeb3xyWr7c#IbpCX!N%z|V5!24e@)yE zC7oyYh5>JHnXV#UhMiE?%$hrrLi7vuVN39fn#5`jx5h4hEA6A&)IGc%V%pjBtJCH7 z<q)y&nuTZH^`EA<Jh1aJ^G$9zB^u`L<gs|Ha!nrG2|SwE7Wd$ASFmN=sp2d$>9X&u z_D!xkSDviZRo0nb@Q_<+++2Bua_9c=qr<u1Nn$hpSjmaKPmjrS!UFBw{|Op++$S;F z9NaH0*zj!q;q5<cRS*1rB@ee&jElL+kEweCm@*u8YpNl8+e!$JrND#DPj83>c{UOj zI@=`uIz+hoBwo!1=Sdzxx&G$rsVctEZoHyQC1udJ0l(=Z_(JcK0Cmkt^kHCC5p|$} zi7n-UHhY@H^MT`fN?f52l;Qiv;1#PVy}EX2GKNSb`)^CASeBw0AQgkK2bvYgOcrPj zA@bcWV{wMR3QI1)=wz5+)Zf+j#>}xXPw*R`ZXz>I89*nuK)kciF0cV)-Hl;3L>p&b z06&BTwwU1M;!?nvj%Cz+f3uWfG$Z!IpR@vT`uW<dm$&2=U_1O@WT|cD8dN!aeC-G_ zhqQf_c?Z$>Fgqb;KLsEP4AptE0O7V<7NGmN399{+dFhVO4NKcx9Y)22j&Ob*U-xDm zLqGrZ4_lX%(eR#>LJ-X&a~DD9_$=}VR)uOqSNlkxa#xsL8AUEMVIl{BKp-D;tWRB8 zp}jt*@WC5&c;(GZQBHRxaEj-(D-`=oKB*J<BPa5pcyXdzuF&<FDcxF5_hVB(x26bM z$9q5TA<L#x5_<Tl*F-$qi`d<!bd6}of-U8yjNuf8pa)0d%yTGDKliq^n)4oCxtynf z3sC5Y4q$9Ya5J1U@YIY_SK%Xn*bM#RhRhzNln_p7PQwo>&Jfnw*OQSWf{Tk>qKX{) zrQ=>A!47WTPE$3zQ%)(}5Jlc?eqMxq=O_NAGjl%nuCrKgnA_&pqVM15JRSZ4J1CVP zghC77;dVnPC(eKW@K4xKkSqPzb9ITlZoWS4cD!2`*Es*%M=nwIuz3)j*zK>LdA8No zRQPE~)H^wrr8RPwW)E3-4PUH^pq%Y)iN;!AnwYhZH}@i@jYKB$Hsmz_=+&@_x^W;t z;^)lXv8l}deMWDUFv--wi+We|m2PiU_pE-H^Ene&t($n2QdKskeaDgefp^!}0gjg^ ziA_LvSycfjM4_wgdds*9-|h=SH{(HAmox&;BOU8g-9`1lWh)M*)`x>Q-Ne%<m1|is z@jBLL<zO(_v*V*cdSeHyzXh(g*==VpJO?Fg#s(YOGB9&Bgx!L`V@Vh{L|`n%Eg`gl zml44rh?zhVXhj%=D9Azq<j}u|U{U&vrhEgD4FpUR=3osy6u^}^nklb@Ms2AG)`Oy1 ziipbJGj+L5OO<>{<Jf8Y2x@S~8iKFX^B{DK4)uWz*eAC|%@ItYTPENyTbML%-~7g6 z=XDX{(aG?RWR)Mj2WA2EsuVatlOT2AM-=z1yYe@P)X?lN4jVQGm5`P>=SfLEvH+8c zT@{={&|l)aq%6;XXF#~nJi(oRWD+AfZnjIV5hibiLXF)yiMZmZm3<`R5aCUl&TpfN zAWFs-;aF#0xPi>+??(Ki_sS8+bhwwY*rVe;)$F7q;1t-Ux&GAMN#8PU6mwO#Oy^#* zI?-{{5cu-Xe+t~39Q~kCW*%(-sPMMm+8wV!{@nH?FG89=;v+R=-C)R4Bqy?;^2|-j zu91jotEQ5^BEP@bK6BOH_M8pUZBt@b|D4?$jK9^zDwBQtMs8d^xaVtG)!osTh5h!j zdhVWUkxr`0Yz4bD>@ve#3|sg31E^%Z?Ly6+BUvv!6A?*GpNwaHBdsm%Np>&B_c@B7 zrWT46ue1(zE;N=z`FvY3Ao}=IECd~er!u0Q&yf_%w{{x2iu55S@jO0u>j^$5ruDBr z36SWwJSQUY0eNT*BTG4W(%t@;0YyJWXHM*1k5=c4Il>%P$kX$CZ@9*$`7)yRkfV-< z?Ns8(&FVVp(SbLwBU|$O#vpRF0Yu|-77)ln;<6>ZKtxMI)s`;|eP<lqI}F=Ch=T2K z&m4Q5cOh{N6^r7G(N?!<UJf_$YoC{vLO%sQvzz2)VnGx#I_taz5DyH3#l{|)MYd*L zjoAq3ztiRh1hk=Q+>mc=<YpjhV1_7TrSSA;*uVICL?s~;?OK2`mNQh2>gvyvOZ*`o z2=p$Ld>Us9R)$tQb4ATHq|BY(3A<&IHUkUBw4=!-v9E_=$2UE<bLM~#hAluCFX-l< zML5Ij+;ef|badO8FFo#L>ukddRd6_A1_-SI{<GH6h0CCeMM23~7YPvh&L<5(H^%=e z7XJ;LvT&Onpaq+Z*_U*!0*0$O*%SPi=2d#zvE7(tgxN#1eHSQ%B5RqsIr<Zv7jm!s zXn=pzP>Sjh_@HTcf1oK>sVX@BeavTJ%dN+I=6@UX5<RoG4sU%nFZls(>c__aIddLo zwM~~0s&Rn7z`4En_k4So$V6R-t~Ej9S~AXdodXg2g-0e#$YfZlBcL`6<qq}=4w7Dx zL__*vDp+C<n-4rdwu9YzJP8<(WE+5oZ6L@5itbi}?@!3#Lsf#;+pc0utNFEhr&ckQ zef@pdUYX?+mlJaHK0zmW8GHi>7Th|>6(T3(kv`q2e6zhrn_jH>!T!^!Lb2kfwZq(U zB-y#Hpp32pOV2&a#e509m_`Ni!|xy@!!VMLZf+|9KLwNoSDyfC)5F7E3&UBT@c3;j zzT`Vm&#jAt?v{niSVb;1aq5?oPPd;t(*Db=)2O?WWbo2g7NaHLc1vP1B_Mola!hkh zaG7RJ5P!*+oTn>YX>vS0x3@z9yhTG<BlG~#)URU)AeE*n3879%=?rcnt6}7_L4TX4 zfBGF-WualME+cONtj_>=sar*sW@KL`=+AVE-PS}_V`N}3<S`G<uz-6;7y>OM=s!w8 zsBch|z|VAVGy^&;$f3|y4HB0#WQ(8^Z)1FL^JxZ`kJ)1U&w7^8xNNXASlG<@WxMBd z!aOe3%8?$A1UyJ724*+Uwq0@rB=7~H_R{T2bIik@&y$c`ffX3Nv^%S&i=7#^-I#CI z5BAIYt`5)LQ}^9JyB59)-(U3c66k=ZY5-oc1N6j5vo2~E=rwLV!jC_tqko44*NmJ_ zId4%^)9JK2D$(G?XpUoLMkY;Th<55h`*XiX^dCpn_5o0fs8u7rf5!CY6Rw@8bFzeJ zl+C!R+@nz5D>BVQF&*3~xEj&UC-tt(4_%@5fUH{fgSiEFffL{jhw8Vc!=bp!N^SDd zocb7}5r2ZCKr?^72<*_gFry%|XnlDYSOeJ4fM7KO!D{SL<c$@$N0<%AtUIr^WrGRV zsV;YXzz5ThWXrS&@=N(popWe2bL|K_umrX^`C4aMQ?rV!uYT0+Jdxf}`0gv;fCf^^ z(&G?UgOWFphl2e<U}b3ddLE55{;lhM{Ntb2yM~?+T4t9CBePQrm|a3jmm14S#WDuF zzEPj(Tj<x$s`e}M*nSE1b!b6ev-~G_yg3`o-`M2kD-qQxLw!6d(SA^{s&Oy@|E_MX zrYa260{90fG7x&u*=y7^E(v;L2XgXeTJw>(Ah4wc15(3&{>Wt<+>j6FQI94}Wp!Nk zn_EQ-hF8z#OjI#cETEh-oQj!-@65H3HB*BK84ff1R2KTp3>_wy0U+KiSECI_Z{{$U z0SY^d%)n{|Hu5s__o2fK%#6yM-$3LdVyziOQ7|B~<YOU3bv`!2PbKGPU&}CG#0q7F zB5|P+`pV+qwz|JD#Jd15<43(;#_j5V6TTx?xc#MzB5$v$Yvi*aUl`~F-ue5Le#e0% zdaw+Hpjt*8-cPd%M{@v!nyfbXh*h-{aFPk$GiG1<f0Ab~aQUngaxshMzAE_afsmkc zvzN_WN2&QBLOzyP{2csjo0l80SzcyOjCLz<gNMtG8}Ds4(~ZBKd^cNBI3S^_m|*cq zPNw%>PbB}aV(tn~reA;9G*PQ#m-!+QE@jw07$8T?k{(Tokir5Soe_e@2k~%KX$kgs zqRU$=B`_eDi-$9lW%1DD1Tw%<Ou?fdO3^2C7-aq5p&j6IeU*R<IN=S{aZKAkK>tlU zIOIG|_sv&XzNme3%{^yu9b5$-_B&k?a5?iuh0tlT4|15qi?^Q8RrASQBpvH4JR^PY zw0$+zkrL{on7dA}rbi;V71^-{Cq6F^<6~D%&sN+l^QgXc*KB_3oa;8M25bUge_N++ z{!k9`6{_b}KMMw{hY-Sr)X6{Ilot!$O6sk2P}~dF^Y(&F2SEWkEkmj@9p}EGh^OUp zCMtmQkbn;H_(%uWe?t%yP^O@prOJlyHHX$LkfIPs0a+L@EASW<AAI|*MFAke*ya<g zPkAw7>MAha908em<Aob(?k`Q?KYs*p3w4Cz2<%rG&hnt807t-f-Y#Fj)y@F`{N4Q& zot3Hv0fMdzy4lR4=9FEDaeyWhgHF%HzEMY3xe1C4i0D+g@hjVy`$rR2*@tGEL%M`P z?A6o7I{&aOenJ`J8{e*WmN5!9xQGerv`^1a^UC(@l_?9-gPKmLbO-&fbfa=xizIPh z52`D@;uUYYGb`@d+?rA&CR(bM?RpEL7;y$&zuKOsI{I{*vUpfu5LaLL<y{2t1`bse zfo(DSxfoH|`h=8W_y-R`^uv_+Y-_<&aPGkobogh&!=ngpXFzC8bkPwgJT;uyp3n(# z^cfLoA~K|3gn!4rF0d}~b`if=_Y_>KrJ^rNF2?oPdd0@`W^7IE)wlv%#SZ%3Kt%Gr zRY*+4*nEX1XUHlQ*sQdu-@)?8Y^yXG4p*#yR37eh^U`fEp2q!+rJmVSnnMRt0MZB} zRUUSr<LchA6R6AYRxSEVonE>35msv6b=!ZRz+S%=pkRvf&=8H1NBm0O-?_N=<$UG} z0fRz3T(Tg_krX<nzn@ZiA@ziGgL+~O@i9O#heX8An21k(MawG)20$m(1+JqpmXr+e zu2lQfF@ABE*H9N+458i*afa`4H0S>8cJ?Cp>q%Xw3e*pJT%sbFr-C%m<Auw1`!%G2 zvnz-$paKVQz}SW{z=ov|h^-AK*MAcsL2VOks}z|LN*gtqsfuL*Tp6#J6`E-=#}JON zk|FDq5rcYfl++7_E||zdi0Frp{7Pdea~1WsI)Iwdr`4SXFP_vFapnI2J_Y)bEr};y z>@Qm|sG_1jW_<BROT@447+Mw<Hkz@BAb~k&3_1BU2dr-`{nAV62tI0tTgvJvGR~(B z3O=#6Rg5D=WD$%(hb<9)Qn-%yvPQu9s#FBmhHg0SRHbz$8GflfN>6+L79rH!@t$~T zRq_RtwTz@V;SsE96!<qDM^D@JTeCOoU|h*sk8b2?zu_tQHfP$>h`SU(>W2vxyzYj} zKH%uZ6?uNv+CTRyF>^ttQK`+@Ybh&MG51?`-gK&lHt-<mqB~57Y+optS8@7~^sP(2 zu*mU?uSC7O`{r{-!j82|c^=qFiM~pS!I8Ph;2F1$+PIySnk^wZ%h>OvcWoBqZB(zd zBa}~5H<WK9*U^iP&}0kUM1_ng(i)^CI#f8DM5(1i%eT6s@ndSm$iXxZGTzql0)Xgf zK|aE>b7Y^YxgC+aauy06IDQoBN~hvJ2gfK{XK+niRkS)%*+^!0T-`Mx@!gL{MM)d} zhwUzhuM9-UKtl{XNPvl+*lSTz-<eltjqZt~q~2)C!EN3)sjZGM2}9psOV0r3-f?@u z;m)PJ7-uBcr)$ZvvVf_Z1JrsDn3V1kVHb<imjZfxh8`4t%#xA-tYFo_?Jh`iq=$#j zzXM4qWUkWkzjfN*LJDxD%dV{%-`bz5#9mzmFJz7AQ0J%d!8KaHZwxN_87i5K^!LAB zk~Jx9(A1$lL$^BgdHlw1<67Hp3S>FRd|-@OAzPpJ4jONo=gM|`7mlt(y`KG4V}v~o z$Sv*qr|tL$fn5i|P})WRxVK5-QWl385q$k`2=I5_^62bOkbQ(3X^x4{mHgy6g;j%G zMxz8)Q+`@xL1Eg1UmbzV1L0ELD?b^0(?f7z_4T^MXbK;I@=Q-ll+UrPfbDk?dKg3N zekBq9Mam?@=UaaCPogE?%RuA6Xd{keM0VIsfihQ9f};@HYTKkfs_8Rd=QE>2%|iy( z{$#D1vs>XFAxBb=n;E8}8`TIL8cm!C+}Rjgvgj#Hp$WRXU8~nBH9K`Q`I1|XZ8rD@ zd&G{I#8u%?M<5{8@m6`bgq-ihoty%m8?FujcJk_4eQTJ#O31iDe^Fhxo)UMxD*8a0 z2`$`<??I)k)9k}xp2shD0q><b?#s0TI}SCPtr}@v6}XdgJgc}ClEnl44My2cT!and zJsWHwL9rwZ^i@3k!=?tap>rKNOaHpB@gNWZo`cPv{S_v-f~V+SQM!<ocj>s?DyGmA z*M9b)YonUD?)A+ackvIauM|goBVD1Y4Jny&7Pv1S@K`lrxC_CztC&;r*V+x*_&dxA zS+!RA{*kfmw;grz8L*`ZAkdgSNNa|1K0$+Y2U)d+_2u~sP~yE%{Kh-Ck=0NH9Y{Mr zEM&|mwUkF-j|8-#0QLvr$Q+k9OjZvwT(npt^xuW=zakWjEm$G0n|dI+SSu?CdD@st z80nEegw54Zc1;F^-(PJ~Xbj8pT~EwWo#A(NFb^>@8Y|a`fcgSpdGztsQ%^Qi_cG}i zy*XKx{RzqsNKZxtZo?HI%Wse=6DtLu9CFch=?^*tE_ZuLdOgmM{$h`NtJK&?v~9}c zh3|zeaMqJnHbv&r-MjzQGCo<qOOvn})}%dngIr5#t+t)*QYgS<$1R#eJ?(tcNe3!M zzvqWt3*ao(7N8Vepu(=-)W;dtE8<$i``{qb9wfjVeEQ(Ai7vXDwA|*-XNJ6`)<RrK z&Qd!1dOAg~Ibn!~{p?&hzqHxh^0fvBxi0g*1(rpD-Om6XM^=t#@i*9YPnPR`V4_KY z>t}dTi;jS>_)Li;Y>Q1ipo%-5svdDy<#pAO*msGo_WL+twh+7Sj=@rYBc9pOE9OYW zNE<*<+_Pzcbbh^9l3esG_2RzWZ+AEGWgn@kc-x)Y=_6^KD^hg=u0@mZBJ6(}0Y3=< zJ)npLy^c=6Ig2Otq1-BGTYm^Sybh!5N|XTZLe%-)K2CN~S1Whz`NQVJMVlFP#h&po z66k7QGxc~>@l3PSJ2L1h;O8R-SJ8Ju*ok-f!j4Gwjx3YCZ0d@X%<tWas4kD00ipze zUG5u4<q+AG&~}RLhwg1dSVZU@YC4A+AYyLG!}j>}+41QF<hK~hixQ8-#6QlP*$l34 z!#S^J#HZ2#d+taYsMD<Z1o#FSMn^DIKZJYWf+s6j!S|j;s$)Wz%+`-7+xfeT`WtAV zq{5|>$Y&UqD;r)dEZR1URm#LY8$5HCm?sOFzlQh}jMTax4^Fv4l{xG24x>cj*zV)0 z!0uv?zph`$_Af5odEH^MD@%EFF))JQ27M()x7TzE7FFq~<hOzc%%twR31l2op~X*p z31E9TYMfv?rN@5AwEFQoSy+Kr>s8E~|9_b?lE)>lagiR^OMUYA3H>!Dyl>8-qe1Gu zh)$f!v@-ky*Gr&vW<ygwHrrkQPCn{0hoKB!MQfjVQ=rLq?ekfak}zY9MZGpVO5$xP zQ%!wwyU4?05#oj~xdo$+y}h_EmqL1VAikhh5@rUP7pY&kOFcWZ>Q6?i0wL*5ioTSN zp-0XaP1w=%#~}9=$0E+@uN_<V5BEozn&zFkRad$162-^6!yQc6XD&ZZnXD09<6H6u z72)10#%Aq$&SL>Ug-PDq!m)1Or2@+!5AvMElA=n-WK8aylzO!Y+8+QR0yS5Acjz0! z7;V2;48>mFKs}Cc(h?wJ9RIx9F=w_TdB$-&*i&%$IS5(9emjx*K}dGXt|4Mlf5Rn9 zeL02@oH|v)bx&u*11j;9Eh^@7UDsxF{;-j6ur2DW(#@SHV2H7Y&I1^y#{&KEH&+N# z0VeI)5pg;<Ry^}cA^8e$WyPcy7_)Ke*eAMNZY@(nJC3IL#aa9|0;g5;q2;8JTo!|` z+zvWNCfsO$iq&R9b|^rC#_}dXon)FhfHoCMf1oaByk+VEAd6Ve)-VyB)4s>wE-<GZ zMz%ySL;&D(jlvk7m{GIvt;(Gs0RP>aLOB*t;+X!}grMhgjMD?+1>eSv{NKbDama!} z8g<LtnAb(Gfft@s!$SqTYSTGc+CvNyly^P)^A7h3yG6^`#8%V?&n#JReX$tIPV&M0 zC^vAQO@0;S@63TMmc#XdJM;O;E|!b4lXTU<34D@Ad<`wc5gdGt%F>Z?)@*&H@}KHH z2V%5n7`xVn?}E=&&`(~%><2UrAK!@u`~JdTFeU5wX9{f*yyBYD+@|+!oGd%cYd%jI z&&W}7WfFP_p2NiB4R?u8T`ulKoRud_wGRsVc%ER(m)+tFM|77TOQ?F1++L?m$vU(P zl`vy$(wdpc#i^s#W5=sAVtk5kYo-X0XSUIA*&xSUC@(8a4&1XBGsP~rMsy6lY2G7J zXdFpbel8*16RHwiT~6I}*uwneoq<;<{WlShC*&$aIVUYwh6Gfahr(5atR1$~@>9Ru zWqjR3i07b#Ci$o3DP=TikIAz&i!I2fq&pyY#;F=al;o4wUR+Ye&%MPyu_^Rfo4ZI? zo5NRJQUSIWW;N%q=cz)s+DL639Liq<l=I*F9nBIvRu~!df`85;!;9#P5A=_>_WivG zmU%&|Xt?;N+h7wk0m3rRrcg)wJ0VxLH!o@8@bY*ZyL)DO#<~8uRkZklDnqejVe#S6 z*?@Gv(n}Ew-QwHXfJOTw0=T_+J{7oj5STLuw5Wt?^S{9!My<{&(-#j-Y=d$e_`w># zS<NYH&(FBfW)iSR|NFRMO<xxLXN&<P(cCZ|WJM*j@^1j{M&K?uGd@=t`g;?TX>bcY zr*^QZwsle}WOn^qBW}ggB{V)iXQZ_Z7XpQ{bWzLsQ-J2l518(#_AitY$L5)R!liH4 zaZ1k0`F(Wog=`X9*Yhv~3(e3UB(MZ3^RbBUqBa8nk~f+@<<mGcu)@`78CV1ul}@Wa zEl+~SzOe!$nBw(Vg~u{72WB%JZNgsq()26)XTD=?;66Ly`Ta830dAr8iTj6+<vTWh zHkRNGPAL(VLjO46nVaF5YSJyW9HJv$L3m~N<x?+VtLpn4iy(P(>#fNG!W@WI6xVII z=ktC1i|T#GP5f?oFN)ML^(VEqE2}HsHNpZE(h(@yB9GJKG+V*;YN_D!6}mF8rVzP; z?JqR};uyoa7pc$`SGwp_d-?1nL1IFrTe5x!#bC#nV72tMI4hF+bAQK@u|wmp5Jprk zb8F^FFrcjtfWFe|5qPf7uL-w`?Ey7s&kA8xg3g6Jpj}|QPhuIX_ezw$0-jOK54%aM z3e6bg;Y#du=T?9Eb6*ZXcsL>5PoCV1dw)L0(qIlDwOJWCls`3hHYH*bYpW&YZz!DE zhAmYa@W=((4x%!Z8mo^)U!;l7=EeAa$kk)#F>Jr32(pjiCuexZEIbBWhX7|MVLYl{ z?L5nQ(kkXC85AIJGk|{HfOx<?VXkYK?IfeX-VYN5APtM_!5E;GbMwk`Z2uFCqTEc= ze=xzMHbAQtU}Fs+A<rWPS=)03Tu_PEDbc9m%@EZQ__6<=)7Z>}$@IVkuS|Dg7^8tz zD<k5wviovUatnwQ5Ax+o<lM0eV`M<J86Xlx1`97<DbKV963Kt~O$gCCg%QV3CUXE& zH9)1x%~hoongQok5u+=wKZ13P<<#r~{#{aaR)vKv{@p|u{Wamn49zG0JM{~aa<7$d z4e^^V1X%7J^y01f!*;S}GRgB57=?tV%yGUGs7cJup?gdD4!1pX<L(d*4h$1quZ8RF zY=&7+12d{~F~OPf<~*rxd70B@ZWk-9h^A7B9y#A0%Og&3?Jvd<gs$?!EAoz0a$dxc zFN#={`lfPlsE@qM;6dwJduZyo5$?Gd<vo(mnw8_f)h(A@kcj%;Y!>u8{uUoj2QtET z90mVet+_FH2+n!|8FXXf_1YP$N~DG1KM1u=Yk`Eu`+l@YuT}iumAJVrc(XNYvdR&{ zPt}<E*62#g56-nx(zV-?1*xwsgZMiFJE8dktc1r6A?OkSZvC+hiqtEu>g(G`#G1i0 z&M866{h1JLnF<F#wyq!NCN25qE^{v3m-fc|lQtr~E-}^|k}`P;KN(F&=SL>|CLO0H zh|n&!CpWyL3m>fhr!6v-^y<b49cJDpvJsmN4$g3)q;E2%78Nb1k+o98rOdnqZwALS zbx&(*OkguE_2;oP7xD#&eAFRpo=CVQy?79^g92}m3j(<=C~(<BY9Pi;1M)n`T&(GZ zS;^shC!rn5Mt01Px6x-NOh$Xkpl?9*J?75*%`($o$H=(ho6PuWPMCJ};vu<l07`+J z31~@-iVkIE=(q}#J<B{v1kFYQ*O?1SE!87wzz7z62t0cEN?{-BO1gPg^}aR&TIsyS z49&NEIqx3IK|WJR@U*wF$&*4oM*ht;yp!Du?(mgDrykSGT!M*~=~V+mU%wFivMR#u z>1s<gi%n?nfyL1>73trz%UXZf?$9KD%<$oxj3o;}c+y`Otp2c+{F^xA6gtXR2`vXX z6py;)?sPHU6hkN{uu(G2**{C$p$>jTf3FW~%@VLGP)ie!kZ;E6g*6mxi%0arm*e*e z-F#8D^R^c{bn~`lt4DpCMoZ5I?zNXb|J%AX&H7bBR9);@&LhC}*lW(f$|cOipXXvN zY?r)DVOc32K$i|bp!%I_Q;HPwLqE%pTrd@VPU7mKMs>Ou*X^3RY|Gir<103+{mL^y z5;zP{n+rdJB_Pc9PK)ex;!|uJk7eWFLDjx7MOS+62l~PM*T885$}GUP6#8;&d7<<9 zsB0nXKS<yo>qKRnmGqz9mthyh_qA(eXwve)+%=^4t;Ggg{9V7e1)KU$cgv8AO~5*} z)AEuZVidc_M8Od8*>n4neY`iO*WvaVdQ%QCu}M>g#{gb3CiBSS{4y_iL5dq%b5a)o z;0B$~jK$bGwCPhepeX|l7T}kPcBUQFlZN~R{%;@xp=fzdB%tU+$&PUc6`F7$Q0Z?J zB2=cNHZEC+7sx^XG^S%Jh^q~ZD9(!z7p#r}tHfYtdIW3fe;u&in9!j+&EQ2w>aw@n z4mcSxj$3WmutOcW$clZSS@Bu7ilD|z&GV#3i$}#hYgaoq*P=kuN<F0y$AvcVoUo36 z#N05!$^209Za9i9yj5csnRSNQIEGAGbe13~cA!?7lTpAm)zTh6ECBYl?wKh|_*Bwk z8nAjhtW{k)rZBVm9yuB3S^cjhX*xV*CQ3YMrbVTM?R17;cO~%Z9Y0hA-+lXR4pIGt z=ak8*OM~d7r-Sj&cI_)vj_@-=OFjPH9Z;T@An~F=qu=Z*!S&1A)9~ldyxW9Ty|`?z zeKjuY%UZFyIUyQ(x0VREx@CtNeOd&p_&yQ{ncudN0C?#*%r^c$MJKbyE8eSvM|1r= z*KC!K-)yAUM^L*_esPhUtD~e0za1jfoK%`bAJXn5Y`R*6$GG=K!N_H4MXs_n<m6<& zowT_8Kd9kZQhH9_g0V2iIlWtTNruIv2_Oa^o_YARIfH9;U}++<nJPPYvAUvU#9-|w zffh=FQFET!3aobR%Gi0pAFE1}w_a*A>OWRUIlcHZWlsoA8|B@_GgyuAmHWe1iglNC zN(DR<njNm<P9Cs-<eUWGM}Rrzz2J+5Vh|!=+NCraj2mTbB5SH}r4VmEZ_48MFsBPv zJirbzR0t)f5*xRNJ^ls^n++163t64Hn_;$r|KWbJegWm24Ou40RIL3Bh*?%o$byrY z!*n|F;fz&5*$xzry)y;~>J~uAK{Xxv><v$i{Nd-hwY6joz^MC6uLFo0^MVz$z&ZVl z0g_9=&%JW2E-iGZy{w<I@Tu$lY8efWZ0~f3tSW0MME)*0fviUT-ZO;oHxPVj)Q(!n z$jORs%76TGIb+g--OIR1ez>)&d1!#<pE7AN4K|5~y^#Q|+%Z61MbylN(6x&q7f5k5 zpshG8F!{B#c@b>w%=5`4{BU=9*Q8EzoX43~(oZKyby;-5lg#~{l9(jEU}UOwscUmu zB-i&`pE~^(1M@(F@!3~)Le|k*+mK!<f=;+Hm2bnFaF0^2eLfv*Le@fGK4W;i(d@RU zjlcdQP4VE|Ly=+e8g5~OsKfI(*$I!f`LkCI57Xhr{5N_C5Ml`o0ixX8wS0dWCtAaj za=7aTF(LNDyQK=QU>7fV3x0fH<v~iT=02;W&e>W0vuoj!&-tPJq$7iy%XY<@uTrYd zttS`#m|YHc@{w?_zd&YF=~zAql1q3qE+QeqRY#u#RKMp*McH2oYkQWu)_?x`!!}DF z^c^S;qN$p9jhsl7Ckavu%FBY*C%-IM2S^N5A4s7l{8ApqP4sNl`8^P-U7;>w_Pb_V zQhZjjuW<GB`FZgr{`&XnARnd=c%?$>VMtg-66?zYJwo2Xv;AcC#Iv?1<M+%M9V(zm zX%hm4C?Q6z`EMfPlD*mtKo*2zjInUmbO6@qn<4Hbh@5n|`dMhmX5Knu;*%_KFcg>@ z<RFmPB09FSh{YQOAt>+|%_OU)gF|Jy@1j3L)~WjPj2@ARFKsBxj%Tv*#+EYV{;c5$ z+(UyL8$s5D?Z2ur#ZWBUe5k2vCh7__vajWe5PeGX@r}RN^+3W`Y~#?X+^h_jb~Uiv z1h!9v<Df8S6A!8%hn*0TQ=z;$)17t5vANV6UthDrj_j=Ha{{#*zu1J@S2MQ&@+2QE z#zJHqD?!E6)ug)8>{BKW0Ql!2kSaHpx{x}PLjz4wj`{W6l_v7%&2~nJE4Ua$06@Wf zG%@E2QH!uIKHB_@aoo}Nri5w}L+J<9%#+VIXGLjQ+$EYsz@76Z<F8*~cf>u?Blwv` zey*)+-y<PaOS!MOb$iydaW5hH0*7-cYIk8ohrO-DJOLdPZf?-G-VGs@R*Z1G?6)LN z>ddvwowuw!|4ww&sqm_qNG##YxzO&a<-uXcxqoWfF=L5b+?NhY{J;{b_s7)Yce*u) znqGXU_*y9;yo!G=z<%P2-Q&?MN%GvAU<gb`Y7Wq)8oiz}YTG`tNw05yu&ryl>)XI9 zu~ma#HG|qu((4a_fBfSbk)B8PA5`F{9IS@ZNYX9kjYF2pvs14owR=XcS;X)SoIV)t zjNjSi5t?$|^2$)~4sR>`IMMfq2+cc?{-N~_KiXpk1&C{4slYHWL63->Gy$U(CTG*z z_nCmyZR=Oco{B&R^KxjGjebUuF)o(@8B3ZG9>5L`b^wUu8O9L6X%reNKx4-O9+~TI zrZ{7RM*J6?WGJLISiqoTHpDUc?aY+P#52Jj&@AQ<xK9b__mKXPpLJ0cNQfDo0MyK6 zK+h9IVdeml$j`h441V(EEUi=o9I6IyDBI;-BC5FY&A#SkgL%?Z1d+V(aLj%iH$sIF zs%d5`L`Wdmor{1=Lr)bdVLf-OZ|<Txd@=uQeaeS7`wptaNzPh#SJnJ~Wy%HQ%66ic zaOpBQ-HCbF_lGS9M_CiZdE_4&j_4rn>&^5l^%E&q2_Vi~gtV9dKSia|%2UM(bu+|Z zJMM+gcVx<&S?|vNk@dKFYs|-HnMGZ06OUi=FzFi_@O`TC2(Iuxob_|(lD@TIJFZi* zdvsFWH)ov;YRc@3Y0A~i$*QW4F6B@;^z9>L7Qu*12djKZ6FsCyUZ3l&0i8LKUA&ht zvNm5k4%1)f_xbG<@{AamkXXQdwK{CxNbcJ~-)#`E`uP#}M+ejEOFiS3uCt0{M~VSQ zz0lONDI^fh%nHX%#aRMNB=8OAlZoS-gS=$5u&Ib8gDFLN%-SJO_)x_OsA++%uqC-# zTF)t;x69GQ&0B~CW9zEAY7NTFBKx#Rs<Bo-8mpX>RoK_K*X^5V3NFgefQv`zatU^B zv}T$#Pdv!k`sm;J^1C-7BF!&27pX(Ym(?lqa=ECZ3`gs_>R|4`4ivQ!vf;m@4Z*e& zEX6M@<S;lt&}E+MjPeR$KF}_b)jBd4gNzLdT=w9E0tgXS4gVito(1kD$bc{cKTIyU z7`A|)g@r+7oH<YP-ywrN_BrNB$iGp!u}g>ULOVf@%P9TROx7CXO9ql&4hYMVW`IkA zq^V~8%11<}^nl+`EqxqN$AqgIp!HnoC7>WFG15bNq8#p$wNsuTc)(}tLl>O*Ha{-9 zybNp6lH<=NdWZZwQ({4;l+D<uQC59AlKLth*;<VOAkoONxG}G;0VimpxkFFOfB4I; z>AP9dmEyvqL#jDFGp4cF+lh+4;_b%KfdsbqWL>s{;`eCZa<#Y28J>QdJM7Y$eA+C{ z`nOMdX1|<e>@As5d9$!5zii>=R`Cxo1h3lfO*xm(o^3ObNaT8+VM~@2@d#RZO+Nj4 zTtCu=c*)?ICuHF4P*^j<U#jP25@Lj&@hn5?%wcye)9e%4RuMMCd*YXBf=<1s?C_Y1 z#%7+iIosqL<b<~g$JW1Th|t`(H$rZaoj{|lCzL*Er8(wN&Bo@=>O{ILb@e(1nR5Ym zSAeQSc%x8&=vBNvvF0>9g129P;B!(Id+PF@#m|09!h)3~iY@ZHc;rl1%($;A$$3_c z7CcD9$9erzOKw}&bEeDcjy=K<#yEvFAt&+q_m!U&WJUV0KMW3v<BHcx^%}h*!I7ua zxU&$!5q)zl)6_MLE0}4HRt$7Jz|#62E=`p~bsb)@P%tj1h&$X0Zj}M$TviKYWzcrX z2fQ%QpKu>s?qME>WNoFvI-jW@+E58?#24xW6a*mZ{<_RUzuuTvfU`Y+s~lpRoJ=e$ z;W36^Rw>t@KvNQ9qGDq3(GiTB5b5bRn3bLIrF_Mvxl}={>Dn)RoKF|!!uR|S%9F4P z!Gb=!CdKwxwCi%Xj^7X9cx6oRLd6<k99Fw7tn;tKZN@FzW`EMpNrNM$fh2t6ddRw~ z$cNM#fS^P#z*>B+ip=3kQhtwP#cfmO`3>r-L@d`DK{|Y}QKu7lu3UHz^I3nZ#{C=9 zar+)2=3}FoN3YBI8yw0vnuvUpT8+TnT%Ob4z+W|ocvSWv{L+ha{ELcSVDS%wZ=2J; z|JlqI9dqQ_sDoa4-j}t6V=-~L^E%+lAW|yV=hrFnxS{J;F4t4t(MNkA_|d@;IkLO- zvZhElQlPOj&k~;_+Fglx=d)X-^z-<-V9s+99NC+%{!H1GG8IaV_Ah)#BYljH?zG*< zvo$M6L8~BS4z`k;+5LVfvRkWL@<X9wn782C9MBR%k;gay3iWahc&};-wVocmw%ya4 z{>;2)p41395u+k|F!ZCfku#X6ab?Ub$$nP5q10)yaoqBm=h=QRwb*uv45LK8Nn2I! zIgfN()sk3X2L!$-UF70te4GJve2m)z+QEV2PYhQ;=p%{u(8fRs#+37$03yZ52z3)> zcm+2h4=ndz_FlgUOws-qd@T%?BSXp0y!Xst<T4W(gIWG}&S2GC#?_IdjQb;yhh+d% zLYeF4zqK13gpEOfBMcV?xvetNS&%n_%F9ZRVPLZkq8GLQSeVdFs0ja+M!<Gwsmo?V zz|PG9ZY}Yp(=!g<m@j@OE#f~8SGk5v6GCHSzzI=q;}&#tKSF#h4#vNzyO{mU3{1J8 z11&K!JsBbV#tQFNqm#J)VJRg9Ilnz-ePZFDHy!y4kb>ywt-vloM089do%;3<+tGZT zKWr*-^N&Np7;}Lp(Xu#Di3gK)&<xERBe-s>U+SXIhVbOhf_pvzUMJN?uZV|)#kEBJ zjXo~JIm`t;G+cD#$F=l1;IB<<bAtuka;?dtJG~(Ko|RixoIKg`V(^ZV_G|Mv<#MIA zulwbc^WIzJM(PCK`CPJ)Dc;CGrqGt8;nMw76!H~t0DI<@ExAiMF15n3h28n)_&l0K zgOYYjjo=R%didovmphjAv%UWLJ%Q^(SfU_)H3zy(Qu^!1{ISa+vqD`>DF-UW)`Qm0 zkG~1?Ir%B)yYS*74>(~5<v+$yVbqT4P1#lKy2g3QntpjeWPNLm;6LwUDU~x6L$Ea1 zr4n3uMH4AahfS&QI=<-u$d3ai4?E{Gyq-7WWAh~tT-*9R`mj!9b*yxCQ-++c@Mgt^ znh%97=!t?5`>QCtSAwBdr3*SIJ%2ZciC^h{a25nqC;t2XM!WUUfcT$x+qnl9L#qUQ zH4@X<g~7wUFbsz3O@K7?m)FQNhles2<E--kN+lrhY-bT4#kXx`j5z-*&@462Ml+dS zAig4HXp`7(&<#@FwR7FjT}TE4?JxO<rQt^j90^N=&fRQ8D=6C2J#V3VI<Ta>^kQ7+ zqtlDOQ^I3Dc48;ZQ*b)B!{Qw^)^qb-r$LToNnTuL;4)vMZR%+;*sX6qi>>ZK2BkVb zm#wN^4mHyPz>>qOiW4Nc$TdEQhjtG5zBH|Jja8q<zlXQhG!uPNQeE@NizNNdHzKPP z`*)J~cEO=<*D0CkMugm2#-y3{G7gm=&AphfdYzK;eCylH_!GQv;-<Tllz@!*u&^+b zVYG->0bBMxyVN+D&b5*W0LG%m28eRI%4~Bx*vtuP=egsx^ba_Xn;v!UgIBnb6*9%Z zm4FNMI0#F0n^|Eml;LfE<eULB#xH7)Tb`llhf}-6vlnprNBrH%UN!Zv8j5dmE(iI= zj)y1MCan9@@|NMZOKW{>T0mDq(;l+$jNmouX~`hpfiZeO@RbH!pMQ=|NK6~-!e`Ro zPNl5a_~91>X?Dm-y}QfrqEmp#DL68zNhR)A|DIv<(ni_>Y|<=+cK@H%E>TKK!i7W; zgK?~~o#zz~z=8^>UYlK}`8(E30(vUEB|X2x4kLCXH9aHt20RJ2%e6ZXs8<&9h|Rbg zAm$Fs!8R#R?0(no*hUD>)n5K=5_^3F1%N+>SslX+SUf^5Cx_`_5_M1gT$l@pHOMo8 zDc@pBX#VzWdK))AjMQavWa>f~hwV2wJ}i$@7F;dvo2#5BbfXwR;!w0PYVZG;-{7_^ zX#I@A0v-HCOgcT3LYW&Ec+l8NR7cebzctwJfp-E+_L5*Jtw2#UM&-!m<jGFynf9DN zYgb|tR}3;ccyX4b5e9HhE=gpAr7fA;?;K&7FGOU18@|wMZxzUMOCpQSt0=(`noneE z(ZgX*+M^^1+A8LKHzzH~YPBnS(t>Z@1vp^UOz=2=a)~j?6(H*eio#M;JW6(-QZO0P zoihm&wIX8sPv?g{-H%XD<0^S)?xODw^q1W+wta-k=mPr~qiGE};(Q=C)bmuq6eMw1 z!-f%Z)@3lbqmW0cPbF`xON99A{cp2keseuaE{x!jNnV7Qk8b#tEnJS`ljxsoal?Mc z3_y=BIPCU2ye?0B-XhTplkT~9um|^5tJkNl<|0i|?saQgEZ&W4Ai5UzqyN+#qG~Z_ z{1I3)wcXTy^8G*nhZn3O^pG~EJHPZW5zq<4gixm-ULn-p1E6>9*`BGC=S9!&yX;Lh zpvy_j6?Qp%UMxD$_`afk-lo*kGzx#Wjp)@CguPV=sPa>UCA~|VyufaHgmxjJB(xoD z0#-3!yzr~JC=X}*8K)h^j+@(4fHE}B9@Nl4L)rek5|rjl8$4z)r+ITKc>K0N_Y#i- zO+X%XO4m}wEa(jiW^5Fk7v7n_D^MG}Mw<}}j10(>Be2pE0HJ|5DC;^RYxZDve1Ktl zgmEW^5FP``VL{*=2WKVZ5&!(lC5u(TnJW}lNdE_;WKnw<3L`+c1%f$^Gh`5r{Aj;K zsHrr9{N(_{!KR-l75!OqG#cAl?MV$rQrreiXp`ZQ)0C&{c9V7OGWUZrhk`lIt82w3 zl#{hQVO)zaDLMXHddUy@Y}8kL0jw=$QQRoGbh?HIIkFE(y2h#jC=nGNvKGhlhi&x_ zTP^0|oHbp0YaD%!6kUP^+v!D;L5CN<XOHD!Z+dFi4zcsbVrH*J&S9)XPOHRaoNU;+ zNxfR#;GfGcuBzkWKA4(6Fn$^+^WC=s?c-uH)eX)CCTe{qYhd`Ner*NL_OWQMGs!rV zl2uBgFdWS;go>W6&{NtnZj!mJZ=$5df1WGUTHN?S!)?3f3IVeqQHS4HfFU}#IjyjV znb;Yak&wNlqjS=<sl_5r17ziq)C9VUc2S0U!mr<rVrj5d<=Kx$Yj=XvW8`Z^K2#mK z@aZxsO36MK@q}Dav8k2v2|rxAFc5spuOsb>zIQ4eT@G~mLZEk2OYQLE<0o6*&2;9} z35!x_m&t!idP6%~W4|7vWB@?_$Cy046gF(R-tm3oa=1&ftU1-oiRiPKnb>6C>7&qt z*a3JIj`qEXXnOL;1v>iUWN4BC`VX5`wPWjC^$%ZO`{{wL#ZElkF_8bBAM_Ap^?^g6 zAi>!Wauaff3I0GNvqAO-XWxWI)0B4N;3V`YOnbGR7kK7Er|TH73L@mA5unyWB%ZJ| z059i2(>9nO0I0$XK#{|Sc0pSiZnUgW1=pNW%)V0^3Q%C$nN!T%0Rnb1(`Eze1EJyo zr9dVzoM|D-TqiQ+I2)TBh*ScIWk_8V3iTEQ8+Z-WFM$6+jg1iyV|VQMq7&F(IL>ZA zwM<I!6BQS%_d|Xumuh{K=r;xv*rbkFL-{HI2au)A?47Ek$$JjkUApd~i(1SDM~_eH zajw3#kO$@%ar-ANCuiH}=Wc`X<spS{W!pFWYeOLVCeb+DYW5;WBFFJFf-48qK?oP% z%@)=%+3Uru<oUu4al}2}ZrNVv+pR5aucjT)9S1Zx<R0OEJPLy4T^XUgJSB89nv*|# zZ-3n0zFu^(ur*nAyUDA>$=`t&lfhkU9e9=Yk2$R*7vt7If~i&Gv4lid6SZI2&bbyJ z6XUn{I>T@1<;O?f`Al%(6v6;x(Y{i_HPcnAYW!y*CS@8ELrs_|>#STh0H?;#PSU3& zyqaj09;7nAP4-y3wlB$za-=MQX}#*WIefz%K?Cx|1HZ27ZP)E;N#Pw`(+n!?`9_#- z)Ul6Pgu%91p3zlFPZL8Nh}0p(y2F;A+>1<D+v{1ki6*-%rL#uxR`7Rokr_cs<;~Z# zv_UV-mp5`N`5iK6LI?5M`&J0c7FS1U&lf~Kyzaw{wgHz;k7~O%urH`CU6%C!GQ(vy z44J2%6R6Dv3&C7ja77s;ucr(L3$p38?tCyy+r>fvG{9%UvjT>Td*F7<vHavx?)o2j zeBEgf^}JIA+_z_}Sr`o>h$2?ndpcaDz5%?j24WV(SeG2Pe+wW7fuM}K$AT08f{~2L zdPA+nT*yEhA=|$bI7`>X`YlNKA)=$^e8%Wrvw=na+pL+T3_SQ46qSJF0r<I0M-V8D z8od^1B$~C>438xDVghJdy148)y8Gx_aU;%m%b>Ay-P83vh2z=B6x(p*<F(-Z!EKS9 zT$9bKnK0c&k~`H7TyS}f>?f(uankNPAbWG1fF_o{`3?4=$h_u4&2qR;WG22zM`St3 z%a61iLobh?T^m^3T7FqUFb>|m04sEi7FNzx?f#yx{8CS|k8DuoPszFn`o{akC#$p7 z_@|ZgK3btan;i1(es%0y2~XI0l<{pUv5DRB#Jv~Od40g9gBx|RGiB7pUyXNR6;Rz( z^?uss>)q^;%gc5<e^Y!S17>~IsY2%i>NYNS<qF}|BS|kv<n05VszZdm$zC0I=|Aow zL#x+(?VBCsqB?w4twy*yUx<DnrKxP4JoeFY@5pS&a)63+eU(qznt@&L0X@lgQjv?& zQ`S?KWwW<N%&7{pizB`g?IG;^yTJLA;{Xup@Gv(4-*f+VOkWLGbJCh9b(C*fMstzW zc=DV_--nthK?=<*p+vl^yV|Lh`l#ys1tqoqM|?jm=ki^hMLN{4VgX-D1-q>0)9m!F z?7CN1&mT6vD|doU;(KA8Q+1;Wz_ZAxdJ)Z7zGX>|0K21!ml3W;&mmij3qUKZt^<LF zfK-b?urKDA-@pZ~cL(RUfMXQTn{sTKBu9|wRJ~e3Q8i|~?f>Yq{~xm61Rm-=>K|8< zLfm4?u8?I^vPH5K*|Ur>rtDE-Bx|xuE^2JaPEp1%j4>(u9@&x>d)BNqWZ$>x|M`x( z&-46$uX|s&@-ph?%=w=4-VT7qSNTApz_<)`?P=jHAo}Y}*&oux>e`P<P^vW0#zfc# zV(IpFmp`#d|JV1uSC$}tb}SPhJDkg@DP<fjPt4qyF3OIai#bOd71GKbqe=;odE2WI zY~$h-KuE;IpCl@(?)Y<%nKlwt$L?zNZuTanub%(z0nTP@?GfML=yH^<qVZQm?M*{I z21BS_7KZO06(&e0%&Pu<un(VP+*Yew`(_0GR{w9m6wn6!GG29_X=T@XUKEU*qwCPP z2|A{<C-HtEMqVRMUnRj;?!!K#H=CMSs3BcDg}N+LCUMS0PMBZ|%BwRe)==WB{x#R< z#`hRgP5RB{&V0J?3t^J`^PuA^)yF0*l?HGWry0i`yt2vyEb}q@%N)kL<HgcrCof}g zMbQcNDvBn?Dj3#F$an$-IAZ)Sc;GWIiBiikB;}e_bl^X|@f*+mXRQKmy)?v<b7NNC znH{$~Z26n+VX;h(cl5B4D?QULyz?Bx<Z~o>ai5j*Vp{_+5QU#09-A1DOapT8Znj|X z&<=IGE$Ytd^bI7MgWIt3v)AOnz27`gqCGXs8%MW)(|yYrgT0>R(Aw-B56hJD6N3;Q zzOmZPeS<+|PE*yAyLRYoio((6Re_G`dGIv1NTvcOExfLpC;ztfn$y%{v~zdY{j~=T zkF4vxh8tjmuqFn>XekuX>c$58cY_`OxyLmEr&nHnbsiHqUkGXj*urvo@JPUd(Bd<k zl)+;k;!tSXG;qPEBNNbksc2zt9&iAw$zp|27!4hSc(FGy?k(R41ULco0W7#C+>alL zi-Fs)xuM!w{Q=@$au={-bp)&(n75%P{onkIy^{Yk&Eoj-1k>Ze%fY9Bx5J+=`Bxpe zw}AgoVk-m_WzTZ8E8=ed5TupuA8;Ig!A6q-xa|Z{=7p6xusd2{o1P>e+sNVn{7;F* zhtIw@7(YrObkr~Wk$Pk!V+}H&?t9VoAon}8Ar%ELWAgk^jyx;@3S`#}hoCWY(YI*a z#=}5xct!OWQ%-IW2|VXP!a(!RjTiE}%R9sgOG&EQ(EttKFdWoYOIOKkV5u^43XOY} z%MRD{1B}dAG3ge(EH`<j-H@4MD#i7|ehuL}N6>nANa(vrwNQ%jFO5r4*Ld8&BOSh* z6t3hP?=NP!BDAx5J55<kB3M5&-mT>&FK_qzWd0(OAgjjt%A+Buw_&*i!dh%coFoKM zV*DjR7oE!O4c~DTe-_YSWjKadE^+$otlHbf4bl;GVZNPnZs?-T{^8Zr0`(e!@jDl~ zO@Grh^vw1$N#Hh~c&AF%lU$6GZz=i+Q4dHo2i?&N@%zqMr=)cXv4O5lFJ?{$nipJP zR|5jbVSz+NVqWrFrHnu0M#R0KA3ZWVGmE{~d0eIhW(9s&1U>2XiU7!@P4CBw2V3>H z{%T46O$6|r1a*~r$Lz{jPhRg8@;oM4x`A##?KN{kYMXnTee~urZ(Uxmg3U4)ydFvb zZvyhO;x{ph;)f1E7h+8eK%i+kFG{B86-3r$;y#UHqe1or>Y}DMM*>esI#}6@(}8>u znmB>i5P~+LbF#px0K&5zfMx`C@YPAIuK0g30{@ZTe<c@i>GTAs)dCt(Fbh1?|5P$m zYk!itu72=^*vbD&m<CtUI`01j6#XZj{4*!0wP7K&;14iL>(qaPHL&44<v?$qi^Q8$ zO_3aL?c#ODs$9nU@AgJJwQ#-G7yo%gbHpna+`!!nF)*PRW?~%`rtpzFgJ|@<k)L_u zoD)x-25Y#3S`@9pK~|mK&+|ni>p}H-81?nOHCWe<iNK=0>^Sus6}5Cc3BZ?!YBH<U z5!<bxZJ2NMh7SXVQLeuAOBZF`ah&9+If%kLk4T_?jw9;`FD@BX`k|glOX*)})Yeq& zJaEk?=RN46^djPlsc&)|v+NlPjWwK<2YkH7g;~b?iLsR-O>m8AxOq$*jHwiVJ<DyW zi;v-=NvUpNFUN$jLZ(SwyG&3q&u;GdmCDE8djXi~=nvc;C#Q&Z^HkaRXOZ+25Hx*% zUuxCZ;6CLmgqW3Bv@_j+=Jz*l)*jT)6`%W8GTxL=dXum0W{Wx*KAe8R(B7;X>KgP` zzp`OrSSXV5>1%Q(=XfeeVgs-Tw<A;oz%zm#u6>iswh%MM%U{B^6B?*66H#jV+*f<# zQ#spF77F{m-*igt{-rr?ZZW<qQA#f!)%;sKd3J!BLSD-E3F=nu+>w~dRh>|FTajBG zsh5d4d{w#KSLfz)Zu_~51X`u)LyrE03&5V_WkH3pUgExKsN4SZX5I-3?L5xY*RaDE zr-*SNs739UtA??A5EB6ys-YI!VZ#p>1dnqXWlig++HTR9%72QAz#;CdCQ$7_*bp4} zC;LI^IT~T4{{@G9omJxh1!FJxZ6ZMEkytb4an4?Q{fh+b;R=5drT<lZFdi~3I~&R6 z4k%a}P!GxzoD;cByZSAjUk*D0KA`#0BUmj_4thTTDqaR0NdcYt6}{-eM;D$mIbX~0 zA`Is$Z1rTPgqG_rk|Pfte68<|b3I~E6-sCpj?p!PY((iqXah5TH4Dnti7hcJrr5Kj zd6x@gaYv<i_BS01AQ$<>)~N{;vvoFLVXRQaYvlqtLLHR2h+Nd7YB#;0Zc^21lsjrC zgxI#brxi1X4FU4mFb^T0&&TC%veF6Wv)m_6t5~cN;W90`&AL&opWxa(`O$DuB@YAi z0pzswdtN3RE`?mReFhZ$=8s1%`R9F$90zbbBgbwQOP4WwqzU#Q#?8Q=AD+vXr~Qcy zc4@T{jfhLV9?c^gQ>uDa2Drv|-aD`4`1rf^Lw<0F9pRuct5uJUDA5Iyic2M^SsOhm z@`VtpiUL8hYxgCp?aI>BtDx0{m5jP0cE2i0zwx|+1d@)GZUGB^`khI{Pj1Hkl3&mb zR?M$E`U3ji?aWj^T?X%RXdaM_Z{p%25XhCax87FPsi=hX>UnH3?F23g&i35X%8CNu zN)Py(V^`e{-$Z{{W89VCU;VkpIJv(j4Cn!4{H(VoYCjZafnD`Co#6sG73@||SDU}| z_E;b0;XfA9DN-$5IE1}_wYk{Tr5f>rIn@b52$5ZeJ-CznMPUC)P-y73hc+hwgo3@Q zfTjr#{^o%)chSvn5PSs%SV#dnkdPwPkwS}Eha#?EQ0CBHpUakxyag@Yr|2S0{*pk4 z7)f;dIuhgP77_76cxkX((R%D2*8^dq3ju&&OdgNy0x$e4{-AZsKS5c4q(sn%K#&VJ zC@diF{i9{ylT12VbUdW1BhY3D5XW@{8aHr4XB+99?_m^ERA#SuF(x&hetkPd3Wy2< z_H~uAU9p0l6vZ2!xN<Fq2tqUBbPSPLsA5mf1595bW@svO#uAnm_?-py+*O-=cjH#j zn5BI078>szGEb?U>%dqqE~z}K$iNCLX{^kz16gN`EP3-#19jCmI$H$*`UN6YD%-p2 zXaG?mMX#B(xHUSwf1f>~Tgv`p5_aDeCwFl4Idb~;-Ofn!CQNOj(HQv*%FKw7<NN+E zIf750Gr``-81R0Tq~~}z;dX_tGf_1O>&v?GYX`hX0ix0N7#D0r3_l}%c^37>znD!I z)$AMCtt>9MiJp3?(lb>H08|Gh9w4P~HZ!Cabpj@CS(RgVd4+uLaYiw+ShA{C_pKwf zAmwEL>Y%?$kAP<HSTZjQc9*f&U)^qOp5>?8`)}Xe(Mts_Q6ZR^E1O1jkO2~Et-4Y1 z(BxI~V>jC4Lelu9bDwdaw6~aco-Y1-MM=v$q$p~OdvsOfQ<8MXoSgp)yQPsgzT7Jj zXMBP}1NOPTTbU78r96eHA(j-k(d|i2lN({TSK9*&7u-s{wNFuxIdyvj(?ixSMp{}* z+eg<HL_mqoXsb{N19LqVI3*MaL{%?>jNB0Z39kVg5jge^&`(T!$P^*3dM`v409TOp z5cnxNUj2<Kcqw!cz^&QRcVeLkD=2749;igHQhg|_+RIL*THSjM`rs4+h=K*sD^?dS z%1P6sgHHv4jt+qRZq{{BkUM{}i{o!5#{UrN*$U$n1b7jcU{^p-{*zMlhZBHqm@$dF zUT&w2B#Le{5Fkkze#Q<|Dfl-Txz}Q`@Jo+a{4kR*Dh_wgG*Qnj688OM@Ghqp05_EP zy14jHS2yFY8fW!j_e~wCQO`Yd9v!%YT?+~eTKsX=*Q$1XWn^7n3k<5(>rS~F34p&e zZlG3x6TW;D>!qVHyQ5Yl!fqe%w4{)afreqa`lErQ`vNm8O$W<i#Oras4=d8VA!Rb; zRSdu??0NAAp?8_|x1+A>9OA)9le(aNL8dg-?pa$ZJ6<Jouo-_nlGnqqju{)4l%tDi z<swQPAJ<dTKo93Fb@j(yL53KJ9SH(}>HohHtvSG9G>JAL(6cJM@astw(|qcb_-USu z{W(Q;EJVRIGD(Ha%F>#W>UqxNjhFA%$NYCOg}JPAUG@1sgk1s<pi4gk_;o<{HoHfz zcXlt;*I^kfLOV%|^|OojUe?5w?K=J26}}}*oX*)qw;uP$bcBHaZ?lz4l4VXKr);(k zrvIk<Wt$losjT5YNsLMtzt7i7&Q@VL4-Ol+-x8>wsx}v9g`2^%aH-fxH>@p-$#?$* z%Wb6AkQ`4yf4kf8OOU(;2XqFsqhD>q+FwF4vA7{1|A9&Jehhu&BH~S?eP;ISF<`2B z3{X)!2sztlEDjB!>QE}|f2X}VUUppt&vQ@;-~q0Gcm^^}#y*6s-JpuiNf)rtOZSLR zh%W#G0X-y4+am#>{Fhjxub`w5Z}xl>`rM29v6vU2NcT`s0F51>efdAPSHX38Mdany zMqMbo^FKq6+RHBCqdKU$TmLjyb&fvO<Gcy#?9b>xn51`<!#n?`J3~zvt39D9w{HbD zwp$Av<9mPu0-4)_$MZQF4#9*)4^|Aw3)l}_6P;-ELpPkeI|;7R5j$3Y)73(cdB@b4 zt<^22>A=%Lt*|$1U_F6v%m9l0X=Knm)2g%99N5|{+PxEgY?YE#_%IIB6P84S5&Sg; zVq(4*3xJ7M<rKT$enCo=6ShglA%n)7FWy4V_sB)<PcW}ep=|clWV>PmtXHSozl~Q} z9s2}BmU=>~Diy!FPd39cI`QJh#eyXox)1GZ0YrMopNC2cbt)afV4tp#6&H1Peo(AT zLUzSKcL%No`_H?U*P~86=qQ@Cy-e=J`<2#1hZ!mk6y{ItJJ#E?Wf<vcX}PcT1vCG* z#`}i_TcnG&$fXZprwnyN!P{F9VBat+@P#XDZzh??a65SgOmy6_?x;Pj6abImnT`d( z=hT(0UV6e)8#n6b6>`imcR8QSzW_I9nxeQV9NS<0*02JZc_VVS|E<#3<VdU^`g7{z zW8U!<y&WSA+KOkvw3HoIeK#g;XUimNfPw((Ht?n}P(-15k&LuLec6@{XL4-eMariq zn5<@Hfm%UAY9jERZIAV7Avi)v1aNdfQzlUO0#3{r2-Ro>1A3wtlN~UnanPVtP*11m zpw`EMKt?~x>~kz@q#^XQ@K##G{F6rnJ|UPkwu)GILRiutDbk;-*QVo~+3hAEX%n=P zJs5va+VL0b0=rulYQO+I>Jh3INKouznb6z-YqZDQSULzld+N!<Tq--Z2RiA8GpyF# zi;hKHecoJB&|hdDeVQ!3(Rk>@(K5cv<O7keBfxeZ8T0&)Jwq1=%yIo#)b~iVhW-0@ zrvJ=ES67b4?D)1*{m}T0@HtBOZmK<wS`E$xcliTY>Y4a$U<~B0xdct20^9Y~=7??Z zZR?e>I_*Ox&3q0wOI0jAa`$o-eScy>^TSFESCU9_-j#MM4MwcH=Dr`;TN|@RL_2H> ztaU7#o*u???qU{`q3&gwx?H-xVoM-Z(Nx5G&}fG1*JfX?5TuN?eH!Tq>%^l+(=im3 zM7up_w4<3cv0X~a)P#HmipIR7#Iw#_!ZTm2q3w%K_s*FY!21|ST4dCx<prz~j|WXp zYje!IQOtEik<lv>Ey>Cf2E8}B&h&8#-)_eHhJ`FfyjQ$_Jv&HBi;VYUeX=;Bn}M+| z=(K9YdAD8dF_Oz~i|em2Nw~ckuB-J9+F{Vy&!o)zUEZs5?8tP^E2)oO$}TEfioBh) zO?tO0v8?r8^_ZL<IOSw{hLocBta&lNTnPaf+P7%#p2Q|i8=OeCd3N|wQM?oRi5%x_ zN54#cuZA<x>O%4@J1aki&NkvEX}BhPLvZu!J=Gb!-*vibDd4w;)+eJ<Gw17hpNBIA zJiCBWG>sJ_VzC704Mvm<XA<SjoI%8uLKcl}B7QYtGb0%lwq|$mC$Js@7&#<4qK%X$ z2B4GfHOal5-A=4YgLaJ3K#|EzywWtzCXd{c0>E4t2M`FPf=OKDPvt=q>c8Jjgu(9i zU!UD$rF0J(zz03Q1>sT9PznJKP+z9K?mtBU4cMiL_`s_*<f0ig;t+bA2~6DBo<Z~G zq6Zg=ve4}=$Msxm5;U)3#oq`FZI9)=eXb#WhvX{2iQBXZTGQ~SoKOc&l*pK;dsPgA zhypmKnjDR86Elkp2Nw<byXS&fg2p?7miwzE-V02xe14TZZN0dVF^8p4g@4nvvcDB7 zirO0iBKAgrmj62ffOB+%TAZ-r6I<l^WO$dTG8m@`FvWoB_>gG0oSLC*G$Chyj%HoX z`T2ev=RNVz628p%QB4hnhnjG%gI^obd>R+Gx{4K#o#5EnpZ&7W&x90dgnhYecsFb; zeNJr|5q5Fv34T!O+7oFR<A)r8L+zy6`yY32rkIxs_`w)1Rt89X+Ci_^GA-GIksxF> zw^-o&7Lue8on6`*-;-;5$g11sp<^YwBkk$P*^^Ok8!^|X6~od;Nt3slUy+T!1fJVS z((2E4k<zlW8qM@~`RW3*>xyf$8$=T*!(w0W%O1I-sG$7T{AC!I8QV3J(|+6$_7`Cd z{yJ5DhKE}AHLX!mn@KW7HK!{plxMO!#}l`%IGq^2mqI#Xs2gw$W!`F13C_+JxTP;x z%*Qe&%o>E*)jA0z75lEF-gVnxlK7eAbcr_uv*@gdqJD`2K<{;DGEwC)`)-;C8xCC| z)?c5P*M_n#zNj**3Br*~;RnZMzkV@6vL(q~0g>8OA%whDaGNK&9TW*vh?<WcPs=oq zLNyIqY4Q#$9AwOk{e)LT-4=3&f?}&yR_y#AM2l8_R%0o;)f$FSxgnq0bb0ndg44ZW z6}$l&Y1Am~nVt-CC<vgpLdDC0)TKux2&U;OVq+Ci$$_gHZau_5G4znf6Vzo4G@tHG z9ngaU@^aFi{4i!$n#$CZqua)j^Sf;(r30#CvHX8i#=FL;vmVx*(avDoA0nq^{=}Gx z@vab5;_Xv4HO1YqW+<-gabAS6C|*ZHp0_I`&eAI5<5fT8B6iI>%zANFzNcF2ea7N^ zHdT%vx8A$^&N3*veB+dJ#wMgWy#xBPK;f=a_q@vVZ@RLe1aH#FP~1<a&zP$#Bp!up zONSCmxY_^d_d@}D@RwN_^IDGRP_BBY*=@7nCtNx5XR*c`3a<h^bG-^aMA)Xs^Ezj1 zHpsRzbso#gea+zt|8V5%MAt#Jkp0QewoD$fBYs(Um?E9%OP&_?i|4lrdN!hj4rZ(6 zdFNdFI88?eDC}*2_Vt*K3NGsI6$7A^U#^Ai&evC^)Q*4O#W-tisKn2xu6nM%uzf~W z_loY5b84SWRT}X{#iti5Ot|TkSh#xUFbFgvPkOu~F`w1kHjLMCmN=(;#5XZ~@y>fi z<UWbb50|)Chj_*V6FmOyvXja{Sdp{6ahg4XLr&7m{lzJ7R17<+49BZ?60J^XFmfH} zovL|3XmbmYsC9QL>6p)qo)dA2-_KyX@nick=F_?4P45q}9Yk*{y~JpZiq=rA1D&#! z&(_~KyCf+wZE2395`T>TGL=5pp6_3a_ttnUWb{~aeP)L3QO?070d=b%qIZ$u#_*zQ zOyx=zIPG$C=JGV$H*dr%bi3$VP<QIf0Yh*nv{6xmPyY^Brkq$JO+ev6Tmv1Q4f0ru zB<xDq5mRMMIneacSbBuao#1QP3S*gn1a>G21t{P-Iff!M8*#Q@3mrobLHTkAJ1NHS zagqvDW{)&JVHmg+vR_ZbkEs|zg-BB){PhIWYWwf-LDLY>h>7HrSYJ=#`Q2&kILQ>u zL)b@Pl!m5k=rTOOS_vtJe=@rbAqhT>H-pQA%n?x60R6~5@b1-LP!@>9oOpzXa+QhC zH)_GAoj5Ybv{`>H44?Vx(?JH1Q{%;J!ZD#B`vaH+`~xs%>K!kl#Sn2=O40B>;u*Jg zKgkBkjkUBHE8Ljj#(HNEcMM{ChWfprwpn%Q>e<?vLMm$UMaE7b(7d3lwu#hHDr&4W z$jk5*Sve=i0@cEYb8dSFtK`kTy_r|O$xR{;fxHS&y;!6)*e`;kij@S!8x88j2`O4; zsmeuzES+k6*{Q@Oo32x89d{3O7M6m{*rNt4j7Lmud1??Hv0v`k!(T_(nGk!i(bou# zI-L8IWekK4V;@%pN1}Y>*&B~<42781{eYyXx0F}|-Ia-iWdEj@F4gKW@c|N_s|+4a zY@_3jMuZqoD}`dtP^TnhjEu>tS#RPg$mRg}I<b|IF=keIJeN!1o=P#EZ{n^rE2iFn z)IruNiY}T{iT^IslSNO@QS94kTvHgZ_U4U%9d_l2&=?u(Sta^nO6=EQcZPt!hRTJn z4Dny`6wfKlIgK@T${kTP_E7TXB41vJ4i|W`np`AbiEYPkljRR*P%L{Rsw6!|A3DqF zoT_22^PXv1byl0xvx8wDBm3XVrUf5H`@5`>39IF#-ulGzEAKhU|CDS>cHUVJ4L~ed z?*@EVc~rejy%9|H>qK)YfWrx^W(cF`%x6F{_8Lq97mSXlzI3Ksi>H&iVa%c|>&xvl zK|+F<1jyTDhNT6w#v@H`V#K$Y2z||RnowHKUPmQE&?^WM142>2??ZSk5(y>&BW1vw z@tCFkUB5u#WxxL3r2v$O4!ktGC(Rg@1wW!jgKhVm@U&yp{~6*lpFUOWaN!d(NU#;C zMp)bjS1I<qBzrPKCl+9e0&gMOOaEvLX+P&k(}2wTK(I_7YXpM1p~u4{<%XbCl|0^E z6}DMi0v%ZUEU~T+RvWDN#7zz5$MmoxFzM&m2b^Os-@%kQ7S3nKs;qie1gWp&X1pdl zY=BnH-x=W4<*x&NvgI-kZu|uR3cYvZ2UR<?bk|GuLyZgw<BI8{7EiBd+z%R5{ZM5( zKi9e<_oHZK#+04pV!k`*XJWiNoh}q>5SW~MbGukZUO<<O6uO<~b65eF2ijvJTwXy= zQJd~vcFmzNVvMezNWYzA8{(i{UDlvXV(u|}WP*}uB$APfFrjc!*2Z~I-1U>9v93(8 zK3#gkfn>ACQ9Ib{11_8t^z0@8&w8kKRm|()3gFBg&OFk3uKCLX_V=yH%U0_0JN^QA zoq&&G-F!)EaEZ}4?8krhyJ`1)R5Urwi=<Zx#H8G~GLEg}oA{c}>ZHqu2$PQtkT5%| zDfER33pgj_TgJ4OW6}gt@dc%H5JiZKZ3I=sjb@F`nqI!??B2*puSN58p|Suw19QFG zr<#rZdgCxwC%SS<#E;R{7tU6lBEA1P2h-{WN4l-n$I8ERTNX*JX@DI-?&Z?zq2F{P zuvPTCyF6|0elqyYyDHZ<;S91<8-C<1qcGyF>v>><)qS#M6oQSumykHF)MbLwQQ)G9 zVuQE3JVCd62~tq?S{jXlbaQ9`0!?@bzSm-4LV=>4vEuuIRmwOx4*Q%ANT#5}A)d&+ zbWl*JP?O|E`2rP}s4nThp?NQk30eyOJHh#%1pB3^NN|_QlaBm`p3Jft6k*Sb2L(rh zm;ce{>><T+)L9xX4gDrGHI6O7%=i3PVtLIV1!|Nk@#ySXkKK3HO5`D02!3u$OXJlc z$D&yfPs>=Wq)IY;eY8=e3D4xA4IWZPil)>=6;q=1Qb%>pXwr_K{wf)<D7xe4SR189 z*aet{E82QIWAoG+wG&`yT;BjeF%e|8>i4;#c1~c@O5(x#tu5~5{%49W6uEm#McW!r z&Y*7^h@a-neI;;KVhj0M_g0WE=_#9;nH^nwur3Fa4%1qe5?;d;_29elr!+bkT}&Ba zGSYeKC7mP;Pq$Aze{dAAAn+U*T)U;HIl(~QxPC;686|qL$<ZdVoMM{#jpH6n_~b7o zG=O(){aN1Ym-bhh2Zzg9cxKssL7x~iT)jUoue!Jvm~eXGy#%6fbqAi9d3tE6C-63+ zegF69)$=Ka#&G|-;jkDHnU1tI8^$(7@@WCDtoISKE4c?cax?|AW02)BL^rdeP9HO7 zF78Me^WFQpAsk}H{D8OiesJzPjv^c%MOtepcidf*n`oFb(B3*$SS-ODTiSN%A?(u` zX?#afTj{}?#ElDm-Sc*<`)fkn)&t`;FTUF9zEQDPg%k>qBuJ@j<mfcZMZXVg#%m6G z654n@^X3esu!JD^lW9eD2+e=GlGnExs^)zcWeP@Fs7(Uq7C1wo^!GjCYR}$?3#MEe zz_6E%1G*OYwG|XrL(30EXq-H`LZAs@WtRci0cAPhoBtd;2I&z{LH*$vGO?KT-0wy_ za(vBZgb}Y7v?cCO#4_-s$i4(n@ZSu2jz7Qo-defWKmW4;;@vYU_9;8P*eK+5mhP}o z_+~A=B)pabvVc13JPD5P3}mzqdP6=I7~He*x+&+o?847{xyg-6EaZ-om4?Srj^bSH zz*@w%%D(H=RdrP=hcbfPg`ZWY-q>aEN|y!T1a~@AmM1`xPIE_qQ}>*r1~ej!pBNI} zaeA0G_XQ`C-=u+Q6rH1Jo@c{+c@lOpD{hLS2NJ$+wlpeN1j0D(u)t@b_cjrB#yJ|! z6+NdxKi4H3x1Oi`@WQz1_rZ&N;!8&cS&MmvrW#C^A|+e3*}dqI-!6!@p`HNGy<T5; z`7M5{{$O(q8lb#4l{gz_>CkR|?>{O}zm>nK&nS#OH72#4x0n`7P1Mi}0{wr+$Z?mN za3=55Mt1QliH?`fO8mK~=+sMRHG6mrTQE{Cu55g{>Vu+Z#K*RIwc-7i^&@`!vm5h6 z3NTrTu>utgNGEaMQ;nwH=h%mF<`Iw6CO@EluKG<-m3m0Ek0-1XQ6xg~fa7^K*ekwY z(g7V3SA;E0Hr3!Jm)k&}?|D7TYH~rMBarpH^-&Aa%ceC^s{WnG+-xAujx*svCe5Qd z!AaGYF&te;#|zQHu|j*{ba>6UPMlGx1?s_goKd1x0!(VlHZwCdNALxrjI$k?6cUR9 zYrGuP9cd3{T0SyO8~7(N1!`E3jo_~v3j7+*l4?iaWpe%A%72NBAV9zd81nWUdq#H8 zP5Q=Z=9oVM?f=rc5&BlE_Jg+<^;~iIJ3w-4MqAAGO#J|?0iO8N{|hXB3hMsPwgxDV zWC|^t<UbXIQ46K?o=?62_K-mR+FRDT-Zpc;?Nl>3%%Uq9*?4|3(9AswCxZLrC=LMQ zYaC4BjK$g!(fTS_H%?yU7aP;;3@WM6?C69IH{c*d*JWaSSFMi%)!Ze6tqcmJ^kV#i zb{sz!$Ou&3+0C2i#<f99K!#$f&Bo^%|4*@Y<vyy3|M^wj^tm^4Fj7Qi)&fyv8>Rq* z-_H?m%^4Sh{lkeV3XeoiS92gt#R!K*<1UNj!#>zQQ#dc()tNjH9sg^7!bJU2IWdAl zxol(ZEL5U$rGuEzuFuQUs5DS=5vT!R0P?l*=L4JL{h^T{vI|MA*3-C`2P8e;A6r*l z+`>4GM%*WOey$2ku%nt|J8&FBSd5H)_;aL6YjncVBJeEfIph{=6cEO{P)0~IP_66B zJ9fiTbO=L=*x2&8wtbb-fOV~md02;B>u;UC=A<Dsfhn*pv#xAsR_?NtuGKANE%jqW z#+rTEXj0gC;by*8Bi1n$6Fy-6dfKS{pQS!IU)6eb5W*w-@`3Kw4R0$9Cxx`0m(|U{ z!3y8lE+fF@hSD)Y9dDlBECiA(7)))4w;Q>9pKz%0v>JHKndtQ3LCxj4N5j*=xedrz z2LrGIM8Ln=iwOCXVgm{?TgEOJfP4R|VM1bA#9J>AzC_Dd0*Y|JokMEV3()oxM}HAd zxb6Y<%0IeS=vfZnV(2MvwQ9@CgVhV4$_2d{k~97hVDDAqAGrbeLLlz>Z!zwXY@jy9 z(;9giCBPpS>uT)ae_SN#Lu5mS?o^E+sH5C}e$)AF_O{i&@BZhfI0RNpB}}Csl5M)X zlKoZ7AVJIx$P2`0zJTTGYiC(x&!bh?uOQ~%blumKXL^<No04(@^pQ16TGXEf1C2X7 z{}^sT;DNOxD1ooNd2Q>UEbrGQc+akn#4Q%=cd0g(WV)P_H#<c(ALlU~HSLh;$rr0@ zRE(-D%L#siH=Pr+pL1++b^P3)yiat0@mWuO)Aa}ku3Dynh`Mx<_}k7cFtZ@WjYor{ zvjZ`@Ezjz=MkZ6G%ktEebAHH9S-4}AY{2;SnzVB;|KOpry!paS*iq{DvHX8tJ<L7y z3(o5-hzANLR3~OKS14@*jW>_}85^GWQJ%Lt2mrq}Re;VFz|B~N_)v?wfkn7%<e#8C z^6?5VJCB>LvTdvj=n}I7##e~R{H}7oIrU$IDTYT&J#<g-<qlk#7WdCu$qxOIu#;Oa zW;o0-^16PAfl>F!mu{`E7U|t;`pn&`3Agn#8MbTB8arQ@Qmw$8O<Ht|?2_~lT!h;# z5cu^Ta8fLG#|V>bu;+*90oXAsc;oB7s0wtK>Y+~~u-F;y-p<eO=z`J{xFcCHLOr={ zJpeYU6c~hY&FCPc9~LKx{SYJ`XGWMDE9JqEq?)ukGQpA#j)mqDX0bUZ#|R)`3Im<d z-Fx0b>=zJN|4$QzFsDC$W~l0}xy1tYB={IYdMribB%LQg3VhT^=lKrUTlP!=dqoe8 zrI5)7{1|_qBR*CjP4?OIbZ|<J=Ix?^4iFTEBS6KzhyDJ6yucR+Uy^2bL1@U>;B4@a z9XtM3S6}mf+*1~li;d+4eq*9LSl5ho;^g>xY9=4U*(=89n8t8Ij2uU!#dX@nbghBD zHY+o8S<3jfqgL^CD<{qN61;<`D0a;-Ou*f3-l}p8a0<t&FHJis{-(<cn(Or#D+pvP zxODA*)oSbCTAf_v84Pd=er~gDfG8Wqd<p*Wy}NAuC!<*nN1km~mJ+L2)Wck^w{^Lw zOH7*dbE&AAMi)oLvr}(9OG=2(SCvEkYC^vsVb?>P{V|W{uV(NXB_Xc5h8kUBLP|%k z{45ZZ&c7$kok8$+(dj-Y5_zW!{meUQH0K#hMNs>!m9kIvkmC}^{W|{Q^!=scTU{Sc z@OCFB2uu=Q2&unDdEI7&ajA;Q*<KigTc#yGWv$QER(80I2sFDnl<s&v(E<&SU+XH~ z0hccHD<D8?Zp~{Zop$HmqE1Xzp^Z2zi4Q^)gGNnc=f08l=P&P<uocs@u}xo;=66H! zb@QYqa36Cu!^hdO%#CHRJsUbiWRj`N`6VZ25gk9uXTbi&r0}X1?7-q{ib>?vm=sK5 zi0CE8Nz`zMOqVTDC64{!c?rRp2Ai0n;0?6IgHe)3P!~b&lU^1kRv?x8=Zbf~(%~jm zrY*ZsRep&pzv-@p2B>#fr20kj12zJ6+5$^73a-dTz9|y&c#Y)yggNQM@r{RGE>_+w zr&OX*ql~qi{;8qdKCp4Z%c02ct0AdA!23c6GeZVrvjN>oD{iQQO#-d)TH2SDkU({C zlQS#(^(Lss=9|U`XjIT1f(1!o_h2iiThp@9!Jr8sG(z^px<>iA$OjO+1~#_;!b@nu zd&akzXqR=ti}F^8U7$bjF>ilJJlaNu1pF~n;do_m1Zht`n|U*2Z#19*yI@rCvxNdE z2Hunrx`V!^^}qJ_PumeJ=aaF9k5BDTifFjlb5D*UgoZ}s^R5qBzJVM#C(kjw_G=#! z55Jyiq}@FktM-MrrwWwMOY|z4HgAhG?2g|k&2X1ocd7(iRxCShd_6wkpTykkyHc;c z^h9CPsV&2xtm|A<@teudyy#aO=HGkMRXWE+>XeUFn>CF7_}8;&zr^L{;o{K+a`^S- zJDfWVcGIdXJE|TPdSZ$4Dud{l4O|_&W4_htlYX9LS#SP>11Fml2rm>y)bj7cvrvv2 zl>%w0hl34ZGUjF~8Rv4n5=|HV+j}Y2Y7WEf#T~PcaI-clm|k<Sw+-A+&6^I&AR_5k z@{_u9in>R`?Gf$1ba54nsW&%k*5&HFaqrrK*e&X+9>A7s3UMkK7tx&i3pKQ(UQZx( zTH8;XN|bdyj2|P3@m$0Y9}P4kysKPU$zJ`A>{>4BoG@Yt0>H7QKYXJr9-T8B)Z9F2 zLMSkQ&z!999hSYXveBYkVDW5zwe0OetCUxiME0k5Y$S>mk7IFyw_(8qhs2<zCL5>2 zJ1XQI+f<MU6f_J|-4W`Po*he1=PQfI#GWuHHy|RI%|lh)pF0ov;zbi3UF*s9WiXD# z^x{+<WpMHSO8?X2%_N-?<=XR&YPsO8+j#91C&j?eAtM}N^g?8a`pXtDA7Ofv8|^~$ zSvG;Fm7QeMA2Cbf?foFl8Qc#Mlo1a8=T_>i*Tsc>;|EaA-!86@V6Gf&n8#)9n!>FI zys}$<aOP8ZjszQ}hGrf>-H8#x5}_gl$&z5#Vqszmxn{#)5*LS}M5aubtec)V?(QSc z9P-dfs;MDFN5ixQC-{g}fdCw$;#pFZYw)fQaKW&6QIZlJa2(L!hwM)?t=qay*8($% zP*v`M1u%XvX3B3PYWt(8T^$ej#i5FY5MH3HiVX7Zq<Jo&PsiP#g9GqwFBcX_*c*gs z$@qKF*q&+9<Zg8%<lKS&*fRg`Tj%d#Q*k$n&K|~*jFjz2=J+5++%HY1kbUp{8Hp3k z^bbP7)0<)~##cGepV>02Ndwx9CA?&Ju+rjn_bzGpiiQVrZlqb?_KZ|NN;e;vyoJtH zUyyF(2&nj3_?zw)s)fq%bADO<QVhw>N@zosND0MvHm8PkRE2E;SjQl)tz4~at<kLW zaVv@a9qd=e5s~ZEFKoO_t8DC+5{?&626=a1ED%azcQKN(yjPz0PPP7qC!X=6j?P-M zK!Shl0fhvE?`~F4j^AF2XIZq&3Ees0FWb2Dw8P7;ztT|N_{@W`xb=ypzHCFcBPA@6 zPT9c?^##hg_nd92A2+zZ3SK2MFOq|?2UEKPtuYIi+H^>#&wrG{K8AynJbB8wBk*-R zqv`{d?iK5X5w?P~9PkY?Pz?|pR}S^1zZLaC^HSHPXSii_F*4C07&F0d{<K3(*mE53 zjN3vLQxlZSW8d)1^`>o%*Y~W)%Dra}9z?gxm$=`skY$wu>Daj%F#ZNZ*Zm>J^wsCZ zbBp*$*OH=-T&|VWbyc{Sd*e~G6F{vkcg})uLhA-P2ka&VJMbvj$C>eUkt%f~qkB#8 z$u9!m`tqyK`?sN2k6@g|1C1mu`rinU^@(yMjvcXV{!lEsBWzX$Rx|Y`?s(@g7};gq z{AD$~cSof3<egYkl0QOjv}xIDAZz2nd-m&EL3|a8W#4~np*7e-S6geS>8ebn_eW0@ zKh*cgF5|}m|6A`@*^%)_CcsG2?eU7DIs%~5hh1%>08II}{4jN)(X3>{xc9-)<|Drj zv}o>Ape8uIx8CosKRU4JEYWaoF?Ld(mkMjN^uM?$SKDIC>wDB<w>hlXT)kxS!Y(Gx zQC>jyp&ybVw7w!n_r=RHyT_R>A2L1D<(fLpYgt8y#t-F)y0nhWSQ{rTt3D2TZZbiK zOYdg=I%A}_#4=&3iSu1^3s(=BwXk|sFw}N@cA~_$R|Bu);TT(4I5cB^s*8m_)%&S0 z(%{`S_Z)2AhqUssr%h#>`j<x}&2mLcbqRe`?gEP#%;SnN+>z+`<Ew-=NnOjI;wf0% z14L&rN<=y^fmOq@^Q&+TR&=f*#%y>o;lsJ&*DLkdv4Y9)c2zU-lvdx@DNz!7nY|}Q zO4(6<8_9f!q*Z0?0=emc1ne4CS`2iER9<ei7c;}MZToAPAGNjG+mq81gA{MfHuGo; zE#L$rq0h?O<hX^1)zshu&n)mZjW>Eczoh0PY!l#A+N&fa5|O1vkQ(gc5-=MTj1|%U zN)>`gPw=?SlUe3va^i1zN%LKSSEk#=n#hRLtq8kaBWUkM({stRWZ%VHkW&yPUBavp z95Qh>ik(svARGAW*xs`W?&0m=sSbQzW3RyDSN!s4U4wXV#uYru|E4`<4Sf1%s+c5e zsrKvkvFx}8MeNe?Leb*%Zzb38nA#5PgI29p9qc^~xpGdk7{?VHBWEUG3h_&$T<4~1 zu3X1}x0gbv^sQ9$+5HVhCEKU_KH98MEJB;>4VkTkgrzp``u)IrmqygETRQx@_4)u| z-b&r=&Kb6ePobQ?-F#VYSa8UBfaf)SDeIT`RcT*jXi-kFIk#u>XP7j_z*UCd4_&cw zqOQc$jd>SCe<tJr3%UkR(YtT%=l)n>fBGAJ(bJd?rG~jhbE()fC-q}=mjyUCxZ99V za)Q+#kW*Lnk2@cqp#E~^V_V5bdWg(d6wiztd4(OFT4uXxl`+P1{bt8mrSy-O%9sC~ zYQAYX^`>_5wkR-^Bo;4*=Gl%q{Tw;$=ukooQlNbC?R6=yi9dKT@6DT|>0^0qcUUtY zU6{3m5ssdW*?!6Pq3AFpHq6hYCiE3hCvJXj4m^G<cCCP0wF@1|X(ki)JzCr&+L34O z?rK4JL%*FhCUMQKoQs^trBNl}BCt;r&Z@;Rh|Sk-yz|z7+s~Br>W5qbY5A6Eq&sRO zEvo3PTAZfcy@chYm@1VoA3IJq4QJ>sZZgJWxWx~;wM&I~<_Iy=Q4D$X?D25nF&sE2 zap94ke>TJ|{J(AJ^9=61ZIz6%(K*a}-2E^H`|EBe^FMQl-}<ckBmdU@2ux~6@SIds zmtIx0zP&Q>!$7E$*?}jQ{ZUIoH{TJDe_D8IC%478@K&Sq{>UM7D+{I2x_(!12DMtu zTUEy@4Dp+eK36MLHufEBAPE)oZ;?!oWKSB9G&~6ZP4^>Ibmvr!fRfMtq7}n^8&*GV zl!iIo9}p%)eO3@=RUn(~f^Eb>m6dwZG1V|^{d9GAmhpMfa{3(Da$|G-xUeQjGN~>j z$JfaAS$nIa9`z4T4m?;VzFMex+S_l|GF$c>t&!yr7+8BcHs&PLibIvC?brAywbG87 zpp6LU2czGZ7fZo>$t*dbWOz3#bT|Ybpje@ez5MD4$fYkxvsGxn{6)Yjfj6-(^g!?7 zv6T1j5&pdbN1shiOX%6$_>7_WE8HscxjWUeRMzO#dT)R5^FTT2Y&J7);Z*{Q*u{3y zXJsw2>1M2}Jc8pLxfOJnxPk^OQP^iQ5x4Y?7kR*&awSHNE0W12K0e);>0wiH9*H{` z@$dee5*PT?MRZ<jTGO+P*~X#4v$oe_r3M|-EdoOM&3sWoXO+d4Iy>UpvXiG}I5{92 zWfV}FAullP{S$ea(bviYyOnR|qe5STRZ-7bAxBMm>=vG}Jg==9>TpPK71t8c^K!{< z71tWmgIh9<IqmT0KXD&aihQ(sqTXzED&?$ZHGB=nxA~$iN0}MAlr)@J+h=2ASI91l z&-HxnxH$@rCU_%et;HpH#0my@@ur=tk|pO_PuK-_6#WDvPXu0L{otieFylbOQAag$ zv^S)-#Io40`!}6tOm@)Y-d7tL4HfryW3dX|x-oIQ=uh%qZ*C0A72y~##B-X!O$+wo zvs2G`ALMj`lN+uP9Wf&Llzz*(9N!Wn5#|SE`_~JsF?XCNhXc3NF8*Th@csPA<_Sx` zHDX6}3mvcB(0)F)xc8BG{9ir?I_!20Yjw#qF$Hfm-7DDNE*;><w5rFp&#`2ItyDnT zV1r^(EI?0L&OVdY=8^-OC|yh9c5X8pJjc{U-ya>H!f^|VN$03fq3DbG_Nr%j2NbiX zTo>%c^*eB*s?<(j-k8HUR-Mfp(yITZl3Dfny%ntTYi-BP-3igoV)uRB)wx}NWLsOn z_J3eOqUNjrC2qD0tF9WJt*(MDa3wL=sfq(z-Qh)VYV_k?swVhoJyDWZiJY4Hcp|uV zv3~-U<(80hw~V?fa3^iMK4r}ZypeJ!THnA}lb(T>j8pjen+|`e?fLznFG#h)^G(yK z{h#JE>tiinB&PY@ONll*OpId99kvm>K8ak`sazn5Svz4npK+dhb>1L27#teh@mZiU znkLF}{TfbK!ml9vhLohUnVzF0m4HXam^pD}S6pec+F?0+^_7)=Lu%P+fA{WR*33KX zyXE(HNrB~9$qF_PYvaiJ%FEx8At?r&s2jX5$AfQFgjj+^gH!Jc;tYpN+#;gOxJa^0 z=z9tv$6_Q*F!soMr-XaOOLI8;HMBl6i!VBVNAjJ|x-Yt5;|cq=V5iG^6zXZ<sNw5^ znH!+3Fc}1G%~<n0co_x-9m%qrYH1J9VbO6sU__|Xr~?tc4#Swp$_I#hqxgE$tz&d@ zz9NHCXyj3kXo<u{&E(R=;d>VidumJ<?bFtH#(t`x3lL~o*yg(xGGfCHbFWyW`sRDo z+%vwxZnt$0l-~ETOuIp*&!ST#9?dp4vz9)8Q*5c58KT+(S&5yjx|wx)C`9|j6vA4> z>A3yyZ02l#p+nY@xJG^Md8MwK^cTdb2K`p-seB<UU0T7Z7^xX+z@u60NN>9!7s$w3 zfhxv+0^+*am)+Jabm(-@;xhUnNWBWMqm0ZDRU2)5RDX1oOPou{djZ$E)NSr{mVep! zl%&f%`mEvH!+XWPGA;XSH3Ihy9##=(zBf`gRh|5OaRuKrEKW1An$_^x@mJox44!3x z<a@=mEx9&cdcsO+VdbMD<%_@<blVZOR_lG#uCLCEFaWPvhr8YTa%v6y9nTjXk{Xwm z0s?H}*SVAY_uQ<-{XHY|gA#m_8lsi-Z^mG@kJjv-zC5H&5D_@-V;J=V;Y+uYwc$6$ zqsqKd0j9l}_GsQ`H8@UE4BO!8;c~wRoc(Vq75E=M$Idtafvw3kkB-c<(F|7&J&X$5 zjRK3AL13`FE?Gm;AU=Vo6qEm+KY<yDcNRgKjx`}qMLvlt`Xpve<8)o0fAG&ES{eYE z0Et}6QhRb=N+&Jg;IeOTkMXoa4SP{IH6;cRsME%Wc65aJe>rKdj-`6<u^U#|hL!3N z`fHIY?U;l2{Z02y!mxPb^@pIzRCLxx96kDl7O>!FEgk5&6W$$VGe~UoeY5W?(ZnEU zo`op^WuE*A4*xeK)e(e##UE3I@Mu{nafZ*6Xy^8#xHFivw~YaoH%D7NgIEXNe=goX zaoRSCYhpp7F;MshkJCo+RX#(xy1}PQXCl7lie>eS*Ib{y)~9hH(id6J?HY-ENRPh~ ziS%K0`_lV0aQ{MPW9AX#75_OE>zk(YJ7tI9Zha_KRX(Ri{{URTqtW|LN0)Tgi4ppr zg5OPx519A7TFSzGcm}Qy-o;p-vz|BJG!F7NGD@|VGE}RRxoh^NbL`pFt)gf-5d(>z z%98IEe;yaq9{J%Ghq{+yV>v5M$V|9yU#O&?IWTjaF;W{BV#TDVE@7_Mpy`!SpOv6T zr*ZyjW{kL_Qar9zHv*DLb%o>aTXB5J>LJs={;1PaZSQ<ZznK53+qMZ)?7PFaIR{d4 z&JTFrSF&DdcY<eq<rL+48u^b?eHD6iQ&w+Wxvaf%Nx7Oxr*NM`tY1nG#Qs3Is-YPm z7{rWy(dMJ=(mv+1I-GZ1%YPo4xAcr140$q~QYbjV(xaK<qfD%S%@TfB0Pl4i_={JF z?#;Z5oc3I%oPt&I)*TrdUAn>BITNM~y~!<^l4j+X={&QPm>yxh20dpjOT&w1iEFKj zJrnumqi!g?Exgd>13`mfeyx6Jez$2j;ak?rb8{=3AlbU)yum?<i5M(Dt9Qzrb1$2K z#RId=?I|m8kV9Mx0RlD7PE?iYUEeC-U-NSzF<RDzZNSXa^<nByD`bD>vDlU|f`wlH zi#wunCC^;pOFE4wOmqEg?c(oKtfe;Q8=5Y%5YD$EAy;)wM1pcWI)5Y5`OEAf>SkW^ zu8Fno+^WoPy5lMnL7g|P6?UWxWu}dXUbpD3bE%daEj%L1Jo6^xs8(_eIMTUchctg; z#-u3dvAf-G_F3lO{RbB5uh|qxQ3;DHWY}X{L;Q7-YU1cEE6dRLxJq<(<t-bg+^6sY z6Yi)<`rsQMo4tN5zynm)E{c5PoIq<An33z=VYW)$&_Z@Q%6>?%HaC{o&z+nCx|<%& z$3=!0qZN74X<xO8(FuYV2D`5HO&H_&i=~WwvJcqSo@HSjl)H+vbL)T(H<|%++P#iy z@OIlUEWU%do?5rtN@ngpcn<y@xG@6k9C!3hl+aWh2m?EPyQ3J1*Bx@4;U=*>lx#D! zPPhVd-&ZzOt5LJh{NIfr-X9x-y>EG0HO_gopO$LoB2>DWrLyN?yngusKwEJ;WUZ}K z-b!qtsBJ{=Un)2d<NeUU>AOIG&DqrUkX<L2QHNzERe@q(uP2B2<>-6Zt&-fFmZ`8M z!)9W@>vV}`75-6wbsLR<FvHIq#$5o60k_b-(b0EQ2Y4>omd`l)Fm?ct>hO@TZ?Gm+ zu8yqH1Zb<wbABe*+&W%SjNaO(p@1z1fwF@jCpB<vC%qd47lBJVDypjytFVail7WJ3 z)o-eJGZxX^&6WMBz8wG=A`JOq?+u>Qzkr2u;NCUs>Vh%o;VL;R=kag4o8QQgm)-jG z%=n!rz`s)DWaG&ZwGL2Rh~EMh*|0rbg5P{ynkjZ^Zk?B*j#Pa=Ro_%|m7G|tx)KD_ zRy@*up=H=GHEptK#5eQ84=#0V$du{3Twj#C`F$Gkpl;{TFJ-9}ywWNc#6DnV=Q_y7 z|EQ*Ikv;77QejlNK!SJ0i#O8Sy)xr7Qukk-;Qa;r?&}$L{a^hq(_l`8KL^nO>-=wO z|H4#)$Xn989KvXf>J@9NO~FsSzZN3}&(V>^dQbVK7++O5gdqqO8~2_;B05f&2r1nP zge?zM=`mO17VPAl+M?469r}QpIGI1*#+UX@;5j(TrR>y2g>Cp-P3z|l2A2p_T2Y9{ zQIbuAo@B`$+%_uhiol0%gH|)K%lGO_1!J}Qy2k>QzxIFFy|1A4VdsKGLe#n#$Cg-T zW}ic!W4s*@p0d?#Idpou2}R1*N^N-&AM`EvZS|bpNhuXGkax3KOSrpsVdif0X?Leg zth<)nLHzCGM4PoYzHZhktt^S?m^)(c)MM)LLXN<B!*ju#V}Xu>_$534)XkJ+<CM~K zXzLk+-~BANZv%$}Ef`=SzKd_u`||Eyj)7xdaVf2l(i{u19b>K>&rRi@c)rV{L^aO~ zQLH3bCqx*hi*2!?X{x%;Fh9fKf_o?iUw1-jDe6k2QL5n;l-@B`OysjQqG`tj14-MO z1-2Cg|7sDw>5CR0KPz}?TR>S;n^RSH!=usc5``Prbnxh=*^~pI>J6<z7b<nB9g7LC z#mntBACuo^?=x&`wEyUapl^n~P|A?gvmd|jEc~3Qnl~Yv$NiBaI%A_(-#EjGc_}ue z(dR*M=JvT9FJ;vxApIw2u=Ts`*k^(PLn=U`va5OL`Zjs%mqcp~PhW)d(SnvKb<0+z zxS#N}3)7J+d1&`B)kNaJwc}S(rv;Ujr^nnS)YwBziJz2wa>9>XQ1EPCAt&B@wXOW_ z@tSOhGzq&N69#6G_m9-6eFba!A27Jt8C06XRGtiLQQIYf;*YGpYb56Cv-vIOBT;EV zvg2~uSvh83o-8+7M7?%HC&gKvT9h;psD8@Yz1+viiGO+FB1ikXa6H!~Z;mhR$lPX_ zyaB`27LQo<D4ZOi>TgtC0$`n6Zy_e&#7_yucwbYMd{tMc`r<%Qq7e1UYJ|Pi1$b?Q zrt@#Q&v>^)O9@--YsF>#yD^n&yZwb6X}37ZUp{~PIzau$*6@lr+56_>+z|X(KzO6t zRU<aEf3@w*%+L2%C%J@3n&+opQ&$c3e<8x9@6Wbv-dHkY7&n6sWMz}N%-=m@W_)0= z%4!jvZ}<;6R@LE9UFlt4^uvuKg(S-CytQ4lb&PJpR+l6=UUS5MW;}ePK)%?nKj6d6 z%JHULu65Y29MWk(uD^uL{i}quxlRF+8c6>oqo4ydfQQMG2SLv$%HD8Q@Sr(Jq^Nww zdJ_5VMNh;EkxwCWkDP&6d_2_J_GovQg&VTJ`G-aGKU9(ZHP3q9I&&N!e}moRX;fDc zu@@MYEBJGi2@pZ6(gFQYehVOjRwduH-4CgMGi;Z_D#333A}m{bm7H3oraDIOpmyI# zlv`FYb1Hx<g0unt=O%th9ht&R`xx<OA?nrmQb5BuZ(xSzu|2&gV=?|1C%3}*c*HqZ zXt+w}`R3~J*BK5Sx7Bz1H=n&vcDZG!Nos(cihzCnq`-0Nm*WroWlf2G6&A<gK+=V* zhRG-ARkCXycD+#f)W=6`DrV%jvn@Qj`HsXnAW>SXyE*dSElu*McJgRDQ%)Q6l^Go) z+h;k@#i_jazG#rQ$SOPk#``{BxMaKYjPRzp)8~Q-qxa**c3B|`q(hVA_}kujpJ)4J zzPmGcpT<o_-q~<c2X|R$e3;o5EMl6w=y>Z;7`RTf)I3?A8~v!<60z3S=#GANyt#)c zoS|Zfw~jWe<V`*m>SG;qS1F>gOOW@1j76kN^#kKhd92zvC&$NBU5U2~_tUq3(_IW_ zwn~wGWkPa)pdT(scspB1X+%dGX6!Gz`K-hyu~=xcE5>Y*jpO=@OK54a`s&+V*S>v6 zisAX3au){8=OSN(dcDmUTD&f!YG+dVebFS#Ypmc~Dald1f0N|rMOh)9d*sbMxY8ss zDS%bv?@OthqEFrY4zv~lrx%WQNGdLEHp5?Ol{o#>G50XNI`O?*zxlRN+I)8edn@T@ zawJnVI7_SeC1mP=FUs=X(7lzW7(ND{b5SlwYKSMBKhA_~p!LSAH|hF;y-nT7Gwc*_ zBo-_if8G&i{^ga7W*j~6ZM3DQI0kRxTz$mUexOO>_?!-3iKZ&kqv1=0xvSACU^H_6 zaRcTmg$@Z0M%&#BBj>gh_%*t2raA=aZZ=$B_)Yi1{f=or>m`(fl5Anr$IW&xMd3J# z5vR>vrhe*|%BSB;VS??aw%>O@?V2>!60A6KT<%0+Xu&%2ZK;!K^6p%BeP)&WWVl() z`#TP^$a>7iD(UpZ+;2Mjs?TF*{Nkp|z;$DdV@K1&Qi^=L-Mw7JIp~cG2fB>tc(F-0 zKViE3v_zhnnr?@{u08XX1B#0O-C-y<x=ig0sad@tGwLT`j*MFjwq`-(JgS($&*DbM zokITAx0jpTkhmjRskRF4Cdh~b7Ji*wQG@88*1vwW0VwT2+3W?0;lAfKM%5r{U-wad zU&%R>E$;1xwYPCpaklW@hK-e$<_U=@wel8nXpj@(A@%d!2SCU72+sOY-?#fI^LQFK z_wCeknoq+&d>io3&2KYYDApIfImb;qf71<<i`btqcBDhcfl&jm$Z1OECj;CKeA#cT zWjt6ac&n+<byH==Y7pkopAJs2VhXhEOh$?|ViEE#_^Z2cC0pFBIe6TDMmeh_a5L2w z7gUMj;VIP5YJoBA%|V|w=702<Y)dZX{_4G*$%ZM^+Mn770(CUb(lQyeD5=qVG712? z!$o)(%_^8&dYsYJ)SP8<rqbn1%PU%!CB{KMlE6luu%RZk__ZRF9k^a;{Cx`nm^^fD z+}syho`e{gOof@pZ2W(0z4tfUfBgTg3)P}ZYSW@cViQ!2YHP)wAy!*dC1&kiZB>Oz zQCm@)AXe;E1U0H+)!ri|_FnJn)z9bpUguore9z$z@Po(m`FcF>_uCEb+ABNR0rb#K z<IIij{zu_6`m0GG!5$5ZT27Ur6!N<)xK1d*TV{8H7`_~2+!qM<|81;>pnygF`vbUP z4kRsJ2>Qf+Rw2p!#*`Z80nJ`NNP2>I4@Vo_6$^E1_P-i^QXJ6fmpfq^FWw0){r6zV zWMFH=x45V$3zeZlznYAs8{Vh-(WkUN&Ej9=E}7m1_btSoJbKxnYap8xYLj*Lr<f(3 z;{^UC;Aw?j^T+j@ugc76diHYd+<;g9rlH>ZBEvcVCQ{zSV`tpUYU}yuko97bF(Hrq z;?d8A5O&0K9-Mex><Y3^_0s3pstYVwgLLVsjD65<Be}M8B<DlaJ`xy^|Da05AT~s} zr+v+fbYY*9(P~PX6kX&jG~#nbv<1GmWms$-JSjOlJM#6-cC=X&PX${PhR4%x5gu+< z_IN<X7;6_kYxpi%)k+p%X$p|6^5$5yOssq_L?9XUr~BR09O6YiVZ1wqt{S^0MFu8Q z^*3pz!dpOXJ{$dgcxHizh+TDakLQC2!t8f4d0m(;C2yPwGjFgNK>SRux|z{)e;Y*q zs@1J<Me+60QD6@~lMt)^COP%StEPdQu$}&J1Y+{pDb>j^Awb{zdiA&OyzCm>amJbG zleXEMnuxZFUs>^PfS>*6VV_<iZ8lr)OsT(#;|@6{d$1(fPjA$i={>rU9Zjs_4GJtA zuokxh?p-Q7<7?W@Q5hx)pX@{S%wHS-u>JB*3H(bgu4$Nc6;hf)VADL4tlJuMnduV% zD}=tO6UlS3&$(Z)m`^a3tJG3A&Zk}7%Rf6iSc5zAhGzd!6Q0H|5876r_h1@-6O~y$ z&2q*0s&2%+yz^rMAufX~E>>G6y#dG|489B!A=**Xs`q#}!IRRl&OIgI`Ier3*hp1~ zg?pdXozf0>Lx_3aO^BMd`0?oi*}VUatyBM@%8OtJ^C?S~ES53D(C(ybiXyVbQm1&J zHpCt08YGVi(A-eU3CNL)mW=d<(!vRf61lnjZWP1S;p*&yn63qMH2ihGw_Tb3*G?!9 zlri(Lj$f9CmruE~$>8lV%?2Y6{tc+mwe&S4D)?x>2x7h8k-05;=7(vm36$J4Az7y- zRU9T2q~|CzBjR28ECw^@4o*jBf-4*+&e*-F$pX+l)J~y_5=&;XDIJ(CdFJEKeOyB@ z@=srXTX0xO`tE$z4ldb7-hRC4?l~^uoLSf901HUfFh^<!WWe3P2=<x&3A{C50<B44 z64A$+2cd&p3M@0+bw1~iB~i+s)rRFRY8Uu}nyaZH<Eef`f8*=S6v@XC1Yqms+=D@& zC%gv8=yfR*V6B!)Rb|pR+GF!eT(k6L#$w<`98-!L!LF;^KGFyk^;u7viX}gMKC_F7 zvh(tHk50d$$7FqwBA#JBBUqA%-6f$d-1OwCkxu_Rz50E2KO0kA{0#;--KrEPlPV2L zA>+x{70Ptv{fzi~q;@FfjMN5MatE|ra#Vv7bLX?}dV%hBfa!CXjO<3EAQ@X3X7b98 z8Nn>LH`@$A_~(*8{hBqOPvQbWBDnb+<?c%(oA1s2uOgP2Qazo?3zDFZkBuaX^#MhN zKnPjsvN>=Nohjj~Vo&R94spE0Zs#R`NHwGVO_0trzNEvvN3K-FOwq{o{KH3{xmTZ# zq%qbF7KjPvIfLafuoTS3AdKdfI5BqlAU7>;f93~EL-V!nm80wnWBh{VM>c;OypK@q zodi%d(w(6%U}pZ_(oyK{`QJgfQx-{Q5?C-v1F${&etiR1fvYD5sq;;PNB#~6*3<}o zFZRNNLh@o0sujxLj<Z;F9xHxru?2}bil8HlJnY;`-d(j0EPuF{=fdQ|w2sy;^vzvY z9O|Wk>7eqrJl|Oz#Y`#Cq1K*We#)Y}W)WW}$w2TmUg^>(`jC*^%z>}C@{tD85#Uch zhL8K=R#&dKbm<`Pf3I19?W1+ZDf>|NubUO-;o=2oWqiARtb}Ljrz6eVUI_(=GCfZv zxu0bZTX5R$xeuC65D!c@j2HF$rb>wfP#g`N$gk4l5#IfM_d)B^>=<YCTW>7<`G*pN zquJ$ByA)Qa&ZC;K1I9k59}nh25Zkw@i%pmMxrVuL^y3~s6_apuRkE)leh&lJP~go$ z^&w8@_e%!S4~$=#*q<@0IE>)EY8<k+v0jEl3EA>F=Xe}CgMp0>Hq4_BZ!E<UtD54x zD6!8sW<3b*X^=3_uWz`9x9vXzXLcFNK!8K07ZNod2yXXsZ+@&h2e%<^PGsu@p;3Qb zKJ5NSVdLXK#&b_4_-&dSm%D#}A~f^E!0u-Kif+k`_Ai`#2bzLf>mqdN%sY{${F@4> zyIB+6FJ2H!zGF?6uvR=8INoie7ouaM#cq#!-aVLol}lAV{H0;9m}MYhUOdEPF8t8f zhhU8!IO07v-m8%9&%-N1ZhW5jG7Hx|uPnIS=FO$6HR9jTe*Qx}>b!7=F-^rP!X@XC zf%Q>B7o6DSIJzHe^9E~CbRj$>!(9;&S22gVH8Y7EX!ALZK8540+iBLTwcf>r=8Rd6 z|G0?p<y#o9WQR;=J=gUs0~$#;WlPq`ekfC$qiu^!6_$YfH4;K!l!Y>nVTHo0Sb+J4 zNx=IM3}Wug<H7=x)^-B#krA!)g8W5BETWOX3kLDh$Cd)~WW5P+`wR0NE#;0o*s_U{ zOq*mN69wN363J5BCs!+NZ?gNFyoo}>I)^_#M{a%d4lmOMDrgu)Th+Ybe)cvC<={>U zz3#CE1~yJh(E6~RXAvm^Zs16cd2-9?Ffaf3kmfYuz$PUqBA8;8h3zEbQ7q`bR5TFr z`NEkEUu7m!XRge_+eSBp`T;py-lXF2Hk|AsnM)#HjFq5f1IcwHi3b}W;FUezPTc4s zj#5tSptHPMCgA~p&9lw|0K(sCiF!67FMhx&=LW3)taAb)<|0h0nyMwX%4+yd;iIK% z;~pVe&U9+9ugLgm{M{kpPhC)i#z&$*yjKwn?9pRRUPbtaEUo;eS*=8sioAR=7T>r8 z&9_wRo>CByS#7(kv}F7-n`(<K%2GFyx~r%_l+UI$TAQ&aa=sAXUfY8BH2L#<+&-QE z&_RCXf()0?{A1`n>1|<T->dMN>p2j&h)I0voo{+T(!STJn(GD^x?5XYtL|j8%M#u4 zAH_ageEU8^*tPQz7Rs`hFFZmf1K`xmq9W#y$0A_q>RMg^kp~W2AJzO3lVfh)ltNH{ zp6ZDV%}5OfN&ZYZ9cp?um7Mk3nR!#%A;or;mP>0T%MjKjm+a2^mW2M01bpA86JtG^ zhWdU{Uxi!GhT3o6uVa{juGh^82VMlC7G3Ue_~dM#14IHuTEHTmpgbv1P`*D$R^jQv z`&6f#-I>$MrdNLNRe}E~o!!9v-7q)wi&VO?+@#$JrWq+e1K%FleX1Ob%C}Qp_ddPt z%=N*Q6g8;W<s3N=!fG{ccE5E^^}vB^f+cn|sNAEiF3o2F0ecq3y~7tF%1KmOnAX^S z>)`Ip-N7@ob!9#&z5DCb(+d^;@fW$izlpxTPcFW0;zhL#d`W64tl3@JlZ_BE_s7c+ z(W?_#Hy_<rFSLTzT9-DVeq<#=f9P9sCUq}NH~DV+>@+-?CL_Xmj#25#y1RE`$&fX* z@z{~?5~A)JjS3Fw!ZIQHWeD#DgUk)rraTa!WpFNLRIWllI4ujoz_N-g`M&}m#VhAl z>%JwZ+pKLIBkdAyW?WK{eRGGMk5FBX+@9zayyb2J2ho?Lefs1ei+qKMsU)E7)0uO) z0<6A%^eH1YGS0<!Y~Swk1CJ78EwifR+$=ug<<_B#a>W4bE*A6)r6X7_ZhmLSi3atn z>0XO1!z4X&(J5+`>D1_44!AA<i?5KapZeUMSwEo&-h`_?1a?%4qZ1Ozvo0I*RTO?E zmZ76*8K<L~*Sl?qmEV=RE6EoZz-a&nPJ>p8xx&Jdxe&el@qH0G<kuO<tWj33LmLjX zA;)JY)dlA)ILrbXEQ=x`&VPz>D}{d>LqzF+x_Mdp(GWuve=YN#K?_)gTd-fYP==f1 z4Z-W9{X6s(e{VzF-WvuM(r?lz4pJS4s@xx<*l{SEe#Q=+aR|CU$WyUnS8#tD6tRU* zKRCM2UC$K0*dskgg;@8<mpanv`t1(K_d$SLuU^SzKR7?@<lEs-DU_8wN-`v4d1bou zhh=9xP5#4<jwSrN&U)e<kBrsVg_zl2vYgNiM%^&(060={7V5tPhp&(j;wm9A5SVNg zU7W*9;X@TGbjQ5TyXw7jF+`UL`+KWcRDr2N)aWdFcGK#iv)ONBWZCs~6ynMxJlUsE zetOokM9-8ZHlR@wp-1`+y4e6%tpl~L8m{%Qh?$@N?fbn{JzU&0=qPp#+2u6vD&8lr zLj`lFlU=U#@UQ8cAD`a(+=7*x3j5=HmN?<ZrDCJJY!AvVYN4s;LN59e6!#BE<<5J! zm@^bl3Vy!k%|+bH>A88=RaapCXKno|Ozw!~>^`5Bt{%bjYtMul+jb(tV~ItDmw?6% zUg$LnCM9pYDRkee+Ts#|V=kC&M>O2~l_HfL(Ac##Q*<fT34hB~sBu^>o1>#>qcd6A z$(L$4|Aty0-d&zMXPorjGe6|&d^3={gYTsu9bwk2CX}S3&%t3^7fj+U^X2>2`;-m5 z*7Hbn>!W>WsI%KcuKCXa!QX>GEr_k*oaNM)S-YuRf(gu$ANs6_V|jCaBj3^T^RREX zC+Q$-{bOAyCEJFJUt>#l-lIdjr-s~Z+OemvBk$>(l_QSgE*1;H=?8Fh{S<EL3CW75 zzt2Z}uefX78Kg=|tR@}9M}RpXe;qe|CcYJ48;I3#ckyK`atrPkPIV(&%T6BA_^*03 zeU}P;n!bfgx={4-Qlfl)P`xIfkY*c79b0{cWzE8+wU2GE{Z8yp5xq#)xHaL~Zz3}m z<z<h??ADU^jgRc-qE9<NrFS$`%pZQJ<h;?Q<Xj$s`iR3+`XAQShFZ9;U&3J>D}_Z^ zc<m@Q2-X)p<%X?$1%z+On0n(pbq1Zm-|+4xzL(>@fA(|l_llc4I@3YS9}hdu)`o8! z=>eM`hx}EUx6q=2>IHPwG|(I>jHWMzg6lkFb79XrkzI+MY2YfK`9kr2x8ot-J%Xw^ zR~*+iS>IVJ0Dm2V4ufdP?@6T@?(rloF^*%(dxQQCvW*09n2-}fMR7c4=C=07H2a%Z zNz!#R$FS~E`u`||sUAa?btCmd=956?LH_8SwP27&PV9B|vhk|S?Pavv@?~0cu1CKq zPTLKG=N|r^$YOKd?ue3Q&DZ_B*YBq^Cp8$j$|XVEZGk@bDgROTD)!<wJMYgvS=5MH zh|a}GHPV{=$T?2Vs(ob%Dw9s9h-A2De|lz;#1`PtHHl1*bCC{mw8`;4(Fuiq&`0K! z_7Ur*#Cjxp*Ztr<LBa_?x0!ZIXW3S$Fivew$-IV|3*W@ww!cc1x6flZq?Nh2eg3GN z?e%t0s_xVaLmavixIriSpb019Ab}BbN)}tRXH9Tu!OVmn<1SRIu87mPP`TjojBlBa z*^Ah$Z39e2R322wt=&+-4PHcUn|d~If<Ae7+Fq@ht(*tunUkJFp`|sy^^Uc4fp$A1 zU}`uiV(L}-;Y+wx?aoB7-LOZ3l2Ewr#qYu3l}tmroIJX#g@TGR&;8UZH}QzzewA~< zfHmt)%rA@tFlJb?0-IkkeJ}1;WpaubGH}A+W$e`6|AtRlU5~mUN`=sH=UIFvX~7+d zKYuVUgRgQTldU9QOS%H<Q5A=sZ7aqFmxOk{p=b;9b^RKe(u#@b!%)fI>WiHVkNS*# zrul=F?;u8Bs_!5=8xl|xJumo>G3PL5t!3P!1?@#${KnPK212D)<D_q@W(1Be<FWNu zKZn@Ld+{_`ZyS#VL_F(PC{!0tV}HGr=p-arO{{Y20<7LVhUXz*df3*Kv}x9daM@yR zX|7&@-4_=-MAl3WXN0m)5LRo78~<SMAbYy;ZO)_uWJvLjrVU*gWJ<0>`lj<NykYWh zG7Cvc>2TP0CET-5Vq`Mn4VUU3bZH{vi*F2lBT2{fw{|E%?loSdxOENHc1Sg6k&YRa zLyD2D>|Fc+|4)*GPIlgsP=ldro=a3FhRj0$REzC%Er}p&t?CEmc8v4}tpkdB#cvLI z*>GlM>WiBu6Fxmp9G4AHi9=^kb1Y;w-k?6$HAHDVv5CiuPnesxQo8CQN2@!!2R~W` z(+ow<Ua_)Vh#T{X@rQp?Y>Jlds~jGE<Bm>5>83j6+YRx3S#dIp+8=w2C{KvWc8i2t zqZWj9SZ>R<%o@%R5UHs(Abot#Pv$FBBm;9~Max9$1;}~SI+;@sM%RTw4yE~&Y_R=h z+!@Xnql3VNoQe|%7kNjT0=MM?)AbWYS^8X8$!Twpe{T91qRY!_loTwY7|%G2hn_Iq zG(IAarGi-ItA(7B6koAmV^ozV8<9Mt@8%FP;A>9Wg=>nYQD%xdUn34xblyh}*L;3t zxS*YIK4`_@$)S6f?#YV6>+0(2P+t$;HJwxEaMm8J2t!);wzBiJN>FpAB?++=?Qux= za<90^{0Rxv(s43y3T+6;5vVbpKu=e^cK+?OT;+MalKe>LS`Bi6O<(3$BdsQ5D9A|- zMtn;LdAI#${)7kov0A8jZZWK9>~yBlI17cTpkz2GnPx2hkD|4r`FuPu#dXHYaBKRQ z?_;3C<H-gz*|~BC-y5^HQ=5?|m1e1X)5fpbv)DgYK4L{imId@gD7x?UUE!VKuT%=) z`70p=gKfwskM~jgJ2K(RyPm3h9B`?iB~@9R_K`O(*#0l~i^O@sniICe(I2d!D*~M$ z${!~BbV$pO*->I*;B_QLo`$3{yH?xAV5Kl@#*p^FO8NjgDA6>?yQgn0e)eprVJ$vV z#t^+@RMpwf4@<LG!`KEG(+JW;&1Zd~kY)PR;&1$2h9%$HjijxO2ST4Fd$^-x>wKK6 zO<lJn*@$ZLd#%1%UE+Bg{DV)}xyzh}1EHXZI(Rg>tmLg@Ki;>&-Z8PD?>AGMSJS(U zQ-?Rq=tj`ch|IlA*{gmgnNu#u>5a7BY?%1Ql)3Z{-yqKMey3|0>HQsV{&YZyug(kh zV=uCFKL=$ehcqK~Z%2oqs0&?AHIK@5>#y<@aE~i>T8;<>3aXLW7oN891;@z-_-{AN zcs;YuC|NT-FK!ZFLvSX9?bALDEJ+i;Y_oBJ@4<{q&YMgI7SSI82Z2?s5>tT2wo;U^ z!KhU#EV^omrGuV(&S=k?<!>4%y9Y@g@3Jv6lzw}k<icB@Mn2@9Dh@s}zmOyc9Tj~u zpO^Ur?Qtplo1iTf^s&~|lbSagp_D*bH?$p<8%;KUC!GfFK3X%9XYJE!f)1HqSb^6S zC2M@;b7SS<Hv-+3r+-R%L&N=D$^1PX*VJ6x>zH=^joH5$%!}N0zqLmNy2^HdbDa2| z_BaTipC&xY9aa<ks|a%&NhZz#&mdoXFmO(LmtQ!wdGnctq-ME>wENAx=P#fR0UE)W z{g1iUx29Iu{|*J+ZIItAfVX>FUN0DJzrFCNu-oUI`*hKR`g@xuA1joKwd#h>S%&}Y z`>Ov(VFo~#QI;WJhF?t>HaEvV@_1xf(~0-fE{UFh^o$W0o&Nsturpnu@sqALR^#~w zUNhSn2qwO!p?gN`VV=;3z$NVK-k@26DdkdNp@+A^-yN4uL=x8%R}>67DVfZWb8)W) ztN8#t4(;4R*F^nC(IJbyXS&OPz0Nn_cHde>gE>m^>uUU8-p*bK3>vS;l=~3pTJd_H z^A5yuZh>VUN0OFMc5rRq1MOIUrauYnO-F2v_5BP^&tc~SODD%jC*<W=>58G_Y-;xl z2An0wi!*y48OKSai6aCsn3&YtT4$}rB3p{eCN|SSM_4QUHCkA?F0%;!yR%kAEWrZp z|G^Hp&;&L&agVtIqxd$TFX7dy9DaEJQ~g&;FZq!1Cby$dUg^9y5z`HPwUP5hor0a0 zalEB#hT-r=7)x3lSY6GXU=gJ=Io$r0E_=9Z$=cB5S_j=j&<p;4is28bA(6vh({wtr z%@z@(mM(CHPb2e|jbbbdJAEF090{>amf<Dwy-u}u#j9^Pu2?ZI%vB=*KMY6p;gzG$ z2+h-|l+RiT6)T(Eze?^8{aI>8+}SYf_?skhUw#9-Jp~irWvi-|I6y`_b8t7pd23t{ z<<*jx#r_nF7b4%%?<I*}92av+>eVK%3YFL2^c&4^NboAl&|u>7A8u61L}lK6-c3Q$ zeqVZGh|dAmoAPTHeF3;aZ7F?vQFM!WZGEg^PJ3Ezo*8$pwocSkg^7W$!rxY%m64*N zzNmdW;N1FM9rH@5UIF|&ZH<>F_f?H>VhXe|6Ioq<(NT8Ys?K}@Qg8O*@TtRdS&{(` zIrRSA(*5G07Ky!4>123UB&Y7-<13f3*V&XyX)10vT4L@R&1onUcDE+3fTT18j@4&9 zim!4@Z$MPEYS_Qh)N;I00=EE>V#qyj-zu_uRGd4Z4m$jy^)K{TP&n(nMKL27TnoJR zR}OB_?Dl^WtZbjg&okdS&Eo~}n5k#n0-t#iB`K~UqJ9M_gPepkPE(C*$Pccpuwn;D z%gQ_N#Nj3_(Pg_Pqp%q9CYlO|>>ketV+l@vir;2?tobx~Tv|$yf4kYu6Exj0NYfKE zQHMp?`B{)1XpT$heNdU)>8K1{vhq*tf^PMN2-wXT4c5QOx>u5-Lk#VG5z7Md6(ZZD zckwS{QJ1KCR<H57J>hGC4scSM4vTQmhBdzUJFUfxx++}5HB7-7YRcheGN<E9)+l`L zKm<6ns6`C-r0=V{C58`4R+h_OG$fT)jDNnb7e8~zn6R~Tx0=|}Ip!UCRiPYm7ndor zZj;nre)HIqQ6hSfrSS7D{v7j)c>h=3XPN2#f;Gzv%S?TR=*wGRpD$wAZaFuE$wKn( zCPQ_4ks5t2*yT2D6Q@2P5kW@soyUj*ltvz&;5l97%;xA%t{cO_<qgUlVH-bpMu}QM zj<}~rXbz&I)Si~-njxc7!cy8-l^X&l#*3fdvS7Q=^w2j_9B|<Uvw(VN#CVhP(4xe2 z*Tqp`l-RrPR~GY>B`3Q0bf`(zsz;LTkRo$xJEexm=cn72rCOpOxej`!{Yb$aL6Sky zGn&$}s!7AX*q@ieqr440riAxmtHvnVi!HWA3h0t@#cg_Mj%5%{6;1Wt{CSsaua~f< zpggiae{`J^OozcV%oPNsx8JMZVu0~>K1eiOxty#1Q33^oY2i{c|1wqN2*B;I+Vl>a zR!N6X%8zWFfo%of5@2*Q2HyEFZy;QMUcLc4d0!|mH;gs{@|j=nuzcUSN#^;}?v#7j zfym_4HiN+Qa&+n4;Q0arDFvT`XRouCu==_5{RUFv;<LborGcg)i9n~|lh>}!Vbt6Z zM2+Qs<@G~qvqIwxDiB`Lr+x5b5d;NKO!DghALsThc6otm%5O7qW)9Vtox1TN8TIx? zFCyVGzGAn_8T3@#INU@wyGvbIOZfU>FWbAAViDr`jyH{m-tH4jO&gKjh>z=##|}Gc z{oHY;rmQvC0SBQYp1jkmKM#$DYdmrjHU&W$$yeLHQte;`0bsFsawAuW&=fD!<@EB- zExO)eY~XEQAKPNkR>Mqd<=pp4m5%YjN@DJ9zUVLIIM{xH)xoGLmErNXFm}}Pe-!8| z&ZW}-WC-sk$Fx0#@MtO2*V7CmY}TaM@mKneVnT+FDi2TPi>;-ZYbPd{Gu~cBvNl(U ztK1&;XQluLfEh?QW!>I6C`LK4F}6<*k8DkqJ&X)7vDrFvW7wr3hP90tzS#ix2C-Iu zIx81O5;Dx9KmN!Ao;aDa(Rk;HXQevjf@df{VMbj$3T?J@KXSvBjP^9XuwUQ!s`@vX z-nfyi78We|+Yas=e$EqBMxS+U`^67A-`j__ex`FsSSE09VdQ3C71LfdY%cAC)jjny zB4tMp8D|sE3q1#!8_l$3?5D6Ac^^;zU>W{Qd|xvO{f6@@Ahr(6$zmZc_5+DVnbW-h zzy+>ZR?$$a`Ql6qG9oJVq4Jv(?=sX1oEC?S_v#Pr&<^NZFp@;U1;l)D5IMu8CVi7w zRSwW{-bK$By06<g+pz?#WSd1B{w*vi2O`=FHq5;$Pg9kw7wz{l_o8pd4P8^`_yz;} z>X2q4ZZfE?;TDaKJr#esiX3;)Py*q&!<;GQ3->K$lr1Gj9{sxXf>_~H=APf(ok&2c zrc11hGzA@fltD=d;MgvD(!HOWFl(lq)?hVrWpd24h3n>v9>i;#v$?PmEW$J;fF}9h z)jpPEZBuOlC0c^1C1(OV^27m_<@olB39yE~S1m9N$sO2xl=Y_Q-h3UWnp*NBFF_Vi zSZ4cES?KT9M4nhH*@0Z{_0e8<e3MfXm5rH3Rzjz~$*8*c$<WX2is+G&&w`^-$QI)D z1FS|i$MB!MC~!CF%2qMNl43Hrvl>B+Xp?(a-CJ9HZEGTPR)p5kK~7%J-DRi8k`A9w z@Lig)7BCB2GtHIyC3gir7ilZ{!eaDu^Wx2*<~eJ{p4ayS;`-E+p9v}7s3yTpT4&xW zL&XNkom)l)PR{8+Obj5#Yn+G=PZaGDQ-gc(=Ey!LIyXxWEA~YCX%)2ls#r&m9l>Lo zYtZIYo!aZtOrw)e$qBVot_I~E=h}zrwr53+bmAu8ty2_-gYLb(=9+#hXz_Bxm?PP} z23^iuZ6$8#RK-FNO?>O7Z*Bp(UGHZ+C#y$|*!#?{i?6FNTeJ$q>N&(eJwmc(sBqWo z#956Sg_n{n8~n~I<=i_AUv1oJC>$Zaz8_bT613cX4nB!OuG`$Cb$To|c7UVbzTvXX zkylzc1-=s_-j*5&=7u(hydHaW3U`|`thKFz7E6C=cG2A27!KnWFU)zuF<<x4GyK6| z{NO3Rw?@N`?z~{`auuyPS{z*!9%7cfxv^J86^TAtn|~CX{UmPLOhFK6=*&%Lp9Dt~ zn{q&;2d$kHSyDZq>2GBLhKqpKenw}9;JhNZS3e{K!O$5a<5B$j3!nc;L-Ka}IO&U5 zvCFOMq`5CMd*c<17Yc@?bI1Vs;gMz$z2A|Cq>4ba5BLqhFGz12T`P28un4{*7ECiJ z@W_Zup9)=Bs6L;)W6iW@!U;ZcUVujAJB-5RvKeucuyyixxG?`Aig0mnE#wZIDq|e7 z-2OmKWCo!oguG4AR;-i?G+9w^Fz<2yy|>R5w|Dq)zh3v&cz7|US8?YMG!R`mACqmo zfov6dh^2<8-esahrp><=&X81hy%x~3eS-j~NK+>s1F=w+c$aypC5p&F(vLC%dva1G zBeCdGNQkzb9ScFN9~QuX<uFMKL(cxgN&R1rlFa<+$aXcnkJ6`v+sXaq>=}fYdCXUh zPG-*DV~7nCjfT&?J@WrNH@<^O9cfI7W`Wk;d{<&aEGlA@VYql#BpkO8e1-dn7GcS4 z5L|x+faO8uR!?H+ld1lrXhH(rxjUx=VrSqpwg)+amu0agN;Jqt+o$mPt$4uN8jB_> z(hS*NSt^Y2v0Cmwe~x8%Z6HGfQ3-e?e&tGzC8o_A*V?N4TVE+`rSemsC#woqW<{o^ zv@E(#Q=4*QNjXXp;ugRz8B9fjFKmUyD|!~6E47t&s4f97eYTo(r2`oqkf>U`nQ6EC zAP6z2aSA)DEg96_;<Xg`g@Rvz{&ch=+Z8E7WeKnOL&!tV(MbWUjy0{^-Nh<%{-*sW zu_nxIWk42^5uK)RS&Bq!iGhJ-BWb=k5a|jtQ-yODE~#iWIR;28fnDQG?#{ZA4Q~9* zB5V7few-_a5XxhjFAA&$=<F%yE6FddQyh%HI`{e8hsCx{3zwNcEV<}$&59iDn*ovA zx$cPxPL(?Km&oEIN`G%SFMi3xd-AsZq^D!f%Yjy!>Z(|G7prAo<*pxBqA9Nn_{M@; z(wF{rK85H0lf&sXpMB>kcbh)D8i&YCcdAgg_gSGe-??Dsy{TrH!{@Lmo5#IDm79vz zb1#+HbSt}jY?AdM2Yd$M&hBla1!tT?In~=%ri<5pQjIsg+rG%?VK3qhH%dM`9uf|{ zs1-{&{X;+re=ef9#FD*ZbHQXKm}V3_nY}ZAv6|;A9_+oBy|ci{%rq5FIx%px)+NT- zJo`(v1T)rs48EgY=ak>8LDCs-{Axgb#XUr4T<#^l(u_^P<WC-VgTA#LD*4(w4UR2L z92Io2F0wnOd_uIxS`>v^@p<?B@tX03hTbCC;$>o0bbgyE)to_bV~L#2R>8Hn0+NC7 zSJc33>F8<-!=}#Lk<sc-LpKF-BLaZS#g6ngF=Z*w&yt`xo4fI9&E#dBSm|94T&0xm zbqD(I=2N~;JwCB3h1&g9<S4Jb$56^kwlW&gMEOe(cDU(&R`kTBHQ37cGs+q9!ros& zI}AFVUV=&Ghv|IXT<;1~);OT<gawcBa$b|{QMmI}CB0#2myzp=0cE^mUXEF5vbg7M zof{urA?p#`RIe`+1sN3go(~DnHA?*6_{2f8;#qGgYg!wz36GvIBRFqL1=?cWT-`{< zXHRCf`O>*zTmFx%ADVIv+pk}8GYAYfZ{#17W~fZ|33FS@KjlAt^=;ASs83dqyTf5j zX&O3pCSM7poiC3i!R*|R;mwmiZd7NL&~W#xCn=x)g1<$@=1$t#9$UZ@*RH$xV(<Sj zkbfVtX^?QfJvEL0w;HOY=cu*h=h|N~G3g%IfMyrm#=-O}PAgr2@WuNLJOl4<L$jSH z4Cn*Q#~9TEi2^0BMoJagjsc5b-|6x0BQ6ID%C-vh*0A(;xzG5PQz_I=+BudIbcu;> z_|^U6W}14oXe;mSOBH;A76^M6*!3Sj5KjjD3}GE@OY`~WRXy>_h=G_k(BBKjFB*BJ zN^QF3m5pHr$-WcfP0|<`G2y-#{@vXBv%PZ3=XW1o9eM@jsF_N34OfGGaf>urmwyn5 zZNYo(LX-Y@A>TV<4*QuhSw?fTD_oFzZhcNiUhZ5O6br$iRd-${@nZY91qZU84PJGH z%H2)pnfj>fa$d(=pDxSgN?si~_`~_OC6X<iV5L~I>!~XgOigh0&^MTvRLJSJAhg}P z8U#92`{3!bKSTc`zr!z*JHI&hQXx&M0OvIr(54qIXq9*<|FRfSQxgF}z;6e}YKu$) zTnQ)l<+Y*@`=Ft<03U1az43hhGrzpS6L_{6{ZZw3hXQKur_yLT>>!;6c*TE?7O*|V z5d4C_(d!Mhxl?cInpg5ire_qy+q;K8H5s_SAr3cqNZkQZzI)%u$ggsXl<a<~jqRAZ z6Y;&F@y@Cb)q|Q13Tjy>)m^|1^~zDN)9LAZbA)ttVCIx?Uo4q7e_bW;`W%jnG)@$5 zoaRZ{gU%Ew*K&fp32EBEUlI2*;aC6Ga7x6QCf}|zH3hIro0-3D!RYXOMqmNG<&Ycm z*PRzo`vBQLngn*A%;+R4nDe%-MS8u#<+l6+&>=@MOTqj%noz&rHfeD{=KTM5<`hi* zM}bv>ZKdB9xXso-*m?4>$Vg9=4t!CR@rNU7c$r!TreY@jVYhm((EV}SQ84VMPvW;i zC7KH79N7+t7kw(tNVu!J)xwthlL*Af{dXvr$`2M~60s>8zvUeDIeagd0$?Mb@s9Ha z3lPoGN@aVxCs$>bv@W`S|3|S(e_}YQHSl#in*kwCs!H{hGf~9vt3}8wFq|i?I|t9P znf^yXG(VRC&5f(3xJoUm@2Te;tMv{qakH)GR&Ny~&$m8;(jLZw=4Ni(n9}L7ud=`_ z;2ehU4jY*zz4-9T(aj2b9#K+$Hb2R*`mW({UNN>vZB8?(#1?a9;97uFUJv7j@o})v zwLqtAQp`6+ehsg)%*q6f7l*kI@+?IZBNvAtuR&XKH%I%XA8FT}CGHpf**n^Je$5Tx zr<lMYLGk!>crPj;*R0clmAVl;S!GhF%8Pi756k;Xk*iP%men^S7K&a0>0QL>b;&X6 zfBQNZHAG~u0*B8Mjb1;@x3~?i*pMo$VZso<x8&qu;{fLM!F*{DU%=sS?vq#GrX)h< z0<pxFXm}V+Oz1_b-lZF6rXqgByJ<ZK7c6`SAW3Tc$cW1T0)U<;W3v0t3C%w4{m5s} zc~(Hul_tiv-^^qoY4#sQJuB{$j@_tP^Eh;{tP@f4<S>7%p2k`GK2w-NsEjDdz;+-; z&cKKtK!tlWhFT7Ep6NKb0dgCIruE?qO&)-951RG1;j&Guh3;NEkvTZ~;Ms@N6jPz_ zENIdxLQ3$gwivw<XbwRtfsIddzdU;NwaceZF5y9RHC+P{01u;WWDXrDEZns@Rf696 z_;4RRa|~WXk1FI}x>*v4?G(wJc{79Hu};J&TSJc$MCTpo8_hXx>I2cQr2k>vX1=8$ zjW-<**hZ~Asi^rBxC%cu_Fv*M^oPeH@1~0dqTWBh;z3Zn*Z1<Mtm<|7Y4Y|d9q6;Q z4m{amT+YxfZExBrpt7DIxs-b@m~*LQX0CEz;;3X=RaSUsbf_+F7++b&SH#pc@wf<e zG+;!AwrL2(7nz~ZwOU=;qVd!}*G#gma-lwNug(8po^IHgQvVbPZm|HoM)?*uiClP+ z_01CbVr_EDMh(d-#M?Vye5&rT(wnyBli{f+(j5zH{lr>_1p~@!FLmiO`lwTkXwnqf zDqoJbNx+kQ{ysh|%UHekhRNW$VF3Qb#Hi?Qo#CI6hUW}*^)5I5a@#rFvlC%2A4Njh ztzzsH5)BU@t930T=kTdCtx^`U(ClipiNcaYe?YUOGTB*e<)6btB$<;nQd05i0K=H6 zRQ<PH&0ku-;i4XeWZ4Zc=R1s$fiG%0Q#^Em!>BBG!H~6>oOt8ojrtIC@yrEJ-|BYu z0VkIw#zWNwYg!buux~J5=Scasc0XRWi~yzchu5ERZ9gw>kOK{z4>i0086}p}enw+> za%T5mz}(WZ(D4ryo$>b<gPgvrtf4V&2ekIgV`?J>K7(-0N4k8eH{GqS&()9AZ1W{B zR3}o;sUi1@O_mprf*&YN9pkSvzcHu$REXa2I2AU&;6f4!5}&AM5XYBMSi^gIiOcm9 zB2EjCPM$hZ+M^U*|IR_rE0r6q)yHJ3yaQ?<*{j^$CDhRrmmXuwMC6R7_4l!^BG+{6 z%w;2Y4sdBrd_KQZCsb#|XD^L61vuFH%KYqMEB~BUnS)Wuy*>38e_s^#Mt#*=u%t(I zd!#=5R#~?t)mAl6<CC6wa{i~l@+<Y{v2ZHF6kl);)!Ba(K!v^_z_RfRXfTr@s(sfA z@RH@34x4+n=aJGNX+oxpgA`YC1Qv3b{0*G+d<tN|Bb|PfoN@jx2I1O*C>TvP`sGtB z|0NEH>;GSdGu~w7+>C2@Zkk`~Q6P$0`=5RH{>O<n^uW+ZspTughPuh+6_O>BGd)X= z&r`1=rzgFt^6j!k9#2-hTv54|5w~oIzYw@7o661;f5{uVQl0Hw#2r#uRVH#$WL+U< z%5uC+sSPaf1{&6b1~r3t(LX)9<-51mhjf1eDOg+#u<}=}{GfdB0YjsRIG#8_4>{sR zFEuu%TsM_b!6jVKHH-(g;a7U9qg4EtD~io(%1u)PD(rLo8apE@)hx2h-lF>D192qg zraQIx>Kcn^YmkFi`Q;rso7?D<Q;mjjsU!U;MSb(j8@xY|uE})tN`T1~fxYeyT!D7& zqekWSK2Jb(I+u+mi1-X3%`PW~%h(%hn4muRKBuB9)cN|DR+T^D!guJ6t^kYph(~Nw z@bIv%;)?-rN_YEtH*Q&$tUEpF1iF&s4_F(G0lF%{qWPb|KFKug5qrsVrM=!@aNdh{ z8im4rrl}s)rQENbhT5$sgYW#<oGCVqU;nRZ2Q5bv`ps{&D&Te;qgms^=2Of_BY(RX z{rYkL;Y;YYN<;9r?3+MsC+RoZ@JAS=7B>u_%%lX8p3KL`N>%FX0a#>1_85q@3d@MF z?l}~8im?VKYbyGox3E7V1Z^+o@c|X?vX(j;<3;1&zcnlnD+6kFrxRX!F-;Z8v1$LA ztIhY?B|PX3WQvF$NmEw<Oi`b7XdiW3b$prVi|mj<krl3(j?Gz0|Na@tvzdn)Y*%jc zhbK>F3Xc&CTW*&Ex5uW}Bd!;B<H8OLmj^Z8lT_(*SQO(}9o@929lrkKq*~h@ArF?V z!@LgVTuum&Avp;Tx>yyr_0zi>s?Kby6xO2Rp?!8!U0c4|%!e&Xu&(XqpP63(y2j^m z?#b9qxcnl8VbE{EkF)<#(B4hcg;|R~BKj6+E(>$L995n>zB34~s+Xt!!*(KSSXVk? zU)`vB@5LjmDnKMo<1t=~PFrSeS{M~{E#zAmNi7tEfZ31jhV9BcTRSq|TQs**o=;x4 zU~)F5L~4^GqXcWEYzJaBlzE}Qj}V9Jh#`q9Kkl-f7&<EOa&X0^=d1Q`=`L7|5MB^$ zC!hXoDSQczBH3!P24I@2F|9=ow9BTv7UyTdu$^>Jm+f%X0Vqs`$;2d!ZkCU;aJZrN zF}<7l30H>4xrRj`WI~*?{l%i*Q+ik*irVN5i!K@wQY7&d;v0JOB)S?M^bVk*ITIEW zNcSGeJ8JU&Ch6#nrp}zi&TX0<mX5{cbU-oSmT<Y=h2F|Ja$LzdZg8EzE^f$l)e}Vb zV-1!e`qT)@DSE1<@^Sp7)9~OE&48(xCgc$wM=xS$C3E(!$zp=_0xYd^{?}q6e@&xl z^!sw|$2Hxjl>~xC_3-+-NX*8xyu>Y41?*p?u#0=|2`65p`*yXT0(z`I)LB^jmg|lb z=O$6C<`#*h-{SVl(*!*MZ^p>C#CaMEWjah8p_bFb5tA{hTi=&X0wG_Itb*q~jxUz{ z<AHB&9^khGpGGOQYHBmy$f(VK0cxtad*w<#?vpcxWU5D>pJfIi+gjhs6Wg`*S3*AE z)>J(lH76R8r<v&Bx7kNMD|3ii4HShF_iLV=SgZ*sge+H^NIZIp6SCbNuYl6Js}KCf z_pZ_$;I3@j6I2rMjUhjQkjFh=U*W}E)ce};0(wLeb%%nWQMDgSHS*OQNp+5-y*Thr zQ1Fcd*fw}B&yc2UO_vks;Q8GWY%c)O`&DLpau^snPR<%9X7bq%jvbr<Ork;HdHRA? zx6$9?p_8;y&J(}ia_9o@i~Mt1AD3{oP0UDz)Ml+I@N&{g0-Q(}%H%zqFy=xL<s~yq z<DF8vYg9th1+FQlQASqZ@BDHZ{ri(t&0Y9_HH9Zxsg3JF+9BLU<Utt4=?Q!YZp|hS zrN6V?(46yJse={)xKH98*3}%*W!Xp7o#TxgwAEk3#v6S-)?z|(Y9DTf=$ull+IgKh z1XsXM`;P&nkW5=Mz07*CXe5iqK_Z?TvUyeytjfKb>|>u1!+w=fDv{l-sJ8!73(M0= z#h3BfQ7@@NmUKheJ|yh^JSd6VL?lnB&{ij4_OVu2K17gsnG$&R%pLV|nxnRre`*hh zUe}-ppQuB~-)_)nn{x#Bh@TanWG-$AxXR9FJg4CB8|_z=|MZ}6g%d^D9`}Lfug5U0 z2l`xw=0sYYt)uY$kqW#n+Eq-B?d{LhSJ<vUizc=o_CRJ8(}mBC05@}@sjylDK#`vz z769SL;#3Yc&&TWSZrYrJ64PJp8o?OMy`83B-LqZp?h0WR7CnFCe=W+l`#F5ev9dXg znI)3?$Kh+*Gh{75)Rpo!cXKa$+9B@xOP|~Y{9WzN<b9=3IP;y8UJ|{>h4ET)(W#W? zeDF#dWZ|{#R50Yy8vNIJBlu=>4r?$>;v$agRhFcFl7oD8-nx{dRAe^I`xjX+GVXB< z4u(F&)|oRmS99+Tpw`drHKgl;)U@%-Z26{@k8l8zBi;R#^I5AbHrcpxB>vsQD2;Q7 z>i@AsB|HGEFdDH2**l$w+JWD;x~JQWwk(+81&up!?;yeP={U!Xbxz3p<RAJMh+;RF zMKf*j_1q?t1W6?E=fwavxalDK{1DIGbdYs8Jv9EWRp0aoKB#m9*a1|X$-?_yH}xL1 z9O7W<s)E-k?d9RLo;mridTL8vF6fN=CF2eR&~H^-|D#~AH2DRw#R-1oL{k-;?PTrc zu49M^j=@v8$8H8J2^>Z$R7fwX92Tyxv%PX`C%df%rhn5|@eQ`us;(*-7vO}1AIpA% z3%c3StT4QV(9CzpuYfGfGMHx8E2pA6i4DOW)z+_v?@alrLgL5xp9?<z>Oo-r;%Py2 z<{U}i2^1KA#1@GaoI|$L4XBr2Thb0>&p??Z)H%MIYb|AgdYSj!p^|t<1^a;l66z<$ ztoJ`1K+WB`!jq#-yjuQH6qMX$c(Ut3gP-+|f%dJJSIZCUw-5lv@vr(!o<ao2gBe(3 z1DzV;Ao!;B4YC;jHa~Zq$0N<CZ(yDe+vw2m3!p2H>0jud$0^Sme=3@H@7}`+Y{!2; zNa-)bJu4B5<OeZ-nVHV&a@o{hlsU}bVLu(B*3}zE-j7zd{emMlUePJlTy1EN+kxmP z+!k|h+=Vl$;yK@FBQV<4RuROa8?v33ke*d7$Epye_Jr_k2UP*gW@?b}mJ-JEVAxZ- z>eE?tDtEE(c6R=xpP`roSbfdCt&aR3McC%3UTI)t-j?F<LEeW3>)fLXU309#9X%yq zZcn8-k|psb%@=2~!Ns9pzQsy&j-@erN^6jT;M0j|;xR?w{*bv3)7~|`Y94aN<vNrk z?h@;DKdN2uQ=N|=I@wUQ?)a-K<rv-#wj~h!timxzCMSP@%)}8wcYmMc6}&yiJOoew z`ya*5EkM3x2aub%DbsE8tw|Nv_l~XZaQ>dJKjlVSNtfTfKk!_sK@z^vbpNR1$ab=v z{=lciU`=nxB_(jO=syZW?GNsK(mEYEZ(q3Ua{GlE&}qv@4lx-HmI(fm%`b2b1X~sg zX5pX@oyE1t+8oc>JVj))zic4F;cgivBLvO6$3A&jr-B8H`)%;$uw3BQ`!r1;4)(7C zVeDArI9hG`WgNy9_0<z(va%6G*`U_GaG1AdTIcfAOmf=~rF!OE>XPGY5n%bU`X%hW zeyfNY6ZXz31NO<-`^Uc?3qj=k12+L3n%VUI7SN{kRUwaae}dB3N%Dq?4pn1dh5f7& z4dP~}V}swQ+MSfV3Hm)B{l|NkvjrJCW&kDcC6Y!hy_LfZvH7vQOho!0oWVz>WBUS1 zfMbB3|Bu3j6-RNj=J8;Q^ABg4HP;#VTa5k8g%8eaXk)ae>IVQJh_EWSzo~<wC)^H~ zSC9j$m@fdnB{yTp`7DZTeY3`iZs<RXL2*R4sy1&l;qjsqXm;jStaDChj$2hv^>ff4 zhu6j4cNQX{{&iDAPcPNe=vG2LzC>1!XYEsB@!bpgg)y+O#wUXUR+)vH3I%bO0GAkG zB8MWf1jGSet5o5B{!Y_ZJ2fPx6KE3MnFQvz#d-O)aB-4JKG3*)4bT_U5PtegdBAb! zrWd1qUn)k<uu!3oq)&{h916^SKi)_`mp;zj9%P}g0A0Jd*XrZ7T^CS;`?8+(03P%W zr49~>G_d(&C_@hee(acl&J!a?s-K}iwgOm?{Yw+xTlbu>RFS@kS+RbDs$lgf4ITr{ zH-V?<!rV5f_He0lr$vFJHlSPozfwt+|4}`F_D5Sz`zw!hP=)~TiElO#RXf6am2Gwf zL;D4ivaQfLRw+2aGT&rg!M^C5Tr}|iQlj+<{-Z5@FmZq1Y^AeGy@kJ!)f=U)65<w| z^U^!w7UXtnS~U({XK{iLGsZ=J%6h%+NX2b)r|bRrKMbXWpp39obI!B&eSnT>{rK$O z@P~NA*ZsqE`zP=s%hp7~n^Ez*50}gHLaynH3Cw5KUA|$TaEi5-nbC6gyl$`1r|Olq z&q_g8sjtTMF7^gVKRy9}H%4c<k-3F=q{qt<_c-tzGRCb_MvLLQX)Gvg!wFKGGqSA) zbR$m`hXvl%S~Jf?aLTrRGe>V<I{Pba@dlv9sX3Y;X=CH|vBtIE|L&0Bnmp&z3*(LB z<EA3yk-w9RVg+Y-S-V`8Cd8*!`pfA{sZN*6@O?VM4}Mo~bG>Vz^i5ly%K_e-MmkRl zUy1*ln^(}OT>Fh#$QZL;>Qnq*>0Py8mY92RBBeYRt%dqy)~<qvtTgIEztBZFr`j~H z4mp}*(fQzZrFczEuk+orW@T%MhBVY21?{IQ_hyaE!{<|AbaDnBB*ckob^dCCrgvVq zjT`9<gAcqhhx@!;graNsCOh3cXB9`)A$k=?wb^wB#?N$Y(wMtZ0D|Gg3$dfoeB|>9 z(sLEo&FKa=k>#eLtD{%zxt1&QTE5^Ad-NaeFZgA-r*OVQ$6F0q7s>P_WASfb@jaa8 zZ`B}<wfE;C);ECmIXBgsRh&KGS78WL0nD`jQQW)UgkOfIZ*L))IEEMX5pF=DQkPcz z)ToR$j|(rrD<wWI7}6(!)+eazz|o(KCPqT}&IKUJ`h&@S3-W`nb7LcE5?)UvBkx_W z`?B-qHB%nze9=TqD)F8TKP=H!8p-;Ae+dUf`;CQ8Myp6OJJbj#fxqDEqvGi~KI!O> zd`gIwy^fze<t1;KixCOI+p{yeBrAjT?E{q6Lw0#18MlVF#`*KX0`$sSdaDj3z)bZG zPY%9H__6(!d#v*|1NyY#&k;^(%_d**$NZ0$TIC~yVEZHNMG)h~aqfQ<_CA$c)znJ# z7mZS+CL!x)*YtP4J!Tj~UsfX<l|D9o#E;6`*=<RzsFx2Pm_u9at8e@u1mpzI-#EQ& zUtf1gX&lG6y-5fZ0fMivug8CV4siFkIzM?#Et(OQPT|=?)iU+epB5BQ12!1Loevd# zQIN=O(eR~@jE)s9itiet9`Y#jrRf={<MIO@*(i))oVUA;oH%G!;W}|jO9cf%9Sh%< zlX$-27p9efzM7_nf{N=cbB#EFgHyShwDQ><liZj){@XYBk#Tc*E82I>_$*ODu*oPe z^s!AuX>Q_|$d_10g@VLRKyfSe)yUc3$kQsD;biExTIDt%sF8Xf$QzOtcjGM;sCXge zxswwOX7+NekIi+8Wk4HuX$@dy{PS@9A1@b{7?l}~+4dVPKI5{}1=VqVzJ6i6$|dRo zX=COeX)>qqVygWA#6>6$nvVc7<OnOq@$2)T17*|l&_r+;c`}$y@GR5^gIV735KEs? zA~w)wiMOW#X7c~}dIz>>M#6^$mGFU?iu27)mvws9OJQ?Xqu9<ExAB@R?tUxOwj9|> zD*6_1Fnq(V<cDpvq63-!k$3^2$PC`o>c$AW^7c*ULf7oKGqBS)z9!0{OK#B?3d^QR z;>6NitzF~XXs7jQn*o)8=EB+`QM<;qT@&j@rrQ7Aexla`n1LhtC92G#dWxTlWNqG4 z{<^*3(84wll2RXme<`<ArXKB!sicc*IeR?xF(r?hM@hbcZR>mM?0z;dy8-zxU@*nr z@s=>Nyx(iV^boYy5sGaqb{Lpc4SFutiqpO!I>}+|B3w^{>1t1uIySx+*)<jF!ygWn z%>OH5bQaOFH(#?m67#>Fb)&_|<D>$Cl7-eFUMD#>)SF<BnH+x(gQu>U=C7y}zwV>; zhlW}?=L@VX#z`i9QtOa5dF7&?*k7vu#?G?YW0uQVR8&&`uD*gVSXdDxsn0sgMCEsG ztEhn@{DgmWl@;x?3+b(IHUCklH+~j#i#&ltN&;SQStT(FXU{uO+2IlboVMNJ+l-ac zw(Z}_te`^WT1!hWJBNlW|CzN2DwSv_0oGZ=DmFV7(947eF(u<}ayH|2%zAt!n{)LH z#S7=jhka`4H#ITGt4cX0y2sZ#_dp~o4%Q>z63oH108yp0fa;OP2mKfFJSXVgbMuQQ zjDe_LoYKPVAnz)8o(qtOCC6t+W#{4WI&P6Pp{0$oxz7)>GqWFq4aD_jIgz5G-cadn z)p<Ges|7<kKSNcfOS+v*i8=g`sywfDACR$*n$+Jon+2%&6AGR<cfj(n0j7LxJN_?E z{r?|4g3ZI}-*KRA`{^@OBJtw5Xs!9^6q@G^j6~YKi?}60U`D>G`a*%6aJp;cOAssZ z&F`elrV_4dZ2s3|^M2h{OZa~ndlzt~`|y8Uj-}ASN;y?3Op=&Wu_VWw#%3j_NM(`` zIj<6GEh>j3A&l8D3ON(althlDLe7W8G-uZT{TV&q-|v6@e%JN8p67b5XCJd+uh0Fy z@7Mjh?^o!P<f2V>RvwJ3k-uD>l-G@7Lj`AN#y3eTgxMu$^?y5l5QzAm^T0-u53Xh$ zESzrhcQlH=cwi`LmiB1n40E$(XUeY$`IweV8K0{p7v4A)tGDS7p2FX!ww;jdqnho0 zW0(I_a-wC*_l4FwK4SFK{5)wJrp-(84pE_@tkgWzc4N|hJ+$XshS{5TY-g3QpQF&X zqreX|MpL5IgSS5|j>{o#SVyzC=l)(vg{Hef`*VfhyPjIz-cd@!oxT!PKb*Yj(x8`- zp({D4{c6c_kzLXax_)b_tgLEnYI~578nkwmW)&&gCF2RRBHUkUH|s7-5j{V0=G7(k z<aPPo(YwdM?+r{)fPEiuFXaJ4(;&M60Hm2{WH|5-v=CTR;YvdbWvc8IvlZ%R9T~gL zc;S2HrDKlAmcb45Z`U>8bgw|)B&>z)-dT39V%j5)v3g9pwZgOCzUE5q<kOZtGiIiI zaVY-{`j<Zc_kC+-EtR`|UV5|opno|y=|Hbcpi@`ZQi4znVbBy`G3IzY*tT2+=k8Sf z*1>vSNbAYE4YBxKcFaES<4#>)szr(hyMm7r8S}*h?jZ^$zeMDdZsr)AtSwQJ!s(f{ z)+a>@sn5_hR9x78SfQ)(68Nbh699t3C_Yk3Wl!AGxr2W~m-fx<_<>*Q7**%-bC=V9 zi@TUmWO2N;>KfCA?EBCRoIdd`kb}t3;BRuXtqJ({@F=h*ZnOf~zxjpmsFw7Pc^HfT zS*}~+_YJujbpvr!KrcQ~PHH!u;63-86cGJj<xD~q!>whWwm;r(8eRn35d}C#Jp+M5 zRLIq+G}Au})%qpCB2K#2y{u?~Xt=bXuQk%I^>~@=-aJ)AUA1vhZ1no#2YY0HGq^o& z$1LOof--*)PE|JDFkDoaZTB58nojIE=KO;Ug`5vnME9qEHfg_RWtLhZ{gH42_`|8Q zGB2_+vSqU6iIsGH8@aTsTm2Ui?M6o%7qDK_y==WmP)mLL4A!~4tDbGan?&pb9yJZ@ zJC(9^Cl)r_OaH>wf~7Q!#t`?`oX90!z;T68nPlL*1l|8XDXL>Ou`vx)rXLjnzme6} zFD3?4R5h?T6#Ixz*ZLM$_KsYmKrd9d=J4}<-&)gV#s)7sr}89W2E|~u<`w8$J4O3T zY+X%rGA7A$gMC(ed%lIhyI*c5RD9TZ)C_Cv+)D^Dd0w2WduRhMWQ7RDf+DvA#gF81 zUM=YDtGzW{4;Egpx_SrR>_M7jb1J+%<A1RLbP1&6^6$41UhR@Bp+w+&J?L^iNrIjU zaR;m<dliFjzBNse=*CyFVM{i;%_daM(_lr-7o9u#G|!%GNq14-yPmmMX@6$b=ot?; zAj1Q(5eqT>KYo?Rf5|yBS~Sq*aIh0WeHc&q)I8P{s2+yAT)o4;1;M8L<#K%^@u#zL z{^WvwA6}qV_Qts(^H<uJ7E<aHwKFbtepk3%BdF{kPF{G@fBCEDjBILNs7*ZnS<`{b zmrYzdR!JE_BThPT_oXt+?tIu9d~XAPRqgZ{foXcy@}05*hKXGw!Q4HXX{zH|;%PEd zPHsPGo9B;KaNpX1kEjgzbT-k`Jho`lDY#@m<wdm#kw~;^SL~!p6~>8!Ej?&+%}gtG z6AD;NhN9o>Ic&cKdrtW?)b;F4soFCE993WU1a14B`_*5pE}!@eWxs1T4ox36irkWC zB_d`U$ySQRz6?gcICB2tnbxYnM5P|sHKBi&ow_a1#%9Pa)R#41S3Y)RW!qq~?RM<+ zq=VbQ&Y(%pM#nO+ekal1c=%J(f*`ahf8G6aEgU`Bo!pHnx%czYpi6hvkLgd<BKIqf zdj@P<?Gv{P+;*;e=v|<8&eOIeUTHREQQWTbxmCN=lFyToXp$3jb3hwv<<iQL{Qj>d zYL^l}MIL>#UDjD)Tw_WRp@1oWb(OKVA;;c)sm<iUrxLIUZkdL2bT1E@G#X6a7Q%OZ zyXND@WYz~@-3zuAu36<|EB-!mIB)0gredQP8)+WXBk#T)k3Da8CBU-{?_z(04WIsn znp!q_JgV^igvEeO$NQo;hcvKlRQxRU)5VyZA2hgMk`tVuwcKk4erGSm{|Kw0Z)EkC z0m9b3vtT3fdChFj^Iq8ae8$wHTS0;~PXb7qkMEO#y#R1_6GgR=3<fHXZdu>+$T98# zW|CP_sWw%hOC)_U2-}c+OpM9fYs2<!aN%8*Z+gF*d?kH%KjGmr`Uc7de#p80u^5?d zV$LU*mKnK<!(x<rp!uJl%`1^uaQjc5#?$3}*)u>*oL4;~@L-x|FdePK-(|R}Op7?; zUkbddo@D`>Hf>~&<CsGb4g9aIXKny#Y9$23A8j~ci*!BhQ~(`k_%LhCN-6NQ*xvpZ z>ZWL~&L>-lf`+apl=DRNN#TzD5)v5tqBZ~X5<gO368ado_)r?r8Oo!ouV1>AqTZU5 z#ZSt7^;?WAz2&5>Up>(|<NllkrqMa$kCk08gFt%i)^sKxebI#gWP@nM(A6M|$S-O! z*64v$@};qbJxu&gqOn~>Qm-=1YW_iDrR<8oI*_!)R<DF~zB==`GwWRBDffLD^iPH+ z2~AOPJf@Mk+6Q8g<uv;R_aGmVdrNOhT<l6#QHV{b%*1Zwl~M_;Iyv}!<-LA+Z~cJZ z1x$6z3SI}h9lsQs9j!Wwo}DO11GTPOiZD%yc_^*NHaV@bysq2t_D`|6$pNc@g#;|h zhZ()BVji^F_xmJ}MegYgzDXUwcwgcc{w@}F_~~}_gb}HB@;joG{1emSl@DHaYOe?U zJ^lzKG~W2pUE)Ii?)ZM#PG{;uYo&kz@-XN^yi%Bq=EgS^xPyG5mOwk#{UX1l$dv^f zv<-h&XNdAY#jo{AV45&@>Zq5o*@efJ9l$x49}M?r$a1GrST_J~q8fYmcIO?)UKP{u z3s)&^GHd3r@%N3*2Vw{2eTQrd_itJuX>!?sJpXFRAcz;BCb_|JoPu)rB2|0CWf_|= ztNP&hPkg?%w1;3P>c}4l9fk0UNA`BRZ*{|8tR?&M0=mE&OB8*$B=5B@Ga~)xvgYAj z&2w7AWaIwL&$iXceP6ZB2ewqeBLi|c1ZxM;dx$SZKPb?qvxu{fn?5$X{*js0Yo)nY z>9iO9c~EdyV4rSHp4Qy2o}<T4@rgkz37~AAbF9NFap&A^^ODOCkN7iEPhduvhstG_ z8t;S_JwE)z{M)cIqlbb*X$%9aD<a2O7W|CU@<-)EM$`Ve`hd08;Af$*AaaLu&UW@$ zTSmo!+Ydw)PW6&)P2yc?Bz$S}uLAZh;9gnWRsWYu>E5NkTmjWDycKJJDqxN*$1ygC zUc!XmA0~fX|FlNd)q(ww3S?k%qw=^b_)e0q&z57+7wj2zVB+mB*UhD_mR*3Og#Qqk zd%A=H)Y+pG_;7HZlup}}RkP}=#LB=ZMb=VRrW<&cu*Lk-C2aCS82i+p5ceh}<iIpg zw{)0=&YmL%cTlfsXi~YB&>y_zM|gcqBlF-aJH&zerT185l<t8*wDYlw&u?M~uS*6* zyS;t0G+3FG;kbJz1oIjRS6JC+CpAbCgcs)eNBT5K=o;Sk*0h8_=rSp|ze;E3i<#bo za(%(=KL&~n0%$-&#kv1(Mj{8d<C}4>^>x)PYPzEQ3xhlA#(F1&u;6bLo!Ejz#E9T# zvLn8gB~|GRoxJ8XKmMw*^i}Lo#IT`G9Em?E#~=XF`gL?hnRkoeSbAAuE7$Q?hPYf{ z)S2L6&Zm2=EH8igf)!uj&ij3L`_0Y_&(TiZ`DWU-H9(L`h!}ZyMr5;H?%Zpy8(zr@ z67kn;pZ%7T?R@Pk<RGrEAg#DUZAM7q+$^Sq-NWJ@nVt#hE^_1j^FgOp#i26e%a3mc zZRX_$AC^^qE?=9bmxAQ2+!os4j=3nYRpA-CaZBDi-zJ+DRnPoSUA(?|8IRn+hE3EG z8nb!Jo@>XHG0$&XqIqMCfr+|aXI4f{rq(>{97FX3T)iYIvvu-z%ca*Dmo7I-v;l+% zqA?DHTS<u~?$8SKHS;R8Kp6et|8}#Wh(r#Y!Ck@0)&TNQN8dt8Uu!C~)bk(MAxttP zKqDXcZwjb>08i%_&a6KG{_@b5)=cHV7tj`+0QdjFI4dkX{iQ|jRZs&kS9DTZs|=aV zE5sckwxv5hutiG;1@GSyAb5!0?L&KXiGF~eCe{D0uo7jFmZ>Q807=6aj4w|qwPVkD zKl5V2zO3lfPBb9DvWr--sTIOJ9>b0^S6bwe{pk?hmlwP*PYF6g^6&%W7TGkDHZWfh z`5kZ4cS0X9SLZ^DhRPyWLZ$z7Q?q)gsF3k5cQ1yDwmmY+-mlT0gZz=Ut;ycJ@L|N5 z<sm)m@7ulM8!EJovIO{Jt4U{1DkmCvnpmA&)Hgg+58r<GM%J;B$EX>8c&!?rrok|E z3+cKL(*L3YAu~M*^M&hM@$*Ly>DtW+8f0CMLasmpkeU3S037XK=xugA@aEEhB~F^j zw6$F6Bmx^2TI_?@vlO=J;7Z)ySC7DQd}`;M@Wz>N55r6~6?K@$wZc^muRnXTkoS({ z>6|rqi`o0Cto>lU@u5mR-D&iBo}R8uJ)!s%u`}q+gj}81^`E=*FSQ?hO6)jxCM7Xu zU!b+|EXBIF?wZO$@3Q#fLH1;Ra>s{e-@}Z-K@95ZrbZtd#S>afu>(ZGSxJ$)__9kH z?{kBuL*MU}yiLo}5yv;sJlT_eERfq#eruAamEVY_!t+|-$Rm$3`P6yQrj>Nd&^Q<( zLSN7FqmEsNI#^l_6JN3xK-n18%NItHFyN~&Ox2_{$0XZDZUSBAW$M$N222B$A<H5T zDmf97lYQ(RUGoa5<e&;VDLBSyR!1A?y8ogj6iL^<PktlkvK458-T}}DI}jm!uU-6? z`*F<NpeXCIh1dq;xX(fhwxQSm%hi{u{=?2@_yx#y(!nUiARhd}-k$T%7rXW*WlP;j z)L9ic+zxKLNmTnwe)%s0-09{;iW*07>V3}Xm?krQhu6y!v#@V=vYNnM4Qt$|{FiG7 zYYA_=Bs_Y#PTggd^dDv)_C+tke2ajIF>HG13;lc8YP!SYEPMk@Cw&Ra*AGgg9d0^B zLm=y7E*LJ3p=3?sG;m*wG_6xi43^tR7c^Pat2(wgDP`=>K@Y?}4A5y8SqR=KMQpRf zc=iuJ8aRPws!O!r6)LrjBEYZn5Cy3zF{&=!#I~AW@&kjo@<JzT@xea9dwfDMR;QB& z(WV&l?#;)d<Q5C8oqmB8D{X9au6uVd{99qYBd%26Q0co&cZCoA-m%c4+OyYLjV-*h z>F&Fp33v39krCl_zv(hpyxyrDrQEdjjotJV_x`EP>tb<_ngcg;0(=$9Gr#S`b)-a2 z{r)s!ZLdhXJ4}p_k!da0Rx&(;{az=QmrHx{!!Incv83HK=5`GQsp8vDIw=5?<@Lg3 zC5!R9A{rgtuO8d40c&u;d7FI04$n~vY>hR4>;t-;^l<bq-Iy_ZSbX?_FHZ(;kJ;zu zX4s5!-%`eIVj%8x-}%_8Kbl#UwQz}EA$!e`bd!bl?50-Zq6m+&NGDww=JIE~%yXV{ zAx^DQULXR|!bdk!J|5E`U!lxujLKgDtrsdVs(9FrKCH1nyV}-O8OxtyR7c48f!jqM zUH5v;JT^koCwi?z^5N4GGC-I-5h%}GBmlDh0Tjy1pB^G60tq8<?*>kp>j88J(Pzyo z6N;{DffxotzsLVDp#r%F!K;9h1J3gnishWT=LUG)e|GiY#-XVE5Ph*vH>qPBZZvMv zmft@cbP?>yJ;Nwiv}M(0eRRL?zz5^f7!GSPVDN}OZhPC%9}jMmwCjPb4EmWE1G965 z$6c-MbDr>sEn%_Xv}fyOJL=l`{49UVo?=mKKvKZtSPL33-$(a=T_RbRX!j9ElmL0* z--XY_H*5(pWaTNm^JjO0jNOI=?jZx}5u<GDDVyBtAK8opxd+a)qnjT`n*=&VX>~MS zTrAB#=u?f@g^$nW66J0;{TZQ;a`wB0(|yKed-eU$PkB*dh<wL>;*6W^38DV@?J8lW zzL=|uDq}`kJ|<g#3lurp7Z8(+9H}v<9pxL*5BBlWaMV9Xo6L_cG@U!HM)b=Jc-Gei zI-k~)h9+~-8-1J_Cv9bO4<559C(Iys$t_YpUH#;$I;nTx0M1UV5$Un1tk2>r3<>wr z%DU&BanL6SA!HOfbS6Y0x1~yaJn*rI)-T6E*0M;XP2zRlyaD_DS00@#*(*m;7s>i| zz2pE^-OEpW)o~1sNj5J!YI;MognsNCcb*}4{<Wf)Tfa(r-%O+;5Bp4>Z5saWt%Vu& z*ty~9NKav3;gg}_`lH(JdHJmuipB4}&x<%<DIefq!Ch)*yL3~8d-e0#ZatMBTKIxh zg<n(Q)id&S(Wcm!pMfE9-YP{4zGD11G2+H%Oii<B+*6G@jE&|P2FK;qnlRbCpBfKp z!tZnBajzDu&t{(G7{?+*(`#u7b%|-fftvu2i2}QSQJ^oziM#TGVIY&{9Oo}x>1qHQ zkH`o<2)%20DTH#vJMvIag(x0y87inxNCP7Su#uF!ks%uU59tQrF?gO!6de995U*n% z${^5+ozKB{>z`@_=RXSkT$Z1qhXCH!-hH|*-|j~@3ad1>E$&tP7(k0>%QA)*o?Kve z1Wcz<FWvyowf*T6CUpX$gRE=--z|o={!VU21EMwDtK&~%1JNJ6_U5H&s%(XQ_ZNBS zt+lk%b8(laz;bnKHdv_HAcPlW;Wum<4Qv4r_Ho>XOJS}mEqC;erOfb1qgEB}gY~E3 zwiT~YyUP$5EldWcKj);81}s3!D!g$J-P|QQYS?7!#(?qGB*yL7Y<@({1F;jm#g{B0 z1+Uq+QFQT6gAYbcFu#O{|B;g#pZ50w53F9I_88@>M)pQYGH+CzN2%o%^x<Rj<&xIJ znRnEkSR_pI2e`|2GUZ*sW&V_U4X6o*{?$ba61gj^_)LI=%dgvJ25h%xqIad%VH1Ho zKd<Qs>0NE^+mF)a6NC>TDpu{Jne<ccC7*S+_1K3e&WE#T&YxFyq+gj1k2-30<8ZuR z!JoT4t)=!B?>gg8=J;#SR60(e5MRH+E->bveY)6RB)pAV?xl`{Ti(iL(j_|_s#e)9 zt|x!!zASg?qNmj0<Xz_!&r60XHuu8V{)8_Dt!IA@50~9jbh!nrGHVNY)O%Qy=K|wP zJxH{K0MFlT6}u=F6#s};#gn1^m%9x~e!aU2H%oGl9!f69iqWJ#`^<Iz<?>m=eofhU zUuTD7ZlFF)e2y~Jot{?s5~K`GHs*ynM^giBOhIrFOb04b<t6kM5R-8`C(P1FHox3v z&$2R+xTu65`iP|tP00BabIuT9Up1)*dfuGK$-yxvH*k>wJ+FT?7l4@<Y{wBzV5a)N z!x-R{0N*JF`Xiag2BEZ8)C$J`QU-$bTDqGd17#I!f%~5-39?jPCrb@Lo<0h+t7~cZ zI*)veC@3}w!}WyxsTUyAp0niv0N*QhEn%O2HgjzPC&tO$StSFidjXDLYD(<!FuL3J zNx5l1i>{Sp;1gzV&_sSPX`gZ%Kd220*}1Y1%EFhg!XJ`9MQ9f|L{BfjkUb~O`sLm) zdH%szWdhhAabnbcR=TwWza6~KxvHX}?#Pu8gtdjqi}OYH_gqMJd`8{44=zQ>YyR0N z?)GJ{hw<U7rWl(=8L2qaBsF=_!9H|zRNOYto-K1(@r@p$-Bvff<pZ}6>}!a7JmY;z zP)GaIqVwQiEgw8SvvJBQWF_$|kAe?&OHle-%Hfv=@OLN>vw^vm5-t<{;R`Dpwo!}* zIxFbO<JdfZ&1!Fb4`X&wxLRVbU&Whxg_&Z7#$1i~r&fL0OE!6g`zIQubsbF?98bL> ze0JS-C&WE)Dd_yhH>Et1)TScG-KX$3w|*o12{EK&)eWy4%AYs$zG;Hfzax4=821To z-zP{?90lZ@!#HV`8lU`^OCT&ULouV|YPCrlVdG2jlerrY4?c?s#G1Kf8E);fNxK_; zH%mB;GJbQHvi{KdtdEBL6=gF*xK7U^obvDJf;?K?o+O*47nLg^GLO$jn=Hu;sNmh) zTE@L-jYZ~$tyNxt%N|&){?3k@bF5Wb6z!UDh|xD#rIgQ+M|0&uC-r<VF}cQjC(gc} z6#$kD{FIKsD2sAB`n_uGT4N*bd;!@EbkJ|qkIRL|S?M;}sK(CP5nQnen9wf(x~P&V z6ciXCTyg5IeO!bvv3?Mj*DQ%et+v&3@?$yj*C0X^xW1lHh<5IV34u%kvatt%M?^x8 zj0`x&duz?ae@rNcDO`KKHP28^6qe6jGoF#lEa`s<$cpTzzgq@|sD4NB8M5uzCg4^i z@U-8};CNSjRBR!r`jW%AlTMzn0&}-#^kMuy=KK5xEuS@u(z+j;ov}8w_ZqTX7Mutc z_M+7}8l)_8^@_~nNmj3<nfs-~1Ce!kHzr;2V_&-7X@Sn8MH0Tyy&BBI7<G*!NnTQi zz%rbmu6W?C%V@(VcNhya(ap68<vS+(bHW~5>(x17%C39EYY$ynPL0Sq9NE~6%gJp< z92Lxs%TC}bC7&9+-1;OjHLCFK6SdZ%*gvfq*}Ns<@*0m-FtrjLx1vJhUW&x;5PfG? zK;5wIs4c0R_{}C;Ype1Z;XpL+G0hB~3t2hO1G_*+06nQQ8#o_U-LY-b)*GLPv<*R2 z{Z{x`VW)wcX~1{2;$G}5EDS!4iOdbMrxA4+S%=TGV<oBn$>V>9ti0@!B8)X3wWDe` zjU|?4=Uc^ZHtI5Z5OemXR@5;8laailBN~XPR~Ftq9iif4uQm<m-4#A%pgEU2A*ryC z2`h^)$U4b)j!TI<HU3K1h-)q3@TD`)zkCiI@&}6@5D%U0y{~lZZ8z{E&(U<Jb7B@E z>tYa0vFJf7_qa9>zKW(j*Gm~gj#mEhtsU&0Ujt;1xLjJH4o^z&UzW;tbPkq^(Gdr= ziZ8Vth)9dDq3tbxZEu!s?w*dL%p=Tm&h!*yQrdhe-o$BmE(Ymu1zfKa!3yoP1nCp# zTLT2YKb95YB{1R7N$pny28vXl1h$)IB*O*tOuvBqO&GU_26B}s4)Feq#pJV2pr`i_ zubfUlO8?M?Oi@<mRzpq;48&sy^ky!%E&tsFdadc^g&=Sf{mAG1pq3zXp#-8WIC`h` zS2^hqEKUB4)ZjJ#6@+U+`J{m`l)?bV+(nMN(leb&ql_EWorb%vh!h2{GVk&+PxPWz zs0=cAQW}BinKfu7v5kP^7J_)TeJ2g%(`3GhUPbK9tBi6YE(?yWh~fKh@@wOBLk{=O z@Ks6w68!WEaBJH|NC4c93v(TjtH+Ci4XM!!&rOkFA@rE^44+JQ34RB-puU{Gh<!Sq z!esT1w7zzc;IWQM%caj#mRR3xoPSbozNPEk%1tq;-oagHWQ@CbSCle9DBS^6M|neZ zoBGd$3(h;!dh6v&G%~WXda@I?3|d*I4-V%U^(znMo-WuOh>45n6Cr7w{&W+8T*Vy7 zQ{z=_qErwbe)Wfm_Nw`@C?>)R9Ew{+lV(5dR;%7xd{Md*X=@A4u|JMGqvNO_z#y8v zLH4{&&R7k_rp)}J=i&CLTSc31WZk~a5Z!$$N(1)H%U?9OC{iswYW9J4<A-mSm*T~@ zH<dY9klZ$QB4e48Hcvhov!}Sr&PyWpiQgM8=FU5+K|dsP(^jPJN07s7Eu#ETO{E<W z!_$vAfC&7%cI?$Y=km}bo1Ukki6OP$c^jnbY;B98@60y7B%5cbX-dsL_oAHrW-FwA zhG;0_bGDItyK8jTLgJkJ=Ar88Q{SY_N@b+J(6+SBlmU<IrLMlNm0MsqFR(I@Kr_AY zn67W6d%&6YF1I)>CD%qT#>#kJ;UIgOEO8lO7RgP)SkH$Wn4c8whPtqcX9b;{v;-du zj~k9LU_uIgL`55tq?fKHVh6}czVun^L2Vqf3p4Gi^>#CGxco+5v={?K-Sr^+FVa4Y z9YJt7UTZ<&4!}aM$94ElO^zf3q9BX{(QX_D&EPnck3V9O+j3PQwix=N<s0DX1CkqG z$TfOh-Uqdy$lq^5#U_VPUVlrVJOQq%V6QwNl6A7e_W$0mO??}x%Iv={kcW)(?*MNO zlKi-00wI|qbSwvcn{E-+vGXq%zVlJRq>;!8tldL)<nFn=*KdJV%x2&_UTeuEFFIIY zUSJ0H`~uj+b8tnWRcDX%4_p}gMR(P~PX7+jwDIo>NJ|>c8neR^kb`pgAJQKx-e3SX zTP!_Ngo^$>(3-3bXDK8XdFyC(6lKTcs@B^V*lvAWbR8!kjci20nhY)O7i*t)^9v)~ zO-hWuE&$toq3r1aqP3eL?6PNL;zc|H8HaG<2Md}|WYlAuV@yVjS@?YzZ*&CLJo#L_ zfmAzNnc&y)t;CO#i7Fvtg1sC8du)AmnGKuJ5ke}2C}cbe9)4!(6He1)IxX(0h}gl7 zu^M-|y8;hEzGP8bE}Ts)Qz0haF;=^dt9V0BE677g_#z%CP8icMGY;k!CZFFFpJnhc zsm>>L`rZR^dYf5L#CGGFym)c+{gbwZV2f5AZ<o?gO(}w<bgODx<)<dScQRLlw<cGw z;+A^rLIv6@^s~M%;A`VAx$RVZD<cVW|HGg=Zb94&b`84zVXMkkOvKTkP6dA+v_-#T zZOMLBa*;scc8Mr0n>TZcRJj{2(Ij76$J?Q8&Tj-)lo9P;7J`<gTIkhx`20y7<YFcd zLz+hu5Ou=J?Dx-(0|OC|DWG_@$Hv1D8Tao3n?hg8V>E4EL9uG}<d1QxF#PryCb|bE zr2L5=4hKedf^u|_HfRi|x!g9V%x)NLwN`lpfCRdffXo0{vGqBhRwyA@i{1nmVCo44 z-@_#kD6MxF)R1S~pxDX@-5mMTzXw)QaeI6@ssbpR;RN!BP!R|L{UwJCgv(AqB*=P` z1}X+QRi$zi6s<W79c%~9%Z%rQpb2zA`bqSY=jPpBiGeq=A7LJ-0)vHUosPZ~@s{YF z%5wmGz!aS$JlQm#{poo7jp;9985Wh+LFjS+;j|A+=%Ag+VlvKUU%rJ91jmD6fF^Fl z(`IRzE+BN9O)bYg18kgdrR-0dbhitHa``Ugpt2X6nb&(tv!%JUWD4+w4QF)f7O`<4 zd@uA`Oy_i5RfE^Cs7x=y>*NmSBONkKBKrLyP1sBEcs|@ttJ2J0-!&+|j(V9;^w1v@ zG)XdC7+d&t-7(|WhvL$*MutGi{rQO~W{bRYtb%p7{luHr^xdQKQ5%7gg6?ZSWs6u| zS&viVLzKJQIx`NQ<beTdnS<`}Dq(HIBHv>oN$tK8DL1ES+Dxa_Z`i0hz`-DNC>pv} zUy^$|0%hJDV4Azf=_Yj|n)+OBx$imux&<SWXfT|^@GQKXYs+UHRn_6W*-iEYi<LX! zp}kdD!BwsPXj)2jcbOSa9biSKY?{qYlSf*xoerB8>`4oOh>|MQVfHFtV7<T()GZC# zYvhG`<n){5Z-w#J?0fEi3<o50>9ltbO~k!wUR1vbD2=-{h;6v39L_YW4f{ONsmOI@ zx9(`s#1ii&>BxP+yy&UlgPR*PM)`uj<-C3KE(df-cTIb;b$vwUs9&#ul-NjIi169w zpx3!pVq%0cX!$ND<TMYEffX476cv<e+&u{>dYC+1g=<}#*2w6QS6{N;l90VQszZD` zuJpic##rmi!$4c(awO1tBM(W9gS|9Y#{Op<#AW6;kgxn#7($6dq*y<299u8@0HPrJ zf_D(OWPvCOFbd2NA8NIM>zn|*Zw!@Xiv{r*#BOkH{r*_btk+KhPVT;*+H+_ZIR?%- zPY9w@^z~*?GuB@XRE#2#ikeuDv%2*P20skD)4;NT=qRs&cdnI@Gc*C{o&rDjsgUtR zj&qxdNR!P58PahuXOnrir=!c@`C)5VyT8)IYrQ(vomB}B*t$>C+0QyJJp-{@&mm^I zWn~FiPG<Sh2(v#QUh2aayBD?~2l?G&m=4H74fZG-Gqi`c>mds`1vhbByp$6KXGwb5 zXq><#l%u1&9}5e^eJ?r0IjI<xko4XRsea{>C7gX)B%@|7Z`=U0AtZ5WS)~)(8ZSD( zw6d@bfn8{v>~?F2B(~?LD`)YYSVl|4gxR?Ct;#>SD3VA$y7zLCwqMyKY^Pv8KSVrR zUq#kdo_PzT#-VXtX6%BhA|XW8<n>VaNsovAWx;O{?kJui)kcAC+!^XE@hAmB_f+xS zInOe0ddA=D_i4m*=<{&r80^slzoOQcqSn`c5I0)RGq&HL%I6nZ?C}htD0HlBo2~`M zgDRVbtn!x<m)h!j_OzW)#}&^Rsc&d>E)yypB;1k{KHK$GI)8C9v+N5#u*VC;g{EK; zW@dXGQvqu*enfh)>*4qFcd}s2PZ`Sn&lt;>Dvz5<@1tF6sUEbyi!a8FUss-VR9z?^ zVg~SZRyOy6zMp=X^rXm;Ll;0!@(VY7R4#Gj>UeAtTJA@7o_A5yz;Gt-hyGNV0*ZMW z#fYNS0mi8$VVh?&S-i^-RMIc~f@`^`X@D;F-COYOKE?numQG8k!X=D1Xv6<YH8{1R zE+BLd0tu>DB4jYLRzGs0Z93rWwEh8ht#JZHS5!gs2l*O4*fvd&aOgqCrt&%0;d?+$ z2?RXQ)5*uKyod5?aHOm=c4%{DAovDf<3wk`2AapVPgu2w{U(%N{mV7BEocu@DT*j< z&x`lP$N3)=9ooAGkdvlB@AAnl?bfC-i*6B<C)D=0{Q4I8)?*?jSA((VJ&#Pl21qw_ zL^Zl{nd8V8A;+ax!e|1kpga-$*oGY30Q@cMknR;=l;MO_l^PSd5_tqa@iMRNB=~&9 zSAnP+@MHJy{N*Z9_~2`?uqbUYP1&fK-9@I3>z+V25{h==e4^ZTk*ODyn>2U1z0aPH z>VT;ok%p<>y-c`du8gX_U|vH4zdTnB{T#SdjP|IPZ@B(e=$z5hP~3C1TC>xrI{}4* z!7i#}3Hc3_2Q60cc#qnI513LK#5J#Bw;EtKqHL_XQ@!(LhPFZ^)3T|QLGphf&AN?6 zY*;2CU}R}qdV7X%upk|C8TXk0o3g?*9DecT8my)JONJiF-7qTdP-`7GZLHga{;O7Q z*8!%Z#lq&k6*x60k2t^CQLp=)-es;guPyIYpviGZ_?0n9*S#DaL*GSuGPG6kftn1q z9)hVf$y;Se|AEt~{RzDC{I5HGsOh42r>s20N>3%SeyIP(zP=(obHtFnNUgi=i12T4 zp@&z}gFN55EI%jB!zNjnK)4lmlsvWZQr>Mw>+9b~h2aMnw(eV$5KmTdd%u~(_lMxp zQ{rD|Xi|PvfMfv7U3V@=q^1GY3!h<(vFRlScUsz`M|`Ku*Ykqx{eA7|_4G6YE@WUy zaD|A90n+{`x59snFeenR!)lEqUT-r0k9I;CE0O3T0o8zOj2k)W5A;f=puY&>=o+jc zsIFfSYoMPr;FN{`xRVYsvCP!Bh=XR)F)&zq3Igm@AO>FyS<17R$1Y+cKAVUp$8Oa> z2-_@?EQe`sjeW%5L9*d;YL9cs;G2Pmd;}BG3>UhY<c(r0zFYEnS+(EYi$|bTIaKQE z5#T)nX2cwx*M|{U$Z*g&*;?+n<UGr)zRy^(IAXY}iume}XP@+B<ss>NC3QK;aymwO z3^~$G&N4|>ZnA%9Xp&DUg6DM?5efGV#9`NO>`skRHp(iPG*2gqmS0yfz0i<#Lo{K~ zs<n?`S$)K<=!B!3B39<Y>q9AThMSBJ+zz$9ed`ikS2b+aw)J+>p8T=pDtNN8g{7aD z<yLn<F<W^UAWcAs=kvNb3xwMD&reu_B<-DlDn31NdQN&wW1iZ5OX_5k?nNK^#qo_> zijqsLAKRoq92`}^wVD5Re;M)B1?Da`W+*A-mn=3NO6@-r_vSV6*Y6+HUn2a$8m%kJ z*YX<nI1F}?$bv^J1pUmFjX{M2n|=DrVJK94Y#WU^C7rlu;V;+R)94QiO?eE!{wS?9 z1usX(_E)KOxy%Hg*O2Z-j3%C2?fU7^_VZKlu}F5}o{BnLSCfv$Vz8A+3C(TcXsCMu zi{=A9R;y|goG*3YcjCuVi4LO~oWTLYhsW2i;|}eH0b&^a^tW^NvEkGM!bN;Ahv%|C zxL>A|bUU9wNYytol5{Jl8<@MvZ{o>S_fKE{C+oB22MtQ$zuqyyl*d$l%ye&5VXPG& zuyJ2w7S<R!&?(u(A(_|kMI@qmogt@E&S?*ABUo#!ke`(c0+{N90}bdHBX2{>C2MIC z=kQ<CQGh(+-vy|R4kEn1UOv<&f&LGs*@w1d?(d2YzD&$ZjgBfHOru)kN#?Q9sJ63x z*05u6J1+vwT+paLGc7~6CvKr0{u*?DS|2tsOtBWOJ12nobA(3cB%_4wJ1ay}Q+J$Y ztSBe|{pzFLQgNgB&DVW{;y_bc#8J{e!^OUovBE-h`3JF2nz8b%=`yR@`0pUIerh8< zCLMk``)xPw#sLXTLtw{a;FR=w3yW%a+mhBpP5(`J6wX7qR>MCY7LcXjmn|pDlW1WQ z)2RC4@vce*R_3)uzt%}{pHpvuDaR-O0hpJOjMpT}B-!(0+}S%3FOfmlvty>5^Bxx| zoZvR%&P}_e)uE<ws2VWI){6d!F$a--o=p3WhIb$NY|=`acSN(iL#VaGVx^2qyUO8S z1mDBU4tFk%o!+T);gdpYVF7ybydWV-FvM8ml65%k%CvOt^B)17e=McYk_JItU4a6T zH=4M=dK`Aye7mdj%^-2$(95)#{f~gDQx$17>I;q0BorxqTxmF>>f9>D`oqFdUe@Y~ z>OY7-(Ye6^{kNlcHM1A<{+#*CWup@}nY`yO*JCGqmo@g{pqHcC0@JHMe2Fk862=?Q zr8nj<1!7yKXStbfPoCgQr0t!9bUr^~r(I7PC32R0zlQS4mlFM!a!sX4&*;0Nu4zm@ zIU6ElA3o0~kCHb*2QVb=0cUPtu|~FAG!X;mu)fy$LaM2gYu#oJ!N37i!aya2EVB!A z4vwIbD(%rNs9Unu&|A-HLB0U83lLT~z=MecH*<hB&~iaTpo8i)@P0Ii+Ww!s0cDy0 z7ApF{GteU>J%OdSzuX(E)EM`3dpq|z9v6-+Or0Fl)ub$r?0=GB!{uWxJJdkN`7T#j zeI}y&oSYLlJo)%{WNVqdmLto~xr`<xvXE3`F(3Jdmh}rT>z_v0B`IU)Y;UgI7KZ_7 z9!0!otSaL`yrAo`WuH3Eex_2Vr&ex#8?&n>2rLESOOSB^Qu)fh(YU61b|AWOCc2gO zPLn(L*zHy@0&28r6z59x%{Hd13$<o3eviK}+lDefk?6uoUoN^b4HtYYGTp+C+u#)? zXa8f#dftUlKEJ~&`~GSdSW$%Q2r&K=kbTEh#pM3XwXBAB49j;qUWDShp`2nHiCjG3 zhpiO@u^Ik`>{C1wU>gy;fI^+kOfIVTf6mqhn<S6m7Z#DWr8nvMU|#S3B-Zv@&<HFw z{sVzaqT_CN7<Y!)Xh#9*N@7Izb;Zf8C5TyU-PGOqxs7j@C__uP+<W&Iow@SPi!4~l zHEAu|lPwLbmob6zDu0}-9<Rn^sr5?U5Rm>eEikO?uwmKB;KIV6{w-i}<HwYxZM68? z1Be-=2gpJ9l-2QHH`0P%vS`<*89HK&jG{E1+2Aqe4j%e8Hf$_~|M{+YDvOO_Ndol5 zu+Oy}$NX%;Y@$>bDKFWa4&#5B`Q`_O)=haoHi^MOEjf&6N|03S2YBVF-oWS3p}n36 zqDm*B#)Z`&SQ(;^9i#tiVZg-YKj|AnpgC2?4|Rb5WvuR!X%MXd3Os$$8=U{Hg~oM8 z_cTKmyp0?=B^OFJ)A1%yuY<5QSH}6a_2>NqD>Rn^o&f$Wz&xE2$qlHkFFYKdha8Cu z?$HvoeQaR!><(N+Y4`r;`o>@+c3kU)1~;jpN4`y>=xE9#%aOfke*pq9QwyEiNBC8N zyiUE=*JY7$3~b}CF`TD|s5q&3cq7LivriS=h+gE;aj#x*NtqnsVF!RokS7&DSScga zwR!{5x&Y4jCIDEI;b0V~#UJBK6yE#hDOEQYxylV<;`(WZ@5QKRHNRQQ3MEz+`CTL3 za&jhp;qIsE1hz<bCd-Jlz8JbYXpMPQl0_MQPV};#=7%4gu*z?!A$vv1XY^TeiT;e5 z_2RlH*q+CW<3d>fF6P_Z=wo%bqz^sTraJk&$`-e`mw`))hi#_4PXt8o{|idr1c14Q z4wI(h#P7x`*f+r?Sq!P)3M~~1eUjLBSa^Qc?`CVq3k%0<Y%fPBc5U2a=WRsOx7?9R z*C-yp#wP<z#lfkEx;#t^U41q@qocME5WTWmk5uEXpv`@ae!nnFbE$ln^0BMIcph}o zjG3M*4}I{J_EE7aVp1KGJun&ew)naD!mixl38r-Pb_4tmn&E<);oOVSB|Lmd3Pd94 zLmPWRnI47T?XXNjhyCu<ui;{13{5~TNCAN*YL-XI3r$g<G?m1ag2_cJ`TUeML?5gt zmU{G4=AbyT0uzsWb)#@_pd#=Bl?;SlDB5xAr+q-dKzM8hP_)iSS?=J(UFeHuc#dMh z`uv&$`sR>v4^b=S8mQ#IzXXv1>s(e^n$IWsSb%BhjT0Lmqb333I1eCfay0YMLzw0m z+ADI!{mw!&_{$fk%zmoEN%AQgMHXp-G=X!EJg(}?B)_NI25;Gbl2SfnWX|tqXaaE$ z=0<txhSq~R+V14f5-*&;<BJu>D^+<sk*nUw2AiERpyH3D2MW|}0E)61<X8+Iz9?HC z>`xfQx9Qo-M*ig*+|nD(%DYULW-jhpzEklOXe6Qs*dYqa8pq8{wBf%re_(Zoa}2=3 zhZgUW^emGU$#G31*jb_aOaTw&j6=`Mg%~FJk^IRg$8i;R=dv<4!L(1mlj1WlFp!hf z%;IY{Nj^A0Fc2?mcl6CZA44}54O+}jm=uGZa8bN%bAoi=7_ki>i}s9P)W-w17Od=Y zt`w=gwRv`lz<U06xeg-@DDXVJclV#WuxK00#IHqn=Gha!g~AM)rwCsjOfhX+&cFBW z!G?CQ1a9f<up6&G-gNSU!i2}>y16}kX>YIGa`Mf69oEee15!U@Ml+AHXdbICdOhnM zMMTbg!LyX@)F;8fvn)>@Fe<;v_GOmzS6MRO1)abg;Xme{_1SyB-4eEV;fz3CjEJ#2 zN~`M=m|LnI)ZR94%d!ZIWFP7Z`vPzY|Nr4qPcs{nU(tzq`<_yFoAAKTK<ISc{#0#c zjNQNxB?Px?!b}2#gW9hg1_}}qa0tr>0huGJv5=%Y`xXyL5n`C4G{|H~i38=A|2^*? zD)p6t*o^#dgam>(5G2r{Fu7j0uZ`ZVbr}*Gll7s5!19f)2f!UPbHf2A^w!X~u9r=q z2gnK1qF|z<u-ZQa0P|hySaD9^FWR#!nc2-hEe<4_zz>dIY1Xy+Z0@8&S4&uxLwcv^ zt8VG*I+Jd`eb*_4G$5}TRQF_0({fZ}W=xS|5AgfW+FGpKIY2wPa1r1Cl8625%?vGe zC76&bR}T6F$q~gBnxCEwOxSf1ke&MMKH5Q`5$TftGj@*4hftCN763QHLi`dFw^H17 z_ct`-F6$8zf(tq>H}1L4CHSxzcf~5u$_3^^v^1uxj(BM6viAh^5~31s;)V8a@y+T; zQSel?ird>~iS<x5a#=1?H9ff8acsz(Swj_WloO+T3YZhUJud<2b*&X2{mz@OJ9mC? zMWJ2EKzf=YyMWUg4nA30tU=?gUc6>@Huh30`RgjvmYJl3Tg}X{`F*UqRzH-ua=dcc zGt%SB7Ou2P{wFW@Lc`Mz1ezgtf-+%t>g(!<6_;ryVBR3uox{KRxJh7gQx2Ty8iwx$ z)jD4=jk&>Z;pOXISj&}!nWs{5lU2eXoAev$wrzV*6g<ULVe470>Id$6`x@NN)aq1l zR^!d(;gvAimDibm)Vkk<mxxPInGwzcu*AWbFjR-j8IY&Ztsh++#Ow(#YqQvhs|3^B zYfRC<aL4)RVL+<l3*jI`Mh3>Wo--=Py6jH_87F6A0U&W*^@Vyh50m^i-@u_TZ*gdU zFaij*qToB1+q>7vBLZB_ful6zkoMqH;+))^vS<zOoLCF(h~ofJ6hp{W>XEkn8G013 z>r(B1xn4UeqYUJuu4`oUTA|Ohv>BqTKetAcR6~AQsmprE^Mq$vMWx*-_n*(rh4DPK zru&v@e9Jw*svm+PCG7@dMV^BS;)bBSIh|r{KUJp^y)A3i$8*S0F<2M;VKb-LWqZ1& zyH@V>j=Dc*o?IP7{uZ1uyBhkJYh~HSmY6~^j}(AiJF+Kl!zXw<-e0imUT_5EiTpRl zQw+}aK$P2cdAFQW5)Th-zY9rqwm(IzKkGyPOL-JaHI~ISOC{)-yl~+^(H2}GfwtyK zd$xU(fGTs7^-No4aOS&Ay;6Q51&QlHZTn?H`S6h9)}w0nrWCMRh;D~~$6i>%Y-8h1 zyn$2N31G!1HR*^PM>1KsNybXxK=<pb_)d}9!b8jLZjEJ&0wuK8sYuI>CzP+Ix)4~0 zCd|m~KXF>}BHXE9A}8(IQEiIs7z&#myyJ1&0`;X)(zbw|$f=jM$Y~TGV^SbnJ+FC{ z3;WiQPFVEp$4V)Brgc``y&g8^Fwpn<h45sMCoHd0KX{R;txP%9GqBj@Hht$*l}u6~ z89)#mv6yl7N$WdXf~|wBzt%|DTzzsm1`~B0ePn?W8>yWw%tgk@PSDX5fm~G<WpZ9f z*U*Ia-^d@QM261Y0#Hk=QHmfKnPTY3Ztx{erU=H;)+5py_SU+g(2Iz!O$?b?tZ4{Q zNLyDB(@y?ygLVKw-?P>?1)RMT#Mz^-t#O~6L!JZOf7~V5YJYJXM5yY+oXJh>5)m)E z=z6~1pWlF!U2vh6)n~)2=;IcoL(1k~%@`WlOh(bk4Wn?3I9Bw>3bXZT2)vJw0%(H_ zUKri&%DV?N+ytw4adRDefkt5^T>|N!Y4i;2K^lOymSc9_pPzt>Clo8Q-?A|?^Y0uN z#gBmH@tz~LRiLf($UQ{Jr|RHxXYX%p%*2YlNbRc)2Px>~4nMv|Ol<<<(gA$s7`ETL zPN3-2*UQ~*IVDo<0k{Cs$>g~GM5YOoXua*e=&TikJEindoACKWZ*+Q?38T{HT7{K$ z>@D0!i+Z^J^97upyy`ERmCTnHm8%<Db2W4v+%+y1cgLUJpRQ1xT(TKj8uWibBznxQ zr((lxU?ywoJQjX7cDQSrvJ*KW@Dn@olWJWDTFGvm`-xkI!b6i6{Mv0t=ca+3%o{TF zsfH$yv!mO9R?4#4gitB{)0Ocxbf4QUNj1BA{2>?^0Dfz*mBAdI1PgWwQdX{GNBV{) zhDGkXu;DpNx3Mg>ckT|oeY8bx2e4pY!B=Or$zPp*kj_#9e<WGPeOGDLM=VqtJzPd5 z9g%;gEl=CaGlt$YWhTo_(VR5R_{5JByp`072}})avoOi)z1}X`1q6p606}fe^#c$< z0!^rFg1`XrI4)r2?7tik5IIm&2;zL;+mAwwB?OqwN8}6FfVP$y?i=IqI@X-@@ZVSr zK=|5}r9P)x0<7nnyzAdE19+wXl21;h4k-7=IS^>Ud!&=ICl3AUKaDi0S;$jg!0`Y~ zW<#T+Kw+z5K{g&isQJ&4+bWGGQL#WB3(~X#LtTBGo5n6gr(2d*;aLDfDl58Tpi^cg z+-0<PM&$Xpd&$COP^nzR|4tclJhozN=U+SpR?<x9)uzk{U-;#o0)(*T_;Lpnn8IY# zhsF_Kn3=x7&A#cOmM#|9>{DzjvS{#pN&tH$=$c+{67TWzC)Xh^h#rz}ZQ$yscHG-I zX5B#kL5bF*Yie~w)VJVtHj)!u2&PV`C>0y-pWa&NJIW6`cp`bX8L5vP%B$Cv@jY91 zUFMx{%1-Z1)F<BX$C?wyjvS)0YSu4V`l`brZE7bikk*<V{b$KClDqVWCtKULf(H^A zq+7iQ0Wu{VRRAWdk%HAoA^Z8d<I=_c@q9cd2&?jiy0Aho;SX>+ICbDaL`psnoHtmR zZ&3D6>*hBN*lX#vO>X<krR?w!5TXYkT&^F+Pw9aR48Bm`8}#5NrpC7ZllZUMsy6`u zC&BOrk3&{S<N0h*!Bi;qr>um$J)g44a0T7;m&-0Z#2^qL?BTNYb1pQ(?hj^sw=g^x zQC%i4tkSG&nH<N51-<nNGi`WzNS!6x0vdjTbglp8cAU1MHIUYUPrlv`5^}7;k0YCg ziPOALpP`A%&k*(?h=MrADR9UsdGfK4iUhje4#Ap}4MJUaC`tl}?SIEJK#n_9r~wGA z2?C+l`mcchH&lQ^#d1z`Ig&$KR!(W#jR%ti#zH)g|2dTjFdkC}wg}2)Y7U4FgXLs% zmXtuLxI@aVu|c0rH5&L6>I7g2QOu-v@pmE?n<>4JNC(MauBzwkU3}Y)m2lV5lo^qf zardHy%M3#QlJt<Hdhi)B=EITYk;QiQ4)B=@NY&>Do6Rf!<@!#O?ZS7CjGZ+Ky^2X_ zZi>cLd(Ma3Nrz@(wZ}i?GgN;TwpZC*bP7cq?=b9)*Df6<xiU<0e0pB&35eWmZkO)F zwB9!&`jyMY^61<C%uiTRxth1o`H<{o&9~^+K3-zC=en3!x>M%jz6EmP?j0n=xoG~J zJEHxhOT12)n>@S86M%d~<+4}(_Q*K@)|y?;yAQQV(fE|s^c?NWZ0(1^V5d8t@iqGZ z_{lA5$zSm~(&3IJ6Aok3Di+Iz_qLzXuwCxot3J@3g32CF&$uQaTFHk6pE)>I4tu+2 zO<#O|!p!L}7mF$V2lh*P+NwsN{z`LhA##a}*3{Nr<-YI|+^pQvb2vrWRjW|glmj0) zD11lfVR>4DOlg86^AF#(V0g^s`%hQN;UUIt1QU+xj?*#>FY7Smi$?Gnh}dMRH<|*y zeMcY|QlUitJB}@-%nm|##(DwFp%g8tQEn^<U~4kcwVutxF_^cCSv}~ayu1)*mX_|j z-b;ke)3s$|Kr{j^xBXuOptWRBI~s7_Y`}R-@||i*^Z;O64}xnIIj8&vnB=6QoZtt# z`5bhv7bey*Q|N&_cwx=pHoM+;DT}bJ%U$my!BET%nDBtHHTOm^$|8SE%lg!dubBfQ z*}}?AU<cY<Q?V<Ef1pHrjIU6b$Q54&f8adXMZu4s@dNeOwQb9#!Hz$8LTKb7_EWDY z{|VOs_9FYnU#^Yd#*c}1IqM)Nb_PEWIGf(tu<4xB4nEfPIxZ|~=VS!^yhsF9Fm*N? zOqZP&*20v`022(&7}9CN2cPb|#c@#WvCj+U7R1D6zbQ~HXW)oWt~6^R_9y$bja8^i z#RfPDwKMC5OvI%4#H+4aZ8aVsqEj!E&YEtBBp)>D8iq+Cme4MW<{KdkGzfRTiC{O5 zp~HKxdF<+EG-Gj9exfJ8=#fx)5Vkq7?=P2e|1FivVdvuU6ZESl$CMpy+0A8s=kmO| ztBM{x!oi_DaILKi3gOb)fu7<OrN{jW$faK?OIvBF(CC{b=)Y{1wJ2eHoU;V9K`>#Z zmiD4b9waQGN~!EPN5ka@EZA=cF65}~tvOhsRwC1afS+(#Q8@q84dgNurKLfI@z<T8 zp?laHw^eWkr=?dzi9!-mfiw;SMDh?@f&jCrT*5-SvUV6gN&RC$cVXfR#Q6YDsWSXe z2=XLd@;%OY699;YJVK7^1_>k$sAKbxT%UtDaNy0t{?#7;@rU6NLTYPU9qva69fL#} zcc2Qm=?g?*b8rb>5E0pExt>pgM*!~sO{ReNfa2dt1EGWK<F4Ql2Zms)(J9b3q(aZm zlI@{x>WqtoeOxgRU)je(%*Y7k7?RZ1e{AClzbu}|sMmh5y<Ea@!54voMCnA(NroF$ zcPjeYUS7Go4~XQjU5Wb^pRNLFPAZ}4GqU{?P=t1^XlXEgixp~g6z~lrH`&X0t>{`u zX8&I<y%nnTJFupIwR^^KE1o88GSZcM&b-K5IFkk@0(E8`$Y3R8>!EQQK{));qg_|X z<IXuX)*COL03=lM3!JG_+oNl+{jQ(7@722;u-d}KXZrn!yp@{Y?(DB7!t&qVw3|Q6 zy4wHJ=_Z&$ks%7YYv@8G;r|hDaPwz5iWr}(9e?I3l&`xz+S0x4TxXJ5;x{={LeV_3 zCIs2g65664#IhfU!_~FHV3N8<pA}C%_&6dLD7$_s;Om0j=Pt9K%l?6}JXb`Ug$6=) zy0R6uL{|B$6(>eK3Bm54Lj+iqCFFO<RNA$LQ2ggv5aTY|OpgO2DLI<*p33Rcg8l^j zL;@`bjL%URJTM`Hks?FDHe<ky(<-If9O6ni{gV4nML*n{CENL6#I7QEl2*IH7`5eq zgcX?SNKH%k>H)(~ay9E8yEaxEXXkR8g9zx7G6U!<P?p<(@NDfF5Cg}Va^k3i*3M!g zXS#o_jmOE`){bECvYa`ne@P;UX`BKB>`sFq1|@jl(nCfdn92mf_P<Lp-0@Hu1i~C9 zcEUX277{)jd_#S~_N0Kx;&#;ijhtinD0~Cqn4yV@rO}wNb<~|yswm0?h?$xA9NY05 zZ4VYKmQPicx8&O+zay76=B#dH|LzM)oY0X<@-O~20TvjaXB!@`o^Sp`UO5PoB_$T} zL%|B?eEoqKtlA4Q7lEP+@P3j-CDx-$$(GB>IrE+m_TD0#>+YUcNrIB_!!88nFP6P> z!-Y;(btGNCa$Cx0eQm84M^%;w)n@;}0Mc{W#HiB_%2qj-iS0F8HAEGb2;PR)S8eYR zC9HS*v{H}r_O)BV5P<0WUogf{QZ@j4EG>Qia_O{Z5j%A<RRGH7@9hFcT-TXy3pN*d zL}DiFwR0RiYUQTrq4$CnUM=qmcj0x}U%59pUG;;OU|8-!Nj}}qnAHB;4QU|4DOjJz zE7=s|jdv{)mTs~I?YG6)O*f6RVocur<!W)CDXR)z$WLJ&y-igxMD7>4;P7*Lni*XE zOK>#u$6*CVsGOYqwya>4tNv-dt8X3c&&*Q<#xN;GhL$^Gj4gNcP-9|@p(PKKm?bZi z%AgC3|1THr)S?*ul%s@mnoAUpdvVc->?*AUwqil?iZhb57Jk+!Hu;myCb4p&<7@rl zwP_G&Apj^j7!sF&V&cDUGJzA?ID<*>t>$ip9OdtNe#VJVYvRd&47NIlZCQKSe>*^- zKnL=)d`Rw2KB|8Zf*q&y1(%OP!_1%cH4XOU9@O`GS6-<gPXEiL9_~6v55{}3E7_bR zQa7yoNpkw3h;QA`0PfN^|8dTIJ86O@cqmosD9t{w*S<~vg`5&xngC&K!dd#4^eQh# zXfxZv@Fk*iVap`bESn~@@ODoY@%J1EfgREtw>$YRbsFAB4)k=5y1z#Nhfh|{b}zyU zo!KkrL&l4<p1?u1>w`RKC_b0Faatqwj#h_DXU@IpQkZ?I233vrW~gbGd~^clkPV~J zDoY{E+*PdMr52`O`(q3-$TsKnu@b6?bYo$=JC{(?aim&L$5l~<nf5J5uLyXWc>87x zUh6|239iz&d=!wipIYH+AcP0B9|w|w7E3JJ#S`7{LMUmo8P|GEKDI}AB!EMfz1Pm% zX9_)8J<uMF%SbvZHT&(#){u0|+X8;DC5xZ#D7Q3SVda_VA$y*cY*P-S1r@tw5>J#o zMDrG^(iS(qWiNpu!_fx+)=;x>I)vf*D*+i7ikhc!FBGPX6%UuLZW-cY(YzM|*soal zHf4L+l~;&C=^c^3_aj8=T%vb;lb%!fwMl38)DOyQ7MY@MsR`pr+Jd>MAx2)HA4J4H zrt6_JMi5q<q#o1`d8_clmq6JG`XMOJv=Cffa$JiOdN}CGMBO%rz;TRt5jrZ@$mF&7 zxQ55I*&z^_&R#^Tf=)6hJ1m9MpzYxq{}^Tth4(L=TMwRV&EYj}aE(1&o5lx+auRV5 zsAw3tTSSTfkFYlZhkAYEhow*oEv96fN`=uv86j(BNwzUFrVydcNV1iEDoIUtp~jYF z80(}=$eO)HvX|YEHEVWb`aj<popXNI`@aA8y1F_g+cEd|e(vY9-6l{2M7;?F7aH&f zfX+Aq2Ou$esoF?P%k9Bd^;8*=s#p2`lK)eT=R`INc6iPzG;i*Nx?oh+hG1#k57jtT zkOmD-TGw~pmn#SzAoMmM`0yhFxDUP|k`vwDuaL$V0=2}WYBV}Qs7A%fRlOstfrpTZ z|1@)I<(XqmamZzGbu7~x9<%7<ZOmV-$fk0qp?~wfm`klt^K3gOL;>sX0-eknxo+lS zL=md8`yF4}UD&<Mcf^De0;tjDLVBuU<n0%0(qV)BQCao-uPC(M-6gKI&sm$x?BT^$ zr?a|ZOf%6?Cll#`16ew=ZW+JBVzCOLM|C7Tl8FHQW0jvWYHbCVH~;#{im99GO562h z2=<$!a?I>m`8}VZ&^z<XH!?o<D-YRos&ah4TTW+fAfuv8D{Ejj+a{zDU+G${OzO^% zXbWdU4cPDZZ)U!C>h#*>DGL-IHyDDN-o0CvgooR8^4E5kNeS+>ukbxGgDl9g(p1?n zM|B0KZu4!OwG+s1xfR(SR#jz7GsJXn<$)>%xZdiP^Z=S^RFasM*72^4`fq3>GcFBa zsz@vUfg!^c5ZkPC$1x3N{(u3aoWP#~kS_K~9W*{sUIKSoD1cH90w{%b_JPiWP(a5^ zZ5cP>08#;{476AnA2eqHmYH%h3F2_q=Q!3K0MgI^%A4g(14;ML0iMLZB(U&i@EIRT zlN~2l(BMz3^t|;ZcpGTH!RP-cjZ|8e>kM=l|1H>mS|I{yWfo2hSH3`<2i@zg%97sj z5BmX`gry}yI>hV+t(pjeaaBLz?(<N@juy<^;A$)KoVkSHC+QKF6F8i}%1G{*%=pob zQ=J2=39Cm<o7CIDqOW2?oa2(>#0)lVb$-xlZ!H6N>KwuI4P&=P(6~eu$afePXlW0( zFEK6rl#81P_=5N*N~aze$i65yA(FvSsd6`yI3SqQ?|%*#M*4PM@ED?S^~Z#P*4A_P z@1{zl+EPq}(;awSaQhD#g5}#h5@hA;Tz9dugP1^ui;1SoJALuF<>@z9F?xl4m}!^< zG0JGz;LPUEQIm%{de+7sNE2P)a_dNRhs2A<^wrkp(X^e^wvu=1%iOitG0E{uq!5Nz zepB(rDy#93HcBU<Hg^Rp#eE$)r}N?S4i~!A_u$>7vs?2vj7TR`Nzb)SprH6S2x!Qi zLcX|l@P~7XfLVA4v+dV)Ztk4EmQb+>8BgJr)rA$*sY>_;3-J|;v$JN57?eMs<<=Q{ zrrJJ+{qt|k39p380l;x=h15ug^S{p!f5V?{RM>KfAn;va`$f2|m2Lb(k{8yFhkQ<% zNVF=%#=J_62VZ%%RdKIggD-9C9W5+CNsWO?81OGN%|NH~;2xWJt&Wnh+X8JDSO{jk z3O|}`x?l%*ZU6oP#<B%ZlUwqi&b(^5wmEg(n$9Yf^-+&?bV9lr&_h|r@Lw-G```Zx z5kRO7C~0IcH>99tk9rWHEEmlBN`Gx{>-QIEq7;X=!#sZuD)sNt4Bj(bS@P%I7UfSN zOJ}JiQKeEqK^zjWLV5^>%wF1g?C6Krat3J`u`PKmj+U*`w*q+sO&ZVL*d?9wre)}6 zZByx65aQ4SCZ2mMSO>|clL4zb%WYGS2!nQc;C_dD&ai{em|uo_R!-ZAh??Gb3W;vu z>C}Vmp4l#uHhB(XpTJq1LMk@2$&ix6J-i<&7;q39a>OBBLZ9Cbe!BGew|g%7M;QlR z20Ni2yd|4jhY?B0>$NniVC+Ux_J00l*tQt31xV-dUQ|=O`JJKI?07_rn1Rv0Wi8Xd z-=sG|Z(^@rj(L)?Q~zQ=o*UO$O#o;gRD?|zeda;_VkfwJDkx`ow#>(+6KabD@XJ86 zUAb5r{P;~a&Zn#&)BH48W>ozlKkhPWOlHz)k!vgS?R3(A8X)#UjPCJ>&yi<+>>K8f zZ^bKw43E6AT_b(A+BM#RUiJ(;_@F0WzCrY&#f4`fQKc(u1&7QV9$N8FHBY{a1tFW> z*}g`>k^NS?qq)05G{Con9mGZT00&T*N<fQ*EH)2Twg0Miz$Go`w9V_{O}#Vf&E<2{ zJn56c_yf$=4ZiLaE3)ae2ED-fl+>_T%y@;VYq9`pM;P|tm|En<ISPQpF;Ig7{1>p% zCPLvjEG!v{C`%(lEbc$QShwH5((C_gMY5$ce>H}G8{fJVfqg!+Z@=t&2>2R*iM_v! zFy;sw+V<C^eA>ZICSg_Mt*&E)2EFXe*d?<OLM{_F<I{5O2Ehi;0hWzG4HA71$+MRp zW3o?d%tWsG5cn?do0ARB_X@r;E*szd{+YzfW&i<tpKj}1>m4<=3s^fgLdYY;IV|Z8 zR4oKFX)?yYlq!H1ebmWf*spZJ7nwk}TAKA+8?ZbNKxjS}<W*1X5<jBmjy8hfUc+bT zZh=9{9!%wuQ|@b{1bTR+MqcS@-7$V%qg*~^C@f(kcZ_&<n*4}4Up`HDybJ3cdPkZ! z?t41#9R%01Cnjc1`q>A1j>PNJTBi?dqOyFg%!-0OhM`Uby^ycmDb<BYi1`hJ0o?EZ ztt9>53nzNJZ1j=&;C+EvSQ2DwH{j|qmo)=fZsr_6+}ld6QFXGqSIeZBgp}r?&1vU6 zo7m%xy*6%g2IWEM!KcgbFq%~k5T_T8dP}BsT?ma)i(Cwth`cVb7N;h*Z{*!0U+nV9 ziuM48)#cX}J@doDGQJarGCjT`v11X0_Fb2GZ0D&eOa4IPF*BFrQtoZv;ow72=Cxnz z@N;e!aRgB^pJt3(J*BlSFyQ`R9cE_hC7z9)#0RAlngHGa9u?`V69{3D+k3nT+&RDj zt;mY-Sf_oZQtAMF!74#g<pD_4!`A&nciF!>Yv@J`O?E)E3W;IR@Km;0fPIGlEi6`& z0uP8%SPvRu&7Xq63(O6w1oX*&PUrO$DE6EQ4F#+r75W}LJ<+M~!iMEh3{`t-+hxDC zPfI=18=RSgZT6!4(k&>+VN8@B`%Wh(z4&xKjf*pi7=_#<9H8iyL#lilF-^@;QTq6f z)e3!1an6o-kvgWM8G&seiWW!mz75FWCVF85k53K5UcIV!<|of;O>u-3Q+NnpeX}#z z33u*n_IZKJG$$a)F+H%iJna^5d0R&E3CuRRN;FEgRj^Q$XcPObDmao)6(cT%sIwdU z)rI-MAzvZuWN^K_TGI&AZ6MTuR92qco2jyE7W4RIAnjl{m;NEmgz(HM8>LZ{cOi&f zYG)b`tj;%HB4q0=coAYQ7~vmbs2%B-11rFiYDuD?2LRw-|KTvvp<Q!0;9_;oTU2pI zR2^mIb?#09Z2wnJ6SNWjNw6LJRtHd6w7Eb1MF~hKXqX_XH2iqhKj%j)PM)XMd2H#n zl$&v3s#>cJ6}JP197|kics!ARNpZvmKXNT}kX|4lrZ9o@jcjn2TNoobS(&Y#k&A@M zfLq7Lw#?wXNHD2o7<`~y@*+Og4>R8GMD*Ka0tPflt&%YhL=XSGstXh%tBIs^@EsLw zwZME95l;Bnf!7rGLYpB1YbVYd?;zTZ8iS7w0cFU(@ctzypraGI$AY<#rSoS8%KV)X z+2HUxzPBz&T|Yiqr1IY+X!ef-l+(FNZgxUlKq~M$vWh!gy~M;)c2xlp_hILf&8Yeh zY7i1x-ML}>(uec%ESOMQ#{x5l^$b%*=-p8iN^Md4jJt57HcE#=%`R4SK5Dcov5W#K zNVRLjt2H!lDJS|?$CVNFxI1t$Z56xY-*Ef;;)4<SPs;{s)E7I711<|~mWdJ5G6OK4 zxXju5KB=^GDWp8lfo~Z1VdT}F#=KDy#FDL7n?CR31B&!XtrM5O*JHZuXbwk%PqkR* zyBJv4rQ2G?5EFon`EYN4MyH4hT8(yF0l}?`;D*bl$<`%mb6xC?ESGPyq-WL{oYU5p zPP{t{*}RQG7}I>hN;N~KBkz|&WP+Y%TU;xi+`jTqro!8p^NW3av+@q?RiQ$4vqh>O z;Id#)Z4tDZo5+fc3}wBbTzxjH4(KG%3-k?X3&Rr^)f!h1E%6Vp=6+H)WB5f+wFh~d zZ~V1AKaqN*u@_pL%sMc`0KU}meoMj-vSR6rU)qC-i{b+6Gjh!ht8NQjR%7iW2pbNw zbYpRvg_~gHhD~lj>6`(&4y7kk&%He3dDnm+3U(lz-K1bvhm)^(vKiaI7%+fL_MVY0 zfMzH?LDEax^zfs-dan<BthU@;nC27HIh%$o5X*RbhDQ@~SrhP+woM?Wl--e8MfEqn z=sz6|(&dZgvN5~Ad;|-nW4o)@v%l6+#Pv?~?<~ijf<f>48~h2eD)DT43d+bZ?{khd z(sbw5#$&c1S-ZV<C7$aywd6*WND$C!LkF;2jh*!8wp4&tqFM&XN0q>81}mXkI32r2 zwWQK_)9qbgh;t<%d`SvpINP;kGt0fpZmZTHP@d~fnK-w~^*<b%7LE^>jv&ea&hmjU zo{S5#AMnq)3UU?IOH32@(sQ1Vnnw6@W=U~58Q*s?MW^)}i7Iei((bHAF3Ioja6#+# z1!4ioolGp@YM&Ms!@|Wf(oGD`<EzS$POmczu1_k}rDc-rLk+bIL^xgv>kpGp-c=^P zyt@M>s~Th&R9kOcAYg1OioUp`sSH4V#<(e)_gm%asMnj`xMsoiq<br|IXsi&6~(5> z^@j^fPL`OwxIVaM-_6{vXy6Q|P`@dv(OV|kr$Njbl-$bFpMy9yUeF0_+^7ZWH(OVY zewp_bg-pJTo~PFScu$&Xct)7rqCIE5CQ~OLU3I3!tAB2(?Hi$4At&6f^se}PojW=I zlFe%s0D!{V#2c*cR5H_jAI9}0vPSy7vWPM>2big2iE)cb>@j@eAlBQKcxD4gw*u-r zdU)u4{NC-?GjwI;j2pp-_9zenF#d+r-$g3!PkYc2_j48V6ySjs)asi8obM*&FCARX zG!JvXZT+~@tf9Z%cnfULf`*2(4F4n_*r_#qV_947(!s@y`ld{X8D`ykfd~s^4Iv~! zq9@d&K+UmKFgP~ivTnX!zbCH~WHq<$Kqqf#FsrYzAesN%Br;oA$O`yu2uUF&mJM4= z@X^LLzzIQTt6SQqnB*%6auT8H{ZI8D$eEru3ixmV&$^FFX$2t57MP$&`ZGj5Pq%as z5JC~$G@p*ZjH2T6YQ$vj_D+J3&bIhH>hJT^J~RA{tZOn|%O-?N`UgU`n-ki>P#3r~ zCpT~yR4Z;rU+;V{LLI~t)dn<aQzhDKKP5Bfa;%kGDPIv)Iy}gvWX>$!m+oem8iNaP zF)w2yCD?)3=7QUKtq0#BOhpXGo-%K1aq#6e3h^LMhntfE?$r}LL(>jC*l$gI<kPIH zOf)IDg-+RPCSh@p>{278VOP%I5>%d=MwYnGC(r4L12~_N&dLY#1s^UiwZ~`es=P4I zfe*-uNg+;8?an!zV`RAc3z5043!d$Tt4Nc{sZg!<4KVw|ksdOF`0U02@*yZ}2TERp zwle*#MW%AdsRg0wXDbG>YxXmf15-%%;cDvghGXi*>SXtvsP9j3sY^S3NDPmGL1fcs z^(m3Hv0;YhKKqjs7kgm0E`JA7N4-@Nd|rA^aPkkwa1*;Aw?sE(JcPK-%u_uS{M(=Y znk+RiLK1)u;rB&|>9U`O00zGf(n09mw2#yWkl!86LzX&gg!zzuMs7sLaI14A2aeF+ zuuXM!BXK370=`9}pqVj@sx~W|R@uET=WAp&{=GhG8;8tSYTxYd8kzeocQ)iGj|Lpb zwV1&sq$0S1m;jfQcsmbVmRZmu@RhO^d!X&vZzDbi$35%u{F_FxKL4=@6l5?L%YL#R zyz>8Dn}4G^!QjVkx+x)3n9Q#(#y^gY+ckf0uT?u>@V=^YE&0+8$(~eb;6s#3B?0%- z3IqZ5G4rOKPnztXFuWs23UteUq25Xbh3P8<)~a3iiC*T-zbcn~SzsZf&3|@$f!QQ5 zY!O}CS{ta|$5~*+O~`hvcu6-}=J~_XiMG_C^FL#H;bi0RuH(2QV-Q$zyCz4f4kj~Q zkjTwt5TAFS^N!SqvnDx0GbX?0$aSFj`V}efX?nVxaYY_=$=7A^>c{QT0-tBUsg0(H zX~`&fq9coh9lP;fb17Yw*@ofUoDoIRk_Y1Ak~#gC3z3Q%JV<~68YZvO-^-{yEJ*<J z#Lyf4Xo2^3JbI5E3oYUFsre9#;F!wROTOl1OE53>N}i480b??AdIC!eA#05$!Ox$w z1?kw4e+#on?Rah3!nWyA=FhH#Pi4YWhm5Pd+JhLVh`V7SPL=|8N*H<(fv;Pal%=DZ zS?F>8c|=#Ms?#OcAxC`8bYZ94)mo+}aWz$7ehbh$V3_}w=BWvc>5DbHPac%RV1L~< z5N4cFqLV)eI|S7Mh|J9RrASZun0z>#J<zclS=?d>XFP>Vmm6H;Y=AFeG;j6LL0p-; zc$?w^6Sko4r@v#g^V)5hpqT|)%INfKZIP19pC!1e+|#1MzvC{L>qwINr;r>!V4u4U zFPfSw*g-4Wpt-M^eIm0|Fd!+9NR-Ylr`!b1EmaN}P*au4L0aLueF-YRb$<$aZxJtm zqS>}8DJZxce8m4A=Pc}Iy~Be)0~{Y}m~1wk)j5+DjS&~DiuQ>=E>)aStf8r|*5oFw zK2E;<5VTFpXdar-0kTn%A?w+BDIhq#W%L3qJ%DU)=F<wsN1$yH-%ZeBM&9kRtvW@R zBIqUPffxP@94yFC9#&J|@P}iI@gEK+`>zZMaAF-@GI5V!YW6Mw#L(SulDa%$@y0Dv zdK4$Pn7yIiEYQV77LYtIjbOGmjk$KK3Qg$RPbX0kM3J<n=!cQ=QW<?<0s5vv?Cl^7 z(Ysc#199d=QgXHQ!TB`rPM`EMfmd57OYo!GOTDDvuu^Mcr06gVz=Euz+<J2Mq0A3& zHJ8)`@<p;3VsGhBcfzx>HdSZgdp#NL@R<c)+PFHOXwYqNa5t_Jmgb(VH8L`+o5I<H zJDB6a&<M0i=NB_4Lx{UP5?(8W5(+&eXQ@^8<L$q@_*(}Pw!7^=7VS4-dC1Xu+up_O ziQV*btp~o_w;6YZZWdhAZX3H`D>A(~YeF3U*6PwZ!Z3we0DgjCBi5qMZ2IXx90_`l zq01=c8Z**BZ9==(lO#aaUQ1sRLu3ZiGa}3DO>66k4lErMMO+PW{8-Y>T>aTGWvKC- z19TR2743T*_p{|it>D~Vd|ue^db>(EtjX?kATE7G_~|>DV4230rHI3E4uhF@srzSm z0<X0mJd8sQwR^_wuCb3RD7ub}I2eeJm^_flQrWXCoNQKw^_@YQ)cyN-AH@O$T9o(t zjG-iF;y4f|CIXkre+m@h86nQ44{$Dju^P5^ntiVU*CEye#VXgoCaQlzD*iTKC}TjQ zPH>#xQfmPTwk@D<=Y#Sr9AQpMQvuPEbbXjJQc&Ek^FBSapjI$5@CureQmq+Wk*ZY- z!xOWH{mi1Q?x{u2r}-PL@Fg&KR!jrovvQXO2%{#WWwU$ynD0RkT?Dd`W#NF;XO{Q+ z;Y-Vo6%kcHKM0nprWQw3!QDV)`_G7M!(!og0fE>-MS6DfZ<DCH>Jur!WY8R_uX>~@ zvCVaRtIv#o9eePYe@sG!o>L8PsJG<c=Q4E_B_(4=(jz9D6gf;hTw?_Amy;dkb?z%B zzMC8h!|c%IQA8qMHNXIDXb7%0Ytbw37u5O0I-JB?UD5=>v97-Ieulc6IwfRNaN*d& zj76)N1({Y~F+!b<0EOCgRGp~;2$nkp#M{p46tJ|AMJ{B_0UI<INb=bCnFG;V1&5EL zmv(mcFBcwe`q6>fGd+3bBv>m_v-nZeJmn79(QaSsS=M=*d~Vf`<{{a+8~MYMI^BFO z23NvtBFr1lgWQ6}-Z!uMj>(+Fg>Kr;J5=Rs(EWBrSLRpD#+aKSt6Lcvy@cPR#x2k- zcN+*PrFK&~r_dU6$zl{mm}TZEJ!*bz3!54Xd#t4i#rW-%t2SkICKTGi%uNvUrLg*f z@IaX9b{DhP^mngbXa(bc<9~8<UF#mBO3s)b%nxXLbC`4%vo}67ydvrDKAS|g;fcj9 z1K}3vqFU$H?4CE3W6lkQ6ZIeHA0O3ENy}}}yLPTt1r02Bto0xe8ndqJ4~^x8)K_eP zX1#Mlb1Hbt|J3F>fb-WuU<)8mXygRi6x|vPL6XiXljFJ6a0Wic4d^#}kac7Ms4%Y$ zABc^U=Dj+jJEkyWzyp)rH%Cs5+DNo<OMmd8Ua@e(;3K8WsoMS$A(N2_)~;@OcMAkg z^r<(|fW#&&e0Usf$H0ezkqQi-A_KG31%^>q4Q(iX2mNOmZ*<jDrr!au-dS&EYP(M> zSSykl1p<4=5Gx>dE3!t*e9O2A%0%Zw+OLoG`m&V{`q{zKKko~cudSNwX%OtNnV$ER zy;P8yQ6xvAo`|EJH?}1`c+I6{nzS74U_g^ttwf6YaYy2UwNCT$ATK>9@X4nkkK9zM zmy6&-*KmW425n5ki0s>!{%~YaZKnZ0sp&|*d8#Kx46)@8M=J>+h`XhK^LebL?exP= zmJR&EWiXV$nNS5sS*4f}81A*qJ|^}?e!nhQ$Hy|DvCsRb!Je*3m)Z^AdX1juOHVMH zi8GxwPv6@cZvVmefPI)<RPR;8y({!m?N+gr@be<cu3683|H*e;h{r{ERiL6r<XNTJ z5e0<WElw~mF=21z-9_4pSH^6ed~vTuvAYzbCXviv&#bNit=G)>p4Ddze~T%m4?-Av zX)_JJwSqNCj%~5YB-?GmLD8xRiNF~!5NPXsM6s_P5Zj9ux_UjGT_Bl)=vJ5d^Ld^o zt&|pDtQv^Us`)OMeNvi28hhpO`x{olcYY%h=ZMd8R>r!-x8$+-XVz~3-~neeWMKm3 z$U+k30L_B<Z;>K)gN2hx!I2xFER%H}(9nbBih^({(B=OnSwPXUEA}4{90b;bWj5g5 zj0|b=ws8NGX94Z9>>D|o7W}x|*NNGfv)|qJEJSg=8pKqR4{y1`wLe5m`src@9+<6^ zmEHFROWSEQ2nH5u;eYrvTVdUGf!ga5p`1XzRU=0?51U$(ZiCP6dIt5+OX_gK;3<JM zXRDu<*ZPkyEjd=?fHPiY2q+aJ2gLWSW`a5NNF3g}#q{|t0ln9Lq_@TV599f@?eG{; ztiN?rr0p=#a$W|67~~ID%OUjiADHfU_SeF%{p8N<=I4NguSO+y382r1nK{)EH>jpx zemtF7ukl6mm7F9eSwak-e5&3bcDOkfV|(Y8iLQWP_ZJ#KAq@wzi}ueBmH1VptqD?T zc4eSGrQf<D2YO^z2XXN~2-(%R5}`t~xw3#9v`N4Zu<CA9@^0K-px46wvL^64u*ori z>FF4eH3Ng<^HvqN&3ecHhjryrk;$HuacTmEj^&HUVP$gHU4;<&IDc=u0R!uK1I<Cn zeWJX-H}2`kkyYkhn0o9hw5wapwBJ`(32wG<<8x_G>lgR%X>)TAiHEJjINXl!-$f!u zoGuEB)y8ndt>jgd4mFARCTs-i2}Y(#CTOd2Y7;70J1>CvB&LtCwBJ*hV{#9$7q7Ia zSJ+trkO%a>NMPc$9yR{Ue4w<X_9~{2fHL*lfm)u5ZIUNvAOc^H(8M5~4~(1;ryU}c z^2$jI2Lh=nc3B`R2T<Er`b<!|?l3O)ou?MaGC;qBN)Ehn3#i6WU^EB3br-Y|^RIql z-3R)=a-H=tl-*(3csY=y`LPTt+K{74Dk(O>Gd1NdMZR5bjJwog$q(p*x0OxdHZg8M zUHIZkYXTYaafK0|JVaa*5&~HM$p>b;%f{+`F7<<Ha_2J@(>|zOj*m!#DQfTlfWooI zLkgJR0kD*F7UY^O;nwVZVU8esH590u0Z<<59<XK%6fAm!yRt7D(tM8<WS$*VX^C;x zGDkg>K1s{Cdi(MHlTEQo%U;+gGX=aPW5Fw!+vNbr<4(CD!FgXZJ$c_LBo(-)2Dzf% zTHTe!Q&lsr>bEAAe@HurHPq6SS<riMzKieXRozI?AAe9<?>19X-wc%j?9woK+<dnx zpXcHu*((wq?_z(ZCzE&HqrzwIFNZ8oSUO#GLh4Wg4dptDdO6?KpAjXv<3?}$e~kts z^cB+(yx!l#{cfs6e8MnHG+?NsY!K7o-!bz3<i{qDn(dyvGdiJ#zrpyrYbl0)9C7@0 zg(q>@1@j_yg;ey)?zqc|bACsLIZNNZZnF92`XaBcMr5yJdg`Z4(d)M5FtA4WV+&1` zu$hS+ELCh1Ki}V!ZKx1$pZsm#s_G-{+mE%Vg|4xLYvu!KQMA{H5)IGhJ(JDVrqLy) z07VD`Nx-8b{uIRF5k%23#Gxr&5V{1Jh@l$|5VNxQ7x0o3!3!xkhA?2Z07<d64UmKB z|L8-rkRUsV%5gH`I`c^`4AlbYjBtqYi`*6Oq@R>%8v(T1E*;72lpH`#gDII^m&UpE z3PeTNE(LcWu}wL+!8n5Da%R^gYf=WKww@EQUWV+uIrQDIj&*iJWzm?RY5wD8QBs>X zFxXND+ord3rPLgpYK(xNKrB)qtt@QD((>wV5#<Gdk`vL<+oTctY-gMD9MoGAvVG9~ z5<%kMLVh>ppRav-o4^ZI=Rx)Hq*nD1!mMDP`rH=+Vm5*I4+qt;g6e+XrostAJ>8jQ z^#y8wIGPIP6p`1ITkAa65cGk>^kgLon2&}n@PVc8nk2p!M9`DO@O7erCZ+fjcUvrS z>0xh_kirW1LGM}n^9Q%Wk$XB$mQ!LKM=?U8Ei-k>m|q)2O+35`MA6>GZmACY=wvKH z`XG-Gj1L(Dloy83iXy`UqvlZ-T9&zev*&!fW!wsEq<Qpo#=t^mOIf%aG-A{rRc}X8 zs8el4j$E<$?E|Y7Wf!~^T#_}JBiWCIQ2K(bvmA`!k(R-y=Q2`$Mes~#u3V!O7M!TB zLIr*Cjm!M1g344&^KCx9xeOtoA@g;9b!4uS=e^1mC#(HS(U@q=dyk9r$nql&_uL{^ zlZh+ve#gg+WCzQignI%&h~inIH+7;gbP<@TSDw6W4wPy2cklZBOho!PJV%kbqiJ8X z`OHSkQ!)kZh4sQ8IBSyqWvpyQtY*0YYX<VWZr!8wW}8GM^AVqK$0x@-87oZy1c;@- zJ*9~X3nS)mpOB^k0w>9rW}%)f;a0B=N%+~KZK))%a$Xg5qa$3W2xO79bn;t+q`15l zv>kavDp*UbfRvrfs4u7BOCV1&L}2T?JOKDUg45Y94GPI&kD(w)>fA-hJ%BoS7nCd1 zBjsPS6U%@Ak{$Z+|I<xbLR>ahFP)`k2DM@K5FrT3dE|X&&hKFm=%rRmLA&cc&o+~O zzvM9k^$LCRFfKhqJ1DP}UVAew9pXk+Gv=Ruaj-(W0~u6RRNMQ#z&P-TM0k}Xu)H~B zu^PKH^Oby)Fd7Pa0uu&?h&O7HgevcgU)4v+?#vQ!_fG~knjphg2W5KBx!BfJqi}Kn zvFRBN5a+4SXsVT)$cRl|0cNgO`*xXb-i8o{V6L9X69t{`()K+Pd^Q_MPua6kF;x!@ z)60?&qsbq+XA}P;VzRMQD1~P(^`+8KB2O?v0hBsoD20PR5@4SOxJhF7Tli7W0Kb?; z_ncJAg9lzHqs_~jiW6#7$3IV~w-Y1K@DjM*7(=wvk*-EByP$Hob52p<H51!-fti!c z(p*8HFm^PgnKQ9-NV&4RbgC_DDQWQLd*M;18Tnq{;)jks-hO^o>fQ!3!o_|D_ZjJ6 zSM~%&5BJlOT77%TQQJO-G7)+$WgqWK$7lU#T1`n!NkRxU$86)GPT^=(F8AmsQ$cHg zIG)FGdB8*Fjox(fsi~!gY_wCq@$Pr54^!*jDV{H<1s0=`3x^^0+x!;c-wI76^N1mG z=UJ!@xTZWL2Gz(Sl%E7|0a^^L^Pz}Sz=)d0udRxJmJ|Jxn2X8i4pJkYWo0;o8QUHP zNA-QrW?m2yDUrROo~|?uyWF5i`B<J|PKsq~&QXo}mcDo$Ag8pA-G;%kQgdq92flv@ zE7KQrMrh7lzZR`0_pSr+5E?KF=7RNR%5I{df3gKc>u+T@T-K~A{Sl0pH&^N5@a4_8 z`ZB?!AK7x$V~!>IASi;>bTw2FcVs~_MB0HQ#}Y$pe@;^NyHrry3$cpUAo*LJsS(xs zt-kgtdFA*lIYa`WN)L$CnNFs9w!qp+5b6|D(L2M?X<lv%c*?WFSG(p)g|`Q+NUgN* zR_1+|;7P6W5XyY?uo#V*upTvgRxU(|nZiDKexFa@_gb|!D$=DRf<V3qf~Q`xly&Fx z!evY}Hc7zXFA|-Ilsj<M^hXgI<0j#PSJ2-Uk$5ExuYP<<kdhv6w&dX#+&qHK6CKfZ zx1Sfte4qjx)L<9+_K#dCndaiXi}h~K0G!R12Wt#wr@#gbCrhkj6+I!Hkfk?Pyw8aM zZ^4aP`Q-xF&e}WmqBR)`VIC6+=wesO(~qfg<<)0@P7Wn?`xV^H_Bq_47-ir*?K{@x zG}-O%p^%%=H5Tn~&)NBWpC?X$?tqf_IXZcMLtQyF#H~b=dMw_<W70n2T@cmLyFv}s zRQi0$sGq9PPy1LqIZ^vL!E9cn#_pOOp~OPx8ItSu>+b@Gi{-x@==G7*tao>q0}!26 zZ>vk7k4(p{<lVx)IzpnRN1qQ}fBCx$*I5c1)_iBX)@XjtyCPs5E9O#-12_i&cYmUj z(twuzxF=N$=U9R&BjZK{+LBXG+CIR(e4;2=;Q}DYrwxjL!(n$Zsic(N34L&ZzbG_e zv?T(a;-0Q>RJ$L8b#}&Y5xF^#jlLae0UiTr5<bLURskjVKp_!{zIh!85JUl7qzZtw zXQkyT0L+vHm;SvXv8tD)t^n-Pwr!Y8`(_O5Zu5zQhbfmw&+e9!QPTe=N<ud$wz?9w zp^whOOQjOu`?4=tR4v^M7gBg;qan!R<wr;?`g73xa19AC^}%Dl3H_FOm4Hi-qV$B} zR7jyxmXI{`Ozq(~vGZE6w6r<T6_*b>%!BWGT3fmabq$grJlzDov<9CF8P;DKU(C8l zXaGZhjfxCN^W8X?UE)r7)lDcatHXsX`N6NkD)}E~r}bnDxx+m6Y_0Wtva5(YuSO2s zB#Zs<f#?U-@^h5PTvHoI;7Nk^C(o@`<h-?Z!otbg{QP#(Iw%crB^dqS?1a<MQOrDZ z=<0VwP?df*HeA6h=z#?B`R*O`MDZ&~fSBqJWIx;KWSQRAP->qUv1adMmlR&yT>X6? zpe3W9h14Wa*5-1eD{eS22q-IZ>1Kxxu6(ec=6&kw^Pq|rd5q&I3Ye(u$P0(1+wM-> zJJFeDsz_0BO3#vp2V@yaJn~**N?2OuZHTZ!dK=A17Z)oSCxj^ubQJHxgl24xo<h3% z3OD|IPda_G{rG+k+>dvjSIzjJ@rP~xz`HeU9CLg75v?^Y@0kI<OH``C`#H2FZb0n( zE!T!O`<LSj6E@lXI6SG@PWIH!SUt)spf@xpnomk=!F5^g{4m{}3-5w87F766VFx9% zHGW7CAEz1>VXv)58WLanPT-(q9Be}mh-%VcI2nVgMY&Q0K%fcK(f(<2uXZ)XOQbDh zt@lgN3<Y`Jt4})*kWqIvJh3)w{+O_8(|fAQn1e%!cgw4FfbKU^B=!#C$Zx+3z#RdE zaz_`_X%J!s9pzvpB9vyvHu>*YgaKjZKMj|Kk*<#ez>b?Bh7dqDa6Z`OhCEUGzyxrr ztnEYp!K+yG!8*$Y=7JaO&4+>*-V;vf`#gHmTL3`-UAia@D1FI22vz&xDPqFx9)@~F zaU{4Evf}`?B!tpX8bW<04%~iCufRHNsieF)CeSG+a3w5-o3~@{)jo}ZgLL%JSSvz# z_3>J{)uP=%<Z8Q&d**H)q_HOBav6*YBGg4dS<TdYF;!)V#wUq|o0s33?HEwZ9Mdqn z&zN|C!%UcIwo&IYCckhTj&?c_i{s%;*jrAI(>f(`pJMfM6o41jb(Dn3=ET5LX7{I^ zG{z9;M6ai!NUuYOV=<+cO^7CiN>Z?mxg<<Cy#`;(e^S?(+ex$UdKo}dK>>S-M~+$Y z-!dSM4+%x4KO}X_d{w#lGH|A&*k5NwhjuuvRp!++h#^U>orkSl>f7D@3M2=C_M6*) zw}-YrA8ktlX|=n`DWAh-WwKw(xjX9k_>OqbdWVJ(%w~!T#p(BoBBER@Jq8>+<Q?|6 zz<U(SsloFywJ&>y@Wa^>_MiPuyG~f48T+R*8cvTdURb5*d>kds+rK-h*I=Rk%uO?O z^ms_I{ZKa3wxqfJ>G&cw)1Ld_;Km1*nf=)(f3<xUb95)wb^egS?M)Vow}vh9JY1e` z1?R*Soc2JNzNiz>nwb4lyB2-GxWhn-!7yw6D7m3b-R`jxXt-r}S@sbwh%$KuL*)2I zo}gNzH*sd|1gR1ajPqVl%x=qJ%=Aftxf$dd{7z>(Wsnfva_f5^2IC6jF$)TCG7<$% z?fXN;jIwH$&l|Mv^%y^PJkMbz)~1&K4g+$Jbs!rW$gX-Pd@p+Z{LgIY?hm#M0kssU z@qZsC_QU{!FK%v{14bD@EP(mA41c?88<dWU;Oc8BiV7`&hIQylrd#<_C?i;)qglMQ zKLJLsNr8XIJ!9SZUKr{KQh<oegqsz_iUaO#l-X|8@lnF2*pbk7t9t-n*suO8<R?m< zLHNT_Ui&*;O^Hw&=O?f{RQ9RZyb?aMmVobR2Rf(mwVzDvfbuZIqg_yhpX;VhIqaH9 zY-?<U=>d&2q>JMVE-8aIUKp~fv<R2nnGL-(AhkRkrDm2L&H<G6FVg+=Z_}hkjVyvA zMPmb-jqjy*sJ`G#3+CLcMx%_<5Zfkid7?#z6vfg5%|*1dFW8cCr$^On@9V&%&o)DX zO?LT?Fn8R#?2t1%XmghmfC8>(3pg=CPIx9h!gf@@rR?E5hFmq>N6R<LTSaMltrVIa z^5C9fz`g+VYp?FkWoK{H^T8SGs^51W{>J-t=G~k3QAtOS7QCa0?9eeh%|s5H=q8;! zc_-cKAVYg*tG)2c9q{fn&f*)UF}_D55(nFj`nwO<=LdHj`mDsOF1#9FQFD|>!%yoG zM_sb-X;MQdLR#`QmE=vx7Ks^p8#u@>2Y6?hhF{%M{$uuEy^p4e6!p?Ro!C(Cb@ib6 zKF)lGe!|VhO|+k$3VTz`R_}cPPV<UWx72^Y+9v98;EJA&mh8@Wv-T-X3wHT^qZZaW z44Xj40ZlQ~C|RZT7gWL$Bb9B)Xg@T1>wN^b?@8?C62#8$8AWU9fmOt8EsgWYt*5N@ z0X`*%Lh12{ny^p?i2MvIFndVU?#J`8X;N0{p@qPs^A~3Q3;(Z!spvZ#^cPuNTyNyq zD&jL6Ajv0G)zAk(zu4vtz}aGj%!IsIZZnX`kw@U^H*N&eu%WCwq*j6K-z@=Tx#uEP z44FzbSwiisk4&Z3QSd;>H4(#J?5JLkhXDm!?IY8du)N{y<;Y$}pw;valtB$3c{ako zrYsG7jY-R2-MEY+y4y0<)p<wU8krB==E17*<2i)dv;hlKC789LY0lY?*@sa1q?fzg zE(hJcFHNlaNX$2$80L)8<=4h*-EsnlhhWocFqgI_+JuLP7^m|Y@XKbTQ;5xJ5~nz6 zpPzDJ-KUHE&m>=09W#D;tM$_0#-AChwb4YIf>HG3fCH2lX&^Y4ZEtNE(7#*e?kilP zMW8<Z^@z0nqZuQ;8B=foyuFalFW43x@U`>F3}E?_``=DZcfs|ha%WxiSDH-3xo|4H z4@u~IdUKaAtM_l6E_hH-QYyNV(f+vb#=(5FrNNA3m0gk@;mUpbd3S1<W6qn45f@3W zd|s|D9i_QT$bPrq302WDv*v`%Mg06~l$~g9&dKWc?{BV{%Z*iXmKuehb#h<4<$Tgo zX@F0QN<02m+c~rPZv39tt4H62tJdRtyNBGg6gw|ZFjvd?Z|tKh&pK?~{98-X+RA=O zV0gNf`iA&x4ZpwXm1GGn?dkyFww%*jq`@tQ#Tc~ejADDqT5MMjR0k|KEJ)--cp@&- zqn#TIZ}!koy*-KdBp+aZtVxq=<n$>o-<GFhZgu->K$*P|kNObgRe>KvSTL6+fEKg? zHUMxn-~}E5m@F&v6wC)_3_<oZh2{ADdlh4|r_j>?6FH{Dj#xoy=`h^HKxzJSC;P{# z^siCZb{lJ<A<-E`@5iRm6da>&)=_sZmF+$zLBLOc`e(oap9Ms=WR<nGH?wjYwqZL# zU`<_B!aRVkh>J}1f_a$Zz)g@;ZWssAIsH8%;3dx(LG}Y&c9jZJg7jv(y$MN#1blx0 z3b%`ViAa08%!M@i!e!C>q?}T|oQuP~dL<=>I3+st(&W}AC$v1_D2~?%X1(WU^_lX- zRNKIof(m+Krd+D&^PCRBiELTQ_&dsd<8Wo(_`Oc$*;*Xcn0qj!RH)EW*0LZMJySr> z;tD;*FcLtm7X~DV-)XBuMZH_&@;}Km-wtS4!kWpjN)srBLn2J@XBRbE>o@tw`O;R- zPQTOW+55ytrs>5D5hsd4ZVKk%e05KVGsdcrFnyuyyG;L7b<m!RYl(k2ZXP(w*xUai z@aw^4(|d+algXlMay?}S%j`mSEjd;v2+h}9eF$Ak(2g21%GFu>epbvc<QDGhp61FM zTP^hOCgG|r)!I|qkapJ^>H@Y}Uht66Wg3rPPV;y5$hmDzd*E^~<@m6bd&lS<cb9X1 z=knoWEqfMiFFE{HFv2gtr9UoP$ZU9B<qmOU^RC^}Ln@+9mYT`trDTdn(8sU#9TPUQ z4&~yJjRw=hs7v_`CxXgl2io4HHHsKEl1|;~vndX)IcUDz{0;ZRieHzo?TnAiJKxkK zRm59p>EC0pUK1|}KqQtqL&LN6lCp3XfWTN&C9CtYFY?+5RGw=Z>U^j)z;Le*7_7AV zlrMrMov_^+l+H~vXCWjOiu;AOsZjnwWT9S+Ip$G)iVV#Tkfn0n<OadI-~z`cR@WOm zySuU;ss9u>>JNt)yG^dMUyzvgzXcDK@4DAr7Lt)A^E9PktJR+0vCFs6jc*-D5K@~X zXj<~Dk161(HQ5a2aH%nbz2PC)T>ArlS0N^?)5?hsj;0)&#NwgF8JNq!#jnrOPC;Ea zz}=py&XM!XQs{LN{1<hODh7syuLa7qc&^J&X1Q)Qxmpw72*F?oe#F%|pfr53p(*mD z>4js6eH>}hA1H@@rbkMvAJQ@%xUxGm_FE<?Otk6_{%V-s^LdKxvK1^VYm?>trLWqj zF?x5YU@cG>(dM|PX?ZI5zAHF@(Ox*vcl6fxfx|_;d`{jn%|K<>cB3Ps(L(a+HxDe` zB<L+EeENDX@`hI3OHkEEr%6UjY1?rbi$k&I@->RE^Y2@>ZBfA%xqo?^a)EJ<ch#!~ zPHU)E=k@0BTe$uW$(`4DVYwYu{UI!5x^ObNsdQseq1Q|OH@>jGvfbXM?-Y{H`xg>Q zLYhjAN(w}_1${F$jJ(zE;*oNLw9?yG>n~`?JXmBDzTpXzHgW1}b9igDdkoe9e!=VU zm^PQU7vau||LRx9Z%fobkg);6Zbm!~|A)hGu8H_oe13FqAg<JE*P)WU_+0927N50d z^LMzW<wl`Sip7MOmXG6fmu<ys0H_xw(D7%RGG&2E2q<_auoUzZrWJ}W1rh-4)hTQY zi0EMb73z=>M8!U)Q|bik=}9M6Fj`M37go?0c0q2R|3`^}kroWS^rTu(m1Gb(Cwq(X zu|rx2lCZGBT)=zP-lW_Fg2DA2ne2ACUX1J!Tl;e`J0KVapJDkn{}~njs$SPi{A@1e zd#l9yCj#FlahfsKI#33iH3fRhy{8RWiRz%Z#iTzu>D8)AKSxIznMHNkT#*^20!pZE zgBq<9ui{QTzPLNF2=uh(d067iD?+t;8hn9gmbz`amO*%MS^T~Fx5?ThP^!Z1gn=)R z!l-WygjlzJ_NArN{-nQ1@XR}~nv}!Ec|Ug5Bq9&Jai#g<P>S}(X|kk))G%2$v#a&S zY8U3p6`M4xBGj9SltI@to?m#v`<Jkt{PR*u<w&J+6|DazO1g-DHCnCJVj6!9epGH` z%eWOlYxSBZkJ?=XTi~f@r+;ux*tZ<#?-I^Zq!R~J^k3#v`HF-J(<S%P>Q8I!)1$43 zP5bAMaPTgu7VbmiIbG^;DWjH=eL-q6B6i+r-@=P(7axpRwNFzO+HPNOp~esOKiiG0 z9T$FN=I}f^LUa>sni`1wNQ=8Pc~Ip>2-%~4Fx5`0*t`AJ((!Xqzfl23LC)9r+fSLR z9uwoy4$#gQ+7awiZ+v@4z+zdX_wbCBIS=ztV?5w-7oA++nT9z3;i$Acb_!3*4V~Rv zrnk_2pxa@hVve2@sZ{N==T6y3TP1w<BO&sNy$tgagTUuKmoO_BDd1#f&QJubq~-D7 z9YrBfwL&s|XE4<og9UdP(2gjOcz{ir!W!v4giv`_mt&#&;ME2Qzz*B<s6BJ3JB`e& zujJJay{IKV^GI`CAaBcSyIt|>Kl>;^1_LKRr!uMl<8Xr}75!-_@#GY8FK}s|uRrv6 z#}8%`(8EY2zhn2(f9D49wf@s&1x*~5->e%-)~|}_i%!O1O8krO{v*}~4-~~wr!L6S zc1F9~oAPvy8aJ85+l5tTKWe}N^FoM7BBDmoO`1UQ$65MvdXF+M&Vd4I_T!#47c=4@ zA?;L)X><)}=Yl;X9k7&*$~&FUcx3wC;9iXR7lNC8&3wYrZ(9pKLuK9~o+a!jFs(HD zy~_NeL4Nu`e)&Lo##P|Mw(!K1|HSLQcQM)Zz?he6;`fO1Q8N1yrj8P5{#Xa^q^K`! z!#}U)%t?$tA%u-T<7aSV(?rHZTgKbImd4m@8UE*E0I1cYuSRBD_Y~E0(8pA8SyueU zt5{)~5D*>bh4b$r)YhMO0W=3asj;8{HAihU^1G-ePA>^;HfPbE`6(9-(tCAmZ=d+8 zkyBYi%98yxJrTW<iE6obd;Vv$?qpFJ?{eh;&odR8u<F}8Y6~(yi++6k+<H{}dzZy> zmLhBcSKh!|^QMgGxMwh5C`7%7dOMC$d!&0jaz>oIJ38f~i=>b!u1c7hc`S`mQt7;f zUYuOJXLbK&wOxzvTaC8ZmB|)3S%w{aCe$J049J^%MQdSJXLXD6#&_2;a?L)p*mPez ztTWyIb>m<gS-hq+d+GWr<0z1?$4B<cs!F$-Wj3NdFCya3K&TLuP7bc~rV%ArK<Pq3 z&`__EixGvA6}0QWqcL<c`01A4P3bN$xr2aq`+$E03RG$Geah2%NzRx;JaF!_ZuXGV zt_4iGI$D~jGCcq&0}f2C0nf@Pghtf=!V+v`Rf_WBN;9j7lC1sy-6qfWlH{>IhMmd< z_Pf=}e`1##;;@D5x*MQvl?EuPl{|*b7d7dK1tF`>72Mb6*pCVLZ0PGjYM8vBwv3j{ zq7wZ?r~1=BCya(AV1k61S@j0b72E#NuTMZr9g}2Az9zKG8I{rJd_hO`O4w{yyB5aC z{7?);Oz_dmYPt0#4XY1}9l<;t>a^0n!8BrWpd-7wExS=9ur2%jPmN6UcAlni?vC&C z=|4~VV=VbpYxh#h8#o`zIvHtqqH8K);@mE%*B|P6hEz;oohHE#pKsfS)*JNG?r||{ z_)LsC!cR-;)Z2zV(!6CE|2j}S@*0OI`r75ZI|D?3&FWoQjZC}IRur_2KA}eYb;@e& z+bUK(a%a9`j%}5OPgL<?hRtNcDTR6N$f_|Nn(t$8ScEdSOedfGN(&D$r&3I&(e*`h z1ykI|#_-rNU)_>`Y!8R3rptQQLm5@SEqb3K-Q_PIFi$t+S2J5WRrNlF6!*J9`e)Fc z_M+71XW{rcfh{+kdwVt0I;kf@Wu{`b3VEw1e&}Cyda&~$b11B=^><IH%hE@>(J?u4 zxi9UvjD-&0+Xl($_NNUl$Feiyx_(<$CYwDuTBAtMtXB%3){ZZcX*`Nv6S}cVo7-7i zr1jcy#YRS9rB}gOz}D)h#eS<Dx}`Ox2}{_+Q~XJuNYDG~?w&TuOnAjBP^HimfC2vn z<?wW+_1-uZQNq%1Lqcb$=Rt8+VuBcRRl9o}vU#8MSj(qQx&z9=0Bli9hGc?C!CWWZ zDU{>~`aM!T(pg~N`Sk`)Nc>EylpwmXiWZ`A*@yusB-VM)>Zkv7$MtRT|FKG~pYrQ& zWk4K*=b;f4Aq)RvZ3Ki0c>TSABu9(D%vR_9ef%ld!1}ZyZH^inlkkb{ZUOIjyD_$z zLKf4yC@SplYwnMnORH=K7p)y3Q#hCOnXJx)mFv=rK-adsY?@Hr2>R;XSRb%xjca<C zK}hSrtevCYI7#S&4JbD-+~L%@obCPYW|2moWqg;&65M(Hikb!<rxXxf?u-mmCHXJg zhN2<>Qk<&!z%a!+%mCOEq_e)OpbBi|$D~L6YqZYq+J2W57kUMKiMu1~5wGd8p_at< zF4Wtb!2j9$Pkmm7KYL!A?Ip@65BP5CaRo;t7EW#7)`@$BKkLvweD?P(1mEeOVMa}5 z8ooSg69TX)o~BnuB?)@C%40H)mC6DOCCoO(hwzsTuTy4x^TpOi9``=;a?0gtE^*=+ z8g!*b`5s%!>IT}LYaRKM1LMTycPlpjAudgEDVJUz<f`^@nMPM`K1A4VDfy9Ot;ff{ zd(dUST|%ZQcRodjJlb^md`)Auw<Nv(y1@->cwcN_EH28OYP>t@K&wE#q}dRFuc8Wm zTewnjbg7EkQHvCZw<f1EzaQD<mXUy^CLXmt`f7BbN%=w%VGg$<yexw<h(8<wMD&46 zMzxP?S6jzwNS;_1u!bx#X0nyFjtpA=fb*pRNf$(+vW8Qz-U%G&$sbdo;yaDLN3sJ8 z{wSYUfDc_Zc3aEAq441670k%J;H^m!`_Nlg(9+T;xMa)7C)QQzPn6O(@PKGcpgI8Z z-z}UkAjEgQpRPl!|2^jau7ZaS@z^WC81=UigTHTPS*QQ4RFI`}fCY<zNqT)ID7X$Y zGI0)lV8K&G7U-wEAjHcI(MEhDcjhR`pBN5<3^kZTA$Sr|+Ns7)3e@W*5w8}WHRtvw zIDfD!d<k~1BaQL+XxaFSlos`YUm;|B22e?b9XDbb0jH1i#rA?~wFJ2Z;*09@UvSUt z;WLB2w92%-utVnl8573@^u8I*V>c^#78N<dY@TnMOW8-%Y$ll$n%#(!GZJ;u)fJSk zBa<y|ko2Ag$ivFh(z??xX^f&W8C~cP!$_wsVfa0UPN-W-uTpsgV~m<oYH*y;R-W?{ zE5eQW<Ch;lce<0{?`37KrPdm)b;Z7SW|TDTgJ!CgDa$dRE@8dIMZIiF7nTHnG=jwZ zEk(_WDB{KEMc%Ygv$v9uyibrY-j};wj=!Fx?v2cU*FjgYr7IRIrRaXS^GlXC&CI8$ z{_NBn9&#ZK9D`5nIeW9tY%XN$&A0eH#y`%SxGFJAEt!zNDSvb~AL9F!eIliK*>!wt zjaI7ORx_s}?bZ@*-!US4Q;h1a;%DleM`?We59&mD=ZyHjKXK5k;k(%&<CCHzX0z<x zvc+?u8zHwKH8X0ZVV8XO!BsD=YNI;|BMr<6Z;zay(!+$B(kDv>e>e`*L6Lr$B)d^; z1Be`iAOLpsAP`JnUd5hm%Z#UqfU7y1S;}mL;4TpN33OZL^<YhQ69DSTI_n%3bgPDL zM66ba9sP6%yw?#IgQQoIkXhjWR+Lb(2-FT)7JlfgUcXZPoA1CfR)co|=RKPBp6hrU zN_#CSz4yV9GX(^A>J%?Emm1v?|2*q^pK;0}L<oZi5A1$#&d}n>-X{AB;|j9Y(<q1F z#rinVCHV=19E2X~*;XBfK{iO`18$5$$x(Bw-8u}E839^s-M|Eb(2#kCOm-`w#RBND z<t&e8<TwZyxK5d18pZ9kd?zkWncCLK+PyheS#2P4J5#AEZ$#iUUPlOj&2Z1+rBuRa z<s6XW=sKqYjQvF08KTcQUsHO@(b;dwoCzQW?9zFavZxd{o-oY!!G62t4y9CeiJz&7 zoo$en{=9>4f3~|P@3?F7)95joA1@}~8j)`_UL?_nzP0;}eSS9_VrI8DPog8^d&mm` zvQNYGu`{ksw7HuD^4WVkC+!=H`I1tH+Z`Y8%M&S_^y2L=zK~&*H5P8E=PvnR!XhOw z*Y8N&?$R?$>2#M&e2Aln@7OUecVyL1&9L{R+?0-;Olug>|9=qJD)Y7H(0i-!{ZD|% zo$6U)EB`_)bC+pxh+%X5y@8w5M+~Q|cht<&ezQZxX;t}2wMNUHWt_#$+BC1CF9T#x z#+6GyW@;2ONV==&qJe^})xpk8^<3Dm4j|)91hCrmQvb#PhRM4ZVnG%O@as;@dT&Si zj*#82)#j(lHV=Ni4_+;|%=ViL8O&Bos7fzo_kf-RqKx8D>K530<HU61<0!Do6PvyT zC}1G50Sc`0qwRdXk(*R2-yyw)1EUX05roM~nF@WNjDmbs_C`O}UMlGA(#xEQlECc6 zj&%n$*tTyQxcUDrYQT;D&jMgjgzFJIP!C-n1fWo6P{r$<0Du@Uei0_Nv@@UIv9_i_ zWv;v4WdX=@q-Z^Un{BUw%KsP_u7tk9f)Iow_?vf>nn~=1?OI5EU8@Pr!^xaP9;8ex z?|oSnUN;Dy9Tk~6<g=@fU*1{u4+q(kpISq{P8f|-SX{fwka3|$GoJ2NHyX848-dR- z68!I)Jy~mQUvmahnHxAz)xapIn)x-O`clASSW>YtiMqdh1)cI?6qPt(VjSc*mw9yx ze_Mg%;VWlc)=hank#cuZN>$Cw^;V^yN%}{6G{<~uBzN>iA&RHdd6T5Dwk)l{-{`z6 zzx6k&m_X@~*BkV%D2`eII94}n#Wc^N4~I=<yglA;*}9{i2*;DPuGw#mIcd2yyI&G% zDehp@l->byAXokR&i>&@K7ni2ur5QiH6OXwG8JC4A<Bg~PZcgU;}78Rzg6IU{g&qn z?r{SLb|BkBy{c@dfWSy_*xE98qm{rI&e27#%R`0q^XHd#5%jA*9L3%IY!q`+WOMtG zLEhD7?dAj1L;l=hn`@&^^iBysU+c54V#+QB+O6FCPFHzN4f1YtzDh8gCF~x9+n3Dl znoNTSIk=k}ec$v&hTM9!eD`=ymiu+pXkVRl7<c~mkg8p^Blb<MI@K8=TGW)hT?tz{ ze38zM^L(J!I?=83t7~VdZcAD~<>lc^`{fE$(x%W%&}M%ROn-p!N&_TRMqb<)?aZB| z%v~fs2o`1S^wVP50;pPtHBtc{a6|rit5Pa7&5B8%kRt&D7DlT9Z&0s2l<YLR4rh%( zGz5$#<TBa0t~C6=6tEO{0h1A0tdd>l!;Dz#+y6<N6+{KMZavoF0F^j9$Q!Cdu?)`j z*pt861w>$l$4n6h+L52!DcsX}0ZpYBRSoewH4emH(qIp{or1Z6+ofX2XX5Z?QkjBH zzOJx2T;-&z-#jyN#H^O_D2vdQ0wjf&Y7g_(B!BmrA18bN?*GHF#MHc;lgP{f`+oLY z%4IrT0S-=@$Jl)WB2L>qbF&)0#6)K?7w2UY=@f>>1apXD-BzoxUnBR4L?tJSVuXe{ zUsOs6W)$?HALf&F?-Rqc-BaVaPPwOGc}Vb$4-C<y{B0iTS2x{}j!i>uz6G}I33fk( z-2S@1YA^|UE%~eSE#G4eBPSG!M?cQNOk*=i^{so>VE*m`AmH<Grg_A|El*yuJ+ln9 z5K?Y;$4ni+^4b$u>aFz6`rF*c;v4BXD!ES{Oxk~)FIslHF#Nti{bX#ybdHg6)ajdM z9*P{e3OGy!yY@D-7?sdnTMp}gn>)CObUdHOCl&UdcU7d%@zJSIOo?KvaJktVZ6)-{ zGfffWmrl7H$}TdJ<ltSpLB~C@!nO7sndX<NMaDE*<G-lNeEgN{)!CKrLR#QE(fK)V zNASt>*_~^oivg6(_+4jKny9Px7;jUuH(C+ilQVqomih6f(ihX6H!2j$f-EE7Zrv~n zB)PeFm-5yOymTrAmU%1)C6>)_O%ru9vLuMo`QHNO$;L*IO>cAIY^%@eyMWAMwwXTz z{C{j1BDtV;9|rvobMC%E_K9FXXBq5QN}>EH;ths+CA$FwD$=UyWyE<MO=CBpT#RKK z4F97(1m;WaIJ@WnnGOC<rR>3CT_&?Gq=D+ymd2iZ{iD|t(q0S%wqT%M{ZHh<tF>k< zb<f(Sb~*YX$;zF?WfP-FV#|>eaws6L1RD{+H%)vMZ1;U@{kdKwP83@OHl2fEGkrs? zo}apM2w~hxn*myHC;+-tGr!Ffmi}<O{=?xMboN=WDwm_T9>)^@r&71+MaCmRoP!TD zXPjBcJL6-;RIy?#P*n|Sc08W(>ZOPYC3mEchlF4e*wI_lVW&jqHPG$78zt-^;+_hy ztzd*Us_jLYJMU|a@@hor|7q+^z@coz{$VAQ$Wu%qOHpJdmCBkWWX(3r7>%u{WNe9K zpCqZtlF&lPGK>+EhskcV3{sM@CMtVF_I;b@f89ep&-;Dv_Z|Nu2eaPIa^B~4Ug!B+ z)LIhw2CO8vOd)>>(d$)+a`AMPV;b;o)jAmBQjnE0=K^{6zGKA03OWVc@MFf$AjJT~ z7op626|Ht&=Hb#r#MhJkDGE4g%bXsv=!3?J5JZi-e!7cdiaWmf?mSs3XKi1{m$Xgw zGoaPqGwB!R-KTL)UX$-ys8iskQ3v{z0Ok(ko8%4~$sTN!cX!AAdU|Y?Kc!YcFgrSv zS}eN|bBrr^8{W6Y#J&mJ5RDD+rx;JZ3O|w=!XJfrIKaCm(o%d1&%YSTFWSxFjI0<% zM`TotQ$!Xi1<`v<{9!L`ydAeW^z6-hRHiZdG58#Q*y#&s-8Auaj$coS0H_|%A~Wea zm_hAMQq|oZ3TBf!+*8Moy60c^f334f#xIPLo9kDOhdG}0zd-AYeYG5i<@;WtI30Pv zg9Werhoe|8NB|1x?%4UfF6W<emo><lP=R}Sg_;B)GeW5M3$8s}n4j>>Svn^43HgOj z4Qbixoc;+5g_=H~=nmZuxY!@MK`{xwoQI|d74Cr^SOVXq99&kNje>!CWq^Ri9^HZo z1lz}oWHZ1<v&gU?@_T+YOKJf<H*gmG8NB{?n6Tl}wgE<j;uhupPHg?Off&EKKogK1 z&cGXH1E&ZSTDqZb-O1FgLSN%px7?m~2;w7&V0x%FG4Lc-7l|@adItFn>%pV~f!}Nx zkT$?r5oK7ex-K{6d_M8(gf3FDG$ru$`)N(MS$W6%qns@I5m2H@@&K$SZ6|F&yGU^+ zCz3X>kJ|0PSLdt6O!TkL2Rk-Xhv3Y(*}U`4VIU#XvHYLp=JIwNQ!t0vukJ#9r?b2& z&hneRB}57(V;GN~U+?U0i<>#Zr2%}9V`)M_tQz3t!^4x3_wibAFfsX`DcHDY5}@9n zB|SYQ8lA9-&f61hGz)=i4e||Od7i4U7T50MN%K|eyBTzY;$_QU?%pVhR(}sG@dpdg zBkkIrUSegfA!H;M7b%6I9PY}O|5BxgQWmug!fR5wy#BJkd6c3rEnWlaiqc0Ty*W<? z3SWpDkBh6djUQaniAq|XUrgy^Ua!KQE4hRk+gxdR+3DL*$;q?kPj;zcx*UrZ!a40q z2o$S<l9e*?(Vr>$)@2V~j=RAFb}_yT``pZ^-m+NL_f*mJ+?bO)Nrl4KD(>NNHuX(q zSPx~QDL84)RO-Wr2n#;Ui=Vq+J8g*pR-0oyUj>DlxTD-YETSbv1Qy9MGOv6wYj1`? zZhkxb`VotvJe{xS1;oG}RXTYCH<ejNmCq068lADyQ36D5Ju{go^FR+6-*>+v+bR@5 z&VUX&7MeiJZ4y=?4|rs6`j#FHjRZ2GwgXWbwtb%D2o%rcUVH`G%7AZd1n}j&f7Ah- zmDHeM5~_9g1)C`dq@X9{N7sAFh%feFgAV?!TxYYD9pA87UB7o`f3oa<D`lWJ&5qcO zF#luSv5tR)!gBA%)Qp|`(>}9c09a73F`C#4I5b?EAzH*>qOTU?fW(}QuTb5(xkqlM zBUaek0@R$hULb*fh9ydx8nS2dJ4?F&(X7}s*Dg8Ez{v{6F1QgFBV!jaN>nI-``0uR zyPH@A{jAas0**EX2#e7HUDtCBkQgD)&1nn%dE2_EQY+L8TRFK?tK_a^t4a^#)V<zr zSq)lQ1SF8Ql1SakLr7D<h&sLc<>V8R-3;NHZ+fzrRY$6IaoAdiqCKrr?%sa=p{%2E zgs?iP$LBxk?KQ-K7OuhJ<@RFP=LJdcdLx1y9@a1`1Fep`Zc`yYPMZQ_UE@joPJ99G z<KI9hEi^HaXEnIv=bm3)z4%4LO04?pmAj!gW@{*)V<krO$T<D3Zcs1VM#qtu^nlx) z#!D^zF83dswP^jFpS;Vc12&nmn(b;N8+K0VZcDdsUzP2fB(bg-B7fBO`2E`*vqbgd z1R_?Ix$kkjMt@kt9aF8#_Xh^GO+p6gOnJAx7oK2-+tdBMDA>WJ_Y|e6JGsT%!8}iN zcvaDLxN%r9i2EtGy_EQ9`{DeL3Y!QsvEsQipVtstuZKmaLt(acTC(>pDc(2}{4S$9 zX)@F0wYPI|{%Ri55g5|}GL>jbwX_bN=1?&iLhEOSjCMm30=W~Wzsm~>Fb)PluQW!I zAzc?evS$>nIRyq{++@J{ikC`Poj}IN6u<F7?vZ?pL?R!9XvjLid$;i9Q<;ZJHamcF zDL^Gajxj*-hFxu}-`fS)FwXI@#+QUFH-$ASvL_fI1^=PX?q`~K(!k&XMB|@E#Bcv3 zaHA<OeP>H8KmzK}gEl%Fzm;R4@gAthp(Fn8TChtMnDh=RXWFa?mya^giH}u_HC{5F zxu45Zg#sWLFck#Pcww1TpuYpYi>53zz%<V}icQM&R9M7({>~q}diKD4-899ZL#w?L zUt!uxYX{*>np$X_?E5M~ow*ZEpT_v8F1bj~)-7Z1k7Ta#8qd^}=EP(afEL)E_(rqJ zzYu0e%XD|`;Ih&0haD8U9cFg-=GR8-l0)9{M3r=XGq~w}^pi0SxT1=pZ|vjEPcom0 z#_4mzD{@Xo`NhDc8%=J8(H&>FYp7CZ#LlBtA76M)imOqS+Z!n)6^FUSZPEdHzxwWO zSb<6|-$#*ga}<~6v*IV$;8-~I^T)#)d2cH9)2bDto$$VTm*~?yPSxFOPpK98nsZ|w zdtD!g&r-_IDx7*U&@NFCvioVy`w)dU&nb=naNKo}OSWylT<#P1>?or$b;u<2*Nyx} ziO)yGD>}M>z23sDcP+Gg6IKg;|8V$7SB2~i@ENW*nmBju<Ex)7TATEOC8zS}vX*V4 zJ$v{2Q&KKH(cXJ%9@Zb2HAcdT1$Lw_hJI+c4WPoQqQx^ZGo4qdKV?ifxB?two;?+u ze38bh*%NwVHXBrSEPefDRMO5R6s9G0$M9<{BlGF}Gb?Ek!5{k5WB<yP{01A9+zKWt z@oVG-BqKBQG`X=oSx;BF=SBMj8sfP>?<Wc+w5woAcJrhI3nU{t=7G1xY}OWZNT-&u z>ot&&rNv#<(1GyX?k!h<Btg3D$pkC5f(E-P&K}1q%kO;@{Q+6z0x5m`E-%>m7HT7} zH)}lyGuNdvJ%O+S@KUncOX*!#C;!ud`%f@KV>qCAn58#<1$ab2Gu-t`1lqvgf?{|b z-UtQfZvi=Q5wu=l3L;GOfxdQayV2<7i=&`nlS7JfsMlyjio=0-A3K^+xT~G%b%CD8 zi^B`x_8B*yTLIr^P9|ZQv$qT&$53ezf!0L}F9cRj;+%&i$2&~>V?xDjV|5)>uHdIw z)b4Kl2mEsX8lv{P`QlXk6f1E!K!mPx9TvDh4$vUw4MqM&n8|n~)Qwu^;0l4q3T&T6 zmE3C|MwSV|C%Vn?Dv!`wop5$DU=Y&{t6T@`aBjz>H$O#=zpjNNfs2y3YTjqTA_8GZ z{zG}u7XMLeXBFYx&rwb<(uIMLZ#zpbpGUDsczCMdP6vr{d2*@o5f2f|q#x8i_VG-R z=#=Cx*@?RaUS?Wyu%vGLzUr52sX5cDr^A_!8BWz#7McADZmw$)?w!sc2luQj{XOvu zA#=#|-H&++YSJ$fP<P%s^R7*EP#BFz^-Cs8?u^ZD_r66|Uc)69Fm-mc4Lk0nzH2T% zw^hYSh4RT1ZxNzv5s=niIsC38W4rzRw!GWT`PiWRUnk-nsxApUB!^c8vJx*I{)K5P z%Nrgas%)y;HY3|>6DqOxt!$e_n`|tG1>g1k7r}n}b4pIIAZY#Sy0C&I2eEDoTD(h? zx*Glf@3mfs%*iNV?`aRlCE7J7-!AB#2C5pU6CquVo^xn6MF1Vpq(`2u6OlB2(aD{+ zyPgh=a^YpC^l`h4z{U*#vex?#>?Sdik=JZ!Cg%#}!Hp5Z`t9q96{ykif)ImR4*<0# zHw)P={V%B(v`vBdKS;*wsTTNq3T+A_fcp234Lk@_Sz-1__}_4i>0IwStp8U4fPy-5 zOny+}*2@dS=4oqPOS(3~w0Mc^Toh1s1z<-;4te6O_o$U}59vw{x1yp#jEc|_x72Fh zcg?+NiwW-+@$lI(m;6XZyw!-nieig@6U&HRMoFGE2dM!&?imPDl^vew|1Fn(I}+^f z6txiERxugH=Y<t-T#+T}?<`^z_vwE@0{6LXKojx7Ux8L(Um2-l9(|cd^pw3CldNip z8A&w1tPA0E{peCFQVu-4{lO10)Lo;z=2CRuBZIYXU7wr;jH8UGg_uOnewbQ83jy?q z^~N+8dTkZ1E0%eE#uWQsFUr|zUD5n4vvei9()?Zj5xr}V#LXF`CQ!j&pB?_Sro4($ z03em;<?|Ho$gB^!W><ImFLw+}#;EHlm5>`l_J8W1UPF8=kYt^Unaj__ikNePk_5hD zH6Jjk(-_Q>sWk7gjeQ(*!qL>B!PDi0vRPYlobZtlM4w|!s{HY9dxiH7iaAwdQdqju zqSNMoeG4Hk>Zfq|hDuQ3x%<UOTMqC0uA))oK&sg)T}M3A!ynKQO=~6kREuj(soz~g z==O2czA9z?Bq!|=!?bF0bDM8%sD8-XftY@vfdDny-ME0jcc$Zr>cul);CZ~v5xX$A zQXI|51kS`Y^!@H)C_$yGTo#^l$Yt~iFa&-Y!-WRoFBsV>v=3d^lurP*sUHl?Am=hY z7>9~#_G3GSC-#E-q+G%}yO+A(JqmRcL@bp4*h(@``m|!B8P|gqio}hn8iy)f157}m zTfmRbTb@5^>}<tH_RSlkUv|m+Cz8QEY%~L;TEl+spII_Uz^Jshi@YDxWJL5_Y@(Pg zvMY+y*?(6kszz2_OoeK2q_G*!B)T+Ppvuhq+nqr@18cZ)HfK!2SoisswDC~%gciTR z>e&IwVPar*$%5~)snrB!h1%x-fn}8CXyvH%lQu16{-)yn>384f-hnT7Dh0z*cc|>P ziX=K{V=_FsgHSgI!m-{V4P-#OesR<Rj$Vq`tCWNd+;IhRH7HQ&d$`A@`vhNK+$a0H zL>^pA!hn@=$`>J3=`iC+snl)aa))vs*`e;3uA+66uV+a|iKcP`J%^%w>K&jTd}b_k zGQYHX&iyOU5W772_HrF8%ir1PTV~pL(p0RFz&Am=>ydb(Wg1I!^k?kNnSjv!_eT&v zC8I-CSI%sI-t`Km8jPu1@CkSbT$z-<o$yu)!sITRpGjJ=xK+#bJ|O~-ek(OHUiX^w zy-v4{I%d&?tUvpT{u6O)F}!cf<V56Pxh$VPSE$Qkro&^~HVIb&D?5R^*EhMizPxH0 z5OPanY^V>>K0E3q)3%3Ep&=I8tyST0|C#Onc@pcVbXTbW7z&ZFgT<UB*zlhS=RN?Z zc{g-|RZkW@`u(dTGFW}zB6duxeAM>dsG~}-1?P&Hx}Q|}#O)lGY{@oOV~7y<w(Jt) zyU);<J*YcX6$R&kkDX;`n*|v1COm6B{+EJ9k#`vS**y8hHCL)bQjWUlohQRDNo1*S z2@QvSSSb^3KSRkv;zh{EzrdQ!){6t{vkmVBpDuPqx{k^L^MnU*sdrG@0Yvipx{fkb zZRG#9E+GsA*6--Cg$<!F{VlT&l;=Rz{rd@jHh2K14xud8)pOYayHQR+SytV56``qJ zb`fY275UOqyUu9dsXjNwJJvQNIcB{b>X!&1XVX<{T@4)MPQN|hTFOJXSKfDv18KQ? za|SeY0jLoch+00Nh4#jLrmG5LyHXw^le5sV)-|er;UA6z4O;oZZJGFbBe$w}7B+U- z37_a+3(bj-AU<(HCBX^IUzcve)PrB<@1M?rIoNrr<O-??=Sdpd4Lt+`i#dFNnL%Hv zz4;`E0qF}jpZ?)vz$XU-W+tz*o6XPkSh{!NcC4b9!k5UO_%260hJg<78INT`+kFwR z{*TAz2k}H0DP>t#hVz9cPzBfCE_THF=Z5+)?erdPNz@r-X}+f*Cna8W$v5=qwYmAc zQyaxC#NLp#E>P<;QzuSfyA)r}aCj!p5C7`_ap6WT?H;9LK`G5g<AkHRo1lniRLUk6 zI#nsdO9Rob)wR8L`+>AC7RuY{!LHBh?K+Yc3l_$#mgGL8s>KVtIA4xBL`dJ=&s|)p zp!MW$rNE@QM_{01Se>{%Re(`yF3k5e+%6`{JMVO8;^$yJ$*Gf(JzOqVBuDYQ%eK8= zC4cP&n`u`>?)JNjl%(nd{L4wh?d7!Fpos(9lGEnKJZyE~2cR|M$aONwjJ$?#iKh1& ztwX6O5TDRs!aAO6@ELvC-Nypu{{0P{8xn4HJ+FpRga!}m!wO3zP?)I!rPpDuGe&?s zsRtOlDCECIs?KTHP9XjP;s{820F(n1puhXMLMYQe0m}BBf}#`p`7IOoKLYf(dM$W9 zJ3u#12IzqQf#^Kgp~d_B!%CS}&x?G?aYJBs`MNLROM!{TXwrd;t=ADZcPBy3Wizwl z{0_o{*}f#Dh}Y2g_<^&BV)eqH<LTfN-~%>T)k+ME0i~-%*NxT|#Up<BGJ8kD(&7aP zx1pXrES>Fh1+&*?1lYm(DxaS4grX`mI07FC_F-C&FeJ3|GRONeoFC;Oqj>$9jT)Hi zhJ`IQ&T)oYzk-e&pp-%%!vhXAtJC|*7wfD}b6&T(ZeL25xmqgZGDt^h_~#*NgmWv? zrG|>034bL*j!(MsO$`W~fVOQrIQ6RB-pD`kwg)GXe=|}USfV+=g=I<+jx_WUgJm-} zB125-mYQhSk*r6a_fcb+C+s|>nGVF>Xx<Qg*4{&ygY`^DQnmQ!-pR+e<!2Gz_qOuy zhY7M)mM{P$gFfjYWBXX8D+jg|)?ejk?{e<Zk7t81h))v*T=_++vlQuXo|L8Gq}i$? z-E>isIJup)c>jF<(XG3j;|!b~8uF8E>YkI*_PX7j@>&gCL&Pxr+vI_=+(@WY?BY{E zyevgX>uj+Lh0RjldZ!$j(rB-MAxpTcy%rO<?pdiCwdy?^*0;mIfp<BGk@1-F16~P{ zaXf=i0u1u|uQ1fJqymT|#snHNMYD8tC{<95x1bS{b%i{(!D0;;Z#0GWRPWh>T2M<i zTqY{Xm>qZN&Oky2T-qQcKo>Xqu}F#1g`DG2-d(?eFn@GxpeO!b;vq$)jrdd-g%0_r zl>iNmxr8i1Q3*Z%-x!B-XHM*65pv}CvH2Gv(u*CVjwcsCX(X+F$M%2CKXv76(v^W9 zjF(>-N!<QI38>PpN~=BLmV(77d)GZfDlq9<D{!s}S*B)AQl5v3;Op{Ok_}Y`0HF|T ze`>@v>G328O&5Z}Dt16Kapv-UQ2dR~70hY1LshEzG-Y=izMo+{b9;p<1sqaR;5|0? zOQ?=KQt9Hjk+m*ou}S#FQ!2S_YjX6fC(zq!x#VGLvoJ2mtxqK@yYQ<e*8%U-R$X^w zs|-^Pg(lF^Uimg(!c2F;(j%Wbf(EVbe&%9(-&#{ciAVKVAT2z3@WPn=!Mf$QMy5Wu zrMoI)=|=A<sz9a5-UM{y9c@KDO`Ij)+8#f~YtjBG+TFpzn;ufPqPn<eY&o}Myk$Y@ zt@NnlIh@bEi<cczxSUD6Ws1`-b>D@Tb`P7Bc=qJ|7=G4m+@j@dCvaa;p7yhO{)N|$ zF9A)%r9)L>N9v1OJkGyAVQ*+SW-og?M!k8$fewV~&S;NW-0~p|RANs!x!rAv>9Ooy zLr@nV(W<ENZF(1fat<oaK7Jd<iVWtF+*j}tPgVg)=W4jXEIm()Pix@P{k0~hqm`#H zUH8}!*-#Uk16r7*G@|7*UquJ7>j4s4XWk7x4{bYFrwB!-ndw1DQp?nHcRED)0`5_s zZ!*`(F@Y~@`3(TfRvglRV-E}1vBE|wLW$28T4KQkb`FIufQA3YDg-Rwh$)czy5y>D z#!NalX1VOmmZdTP^njStXVP^cF-`#Cg@zXFLt&V7aDBao{hfCq;Tk}()$br@4*5y6 z#S>TKwfY@T`hREXt5#DReEZl5)e5LP2BLBj!7hnC)msFf$j>$R;_E8YjOT!lu=)%9 zx08*!i=l~ai}%waXp``z5@QgSv&$Wxv{6S^Y1*K}DNt3`Wu+O<09T!~z=FEZ=mF*# z>0ua|%sYj28J1|f5*1~|Q{R{E?jn`4P<zPdl?HX^zU$eXGXtpGGmR=rYL=YgN!#8x z9y~Nk@VTll7nxf8rc)))^_~>nNTO|+h<PwDlo@^Z6xm215N8yFA=+8*IDxF^(iDNY zf%dD;g$dhx3p|Vxc{L1aQL);ix~;uwAsXhmXc`bnz#Mk_IEL>?BCM==^<ve6BZLS) z<v)Mwg!b*B_Z8PxmEw-vI0jqJ?KKzB{z2n;opnax@XZrRw@fPfsn=4Ew5NYAetN{F zKb){yyO`K_j+%nisZ*bFK>LllxnE?4IcNt-JA4~1Fujp<@aZdL9hUau`+Xa~n7OAp zI|r5`t9(OYTI!v16u^6I<1(n=E{hd>;M-65;V!(r!fzRqzG`BpeUU{*@VpHHOwq|7 z0y1-2odr~@h3hjNbl<O6_lm=h-q{i>sK*+frQ}8^jO-Rei{7hK6yzfi_rs7ZkgF7y zozm;c<NepQrDtnMCA$<*PXNmW1t|<>;*De2v{?u^yT|zSTM>ZlJ}3_7OF9mbY5ue{ z<)R>VI225Orc`XpKq$_@&q<1jB~XK3zXE=1$D3n*0S&VV9^3^>_GFd49a>+aQ9-Kf zZQ6|VOLTT7-cXL;$if?ey3V@Ek^9hwUb^VMY;Bze(%NB7>Wo*+XM;WwpHX1E039_; zH-=w&4nY4%S8{7lp-iKuOzVh3FQ1iCp0hxp7SpsHp60(g>>l#0Wda}0w0FFV9{}}J zP2Nxsf~D0mYG3{jM?QYJ50seWP>K041kq?<90(;!gti*$E{9^efC;L0e=CEpMKWK* zT&$)4ye%QF!<%Htlh3h<k?FpWyThB#F>v|T)e~pU9EyEC1F}mrR7i!T+_}hC5^%<t zI_laP1L-g$(L<Xv<H~+m33)Ir52v2Xdt#k^Jc0rmss9a8qQA!7$DE7`+px%!32!=i zVmc|ur*vYBDDvThrBa#Il9m08{LYS`Y&~jGnB&#ZMu#n;kMh@O{%NHpBE#8kzdWoL z#xMsXIj-_hFJ;^lTETn-@2b*#cS=r3nBjZMr?aDX%BuqIP0+8h4pmR5PYZQOXW5Em z^M$yzy4OVL8yFAHy*y&G%<GpjZ5vS#`&L!}zS5Cj<8v`P^YT94;Yytwu8s7oO2KD6 zLq=OP4@NQD`F|mjCTT}%mN6}oJ9s9Je8xAa{pu6JF0J%+`#Xj3I|r*A@PBw1?^jLI zaBXTQ2cZKa06ncv1*UJNLY|Hi1BQ?wyga)@6CFT19a$*+noKODTLVG31V~&9zz`Xy zVaV=B*%zDRjZD7*eReSb8DRTz3t34L+2koeuLZLJ(Cr6VFe9{dgC+n3IM@*ig(eVm z-iTMAz~P~pFlTZNXAEjE;KX4L#sllzmksSWXtfvG*MD-=%1{2pg)!6DLJ7eCXOr-H zJ<$(FLO^8>vIv5XxV|@9KUw774i4qXHp(qqo2HGA*DrT`O8d(K@AckJ11LKWL)u`_ zOF`<HadXR2qEHIa`Hniliu=Bvjn#H|To7gR1z+vD;4&V2!QSitB2aUg?fJ3*C0ju^ z-pUEP*8SibF2E)}%=|rqaQ9sq_Z{_q#@$cC=*rDEcwMGu3_}-SG5}kywAz`CG;`qJ zvie2nHkb}x;*7JDUVupz9W@TBC><u8hi8D<9?eTezeV?aN+zg1+gaMZE48oU*RU*D znQMF1o;ULMQ>Z_cwL&u-Zax1b*73|g{l>+PM9PO7v4LlMX9%?HY&+*xOwpp1!DFk6 zvuCe&f7BtYIZry?$zO&2NDfijx252D*{U4fNHHb1ry%*_jAX9}1w?AJ!{K<Fc8Pu6 zvalJZN8DpA>~sk3XOF|!FGTidc_o9PIQz3H_Xxvco?)E~*SEe-CF<%r-;5JSAHCR- zs?~(M7t6s*Z?E=H$ZK+6oVINqZDmREFN;T|-o(iE9=Uv81Ht@<BT{-zX1JxHpncQo zXiezRBQV;x0`uP42z6atNZzP)`?ED15d%Q5Xy^94hT{fQtN6GiG7#P5eJ0^b-SX^m zo|V`QG6>iplrM-+)Zu_-G*<3~AK~spS0Ldo9fkzNaIS;U7yUarb?Vlm6}WZ>KszLG z-+vZ(Fb4%a&*qKLfS$J=RP0g!IIXSk;H~CY%Y?d}0MkLn?wVY}?agpLXK2aa@F7?i z*7*HYPy;JN^U|1vOwdG<+|}RpcYcR*4`LX9_wD7XgICde=ZTQtE4!$Gqur;>YKTC( zGX19kHE80kbaFsw;z-~m=-Y?f17^Wb174dG{T%j7PPyTKpl2>8f?Uj;E9k+u)7HGT z8Y*v~!J==ZnK;yT;JT9<ZI5x{Rd4KPgK5Ut7DlT{DDKi(k@}qRFOA|$xgy^6&$aUR zdtQ@^O%Rf?u@t=X)lfhs2MMqhs$4ejk%W8QWAu|8RzknL!_ETCr_biQ18+TWp!caG zCCTJ|mB9qMnh1tEz>-SBpa{%uw%c>B9255*+;AteVgzAz7IH?#uJNorR^O@^ecla| zyONAgPJK!#qrQg?eUa>OKs<x%@^yp<yH1^E%tqc;5{U?PaZ?K)QGU@>-{>7U_p_uJ zt|C)e%}^>Y?-_Ax`*r@WHzXcy3&&5|JCBO6&}p%=$}sLnnwHcu09t#rMh{Ghm;4(x zdvf4~hBHeYTZ#xR1e4CXDLJ2B57o$}zS3Bpy22+hbF&L?y}sdg0WtW*8zR$1B}@mw zsnk~a()bS8Fl&?7BI(zff}`!xZ>w_O-%-u*Rf}jfz|lH32`{3e@y6sHoKi1tzY%&S z-a>T^PV2F3!vgeFWd1=&P{a7<9KgCkK-a8#pxz3?%=9o140h1wH{bgA0;^aG<6jT5 z-`ei%YY=vjoj%#WiGV829)F(E7E1WtE&?1GrUg4rVaG$dQh;!B#eUL!n(>pX3TQE~ zs*~7yE<o)8WLh99!xne>Jys>z-15%`&&_L3k6gRai}tvB)UYmaslV?USI4=Cfc$l_ zFDUX4AWt$58@0tC(#t2a3thbCpJu+<)LuqTv@Oi?s)Va8#NLq{$y&w~jApV9D&Z$Y z^GPA~ti-Qwj?-st*G86-jX*T^&J`?c%}szEkiaxWtWB%G){z*H0=uTx>^Pab=N3Xo zx$F6kM77{IfaTkld12<fm4#0U)daPZ;5NyTXRDj-3T7LoI>4|T?j8NC#a24bqFy^Y zHW8<ztt#|JnHPsjZGC>R574}jcbZ`P>H-C136=tZS2$I3llQuTzNb#VWK|=st`>o- zBL+&|?%ZC9$+TNr&e6N-Aj5PpkX;QGjTt57_w3kz@Ez_{oFf&_Gkf;v_En7%Tkm@Z z?Q6?jvyLmPx1Gwd4N@-kJcgJF>Tim|{=;DrbR{{Wui8fUwIAi=l*Uw&*Zx!9mi~Tq zK1;F9Zq>bliuH{?)pLa{L_3G`f%(}}akkj~l3gz}@>+f8>4h*EH%aTEwur08ri#9d zc7^Ucn*5`JN1XPia^;QrJsq%w^LM`@e+_&R9eCJVp@D{-q}~7Inc+_>Bg{B%PD$PW z_iEl~^H-*sMqwAZq0H+IsnxxTj`mxFCj*tu!U^<<@@%#r>3cR1QzFL%p>|1ZZncMR z_Az2}vjFoIKw?h=koF-a6mQPT7r+7yBGe5?Re(O^#@xtq7YCcx%FcwRK}2sv=EmLZ zo1vKfk=2?fu2L&NG#Ip04+64@6d)hF0gC$FO@i$+$No)FnuLFPjV!)y{}{GiL5!CK zc4!JsY`NnNt}Ecu{3c<qHxPb9Z2_~~aqb7&@UHC|^#@I;#j~)E7+^2dn2>6}J_%Ut z$vi*$8kX+;0=Fmg(!1M~^cM|JF`HvnaH9W4Ds6gO5o9LrVK8nmTk!SVKO7IS-zP91 zyUbVd0{J)IL;9MdVL*l`DQDIH!z|@QMu7oVjs-i;--O|)p&JQ~1*85ZHGvsMPQiAo z<Q$>b3;aggCHQSz`1ctD({}MwT1UE~#_MNuES=T;p7ZfpPRivBs%Bj?Fh;x2rYFM= z-5<(5ShC-rZ1|BXeKw9@H<gsYmyH08Pu&D3<IfHXi`I=#Yq@T)VCRo|PdGfiz7TCC z&ZRO}u;<<TX+eim$H&T4NS=`mfUR}Hqw=1H80Oc)+vI;ZsQ#K=I)MlMUf$}LsjTRu z5TrjBtM0UQMK~r(z+1mtw+^JlTG?r4UX{;(8c7T|TUb%i;}A#0uBCnfSg?vfmK_h% z?zC!}bbHDEp>3N;C#UYHFtLFOwFTZxhqQ~GQTa9p2o0@euM}S!)M}(wy{$zI1*;du ze+I~z=_cNf(p7ru7cs4A+dKI~P`(ODb8^QX%SLT-;GYWJ$yM|*d;$}<s4!JvlNPul z68e)kM%UdpL^55#<)Z=nMKWIp^oDNEJzqxqskfR1p>^LkVq|5W12nq_#Duj68y{g( zZWNFS0Bf;Dkqc4jH+B^yIJO2S*wn1&I}namXEz}Mrh7eFHyV;4iT=;TnhVpwAtk9s zuguzx+dfrcTCGLJCM2of;k<-?v`a-1^In52r8J4#Q~PfyZ*=Z0$^G$`q(-~bo2SgO z3pt#~Wn*aDeDu0rGDzC&Zo*Iaj^YIN3G$~R-Z*Q}7iGsblhU{6V(zY5J1!>W1z{fk zE?$Em84viymEsYgn^g6^H*z^wGjX(hV)d3g;D9LFB3I(p5GAd&fyc@#Z8H+_V6Al? zb-0x_wIaKA6%+t&>;fP(amaju+2(hInn7a_b;B_RCavcOr{PzJt4?00pF1P&8fIpc z#mhlAEagcOkR8l)+mYab^APjRbJF;L?(tKSOEY$!%@Vml@D!dh9W(o6Bl-w-YSeVT z^hNb1x&}(&HSwXCWvv1j*fUsX@G<#;p)jgzdqop3XfgbxSd@(};*Ei$sQ0Ly*FDU_ z#g6;m_)El4H}E5O;O#fnD}H`mBT_mY!#zFKMR3*6@$k9#4PW0h0n%04_u@U#mCVN5 zUSp2JAC3(5fSTgyO$p=q7p6Npno^7?CihN@`Ss;GIGsV*c?&;TbMxGRtiF}^<;RIl zSnP$b<WLw>iT_hqWnC&la}}SN^h0nwZ6U8G*yO}yLkEz}rTZ%O_=)>>Ax6w27#?k7 z-E)WZf)4hLrxZFUPWgQeji8mndNqN?pvud-g@}-cl~S!>EZDL)|8nD>SjB{vlA1QB z3nkiCVSMP;&JlI_x@ab#zy!AP^{nuE0676Juor<a*3hkxE&vFG^)Lmt8QaDF$8ZST zwSmh6q4PfytJUNDbK2JLLfi5@E=>owrF&(aJrO!iZFy62Ga#C7<GB4pbfZnuowx&h zx;qe0lLU@3&wYB{<`;E?w3U8vqm*6GzNke`qPz((Nt5j%eGrX~X|_=4SLDKEd9vr4 zpzMXD_n<PG9k8(N63~=jW7L!dM!d8^s)f@YBxUd7i}0~4ZyA->ezRzy=|URBr+|n* zU}VjwFbLqH_8s19@h+?>a#w73EYrR^6AY8eXx}JLX44i|B(bwXpfLEN#m=)>%4*=* zS;{f5xx|C^_w%n%W^)Bfa5T|z<11E->?`vHIK|g0c}N#w#eKrUq=buoS-==sZ*O30 zRF-eLP*V1Z@>?8BWQG|EwM%p9gyB{Vxfl35&p0?Yr-VnfYIEbzv0d3WFO8fVm~Mil z4)9q$(l)!{B$s!jncXrS052p1-t8PV2P^Sv?eOS*`)bOqZGu||aP`~H%&p4J)i1`c z+54vej{9=V=$c_}vCsWP&8VDdN=H+ekJqFJZDk+tSoQwJJMx0sk92e%QkUfW8$IUo zozB?|T<l1-GnW5xTp2fQ%fyaMS48jl_?pA#Te)U96WygQSYB4qS@|@4$6Vl78iQ<e z<Z^I(;;mn8tsOyER$S<=!yJ9NCPufz?Y3Wy+Eax29C+IaANki~)=mel%q&-5t`L#Q zkF~)Dys^3tb^E_wV~)Gkv*ZkcnubDW$4!59WtDzg)dASNJI?_BFS+4^-h{9xzOYoF zkJ(33)cp$6OBl*H?@hSB#mZG+Gg*rWhD{<rP@wz+%bQSD1SocQ`52i1HAXmF=QaBT z-+Jo_Qtk-^S#`sv;P)gHs#gCrs@SRbe+F~>1iI6JX<zX4N{Mhhtmn(3=iaPcTEYbs z^T{<T?GumjPti|O&)e-@>Iv5(V%uKaCfHH~Vkk}*mN*KKcYsT2a)HVi@?}FSYGX5p zOqk8uiaX8m169~kUr#?IEPQfypM>k)M<nqQ=dSe2bssEFcrYy(f)J)EyJRzfk%L_! zhZC48c&m~=Y%&zHS{$=jUnjt54DwkZr~$Sw>SBC*mh~^!*)N8}Omv-?HGrZ#!Ndid z=oIBD4xINP1RdH;F2TZlj6Vth#yb1l&TSETQ3l(+HAkS#p=I*<Y76hYxPRKOWXFYQ z13csCf?Ij3)<6QSz1q1&tA8mpyJ8XF51^Q%;duDe7=Qr~DGI9HI8@%FvEuf77mATg zLQ7Z?{gkJcTIrqzv`IRDyjd1zHYY+RM^A;WYN#bQW=P-K1sB}^^`$RK=zN^9Id_7u zP;sqY(p6yDklPolsNVjLkC6S=^{eH?7sm4k#fhM~;@K|L<=5f}nz6b=l1zDwl(2DI z$tdC1tl+C9M5kxr-&${qDp*2OpD_pf%;&E6-2ks}<P>F2irBK_08fkLCmI&-@}*=^ zV;f5X@t$^tvNzz0?@!wtF-#5P<K+kSJ*M7(usH3sqP9?gI9sB;NBVl;?XA+$7QV0m z3mADJ{8IItIO0)-j{>&j%5nc$a=YoP8+nsPC6>DO&v+Jo5WdGo-63~q2S4Nr=v~rX z5nW)4r1hruHtYEpM9Um`tvK<Wf1EE==2e}J_cEr$zG!<+S5QaH;*_VO>4OsE$+1oI zJ+>ulCt1|_#JGPr^mIoFuj<6%vBp^g5{c&uQ{g<D^Jv)T{Z$6YL_kN3ZGj=n+i=m# zP8lS)><IkuxO*$$E3%C_AVMQsI1c2&9YdKu$TCuQo8o%pL%x<C(AWN-uGYU@1b`G+ z{|9<g|8C@-(E=&->1;R3XG(C<py<4~=y~T&<(LazTOa3eSQEPP_%0WD`p(JIokrBI zpgL9Q0WpP62M$g#Du-C#KRi~9F~E`a+v$)Q;-8c3S^@5jzJm2GMY>`KRbR+iCf$dA z+KfxvqVRoo3%eb6`zCY_Z<Ic6Vr=^mFt^z7Yal%>s{#Ev7`(*U<nb~(V8;Qv&v+-T zF`$EP_$t8t6k!T}7m(f`$BnHM9*~yL`?BZ?)nms(8s=kf1CR=CUOb4Utwfs;z4Q-< zA+4ui)B+ULmH?Zz6l(%f>)>+I1lX9zf<|uv|7u<x75K70s{A-dw5~Iz3aj=N#HYe9 zHi_h)4b32)Kizol9CtI)utwgxyEB)^I7M^JFvr8%bu(4LCO*l|CkacjqG+GhQ@;8M za3<ihW<uzn0|f1GwCD4f6Xiw9gJl0N7!qkvMIF%L8BeX!68)j3?wQNr1>DKIx8R2D z_ObVjo&IJJi*%^F{&8ztD$g`AG_i3s_sI^ow^Z1>Iat&3O}!(JzFxvCz?LsfK7Oab z4CQqBqyn32qNnXL%6I!a_={a%<@JFtO~iogs_XN~FDQ&xC$}G`Rck2NXE_h%6-F0& zW$S;#6`#3?*%`Fu)xu@z&$Id4_n}{gAk;eX#L~Rn>5;7nYKcb?Ux&`^_(tn0KI!v_ zFwWsbw{Q6aR+A0rSy*q9Z+H_Qbv$%)`L@38`_vv$0!rhmTL+dqxTZMp@1h&#D9<W2 zz18`GjI~liD4V!@3?ZAvW%AoWvJD;M&PlkVqqIu3h?>Nu$HLAvU9cDvX*{W<X=UPr z26iF1-J{5o?G|l*7vfDM;jJjPu?OIR#K(ipA$}`_-G+-t>(^#FBMZqmWGiH2t#g&F z_VNFb?EgomhiV8+CTI^GEqu#6_g&z7teiP9P%&jdcCTA{?5SxL?&K49`xHMGf1JJ$ z+2CKG^-k11PUig2w!uK+v-=--2W0N^qYsE(^dpa}G#Z!yJ_R_}WL24TdBgB3yIhMX zrzZn0fH{8}UZ|?L9c*^XAfLuFjj3G639jeiQc%D{8`t}g-q=R<Z)nH{_99I|=r@Dc zXS^EwCeMgfq}XIi9}i7@6KwTXcPIGZ&(+tHPQRzCL@8?2{cg^fWpcuf?|}3CaC)LS z2zYt;D#f53V4JuP%I?Si;mC3v@3>CFzn8=32iIi-jnOsJ8=zxX_W|F*4K|Wpl--sc zNjpEe3J$7UKSN9ppnw**b(`u?LEUs;>PO=#9pCH|f^=gw)Xm_hIr=O9*`7cZN=B#d zYF5{WMh!DPc}%WVw%n}M=JPGgYp3a^oMX6<kI7SLpd^Ho=_NS{Y)%qNO;mN4hx)^3 zh5?x~G!Z9IwrEW(>4CK}4Lk-6m=4WyjSrQnNETdwg&LV(;L*gWJb@NYBAYg*EADs{ z8XPFP>|!*P>B`#Wrs(eNAV}(|>KS-gqN><{>u_`_kq3E5yaQt}>X4FCv;P&URwe&# zb76@%t~>3p@QX1Oz&EGbhwK{>JX9x5yl7{8-|czk%Yx7r?#0+Zs@xaS^MXSEQtZgK zp9Vy|t2J^>#H+_+zt``sDl+0WkGydxNZ$Y3lfv46IF2zLs($RYo-$2}o#>#AxLZ%3 zah$+#^~<Hq)|s`<)W&=@mNcT}hvYkbY3cKtH<->tJCL=EiNNECa0^+hXK~F3ot%Gc zXIIkOQu0I#?A#h$jRMpX&iKRhipo=0IpAtH0f+bSdX~Qe;)6{MgHoV5P|h$1y2;Px z*Jl?0W_09641zG+sEPm0>xA+Y1<Y8QEA0CfOrd@?a-uQN`c}1jrUs(<!V1w~vh_W0 zx84{k*_f}}7nT;n=dB;yoCq68m5SN);3g)~eqXn@&Gb<f@)MTmt&J(P+(_A|Wg8n2 z##uuK9HCuTPgr>NH0s-uvM+*G9(#bij-DVrnPJn)ge(OCJPq8Z&7L{e;SLe&>T#QS z90P|7X#ES*lv9fdH{RV`#@q!MUZ)?TK-J{H)l7&?WY*bQv6m4K&h*?7j^&n-kNZ4G z&u)<4j$?|0Wmj4-FGs&mZ=-^aNz2h?J=WNbz`J#C9)rwZ?ew2QhW4L2=7fg#=~3*l zw8t<t<)-5H+b%xd);dWkrvZu6HCMgRj2A%Wc5t1x<q?{DE5;k|c8GpR#7;Ew3a5ws z>A=rGDL=VJB}Xvq^njJF4<SVE00U_{{eGbJlDFZeF#`<*guOkgf8=g1P!P-W=$I}j zGVUAFdQ(NE^}p6kOh^lG&75dIQV2$E!;=)gHd+T7k{-npU2Z=tuWj{q9Slv>tDjzN zn8EMrnMlyDg7fcc@=dR2Iz;Y9doyjZXK1dKy9fLzHh)j*^nBTtOuVA~LqkbK`B2|0 z=}A_ymxL2C&QWbKMQL=`rq7~%&P$4%7}>pE&bZNj(Bh;;_^K}9c?<dxc2-gL9~_!{ z%hbPb>ZxPBr@&r$mmUIOwZqkp_vD4~O@OtosJ}h;qt@2~!FR)ci3fv6iC62okgKC( z(Q-vu+T&cd&S8Ye=VZ^$El%VUyWpA8Z}N^cnYEpJ--uR~RkQ(;HQ%XF%?|9x%-b_A zOt<ogkL<dJlK~J1HuGk^BfSx^z>=(`0FI?tC}WK`lp5HTD-yYH_~g*K3piA-z~xgD zpxMTMN*DI!yqzV1#W_5H{a3UFnKT#6=irMSpA)w@*EM#3?P5atE{A|nkM{?bG1vkF zB+4@*#^#e=0Op?Wpz0w+{e=5dqnZMzUWMspwB%73x|aX=I<Eop9<h|gK6(sLLH7pU zOrafg33*5@qCNm}0K5fTMT*_F0ckvkZ5#<ycnm;(hva-g*AGku)xZR>r?iXuvCNU` zRBC?jbh3Zvj<(*xt0#c)uQ%gq$qlGdLlq|Zlrc@dTk`p3WZ&mZa*LVM3+gBimQgoz z`x2}TlKFk}g~sCxP*ZRLP^})KfM2wuf@|8;GA;T>d)@G3R+;iNMHC=-8jNRf@LvWn z&zzfyft@Q2a<@73;laB%zu=Z8xSfC2!t1GS36Fc7d8IG0X=>A1N&b4$Am{aC-V7i+ zD2oje<Bffko12OW4A~rI)f#4Y<dkI|r$za#)|;CcQG9IAGCiumqhCo6k5*t`)ulC* z=O63q0}=jwCMSoH`+Vuq6U{ZJQOT)sJnv+q?b>w|esPYh^nDcG^aN{~=(K!+KW?4^ zFZC-gZ>qYHWJ*aCmag*Z=TyYM<xnb|rR1q=ip++MnfrSD!y%7JMCtflr#ud}q)jP3 z9<|&4S9x3>CTsiM@1Hx&)1Gqql6=GwA)gVErQjqgS;pl1A9qxKvj^1Hf4kB5IbE!) z3N*i+H9hyi3Rr1bRzK|!&dxhDS2tat{7zCSe&0MLWtJu3HGh#(eA4Apw8!|ZVmSfh ztnYzj!LX$4ci})6jXSrjFYj4D*rEX;vCAuMdx17*o{}Ny8m{a>>*1b=<3J<?t_Jn3 zf9KxZ*E~e|Lw(s>cG9&$M{ixU0s4+XcHXO`!e&UauL7};OA7UDCfa}UHE<D)<biqY z&_`H`DD8BJ=*|0RdMgm~0voWW)OjYMp!{8U6n}MF#tqJRlaPFof*^F^IcF_-|JsV2 z;sXy<C`T(yi=3xkyuZWEWpN?SqD7#alnW#wqkITxvDP-Hlj1)C%BPM=$lw3w2l{vj zP6N{GV|TdO?*yDzVEn`GREmS;CyGWq1_}E7iD>A3uo0W{1*#?d7O{b^7YUnM;%X?H zFE4?%eobG*C)I2hp7pGcG~S_x>Pxg0mlLT-B3B{0GzIy#(SwfO)f(98%38{HSOepj zo{?deylsdns7-)?ZN)1s^>Egcq^TZTmO7Z-Br{?%@@28j#z~6Y+SrED)2>^2@*OO8 z>YXtrkQvXW%yuQv&4&<-@_vE|-}#oUvsr_8G~^QZimhfOq4HI23v(arxO3~6>!y7m zY1j?j+{V-v9yN(Ym=Wt>TThuQg1)xiocZF?$)BNvxURX?yquO#N2Hfy2OWAP)!gys zOq46v#gV*Zt3}KmH@ACu(MI*J=<VJ!eOW8<qHm|T#yj7g{Z`g<r2B)4BGa#M(;jgE zV@iB-){kjE`PIE`4KebaUujH*!YD8~W@`B$bRafAxT^1Ui8Vey;MX(U#aLWPpz?9$ z(t;=9<yy}R9xBvGw5q;VthGD3Y!!lNRo~VW=><lZ7dv9kZ2oAlat0I7`$Zwowj?VT z9NPRZe7!{)TC$;Z3~Y1$7QihHedJ2*4f3QE2CJ|xhr8oDVSlUf-ku{zFW`#eqR{%n zikxw=M3*wsG?xw-vB<aQNtm8)O!BZ+=PmGup&`~|=CwdTV&BCBB=I4znS|*<C|WHq zT7}gaKe;C7sx3_fjxvyTj@~_JP6tH<C|@&xaNeJ+9Fr&#y21PXZ=#0#cNM$=stDIb z6>GmNQqDDdvOc^*|8#5lb!5xky+pSnP7%6J8E2en+Ctn9-kI2)U59kz90bW-$BnP5 z;o(CrVr%elJ~8w)Fib1iP9PAq>6(d{XS@lAU~0bE$6k{b4v|tKvE+~N__dMCdQdI~ z=NuRvftLx1PpCsZcQ%g6)B#wE=rpD#KtK>S>W+O1nl{KKugO(JBj!ks<5PBt%?cyZ zR|~xQ1U(r$TYV{<%a)r6ZsA=SwZGq0!Y(z-$0}LkZeLh}AuHs0E%1#<wXDsUR6&jK z(l-1+qGT@R=}Fq+8g_iFdNpnCeO}#lFF;&lI`|l?5lZjJ;HFb5+ai{pIK7gRte~H< z$Za&as6w}L-Qh|I5`Fo^D}izRxRQbK%L2O#Bid0>El+Z_<WGM`c$><~Byot##R&B3 zkfhS~2sawOlSpWQ+uwRX+MFaD!zJTmqz`P3RY;R{NuUj`uXtXsx$o|#>2mADobLsx zO)O1mfLsnrDQV1>W#q<WBn4XgWtCACd&{T$bmv~&9@-4QE%x4org^Sl^YTDXQ`l@l zvLUrI!vu4Q<EsQB!0F3{q`GF?%YTP|tInT{=cZm-woX{=K_9GbaXh-%=!a_&@Nw|c z`ap7FV)ukE7=MdGWT<=*k!WMs`brv0GRn?U*On+}7Xxp&-avvD;fbT~ulBDM*_+)v z@?p`onNeNRVW?dHjii<6UEVDD<s)LaQ~$&Jgyo^?lF6Wn$+29?o`Tf8LXM;ifB-;m zt7*i<%QvE3IMCuXNzwJ$o>q-AdKk~$&&gkeE}{+8dBc{S@=App(a!ONfY-vL<A>@= z+c&$i|L`#`BIES+v}xa>S+iaXS@oGxQG~)c%S=9}G;q6Orw8d8eD{SUPdyPK_9OrO zgF5{7WH;eyO)U<-5fh{m;Qt3Mn-IXUp#%N@{kc|(E!un2&Fsza#V-_tW-x~Khm~WB zu3TGc7Ql`4*Eq;A3}oXIvu>#dSL^u%j=g-SE;^NhH`}V*p934(^OuKHP6;elsvnri ztde<ZftY$tl;r^GUV8xt2YvrLXCcqMKBzB~-bus*nKxkPvc$PgFM2{Rm7VN2UgGn^ zCyc<`WWOooDZUo)g0qC1gvx~KE<~Zu{dvbI_x|UkY3MyYVxKZVnB{D&v3<1pb@#R# zwHyUjn3;@cM#4>Em_2>DM~<EpGgKf<{iQ%xEqo2z=`Lm|kVe57YzkOE#D71QtOHJ| zYJ_?G?eC!@Rk80Rr?&zSaB$1f&;h*hxT2@#ZsnEQ>hlah1DVByxUv2=Umj@dFQ={g z1Ao6^sYJv2JaP|!hee@D)mDsRO^-6Vl+w6@`A_(+XS12EO~!G~?yW1d+XT0F?;~@@ zReo5VNmFXE+IpgKzg3h|hQdn#+nUYV1_W2-#5SER?n}1xL^6PH^={Sdmb078a;=2v zT>2{697>@0X<?n2vwMHdFoScY(mMLZy-}t;I_uti)=*Vf6H8l;K-6==9oTMZo-;?; zKDFiEkVH`XNlV!W0WVh03E~~*bl>ed6dO+Hn;krt0|r4xqU4+l*lMT1c7}2G`#XWw z5|5?u?l~HxqXOH+Y^o6#!kWw($+2FH>hn|GL5fc`se?D9_YguNY|4C(xoB+7pHMK_ zDK-ydU>hQ|n{a<m%Zhc#-;fFbi2Jn29oY?|JcSg|vN+Aw)qgld@=f9MvgN!viBi?| z?OOdq0?PxmhBAKlu$(f02A_D6=9!k-Hb=R&Ra4|u-GW<ImIgdNWF-5$ABpjo0wec< z_75vV73MNpcZl<*ma)kP<}w7chf3i6OjPm&+D}!{8WIQv>##35GQ1{hn2}tHkJImE z>0!FH>NBqba%nu6XGq1yuM#xPrw=WG8=>n_lqHx8bnjz-ajirk?C|N(cb2#QKO8dz z)3>XHd;lW)e?8~_d5r&D&w3Y{Mih>1nI*DeQPA>a6vou&Aqq<*oDW2@Fa8VgTVKBn zsPG@6G{K01nA+KQrxiz+1@7&Ofm#2UrI;4ej*oE#ws$7<i{!Q@{;<B(#WR9vtVCv2 zl0+qrUGtx(>}-?&X!$G_H*i__0GfNHwcGN1pk=ew5<x@m+jUG(cnm^y&<E*tGPx>3 zR^k@W0K$MqzKMV_kmun&lo8L#h=ML3s;M(3`K$Aqg~)0Bke<$z{1w{}4}B`p{}-RZ zpZA=(b2&7@Nz0s(HyCtiH9`ink~uAO316<Y-)I_t75^Q4kSpP=C86N7Zpj7k@w0$c za<!hMjKWKBA6ZDprx^TA9(?{YleGkk$TN;U;Fj9fxcE)Df3o(6cf6w-&uN7uM+FVn zPN7mxqINh_Uw|mAnQ(p?`M+EQ*vW3_v_9imMh`kd1DhB(t>2rNua3TwyvzS^>}2Uw z+cOTBQ;#bC-2J!gQ(3L)_cQ>prAUQD0RQ74y>q8C3Nrbw;u;Lg^0zz*WO&9F;Ia11 z(dFiHEywnF-%wh<>ChWB$@b{UKvr?JyZwn}M!<t*7M1tIj&WMPy-~*31sc}zxTIry zEc7dH3EWu>J!1V=wY%fDHCOfe5IpvO`(+9p)vIKV_?_b?9$Pr1JG#v93eU!4|M~KN E0NGj8zyJUM literal 0 HcmV?d00001 diff --git a/examples/python3/actuators/step3.py b/examples/python3/actuators/step3.py index 9c862464..8f541882 100644 --- a/examples/python3/actuators/step3.py +++ b/examples/python3/actuators/step3.py @@ -16,6 +16,10 @@ from splib3.loaders import loadPointListFromFile import os +import numpy + +from numpy import ndarray + from splib3.numerics.quat import Quat path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' diff --git a/examples/python3/cosserat/test3.py b/examples/python3/cosserat/test3.py new file mode 100644 index 00000000..7f43704d --- /dev/null +++ b/examples/python3/cosserat/test3.py @@ -0,0 +1,21 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +__author__ = 'Younes' +__copyright__ = '(c) {year}, Inria, {project_name}' +__credits__ = ['{credit_list}'] +__license__ = '{license}' +__version__ = '{mayor}.{minor}.{rel}' +__maintainer__ = '{maintainer}' +__email__ = 'yinoussa.adagolodjo-AT-inria.fr' +__status__ = '{dev_status}' +__date__ = "{Date}" + +""" +{Description} +{License_info} +""" + +import os +import sys + diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index d0658a28..8fe2d21f 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -15,6 +15,7 @@ from stlib3.physics.deformable import ElasticMaterialObject from stlib3.physics.constraints import FixedBox +import numpy as np import os @@ -61,6 +62,7 @@ def addHeader(parentNode, multithreading=False, inverse=False, isConstrained=Fal "Sofa.Component.Mapping.Linear", "Sofa.Component.MechanicalLoad", "Sofa.Component.StateContainer", 'Sofa.Component.ODESolver.Backward' ]) + settings.addObject('BackgroundSetting', color=[1, 1, 1, 1]) # settings.addObject('AttachBodyButtonSetting', stiffness=1e6) From f98d7ed520b09ce63aa4126343028cd6e1acbcd4 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 8 Sep 2023 15:41:53 +0200 Subject: [PATCH 09/71] upd --- examples/python3/actuators/cable.py | 5 +- examples/python3/actuators/step3.py | 99 ++++++-- examples/python3/cosserat/cosserat-tuto.html | 228 +++++++++---------- examples/python3/useful/header.py | 1 - 4 files changed, 193 insertions(+), 140 deletions(-) diff --git a/examples/python3/actuators/cable.py b/examples/python3/actuators/cable.py index 7b242dd9..028e21f3 100644 --- a/examples/python3/actuators/cable.py +++ b/examples/python3/actuators/cable.py @@ -45,7 +45,7 @@ def PullingCable(attachedTo=None, # This add a MechanicalObject, a component holding the degree of freedom of our # mechanical modelling. In the case of a cable it is a set of positions specifying # the points where the cable is passing by. - cable.addObject('MechanicalObject', position=cableGeometry, + cable.addObject('MechanicalObject', position=cableGeometry, showIndices="1", rotation=rotation, translation=translation, scale=uniformScale) # Add a CableConstraint object with a name. @@ -70,7 +70,8 @@ def PullingCable(attachedTo=None, # This add a BarycentricMapping. A BarycentricMapping is a key element as it will add a bi-directional link # between the cable's DoFs and the parents's ones so that movements of the cable's DoFs will be mapped # to the finger and vice-versa; - cable.addObject('BarycentricMapping', name="Mapping", mapForces=False, mapMasses=False) + # cable.addObject('BarycentricMapping', name="Mapping", mapForces=False, mapMasses=False) + cable.addObject('RigidMapping', name="Mapping") return cable diff --git a/examples/python3/actuators/step3.py b/examples/python3/actuators/step3.py index 8f541882..5e3206e2 100644 --- a/examples/python3/actuators/step3.py +++ b/examples/python3/actuators/step3.py @@ -16,10 +16,6 @@ from splib3.loaders import loadPointListFromFile import os -import numpy - -from numpy import ndarray - from splib3.numerics.quat import Quat path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' @@ -52,14 +48,14 @@ # @todo geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, showFramesObject=1, - nbSection=5, nbFrames=26, buildCollisionModel=0) -physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus= 1.0e8, poissonRatio=0.38, beamRadius=6.2e-1/2., + nbSection=5, nbFrames=26, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus=1.0e8, poissonRatio=0.38, beamRadius=6.2e-1 / 2., beamLength=65.5) simuParams = SimulationParameters(rayleighStiffness=1.e-3) Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) -def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState",rigidIndex=2): +def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState", rigidIndex=2): """ The intermediateRigid construction """ if rigidCentral is None: rigidCentral = [0, 0., 0, 0, 0, 0, 1] @@ -72,7 +68,7 @@ def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState",rigi [0., 0., -2., q2[0], q2[1], q2[2], q2[3]]] intermediateRigid = parent.addChild('intermediateRigid') intermediateRigid.addObject('MechanicalObject', name=baseName, template='Rigid3d', - position=rigidCentral, showObject=True, showObjectScale=0.4) + position=rigidCentral, showObject=True, showObjectScale=0.4) # @TODO add the mass of the disk intermediateRigid.addObject('RigidMapping', name="interRigidMap", index=rigidIndex) @@ -87,6 +83,7 @@ def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState",rigi return intermediateRigid + def loadDisk(parentNode): #### MAPPING of the disks (here some torus) #### ########### diskMapping = parentNode.addChild("diskMapping") @@ -95,39 +92,95 @@ def loadDisk(parentNode): diskMapping.addObject('RigidMapping', name="diskMap") -def createRigidDisk(parentNode): # @todo add a parameter for the number of disk +def create_cable_points(): + """ + This function creates cable points based on the given parameters. + + Returns: + cable_base_state (list): A list of base states for the cable. + cable_3d_state (list): A list of 3D positions for the cable. + """ + num_segments = 14 + norm_length = geoParams.beamLength / num_segments + + cable_base_state = [] + cable_3d_state = [] + + for z in [1.7, -1.7, -2]: + base_state = [] + pos_3d = [] + + for i in range(num_segments + 1): + x = i * norm_length + if z == -2: + base_state.append([x, 0., z, 0., 0., 0., 1.]) + # pos_3d.append([x, 0., z]) + pos_3d.append([x, 0., 0]) + else: + base_state.append([x, z, 1., 0., 0., 0., 1.]) + # pos_3d.append([x, z, 1.]) + pos_3d.append([x, 0, 0]) + + cable_base_state.append(base_state) + cable_3d_state.append(pos_3d) + + return cable_base_state, cable_3d_state + + +def createRigidDisk(parentNode): # @todo add a parameter for the number of disk """ Create the rigid disk nodes """ for i in range(1, 14): """ Create the rigid disk nodes """ createIntermediateNode(parentNode, rigidCentral=[0, 0., 0, 0, 0, 0, 1], - baseName=f"rigidState{i}", rigidIndex=i*2) + baseName=f"rigidState{i}", rigidIndex=i * 2) + + +rotation = [0.0, 0.0, 0.0] +translation = [0.0, 0.0, 0.0] +pullPointLocation = [0.0, 0.0, 0.0] +youngModulus = 18000 +valueType = 'position' + -rotation=[0.0, 0.0, 0.0] -translation=[0.0, 0.0, 0.0] -pullPointLocation=[0.0, 0.0, 0.0] -youngModulus=18000 -valueType='position' def createScene(rootNode): addHeader(rootNode) rootNode.gravity = [0., -9.81, 0.] stemNode = addSolverNode(rootNode, name="stemNode") cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) - # create the rigid disk node createRigidDisk(cosserat.cosseratFrame) - PullingCable(stemNode, - "PullingCable", + cableBaseState, cable3DState = create_cable_points() + + cable1Node = stemNode.addChild("cable1Node") + cable1Node.addObject('MechanicalObject', name="cable1Pos", template='Rigid3d', position=cableBaseState[0], + showObject=True, showObjectScale=2) + PullingCable(cable1Node, "PullingCable", pullPointLocation=pullPointLocation, rotation=rotation, translation=translation, - cableGeometry=loadPointListFromFile(os.path.join(path, "../cable.json")), + cableGeometry=cable3DState[0], valueType=valueType) - return - - - + cable2Node = stemNode.addChild("cable2Node") + cable2Node.addObject('MechanicalObject', name="cable2Pos", template='Rigid3d', position=cableBaseState[1], + showObject=True, showObjectScale=2) + PullingCable(cable2Node, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[1], + valueType=valueType) + cable3Node = stemNode.addChild("cable3Node") + cable3Node.addObject('MechanicalObject', name="cable3Pos", template='Rigid3d', position=cableBaseState[2], + showObject=True, showObjectScale=2) + PullingCable(cable3Node, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[2], + valueType=valueType) + return diff --git a/examples/python3/cosserat/cosserat-tuto.html b/examples/python3/cosserat/cosserat-tuto.html index 41446624..f55ed127 100644 --- a/examples/python3/cosserat/cosserat-tuto.html +++ b/examples/python3/cosserat/cosserat-tuto.html @@ -1,115 +1,115 @@ -<!DOCTYPE html> -<html xmlns="http://www.w3.org/1999/xhtml" lang="" xml:lang=""> -<head> - <meta charset="utf-8" /> - <meta name="generator" content="pandoc" /> - <meta name="viewport" content="width=device-width, initial-scale=1.0, user-scalable=yes" /> - <title>tripod-tuto</title> - <style type="text/css"> - code{white-space: pre-wrap;} - span.smallcaps{font-variant: small-caps;} - span.underline{text-decoration: underline;} - div.column{display: inline-block; vertical-align: top; width: 50%;} - </style> - <style type="text/css"> -a.sourceLine { display: inline-block; line-height: 1.25; } -a.sourceLine { pointer-events: none; color: inherit; text-decoration: inherit; } -a.sourceLine:empty { height: 1.2em; } -.sourceCode { overflow: visible; } -code.sourceCode { white-space: pre; position: relative; } -div.sourceCode { margin: 1em 0; } -pre.sourceCode { margin: 0; } -@media screen { -div.sourceCode { overflow: auto; } -} -@media print { -code.sourceCode { white-space: pre-wrap; } -a.sourceLine { text-indent: -1em; padding-left: 1em; } -} -pre.numberSource a.sourceLine - { position: relative; left: -4em; } -pre.numberSource a.sourceLine::before - { content: attr(title); - position: relative; left: -1em; text-align: right; vertical-align: baseline; - border: none; pointer-events: all; display: inline-block; - -webkit-touch-callout: none; -webkit-user-select: none; - -khtml-user-select: none; -moz-user-select: none; - -ms-user-select: none; user-select: none; - padding: 0 4px; width: 4em; - color: #aaaaaa; - } -pre.numberSource { margin-left: 3em; border-left: 1px solid #aaaaaa; padding-left: 4px; } -div.sourceCode - { } -@media screen { -a.sourceLine::before { text-decoration: underline; } -} -code span.al { color: #ff0000; font-weight: bold; } /* Alert */ -code span.an { color: #60a0b0; font-weight: bold; font-style: italic; } /* Annotation */ -code span.at { color: #7d9029; } /* Attribute */ -code span.bn { color: #40a070; } /* BaseN */ -code span.bu { } /* BuiltIn */ -code span.cf { color: #007020; font-weight: bold; } /* ControlFlow */ -code span.ch { color: #4070a0; } /* Char */ -code span.cn { color: #880000; } /* Constant */ -code span.co { color: #60a0b0; font-style: italic; } /* Comment */ -code span.cv { color: #60a0b0; font-weight: bold; font-style: italic; } /* CommentVar */ -code span.do { color: #ba2121; font-style: italic; } /* Documentation */ -code span.dt { color: #902000; } /* DataType */ -code span.dv { color: #40a070; } /* DecVal */ -code span.er { color: #ff0000; font-weight: bold; } /* Error */ -code span.ex { } /* Extension */ -code span.fl { color: #40a070; } /* Float */ -code span.fu { color: #06287e; } /* Function */ -code span.im { } /* Import */ -code span.in { color: #60a0b0; font-weight: bold; font-style: italic; } /* Information */ -code span.kw { color: #007020; font-weight: bold; } /* Keyword */ -code span.op { color: #666666; } /* Operator */ -code span.ot { color: #007020; } /* Other */ -code span.pp { color: #bc7a00; } /* Preprocessor */ -code span.sc { color: #4070a0; } /* SpecialChar */ -code span.ss { color: #bb6688; } /* SpecialString */ -code span.st { color: #4070a0; } /* String */ -code span.va { color: #19177c; } /* Variable */ -code span.vs { color: #4070a0; } /* VerbatimString */ -code span.wa { color: #60a0b0; font-weight: bold; font-style: italic; } /* Warning */ - </style> - <link rel="stylesheet" href="../../../../docs/style.css" /> -</head> -<body> - <p><img src="images/tripodtuto.png" /></p> - <script language="javascript"> - function toggle(target) { - d = document.getElementById(target); - if(d.className === "show") - d.className = "hide" - else - d.className = "show" - return false; + <!DOCTYPE html> + <html xmlns="http://www.w3.org/1999/xhtml" lang="" xml:lang=""> + <head> + <meta charset="utf-8" /> + <meta name="generator" content="pandoc" /> + <meta name="viewport" content="width=device-width, initial-scale=1.0, user-scalable=yes" /> + <title>tripod-tuto</title> + <style type="text/css"> + code{white-space: pre-wrap;} + span.smallcaps{font-variant: small-caps;} + span.underline{text-decoration: underline;} + div.column{display: inline-block; vertical-align: top; width: 50%;} + </style> + <style type="text/css"> + a.sourceLine { display: inline-block; line-height: 1.25; } + a.sourceLine { pointer-events: none; color: inherit; text-decoration: inherit; } + a.sourceLine:empty { height: 1.2em; } + .sourceCode { overflow: visible; } + code.sourceCode { white-space: pre; position: relative; } + div.sourceCode { margin: 1em 0; } + pre.sourceCode { margin: 0; } + @media screen { + div.sourceCode { overflow: auto; } } - </script> - - <ul> - <li><p>you have installed <a href="https://www.sofa-framework.org/">SOFA</a> with the <a href="http://stlib.readthedocs.io/en/latest/">STLIB</a> and <a href="https://project.inria.fr/softrobot/">SoftRobots</a> plugins.</p></li> - <li><p>you have basic knowledge of the <a href="https://www.python.org/">Python</a> programming language. If this is not the case you can go to <a href="https://www.python.org/">Python</a>Tutorials.</p></li> - <li><p>you have basic knowledge of scene modelling with SOFA. If not, please complete the <a href="../FirstSteps/firststeps-tuto.html?sofafile=firststeps-tuto.py">FirstStep</a> tutorial first.</p></li> - </ul> - - <ul> - <li><a href="cosseratObject.py">Cosserat object</a></li> - <li><a href="examples/PCS_Example1.py">Exemple1</a></li> - <li><a href="examples/PCS_Example2.py">Exemple2</a> - <li><a href="examples/PCS_Example3.py">Exemple3.</a></li> - <li><a href="examples/PNLS_Example1.py">PNLSExemple1</a></li> - <li><a href="examples/PNLS_Example2.py">PNLSExemple2</a> - <li><a href="examples/PNLS_Example3.py">PNLSExemple3.</a></li> - - <li><a href="needle/CosserateLikeNeedle.py">CosseratLikeNeedle.</a></li> - <li><a href="actuators/directFingerActuator.py">directFingerActuator.</a></li> - <li><a href="examples/twoSlidingCosseratBeams.py">twoSlidingCosseratBeams.</a></li> - <li><a href="inverse/inverseCosseratNeedle.py">inverseCosseratNeedle.</a></li> - - - </ul> -</body> -</html> \ No newline at end of file + @media print { + code.sourceCode { white-space: pre-wrap; } + a.sourceLine { text-indent: -1em; padding-left: 1em; } + } + pre.numberSource a.sourceLine + { position: relative; left: -4em; } + pre.numberSource a.sourceLine::before + { content: attr(title); + position: relative; left: -1em; text-align: right; vertical-align: baseline; + border: none; pointer-events: all; display: inline-block; + -webkit-touch-callout: none; -webkit-user-select: none; + -khtml-user-select: none; -moz-user-select: none; + -ms-user-select: none; user-select: none; + padding: 0 4px; width: 4em; + color: #aaaaaa; + } + pre.numberSource { margin-left: 3em; border-left: 1px solid #aaaaaa; padding-left: 4px; } + div.sourceCode + { } + @media screen { + a.sourceLine::before { text-decoration: underline; } + } + code span.al { color: #ff0000; font-weight: bold; } /* Alert */ + code span.an { color: #60a0b0; font-weight: bold; font-style: italic; } /* Annotation */ + code span.at { color: #7d9029; } /* Attribute */ + code span.bn { color: #40a070; } /* BaseN */ + code span.bu { } /* BuiltIn */ + code span.cf { color: #007020; font-weight: bold; } /* ControlFlow */ + code span.ch { color: #4070a0; } /* Char */ + code span.cn { color: #880000; } /* Constant */ + code span.co { color: #60a0b0; font-style: italic; } /* Comment */ + code span.cv { color: #60a0b0; font-weight: bold; font-style: italic; } /* CommentVar */ + code span.do { color: #ba2121; font-style: italic; } /* Documentation */ + code span.dt { color: #902000; } /* DataType */ + code span.dv { color: #40a070; } /* DecVal */ + code span.er { color: #ff0000; font-weight: bold; } /* Error */ + code span.ex { } /* Extension */ + code span.fl { color: #40a070; } /* Float */ + code span.fu { color: #06287e; } /* Function */ + code span.im { } /* Import */ + code span.in { color: #60a0b0; font-weight: bold; font-style: italic; } /* Information */ + code span.kw { color: #007020; font-weight: bold; } /* Keyword */ + code span.op { color: #666666; } /* Operator */ + code span.ot { color: #007020; } /* Other */ + code span.pp { color: #bc7a00; } /* Preprocessor */ + code span.sc { color: #4070a0; } /* SpecialChar */ + code span.ss { color: #bb6688; } /* SpecialString */ + code span.st { color: #4070a0; } /* String */ + code span.va { color: #19177c; } /* Variable */ + code span.vs { color: #4070a0; } /* VerbatimString */ + code span.wa { color: #60a0b0; font-weight: bold; font-style: italic; } /* Warning */ + </style> + <link rel="stylesheet" href="../../../../docs/style.css" /> + </head> + <body> + <p><img src="images/tripodtuto.png" /></p> + <script language="javascript"> + function toggle(target) { + d = document.getElementById(target); + if(d.className === "show") + d.className = "hide" + else + d.className = "show" + return false; + } + </script> + + <ul> + <li><p>you have installed <a href="https://www.sofa-framework.org/">SOFA</a> with the <a href="http://stlib.readthedocs.io/en/latest/">STLIB</a> and <a href="https://project.inria.fr/softrobot/">SoftRobots</a> plugins.</p></li> + <li><p>you have basic knowledge of the <a href="https://www.python.org/">Python</a> programming language. If this is not the case you can go to <a href="https://www.python.org/">Python</a>Tutorials.</p></li> + <li><p>you have basic knowledge of scene modelling with SOFA. If not, please complete the <a href="../FirstSteps/firststeps-tuto.html?sofafile=firststeps-tuto.py">FirstStep</a> tutorial first.</p></li> + </ul> + + <ul> + <li><a href="cosseratObject.py">Cosserat object</a></li> + <li><a href="examples/PCS_Example1.py">Exemple1</a></li> + <li><a href="examples/PCS_Example2.py">Exemple2</a> + <li><a href="examples/PCS_Example3.py">Exemple3.</a></li> + <li><a href="examples/PNLS_Example1.py">PNLSExemple1</a></li> + <li><a href="examples/PNLS_Example2.py">PNLSExemple2</a> + <li><a href="examples/PNLS_Example3.py">PNLSExemple3.</a></li> + + <li><a href="needle/CosserateLikeNeedle.py">CosseratLikeNeedle.</a></li> + <li><a href="actuators/directFingerActuator.py">directFingerActuator.</a></li> + <li><a href="examples/twoSlidingCosseratBeams.py">twoSlidingCosseratBeams.</a></li> + <li><a href="inverse/inverseCosseratNeedle.py">inverseCosseratNeedle.</a></li> + + + </ul> + </body> + </html> \ No newline at end of file diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index 8fe2d21f..258a8bcc 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -15,7 +15,6 @@ from stlib3.physics.deformable import ElasticMaterialObject from stlib3.physics.constraints import FixedBox -import numpy as np import os From 267b62066472151671b9b77f834084569b569a1b Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Sat, 23 Sep 2023 18:03:10 +0200 Subject: [PATCH 10/71] Fix the CableConstraint issue --- examples/python3/actuators/cable.py | 10 ++- examples/python3/actuators/step1.py | 97 ++++++++++++++++++++ examples/python3/actuators/utils.py | 104 ++++++++++++++++++++++ examples/python3/cosserat/CosseratBase.py | 15 ++-- examples/python3/useful/header.py | 82 ++++++++--------- 5 files changed, 256 insertions(+), 52 deletions(-) create mode 100644 examples/python3/actuators/step1.py create mode 100644 examples/python3/actuators/utils.py diff --git a/examples/python3/actuators/cable.py b/examples/python3/actuators/cable.py index 028e21f3..3f54a60e 100644 --- a/examples/python3/actuators/cable.py +++ b/examples/python3/actuators/cable.py @@ -6,12 +6,14 @@ def PullingCable(attachedTo=None, uniformScale=1.0, pullPointLocation=None, initialValue=0.0, - valueType="displacement"): + valueType="displacement", + input=None): """Adds a cable constraint. The constraint apply to a parent mesh. Args: + input: name (str): Name of the added cable. cableGeometry: (list vec3): Location of the degree of freedom of the cable. @@ -70,8 +72,10 @@ def PullingCable(attachedTo=None, # This add a BarycentricMapping. A BarycentricMapping is a key element as it will add a bi-directional link # between the cable's DoFs and the parents's ones so that movements of the cable's DoFs will be mapped # to the finger and vice-versa; - # cable.addObject('BarycentricMapping', name="Mapping", mapForces=False, mapMasses=False) - cable.addObject('RigidMapping', name="Mapping") + # cable.addObject('BarycentricMapping', name="Mapping", mapForces=False, mapMasses=False, + # input=input) + # cable.addObject('RigidMapping', name="Mapping") + cable.addObject('IdentityMapping', name="Mapping") return cable diff --git a/examples/python3/actuators/step1.py b/examples/python3/actuators/step1.py new file mode 100644 index 00000000..2baf5f2b --- /dev/null +++ b/examples/python3/actuators/step1.py @@ -0,0 +1,97 @@ +# -*- coding: utf-8 -*- +""" + Scene robot ISIR. +""" +__authors__ = "Yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +from useful.header import addHeader, addSolverNode +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from cable import PullingCable +from utils import createRigidDisk, create_cable_points, FingerController +from splib3.loaders import loadPointListFromFile + +import os + +""" @info +Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) + et de 13 disques en iglidur. + + -La colonne mesure 65.5 cm pour un diamètre de 6.2mm + +# -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g +# +# -Les disques sur la colonne sont espacés d'environ 4.7cm +# +# -Concernant les trous des disques, il y en a 3 sortes : +# +# les trous intérieurs sont au nombre de 3, ont un diamètre de 2mm et sont placés à environ 6mm du centre +# les trous intermédiaires sont au nombre de 3, ont un diamètre de 2.5mm et sont placés à environ 2cm du centre +# les trous extérieurs sont au nombre de 12, ont un diamètre de 1mm et sont placés à environ 2.3cm du centre +# -Enfin concernant le routage des câbles : +# +# Le manipulateur est constitué de 3 sections, chaque section est composé de 3 fils (disposés à 120° les uns des autres) +# Les câbles sont routés de manière parallèle +# La première section (celle du haut) ainsi que la deuxième (intermédiaire) sont constituées de 4 disques et la +# troisième (celle du bas) de 5 disques +# Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 +# passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. +# [@info] ================ Unit: N, cm, g, Pa ================ +""" + +# @todo +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, showFramesObject=1, + nbSection=14, nbFrames=14, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus=1.0e8, poissonRatio=0.38, beamRadius=6.2e-1 / 2., + beamLength=65.5) +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +rotation = [0.0, 0.0, 0.0] +translation = [0.0, 0.0, 0.0] +pullPointLocation = [0.0, 0.0, 0.0] +youngModulus = 18000 +valueType = 'position' + + +def createScene(rootNode): + addHeader(rootNode, isConstrained=True) + rootNode.gravity = [9.81, 0., 0.] + + stemNode = addSolverNode(rootNode, name="stemNode", isConstrained=True) + + cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) + createRigidDisk(cosserat.cosseratFrame) + + # create the rigid disk node + cableBaseState, cable3DState = create_cable_points(geoParams=geoParams, num_segments=14) + + cable1Node = cosserat.cosseratFrame.addChild("cable1Node") + cable1Node.addObject('MechanicalObject', name="cable1Pos", template='Rigid3d', position=cableBaseState, + showObjectScale=0.8, showObject=True) + cable1Node.addObject('RigidMapping', name="cable1Map", rigidIndexPerPoint=[i for i in range(15)], + globalToLocalCoords=1 + ) + cable1_mechaNode = cable1Node.addChild("cable_mecha1Node") + cable_Mo = cable1_mechaNode.addObject('MechanicalObject', name="cable1_mechaPos", template='Vec3d', + position=cable3DState, + showIndices=True) + # cable1_mechaNode.addObject('RigidMapping', name="cable1Map", globalToLocalCoords=1) + cable1_mechaNode.addObject('SkinningMapping', nbRef='1') + + cable = PullingCable(cable1_mechaNode, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[0], + valueType=valueType, + input=cable_Mo.getLinkPath() + ) + cable1_mechaNode.addObject(FingerController(cable)) + + return rootNode diff --git a/examples/python3/actuators/utils.py b/examples/python3/actuators/utils.py new file mode 100644 index 00000000..560a92ed --- /dev/null +++ b/examples/python3/actuators/utils.py @@ -0,0 +1,104 @@ +# -*- coding: utf-8 -*- +from splib3.numerics.quat import Quat +import os +import Sofa +import Sofa.constants.Key as Key +path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' + + +def loadDisk(parentNode, filename): + # ### MAPPING of the disks (here some torus) #### ########### + diskMapping = parentNode.addChild("diskMapping") + diskMapping.addObject("MeshOBJLoader", name="diskLoader", filename=filename) + diskMapping.addObject("OglModel", name="Visual", src="@diskLoader", color="1.0 0.5 0.25 1.0") + diskMapping.addObject('RigidMapping', name="diskMap") + + +def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState", rigidIndex=0, filename=None): + """ The intermediateRigid construction """ + if rigidCentral is None: + rigidCentral = [0, 0., 0, 0, 0, 0, 1] + q0 = Quat() + q1 = Quat() + q2 = Quat() + + interChildPos = [[0, 1.7, 1., q0[0], q0[1], q0[2], q0[3]], + [0, -1.7, 1., q1[0], q1[1], q1[2], q1[3]], + [0., 0., -2., q2[0], q2[1], q2[2], q2[3]]] + intermediateRigid = parent.addChild('intermediateRigid') + intermediateRigid.addObject('MechanicalObject', name=baseName, template='Rigid3d', + position=rigidCentral, showObject=True, showObjectScale=0.5) + # @TODO add the mass of the disk + intermediateRigid.addObject('RigidMapping', name="interRigidMap", index=rigidIndex) + + # """Create intermediate kids""" + # interRigidChild = intermediateRigid.addChild('interRigidChild') + # interRigidChild.addObject('MechanicalObject', name="interRigidChildMo", template='Rigid3d', + # position=interChildPos, showObject=True, showObjectScale=0.5) + # interRigidChild.addObject('RigidMapping', name="interRigidMap") + + """ Add disk to the scene, actually this disk is only use for the visualisation """ + loadDisk(intermediateRigid, filename=filename) + + return intermediateRigid + + +def createRigidDisk(parentNode): # @todo add a parameter for the number of disk + """ Create the rigid disk nodes """ + for i in range(1, 15): + """ Create the rigid disk nodes """ + createIntermediateNode(parentNode, rigidCentral=[0, 0., 0, 0, 0, 0, 1], + baseName=f"rigidState{i}", rigidIndex=i, filename=f'{path}disqueBlender2.obj') + + +def create_cable_points(geoParams=None, num_segments=14): + """ + This function creates cable points based on the given parameters. + + Returns: + cable_base_state (list): A list of base states for the cable. + cable_3d_state (list): A list of 3D positions for the cable. + """ + + norm_length = geoParams.beamLength / num_segments + + cable_base_state = [] + cable_3d_state = [] + + # for z in [1.7, -1.7, -2]: + for z in [1.7]: + base_state = [] + pos_3d = [] + + for i in range(num_segments + 1): + x = i * norm_length + if z == -2: + base_state.append([x, 0., z, 0., 0., 0., 1.]) + # pos_3d.append([x, 0., z]) + pos_3d.append([x, 0., z]) + else: + base_state.append([x, z, 1., 0., 0., 0., 1.]) + # pos_3d.append([x, z, 1.]) + pos_3d.append([x, z, 1]) + cable_base_state.append(base_state) + cable_3d_state.append(pos_3d) + return cable_base_state, cable_3d_state + + +class FingerController(Sofa.Core.Controller): + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, args, kwargs) + self.cable = args[0] + self.name = "FingerController" + + def onKeypressedEvent(self, event): + displacement = self.cable.CableConstraint.value[0] + print(f' The displacement is : {displacement}') + if event["key"] == Key.plus: + displacement += 0.01 + + elif event["key"] == Key.minus: + displacement -= 0.01 + if displacement < 0: + displacement = 0 + self.cable.CableConstraint.value = [displacement] \ No newline at end of file diff --git a/examples/python3/cosserat/CosseratBase.py b/examples/python3/cosserat/CosseratBase.py index 88865af9..0a6aac98 100644 --- a/examples/python3/cosserat/CosseratBase.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -17,7 +17,6 @@ class CosseratBase(Sofa.Prefab): - """ CosseratBase model prefab class. It is a prefab class that allow to create a cosserat beam/rod in Sofa. Structure: @@ -40,7 +39,7 @@ class CosseratBase(Sofa.Prefab): {'name': 'attachingToLink', 'type': 'string', 'help': 'a rest shape force field will constraint the object ' 'to follow arm position', 'default': '1'}, {'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'} - ] + ] def __init__(self, *args, **kwargs): Sofa.Prefab.__init__(self, *args, **kwargs) @@ -48,10 +47,10 @@ def __init__(self, *args, **kwargs): beamPhysicsParams = self.params.beamPhysicsParams beamGeometryParams = self.params.beamGeoParams - self.beamMass = beamPhysicsParams.beamMass # self.cosseratGeometry['beamMass'] + self.beamMass = beamPhysicsParams.beamMass # self.cosseratGeometry['beamMass'] self.parent = kwargs.get('parent') - self.useInertiaParams = beamPhysicsParams.useInertia # False - self.radius = beamPhysicsParams.beamRadius # kwargs.get('radius') + self.useInertiaParams = beamPhysicsParams.useInertia # False + self.radius = beamPhysicsParams.beamRadius # kwargs.get('radius') if self.parent.hasObject("EulerImplicitSolver") is False: print('The code does not have parent EulerImplicit') @@ -69,9 +68,9 @@ def __init__(self, *args, **kwargs): self.frames3D = cosserat_geometry.cable_positionF self.cosseratCoordinateNode = self._addCosseratCoordinate(cosserat_geometry.bendingState, - cosserat_geometry.sectionsLengthList) + cosserat_geometry.sectionsLengthList) self.cosseratFrame = self._addCosseratFrame(cosserat_geometry.framesF, cosserat_geometry.curv_abs_inputS, - cosserat_geometry.curv_abs_outputF) + cosserat_geometry.curv_abs_outputF) def init(self): pass @@ -166,7 +165,7 @@ def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): framesMO = cosseratInSofaFrameNode.addObject( 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showIndices=self.params.beamGeoParams.showFramesObject, - showObject=self.params.beamGeoParams.showFramesObject, showObjectScale=0.1) + showObject=self.params.beamGeoParams.showFramesObject, showObjectScale=1.8) if self.beamMass != 0.: cosseratInSofaFrameNode.addObject( 'UniformMass', totalMass=self.beamMass, showAxisSizeFactor='0') diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index 258a8bcc..67bcc966 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -6,7 +6,6 @@ _type_: _description_ """ - __authors__ = "Younes" __contact__ = "adagolodjo@protonmail.com, yinoussa.adagolodjo@inria.fr" __version__ = "1.0.0" @@ -40,35 +39,35 @@ def addHeader(parentNode, multithreading=False, inverse=False, isConstrained=Fal """ settings = parentNode.addChild('Settings') settings.addObject('RequiredPlugin', pluginName=[ - "Cosserat", "Sofa.Component.AnimationLoop", # Needed to use components FreeMotionAnimationLoop - "Sofa.Component.Collision.Detection.Algorithm", - "Sofa.Component.Collision.Detection.Intersection", # Needed to use components LocalMinDistance - "Sofa.Component.Collision.Response.Contact", # Needed to use components RuleBasedContactManager - "Sofa.Component.Constraint.Lagrangian.Correction", # Needed to use components GenericConstraintCorrection - "Sofa.Component.Constraint.Lagrangian.Solver", # Needed to use components GenericConstraintSolver - "Sofa.Component.Constraint.Projective", # Needed to use components FixedConstraint - "Sofa.Component.IO.Mesh", # Needed to use components MeshOBJLoader, MeshSTLLoader - "Sofa.Component.Mass", 'Sofa.Component.LinearSolver.Direct', - "Sofa.Component.Setting", # Needed to use components BackgroundSetting - "Sofa.Component.SolidMechanics.Spring", # Needed to use components RestShapeSpringsForceField - "Sofa.Component.Topology.Container.Constant", # Needed to use components MeshTopology - "Sofa.Component.Topology.Container.Dynamic", "Sofa.Component.Playback", - "Sofa.Component.Playback", "Sofa.Component.Visual", # Needed to use components VisualStyle - "Sofa.Component.Topology.Container.Grid", # Needed to use components RegularGridTopology - "Sofa.Component.Topology.Mapping", # Needed to use components Edge2QuadTopologicalMapping - "Sofa.GL.Component.Rendering3D", # Needed to use components OglGrid, OglModel - "Sofa.GUI.Component", "Sofa.Component.Collision.Geometry", "Sofa.Component.LinearSolver.Direct", - "Sofa.Component.Mapping.Linear", "Sofa.Component.MechanicalLoad", - "Sofa.Component.StateContainer", 'Sofa.Component.ODESolver.Backward' + "Cosserat", "Sofa.Component.AnimationLoop", # Needed to use components FreeMotionAnimationLoop + "Sofa.Component.Collision.Detection.Algorithm", + "Sofa.Component.Collision.Detection.Intersection", # Needed to use components LocalMinDistance + "Sofa.Component.Collision.Response.Contact", # Needed to use components RuleBasedContactManager + "Sofa.Component.Constraint.Lagrangian.Correction", # Needed to use components GenericConstraintCorrection + "Sofa.Component.Constraint.Lagrangian.Solver", # Needed to use components GenericConstraintSolver + "Sofa.Component.Constraint.Projective", # Needed to use components FixedConstraint + "Sofa.Component.IO.Mesh", # Needed to use components MeshOBJLoader, MeshSTLLoader + "Sofa.Component.Mass", 'Sofa.Component.LinearSolver.Direct', + "Sofa.Component.Setting", # Needed to use components BackgroundSetting + "Sofa.Component.SolidMechanics.Spring", # Needed to use components RestShapeSpringsForceField + "Sofa.Component.Topology.Container.Constant", # Needed to use components MeshTopology + "Sofa.Component.Topology.Container.Dynamic", "Sofa.Component.Playback", + "Sofa.Component.Playback", "Sofa.Component.Visual", # Needed to use components VisualStyle + "Sofa.Component.Topology.Container.Grid", # Needed to use components RegularGridTopology + "Sofa.Component.Topology.Mapping", # Needed to use components Edge2QuadTopologicalMapping + "Sofa.GL.Component.Rendering3D", # Needed to use components OglGrid, OglModel + "Sofa.GUI.Component", "Sofa.Component.Collision.Geometry", "Sofa.Component.LinearSolver.Direct", + "Sofa.Component.Mapping.Linear", "Sofa.Component.MechanicalLoad", + "Sofa.Component.StateContainer", 'Sofa.Component.ODESolver.Backward' ]) settings.addObject('BackgroundSetting', color=[1, 1, 1, 1]) # settings.addObject('AttachBodyButtonSetting', stiffness=1e6) parentNode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels showCollisionModels ' - 'hideBoundingCollisionModels hideForceFields ' - 'hideInteractionForceFields hideWireframe showMechanicalMappings') - if isConstrained : + 'hideBoundingCollisionModels hideForceFields ' + 'hideInteractionForceFields hideWireframe showMechanicalMappings') + if isConstrained: parentNode.addObject('FreeMotionAnimationLoop', parallelCollisionDetectionAndFreeMotion=multithreading, parallelODESolving=multithreading) if inverse: @@ -107,8 +106,10 @@ def addVisual(node): 'hideInteractionForceFields hideWireframe showMechanicalMappings') return node -def addSolverNode(node, name='solverNode', template='CompressedRowSparseMatrixd', rayleighMass=0., rayleighStiffness=0., firstOrder=False, - iterative=False, isConstrained=False): + +def addSolverNode(node, name='solverNode', template='CompressedRowSparseMatrixd', rayleighMass=0., rayleighStiffness=0., + firstOrder=False, + iterative=False, isConstrained=False): """ Adds solvers (EulerImplicitSolver, LDLSolver, GenericConstraintCorrection) to the given node. @@ -138,7 +139,8 @@ def addSolverNode(node, name='solverNode', template='CompressedRowSparseMatrixd' return solverNode -def addFEMObject(parentNode, path) : + +def addFEMObject(parentNode, path): fingerSolver = addSolverNode(parentNode) # Load a VTK tetrahedral mesh and expose the resulting topology in the scene . @@ -170,9 +172,10 @@ def addFEMObject(parentNode, path) : FEMpos = [" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"] femPoints = fingerSolver.addChild('femPoints') femPoints.addObject('MechanicalObject', name="pointsInFEM", position=FEMpos, showObject="1", - showIndices="1") + showIndices="1") femPoints.addObject('BarycentricMapping') + def addMappedPoints(parentNode, name="pointsInFEM", position=None, showObject="1", showIndices="1", femPos=" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"): if position is None: @@ -190,8 +193,8 @@ def addMappedPoints(parentNode, name="pointsInFEM", position=None, showObject="1 femPoints.addObject('BarycentricMapping') return femPoints -def Finger(parentNode=None, name="Finger", rotation=None, translation=None, fixingBox=None,path=None, femPos=None): +def Finger(parentNode=None, name="Finger", rotation=None, translation=None, fixingBox=None, path=None, femPos=None): if fixingBox is None: fixingBox = [-18, -15, -8, 2, -3, 8] if rotation is None: @@ -201,18 +204,17 @@ def Finger(parentNode=None, name="Finger", rotation=None, translation=None, fixi if path is None: path = f'{os.path.dirname(os.path.abspath(__file__))}/' - # TODO : add physical properties as the finger input finger = parentNode.addChild(name) e_object = ElasticMaterialObject(finger, - volumeMeshFileName=f'{path}finger.vtk', - poissonRatio=0.48, - youngModulus=500, - totalMass=0.075, - surfaceColor=[0.0, 0.7, 0.7, 0.5], - surfaceMeshFileName=f'{path}finger.stl', - rotation=rotation, - translation=translation) + volumeMeshFileName=f'{path}finger.vtk', + poissonRatio=0.48, + youngModulus=500, + totalMass=0.075, + surfaceColor=[0.0, 0.7, 0.7, 0.5], + surfaceMeshFileName=f'{path}finger.stl', + rotation=rotation, + translation=translation) FixedBox(e_object, doVisualization=True, atPositions=fixingBox) @@ -222,13 +224,11 @@ def Finger(parentNode=None, name="Finger", rotation=None, translation=None, fixi else: femPoints = addMappedPoints(e_object, femPos=femPos) - finger.addChild(e_object) return finger, femPoints + # Test def createScene(rootNode): addHeader(rootNode) addSolverNode(rootNode) - - From d93568addf7d3db6abca6138f97d4c4a22a74329 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 6 Oct 2023 15:58:37 +0200 Subject: [PATCH 11/71] Update the Readme.md file --- README.md | 60 +++++---- examples/python3/actuators/step1.py | 63 ++------- examples/python3/actuators/step4.py | 97 ++++++++++++++ examples/python3/actuators/step7.py | 186 ++++++++++++++++++++++++++ examples/python3/cosserat/__init__.py | 6 +- examples/python3/tutorial/tuto-2.py | 35 +++++ examples/python3/tutorial/tuto.py | 12 ++ 7 files changed, 380 insertions(+), 79 deletions(-) create mode 100644 examples/python3/actuators/step4.py create mode 100644 examples/python3/actuators/step7.py create mode 100644 examples/python3/tutorial/tuto-2.py create mode 100644 examples/python3/tutorial/tuto.py diff --git a/README.md b/README.md index 5ceb826a..ac54cfe3 100644 --- a/README.md +++ b/README.md @@ -1,43 +1,38 @@ -# Description +# Cosserat +An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. We also welcome contributions from the community to enhance and expand the capabilities of this plugin. +### Description related to Soft-body modeling -Cosserat model has been introduced in continuum robotics to simulate the deformation of the robot body whose geometry -and mechanical characteristics are similar to a rod. -By extension, this model can be used to simulate needles, wires. -The specificity of Cosserat's theory from the point of view of the mechanics of continuous media, is to consider that: each material point -of an object is rigid body(3 translations, 3 rotations), where most other models of continuum media mechanics consider -the material point as particles (3 translations). -For the modeling of linear structures, it is therefore possible to find a framework very close to the articulated solids with a series -of rigid body whose relative position is defined by a strain state. -This model can be used to model and control concentric tube robots, continuum robots actuated with cables, or pneumatic soft robots -with a constant cross-section. +The Cosserat model has found applications in the realm of continuum robotics, particularly for simulating the deformation of robot bodies with geometries and mechanical properties akin to rods. This model aligns closely with the dynamic deformation patterns exhibited by soft manipulators, as it can effectively replicate nonlinear deformations encompassing bending, torsion, extension, and shearing. -## Features +One distinctive feature of Cosserat's theory, within the domain of continuous media mechanics, lies in its conceptualization: it views each material point of an object as a rigid body with six degrees of freedom (three translations and three rotations). In contrast, many other models in continuum media mechanics tend to treat material points as particles with only three translation degrees of freedom. -1. Pieces-wise constant Strain PCS: This feature is base on the paper - 1. __Discrete cosserat approach for soft robot dynamics: A new piece-wise constant strain model with torsion and shears__ [Link to the paper](https://ieeexplore.ieee.org/document/7759808) - 2. __Coupling numerical deformable models in global and reduced coordinates for the simulation of the direct and the inverse kinematics of Soft Robots__ [Link to the paper](https://hal.archives-ouvertes.fr/hal-03192168/document) +When modeling linear structures, this framework enables the creation of a structure closely resembling articulated solids, consisting of a series of rigid bodies whose relative positions are defined by their strain states. Consequently, this model serves as a versatile tool for modeling and controlling a variety of systems, including concentric tube robots, continuum robots driven by cables, or pneumatic soft robots with constant cross-sections. -<div align="center"> - <a href="https://www.youtube.com/watch?v=qwzKAgw31pU"><img src="https://img.youtube.com/vi/qwzKAgw31pU/0.jpg" alt="link to youtube"></a> -</div> +### Theory -2. Pieces-wise Non-constant Strain: -3. DCM with Plastic model +### Numerics + +### Some use cases + + +## Modeling and control -### Modelling cochlear implant using Discret Cosserat Model (DCM) +### Direct control + +#### Modeling cochlear implant using Discret Cosserat Model (DCM) | View 1 | View 2 | View 3 | |---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------| | <img src="/doc/images/multiSectionWithColorMap1.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap2.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap3.png" width="300" title="DCM as an implant"> | ### DCM for cable modeling to control deformable robots: -| Direct simulation of a soft gripper | The study the model convergence | -|------------------------------------------------------------------------------------------| --- | +| Direct simulation of a soft gripper | The study of the model convergence | +|------------------------------------------------------------------------------------------| --------------------------------------------------------------------------------------------| | <img src="/doc/images/cosseratgripper_2.png" width="400" title="DCM for cable modeling"> | <img src="/doc/images/tenCossseratSections.png" width="400" title="DCM for cable modeling ">| ### Some use cases -| <img src="/doc/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="doc/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/doc/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | +| <img src="/doc/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="doc/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/doc/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | | ------------- |:-------------:| -----:| | DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| @@ -49,3 +44,20 @@ with a constant cross-section. Format: ![Alt Text] + +### Inverse Control + + +## Publications +1. Pieces-wise constant Strain PCS: This feature is based on the paper +1.a. __Discrete cosserat approach for soft robot dynamics: A new piece-wise constant strain model with torsion and shears__ [Link to the paper](https://ieeexplore.ieee.org/document/7759808) +1.b. __Coupling numerical deformable models in global and reduced coordinates for the simulation of the direct and the inverse kinematics of Soft Robots__ [Link to the paper](https://ieeexplore.ieee.org/abstract/document/9362217). +The link to download the Pdf of the Paper: __https://hal.archives-ouvertes.fr/hal-03192168/document__ + +<div align="center"> + <a href="https://www.youtube.com/watch?v=qwzKAgw31pU"><img src="https://img.youtube.com/vi/qwzKAgw31pU/0.jpg" alt="link to youtube"></a> +</div> + +2. Pieces-wise Nonconstant Strain: +3. DCM with Plastic model + diff --git a/examples/python3/actuators/step1.py b/examples/python3/actuators/step1.py index 2baf5f2b..112c81c5 100644 --- a/examples/python3/actuators/step1.py +++ b/examples/python3/actuators/step1.py @@ -19,29 +19,15 @@ import os """ @info -Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) - et de 13 disques en iglidur. - - -La colonne mesure 65.5 cm pour un diamètre de 6.2mm - -# -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g -# -# -Les disques sur la colonne sont espacés d'environ 4.7cm -# -# -Concernant les trous des disques, il y en a 3 sortes : -# -# les trous intérieurs sont au nombre de 3, ont un diamètre de 2mm et sont placés à environ 6mm du centre -# les trous intermédiaires sont au nombre de 3, ont un diamètre de 2.5mm et sont placés à environ 2cm du centre -# les trous extérieurs sont au nombre de 12, ont un diamètre de 1mm et sont placés à environ 2.3cm du centre -# -Enfin concernant le routage des câbles : -# -# Le manipulateur est constitué de 3 sections, chaque section est composé de 3 fils (disposés à 120° les uns des autres) -# Les câbles sont routés de manière parallèle -# La première section (celle du haut) ainsi que la deuxième (intermédiaire) sont constituées de 4 disques et la -# troisième (celle du bas) de 5 disques -# Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 -# passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. -# [@info] ================ Unit: N, cm, g, Pa ================ + To construct this robot, our initial step involves building its central stem. + In this regard, we've opted for employing the Cosserat model for constructing this rod. Our approach entails + dividing this rod into 14 identical segments, each of which terminates with a rigid element. + Subsequently, we will affix a disc to each of these rigid elements. + Initially, the beam is affected by gravity, oriented along the -y axis. + Later on, we will adjust the direction of gravity to match the real-world scenario where the robot is oriented + downward, aligning with the gravitational force. + To simplify scene construction, we've also activated constraints from the beginning using the 'isConstrained' + keyword set to 'true'. """ # @todo @@ -61,37 +47,10 @@ def createScene(rootNode): addHeader(rootNode, isConstrained=True) - rootNode.gravity = [9.81, 0., 0.] + rootNode.gravity = [0, -9.81, 0.] stemNode = addSolverNode(rootNode, name="stemNode", isConstrained=True) - cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) - createRigidDisk(cosserat.cosseratFrame) - - # create the rigid disk node - cableBaseState, cable3DState = create_cable_points(geoParams=geoParams, num_segments=14) - - cable1Node = cosserat.cosseratFrame.addChild("cable1Node") - cable1Node.addObject('MechanicalObject', name="cable1Pos", template='Rigid3d', position=cableBaseState, - showObjectScale=0.8, showObject=True) - cable1Node.addObject('RigidMapping', name="cable1Map", rigidIndexPerPoint=[i for i in range(15)], - globalToLocalCoords=1 - ) - cable1_mechaNode = cable1Node.addChild("cable_mecha1Node") - cable_Mo = cable1_mechaNode.addObject('MechanicalObject', name="cable1_mechaPos", template='Vec3d', - position=cable3DState, - showIndices=True) - # cable1_mechaNode.addObject('RigidMapping', name="cable1Map", globalToLocalCoords=1) - cable1_mechaNode.addObject('SkinningMapping', nbRef='1') - - cable = PullingCable(cable1_mechaNode, "PullingCable", - pullPointLocation=pullPointLocation, - rotation=rotation, - translation=translation, - cableGeometry=cable3DState[0], - valueType=valueType, - input=cable_Mo.getLinkPath() - ) - cable1_mechaNode.addObject(FingerController(cable)) + stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) return rootNode diff --git a/examples/python3/actuators/step4.py b/examples/python3/actuators/step4.py new file mode 100644 index 00000000..2baf5f2b --- /dev/null +++ b/examples/python3/actuators/step4.py @@ -0,0 +1,97 @@ +# -*- coding: utf-8 -*- +""" + Scene robot ISIR. +""" +__authors__ = "Yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +from useful.header import addHeader, addSolverNode +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from cable import PullingCable +from utils import createRigidDisk, create_cable_points, FingerController +from splib3.loaders import loadPointListFromFile + +import os + +""" @info +Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) + et de 13 disques en iglidur. + + -La colonne mesure 65.5 cm pour un diamètre de 6.2mm + +# -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g +# +# -Les disques sur la colonne sont espacés d'environ 4.7cm +# +# -Concernant les trous des disques, il y en a 3 sortes : +# +# les trous intérieurs sont au nombre de 3, ont un diamètre de 2mm et sont placés à environ 6mm du centre +# les trous intermédiaires sont au nombre de 3, ont un diamètre de 2.5mm et sont placés à environ 2cm du centre +# les trous extérieurs sont au nombre de 12, ont un diamètre de 1mm et sont placés à environ 2.3cm du centre +# -Enfin concernant le routage des câbles : +# +# Le manipulateur est constitué de 3 sections, chaque section est composé de 3 fils (disposés à 120° les uns des autres) +# Les câbles sont routés de manière parallèle +# La première section (celle du haut) ainsi que la deuxième (intermédiaire) sont constituées de 4 disques et la +# troisième (celle du bas) de 5 disques +# Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 +# passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. +# [@info] ================ Unit: N, cm, g, Pa ================ +""" + +# @todo +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, showFramesObject=1, + nbSection=14, nbFrames=14, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus=1.0e8, poissonRatio=0.38, beamRadius=6.2e-1 / 2., + beamLength=65.5) +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +rotation = [0.0, 0.0, 0.0] +translation = [0.0, 0.0, 0.0] +pullPointLocation = [0.0, 0.0, 0.0] +youngModulus = 18000 +valueType = 'position' + + +def createScene(rootNode): + addHeader(rootNode, isConstrained=True) + rootNode.gravity = [9.81, 0., 0.] + + stemNode = addSolverNode(rootNode, name="stemNode", isConstrained=True) + + cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) + createRigidDisk(cosserat.cosseratFrame) + + # create the rigid disk node + cableBaseState, cable3DState = create_cable_points(geoParams=geoParams, num_segments=14) + + cable1Node = cosserat.cosseratFrame.addChild("cable1Node") + cable1Node.addObject('MechanicalObject', name="cable1Pos", template='Rigid3d', position=cableBaseState, + showObjectScale=0.8, showObject=True) + cable1Node.addObject('RigidMapping', name="cable1Map", rigidIndexPerPoint=[i for i in range(15)], + globalToLocalCoords=1 + ) + cable1_mechaNode = cable1Node.addChild("cable_mecha1Node") + cable_Mo = cable1_mechaNode.addObject('MechanicalObject', name="cable1_mechaPos", template='Vec3d', + position=cable3DState, + showIndices=True) + # cable1_mechaNode.addObject('RigidMapping', name="cable1Map", globalToLocalCoords=1) + cable1_mechaNode.addObject('SkinningMapping', nbRef='1') + + cable = PullingCable(cable1_mechaNode, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[0], + valueType=valueType, + input=cable_Mo.getLinkPath() + ) + cable1_mechaNode.addObject(FingerController(cable)) + + return rootNode diff --git a/examples/python3/actuators/step7.py b/examples/python3/actuators/step7.py new file mode 100644 index 00000000..5e3206e2 --- /dev/null +++ b/examples/python3/actuators/step7.py @@ -0,0 +1,186 @@ +# -*- coding: utf-8 -*- +""" + Scene robot ISIR. +""" +__authors__ = "Yinoussa" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "July, 20 2023" + +from useful.header import addHeader, addSolverNode +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from cable import PullingCable +from splib3.loaders import loadPointListFromFile + +import os +from splib3.numerics.quat import Quat + +path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' + +""" @info +Comme tu l'aura compris notre prototype est composé d'une colonne centrale (fils de fer tressés avec une gaine) + et de 13 disques en iglidur. + + -La colonne mesure 65.5 cm pour un diamètre de 6.2mm + +# -Les disques ont un diamètres de 5.2cm, une épaisseur de 2mm et une masse de 6.35g +# +# -Les disques sur la colonne sont espacés d'environ 4.7cm +# +# -Concernant les trous des disques, il y en a 3 sortes : +# +# les trous intérieurs sont au nombre de 3, ont un diamètre de 2mm et sont placés à environ 6mm du centre +# les trous intermédiaires sont au nombre de 3, ont un diamètre de 2.5mm et sont placés à environ 2cm du centre +# les trous extérieurs sont au nombre de 12, ont un diamètre de 1mm et sont placés à environ 2.3cm du centre +# -Enfin concernant le routage des câbles : +# +# Le manipulateur est constitué de 3 sections, chaque section est composé de 3 fils (disposés à 120° les uns des autres) +# Les câbles sont routés de manière parallèle +# La première section (celle du haut) ainsi que la deuxième (intermédiaire) sont constituées de 4 disques et la +# troisième (celle du bas) de 5 disques +# Les câbles ne sont déployés que sur leur propre section. Par exemple, les câbles qui fonctionnent sur la section 3 +# passent par les trous extérieurs sur cette section et par les trous intérieurs sur les sections 1 et 2. +# [@info] ================ Unit: N, cm, g, Pa ================ +""" + +# @todo +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=65.5, showFramesObject=1, + nbSection=5, nbFrames=26, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=5., youngModulus=1.0e8, poissonRatio=0.38, beamRadius=6.2e-1 / 2., + beamLength=65.5) +simuParams = SimulationParameters(rayleighStiffness=1.e-3) +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + + +def createIntermediateNode(parent, rigidCentral=None, baseName="rigidState", rigidIndex=2): + """ The intermediateRigid construction """ + if rigidCentral is None: + rigidCentral = [0, 0., 0, 0, 0, 0, 1] + q0 = Quat() + q1 = Quat() + q2 = Quat() + + interChildPos = [[0, 1.7, 1., q0[0], q0[1], q0[2], q0[3]], + [0, -1.7, 1., q1[0], q1[1], q1[2], q1[3]], + [0., 0., -2., q2[0], q2[1], q2[2], q2[3]]] + intermediateRigid = parent.addChild('intermediateRigid') + intermediateRigid.addObject('MechanicalObject', name=baseName, template='Rigid3d', + position=rigidCentral, showObject=True, showObjectScale=0.4) + # @TODO add the mass of the disk + intermediateRigid.addObject('RigidMapping', name="interRigidMap", index=rigidIndex) + + """Create intermediate kids""" + interRigidChild = intermediateRigid.addChild('interRigidChild') + interRigidChild.addObject('MechanicalObject', name="interRigidChildMo", template='Rigid3d', + position=interChildPos, showObject=True, showObjectScale=0.4) + interRigidChild.addObject('RigidMapping', name="interRigidMap") + + """ Add disk to the scene, actually this disk is only use for the visualisation """ + loadDisk(intermediateRigid) + + return intermediateRigid + + +def loadDisk(parentNode): + #### MAPPING of the disks (here some torus) #### ########### + diskMapping = parentNode.addChild("diskMapping") + diskMapping.addObject("MeshOBJLoader", name="diskLoader", filename=f'{path}disqueBlender2.obj') + diskMapping.addObject("OglModel", name="Visual", src="@diskLoader", color="1.0 0.5 0.25 1.0") + diskMapping.addObject('RigidMapping', name="diskMap") + + +def create_cable_points(): + """ + This function creates cable points based on the given parameters. + + Returns: + cable_base_state (list): A list of base states for the cable. + cable_3d_state (list): A list of 3D positions for the cable. + """ + num_segments = 14 + norm_length = geoParams.beamLength / num_segments + + cable_base_state = [] + cable_3d_state = [] + + for z in [1.7, -1.7, -2]: + base_state = [] + pos_3d = [] + + for i in range(num_segments + 1): + x = i * norm_length + if z == -2: + base_state.append([x, 0., z, 0., 0., 0., 1.]) + # pos_3d.append([x, 0., z]) + pos_3d.append([x, 0., 0]) + else: + base_state.append([x, z, 1., 0., 0., 0., 1.]) + # pos_3d.append([x, z, 1.]) + pos_3d.append([x, 0, 0]) + + cable_base_state.append(base_state) + cable_3d_state.append(pos_3d) + + return cable_base_state, cable_3d_state + + +def createRigidDisk(parentNode): # @todo add a parameter for the number of disk + """ Create the rigid disk nodes """ + for i in range(1, 14): + """ Create the rigid disk nodes """ + createIntermediateNode(parentNode, rigidCentral=[0, 0., 0, 0, 0, 0, 1], + baseName=f"rigidState{i}", rigidIndex=i * 2) + + +rotation = [0.0, 0.0, 0.0] +translation = [0.0, 0.0, 0.0] +pullPointLocation = [0.0, 0.0, 0.0] +youngModulus = 18000 +valueType = 'position' + + +def createScene(rootNode): + addHeader(rootNode) + rootNode.gravity = [0., -9.81, 0.] + + stemNode = addSolverNode(rootNode, name="stemNode") + cosserat = stemNode.addChild(CosseratBase(parent=stemNode, params=Params)) + # create the rigid disk node + createRigidDisk(cosserat.cosseratFrame) + + cableBaseState, cable3DState = create_cable_points() + + cable1Node = stemNode.addChild("cable1Node") + cable1Node.addObject('MechanicalObject', name="cable1Pos", template='Rigid3d', position=cableBaseState[0], + showObject=True, showObjectScale=2) + PullingCable(cable1Node, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[0], + valueType=valueType) + + cable2Node = stemNode.addChild("cable2Node") + cable2Node.addObject('MechanicalObject', name="cable2Pos", template='Rigid3d', position=cableBaseState[1], + showObject=True, showObjectScale=2) + PullingCable(cable2Node, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[1], + valueType=valueType) + + cable3Node = stemNode.addChild("cable3Node") + cable3Node.addObject('MechanicalObject', name="cable3Pos", template='Rigid3d', position=cableBaseState[2], + showObject=True, showObjectScale=2) + PullingCable(cable3Node, "PullingCable", + pullPointLocation=pullPointLocation, + rotation=rotation, + translation=translation, + cableGeometry=cable3DState[2], + valueType=valueType) + + return diff --git a/examples/python3/cosserat/__init__.py b/examples/python3/cosserat/__init__.py index 2d711a6d..c52b61c5 100644 --- a/examples/python3/cosserat/__init__.py +++ b/examples/python3/cosserat/__init__.py @@ -11,11 +11,11 @@ Contents of the library ********************** -.. autosummary:: - :toctree: _autosummary +. auto_summary:: + :toc_tree: _auto_summary cosserat.cosseratObject """ -__all__ = ["utils","cosseratObject", "nonLinearCosserat", "createFemRegularGrid", "actuators"] +__all__ = ["CosseratBase", "usefulFunctions", "cosseratObject", "nonLinearCosserat", "createFemRegularGrid"] diff --git a/examples/python3/tutorial/tuto-2.py b/examples/python3/tutorial/tuto-2.py new file mode 100644 index 00000000..fae99523 --- /dev/null +++ b/examples/python3/tutorial/tuto-2.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +__author__ = 'Younes' +__copyright__ = '(c) {year}, Inria, {project_name}' +__credits__ = ['{credit_list}'] +__license__ = '{license}' +__version__ = '{mayor}.{minor}.{rel}' +__maintainer__ = '{maintainer}' +__email__ = 'yinoussa.adagolodjo-AT-inria.fr' +__status__ = '{dev_status}' +__date__ = "{Date}" + +""" +{Description} +{License_info} +""" +import PySimpleGUI as sg + +sg.theme('DarkAmber') # Add a touch of color +# All the stuff inside your window. +layout = [[sg.Text('Some text on Row 1')], + [sg.Text('Enter something on Row 2'), sg.InputText()], + [sg.Button('Ok'), sg.Button('Cancel')]] + +# Create the Window +window = sg.Window('Window Title', layout) +# Event Loop to process "events" and get the "values" of the inputs +while True: + event, values = window.read() + if event == sg.WIN_CLOSED or event == 'Cancel': # if user closes window or clicks cancel + break + print('You entered ', values[0]) + +window.close() diff --git a/examples/python3/tutorial/tuto.py b/examples/python3/tutorial/tuto.py new file mode 100644 index 00000000..a8278d2b --- /dev/null +++ b/examples/python3/tutorial/tuto.py @@ -0,0 +1,12 @@ +import sys +from PyQt5.QtWidgets import QApplication, QWidget + +app = QApplication(sys.argv) + +root = QWidget() + +root.resize(250, 250) +root.setWindowTitle("Hello world!") +root.show() + +sys.exit(app.exec_()) From 76d2c1e6b1d8e599a54a76221e8882424f861d08 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 6 Oct 2023 16:15:01 +0200 Subject: [PATCH 12/71] update readme --- README.md | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index ac54cfe3..ba3ba66a 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,9 @@ # Cosserat -An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. We also welcome contributions from the community to enhance and expand the capabilities of this plugin. + +>> [!Cosserat-Plugin]+ +>> An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. +>> We also welcome contributions from the community to enhance and expand the capabilities of this plugin. + ### Description related to Soft-body modeling The Cosserat model has found applications in the realm of continuum robotics, particularly for simulating the deformation of robot bodies with geometries and mechanical properties akin to rods. This model aligns closely with the dynamic deformation patterns exhibited by soft manipulators, as it can effectively replicate nonlinear deformations encompassing bending, torsion, extension, and shearing. From 821e9545bbac0fba79f118818d4e5f577467be4c Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 6 Oct 2023 16:17:29 +0200 Subject: [PATCH 13/71] update readme --- README.md | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index ba3ba66a..dfce8ba1 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,7 @@ # Cosserat ->> [!Cosserat-Plugin]+ ->> An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. ->> We also welcome contributions from the community to enhance and expand the capabilities of this plugin. +> An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. +> We also welcome contributions from the community to enhance and expand the capabilities of this plugin. ### Description related to Soft-body modeling From 0fe1e0368c8fa6ab2697305edce487d34f6918dd Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 10 Oct 2023 14:56:58 +0200 Subject: [PATCH 14/71] update the README file --- README.md | 35 +++++++++++++++++++---------- examples/python3/useful/geometry.py | 1 + 2 files changed, 24 insertions(+), 12 deletions(-) diff --git a/README.md b/README.md index dfce8ba1..b649e8ea 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,16 @@ # Cosserat +<div class="highlight-content"> +<strong>Overview</strong> -> An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. -> We also welcome contributions from the community to enhance and expand the capabilities of this plugin. +An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. +Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. +In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to +construct scenes using Python or XML, or you can take it a step further by developing new C++ components. +We also welcome contributions from the community to enhance and expand the capabilities of this plugin. -### Description related to Soft-body modeling +</div> + +## Description related to Soft-body modeling The Cosserat model has found applications in the realm of continuum robotics, particularly for simulating the deformation of robot bodies with geometries and mechanical properties akin to rods. This model aligns closely with the dynamic deformation patterns exhibited by soft manipulators, as it can effectively replicate nonlinear deformations encompassing bending, torsion, extension, and shearing. @@ -11,16 +18,20 @@ One distinctive feature of Cosserat's theory, within the domain of continuous me When modeling linear structures, this framework enables the creation of a structure closely resembling articulated solids, consisting of a series of rigid bodies whose relative positions are defined by their strain states. Consequently, this model serves as a versatile tool for modeling and controlling a variety of systems, including concentric tube robots, continuum robots driven by cables, or pneumatic soft robots with constant cross-sections. -### Theory +## Theory +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et. -### Numerics +## Numerics +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. -### Some use cases +## Some use cases +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. +### Modeling and control +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. -## Modeling and control - -### Direct control +#### Direct control +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. #### Modeling cochlear implant using Discret Cosserat Model (DCM) @@ -28,12 +39,12 @@ When modeling linear structures, this framework enables the creation of a struct |---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------| | <img src="/doc/images/multiSectionWithColorMap1.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap2.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap3.png" width="300" title="DCM as an implant"> | -### DCM for cable modeling to control deformable robots: +## DCM for cable modeling to control deformable robots: | Direct simulation of a soft gripper | The study of the model convergence | |------------------------------------------------------------------------------------------| --------------------------------------------------------------------------------------------| | <img src="/doc/images/cosseratgripper_2.png" width="400" title="DCM for cable modeling"> | <img src="/doc/images/tenCossseratSections.png" width="400" title="DCM for cable modeling ">| -### Some use cases +<strong> Actuation </strong> | <img src="/doc/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="doc/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/doc/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | | ------------- |:-------------:| -----:| @@ -44,7 +55,7 @@ When modeling linear structures, this framework enables the creation of a struct | ------------- |:-------------:| -------------:| | DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| - +<strong> Tripode using bending lab sensors </strong> Format: ![Alt Text] diff --git a/examples/python3/useful/geometry.py b/examples/python3/useful/geometry.py index 54778369..cb4b5929 100644 --- a/examples/python3/useful/geometry.py +++ b/examples/python3/useful/geometry.py @@ -79,6 +79,7 @@ def generate_edge_list(cable3DPos: List[List[float]]) -> List[int]: number_of_points = len(cable3DPos) return [i for i in range(number_of_points - 1) for _ in range(2)] + class CosseratGeometry: def __init__(self, beamGeoParams): # Data validation checks for beamGeoParams From 7f448f26e1ade177cc415fe8b6f64957a3e32dc6 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 20 Oct 2023 17:53:17 +0200 Subject: [PATCH 15/71] updating the Readme file to much markdown guidlines --- README.md | 165 +++++++++++++++++++++++++++++------------------------- 1 file changed, 88 insertions(+), 77 deletions(-) diff --git a/README.md b/README.md index b649e8ea..efcb05b0 100644 --- a/README.md +++ b/README.md @@ -1,77 +1,88 @@ -# Cosserat -<div class="highlight-content"> -<strong>Overview</strong> - -An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. -Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. -In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to -construct scenes using Python or XML, or you can take it a step further by developing new C++ components. -We also welcome contributions from the community to enhance and expand the capabilities of this plugin. - -</div> - -## Description related to Soft-body modeling - -The Cosserat model has found applications in the realm of continuum robotics, particularly for simulating the deformation of robot bodies with geometries and mechanical properties akin to rods. This model aligns closely with the dynamic deformation patterns exhibited by soft manipulators, as it can effectively replicate nonlinear deformations encompassing bending, torsion, extension, and shearing. - -One distinctive feature of Cosserat's theory, within the domain of continuous media mechanics, lies in its conceptualization: it views each material point of an object as a rigid body with six degrees of freedom (three translations and three rotations). In contrast, many other models in continuum media mechanics tend to treat material points as particles with only three translation degrees of freedom. - -When modeling linear structures, this framework enables the creation of a structure closely resembling articulated solids, consisting of a series of rigid bodies whose relative positions are defined by their strain states. Consequently, this model serves as a versatile tool for modeling and controlling a variety of systems, including concentric tube robots, continuum robots driven by cables, or pneumatic soft robots with constant cross-sections. - -## Theory -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et. - -## Numerics -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. - -## Some use cases -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. - -### Modeling and control -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. - -#### Direct control -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. - -#### Modeling cochlear implant using Discret Cosserat Model (DCM) - -| View 1 | View 2 | View 3 | -|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------| -| <img src="/doc/images/multiSectionWithColorMap1.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap2.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap3.png" width="300" title="DCM as an implant"> | - -## DCM for cable modeling to control deformable robots: -| Direct simulation of a soft gripper | The study of the model convergence | -|------------------------------------------------------------------------------------------| --------------------------------------------------------------------------------------------| -| <img src="/doc/images/cosseratgripper_2.png" width="400" title="DCM for cable modeling"> | <img src="/doc/images/tenCossseratSections.png" width="400" title="DCM for cable modeling ">| - -<strong> Actuation </strong> - -| <img src="/doc/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="doc/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/doc/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | -| ------------- |:-------------:| -----:| -| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| - - -| <img src="/doc/images/example1.gif" width="300" title="PCS_Example1.py "> | <img src="./doc/images/example2.gif" widt="300" title="PCS_Example2.py"> | <img src="./doc/images/example2.gif" width="300" title="PCS_Example3.PCS"> | -| ------------- |:-------------:| -------------:| -| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| - -<strong> Tripode using bending lab sensors </strong> -Format: ![Alt Text] - - -### Inverse Control - - -## Publications -1. Pieces-wise constant Strain PCS: This feature is based on the paper -1.a. __Discrete cosserat approach for soft robot dynamics: A new piece-wise constant strain model with torsion and shears__ [Link to the paper](https://ieeexplore.ieee.org/document/7759808) -1.b. __Coupling numerical deformable models in global and reduced coordinates for the simulation of the direct and the inverse kinematics of Soft Robots__ [Link to the paper](https://ieeexplore.ieee.org/abstract/document/9362217). -The link to download the Pdf of the Paper: __https://hal.archives-ouvertes.fr/hal-03192168/document__ - -<div align="center"> - <a href="https://www.youtube.com/watch?v=qwzKAgw31pU"><img src="https://img.youtube.com/vi/qwzKAgw31pU/0.jpg" alt="link to youtube"></a> -</div> - -2. Pieces-wise Nonconstant Strain: -3. DCM with Plastic model - +# Cosserat +<div class="highlight-content"> +<strong>Overview</strong> + +An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. +Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. +In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to +construct scenes using Python or XML, or you can take it a step further by developing new C++ components. +We also welcome contributions from the community to enhance and expand the capabilities of this plugin. + +</div> + +## Description related to Soft-body modeling + +The Cosserat model has found applications in the realm of continuum robotics, particularly for simulating the deformation of robot bodies with geometries and mechanical properties akin to rods. +This model aligns closely with the dynamic deformation patterns exhibited by soft manipulators, as it can effectively replicate nonlinear deformations encompassing bending, torsion, extension, and shearing. + +One distinctive feature of Cosserat's theory, within the domain of continuous media mechanics, lies in its conceptualization: +it views each material point of an object as a rigid body with six degrees of freedom (three translations and three rotations). +In contrast, many other models in continuum media mechanics tend to treat material points as particles with only three translation degrees of freedom. + +When modeling linear structures, this framework enables the creation of a structure closely resembling articulated solids, consisting of a series of rigid bodies whose relative positions are defined by their strain states. +Consequently, this model serves as a versatile tool for modeling and controlling a variety of systems, including concentric tube robots, continuum robots driven by cables, or pneumatic soft robots with constant cross-sections. + +## Theory +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et. + +## Numerics +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. + +## Some use cases +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. + +### Modeling and control +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. + +#### Direct control +Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. + +#### Modeling cochlear implant using Discret Cosserat Model (DCM) + + +| View 1 | View 2 | View 3 | +|----------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------|----------------------------------------------------------------------------------------------| +| ![333](docs/images/multiSectionWithColorMap1.png) | ![333](docs/images/multiSectionWithColorMap2.png) | ![333](docs/images/multiSectionWithColorMap3.png) | + + +## Utilizing the Discrete Cosserat Model for Cable Modeling in Deformable Robot Control: + + +| Direct simulation of a soft gripper | The study of the model convergence | +|-------------------------------------------------------------------------------------------|-----------------------------------------------------------------------------------------------| +| ![400](docs/images/cosseratgripper_2.png) | ![400](docs/images/tenCossseratSections.png) | + + +--- + +<strong> Actuation </strong> + +| <img src="/docs/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="docs/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/docs/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | +|---------------------------------------------------------------------------------------------------------------|:----------------------------------------------------------------------------------------------------------------:|--------------------------------------------------------------------------------------------------------:| +| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =``` | Beam actuation using a cable ```d =``` | + + +| <img src="/docs/images/example1.gif" width="300" title="PCS_Example1.py "> | <img src="./docs/images/example2.gif" widt="300" title="PCS_Example2.py"> | <img src="./docs/images/example2.gif" width="300" title="PCS_Example3.PCS"> | +|----------------------------------------------------------------------------|:-------------------------------------------------------------------------:|----------------------------------------------------------------------------:| +| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =``` | Beam actuation using a cable ```d =``` | + +<strong> Tripod using bending lab sensors </strong> +Format: ![Alt Text] + + +### Inverse Control + + +## Publications +1. Pieces-wise constant Strain PCS: This feature is based on the paper +- __Discrete cosserat approach for soft robot dynamics: A new piece-wise constant strain model with torsion and shears__ [Link to the paper](https://ieeexplore.ieee.org/document/7759808) +- __Coupling numerical deformable models in global and reduced coordinates for the simulation of the direct and the inverse kinematics of Soft Robots__ [Link to the paper](https://ieeexplore.ieee.org/abstract/document/9362217). +The link to download the Pdf of the Paper: __https://hal.archives-ouvertes.fr/hal-03192168/document__ + +<div align="center"> + <a href="https://www.youtube.com/watch?v=qwzKAgw31pU"><img src="https://img.youtube.com/vi/qwzKAgw31pU/0.jpg" alt="link to youtube"></a> +</div> + +2. Pieces-wise Non-constant Strain: +3. DCM with Plastic model + From ff5960c3345199e12839adcd502e9cc8a9b5b313 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Wed, 25 Oct 2023 16:33:38 +0200 Subject: [PATCH 16/71] change folder doc name to docs --- README.md | 2 +- .../images/actuationConstraint_1.png | Bin .../images/actuationConstraint_2.png | Bin .../images/circleActuationConstraint.png | Bin {doc => docs}/images/cosseratgripper_2.png | Bin {doc => docs}/images/example1.gif | Bin {doc => docs}/images/example2.gif | Bin .../images/multiSectionWithColorMap1.png | Bin .../images/multiSectionWithColorMap2.png | Bin .../images/multiSectionWithColorMap3.png | Bin {doc => docs}/images/tenCossseratSections.png | Bin {doc => docs}/images/tenSections.png | Bin examples/python3/tutorial/tutorial.md | 105 ++++++++++++++++++ 13 files changed, 106 insertions(+), 1 deletion(-) rename {doc => docs}/images/actuationConstraint_1.png (100%) rename {doc => docs}/images/actuationConstraint_2.png (100%) rename {doc => docs}/images/circleActuationConstraint.png (100%) rename {doc => docs}/images/cosseratgripper_2.png (100%) rename {doc => docs}/images/example1.gif (100%) rename {doc => docs}/images/example2.gif (100%) rename {doc => docs}/images/multiSectionWithColorMap1.png (100%) rename {doc => docs}/images/multiSectionWithColorMap2.png (100%) rename {doc => docs}/images/multiSectionWithColorMap3.png (100%) rename {doc => docs}/images/tenCossseratSections.png (100%) rename {doc => docs}/images/tenSections.png (100%) create mode 100644 examples/python3/tutorial/tutorial.md diff --git a/README.md b/README.md index efcb05b0..63725184 100644 --- a/README.md +++ b/README.md @@ -50,7 +50,7 @@ Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor i | Direct simulation of a soft gripper | The study of the model convergence | |-------------------------------------------------------------------------------------------|-----------------------------------------------------------------------------------------------| -| ![400](docs/images/cosseratgripper_2.png) | ![400](docs/images/tenCossseratSections.png) | +| ![400](docs/images/cosseratgripper_2.png) | ![400](../../../../Templater/images/tenCossseratSections.png.md) | --- diff --git a/doc/images/actuationConstraint_1.png b/docs/images/actuationConstraint_1.png similarity index 100% rename from doc/images/actuationConstraint_1.png rename to docs/images/actuationConstraint_1.png diff --git a/doc/images/actuationConstraint_2.png b/docs/images/actuationConstraint_2.png similarity index 100% rename from doc/images/actuationConstraint_2.png rename to docs/images/actuationConstraint_2.png diff --git a/doc/images/circleActuationConstraint.png b/docs/images/circleActuationConstraint.png similarity index 100% rename from doc/images/circleActuationConstraint.png rename to docs/images/circleActuationConstraint.png diff --git a/doc/images/cosseratgripper_2.png b/docs/images/cosseratgripper_2.png similarity index 100% rename from doc/images/cosseratgripper_2.png rename to docs/images/cosseratgripper_2.png diff --git a/doc/images/example1.gif b/docs/images/example1.gif similarity index 100% rename from doc/images/example1.gif rename to docs/images/example1.gif diff --git a/doc/images/example2.gif b/docs/images/example2.gif similarity index 100% rename from doc/images/example2.gif rename to docs/images/example2.gif diff --git a/doc/images/multiSectionWithColorMap1.png b/docs/images/multiSectionWithColorMap1.png similarity index 100% rename from doc/images/multiSectionWithColorMap1.png rename to docs/images/multiSectionWithColorMap1.png diff --git a/doc/images/multiSectionWithColorMap2.png b/docs/images/multiSectionWithColorMap2.png similarity index 100% rename from doc/images/multiSectionWithColorMap2.png rename to docs/images/multiSectionWithColorMap2.png diff --git a/doc/images/multiSectionWithColorMap3.png b/docs/images/multiSectionWithColorMap3.png similarity index 100% rename from doc/images/multiSectionWithColorMap3.png rename to docs/images/multiSectionWithColorMap3.png diff --git a/doc/images/tenCossseratSections.png b/docs/images/tenCossseratSections.png similarity index 100% rename from doc/images/tenCossseratSections.png rename to docs/images/tenCossseratSections.png diff --git a/doc/images/tenSections.png b/docs/images/tenSections.png similarity index 100% rename from doc/images/tenSections.png rename to docs/images/tenSections.png diff --git a/examples/python3/tutorial/tutorial.md b/examples/python3/tutorial/tutorial.md new file mode 100644 index 00000000..80b5897c --- /dev/null +++ b/examples/python3/tutorial/tutorial.md @@ -0,0 +1,105 @@ + +### Mathematical Description of Cosserat Rods + + +### Reference Frames + +### Conservation of Momentum + +### Linear Elasticity + + +## Numerics + +### Spatial Discretization + +### Time Discretization + +### Reduce to Global State + +### Global to Reduce State + +### Boundary conditions and interaction forces + + + + + +A step-by-step tutorial for understanding how to model a 1D object using the Cosserat plugin within the SOFA framework. + +# Modeling 1D Objects with Cosserat Theory in SOFA** + + **Introduction:** +In this tutorial, we will learn how to create a 1D object model using Cosserat Theory within the SOFA framework. This model is useful for simulating various physical systems, such as beams or rods. We'll cover the essential components and parameters needed to set up the model. + + **Prerequisites:** +Before you begin, make sure you have SOFA installed. If not, follow the installation instructions on the SOFA website. + +### **Section 1: Setting up the Environment** +1.1. Import necessary libraries: + - Import the required libraries, including SOFA and custom utility modules. + +1.2. Define the class: + - Begin by defining the `CosseratBase` class, which represents our 1D object model. + +### **Section 2: Class Initialization** +2.1. Constructor: + - Create the `__init__` method to initialize the class. + - Define the parameters and attributes used in the class, such as mass, geometry, and nodes. + +### **Section 3: Beam Physics Parameters** +3.1. Mass and Radius: + - Set the mass and radius of the beam using parameters. + +3.2. Use Inertia Parameters: + - Choose whether to use inertia parameters and set them accordingly. + +### **Section 4: Adding Rigid Base Node** +4.1. Create a Rigid Base Node: + - Add a rigid base node to represent the base of the 1D object. + - Specify its position and rotation. + +4.2. Attach the Base: + - Choose whether to attach the base to a link or allow it to follow arm position. + - Add a rest shape force field if needed. + +### **Section 5: Cosserat Coordinate Node** +5.1. Create a Cosserat Coordinate Node: + - Add a node to represent the Cosserat coordinates. + - Specify the parameters needed for the beam physics. + +### **Section 6: Cosserat Frame** +6.1. Create a Cosserat Frame Node: + - Add a node to represent the Cosserat frame. + - Include mechanical objects, mappings, and other necessary components. + +### **Section 7: Collision Models** +7.1. Add Collision Model: + - Implement collision models for interactions with other objects, if required. + +7.2. Sliding Points (Optional): + - Include sliding points or containers for specific scenarios. + +### **Section 8: Setting up the Scene** +8.1. Configure the Scene: + - Initialize the SOFA scene with necessary parameters and components. + - Define gravity, time step, and solver settings. + +8.2. Create the Object: + - Instantiate the `CosseratBase` class within the scene. + +**Conclusion:** +In this tutorial, we've learned how to create a 1D object model using Cosserat Theory in SOFA. We covered class initialization, beam physics parameters, rigid base nodes, Cosserat coordinates, collision models, and setting up the scene. With this knowledge, you can create and simulate various 1D objects for your specific applications. + +**Note:** This tutorial provides a high-level overview of the class structure and its components. For more detailed code explanations and demonstrations, please refer to the actual Python class code and comments. + + +## Applications + +### Build a simple cosserat Scene + +### Cosserat as cable for finger actuation + +### Cosserat as + +### Cosserat as From f4d8dd31c5785cebd7350b57f4dea9759760f530 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 7 Nov 2023 19:01:23 +0100 Subject: [PATCH 17/71] creating tutoriel for cosserat trainning --- README.md | 20 +- docs/images/CosseratMapping.png | Bin 0 -> 137874 bytes docs/images/PCS.png | Bin 0 -> 9582 bytes docs/images/Untitled.png | Bin 0 -> 6025 bytes docs/images/exemple_curv_abs_input.png | Bin 0 -> 36177 bytes docs/images/exemple_rigid_translation.png | Bin 0 -> 17538 bytes docs/images/frame1.png | Bin 0 -> 22983 bytes docs/images/noeud_curv.png | Bin 0 -> 22977 bytes docs/images/position_90degres.png | Bin 0 -> 25582 bytes docs/images/rigidbase.png | Bin 0 -> 6501 bytes docs/testScene/step1.py | 152 ++++++++++++ docs/testScene/tuto_1.py | 69 ++++++ docs/testScene/tuto_2.py | 100 ++++++++ docs/testScene/tuto_3.py | 34 +++ docs/testScene/tuto_4.py | 125 ++++++++++ docs/text/Advanced Topics and Future Work.md | 48 ++++ docs/text/Background Concepts.md | 71 ++++++ docs/text/Brouillons.md | 40 +++ docs/text/Complement.md | 82 +++++++ docs/text/Direct Simulation.md | 51 ++++ docs/text/Introduction.md | 62 +++++ docs/text/Inverse Simulation.md | 46 ++++ ...el Convergence and Sensitivity Analysis.md | 51 ++++ docs/text/Numerics.md | 10 + docs/text/Setting up the Environment.md | 232 ++++++++++++++++++ docs/text/Soft_robot_intro.md | 69 ++++++ docs/text/Theory.md | 40 +++ docs/text/cosserat_python_scene.md | 137 +++++++++++ docs/text/cosserat_tutorial.md | 1 + docs/text/tutorial.md | 104 ++++++++ examples/python3/__init__.py | 2 +- examples/python3/tutorial/tutorial.md | 27 +- examples/python3/useful/header.py | 5 +- .../CosseratNeedleSlidingConstraint.h | 2 +- .../constraint/QPSlidingConstraint.inl | 4 +- src/Cosserat/engine/PointsManager.h | 4 +- src/Cosserat/engine/PointsManager.inl | 3 +- .../forcefield/BeamHookeLawForceField.inl | 74 ++++-- src/Cosserat/mapping/BaseCosserat.inl | 2 +- .../mapping/DiscreteCosseratMapping.inl | 14 +- 40 files changed, 1602 insertions(+), 79 deletions(-) create mode 100644 docs/images/CosseratMapping.png create mode 100644 docs/images/PCS.png create mode 100644 docs/images/Untitled.png create mode 100644 docs/images/exemple_curv_abs_input.png create mode 100644 docs/images/exemple_rigid_translation.png create mode 100644 docs/images/frame1.png create mode 100644 docs/images/noeud_curv.png create mode 100644 docs/images/position_90degres.png create mode 100644 docs/images/rigidbase.png create mode 100644 docs/testScene/step1.py create mode 100644 docs/testScene/tuto_1.py create mode 100644 docs/testScene/tuto_2.py create mode 100644 docs/testScene/tuto_3.py create mode 100644 docs/testScene/tuto_4.py create mode 100644 docs/text/Advanced Topics and Future Work.md create mode 100644 docs/text/Background Concepts.md create mode 100644 docs/text/Brouillons.md create mode 100644 docs/text/Complement.md create mode 100644 docs/text/Direct Simulation.md create mode 100644 docs/text/Introduction.md create mode 100644 docs/text/Inverse Simulation.md create mode 100644 docs/text/Model Convergence and Sensitivity Analysis.md create mode 100644 docs/text/Numerics.md create mode 100644 docs/text/Setting up the Environment.md create mode 100644 docs/text/Soft_robot_intro.md create mode 100644 docs/text/Theory.md create mode 100644 docs/text/cosserat_python_scene.md create mode 120000 docs/text/cosserat_tutorial.md create mode 100644 docs/text/tutorial.md diff --git a/README.md b/README.md index 63725184..ee615b6f 100644 --- a/README.md +++ b/README.md @@ -3,9 +3,8 @@ <strong>Overview</strong> An open-source plugin, designed to be compatible with the Sofa framework, facilitates the simulation of 1D objects. -Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. -In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to -construct scenes using Python or XML, or you can take it a step further by developing new C++ components. +Specifically, it caters to the modeling of both rigid and flexible 1D entities, like rods, wires or needles, using the Cosserat beam theory. +In this context, we have outlined a range of potential applications for this plugin. If you wish to explore its functionality, you have the flexibility to construct scenes using Python or XML, or you can take it a step further by developing new C++ components. We also welcome contributions from the community to enhance and expand the capabilities of this plugin. </div> @@ -15,26 +14,25 @@ We also welcome contributions from the community to enhance and expand the capab The Cosserat model has found applications in the realm of continuum robotics, particularly for simulating the deformation of robot bodies with geometries and mechanical properties akin to rods. This model aligns closely with the dynamic deformation patterns exhibited by soft manipulators, as it can effectively replicate nonlinear deformations encompassing bending, torsion, extension, and shearing. -One distinctive feature of Cosserat's theory, within the domain of continuous media mechanics, lies in its conceptualization: -it views each material point of an object as a rigid body with six degrees of freedom (three translations and three rotations). +One distinctive feature of Cosserat's theory, within the domain of continuous media mechanics, lies in its conceptualization: +it views each material point of an object as a rigid body with six degrees of freedom (three translations and three rotations). In contrast, many other models in continuum media mechanics tend to treat material points as particles with only three translation degrees of freedom. When modeling linear structures, this framework enables the creation of a structure closely resembling articulated solids, consisting of a series of rigid bodies whose relative positions are defined by their strain states. Consequently, this model serves as a versatile tool for modeling and controlling a variety of systems, including concentric tube robots, continuum robots driven by cables, or pneumatic soft robots with constant cross-sections. -## Theory -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et. - -## Numerics -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. +Go into theorotical part of the plugin [Theory](docs/text/Theory.md) +Follow the tutorial : [cosserat_tutorial](docs/text/cosserat_tutorial.md) ## Some use cases -Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. + ### Modeling and control + Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. #### Direct control + Lorem ipsum dolor sit amet, consectetur adipiscing elit, sed do eiusmod tempor incididunt ut labore et dolore magna aliqua. #### Modeling cochlear implant using Discret Cosserat Model (DCM) diff --git a/docs/images/CosseratMapping.png b/docs/images/CosseratMapping.png new file mode 100644 index 0000000000000000000000000000000000000000..547cd2428560fff758040c703b67f9e6443ec27f GIT binary patch literal 137874 zcmeFY1zQ}!wkV3bySuvucL?q}Sa1k|VQ>jBxVt+94}swB?h@P~c!1ypmpj>e-+Rux z_niF)-s$<~>*}htN>*1b????bd2|#K6euVtbVUVOEhs2>GbkvS6eI*lO_X+`F%%S< zqMeM4hN6rNm4*w*#?HYS3Q8d|RUZ+cJxY*gq^0;V5J>^K6Pcz{0lDBkRszd1k|I^X zKmwNR@3A_RDic{rlNnuXLQnR9N_-y!xORJQfQEqqAu7MlW^q6j_`LHx_dMI@El223 zg5LE!7h19`jWPA0pbctI8O0hov7j>2?uczxCIHG$68>{f@^HHH%H<_D)Yy-g{HsTj zhA@|v_oIJKpZ)R00yU-(p(4WtwW$sdWjZjSI#M`O@nIxyLO-7nhicL1q16VWF(B3I zMAk2~=tS}^v?y68r}PAR5kgs!#50Z~NVdZt8@zvZ7%B3DwGfDuWP_FrM{~w99l(_& zgTMUx{CuQ@b{ZgaKq$KM_H%;lVDGXnyta)XHKBjN#f}1W@U{~7#{S?PRY2t7^h37p zE1dOY4M@PHOrDh+edmLsjRV=hBUU#)s?IG|kxn8Fivch`>uR5DnYSloS+xf>I&2wl z2TAdRLyTO0CVkvbX*7K#LpF{*20LFu)cx&9k}1QLn~)aj9QxgwcU`ffnJiVauOT!7 zncug&sc~Gw?@d!9lC&0tEaz#QmDmPWv3U1eBWFI5PL#?HM3UDfGUKE?tV#anOpy)y z_E1}HP!|Cg+sS4suEW^`pgS1)<m6t!#H`d`A3d$T4}x=!*635C*ufrS970>5!3qnl zupbr<NwQMy1f(}`@k#AINoNsO*AAEWbtsf<qF88qYZeX>VzPvwYE8xuE1~Wt&wKA= z3UxSN9{XNcV8IGfq16Py#HnzR??E~HfLuABOY$P2M5$m`B$15yvZ&*A7GmH&;7TFi zqtZ|(U_OO@vkCozbS!~kzo1W;P?E*2<-Hdqk98RQF#*w^Rp&#}_DANQ)bkPDkyGKV z2fYP3PkO^)SwyjN+ympY#C3FGxcw2D14xCmjzNgq&|YXAVLjV%Pdi|l6>t-yD2*G= z8EzF$8<Id-B;i=sw{ZBOU=AW`X>Heo^mn@+2@9y0gRs;RdqbHm$WFat=5+iNXqG-w z?DEO2b&u7pZ<_stCQHkj>r716aP%QN7ma02$xTaK(RF2}9tyek2TrC!{k*2bhrTm* z&>iyrz)1F?TZ^(<%VmS#REubUW$a4$_5gCNoo(G4jmD_3Li(>)qoJZZpq)!T?$q3r z_IE9RTKqJo@lm2v&*ghEIdYkCZKF{P9PSSY>soNSPMFf#v)f6b#?B)i-~CA{e-x*h zaLspzmxsP!4IleGEu8lb3XuZ3$Lqzw_60_qf)z?|zE^)FYF^mbo4Thu8N;_QCQzsb z0i%Y(^CvotBoY$ht|XZPjGY<F?>eL^TjC68n_&1aXgUG-X6#=PvU><>V4u-$18khI z$Y9HQynjGf1sOU0aSJZ{g4uxpixiZACEO<&gN-^s;4HU}ZAyoPEN_tjM~6NtS%-~W zC}~3*oq%G6uNCVccbsUN2s^^P$2J?eE_+5THiEh*7FEDE5A{yw^vBFs&M~>789FzV ztXP6C^dFhq(7sEb{4n{5`x#9v{=@tBA7vjU5V+W5A`L7!GB}5NcWT_&P?ODFYh5aF zD*8!k_3kB1huUgB{3cf$AQnXR3}h8VQ6GBnf)*z<jndy0xnOvP0~2?L-)-k3xdk!z zX8u(FiNk<Xhs=v)9ir67-v{nfyytVr{eT-O%P^Do3pRg<&jQ1lz?s<@)>+_^sW$mO zU|F3eF-CE!SW=5DQl5n_HE}W7BQY+4Be6{pG-_ytS|=hDl%tlGK$yfjDl!^Anm!Ug z3X5kF#XgviBaf|Nqm`!Jq-DrV$h?sP{f%NFk3>PW@IZr5qvC7qeDeI-e7d2bp`Ibw z5Vv8#@VfC^19(Qb$X)$}Ts8kdcJ~Lv9A1NU!)ZfNLv};DoA5>)g|vDZ;cWWM$<gqU z=Mkupc(rQP7#MgfdP;K2aH_mI?ZzbBB<zq|E=(_+D(vIVaeQ;E<#y^O)F!&o+V-vu z(XIOA_JsRp=-1%U{t5fSTDhm*d8D}FmYRgI=@-*)-S6L8USSc2YHXZ{e1~X;^oA7W znxSWUHUsPvEH%t8>ZRJH@(a2O%FLt8Yt3V~srxw?h8iqgGQB7EC&VV~C+=t`<Z9%R z<k^U41b1d51mtLArDH<m_T}1Rt4KNpY>2~24@s)|9QnH}gR%uPRk$+E>t^<f70(rd z6QOAzXvgKxh#$h4KOI|TnF)`(MIXV>fq7l)6?n^6KG*NsbRMW&V_lP7zdHz@^kE|+ zkRq^%en%kB_G(33w_GWzhkpWBF+DraGp1$Ux>C2{(lfTnvht~5!LdSQQODl&gze<r zB5=`<pMZZCXtTz*{A{jV`==3qrK(;G_%t-N$+2+e({9twcq?~n{Dkv_@U({E7H$>} z6D}Oi8Ye4nI&3_Q9!IYBH90+bq<rY8koWlaDVxXU&vl_Ft}#%GmCnZ36AnJYCgnus z;BhhiQu~+_=_Q*b+ajP`S^Ni~$D3d3jvpMo9gQ{|V`nIN9Vhy@zgvE25ox{NuwSqC z`XNRmdf?sQC3@#}i}%^_rek~Xg5>;9r+)U5JctsM=~?6%A0Mk8rv81}-4u4qYpbNo z_8AFW0KR_4c<j8syXCyu+I{m3P?mJ;nF?UEJRL?Eb|inI`oWSw*dkQJ8iAjJePgMi zUt`V1*}`!Tj&P5lvN9U6Y@!tj?~Hz7n`hS{Xp^`>AI|3ucjZGvjYea|w8vb+RL7{s z=q5GCPb8ngnjt*G7h=8oh)2yL{K<OWy^1(}`upK+>@~4~?Rw-#LpKXI_nQ}@G9m+& z6EC;tmdlFat+>Y6)B*nCKtad#;}((2+e`S%ZdEF^h<pv+ZOy)nkQL-IT;j+%98ZQW zH566DJU7-AYJ<e}w8CT_p%U?Z)lY!qZ}U}=MT}FKUgDE<syT~EYD(&gTWOmT%)Ya$ ziW|wD4C$&}{DWYn%anR;)zSl1F+NpW642@<nzY=fp{W?m4#5xP)e_0s2H7jahZjqi z`6$wG_Hbf-lG`lXyOlkax(4cXu=V=3cM(DFQwu+E%Nw(U^Ket^nGaPRjn8h^dpqVk zHXin#W1eAg{1mJ92HdWX2IoXdre=BU^aK5SSA)b28XU6864eu%@kn~mpWs7-cSHs| z3%?X*6*lu~+5Bc-WKF{}%{bz79i14a$EKH<?6bYJZJcb%=`_3T6#6ZceMsZVd)PEt zpQkTe?E~I>CP)2>>O%P3^#i#5Ewq}TgyR$YJJwv&$Di#Z=Okkd<5t#7-I({_ISb!f zFXtzmc>0rcUlziY{0gUvua);TDcv{gn3mwLkLFGWi*>jAo8tmiR8<L;EloUL`*FIT zE0pxa0AgVGIg-V!t9R9lYDPXyv-K`>!pFjcZB^egzNP))Khdvz(_sJBWr%B7-@e%3 zp?I2&9)zCGALih&Zq-z7G516{D6zRr*4kP=RaNDJ>a0AICU2zOl=nJ%SM~^GSYv7O zTjyBWY@{_Gj{Kbe_?TNNk}mKCJt{2EB-zvbne5h8xk!2UU}ItfzdOJbulxDIeyDos zR`%R(?WDcgIsde4^(E$IUsYjlqO{9K(^X&DQ28*>8FAGR*6{A_;BoCXI1SMrgP6h) zobkEk=Hh2!677q8iM&s|HKorF{_m%YmyyHOIT=ocFIG3Byk#_M<PwwOetRlEGlOkk zrYQsueX1Th?jA}}KM>x&o&9-w^*FyRjTR>~5`Gpo6dCrQ=)&_oTHdc2FROB@&gmxc zX}mVPY9w7^G(B&lZn@mE*_=G|$9v&+vVR5konDEwd9s{mZGL}B-|hDB^!6lgBlI}$ zdl`6YrnsOK^<(nCFKEBPe$m{wj2`}@zMfC^JM!1jz3XiLhI)xQ;^*<#*{6!z%>H^m z|L|wO0+5C2o$JbVFQKw2N%#8e*tM>azwg_|(nB@kW=i)vaQklVdHdYC_Lc-i#%175 z!Ew><@S^%mz9Z%VCWewXPu?fifZjkGYv>CL5vUu!7SCT$0m6!YQ`*Rd;@RJ@?$rT) z1UiudP-`+!3VE24XzN7|A^ijvBps~H$BNWYe=dk9ND^(mTPj*VUJS^1i3r}$qCsh~ zLQz@=2g8ygAWArfj&8#J{22J?TaHH~O8Wfkn=JXp9ec0-73g!2KX`Fc<rHFDcv%A! zZB$jESRiF2D0pZbC|F1d8uEjJCV_(gM;QuA37Yi(l(nFl{sjXA1r=@w1@|u)L&*K_ zl>qreu>W<3`2zF5A>hrv!2a(tOv+zSq7Sv6kQ=g-f`Ka(6aoF;KeVD2-37$-fw$8E zxB*mEge^fp4s$Dzg*As4(CIH0l&F_5qzJTjGpF(bIykxtdx_Ef140;5{#(sSL-h|3 zH+wM}fT{+S49LZril2jvgNsHSg^G$w)Wyn1SW8y!U+9o0F`AEVZcf6SoSvSZ9G<)! zAQxLsZXqEdPA(o!9v*fG1iP!Zqno)GyQ3@ZKRfx~{m5FoTDsUdx!Hjnss8qBZUJ(4 z6QiN|JJA2R{y9%;FT4L3$<g&+%YrPB^KT0$HwPEze}(2|XY=2n{cZUt+CSFy&*4P> zb|$Q0=Vk3+AZrJ-c65bIO`M;fOY|SZ{68)KG132o3HT38Ze9WY|BU*dn*I~&->C?z zyVzMnsPvZ>;@qN~|4-e&;6*wA66!w@?w@bvAGMIzB90=;`F~!qILe;c#Re3VB$T48 zl#Unl?_A`L_u3Dy>0|14e0Yk92-HzDszXSMVZ{@8?@MJPQwk<{QdFq<G9r~U6Gswg zWZsV^C@IcRp|8H(wZDGfSUsuioZh_4b3Jc86hA+7J<nUb|LwPU(Q*EHi7YfS83~%2 z3N9o73kyaXqL2T-4?R8DUVS~<Izj(+^M4@z#KwZIz?Ay0`uGnZE;=~b9t>mvJ?p<4 z69Nxi0s1ee^Z)58kFVIRjBiEgAj4AWTHEH|%+M?aiz&(?C90@S7HI^AA4aC^-vC1f z4wRyyg7HZB$in{bsUsQE18AX2h;+Y^b7%Q?OX?Y+qC#Cx^u}k2_-{%5cWt|20Z7Zv zK1JW+|1B78Fa+#>di#(4`ag90zYg&K?2!M9Apf&N{x5?3|7?dagYmmxPC*-t5)X>a z8y;(|q@WJxC|An!->+Bc-7UNE5}TGjuMdaup4Pe||1H-KBo6FJ4l@~(czc*W+YYC6 z%$>x|yMPl|GIni+^gMdTtnMA<Gn*XtVPMfZ`(sZb(>lJs@%CtMG)LRW%hT4|t>X9E zA(FF&YVaS~WZjN88mDpgW-o{C`$0}&1%Or8!+|R)uwlku=GVUy%cY2c1@+na4->ZQ z;!nSM3sxt&hshiR;R&2jIXh~623bFBFB-e5s(%x^j8xCj_^eHSlqgT(T$byRC9)lY zyH4)8&b_b_?+$)@T<Tt5vCTh?TsrrEd$Kgq*H!y(MY!1k&BefrN|?d(djf-j&OhHl z?yS`vb-{d3gPh<Q=JxK_Kh<Xf-4C(tN2S^8-iNt|Q=-=@ppBLZo^dxNTVWXgUD7S5 zHHZ3GpI-&xbt|Bb%OS_|lC&}Lxk(#1@XLv5d#aw{=*zKw_ZWh2Kk4Sr&6`pI>-?iq zEFyO}3jb$k&r$mH7Ea%7)Xi^C^qk(2mhL@n$Up%{u_@sbwyn7CU++0xm_`to<HaAp zg0>`{R;Gnh^qDpgsEd7uh;6;B(f<HkM(Gg~e=C$qnFf;*;Q6cj9cyn`M6>fJ?due@ zQ3oVl&TFgx*)2=&{B7+xC3N^ZEkGJI5L@o&UH4ljsJW``nB^|#P;@x{Qof~yCF?&) zX@;1dAM9qP7eR!AuL;2BjYVM7ip`m_>7!Oj&$Q3x^*V*m@9i{z1+v6_pLMS~_zL%K z;~cz{>vPtcTI0Fp*SrRq#=5%yqxQLS<CW6@$KnScpl3h2fZ)iE42IAEdgcj5?J8!o zps%*sxE0<V2FPb^EiAi0i_!;9Zq#I~s{QOZPUNfw$F&Nw{9jj}zo|E^eqz1b=k#x# z@OXQ<^Q3%Q9v(Xx&3XQ9D{)-`rzY`oGi!ogLH6;Gk+yjY+^$YoLLR~qq@3;Srs}fc zzT^$Fo8vm=94~g8QGGJ2%z3J3>gVoX<<CnPIPL#>{UMR`Q_r6TeN%D{_Z(=X=a+MT z&va98Ymusj!*~>vg4+-`lj5R@r%Cfp6l<CiJCdTFuir&5WsaMO;PJ&5DkI;^!SN>l z^Ugbu=FQI)F}RN%Er^u9KjQuR1>BcRJX>u=cZo5I2rt&1`q5wR1?gNT-z~L3w(d-> z@71VdD83$2vpbnH9G7I<)flT^dvAN!VV=)=$Mw|78U~t|*K}<m{@{ze#G__4m;Yt7 zspw9l_T@iR-FiIeYjxq0t4R>Jp6e^Czs+}m5dvug0pyT=r1y;g725ziG=0oqkMo3= zaUL~U4`SHkTg$)xeA>qJ_ZnJ!51&r~=iu5gCV;n^$uD1zz)oQ7)Z6DPOn45yYexmI z9h`Ve<39{bylRTR9I02Q>}O8<+FU|t<|=)p%0El_c0auH_Im!tvcG-DPYg{;iyEz~ zZ_=3L*z?$V?sp!NB!Ifq=PN}B^4%q^Kk9;1Woxt*5sgMf?+oCovwe6N)3-VKJi$F2 zV^OPH8i&+z=3af`-7UA{uJXRO3^h=hv$KIKsQ8dPtcimxHiq3}%kQpFPYu6Gu>#Y7 zFHv4izqX9cRGaC>tbWb0UDe=~m%Zri`B0*3Bi}a9`?C}3mX=@^P8FB6-Q_9Bza0Q< zT=4apqA!YvvdpB76D+JrW%JwO-Bmm2?^x6CJk}NOVCI(VPGTwedmPNtXt>-^0i;Me zaP~_aeLOB~h&42WQB-NLn4&+75ZM}jNMD{Nist*jK6L)kT@J9PLlp`}{j+{3zO>>0 z_QKnO!1CxuTk~*`?ZZmPhUVmHfqS_4zV5YO?4k$u^?ZmF<W`pB66LdvYWfR9@F$df zn+cpgtb;TWe+n(f(%gO!lrsBk3=~HN_uaZ{`XR1R@9KT-xo=th=$>rh($E9s&>dbL z_{Fq8-w#W8$mzuUytDOtaiYgYt&;eNNmmpLb*9#|?xK9&M4ytv@4I51{->g|C0x1c zq`G@^=EDZ$sGe!(Kc>8)Zrk>AFQxCDO(L*8E+oF9M-O{#!Sb_yaBSUQ|9kGk-*M|D zL1ay~I*PKzD;+OtpeaPwyo${YBYLmS<sHNrySMmTJP#c7dv1D{`A=jdOGN&Yp-iB` zm9Ce6u>*?G_Vb`b#OS=<Hg~sL#*6WHiX|;&@uA-}av`N61&&hnxM<YlTvlmyL3nSw zs=!7AqY$2gJh^*HfA@7f_=fflvh?BF8LHPDZR9hpHb?0Zo(Bjkdr94E$*Y<~B)-qq z1(k@l|E^QsZ##j1f#Q&Ty(yFM*5@_ZT?##X32}2)<(az5TIv|u{v4nv05+xHjqI5c zIXBkq`l(I1A7|BoU85_Ae}$ifR)=2**Ua>6;&a*<SF+ne@?|4Gw(j-uM8s%cPcOH2 z9l`_it_&I9D4|nQnOrTeQk$SW9a`vm<@v-{sf{0oHvd$4BDWDoKt(wYC38QF0r0HR ztB^F#cC#=A7`C1^?>e56hykkj27d(<S37pbr*YG3qxt%r!cllBrhL0+l(dJ{wQtYg z8y5|!M@A^~|5V!Qj&Tse1^ZZ=d+Xkd?**ATEl(|`l&+aXsTM}5`|jYv4{KswQy-4= z#*_d#{U63zfxEIMSjB>w@eN9CyL&-YRjlLq+5*@vQdqQnhKF)3_y-lW?gc8DyXhHO z7GKSf>mUSZx!;LqJ;gXB<&eo5h-ln-nDz(Le=s71i>Wa9=8(<LZ_QmdJppnz4{^IZ zQulA`*^ezIgf_a=f8d`;_Xd60i+ccasstKFE-k`CZxu27p=w{zmmj-iAZ7G@zv^0z zF;IbCn|s5w%;BH-%nJOgob)(In+<(kpJXib6ov$|@AQaV`JFPEc}xf#c;WL$Q?!@W z5X1&2skt`Jv;dAnTVEp{3f-R3Wt^yS(o`{c{AR5c4_Z(cU8ljf^&8dxFDK5`$1&BE zte!O%N+zg$x@f3UY%KJ=uz_xaX%8hHFM3BEw~f_*96`%5ClGM^vZ%URoGpBRUd@9n z`>Ls`&o&lfjD|Mr24ub$z1D8L2NysE@1g@Z0f`pYUSOcAgT3@VsJ`vua+va*j59y$ ztV!x;K{&+~>o;kDo^|7j?}CCMND9<dB%?zf`VS-DECf5lg%B>eH%LmJ#RL)G?zy~U z2tCkB5D95*`=@ZWcJB8xt<v4xJ6c8t!&37Sk(nzr-c5&ZCtS{C9;+?UUiaJK;kmK1 z`3!Iu8-8=D0;#Q>H9at3%-}1ze&qJ7-JR0tpFsna8||{1%fw+lnBWW8^G^(Tq<6ec z+_o(aqB}e0!{nY0XvyMMts>wHdhKW^4)`6R(=pcS-x_KS*y|p9#^#NY6<q&xC2%z& zO%S01_<Drw^${v@v7hN)F2W^lz+{*E3Xe@H6PPJLMBw>+mvWn1mRla0;l<IP?5*b^ z^G5sjgf@IVKtZ(!rG(lMgC(^;zhg~qRey=ZjtDkovU?q5cQx156s+&XPBUE~;UYet z?ab$6ke8jCgs8?4aUuA=K?V{WyN=TD=v#5jjf-7qLs@ig${91NH{XY6=<u0c_gDkA zGn8FOf8m5_DsBg57(?;PJ^lz6*CAHG<+wdcjTXp0M<0LNu9+nt^n90nEF5*;%sls3 zVBL+XgX>f^LNg1HGAal_LPSwp?(P_*o_;q)l<p2K^K!SV_SK8#YsF<;Md3XVDW=P; zvjjq+>}LY6I(#0L>jmh1>i>zdr|rVMa@PTo&!69Fw6y@%H2?IL;L4c|Vbx%TKqR8X zXBL#+mG@Mz)W11e_mc8HI&21+sg9Nkgj0O}YF|&v3U{_>1j^k2;%VL1=f70)Zt2B! zoLGgEdwku93F9eN9-ok~E=u-efPP6s-GWFG$7uGZi@1$B7fr`KOUkE=EjypTTF~{B z2#BQ8CHDG0-gl37Gl+I^2M5U_9UUgYebHdJ*2=LUl;CPf^^J*k{L}IcQ|d+6gnHH! zL}5=AUu?w6Ab=a{H5t=^U2>ORY4Yt?Y6iY)6Fc%RxU)Eu>wJh8y^1gbb^ft>5oVH< z=gUQ;@cN>~lX97E;*n_t(O+2aPB=84A@Wr3tfn8M0#$4C4I=mshtu}ab7SaXjsyk~ zl8J<WW);WQ*inXI`i8$)-EDY!9xyhUa*0vGz#RGTo6cf1!(C4bm{zQ(nS#ARm9CJ7 zW|V5lf9*ptqzNQKI6#=RMrjbJh(jDi)L_Pq{163C-yXs<VjX^dD0(PleU%XY+d&P0 z)WcxTXp{zPt{H76gtGGZ9ppET+cM5pAJZNG?qhNeL`cV7HJY&890+u;n1CPl#W8)~ z-0`o99Q0SKvXI)#>uyf}3PU5y*mq;(OSNbSsFgw4&q?Mh!I-=|!IZ&bY<}VwftX$@ zz6@_K!x+~9(t20>WXT%o8pJDnLOeurw**SrJf}WnM~EhQH}k%Wzu>FwTwsriXFAV9 z2KspDNX=~SC*RdQf$ZZ|gm_JqV9xhLq^-K5MLKG!)>lY-LzXex)Dx>?O03`K1(=jv z(BSEI<0T(exfxe|uO~@|_n29LUCd~-8QlsHtLa8;EzIo$aj>(pk==FPT4{;Xzo<qA zC$|Yhz=L`9uGu%eL?4(w%nJy`vqFwL<vU5Q|7+QBYFf8W8f{*sMTHSbC^XTQv|se0 zjyqi<%W^C>n3qo(+JE1lL*GM%qlUFYnzXO(<d0i*jSF*4)z!Q72ejvbACJV$cS!Hc zip8G`Ho(Ioo7fVLqQkAPe--!spQcEt8(zc`#moeq&cxuW<otVU#insb^;Ndi{z(|{ zY0aY8<p3@#2O*X9iX>grubxmC?@gC+c5re4pXQYjMCdBp7tp60&-(4NnwBTDu7SEc z8K>1nP8;~zszQ4jsJWOtnLXE?!{6Bb?%KE9vw=;S{X8Y#Yf{ilFiADGE#N|NPX{0- z$iW42dK;fzGKUfa9wj8`Z_iY<I+p9Xd9)l6#uubzA4#8fq4cHY)Gm9Is*k(8K&*ci zv6=gNTB6(ZUC&scK*u&ZSUbAvVL5IFqayXM#)A<pzv|*Exib|StHDrTPU2`XCH~|v z>=~#_j-s$$lfZE5o?P>}c+$q|#>AJlT!WBn47sJ&U_=&vkYZ~nz3YZvooQf9=@BBX z#Fkd#)-ft5Dt%3F>(U=mNuA%w4=2yzb2Lz98E3Yt+m64z`T*+->D5qoQowmzxaW8~ z!CL~^?d%X0=M19E`k1ovb@_EU>y->h3s>ev?h{XY$(6*TPXDr07yF~Lg;>}za8>&~ zfb+};5GqYh1Uo}f0|P(Eaw<jWzf>$mIel&eIlL7&Ck{ztyqgQbnBu<(K6shOi@hSZ zTWmFfiwH32eOVx9Hh<U08Xqg;4wr2uA?HnglhU%q?{;OlWB~1<cuVIvF6tg2E#0&| z6a@<ALOP`$^X?KzxvEUqAupBo=>x?$lh`G2cH@Hy8{mnME(8v9TuU|Umj?dY#>d_E z#wsRGz3{Q!tk1u-^v2W-s=8kvc}#qFu8hnlrklsc*kjN=R_z#@M`)r`wryq=&$0`} z0v$vkz0?8a47*D~C=>U2_f=X2-HIFB+~6<h$bBL`FC?xAdXMI0eK}$0xYFtNQ<-Ho z+<*+)(EII?X2rE$0TqcJp{Vz0++N`gyA$xMNI>jvf%Wtmgt?(a4F8+V2`P^iYr?HN zE`oC0E>M^IY=Qc=Pt@E4#4bD^wgGO*n24`WcOF*zo!W!*hMPBSESF2~$PQJv#&V+E zyeXaYrA>Q55w)~i2!7;Yaue1MvCa5HXcPIp2@<RL{Q1S|rIXt}UnI_1V&nn%q{fGd z{4d12mHTN%Q)O$`?|(qF<AXVrE%I{`%5h)UXYOWDy+ysf7~ThnJKrEC06RyUg`dfm zb!seM)uZ0J<yT=eiv2T-xs363JpfRY8JoV@&}(8ITc<vZfF6o&JWKVu%3vSrekS&y z8K?6Kv5p8!zq9qbOm*e}<V`#F=sB7D!-N54d8i+V3INFVxakfpPIE}HN?x<o6-DSu zC?`<k7YFuiblO5B+a_Vi`;DWL=D0tU1UX_NnEO}FDh`DNybwtpYNUuciVf1c4d&9! zy=~>zt>zk~WX(Cy$7-leXnpIq-L;V#-hWXx!Y{M4(wx2<@mx8`ZctQ`YB$4;RU(n= z88Vp9%TCq3y~6?%Zhwr*?(?wVoCxZ^k~gwV{=(x2KDW(rmNPH5DiJNsVCm<}T@GmH z+Ns46NTDW+{lex@_yJkwNgRoraxv9yvN>0MvGN?1mVjki+FP)yZj2>VwbGEV*SHVw zV5^P4GlBml0lWPB9Q_y7fan%6G`m6h?17s-AnA3=1DV&)K(XoF`|X@2QAV3i1JbR^ zCl}4f&H7RI-Y2efa_d$86^>ovK&@rjW?zCaqBy&*o8TrpMW7dL8Y-9)7}_;4QoMR2 zEyTb2v8Yd>$f54p!@;$o%PyqBp-^A(P-N>t%{+O2?7W|$DwWHfQ0|qmRE0fe9yqZz zlG>ND5~|v8lEf0j#u0<Z>Okz*D}u8B4rX<@V1ox<(;OTzZcB|OKO|Ag_f^$@oq|Xz zb+A_fdJB`!oV@0XD)bV7$dV*6TUBI8M7&Hw+QHk^`Jxw*ur#7#pc!8-6#HXn>+sig zMs!*m6k7dpnjZogI90W$Xx^lwvv+qxpxa%_H!t%6Eqai4VT$(<qg(=BsTXJ7Z9`e= z_5(PW2w9IfJ-p6|F6Vm}ij?jA4AP-e?(XLqFa?AkgJU*ym{(y}lXYTr*kbNkFJtDa zL<CCW)Q2J_`<}-M<eKz$uD{RR9Ug$>JZugfo07iQzLc^(gJYO(x9kn$ohAi7-^|GC z9|*bs`Pqe?L;Y!gBxgT@HjXL7|J@+wbc|KiK>i3kkj@>=Zb)9+?XlLd+imhwlbNqJ z<4vGh%g-Rxw1*$!v<<MOZp`Py53Y`Tu2McT>h~tRX<tt;ciiT{9j2>tcz1ryG2trM zo1DyVIhTO$^R1EPKBObPBj$v^ChHe;7&gLut<gjhn;FfFckj(fPIqwg?`6#waYEVO zrafTXZiJ*8%5nIX3wmuY7U@a{+55u;g@TB7xI_;X!nf#Jk)6n)v(pMFp-~la(nGI> zVfZPmf=ldh?4xtDeY4~maPpwJ;h4R%^jf7ibzoNE$^8x0j)x=}2^c;*3$CTmfY)88 zpja@by-DjT7^yd~V6b6Yn^=|zWHm)26Ybk43~RZf9|b?|=WNwHsB=)!&Ve#d_~9xI zNOTZNZF2S0^8BCHwrudJT015_^){m>2%xpNny+HjFsV*7Dic!<PJ^FL^(EOPUk~sY zsjJO#YHaL|7<Z|w+i2mWN$cj>p2qnT8mJT|bd}5(B|{BR2vu@+L_cy)eplXqSu&9% z8i30)FvmN%ZsQ^pfQLJYVyyxwicB#wm`&nLsHdEa2tJzO`I}qhriFvj!I9506!Vr4 zyN<)bz>lQkGV8pdYCSL@R3jp?E5Y_NpMZckXMMm)uMqn9yFV&V*$p)bmfYJhJ2REg zVx!OxR?7aYAxuX+Qo&qmgT^QiE|=&7vaU>|ce~wR684?~KB8~$SdzjJ%uZCMjom-T z9m)UoXA_1~f?F81cKL*CXS0%uv8oRcyRJ5Oy&yDTSxpEE$z+GYCfZHOD?<Av90xCg z_v`WwXXu0T<E87!B3UG5c=ye$ve+o)R`m1(I|4WBtWqb@^$JQEOkWC!|CIB-bRyh3 z;sXV-K-Vb{R6(Du1(Vh^tY@Hmg<%~62z6V7@b9{58Ns-Qk^~uE&5!oGZN-NT<p)g_ zt_xmomjcP9<L=Kno{j|b@Vn7%{3KceM4fxH%7={41bxl@PYw9wUAaMMXm`7AR36+8 zqsUv9NXkASf{m{DLcg%z>c|ViFt-UZ7|e6#D)Qa$O>HZvQC5#yOc}bRuxjSRA3#k0 zXAxKHY<#Y|pbmL4V%PmuG$g>#7p7$w@1eU0%pv!_b5^}8uG<Z_In|f@!1E!!;F~>Y z>UDLhG)<4NI!UVQY+EoWZ32F`@q&#E_)ZR3*FYSz5p<RRz_n|5_PzbA4SpZvD1`O_ zSN$KxPX-$dtyE9g(D$PV>uC1)Bdb(6K{poea&u)45^l?Y?6hELNwx&yT6|`7iL8Ex z+I>E;qebi*G@>1z8(OnkxVV1TJPaqMZ1$4MkYF^sBuGr-I}QcA`RYSPb|}w8*VEZr zN{&B)5qda}3<g|p;k%{->EPArPm##3!bCXGq*x2ig-CAnW)DCIh(@!2PVKuz_Vlty z)pegM12~At0>k}=__|INza%iG1wW@*1bXoZu&!K%dXd?|)_&;436^pcHm6pRfJxhG zVAo~64sseXs4WAkFb&rr0rUj9dQl&4M5F~Rgmf4iys6PI#talCKOX8y=D5u&x{p3S z0cr<MNpOFsQ1we!o#hU}IgB7#(CWW|t&uM+$A34`xkQl0sZ?dI4_G<&Bp`P_&~S2> zO!q1guvU<T0e)q!h4-bUKMJap))0i<hy6rOu1FA<kGK@x7C@`T>f>b&URQ;umv#u1 z_X0P!)=+aSLgZ;2;AH`s4zZYHK%Ol88VtvFsu#m9%SK>VzRXZ028UvYD}l5{NTd-* z<_%KTVwFXG5g|BN*>lD9bIN9)wNfP5WKO${L1$zs-`9(C3UDg}N*CnOPFQHsrm%`< z`Cyrf;^|-dxt9DWnvm2?em$Tv)hfs-P-#7<qc_w1{DWXf&!>Q`!IlZN{~Zu@SL-;H z_WUEMO(ECtuja9!yKz9ExGzl~K=>z7+=0tiM&`%UHvSy1mo8@4aP3lJQsW=5H9Rx~ zV^-tGK4Yo8rGZrF1H^Xwdh|T}k!uTN(5St{kBY9>$+{}iJmKJQVa%w2l8M$Xjt<PY zXAdIU{nbB2?e{sK1JF?h1=*)YF>!c1O+6<&D%CEPvI&NZUKHuynbCBd$|oVPR@Xw= zq7lzpzt<Bcus}oOfXL2G>IxxO99BN6#>}PRz7F044CyxDu#&T(Fd+=YhAKviL4zJI z4wp)Pa4P5f!uL5L_mbyp1CHvF+d;wh-Uw9KsMLn3Xm8B!AUQc~%RR9&+!HcxyBiGe z0$k<8?DrJXSjS|^Wl1Kp!G0@tKSWW?V7v>nLcMVN7Rp_MsmVKi12neXK0in*|0)uk zADKFw1L-_oDRLkO92)^y>%NC?GFr-7i?Vq_B$s!Tzkcyde1K~D*X*qchlL4Sy?syV z)r29y=PO(BmocvbQLM6~flf+j``2vNhdn%LE7|ss;@d3dur}6G49-byR8+v%j34Gg z&_ZL9q$ktD>2Qc-PLfS<0MbEN@amFquM$_@jV1yTe45Dt+zu;)K2`4=vV25%61OdR z8m(DmFuq0)HQ8DM4nRiQ3uoA4>x|k|+WV3Gfjy*T;Rdw;?J{wcV3DWxCk+znji9k_ z+`^}0{-7@UTqo&?MdXY@JA^A{LW<~bf^3HX<C3U&tY%bb)T3z-Y)+5xR2d~SssD8Y zEf&0cU($^raB7aepnzPG8J87q$IG{Z&An_w3NV8gzAf4Ug={|bFw#EW2xMkx_>L8W zOFg;6ALQl=$JT8GA!9R%-K#P0P}s*{G@Dc%s`tS7P#(v}wF;v@sW{VE-Q^dg$kwY6 zPm0f23QkP}@jR>|a-Ig|2>rFak#k8e&O=JWdm(OZc>5hPVqz{N`I`H`E~Otf9*IqG z4(nmV93#@NWOmINygv|zSt)Az(4>WX4U;^C8Ej;T;u0*&LutFS-Hdz3k~I(x*xmcQ z*h9v#YnUebT}KXtBiT0)-}fXD>J`^gD={g5mPH=9FIH3}8=GqG2O(MebDVMwS&Bx~ zVsw+o1iG-cF(IDHvUGGe#B6&~gqN_DTjVcPyW_9|G~9-i`UEjtFZui<7Imn$`&-Ns z-xG}D{27pHB}IBk;3yXHE0Fz%N0}H-E+`;2{m*Po2`mGNc*ChXZZ-oH6^(SiP^P6r zNkY;9aJ0(}MtlLzK}qX?Z8ob$C4U1*GCXQVvNMz%=GGS!s!FQJcm>>2%x=K9@t{ed zHKPWE9dXc8<r=o}Vb>%?Y&YY@xx?zr%CAxOIXl!1pzcS0$BdYh?Wx;)rzRnwfqCR& zg@Ye{=nEjIDW0rrG&Y6l&D>G*Vi2l@iR0l-jC=`|8Mq})Ib8q2wK9slSi;S4|H}a< zB3w}P&>fB~`9nmipy-|}MzY|vmo>t`1{Iw=QbEjj*U*3@Dh`3eg!k@U!_2!3*$!Hf zGA6Fl{sihM-rd{<8PS%c=(@9|q8-sWZq#PG_X%mvx!Fj|%ULmk%$X!*<3b_IZ7iXn zR>w%z7iVLFDb1Y2w9I7iF)IGmM}B0bPYMM(1!)!|@AhtoRfYOQ>{x+F%Yy8ywZ@xG z2AX6O$+rO3VW6}y_<MbTttjE4)J8U(C!Dj_lr{{1T)sUo0H|r}7l#_l_cFiAuI4{K ztr=nVlDWw2ISI<XjX1A~ZJ;;XZMZ<rI*7$@0M?KqUZZUOj29G*K%V;vrWaL?Z!&OF z7YD2j2Pvm$5GV{WAS;cNL6f$BlBwOKD~KhfgH{GNl-q6LAE!|q&CPB(X=fT-<(Epe z=W7dIbuP3<w?QJ5EGxw?nBH*K_Viy&YQ|_eV9!)tq@S=@+ccNw6<3Fo#21&#2cB?l zT;Y>lGkZK)vH!9?6@<VyprsxA0#gKgulr)eV=m|JRYqfEy&PxP!tr{g1k1LAK^bp! z*_8k9%7|s2FL@hZRD+F1Ep<4TYxxOi+jhsN4w;*5uxE(%H$xM#tT*k5ZBd%6;oW!^ zk!nP~VPj0OrRAs+Jx|p(4U}uyYP;QUgsey{R-Up<uYOpbEo+kU@z58D?W`Yl0s4B> z$A+4et+ci%uBHtO)7p;3D`~x~0>>;DuTus4+qlM!ZN<5A(SP~WnR%LeAllxo0b<Z@ zMBs<-Vsb7-0>XXxGhJ^?RQovAZ8|lPEwaBn<mT;W@7e0H@3R{T%>>&$Ty!(?ODTaC zK4kBQ^HwB`xz@K_w%h4DG7uiT&2Mo_4`wcCU%6SNw~CK241mk_jHBcd?tb?<EVhHg zuZ_LVE`4GLeMbk=_gk^$!NZ46{l+3UF*1GiPAblOUD)DNY)R4yij-@ww<9CI*Sc4{ zrXHy$H+>2cwgewi*W?xj>+>qsQ3>UKg=qUXlzf>&BI@S#+VAz}oIRga2sN&$?X(?( zw(aVC!C3oEw@GKi42iKh**G7>eEozXylvY=*UebPyqAM5mii?3TUh&({;DEv7K=HP zt=jBX12$J2=$l%b?^balIJjZIG{d=}S4gp2s&8WN{0Cl8TvOCmF0;C;F2{K$&0;3b zQ077nZ$<ajE0wy-*8E>5-UPZ9J?W~WQMvZ!F8P2Z?CKf=_rB`%u3ML+1i?Vsh=?{x z*mz!1>(H-OLdSt4qQu`5G<>4RLi{CjxGnwYPVcl9G7Hppz2fMYtBI=xx%l3@Y#C2P z)icH<R&(eRb_p0EAN^w0;=Y4PHL}Y#Bdrpm-DNfJd%vni^gv0W8`o6#)j@)2ZPg|| z_3$#38Odh|U`P28#ot!8HePP!<6&0uq~{Wz>GVHh;6iY6aRDU>e1$e8^V%N}%9>QZ z9fId#Q|PRyJ}P4fzlDlA7|5*<hxoiOY*MegQBVVjVg@Y;j4rJYucgdUsRJ$?9fr@9 zglu4%QejRkeq(c?im4xG(EF;J0GZ2zb$C%{@**wNe}<8^_Bxt4)nk1X<*5+U<JUPG zBy8|6zsb&Ngap;!T_$fQh|AVIP@tx-(BghHf=~40|CQa^HtfyC&Fx=w$?l)m<bE_@ zS(2)E9GSdXv;Pz~D$CZvYV?hK%Y~`Vf!WU+b0@e()nfcp?t`;Eik7#{ct|e$QRTWN zkMZ3`MrvbyY`3phJyYg<Gr8?p2n&G`!qKeHrRx;+nB~zOuyhQG;WIP!fX`1)Qsrz< zB_f3pz(m_r<~to<d#%HlV?rE(w`>e}S2o}=R3Q2&Wi;?LO?RyLJnVex8G1;Q^-wf^ zu(Et-+`tus*qTGR!-7K|JRtdFaXE_9whLi*4OVD6k^11NR(G`_+Q#mXDs{=!-_JJt zoAvH~7h-+eblASl+PMf_0yy}FQdQRK5j|;2&^O%1?_A@mkWGqtk&dV)gT9P+e5ce5 z_cQ+tD9RaiY>0}f{;T!|rK}4}gLe~2Nk=Xik%?g9TSp-PHPCxVAm>S}^eAJnxE`Mk zgI<vZE5CTII$mwJv9rng4+hVQF^di!P3wKbT9eXvi5#@u@{N!A?*ta}9YH3=*;>@; zOw3^m){>m>%NND0FC1fKIX|{atw$QMnUp8%I#v4g&IFORg#+gs7rssTUW+`wi*Svh zx2RQ}A5-okU#)8c#XXfvK__bObgO7E{`Ia0rXj^ZIPeP4(=vRBkAOk-<F5%tZ{POI zbzdyqygOPFmOx&@)-VBje%_hV7d<uBPs$vOx>Zt^<L$kDf@zrnK;sX&@d7Ydp$9=d z$(kykwAjVdKnEOO!haq`DLLX8rOOFJ_w9UDY)#5eIA9=f1_Q^FanynA%fUDdQ?6}O zwMZ)Ly3|y`l0Qu#DJR>rlym1_uDIIFcv4Z4e*sEiWV$kSMkC#ufm+0bC8FVID0^(U zl~Rh2r%j3iw$2N9oC4f&jHd(p%`x;|Y{9-|&TS^s5EfOF5*50oQ+4J{G*x>)WdL2W zMQ`q!w!2=PJYOevx^=P>yX&_}8zrQG3YJj?NNY$^{a8XXq|&fdj7+#U@a<YOv=<tR zVY=3AC}2Z|@wUiz6RNb+j;_ZlJzKtg!nn+KLN(v9d_=!;Fz%9hWM0efo$<Kq&#grs zs~?>Tv~Uob?u_T(()l*uu>Ttjk5ZxG;@^}npVi1qNSs=$_NintCvky}Y22U}yW4Zs z6Hl*J*KveOHQX1lVs>Vl)9U6FQycVUgf7>uizE+oXGFkv-Fa9@!M-vxdk>O@l*~(r zf^R%~aS0Oe)AK~1$!AfX^;B5@n<q#5^drCUS8V7ltaOeuHBdo9@o)`raECi$wb|OL zaM>N%;HNmA^R&3*Bh*Dr&U(X|oQDbxiCSyH9jg+~CTROk4*VWBeXX-x(W|7l9u*GO zNALmC<yMvuqyc9m`ZKhj?q~D0OEn4E2(=VN3U9o-?akLPsl_O5;ey)n8ukKn3cGqu zPz>)Qm4rV!C^5>r%rY!sD?nmz3iLt@dw^j+#kH$q*aPF0tSjPBTa{0f{>Fnzgv!}e zDl|LDM0eV#eOUZr2W(E-6SF7g=J$Db9m6X_gsG|6Oyadjk)ds?4A!q{5AWT9l`OmW zs)xYt3c=X*5D9QzURj9tV~#yrj27{pi0a&#%LYMF0|szh-Qc)OnT^}h&L|DbHU*Eh zKxNKvfCnuJCYmQj3`<=o@TL}hp#vU3cyeoOcqs;!!0N!o-t>3ij=<UUb^WaMZK_ee z+qVs@ZQ}pde~+N4v&~ZSohyFS0IMl>i<4{%aS@Cq-(;@&J(Obnb?b4l`7t%bWHr3> zxxFhsK~MPY%Zt+YY?<XYTA+_;bFb13#Qo=VM1<If_Iz}HyY8xPEAHkqG9ZYFM-NF2 z(Xl=obzS3|8y+MfkWLbBu+QA}ZOh|TE9&fNg!%K8w{Y9DwHJZ(z9#tbwKiz5jlh#q zN@Ga!eh3INZ6Tl*6RXKW>GQi50}`*QB%3W4DYYzU;|7{MufN>4@2)B8$L{SE-<4kF zmU*8TLQems<d<(Kl(oVIr_v|sC<AO@i!~&Yae%|&i5fuzn{J=2*@b#PPPC50-Rg~A z#R&(wW(8c4q}^&l3A6bsL4QIe5d8BVHOV5nQLej$liE>mr=A0FIECjRv*L~i6YQ3b zQ?xQDO)Vd>Jzb%u6^adRpM`cKX$E@FLSL)6Q(K4#>QkBR;L{DpKOKc|hN#9Ta5l|o z@AJRN*GLZSNc<TVVMAj^?0U3ly&NJXe+62a*AeQ`pv^wMo3i{iJ$LTSbIvFKq15V^ z)p2@SBggj!48U3OZa`a0f0fKgGtfl(-dS9_bU7?EPbE^ZxMeDVw6$c(IpavMY_boN zPdTWzC&YJf3~QDJDDjwDeIhXP&X?nDv{XtYlHO`fB4VZ-i*1ECcz3AOv7FzJZ!u?% zof})u;A6$d@V4g?N4JdKi<bp#cdS|_v3tEt`9)-K*kx_@BPqr<F{b2f;n&94y#7;W z5sT3Y6!?gr!a?|+e)1IFdy?ZRanTALcCX_~)G3%m%wKALdWHw3Zv_J#7n&W8yz1<% z^|uCINvU4XKAN`sf~XzzyBC1trGMk06BKZASpoa+99s9&42FNQO-H4NE_T+<tJ5a0 z^<#)sa(GSqA(`>z3R=kja?&m+QuZ4wF?U%42=395lc^0DQm1=-df%Hw!2kseiJSJ= zsro3P?LaKK|GYn660a`x90ec#i>+Sq<<Dgttdvo@+8Ma&wbiMO5so3c=gWGDN(0$F z!1~CRjVa4v_~brKqAXYGB^_gohf$saVW+B$iWa;J&*>#q5>lH=ATF*QDR8QgU$TU@ zV_C3)2J{u)rdsFXwz905$B8-@BH;IxqH;KjAJ$~JR-3y+7N47WD|R<)1u7jZb+&7k z%a}aa%=$UW+s$~a2l<aeqNW@B>&Y4*UxG!0Hr00=4Y~=!F)zy*;paK73QS1UBj5QQ zIZNBtdBr4rgRWH@SJvaZPzFi1bT)>pm_C*j#YS!Qe=*4jZCIJd^&c<)1NNFqd?oSp za40rpymzP1ogeljqqs`k0(RKhJa?Q3WnAQ~b&y8rk6~_4+2{)?4u5XtGCA8vS|(Fe zH4WhjQ2iLJiBZ-1k=98pU|U*vdNP$3D8smhG0Q(p$I)H3yald8gHR5l(h(uR(5m-n z*`?W+EGD+l_dIz2o?}GR_*9}u)NoV#UYmpBt_Eyf6RG#^{;pSxdVy_@xtP>zzJz$I znijY+!btFJ@4mrDmF}U`lO%7%^SS%w_FAv!k`DSL-0cB-^^kuRjBw@fE$j<9dJ@k1 z{jtbif=u7;;;`|Hk-VNH^$+O4pB(f+!WxBamS`zox1llA)fh+$Y^g0WIRS1hd`~+h zzbnuHFsXCL)~cV|M0puEC3F(bA>KQSE?y&!0esc59MO_W0}chD#@1-U<CfMqqi!j6 zG;qc7&P_93s}WNcE8}R7SC;qK^0+H>D~^efyJw)}gykYGUVtFZdmlU#)rUg3K)k=P zaGxM<y{Pn;Teyru(wN2-Yx1p`UU<|nET*e+5UD<;w$6OwI0HGOC%ajXV8bAAr%2Xn z)YB0o#KPuBm)TkhGe&aNNOq-9iy&~7<B@A*f}y*BiL_soE{<}Fnyk9@fF#`i)D45A z&uO6gs27ovY%A-Bko7@x%C)CaI@Ni)xBgUAUhM}*70q<L?k78m!1mG`3Is*K9ir)N zhi#V(KdEZ0$K!tbVkC&4Jo}F_Ef~WtH*OB`VPnwy$oQ`};zvkN3T};1A7As6x$#GY zvU}gy?+IR0JYT?Yh>PasxZri<FAH?wT&^CgOhj1xoVD<dnbq228hl^W#u>w*%OIoR zdx}Fl#NJLF+>uVI*3WyhHn^cWzgnJ7gM1#3%6t%SvEVOl$OTuYg=&WHG}@>YvN&I( zFFJ$Odozf@3l$$y5&pD8dr}K3Q0c$rg}BQgp+P>2YEjNq(Y(MNqY}uYs|j&@*iXO1 zMN3h8_UN|?_Ha1)-c0dJZ4EF}f;(BdZ>Rbv)Gb3z5#P<Bi-1lS$C<LO^LsI=<ltiX z<rC@=I;o5=LTR@Bk9_Lh$JA@EAG^8DH<g3jtM8?L{?BS<D9NMq)GrLo*KYIX-)gd= zd^N1xu!k}LNjtXOsSRRE`Rar3P&)snx=x^6rN%nWHWi_94Kd#2#yGFNhJroo65L)& zGoHAHrVZ%T?*vkD`hArHmqEd}tiEwV2Sn-i?b5!L;|97xCk;6z4BK2BM`b^IF5s-` zs>m(gdya(fZu*>?82Sv|F}iI25t9+TUYls8CED{*JJdZA38Auvt*N;R5~A5MRjZvx zNcVD7@Ip&mb=bt89XjL=GrS~Xp$~KpUV0C{@2BK%tNxXg)`tQ~Tl9fswZZT=7g2!$ zkI3UnF5{vA3#nlfMgT#HG7IuJ4qn<<u3nY#kalRk7pdT3GuAXNq1f|Uojhv^b7s5e z7}qqR;y)_sXkmh_CSxbU<j=<g#UB-D)A^MhgXlp>!->7fuQ9W|nB%-o%mGE-aFY&g z?aaCQZ7CsYS!$R|=$9^-vjGZ2Wd;|jDHh7$BaFR-TO(kj?z9h$SjZtWbW+9J8|L>n zX){42l|_>=D`ohVF)JDZUriSfB&p%<lo-}+WZ>_o0$|IMoI1w1t^J%P>J6@_Eq@2+ zHU7?&AD>7;8r!q`iQJGtURG1E%Fk8E)-sW)Y}tvjuFWJXPO}o&aMO;bcO@>^E@ltA z&lt?NWV`VL7{N<y-;lO;(Z=y6PrE7$9=WbD!DQ@}0EW-qzB!F9P`BJ2>4)89(}`Mg zj1FM;xNz7y{YatNU2r>e>T7<$$ezvp%{w$uK0U#4R$AKroc!INB!9s)!3Frn1xFlG zGcBzz1^FVor}QbeSe9sS1DP@BN89Jh&HnxO>-uw`61y5{WPOo|nd2B$Dr8G3?^x0@ zz_07f-CAnfwoh~+%5%tf?G%hxd7A43yD15_*>~%U-}o4K6eV;Yxhc{1Sf}+({r)WO zh8YWK!=&-GW0n5i3QD4L44*qcD~#s2+BKhbq-Cnq6j%I*^_?tbHio>Mv!#dd<_v3~ zPmSPPQPuWo+EQ4Tt>YN3?>x2I*LvEL4ODyFTbKO5SbM9Wx|XnAH@LgILvRi5B)A3F zFkzy>-Q9z`OVAM9-Q5Xp!QCxbfSf_rTK`|C_C9y#CRJ2r4(ZX|pS|DH`@C=lfTs9~ z??nb<tH{0Pa2&|sO(&4Hb{jpXeMYG4eDTP!SsrF@{*XWThH@a-g!S->n43S$b=0Iv zoUSXn$ifHvBvDn-el}(or`rQNudd=cpifdRnpGw_RV>$NZjd~5n1*nE6_ZFhC-FT> z*VMx%a*k6MZYdbH!Vn~($6u?J{d;xa^qGU5+|VvAo)|RvEO6e&sW{Lo=67%CK>T#4 z0eK(}j||~I4D1kA_V?qV>y(|2%eX@V$(x2Gazqlk{?7eX@Oe(66S;(qaQZaXjI9GX z@@~uHiChC@dgx_d;1uXpsY~3U5%h|)REALHNEm<e;^!Ece*J`ac2uGq*X~#x1bH>E zwn>t@Y~d!aZl{Xb&}gDsaf~%MJh4N`Yj^9n&377}fz8JC0q>7GaF0hf0+~mTV>eG- zSxLJ3G&YvvtA`ps1)eZfh-DEGUs$X^eyfdchtEC8S2|}n<Oz<CX`XPB{VXJ-jn7yR z!qCjYVb<ps(hTGHg&aTOq;^tR2$4M-yy)N0L?lt@t<Tnga0oh-<!?U6<q<qV5nmzH zkPLCN;NSFFpn|rOb!m{H@}7L_<nX1Lt9<sJ)|<3KRRT|gZ6Lk@ORKjbiFlq55*H87 z`q5-B#0$-egD9b*`8@hkiRDk-$!ts;xY6ALU;l5|v`o%c2+brQGy_o-P)LLN{2L(< z_Gzeq1txU|ycxVJI+25Pnc7u^RTfK@U`8D53+TTt12b~Nd(%s!tAh08c~~ig_+7oW zMEi^&zQCf(t%wGM2=Yy*#laFDITf#{^?o7CnbXi6|0**G86gH2#0rG~3t1xiSi^-Z zPTioE%fyF-v~}%6&R?zg!4kjBXy~;o<gi<42Z3F;u`QGhT?8aINU*A~!HL#GNz#Q* zTJB;qWe3;-4_BDjJ`hq##5~V_fIkFG7RzX`Lu+3`%zJn)ida>|;PXb7HRIL7K8q0U zx2tlMz0Y=iS6e^_L?s>M$L!q2t`;1X5ED18t|^;>`6LRTPH?)f2g%mHUYMwO0b)FQ z$62Z>!(1@QjrU{TqAlU6{Bp;Smx6%OWFN>9yvn97C4<lP@x2#7FmzxAvjQVA(oIXi zXV??|XW?U9i*2Rc!!*}7s?HoWVOvJ4M;X~L(T;{{ra?_}BAL<jPoZ4+mIVcf>!KO@ zEi?SH-bfUcc4drmZrP-*Axhhmb(RA$3UURGzrvY^+$OZ>_mAlD8c%s}2Cc6Z?eK8q zG#jB5b|hK;thV$1xo?wOM7O212j-u!qOnrYO-7HD+2@^)nw5s$s`#MXvM<37dBmp8 zzFAd&;QC0diM$;de4n<-o&{;!$tu`&WO&wll&Nqum|+bL4mm3bH2WPH&vvIbeKa@k z#B<iwr|*y{GUCUZxwhG5&iL-SGIsC8@Q()=&Axd)uC>%*9Wr2E8S2Hyx2+BeZ2+A~ z0~Q(^*axBXoZFjP8lT*EfoQvy5*g3iOTf8jk@+T~`MiQ9`|R)BtASq>HU4Ha9~!J+ z9?^cgT*_91Jm^#J+tAm}c2!vwZe@tIvFt#QrkN3<?T!m%jZ@XF441cL3H68&J`(Y; zWLS(NQaLhS&LACIAs!R!6q;o@8z$6bSIvvz?CF-?|A_HXlUalB>nTI_=ovJj7IG9* z#-~q2F(WZH)Tn{kjqK;Y>wzVQ(E=zz6T`jS_!0SLlj9uqYz~dK9y^8^!PusTnF@5P zb^h-Sbp|vJ35L}c{c7mS;uL}(&Y8z}RHQYeD5eM@u1V&v71Fly)t>@U`M=Sztan)K z==K*gNBYKaZ&*c|;ij3m>EdcHQWvs&EdX&f{Y<f55!(o@A=F||B56`pP@{}`w=F-N zq%yW7zs43meHzm8!y3?wq9?P!#78uf%T$EUxSh(utZSpXj8i9YDX_Jg?8Q@LJ5nf1 ztSbI1sPShhlB&FVPaOAoQiCuZw+xFsyLNc(^X<xh!2DW%PVTt;vGJM3=WY4hZq3fe zx$GzT%O9zPYiP~?u>i_2qLO$)%hW|`WkJP0rY3V({n*jL+Q{lXgks8zv>8H%+eD^W zS_AAfwo1N4J=s7{iAj@Rb@Ksy%(GiR(;`x>B=fnwQIH%B>AG3g)IxAwZ=Ag*R?(Ab zi5a{Skr~#46>f%YhdV*^g`}x*Z*Yc1R=3$|uq$EJjyd&*VuovhnC;5i3I6)a8T%M| z3<ksTFO^j^OG%!GwohfX6W;|V^;02>RA`s!RKxC|O~$N@?P-{t*{^y+0XdN208)~h zm#@7yADv!SD!ZtX+wwNQAyZb7EpCW&x73xeTc5MJKy)t04Z-ETpVOFuMML&Rst=jz zsdh-Aey%|^&bwWqJvaL$UY-T1-RmMON5%!LlzY>1oy8(2p>2H5tqU+h&!TK%53(7< z@C@nYm<BWMnB!63P^)Z5QEmk^iX)oixdxZF?%2u@>l4ADrcCiMjAMB$?jU#Pcq|<F z4HXmP<#;@gU<L7m&z2W2k3n@3+hH($0)u@dc?C2(X5&>R*Z6%QCavD$=klJ!?4%1* zt!=XFHGId^={1Av@<Nl{<;1OEg7qNk(fno~`u#vJs;{T?P>bOh_e)&k2j2k)h!JtX zU(D@~>5kged3<HF6~njE|4NS+%<t6L|CBC;uq@<;cp|?U(=-P+ljBO<w@?||Frc?0 z+hq(5lDI5>WwV^(`h2^boQ89_!Nr1>6{)@c*exnAzc`&1fI3zevgFh}Ob!7_uE?4x zp#>elO9P^aA#hS{panGba$a<})ABLMPu2wTs+dV;McqvJ7a0TZbWNv=6HM|}BoD$w zZmVNVhT*3v$sALZQyXeQx!5C0gUFk{t~ue3860oNPCodpOWhasU<4FJLr27It(ah< zZv|7GqCzeC80kF9>gl3>BBGJPmiWeYZz2xDee-D;>H%K6-xgbCe<wkSWo*){8@fKH z0E-t}*4ao7iqQnkxpCJxnEABweLiz;CWSojG#p#A|692v)g<Ugy#i<^sFT&)EMt80 z{HBOeyWJ$s`8~fY#vl}_M7f4#3L-co*g`G%)&W9G<6iq2ukoZ!akuEV&C|kAJ@aMH zo;?|sSpk9+H}{gu@b7&y$@U9GnAnkKvY#G*p~XJf6a2=|YhJG|9~sg(q#}Eerm?=- zY}Aqh<w-}58oeaf9y)MJK}$4U2~*Ts$+-H9bC>^t6S?n}C5^>WC=flndoQ9*m&jKk zk>J2}W)`l>(~au>RX%2B&uf*gk{&`Xi=rYU5)tx~#mcblqK0hnpwM7l4ybMTH&{L> zKC2B30|Tw|C~Ot@E!$~^h%XO$J8&vn<bESCxViLd-8Nl#L2z4_4UZ9K`&bKqu*lwO z?mcmV!-N|@%6bs9w>06J#<co0@vn$PzhEsRtJR|OhB>FC$Nbn5)ha)zb-l=x^1SQ! zbckw>?Rz<fYFK?`aEzPb5pnWFhS??+iXK~`PZW=7$86CugXEE56$EIe%Zz0sT?(yX z&I&XOSjc22<)VdfW~s^o&ZTn(Kq}PE7Gq7BKu`26#y>9>PJ$I~PvQX0^emrs(Vi;M zTvO2yDf0W2x$UCIB=rK-!dINns_+BE5=nNyRHQe)C0oOeuwh`|IaPEopQJiIyV&wH zS-+#_eQ0JXnZY`4p+)d9n@>YK$fHB)8YM?g<?gSmoP}<eB_8t;R2M8CX7$i!+eQH5 z_-c9~h+&8s{7#9S2cMeb2O0^Q#aZilN3gZIdak!^x@iBy%;i_+0<2z#jk+1dV+!2E zObS$d^RLgxl!;JzcpR|D2#&kTY+>dChLgK6V$MLfE6yOPXIW(>^9;Qefw2ZwT13uT zZ#o)fkUzR_tQ5MGJV$`v4-H-G-E!v@bYqI_XmRq;H=P2BFovSIWaGc2SY#)K!kT6o z*b91t+9qU!5L~U|B#Fb;TP?8>`H&K0l`^P;Py^3f)=>hDXua%p-twvBy?rC<X*`O= zxGAB>v_XzS9z_0o?A(c44}KDq&g%@VHB@_+swgXs*B|vTTQQpwo@<?_K_6k=pp|0f zp3}gb_>P#ueR~+n-vYcHPP^}Xo^TNhyNA|FXMF|A3vd`)CBGj=F3=xpJu_#~mu{$B z#O#&Td4_N3K;VYXJvR(UNam|wj7R|C$bH|CNLzZ}wIjWo>5%Mok5VwdmWWm(STEnd z%=eOoS$Qb1n^iP#V)66P7yOkZ;Ehc0yYeHpb=T}Mh3#1GLl_9(0cv|*>=bA5hZ)-_ z+v;d?YHw*jUhfG<jdf@DiN4=_kjWkrin&gcQS9uzpeM`(xXcW>Qb~AoDOIm+%Qa1_ zF%V0aM~}qQoobzgR=)|7JG2~-PFB?945}g?&k7(T8c52^it4pnE7%x~V~>nD4r&lq z$iboIlu?1?o`nM=9c6Pih?XQ&;BMTdSA@ygOD8b_9$V1Gm;HCK2AkTv%hPwH$8%gc zb|~6Jz9JM+MO39q4m*zWUGcQn)w8J~ZuUem{l4F^zjU$>2)}mddM>*xKf2A473>&m zk`_W+b-gKdSb?rAW&sV^a;nR62!qv)vUcFLeAeIksTkT2`AThkG!vV6;!flfF4~qF z$ZS}0;%2(+dUqyAAaZ#+U~wy87Wtk`jjm*?+Q385Eb{GN1pzXozqVW#Dx_c`1<=-a zPyX7mr@WDC+^xdJgKwPIWsLdZBLn*TW?ua>_MsR$4W?G{r8pK#Bnu-5n6I(5sS@2d zOa$V9nZUwZv2QPal7~-4US_F}f;z;GxF>WlU$Jf+*ZCoFqGCpi#}43wFj%W2XGXI! zI)9Qn1k`X2_wpwQ4l&O90`1h_XezgFD5f2nf}FOfaHpH^ptZy2Fq8SMX&P2-YTjFB zd?G|G<y$GMa3LT!31NCq@77390;q<zC2fCb@>p!^zUMRR81;7HS+xs9L&HGd#-2#a zT-h^wxl2^+XpW`>mf#M?I#&W)*^rSqqTD<&MeMv#y(x-?;|>XI%^MingdMj4ve5o% zj4N!Ut;}4}!uGIjyNN5AM3J|&Tj#+D91pvF+@zPhVq3+B_9zrkx9DPT4U{4C3phmF zmo7HKwjc{FzS**@r+HLH`=Km~>4;};l7@@G->Q}P(Fg^}i5R*w8%iu+#(9z3RV(g# zPvIJV#0y2(f9vTsAy9&q9eUABWz5>CioI>`iPz(RmVym$0|zg+k`~WNA@~Jr8KG=W zD?0L{#LsEN>5#~xaX<N@pT#V7R3+2o3L;F-6{UA?S1YMN68g$hc{e*eQaRz6Y&7pI zs8;aJK_|+0Ss;>8UW8JUA+MF=yxWY8)-{XbteWj4Y}Msd{$TJoFz<BH0&_|X!XkS1 zCH8wJ7L@yJE3&AXu`=1Q_CKk9D2Hr{-QP2X<JMKn@V9xi8oyJPTh2I>KoE^|ArcNi zZzz&|AR@h!2-+5C0@|lDYA&t4r8$KHSkG}IoPnO4C)Y!v&8mQ1{kiamapti`yKvid z?uFQW5Nb&C{!MwEcF9z6f9n2Li09jfnIv%w54{{ft66_4A<am9ct<B!wLg;U`C1=P z1Sn1u6L%FlK#UOkcg7kS#2Zef2<&-58Zo0QF*#f=uSPsy*Z)ef&UmDeemRdXEN&j= zH8I?ZniDp*KDmpPA;r30?K|+LcNGBlgq5Z`sStu84gE7h5@RhB5>9>e9!Vl*A}7<Z zw|yuZ#7|PV&v7D;Mo^l&T#+6I`)GDT>q$!aRZ7Qw9xjO~W1Xt<!poJH`>e4-WR%{T zbyAhGr_TOD!pjbX=;7G6t2`XyNv)OcbAatBj=n&#Fmex48fg%3xmQB%MCjmq(Gn)` zb-g!7cIP5VyI(*^_@FVtrH%U0H;e^-oxg-iWyV1aHMdJ9MX-2t>v)mBmgP^HiwGc# z=J-Yy1oIx0WyCxXxXyQ0pU%{xDyU_FlR#Ynr|krEjz8p<)rDP~^A8qVWliBO+H4A0 zW0;uMORs(cvk$qFT;;Jg_jobF%6OZF*fmoj@(vxW)~*U+2WTDaX78T8(_Rg|QoLhF zud1^w6NJDjL)kXjY;Lhf+ok+6%Z-?)tc0z7ctnyY7F#Jz;-1VXp<62E!{a<UBZHTR zfyZ7Q&zs0Y3<ZJ2;_OXpaT)2tyKtMJK@Oq_&Y1rCyaViAy~;%_gQ8vHH`A`yr1%Df z=ahh`C)|zoc@;-FdlnM64gYt6u}vnL>`RNfl08Xv)r598_!prr=FC8$4GlgV2Wc7B zqcrx2^X_~0a2(r&UCVUtbtgfWFUMniBT@Vx%+ix9{&w?PW26T9%@0ZcHR$4?5K52_ z%X38=_q_|Zx$B9;SacINyB+tGvuV<fYtXKFpqANa_;Yk+L)~Z^j=HvG?XuOXSQGN% zW*-xNRvh#M_mtg<lUxc|<7>2jY!vYo{gNrxM6$Yo?$y~C#}9()MT*c{v8cqW*8Sz& z6$1L>$Sw!qKHP?O+yr)}4>Q8m^3uAuhmm&ndp<qINE4E6{I#ogl0&>1V<twwI{O7` z3qwdHsLs9kx~I55GmVZ#AGaxG1U>5KSvxF>Y*Gisy`2~$@=YPhw%*DPO4U!{j&n4{ z*y}V{qhF7}IC#klcm^8tcql~gQLXcie9<Jw_-gyomHDkH(~?R!BW!YV6ppguuA^N7 z&ZqUDd8y8qsq@*GF><3gG3U~f($}>GqD_sz*^-UvOf-&5a`RF>JS(o78lJ3>cT|Um zX@@<yj@=oL@bbj1`(}7Wsk!VK^`{k<*fN?AMtPlwkDT|1DR(9`(>v>&4y+}F*|<R; z3_cW%=?8N9uG28w6z(PW>pRb>Pn3y!=O~d)+Gd;&mwkHX`9QXyZvI<(MVcoEb$w1P zOk3)=*KkHP!b7^l^4$+p{Ut4ERcgKgA}?EF>-ykrp23{*BD*3rC&>mr)yxN{V@%G@ zh7M~}L2>?@2nv$g3YUiXu3`x?D@K%~_(QLp^+fudEbXJm4q9qa&++@iqtZ&3r<Z%u zw|MT?(GU5b3<Ytv=13Hp59ALug<-dqrE0UC>i{*;-r67-?L`tYW%GBI@}~jH2ATA8 z%P^&kM4~^bMg#jF1bTQ@B+Yr;7eL~C1O`9w5+>hwIA3w4piF2?+}p-fbGpToJ_CG; zWo$XaztgWA0M)G!GQeQJ>h~f^A@|Uh()vR<k!W}@rpJ=qJg#uB&>cb`%8gwpLCGFx z-}0j!Obxfl!&8Uk{+Yh7k`|z-9qmUFvs{7;Tm;_#hZM+Yk2l|dHA(rel=K!J^uu(t zLGa<T++BOH{DLfa7c{!+#l<8*U5f>=GSr_&rexp_?;TfJdo7?`{!hm{aG_U~1aK34 zR7grtXke)d&g(NGlR#WI9*jv9O%8G^+3mU7io4e&BC(TMVSTBT<|Ko-Cfon1u8ehU z$#czEK=|J^{+IS72@io$MRmiWhW&bVQC;YZYO@Uc#O}*RlMLC!1#2a%L0#9)U_6hj zc^4^LB85%Uw~+UXz3aLsFF<<2*7dcAxiao_>g;)FV(O@5@%4@WKBy=P<o#U~4JlIJ zoioepbE8A{iitv>*x9Ln|2r&SDZ7d=t2bJc#%UJ2{G%El5vYliqZ?FP&^#6mL-~ey zhTSN;3L>KX7k5IV8Wv-X^P{*O03u1bu3<3Flce?RQ*I#Yl`v=!3uaFC-<x&;0q8TN zk)Z_ZzpM;-63FEs%cCj{#lQFTr|_Gc_<*NBYxpB|Bq8U?xDj9j-RoQ7>Dh@XwNzJQ z3WJwEq@XmibUs~8BRT+Wu=d5-9-q@AD+b~HUwad6fLOq~41?wED^i0e<cGvR-{h5S zVoF)H@X51T0!^rn>1ow*@)Tc5coU&!m_h8v--iK(!OM>sZlEI-6#Vl^b44HlDb37J z7(BfVZUAFLiisNmoBb<+Z$EPetxp7KjJ`qozRyVvF?2`kK5qGG8z2s47Lj|<{xh1u z3ymp5lk0#N)YZ0sNRc@g=lHZpV6gsm9O3;psQ{+nCb*3F@6by~yg^#TQWE?D5OVBM zJFBdB!j-)8R*VxAR)I>^X|m4e67G-KrXf^zlR|e*DV<Ndg{A&Y{I>3+x~pks*@t_; zKlcq2|1%f;2_oMJf4W<-6&VzU0E!#+uh1rs&w;-f8IA3f>iThYn+j7twa`V{{4*Q6 zKmfK;0G~MN%WFdzNC)G7q4Q-IK!pgp0wdb&dEVamwEgl*=h@5g^=a(GlxqTT0dwWe zd+BEYG2^8!Su;&Z2$E;rs}`s=2=7mb{PF5sy#N~T>wzh8`q)C7`WVk3^}k=E241wQ z<50oY0l2<qX+gBmtrox$I<7}7{kIi<iUgSWKiO50|K~UV&D_6)iU0l(WrW_bZ^e;E zr2d~#|34QIFvJJZ0Ce#zl|JP4{r>y$|LaPB|H#Dw7O!r1!M_gyEV=*l{{X-CKZ6hR zJB>~=`oG@mfA63}K@QpQ|L4Ogea4aXAAs}+Fa>j2_5%d37&DjG)-TWb+H7^*${YXy z^IEcU0B{8<E1yftSAjlyO(G4n|NDDD{4=;iRBTd)@xBGE+kRalFPCUQ_Hn=YRV=0t zT*f5nFWf5_SLa(>v=Y#)?C}=~)rhMFf&g$jcg=r(cm82KKm3~v`~MuU7XaPaAR@`h z(I<4bx-GMysw6b`3=o+P)Iuk{&m5C3I)DE>Uj<s=w_aOFN4)ick!5p(R*u#KCde5e z&~-o)yzujUxz0HU76bj=08hscp<Q|<0<VxX>_0DeovlEPXNA#PL*H4w5g?eEijR-! z)|tIR(*|7u%)~3HZFQ_HOqThdPYNZr0pLtr4Sp{#tfKI&ZoJYM8qZpeTj+!@!=Yq6 z6S4lbK5GuVa^GBtY?{7$9?BW;kMw87*F10GbzXp>s{r(x_bM>h{4@^?SpSS<DhV(# zNM`Py0BF<ziTh3**7u(PVqrGh4QPLNofHCE8^u9(@UMKeGoZyXNZ`1vcJ&odkR6l* z5H=q6b#0mpJ$tZ1wmW_UJTN=DOuGPq=bM?Iz=x$X2m!JjR!s1V0Jv?Mv5*Bw)nKkK zw4XUsf;>C8{$6?!Ui7Mp;Sfltu>5(&4)HC!!{^|2Tm+vn+q%o4QG^iD54gN?zC0%! zvpG+UCem+SH?pSJjn2dy`0i$|C)I<=3)^m22l+8A{dfketu*;Quj{{8od9uti5C3= zKfOvPc3ne@xCO8<5q??LWPwM2k+Aq2kPc#O#(u?&?p%#%!uPqJ0J!Ufdl3ZXdRUmE z@nw1^;LV>(tzfY>a^$I3N&<4!O$oL<9*}6Hv;!RO<|v-E#b;nUxz*r#da0W2`z6Kj zYET4r6IG{IusTe)?7Ly`?!yNGD&LQUiM<TlGk{Symi?P^bAT#FaEn=6QSkEp-78<D zc&H40(KN%_<LvnFiU&=>15Mz6><s{B-cS2MlKqZ{aoc2SB~{^9tML<Hlbmud8DpKp zeg+5$c6V!@m94<b{fw7mS;AJI)S>k2aRl&!ch9zASCM9dy_KXHjuU*n<<$at=DRCj zOaM-l<EuE&%d%{ez>Hm(_hBdD=kwkAy6OT5<L9*~&wtBL9vwovOA)>4V@!z2`>N<g zU~lw*Uo5)f>@p+2dIj+b0oc3S3b+sx`vtXVLlJN|kF&|r5}{=o`^iaS2l^1@#Vh4Q zm%kc1HtG_nE90KK_;pDU+Xt-x6O8c^(&9dZr|qkQZysK32S5pK)ro_^8V9#*iM<6c zQUBBRKnJO{@w(bv04u`E*sle^2!1k@mTlqcS^?B8faKMhWk}Nll$!REBms+AzHJKt zQ0$dFrW1%YYKC63E3*78sl1SmW9*@>=Mo0^JFl3T?H67-8x!5LHD0hCU<jLHfFfAE zI`N%tZo`(xzuSU@1c>)oD^x>|Mi2uUf7Ue#2y`dW?kP+MoUfTzxj+x-v|Re^DsB{P z+R*p6%CVvyluhJa`<Agnw~M{)ckSmWDZ3c)F3KE}g4b@Hu38ZsKgj5`fvOa724c<Z z6#!)+D*j%=@@jd}p{w4$A0|qud<8?bI}6X3y}~U10Z7g$3OopJ04{)Y+4~+Hmo$^) z%X(vpIkz%Qy}mJYc*&Mj^p#hY1fvNcswENH)Nkf9#RC9hJ|^x$!h7r2*>{oJ%o(M< zU-AG9<&Vv~>}$0E#(<lSf5Ii;?(*1x?ZWzC1KXeRJ<8J*oqA13qGf4Oo}qJupA<e9 z8r0iH{;GQFwQv^%_{Xb=jAhE7IJNtDK$`Byy6Z=4PkTIO`I}c87D}G!y7v7zKWj!= zGEg|NZ1V&m1(ro=XE9&5n=Um9^e3}(pjosqKB~>0?xL6MWs3EWjf!0*Q0+S_%CK>` zfhY;{Q@}WEH-(bXJE)8EzWce*iItd(?x3I%XYbK;-J^5MXz(EG<+(gzj~B8M1mNmC zy+=iP^{zLJ;Qutv!mRh!$}C=QsaJX=`G(d;d1Wh{YdimSZ6h&Xm%FSjSlYzDDozap z#JB#syp9y~5&Y>T->jF4E!y)np&;DxPP|*t^HGK84h7}2Fqz_M8^`fVuRC&kb<Yg| zCTgCC3HMt5aZn-Ed~<>IlPSNAvzj-sVDL$x$v;)wM8SMOH`df`R15;QU4@D~b&~+F z0uvQVklfoEI>1`Rkl2u|-8M9u<m}tzh3!;EcmaeV=Mra!l>0!`(Z>ES>5Doo^k@Tk z)-p#$P6L}ukVs5ysB_9B|Ex(+9|k%n&lamWdVk<z+!LBVP-7fA=latrz>fu~8uNx| z_jv<O<Spj_Wc|cCe%~hW1e+XI3kd+#v7kO?!M-82*oG3+>LY~63i#)m&@3JIMxE7$ z#AptcNDqXAuT;Et$TL8JaNGEyYvAA}n+$+#we!Gv!8HoKm6ZD619YzQbI-@iBSSEy z(fsF{ghcu2p(7J*Vn}yJ&l33ODY#>3(cS_DS0@18A0kfv;mx{lwQsc{%1brm5eGey zS;T{Vh3=#G;j3u(Q0xt5Bub+S-{V2Pu5L$>J;C56_aR`BihK(cnpA>bT%*qQxHSnI zs=Bwop>IagT!153Rfqe~r|v;UP4vnCxJXVCART59na{o9xg~;u*1cX2-WD+R1@Gch z+WLO)EV*q*>1!U3=K$=%wU#)lmq`3NVE~wTC+BkMKV(y@KZ6|m0sv1O3?8Rb+9s)o zu%76uy+Rcn7f*r}aMPdMgPnRVLx^nb=(64N49+6f>8C{(ah`#MzvC<fnZ~Of)cssi zC|;LMHJSr3r7$}Udx6=z|C~`1=?0jSTa%*}y)@*%{8v_=%ZQGS+3S_{7Z;_DOOz@@ zhpsL>Us=F<ia(?d!!L+D{)l-(?L=a(iv`2Ea^v;XR7SBiJ-zZ+m|-6j&pLkFh)fv| zbKk$3Vpo9c;qSZ9e6whUG^)wn5+=jiQ^O8x5&_fZ-pFTYftMW7x4F{4KmT++dH(70 zi{?EFr(29(BgT`H_jSg)(<_a$_0P-i=MeZdo|jk0qSGsG-wP}LQXFvdwL;kM_g4lg ztrm9}Co0dp@=n3}9{EnbnaA9+yroRyAa1IQuV~&wt;k{Qi{|-Jt3>Pf1NR#Hjv6vn z?Z4*N=uW<&`(`n+@4#Dq8rZ8o<h7kz5-;LZB*W=8I}OJB#LLj17Pkw0Ny!dw9AGv8 zZqzk;mDosK7)DG#u;=OH8`b;Du{0YS7U-5<{q#64?+4&V>iC;F8Kmw6+M0{xh3e@P zv2pmpDA`EInM5-HWG+YF3vj&9e$+@&aU)StA*~z~#m{3%5pVYT0!YxZ)#9-o%lG=+ zLb}l!v9?&zlE}A$JP!OB*$+NUk@(D3xd!3a_uDadLHpScNlbvPZAawZGn)?GeHawJ zt?mgMlhyfJ2C#4K>;Z7-uL1x~6r<U3m9)equ0uRN2)+cMk33PI1ObBN2h>1b8xI>{ zPS5Gh0l*9Rm>Qp3&D0hHV8K|4L{_<ulX_@Xq7M5^5HFpG$)Lv=>aSibGGOT&W;?2~ z8W`QnIv$U_YZt9*#~JL$MD*5qIcfap^BJ54e$A?y$^KAR1h!SvH;|H%xDDxFrzfUT zGUC0+3wcB~d@?PG*iot5?PY`P=OPTAwh(Xkpj<Z8xeDD(#zud?3k>$(pWznUgSd2y zyMC25S~~^*W`#r(x=}`pHnpPg`p*GC#`dRg^s7gmu%*P}s@M9w^~UG2AJ6qQa9Y?f zYW@P!ZhG}XRTcUAty@nUUOt_XjgH7rS$z-sMLA!gg|QWu6J@g)1lz5GB{vLML~qpn zhv(#dqObeRLyK=9+<!!T+KIGt0tm&WB<Z)W;9>wRVEqCRy@U_Sv8rZ`w}Th+#-&Ap zN&4G8LZwX3(V+_ht_g6TYWCwW(u7Gh@~cmPI4@d%HW0)d;S3$U(^~^BQ|ivmxe!JL zUdQ$M*TNmrQO>r(aY2HjgBHLE6p7GcGXU^G&4VwbxH(p_q7O&h1sgvH1rk^q7L6w0 zDb3!;H`>9fG6iEWsmh?0s!(M=3B6njUE-CgJiwl6stNB?3nJ~mV$pW_aD(nay<ctt zrbSHemz1o?>aKSx^V`orj5#y7DbRIf_xrT*4tF9c=p>*m+!N5S{+0>?LR9@MjK;N^ zl-(`B8_*zBSeOZWgFCyQ<J-{+Fz(v>xz5wqX-@HyN7^Jh!hL!g6$POg&$Nc9>ihN{ zMnBzhn2mhrHDAAewfY_7ZQIcT42Bk-(}MRQ3Ir+$3r>czShjId>fE?@z=(c(Wx@Rf zs)_0r*Xh&nljbSf&wey~yGH6jSj@D^JZx~CzR;AU`H2sj<Pjr+W0`AN^bukC@zqmb z`#g?qT7JEMCq!WR%th6Kq(S9}=8eKg+7<SKQtG+P|0wkc$8`RPux`_pkx$S1d{+<f zm+x=1hS}rPv7WEy94Xj{&_PMF0B}R2gn=<1KL<rzi{cg_yfwQ7E2hKw$P&a%-%Yu2 z?wPcG@a_M?Hc;DLE=I`XI_?&cq#Nm}b&6$+Jn#i+S^3H+^FwEkR@7}txvjlMNVOrg zHOVs)W9F8+m?YEV?FGQ>i8ctv9g%j&XH*H%`sTa5|HJk=1u;WUg=b(g!=|N#GcZgR z{qd|9O=LA@S3-mok_}h!+VF!x>SU1JWt<O9cHopq=%p1gOXdt+|M{1OOm`^oo!Wu! z%#|M%<Fe6L(i_b(P=481%E3&aAKAKsh#~TG0A5=z9sYJEzoqqKb<25x*8}c1sAuf+ z5L@mW)iD(9pS%n`cY~{ek5|lWa7Luvccb`m56b+N@Fx4ZXxE{3tincVat1N6HmQ>X zhSS$ToYi<m>ONr`$gaUKrrxdoFS<}Qs7v&4RXAKbR7Y#@(`S5ZzT`&5$b9WVmBo!J zWH6f>lI(Hr7HIdOc|TjX+M{0I42f!JWIt0YRCRHqF`o8t*`_YZ?l9Q-TQG{oh}#}w zZq=|IP3nU#!)vC91NrdEEJ(hPSd!!3!RQx3F+mRzy<Uk_6InFb!;loi!&&>?T9Tmk zmj0sXcT8A01S&A&rnm?9)c2rQoHZg5JPvo)aEQ{(p3ns6q+ow-_OG(+3&x5jqv~l{ z#-uxIa%E63DDaonPiqHddby@5lLs6|sF9Fh2`0%F%?|n_vmkZig8kK1(nJ#~FQN!@ zD%DZmHb$=9>I?7Xt|nwGyM}Hn;;|f}OM{SF1c^yU8+-`e5DMnu8}cq!+mR3>Aj~Rj zi@EUW#TfMj@>Hs`v$(Tf)9;Efre$OFnc3t&PR)cASqv-yJCttWm@{q_0IfFfz9Srr znpB`y2RW}uN{=Rj>MequwB11!gv-=R4DwkpOvzQ;X{F3)rI3;LCmDmr<-cZ--R`*A zzcXugh36|=Odkj>lwq^On1DUX<k|Z_75+Jrk$w%GhA2TSsUAKChU&`PJ<v8B$)+bu z)MX9JKn2c2gR|cncE3#7s4zZmpnjNuPmOKf6b8myUz(~cI@g-IvPIoUvJU4p;Q2hW z53&1>tSIS5Lb#bKc|Z*R&%o|TaLoCV@EeNHVm}Wu+@<XC9l^>Wn?W5}!YrsW=Yl-v zVcP|%U~M81rAaX3XI0Ew>(QBe(;Maaa7RbosoFe7{SN~IiZjFdwH~ZE1H;aY8`9g! zx;8TT_m%@YV?+)QL7tMgxJA$t133o@BSh0^gFf4prIj5m9P0>|(^S{OOi8K`=Ui4E z<6rv7Z>|roSL^A~#j$<4z?mmc5lxcFnmtG2|D;btBDxYe1Wc>7U5I1V>BDipr&Dne zkQep%P1IGGq??u}!UC<w<P}vth$f3uhH17l9P(a})ptF39aYGGrc*j*(Pp>UHi_e5 z9oP#9qA%mAr46UwSFjoJ1ck>SlZS%|XM31nNBohXFlN4lo*>R3YHoD`DLRInLORoM z<sz*8B+M#gXsBi@T;-&j@D$9d*<gNl^N_Hp8Pt8IIk<IR7N{Yo*q3P6HY(<Z&NY)1 zeTGAEzx^E`3;#Wc>JKet86!l5Zb&XRNXC@}BSAMAb~8I(#k52txpBB(QvPx8sNA#n zgP#n`s9^71WCRkt*lMw;GCMlz`UiOMd_l1Gl^K%h%T`-F)CV|U3Ps+l-)NIP7#xwe zxe*t?3-xzcQ<U6rqf1s20h|iL@<5c-Pg_0~Us=d$7jcJc&lnsh2s}NH+%Cc(pzu$7 zPElDz^`&qf2({|_*^u&N`Ay3WPF`gw+NuvOKbaO7CO>}i|B#i6qkyr@&>?h<b=Jw; zQTfWRhhg#9y1JzTeS8Wk{811A`5JgKD!+~M$;90^ozuHTa5kCs20V$E&^HAdj{;lE zUXy=Vr?4|OxfxwVB#2tZxmU28+Sx6KNo(Rb@(yH@^dph(fMk*m4D}9ipQ4Rb*4EVI zGm0b<1*$jXwy|#a$3+GPgWE(<6oS^k%U2O3Ydz@*Fz~9e!?P#=$BrsE(XSrIJ;`bM zs^DR2jZ>rZ=zHlGAkS7?rmI(x=x0(kl)41a$RbI$t1<_nPk?Alm0pQ3`B>Q?+6ygm zVLWe^=zYQV1-b|gh&_lGXblpS!RzUhS}lPQoKec)3oa+T0@Kz)vL5&1r`p4PS=3Ty zI04?-gtzvdS@>xa?RN)SestYf8<g~pn2aXm{B7H}*mP5MebM(4$SYq;dYBAGTl@&{ zQ+Hhon<6<&pumIp3wF`=@+SdjW+K0Va!SFoFZ|>=axmn8d^MZx=FcKoCtYuyOd!E& zublN)%No=bi;>C!iOXyxufc^PT`h^2CBwTMe@gl`^(1tk_;_d*J+51hINK2xt)!o6 zQ}v3KR#n2|GVZa^f^$g;PKyE+Dv!&nEQyX7`ua7i#VK8F0#0gr=BjJZE62?C0$>)2 z5!=;+q$^m$v>$<Sy0)2aS-dh7VN>dL$kHKX8yZ1?7R_WSa8h(wT+o)s5{V_GIQ7A; z0&;N<+NgCu6#_(7V{L#(YU4oU9e8oBUaY`c^ToHD5B~AIN$#gEZ#CR!92PFkfb67- zgyyp%KmUjjWOXmeYxINNT!wk~w?e=$F#eb2)^d2>+7F~@YHVqf7&Ud5hg~8SSOrEG z&*SH@GO`SOqgq#ph`_s~94Go&Z|m~=NX4%35rowHtWHRX7eJDpd+iI1+I|c73pPjj z<yW>L)EAI*f=$%(ms}+(0F6%;w65)yDH{-2O%h}|lvAyxNMU`JF~UZ{bm}E<B_8%e zG2xS-4Z<dcti*bk(2#tXS|p?cw2AB)jM})hgm!X^3vx~oP`GC?lMV&*yHs97ShAG1 zZ6RziHa=1StPeq6CC&bu3@WyHq^4l-&nLedic9e(yGR7Bo<2;h%pl+g5s+y<nU|80 zW<&XBBtOh{hCWL_`}8#NM7CCk!2Zrm)%CBLKo7Ry4I8S<_A=XZpij};_tb~ia(t%| zZPJBGWBQ%RjClB*6*P*mO?6h>Bdf3{Zm%_QToy!c8C|E4^wvW7?K^SOdpSj!3$C_* z^D>|dczJ-=pFkkrH52`=f=~nc5OhAqIT;y<y+`z&!!6hGoJTCwe4Ke-9&XV5E0m0= zR6mGD|M3(3m@lhCa=tT`7Sm@5x*-h96(6~gA=oHOVl>N59|r*CueOEW8SXdEcVkNl z()PejK~V6V>54}g+`7;T*rl$Q&nM+Gq}RwK-Pa<WmBEJ(;Z*>*Nq8(X1JgWG^Menm zB6S>I(juR>#$B<`9F0XI>SeQ_F<Z`>&(Po?nDDmmf}9<*E}r`g`3Bo%MbhY@t-cX` zA@;GX28m&3hvq-XL<g!(r0Ip)Ib-oGU$R(R&;$zO@x{kofnX5RqNkxs)vm8o>Pcx& zcseelvh}8A{s6YOx(<bxy}A^O*7~cWb05skXL9`1Dt7xZgkPwe;%ivdT@!`no<KNC zj*b<+$<r5SzoI51Z&VE#Q0<Ua@Jwv-&i5v1LrZ}&a#Zz-aTcRdX-}Y)Lzv^wvk4Jy zPe1r8Z$i_U*4=`PAZ;cSgdFKt8&KlB^%S&~U^22BS5yMU05B(rp&=}P6C^sKtl|KQ z=IUran94<O4fvQ}rXtNi7&PK_VCD#ENIc!=Eb&t-<3R@=FZwOS<M<y3_oBNN^r}Na z*kB7qWsXpX5Gsu!zTxrqBfUBdk;X?>v$yE`{Y{LCRP_T<z5g`jkwb@sc43uKkhY{s zP6&KNBd8AdQ#k1{nZy|UWi@6LC}Af2wJp$%2+(9})1B~0Ao9Ex2X2498Q?0k0TOD6 zA4l??rFZ%0xJB)_@9ED8z8*w+F;*TcMn)dECl--F7DQh(uGk2e$rbl(FN4$JGTz=K za2sxMSxu1|+zKg;S|>aWpitTskVT*bY>!^8mYv8BUNk%{r1d*KFbRkA2q4{AgNPLA zoa?&H3D#ksCdwe5Vezd3;(mkkE7TU{S;FGRlWf=F$p#xO<(kA}N8-k}J^=|g&9g(J zCiv8Te{e!Gxn$9!LQ#*iho0~AujeAKOK)y4D6qpGLl^g8@u`o=pHY3wlgC75_tR7R zAX*o-*M6Ohq{=|dsH4wh^EkY9k7@|PEP^+rH5X9~zW*W5Tz>mH5Nc#HlZ@NU8c~ZD zo_}R(V5(9n(93x5=S214tXd4raJffcR95zrI1WYID%_N?-N9O8ilwf)2))dT7ay)* z?M9+{3Jo{`=JJyHbu(8Ee3K!$TVQjYrMEb|%E>4%@(I<V3gd0Yn>mD2VsO0HVkY<6 z&R`_P6L?_PDl!!jOi8tv*-Y`x>TUmkt`#`}QU?7lwaxjWUa4X#mJ><Nd}05yG7nqL z9J+!S-Sb$YZq{^ec3_$1&?>U*NHc5(jw{Avs1tJ6Ucqx;;<#{FGrq&#KnWdh#%g-7 zoqG;S_d$lEk=&K%fNqhXQxWwf4B2wK*xdtm;<%o|R~>rJ>mU4v$R><c3^7YhO)`-? zzhcr<Q9gsaik@!d|MAQ`Fj6rgxwB$dYC_lIsa?ldqt<`Ucro)|_a5ML^~IlI+K&2f z4c6~Fy)>K@T|E_xJX`E~<XOz5EnRKP>YSL5Y)~fE2^V=Q1>Wdo?8dL_bNhgjYcEZJ z6Pa^s{qr)Mcf_y@9Mb0tuh<;p6eY)68deE}Q71OCemYTHEO`t23>J~xL9sacZs5<N z$W4=2SkqToK906q)^f8%4CZp2m=fBE_lUDd)Ya5_F`1_ATWN#6<n|>bH)e8PoOXFe zZCanH)g#eKjhOC)ZsaThDlJX}SS33H{j0Pr4m3~?v28%SjGnGLR4~G2-lb*_$|qq% zO0wgN&40kHqzSO@#W9;77kUt#lHl!&S6rJ}cY`NtG~E1Dc7k*_w#=0InE$X*`kYK2 zeY|W%TeN3cDL<NwoU-4H<zlHwbJ{tx-+~J%zVU}D_QeK@<uH|QmF(scsGF(L4EuPe zl*3+0qS{l}Qad%jM6&IDAxAwzAif5lD?{&6TiZIE@__kj?^*LD4hq3n7wA28j28G? zw*t$b3w*?Ae+e%5-pbig+CLT&h@9(~JrYDh8nL??uyCt|<=97Gq4mEp%Fw<Y>uf^X zBm@W;Z|(L(vR3Lj5TDgngmd@|`K3mFJ*Xu&AHK%>C5_f6+5%_Q&tk-mL0W8z9C&b- z<yV>O+T`EYpU+%V?wtP%FC)4ViYNg<UP?xg3q2fE1JH0+iy7>1OyqySC3VO`+kcQa zhT*{%CjTzOdWP1wE@jWQlnIe!Q{VOHE_otYMquY&`=|RCs!af5>U=o&vod20jloM( zoR{=wC0;i)<gRHu+Hudeq(U01l?<zDucIeTX>Gz{1#?T5m}%M}0sb1iYjs#J!D;>C z*S_@?^CO;wRM)DX8`3>5)yfk^$5=KPCZdPjM!-Cu{K!EgX6e1;4K41eLcEUE4lUj) zSX}~Lmw*3NW?`2mv{$wWP$Q*D6AMg~X8N~~FrnfpaF=1O3w73dbk_B-c!!q6w2r~n zxJdJ}btveY^2%VtfWZRZMp>v`lxGw46)w6=)0jk&B)!grkRSCxdbwhdkQo#Z@4gsN zL(@PV+-5nWkv<9`<w@MQ5}T{FRt!#Ys>eE2o6%|*|4b)MH?Y%?mJ%9P&Ff8T(zDD? zLov?tjjYp^r1-Yi7k|F!`6}~lAFG5@qiXN-=u(lQ$t6L|$|r<fXD=fbnoR5E<5bVN zI3IR@B#hCc8rp7n%A}IB;wp`IDOAz+0;N*;P&+~FG>+05Q!v9();+c5jcd!>mPiKA z%zLqWAzf*ujpzjqK|xW$4|HDuUcHKcW+C&ItM$wF%;4*+eU$^y1Cj}NEv6S*D&$!e z6tcjEhMoceT2MHgeUEX56WCgCvZW}CrIzwE(U0b5MLZGchDxesPwd{QOCXM`W#BM{ zu8(mvejLrJIWxJ16W_QbgRk;D-DLd&S#3<jk|6p#m&{NV)`r)As(WPm>8lB|FU2W* z@6Isyd!onbrjWde7OA~bfc<kI+rIKPGW9(Nd1KZQqkWqEm=k1!%Ga?E{NbYtELziq zwAj>QL>UdWX$77(g{Lk`eiW;qB}>_^JhccKt>ao*3JrV=SV-)eCGHfbJvg>#4bSMB zP+JCCrOLJ|+4J~d87AD%_PXyq;}f*}`v48-J3Q77Dc{l7;|0k<dnXoXQ!2=&g%O1L z-zBBVdQHQta+)@qI=N9b8MmJSl)n9qx7d9<r%io3Q4h1P6{RjC#2?Q%otJ?EePU9} z9?>p`b+27dIne=;2JKWbwBU=kdG|zh$mvrgP7fh*YwwT7nlf;78(5{Zso_N)_tfmA z{jd~yyF<ZViMLS{{$e+(szTgd9{0ehCicz3IUZl1`hG#OK$GXLAWFU~D~i;&-=L+J z>f+EqneVrMq|5PgNcKaiASX8q{2j%c{jYik^cnr{W^S%D@4!y_4JP#{*(Z4aGA^7^ zXH=_4#SnJnvLJ;`e<pfnSFj*!?c5`a3Uti>r@|t}!A%-TI<(3wN=zuwfr+AO2p_wH z9`-GwQQkT?xdYRr-1A-0<+2`Us*$*4`%wq0m+2N6?$w}6rENl4k36RTV!%7<xp_!o z+CK5sRa<UBq7*Ry@T5Y`3<9q4&TFBJAYeA{yCWo4Sk<b-s5@ij;uq%IID9$+B{n*6 zxvhX&D-c<haSYRtE%UGRFDEo>)fy?R?@ZGTWS#SxZ4#!4xK8}Wc}SO#ybBV=@u!7s zAauCUv{;{OSkI$&_STf`a-lhy?)X|UUkAR&SAqe<Y9PI$_ib{#Z|xfnPo|dhDxBp; z`LQbLbj$`S*&&D?3!zYXb0MKBdc|{Ufvl-Uc0ZoI2uw4o|Dt+}*SY?T4I<gygH{~) zGC~}C0T~OY%mNIVJSPze2t6EzW#j3xoK)sT!<ycPgL|=uwyGTJCNP`hn^^uW&6&ds z8k*BfArvdF9OA3Qb0V(YaqTyLi@4=1E<_>1nMyNq#~#g{j-JUJ;=_7WI|Gt+H}hKh zwKCA7txyjm)6^@wGnRofyLN#UymB7kEq~jFXty-!wflKv(V#iwpRg!eSQUWmC`!12 zHokFd2V>|tds(MzpSJq2fH&uOtRsVg+5w>Qbmuk1rftmqVjZ_+hy}-|-x|IJ9|gG( zmTF6@Ewf@rYoUmd7bMp@TiB7gLh)(R2uffCy+b;K*AmY>CW6P?j>bWi^KLa-8-UDg zqZS7>P$`@3E}J0peMFw=D7EhV;G;U{+P_`WlwF3|t?B&p6FksmpI~6v!%#o_$0c*Z zc;a}3JB>?9=<NORScqi_nZ{7pBFMib6ovRQJp1tr+9K!%vywkA=V)09LwG-cZioGZ z$_93kI?-WcANLAJ+zlw;Uv^j@y0*f5CKdQ3fep?I`tdgag~#pimLfUrOf_h*(uN5j zIj~Ed2-BnHJHD2e{m@ehp})&-$6m>oL#8shTo#5W(UHif-f$2orYM0v;OoA9ryd;5 zh?}eqqk<dd-BN-DwbX)OlZm=-vAjBpV$-~??ht)=%-wdF;?hRkWUzSX;R77(qv;|s zIEcNj5bZ}MNuaGm67~@5(=z;_$-uSmOTEPsySwO^=t;+)=krOOg*<h$;RSg&GiTnh z#NP?k6_d{sp(a^EK*p8U`S5I`+A`*2h1^>r<IhZ&#&jK%wj>d1i40c40rkT3Y;`lM zax>xEMf*4Q_dbQ*->7KsJG6@AR`3(m?D^Tx(6{MjutMjW0dtff;b(7r6d#N|GyaY) zMNZgd*_GY2KgN=XAh;u9JhTHidXmSc>n4!wsjJoWGofmINo9{bsXuV8Msqwo<G=+8 zF*FY*a6C>$=c-{SNzZ9E80dz#D~bZBfNx5GN$L6cEOJpPYoOF_mloogS0PRm|7hMn zCn`AD|A*-d$p9sAN{)F<4Q>y2q=*HaU9jKKWBu`pvfJxd=-R+Y#f41%>_ky>pf>>= z7^%`a0xj~ZL>3Oq#q|Vk1~`~a86kj{=hiyO#zA}oiKQtQv-pfsfr!IZImobrDs&?w zEGXKY(!Q7yHQi|yxv%E;S?dBOhCS~D+y{*!TxRpQUYl}@?8A2^ppD@!CS2|m&=f8b zuEXmAm2J+pHrvQ$&{dFe$awy%w)N$|RAlE>r&rrI=RsVmN<3cxKSV&XHuqiO7dl~R zZI8o3PjS><ot!y*`8_S4Ftm1l!!$ZM9@P(<@`LRa9WAWTk{A#JMTchxiCB=_`$V3x z&Z+Y2ILPQ*SMpNp!8A<UjAaPNOoRljd9kLhZo@YeT>@b#>#CRoRbu3C9`>rC`?D0Y z3cRu3+bqY-^=F;^j@-S>Ax1V#m7B)P=X&-%$%1Rb{;=F&fQ}KF8)n%3;RA%W==*1c z*02^+jD<)(BP}e`zD$j=RLA*ubZmZkZx4#Ug&8CJK~~f-)W9ZgJp86FuP#=a%uI7M z-IH%RZUK3;Fs{8TZapq(T>GL^WvZ)rYK?*Fu)EL0GPfuW%Yb+Ur*JYtqswc~#Ba68 z=6V!Pmu-jDqa#)jbqbH}_Xe6=xf4LA`6b!C{UiDgM*GB^zR2ri@bgk%`;KIadBKRl zXZk9jT1@w0+-yw-#^ixU(QmHI)VeS7TW+k0`W31E=vYtd)d+{S+$|?c^JfFK1I>=t zV<99VD^36GvQV_-mqIUHM0{>isKNC;tzWR(=<?s3Ia}=XQg7`F&%_A(O*A_DnQh|E zBGcsK1cR<P!G}N5Tx>%FS)s7RntJxZD;Igf>8F|o_ci%MrMoLS29v@+m2So&lTVKe z5C~D8dMHMOGQyR1^M9upwBS#qfZ;{Sv%3J<jrwW8nu+nxv{CeSy1Ct@q{$@Rr3UT! z7eJEx-Ekprl2@cAJ$FG;+<tP^YLv0?zL|q*=tIUF>oPPCab06bw#4^huOvq4i--y> z<l?wE*}51SD^o1$fl%)v(}acw`})HypB$euia%u@QZc$ES{WQWdlX04>KXR*Lk2b3 z<A~|^>QlT_M-0Qir;{eVVVb$(tKlFZUkCjtMN|x0>+}ep1pfOHpjZ;gG*M!JzJi&p zG!RMf%{p*E7P{}zC>@a)oxx+$ie(UR{lsdu8D(GRCBf>jNe*}YT5P#blwqqF_Raak zPb;4qo5;d&MyrqPJ-pK|i(KDELws`)!{32spyW)9%ad=vb%g24l0M-(No(_+>m$;~ zU(Po)<Hb?GZ&*LrFXZh{KgiBZubEF3Y1K%|HP)7xcEcg#Z^Vy;T64Wcd#>0HSY|+q z{gzYIL^EK2$fxNE*<9zN$=u?4{^|Ef;>VG1G|jM2%WgC?x%$a~_-U*ltA$fRcfqZu z>5C0D0j}7!VR_|l#?>idyVSv5fmvL#hh%xo?8E^>?AyB^`BG;6c2l`xE<mQLuVuc3 zQFB@%ml$El%yU+xXxSa8KQCCE2eL6TcQ5Q@KiNFSj+&(~oo_F1jE?*&?rS-Ku4MxK zBBh23JfLnES@_Ol&7{UaG4W0*v-8I3l)fR!(u4c`pdklKEdCLXmu%xh^78j}oy8`} z{fdsq&k+^0vky(=jJn#s^QOeuDF(oP{DMh(Y+kQhq*1x)bT|^B(>+2HH^7)4sWG+J zww$Xd_MAK3+9P%jb%fNZf_VpJ$WJWs1`_?72qX*!=$GHGQJNlwIh6#!Pv>{Bs3*l= zhWI3&{9c8*79OtM>NDPfU2M})R($AWXv{myhhGZ@bc(|=9!`?V8PV^biRk@(4`?u@ zP$i>@)7%cHXu>N=1Y9Ef9#1XR$mQuEACajM{~z|=GAzoj3mX;~T0#(z6p;o&DG{U; zkdP1<U}zPP7Le{#5m6+iJ7?(bZfORP20^+(8ooW~9nbT9&(H5T-XHJ3`yPjD_O)Z} zwa#^}bF~GKn}sG&?%OmaoJ+B~ahYM#)RLE}amA&1yV1UVJao<TF#6LEJ)smMX?Hrg zyXwLz63K=WAymDpmY;tasp$~mudYzQ63$V~QK@y1>MMv5gz?|Faz*@#tfYh*b~}^5 zfS=Q1oFfVEj9g-=siP)rHJdQn?LDatzf<sLtC|F8%{MDReeor0XTi+{Jx<tBam-1f zV8M~=p=l`lyQS%{4Gxg0o>rC0%iOggwVp~YVkSP033Ez9vk*|<;$Mhaw!afVFrBx5 zzXrf)%pr?STKbQ&Hi&G5ec=Y{Sm%H>JO<d25t;7@?YIZi^+lU)BK`Fg4ouQU2<Hpc zrog|wa92IyIrO^%3Bhd+kZ{r1QuppCC^|`Zd{J{^hR%HYiMY&GKDR1)Q{5&_Dna)+ zhI{^}YvDxX5;+AU->Rq+pi630(U4ifrC5_mpZ&mvD&(dW;?6EA3oP%DX;`s0)=7k? zI4*W^RedANa-7a2d!?hB+{;#TGXbzrZJxp7s`iJq<20#R1~dX=Q%JSQ$UK1Y5((uc zi29Xs-ot;sFX7q6BkBU^2$NZvuDrOVRKkae+wUc{aBB-c-C?|~k1cxZ3L1`hqL8=P z#t<@ZVeeyv=#m66feTtcy$W@tiG$(`*ydEtq}V!RmNj4$wOZ*h+)R3wq)2qGR+TCz zd6nC;e;~4)!YDk;=x6`;r!eYv+k0F~5)|Z73nQ#?H)u-YzYPU>(be{Ue-Z8u`1R3F zlD-o>k}c*f{qli`zT%HkF|q!S_o{N!ifTXBO1f<G#=bh#<ksjXCU3F7(-Zx;jsTYw zuk*3uGLv;1Zc*XeVHJ<F2*yPJ$3tabBNk0e^Bi7;)8~2Ma|=fjlXzrpJIjWJN=5Gs zdKrPu<Dkw48t&$s+De!<i=Cn`46f_~X_tF<zRQs{#)fGKa64t~%!A!SQjs$JOD@R+ z!6xax*I6iPMoZFjyK;>;)Z13j-SU(9@i;;uzMs!#n6^8bpEqE<KObD_%%@>ec}JUt zoc*2X3QmSqG5NhITnW#f(^szXBn%&WkcO5Y2l{Wg_lKj+x|VEsKI?+ZhB8+K^xBb2 z7ak%Nzv1<xIq2vLVuRMg65<CXOL*kENQjF-uEu%$cG>Nkn2tvE&Ce+Af5>({V0UXN ztc7qZz`BvwlY4XRM1`B2TP9bVMpD|A=enePIWK<rY&>_VBO9^CnO<#NY-)=V-A%R+ z^dMTKbktFOVAHjg!oksaBxmwjF)U5Hf?N^)BYGu8(8ltka7KBSkNVZOzUr1vj#v0$ zb;ou#(s){;o~X7vFJ}gqRDYmt?%by6%_=W#iwhLpg;E@8bn_XSb#T`8pgOCnlpa@U z^qr`wDI>oMAXDpF-!D%+3B{YmhtPxFH6JOyWzD9E!|9Oi1DnZCl%l-A_Z!a^H+Twb z6ZeDT>Gg!{XamusY;-g(HU)YTbxiK&0H+VTKzxL;CBOqW;<Xwk5mJ&0DSTs19mN%t zwa4?T$`*H%Z&r<+NxL7dJLj5z>v4$?wt5uQ+dB4r=mvehTz141FM)9?+-K4d?y~@g zdgsSwhSt#?ID-g?`2*>ywYJ--xSvcj?o9}{Hnc%;T6W<*j9&3=3KK0{$-VZRmslip z4&q}0r5{rZTs+bG=ssp$cl>6ySKL6MQ<zwW)U;{)v|ubnl;GVA6R#yzg1{-I1r>P@ zgAGkJglPv4p_z>?RvTb`PEYIwN53X^P03x3^{RKhStUDhH|ZKO<5*#dE`%LIP5^Ca zmSIrH-<Cv9RJ>7@a$MYxA-d4pa|~T2wwMW1d+YJKq02M*s{xxi^sY=c9+pGE8*kU3 zRK5m?;+)om#9fIm*TwP)g96pbuI7i%9hI)W7RtBEZq@L_@FotHA$>~K@-wEpqduDb zOG4-8De7eBEW+98NBJ*O<lJcq8=AFM;ydq;CJEBC(5}Xlzdu3FVNn~FuQo91gm3WT zc?Y6VaE}sHuzzKIv#4@b2H40fJJ-9!H5EQYuXtp50B<%j+b5tS_0U_aCcEC=yGyn1 zhXD`UvXDOg74K+VNW?Dmj#jbEspauWTs)IErgk@_<O|lidX>Hf3eK}nI%n(fy4Qz= zdz5Pl!FIi$nTO68?i$Jr@#bqH9F(?9lY8G9_y^ZrKRKH5C1T!z>e`6~;Gfg-5D(6A zvGia{6U!c9a@-~vIrZMbDHHpurr@GKauPB18N+6f#U{a}$A1u$Yak@|NgbqCG;|KT z^;!U{i!@|708F~&oDTh44cFHivE_-=PbN+_7b5lPC??|qTZyh}kk}yAMYK<gTJ>=t zo2desXH*A<)F>jQS{F-xVs5J-wAKad=#^qQksS@f4>2%$?;)YuDPa6`oW);f*@}#2 zUq$q+#@*5K$fqjOqVqO#E^)GPCw&?wxZyD|w@c_&Q1uX_Yd6~fQ@`Z2iDmE8&q04N ze!?L9WA}GImNgf8V;}Hx2`!?|k9Z;-jtN$A;;no$g`>nEQ9iy=B>p1>32vk35<QEz z(RlK+bMTBIaG&ps&5van(&(0=AT{|ih<)c{rJ7W%bBAouDla3u9-YTVmpjCUXsv!M zM{fUWL>WuV!O^nnf{b;am*}zWjU01>fEb<x>v$nW{wqWgG8&lVl+XraLg-+IQeH^? zHBA`v7)j5Q<k=3E1RZ-|U4?9TwrUnuC=YLb2)enJt(_M65|@U=5uIZw8%0gc_PjVR z*k-alJl#*uPNYCs(<ZmMWZ`gz!<z-Z5_}4x)>M$}uc#dnr;kpkmEU?#`g4CL!y^E1 z$HsXnR?i`&@ok=rrq}-RJ~b_mp-i~m8ajL}HFC3Fh~7v~R7v!WJbk_`;@1hz=`#(| zX}2tIrWY!w^+eHiVLQC}rHXPX(~lIAEjz!d=m76NWRy}<Ls&wM^aTl1(*gCQ<JqQ4 zf;aNnhY3$%+Hzyr4|#P-nKH|~I0*L8xwl>Y1z6ALXf&&s1JJWoov!@c?fS*bUXMkd z4Bh?N9oQ}Hn_+;IPOc?Uots<Hqp^G!j{%Zj(OnuxGVgH^u<RC9p~(b{z*~;G>*_f8 zY%ar@bt?V_CE^VFB`j3v9PrUsU-RCCGAm@e?5{w{H2a{K9M4FcmtFGFH28#TfgeXn z;sknQkuZF@a2?EmC<WZDyl+T?9{D7o?s*MSYSm3Y7DKnF2HTCWmL=NGwn5?WsdW|1 zNqsjRcPy^wDpK}~7?Jq0+rHrsp$&4M%}lGWz<2oB!q_1kqaiz?th59!pYcYXwFzY$ z^ik+JH3X5_^?nphN$#yFcQq~N#2uft-4net%V*sIP3v&f#aDmeAIhjOuu{2E1Hg%` zqs0W_S@q5LHk$zr(&iiYNj0BonA+Z@K_3y6-S025nkct{x+D;~rB<5j9qumkEmK(e ze)_>o<bJA_;8OPaC#k@iOgNXD9;s*l!^Ua;o`Fq;i^g7+pfj`R)T@!98=5~Ft)qkp zPkS}wNi<nB0y7Tc4O%_~!l%nWdL=W|^lERCQIRe?QzHzsB0LZMTJO*PV*gwpCq5vo zEm+%1+aHi%;IAi$*Y-QG?1kWQ)o0f<418tpPF*$X5({oji0%mQi|qE&CNdB)R9VP6 z-4CI#U=Jyg`mAT?W29feEm=E7qQnnB2Yizjhb+4GD6I?jcusk9yy*UquHS#z4>ai( zeJ9a4d*E)Cf2V6UU;IXi8crM0&DAtz@@J?%^PxLe+i-8LF36naQ1ovd*|m`@y9cw< zwB@K~D9WlclGHaosz5v$gq3yR!MH_dU1XjT>YyJczZ5e{qbaq!nlVz~QANd>hW{ed z`#mQldAVtNzmbijBVRCrOFwtvlNV>=kMmMS`p%GhG<(AM+Qg<Lw}r~_+eQkoK0OO0 z+jlSZjWDV0-=y;L_f)lMi@vcVageuV7(TaZq{pDA(>EjT8QAZp3hQ6eqZ-*TIo@(S z(|v*+V`JYjAB&YXTWyb6^kE)rbZ3U&4M-BrJ-+`?nJ_Y($owq-3S0;h;{i3zry*#t zZI-09SL$DRUrt<7`fFY8AnO$!h%7Uy(G-@_U52r(awk&VW^M{BS0qF6NPh5rp*VC< zI1R$?dT;J_Ggy#9Bc6G@X)a^Kv9SK?GzO|tD=dg$;wGcWVwmE=j#}v3PO;H;4mQuU z0PXD`n3@T%Ms0^QWDX2r>nF!%$y{6}JY8+F`;=sq`xAk+uU1@z;1aM~8J+rz{2e#T zWn{9GA${e1(N0&DJeFyn*$;J=mmdnT{P=ABUTaHwaQXf<vW*lD!!YSh?(bL%j7w!} zU211WqhBm#jIPY>2Ay0LFzYJ)8n(^<?Ao2jaP?$~ml*~Xo+ag?InA1$2wXK!nghyL zj3jq90UKYw^KmQvvQNU5tpzF1&E)}Gg3ADVM=4PcqB)Jg#3wKRZY8pZzBt>{sNAK- zG>Q~hN`ofH=?R4A>D}EQNHL<BH7YIX(C79ddCSDiuJ67gk=bCYyP^|Q={G17i$gPA zCDcK6XEd0@G(VSet3EQM=x+DW&iz<V_nTdKT6KXy*X;ZL%WS5C6^s&H_w^i;L8LCa z=gi5s{RGHq{*_R!xLn}5cER8)EhhC|XjX}gHUgxxIvZ@&fmmk*kn>k@X|VjRs-o<O zg?!`56z)xaWWZ_#QzBYMMCnna<^`L#if^2OuU~VBvZn(1MwZ8u<4G*);s>isnNq$= zc}fd8u3z<{RnLZbEwfe_ZrzFXJk(S_Jr?eRyhV7F2+_Mu-t4NBj`)6jqJkqJW>a@m zj}5bMQ=n@fP$w1XPn58nsGo==J6CfbfEh~d<}O$H5yJZXy0+R#T#TZUnLbmAAMYL$ z__6rUb-pj+`?b8E70_UT*iS)6?DQE%a7OKo_xVLdaJ^-rNf}n?cUd{O9-oRg!tH|a zwq`!)Gof^QcLkD7+9&*R$|lA0RsZJkNm%<02iIi5=qtydiWe&K<NB+;_>8oJ{!{*C z#L3&M^u=-=`WntIWkL9rBk;8#fic!=(;0&qJ?2LxWf74xh?D0tRXhT<l2Vk9Om^C- z(fq&;J(vddgxLm4*az`xI}4(1`h)W(?5oce@XVyXe5O9zv(g(<hv}}+iXwL$VRy4F zZ9-p1OA=HC;6<jKla!hC6_qL_h_bDwKQttRA2|C9qNy+L(cqjWvlwxkuV%hqTTR`a zYKig)TrsbK`z5>)%@yVE=Y*>V97SQ}80<Pj&NX=zBCadBvrv%CE=KqA9%tb`35d*^ zDhuIJ+?7f$_6W?b+xZxgvT6GyY1%ITo)H6!f<tQyLBgP4z|P1@$d<Dwf-E`;5~Sot zg*(X~bf3R=YkQw7qNAKK)P)%Pa#PzrPSnF3o#6A<x%BPdd2xQ>yMj-2ei~?bsM<yG z1Iu()%e4NwVrWM}^I0Vp!4<<hDGmNNN6p2VlcrC6!~Knz_rH(@`Cu_dHAg~~bo%PG zF~s!~%B$x&g!Ds+wb--KJaj6~W1EQydPGvn9sGJ_Zv;_a8EMs;#?LQI{?Iiz@+_fn zqIW1G^_02|=5TV#xMMsgdV9j^)2%Ds-*6x?2ZCjqHa;mA)K@)SG!#ps-Vd@99vyrl z-FBm_yugZ)QkSikC!6<aZBsg6yQgxCH0k@|58aQ>bp23S(fEs@`3%YL`An~MYLE^h zp-qqCH_|E--f0ZCDC8d(HYQ|EY_(5nYPPFKFP({Mi78BFXhn0GcjV_&Z3tJ~ydh*~ zG8S;JLi4@ihFPI1$8)zEVjgbNXIZ7G<6Vu5i(>m0+tp7#(JU*Ctf*SC4xEwOt(Q#e zo(^SuDKk(Gr;_M3)uGXL%`njH#r~?BwANA3e5Xs1nftu#%F2jfLcwfxN?XI*y4-1% zBZ5z@BXUoWY!7FNgPI(1#8KeSO>_b^3+qs3)c<&i<Dq-wyz(B$!^e6;eu!35FV}$% zN5{ufA-`&kc-i)eO@+L7*&wSL?rI?NyrEDXA1ifV@4>wx!ik0}{pcL3_*kFGas0>+ zM~dowI5zi5N!JBLOa~YTZRlk*XI?a;U(AwUb-Huos}b~Feez@pi#3HoL;Zx0gzA9e zf@qOAy>(S6w!G7wtz{E$XkgvEsBiZJ&ivt$`kYUgkMc3Q9^A2J`f<*-DK2R(9FOhm zj_*chtgEze^Dyzvggs(9uN?bDE(doOkDK=uh^?G>FX{SBZk_4b877w=C-Ln&#BVsQ zL+8#h89re$e5hhUrfnIZ_n^xw4Z7bZww-jBJs=XP@(H+)uTD9{bP}6N;P)8+RI4&> z(*E_{fl%+0sw!-1kqTGcyOhy3Q4Ot8<mKT!Y0Cp?ftcu4t)@i*nTu_0H$5%9nR2SQ zNA@OgCgfl<9~x?uAhj>=<f{~m-z_z0<jESXryBAJ$02_|zu_{_a$TP<b&!|e8gAg7 zr;RUQRV02x;hJz+21cM7zB(c7Zh*!j50da6@{Qa@^V43I8fwrbX{{}IymN%7te#|i z|D{3N%DD%|h*W{6YD20wCVY2d`pw-V>Jz=-T)boI;n&Pxy{tW(mgiQq=wE0X$XYgZ z3LV5C*hEKuV>s3jVgvlP=#a~p0ks1Fu8s;H{`yaEyxYNX&Px6bNfrOEfBXAuE03<A zm2&OL;Q#%}e>?+xN>6|W8RfGshy2fPByxd~tUmf&{J(!@fLPp10pp$g|Nh4R9ms#L z;Qv80lDGsJWs;8=1!XN3pi|1bvxB;e9Qkn>ZG3c;(845WC0uIKpRAS2jQgK^@Si<H z%-omAjx$TT@9YM2*T;b@$jb{*){c0VA}#QG>Y@4fLL+zethr9BvEr;VP(@e@^e@Y6 z1-F|?bDlRP4=!`$>YLpC|9rT(DG4i{k>$ojMJcFa{*J1_YaRhWY3~#$$MpG-$6b4v z3_8`nk{Sstdetj{%u#;6Hd-*8^cedDl*^-1L&F(LH)9^WF;4oBLG#b~`Dg6lRE3dw zyHFUgD8*Z#LfsnB8JN(b%xZEC)R5)ViMU+9x(C!7j8K#&R6kuz4&G27kD~>O)seh} zbx^2W>a;!gG-T+(r^7ms*D3{^g!1avkCZQgA6HQWl8^R1F<1Zl;Qcwr%BGMNs8@I< z3%+~>jdJk9!uxBtE%uQb+?ryb`4feJLH!ktsY0VJJasE(Oai)xqs)r2COah0WR$Mi zKHdUFwpt^(y1M)zrDK2+4v_uG^tXlhk2eILMv-RTM^l$y1$rw_%7%22mVJrdlc0{Q z=fLDAGEe(yKr~Q|&`c(@2f`6qPlBk7Ms(gNSn+l<l!3~w?^ZSY>Lc88zd((@FvqOv zV7k#4{AZV@>Mx7*&+jRJhpb3>A(@q2H!3pRLHQc)F*dE8vcx1|<_xGRpF(9KG9MSv zw9oCKdK_mW&2`2Xs2-iofgN}{bF7d6`5)^fo@k7|&rl!lw$mZtaeA0K76*Poc6#?r z%0sbNXcgf`5o&*4cYX{X|7bB)?F`H4e&PelEbl(Ygr6FrxdH@qF@<#pK>Yt&jSpYF z)QP!tD~EDEX_s3kjb|hW=MH?hK>+pr{k2pkWoxuwAg56Tx~+(0sT3AljF(ytRJeJ3 zIjjVwhEbe0fo$#A>!7cOg_78rUB4P!Ax2;rY{t~%ho@Ujpc*faDelK_^z^UAQJ#Vn z%jW;e6g*igTJL*IRHA`VW@-zS{>#eKi+KA02gxI-Cxp(r9&Op2^38tT#aUhut?)2x zz^ubVa4F58C-%XtYQPVa8p#`KIjKQLhM`$;XZ8z_PH3~_B)5E3iJ;)tvpCtTs}tGl zd%T>CTp2q(+Fb{t6L&2I)noeVJTJ^T6dx>H4=v&Pokjd>UNWzuC%EkdOj<V)I9!|^ z2y0lqBA_z7>Av@@WLwv$FERYLsrUYd%h&nPZ1N?@(ii;#=S{uK1V|KRIdE<G8EY_| z5>N|#0|lsX$?KLgNN@}n??dIED+(<$3eWnH#(o}=Or4oQiGD2dzoDkEs@`rjqqe05 zwAoSsOtwjtY3Mn(45eqOW>k9WdmI_5RFkP|Hv9tAOyM6Nc@e1Sd!$kSXHVSfTn*5! zm>raD8{<US{Adk$19n+0AS*b_ZlIA+_+lVezdWI{d9j6n6_G@0m04NVxa@;-TlFpM z3A2PH@jL6Ucc1%+03q9+7x&%bLAn?0=}Zwc1q;(1#S6P?z&)xsacg>uT$Cq!66#o4 zdb-m!Qmd@;==av=VcZ&25{uGFI|J2}Z`edHPTvfk6Q4(gKNpbvvx(Gbys;Xt<Yp`9 zpo)anK-IDgdoD1J>DbN+zE5B!8=wy3*K$SzbDGk=l+OaHlQq|>zX1sD96*I|+K2d^ zYEB1~#zE?8D2q}l__;|v0M@4NX4T5jqh{C=7&>IKOt5;DVOq2$aap=T3^UW9feypI z!u`oGLGD|c7pH+CTzs#mCc1StD_3&^oR$e0C*)WO-vI+R3M!PzL|g7%o{J%$`edoV ziPkW!$)o^Dcl|=cfU36p=EL940TvP?+SDtjAh|+U4RoqBfsG8wMJD4h0=Eveb%tcb zeOAFfeO<K>p*=C0tY7D0r5^<Ln_${=nV=|=KbuS$4T5Kk24C2`E&Va`ts2qlmRF&c z-;5tkjk&XjrrUa7k}pc~t+azVMlf)6w^wYs(F&7~bhYWT*tsUhHZp_A)2t&%5*AR2 zM@1~J8Lk8?`B6G<RfKBt5Zesnk-Z*{;{uc{m~=zK%`BToQlENU@VNf6cqPjrRwep= zbE!Wi$EYj9YL}DyQ6Lg1lKec~22H5Gh`Mwt*?hvww=KK-vh}Jtu&kYSI+sV%dkC`U zhPqJJKz7x!wgiYCW1N5rZv_tiy>G#o2<Cc+(dXC)uZy|`ilFMS7Tu8|X^vZb0U2a; zE_B!aoT?+ne9%O%V(}C61z+ocT!VU!)~(u~q(aW9T(6fnjF|N+CW2F3NqD{3tPfmi zH&F%)9!Hc={xjNqZAev#AOS^X;Wj<0g6LV2?*l-q!U=p?wQ)>cx>m2+9o!pn#8F}2 zH}wg{POYi0AKt^mCNR-1Hknlnx+ykQ{QRpx*N#L{Ey$;TyjT%E`L%A|^o~eLD1#fG zQySeJ`(RKVbOmYVf4!bcT1Xs0lvYj;*CuFfdfr5E|7rDFW{{cZP>}ZozZ1vE>$<aH z#&)y(P2Uv;eZ|7}3KWd=Pwse==@TAugZtA?wgT(&KDY<ryY>qtUn^gQ>r`F}(&QQ! zAI$>gm03Rx++r6GQ?mE*Pf%LM)Q57JB1?(Bv9C8lA=jY7>8<)!@t@Z(_tkum*Hx7{ zo%#73ah|uow_4a;Zy#8_SrekXui#}{`Jn7#yvOl!>gF*+|6Q74T}NG4kdKYS$x8e6 z9AC5Iiph9sPN1m!@t$>I>PrGW_v%#qI#0@nPSzoZ*@L!OcTERU8E@tR3-6A&0yjz{ zkpaeIQSz60ZbkZX!Xq^U1xY+YwLH6#n?Q=gYz~gKJzL0FN@vr2&7p-%gRwAz)wP2u zQjh{SAoLz~p;r)oVeapXSlj`!7dt@GgSz%|7?sVAj-~*wajltDsd!_uY8=Si%*H>6 z&ZOow{#d2abry7*Bz7?IresR<UR5*+^>3$<Sn0|(e?0!HKew$7Bztq^8U+XTA{b)a zs19E}f=y=T<6FUg<rf<$X|&|Gn4>0RV;-NiBH3>qErp)=TFbohXS|PAK}hv6!G0Kq zESxmYtI6(`Ys1YNb9>se2eK7F$f6+9$e#)S4*KPk8%m3lKh|Q}&htFuxK+!Z7GYzS z=B<9mWWk@AXn{qy>tP9Ha&AuLO7=$7ZHb6~M<$o+o+gn<kB)GAXJ%@oqiLEJKBvgi zBP$cWV8Un8QKLh(w>d4gd@RcnH-8%UQ_BnK1&h&Z!K@&|d1n`qJ*LStG7C&p-~wDh zJNcHP46;=>3u2of3Kh!|(V~+7eImc%nCv2w9=~HgLJq(Eu)`g127TW=I#uIZMZmQ1 zhI>4KyX69?LQNDs>V28xfm1cuf%w_%gW5dachQ1~=8Lp{5Kg`X&Vu>kiu}vS1kdyD z>loKQ<!uK}^e)jM?9#69(e%64T@@R`npV$Q3YPdVMouV{A^4$dm-*@2KX-&0I;M?8 z;v|o%zglDb=enIv4q*v?q%?G_SuREbb?FYnHMmthz><D;y|(2%Kc^~hQ3_PwMuVCS zqplM!NBo%oVPp<4_SreoHk%i4tRtJ}W5uR68KjHqIyNoMHhbb5^u_nC{x+Ngq<sdu zx!Ut5{4_$28*7l^t%{`r0hh2mYlX^=I}+&<wfz}Sqe5;#;DjW0C12z+6yrEIU|&q9 zno-w~au$S<-Avy<tKn?_$BeG#W|P)3vm*~m`{NB;N;m-=i<$-NzAlThTs=T<@#6$J z#HOgK!X5>G6?)Y}6UuSFMD?QBMG?*;fGZ$9b#K)5@y5WZ;A4yVx>Jybx1qK({Y)V8 z<~IZEinkoIGBKJuZ$j211$4xKsljn4M_y`Yqh&QyoimC!=-T)0EI$3IS|C2iiAQQ< zu{UT)$UiRO-3J0hk?q~w915}TX_hdVM{a@DAA<_BADZ1RC=c$rpF5YanqhZFtwDa7 zPg7$@BdFB}ccIzAPoUr=VCvhd<~G0S29!g(G`*1YFb`uUyuGFVCLsuh5$xV_#jT5# z^|6v7&>8TXyIk0xQ`!x&d+iQ%z$WUP8|3QJyk|09;Q}S${f(K=Qr1vc3ospmbyH)k z8XP^v1zR8*SlBoiyIX#}5!BC`1CRP$%)_u5P8(=1ehJhE?iQj?fmjg)>%R^hTpQ~1 z51%J~e!Ow7vC?6Eh4YnsQqF=}Tc(t)g5?j|MCM020MDdXc0`eVO1?2eWmwjZ_)sd3 zT4?Iqdptm`ilRJ7F5YPlw@kZODFLno!>s`h60`X;0^<_-5`n$}j17>*v!hOZ`t|ND zjTWP@&ydMXd`N<_yv{y%s4@k<CS>#}4k-%q^QuUT*{r+p;J;37S^TA=u_V1ORW`Jk z^u_ERaIw<H?Vg3&L??#ruK_FdGajb(D4VCGB2_(02i(V+jc;ddu7cxD|JG~biz!A6 z097U`W(G)HDGg2d8|u9=EWt%#7xQyvQu9EMGPr$if2)be@n95)sf|?l^y7);NV5(n zR(9kxf{0>SQVloTmOs&*tN8mC%6ZPwE^}~IXwL~^-eW8^vzMN(b&s=0v`X7H(a%N& z>!VWznmt`|HrGMmqPY)WXRPKbo3Pz*<aj1BDc2LdGbeOuwo+M8+YX~ft$`aVYp=VA z3U+{|_~gV@^Gc`6bjnwE7W+w*0#YgnU1UsebJRtJ>meA4M<Q<y!HSI2_AoQwnWh)5 zf+)~POAQz((Y!y5MqacWxx=|Y?rf>ByV0_JysV@gWCZd2hc!TqD)u$3q7(OoWrY41 zXobD20p6hlNT^ogN*yVWyz%{Q8@C~bH7>xFj$s~{|EztmfzsV^Xr+8L3Ph{SNYt4O zWUp$23bwc<_5$@7F1d*TzevA=7erK5lR(e#7nn!k5e&1>>IQ3oT^j%;of7#D7!_;k z#xh?$00r`CE9(btb6CKj-zjO|>t`I=AjDe!wI5uCLn$sBoWr&h_b8X~R622tUO4pN zWAx6#@7YpgQ4Y>X_7vCPp5pPq?SBm9h8!JzTgu%U7t<Bv%+8MYi@@dj(~^7>Xd^oC zPWA$k%Vd)pJ5&^Gwft;|+k!#m6H##kESr7=N6RHTFp(ll?G`CKN6qvB5!fh+Avo=F zX~e_gREKh!P-n0Zx*>-v&gKTEWp!uWN6L}PaBusGpFyIc38;XAJ*plMd<@21A0?1f zUk7&Z<vT3-O{T`Tcd+-ZI34e4In%>ou!c?w$E^2xRF5aYaB&+nePSnAQDy9kCWQEQ z(G%v=wKeM?4o?>m<}>cvH*OC<t%7H*1Gm{hT8>12AyT6e?(v4I%IF0e{FF?8c*5ls z&Vi+Z(Hq*!+qUrbrQNE{^07LMf&`Q|y(K7m`RPGxv0Fwuy;zQ|RDQ4M$<THF)zz{2 zRX<WinQAvS4CE%Lu(sniU@ucnk_see3ykJ7Rp~VUuD8V<ZL>VE|60ebM*<a7sG*aH z7~LbQ$@uBQ<n8v$G=)0{0s{>oRp%lWLJ-eiefv5a(Pai>`)%*DNrM;Q8#x|E2~(a% z{Fw?aO>^dgX#(*Boz+&8l@C^%w@NHN@!OOMYDyFo3hZ^h34Wj9&OPq{(lK?vHYUf{ zyS~UJhH6ve_HS12ej?3sAF~jxX-S7zs2irTWRUTLtaSXF3;J!S)w|+r(K_=TtTH1D zbdO?^oV(0nMvlt^EeeE(6Z_-gn22L;(h)CF+RJ644;DeeB`Lmrb_#u0;my6EZ)U5d z8+33jo2GS9%S&YU8*iLajfqIfkSaH=KjAVWobPrtJUBOj*x-#+lpDB#ZCMgKgw{XN z+CNT|P~p0xWLT4W3Vcs{ZKiH7-P&$`Wz{1pzT5Q?C)~lmz{Gtg**aI&cbdg4Lri7p z1HqdKELE+-ICdF?#rMLrBD!!H^%(l?Z}@d%ry2`CIoi!s7EFuUt%LpH=V`9-GVOz@ z@e{=za)RUZUETMmoSI<0opDVlc|41v%&&*|6kK+>baYNLXp0VcAbjjuj}=HGzaP|X zIM28Z?R5xJEiqH6gW@g&BtzdPocZm7nc^n;Z;Yay+uH{xe;M(50N1s4S!*~issbga z7B`UL7O^t>#cB|~JeYC9X}fa-Y7bgJ<bk!0+*OSUeN^~OGD7V*1KWnrgslTep8U|c zFPUd_BBCpnR@B&CN;8KF3RqvEQ_YxAW<Un4gT-FM;3lCtb`r^E%+zHjS#Tc&Y~W~X zxCn}Ie}N;xrsBHyV2Q6e>Kw`Wdre@q?|&6Y!sA|!Xit+xMEh(s<Y<*-vuSm%Y9Sr_ zr6?YFW|Ii==gJxRNArYU<!-OkKwkr4Ux-ROx&Wy!ev2%qLNlT|O16m+@Cze`6Lb?B z-1hRgVE>{cEwID!(D>U|KkAR57N-7anIL0jqM~Sjd9W>@fQnQu7<uB&jJfjSIid~& zcjM@o_U(8*DzfypW$4Q%4(boVBG{RG#LR^=zjZ$P@-zQB>&oLQhxN7fvS|TJsu1>e zqGx<V!}?itd^=fG6oy}70+q)rJEGa4f<QXdZ0~+rB#k9qFjp$60r;zEF1C@&@M^{p zokY0Ax0qA4NurmRz{MO->%}2bLmzp)`^a0BksyD7pwRGWF0w~Xht<z>jEY0)asj0z z#nBOvyd@8uLagv$sA```Y3b&n$ACgBc_AM1D|<q6<izZ^*at;gq4Pb`_L*!;QOTYq zxGq?-_3KkLRYj#a3UuMY(z&+`lQ_4bo7brlIxli3bR~T~IJBHo6z=oG=zVDwO3la= zop^3Va{;P~hzateBgGdkuHWOPk3#XbCr=k{vvK)JA<I{VSORb1dKLN+U{^4rl(Dko z4s7NkmQr2OJ`g@^n#+%PZ6YneRegTEDw{D_BFn9k^(ftb5JNRWMRX}ChP^#+8eDe~ zD}^XH<5Q9wW;%Y>goufBHCNH`a_2nN<w7vhUs#YlZ)(is^o$1xTJdlWm0$<<EKqk< zzfJDho7?e7s+X3#ex-uMqjX3U=Q4m*yMl(B=aK-zW2%ICSF*3I%44IBLz&O4UP|F6 z9bF}nVCs|dMQH8TNV>PtI@-m=P6AbVE8lh#+CwX=kUhX%wmnH+`kr$y(d}wRkx4jx z?d)6XO0s)XanhEUnrF1JU?2`d&z^h-S55rawY1ll%Sz9S@`|8j-Nvo{PbVOU*ylh5 zZPqw3<;dhGw^fu}+b7zTXM?p5O-4*^f-7q!;_xc1&`?~+W}2D=c_m5*dba=wmoBCj zhe40?GpW0K%XnS%rkm`Afu6^N?@%4i%B`<GETITL6uM&e-7IndfRGd2ohJ_JfqN$b z`M1xlV=oRa&h-yD{%}w*&~kA4r9at9&9F=vK4Y-42i|3YdZt!?5&>(;JvqC=yIQej zUk8q&Inx?P_$xA8h<|TTB6N~UM)Bhgc2B7TdCQOCoAhW38>Xkb3<(Pz<xEz{<al9! zC((ATH~#h6p~On!SiH8+Q*EL+LmbB~K}SOR$=8p2onf8F(|Pgxw)ejDu(Fo!)xVd4 zTgQ8zJBMmtg~`90zV%|zn&k2x3&FYm)C;+0sT14>Q{8GzJtbKOA=Spun+msY-tV7r zZ++Wqe$b{y6!^U9Z4_koVA^x~NCD~`CuDEiF^C&W@(92Xd@MXD&)QU9d9SY$6%v$F z@9W3(gnL2sM3%6K=qzl@xt<)JKZj#)0bKr?mGM9UU2#UN?FZ^LA}YT23d=sOsAzuZ zq`ksX8h)0*-arWXpWyOI;*-yGJs%_wltEA&tS@kMG?+T|<fi+41Wr%9$T)!=D8#ib z8++WvYd)5y3F<2PLQ3Q-B_iU9&MOD}a%_vtuN9!e;V>4on%Cwp*)FEmwX=}U)2W)Y zi$CU9c#)$_8b>E?eChAUXEfj^0~NP-msgLM$0#2*;UICBU}r$jf2`c*$AqT(%LkP7 zEx12thvZngjJXq6A8;p$j8BIRTbn(cNRy|yPdD<4*~7cZe)a~KSMfB`%(&2aE#=T@ zhO@vApQ3Q`pKq(mb1%G6+rarX`jSY4ltB3%(am@@jysz`dr%~_XE`upV+|;l{@NQ< z(x^&jilG&<lZo9NFUxbj$OT|2Y|gC`LuAMh>H>~Uv$U!!clivu#^<HNG&BsX)TfR= zg6>D3vt?d=kVS-j2fKd*K~<cA7o9UyXMG6NAB};dsduQhRxsVi<o1l{RIqhc@UnKm zOWYov>hKgml8&O|^KA;DD2ke`u()}PFLMiDe!rK7sJ@YVF#tgYug!prjANCgM(_S- zUcJ<AX%LS;z4-0;Zee@dp<A#Y7<#7WPJU_TvHZ$7!aHUMw_hEG;TxB*!O$&Y1T3?e zpu#ogF=iBxSr~sE$=38OhrKh)h_}%i<C1u08D7GCE6VHZhj4Yn&SU7t^zq*EOE|>p z?x~--?FX@1(`2Zq_F1c$OON?O9o0%P+rxF4%{wHz0Ag~8RQII#{_|RQ=;oz=7$n{R z(ey?R94)28rbdGGI8`uTqpjwdANl%;!9L10y8(|T<n-r0@O^L*{ZVEKdUH8gm01x; z4m|)>PS`3ZNY51@oEA2jp?$3eF05In0i-NKkq{djWIRfhGkR0)s3ROR2ce^iDY8`j z6uOU#ZMl?;R*kh6b%?E|g;Y(>i8x8ccd=HA5y;UB1E_OeYcZ0<2L1BP(V!6+7rQ); z$!_OH#2dMAbqvUG+~wOEK7)mRisl^TeYD6+xn)umwEd$^cy_o79?-;9COE||jqw^X zDkv8Vf^_yMuZ;>4Ec?9Sv+wvY62d`BQ77Y_99jpapS>B!rvP7GRe#hz^Ju{xQ~_+j z`T>IfapNLur+eOQupa5%ED}`E7-Qppy4|MO3}^d%6XPYhNCpq?9Lsd6)@;VBxK_=b zSC#9f<60A<bW!uLTpK>}7-7fU6OpB;T!JzX=n8A!TFQ&|nKSp#IF_no3wpfoI&4!a zVLDIv_?9;Qm_-+Z=<gdu`7Q;-C&OsRBg^PUx`XXg3P4MI=Z{dSG03FAxYHEu|Cxw{ z-iToJ$Kmd*lE{#e4Wm4Asp*OOV^mXs8UU0G12Ep2XVG=D{r2al0D>%xMj9KC=rWnH zKLiIU;H4wOp^~pQY`xRD^7CTeQ7=mEd_D%6OOh<%VTVcwEDF)PC`|LeK?t?8AUp+I zTS86lBpm=p9AU!-ALuf>Upbg&oY4~SJN~l2-B)a?Iu7onb-+C?1)U+gDwu=A;mkkg zHFOpMr<Ud5^s3nAK=_J#qIrFI&q28)+T=8U@Iav|mfCVAiUgJ^iC)QVW-FK5ZFqN% zrNNMR2ZXJHj`y<4Wllq$`$c>jxo)_?TJS6B9i6RwtG&|juEa~)igaB3WE<x!1c;p` z=s*IcOhq}=<$EQ8$qgKEuDmb^ts^qeqv+Ap;j;s<Q@OA4#D}a%&D3=IXRzVePSu5u zg_u@j9-aW+<4m?X+q&EUm4Gu367{$DZLIFi37TLAO{~g(8@U0pq4yo?IHt>NOb6mr zE636mBDpU;3^jCbAFX=1iR!h&t~HQqQh349@GSXxHvQ}~54i<uCFdnHZf~`Xt9#-D zj(5`fHln6pnP*p@ItNsYeUpq)UG`3=K&w$Rjciw&OVhd4UQ!=?>+yuK0lPMDv*nA3 z6$Gdz{&l>XH@;Rc;-mMK5vQw>js5WW*iXy|RtZ9-ateVvVk+*Zg|XJv<u5BRgUL2f z!M~qL&0SNk9PHfKL-SvH8<eLzL*);X7xx$_2v7$RuDbVd`V#L<bb#=E2U3jP<+-x} zi-c3tBa1E6(0wAp<#dAewSM0x&7{G-RzV`gE=mWA0Wl=hCDBh$*d>F+suz-)RfBNN z@Z`~xp1N|$e5DbzPAqZ>x6hP>-MN*(`$}=l@pa86oQn#c>A@rS0EnV0klIFl6mvV< zyBbom4)EahiMdQS5qZX7Gu+CFA}I}d69y%#o_Ob<lx3ZLi)06ENwAlBK+JToIBFAg zk62rQ+kEKh;)w`;D*jS2h-E)!@P^_KJxV+zqaS<Rv0|O}S;SuKh~I00I_%9x@z4sF zC;eXw(``e|d+%SSowgu&?Dg5ou*3GqEMp`0KKTGWPP@mS@u_515{RM+BA5{8NPe08 zp~4;uA7ffoSibb`7eQ*4KItD)b><Gb>iISi`TgZK(?*u?@2izqHH@arqBMIim=lVA z2P~|L=+RrDtLOn3MaJE>zCX*OJ83^RLtq1j$2x&s@7|#7Y-gO;)CK>iFT`nNrX+Yq zCN`i2hoHpMxm1c4!z|W@r#?&IFs?%6<K!tk@UF^*<!!V8XIZ%XDjQ?9S&6RQ=6e&p z?B4b-x8qJIbzMOLv?a(d@KE|oYV1o5zOC!>k7?y1dCfGl{D5Iw5gmR*#w|R-mNMN0 z`W7Mz%Q35_4>U+Su%c=_I(~^;sqeP!A9Fem%8YgBv}jq&gh|MoTs;r@!q2m&eVR4) z-yLS&<hdr%qBaNj$dJo$#5n6>lyL$vi29@K&qfk(m-a&$=TsiePR7@Bmw7#a*-{wn z=l5Y~-M5+?BHP=l1z_4bz;<$nJXpsZx<vfw#zbXqc+7ZXn@!jZwk?ug8uuL~dLiOL zab0TR&JS|rvO8oHx<~Z)#C_cfmgZALdZd)k%@uJkqpx>ft=uGqjKPE;`&o0l%MAJ= z?bnAsxrZ<cGt3yyhb4`Q!pJVFUjWE~7bMBSPf8%F6{N~jT4{-779=8rn79dYEF4mI zgd>&Nw-K*;<6*e@?2lWywC-h`ZdC6oQVTmENMo5;%~h0Q9+|OKjqN|5aWDW*sA4eb z%^+%2QXmW(UV`}ez)%)$%Q!5T8qr?0np-90&22P?SChCMd0H#C7v>e$A#FsZ59bEi zblFJhI*y}}?xFH0KkO>Ff~870!;xagv@$s7j`SOO6sH93W>LTGC}0spR;AO8M&B8h z))LhLIVa|eY?q{4*Rg?>=-7WO*iPW5*Zv1Jb3&(zebS=tejtkL9<+CfE}if5E!6@3 z#(F&lkzH*&*%J)5Blbw6kEccQg71IM?#}(5?Q?qiTWYQXGJavMXaPYal^{tc@JcQD zq?q$TiF5K)3V&$@NHLzb)3<zS?%6uWBdG!r>Ffld$+A;+x4*js`(j^xcg)5n$!nvd z>=PFubF~D44b@(9+}FV6it3<$?D|B;B3x<%6-^*+G1Z$6a^Ys!Hr@3+ccTWhKOIn( zW0s+BbBjaXQi%Cx1xXOH=P72R<XbXp`kuMu05up<S7AvyJsb*S>|)pA5M7v3Jd2Xu zis%JFc7RS!NPla*?X{#@m)q7)3RLO$<gfps@%=<GBcS`mlt_>RHW@RKl;Fm8S?==+ zR;GdER{W$YGf&S8(nIVu%KpxBG+qlX2}CFx@~3v|>`@YGIb@@K!7?^S6uf;SlDJBB z!*nZex036^i%QZIHz^{}43;I3GStd*HMvpp0V-1#9Pb6WSK<7n1<pyp#JEDo5vT!k zlrs!7$aW%mTtv{RL|$wwkq@XNusppQvu}?MTv|fg(}jYl_&X~klxbH;h6s;L_cze@ zuBr$d-D2z4P)D#ozOWOGp<mTgAYtc*^_p=LE<~;-3PtXOIPZJA9d(lVPhregDxt$Y zUfG0Z6sm+9aNWOttV;u^MLi4gh!kF26t#f#!pM0tS66s(M?85GluAv$)~(~Nk^dbl z(F>#7yE44eP%jw;{%yQAT?%bH8PL<RDeI5uAzg{|5|G9Z%qdhH{^l{XlkH(HyL@T3 z61=d|qw|OA)kDLdbx|DIAm6B}YZR&t*gm^C-?j<BI%{7i+!89jWzkyDFs0Hcm&EXz zzQ~=+s!2md@kR|NwsMH5<qq6++qR)(#yG~=_{-O5yU>!PUv|Om@E{*1r)B-vnV+Fm zg}ysv^F^u~CbqMx{IPjD)Bt1Jm25Q7ZN+k_?KqT1&k|6L;Lmx)Y-xXO@HFG0Rpl~s z70BJjF=aM4OZZ|vh!i#rAzNVDcLpUWlW(-i+escV<;%r_nsm`%>%3Pr6ZjoFP<MNf z#EudO4vk5&tBbR4I%9rg3#0#{u}QaM%6UM_uJowFPxtSLN)J;Lx)0R-?262Q%1B66 zMHhp5Q4)|HksXj%aOh@m(8X!rfu1E(aMW1Kz7JnT`~8>K<Gm0c7{fZpq<q~ivy)wm zuvDllmi6vL-YX14{=5O`+>rtmVNxH<;=`2_X{&f?KT7S+3tximjHEb$VI3NU7tE_r zSdYWT#CHV*+iMt;oH7lM;d@tdr~W(84b}9gHsl3b9`Rj?wyS1P_^}BuZ-r(s2TefW z4wPer0MsKnZoDZ@P62G`lH5wSJu~zHY#6CI^4)1dg40~Uxt*;0$`N-Y0l;pjbzfv6 zf`P)7s}~}_q)|%Lndwv4x>vKt8CIe56o&^O=EOk@r-Yjo&yw#|3gkt6%_+RJ$@Iar zD992znes`flYo_o;FR3-T{o($O!rvF!L|DbYeL1j1^dCn7`hUoxhS#Xk7t<35{rS~ zsd;<!LOmf=hZAF%o)hwl=0$aQu%zaZg?x#fs?Gkxg($5!?pLTN|2ip}0s=)w=}B18 zb6sDEh&RV<2H5l}f|@CHIX<3!se(S~Y3(DUny>iyqiROTg=#nCC+hn>xCJ}7CqN~w z1GnlW04RTA+Ha2J>FXBWKjIF;N9D_C0S&0fNNHmKg=j{H+R>XxPyHi@I)D$w%5axa z6f#H1u!BX&?VQvHk<P%mx=INYZo1cteMZL=0gnZojLi*QhRN4`89#m-*bv<7{#W4a zrZ2g0bH}o_0ZGZ8n^J3|-r!zE)6SVfQOj5kl)PgHKQoQvx8nec(F^%P{PBN7)13)k z%tMTcW{(sOJYet4Fc>X=A<JG*Q{^a?M1{Aik}S`YNJIp;+~6~1?N|0GJgqbPcHe$Q zEr#|`FuZS6K=Y?wB)yf5gwcnz)3Jyb!P<D1?<Z<p9bXY}L_%y8QXMf%WI3KQR(7!q zP%vaMLm0#4y~1y59iej>c~+*4E)G!waP%g+)a`n_EV}x!0NBO6j!u^{jz3f4f`TP_ zg7@z+U)oSq!parB@X>y)5P$j?elx-Lc1a(UCjUajyRJ64A3r9yOy?uDW$BMMo+o%5 zXOXHhRi}|6=RZix_ZcbM01gI4b6eRMyCXJ<0H6r2O)MOix|r)66+^Y>-{{O`H%kQg z=~mj=Ofv~~tv6OX?@k<`k~^hxw7M+qo&3n3Jz6UI*%Ea`0lOp;`!Uy)0yfU8{VZq~ z8Cdm?qDD5Aa&d}pMSe_YT!FtP8#tqT^9*|jHE?A`$Okzu0$*g4pRyDB`#k?wiUBAy zcZnulL0@<*u8w%w`q3sLbEhtc;A5jit<b`be1!kbb`6laXM$)}M1Q&WK~mso{TxI* z6SmG3xP$3hSw5X%o_%0P^;m{5+VGB?>;LGC@SjI@6GCV#uuHVkh-NC1B%*@vGSg6q zA<VQ>NMr7KLVZS-`h=`tL|++T8^tthAZv0ZsMR_Kp!T8kS!ug~h7#IUs+r?cWLo5> z6p(*ZEDf!z2HZEr8yX4lT^6Iiv;aENydio4c_139J`n-!d?Fr@x)qs<*<7MI4Bp9P z2J+XK?f;NG{?O&vW4s{j0bg!<?tS6MX%>UIy_J&E9br~0Yz||}<b2U2@n{5O(N++$ zOmt?Cv!i{Q6=6x818Ol;8Kmasog6W%W`PKIBzb_3Rs*YklIT*Uq^A1^Zv;EpP_Dg? z0t29szF6E;x9VlwSa{*ftzX(Kai-drZY*lIGSqQ%C(6g`SiVl)a*64=z7@lsl26sK zDz&$1s9@af%khaD1A;W~4@u7dA}#Wh1e2LxoS((jJ-ss-k(v4CnB}=VLxfwR+{dAP zer+|!s`T>j<u6q!0U(qQhz#U*MA+f3Alb_}HaE`h4Yh;{yK6HEbanF6FphQdOVs*0 zKB50|pY!cv)r3m7zB>!P#nD1IS=s3|b6;ZxnvXOO2F|QXUO?+q|6B>uSI`7_6@POc zE=d`eyGQvpTEK@wbOLRk;jgUN*VL?%?)O2X06)cp&@7>j)3Cr9Fj>mcQLX)a%8lFg z&G90OB<(6b1lyN*bVYLpGi{@|u&6wSC2*Ym;a8bZnJrcfbew#nz5u>I6tCaTBI*Z2 zaK8aW55~Z)Q{D&C-)0!tgik-!muaGt=o=MOg9veSYqlw_?nMP-pS0;t#(0hEflo!n z`y6_f%Pm3gjn%N@GhKR@v!PSf=)a~I0CHdJQJhhM3o3Bq?B0WS*Dx}6CWi)7dILtY z;B+lW&*lbX2%Lu89WQ#Nq@8DPZccS5@V7Gt7VeeQ)Bk=dt1UVhMd`hlt%7yszE}jd zqRtBm5y2v8WewT}64i`bi!nj^b8GSpm?$h{huQ0j_SBjD>Ys!8*BMp2?v1)&j?yPl zdZI{UDgOA@OU9u1GZJyHJDpZZDt~?T&p!YA0pbscO*9FE5()m-7p_1)e7S;daqkzN z{UxR4pXL2$;yZo7H(++RgZ{A@|Mj^4pPqq9zXi<e_r2vo%LX4zOx7TVzh4Yx)}kO( zP~##~{=W<vu~$9dGg@ls+J|F+$n_;4i>Kw33~TY9oA)PUZvFdjuXta@<;%o-^wuWe zH@)ogg_NZs9;e$+Rsn6WJBpX(hdQc{$S=S*F{DX&|L<4Mv_mha&)n0$vW_BLpk^xZ z1umj^K+Xa177QoOQS?$Pu&F=(AiZ`O^ZoVPcOQE#X#6v?>|e#}JkFk8@Zi3RcTTqi zywxa4Cc=N-2RwXB7)^(GOZA_rCsUjOM8+}&f$z=pA@oobA59_t;devK-*l$G7m$a= z3)A8!;yv!)pLB-QgPt|7P#r<XO8Ef~6EI$51PCcE;Sm&b5cMwJE0BDzoE|^kzuz}; z4u=!4nk(&BjY(M)pML+vtPnj4D1(-^QhfmV4%;sO=Y>%3c`5;V^@wR&|5FLV9wDA0 z9kd44vIL8Oit(N%kaa-CqZ<>zdRw3zb9><O>46Y1)d^MD^Ve*F0nOpk*SEfz<^21z zOhI%Jm%V)8ez9jwqT2DHn9RU?;R0*yUnKzOmgAsn3yLjMaJ0L~(z5uUeCgn)S12GI z4-fxYb@u3bA546N`^hgwO;igBRQj;=ErDlD(FKa83BdL;6zwECJDVosXLrmvK&{pQ z(ugn?(e9@=efamlz+gSVlyiz<{$mBaA!xYSsN50gplI8}<V~SZ_B@DxI3GB2<Dl$- zV0E-0MgDe!1EA*uepg=c`Abqv>wnKCD9!<^=x;CB?f>_*L=ij9e|ch2clJx3(!L{v zNinkq5K7ho9BR8g|K!(vs8T7AGOJhDGEECJt@w|p$uR&6BU_`O{r8fKf5LSG3{eLF z^o|4bN%{adePdSTvsj=cL4S@0`|n-wn{)tn{ZM?y<lmptV?$76-tqkBO>2NTR1BD? z6*P<AqF#bG1ZQX5irM==D1Cs<1xC<Oqcr|!1X528w&z+<jODR`H2J{t2(@lfkjoXZ z0Hh58>lyJyG4(~JZ&rmJ%nnGXM*nBJ>%W-;zh8^&2`EdNtBl3E^sa#|OQ;8!ps7MM zUqPwm_!y9>R5>L}fBUH(oM8)4g%DH&$|{C|d+4Zm{v5@zUmYufqbN|p|2BT&E!V`o za>}_f8vY!KIhK4toYjIt!{JM7--`n48i(!%h(~hiu7PA^A*#qWn&13qF6tPfI!Au@ zLc>@Ch@ZlTUW$MA0?0A(f)Xj)4c)Onn~(Jw`VPkmhNz@Sz`(HuD59VRk?rLU_PjXL zU0}+d1{Aho5Za<zV#&iLhRFYIOG+5QOv+m`{vn2o(|ZE%VYjWc??IWx_W?SWrCZee zW??9sl6#m}cRoh=V4iq&Fyr$swf2(GGrE88TRd4Xjlsoi_<z}ek2t5xN}fD0Wp)F! zm}`Z}pNl~$%4l-{>ADX-m-V?jbaq7Fb8<d+2JrO?08fR?ojQ~L-%m7q44x=3B!ltC z_=xM_B0zHu=4<L`H}jpPbo;&`^H42@z)E$Xk_8&SLYU;&2IRR*KG6z~1#;JF_8lwV z`1cd>B)}7i!`LwX8Y2SN={`iW-Z&_CiL}^qd>9awOu-GFp99jbxwQb3ECjs$?<n^3 z34r82)Dox>|9kqPz}49uc76LVTf@rgEnqoTzEgX;Bd=X)XDZQ^p5I8kG+kGxkRUn< zY6}F-N4LsG22fPBv9i~%!35OY(Jn>YB}=;g??s+RU8i)jA%EXWB`h;{444|9V`{s8 zYKgZkL8=#_^gyOOPAtbkH!U4|KrwO^UQP|Q0Oc~ppe=0KXpH#TU&BJ#<lqSKNUeuD zf0dgg*5Wv!sW05FAJ*W$o;z`;bhNQGi24=a_s8WFcCzQrfV2=GhE1*mpd#NNpMpG> zC+r_%3`{%?>fLWWE&OZK(>p?{@zEFFUx^XUZHXNOsf|TW{e=hvkjb`%g8Y#FI-rQz zS>b}LL;s6hQTxBP9O}*x=LDNtlQZ_8!QuMdF#yJ0cN&>=icX>lSeXj71}M(WxPdQ$ zPR9;rHHa#{gAUuT0emBiX8!ou-{u5mWT?UODz|U{J%7#&ec4dBWRGS&v$EPygQD=d zA*yl#U>~p_twFlus0_~PP*$ieD0BMN#a*X%orvmRWs1tt;8@5PO=tdjVB*^4MO}&_ z&^s{HN4Ps?SQreZE1=4+if~DpM}b=P!W^o!%mDzPu*IIZbwK`5h>F0!9A&UJdLa3o zLeQs-uPiEr8thPSJbG{t(c+$x{xNB3a`jcW>M<p<ei>}6OoI9`Y7v*>Nsz)V1xBRu zquBA%?aM0)^!P5!t376S^#4K%F_V}9>WBFN*&K=BgsB7$F?x%e65jwPIOfVA%Wq#8 z+~`+g9&o()Q!N5I8KLWWoq^4b0GCsJnySt{5)@NZA;yjt@X3c0B``Ev01fW{Ve3u6 zp>Esv@tJ94EM;t?Qj9gr5G@EXgk&kZv1N#otq3i|j4ct_Nt704H)JPUl%;y8tSL*h zSPEq;>3@BczW?9v`#TQD^S<x%9(=a@zOM5+uk*a_PLG$qAeg(ZFfB~Z?8J)JEqoms z67Zjr|Cm?VIc_R|W!0wkF&w_A`2$gn_<GpPN#h8Rl(+y;Tx=+8FY=vX9U9ePYf&}l zXC0x_=eewqnCz@g1*bp-xFueJOYQwiqtq;{-;+<bpS?Oi)&EKjOiTH5BD=8@nhjA! z`YE!${jlH_eA{A5@e<aUG~5ogfXcjE3OcHwFuA^6X5if&M_5qB5PfCJ1#YXYFAGsz z>8V%ZURU{pv8<Z|cXomjnqNJzcGK3~&0~8gBe2bjLB-ae^WdhdI$ZLr{4$Lkh|_B6 zMa~#q1^3{G2XfwF<OAI2K{jb9Z4$6W-Z2#Mg{(^dm7#^h2HU1&yS^VX16j_qQM!Yp zD<>*;MV5WniQd+~^<=sO7=_BfsP)|ZEZ7kJp6}~TU3sDgM+~=E`%ajTV)6F+wHtB* zd$5QU#`P4UYk(D+=XaC)&(bk~GU__>(E8Sv5Qf*Q{d%kRu_VNXc=OVN)y~RtNWa|{ zp3;Z}U=mvU4jOi2J1CCb2Loh^H{Y$^FGT!Z)Rk%Y5w?#yxXc{BbN%UV5w+ltV?z$E zhoZ<R8sAGZX%aOm?{s9D0+NowO!mBr80(uK96<1!>gy`39A)*(-qjN$efy$NU9!<h z<L-3M)IBF-3_<*>P!BRzB#}85dHvCW1d7m59lO@6GWs2{&U~vqZtrTV@&pN2wci+O zTgoqoB-v{&OHXy(y_`1$>D38AwZ78>-A`h6*!cL~*UZvD&6e%`amD(>O>+9YTV*2n zHJ*KeL8vp5VAF?O@xLD98tvRcKtQwehQ+<vXFt9`ykP^7b<^;3pip;2sw-d|ULu_r z$J3a3X<^_u;GLRf4P!@F>UE^OULM|g{Y&v*=IIFJ5M}Nc>s6AG78YQ}dsmU5n^>Ha zekQ~eKVWIzK*6!rRcOo0&7Fb~Yb6WQZ{7fv=l0_WjjRk;`26Wi!5|B)H4cS~-#=}; zQRUJl{05f(y5Ue4P|l5KA*a_@Fwa)>X>^|07!s@Ex??61S?S3#HUlt#mI@Idx6G~g zh51jYoXZh0dHH~=^bKWS*POj!7YV7TQ8zl>)V7NgS+u|AI(D6!EE{mmv-<Dmfdb2- zV+&n}1hb+$w2|+gqzjM7<)5MO7Y*q}(159Q9>gaaJ>@-R4*gZP8%kbx?0mYkd+r_P zw(NkqbWJr3axH~q8|{J9^X4+my+4GHR<&pmr+)i_BgLn#lwV=RP_Gl4tnldv*dWq7 zQh?-tUhVVQ#Gw0uEb@erNPTGRvmpry5^G<P7yUJu+{;NdH69I6z;09YbVry+1Ro*p zrW7AQtqahD?LZEW_8$r3D`|_Vbk>8lVW5(H!r72~W2+iSKNkQ|_JN-0^!umRD!}{I zH@*kDDsJ7m<~<kU*K$u50@O+c9z6Q<qUl^B_;Omt0e`<M-8Ux)d+2aHc_-N0#QYJ! zoZ;K!W!`<-9VR*#14ifoFmL&+`+?^LQQA`4p-Lw^Z|vBi8gQE3_rG5e@T<dqb#!3% zFEG_FG&Eb2?c9cXgpj5*j!+eAxtW*FKt(aRTYQR07eae%yK7h-qrSQnS~&wa-1_q7 z9aA8ddI%md=Tz>lb~=2`{ojQ>S{2c|8f1^vZV?<<4mVtdpl1cncbO>9dz^otWKN6$ z&SnZECc6!s)Q*Z<lQqtHh1I!;ky62PP-(KK;6`3d^1$ZpN}UQr0cX$E)lKRyFYkm$ z33`%fBmj{*ugBo}?kv@9+S15J`CquCN{G?8k-zfl8I4%}n`7~5Kz?6gAgJbWqB-JX zY-1jUlO&H;bQw&%wv}{-Ri8EJ|N2oUwh5EJa*F%Uhduzw`g=en>pINi#Lsx*pscjP zmfdC@KSEa9d{k)!`!SgcdK$myYfu6<FpLFy^9Es(y$>0AO&<(c!`i;0nOC}C*4n%A zV3f_FR8gp`rI3ZC?XxHPFStllKwcZrKXpKizw~4;+qD%lkU9yL$Fuytr@n0sgU!^w zFccI7D|C7a<bSf)%Z<8TLtr+2IKqlG;f!6X1}k7?2ab^=;UxfHut5;e!Eb6K=Q`BX z*2{!Ac_nQmoJbE2!Ep9LyVwBpc(^g700g~-uMsDyvhRcw49L2T>_(<smX@(J_^gFj z;_bya;pxBIf?w>Gbk65eUbq0c2QKgsCJwI$W>&)nn}%Flg;A-!m)g1MNG%N$-5ueu z;M<7sRU>ZZA~1JKLKeZK+od>SU9v@x@taYRVJ1qI%XJWg&zi?>TjR<8W)Cx_KMN5> zKM(0-)>g^pJZ2946KME;023z>-&r2bma|o?5zV}P*p`Q<&LS~Y2Ho82euYyI)6D`% z((=B+b&~^_wY~$H2sm4T9=u`wej}5}eN1Qqqh&xp$-D@B?0wK5b$}Dw6Zg4vHta*@ zq59qMK_r^uQF5AIT;u?m7lF4evJMeR4WrEE-+x@&2H_}73@{SqUE+G#O_srxy7%uM z@#hv~l%aIvYw<3SNss{nNPxEn)MdAI=+a`w4zOMH+&#qc6Nu+I6WQxMH{n%J_s4Nz zj4_i16*u>J47|?Jp+&zOK^jSPCwK+_zv7<E$>q|=xP1Ys69^8>=I4_{%j=+)@*7XG z9MF?47<0J_9TPZcm5m?d9G3tc@E*xlO1rjXz5N$iru{PQ=JSE8Mrd?-z>lP42(ZgS z5Y`0?$Nnw%7^DWlG4^lN_uDVjnQbfr?DZ@6iPt$jFf2LcBiQZNw*TfG%6-6fCM9^c z-t&Xi==L<)3=hYQojWK8GY!OVxCXcQ0)=!3VvB{(;;Zw2-aYv<eulsRtXu#P<7k$t zm#eigwp4TxoO#6%v3q>-i4Kk+s3^7b>u)*nJk8u#HS%_GL{Up8+w0r5$cLSVaPL^9 zkl=?bm~5o_R2C8a_hnf%8rT?8ZXcdq50i-BO*C@DK*fIJVK{Iz`Nw&W0boby2|Jii zQ0~+gZ~f7*=@|>L?!=48RDAX(B<k@858y>N0WOq;H7=d?;MC4PyC}1n<vbtOb)zRv zuXd00y&rST()A1^hTlBkUv06=y0jHoASWn-a-z5Hxv#1F`sf}``^n2HSr!Deq0}-B zHF<ajVXZQi;f^N^l>QZwoLo4Y29R~u;M{bRh@fn}@%k#TKc3KHumSSOPINi)En<p< zyj%e#ud<rZNjF2tDm|ZcarAs#e$AKaayZ|wdM}P)bsKOg(Z~V0^ZduB;G_#Aab=pZ zz`!OFRlkf+y5ilYZF>=(sr~-ZTb{_g*bT<!=FW%%uk7^DJLKT&SLZa}!Yk>?5ZX^B z@?((RO_y)bUou}6ZvMP%`Z{lu*@|mzKLKruvt^nznUWW`mA7(J;56K6P;@?oIny?f zD{QMz*DXJZQ5wZfzOAV+yuMrPeQg9K1D3q6csiY2$8uhs0T3eV`7L$zp_VvxWXZ=P zG(h}YovgprN75lO|JE`<k^8puVUv1)kM}rM2_o^_&bv*l2b62Qs#TJofcAiNXte-* zX_8ICw|4@~y|p6uQMhKV8BD(HXgHC;xyG7r!I0Gdg)Y7DKVYoQXDhGa!AyvU3g>62 zJ1J8D;AB5Q0q@=#D|A2FBOGL_;`>sXV5L9as}xRlU}11tI$SUX$@u@O#)Oe|s=pn^ z3)sf7yZ9_~_Cb+21=_n(1R9RH9@MaS2h?2IfrY-uNM3<K1`bhp`?I)&e4-H>=3Pc) zyd&C%jfNP<|5v(TUMuOtT^`;6Fq?Gft_u@TbPPC>=?xSVh;`OrNd>&V4>F4Sz{c7G zkZfZf4niXiU#AJvH6cR1>^bJ|VYwUQe!vH%4Rsf^DA47i)mQY^YcL|_9me8mr4XJ; zvx<`fHHF8g&f7?WegkeRyKiu41GCC_qG`TOh35jOx)N;?+}^^=w!SMOg!Mks@ROdQ zcIo1aZ{lmf9jY#L`Sy!(3V#8rR4C-XFrU585&GrXl>)`VGa&^44`W(koQexVg9205 z0}H4o@_y)&b=TXY@1tS?^C3e#&VG0%*|g0>42dQ4`tWxHmreh8wcuY^;b&xViCDHi zQUhn1D9c{=zD__b=OIr+(Dn6*{TU5i&F+CRx0A>*+=t8a3X^mK3Zyk&9waUz$RgeA zV61=L7!EisHCW~^zaF$kwht0zwqU>>QUV*ia=|r07=x9fH^4lN<JVN@BBH^!I8g2} znU){@X|w7Kd94b*drd7D%U&2AQN;VIdv9qo&S$Dm-uO7S4{AMRPm1D*Q275NMajk7 z6o)Wg1II)R<fL~tuXpug%ZCE}Z|pr4kIeAs0p3657aS7nnxS&89C7>yLOQnPvoc#2 zsw0@6Gunz1<#Yi@;HV159mBN7Z*oBp;FeHYN3WSYxV5OB)oJruz84D)EJr>&pE$#G zrLOY+6Z|Q^cGa(pzVL;X-Z6-c@TYl@Kdr53#Dcpg3PsVwW*ty-OUipet&~lLjKn** zy!VeMjA#^zUD2^clxPTd#B+n3A!KwC^0kWVYYC+M&IhC@TYpq-x!FnVO?^<%Pk<Pc zwmQX5v?XiO0gVHQ3}<nJ3b5P>^{#)qb3nJF7dQyp*Ab}^2ELH=>^waCF8Vf8ZQR&3 z+DgL_gv3(&@hLROX*sIfdl;dh0s)V$@E)V3bK0|^t_u@mMG!t=_Nm}BgoWqEg-%G| z%~XXCkbFq}CF|d;)Pk&?*VIA0nL)*?&b`<)#nYZpTI7LG)}{w^?tEuQn!*r18KIy& zR+eT@necrTYwjJL=6BslSHieA^BxLYQwRQE6=l3I5M}0{`yZZ6F?*Xs!p<EgJ5B=i zei9+j3u@=u3$vlb>MbAi)>i=u#Wai~`S0ZH{^$I&`yME@v16Eokl)`DNM#F7*M!K( zg^=Bv8QSK5BO{*CEH3CsXCl?(aH8BUue0MayxS!eKuqukkkVW2s!5pBmJRb`9Uk^= z7<DUN#LtJ2Rng1$J%O67i9qrH7x54P-8hhE1%q`D#{VMqc+pO1jc7gMTw6nAF7&Sq zRY=$iAlerbmnrpn`_BKX2Qu*o#v<&I3@i@N2#`s>nJIv8z1a{cUFd??XZ4kw+Y_hu z5ZBs(yAg`~NrwKbwUh+?d0n!89x_6wcdsoz@i@n;`?g%4fEsuhegLMIK<hT;oK-z^ z0PbfsL1}Yc=2)##N=vuouI66l5fOQ)&LC>fz*oJI|MicAWd<lVO5mUW4m%9a{Qb&I zVC##YRF<;kz&a%<IJM#{wnB0F$aWJ!#@Z=_nWG$rf4qi?K@^TMJz1{VeF%+Vl#8ro zIOi-17}7^(H#8n0FM2E;V%Ceec%eTT6+n~tFjF6>ldR0m&Fi8>f^dmUXsi2>`JW&f zM4RK$`)qG~R~(aRpUjJkD4N&4=`9rNk3`k|@0k@A1KOa0CSeD=DC^C+*W3SKU8CZ) zx_v;Fjh{sqN_+733=ls?h{T*pJ_YB&WZQw)q#VYII3+7_6yxo`p^`{KM%Q4MPjaeh z0~*yf%rrLcjcH%sGAQ~M<bo+<;hE-n7V^bPOlaIa;m$kSY&B4~n%K#<UTE$OrryWn zcoNAV4Jv?vE9FoClc;QZH=AIoIU>EbwFUFH0?yn<&qmqEV0Oa)c}E;J@9Vb*#}SAX z&97JvaIo?_sF`wn)kKlX#>f+Ht)t-3DUQD=1cO8HlN7&~Ir;Ld<`QA}eT%n;j}wie z5y*J<gF!+b@z3T@6>6B1{uj8$aHXDam5o2b7TOuJAO3aZ4ZsdwiyUPkWLYGzb~!%; z)cu%MflsRqh;#{Nc(3D~QKf%b9e_i~ZboK!xa}h_czc%jRyYB`Np|lw_QE-7L**jX zHP)8!P*2|pi3a0(kXLN|lh^PiT&_JG0SG9Y4?7IMwFkqc*P6y;9eBJwO<JN5Oqw8= zSWqs%vi%!Os_--XUeIfOV4J3;LNrPS$k0(@bBYIR!qtgA1xAxWUt9dW=4R-r{l9(} zGX;ZOT)ut$Z&%8RuFWug3zB!q#F1?q=vQ$hXt{kTpn7S<a_$y}FU^Z2SB&y?@xQ6N zJ&txxBeQ%YJafB$szQ=7{Hn=UjR_9=05{yzsia78y|pbOl>rMn>o>*)fm=vG)I!KX z^Pq*Pez5`8+)ea3;18^C{?f}M#!3RsV*?-&`lQeHZe8mwB+5X7ESa|6w%+tPjd4K3 zZkzk!W^HK=&#RwTpDlx(L%?`Dzan;-XmAsvOb$YVmI>Ug`x9l*I3?&f4_`*nM@8Uj z0hctRiAI7@ij(-gx({&}iNh*#hu0ica47rlDuQv*oG@%H3@MRXT9`C+S|hOZTBy&S zOCQ^PnS7Yjr8_ritzQ7tda_xsu@!8jqwqJrVUyk0LuRWw`ZQA%Tky)m`&isPxO7^~ z=3b=p4mI%DwiuMn^<PKxV8G`8U3jr@&ID4+I(8!|P!Ont`NtV1LPk^ATK-_9MkkOc zMpNBcfyl$n!6H&9I^XtpZ=>h|Tu9k-X>mtLO+c{tY1};`To%Lr0Pg7<Cf_IkWZ-zD zNo>>wH!EHJbG-+fS&Dp^GK?ZN>ut*Gy6;HweC(F-aU4%PnL=yXq#@L1N`POxioB;{ z%WUrT2(=a7^>Z9|95MDR-0J>Adf|8p6%698Dm~SnD0$`h8W1rPh7YMX<vV~3E&!w> z!Hs#xL{AH0a=-2)^<3g2{HpelHZ+;EHK<^uF9$SPT}?&X@YrdJK@_-%;Ph)VlH1nH z^=i()#f<0mIQW;@aj;*aBO+jlg|2PYOJIkx{zSTryd$Y=um;EH_sgu$tl5ON>Lo$w zEj$3<&amQTtgsj?i+ei`mJyAbv9*GINFjj`T+REkT-V+*KtP51fVRIl1VvZ<QyNRd zL<iMi@ySSFj;v?Z(I|4J1%mLJD}}OoHMwBlI3uGU4V2?gAP<e)OA;VVFAbxddelJ1 zX-tb$9Rh<C0+wb16mPA-T2RL0*ck53=FG98Q2glKgj;VrC$tHE71=*#2#4c(;XTm9 zX8m$52e94-nUt1ZI0B;|8TN-@{S3c>Hh?O3w^yW3!JD(i1EfAE%uo6Y(xhVHFEaTl z8?L_$ZUp9wriJjjW3(UbFf%vrw&~|dw?S?#Hwi|X8tz@lN;y_?Bty9$DBdaP;2ETU zM6hZQ=J^f93Z!QpNo?o|3NnJ)ICB+3RF9y)-nw!OTHLiv`6ZgP=jcxB6Y{`7B1VL1 zq{f6a(EodNvEKTFR*56g=-FuA5+Y7s05=Z>jz`&1*b>Ee!<MTQ=v}jO5U`C@kqrPo zZoZ>g*~kb)I))pzx!jq^^^O{`;?JHQPxcV6LYh!WDFHh2?4OG;wy7URew~1MLJyv& z%0Gtnm3&yCSyC9&B3pOStmGo%<eFan`LzN@@%3i($RgOO!UJHL`_g-jSr+<5BoV{N zj&~<sq+9)0c6*Ixm`575ft99G>ziS}Fy2oCXbzF=ttUi^-Jmh#2ZkW!NlPo@Y3Rbk z(6q1pFjdS0qH7eesBY!d#$fidqSlwVC3t7|J^Kt@EpNx)k`K}yp%+(Mv-je67o^D! z-}F@ZnUSV5KFB;?3^$aSk<KE8n8y#4;GMg`J0}=g8gc$f3n;AXL2~lxP5i41dLeAU zGUVH(*$4gVwi3J;=L-+?5Qy{6BdW7nZ-57J5976vvwHlFm(p}3RqnQ5SZr=4R?j$K zo@R0Ef^!Xs3=MCb^#HZRm+zo3c)Pz!>^w{f+4Q^lCgB!df`kwmf_+UT5B9=+oJa2C zsJ#*Qzx&W26HW()aFD2OXh!nkG3#Mq6&0@7g6TH|8KM}@zSZ&9&&3L$*`7E>S3(!! zO;ZEk6lgK5J4|#fBrsW|y6~-s-FE<a4<+pJ4{s9!pk*d5-49&Iz|!pd$6biJo|T*l z3xBO+$Axi6(@e3jSQ4?@uzMQa&219x4rcwug80@%n!@N-81hsA#<K;elbzD8p7#|c zHri;qLu1k%L=pwbZ$KCG*)QvKPyY3S;wRg>3(wwB!X-v6ZOcL$6*VxGGJ`iifLFTJ zdNuWUOmUQKb;OVp&z2#f*h3hPH|4$wUP$o-&2+hIVsS{{ls+m70LN>At!%wTMugg% zBcJrPlwbL_92S{`=U6`)DgDIT-mRd_9adrmbWI=0@!m<yXGzRklEMS4TBa{s)r^b- zfx}^<j*Ike1-H{fM4;dYhSk(Mpp@w=+`yp1-WO3g`ApqY4`N1SEcvc*KDYV$g`s%m zoY9XKyWc8x_HML7yVNDgLxDgAPQmrckRkgozUGovN*fL*=OED314!<2IF%>O@9LsP zdg=ZiFcVD&(W7Y4F-JUnA76e-OZE~3O>|G~g|oLr7fhYo+Gn8Iz<|k={m_6&=Q*l> z<X6e7du#!cteA25oM<;L>e9@}0yJI+kik>7Cj(%f12SOq=WjSeFO|o9Vd1~ngt2td zr|SEe#h8t?%(S$$oHVe`R$2rr?#f6~6zOoVgO%3ynFJy$E|?gMZR5IJI+o5PI&b;a z_q0vMiE4jkGt2tL3n!|pCwey3+t|IGe|Pr3>#7$@ScQ9`ulr4MP#n#LlSkti0Dkx= zcMpaZP>LNR+^AlnWQ-`)15-*XTUcWFBL8dcClKF>A(cG2AxK%OhvNofN<M`!&42<! z_R5tj6L2mQElJ8eK45vS$|zKV^#tAyM%GC~yUn~#K2A_mCZOU(dt%%8cKg#aaxnVr zl*U`#@1EmPiDe5<qn2FnuYv^!w{jF=<>U9cS@`1A96);_dcc3d=h)*9XDbacqWEo? z0SqB)y02JdZ&(Qr7ZJ@BAq00BeY?@o^e_#pyY^Gd-LU(7#;74JZ0ODQ{oc5h$;No! zx7EJh!wu*%y8`QdIaUwv&voT45A$N&K{u2%iNYD<VlmSF?Mc#XgBu$j<f&t(lB6vY zGs^;hUF@&D@URxxk@lhw&|<>|+K=3*@cI1mLvED^8Z#?V=Q_1?6_FOt!T3|DsA;I{ zO$@ieNYI@a*)vvPQ{Saq?Gs?|^4XFe<~ET^pvrU3!Kl8=cPPmk$ZM59NUJ9~p2+Sq zLLO)B#~%BPzyKz1F6nvlPvn3UEG2>gOW!<Md&cX+WRHw<7qcbyizC+{yZd0Jag`tf z!hmNov3dlwde<%;iEr>x2)Ls2v1<Mc`CPVqvbGWk<(SK#40DsO=W7#hwpf1CZSdYs z8jgGqY0cyof8~2brUK0#?I+g+cOgen-D>jSBGS$9G&kb(#Ks|h17s24Ph&p?6W{5i z{}TIqxBOgWIf;zX=NOAc{vw8}M{i+9iDQ^FZU5O1tq`9QiMihzof{z0Bt~H>#lb?c z^B$P|+k^67Bn(bYzo|%i6AZRzsiEsI01&WxS}RO$$~t&?vq^=g-Kn?LWx%rO5WVHC zE~8p3|0|}oM*jC0#$bv1FHA{oNIs-^`kn2vhT6sN*&h!N9)$aoLmSLA)+=!__0eW$ zvG79q@w#$>=_>A>9Dek_D@2$0f`v!cmcn$Wsbmp8^b?s)xK0?YlK}c(17dR1&^U}h zx!Y`neHKiNYB&h<*Lw<V$ikBCDt=R`)^(fM`hLt$N=G#+6ui+5zq)la`2xu&eblY} zE>`^seE$-d(DCYX#}--TcLCoFd289eu%*J%4BpvUb@t@-1ODaKNwd(Wm9pI5nDS%~ zvTljxxK4~h`ID%E^|#73qd~3_icsXkeo>l((j@4|t6Padmd_preS5Ab)j+W2YAE6O z!a}rIob262oaLRjtvsW_v^>CY2x-`aUU6wUM{2QLG-mYpM;5I{Gp`8#mnwe{(WT}X z-wju05$=L!6w|6S$j>J1HJ)i>M2C}T3mc-^YVB(LE<AsnfqZMKC5DGOtz0t2#}bP| zeww$UWf}z318uK_c=cR5d5%*x&#@&kIN~eCWRre3xD^iL-9G{C!@D#Rk|Y>VwlQs3 zgj@JE;3M-hyD9@|9M<BKT$xMTmiijRnAH?#HXs@hbFzs^ymtXwk)N4EfW6k}CTxpL z@!fkjRtt5C!ln_$@4`wnJn7JVc<WCT5~ZHSi0LI79SC(cRQ>5;psO1Tb9W8{R$@{+ z=CJ$&8fP6qpd~J`R&1bHL<i8tv0tmb$0Mz8+TGS<dZ5JXvj3UjRt%4Q$j5YX!)?g< zi_Y-N?RU0+jf3H((m7^1@$7<Xw!<$&u3&W=f-tZ`{7&3QO=>l6f(@Z0L`Ewd*_ifL z^zR0!;qD|bKAo(s5z<YO&3K(_uFupP%p{0CRmq+WL6V0=k^7`C1XQX?mLBhTJx3iC zNRiz3;Jgjtyf|pj9=W%)ZCn0@xv@A%mPXL@DGCs{YlbZev8UjQ@lMxa>8ywtftu`O z!y#72s{C<TSk*uAx+iZHGIsubC1lL3K?A8l7;mn+lTy*t&bvw-iARl2R-OHrh_`|3 zWp<6VC+S1OU6>N{==6{pZ$7SxCx3%6N503%%}f|B+OBM2v*}{q48WWAU^)F{(u+^u z-pzU04`U_jHohQb?UB1(eB${w;LMIX0hIQJ0KTtlLkbq=q$LB1zh9*Gff?ai0=bq; z7lsj}RrW#HG@?cK=FxtM)0f1^Y<){R{1?*y?m%~Kat)FEVAPKG3zV`>%X8!H&rzYL za1UTx$AR0!g6Soz->?JPrp(nGJqb}fn<&LbAQ>4K07=DmT|KA{(M_~#%2g>3x1;Ku zxVgEVfm3O79xq0*7zJ#?Q&9c##a$q>A5TVoVWFOiDRpY&a^AYx!NMkt*@*Noo@~q6 zNw1taa0$lmRZgg==)*!A!n&aOhu;79E@5rC$I?7-L}KER*@<A3CkkJ7sUulN>XQZh zLQ)4BJFH2R#S*M*{0dk*v#geXvPuu^Ir*X$a){W$aQ2ruraQ%^G|yC@8432*pfwx= z1Ay7jgolCJDqWjZX?&6<%|qgH_N?%B@1rENE`!_%Wrx^MY5`c4IJU4l|2p8<j04@# zstDL>;=qP3tW{RLg$s8TB|bdEr&l3Yc?$+~88g|jKMAU=Vz#Df|D-ZOhrsTegC}zT zG!GUdTG@1G$??By1aFTet~T0>Bo92j%al*BFD^X`h3QKWaeRgrowqtl0PoBpsFsiM z23fbk0fV1EiP0sEycT&B*I%HzZi89dyQl&NO}k&iXcV&<YiRgVBZv2U!Xs3puQb@; z4i5$WeuM~t=a6GhhWVBOn!ZFr9_U427NCaJ6P--S{9r5(+91)vn~mFf#(aA&_M8ID zWlo&v&dXz|e4RKc5D|rOcXgSwg{?*rCi7v7_gcG4{|!K~<PvPDVBdKj>gl06n2WK~ zFijLssX6zxaE0-qBjqTFMDhjFh3+(IH$cQrYB^RSXUJ^45Wb0j3|a*7Fpg6n@NF=` z-naOC>ScB7hz|xiBIMb9zAGmF3IPI-Tb@E~mp;m)c5<KV>sa~*X4aJ*d*aBVxCX^V zz?pZ&nFza%<%=^>AF<|n1n?m_<kt?>^F{<nuxEB`IJa+R#4eMJ_GPDU11Dvktvd{V zKbUm6R)T+sDaR17%XlY;yX&dBfIkn%)<@YUQ=arMD_LP?468w<w%>a!!aDFXc&tjo zo-}A+>w|Y$P~HRjIAT=?eZ+VDb08*@>_R|IyB#X|=;Qc(=e`WSP;K)d+XiQ11sRMl zk4;`vxk#rRl9(!(fXU;iPNz<kPwwZjFOV<6T~vfl!RPM06c~JJzibn}Pk4~CL6h(l zDCqkuyKU~axQFdvp?X6qx6?bLO{<(6?~oqhZQMNaa7*6i*x~pOeO-4)<;tZk^0UQ1 z%Wd6QOjtaHD>!q~wD!E0*vqD0R~Ihiv+A~}CtmrFt^EP&25YP;JS6c04gx}z(D9Ie zP%VHHLg!4-xzT18=jZRGi|iKe7U4(0x+#gbwkdbd5%7He>+zg1>09#<WZWcaG`7CU zUp4hXVtjnO6W|4@CBooltcd%q1O663GT$RH71`Gpk_tgvyK8>3_h`;Vfkh44XdZ{0 z@t|Fy?SA^W(2DG1VZv%Q*gFeIFOk8?5FqNVU)LqR#uC$-m^NuyED-}iP4xQL+kpD; z%E+(mQ#B5?O~QmPPSBEn?`ytcL2zHFb>&|2F`41}_ouUK^pd37%`r@UuVcrmV5=4D z&}4Cr9?gBn{sFpM*iuv!`|NP|@MudEAj4Y{UOXMj$fTO&nCcC|<0fUU-DWc~sw+*r zjUWvlf1P9c#p+SrQ!dvTtyO8uLhSazagbD&c)izY^tLGF)OT<&j>@E74W8z`5UC<r zcRxZRcPk>sbiT3#!!PpMHtyX>_;jWQ?ZAFZL!1l8ONT8YWy$w*@hjgF<<f`iCtqu& zTLoy_G1}EG%-u`NY}Uh8if4maoV9SgK<12L=371<DKiOC3~8dv6DMaJ`Bh#Vd721j zKm_j{68jJReYOa0j2Jr~R=MAt7M8@F9I^_~wmoe#hLlekG3BlM8ITol;ag7D{WB`G z%f3tBLr@d{J>HcZ)ijMtt`KJ6lZ!@G6W<?g+MrJIaWDjh2+POEzL@0N-Ap>PQ8#Ms zoh1IzZg3PN;o00yiw2w!KYEh{%`NlBxs_k++IbxLiVC=fT;KVLZdY$MjQcy)3y&1G zFWTk@b_QO7gqxFZ{9M*;@Mvf^>C5jCJk^-b!cr~{Vk21<pUD<{ev9)$+~3VN8cOTO z5cGqN3pEOVhV_1=<0XI!$taO?LH@1Glj4<lTIQ9@7E1w-AfU4{!kk}#VtwBAcIffe zYiCEE@;2cYo@c07K1!Cgvu4peKcCFV--g*0U<FEai{<GMF+nZSrEiZzE)?2U1w`hY zKYv*XP6RkRzIYmtwp7p+|F6E*%op=geyT$Dns;)XKTx?)4_IWJkFe?hEwDVb3MiS3 z9ZBN*hSfqP)o=|zw(5WN8oC@Nl{|l3nDxy7IPEl7w3?)wF9vWB8w=RKbTE!+2cy^& z(S6L5FZZ5$bkzM6n!ruP+eh(8-oXg{NW;D2#%|s1WVGn|R@VHK)T)MP4+{yzd1}9s zi;$E-wSkZAp;9`vWgY$rq93B%oY^R<*!M!vlY8&Vq9)KRbg!wJm*X|VsU>8uK<s>o ze2mZ*f-N(Z{|?AW_9gL3w$shI2iebm>tZhEy|a@<8S&@1Fhh(cO3YYVHQ^%!0%kO3 z#TqQ~jf|IhQ~_Ym$t!`N<vM6cOR~f8Z1yF%F^n<F<Fa<)vc`__(XYTrwtp40<;<+} z)}d_?|Bbw{TS>fU%b`#(3|;wl>vtlw_$)82mb>@gX?_5Mtvlcti}*6f3ddW0_ZwJ- z1KBkMG*z+YGIbOFmoSlgzx=0r0&Nk+U|6(-QsA>>U`Ss+w?y)q=CMB;3dzO4QkQ9H z!VnfG0l={|caL#l?efz*r}brv>YtXfVa6T^Qi5{i1z}m`b7!LXCq-Hp{sIUTixNu% zD>vcZjK@iBG@(aJ(Q_~shMY_Dp%~<r4f0q6N`fQ5g#qK;G{{|5fv!9v&mAnCEI*m` z?8T9v#q`T|-!>EpKB#nRi<J*4=?sZbcIzS0QBev4kaemEsR|xxter2R$8-V0iaAy0 z94CS4&Q~Qt%x)|eSC4CD;>5gvGIj$>ry+O8&$#A7aCYWq+6FCm*qeo3z_~54JD6;c zWrN_#R}%59xLN$zK;&06CBNyGf_RosQ((kH$_VY}o&6&<n-XkN6CX=$On*>d8pn~h zZJ^XsM*FHc9+HdVt%<=Wmk7R&!W>0QM<h(|U;S2Du_>YuqMBa!;^hkOF23(9+}C)h zk2puwAaJN~>B`m31ljjepS~+T`VYZ+fe%NUF(^Q|KBMBA73zEoKxiC5%bap#K-0?t z8^w8QK|vJWOIcpt_+8NNOGy=)VXTtY651u#&VPC;c*o=MMM9lZBY$IQC-YJi2x)Rk zo`kvNbHAW7d4O-ytTP1)&%+=abq4jP_rjDFk^*0}TPi{=@Rrv1X*!ZudJL*z7?mMq zo+}DsBTHEo_t)lr<3ZT(SRpN=hY_q@^H8~26gmv<#E;y;aC<|Rv6S92H`aDn{E=MO z`01udW{U0I?YKv9`8XJvmd!#A>cBbI-49nkW1u7~Au{k-3n}~kb`HPYfAy{Z^Hn4s zt^M>R(~bpR7;EL!pXanF!kaU1+IA0nNbAt$PdI(zl7HCwE9y(89xv}*8K?k^;QZVz zD<(7AWml*tWkQ2=j6tQZ%ohcj6AJKreqY}eBwOBivuUyy{H@u;yBJF?bG_poDf&=q zl`wXH9A6Lw)VA8#6k~(GEq7fW_|=cz-Uizn)3#%-cYitVw>?C6ktM<GjQj?^-3;08 zpzb_NOSLkG=My)F(>C_xw%Xj)+2mUkCgx6L@njy(-6$<HEPNlBS+%z>uqK|23-h_` z*rd?zUEIjC^<|)#C^gsQejfVEBYEkdItJp1*rt+~tSmjZXWsq*4pL&a1ZZ~G9JTz^ z!4Qv;0|K41vFydKa#=0~he>0C8adoyfcO|F1uZ&`3(013d<d=G!oQSrz^QT<Ele=f zS~WD~!7j=ksgDXRmOEK(P7m)<2kX~3HxFTUAZWL^A{DLfJ*Hdc^tJ~-ntgVQ{gPLh z3hN->^PmCs3YD0>Pxe<HiRJs~U}L}Y%Y{pip0cvTrk~(RxTGABQgpVdYUlvoQfbn$ ze=RaHVS0X<pJq~a-|!EZK0~04i&AKv%g*!uO(iB+JGws_7Xuuq1xNimflSVHw&Ws; zb!1j6og^RaWPdbW>2|(7$j^n@>X&tZq0j!oEL84vC0@Xjn@DOH;7hIt*-Y%5<eOY` z=^VS7^2-$dwm?dmY-Ewej_WgJY!)Lx4OybUQ9nn7UWpMp7@qy}NyShge_gv($uvu< z3{`&XMm7qrs!I=W=lm-U_fj4Dd_0OpD;~wvr~C4R-M@|JuoGyhx4%AxJ@T$#CDsWK zvtW)k&f((j3FW8C1bqiAHiKuCwpubmCb@OTn^IJ*<Pj^1R0L~s$1%l0HX?(N{CeT@ zt3%!&+CO(Ivt7~<T>|Tz9!x|{R6iJT#GnwV5#}N)&dq$Q0!j@j2paSRPJx1E;_L?L zvz2pHVLBN{)n*c39G+u(bLON`rO^mE5_jR4f!u@^+9F{XDgasri`MD(ju&SAitEUV zp3O;fzIMa{Pvy*JB@{5!q(Bfe1|6$m4nm_P(OOuJbx>@0WQ(JWK&*o#s}Q&F14U`8 zxAiV{1ZfL{naeJ(d>_7Fp9S#l<A1j-lP}^;yFMhEK<+SU=c;%rS@&eRv&LupmqR}m zrt@r*YM~V{2Xgrw|BWj$BC&$`jw9#x8>wf?Ce0WQ;wuA|OIU+(L3z4a`YFkpVQkuE zzm;SAz)Ix|qd|>5*ray?X+YP-Lz-Y|&ky;B{2dX>uM1k>bYF0V=-Gy4V(Not^x4=f zaSWV6*r)&S_CiigyM{nIo1L%qi*vWg#(mc#sokvh!3H@yp@NxbpSHl{e;E0&fqOUZ z;v$eRIsPqRsB{8v!W^jN^#v}Ban|_W_{AcRuDnX;-Nz+9Per?h{ZtqP(YW^T{xy8Z zP(iaY`~)2quC2qOt0*l4Qq<+jt%k6c@)_=7lXL*26843REuaypyod@vYDT&0*smrK zUK~9vWiWdffLlOJP5mRCv7Zn%q`P<t#jtTr78SAILw1cL@tkJ2n*20iRvRV!arM_v zrXiJ?U)E4H=`ZnJRuQ21Jl5nJ>ixj-dTE=`LNb&M0=Q0Qch#%Af9kG>4=q&BfgeJ$ zX#g|r9elAt{<?U3C>JE59a!o!Jzx$r#~o5H0%ask?%`T`m8x~#*67W4XW)kXMQHvu z*8~nY0ps%$v{5HfVwBgG1=i+OVhv6l+$@#cG!z>fB*1J+@twIto8=V-uFxy*9Kht? zf?J6PCQ2t>VN&=n^}`i`Lr*g+q{-soM6kPqYz<rl7K=kO(~->76`>z{S7-3<=ITY9 zTl1BQLPy=w?NJ&&>cDX9_M4)>XO7wnb#@Z%%FQ^DLsHUx&CSh3y>UrDG1Q_$D!VGw zfIq&_DYrxpZPxcm!Q_jD)1wgxj)zagiFxk&hwO%b3LhfdGzib|CM)QOG=7v0Haz9U zTerPnu9JV0K>n))$o)sf2j8osNkhl#0;+(UG>s(4<Q@sl63L%LhVPHBHvfK^`YHyy zee>mX)e9yu0tci(N@<2674qi=@HK9;d;oe;?bCB>g{u2u8YW-na#F_McR*hf&t#$) zMI`f*@@+<}QAN5D7BMvQRdLFTrZ7x?O6t@hD8PO_*=v0uc(~es(G!k2VZ2Ie13O+~ z&}Yby5+gF!9>*VbiJ)eA>pCq9Z6$$aHQLnJOcdWx%=(y>rBNJ!Ku+47H!fj*#hZ|* zh2IRw^sz>gGla80xl=2N1`S6Ytqu;7fX_F`#)F%Ql|4W_W~@?8gF}Yx818WJOdOD; zLRnL)0>>d9J?W#hkk5j}GuIa15II9<7BG?t=jW-ElCUgHH@Kl-NNknwztPYb!t4y` z{U!K)FF@fm26NI9kb{4!1Y47&Q-=Ld0T7-8mR}-h3_m?`aEqo#X}sS-+F|T;$xdqz zhevDodjwN|!zuLP#$;$>!2PfNaEeoz*eI0(v?OCNXmrmVC2crx?u%`SC^43N#;(FM zgM3fgJeNmMH$jZx&kS+sU22O-6i`soFd;k<h`n~`jgs(VaPHRK;B(-CJuGgJN(4pW zl`Prf0yMrsFAAznHu2fg;bVCgGUk}N1jf<dBL~D;5NaZ{AC=2;%A!(>0>HtxKG2Sd z^>HZrPr8nSbgdF2^>YoVz|DFc0cugF14B4SV;(HDt7!*5B~eV46aYFOS&HAOBj<^A zF#9@PJ?I$ZF$wtdrW`F$u5eOh<oiQl{rO)#PWpZavU@uha&%cj(8_y3y+P~xz(=q1 zERVuL<zmQ0`0A(4n)ZD<zgdW#$02jPzV-X0w&H_wnzl5x(Gaar{l0Mkh=Zm>P+m7Z zO&0qHv9+#{K`fY2XL(nq!J_Dx9TMrps+;%(SE-*j3>7XtR=|X5Y`*}){Ba12NkE<C zj5jlmG{qa=??Xc8!c)1Pi?NcX;uoL;=mea{OR!sZ2N*0EWGI_ov1LSr-N1-*MTn!% zp%v0R9Nzx@qNTJ=JMI4GgW|!cAydr$4Z0V`Y)#HzmOwgLgo#ED8Hxk#p*cge6t3L< zr~yc*aVTlqUzR}y>Dn)s915pn_1I!7j;EqpdbbFu^6%XtjiH*?17Z0YS~5Tg9I8_O z3|c*;Ia4L(GFVx>>0-NVvoIa%)V!}M1{>w@mZTWs8v|hRcR_Smjdw&~_Sz3URT$NU z#<=g5q3)Ag8h3+ku34_x;bAsV9zATI*k@lCfEn5FbT$R1PtG5jHBX58Wf@sitRC+7 zSp)1r&Ooy426PB^nm|o(^-IB#47XVOu;-Y<Sb0nI&-Gv1B81ZSSdtBo5~w6n*J45q z*KnFbO$_NLbQRWCy4R6Rtt(uSC`>2ydQhn;TsaFK1?lfpfsZ0-7X|w`$0RF~>jbzv z3ov(#0-_gm!wLf<i*6rpi`P7eqN6XfZ@rUGRe@7xNIo#H7o*<{uCrF4p3{F;X<*`r zG_tMk;lqb(SB25(z7P?#!T{rBQ%`37xdHg+h&Xj~vo8?WXDmNjF5}vh<d5r!l_DsB zie{S>{BdEP&ECNI&eAs1$GqpF!){GAH*1Y2Y)c^PLPUxKCQuKmnK5ucMyZI8OwGKl zImfhm?rst>_wmO{^91Oe_%(4QL%V>6ozjH>x#LjMrGH5R4^=ahB6fTHk`OGnz$eN* z{;X~*5S*ktEGx+xnw^E99$_IljoeC;RKnoxP7hWJef%#Y1vX3@95*-ivPGYhPm^<O z7J4=%LB9jd&+QGP+KZN<qTc%)9FF2zgssr53?IH&E!bUs9g)&3F#}BK%_g+@$Ox6k zWJt?fGD}(+T(ma{NYt&s!ZYwuCPbd!JYXYbkuL$KpG8!<Z0Xs2D0?P~Z<iF?dyOLY zco4<3f<9dQYs`5|1@}JuZNkd2=fF=fz5fBK;tpU8$DkhPEEu}g{tQFf;I(}4>IHZS zju1ooDBJgyU;hVjv@s{xD0!7c-Quoi_*X~({yx)k={=&mgZP(#bdOwn3k%NM*7zBQ zZ{8s_(*-(%JC!GSa5QuE6(UlN4T9zC0p=#q3i|Tl`zD}yXcrmcoV#oC_4lp2q0LHv z`k&5)>`6FK4RiYuNJ=KUvmDuK=|SJwbp+#F&~9|J12^1UlO_%0PGOY%>$uWgxFxJh zvtLz6$x!be*tSq~3o_PIrDGQ<MaK>}OYVoGiQ8@{7ELH<)%r~jv>oI)a1Z<FyaT7Z z`p9YD2P5qcKtOrVjUDEtOn~>zJWqaj&H*-#K;wO4vM}{tja-xhd3&#{Fvi0a=;wRj z4x9rs4qL!)Yxz!*=5bbDsq8{y+9sdS>j=oOKxopWI7gL#G$}@y<}!4?PwNhfAFq63 zb1cLO6kWb%oP{Vyy`^>u!7>x(z*U3mDRJKv7?y<?G0t;GhF@f;U>f1x@&vXH1Cd0H zdzwD83cOAG>HG`o<@!ldS^1W47ax2V_#&$8^C>ep53<K$@Ed*bk&k;>6{lAC7T;hm z6YBB@8}cLAkl%RW^7<!jI86RY&tk*u<njzfVi$gcvsbckthA*pU2F=Z5m_K@%JpD; zL6i+iL4D8=rsO`dIAs8h15r4r+8b;~m3vt<{lKf9sGZl(#fz>X_B8$A)_CZn8JK7c z9WURQcY>|b;v&VhL$>zBkB6j+2=G}0sUq4L^T;;;U!@GESmv*W39(Ghg7l>Rn~-|m zaLB7Hsbc_%rhqC}@^{vZNTkowi~}zv7l_1?4vOc0-<i?42TQBa_IoL)5-mf?OqRAh z0-XdBC}eyDAn2rfTcTo4<n=>Su^q~u2kr77&)synyGf?uj=s-9>Rr0CC9JA+z=q1k zXZ~UO22Wsp*`l^ZFd2yArGR2Ms2xAv%!($RgwIujMD>mATZY+L%Ro$<V^NUCE}%*Q zc92W@EsMVj|6Z5Ol|s!kVb@G&^300wP}TEI;^0_NQGmH|5Sn-ylTBf4!C$5C32R5T zCLC4ENd?F@c)Ay@^c((k2^3k*RabXkVp=rewHmu+MayE!*WMWR9I^sVl8$|UVhVTa z3hC<lm!x4yn!|9?Kq4fkydJVB;-k~HesZFDHyV<G>P2_|Y~0jfl__F_wE__Nuoak> zHpJO^VIt>2`p;3{4Qh5Hs~><HNrrA|uJb(5cNReHe`cMupw!${^3q%$fNn(|mmY%U z231}c+S#Njct}A|^)5~}jM<4jgR6!Jj#0$TJYemxs=P)%vv0aXv1<1nU-l;XL79e% zGtl32?z*Gh<;psVbjj%qye?m|iIv29z(cW6Xf%KerZdFt94zQ#)Z5|AUaFm=bp9Yl z-OHd8n=i@=6t!}6q10H}cqE8G@a;J{UJmU6>0KMRmNHPuy~iCPKUx9VR0IN_Ly4(< zWp0+^ihfO@EbY4$j$LT{DAoKL&Zm^%!>IrIo<J_uK@~!b&iOeFk*NFER^iWJ0eFCI zP21<D2Wo;W*Y4c-oks=gXGc~a0b^qYt-`@-U;SYP%#c6iR?|S|jzmcj=zV^xsntE% zyl6Jwp5zR_=%ax@wUiGf7*QChH?Vu8h5jUSK>r(og8e!4dsT6pVZ`|iMmFN6PGsU~ zrpPq7auPNL<MX&fEq^@#|Jk{)YnrT#w3lCtc<k*i%<N#Hk--s}1rjkSx!zRy<5-Pq zL=WIx)n9Sieyf6eDlyekRebOq92F}I?i-UJ90Le>S<DPGnqYAYuQSWs$cujXY|$mC za^&5na~ly4S)zoo=Ea4noOb#ybIQ<{caLlgpIKSawADw#Q5bOWA4+mz_gmAAQ27uo z!S47e=Jn4-gKc+3xg`q4*2QaK!MGUwRsC#}Jn3t5-u^~)q2wpRWOjiShy7t<B?dwG z%%va9Y@Ts66*T4fwJq|REJ0`V88Ae`*-$-j<@_>e9G%Bn;}8i>E{o9O+4r9hd?}{- z7R|o(d5SlTJM&*yS^iBDn^}PN*2)Jk`pt-?k|7LyeMR+eXe8Q!i8{NzH}GWKP;T24 zGr{BXB=%3pV?#pT*24?`v#CQ+TH2(n%PpMAj!zB-Gnqs9y$2H=yuW=gOp!f)Y61*w zW>msAw45stb*gi%BJK9b$+#_~V>iA%d9TpYdw#p`!u~B7%7@KE8AwN)UJdT+Ows{| zxcwLAoai>ekWx3Amdd>763*jHlD_wgE+&I9w8$~hUcMH_hN;|7Q>O%QG)RGU;H6N( zp6y}RnJCy%$PAm?NeQrItg)K@AFo;LqU>6K(I}QBB1#d9r@n8&5bChfX4#p^<&IXl z`yH-KAfvP1Wt9t=9XzA$<LM5qv2nSskJ3dDCc;r5I`w>OZB<tXW;gF&KYYtdYXg7% zXxCc+>1J7}`b+AM?a$Aiso!X`ln!RX`gE0ZN0x&RKtrjzA_YRIRg2EU=+)OA1nP(y z{SP$KB1UH@Kd$>zvmyUPKIkg(bLP&8=;+^#O{{86BWF2#7$4N97R%XrJM4=|gbs^1 zb;uS{!R68N%ia5|>wbh?xvtwFjgAODT{{~-r#?`8{7@3}>V0G;3Z1CrHL5j!zhSa% za4R0o@C3YD;?trKYMJjxo3VRvWQQamUW3XY3EN7>k5!G2k_{VuSmgEqch8QHG8;mg z#s3wR*rR0T(WZC<>;eGWARM$AE^~d0CAVX#cIt2jp%|`7S&$|0Fc`745lLCTb(z$- zX6ob9m>)G?z*~pU4+gb%xw}>Uf7kqUDvim(yUzYuR@}(4+Ge;AwjO^QLTCi47xCC2 z{ycd&h6b0~gyY+jK(ohMm$`~T;4}4Pp+;W|U4%gf^*)n5hB1QbUo7`OOH@TK1&4j@ z?MT@L4ceX}N<V7y__>O`Z7Dn%cLz41ZJEItsH_}KEkJ-Uej`#gqms1$Jt5^XQZ^He zX=N`eDP>~N9ai4$p0Weiz|;;{(;3D?fE<MHWD3a2ZYQ?^ZDLJrY~xWyGm!e!sWn!E zc=5PZkfvrZSIuvjS(TINf<Io62F=a|Aw1uoViJ%zrRJ*W&o!|dau*;p>c=dA82i|_ zGdo#mkfV<=i{iIpprD9{tihVxhR`wQP!*bQ-Rly2u^twB>)z%QWerX92mrqH(~noT z7=)Ga>h@~m+=QMdkT;SSYupIb&&)k1_#|o$Ld6OQ59pRDwZEGHDCiZA2`x5?VQ|qG zgpA}K@#n&+(?QpF6w!S{7*9&ye>Ru(+}C$9h@=H{-d^3BG!QluR()qvUg7Rja!kb9 z+_99<*s611kL6ev-DIuAMN#s^ORaW7oW<G$T$>^z*k32^(%<R}%{6nF2!u~OU?Sgi zO#V>=uS)>LZ8_9c1f4PP3`szMNz)l{{ETarYFg-j&XASHVHQmszoMsBRZ_9>fza;l z;WO6vbUEAXGik2h+Y)vr9i>E+;LAX4;{N%?*dCG}+e*<i4^`%XnfrEF$27<p8*x|r z|Di|6YoP4X2O))`--xGtOYa%(6U(B*f@mBvI_XNjU5y1aw(lOP4*XS(=on3^yq!UU ze0oJ%BIc~dv+yK0Sbs@Hy};bHL2)|{xZ@?{MM(h6_w-X<%!QWn2LsD(T~`3j0NB$@ z`tT0w@1?F&h`PiREH3H{*uutfna9gT+|TPG3LVKK1Rac!kP%dYyjrdxM2S~Cea!p= zR9a)VFAKzjRoV#9K41LBDQjI=8u#GCv=<zNo;d=ak!FyX<I~`!NUts+0sUqlJ^#~H zA(GKOoA0)&{fjW7`eZf+<;g{OM5k|a)BwmN+XUY~JN85z4PiV2SC1q_UW%Wv3}l5X zXBm-?{HCql{bZjNgumGl!2pA0A~eU?R;HSg9>YPv+#k{oTGkS%#-q^K)wGn;M~XbU z1Q&!3?WO#*_5DoTjfKYGYaMk)oP+1MwM3ou1)n|zuB8yv$~hqZjS-pzOk5VsFsncj zdc49SY8?hQu|(?Qfqh4Bs>TZ)-1r|mVd(hUk{%6d`2bC#B|~_xL)oe89cw5QSX|gB zrMCj9$9;JYzVd{6d8E|@At`}d6VJ0KhzFB^{%y@Lvu;XSOs0v9bt(P_YxI~)Xni4Q z7WPZuUYE3O*$I-iC(N<W5q5g*NB24n!Hn+hwNq&!qj`3Rl7B_=VP>4GPyQ#sOOXO{ zC-)5m9X?zsG}hwbzddDRwOQo$<cZ|lRro^}-P3dM`HMKvSiy_2eEj^y--tsF;DWyU z%r%4=2CyRyY4iDvB|&Qwi1BDoOm!QAvBMocaCkt8@1(`}M;^o4OFzp8Eb9U;T$ew- zF+|4t%pk@C=rx90uWZc8%$ZcEml_aK*4mrWC-IN-Fyd;3-0lR^40sRoVQ-86teNow z%)h2xgEPYBK;<1)9*j@ancauQTVYu!S5X*!8M|t;6aU?uE=^X26xN_eSak$(se3Wu z;eI-zdk!wxp>&2AYkEBe`N|}O1{J#;7X7cv$L&LVFu^vvEyfmQsU>x5pIfr1xOh8| zJDN5cQu=q7()4Jm8CcR0R3OzsY`@PZqqbD}yROrK7Vkk-IR{Gcb{IA(^KOH}fBc}c z9NqF3e_o{d62wf9lwjQRqqn>Pk=h!gB8umM6r$mvKYI_99qlllO%&t~!3~l#EiOq~ zv)xiK4l<T}o&`oOXu|-q9sR|}FN1;Ph<UjGD;U6+Wn1NqG%;A-?P=Lehwq@muaEAz z63h>OUETn$#m*sc<H-88hSkwKBG~Hm{>xDL`1{JU>m+ogAL4!(M+ydLZRkU(oA6vP zCxpjdL_2Lhmgb8~1Qi5KQ{rC+H44)k-O8cGiEjOgo&srry$_EZ?~iw4X=u?(+gsnk z%R^1jZV5pytO*ys%Fc7+@cM;gl`)`dlk_`#@C+c=Y^!r(qN2F`|Da1N4o__HCWk-g z^({lB_hE%$fl|eQwQ<`5$O--4B_JCNCNIQ-0J$A@!SO18uP(p*+)iO-roPH8-hS~| z_oMIur!S}OSeJ2fq0rO8s5gFiDxx96Bs{yJcobn&VNP5!6B|L-#Kgp`xet=jVQ8t) z6?3nQx|z*B^yXr)qnAQ1fmzE5bQ*Iob~49r|Mtzia(GDD#n;-TLGs!eNF6!30^zL3 zL&8P}dAvXX8<WhUC;kW6Ujllh4`k0R0hc#}2rs#Rb<+NK{K(_W()vYk>S;UZf4bw} zkOeFpT5?k^{$Tq60ypo^FU9uzP9&1q%Y%coLFgMJ@GXwKf~Wbaec6OeKA~EvaDA}@ zZ%N9weXfW!@jbK7)p;{EhH~HWtNU&}UsD?+$lUJC%%*j`NV8)}1@fkX7RK8P+=276 zRCzsBa^hEb5$!+@IDuji{)0d-vRTB&@qDb_Nhxxy+8Ig-;%e?i6p+yQGs^&}5n#YV zE%VT<rHTJq<vCcIchNzj)e5)m40{kM{w45lDo&@s2GIl3b-b_m_$=GgI|oh@WurE; z-vILP?;?MH7+%<)pJJU%G942vmZMuN+i(nsq9f@_LQk&=E^gVl{S63CxwPJLjBd#{ ze`^Yr^gVDQ1lHhFL2w-@RR`MD{UC-{{W<keYCtLZhmMGGK=el6p2L{pLqv#YyIneo zpk=tmW#`KQ-X=+2DKn!{QohXfd<|%?+}ZbigIlz`gEVaYU?f_e_frM5{l{`Z497K8 zo7yx!sb<4O;Fi99P(b|()y`9Nv!I-Bbf)<SqoT5^B$v;GB~8NG#S)6Z(Uk&%cnHGg zV?b7wfS<;hbMly9<&bH>CPjzjqnHH|qiiD~2zudwD)n+Liwcz^%r}6CIvHYnI}{mH zy`Q&CaR$tf)@;54`*kz%2EzWr7RqPaT=#EPG4?<pc~Z?p63|6>HXxjRx5`ezMy}v8 zh0e!>YB+fh{;<PsR!gQ2W+hIC5gvjZJ0t#SqV|j(s$v5p@OjFvTd#}k?Yk3zAWvc% zKcrlu)M9x+IRKUpE}RUb>BhlpV1cfZ;|#-2_5qg4Zm=s>v*Kgtmd*(Ix;Os?`3}l0 zE6%|Nd2@(#dW);-KL&{?&f<bz07P*t<<nEW2h_LLxn`25VA>AZrMu}A)J<6+xoN+{ zrnXtA_Snz)G;ecMl<bm<){t*I@Nr0W@+)g>10m2J9%&~)rbMLl{`@kFsqW;6=`3`^ z6MziShhDBvmqSq2(l)>5d>VE%7)APxfcE~Hb4A}_#NY+>3=kVt-$JY>-ta_~REL%$ zu8LUZ&D)2SC|<Na1hv<Lns%O_ch5iU+^kIJ64O(v!B1K+fMZKQsFU#${86DMO`foE z0@fOuh|Ucl07&ef0R2%SDi2Kz0#`@k?;dCbe15A2X0&-r`f07o9TF5qrZs^zWn%<s zGn#M*glEo|ZVI+<0M6)ef-~fP8cO^gVra4g*!{Y|#!`d+-xQo2dyu6VN=Rb11d^Y` zdCpA_@P-i>dPp9`ZKC_!mJHAO2ZUm2^J{Q{M_+$FBxBy@OMesl*4^0)*S7A_S(Xkx z-2;oO9n5|^k$6Y4D#7Jj2&EsZ_Bp&981{*k&5Bgx0i+Pu=_p?558d|p{?Ux=u+v&& zhsb*(3h~995o{b!K%h!knq)f%EV^eC=@xeM2I`A5NXwIuei=}@xwb{a?|y)8TOXlv z;Fx*N8}5-`<CY#F9t=N68h<cEDW##aYt^>n6@)?lKjg9I*k_OiZ5lw{-my9>$J)CA z=pz%%6xc@+$0y<HiKwXYGW^jI0n~CNh}=ld4h50FaDC%PHPyzR3PJ#npKD|G;%ky_ z5Bc4HMm(};<X%S!;N-pNLHpm|AE>t>)4pKlPqhJb(+u}QgPUR)fE=Jb2M0tOR?)gX z&g@ggKI6{%zJXuh2?^1(?#8bCY}s+WoIzMeAMoy_(JEC$ltcuU5vm=_wbFQW1a^E< z%Oogpl2B1ZMBi%^gm>R_;@PL~Ua8yqfMZMqe~+Xk7OC%8apBdm!>cF{Hl!b+mqv;L zkRymmE!_t5D!)S_MOe6H5W*x%6Doa{fk}1-#54z!XqHTQzF`leR$q*qVE#gcGJqxS z0jwTMFzQl+wd0mP-1<F&0s$$2UyZ(s=_=Uc+<tH6q2^V@(Z%{Q%#xDb<Uw2Dy<y#R z#)EPE>E`}&j~gWs9^f&O5>#_^;EWo!J)@7$)tcRBCTg`ADh@g9aG*25x!o{Pq;V1V z5_q31uzmf1?7j6{RoxdoN*v^XASJD&fJh@DjkI)$bf<KKGy)>sAtj~KhY*nNR4GZ3 z?hfg?Yx};hpZmSf{SWSa9v*){J$s+E*Pd(6F~=Bl7+5>HieP=v&5Y+n-sVT=+i(1b z`&2Fqr880Ye*W!-0@V(4H}G`&#LqUShYOoN!_7q6e+9}<r};KCP~*|qgLrNVrWbHR z%s@bT<0lGx#Ml%PNYfAPb+iD`l`Qm{1?267BayzKn{9Az^@Cz%6sG=g!-%vL25OW) zv^#-P>9Z&(ZX3S_+iQY^p*rqw6qf-13I!9<irUGktmy|j=_q4R3i;(eBxSe+%dA>y zt`NX&_mZG<{0IKh890)%>5=@VfGfEw6O!Row9Cb@?Nd>SV&N2FpSn8Akh&QURweX> zKreFb)~>_EmZo@78;BtIbFq8uZ}$==13(6TpYy7NRI<7CuXecpWm@n%h*!a8_}<Nc zc0Be>tHM;}LY1jS)q6P~BoBsWDBx_00eS-X&hv9Gh%5{>r>%e$$w92`@^QE7&nh(L zDR~h@IhPZ}ocB)!CHQ0PKcawth-R7ozRDqV*d>Oq$#;N&hfyRH0eekyyZ;4qyW|`T zY^e_f{gH7yc5YCog^&$^<0SM}0I*V$2YD(T@bi5)azM$1JohdifM<OSZd_AlANd(u zrmVOoiSa`XKsvGLzBTFm?`8{?gZfbXO2|C5a!74rK;o5fI}l*+1u}D>n#0!&0!CQE zwPH8!M4jX6^NYP;Syg};?i-*2sn({r0W$&%h`=zG7eE@87f1!_^5=V*piP$YyB~OX z@u#xF15J7=!4u6<qH0B4J4iH>+93az%77L@NDJta=7W>3u!2$TgABmlY1PUjU$zc( zgQ}$;01iu_OWwDQL=gotXhuXBHjj!ocGA58T4a0#egMcb`?78>EdWNERjIWXDP+_J zvjR>o&Xl~D3`jM10A3smjNkh}2)Y!B<%4SO78;-;v5pNeeEe^E02mtLklMu-bd00; zbg=<YDQ>8sTVPBFZYW}e?x_P^*g@_D09uxHh|EMktpU??MCZOBw0@yv0btD;ttWtB zTN;f~LL4EBL}Ltq7+8~WDhlm;RL2ZK&p5mLDB|7IVBv_s0Xs&6+G_qc>`R0oC2@Xu zc6gygg^4II$z;{z?~UUQ2iQ$(FINh_)fpKUcP7xyfn8P020TU7&)#eUALN&hG;kme z1lS2|02^^te4_P*Qo|~35@!pfu_eRI)qjHYB|W&Fz53Vxm^lv&(NR1evZ{ZI+2{jI z)2+e$lpWO0@e~SSo=gxd(ZEwn1L;_cfm^<8qWTW#_x1vJ*gS9^R<ywldlEPybQ{nb z^1M-;p|9ZI33_3lC;Sn7;LH8<Gtcn;7dY;CE{o%f0v4>DTs%M*qeT(&9AO3Om*-D! zyNWWx-+~??L9GEF&;@4HksmZE`(yK|5`o*qH3Hj{7At)e#KnIWNg@kiZ_$(@tf0Le z=KFd9fp*tm(P41X3_sKv#o;F>AQ3`&A%wckDUmY*?&%}-PgJzhQ3+|h_Fa5*yT1ki z_z98D?oWd<>qLI~PnAXlElu0&_78tA6!ZouP@4KzqgS$qbeM$c4ah&4?Z==ungs<E z7zv<G=?5p}r)k{xuFcoyMc{arC{!<?0nONIjn^#0WQeCAm5N0+f;JWk4M?S^biabE z@1K<cD-U>nKG~ELJy8!k$9oRUZNcA+(G4Pu#Ls{v&TOIMZ5)u>jSd34+dfnrL8|)# zZVBMf*RI)DvD5<L`*{f<z!4W48vVgEfc6HNCrK*Y_D_uf?L{~Scsg<-2<oRBFR1St zT(xyT$iAZl72uu>gC0V_-V`uZZuQCoK0O8R^&mYZ@c-||!<*I1r_`La@dyGB>KrQ8 z{URpB{vJiR1cR(_WoEPq-1Z}tdz~*R4Qtb&n2d!2N#a2NyAJ>``2cth>jjX>60q%6 z725*U&|)S5sO6era1hMjfnfgcCi^!fCqV&6u6w2wF--BU(N6&S@KiCUfa{yXKv#wi zdTpVk1lI!-V^$5a6$9q)8d`l*#r?kS()Cm=7{5_Bd3nr1ZHRz_N}Grj&hxhiK;;Ch zFzuxQeH%5xVHBQ*X>brFv&jMM1VI@P6a@3!`LdcYF$KtF&wvtcV+o|8MS(8Vn&SZU z*dE`%`zir&Eg<-;?+DuJF==o9gbi(IWvm4!$o{Sj9B<GL{;(wk=Sk=IUbz_*8IKua z03VDL%v`jYY0v_$VmbWYp!Gn?=ai@ZN%<*00l_v-Yss4_OgB(5FE~7zjyhn0_PJ&< zI0H7Lu>Yw(p)G?eg~E?J4%%ExfFN&F%;+1wGn^kj-Q=T#3>p3X2C`CLBgE>TfBGN* z@S%G^?P3ai9#sJr`MeL5q_C3-P`mYkc<`E;?^tmJz#7Q%#A4;VzBU{f9go4X?F*i7 z3H<w-b#Q=EWCpaq0CY{!{XlHiRTI)OWiD6)v_}GfXiw;oT3ta2%?a!Pdt<0y)08_c z%R;z1774p3XnmS`@dGqKdOf7&xc%FmIR6qTG>ke_Jce%Z&(AeJ*hw*2cJRymBq!mz z`!cC`f1-#e0tO1!54yNEKdTi$@tzyjDvSD;=k;w&?(iE#T|o09go18>CDaJO-YEWG zeYXJvCn{N+SwuGJoqtg_u+6CGP(VVL4E9++fQ}`U9%c&rXagr_YDmupw(19U33-Y# zKqI7*A;o7gG;xAYTH=R7qKZYgwMoZ+A9JWZiaBx;5u%`(2uJ}lspY_%Min560gRSZ zaAP)ri9ie>%M^@2T6!?%I#Jl?ya$lKP*{eC&p-+H2+|eW<{??HXB#hqw`LlwiYsbc z&EG}Ye+rVVwXRgK&YBeu{=CNtqTn%_0aFgyP#@qzGP(|D<umKM3%vRP(XASjrvSA5 zDR%&-i_+P7`DX(Vf}73_%t-uO{79sUM&09kVDUY@kQB5lFD*f)ka>Rq!cqd1@%_!# zzzYgBYXOf|>-ld0Yb}ETlQF;xupd-tVp@7X`i4=qzzI(euzMA2bS7X#0KPQ1ckCdd z!@pOV2=lKF%)cEt7m~PO?J(^@1ns4uc*s2~(eDQytrR?Iix!k6T2Qwh&{>i}?GjRX zjz}&+(^Qw>g&B2!!vt$0CIOZpRJ4NR@0&G2`yOoqB!u1ii@DRrVPz^5NE%AeF6zYv z?vt;f$cvC~2084bkL~j@ATZxX@c?FHQg*XV8S)roLZ(E9?pqT^zd|a^p!G2Xv2qOd zI_-apE-5M<)dT=_s#jd`exToQ-u?CqxDy$wDHtGMJ_3FT2S834PQ=P)(8LTl`UxN^ z^@2nt_g9Di<{STXa7?>Wuo$9tbwh-e9Ow%qv{Y*U{Q_%{=GYSBs^y%Q0)*nl4&6WZ zL5Bj_1lYk1&oC+1WT3JFKrRn&Pv%NTYZrX!twtMboa$yln=n<`2Uxv-F!Txy8X_3~ z-gqn>pn|WX^OzmqHBd9}xcBE%pQ9ki?z0>EL!5=PKm{2YWd&f5T@3}CxyQ$V{-a^r zBv)U>z1!q-0c)*=wC*x38&Ej&37YsH6Agg}1$tz(i6ss-Z-q>pXy`eM7UMote(w+E z8i2dU0+grf->$*12s1#{>QiXVkql>^B?L_TXqL-qPUtB0ABAMC=kRg}82#tRh}N*$ zAMj9SQy81h&D&|A-{Ka*$ha)2$a!pHfGg0mOhHd|ULYFG1M+r=-pA)K=Wka30Zo%D zCZLvCK;8yuocuw>sY!rk_jmhs5C?$yd9r{K@cg3{@}|!gW7DhEwm*zcaN1f8=fy%V zBgE$e=PPl8G@yo;<vA_)9f0l$CdzYd7SNhK5BNN_h7ba`Gy@j<NGkXOTAe>X3n9?% zM%v_Cx@#bm>VN}n?ul4Yz$AtUr+qX;N#!z-UI<`-a-c0_2L2*x!wsMtbinqlPyuv& zxVdbwz<uL@x6{Xe-tO=2IHh`zrddbjaNj<xtW@yyPr<VgfaKlQ#=8X^v+V=QG#|(- zL+(h!b*|R^r#fKQlwjTqIacvULxaGMB2cDSAK@AQ?`GR%K_3NB;Z$%kG~M_>&mHQ` zL13B_2-%1+%96JDP2$dR%gBGp8EXVGV4uwTL3(aLHv{CXb@f~zj(Y@HIEjE$+Yb)I z+!^KV5F~<6aGI_^-5U-1m^t>iMDm{Mzd2Kk=qGqOV2^-jkX!7z*K(@}%$#ZUwO<Ew z8sdOk!`GkLDKqGPzJP#{4ERMdfLo|{F1A04hCT~cGe&fpKs2U^*uYyw0|*jLRluwR zQZNl;&Wlsq3Z&tjz@zZ_6_j3pvf?kV<SqtCFC`_u{<pmz0PX^uHIRxHvUaF&3jSQg zwomA@1N?~e>UM@fQ=S-tMSnOAgMvaJTE*KnXYSUYL$BoqPDL^fN_sZ%zN=PQs(d~H z<f{#V3a}$9fJM$H#4r)!Q@R~IhZ9zu0D=P&c#x?6oyC85cDVx5HN>P^eZc^N!$+8G zGiSHv2QVQ}?6U`;(<tI4Em%ij)1>{$IPvHqe~D#OB8`ubtnc#;Kw40m%OUg^q>xfo zlDHwRIY>p%_5g0tQV483S_)~~-Tp3hP-F`jf<OasLZ#|UkZ$z`VGzW9BM3*I_eEN$ zm^9D_sMIoOz&e2{ca-io`IW_gtq*$`c(W4L>Hr^O)yTW10ni18f!%fh<)j0HhguN% z{nK1Ye*}p3Jk!rByrEqRe}}|k_*$x);D1fZ#1`NQNC$RUFVF1v9rUjYOjL7E-z`{I zB%|W|^G2q?4HxXdnF3(|j9L|W{7x%hNrBVnM+lz;2CWuqJ9{=_OQRYHP-x+pBtg~@ z{9r}JyW{Boe#;Jc093C5u-T`&TD?GZ7#QJXb(@^|yNS$|-~d~R7%&CIQ{YeA1$qo~ zPu~MjzQTD`5n=~JU6zd}D8^v(D!n?{VF43rj-D_i2vh+_oIIcm6?+(NuJtGUs6rPG zix2+ag@NC9B&6sWUy*uTSUG+x*pguy#~YX&3Cjt%ti_Bl6c5M?{<r7oQBpb0;(+8_ z4Wry)|Fz4>j@}t~ocRFKcG{WdQ`;G|dx=bxzXP0bs)8%I{;VlA$hfG3dUO5;7~}Ak z1V%OJkfw-?VmLwF$>2p_aT4h|`FDTKg(GRGd<CjiKn`qUQUz@sI?#M<Qhavgt2yTj z9Ht=09DpmR6!x1S|M^y|C|GTTtQE|ET42z1sOaHP=tjdDij?G91xe3FP4z1uphYwT zZ>;YT22KU!36KXg>t&Z;|KpRt1GBJsA^fkeL?HkL?YCXipOau3>Y~<&4@CXNMl4Z) z*MeHB#GWqzxS&GJr-!G^LBt<Ex`SN%^}al?+khk#nH~!mz{0>pvn1*3k<*{z;qMx3 zfp%7LhIFzIsOO=~3UuVdTL3_X=DP$SC7KDSRyA1dRQ&+?_CPb8qv_RLjzrt;|GP&2 zJP=$}lyxy}vfF<@gerjKfiifb&CcGXq*%)B6N(=I3ELCtkeng{G~T~g|Fc9}kgLQW z<oVy<1BNG*i56;<kTHEbs?Tr`Q3intR62Kl-9A-_B>nqR{Q2)(;2;eNp_Tg!>Qf>2 z<NI5q!6Yy&9=z;#%f$ZQT|rsYLkMD8Mm9Y9Kfb|#8|$B69@E8iHR+iQ{2w>^-?{YP zUDkmMOC^g~|7{BYvwr{gKM@>Y&+$;`x<&qnqWwQU1ll71|L6RFb$x~<YhI20?IZu+ zw;-+p3J}Eo@mu1a2Q#Z;Kr2O}k}v6#7XW=Zfehvua03<u<6Gj`420#Xm^8>8K?u|W z5*~=J0{UUBz*#c}$h>HuWn*XgU4MaC<It$6P^w1f)hMWGcD(b82{;NR0RJdifHviU zBOX%qg;oV5N+gR0w#y9JqWr(^?Hjl*XnSDrfnH4<fO&dA{<RF9+e;{Dm@+_Vl869@ z&~2zyCYKG(ic>GvQ~`72)+<CZXVZZZ1=ODgd7Cl`RoGLiN7_}E)5eg8*pFhZk;xmt zE$9K^2TI|-`%J?lS|FYk2(jPeAsGx{61q0woOFTn#SGMFoPc-^>BK7Q9OR5~^&zn+ z$mEkiz3^mnlpF&C1EP`l12(8TBhcc_e0xC-La257Q?um%=Zg)<$dIv6Pz2x(n|)bP zx{*z0Wr4J*e&F-tInDZHfUw96NTaXQDTqD694=aL5tsE%AXHff*|_^8v64N=lNczy z_X6aSsb^f*hda$EXHTV(#>zl-mkdfJKBb;Gx^U6Ufpoq~XM-m^5LOH<Y!e`lPF91a zEfvWpXqur-z?M7@xZ3j;&H&~z{F-WSw$8ObpXH0wGH`txgQz~b$A^(VaEb1jpTd_D z1ph|u|3#eucKj#KD-rljpo6-iDhJFHmmuwyMk(TzLOgxs79gR5!Bo_cZ=a#o72sDb z1G?gKzjM=sZiwk^wA1@j_(agncemtb=6Evo>BEa#OiJ$A+`wgL<1u;PtA@njftv`@ z#|`)KtC(~#lFDqSs#J0wZFqndKa7C<69Lf*L=XeCA-<w!U<QFj#wF8qeQv!fY&Q`O z(wc4V%&ot@bdZDo`I!i50cqSa;9NYnyXEq+!eXE_35bbVi@Ut(PCf2{;woL(XNvAN z^B^KUecc@eF$}a{36@4=-qgCQ;Iy>EdrDFS{5c?{76%gLX;5U+fT{o%Y#OHpJ3tZm z4aI_Lc&*0B3!+~_LM$*eULRB_Z|5?N73VAbgZq);g))ea?hafDi;TS{{l-@ZfULct z*GCA~Eo7gJ2c?f!6qDC~lAXV22ZsWZT!`1n&h~GGu<u-U)0$e9Pv!R+o_Ykp4|e@- zex}~12|ae-m?m8%hfBf6?`RTT0gusMK$Th~#;avb;kD0vF`MK|XgDul>o(_xL~{dr zY&$fWTD6mSwo^dP`jEdiNrce;SKV_hk2Y+0N4LyJfGrh1BXw?^$2Hvd4D3f^DK(~n zmkLi4pv(dUM8SnzA2e@CK{L#Yr>O=5xsD3aD_Q|@SN@M5khS9;;d;)bQ%!)$vs~{* zWdLlF1h$_<1%OQm=;f6=LBH1?)N6#zl2Xp(TXm7kM}U=}EBfp8GV?^6@mLhb_#GGr z{VoiIlA^%*r}9U<)DJVg3<doLuqB0I>){gT-~%!im^J{XHfH=K5Uo7|K<-`5O_0WF zDLnD~){{{UG17?IdldiK2mkxiUkGm4%TAM*rdDp;nUHUWP+2R#=K=Da10WnLGA^H< zF<?@17O1^KM}`%E>M70^Z9?Q#AB#N<n5PPTT>enAs4-2vbwxYawDw--ykUtRK#G>s zrzRC50bIwsG+uu(`M>Le%LFrg`*v+@<@ZVRjh<Fm>Iqs!q`w|e-#BOHTxIaPJJ3?0 zAbcepXg{1jKzN@yrGl{%UtNV&g}w1i`_pOYF5hh~RUZMXy0KR#ZA4IN>)(hmT}vNj zOWv`6_%b%{{=$=(2TnVIJ)^S{c6?jE+>ig%o?l_Z<U`4oq{w^+OL0M}W|DmxNkLPQ z53*n0kCo3<>HYQ*WNllrNE(Si9^<sG4}vVvPqVUK1bV)vYYG)?0#Z1OmIA}Rw<peq zM^FcuX>;7e0x$YX+P@ma^<EIkj7u*7pE6P=?HB5er0i*=%&O+IL6E`R0;%sm^#e?- zrQ9y~$;x-!H}mxhcGK8P>MMW1Z7=+mypdq?u2~GnEdlC^C3MH02jboev=}AY&&0Yv z(q-$bc^zjo(jc?JaFJdD+>Anc?#*Ms8KJm%Jvjt$Ub+_jT0{A3PBeL>oS#69!3e5e zj8olA+zS|pe8nB^u!rHD2{DH9-tXcryhgIsZ8HVjzb{{MS=F9SqsgQ<Wh0S)L>>6k zp%cx6Kha>0t0#!0dnte;StvUOx-)<RrqGg-=fr%farJCDF7Cr_QQY9~fQcOf9VNge z@}HG(@8^IGY>a%2rnI<7&Ic$*V9#Q-(6MF(!*qkE8aPX6A&=q2&&<V6crEBO`+x<8 z_SDU8x;C2`nOcU%Fy0H4Z#kHy@d*hJpo0&bGnmYKpo>le0gPfAfELl228S`JX_9?N zI9U0{1YpmTo)EghCW#er;K_n3=zV|c2T<pt^V|EDz*ZBIJ|qj`>djLagJulth2suD zi*=8eLHFxulrp;%Fgx^7i@=7LD>Z1|Q7!dV1E+M%+k-m!lNS<*EI#KCb@~oi{X6jl z!+>i^PwDeJc8*`_LiqaB#3B|b%HsePwjT<r;A}=I+5wu>LTdp~>wNdVwwb#Gz8p*| z4{?r?7}caeqWuW?dEx3VUTeOB9E!kscNe0>fw?~#kV^dd6_9PQY-Q1}{^tb%)My2D z=0+S*h900*nF!9~qWw1)7|vp%0w??37HH#NyxO=U`CB0tT_Wgo)miL&;J814s|Gvo z^NIO!P^*FBfDwdnNCKeR?CTSKNb|)6;FeJJY>^26ZJ}scBajPtcm)^!d|964C&^G% z4-|Iq&!fDe+vk<X@0{QE4S*50bBDh71Vwo=U}6iDZGscEN91}R=Q&QPT!cILz|Q1R zR(d0cZ*x<xmA1jbRM=1}1&CfB=`H6f1!97{9`uQ&&IMgi?%b~ZF!aL5_JcY-J^UJ& z<n#dG9_<9j`_A?5&9#yb1sEM&Iz1tH^g|6)S}k{*QB@0>QWi0~kenJV*q1y&qaOlP zDq#1zubJFuNgq}?`Ba>F#QaJ8TX0YmHe}y5H?m<!?i|rRu8a}2!3P6U8bvQT7($tF zZ_y@F9RNA)C}YFME68I`LJqD9+Gk_+qf8QS0Lk`=q(W#2WW2i!U{T^wL~lOuhVKEe ziXciL6!QTAJ$AZaV*)fxiZ?hdg4QsoJN010o>W9nsU!lG!>`3sIKpRf*{O8bU@E9$ zPb8@Q@Fhe;e=xGBz3D-HiW6AHXJi06Hs9)XtEt<vqvvJjP-Af~sn^zm99>VAG5F9} zS*S``H4!b72JlV5omCAay(DfoDCKp7c<F$j@+d%Ud~uV|_31+|P_vIp_?LO(7PITu zvi>3{l@2Y^_89G^z9+8h2L{DJ#K<4un_V(2l9a~RyI<*a-U_%Kup2`q4^`D+L%^PB z6>EAF=oYwpvpGG_(2a-#n!r|O0OK-_;ufRzAQZP$Zn}Fl`d+iWk@0*0`gO`+$I_c- zA1Ai{O9}$&9gVV;#hGeKP_WV=>L^j!bRVazIi3XDeh=^U2Z$t-RLb67lEXJ|pn49w z0w`wsxB_?!6DKgJ@5QU^oG=#ilYj$MIu;cD1n?BxU>~}ORxpn?uXH2<<vzr$gC=qp zy}fO)Yy`d3gg7V9s1Ny0FB^fQt?YZ=-IMCbL?TFkQ6oP8%K{5dfFTj-zc1dk51az| zt^t>ZFM_S^)92TOpqLLzYWbCac)w;d$zi%w{l|qt{YI1kt-j;*nOo`NPNu=VD7n@9 zQ98WhKSN2FzojU+k%$c5??O#$KW!yUq9DN$yR(QMw)lBm-`N|?DY;|9BgA}!P~OBp z1%v*6xbm2PC3&-tF#HuFRc?0b!wF1Yj!qzjls8MO&p_?Xym06R^-g%rPmM$0*^a9p zwPg#}eG({c4-7Re_^_<$NYKArl8Pxx)YSvmMQQNp?}bn;sy5q28!0S*(y1vOH|a46 zy;qnKvbN4%+^u_%tt<Y+>3tNa3IsR-fyZ$gLF2m4;7dTV5Z{h_PxoNsm?SCcPCNg1 zqtI8ZtMk}RKmE?v8QxG=@L}zL^=zWX<c|<Fy(9kHfn+QKd}`>TU}=9>5p_#lf^}%w z9dT1tzmQK0j#0uN46tJdjo>MFeps=NH$;|mGtcO54A~E|iKn=b1cvpWg*Yt9$jf8( z?-I9j4h{hvEBXBEHaAT3m*COM(Cj<yC?nRszklN5-VeduKC1nqD{kpVl9MJkxnqx2 z^g<fs`x$1WG)3*WvG<_yq3sBKm!0utGNSJr?wPFUvu0p2lmp-ocha(b=YVN;8(bd{ zmvuWd044YLed)<MimSqIy=F4xx_h-B9Pg9RR7(4%Tfh-@o)l#vN9FyWUk@xpW+kNt z-eXw(T5qUl>JzLrgZTFZc)yrxR@A4zb`p=pLY_coJy&ubDm%TmVRAl-%O_OWwR;16 z!}xxN4!ollF1&bSl)uGJpO@b4G8vLz-i}Z_d3gH_yGT9y@(E5BZTs+#`R&Sx#gO-# zDw*YEEwL;*JQkiIl!kApqXhQ&EI|U?-B<~dUHx69IzyA;J{8~qYvI`iOE>8V#k=G1 z1wfS<7p@}M)&}U`_mdp#M^APDJjfq`frq}69iqI&9%K`3jhmHW`QWQCECVZXIsnJX z$?uc~Tbk3nA+BUxa|SQ!rItAyPV!j(j>$^z5a=x=Q)+doM&c%XrvX)1j>6pcJiM9C z*N-IcyX$W+*VbRHTJjFX9W6e6cGJ?r<Xc=P5)qs;ACey-Clrz|{xHmpltZiq(d9_$ zcWL<%zRT~ypp@x?#~fi6bw}`2igRB0?ZvX~V$-@U&FvE{dVB;qay#aa<?Fm=0&J$@ zP#4#|xmH<{P9K$VTVL+tj)t9aPpl%%QAK%&4Ihu-?6+QRl`(uc)!5;@CpH_6<t~%R z^Q}V7M)Paj&7KS$pFoeN$Qio^^-icZ|I;;pe=}yn<A>y~Uv4AL1slXVxNFeOPGxb4 zsMAvqO@1Quk6gq0eM1rFx}ncPT+90Rm75?ywjD8}W;^2g&fpiCW_#NYBWBtcek<M+ zfTUHO3z#_Ht7)_FYURt>!xuo_+C>n^2UA`OHjH}vN>D9r1i;SeuIrrCGav<!GJDLd zlqecpe!w$?ysw(Ix=k1##}CbHremWgX`qvr672z~d)6U8S8_%=(rvu&>F$H?pHe&* z4dq>J<$3ZTxs9%+ZhZYZm0MS<7M#)10}R3+>y&U$u*21&y>Z2Uby|350s-D!9P#+a zd9qHU+FFOCf_@&LCkoAa)$ALL^imN_!T3;#)y@*}?vjJDn+K-u)8xy|Z1k(L;AD+h z*t+M<vC%=h5UIvE#WL^}>o=)rLqxgx3RB^F5#(aaxgDkc*baM!JSGUQqunX19Wq>D zNa)q1pFjFAuYUrlui{!P{jzk(nv;fZ9ecbB`%l{@RQwg_3^Nr`h^QP^8(Z}|1AhV$ z*AB(OC9+Wfz0L=W8DCS9rd6>iVL{mZo0PK)e36`K%7<dwjJGTABDa?%_n$6mvnQcx z7e)@*VfhxNh|o@in7!h{-$|?WdqrpzdBH+}G4a;F95%C9`DTDp!xr|AJr?D*lHUzG z24=XN(EhreYXO+^RJO;AiToL;xW6B_apGajR^q0)_%@LBk2La7iUsmf7MuIz;|QO& z(6N1Quk?_$0?FL>Lr6mrcR${K>eZMg%GTG9Kkq(5CQ1~8xzsEL$E-z{j{*1Yblb<? zg>}EFf7pK=_vam&xH`cPqJ(GTexL5vbM6S@FGa2lW-6t0N5)QyY{KuL(VJl^Ygk}P zLp4tR{?TB+F&f69e|s-P4ky~XCz@xT7a7KElKKUeAZ7xGV`z_Hqj=l^nTWxX1)lXx z(|5ydel!^=-0d9;OYHcb=Vq~i{d=VyqRbExbDxRLqC_;!lY#7c>q%=$1VLb9DqXeX zw|4}kN)L3$wOiapx*cB6`5Vzm__Tj4eMFF@pgFJslT-C!ne$#cN-_-I&=<}Wm}a=` zz#6d+eCnIaY8HN6ktB8UXZc<M7u@AI$}Bb?tfIT#bh_gnJ5Og)?iym>Jh>xyZ$Y}C z3|Vp&YnHN!1onA0RCgU#{B-lh*GER4=;q4%)D{(YklV*21{~W@A$gu=Io$(XEabAJ zGVXAJov#^q@{W$~Q8kp`P6H_Vf+!1jl7vo;V7JjeoKnpxsQW+18li+WXyJXinYf{K zH?4M{Y_y$L`W39H-6j<xV*M5i*`Q0PwU)8{K<&zVZGb7M_+9)w@zA1osM=2d^8O6m zbV+b@FMGq0qVFJSx|4`jG@{1lC1r;yOVrvm$+ecx$~Zcr5AAHfIBFKD3BL*5<;yvD z0<a71#CO-L_6-gXN{E{;(#Sw>XVnapdgNIjGL5F`tb>)+NOAR=u(&Mo%Z}Y6Z!J7Z zKBta#9;9)9qHo_^H*NPE-R+UbW`gW0-+$<C-_t1$S1q%wpO2r+{VodAbPj;%vA1ar zP>Sbo#_1@h-Yg%?sDl2Z-hmiGj#UeIkWRdGLtkM1P<MinWpQ}mBNQ^&+CXPdrVZ## zdctb81O7PlsV;#YFJUcCoIEJkp1L?I4KuoAwFZ7G7m@R7I$1kMqwufG#X2W=S*Xr| zMMOSW<E~B`2LSDP?wL#1@_~bl%tfq&Z&92!WEPLZ9NUM#m&ZGTFXQT#-sFv<!~<z( zuBXnP4kVGGc3qq}R=`bC6mS0PvV(vi3^yMqb~}O%o5OskO$|d1l%AoO$ldM+Z%r;G z#_JBvlen^2Vz{DRTz?I?>tj$Mg7<SLJ-?o+&~?SJu3jkHkcez0sCheUeIjlpOj&sC zf8lC=d8*Nzx{!NveS{xi|Me*aZUz}%KyIo7W#^T8#6=<Bd{g)Z8+g|PkOFl*<*p^1 z-9-lW6h37tiCk<wCM2A>s`ZT)<q9p0>iM~1DzEr%w$OI5RWD{XeQyR4<hsLoX;3HO zJC0YIK`KukvS$5?!8p`{b@!V+*8U5$7S7$rm!3s)3M)P<wlH?Fo7lbd2(TIAz*(}X z+;dDWmMZ<8Wepb6vRHXXJVABnYb^3AIZ=Y}VaU1YdwHzen#uH3{u2N}opTaOc}yjf z%6Eo27bN=he2N`BkxLD(tZ3Uk4s^wlZanN6A=1F=e%5qeFd!q@rz@|KM9i?lwJtrT zjodGltbZ15wvj*EU<M^@-h(QORxgv#Ao8t#@<1D~>PWD8yzdE#X*Ocf`NOFdUu~VZ zDT&9h99m$WkeV2aMqrSyp1~(V44wE%OR2o|aYAr3@^LmAJS1aU0gENg9Rme@BWRQ9 zi|J_{QB{9>#9QR#IS-Grcxsv=QP=av3nr9M$;V%g9}u#%2HSty7zR^&qg9b$yf@H% z-9^p!0)V;tAmmxy_z2d=Vf_>5kKAyQJI$S%FLTLWueo$N;ahV>lmL8Fh7h^C{HE_$ z^VQ^MtkAM7)})|?eBG173?-BhHu~0+{CQg0E9KU_=T10sD}fM?3Csk!k!PImCiB&$ z?&E^#n-nO@e%$lmgze2mzG0S#jtVw~ZQ!=QlhU&|-45Br5=o&=#gfD1n8tfMFU}q} zdajo|&!!S_ddv7UNo}Zj-{hAj=K9Imd|!%kc41xF%=VbZ(w3_QckRuG0!;<{u<6a| zZftx60kX+@<(vR#46GbEc5WX%yB~gwHspDR93HL*F7mX_Z-@4<K03CUIW6A&pbJKt zAMK*Oh@`ur)jMtJtnGU0{;{%7KtHR00MN7W@|T^d*eb)3bG+YAR<LQ2lEUsqKhtQh zDL9MiuGR|Le?pRTf30lZ;)NvRxFqB-5aItGrFB||vsgK!o+E&y_wGXi3141@2rnly z5@CUFlZibqHMzqsf?m&~j;9X5>*!AfA0$sR5X88HI)-BW?FDy~^=RYH(gwzgrjy{; z<@tBq-i+Z!`JbBJIQ}A$>;9&d{xiTgDxE>w5>+aM{Q(z4yY|H8*rpp`V0CKpQLXec zwX13>XwRKw@_mWsg}KvCB=d!j+qRc{?7s#yo-YmVeyAqB0FUT{JjgBWYJ(hlA*Gh9 z{4SS9e|R~*cJtBs%i7(&iRfo&)8n!1Du#+7lEtq+1kNn64(8h8)?kM_A2Q<oypxI) zPShUO_Cjox!#eRD<=JUPfb1^Qm)9qW(HFT&EqlQPS5gQxfDTbpJDg+$(7aGEh)5ll zdB=DYy<m;&V#K#NfSUQm@)C)|o3a;BJ`HCwws?F6fqdc7B#MVJ9y?7DX0fyJ_6a%# zW@LVu3aO+Z30c1@OS3En&MQU?q9LTvXDrhOyKc5@PK$mTCS6y=C-YU5-lUQA<%;-l zQe<!RS8`Igg7)=SGw9i)du8iJgu%U3_6tmy$Mh0s_1dtp4<0+gmUF_MsM%;lH7Qkx z^a*t1jGD1R`yB)*;anM52ARgNkH_aid7X0Y-MLD5n#qf-#_LzvzQL_`CAiz4zpu1x z&&Ym(Jf<ndjC(JZ>aJ16<2XiT`kB(yr73HDtL#Hk;ZQvZordn9_lk(1PWvWNf>OMb zr5Sy{GW!!J6i-UHn&z`M%iCk=I}4kD$csjRb$XAqloQ1&knZq%8t;IaF<PVx@tsEQ zdpVDGYyr;Y%okyS3cS81_Cq}E6~RnRj^?9@E|NuxH6}Vbx-a(vJ#2_#^zP6fc6lq1 z@8}3REu15b1Ko1rY{L`^$*Vk(TTB#aA(qlIXquI&wO$wO4v1<Fn%pmx2Nyz3HeY$I zPY8_4Tkev>rY+zmxuZ6807ex+?hccrVH&UBQuMge3&<x@Gli3=M9`|?S?^Pc9#hDu zPCqqgq><%71u5hJ|25B2bVHX9$;o2Shij#dOGnNcnHDmbw^rB(4S&hqhPR}>EN|S1 znNaAKu8UD);UN;ZXojTZHk>r=^>75PC$>l-r}wEtGR-{2;9f@2acc!f{@qY^;HJ`h z|4k7coCaa}!wOW0vJ4IePPQ;o)zZxvw&Ag|Pmh)916FwJGsJvm;^xEEwEQ<rG_NDA zsRoy}D-)-z1qXSk{N6_(0>{$Xt&qzd0SSO2FrUw$*tQ*iTIlQ@@ccn{$KL7H<LcZu z>>?+cl$v{#ywLbdPLDHhuS?IrQ>Yxs%o)>{Jtu4~{S*Bi&`~!HoH+wy3cP4_Gv<Ut zy`t*{V9wVvHWzL%0*UPvoP>+yJ7MH}PNul|*S?tM!iJd<L3F7z=9XWNZhVPubW)MJ z`}=a+t7HBBU^~8Z^w+-(-Uu69i4(`^0)*N1-2L{m0Ok&R6wODs`e}iebjv~ud}iYY z<Li37|3QiEwEef<MPD1?9$WlSWR#iWl))`RCXKwhqa7lbhl6mU_zfquM@S1aSTTl? z=CCl01t#4aQQaWxMp1(A!Ag?O@AzE{TU3YBT_!cRjgM8Vznjb`etY!XneW<0T;BCW z<Q$B1_DIJxBE<;AS@<r&FB$iCC(SEk$C&U^N6g{&?*YA@A4ihsqm6#oW6eOBzRc4P ze@PD+zb-H_PZ%j=l128;p0{W00zU<c=ei9ZLnc`@_h(?5_JO4}&T3ONz%DG>D;!Um zDSsqRXvbGUd<pyaD=FW~q@YdA=KguMF`YmW8(jv(OlQ%>)$mWg`6*&m<gsa)uitC^ zAUC~|q>a?WvwG}JEgxzj&|ekKV876zIF!s1Wv^r(vgg(T-G%oUPsU1cCmofWxj$$` zVpLH7-o8YS*|VERmj@wN@80p78mXjGjF!0d^^aL&_GjlelL7>%HyeyM&E%IXk4;jg zlHx3FVjsvQ5s4LvnJ^YG=Xd3?KX|EL&77)?kFSy^zgaa%Lnm9*Hw909i%Vvb=5(`q zHumMa(239Ps&CTnxxniFsqd`2r~QfR?rLMh%xd}x608(VmJ2GY81BMFjgwA5LHW{{ z=vG5y742NFYY_Tc)X<6=Nkvn&B37@FU}bGY#%e~Tjz@u%ho$t;;V4jp=ui_j`+7CQ zUB3>D#Xaour3<D@lOEp(Hv2=hXw-p}&k3#TqA^a42}12}uyAb}EC^-XM;p8*`}LC= zZe$~Crp4{wU0v<^`F#;_T0EP$c!NEb^*fItzj8oWVAiD4m8)TL4(lc-pC>oA7yk+4 z+0kcmxg#O5xBe_=^4tBnoBF-yNF`fVrln2mqZ&Fa_C#G$g_&=DoQrid?MK?n|Fo;O zHRdp(HvJCQyqBNs#+Bw0+-5gnsz5}9QuWZ82kvskZXWNogb#<II7f=QE_@`HEdIU4 zGAxUuTj|K6xN-~m-b5wITedGTXOc+GCO>T|6=o((edYA)^2;k9&oZIT#!OO+deskW zC?umc>1FC!#i~)UpTOVeznD@Ed&}8$nG_}(no|%~z!k2jY2S3xxchCXrHkBN@W^Bi zeJm}3^3__lYm<#bPl$f)s>!@H2j=xoqejJO;Pac$hBcd|^{ideDarf=v$8Dm&#Z(D zzEexwzfEGZ5hU7ns3-cP^2>}<T%5q&&Bdx+trFmWnKpV$E#{qm!>yubkqvLwW~-^Y zTzOi9>(16KIV7^ol{AIYLY0joYLo~blPGFg*G{EfBi|6UIcdQKyjNDHJ&)$mh;?HY z%Q^cnd$<lhid->5qnju9`8H-Q=fmINWJMFYx}}p|C}ykEXFRI67#`waG(qS6_4(Z> zG8qP!S&BE}8L7Z$TQI;->*`BFR&!VPVR^I<v%rgP^iuwh7KuR(Wwi@o4Fn7Al-GOH zLyPaz?{9bEWg=5PJymbDzvY>O*#!JGESyPiiOsw{{B+rxk|?KPqE(RFbPA_eBKx{s z{nJjJ$Wa6r4kLPu(tKlE*m3!*Pxhw*uc-O^R;qBf=vJO>_O_1j?+MjJY9u@??^%|2 zQwO}wf2~Z_{k}iaG{jr(r0839lahlVXIY81(b#{FF7$~ld`#%zY<g8Vx%A7*JC|Rs z<IDWRGeZ<6teuz#ATK_jraxZBe(L&_qkHN8hSt#dsILyy74;NVg2{4{j-Az+aE<{J z_E(v3E6S9LL-wLpaWsRiAF)m8#~H7TZ*@>%Q_9=i;)&A0@xgKZ0;bngM)L{`wYeOA z%8lx)%|UB@B(lWt`ootWx*KhQCjs;!zi?mI;?B?P-kl}TmdSPdZ0;1W=PgdJaSGFM z{<b29eq@wB9~}HWj*n;-Q@Dox*Xz9}o5hvh!()8Sa&B#s@rlod0MRz{!llXis}bq! zKKWc)#cs%3{1lF{ia@K3?g(stxil9*o)c<j>(a*Y>=EDKz-(sYaWGN|v^UcbOY^UX z9V`h|tiR<={cIK>V)C?0sH0NgT$NWos1<jMN)bTVjlT<DG#0KU53dMpc;s&zq!z|^ z5}$0x{an8COB>dE=X?0uHz=URSQ@EBWqQ+t4@_lro?R_tt9I_X`&(_pFY$c-!Znm~ zEPEhucTmr5lCH+*T?jUHYCA`i%7_nF>m|J*nP0Yemy^wpL-6L5m10h{3Zk30Z7jUu zkbKr&rdahA=d#OW_G-u7`9@XMWiv4F8hzm=8^_1;MS`Szh9l-c&tc(Uw;dQs`Kqp1 zto9z8@AT5{rsuPGXHXJyk7?2p%vNJfe?;`oDH}y}O+;az;@&7c9$V02v<_`~oSoh~ zQBf6p-xGn<RT~>z?{hr)u{y8jY@}<B$b6;*7UZ3l+S5`S_omNp_}PkguuW0fx)8Eo zF{c@)?kY9aN)=~8Ntsm>rzdGD+q#?;Hx70uR}TK@@%KyL<I1e(2MbK8Fs==1f{S!> z;6qSiDmGR7(NpfDR&W2#SDjlMqi=+NXUobANS%}0)lz@-yt$Y)=v}IIR5~O&sENa7 zeRReya9G1@N~6~s^d%+vo0=PSv8kw0yc>mFw^lDs5w8+QtJSaMURjGwM_TB0Ax815 zJCz$Pu`W4IZf2o)tb%3*Mz|e*mF*dmN@M&!?CdKxsLmN``I&f1c*qxHpQF}hYOLv! z%U~nd*3Mw1!b$tBnY8P8{mkdesCNw6@~mN#`{`nW8k{OGmlkQ8&%W802B}+jl%HLg zXu(S=V_MZ*+b|f^2RynSlX-@cD&GIND=M=j%VqV5TGy+eI1s_Vg=l}YjU(qdY|y`8 zOt+*(TLwB?BGSZSmH5WBjswDJ%sd(u1P+XweD&4i`d+SM-D3*T!Mfykv+Uuqy}#d| z>e!S^E|LaU?Ot97!EHMTD+H2hZ+~^w5>})QNbh;@3E$5r(q1a7{H`h`;pEnP){l3` z4MtAN)`N?SJ@hHdTv+p}=+ho0bSAvqZ9FLrdSIKtbQ`!!ur=(p$xf@NM{HN=iz$vf znw2-;vs9gDc2VEs9xHxK>gcd(zImC?lH`_p%m;=m6~fuy;N>SS*h>*9G59i{-@CY2 z)YM&ZU18AHFFCDxmMcM2O|~xavnc0=<t_6b*FqSLGNblBnQQh{^}vJh%0%Y7W8<c+ z#VOS;DnzZDF7G}*#7oRsu@(#AUWit6|CYdcl@iEv117!}9%im&So6h)07C&^J)F)w zdtvVuWOS~D@LT%!Ltj(54X}N#e;2$`60ePD;z(jiXu9nynt-&m><v)L$cD2>EJCeX z`#i$n(5KIWUF`D+W}7-)7TRm^29Aq_k)3aKhA0z-_#||lky@k=g$~rdVwFgsB3pha zqVY)XE;*T_=N*+PCP`a80<%sH?IspBhZjT)DoA@OVXK+DG&ovYj9o{>lJm3!yQW4Z zO>~&-k*{JX55u!_Y?-se9<r;8Rc%<&=3Q+s449S|<GBkfvWKUnCcrg^0R2;5oJpAF zR${+g?$BIkPoJm)bCS#t6&N#t*u_xqhIXf+0T(yZ5Nip=<s3Ti&h1?Nx3iN{LXuwD zaf!)YqCZ!9CBmLnHIBJ{4eG+oxJSS)z)@jEjryq!{7T;BLp;Auh|q`qp%CPX6pW5~ z5HwzbyrooPr26@t)9`1J-*Q~PO0?g()j=ppA5V(avmxE-`6A=BzilfiF-m}Bc#G|u z#zv0$=IxB_06l|c>IqHegV!RqlqB*`ZA4erKbI<N$TMkC?=rEnQ4MujQN++yROr9$ z)u($$lW6(2iXJ(J7OUxE$=2RWC*z|fnFjO0kUe{?$4J`D4{hc{7_(1a@$i_Z<rUX& zvv5f<yDY0*xjeS<ZOYd|`{FOkA3iJ^=yVFfMSzoNoM|YpWaKe!lAZ_CP|nw@ILpJ) zld7G8S7Vjh4+<>VR$TOU6NMGs>`JIcxUx!Po?d!mnwA^uXv0Rmf@0iru-{z>g{S!t zIn>OeF5aIUtuYq0SzPD1o!p?L1REajf8^IWr?H5C@H0nA>QgvFJ@?K-l%!60B$I&p zDhI)At>rh39ONMya~9<Onvz<qR{1KtjTe0n)Qj_-CL>TuAL}{w(h&v)+Em3b&}*}` zSz&0hFQsj3&+XNQSNpC83OD22x{UZ}b6>7If?LZYOUlx3JCJ1CS%wOcfH!yY=}_dN z-U#`*+vm)+p_Op|qi`#qjz9*(PAB7Hi(Ja`Q+8I|o0K!M#b8HMYB=zc<+We&!J#AT z_8iN0Bt}J+)00~a6*gnN@HTdR*Nnchpnpl?&4GvT#mki3X5EJ|dy8i=OQDP%Se~bu z3(^oN`b5X=a-0lu1vQMv$;-AR5w&%m*cF71aXTi*ZPI%^9X*+gxAEay(Mq+B!0*yv z9^`P7q*j$A7NIh(mng>9cBUrkk#;oKJ5zY&^BqHz>>Ivyl+-dVo^#|m+GL2iE(*~$ zjlic5Pft+wzptNep;MdRi+nje^!6rJR{of5pDQvY<!;%g52g07N_y;Sbg#9j)jP+- zY7cG-F~yW8j1-qLsXsK0+M4D=$g4Ba4!+0<UrY}0+>(=@+LDNHF?P~?s=D@ga?p6_ zxs)yr3?-m5pvBh97NC<^N5l)JGT5%lKP5Y|*BR?)h<;-Jv|HnNhtLb;!R`p_k|fWs z;`}=I!@97XN+V28>xG`{^BtTX;_%>M8Y)y|$7a=JTMXU<L*uTXg7ABEiplT4<PJzY zG=J6k$rvRo>$d8k2<5sI9^!Xa(w5oh32RH2SOrUoP)2t>HV%$HADjUlnkA|>7NVF< ztb>jt<wdOmULTG#mLSnv+FPj)T`=C&S(;3o-V+~A4)PsQ3JZ<q(a2)Q9pxnHADk@= z?GF*OE1!5dEsUa}>-WRc4ZFHiNK`13N@;f2`u>(jlt*rpK#@>5kNUF?14F%LD~ySn zrlXRxG_i2G^73p3!=VQj4J+Jc&uGDHP<x$`k*K{3Q(bkkMU`VNr?jeOY!r>D)fiF3 z0@}HYCs#s^E8JzNYeVKwTkcScyUfdMGMQIo938=!!#Eb<CYUVUZ<yC2X&*|T2~siF zby&A>Hl;{tdRO%cRNrBC!od@vCyg_gxtCC7<MU*vvPlJBW+Zg8W5!sP43U4C>Svuv zmLnLfVUXpJb-F<G@l)`2H<{0L09&_pOT`?&gy6hlvnIZX{`!c<35+?Z)`w;%LEGcF zGwV0SA-0b}5arEjw^yYYM@QGHN6+aTi@m2D?S1D@aULi{isqrAY@1To+R}a71U_uc zvR<1ucQ3dou~XTeM!92nuC?(9CK6t4N4|VKmsTZ+E!WJKc2XR@n(m+9W@)&F`ZClU zk4)L8%~XuRN4_IfqA)_P<(yJrmF_96+@=it+1s-W%m*xN7#|u;>&ggZH89ss2m2PJ z?HF!&{4^{RTrDJ%--ch++UN>(r3XC2BYTK@%QskNF+j_Trb9xDTg9q@;~6u?J6TH% zYhSW3$|?<)1#Oz(Ug;MW9wQ38&o6PgMX;eDOZHEYEzuEa;+Ve~aW5q;Dy?#^LJK`z zvipoa#adj^_bAauH}-`jHOf%l$;wMI;up8*_Q!A*>Ob9O0jYOLs=SqeEkVxnLbDTW ztRd|m9-0362Du7S?A*g1WK##1<yq-&c!<1_CL~^zDJ3gX9|@9h$0Wg^iOmt=M+*3w zf>k-Lj7BA{Ia!B94^xQNeXxfN_2Hy%{PTU8U%kxW?r12LyUa`H((rnpaHmB1o6e;b zcg`T?rhAA+LKp28tsyU{4*6Nbi}j3qRehR;cWPn9dj9Lf4j=Caz?b<x&>3ny9CS4A z^$B7ybY+&g?;>yJxJ)93vTfok{b*sc_A@T$4=m-wJ?iZ;Izy{0ag>1kD5U0Rn<3w? zn;gp8?d|W8Ci~~(RG2wUOUt~}8`HALkm4^!k}ZuJJUBXJKDQt&c6K1=l9hEfo>Hnm z<$Hv)BOY|Vx;-M3YkRm~B1P6G6hl{APfk~uZ*^!A>#DBZ<-9R=XZaEQgBIqZtPVre z#p!JkR)U+g#?jW{{#7>NZXGL48x6&d?pep~`#RcjO94#xpI5gT7d-G4{_f%R>7K`2 zKxExx{hFyhOS9qRSHk}1Qx<Dv^#{VXf<)4Ci%K3CH}|}69tp;0QL;-_csko$SSbkD zu66$e#)S^{NhwF00wd?yS2n~yd~W^t8I^2lzqLEqRZ}X|L%F$2Ev7?r{aPm_7TuY8 zc5IJ){#Owp>TFK(uzmQY4C*>ojj7~u`X^<2WnID45*YJ6^@7IHhBe+T`?r$6&yqZ; z4bSHHbJbh8Olf{GU_RLQnO3z>8x|hEY~*1e2#6abeR;)|C;kY-?lxBxc0mm>{qDkC z4M{T>M!W)3m}7zaTlkuj0%F$p;;c~JjSw}<&Byq&!EaLP_(qRek6d|@Q|gz#WVetv zRU!{X4fkmrHr1}PIp)iJe^IbUsd;Iver6fOUBHQd!d5k+QKY^&!ghL$M`@+881Z~x zCBAwX)1@Gznw~Eges{Z45ZO9wJ4XDDm674@g^9@EE?LL9OH5iAsSzde<^_?`hx3M^ z;UCD!Nv(#1I_Z}DW%Hu%lAAA=I|JBFFfLf%3Y02&vbaw<=%OSY{3ch{-81<~7vtro z63=ydyh%XUti`@YKu@cU-X@GP7WJ!+sFX3hH{e_}0}Z)fETDw8DXkthuH2E4<p23B znf_L$|L6T7p7Nt*5@R%XGP-?PWaf|y40%SqRc<Rka#(TI0Chl%lc>M2-cOzzaud$d zaC-4f!foL!>DdLwa5~}Z{ccK;iigE$-uy(GiOQnkNuKe$Ox)NViE%o)=emy;eazyN ztgd+r7q)zITn7gUUhv>dJ}e>35+*&s$swbGg{$b<)L30{><jJxu+S2F)nioh5nIkQ zn$3RA)2ei~^LETf24d=x^Sr7jKR?f{eZIH-*coeP0Mt~KXiQ;tuPEhcisa2V7rD6{ zvpCdclfF1m?QuK|-QO8PjCLA)OD-=Qi$usdkFg?IUjn0qItrzQvR^0pWYNkzuy4Nh zd@DlQjGxi+&q5R)@03$^D@U`^Ot08Jlk%Y`UanhVt!ULoRjN&6Ef1qziWHN3`-3&V zCj3&H4VyIWunFN{q1ak$u$#R;#m&0pHR_Qc!$+>+Ua{_E>nPKJPi*EXez1+dg3r8T z>8Y1)_~KkkH;Wi0DXh(O^YzQn)L;X`p*O|{+2(o;>dj<J44g}o(k)Hrqh)pp1BJ%V zWbcgEYX~@EmJZ}l-#1TYuRSi}%UjGn2>g(|Qa~N~Dl6f#-t)~GS4(wy{^1q@{XOlb z5UxFqQec!3B1M)F$?(+1J8JY&^Y8%{%2@8*)qs`-$+<CCiouk<7dI!wj}M={-1c!0 z|9XTyb@iyUn(j$X%>p{PxIFO?*N;oCyygQ`c(aPJ0eKe<jpq>_VnbcO|G`%LGYrjJ z($x{HC`rQocXDLJy+mYXUrWo6$}Vu+ljP()t#)1YrZ&Y#(QtcZ_amd%JnJ@EvkIE| zmR|hBDs1%;<Ahr=S;`<ZH~58fhd<C~nl!#?SQTRHK4~V1d>nO)`JGy|O_#S18Foxr z<paYZvGQf-Y3Y{pPJ%8i-|509xUc+dm&%qRB6&|Wr)F;<GyO>=b#X<DqTUMKCcJik z>qbIubZix>=eeAi;brq157C7E!KNpt)J=2$_`{jDMUiVK_c_vTspukp&M1%R2pjxv zy`glPuqlB`Nm<BP+|$k0K+EJodiU6#cTG43S!E0+RD<WHA2Zxu`rsto{=(U3rex4` zOtBO#93G<Cp9E8o_@yJc7^p-XElS}lD8+wl!iX^~lT4J8v?|`jG5s(huSyB058LPH z^V!<MN4AknuV7{w#fuXB<j$Y?>suGkzm4xEiq|VUxfkqHzu)#op&5y9=`f4nkz@49 z@}~4LLG4?0e?Aq2ORU$F@fx;zQaUizO*o{;t~gvv=4Pw=ye%j1ea=~en2d+_PdAKk zQo3=={D$9Tvz7%ul`v+<)bNRuQddKYPoAwDQI#s$D;%~HBK72t-8Tg%b`QF`m;BfT z8|-lB!z+qB=~%uwf~=O{DrLWWIRD+ZB~^p4kQtG}F~UUm$lUDbjpH6Xzl-kXnW!#y z8W(sb3-hFvO29|<h7F56;*}7FgxQ;AOYYI<6RmIT4W$&`7u+r~aytqTyy&@I;ujPk zN`-iWYbk$hHok4ud4bYqubd@%;NcYG)=}y-Lg7{UpuShh;Ckj|U_;|dIAzPwhxz!5 zDum3em{<RTc5;GDYH6)*R)YWMwAg)JJy<dC(829jdafoFa!toLVvP^v&20s_>@GS8 zvV64je9q*(2F6ViKHOR6!2NxtpJiVbr?LErgWxQBikTo@Bixf1SuVqsT6eM1=x%d) z9Q`fd`qQrMl-GjlUDSqhX|3-uhPbIM@Y|$tD&ykT9YJ)~vmM&`{gxr6HJQhlEY&ql zP(hEzmWrJijDuzU;<tG6x{K0>6O)%&tbDB-HqCZmrPD=0X*uS#i4`iqj8?Bp8AE}O zb*MefkQj8V@@?U>Amwm%&Q;IlkJ-iaFGk~+mFgcpOKcq!Xvw-SM)GP{qPl5WsS<}$ z-c6Q0RF*S8U48FIAuT@nT}AqAZ%J$G@kK@VzS)Lj09KyDuG2nxL7%%6DXy{Q9TP28 z)u0@G-1Qjo6nXK$`Sa+@*3t1a=X29<v+=IX)fGc-j2X?h%9r)fvx}uBw**W+o7!qO z357PO1U)dZ;aRD&+Ad#49n9;xZ0gs;!F-AP(^9Ljg;0}NlgD02iV>^miTB1PH@TR{ zqt=iWzFEh&zv;1S59{f_;~ETTE0G_ht>_F!?%C-5PO*?Q+D$QuD)>%7`JJwnveMlQ zgm~*|S3|<NU&$_3jkz}H)m5I_=#;7kJa=};SCy5BRvJ}v2jm9MqEf~q@TaCrzgcjz zVN;J#U&}3EXb!WR=V!E(5c}=vy(8`rvJ)c~Tlv4Z`|5`%+iqQH5Rnp)W~4-h9=fC( zL==W@X%LWZ>FzG+?ydom?vO@CTDrT=gYUQZ`M!PjUvPc_hM8yPnftz1U2Cmtg?q0r z%d&(KU@B?Yl`|51t6bv(e(jq^+7$vTg+5`=C|dYeZF0T-(@x>ggcAKk!qOS{Z&hR1 z;y>Q^7F?M_&2RT)31N1Sb~Di%q%+dQGlkc68GglOIcMmI)7kjFfZ~+Yn~wFUKw%H@ zMoEt$+-<+#X`k+hceh}BNAc>CaH?KL%x3xBv5c%1s#@vw<WeMco<uF|G#0ONyF(|l zB-DE<U5<0<weF|-a$2VF7&xT8k2}QsESDyB(LYKCh--^9vO^dQ(_>i8>V(=L_pUo- zY9SeQ)j?wSIbHa79?0O-LbExpHO-d|qZEPO{vDP3*p_pqGWsL}iSLj7O?!bXs?7*b zh<Epw2_gJmkNIv`>%>**!rFUcTP7UnGa$i<q}*w=_z-bDGT!s`#c=}rd9tjhLCf*( zd{Wdc)rf34I+Vs&pejXu>4Cw%$#wxrS}e}G(88?Z`AyjQOO>PY&6629QmF~m9NLo5 z(4mDZ!x6YKmi}NvZ-O`}JL;~T$lJCfT!Es>+5OD6FVAr?m8Ydd7ryBEiKa9sR$eqm zv=HviX@wp%F_Ihl$CMz$<UG{0&Cd7|$a0WH6D4pff49XFmWjsUmU3Fk6p0L0W$At} z5t*})#HTD%=W3X=rG;nBjCB1<sAJFmRcU-iz6y87V`x(N!x#t$!^LHi#C|(=YB1ll zN@L%95Dt6LG>wkppXa&SVoAtV^jn@792vwtd`jgu)LG>C!)<gjVMs`E>akGkT8a$L zwFn-abVvVQIw%ph!JW8Fo`-irXD}aSRL9njUCpclJ)qIxl2Ikuv8cX|Zj9*LHjeSJ z^st#n8c!;&iIRLRBb9383osi~oSiiZL`ky9P{)b;<|>DMNt2<=4!4L+3yRF5!H<=E zf1E&&>#krsg+5V9f2F^(_3fSK?iqh{{3?x*BFR=4Ty9lB5fM<5I7yhurU$KKOGSOi zlGr=%Ac)(mFeH$&W<y?$wblYKa3$7sfQHzct9&q9KgLHtM#K?M*GPtrUIsNZoF@;T z*g1}Q^mcyCPQX*FDyQ?e2^?j{ufzPzUTjCy)d)SpE24?#A=Il?U}JoKoIZ3~3GbCU z%X$>s*JnDUGd#G%$ut{BGLGeC2mN2IV*FR!M;f?fd%kNyUd24y)l?to;_f%151tmq z<EE5>l;auts$;nHBTB^tTQLr*C<$^N(a&4UK!h~l9~i$Q6ZL!#+U*T*|JlBZK^0Ep z(=mjD6GL}IkC_+jnS8E<K71Y76fEC)qUFy^<7MzY`i55d{!ba2)t@NGT5kL%hIw6? z#iz7$(fq+5rSVX{(abkC4WByTuv0hWRKHE@B6)p*wpw3Mos?*Vz?Vo(iXTy|<B@3_ zhl6!?)rj^pwy72;KbQ^4-hJC(b3yFn#qbc>M=eg8s&cYq`JnADK<`0;lGpX53^>v* zlL~V{rj!-$WKRY~(SS@|Tm^E({ozl;WvZm#Z^i1u<jl;2Oj{qEY7BWlcZF(no!!_g zX8+mL{6CT!126WbX+n%-z-lqjKDzN*`E2clAo_AN(oHcXBM?_`z6*uYF+Uz6bEMa6 zG3k0fQka;sL0>y(BbM?{IRpKV@J(+n!?cTeX@Ns=un%ev8F{!3G!74Ml~w&i{{cx@ z_ns`C6OoKo1FfxLGEmyV&Cw%QL#Pgs&CZSPGT<M#_GxNF?b{=TQ(ATKbS6oIlVciV z`{C?xh)d|1)}6v+zy(Gc$nZVr`$+>!s^dCWu%iqiHQru1^v5R8ts>$34U>AO8+>-q zs`2<Z6jzrX08HeiwikdgnL9hH>f~=*-=nf<(2r!B#dJm6ulV9Al&TYa95M;#oHo@q z=@i05tY@@g8pE&5u1ZCtarIgp!^g`lsCtG0KvZw_%5h&#E%gsLl{}Rn3Xl%=KJ&{> z;-W>>%yvjZ%M{WjJQtUvzu-2AiA#EU+TVy@4r{&M$71ST<$l3Gu-|Dzc$el;pEYVQ z30`B%1tH0@-ISJq?h#1=uoxLe<YxnbW7}0vXS(8*@wgSpKH=6BlZ7zo#C*J4sBlDE z)vG`1A>Hh+ODdpaL$fp<_?F7Yj-kiaspPDI(bL$09NQmYupE25u&Px1Dkh05U!D0r z!Z*5NCU+B4c_Y^${0orN5_v11g6|djv1`*{#U^fOg_p{LP?l=3i``&l1ytBAsHlh? zji}5cPBq^}@<xh)saam$HakR0>=;^X3%xXCn`Z7~{#o<3QAxBJyNtz;-75##AfbJo z24^_CJLQ3J(mwd?10FZVm5u7z*D)eB)hnAt0Z=v*F&4&9rs=!L)Ty-IhZ0_v?*#8& zeHhQhp?t}kZ|ND6{6(?r)GD7PUZA^_DtI((5h?}~C1j7*&t@nd48|DJk_(35=)UD( zaQv{OGnqK$W0ou4F%cZ_xF=MsGw7_d`0$l*14~VF8Rl@B4FlI%(gbvIi?*y_?pZxw znvJkz?+FW`TrZIvQLdHa2EsjF5*kx>C~*k6S-^_Pi7svgab<{2T~AI(k*2{);n(_J zC)i1P>(@v^PRtoqXxGLam3yqYGIcpE-qona7^)a%Jp?vZeTfy+q&xj~++s4oU;>!Y zL{)f0x4JUJi{EaF82I<zaL~bm$Xy4Y%90tFJ?UJZfX$V`Uz4-|a$x!aYCM#G-Tn|i z!eB9SS259t2;7ppH}{(EwM8S{4dNMn-(V3PK^%GoS(!@qtRH&Y^z7I%iQ^lbxI1WU zNN_h-%hq%(iU~l>|11PGvU{q@!h6Vvwr|SZ;;aos!m8ng+8ZoM2>M@roAfDVXz%4n zJ+!D#Bpf^6)N+G<bk&H9CKm6*F>RX<8S`{UW<HDQp$r=w4Ql9izCjn!B(!H(REPS! z6y9%KJ*GYSkuq#Oo^g6L51FK}sU4S`iwkWIhF2Ikn)X$XdGoG-QB*z*^%_z8E7rUp zqGZcE)7Y*lm0BYJsuUjg$qo5k5ME|JuVF23RpCpuF1Te(_>3L9{E1v>$La?05z@a5 z#zwmLI!IQdGHEso<?9BTD3U+~c4}JTW~Sw{c#k&o7jq~~H~Oh^4lYcCfyGVPGs$ZS zbS17{X=9rT8YK}{kxhZ^>F-JQ<B>10E}N9C$b-;W8dZ|SH|ALeX&gczz^7C;;vViL z((3J133c;eiZ87-+q}g_pd+<5LJZ=XU~x3N0)tm(Oc{a>Sd3zQzu!*?IttiOddeY0 zs!!o+wT-IHQE`|=65t5w<B~Jt&ZN!`<SX$;>=vhqxu?coue#eyK0pie6`>=)Q>U(V zCtn@P1@u^N-C3l`h<YkrzU+!*-6*29_n0d+RFwH6vrTUHxIRFt^FHj!iNO5lgAsHT z2EuV1_mD`&<|p*2A5GLC(As}adnFVXii1dqH5=pg9Cb>zvwwet<3|_<pW;|q>%Kz; zX{*`S>Hho!zMfP4IOneuN_H(1N--Besmg;9x8l*g%Iw=60J7P7Q|*x6s8^6uL;KYi zV~r=t3?#-`0s+$Az~Z>$zMNPRIlfeQVwL*gcr!eIIqDo^&$Ew)aVZyTPmHz$LP0~Y z7Po7cQO0=MjAfhO{vy|plFn1C%Z92u;C15z#uW!*HNF$lQ~6ul<Sf;<mN?!I9|_tS zo{`LKrr9g<-JMR_zwpwXR3NRkeX|brd1f5#WBb-Di%fxLn>(D9LQjmiJ(?8u!Z>kh z_xwlfL|ktVmianF;VPO7SR`Pr^c>O0)T+?sS`;WdKk?#JSkC&U5+hTtT)v=u6E=Pr ztmqZYFLwK#9nF~ITh!l`C1gaz6zxC^Fn5ge&hj}I8kIc?&}jks-7MPKbHA6qu!_!N z_d_3R4cG<$;jEO6MIRmwsOf7FKVP{=7>-u{dd`??`F6WHmcG+({@^}TGjP=F{v@Z` z;uj^_rs_)L<82K-^#SdX&p$UcF8)Sff&q=Vv;G10E*iB}P<z_;06o^Pp=2~&%PP~~ z`F4@~<hL%_;PZpTn%a`qd`)?Mv#byFvN_vZM{Yp-CfrO&=uO4Cb0%BFnXddpZ$qx? zTTfh)_9~s#7svS7cn^iE@*2J0V}ChajmUj%!6L+$C6Sx-T)iaivD^BS6Uj`F&h4h( z89s=_cuV-$_3p+H@mIKjWco{=hSqhaU^Y@wevfVfHKV}~Tz2BKN9q1;w#XNd3iowJ zdptr+mbTN0*8X)K7xBfv%eO)5lZ;pC*l8IlhuyuFGf0NJ2U6O;5|G`n(l!?D&;Z$x zTxYRAXZyp=#1OB)^MelGZNJHcL1Sk=s+Fbj_gBg08Q6JUxINv^B`?yeYL2syYT8pl z7D}IapImv*^#Mg0+NlpdhGqpaL&5>3$#d+j3{`DJy^p8S0K_We7Kkn1qK+MEwY#)$ zj2_&#*6~#6M;WKjlCP=wYPK8|g<$e|sP1j{%eJ4N63Pki2PJH#X9z|&w?;Y1HR6}z z5iu?0?IeSH54u@Aj|yq7Jk_+D@ghS;Ju3Pa<7Xf<fd&=Ezg_!c15H&_;Anz>M9SP6 z<y=SXGjjS#L9^HX0g}j0D{Lp5%&tq`B|BHpQ}5SjKspNEINZXhL>d^b(t<49eVcFx zwUeIHcG*6|qsy}(fd{U3P1VNcj@RO%KFW7x67FGWb$$7e|D1fxuhCxITTe=dpUQJm zJceyoi=)PAu9E*OHW-luP)&X=aTqUYUW=Cy(T#fkz@Q8~ndoRMk+0zVYR1sA;i~V8 zt2)_gsxB`e=TLtXJV|eoW-HmeTRph_ItgSDz$Pxa?y(-PMkjCZv3}Mdv^6*|13x>y z`%P{lKn)>ulbb_*Gi>8I*{I;b{p-u*={k!SFMb6D^}&))*CkKajQ)(@*YM9jBTEUV zXLv2r(1GKl*Zo%SgIgeKH$VJpgydP@xKryY`B@VMFqciJY`9jDXW4J})!Ws$PHfLZ z-!o&v6xqFe$!`?eR^+zzzZ^BgQ+@!WS=wyN>0t_Mu9Pn52*&=7i{`5<%)h59JRKOZ zbrsc!!P9%d4B`49_tMl)_124?2*X{WEU-pc+uWzryaJ)KqO&H!4y|9ZGor;kRinL} z4`7l5r}i7|dy3C3NQyuu(TF^E;PLD#(bQAY>Z&L6n;N|>ps~|1j@D_&MRSkjYBS|w zl8>3LpbPzh$AMd&YxkJN?*!P9a?-Mfw@HJ;cNCFK2`r7SFs0JCf%=O;GPf}4$us`t zrCK<fOWeSktMsFqMwBD>DMt|}bcy8MNZMU+TQpfTPSl<N$~^_%n^`QnQ+xh>m3?rB zJO-4`>y7!RZ<~2h{eCm$`kSH_32L&vZyR!#4|6E*3SS7u-_BOO&)1N{iLmtkZvBJy z!I3`G-ER8Hcgob6?IV<J=7{^|49(u(^44;GK0Rm4zyPI`>sniEfy0gzWN+3#?4(_r ziWvBicgZ-S6QWNi)w9_`ZOHr7{Q6rje9^~SfHJS^?G20t#|5jIl-ejFA+OfA_wUhQ z)Hh65&bAbfii;BA)*o06_>TL#K9VyDg<OC;gXPzz(1lrdJ5c%eOM}NZ%@9-+`i}SE z_GI!=lKEJqrLO~-_4UglzZnGTGMaWLteFVksPEVnRZL2&E+krj4Mb2++>^WyDt|l= zZgvU9(^b?ZcH6Cz8qCE;B(;i<c`L5@HQ}C2?U{CGX90osVeQOrRquQ5{YqP&{2^|j zDo33I_3IHS{8DniK#_kBLg|ogA9?36qn&u8C0+X%ohdy%O4oSxzODm{YxdhZQ6if% z5nE^i!>0$;KP7VIuPn*DcHzPoH!y^K4pm-&&5#!y;>DuVl4v!Bd+}df0OAxJ(mOye zD-V8TE0Jex+%lW5-aaY*Z1s2SvO+Ust*~3CA)Y!L<(_Hvo%u7Sox4X#p!!=mBWbX@ z8O}BTdh{e&(}29|6)9=bzf5!|6%|rfa?mp_#<`*fyx+%gB#J|CS;%{-4JO!+ZHR%W zT7M5Y^<*D%jbhF^?$bH7e({oc9lE^ur0n{Mpe-#J9ZB_>;P^yQq}7tEJFqO%SA)n6 zFV$`rRI|S;_pZLBGmbBv;9Lm}_(&Zgh`U!Isl}vA_nMc5R84v=gq`zwmZ=AjnlRjE zjy;wnNrim@-y1T5q%~b^Mfk>KYc)fz`uz&=uqtKw=4JVoMAk!^Y^u^4Ujj!V6v;<( zMx(6SYjRqa&|hOO(6Uh_cyw2FT69FU+WTWKkzFkwQ=6(l8<n^PZL09}QJsg|^<<__ zFc(a6Fbmwsd5t*_o<E2|A6MCwaeISlNnotLtfkfZ^T>JRJ-;lRHYM9ZpezTRJGV>H zyE2kbpgU>ynr=QEvZ7goXSFQJcdY|zAwAmdmmt#qX%6?NDS6JnTN!dMB@qOdrF-wN z)P+l#;o3qF;vhk;w!=tLLa-Vf^Vy?rO4T9{M9E^%0}qiRc2|LUotp)wWdbwZyKm2U z(ftc4lH;LKkYn75M(%KME!RpYyk+U~p6;OJRPzr><SaZHr?C5ifpqyJaNIq1T*u*w z;<w$?wqV6`s5{+eu4p3=HY~wT^H}Pt2^4k)B9^<zMHxqEh>WV5l!Y9C0ax9nmwV+c z`^{yS)tAa)qY~q%0C_|A(a5Ek_3U}l>OW4%zq~x4*1`V?<0*b<QmdL2g^LmGya>Ts z8o9VVIF<9GL4Z#GbN_A`2+H7w5<#r+N+^R!6>~PO3R|$Bvwzab`mFu<$WW{vorj|+ zvj$<?R@Z|(3h_`^7{<3@l}K#9Ki?$pn$e*v9Q~dbEpYANgm<(l>hYEuA2%6DM6O(^ zIh-aWI$|0w`Ad>&qq$?*GSqior&LUV0?AhF7&AjqKhx&BI%o{%ycm!*rk#JY9%kMC zM#zY9F3#ee=Soevf!+QfVyd>&uR1)dyrt@uPk^QagAr>ob`#N|^Jv#-RbhqVVz93? z^T6~o#(4`X{x0sbZ{0$DEhd6H>JEGgEJ8ot9P8Q2-KwiKv-aL4wyx1KiB4r(V*s;1 zH@^*=R6YMXaUKrb`kjWy@?&L$Y^|srIRu+jbXRoReb<oE0yp+lE!76*vXcxEv?_XP z6lMBt4JLE2@D9RgPsy12)+|QS8OSn!1n18|$R;;x8l~Z2PuZQDmDSqqSKp}UKqYGG z#_@cx;fte4FL&Bh+YbiOF*{WA(ecnkNRTC|E+o@l*OW+Ff}=KxdrRED`N%Rh?QN+I z&01?&pdjG|l5aJEMb@?3h9+4Zx`O*2|A8xz-dcHY_Kp{RyTQ#k{<ORvFjofY#QcvQ z`5-(QiZbP*fvB2k^8<^!RGhk=4+y91OyM{9nU`I%wfsA$=iY3|mfjlR%+`x}iweGG zdcCGm8+^M&wg}UXO$lw*N!KH{bV;fh;p_3pPuU+&PC<KJxKd=%MAk104z;VJR#$CD zMA7{C+O>O{;rHha_V=|W*UvrpJmuC#-6+&P{i2K1^z3@9via-H{r&YvO79KgITGdN zTidZMw79g;eq$4bu{V06zc?90ed{bLHQvZocmTp(J}55cbIq<lenS#+rGr9Tgy@2a zTX>PIHQNf&3HJWw^>9Zz|1u>oU?s5Jpi@v*78xwwQ1+PFBY9=&8%Ay52n{arLEZXx zW!9J5XW`%w|J?|OU2O9DGvJ?$;NvU>;vIBF{~9<E|MbVGy5zR;(I%bvc9hcJWOz%& zPUzO`VOU*_b<;`sIilg2PkmI|v&?zDilO8zO6LsGRx3mXcNNq6TM6>!Ke$en=zI(g zwq<0zCZ%i#&|Ah&BW0&i#-<Qa#iEZ$YxI~2s{9Ud4uJ{%91a-BQ<%D!olmP3S8t*& zL^GEPl=;78MO=8ly}YuM-Nfm7;}Kep(_Dj7>Ry;iyVvcn<Uh?0pMR%3yjd<`ni<)6 z+wU9{is4mql7<q7_vxPGAi>t>DKdDpmwSJ8-X6wlD>z=nRDLzyE2gD6^xF5rn62gB z5etg0+JjXO_6k#l7(!BY21)5#*J9*c2dmaS&q{QM59V}s_zBxD)uX?$M6@|g$k2zY zoRK+ATOH351R?+11_G<phF;pGO?+C$Y6p<66#)Dx0yk;;IjG~)(wFF`uVVfD4%BXg zmv7?9L)(6r$kV~X2icbu3|5kzf(gT8{USM%cTI$gFI$$KgQBKy$hs=Z<ty<?(>_x^ z1hKQpWHZH`Tma=;aXGfmI*#=T7}Dp-^hVa_ld|b^9xhtny-0*!7{|nT41CQ@TBaLk zExBu1R*SYX7R?m*HClZ2>d^@TQz1489wUTL9DLrx3O}(`n%1x=qX|`UV0VYEmZWm| zokzIUR$R8^4!ix#p@{bb7q3RzQ;92_TPSD_1bAl$Cm;4-{zen#+0;E&)*he~URm>J zQMxUkpbJgVyvLuxn4@Pp%iW_sXnHZPl_3G~IN^x9E>(|@Y=7tOIMH5pMF$f!7GVmW z^Ez*rX>S_qbmKi}Jvl~I{23^u;87C7WrJt+C;6jtt?G$W2(|&&O^p9U)p34?!Fp`h zQ+mNQ5H@i#q42hWN8I749Hn4lXHQ00{GXPi(NMVYU5|@(54rp5Evl?xQF(K)q$%DE z;Z;Mg&AefNu(Pdt)ZMs>kdSJfmMDy$3z}ouW9sQ!QEr!ba;DzUKS*5ST>pQC5eUo> zeF!4F(`oyFY@n&Ag0?&n0%Hn=$|gDSKi~<|zjW+4EVDi(S_r2PJq-x4&Nk$;`xoY+ zV7;fv34Dk(*0G6v6v_|(@y4WxlN|n`d%@X4|9*I0A{*HkxChWxCrzgE+dkU<e}5Ku z)Uim7gS@+FNJjgApXxvaeFlO?nmKfaMCMdO=66ilv;Y2Cf8PTdjf;-x7}5|K$;(n> zSHz#_a>Li_^4BBA4EMG<`81Wld}=Rog&Eobc+Cl1K=`pM?3`*<F9Wo_>~*TXmi<pf z^>}Lpcs^8m1<re3mp>>qioAf5@`iE+JALMpj9j5;y1$@6lXypiOO3hQX7xz)1yCQb zDg59v5AYHnqbgXwJO4`5N=5E<dlcHxsa*5_-tsj1qOH2{FEU{=ei1kQiA|@IGuwbP zr*%Q2z%|g7RNCJw2=NgC(q8)<zS=yXlq45j0MN#Yz@#oi4FJ!Zgx&0?)-T!(%G88> z`5#O9c(r`^Thk6j^ku7tUkMRF*r2+N?eRyf%pz8c2cYWK>=(LS#x7tTwEB(*RFu8d z3#R@INPeECbyMEa3;GOagX?}J&xuAtdY_JW$c~G)y<bLnH*+fhjUfVij>5F^7fSpG z9QnJ_J{@VG$`~BiskC+2GY+BCF|kQC*m3-qWq+dl$FjU``bFo}@JU0;o7q~R11YaS z5XfWm<b`J5uF+4rY^EnN15x`a02{TxpcP!kP?A>iJdUkVr@h}5{b!TWk*(d<kVv|h zmgh-HHggnV_h%IahLM6?+F!;cwvGo`lp2;?Eg1VBktg|#GT8ODdT7;uA(c4jM#%YA zu}D4txf4wiR9ZM;!3O|15YK78|2dF97ftBUr~4<s;N`Jm189EoP;Ws1J(>jgc+*aH z2X25yA2U&o-4Q34{ZqtxbT6%Ez+s{F?s$wJ788^|&JQqObrQj%_5o)I4PgQ0-QQBv z|NK<o5%d(@4|O-&OG5ek-{%M^5woo7E|+9}z6RD*RSRHx(XoYl2>f%3|L!gr3%L_* zcfwgodGP;vyZ;m>=vQ=Pgcf97jSsy4zCr)XRSBqwA|1@(7cc4_zsCRag8%*}ZO~hs zO1Z;4iTHovI{*F5|F}xej0%wA|G#c?(H3Kxw^-}#Z=h31QHs*z3s7j}8NYOragpl= z{Pc%<!A{F;JQ&lzOvr3K9*udkg7k?2#)?H^ZtK4bTlwnM;jaTvZgK#B+4`#}04HX$ zxTL(9iWQJUFX>)NFL%DjU>B9tGU`#>P>Ona{O<vWQT|aF`2ZMm0`Sz*f!3f%+ZZLX z#QTG<n9R}-SD6pV){V;nUw~+uU+_3OQeMerKxG1c_Y1C&W<&G8Y^$CIvTCt-{xHo1 z%QHmzAteAs`2x)CD0oET9B6^;{5|6@fZeZRbnpA)p`Qi@3tmrn?AvFa0`S4>yY`2R zhiwbnzXz-1^*=JHy#LqOHt}4YRd}V3@T`WN`cmFf;ak>fKit6|(nGVEa(-!Al+{hp zrCP@PEyyIOUvk|!4U!Ug)wZL3V6N3b|0unDz))TLR99f+4c#6^JJ6VD^lH2(eP{Kt zy^q|s3pW}09sty$L*2e(>O@8G?>9CvyRO_m>gfDP_ciLRKI%w$;kzv*dm&A$x{rJS z`yBm<y>w@)bu$C`mobqoK>I+iGl4}@jd^TrFw68fmvP&xQ)?d7-k)fu1Qg-AcZX<g z{~$txbHKkJ><vtxG4FJiTodT?HKg2~UVt>OG@Vm%TK-)btIQ|6R-oB#e$bZeQ4Tw@ zMSjP~G4~ri;uCYH3-Ei#cWu*J_QR)uUSNH=8;0L1@a@%3P5^r9#y~?_t8XOI^E77* z=ye45Bu9n<Db>ts2gE)8`5f6Nqf&E|akkf61)D;_Q6@=BO+d@vB+y2eOyz|Ov3>x! z_E<b_7U1P2wu4L!Mu-X59!H_NL(`OJ!#w|~6aGHZqrd?SCB@qe2i!mkS5v;r-@fz% z=M@jv6`EW7jtwn!<=y^&zcnF=Pv+gOiCN2D{h(29879fiWBfC1C$V!@alc)`zKlxj zG|V|eQ~HEe%&V7wDf$7zbQQk_RIA9KQ8?>uslw_fWEmZnQrE*D4}b!T>v$-;56__c zCOeDt3c2Gf=<YbN9ZblPIC~Uf%i{eB0`GV%)O1&rP~=^YJB@s}jKl)lDtT)L|8iU? zgU<ZL3jT+J>d*q=q<$VIsJ2f!AYD2PkZ1okjDo=y(Rv(TVVR^Sw5yLT2kiV7kNSUM z%49x+%q?KSecMQjsEVW*uir?N(!y8$O4a#)5YWh?OeY=Zj1ya5J8UGI{IywIfUqf) zlvc}@L}(-L0^E)num6I7uD~KM%5v+b6nfn>c%^>E_l3_fmN&kN4JjJ{S7YLo66rYW zJEHhZZ>8^lDUih4e9C{k-X;cn1;pzX3NX8f!QjWRpNtFH2@mu?zSZOU4{-x(d4zj~ z<2AN{Pq@Uacqqmnp0C*A=pg{r>RocK9(%~fm>oVOXDsH&B7_Ez#RNjc%<G>86Dq*Z z-AoOO5#BulQodh1Iu{dz-8euQ2&wy)obG%hc9lAw)(e62s>tC`6&9eqSXOysZ@zh_ zJe6D0eaMg^HUlunqnb^VFZ|%YZUBuHjM9e1z4$q$6t$o`y#uh*YQ0hmQ-i_}C&C55 zaAcUR3*bkYrS;1E;{^P>%pjilyltdP!j9Xld`8!{IsoXyG@ZL`wa8RUneJW%B+n;o zTUd`-?mXWP8T$0NN3AF64@9W+8{KiXT<;8K+-{9l9sSRr=&y=$nTbx;%I&+sZybN6 zT<mBAZFp`HJ+D8*4sR~J9xf!yny))^B8B*3J1sw8$dD3JV$H5RF3dl^0|>Wc<qv?> z%7$rHdcJAe(ggVg2R=v6f9s7EGgpHo0@^^pHnpA?keD8%GXw10?Z>6FawqK-CDxm5 z!%w^1q^TYZ(T0yZLxP}%>0IW?XDvNv+oz_<a%=3hXQ3;XsN-q|lfN00>QK~(V6s>3 zm8<f|WVyXx6~50w;Mix7wF~551ho`(e3bYH(Dmt<kopaD=nle`dOh%Z@a?w}-50OL zZ~eudsC}GXe{mwo<&L!_<sGhCCDb{v3rxNq^}?}+t^?i)w!B4Ym1O-y_dNOzJL4#z znrrHS=;9RQ#v74{i)d+ni~VqjeRhv|v)7<o|EU#tMNL?S-L(`3qND3GB1j<r5}Qtz z7lP@<{RVgYQR1oquug=$h)EA_+z2*q3k%hbow*--3Hs@Uj)G4Mr3BxYARycTF;OE& zOZU%wfDh>l;)eB*RQl1>&1B|%t@5!uZhN@s>c5s-ZwXf~N1-pnb{$Cj$p9h4W@G=W zdv@{PfcY?8E&A)W0e0_=&Hj8NE<Lf2?(GWEU&S3r>FIp^9ozGr_<D9Ib8$tELfF(e z0CA^r&70<Y*)A&hWE?^-xFzF|#sl?4cR!BJEbUjz*pKwOHSEOO11!(ovD+*|#_QP@ zh7QeVGUNLgSD1*quI1(jUQHxYfS6Uz;_6A<hH;FTe!$0fA5zOFaQ`H{qdqDN#N<Tp zXC$>WdJN1}h*Y#+WGXMa|GdgiwKo4~C=>)&&9VjkbC!TF_crw@lfbzf4`7k;n9V-3 zeZcF>Bx?I3u?50*kv>?lV6f8CgrUbRVu2+}a+*BFOjC2ZFKr&qZGwl}%LD+=w$G1K z7R$8b*zFc@6=InIYVj{XFiqdbbHDF0>Xr|9;I#DXu6@T6-%eYa7k=&6yHh%M(qkez zivA{)t7gr+8cgK@?Bt{Wf0Kx5`vN%Ra)=1GoRptC5XzdXgC`!9&h(iK^EYB_gquO# z`)Y2NA_XSxona$MZldBvv*LrD-O+-6&B^TGWn*4zx~)vMk$-u0@9EsQmYi3+;J{_a zUj`Toawkwjfd*y=K7e8+asAVeBXaq`C#!=%J1mC?>nlL^)m{IHQSxc$4}v)f&A>X9 zeOaB*P>TweVT*}XiVL2$Mf57s?z<U4aF;BjuS<0AiebX$&vc~1d})K9xH$t8gznF@ zLhpDSXY~VVufX=|TfEeIS5?dQ2i1ejgP`qg;H;SI_-NU*olO8dv$v4){Gkh=$+`5G zbkG$BKEL~we!ww+D)2jXt!@<kUi$n43&V@`5tEw41{?!{EfY>OFOkRgSJw@W%w$$$ z@;8^!yemP}69j5n(X3gt*lR#ONl}X2;lm1X#(8bQ`tYZ*k!?KHFUkuhy(aFZ-`cuA zQCn2BIhIe-(D7J`+CO%-Z~8A*Vp$YX==s`^ZFjWX90m$&NwomgGAFzx+Lt!shT*>k zjv8jxV=ENhZ$v(R+^U^aluPnDO#iKdia+^LRh@SAA+A7xc9}bW(1v;qE2YB5>t+Gp zMg0okRnAmf+2uUk_?6(N&{Bvt`lI17amH~67*Y?NWjDYLONUc$imd_uU*E_tV1VlU z=_=&|&rSDo+tI~kudt8@@J0JCuIPZkiGUd4*2T3<QdQY$!KxwoyC|uAO9SAnjDSbq zOV*0q=C@yVv(U{`qGs2c)GjoNbkOVo-l#Lf7IenC?QHrBppw@yx*l^NfYEfzr3b9# z)g!1#R?^;lJiu6UURB?YlU55aserkbpFDzF?gFYPCNGm6iOZf6%p0@7FMGISbd7t7 zh<$|_Eqf&3?ttI0hJknoP<#a>zqlLa$T$jH<Q4{ub&bpkTP!Etsh*@(52mSqWiZ+* zN^KbxkV2nG1Bh^&gu(=&etO^>QA%-mAM|M=rfITe<#*IMB|9^L&PH@A{A<<-m%vl* z+X&gw?De?L$1_j{!vW6#4M5_$jaM6~n?lWT)4D&v(ZS3~92vh`vUS$Pbc4=Gk}?1_ zB@*X+xbmn9C0{)mA0Uf$9DTYm8me#m+)8^Rx^}BJ3uN!xk-Bu6zianYI4%ddGoFoP zwXkklgYm*FXQEX4Vwol5ByH1ZUnDcNi9@R&hz<nWK0G_RyH03mrQHLhbuJ_vrcH|u zmB{A5-FIqFz5A05$u|7CKO4I9e160cpSjQV0Mi*{?*7{cjZSL}OoC;Z3?9)kvQz07 zN2e=2Q6g!Pr6cqm07BamMzhz9AT9or9B}e2(27nOS0EYF(-4E<Lfd6!v-Bt+j7QXk z{UKR6sqs;<Q-FnE=#x|Rw!58a+jj`x`I&6zU&y#YpDrrV<iR5=wbaal6lLH!k)$db zrg|)9nj4K_%qTSD_oB$?-DJncmXeoi#NeIR-HcaRE}QjQo`bek-P9X43Dfl*mUlgd z6emdr6e&bmQEc(@A3Tm_rQyYXJ_<XL{-vhtKm1Qd_$y)%v~0AUDe2Qbi?X%p#8EoY z`ofmnEz=>|em))VMSoA%sg~@*Ar5f!k}{2UBH~Mh*!3<mGvU31Si|dYpjXH?v}@*! zZKF1^3S31--kj`m^A@S+C@jt*iqx3m@jOj7i#11nKa2hTkR-Q9c{V+ePBqv)072PK z-)+$0BmIIh3+M$}-cIN#5WCey7kEs=4EJh`MH;UG%Lc_jSn3PB*WijP^!o-7*eI!| zl^Rtq7ES{x$tIBlHPmke2ZeHfsEw#*2jmD%?D59=igb=b)V@TxJbL!BeQ-XvYeV%v zWnEZeJG{<>AgW@(EUh}+Dx-zT_|Y(J<T+Qg9uLGf-fRtT14NDvbwEVpC=|Gnmj(WC zx<SN!gIl@B)(e0<A%0KpGU{nbLfD70y}gf~IT%n7vU8)4d5y8KDPbl*M^HX57B~BL z<c3FED4;~aZ35CNd88x>Zxv_LU$j&$yv$BdKf*(4CD?A-+}7{LwxX5ABY+<o;6hMM z=;TSnRjTfzk5&l^TH;NWRNdui?c~V#E)rN;bh**R#&t@U0C`oF{{lY@;C=xx7vv{> z2#;a$*piDk<(NJ*eoy`8jMs+E*hXRckAQ?*5nlM9<a9PlO0a@XspB=5pEtp9!iwNZ z|5IgZVZ~FRLcH&(G;In~ylM2><^@(x5A`X4H70&ga$mvcAG`qmj#bU({SbzYFqkWQ z%RqRr;L198=CXjc-cora(NcgX%t3JAf5CX4LUNJ()Af}f2K&Lg2U+p2OVoa3Ssay} zH)|doGI>JT-Kp)qj|FsByb_az%GfKcMPLkgda2#a(Unfpkm#2nuR&SWuiI|dyLs*_ z8jp@Z(v*=d<c1_v;JU>baNt^~aO6chLb%KUUTC+eb}PbZ@z82lz-Fn9_XY<W>4;C5 zP{%3cNHV`nK!*}COEG<pX@}yh)z@N*&%YlxE!_dn$4oJ|?8XpDGWd3LYwAWAPllB5 zZtvKObc7_Bc~XqODZ4y5TOkuTg9V%>S66A$>)=#|Da&5jhP%Bv0PH@=(H}XgJoT4; zf6n~!E?-+RiG~E&)=et%I|v~G`G(ffk`KZ?qVhafhCa<NdUbMaUMPI<NHgej0_Pi^ z9YiBA!p}s|$m0fIpZSBi9D}u?xMjb?2t1Yn<@YgIMk6!{3$Y%vUw_7AiVmBR$p8g0 z6ceH9*0j!7jF4~hnnC=eJwq26f#1m#h%gRD4}{TYx7e7&AD#=Ijs<f_f<k#4BV+<z zqswc};wc3gBu5<idZ!N$inGPp*r?-GM%g9Q;&U{WrkiGooxGD_zQfHHk=gtJu#W?6 zs&7q1_k%w|G^yx;9@dAg%=@A^V-GAVDTo#Xc3EnQTOyAtJ`9V<u?0<83U&#w&fu3R zr55xA#xdjix_SXIdeKg|PtrTcfS>8PIGyiPI_H!?EJ1{un8a2ZrAsP8D*?fCmlKKu zhYGikI2j~TKY$rC?bW_ybcgZ)WpTshuE8g`GnXK4&8=&U)Y4C^GAhQ>s5zSuXL;8f zWIT}_Ssrm}684Xihvi+j^~%Wbf~1RSTL^PkJ<*(WVMHLRip&_vgaG<uqiIk_Dc#Kq zV&0M47#x)(6cZGSQ(0T3VS}n@FtSwKoaAqUr@V?gp{s{7Mw{Vnto+pCNvaf_&8pF6 z^mQm#CW=&Qf<Ft(c~cN()uOS;H?z&J-czld$a0!a5yrk~ZQ6kXKyUIi8|~iM`v>b2 zf(9;L7F*4+*O3>$IeGrH?;`uUchQP#6FrCBuCr{qH}^bsJ7{w%a}d>)gkJ;BeAB$$ zAQS1j1v$ua%kAt|1l#ppHxzXu*<^Z$B*e{6(&IK*`%=Q5nCT^BR6!UPL>NmhrP6e9 z+oNwfrn1AjS5l-S;T?&mm8#Y8As+Q7s!C^^w<6*TWLWB_8qy*sAy<{t^ysrqE~L<! z?7OEUA{~l>Rq4IkPN7rPYC@z9FM1eL-~g7&X?;xaN@x*}EOzAu^6qJc_9Ez~eTA`1 z$9`2W#Tgos`p1-01Vgh<UxpT<+U#AU9wj47_oG;ienoeOtLtU<Di#cUdb&3xN@><= zUt(zWv(4#wQc$rJ2s~N&h<#_Lc({yWL{fITEu;FQQ})I5LWH5i#hqF``C_5Pa;6;+ z%G4hG%9YG=Yo0R4{Ct4QV6>BC`F$2-?iKm`&~J;$iFeLw&&}C)GDWz$%mnCTdt&;^ zL&Kfp!t)&xf%X^nmlF~Q5XY+o*{?kjUR-qJo)awhHapknO|zA`Hbt$Cgy>*L<WHP) z4dUVTGJdho1faYDVAAVAvzA0#jM>LRy)&B(*LDEdI#!?FT<NVn*6@RJm_8^=wcd5$ zSB79)5zMEq(ckCU!zb2bo?uC`;B=)Bf#$1eadk_=oxAP;#(V7$4P8xnWbj?=W#q8K zs$2DFX>aWg_-9oihH_zOp&kG}&u|LqW2mg?f7f4)Cc3L2@R$KB&NsTslN=vy$$Dhv z`^aCclJ}_`JP*FqzN04@pYN?2o0AB5A7PNYp2IL`&`8k3?AktR6-kcyCEn~LeAOEH z(-fUkB90SKFc8{dK%-anX52A~6@7NjOL*vGnOhc>9(`|;ztI$|7S2SNHu?0f<(MxI z<-zPk_xV;^-6_q<w{`Cyr5Qd)?c``I{D_2BFKDYSzZXwSV{}XyX>whfO87U{2zv@Q z9b(AFGQMp{DNgBme#!77rii3BfYyq1?zWgyWCAkZF?(&eVvX`u-EptfC<oK6DTZ8- zbW~x^qk1bpm1{*MpI*=E8r%IhQrTsKc%3cp#;@7U-!Gj|8?|2tQ$As10|z_lKVi_0 z!8_L`narh3^p>EO&OGSEWC4H7f~m6iU-n4}y@#Vo?dUd)`pu_k&k%QsP*wWjJX!^^ zvzd00J0`q=d|AUB1O~H{mk!Tt*Nn*!37zP095kL=wbKJbK^m#YE=j(M$N;%#{N@Q! z+|Z1A!O2#Tdz-Me7WE$wQ7}%kc%3W+b`3cQX-`6j>h{LmAP()69o`cw&0f6bzvDW* zPV~AWO3fAel%;4p@s10r=wJZ}HGo7)jIcso;1AwhV{tsHS7*lU&(pl?zWnE|Ew~z; zAGn507f<L_#l&{@hw;nYLWM$U=-iuM<06+zxwf9D*Y&T)lT;xA+!o%MUSnKLxu}+A zFaqRV%XWedZBJ`L<lVKGhA#OY%>j9~$GNn>MPu9pp#_Q>J?|9)*#qm)5etAV_DVhU zdOXCW@DqbqdIzsroXzzEwOz*2B1_X~#-DEusRT8&lBSsY{Iu;-f_e-gw5)~nh<hkV z*L9VTc)X%>b&=9`6jhCmU=FTV#N&`{i!;gt2Oo@IYe9r0_uXH|R<yd&wrG@8o>YA) zmvQgf%HxX*mcnC-z1FI=icP|u-X!bGZL3;fn=$fd=r6_zRG&4Ds=o0{Z!?aWBFeK> zS|o&wNTo|lO$WUy2@BRvl{l%l)mAEu{I&N^8li0p-FUUEYv1#YcFR}U9~H{mQNNN+ zK%(B8CLosa)8UrDi}gY4;oK?%r&U63GM8TaHkK|=yx5Vhn~Tny#9(_QBuaW99wtCQ za2y0<Se-P!O1E0lPfEA)e=UECK<fgOgrqL)E8od7l(qHP+yW>;F-z5;t=d9ibk~qT zFoWtZ6T9^0r*kRdq^datV(PcD)qhl4rP{?PU!_#`?>_-gle?(tIX?NAbyqhrb&nUw zHCw-0WA0^jb>bk;&qAZCoo4wg+Q@$BIt>YwbCTJHuCroZ2>a<j!*fSqNK5=|gDv<I z*t6H|29#_{H~wMjkBpZ5niDfg(HW;($9@z0x86|&4|Vj>YbbVCgF7Ekh<3u@Kyudd zjiuHQf;SJt3A5teWgl*Qr^Rg=?a;@s&utEGn8scC2g2hOe@h67jiPMIG}@;leANWc zkv<Ad@6rH`)^yz|X8+2E>n$;28gy&0wG(7B1T#48z#47MPVdC^1SV*!8xy+N+50_- zWVjsV4T_?>u9+k4DenGA(Qk~3Ile6LAQTRgd7%&kj-gX_?U$IS0I*<vnZ-`pDjEfY z@T4E_Jpd=$hZUnJy(@*|Lc97;TGuZHz{9r>w(V=|bk~TpI_5Y|8=5p$idxhi;||(s zF-WMcOv@D0x`FJUjC2e<z0)Xqz?F*@pukVG+tSB&gW|Oxaj73vfwSps+hYd}h8T=K z@7oZI1#ueTB{~`|Bb0|7B$0+LgwUw6I9wgRY8CFO4dcB+{Zr7L!XB(y%(qmFmQ6D= zAo`+BV}`D+<3RFuE0T=f;y(Lxd>6U#iuTFk3My!H=1R!Ou;uhIrZ+4<x)EK%Znxs0 zI*b#<ngBWy6JuE=@v1q3HFIeajDxSx;Dd6y*AutQH^)<M?oLA(mjPFTY|rs#u$t2K zhS0rUm1CS-$lrYHe5uW)tPu9F3k|;!Xn08Imm)0Vbg|BPDctXgFB7*KV@a60iEwD= z&atuq4z9EQs`7|TrwLSuN!F^@+6(Z*L6@wKYnp^=Q5X^7N4c*xr`ONPXSw3Jp54p8 zc*YmY+6$nqLeahP*{9K6UmGLjT$kdZ;0;%0uST}{DrUt{lP4C+OQk2vPviwMYBLQm z;6c5?(BuMODi!Y$*2Izzij|O8m{0q8T?OqCe|qmoEsNpc+TwAhN_IcJ|FqX}bodaS zumR9l!Qh+BMJf!{=hjW7*T@iC1CVvATx#rEvC_-%%z&SXr>1_he6~Y$FKL&X!w2(K z#r&FQzm#S~;4R|JLdY)6ItC(Z2{H+~m_;UgH%6b@XI?sa%NWW4<ytl$*`51bR@Lg| zauRmx-6M{2W@uMUJF>IPPb3)|4l35fqAuT*);mvP-JVw4JIWk_7}KS;RJAaX2?Y^r zChB7l6jz-J+hvG%mHZLriy9NhZy{YQ=7~L2C=odbJDk)2r}&|W!#N?v&$6|XX^RfW zrY}|g*};XQ#h}y&^{i0|3*<opcmHe#09rq}H0hFZ$pnAGf`Zjv;CF&Nz@s6VPRVKO zwWh?YCoq~zu7)f7MUyI@{D|<#$XcPJ1H$kf<rR;nM6UNLWiQI)bcOrcVs@xYol2cA zBz_WDP+!ZigduHV%BB1gvQBfNW-Z}rYVm8tM+fU5_e^<r-;vsr&C^-kpdS$jvCdTP zZ(EW<rYakczAjLJz$905U-Arv(WV9F(7GGoLV{;I?3+CyNQolTXiQsGh!T~4`Vku^ zr$TLWrZMMpy(gPc_PFz&vCSh;IZ|_v7njZXMrHYR9~zO6C(L;A(oon5r3QeH%IjfN zLeS^9V9rZxSvTKVJKHHS0SDg?1F23dG)i><)WQu8Ce8$1Y8z9&JUEvc)ITu?4a%xV zdSLBY4$lM(?U*neO6G|7l_f}2mc>%6M(XypE$vo{;-UB@=(^wiVzrKyIA5tzc@Ddh z!Y~vcT{b26XaqiZdX5eLTAk|(a<0|aot80dR#kqUT5TxU_p<IZwc8;({eiW|3#jG$ zWsYR!;`*#%YQ0mIG6>F)I&;l6_29`Vlp2T0u=rAC!n2sQ;J7tnI&cS==UpXPCI$&E z<E-vEc-j`K;t5pM$)+hWVB6?J)r`6jEN?#8Wt_N}3zy1p)Wfu#XVV?$&EBa#TPkBj zo_K2bOWI<1w^2B5krw|!WPC0z?LA{vA&YrjKb_0qfFh796h9+l*Bl(LjPyQ(JxEVV zbxa(Z!u(+PIs2-zbdlP=m=i~fI)#y@YagPp@`9I2(V<+#Rij+}RrJe`9Ipf?YiL5n zv4=ceE{`SsfREB{L39lyJ6yMW3-Hg{Ej%wg*yFs7Io@PmysLTRZg5>o%drQvMqi7_ z_gLOnYiPO~EfU7fo80<Tzcv2FXzD4K>}_0~Jt_iCc}wII6N(e)sq$up9aRspJ3u{8 z<~=3C;APje$qR%XA|B${FgzvHpn4TXj8!hpNSTOabae)+2wB+WPNu&wucj*51F;X_ zcKDc3RldM|Dcd31%1U&)0h`|!>8PgSGe=Z(4SK~GhG3d_b+YdU@oG~FlH+cFjiPVj z(K}IJEqy-S0IM^|#1J0Mqj=3+RLSiRb^MZmji70VR(NJODMfJ26^i6RXvnpQD2k)` z5R%&tq-x)b6o=uR^Dj5m%75<g0C})8TMIM|e9fS>JzumRB{3NnDmfXy1^19~5Q_Kd zLXtF(WVrpjjotg4We2l#ELCOU9*5u2)UvBI;gdW91@tn>oBIF`P2iW*Qv*T<uX2pr zF)cONZmF1ne)evZ^opTRs>fBh1QFU9?vHZ!=!iV#+KOiY)-0x1@vaFyd9Mqr4x;Wn z&yvy2(4ed@MW;nBoiM};WBe>*Fz4KWszcSdQN$p%ff@l~<m@|DtGm<LB@+&ar`xTh z2miMtkZ((mZdcXGi}rD5IB9BS)t^pJLeEKEp63UA_*xw?f&tC*A8r<Cg$AN1h{}Ww zRfF^!h1;eHzJ|j?1L4gE`3K$kGj1dk3D7FH({E7k1?KaGCr&TqZ?mVq;#NM}*z;9x zGV_y^x$`lDSsrqJm?e{)G&7y^gwHNh8WaW<yE59Kzhi-kk%)F2ADMe_?xr@HC9mRD zx=W|D2LK)P{HzuNoyy3TTfDOP?q%&*<4~lMasrdG-p8X#GA;lbR{uzHF{;!D8s;2* zA5?Dx-_RnA<az!`JX@2pTXU^(UFHl=i`859NPi!Zly~}xGtPV6X?I5fO;B7GR@R0J zx&q*rn2{S)lNeT6D!k-(E>^@3VR=5~!)|OA9rGBJqnytH@}Fo!LhR(zgdQ@&8kna$ z(1C2@E|!B1Wm~uDGI_!)E3l>YN^dWlEq2oOMr7rt`vV~v)ARe6!{%%k7SY%_8T9-A zsXqhoDscev#H*`s^~$P8$Uxy1`}vR8b!Q&30+$Wb0-WN5pX2n5za0S+)-DK_eI)XA zcYVXg1;wa_s6?scK;i(o!gxLSN^IuFG#3P=nm>&qE+#J>?f6>J_|7yA;b@Wj;N&cj z_2{U(wjr9{L5#NqqAOvjwxbwiER*<_>WFOV+V2Z+|LDr#fLbtwNbadp7{4HHH(ik> zUP-5YWe1ijZ45f%ur;%yZX_KmJeA(Na1_U%iK&Hg5lF@Em`s|8W0(v1vn3}eK<8D0 z4i+>&;m+9niNHf^$6QhmE*0;8+poSvw1}lKo`+>s<^9IPP0w(FJg&EuwVqDbgBhSO zYxG>sI@PHv4xryLZ<k~$%%l&A4a%gfI$ZWgp(|?$Fm-Tq3EedmNj37KB*_HYl=V=L zw6Doy0=q+<Yt>imvZWIeVYp?KhVq)&gcjF+7X?S4IJtu~4-(6p7Cq$BOv`v3J@}7n zw_Uzc?24?*+@o>6QGh1r3(59VV;QmOlqjc9t~Xe!?;%Q9E=@XgAU$>4F#*m~d=lN~ zo4^^&lTqG6nyd!+=FZoZfX=(Z@r94_d~^dFKU4)EX($MCCN{yI@+u~@rD=(L(q+OR zn%*d%+0yM7SICGpl6tDKcN5t-?YIz(e1apdpXS0)k%QPQfd2%oU_@;Az;waNt%FUY zM2C)6&x7xnh*C-D#$8b}sK<wP+muwDm?%?jE<CbqCq%L1cz=w!8XroxQGBLXwc=cb zTN%b#>O8}nR5L7lc{k@%+#6s|*Ck6fRJ=&QnF**w#y6fvi*lq0a(<?oKUSiMYD>Pv zN)Q@xmScg8#(3)XKfP-_)X>D?Pnt*sNPh^!Rm!B`w?A7Zsj<Wh@sc&@H-co@&0r+i z%cu;m@0%<PkgCPFX#)O?H~MLxiSUp0tTvXwk(_o&WY4h}L=xGUnsnc`j1KZ3gXg=4 zWWM*a^hLbV1LdFbet)6n3J@8V_Dtb~3o-K1`OcoD1f&G;Whq<M<=R>lTyXBr_su78 zZ#SOa9I1BY94BqSF2}8YkC~LAI&Krnvi)u_-JEJQnVLR@SLcJeu7{49avAiMuk)|& zOm)IA_S~wWV-baRbG67|Ekdt8p_^Tm#ELU2zuC1LafT5g%=rZksgiz$6lSO3#^YL- z9O;ej`l7t6KzhCJNpPxzzBfPS>^>j)yhnE_VO6cw!aV}5wip3)kTB()vCZsfD4=j| z1_b`0)bh9qTE`mfmEVPqB;S21i9p78c_a3q35|<2+D(gNBnw{Q%#TZDqP?wp+?8Xw zJZQT6uYALI!6axud31WOs&SGq3U;;dv9fr5-l~qp+!pS%+VU`!d^o#;pjo#1=h&#H zZx2cG{iMMkP4N9Qf((!WL-Wyt9A$oFwF>2%#&U5TkMFGdRpU&A=rm7<Kz?^ZJmQ~4 z#5|iO$ukw6YUEj#Df$(MA;!qfb*g8`lKhf}EBXm(6;J<Nqbc?mYtQikQ<SET{0vJw zy4aG|?}(}SRar=@6h{`qcKCJO=&|zmG0y^aijTBwT)M!1SfaBuwGigX+c~HYmp9hh zKV^_f7RW}*g-giNeNn2m?B7RID}oH9@%Fl|VWuEDuJPJeMv{2;hHhpnh8r}^47pJ< zF00AqLpt}ziJRdCdmdbg;|fv!(!&k2P+2gUWv%<rC(Ue^6z(eh8v2b+QPs7m^Ov~C zT!GgWkbvJ5q>3)M1_QbSo1$84;axnqG5j_HA3~(>y5AH!gerW^#~o)KBE?{v#w~09 zu3i<5OA0QkOpeBpa-DxF!CS^jfrEeD(~zBNQe~^YrOpjx@mmo{FTch=O&zY*Pa)v) zOi`63U16usWYM3b;rc)9y>(EO{o6K9sS7A9Ae~Ehr@(@ANGaX0ARP<RjdTmrB`BgG zjkqA)NOwvsN_RKE3-9}W-uwIf=6U{qXWp3|#@X3%_qwk0bH;I==Wz(W2tr@OFRvok z!;4?Yx3-#4JbSb*{QXF@kP;j_TaQTzb0Hj=Qn5Ss#)N&(BUonCI2&Dy1^AD?QO1H` zSrNf9;#Nq5z1DBE?Upyt^RP7Kil+?;6^e#bznmh^!vb>hns!H=W@|o6WnHp<9r$B< z5&awW-AIMb#MtX@1KI8g`U#MChO}UB#`slFqnd*<dFW4n+L_VxGS;8u-VU~C6G_in zF}^7b<RwFlZRGie709wet@EpqQBPbOJ8@%D9W1rIX2qC9UZx6hRl00)aTL3fDY^3i zOWqMSvhyNfv=@EGD@S@A^xuZ_hMlY0*1yPTM;+3<#tCULRJ33at|<O`rqA*-&Mv4K zD+mSM{640!F4#<}T-S2KFZtv}m8Y?umZL?Rsob+3vPs=5^HWR8kf(`v1F(wPeus{^ zvE6KEkzY!g80+&1vpkaS;oJ|~de!SDDrsn|&cm}8jSoJo!gn9Aq#bOZO(Yczh<M<> zMu<%b437Ni|EImcVBgQbS3xo+OB>PoQLb1zyKRh^Q7rJ`h!;rIA(iO4!$f||OSMC| zV)}#N!6@q#M)>JVuHTeDI^w-xg)Y-+pYY@bNo}(>F<}s8u**-*4I42cujzH8dojwt z%I6E!%F*`eU$&f#Xm%Cw80v(Xm;OWmt5gO81J{_#913J?eS94Or45?Ym%9lb$^oEt z6Z~7s0VFv)%ZGkqRP4x?m|UH0ehc^0B!e#(Ko&3?p2=n93%YnQ-pCrpa1K1XjrQGk zB}`a+x^=P#tLxL00q-ws0kdPN@S@xo!#U0>0fh-A{-}AIryLVrL}5s$Svitb57{TT zj%O=0QGVCe4{x{mbYy~@h|CuX5p)XqaFf22Q(fAo=r^LAg45k`3Vx~SQ+h!PV!z+M z*eaNZRf}1MuY}yEMawH@^T+^8UWGj0Js+~;;jK`Ao^l_4$MHdr_jON`R)YMEqr|?K zYpq(<`?vCw0z9|&Kc%o=;hR+=rhbd>dZ|s&j(Cr7@BNIqY#TpX4*SyR+1ln&{{BEF znh^iJGPCp?^Dk7w;=F>e)TdGQf}Jltji%d=B~7R4XjF%y2bnW*2+O#_q6=DDgri?J zN~CL<pb5_8vZ@+OhqlC?=@xx`M6wrQ@+n0-^rOkJH2iyl#b_egeWHQ(EuM;mZ)2f~ zC25@kRIs^5Fw%I=iT|LSiTzXlbqkt!liQD@)?j+Sr7!%XzBhl?H-iG@-+kCxQl!ib zYaIDzQk8LKVEGWl^7i?~4NXElKvFGnYC5p3h?|SMYMl{T3vawf8dmU3(fYeq=8Ij| zer$})G}Xz}?;z?}ls6$OpAib(t}HwfRGLmI608<+f--5*e9%hTOv33=<UTN<KS4&9 z1u)9@7~mvL1%&HPo}IqL#+yVrdBuqF*5pHBVBVbadtQPppr@E?{edi)>r6LRrysER zbu&tD-`e3*(eO`4?XY!^(yK%w45nt<r|TXdJyvM8XrydEEUWw|wwuxCb)~7HvZy3g z<+=&$zPiOP0hn@=gTdm^Lh{G`-TMV!8!Nuvp7azRIr87ar7odfs*gc904#vqH3hh_ z2PO;}Z=`!OMNpMnmLJaRaU=k0+pf+~?`Mo(-X+G7&Vu)ghQHA2ZR1Rv<|nHxw71Be zcuB7eL~*mLtU%5f-*iBOp3cf<EecV^CQC_tvXS9ts-k7<z<tvrQ1CwP32Wrw+s?10 z1RIjl8#;VEzwvGrV=a(_f{{(#UpN>VO~_A$TLi++N^Fecv4IY9FbZ1+(xBuR@#Q5S zib>4#4P{*(O54WmOM>jRKBQg)OFBRj{mtlo4%j3oWV5L2%gjRQ74fVak+tP}gxpu_ z(``gPd^DT=UcIkLMDe|66JemiF0}WPCwYUHiD~tEPcv76$*!L3FJ}x@-wt?mdv~Tv zHvb-ws+Bag7Io}B(GN<|tlsYwCz6ParAJar9A692F8DvM+&CH(epPyJI4GKAg&ExH z?+7S)e@F%P9H+;OeO*$DMiDEDEOX}oe{@)1aXBMJ0iFmeSHJ>+@=aq-v{PSL;zLgy zNVx_hTdfFlKi{?JNagp|+Ozu&Qk0g5JFC*VLp8`AHJ?E$KKEl@Y~LPNP^Wdug-4eZ zRy4Ntq<6u?X+zF{-o}BXoXg4{tF>M7N9Jz@`~d=l!n^U|SXN1Eq%pRNY4<eTVr^IH zkX`)sJX`2Z1K3L2p?vb9(1?J#<=hWBfy&`dIQOmP^exCNc9eJk6BQe-@LpW$jN4K= zq8gZME)bYBtcu$~T?{j!{7m;9eK*w!n8kByPwTBGzZdKEoYvIlh-u%0&xB1I1~sRo zq-L2A3)K>Ob`t*MOU@uJV>fZGf;3~_6_`iD(rpHdz?CtFA<q>?s3nMM`x9rhmxvy2 zc26oWRH$#aKAMCkaIV5Xj|iLn%Ukb5Zgy5xvHkWpT5n??kfYzvp^hEX1EFI`3|C;V zW50Tq_2u2Lh~~@j8ypU&yyd5~Gf#<MOWZGzwq#lSeJLf7Off>7zaNAvvp|f@eN_3C z-dcZX)r;D(J+`qtL>GX}(1L&`Y*-oi<SqZb!V+?ak~(S{t_b;+?&X^b&lO9<;I_hV z7IZKk{#IS?E|)j8wb_H`)hBcD%3+E2g7JD(xPGVe#GLJ{uo}qoO8W!hgu$UY>vY%s zN1TsQdlA!Y^sj2!Mph@m_n69pKu*Xmqh+M>jWl;>qI)={`_RT1WZ7Oph1>E?D_7|l zUZGgp$+vz!{Vy$Xel#?M5aV!XuN%D14(~ZDk^^Jk?64d@Mvi{zB_Eng>f=xH3^Tg7 zevkSWIx{l@W$ij~=UGq+>k8!Lu*0=F7aq<?rAh0yVAcje(hB)(wh2g_4H&6|JSL(8 zG<<RNgSb2SOV!pW8s599?YI|E^G2ddJGHi8bBYA-u*#R6x`h?gy)CsdhEgz<emu6R z4`bf-&Y~U@riMQ9N%f>=X%_`1zAK%Y8pjR!Ur!lgw1k%sAFPc8FYE0${9@W;Sm1>& z2;*X;@S!Dy7)Qsgc3ee2id#|k^^vVDuzT3ta9<1_&Q9bV>ygtiND<{5j)m<paS!#Q zp?2GwlitkD7#J`AkJeV$@4;}WyouOuV-VtfU%t}$qtBVUWoyMs=+)0}49N?d$h2}b zPQP!MmZcs5a{|`J!%aVdhOwa6a@sx-)cMVGlL$G)?F2tM_uK5qs>oDhx|qhHe7rxb z7*hba(|IiZAfwoQ9%UHQOK2ze)L>d?MffyL$Gk$xZwT~$yO8~{5)HGmz6~@$RAQAX z6T<c3p`TO2qIMcJ&i14-#uuhn4)aNX5u`L;Z3}BGn<bBQu~^sJNX2t`9ryoq&=dPc zE!uW3`Jj58QDmo;q@b9S;eKatALiW>Ux-~`9w!&m=LLS7A+j*j_R9FxC31N)Jp9_~ zPop~8#HvO%ov|iAtcbi4xG>nT+;f=5cv~<hnSn_g$6k)ePEs;em1f?E&fG#`GHqX` zvq;8$8nJ2AoJbn_&pMD*^gTALt9NzPEY<d!QyK-@OE4?9b}Tl>@=N3T$h@XOi+0Cn zsOS2;=?vLUY2p0z_4ZeA&!u#wn`itvB}vAI`pw?i<@}1<FMggRG0i<ViX4AD;@SAD zj7n{Jryp0LS0)DcXEd^>DkVmP=pQbCOON#c{uJHS25#N6J}YQaReMn7&WTNLGsC^2 z-)D-|yNOmXV&!VL&*;&(1(9s%OoEl``2KwUl^dc7rPXk8u<igzvb((Y4e_&~J%}D{ zyziXNpr4PdzmWs|Hg03xmqo$6UikOUyW!nW;d)7Ehjn_OvndtMJrPTfoq~r8H!l4b zLcb~UwqdQmF%=korLm8wU3Rd>n-IGPa9UR07GSn~x~K2QXpn!xaFQW$;<?mR@(VxG zU#CYQGd!h5w|h5OlvBG#B0omsng{MnX2J;9eYgPZd5PGAuot#!V&Zi&as41S>HBW( zz>KR^z(%Hhr6L^%Q~f10Rr6uSH4b8!xW+UF`))e74{y)$^;EfS1xTBQ88eTvv;N^D z^-j{U^pggex#W!<zg%Nr?XAE%dM6|I#VE0NY=5azDrib0ddkSF|M)oZK08dQv)Yw~ z%H&67CM1^CCy!_4H1Ich6s>>#C%4sXz8!gpIS&W#3$BwQ4dk2C{*`+69KM&b*b{6I zHuyLu6Z&t{PT$V;t@D}q9gnY*4tfIY0Bi4$N2Zp>FxVL?lgw=PVt2vD^!~<aY213h zmzQ@l>`Hr*?-nrT^&1xNL#3|6`+iXz9w%}SStXWMhMie$k5F~=T~VDP!sYrQ>=GH# z3}%&PiZ2<z`dO6cCg8Zy1+J92bx0a9``qObo@aFxMaUjIr0I|7Ffi+=z01pvT-UNP zp1m8BSG+cd)m;oP%#@=Dz8z^CI(%vpJ_zIwT;#;7dWOaGdsVcR<vZang47(9&|3i= z<TamZMEaVU!-lWod9<3`L7NWciX{I5urmWQ{>t#^%;WRS?)TkBuMykLm+>5`zkYjM zR>PNt!MYmYW>T@H^F%k)Xp6M<c<D72si~A1>4mWMOG($a3w4Au_JYNG(K=+|HKBsf zLL1-I*hiFm_L!tn0Q1L>7P6}Y?CotrpVoZiHUsB<r+smIw^-x_kHSpt%4`uXZf2Jm zR=w;A=_<n(H7JC~D<_RYl4=z%R-OlRh>kXfH{LVRJJKoO!9YJ8Rg(}urF%G|+1zg@ z9Yg!Zq3J0UJe)!@UhlBhV+$Hh93sBh4fc#N(fuSd8!3Ct@okQmr?EAFguqro^Q!Q2 zKO-fm$!vS}IOEYZUow%Y{S^R70t*4AwU9**K6$!{QyuL6KK54LCLO7VzgaGLI`7-3 z@Wq`~bQ`8y#=j_pz?FR(-uiB*98_jrtob#eRvVkFflC?_v%EJx7xeOd7kt#HY0hKX zCq^|8S;6ze$SA-4=cfu|fUMfs>MHV>a*k}-A7kgyZ@%5<wkf|kL+j5t-qA;WCoJp! zeEfiKPWjXGTw`jA9~f?ov^aHaW<AqC{PuFe-;%{7t<HICi!GcNy4A?8lo-om`K9o+ z%}0#7=;F>0cJ2F2`7O_TESglM8#=1X6C<tPtMb+sh4>aP<E?&3QazX+U#)C2D;~&C z*29DwcCCvhgq0>6^CZiCPmJ_q_zu#MvY&JtxhzoEw%9;6&p@L)C4g0+P2m$s{w!7= zHk-HTFQsUvtYcyGpI3_W5^`dNc_C#MypvId0H2~jiC>v_f0z_E{{c~OwW=MUh%(qF z`jys^#e39RpFHYwb$>oI1=Bt|^-QIxodVHV_&^Fphj*%Id0+Kzget5V&{fi&Zql1D zQ7BL%`oOBU_$h$t;xeg4n;|J!={|0@Y}EHOC2hxOzr?MKne;gFO36vq7ep;jM%8s7 zVFotV?`6@O-l%3B3e9Np?0>ePnTUX?wMPc9nUJn&NnL158IEhn5>zJ2evvcW+r-za zb!gYJ#|%{{-i_=~V2DmWu8r-gK%CherJA3QctVjwR^7pNI$E8LoWPJNy-Ts`ofzJG zPAF_&YeuQ9YQN+t64Csry-SykWA|yU8vKn4k-`2E)pce<g`0-?%2*Vej1@z4p&Nxy zvzy*y`-1&tNT!@%xm^cw?q#xd%Z&9g&vnLxhqc139=<5mhbEZVsx0Gi@<Yc>-t!zO zM)~HNE((CWj}0F!pIze{!;C-A{0;#G)xbuks)|dI0b4zm|BkeSr;*)V0I9(=%*xhT zfD26aRK&1!Zr3SLcagM3>k0$<SU;GdO8bUixX9Nn2);~QDH2@Nn%nFwcTx6@Uv|PX zzJ(oG^#wF^=li|S>1zm!NMMV7Wj?O^4A?^XE`Z#pvOL@~Hw@SZ#_sJ3Lap{%UDt(_ znHjgCO3Q{sKIHqdr0?JXBS|9^#$W2ayR?^6?tP>AVd}=)S^4Bv=OM`|E}`B-M^lIo zUv(m{>SVpZ+t4L#F`t%iO!+LfPN!6D=SQ&*&Oa)lnS3~=3nADbaIW4LAwrgODK^Uc z&|$O1R_BBDo^>I{Qy@@S^!^d;Ar*NpY-XA>@49;5#^f^OWV&;=m%4GFv!I_;XEA1R zWGiiAMe%!oy@jFTGUHnGAieT4JThE6Hk)|ar2KqWGKT#0j7W{l6d2>T{Ltsa@1id} zj2P(|EcU=6OCbcT#$kg7zHXYWwmOwQW(;Hr$9_*phM~5W{p}InQC>cDjs2-E*7Pz- zHORJI0y1rb(*7=L54^Z%w(SK^85&X8_Jv+VYTGmDryN&J`O-YP<Izy6_H<cgol&dJ zsYFwcQEOw?=OFx5Xg#T!kEuEQCRqXWV`+Kp>T8uaAm<h3W!GRG1CeS@Q8g)>RoAxF z=RVl6p|BSd|M;2}?+`p%PpsB$_k@~v>2XQ9_OxL+#+Q%F<e}X8Z7GD6_s`imA3ix` zB?1$p2gwFE`#w97jc!Uzo<i=X1Ks_M9*icF;qLAbQym}FX_ic=c7Df#R02-QN&G?$ zHE3g3SNp5$1-_YlCXUw!xWI>Pg4mY1+###!lc3FfhS{R%1{$)kWP7Oz8d-<=yFq5Q zVHt-bSiXw-)1BkUFC)Z<WA&J%S&`{RZxU9Ze!}QBAy8>{^(V8o_W@R=BhviyX`Qb~ zaga1fY#tuzJMR60Y1*;||L{zSU&!@VW}!=HWSpy<gt^p_m5BB`QONpkb<Fc_AIr)< z8k1^YefasuPsHc1QPIy!TPP6Gg0>8f@w`O&@T`j8(@K`oIDB5B!2SknBk}!U^9}9& z26u5jdUjo7Kuw9GUXS}Lz3=B|4W0D)(S01^xd@R@?XLt*Lm!@OOVLM{#4rH|&J;TH ztH+L*1wE)%wwZvj`h{|6;62g`B8Tez>V=d~8`5gkmTVDBaO}}2K^8z*g7+c~&_lA1 zd^hKJ`jdRH>(XpXP=-XP`{j7DZbo(fpa81!LWy5am^3lAa`d|xm3np}w3K_nBP593 zpO;qaqE-*vPrJ{WS*0UGZLnd(?OVM?jjNIEB{efefOB+}ZEl6}G*)Bb=`-db_`m3a zhj!)KI4c7hK~sDK!tXVh&hTau00|rS$C0&fF?EULzvPE>NE=#eGJCIyRxf=LN$r=9 zw^C|OWJxmMfw0{Ker8XiWUMnHpe#vylpZo#kwSLwUSQ{+LE52aQu(zkJ)24bSpN%Y zs34g<znM}i#s~iCp(8>1994Z~uXO>QiZ4LM(nV;(e?F}7z5~0~_E7$HSY#0cs3XXQ zE-uz7z6IqfZEtqdsLQ(OpmDf!BWk(KK!usHlVNVc*k`+wl{1@dSMtz&WJSP)P)Mpe zA$`xzSE}1$A7=IbYn)yMJ~24<l^|{-Fq{WPl?K)rDXIV&3k*?$pBfgvCVFr#u&x5e zifd&6uspWn-eZ?@wva4g#eG<r+VF);AmP2k?xu--W3`77?MLS1t-bln*+RefxD??L zA99f*^<gn3#16PJ$f0Cic>hSo-W%#9VR);_>F~pkB<!|&Z|O3f`7hEE!y-CQm+0xq zW!x08$5$N&AxCSuUt~iYcH?apzIQS_obQm8=HXIsCW2_`##nL}pG!v+3xdyI#LaJF zlOEDMW4u64`+$qaIso>Ros6qQ`33VQ?SarF=r`Q;*>jci#;M8h`cL7MRcG}`UlO## zX-3>)jdm=I72Kc#)#gg(%~|;sm^20h?#PImS9(ZbDE*P!dZvjFT8gYX7m}+cnMvt| zbSK79@tFJ^`?-B_Eu-l$>xnKm)q0ijh!XEal}-9&szn93e5^!<m&a<`=eEF#)kvD> zp_ux+DrA!eQgR9x@9heEXMvLwKvB-XbO{nB>eM@`ar<=!tb^Ez&->z)R|Yx1hgORl z<qv*3E{yZ51nldv7|G}<=3K0KUY>p5eCh|!-MB>0kF>AX>tB;JGVIZ{tUNl4Yl+XW zMq#k=#fNv|xyQHdQizH!D?jR5;Kl0~mHV*>y;QN}1En9uBss*f6>}=~309h@U4843 z5xT5TQZzUrU`txxvi?>!(4PIZj7rcmQBi#!m4f<Xs)@f>qSo7xvd6wjMWe3iri?r< z`Um5<u!e7J%>v5=Z^E!d7XfDJz5UJwgjB=6S@e6WtG=bKP^-fmL5l*O$d3m2S_fO< zaj|9fxF!ZQU&0u!4kHBZTXo)j$ykx_tv<pecT#+v)`Xhg{qo8(loR&D<NLsqP5Sj$ zmz4^@cG>FT_a&cIp=QU_i*N~}My4#I<wK2#U-R{Uc&DyNQHO7OZ<uUS_ws)1CM_i0 z4CDO3pt&TlA^<d6t7I>s8$!yM?Zhtjwg{7>d}4;1J*_xutr^HhsD$qIHa3s2yNFnL z+PVeP&Dlw(5FR8`sS*{%k8OKY*pJ46!)r(tnTkc7V~+@l*M$shJbCWq`?V*^>!d*C zIuum4>l&C#f3u?GDW`|XV)oIa$!5-0ky!|eKgn+Y#&u2T8Hnn4e|Hiqlc*bm@$$T2 zkf>zPn*iOJa`JSN{$|pm+NzlUgy)*luaf=QFaLxE@@vv%>}_m$KRaHQ0g~Z`{mU`` z1a(FiF9PMOl@VgBbqRM$x~G4J0*O#}%d&jTWv$*nd_wi@nt}=HV3x}L4KKE*)1iW> zZ*>b!tL+`@<4vo?<b_T%aDBfCnCF$=*c4iz7kB-cM;oHU#(Mbb;<@OAx$z**!CA-d z#)~v;?5F96Fkb<s3+@^lahw~&<q`Sy&OYy0_&vWYcIak-dADcFkD*#m9V2_=6VJIb z!4ip1+)oLPv8U|_S)%zQYe8baj!QA6Rr|TfCXJIiJp5w3&<3wX^Dlv13w{e8U5H=a zRq5m~S%|BHV0PEC`2?{EXbO41^)ZfGM-?|wrNdih<?55`{bb4uj@eg!$77y1r$3Kp zN6!Q;ZiAsL$tHCZ$z8&5f%rU|#SQCBnKwW-AT^Uo4I=I)X`-)|-OHRfW!rVJf1~sd z`7#C?3<93fhP4pB`KP0juafh^6JS7&Ls?np#dN%ibx~yc!4Z4*VfRo6gi&catMIx* zL9smU=(ys>ykg6<gUwju&lZ1ABo}s03IDGk2}O2LN%H-DxXydWGYjeL=K}iLj}fKh z40mHF`p1&5$FT?1D+4v2S>V-GLXW(R<1ts$-uT2muO{k|zaDxotBZg2?otfiR2Zz+ zz@DRhM)3_P;8HQMhHr>^&g&f6EV_md86=y?#C^<n$;s!$o@IZ7nBO3{?bFSia(d6T zo#69;@|F5~sJ_rfhifbwg0j7zTHDab2l<x2`MmKGBi5;eJP%you_iSph{PjiLqgwl z9Li;k%ySh{M#)uw-Q)PphK1wiU(dx4YcLIZncHRSyPSyU@nE9ifnzHmwWC~0<R^lV zs9v|0J}dG5Bl|mxOP&h5-l;$UqYdOe%`IKT4DoUlK1czjOaJf>1TNLd0jUcHhF<4& zQzzMVBUFh@`J4lCHr2@1v6X1-5qN<KgSrdu9}@Nd|7toBIhwVlnZx?M=pJZGRA(=9 z3E%$dlmaa|w$Q*aM!$HOUf2qC3KMcxpr>6TGSVB$_-Ma_xR%i=r1Dl_;$54*X;r_V zGV)T~;2Z==;^1a^z?PoqiLLU5Tn<y)*VuwC!#=XxjsJW|7tkM3oa;INq?bh8i|MW> z0gyp$T<R)EDc4>Y;+DJoo-XfuBQAZggB*K$bzp^!#h%_=L~l;DP{+=RNuY0|`%L__ zcCeo;Vxlq}qaK~j`i1_sp^w^}0sR-Y64U;mm6xgS8e)!<u(YL+8S-l6dAB%S*Y`uO z6p``OZ&vx4?$$$)gV6~om~70D^Q#i1NQ$x)ClkEjjR0<_djCv&K{ryq$;?ldVqYtF z!HfmEAfOFr^^LCVDa{cCU^$_#4#cL1s<D&;<No(t-`QqyLg3qFU-s)Z6z1KgoUaVm zd?>vlYR2uQC%m0qxu9=yI>0;4Q@qMr`4UQ@TB*}=>$Lmq-G@&D-)?a@A)FCWQNgGd zcrthivVtw4DtLtaauJ;j85H=j{u?a}`?nH2oRMkW=VR99>Q`gVn$FSow3Q&*h{_0B ztYA=Zu##cE-1_c~qf2;3PU%ig&Q6}sO6_X(xRH@ts>x5=^unCW#vA`%r>wOIu;zTn zR%?#d#ZQ&SGGU=?Y5wz>@`JQ<3Y~n4HXisSV>(k8ALoqWSKH)UhvuG)xg2aSWB{Mk zb<gZCsPlHQVNuc4h9@2v_3o80tK=$)AtQ+q6&~oH6uqkdiAg}2Mr7jSC2UIc?cBls z6o$wVx7I-PtLXuwv<j>NrWwdfQ$y&38C*ZbuN|_HqkQ^B_@|;{q^pnHmwt!*#PXw2 zll{20@rzYawUuzjJbIbSm$B5(GuJkAONrjhs%Uv+o9@27VM}NxClq>|XeyvjVp8NU zsv+X78+s~?@w4)ml3x=bkImN4gU`9_@(`x<JLh3?QVc61t!=-3nm*;Fp(5dKnh(uF zsKr!Y>QLF*L}-K36|g0LjH&jTF7YH=_&030Ep)0PtL@Br`z0$qIJTz6Cs9`fuc`I( zFNb&6&g=skSp#r@5p!v(oB{4>*m9mO=7=O*{t%n882HF7F}w@&a9H}v$1s11WJPvP zjGV_@<{Z9swnjvx%Fa=?5cw-P&La;8Up0YUf^nRjc%)*)t2*h*prujsRB?@9auTzV zFoQ;3<_v1TY_7LF6KCAz?EA#S#iib2poKK6$T?R&pjhg9n4|PcJs3S@w+9x8E^&UE zE&^6b>vr<xWY|?ixU7c^;Qe_-%p7PJu%_zLRBtvkTJ`UkYeKc|CML0t4^U+y_LsYu z6rjnhHtI*X_8~HfH#9_V7Srq}EZnSYd^PE#bC%7$E@8S)Hs=id(>XAOlaf?IT@AA? zFp$H@j%bfpBMmT2cIC1*_%KKQFu;VOx8w<>S$V=_V!x2@mhgB~<N+Ip1XHF^<Y!!w zUkPs=MwwP;4wP$>Qg6a>3h*-lSwX7(V0!(5H<^{$2pOdiVFgv;w}wKwq$W?EiXA0a ze0-AY7hw(=PIdk5t-;{s<t3aNGHAGpkQp2h&}n=olGR3J*4N>of~aT2lzJ4h3*LVo z>iBM<>Sh1IA#n>k1@+J8gDOHlf2~rv2Dg6(rqw*QeC5UHYVoD)H9ug-xcsd1y^pyn zr#js=WU@ntAD2ikx`l1fYWsmeKIyVUJX=Y9cldpHQ+%!aaIJLfkS1mccm?x3NSN3I zH<6#}V>tsJ^Xa3$_mkW)uQ@OqYIB}~Rf$YR!Zw@zp60_7-&M7XUx+5LY8abJD!jGe zfmRQu)e=PvUQN(UFh;j8>Ef^AlhGShYNi?#j(o*htzs}^Uw+@PcC(k`&l}DnmbG}A zywJbrcQEmrMQM*FbO<{n4043hl-bj@pZ@F1+-aZXs`hbHQdaLSW)tS;fjocz$t3Am za3^GZe~XSC<B<OCClvC5B~)@;O+$(W45`Lm9Zh5E(@@u(@X_MxWE2Ai!za3Tr&k6A zuo08P|8|l?8JejZ;Q2~tZ6f0-5*tQ|$p;eeUQiPJ43CiNYhG)7wTq{kgl!J1<PP0i zOzC2x)?cbpez+}Lf;a)EEF;A`I}%k&u~EB1Z9WY-9-;3uzK-VcE>-@Z*&?e<F}p^B zXElPUQXK?(jV`S3bkv}Hu~w#4Edk$!k3a?x7Ws`(46zWh6Ir9^_4YLD*%*;hnw7c_ zS%k>%a)ZCc4UMGuxzakuU+ZT28W#-;?>nc}4L#JORHKA^v^1R6`l)sqVIb_Zj8Xop zk*^DH-^eqeNN}}GG}z81dw7r&vxK-4Nkzk5wv6$^TD-n%J=%3L^gv<urLfafxtag7 zr-8EEF$Ah@B9x-;?8NM&s4dq$Q>|Y1kpUFutBhULu~ey7^Py~!4p>WX9=zyTb>2mk zQxb+eOXY7sQ>G%5k#z$$ioB7~Loj_Zoyd+SF<OfRI1*@(2e1|joT@sX@<LbcnZqkR z$uOo64|MW448Mwf`aJMDj<+<XSY7tdLy^R&WZW~llxCy&-WzpH2;F=QiU<TnNcQ6m zIl1&#Xe-mI6QWtnGcvMPJTR){c2(A`dXg<M42asibTn?SbK?}-94Uw{>xvxG8-J1g zI!hg<YR|Je!4W^YVQ89ML_c3>FtY`luCuJYnNoUCFtyY!<%$+364Vnvh^aME>uTky zoYWu5z%mfAAZssYuHD)nIkb}XdH;dVAvw}tHAif^i<!awqd~qSr$(Yvs_^H5P~Co_ zsKZw)doiSZzFTUY{k<Zu`o+QAs}#pvOgWjZAGLi@I3K=N$$m0!_*}r1wy-GxQL4&( z$m5m0XuK_0^a2&eBv(w3>316;tzvI#+;0B6ktu~o48fGOm#XF3x4@vBLUJ1Bqp)N$ zAe%W}t0f+hRyns2(}7vM(r)bPIIA=+oLV8$Rcy7Ji1t!EMTv0x1LaOjWG&$%=m7WO zm`DxVafsJ;R@2Stcx3SnS=eUJ*WXm(coikt3I^*}MOz6d288-gwEx`xW`ZH=%M1`L z4d6D#Fpe?}#U`c1|MIDK!7oS?qcREkBKx!7-6#I%mkp*uph~p7Nfhwt{->AZ4hDVm z%7CiX|N0?)G<?%h<Z$Z$@@2FMqNteVwN<0(|LccR0x_nlJ&y|h=U)^E`lTv~X1}xb z3K;bJpMG{A=mP@{svrlIAItxC2WkltP%=eDv;Wr*{lDAvf5&Z7Uj_M|{`5EjR>@~i zwr7=JZXF#1k)P+Hl=eStKtKgB9~A-}pT7+;fi6gf)@-)Mp(-AF(R~AuQLgIt4oGYR zq5|c>BGFLe)qyhX8Eb*`;;d8C9oayCXB?#+weQ~3o``ZboziNcCpQc9Io%@53;2GH zz4$u;1y1580pRdVWGH_Q`pZzq+|eRR2PJOn#ev>Ujo0ByB3@Hs88+Jd^>XJlxl{d; zQDo1;rYju3`S^+DkH_C{Z!R5Djod5bV#)LxybJc#deCvjhBEkV%mK2?hW>QEE>F<A z|8{Y*rjr@A3fup6GJeUSq%u1W159mPHMZldn=@aF?|AhX==>St>$HlsYy7Xh$;G{^ zjr`AlPgGf{%>pckNw}k{w6x9mH|wK?vjl2lW&kID_#-N@DS)G7*K)kAtnuQ<M5&RT z!8ga_)@@+k>m|UFR-D^3rmTyS^|js|$Y$(Zx*_i6J`Abx5;wql^}v#^F{tJ72B>sT zTKIPH_4R39T-YOW{jNC5Z9wtiD{yCjmey^s22gL;uI4O(9c2GR{JR7Ic)c?P?jzB| z5>}!=c_TPzgFw<(wz+P%@zQ>0uJ$e<08P^6hj?tWQk1tBlTBOM9`hB0&`b6LP}rwX zl(2*jY!BFSXRN~=Gr`!yCG?3eddrlErx-8;ZEfwR&+LZY1(nh18U6&gV7CBqlp4pM zb?0zM)*Tyc4e%}6w#uSWubW##u^Y~Q7*Yt@r+syp72J$-n6B)2Ihf<no62>1m=KN$ zD(oX(F#?-Sp8{lx&0!BopDPAhs+Jlz%yh<6?@Bu_*8e{HgwhM8dY0w#gT?=bmq~i* z8W3x+l>ite{UjKlrI{XYPM)3;<d;SLhjV+J*c=y-PE<)a&hd{eClCawNn8UnSo^YE z{$HII<}XgR?Kp5nzbLsuobf76SNhU{%XpG2iTRXhA8VMEHF%%O3bs4n&@hzA-b@?P z00=mo0M|;^st<0Nx{sOyYXoQ{3<_1Vzo_Lxljll6#{HQ>-vHXEQOEjyxlBQa3<)Yc zB8_JS2$208Vi?ShHy@5eX?uNfTwHnS4Uih~hIkm3N1Td1GtE)=OdG0mvlHF;^#0*6 zbev)lf=0{gy86>&;j3kD%K3x)eQGiWt=Qm~D1~e|Ml0qndB!_=(VTVNz+=RrRz)4Y z-D|^DgKFmfhaJ$A-324ULRNym?cfSelHRDoJk%qS))~1ax{?O_(iizrizPw_f-Ytt z!#!6Xp&Mc98xM~59RH|7zWccSQSZ&KV999MF|ZH0-&>2<7V#(w5!xJP=f2x;Dwq=V zLf-Hx{pL{K>sS(=)~?44HO#%8dW@yd#V`=_FA7zUaZ#N=;*jxogI^Rs&k%I5rIU|4 zDg^r^Kfns1_XPfn`m@0~5nyo0e(aM*XT@hMBwH|4Y7^i!67tzB`F3U4CM)i|D7iUa zoJxGm7y4MTxu66fqU-tYlI~iazFx2CHv;`X{sV9!-FE@eUU6Oc?{`0$p&_*3;Ygx- zU`WQdPbs9gh^U>-(7$E<6xjbBUFpxXA~tjmB8K59!5i?20?*RqDc~~pzG`z(!Zac) zOX1Xay~BRzb^OWX>j(p&OZkBq#uuu%=wn!J@zE*<VLSWPj(FBxtE*(WSRQ3R*-rTk zyWP!j7@<=90{jGC=kgQ4LsY4aUx%Ya)TK+Q4^d0e3^BFpUtO(Ad~+QT>B274S|`9I z55uK)j3(l!)T?@V{s2|n`$%CuqeQ9U?+oUj(~Sga_Dd1yM4v?e6Ul!iqvSKA;SH#V za8da8RA{<7fWtR5RO!V5;g%n=T<silL7>m+AunbgnUf3{wpa7OI?tTZj*bJ-ams&Y zt!1h_ec0Bbu%(*y2Gq8mRW&{K8FnDOSQX&^5;*^d5T*#xXK8`HkJ}Abj6ni{qdq-} z3^lLTN2<reohjnQPttz+9`?Hf$k8f0Xqmn%=o;t|P6KCPnG$J3KKY*sj`|}Y?I}i8 zEBre*lFS1(JnN^vAL`DljnK^nMI@gyw|C8*HqnygbLL{QmD`Lmas?uJpXq>G*B06% z3ATaNx39{awe58tyE_E#OCOG}U%9<BaPC7!(f3|opDyeYghKX;w#3j7&xQQUhk@P- zRg+k5!43Q5puAaJwf*#n_sQ0Jc3DWBB*^dlcPgxy>DN76Ix6oq$ajEtw87dW+XqcY zm?s=lVh`YQ^nBoMzkDI}cMAWPb1hP&kqGF~sv>w|^w0aIKmo2(*-7U@>kWDQW{frW z-YEp~0K_1<rGue{F;$r3{Uc(OR7dJ8xG>j$CQkfBmkWpBn}CR(&fNLu6IV{RYU|-v zB6eNV!_`5d8I5T#46s-&FfR|#))IUH>|q{~9Zv;0BX9|PfQ>L?*=@RQ^Z+QW1#7v9 z8P#&^`Cj&w13_n)32j+yZgQNZ&tydcM*leIzj?$c;9y9-(Q5dwD2|E&G4wL=KQB<L zlbutc@HuCX&;jMLbKpkCJJ--&IZl<gFij{q#sd@2wAzrV8-TInc;C1<<1I_AF*GTg z>gmHJT)0PX3dd)h(MB@bJ>aZdoV5v?J;0^fl9u^ZWz%Yy1+WDhPj%o$Z+id!k!*Yv zTho@+b{<9Y%oCs}6mC0ZpmyB53(=F2G%@HNfWZxaJU0I4w*ImC134i1m{%{N{rfz3 z<Dw$p0YqcpC+fXicl~8)ST$RWqRT^@qYsJpQwtV>5X<3|$bbxCrqLrpGD~frujcL= z6+_~z&RawpMF7t32D(&w*j-X_w;&mHFO#l!Bj==FXkqH&c=K9J@&l6$2K@D*9$4M0 zT+;eAkV>2vr5}o+&@i%x`uAmtjAGxk6G8#L>}^1V=WyZovcyr4*CYZClh`HZG)#-P z)e8TQNTf+igIa@+zkOF|+|?S{$|&J1Qq0N+Jp;zwQd{Hh+cU{r_vEb^Sn!lvrCYY6 z=#ByM+kGTS`l=#U%3v@ZF=Pku?WZu43Uk?P=N4K=I^SjCpY>i<tK`JDL}vJAS?YL( zxN~_~xx2y5Hz%`Bmp9cmqn%{@*6Q28Z$4jizYcx+`o0%2`z|R#4??>{-%{8K9wf1Y z?})eQwl<VE&yZb|v#})|$WV`FxZ0QgBD?5S>3>{8JAU`Bcjwg0qtJiemSjYW$Yp=+ z4-CBd(XwTE-3gO@94$H)Z`GMBHS(*Uwi*5CHObQ3pi^eNeXk4%V?VL;?{csT3vy!G z(hjM|=EL|=ra&%IvsjQ?-$r!*>sOi_|C4E}nwR}#K7hP+J$M#~hr0@lB4oWscrd-3 zCLn>>RkHL46D05Ai2MRCdxqGRzG%cU=XOna5=oFXSeJA;H7af@`OB#8)#rHezOx)p zBqlYTdtVyQeBKk^Gw02@TGxZmUgvWk6bbBhvQ`YkfA^;P%%6jt5>f{~<Nqs+1nEly zR##H{mMr4W6-zdP%8$;0b>st_W+3C45Y>P${T9Wsa|ytk0p~}&j+#<LE6o7Ee&Vt5 z>s~3qjN8I>*@@cYVn6q(`Yte&OKpEH%-QIe@oo22p%Tp{zwxLQb)1^aMkgw?a^N&{ zYUPNb6rH&9YDR@X5I9((1eoD-Jt0I(gjS4Q2@$b&Qo1NBm~ds$S8Jw#wpfw}kB$(F zmTCW701zc(roM~~)~H+Jo(ASw4d%?BM_m#U-<_*PSfdMWh;Un|?d`kQI0v*`aRyXR zn#mgl;0uJd&x&;Zb<*CQffNEc8tw9_BL75|Eetd>7U6s%Rbj(0P-%oQf&h;az68Nq z0vmpJFClJore0BgXC8SDup(|`2ew;wEa?*bHl4(QLk()|*R$h+aXArnQqc;Do@epc zZ|L<P##WGv@n%dDP)v&(wv}NELfj4p$s;{{^aj4z9Atb&4kU@O<U#{X8Be_SdIWC^ z&cm2}0Q>TJnnO|>@j3+Lxt15c1rSPqH*)P45cI$Dq?SX=tFH_FeHQUXU@5Smj6Rs| zgbj@ySHe0MZs<2YK2Mn$&(p#4w0dO;>r~$pC75JjPUrtr{db4a7Z0dsxe|-y|J;dp z7MP3vZEjI0A+t$mh4i4-Yk3e#BKn)hSV50b-KQ%pjo)1j$NO9OU7qwCgn44nTu9oh zrN}J@mP7_ONA67*s!?+_k1+D+O59$#Hep=16Q}{4n4%m`Qm%7p;07T5*$9;>MeT#r z6FonQ-Bivy<x2%?=v_cfn^7b>@B0Yt<x6l5-PI5PRk}UB$eom81GwjsM()6QF@i2` z&zFeHc&kh&mDA{9P)%Lvc{nJFyT?!6dR2%=7t<{e)a%yerb<mlna~tYzMjUt>)hbN zftb7#RC^V^Df%x12TCno0A0|M`$+ItRI?>OHMgg29B_#&14uEoxloJ%&hRjTHyGl1 z<(d>4Tfb9HP85T|pSt_vK%KlRzK;`m@O%g$MDoTeoe~V+#msqoo8Z~BjkNgqu*cyq zRoHvv4BJ)a<~n{^kcy$P^E|bCk8%kR-IC-{frZoM5pfbXzhJq(Q4i2Si_SDlq_}9o zdt@u5xc9*dETHf)d8w}(Smo8RXFbuv)ps1fEoI`Z2Q8cvT)0AD)AWECtG2L5H#4if zW>ixQPM@j6MO%08+_&I4iQnHf&)@EL1N=!RJIU=IhxYaf>RcH60%OnPoo^cN<)&E* zv!2_W2i#@(i=oWjBA`SL{p!6|l|~X8lsA|;9C2dC0$SF^4zo4TJ}GcLxD^~~C*}KS z`2)vA@Fso`KD=I#2tzx>UFJpm__pfVU8{w-fs`wsPxYB$Ne_~3A>8h@bMIy^SK}U% zW1)aGVx4_=HAuQnDi>@b!WputFz#RXr09aueDewMO0Xav3@<41_7WM*<xT9YwOPEe zAEGZASnv}!YjIHfA1Lv!Cw8C+xG1Pi5$9iFC6P98=-_NQel`S?pnkdPR*`8s-7052 zwS|d^U+S%lb4PlVdi!a+iUWX&&hXHEq@|^`Eg*0|<7D-(U?<}#`iRxa<iOj=eUcD^ zsbk8x#A$N<f%*~Il@*J>1Cc2y`7-?x`fme|>&V+)F|$%U9ApTAYD8>6Z&oX1pIgwh z|3FCwt0v0A@<fi9SEYxut7@IpB_g-Y_uYULR{7B?@LMX}HYZ3q?G2mq!~nXU->`?5 zSQWB?9U6V&XBEpCJ5Uap%c2+m_DClH*ko{7Rw2jyr-VxgMk#I4G4|@P%Cnl5=*^Xn zp;(uFC%nXmc!XD=n-NPB?M$GfOQwoeK<<cWxvPtIonu6a<mtNTZfN`=SOxfF$bqsQ ze;MsoHn7KINJ<S}2>jk)w&=Ic6w3#wM0g}r^wPz#1uB_>6JPCgxK8+>A>QV-{!3Y3 zLaJ%1W%)7Wc+v6SLiB0l@Y_<=@jkC`;Jn25GlF*zo@|=j&NQi&vR#m(ra+yqNBg(e zL~83-jgd2VnF2J2m%X(9KuPrGY`OQ|!ujFqr8>sZ=L7~&`Ml!RjCt{YLK5fn01}tW zua){&>`??a6GrqpjeJl9^6uxmXAc!Wfni7`kVK&5bdeStbt1|>Tj}C+nX&rQd7nEp zfKR3h(R$#FuL`-L`7n&z-krf5qA6)%*&|eHj87Z7_dxhDP_%BOc20(H6JqFMNT&1? z>-!dCHh!LI{y9^uQ|3~Ehf4H-9m(X%_5w|Cg;ud1Ty*Mzi!RKRjH28Sv1a&PHT#Jc zR>_+=A<x77`Hjvbl~U0QQZo`A&LxTaI23Eys{q!1RJ!1ddw>$yZg|v`z`)u(QkIdn z8cGqr@$Uo53`G+-Of}k%H4w-Db7DWWVSwG88!FpLSFJ`rsx%18K7TJfOc1`|!>P&; z{A=E4*9f9*OYvjzWk-L+Vv4G!^x4zE0*nW?hJfB@eDAA)ED^z828eVs9V%&LE&%-? zGtJH~g70Dby3k+fuHh4!nhg}!5F<*BzE5<C%W`*6lAm?OQlh3zeMV@Ce%Gyl<D#AU zw@2U!!a5&b0@&6rY@l<z$DiVBy{Cc(^GTn`g)0!1W&tfdi`NfuPl6>58-WTPdL^|+ z*9GAxu5`}j)n1`Gb)R#Rgj~L>`*%HVD+Ku5ua_6Lul~xxSwIPESgVw@L`dxPHMrkL zHiQnIiJqWJE7e>GL{DqZD}))KF7`L$s^1F+)ZyHWb)!Xr=i;{9C>;?+09f;&n?!Ft zwf~vfE}~&2!>(RI%%U4ShylTZhA=djoK+COu#JL2Vdw-ri8>Bk!hoV>GsWTsT{C{P zQ0e0Qe7V_cwfo`CO8KP-XTrT-Bq9CiIKs^)s|fFDHSv1H4g!8?<k`*LRjUsqJ?>nM zC%X#^;kWN{K}|6}K;rnj|6m9`_2P23$)u5M!3k^vHy91SHexrbVf_!tIzbKXg81dX zTop|qdVE3uQ`1(|-jT~!zhi~wxkC(;oSVZ6M%D+U`ykWL88w)Mai?jYASKx?o*rci zIpzEW$RPZ;?n?D|aiz-$^$2fz+5Bc3WP9Yvk~}qGrE;Sqh5`mpXMA(E;xA6maNBpN zXZZ0X!%0)E?f#D-G|vU%&!T7|P00a+-+XmXBiSzV^J4G{Fq&i*_sdlTic11=-Cu*n z>n$|;Z6A%Qod(-!igkvnTHhxrr}p4B6HDPT$@#n~5-{kCZAP4SnXbDsm!SIiuPF1E z<yPH+m($8+L3g#e<WKs*cZY8X@FUqG_kx9^HgP;m>w-~wy+E4uimd|QGYKMi31zr2 zvY#P|(Hy|9;LF3`qzEyrF`9q^UH9^2+hOS4Qvfsk?lQ^IN=!?VN5Bm7i@61`S|KU? z$CWhov<j87Aa)Ci5vjQMtZsb9_|A~}2Zgpz9`L&oTQMJEwItf5v6Jx*!ad7$D_Wth ztyVR`&>crAZfCJcafC}TZ;oacZ|Aw{9upDo=^)@XHl+jT<CA<)_T8ETQEx6@OjcU< z)=QJTsRoDoa0r{?HS>wHv&c|u7XDKN++F21BT(JkHKA4icy5|V6e(;eR&yL$0=S-+ zrHlUk2kdB%^6oiPrF5`sy^Iv*5%;oWBZGL~uXqC`vRxPVqnjQDYS*Pu!PZA$e@Hc@ z^PPOmJZUrm5MF8yvwYw`>)e(Sg6-jkBk~k!+$&m{*ps9hmnGlk4`6c7EaM8;K;`Y6 zVUKXpJUzjLk1&%ftcPi-zk4jThMpu~^E~Z?t!RCe$~JTj(I{;J%I}P?p5!`0JgMtl zF{`<!*D}7c)~ZCYZRZiqR=IvP#Hpl{A5}8zLCSrzQjcX`Vwhh5WV`RD{0Z|N#{b>) zP!|Hy<r4Bqz4w2az!?{6I}t{sx`O*FfY~}MKDj0$KH^h^M6T~aq(lvnJ|xG%9;iOS zzmGRa5YEz5lH-w25Uk56&xYo#>rRywUY$J{%$8U%M=xkjdI@}^FS`Lne9yg9S~F7p zZ;nPc<AzMlrG~Y<%ep_*x|bfoaM0NEogIix@oFXkWHwZ_ef1d{doTy^oU!s!mf!De zl=tPPH5kG+>VW}@?Vtx#dps~cBm58@!=*mi8QQU@ZdCVa8u8nXd5GNuz2)L4(s}Sm zI1izI7oKlYPGf=|(73J+^xG+fGzVX13U`6Z`!0pegel5O{`K$!L7K?`rci`Gy8qXC zXHcOD!2rE(-tXkyK?FNTEju5s^oON|=w>Pfc5o=<m%;(q9@u!<jt^KbNCjk-IjaC! z-VsrS<r&l4)9j(gSur5hh=Te9EwCWz1F5MZt>XH#nG%C<)o4seV<1QCy$6*kU&I*D zX-eEQ+j3J3ls%)XM!)xssc*Djo(hd7suD;jK2vZ+yhYeVE=4!b1NgkjE+A|BTN+;` zKGsL=vOh!MaOuGsIW9(#J|Zrw>l_gNc-{07(0LA{1X%A$i;+~ap5lP?KreONp6TmL z%tBiz_H_tDoOvsCwe5J3*kgI<tcKCQ{hM1Ra1-kMt_8gBGO<st7|uR&e0|F&fM}Y` z!}gA-Dj;$30n~?dkYTgnNl5-W;K^1^D4)FA8>o9g?K>n&!Iu4ax}w;Xs`7|z6@nu+ z(?*#dA1oXb=nL@KdqK9Y4hOl2S4PI;FTeVn?lhW2m`7-ZaG84f<SFT%#O?LFDS9|y zjfZD^N!>$_cpFjHr)=Eb7|SM{fSLCcVy4OOMbQ^g@gobm{vqk=D$ns`**-RmC89X@ zS`1`8`Z1PRJrdG;uEl{+0>FN~?|^Kg?^zHaIyNy_P&6iOk6ct;ZIlYh7O>OSD(d#! z0*u)=0=<=Qk2`D#)C0HS)6Pf#D<l2;FAaK7-?TKZ=DV`LW8b^CphcIqrLO0&cCL^C zYlYx7U2u*wIdse1+QnXBiclucnLQt}^Sr$b5SVH0ijbXZ!Rz&4Z;-3+(*#KeqJ((L z&M6P5IkLT=>{*~=hZz0@WKfN#wilY3AYq{)COuv963bHb^A1h^*Y+D@pN%76A|gwK z_i?EV!FgCKAwKUGgvIbWY+YOYB8y3e8vs}u%IU=aLGl0)%Sb0SBwyiH9ao=P005=i zKop*U<Bjo~y8UZ-7v<``S!eq?4m5U7C&Q}gC#LX^i6k*MkQrVzP)Eyko51hGL<VJF zbD^F0h}H(cT@nRws=91^aK2rfYh2CoxthYHY$ZvjUdPx(xVQT6@LebvA>s-BX%dG2 z>P!EH>eA%iq4Y@~H|{c^pgJkjZ@k2N{Ityen-nhJceL@}cioGy=6kiK?sK)@<(Ks= zr1%$pikbufWf`l}UZIpW10G9TX)4q-$~1y*|E^BNEHU;!w+x^{s;>@YSK&v3$912_ zp(x(>Y0vxA##0-g4&~!aq*loi9*%AU`g0}6Yr}Ng_@~y{pdgS@L`{3FtU{Y#By)K8 zL<OvCZE4&e*EQuApJPaQXDqpo(95rEoFiCZ!gSGyOAr$M{=+@mfV!Rgs6=m$?jSL9 z3*knywlH@<&E(<<NF=EI3?QZTOc~2ANu$Ql#czXWr(YfkWOMgPM**d-PoV&=fWmwS zkr2!360Q6PN~kXaFN&rVjC-mUaFGN+lUW8ca^;p#=Ux1^vpZz$l;)HOS4=7`6!Bzq zdlmYc0M`;Bq*S?gNzQQvE&i`Q9`KLHgh0L}>n1WrdUrCJ@z8wy2Dg&R++Uq2r;Zgp z^`#i6d_dGC8Zv@MC-=6C?@>Mx8eyE4j2zOMQ@6YsTRox}q>sSvd6HX1(?{$7MmP$V z%3-i#0upVnY&T2&Ow&v|p_(aJVi?%}O7$$qe^iYkIU+5>JHm?3YT&4qWPwf>VgY&e z(xsWUhBhA(48ad;_4iy-mDz(Cj)nT9>bPNTe=+zrfb9nS*7C377^pbfQra|}_<}Uq zqK}~n{o2luZxM_NuSLH&tG@sf!Lw*zezTh#z&@X@w8-I}gokhf=(*^pTB`K{D~bm1 z;{!*h6%sD2!??>Jjzb2rn>Ol%BkCE+sZ}WUad{{%Ew|fJVgdBTl}o3Pd%=@uQsGJ~ zF?3<Udg)Z}-?intPj^sIQE%SB-OZGY1WzqQmgM@X&ri31jMdhb0zwa@r@$Fm(MR?a zo)XOw`6;xy`}r!+p7nY_9n8EVj+L+Zs>cIG(oip}sHG(8Ec8s#P&W~$;z~5zlW^nd z8CLJmYji>1RGZ#Phq<6?<=bg|ZxmwoRzj}Mr{u!d&T1dofP%$0QzD?TKSz8P+gO+u z&R5BvWnnxP`Yy~mLNrb1NvcKN$r(=9FIFaBy2=WS9EOvxwarnUtq5V3KCX~X1eyni zmSLW=8j<PyRrs|+cc?HF$c?!)X?1yVnb%7R{Dgs)G5`g)>maOaYt~oxnuE||b=<Jy zHt$ry#!DEB5AiC!hNKYSol(t-?5ZMbChGQGr_k2js(<6^k{SSlWT2TUoqY!^1&z?C zyX)F1*Aw8GPBuDNI?SZXt=`Tmx3{yE)sH;+j>uFK5n2VLBIS3_WXfBE!i9YRP;2Hb z%Zndfp^`+afgAucCgcjm3<Kmg1k|AaUt3om&-DMt3uTUKCP(g&Ymy^Z%3aaI{Bkz6 znph>rWD>~{SuJ0o<Vcg!;TR*!(Y7$@aCEtk)kI<vi!jIUJ-*-H_uKFB_3-f6Ump8> z-mlO5^?Dxf&r|u$&iUxRD1|Z*$oB*t?y_)@X~KLNmhbaOZ0#IK)|;9%!sQ!o6f$K$ zQq|!Cu#-ju@1+a}d6YdM1ytJEsd^FQ$()hYIH-kIN;%mQI;Fzi3gsVOw)`fmyMwV1 z%Ht=+U2E;Rk-T_LQ-FhV-u<GV@FTgXiYjB@au5@7%v!-+7PkSaGuSF7QbcGc3i1G@ z#bs;9t6k}@%4jBrC06sdrQR-zZ}hCFy$@M9urnhbksBgc_Gzo*V-41Us(-1lDt?8L z$L<cSRM;u#$#G`Kx3l3tr`zZJ1)W)w)d>Um@s5^_=YkOIL#hj(#hKmJK%S1Ez~a_- zs>E+5+s$Bg&JH&lV7$u}7628YWu;(nbAGTdiL-xqV=gfYu<Di63*Dg>HG}Vl@Jw1= zw8KId=vdAnjLX|qgEc0TO~~~5)3vi~;$r9o(z9!7&$NLOm6POxU#IKytSadE+m<6T zLLoO5h2qx`2W8i0l&t~cq}df3WN%#WmJA;?*yG7#YjE;7<0GGyo+mcrn9GgY2QK*5 zLq1-vkB+y?<lVR*#*a1pwvqTRH{kb2>=aaM?EM?q%-5+_jbTe{xYJxyTI419>z;+S z;%*sJYKG-~@^$cB!RuW&AP>#P2%WFYbpwYluyHUKDdFw5r+jR*?0#atnNC`MrJI?; z*GeDPC9!2OMy1(0%>Kq)F^1lenpxx~LadGjL_f((&&4b@jJ-2oHD24+0_TlG8kvGQ z)zRt~)T2VX3LC@CVRi9&-3BBy|I(a~yeK#DUH)Fnor08eBGt&kZ3a=1iDWLX_@A@| z(np9bm@MUK)h@qENU5qKJMI>F@9HbCUb9AY-qGI1ZSm!@ZATD=IYuNtN@|}F6)AzN zweE8ga%0!}zgBH~A8aeE@+3`xkeNoH63`$})#}1Qj{&R><jMGLhZmu^1TSipQ^47+ zN4MXV*V4_>TnaF`D|6Z?UEhSf=d&QxLt;i`&vm`c>-DhA0E}e112KM94kOiMj<t&d zr)aixj{W%Duy_d~bnG^}@-CFO<zWZ_do)C@uyTRd!o>F|)VZ+!MLiztt76p8RXnrW zpz|OQ`=v;|_<=`atAk&GP2Q4{M+YM&k*=|{bW4;(oD`filAu7~u~pg5;*D1v4U2%n z)CYYMvXrX5=g8Jpo#}LSk<?<~AK^<)vLdO_QYbyU)~q~Bv<ZLiO+GF!O+_55h41VT zP=gV0M?yAilG~|Oq%ShZuA9~w7EtzSw;=?BRXDs>`mz~X<d#A7eAomg8VIk^X}a~B zpcSS$@mh{%1Q0~i*0%U6T~nTN`Mip2VPe!BeHq}>c~l8HM+gIEdCv{OPK|<x^)Kty zvanJsi?xbk<Jf$us*0Qxsm3SVw%O%zt|@zt1hBJSWq3WUsi$M+V}Hb3Oal(4k{>)Y zka{)mW?_Oa?nGL%XdTfkHA~1VVf*bIzWGH4g;OAd-loaGbejd)X5g`hoI?$?C6b`A zq;SXjkpOKm^tTt!&U5`I%9!|rQ%3fu6BxGAUISn_wp7vyawWF`IT!s><1AS|E&_nL zqg|S(WG=j~rr^+$lCvO4u>e0Y(4P{>$Etf+?v*NTcYv6_bX-7H7Zai_&88c6ey8(- zV$h(nUv<<~w|q#H(jLZ5Mdi#k{h=QB(|GP&btbQrzN&VtY(qy>ujj7I*OPeXwK}+# zg9@gRym`|8@PWm)Nmf=MWBPROP+NNWF2;jRs&i0*UZ6=Yz7O{)0G<wnHX&`{D$`DP zc|TGS_=DQkkWM-7t{?kUcZr68cEY!Ok@yv&3g)sQOKnf;pyk`jUVu&}#B;%}jb8sp z9_r+A!``JKZdH~McK*Jr?k#2W(EH=xGw3okySdFq;Q%pZnA$-S#CAM;E7lKOP9R4M z6LHDw8Z-q-xFnSXKf9f*?_$3GZU#5gsJX%CRyP+Ke|`~&vU1Lcl^~y5TTO1*_*eym zT8Tdm>K|3U{OJk(Q@j}8yFx7`rlSfIS*Wv&+M&ipB_3;NN^!La{scNmU7_$fwCB|V zqtR7$)B2QzmPH<An}$`zy$@q1*~aECU-yJ}QA!;Kw$>cXF=-Ktu7XIQy+)n)%^|&p zU1lO~rz#L<BVTR11qkSdg|u0KR|RA+QbDg<b9Z@TWvF@QCI*g<Y*V*!XC4~04QX^I zT33UKTDc?Ea!BWXB2M~^^nUjH0t7#0iaWR)xEn42%`HS-l@8NWt!^e+vC!Nw0qm4{ z;?lJU2U&rm%%;ZntB**JpG$nc=|yhOHTr0muag#wOVPh2LZK7|G`Qb+47XT}s!#cJ zGUiL_evbWDJ!RnUPu9qKV;Vc|VtFQf`I1y&$uCAsS^01Yoby5Ww}(YVMHsLW!qY4E zfCFjP-i$i`=-RB7qh15c%;Zk*{BhU4n)T%;EUIQASQOv=69l`DnDbU5=OHrs!2`Qd zjEgidcQ<H`Y!$b5w|BAMk#R<n8jD;HDSsBKeS-2(83eGV(8hiMYKEJyiwSxx({=rd zlBeNa;ZGMpW|^NN=}FCCir6}dgk2dAWe_&vN`@y0G2_ja#sMA8ZH?N89z-OWi4+q^ zhf9Toyui8Z@n!>s)<*R*&*^Lp4?UxcSor2&7Mz$AIOpSUSBBY&9QKha$Z@>urB$fR zuK;9{h`LE}#dyPfR`k;NM$u$?@bnVP4bHQfge0B_jsd!DU<N`pVHPwdH*iXP2MbI0 zJ#VP@0SJ0Msr!|_C1wNhv`5b5OqH*X#b-r<NuKlW`SE1adGVhR9AIT4JvP3~ecNB0 z{e`5&WPgdg286&S_zD(?&wC*HW(1f1K<8W^E(v67G7e1NoG}*wnZ1>p0%PqgI+MhV zH^5R!;BDWSuN`5e&{I1m2jqG$epjj3zTAVGKU#a3=2%f&>{y}5`+Zygza|WGXpZQi zE|1DcS)@RsCI<HoCG3sZJBz9gEhqtwG@=8+vFfu!Sv!!ANk^2L0^IA@xhX^}Sy9|# zfGOs(K4An8ZUj&FSGRvfTTDu!r<$#75R>mzJIbMt<P#UDHE+HY^}t~$r%e62CZQK` zh}(x=17g?j-oE6*(|G)FgizQ~pVDl)f3@ucM(@+$9o-42Yw};mW=Of-t{3pUv1A%} z-L_mdTrOAhFIyXbc?9{)<C+u3z%-^JfRB4V6BSg+T&5MVkz<_|<*dFl)6UA?IELkr zeXJREuqov!-v|fNyIJQ=(T^d=-mM+9z4-Ipe%j0EethSgAIBm}0a&x{P?&cNv8@Wq zYGyrHnoL}-V{B%rCFi+kFFfoX=RMksMnWGtPO{{0o`3yrRtAs@9OL+?wgS1l1$tww zdSII@|5Lr(gs+V3?DO|)Iqb3I90mOFz{lAAVuL&f{<UX=BQ2a7l7;`OCJf`@0q;)* zR?aAiYT4V*d|zCnfMKL3si5nV?EdtMy*1>gs>pjnurZI`8B}Sw%Q|WI(@#0iBs_wD zPQb@IH~#jJs)3F+OTH4RzS7a0R0<?BBvN%3Kc<&(ZX=30FMSV0UbCp+Cb%BcHqQ40 z7%JS~Gc+j2;71{vaj_Nug=-HhOEm-hU0^s6+IvRc-Q#-GMqzO}k`B-4U9gnCfGaTv z4S3|KZ=rM#|NK3F?w9;UX$FfT&24vO@p+Lvdy(19vd&udeeak)?<hNiPxwX8=itAe z@@qk%ya(-?XF^0M;r-hqZwwHv>qLryI-$811=K{BX6muJ_%ugd_Ykwwc|U~ci%+|6 zkx-Zq`w+#^y`1*BjLbd#99qfaUX9NkPQFrHV`If}snv$gM<n^c)=fRRBYBqw{|*#5 zsZfsR1~R@aXM%mIN6>YG-|F&YAwS3cr^(CrZW_<I6tgiSY4iVd!CzMdi`tEQ@49+* z=HNle#`I3m8_zV>ns?-VSh>KBk|$a9qscWLuje<A8=yPG{$2;IK;ZjA@a7-?;{OAr zoDfU|p?f><il$OI^K4tzHoqyoWSd7TUNNMd&?qR`rNt63d!W33T{QmqDEpt9z1C*% zT@qD`B3FC#e<Wu|5eQw>i7TGNSu|QbEWoF)p@dWwK|$v%TBOb^tlW#Z9tS|GRM6;H z>N4E}Ahe2(@seW14*1yH_TnX_N*q%z{qGw7=m@^<*cZRfygv!7)hY1zzo+A^Y1t?3 l1OHd~|MJ25i29G^wZ}|pIrUCC&^6%4aj&yI+4flce*w9&Qhfjb literal 0 HcmV?d00001 diff --git a/docs/images/PCS.png b/docs/images/PCS.png new file mode 100644 index 0000000000000000000000000000000000000000..cbca6ea937cc3b993cf0f4ab82802b586d08f23e GIT binary patch literal 9582 zcmdUV`9GBX_y1J4)RZKRqU>v9Ym@9dsl;f6Y$ZhvW8c?1gt0HBtTnisYHUfiG9g>S zn=-bsOAE%5eTMnIuA%O}@6SK*`TS5GuIqYTuk$+Rd7kHa&Lzs|k{%nJ2M&Y5*!0h7 z8^d7R5ir;`&0Rae72OC~BKWb*-B?c(R?v3zJNV@<dkq5(7_2yc5B)j|_<gs_IdgXy zY+oJpZ(E}?!43u!-J!3of%dVU9@vv&a&vWM?tPNBwy0@T{+ol3AKW7_j;EZKO_6^i zZQ&DjlEWDh_O~uRlt9Rp%FFgOmk7&!Jj}+T@lIP?dq3LfFWtoGcOh<>BO4q3OH<zM zs>8?KCwjkT*tf3+k^M|xx4)ZGFrckhwpT50+`I61Qc}`vHVhVG@+=bP93YIS+6_}j z2_s=Jb)iUb#)Mt??J$_gT>>yXO5p$WWqhw+TZY1jTCWxw2D@f++#)q4r97KHE{+|1 z<6EPPfsQ*xYhdLM7>-l?LAW-G?RtLSqTJ>BN)oR&2;34&$>PHIPXi+n{CpP&8~KCZ zSX6r4p2Z`WH+4!D$D5M}YFPP?UL1Dnd*zBD6L;GjQ-<6}J9%re+uFZX&Z+P8!}o@Y z-$lwiC&{z-YlVPAi=0z?{T9A;6rgf+YqWzt9D5pOu_qe%`(1TmX1-qB(eFzX_x5Wi z)z%k2)#Zn88edwnSaiMaZnI@WVbJ0W7tHnj0E0bc{k>~*jr{SoqZ#gPyUQl{QQKf4 zfpTqRc9jLAgIr&;gM-TDNX&D-=yFuK_AW$1N~U^c)CIG_TyHwrTWLcILYdJg<Vj#X zD|5YhD|tR<KR;Khm6v(B+%j`{i{EQ%*9+5wT$zfV@UjUm=7XMT`HZ!0lJ0faR=Msl z3-<`-Ar#xmR#jfHwRrz!>Ij(vVW`MZ&ceofz!PP*Kpjw`q-{FsbIGEKsTCr;US*lW zi8a`KXVgdX%WIz^>eU#l?JgKM=H?e1UsHREZye+@RG!l=m*ZyoUsTbeW#CMpS<K-R zLX_uv%n*;3Ec$-UJQQBvB1<}o?Gl8xmK854RYnd()Q9cntj+h_e6a1-<fltY((q^y zgK&$<drZSK+Q{~qo>vZXg|f2mE4vlHd9j^5_d=7;XZUXyjMt_sS{w)RE~H9GVM*&t zE|_T!C=#h<y_I_Ld?+)D&sgjTxo>mp!jeT^Zwg1a&eyigx_mh(%Zg-YN*3S!y(6cn zd_3twZGP3JK^nIv1-0&JU+<_6q`6=gnHx#=IIh!ww(DK*_{SjKWwM*Oyzp_!Vy=EN zzUb_HlW<*r6%$c~!zGI!ADzl6av&2y$T*qN5xX_XvWE-2l7Px_!62Bp{P>Z4^X5&I zS(6zlC~yT1o>S*}n3iAW*gMK|+F^fqeUj*fyVFenKFY{vKRXNnGx6~egu#UEx9lhD z_9;oh_b^{|v7M~8{@pP2arp>73rkIY(Hi%%_sa<14w%uKkJ;NDx(hN_2`i5DtF_x< zMhnJs6?Yd2vpZlRwhwTGgm`rs5`EqwP=~RxUS|r2T>aSi4qnr86C_i;r+Th9KxW)G zMj%Ef(w*aKNAb}z@G`D_kj;6Yb;4J=NgIgpa7#hsbDIxxBWypU97CB+y<Hx}*5eQ( zlB+tvZlhzRD8Va**3&%l*rWCJG2EwWP3Iw`J~n=yQ;X?;?R1b!STAnxCi>O${5TM! zeVD@7+R-e3D#!^w=7xTp2%+kb68Eod0Md}p3Ftz+W(>cYDm?nKp-Pt%rTj#Is5}%m zWLFho|9rUzDdZ<@h*6y`?`*wtetz>#3t_)a;G#*x_O{)eVqt|MP})B>ej5vytqyT- zN)Q|&k3)%xe!h$n9KQo{(0kC=ehcyUaYD%V|9PSXkh8HiS(op}JT^`Y8Ag0DyXUNu z$G71JGFCj*#@?GZkjVFX{DB9hhf^XF4bsm@2jpRyMj))vk)@dK$~a!7oxz35F&Eu2 z&LE;8=XJOd*2~m^P?AN%4tC}J*w#&7<Ky5Rq+o`Gl;6@6H#T2o^I3j`ZBNnlj_qwN zGF2b*&5DHr@@_Hrjl}&2;M20@fpq9hSEVOL-gWf-?EL`<yaa9ZdnvP`cUCSnEH%sh zn8LRdkO_6B%<MIaBCPO~QQR)fs@!aHs%~j%sWbIr1~7_1XqX+T8(<Hb4ITC`!*sV9 zWUHzKh(a(|7scDkPqbxDwyDylhH3IneV^I*l+Om_F|jR*$8(JvU+!h)R`FZdRd$6L zIBoRjB;|xD{~?-nk*wR2CU#kx=@$-!`9nF(1EsN;Q+L-D7XG6(P|~iN&VjhnXg@}- zykGLd#t{xvKM;wNa_WEG3iw>QN1WS6KFZ?g0WKJ9`~V827rK+pjrFL@yY5TFTo9Kw z$>B9eGQ9_zAC@=9@gAwRt!qG7yugo|03Rk;XonjsBkj~?s%EM|Y3MIc0$><tM?E<h zj|*Jt74PX*qmQs-Thru5Ob<e#XcEV39^*qeSFiqq`Sg!L5otdA@;?`Mlb#<RMa><9 z9yq~#K(o!rgGy28vG>hb%ZXRzag+^ngErLD4)1J3ji}7N+d;J$TDwv-19+NEMyFLC zx@!o`@k9xVU3@rvwG7KUMWURZ1evtQrkQ=~b|)3DNwlo!^!)Mp*b4X3P;jt3s3^1d zDJ_w>Vi0?QvPgJd8ooC9VUIIu{cd)iR>VGRLk#zbWW{A`U66_(?Tnr~p?B?$`q`!= zyW*R6`gYP!|EmD;Apt_jl$TNP!eGV*vo5xKQY*eze*g3|Vlzp`IZ;p0sf7LD-0l!b z&z3YBlu&_vv-hElVXptdgRmwAty8T1rxElR`|Lok{YUg6B3{)-OWe-UY|51Xl5}}h zVR_Ks*?W1wJEHL0ucb+m@IvRI>H>|>oi**WNgGC=L8hV{$e5FO+r5xyrGaOg3HurA zGr<GTo@VjTKe8P;;{n*pbmjcg2UAc3Lg<3Xl%zQL4B5h&EeOj!-CtJtsjeA7OI?)% zalQfv7c5&<T^&yj&9=!Bc5CGI4lDfpJFKZF!PnS<AAXBJ5SgV3ESbsThWl&=pj=}H zrXZ)*f3eGSAWA&z@S8*a)QYE7>r4G0a}LGhjG>2afaq1@HPL8vd6tU5uD$dnrRi7K zuG@PeAp`h;0jn`^XP`Q$VVswC4W_Cr_0-)@NeL^ogK`3L5CX8v+Tx@YV1S$wF7Zr{ zB>#=ouXU!9H?`{}e??bQCtO^xqtbIyLZ;x&{CRnADrLA7*9F}U2Eo_V3zv|UW#__D z0j6vGyI$S?H2g^DNXu);&u@T#q_o4AH)u0emogP~?4=dGR-_^49>Hri8>4-4bYtB> zYI&-u5>2``VlDZqf$7-&i1S=Ino~W+bt)&X88vK}^GXi(e<Mo|9;GV41oFYIE8`9Z z0Z;x}ET*~xS9Hb^jBtiAWHfQ`L2>W{C=I{sp(X0Ybuq|lA`aJ?+WlAm&V5I}?Nb;} z7*=uW%#E4^q3VBAah!8)RGzFyE5mYtMYqACRejVwIh#WW+qu#D0!(*74GpP9ZBwv) zA357aH$M=KD+MRd<wHFg7uVq?qYohl0rgQ7zGiUN*MCX1q26juLsX~vUl41=kDl7H zZ9W;l7jp*(pDAwSbJsiSsy(YJkEQf1e*Yw1{^UvlK#~y&oH@ui<+_1Wj%LdJ`xWWf z%40sn$~Qv*G#UPD-=Ef*y5DF{FD9&{5MUv%gpn!qT#33gAG8!v5c%fW<)@X=vejpO z+HYF=eb1u~cn`7JFxA!Ko-IoqaeDRN`gFqOJ-!)rKR0<HAyet`J;}#XDif4j%=sud z?3@yai6QPJv3J2_AV<@&r>F+Nr96~f^{lvSvB!sd4h(V%7G4JYjUyN_&-4m4B5hT9 z8r)vUH$zK_AYlU2k#JG9V;_pdo)Kn~;vn7d<IvW7^%aqCaz|}@KR+j|+}ZZ0zd@!L z9ytUY`&m{yJSqF&O|#@l!t4*8L)@qn*?*olKqoxa$x_Nc9b8-s+p^*$el(Aw7jD{L z4ut39Ab>fhZwxSSPK33A>s<XSu;D!CpTU6hBCI`K=Qh3>=B$G<C9u9_b;EhIk5Z$~ z%+OH!9DrSPL!rB*{nw3W`LF~pkZu9<#SK@{KB_WnR*d$T<@Wg%M@pZ|%r+R%ohhT7 z@p4ykYAt5hJ}_@hL6m<-6T%@MhNxFR|NThLy8raEG78Hf%l&j`=^NRBORlCifu-qZ zU2RvoR?A$!kR2Exc?sN5(0IAYcG~sPJ99<{o)gU0Q94D_psu(MRC#-Y0ujA^?Bl6+ z4<L`j`d=L*MJtSL76duKs`Ompy0liz3%sqyd3>!!>7DyW&bmBi>YhW=7O(e`Z9k^V z%hI1ykmBI%l90<i?96VcB5%FN+hT8_-^cQ)^jQV1e!;e@Ebk3E#B;{+TM&abROLF> z5N?xr1O&<s@cMjm++OHlI5RY{&j9V?KJn4@t^cxDYr1@Vn>BqtmE;kxx<=?Px~{ci z(%igRF+MY+1{QwQtN&<*{`gD*`38rBFRzTnvtpzJEa|fmY97I0vw;Zypu<7;t$n!x zQhEipPPN8^a7`97aO<{okHvK6>d*RjKGxXbU5_v=PqhhBpyMi`a4P+Kq`_#N`UuZx zxN`?yhYC2#EB|UKuFX0lV7{3O8aa<Whh+AWkV=0Z3E+t(8inGU9(vB6T*bBogvcqX zuizeKNN@4^j&qdRH7Cu!xC82&I_M8X)xI|s-TJB6k1BS%VuDTyOrV#@jb|My8}xgj zw6QXl^UmQjA+ZWbf68!8sFk_7`O1A8Sz%-YU`QiQC^r;O5|1qrBK^l=<tYa81LJY3 zYu_Y}?*mf&+Il^ZnqSBT19Cjfl9Rx;wcrFlqT~i@E@&fbyJ8UCr#s(5z8kL-4VEc> z6Y%abF|9}x*3<Q-LOJ=%9a`wm7qLXo0nhFVEq0aD@V%?{y=OMUyK~khMM381{_>g% zQbdHlp?~dQQbuM%$w9Z*nr&B`W+)wMj=a;^Uy2>*m3K+OFad~%YX*4mc&uGuII-lL zt5%@{gBai5;3~$VJ_72`+>R=_N2ocI@~(a68Q+%;xty+EF0Q;|5WZNG)4R<~9i#^P z6xq?bOr@`krJWPei__EjE{O^Cw`_VV13b7fa_giWTSH!|HIK51CumAWvfJLS<n#iv z;sSiR@mL1Hd@@$AKBAc5(;kF=-)yD$1)F)u+UJQ9P&_&B5(MKNQlAn&gtkFdc-BxP z{wZO5(LDfNR!?s7`yAWq8bX4FJ8eC=3Uf7?8_`v$e@s@^`$j{I>s!A?IF^l%eJ^+8 zQTL0p0ZHQ70iDt|)ynkCkO~Kr1kqrl)a$KWlc*EoT!>Th_bjFfW>%$Qc?)0qWIe3j z_!QHYNsMVlZ|YRs+0jTVp)pW~U4Z=Zl&xOD_m>w_)#S@KSg)~xTxb7r641B@C{`Be zDaWO$UTQUs>JEDOYE0j&+q&1LK;fX~CSP)6iskoRjsQAfK?+^N>Yki-_$6ah@u?`* zRYESPrQClDj`a_1yv7VwzpVngX8>w{)aIc6lDy?Ko=H@(AJzmdm5owHafmO!_gU(- zA1Lj%PIv8hQG=SMjOGNT09E>I9rnlPXEi+gG|;f$ZUdy`uC4QW6jgj&4^>>!+1WY# zoWnQix$>;z*QQymg5#?fQnNZX0_n9MW}RUnwZH7NICD527jKK2D|k!j0fM(<H42w0 zZB`^u9$2niYelv@8niNkGCTS+XAHkyqFf$()<~HNu}?gBP5V!#;qkaaVg5%=Ig|+c zq*}*@IX^}BsKh=%%k+1*V?pD2mJ9JI3g=kQ---=%X*7I%794kO$5T0S&S;AnIzR($ zmoLPH=u%00OC)|YczC>KAegaE^(N6Wm6m#LgtnNi>q#iF`{w)poTx!aygd5~DASro z*^*nWZj<EvJq&VR)R1mQy8E{Jzaaz}aFZX#<9q@1A_z@nDpuH<v%<RpbZY}3hYw1@ zRjB1-6rg-a7wo2#t7!u>m7Ipk9adhwHw(OH2B|>T?NY@he#KA4C<Se=hxinFWlucL z061^1?VigEUT)N!@j4FogJ}J>4>UjnZ2YPekiAwlRvLy%)2F?Au18ECIII+ZkL^e$ zKVzkl3Z_VG)WeG7jOXNll(^z$8moXW$Z9nQP>_X@y4*21LtE5|)@x|uv1&q3CV&eI z`?(`ZUPS+IPa-I>@`Hz!jq*)iT)_?nE)R&FjB}b}P%^|#b!ZNrO+v;6m$oHoKuLRv z?AUt_?T{;pgp-0LuMl@(+vFU3j(3+i+bl0*MWNVOW^NY=1+t9)A+eYbVbfZO!`*ZS zDgL36S50ozoBm3*T#@D6PSE<O9XHoP16i)fUB*#3@#CO#@5`IiR{0?ht$TZ2%LcsC zY17WZM<`kJ$D#Xhs+XQ&1HLK^xvJ56+buzd6>9%{FVATSpK4qHy5zdnBFR)rge3_Q za-m6kF`!F|swbH3kH$S~$Qjka3t7z396ldJR0+pNFor|fDSKq!4DZ}~cz9!_QLPd* zfBn3^<B8b9w@ZDZC%yP+(`7bAAqz35+FZa8%q^JKKLoX}1Cs4;u9ODfn0_0q&I5RE z<FQCxTE2Gphlx^?<fZL+A&kC`j)5wJ?!LS>Sy%<eh{`@;bU<T2f;N6;R{`$*9QZSR zh$4EDzKbhqU%utJwe0?e%3G{*dt~zOzc4MRnBeJtYRJFbb0faO)Y@0H+_3S(ePtUK z!fuEx(oRAy#c*BGsqZX{#5tP#oN1<ho|v#)71(ob$bUvf9?TktuRDo~ic){PDD>)P z6ihOf@=qeOkiMQ}@+?2K+G3i%l+O3~RgfYq75zbxFNfI8AmeODAbqY8yS}zK;=L0G z`cmd*fSEq(>8MmIn5w?-2Cy<8<C4BQKIk`@Ka5&nS6#X0a^tvpzbg=_to)^?Z+F_I zHW9E*-5;_O)g*%>=vMRIABLodw5q$w`4)95+kUWv62_lmXO_%?5N6ZWxh;kKXFsA> z2<dT>D=992V58Z5m%<T2d(rW!u#CKf5`-IBv(386Jf@HMb5@IL)CVRE-faqB|FSn6 zm%?QjB$goEymZ=L!fpet#f<vv2Nv<T){YJ7Oxu|hS6%cQb+lbe0D9b|HG)V=@I3sI zPm6rBX>G6hQ^83&y8&INf;)3s<nX4o{pRAGPqbLQzuY&i<Wuo02Q7`#N|jzL4}yXW z1cPPl>in0CZ5kR|G3WV-ngiAko<5A2jD*MHx=d)McZMe{m0G$rJAX9sp1+y+z2BL{ ztNhBK;9R2Q<#9No!dR!kEK$<bD=wyQuWwvSe9%J9uyKD$o1)~(u751bur&tF<5+^Q zZp<#e)8Zo~K6AFFC=>@3@mOo?a6oYN0j({FeAy6q+Jh)1k{?CEXi+N!mj@H%xZ{=Q z&&^tLRTxw%`(9}a0$zI{ZLxECsz>4Y9VNi>{N7E15r6SFX82A#stHuXmXGZ8p3E=X zIjJ#z>6u%!m+zU6PqTy47B6E^N0}uq={iKMQe22+K&>1IMY38}hgs<zlcJ>?VDv_< zKV-8vON<sDOcy@ODTI-isr)A74d&bBU<%PEhapS7@D!L648F8MKhbz}?2^hN+Iz14 zP?d~T<zGWzp&|zcuU@im7mSO}n$(`-GmBV@g@{m;8`LUA?eKl5L>ae<C$C<eKFcX+ zFEaiyEaORnQpN}FJqqrE_Q&lEB8hVjl=3;5L{z$9Dixa9)^we4>qf8o=yFwlxS9yf zD>V|D9vxmCberK=CFqj>X{t<objrSR_2<_rP>Jte@Q#HfvxfdXxrrQG6bNV0VT8%d z(A}>fy~#O3W2!vbI&VQ+D+XlW0eSGfWf=F+KFha31(Zi>o6?L&@M??A-9<sSn=OFT zzg>OhFp_r0sq%uIL&W=7sQ@SN<zcqNpvr4{*Zu9kb^^pse5>zjC57a&h`}v3<lMbr zZ9<e4$uE5EJj7?o`?EujpQYVDvDr$@_tDhN&eUcbA$41Iy!xoRkcO=WUSm{42wz}- z{?4h>PlUX^?`L1&8vbC;Uvb(DdrA%J(1isQj)*KDGY4NUTuS2t(50X+6>zYtnF4U2 zfH7dLw`AZ}d|SzI&^!1_AvZ9x$k(6)0HSDEl?RHn#&naNls)&jV`zqFLJ2#UmT13V z>H&E`^=9glrrVm$`6>#Vq0b>w1jrkqC2D%Sp6H@86M(op#WP&)LPM+B;w0ju#Pq^a z=OI;}D{Wv}|5fJAZ0)dpYW&NB@=@HiCo|AD0b*zcm~jqdGw5H3_a<Au4EWh9&sz32 z)&Hp-rvg;NB$|N)`41qYNO<mjF|^&uRDCNk??>Y|U#9BYhy_Q%qP9hCkJ=ISR}@Rs z&M4NX$N`nYfA(vUKkrBQj<cUXNd%HPItm_()?wMB|2MIzQ5(!@_hofTMmvDPbj$FK zoSQ8VSeCgGTl_@*#*x|VYV_mfUz>n@qJZe%eGw!QW|!Gg?m9+!c;d$07cO8{TrvD| z9Hfh4x$snipcdt^M(Ev^lrI~i2QDlR1(PO+NTkW`LK_zw&NlS;Bj^BPCaAf}If74{ z58B1^JeioSzpXQJ3-CaWX4MePNOl)q1!t46GrEe9VuH)~ng}98#($L=CjgzB<y~<x zgooN_yJ*NE|K5xt_}n8jaiN|7Y6WEww;f_|aPr>QxAk5*i{;n?wh}vl=zSUFF7tDb ze(ayyLj@Rh;=^#R6Me!`o5d*LSNbm!dWwihB$vVQ!-ykJdMv4Le(Xo6gXuO9z)9DE zd<E4z_jYSU{kMP50)&w)P<m<8gq1KtQ`#b-C`gRuobVR$g9VPId<e@-Fuj5`L$eGh z`@rtC)@VmdYXl-YR-O;Blb<)cfN;D#Seqr`?AFQ>rxIWe&-9S}ST_*dO+FsVs6@G+ zrcV#6C2!B=*g7r<v?P!@afGG^i-c>ftiR6!j7@${xF&d;90}hPMj$2)0cc{3PW=m@ zY0Jk=8rOLB|33XIPsurWWiCYa)p&TQp|4zUGX_TvFpJ?6i2dc9Re}U)FwH_y9R337 z^@QOhQ{G8?<B;Dkm?Nw_Bs5)pj=vk8YcBjpsHW!#hq1?zSL&f@W1=)y(hsxvf8X1> zB>g%EFQkJy5f9wA8lL-y4?v%O#Z(70N=tZK3uWZq!3kvpR81N?Q}04j1jyyawUWz3 zJ)P%VNjwy_KdoJP`C~#WPqx2mHDMJv;u&r+-u_=}A;Nu9*LX^Ojw#wfP{=v9pG-|q z#V)6Tk<fd=&EJv-z%32(v0kISlt>`?+Jad;e2m8WI}W|oT|Q{y2|h%_%(=?^+LcEs zE4i(Y4nCG(_8~wsp>^sn0JpFB=z^~^zeO9Ua1*84;XoVSSicBQfZ9@K?iiqoham|^ z&Z(uRv5$4^_`MMb_+%$1f~zp=1Suiq)G_srU-m!4;SNpdgfCujQ%J@q`-+8weL&yI zlnJ2EKL!PEVd3tfDc;XfaNeJ&>j8{^-O*px8;6rFCOl*Sl;s27=-6?PWebU%pqGin z5%Z2ABeSMB{>_KheUqr`^o~#DnR6c=9sK{npdB8!7+wJVzrN#l+CKz7i_a26daU^D zlu+F|Yl9!!Ecm<#2nKN1$}e|)Bovhele6C@JSPbFy}T9phpB)S_#xNK{Hy`H;<ulJ zCX~$7FMfN6aZxvXu3yB0B$9gSm?D6Z^41}4s31qn^j{xFkh^n%9e7p=P;;5i21#+4 zv}y!!`>i?cPjdlHOyt}>bqx9EYgCajHl6l?PcUh1x%*YrU7=|Wl+w^qm)rf&;M#9Q zaVL)+_ovwhE(ZS3mrwO*pdA2rpfmLa{X%Si1?r<-_+0xd5TCXM*k+>y^Z}qt8B}6v zjDE*3O%MIeZ0KK{$ITHU8R__Xnv|K^r@GvH@GbKf%P1Vf!ISr_5=p^x`ibi;Jg99V z@tgcRk$c<tba_HMotBDU7xoJo-P+xKG&!zj{S?C)*C6hM*K1tc*mfJt&UIMx7;Mo} zGd2yRX27U77@#Z(xPoTX!)R@&sA*v%Z}@Rm+H(AQOBQgSF(CPuK}P3WH#iWUwHx0d zYn?!I3qGGxAF($6#kk$knEU`u9ip9CcFqfC#88K-WCQ7>b^rPmn!Psz8O#7Cdj&HF zea6^Kjg3dWn(V`M!2r2&YNIt<ZD?U*cMDD4cYd6>98WkG@?|}laaqoJP?_$0#yp5I z{&=v!s%n<h`>K)8|Dh_O%%P)pL1SQ^CQb?_t<=k2Bn7kaoObCib7p6xOV87~U*5b> zLKBxF1s_1n(^4U$cMCvumlv-Yu~~v~+Xaw6;<n21ugmbT|Gp4HAb_dz)|$=b68r!A z0t}C*{`qe39A5puFTf(9(cYgn{5XnmYdoV+bn5WlouM_??3A!o)2{`B6fP&iT4;@r z09w%BT>jCFIE7Hmc=n%>vH0yw?eNQ3kI4T8X8<-NDkWVNWjuZPCb)Kfqgf+!xscj9 zOM}|KPbk5e>@S2O`bIPOxz71u*$^+(56!FpFZ|(-@d@aUZ^9UV!C=JEgWyk#&V{%$ Z_$`P%dEqV<ir{yczRo4>0?li8{~tBR$+`dl literal 0 HcmV?d00001 diff --git a/docs/images/Untitled.png b/docs/images/Untitled.png new file mode 100644 index 0000000000000000000000000000000000000000..4ac5a8f47e8e2f4126421168a83d8e445a506729 GIT binary patch literal 6025 zcmaKw2Rxf=-^b%<tH*4sR;>;-i=))m7*$1yl2WS_6<aB4C8*-mYEgScYR6uowW@0G zEs4?A4pBiUl6XVUdEWCp&-;1vN$%X^%60wk|8?Ep|1ZDS2Krh|^q1%X005Kry*q{g zz-c6P-}dYo>ejzQu95mh^W0EN9Z)vFvr0WU1yR#e0{|-DFp!>{rXK(P?4Id!0D!se z_(Rj_UT6mZaPVp0Q3Lxv#?SOSTP&mLz6Q*;w6=dWRFb?`>0ILzb&;!aMSY^Db?fR| zPBzi=XXDs+ks=+rrsz}Mr=r<5t?8=X-p`21&5Huw8OGH62so_o-b(oyG!!t<$K|-A zAg#s!{QC!q6kLY1p=@{g;P&+LzHq6)Zw_WfU?k}xuR|tD6}Gj#W+;(t>+37ukaN%O z_pJo}E)Xoc@~9j38#QWxs<|+j_IPK=7)1$YH!Y*x?`ByL0#?ZVtF4qYlIFODgP1gu zWooUHzjG>-V?4bL-oDT!<dN%dQh5L!B&I05Pz*@(4UlsqZR#oeC(LvbR)E_N11YV; z>sg`S#T^b820-75+YKH+o+Kf}o0qM-K!*#xgT;>mEn-*cstGp(Jl8j^Eq-q5WGKE< z`TB`^d9i00E1>m;a%mJ~Rk9=;&jWq8u#&-38+M}>)QocI|4x20Zx){yDNe~E3jy&7 zLcpj!(Dl?J3%3zq4JRDl<tBe_YxH)5W6)z@%Oxw|{SFPB2i@mr9PRF$Rh4z_Y#{4i z7GzRMTis*T9vY`eyvnB{&!5cK(zEexCRq&V&fgJJWF#e9Eu}GJYBo4nTo3fVT{g~E zWF$G)*HN2pVk^}Up+BM%+q3Ao)uJ5>yXOhE%GJNFa6nn=^f+?$Vd1@MVpS%{#ahZ< zgrLQX0*AhBEeS!<(y~U>c1?e3wU9C_t0ylau?th*<`dy>_-11!6N~Wzv>7}7dj6@+ z#C@zy9|`~1VxuUKOOpQ`8^elx|FRJDaNkuqvh}CKihrP&e85@Wl0*{No`G>j7nA9P ztxiIqQ+D6KW1a|%g~cA(DIj;hvD<FlC%TWS4J0gk-hnukitDIEb4you4+?-(Y8lla zPAb6exr`#>^2BX>qtVx9J)p(Yj{XmTf;zY1g5-~s{$kh^H~l!?b4zlZCMZWv!Tsnw zs7g+bT;QzB8rxAs8T|fe(O;IbswbM6k0uGk25wsRMO(anE;QSlr5fR^2-KRN?t0OE zIUkjacOZSs{SE-jWaf+#{E~7oTO-$mDDQ~hvO{Z!l69M48T!iic1YI;j`Fw8Dw;&? z)8J~}!rO!LB=3!Ks9251yuJ_-56i@3cVpDO(;G?GzfZ5W_7G#;J!dIO=A!<}Fcbb) z8b88jo~?lOmg%PK<o1iKZoZIN%~mVuf#-O&;M|Q5eW1ipzLm@3Pgn3WKR;HLuUK2m z+RQnv$oOHhlUW8jhms4B@S->K;cO~ig-hGpe^5-ZbL3=Ci?p6Cqwb;cM>SAv^MgXS z0@gP1#^3Rgb8g!mOXKD-jJ$<;B*5B256BXN--LL~dOlFJ998h=lyjm@mmDP{6SP*J zM8aXqe`qS28*%CE`IR?MukwGqP=I6!nTZaYZTwS9dZ6KbXl)8S86>y<0N<Ad%`=!W zrsgkVTwK{KbNoyf%fh4+Y$TLT@?o-NC*kKx8?nGn1A<Y|YHMplkF$@oT@0$nQ3tS? zN39U&TRQd}Jw7oQPGx^+o-TU6wwIU1gQV!;7OR6eHHHysU4vM7!g+)7%B(eKNDSjc zh%Gk!#gQ<$4vPSNSNH$JrcF+vmk@+yw7=1kZ+k0~-#Q_Gds~$K2fUn}{sLLUKIAhp z-_uL+_8juwTlV7q4#eoKt|45KQTLuLy6078kL+dVLAMp!ks{CNu-J?)iXd@mjxe`= zK~X=4H0D|tu(MaNHgHLSm5i>PVcLyQ_of+RzI%Ue!Np0Kne4vXv8_oeXf|j%@PV|= zjt@QY>0_zLvENEyFDfpuEYNfk`qFl{6s55ic}nU2onU>0B;7H?CS71Cv3uz<AAuK< zQP~@M13T5YoQK}-9wVFJWP!%W!`e_^<|7eGwt=1yRs{HI;L-wwKoQY&a<EJ1N$g$h zx$-PIzpR6NpivwTDL!oa@$Ag+UeUam_c2&@u<`W_g~#NrO-N$i6h=@HqYwR1!emw= zR@DT9$>lq{8VqtBHjkoxco;Hcf%$XSAKw-(=gazeK&UImUP(KNiQ)U$hqc5-TFE&( zU9@p#>~`(IqYGKM__}QZwDj3C%xy#k6n0^-yo}HKA@<|ttj9fBrk+gL<${gPFJE#} zaq(-lZ%C^Bv3P@z?VWx5wd>O)LGG`2c$B0|?g3u&N}pOUe8BC6UozvCkxkI^jcTnA z-0)hYS48XYD-aKB$%W-JeK+5^0=?J!Oi&urLiFQd4@}<b^BndEpdWsTV`(mSnS$L= zNvsi65r?g0ah)=#gu;UFF3|b7r}OY02$Th-F$Oc2Lz5MgcIG95{3XkRth<H5j!~Ce zj4|2s=+<W@jlyA(ycjsEi6|s$r@XkG_YLI=w4Mw$)3%#bW!1?uTr5~oU0a~rN`PA> zd#%0s_U+qx?A5sI)CzSOxF6EdS9n}~0okQ}h2iXe4D|m`X$o^XZVABXAT9v_yN~=+ zu2M^y^1q!00D@75fA@ItubNgoqI0$3Oqzjcq9{<4&P)jS7Eby!`}V&>`1=Q9$9+!O zE_y07Pzz`p!oX5~TgpuI;jRP{dUv_HJXr8XryYD<)p^3R`r!O!ht?&=yxg-}$liCm zXD_AmTTY%Sh2E{z94cAtUctUaG<Pqq>oP~Gd&hy*J!G@=Z#<Np1Oatfo20yrTba@f zSF^o4f2#Yi$UKF~bn6XHQ|W$F?t=Dwjyyn5M_LB@r1S_?b<@NTW*h?WG|g&E*;)3_ zsgnx;$ROkdlbrAd_~&A0s@y~H;-Fp4q5x(8r3uJN_al>CZk~%_xZhG+Wce7HSUn0P z&RW{Ou(`ULtw)C5Z0ro-&6V^Y(ARW7crPSgMWe@EpXl|)ZJf#WjGN~5yGB6KDmB&- z#!~*Sv8^2$*hokydw*vwA&fJ%ft9052vFgkBs6a`vXNW+>fp+GJT*z2+k|=WogZPX zkB*x2#m-3X+`VzXvm}JsrQG>Omhb%U0r`iyjxGS6#{J=Hsd1(A$!rV&c|dRVXyv(U zgfKJpE5cxo_AL-WW`B5_vSjVmG?zg7p{{I>oTdE)GxxV=;q7vT$%IEl<h=N<&$+G2 zKn>uBQInJh#HDS47cj-rE2Wef9pDeT`(pRiu3@1>WF7<|08qUGra!G6<odk|%7hT% zW;RkzKPCJmk)`Hp_i#Jm5$FDA2EMMRS2`NjFz*em<ms5x##p5q2+#I!n{T2*)o%d| zgv2gBqMQ+5iL4YNM*IM?7=Z<X+54=b2w`z4)oQ{uZeNWpxxwVV7%;=+Ku37y4b7)l zR>!=)WF9c~w|9N^^%67Ymk-0eU%AcYLwh=VW=X5THt>qdtyvMm+d0*Dy^EaMkUC4F zE5RL0wl$u@s6^!olQVAp*YO7avM8Uks7c<$96#C8C9XevSqGw=>B4X?{XVu2Z}tN7 z8cg;&w7Hi66>pM+4zJEsTH9^BemYq}CrS%10H(gCjp;k$Tn$%Xn4j_PEgR)1=x!^j zP7J74M?5s8(N{VZ)2;o4nsv=dYm36hlGK@Vv6zkx4jY4EKrl3(y{Ms+<NXU8k&=($ zO%F_UFx$-<-?HPxQR0tGO(VT-nn(9N+^E$XLb~YE;?J#Ti=7c`uZL*cOce7;%(4Dp z7z&}zL3A1Cp^ZT1-E$mkveFh=jgKr};uo9&yS=0pr#Q?v_aWpy=Zp-t8k3wJnalFR z)SD@o3|1L>VXGvAej)1^v3|%L<Hhv&p1+Hc2kQ2n?w`Vzj!wGBP!lt4E07V7Hm8$N zyGh>RE3=oD0;?l!?^Z7MZQ1R37tnojMZCD0l;w*yI<;kVXH`|u{BcvFmtZ=L{*^9J zh%2r|bGjL-bPy3yt8!XEw}svGa4d&c^uoSKp*ZG>ZT9y#_;1+vS%2Jw+yW^HgEgXL zB&gV+YHiv8jih68krwDKRTJq>kmQ<Yz;wK$YA!-m+MoEul6%o?R5&sI7o2q7@OV!P z0|4s?Y@K^2{D`!?&P<ivU!wnF8?q+8t4!oiLy^oCzHe4cHTox%Y>Knjj=jw9dY-D< zsZm@E<r+U3w<eLgJda<$0thIvkbsy_!;t<rl2Nb!V&*S8hU+ESR+V4OGZdk+Oe?1E zjWH}}8zPfN*7{VAHFGlt>d^^TD|11KLGZu>!Q^VmkXzn<&bJ_&64-}9E>S-BfwB5E z>6Daa9vAm0S)JR~(qT@8CXUJ<scX8yUEBTsjnXeYI^<<zM!UJs4KBZ!h6y@+e(k&w zBwgbDzbJ*<uD$^3_*gXua7q%A6vTtwcXsVrgmaHeL}X}UIWP%jJIaxSqu5K_wGkZ< zH6B&-8RZ{M4&}}D4zD(nGK9aeYpnTWw)7DbH+6>e6lpIzD*Fq?tLd28(Wc2h6I*qe zL5k5bPDkoQ=fhl-KY^-VcmyKin+}3bRV41$CoMd++t9b@$^tYbqiok0oM=7#u0pw~ zurt)iW?jz*=1bBkr5$;Q#s_~{JP2g8h^<LA^+ml?0T|Mc8;ss!2Q?BSR7RmyA6B#e zrr5fg#&!<G)@fdq4&dV`N0x#rIDGzG{m3f*aU|q}v1eO@9^z6kv~mnQ=&WF0kTAEV z!Zm|twdU?kAnX;*rqoNb>(I2DNF-N_!4j9WavE-G?C2LZ5jL=TLHDhgFLBi?pKn@2 zCFl%l%BL%Hy;kTwXU!YtG$qX-HES6puWmKv78(0cq%coxT0*W46af0N-l0))AebP* zW01(`AQ9X7xr-yxz9OfQT*(w6VvlV#b=1;ApLC8&E}MOfWGfyG92?m4$Y*oOHDC&O z@^u1(IE#k3<tiFDZQW4tjj%gio1YYHuREKce{Ew7;vjLCy(0$;phGT|xBq-;Dp!$X zN$mV+v#w2^8_*o|eUaj;3Yj_?Ann1-RiR-lcOuh;(a_~ZTG<DM;n17U#8kv@tLW<I zr48H!VtD5nnxrbn`WQnt3SFKyIVL&y{5k&Fs}I*SOrX;7W<zy18~rCFiCh^{pU93G z;lfPrEc#C3PiBj{n3LWID900qbxM@|3>CPYudDdY_VP^KL0sC^n{W&`NC=OJtyD&H zKnmh3d!`d6P(p86r)EiS;=YJ-_2yP9IqM=vIn=w`ykzw~-HFUDkdrA?>~o`-C$mmr za7ll14=8iiv*|uw`Xop{Ug2K#^qI;JrJcyww^XT02NKuZZeaCl{~A^kiXvQG$2^Hv zAv6PqS5Z>~)=!^`j8y7H=N@vG)x1?;?%CXY=A#*K61i5vuM7n@<rpxPrtz2dJzg`P zsi^S(IdFh>(I@1!34ADID|(^q>tqCr|JMIC4A**<ctr;$nVITZObbXGRS$A8GMC}c zNjDZ8qoCvjC7fUT?%kR>eq1KJnC>oG4*YB<LilcgI@-PbGD54KP*+W%_NB<?+|fjz z#*u_sBO^%lq4;hL&NTDV5Sy)4bP3sQag=vn>bx#>{A&WC`(7&MHspy@Xb8Eh#YP<X z8Y41=W<Qe%if@hkkeC@Y3#dR6DN|<VGUw`+P={Fdx~i8}#q5W+2cAPExF=1uZBP?w z!<iaI<NGe5-a2Bd{txJ{lYyo0f^M~gXJ)g7mM$U~v|*8Y$8T%*T+@%xLlhoJuVW5& z!MwLgfZLq-8j)&<kHN2Ux<>L4kZY@{XqKAng@Ueyf|Uij-MeYmsbzMAoh=hp`0Er^ zcG^@B>1wR~wtgII4wUGtiEb7EK41JL72v^S`@7yWeo_B2L`H6;K498+i24Qi0?vP^ zQ;Ey&9)EHFcpQb7fi;@HDuNNC{onoy{Xe<9Ug`NE!;<Q&^c(!ABt21>|Hfs}Qh_RG z`uAYbhp+<^+R~F-Jx)UWwJt65Q@>Pkd$xh4>gNZHR0pKJwxC<{#F6=U@Qk4xJ{J?f z((+o%JwE+ROD~0b(+(MMlggj<Jfkf3^G|oF)<bLk=C?$7Z{dJXAqnvB4k?H_?QlNw zt$cX%qkaPct^?ujAq6g{1{qz?F<AfZqG8k?P#?CZNnF~5NGWV-^Ayc`e5%oG9})%@ z&$%Ol9Hedo<7S>wbI+OP`oG?bqd4Nb?+$!l^!CwL2cJQ;_>=T65O<$Urzo=7N}I-A zav1r)JQg}sg564lfCf<$2aZSlaEI~i&Drm%KF_kU6f>m#L~}0+Z7WT^I2Pr*(>sX1 z<s}&A)U`_7cAtO1*rBB{IiJ&p*2vcG%n4d~+(&Yi+Mh1&9dfx3ge6+injb1q5}rC# z#Ut8Nl%FdfZfGj|NoZ&q98)$DPmL^94<?w3D_T73Fi|O8OPR)Wx;QyxZ@rXhD&%Lq z4hJPPTOJLF1%I_HFkn*P-T&H<!u8?8vVLQ-3QgK`nSq$VWJVh&T}*5TzrHB5>b8F8 zvT3-JIV+C>p+G*#lD0p9ET8H7c4c2T<4AAuJYc=}Ka7s%O!4WJXVk@0GZPeKYVHZ8 z`WQ5&_x6e@g4i<)zB}VAzQOpWCT=U>JuJMne%hMF+1go>KjRHT67&#g#NWwO?4KPH zK^VkPHd@}zkARclI^ks<@Bi-A^j|)O!{@g82i#+UsT(Gl$~r7Yq#dOQ5p|=HrrBai z--C#<FGV;FYq=AHVtGE^bvj!_67DvYgGp7%Hega!%A*r|jFf1IohJ-Oz)Reo0&0X+ z?h_)4nT=ivHo{1gKW~dO`>N4@$WW|<S>d`7gT{5){`>3v1jU9kvc8AUZ~lf<oOlk! zH^w1a*H>Lg+kQU3^WLLYL|H$!sJ%fGhSRSpSESVteg*T}rSzv9D>3&o)H(V12Firr zkBb*j%{*H)?r*n2_@e4)Y{pLki5)vRcM9)OzeETVa}!6g5RpXjn(?~^c@J!W5hswR z6qBhk$u;gDUV>YR*tsvBB)BQ{c@0BZs!{LH>n2sKF;9Od8%2)2oy0bHIO3e9%YhZ5 zeyER=0bcFyrTW3VuG6UOs+-^X2)N`3VDXLi3E5WJDj$c+vaa2O{h5@qS`8HlRk30f zd4u`{IT`~E9;+x5i1Y3ybsD5h7!PmBU-GU9yuWIt7ckB-GNDZ;c@6$0ZrQ}v!Cp3? ze%RWAk{;@ZQG-Q3Std1d>@}C*b(`4s9Xa+zVtJ)^o_v{<D~|Z&x;T{@;6bL9_P~hr zkKnO&u1CZ6OoyIm*M6#dYf^VKwG_Y{jw<Bbs?#{|zzYD|E7Hwg!YmHEKvF3Wm;js3 zo+}CUlvUyiFr%N+$D^donGC#DPh$;tMKkjbGKU-GhKK806lF+`1j#pmuKVHmN8Zp% zBN@8PdH(wAP8Fry(N6!Mll9$yiczWz<<=wt`?DU2d0${<KUS&Qn)-Lj)U99s5A7wu AQvd(} literal 0 HcmV?d00001 diff --git a/docs/images/exemple_curv_abs_input.png b/docs/images/exemple_curv_abs_input.png new file mode 100644 index 0000000000000000000000000000000000000000..56c854c90cfe5a5d3f22f2ab8e1772d5077c544a GIT binary patch literal 36177 zcmd?PXIN9u7B`yE1!+nVl_Et%iX?QYNg(uI0--1+gq8#nNTI7pSBhXm0Z|b_no>m& z=}iGaKzdU|x=2U78~va6J?Gr>>3+S>1Ic91?6p_@tu<?QoQ0V_JL^eS5D3I>XrOBa z0@0NL;{g^X;8WxwcMk9cCRypjK}8=<&x1g$8-aTEfjFwCw;u*1p@8^1l7Py45lDd& z3c3<dsH?xfoQJn7mgtHj$>A}9z$IWFNAU3W^u~DnT?3VeLS^MuWFbm65U7L#Oi>m1 zfT+kRL7?cr>s_%J{67Sh<m3SY=TP2w4+4b*49#qS4~RT)Spg1=fC**AzeB3Bq7-li z=I`%^L1EmCy@97Al@wIu6qJF>=Zp<(Oid)92w?2z?TZ1v^fB(fgu`19UPJ;8xPpYp zE6B;qDak9#%RwNDz>Kx4rz_F>-|6UiVE@lT2vk{7PEqYI(_{>h<W0c;OGbbWK;Te% zOrR_F?^PuWYn;BJp0&y)tPM&H4+{wP1w=Yr6G-#N{9WULA$z+6ya1Zf19be4GJz%D z|EP~hR5rz$z^wxuOk5#q?w(%0XotVcRqUv4e#(Z5dKQWh3m*qOQq{!I-OXPGL-vF# zpdrB$P&f{$V1V;8GKP9s+M8PWV-!@>jQowTmR<-SMVzgjy`rVJoiU&yxQP-fz|cn* zW}{|d=ceE*j|YUNSy62)Jq+OpGMwzCgoVR=E!_d5!-LGNgZ&V?o=CJ26;HDEhS<7M zaAcadCDvQd!w9eEVXOx+F)<{WppBJGyr_O8s;>tUO(4<879>kRdL$GdV5dw324(~s zm;zjx=4EVy!FyWUQBAFJI2bTtsG#bh6kuwkVuV*VwD<Ex`TFWBl2lN(G;ec@KuaqN zA0iB31?h*fbG1bQJnP9rmDF6VJZNMyOrRGn(8QaDC#jm?;7DtXs;-%_-=T~cs)4QD zp=3rlssav*Hw?s?0m35*0VKShJUWo1OQM=!%}{2hwnR%ey#T;{kVd8uJqLe;jS|Hh zY5|A&o5Ot^AY@Vy0WdBZsb}gcZ(sm}83q^tP6s!Jz)%Q7U_eyyLF+rf$p~GNJe1-V z7)Ze(+*DN+tk6nCQwM*d56oUg6^F1ydZHl)h6*ZJY_Ps3&Dss=XJJp%HN)djDrjF5 zjD;79hBCDB0VpcEp**SfszHbVS0sY$?c=YD#k+Zu)NoWga}=74Q$|s!7)t_HO(DR| zkVI9pHMcU>SMf6aqfLshjg`F;4G@QDpk&~OveH9Y2cxlyO6E`~EP#OUf&{>^6dNK% zPtVi<W37)<QX?xOyuIvf4D=AXcwdZ}kGp}7g9_A0mq;=uTlrd=nqqNqvXT+pzyOZL z=u#E@32x>H6S5`R-7Clv>jyWGx5k*msg{<O!6ZvVt00K70oIairKD$0h3k5$S?dFK zfUByI3I1*lFkg2Hm4wk%3igCS-H~{6RT>)VZce26lPn#SP3){Z15mDdh87+eE10Jq z)fncW=I!S|2qNg|`Z^H2<xxmId=T2l5^8B=C~swlH6WP!=<8V!s3=oaECsF))zyc~ z6I}HWFd{_H$I=R8=`XKl2$eU-0^x`x83x;^I4ICmyp`<ieQ0`K%22pGO~p<P?Pu(3 z8K7Y3edr?;6Bsm*=%<IqIZ#MMjG3-04eGCevJ0Xb;DRW4w633-zWbrFJv{BqjJ#~s zJWWZ~5WF7J2ut$uwNW%Rbw5<UnI0U1cL*fmfEb1oY>h2&fx#rmq01Osnvoz#KSMQt z2b34aT^UC6fy)Ov=mAqE1Sl5nV2=&3_pv5ec$-p9j0r&&HU_TV<_5a1M3X?Amp4w? z$JCmlY$6Xq_)_KJDta)Oq6H!d8({3IVx>k@HX)PoP*r(<d9sI!lAVDoKvv#{>g5-J zQ1UZ{I@noRAw4ZHDi|Ei$Cap{5P(s!^Rt$Bfa}?t8514c(Im8oEz}%qMAY;1H#9TD z;4S_AiDraAQ?$NfkRQpyNEc5IFmN!Zl1*?le~7&w!H|koQna<hS<8C{D$s1nUOq}R zlnMo*N>(O$lZ@aN@BmBG00Ksh<mu%Z08ud|DEUHtaaOttK_0pR7+;e^9(B#^lwGYY z6p^+RsB#d**op|`47dpm8h}zX!}+5LNHW0^V(aNaFqU`4!UC<3`mR0(c&vrKvAmLl z6`*n@ePpmHfoKf`Gu#AbX6Wam;0y85#p&YpOng-B>}VuiB*7d(QUt(67Yj4?qPg0^ zEU0*-jRjy41F8awVDDvP>}lYuU_em8BfTsgJapaM+zbNr5ynP(iryF{H+^)Ffxfi` z1w%D44RG^x4@Q~!n?k%$6cPYzs#FujV4N$?LEhbpZ0iy1Wn+f6H77!FZi;5gZfX`# zG>j&1hsTnY?V+v#M6$h&u8q5%vI2zW=4<6?2e55z4|jkl1w-*>KKcfhC>vK2nurJ@ zc_Gjq%1XgrR3%GScZjYl#M;JN!Ars1+7ksaGKVVp*#*;VObqRVs0d#_#Q>6}70koP z76UOrc)Iyo69C<im5^i<Qq9|3*Hj-zF|o4^_CUb!t~eqQX=5gD>T4+P=iyDp*eL-? z8Loh%s<`T7bj?r-Hikrkn}NBvk%gt29n{dn(hOl9;HFR2$CDjA5jcdNi9OBxFpc^f zlPq8~1j!R&tYk$~^9NEmoJ??qP$9q|P~Ox4>S?8?h$eU#nfrR6je>NE#`5k#$_U*+ zq*oAB(Zk!sQxOT^4wU8^=!G^3G$C2o%6qt>RFQ$M-hsYm7ODyWAtKozNX;LLr<%dN zm4oC7wrB-Qs2K!)IEgg04mQFY!(4rENUWj-8trcz<Y{N;0f#Ch9msYx8+U7Oq^gRy zy9q1+;p<_kY(_!SOjV4G43LUAZ={v6DNu9JtZl7=EQnt6L<AD%5rBbP`Wtx%08jQK zD8U2W{H@4T;D-_h>jpyv*#;=t5`k=h4DceMecX}W$~YoSFA$=pYj1#pE0UFoBwb6G zKGqH>B#^*u7*j*4i8s_;-W;l+X5x!dgaO7dFrio~Takfjj{qBjH6BJGdl*2la3C_= z$jZ82_P)TBA;eyhh|yPt8wZ<un!~;Qy#j5#J@kA6?NkxU2v=)UUyDGBziIHHsqL){ zacGpEp^Y`g)SCpD0)@gOl&$R#$=D#hf{o1G4p~;Shgwo8NF^m=0LseR&C|yt$Onor z4I-P!TLNGSw+PnPGYB-MkT7}{XiJp2Db&->)eEa?XkvyXku4R>9Tbd-{)T9{jf$!p zRE6wEa)TT~ofp~L-0jf%mO()Z7BqvPU<X~eyo#zPRL>$10#yQLtkj?Y3vdgXl>*v= z3=2?EG;oLEgM*+BPz!)Hn;<~P$Y4V+dwVy$DliNTvIz21atkt6a4;q6%KPXNOwAMn zEflRtZUF&6(FQlO3M7(&bVo*eT9~2D5ATLpP!7wk!@omN|5vs3r}P4T|5M>A=n36Q z{Q}g)AVZ)cqPi?PGp6yh^3^6VUaetdU*;OsRDGwZ$|i1aa8*wvnE}oKr;}M;UYuTD zUOpyLRkNsFNeTY#@fm~7Ex_fDtA#*+_x;NMURSj2SnN_e$1HUW92cppBPzn3%woVG zPInA^N^BB4Q`cE!{O8xdO^O^T3}rc7@o(4sZbXWgRVZgIzWEOtalq9d0{^1;&-xN2 zy40TG;n0`s|3N|=xY~jJcMgE{^#d#ha9`i`_7DHf23$Jp-x)aM$59Mmt?<31`i1`^ z#NS5(3^V=zj^WqXx?`XU5DTb>zTSEZ&slr%WF#1*Mb~q*9>=-SHX=@Eht%l|HRQ}@ zi~J6HNjJoKnIm!ygh$hQUJ?#1V=j{Y<=3WA<VnylI6JcnG;nd8kf7+#mIczvff>OU zGIz=~>V1sGUkQTu87^mtmn{qExZtE2G#*}f3Qi2*`g{u{M`tj%J;4kPq$?S-Gidu@ z1o+Z;bmX&@${|oVxJRHK0b)K~KTF~oNdeU{tqzTV`a(2PdtS$sJmV}GW<|M%fq#<s zg{37P1$BdN7HF2!XKnf2v@QL<Q!`^PkVIF)U4JSmSe(Gh2{vC$J6Uf7VidfvFTjz} z^SJkPy)eiQw94#{YA8AaOdq$r_8Hv8P=c6QPR|8@-uE<LN@1-J1Yss1;U5HD#Pm+n zWez296lQ{$)W=EUMZYh;PUEi6y6G$xjITZ=(ag>u{wRoErgb1v@(gomY$te|TjvZ& z1=N%(gx;#BydJ*Ae<W)I2|8d(W{Ld1lfayvhft~gx_?XBJ;`)E>y&2cafE-an#*G7 zXKl*IHpVkcTSp>0IDUxdKC64)e0(n|#s;o`!j2w1WnbqVmuwm0!x>#9%b09+42=*L zHeXCXUhl*lhXYR<-4)_zs!yhu)2d@!?dswF{03s^HKvd)$yu_V5I@2;YGyyZeF5bO zjULcEMctk5roYS=xdjeox?J73-m0cUm}CLzop#ZgZ}*=#J2f`792&=(EfHx4ioU4z z@k4Mm%afSf;|?uZjB)e1-97<>T2tUJiviPbeKjvlzG~^w@$v=RADv`t-CxBVy>Yrm zay@3HsP|?G;sdV~9d~lnfTp}AE%Gy6?Mqvb36p<2H=F86snIRq`YEcB7cF*$(n{tu zwDiC0Ilq=MXD@hbmAH0B?-X6;hdZ%o+eU6HP`1iyUd8gx{+Q^Zb<3K|2%CsXWDs<= zerB%2I^<`-qRg6L#qi9)mmABXlSQ>|bldDYf*>WZ{|5u^SO9RAugovgpH3lX4&MeI zy7;h|JjfB6@{^RDT>+|y?kg*co7;^2W=2`!Nf8PLuhVaTn7W5KdQtmmaTDe9Gew{B zq}TOTbE`**cMvT-!3QifH_mi%TRIEj`ZL`bcPOvpB5O9?yg0g<SKpd~lOuu{Ee5%n zT33#_dsUxHSy5KG@val_S58HW@MXX*jf0;G^gh3<){GYKL4=q^U#aqmHYh&sD%q0q zYtk#ObWXhdRzuSOa+sS2t77pg<>Z`SGtp53-4NWI6m>p^?iN-yUrgZvahh4ZruUj= z$(U9H=Ux$orN%gGR<_qH2M)T#36_=~Exf-HsJgEhsro}EhAd_XUl593)~Y{@rQ!lq z!pm#JLUUlmv2PovzO`}h4}bd5wjipjQ}ECYv^~x}^FnCc{al-WtCTB^YCh69_dHDX zlEH%$Y;FCBM78eep`g^L0a6Cljnfn78t&<doibzkefR54-8(fW(++MbT4sJV-3rwm z4|`U#*)gly`VJ8qniTNp!{SBY%WUnp@YmR<%b?3ns*eK3Z{)S~9&#7?pWJ1hWZrI? z!ljOoi_p_!gK=fYCv5k1elNE9*B@m`jJwUo*^T@1JnU|cZ;lv~#rr$YqZfh1@Iv#1 zPe}(Xx#}D?n#+?ZZdwF+l)jxUQu2HCDoY5teto<{ee9uj*HcqMa6rs@l&k*-2dCI` zB>(kQ=p1+BjE4_gB~t;g63Dnws=uVLjcU5(&lyr)b0L*dZr4?6<jJAK_vW&k>CVSN zPvH%G3fU?s-y8QqeY)q{jnruY05M`RiK*gsjc9t+WiK>fF2BjpJCd81tMpY`T?baD zJ3ciQse?mVC+~0Kjo3LDM$7M<B(9daTMCVXwUnZweq-(%=H5x076r23YnHSaPJi9u zL+_zzvdCtI)!A1yH#W`w#LKf?KiV?rd8$zOTN@gs&6-HNEqPrGu`u>~d71fMX@m)T zbCqZC{@wFNyoO%opRZDCd^u5QlWEmh-7zTTm2_-%_>G!Pt938Za$4e~KeW#X`Xv5d z3V>*1d>!e)qnYp4aFzhEGqv#j6MCs$RUy}S=C;z)1osSmyCbAebVbf{MGvRxPfQPq zV(MB};o3HwNFs<G{J_6Z`bWM$m;a!aj~7Q}k-*5}o9$asc6(x9i!`0Qd(|i;UGWZH z%^&wGx%~%SoVb1@GWEUCv#B->dkZ;ESG$50UoAS!+Y9z_PB3H6!jP(%+Tk(&xb<Hz z9>4$5xIaVYXgo?~wT~9?dSyrj<dU4@*Xl&nNnct$Dd3*_`SS8`tJ;jN#|_~$q1-l+ z;Dw2?@|f>w(?@7R+pGkN;l_4pTE2K0K4bQw3e~Nc6~uS(;F|%BE0<A8H_Cxa>yEAT zn8Mvd$-lJIpLSt8jF_5p@J?CbV34{Rhn4)MN$_^r=V@n32=tPD`HlI$b02uesBPDU z>Fv1O-zb=a*H@!>x&h&|_Cc@Uj#Rk$Wi1c|B+t(M+t{3^Z_+S;9ZXqzC&-=|g*|Wx z?pC?pceL^OH_K<O=6Kf{Pi9mxanPl|pe0)&lU5?O$G{n`hI-L8RU*Z?XBa>aK6K7b zsh0Nin(^|J0HE<Qh}E?KsYdhFTh)(8OK&T?do~XA4h%@sDE16C>eW{hFJ9U<n~vEc z=)VjI?xn3JNJgm<?k-1<2jwQFu6-yHktPf2Ju!_w?e&Urg}hbUBFG*c-a|UDR&^D5 zV0^UD4I1$ke_Kd<Ntrk>*}ivUYu&kJ%Q2|6A*n{diHk4j&BTe@^<z>y;iNv7KaTT^ z(|^bg@FdQy*w|F{pc#QA#TLu^x7O|rmIuMcm*@aw=dZhS_tLGAC!zDCy5u1yH4Uqu z`JG(c{71RkC6<rnQJw?o;dIEVzc}T*mcPu$hkfKvq(!e1ta!zgtwH~|@5HCc`Mn#l zz3&<b$JW(Ib8+e?H9XY#KnhlE>!*b@P^mq^p!;u{0~tocQj(AM8e2AB&n!+$Z*bBv zbeU#nsZviG*NYW@^yxqsz_9Sf1yzo!kL&zo{cAO+x=h|xnO3v(<Her8Yd9=6U1!>g z^kO4xE*xM%x9JS#>2d)nL8)(=q`CYlLWb~y;?LznVzpw9#zTVaUys&h6DpsQ<06%~ zfYf)AoLu`~)$S@6U_wm>v+=Y4S(IKrtS8E&1wAhOS7oZ9t8)y^dF586;eQt1_J_Vu z=*s+=?ceI|!+SXolP+R%7WZG}^neaP$ae^~3IDgM{;;M-08ifFQl(}5SFQg4L4-x5 z7e>~{S3~6`|9?EaLG<#;V#PvN&aD3_J(i(O+P28^T&rRk1SV3)#MQhed8A0h0-RTc zWL!l)KtDH>WSG_HIbsj<$)b-1i<|`=+;-EVy8zZD4PAfx^lnU~R8;Gmsa>be+@Zmn zQJcJ=R5`;pO&_>7Fx~uG?WsJzVj^=_%9qwp)bD|&L6ZcjuVSl5>q9_p;KT8m%dArn zLY3CwOR3Fru}8LXs6fzuo-y~edNxo~nv2AIE!VZ@nP`B6<IYR3SHQ8HBH+lq;ZKI_ zbX*qv0;OOL?rih?)ze^WmZZ6{^uwCqFQLjG;%mh9BMGy_Pa!Z)ruM>rF+yU~aRV8G zMk~muuv`kKpwK!MwCxyAW4Q~bcAYBfF87NMTQcynotAL#Yx<D#>?Tz^uE5@D<Kx-6 zD=uyEy?YlTXF*n=DmmoS{v2-bC*MpiP=qmr^N<5t<3{yu)6!zWBeIq8C+H<+vH?Z# zqFR2Xj2e|H(-DR2N3?!}4A@23|7!7Pnq;aAX`S75K#FRdII42-%#p$bvfWHJz&p1* z|Ai2S$Wjcnu1l}pq|W36{VjGb!}U4v6Xs-aJ)<w>6E>JauVWQ6_u&6!2O)GiwY{&= zZ7%lYB|d%-<hC0QuwqF?m>GQ=gNQ<;!oYHV_s`|~VhrNEhpY(E<#GwFM=y|MGu$qz z9~)){8N3!>JEpF0<Midqk<zN~Pfb72*Cz8m-cpV91HGhIJ@Z$3rK7X-Ae7?w)Jk7O zJx{~q!p<Lf6)ySaI<k0~$rZ%M<}}qm){G3k44*#FWL{g|M$1-d82%~Dl+30h1lpHv z4rKuLCTt>tk;Y#st<ORLe^~Qwx*_=Hj~UZ<1UG2%D;J5L9mnf;C#BH^514bfc?$@_ zk^3N4(9i|D^8T-9=zN?=$U|Bh3?^qZzOoO_p_TuzKmjEO8cs`)Z{|rx(pc}#+QpZ1 zC$HBJZ+>RX=89|pksWIawEEOrpb_V0?#sFo024|emrp(XE5P|Rw~xf|{-?1p9aDx2 z0le3qjUPJVDOcQXCHNduwrb?kuuXdn;~D>BI(+(m3jc2}STfZYf;n8#Up#FYfI**1 zb(9)F>U^O09l;)tv;uYfjRya&0D}vX|HBGsr8}3Qf1?3ZAi!-MS8zgOV?cE7$~cQ} z-&+nHH4raowUTF@+k*4^7bgFv{pIaIPCx-#H>ygnsr*p@AcBM8z0;1Pi1Wrl@r@r@ zOo>7#uDqPXy<o5qsBZ<?(Tb4cQe0Q)K|ko)m?yJ!YOT`u4kKZ7CHGAug2Cj_mkaNo zb{sI+S~X0VROTH_0~z3-+MfcealXK1iGV(VY?w>BhMhO=jV}dxJltjhy|OU)?`T-E z1&KSq98MTgYtWr(vY9^5hpH`Wr)BfMbo(jCWWlC`0~t5vrJ)r?>-~;1V!j@^aW1}k zjHf{?cfl%wjpgp4Pom3*jeY)VBk~1Mdg?zeYolG}`IuR*AgtpI+5rDi#Sl0<7D(Oy z!xR{hjPtop{`iMtFCN@#S<`<h-aO0#P{8eV(e<$CxPx95j@f3-kJ;&;EKmL4h|qj2 z`mZ<3uu1*<^VxM2K<~jOTPD}v7|YZ7oG<?fQf3>F{Z#!29Bbt|3Y0`H|3Q@tsy+do z!J{WLEBx`c0j8Xh|JNn&G5p#3o&DpIH5;IgiyxokR_|FllCpu=^o38Q*Fyi;)JJpq zC}`XAjwsU=5-9e0lkL&WVBeH=9YR$3yfAaNY~<!4_d6^v0%jSDSS}atjIGTJ0VWMS z8Q{)L_y^q5xk1|Bt(rvq`9Kg%A<0eVU&=_N>*3as1U>$vjE7z9euCB+aOw+%(BhT2 zKOw0(BjTJ&jeB_f8Q6ok|8Kx11`6c>Iv8(X{81wjWP5t&%Fh1+)^ve?p3Mq^yr+vi zVf-&>i~xP($Yzdo{R2*NJ(k~c{$!i~2B%vbA0^`M45{Tz-{%GWUtm|@slNlNqgyQ~ zulcS}d#hRQg}V<B&_U5F8=8<mnv(?J07GA&^qL34a+-4a{C|XW1YHla&LxnxueHPq zUsOFEDCjif1wPh~QlF^NhdJ(5QAdr2PCd`wa7s^ple9YM4>C-i0J+_#|2KdQ2d&CR zu7Hk~{Yft*!Ss=npu2Mlk1M|Fn4ZxXh-#1y!Thm7(nW(i;x2A;SK@umK;o5FFK$FW zU>>O8j9UbO#49HLB9lYy`-{2C*H`Va+b$Ewtrvau;UNqlLzLV<Nz#=$_ZSL7{a&aC zz%%ziZq_3vZMw_fVA{C+*|Do!mzyhcZ?fVQ80OP_G!6lJ#sT%kS?C{U<OH`ZZO`aC z$Dd%Zaasq7RHy$dOVlyRGk`c_)(*kt?)P(g`%?b{o`$ahN#Y0H<R1bYs`BYo@$ak& zvP7Y8H%gR$nG9~IgK}4P;Th*?l_CrtYHlzcRttC5DefM^^9H4Vkj3cD5Aa_CoAe^N zJ76yNe<5THBkuu2Jsq3#->9U5aHl2WB)7Zr3e_wCt13NO?QpsGCs&32bq8AZG#d18 z?$DT8DF!ZKz+?X;N);xZ5Rf1!apQjkR0udZFpMEmI7rHkYiOn(fTw>;RJT-9bZ(H6 z&*6q=$3(d%r*p(Wa>~dAi*rHL#6!238SgkXruQ$mC=mJU7ME2(ZfKT&a|<;1E=y!U zM&Vy+E`hY@SJfilhI#f6oX!KN+_#`&ivNJ^k{t8=`J<8ICV*AMi`@JbjS|Z4SQ>;3 zn2}lycfCPqYA$?S;>4Ayo7AuPo7<l6zCXPPWZdhkRlVA@=gNQex&(OCD?QNaV>zc5 zo7QQS@Vu|gy2pz~b6A-P;13h@!FL#-;w4^^m`XUe#nPu|;>j+<oka7N<%0UEFr7y> zI_gXYh7iFkYORswbCFDHk?{hiD>uz4_1f|t+hC>8lT0h8LgkBgcBXt{bR@)iB2fA_ zyRRk|X!z*EYXo&HTZP*T<pr$iyRTh2(ZDlo(3@OXUtOb9d`zb$O8I+L5;<tqZgStb z8dRFUv*k=rw@JrnMR(9q;2i&%rAwXZg%)#vH`oSfb=Z)AeZcws*D43Xd%IKeS0OFh zTt|0$Z5Iu^{-$71s^j}(7WC%eCL7-7#EcW(tagZD_$TfQddN3f=Oo6>(^$j9Efp&< z(O3DCR$K>XwN$Ig$6Vf0a|6!=M8DY<iNHMRa^?$2eFED+;!4~Hg<d$<u~aMMHe6en z^Y`wCI*kiPVL1uXTTRCIj?lh`UhzvGxd%C#<+J{yj(135Nqtm{KNTk1vbUB3r3gIv z;0QL<l8GG7BEKuDWiD~uV4eMt#%jLo)Vy(ggg0YM<JWJ42QPRX#Ry}?$s(rYtOoOy zcjIq^PpV6XUT0J1k5NvCqPzhz-1{r9AL{qK8Jo+qEjXKdL*Qm>W%2Zf=EkZwSOK}E zBk<J>m5wkeQaWt>^(9f<nfd%<uCIQP!W&YaMoiDwF2rA~8`+kddn2H%#3I&W(vo}z z(bN2vH*>TuUXoIDg>*xi=D+lUX#VqVY09%@RNF*0XO8Z=;qPb`>&gCM!y)Z0?C4vf zQ7^wjxK%U9{<23w)1tSIzrTE@_UnQ-Z-pkR<9+p&r++MCs)Ck($B~J4zfEW{&4#zl z4BkFDw#DUtUAxIB*`)Ns()R48l6Yr_Y2anzt)@r&;CgR{8Pso)FC{PJ+yHm^1oJco zuxG=b&SzSm;hMyGUc>wIVqf$&U7sU`7RrWi4Bqr>7`}9Js(ma1p`HEoVp4FzWSWe_ zF~>@L^KDs2iyVeWzurC=(>N8ww;!K@g@1@&n=uwFy%l=7d}_E(+sWTgc#yvJcFgI9 zo80Q)A1aFpqvfxE&CM8{!i`jzmO89WJB|FhB;=x<gh&W)?X6E{gz&pbs3+-eo<FE) zZDplbtrG=}w1!<lb!XLIFtYI|80EWupVP|aTRsCL<0IsalX)(+7wPB)_X=)CJh_o1 zD}4PLTez(jD9uT!CY#EfTbMq5gf0p1)b#xwJDi_%q;FOyMH!J&ak<<gC~R-Dxm){p zVpjO>k+9vLw1RsPN%)p`jEI1ML8~tl$8z7tr9RX@gZW^U8Q6|pIRi%j-h1{)_2U_v zk{uoYfWnK{_xIs>%tvrk;!4)>cv-U|4nzK~t;^3ph^@KKpVdkz5TK`|Yey|*yb5dl z!K^LPv!Zmd{L;+`-K6%LQDlY4)SKF=j!EL#Oy9^RO&Mxa@nxs4c73T`SZv9hpKzUc zafMaOY3%mmHYzGJ+v=&2lm~hJ>wA%Ec5}1htoVnwf~8#8!`~POoxFZj;yW$s?VEWV z!?$*Ot?Y|JPU?^M#g2GQ-PWF|RVB1W=54YPz&Sp-{A-i@m;Bv$74%^{*{k$|O1mM) z!a2F98`Dw)zdnlhOJ|5;rP2;$M4VQ(I?|;rpBnLo?yt4lm%8ay74{l;CT$kA*QQ69 z-+o%+CLBEZwCZO44sN~lAn7)BV-b?mns}|Dkm;IBZOM<N$_clgY}g4^f04SKuNf?- zs)+vVn<l@729sj8jpNG>^wzkH;!cB?ISRKQdFI7vT>3SBu4h(VH-URWTSXt~^(ldn zrOgsN){VROc>j{q5Wlas%#WLG(u!h}91$!d_SDUwubd$K?#?6Yn5TD(s~?-O0?4ES zo=mM)1dypxBAY3b)Z2QhkH6rW)kCDHT>}q(p>&b`-Mb;x9Ot(01Kpfz`DESRinp~J zRsqWq_n?>(@4mBsqgC8bjgJqnewiPOD5ZHwIt`T?RA)#1W|@8QPDa(LOvHcd2SjGc z7X3MMO4<AKg<KKa<(J&~Pi|CgXTLYVPe_QDIU>mo8H2^i8X-qQ_uq>)CEn3Bri3lK zq&}@DoS$xK7wpiOhKr%z7j^8jnhz8?C&cqg=fJPC+Q0IAufFD%$FkIzMCm_K%CqP1 zXlFFb^5C<);6gY7hRT9o>WENtKElanzPq)O1g2+-{Qc`-Z$-?uE-cjiv`f?XW(yW# z+|Ac9Amp&5^d%k6t(OP3>DTqH_B&WU8uXJWlhp`F@5$dHwtBa2XLkIa<(O)nkcqy; z6A}$Ve~vbq(3s?OZRJS`%NiGp_?E~v!k=Fm$SvRq)IK%6Fwaf^EP{-Ys8(a`x5<l) z*Bv>Kb-T5ruO~S8i+|TLniXR!M6x?5SBzx*J*+DH9Ikiahf2WWl_~94Xb8BbvEImj zyhae*McHape{$e+7|U*M&N1Vb6R(WI_(cF1AAjEVi7_^R_QUnYNfPX1nxZw#=D-u; zCdu);api#J%^nB-QEJ!t#aF1$@1L*DTom6H8Bu3`U)`kEe4RN$|LnVWgp&DgvTC(w z&W}e$qXfuD-rE7?D-BCtJrhG0FM2?n^O{9w2}3In<$td>a<Zm8eRlh;Gj}l4;L#&T zV4a%*A!!Frm8;sQ*Y2Nv57bId7BCGkQ6SKCT=Wl3M4dKwTus#N-~-J%-i2u8=EoU# zR$+BU9qKZ}A-^~F(R?DOg1U|$aFMAgp9k-0i=4Q$%RHsR&Gk8@r-)f+&{hp}Y7~4X zo5=+n+Yu69zDHl}OQFn>9i3_dsHeU>J|XMrXS4A3^eA7DUdNpaNgE4;(h>VyHKH;6 zoYvEt2(5G4=SwrKMiG-!H`wfZ3M1j3eW5nI>3gz)QsUW8)x?hJM!^us&EQYj!&L!3 z{KuYl-|(TgJI`Qh)Wq^8eCM=raC+1Gz7Q@I8dLv1jec6(^puoGBEj>4!c2z1++u!@ zbwP_cYPphSK4E~oVVCuKxvNFMe#=*(8R7DBW}?mVM)TWoS?z=E$H#nniZ5wP{H(XF zenU~S<9KmHrTCJl@s7D=MXLvjuo1UFt#E4}lz3O2T5feJZ5}Gu@Q{r+xsAnKw|=ZP z^mGB!r-okz*tEtwpO_2v((<%!Ia_bdwOb!>Rk#-o{n6d8{cEeY2EahUUqnj&`~%qd zI;TdStm?kD`=-i6vJO;R{ARb)!O!Mj?*gPe6)VA+pqgv+FIc6T6wR?s4}5zav`}AY zmFkH4GW0TK2zp-JrLX~|0AO=V(fIfE!CLAM5L*ZjgS&Gd|MMI1VPC8FiFW)VWdiMm z1wZzC1z(*0d8A6S?f4GB<e@&^;5WKA-ko^A{T%vu;DRHUbU5^m|4_Lve>{)W)rRYA z?sH~aFWK;?`b^cH3v1eG^dDdnUT!D<h+r_t=8Ld(I`T;Bce72i*thtjLK^mJM+a&s zgfISg)rnsw(JxNhIDR(kp2*80vRJUDHMXp4b>F~p;-wPeQy(H<GbBhyNs8)m9%vTG z$S=EG%nv1OkEP@Yf@SyL9fx;@JlMH*N&bEyOM{H8SgF_}j1HO+r~`3Npt($BrWhV~ z3%7|AdCRzlK*=j%h*+;1Sp(7qC`!~?xcIBYEwSn#eU7eEFP<>Y7*%gxa7<A&Ht67x z;uhoD|Eff{XKV4XU%V4-b4E@BvXY;-Nu+?`zsy%Ano^66&*@$aN#{7X;SgEyez!k} z`RhTVv-R$DZB<;)WN{;Ri)S=*M_t(7YOlWVBb_UBLp6iHSjQG3d~f!h$`uP}3GH|g zzd63Abv;b?T3G0UaM#N1OJ^*WqZ8Q$FY;W9_@z|0`(1kfN9P6nO#33UH1mMfvUDHr zDzWY3o$FJK3Bi2L57}apA5ooczR&FL2+2m>zT0QrNjX8OIN{Tfd|WD1EE~wbxX*%n z`9SScprR9Jb|sU)>!sMEr^e4kBaJ}gVZ(Iw-%jSuGs~Qr?8-vF?zHbN#P_OajlGTg zEcojDtr6=6mue#Bg-b1ZN6dkUQoi9;{2+JEHPSqM<k1s{lw%OO5bV#^@q6?<Ntb@T z<*ZrUu~xFnw=r}GrTSbD!lU<XkI0i>85Eppb6oNDmXl<lHiQKfr><Vh(r0Tz#BiJ; zjK68SCCSMlr14F;!UWsIsmz&JZOk`{?~+qtV0M4Ue?86KGm~v{2Sl0OnuyTv&eU9M z=D##qIibP!S^bU2iHaolBd_w+sA5)M1G@tz%_0iJao^N`U-QdT_bYZxkfQ)mr|L8; znCD?*!FR&BReFj8fL|Skh#t5Xt$0@kthyt9GJexODr7l{p+xMF^B0j<8ce6>!@YIb z&&4fUeUW<R*BJ6xX0ML*;B)22$9LYuGxxC-qRUxLRCI|8aSWT%Nd++jF-?|1f-7;X zSyeGYHyFpXt%&j;6@a6xnjASDFNIV`b8$ruZk>k{lr!F6;hA}BuS4!i-e%Jk(h3-4 z%exw|I0TvPx_A8ZD=c$Fh^Wa##rDE6YVZnEe5G)-Q~7IJPK)odYy7K+$KN8~qzUJY zXECSoI4`%YPBr${hEM_*2G|>;X_>p;zB;JW?57{i$`-Hd8{qMmZWY9+h?Ef2nwiQN zanm<rMaukE+ES;6lq=M8TH_O#B7_5^>c$?1?>3Z+ZX@g;Xp|Or2!l*kIdvV)ODcg- zvT9ADMGDt<P}nbKUtE62xpoBq>upkGdqu73-H{uHFXrccdHh)+ZmnBhv0e8Jp`8!z ziC1Q_Sew7!leq)$KOd^uS-@&Ty{b>$l3z}OU`<XRSoR%k=NZn<Uu)<SYXDBY!XH@A zo{K{xG&-(IvYzbx=6d?#Oncd7;_gpxkM>l?dkWZ==hkP^Q#DdvWq7(S^_(?QWz`-^ z!Jt;3u&a+Y?m&x;UF2<^EenUFSsbN&DSmqZza!_ox-*yM-W1EdJbsY1Ah20~KK#X5 zyKmO-u?~tG&EGNv_Ozc_D@zE|J})0nc?y@VteHGA6_=M%{#KFc))w}h3upRn7pdk# zUFfxQ2O?K{F0RL1&JJkR=^_s*10Cj0L63^_k*f-~=}*|QZ{+A+`4Jf6i=?l!*mj#@ z%XKSOYqNiOrDl_}whmqHV_z4l25c9i^KFk5Vsr5A5Pos(`YB$<Rg+hg(ee-<Z3#=& zP8OBZL8D&~mtFPEPX(;OGEzo^&x;R{v^$@tJ(C$)WajbOFMO8&W?D<4e{$iNk!?i_ z_?d=WCGB9J=FxSRTL9`&Urm}*bbXwu;mMbn|LczTM@(ym0H4BJ-*5>#g>K19=hVtI zQ&PnAr(bnzA?7|jTm#}MBuDh8(6VmtW8LTN3T!KF0)@}du#LZQwU>T?R(I&TYA*gL zEOd|cYxr$8lVa5Ob&$vJs%wmvuUziv{$S>gx_$8hJh-Ti16lL|R<*!E1T+H!*>@*L zh*wU<pY)l0FAP??^gwdW!xiQpXO`-4dr`dllW6B2ir#vx<fHBLZn#mE5!gPJY!}mI zH2Pig?Xtyr1nqo&ZJC_T(81F&nEe{U;6opiSW@s8vuJ76J~@*5m-<?1NzI#jsFCW> z9q7kg(*#BDkCPvt8W$-FPbqZ^k6H5x%G~PQne~-Oyw{RA-(|m)oKRn4`^<?^MMMN7 zs7{W0`&Jv7G;rYJc3tIb->k;LtjZSDp=uag;M{ujIFJ*q{B#_9&Su6Mz&khZ<)^Y~ zdv1F}53UA2sk+RQvJc~V^i(JvC~&|Buy5ZQEZ`S_ob$yHWXC$me|L6MR=`<sWPjhn zWJgD#Uj%1HkuPm7-~aYwW`SSn{QX4rq@g%#-|v+7_m$G`ukVXFd=xc#*1)T99pag& zbc;@caCXK{uj#~Ko+ZK|G`55v_iBd_arzR3>0XDTZNBVI4q%ugr=rV|qaO3U)J1{H zmu6AT3&Z8U2I=Q{t)3Ww4+hT5q&09_Jb2>W<1xyZ^*ptS`c(keC;ims-ea|}UUQ9T z;%HTX*F>Era92#Jd-G|I%%v>et>R28j#KMBrInqjE>BliN@dRt`GHs!4?fIH#h)!( zWa-Oy9<A2B#Xm6v{=A6n-G>3^y<a&kuUeLbaXFbCcL$2(ewZii4P?~4D4#Nrv7l9a z@@Jftbtdm?`{%|5{rR?R#&_hJQzeXbhy}J4NlP~yjiaT7MZ#l4oww=k^+8VMw8X~c z9+!Ll@RNv4_;<P}WwGi{=QTh|uW(GwAx<;Tf(+6}HbyJZBNYw52rjivU7G^$$}AEa z-8C}#s)H8zQqP*kiyNj+etn;Twz)oDQ)VvUr2ew~8643c4{v|PkNSAWJ0<S8WR7Wu zve(#arL!h?v-NDh)jk_AeHX2bKA(_%cBY%H*V|TNH0beG;+zs-u4g<eYc@Yc%4ANw z%EJPCBX)fu#8t)5noF636O#9}W5vt*pZ;J5CG68%w%T4BO6iefs`rSLdGz?n4DmKl zvNb$mdf;c;`cS`X+t9hWL3!}`h}Ni!_r*2h6O5I!fc?^NIWM$^y5^QV>cg8$cdu9O zT59Z@jxCshqlM#%YXb*&!?f2?&?Je1=cW1g?YMClHnH7hD<y<You~Ww4Ooh2Q{P1f z<FVq*+h#vp!4ixqcGZ*>p<`!FVi}Gcn_PCTY^WFY+s*n_P_kH)lx{>EO<&tQPq-j7 z(VAE>U;q2#*|Hma!0wL~UEvpJuKkPWmSjS~=F?zVXQ{UZPk(z(s23Xxl|(78+bKkp z^Yvcqd8zHQ`>YF-@z|;RIr{at@~!XhgmsUju?Jj?dE;7Ka)LsKS#(z9)o6%lHM_A_ zx}viNt>bv!__;)i$EcX*tDimb$rppZU+&G(v#;_$qqWntj?<j0Tg=*1Ae+x8*i?6( zuhs~&-R7Qb74du{9*?~y<yppxYief3A&Js(m$#w0RBs2MjY8lTb9P-~JH`DA3UBS_ zlS;$kg2D6b{pXW}G~s}Yb4!|?)(G9UD0tnoH+U2uOLCkO?UvNEEGyi6DBvpC2kWi- ze60jKT-j!yqji2Wv!MF=eBZOjwDqrE11|(}O*3*GvhpW^W}E#%m@USo^6qZ2<Bt9H zAUIZUv}5kJR&D0ba39`U7FpxCbwT9w^;W$2dm9U1RPA!OCXh^%b%#)2IK%6sIj;D7 zclO+jy1h5(;S`9tH5zTC!!ECF_VsSS@y9#;5t>>s{1?gX-onniy=Mj8R==n%MNb!U zp9xwRux(qs%E+bzh)um3j!xjAZmw3C<J}8R<h#%p24FuZ_qqe+C^P^5)rZGJ&X`^~ zpLbEDLE(<55NGE%)mPqU2iS4(Y1JLsU%O95{agUbi&$Q1KDU;{xM${Bti6U3DrQSI z`3h?m91{VfPuGyH-#W|8t)&u<S~BxuKRk#7bdY0s>+D^Kd$h$+zf-2@!=rHZJj>57 z3DPrJ^aYj`d*U9?d#oNS>o5Sx^Y}>XM*UQCW7GrN9u12Gsh$MwZ!oWiJM>pA$F*5f zf}4R3g~O#{IS^B|EDOSmcg61taw7Zk`W3#Aw5C98YgDnn*Hm$va}6`FJ#<dA0s(u# z*8QFJbf8aU`4YQJ8B+1hPPIyW-W+Or*9zye?qPJ$<$3D>_JX1Px{gJ$iza66%&^Oa zEKR!F^rO7bH3LtjVy!>e1((b0ycP%ct+u4^>eytL+TiQodLN7V^yf_yQeKAY1UZer z>YB;n6y3|YQ?x$v)g9RAq|YUFKVkuD4~~;cK2g!^r`$IEDy^OBUa@I(*H<-BrJy-$ zL$5?%`w9qh7Cmf!!ErC`SkHUOOT5#%y|;Q^KH2j7EyEga+IneK_4qZ+QIQg{;5BC8 zeXby4OtiYvYNONdr(P!ncz}f2C2I_I6xQ)t`_`*e+JC{mJv8#Gb<y;%C@Ha1HA@G- zHah26)q>Z4o;k_<fLwF2vxaFj8%E!ip~6X;`(WEvc#cNgx<BpxNO5~X{#Y(sd-$X@ zk-8>4q_xcUw2dLbH1=2!7!H&Z@jQ0!Znn8yU(ng3{MNep6%XXju4j&@J$u<Rc~#7) z->YHwgoF{#)3&w@6#`t-N;IuNLVHHswBWS-Po!l5Q~HV;`@Ih3<4|3>166|RB~^kh zTfy(Ki#42>5EJC>A6fBsg!@`{({71so$jwpDp(Hn5U~*MdsE?5F5A+p*no`Z2y>u6 z;FPo2=~Uf^j$VyXdDk{3#iBoc{Solq!dU1Fk@~kim8thXi-df-dF~S}?Oyi{Jg%U6 zQ|sI+B%eLDBsWTbsm~V%HNF76R$=g2<K^+27ldy-_@w?=S08uez22rV#rfU4yI-;d ze){*Hd~-yKc>CDE6Q2vcY+U5z9U``(Gw)}5Ow#mO^9wH~?5xY?i#b$Fi7#^Vaojhg zkclU#J3k~`-cTP=ef2sTF0jsgogX{bhZB8i7x>odR$E={z?VgCKgh=G5<RAw_X7Ei z+oWhz-0kB9EmAS5sTkRu*?XHzw2l2ExncLM0&@J<cq9!^o@qR$M-}~^h!(jX@Lm=> zicIrzo6F+jI%=0A8PSu_W3}=%MKB<g2D*9;^3t74Yh4-MSu6TF^Awn6tkLcWu6AlK zS=BxKnlP{XeaD_c5dPsvQqo)JtAW?cpA8U~gJxQ8q~od_UU^E55JkUiR{y#?Q5c!J z`1(tix~Q!qdQf}M?rLd}Om&y4P73^=(lVY;35$PZ9-(`{6sA{D8KqU*0PBBO`}<(e zXn*mRq<I<@ok9%#a>DPRQ&@PmILb%+#j)qZfzFQl5jP*hBG@`vayVk8mhZm1F12#E zSC8}FM;WP1&8ja-%&B)X?yKeZ@#SARKLK&iJ<*%d^YV`IURrax*eRerBJLqothtQp zYJ1;zDE+OT@ryOWY_FvS%$9eVMN=xd(aR&L0ZL48pI=Nitzp||GTW%q>q0fFj&%V< zNxm=#8;3J0_x!=Y$x0MCg;~PDljeVQ)~-zEApb;B*3cE!OYfUvo;EM=k6q&4?YD6b zwxN6^fg4H-Muy`)eu4jb%aIV-NW4h(k771}-u8=)uWf3vA(pJow6<Pj=Jfx45Z06+ zxw$&f`7BAk+7P}vsXGHXs@>tC7OFYVrFm8Sx=ddE)`N3NB6|(_!7?Wsjbdeta$@{W z_3`T8zPWmT_TXr%tG(H$gU*z%V%^4m3x-tDmosa;;Gunr{<qS{&s$$Ter8s?b8URn z_Me^wJgPK=d{k|6t^aJ|7L&a7nKGs9(@fIKza@#EzU9o3T<<S$yp4$OTX^=J%oX)4 z!qAhpdk2tsRigWjre^0)`H&jbtg|?+FZWk%w1P(xHt+SGl@%I$lX(A{iYVs8$8ikw znSb(qZGvux({$?{)d08AY7%oLVFH<>yAmivjau5()@q&)vaZeVX(+{rm16p_uX#Ki zO5GUq?F!@1+vZ>1A%;PzPTHk{32)CAJ(!ww;816iz6xoT<L5PcQIVzk`f^mvZFTuu z8RAwPvoC*Kdcz|;{Q30#-6EBUo{XOS{VO*qzjdB+z^X)-k9=aNbX0jIC)qAz&f3M2 z7YAcOYWr*l?wU#rKC5hBkD<ty>k*&wNSfdKQTE)+H5~cX+vD(qM|L#&@!a)~e$$vH zvmaN!ot1fNUbvoF;ECc{k$0j_c!|kr9qzL=J?5T_tExt@5N(!XQ(gG(6!A&*h@I9g z*ZVQs9x&6w?({ZXusv1cI6kK{1a+DAJKtaxrmT26$f+t^f#-*!rn^@Gr_+u8o%5_q z4c|W%SOV=2n|zxi1$OiNxsUKmcFQ%O`Gh#bE9ZDv_|ppohZ(Rc@8LijT}lX>;>Pd@ z6EXOEfbN-!iS<h%$X?2Yc<%i(GDSH{3thrFZ;<ylJJ-yq6=lH2dMD}Y&A0R5Piu7H zu|<Owk9g14U!h$q^(6{_nUyi``F=(gU1rg?*#F!*eRd|e?fx0|0DPwtkMD10;^6lp z{o}WL+WVep+-v7IoPl7YJRe&y=M5VdGqQ|ShaHG~rM!P8lT9sY$j~j^Gs`h+D2jPv z_V6UC*rhpL8kKzBw$0GFx1ljaqiK#^YM@AHJhHy-OWIBYO$<Fy=orJwdp<jK=ZAd_ zxzKCl(eB+dQTO1`bno~dmp=Y>({??Wm@m|_cyO+ZB6o43)T`k*cf*}cnZ|hVrxaC$ zQ2*X~_OGL7vRjd>%(X{kHwyN_@4ih5N4ZYHfGt9&23+=AGNZgLyUMvi(n%<r(TeD# zz_I+RPp;19`25BgtXtYXdToo5Inw?y`Oil%3#!8j5;6nh!@jX^zVXRE)uSuvb>r4N z_^I1JMz7VCrL<dB$;2(NH=M4ybyBiEL#4Ra=c{v5tl*_Pu20Rgg!nJG*c<?x#RB6~ zBQ1fAz)_`W#N+UD{h`TnxD!v))@~+-$n<Qhm$1ZneXa@+>$okO0L64%Ze)TmDmE<4 z{E~hqU*m4q6#EcV=ou#!B6BjK?dQC}?z@T`qGf&wuFSx`Q?IdCGFc>Ope=ei=r^7r zLjEe?`)5>76sR*jdRfVZetoXJ3eD8tfO`WIVQ%SL*U($R{g__UH1T<0;UHCcZ_D1m zYGGC0=Tm+<+*8u@{*!+7LBzJzROj^ue$7kU<LA26JNIAheBZKi%iQ1+;}cn|JbCe* ztUg{d_*x$Gc&evd)Wx?eA8`giHQxY~dI4X%1VXnTX|09$oV_6~{8fL<byp@ckp5ia zw1eQ?>E)w7zg{v*y}ZLUzIb?;nQtR?c(w^7f4-s#het-DcduM!qt>*4&svz;uV6g) z*;|}wvmpLv4|xo&Bq__rT`H1tA<lCD9Sa<A?o3@ogHVG1N+B8NH5xaI0HK-tLD!DY zKnCI=sPS`HmF^bcBvs5dlb8pbT#Q8zy$<rd-evYcm0P?r*sw<>-T%wvNsRPON8<Q7 zBvt9g%fa%;86{;Df#Uc+o8!%MgdzUx=>5DAvAeR4$`3SX$0W@j=nTBrrA41risuxH z^j7?;I6a~`@(wtbNJ|~>b!$N`eBMfDeB<@GE=)b1|H4hT=6Kf;Wyq&i(eE?MQep4V zKY{n0W77-8RZrZyFHYB<>>{9;C|-tD{s8LZ$_0+WKQYrJ&11jqK;yMfz`Q<3cL-0$ zcpez9+5PfSk3MZ8a*wg+Y&O%jqZD|dQ2N5z@170I4YCo3M?yg%7b<Wge8<n4)NilN z^yZqL8XLBh#+L4K7Jz6O8nqGh))|s0jrl^)iNW`e&HhQs-=$=(ciw%yE5>oga(6UX z856r)o%N+*%vj%YeU9DWUO^%r_q8LPO+QJf8EE4qD`3q4vYabC1ntw+K0%)f1vPoI z>@|fl4*X(%>iInWp^^~j?E^G=&Y{cB9X9C&)ql!{W_z;4W}Rm{$@rijqY*5HdB?%G zJo(O9Xz~*RkUsxT>dflE!_inj51t75_(KOiad#YIp=P`x40JgJ&7o}BI34!YN>po0 zk1uRRZ%lhr#4tBWBfQe7${(CKpI`tq6`m!32B7xJtg^=8Ry0rYQeCLf*35YNt-HV` z->t<w-u&6vs(q3z!KM}*Jg24T1BO3P;ULi4-IE&Fq|6>PjXRRRUqwVoCa<4?U5#z@ zR5b@0#If|u93nu!cuMQ#1M@V>`}b{`8$eog{k0;STwxJpvtt%l|MFqplQ+7pZ<Al` zswaT;R4dvROR?QTJm+m#7}@xmmd9$u`Wv^=EyF&%LPs(4W}exX&$8CEU8&Y~A55!j zb9qW{6vj76uJmR;s9m^6zTQK``-j*1-mD(3#!T3@Xz!sO|7q@7`AL|d_Aa*s<!oOg zO}sBV?3#}L<ZN<$?*78St9s&nWvH&@o;$d#AVW}J`+!Sr=B#lN&|HX_HZ6(a6fO$Y zv7hewkaIh7_7Sg;OK&Q3@)Sd2%Hd&VW0(WwTMyX1^``BC0lrbIzA131#C7Ox#M|7Y z3mYH&GQgY!C!Js1%qi!>gw!*>71kBZn)~LT8cq<7iq(3tG*XG;6Q25<@bH)#r&-~{ zDE3CQ7^3ubUO%O-a7iL{AEFo|?D^sOs@Ax;xwz%w|A&U8jYu$kN%*f|OiG^KUFo}O z*Oo$A;^r8>86Gxw*Q_y{EF4<v4=!j1|76)Z4VrLfWaZI0*xxB7OpL6xh`%g5!g*t3 zWn$v7mg+>Ar-9gm5h(N1nnb;dj^AO=eC&!IU#$=4_21~ZX!BixQy_kDJx^lz3?lj{ z_lFx4Zgdd-fp&z;&{S>MD`wa3GQuO&NxdYUk2_~m_RsjC{^-_4A2$BM*uSlsU?*M{ zD3<ytwdY5kuf3Z(lg^$eZ8bj-t=s8Tq1LhS;N&h?a^CH_P@(XVhgnK@`U^134h{*t z6=m_k-|us}+q*5StRz9)TSS0Xpm=5eYO@)%Gl`K?G{wt1edDcC>pXj3kh*_%c?5bH zg=%_H)O_AClQrv7I9J0f-k^LouHnR4JKprR_y^1yd5!eyrPGp#1n)sj!BmN5F^D7# zi@zK`S{Cag_8oXp!PrlrpuG^+f+rSa<b=QYL=!*n8CDU&H~Kahy>51sPeY@2>%(=# z-9d@sWLbP&v4PS2r-kuab>QHR@B5T`;J4)IZ@}S5(zF^%PvYf%@$M4W6tBiHRk{(n z*P_PPZ=V}+-V5oo4jrpbl42IP^=tPNo2h_KET)?HB`vox<J1)QaLNBe!#Rf687*x% zXk*)UW81dX*tTuEaT?pU8mF<{*l28hZ_hd3kL+K$_O)ltnzd%0xo0^CNAn@)I6Vl- zL8t8xfc<NV@Fc7}XwSa&VMDQ8RNg>-DQxsd66bmxj|xeB-#gccUkfL1DFl7u7>7@m zhfF@@h2g0kQB^;9OIH!~C7bX|TI{km?TC|Dl3v@>enxhUYjvTJ0aR7h(Q}}x7IGT5 zel~Q_!*Up^GPPD6x?Q=MU14tcQGLrA_Gpu!n4lQ}Q>w_KP*+_y$X?Z*EX87(WOr*I zzJBN7vR81iXMw#nQ5PIW8c!^gd7fFyDTRvZQ^D!q<ynwJc?Nu3H+4;|-U9kQw;`;( zt9hQstKq0xW!9l1cKP;9!B)MokAlf-8=thlynpCXft_pP2IEl13Ns<&#V-%DVKyFA zt!6QLX;BaJ^2??6cZ0;Q-8ZLRams`4dR%o7LR;#>4OL=SziZcaW1gpsDw?hi!&vg+ zWlTJ~j~A@$^?C=NI+&2(4r8YWXQK`g4RdiC&w(YxSh_(}g|P{Z0tEikV%NWw(l)rD z$CARhbTD-vZZtYCN1x;nVt!<I9)@jI^Cv~r#&S|gq7lHqE)7Bc$cY?^#{Bjy$6>p6 zw-m0P?4EkD+3xY>Ukj8|YCbGk^$vxr#Rjb<=9IPyB&-oqF;tSgrO|v^9fPn?JXUxj zooP$kCn5*Z>J+zo?g{G}>KM5fKUI)xJ@Rw-Nh@hXEE*$}zHQN3l)g)$CMO`)zeQ{q z1zxfK5s!2mZE5)CW6{C$(n<B44-;EvVYy1<evbPaNxf-bdhf@J%x~zQK(w^BG>Und zFSbx}NW~n*|D`f?go|(ND6@P4<Y9H{@+z^P-5yh3oP-PbFh^Tc%Mo`|6<%o%)WHC! zMP0nC74)Z4jPm1(Q21~^lw+=k#vjDtw*b<~&-E6Xd{e^g?xrbU3U4`d9*C=_q4oHp z(fE)I#JB3k*Sfq{iT-)=(EGU#ZgHhet!BRaeV@I0^M8z;MyKJ)*}_KbK~H+r#KEBI zcjt#WZp56FQq52r$KAm;-`5Koy@I1a>7@&u_v8N%5HHRq)hjrr9n{duA(9?nXqblz ze$T&uqh#tdX79>nB+pcM{sa?f@JoNc1YF%e2;s<T@5mERS|BEFVr=RGCgLhOHWt|I z0Ps=kMbtVog+zAQtI^uQ9K>Q%%9;64XG6|n`4*Q|YlnZ!-|PIR6r@{-%;0a#W}^i{ zh9+o%E-bMZBfkx5h_h91m8`|U?Oe|-HrhoB^KGEUp8g$`J8n+egRU|9Nw(U$Qa3Yz zHi*6yJn(mw#!1EI+Ooco?UqiF>|aAq%iv}h@f`+cj)gn+#UQp6mR+ZQLTLRz3(#0F z{>Mu=PZUs2TGBUI>y_==pZ6<01eBz|r%T4>9{B8ZA(Q9OZiq3gaiw;%KpI@ee2i+; zV#2h}m5xSHO$2Rq4YzS$27cOhZf7JU2P1o0ZY`Sgbv4?=hmst-NPe%wsqi5rgJG9B zo&6!eiMaC5GEl#=y<W6@&kw+`$nT<hYYv1YvwGAlxeNHHJ%jn7z0{Fg86bK^ZLbZ> zdt$xL%Jz6a1-=lnUBt&{`Y<?olpOCG!VFt55&Lw8PKQ#2#gEG1&I;bAL!LgZn01CS zAdzdks5mUm9q-o4Y`<LFN(Z7~&>&O)^{^E4HeYo7@<3OL=U2{c@O2LDNpt_oW!}~9 zjJFDVLvR)BP`ysl(R`<7q#)b4z0Q|d{asaqT5D?VKpmsm#Qvwr$&5=^%LMM!p36vd zX_|ZLyAopSX@>qX&BNjkfe`#cY@k*L5BT^9l)eEGtCF|SeV9Al0i3p@+FBtxloE;` zUCH3xt#@bDvjjJER-jDiT^dBv;!Y1#@gb29tki^J62sscITCzFf!YaqQ-t0Lsv`0x z8pHV`Y$}=LLyeHFGd6Pq5!sy0GZY)wz;|aK7_`Kmgpta8iY6}g5&^tsNSp$L=>}kl zLk>5fUr*KwXZ_bAz7Wy>ijPOJ)7dFvbkOerl2gX+kWyFEu{Sh7&QpnCW>om(@w^YJ zE!!QZ3B4(8Ok*=)_H8apfHQs??w{xSG`9&uW;UGEDVqi-$r-8%0Jjm2ab-8`Z3<Aj z@TmPg9oMVHe9w*!XS%%Q1(HWpAbDg*wIa5yT-WmQ$XpQuMk>6ff?Y+jb|*?Qq~ECb z6fejC74}~QrP!+4m7WsUcv#-wOgZsVs>hC$AYbH_FfSO#6u4Fx5>43sqJ=B~ma$VW z+Rc^L%5oP&<x>n$bj1*r()pWVRHkrp3jzMj(5rkDogpV@Q_GbRKzYC_+tdi#aLRAh z(746FQO{=qo~oSvkEd8Z0-@w|Y$1hl%hS{qYLl@M%L(dbcVbB!(z-VpyoRm2J@19f z{}8;tdzcB*RZW85LKp*dZU<nAltx#R*EG0mj9Zn0|K0*U?WxumDQ2K@+Oelx#JndG zWiP$s^eB3GKP>;FxzbptToocFb53N16`^Mup{vz))@*?&Q&90<2Lq^PCR&Y*DI_W+ z=$BW3mUB+hlw0F*efKcsBsd{F0A8aFy9M=CqK>%`$RJxM>n_{4nXV2OWqAE#pLEmq zKwpg^g~$DR=4C2NHKeZ^50kiEv!q>URaS;Gq|4;9xse~FE-~NV?4BK8H$WGjjX9Fc zUhK)q(*hc1#H<JuyLsjCtW5N@yN?1p$TLa=(N*#5HiVBQHqo1f)5}Q6k(;rw1LvIO zyS=W_P*1z#sb-C+95>vM*x-tuldU}j3}JLT-fG0cHly7TEN(~TIeUDXcJGTG=PL@- zp(-B+q<s>48?Nkn#-q(c+*851TWrW$VqV}@1^xyo=XUBZX>d|;Q?W(?_-DsIuZUdX zqMf$Ed7q0~Xfb9(%WOIAIl?N?mE{dI8b(PUn(R~a&jLPzrzi-YiNJ(Il)0J-(R1t< z$FT=Es_V<^>Y4HR!TKw%Qp|@wa8sriLM9`EjcymTm_oS(?r%78{Dx#*nd@sT?>y&O zY>Hd~qrnkg(xP9+pl(>JO=)=Bo#Evu^@M+tS>EB5nEkQBlDtcIobmcAGWo)*Wpdp9 zOYzm&-~;JAa{<?r|5^ANPFt;{RX%v6^<$RK{BLKMhq#A%<m&<7c)d>m)0TSUxeb}W z13}?`EJMo^dKH{#M9nwVe@6E@<LuIdq@D1>TBS#Hy9x*gcAnt~`mBh>AgtNz6N7`t zEMW`xAj+(BzIxu={Ctrtn1tnY-8-WZL6_G97Anr*EE|Gat!Jy71?tZ~tm6qjdBE`- zOQZluZ-Hl&E%}Gra+1_U@nw1sd3tPcWR{0PWw)<(d|ApgczRt=TO{=2w2Yi(jaf$q z7Ywlm2jF#97^r;46Om#b2xz1~DNhGnFK-+tPJV&|S-p5+fJz6yvl%r<(!X;q@jua1 z`wq^uU>B0Ar+tVLSsPS#1Pa?oAl@>*e<=%AD?zK`u?O>tgmWLn)!_04IHjWS7P$k_ z%g$-UJu@Q|JW5Yue?rdl%SBSUe~L9mruE%%xFKUu8#Y{b_@4`*fHSj(kSmHOmb&(` zgDZffT`*~tYnq!X4G6|iEg^6A|B3htaoy`_g^9uJ_d4)a#v|MNWJ}kgehYe*ZO+Zh zgSEq}RPXt|i#@y?9ZIECnE$6BO`E9kyj%Ph(wr#fUm3O?uJj=@yJ{Dr?x@J+Z5ewd zopHTD|JuU*4`}onVh+VuSqYyh!<-n>4b<eSE1`2@?K$I8j7GrPu~eoI!eXdSyfwJi z7;<<YL@-PViOJNTK$c}dYi(&Cs%{OrpTiN$aZ`AQcs+Wvh<=*_c2b`ixMJS5yI0n} zz@|_k#s%I&<0}VKu_tpECMB`<R9E3EC!eL@B;?P04?fk?!t>2jiYdSs7kLO4UX_Sf zPY>wi%k<Ob9$8qEg#Ekb$-Y{F@h89E0uJ!OlqTas*oCSr+FtL_kr?dobh=!yt7b23 znSq8lZ<nJ`t7gg7l`^3)sXn8X+~F5O6OjR>5nF3<Hp(329Eza*^J2C+p7ECD_cb&? z)(~w6XkF)ajFviVzOg&nMlXy?3vBY!pB1{D>>eQVP+av^cmUuPPm8XdZ}S)_&U)gA z3)mN0YZerKe}{1t+NlJb(6Uw^^QkQM09YM)M^Lf;f;jPx-C1%c)&t?I_%xrp(X*9} zJJAIG+Fqm~_2w<Rb&K$KoA^bW<tg|UE2aT(P<s800MaTj=c+^s8w89`Y~7uN1`23( zCg+tRR-DSAsQJyL_?02%Co;SMsiu+B577t!p4Xo2IFsg}^MwD_QO_Jr@Oy_8r|$GW z=Jk}JTSPSxM0L6LHWl&pyPX1gJ-~;8B>8B9xQ1V_RZW{sl*@Rh8V&`V)`?I=75k3u zt|i8H5EQ{#+t4#pHN_?}11QkO>rqjI!x7k~RsRfw-3|`+p;;LI%HjWXSJiViTx=Qk zrc7$q#}T*>gJE8kXK-KMk3dNa9^v&~+TB5aL_|niuqmDHvy{!%?QIUM@84+N-U{;G zla@0H?cC84$gZa)vA^?VD)aojmW{D)C@i~Qi{%um-4$W5?eTeb*!~47auk>u&948h zN3}6W06X@N$4}ZUP6Wm>0AjT;KR$idd2BRTT|4l9xu><JP9sa8a%A-qQ=8W(kQwd1 zTvwN|nXoADQ=OdJhUu1;;Imd(M0Mmbt|5F;ooxNyFb{yNa?ss(I7~q57HpC1`#Xj6 z&^jKe`xBz8L54v4Yh^v#?7JM}hX)=VlNW8*0UKiet)L!nPq<Vp>e{CDNrhuci)38s zqusAlHJ44c93Z{x2hzI&i>&-nl@ZQb@@TrNtHeYnqXSKwmrC#kHM{UR-C>;7rV-n6 zOPe{2sxX=@NYAPf1da+Wsy&M70E)dSt&VYLZnFV^>q$X#ko|fz+2EvTtFzJm1xSH~ zUkaM(I2Jy=>5hnue?z36<&Gj;WIWJ4OcI0yP5KE24sS)N+IG<A?jcV8*gJX0jX?QI zy~fbz`W<=AFx1N4^PSN=a&VPC|DeCTM1a@JCBPFT12KVe)H7*=YLyXWWrmPyytg%} z@MJl<J==Nr?}4$!)gv;QY?exIn9BlQ$L=LB41mfn)E9qNvXAQ>wK5Ez=AM!OAdO=C zmaxchMKiJ;!%gtyg_s=+4!PNi<a?f2JUV9eQCD{DN?Cp9T$~qY>1vTb5|5*mhTW`> zoc{=Bt$&@FnjQ5DXBRLwkr4na5b^he7P~*zgF_SEQ=$4m11VXg!z)_LZMzMDfgtQ+ z&x=T-x`t}guWeI=O|@6+jrg4C`ETLzBzbyJZ28LDTSDc4GF~%!KK{$jOji7qUj~_J zWaQPBQLXk(4gccf2N&p)A^S^SGB%;UQGd089klbe^zZ#{$@jgjASy^HuSPV?Y1Ve5 zNE3kYN(u<C3fM)XTGGE=3?RAM%}CmcGyg*}b8ptsXPFi{<_`YKT4tDa+i@0+#Tcl& z?pU8G8iu~wz4mR&bVXz`3O6%$(TM%NoF!J|CjW*5i3ul`s4kMwy18t3zZwy}_{ey~ zdepLMl#0(;GvnfDnw9S}ZRv%$sQ7Mn9bOmAI@WXQjEncxl$*Yf!W(%_R)F8nrR4I} za%@_7z4;|KitSFyh1KnLf`Im12}-;;KzYPsX~cao-qpcyghcg}hY&kzkqz8w(ze1l zZzL&4hIEkDyL_=9rQ~-Yz>?uGsZQFKJ;OLJo=5HC$J~ylo076=INbi$xbiDd&AgtM z3B>svZUp0HF$lrB&xhwp4F>2xpszIg{qb9ILd;@FIEAN2!`~}k$t0%UzkgW95%AJ+ zf=t4LfBePir~NR%$XDy_?&~XCW`crsA#Zv|=H<jXzK5XVLGl~3g!}Nn69q4uCG>0U z5p&3(3h>%@2_u~85qJY02N})JfaLdgdC9^$p<xg_OL-s@NaV}YK(rS$*m9Cg>7=!K zYvOMh4}I^{BHX&~ZT<!5Rf;u7swVW-G43i@76@X1hS8q_ZmsCMZB;a-q15!^aGzmX zE5X5FD4yja{ULtn*c4nw9r<q<Ntn)$wQAgK)dHaJJRC0IaN@aQJ*Zi*+4bCUlu<V% zVv$j8j|5zg)a8~l#fmhk!l5sn)j#3Lxj%|6;k-6@*9Bnz>ho2rP8*@qbq~?<IOybu zi#n$&)0}$#NFO4cAZeoUhe8mKjuT2ZgUbJkB(0haT@4;02x8p!3K!7JaTl(Cc}38m z&w}W4eRan%%c80qlR937smWku1Q5Fs=mHC(Yr<@b2c5+vsvSiGRq>a@0_(f`r_f{S zjIALTRM9=OVYrm;+duSMNwt;=!r=O7y+aRO<kG=tZ>=F$`I-qIrk|yL*Z$_s5|7kk z&wSOA-{>A}yDOATXAf5zaIMS+7;{7E#-a#p25A0lzxitKW*r-hMCDs>^Z$rQQ`6ba zCfehw9!^J@Nu?RjnfDlt=f52Pa5kd?__f%7wIUwi9?XB4+(k4))=m+4`dVlkP9zIx z=M9-6>mOHH+p-q=;9NjW&(~(y-D)WG!gh;TOOW%yZZ&)=^u$`%k&hUq6kET^iyFr= z%ZVC?OK#@t(;9OcV>~WSU2Lxfwj9TNdAnhdboAnn4<RFgLu|Hs_FTx5zCl)>gqI_= zdqD(rw7}1@a8ry`h6ZVICok1OTH!bNANH{gcCaV{;<ISGl?8{Xn4%@KwK=}xepr+z zlbUH6RsJ3fyS}<P5jh|tMnpTMGg}SZ>+t;xa_BxDKZt#szj^ikzmSA%gsL7RM2eaE z5W+GAdYpCN=BclAEa5>WtcybMK+4eJd>(PixS{+;UP;?xZ$A-W=Vm6r^#r)zb(4Vy zob#TOXu|lZ#Mv-9k~lc&l7OvyVcfZQm9#^(^ntivv-pQ9J+#GG+!R>c`_olpSqmh{ ze+`_h_V|$9vb2U7-2gk(gysUraH+|L*#d@WV2CI?>@QZEHBa*xB4&UN6mae$mp5ja z8(uIB^U&xFxynu=(aac@Go27lG=PtcR&h_%7?(PO)U3_^H#`9*X?8#WYQTlEiLBN> zVCyY_>uwHgbeB5+o$WSY8BxI>lic}&&7x&AT~kbhkW6X0oLbCj`EQ)j#RpO`yD}f( zBX{}J(BNDD`ty@5$w2VrY8AVDr?cemW#SQ954$IxIR)`3Y}{*fUWS8;Y_0YGlf}`! zv9pZlX>sW;bRm}G>>6ASk;0A{Rl|w7;TD;sCrFerTNnl_fcr(Ho*U5Y1A$#yo(+uu z83@0xL;%AA7A%+bGLIJBqqIDATUIq@!)Yv28(D+@Z&iTaN8r;Cl5nM$S#V(8rgkfD zQ?D7p)#1*`<(m<CcQjgiinKZMSYzj}dG7~rRejzL$W)hTWJ=J@Xw*I|S4~lYPRJ_; zv!Dcl!u{tx@9p%h=pTaA6owL>9(yE6crk6i=K`UxV~`rphwAyd2%NBJ?VOCGxjmx3 z!Ma}+;(rrz67^<CEw$R{nWn|%Yxl;t*V_`B@W4i*6PIm$t$q%3mkmt64oHX2@7lA= z6)5Z4Lopw%Y?snN*KxoTkSA0IU1s!rxI*}=!x;k5ail;aEUfuVTI3(?**nro6TN`O zCEex}eP|8%mFMH-!1*7Spj0>_dSf&E({lzcJsReT&dcMScb7sgzK#0MS3n{XrYM$Z z0M~g<<!<V+3gh<`c+Uk=giwc{Z?>_KKB!b7*f?m>Ex23Keh03|t9c?!En)5jI=NTX zhGa7T5Rcs3xgV5JV^)`k6QOJz!QT55GAgfbwHd7uStFiv%t}=p#`MbY*XH3LpJYvr zNhNGCGccze5>^C%i1P1MnDI5GNHQ@LF7-z$j}%0pY~l8xs<l>l+aDP=yL!UYujfd$ z@2;S$5v+GV5g+l#jLBV))<zzaHHROKC>4#cyLADsCYA>ik<@I1Ofq>hozq)`>7Zu3 zcO-_qspdg0{w&>a@8vhXo|FaQpSBRl<!NHOIhTkml3;?X&{H4G{DYv-Xz^~?Z|9kF zm=i{OkavLXxvs_HhKQc!mR+jCXM*CBPK@8Mu+AWL;;6=j1mU~BAjL+OXXLHnhK6f+ zL<}AO%rG--XUl_)gZK#D{qQHzh^04k6;bI_!9RG^mhFtwy#4{e=J#3pyq*D4vAd+e zDBFzHgKwp~#t9*!)=k})e;>uI<NqV7{uQj`xy|SY!{xe~3yn}orqnSCeue%6od*+P zCz_AnolP1HnEe}-%Q8%_c`y--_0o7Hlj%85KV3(w?2hMZYHz}~4O}j;LXgE#wIQ&Q zekmvOHf<4ccAmDo%3q@AG=o>{eSJgX)2OxsGNyET#E?~Kg(`x0IsX=s7HM0hjx)~2 z&O+~3fTA8QZ~mcJvMve;!_torcNPX_oiStV3O^i=kT}|VDvkJFF5{+v@n<8i%7ut* zD)dabp53YH65a9VLC+!J@8F_eI=BjJ!C}F%csCE7yh%`E?WgprwSC&&IC!0>iG)e* zZoG1CY|Dnjh%X8d4ZXshVhqUSR;=Uq3MSzIvJ^I?pCWi;Go<K!%$`^ww|r3f);En< z%|kmxrVCwdaR#yQiv{HJpll5q7z{?M-b8tsvdf7D#uSFbi*fS%mm6tkDfxKnUyfcl zdu{n??sKAnaoDrfWV?>`wWEsOj|h>}=y+7VV{Z+4Bl!^<$^XhF#M<5TFD<bbaijo( z9c@4#)~#F8`T`PfuP@Xn^-1KmyO4_aw-6VTsnFKzJNoeq*glZs8v%r7Lg`c*)tXru zhFZtQxGv`39*5=7PKHg|&vX4y(=Fc^#2XFqW<qtZMMd8ffiK|j+z>`Nf1v2%4SIkl zx!p)}pJY0N>vqF&!Z6htonoeJ>Ha%cgR%%w^$YSVKYJx^=9=!Cn&Ux2U}7jbtE=X~ zWPUL^i*E?G|M_g*@3!ym|1G}DRH2QV8ST@gVo|6Zfkt}x;O=*&9KNntYPla+dYXN- zv=38H1m5N!0r8m+BNB2w9F@4pEj-nxR)83^Sl16@1||pzgHH`~BgKmOZzs>Au3CU! z4BXz*;Y3wUxcR=n1{P@($CS%Asnn@;&Cyz-d+7tuMq2ZM5wQf`P9{nlvG~cDxz>V_ z?FxP#{#>h*@9O{kN%hSIB%Dw1YYd+70=-nJcr~>{wtum<P{T3a;|gs3MRF8+>VC?_ z(ED0bfRrxD4~H36Clm|IBwz6Vo~VJcUyr*qrz0wR+nKaZK5xSNej#RIy-N|4NcO*q zgN{@4VN(%N^H3NFB>M3O71fbL*WZ;zjpYKnM8MP|sdRO|m-@RVB&Hj!@PR!Bu`lu^ z?e8iuFQ9Evg{KL70<-*UWD7?lQ!831o)$mQ*0|$kP-r}Dn!uO@Rv#-}WkF^ANqOV& zu$O!LX{?^=-V>z3f1^)j)TPs2s1>Zu)vi~WYka*?{tAg1k@TqQgG<^4FCVwWjOsz{ z1Bo2wrbRzU#ErCR1UbeA;4g)%`?4lH^jz$3HxKsG=eZzJihjod{k@aToK^S`f-)R$ z3`Z3c)=nOR=IQxy-XWcyBh~}7Mvn1}SeE*~%O#_#9nfR`Yy%h~eC=LfnsgIcA}OjO zyzQ?H{~${#r6r@&-qe<Oh9TP;+<!91r06q)Igv^RMQY>!&oTV3BDQS*h&-POYzH7K zX~O-=E!@!WAGFHNCmlX10$m8h;n~3sQ|cjZE^@Tju;Oy|v|6Q8Arh_h#^Ps9((?1b zT*4`{(9#`53mm96lZH-40>#rOle^Bm;I^+sePx<L0QrT;NB5E@(aY;@C#tro^&0$O zOs=XAIE2LpK>y+CBLm9lS0Zn8$4yL)^Co|=x)nzU0U_?ZRVN}#w|59%pCN#^T-U#5 zo?SPAG)!Sshn+vmEADiA$s6@Q%8-P+)aMIc{m4LOI0(1kJ&ciD>~}puZ#{|PTj(ph z9eLKJ^2q~He^W$FbA#O7vri+^-O2P~&6hg5`A~E8yoAX&$JVJ2zI}}bAN`}+Yaa_U z^S>^Y9=3`-`p4Bi24f+_)wI0e^kvc*VL`8W1N*q+Jg^`(axVU;F#<;9l3^Gswbq%x z)Vnj#T_`xDLLPT1gvYU4T~A703LO1BL&%$^5Q}mcGOq890<T?w+CfZ}r2+?9&|@To z!O>#JzJG6zq;Y;P>(^a{V8&&@o2@Vg`6I*GtB?U6(H<x^<fw-r&uB5<c%6};YZ09) zzFLn;BSh3$JCEC#_P2ep>7qS!$mp}+ipcfh4gSLxrq=js+D0C;A%M=Bq1r~<Eghq+ zs!UuJ(XHd@-Mgb`l6g%XXdb{-+$+5YCP%iJP3eg`%^bjgu5<sJ?h*;xz1L|Yy^#Ty z1^Ke7j?eT7c_1Om9jhjU*z<>Gpa7CW&mR9N$i7uot%~dcB2yBPIskN<efy8#Qxp>% z?xzIkJG;x9cX(lO2a}bUSQ<xsqOl(YYxD-G%-01y7G>=ZPoF=C7ey-h6LfS>+O5n& zGlAk+QJTKx`<?KcApBgL`OD)9#~CD=%>($qW~wIe`=#C)E8*wX>#rewyPLet5q@oA z6H_*O8m%KZU5tv;UZ|)OqmZE$4B_*XlSwlOdtU%FB#=(JL5<ISvzu4*=F~6c$k+W} zdlEP|#ph&~zPa^@DD%>)0Taq5)Su-E)F>JFZF?j5zn(1bv^K<8BVq^ExA!w60o)m^ zLEVPVq)J`M=<A2W9#vgganBa<ZuJf1(@ycH^5FKT`8VNl1jvN|WzBj3GM2`7ut)0# z6nime6AUCCPsw8SFl?LG`%hxX!Q{_QMRNl?5u%;&7ms&gjUSFEG!IRccsh(|Jd}R$ zv*_m}jXzj`xA#z(To7=PV=c=#Iwlp#0of`<G$<rUtx=Otrm4-UG;8GZObPQ3;;Bma ztR;U%6foX)G8@8}E#s9o+$+HW8^7){M1aX2=Hn9W3rc(Wuyys#5ZpzX6=>`NPl+i1 z{xg9$rT(M3P+(*>uUF|mB3N}}!e22nNcI9dncLQ!@AFgO%H6Z*-qS)rZ#*PsQCfQ9 z5Rozs#Cs&<Dr|rSq+7U3^#f$P#-9jfHFIX^6JYI&8`b4(lo0P@*iWvG56M}xJ)nWd zT#$>|RpW8=6sydk42#nq9?DydE!2{VF!N14<x@|Z1|E((V;sERS*w5-0|3b-&`Dnw z*^EKsqG*`=_CTp2t!FcCQDAZ4`2se%fG|d?Ihe7RVvkMBBwz?aG`iBwsMBktm=GE- z&=ype?t9{?z@U*NDPvFjf2kzA`iKdFshmDpwLmG;d&;K0Q$VQEV3;-AG$scRT@3Ne z%&2V_EVNeyp70?46Fq@&w_m<eN{_Z%-R-Tu^_2^<#A{sO*%cCC*-3yMplrnMPn3Vq zj&K9RCxY<L{s4cXoAt~YW>X{;NYBEMLpJ;-i1J%?B!1B&4=pdF0Wa%;;q((Ri^Z2i zKrR&>(rXNjpQj4VcRgvu0M$<_7*yja|L*No9g;o5@_4(^=6xM;G4~o%i;G&T&#%$% zfi*>{tke8stt2O(SXN@NNpxuKBWwd>!u>SnHOF$xXzN^vYQYEzP%kJa$bd+{Cvv15 z$WSeZGzoPb%s=jHW=UTpZY-`W$X;j0v<_np8FhCwabqMkiK56@VWijN_uX&q>@vHB zoMJed;aF5*c=^>ZMhKAirN&5Tmr=GN2vP1&sO?s6$nSsaLwe{6`3C?dI@Ip-ZG>ev zc~+25)8%q^{X4jqx5eU$N}?Vp3*2Z@qO8zhQX(xrwe(K`DCAWsK60A{x9mkeIb_4y zVe2LQ9z-c-nrKhM-KcDmOn*axQ*EB1q#W9d-vjo%U(8Lpy8URDK0nIscyP(843Ff3 z+lj*|+q00>@1hFT1_b#>HJ}$EY8r~9fPyLFS@-te>p^9YN1(*MF7A5A?K7|X-pimE zVslMfU+*TOxFonMiaGzE1-KIx6&;G;f=vgfGW#;ITb@4UamaG?voWHd<dF6-L~8=s zd1~xKfsKRU(;W<U;#~gGj&J($*nP@HL*ssGK~<x>wkZ#B`qJ2Sq)XB=8{bxgH`O%T z3U_ejdf;<uhUP$n+HVHb|JkZ9Q^Nz!q8GHT!TvlPCcCuEmf?2+;`J2jC-1+Ht__r1 zArXd!6=ol4$R=-!j^MV^%17PE{zbk6y%M33?>iajxm&y<JlH!UySFM6Y0b(Ed+Fl) z#Peub^TpjIqUEAKeo+};C#*_o$NJW$zFz%3!Cy@TPkv(J>vqHY{*q!o(j%R1GkEV) z$fiVBJx30S*&;tME9O_{d=e+!)0oU?nlw^056eB2(1^`N+zVU2AAnJSCQ26je)UEW z0#_Z1=ccyJ{vnujQ8Ek~gD;REM@EJzysZTDqT*F@Mmw{_0afV%Z&B_&%IzOYQO4rY zi1VnD<l5oSjh0V}L!@xxRVF~f`g`yF66EtWFS0sc@+3fgER!wA2Tv<HImI_S43E(w zfQ6(MFR{6goL@kyS(<6N+@$2eyySO1J5G$Uc?mUpZmu>TocU6$cm_ME(wJ|0)pt^U zfg!jG3!`F#s~-R72=Ymlf&Mudz3<1J`hScfe!w^Q>cIa9gR(%JK8YI7zg0y<ZSF88 z@bUN%Y}t$r`JjhWVs`ah*TKtKhZj5Z$d{fDJ^ctIQ|4hCL{tVpua);hZLj*=pcq0_ z5^S&0X4F>uU~Zy^3Wh-UuqTTeFSjS$8sxUeEgIKD`U`76cHqAl+gK!q<Ma6jioet? ze6xV9TB<LM_5%HN-kQm{2t|qBCOfJy`lW&!aNM8bVLl@#QgIICgQ03?sN)N$v#y~T zqX%;OR4TA~X`iqqgz`v<9d9N7eYbsTHIAO~*oVuc9D100J1kp6CJO$JIz;*}auV%v zs5>)Fy*R2#x{xZ-g#6llYxb~u&e$_k<<Z)yzw5^PX|TJ%o`>jTtufCE{1|DqUmC}k zE@w0~$9hg;`L<t6-Rn!7{ffrY!E?q5vA<`NP5ax;d;HYomvlR>A^S$L2l8o_`BbT& zhVz&l^fzgCB9h?rFdu$}r5^nz%|3=(1Pqlgj@W*KI}asC2l~go$w0!(8O!o1g6GxF z5V!|zM`+V3%&~K{Qca@YmXokMwkffrtTbhAa$gmX3+zpbbrJi$$?Qn-F68mm3gs6r z@&U)ReDWc3+O@;R{zRtSZrUtC+hChxtLSCKnu4L9GDH>nv-^GRx+@Rn`1^IW5FB5B z{e`!!T{q0Cx7J~)35pC^lN{S-#cIcISNm!Cve=Q#y(wP?pVF0s1P;aZD?dYE%vCWU zOcwOuQQ<7&%sVx|B99Vxi@$qdF7?D9gZ3-8{YO#2*8^N-?m(pqcM*O$RDrn;dUg+7 zPgJ@iJ)y7-F;szsu}jvJCn50j$EAV}Bv9K}ze+=u=H{_h_1%T_YYoy3K7zs1ka9gu zR$?T3u-lgEv)D1dL+9SEG<OCg6+~~7QRC=TXL{$}9DTZgG+7m!VPJiEHF(8o&d&Rv zBkB^$n}SNWuQrAqIqQw;>L_ui?S2a9<)ShlG6Wv7OjmkM|KY(7x+v5^Kl{V@uuG0X zSJ4#1|J=mbA{{kpPjd~<s=18{N4N>Tb_qi3IVMWxazyZbj&LW?ztHCOnrd}JAiuTp z!z)su)2Fmoso*zZ#WDx~*J64@8pLauHxiwUh~%9n*&MKJ@P%y4s7Vdwy`1$n@KL2M zX&?H7zgw+uN(idjvkv{lCJcuYp&zXSV0G3y&V~x?c6ge>-TtjYebSRk*4yH0ultjQ zP*soABsQ1B<DHmw<r2`t3*s@hB+=!Ah%@=Q3Q!cc1T*~L2^o-HBZD6nHGefDf*ZTA zmsuU<qbb(ImIs1acoZL}iT1ypQ4HRcQKVZ1|H0f4?7#~R(frXAVUApiw6ZLv{!>~6 zSJG;ua?ThuYU#r0_yj%IKBJSZ$Im0Sr80-e^rb3lnsVd|!==uzk{t37zE#d{voG?% zGpZx0!8;3XF?bXzHgL1n48`%3URyKX5++Q5dm&lx7D>`C16qg=NntjrSxiLMQxb*$ zj{EbZUI4KwwzJe$AZO;|_X<W3ZAWU`@+MrRunSc?>kn^J;Q>`oVTmkyClv6<Y5o;w zPLf3Ap{v6k8@F?vslujU;!v!>&u4`B5sqlIULJR|k4DT&Pjy*ldM1&+&EE=_Lv>bE zOg_0FmV!WteLc#nIx#IejsYlT0wQBl;#N*XF;pT63#t_J&M-E1xbw&lK5gMT17e<| zVB0x7C)$qpA~4<ik!R)uUEh?CYN?z|U%~J)FM>(fc=EJ!iwkI@tBo&B6p$A4oLk$e z)VI>co8QU8Mw2kB(>4yA;OnXBOif_a+$1JJt=qNNAC&Cc+?Au(g25E?j8tk|;uW-D zmU{g>NO4=NeQwF`w-jpdf*Ns$3z|k8lI{3N$_L6%KZriZBD#FA?!)axa+vScinCD0 zA_xRP+Aa#k`qEqWP!5R91jlb-*?Z)=%#$GP2y{k*NMVvh6UXzN9X;eZ&}t4NPyMUV zOtpZ(gFWj&GaBi3IscYabx#xEuJAYSdBVYDVw$00G*kZh>SL8pT|}bUr63{%Lvhv| zBC7L744R$^cXjDj=-}_Is3UaF7H{yRuQaKzJZ@7aVc$>(LFi?$n<Tu+H*L^ZicrV= zMt<pru(}dzkZc6}rC#wH)sy@7*fVR<c*49snp}e>bn?7+Fe1+#D_ccf#k@P~&eZK+ zF;nMHnQ`@EiM~J9NsK;eINh^?jqW?68faS(s0|93k<Yr^gsU$8{8-mKQ$wPjGZpV# zRPC9n#rwJXRl}WLSj_&T&SkHGo9$LnMPc5uG_hTgx(4s=^uyHV+$@|m$aIRq%ACZ; zj{&WGm0<COcCVjO6|A924Cn3XL#+%YK?3tZgr|-B)po{y5KZ*%36$IA7P?P|7;Nop z%}NdUX~|?JAwje~Y`XyU4^dE*dJE*NR4U;<<gZd+j71#SNuX2k6i<Y{)|S`VFGxfb z&yGO)hU|Y^Msf|eJMfa@K&*yz42WL9y7_qatvX3hGtH)Y9W1Q6n+Q{|&*}FS`Z9M= zx8n%?IjgmsS-W8jYQtqEoQ&fpMgz*#X$U7@gBP`H$G19CMICW`9US@<uj31`PDDT| z2Jzx-l$#IMywI7i|43H&a{ENr+i5<rsj+g=bdXzR4$PxYyQ>Lm8J8^C7X)bhJe_c8 zIEG|%Vl<Eny28Ukgfl(ho{u^@VEhxA9w3cylWG~@H6YTaGyPG1;plq_6EUdV++fS@ z<Mp1*c7NldjY`0YJ(7ACEJ;p8EMmR8^W43`di49A6oU<T7Is1+`ctso;kyVfOJ4Oh z+t-KKxBWHn3Y>86@$!K#n^#AwRiC^H7nvC5xq$}BShupnR$eBNvKImjMo*KFVl^k1 zjVHZ`086z_yr(A`<@A`B!_DHWw<WEJAc=3LVBemng0f}Y)js)+ROpSiq|dYF5T3`` zgtPO%x9Nz;7LzjI3(x$biHVKUEcZylY@H^}(~vTh7VPQr4?Q5j&VZFI_ETT8FBnF| zF$itNxcGc@AMzG_#SmQ6A-C=`y`#^`!S*`yI<g>gi?faTNnSDFI-%Ensd5$yn7Xs` z%vZMRPY0vss8N|IHD}$ZkImcbh*M+yKx7_?BZV`*!Xcr@A4KGDUNo)trTS2prG>j; z!r$iv<mVQz6xLHtarNBZ`bevTzQ>Qi-CHVEJ3&*(0+Xr8_ZZC?s##%Z%uUhL1kC&| z`@<h>D?IJ+PAOIJX|p_@&SFV-=xly7$J;yjL9W7Io18ahR+Pg9wN+o68Lq$MoRM+q z$8z`ssgjI#NoZ&&`S_C-#j9Mb)oJmMav$nkO@62&b}^PN<ayj_lD?;i!OM^B4SJi` zMuY}5H{l=Dlpbz~1V8^o+76tOI15RzX8VPmHQSu);nn`t-Hke-We<kDa~h0ZKbkRE zkl%N!n#|UJkhhA(g<OVF0&B2upd@*y6%U<KG1$_a__49Vo?dnh&QBUVZP$fNlUF<> z>Dm<HA{YTlGM4IhaDBJts7@&1>eLk_3Qp}Lp6w%oZ80Vqjbvi;R|RI;K1VD#aXqn9 zRadWd^K(ASA}Xy}dYZePr^@$tCcS4$A?&*Yu>}sMtm^eDr;Q;YQiuliqkvM$WZ4tF z#zk+hrw{m9H>~rYB1+fMXhpDwE>{X4&&Q+`KSk(>@<@wo@PI%3+HW`C63>#rF=jfp zzp+ZH&$N?UJ=bD7)#hm5Q%+TVMq8&+IK>PWk-wzfOb48-W7c%GkZaGGP|p|aK~(%j zmMEIT+;ps3cB2Q*&P%Ao#V&W|FY6NR%*o)7&&#0jxwWOYpr{T$tAgsvV#R8_QL13V zltH!{d}6>k=%E8adQP;9U^RxC=%_+i8i64o7~I3(m;O@OeEU2YQJ>^lgH;I%G3!qf zBilcQCP!uhayt5;gB^)x$>P{LIBlP6ES5zpd&xddK;&AYvr$b<3?n1qHuT3Uzu@sM zWTPU}TA>CDxIjkwTXHyP+;eMjy7v|LPiuxaIR~PFdFA){d?@@`5bT?kf`gyqPU%Bs z#xvpD6%Slm?A3k8*`vBiy@g)P27>kyNcR@m#DSywJ@rbqnaRI{Avj5I#*mXQ?>MAc zpGm1jurKr?cM{6%B5#(^#G0OnVMhO`MTZMRG&NC`p9`|q-K8V^V3zJGz}K0Z8ccld z4(b1lIopwB0P`YNG#hXpGS+-gjp{Tn55YX=c4Kf_(>Rj<Y(tB~=4He42f!^F=hhxy zm3301OBgp^g^@cFD8o<`GpbsNKMFMj14|$12{gtC9`yc$%`$fQn*o1NwZ#hYX?q5A zhu_vq-HA>Obyd+eFgFD|&O_TCB$Sge$^Af(&I`o`R&4rw!&1LC(R+Zy&zXMHCWxiL zmy6m`^S=Cp+PA{gLG0azlo%pzoUg6xU%ayPk#e<fg=Ka39XzXoK<6Y!)3lfZbIeXT z^#`S=gBc{0LAJySvF`<~YXN4(M%0eV4cWrEQ1-EsKu`YS+nHo;BcsCUNX1#{vO-;l zh#f}AjB{L$JFnDA&}JJJZ!jC7k|p|d!MvEETIWxq+yz49DBj{T$L62kcrdnSXbFLM z3x+6kb13fI7>hy?(6pH8kYO~c-a{tIGZm`-=5lA=cw(MVo>#c>+V`|~;xgM*F@0J1 zH&=*u{&#d&8-84X9)e^J_q#xhdB063r>=wRh%nyIgUN$>cF=oN1OJmHQpGi6PKNJv zLSA#xnR+WYu&_;fUWDaUjg-fJ#(F-kM@D!*PeOGN*miD~?Tjl(UN=x6yN$>D9ISZ6 zAFhF0&xn`w4o-M>TNlbJhX3t`yS-qu&Y&i>5MLQQzW*`b>XQ7aTV0~YB~4cgbQcoD z-lvI(>Kn${yL3n-ZBf8dOAiB$`>X$5Ps1g=F}#Q2nJS*{LYixq$}$&&lSLduO~_Pu zwhV{rP4;B;n$*&dxMmG6v!Ug9`&oxwLzC9(<b5W1reEPlh;=|g%8qV0jRH|!*5EBH zv%%e!*lGOwt4H1g!x2W!n{N2BnFsnHhf*Wn$oey?N+ZAv!o$$Hv%?t~Vd^}nsy9t! zuQwig2erbyq{B@3OMU~m9`m6>O^D%HfOOS<<;56footRUls}m%a@PnVH~!&M7?J!T zmLZTL*v*`}I1q<>*LZ}eE^#I8daG^91R~e7`+mMex`N*R@|1^DDPn=PM@w+B2`Y?! zb1*z(T~WOjjQz0Q$5Os#lCQyv0b<s%*x4u+#q*gl=<OQ-|7IN^wo@G>a<^*P?j?0b z>ULCI{#e-nwjz91MYURWWzohVfARI(A-3x6_b?K+4-uomAsoNr{Xpz&Ax1sk9V?kh z1BA&pr5f-p&21-Jyv;qxScswSU`J|tZz$B6Ig(;px=YS5M=sfdhHtZN3}fy&w99%L zHa}G=!*?b+W~nsGxvbzf%2s%-@SiUBa5axqLXeHG0u=ii#%vpdseC+bQ>Bmf5`s$C zg4y#0hs>b6|7<VY6P^Tlm$pEQguj0SmsV|CwfR;sJ4g!A>L^Uv<;@Gl^I;Xzv<lmA zyfYcHS#x?;Oz%0CJ};5G_S<)pH|m#H?y(AR^~z_l^;TS1OCET{61x1N(5KTLH2+o) zrp+NL2#LEHSF!7?JmK&E`b4qhxh_grT;)}98V<|mR%Md~|7DdN4Bkfg4eeIj$caRp zk|56*swnr@i&)iU%%s2SH(9m;Q5D%&)ybQ?7igR3LOdQ}+fL@Bz{hARAZmf9@$fxw z9U4%%y9oZ~t_C{cQ}*Rs3hd~h@RrdK=<`Nc`Hd?TiSww{#*f_`dt{%QmHRExerg9S zKM_j@XX*ymbMWiKpwG-171LI$bk;lA^le*)qW0&I!HwNyQ{;=H-t+TDexz6!IHT2q zwK_tE+y?i+CN*&M7Eea7%lu{P@nVB<WkXf`d^LakCDWoz&m%p_YgOx-YUOu<`<x$y zxutt|{rq>LLy5E5i*r14-cPksGJ@#0a#7gP7-gP-*bknO7K5X7ii#0lzt21RB@c8E z7jD-73Pk9W=u&!!_SfJpoX4m^6)&_pT>(p9<MV_NU~se<I%3gI3j5x~lFT{eiD#xG z^C6n_eA3>_+4HMtze;TJ_eyl{Xz$YvjAhBGv)|K#8f_{&AF-!|DMm^nbkaEB+G`UM zrL|6i;*Xe8>p;kr{8T;QFQyeReWj~PD!kuamrP+QrMXX*p$?+>{)d`je2zWC3q{Lj zY?Q63YEKcKebI==GcL@yGQT0Nx}>iN$B=CR38exqe;lo531ab6vzX$xTpV)~&^NYE zQG<|t;iz;3Wuj9XnjYZ23x(4xUseJ;t;r~8#%7dD)NP$y3<-6hGN;m=BA7-N4uAxX z$ibSMro?V18M~o;jEqp9e^|Q~EDuM!--hg5Tm?mU0nz4I9nPLWPvSxdluEI_{4|vT z|25T;1*Lc+yj)&@9Ic}$JCyX+o5Y*RT>P?<y}ier>p|h{*C}hco{C9g0{HQ&*fe7^ zF{I=H=YDXib1fsBZR6V-Sl1vTNXwJOtf;;~6!uI95gd*x5$Tnpe{pT2k>2Cq-?mkc z@7eE^@u95=+|GXo;R;9j7%ue&O9&op&M8zBh@<5!#SV9D6-j9F_I?*M^At+gid86o zj&>2Wp)uor&HkPTOlGN_m{FM)87~4N(J!E)V8uuc%jDklETSl9)w=m*JZr0Vf>C=T z)fT|dy5w5l*IDYWXnu?_OjJUVe@JR2TruZN9JO?<{KG2hSUA>RRk&E(jhlpk1Prv` zguFwqanKG_Zx<34f6N8C&(hbI+5}kow1y^6>1By`<n_B|NR4Hwp-azf9Yy<eb+!%} z-Ibx!*M2QU+3i8BENKKVuapo3?l6_|)R&s@BRA6h=`|avNwc34C1B(zjl9HviO;3S zL{n@zFv!)EgB2oB2e}`2hD6Gq+ce7I9e8L#I)~XLGOM074<~6nrHf0XXWCHae@eDB zUSkKyGai!-%+YY&eti~&cd~tC#!KH!WRp@Zd23}2>9tR7qs@B&6sC#Wr2=c=E-D*A zo?3owOWM9C+HWoyFt1_0C`Op{HSaGw@a%4_#ta>&z8VD%t_p=`a_N;J-O~5IbY{9B zY{D4_`miB%$Dz@EEZAWV<6LQ)d`0!44JXNJ42xD&V;*trE!^VSxkOQ5Ufdu!u!n?f z27EGAww}_9BJYX$;?42(6lrb87djn<Ntd+7<=4)efGU}ful(cPf4TlOVZJAG)|ELK zY$WY@&*zuuVsao7^29K~1DsWz)1zly^^q}^iUVJK<{l*c)#xtndAHlPsc;Ofji8Kp z`eo4a3{kguq0sFrreSuerm)SxP_wcv1zQ+$srT5OR&2>*WhdrpaA?tCfGd@1d&;bf z(%GPBRDFIWT^a6jzNLTi8Ru+Sg|z-jNwR6w^tQ4)pXm&)91P3p^+)V`r4Z4z>Ib0H zd^H)h#m#*Y{^0R#vcIAm%akooO|`O$r4~JqOWus5gBU2s*T3tMYW}|PSi3Sai4amR zM~HcsXehhN*Ynj5f7PTx^GK?`TYC=@fBSFc&`U^-+;Kqa*XEkpu3jz~)$p@)55ox* zD*-hf2Bvl-UJO%MRvg&EV{%iaveX!>v56aNSjltMeM+leV`>elO0wkm2Xp&qZKmJG z#-`--pukhgO!YUo!;>Z<nZdw~p}xX>f7R$O<xo(X^#-Jjd)6?Vij3R;ro-dMr2>Yq zUVBDYa3<8}Arva|WyAbosv&F!_ur<a5uwn@j6aS=!}3Gl1V8dZ<Zrbw6DXWnO<T3@ zS_9UAOeWf=>A2t%=A&ErDZnib7w7xwueEbA_$DfAp;g#1BdkiIk8N27oj>hZC(h_X z^W~)pw5Dr==Mq2KkFGZC+PZA*?t(qc+WNTWa<@2Rt3Oh%_s%HOm6yAEaAShBV63Ry z*dR_p*+gvdw_{3|<MIW8egL0GV^0OFZ}#2n1pns9Ih)7BPmtFW)nHNh3?pOi*Oeqc zD8!!=Il7Z2xojSu86lT)>_lK+Nt797`swmYo<M)OeuGUu!3%MR)`uqY0d`KtQP2+@ zc&rFw)9+MgB$-GpIx`^V5S=E+m{%G1{yPg50$O|)h0x)N#SuR&4pV&jRK4n&{l!wh z7M(+|MQXjLN<Vn|v27o@GYGC^)L!cMT{d&)SzQ)GWTdr9)m-RBfzR_W^|EHWt>rNa zdQ*6AANIM9>dYXEJ{XjB=erRi_qYPJhT@+h-$MSfZMH=Nnk_Dzh-~A+osDA-kzRb2 z)UwO1JbWGeM2$Gc8$6L5gq|+cDgLJ(U$2ome`xR(+Q`;ljS)Z2vkfMI5cdg%nA+@< zWJPL|`qH$2`23$Fe|9Uob4t7(;t$HDZ^|Y$J~1l4!TSzz%$SO0J}s#!t`txJN(ddL zN-I!LJcYb>l&697_j(Tdi1Dl7tY5#TA;w%E^{whwC5Gw=n??QsGlYHJHkxsPh?c<S z61nP^aaJy6pR~+go;okU!pK9cpY+WZ9E3%iQ8uV-QmiKK6ZZYQK`!PC%Xc|TlvemX z^rXMp3x-UO1eXk-h<&G<@9`TqWp{=p21m<s3daoWtJcF<^#HDrY{+mFVF9bfA{&-e ze++BJf5PMmAs|o&=TwMlTwdlE5z6`xVs=xH?JdrhB7ylDK;3b$U?&32%w!;k9eiU} z=PoP$<$1J10jP&xPMk5!`fN^R+b7~82Eari@wlr92!5`cCgiCbag(G#Ma2_6Pu%Fk zCJ2l&>=PE}9)#FRgQBGbqLt4gEWV{?>7opPeK`<2;L;c9QR6Kuo}hi+wcV%tQL3t8 zgqowr0tW0+R!K!%7C(^f%R;dvo+3G#e?<yxj}Z8`7w^@FJ*9^BUX<7VGGpnd2x*9B zWlGLh&SPFcCVG$QFw3DdU(Hpr%VYjh9Hb5Azr~V|p0mXrE&CM@%NrLNDxKU9HbLJl z);8?5R0JK?ikfkqqZl7*@fXmPxs5NM7aKXk9;3R*-hgnqt5#L?zMb(p&p4h^CFZ0G z3S}PmrxTn;zu3ls<CZCxrP~p?#94+T)E5gPIzQ$pxQk4se#uOKj>w-@1mynXGgLS& zt8iKRykhu{U+DTSAmAY6R!d`l4oQk#-SQu5LLg;as}FeOMX$rUO|=LYYw&ZHv+IWv zkQ~8~snW?UG4c)xFJ`pQu~JSctPv3s=(fqc<ZrNJ<s>2QNEC7J?dGaV-~KG%wLD%f z<q^?{bxg#_#U`liCydI3J9y|JDn3L8?EDsRilqzpvmzip9Lclgvk!wX%sA)JQcaZ> zuwZ-@_XC1OEY(pAfB!zXat5Isl%}}gU8WcLrFxY3h(n?Ox_Fi{;E+O!ix%e*D}+VX zV?Y|HS@J4tF&ccyGl9Fi=I7-Yh&Oh&WJL_uN}}h^scp&@HN?-I&2rlq^Ph2<w?H9h zRVyY1V?y#!GdMfs_w@Gg6*rs_3Rd09?iYF_AG#@*aM;3^#bRXXFQ&mZ6)p021zQ5W zh%`d&9i%wIlO+|9#+l5diezg=5uUQ*r98#FVU(HeQ9&j+mxDJ#vc&yhHTyj4vgp}@ zkARvVX{uCSl5`qt{h*&khDB{O#ZzyDlq2@jC=*GY6&NZ2{IB@n@|o;bB}$p%>ZYEP zxLz;+#xd+P1V~ekUiS_gTs<kehFf(UG%gvb$JY}ar}m)adypUsv;hRVO)Evc;@A3? z4WJhSLUfBZZ$8SV_0+*Aa<9;0P=Z*guca*`@AK<ghXs<84-OWG@h+>d!@WEo?f(}X z1LOQ6V*e_H2Ts9@TW8sSp)X{5@zRHYS>&|<Wxx;3@x{H9A#7kG1EJbvI>xiGWR)`U z%7+&Zn7;^OND}gwor`#lkntKrfeVPjc=yCs3?+gxP<F08P~5GT-gKKkzI|qFap7C0 z;M1!}reTT3eNn#iWCgS}jUfr_pFRx2|Jn0Yu2Hht0A#nTthWJ({fl6z=tWMFsh}gA zeP<z?ZAHDuFkcvL0XniiwzNNfeErNQzUiGq?+s}53pwbtf_@)#x<o>RK`epd+`?>P z16n|d_(2B*YLcV7&t^Q9dnx+uF1cq_*?99^@fpC+bE*_+Ga-+Y3-Xp}fOOdkB2}gw z49weDgavY#D`MX&oL)NuZy(=e!_l#JPKO$-W|P3EQ(9+ZFHQ%F#{d8U+DSw~RA)La zqW`^lbe+`<-ai!zf_Wmzkn4BYH|Y!8y54fAWF8|93)~Ldj1$WTf@)t$2(OlWmCK<f z%iyI*pA{)HWMw#<lF#Vqntb;7(!rl2+f?y@Lvw#tH)|GoEpTqrct!zA8Fi8z#j7&^ zP!L7gDS8Q8rAUpBFCQ@<J->A>`Zsktlr<QU5YmKw<G#pO)=ggJOms9NEuo|7Cs&U$ z3lJ&=5tmSwFkMa?<`Zg!q!%^$gs{6MpGeQfWU11z4~)_t!%ftR@+_O0#f~o@2!cB! zAsTf0eb8y4bsk&hi!@pDvEL7ShP`?WDj^|%5S*bTb}l{O*m4ki2b;w>7LX%;0B{XD zOz{c90;N`A4rpUoHfC+DQU>R8T#beW^E?OiT-qIAUEI2;DEb?(OEBwgwt(3JW($}t zV7eB#1Px~T1Y^F^CNKxIzp(HER|M;TdO$Q9f?3QKFk8TE0kZ|n7BE{tc?)O~`1Nl7 z)K}goam)}ihSWiWNa*kw8dgrQ2SBJ#Fs>R(Lvui@r={nYMlwAwHDC4%3lvE!c8c+U zk-R=)Kf_iwi`fEZ3z#inwt(3JCT#(8Kx@+OH!t370kZ|n7BE}DYyq<c%ogC^0{;h0 W_G1uprqZ4O0000<MNUMnLSTaZaIUQY literal 0 HcmV?d00001 diff --git a/docs/images/exemple_rigid_translation.png b/docs/images/exemple_rigid_translation.png new file mode 100644 index 0000000000000000000000000000000000000000..09dee2f269e1b37f5fcf3c0ad0b23c819616250e GIT binary patch literal 17538 zcmc(HXIPU>ur?ql<yBEsl&*+MZ=p+v0HK!z2%P|-CO{HGFLtFVO^P&W(vczp2C#vO z^b+YPNGBk@2%HBI@LbpV{e6GPlg;ivyR$R*%-p-nLp>d}leA2<WMpI~HPlrM$jB(# z$jHdgQXdCOx>A4C0w3fU12rYGq864ZGO`nlSXC3Oo413Lt34T)sPg_3mxz!f8iVB$ zRpAm5v2k}7uye9OdfK>Q1W@)^pa}Tg4Q=P-;AC&NUq?hpM1)^Rf?rt7NLZ9hR8a&3 z{1KKEkP;Px@7K3M+N1t<C?+5Tba2Di31x@IV}M5;BjAs)5Kt_t1Uvyhhy(5S9=*ju z+`xyTySuBsvAwOP6YzGhn5cw+s5nr3LsQ*ITZ>CX8F+Sea<K<K)a(&1=)ES&j-F^Y zpad)|Bq|^zASNU(Bp@sd0)8>Haj@}p`nMldJLF+SVG(hV07z<o&|dbQ7$-F9V2(gP zKnHuXx5wHb_e&+TJ$yVBoqcU|4NPr(Bs|oW9f2|K)xr9>+wa%0v-fgB0Ams15>*9c z{8yMj6{o-Av%_1dXyOq{I1?Dc%EnF?;iPT2UtI#`YUd(_MuPQ(g!Mc?Dozfr;+|R_ zBEZ5Z2@3(T1=~1E80%<5At<nmvKq+SOH^11s*P6{cZ3Uz``Ag?!@&rowu!E;9YPDI zqKNYF_4V}e)`s~?p`Epz6%|pcKu;J=go+PH!x;=hJJ{H{z`z(UVSQsTT-(vd(-`TX zq9H1#<m2jS3`|Q&(G+fLtce0^DI;KLQ3GcK2vpm^6YH+%jq?yTF&0)bl<<Y>xQaWv z+G}_#3whcCZSc-u2QbXmK@uq;Vv9$5!9+~-gcL<Ifwfb@;XO6I-CR5X-BSa3Lc9R! zDVeHDn!4NK(Vh<45DiC7DOGoSCsBJ}4VbSG-qBIZ-rW=o(@{t2`ao@Uj7&weBqTi{ zT8=0?cTKd7siUte1nsP14|B1@Y9JJ)5QeG{B_%rzNih*L+T91N?u-*s*VTl%p!MxU zZIGgBcs)rS4-pSfLl1qV7Y1#lsqTa|bd|uV;%$Y&`cPj76;mZF5}|=Yn@ac~O&x8F zabiZUCdMvM2@g*Zu$#UzM9tMf($)lxP;>`t8ybMzOdWk7s!B>mN=O%1FcK|}_7cZv z!@ad2I6XClC*BF9VdSJ|4+Wu(yxf8L+Gs0Dia~(~tUKP#5$df06GowQR8cybYO2bf zz#<ztD%%?R;5CedoDCtWaC<kTF-%X?R^1b)?kS|?=HUqjySpiScnKj@OeNgyg|NaJ zzPg&i`l?Vv4=o{62_!_-RvYZ8XXELtr0y)@V(OzWWsA|5fC2A>I~zIMAmI*TQl9$W zNGU@bC`u9`sRI@P3E`0LXm^kh(oNAs-_8}I?W8QFqzyqU3TY}SiKsb97>Gf%?GZ?C zSA@PgNJ9uAt_Fn(t7)T=YA`^F9DR%oz3q@bwkSPSA+!^q2w)9w7{bQ@p@G2*tJ$dv z!|`a8k%OWR&Q{S@S=|%4r(j?-#K%`1_|y`1(NXtu5H>)$!NlC0ynr$#F*`dkd#IAO zp|6{!q>hihlcI{ZjSvDDkFt@57|vKj-$U0~2(DoY0?<QAN=r>uNln>aQ$o~67osBN zpooNlpqjuh4kp4vB9d4q3`_%NgZ0pJLxR+hP+<cx;02O8Dp(goNikznFBNA|cO#U$ zx4o3DmZZH3R9Q?4zNfRwE+&p>B`+8f<Ee}k_jGsj(AV?Tb#hR%)6vxt*RhchhTx2a z-H@)59%5<$mMDqo>exx>xI$32C_6ipqKBK4kfVyYq%8z5E@G#s?kWxvR#nl5+N(K; zp#d}lI|6N#L{#-bNRYm!imw|8fj0zUjlA`>P*4{n%3EF22B@K;4FT#(`2deNQxkh1 zh>ABFs;Vieh=%Cxbpk>vqTP*!Kt@n;N31YH6wrG`V;sUA;;w1r<_lJJ0V;_CjrBA< z>>!TXO72i2qz@G9Y-F!*qHKf&AV|qU2?ByBqV0f330p}!Tcjb*#M@C^!dpw&0B2w- z<e=dpqOXsa6w!hkp+%(JVXA0dl#`f&9tMR`!66_pAAJdBVc<PR9`0TmszOpal48!l zS34;UI}Ig}y1k^T7RuelP+#B8*GNy%!QI`!(N##xSHuYn0oh7meeG48-0(i)q8f0J zfxRYFOTx<q2hvrA=$Qzq+BqR?Jy1|JILr$epS!Z6kcTrMZLl^HB%*KcA}p!oq37)2 zA!+P^(-M}{v_n80MDe2H@Vz?Th&^l;-4pf!9{&Mn;QL=6D5~1WA@PiijDt)=MbXIH za&GVh77DFx{54#gt||BkdnQKj+|1;+`gig4M&~GASf^8#Jiifv=J4Pf{rZg=s-h4Q zeCx5T;@crTeJ36sRRzUI!Rk$e=((gjG#5V+Xt>v&&6~QwIPmiUtGi{V(c1&_1DG&L zdId6a%D;a&T*(={G?}ghlTlD}?EeX-ZZoGm_yQEGa3};vkcDRdQ$(Lub^M=R9w-Ep zv65fVK6BJDhXUs0-~RS`rVk+_m!{xL{O3Ii!Q)Iv^%XcM$SJUtCLq<Lu?3Sgi~Tb$ z1xgCaN$L{EM@K^?BTsZWs!tX|O-bE$#=8C7;q=JJDL}-3>QkJdrcdLnf6je4TQUkt z$D)7gQ(mFxP*4k2H9U|I&_5uMWB<(l|DixGnuLn_-gL4<$1J<0nWrK0bqtAY-`q4D zA|IB%s?3zIm3Inwsi8r0PZ*?qv>?y5fc0p&#os*J`?ha{Pvd-;{_wZgUEDr3{C))F z?UA98n;MPqjQ+k4S#oC@N<fN-GJK!}tir|6SJpaDd7!pD1g?a-Pw^UsquDE;``w%z z)?5n3GVCgPC@Cfy8?-I{kGAoluOvBtp*RPx=bt}uZ|vixhn?YF%@EPP4>?|^G3tqz z4;NG=9Z-p{s%CM$Gk4OOeYFkv5wrE*UQaQY6SERzlX|Te_%C(0&aXxY-OssnxLgV` zzyiKEzmXJm*2H%+%9zU{2A|{O1hx(0mF4Q4*SbrX_-HAKLBuO}{CBvj9JEw`Uhwt( z`1&C!yqmKW9_z>47!^h;*2s>I^~uxzU7mF1V#GfRu73kidF%GYfui>M!G@O-ybB&$ z^|jo&kAy>-Y)7+OBCRF=QRP1~d8gX6{Vpxjw8zoXQ4Q|(HliSTBDK%HC4%~XhSWd9 zrvdcOyd*2(A)%nVEDELx=blpH-OkYVpFVcxlq%*>>q2gvThI>n5>)n>G3@H+i))#K zH<AR_UfD%FEm!M6lQS$;!aNLXAH7>aemT<3Gqmg16a+u3KNB?Vmk#u8qz>Qdy4jjf z7(~9Qu6dERtah-{&(-T0$)zWt10-m_$hEeYpK986{VMQK%RyFEV;RFkD?D{OSdap{ zN-Aq<S}k1)t)@$6_=NoI%uq~{`_K5Y@}Y_AUme*XOUAEB;Vm9j(-A<j9x-B&DB);$ zqxKAg>P)lI5jH%!0aPXIk}yTEv6{9}t2xV>=8v5c{GVrspgm!6Mnj1TmEs<TgP1g_ zBbD~QGBQP$JWRsa;L{nAS8I`(WuBX68qs?OkPH~W<`_I(>ri;)Ysu1rykm7+=C3U# zxu#?rK7X6JIv3aOYW8{6t<z)EOK?k{`EXI{Q>kt;r=70YGXG}bD8O;l3*}xhVXqTM z0mgreFQvWj4RByg3}rvmu{0ryl>gek&&ie1S;W)blRH?G;9;tpjA@*E)%)h3%CB%9 z7{C)cZvh3hS6g2NuwzgElRcbj5S=%V0=w<nhK~kuj1M;?KX11Eyf(RQ`01JM!^S&j z7L0;hkU%8_1@}u2Lu0<r>R3T}{h4*6GEf;()a5p}k5WbEr(vDR)TTR-BjI~e-DF5R z{ViaK@fn7$nK=y;gtvYS%p~aI!GOsqsA#;eDNM}D6@MD^kSkgEO@WnDtTvrl?>a@5 z{_9AWgM+AUo=K~V_c3jT#PW1wE1g+fxlf-@TRJ|KEQ3c$<<1oF?+~uOU^$f0h#o}> zb=!A74@q+AXC98X4}p0EO-@l>M@*eQ8t9dC01Q)uj|_r5h>kvOo3LXPdDx784?>iL z5)Z{fy>1pvHaEYL<9oPTA=G=ef2;jy6!pUtwKQ#rmfu||AnRK?H6*9uuGx9bq{Eko z{5Z3q8n5+a&N|CyMR&vCww%j+XkzGur;X8Jx8zoLKA-Eghe;3dS3Zf*cp^2)OjmXF za1kl#C1Zjoj$uh84BH(d=}A?56UCtz$U@#xuU}S}?+<99vSq9mdP*B`)bLqw&M~Z9 zO>0$tivWlyf2gDi>6CBS(ss-D^d-HBLHY<t$Edx<_Y@`p(9)p80fs2ic}pp<V}asH zB`ZO!%7Nwk3yypSyaP$JrmePanf%ZN(_SCxCbJmXE5BP~J$d&)%Ig;O7;@=bgGjIR z?Z6eo!x8CGlM5c7EWxKP%_<QgPkIfg<*N_jfO=i4-jG~cRs1akbHzfLQ#SPq#w~N( z@o4Qv<jHlZChdC9M<ueAgeh_smUjsM<RNtoS)9j1@~{d?1aMxXK>6+txt{QW5a@G* zk$^JRv<gVp3{JY-?l=Z!GRhrCZ*IjUUQ=CF<Q<HXP%oonoyt=7I}k*DDn$xSn~zuO z8r8%A>(B3{oX0xq2gs6Zx=v6!0aMyQ2j?AVUC0AUK%+5UsYoX7!8u8GZ(eZeta=rh zg-hs8ZB<XIbIZvNaAE_Y?Tm#y2z)5e>mv`zlKGg?nWs;AonE5u)dxeQO@do2R?d{l z?r@7X<BiFwj#TsxKTzF5uj0ME+KEi^SQm7UMUwN@^YL3+>qk18=1x&d9sRj9Lp4}n z;JlLH!EDGvwkiG3q^W(15H{HTf)k%A3di~DixQ8lQsEc%`W3BHPg$8CZ=OjDow#Cq zsI>LEK&Ne=OA%Zv`3Cstd)r@5m8S~0J0F34B>?uz)V&_yX|pU6_~ceak)X5O03+?_ zk+#{<{pmhHoWsH@YY2R@ABf|A9J&?y8*ldfMd@rAE!Cuzn5#0uHs8k;`SEy`w@cS$ z4pz59rcW;dzdya7@{vo=l~K_{JKp2W4RZ3CXzkduX=CT8IrPp_z-GeQ`_jr=Oqz#z z?FSwgWpQ~pTa7(9Q#u-swTR^m>MmKiFRu`((-tnm#F6jC_0sX#u|wnHU?<Ngwimm` zt*v`LC-To&Fr@RtYAjWX_#*kmlJ1+=6t@ep_cP;APk5mD84WoN`JbJVp@cvTG&i6; zuM5S2p!isIFD(4P0KAo~*XGTZKQ9FlCD1y0J*4FH#Az1HbEf1j4YkUdv^*ShzGpKh zG#4y8_pKZzBVN?mV-?tzM|BCl?NsfB>W`mUNG@Q5K#1`_f~8z-N+qx1UpEXerbYIp z$pmrx2D35efK7#&oH8jT8h!b7+G(B+rz2XYJYHvil{`S@;9|-ieqS~8PR@NV*BvRN zwRX4GPN~~!c@CrBN?2=y@QJm)8<*WoYB{<Z)t#<s-rht`=aihF$w>dRqBP*@@dp__ zGc8sTJO<5(>PcD`v5ub(mG6H)b=fJ5n^-$_JMr4VyT~XuX!yKs?#QM3q9-%*)Wo}c zkEI$!cPeeg+?B3PlF(q+y_n6K)Kj&?9M+yjj#)NHKi-sM_~hN#_e2$s$Y{Q;H<@y3 zT~@_1K?454rv_*EWT(daXTKInBilst%tPm?FRX0}%l)-#Z=-rRVcSkVV5!0T^Tmn? z<`<%yas{5}c^Iok<X`<Rz^7g+IM3elm31cjJq}%7Oo8p*oWZGGKDIpBQf&b~U3Fe^ zJMlz!ZGXuXLB3;$2o!iBeoY-6Ac6LLF!JM!Q~LZ9RubZSSkO%L#QYbw9%n~`YBqss zsXxY~12UM;Q`>zm)6*UKdR&-hvnH0!{Tp)C&uC77Q1OCv6gK(uFRYFdXOgN~bIr3j z&!tA?Zo0K_i$@k)`Dn36Fh?;z-xcJRl_8#AeITiIVO1roSJ2ceDl?ysA*~S$({%xT zY~Gz!)Xm5J9_iq_i#bFEeZdmPmgr6Eug!USS=DDrL7F(TX9lxk{GYwS^WkqUW7!bh zE(+Dz7gjUn=-T9GB5-Q=EtWn}CbK;rdTK;kcG<~V9rS#)OP8-Le}EPB6BIKS2!-V} zt*5!K-W1YRtCX$$pmL$bTWC4{riS0`4%6Em%NjO1Y+mtvUq|e-TB&<KgRAr4w^PLc zwwBx%i|=k@-&8lqhb3=L4J0+h#d^k{IE3O@3Ynn(G^b;c#G<(*C_E{8{${ULlO_Aa z@7i8{9prxrS^Q6IH?JsMZ>r^(`r>@D$7!<fxJ~y>X~lG6kc4D9Vsf{lKIFj0IP^dv zVPl~yofE}(YxyQ?K_+muzTM>F3ae&J4tr`$cI}fE&H|xJQ)%{v+tj^`;a&Og_c*5N z>=80q9!1$OQ1`_Ql&+vbVMAdPT;uDB12}lVL%!xZ?i0DJ|C32AuW=F${r-R{OMJIE z|EXicNjLk#*jV3FTAk(U*G9|82ry+L=%!tBD;8FGag7a^ds%nj!I;5w{)0(Bt_$`{ z*O*R&^$`&H0xWTP<4C+9F0U9VpMARVUdq>(;!SyTBUranc!NJcOX6md%@>2`r^~ZS zD@2kC^hF@f{*Y%s3`E}HGFcCL4X#(D^h{kd@2f<yND{urco**Qb;`2)VhyT~->V4* zdg8RpVaioo0lVO~E>kSO@J@E7*zEd_!&jm}P7Fnyb4Ss`;+b!y<ILLZUGQtyz=VeF z7o5`|K2e<{WB#6H=DvI53?<SPLDh0}NY5SGws7L)YIpc4_)<J2!8NOBPM}H^xf;aB zBHwptMbs=xBP&}1osS}|+G#A%#7o5cmec0h5vLo6_NGl52k~-iTf9$rwg<EYHNrPv zZtjhc@*^|%AmQZ17Z3S7gK*#P>+Q!6RzzWhgMv9uu<h&RoV%9so<A}9%JNNp-`NV+ zZ0iu^_=$O1_2jLb+<HInfIUB#&6Ml6a!r0}6&k)&=%aOO+%)&SQvh3=#-Q@)Z{vr- z3;m5-_4&J6ZF#z#$}+8}6V(N5R$9AH<&wQC!$3g_iP9H9x>i(^Oxl4RZX1-7FKMRf zW5%I*Fg0V{P1BHgPpYba0^9n_l&^NH;ewXKM(25q4d*}4oHwksO<19InCl)JTB*SF zgV*l9TZ-;D@2kH2_LLPR5XMYJRd+j9!z&A27jqKT@cMZL)u{uc?9waKeoeDKM1&8F zk^@dD#}stGHgV%|pM|svfH9e0b^YGbaV~Fk`Eg}TX<%X|x5#9byzV_I`Xs0jIa}~5 zWOhPsX8NHEG^?lGJ}@MK<3Mrr;;2ejXFD?UBfCiQuW~0Q=Z&@}5lxF&WlaA|pX6(6 zPV}3Yw!FbKEdS!lspVR-LDyK6Sv$6lby7chrCgYag;_#x;y*UiamJ@Khs=z<#Rvdz zQ*({Q#u?GO+3S9m{4<?{5_JF$XJ#d2*cGN+iZ5dJXHAQ?w~E60G&|&j#)8RYr4^H| zc31!S)e6no(9kcd*E%F&Zsb!44ttgcZhxoSc3XE9lO<@HCXc6%SNys!xZJ^iy=EA# z12J^7Ix%^sRFFB>r5OQp`V_g_AHvpYDqGkdlL1f8)!f}u?BWw(I1E+3<kfGY<$4Oz zkuRJF8>Ynq?}pLDbmxxC6dRKy4eR)})En}M!C39);wOT&D(iJ*1Ow$j*H^{k?KFw} zxlLBlDSG{PlAb$zB=8-I^8(elY=_!#b5dq!v5($d%}L%+!<%EzE;RcXu!mLkRwP8n zWNZ2}0~1F=stX*JVwo0|z5aObw-*b&f=Em6jzjY-C8jUL(;Nc3y@oaMm3Cs+){O*( zu%f`gLLQjRqy@dbQ{Psz{X~zI*sr`<#%Ze3uGc}?fzs}!fxRIq_L-V4;#TRG<yjc= z0F_6*>_9ZP>U7<GKM+d$PfGmgN{M^J?ai@`x|!EYTQA-}o(L5&%3V#~nrGYmPB2>2 zn!Kzr<@=RLUfuJO7dx}o3qblU%jmA$(YfgE()ZA;YV~J_5$D3KdQFK+Vgq}fkvZfZ zQ|ej93a$W&U8-ikb>}rugv9ae{Aj^rKw!rkC6J4ojjUeT8h7~PA^Ls@6(y8voX_uh z)JNs;;~<DoFs1*ty>&r*(v%mw)vzKODA<W+<NM@7Ty6HPHC~;&F7qX~=do#TmGIg^ z6F*B?cvluIlpQy-IPT!exIzmjd@I?$JMBNuOm%7TpXipHVz^F58wi7Pn4Y!i)2!8< zU$LBeFW8ZI7c-bdQw&MWU<_bM3u-HDiWJK@3+h!jt|CIJiJG2AkakXcB>DQ5OYh7m zc2jKEU<-vm?^Ytxwl!nS)_s2z6&-7NF+Mv#fDu^d33bSe!Nn7Ui-Rv6u(x_N^PWmN zCpe4Wto@JgjNu{pJU1KpI0MA+_n_6k+o|&Uf5c1*fIH&EhHv1kd5s(IWrA3zY5<!S zZ&pussr+pTwKaQo@xSRNXEkxdVq{R*=Ep3u1AIs;r+QViWodY#T<<QY^JE`)64z*W z&7GWOS#W<(u^vp}`l*z{V$WoPz6H6l_7IuHuh$nOE@tGIdA)|SqEn6fh|Cj*(fD&q z>#2OiGO1HTdUYVBdL)8d-%1xnPSRi@J!C0mdKOdkq?Q&)2&STbxUjDgcvy+=1}Ou7 z0%0YOI4TW!AztagvxIb<jo+GA*<KjJCgYdNq<5arXu2@n-+rShqBcc99<TDS(t>o> zPOxp+pOAj9?tzOiD|*yeVa}DSQJGT<o6B}PEdx4sh%vQiOJEGX-En?l7O9_SfXI2( z?DrdYS9q1WD9UvLVj3Hhon6}(!ge`{H7(Mr=n=nJo@aALmtRM#rHQfgq2M9V5#qc& zv8giUd15%6+heT5AX(GnnZLpO<|d*^kOz&MU76Z^oBW<p2AE|+lt2;YH$Ly%;_J2~ zj{#=Se~9o$*B<-rV#@1kx2$OsxPQU7O|vzdEuzOA<IsBvk#YEPrF3Df;l~S&Qy+Lq zT~<Zg`1Ya;zK3Q`J(=-Kd8Pa7eH?s#3uo|SFoj{m`<=z+VwN6CO9Rp=TT9o5GYiP4 z<&Pk4RO-S)Pi>Kotqmv{(jTIa0Y&kk-$PiSh#KRNm_>8zG|V7}|K$>2(3UD;r40%! zn&9=U8QS4JZ$rF_%VXXu<YDo9Q!Tp^>nw3{kiO-gV2U!NOYvpjVy6hsZ;`hfHBRua zaQaD1^cbblar7}rgl}F`h<qF{sLt3Oz739zK<5OC;u*h-r1Kt(CODX(<Sk$L3|x4* zY`#eb@PE&*+ce+`(?*75`(m@0B#_Se0It3kRH)nmt66<BG`_iW_d4U#=Z6Xtb?#HZ zF`I7Ar0Fk6<Cw8r&1G}JLC+}hof19q7oEo)97F!(X3S9n1^vDW5jE2&T=mw^v#Jwz z2M7|(NHx&OJz&VgR8gn?Yps^_@vO2KVW<8l{MUCas!Y;$C+IyRx$m7>b50Ar;%1TL zn|5I>vs(|4jPdV|hH=&eG(i&}G=8B%<F!7LOV$*S>aQjL^;x$~-<}N88~nAbsXAbF zCS=#|^<5h<`mykg{vcLaNUYz=Kz03C&RHRn>%MSfoFC6u#iVqdK%l%@Z?PqS)NTVo zO0@lO3^tJPN;7t0cFoz>_ZG3pYWk2;hnRC9ysvMUFP!|iyCfziooo0owJuZV^<p%L z;Du&fJO1t~xznRH)nK;ETX9dMtH}m=`86w&Uh#9ITMh{_Z<sY?7*X!FO}pZ|ss@!Q zO+d~JlzTpL7`W)GGF+Mo`nU;jhP|kVn}P1-Jg~x_y;Rvkhmev<nL>CI1%wKV%bc^% zegg6Oihpq*Dbg&e!>Fl@e3PwLrl3paMum{U&jGqzfBRf7x~V%u9j5r0uAd)$4n#?g zrZHje`le}Xr=_rsMEc~v_RqWI=M?5D^a9rp9RfHaRj(JZ_cZe?+aRz4fn*tTX%|OD ze!|v9ekG((AUYAZfC@Ld_c!9dZ?%_HgVK@wP|4@nMak703#n;g;gY#)`he;BQc>j1 z=aMB~ks(4DCFiG4W~~x6_yyu>HKT_D^rR;Qa_w)G|Asn!$8_|F_40Q9rpRp_5P1dR z0wtec%A#Q{JBGb)cMD7N62r7Fh3A$dYgR!WbVRY9GdSj{ya||EfGpK{p#XPgH%o#_ z!;3<ISSp>pAJyXiF?H+o)NjAtMxk9cr@%*DZ?^?Eg6e`?UN5%<^ai1^_qtlcN8Tfp zPB?w+@4Z{YF}MTI-4>I(lV<l<;M8W;O}b4n(l=mY%oPSdK4sagh4$Plo0m407YsBO zPg?>wCPTaH)mzDfx3Ec9D(0$oJ6QM>YG9$+5K&+IO8lCtm7FmAX~n`)%i!G>8Kq{2 z-rcu~j|JZF%I-5&3#Ik<e$s(3pPcfDi$=JBF+;(pOnGxFTQ$xf)ynJ&iymwOvg_~r zY0aA;kdbA0{I}2csq<+TGp!Bkn5Z$fh(hKI8Y=@2<YX2}N(`9+uhwHi|E!C`Wy+pF zSt}<z-srX$Ys^CZ8>KLM3yX2t0kh%e)L9BFT99%wvS9h?x27yM!EK+*;(^z-=LNQZ zXBq9P<ZfYeb(-WWlf3ShFWcv~TV)2as}gUqMf8qW(rG`IV<`>Whp1o)Dp){bw()MS zs<w`1+eglE@3K!fp@eM}t349nQhu#IJ786V7()tT-E}c3m)(jaTw(dbhJ0~O4gdF2 znyuZy?yZjXGA@S4QH0&AasGmfx95~57&FZ*c%XSx8$rD19{km_6KB?Ul5>5R>Im4` zDp}lHR>Pa~%R`^u!lQ%@O7(Ym=Fjy8!kEk?VAUR<cV@<GSte_*dY8Np_}muID>VPh z$YqL{)xm|xir(_skzO|pp#t7BH}Y=jQY8dAp!9fkI9BQ7K47T>$!`umWw!Wly6l@W z_Wot%^h|Fg;QO!U;ei=l*QoB375h;-v1(Ph+ZF5OdUG8P%jF#0nAu5ft=54{Dmr&V zr<bknuD-f$y0tqnkAM5Se{8jvD84@7af(G^d5xk$#w1lfSuoXSo+y#JG1h`>qIGJG zSlB&DpZUJ>IoCdZTb^CtjBQ;0{`#^reyUKqY&gS`hkqC@mm;KPRlCf-)?4Cux(yAH z-mP!!srq8@?gigR(tPyVORtnV+Ea!hvCd<&D#KrNmTj)sU;Jx7N+U~7Yff*+zDrj% z%44UyeNxz2&X+~{M-{=0%bwi3e@2v3UQuI3J&r$)%%UjDs4)H9gU_|srI$ssM^d-? zRNAiNXZ3~^yeE3ma(8Dj*4m`ss0kl~>rTX;TgHz^%uCMj?*k2>+l;xVCp$HEbE41A z_c#&e*F1C6`{WY5D=+BmKBa5JtN8^B#F<IzyoOf~gwK|}C%87qE*7V~CxkT&?tXnr zO&9g!@2<fcUVv3$09X}%=l-7#+qnACA%0L!>6+Sb=0_*ps>W}FEZyXZf@j!jU2qc@ zrd}eht}R*L_w#+|SM|v6GwlJ{v2JGF%iKDhe0?*wTQvYjY975ADZKk~W_d1&VIcoa zap*MJ9PCl!H`bJy6}_5P%8B=guQ&FU!dqix3!gL9yt~}>a$>oS3a_(b;Iz@R*ictJ z)p*)6Dz;iJAXw)K|AH#d{Lt2!uTRLxSWoVq1rV&t(R`iUiP?!{%w_S0vbe4#jLdHA znkj_rcYF?R-JLV#yOK&%>+=KxUi`Q@wL}~UH4<1=3Km#^4pCWL3Ji)}3)vgat)h!^ z2QgtC;mcO6Olyarro4Nkq@2w3vGN*!0FB_em0OrfZiD`m?^a!Zfk-~R61(wXVaqq` zC!#r%pEt{4!hU#kpy0MKPsXXgV0S|x<YW`0<M`uFqvD@V)0>~Jf5at<h?2sRbh@(7 zTUF&`Cr>^ko3o3ymyf~T+rk94-fhv9pU0#!CtqH{aIVj~3r2YCa!PKwe&=TV<99=@ z(7KuujB;<A<vWa;aLHlndDBBBy-a82vaB#}TR+w8O<89W$mReHoq$hKtW6wxhX`k0 zXu;*VP3=wlCr93)Y2Q1PzBc+OpEKb1K6F>>8Tnri|K@7RHnH3HSM{|#c=5v`mbwnj zte<90AM&T2fZPl!r>W-4qcCx2G9AW562U6+n!c>YlH8{X(y1!Oj&`O(-cZ!MLia2Y zobzof`l`o2hNm?8tUmhkrH^2Eembvof&xpL9^~}9Un3}eqk>vJwqPI>k+~R~)yH2t zkC&S{)mkh@br>6eyh1-vV>Vh1Gt%04G`+RhVk@O)dI=O?p*AXzKhiOlk|~up(n}V= zu^ttsG80Jr{Y*d4qylDYdV2gY0#qrif8F$jH@?Dn+hI<hBip>IN5Aa@2H(%+wwG!T zQ%z>TPa6YKIi2T$tpL^+LP2TyrZ)E#+9ZoN)hr9(wf%Zr-s4l9$K7&jHZK5y(p8`( z56(A#YKkVs!kSk3U<(8S;Rsk)g_pS(Ne@dHpVa+Nw()Ir<Kl+kWa0hdxC#hsd=VQE zW10H3!ukayd^|n4X%Awo8yX>N;Gs0GORbZCiP5N=xQ8h&Z|Od7`cKOby1bcZj?exM zv^MJz?@9<@=hnyS97GY+-ul+<vyCfnznOKfMwu-WcOrdWe$e}qAMSDDt_p+`Ej@O? zsJpFZ^>b>hR%a;;FCGNBdIl8v@=Zn#kT*=Jo-YAbPIJ1PD=_6LTFSI;XW{Ox4y)r? zQw%_3uHwLaUbfxmAHGXnK4?557E(A<OY9=&Hv+Z}R#>(O#4r8Et?MLc1wdl;>FZS7 z``U2<XuQ_=)u=9^Mz*H@+~KfeVuDXP+)bgH3tSDdFV^D7&eXB6o#?F%%(9&A*D8fS zjVU@#`T)#%UM@Nhr5ljdr`;cW@#b}<1A)Kcc?`rCW`Xc*QY#+}U_E7x$93t3^%@p* z1VF9qkFz6cPqs~*4p8K8sp-JbX(=8A)e0JPZ@h-H;2XbY+wfl#lY1*Nb**M6%%1I( z53%Di`n}kqL24R6<Lj2fT0vE-Z*5OZ93BP=CQ==cS2}g$iWT$XUok%eg~lED6PGe; z?jrU$^;NfE)IP^~v$Fo&oxg6FI;On7l-MwxoO66~ovygkr!q`%s*`bRLnKPDM>n-@ zJcT^qb3Lf}ms@a=`O=M*lx57z+Zc+!Afr$}L%|$m^5Q8<N~0pNTz@Tx(WhwOp>cP2 zOCj@lz8u8y<__Ar<CD;+M6BPmOE;>o2NU|g=Bzbos#y~>{Cp@nXpaewTb>G?^Jg~p z&w7fIZV%r@7$hc6q<o6h{qC*b5sN&{mfPcTEcE2Fkb|8;@;d4_8^e~HKrAusK7)}a z-ExsNT#fqr#CJa7Es5?<boBU(%AjM*ow>K|m$jNs8SjxSvSsz>ZXF6Bu3iEiM(o#J zhK6GNrhdx|SY}B?_?%wr!7p8}5u`t*10kvpAD`UFFwhO7IV1;`8>S7Y4s=fM5k<d5 zK}RT20t%1=(|x%~njY8guXP!2iV<H~1sZXrF>JN=7z3+UIBM8DNm=;RNYJB8q}$c| z_xD%_(4jQ%Q*<6@D<1Cg&u?Pi(!xc`N=;LV7h67`y50X;TKsC3Qyp_n0RD72UE4l| zlH5CgrlJO`-X$nRb;zS+@h=R0VlKZrdMP=uxvs0W-y%yk`AX_;e!}S)AQ>KHroMhk zy;IER#Ik)b+n}oPm+8Cr<^+u<{DyCc2>r89!)OAeb9-r>v%8WS*T62U3zNA!s#LhK zsC_Bl@>qvh_Zs<Tdy`Sw7t6b-wkn4&*PsP(-f6}Jii6A~q~qMTnk9U=Zb7yJ2bicm zTok`}UK1m&D!ukM*Xc#f8Z~EDZ8oow_mPK97ZAhSRrgsCmIK2eqfljt7hC?XaCaPG z@$6aAwVVb<w-SR{!tXi8l^*4Ee@O{$ZAMnf^HxLezSD#8J%u8^<r}>ZtKGkq8<=0w zIod8%wg$qaP5-_C=iZl<(nI3H&Y_80*7)s(o&VN;PxMEPPwG=({hcS}nHm~$^@YIs zgQ;6@N)%)Bh~a&z|BFET6yT}Kk^QVFWw{L4sx-WieZHN=3$+bpD9&S?W{6=r3F%~_ z!0H5_np3*&_$pH%h;`vkpH~(46?3K|X5zOg$66D<eG?P`#5~j6?GiQb#;;~gMg8vi zR$1vT877?E-N~damDhc#dby5$5q$tL^a^PYD0t-)GKeIC3Uo${hEU!TuW&|<ua{Ij z;1d^Ux*0+NHeOB5;HGrcAW60PTn1lvjLw7uOhDB%NIuuj_(9p>wy`BciTE<?-CSK! z&+xrgSZ8OAiuT<kn19wKiR8)gEi;3}0Yo1kxpXR-Y+hN4IQTYV^!W6%w_BDTY+`iH zDhFm5QhIG+g*S5gy+>tk`{y9T-?D&rnPSDt&C80a160&!xU8s<g#=4MdNKOD`wdQ+ ze7E{Zm$ixf>qXF5xSCq?6;b^ID@fy`ogI1!joxA@B-HHcwYCrEZMO4&`2ku>>WpZX zzdt^E3en|N&%%FA0eSV_tC7=h?!MnfVHvZ&<ZXSHy+6~HzXK5G@&6L%9BbV}*Ui0> zS|+#LO;d|5ym?&EnzPe6SSF0HPON5kepfpja*ArQW%@=&<v<2(fYW#&!}uQ-idL`$ zH@KE4opzVUD7R=Rn)q}|f}zh^FWQ$#1d#3=sM@-Xg>}(ljB@hXjP1XhA-k6A`FB%} zbop|~{yvf+(tOt{xee!-05z2yRSa1CJv?Z9d{_fQ^r6y@Axq{2i7Wn6<R$={nb@DN z+4q>ZW99#F%(T}_Y&IyGSv(VYSoD>R<!VHh%L-UYAGr-T*)n8hDr?A+AIB6e-x^mB zZs7z;D~fVi^pK*=unxP8w56l}gh&*WL!0xl@ST>Jwo~Q(4+UHr?<3IN#4>h#XClD% z6@C92NtUeU<cdr_3xbaXc5hFq=5=RkOWrF#WK!rQAJhXV*Hs?UcwcT#Z1n`Iex-iG z%f3H6$TtB{YH)Y%cIS$zWHhG&dm5;^4E*^<?k{eSN1C6h8y|}w3Fkh&d+Qyq)_W*V zIMU+gmBOzk1YccbA^h=W&Tyv3*^1wF!pH)GyF`<rybX>|GLHkBV!%dlm6*9^-=RWN zk8zf4tqp^=?}={)j56WgxJALe-c)xb*9QI+4v<7WplfwG=GRp;?2=w-cppcfwq(N; zo5luCbPm&(!1Jn&_So2TP#*+A3LHTpVpg@e%R%NBH?P=40=noK&Z!yhy!1siF$FVo z?_ifwIauyN&m^TR@6_h;>sX_A+xPv?SzjG0Kin7b=UrH32v})m9>rn%F|iBvH!m^V zI8VnoW|8(3B*3k`&6!L|zR6)5X_=h}U7hCCXsn#>(w!Iri5r;p9f8K!8TZIXnylY= zu)K}?`+o99KjeTdUfm{3{8r}XD|3aM)#O6ACpx#t0;pd;p^=v5APD9TOc8%;&eaT_ z&lQ|Iuvv1-MQYb|l3_EOSH#|Sm1<CsM&s|5#j{Hr07k-vd|ubg1K~gmn~+-Sg>gW& zDY_c=x5~w2{MtI5S>;~~wJaZL!KX9p-w9KR02}?$=tbu1F|3&6_usaara(eJAO5w) zLotKx_V|s8lIvUw_b*FSmyzPyw~M9{w%MRHnm!_G7hR8zyPo1%=nduGbp0aBb@q83 zuq6jXH)<sFdt6yl@~Wl)w8r~p$jo?Mx{K<P`g_Je$nW2CrSc(vbIJ2A4|afPwPNJ% z*lZ{BU>ry-@&Zl_ICw@K0UT3_O2JwrCVM2bT)Jrx>(U)*P5IC1(XsREi&?vqqcrc& z-7r=}ny;}}5XR!(Q!H;4%TE#XB^-Y?mMM>#I<?h<!lhYmGo*1Ev2>~$o8&)<n%+CH zvg0{d*IkO3r&de<XP=}f*pGSScVkg^%dq&1&rUSb^Wz?Q=1VV>js>jsTn$*CrJoz9 zZV&&ZsZjkgDAD1ZZ~ZapvuSjfrNni@UBkd|?zgyN;t!)__YFN(Kb=UWF!0d<$PoEJ zv*L|N%Z%<+LLT61aRXGu$q&5ua(%bQZASeif=Yqy%?IK;3#z1|B`rfmiK~PHoXzR8 zU}fNJvHA%Yk?OMJpB!Ig#uaI2Ipez4%Uhg1o!{iKcbh|}Sqgb7m}B~s--YTiSsbWP zh{2h4)R0|(IG3s!F@Rk<XmI>`?%RhG_fxv`D^Lh%5iW)YTAU9YNx8eT*58M&*eug3 zw0xYK+^;0lLRtsIBClq-XnCAd43_&ZFWoOA{P?H5L7R&amk%Nca!LT`Ou)L=n%gJe z;Z7F=M`Lg1l)z;NO<(@ZJUY2FIawmzxo5ODj!|4&mSqN#;7`2u@{dF?vSZDKFtB`+ zbF$Xt>VIpNq_3G$aM;;0E`_IeL?#Y5Ea(@)$jJLdH8n0Dp%K?*Ae$p#QK`~zWo3#* z46d72Jna%XfejD40H0b>*nkLru$1%|9vtT)Z}|tApPSW3llwY>e{91%i)q8St$j+v zmgm2%ckPCf?Cn;w_)CCupeI~z6PXy)ABHDYKQEtnzwuX~Y3r0X&!;gWv1qq~gc})# zET$FG{6>X3ywKbsy`MZVI&RWng|^JAqV`weP33N*i>{{mtpzUw`abAd8TfaF&Ei71 zE<If0N=6nY&{N0zQFmBcc})Mw1{d=8j_B!l2U>tn@<I!XGa{y5@Q5+7ds^Uszk=8O zmeiH0+?`cgW^!@8u2gQd%YBYOdS)@{Q^k2EGZgiOdS5Ovs^qPdz`@;zbOSAzia!1> zq1Dn7D@$89J(swaj#t`E$};VRGC3*m3yhDXRPQU01h7NBXEQSpbMb#Eu<x|qR}>}& zmi#OGeNbLMx^3=H?9QD#Uh$*pb9%BPr)<4!`*%yZav42q58t)bhWOdF`)uy?nN^ni zDzR`+q3eX>TKUNuzX?GS-EHmul`m_r!iR&*vXc9I?!gKSDvnD(2S>{nrqm=Oei97_ z=F7D1Lezd?Pod36vh+Vjg?*rjDw6t8g}lVzeN!BjSA$GEIHdMmi(~rO^8R7;QK0j1 zTfyN-`S=Pmms*WZFT5W(B_pq<d32qU%9dw#Z7VgdmSxj6U937w+kBcq|5cn;Wf(Od zaJK(z-$*2tZexqYwT6J+#~c<y7yfc+H$*7_2KA}kwd~J%nA@XgjYdE9Y`rbAT=cwg zvoWUlIg{Eent;{*&5vLD%9I6EBv6E)ksY_~vxVE@+9D7%>(fL%2iU`hD#;2LYubFA zuc)gHQi$6837o9xRDyzA)PH{_T+RBJtHEQH+fe%vTj^G?>Fa#sCVOXX<QL-twoTX8 zqQXs&?;rFYpgM{s0xL1Iy&Fk!f*0o!3m=BN4BGAd-UvC>9U<C8EI#G>%~GtbU{R-R zBN7r4f4p03L;e+2;4oB<-VhbZU72IfL0?9k9WWH2H}o*(pnqZQH8;pAc_sT+F9DCY z)`e-Md2%?e+EGztd-^bZ>SGWJ@pM4<3<c91r)Z$mh6&NX&=YoCJ$@{tpnwoUOIjKk z3Ksr3&=^t>Ul1%Te2xAq?WYg%Y0b2+hnq|o{tI`|Zc9{v30=H_q)3-%Mkoi|4zX59 zuXETfe`~EEm0D9P{DtJ=+4oxhejwu~w&8Fa%%(%+cknAI#6^a3ae7X~tx|HA^VFYK z3>3f(CR76x4Hq+>r7GgDxLAlH?2n-oT-@p*<ZFx)_hxwWgSP^_tQhp_nP$dw-vn6r zF_-j4w{8!pqgrSw!@`&)@B$>Hqdz`SqUdFjM$3lws<~$a9`j%K_nqi3;ZL?ibI^{Y zmUoE?UaV3RUr@%D27{k=is=-kMFipd&RkFWk19A^B~=(`<(J(ft^Ir(E+3G&!aJlt zcQ5BIo72-Z_sF9D@^M4f-dXc*Cu~D)<N$+I9AQ^)s(=!ys^BX#p~^SV@wR*a;JU)4 z3mgjUR~4AKd2irl%5S9`7uxN9-I{2dchzA=ocr&%{h%&!2=aEewx_z;l)1d;wRYc4 z#P8x_n&WE$r0T@9*b1=t#lCMR$HQ#O8mW_;#-H(CbiN4kMAX!ZJ1X}#q>EPb_omH6 zTWESQ^Ge)1$>V6=nbv&C7)6pAz1L9rWoky}NvA}4I}4Lkd_U1G9jVKSM3KzJ{rDs# z)~aOGK3y)iaJ_AcnlVP9LehBKwy}nl;`CU*G17lM&FyZu69xU}PQ#hYL#%bID$kQv zM+fHzkf*rgWx<p4MUgWuuI|Mr`{IN9A5^|2C?XJ^a&*UCg|5*v#4vNkZ+C77RN~}s zzx539d^_k>98MEM*Jt79CZs1|B6sa#d3wZKYoUuJr1`gmpSRx@$iA|zqJ2AD=G9O8 zv+UM26A~Nm%IT$HxwleUH~!v)(YrwTTuwodJKIbW-k2lKLr3?4<+<)iXu{L(0+W}w zw$9o#Q#k0lN7VkbZ`jAiJEZQg>Dz*5z$=SBo{OQK42EI)i<cj9O8R;J+^5y*1^3q6 zCoI`YpnLMgQd>={LzW%djWt!8S31uo?yu{4oVo{bmYMJFTEtN<4hM+yhSOw!Xwb$B zntcE3utIJy0y{}_zkOoyF;;ik5_VGYsWdHYrtmNO6|8|X+?0;S?NQ4gs6?c*68)O2 zXYIFSJ4kviBsPmmhbcZc44Sumvj8{IWmpBKzY$iy>jm_1_gBX0eNLnO%18nkK{CV7 z1<^bs;%t)Zyxmron&0K<{|Wc)SHE)=QfYo*rwj<D3tlGgxu3KAp^Z12B7*w^ij30V z`BTjz2J-a1dhRCd^AdV2d#AlmUB9lPi<N07&38|i>s3e>8fEz^$L5>xk5%G{;&b1s z!TsU_oq%sE(=L=NYgoN}ld+L&JW|*qSnkiIg%@!=`<`;4GB^hyZw<x=7-Y2!w8)#1 z>@$NJ8*+A1>jaPG9dPQD^wh?HGwwS-pVD$>plpeU6Bh;b<Lqu7a_wmqfjedqkNxB& z(EEM=5dPh^{nTO5Pe$H)+%fLL(f5!az}+*(`#gw4GML&M23%<9&B{95%_aLkE2XJW zEdK~gxqgXi__0wA*=PB`H@;HN=Lk{K(wjU>@UD2t#FhK#$+Zs+IhLuFO~9J@*)QWY zWD48s#XWMP75}CXAyEuBo{$kh1V0&<uT4?T6NZUNxBb*HQX2C8!Gv<)rj9(f6h+G& zg<b}e#3zzN5F(@xm6>llYB=%QR3NZoLh9N@e+`4d-|uj}`FAeuCrl%<A!ljY?%SFr zCd9iI?p$_atZ^EusekdpoubKdzL(>*gru=SfgR(wFVmA?ks!wuJDuiji=>FoN=DLu z%YRwVkax5(&cT+?dY32=w?(gZTT2v{XsXK>)AH%)YJtF`T+pcQx^sH`rYGZ;^G{M1 zIbwcw;R$dV-2NDV({d1g1wp`X@?9)XX!r(;N=EbM)73cHZy4C1vMxWKfJG!rp?m(j zn6YI$YB0|ozTvL(mn?V;;ZhJxArkU7lrdL3-@?oI=!HD?uHBSyP;->j)$de#zHVKQ z)Gj)+-vDBk_TgB$wgwHKY`|wsl&>b7{c(}w`P9uoCuR3QO5pHX)K@kJ`@*d?+p6x| zf}*oaf9ALlt?=-KV=ZVhrzsR3%JX<aZj#fpVRH~}F`SKYcGhpqmj6oyp3_NFIfhM{ z=!cETwY=lMNche9cy0A0FJYWVqGR|f|H&9S^KW^bT@^d+X$Jda`Vyh=kZRKY(nBN_ z*V^yCjIiaNdD9@QR7KM>R{Q(65;*i;Q7-z2EHJM5FY5)LN;LM|Ik`PW#cS`f`t|SW z&3W1w_28l1hs<z0tu#6-re%_<s=X@XC(I03m6xmXp>9BZc=fOubyaM}WLwx@e{q=- za&_-Ynm;VckM(72xpv3U?Ursw$js|5W;%U33;KmS_2j#6H&O~+M?Kkp#V=7NwKW-e z-wMATmvrS%H1=FC&5mMuH|2_+(3AZeWrps`a1KDJj-?nZC5eTg+<s)&CRBF35#)#h zaj!=A5EEiz($+vP_7m)oQf|E~<khZmEd@sbKm7x9;F4t3rK5{il>U4Q!K=T17)l@T zt-%Uoz?IWa&69^4D;y&T;HFX}V`|4iZbD9Zg%P-^gaV)bt1AFBvI94j0^Y30L>!R6 z9Q0MdO(joJ-$VA4dffyt?9q=o*u!QapMaZ6Pm<aX!bEz7`bOY#D!ZUu)=^@vA^_Y> z90+4O${*waf4t@Wi<|WjM>srzOPpg4%m1VuFM+h9F;sWzsM!->jGPh~2YZ|x!NHNh n>*Xx{AxE(G|6N2QyX2vhVGVACL0#aVijZlj>ZlYcS>O5};L!YJ literal 0 HcmV?d00001 diff --git a/docs/images/frame1.png b/docs/images/frame1.png new file mode 100644 index 0000000000000000000000000000000000000000..0cc020c9b2d3111ddc8a5989b09456e16be9cea1 GIT binary patch literal 22983 zcmcFq1ydYN*G&jcV1ow_!6CTY;uhS3yTjtnBEc=VySuyF;_hxig1amZFHe2H;hU<N z>8`2isg`@^-g8ceD#%HoBI6@}`0xQ$N>Wtm!v`4L_c9m}{{1>=mn-;w`{<}7A^f3o zg7EOY0&6BDEA-(*O%%$r0o;2X$xc$k@xuqS-v7>zgSN%SA3kVkONk1pxapo|AgHTI z;09F<=wf0jM+|3e$jl~ZE|owx+6FdazqZv3p#40TEzPACi=q6bfb|7iOhphD7Or6N zJd0KPJ3f|+#uCZ~=OiCwE${?Qd4k(9>>Jtt-_g6oA!=^(SauQHSvaNpMit8LAz!W$ z_V&8Zp9p?Ew;B=fS<q^^q<MOjn*4W(snx>#e?{iFv=yzE2X*LeT&BP!`)x~TR#Wa| zXGPSMjkIk}frVL4jT_;JN|I_>KoBK9#L7benF!Sb1x2O-mIU(@-nVcC^^<Hpeo2=F zCo<ctHHP_0QU{d|X>^Cc!X$o&L`6{f^zp%Qtv3|kg9yz3Lipkt*mZ|z$%bayimG9> z0~rX8!nE>yzTZq4sL>VxXQbFH-?N)~VZUuWu8j=*nJjQH8W;?V&^TPf91O<?%N{1z zTzZHP%GexP6@n&G4r|?4o17S~xQF-64s~@~CkU#4*>u(}&P*m-);a6;oR`awmsd3- zgzYFdW{yGyjVgk`sO$mrZI6ilu26K~%rR*@Bp|AAo0%q$TAT-hLfI-T&oNX}$TNOz z9aP`HVPV^|e^-UxTnO-6uqtag{ChCa$yNJo#uWiVTJ3}(gl~du4BK|^M=@MzEfe`# zvHxw`MIcPR1!@mA`mc8<Rv#{YnaErDI~1mOKZ#H=Ybbl20_r)reyTY7*mQaNaK8)y zp)FoA_E>H0gS35wx;Hzv+D@nlldsXW2Rjg-dMXT7tI!F9*!Fft2BThxXkVY^CdG|# zstY;SDBEEOI7}NqnUCoj8$sbnSTzZ}Pd5Fpfm=IAOaTMs%p`Rp;ca0?(31)7mU)NO z?mc=dggsBhHg8ZT)OHLyx^J%!4d!a!1>aYl4W}(a7`G;%a)Soe%T}p9m0jI>y^DA7 z>k<osUY7O5hv{}{7c5#uFemVAJK*f1W(4@k(@&e&T@bGYs%nC3<R6bs3{0~&7^X{F z$uh!0#|m5AmqYO-p9>=zmR2O(;w&EIa8AD2XFOBNrHzZ-7_hE&ehDaVYa+#VAXyU& zxz(#CS^YRMD<G6Si%*`;`zQUz_!3*tzy?RDDsW4)8fAi~GUzGyyaqhOi`by^ICPvT zhJ5XaUSms_Ug-Tf7>US!#*nl!Yb_jMcu`SB<^J4i#zwdM788u#>5AE|cHC{c8_s3G z0l3>{yj<jy#=_p+%1vTU_c?}rvL~{GI7M=qaw`0Y)UdZlKcmowL?}Nk-`n_4roMv4 zbRp9^$}u?L%r0^9!p3IoEx_cz4g>C8xO<zgexsc@k{!g6erpKZbiWa3IAiQy5p(%a zm-#Z#+G?t{|FXyegGcwAz4D8hNRm8d9v%!hq3nd5DKA<4)%p3bcp(14V7G6UZyc~T z2a^M}^kemK05a4qv$hRk>C5|gcMN!uz+VHJkSx;`R0b|o+i(%9$L|kUG{A19+~(pB zO%qQLYbY+$@nS4v(2Z77e~~=Zu?>tIt8bs7pjGquBViICC69?w+Vc@47*4@|_8pDk z5Us9Lc6p2QgR9|0n0%I;_b;A_Hfv*;^|ETBYy9tPP1)b}JMZhg<6_*fH|QGlOINXU z%bcPybQ&6jb{q}5hzSQ=f3F{?HGfHui}?;rh$+Fls$=<L*@TtozseGLM6ZqNASi@= z*BVeQVy8ESo#?;vO@EbZtpmLW8ew>8@$!wIG&RHi#h`RH07(zOnaEki^UCRJ*`sqT z{?xxtKp!krCyFU+kns8?r^D^f2w&vrmz)+Uy)9em^&l>;H&*Q%4pSwaOs@19U)b<8 znbbz2TjcaY&))<^cj59_WXvqTWs7w|4v2`3I)iLCgqKqM!ALm9!}b{u+~vVtf24KA zw?Fj{H9NxvFWd%eybW+!0JDg)0S(!Y@JL2?$xM43PjpM4t)hm!Ruv(y%JF|znJ+eZ zkoR7+Ahy?tyZp^`z?c|C`j$Iod#8P@<O9CoZlax-ghXm!2@g3|mgD*mbcHk7^o>SY zaH3kbf4^hy8)<0OKDS=4<$*NfW?P_#Gzsm8ihbn)*1vpvVqb63370jlV%^e5;)Nz? zWU7;G3uixo_dP?|C<}hZ#BLk*WnKD>ha}b5ZcU#24#&x&MnJ+6^1#$zX+rwWf72XV z-s#B5fLzH640>sfl>Bpn3r_GyTW5vREg39-H6u)XUjSO3N?pxhG7RvZ=f^hYD%OYz zi4)b#p-;T}%+*M8$zxlKE-Wmi<N~~(ByNkUy(*X|xT`S13Bhb0Z8f&N*1xDKPZyof zbfdaA-1T~FZU{n9ZZW_KRACuJZ4!I{GT9#EyvPebxAKwlM^$s<LW)1E(>Pbqv3uBI z+^A3yO8z0IF7URNO!YmQhO13j$9&#z>$BiR)S!porXfg9e-mRKf4X?EKp7t+k#MRU zM<ZydX&4~(c_~cu7JY2L$Ei!raI({HcrWg+)s`YGqxw*M4Q+3c9CcCZUS*f|y7rc9 zQitcb#NZx4HWj`l3~5@G$Nd{em_CW|t+@B9mcK0hmbC7&`KPQ3aNd42<*C$VrbGtX zB{^5)tzo>Im-v+yR@9;y0gCk&E-Mk~u=U7lGf_$Fxbpn&hFRJ(i9nCR^Xia{VuZe; z_=dlVTh&6)d^JZ1fVXel^fm&faQxmH|Kq3-{gPRECsZdhx1I3bmbjmzJ}88zxoiW` zoSZtwV%bxWu5imOtfO=%|4>`~v$-D%!p(7m0-ZANRHs<vv8fkadaXJ+v=pt?uaR&D zzLNl+jIr)a=MWovcRP9dbMl?l_`<bNjhb_M%?k?7r?g&m<@=YE$xwq033IbtnsjIU zI~JQv=$Bwg4=h}qzxfX^ufb)ZQbNY-9f4jlWv(f&=yz1b@>93{VvHhZ?RYId!AoVD zLs-Xkg(SQ`R!hfdbLGtQI*-gg)p?`Zdrykjs5RK-fJUh~s<bYssqj*c1l2Ozs9XZ} zYl+uV>L{}%F~fyq(Ji~uwdjwLJ^2xqdQ>C?lSlD8sY>x{@iUlGkT5fXG=frvNiLJU zpxO7@WY$8Hg|=kr2AE>4@!wv{0b`E>!F5o&zRpzN_P6mzjzQ*LJejz1fi1P&c4OWv z3c?MhdU4KxvG`-V%tul*hEv7;7si<##vc2twhPVaG;2|IE>qX-zdU7_Yq%~#LUM&m zbYyv7vA&-+xs#U%H&rw;YMQ{Frw%}e2P9h@G*4oHhe#lPd5^T<-Pl@9<!G{s!RJYX zeA4u6P}a8n6R1X7?S4g6L=vj~OjdhN5h_B)?=TZrZ3f+6;yt(8HQm4jTSY27naIR} zG#Tq{{nAyuUKjo$>7VuMVZA>w*K?$7K?%8H*<KOW34k5_ZEa-0ePhC4Jjb>e)fR>m zE9>ksW;{3A(7nzy&7kATKK`<MY?pe)(5_}NpByNf5dBvSoi))vYky*yUG^DIULDPH zph|*zw83o`NT42tn~G<Fa)u_7Mh0z8<07B&mr=u_G%j5Yc@mz3U$zLf%eX{>(m&$B zwK(g=wc|PbCeog~G?r`l$UXE}J`;3Ze`lrbUrJ-c+7k<#e_eTONpVpbfW#WSaB#)< zHQ!)(h#Dr4ZPw#jdj%D4xgpMxa%A+kM4mPfq)4Xrxpdb>g^5=rm2B+Lwx(zgX@$oR z2^TeXtRXO}-{@|+TSellLFIb(?=x_LjHxBxWTCt9PPAr3WuY;vsaKZBoNtEnk?y5E z@)e7{orZk#Gn5(m+KO>ErZQ>lsiB+MfAc6k&rs2ufzM*h)br0tTi8Cl0?tnu3Ch#o zr#qH&AUfr)Z_>E`baJNlxC)sUaq24pKMv874zn&miAn{{Oj%T&jt{5G#s%}b@hAn3 zc4=2QpTS5AlQKjY$Z^cm7_metiK3UCN_#)z*oNbs_h~6?71M<&;6Aa0&+0s#A=!Q> zt2yIw9f0TUE!QJ^tzx0(^%kYROScImM+)Xp>x+mxV<MS?O=^$mC+;tvNX~H77>sLO zN4~=Z8yjb$1qQZ`-6L-J9Eb6T3H?l~bxa%)N(PvZj>0q1NSq|#VBwi<bfGhN(0S{K zhF*o0ZrM6-xTDI{6JV#9Bl2utYIQL$e4$J>=jg*jaEOer<fda}&Db}}CRghZ9N|_A zq7?hitlYvj8n5hMX++)OtP^mC*P&(!@p|R_$*Tt6AH3}wixY()RU^X%Citi&zKAE_ zm+MDJxXc!xmK=VCJt?O(#<BFf`O7YyMaA&XHn{!6^PQ<w@7s|a^}@XnXhQ(fYEdjB z-M)5;TKwdKJ0d0%R+g>tJb$Yr#=9vA{i4@=C`GOy-9+`j_xMHWZ%4Tb@WY(Qm6X~F z|4Gq2`S?55s$~Iu4A;MbZ;3dVG0+t>N4pTKfcqYT^f*Y;k*D8bgR%VcFGDw^Ynb%o zlw!GMWq8s{yrrzyjY?zZmK<d)ZH65G(ur_rsdw>21iJ^M&A66QjqO1U6<F8gBeB8x zviJn7;X?H8L|;rKhdaZoK=3_J9@R^ET%;V~2E12dYb`jG(4irf&pKO*_w9>Uz-KFy z=0xIPMiBhpz6wXfC`0nhJEJEjY0<OIiO#shT9188YR0c_6JjmKhFdh#_pufGjx-}r zLNT`x^*o{2lFEw+x6h06GWCJBvJC-RA7yxrii++p3lRR*3pCgBLK*JGEh_G0l(059 zP9u_BUP9`IM`R<Dv)AM8Q7_Fp`ZHTUMrcI8l5@#|lfW)?$SI$6asfI2BCDpCT@W!? z6UvCwJP%>ZgBrw=XEi;P4Xd2C5T1(F5?VzVOpQ8U{;&s(ljLo7YBXmRrL)=%RFqW{ z&b6~e2@=)Z4;2Tm;`+I71eJY+zISXYUB^WR04W48Pgo&2#1~VD;mo{r`Ao9D?J>*h zuvAatST=pe5m}*4P>in>*?X}4eKCoUY;PQ)lt|<kM#K~0j!vlw**rn4%!(n4-&<AJ zTH0f3Mz@jVGQbgXo%rRi#Z<AXeWLhTlP%o8F?V=ja@y%BDS4|+oJQH1GA-Vw4%nO1 z@Uo;`!E1Un#>;6S0A<gNki%oSVr4de(`GZ>Su}iFoC4JCQ~HRJ9s>$cT(UOBu2coD zS<ZW0jClz;GfU<YL?Qm<p8HHN<BeXS93Gq9Wa1ABrpQDt8Ou^Lq}wb<ftBRXuXqDw ztF=ly{kr`jQc=BwIIW%$O{)+5k?Tqmn&JzJ7$H`(IrS_KXGK>5hC;kW)F$p7@h%Z` zMfv(2pbN|inv(1pT?eN@uCF&Z469HqU96~`$H3(eTc0TTDOx69glEvd<X0$S(5+6N z#yowKJyHFWc87WC+k&Hc>?~A9lyMohHOb|m+%j{iQoCenZe_z#g;^bl^`4A?Co7sY z6!4yR<gS_XF0E>I=seAHB9=b?<Et>DA+qlpX!bUYS|XFB7Wfd6!ZHzWd|1<24Y0oL z`sXKheX6$=yq;&LC*_0vlij8~r=6@)=7oxXiv=Xn5u&^+QvzF%$e~qlXw}Z1RyUrE zQP|+h<B(9T8!g~}TAcKy*^3WQmI$K;16uB!g>8zbo>1=_FddgNqEvU<J8n5_WMt|y z0^Z3h2Hmr6R2R16dId~x+iQ0*&0`N}T5@8Y59FiFqt*~Ve&<A?v-+v$Iujrt()g(3 zZUyNicGr(lS_lW*$5i9bAd@cmEFiHu182MWU!Rc>5}h#L?Rw0|sN+?5_7pH!b=Wvr zbJYBCGa4(9gLp9X&HsFWG`50A`rQ8QT%g<Na&m2~jQZ}1IJ;>yKG;#NiVk<=2iYBM z0lVUcpI3M*#L)sEMF+!j<O|JVDq`3EDyLSf(o->p^}aB!Hk~(uknkq!eC~8_l_8F~ zutgQPy$*J~-W5eQ)bZd=NacH6fb#H@%R#pdH>wJR!0LNU2jr-5brJ&mlh_@!I>gvM zfcU}m4@mGG0l({REBA(Ib8=z|znpPx$ueC2#KZ6|4+2KToBwOiI{&vZxc}=@Gk4jE z9jNRLRaam0Uk<^DEZSrOzFpR)##N!0Uu;Cm5ywD8+*2QMf3p)O4&&M5N9(2Jga{G~ z&hr$jZNnAzOVuz1zq&Rxh^Ibl=8<OD8jtJOL=jCoFVubT4lE|6c_%+%9m{cl1;WTf zS^DNR01%oGXF1F#XXAmqhU>I7d=%e*Sj*Y;D?Y1k&7;PQXT|~RE<-XBh!ieVVb>#~ zccMrlr6|!N{MC6%@ZCaZ?bH~Y8qfy=@pY;I%K`vAnHYs2#Kz2s1_I;vY=bAf$l;~i zxp=BCyD9qg4lqlM5`Rrwi7NTMi026*Nzod)Uv?y)0zchxx9|tcVUq0UPP=z=%w&j* zPN{NJH?7ZN|AEl3ixxIh2umfif2pz=&!M9@6lxK<$-}lOls3^@lP9)dyt;p~thtLz zXY(QzhHQ#pV$=uA9m0>{H=d%fTEKL?`sYc9`lpaR>0{gE9;A=VNW9RLW4|##lg8vy zs?~{*gKV{CT(e~eJLPfobm-feIWbtK<zyrUZuwx3O$aN5B%^L_klqG)g|XOf%eTvW zz_(!iAytWlg3G!kBzQ1(GCg-~e7L&_jf|F%pw-Yd{8wf7w*sOjyp7fnnuqItqZV)d ze9{}%1@ma!vtO+9M5<yqvmk5n_TS1N2kK9OFfOi{-2liHra%5VUE}Hl(Fvo69jPe# zjICI&N)r-;2Q3xSA`VuhcnU=n2tVjM#hF~5lF>z^M%G|Cupr`$<Z#)ZBE54+3p|<5 z__xcseu<3e;OFk&8Ji338J!Zkkna00HrQ69dy6|p;*kzmsXw>8!-V&=N6J0SW%W4p z{uQIA1dE=m!(97X+X*PP(1pCHy)3PHs(fXzGQnxu{n7ujE?JZFk{0G#f<i0sx1k*u zI`Q)Jefpom5gynd;|2<YuSN6sX);rPdn)qnd5go16HdsLNvM&DYeIb2-(ji5SZ*@Q z@MJ**N_${b^Ot`krETI*7gAH2T_~D|2|PQ|?pd9b((oyblK0IS?h?<Tr7>AvS({r# zx}1V6Xwuk1p=E!DtHeWjzUS*yaT^SAX7~(7MG%n)P^w4UEyP=F?{p+lpR@@F=e_Nr zSCiZY?LIS{Q4Mq(+R+7^FZXpS%N&rG^^0cxd$ws*sXJ8SF*VVv^BJCNe@^a%z|adp zzEXS`X?4{)iE-aEfT`Y}Ipb65`lfZ6Yp@%?<g-c0a6gmEkXBcqmvolGmerKefbNrf zq>bXTMRQ`CxxxsY1G?Jk>OaXKq}!|0Kvgo*A=)<Ulx6+BHKhGFTi%kBW8by=vlRX) z7uM;|NrW&F(K=y8?X{wIVN8F4fsVhbS74YFRFB^!U;bcth!si8-DQ^Th_WhC){*8w z*JZy)vQ2^R8i<l;9Q_T<*mQ_UFUQA;2@_+O+HxB?a#csQ4sL%6>uOrro*`9cNT(2o z593$e_waxLHW7CZM&T$S?3}sv9;hv}?sz%Mb{<aMPv`O`W;fq{ADR8K(7WQ`*cG4c zv^k&|5$&XSc_$Vc%#(Wa7Y6pBz=`d!KM%CQavIpAktZ8kpTQ~Hx}({;z2!#^QqGLN zuLBxJjn&DWy|5+U+5S;@DtM0%+y;sNfxoMLU()m*&F6f2m1wtG2%a=atz*j)Fa;Op z{!}-$B#gS^wdnlqRn*K>fn5BhC?+U-4!dzRq4zocn;8f{_^pP0Ei(f3A<bF;>6@Cu z^6S#F4YiUZR+n%D@99U(ad_@R9%05yx60MzBjhf8D<oI9?H@?J=O;LC5DEtq#1Oz1 z!2=3!S1&HdrxxW2(A({Ow>ANSA<V^{y@;pfGVX5o+;CwR#G<E)$k8_x>e!53>1M8M zz13#Gw6^CYY!kFCoImYO#n*Jp+TMH&c5);J3`*-xIcND2PhkFarcZt{Z13Ia<jp(Z zz#F0+Liee)%-0c^gdKE2bbXRIiGi26rR=qa77exMEp6$kD+LJnHRf(5$}hv;U_Q1? zZl}$1LVKA;t^tJ2I3f1BJ~?^zfJ%x9o?N#|?4Jm7*w(#nK|;5n1(um@(_-975AaK$ zZcWjVLTot=knTR+tN+044_7rJcq#p5u9R^SZrA%3G06RgKC&2R{nS&c*4hwH5n{Yd zcy1-K!<?dGDvj?RiUH>yd*EI7*z*q#Vw4Bsdwk_m^V3#ssKI_PB@UcTkkt+8=Os>p zD*RUncBqeB8eRIsgV0aH^nv=|l)`FtzRY8e!W9Ti+pFJ<MYa{nPgf9YEk6UH!rE%G zVI9pOrc|=DU(;I|#Zgwnj^-Va;z)ZuPPpoz>lW+r>ypQSCaFXl*dBL_>w!MK_F3m7 z2FJ;Hhws+w%r=J_%RnTBi)Q{5%E}=*%+O(*aZnep<&Wq9<x6nOM8Z41Oi>j$X)9F+ zBG$e}hrV4revFlp6i2ct=E`_mV19m~5x!YJ2H99_frDeJTdDzvEd{!}>*<3ABRNWO zKdkp8Y%+IqI@mgkFnZm6RA~&1<dB9u7Y=Cu{r#c*#%04oAg8?1|3cocd=$JEX}scQ z>*R<JNHWjz$ylX1xth!?P%BZ99%AJ{6aoC`27qkzBvr?%{DqBA2Rnl1maYxuPledy z*Gyf7yBDUZ85B+)=NZqi-i^rkY2ElF>T<`b>GvrhOa0JreR$@35EhLvjJg1&@$(TI z8uK02bph?rc)+<P(N`!A+H{1Uo9LpfOc7FqtaHFPv^Vv#&4fmT1{A@De<7l+$WS<N zf&bksj^st-r4FjyoP9BJMb0O=Clz&t-TX$S_t60>H(JGng=>K=6#XM#jO>j8%6|)I zrd%KehxqO9G-6!IN%Zr)JD*Y=3HwK-Mjls+?X4(+$!(Z{7jhF}O;!1oamhkB4vG9h zwD%XAb)f@CnDEVd3~Uk4w2#fQJ?4`F(ONgfA{9Q`h$LoW+{e|(jWP!l@pc+kDJ#BV zho>n|6ntto7~oPgF&}juyTO53(;+%e&N>tachlu%iG^2*<*WD9H4YiMFTQzFR9ZpW z`0FVhmYCzR1hZIbEr1}y)fBl1H7txIvZrJ1Go>3UL{I4L)_|;NiHX88GTl`}0wUJx z+jvpxCbKB}$2ov=NndZ3^;lVVQMWbzZ@{oNWlUE@`se<$2SgSN)c~nxlqOTrHAUHF zr&ek5B2gAK=?F;xzxroT*k_8XWMe)dy3EriVga5Aaizv>pSZAQoRcxxR+Ul>WbG^F z!1V(tpUN*qVihLSdf(Yw#FWH36|5^Fp8=F0ez<(?UkttFGB3UkSf`oylz@z1SUiGs zD^!jsjx8`kVF9(btRo^@YYV-rq<t=-OUmFr*t5ORehlof5h*-wy4F1kX}G`whKsjg z8Z<*Q_7;0fk{|GF{S2r%Y5#Q&^bUEX*eMFTUMkHsj()>T+`rnm&@BjsXwRqkROGIu z*yZ@LHs$qY9`yk7n5(`Y<~j^FTgEEmgzHb#+o>YQbRk%8X^!vUpqfavp(FJIVJhkH zvZ^fQG=Kc=g`GzZH<lxAwnaPJFWZ~ozSaDSiJ!I;mQ}Gtc3mE8cg6$~??9w2E~cgS z$d6i8Dah@n^@G|*3Ha>dxzi|{S_{LV>fn{oUJ_Pp>7@@C7M|lX{4R!3!f=W5L2dIu zp6xSgwJ}_lzweWg{#&A<O6f8GA&@&o=DSb0M0hbvq0b$Ke7jj;juZFRU``nVa>I8d zjh|R`vOTu5cFp6j>2qcYHP6k!)+Io{GsSTjpB%JfwVH4ZW}iI9wg9&C7y)8`)J7{? z!@pp~>;!!+RQcg4Hnq;9Ly^(=DDwU*{}l=}9EKe?ZN_vIKPdr{YezR&_w|UaxmL7d z)iq$%8}Y5}c}~1^TgLSsBlLLnaQ>v|EkmrmxpB$(BLy7AcG>X6NTIP`;%&n$fZ3!Z zo^{4_l-+VvM*Wxsph;S2ZXD|H36?MvZMMY*t9&w11}7om#ve#x8?T3&1sgf0yHcEc z9SV{TJf$=Ws$!@PuP9SKPh5_45E#ne4o%AJr^!Wch^_?o>E0?NXMKw57r5NjC^a70 zO7IkEEfYol7dB*M<YFhqNvN4e2OZ)o3*fHu*Vqginp7I!l2Twp)L4Z-O$!IXk#%SG zaVI(RWq7-^I+UCz_|Z(N^sImj;GZ<v!6*?3Vq+1&`=X!aJh1Z&SGo(R@caS(+srzg z%rh8;$;TXh71t7dQIxVnH&(gp9~L8dLitO5As=bHwU+%@-+X2DS7R7S-4>l*8&tkY zP|`BWu=A-5C$j!JFkaUiPW}ECSlQ*t`5E#m;4Ny9Y01H2;vVgQS;;EUgA~VY7-gA! z+J)A|6ScE!sQQsRREaHoC*Jj-ZALD|48Q>}-(2SJ{M3Y2j65^c(qKJl`z9Wxl4R8* zm!Cq$FUP((txC#BM}&sS^Y@_A;(ge1@-_YW_Y4la|Iy|C5}jIzVFRKUI=6(R#1z_j z-Yq39Z_%GRY^l+(?uWQESBPE}71`ep*k{(J27Fev*T0;+(5;Agx1ArNs?i>&KV+Ub z1{#b?>8Cr6*K9mN1>qsQ(}wcw24+Sfw}wl9JfuttrA=}mZZ1Z8??^UTjRbpi7IJ}n zXGQ@&mHPKN7bMpO`k@jX*1A7V*-YZ+38@#l)4{`drFD;rArJ8)bW@`ywIj~~7-XOH znVY!{<>xYORab5im!iBPip15h-2)%^%w#t^SXCWNR0g;Qv9S~#dy9)MBHdIL`QHH< zw>x(|7J6BB)6-Nxr3Ri@GP!n3IzjmUK)Wr&N$mLoegH>u7=K+?v`U{Ogj<giiBoU{ z`ycHv5a}9`(^EeuuzFC~v+R=zI{Vz0IUtp75aDmJw?braq8dB}@#BDZ@yxseogZOn zMNos#$h<<0#GVG(lg;-vQ|~a$!qSHN7!y$9rsnez7usP<DZ1|Ydi#gLVcY9;+y=M` zvs&6s1%o5|R+iMib)WGomEDIbOGA+AO-BAYy3*GN>h<Ndo*7JONdljnI2b3$O(H>r zBSiLBbt;bXI`IAG$}`F9xcvQ@M~+*+iPQQ{?e0wTm-4(B2-k*ZMa`%+h7P2bbojah z>t>tC-n|<p?h#VmYedU_8&AuD(b#pVaRE(c;*-UH^P$+~E}-~s-$?stJuWxWv=JE5 zC0hA|dO`Ei9L)zhsZ&y_3imgVZrS?@?|0`*t6P@;-GNofjh?bg_Py;?s-wRQ>Z~81 zGm)zd4@S&e&n+q4BGkCZE@ve}fpDX~<0yaX18cSwb?%rBD990x<*@`}otAmKSoxA@ zGQSqGK+d)IAc5;}fSRI5g^iCt=e`%<<Gq84JthNGGHr?#?ENpLj8&5kM~z3drwO_e z?YURSh+?E~SY<iZDhyLfL9<cx&Z@N9YbFGg|J1nmTZP_z*FyHL3Os)xKKe)!$?T2> zk1B<BJQj8jH~~lPs})KsPd)w`VPH$CEH7}==ToQS*Ak^sv55}yr6}`Hy{)P6gnm={ zYVxEH@rR&GGAZ1oLy~T@hNJea;W|!wDk9&@9Jk(PUXEb(tN4Y|<ZtB8XGaWwe~JEn zp8*)xKW3?rrlFRqRIv9?FX=#c5W~rSV6)^<_Bpn*W$Dn%#aV<Tmz)R6{ybr%$BZY? zholraiEPrrVO!gEB)JG3=zPq#S&m)#jqX(|bBx!XPu4v|_LPb;HU_>aFVfJA^Jifp zenC*BNG)=0%otRxR$GB`2c?9WkFFs1R+JXv`tprS-b?<ua*x}FBRIIF%x@;Z2n4E~ zxkx*=^t7A@sLk%UrNF8N<m3GN2eH3FA=fTPk2-D*?4j!FD!qG2a}^m=B@oJXSRx6h z+(O3=P@Eyj!~kkYv|Q)%k*J$rv$Uv$6g7<+gOF<kMMto`-G0Gghz|{yJR3^45l3do zG>7o+P(X{*Fz#&#$9l1cjaqqjYy2-p)(NI~twxPDH#rUiIXrYOA}vUC>x093bXvf5 zBWVDW<~&Wff0$FoYpsxLj(`;!wRuH~>N`vj6Y4u-TH@kMkt)3($7t|Eqio(Rv*j4E zw<dwZ^VR(Vz@^O-()`p^mL5PAVSSbYnk_=D{EW=LF%FxvLmLT-DdFu4_UKXfN5WMr zCHW=qcX7BHqwcl#8<)~Ef#!?#ZQGTIQ~M%@?(ZmM-d_z+C0ga(gO%Tv>LVAMe8^BE zJu^L3a)vVEFpL_4>#+NbtEqji7`MnLxtDFOL>e`L%bJHZ({GeSnvpNeuQK1Hy^Otp zs7fQmYL?Pr;afbf*rgk-VtkdyILCU<8J&gWuem$C^J-dMw9x_~v+=HWDz>ppd4x`X zAG85`fsN*li)*Z?;ZZid3kr14UXU+Fd~bcLg&qIFnl6E-l`}+|YcHa@FE-~1WZEbN zpSHc9DUvObXaQ-eI5UFnzo5Q%wAN>el|QgtOkAfwWt;~6?bi{|4;kcZ>~=Af4#7^W z2^5F)TLpDpIP|L2m($`uw8Trx#BmDgYa`;anRD;u4_v!B(RSxE{9FRxZSvqh;W+*4 zkBtAPd-mxdc=?)J45wBR6j@>F81ch|?arK`)A)kSqgkeJ`kqyF#sg+a-CE!8r}+#V zLo#~*LyKMNvjFT_a(7pfJ2ZRlL4}l)z0o7aN2Slc*Mha(WF?#q@Qywhj!TgN&2Zst zwjcx2pcmx;QFA5Z1lZ5CPK_xvHd{1FE&4KqW{|etrA5n%6VdKQdl`$8%z}XL?Z23P z%RXt1#xJJ?gf>vgCM#Kn!hL-EYgT0MX20*s$9K!Ox@vx2@%fIf^W<}_kjhbm#6-Fm z>xREQNsr)vvqGTf{9=|69cHwOU1g=0wriZ<Z9lU*f8|#QXZMXV+A3mm1$9UDbSOYI z^LZOa*T|TS_d{{{eUP$gf+iESjFm<;Pz$taR6GcCKM?%)v4NF|WDZLWO`41u&m<|o z9X)=#Lvq-P1Y_(5a&q6Sz<v8SpzaO5^B^1L56ZtZKt$aR#pF-=uUMU8D3{K8dd#O6 zwCPeUA@RJ6TflQG!gZjor|PLlD5#i+F5yniW$d6X=EJmR6$+&XqsZ4MkUJ<cAsBY% zWf7)%;X0-O?b#-?)TvHxa<mVCme<@65;iPW(7z2N0PoYBLwt6=T&l86;wJ&Lx-BK? z);ipUP811gYdLp@@Hx!7dO%&y?b{a9Mlg&>Bn(L%?j@I1)(AUJhWBJRp<$9^?Y$Yv z0!)j0!HytP78n^bBTh^PWLDMVSrznp1mXuXYUsq1(tCrooih5z%@w+8&*=4VNi&r% zgFHfNl8uT_DX}ZzPX?lECGC;Qpm%(QZE?%{9rRY{w^@<y!10Eg1^NZLX)n^hy3e}p zr|x6eIV9Di5c4-X`cwV>9!zMGqjY4PaPW`iP$1GNpFS~*oSdm#Kh=%krLsEAsmiHN zexfs6{>PK>(lfK>`7=(JI-sXK#kSjLbAVQ_YK~lmHE6~g0Yp@$;y{FtM~ku{-i1;~ zta%xtAe4rT%}U$V5)EfqJm^_i;<^K*PY_xN-@onZchnLP;iYW<yvhj}#q~kD8y8Vc zO%_Kl_H0=U+u*8i%u-6lw)pW27n<7-t*X9SVyJ1tN|le&qBfU%-Q@}zC)3d_?O=iG zp$g8P>RmCDWhJG2B&arA;9Y9!6hOwh*@`Y9d8fHPwke**WM*qm;H4%R2ZBl#@m7;5 zbuz>Deo##0owVzKg1_e=Hv|@MA316PMe-^#reZ8!{F|HySGdo~xDPE8suU9ns0DC= zR!;6{-%Y-S-~6P+YA`f1a@Y_%p%2XD2Xd%jKPs1X-Y?t#z#X9VFHb{l^z<88<=LW- z%ha}DQh(rYJmPTR;jM67m(FkaN6%m99D!-SvRi(SULZA4A#Im@@vcCscqb9ay0}QL zpE)mz;ja*={n<v7!JJ!;FJFaiB&tO&w-SVaywOr3ZxGWD7%X&pT;f}ip4*C6wL4bz zOVfA)8aIQLj%d$+6$+?oa^sn-m+ePZ`QCz9^7l9Q_nxv`qPFC!O`_{?Q@A^-5Xhe8 zZpefYA~dK9OAcz8$-}2+zttFLzKOFfJ|R~uHM6h0!fD#R!0_LId!XCi1%zT{(xe(# zulK~STH@80%APyYV?TSSK#q9se_eMI!RNbKA_i?h&PZm`ZTK{QKvsrS7$l97zj;sH zuLz}{Z6Q831@<$3U69O>n}IUb!NFb623_#OW=SC@2+zWP;=%SLbME6^T*7FgG(H;< zh;{jyPPtgp;+u)DC8Hvw$Li2NO4~KI;MByQq=rvDstan7zgH;YIH|(6dI`5m(j`pR zsMcAyh#kj=v-P(@@QhkB!Ai)4dZ=SEK9Kn0K}-5X@lSF6*LKT$I)R(fZ*YF)o5ub8 zo;$EM#^k`-J-#Kg?<N+r7Nb80_kNiod%NI=n}Yb8^!E`e_9J;)v#&=0xxAoPL;W=C z%?3>EU?3Io`i$AEmX<XKn=AzH8gc5CaX!(7|1)$)Pi(G-2pd>c-fz6Nn>pc=Sk@ws z(s$p^dPm}xVX+in=8H4Go*ta@i`*{S7M^>J`5_;&DH{<sY+5anmo_U3WFBfM8lSLz zAYBHns;%)gQp{m2vTV2HsTe5Q2X++|YAOl=PsE#grNUeO`wUU1d%D%&0xt36Ui7lf zI1-u72o*|yFwV;Temq_+3JJ1eV$7N6^8}@i@UZeg)WS~xoYnnYEu-cuueZ*$WEbmO z>XF?NQw0?%YYIw$SOb&y!}49V*~Y%iw=_tn+Vh*4y#c`0?>Y*cTz}%SN5rtJM4yHR z8l$%6(HIy(ksFOX+L7HMmcf*%bQ+7Sj>tIkK3oYLD4DN3zfW%1y!}+w+In8f*i<^L zT~)%2Ihk#S;37V?q{fDGWJ9{p)qC4?7t@bb9G0oJz!9jKO_nBa7DudGwx%C8t&)|n zb|mc>Q7N>R3*dJMk>jlo)3Q-sPIaG2FW|2YXy8|i%;v`wAK3#*FW}o9uQI;JEv|0; z#Qzono)b7M=xu(R1u~<fGX8_xB+0c*^^pC929v>?i^`G#G7~hzv;NEagWV)yqw9(n z#LUAM89`dpIFozdzynKxbQJRhp+y?TlV>#Rn@$=cf<}Z!rq@g;<TJG67{z1LvT0@I zfug70(a0cSN`Y^nV7Sng^JHV{1_+gx77ZXHU-fI!4V;!|{ad%x1=*LkiYZUwfz2z~ z*kAit`Pm`Ns-Mzr$2u$T0a`WXw3?)?sg2c~B6V7zL@711o-t??J#Lr|mFcCaQc1s% zg4FajeeonG7V_r&^7Tvj@9Z)}#Lh78$Vc<eh8w#dR`nqVZ$hVDj`ZdH*05QaTU_Vb z-J4os=Nj{;?OvoV&KV!>4&|_cKAL%V%|k1Mr_1E>MyUuwN?ay;AP7)7uA*RP(anmg ze(jYVlNx%l_{B-@DW-q}hX<c@_pc6zHw~BE&OTja)|)fX`&FXq+utSC8_qYP@f4<C z-p@m#tI00{sWwkAn@gzvJ=_TQaN7OuMY;GyU3G~7{RKx-s7y`8#Y3FtA(*yD|Jvjp zQn}fcW(Ryqs$2=6&#JY5@{3w_Jh7U299e82^?e7O89^I6x;&;E{|0}&FDjU-o~VeF z^J(b=OQuXK-+zODVAsS!44h^!>pGO(v};5{o%SJiv|c_jH&tPpsg{nlQpB1t(+I!q zu%q&5Q&)}YlC7RY73#qMjR1-(tvKh-=G40LTGtZ^(p6nlxqtNoS?8<y1c$L>;*V}B zOp?8ZWyf14p0Bq7F;4~oZefm4rtxK1*r$Yv<=@#~fo5KQ41bkhNI~abPFeXaE9P2M zHi5G%tVB?BT|}tV4=<nXR;9v(ic!`*yy`h!w0(QZH>hgC^f{s#c$`z*h)MrV1i`VE zQ0_t(*<g0?`6Ro>qI)1HUcGiZ(ZI`q<gV*m&LJA+jV&`A%~_ANu2^b7+^B06Yd>w! z(__ZZ&t}4@XieTpBx#L7o4FO2u5R9oP39fPT3P!|UYtjPK0K~iQT7(Ock_0^<EN0C zTGfw<O+m)1VToeu%UmdQsdTSEwVJ~DWjvw^AFsYe!^};14$@A~-6%=ST_Z~0qHrbC zkC+-%B)XA%J}-X&@RNg2y?fj1F|3ze%(Iu!dm1;Z8PRrb=N~-J9LTm~Uqd6M;dlCp z1aj%)xJKV}E!hl)cIV9psqQVu^wj5gKG6|_tJoJbYwXSAL$SxNXuV$p#LsQT$}pVX z@lBmIcn3YK?^zZrE1*x=m$Ywqhp#@#gD^lFSRJ$HZ9bgI$yrFSKhAcCf#b!*5Z?Xf zl7$->V(gU8=Nq+2z`Arlj_(^u2mcrD<$UR!HerpV(e}Pjgn$r<ZT<1<cGW@)JCFBG ziyFtoz(`?O)N<^vhkLtina>xm5mBFF;uA*Lk`1E%;60=urV0F$%QDgZXS|*}6q{uB zc_7$-IT<x8!d2qsm(AF~&bS3=qUK@20E+0OKHCI&5XZ?&1dZX_o(JHhbqZ~sYuA*k zGHV^*EUPRE&!_E|FG!g_hHkw5F2Md1*h(<2np#JvnW%FAEETcWmsL@Fv2Ze-On5O> zMNj!c3E;Qxi4UrE@83U3l&|KVQ}V>-4N%UzY!z~C2U;5+rV}xvoJYQseQ{IvBW_N~ zKzJh4$i6hkrFNa7-o29@tMqY=!kV~$wU?2TQ>N=tUvCo30?*ZA#K9zbX>XPL+Lup1 zHCt}mi&f!u-@Lxy5QCGm8TcqttCW?BM>YiBIW5`bAc33VY`Uo=R3FG>q!H7a(SOvm z-^2#qlv7&RJNrEqK~uGBCAM&SPAG1-6|i9QV80cy(A?AHws8aIkkcWlUw$2Dy8N0% zDV{1@4tneix7#O^?C3-L6xv7!+^Rl#!<0+o`E}o3+qk@lZky_~Pua=h&D);JyPEL! zDfVV<xKuy@5s}4Ku_rSrWdX=%$1woM*d1@=V*njaQ2$bk;}iJmuWG<sz19BFMZ3E1 zPqwPL?L}{wDZQm}OSXRuByNbW@$?U>A!eLCRckTiP7{;<pYX@A`qplrmp$Yxfr|AO z6+asAVs70_w9mMgN_kP!alQlxk!8O7=gZ_tc4EKEWNP{|aAOA(tvSO00wbh;N1ADW zj`qiAjo<<^4kLDgu81x1B|MV|gN^HpcHP6C`}=#vAMSw0uhw~dU$X1~B}vk>o?WGu zp$2%>Bqia!Wv`}hRbhJ9`H6PS0DLGb@w5|0%7E~MZB!H<ceA2jF3Z-o#{m7iOeT;q z<H=xd+CBNpGjAb@-pJs|UGyzztnu$TlNZqR5j5t}CjY$HCliq#tu>QeBfjX>3O0l6 zSbnhS=hyd<egxOLTq4nz))%NOEPd2ka8OZRYM4;yE9B6y8i^80&=lJ#hKT!cZq5_@ zWvUg}mLtD(SD!wnwJbTYB_VkDu&EgV*%cY>mq#vC9o!~ES$~^YuE=n^cf-S-HN0ov zbOi_LJ5BM)@Qv)9Fmss6S9&{5WOAB5<zst05Z^APn+U@xcWRy<_(f9kGr7I-5r*;m z_8n^g_Dz@9RI3vzhP84m>@vAvbi;AqR@LTR*sq9zoFqew7I+3yitVW`%j`B9WM--k z6F+ujX5i{MpV2p2`u%{o{~B^a;to4~j4I#YiJgVFo{#15uge^fcNhgY+D{)7k#KZS zR*!tr24GR58a*~|Jnd%z75zrqsb7x~;TwBl*FM)^2MedJ$#Vy<$7K$R+5ThUApUc` z@ApZJBEE)dCFy0W^Isa1K({)X^nm(gSD)H%+(S}{ff`-FQ|3Ty-fD}fET$jF!>>o3 zWVY1=5?VU>6XBnUtuEW1Tr!|=<%N+1d|jV`<R?J>enQaMjL`k01xh2S=Qur!3Css; zG%ewZdn?41bYR`tpq>_<SbzW5dLM=^7HWd7g>uD%<ES=?-ivgy$vQ=?`1rNnR{??d z_*xR0u^kDAiAKM57&}@iMr~>St}U?<rcZOMXYS|*W=Yord{FJ#NaHtcd6SO87*0{E z^Jh8i0R!Rq>lRkk?#Fh+*Ls+)I@wH|DDEkT3A@-dG<U63`#Cw}qVXCDN==Kuh~b<u z_v#TVSvLf2O#e-bzZD>Ap3S;_@2NGm+4ba$JoS=Y&iut;b~qC8T;*vCl+hEMNZv*C zI1vArB4le;=<rrvE0Qv)QTV6B@PgGf+qKI>)U&{nhM@&z5_=QkQx>_DhX{8+Y=ISY zlJ!=VN5?HQduJ?5FTfE$y0=?l_lgg>ti|2nI1b!tg7jrlIkJ+)n4J~yC%`hSd|Ev@ z(tK_=SiEWEZM&~upLYK3<|Iu*W^Ldv_O@^L5S?;=nJ*=7_?eKhJ+!Xv4d-2dbyj~6 z)k(3NLlaeh-ttQDkefYzZ{nYoy~U9L7D*Cvme4gt2_+Pu+j(a?+$Oc-NSZ5B6s8kp z8=Fvl`jIIUGL;Sb6-=lZXn$YV1JLsYG~SgYKSRWDQa&vb7qZHa$n87`Qd{6i?NwD@ zrk&KK>jlPdISq%SAjCiAva}oeH$Oyk5UqeR%^)L#LHyaS3uiH1Qr1Em+<@m>6vkwU zoc6F<|BiFCfi8#ff<MwFi}%hL5!eySR^nY3KYZfz{J!NxY_Cay+tP7HpE6-P7Rc91 zRE~{=iLC9co4f)UC^ea)>|Pchf2n;l_-44tL8vPbxo_pBG<>n`=P7!&`f(HW#JLl& zc)hcmPqov034#UT1?Lxkt7-Cf+%WlcGU%$%%0)^60Z+=r(ZQLdOGR#bo1I!r)GqWC z^K!77<j71>2^kx73luasEN$Jh9W)Tgr`d}I?18K}T=kYV@c7dQdS16bu8k_ouE&OD z-<~umVd{=Ph46<l58Cnr>yCm6@Q@4vc7KpQ=ig5~2t{}*x&)o>nV|?JZVUtIE*eh1 zoQ=J(Q6~+}{3X&BB&CQ5NPx;TyMc|0j;pL692|IGDy{pB+HCZ5DSog`quXs|cm9_l z|FVRcbhKZ21k^|{*P=KuO@nD%8S+=qOr}T#sDbe$`V&bVB<|wG&vl-QzjGxk*UO&m z$jabSP%L`djn+POF?bW4A&{g_&mj>-g7>{pyXeVUvU8}VWLEF(@2Jh&UIvI#M!s36 z!=iOCX%YTG6?NI_HFK>!7n-%k?=%xg5^3Bm5(E;)OCGn-XEfKprl{)O=sltn-in7- z6?;k2K{ZO?s#G<pm4vS;4B~QyO^GzZueJ)YRCmYf@mMmH$fa@)289*OY29}Kyw!py z?kqGK7SEN5dxY-EuJ&Jj4X!r=juUgX>5g#NB&3p8pH)BITNhqzhKXPdTiV+pDPy&= z{eDZNnvD9>M_2uI3d=))y<6<ute2Vm=&#(;A5iekeK3xu7*~=*3LQ%RmjnPOMPScs zE`m#@qoAGeS6tBOxBgHJBSo)>k&y9_!6Xj<`*|U7p`>T+3$KhWlzSU90o)ZPXmx+l z`nvS?boVZnA(ZDEtcz7jR2n%}hChwit#3JAJ9|?J0>-#yO2ozk^t><>Ef$l17mjBv z>KTTu0on%jUrVcM?Dg~3x9xSBm=?YS;aMQV?XTzSNHL%H=w#+xzpIF9B<zRU9-Q-R zl6N~!&`EQ@Q&Yjoer1tYtcbY^FZoVA2-FaiEG0RugME@;?rrqJT)XjNLyu_9j!5M= z6FEl6rhXeP+%4L&yZp9NBLZ5N!qlzaw}|Gxt;$;!j7&aLqvdp*$psCweJ#Ca8TI)z z(MK4(*gnCfG46Ce@5|yuyvzhk9PXpYBSJNgk%Jlvk)@L^6nBiBnd}<ja4kJlz;j9v zMwg5aHj%0(mKW*r8F@l{EV4nyWs@jTaf{ygtjqB#m59Pa&hU`@T{25|pBnm#TiSqO z*akZoVfu~xF@H&`tHq%YInh6D=PW`3z%7<-&Rtu4+OqvLx5k3SEFJ^!S~sihsKR9^ z_+?|k%5xq-DN}tg#`bV)W?gMNXnunC1pl*CqpgT`>TT2Z`kin-B8O6=JxD1GmAHZ~ z$RLY5Q}amw+Oq>9NHh=Z1WJp9sy4qGMw+hjT-HJf<WqKR<anO<ypYN^{7U|V{N8m4 zjGw_MfC(->r|p>UP6*NsV#T#)&P&9Wy$$W}eDaqRkA$?m(R8dsfDAW2wHKXKQGBOI z?BvzYow!3et@CnzPFLku&l%Bc+d)4h>kxjZIVGpF5K8z_m|Ml1pl>WT5GC1EYB)o( zR2RK`QZ`$KEc?Ve@s%RSzmjPW0knI|a$r~SBL?$@umF#Er{U{h@~^(9Gs+(4y&^6H zo+O_tw4Y1+sB0W(;C&yRP(XKFPI2DHr@iX&M>U(0>@wt3Ba^#EwmZo$;q8uad3<l( zWgz9EA3+I1rfOj$q{{RrFuPd0z4ljcOF3mgUm5X^K4Ql}i%odRh>~aTHz|eFKf0B1 zEw#pYHNi+77TQb<%GKulvzd~MURV!;YHs8qD)1E4<onwKDKqE^_`OeZXQ^mUHB~ew zcq&2f8{6*j6%z?$B(p{RoL)}9IRB=D-EG(P2APj5Lzu7T$;vp9z9$G7$^3fHRb3s9 zP4K`)9iNQo4T}C7eC=RlSr=zqB{?kyEP+V298jQ~@}_?k@)6|$tI+SU`Sax4z0B5K zdAlPQE_vGy`Z@gdbV|G6f|B50KnJ)B@&oq4Wn)?tJqjhG$?Mo-q<29*v2$-e)F;TE zo{v%4y=aE8uqQ4wD%Mmn;{&a!=rT7AFm1b8jd-)a0izUCxbxF?DwtM9%ReCOs&L>& zYx;c`5pZIO5ff}lvceRJH}U)0mPECTmKLeZi9%wULEwaV90hAyo9sQ{`s#D$E0@AY zgR`**0bUkmq7i*y+xs^>A-SijI8PHjT$~iZWLugW8czqnY@+$3(L;R{{yf#nE8jiA zgaF%@v6mpYo(o_#(WeJiPi<Gw`oW<O#>Y$z{%~-5F%ift&0Rnn{9M%Qq5{6;{TE^| zg2|oP3A$j#{r0&x!!7g^K0%VXt&G4kXVrtq`~GVAa%3kRti+pQJz^6$7rZx?&kX_N z@1EvPKUn_?X(#ydUa8;YG5DQGr}tLlr?xZ>I=A%xqU1bT7;p0q>Tfhn8HZbb?82-< z8%~n%&JO<FHzZgi@e<8i^aQbuPK)^trH(p}!2Ifb;Y!>nJ<Y`CZH)f7X8FPOD1U#R z^i&-7t_Eo{Pd6(;IWhb%Q>XvTLgv*}I)1Y)!(Dt)i?~Ib#hK#4^1Gm~z17&+En4Q* zmFL@>oEJ>WJ6+%E_J@vLDv35~rT8;O<sna1)|1THu9RF*d{J<0XUt({rF^bZf+Hb) zL4e*YkNlh9bLSqn1qUF}Uu!BD6CCef-aN21F|~Y6fJyG*e>FU{6s`2gul((mr<F+U zoc{-F&S#a?A$t|ATJ3V2sH4_kAx2Ve^Wy_59tA15D1pxXNNxGnaMhrtKd_m&nIqM4 zjzlI>;1wNB)tuumb>6b26+*?aU()*RQlUT=<(+r-TWAq4UWb92A;2t|d~m50YpoPn zO0j2+`7|uc!|T^XTe*LKHqH=O!F?;IR4_6FcZo2sMchc-F^c83#E+NROkV)1D(Z3a z1#Fzj{=R{^r&?a5FOU!mTngasRet%_)vV0rx%0JYW~1Fl%d?bk_vv3tIThOTZP}9Y zb-<}E915kj%Aki9F|Ds)7_G^CK`Y(vqFMrsjp~+=(vR}s23qDBoV_p!=k?y|Cc9ND z4Zs;2jfvk4rQzfnV@$^XsyWNQCf~3R|BxI=m$XPX5~DVdZs`sw>5vj(43w5m=@jYi zklJVoL1LtYfWl}QNcr48&tLKE?e^mOT)WTDeO~AFJq~O5WOtcVH%xr-a|SV}8dQ>G zI$-yVXf@8j%hcT{26}`Cu=^dp97<?CQj=Q`+d0+#JN6wy`FYO8q~mvoF|T9f44~Dy zT5CJ^hmTMRfgtiDQa5h(jEVHzSGgB-iF6AE^N{Np+!|F#l8gx-X@ZHwds|sy78Lu6 zslg*|=6Qcodt%mM|KVtepXPYP@!A9_dhUSKcUhCVFEk3deaVuNd-@x-yZqzzoZcf0 z)vKGZ-}d)xmtN70#%u-E&+`A}<Bb)~w;W@lQEXOE*4oc5gX9|L%%1Nqv2n5C!f5@5 z^*GL#<~aTOSCRs8X-UvjFxLW$O;sD2GH8-Ys&pnaV4&11ywu8Ef%deb4wmIY2y>5a zSJr6p)4HPeK5xOViEdK~MzJ=kcA>NHq=F?#l+|r7>P-!mfs`G<++EBKDy9~7;EZTH z0;u5%1X&{8`31);`n{LWfbo7ZTlsvl@w66LBm1wuVRAT-Q$lP{7a9h^Ehz`{FQUx8 ztEkyL2=<U4djupA-!&(WbJ*8tD+ti)4%)_BlWtP~-<m*OW#;J*Zr@%tma1RZ^8Hv1 z;|p1^OA_Omnhxjq_E^W<uz;WvJocFqKa-Bdn@gET(YDaKT5PjN-{99RMb#57==&E# zxck~<uu}D>ly-25hjzyoME~+4JEeahsKnruJ(m=b8C8B;R5ungyBt(5ikD|%`W>Z# z`Gd9uau~aYI_P%sGF)DVRS8mdz*z>5NYWC=Q98<OV>1nTEj@A5-Y>P+3an^Mtz!b3 zD#ZAe5>|?3h6TyIjJkAv>2t8ioPIm%vfnLfD}v84G=IKdCzvii>l>(p{(C3WsG9Sm zwA|)<iC1AxqyFyFV+5Q}%OCg0szHLiEr5-7<FtLWwmX1oqbr#(0%*c%jx{|?^?N3N z{p6ef@b7P#@z!v;PP6KAAN?XI%yt1uI*P@GxeX<8K?$=|4!}1CN2p4z+UVsi$Di`1 zN$$}MT$i!X*|!s=@-m$L-s3X!Btuo|Kt0<m)RR+Am8PW1+N?MiFd2{M*aRtvF>?An z16%|DyIae8Tp`fcHwyDU{1w<uEldD0SH2}UQTqp-w^OVX58DfgbQizzg%Y2IvdgK3 z7a+d>UrvimR&18y>~ofJwbt7E<uDvV0F4WLQgO?8u|6b6%-ib#u>Q<6oZ?fc`nN89 zd%DTzziU43v+rmSNMvdZy%(AAre+-OnL2j+q~Y_Mr>qvNf(A+aTT!Hs6;O9ZvqRiO zsQbx!hW4ate<DO+duRg;k*n5o?@S@hlk$d@;PprAC!2OH|00R};*l5tWail$W2(-0 z-vBO>e7Q0s#CCJ^t@^k!A(g_@teC2~lj7mwr)6v^y<~pdy|uW4s0O;z&kjBjmU2gU zD|$jt1P!}b3!ci82rmSYxcEO#)hKfu)6(8pim!Z9V>s3eW1zvd*vNA`Tx`)GIDa?v z7PumU0eik()yJgOTF3|9XY->;`Xx;mfyXJ0(C>anJYQf^B(gR224UKam1>myu8wnb z`g3&8xeOAPQHEj@I2w*Z+TJp_>v>VZN=G(Zu{U}f_%7L!AD9Jr4Y-=Rsl&2Z<_mEa z=~ybEekLk+x|KN7pP-FiGXbfsN(QMy25Wn$5bK*Aa-Z4b{+duq&w=Ev3t_7lg(A6{ zbOrSXZiN2T6G6(tn|3)Fb-I32%F9!!>FmSaXEFqh*8CW?xF4EaooT6tx46vFvEDOq zHmi5)Pucj^`j!(yvROXp+a2EuO8#yaj6IuY=+P(tL9`{jsm-`1h075+d!d|K39T3x zx7ztMr133PSzOjK<fg%xO?mwByEu%TYh>p*HG7RZclOSJvXw1Lv%$Jm!<n0T#-COZ zh$|vx5yXYmP>y`OJn*dI0p3YdC&$pNuk5GPnc-z(@8ezEM%5sIi39Dq9B;~xBlltY ztWQ@-!N`J<9V87<ladD=IWk&~>`HOa+0CO#wXA&t_oM6>sK~T*I^lXvsJ+sSh8q+4 z4;fYe5|Y}(FHACSg%kzt!*(`&4rPPy;j^29GBWP?;zCasXgK3WeAl8uwCkP*(jqSU z;uoy0gd#c?#2yJZ6tKb;=LZ+VK!e%MJyHERr>g6*0sH)y4sX{!fM`MF86$%RiPVy4 zzr<)p0J~{ZF_WzNKs|xrQULIRhy?7Xr?7Hoe>nV!0qQp`cj*%jQ$c!|%*4xll)=qv z>`C<dDc=rn^Pud2kEFTCj-+JAD!yPg=1G4Rdx3#jN40Yb-Y$-pp31_9ua#uR)OQR$ z(itnmh|4uS<ukd2M45K6%}++jdDf)#9o3JG%wOFd0)as3WNdmPRp`rJT_Ex=HvQSy z_0=@Y-$^thg$8S7*cJeC*p0&8K0c_sIN3|_(}Rcjk{%5Xc<h#^YNau^1agCD2d)(( zFk3U0mrobSdxg;gKO&ZIc`6n6yt(6NLv9%e<_i1Q%ly{&@~fR}N|*jy3}YH%cG1^2 z9HdlavRuZ-?KHEizb@9*(J1hr4ekXtDwfD+vpo>U(kUdWMB&$u?$O@Nh&9UZ3L7LY zPGlLC@H)I@q-pn4{rY@L*c>ScnSQtsf_CGcFe&WAHp{*P6Yp{0m8OeU3Ug7y%KRcy zqHGA{ogXt#USNl>BcRr-;(S)O9kYW@34)l38x0Y1+`+&_;s&~Vilg-y;02*MxGvD} zXpVxez0{y4@ytAHU+mc}9ZRFCx$dx${UP3Hhd{nYyLWnnhpELNV@3!oXZCU=hV{!k z0kU7L`C0?%;^{T+s$ddw*qrKBZ*2qPtcL!d7*EwJq@7K(!pC*Qn^UzqmWNEd5T_E3 zH_Ie2<}p_>Go#4rdoUm;VU&2TiS#Psmc#dKmJ45umE|6tB7=R>JlmlZp7%&3qF8zp z8y81bDgkQy_#(q0ge>e<&|RfXv0_aGlYcGXSnACrk&nb#rcL(ODG7YxFsBk?jQ9D& z<zRu-i>fj2vp(HZ^>4k}<P2zjOhpnv5;rif)0BJA_{PO{6+epw_?`+=vyzlVAj8SO z$O6E;M~?IgGd#X7)N4VE8f&f+*TmLuRR|kb4J+q^pHV6W(#1e$ISWD0toecl0<ZCP z1H6Twh>9~Chp%j;4?P%D;hT{RtV3gGy0APx4yi&_%QCZDjU0iP0tu?(wUmKr6rSi> zlv+Fi6>JW_)~#=nZBuyD%H`^v@Vl*zrh<Q6RMYV~h0Od&c&RBm`;;}ZXgOxY`wmf3 zc+yqbMz$%rDPAVO;3-e1T#S&|y<<3sp!Z87KoY>ydzRkx<I2PYa14aG^hI?9x)!27 z$|5d3w>ZatXpRgryZ9uySkhqUY`MPe0lpCoqC+TEgY*RpsQ^ly8EENDQAx0b8zQ|# z27iU(V;U_i8GD@%axSmVe`B>p;i%U*#ZuThc@<Qaous{CT$GFVi|hp7MIeaq17cY$ za!ReC*ax<US;>utK>O&|u1<7Sx&&z~_k6a*7@&iWLAqTRR|vmA*TP4G4@9;puWoC@ z5s+V!S;jb^)bznavIMgNdZt-Iq7Cp3Q3$cgN@StKK8;~wf5=3&D+ZTOzT(aY6(5`; z)2kVYSmkFH-x^y;k!EToLeXQ)*0J$=a6%W06(~=+>q4_Gsn<mp$m~9UxMlzKz@%m1 z`c5>RCHarp<>2}<SMW4v);`!S&ZH~yRly*rxwC<3iTR)M2HHA(k#+=d)DLHRjqQ?J ziV=Rh*cJ`iB8KQn_~?Yk0s!d;GQ>eeM5xo~8Gv4SZ!YIZ`dFS`XLYZ+jU|?7u6z{o z9CQO9qLlf=Y6*IUU(@`aJ~F<`rJ{2K84THX+}l;~pc@$$=ue$WEo$C((D@`YX$idA ziD^X{bW=Hek3OgYu0CrgTbH}=GWNkUF0rB{eDh7GRC>R55)|K1t5&LVXUMDXx~sO* zDmuD_PW(Jt4m~HZmX<qD{4MfuT#bkjD%Vkpzv>t|WuRFdUM)`o)Hc;3dzK>4Hb%Ux zs5fE5%3v;a`E8zh(s9m1;Q8SAa{Y7kk7U%cLO{5+f?hwS(N+AfvC2~mNvh=^z~MtC z&s9!i`}(PbuuIzap+#k&9K9WokI@AuG)><qfc*?_(pZjvqjzXx5!>I>B|wv|;!-*s z*V8(Z@8<N6ya${{Yyf!=VTzryiOw{~@c1xu?R@bb?@sMOuo2Zwj?#7*y!1#*c}16K zZyi<~)u0FoIgkU|1ea>8$-t}R^iKK~hTXed(MpsN&=C5Fqz2A%CCP=PThc(3W8@C7 z4c3MUe62O@T2L0}y1$1~wApOrcE!t}gE2k+*doQVcitYV?O(I>BGNA!z^nW0YzEX# z-_kaEi-=Yo;jv+P%g~MbtCfDka;XwXz<cOycsaY%I6~dGt-x*OG$VK|Q3Q9rAt~9t zm?xNnx#xm~&uY_6RGW2v`|>zBvr@J&YP?9A89&o6d}VcNbh;{^YLsILm!S2<Ku;mh z!&X5>%2i-oWlHR30W%`ZCi6Y4pqzH5Kk8LR*I48U=Z>6P&pA>sYvjCKsAol3NdWI@ z5hJ$cB&M^j2Y|z;lcyIv`dl;OTl(cjXG>=3-DM1L&_)G?bQ;4expmSelZ}-*;Soby zjW=kU8aDT~Iht6+8hD{9s*Ky)>9fsxAJ24&DZ{+}v85F80r??W13V99(5`MvH14Vf zg#Dy47OyH?D(G32V;C)$t!BdxzKz;3l&@u(kac)4#<~{kGQIrhUx2{^<ROWm8Godl zvWhen%@2hAsnDyuTe(%8nm|ofjzAd~Fw2K<^G)L`@<x*`hfnKaYp6sZ&RS*sMAexX z#(#^4*AuCGaF00ON&!~7uJ|TW-H5!-;GU~etTIUv-|n%@&#@W7!=OnO58dat$OAk; ztiym#{>+0}fIrWgid=fj86yLKhOVR=ML)7@e&l#Jw(o0-uFbVPS;cJ*5%Au2nA{~S zPPnf5Mi0m};&Ul#9Qh0+I^e7^lZ%c7;4JHH4V=5any9t`@3#86C`377$>)c*%k59= zaAg{gU5{e3s4hl(a&1ajS0!esuVY6Jo1-i1guk`4Cm*-FJW3+^z-v|sy6wOGW6?hR zgw$DI*C93~>Map|X+FM^-e}l{$TnNY{Q}5LoH|lhKWs4Ozk)*cH;ZD8%|{9(uF(s> zBew?=A?mu5{loks1YqQfH<r0dnRJBdUtD_+EI<M?k1E!o4k8sizygMBY<${xOG4Ee zfc0eBR&h^F`}*Cd;k?MZQCf|MHw5775Ni7Os)x<*QxZ4qq>8+sQty>W)9XhPN@icc zNSqjrPauz~B93^}>AypZu}SI=zw{IxFnkKQ7TD-}>6bu|8sMdLHeS-r1&@g@b+hwY z;}ifteEo67*UeZv;`$Spiv9OnLE!%tWL~XfvFH3KJNhRWAm|$yZZr~1KN6ick=vcq z^5eJnw-$Ao=qBaKc&PRaW<=%DznbeSWQ<ef3j!QOG2j`hb?PLPQ)WIq@^7{?sMr{r zelxY4HS?r&9P~|U^|xwj=lFi2aDohnG|uyH>rTseBWjtt;(A63AF_2V%9fk~RhKnV zg3u_%`+#?qHW)h>KwCD0*Lq0;^M0}!11&<V=<6?r(vC})p6A#2ukEdeYtLu<+CNk> zuq)%9$9%*N^;dMP+OJ6$yF^+p4Agkp=e6CZUCf276Bv;lIuW1u3IKjGrB4S^!1zEl z%g%MxLak|z!f$BXXxQ%UNl$SZnVV<_M+vFfT<mtCh_3c6((MN6dPNjNB-MXhU5!i0 zKkKQ~A9&3LS<)~^2cF8`Mc~A<F+?{Zo3H?5T8S?12VP#S*RNbiO^IRTr%s=T)~}Ug z4k_9y!5jYihEE;S3)TYeo|zKEdx!6A915UsVz?<|NE>_fsl`*&Hsev<bY;>H5>s?k z1)}^GaBLH+1O2omZ?vk&gq`E>B#0yRgjnabR38a2SBt!Cke{(J_lOmc>97yaXNQR= z=LZqp{Jnbb66|#XVH!8SFI5cFiUzKFK;1L-+Zfyn6WSVLpW|`_>=RfhiLo;je;Qu@ zuw?+E*82{5aE%PQI*-Y)iIO$a>jxLvAb$xTf5#!eY2#%IQnmk(@u5F%(~QJ3@h2O2 zi;|9RUSUC<GN1EgO;}BfpgjIlafGU@5|fyXZy)tPF$amg%OXJ)p`QSw`)`K!u(Y@G zOIaE37JM;lN{sWl&q(q}fx+eX!EM7`Z~kkLV!{nU06MCbThdmH@^Y&LwOQL+BBb-= z;5h_v_MP1{Yg!Ml+BQ~gwr~tZu0~J~kQkTq9G`tpAv2Z}KjM-v{JwX5uNCAqDC#_W zX*93Go#1Kh2tZA*bC*E>0BQq!c=T;B_kL6jaXCNjxm!Y&_2f*}3@3cMR0cD3JQ1R5 z0sh+-r}NUmHR{}x!FHjY4w89+$j=fbv<l4Rec?pj0jJ={Ya7^X4NoZ_me#3?syXKp zplNKqdh$F+U}FJ4azWIfcUu9v(RnrU1OS!mipx&A|4HjW=l5Y?O5wbTAfoIkgY|(O z<Zdt<$FD?ACnM6+oU#t#B$jvx%e!?Yc9kn%)^G|h=su4XB27Idsvt9v7PJ?<(cC38 zaRc6K6#{xUnirSu^1J<yIlXg9-N$gmnN}Z4_1Ds~&&w5zCDJhU6p)O{Jhg>14Fowe zbO>FMcwhYH{h@9t?SK~zIz|H0Gta!`5nNIF=8?$ekr9695%#u})+k`~yJV^<BMN9n zHbrvlG24GfcF`7)G)I*!>fX#uYq(sC<JaEjH!{lMx_;IGcq$nm8n+iM39v9{@0-#i zDUzk0hp^yhVs;UsMhm|5lyix6_jtKj(=QLvoH+Dugo=aP24%d$F7DZSESp`Ob-F)0 zOYxuQObv4gVXu;0s=hXd_#AOoweF<$BiVmF3U%wyx_P_kP*kEri}6sNjeNY?=bznk zL^E5LFRxXEJ#}P_)t8{yS>_?PPpx!xhu=vzHrgGEFLjAJ4jwl545BzgDa4+A4M(CR zY-aj+NNQ(?rS|%~`6lpxo$3YOifjozNn|S7gn>7>DYx><K9h=CVF3}$?GS`AIHWS^ z)@mR2Wm;?d{0m?p0j7Wt>UVm)r(CGFrh{0aM-O~vDXy~C92kr`R)QFTsYJQDm?QD4 zWjk3IP2?@U`vmV*?x?nBmFFL=Vhu>>qxCO0C-m$`=Up4=e;|X*{tmEhGl#X#u|2d$ zS)SDy*zV@mlJV-CHp>}wVqP||Cw|!6`Kz7JlGMLz<_e;w=tE^O9qJ!FU*vdV&RVyp ztJ7A%wshdx*!+Wn7V>1(nKTclz4CbXAON8HitQ2tUjTE((R4i=dP(pY=J?h~vb(uE z*>1^Xw2@_<cQFv*)>)S(Q_-g#D7pyWRqagtXgw;vNa2$JBkZK<Qm8|oEObuUuk3Yc z1w#Waf71GR;DdSL>x#gS$bABmoO8QFG3A}G^1jRi@Wr81+hO*-AVai{50k2F;g|ci zPR<_Gl`~N%25G(vxP*8X1Gn66Uvv*>`wA>|%=iMG)S{#A$5m)wPiA*!E8$<ki_e|Y z*W8OQXWc&85AQOvG#3k8nRYg`>Pb6J`UsfzHA*_ZR?KPayk;$|_cTCVebM%8{fg1L zdvSCxRk+jjJcw=4@fp(co9qKGa5#N4yxFSmyu;*=tolutksP=XmRaYkiD~^ZX!0kx z)|q&&e0WiG<=}n|d&x|%tKbDcRB^a%T7(6~p8%q4yzV2|BMu^HLo@#3XHFBDA1W;@ zvaeuu7yl`Mb_k0as5=TPHp~Ie+|DHi%Rk-1t#=A8ZQyW}sKBW>+|0hd`2MVK+sspp zIoQ%U7$r$JbM<~(G1LudUE@NCH!N-UjppHNjKkrgQ+uNn=J?H{rqiOQC5^mp!4sx^ z5J#Uh1wOeKE`szJ+q*5xdHV#6e_Ozj!*l@s!3QwgLiyt1lJjq~zjv$Vi02_w7u+7# vYmxIR(8vKTsXHYI$xDa-4<Gih$G0q`Vjw_AI9>+Gm;X~&ey&ufU=#K~k?w!+ literal 0 HcmV?d00001 diff --git a/docs/images/noeud_curv.png b/docs/images/noeud_curv.png new file mode 100644 index 0000000000000000000000000000000000000000..1ab57cb9bb42ce3d492b27ef74e039bfe75b166b GIT binary patch literal 22977 zcmZ6y2UrtL7dA|jCLK}fNbfbFg94$q013VK1QJRhbOCA7L5k9(cN7p%5a|K}(n0A> zkSayGD1OWHJnwgX|9|DmX0tmxJ3Bjb&VBB4Pb^eVot%_`6bA=~TvG#Lh=YUI4eSRK z69QWY-7lxW4=%<~T^Z-~2-7wW4)L&$s;Ljk-x=ZVgu^AF^6ws(xTvcK#)nG+!X++l z=jkczh_G|<wnJfr(M~?VA>cg9!x7<(aB}>&jJT+{xR9unkQf*yCc!14Bq|1Mz#w4> zNip+(%iFm)q5rE8EG!CCz-xj)J9_wGfL%Qpun`jl4ofHld%y`v(7(I>k{~|dh?1wL zyOW8Ny*2{4yBb(R3aA)3%&V;d)79Y;R{{3j5pGVvkGhkCo5#&1Dz4rhDBy^in5cxX zs4!SmQdC$>3<R7pvU9fcM*P3^s5-j*--2S|k|1G_%)gDsI(cId9_ar)BTx@e!Ohb< z`PjMqdsNHO!`w#F3+5?dDD9=H=jej)aQnB6Pk^V>zhxYqum}gBE#h1fsz4wA*O@>y zi2u3|q!(!9ref@`1PQQ_5p$6i_i*(5x44wCkB)<+E=Uy$5`%i!8vzYfcJOyFvXgR^ z5Ysg_kd$(eHgFM_F?0dzng)n#ft|7bnwqLA%18}Oqz}qN+sj=|-CN8I=p|*S8`{y{ z#7P|t#v<({QNSacI?HGo`0GGbl@L%};J=@wfu9QkctB-cX9Kj3ww8ly09q{|z{pF_ zz|P%71?U!K7qlB()5X&n<DsSFYp3a@D{AheF0SL^@8RaDq9kTw2$VtjXhBR(#I%6k zQuD%?NXV#}c<4y@X##)kMbSV3gqyZlpqH7igAo=ag)p}FHba@4VWAr8I$)SP&@$yf z6K6LUD8j`RxCG^-1~x*Vb)*9AHT2C;YBGLaz)`S1)F}{aWC8)(8M#8?<}Of8Whijm zAEYBAqX%_$kWw=ODv~ntbq9X5WsEfgFs_DRaV?+>+ztVeK|qzHF>sKU0n$-b%g)JH z(?ir%O$?){f^pU|K>M3Ryu{56G~6**pjKrA;A`w-uc`rYbAXy4y!Cv{lvG@hT5vC{ zhoQ8w1K8Qg%+%RP*VzMYW`NZPp^?7ICK7%|D1D$;+?+Jcogu!ynr_ZcJ{ll|zLJ=< zwyBOeN<C0YM;oZwNJ2%*8;$Z+bw-HkxG3Lrvl<2r^^*#eK$?3X;8GGd@6P~)b=DC_ ztALS4C_9*$k1|Ty$zR9bz|06O1M@U+3Jipzl{8%p;f8+R(%#M(5LO$m>nWqAr>};9 z0oNlO4UJvZRMBvRijlaKtG1z%DoO_?tq0SwS5fnH3AEEz*Mz$IYPrGev0{FH(yktU zE_TWwBPBH-teJ|KuDZIZI>Iav4RP~ULV-;&E?`d=HE%CTUwsb`xGqLUM$$#f+|ySd z><7~K)ACi5QbO5*l*OD(-Sr&JoG~t97%wSbl(?UaIzrdO(MbuR8|Y$))bU5?s2XaD zV^L0Ca5Eow8BwU7gNLZ0u7<7{O3%&TEkH`wz}r;i=Dh*7M9s-x%?0ag=%gZrG*#15 zRdGP5!j(P20dOrzuoBR8Gf8thh`pAnG*aK*0ivOaz^F=rjb(h1-oV9R52Tyg&3G`u z8k@P;%jg@KVUXTZk{*UyUh2yBNFyI3u&%SA5n9O&r0nNn3I!q5m390<P#JSaQ~*L( z83wb{M>&CA1JO!8N~oJEb=3`2?bY<);z+bqAXLX6tgo%>A+0Q_ZRo3n!k8ls)S+g& zFpQ3es4vJvOV7?hQbSYUS;7}C<7xzR#fT!I+DIihP!YsK#v}j?w9Vd4M-p!DqvfuI zbc4c8#g*NBP2HqajDb_`VxqqKz%)`el5&#vH1c!Tbp!^BnzIi~PcqQY>!yEPwLQcG z9gUFwK3-rql$p7PmlxDW?`G=h*om5o+Nr9$tHTU5u_kWjCQxTFFB24Sm9j5F8)FVb zAr16VW~N?#9&oIemKreml--mKjcx`XS`Xv_Q<E_e*HJ<kA|VKU4J9!4W`3(9HS9c5 zGMY$bkeHX4x|WL_$VC~ctQx55rLXGjD<OvUK!N@3CA>u)z>bb)AZ;^otd^!YNJ|t3 zcXPlPNx7P;xvAgW>ZTJgUT`tAx2KMsoj=w)z#WDO@Q_y14Ky$e01Bv^8#|yuSYt0e z6NCfW$lcEi3$};BbWwrMNIi8)C10q!sGgX)lDD#hm>X2W!`;v+Kpz6u)DV}DF$e6M zvV*<1o*!@*BNI1!;IERZ2NLa$mIRy*@RGGP;c$@7O+&=>H64H-HBF4Ei@l?_lAepB zle(UxzKOW1CISgJhN}W~pp64$blsF>00*Y5gayWwnw_zavbTyB1g+%d?r>9qj=DG0 zQ4MQg=jUYT=;3LgkC6;O!~9V&GoUmU_?ltt#IPv9>`Cfq%79S%?%FptQdwF;QrQzY zuZ)(ocX1VU#u)nr0;R<?j3sZZtGTw0E5Zb6>TK#R4U^FE^zubRAV?=MtcI_z4$@y; z)E(u9GDab^^*toe#_nj8iH3<Z2ID0G3xJt9o5`2}bzrr$^bFkqPo)f!L5f2>oQ=&S z5e|M*U{5I0UB(-0AOrT5LQCqpNI1Kz2TI$SAT^xzH3A{xIw)}n#Lo%js0{Z9`b|w! zMaCKIt>)$9kA?Zzc^i9Z`)Wcp{p{7H48)LH>RKK!J>Vt=>Z+~~q^g6ygqJ?r%Sg&t z%^rkQ4ivjFtJ+dB0Zw3us5k~;EaM3E*MX~f8~Pd|0-d}ifYVU4iI{|#y`KaK7y@e2 zHy%|2aQJHf^P>N_RN()A$VEbRA*um`gTscS2~mRiTmP`SWeT&nXB81=H8Vqw<>AMY z^Ag$@n6hEtDbBmR!{d&Nv&YB!`T0Frw3qn%j`HBwMF@Y7r_1-35`Lk}SHZI9FB{Hf zrM@V*<hOyKx~h-<f1ge~>M>K>&tlQ?O?)&we<B^m3UR{x#a<S$6tMq)KeoJh2RM;# zVWN2yU%`)DXNcTc>hCR+p`gphFm@(#K31XM;4nEHx_cqDY^Tz6xc~3xlKP@%+%}Km z#U5S4<WDKq=_0KQoC{eyLZ2<tPAxpykZbQx#_w6g=S(0pj24{r0|dLAe2HKRHIMV9 zBimfE`_cFOM(W#Z(#j%HsmM>3jj|IPd{Gd-$p@8*LhYef2~VHfJ@uzf>NlbM)-?c? zZwWk!2@R-jDc0yw)W}QZ9)e5U#k1j9T7z_oTF$rJU+xIDUz~9ii4^2Qau^j3YGg|a z(3I=M05x)~sorO7@YCO4xgHp94i&#+qxivYvt%%rRh8j1!s^vopZB!=d|RCt!$@uZ z6G{;lF|sZC)K`uQj(i5U`NY4g6~VSs1yRPqfmdX#){z`*@cS%zvt4~#r#;nsOx6BJ z1~a9UagsYjr^mhaB6wg=RSwUC8SY$jF+7n2E62y&I++Y_qnJ}GHQ*(~R(P>SW$Hi4 zWM+<^y)0z4j$R$uP}yS%dAw`0<Yd!Nt7`d+y%c4w+FuRXTwh}utBW1feA(5^>6d#~ zKQd(Z8y`r62iM|LrCjSuTImqK)E8&O!TcsM)7fr#_58ix{#187B=1BuF51#P47XNn z3q8Zx{HovAyOQ-Vsdg%WWp5Wdu^W6^F!SJWeb8<%cjZ@vtrI`&7M<L%GsM)UwI!5m zq&6pV^W8|D(VOR9PgFJoG_tuH+I1`X{}AG`w}TWxdX9YJ8%k!$B%jO*Q<q*Sv^~yE z9Q~o<Ry6nNMSP-u=33JUT15d0jLMa-#A87RDIQXm^Yu@eQ+NXy(p?pqZteIwv*!Pr znLo^teuox+?SASM)8C*+Ky=XZ$)@;~V!6d{vA#7H+0IrY;^1|H8T;772~rJKyPls0 zGlF$iKPY&=II`soQ1@CtY<?odvD=WP{N~ANYXPi!e6M<jD(LFs?#Sy)Mw54{sXM>H z@+&I}$qH<+G@|gdp_p$zE3RKmCmPM5;}~x5bU(4?qutiuUJIdY?A8j-4Xlv2_9`=E z`=(>GthsYf@@TVHcl-VJ-is_EL06uVQ!F;JVMYS#YvV0eHL-?5>P3<Bo+>#;qej$q z{sh(v%?YnKnjS6%MKPX02JUj$<#9$S%|L@(BCh)q6^3Rm&wSgU13@eW^`^h>a3uAu zve0_^&If;arx(LT^02e@hc!g#dEdC8H|IT9gFkY0X?4YB2JA#waId-S<A8H{WkQpl zazBxopYBc90%qAUOjzG5Wv1NC#7`bJsa@@ONXo^h5Wb1Q@y3m}g_Cy6H53n>MP2z` z2VYe_&F4kripBcVB}HJ`yw11Oz8I_4n(<bY>ab1QM|3VaFxF#&X(5mQMxR^`6$So% z#HpXpA*uWOY=(9ydhPR0{hnX8SJeaul3N>mV+H<D7o0DZg~Jawdfc!c#y=R@=7SCl zx0slI#s;G2?p6*i1(DG3d|j5gEi+NE;LxvpCd{#qyCMp5U7<_Z^oshj_Ownvq;bNv zQ}M^dx?nUiB=do<U}o+&(q_JqQ0zAX<(O%E$_T+;WYPB&UyT&rtQxD1_kPr^<;~xE z^BM&Eo4<^a@4N|OqFRz$#0Ldwt5MGEIpuvDo2%7VU<9%BKc{ehnCT`(4@{>|OEDGX z*2_%<LFMW~v3F5Zluq+{=?bvH(s^(peS65|Q+c>~f%)>roAW}+3U)SrJpEec-tQed zb-~N-rA-xLp5QeLo=ot9i<G|I=pDZgkNu;l-2)FQ(;od*c1P~xlIyAMjE%_=7%+m# zK=JI|k9}9l;*&EX;lF~N?yqX($`*%@@f|lx*-6#4oA3q4`o}XlF&6Z7vbABt9T>;^ zO_J+TI{47`V%@Xu3aLQ3XT;Gi?qXu={)4M!zuf{|zp}7=mK0?ea*g<!daKRsxYQz9 z^{C9?qiNGJhv#1i@!KS<^R8FAIjm?FTHHnV*o(Ebe9P%&wLLBNZ&ev!^ABAJw%Xpk zRrd<MI(e|uCgqyA)Y4hsd-i8CXpf~dadZ1;rgEFXJh`4!0%}=HamjK4pTV;3I>{U* z^{u|}!t^fn7j{D;SMj?wA2sR<Ti!%JLG2wYc7#UxDrl`NPPTs97)uudrpQB5yZfa< zJ83MW>ANplOv$HM+j@BaJe}i(N6knTGi!&BCC!pl8QZ(Jeh3hz7}@Q9U-`x3)=wB3 zy(ip)%J*LUaw<6Bj6f9Yga<CEB}X~GeVd35OZIqKREN<|Kad{Y3aMhQAU=!>lUWK% zN52ixQIRBpG>rO26CIQ03qH<qAS=R9;>firLnp^<1*3_tkY)zo{rOPGodMksIQ24? zpr7vqycGT^CrMrr$zzgS_tSjND=0zl2^ZT|R9j`J>Iafmk}Fy3iYe7E<au!)Ehx%e z&qN$Ge7Ag3D;^@{u2MuZ@~kAnQALv<<C6(#DeLKIrmtDU^*!<%%*rT7S&K|3m3Suu za|hT+<vNHSs8rQo^ZO4w!mVLO)KKb+Py${PkUx~J;lugT!_dy9AQ(KhN*8{ZYnR$n zd}kk*Ik-*P4$3DG&(_^;4mFs*1Cra3KVlP~$+)-wM4{fDc%+7<AITz>7lKQYHva;o z#=esCOHS0#<n0fFJE*DUl0U~^=tG7Hv7gC*HNb`pcvmGquRqw!|1p4FE&H5HNzTJc zhmPWW9TrXYI<D?^knXh|-=!`W<@xB&r)%@gTBxG{T;%nG%FSwG;;2rqze+XF4Bq(6 zj`{b|r*)ini|nZ$u2dPY)-byiq+t9C52tzVb9p6e*oOHL+qZ?Q__Obo_ZnKIn=@6N zkvy{Q&-|4jWYRw-JlwPxuR<%r!U2NuE-+yo4!rlWCgOa5i2vXOoIZj=s(C9dbGm{Q zSDS~vY0<sZ-&IX^?>E|*v{oy**V5L7l&9AHv?pA~+WD$3-Cn-khe}`(!YZJ<X(?{L zRLmy|zk*Vy(1vdU^E2c?+?_IEXo|LOz`%6m`zd;NE(sWX4ft~H1ADjYtIl8h@sKJ& zV;6d~Vhov8y!a(kNC3auG)Bz^Q+W;nMiXF6>&h$)%3$!h5W%?CY`<gLjOT^o66r5j zL67rYJ%?yUU;PQ60awc8w0R!4+5I$2*istvrJX8e^GQvuSn{~#U47Z@|94N(*iX1q za!FcWIxOK9lOw&K3gaxOPJF0Kq~b?(ob}(hx%+c317F7B8~|Q2d4K%f>O1J`#S-c1 zpPBf#&07lTn5rfqIekK1>4ORdU5{&RVX?#aiFI#4fC5NE>&;W(`6J=MyEC>uz4iTf z&-+_^(^6#Ja6wriEDY8D&Zjx(qypinM{*k4t;tGWUmrN1sw4731CPn7Wj9>-s9`Me zgN|AA!szVqp5vf5ajd%EEgkuFGTj-kOdPAcU=|;|&v}pTW9AwddFtE!5Z{%5*mZrf zR&&$yn`(y>d`{{dR}IPf5Rh%zJLWp4+0b#WVH>j)bVB`#z#bikYbbsmMyS&Egc|<B zijp=Hn2Tb#INGpM=DfxRBM?V#b7xY(%o|w+vaP}b0*8$<H5oAz%S|h#DnYE4r#7`B zG>W+DjuO|zPO@FLa9rIhj@@qne5<Qoq|Rvl#n;V)kye_RYUOFN<qsYXuI-UUXknU< z@)b4RBOp?SPE9ep3qx^-n!d`aolL|Z9{Z3hE!~<4O6CrArO_b4ZXTNN-CvGunF#Je zagL@Kk)Y{&iCCJ6Ky~M&eee(*sx0DAo>l2qb7p9ZMY>?V>s!nd0W>R_p<^i_qLR1P zK>+rHmP;40&8^VM_dG`<)3VCZdqvBs+qE+Fv(t`O$q*wLAEBw%nvbt=ERHblf2o~P z8_1{{)$!Vd4{Gh$a%KcAv4aV@PQwTU$-|kyF@76a_2pfkBBztj$lz~uF=t$uX}fdj z_Esfh|8^8J!%f?W4@r~eSnsBhXh#0Yt+OhRuj2a}yvnRfo%Dhbvb=1w)D{L_jH~<A zaB`|CVX7rw<@DiA$ke_1N&mS3*6MU-t|;~#5xKwUxcQhbyl<yQQlr|u?0P_DNOj-0 zLc_uyM|MB+Bxi3I9@SvD1s+z2jQAzj^q+Ypn(74{-}18s&`f)IRevQhad>A#4lpE4 z5NAtnEnDqo=O({N$E1>9+ri5#=*FVcl3$bvf2btN<k>GA?;Mx7FNQXzNhAKtk*joB znO@FcgrYaNN2!NW9rzwv=on8ON0yrDjnI_RKFZb!>3^mh=uZ{!fW~3xC-#@^-|fZQ zXGhAH=%O;(KNK+sHi~wtS4<Zdzesix7vcb{zl)zWkUT41#KHmqwxYzV;u<2S(8@A) zTNz^LtKa?4Df#UkE)Jj%-&e2#=w7g9j8K0;rMQP;6gm~RO+lSRd^O##nMcTlh)#Eo z_{O6{Lrb{uM>vFzM=v9Mm{0)R=aJ8Gzn;A-QMN}V<&{s!eqH8}UG_jReVaI{uh=v# z+#4(qB=>Agt?Wt0%E|fT*?ALW#JvcY)jAu$-VOBMgs*7=F?IE!FuHhS?H;%$rqmi* zW%GvPQPYmpS#_rtgJgc_?V}pnfu$HG^2d+=G6=}6+lp_OG$OSMIc0wTHDZ+arratx zB~{(ZU!wt<i=-xbRP57D{rooez=zUud1EyFwZ@UwfLiZJ<(5n=ZVGQ07Xu&FEBEIS z3e6TGp=C3a_ZS#yAS9lnPXSk2KOEdxIZ7iqCP69C3yDhr0uwssH|h2&?1G$qMcHv- zTx@kg-r5Tb@1De0k(C=KeXOM8NGbks8%b`>^ZD@blY&p@cfAJ}-vo1^kQtNs44j3h zp3Ndb?2Z(Rn|>nHV|{lU>tpO;YcxS8t=HNgEd(*6IOc(9>5UhvT9*KTzV8yzS6uK` zfIo29@V81T%gPDcs97O3lES>&KlIzqN^yf6wQLQyq2nOAR7Z{%YGi9u`{z)sVTs)+ z4(7QID6kVrbT=8N?R-l?`Rn_jPNUwA`AVJd;^ztO_Jv2EB{b5E=;`v-ydNC(D=gKC zvF%fnq@PlB9WD2Y+@U@jUuz|-D`K8*Y%qt&y~DC63DJjrfLjzIJrt|Nn5<@qHl=i& zS`QIY?ObN-=N@~wdX&`cW{|h(XjYqtPKs&ZEME#qnK<6X4e85wAvL%6Sr&1K4rF+t zwV2#F@#%rC2qtO(fX##TTQ}iG)Kv7imBF^x3@C%res*EyjE|*zZb3zcCN{#s*J)|; z7)sZb13EIw)!4&e7k@RiCswErR7s}G^s>yxjYAaX$W4SgzmUx2goIhV>UpZ5)fdy4 zkzEq0GXmRDnBUCZO2QvARtu3{W97GnV@9GvtVCctdp(KE^}gxljTu|@i?VeLt=y6h z;P;ir?~wd>MeLmuP3H4&5^EBjbJgZ7ds~Q4r~eG;G^KqGnROU@$%0O_*!N1y_{gbE zML9c%`WRu87%nOSfRPWkQsn(gohz0erp)jD&`;7<rh`5Du)Uyd+1u<^#E51#je5fp zTI~7_*Yc9(o{Q9pP;&X#q&Ii)wZJRA8Y(YKS}O-tb24fR>ffyOo|;|;*w0esnkgh{ zlbm%XwH%!tp{7_HZfC_C$HNzPy7=)vu(4&3>*RL`GUzD|#?OD&M>JIi#~^qY3V2M~ z)%`L(_Q%OUUImkOw&hUn#xqvhSmIsY_j4*zY(cYx3)Y^Y-j@6p%2DqtZKd?F=QC>V ztdmp-@4KqsvRneZ7j13wmlY!b^jen{2F%JkCeJ0yIwi?HJHHLZykH|GDSqlKU-k;Z z8bOPz;^jPTIx~$-9$fq^a!Y9Lw6L$33<yuYbQWV;p-tz8>#wSwD?SltBJ#XiLGI;_ zk!}CXh#pE`F00`0TV9sw2A@m6r=IVZEEyXKh+26*FsDpqXCqYcs{=Cu${P0`Q0cXS zMN5C0xc%X0x2%`<TQfH6Cy~)0hc6hsIY+gRL!zJ;{>1cq0xzcT8Tqt(I0pg2G;yhU zqFSu8itc!6O^79FUc8E;RphG+FARXJUQUp{RjpE%!@jGT$tn^<Y-bGe1QN7Afd{)8 z`Ba}3vfGLilr+lD-B}uZm@ss{G?BS|xcvjutRolh6QGqvCf6cM6C32}Q?W%K*YnVU zgWzV;R1-e6`B*9<@QS@ilW`=j`9!G&o7O^Rzz?#ndwdVJ2g(_`f8v`BA9BrjnX|*v z5x0AMWpe0&?s-gOP?(B*W{8@|j`+gn64m#M;#E;nn&dE_0gbuAqskG_Se)szGKOVX zP@Y!NPgg^-D8@6j01Bz2_>T%WpN~kDOdiD6)!r2pDjGjA(#UBgNIoBA4Y|HPmEeHe zD7LEr^CCr1C_iWT<+5y|uY$I?jO%$APj{lxN!SgWQyl+`U4P?y1rTSvtKWY)g(r1h z3u!q^GbpiRMSr`PJu;yb=BU6Zp(l+?`~fQB24!|vnUY|-D#JfA;L<o2&BFLYr-R3> z(91#kuUUHg9&e<AP<I<Ge-E{p*Z1|oc%JqF@XV;z_P5Jd_H&8u$9glbCkwfg89$x0 zy{K%Y<ytHsHHn^H+n5FLVAxm6*PVz37DvNoPbEuF>*ZF^%SGu}VBE3?nQb<MoW5W@ zeo%gVtvTFM9Y{^<3VV_=h)d_aA5O|#-tW_FA6lMw0uwMQu2-Hf@Qb_aW+3>q${`N2 za@NHLa5-@aXLPIbM+NL5Q(r3qcy)MoBm{clbDw^1a5pG>Hkmdx2!aQ1Q>l}ZZC;=S zMxi2p-CY@>wHt<pG;8>$4&QRROR<?@wvf<V1?%A3yiXY3j?+IwF<(t57P#YbYXT!K zVxM_4@|5}uA~K&{E(i8vIJI6z&zly>wFAILz9S&6lKI)rgVDS4b)?-QKhzV$l|I4i zNk$7R+N+6wKU(R`)oXq;eXrC!2}1I2)slmwRQ-mpDwPS0iT|X4qw|wgDRlg)sCIn8 zuyEtHD#YRkD)}pAZ8ze#q9Z>nYnO@(UNbdITC|-TZ`uD-Zu5Z2ItBnw91gfd0M70V zNwB!CiXbX~=hfnNWwH`~QmA~CXC;T*|D23K-yVNq`3@3CP5sd`g-z7mQ<F}4={7px zg80Uk_~P-CNwt2x*A$R-798P#sDczx$V@*;8c6m;H=SL`TqKnH>x@8E9^gUk&8o@V zjZ>ZPsiqiZV8<o%FeH@?bkI9X-qILPYZuEUc}n2<lu6#%d4mvNB!vk_KiYM$e6pG) zpT0_slUc@IjWO)~Zsl{oEvGDprd;mA@eep)|KcO``Db3GX9r-WKX4pg&xUZbs2;Ro ztCw*Z_V3l!&w#nw9|zx->R{AJ<<qj&8sHW`AL~`=(qr^8>(1Y;9@3A$C)>$w)AYr2 zZ=-hIZP0f4^})~nrEL~vRP?OeEArO|)^VgSC7_=wTf1g>Pd~z~FAur*2u*fEL%V;X z{L^LiyB#aXoj0^gyI;SvnRw=gIIrj3mo+^&P7hu|9^m=^IgAtin)|HYI7C7b&*Ys* z=d~Gg>c7Ci<u`@y82*o@0)=}SvZE0pi+bE!VrZ+UpA`y}C~Iv$-+A&cZc*u7udMj+ zRPE;n&Pj_d3^%EaFD?5=fVZ^&TSEb`2zS7QHFw#$`G~g#<^VwNUlYvrQHQXXTgYhQ z4U5phk-MSbhcBnU>CT9pgVqM$Ue+|SXPCltRl{5eIJpdCMvkFj_!AYBUmCSEs-ps! zEsBu&I3apsyJGBsr=?n_BQr60Dmp}o&GVzHe6udKtLjiQ!YB0PQ%3bDykt;NEg}6t zr$t@UUA&%sn|-z^FTUPGP0sjv=FViCeIvh;1i^>U6iw~dMIjYqq_<x+uJeASYKpG8 zxADg4TOE`jv$>RT<7ew|N7Nm93`zJCPK$i`5DMexR@=b43Zq!HF09*lNqi;iz|KCd z?+BKu{KA)fO62f<;CYZ^SIoWS71?ufAaY6G_C!BkR%qcu?^}dxSq0nL^v5%HIC#U% zt3Ge6#4+F-_ug27j`t1^&PGe7iQB(j(678p_TZ><KtKIpqg;P4W9LN;@rPy%g<I>r zZ*TU|I*$ZV87%or@)0@9x+R~|<;r@7&sw=WDFv8GeaL$0@UrHa0Bg{V>-gEKlD_Jk z5;T9y;d4@{t`-(NU+jH;t8Z^`9i^>p14Le3ud(WB=N>f_rM0g7xq7UkMfay4mobcK zy1S1L{-u6rrx_6F^Kd+b>)ETll-ma{7nA^(o67BCkg9CtP|rrdDaNi9TQEhO>VDO% z)*R%hkp7wgL9(EN?;jX#t9Sspki)5tvu=PwuULEKAMEF$iu1e<{6#r_K`vCqtKxOQ zq{ncN9u`venW5HuK%h>2R;q9FyJ*%s`SZmgd%`Y=88HBFq@;WQ<xB^a$QYE_Rd{T9 zr(#!VZlk=<;Q_Jxf3e4~l3QwnGDl&NVuu~S#+w)a1csH)Bmnhw5p=63!jJv)&j{5D zv5VH62L*{j?AFo6mrv$3UOp%{JfM&G9q4^ZEO}NP25N~bJ|cU(!+*_Z%J=YvpV`K8 zFRua<B7y_uvp&4^uq}q}2Zq?fd9S-{TUxy1-n=E}oDPG>*X*6zRbq_|u<CD9@{VRo z05+y7hMIwLgQq-G5`xQscjM~WCvcyunX6m2b5Q?wHnm!7!MUY?-=F<J?!<$rM4ATx zOmOYkPfHaEnw0wcW0FV^nVm4Ly5GE7O*KuIbVb=c3l1#?!Ykg{-y)L{$aNNdLB=?V z>VEHP&x^x73U?Oc_}GaQ=|tDN*vC@J(J*zwD^gd{qZHTG$|F-8Je!AY{cB|dQ6UE* zkN=Wh52L7-WyR)RB|_Jqnv<U694-nFkl<`Jf2Kb3eInv>Si(;V(^Y~5J>CTYEFMWJ z-HdV2{OW0sTlYHXSvFJUAbj^79!Nki8^ENb>GOGQH4*?{{mIJzx$@>pioVIr^iJ5| zqABtP^b9~FWA5fpJ`Rj!LWlw4Y=tZwz>;<<%ibDk)%O`jrF*i@f3*l~{1oslZszi$ zWQNul5sw^cMm9AQvE@AVbuG2fWM@w2P;D_}pBo{0-5esSaev!-kg`mERc%uL0Sf(g zjXhnH5nu-Y9!p%rY@UDY)s+Ca7tT9g+X7QF8eJ(2_cETkeaDdVNo>*rIeK0%>VoV` zScmbt?jZo>J}wqB(zTxVKWmOri}>=g%d}5``kJisJ&=KL&oYL{F-tS>Jf~Ez=f*cE z8}_GG`M3>t@D#Vb&%p)J^Ow?cDs<ukHtBb%Q3h$87iX6ob2Y)?kpu3{q+UZ$1N}Xb zw{wQe%uv**U0$Arhty9P@FP+HHkVoj=0I~FH*j;jHMwM4v&b5fX3q)NHhc%mHlsNo z+ZJsx;{A1`6`57UM3+>K_me%lWM^##BlZ*S!pIoa(5fzFdu4jhQRG|XT#uv|b3W%( zXHY=>3qpW2oAAee<9u$|{;VihV-55$`K#C8aOqZOJgtA3BQf&wU#)RrMN}z+NaJ1F zF!>}Qx{Vymkp;zO200#(1D#lU^PHRJ0{){q6XM(euI?Ip2r%taxLw3rUhAtiH5BTb z$pd*JRAAw-2>V?8yh}a6M&D%XxEn+~nb-b{`Tp~WU+aGl1n}jRnlICRGK$KVcePsg z6ZDMDE<LEbmY6T$E3%s1iO0vtlH?Ext-Yue`xD>!o`vi1_ZfY&jzW@8fc9;YVSux$ zYxkqiR8&X!Xh~?V0Zu(IszCHBWQOAqticb56z4TGM!Y?Z+tf&xPkj1dZ74>{bS;yV zgoaCX9++tTyxX7BZia0vvOklov!#i4_8E)Nk0bk9R;!*JJ*);I=N>>i9j{?){sj96 zGD`l169LhS`X4blhmiKbCjdoFoiZ^rN7$zF1Tye>J8t|Jx08(F3+)$zVBl>d8XuFP zW}Y<@g;82R(CA~PepwzBPge(|*2Y;|J7~G^6{sMRmChwsZ~AN61!}R5N+Oms(##uk z`bw$MZ2{yQY8_nN9wx2${C*qdKk-N=q0H+yxe5t+=|1TIg_YsrUDIj4hlY-yZ@s&G z=TEM3I*<475YAk}KT)Kbz1v#$@oTaN-Mg>dMa}B*jTa~Tw`yuqQsvn9b|ag{3Ju<W zC|wahjZ8To1o(^k`cPHJI)PCF6^P_Zj9zi_(3jLxufOZgQ}irP+)H<F%Q==@KnC@* z;-??|8JBC0HF}0BO}_KXlzN)IBgBr6jUkbcS!&#v6rj5<9zCMTp=uiOJ25bwe8p?M zq>v0uN_N!#vp9OT_%)U`t#7l#X>}6?^2v}3Zl6y=-rJ2pj;`MCeGK$xPe<!y=z6ZV zb&y|%i6X$(cV#XjF0Eiee-8Npd&8kxChvLN+NJv<T}u11A>;i;cY6|#)MLiAt)Fja z4_7boAJFlUcd01EP!haG+l2jTkTr)qzIrQ0?sYJuHpSFPC?fze{)}UG=lr6T56x<h zZ^dbTs2<tme~S(NV3Va{%<H|qFq;hX17C4NKH3(a?8xV^`KI801n=I0k=}jXxy*DE zE^jm=?yu8ta)MahE-UMEp!S<|uyI~wRr*tRryuX-{-*_)aK87<lZ(#;=oSA*kND@g zythFJCLl3FrX^85gP<V&a!~VP6+mIDU-1D-2~YN9EtNQwAmu5NY=WGlNYn6bCKPYG zzo&K<3bk^z9v<b}G5$&Bd`ma-E#M%&U47Me?KtCDGvirfH-5&#O=ACJX0cAlFynSU zxv%%or(gcIxCq(kwc?lMIs_$&%}xs31+L$&2Yn2=YbzcrPLGRBdvj_vlRvMVZkBS0 z1$=bEDscZ>RLfmK6r@u|BhO(AB3+>tDbAXRz8vRvRY}A#Jp6s$%2)u)^TNkhC%Ez1 z+$z5zn&U~wJNJH(b$TZYUL3Abn+rb<D?v1DVd7?!Q=K(cg@-u9Ke!;>7G@gAlG-xa zY?>sU`>lNeT>~ot&>2sLayFIM{aPdO`79@b+Ea}DV28Pdl=9p%eQ%okEyuv+_`%H_ z-9~$a5@Lyjk5yA!pH*uLQyBTZ33Vp2T&$<cXcY;w8b0IRef;sENe?lt9#X5fH(=!Q z8ekDKTU<bwXctVvJ*xx&E%n69ZI1bWH!B%1n{xc>Vkt|yV@XxZVi^sv$r>5cio&|R zJC>M))KZve?DV4wA_120w#m7bU;Cv1>P`-xHqZHJgIUPGGn3ecJ0sD{98lHxsHuHO zm!?`V&y?o8+1D0~)paLyrTWNBeSKS2ZBq8-VlUDu&h^=Qz0>P(9n2!kIVq+apcbfP z8wuUxVG-CpVWTL1w}&1*9^tT||5&j%Z~v6{eHOD`PfmA!<ckbwAu<8zBE!FK^%siI zN{9JR?&p~)+->}5R<q5Pj!+nJtgm9OB>s5oe?&8Yj9_1N?7jy^YfbyTNv}u@<an3O z4r}{W2iY&g#bUH0TNf4khuzbyO>6-xnKZF>9Sco+z9!zU67GB#5k1bWP7TWP6@Cll zTl425%w{e%Gc?MQ>5I2d;}4nI>L6{AHp@8jNF~f)Zgae~SDDgQ`I*VVCm^1ZV&pVB z1f>t#*>S6aPCtebtVMQyUu`-%{EVGqY$7*{`x<9t@$02~(p6e;+SCS+9wK>;;5qgE zy47#Sevae$(t>?KZtreRIPLfoBAF*he%Zw3c%7)K7lIIs{GHF>9DbgP<XWcgvTKS@ zt~S&ow3LIhC#>`0{r;&cSI&(+0H(j8;?`@&zc?QCm2y<Q(gtJY(7z}W`}qHRx#Nin zz`L7f{x^OIGrg>4sbRMjCaAzFPS>MEkEq0FOhjWDzc)YR6RjlUDn%H)&oul@(?aCa z>;z+%$9v!5+Zm?O=>-B^xz=qj<4EI;C53&z6y2&a#SQw~LS^h4mc&sId$Abxpj7Q7 z<gBwqJGblu^y?{q6p+Cx9B)k1$m#d#eLH*v_5b@D*SK-GukTsrs{oMZmoHO8mf!D- zFy!L{S$wB>%Cu+PnuyXIy?e2jBS*G$%M8q4LM1C(zuzyOCyJP<Q5X$4=Vs<?l2B!1 zi`5w$WP3%G-Tm1s)X>s{by>}}e<98&tPuj_<-;|fiiWWgNXb%PZz@ybt`OPMma^i_ z$l+y&i&3xQ*1lx-syZoaHqlw?2YjFZpDhN<kk{<+@4vZsmzgM|l56wrvw{fIJV0r* zQ*tq1?fWmdYeZ$~G^8@J96s>A?fE-pQ?fYHxNEk3cKJu(Lh7AT_qwEO!&;Q)BDnwl zqQXA}8RYEENQHt=vF10poDsF?9bEQk2$d#7E@!u{-A!k|29!DWE$YUcx@otBp394> zRs^2f#V+7?(i&0QxrUu_6qwz~BMv1Zop7%MIs86$KdM#J%cf@eeGLXwMiXwH0diaF z0aaX-sUThFv=$Fwo;|0mt^X(lX4Fo8G@-RR`nj~vA?c`ST;^@_!;x1xk#A5ug|5Zz zajbQ$)fC%r3VVx!xKF<_Ih?Fa-38(ZN;B;#rNvYW9fsPuthlg3VnMeIT-IgzsGv?- zPCZ1nrZ8X%B1g-mM(Y~kft*@d6tD1KGLUBNZ308NK!?tV%I;n0eJOa*7+!%Ck9H!? zN)3K=DA7(*`1e8LtvS`dSNTs5$MmV6=8MMe-FrgAU<m*eK)V#K&X)Qoof|U%bUl!r zsH@O4l+66`C0Nv~#vALy=R-kp>7&~9%L-aQ=`NFV?O*{68Skg>igs&RExUF`ZvB%a z%nKTD{HDU3<&dBu9myY*;z>;Mw4#i?6Cdw{rQjU5jY#JdE!F==)8U9~jXV>ieG8Cp zt=8`}*+=&SLp_YRnAVQHEw%Fwd0n=16z+Oj1hL$8DLzQeciH{kCXg~PTjt84ltLr~ zsY9anE=KdYaUYfURAv;L<_cO<{5UF&C=mCgzYT+Yw+HLo4L9q%{pcbpgt(QeDRuHK zamXb9JiB$|DiGppWcS_0HpyjAnPC#BGh$l<Z12$U)Q0^A&;Jo$y3d*y>fiV#|N3Mr zakbtu;HhTJqnVMjWVorTSIxsvb~Y`(w~dyh#j=K@e;R&VZe|$yrpMO(?l1gwu<RK) z?P}T^pG-6Sxjcmto^WO(*XGUXBg?Gy_Cg>!$I|*k$z};3n9L`2S*$}Tm~_3>AZuO! zvNOcDbF`tS{w4LxbiaiCq4>dyvEi-~PJ<=8zZf@8xtjO{N16!+fyp19QcekmHnL}r z?&BxI<<VRX`Ia(~F)mp4;*eX8!q$^aqS=k3hqr^Mv39KPw@sAFx|yg}pRWS^7$v|! zbhRgyYu1aayBy>%^$bT8r%FfR|1>$jD82o#1LrShjP*Xj)wVtv2jQ6kDnSNHT|2s{ zLU-4QY4&3l+~A(tk+b-%vdiQ1?1Az4X#MqfwbG2Bm#7t?FDLITiV}9#Y873#t#k-d zKefm-$MEs2wuk;n05Ah}pUs;8_H{sR5$&qSqxb$eTs2N#ar$||-6;S=fSTf%Ngv`- zYhwr<mqzUsk}H<I4nXcmS9a(hSlc4v8v!g$ZeHt;rntAZut}M<6}aSi_>yt+EPbgn zH7dl@t_POx_VAV}!<q5>R`+jwD7?bN@<v>^PirVUfrYxv1B>lnHFsM8227sqk@zX6 ziT=$-<c;cwz=W_bSt-)KYRw|#COQ?F09W`yl%BfG5Md|-jwSvp@yl@f=_6)Q8+`c- zqiNz;;>kXKJE@_j;kX-7#>N^EAP0=MN7Fb+|J>iUs&UV!9hlsFbR6ZEFdj8N&uIpI zM#Ocqp<6r~J^MI~I?gi1kCo(I+_E-bk`!otzV(u35&bVQ3&0D;s&gB@z-DCd6E@qV zVejux_H}2-Ykm&K+{yacIeZY^vT&i_agy5z0<=N<+1bS9f65^Y<T%wF@^@r|5M|PV zSxw7U^fc61o3j@g3pC>Za&34r|N8hf8~m;uwaRbm$)TWo^<{2$|BI051qPlxljptJ zRBXL<GrYYp*FiJ=>(!%|gTr*JuZc4>?eWD!O2+!*tX@%6ETA5{>%o)Z)S`@d-+A+$ zU)$y{%L3UBZ8p^FHCNEL#(&y((}$KIern0SEiK54kM}epl^_=X^3e!yC31}I<@ye_ z`<@9dz#bQOmGpe~d@vI7OptdVBHJ9wF_OeMgCo>B`7`JrQ9yKD2k*SA!{C!>l9|4A z3dVN+c{BPCt$?I5NpLH%n>?^EIHpp(u|g6^KLit8(@jZJ<}gJiE*H`V5qC7QcHvjE z8FguS{tD`#SGfH9S|~LLN4i^x8hhMYsU;}z{Y-2j6_`1;$A{*h3_o!1B+jAzRh;D~ zEop|nlgjwlaa1!EGQT5w%jBNPk;@tDWSCh@&d)x--Dx1*@>}HXWg|@62o+;OQ3NFM za5Z};su;}LQY~iHkvdp0e{S0N2SdhHEJ!j_W{1~RCH$J3V>@}17j50IVSSM{mZ9Y& z)Y<n7Z#LAk`}t(OUsBDndDE8yFtNgHZTnd!9F2c6%IH|n|EMm^ipz=OyMIv=HexK1 z{mmZ@0p4X|Fwt?A@!{HtOwA8#GK4ps$~Sr!2#fID9L}EY8!b#06i;5b^Vd6#h|vRU z^N)m6p||w8i(HEzdxa+sVc_haH|p$;>&*TAu|zw`OLi0D>E9piehG)qfXB&O1X=*y z9{juK>hlnDc0hWu3s6U={d<t_MbmT`+=1;+BP7E&DXOXab)+p!mK*NoUMQ>OAIWW# z^36-GXOh3U@f42v(cdEK34`F}zx|K5-Vbnfexn(UdprAx6vJK))4X8H-Ax>_2nGPY zFzM83(rtIkm(?_O!ZGCY{qI-y$H^<ejtbuCZl7GJ0s}*QukiNrr>Xy=5CdO2{q7M= z4cZDTm8V(Ns5%i8*IbZlP<Z{rG?HK8?t{?8w|yPIhG!yLV6*FFX8chqzDSG9n1R_w z_IXm*G<s^0o-u%5d^R(~Khd9`$9@w`H$;+G1eG;*C$<e4G@XmDznY7SKQhRJQQyEf zAW2$ao{zKc<<19Ud-(GrFQ^EJ)8b;MZ`_xRJdNGl51Ra)rn?n9-`$BeDh=ArZ;fUF z3Jl$|9LLQ^D=P$@4k9VVTCn3255IFfA>}Ym*gSscS7O`Ahsu^C$KeEO&_>19?;cF& ztdaJ*gatY|9Zt#9cgP?AIbn&<;Z_Iut8wh9#q9ejm)sFSJjrL)92>mOMCNGRiP@p= z-6D+Ud)WZV)~+%S_ef#WB>jfvHrm|{dfo+47c1gF2mt8IWmNrlNlt80f4rYhd-iX~ zsG~1o=l_CLhBvq}gW#0bfF=bx++sGiSB|iqHGDw4MtFX-M_TtmIHif5t?gY&Xtg*K z?|RvCkkFb;o$~E<PXgqp-$?fH8bA(P3~4Cj<$C_?W!KX`K}Gc~F_C<yyk3d<UhS=v zrfU~}e?y|jt|ucuD)`9ito$2#N`{X)Q&Io8nCQ~+Ez`+4;{5`7JWU^KONTx>h*)!B z7qrTyOvW8gPGdayPddu`Ly@r8>T=rp6f^P3I)kmu>(`;+PPjhh`Pz>nMdu~?3qPF= z7J*8IhdhRIQ(YJ%PN|)w2NBicX0CIeAroWX=I(ub9Suj;uMKqoMI8sA411cZ$h~<{ ziQ>Z#2NHa1zkl(0-Q7vmIM@yP`>b*c^5SKNnAwRW6X7TQ$k6qpAe~3!eSaLh`yD$N zbAlk7bmVu{+TJBxb{+AoZ~`Ve`lm*u&G@>>e*yl0FqIM3$N5w`*Hki+T7~_och1RL z8MZWDOqRMVv|PlFz00wWv-@HDBRM^yM84X$0R9TTVhYE)aR3x)y`bGkklw`Swki5y z*?mT*1+&#!)@6r!H*ZdjbTU-L(g004A495Ed+G!O-|GQHJw1<+{K?mIz6h7E`UR`$ z4jTEj3Au$;s7m7d<l#mFYAaKNsl5LN;!@4|Tb#z`A+d@Gs>uY;lj8vr2dY)pfZt0P zXo0m$ghR#^!~v7M1u-@6(#hWc%R{6C<`4u3(y=sk_Tbx(URzS=nguXY|Ck%;y%A*o z{OTUVzj$wug}tp=gb+_t0;0P$PSd+O@V8728gp_!kr&Qp!sd(qHY|>2{t<cAuL5;D zlwIdNU=OM(Ly7_tlBMY7C-c88G*ZQ$3oiD7^u}WkYcq2lz1GUrN=WH}wAiCbndg9y zHJD4EI@GXz63M*|3hC#2+h7>|tGUrh7Le5ERx_bh9N?q0MBxG!Azrq6Ja;PQNhtC* z>6u>m<d-%Pq0x!idjp2o%hM7ePY<V0!}7GJWPCm>R8r^st-|MTGYOjE21rdu&l>N1 zSNHt~ZRI|)D?Mqv?gA%ZO6tt!7(&;Ntkl@<z^yS+t0hCvtU%@c-AB|v{#0mNbmETC zQheG^16^6P>)#nKCF+ge{X0yZDQxaQV^@i%G%0g0Rn|gj)&UHUuuz-oi7>K&`hC3X zC}gIdi9TiK;d_47P5SM#HH7l}e<@g|4aTA`E2nQhBI4A51aty0KI^^hZxqK(+9Cb1 zvS94epZ_8PQyyKC<j${e`YI&>y^;<=_sD_LrxYZ>(2&p7x03B^v3G9-slP(DzrQv0 z0>|BzHbd<$Ep?`B=A0NIwe{?SdrJx}5zdMxsp6Q&|M%Ss*ssg!egdBmVJR-8?#;s_ zx&dm~75Wq)_KH<$$*IzLRm~f%uXX<E0!@(yV0}cPZ>Q00NZd<8C5euQqZHZ_iGAGN z?>`;9SY}g<PrlQkaT#wSC*Q#XC<VJFeAl&(#{6<iN&_4`x{K;%+K^;=gk&o9efZEm zmG8`)YD~X_`X%k=Ul4w>{zBgrgHCVa3F+6|nR>w|m@LBDU4~1c@w^sfS;q7ntk)z) zhwH$8xZ2Ahc>d{02|~Ph<5>)$A6>|XYBovPw0?Ft43GNydV}_^q#hXnqJ0)FhF7E$ zy#Q0C?!zuPOrW06T$bf$M76rLz_A>}xspUYxuPvT1p1~V!OA}O%$W~}UWDY0+rpbZ z%N-YYG?y;$&6yrbq>4*YKR#U%e<FJiqBZ})^?Oj>uHA?KM9Dwfm_BTNqKQ}h#tG*T zh4(&HFtYg8_tHtwDaO#xU(ApmNJ@`RbyP%V=a!91s~#Mf(3!9Q+?*Rx1?H5(PuaK1 z(~3juNMn?`Y9}YLpnE#;a>rw}E8l!75hdk_U%zE;ZErGN=etBA*fpv?&?>Obm`ZdT z2AWmXoO$L2%@*8G40tBi(mxu+S!6PqS|@c27{f$ijMfi6^@FLo=|l{VX~rc__~OgI zCKs=+7i;8q)YLq<{>^^9m{3$7D@vzd&c4$a5GyHm<eogT580~A)>)6j?he_B0iuZH z7h9!=>swcTDEBQR3jJDE2R=Fa+tT+N1kC2k=y9HzadTujWhbT%*)x=vKfe|tN^dXl zs#XJ>+|vd(Zc&7jLG{ijFd8X0sA7vsUi0_55@Z;bPHb$6V_aVug-HMUE~SMJ@<V=1 zK6&$o9O|}37-0|kuGzQF@{o3QD`!(jGm;B1xyo%%3O6!{B@D<@>0C?J*5E-Rs!LV- zZ>-Nd1Txg}AhjIs?(D(n9}p%BaU5Vdh4LkZkyGOMRAO5wmQ`TRN&QWuSyo^c)7?pF ztND`yo#?6jdY9-wIpuwu=e4UWhj)NQHfbC>X-!8CD#gp>Wq7>LdqH~X$U7m%gD>Ew zZ<F03Th+f50}CD2Ur*`0rkcjW2y~u=mAK!1zI$$xV_2G{&P8R%e^0BlHKE={DM?A3 z`}_hv&4eJFNr#vM%W~|pO?U&3wIUzl*Oe(x!BWg2X{2bz>d0&w(KMJlzwb+;tM_^7 zD~7qjDGp{LdKC9B*PlLLC3bbVZGC)PN}kxqTj=b#b&6K3(0=gYeJBZgZRR$4bRe4_ z@z^!~TnyD$8l)CQ@Ij+wb9)dUzn=w8tNGuG2YjFGfK<l6D`T2DyA{nBzT%jv3KwE` zJNfsrw+K@m7C;3wEH;Y7|1!OBrDVJwOS8#W#MXc~v`=D`U3a7?8eFu}0BE^Y4sF#P z>uSRQ89U$1q)jU~%C%&g$UKT_{4S_bZT-B~_1$;;H6GBDJ0(vGD#iE+apyuGT~TS+ zXO(2CHj;-7ecNs-_Ph>y2&@YzX{Hj24SE!Vv@V?K;i5j9wpT3uRXX^L6$onh_m!XZ z6mGs7wY5s70c6<(y3ToN#hSfM^)+z9;Nau*A5>*|-5=(Yj&wZ%UG9JQG=OsR;kC`| z_Za+!wv^iUL`*@#--Q(sDjWmvo+VVfo&nMY<A4p7Hz%{>_N!Lo-A3Q)aR^>o%S8hX zQ(FI70VFIB0j>#9CMJBW6z4_5fc8P~%s!|bKGkL?>l`$RKk&KLbUQE^P_*#x+s9R_ zG-5I{=MbBMKMLrED^?!TU6;q*htaDLq^<L*>dvNeLWdezV(fK^yrdi_qSeep3gE=! zdjK!$&RnXRxdt}yn8N<oj0!^<xDeHL8&${*u&hY!(XNihiv>cI@rVEAPQM5c)a>1_ zg<PnUG!dpza70)Is9Hn4eEAD>ogp8{{uMP@y=|5(uQ&!+gM`FC0;H!Kp&?&s_VSkQ z22=wkW@#<s^_=7!{dp2m@%MtJo3&U)uX#dpQzb#%_4Q6wZbh?EiIbj=N*;G=mT#7K z-4&7tv)oo%i4k9$@Z{9YGpMNO5!qKiEa3lSYeGTJ&1~TAp4q8T(4$!kP5+)pJeg1j z|7VTRkE)s5{K82nKtbo1jDq|t>Cv>zHe6`AC#l<?df8@c(xAZaXHy{km(1&_B;UAm zX?oUiVb&;EB^!Do(`b++`Psnz4o5O~>9=Mgd8M`V?EtdXcZvu9$+1d>+v{q-@xk1Y zqL~q4jg=XZ9vV36oN^tHNnM>1_x0cFXCQ%=ffxi&$kd3IVh<f~=qn&p8RpdE!cik# z5At9CrwS*bV;?v%R8U=tq_<}vh;@yXj29s>{0Kkg<NlrS=W3ttl_#K(gKgInU%EAd zv3}gB{K50_8mR;C4endIKXkl^pMH4rAVbRMUoKyOB52@&_6iFF^ITB0J@o;^Up!3l zL&uB1K0G&q@@l!+`bJ`QWA?1ZleHZTUFDsUCKi(ft_|=n&qB)k27CXlJUEBzl$>NN zWGq74mbDC`i2x>_eM~|mXQONueUtf74dXw6-eRG?qaMl<;j~YGcywyie7OjT(`liT zg8&cSZqfDnn7gjj0*#3r2+%}kaT;mL!XatS_XDhxt^+KsAAX3QUcyp|nHcf^RjCwA zpJ0#E1m_F*<R&SPC^VDDSEY|BIOT!p<c-@2K$Z{jLKE<(xk`VP$PBg?d|B~bNJ`#m zj>CDtwl<iZF55r!G4m6U$$eo${5ZX8?U&F>^(~_pMo2rP3=85v3jKkh@JSPM{G*Rr z9~lOUXoSqO3e51HSN5k0i_F_}zIt``mZ&rkl>L|#fqA|nnY5L}`r=!ZfW@Ex<=7!Q zNUF^Eu=H-uiNU!H)UlWCTONP2M4GIiM-gm*lCHvQP>%XB2^)B04my(fR4vEGl~(6W zT(3gGJ&o$Ye%1u3)S0mQWzr;crlp)pOqEjE@Ej?<aerb{peH2wCRMT?`zoy@vcKx< zLO*7vRt^whDQ8K3GpHGOwEwLT=l>LO7G6=eUE8J^P#Pqq%ORvgK$@XD6+}8j1O}u8 z>F!jzk!~2I1f-<}DT$#ZrAvYL;`4sixA+GH*ZN(1pXYIG@a5=BuihbSj));dFT~0v zNBiM^X#sHRMkV8<<OY+(wAJYwDM!`@xeeN}+*AYhA{BBb&>i>TOadTmP47rAo9%z$ zaar;%(FK+MA#w+vmKXb9=^@9TU8eX*)3+MqbHPhiWr-CPhB~MICNa6$4_=@PbfBK} zE1`_g)VS!$JT{zfV^5f|l;ODLkze{#3WuUy(S!dAFujx<uppz6$AN{1L?6B7MhS{M znpwL@{gT)?BUFD^(GtJ<Ox82hvI)EtIzF<}@=>^4O<z#vQgj@{lv!dMPujPqRfdwQ z$eC*rhM6aW;R7}aQLMjNllfhCn=vj+n^q)ffDneNvY=ff0*Y#zJVEjKSwRvfU_*k< zps%zV<iYf4Xxg|s-2<>YJf%|B3q%h>1ZBYhd&xbF;$Qg6co#L0w+3i2U(tt2{lDk1 zRb()hWSm*P3Rx+uIp=f#2Lr9i0>S1FH3hJRX-!+8fqsAF@|Rqs^`WQ!)4yk;Xpw1h zkAx$1y;Hv$D}FB=G0p7<am<e&W(V}JAk&4=G=M+oRC}!&6GUyl%OH%?{-E4I6HM&b zjr^X{tihT~4ZR18$SC+W5E*{Q5T4+6qKt<fsH05j*l_t3!5<&G`1A~pViz}>4~2bp zNF;u(kDM*|YqW=usOH)Qh~xVcpGiMuk9U{!9*=R~Zvr|Gl)ulzbI5SCcGr$NoSrz5 zmib91^LR99yvZ`ND`Pi{d;4mU$yerZZNu{+_0(?!1AQTn73VU_CJr`o`oqW36ze9t z;5dC;PhO(tP%_O13&<I+e9$9`M-nmxCd=d4;q@Kl!fGM?{l9@h6a!Mj0~fmM?Cep; ztgfpUh4e1!O{6^WoQ%&sp~A2RUk(J#V;8UUwG>42n_x}qA$IO7#oSo31gF<qw-Bmm zvef@IYYNi|Zd&eNt+_2UGxdos$j~MR)42JFhshVsPES1R!N6!Cn_a7z0YzU(jmM{u zWTgTe&jJU=mM<;pz77*RJsnrOz2606F-%d}0i?7FKvTJBPR#R!a@EB#3nd4V%rg6< z&n?W@&syAZpDj)ua;?D~&+UO8XWPCklwi|8U~<0${=xj&EH^eV-2DE7evNxs3+35O zN+ML8^ooaLP+r>?el%Ou#?3=_|Bq}4&h*X^4=vMRbS6NlYm*sMQ)S!@dKryBS77G= zAZez$rPf|2skF{o^#rtiRE_3^<+=qX{->=F*}(A7xX$(f-j~|C>ABtZ$nn`s&Z_jI z7Ek_C6_r!Fx_|BF(S~o-P1bW^93V=C0^xit<|o<ep|aTWRNxQ<bi9Wotp2cN4#S=% z{j|tZNhq4L%<{^|y&3UVp>)L@98B6WRxUUYD5|pkeyF_%|H^25G6`8{Lq$eaX{9Zq zh7d=om|8rf>+z%0wL2^Fa*yA^Mr4n0b721=L2u*u$bW;+>VR9IPn)+ZdSk5Hig^}R zItmJ5#NAzhx0e!@PI^HmGxz$kBIBz*hjxmvpUR~j;@f88)H93?|Hg8E1Y<)FSv@Ho z?>DWJD0MZ>(fy#;p^I@JCRHq(WAK!f;YEc8%8^K;Kr0u2hUa;|mjm4oh#i~^mQPtc zyzDP-67fX>CF2}ddfb$OQO+I%b0fb;3@=VK=~;0H6=zAm$F>9Jxa)|#XQdNKL+!tm zSsP(IDcRYVvNXT>^^eW@$6c<0r6co#Rt0Ktz!g~6MYpC>{CT*Kz2VxGT+zPFYr+Pe zHYUg^?6(wXc08KvbtUyM%!5%1$uzyBv09E)c|zC{CvX8<9F`Y-b+~qQdkIB5N8#z` zz<7U8Eof6%DitiAYSN$oJ%G(^zkD}ESSqpWYpl#kfxakx^>-Z+rlrlwWMeledvqd- zICzfFHd;;_3eqN?Jei<i@<ci5U3)jFb;n~*XR&Et1&znHZGS0M_?J6@r4VgGlFp!~ z?~NE~`xZD<8Vg0kVj%Qc4`KDQWemgiKK}JY-)(Tz`1QXceK2so<3tN%pXd@#w5<tQ zIVSfZ;CKothQg60oYdo5e0RoRvaFZ>jh?&iUYkHsH`(EzaZq&lcI&eCO6A>8vCLj< zlk)Rc0A_XX@X;TzoK%04KnF}r@TX+MJk!8j*;mUzCU^QJPJp@n7KuDc5*pAuNDG&l zyWPEBX2hCOB182dnvt9*F=!gb)}Y&fZJc)nt4#(IeO>{NCHi~tSPFG$eE1Gg2+FL+ zdLj^GlL^@$%JLIR3Aavi?O0&CcP}#39s}fz76se$o3XYc>+BPotIrww<96)Mlk^eI z?xKLgg<+0Th6tEVz=2>I3I39RMz_(&HgZkePCiO-k@K8S>QJK&`$UtdfHLbgUd1ce zj$k<0zG2bC^HLtq8%8R>Z%P#BeVvg1Q8%@OEspz52?908ug-IW_Rz2Pq0GT^BCOmn z9up4VXL8#pYX7~&n8r_!TB=`Z!x!f0`sLgA0A%ItFn|(S3BUSRJ@`wsKIg(S_<JPg zW9#E_2yufsNP|z@T8Cfqbe=jOD{Jet?Zru3Q;+af1gImlD-<~J)TZd};?U}n4s=>m z(V(M;MY&FaSqfXSl?tO+(S4wJjIXGF0F2?Gsq)$R6;L$HAjtwG2SagTcV^{%0rnIT zE3cH;L6s3xhf1dsDPbI)dP7%@8eZSqBOH#o&6kB1_5|}myH*+IBt@Ei$`M}7RZ4=q z$@b(zs@*`TGrAF7&wU<YvLJw-L|$=X?6{R5Q31J>lmTZjR45q*)$hTUH*S(=BuX$z zifn5RxNX-B!WHyv^(VZ45A!oHFXUT%V>%y09m$kA=&K@H33ECzGAsS5ENCn*0F_r@ z8Bi9wy~pxAO4Bl|zEyo_7cf_H*W>eKTlpm!3Cbl#Y--^f$8VU-T&Q*2D%>TLdTaB1 z)Zh7@qX}YH$&VaGpFB-HN8ifl0_j~kPI20Ru9#7HqnoAAf@Jf@J*nc%U!^4wLtHeF z|CBqP?ZAGJnxto12iPeXe!tog2j4v`G4Vhxjv{Y4MUW`<aN}u42aq=?qe|QlXuU`O zqU)>e)7uAsl=TzZyj{pS#N-~ui~b`t*asx)E@Tqgbu(Jy-~_swIbDQ>)tXS1Y3)<Z z^D51{mzE>yZ+4ABK-$vH3NsVP^3->(9nw~t0AS<{Ty4uUVS`4c;SDcQ+|lJKn{q@- z<UWU^%*x*CJY<(buO=c?fJ3&DI13<|=&;e3yOEF78Nzum_jZDQk99^An-uZlO^<e{ zh}qc{i|u(BB<z7|0zm9ii=`F7;^AXywiYtY`Y9fM+NRtM^+gjnZZ2XUK;Aj~gB*0- zz1m5)zHSWVThA!KNsl06mdGEcoZ*{I>ipqurBV5J+8pD7g-mA&HPmB7mlWfVbz>hG zkmIVJy*j&3H07~OJ4XM7gJS<G${!(T7&(A)MF>eMS6AA}qg-Fq#^>gM3xfV<4O$dN z_&XcYGp(iN(K6B!plh^Cx{^wqF~i%AvrqFP@|%2F{>_I>WvB4VY71kg1<_hsu*t|L z(?*i6rj|U!`RAPbpHT=Lx8W;WX$2^qewzB+sZ4=4g$-w<S7Wy=M?TtaV=E~p76SAl zL*eW1UjxE=(ZLLN_M#I}N^sLfY=*mN5J`ZNP*6WSlr&S0e7+NiW6+mjDv1drKb7Au z#{_&7WnG`*y1A`>v^9lF6IC>FIK(BmxF)lZ=KECU?!oD#w}MExN7_91o2<~l<0o}i zy+w788N=0B;VqWaH|}b#-4*C%q;+YByS+H&zfD5Sw7q8(K!od{|L*$;FpHzV+<biK z<kr{q>3p#qUd;!`k)E?4{NBK$<5l3JR4=LIssrQ))b1z2Qor%cWk^=u_gBZ<a2j^p zgT6KIf}4L-4+SZJ|6BM2_lHpv`xe7gOP!u3PM*icDI}`Rou$|0{-DKja;g+ge_db% zOY;#(9ml@sgBZh(BA!J3=6~;zFqYT46>f}MNGLt%q&J*aVcFWV?8GDVsCakA?nBhH zyP+V>5Crq2fRN+oU_KEq-t;Q!igBW90?6iva(J){0m`3NnPm!U8cu&m74wu8S|QL8 z*4!K@sox<)QrcyHxN>#%N4*6$5L9=T(|2j139W?<w(<%m!qOSlXb_%XGZFI>@7V@_ zsFEJ!yYc=l?Di~IaOTo|^1b!I;|~?8v*CrZPOP>xDv#}-{0V?&nZ=~b?dilr;;5KQ zWG3qBI==>%ujPwIeN9jl2roa3ngskbLUe&gC0luob}XmBfJeO#i*O~J$A9JDB#>Vd zaQrn8<N;5GD4d-+l_(OEc)8vPXE|dHOjz-kENN8I^nw6)Y|E8>hZj|z`drxVw$<(I zW=o>{tg)}@G2L*Hh<iVf5raqMK{8`h`EaUGf6o*n3_`-74%{s&)hFL{D^%^6AE~5k z_j4*Nd`&_r^Kp*-0yGsw`%rd8sg`|C$&S5bvkQd!j~EY4Nd`l*V7-72F&GiPaA4F_ za@Y~cec)C#<!VO_OPvrR$Y7)8+i|JaawN^fpYIjI0IL3x2J?<>DY-jP=gxRM&e!mh z3_H8nJ%+}9?FCBHC-c<W`=l~yBtPJ*FEu6EoL1|q>CvL&$V<5#CkS7nI|YI9^f|QW z=%<~7ZIr4N!RY>%4KuCv#~fb6GSaUNz(@5gpYaPGS`uSTuDemIm(%PTU3pT9G>7+t z+eID7`54O6EQSN2HDm(?<6i<w>&q_6d-^haxzzDIM)tBiI=i9*EsEOhj~%nECJ?0g zHNp^J{SwdjA?W{3_?q1dqlSOc;HHb2^v|Ca8Ta@oGx1^YkLE|Z+S0aE#y5Ix&~FqZ zSUru`cNoKt7FzaFhk3#t^G`<yZ?8S}#%Mb~FrwD-+39kt-5qN2H)WEV`1PuV%<BBp z)}nV+HBeT&9`9TDOhiPpq&GKX3(RbjMSTv5@s}rBxpW(U!bfZ9+;MU_$b*arw1sSq z&YCA^UTZ21l*Y1qec9i6+{8)T|CAA}b|%9qX=L&ucHN3-@6{Zs<%M>?1I^K1Z-#Cc zYocMERZ6$gv<NtLp<gsMV<`eUJFxQ-796G4$yfl+wwIH)EVC4H5cFl0Bb1O20d0Xr z-z<6`j(Y#bYCFf36?1I5T12PV<iWmMFKxA^I4DN(+N`-EAazD7R|g?j@U7d)|J{u_ zlL<i<_aC$S`%HcrRAA|@+Bf+M%I=v2QXk##RJDt1mqrm7ODM&*iA+A4;vx+_pZL2A zs9@X9mR8SVVKqhQcn8yb8o4#Iyp_B|TS5;g+uw@^6$-~EaSl&RI<x^C1+3%@Qs?Xy z1r&+*J3has1k5|;HRb8z{L902*8JF*lIBo+k(()8?w>*osvTu(KVU{QM648l>z&3? zcYfU}tq*m2)9%{KbCE@w*Bg`aA*jk;eGt-6QqWBVw5E!OLE{w?I1qPJ;$Y8r+FIIa zC7pqZ#zG+(!+n}13=q3n3i8_Fw1=sf8ZBR(Y*6A~xuUK!C&st(4~UmN5W`@%GCMw) z%UM`4#;<hRZKeS0Ot=YChv*gJmOjJeSoqHr;Gm&yhslK|4Mb$9Dl&dhB?s#DuTKrb zKTT6mFwgfo&$TL#YBA1jd;dN+NG<`b*-Se9Q{y?uFFS}As}GcdaO&kx<9Eu)9OLfu zU;nHGIlyEhqeYTB0&=$AP2ITj_pEcO+?s2EXR~BsVR<Y}Hyf8Gn7SpOIZ^3;S8gN$ z5{F&aoJY}F+<7VLEus<5`zko)qV&WtirHClDYr(lHisOna~40Odeq@ToD3AOnbW7& zuP?ZE)7C<4gw+`V+I@FiV`81F;`~yQ?&4wsmBv&E<AlwqB!x+<>ouZtuY|1>V)*3l zd`~xEN@uV+)W&r8w?jeei5C(q)SdZEG(oSJe#qb_dh)L}8zhtu3;SgVN%XJ;3a5G| zMW%7!fqcvXX9`4R`SQt%sH-B=bsM0Kg-B94GsWwQUG8fe&*xmV7tkn>+kjQc$c}#w zv#N?}biS`i8p_9<B&|Sz!l;`!oYzNY(>zj)&7Iu!2VnIo$@D+3KyJ(+-)rpUE?w6F z6m!%z(*D}y(!O3!&k!1~rd-;KR~WWuH?GU<al5>Qyq1sj6MyP}$!?6g7Mw7sIcx@^ zlvwCCM&dGo(wnlon?8iX7@x#h)X*fv>oNr`6Z0Vvf|Py>$!S|Ab=N-=Tfki(A2Q1m z&bJ3e=PyDLqBhbtL*Vy(*Eo@*()W@xi9{iitqY^5ip2I|ZJ>ad>TODAB~5KgX>8P6 zvN&cn)|6ZOOy<Ijne=+DXO$w9JTyPtxy-Jgu_<-FSojz@Ej72$6VGntrBMHiBW*BO zz7-dC(Q^&V6%Jb^!`gR(;+o}$C}&9hVGjtXcxk{nCM>Q#B?W@xau)kKD^X>*QU+9l zxOnjHxKHgnC+M-fr^^Z5btb3h6%9Lbf*P|yi+W8rkpOj$S()Wm*9h#9QoMlRPmPmt z>Dv8p?LwPXISZv#>2uxh7Y;o;p$4;}hs1{YPTf!0w}fc!t|@G0%q2wlMW86|20)L; zEb%GzB5Fae3KR|5xdoP4aJnxf<Kj#d*(X8eYev_iVTYb&39if4ky#|T>T|t?^!EVf zfpgr@EWm&#k2Z@hO*tsve@ln1On_>PDk5S?gPbxve(e3&r?GyI+pX~={LlT0AO-0V zPw8EA@7Nkgc!g0Cy*y9)NQya3(Ky!-;Wt2(W5X-~L)Dko6Z9p#$U{eCs^BR+X3Y>z znTM8LV%GAfGn#b8&Qzfv*%2nomV=q{|NqF-=kQri-iN#5U(rg5xI#k7xVKzqjxHn` zqh^M_jz!r+iDEEY+gX5lduVu4QXs4IJn~ZXT2qOhdRb-SaqoLgisck@je%6-Z##xH zeq}K|xc)vhPo7B_;$x^vH?AG%yzUl({3V!(*SC)+deRPVGNUNTtIJi&ybSn1Ze)`d literal 0 HcmV?d00001 diff --git a/docs/images/position_90degres.png b/docs/images/position_90degres.png new file mode 100644 index 0000000000000000000000000000000000000000..3c10d7dcfa51a628ee20599e2612cd5dc75ca4a1 GIT binary patch literal 25582 zcmYJa1z40{&^}D3fFRw72ntI`w}60>(y?^MQqnCAQYs;hfOOZA(y%llwRDFp-7NJz z{NDHdf7eB`@XVPrXU=`k+!OUtMV<hU8V>~ph2X>ccj_o8XpO+vn>bj&$41pqF5nZY ztGc{2O2sJcKj0e-Ybj+Z6qM?C{998@;Co!>_j;}<D1_aQ@2D`RA`280^N<hkq%^&Z z_A{})Naar&u(Q{Nvs@)^Aj`9Dv=YmA{@bUR*fITBF+5b}89XYK^Y7A4K547GM|(G_ z7y05T&QlU$oFFu5;!TdJ87&R=E?nlE%*E7MA8(|d!+y=g)FSUGBJ03T*+%T%XwJ3G zD6K(N(V@X1;YadMBchVTo&9_VoyzfD_mCG81<FgHdP*&)7EQx)wMs?JFNqc<bq4wF zZJ_$FUH-RI6Bg$pYTu=blLTavTz(>bp$d7{(8)ISL&-+A`af7DGsL^M*DC%?%D<s0 z|MGt`4m5qJzn;;Yg`PT;yPtV0BXW21B3@rMOd))C&kb+qTf#2deC{S2k}mR_+uJrK zw0(n}nt~ZA!$gj;ik?-z&HTmq;rolnw@=FImrDvsHHnl<rAy}9PenP6**X`bqBh%= z>`NDW8|<W>Qh&+*0ezeKv7RCel7cqBjN!U;kI8X&!cgV5f}gB%DtSc^>ehDp{DJ$r zp@|U9_~F&C|Mrg!cBJ1wPwAEgf>X&`I*$82r|$-d<N+tvIEU9bR}H`K19#CKg6JH> zy$>Jsr~ZxIZ=a$-8V<#@oJ7BFwDMgp8cThIf$s}%>CSnLr--I=j1k!ex0%`_iFc;D zx7W+NcZMHyvdJ$Vo(=DMNM6-9Z{@y$iFBMkZ-vP`y*`+Dy6_JgEde9F?W5yXHDpEH z7=DOVjh66_n-g9#=j5<%pPqU9wuOdiV?=by|6jvX<dz|Y|9#$o;*gGQ1ae*{YME&A z_YLN9+}yq&I|W9k)LZ-V29Xb(Bv5;~x?q`7|DQsln0s%xzUemq6us@nSBWtW6ryV& zDH&9}0#k&vnNykQ8R!b67hVMYb+x_*2dnj91$wJBRZ=6V_l!lTPE;6HoD7t-ykGq~ zFqA(R(ZL179%NAc_+E#$vj|0-(^yOGfG;PLPJ`nEh+I}>7}q<<@B1FUr)S_CpUO|f zE+0Rj%`F$*FPq$l{~`TSt6{p?z%`Qu@|Y7;*}-BJ7z?Vo<+z{j)l4Sui~_luuJ<@n zM3rfE8)?jp(A|P^s)1ifpZ%hD-;A<dESmY3rS5g{A`oF#!al^v;z$NLy+^US^e#Ji z7}@n<;Lw()8mnGWX)r!Zr+DekpsN0Aa$XUESeEt;cRCJUNi9lX(#xcDU-Ll3T>j){ z{*Y-`kEF78v9m8Rz06o$nc31m;cA>Hf65?CQj$bz*BD=~`BGOP?vr$opWXJGdjsc} z+v<efxA6fwI@8gTzJ#At_Ozz{93i_7>7((&t{Lu=0}H7jsmG4Y0WyuWWGrD-j%NtX z0$nKaZ-%h-^yescc9Vq!9L8Ei)<ljW^~(*b$np1QTUjOTr_T*i6L_K-uLulpSKjX@ z+aA81ZBjb_&^?yE`{fN>)H)PNM?dQ@_2hypy(=4^fCZsT`_6#z<4lYVF6KYj6l-it zIGz3`fh$r%?NYQ_%J`2pT<?P_{5{?Mh=xyhE^1)VXAcVT&5}*2Qa)oYhYDl%a#dZ? zebl=OE*$#LBB&*_tUbFqpcR8%)4QG;TrEqMD#)MqT@_>zgUBi7gI#g{o35I_fwfe7 zcsJpa&oVj(_VND}eA%S=drfF4#4npz^5E;-d)6#a_49$jme06R<YY=2*+t`N0ADGX ziWe#Tdnw!5>Y1Ih+-*w`F@t$zEiDsue50F`9k9fK+!*`nY1dw3<o{bUd1Hbt*Jx~n z(aw*esDfi#HH=|>#V)(qUe{|Zf)Nz(yGCH2nq1O}bSA9ez?Q4z=8xL_Q?>Tk?Vk$5 ztQQ@qQ%tkm1<yh~1FH@miZr8xXJCr+yZiYBcxQhDDoatMs+dZuXN0I9vSz!_6MEz{ zNw>SDr%GiXq(vT{sO;<JmW`fNCl3y*1@OIL<4gVJaN1d!B%$g$^>s^mFUCOWqFP9o zZ{=a!X`M|6d9QpM_2=V>I?;HZI!AZEX8^A7hvUKB3|GADB1qa~!dS7@*G7xyfzNL# z>lG&7Deow3ZY^Jkz(p@bee5=Ak6!h2;Ou(w-boOWYbKHcF7bcCnW?l-F=T%_*^pCG z7b$5g0w<2yyHrFvWVC%v$mq|WjNtSd%csp%Gs&>pp4p{_CCurQv`~r{C0*#fwcnQ_ z!3;LRrd=avZOUG1%236*`KX<!c*;2ri_D6DtG4y(zNg7#)|6_^C71QmtkjvGR*wOr zt(EbmBYE5xnm?=R6t}VK&3|~Dm#pn>Meg4=k~9^PFr`qOlwTnwe`Gc+@!2t%j(dq< zeF?q7G>3Ce$}79`m)*62l5|XfG-du^1w3G*kglA@)cB<L^rQaQk!&1_;M4vO3(&tS z{rY}*tGD*LT6#R?vK`Ghh<ip0y7+a~icpEW7s6IdkgUJh6iPaXZK~)+?K!hUZGBcl zCY)edHG;GrkR0y&dHZ%6KP^it@o+hY?F)Yrg-?I4o|$*NaeHR~7pfKohxL7SO{L4D zkBWBL7)5ab%Yz{5nZ#n`5^{;(7T7gXQkB?$R}VW|{4S^omgEUXA1eHJo;TOi7A9Gx z)ktbU8oo)oaID=g)|y$~_c76%nmphPTZCRtpt$1eKRk-u_yxO_!irZPz|UvxNbB9{ z(!X+gN*!2|FB;MNyIpQTF{=V55tQGgR26o7d~G9=;CD7g^82hDR2ZGqMOpeRS)@{x z%TKJI?C!Uu^S9ctlp*{-e)kP8@B1Vd^@2k~?BHOw8~&OP!*7oceqX5RAu7{mRysb} zHBEK+m#5oT98Gq%7(&6BU(=e>_1RPpbiL>FQNyyV(cRfAmVxe>tfTrc8WfL^Hh8do zq~7`B;}dXfKHnin`37vgf??uYxwMa&+u~#iGXibaj<3GTbeP6X=?SimR#0?7Ww`zq zoVvh)7k9<1_=fpppERj?<fP+qwL4&nLwyOT69Xw>3yu4|OWw=_l70q1d_OUO4bhW} z^ZepvBdWEocm|`#q~2A^7Y}O_ovP318-yLcwlf`Z<`NMY1(ELNkeh7&+0vA&^}VAV z#CN?$pQ*BrlNh60hgz}jTb4TK{1l<58`Ylqn(gt6Gf}r}NaWWRX11fybDf^6fMM;K z&#vVZfk+*Zi{^1U_#B3vz3rLzwa&vQ9782<A=Mw2p^Pa++2nKTj%82VQ5deNu5sYv z77X#|#u-HO3LzSzKWe6uCc7lGpqiuQX#)gJs6UH(Ptq<sopSzu70#4YNhN`t3JJX7 z#3AOidieXQ1d=w+eB`PCZ=}uO6|WYZB69o_j9(&_d6FxJv!9DUypNjwIvO#w;kJNh zh*FH84PQIetP<zE)y*bsSWEwr(b!nInxQDFK=X9fyE%HAlP^jCgdN0$r%hllb-uTr zZ+eEA(flWgC5$lz+a2xi?f__FIVU}Qv8cGB41X_v_0xjOIIHHY8I`$2a^Rhl0N%Na zm`E_^AY~-Iywrm1R<)s~u~)6ioJf4RwA!>Sj+bFJSS4p}Axxw&+3#L#)4XMw6>?^f z+t>ENvij#kw$MS9Xi+}AF@-22-SGQ%TCs^0bHI|#Yjo0-&E9K>yLhACx4iD4iOmd5 zyu}T=Xq(Y`lE%g;47^3mHoAIwJ$;;DUp0c7C#up50ouz89RYh!=-*SM&AvP$j*qvD zy`B{`)()DHx0TXfH2;mxUQj#b|AHgyt#{PU@l)mWrzpw(#fN<1t6>Y%rWT|0QROW` zg?mN=+GEV_W7Jx#BaA;63BG0r#FRTqM=`*pSxFbOupDpKD|b=vRA+yGDL=?1H<LLt zWS}sG!HQQR9SM3bdO;a3d^(xYVG4U~BP23U7eeeJhpNWcN0_`}W{y=C&jp2pJob+@ zDDKP5Tj0A!Rb_O77EfA11~KM#T{V^W9|RQ|@=mHg^_M0VDr@-Ej=KssetMZC`~F9Z zEp-G{$081os!;x~f`TvQSu(P=OrVV3H}4HZqRJ2Qk05WjDjcxnXRvFh?pOK?%n#V* zETo8cJT$Y&kKCdRb3))d?<Nl^wtsaZ8ASd~kRKIS{U8@`EAk*1B9L+hl~hkmhL-a# zcaxV0YNoI1PSMcBfGN|$^k2IU&+M*(W?wQE`%eEQATE4Ky8Wwm>TV-bA~NVtvBvji zPXe$w(UT2^g=<2)mIH>=W)$}j!;{|SSH^X|X%RsaynilxvmZucHJ;s5%+)Jy;+xlK zx3G1Ex8$TO4sPo$9(eA`5h}BYyO=L_;1S+ZqJHsRu;ngV2Q~LQ<TzXg%KCn1iC}ER znz~Y1{XqHm+WMpI#G>`tRq?L$#3ucOa(l-cSdBbS;bHDeMtlh*-PCNG>^j_x{$iL) z${Q?jgbDSc7ea<uR@uSrcQczrdMU*_T+q3O-&mcJ^9D0p-|trx7HT3rc3(>4W^Ecj zM9d8zMCL&1xcH~ENcErIDbHE83E#v8kv(CuqAVG8P5hkoFn(z3SRum7d)Hd0qvwMY zd~CuDvyfw2<)CF>Au2yNk8bLyf!%_rk0_vC0t53D8r~~5@#E>324wa8yIc7YAW`V} zsr2upE$hEsZw%izG1*C@N3Lb=K$UzWKo{7|em}>oG9^OT531LLG<x^wHIN-O#hMiO z689lK)@_BkEKUEO{<-i;f?0hfZ_g_4`^-}_6K8jrQuA?h!r+E$h)9Z?aBAh`_(jJ2 zq0Z!d4KpirI3Ir`!!zrXqE|9j&LBMk<<#4&o{L8OnP1)J&R5!4Jk!!^p`LgH=4Gwz zxCr9)Q{rpKExPLyb;7CGH7mOL0qq<0#8jm&Vv1zbw*j>^rVwj8(Z--JhMoJxF5BE^ zyz494&@`e22+nDv-=Am*4`FMCQ`WQ&MU#<!l*oakZa7XbkI8zU+hiXP9>o##o7Hk1 z8ej!gaZe^|UL^`FrJ-HGvruu9pnJ{4h$#JR;4`si;s(OBb27F>2)2;t9Cuwr18eUk zzghFzprsM}3fg*cd3N6%hb>20#T+-v)fb^ffwyQQZD&`))XJ)oXM<JfS#DD5Vv-nU zvmii?SXLY&fK-SNslR)g5v{5S3JLAG8A}7d=L@QhXqXtFSz0&M05uj-&^Bqh2f2ST zJEaxyp^xjwjhId`=A&Qy>8ZdS*;4qm@f}f8IJ1jYA@`|fX3C(d=%DsZ(6?u3q6<nI zatbGJ;C4m=Dt`nwBMFchpo=bIdvW(eeQ3&$t7~(%%F+)pG(=w(2qbsF*rl$nyhFrN z&YY7Snj%#TcgM1^X6ua&{V;$0zM9?z6GM{#ara}AIGi<3*G6V-cUda1a?EbxaKH_& zmh}jP#^_MpncWDIXBBYf!!(}YqZZI`Gw*pC0pz-G@d&wk>*%Hdv6>JOdP*kD-lj~U z+Cbi^-n|BfhMo>$_c%>)6ISliNc)1571Fq-!@r5G`q{~IM9t5MF<5h`wa~IcbDS3K z=f~&2<cb|R`O+!>^4vb)iItwhoW@nYU2X`9%|Z`%X67-=$t)rvk1Z6dyuBcU!ha+# zmJaCnQ^)dG&`_RI_a?SC6Rz-g#tF$iaUuS}UlgV#W1J^;2#y4I%|{TJi+nSVQXD1@ zX=K{Nxk@~t6)(mH$FPc<nlDyZ-&fjl)$$RC7KFr7O&mDigxk-GI=#rQ6Q4CBs8Zox zzM_OBbih-XTJ2NkJ&o-!w8$(0>MCF~ObXNXt+Db_EXkHh*2mGqFO}c9R?)R-f6w#p zCbwU(G=@^dIn*)Z^x_$$TEg-=weAmB)t&N3(<CV}S*gCL=3+5Q!%qImE_$Plg3tr~ z<d?yJ`25oC>8jOCL!kCW$@=G9W%GA#Cl;CT5pDa=?rV+kL<%b)@zO3nRXVT#6nQQu z-Eh6DhUxsGr@|ygD?@_BBIzG9h4ZHy>5}X)mF29-yE2;DEI-jIKWZ>XFv<GW3zXA1 ze8v6G%&$AQiv4HJ=$w7<x5QnJF`$%0goMs@QTo~BX%vd2QjI>EPQ_1YYBD`X6_%<) zRi<ULC9I3p2(WbpQvx%<+pmTnRs=Uri**qW9xfL+oK};Xg}bOwIFUhSyhI-WT*&cr zDo`8K6D7u+v1!VQJVe;|bZ^ps)(ne@TJn=dFuHB#x#V?3VtC!Jue>`bzJt^gewg3V zFyuh?)K|mTx8n=e0U$}En~T#m6%va(ajab16g3-9w%qnkVy);WnJ_(_)V1-+^(mxU zkg`xS-sAY|b)Mm51j$EyB;uxp^-#A*?&hZ|!+67H{ok{1__GI+pHCRpt)+qjsMfl$ z6I8(km*&y+9ng2DdGiMNTI8fV6l+f-k^J*MA+IS5J+x<T&Wg3=4JibvDVj`aI+_|w zZV#+dpX0>BV2VKOn0_prFP57B))kZB_I*v_dP*w^Qctcc*vZD0$N*3wNIjQOaLE2A zr;Ybe-FSce07i!C_<#N6H!G3jtpHA%6ty=Jw5d)#L2W=l(S^(?=QbTlu&-^W_uNdt zT>@d}X6L$php>LX51@@Fw2nUSDCFJg_IS95xDb?v3ly#+y=@ouN^qpt)qej{fV>A= zx5AW%0)*&&d$IgG$?b#PLj!(FdSI<T$AY$h%QZ|S)AbzX2@}d|nwWX3C5sE*?<`@e zR0k_9Ij)Y|PT3j=y<JXWw!C~Tpicn{XB)!0PXJAC^f$jfF+X>n=`rOG{^Y*c)rk}H z*?dZh?8T`K$CNC9d1u$CFSuqJ__dKQzUO~o<fDhYOHn!09|cTVVSawbBWlY9E*p5I zCBFk(LmjK`&C2)?^HNfWz&92&ZTYW*qW?$2JVjM6a^)-(WeT-ZH?@9B3sV0QsHPMJ zK)nO|$q{Qf`)<ygN>JT|zqcF*lmfLIVrCmV;ZIAVK@*jZH>(68DB;GX71v<+&$r-} zQxukk?RX+A%8O^8b4E1(qL90x7P)yy>bs-yP-7#%d%sAI?MrYm!Ka(3%qQ<wmwiet zZ^G_CDe(M>X)wWT96&{P*nf*I7A)y4$ZN^Rp)AN+C(PPNdW8GQQZ)3iJexH$T-*MK z|58A8e}o*70QIE14$Xm<#hHiNsbs@|-){YWus>mW7<Pf`Qoz>l01^#113iM#YnTn4 zPB${B*~Sn~@U!Hsb>yLP8}k5JiL&L{H*WTsdTOk!e0qP>YJQlg|HmS+4BSi%(^};Z zkCw>5C&12#T^5bAQ1?6$=h_+uR`WCGw;oYUEsm3jjj_%oUbvYgx7#yhitp=hplKFX z;UGU;ga-q-Ock=Sy`i!8cK}k&T{1yAexr5*8{~;r<hB40Sv{RzmxAijz;4f#6UxbI z7o^@>`=eTE{hNw?D~iDxH`*7G(I5<bG0EwLZxTY%B<Jcgqj1ujG)`K=uCS9LVWf{a zL?&fJ3;)c$n!(yqV~G^qSYNG2g;Wc;pH9emRreYRZB>N1HO<qjk|h$gVzOA!wyt>R zg{3}pIt^sECWZj71Y4gm2Ld2!lpNt=0Tc$Sym#k;A2$_VCP>ygTPsI@^Y;_n%#>C) zVqvpl6~|k-vHtvd8&$!Ti@cFVc<^4(5Q9kLxz`|<rZtl7!J0J$KLcHKL3+m0plbhh z)f1lYX#ZzpQkLkD@?gNqhL`AdByc(!afae(mw!dbL{ndqgUg5<d1EB>^xg`yarLhf z_8VU8d}dSW-4(T2HFqg}#33iEJzGtXY9R`@C*=Y)^pb(3o4z_bGZ0%bLY{OXd5Y>A z>9cYDhz{i?4DNTc3DfJ2wn$CPwCvK*N@AfbT6#T(9`g0h^{5WA3cO|QIV;H9Q;91A zLDrjZ*&c~1Bnv+lRZKE-jID`!t9m8gsqU(@tv)Ac`AS;**-!s^e+W{|8Fyqt!|G-p zeg29|L_Rw0R^J$%e`?y`m>z(unp~T*-oQnZUU0#bP4Yv@ESleWm_bD~(n@jN1!rN6 z<8ysBs#1W#?}vHsplJUg>M2b+|6y@dl!O4nukP;y4<RH!RGw!GC?E9xKP#u42dhyX zQeE6j#mZ3*kYN&YAPnkhDrDH{<Q^6#xlY^czhY_JxMp_Luy5F9Dw9{7nv$?wtLk2Q zp)LRH4+}lyh_CKqaVK#!(QsT?9X_pi9p2O?%VV_>$Hpx58-5|P1wBg2Rip%2r)f*# z6{Ej`OtMsMIIRQZK(yT=`grB|-3p!#rU1PXjDt25sZd6h<K*P~cd%Lnv8wAvd0lVy zjvWdQSx7(zm-Sy}nMV7kTn4pu-R+s$$2U*B&mlp0q)(Hs-w;oYEj2CI_KNJq-e#T9 z)10w@_oVJq%{OMsDyCB-eC>WnELs9}E=ZFICut+)Ew;RiOG$8dxCSZrJNQ3`Mn*;V zKg}ifO01s;&F&sVGxe8jiY$5AMior+s!fEyJnkq&ECr8upUQEtS`P)O>z%}|H-h)* zDt7n%cU`&18#4mg@o+N+XN2b2$Y9>V><8a|Y*K{BdQbBElk(!O9y*Sj-R#86$=?XL z8HF8U`s2pSL+kXWPJ4<iib_jm(?tq}mAlPb8;9y$)wN*W2!g_wWp|0pprVb!Jz1<v zVI3lSskTh#@#K3i4&p}XJhfOW0f8)G|Ll(=k*vq?7~Y%n5j66^g639eUh*#C-H@pJ zXNPI)-UcLjX5$XbQAloaCKduC2OKLF61}x2=i(@GO@7<A52?n|ij!Y+sEjE2@&-B= zQRIS5OkpOE3JyVtbGK8{SG_V(0>?P`GF{zE(*$4_#+Wyswa9(+yuWF-nl}<l#xckl zFA7hHinZP^x>!iui(rmh6JS6be$-^p_1s~QqpQM?Bfk9ZN(HGVYAQUdk_QU81LTP6 ziyJ7^-gUb;?1-KyArRC0JKQQ@bZ=S7+la5jokzhiYF&hW{e}lTtZ3=YBTLyiDz~`H zMH4iyXKu*BaOMQ1#HUxpsQ6>!*IH)>5o@s~+AOe;6gb5*SeTfL+shJ<xt*s1(EW5c zx!J40V59a_kbunM5!&41TfvT#?|uUM_%Ic{#+9D9mFYh_#wQoO5FSbSX{1J$%W*c{ zhuPY+Tk!o<JKW5uChj1&b&mgynoHb$BJ<gZ=&TvX|Lj3$c*sAy2I4xjp|-y=^}qHE zyUBfn+#~MG>5<gnvXR-4`Tp#%?Auh(1-ks~A6N`Jc-9Pbq$af0J{KO}^$q?tXk$5R zb~;KYhR$G^*TZZ7y~_dB2@!>0TITw=&yz!UsQ(*%{MzOvRS9y-EVFc%6&K*V#A4A9 z7NF7W=>-UPHA}vgAkV7belAibdd3BGUVzjJu=fN>n!euy<Tur}3Qi}-D|iTpT7yLQ zFDDYE^LLPHhB#%pGSXzb#rIhyb+i2Vfd=s;T8m{apk=yF)hTJis=$hLU7jn;lW{V{ zizA`u&S7#n)Jj|sAtt8<(;;u^_wHI@BEnvriOLk?ri-R@x!E2mwO?B9O<L+s>r#92 z69(jCicI+bUO4=0<)XVn1MfwcXPqsyP0v#HRXco|j#>n4U`M>0QirA_#I7&p`Za%Q z;L@pOKH>!)xq9|Lk6c~PcjyhDNc686Q5hZZcl$K#`=AGfKP!_tJKf810MaEw-t&d= zUeo6ftN=ASap|3@(EGKjL|A@O(7Jx0?vW2I2>0vp{>#rl1>qNL^v2nmt(cH|Dj&1f z)2odC+mbK(+9$&_1aZ76H0;_YsJz=rzTUAO*+E7fX2+)ocb<MY!V+Y@arrdwCn7u@ z2N@#w4R((VSX<yKtzF5J{L1BF*b%x>hycrv{X3-umvzT|R(*ANLq6wp*@_>vbLV<e zyE2RmP`0%_%|UjFt_I#H#h2f+d0xiH(*d>EL2Fwnad7NxXq`V|K;B^8jL(bq@n9dF z|9xGxy7#0SwtIt&%r1l>q6zMUK^HyMY<*u^xD3CTzbL7x`wGNV!@)ZSm(Ztz&#Orq z?diAfHVA$9@w{FQVf~BNm{=36>TUhS3i;JK=RJq>z15uOx(OgN(3JR3EOtEc&{(u? zQi}{mNf&g&yw3ktjVVA05sJ{haptXINPl^mn}E(x2u}?uAsinY(I~rvH-_pci~+qU z@LsgJbwSq?M327g^JV|ElT6P!37Y6h`Lm6z<R%YV{e4C6`qMh%7uyzM*TN6}r{T+k zVyz)3jXM($F!FSDFn$0i{ojO_a|AAW=Lu;LJ0Bi|FGbyfS^{4W*}FUd<HZ)J?aeX) z;)=cP{t;lN_9$<_{sujmMEkoyO4Hi7zJRu{<<noiOZg#}_s64;*w|;Lta8@O$OB^s zKVVP7;aAPC&$mzf?g}A146t13SMh4=%VyF3sf*h@C-sbra5g2cCy&1FkPCSwc}EHC zG7qBMw_koitYh@?xvogDQF8lFK<)WD$h2-x<?Mxj=u`AFaF}!ehw%K`ei;*OY?^GF zoF1b=ruiHWu(zVM%}4y=V;RKeYh7(QxBFS<nUsS%LnoCFGHnI>hC}4$9p;arg(*O- z1ZRgb3(bYzU)MKdE&r2CU!$A_dL{V4LbIBf`{Ns{oMz38X@jl-mSh!u-Kn*jvYnqT zIYxf-y*Yx}(C>x>Jd7_v2y3;XTLjMdn{3bV?vIXE7==+L_j?i`!YJySm)CY~Jv3tB zKyL2z^0g&0&BL|vq!VPiQBzZY&l)}@Yb=wqZ=BSwP56w|UTWO4{sjlEV%q`EZ3buy z#)RaiFJ2swXiN7qJUV6o-1>akH~A#(huNX`cz;chSiN;1A9%PooIyn6UIp&a9edhy z<@dgg`Zs|Dy$q0&P5i+2cmCkj1D%V-*rFGLAu2Id2Nmbl++>U(?Lc>y)kTIEfzhsi z;b!7cZv@3KI+igvSC8SjyPM(D>o3u%WnBX)vWeC@5sR+!bgSgQcI>?><$*-}+~*(D z$d@;U4c!#e*e`X~;nkp5R;Yj_yQ@gIZyKV8wNzm(yQs5tJc)j>(Ue{P<MVndnfkfI z2%CD#kovjy+9=3t2dez3rLe>Hal34t<zn?>x%`#*x;dJiXdRQ=+U%aVHYePxcC+Op zz3YESa;WRF_jgc*>4YZ=bH$9YVU#&*Ud9FnK>C`!ixKFvW?}~=Tnn+d{)XbYWZ>a= zbEDlp+zP|D>v19_uR+g^(Un?%4oLN<d#V`?;ne`3UzZ`pU?kbre?X^J?m<stXF0L` z3}YtrhpUb_BX+VXvvGq@V8{P6ou4v~<jFMSyWdM*OWHK0Mu*y!p0Cwfw0^gh{_Wm9 z%zW)H|8R|WdlY?4C6hk&`4GQzA#_h(<$GK7Y;b(w82QXo@h2z<0%OC06RC&iffFQU zwXYx4X<JfQ9AW_g)>zs$O8<q)_=n$dAaMU->+H6qIApHQfx;KH<b!Avno3$jL0cQQ zXTQ{e62ha`YuPQHUN?I#y@#em%c7qd4!?<Sw$hz4JpY^l=S%ln<er9)<Q`EzcXkN3 zt9#*`WK*tHJnx;(>5Oe(&sEfJKehbOH8$zlSA03&zBazdV7~V(@5@mG`h#eE`q#UD z6V&Rnq4wHd{zimVYk(W}$z_i=V)|c64yZq3!i631-$6;`?IiOCVj%!Pkk=n{`La%0 znU6G}jaZ&jYVYDB29|U8CV+Dv*ISojfcsyd*o4fZ8_Z+T47OgL$vS%%8rI^B0tWxu zH<SmW_UW^DCbSu=BDrWY0a@Ic-@ESfHUt5E0wj%tON#juA$4=s$2Z+|a}uvvO2@Ja z7_Nx>B(D8mJ+{2&JOy(#C9bszy~98iorZ$zvCmq*wf_f^eO93HJKa<ioQy6y{$!Sg zUn_~lM<ihroj@n-)tJj_2*9luwB&*4`f|(f$|maxD(FRaY}gT2WPG@H%)FKW56ixD z5*L7&Zhe4KMgws@Ak>)TXNb(Nb{RVUU;mmXe(tr!b|T1=Gnm)PS0fB6HS#TW+Xa_j zP~F{7v_J6lNt_!BXOS{hg4SPJNPcfX%!^deOlAF#u_GGGF9XYIv#eHG1DP0V;ttLJ z3kZcV%kP!ibM+vB9mT=ZHlP>!pQVp7lWY6wubS@{&E^~{9OVBC<W+anjYF%1gE{g+ z7oVXMUH}^%lwiL=z&TIc$5G5Z9lC+ES5H+keq!UW|65^0MZJ=B(muv9k9Z+k4l=b& z5xa9wxt@Jnfu{OJ&xpMVcQ)RfrhBI+G7BF2KUO*{9VWD6YbyaolE}S6Cv;!VO-67G z%<x=G%`eW6AYh#kn!-TKKQRyI`!5E@yY2&@2l7~?=(%tdWKLXC040@2Q-S7hn@g~L zC4zwE=bdt5d&!B}|N2#U0AV2U#v>D-UWSFZ(L<VluK6F%vR!?<R^Yl@7<Gh0mG+Gj z1TI9O^B@s>a6nx=wIm~X#2n-M=^feqa+UVQV!`FgYX%V>=%`ox{}{c0kKVuhUp+y* z%U42LqVdycUdt{%1!qpB)sn}VdM@k5PceqYmAT&HgOWU!><5Nx--{y;;C62Atz)>0 z1680R&=X2KF^hH%flf<xuUMnGL>&+W!asac{9^qsZK0ItKZ<b-M02PeGCME{(u&(z zPc$)Wif4Sax~`iRw{4G}ol{FFm1h1dK0Hx1NOn;rsO(F4p8LBRyw{X)Hv|hdwkPli zYx3af+B!VLCv0o}-gq?DzZ}{N@F<^9kESrcqSs@l|3w5!$$-uS)UjFA5R;}4nj^+~ z=w_IR-(%=rcbmRFuv{A<SkvogK|ha2IpO!OV;hK<DhckUv<Vmdfo1o+5elQqf|9Q% z<der(P|A2<5wH5+KR*`Ub}-MT2ZDo1p(;)%*nNzV{+m|pRlvE#eJeqlf9ce{k$=3L zht?O(z-2ig$Hn-bv`~w^l3VzQx_*ESE*Nj1=srU5nr!ULo(BY&QqL#4E%(}Plp`^* zjk)fI`$Gc=+wVDI)B|QNo5=n~(u{p4I`_BIMBbDCZab=P8;e!iLEuo_%qO1RfwtMk z%nvv!FJ1G#x9slRq@SAfjL0Xolbr`R+N>cI{b$&fcmuJy5o9Rs4?{s}mt|p5@vw1U zo%}<mX$}8us?^*2<no)Fo-7|pPiwquRm@F?Vf1m}uisI-&~<oLOiWM&rQ_vXJvlsn z3XYM&s37o`4?&#8(u~IUuifA~Ap1ENgrrJ;fB0>rYHWwXdw=e>c~yulbHqOXuR5D< zB0~jia$6ZL?bUMrxYjwhdfP^Cb+7sJ!DS}yhSOvpNkOq#8=tf@#9<Oqi0S&u7r+qN zxxHLc@z!v^%%iifz$?u0Zk;eTy=~jOf&Za~97PTs_5$R54@LLb^bO?RXqJ2G^mntS zv9Q6{U3;hVEXBBA6+GvLmE8Lm*g|d8j2>2KO5PR1p`OU^OD(VIz{Q0~3Enpj>69|} zqx%xMOJj?vgrL{IT1Wh<&3|Xpe0y$;t-D)r?ty9Tg)y^oz5K`{R_AN<QY&Zbs}=(p zCpA~|$Zqm`SSC>Y7es0Ue`n8w98&L@u3G|UhkYa)q|>I(O;2*zc=MLV_7fGxGMSA- zL>CPYx2=?D0(RuQC7`ArkADNYx)MGSJndfs)@)ybRaB1JFVYO&Jf_x#KM4CcUAkGw zP+rsUx5@v`ZsFC^(NtTyonO*D+?M-QZ;S$QclekfV(~52L;)a@BoIEHHU`&cH4Kf5 z?8rudJwf5=Ku%9+hY5t&^!g0{yTQ2r_|*k~<N0i&Nq(_A=iK1ovE+ZP%DdE(P&my( zDEi%qs^lQ~sSD@%(@ma}-_~$5C&J0zPWSz_)$q0D3;jW3<@(*A#?S7?Xpozr<;Ij| zp+;lMmQ<4evX6B4N3;eUnvvvx6^oxHl3qCQ9NK}Ibwz9FuG4920XmB=kM;+fma0nB z`&Bb{>Scv{=m25d<TsPm_jIvLWjE*>P9F}afIPCs;otrB$Y^?&``4=;uB)Ki-jrdh z7aOsnY=N7-+i)OFlQzEc)lR4^4d=6t=2_v<Bmt24lPTSks&Po#LNst0zmEccVC~yo zH3Dkz>{#te_iGnX+L*xeBVxLFAk|!{Fpuw*(FBCw50uurur#tRhk?X(@v>;We8b7o zmI*v8FRMns$pZ-dX3d;D!U9VhI)$0xW}LM1qU&fJIx8wc>2(hD*I(v)XmI~;@v$uU zG|H2W4UND>z#Emm)1xb}BMWQ-(EE+O9pQ5s9%Zlobi}?Pvukt{Ug`QZ`KfGM1t8!7 zz{|~6e2y3_{E0=hzc9l@9Tj-^gR(oz=0yAcIj{hp`|Pjn00FD+HF$S%L$-NnFh>mJ ze^JbXZ|71QrQ_(9NN+YY9UI0rBmFl5X;aL@6pDZJRt{u#*1J#xO{0IO!sfqhrFwzK z*{dBbd{0(4E@S~83{)%j&(ts1n?_#?H=2oTdZ&*?06!+n58JT+7y$-Q>+QUeytn&Q ztEy*>tsTS3dE|$N7sh7;*{=d;Sud)3br)VaUvi~O13)AhJ3i+-0NG8i>L$&q##dCt zJ@OrYkcChfLukujAxcdqE2IvcTxf{~RmP|lenv=v4zsD*at_nHXaCX71~%SQ&@{7; zwBX5O^$eULFSGlK2hF7C9Hl!Djr;ruN)ybzg_t&)kkwc)u3=OoF%J>)YHS=U2F_O! zP%*V{iKXJoF{;dJ+}$kRL4LZHa;c~GeT;m2{Hu@4SIUaO%Smkk$_^yM5~Fbfbl5Vw zNmt+~JF%S?8~VTNkc)d^>=_m?@(5pxUI5;tTmtbML-@YkO&Tr~ke<GF&!aFdV<^JT zkzds}3|QKF&~ZoapI-h!QI!6t-F>z0XEYBQ#r8^0`zB_^Jm&E13UqL%yHjfk;zF-e zQdlN~@=Qx(R+!*tE~UvxA=0x{;rvj9=8V{XQRL1Lnv$IWw3xDH9{Vuc<0;4i$@2NU zwyAb&jP1X1-zy)X7HF%t-#c5UgaR8ri{m5p;CS*<fV!i^6x2VHXb7N7PHoqFl|!Rm za&wo$jzuaY*)_GK6CXGR_5XIp$Cj>oJhaW50w7bXCA}1JG#yp;C?s8D^R$8}w3{9H z4<_fCOs}a}obTohRPU!XwW@l3dawdiBwldP1Fm$*_vuRcuFEC#H?9X8T`52bx3nAS zYhCL!u6sh}55;@sQpz^Q_9jDF22lvrcc;XkQa<EDv6q|xR-wo0^+n@Bvbwi*a^!}O zF=IAqw^!=y;~mnfuEP+SBq5zv9mosNA>=sStH2K>ygPV6Y&Bf_y=|k{t?<dj3Wk0B z0MIk;E%(WQT){M}-M*XyT7h4V$Fk`_QSymbHS8P9q2!J<l;d!X=Iw{%-KjvdujQfN zmmhfLR<w1J6Dm>n7wW9@65zbPl-JeZ-y-SkQxjo{+lXZ;Vy%n;Io4+sJfVJzyuL!< zVb#7MP@**{)o4M^c?ezHKzu1QScBW%J)QX1Vf;(uAO7dh!NWt((YO5tei=C<yIxFD zz00u#7V_sIe#1U4daF@@+`u{PTC_&${Hx(-QA|fbE4zUhCt!l`V2On*0JlkacP!Q* z9%oa_eB@`SSc%?9_b05k6gS(zcAODE$%ufO{=pPPaer1(@#jG<ofxfQ&*0^??fFM3 z+~~dp20%$#)$46gokdwz%Hn@UbDoAeX!133?jZ7&eTPlGnngBT(c7p9BdONb=5FOZ zXPfa+a+_?in#OyTUQQO{Sjut_0k$rlN;s;E01!|a(5l9W-JVNqp{8-KAkl`ygpE=? z!DaZ?De>lE$CrN)9&%4S16c0LFG_Ry(qqckK%an`P>{M`<&Cu}oa)_~U!ot!sETRy zsY{F%X|@){bv$Z;M1JV`^223cOkmy!PEfjw4b64am4-WO4Yxaf<x4lq=u;aTaR+Kb z?mbqNrFLvKCF?xYGWw<Oe#%RxnUTaS-qvhm0Nb{BeBGT;2eAR|0KXkxR9-C^P%{VI zAI{TyWM}^ZoB>PP#SC)-`fK@3$oHIh3-}bjgcH(A6prlOV^7Gk#nO1q-Ys^ORyqC8 z#c?Y9N!8=85r9GeH*c@Xp|duCJ-18QtJl&WzQ^0%2vqf63pt{ARgb+#Nja*LFy8-5 z!+Reqz>HDBOrJyC^(V=KZc0#6*W&X>r}yG4qga#xQo6c99bMs{?~q?<^uqNY5%vEH zBL4{`4;EQMYb#Hava}_p$&`^9W5!lfkfan2vly!LEDA8-Cz&B#>+(89M;BPRs`eRB zReN5@+tHvfX;%338J>ZkvVh4Kjx6?_!c>ZT7KhCdq9?kMdJMq*Cv-P9qZm^1iFNr8 zC+d&}0RE-B)d&i(XyTISzX>D*%wuA}#iaKMR45zY3FYdFlwoQ$uT{}$_)2gt=4qp- z4A%E-?Pb%FlGa4d6v~VKS%c!NPjUZpI*+jY-=sYxNbNAIjc8`3dcN5Gw35pXu^-Jk z^v*|0b)GH8qS%VMpuT$B@qk)({q9aaM1(00c5i#UwM_N2d)L%RFi!Ab0JgcCU!qh= zqy*DOY!kInkC!EQa=errX%)3}{DijYav#xd9$nq2xI&&GEEOPk=938O3xcUV9&+cz zuWY^H=G#B_Z+@s0By{(`ooxI*zfH7jmYv@YgU#_y)$dEw1PA7U)ZO<oLC!OA5cvS= z<H)~L!@EA&C;3!~Swkk#u8r#A`vfRga*G)}1P%oeZt1u9=JY{eQ(!?5%K6lj0KW+c zR49UdiU_YjYgb*CIdleP*q?4Y3$e@}Ty=1nkS&{92wZ}@S$>pN`>ryTPB^2Ty{Fj5 zv5WzoL>t?2C>gX)DkZPaRD4Ws(jSA1r14eDdE{&MHvg#qe=z_wn}9nzbN)1ZEX=FK zCCL~8vEM2CA*u0CFVFX1M#p!u0-^gtYpam|8nnDX=@DEuR1?JYmCHJV7Hdc0TvNk4 z;Kks#*U?k*{K%Qi4<{G08+obnxtuUSrj_XF=l+sFIQ~d9uDN(ErA+Q)91|9pKcs_D zu+&`ijfD}dszl6FErPbTSKOgA(*$kQodvIc7w^;Q?{|~C2Ir-vj7d|t#VxQnKl47q z$^K4FKrjEl(PYIWKuap`k<ZN>r4l#$o54Jqt{C%SdS=%(=k-yAxr4x|c1FbXRdsJb z&lrP@!~vjR0Zp%772pht#%;_cDbW)fUL7;Q%>u04fB!f!_`bcs%3x*o@5cip!^E>E z)XzOggi4~Wl@?o)L4B*7K`rhDZLh}eEfZ$VXuW8YfOY`^Ygv;AjR37dlD?s7M^!Fv zQMuMy<-R-LGV!+f+_&2^b2rqK#hY!Qb8thxOT)N_!^i!lJ-vGHy{5kf!;Iit-T#V! zl5q}`+jWjts|3J3d#Wn&BxZcmN_x3D-H*=<CSYAN0$xTjeW)o06kDFS1~9Y(K*96> zY={k^iEFm)b<wC{h=W}=4MahzDF9U!<AXL~Kp1Gck2r90RKt2#E|+9PoJ5O3PJ&Pn zKduPlu}WeVAfW1>e&T0S&jsGY?6Zg2GIwS=!oJ}{(-Hucv%2BWKm635xC=*F$csN$ ziIX-*LjR>!YyoPBSi}tWC*YX~TKp=5I``bt54vJf?J08>)hkVt-5c>_6ej$nu=ko# z13(<e>t15BJ@f)P<Z228%ng{P5ed?A7Q2Q!cG_|gtnTGdo;ZzvZhx$*ALz+=yZ54T zc;YM!ewW^bVAQpL%K|n%Isfrm>RUzRYniM^9d~<)URYT7>$n9!wk1IqW<zHI8w_#O zaMU@orYU|t_rACZg+aU;4qg&>;bbBtMZGZdx?)QLCc{I}?T`pG0kpM!n?QsB89;F4 zr?C?P)z+JV$CFyU)G+GymFOa0caG?ASJFs(SOqG^Ku_v%yJKbe)7If$+J1KojtUp+ zfW$*YDwoy6I{LTn{YYSc`{ZwXxS9V}+a1QW8|OX_c&~f5dw!rnHajKo@ldBu|L_w6 z<f4GDRoah^|NhKv{0!8Dk2lO!mRV=bxIDrGl<)Ub_ZN2P<lfp#IzPjh`c}@tZdJ<D zD6^6U7mL_6TP(T&E<3U0|MA75x-SEbs!0U6@zreng2s*Q=t@RIU?<Qhi;p_8GDr^m z@KFK3b`@KEdbc{Z_OXL%PIl%nbk+u`rjMAp`bIRK;9JuxVUhhuzHsZ}CdtP-lh|W{ z`vt%<&NlMO*nX5>m|o936!>(0vtzH?IDN>w%@Q{0NOq)HAq<M1*U59L@Ok|Orv8`| zh5R1M3}LY__4sva83%{Qsi}nLuXLGge9imCs1@A>5AUo&H;pY4ab@_7?YU3jsRN5E zMc7CWHyIponY@c5wR;ILP&Gn+Qx!N%T9U1t;8Wcz0?Y^yY~BIAaHp$JOl(Vca|VhI z6${VT=qT9C4ENH`3BWO(bZ9fx>83uxonVPK|GQ5xc_*>Q5eh&c5G0N3FV;Gp4Z2`- ziE8VBoN6NCu%?0MH9KHx+RXS4G~Dt6;u9%NYdi|nwK&(N!acG~44IJedb8N`3Nmb+ z(Vwm6lp><v9sxrB*ma$pyu|v?tnL4Lk9{k4LDA_yuj<?6^6hh=&0os<f;WpEdB*XT zkL`99YLlHrtf&w<nF8y;qXylKXgby>^H!u;A_XKMg<Ayl-L>2JL-wBe!fpI*qL;Ks zYzmqEYD_F?gO;9=$67~=;{a6+W!phTev^2skXQXeQkjKE2Shc!^n2hUr|}l|z7~L; zvEADYMv{cc#fh}&uZTc*41rb;P(1e%`!8ta4WGhH(eeBd^o}YQ=;mx|VUjzs^B^t` zP76S(RVGR8MMZnsy7t%*Iqzh}*-1zec-lxiAWELV1>6(>>tU7LXLEns)huo@fWY8% zOuM^S-;g=@2k6cu?Az>>9S8(hsz~gGmw~w~D*$5EcPx@!5L}be{36_Ye&qFE#u!W7 znj@I}JSoeAxN>w<_sApP3OoXfs5z6h(DjQ!qj#S;*?5rb6RI2<$eq^%BSgSC61e>d z(-8-VAGl0W)<ptjgJ<Iz;@~0eCbkCisd=3)+=Z!PT!Sw3Fikv_%ZA_smv`Q8P84wp zD8F&!DJaD}SW|sakjPxB&j9s>z%+m$b#^yd@06?aJn&rjwFmQfKy}OAOXZCLO<MuY zrHwIQU;>ccXeN<`1g6{Dx<t`okj7PDx;LgePKHsj&e}Q9viI^-{if69?TWq?u91iY z2%+t~*oo=pSDjfi2lb1xmx1J~2HMe}Um&48RVv(lvxNyY9Xx|QldJlBT#UARjUt!v zTQCN~7`VW?rdB7^6?^6Cu4>y|5^5NV{c;S-90xs65O{aO^{!Npo!vnHg*f;wFhi%< zwt{D&vv<FaxAr{zyQ(M}R#k7aNvpbk@v?Nt-&-Z9K2b|-8SE-R$zgcM21D-iw)eZk z?9y97UP!4IV1c|>2md3Hw(l@60k~tMNP*|1W2ao`@7i1?dvPo~Hmyw-WaQ72>YB31 z^66h}>|wrt1)Cr&rK0eWyh$O3nO(@`L#W>@l?brtZH`LEc)vp`sO}Fy^xyv@-}qkU zcdZAu#qs9{`L<uhDoInR6PLL9XPy_%Przlp1+V;zIAio<{wV|@;1~CQ>==MzvRJ`m z4l9kIA*R(|9~uF)MSd!0#}>oVP~B%RGZvl8UxvzC-{{UFiJU%ZV|Ux-a8Y45)bt`v zw($g`I*Gf#xAFpNx46aG3%NLpX!lMPQe+L#<OalU3%|U+7}GDEGNnb^%hI+4lwV!2 zK!E}??m}7#-lI-de3fnVgJr3G$H{*|ab9Hf>6O4QEtxdeTHp?qeW6W60e!54L}ZFG z<19^b|02gL0*>gcow)O_Xa12p=aH69lRwPYLmel{L3Hvh0Ek|0%ye85W?i4PF$88G z8I8}J-KObcJ<8zAV&@J}T_QjINYy!K#M1ZHCr}Y0z?5~4$sfSTMJ87TMtmudFjjX{ z7mR%IXh=q7x(ALue$^y$36!wf_4M|UZIm{5GS1&SR2GKmdcdkvMh69(9K_<C<yQ&; z*~cu*bE5xjZ%GoU;lH0N;TqPzoi*0N?m-fN;4Z-{_i&ne0&ptR(({zXZ5KQ6KU_6P z^~?0a-3ihQ%BskDEi}&&9Py3W`}~C2HIbvn$J3hjj(1rb$rt8DBUaEt%a-^D)_9Zy zsV4W`j?KMwqMQi>T@=(Yg0r0#?q3$MflNy4JIZri-i@fFYYV-VYFx=%PDoLR0{3d$ zS9@51MGE)o($~MaOYwP5mAHJ-SfBZO7TR<u;c#6@?_GE~aUD<NEaba4L59}ACK@(f zY2y2uYuL0D(c$_ZX_)vJ%Z5ucAx6VN-9#G~P2h-b-;2L}dzqcDMxfKj<R*xab2mYK z69oV}V3aEH@=<IXJ>H3QR=U#@AC3l1=LoR^d*h|dR_lBgs#sjY7Pb=CptfDr5lqv$ z;?WH+08SKen0A<V$6f`d3H#qguwyuOnfWVT)jQ7Zlg5`nrgK}2x@pJWzR*+5vAyNt zks+f=@ivVBdO_z1D(3e(?zv-|ev{MV&p289jT0>yLPVh&D!PzLkONl_&pCGCD5-T} z)fDwg5omfW?Qp)t^8#mitAp5#y{}RdTqY&^LE@^RB};^E`)_>B)Euo5#e3$TfPNLI zw5;F-Me{@+BYgp(1hkPH(*585#APp~m~_KO7h3mV#BFen+YK&2X{5`lE7&64ZWV3) znRy=&0u@VQE&om{-@-OG77-}z*w5V`-m*nbX2VU~Vf9a4mjZ%AH36g!#L%?@Z7w(N zt{1yz5-{>~3kbn=2yIo+Njy-7mU(isJa<vR>2c#|f-H{tgQxu5EtlpWH4F!|XM!E1 z9+CJ2u1&FfH&$4w#Hk9y#!D-%QDaC&P}#F-coroB4S|6ucri1_lv)uUDr-J)In}LS z)q4w!;C?=7b@u@ZyFXer0IOC64?d^8zFfee!I$Xl^v)8BfG3IaHsQtm{LCB<$090+ zs`QZgsmo->!Sf;2*zPkSsfV@s|0qGuE_1|$SWUcs^vS7@DW%}qU9Lwt1D8OzynzQx z-?q#N@wSg%5asfH;_`?FawRkRaWv;x_zP`NUXHfc6Ql3xD%a-$%6Z<)9@|~TfKCY* z&{<f~?iT9ucAioKblIfGY#+D$k7%GN>A>XjctTp(-2<dW1s2A<JF3rZ|Eps}44P2U zAVue>b`7#9MReMK0Sv+1UYSu(4~fNd`lG!BJ%I`R@JNxv<+h;w!pa*G-%!ozm#91V zp(Y?>w6vGlm0w^7ACR+%yM}8R0a`MrbXb|r+D^C$i3UFM;Tvd+1r#7I&Pj;4e~MY% zz<#AmMKQUHcr8#p)w*KFK^oKuDqC!Hes|Y#VheGgmII0*((U_g2btZm-j8*u724;b zHiFluY>t4Ybzyi9^Gh5sMgzVa-#EqM2}~K|?*{wC=$6En<%u?F<cb)1ThH1_D4f1w z{COA4=ab&%gbv;(Qc=b^a1&L&<GIP0ejLIH)iem@@5U4ehkvasTF-Hkff%Vk(v%&r zDaQ3J(-h5xt1UU}TOOx}23u|NFgW`f`Z^g7x6<a<*P=VfGUDt$vR9j8*0rDl11v5Y zwG`HbkmtlCS4h<yZUiZK1T$HD8g+~J^gRby{Fwm+3d~%&b@HC}5zXIWf25xYSe`!N z5u+IbdZ;^C5)I2-vt|-1kSxW#hDJ<?yCoHPAHR>2V9%NN+RrY+TQDFJ=<Drv(ChMq zJSxT}$5o$DZN<bg#E>*nk~|q(caUKC+g~f%X<z)`*6|=L_qRSzBiS6!dJYyQ0f)u& zGwXkgr(yLlFKvp<`jaVV49Gn#=Y>jQgVrcZPddiKT1ihq!NcOIZ<&YTOx5dsggUuE zhhJ{RnSS%J%F0i1x)c~5I(ct7>a7I9T-%NnSw7}oCB5&l)Uct(l!I2ECKA7JAJexB zY!r9X3m^wq5;9{P{97z#Ln;D_`Jb&F=QN@QUvLaMpH3<_OA2t3KKn<W((cZ`(zf3i zLL<l4FH!xYd<$iJ*tG4)%zT>IN+(2v&xW(2S+A0ME~9*l2~Vb}xYZ%`A`Yg)+8HM8 zg${#NO_6O;Gl^IEy~ZuZynC?lWpZbNALAf=B;CabQy~HNdZvU?;(MeoMZK9Zc!SZ| zhuW{Xa0O|Z9Ps3D7Fe<+Rksg~(4pjQ)BryU=dR21@Mj$BH7s((@xYM9kvQlZkL^Xz zGA|X@jYNe`g;`l2y&Yx)hpp}L9cgrB(>J97*UPao@gx(jP2e+GwIj_Vo;^TZp*j=0 zf1h17b(hioPeM#kWI$O8v53ow)`R$9^TRi>XxOs!W|l9XsGe-EYL3SM?7xu#S9D)p zKEUc%X+{Q-S>rE+hME6s7AZV@_R&ypRQvKdnhtkNs?ps4*WOo!McIYz(%m4SbV-*| z(x6Cp4J8AJB1nrMJ*0?$K?;J>UD87h2%>aLIxuv1$6o07`R#qYPyU1dgzFk+c;EG| zd7fuIao;z+E{N;V-d{ugS~Ytf#Ln5u1Ng|hm{aN`n{Rm*Um8c4#`2;=IlCyI(pQQE z5Id7uO)<Hcc6`j%Da7J0Hd5Y>t$FsU-0OKb`|gs~jqmNtH<FZ}mku`+G9KKhyzYyE z<W^i!EJc+a-Ij@+7=ODCID{^;BC;%BpSuYRr#i^2VB#88_4vl%7=ehgTHrs9(tss< z@R4AQ=aE3&-5q_e)=Bk?dR*)2!<wJVT^Dvv&ktrZB|qz?V0qMI?+nJ24a;P5-diT@ z916WDgGim9GT7=r42ro_p=ru>wfMOrn||{dheEh}U4hI}|KWV|@vIbv9Gk-R<BgI@ z*&7v>9+EEk+JF?V$wb|!(v!uQmwXVydorcET>C``0JWCuBH;<OKEhx?&L7cQCx=%v z)=_L?EbcX@0fVm<1PmP4*|x*8SJ29vvE$i-kmeYs4%L#`JXf+9&#cPnycA0SY1n&+ z@bpr5>dh3Jp4x7&;=`t#<@6YRN@>Sy{x;21UtD78oPPo=W!dmPR6`wrlw1V6B)%Jc zF0Xh=Ejm-*o4dWS8j>>Bl$0F>4d4E{aOdg1PV7q!$Sqh1k*q6MhsrFec`s<iFL_78 zDeG3fSDo}wql1+Xn54(MM#4~hF!=3fWSW}IJ-K659@H>i+UQH(@sA3$h6+=KMx=+c z*^dQX^dsN&$gwevM)`j%D#jK(ke~phxF(Hi`EO5=FG;lw`;@1hJ=BMS01f!=CkpM` zabD?dQn!pxSZ|R$Wf2Z#2>i<N{^yD$L2qgZAj#{{A(UG-#<hQGASrPsJxJQ-&q)1I z)UMYHBsV2q(T}YAb4j?T6s6*lK%b_LB=nH;MW)~17+4|#b+klAbLw$E4maGmY*-oq z+026|9xyzSby{^`Y44SeR8CPfZNc%|_*8e)-pkZ#G+Nqyde<-La-u14c2cB@Kn_Rt z<iVYzYjq0u_Ac(k)(RC8hhepH^Gn>Sx&82sWALCjc0DYkwCxsw*LjYysG3J5vcBEc zvH>El1~IfMe#`9{)WS5%0F^c}_FNz>PBan6=C$p;5wl5UL`BnlMjBvtxK}FNFY|%N zrR)sTa#U*Rh&{im-Pe6k2}vMewG=sCsiyLDTR)1J1{-NZ42Ox&0j~HSo!cqh48(vd zz?u&d56QmB-wn)opxBBKy8CuhMw5ZEULls|y4*L4*3Ow{4D{D0g$^{YJ6@7+g)zv~ z(!>oHR&T%xQSf6*RBlmmkVnRYoE+gR%zrG+;x1>97XL%W>Cciw5^am7A3T={q6<lf z(!A>P5rEI}kbqhr0CIbXpO%37wHDzHO=fi&q)2DZ4W3r`cD(b5IGGc}*yXweld)(O zJyq>b!e8WD+~Rjn1KC`cXi|@0fNdW>dV@~f4IU7{(|LU*J%Eqrp1_H*f<imKpLc|P z!miwjOzgFXyPQ3o0F2|k7M0P?+juMpD#u;Umib&h-XM;&b7Eh}T&k#0xgr?XM*W;U zdunbF?=iV6Hfe_^(c))4A-!cZ%CKhc{9z#ZN>qS1XR!D!my@vCYtA+nCqT_c^x!;~ zbfG&A<Ljz7h52}ox_uZ4J*>&acTPH42IxaX7IaC7NpSu3-8rYEY0`Y&F7n&GCP@4y zkA>4`!tIf6vwDlYOojPe8N}#98YBmk+E1g{UHQ!!?x^|zVHo(5wZ!JR<=y34jf<}@ zko1*(;+vWMDz6g*t<~&kYa~3DX##S}376eyQiPGJZM79_KoLjIkk0Nt+Zt#xvd@K_ zAl@pb1TS~*W&%-`A88UaDH}>LEtdUI=efh3uNjP`AG6y^a(Zy?8$nLy<%+qaOYS3Q z^;PL>+kEJHE=7HCEkI)87Bpe!$p!OaMe{`0=bQs^4DB(gBkJZ8QkTOtz~r$CtK&jF z!=~ElA+UA7Dg0r<Vup*7U`an;c|D@+&PV)_?%LR3vi@D&8x|iyfs><k_>z!G(cNjg zz4RhnON578BpR^qA$R5sd0MYh%=1p6N2Tt~QA94ve1)e#dxeDHR<un9QaiL0_R)Uw z2qWhRc_R=|<>o3lnL{7Hw_5jf+~YJ5w2>%{Aij~bXRx(w5mpy7D^?3(A~cX{U)D*; z0Atlo1{%`=uDZIMwxfd_pOi6j7;nvQd7b=4CaQt^Km`f)Rhf~tw^su`Cvt7_;mpr= zp)Kbe@8O~n7M8TS$D#q_UR&)j+c_`kin++9!IXPR@ksXAPuxAKp`dVQB@dmizkQ^h z`?Tc|*%P19mRAVDK^3X#OxIS*q<EKo=us&^w&wBa9wAk{{3(qFP+aSPq`2ZVNlR0! zxG*V3ux6enLzN*J8l#KLQonfDB{SmlAxU9kv7D~1B0s>kv!~05(nD;T-<tbUl!1;! zzYJ^5;5u0oGTb|DL(~9i-G#ztI#1oOYAh;-ovU-2J?hT_Ht3ieb~xBqHEuzx*kviI zSZ_6B-ZAAKcGrJg*C~AjM^FOLu$tcq?td$|QbW4JVx_z``3bdpWm~2`HB|Q0CH30$ zOPjbYiq8*;ytZZQ#pDAfM^88nHUL!Qe95jO3yEqOZZ%VUlkZ%=tPHRPnYlet8f;G_ zAz{~Xt5)2T;?P=>kLq;S<BDc<sc*%s2Xzll8(kiXtw2w!YZ*xjQ@CTAlF_tk5k;M4 z?k}~A0H_+!?vjb-iRmkvbs}+%dID?DQ`3FWW!7m2@qg@mc_`BG7TI96Ik~xn&-%RB zRUgm%^=on=`oc>B=125RwOI8yHytBFI4q?tt4p2B>YQhyZH+!$@_~pVm5)AM<h_#Y zDw43UkRQn=8)SaA>|QEmjR#6PJTQG`=HzB{)86=E-r|cwIZgVaSBJOdVN1kt?{&kW zV+ogmj?+xdKw;*|x6IfnhYn+UbVUES66S@XEo_2$wwu1y)G9M<4F!J^;OkqM%K1GH zzf%-UW7wT7K`$`>hm3rLMPWFYg9LkINcAZugoL70@KDdoK`ZZS&R^<k?U^{dFMH!$ z$(8<OWNOcDQ)BjK{%s;sBTKrsLy58Sr`srlkDBj&^mE9i{JD%=F)_?lqX}hP8*fHq zWp73X>6fX`fbNat=tAQzRfP3gGxFsS4oA9HJ6~X727IY{RW3V|H+v52#&=C~Y1N2{ z$0`tHhnLEt6u07c&;()@@D*a``yfC6k-7;zS}8maP$3JC7C2T^W)HV7`Ol7G$bdjk zicC$>g^lXTcIFBzNd7e&5XUtV6vd>>Q|O?mRn_KEG<ym=o)YV?H=VTI`x<|TD&Bd$ zqe{d(`p}9VyM5VIf+06OGZ5!#VF)l#Dvc+_Q(=n65fKdtwWai*`_5CZwQjw>9~gwb z*kK|X%H<m3-)F-py*z}C8%nvJo#j+fmnO#{Cp@D`r^FvEFmp)H$>UGsJm>XU5yA1j z<C)YH6}|0dE-sb6-M6>Ig|`byQ!FC`P}X!Oi~+`JoPLAY`-TChZ-$OSY+rc<F5(Tp z<#CtHG5ChDx_EZSqtU-KWA;d(AwOg>=^|NAPE*^nZ=bN2T>04A1l7VxubL^T>k-Cq zhSXXy%_(;G@;@q&Y()@j&<e_wu2+(!ukaZRyXKx)WV~bh^;32&VGpR~pr^4~wdA}! zdR4Wp9Tl$Hbo`-*P*Qy8PO$6Bw$$Kd0peY6S`PLAKqm3QLu)dK%e%<14rfo_J%`)B z@pPAbN!U*xG%A+2j-A)oE2tTD-pIa~-5wuc(<GR;ysZ3#zJ$pmuM$ULWj{ScOjT2j zCaz2k_9Kj2o<nXDiAzIO5HjjsUSPaQZ5q1rhAJ;Mqj>+jEPv(ErRsw)&J`;DqpiaO zO{Vjibdke#POi!6uQ{Bn7{(r3@&3o2;}>24({rUm(>BsZZdTCibKf;GVjk$5gsVDM zNI{m=ehazLWj%4MguBprYN%2Df)U18q?+1S^7OYT_Np#&v3_6C{sA3)N%4U#%9@%D z4t<Cv)kfQ1*Y@?DA{mwf85ZI~0;`x)QJ1QHhb|eU*S~)m(~830FmxJrxCZK$AZENE zr0dJ(d2ul%tYYwj8ILg>&)nZe|9{{7AGQg~gp)8eWc2^@O-*4tfq|1j{I#oOhO0{> z46tKkw>Ax#5}Fs@&hIh6|NGKkVTjAE<E2bj5>e1-2Nn&UB0!A>oqw}%CHGgl^j@yD z{xB7`l}f5luzG<8#`SVt-m4Gr*4@NI>R)hjocRoV8HBE+HD+u|G{#(df|+HX^NjPX zGfEiHM)kg#7f1WWx?2(dHJe03q!HEP-H~kx2}TBzE2TU8wdB&$%QWWt)8H#vKC+=1 z>Mdt?hNFr;=t2QcLptJhf@tD}C2=;uE#zGeQ2I0WZQ$T7`*Mctd*Ol83y1YoMl(R$ z_Yr}{SvT`ZH0tyyU|W2vdP{t}dfWZ7YP4T?`{#@dBRdO&XffehG_B%`F3Gawou^{| zElLS#6iX#PFrxBPa#tqt@Zt*@s82Z50&qa;i{)Qbg1$K#yXC7&^V!N`GZ<6~cxKrR zm;l&Qa48;h-*}KhOc5vpcF0sR0cF1Z*!LtHwU0ls3t|EoX(-U;Q#(4$kBMaQhM@a> z+diM1yLUo-#(&nG$^Z5lk@N@<(ZL6-JM|aM_0Uuy=S1Z$-h~$zxJ@w7fl(Z&I-YwE z2g%cw3kH3gk%gHNF00*Z4<!w=#kAC!-9o>?(pHbe14G9#KY#RsutuDTb2(UWLH+Wn zgeP^IJ?K^#@SvMm=n{wy$LW~qXZ2<k70v%@x>eJ`m))rJXyxCXqV?jFzR5_p3qX$8 zV8)kOZ^bBF!ro#y-H*G6?Wd?)FJ;Y@0$8|m8>T{ni8XcDAdo1Kt;NI;VmtMG_X3(e z_#?ifH(0%8F%Zs^B>qJKii7An^a4N%vh?;t=FGJR*ll<6M1Gh)h{cV|Qqr+lK5K(& z;!}pbKuB9n3&kXY!@a$JlZY|b_n6m9d^AV$Q_K?YN&Ny`tTbTxVTY;~(()EHdCk>6 zFniJ8C!EaRp-_Q{kX&IfOeg1m9e95jebv&tEpa(lb*vNXaRUsyxn~s|HAOF-ZG>4# z1Qr<l<ShwqYrl1#sF!2DbT!31iM9>2g<Wt8B&pawqyinvt7qDh04=a1+JNv&G%(q~ z<L_%xKKybjjRRO}AsKW*ESFuv9|+BWloQa}IcqYH<Q4Ol|JC<RZ{ETGM0iKWTaWbR z(m8FHP7qC-)4fe)7O^FFp4*Sv{)X8x3~?at2)S&fyXr2eKxT%5qfqdH7JlE?F@z=d z`8-Dx8*L0yNuM_%I1p;cP1*?b&W>us+XS}Mq8pkLK3ri<Q_udIu7o<$dMMB~_(7%} z2G>tOIK?YNSPo<pP{|gMM>d&<PE@ZL+Un{0lI&<P1Tw(V6yzsX5z284VIpRL4FuFZ zSTAOW|1K^g4@2Dc&>pfg|BEGe(2+`9tPpr503}kT%3#OYDxLAW&pwCwphJv6C15xf z6$F}@Ipst~wsm`*0rD%;m1jlme=mlz$98(ICtXN?Mu64iirb}QO|%%x_yDDDRRLr( zkIfd^H84ie1tfUCOJU*~cW2&G`b?Mp!)w2k`i*<}_FJ02&nRMq95FI(ecq&PS71gI zd~JMQKmw?cbaS_rni#db1{aCvh+n?2)n@^G+1kR*Fz}rE3?fv2jU|e_28?-1ktjJG zbK}>q1CvFdUL`;e@*=EK=u5LlplzgWJ?|PF2s`{oc_AKseW7-Ljo}8XivtfYwDYy+ zRgK8yzn=fOdj_aG=JN0^I729T@yu~)&BO)g$qMOr2!_$47n}~6<UMw;_;<h0T2#%u zX8s;67-*4WT{sqJ=op2Mp4@$5MG|1|Sjg_e03Acck~JBP>JUvSrJY?@a~nJ!y!?CU zev84MTtm4EEv{SY{1lvgB(@4knO_*Ypf#eZ!P7G9kgOtnbm$$s@@PX!TcIbS;cU6> zzZ<83K71YJ6>Zn7Q-JOWBeWDl$dYd&8)^tE&@Wh-V+Yh`!TbzBiOwha?sTyx{r90) zC~InSNVpJtWTCmH;wv8GdZW=0Gvo@W@%0(3ER^=VsodUE9#b;>-Qom-$+L<KA$TuJ zgy&^TUOiWWTp81IvKqV*@(6Ro#}H5K$I-i-|K30z5aWlhWnC$^ij)j)%u<&{HY?Gy z(yTgxz*iJm%>1vnpcG+rGPRsX-pd$y^?lRegYTP_N_(h%kEAFnfKG|B*xwb9z<eZ~ zu(2xOFg>jSSqkOn-<&XL5OuA@EI>IG4=92CyD_^ic$0w2j+RD!19UwJbsS3U@Dp02 zF~Hpcu`^GA?U&E}f0CZm@ViKBf{nA=T!KGrvK|IJ<#xFyVaSrX`>{e8<U_whpmek( zY&A>a?5v;ftu!W_z?>Z@!sYA#U+aq872{PWfH1zmc}`seNdSXO%6|g-;tW~M6{H~R z?IQFsEV2+_%m3XXX?hI1%bh&FNNHR+=-swa{_74eB(QYAX%nxM+S-mlE7L!UA_inF z!~a%{cFp$VBa?@g+0w4AH~es$6X6%5PBa9!-u=D8Q5jl(QIQq+Ok<ybmZe+WkP{6M zZ_RTmi?00}*tOM*(3Erl&Y+X^^qo(-)pr2{s*i)pE)5mF#ZJGU9P1Q?%3@F=e<m<b z*2#(x0Qzbw7{<ff<o~@ts5cSB$|d7UdG$UZ2oEW{nA!K6PyLSKcn8Y(li#_5fP~H$ zK8m##fQ^ghCeZ(H2?4xCcLWqoe_m?yMPk7NJzjaNu4h#uSE#Q%OQBRw|AT`#7kO-q z+5Q4MXQ>E9q1J;REaUzr!;Xw2!p7CV^VXop$O*mOR^_qe?8fdLl~PHd)#I+AjW=um z=PFzD7!4JcpJ)jHf%i>vN(aUFldrEa6Hln*+hxVL`l!dyKZ$4uSX!V9!9|;Y`k-T6 zqU*fLo+#1)pvYkkE$uBI%~KBJFMsZ}i1uNmt5<zjS)l?9dgE0`9#7Gr1&an6GNBI{ zq*WhZV1Ht#`&2I<F?E1u_6;p%43q4HqIvcKT3ptNXVH%^;g2elC*DucA=T#Hf3_&K ztt+9@$IsOM3Ho|*IOsEcF(?;X#l;}f#W;l1p-1!Gao)Ww5OC4ALBA<O@Wu~vSy+zs zX^Ch9ExW0j6;M1w1D}h3s_EWy$dTz9{*y)^lf0@2ritu}6t?K9uMk-#w@hfLzMz=; za=1gpzkO^FpsqQ6v>Z_4MG9T>L)(?aFfiT;sA2|UBDr;N%u*6RGyAC;(?1!2G>y6A z=Ad5k^**)WQYTV*Ej?*<PKO|C>KwMU59mS$gUYTMjduiH4sp<4*PugBu>$v|(A>u{ z3ePnnCfzR331Q?yS4jiJ6B3RPv=?`){9S!8dx;@H!4oTQO4X+q4BR!uJ@4#nI!NNa z1EC%|wI}Y@F`N8SKri8>%mo^X2}`0?(!U!mFt5qLdOPuAng`0z?YGF?EV;Ws5O2fa z=JDsEcrTsR*PS?GjZk(-(8nbl<9z-lww#&-X7&N|O&un5((mMD(Oo2?C8p4}Zr~*Q z`Kd&@lmh;A7v_l%?;CeFreX4^N$)2Pn8^-@E~5WjlV<jp8eAJcTN73!dWBA6-$WXk zQqQ&=SBb`<sr#(zUZWQy!WTQgF7u4Gyq-xO;vQJ;d)_dn8f~HG5$qA-5$e%C%=tUP zV+Q^~xbB}8Z|bGPOAG*yxCer1KL&o>D7>JBwtqouGdVd;$v}G_;5r@FPw{R9Q^OYv z8SaBtAAtMDLubrke=|Ahyfa(pBXsJhYUq)Tg=;1LA3Kt3uK-OcfBs5cL{VJFx-ag% zC_hSq9{R^gwoYoXFT3SDWN`!tM$ZOmChYUk+~TAp_-9hegTJ@&$Dg-vTNqeOl0Z0R zAB->Q7%H1v{JEy$T|B#@sg=d7{r!W1TR{_+xa19tFwp8Yal<d3-5N*ZIVCg1o#wCj z0+i4FfwNY-ivF{lDD+mX7uEfYyDu~&iJY<!g#w-}pzvTpH9v~C4AO;Ow=uCvvKg~s z&~VI>5%}Ev+u_Ml(3Bu{c?~7^jP9$z9a!p5F-vXl%c+M`-sWA@BSpk7pXa_VD=h2s ztFJgLC8?48^H*4p$tLf@`%ewmh2;btQz$G9KQlOGYT{I#k_M){$LH$}DZsuPU}a*R zWIg8Hlx=7YZrzz%^v9!NM~#_N#aJ88ex`PxStJ}kqqO6=d}zgh>NXH&gB0TvV|NmD zl5~=FQsl6CRre`k)K~n1nz)w{{@J7Z!39Tt$qttQ-FW6&A-uQ0%90M2?Y7nF;xbRf z)uZ_spVOQmz8iM!Hngq!GV4}rd2-$l9giDlzNYq<;ktY^iGTbI%NTX}>UmCe!U0uS zv7X|gh8_G7+4THlp`2b6Xk>}2OgEC*^K_bwzYqW?Yd#;fZW441dOfttF-)J_C3@YC z?=GLZfYG18jhG4%9d+7u$dcJu&Du9gcTDmQHIc}lSbvas+Vh@$E&3^5*ep=(@IA<p zkh&JllLi{v1n#G@s<trOAlqQuxlzT{2-`5*Z*5$E>^3oqyStL^X7#`Zp_k!l9EDqO z?3;;DDd+B$PhU68JP|3fF^C^5B`v9AY{+MmJY2jTkM7v{{UC5>1~Osu6D|<ZJyAeO zxvxt%q=)%yv|=4tjdSVKM^%FxA4hfJsgat$n-mJA7=u#w)kmVEj0XomhdN{mZF6CK zC#k#goymGJY^$fbWo_fIb+WN35DerAt%I8afm}E<=$ge+Z^^=MW@qOIu`<#BlBNS9 zT-abl5wkOopE!l`-y!xhm~GU^y0#=G(4{}WMHY`w6Z6Lcptind_Hz5qSyMR!??E3& zKy6FYpv9T@RkMksD4q}MQR39TQ{vz%3q`~3v=5FEsWU$4)wY6k6uDP??M;H43cmVi z&mw<!ZwScbL;|RH%fLW_y@T!73xb6`e=OFzDa;w3&86U-tRP?e&zd^2jS9Q=alK1Y zG{OI@K-u?Ke{u5AeK^~v$^+(C@=c=^@xT{dfK;z92gM<%mU=>~MxaKg4$Osvnq>X+ zB#Be!vK(AYp&kC(h}qr?0)R0NS^C}pP3~1Dqmw2(=sG6>^?69E!<ilXk--{;O5`uJ zq;OApAfETe^MpC72B>G^Uk|TR@KzK72xLsoI2W060W=Eg=+KX!gRin-t5(vF(B%Zd zp?i&|A`$C%8W@efH6`qjk8Izk_`*}dWk=fUt7(?`_2lsOgTe81!KL@k%InX6$vKRc z!T-2MP>wLra*d)0tHu!<-9T^?%XU|Co|!#qO72&5DEYdv2y7rp?Ow62^-c&yT;-Q> zJF<h5O0tm|96VzTT4fzqQ#69Um(?2~V^bR=*sd|ScK2wNO&57wUzczhE$$gqrIPkN z!=Na3p28+~p4Ms#28u;e1`&`H@q*}t483|abwk<g0ulL$iG|x{4oy3bc`}l_w(HZt zk|(ZMOD!9JY#UGUoXAfX{(Q1?yqi|GbJ1`eeN$}QMh)*$4Zka(r<ohAyHeJlzal2~ zh(7azG4BCqo^b$2$m4>Fu0v7BU~i^^HQZQv*~|gieOWF1CC8QBC19`~E1MiEqL3{7 zMquf&fqntm2_s{p>OQJ|hbC!N<CF@H70NF8u<}cy96F-m3I~bEe|8N?pB{JA_LBH5 zLq&3SQ|?qyM())~>GB?H|4@cYC8u(P@hiC%{S#ul&*$`(kL%NAf+8DSc+g)xI%9M) zh3VgPL8o<6?HVNfu&hk+PlWsv75;yIBJl0TFL9sTjI5k8D-QtwqXSJ<N$Xy*A~fj# E0EuZxr2qf` literal 0 HcmV?d00001 diff --git a/docs/images/rigidbase.png b/docs/images/rigidbase.png new file mode 100644 index 0000000000000000000000000000000000000000..f680fe4c81780913d797beaf99b1c07d5d05c0b2 GIT binary patch literal 6501 zcmb_hhc}#E&?h=UM3m@kkSL3Yh%R~;o#;JYJ<4jUMel^H78|{HqKi&gz4z!u@2vJc z`@Y{l@SXGBb9SG-=iEEb+_^LJ`^{|l2NhXDd@6i2G&DkaIVp8Cv_}-c??_y1;CpPf zNe_6SyQs@bpp^~L>;Mx?>-Wm<(a<Vm32sfXfH|I%oSq9B8c`?egWl^{V1b54iIkUm zujyg5zX);F(n5+JQGBT2;s8C4*xoKc6o|QXsmV$!c*#kHhiUd2iAzy_WWdE8i+^#s z6ci^eQJyK+_92O-CDce#*<V~xe&}>j2x5(W9T1qc;O!x5+rs|4mH+eQaqQ*q*{wa0 z)c<8zP_LMYoaE|ek_4Vug#lxGdKaucjaxY;6sgtym;@Mif+T@AUSYMhb!coRt~{M6 z@xNm5$!Wa`O-9FQ!9UNR?xLSQ1y+u3sF|)F9GLCzs!?(Hb7>XAh0<W*fKYI(5%y?+ z1P*~Aa!;DLa;z~zYq2>P^|rAB?qdov@Xtn=<h_npxD<5XVo3&gfvZhp<mB-}HMwOj zOzuoQ+~_rrBQp~d6VlVLt1&-RcYavRR!v*bwP3m_wT={}r7#(dVCqKf7%!QnHFtk& zsx8+~nXvP?YcgP076C6LY;O`>Vj5=lUE3UIA~|>1YI`J8GQ?Mz>wB^>2w2m|O~$~4 ztp6gJflsE<*<DoFdNF0q?G>&i34JK^vach0{&#Ef@0RyqIqIl)iTL<_8ttY@L}Vm^ z6oVD5_0?&5PaEDpl(cGVGv<7uQq?g2#Q{ZWHhQgD;E@H>Z8Z(Vw<?&pUdf6=UbkkL zwM>01QTWg1ehe?ITkpangCk#4+=%?EFf!NaJ<1Mxlwg#dBFyR;fOD`%tONqnvI2H8 zFcVXbPgd*#%?_)okk7`l+BvgeQHD?cKk-Ok#>j57O5LT8qeTV*MS+XPwCMjJrbX!V zRLKjBD9U{uN|$c3KynT`%C*flvD10WRA2^m@Y@d=u2=F2g7weKe(Xlb@ZEjo+Zg|4 z?!E=%W^Ils($VE0kL*6_Po-9)e`RQEt~5SRLh*v~fJ@G6ja=#O$`tXBF~O^%X=cBR z7czAPA<1zO-E1Zng+Jn{C^*iUI&!jXVAJ20pMqTlU9jYY^5Hb;XG<8m0#&3xb9>hM zHoN<T+%PLRo{*4uRtN5V)fLIZk>P6~%}!m4COf9BaNKyDF3^Z09qjo49X_UIuXH)4 zETNqy<((73fc;8$#_s=7FJ5Rmw^_S39TJ%=?)g5qI@g(y-E5_e<z1zp%MLmV6H`?r zLWG*TVNk;f8+Vh~gCL*CAy`Y@&Zwn+;cKWCu1#zgOA^UGsLAY>S*do&)_S?Xm=tUf zuzHA}u%;na7!DoCPmz?DlCq%h{aGrm9{G=)oi>&bMJ!)7jMcoCEhlLDy;8-q`rF)6 zo9qin!-@p$4+`4Ws)zZZT4&@D*yReiyFHNkmO_++9>&@d6t`DP{E8FbrK;j8P1`Hw zMep;MrAk7zbpv=5&WtBYHL-T^DI||Yt|NbFbXZuQXjSZC=M03tr~cA*b^Tu1>a6Zn zpJ;$5l!~dbHQgOs9yG4KzpLIE%&tiXLH_OuKNJZ<i0mR(0FSDQ?N}I3p3NnaY0<*! zh1`CUDUWK_kd1$8L`-BXKt;;LnAb8lo*NYTK6+gy6wZ-xq(VruR6jxkn2pI>Pbib$ z;QdCW?eRO_&z3tvN>(*~L|`$2C-dTT-1bwxU}l4NcN=RYnMn~4u+r<$P(WLwm^@Bt zgHHX5uGzV$ThSN?{g~s@gWz#ln!LfeVXj~T>#$p8<`UY%7HTx@aDg{~w_m9FyrtKe z6O9a~7mZm!xbh-z^uAA!@t`N{<HnhcJM3?4bp$Vs&F^q6M>%-u?6kB3o7@xMLf)BC zFZk0E+$Zy%d5xFu*uy8LjS;j5?2zQ2w)A2YV1xVB;tnir=HRqWAgV05uJw9(R<cu* zXE(?a6Q8AwE-xR@voML)&=>@awbvNl)a%w${sHk9OVxgo3EhhGUab&#hSIN!#}n5~ zvb-}>*>8`Kpj$dv_e~B~7IfpsKKP(nx84b}Z?}?=ZQcF>JVb+yGTd*m?*XsuAHoyE z{wU5(-6#lEU3*74xbtWE<fPgBx^T*L$}F#Sx*E88MSqKBeOf)p2!weR45PR;*yvuY zLa;mP_IMLY7V*+}HuVWxk}~y$F9kluar;S4r%nvu|D8(T0aN>01>Z0<-2GA*HZkDz zhN;Ndec2^2ydOi<m>xnhomTJ@k4BZ*V4`;@FN#swn-8lGNvd$~(6L(o`x1<h{Jh)y z=Lm*JQoF$ld+AYn+8GRFhu9KUA#!5-;Dps`tH1vqzH5?7e(<n;2c+}Bn4Xq^vqK=H zD)41}c5HKRe~6eu&3DW~sxxAy+BG8OH3><4iv|61>@odBS73nhVBcgeJ+@%0G}+zy zglO*I?EIbIN>&CUb#|p;j8GI67jllNWTY?pW@>w)3=Fm9@q8&Sz)ZWpmx8{%)uj?( zH87wc<+v2Uuo&*Y8Xj~7U}Z1&$_`!qCd71A)=yULecAICq&o*?@J!r^wA%eimd)r= zF^9qS;rIJ7Cy(v(h8rCvUJU?4s$dJGp>Z>}!@A`2Q&AovK!osI?B6`m8pifE+IAYv z<}kpNTdq`gl)X<;;?+Xk;;5=v^aaVDVZ5D;@E6OZKl3VFe{<upatY_scAQ8uJES#B zD~eS7<Wr{EXOzC8E<~Hfy*pWZ()sg)74NEmHmiFeySRHV=0J9yvNtO&xRD?t+t|1M zTc;|Ky$YR0o*dwmVj6S8!LuTd)HIVFWrTY(Yh9jDt7nR1MfCuC@~fOkv@T<`k23?6 zh#NkC10X?R;J0vCP{q8$u#pE7G+-x)+;7a93p@Gk{`Y?Hc2tqRspjXV{5bEEuoNcL zZR{Dmqsm@tJS`GcT;JN>1(RP8f9cdAmuY2#q-yU&nJ`yc1~58};-e!&-fWen0~+Zo zn$Iy5>S?W8((;2ctk-G+yy}J|hZwGlZ6=pwLnB4W6gs63{_-p$CQuh>?Qp2WbAR_M z6)rp;kW_t^LQpTU{(QWsC6<T+I)DLwh>%O8HqQg#-GVDvKu_-Ah%4vpY_Ewa_Rt`> ztAd(jjmtDo%Nst%OR?d9B?DP&`>SX556bfr+&<y-_#NSDcR{#889Qey-;-}wj8~50 zo&J+<ERWYy<Ace1QO2(UV0je`qz^N(_$pKZHEMo-taP2v%iUy4+oEBe04Sb+7O3*7 zBS$qu@;>D;FCXfDXPaCjTDwVme{urnEX=9Ljl|}c)TF)Uk;rMbnO^Fq1rM27<%{!j z0*h~Eh1na=Bz~s@>1nk=o7r7P)9|-}?z|#AZf=kx(nqW$It5?|@pl~5_X0ilH@?p- z;BP<~?3~@<GYr3J|AJyu-1iM#>qj7wC2-*pCBTvUj1(g9<L9>A5Zjvb*>u&uJb<tE zhRM`D6ZCn}R%1InEn6bg6fv1otsDLw^QH-xdv7#bZXcJ%DF1;qdDb&C>ycJQouM!Z ziJ`RM2L%3Qd%6+f2On)dd}7F_P9Ny8jap4Pg|Inh;AaxEU{@0M(!)~mTd{!fa*VG_ zm@<<%*g7~J0~pn!kA^(%6DF`MbI@HxaV|J74&ngo>kQ2{+r6msqdP_NA4hyIh_%-b z>B@t^9v8D8CX*keFkx;0x|OBrddj=`+mHJ%xVVdPf-z$pACbFacr9ag31g(sm>Qk2 zkaORO@P*F%7jpWy5S%B~Z34D$WZ5CCVX5<d6dBq=P@K~h<yD4?$Honju#@<=dC}f1 zWNcJ2VM$+4!d09$$Bny;&UGIAy#p}GBovyD)IhRR=*Bwef&?SGGA4<{71ro5MSvb@ zVa>8~AGF|9zPaG#U7bA(F*aXrppQY0b=No#pC;*QHAW=8?a|?zaS060?a-e>|8qs| z_GdWxz4?IDk6yyIOXC!DuCHU*xH>CYX>513-kv54#o`}dw^>&MHr7Au(F`9f_S(yy z8iu8%#DpJ;1%0C5vHjSvg-1~={VOeib~#nGbes1nK_kX!EQTaKX2Na2mjOg%1Q8ul z@Ue9%91Qm$fL@rj!53GUIucu*YNt8dk{L{HI4;!z0yJy9RG1w`+(fp^a=`=2DE))L zQ@XFuBch1UOY+VDn<-PBSK;Gr*|iCXEi8I86^;4L?)Kb7<3CTCAEZts%=RzWd^yWI z{MaBY7cO>41VYYX(|$ZlL0_yNI9M35Rvg+a>L1-TDjKREPJEWGZF7=XNcz{WwP-=< zatomrz_OKGlr4Ti0{JemUN*i{MASIkXt9r@vaeA~@vhLeuE_Af8Jf4c;FMY1#3r(p zG2K+oKKo|q?r?ip6$sWu@6{(})QO#WDV>NgYj!ZAx8|)XLu1B^WbFe_!SGt<hKB2| z{z4J)_2q@k)rFqov;*QhL|S5${lTU%STi^t+_u2wpEw*aYwzzUhHeGLMR*ubHi@6i zx7BF3Jv%>C@+C-~piF*(9pyK;xZWFrW*!(YiY}f7zbWbK6BG}`7XcYPS~Wroc_0mg zk~`gDIEmuDqr=I1C=<0+Hks*UyA{TK3`L_<$Dq`trPL*){6Mzt$A5JGU3|G;9Img$ z(1^F~_T{Ey!etBMkQ5vR-dI$8DR}jSBwobQnnqj`+I}&C$-8=ORpU)HdTyCuvymYi z9NEIFh4#|Lf|Fa9ZyNy6druXiQx<7B<H(8x|Bf%DA?>P7thmRw{N^(BzI*WqM30`O zi92H2cAj_>C0>G$FUY<9C+;W$pVUpO;0QfIvwmdY>6+%uNV~Zi=(4opYg*&s!3eq~ zQm73<tm$#Bi<P3Pb?R6w3d4W9?1r}Kru{yjy`n;>Vq4L~*^w*^`A89op@@Ud9#Ry6 zIn`C@lzl%hD3vZGdsm&255BvG6<@+<uymWVgTnfL0=!bz!mvH&I^3%3bkNRNF*MR* zykA6Bw(^^**PUPf{rTr02c*}l_1nB+7+yb(?j{`<HM`;5h$2nVnY!#wf~+1HT6ZJ< z@T+R6ESSPs2I&K5i%*sUzw2Gfy}niWhQbJ(>!1OST~KAoKpS-yT;!RuISAl@Ez*-| z2(5i;Rs{%Cj>%{Fbx?I<7oMq_&%@(-C5$ntVl5eFszo=CgNP^_SKQgRM9n`W+b{jt zCJ@EZ!XPT=!7#FL;~2>f6rxGO%5VRt6^RI4`V<MI0NMuDSQC#<g&FQiAv!m;M0j*z zDgF2g6H0XU{Xc$c4;!s^{?`*dqi$^-xF%DqZ6Tuvyi}G|#0}-PBLkF{*22xft(2}^ z0|!v>*=&R_q_O<@D24ZDNlvCLTUDbeo|f-#r=oUkWQ6s7r<|3L+ayvq{U(6bV)4nz zCXEk3I67EFrLW<)*4w#{p)Hb!X^TPzUTM+h{wi#mXXUF)__t^1r;mVq^7Ta3+RU~1 zuWtMiJz$2a*!|9{OFAhF=#J&b25WqZ-S{#yd#6cE_q_UYX#EqQ2oe37342EFE!%d3 z2i*^C{osmhYHQ!HiUZDVgXGy=6Z64TG$?A{5qT!OQ251$^5*d74C_0sGWDeaiJ3^| zqn;{JehiIew4cgu%ioGFJ>`t?IMhugjQ0u-iAEu29&1y}Uc}Ma)C&}e0F>DTH{|nd zROeSZePY)&su0bn^d?OBs98-TdJ=B4lCe)v>7b3ConLgm*xi5dYSSU&<Uj;;=JKxD z`Bf0WQ_O}ow@hSuVev>eN`(mF2d=Gb0G%iF{n)}wSUHt%E{I6Xw02pJb__jj>H_%m z;pwMvfm}%N5tlCj<!M<R!ia-|*hISbFGY8+RV$T@VG%+6j$9FE@!aD-TOz9~7Y^~` z_o-Rj-)I2vTm?&5W#XWmpwXD0?3lfExiC2T&_o_PSvN!u02UVtds#x{yFVH0)fO0o zcu_rt8$I3&#TReN43I&Zs&&4fjo<lfAdVW<yK8I@Nwrk1eCCgX$7tJ86z9`TbG+9w zE>MY1M|qUx@|2S3$zG^D{)!Lq7J4!;wi2?Q1qdeI@qabJuvO>2os4)_Z&e1c5NRv{ zx&6~3Uvh;AoAISrMXk-SiDovSNaFjCvqTx%qHu2}S-308BQG5xnS3wJNegb}v7ZwX z*!|7kY21?OF`OX(zm({!^OLXo4`M#_=K+9lR${yMEA7cYC0y`SfB-T{=6tM)eP(xZ z^hQ=n>dZFj8N9p1iC*dOh>LeM<&2Kvm@)8^-!UH`nt9?IHPdeY5}7kRtq^Ee%nsiM zDD&iLx#`k1V_h9|o1gz&#_FW*BSo>$u({8Mnj$G_b3zmB2M>VpkbF~7hrwM|T5(CO zi%}jKT6nZiHrVye12;s+^IBj7svWG&hJ^XVhp)%~mzeps_3<By&q186x~jKJe_Pjj zQ<b4TFTKos%{k}Y{Wh+VNUV~mEW`d^PR!LEjD<|0)ulOaeSXX_D+@7S-%WC@zv`&5 zKFsUr#vn4Dy<NjKf&fL`#rdKRA<ur~Ry@pYA<83WzYz3<)BrqA!r-Rtec|9m!ENpT zV(@CuS(kaC5a8&0Hobu_y7-z&Wb3?^mQ<FB9q?iB5(wt+{X7wGF}_T9yl98^LJa-E zH>gsBd3S`U{t=eGRTF?|FM*=l#y&$zQ{=h%T$M=I)j(t=VZUY0V9e|P3Jjosk$iDo zeN{HRo2#mL{w(w@M_U04glSH8iN}7H4x2B5npU*R)bxQLp^1`i-5o|0=IB~1E5hj3 znRxGXCEr>cBm8Nu3R=+hOyKw~)ammBIj<q$RNk}IuCL9gHD5y2i&#gjHLOCXWi_FC z1(zAGIcG%;&`+W|bt2xXP}}7xp=dVNY(97Gz8H6{At&!=w;ksAdXoT<+{aXRJ1(#B zm{0U60;ghJKLCEgYmXAHC)Pl}O1&5Yl%ISco#9JK{k9!;>eWZNAvV1iYxv)KDhV-n zY&Vl_fWFqO;!>eGKvFh}#F)<!qau{!d*F8%>$c+|`>*D7ih8ep7fIhyr4*u;4p+_m z1X?A8`9ygs@nTCzJP{J=m%RqQC(SmU7aO>7OX1P%YZK^3GeB?U!qsfpt1Cpat!GCP z(MMnWM~NlR@4lop&gCaiFmE2g^3%~j`(V{!ure{FvAtsJYW8&mvggeQSF#NJvP11~ zf>N}6c(dtT`CZ{}BAV%22b#J1zW=Imd1Eo+<7kK8IXoyJ8pOJWmY^?I_C-2^GsEAj z@T_`0+sEQ^0mw9LeSD!`P{e$b(1XBysVsn3);%qLc{vs|*SW%;Zx)!-YST0wlPqpS zN6o>El(z?XvU?7^kZii*>9^imUeK>{kiM_@n10d<ZlZ7AqLKcp#JYA;NdjxLK8C>a zn?X}XRI1`z^JaWo^N6TSo(J?Rw%XG=Zfp=oO|*)yf9U4p?Ng|?lHCsr&hUG*ZtK&* z71S2u7U%V-m|C8dFS3f4ZC5RJN_2r&I_2ZTBsLCnd$j{(3@xEJu-?C;EB=-#l7Lng z^r8HIu_V!Kpju<|XB0-)VtEiwx=6KXhmdjOJm#82YNf~)_wHt{X(5btYS=Gb>bwj7 z(0_}Pp9uFhvKLp*nylw_uHnz`_AfZ$n?&TkuX!0i6s2A$EME=SvzbK6dF;#B!C@vu z6sRh*B<#>X8GEC`UBZ#~WIm@{vAdr9ayvIp`Z!a4u||uHl$3*C0BX6qod;pGS9u&U zOr9(Wq$mqwFL{gbQ&J$tY<n()P))f8VW0^xHl1(QA#@4q*U>f_r*OJY2>MXCcLY1G z3{bBz5jVHk`>5fCh6*7GoCq!Xl`!u+77m)RrvfQEn@Nf;K+o-#a+wZfT&(HUBXQ?^ zUtp8%$|Gn}PbFuY58tDou40=~-iz)?=Wvlj2{B!c<^8uWw6G~}m-;*$h~v#9f^lmR zcSK}wVl3Shg+qobR-gYTaIir}{d7(UKBYO(7CY@Nj*B1LU@nQWja-cEVQ{(pn69v_ zjjRy>I;Lio&1GYCFwv(X&`ux3o;q<^+h@wfzjTPh<(#uIv=+CkaA;bEWA~d9>UqLb zZ!EKZ?@M!!J~wH#)&#13u3Dw0oB^!(lNdC-sbMDPtKSo!#Po{U*ufv3(02h%UXE`N z9SMx~z7LR{!?iEUDbrdH0~&W+%1~uzWaK#6%R#ey#_6=T^1mke@73jlBdE$uJdJQ- zk{R$!fz9LtWqiWAR6w1+(TC>gVV1mLHpd8n!2i>jP40U@hx8dS*#FRU0{$97lb2SJ JDw8k?{2$E?bNv7S literal 0 HcmV?d00001 diff --git a/docs/testScene/step1.py b/docs/testScene/step1.py new file mode 100644 index 00000000..1f09985b --- /dev/null +++ b/docs/testScene/step1.py @@ -0,0 +1,152 @@ +# -*- coding: utf-8 -*- + +import Sofa +from useful.params import Parameters + +from math import sin, cos, sqrt, pi + +# import os +# path = os.path.dirname(os.path.abspath(__file__))+'/mesh/' +# +# +# _tension = 0.0 +# class TensionComputing(Sofa.PythonScriptController): +# def initGraph(self, node): +# self.tension = 500 +# self.node = node; +# self.BeamHookeLawForce = self.node.getObject('BeamHookeLawForce') +# +# def onBeginAnimationStep(self, dt): +# self.tension = self.tension + 8000 * dt; +# self.BeamHookeLawForce.findData('tension').value = self.tension + +stiffness_param = 1.e10 +beam_radius = 1. +# params = Parameters(beamGeoParams=BeamGeometryParameters(init_pos=[0, 0, 0])) + + +def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, + angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", + points="0", template="Rigid3d") + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', + length=list_sections_length, radius=2., youngModulus=1.e4, + poissonRatio=0.4) + return cosserat_coordinate_node + + +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', + name="FramesMO", position=framesF, showIndices=1, showObject=1, + showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, name='cosseratMapping', + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node + + + +def createScene(root_node): + # + base_node = _add_rigid_base(root_node) + + # + cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending + bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] + list_sections_length = [10, 10, 10] + bending_node = _add_cosserat_state(root_node, cos_nul_state, list_sections_length) + + section_curv_abs = [0, 10, 20, 30] + frames_curv_abs = [0., 5, 10, 15, 20, 25, 30] + cosserat_G_frames = [[0., 0, 0, 0, 0, 0, 1], [5., 0, 0, 0, 0, 0, 1], [10., 0, 0, 0, 0, 0, 1], + [15, 0, 0, 0, 0, 0, 1], [20., 0, 0, 0, 0, 0, 1], [25., 0, 0, 0, 0, 0, 1], + [30., 0, 0, 0, 0, 0, 1]] + + _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + + return root_node + + ############### + ## Rate of angular Deformation (2 sections) + ############### + + distance1 = [0.0, 0.2, 0.0] + distance2 = [0.0, 0.2, 0.0] + distance3 = [0.0, 0.2, 0.0] + _distance = [distance1, distance2, distance3] + + ddistance1 = [0.0, 0.0, 0.0] + ddistance2 = [0.0, 0.0, 0.0] + ddistance3 = [0.0, 0.0, 0.0] + _ddistance = [ddistance1, ddistance2, ddistance3] + + rateAngularDeformNode = rootNode.createChild('rateAngularDeform') + rateAngularDeformMO = rateAngularDeformNode.createObject('MechanicalObject', template='Vec3d', + name='rateAngularDeformMO', position=pos, + velocity='0 0 0 0 0 0 0 0 0', length='10 10 10', ) + # (2 series of 3 angles for 2 sections. we suppose that the lenght is 10 for each) + # BeamHookeLawForce = rateAngularDeformNode.createObject('CosseratInternalActuation', + # crossSectionShape='circular', length='10 10 10', radius='0.5', youngModulus='5e6') + BeamHookeLawForce = rateAngularDeformNode.createObject('CosseratInternalActuation', name="BeamHookeLawForce", + crossSectionShape='circular', length='10 10 10', + radius='0.5', + youngModulus='1e6', distance=_distance, ddistance=_ddistance, + tension=_tension) + rateAngularDeformNode.createObject('PythonScriptController', classname="TensionComputing") + + ############## + ## Frames + ############## + # the node of the frame needs to inherit from rigidBaseMO and rateAngularDeform + mappedFrameNode = rigidBaseNode.createChild('MappedFrames') + rateAngularDeformNode.addChild(mappedFrameNode) + framesMO = mappedFrameNode.createObject('MechanicalObject', template='Rigid3d', name="FramesMO", + position="0.5 0 0 0 0 0 1 5 0 0 0 0 0 1 10 0 0 0 0 0 1 15 0 0 0 0 0 1 20 0 0 0 0 0 1 25 0 0 0 0 0 1 30 0 0 0 0 0 1", + showObject='1', showObjectScale='1') + + # The mapping has two inputs: RigidBaseMO and rateAngularDeformMO + # one output: FramesMO + + inputMO = rateAngularDeformMO.getLinkPath() # + " " + RigidBaseMO.getLinkPath() + # inputMO = rateAngularDeformMO.getLinkPath() + inputMO_rigid = RigidBaseMO.getLinkPath() + outputMO = framesMO.getLinkPath() + # TODO: + mappedFrameNode.createObject('DiscretCosseratMapping', curv_abs_input='0 10 20 30', + curv_abs_output='0.5 5 10 15 20 25 30', input1=inputMO, input2=inputMO_rigid, + output=outputMO, debug='0') + + #### CylinderGridTop + CylinderCollision = mappedFrameNode.createChild('CylinderCollision') + + # CylinderCollision.createObject('MeshSTLLoader', filename=path+'trunk.stl', name='loader', rotation='0 90 0', scale='0.155') + CylinderCollision.createObject('CylinderGridTopology', name="loader", nx="8", ny="8", nz="20", length="30", + radius="0.5", axis="1 0 0") + CylinderCollision.createObject('Mesh', src='@loader') + CylinderCollision.createObject('MechanicalObject', template='Vec3d') + CylinderCollision.createObject('Triangle') + CylinderCollision.createObject('SkinningMapping', nbRef='2') + + # rootNode.createObject('BilateralInteractionConstraint', template='Rigid3d', object2='@rigidBase/MappedFrames/FramesMO', object1='@targetPos/target', first_point='0', second_point='6') + + return rootNode diff --git a/docs/testScene/tuto_1.py b/docs/testScene/tuto_1.py new file mode 100644 index 00000000..c0990b52 --- /dev/null +++ b/docs/testScene/tuto_1.py @@ -0,0 +1,69 @@ +# -*- coding: utf-8 -*- + +import Sofa + +stiffness_param = 1.e10 +beam_radius = 1. + + +def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, + angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", + points="0", template="Rigid3d") + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', + length=list_sections_length, radius=2., youngModulus=1.e4, + poissonRatio=0.4) + return cosserat_coordinate_node + + +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', + name="FramesMO", position=framesF, showIndices=1, showObject=1, + showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, name='cosseratMapping', + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node + + +def createScene(root_node): + root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') + root_node.gravity = [0, 0., 0] + # + base_node = _add_rigid_base(root_node) + + # + cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending + bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] + list_sections_length = [10, 10, 10] + bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) + + section_curv_abs = [0, 10, 20, 30] + frames_curv_abs = [0., 5, 10, 15, 20, 25, 30] + cosserat_G_frames = [[0., 0, 0, 0, 0, 0, 1], [5., 0, 0, 0, 0, 0, 1], [10., 0, 0, 0, 0, 0, 1], + [15, 0, 0, 0, 0, 0, 1], [20., 0, 0, 0, 0, 0, 1], [25., 0, 0, 0, 0, 0, 1], + [30., 0, 0, 0, 0, 0, 1]] + + _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + + return root_node diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py new file mode 100644 index 00000000..18ffcb64 --- /dev/null +++ b/docs/testScene/tuto_2.py @@ -0,0 +1,100 @@ +# -*- coding: utf-8 -*- + +import Sofa +from useful.params import Parameters + +stiffness_param = 1.e10 +beam_radius = 1. + + +def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, + angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", + points="0", template="Rigid3d") + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + print(f' ===> bendind state : {bending_states}') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', + length=list_sections_length, radius=2., youngModulus=1.e4, + poissonRatio=0.4) + return cosserat_coordinate_node + + +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', + name="FramesMO", position=framesF, showIndices=0., showObject=0, + showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, name='cosseratMapping', + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node + + +def createScene(root_node): + root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') + root_node.gravity = [0, 0., 0] + root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass='0.0') + root_node.addObject('SparseLDLSolver', name='solver') + + # Add rigid base + base_node = _add_rigid_base(root_node) + + # build beam geometry + nb_sections = 6 + beam_length = 30. + length_s = beam_length/float(nb_sections) + bending_states = [] + list_sections_length = [] + temp = 0. # where to start the base position + section_curv_abs = [0.] # section/segment curve abscissa + + for i in range(nb_sections): + bending_states.append([0, 0.2, 0.]) # torsion, y_bending, z_bending + list_sections_length.append((((i + 1) * length_s) - i * length_s)) + temp += list_sections_length[i] + section_curv_abs.append(temp) + bending_states[nb_sections-1] = [0, 0.2, 0] + section_curv_abs[nb_sections] = beam_length + + # call add cosserat state and force field + bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) + + # comment : ??? + nb_frames = 6 + length_f = beam_length/float(nb_frames) + cosserat_G_frames = [] + frames_curv_abs = [] + cable_position_f = [] # need sometimes for drawing segment + x, y, z = 0, 0, 0 + + for i in range(nb_frames): + sol = i * length_f + cosserat_G_frames.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + frames_curv_abs.append(sol + x) + + cosserat_G_frames.append([beam_length + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([beam_length + x, y, z]) + frames_curv_abs.append(beam_length + x) + + _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + + return root_node diff --git a/docs/testScene/tuto_3.py b/docs/testScene/tuto_3.py new file mode 100644 index 00000000..dac6ad97 --- /dev/null +++ b/docs/testScene/tuto_3.py @@ -0,0 +1,34 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "adagolodjo" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "October, 26 2021" + +from useful.header import addHeader, addSolverNode, addVisual +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase + +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, + nbSection=6, nbFrames=12, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., + beamLength=30) +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + + +def createScene(root_node): + addHeader(root_node) + root_node.gravity = [0, -9.81, 0.] + + solver_node = addSolverNode(root_node, name="solver_node") + + # create cosserat Beam + solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) + + return root_node \ No newline at end of file diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py new file mode 100644 index 00000000..41f31107 --- /dev/null +++ b/docs/testScene/tuto_4.py @@ -0,0 +1,125 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "adagolodjo" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "October, 26 2021" + +from useful.header import addHeader, addSolverNode, addVisual +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from math import sqrt +from splib3.numerics import Quat +import Sofa +from math import pi + +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, + nbSection=6, nbFrames=12, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=0.5, + beamLength=30) +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +force_null = [0., 0., 0., 0., 0., 0.] # N + + +class ForceController(Sofa.Core.Controller): + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, *args, **kwargs) + self.forceNode = kwargs['forceNode'] + self.frames = kwargs['frame_node'].FramesMO + self.force_type = kwargs['force_type'] + self.tip_controller = kwargs['tip_controller'] + + self.size = geoParams.nbFrames + self.applyForce = True + self.forceCoeff = 0. + self.theta = 0.1 + + def onAnimateEndEvent(self, event): + if self.applyForce: + self.forceCoeff += 0.01 + else: + self.forceCoeff -= 0.01 + + # choose the type of force + if self.force_type == 1 : + self.compute_force() + elif self.force_type == 2: + self.compute_orthogonal_force() + elif self.force_type == 3: + self.rotate_force() + + def compute_force(self): + with self.forceNode.forces.writeable() as force: + vec = [0., 0., 0., 0., self.forceCoeff/sqrt(2), self.forceCoeff/sqrt(2)] + for i, v in enumerate(vec): + force[0][i] = v + + + def compute_orthogonal_force(self): + position = self.frames.position[self.size] # get the last rigid of the cosserat frame + orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation + # Calculate the direction of the force in order to remain orthogonal to the x axis of the last frame of the beam. + with self.forceNode.forces.writeable() as force: + vec = orientation.rotate([0., self.forceCoeff*5.e-2, 0.]) + vec.normalize() + # print(f' The new vec is : {vec}') + for count in range(3): + force[0][count] = vec[count] + + def rotate_force(self): + if self.forceCoeff <= 100. * pi: + with self.tip_controller.position.writeable() as position: + last_frame = self.frames.position[self.size] + vec = Quat(last_frame[3], last_frame[4], last_frame[5], last_frame[6]) # get the orientation + + vec.rotateFromEuler([self.theta, 0., 0.]) # apply rotation arround x-axis + vec.normalize() + for i, v in enumerate(vec): + position[0][i+3] = v + + + def onKeypressedEvent(self, event): + key = event['key'] + if key == "+": + self.applyForce = True + elif key == "-": + self.applyForce = False + + +def createScene(root_node): + addHeader(root_node) + root_node.gravity = [0, 0., 0.] + + solver_node = addSolverNode(root_node, name="solver_node") + + # create cosserat Beam + cosserat_beam = solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) + cosserat_frames = cosserat_beam.cosseratFrame + + # this constance force is used only in the case we are doing force_type 1 or 2 + const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, indices=geoParams.nbFrames, + forces=force_null) + + # The endffectors is used only when force_type is 3 + #create a rigid body to control the end effector of the beam + tip_controller= root_node.addChild('tip_controller') + controller_state = tip_controller.addObject('MechanicalObject', template='Rigid3d', name="controlEndEffector", + showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], showObject=True) + + cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', + stiffness=1e8, angularStiffness=1e8, external_points=0, + external_rest_shape=controller_state.getLinkPath(), points=geoParams.nbFrames, template="Rigid3d") + + + solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, + tip_controller=controller_state)) + + + return root_node \ No newline at end of file diff --git a/docs/text/Advanced Topics and Future Work.md b/docs/text/Advanced Topics and Future Work.md new file mode 100644 index 00000000..f21fe29c --- /dev/null +++ b/docs/text/Advanced Topics and Future Work.md @@ -0,0 +1,48 @@ + +**Slide 1: Advanced Topics in Soft Robotics** + +- Title: Advanced Topics in Soft Robotics +- Content: + - Introduction to advanced topics and emerging areas in the field of soft robotics. + - Discussion of how soft robots are being used in various applications. + - Brief overview of the evolving challenges and opportunities in the domain. + +--- + +**Slide 2: Applications of Soft Robots** + +- Title: Applications of Soft Robots +- Content: + - Detailed exploration of practical applications where soft robots are making an impact. + - Examples of industries and domains benefiting from soft robotics (e.g., medical, automation, exploration). + - Emphasis on real-world scenarios where soft robots provide unique advantages. + +--- +**Slide 3: Future Work and Research Directions** + +- Title: Future Work and Research Directions +- Content: + - Presentation of potential research areas and directions for future work in soft robotics. + - Addressing unsolved challenges and open questions in the field. + - Discussion of how the combination of FEM and DCM can be extended and improved. +--- + +**Slide 4: Robotics in Education and Training** + +- Title: Robotics in Education and Training +- Content: + - Highlighting the role of educational and training programs in fostering expertise in soft robotics. + - Discussing how tutorials, like the one being prepared, can contribute to knowledge dissemination. + - Encouraging the audience to explore and contribute to the advancement of soft robotics. + +--- + +**Slide 5: Conclusion and Call to Action** + +- Title: Conclusion and Call to Action +- Content: + - Summarizing the key points discussed in the Advanced Topics and Future Work section. + - Inspiring the audience to take an active role in the field of soft robotics. + - Encouraging collaboration, innovation, and exploration of advanced topics. + - Thanking the audience for their attention and participation. +--- diff --git a/docs/text/Background Concepts.md b/docs/text/Background Concepts.md new file mode 100644 index 00000000..70c3b24b --- /dev/null +++ b/docs/text/Background Concepts.md @@ -0,0 +1,71 @@ + +**Slide 1: Background Concepts - Introduction** + +- **Slide Title:** Understanding the Fundamentals + +**Content:** +- Briefly introduce the "Background Concepts" section. +- Explain that to grasp the hybrid FEM and DCM approach, participants need to understand some fundamental concepts. +- Highlight the importance of a strong foundation in soft robotics and simulation techniques. + +--- +**Slide 2: Soft Robotics Principles** + +- **Slide Title:** Soft Robotics: Core Principles + +**Content:** +- Define the core principles of soft robotics, including compliance, flexibility, and adaptability. +- Use images and examples to illustrate these principles. +- Emphasize the fundamental differences between soft robots and traditional rigid robots. +--- +[[cosserat_python_scene]] + + +--- +||X|Y|Z| +|---|---|---|---| +|0|0|0|0| +|1|0|0|0| +|2|0|0|0| +|3|0|0|0| +|4|0|0|0| +|5|0|0|-2.35| + + +--- + +**Slide 3: Finite Element Methods (FEM)** + +- **Slide Title:** FEM: A Cornerstone of Soft Robot Simulation + +**Content:** +- Provide an overview of Finite Element Methods (FEM) and their role in simulating soft robots. +- Explain how FEM breaks down complex structures into smaller elements. +- Describe how FEM handles material properties, deformations, and forces. +- Showcase real-world applications of FEM in soft robotics. + +--- + +**Slide 4: Deformable Continuous Models (DCM)** + +- **Slide Title:** DCM: Modeling Cable-Driven Mechanisms + +**Content:** +- Define Deformable Continuous Models (DCM) and their significance in soft robotics. +- Explain how DCM focuses on modeling cables and deformations in soft robots. +- Discuss the advantages of DCM, such as the representation of cable-driven actuation. +- Share practical examples of DCM applications in soft robotics. + +--- + +**Slide 5: Bridging the Gap with Hybrid Modeling** + +- **Slide Title:** Hybrid Modeling: Combining FEM and DCM + +**Content:** +- Introduce the core concept of the tutorial: the integration of FEM and DCM for more accurate simulations. +- Explain the motivations behind this hybrid approach. +- Highlight the complementary nature of FEM and DCM in simulating different aspects of soft robots. +- Preview the real-world implications and benefits of this hybrid modeling strategy. + +--- diff --git a/docs/text/Brouillons.md b/docs/text/Brouillons.md new file mode 100644 index 00000000..7f988840 --- /dev/null +++ b/docs/text/Brouillons.md @@ -0,0 +1,40 @@ + +**Overview** +Remember to make the tutorial interactive, engage the participants, and provide opportunities for questions and discussions. You may also consider sharing the tutorial materials, code, and relevant resources with participants for further learning and experimentation. + +--- +**Partie 1:** +Each slide should be visually engaging with relevant images, diagrams, and minimal text. You can also use this opportunity to set the tone for the tutorial, making it clear that participants are embarking on an exciting journey into the world of soft robotics simulations. + +--- +**Partie 2:** +Each slide should be visually appealing, with clear and concise explanations. Make use of diagrams, images, and bullet points to enhance understanding. The aim is to provide participants with a solid foundation in the background concepts essential for grasping the hybrid FEM and DCM approach. + +--- + +Configuring the environment with SOFA and the Cosserat plugin is a critical step in your soft robotics simulation journey. This subsection serves as a foundation for the practical implementation of the hybrid FEM and DCM approach, allowing you to accurately model and simulate soft robots with complex deformations and interactions. + +--- +- Voir Deformable Continuous Models (DCM) + +--- + +These five slides will provide a detailed overview of the "Inverse Simulation" subsection, explaining the purpose, examples, computational aspects, and concluding remarks. This will help your audience understand the role of Inverse Simulation in soft robotics. + +--- +These five slides will provide a detailed overview of the "Model Convergence and Sensitivity Analysis" subsection, explaining the purpose, examples, implications, and concluding remarks. This will help your audience understand the significance of these analyses in soft robotics. + +--- + +These five slides will provide a detailed overview of advanced topics, potential applications, future research directions, and the role of education and training in soft robotics. It will also motivate the audience to engage in the field and contribute to its growth. + + +---- +These ten slides incorporate elements from the provided paper and database, delivering a detailed introduction to the hybrid framework, its motivations, objectives, and contributions. It also includes an overview of FEM, DCM, advanced topics, and future work in the realm of soft robotics. The presentation concludes by encouraging the audience to explore the full paper for further information. + +--- + + +These ten slides provide a detailed introduction to the hybrid framework, its motivation, objectives, and contributions, as well as an overview of FEM, DCM, and a glimpse of advanced topics and future work in the field of soft robotics. It concludes by motivating the audience to explore the paper's contents. + +--- diff --git a/docs/text/Complement.md b/docs/text/Complement.md new file mode 100644 index 00000000..faa8340b --- /dev/null +++ b/docs/text/Complement.md @@ -0,0 +1,82 @@ +Certainly, here is an updated version of the extended introduction section with ten detailed slides, incorporating elements from the provided paper and relevant content from my database: + +**Slide 1: Title and Introduction** + +- Title: Introduction to the Hybrid Framework for Soft Robotics +- Content: + - Introduce the audience to the paper, "Hybrid Framework for Real-Time Simulation of Soft Robots." + - Highlight the focus on combining Finite Element Method (FEM) and Discrete Cosserat Models (DCM) in soft robotics. + - Briefly mention the key points covered in the following slides. + +**Slide 2: Soft Robots in Modern Applications** + +- Title: Soft Robots in Modern Applications +- Content: + - Showcase real-world examples of soft robots' applications in various domains. + - Cite specific instances where soft robots have revolutionized medical, industrial, and exploration fields. + - Highlight the need for adaptable and safe robotic systems. + +**Slide 3: Challenges in Soft Robotics Modeling** + +- Title: Modeling Challenges in Soft Robotics +- Content: + - Explain the unique modeling challenges in soft robotics arising from deformable materials. + - Discuss the importance of real-time simulations for control and decision-making in such robots. + - Reference previous research in the field that addresses these challenges. + +**Slide 4: The Hybrid Approach's Promise** + +- Title: Promise of a Hybrid Framework +- Content: + - Detail the motivations behind developing a hybrid framework combining FEM and DCM. + - Present the advantages of using FEM for deformable materials and DCM for cable-driven robots. + - Provide examples of applications where the hybrid framework can excel. + +**Slide 5: Research Objectives and Contributions** + +- Title: Research Objectives and Contributions +- Content: + - Define the primary objectives of the research presented in the paper. + - Highlight the key contributions this paper offers to the field of soft robotics. + - Give the audience a glimpse of what to expect in the upcoming sections. + +**Slide 6: Paper Structure and Roadmap** + +- Title: Paper Structure and Roadmap +- Content: + - Offer an overview of the paper's structure, detailing each section's focus. + - Provide a roadmap to guide the audience through different aspects of the hybrid framework. + - Help the audience navigate and follow the presentation. + +**Slide 7: The Role of FEM in Soft Robotics** + +- Title: Finite Element Method in Soft Robotics +- Content: + - Explain the role of FEM in modeling deformable materials for soft robots. + - Cite examples of soft robot components where FEM has been effectively applied. + - Emphasize FEM's capacity to handle geometric non-linearity. + +**Slide 8: Introduction to DCM for Cable-Driven Robots** + +- Title: Discrete Cosserat Models for Cable-Driven Robots +- Content: + - Delve into the details of DCM and its suitability for modeling cable-driven robots in soft robotics. + - Showcase real-world applications of cable-driven soft robots. + - Explain how DCM handles reduced coordinates for modeling efficiency. + +**Slide 9: Advanced Topics and Future Directions** + +- Title: Advanced Topics and Future Directions +- Content: + - Provide a preview of advanced topics that will be discussed later in the paper. + - Offer insights into potential future research directions in the field of soft robotics. + - Encourage the audience to explore these exciting areas for further study. + +**Slide 10: Conclusion and Call to Action** + +- Title: Conclusion and Call to Action +- Content: + - Summarize the importance of the hybrid framework for soft robotics. + - Invite the audience to read the full paper for comprehensive insights into the topic. + - Express gratitude for the audience's attention and participation. + diff --git a/docs/text/Direct Simulation.md b/docs/text/Direct Simulation.md new file mode 100644 index 00000000..82af0d81 --- /dev/null +++ b/docs/text/Direct Simulation.md @@ -0,0 +1,51 @@ +--- +title: Introduction to Direct Simulation +--- + +--- +**Slide 1: Introduction to Direct Simulation** + +- Title: Introduction to Direct Simulation +- Content: + - Definition of Direct Simulation. + - Purpose of Direct Simulation in soft robotics. + - Importance of accurately modeling deformable robots in real-time. + - Overview of the content covered in this subsection. +--- +**Slide 2: Simulation Setup** + +- Title: Simulation Setup +- Content: + - Detailed explanation of the simulation environment setup. + - Mention of the software used (SOFA) and the Cosserat plugin. + - Steps for setting up SOFA and enabling the Cosserat plugin. + - Loading example scenes for practical experimentation. + +--- +**Slide 3: Soft Gripper Example** + +- Title: Soft Gripper Example +- Content: + - Introduction to the soft gripper used in the simulation. + - Discussion on its mechanical properties and complexity. + - Highlighting the integration of DCM to simulate the cables. + - Mention of friction and contact constraints for realistic interaction with a rigid object. +--- +**Slide 4: Observations and Analysis** + +- Title: Observations and Analysis +- Content: + - Presentation of the results from the direct simulation of the soft gripper. + - Discussion on the influence of cable properties (e.g., radius) on the gripper's deformation. + - Emphasis on the effect of using pre-bent rods for manipulation. + - Visualization of stress levels in cables and materials. +--- +**Slide 5: Conclusions from Direct Simulation** + +- Title: Conclusions from Direct Simulation +- Content: + - Summarizing the key findings from the direct simulation experiments. + - Emphasis on the importance of accurately modeling cables and their interaction with deformable structures. + - Relating the results to the overall objective of combining FEM and DCM for soft robotics. + - Transition to the next subsection on "Inverse Simulation" and the broader tutorial structure. +--- diff --git a/docs/text/Introduction.md b/docs/text/Introduction.md new file mode 100644 index 00000000..6dd03e7c --- /dev/null +++ b/docs/text/Introduction.md @@ -0,0 +1,62 @@ +--- +tutorial: Introduction +tags: + - tuto/cosserat +cssclass: + - dashboard +--- +## Introduction to Soft Robotics (SR) + +- Soft robotics is an emerging and innovative field of robotics +- Focuses on the design and development of robots made from : + - *Flexible*, + - *Deformable*, + - *Compliant materials*. +--- +## Introduction to Soft Robotics (SR) +- Numerous advantages + - *Adaptability* : Their ability to deform and adapt to their environment + - *Safety* : Ideal for interactions with humans, delicate objects, or unstructured surroundings + - *Versatility* : Various applications + +--- +## **Key Applications** + +- *Healthcare* : The gentle and non-invasive nature of SR is necessary +- *Industrial automation* : The high [Compliance](../../../Soft_Robot/Compliance.md), reduces the risk of damage during interactions with products +- *Search and rescue* : they can navigate through tight spaces and uneven terrains +- *Space exploration*, and *extreme environments* + +--- +## **Challenges in Soft Robotics** + +- *Modeling* : due to deformable materials +- [*Control*](../../../Soft_Robot/kinematics_dynamics_control.md) : due to the non-linear, multi-body dynamics of deformable materials +- [*Multi-dimension*](../../../../../../Projects/ANR/brainStormingANR2023.md) : due to a wide range of shape, volume (3D), surface (2D) and cable (1D) +- [*Multi-physics*](../../../../../../Projects/ANR/RobotMulti-physics.md) : due a wide range of physical behaviors, including mechanical deformation, thermal effects, electrical responses, + +--- +## **Challenges in Soft Robotics** + +- Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. +(To go further on the introduction of deformable robotics ⇾ [Introduction_General](../../../Soft_Robot/Introduction_General.md) ) + +--- +## [FEM and DCM](../../_docs/DCM_FEM.md) + +- *FEM's Material Modeling*: FEM excels at modeling the deformations and stress distributions in complex materials, including soft and deformable ones. It considers the local behavior of materials, making it more accurate for understanding the mechanical properties of soft robots. +- *Cosserat theory's Beam-Like Modeling*: DCM, on the other hand, is suitable for modeling the overall shape and bending of structures, making it a natural choice for cables, rods, and flexible elements in soft robots. + + +--- +## Motivation for the combination of the two models + +- *Combined Accuracy*: By combining FEM and DCM, you can leverage the strengths of both methods. FEM provides fine-grained material modeling, while DCM captures the shape and motion of deformable elements accurately. This leads to a more realistic representation of the entire robot's behavior. + +- *Unified Simulation Framework*:A combined FEM-DCM framework creates a unified simulation environment that can model both the deformable body of the robot (using FEM) and the actuation components (using DCM). This simplifies simulation setup and control algorithms. + +--- + +--- + +[[Complement]] \ No newline at end of file diff --git a/docs/text/Inverse Simulation.md b/docs/text/Inverse Simulation.md new file mode 100644 index 00000000..3e8b6f27 --- /dev/null +++ b/docs/text/Inverse Simulation.md @@ -0,0 +1,46 @@ + +**Slide 1: Introduction to Inverse Simulation** + +- Title: Introduction to Inverse Simulation +- Content: + - Definition and purpose of Inverse Simulation in the context of soft robotics. + - Highlighting the role of Inverse Simulation in controlling deformable robots. + - Setting the stage for understanding how to determine cable actuation based on desired end-effector motion. +--- + +**Slide 2: Soft Finger Inverse Simulation** + +- Title: Soft Finger Inverse Simulation +- Content: + - Introduction to the soft finger model used for Inverse Simulation. + - Discussion on the complexity of the problem. + - Overview of the inputs and unknowns in the Inverse Simulation. + - Mention of constraints, including sliding constraints between DCM cable model and FEM silicone finger model. +--- +**Slide 3: Soft Tentacle Inverse Simulation** + +- Title: Soft Tentacle Inverse Simulation +- Content: + - Presentation of the soft tentacle robot used as an example for Inverse Simulation. + - Description of the scenario where the effector follows a predefined trajectory. + - Explanation of cable actuation to achieve desired end-effector motion. + - Highlighting the importance of controlling multiple cables in the inverse problem. +--- +**Slide 4: Timing and Computational Considerations** + +- Title: Timing and Computational Considerations +- Content: + - Discussing the computational resources required for Inverse Simulation. + - Mentioning the hardware used for the simulations. + - Providing a table with details on the number of elements, constraints, and computational time for each simulation scenario. + - Comparing the computational time between direct and inverse simulations. +--- +**Slide 5: Conclusions from Inverse Simulation** + +- Title: Conclusions from Inverse Simulation +- Content: + - Summarizing the key takeaways from the Inverse Simulation experiments. + - Emphasizing the challenges and complexities of solving inverse problems for deformable robots. + - Relating the results to the overall objective of combining FEM and DCM for soft robotics. + - Transition to the conclusion of the tutorial and future work. +--- diff --git a/docs/text/Model Convergence and Sensitivity Analysis.md b/docs/text/Model Convergence and Sensitivity Analysis.md new file mode 100644 index 00000000..61d482a7 --- /dev/null +++ b/docs/text/Model Convergence and Sensitivity Analysis.md @@ -0,0 +1,51 @@ + + +**Slide 1: Introduction to Model Convergence and Sensitivity Analysis** + +- Title: Introduction to Model Convergence and Sensitivity Analysis +- Content: + - Definition and purpose of Model Convergence and Sensitivity Analysis in the context of soft robotics. + - Explanation of why it's important to assess the convergence of the model and analyze its sensitivity. + - Setting the stage for understanding how variations in model parameters impact the behavior of deformable robots. + +--- + +**Slide 2: Assessing Model Convergence** + +- Title: Assessing Model Convergence +- Content: + - Discussing the concept of model convergence in the context of deformable robots. + - Explanation of how the model's behavior changes with varying numbers of sections. + - Presenting a specific example (soft finger) and its convergence with different numbers of cable sections. + - Highlighting the role of section numbers in ensuring a converged model. +--- +**Slide 3: Analyzing Model Sensitivity** + +- Title: Analyzing Model Sensitivity +- Content: + - Introduction to model sensitivity analysis for deformable robots. + - Explanation of how variations in parameters affect the model's response. + - Presenting results of sensitivity analysis in the context of cable radius. + - Discussing the observed impact on the deformation of the silicone finger with varying cable radii. + +--- + +**Slide 4: Implications for Design and Control** + +- Title: Implications for Design and Control +- Content: + - Discussing the practical implications of model convergence and sensitivity analysis. + - Explaining how these analyses can inform the design of soft robotic systems. + - Emphasizing the importance of parameter choices in controlling deformable robots. + - Providing insights into how these findings can be applied in real-world soft robotics applications. + +--- +**Slide 5: Conclusions from Model Convergence and Sensitivity Analysis** + +- Title: Conclusions from Model Convergence and Sensitivity Analysis +- Content: + - Summarizing the key takeaways from the Model Convergence and Sensitivity Analysis. + - Relating the results to the overall objective of combining FEM and DCM for soft robotics. + - Highlighting the significance of understanding convergence and sensitivity in modeling. + - Transitioning to the conclusion of the tutorial and future work. +--- diff --git a/docs/text/Numerics.md b/docs/text/Numerics.md new file mode 100644 index 00000000..ebef7763 --- /dev/null +++ b/docs/text/Numerics.md @@ -0,0 +1,10 @@ + +### Spatial Discretization + +### Time Discretization + +### Reduce to Global State + +### Global to Reduce State + +### Boundary conditions and interaction forces \ No newline at end of file diff --git a/docs/text/Setting up the Environment.md b/docs/text/Setting up the Environment.md new file mode 100644 index 00000000..75c845c4 --- /dev/null +++ b/docs/text/Setting up the Environment.md @@ -0,0 +1,232 @@ +--- +cssclasses: + - dashboard + - multi-column + - two-column-list +tags: + - tuto/cosserat +--- + + +**Introduction to SOFA** +- Have SOFA installed on your machine +- Install Cosserat plugin + - In Tree + - Out Tree + +--- + +**Step 1: Installing SOFA** + +Before you begin with the specific Cosserat plugin, you need to install SOFA. Follow these steps: + +1. Go to the official SOFA website (https://www.sofa-framework.org/) to download the latest version. +2. Choose the appropriate version for your operating system (Windows, Linux, or macOS). +3. Follow the installation instructions for your OS. Typically, this involves extracting the downloaded archive and setting environment variables. +--- + +**Step 2: Setting Up the Cosserat Plugin** + +Now, we'll dive into the essential part – configuring the Cosserat plugin within SOFA. +1. **Create plugins folder:** + - Create folder externalPlugins + - **sofa** + - ├── **src** + - ├── **build** + - ├── **externalPlugins** + +--- +2. **Obtaining the Plugin:** +- GitHub : https://github.com/SofaDefrost/Cosserat + - Download the plugin : + - git clone git@github.com:SofaDefrost/Cosserat.git (if you are using ssh-key) + - git clone https://github.com/SofaDefrost/Cosserat.git + - or Download the **Zip** +--- + +**3. Add *CMakeList.txt* file inside the *externalPlugin* folder** +```Cmake + cmake_minimum_required(VERSION 3.1) + sofa_find_package(SofaFramework) + + sofa_add_subdirectory(plugin SofaPython3 SofaPython3 ON) # If you want to use python + sofa_add_subdirectory(plugin STLIB STLIB ON) # If you want to use python & Cosserat prefabs + sofa_add_subdirectory(plugin Cosserat Cosserat ON) +``` + +--- + +**4. Activating the Plugin:** To activate the Cosserat plugin, follow these steps: + +- Open your terminal and go to SOFA's **build-directory** + - run + ```bash + cmake-gui . + ``` + - In the *Search* bar, type **external**, + - In $SOFA\_EXTERNAL\_DIRECTORIES$ + - Fill in the empty box with: + - **path-to-cosserat-directory** + - Find the Cosserat plugin and enable it +--- + +5. **First Cosserat Scene: *tuto_1.py*** + - As said previously, this component is based on the PCS (Piece-wise Constant Strain) formulation. + ![400](Pasted%20image%2020231102173536.png) +--- + +- [ ] 3 sections with 7 frames +- [ ] **Goals** : + - how to create a basic scene with the cosserat plugin + - It is important to note the difference between : + - **section** and **frames** + - **section** and **cross-section** + - The notion of force-field : here **BeamHookeLawForceField** + - The notion of mapping: here **DiscreteCosseratMapping** + - Functions: **apply, applyJ**, **applyJT** for forces and **ApplyJ^T** for constraints +--- +Start with the base +![500](images/exemple_rigid_translation.png) + +--- + +- The beam is always constructed along the x-axis +```python + def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", position="0 0 0 0 0 0. 1", showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", points="0", template="Rigid3d") + return rigid_base_node +``` + +--- +- Add Cosserat **Reduced coordinates** states (torsion and bending along y and z-axis) +- Add **BeamHookeLawForceField** based on the Hooke's Law +```python +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', length=list_sections_length, radius=2., youngModulus=1.e4, poissonRatio=0.4) + return cosserat_coordinate_node +``` + +--- +- Parameters : +```python +list_sections_length = [10, 10, 10] +cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending +bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] +``` +--- +- **BeamHookeLawForceField** + - **Force Computation**: The `addForce` method calculates and adds the forces acting on the beams. It uses Hooke's law to compute the forces based on the deformation of the beams and their properties. The computed forces are then stored in the `f` variable. +--- +- **Derivative of Force Computation**: The `addDForce` method computes the derivative of the forces with respect to the deformation. This is used for stiffness matrix calculations in the context of finite element simulations. + +--- + +- **Stiffness Matrix Computation**: The `addKToMatrix` method is responsible for adding the stiffness matrix to the global matrix. This is used in FEM to represent the stiffness of the entire system. +--- +- Add Mapped coordinates (frames) to the scene + - **Mapping** between **Reduced coordinates** (Cosserat's state) and Global cordinates (Sofa state). + - Frames are multi-mapped (under Cosserat state and rigid base) +![400](../images/CosseratMapping.png) +--- + +```python +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showIndices=0., showObject=0, showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs, name='cosseratMapping', input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(), output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node +``` +--- +- The notion of mapping: here **DiscreteCosseratMapping** + - **apply** : It calculates how the positions of elements in the input models (deformations and base) are transformed to the output model (rigid frames). The function applies the mapping to these input positions and updates the output frames accordingly. + - **applyJ** : compute the Jacobian matrix for the mapping operation. How small changes in input velocity (in this case, deformations) affect small changes in output velocity (in this case, the rigid frames). +--- + +- **applyJT force** : It updates forces in reduced coordinate based on forces in global coordinate. +- **applyJT Constraint** : It updates constraints in reduced coordinate based on constraints in global coordinate. + +---- +- [ ] Example 2: **tuto_2.py** + - [ ] script for automating sections and frames + - [ ] **Goal**: show the role of the number of sections on the overall deformation + - [ ] Example: + - [ ] 6 sections; 32 frames: $b_y=0.2$ on the last bending_state + - [ ] 12 sections 32 frames: $b_y=0.2$ on the last bending_state + - [ ] 6 sections 6 frames: all variables $b_y=0.2$ + - [ ] Change to frames = 12/24/32 + - [ ] Shows that we have a smoother curvature than previously while emphasizing the fact that there is rather a geometry impact, but not a physical one. +---- + +- [ ] Scene **![tuto_3](../testScene/tuto_3.py)** + - [ ] Use the $CosseratBase$ Python class and $prefabs$ +```python +def createScene(root_node): + addHeader(root_node) + root_node.gravity = [0, -9.81, 0.] + solver_node = addSolverNode(root_node, name="solver_node") + + # create cosserat Beam + solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) + return root_node +``` +--- +- [ ] Uses also python $dataclass$ +```python +- geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1,nbSection=6, nbFrames=12, buildCollisionModel=0) +- physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., beamLength=30) +- simuParams = SimulationParameters() +- Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +``` +--- +- [ ] Scene ![tuto_4](../testScene/tuto_4.py) + - [ ] Force type 1 + - [ ] Force type 2 + - [ ] Force type 3 + +--- + +- [ ] Une scène avec contrainte +- [ ] Celle de l’actuation du doigt **[tuto7.py](http://tuto7.py)** +--- + +- [ ] Celles des trois doigts qui soulèvent le cube ****[tuto8.py](http://tuto8.py)*** + +---- + +- [ ] **Une scène pre-bent, s'inspire de la scène Flavie **[tuto9.py](http://tuto9.py)** + + +--- + +**Step 3: Configuring Scene Files** + +Now that you have SOFA and the Cosserat plugin ready, you need to configure your simulation scene files. These XML-based files define the simulation environment, including the soft robot model, forces, constraints, and interaction with the environment. + +--- + +1. **Creating a Scene File:** You can start by creating a new XML scene file. This file will serve as the blueprint for your simulation. You can use a text editor to create and modify it. +--- + +2. **Defining Soft Robot Models:** Within the scene file, you must define your soft robot model. You can specify its geometry, material properties, and the use of Cosserat models to represent deformable structures. +--- +3. **Integrating Cosserat Components:** To utilize Cosserat models in your simulation, you need to incorporate the appropriate components from the Cosserat plugin. These components include the Cosserat beam elements, which are crucial for modeling cables and rods. +--- +4. **Adding Constraints:** Depending on your simulation, you might need to introduce constraints that describe the interaction between the robot and its environment. This is also an essential part of configuring the scene. +--- +5. **Configuring Simulation Parameters:** The scene file allows you to set various simulation parameters, such as time steps, numerical solvers, and visualization options. + +--- + +**Step 4: Running Simulations** + +After configuring your scene file, you can run simulations to see how the soft robot behaves. SOFA provides real-time visualization, making it easier to analyze and refine your models. You can interact with the simulated robot and monitor its performance as the simulation progresses. + +--- diff --git a/docs/text/Soft_robot_intro.md b/docs/text/Soft_robot_intro.md new file mode 100644 index 00000000..c21abe9e --- /dev/null +++ b/docs/text/Soft_robot_intro.md @@ -0,0 +1,69 @@ +--- +title: Introduction to Soft Robotics +--- + + +**Slide 1: Soft Robotics - A New Frontier** + +- Content: + - Soft robotics is an emerging and innovative field of robotics that focuses on the design and development of robots made from flexible, deformable, and compliant materials. + - Soft robotics is a cutting-edge field that focuses on the design and development of robots using compliant and deformable materials. + - These robots are in stark contrast to traditional rigid robots and offer numerous advantages, including adaptability, safety, and versatility in various applications. + +--- +**Slide 2: Characteristics of Soft Robots** + +- Content: + - Soft robots are characterized by their ability to deform and adapt to their environment, making them ideal for interactions with humans, delicate objects, or unstructured surroundings. + - Their compliance and flexibility are key attributes that enable them to handle complex tasks. + +--- + +**Slide 3: Applications in Healthcare** + +- Content: + - Soft robotics has found significant applications in the healthcare industry, where the gentle and non-invasive nature of soft robots is leveraged for tasks such as minimally invasive surgery and rehabilitation. + - Examples include surgical robots that can navigate delicate tissues with precision. +--- + +**Slide 4: Industrial Automation** + +- Content: + - In industrial automation, soft robots are increasingly used for tasks such as pick-and-place operations, packaging, and assembly. + - The compliance of soft robots reduces the risk of damage during interactions with products. +--- +**Slide 5: Search and Rescue Operations** + +- Content: + - Soft robots are being explored for search and rescue operations, where they can navigate through tight spaces and uneven terrains. + - These robots can be vital in disaster-stricken areas to locate survivors. + +**Slide 6: Space Exploration and Extreme Environments** + +- Content: + - Soft robots have potential applications in space exploration due to their ability to adapt to different environments. + - They can also be used in extreme environments on Earth, such as deep-sea exploration or nuclear decommissioning. + +**Slide 7: Challenges in Soft Robotics** + +- Content: + - Despite their promise, soft robots present unique challenges in modeling, control, and actuation. + - Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. + +**Slide 8: Interdisciplinary Nature** + +- Content: + - Soft robotics is inherently interdisciplinary, drawing from fields like materials science, biomechanics, and control theory. + - Collaboration between experts from different domains is essential to advance the field. + +**Slide 9: Future Directions** + +- Content: + - The field of soft robotics continues to evolve, with ongoing research to overcome challenges and expand applications. + - Future directions include advancements in materials, control strategies, and the integration of soft robots into everyday life. + +**Slide 10: Conclusion** + +- Content: + - In conclusion, soft robotics represents a paradigm shift in the field of robotics, offering exciting possibilities for various industries. + - As technology advances and interdisciplinary collaboration thrives, soft robots are poised to transform the way we interact with machines and the world around us. \ No newline at end of file diff --git a/docs/text/Theory.md b/docs/text/Theory.md new file mode 100644 index 00000000..d40f71dd --- /dev/null +++ b/docs/text/Theory.md @@ -0,0 +1,40 @@ +--- +marp: +tags: + - tuto/cosserat +cssclasses: + - multi-column + - two-column-list + - two-columns +--- + +Solide Works +![](Pasted%20image%2020231025171449.png) + +--- + +![[Learning/Learning&Development/Formation/cosserat/docs/text/Untitled Diagram.svg]] + +--- + +#### Mathematical Description of Cosserat Rods + +##### Cosserat differential Kinematics + +>[!blank-container] +>- Configuration $g= \begin{pmatrix} \mathcal{R} & u \\ 0 & 1 \end{pmatrix} ∈SE(3)$ +>- Velocity $\eta(s,t) =\begin{align}y &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ +>- Strain $\xi(s,t) =\begin{align}y &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ + +--- +#### Reference Frames + +--- + +### Conservation of Momentum + +--- +### Linear Elasticity + + +--- \ No newline at end of file diff --git a/docs/text/cosserat_python_scene.md b/docs/text/cosserat_python_scene.md new file mode 100644 index 00000000..c27d84ae --- /dev/null +++ b/docs/text/cosserat_python_scene.md @@ -0,0 +1,137 @@ +# Principes de base + +<aside> 💡 _Toutes les informations concernant le logiciel SOFA peuvent être retrouver sur le site : [SOFA – Documentation (sofa-framework.org)](https://www.sofa-framework.org/community/doc/), pour y comprendre le concept, les principes, ... ._ +</aside> + +## Théorie de Cosserat + +Cosserat sur base sur la notion de _Piecewise Constant Strain_. Elle repose sur le fait d’estimer la **deformation** de manière très grossière, comme ci-dessous. + +![PCS.png](images/PCS.png) + +### Base rigide + +![rigidbase.png](images/rigidbase.png) + +Comme son nom l’indique ici il s’agit de la base de la poutre. Il s’agit d’un repère qui pouvant être assigné à une translation et/ou rotations désirée, et qui résultera d’une position finale. A noter, que le repère est toujours associé à un ressort afin d’être fixe dans le repère global de SOFA. + +$$ Rotation =[x , y, z] $$ + +$$ Translation = [x,y,z] $$ + +$$ Position = [x , y, z, xq, yq, zq, wq] $$ + +### Exemple - Base rigide + +![exemple rigid translation.png](images/exemple_rigid_translation.png) + +$$ Rotation =[0 , 0, 0] $$ + +$$ Translation = [0,1,0] $$ + +$$ Position = [0 , 1, 0, 0, 0, 0, 1] $$ + +### Section + +![noeud curv.png](images/noeud_curv.png) + +Les sections sont situées dans le repère local de Cosserat. Une section représente la distance entre deux nœuds : + +$$ L0 /L1 = Section 1 $$ + +$$ L1/L2 = Section 2 $$ + +Une cross-section est une partie de la poutre qu’on vient couper de manière transversale. De manière générale, on suppose que les cross sections sont rondes et ont le même rayon tout le long de la poutre. Mais il est possible que la forme de la poutre ne soit pas circulaire mais rectangulaire, et que le rayon change d’une distance à une autre. Les coordonnées des sections et des noeuds se retrouvent dans un tableau nommé “curv_abs_input” (:Curviligne abscisse inputs). + +<aside> ❗ _**Attention à ne pas confondre : section et cross-section. Ceux ne sont pas les mêmes notions**_ + +</aside> + +Il est possible d’appliquer une déformation à partir d’un certain nœud, les deux déformations possibles sont la torsion (selon x), et la flexion (selon y ou z). + +$$ positionS = [x,y,z] $$ + +$$ Flexion = -+(1/LenghtSection) * pi $$ + +Pi : Angle de rotation + +(1/LengthSection) : Vecteur unitaire (normalisation) + +-/+ : Sens de rotation + +### Exemple - Section (1) + +Pour une poutre de longueur de 8cm avec un nombre de sections de 6 on a : + +![exemple curv abs input.png](images/exemple_curv_abs_input.png) + +**Tableau curv_abs_input :** + +![Untitled](images/Untitled.png) + +### Exemple - Section (2) + +Pour une poutre de longueur de 8cm avec un nombre de sections de 6 on a : + +![position 90degres.png](images/position_90degres.png) + +**Tableau curv_abs_input :** + +||X|Y|Z| +|---|---|---|---| +|0|0|0|0| +|1|0|0|0| +|2|0|0|0| +|3|0|0|0| +|4|0|0|0| +|5|0|0|-2.35| + +### Frame + +![frame1.png](images/frame1.png) + +La frame est représenté dans le repère locale de Cosserat, puis elle est intégrée dans le repère global de SOFA. Une frame est représentée comme les bases rigides, on retrouve les coordonnées de translation et rotation : + +$$ R :[x , y, z, 0, 0, 0, 1] $$ + +Les frames ne sont pas obligatoirement à équidistances les unes par rapport aux autres. Il est possible de concentrer un certain nombre de frames à un certain endroit, ce qui permet une rapidité de calcul sur l’endroit d’étude désirée. + +<aside> 💡 Plus le nombre de frame augmentent plus la précision de la courbe sera haute. ****** + +</aside> + +## Plugin Cosserat - SOFA + +### RigidBases + +- MechanicalObject + + - Coordonnées du système : + + $$ R :[x , y, z, 0, 0, 0, 1] $$ + +- Spring + + - Rigidité + - Rigidité angulaire + +### CosseratCoordinate + +- MechanicalObject + - Nombre de sections + - Taille totale de la poutre +- BeamHookLaw + - Forme de la cross-section + - Taille de la section + - Rayon + +### CosseratFrame + +- MechanicalObject + - Nombre de frame + - Taille totale de la poutre +- CosseratMapping + - MechanicalObject de RigidBases + - MechanicalObject de Cosserat Coordinate + - Curv in + - Curv out \ No newline at end of file diff --git a/docs/text/cosserat_tutorial.md b/docs/text/cosserat_tutorial.md new file mode 120000 index 00000000..c8e94902 --- /dev/null +++ b/docs/text/cosserat_tutorial.md @@ -0,0 +1 @@ +/Users/yadagolo/travail/plugin/plugin.Cosserat/examples/python3/tutorial/tutorial.md \ No newline at end of file diff --git a/docs/text/tutorial.md b/docs/text/tutorial.md new file mode 100644 index 00000000..6732d91c --- /dev/null +++ b/docs/text/tutorial.md @@ -0,0 +1,104 @@ +--- +title: DCM-FEM for Soft-Robot modeling Tutorial +tags: + - tutorial +Audience: Researchers, engineers, and students interested in soft robotics and the simulation of deformable robots. +Duration: This tutorial can vary in duration based on the depth and complexity of the material, but a typical plan could span 2-4 hours. +Prerequisites: Participants should have a basic understanding of robotics, mechanics, and computer simulations. Knowledge of finite element methods (FEM) and rigid body dynamics can be helpful. +cssclasses: + - dashboard +--- + +_Welcome to this tutorial on SOFA-Cosserat Plugin._ + +_Outline of what participants can expect to learn during this tutorial ?_ + +[Formation plugin : Cosserat - CodiMD](https://notes.inria.fr/gcfuFPDYSeeAlG4gzfDJwA#) + +--- +# Tutorial Roadmap + +- What to Expect ? + - Provide an overview of the tutorial's structure. + - Sections and topics we'll cover during the tutorial. +- Ask questions and be actively engage throughout this tutorial + - The first time I am doing this, so I really need your feedback + +--- + +## [Introduction](Introduction.md) + +- 🗄️Briefly introduce the field of soft robotics +- The motivation for combining FEM and DCM models. + +--- +## [Background Concepts](Background%20Concepts.md) +- An overview of Discrete Cosserat Model (DCM) and their relevance in soft robotics. +- Finite Element Methods (FEM) and their use in simulating deformable structures ? +- The concept of compliance matrices and their role in soft robot modeling ? + +--- + +## [Setting up the Environment](Setting%20up%20the%20Environment.md) +- The software tools and libraries used (SOFA, **Cosserat** plugin). +- Instructions for setting up the simulation environment. +- [cosserat_python_scene](cosserat_python_scene.md) + +--- +## [Direct Simulation](Direct%20Simulation.md) + - How to + - Build the DCM scene ? + - Integrate it with FEM for the soft body ? + - The direct simulation of a soft robot (e.g., the gripper example from the paper). + - The role of constraints, friction, and contact forces. + +--- + +## [Inverse Simulation](Inverse%20Simulation.md) + - Demonstrate an inverse simulation for soft robots (e.g., using the soft finger or tentacle as examples). + - Explain how to compute actuation values to achieve desired end-effector positions. + - Discuss the handling of sliding constraints in the inverse problem. + +--- + +## [Model Convergence and Sensitivity Analysis](Model%20Convergence%20and%20Sensitivity%20Analysis.md) + - Here we will share insights on how to evaluate the convergence of your model with varying parameters + - e.g., number of sections defining a cable + - Discuss sensitivity to material properties and other simulation parameters. + +--- + +## [Advanced Topics and Future Work](Advanced%20Topics%20and%20Future%20Work.md) + - Explore potential applications of your method in soft robot design. + - Discuss the ongoing and future research in this field, including real-world experiments and stress validation on cables. + +--- + +## **8. Performance Optimization** + - How to **optimize the computation speed**, potentially using **parallelization**, model **order reduction**, or **recursive algorithms** for DCM. + +--- + +## **9. Conclusion and Q&A** + - Summarize key takeaways from the tutorial. + - Open the floor for questions and discussions. + +--- + +## **10. Practical Hands-On Session (Optional)** + - If feasible, you can provide participants with exercises or hands-on practice to apply the concepts learned. + +--- + +## 11. **Materials:** +- Presentation slides (see GitHub Repo) +- Repo folder tutorials. +- Code examples and simulations on the Repo/example. +- Reference: + - Paper RAL-SoRo : + - Paper (Féderico) : + - Paper (Flavie) : +- Q&A session for participant engagement. +- Feedback : direct and mails + +--- \ No newline at end of file diff --git a/examples/python3/__init__.py b/examples/python3/__init__.py index f079f1ef..9dcf5866 100644 --- a/examples/python3/__init__.py +++ b/examples/python3/__init__.py @@ -13,4 +13,4 @@ """ -__all__ = ["cosserat","useful", "actuators"] +__all__ = ["cosserat", "useful", "actuators"] diff --git a/examples/python3/tutorial/tutorial.md b/examples/python3/tutorial/tutorial.md index 80b5897c..18741b1a 100644 --- a/examples/python3/tutorial/tutorial.md +++ b/examples/python3/tutorial/tutorial.md @@ -1,33 +1,14 @@ -### Mathematical Description of Cosserat Rods - - -### Reference Frames - -### Conservation of Momentum - -### Linear Elasticity - - -## Numerics - -### Spatial Discretization - -### Time Discretization - -### Reduce to Global State - -### Global to Reduce State - -### Boundary conditions and interaction forces +A step-by-step tutorial for understanding how to model a 1D object using the Cosserat plugin within the SOFA framework. +## Modeling 1D Objects with Cosserat Theory in SOFA** +[Theory](Theory.md) +[Numerics](docs/text/Numerics.md) -A step-by-step tutorial for understanding how to model a 1D object using the Cosserat plugin within the SOFA framework. -# Modeling 1D Objects with Cosserat Theory in SOFA** **Introduction:** In this tutorial, we will learn how to create a 1D object model using Cosserat Theory within the SOFA framework. This model is useful for simulating various physical systems, such as beams or rods. We'll cover the essential components and parameters needed to set up the model. diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index 67bcc966..65ad55fa 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -58,7 +58,9 @@ def addHeader(parentNode, multithreading=False, inverse=False, isConstrained=Fal "Sofa.GL.Component.Rendering3D", # Needed to use components OglGrid, OglModel "Sofa.GUI.Component", "Sofa.Component.Collision.Geometry", "Sofa.Component.LinearSolver.Direct", "Sofa.Component.Mapping.Linear", "Sofa.Component.MechanicalLoad", - "Sofa.Component.StateContainer", 'Sofa.Component.ODESolver.Backward' + 'Sofa.Component.Engine.Select', 'Sofa.Component.SolidMechanics.FEM.Elastic', + "Sofa.Component.StateContainer", 'Sofa.Component.ODESolver.Backward', + 'Sofa.Component.SolidMechanics.FEM.HyperElastic' ]) settings.addObject('BackgroundSetting', color=[1, 1, 1, 1]) @@ -129,7 +131,6 @@ def addSolverNode(node, name='solverNode', template='CompressedRowSparseMatrixd' solverNode = node.addChild(name) solverNode.addObject('EulerImplicitSolver', firstOrder=firstOrder, rayleighStiffness=rayleighStiffness, rayleighMass=rayleighMass) - solverNode.addObject('GenericConstraintSolver', tolerance=1e-5, maxIterations=5e2) if iterative: solverNode.addObject('CGLinearSolver', name='Solver', template=template) else: diff --git a/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h b/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h index fef8e2d3..ce2663af 100644 --- a/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h +++ b/src/Cosserat/constraint/CosseratNeedleSlidingConstraint.h @@ -109,7 +109,7 @@ namespace sofa::component::constraintset j.multTransposeBaseVector(res, lambda); // lambda is a vector of scalar value so block size is one. } - void storeLambda(const ConstraintParams */*cParams*/, MultiVecDerivId res, const sofa::linearalgebra::BaseVector *lambda) override + void storeLambda(const ConstraintParams */*cParams*/, MultiVecDerivId /*res*/, const sofa::linearalgebra::BaseVector */*lambda*/) override { // if (cParams) // { diff --git a/src/Cosserat/constraint/QPSlidingConstraint.inl b/src/Cosserat/constraint/QPSlidingConstraint.inl index 3defedf8..d45b7a34 100644 --- a/src/Cosserat/constraint/QPSlidingConstraint.inl +++ b/src/Cosserat/constraint/QPSlidingConstraint.inl @@ -206,7 +206,7 @@ void QPSlidingConstraint<DataTypes>::getConstraintResolution(const ConstraintPar { ReadAccessor<Data<VecCoord>> positions = m_state->readPositions(); // std::cout << "The position size is : " << positions.size()<< std::endl; - double imposedValue= 1.0; + // double imposedValue = 1.0; for (size_t i = 0; i < positions.size(); i++){ resTab[offset++] = new BilateralConstraintResolution(); @@ -220,7 +220,7 @@ void QPSlidingConstraint<DataTypes>::getConstraintResolution(const ConstraintPar template<class DataTypes> -void QPSlidingConstraint<DataTypes>::draw(const VisualParams* vparams) +void QPSlidingConstraint<DataTypes>::draw(const VisualParams* /*vparams*/) { if(d_componentState.getValue() != ComponentState::Valid) return ; diff --git a/src/Cosserat/engine/PointsManager.h b/src/Cosserat/engine/PointsManager.h index 4ebcc49b..6d9f7353 100755 --- a/src/Cosserat/engine/PointsManager.h +++ b/src/Cosserat/engine/PointsManager.h @@ -43,8 +43,8 @@ namespace sofa::core::behavior PointSetTopologyModifier *m_modifier; core::behavior::MechanicalState<DataTypes> *m_beam; - void init(); - void handleEvent(sofa::core::objectmodel::Event *event); + void init() override; + void handleEvent(sofa::core::objectmodel::Event *event) override; // void draw(const core::visual::VisualParams *vparams); void addNewPointToState(); diff --git a/src/Cosserat/engine/PointsManager.inl b/src/Cosserat/engine/PointsManager.inl index 71754de8..50c03e08 100755 --- a/src/Cosserat/engine/PointsManager.inl +++ b/src/Cosserat/engine/PointsManager.inl @@ -74,10 +74,9 @@ namespace sofa::core::behavior { helper::WriteAccessor<Data<VecCoord>> x = *this->getMstate()->write(core::VecCoordId::position()); helper::WriteAccessor<Data<VecCoord>> xfree = *this->getMstate()->write(core::VecCoordId::freePosition()); - const helper::ReadAccessor<Data<VecCoord>> &beam = m_beam->readPositions(); + unsigned nbPoints = this->getTopology()->getNbPoints(); // do not take the last point because there is a bug - size_t beamSz = beam.size(); sofa::type::vector<unsigned int> Indices; if (nbPoints > 0) { diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.inl b/src/Cosserat/forcefield/BeamHookeLawForceField.inl index 5acf74a9..4efb7588 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.inl @@ -93,45 +93,60 @@ namespace sofa::component::forcefield reinit(); } + /*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties + related to the cross-section of the beams. It calculates the area moment of inertia (Iy and Iz), + the polar moment of inertia (J), and the cross-sectional area (A). + These calculations depend on the chosen cross-section shape, either circular or rectangular. T + he formulas used for these calculations are based on standard equations for these properties.*/ template<typename DataTypes> void BeamHookeLawForceField<DataTypes>::reinit() { - Real Iy, Iz, J; - Real A; - if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular" ) + // Precompute and store values + Real Iy, Iz, J, A; + if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section { Real Ly = d_lengthY.getValue(); Real Lz = d_lengthZ.getValue(); - Iy=Ly*Lz*Lz*Lz/12.0; - Iz=Lz*Ly*Ly*Ly/12.0; - J=Iy + Iz; - A = Ly*Lz; + const Real LyLzLzLz = Ly * Lz * Lz * Lz; + const Real LzLyLyLy = Lz * Ly * Ly * Ly; + + Iy = LyLzLzLz / 12.0; + Iz = LzLyLyLy / 12.0; + J = Iy + Iz; + A = Ly * Lz; } - else //circular section + else //circular cross-section { msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; Real r = d_radius.getValue(); Real rInner = d_innerRadius.getValue(); - Iz = M_PI*(r*r*r*r - rInner*rInner*rInner*rInner)/4.0; - Iy = Iz ; - J = Iz + Iy; - A = M_PI*(r*r - rInner*rInner); + const Real r4 = r * r * r * r; + const Real rInner4 = rInner * rInner * rInner * rInner; + + Iy = M_PI * (r4 - rInner4) / 4.0; + Iz = Iy; + J = Iy + Iz; + A = M_PI * (r * r - rInner4); } m_crossSectionArea = A; - if(!d_variantSections.getValue()){ - if(!d_useInertiaParams.getValue()){ - Real E= d_youngModulus.getValue(); - Real G= E/(2.0*(1.0+d_poissonRatio.getValue())); + if(!d_variantSections.getValue()) + { + if(!d_useInertiaParams.getValue()) + { + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); m_K_section[0][0] = G*J; m_K_section[1][1] = E*Iy; m_K_section[2][2] = E*Iz; - } else{ + } + else + { msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation " "of the stiffness matrix."; m_K_section[0][0] = d_GI.getValue(); @@ -140,22 +155,31 @@ namespace sofa::component::forcefield } }else { + /*If the d_variantSections flag is set to true, it implies that multi-section beams are used for + the simulation. In this case, the code calculates and initializes a list of stiffness matrices + (m_K_sectionList) for each section. The properties of each section, such as Young's modulus and + Poisson's ratio, are specified in the d_youngModulusList and d_poissonRatioList data.*/ msg_info("BeamHookeLawForceField")<< "Multi section beam are used for the simulation!"; m_K_sectionList.clear(); - size_t szYM = d_youngModulusList.getValue().size(); - size_t szPR = d_poissonRatioList.getValue().size(); - size_t szL = d_length.getValue().size(); + + const size_t szL = d_length.getValue().size(); - if((szL != szPR)||(szL != szYM)){ + if((szL != d_poissonRatioList.getValue().size())||(szL != d_youngModulusList.getValue().size())){ msg_error("BeamHookeLawForceField")<< "Please the size of the data length, youngModulusList and " "poissonRatioList should be the same !"; return; } - for(size_t k=0; k<szL; k++){ + + /*Stiffness Matrix Initialization: Next, the code initializes the stiffness matrix m_K_section + based on the properties of the cross-section and the material's Young's modulus (E) and + Poisson's ratio. The stiffness matrix is essential for computing forces and simulating beam + behavior.*/ + for(size_t k=0; k<szL; k++) + { Mat33 _m_K_section; - Real E= d_youngModulusList.getValue()[k]; - Real G= E/(2.0*(1.0+d_poissonRatioList.getValue()[k])); + Real E = d_youngModulusList.getValue()[k]; + Real G = E/(2.0*(1.0+d_poissonRatioList.getValue()[k])); _m_K_section[0][0] = G*J; _m_K_section[1][1] = E*Iy; @@ -205,7 +229,7 @@ namespace sofa::component::forcefield } - template<typename DataTypes> + template<typename DataTypes> void BeamHookeLawForceField<DataTypes>::addDForce(const MechanicalParams* mparams, DataVecDeriv& d_df , const DataVecDeriv& d_dx) diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index c43bf5c4..f8ec5a2d 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -389,7 +389,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() for (size_t i=0; i < sz; i++) { if (curv_abs_section[input_index] > curv_abs_frames[i]) { m_indicesVectors.push_back(input_index); - m_indicesVectorsDraw.push_back(input_index); + m_indicesVectorsDraw.push_back(input_index); // maybe I shouldn't do this here !!! } else if(curv_abs_section[input_index] == curv_abs_frames[i]){ m_indicesVectors.push_back(input_index); diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 9c94458e..d89c3fb9 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -50,14 +50,10 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : m_fromModel1(NULL) , m_fromModel2(NULL) , m_toModel(NULL) - , d_deformationAxis(initData(&d_deformationAxis, (int)1, "deformationAxis", - "the axis in which we want to show the deformation.\n")) - , d_max(initData(&d_max, (Real2)1.0e-2, "max", - "the maximum of the deformation.\n")) - , d_min(initData(&d_min, (Real2)0.0, "min", - "the minimum of the deformation.\n")) - , d_radius(initData(&d_radius, (Real2)0.05, "radius", - "the axis in which we want to show the deformation.\n")) + , d_deformationAxis(initData(&d_deformationAxis, (int)1, "deformationAxis", "the axis in which we want to show the deformation.\n")) + , d_max(initData(&d_max, (Real2)1.0e-2, "max", "the maximum of the deformation.\n")) + , d_min(initData(&d_min, (Real2)0.0, "min", "the minimum of the deformation.\n")) + , d_radius(initData(&d_radius, (Real2)0.05, "radius", "the axis in which we want to show the deformation.\n")) , d_drawMapBeam(initData(&d_drawMapBeam, true,"nonColored", "if this parameter is false, you draw the beam with " "color according to the force apply to each beam")) , d_color(initData(&d_color, type::Vec4f (40/255.0, 104/255.0, 137/255.0, 0.8) ,"color", "The default beam color")) @@ -362,7 +358,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>:: applyJT( dataVecOut2Force[0]->endEdit(); } -//___________________________________________________________________________ + template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( const core::ConstraintParams*/*cparams*/ , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const, From 2e6035042f791c46bc163839b1cad2c4562616ed Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Thu, 9 Nov 2023 10:01:18 +0100 Subject: [PATCH 18/71] creating tutoriel for cosserat trainning --- docs/testScene/tuto_4.py | 59 ++++--- docs/text/Introduction.md | 148 ++++++++++++++++-- docs/text/Setting up the Environment.md | 112 +++++-------- docs/text/tutorial.md | 55 ++++--- examples/python3/actuators/fingerActuation.py | 26 +-- examples/python3/useful/header.py | 2 +- 6 files changed, 251 insertions(+), 151 deletions(-) diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py index 41f31107..fde01043 100644 --- a/docs/testScene/tuto_4.py +++ b/docs/testScene/tuto_4.py @@ -35,7 +35,7 @@ def __init__(self, *args, **kwargs): self.frames = kwargs['frame_node'].FramesMO self.force_type = kwargs['force_type'] self.tip_controller = kwargs['tip_controller'] - + self.size = geoParams.nbFrames self.applyForce = True self.forceCoeff = 0. @@ -46,9 +46,9 @@ def onAnimateEndEvent(self, event): self.forceCoeff += 0.01 else: self.forceCoeff -= 0.01 - + # choose the type of force - if self.force_type == 1 : + if self.force_type == 1: self.compute_force() elif self.force_type == 2: self.compute_orthogonal_force() @@ -57,41 +57,39 @@ def onAnimateEndEvent(self, event): def compute_force(self): with self.forceNode.forces.writeable() as force: - vec = [0., 0., 0., 0., self.forceCoeff/sqrt(2), self.forceCoeff/sqrt(2)] + vec = [0., 0., 0., 0., self.forceCoeff / sqrt(2), self.forceCoeff / sqrt(2)] for i, v in enumerate(vec): force[0][i] = v - - + def compute_orthogonal_force(self): position = self.frames.position[self.size] # get the last rigid of the cosserat frame orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation # Calculate the direction of the force in order to remain orthogonal to the x axis of the last frame of the beam. with self.forceNode.forces.writeable() as force: - vec = orientation.rotate([0., self.forceCoeff*5.e-2, 0.]) + vec = orientation.rotate([0., self.forceCoeff * 5.e-2, 0.]) vec.normalize() # print(f' The new vec is : {vec}') for count in range(3): force[0][count] = vec[count] - + def rotate_force(self): if self.forceCoeff <= 100. * pi: with self.tip_controller.position.writeable() as position: last_frame = self.frames.position[self.size] vec = Quat(last_frame[3], last_frame[4], last_frame[5], last_frame[6]) # get the orientation - + vec.rotateFromEuler([self.theta, 0., 0.]) # apply rotation arround x-axis vec.normalize() - for i, v in enumerate(vec): - position[0][i+3] = v - - + for i, v in enumerate(vec): + position[0][i + 3] = v + def onKeypressedEvent(self, event): key = event['key'] if key == "+": self.applyForce = True elif key == "-": self.applyForce = False - + def createScene(root_node): addHeader(root_node) @@ -102,24 +100,23 @@ def createScene(root_node): # create cosserat Beam cosserat_beam = solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) cosserat_frames = cosserat_beam.cosseratFrame - + # this constance force is used only in the case we are doing force_type 1 or 2 - const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, indices=geoParams.nbFrames, - forces=force_null) - - # The endffectors is used only when force_type is 3 - #create a rigid body to control the end effector of the beam - tip_controller= root_node.addChild('tip_controller') + const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, + indices=geoParams.nbFrames, forces=force_null) + + # The effector is used only when force_type is 3 + # create a rigid body to control the end effector of the beam + tip_controller = root_node.addChild('tip_controller') controller_state = tip_controller.addObject('MechanicalObject', template='Rigid3d', name="controlEndEffector", - showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], showObject=True) - - cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', - stiffness=1e8, angularStiffness=1e8, external_points=0, - external_rest_shape=controller_state.getLinkPath(), points=geoParams.nbFrames, template="Rigid3d") - - - solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, - tip_controller=controller_state)) + showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], + showObject=True) + + cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=1e8, angularStiffness=1e8, + external_points=0, external_rest_shape=controller_state.getLinkPath(), + points=geoParams.nbFrames, template="Rigid3d") + solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, + tip_controller=controller_state)) - return root_node \ No newline at end of file + return root_node diff --git a/docs/text/Introduction.md b/docs/text/Introduction.md index 6dd03e7c..f7a45b8a 100644 --- a/docs/text/Introduction.md +++ b/docs/text/Introduction.md @@ -5,7 +5,41 @@ tags: cssclass: - dashboard --- -## Introduction to Soft Robotics (SR) +_Welcome to this tutorial on SOFA-Cosserat Plugin._ + +[Formation plugin : Cosserat - CodiMD](https://notes.inria.fr/gcfuFPDYSeeAlG4gzfDJwA#) + +Yinoussa Adagolodjo + +--- +#### SOFA + +- SOFA : Simulation Open Framework Architecture + - Dedicated to research +- Use for prototyping and development of physics-based simulation + - FEM / Rigid (articulated) Bodies / Contacts / Other models... + - Projections = MAPPING ! +--- +#### SOFA +- Free & Open Source: [https://www.sofa-framework.org/](https://www.sofa-framework.org/) + - Download, use, modify, cite and contribute to SOFA! +- International community and two major events per year  +- SOFA Week from $13-17^{th}$ of November  + - Onsite with online access + - Free – all you need is to register +--- +#### Tutorial Roadmap + +- What to expect ? + - An overview of the theory of Discrete Cosserat Model + - Numerics & Hands-on examples + - Reduce coordinates + - Reduce coordinate (Cosserat) to Global coordinate (SOFA) State + - Boundary conditions and interaction forces +- Ask your questions and actively participate throughout this tutorial. + - The first time I am doing this, so I need your feedback +--- +#### Introduction to Soft Robotics (SR) - Soft robotics is an emerging and innovative field of robotics - Focuses on the design and development of robots made from : @@ -13,14 +47,14 @@ cssclass: - *Deformable*, - *Compliant materials*. --- -## Introduction to Soft Robotics (SR) +#### Introduction to Soft Robotics (SR) - Numerous advantages - *Adaptability* : Their ability to deform and adapt to their environment - *Safety* : Ideal for interactions with humans, delicate objects, or unstructured surroundings - *Versatility* : Various applications --- -## **Key Applications** +#### **Key Applications** - *Healthcare* : The gentle and non-invasive nature of SR is necessary - *Industrial automation* : The high [Compliance](../../../Soft_Robot/Compliance.md), reduces the risk of damage during interactions with products @@ -28,7 +62,7 @@ cssclass: - *Space exploration*, and *extreme environments* --- -## **Challenges in Soft Robotics** +#### **Challenges in Soft Robotics** - *Modeling* : due to deformable materials - [*Control*](../../../Soft_Robot/kinematics_dynamics_control.md) : due to the non-linear, multi-body dynamics of deformable materials @@ -36,27 +70,117 @@ cssclass: - [*Multi-physics*](../../../../../../Projects/ANR/RobotMulti-physics.md) : due a wide range of physical behaviors, including mechanical deformation, thermal effects, electrical responses, --- -## **Challenges in Soft Robotics** +#### **Challenges in Soft Robotics** - Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. (To go further on the introduction of deformable robotics ⇾ [Introduction_General](../../../Soft_Robot/Introduction_General.md) ) --- -## [FEM and DCM](../../_docs/DCM_FEM.md) +##### Why combine different models ? +- Introducing a versatile modeling tool for multidimensional Soft-Robot: + - Animal locomotion (Bio-inspired robotics) + - Flexible arms actuated by cables or similar mechanisms (Robotics) + - Medical devices like endoscopes, needles, and catheters (Medical robotics) +--- +##### Why combine different models ? +- Existing design and modeling tools demand enhancement, particularly in the mechanical aspect. +![](Pasted%20image%2020231108201224.png) +- Offer a wide range of design possibilities: + - Selection of actuators, force transmission within the structure, utilization of materials with varying stiffness profiles, and more. +--- +##### Cosserat Theory +Choose strain as generalized coordinates, defined in global (or local) frame! +![400](Pasted%20image%2020231108233708.png) +[Lazarus et al. 2013] +- The configuration of the Cosserat rod is defined by its centerline r(s). +- The orientation of each mass point of the rod is represented by an orthonormal basis ($d_1(s), d_2(s), d_3(s)$) +- The three local modes of deformation of the elastic rod : - (b1) material curvature $κ_1$ related to the direction $d_1$ of the cross-section, (b2) material curvature $κ_2$ related to $d_2$, and $κ_3$ twist. +--- +##### Discrete Cosserat Modeling: DCM +- Serial rigid (6DoFs) bodies with reduced coordinates +![700](https://lh7-us.googleusercontent.com/q9X7GJY2GxkPSOqb7w_jzbsf5sIiUglQTnJDySqUer-mVAPQPr-ENDjkSMxFlB0LuyXX0DKcuMR3rKqdMmWGJiBBoXu9zM7sbXbgCrZZhKiD0mkcY7Pwru_J7JvyVSCD6o4cYXsV7L65TSJprRY_=nw) +--- +##### Discrete Cosserat Modeling: DCM +- Piece-wise Constant Strain (PCS, treats rigid, soft, or hybrid robots uniformly) +![500](https://lh7-us.googleusercontent.com/hzJA2pzS-naPfFkf-98bPkGsQ86ZGdGwqGW3-un56s3ZcVkdOB0_Jus4a9W_nqO7jU7Tt_FDzCrFIbfA9XFqaPBmmq-do-TIJkFn6NX-RimX2UlWBTis_7bKzAp7fEmIeiuOZ1FueZ5yxijFSJls=nw) +--- +##### Discrete Cosserat Modeling: DCM +- Models the deformation of a soft manipulator arm using a finite number of sections +- Assumes constant strains along each section +- Accounts for shears and torsion +- Simulates the inextensible behavior of a rod or cable +- Reduces model size, resulting in faster calculation times through the use of reduced coordinates. +--- +##### DCM (Kinematics) +- Configuration $g= \begin{pmatrix} \mathcal{R} & u \\ 0 & 1 \end{pmatrix} ∈SE(3)$ +- Velocity $\begin{align}\eta(s,t) &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ +- Strain $\begin{align}\xi(s,t) &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ +- Kinematics : $g'=g\hat{\xi}(X)$ ; $\dot{g} = g\hat{\eta}$ +- Differntial Kinematics : $\eta'=\dot{\xi}(X)-ad_{\xi(X)}\eta(X)$ +![](Pasted%20image%2020231109002926.png) +--- +![0](Pasted%20image%2020231108234643.png) -- *FEM's Material Modeling*: FEM excels at modeling the deformations and stress distributions in complex materials, including soft and deformable ones. It considers the local behavior of materials, making it more accurate for understanding the mechanical properties of soft robots. -- *Cosserat theory's Beam-Like Modeling*: DCM, on the other hand, is suitable for modeling the overall shape and bending of structures, making it a natural choice for cables, rods, and flexible elements in soft robots. +--- +##### DCM (Dynamics) +![800](Pasted%20image%2020231109003349.png) + +--- +##### DCM Dynamic +![](Pasted%20image%2020231109003734.png) + +--- +##### Approximation via PCS, VS and PLS +![300](Pasted%20image%2020231109003934.png) +- **PCS**: A local approximation scheme employing a local constant strain assumption. +- **VS**: A global approximation method based on the chosen basis functions. +- **PLS**: A local approximation scheme with a linear strain function assumption. +--- +##### PCS Cosserat +![](Pasted%20image%2020231109004616.png) +--- +##### Discrete Cosserat Modeling: DCM +###### Limitations: +- Challenges in simulating truss structures, intricate geometries, or volumetric deformations +- The PCS parametrization of a manipulator is not rooted in the arm's intrinsic variables +--- +##### Finite Element Modeling (FEM) +The Finite Element (FE) approach is typically represented by the position and velocity (global coordinates) of a system of interconnected nodes. +- This approach offers several advantages: + - **Versatility in object geometries:** It can be applied to a wide range of object geometries, including beams, shells, truss structures, and deformable volumes. + - **Material law customization:** Material properties can be tailored to meet specific requirements. + - **Ease of defining boundary conditions:** Boundary conditions for numerical models can be defined with ease. + - **Flexibility for creating truss structures:** Beams can be interconnected freely to create truss structures. +--- +##### Finite Element Modeling (FEM) +However, this approach also has limitations: +- **Time-consuming:** Simulations using the FE approach may be computationally intensive and time-consuming. +- **Additional constraints:** Additional constraints are often needed to prevent the extension of rod-like structures when modeling certain systems. +--- +##### Modeling Soft Robots: Combining DCM with FEM ---- -## Motivation for the combination of the two models +We combine Discrete Cosserat Modeling (DCM) with Finite Element Modeling (FEM) to harness the strengths of each model. This hybrid approach is particularly useful in scenarios like: +- Modeling the stiffness of cables used to actuate a soft robot with a deformable volumetric structure. +- This leads to a more realistic representation of the entire robot's behavior. +For example, it allows us to effectively simulate scenarios where inextensible cables are employed to control the motion of a soft robot. -- *Combined Accuracy*: By combining FEM and DCM, you can leverage the strengths of both methods. FEM provides fine-grained material modeling, while DCM captures the shape and motion of deformable elements accurately. This leads to a more realistic representation of the entire robot's behavior. +---- + *Combined Accuracy*: By combining FEM and DCM, you can leverage the strengths of both methods. FEM provides fine-grained material modeling, while DCM captures the shape and motion of deformable elements accurately. This leads to a more realistic representation of the entire robot's behavior. - *Unified Simulation Framework*:A combined FEM-DCM framework creates a unified simulation environment that can model both the deformable body of the robot (using FEM) and the actuation components (using DCM). This simplifies simulation setup and control algorithms. --- +[Hands on](Setting%20up%20the%20Environment.md) + +--- + +[[Complement]] + --- +##### [FEM and DCM](../../_docs/DCM_FEM.md) -[[Complement]] \ No newline at end of file +- *FEM's Material Modeling*: FEM excels at modeling the deformations and stress distributions in complex materials, including soft and deformable ones. It considers the local behavior of materials, making it more accurate for understanding the mechanical properties of soft robots. +- *Cosserat theory's Beam-Like Modeling*: DCM, on the other hand, is suitable for modeling the overall shape and bending of structures, making it a natural choice for cables, rods, and flexible elements in soft robots. +--- \ No newline at end of file diff --git a/docs/text/Setting up the Environment.md b/docs/text/Setting up the Environment.md index 75c845c4..ff858574 100644 --- a/docs/text/Setting up the Environment.md +++ b/docs/text/Setting up the Environment.md @@ -6,17 +6,13 @@ cssclasses: tags: - tuto/cosserat --- - - -**Introduction to SOFA** +##### **Introduction to SOFA** - Have SOFA installed on your machine - Install Cosserat plugin - In Tree - Out Tree - --- - -**Step 1: Installing SOFA** +##### **Step 1: Installing SOFA** Before you begin with the specific Cosserat plugin, you need to install SOFA. Follow these steps: @@ -24,9 +20,7 @@ Before you begin with the specific Cosserat plugin, you need to install SOFA. Fo 2. Choose the appropriate version for your operating system (Windows, Linux, or macOS). 3. Follow the installation instructions for your OS. Typically, this involves extracting the downloaded archive and setting environment variables. --- - -**Step 2: Setting Up the Cosserat Plugin** - +##### **Step 2: Setting Up the Cosserat Plugin** Now, we'll dive into the essential part – configuring the Cosserat plugin within SOFA. 1. **Create plugins folder:** - Create folder externalPlugins @@ -38,10 +32,10 @@ Now, we'll dive into the essential part – configuring the Cosserat plugin with --- 2. **Obtaining the Plugin:** - GitHub : https://github.com/SofaDefrost/Cosserat - - Download the plugin : - - git clone git@github.com:SofaDefrost/Cosserat.git (if you are using ssh-key) - - git clone https://github.com/SofaDefrost/Cosserat.git - - or Download the **Zip** +- Download the plugin : + - git clone git@github.com:SofaDefrost/Cosserat.git (if you are using ssh-key) + - git clone https://github.com/SofaDefrost/Cosserat.git + - or Download the **Zip** --- **3. Add *CMakeList.txt* file inside the *externalPlugin* folder** @@ -72,25 +66,22 @@ Now, we'll dive into the essential part – configuring the Cosserat plugin with 5. **First Cosserat Scene: *tuto_1.py*** - As said previously, this component is based on the PCS (Piece-wise Constant Strain) formulation. - ![400](Pasted%20image%2020231102173536.png) ---- - -- [ ] 3 sections with 7 frames -- [ ] **Goals** : - - how to create a basic scene with the cosserat plugin - - It is important to note the difference between : - - **section** and **frames** - - **section** and **cross-section** - - The notion of force-field : here **BeamHookeLawForceField** - - The notion of mapping: here **DiscreteCosseratMapping** - - Functions: **apply, applyJ**, **applyJT** for forces and **ApplyJ^T** for constraints + ![](Pasted%20image%2020231102173536.png) +--- +##### **Goals** : +- how to create a basic scene with the cosserat plugin + - It is important to note the difference between : + - **section** and **frames** + - **section** and **cross-section** +- The notion of force-field : here **BeamHookeLawForceField** +- The notion of mapping: here **DiscreteCosseratMapping** +- Functions: **apply, applyJ**, **applyJT** for forces and **ApplyJ^T** for constraints --- -Start with the base -![500](images/exemple_rigid_translation.png) +###### Start with the base +![600](images/exemple_rigid_translation.png) --- - -- The beam is always constructed along the x-axis +###### The beam is always constructed along the x-axis ```python def _add_rigid_base(p_node): rigid_base_node = p_node.addChild('rigid_base') @@ -111,28 +102,26 @@ def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2. ``` --- -- Parameters : +###### Parameters : ```python list_sections_length = [10, 10, 10] cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] ``` --- -- **BeamHookeLawForceField** - - **Force Computation**: The `addForce` method calculates and adds the forces acting on the beams. It uses Hooke's law to compute the forces based on the deformation of the beams and their properties. The computed forces are then stored in the `f` variable. +###### **BeamHookeLawForceField** +- **Force Computation**: The `addForce` method calculates and adds the forces acting on the beams. It uses Hooke's law to compute the forces based on the deformation of the beams and their properties. The computed forces are then stored in the `f` variable. --- - **Derivative of Force Computation**: The `addDForce` method computes the derivative of the forces with respect to the deformation. This is used for stiffness matrix calculations in the context of finite element simulations. --- - - **Stiffness Matrix Computation**: The `addKToMatrix` method is responsible for adding the stiffness matrix to the global matrix. This is used in FEM to represent the stiffness of the entire system. --- -- Add Mapped coordinates (frames) to the scene - - **Mapping** between **Reduced coordinates** (Cosserat's state) and Global cordinates (Sofa state). - - Frames are multi-mapped (under Cosserat state and rigid base) +###### Add Mapped coordinates (frames) to the scene +- **Mapping** between **Reduced coordinates** (Cosserat's state) and Global cordinates (Sofa state). + - Frames are multi-mapped (under Cosserat state and rigid base) ![400](../images/CosseratMapping.png) --- - ```python def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') @@ -144,16 +133,17 @@ def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _fram return cosserat_in_Sofa_frame_node ``` --- -- The notion of mapping: here **DiscreteCosseratMapping** - - **apply** : It calculates how the positions of elements in the input models (deformations and base) are transformed to the output model (rigid frames). The function applies the mapping to these input positions and updates the output frames accordingly. - - **applyJ** : compute the Jacobian matrix for the mapping operation. How small changes in input velocity (in this case, deformations) affect small changes in output velocity (in this case, the rigid frames). +###### The notion of mapping: **DiscreteCosseratMapping** +- **apply** : It calculates how the positions of elements in the input models (deformations and base) are transformed to the output model (rigid frames). The function applies the mapping to these input positions and updates the output frames accordingly. +- **applyJ** : compute the Jacobian matrix for the mapping operation. How small changes in input velocity (in this case, deformations) affect small changes in output velocity (in this case, the rigid frames). --- - **applyJT force** : It updates forces in reduced coordinate based on forces in global coordinate. - **applyJT Constraint** : It updates constraints in reduced coordinate based on constraints in global coordinate. +###### The complete scene ![tuto_1.py](../testScene/tuto_1.py) ---- -- [ ] Example 2: **tuto_2.py** +- [ ] Example 2: **![tuto_2.py](../testScene/tuto_2.py)** - [ ] script for automating sections and frames - [ ] **Goal**: show the role of the number of sections on the overall deformation - [ ] Example: @@ -186,47 +176,29 @@ def createScene(root_node): ``` --- -- [ ] Scene ![tuto_4](../testScene/tuto_4.py) +##### Some known examples ![tuto_4](../testScene/tuto_4.py) - [ ] Force type 1 - [ ] Force type 2 - [ ] Force type 3 --- +##### FEM & DCM coupling for finger actuation ![tuto_5.py](../testScene/tuto_5.py) +- [ ] The cable is modeled using the DCM +- [ ] The finger is modeled using FEM +- [ ] Constraints are based on the Lagrange multiplier + - [ ] **QPSlidingConstraint** + - [ ] **DifferenceMultiMapping** -- [ ] Une scène avec contrainte -- [ ] Celle de l’actuation du doigt **[tuto7.py](http://tuto7.py)** --- - -- [ ] Celles des trois doigts qui soulèvent le cube ****[tuto8.py](http://tuto8.py)*** - ----- - -- [ ] **Une scène pre-bent, s'inspire de la scène Flavie **[tuto9.py](http://tuto9.py)** - +##### An example of the use of pre-curved cables, use cases (see scenes from Flavie) [tuto9.py](http://tuto9.py) --- +##### Scene of three fingers lifting a cube ****[tuto8.py](http://tuto8.py)*** -**Step 3: Configuring Scene Files** - -Now that you have SOFA and the Cosserat plugin ready, you need to configure your simulation scene files. These XML-based files define the simulation environment, including the soft robot model, forces, constraints, and interaction with the environment. - ---- - -1. **Creating a Scene File:** You can start by creating a new XML scene file. This file will serve as the blueprint for your simulation. You can use a text editor to create and modify it. ---- +---- -2. **Defining Soft Robot Models:** Within the scene file, you must define your soft robot model. You can specify its geometry, material properties, and the use of Cosserat models to represent deformable structures. ---- -3. **Integrating Cosserat Components:** To utilize Cosserat models in your simulation, you need to incorporate the appropriate components from the Cosserat plugin. These components include the Cosserat beam elements, which are crucial for modeling cables and rods. ---- -4. **Adding Constraints:** Depending on your simulation, you might need to introduce constraints that describe the interaction between the robot and its environment. This is also an essential part of configuring the scene. ---- -5. **Configuring Simulation Parameters:** The scene file allows you to set various simulation parameters, such as time steps, numerical solvers, and visualization options. +**Adding Constraints:** Depending on your simulation, you might need to introduce constraints that describe the interaction between the robot and its environment. This is also an essential part of configuring the scene. --- -**Step 4: Running Simulations** - -After configuring your scene file, you can run simulations to see how the soft robot behaves. SOFA provides real-time visualization, making it easier to analyze and refine your models. You can interact with the simulated robot and monitor its performance as the simulation progresses. - --- diff --git a/docs/text/tutorial.md b/docs/text/tutorial.md index 6732d91c..4aaaa839 100644 --- a/docs/text/tutorial.md +++ b/docs/text/tutorial.md @@ -11,39 +11,56 @@ cssclasses: _Welcome to this tutorial on SOFA-Cosserat Plugin._ -_Outline of what participants can expect to learn during this tutorial ?_ - [Formation plugin : Cosserat - CodiMD](https://notes.inria.fr/gcfuFPDYSeeAlG4gzfDJwA#) +Yinoussa Adagolodjo + --- -# Tutorial Roadmap +#### SOFA -- What to Expect ? - - Provide an overview of the tutorial's structure. - - Sections and topics we'll cover during the tutorial. -- Ask questions and be actively engage throughout this tutorial - - The first time I am doing this, so I really need your feedback - +- SOFA : Simulation Open Framework Architecture + - Dedicated to research +- Use for prototyping and development of physics-based simulation + - FEM / Rigid (articulated) Bodies / Contacts / Other models... + - Projections = MAPPING ! --- - -## [Introduction](Introduction.md) +#### SOFA +- Free & Open Source: [https://www.sofa-framework.org/](https://www.sofa-framework.org/) + - Download, use, modify, cite and contribute to SOFA! +- International community and two major events per year  +- SOFA Week from $13-17^{th}$ of November  + - Onsite with online access + - Free – all you need is to register +--- +#### Tutorial Roadmap -- 🗄️Briefly introduce the field of soft robotics +- What to expect ? + - An overview of the theory of Discrete Cosserat Model + - Numerics & Hands-on examples + - Reduce coordinates + - Reduce coordinate (Cosserat) to Global coordinate (SOFA) State + - Boundary conditions and interaction forces +- Ask your questions and actively participate throughout this tutorial. + - The first time I am doing this, so I need your feedback +--- +#### [Introduction](Introduction.md) + +- Briefly introduce the field of soft robotics - The motivation for combining FEM and DCM models. ---- -## [Background Concepts](Background%20Concepts.md) -- An overview of Discrete Cosserat Model (DCM) and their relevance in soft robotics. -- Finite Element Methods (FEM) and their use in simulating deformable structures ? -- The concept of compliance matrices and their role in soft robot modeling ? --- - -## [Setting up the Environment](Setting%20up%20the%20Environment.md) +#### [Setting up the Environment](Setting%20up%20the%20Environment.md) +- An overview of Discrete Cosserat Model (DCM) - The software tools and libraries used (SOFA, **Cosserat** plugin). - Instructions for setting up the simulation environment. - [cosserat_python_scene](cosserat_python_scene.md) +--- +## [Background Concepts](Background%20Concepts.md) +- An overview of Discrete Cosserat Model (DCM) and their relevance in soft robotics. +- Finite Element Methods (FEM) and their use in simulating deformable structures ? +- The concept of compliance matrices and their role in soft robot modeling ? --- ## [Direct Simulation](Direct%20Simulation.md) - How to diff --git a/examples/python3/actuators/fingerActuation.py b/examples/python3/actuators/fingerActuation.py index 91b4b04c..59e4248f 100644 --- a/examples/python3/actuators/fingerActuation.py +++ b/examples/python3/actuators/fingerActuation.py @@ -8,7 +8,6 @@ _type_: _description_ """ - __authors__ = "Younes" __contact__ = "adagolodjo@protonmail.com, yinoussa.adagolodjo@inria.fr" __version__ = "1.0.0" @@ -23,9 +22,6 @@ path = f'{os.path.dirname(os.path.abspath(__file__))}/mesh/' - - - femPos = [" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"] @@ -33,11 +29,11 @@ def createScene(rootNode): rootNode.addObject('BackgroundSetting', color='0 0.168627 0.211765') addVisual(rootNode) - addHeader(rootNode,isConstrained=False) + addHeader(rootNode, isConstrained=False) rootNode.addObject('FreeMotionAnimationLoop', parallelCollisionDetectionAndFreeMotion=False, - parallelODESolving=False) + parallelODESolving=False) rootNode.addObject('GenericConstraintSolver', name='ConstraintSolver', tolerance=1e-20, maxIterations=1000, - multithreading=False) + multithreading=False) rootNode.findData('gravity').value = [0., 0., 0.] femFingerNode = rootNode.addChild('femFingerNode') @@ -54,7 +50,7 @@ def createScene(rootNode): cableNode = addSolverNode(rootNode, name="cableSolver", isConstrained=True) cosseratCable = cableNode.addChild( Cosserat(parent=cableNode, cosseratGeometry=beamGeometrie, name="cosserat", radius=0.5, - youngModulus=5e6, poissonRatio=0.4)) + youngModulus=5e6, poissonRatio=0.4)) mappedFrameNode = cosseratCable.cosseratFrame # This creates a new node in the scene. This node is appended to the finger's node. @@ -64,20 +60,20 @@ def createScene(rootNode): # mechanical modelling. In the case of a cable it is a set of positions specifying # the points where the cable is passing by. cable3DPosNodeMO = cable3DPosNode.addObject('MechanicalObject', name="cablePos", position=cosseratCable.frames3D, - showObject="1", showIndices="0") + showObject="1", showIndices="0") cable3DPosNode.addObject('IdentityMapping') """ These positions are in fact the distance between fem points and the cable points""" distancePointsNode = cable3DPosNode.addChild('distancePoints') femPointsNode.addChild(distancePointsNode) mappedPoints = distancePointsNode.addObject('MechanicalObject', template='Vec3d', position=femPos, - name="distancePointsMO", showObject='1', showObjectScale='1') + name="distancePointsMO", showObject='1', showObjectScale='1') # cableBaseMo = cosseratCable.rigidBaseNode.getObject('MechanicalObject') # cosseratCoordinateMo = cosseratCable.cosseratCoordinateNode.getObject('MechanicalObject') """The controller of the cable is added to the scene""" cableNode.addObject(FingerController(cosseratCable.rigidBaseNode.RigidBaseMO, - cosseratCable.cosseratCoordinateNode.cosseratCoordinateMO)) + cosseratCable.cosseratCoordinateNode.cosseratCoordinateMO)) inputCableMO = cable3DPosNodeMO.getLinkPath() inputFEMCableMO = femPointsNode.getLinkPath() @@ -85,14 +81,10 @@ def createScene(rootNode): """ This constraint is used to compute the distance between the cable and the fem points""" distancePointsNode.addObject('QPSlidingConstraint', name="QPConstraint") distancePointsNode.addObject('DifferenceMultiMapping', name="pointsMulti", input1=inputFEMCableMO, indices="5", - input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position") - - + input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position") return - - # ############### # New adds to use the sliding Actuator ############### @@ -102,14 +94,12 @@ def createScene(rootNode): cableNode.addObject('SparseLUSolver', name='solver') cableNode.addObject('GenericConstraintCorrection') - cosserat = cableNode.addChild(Cosserat(parent=cableNode, cosseratGeometry=beamGeometrie, radius=0.5, useCollisionModel=True, name="cosserat", youngModulus=5e6, poissonRatio=0.4)) cableNode.addObject(Animation(cosserat.rigidBaseNode.RigidBaseMO, cosserat.cosseratCoordinateNode.cosseratCoordinateMO)) - mappedPointsNode = slidingPoint.addChild('MappedPoints') femPoints.addChild(mappedPointsNode) mappedPoints = mappedPointsNode.addObject('MechanicalObject', template='Vec3d', position=FEMpos, diff --git a/examples/python3/useful/header.py b/examples/python3/useful/header.py index 65ad55fa..ea77ced6 100644 --- a/examples/python3/useful/header.py +++ b/examples/python3/useful/header.py @@ -178,7 +178,7 @@ def addFEMObject(parentNode, path): def addMappedPoints(parentNode, name="pointsInFEM", position=None, showObject="1", - showIndices="1", femPos=" 0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"): + showIndices="1", femPos="0.0 0 0 15 0 0 30 0 0 45 0 0 60 0 0 66 0 0 81 0.0 0.0"): if position is None: position = femPos From 3bf1f85143677c4e4321cd4e2018f06ec8174c80 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Thu, 9 Nov 2023 10:02:10 +0100 Subject: [PATCH 19/71] creating tutoriel for cosserat trainning --- docs/testScene/tuto_5.py | 166 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 166 insertions(+) create mode 100644 docs/testScene/tuto_5.py diff --git a/docs/testScene/tuto_5.py b/docs/testScene/tuto_5.py new file mode 100644 index 00000000..d697d08a --- /dev/null +++ b/docs/testScene/tuto_5.py @@ -0,0 +1,166 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "adagolodjo" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "October, 26 2021" + +from useful.header import addHeader, addSolverNode, addVisual +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from math import sqrt +from splib3.numerics import Quat +import Sofa +import os +from math import pi +from useful.header import addHeader, addVisual, addSolverNode, Finger +from controller import FingerController + + +path = f'{os.path.dirname(os.path.abspath(__file__))}/../../examples/python3/actuators/mesh/' + +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=81., showFramesObject=1, + nbSection=12, nbFrames=32, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=5.e6, poissonRatio=0.4, beamRadius=0.5, + beamLength=30) + +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +force_null = [0., 0., 0., 0., 0., 0.] # N +femPos = [[0.0, 0, 0], [15, 0, 0], [30, 0, 0], [45, 0, 0], [60, 0, 0], [66, 0, 0], [81, 0.0, 0.0]] + + +class ForceController(Sofa.Core.Controller): + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, *args, **kwargs) + self.forceNode = kwargs['forceNode'] + self.frames = kwargs['frame_node'].FramesMO + self.force_type = kwargs['force_type'] + self.tip_controller = kwargs['tip_controller'] + + self.size = geoParams.nbFrames + self.applyForce = True + self.forceCoeff = 0. + self.theta = 0.1 + + def onAnimateEndEvent(self, event): + if self.applyForce: + self.forceCoeff += 0.01 + else: + self.forceCoeff -= 0.01 + + # choose the type of force + if self.force_type == 1: + self.compute_force() + elif self.force_type == 2: + self.compute_orthogonal_force() + elif self.force_type == 3: + self.rotate_force() + + def compute_force(self): + with self.forceNode.forces.writeable() as force: + vec = [0., 0., 0., 0., self.forceCoeff / sqrt(2), self.forceCoeff / sqrt(2)] + for i, v in enumerate(vec): + force[0][i] = v + + def compute_orthogonal_force(self): + position = self.frames.position[self.size] # get the last rigid of the cosserat frame + orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation + # Calculate the direction of the force in order to remain orthogonal to the x axis of the last frame of the beam. + with self.forceNode.forces.writeable() as force: + vec = orientation.rotate([0., self.forceCoeff * 5.e-2, 0.]) + vec.normalize() + # print(f' The new vec is : {vec}') + for count in range(3): + force[0][count] = vec[count] + + def rotate_force(self): + if self.forceCoeff <= 100. * pi: + with self.tip_controller.position.writeable() as position: + last_frame = self.frames.position[self.size] + vec = Quat(last_frame[3], last_frame[4], last_frame[5], last_frame[6]) # get the orientation + + vec.rotateFromEuler([self.theta, 0., 0.]) # apply rotation arround x-axis + vec.normalize() + for i, v in enumerate(vec): + position[0][i + 3] = v + + def onKeypressedEvent(self, event): + key = event['key'] + if key == "+": + self.applyForce = True + elif key == "-": + self.applyForce = False + + +def createScene(root_node): + addHeader(root_node, isConstrained=True) + root_node.gravity = [0, 0., 0.] + + solver_node = addSolverNode(root_node, name="solver_node", isConstrained=True) + + # create cosserat Beam + cosserat_beam = solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) + cosserat_frames_node = cosserat_beam.cosseratFrame + + # Finger state + femFingerNode = root_node.addChild('femFingerNode') + """ Add FEM finger to the scene""" + finger_node, fem_points_node = Finger(femFingerNode, name="Finger", rotation=[0.0, 180.0, 0.0], + translation=[-17.5, -12.5, 7.5], path=path) + + # This creates a new node in the scene. This node is appended to the finger's node. + cable_state_node = cosserat_frames_node.addChild('cable_state_node') + + # This creates a MechanicalObject, a componant holding the degree of freedom of our + # mechanical modelling. In the case of a cable it is a set of positions specifying + # the points where the cable is passing by. + cable_state = cable_state_node.addObject('MechanicalObject', name="cablePos", + position=cosserat_beam.frames3D, showObject="1", showIndices="0") + cable_state_node.addObject('IdentityMapping') + + """ These positions are in fact the distance between fem points and the cable points""" + distance_node = cable_state_node.addChild('distance_node') + fem_points_node.addChild(distance_node) + distance = distance_node.addObject('MechanicalObject', template='Vec3d', position=femPos, + name="distancePointsMO", showObject='1', showObjectScale='1') + + + """The controller of the cable is added to the scene""" + cable_state_node.addObject(FingerController(cosserat_beam.rigidBaseNode.RigidBaseMO, + cosserat_beam.cosseratCoordinateNode.cosseratCoordinateMO)) + + inputCableMO = cable_state.getLinkPath() + inputFEMCableMO = fem_points_node.getLinkPath() + outputPointMO = distance.getLinkPath() + """ This constraint is used to compute the distance between the cable and the fem points""" + distance_node.addObject('QPSlidingConstraint', name="QPConstraint") + distance_node.addObject('DifferenceMultiMapping', name="pointsMulti", input1=inputFEMCableMO, indices="5", + input2=inputCableMO, output=outputPointMO, direction="@../../FramesMO.position") + + return root_node + # # this constance force is used only in the case we are doing force_type 1 or 2 + # const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, + # indices=geoParams.nbFrames, forces=force_null) + # + # # The effector is used only when force_type is 3 + # # create a rigid body to control the end effector of the beam + # tip_controller = root_node.addChild('tip_controller') + # controller_state = tip_controller.addObject('MechanicalObject', template='Rigid3d', name="controlEndEffector", + # showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], + # showObject=True) + # + # cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=1e8, angularStiffness=1e8, + # external_points=0, external_rest_shape=controller_state.getLinkPath(), + # points=geoParams.nbFrames, template="Rigid3d") + # + # solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, + # tip_controller=controller_state)) + + return root_node From 01db2f8367afb10a5c8e6ce2cb9cb06757464a8f Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Thu, 9 Nov 2023 10:02:34 +0100 Subject: [PATCH 20/71] creating tutoriel for cosserat trainning --- docs/testScene/controller.py | 57 ++++++++++++++++++++++++++++++++++++ 1 file changed, 57 insertions(+) create mode 100644 docs/testScene/controller.py diff --git a/docs/testScene/controller.py b/docs/testScene/controller.py new file mode 100644 index 00000000..1242c222 --- /dev/null +++ b/docs/testScene/controller.py @@ -0,0 +1,57 @@ +import Sofa +from splib3.numerics import Quat + + +class FingerController(Sofa.Core.Controller): + """ + Implements the AnimationManager as a PythonScriptController + """ + + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, *args, **kwargs) + self.rigidBaseMO = args[0] + self.rateAngularDeformMO = args[1] + + self.rate = 0.2 + self.angularRate = 0.02 + return + + def _extracted_from_onKeypressedEvent_10(self, qOld, posA, angularRate): + qNew = Quat.createFromEuler([0., angularRate, 0.], 'ryxz') + qNew.normalize() + qNew.rotateFromQuat(qOld) + for i in range(4): + posA[0][i+3] = qNew[i] + + def onKeypressedEvent(self, event): + key = event['key'] + if ord(key) == 19: # up + with self.rigidBaseMO.rest_position.writeable() as posA: + qOld = Quat() + for i in range(4): + qOld[i] = posA[0][i+3] + + self._extracted_from_onKeypressedEvent_10( + self, qOld, posA, self.angularRate) + + if ord(key) == 21: # down + with self.rigidBaseMO.rest_position.writeable() as posA: + qOld = Quat() + for i in range(4): + qOld[i] = posA[0][i+3] + + self._extracted_from_onKeypressedEvent_10( + qOld, posA, -self.angularRate) + + # Pull the cable base + if ord(key) == 18: # left + print("left: the cable is pulled") + with self.rigidBaseMO.rest_position.writeable() as posA: + posA[0][0] -= self.rate + print(f' The new position is : {posA[0]}') + # release the cable base + if ord(key) == 20: # right + print("left: the cable is released") + with self.rigidBaseMO.rest_position.writeable() as posA: + posA[0][0] += self.rate + print(f' The new position is : {posA[0]}') From fc6bcb565a0c94e81290e12ec6dcc6dd48cd87bf Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 14 Nov 2023 07:36:27 +0100 Subject: [PATCH 21/71] update tutorials docs --- docs/images/Pasted image 20231025171449.png | Bin 0 -> 19490 bytes docs/images/Pasted image 20231102173536.png | Bin 0 -> 225384 bytes docs/images/Pasted image 20231108201224.png | Bin 0 -> 609703 bytes docs/images/Pasted image 20231108233708.png | Bin 0 -> 181616 bytes docs/images/Pasted image 20231108234643.png | Bin 0 -> 64444 bytes docs/images/Pasted image 20231109002926.png | Bin 0 -> 38517 bytes docs/images/Pasted image 20231109003349.png | Bin 0 -> 401571 bytes docs/images/Pasted image 20231109003734.png | Bin 0 -> 157645 bytes docs/images/Pasted image 20231109003934.png | Bin 0 -> 100395 bytes docs/images/Pasted image 20231109004616.png | Bin 0 -> 171604 bytes docs/testScene/tuto_1.py | 8 ++-- docs/testScene/tuto_2.py | 11 ++--- docs/testScene/tuto_3.py | 8 ++-- docs/testScene/tuto_4.py | 14 +++---- docs/text/Introduction.md | 16 ++++---- docs/text/Setting up the Environment.md | 42 ++++++++++---------- docs/text/Theory.md | 4 +- docs/text/cosserat_python_scene.md | 1 - 18 files changed, 48 insertions(+), 56 deletions(-) create mode 100644 docs/images/Pasted image 20231025171449.png create mode 100644 docs/images/Pasted image 20231102173536.png create mode 100644 docs/images/Pasted image 20231108201224.png create mode 100644 docs/images/Pasted image 20231108233708.png create mode 100644 docs/images/Pasted image 20231108234643.png create mode 100644 docs/images/Pasted image 20231109002926.png create mode 100644 docs/images/Pasted image 20231109003349.png create mode 100644 docs/images/Pasted image 20231109003734.png create mode 100644 docs/images/Pasted image 20231109003934.png create mode 100644 docs/images/Pasted image 20231109004616.png diff --git a/docs/images/Pasted image 20231025171449.png b/docs/images/Pasted image 20231025171449.png new file mode 100644 index 0000000000000000000000000000000000000000..8d6060364fd2f22bdada7de0918f63027955ed92 GIT binary patch literal 19490 zcmYIw2UHVJv^On;4oa_rg7l(vLPxq%1nFI>fCK{(LJv(rDJs1eDbic$B_JX#R3Y?4 zh0t55(mww0yz{=@Gdr_q?#$kqxqD~kckk|dBLi(}3N{J?0s?AXohQ$4<Hg%>O-6cq zHCFcQxQz%Q&$ZPFs!<#pw>MEP7P_v_o)HM$rpX8Zgm(#u|0B6Q2?*H;0RNLFAkZUZ z|G)HeLV^FKAtE4%^&lYmUmC01_`gHvHr$r}-<UX`@c-ACPxOD(i}}R=m%je5*nP{Q z+xiH|!8(=@0s>0<{{kUFW;P1}fhvLS6E)KS!kuhj2j`2{=9=hba`LF7Bvo!YSS%gP zL`~scn$SD=QvC9TC0!@9KgO1jP*aug>*+Fxhfb%aQMC-d8af84H|K!5x{hsUgrJsj zBNrD+85z=^RT-8I*IOa8nIVS>H$PwNC;Ky6Fvj%Kv5>O&a$C^<>pR?+4e0!#h%j+{ zI1+u{bj3W^MJOH_cte=-LUg>s8pFw&`<nicgXWK#nxMjPCus!|q!!UhbQ5J%YCR@O z9p}etL6C|Mur&Ix7c(cp$`#4(cwgYh&^M;_7ov3Ejc<&Ib<jX%D)v6>e50c`H{a?w z7NYmXj7%xCuWJx5ymoImMLao$kwg1;J18i|{w+s^I^;59Ez@b5`)u>+aN)BRm9HWa zyd&h0oMThL<P6DhW0E*MxZIIJoFSn_Y_3@L>_WzvVjK#;>q+tKpo%6ntQz6N)u)Hw z0L&8L1&sinEgqe;J&a)a5%_;>l`*}eFc`y|$dRo@a@tBVn5t3?B^i&E5HJ)KHq!KC z>MmfdNwb%kt4eORsk21@Y@mTpX>1VTZMKQm8hNj59=1|l+P3Dc^dgyI_^FNMFCy<H zB4gyz_nZXc{y&$42~`17{lx(c&*`!*;!Nw_IlV!CuSz%ED>H(py{W()y~{Omn87yL zJYlt15E5ZFsT|wdyn-7YXHv`r+0X~a#A2+$O6kq@-vIOV05~ReWGRGf`!BK~P>k&3 zl2}7Sti+>$8g4zM<XryZ*p9ftkY@*iPw*s$?wPZ`yKBAij$aGkvhVhH#Eo>sjbG+w zQ6xtGzK|5~tC6M6CDK6O_JMmA)3`o$tYnWt1q(cUdq2)#k+$%lBgZzeDDCl)2?0z# z`tDFVQ%APH@MF!dr}fozVzA2b5%v!Bx9y;h+y)v?_tew^$Kp1X1Mc=-1zw97x!VQV zvk*5RFTUN57MBlUe}f9z<CqKj2Grza#0&LG+&L>WTHG8xl8X}%$+k$#v1<?;g*{^) z7S!u^3B-BX_0`s^SmgB@g~Li}Ykx~qff$nohGHER1e8Y=i+X~Za$CVnR8gXi0Hb&G z1-D%Ts|0M<mPT?;C49p$q;SfP3^OG5lIQm0k=BAbctP&Y=X6!pc%8CYBO{+OOD*G| z%AQ={Ruc_ieWsq`m){ot-|{R+OBHm)wa)T})4_scWb0`(zXQqov0}|Y<!vKg`w&JK z%iigH_j`O8J=l*gnVXOXb#B1ep799COpTT@ONt6H(6n!obLk~-eibQtJ542h427vY zOT;zxDG4a!vrd@zLzfaW?Y2$R8J|@yoXY<|g43yBL;ndOf~i(Rg&fAF9hw+v!JxHo z6NjX!5##_>|E~YMaB!?gVZcL81SrDY#jn>b&Qf}e{j&I2Rj?YLZ`9f4FCej%!Y#Ge z54elZwDaK!3xOS>gF2YSNcM0R5`I<xG4Dax?=Sp;2;^t_lmq%+?+#jiXMDHasL+Ao zhh!~LB{hYHBTOtna=2yhd8f<hA4S7tL5uz(vZHTt76ls~P2f&$-p-ZCCcm-SEEm3t zC3P*OMJ9}N4PoEnf8t|FDL?=^EWlijqN?0XNGK%8J}gy-^wS@QuSqBJ<YEg}k6cT( zq#3^olq8uW72Fy=c-Wb%1&Pmihep#U90xDYYUKBH+I_O^f3LWL?O5@^Tyc=X0)Y|# zRjx~k4$LFbhMw9w*U}5of!geT`e_yzDbBEOd}UCh`%>^*mBmW`<<yI11*z!2UB3}r zn&m$iPi^FULhLjeuDQjgO5pcDNa8nbslBrv0Z#Sz<rB)h=S<C-R9i(IfQTZYaPoXX zxv8CPsB`B>IGHPqt`Ij;Bx|b3Q*2^017bg7gGnlB?-x=GUn1KrV_noOwxr?OM|KZ; zsU(z8BQFJlLKX)<c))y=%6gS)ID#3RTwYLqnIS454vS{Pg~Q2nl;7$4ZV)m?=R8-J zpJGUOa(Wyt-0MK*n923bSWvOQ_}y`Frhg_=l$WhjsOC9KlxKZ=RG@*OZOnP43Q^}$ zEVlw0Y;mhsMw?aFzeCRw;W;A-)dRH+!UUbk12E-LDZFqLx85mZ&c^G}B5;+bhEXsc zsjx^3hamgwmt$ueAVJ&5>hm@yIcb*WnWK83x$mtP0uUY!;4eK_dTI+s%X+{z8d*{& z$$}u%4(xZsnUn1b^ClkKsg=EsY{||Oq=;TqG-SxXZ%xVY*>R0~zb$o2-8R+VeuVwx zp0mC9+|O%O(!KVlcvi0HrGk53L|=WYtQ2ojUEjuLsQf@RImDU^!0y-m+4#69Yg?DD ztroo+3@ZM86ioMJz^?B+$xgklHM88Uk!CnZ*^9Apz>$03Vl3S?^@Te{7vq{L-c5pc znVv1ss=jg2t0)44!GSztgMP~hc}^2`wZK3zQGuBF>Fvw7A(T(RMpt3|=Ziwdguo*^ zn0i02qgWaDNGUfQ_xKrQuar{Mmo;hunf^>y<vs{TscEu0|8M}?VrIwta%muG%qZyD zSs0j^<$8Y281yNU*pZ}?7^v!^geLNZLo|Jv(@7}$?kopW7)=P??XHt=Bdx1j@aO0? zoMOxglm;-IFjoDpg`^wSWy~t3(yE`H>6Xdv^|y_9$`2co44)HP8!8a|>toBuNiRk8 zD#W8jDC_|Pkz6%p(QczAV|0&iD8#~9_f60&G;mtA+Nrs7&dWPq#CbPPa)d%#1xz|y z;n2llM<ud?+#K6v^xV#o)%p?EhAzsba)sHOwck^|xzJ(MGxK~A=C!_A=UACD^e-~- zy3=8q-@&`~&lW%l*VG|C<~j4S&3`?4^i)KV?6mKJgHqsVkRk;N2rTPZQ@SBQz&-NG zpd?B&f%}TzGsf^hBOB}Rv4W7hU6dw{R9>{Q;bYfoa?D<PK@NN@KrN0Ge+cCn(bNdt zfo!d82O))K;%~DC$U?>rrpxBQM($q1D6Y#@3D)vUu}5T2eyi4G{k(Aw%om_Es=zpn z%x5_covBDtrWWtLeXY<{=D`Wluc%x>Y%>7BR%_rs!6Hc_l5+fKhdHQ=Gw5~ENHQLJ z26E6yr$xjPot)3YpJ934Nh&oHN8LA<s(~Yfo|5F@q|lUzm<Fsn*@-0d2u^WWon+zN zUISnw7h4=ON1w}`!9`!<EZEdzXCghg*x{tf>9bPJ6rO@caumHG!>z~Ye+*w-ME|%~ z0>5=@_i5BPYD@2Z1dDA`%tp9$c55;1j&3bXyp8R15D_T!(b(tS{*mdD7&+`{=9R!l zPs_g%oK9}tOEkU^LejA}A;I{2`-=CPTr5gs^D)QI15F1`1X8m0jv^45;DA#+6AI?x zHCx#AB(#6Zba6jpn-1y+vJ@ya>ZLT(K~lE9a4>FoYMLI`U%wW_Z1K=*Zf8^C*hz9} z!nO`@$9}BKWvQC1NY%J4&lSscqgAr8ua9PwiCn;BHSG*~U1(&VU#i6JIPA1gJ@UAi zo)mMu5J5kTvu;rC^!v193G&r{8WXPz39rxbo+9QJlA&q8<{jKYU7J{*HmlMZqzZ!` zza}<BzH!ht=I*iq)ezMyYZkL8LbvK%m%+<Plk!okQh1NG35G8`PT7{R=c|Ea*gXG@ z2>!^^zy1TNxo*5c<^cf@7nCqY65oS33?k(4ZLpjx?)Y`m8KHya$Y`0yXGQRaE>4Yy z2=?idym!UXOObP|=Ac?mU^IQQHy!4uj#bmbN71BaNw$)0iiB$lJ^1W%0;sY*l#Zs| z_JrwXzPuyXB^5X&^0IARK2py9rTxU$3@lD5KVWP05V{!HME`P2(pfQAqw9|Y2+gt^ z+gGrB^t79x9~&$*np>Ge^?M&|Un}bMd4G|;E{rmm5ng4waG><WTMF3yjqho-ci0H@ z<9z5<$@SHAUQL4aG*KV`=Z)s+B3$U3%5QF%TCjwNFaCQTNs#7Z|7h+JV;YY7Lh4kh zluoGzmqnZU?C~%Qg<aa0g4C|0Dt|)~%`RoBmxjjc0bm+`AsfO9)#>2sVT{1Ol`d3< zf8;{Bmb05cg<!{}mYM-WT+7x$fP|kmR27z>y$$mqkaQwq3_V@bFHfNH9-ET=PIC(& z^Nvjm9|&va0Hi9azh4`<P{0t)sexSwC^3zB+ATm{YeooJfigJ9I&{}st<`*8rT2{Y z9&^A;9c0r+d7C-^)qwd~w6sP&FPRujK5e8J66Y-;E~K)l=X*7?s?WDlw^slN-P(ay zAkSD5#7ZoA(;wP~5Jraj63ooTy!Fx8&-v@f<i=Oc?AARA%azo{7;`MIM8_7bFx+2A zNYl0SIY;Kku5d56f@X=1G$>Uak8ahP@3g#z{d~C`zgiNhzC_*;Y6p>!r)OAri!Gv) z&O;(G>+Vj@VHzi4)DIj$EF`jUCUwjOI*jZ{r$(*T^A#v-2BF;dzUj)azOxDuMq>?3 zW5meP&A;(HX{uoI{ub8W4(N^l8MMSHfT27FT$2UQB}~Rh$EadIBeS-FdrS%)oMw=U zGb-IqT1`*+&L?!d?fU7EPJV~oyKaYki)v8d$K>-kQ52_Q$MSY|e|bDK`@-_(wf_cJ zD5-0Yi^EyjKHNRhL1*(ZE|Nkn-Cx1N%U(a-W?>~}ht|{MHAe?cOie^DCj}yF?-}6= zO^Uw`W#x~MdGc%iwNS%{JDT95W{5~7r?^7}-O>==L3!%Pb*jfmXPb_>XAGP6C|h%$ zTVR;sLM}i%f?}+w^3>WV=(EH(G2@6aLLdjQpl53PG|~aKat^lAao8g8mmG<H!JR1I zA~3_A&pMWivwE={#Z=p{+Vn>-->8ezWZXzU`D4sMt@s(-JjMlSurqwp29-+Od4g3= zb+zCAkXs=;Y)1}7*KgaKO3`okcuHArggrMftlBSJ>wHZEJ#jFZn`2leM%5_;V<WI% zci2X7-Rwte$PY|iBr|S)$pc4)!o7lYg&!1GD?0cZRc%TQDrPR3kz4!7s1GYVAtKwv zae56?A&dwT4Q)^$%iImBs}PT-8%jE)7$+v>sbAph>8`u-c^6}uE8NFHx19vDteN@{ zxRR#c*$n#B2+1m!C>Sv-UQjmV%dRnma%YgJz-y-SDidxM`}TU^Q)5NoRtdwTi9lxA z(pUuc7nvM~GR>75mV}T^Pw4MgZn3|Q@;FNvor>ngk_8(J@&`PBFw8{mQ`y`t$H<%{ zMz1`XjN5LT%own{kB2!N8C%9S_1G=$Wl8X^bsZaZP18G}G(R&;5AGAlm6~|Ln6$TX zSm>GHW&IDIIWCeVml!XPNWJ+Gw3tbcLLuS-ko^h$x2tb}dPEPvdD>I3)&VuO8?Mdm zS@vy~jk*-6I3BslnS;CJ2qo=~eaY>a<1E^rT9Rs;Rk`6Xq(nLq1iks*CPgD$VU_Po zDez@WwdQa3s*nUn2UlvO>j+ICnGG34?Z9fq7qcidA1J@gWSvtXmm~%8Uie$w*50VB zX@0w4Y`uLU&*Z_%z7JSlr8+`iZ!L3mQT93boJnkxq7K@ovZwk-1=*J(A(qTSHXq*4 z$8c1#KPx-AFrbu@eA7N&4@95m42u#>Wj82N;d)jI7}qvS@!ZS?m+K(nYd{s^Yim!Y zgfK4J#(0UU5O3HYB-L1-Q`S`v^@`|#OWyD!$93v{WpPf8A8sA<>nWaaQF-kA%<A#p zCu^K%7~=lf0Qbn)s1<**=PRAC0(8@G2`K|?(^>B1IQtpYGqu#-;WtwmX-g{H&xM<1 z%w_;iBjUxZBXd!VD6<Sog-9#_tP-EGXNjh*{=jg?ei4U)`b8t^l_!bf1S&Xnw6p`1 zEV9v+14n6&*6Rtashn1{r~DS22Di)q#_wFEGdXW&w(pNu8+E7qiF>$=20@mer*xKD zaaY7boK*;HQoMMdYr6f!4gKa_r!fhDDdPM=Jv!+$C28JM<+Up7E;r;KM-+=3h-`?F z**Gy;v7vyyl;a2{cV4b6Rl*Q5s*w7>{MKpAjelknH*-C|cB-$Y^*uRb5%^%1eqZnK z(0BHN{QZDxNYJA0yo3ZvO(kukDih(30SL`g|6#3Q@JJ*9^HN=1*2fLfDT!=d;u38^ z2sdarsQzfnd${6fA^xyig?qgm8rPa5RGuO_E>LXhevgFzG*HVA&-Ug$J~vkaNT%@= zn6ji=V_qWIR{K1Q&rdorPkOhk{XMh%^1VxH*HqYMoOx`{G|@-J?B&t^L`5gcF`wAC zp_5Z<ugdS?65)(`U930<%dJb{z!iE(h`D)9jI9&ug>GjhV3Nd5d!E%sz~cwQ2Ak21 ze!T0Zkd><f<0V%Df#&nn*85u>UJfx7_V*JZLoQB-1`oXX0^W|a3Y9ZAsb*qiaPn7n zrr)V_fz0Lk-|KyhXImZ4W@^5}7(exTI>+RRZF*%V9q3M0wA!fuIZFL2h4dcQ5NdJl z9UNB{%l<CP5QSgr^cVZ59iZ|(Fw=Eco2Q28V@GyD5hd@1YBuY?ghY_>*W+9!ox6(? zToa5f_njJ2Y@|GxX>nKX%b&5U$(YMVsw{oJ8jYg;bD6{KFJQIkAaSo$aF^aLKs1S0 z4);1nRdY1@^W(ne!c+R8?jI;ku#S#^WBX%&Ic@!h0Xcc1PiC=<*^#y`osEFsBsix* zi&_&V>CX3XPpL!ZP6NqR=I857avd4Hk6bRB-f>CpSmyod=<d<A<{+nh<XlnN+@zX~ zu^BQK(Cix=H@g`yu*82ga<jD7e9SnM>4qv5>x6x3b$41QX&RWyUU^gw7wT-V<~9KT z3E;&&a3M!A>9HRxt$c>cGB-!2-T62FS}b__CMv#I3{S6L)VfS{_#q1Vx}iF@{CaTZ zb_27(9VT7QH$T@G&3+0&+8O=eh7ccL3Y#weov|<avg)7J5&g|V*ec%+Ox*HLf6*nA z$E-bZCiEJt_VOt??JmJ*DR)-Af8LX0d>(6^RC>ckIa?!4Wz35uiZPH6^`agxs<*co z%Et`4=)XLYQ&d-~__6qu&ZbCaM&sY>q5YOe&BlDkrj*l^C?8dW?O`d<Gk!k~rGw~N zYjWBeck{$@ZKV8})FGHD2j~)Dv-Pd=nH9H?Tw29d!;Myv&$6}b_e}=Mn-I98{T=-0 zIF<7_SnI0%HQCcx5tWRrr(NFp^>)*@xSRZa&`@))g05dos!M=;m=+Ub>dwVY58#gX z108xqa?H*e@OTKOOZfzVtKq#2G?uFRFwi*V_X*<)?)KD}NT|lds7q`eMK*W09{H>w z;93Q%A%9t^QjR|{y^HfC88h{h2US~UcQ+L-w|J(cKv@~RpR2o=Jn$Eg+fi-d2&Mi= zTFC!%YF&H6xxCWkwh1lLts7dL`Exj-AUpJSh_mRa2y4#Rt(^RYHR);nLNwPaRUuZ~ zU%uO08GJFL|6d75QP{(p2?4)X6JIG`T-^Uk-4Kr^qA;v}kv|a3bpo&4!4j-1jswz$ zU}}^k$n&}d@?c@bY@XE$PPADfWGpBRyz=Lj|2lS=_PSBH;yjdLA%JX8$a7A}o*kij z#;ueYv_N#|7gL$|GPadXLA0__6cPJA>DPl~e{xC1V|<TS3)5vh(Sj|ZrmsU>uVY&0 z_wIqnm3<DD6}W5xW8{NhW-~)f0dK1g?|2pIqg`yLXq<8Gzi=`2yOQO(3-XURj-aFS zPzFCPC^HqIrfYkYx1UOJ>n}xIP#`r&%S=Ra{yM{NhIE>gGxsQiT5dTId>HMLbqq=r z{LM4eRjPQbq`qcbV2Ny{TV3fnR|`>=@=QIBB}aVS8~nF6ogiE{L6_sC21cz|)%oq| zEWO7!uU|A2$$AnCoCye6rJdn3vA7=?9Dvz|E6N~&rRA#2n?l_z+$<_&##?T>yyVn< zCh|l6wqz49?+4V+TV?FW+c)=YXtc;t!qx}5Wr+G+cS1nHTS(|Q1uc$@GqrziM+Y+T z@+k`R7KM0hVFm#;dWx^8U~|rL|E&sJt-c;$+SiP$aIKQq@~@s4l*!4W)xWUJ>yxkR z9;9-$*s+fQ)k?pFHQg`pmYl5|YRm^PWDSpI3Ol)E7NiS%;fE?4ft!cd_yB&Kw{JmS z9`g}w)Pn56aH#g^qW+5#RZ0Q5zAm~phB6^U8NPYk(n-=!=lAfU8%z4+>p27msif0m zd7w4up_1pPFeS`4Hy6%DBA#MXa21PEU!fXM)_AsxoyqOo`)k2p-gnmSz9|z({vE?N zayjmycD2_-3M~LDK{=dHsQ4zetHqrA^{U=pebN!@cZAF|2l;3^yh_nVQgl|!Wt#+s zsPD{r(7}_=*(8g$;ky3}j94L+;9GUPa=2oUOKe!eXL5<fr;S?sq;#`ebCXqX>kG-5 zuezq#`qKV7b=nF1Bvykvu)Gq;afSsm+fx}%ea|wr+q0-Leb{6WTP!O%=^7{nO5-eU z4v+)V_4Svvsupf6&A{E1bRLCuDA6;iHslV;NWUqo)UeKf0f#vD&@TJN19Q-(JWps& zcf%hepcp8rl+{Mlh?ax<+_tutxlrWzTvg?il`67HodFsbq)_#UZP91C;Vk%ps^Qn! zM}NJXtBsVchMm_p^0xm<t29Wp4`rNMy|`v-42L&7U|~uTRO~A)AGaPskgFV>WZ0ZZ zd|xDCSTP%S4|QSpA<Zmsk<`BorTwrR>;Ga#O*9|F5Q{aigiAKQ`F`qyfK^ccMtXs8 zud^a~Tqbb@2L2g4TQyhGN-0Dm!nx7Uz7*)V>`W4=fn8v78eD1J!*{`;#*{H9b^yE0 z!a=F0x#|q<rF9Giy6xw0z1LhOWxqJY4C9+D?EpB#gu<NipQ7`Ra%Q8FJ9KP!tY*NI z=V>`NR{P>L4f9vYA7B-P$$v!JwWtF-ol;>Hic8Z($Uecg$0Os@G;$3ehUOb-y1xph zdgdFmSl*ER(IJb>TAn}(CbpuT*v)4OZrc+49-9AH%YgYV$8k`WrpD`q4Lz{`<C<q5 z7$n&COMOtp4Vm~qLd7HVR^I7`NRNbRO@JHl6EI&k>t;;1;SN$@NDCkt|L0nsZTLj= zU+x>5>LDxWt<q9b>%Trjl$~ewxoTY(&h8`}!k9(9m^oK3-YU!$Ir&GU|5V<84mL)< zv9RQCQl(quc-{6B_yPnknDEDh`bcUFl^JD*DC5E$X_z-HdJKwu0(g9ycJ`Ub;CMF+ z50wt@qx6Jvyqe)0`?KUP2euO{sWU-3Dz3Cc6Yib9s>26oIXTi~s8S=p<07A#QoNfX z&SiA5;5?2>2b=t7%`@yz@s2rfFWIsAf{af@8HNjIS2SShvvg-xlbM+SRxu~$LWcT< zk(<J^esZfD>T~h<Dl<yYi1yo^uvearRrF}y9hT)#xMxGKUbS}mIBeB^`qMQH3LMNQ z(F-=_6`d?2(I)o)rU}3aYzc5Z^E|SNQJ3v$)M5o)c7!>+S~vgBV7%BHzf<+jD+pgn zse7+kX(bCN!&URv+SKOyR}W*-u}{;;UPoVIPv;VY4J#K)rlMI|hlTJOv(U{Aws-8$ z*sJ)^pViV<(fHau;@_UiTi?-xe4L)7wlgz9C}CjO@)t9o_FTNBy>I{|j<4GGYAiyA zL}Q4~Kntk;i8*Ukn6|k^UcrZdx8H8$<=LOb;@0eq>+n;ebdnGx>0y#CC6{I13N*f= z@5s96Z2^Xg|FgOt4xNIzRq0J~$Y)qbu}C_rd7dNp*T?VTCh)MnE{B*=O`H$nvv=B& zCzqz5EQ_8VpB!6(tkq<E4zjQ94FVuS31!mY(q7L~wLkDud^Ian*-aAI8%e~(r1g8v z*X)8~9Z4D<X}6f|E3nZO*+usQpWZpPi33mY2d5LO#IPI8-N~LFi|%suJnS*i4{+}T zcdkMN{g(#haq+$orFd3bITo{9xlVd0cW=-b@c}hcFgoSG0L$Le3m{Okcp&Lz?x$N& zYOK|yH&@2Ea2CACQT@@US^M>~n!mF3g$Qy+-jK6|nVqms3E@n-xf&8?j}Hcm-hZ(Q z2N^>hZp;#&)@%Z6J|FLq<ZShaaG%0bFoy_O)@qHS%|FUIJoD8xQ+2I9TCn!TWlT<r zzdNNVTtCeB+F-idT=*3N{}mu?`SH+lEdn5J!sz4jU#`#6NBN!XZ)JiuII!kOe-?9` zsZq+#Ia3))+BJ=qFU$^>`qb^J<lLwvdobg2bangh)UON!_Xs`kppOTm!TBuOWh5gG zCc8Je2a#MVuY_3V-?cexXYVb4KUfOM36wJ5<&$i;+QhwoMbqrO;Ag7G*YbCE)!yO4 zGpo>*JyF2oz5f@i2j#NXi;i1%SFoR~$L)iPufA#26ty1XBfe+k4z6f1JpwSFE)3oG zH**Qf2M8hgWMNkWZlJ4gm_5C#s+S=Pf^vXY@)|1LD;p`72hD{~>BUP;Mm;aAXND9y z0Gps^u_^{0%_=dOx#hps5)*7y4}5-IO0pfy{`2J;?e0qYg?ypek4wypM**mPhR?Wk zq*IQaZ@VYn=c-EgMB`Xuyj`I7--=00(kGMnXNeDyAR&W=06GDq?hQ+GJ9dMJQasbQ z!)AL*bcRq+5GBiFHd2LHN~~jc%d(x&_0O-tDxxejT{JKy&C1!4mwkhm&vS`hET4Eq z4E2eg+r@k;R<$Xv4T+=DL;Vr)NiWBl_`%vj9nkXhPko%@R@#KN_L&4GGZZc-=zYRS z+;#~ypMSqBsPkvNHIx-!@I2u}g+B1X-6M!S=WS2%e{;)t(8U78@yVEp_@`#v5Y%}= zVK0upy3iykCMzc6T0(x1O6{JZg5}q@X8%KbF(0SVH(0pil)la%)x<N}k&s7c1MruY zL@_u|>;?E9n|UaW6KR6XXcyn;i?^~irA@SYn|IDWeHZhYL(DPvZ74!fV6rR_73iGo z6EN}b+ZEUATM4-dB}9E?QfKWp_j7b!2s2*-8#=Q7*c@fBlbEt~FRx5%R9(C*OjESl z9RT~k5o4kGcUAdrBc((wm++bI`Hj6otm#=M<-@L`$JbAO{uA25GX0$5ft{IIhX&$| zV#38-*9$Tq4YP7>it_m=#i6!hQ-+V{YRm*YqL!UfFxOWPuVk2%{VonbH5QeFHxegI zXB=k*R)nk4or~dC1;$=ie|{M}Hn*AGDrVnB1yzwWmo<3<`&2vQ<2fm+GY}hwt<M}Z z+-DftdS$;Kcbf{ZEkD<6&KwKVX|}726q|Wkx|u&P99*%LgqJ6?^CrExZhOGdurSW> zgAB|Sa9051I(oa0{eCrSHXgb95WK?~wExdL<aU0Gw;QvNF}d$EREzqhcSFS=zkc)~ zCc?hrQLMKlmbbrc=v>328~aSMpl{^Y+yn+=VrhFjOxDxLtLqotas>k>QrAhX$?G<{ zitM4pY2iGMckpdFXFH?OrO6K63PeH`p0}MJzvfB7`?^{x-cN<T_`QLTGwzUCs2l#s zA;a~VFNk1q&I_Pqff`>_cCp^2L`4h7H>&crXhNi;Q=DUBDJJD@I|W6$Q$k3T$z$?A z=l{GM-9PFae}4m9mD|0rY+>h+Qmhu4Buc?BT_yNJi=X|5+GaLCX#MM*6-_s_^A_v0 z-?1__*}+rFK5z9G{I&6eeTP(s#USg^E-=#ZIJuV7l*!{iE<@+)xF;X#wqJkW+?dzx zZk8W=a~?)=NdP~`E<ggG9c;4N=5&bpU}Xkxgm?Sgk@sGzkm1x^l9>eV{(JImW8GHc z9?sEn1Z?PYDz?vWkr!Lj!(PiE(CA9~s2`!&V)R?uRh>WcG)!olg64?{_I?1lP|>Xd z5oP;$liVOH5LY1m+PT7=n$MQk$ZtaPGt8&71ukeaEcm>$(y<s<6exE)JzlGju_M*T zhc86>koHS9q;FO8n!Cj0`nf3t5-r!Zz@$-Q<Z<3~EU)JYZQYIKURSM1jmnt2!=6O% z{(c9M8I@0hAPpM&TCv9Y{P8q0S~Q_kid0_2%qIUDkNuGw8B~#lIlTI@ECvs|<*)94 zntR#*2S>Q@>xRJ0QAh-^CVgudZNNwGColCQ$b)7@l{Y_d_6>}x(eB`18Pj@aM*fVD zpuFTW$ZNV~3g>vuX=Mj_qS8>E1Zl?zGN$}}6y17PF|X8!7Pm8Sd|JNL5E)m}!(g+& z&NB*CX6W)!w{LPUI_j6%$5~t#^447O1FGW~>OX&s<Zk&{KGMEC{AHwd;lUrS#TZBv zHv()9g8=bmrI0X*ZGw=Qe{Gmc|1i76!_Xl)Tqf&=H1uH_5+75NEYxPEl=tCb<9S!b zH*2*k?mw8Kw~6t&RLyS*`*xH)LTtg+bTNQ<5zd~Ie*(eug+<K;7%ijkmu0!;mzve) zjoTMxJ%D662<Fj~1j(?Ee||sDYwQw{%Ud#9Kj!dR&U-s&DON80(&AXv)@r#gMbKzZ z^l)av_S_o?WXWq^J_7sld_7mhecKV^I?~)4hT~U36u6DQML&JkE$m&nJ)VE>NW0JD zk?e^R1r<VTjv>uPi94VFVij@0v+|yK4Y$t%>34$J{0YMN0|K8uG#9}27rQ;1Y?nWL z8;7|JPM(44a)~t#WNmvf(fpf4)KH2U%6W97@9oBKa2M%9l+l$NoVG^mB$AKO1e2sd zU}EEm1cU9pe>OK;5ZV!anl+($b}V<_44?PS%1_Hjfu)~P8^h^7hrH+Qt1!5etx^q* zu206;aJ&~2@ohniY{?ph<xKtjm#mh2O7UNN_}YSVemzV&xbqGl_fj{}nv`Gu^IW;z z(3b|BB&)%{JD_JIx1igV!Q`56+<~ba>8GgSa#a2OoZ^ODzrpt7=!Hl1^C;&IDIUD@ zB>r7<7aPcYG0r}uD_0rOO$F=>%*1%bYpu*5y~*m6dN*&yaaM)5089HR9<kj%y`j&U z@jayod#~)><qim&x%gCXWmKUp=j^!wKN(750*PFSC?Q7yQi>U$-tI`eyI*^+jK=NX zk-JM}$+-P~TzBPR>yqDXMN@q)jM+QRz;w2$Y^b7=jigh90?2jpZX0f4kRi)^Lf~<& zDBH0p{!IT~Uf4@H(wNA?lf_?Pz9XTAsbiO61=(6Wi&npAv~Y_f2EjV~;L>$dykTVC z)HO>QX0|Yh(;IeET4N==cE>OnIlm1j9&av~wJb6&n^gjTrj`2g#^mnMeEFKX*};tY z%Tmw3k2Z&orVn()Do;I}wP;|~Qb^0#v8uEznwUh{$Q9muq(w1yZnv`gQQ=7dRs)?u zPqT@j`0?Tgz<<M%Ry0q#an#DK;*h%Zw+LJ^ag0ybb>RYJhWoJ>Y2RxK=2;b4Pnk&r zr142nh=*`O*J2~vsyIu3!eevlO>Xf~{&;@cg66SQUZW}7=tZDGj6}X|Pw2GQipcDT zRF8$L#ye%+K5gIGhyPtB^fuhB_KXFqeYI=|eqQQ@Kq;<vbWt)YM?(04j*oa7L%u7D zrB@PJ?)?hZ-Kn^RCcH6(0i^Krmn1bIif2nxM%UK)xOT=+N>0y^xjuOcH^!lVe>)|x zqWu2fqPF#U*$w71f`&S7G_WlDk%)K=m`&RC&Y2_zhlvdYWc*^tR<Dwsx)NMa080vV z{R>{<*`d#WM$BwVL#%P3HeP4e*x<Jv3Hj4?RtbkBFr8A;=dIA-OF+-83@K3&IF2)s zvuxNWQ3p^ud1z2JK<st8Z2a6qW%H1m`q3&khV`nEqIX5-Gplm%b}F_LNut*X@-4Lo ztd7(`Cp?)Q2a511V%E*?8Q$(?zbfb6FJP4x2ST=~yNOi3tI(eIkb~vUPJLjinxFbP zq6+VP8EfUDiUg_dZ9uXHwg4vknej&U+w<0b;>&5S8L&jOe<A&~M=bM_$xbn*P+Vb0 z`4)OUbHRDd9FanQK-Zs8wkF<0KR_Z5=DL81eO$E<K9JyoGf%~QnHaOj+{iY>b#~$I ztQQVarqq#XJYG^OPZOG2pbGDfUbdqU=PJrx_R`v$B5(+a85rgLdxS=UclXH;DNqV0 zXt>k4vL1}EE^{<D;;nxA&-T_}K-oof3;KJJR!hyx#0kAp{;Xb~(_Fcu@*V0?*8J-} zd8p7hl~U0aWT|?ZPiax67}TxY1?{Smg_d-^f+mUJZ=t2K!Xod+(QPA>BJyY3?BC`# zKK0H#{3c@aSM$}`9g@Vtw{N&sZB8u5Ns%QExpNL}V-D?^vwoW8&9J+LxgYw(8f>dT z=+35`6m%|ODN<FAP)cLMfrgYheDCqbRaA#}-NyuOZ(oh20D35ewqvJx=K1|mb_Kf- zyRk%FdHXz--2j^R9%0|^nwPXss%y^>$3l(d4yhJN--bh~v9**f>xKLagd=#V@9#hU z6`Rs04T{T|@&r~J2$?E*T1eH6#e`m{Y#T<asF}XwfOgh|?lyjoX7?!#+C&9SfHbvd zi#-=MCP_|Na2f+ozdaBQA?2qonEw?F1wI5YOHcLtX{c$8RX8f6=NNz6=xn(mtV86k zG$)mbXG&);d4jp5Rx-S3??puRB+XpB%bdufRPuK5pq?<3oiEJtRjz*(*|tOH0dHt= ze36Wp2B9}LLDah5FU7u0Q&wNE9XUad0wwM&N5RH4ChwNWQXw9K?1?p|uN*lpnJWqB zDdS~s4qhUb$Iff{D{1Yc9cYRp9h;KIX{^~x#j`m3m=*cH-eJhXr%D+HsNmTBe|*vR zi`MU=1mKS6Cm1xZdUYm4VsPk0s_tm5!gw09xFd)|=I`fT!ZQf3HpQ}qEXNX1I<|y3 zmDpWkC2e+z<TcfMrH&A7d*;Q4j__nwyI#+~?@^MQ@m{LEFEQD*mO&|SX#M?O?~{4U zq19G#fLprT!Y;+Enw34iHL~+NY8NcXl6uVsU+P84dIIyld3V;_I(B7%Q6?}MAQ^Bv z1)0=bI%3EPTVS4ID=2+k4XW81mNun$@Mf}!`OPgvm-uEmQ1gz-CF;*n+m1WUL)eE( zI|H8eDkywVg1xZ!H@NOs{5dI#ia70(F~J)|y&K^$@whbE;wDt2G;nOICz9*0MBmFT zuqP+VajCh+z4`~+xf~}LJQ1vn4-`*54pDFyXeo7kZqJ;ZBOv9T>A(;{o#Ct@@7O1d zaov%psHWW!lIwpNJ0vW(utNYw9f#2=h_uI#9>E%vYRU|s%7qF&w5>tZ{t!TXB-Py0 zPZscNju~%IHD<*s5>Jr*kT6&K7;BC(u;Ba=u@N_os~`Ok$`x)ZyLaB@5cfTT{~5Te zQcdvVqa28C(ObQ`=A7r?pl;ExAvD`^3BQ$#E_@4l0_y_pXp42+!d;;7EFRS4ys}tW zkrb$X&-6|u0G5Vr63yx_aVPEl*2EAk&HPYp->S((-;2uFg@OgKOZv8_s`fSY)@-}@ zN%gX+y)6G)f~yDhB^gdu*F!*iiYH$pOIq8|{)|AP!%LPDJ`A(Jbt#50Z<EhP?s&nb z8A`F18Lrd6{h52n(kbn<AzSTi#E5fxObFAX&O8pXDYfK})!uuq?daQu?>|mw6|3(P zLW8bv?vGxq^MwRzj!yWBG!|jhbuw_Qd)y5>n>s3FYic39`2<u8LsGz4iSSL^reBV7 z0$K~FOk{y*QD>S@p5a91J;UL5^!-qS*iW=8Dd>S~U;lAbl52xpE7Xb<<xLUuSksFp zn%bw=-KMy@epn%YI-YNbO*zurleKd+h<l@Th>0W3%4@j3nbwOeCT@AyR6xUvV)*oR z6kcv5Dy0Y4$_Yo$**XWZNqpJxUN8^HcckVTQv9*u0Tt&DA-rXKcA|c1geH?WUF-Cp z0IP@(Xg2mss_nW8-vVs9nRtET(f}s;h0kkCikFijCJ}Wfvb_AsBXhX5RM@zrD6^G_ z>sIkH;<1SCW9?Q#U4BThiso_-<nLZ}CB8MuB+2!O+k!1I{jEXFWfa>XTME2@?;Xhm zump#>q>nik{|R1p|NeHh1C&nu`be%=eA!CPCBEwpwV}tmus0~(I;_Sg)`o7tsNYZb z9GF~x-ost@>)rWV)2CNhUG|tuaV<MKH<KsL2^?xMt@S*D_}442D9djTm~`Jz;o7S; zx&6@NbY=Zc`SlXmmMeShwR%qI_OLFcFlWlW2qiYfvH~sE6K0{g$`5gRm3{Kr43F|W zAFKo8Mxjlp`&>FTkGZlhmI(|aiR~q}p#F`PCY2PU(Rr~w5q%fc&5Szka^U~AlwL9V zGVWGEi$BjhnOqDnXTiNF)9Is!23=FTrR&m%sc-ELog#uJ@e4fS5gOc2h$z$#q+c#P z*Lk$=%cWD+)0TArjv1TT;g2ePRjVtd>C<KES<0LVD_R0i8gY+mEDfHkB{6LZw$!gZ zNGQ2b1I-QJ+U)csPggr$DLjqVKwh6xd=I4hMDI=DwoHjCvZ>U|lC^C9J@{(5h|<~M zUP;9LS4Rent6tz2GQWh7SM7n9a+~o_AA=S?OGpV4Z*--P7G&IM>awy&Kyr}B{ILB1 zidlpP)1zT~0L8Nj-e~viIO(F>)vU0it5-rZ|0b5fHnppITqd%+F9f6HTIWA_WRdzo zlU;mRT0wA(X>t4S7xvu&d3)&dGbdwElK2R-?Q}<)5>nn3lnyEQ*b|ZeZf=jG14__2 zwmSZE_`KX%k;P+uj%}5H*a^bZ50+7AwhsQ3v#K^BLY%1jAW<t-Y-(YT_^rn8((vl+ zrm*@l<;-r`z4jq@_oSJJVc5$qYBprrs(@vT;5=)sK5I&f(Lje4rzVhoc)?Pf2y{-J zbYki1iDF0D1IsJIvlAsX48rQ{eU|%TFhR0@!9<7Ykd7d3ywX?yYDMN<(Lnw~ZuVlu z5fM}s&?BesH>{`eJU_5LQ{2ztW2K8#%9wG-&->a(UEABR5!#+Sj2KuV{zR9#9vXwg zI_}SprWas`lHo9PlOugPC2WCrZ=l@5I@Yw5X4%>`UfE_%y;JUww_?_<`mKRD33aFl zYKSiF4;VLyv?s-#2vpP)9is&qbDRWUopg>{jybHf&b`NoZ@nc^nv}tSGKe%s$~1gE z4Jc)R8c&%^m{jf9wFrU48iO_^lfoBoDOolvDPx#Dpo;us27?Y{FL6hFH%ff=GbT5@ zfAsT#Kc(cytb9?ysH_+`*KClG6KW|tE9QKoV*92GdP$EM=!wq{v;|DAXT~`Yd<cIe zK^a_{dfK_U%FvelA<|7!=979PcG;EUVmzg@6R`G1j?A@NDez$8-rNNRdSgx0!1m1m zawN?*bu|C}$}CCC9oW$2S`#C~u^%FFxpJ8!pC<fvP7h`|(urFGq?4mEsOY_El?o^= zHC|mHTK6=Kmk3j*L~x*6kG<-Qi1ASD@$1NvZO&&Yn@iCg0NSXP62&!H`BMU$q)!7T z8c4<_tp^Q(4VgLP1`z!jB0gNhSTN_&@6pWr7EE5+N?9ic=sQPxCOoewz9Xg^D#?eD zhYszV<&}L<L}lUAtgR~Kc_;?LBF*yLHKV&#VM}^1rljhwP4E<_TD{%(<j1HVpU#wO z@ue9&E~#l5X4;Fb2fSTWC^cAb0=BR(|EFr9!x%w->G@NbqLR7r(*hw04U=aPr@+os zVl<Twh2&dIwv&t@556!(bdD(Pb0hZCV7y65y)220ZT8*nA~XYz;-ECk;8%MUHGO7v zfrVP1-mO!D>(A!9iiB~a%5sEWQ)cf!erqS`YzIl>=f}d6<EF^^Mvol@)(54`GY9&l z0+=YWXcw})q`B4<&`eb9U4%e&riI9-dF3vC2^bQ^L5@3PQQ{g!0*+2Giq3=H=0?2} zFx(<vJhKr;W{ynFoZWDbZ4<mpSm}6s-nT-Axa`cDJmsRRw1?N|s0ewXKw`u3$i{!S zq!h9{*LW<042eobb8s|yVN9^#pHAYRHWq3<Me%+J53X&u?0e*%Y7a~<t7<{z)2KIe zQg=f$X5XTuSmFFXO`3BjP8$di#Gr-(yNXfyBChT4q|EjA$|x7`OcH)v07QfTHfdaq zpyyj8_22RnU|)TT=R$E><;AQ<2<>vzIAM;ka~*Kdng1V&#mpbuR~KHX68vj!$YlL& z%g2tSx?2%rMhGR<=;nyXj|En5=j>aJtQhFt-h(|^nL2jR@xtZOEIFcP8^<(0Idn94 z_83hu8sNNRy6_IXEHt2iU2@db8*31yLBV-#Sj+;JG=K~dC3ivazM>b<^ci`4qa+4- znn`qMMeiU#UJduP4LZ2FjQIPRr(@*ICjNQptU=6$-f-6GVlYKEaYC0hPIS@v8t^5E zp|>aXE89iZ@_|2?;P48XCio?-2YKdRCJXexm=VQfi=~g@++v$lftU+xQfN$7kK2$} z>tna-rtA;)g>3gm`YE+FPB|Svtx;dRK^f%BPN)x<=~(WVJyv+-V=OF@ywlcn)iTO) zR~$Z7U_5}=yx{0+G(!uUZiYLe|19>MylS!?1ek>vzkMDS0=i;!xL79X8ryvg)Vzot zzIebBAio#(cAxd=6%DCz!@cv}+^BZU9dMT{Z6$>N=i<!XLkK97)}bRr9KF$`kA={M zw8j`grPy6aItZ|QF-YEu*rIi(I;&aHhYm5!ao3M%owmDm@ya_-#|E+!AIcYQDFOSo z*Wceg^(m>A#)Ry1ERs|`24-tJa-4BZj=c3#2{44t?B}9)m>>>*wLz51G$(bOY7v5s zv)m|-+Pse-wam!v=ShJ^v^kFpy14Wa#@FQf+PgiiS>n2cRm6so;+L@wcJ^hfz41pD zlA@>tz60em@=Bv&x<f5(k?3Y|UTTAcP?gvzp7^VePoZse2v@<+vWdOjblXq(!#PJ$ z6BM8{JzFDp)9zezT1BSd>s^F?Oa9dpYkDX#5CV+gt@9Q7we5M5QAV#LdOPxXHLmbc z3>lg+f#lvcHJT|DU=5E4XdnYeDClwp$qWwUnzv|SJg2hZK1jjZM;6Vl1Jev|rcr+! zKD(<gUHix{6Q5M-CxVXVmZOY)`SlIj)Bc45`>+8lR8_V2j5qW!1RHn&<wcCoN@Q|= z+SsDnpml0Aa-r)FCWKK$pyF`ZXv{z{>i*%^jgxys+Mgx5olaE};N`mx_N4tS_uWC^ zE?a>qjZHmwEE!G+^Fv5S_Rh-$ooZ5Ct$ioksBR&vHD@Z~Co_*V4>`548V+<(gylLR z6ZMGIQmp5GG+XJdizhfAe@U`VZk-X&MPi^Yr0*V4rMp7*qlax@X<TwWr}4Au0ZXAf zjH>@PS;@x4kxgtL5bG{S!;tV`u^mg(!lX{NQHCp)tCp;O_OC9<)$PrsLE0}WVNULj zwB5%w&4TFAg=S1)g)vSXV;MkaK-ymtd(gJzp(VK&aqQrBMq!#dP86p`DA-8v$Tb4! z`%I2$rHv@0g107L*=sOe5NCA6i1#1<I1Y<6;Tb$x`<_(%xtNv!$FFuIXvv)S=E$D2 z&BPD;dl@%TOUd$DDDM7R{wV`XMmBYKM25q>&VF#kDA`MHx%3aQ<JEa?VPRz=1%Q~( z*XBmf38`@&9PTQ&AC}!!q}EW&BB1c4E1oOJmRjk?+{?#-*g6vMJ-pVb^sr&6h3wCX z@FEzOB<~J6UOB`SH_RXI=;m$+h0KY(xnb!gaCh8Nre#>385hFKdtHR|oZ71d*l5qg zj4WfA0?c_0ixRv9SVOSMh4F8xD|+w8VZVvHiBLsqApopUpQMegY?TVN+?J^#-J@mL zq*r1Q)~_~_?Zmb2&rc~no}!%#s$dmtaKj)?c+9`79)l!?5OfL6h?cg}tBHigBH2mI zZ&*>~i301*95>!NTXu!Lsp>p0GJ5>y+9yXU5rW}?xo5oB%xIq7=*pAFtke-ykL*XS z%KipxKhMLa=lB5wR62l1MtGjVuKxEyn8S1`M2(XXM}udr$2_UY8-4IrP`X*)Nxb9( zHsGg*KL$`Yt9L%__{>hMmFzwpu;-kd_9bwNa+&aR&!y$|J?DR*^#WU0bH6}R_Ig=w z8k#)#F%l{8<gR|53WqW!jYM;=s03r-+U2amr|oA30_ee7&JhBjJg{3Xi2uC;$$}%m zq7@;1#n(dLF{b5uP1|!LGlb^EX%s;RnqUjkKlW8$Vt;=DE`&qgMi$jUP>M3}5g0K5 z&3WQ0_M2$B+er+;>X8;f{GP~ynPIp_t)^syd@S6NYdYh~OCgvhly+W0f+ASCX2aou ze&qcLR)G^YB-perbBs`6jJvqBi^+z2)3<`ee4BCm=|P4B-`C88><iXyYRTt^{W*tM zXu-S~#T=39>P9Jz>QkiWqYQ=!NHM#b_*zK%TCh9Wy31>L1(vOa)*u4Ydh}Ge+inzg zWMDj%6@MQe$k=p$IxE%jMwhP-bM#n9*eaIR!V)j)@Dp<XlEzNA+*JjYLk#PX7d-!D zV2Mh;J};&MOzwQJCk5P{y~mK2y9X^}F8)2WMHPN)?0N}2wG$`phdS&8yhSt=w0ko# z`;BMKEHNjv=N9R?j5dcC9n9tD|5orUJAV#Mh}v>^qBBw#lHDQRV<tc3JPH$GWqdJz zWo>R_U-uz00s9p`ExfVHP>^Gzwz-3dsdO?)cbOYB^<!>~Mh6S9SJXR+I-E5SYzusT z{w;H)wH3@Kcd!2QT9Z5j3ptDdU@;B-3SUy)OLdNO^G+w!J!i;;OZ`3Kx-}Gj=f~It zu(Hi<I-f}gbb{DjP~hcOjCfD$*VA82X5`h`vktL`03TArQd19L2e}vt;1BSy1Cd1Z zTiZ@U7UV98P>enz_&5|4%Kem3$?<_n@EQcXK@02?2%xZwm0O7YF6sE-jHEakmyL4H z<4@b!S*-W2ynE{a(3{eT#Qe-%3!$pICc{N=;_ZIEbX<0hwPQj=SvqKsy-byyZs?L~ zuv1$6JTBl<#vjljs{=L~e~?Guqu!YN7IGPQM$|&~a@~7@q3O6>)hCdQH*mFZ*8N-X za@zE?=0A&q)5DIqO(f}<H`(z^qheqLX9KGVM$F($3_pD!dRRmH@riR;3*&l9mUIpF ziW>eEW1i2_O{~Fv)Ypm5qtM(j6FR%UXwg_$KWxrbz0G8M<oFi&O?q3O^5Zs`Ig)eS z*fs(cu0_N>ys(|e(MeMi!BYj%Sn;$fbC-LCLp}Z{ZrH`BHpUQzd@V+~O4Vr})#o64 zCO&SG7$b<ut|$x1ptwZ#7{-}R#~r3%tR}w2uh9e<`CAz2whvupcTjbaYr~7`Z<)^0 z=7~noSj0M&GpBHEq37jgsH;@u8IGRTdfhPza3aB|Pw7f<K5b{?g5O8ni&mik!ikM* zL$_HpD=AT1P{7KV-~L?N=!XJf;cme85i=5qWL5x9dOhafArWI)q%Q57%V+lbVUsU0 z%|QTljlPi`Hv?$2i{wr##^ij?FGH6()dd>TkiwdMG1*&T`R_g!?l(JFzoU6<?Hf!l z0?f>vE^`u)Lo3lPxw^<WH81%AZPyidf9-q!`EVLcdM*=Lm+#Kt&~Wk)P}-}aiu4A? zft4)S>NBx_6^(dZ((gm-+%(e3;?7;qlq<<c(PR`$<l5o6l4!kcmPZ1J21m;A&q6Yy zh9D6k<NXyqFo3;Q%~vT0``b|pdHZVtO5y+h1;7I49djB>+F(d02<m;AUur{~`KYrP z`)eux{{<ln-t-8M2hHfl&M!%3|4^{b56cqVyQoVqbQjn@UPF;Q4u6CRkjE6ypJ9K{ zV?}Lu4)mlB7)OKWKMONJ)7xh;BZU>RWNehjhpnvjEpP#sa8%zr$EBXG<==<xrl2>t z1U7+YOwk!08cr!PJEG{p?D+M<GtK;pp)9c(>iH}WgCTCH*R9vP7EXkZK^D_vIgp$T zx5pG1SWBB0Ip=l5@yfOI)!F_A{t7$Q(!yp4JJaFtkWge>39d-%<tuv+*%!jWV5iS& zGs*ZVSO;!}vuaz@HiK0lt0~sdxnE-6P*Yq~a6r)e1XG~HVGcyoIc&-l^hTh^eF1{l z*j;R<Jp_iopM<zPBzKt$Bfo>4;kK@nCI7L#wLyzEUH{tW9b~l7c6YMxH8n*agzE8+ zU^!UHgQ8Xmu4oJ9D}M*sZvaPeJ9r*@mCWA-7Xch?^%g&b$>7L*2n>TH^LqP%<qQ)w zw{OCWuvZO*p)CW3Qu86L<8!*9>AhA5>wE;#`knKtM_~;3eD!A8bKyAH0bF%VvLHm; z<&;{c-Pk&R)PmqnW#9A<gM;B3pee#p@HkY0qY*mMUf`zBg2P|~$ZHB_HvAauaGSzq zpyxav?u9?WH{e*<2NdaWuoE8vhPE!uC<48g^Ap8oXI30qf6zm`;z2>vql|;c;N2PO z@;;`40{v7izoOqA?u4n}bJ><@Hl35-u4PcX^WjQ(ww4wIcL~R<g7<eDDEQ^!0yqht zhY)_U+q@MWxthOnRnoSf0Bgb@pr~1&ommWtHm<P_TjwF-wLEV}))bea;}n<)^FWWM zm)jC1fup;kY}Tx6JSY^y*F1gB`x_31zuu4cdORq`tmeI+2q%Dp)z@Gb_!xW#J`0+I z!f5z2{1F^zJ`JCM&x6nL1-KBJHXFaPo@oJJ;Emu*J``?;+0d+6pB-BC0Al9}Hj16E z!tUUEw-Y}DUh_GyV=9cRK@X$Xd%CvIrYTb(TfmcGXSd!o^BFATRsnd=>%kB>6TS#} zO`*LAitg@O;iGEX;OP$L_$hc0?uR|WC}BFB0(w6~-GNZZZ1~E0wgr6AcI^FOUAO^S zVG4UAm<-e4Wzd2M{>A>XFbv)R!?ib|**>CZHh|Z`P|oXkjbM5@^8`#+<bz>-P-xTP zHkb$7f*s!dJazz?cLVRkNJ8=MTs!^?TkS;fn&*T0PlBJp>EJ#81l9w?(n6NUy%)Mr zRX9@%j3t+y^Z}TXsYLcnA113|nakpesQ%sC@mGSK;8nN<W<oP&U8{rQxgVB-HNfi! zFRUk929|^6Yx{~)Z!`xS7#4t@R~!rmf#Pr=$ZCesibqeYr}Ehx;C=uXf#!1?K8}IE z!nqK&;T(96hS!CxzR?R+RuwL#1?+V113Q@^Vbm*d*tDHWNk{2_q|~5LHmvcTlzjE4 zEGL><MRgP?8gV|PV20JU?khq&zY8;>SA7laleR&9-&CM_r*q&=$ZLvQ-U0`m9<lm| z>XDnME*jecdWX%y&U!Q0;hHtyvjSQL(gf@^Hi6YZF<c4?RF7D13d?-nr}G;<fEX4U zzRd&clNG^^J|CU|#T7i4_ZEf2M6=8gI4&_qo1gFjDr?Ucc$wRJ5*+Q107I>pz>c2R z6vTTV?R{IX9$+0f8=Nn_7Yysf^HDhL65`fuCxGRKf_bih*<c9x02m@Va9HQYuqG&E zLqo+D=g~-B!W=9{!X!|*9cMmlW$oVrdYBEtMHM^m?U2V5(hoqvDTp}J6YT^Kf*sn< ztzh(cYk>kW6tmBGKZ@AU@mUxE&VR0hTfw@tt-$&$t68V_;GAg<a86}iFF+8b=Oxa( z_qE|MI5RFoyQfuxYxg&_<o#_y(l%h{o&t9IMy5E<fTbWwaQ!%^sLugCPB6uy01Ovh z2vJOLfb%W49)A?B0q@6a1ydZBc^K+Nr1-@ALtr@gEYm^n6+~L!M-`|-{Ulhvqpbd6 zI_l>8@XacmQQ)ek9sWjm3DWEvoYbqtby7R`u5c+Vgs9*+TrAS4SVP}gxt8CMH?ExZ z-VEMnoLQ$>pNlC9)cbVaXIMQ0tlRU7&8?pIBal=lr`pr%N1gV(%j&M`TR_n~508VL zaX%Pd+gChs9dR7#YeK!?%)2QV8iqL|yKgf)c@oaU3^nV;W(C%5A5$oL#5jxAYkuc? zhL^L!vg?C`i*<yM*7U2O-mI&wtrA>Yzn)AtXGeYz48vTM7!Mo3a}e$1%W=FhL<MID z9|oQ?By6TX1i?^z2~&g$Xe0yyEs?1%!TP)px39uXP=MaI&$l^v&S!QpCu*B<&>w7z zwzOs%xGf)~x~Z<wUoZ6-*x_~sJE!mXEzl$G2zFM@FfJ^1T+Du)hcaJLQ`E!3>$@MW z&u&9AuXwL|H=oZ1m(#&#*%wv=&pH2dkhugbGZDf(klpsMJP+R<cU;{?o)&OUv<j>P z>%%Uv0vHC423H4ff>w!*s=LH8m~B`*Y4%zU8e`#n2;ro2S?l##wgUxbzR$vBI2oRV zwlPP)%6e}L*Z~bIXMrKuweULV4Se@{1Xujr*ZY`XZ=#ho7+a5vABMT!N2s6OOlE%T zu)JRDEC^<p>GREm+d<EM61eE1=Q|2qNp-I4v-P-@)u=uGAk_`zZUNuD-p-D>73>Ma zU?EJ07s1Z17@PG<6zwuQyIx4)8CquPcV63a-k+iI|H2KBWbfs~hd{A;&r88_;5W#* z@Nu{wdepK!c#qy-b@6U(0p~|s!WJ+B3`zBdhG}{dy@evsv)Fe+{|Q@?5^ZVD7}nkg ziXm!>OAGZX6hp-oVFsKD^B~E*zV#a_J2<$asp!Og&w0%`(4&^6p?dTNtBdzo3)oTh z4tfm3Ip;{Dzz|g7=?R?!h7dIxvW0#X-72c>;a*S}L1gT9i9vz+*+P$|M>-Gg1g{m% z%VFnQXpqi*g6humw1A_$9;=Ay1&6|L7zF*mg_#h(c@6uO-YO~-_XmPrb1GPmA*SMc z6{f*c;5^N+v$CoMI<^J$9D0nW;bs^P--YX8Jt$&|%P=m4ZwgNQ1<C+e3lyee(_4NS z6rEc`M$1`8WmOCGiWboOJPvx8`L%t&XZcew)3%51Fz1CE!%lDj+zu|<R93Y>uWEr$ z@iakfYqPI6`ARL#^lhL!OmB7_TnWzOL@!ub)dIb$1^h^?uznnQDm#BzxY#<9-s)Xf zDfPC_)gA`J%|2yCzpwPE#_G_AHKf!GBZIlJ=qh8>HsZi}-bFCJc0zBs7yKGN3`P6P zB<lDCxS--ZZh7caR<r^8RAY7M!_KMQx8K)-xlq!-c3|gs{}J#rfMUD>Hif;x5YX>f z--NTE=mN(z)bV?8{x$$At6HE}wZQv%8beAyULOZrf#Nbv6yiGYb8yAb6-CnzhYjIS z&@KQ&K|NC$rYAk9jEbr{supOc7Vrc1`49x=R<C7<83f1fV*3(%rbj;)SYE*zUY2Ew z{K&E@tLmv*pj}#EsoIU~&-RCK6zIvqXMwTo2m3fXitWUZP}?5H_Aa;+%A9vCQ>(w) zR4veJTHtt|WFq_t!UD<;>?<q@X{WI7e9llZ*e2}wcW2su;9nH1>p^8z3sfx--vVPu zegzcQGvNG9VR?KuXhXqc!%ROP{1*IB{W)+EWgjpModv5wWmOAQEs)Xzn{n>X;5<xW z&4!P`a-e+xT$xl<t|DFwdqY^Aw9I`_c{duNi2Z+W^EX>~bV8H>0000<MNUMnLSTYz C;@|ZE literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231102173536.png b/docs/images/Pasted image 20231102173536.png new file mode 100644 index 0000000000000000000000000000000000000000..f242f32b6447902f97f20ed82f88ca64ec63e2d1 GIT binary patch literal 225384 zcmZsB1ymf%)-@K~2|)+9;4XtpaCd^sKuB-~4H6`{JHbM5*8ssSFu1$ByZb-6Pwso~ z`&nxi-PI-CRdr77z0V0%RhGd(B}RpTfx(cIl~RX+ftQ1Ufzv`pgqENYx4wpfK^M1{ zlvI_Il%!B~vbVIh0l~n?h9>GD>1y=7$<&XFi5Z1MmPKhnq2l?Hfc+k3?_DKM987jM zAu^+@g<8kY?`E(hjf_8LVXLTJ-~3)CkkU+WsWQ=7&izvU(0{Z2us!ViB5;w#wKLq} zj0AHPZ&1aLGzCMUlfV{=fnpM&q-+|K35Uv#Xt4@gXke6?f)4<|nh@E%7%eX$gp{^y zQ%u}jz4)?x^Aab+f}tT^=k_6EBUlfBS=AD%q9KR*5y6-BjV;Mk*RKu%5&2AlXjpZX zkw{r%wZ$pzR+qP%1*TB-mw_B2%tsxH5r$Qe7{*VLkPIoWY-AW0#O~H#zvAz(3nXmd zZM(4tE>o>VcP$>3xNK$P2Zjhc!+t@+<-fD5q<3XJ`{r->CNGlieaB+bElQ0W)tyT> zUAD7Q!Av$~>~8r{3t<TPN%2gvIdDWN{Wf)c6ydAzN63JAS30a=NXG4AyF&;DCFYwg zDQSkgTCgcQl39bqsCB28vQW1tHrwmXSHIud^2*WmGJ0oU?cwq&^kwbHZ~A~*$>eMB zbmgCBQsJW1$u*b;BUJoT;HuvFv2);>@q_>_sy8|ld2`UX=3)bQaji?4eb7S8U;T)I z`6{9v!-^86HJ`k_jWJBHknna>it+6Eaqw34oloT(G95C}bTrp@6lS#O`^e`#(&)oq z*^trI2LYeyuxY#Bx`>2az?<QlJBIPozqgJ~LvfO@XeR0|_ju*lU*&ElVi1GsEo7KZ z4yXvhV;fu#ddIZhk?e=uj_CIVHn%e0ua5!^dBKy!b1mZsJ)wgif&~n$gDPhLb=;;f zm3t)o*Hx7e1Pc2P249+WU{EPuTtc)A0Ah{J^<pAaBtm}t1c3ph?re$CxELM^2+@?( zkHK!Nr9y=En5EUvz9U%GD@1QBs1hQ;qtue#qj7{%=rlpN0iksbu*cz_H*ik(u}Zjx zyM>W<&XzJy14otJr5eO{DHc;{nByK_ZxN2dUIirnl6~MHXuzKYcfmW57h)zl8ZN@{ zua=Kuq1^;zE>R3<_pl70ZqOgK4Xp+jWY<y)#;TpOSBuVV@5Fv|{b(o2SZ(l<LjJDQ zTJp{k>+10^>q+wZt`g&A4p%<}&^~NhP>D9HRtn2riKk0F9R`SB%bvQ@ZEZws`Q5+K z7X<9|y(RIgu2$R@m;zq$d#hb;q2>3rj(ri<6EdV4gbZ3$u0~OqI7kWg;-Fj6TM@um zJcO@bT+vCl+EX-^t^B(4g;{krGcj3(xUn80z&r@89{Ao0T6G2L2Q$L#U|r<K!MzF| zU`4o1R1LQOCbHNz=!cOW&E<f!+)j?*$BzAKU7RxoIcFsBzyL1aKh=bc0TyIJr2A^x zFVX~U7S=W3={qdxtAcht2NVNXzINdT&&Ce4QKV(R5oG@uY+?zSOB}pz+$x!L9J=*z z1WFuP=D3JlDxwhNSSqgAJ6R(2s8UH@Y95HlCc6{ruP?RKZZXQaNFI@15*!I(A9JJ& z@qxIYAI#jOkuvn(iFRMtVzWpmfB!W45lrwtI#Yrzn{O2J^3{AatRnuzZ$%EIh|sDk z2If}^y)?5nrLRlci>rX8C?Y$bbdjdRy}LvC0amM+4zGgOQTVa4{6~5SHV#e!?!wFd z#$AGEB9A0~((E*|c+JS9ow^c;ri|Hvs^YWK{8IezD|vREf>g1E3bk~e?QR^YDeuz7 z4HOMj7A1w`Z0KEa9^`1^MEWu}CBvv3<?eEE$KQ{$j-!lgsq^gxgcXN{hSkVd%7=x? z=E>$sfC~B@6H6FXv_#^0AW0T%POno{GL?<wm*wrKjOpCsMK!qJPQNCX7orX4jIIt+ zml2TsrQ(rOT>LSAzlb=8Q8S~YQQD<q-(yO7Dq54J7?7w0P)SrzR;|}iQ9n^#8U4V` z^i7oIYm$n-L`il=zHqL$YEFqjvE$_JN9Re#sr{+);ucN%68++uN%~@fVx2;A)wa^* z67lKEag$FDJeHp{Kax&2<c(Fx&5-61<)xPV(seG_el=wEo`!{~jDn?AyK4GP*~EK8 zaD<(*)r808-DTM&*QK59kGh|{GJ*<Cil6IU(_FKnlA=nKe++YH$Y+=X0gWl;iL5ew zGHyl3K1*qhSwTb?<`{VB`rM^<vs0!gS3w7N2Pl{FSJ%5sqYt?wqgdl3)5hg1-(T8c z_$s+VI8r`VcC1E-pEw+?Eq8fzDFmO8`^;eT)N)1eq?<PUuAHh|fy^>=%i7dV@7AhS zRFzk?IVPRSZ*24k(}D4f@v{5m<MHT5h=AyCsDrD5#yWSoc(^fm62IB;+HyVFSlT9; zXj|0v9{LIVPPfjqYaMT%YaZ$BHjDVJ82&!IDak@1AC$lKalkq0q^z_ouJnyAkFIdd zbj`Ld!TXu_EA`oPw{wbBMRmXI6ly{9mJ8+eEoQ;<zve*mTJwf=GDk~CU#}027G$uc z-J`H03&|V@{Px?O7#s>+cEOV_5f02wHV$3_<7O89kS*$w$j9x??Szfmsl8=}GBwkj zFlnAh&m)_iLFaOC>#>A0ifih|`0jcC)UwuUW5-n;$&ziv0$jaieZ?`^G42iUh71cW zS~Hq4T3^xDlG~Z%qM5#ftKB(jM{Ok9=-BAa=%MBL-1T($dU@~3ruOPX$8K3plh>eE zgGib;(2J<Gs5Q+?@KN!p!Dq@R`f=##?s?%ctJ+3Suhg(K8CDrK?u#Vs$(+%l-eJ6- zu8FLPwTXU=wyMNv<M-eW%MPNBpB>(mc9dKa%0ajiU6RSc%j<-W?&-wJ#wjwhrIkqz zAKeXZ8&73$Tyf$;@;P=>Dmj>X7Nct;Uccj&@?%h*3@bz$n;z5n5#5b#{==NnJhMA0 zEQ9DXYZMvZTRW@8rrR&Kd1p7cHn_PcL!tYj8+e~^SLk2SCDOY@00dm8XBGMo`#Lv! zUaQNS_17glJBn{;M;?%!@U~h!4xvor<tsI?kC~Vacbmsg(mT=vWNCBh@{SdsIwRM$ zogXInt+lMZg?R0GPF}5KwZ*MapW-B-W#&KRCKrefoc8I)j>YdK>&4D7S)k3J7=ylA z+75bV0TNq;KU2`ZwNfdUxBGZ(8k@wRKgl`geqP&mWcJxHw81=VCP7Q%o@Oo1)<bqV zu(`*}_Lh2u@n`Ha)e-Y4OCj?uJCEbOpY^v1sfqUm3rfb^Pu8XmYxZ2HM9oA)TuN5M zX>$VMJfALXEL`Ugw*|JH!*;+U7^zL>WFVvK=9TdDu>SDnVU=$ynl_q3^$iEfF~%Pi zCgo{p>)*Ju%{E{gGZ@U)K|o{k?^fjR@(2df`x*ONnYUS5Zx0HMXC8r-G~RLx>Nj~L zNjS-&NlOOD^<FZ+EImv;X2Lj__H{V5lghoCK8_co;g{o+=xAsw=(v@J>P|FFn;ljE zG@b^PH>nY+{wnCN{HQkdaP@el!*^?6xbUI2%4VZLsZ*(*FW9EMqOQ1nR$@`Ta;tB; zyKKkD{8_tZ$V7jxu43Wcf}m^n@rR<b!lF6r24`!Q_e^C+b38sXiA#P>BnPDXyeDHz z8g&GRiO1fpY%VK9PiqfpSnODnfLbA4mk^)ATC$=nqm`MMxzVwd#aSQzLkH)0w~1`( zD49BP9^v;MiaWF88wne~dy$l1XYPu=6`A|YxS^?Yk-Po5pf|I18FymbmF{uyuBO9E zCCfZR&~bU^aSY9f0MppQ$fjY_r>J$R>}vGHu8sVovwcb1q2sT!u${#G>#?KWihDz0 z7nalcxr6kBWIL(l4{fOq7uRKH^+3A|d(ozN=bfn~|E8>yp%#?}<9o3U@!yhN!Bf7o z&s7CoEgQO4CRPVI4Kg>4?uKk+JHpT7hL3^Qx$8xJ6W^?cN20C~ZVWs`jy-PB&ca7p zXnj9E>s^g+Z*{aizI;3)S(tf}KmWLTwa#~MU)Sd1y|75W^m1x=+%$5cAiC>2dlq|l zwpfs>q9UsDBynH8U2-&&Z@;#3jJ1i09`Xyf{80xc0AEQ3Y4yq#=0hLM=-OQbr?TU7 zJb{#>Wg_)yR^@sG1KTmoWXH=*iqWl`GuoFH{k1c+{gP-Tif@Qw&Gcf120{C)dP+X! z3HVe(NH$^j-;&Z0pOw_o1$;vucHTfV4Le4T+F(MyczH9k_cTK}g*Hf6&QeJUh7o#= z3<Dc%4TAu^f`$Hwp+6}7hzo*2g8s*a{-nOc{p%^b+;{kYUBhYpsVJ@?DF>x0FdF7g zAdsE&2YYa1lxhUDt7&UZU9hf_BGBC4meth4-VDU*ZtL);35<|C5PE3~0-I8}+uGPU z1KowG{;C0lUjHd(qoVk$3iy*Sm9CO1g`~X`h=P}uot2$R1eJn<LdeO&5~waE{m<sm zJ7KC1V6X#_jm^!?jn$2d)!xa9jYB{{fQ_A#jgylFT7$*e!wzif&SK|G{f|!m)sGa& z+1$z60c>q=NAag$Q!{%PurL+XpMn1U_mB4kxm*7|lAZHEKMVSSY=54xaj>$p{kv~y zQ=vblKvipZkd2;{wJmgdpks*e2=EF0Rsa7y`Fq6wXsP>mOMY&S|7`gmPyV;1mNUpn z(%u$2Bv|C{mHB7m|9tq*hC*zAzWhIC;vdueS1EL!MNoy<{=H@*sPmGfMldj9Fmh7j zn(nZN8Ax9Y-`!o)3ybZdWY=WhEawF>B8Pyj{r!E>!d`9FQ2n4XgMEdMjW2~=HTpV{ z)&KQds*vxO%aT}>G<VxK%ihPs%Zp1b3)M}0BQ#c4!-Ik+gF-u*sW$>#R>PHgbF_lg zCI}H<aM<Cb+mQ)j|8awi5JZCX|0(|<*-lf0ffoF~_1WS2X!=Cq{!a@rzb|s?ut5R; z(e*#aiKlr%{J*`tf}@jrMTklK&)4|-ofP99N&de3SHsuH=%{hIDm-h+GHN3NWSSY8 zmBU)1zh^EKQaKI!htmbP=8O4<1@0$`Fj`n7J^Sn4me)6Cto-{k|LPH)8!o_~27`o` z895*X4w26>phJxyHd#6p#zjYe67hVWLiwm<O7C;|W8^)E=%<IKrET-D;DG*gNoJ;} z<M^ll?T!{f8dDRbkdwwP?P~pj$&TVcXIkc}kf5M;oLr<i(pMs7vUUD3mvVr^yeC3c zjY(s_jDWR@rlslblgqT3@jhD@V}X%DnQ|7%f6anlw!c^!t!VHkX81HS{2sPw0fW4` zuz+?kgZ_I;%{c!#PW(NP$k&0#acX1Rih`QhhUIM?B9LJy(-mVRFnscDmiK=z&nP-F zI-wk#5V~E2Eg&qOQX~fE6P;{pNW`P`K4Kr^)_`m5^>&)QcJg^>L?UNo!dP+&k2>#_ zrs3N(R|rp>arJfNf9;xflXoWVvT-45!d>sJ;W3C^HohRQhM!KBIP2+bl?>&$wme-g z?B%D~$rBiRIeM;#(o=n6A!52pG@Z(h_{3d$PHU{9qhtH|@vL`(rG7Ea$a61Gmx{sg z_UbZm5A%N~<4gOO*xYf#U<!xHxUdcw6S)}89jEKu93U0EHN%C&^R&Kw-T+&h(9><N zsB*N({Rd(JCyTBlI^QETeIKj6Vl)r=U+OYMDh<<089*LGmnp5iMduNv5z!Z~pWZ*6 zMEL&G9N6I`@%><_<zRZM%aF*u*ex|I(y`u97<*q$T^5Kwy)|@S`??p&w_J!zw67Nz z8MPmd9t<HjoktVDU&HcE>4_vscAYg1uAMat|C+ujI8N_%`mX&Wh*r{5Mk>mQhQ5tj z_-Z^^&oZ@kQeEK{>rT3}vgg@v0+M21TcZDclK^}_pQWX8?rKW3^bPh&$CsxQ-w8dd zjKpbU->2FUkq6C<L^6q|M<mYd#!xXa%i~`=nPBLg7I<u@(w9~DGg?RTOc%1U#gl3= z9lWor;LWV{ecT}58{`^6_XoGbBIQo$7z;-d^AyX!pVZvaS_+|m5q-HE0sqF=$(=F! z%wqYyaA9{WXJWR>+&l>NZpPSGm}5b5-stlYz6-r?(ZyD>vGPuan~^7U<Z-WyAp#c@ z>2OZSfDHj5bL;K8bwP%!JT|pypb=yV9!n^OwQ=`H?e358eD9kjzI`zwTEqmVV3F}L zbF2UMN{C!=Ps(xZi!u>}YCM^+@RGzicZ~<-3IqlY;>-*F3}v<B@_zUp+kxUr!ct`N z@L8$Uvf}`^#aQT0XrZ72HA2wt6abB*#iG{y=g%j;FAAa$b0fG2TN~sr?(+^^7?Nz9 zR22Qj_l#(O5uppk#<L!h2{g9mn0&=lT%>9$e#m+2gg+W<N|Le9UG2rNpv+wN9`W~J z4C?3So3>sK+xc3CEb#e8PXtl?8$FBI+N){(g1w1?V9asN8QNq6&ZCx_<-N6Fa?ChE z$Mx=7s4>V8Z5E&loIBb%(MTQs*9J#-MYvC-F(ozk+Aud6fFLG395=BULbqFJBushp zd4KJa>p~vBwl1Yb?9Q%z!ToB95b~=XX6gx>{^|i%5(GF&V<*CwyfqavgVbRG&KOop z!}7N0d+@3s65^f7HIiP`eDh|PT$`mS@BD`x1aZFxc60DvUUGic<0d^vO&}&@tXJf^ zs`jXEA^+=}_YAW19={Ozr!e5amt!&oY4)uG0OvuDy}g1gO!eBk?X-fvc=}#+f<`*U z6zr|3I(+Xz|0C$W+xxuoV08bR%_lZV*DSR5dj6A)zEs4d2$a(cXhs(%y!`9D`G;%w z6Auz=i=&x;j|)T8OL*-2u&`oA2cKGy>B)#ZL6>HuPAlJiQ@|AIvY+RSET(6*e|?el zB6Jpo%f-$d9YA68Yb!~dIYGyT<$^Jah`=>a-}dL!c+>J#dF^Q@nhpwXARN67a*m`Y zg*=r4vn`3Jj}VpkytaYk@6mxn+>~L_m&d&j>Zrojo!9<%SdH(%r`BEXKb7HgNe{w7 z9g@>t0QsXy3?K4q&y)=HUz4u@ApKO^`Hv-K<45%?nLbw~#(66*&o|-;?!EFZ1zw4U z`>HMfy{v?O9U)?Eu{1>eKYMu22C1qhqqfYyxvUzJSjOwpNoPL0a?X3a1l@Q#1fI0L zJcEaLX1aS2(pNloGWKF+$cl&`ARGhG1#arD7O+f}FK8T~KZ4q(%HZ{3RWF%%C3lSm z7WLXYk<J)$NZ6$xfnyAzWukjB+K<jb+@>K8c*L_<ArJ-Id4c<UPd-u15A$eY-m;ou zAjd;4P)!8nXf$1~7+ibigS(Jw>^cXk3dF`Oyr&w-=G@9z82+DAQyby_ip7%%l4pv6 z&9~?viH(y~*H^U}zU4-E?A)1%C`jY)qypT_1@C4D_XJ_oFS+Uy-cDwu=CFD1DeN_^ zJlSDWpI3vUZXzJz5y-DvL(tD+aCi$%@B)W;7npf9DKg=MSuyw27V<Rq#s_{ai%THJ zbt+=lNDhLZw)xtM;&8!K6-1O^yxudYF$*T`S8;Sf4;SKY6;O%dmX@I`y|RdBYOH6k z;4;oasw6ne>%334pw;!ip@<0s6+6`k73l&wesZ?qevd;dbdydL6=Z%phMFtq+mKh} z+Mu`d#U<t6wlmz8UH81bsmx#Itg@6=9=G`dD4x!ueIxX!dAYvuAJ(t<R6UT8(4Hz$ zhrHraIz+xXc54$vMm3cUv{ae2^IA{k*vP5cU2yCL1gwrGsbd=O%OH6m&-6PO#R0aE z=+`MTV`!4DZJW<}s;Dz8PPGsR5bt`%pbqm*6Dpa{?V7dUt2ZG|T6JFiG=tgKIKdhK zkNU7we%bA^`eou1j;c~@DtdaoyRdru|8bqvaJES{<TIFEjnf<#{(i$ju!EKf(xTPa zNnFGH)Mw=wG*Sc2AFnQ_1Qrar1iQ<fZAz3fX4gGu4BeDgZhQF5?uc^z=O}oM+k;<= zG0qagl6M&&G4#E1v2aCS|E;}H8`{i&j+_NWHSvf=u}15g{hTSGIjzB@PO@IUp(jA` z?bfFw`vT+V^JFzL!XIcztv0hTvG;>kB6wW-%=LI4YAyXvC?(~fxm}G%s8dg?o3l*Q z{dSw&_DGwwgj3KwZk$FA_}`_gq#U)UkwdH}j>sNvVj?^roP?P256sd<-S|GA28-tM z%ouRFT4{Keb(B2{UyTh6PC?ypoRP;?BI8><D7Y}cfNvrB{h6=!>wSE%gB(@=`8&kd zy_|xUI<v@r8SDL*oXmHe<w+EbW!-*r#Oq@toZ?AM;+wN9G4`BQzYs8q>d0R9b=ruz zlw%l{U;Isql;SoFltKMEUS%UTZ)#+i-&zEq)+z5ase8^SoEz@NrvHt=zCR%E!ZMi) z$jDsF-|%29lm4{bYMx%Ez|<iTb=TkehJlE1f0U6sPfn9YAQqD{G>S!NZ0ggnI5@a{ zib0-aFBcpF`z5wKHFg;W!i-)+Hdw5R83=Fg3pKOwJjVpN41U=e4{8wA$RM5qDy8?} zw8N_G#x7bxT1F#Be3vw4ZGav}t0?V{cZRKxTWke?4*0zT;}=ga3T*_rSyYW-63375 z=cMs;O7bi$ERNnUR~5d$>2Nz$?i*bD3-}-YZAD@yI3`e6_hn>uutC4|W$8g3F$?kM zPop7VwLl0G!D$s29Ds5(<=vv%G2#YC`y8_0jWe-h^G(--DB(lnTB3^dui?-8HIv8n zZBMp~G>goWI8^X+CWunG*^?@U9}hJ0nIh0@G_WOkIZgP4EI)&5cz;MXHlDi#Xt-HA zgMHS%67&S&49;gbbfTPP<d671U+f8=c&H3gjEPJIbGGB_^t_YG5QR+EnHJ?Gq5hD1 zgn|z2g+>i&J<QxPUSq&j6z9L8USlZC1{0EbtxZa6b!wwtA}n6TPg4tLNU~C=z$}AL zJL9205)a&yblhdv22x+$<jtb9${^=%4?ZL0EN5DYh1|cRNk~3E{rsv&hMr5y<|J}M zy5oy6bjRV5+h`deoRjyn9w<GRlX6)$lS>&P<F4RS4UXyS>|_7(BR$J_n^7~@4fXZO z!$KE>?jzxDv6#T!?-XAk<3<)J6J&b{D_Vd=Byt<~m9V_9=8~&f^XT8#$GhWWi6RAm z!-p1`FOJDodK=v4!fTeUvy{~n7QM*uKlQIe);r!+$5q)Q$p5vss<9(1mq)C-_wu*( z<-KG=kIGyE4tiu%?0sevU}4RPh&>ysQiRtf3lGbC1wcuBq)wo_jGte<qD7zG2lJtu za%(IfBV+48nHV&R3Bfc?nk$1s3@w9@hp}j%*LztHi#y}lcNw%vvx&;KxUHMw#?;C) zC;<LC3M*a|^tnnne~8^@Mm!IJt+8MKVHj@6>_HoZ6GQ_Z$o=jE9yLw#yk^c2Wi>*g zIdT)NOg=#oJL3`T-5Eg{K6-^=3b{v$PreXMebM(`m_E(l<kqF>m8I)|ewjS=acJJm zerY1!o<EhlO-IcSOQIV6z&S;V7J|-TMQkAm+$M5dw<50c(Jr$uwe_SDg4~ti=cAt+ zEsXmzfZ5b&Lpag<vFJMeV;KN<KyLHq+J{`9ywc4vE}zF+id1HvO~Z<}8u^+7YGhu2 zbLj8(I3}c)5g@PLL@eQ*{Hpp|1&hyLFwRK3`>yvEm`rSk{=zsu5zU0XrKntJ*rZSH zSLUx&pF*IxpP67|K~zQfN^^5;r~<G=v!LO--W^($mq!c4+k3O8x^$|=H<fWwPP!R> zFNq7K6$A)hy*_@{xoeU~(%6d|DR&)Uu2K90Ns6r};r->CAR5yd{2AfysKMp^^chZx zDlR6|5hv1W1jtk;33BwDai65xK>uRXgnm6ZCh5H##~+(P>B&#y4f)yhbFq=)3sqk! zqD&~8WS$ql42?E@3n=J$YF&&1Ir}~x7z-{2!ZO^(?jsFgWw7(zo%q}|{eiZ<)8mjc zYI-vIJN~_G^7CqDo0}y!75XeMr-W$Jk#d_u_ulDMw-s+U!uv@KGsL2ALLN>wB}0R% zR#8K^6mk`9&z><fu0xX1`^$RE(&L5EKm_O(vut;mjJ4-dd*fcEu?po|x=Wa(M5fG( zv0CX~oBIOejwXcx&g+!2wTbLCa?Dnm@9oQV7|zK5@Ln-vs?j>Q2DYE?b*zxPxujuN zuHbvGiy^(@t;gH86-9a@?la%q0zl3mA~H#OR;nXW%{MCL2(AgEbl@ybRuz<eYMxma z%QLA*KgDSh520!RIv>UE>@f9JJ|*RsGVVEDojY}19A*6>Pj&Uv(TxdO&z>SQ;#+Y# zJCN$fBPdJr#pYN}?L4#1zG=N_Ih*w3)Me})>e4`#orL0v3{0WZb}*C_Yp?tajo|T3 z5g$|M0y071w>G2{J)Jew`OZs($A3pGL9q$(R!mS1>rR%hPYg|BStA6i<59-b#b`uF zFRygHJ^b2f*ez8)E|9fvYT|(ZuaB?CiD^;lG3ET>?5?d71g2a#lE}#JMGo0OnCmk) zGoUZm5%Is-6f=;KXQ(hW3XLJ0IG;@>R1hGhmXG*Me1PnH`n`(Rh*R&(Ch82+<1o|@ zJPF^cTg;J?_v9t?%-43OB((V3a^8I-@}aDJRqSrdy}VJi-gAu;GxgaaA^THcG<;gt z^JT%_<%CMKr}ue$mZA*6Me~u2W@66eB--=+&Zxxq8Jf`TBtB+QA#^a1(lYk8@+~44 z=Of`A<;FnB2{P-Z1A!q}&1)tYD{;TqU^yMIWi_wI#o8}}q@yfT(Xbwt{Xj2zCs&w# zY{T1*h)jM5ks1F3->-s7GaP$}I0m|#)P+(<gAlIzgH<UdNoKMAC6Ck$_qRTAD<37Z zE*;he0J$Vx``;EwJy5!Xzu645bfPjz;h0o3OMO=X78P`6Oci9J13O5w=C~c&i%O+k z+_cLl{<5AU?85neRFe<&@gICUM<wn{`vXd@Lq!gJ5g08BOr&k!B}pZRYjVI7=AP?W z5&TqowE@6FB=_9Sp8XzL6;c)KC~J;m{{0Y&?{q1Wy6vIx$2u6`D!X9UWIKzp1+U%H z<VPo48{;|prpL>MNqgbc179RnLeMeyCK;YD@@dkqa`@9g_cU%0pl@<}Z%@E>dz5D# z=p1$A3MF+t`xN`_{onrZYnG<N>N9=S*5`6#m4z)Y_-L^TSzJ-}r-oAj9hvT-OX%^* z^#qkHLbT)P%*pin+z|XO|8V8-;V*MEA?kXTG9IBb@l>7TdG22Oof<)c#|_k$q7<B9 z&KT4>#Fy#%*2G;Q0joVig;RzXz=^v|cTNs9k^r{27@NWxahaP8aKL?^mH8b4rFgP| zlblz0SkadAh%leXu6#iUI^Ig){h^g8$&3sD1?XbP?Vhm3O)QOs*;1Pf^h-mw&hcda zOBDF<8rBn_BvrfB5o5=dzaU|Yo46@tG^ND6NqR_tzz8m=9;d__{uSZX{WFAV{=MZV zA*(R5BrC`HA<my+)9%;+Ow#LKD4!xCL9tGs2Tv%OyT~gjC<q+}+897N_MW}(gZ@1f zyQfho7~l2lm|cDCvFp(%TFw(z(*U<+^+$cj6bb=>&`g)_-pK8b$ba!8tHw=Yp|X)r z56Q7}hGR>F7n#H&LFl#n?KS_3s?X9;h@q!ECliuXr|P?Ixg<&8XB12GbUSqi6X28E z9DLbw;?1@^Kp906L{1~Rs@}@Ao10Zus_zusqt5TMx~cPC=FWv$AxfyYSAnf1!RNXr z>$lCok8sv+P?HkPg9<Jpmdz9-hp0##>n12fe57eq4grq4h=+wX>r>MGY|+yD%c(}= z?dl@7rbMf3K4;;VKP$Y;8r8aA9(-Te9979O==X#u7fb>$iton6mnKaMGqanKd?8r8 z#l}SyZ1YP2i~`|Mg;*&}Y->z$gm@;cS(s_;SD@Id&xPuVPqlP=%?aq&xgn@b<)I%H zN&^W$S(LUN7@mYxMMnlw;743|eaJw{<R{zo-sZ{*B?^L0@WK>Q<fh<ZW!E^Axu!vN z1J$2=gcFG4YOOYDP;rB$(~EBF{-7dSuSP&kw8#B)ivd8$72X?Q;gAIQGMG;I@-{&7 znn?H50U&r8BZ(P$%QLM@-MSS*s$7R<ibtnfS@Q0?4vn0s*HX&;TGbNYfmo{Cx{NH) z`kP*1Vnx~O9f*SHz?CxpT43#daY+w`?y}d_Ic@>D5En3^7msou&h&P&KqPS(cu<;R z_R@jn6T`dWb<yCLWZ=}-trVDJvzZsn9#ySX5mI;&e6A_;Q_}2X)9~l@lK4&P7V^hc zqzNUyr3BW7ReyK5Ad!BH1^fI|4`9#T)6EKbnx<G1#CSTEw>UF$5^GLf*>t@FCF?r* zOxU{M;x9=ADDiy=Vi*5mFmUKeXITC2fY!}+cPKQ5L47OZhmd;h8%BScHYeI(j1tIK zRhPG9)&OJc9zdjZgk&>)xJtUVyI9I4%<H8=)~b1bq);f0Gn{4g3IQ~&39j5JZ?YWu z6^_6>W@FaAGiM3>g47U$+vEPTqODk4FkgcJ(?-w+n>X@3C{b(Ow0ge~ykGqIq$awD zNZm;qn5r~y*K`EOwO&XN<ry0lpFu$XY>t46Fe!<z7WwKfd#_h}`};+9ylEM;at6Ms zPeOXKsOI{CfW?($ua!54;D~i{oTo=W|I_Wy#Ypb`0Sy{t-22p^C8q(F5*0F<E_IH6 zseBsOO@a=Ffntn_Ds|Q<Wrh2XTb`cEOYN}LZVyNG^gw5z$9{OuQ8SmzX$O)HNA5B+ zlL?Y&Ic)XTm84Y;<{W3mxgY)scx{5R7=2T)Kd1R0O7)VsSiaNVNRlzH+g>m>7g5Um z-1l=1Bn}wop0~VW3`1B9_GIx+AHO#DyeobTMf?5AM$}nNcJR$)!w^3$d<uu^2B(O5 z+#$kv%tn)cxASlZCrb~<dahMn=e9}UzJxcoxdbV%jIUtjWCPZlPI&aW$9<@NUT&xR zyX!;Wx`ycfqHz=_c<8OnjtRAsbc*|aNh5af#`^^#KTqU@7R{DR%#GVv$J2m~-~#eF zsQN%66-dr}MtVO+#dL>>Ur#5i47}yI$Q%;BS=2b11x{p>w^<aD15?%MBcb^y-q+Uk zB3d4@8ZCRs5E&9#onDHTE3Zt0vmuJjxiyUS+2p9Q-_b(@Fy$@R^OsOKBAOYOaHR?G z@a#M!vCYPa;c@L4o1imnJD$eyz9PM+lrzCV6e_CW`ooScvEb%*%`U#4r=*Sy<S1&m zTk?+L*NFyKt$y1whW9E+Y^d`TfTRBQo8=CVpp2$Cl0A0Xb4h|V%XQs?kn7kqoPBx? zT+R{4-^0}7wOKc7hW4X)L&%(Ega3~3#v&wm6y{M)xUk0N_0OWV68NCb*lJCr!!&Xz zjjsylaQ9=ONx1hjR5^+`t_|jtCkb)7!%#)SOyAcq`n)bs5lOu~jQmBcA_*E@7>kZ3 z3AC-%OAece#uNCu6)Z;J+fOchH!B3YMELw(V=)$W^KG)S5`a#lBZeP{U$?dFc~DjY zps3E<AQkYk<0mz}bYdtU%wb3HOGbE`j2S3-6|1P?&HfD4oQO`;)>JZu1c2`Q@)`Y3 zw?=RWNpql>#)~NYPswu-za_)Mtn~S>25zKx4x8|waM(}3(x7lX9`7G33p0O0h-hC7 z5<C8Uj?3)%Jtd<Mfw9NUN)=oYexMjX;TZsv%w~+HJ@#`&DgbTLH5ROwQ&_i)snFwY zRcb1<NnsEbO?+cP@;$^c!kz4LZL~vRQ_dq)$EY)pTGWH+fCyfoz`%yEM_k(#%=;W0 zj8wcknj&x1qb8#BqxqJ!IJkezL$4q+up^L{9gpS#X^D714hc^dd-nYKny>XN60B{M z(PgDlIRH^<-d9}E5}kh=;Z9Bp*p<qxqwf8@6IXy?fF=Tx0J_9UA}*2g_rr6si$}3L zZtkqHY^l4o%qY*r{Vo`SWMh$F(hG&i<S+A}h`(6BN0=|&G~$jWrxK-b{b6p%W-8FR z^=p0WK)N`Q(ufbi8fZml0SyR*MR%N2Co_RUl8x+W^2FmBaAY@Dkw!2ARrEk2m(%<7 z${r|go4aDWFn>r7iH<|S%!JAuV2`@BJJ9*^6mzNqD!*Prg=UVH9pRIr<w06)Ml|1- zr<-Uc#>~&hzY1ArcFzacRLJi~gV#x0_@^Xw-&xT6CRDukYabg6NSj|NY*ml$`b*Wo z-fejKLb^4gG&sogrrIDTx7pxRx5K^D@Lt=PDnHRIaVFR(gr6S?8|I}F$LWhht8$k= ztrn|n#Ago!vkztwH0|yhIAz^#+5=9DbmSW*yAft%>Ks0xkORIT-#Jk7JD@LrvN#J7 z?LO%eX+*_g!T`O3JN7`3{4Bm#?Q_P7msRO|Ke0l^$gEl{|MsS?HfV&WD~JknBYlb? zn9TFTJXAlNxINpTt~f7xY^R-x7wYEOPayZ`B*i97A~5ng`+e3zJO72Ht4llSLUKCO z`+DvJR+ijaHcuLrNwipuLo>biu)t1tmyJWV&mR-pXn9LEUYsGMXmuxgf`+r*QqgqW z$fWd*`>pJZG>PqNk1BdyVeq_l!EYvl^Z*POkYps(1#unyoH4SFefI_hF1JpVKo<X` zMnlC$G^+0|`+TPD`Kte<2%inChIryoGeDVgfuYpD-r`vozk`pvKhpaFYk<V_^puDM zso)bX{qqDE`7(uOuU9r$iV!}NT#ye|lo-=4uAJ0kPtjqF@(ob}o$&3T|Ec*li3}dS za%s{#4@ij!qw!e`_4215=<B;Fy9u*TQskfCwE=ZIA#X*es1`#utY7hsN}#d4Zuk;; zt}bIx=9BoYd0sqye*i;X=Il@8VELU{5k<zE>bT@+A0YDh9=LAB=iw46g8?_)sU)n# zeU>(h6;jCo0D=9lHgj~~(V}tfevlZ9PG8@NY{AA~;m=44)jb8q9>6BU&G@e@%7k7V zn|<xL$@!_EeosTU)MeRUNqdqA6z>`tnlU>obpb~D@FBI*RPu*|sUDBRFG0OQn1C4> z^Vhhu1i%?djad9hZwN=vIZW&dfh$aj`1OK)Td}u4`bL!v!Z1fANA6vSpp-Q<E})1+ z>L3>A5quv+VkgVD>~4--XdWd%clhR9jkWPM3JXi5>fN-V+tRE<Xd<UqbnILzoA2Gg zSvl51N(D4hcGNGe;s&tQcwoFyljaIg5PW{z5$!!d#wL)3JF$@rtK6Fn3Ag7EpQZ4g z)rg@C!AO&i$vPufha-!5Lkc1VkBVmpA5GmY)6@|#>9xan-E#LWxvc<z?E%4MUL(ky z-Tee)yFYd&vYx>)q#=ae=xK-oB0mP`^?4T^x;~&CnNA~*_t#Tf6U-oX4(wC*CuYbR zQq<9BfYqBTFwWK+Plx#ydTSzL0MU-K$~Hfh0acE-WFUcXe2IT<mNUujvw*Iu8q}sV zhnkrDTiL^PEKzxZb0-Il)zKXGoxr)*X3@geg?2+ljfEGCBfrLWX?_)XaDLfH_jKC0 z0PWk>FY#J>hZG2%AJD1KjrR!z_oII0@r?l$2xYdP4$<0uRN9co0<C>$T9<F3_4%X9 zcyWBg3@RW50~b$0BAwXOdtVFJQh2xJ&`7jLE%#wlTegz)&7`B8AUUq<3ib?z7c$i} ziPd1{T70MOC_!*tE_H=ao)=*1ABtnGq?ot5Ejg!`wh?XnX?$>4{fb%YXxd(x^~6L( zy{UZSEqm*N^@JSgai8DN>G}cQPtPOL@Bp7-a;M7I-Dr)&$(=Aer+0g4^qig7#=W)u z&SX0V{J{~Ugb}RSL*v5~@x<Rl8Y#KeP+UbO5CK{~0nxqEOG-Y129WknyRa&vj3e%d zjq|dqE(>#_P|v#_hVNm7_huP-0d59_3o(8r<&BIXnAQn?Ys2{p&7WGJy3$v&W$GRd z4at@$(dS#;3~1=+AeS~tm#XIpd-peae-a)dHpw9x*&*5I!z$~RtLc*YS3(wB=|qIF zin4H7gm;TOA_NQhlG`atAFZwBysAO*O1wq$yfI`VDxE!;vlO*i0m0KTB(jt>mNCSK zcx1J4QMOV*el<QE?eS@7gqgx@(83YJ2O6&qj+A<;45+kkf3twnqyiduofF)(;zjGc zdb}7xqUj#Pgy7Ght)uQGE+JT(mpDV_wDoPZXyrO5d@d+Q&EseocKLTr+~0TB$M%y{ zqARp!j$jc63kCa(cH^*KIp7IBo_2LSd-%g%5M+yIrWqjwHA9@ut1p#KIEpSdEmz+n zE`Vw<_*Y0)E%V^Tkb?WQGc;xT_aTmW5^?;ygcMj*a{IYc%87o@<CHQx5;C3WxGD-C zm<D!sAr9kTG0!zvO$GKWiqoS)qOgT_11Y{W=c2Oiifg;5Jx6(&{s0f}8SKXF+UyQe z%B>c<PH(Fj{Uy2kMPaM9Ww$Es#H8t^q79`0nOe>lN%mrqG8M6eZ^53MYrPW*JI2G7 z+%*`4vxI?)EMslk4la5+#|zZyISXzr0IlC=-hMF26kH2>ck39@Xx(3>ILvM7C_TL1 ze;9i;QT(YiMO)8mj@xw4(RwpQD1QjzVHOti(*x2=4p$@K!}O?p`8~$@H>D!+&g`oQ z?+Cp=njUF{p3s+WvRkMRF&=_iRNo7PI=UMjL7Jb74Vy+_^EMqqFLD-oxf!pL4~@q2 zSQ-*ec!bFQnuUg8%@NU>B$?Q9;Xelw5hX!t7Q^+hH%FH=3hv{xcvlP2K&Qu?D|r6c zrfBT>8<kAA{A^rukZeg;M9$gQ5C)^Gc=Q^U7=UH?tZ>YfSOQ9s(B-IPfTGC7AXjKA zuVuN^>kicMFdyy5?<y`mcBVxDR~#<k!}AA+I<!<<^U&4J=2Fb&!i(hA%RF6gsg^=| zAOm@ekeH?QN>wT$r?ZR@*OwS|WJYVJ$(Q)7M~gupj<@ZlL|C0i-$?w7;%QcKYAlzS zMWvo%1OuWlQOyC<Dr7)9JG%3II_kE|KKiJ%ub7CPFi?u^v)afJJApB%6o76#zTH)o z&?m4LgPj><GRala9r<pD*Lpm+5D$<H-lxkWwW}K@RhS#?i-ZhyUshOZLu5Wr(p?r| zK>X1TKBR7Mzs38Mo{Eyg3a-1w7MZ67)V_0(AUKcV%5U#LB}Wp^72<7QMM0g|L8k)) znb}l@B^m-m^UzI6p;W79$K0uO>GxE8B*F{FA8gMZ0`p`b7;O7AU3z)>RFT{E_`D4s zP^!<{n{a9aGTjW^AzR<mp&!i3M=o}oeHe3-%sJQ9*lU%oO_M|(985N~>=DM=nA7TM zMV0Hvx;uBt6ga#CZ~S!2!{F6tIXY{#o#13*{Z{e1hTns9gn-%jXG0u7tNyW!eVSt% zr}s8w$uE0kw(tyfBPA6{7G+>7<y8lvWqKk;b~X31ctpzGs^Oa+K}&t^X}O?kqJk>= z6p!}RUYVqO_F>5wWQ{j9I<tfcq2^u%!ymC)JBwA^y!Z2Y`!YLtJAwk3C3gAQpS8$5 zbYnXYBM*6gCf@huQz$lL&Z`i0Z@9aMmH7$f7DDxP%L9u1gkG2SSY<#5;*Y?k+{o7< zGUT3>It`ipiAA1k8oa!;bt&UxWwnr$m+!^{@W1GoxgMdpMPzMA>|$g{D2VWu<%OaR zYm>wLXIc4@f5c33WYO+FrwlTpsG?8ER&)v3$H9-Mb~t=AcF_EosK-YN$~XK^m3az$ z$U6z*y;MX?r&|J^{4$y5E8aJeMfR30kczZqc8kz}pB>OZ9BQYORbM=Uorx@I1|cw! zjd8An+|Fb<&7YrhqKC2o=%k#|=qzUA&gle&2Q(s(fp|vC?+o!^;B|%97L)k(tvtVq z;4X6mB4ibf31~k(aZdBqo*D-Wr&EStU_C{|YKbK<h}KI;_@G~H#WU&v5>Gm=qigzg zzZ6j2FFE&D^wn>f0{cmBTckqd#j<hjTyQ*cW-+sGIE9-rvQMR_Iy<Qz1`GK52?LQn zh=)wuLpA5LMj-P+a{a=T&k7sjE*WD9S`BEEFuCvz!hbW)@r%#PeOa7^?bqkk<=%;x zV^4OLUxS_2-Lw7Z>do;|%cdEkxtn}Hs+2eAui;B%qK0Y^3Ag#lq|6Q_qI9*KpxG?i zj_s@ry;{RW_G3f3gHEg=ucZ00IEi%Rm?ACFy@eltS6W6Sn5S<F6I(jCe;N4I<FG$m zio=TpEE2T#UXy?L>cqd(E^T^8L<37oftkmw0251Knr%edz1A+HOvqq(mCVeG#N<9H zQmH}K2@x;WJ?;skv<w;jebug`XA{xE_boS>`+Ng=0#U?{DWkR^LCc#K%XHmTAW+X~ z(hyjcO;N$Wub)H^`xk8aMsp@<rbjd}^!R~)2CJB>HpQ|Pni1y@Ee?pOL_<~f9L;0r z<X^uXJ2$6S0^z8nZ*D3ifsNi+*fI-tiIcj2{9=%rOpgbCAM-jX*D=6pqLMq(`hy)A za!h}u{M237&<GxlogGk97Df4r@dB?`d`^*%dVu*gjjZhtjqh9q6JHh8tPDb7fnxzG z!7@AIhI6k}RPqQ(A(DDRd8XT8egXWL{RdGwWC<u8n|acw*~`o*n#A`p9YxEI>!N?? zksm8|;gKN!j$!W0@`LRCj_nO-!c)@+L`%ZTb?%U~qS0?G+lMsGkAM<@vQaG&<#a;W z!@o0EI^fGh!<aQYgo40{7Um%m6rgSPdVuVrzQj`8>;e>8Mr7HXXym=Nb$J^wlBZ+r z$;HCWVc(ZNHx+`D=*Y&|%ah(RzLg?NNb=<@-Z6G4lR~akY>kqM++ydq_aQ848%v}b zF<K~f1v2hl#BZDOcK-fBI402;N{lSdyx_Ae4x9i$(-&ZNycW}BupVhrym**H#K|ly zHe<hdQseh}K1|_{Xd+h=0zIPc>`gt0XtlvZ8I`_;e47Y@Sc~!ox$wey8VjM+kwUk$ ztT8gNs^f`BSpl^g$^x{qQR5ISjx7^QWiI`Gc<I$}JR^h8Q&?Hx{s|Z4wQ12@XIb(w zD$8Pck;XGx{e6dqU)a0&a*Vz-kGf!L?)xrr<?7qV4|ivd3`(NlC$YN@4NPTGaNq8D z!rh%;JQ6t|2H^U`H0kSbWHKD30(Q_jqBMcV{$O|In?zfRy<PXvXri~7Cg9CN!6<sp zL8+?6$O2jZDJ{<KB3p2r47oR$6rx7%G6?aDW-mBG%~1fxbX6gIF+7~4jA6aQB{!8c zD2ocqzxIt)+oAHt=Cdr{ZE#PGeQPbNHz%DqXOuSbSA+vVt$Ixfa^H@4<bJt(yZ6hg zz`~!~-Usvw8p{d68c_Lm;aQ$KMz39{_U`ksU;z6T2R)TjR_I9R;c>`K*7G}<cCKrD zw(lco)#tNaDVZ2EkI@IoNH<=FGWi9W?m*$2%M0rclmQc49n79;R@QGlQaucjw!|wQ z4k!ZRK{qD4yuHO3wp8td@PU3+v1j$91U%1GodNJp9gKv_KRc`yyLEKWBIX7)A$F9R zNJXXm9f)g`ImoyOUxFc%C6jrsvGvoGGpX@p7GO3U8IshhIhPqjb4#Tfi<#}{sT%GW zw?GQn7+TArLQzZu$MJW%j<?l1A-#J*Rk|6tG<2dZ%2pfl9U-9|aaJa+O0EXF!RM+H zGAzFiB~TIB=0^Kk_-4#-_Wb}>$Fyi(RQ2<&nvWEv6@Oo0bI4^@z64Z@MxnXfD7<P4 zz!eoaKd^jzHNC%vWZcN9l8WVB9DnXG94Q{$uFNaMV`}V`^gJehCP8^J>7a2QD0|fz z%syt#F(7FLtGC||%^8ad)_XH8&efDdz*eN-F;R3psdY82RC+OA$Ec!*)mJ<OdQX&; z-p?>WjDki26r6Uh8KP@AeS%5Ch%wSPPMizz8Td<OmPeS}8I2x<)SymSZHjQW9cE>r z?f5Z}{~Ae+El6>4A{~_5OeyuJAJE+*bh(2#=~0oFou$w7M2Q8J@5G2J*HnFT5&LBR z<}FjWLgy9a(`nF-Ii1GWxhilRinwy{Zzs8O(wTDe-iDm2#1&Li16v_PR;){1%ib<I zbo-=KK$_Jz_iW>HMmbORNe>DLytXX71&Y~Mk)DZan?&P#kl`q-+=eN09TFA+B~1+d zvR^i-rHj<*D0P>?ma57+H2;k;%K3c#wRT2G7oAxmM%tUxR!%HoJtfJd**y#@BvU`^ zYVMdsDiF~w<5jlCZIRHrLwd>ZEvS`KF|D#MWzYO4n)NK<pdANVufR-+(ZZ)IP5I%r zjC7eRI%b{e*h+S7pvZZ*bK&x>>rkZF=bo`eTiY4n^i(xw>TpP!KRv$9j8Z|npaM1t zklivR<vb~e+MKwVs~{~pE!3r%c|t=5qU^k-#HhE<4_;1v_ETg!kWB%>+62L(SXhx- z#_6hy?T7=FZ5b~xEl3RNpb-{HEZ8ghOO_m&Xh;n#+K#!G=XKSLlR5i1Bce|8L0l8r zFp~#+&~ErC$6yV?nl^mFkTz9EITJ#AT`%`rl5b^AAhCqm57ZTa&;bsn6jh%aOa2SF zJK>nY&&dX!Rop&RU#SPRSLeKjes1_X9sye&h@C%#brSnR#o7H)Nh}Prb}LQ_#KVuh ziW9sGHX5|_{Y=#oMwphIvx+D`y478uq_xV=*WwAtsonu7#JoO*Xt6L0o7W(_+L+g& z^rjRCr(km(qNIay=`xXi#8E4iCzKG#G;WT;;;h5&EPp-$)bRWX{2dOX$>l_n3TZxf z60~9qj&lr8V6Mp#fdB$*2j8nhdewH~9I%5U=B0?6FsnVLOoIV$PRzLuXdm4nW#^h$ z=Le097%d>+8Bizn)+skz5;LP%5R_~Undjkyb7qkn2W<td1&>US@P06<=gTxYrTHp+ zmP)$@pq<8;=o?EN&34%WYm7NoKk;UuajBIGTjC+7TbvH0)iEu>rz#6;*;kq$D9O^= zZc;n1&c-?ikK=GgK{LX?QzJ~;LkeC@A9fRUj9G1K_rmw)3GC(UTc7FPyw7xOm$lG- zi<e8Glrr9}716smv0aHNKUnR$B=bFS7tCjF5Sm`!r~r_5jT)SM`_e~4Ma~thq+pNb z%Qe&nNvU1@h&MqM9zBp8T9UHD(&v;2iZ@JNOynr7%HqfX*iphVubF9~kh5-?=fxmK zn4!D*_|Bp}KI`Ii&JLsEMYxbva!#n<+13q3IVg*Gk#$pzl;Vky=$v_A*`T><Y%H1L z&}=$xZjDxpt{1_(&?|bCQ5)SQ24Vi<R6-QR@~^UYcOOJ03>i<-w<FSzez~r1iyX?; z4eI@@yXp_<VooOoz71$x(?q(&(-!y`Z4qdtNB>i0WqC94>mT`*V<6vEwhfF|aR9)F z_|lX(TZHDYf{1sDjiEk?y2PO@eOxo>X<O2yoL26B%vo|=fSp>R_jgjpKa<R=$dZX@ zGc8WZ@CHtG0|xU^Bl(vcu#thHmIkv!K{sC;<}{JOd-*II#Ba?hEDD*BEaKP_COn|I z6ep2HTvNujI!%QI<A^_oStp<{B|GxVz2f`Wq4wJLTMp}uBW-zm<<GQB-aEb%18mAl z8pZ=nA;bMAv6UG7J$&9;NwhMw#&R)K{l422aD!x3$hhR4--f1ySZj@l@?nCvFy2Uy z$fL1x1Iud8imiW7C4I`^?w6p3j0qQT1g~JWy&86b5cc+BTg@$1c@zOk-nnC?Vs&uF zcf<kDFUU}<NriU1F-_`%PvA4%mOaD^DF}Dj06l_S%JUy!;<{)10yILt)R7gCZsnC1 z*MN(b)8m7fHrDGiFV^}Uq+a{>bB5#_Lh}<o2J2h6pAc7fSBvu6d?DqS4!}5(Ph9!> zLu51CAQpced7yxKO2;uh`Fz|jdgz_UB#K1w<81<U*5f!%Y?*J2xXPaV)3|v0CNQid zl5GT^b-=N~13TrD9B#5IAEL&V(3Gik;9J+sxY4<@bGpqS<w$y7QX9iQ+?MimJ83%# zpoSf|71bN6V*md3-qHZ<oCFwD{k68MN-67gW4d5lANjK%ofPzh|7O_GbQ}Cv?ujr$ z|1<Y}ybU!5NvfN+p~qP5!7a;#yc=8U^Fvnfcmjcu5?8*JIm-x*mg4F4{Ct{XnROYW z&S$x-D<rs8tPT*Gg8@jQ7&j_GF`;Kjlvl~X$?Ls$2L5>50L%MS!a@Hs0V-oFU+!fH z_6#Rq&;MiXECZtY_I^)ENQ0Er(A`L<G$<X?T>?s%ba$uHjYx-d$B@DR(kNXbFm&HN z`hU(j&$;*IeW#<dXYaMv{;gkqKZ^!(rr%rheIMtH+^HY8_U-1c`fpgh-8&L*#QcDA z;Sj5AOBU8rK;|=ftfSEy-bx_&TTPrQ!TC(HB@qQOCbh4Tls3Ps&&qA(RC=PO)^R*6 z)xORcd|Bi)LsC$3QI<`oHaSm9qW74GuCqwmpP%kgkTGS(U<^?bq=43)a(+@VWl+=E zmnGK}-%F!>8dX>J$+aMtuZ#i`9J4;z_lxXMRrn+^QRF5B@f@Be%TaX&9B#BHS<;jP z%o_N+5M;`5TdO(8$H6Zb`!&+`+oYmTNlHVmJfs50mUc}~je(wavpr&RRB4In&Gu&S zGansgep<`PmbySh<1ktAwu56c#(MQ6soZyvDpzb*p^RhAn3dBv1y{g}!ttFa-9fc< zP1z!^I&G96L5dXqCZUe9{EThkCut^Tnn)YxyWWh32knYdw;zd=Mq9h>BkZI<7Qp56 zAuT6JR{Y*!e9TfE7nO5G-m!X18b<Wm?<~<RiI@DWlXzK-%+?jn`qP8R%>$icSp3Dg z`?+Skj)#e3H$2>C)Z~i8PlbnK9DeZ*xzEQq2_H6S>`Gu?UpEZ0xBbG~5Znx;^R`Ep z$sq??7CTS+ATM0&7x0xXsfg@_0{WWM*RZ_ItdMiV>*~-V`i@IqX*VQH2t!!C`jAcW z5nWa3y;88f8u_2HJm46QB!ys&n6^+A#fSGct7Bt_QF-bZx@nCSO!4g{k%=`09&ctH z$*HM~*Wk*v0#@H!uIC!tX^}k}^F<lud;qDJXD)hM%&h2cznD2+%mN#@w9_Sob&iBm zkWB2xskcBxE)CIOGeyU1#9eXF&xM*(Cz;kweL2Qnh!e=+>|Z2_3^cEWk**^LZ%V}N zJ`+6Ss-5t|+j<>N)`~59Hkl!|{Y0&U`19o_+8>z{JqfZql5!(6!u?Ph%4>O6Ex6IT z({i1;D#*c>Qx@P6xbP#m-45DsSZL7e3oaZFA2Dprx=CwZsa}8-36erg`vcWx+)X$z zD_)szdba%r!F?3<7(=zhtVFik`j}T~)}Y9tK4073)_-oU<gp$W?zCjpuGo2Y-NE_Y z(PXSnJ;Vup2&>*+I$#P*@?{wBxbks83JKky|EkJ*4?U$L(D04tS))L)s<2LO&{^$z zvsa4ZCHc^guM%_VkzpA`#@W{+tTYCx!T%J2uXF%1o~OW}6x*K|($Kvadh_(eEL|`S zszz~cb;{tX=8uYqf<+>abSR;XVjD7gTk4)gpY1afsFEttDR!2RJ%G5*&2d9TzqzBq z_>)#n*p_Gu)E8`GPw%)xfVkQSC;;Sj!IHl~X$B}{-cFV)nLP!{{6BnL=1Iq#oyN=1 zu^Xyewm*XMcKZm|M4d<SG34=DZHTJX!IBweDBh0Xg!I;e@b;P51MNkxqEyd3BGG=A z`4=1rG|=bE<|qYT_F>&(cQ<}GDsShn9h6(3;p3PiulrsP*9jQCDPmtvu?LEpi|@Pc z*A1y1S|_zcTk<zG2@kw=ca%`Z@Ckd{5sN4EoJaVHeT5j)sE%iBfdZt;k@sBNXHs3& zM{ft!EY7KG6Z_l)3!oPK^QFYS;=+4P@3}jZ5;Nx=zfvglMLpK9pg{{MoZ@y3y;maA z27FdE1Kj0N-=NYNuA9DNBpA)?3#t=EP0pJv;5OOW!WV{fIJZ2;)nue|0`8o@)^{SQ z#xM~3L&lSct5NaexnkgdKp=Rs98Mx-tp572B$6(lLy(1OA*U715VuQ=xjY_<H)pS| za=24$&-fQ?rAx0J)ZT6klutsOMlYW-qSuA8*3+_f1n-(`O0|NX^qW(vzK4JmQY3YK zlF{&FMKcUrp(89CeU}X+D>!VZ8QP!A9Ij$|ifdKKLIU2)LXQd8dj&0mFJ3;McMPiR z(S1AAXPCCChD>VoGeax5yOsxZ-rr<;O+n1bGLR(WXmyS@hY-{=hV4#tfjuWRC*js- ztw3YR&C`#p_Omb8ZiJe=4Fe*7-%XL#ouWhEo#~S@jA$4^C!J9_st<j!u{h<<S=5;z zXs>S3oju2FL%9Q1v#!Y(YfqN(YB$EJE&fgIWq8M%ErNs#+w|t5D8*6YC<RS(D2`LY z8E{!!HtuPg28*UuOL0hAuV_{v98NjilYvf!k^*nMb(GrQo-!Vp9Pg#<!d){S{cby= z$i_TZ&)%x2+7euY8gT#ZGdaiEE$ae{DiBtav39Lv(x%N*iHp?JtS6M;O}E@NWhK@8 z5J1SAYxA$ss4}dX`R;f@jm1$qP&`l#<_vzefnsJT5P@WYX#Q~lIRa^r6<KhQ1DU;* z*q@4UF@ovr^me!juAUC(**XY0=AL*1haiIR=o!yDm*ZF}vXG}ifvjQTvSO`XaAQfX zVkqiq`I(^oKrUrJdE#>mL9uI)4e?`&R5q-!+%qCNF&<M=Sa(D&yNuzy;9=KXyDW=K zZQ&{b1B(nP%!#}Xxh3G2#F-6;xv0`FP)x%XBIT7t0>yYlV(tQG1OgHoR7#kU(#-SC zYU`(qgxvUUsN@?8LJgIgpc#;gp^QApDkL#*x#m}bfIN0c42g(U8yL|jfoxyu{sQP- zuX)|PJ@#_XkfkQ<Zqj`Ok){g&JP^!{4n8lqpFxKraUpmd2R6K%e6uhAp%$fO5DZ;{ zyn60A|AGji4;ri9qOtAR#ttY7GX}TOFn<>%D@Pq6jjg>Mn_5SDA;!<4Lce>pi_z@m zR8-FMsW8>9h7%dBWQHov6~mQJpz-ygjcWG5pVWq^Ea;Or!Su&Vt>;dMY4ckmh}<_X z)Tbm_r$IA@jd`MHSxmBGPbBU24M{4Sg~T?PWyO%&25APFVhqWU1xz8Fp1OiT<``1S zULdptoQXsR$~ci2e;jtQYtE)j!Jdo~gLM$2$g{0LGoZ<Emx{voN&uC-UI2UNGLLhW zt247$QXD9hP!&nxP4>MdS|9$F#1nyN3ULbIdf-}RP{|?N4E2P(&~}NFN)teZSK2K{ zw?Ki)5U+<~#Dx#;Y6wTr#5OtRQR>HK3P+%0XY>%LOFgeQ_x6|fgkUYc^3A-5H{LJg z9v*U*vw9z~0ngX3q=cui<6C|DO<WwJ1L$Eus{I=N$7<v)ep`)nW4ESP2`>$k)#KXR zH>B?~Fhh{2;|noDsfKYlv%>=(c`*Tv_Pr~Uo6C0%mFFnrB;<(vj9A8N-q*-dWaooZ z3OL`pC6`UAh20u})}cIIoNmr9#Nk{lxYFfs)vZ~o8nb81$nrVHW!3q-N$GUP5f)5r z<POd!w=z2vQ=eH?EDBndMZRN5R^jb@D`NSjH&ylv&}H@Foh0E%@eyFbUAJaiMnE|= zBh2Ro`f;v%G;u!6Izo{gr!3i55CxqM=g18c1MRj%9g4jvK|dzB*8RLDrZ~@8eeTVn zNZ0)=fj#XkpDmd%&hUNxuwp6a6t*wNg6UFU&(gNioQhwSYnbja-*d;iCMt`dD7!(t zq;FKFL6a9Ob|2|6<HB6s`xs;6^4q7%y}W3!;?f$bL-*svXZBY+>BNA?HQA*O7%-q% zz==Eh6~Vh@VV?oXi*uw4B4KQUm&j|Um_3-&j<?_6R?@znBV4-2F;5<3?j_rr*9$8) zM2c+i-izwvz}(PVVb<|Z-0DtsW7qms@INeoy|S#uyG@OS5T_(6iXiH6zbsdmsyezt zUe^?F!E~eHG{4M}8do(er(&^@*_O>IIkFug>4cP$Gj#?hvbV;%99t|KBdsZxbIDp_ zXLCZcp;zkh`-MWOwv9qQVhy+%6&_zn!AhkQ(Q!q;Fp%q%MVa)o5f4?H8N9QGVA{V) z0faY8LL&wX8Bug@hhI*#0~N`vJX1wy@mXdCmv>Mb44*^<vj^Of(djovL@CbXc&PJ` zv~!!;$&gggN)Z<X*0Ou~gevLoCDz7a>=k1;WeZv;F?j7IRyn_78>Ok<*T$pWV_ORR zvYx84v-@+>tHX8O(Qr6r53Ixw<YU4ONQS&Jjr2WCLH9|iS?k5dTh3Ly>zZ-v@*D>} zg332&>0Tp1kZCWle)tg^{u?c3_lw!svDbR54I!ha@MU`GGN1ADe+x|P(az8pdz6F! zsD1*Cs1j~L7Z2an=){RFiGN->AnO$~Vrbs5$6XA*rCag8r3@6BlTq7(4y{A9lIqpO zm(H^~n$8E+1{twh^hjcjxwBrx*@|o%n7Z2B(Xi_F7Hf#qk&RS)UKg_u%VX~p(Xe>= zG=`roifn4>C$gO<YmcOxLL8Y(owcv^NrzfS(y&sCT~hV8+4>qS6^ynNwQm%?ATzSV zb2pZ)t|?B%B6~s+3}2up1oV{{N*pKd<B<W@NytB2_mMZPG={pz^;e4!RV%}ySPzWc zaV(puWC;K0na+>{YqInsu_%z;b7V%|>xO)fk~GB2R}}apm1uOW|7N|TJo?lf5#Dr_ zSglfiXn=i$vDywdJ2<A|dHm*R4cqiHt6!E@1+GQ7a?i~h&TQIc(`wF`4R?w>o`t^> z6@>mwQTD?kxhU?e>Lqxc+QqDN;~H1ZCr>Fz%RmlhQub2NXkRai<_#UzF^m4PnW)hc zwbPElLaw_$6^&2tq<$(Vl%nHTt|K(UyPl9(%_lAW5d6jJ_lVEu<jr6FM1YAwbQN_= z##BA=RsXUWP(2~z<f|T#`ajLF-<9KB9vmgouI%`)a3auCE9kmV(}=#jXmKV-U*I+l zj%5Mbl$c_FIxkbRdJT-~tU`{MV_jq8N8}7Lt1)P#Rz?Jd3*}5VLFhspqpJ6bJ*l=? z>8*n46-35^Ov`0rd#NgZTdC}j5j(Z8R2A+mF9*_5Ue|O>rmhioO9E|*?9uAdZ~+7B zo0K09ld|2kwh0E}LSgyqGm<Iil|(uv!uBu)=B^8p;!?}!tj-2A2fOcOA9?ljs)81Z z$hg9Bc7Hl+76{9KDgQV~ef?tiP&sk$RaHIjv)PiloQfLmP7IcgGrMV}r95F<^1YNe zy{?oa<}dBw7kKRFsZjEPxsjQi^bFUc;HyQSEiV#ww-nQ1a5bG(6vwH+vH@xa?Tfi{ zSGzyEn`|CRJtp$_Kk8kH$nMF^PDZ=Kn*R;_00h{1xj38(`wS+P-~YGL7s#bV1}H!# z+uv0+{`Z&eLjb;qIJ{lspU%1e;7ee<MtYSLw(aIp`M)6%z@RW7A;-|xcC}w-9F<nQ z{lC6>Mhqh@OqZ&tkTt6n$`0gfXNaJo{abMO4|8J77IvA}pZM5-HWU4m+G-fy0LTN; zFTM-nE%irW|MuTcfd{)T;Jmwk<T96?vD^eFMshHI0;Q%8n*PU)|5;(k2(bTaX>K<> zRb$#WViEq|4*`T_7_k4+D2-Y`TSx03m;W>9?`Z#<p~8t!iHh+&3CY%MI2)WCndD#i ze+?260-|iv$l%MEkxbeNnKVVg|HlvA#{#4a+VN+@{7m~tN)Gq`bCHjv@C(lx>M-V- z^lY!5rgM`IjAsefGi!g+@j6y&c^mdU0Q!Pj=To{1Ux&Kx`G}fcrM;+O9BfNAhmD+C zF;telVqVRMY2!baf{+v(o|+PELp>0bzukK3F2|&A7oH$jmo(kCqAqT_-e}IT)7Y94 z?@bdf700dUwF%b$kWx)wmZh5XSmwZ7Kf^%+n=0P0Zt!3~tL49S$bmhv0jLr3FTJX2 z<Od^gX$rV}>YdJZrzGD=b0^?(y_C0*5}H&I5{kf2OeEVW{$insS6o+wNP?AGaR*h} zobBXRKG$6MoV;#l>H7|lbL{|&+$}C%<6koqNEH%*DlNAe<e5nD@rlAzOK$>soH`13 zv-b%Ym%|KjggL!{Jp(tqBDK6<TYGsXS*Fu9B{~b0$aXB{gj^9O;qwmb4q*R!pqrXK z`X8%@oCbu)<$H4mVwaDy2NQ7xzKOU>kR_IDMJ4LA;6;=sGaX0{7f59z&r&M2igc|K zfv8*y6;-6L9Y`CUDa5%mV&(em*1<;J8ubcS>YJkr`@a^PNdgrJf*=^g%bDy9wCNX< zzHjHU(v~Iz5mFQ3MAn)QmDo;~6h9#{-~=?@-nNyE-#;fYvkhrbBod;cTjIoHt;?9@ z_}%Qe4%4L<!5X$ifyNiDBxymG>UQTvt4|IPLVf$h!FWna)Q5GVE_vWzRTeGN4SVI% z7pYfZ;E!qGZ)p@h$3162v$||cO4qXUXfeQjU_b1<{atH++`JK|lzTm94e3SaAZxWd z5CyYmRsc(g4Y1L{7m#MN|5=bR5*|2{_D?radxP{%LkS>2BUY{v07h{I(t^c+hUiw( zAVJq@fM6Psb>wR6*%kwhI@ra4icKsVkmgHzgV>4=fgf{<0bXJ-R#BnBh^!zE2^d{^ zJBp=B9)@ty1H?JggQV}tXiI>s9aIdE-|hi&I7MJ&>{@>Yp+nkFCrHolZht)HxUaa) z@p?fwc>&SJ6ZjxT(TA&zJ&&$i!`7?y=xJb-6Jc_WhMk-bC6V|HvSN$<@Km=G9-a98 z5v@KzN%Kpu?0tyL3kW<gQ?1ef^hha!_1~Bzj3-DS)W#w>NRRy}_b4lV{}w=jvBh~F zfn~7{5F{c<7{J)|{4f!t5EM)^U7T+8@i%a9e_Bf&0DA>P&BSIt2P+8%BY6cDWdYh{ z7#SpvyYsyAeK8;$;k7EGtzMuSF)4{&0J%Q=L=i{jrll^-EQbMDAVBwSR@vjp5G7@i z-AtL<tS-x9z#Z`YoOb{L<E&i8m)WY1QHn>kXrsuV(Lio)3Katx=}sA9()_e4_+KV` z(hdnkeGY~@86)Fz>0`yff_6i{!USlsr2Onwp9uAA@*6gjlm_h~Fhzcea`wkRL>@km zF|Hxa^zp=WXL;+3-BIHQ=hn;B4>U(Z;twY<>1U}7p)PIO1Q+6y+Q2t!6=O0)hP=K% z5h>+iIDnZoKzF4u#v8fIMdNn8m0oI{>&tftjEybOP8{c*l-uN3!$Qep#EQS{zT{xO z9SvoS<{O>uleUG$)@AV$OF&+ArS@NIE&$i&InrCSU@JYFJk$}hXtp#gfu8}Om;GG& zt}tmhMoNGQVR$A@+Rhq}`GBwtpdT?#AcArg2K)JtSyuQ&U?5>4GyvH;daF2)VLwe@ zl1RjK2pax6ITI?`$!8jGs+ZLEn}t3;jcAl!FcZ-l5A1lCTrODudWG}Qa06T=Y%+=k zck_ZFMGDD5jx{2`VH6x-vK)$NE@547_$ne?_W)@I725mZ^`>c487(_FY7D0u@d_kL z>d>HuLl=>Wnj%jS67CWA04(4V9b?}YICAM^P_Q$Ok<0iC^O7jn{a0Bd+7y57tHe_F z_l)-9|JZaU8&D-)2}r*|-N;BZEft=i0s)d+<JOz~ir}*vq_{1|gD>^UMUk{?={$nF zDXZKLqikPeik-pE5)j5{M1=lZHG9^45s1|Dx|v8HRyvCo@;z!h%j?%4rj|KrCb0o~ zdyZJ9ZTl~i4s7ut2>~mUhW^((3AhnYm%OD6=F73Tds!!iS5M+VELqX0YlSGrNGO!0 zyc1rJksi^W3}|v>N317U1lR97ueZ-aIee&^co-;^?j2|3KJkNwAR<i!46HyOW;U=) zSETX|+4qgal>V)4m(45332>Bfb{y-ju?<E=lMcR&JC58Tr?bd749u{v=|Sc?=xc$d zZz8StN*Z)r^<fFK9yUxX&z`}cB8{7seN2duetN7U08E3|cB<A1PTQ|IrF^^^lB^NX z(S0kWIpz-xsSPT8a#5H`UBbU#7E}b{9Z|98OnH=+Z(5O=O!@YJ#_Nb!e8#vfS09tK z_w<rM87H_?J=TLjdx<=b@C2^h8-Wxp`YKnjI(@kOvo(N_Q!08fPXq8M*R@{ur)|Po z@2B&_DL(!Ntls=DcwJX{Y@y8**|uN69qdvdblSCsrx*X--%M~oAf9@6T(uVzQVr)8 z+Le=_vd3kkQ0PaDX}71U0_6sr4^8wkipGYrU}<YCyweeu>LLvl(Z*IPg!&ilF8xib zzg&lI<$;dqH#qod!)#r5P}@klv<Mem8eF0gYUQo<XhtShXU*@?ykH#464A%I(~5ez z_VE6u4IFy;8Nj^l&3ha0DDFxiXOmg#7W=_Gm0dDmm?ln~KK~si3~nUOn}+feM~v0X z42U4R{?Z+(*cWJlFEguC5W#8N?62R;%D?Ld>YuI{KAl6=v_FH~RpZ(~r(Y4R>rIZ? z_sZFAj0~KQ@=yy_LDP#yLZ4D=wFE>(`K;Xcy_e%*TMP)yq(Vh53dtmLPc(1Z2A=Ut z5@?nG2G&&^5*$Ci3P@ZN!?2*kI=<4%jPb5yty)d%5gdIVuhq!v<$a3W0gIpv7##O@ z^e6DWf3}1a4P^zGJZ=#Xi%j>RP?C}I=Sdwgmm5(lCQki7mI4ML5+^8M(y@?a0Te<u z4jww=r5UoM5zr{Z?SpEZ;S!fF9Lw-At2|G0A6V38OlrMl__f+(`FdrPJ!-DQV4RkG zen*@J>PAY4!Du}C9ogAIZkuI*i^cediHx9==b+D3M2?w}+QfS~QgR8thwE?tB`}u& z6(huKB!%f@0vic!z274SMiT=u+fTqP;3!bBsuzw^=zZe+B-cVMR!`R?E3d;Or|YwO z0Rwt0S|q=Qz^E8!mtBvduz6J@+P|yzzh}7z%#5=C&2%orqw_R-9tj~;&rAoeF>b`Y z9hlF08j~bmVfwf~EusLoC{Cg&o9m&(y6^ftlLx}`zALe0;$zORs^75ar={!jD<6q; zUOP1^ddVbbv29N8BkzJjotZC}S`;>z2?ai(S48X|j>j{vvAGH%yS(qNG8!c484JU< zDl1RFn2ar2_LAarqh9t(T6uP%QultrLfT+4zE-?Ti}(OE`I+r41G|1!8URSk$X@_j zDuakmKJ-zQBAOv4t{Ets`aoUNi}LX0?m?2wmn%np9*e+60EzcID|B7;+8Owu#(H1q zW7U_TCbVBxNbL)N%rKHlGg)TGJAns{1s-%pKs$~1Z$1ECT4K;l6Mln-bXmiyJ?EY8 zU5@Lm)T1(ovM*PMXfU?T+ZOEsgzAi@eoI6T?UL8En#$-M$TgBKmQy$Z+I5n*G#SIv zIrQsKW5;=I2hc`~*|d$sfv!<?Ti4DBuJ;+kc+$*OrW}su?h#wg0$?yO2@ij_Y(oL- zurQKBz~39V4CA#!TEMwBHAimRA-txd5R6Nj!Qm(fd6(^>={q99AO<}jv07Lm>be>L z$|k;yfMV8R59TJpm{~!~wHxGXfb53>2I)dm9|*%su>*wD5|_9@fG1`(VfxpGyTApy z7nL!_>qe0D{ZQ7JUfP>@mGIy=nmdhOEs_`(KmM}s^c5uL4wEDT@1Wj7%X))HKaZeL z1miSk41plk=Ed1)#_!M_tG*ZP5@FGqX|HIT<+%=$q^9MHP$>O4V?T0<uyrh$*`6J% z*;>(4Ceq;3Rq4G?*x=WC=Lokpb%f#EtGy~92963oi?{<406f6rEXCws=5(($w~AWG zx;^R==X;aEYn#;nvN}SIMq1`v0^ZH*bezA?XFtF^GY?2<F9T{+2q0>m;C0)dfoYVA zr&Yv7#RP71AMY5*eb1(B0UhpZfS6@JBPH}Q5e6Ka!~r~4%pMD>zdJZF2C9iXcW}SO z<d`lGWaev03ID2}C?;w4_^#UZz!mOwq-Z^!*PxBI^0#XG#?~ykWa2l=eNct!oSM<e z^oQR!9bD&a`rkpR;h=#pMuS1<sT^o?4ufFRz1YlYNW-hAR<RQyRLLPemZ#K;R;k|M zpTJQ*sK_DG(h;0-nPg-;)buAyqg~<=1Qs@cSU-;ZH~1Eis+E2?>fmo|Xy_k{MaAv} zq$$~V<*DY^%SlS?nShj`aWcP^YN$t8?rMyXi?j)*!|1~n7XdE<jz%IZDSj5I;!}`} zmkpGfB&<<2!{aAHvaJ5uyG@j7K;|{9>CI~kc@rO^iW9x8OnYBO7tsx>jO}=pL(cAG zA^Hp8oV3`3z0CeGumzI}^FSON4|Mt}^BT<a%+^ZG>g2on`-eu~XPW2s;CSv2`tI-d zMTwyhzbX*D{Fa`hD1_DOm26RM;f?}&ygqL%`3sJACaXlN&C7`($Ia8#=0!{UkEUyj z`MIuGxC{f5A&R~IR!{ZcwOIP7pn0Y3)xsn3DA94f<cMpoB2&7{5LM3v2y9BNux{Ca z{BWp3Av?3wP7zN%47113L|dw?B7X0B1$LY#0cKbfNhEnjw4K%ApM_2gPx8@WV7v5m zp^PH+Qe5A*R>8J!Yfed{-su|BkPcbmDYdSRvW@kMvVFsa%>~wHh<BFm*TSRj)c1$J z(r(V#)-mOZE=X?a#_mkOyja#O(;KkN)uoMVcUj4(Eu4O<RGIWWqd}3r$G#)bVs(%G z8&;i*>3c&3R}da+MX;+4AXRi`9i_pfmJxy85em+K{P0cmGG^hqRpLC~T~*ufD2JAG z;Nig<5AQ}fZ)BV`2{-ovuSCxNyaVvx<h(Xb&C&Sme%`*?%%=d*m5GV(ApA@A^{}X~ z|AS7WZIVVN%s>9`4Os}OZXwH>Ty{q{Tm~x4vQ*jZrDwjNHEphuqo`q&9rWb6egO99 z!xwv-Z)0H=eD4bh`s%YWhfIf!kh~#$3zwq9`rCUQ<Hm1EpPQx$Zda(;3O!>KW*<1l zwcRY6vhBT#E-5B5U}a0%j($xRR!__Ez_l|&d`y?Qhx!Z`dG&Nkdtq~WED4&rlYk$A z>WotcOcn=BH@KJOG7(7vvPwer2Ve%V3uLaUSYFbO$4;LMUF$+G0q2>bUL%2a_{482 zSw$=p7A-Q9P<QPcheb}yVumbq8f?*6|1oK>oE3#p8sA^*Eg1wSVr{VsweMLwEvhw7 zlaE$0;C-E&k$Y$D(#nk(D5<xAEYg*o(nmle{HawC$$`4VtiioY!GQ;B<(pF6h%krf zsIaSxRuvp=xw8W^+te@ht&!Lf<cE150=b6HYNYB29}B8Uw6g?sT-07_(x_x?L8>ps zcHq>IGM*3_`;6B&yK>^sdE{ARKU^$Wn_Jly#_}m9GpJzoQj6|}6R&}*>moJ^YhWak zcK?PRWK!wua#AmtT<VG)uiqA+{ou+`xH|siU6P?VTps%U0oEtcc%KxD0m$rQB&1-e zJ*4E&ziz(?ClyY0jcUHVz)r_=$h<u$ZtTZwAhoH&5Ge;$O6<7(o1r_Ii`v@0i3w69 z6SKEl23YRX`NjNL(f;hNPMFL^sGmn(1YkH?e8)Tb<kS<k<6@OCf6+#*+49cmq&48R zG%8o<6vukcFI*I5ODUinO`RVs4w2;MQ5`$>`DIQS&Gt3(#B@6xyA}El_Xwr-6;}9f z8*{8tYaJ2!Ng!u|!=sV#5x_^5>8U_#Q;q<_=qn}GTIof=O*0pyXa&g%>=$NocBZ-l zinD&fI+iarFTq#wz@97$!wg$D3#J2q20}dy9E3@9a!FUH;OH($w!Ur(OorQ5f;mT| z=%UAB{I;>7KAi>}>>$Qj^_AAn<n4-1F@o@1h@EOjh9I~?0XOwA0gGv!Y!20oE|RH_ znjS{?WHrVY3@Z95Z3doBO*V>{1vsVYu$%#i%{tpn+ox^!qg|Ckya-hO28g{gVD1*L zX>Z89Ue;v}h&!Q>$jFmw1$c}-01Oya>;(%a)Pdq&s)X$}3U@!oED)RLUSUCi7E1iK z{XKHJ*(bh0+n2Qu11y81C`aLCF%#>qSd!S}HtSwW8rXscIMOY9Z`&$ifo&kY1RPHj zH&G&@>9jWM;Rv*4q#toSMNOXhf-laevZDDW0OaPNs-swW&r;vT=l4$F8!aC{B~rhs z`EM1~bvc2@;YV|1PNf~Mj60S03~q7wbL0p#ln6b_?|)Hv0KHpuO+#VJoS$6JXLW|c z(9DP8V#i6pzcG(hPK~ywLQ2e!f#sVH+m1T9TwDf8tozwLez|)9XrdArz^^v5cXK$| zydGsAK5)HFaSZQ-tq_0}2*dQkBLrSj{Qa>GgPAhkTd6uPiOwxukUOXQu|5ba-T<QD z7iqt^@ZFZ3hKjYcb?G2?KwT*?2j+jd{K^8F_TYgX85tFRRq!+Mmp9AT-8B=)ERUQe z*YSbmQ?o*59}gt3*bvu{OJ)LXY&*C!*%08X`t8{nHb>vMA#Ft1>Bs)&?#94CLasa6 zEsP(G8IR`Z%mC=ENw8uwbL30hBSguM^SgO0Nt*gKR&VDy1KE16OQr~P3=-b~4LffX zF9B6#=|OduSXxg$<;!{i8d|EQWB7s`P`la!UPnCnMNznr%g+opA%I(A#<vd`GNtxQ zSHP4bQJEn>6@*U7%Fh5^SO%8Z)z5~9n*)@d0#>$xie;9@#>*C9EoV~!&q^Ys4CDe~ z^V|~&*N#dUf<`_qO&n7oA!ty`LlbF29O+}i*VX-O&})^P!@Y$xtI}>?@5%4$j{}x= zbLvwiubwq$Tr2hvF~84D4XPyi8uJ;g{+0}@pxX*{tUV&)Cw_Hi9(SkgxP2)&2^%lW zSO_xDX$q6VFHrGWG#_=|;vt3eLTj!OM%O?R)Ka^u#Ddu{s==z7SqsJ9uafX!Psy|^ z9QJzChSUXCK94u{wF3o4Gq2C37{W(T>HgTEbXfKkE%C`ec1V>vpfZMFJTN&hGq^v3 zG4UB5)!f_pZO8s$cDXXOIX#2Ib@Gw(qF-34n1Lb9jKsfMs;<}jw=ytCFL1fcGX^p* z(cPECyqaXwX@jM4pY$dmB|hm0)*NJsZH~)2%dbdtO}VCG2S9|8@97ieY_FU@WA8-C z5h8>i*bI|-3u<<vQhG_RYEn3z?<=;$QU}?vMI|Vv{NkU1j({74ay~S)a3brgcm;<( zs#0}EYT`Pi4oT=Vy_LX?y>bY9M*|@rnVIR5YOzuTd+K~7*I~3ewaLM$e2Eu0GEn~D zAnv3=M1ULK8Yx)!sv0wWhkQ$?9h@|AVz)8Lklok`Wir}1KTEL<u{%xKdik(FEM4@+ z+hhX@A+1l+L;nfn89}P~k{PQ6r~0y<p?u{}9BQL7>mMZ2#jW-A_4U4eHLjlBbb)!M z5<g(iaG9Z3_>U1pKzf_oj2*<>^7L=^i&GlM#sume(a=BpH+F%&K7S_!0CvCwPOdLp zf!3dw>VH0kdA}mCE#zCHtI~gb_~(1Oh`^oRz)4s9vAO^8y*w{qlYN_Gx0m)GAO5Lx zOrpTDLhupV|3nmjZwz+xry$_wMdl!Ef8)o0-&!6vY{y2#sqFoa4EvwAVOtU~`d(GV z`ey%niod@nK?%DU3P>;X?@0XnF2;j_WZbEN(%1g~zL=N<a4~F&hNu5ACV#&75d|={ z+bwDDBLDkhz5&3+C<AN={`D09l$v<4fw3HSVOzob?~C2Q0T&a4n_~X&v9zH8#`5Ei zUMt;yU+n+$#1L~P@dD&&UZ6a|Yd>GZ>;7w=*ZXXj`E&mQCMJ^A_{UTsp%FsRzhK%X zAY8_w0`6DYuI$F=SzP8}L0Xg~ahW{UP0`b6wj&I>#pkKUX>8ezPK`TB2jxH1^hZ1w z$GtqVp{V@VyJ~N^8^yT$QxCTcoQm6fN2X^5op)uFQJk8&-vcd!pV0o4*gDR&gBaI9 z@?_L<H(Y%9ljDnNi&(*SWreR!UpRa>4p{nA79tix1y6Va`B?KWy;t-x8qdv%PM-IL zVOM7;3hCI<RiC`x%h~|T85p-roK?I^Wylp`UM4!1$Xzs4p|qTOXIkJro6NQWX6P7+ zuRh2V7zWFQFNPb3rG~Md?0!yHak4Z@t>C?8M(mnuN<DP-w4vg3&ig!yoq))1)*sPa zu1WL`xveJ}E<0EV<N9-@5Z3zW!J9C;f6@HAv!nyKo`$bTzA>K$m`#5w8D{{!ZfKt{ z0$-LB+cDkHeF27RFNUSe*NtE(c%b4@3WIS$l^8ZChU}_4(f~5}<ABpq$7M-cTH4v_ zWhXySqAbyQT}*biagdjTEpja34KyWB13Zmn7_H$COB*17@>?(_h}>^!Vvl49xxMuU z=*|V~0HW0&0^@%@96dg8uyve43<;}+f&{On&E(?9NGjr*jhs`^(txfWe_@g4w4(gr z@Z%Y|9Z392B)c{zkkqe=N<{sZ!lVHyj2HU|!-DL;{R4$(19&{;bjEVfybV}#9-sbI zgv;zGpp)k`p)C(l=O+<U7T;DMT<Zx9s3K@w_fFk$)ocxO6$zmW&VnH8L>rL)eJ^a> zk$4H$%p;6}boCyrAkqp@%ct>_SaHKHpWA)G4T;b}00|TKzi&U0O(+0<l^T-p2w-(| z$$t<ZfLN@voMd;suhzn8z5#o1&gyB-Wf3qg^?;JLR?D2(O&F+MO&dSn%((*c*kYh> ziB9c1aKD*+3l_;`M2Eo^oWGqTa4ybY$X>#DiZD!iH+r3d;U5?~P@&+LPSRumkE{4W zlh0tpXaHXM`1B<r)0(&BJ3#T!0^6{MYNwTjwN6U0ii6Mg_1f>Cqgtd-%o@Mz*%ia` zDX)QTvM%otR&z=>^0o!Y_0f2=8Ld(YQ=^TgucO&pZS;U=uh{eiFuY2D$6!2@&$_g> zEoma5kmNUWcjbmN)YG!^Q%Yhk=40xd{2I66Tq5s)(!1lvu@`?Sw1HM~0k!fdvL|Q^ zSvbhY6T(MXVgQ5`x!i<MwjOWnsp+wlEPKmlk}KduJxN>yuvv)AiG-V61(%C<)fs@K zyeJt0)Q_Ik;}S365XMG!^bnI%3j?9z>p!4!paQmXw)EqHZ@+wwm{F>pBc{!l>%v{r z-}OB#cOLzu=NbV0W`pQI3LY>TvtgMi<N&x_POIcNf%OPiz&{Qpb_gURhtVDKLkT}m z{6zI1nPkN^wYmnyz<R6=%&o#fZ-B&&KaO@4ftS-*?>*o@%LBi91nG~&pN3_-kVwMd z)+Rr|s)B%nCScL+2}6V4Suvu|5nY8*KayyoVlV=%wqnXRY|Q<)ayro?-MQ&=(sRmU z<X@}Gh1jz-PPvb|zxKcQyHN$UV8Rbl#l81E(BA`6{YpS(!3rlPRmVtB9?LT#1n2u3 zn6w^==^Azv0}S&1ImVt~6X?9#)Ma-EB99_qwNVhL<qQr*01OK-f+e>U07zkx@$AFo ze+48?bIrX-KEI&HC&Xo3lJ-%_UaYu#KBohuU_h3i9GY}zLM`o>^|?nhzR7X8(S8H+ zGbHuiFgOcAAJD!av%FtXZ8Sik+o*J<PG}mzE{zt{3LwUZ@W4Q+j3e!l4Isp6#ehTr zIE!%*Ty4>BfW@H*qo`KU#<Uj1)1@b$j^WqGjj7rSg0@~jI=vm-mw(EcbQ?V|`D-qd zwU(a;vrMCi$GGTVwrIO5H_pWf<TU>rIViOg^2p!({`Vx6ZWE~hr>KQOAeI(f6$QYU zVo5OWKS-Xqk4#|GQD~^fs+^#n6sRA+#i1&usc?#;(_`J!gH>?>&`|JLNWq<)c?pbe zXOtqh0#f?)uGMzTJH-}a*rebjdOqsZp&h>X?G?t+ZAw+5yOQkrzz-lVw{FO}80ydy zLvaHBEW!uhmuU1oUIfgIe+5)Oi`~BKGDs$!DJPDsk$(o>K05HTdMN-WX%1#2U)eR& zw#~FmQ^>vQXE3`^wn%L)`weKjh!7C@l8Y$Q{C2Ny*7%9~T}oaY>TEQnE>K1j&f>03 zdmRVS9QbF}ZKFNsXoe-hBGbwDG&8<`Z!F#bIMjc)Von@XAo(D;H>08Q8WstTVVMZ< zDCM8LGJhr(#y?myD6&pG%~`ZS8+a1$y8dDicPObgl*mW`HHLzWxr5&!4Qm#~u;1;> zC}#76hLyu=-7juTG8^G5Rmu^1<wFk3gHWaR)Cpm;F)~SujFz?g8sVdM9#rg`VML|@ zHNrR{RXG6QOGqlvewuyss@+bO0x}#=lYJQ*0e~>fqG=4dHzhgZ7GClVnFvyOxk?v2 z@{+^4L?r6&^7q?yaR_Z~Rn(s?>9U-T>nAU>TWMFwwzHN^FN*L$F-56=%ol&+Iz5c| zlzMdDyl1Ux6(SoqmW}>YK(BuDcfPmpF4?Z*E+_GuH`cxfm0#)ItGxg^zgaqE&h}*F z6cyAWS`tN042(CuDiXQDgijmA@S4@wqy<iFXMg$1@aLpV<}QuFQi}q6$SI|T-A0NP zaQ02$wsgR)(Pih+W4=>ti;;lOjhmrV=xkJufyzB$k(AiRC@dujQV^M!dIyxBPz#Dg zQsOmyEo^w2xUkeHQQ_K#YMl_FiZqmaWSeqE-tx&BSr((7y+tgsjwD13mHxCt<rr7o zaaW4~%*Rs1xqnV*FX`Rz&vd6O7R-*Adq_MPF>^;#3^WT0mZR{2O7LL|ZYH<_wPh6c zgiIJ*RQ@T{8T`5Psmp{F22fUY+cj;9ZN;r_zuMgdy)xS3a5MMEiI<8ak#T2Bp%`9# zFNTDiLi>U;E0wTurS)8I-s|n}s?V8v?}vSiyn=9T`<x$iTWH>E;g{;-EU3FEBv_4o zVGS(Y2o#AO6XU-;#(g!XgPJ51L6&_!7Q^(`ecv=Jg24)hI%j=yuO{qMwwr6hS0n2l zP+(#3TCsu<$-2NUsuzMZ%7~uhceqn&Y=lrLZNz6=DXq_bXzwUq?`KE_{s|;zP#qtq z<H4RiJ7hbZCdbC!RmNV~&%U4kvPFM;DrII-mg_vibW(-m#2PMqvs>5~P-4Fh9_<nA z#Bd*^+#h{2*eqkT>SY=hoQXed`|5M$2M3Xx$myf6UwBMKpGn8>YwWAGt{*!!B)fyl z53@YNIIfG)bw@TQ@1@C<w-V@esxcK0;yAKrbgw2URuMNu|4_nCIMX~jJby%H3JK0i zHZzLzVPL!IDz^Z6J|&UGK{V%iqFqY@j5^knjr=M|F{y5-mv|&Ow$o>itSgmiSTu~C z-cWg4rlqVnRGw5dMixoT#CNMjD6MypqJkxvqRKMv6~yRaMPSCuoeaX7u-;-SN=%Gp zpl{I_dn}-_c+2GBea$L*y_vihgzkqg++0)1NRFCKn2jiwjia1xnYAgti)N@B7Z>Zg z8A)UCySY#VoPRk$WE{if>b`4Af~a5oyQU9|t4-Q(T#<@pg&BLL(R2@XeuBg)b+>Q) zT2OqUf1Y>(mlT<4TTggE70E{A&HK;;L!K%Y<?H9Ri5OPU<0TW1I&}7CP?}CYc0r#< zJY&3zXatK}a)~!?^+~v;Zu@AzhqL4PJ{j5ze?~cn#Q2Da!2WA({5^YGI3^9TMM>Qm zsW^ez4h)U=oAb>91R&yvU0n8ETt0}5&<S%qo#jj@R|a1_Gg7I~Rcw=?rR!!e{Q0bB zHMeJYL}e4u(RRTY?a%|{zt84P0^MnbB(q0353NX@D1O!H8|hxwVI{CN-69KHeW8E- zF$D`?uFliG^aNG^fVXrs1PzCTGMKh)!xC=BRZQgGEH35h>A#<8lHe>lH>~;`{_fGn z8~B1(1;$(1IcCig#<a@M5PhEW-lSj`H4Jm3eBo?l#$`gl_eS3fu0_;C#JY$D>VakC zx0kxlnkYmLU7Nw3%&c{Nm#U>5*%Q{-`GwqSfs8|kd#PW8tfY3Y$a5WNFxiL~rwBn4 zg_M&pLAfIC0k1i}RL=Nzan4NdQ(c0V^(!MGj&=FI^57VJ7_-KtN<!j3A||sgK7$30 zI4E{gue__|@q0_}b0Ql(FVRH1{@D?QBfw}AV{b~!dny<o)u))FS(f>Qych%(o?r)m zGF+BcPUyS$zgR_Ft=exrHNITcnf)O35)XAs8n=UJswWa3gE$7ghmYNM;x7BuFN<{x ztE|kJQ>UcsdF8BYVsl|WrvX=cdz{y(Q%Em63RjEgM%f;Jcw~RgiKE!Zq?+(MTJHGv z`$P7Jxz(=v??%Fq<Tek#l4*1M%>qo;HK*UWdZeuFx|{X6L;>B@lnHp2yXb4Kxn<#g z_~GWA_du@fokpp$TdF7FBal390(g9*bS#PSVruOB+grOpJaSa>b$SOq5&LyKuon;C zO8fT~?-4lN?w8t<bO(#U%ZlCasVo7(hp&D~eQClKXGz!HXxABifx``vxv9NPkI6cD zIretD)8^~=RDu1SUU*cl{lE(hb=eDw(C8!FAC%o(JL0vgkw<cyqj!bT2qf}CMc?pC zCZ4q7(kx2pFL6y?sHUvc+RP|5a`w+GslS)r;Q|dX*%&7jNk7S_A(oQ+P&z9=^z}=P zZfau_!QsMA4uBj!wBz$#<UL53L6y*AI&40{4MVJ#Ws8%VPk?sYn?B>@BPNMKKz`y< zSZTtTvL)sNapL66;KE1T5$?V+5es11UyH>Gzw22R@CXY2;dwyhpen92BPZZO@`U?o zyFVkG@mkb?q4#Eg9}Bm~rW)wp0P>A<J0e4vnhhG>Rf?M!U#F(BX-&y?iXJDD5xU(b z)yCzIL(jfgkONjBJH_<Myp*T$FWSKWT7Oh%4UvoCx{1KfxSsRB*ZHuSD0f%<6Tn2# z0sHwW8S34J_(S3S%8&bOSRa9GMty{1gQRi6BgMiw{PBjw49tbQ0Kzr5u9W3wr$VJ^ zIAY_gUZP)sXz2HEyR%H5$WCZ#^_3r~#3m5rY@CWgNN?oDb9|r*{@2$F-~7JE607p< zrv4u449h1!?>{y1S=JDT(0(WT6}Vl@{MjSG2y2fH+j5vvB3gh~b28?-8%4|{gCYK= z(D;N^K-jh&jy6sRt~4thN%aN*8E+k6W2mi_@#l!%7O#KUh+G(&Qh@h$S|wmO{Y0RP zb~4-9znTgov>z#oW4$g6qDoDwGE4u~k+O2(=v5-RxnLxxd!BlyxEKX7JWLaw$y?;` z&{oWTI-OfYnmRFIwpFQH&vNOr?UEW89Ip9PYt~PforAqtsU0{BCJIZlB0^Ua$%@&# zP;&}NBXKcn#6!E^q_x^ckX)|0RB0%Z#LIA|bi5%I2pFrKfs@a4`aRoyZ@THGKFGZ4 zqGsVw6~8GI{~R%;!`R02wc;v!YkZyisl_wTBMp$JvN!E<AaAuospXnSF2cze@B!C0 zd6Z)j`4=N~aksaL#-`c%GVf%fe@7Le6J&<|e#qf0Ext{9c)+pB>Bas2kow!vdty&_ zdrFS7(#GlVGy{vXa#toVJsKOz^Hot%a|(SZs#`%O+WQFQ98wC4GYHCuwHk=4<@F1> z9Ts_2N?G?dX;^9S2yERv#R5r<^@kbNWhBZ9L`4Y{e0_e6mB$!!2(t(slz(6^jsp(A ztEEPFBnS+M(p=59k|gq3>;!6jz9K?hWz;xpQhV3G8a!I46Lzi}j4P<^T)8$yZ_W^j z{3btMJc(gO;9d1s@bj?;4v+FrNgY&_*&)}0#WYbE{GQn-k|g`+a=JOG7i?ZDK5}{d zL<hJI@MWmP+7?vRpDxr0#aG;g#Ly|ppMhx=)}MzD_R!#c6@A9lc6ona`ZRQ_72IJi zipSO#!t9kCs<+}^`rP@+f&Ed<{-O|mTk01kj$yS=D~}twi<iG|b6$T~3*D?ttBL4N zuGrAhnU%NvZLzoU5ZIM3na#eM^)nn_W7lt~Fjw-D^f}Zq*WD~{<$Z7g78jGha6c(W zZ+r3e{E*l-^OLeICo_J+2pr$&OfN6Z3(w?%B^u?yL1tV_ujIZ@^ovwkEinirPgcdB zq2~1JZxnlv#t0g(p7mlo9*2#Q>pqJR47Tnw=;aCVh$rQrkd3Fv9#i@#x4tlth4;-{ zrI1S8>!duG^EOeHd?V)w`3LSIZLC+w2ZNMIzQ{fwUOnt)MkSIFbrkdNb@GpdA9%23 zR^(YTz6pSzxt+6AHTPb&s&d?Kn!U$3&FfC8SfkQ<SrFpZ=$c!eEH*{-rNtLG^{Wxq zX;LLCD=J^1YAk0N+x}+TJV%BngeTX=WjKkB&t>~nHR3tXmnq~}V&U&=oPKa@iIbqr zs2w@dX5vpjehs0VPtl(v`RXFpsGyA#%-nKibn|%WeWVB6<qV}LGd2mq5gsF2EBVbT z9787&Qb<1Op`%O}7k1qK@{fnZAMTV!N=Ey@0ZaY|A3i0>-!J6eXNp@_*Bk`<S^eHE zmOxIzTBwhu#PSRASjl+Pir3PlvTvGTs#Bb#H%ti^3H_{a5FB+uzV*brMA`Q{h4(Ji zhqZw{zJqaH1jWjcDj)Tpit^7*(<;KVz!`GhpI8sLO0)SC=vx?Ec{;C7`dA&W4Ep;F zP*DmaMbzj;Bc*k#r71bfdHbR~_sPWl+V3wPAATH08{ZWiNEcEEmKncqG3dv3=>+0m zL#=h7C$c%ZcPcrI%Zj~FLN@Rc`-vI+Y1hNtqjQC(Fb~%0L;m20_eEm_T*e{sdMUJU zRYv2Txo`RhcfBWgaJzWK_buYq+j_`wK`3@sGXoxsgyYLc_7qfchzeYO0hTY|(D&C^ zKXX07N-!0FH`7tyS+ucBbf0(;gGjKrRZRIItH5`?84hLU8yTZ*ct!r>wD^7U{kidD zBckGsvhQXgtEJd!<~L#&^RiO>@WiJV4Ea@;m;R5JVubre*#4*d{u^&2exV^Jz$I`( zyOq?*w)&>9zJ=7TyA)5;{CK$G^4s4cIiXHHnL^$ns^x?G2~Vbr?z1EO<0RM+-c<m4 zQYWp>P1!~3Ng*fVCTn<=n9F&noXI_)b@RrhhT}O7GH65BROsQy<Nc3AIq{psBaIti z<1y#wmT8+IKldsI?6?fP=ueLU@|AseYFovn7?W=mZ_<3^3Y;HQN0W~Y#EAA$Mh>5} zYVJ^Dp0}tMF)8g_IHD22m4DY#lp#VBKdC5XVR$8?wOlFG;;cmwNN+fs3OFD-zY`)J zBN=iMnmZ~CXHMG>t1jFw-wD08Uu~!7x};P13~SG=@-8*bt3djBU~xJke%B{{l~LHG z7ADl(KS{%M$^+PE0YyeQm8)d&YkVCV2zBvNI7h$e+Akqz+in-gdZRu;jCH6Y(PzV+ zuD%~j)oj;&`Pu{bz+oceQH1xaScmz&CG|<v`j>Z!>`U1hPxA^&eVHG!UxpsS4v+iV zN?>VTMYXK4qHI;sHgpEG%;;Do^z76+Z47GBt|>GYl($z@?Z#hVwvCXTO)2$^0B1S= zyf*hKTM89g^S^!nI6k{kXy0nacEeIPvcpTnS+)!uUqV14wM&7>ONH&i=;k7mA*Ljx zh09qcU!ds)oMyQ?rLri3<JRVC{2{DdKWRNmqTn)jr>p})0AEU8_tscT<~E&~yZh(2 zU}sT|r#M94&~rZwK6gq|*0GSOriNQyF*+vrPG0u1;3bKr$F8)y%Z#c?+x*L}&M|U} zr`?JkYc+g2IOkru`R_G!*gLqU^f`#0=$7KCkxUg!nVcV_R@X$QGZul~OKob<8?)7R z?R$OLda7&KGXAc8PgZ=6QK#7b?Njb~RZCz(S37SmAE&q3GR(#A;*SoH_A6*rlX%OX z?J%qAo)uRpg)iV2LJ3Je5o=$5V%CJhkg7{v_e)(ZiU`-9x6||UyYFW?=>tbzH|H^( zA0tQJmI*^G{A2@T5RMF=9@A64VAu(Mj@;$cd%`E=+5N#IM9%t~m+Z+HvFVLqPlcE8 zH(B2+HzCSPgS|W9Le&&1$|OQEJTx{dQL^(q_Cd1X=%ZJgC*W)!Rga7$s|_(dj46tR zy~kAnT6`tClZXqZbP7`7eTWH`n%gh{jT8_LEfWDJL%zB+*YOQ#D*H0vIh<a?0C_&) zTfn~l<f)+^4X365Rk;7|AclOfaw3ZO%B5kWZ{A4*jpMppNM2f`RByPgW1!#>2Xm@C z7+fJbp)A$A7wshT7(95jiIyueNm}7uCjGFN`%wM~3A=TQojKN~S=taqsPoHRqC#ND ztqf(RuYdf7V)S_xPxRdoGkxWc!kT!BP(CWtoTb17{mNvlO8QXhF~fjvwNzEyyb@M) zSDWqYPP+U`W%9VQ8J=$od)CTnIlpOowJNo>Ca=+2!?5-^>eC*ljr<+L?gxmvOr(&p zRoUpOiR4p;o>Ck_P!262Lv6D98Je8!CT}=7h;d`CfMy}?jvi<HwVs;1!qqPe{?{Cj z1LN@;?1%ED_TR2tb6B&~K!x2Oq7k_7Hg0Ka)We>umXUEi^*cBY|0M*q!TE;#6VEgU zKM%1UQkGrY#c=h(hh=!wpoSkShw>EpdO->CI7(>#w$-EuA(se(eg~)3_BL2(SW5Iv z2RT%P<<RMHSS=@7hVOQ#EZjMOZXJzhPR4LeC4;l)8<a|=;We>bPENz3mbhw<xj4Q_ zgj1>ESnXM8@J6k7^jl%=%c6lbW*b;u&ww2J`Q*E^_=`gEJt1r>ft%52T&$eZ*P3gz zYtRnuh9|GpqBoD<NZ`depTz8OoE5UJx%$jdZba?C9SZiTsZ0H+!1Ofx5}<{}uw9m% z7tEjGOQ!V<d_hb8eFzPIHvSoWf?u9lIsz90Bed8pos$I8U@h+rKf>T^zQOrsK%s`# zw&r)LK5$ZuryIc!YhH&NjJ5-8F^8olUNm8abltpCkLuOM8PCE`IHK=*omQKWzG+u> z$jfIt3O4rW)@>Eg@(e4~E3D+){PwAt@9BvMGA(9+&mgptUx@C`MBY{Jn@{9DNjqZU zHXT`WeAUa@X%clbVN<95$1py7762TY*@xL#V}*?nZA9inLnv~0!Q)|}1|lpuu{U#y zMGEc^B)f%!LnAtcyG-PVTx<@RWrzwAGn!DM$35XZ4b{B$$(c`=VYhTTqqHsgwskXc zsPuz#v75kBidvfdWF?k&(acB*5&u=@(5UptFNdYX_|_JP3yo<xk`VDty8kti|6cd1 zNe-HebIL%x*vlWhqPqwA&QoF>au$Z)aw$#H>xsF3c8h(1Q}79=_V@Wl{QgWBvTG-T zV)H8JOfUE@@e=5MsjF}BAnooqVq8q!5-VNEf9|4v)TR=MK}+6bod8EGfyW-dS;A_i z5!B-bk6`r6llv3b09e><((V&2<3JMY44oJWoSLBS2>YJI{NT33#pUBI<*yIoSBZ@* z{;U6otapr$GvK<tCu-Ejc4MPqW81cEn~fS9ZEQ|#qp_NaZQD-X>HVDhob&$9mwd^$ zYv$Us_u6ay_px1W&vd#H*=f$lUe0M9P1>09589iy#wBH01}lTJ{EL!%%L)=VzP@c# z|BGMip~&eNvJvosQV`g(2w?-5SO5GfZ{w7cK8C>*$FR0l(1K2+58yP;aS~t;LJ6X4 zJ=Dld&K!&pc8sU#xxmx!>7$s8gMUZm4SpFX{DrZ(RES-3WRa@xS+avGwR&N%ngH81 zm7nHb<H}(&_}O4KvC2>3{l^y(m~pyYsRt{IyQJ){Ln=4aw0jSA4nm0xUHXP!&6=x2 zKX{+Bt623?ub9({f@HY;Jhl#b?EYXn5!}Xd^SDqa^6qQs3x^cwU4y0^qXn{!q6I)m zO$u+k3clo?k^~T)0P$Jm1W%`ZR5TI#X)%MVBeFdZ;O9F_s%L9oZ>>@o+x5_5%h1(z zN?MJKDSUi=sU`6pe<d`?em|BU!Ib1kkzXYUS%N6mH@y;FD&F5;s=@coT`w_MjQdS^ z09tx}TD#$XFdt~JW+a1M-DrlWzPJJjk-<^f6uZswwUW}te!~*KxvGhCzw@gg#LTEp z<D7QRvXJ{i_(jvl^Fe^M8&n0bpv;!t@6Rhm*J$r<;g2kWaA*_kq|0EFq-NkYyhKQ_ zQ|)7r)E%@8M7%MYSY>QEVTs8H_)6!k6tbSfI&JTz+h7oD+h-C&)Hse4QSqQ)d5A}7 zY{bmV8N`C%bwl+n2o;iSOw8VkR?YZg?E0fe*WjZ%@Za>hT@$5oj~@e#lW#5+7N<I2 z30bEfHUhf+z?+*3{~+=8weO%`!KE2dUT`_j`M|XlDkdZ;TxDtkH<Df<7$#N75eXe9 z7Ub<*WbiV7t2Ar+yo*cLq99iMt#myvrMHW=fo0LBKU0dg0U=lDjqgafeVX%m1Ksyj zCg+}m$uHLZu;8;n%WRZ?4e=8=K){C7Gw{`pl>Zub?dpih>dG&;DNv0bD_?qn)xnpF zMno%HKplsrQNC3Xe{IFd^l4oOV^|Pm<f#w8BG)-RE1n-&C>fhI>t9wt>XMc<zr1LU zcu?82R83#^H*Ng+zbpW;`i&+xx+dvJRh!08@3G$G(K~fLdsIQ|+C7<r<-vJOb&c}| z?K3iv!h&@L?4nkQfiZqs^OC{a(nlk@0(b9Zr(<1~?>uwGiGhV%r*&odCo^6a1Gn%q z39qunUW~})gAmsWfVGQWSHEC-78?W^f;n_Bq9YU;nXEx8XgqErvo7^;9Fc`9I+~L= zU05tXB;ux&Rd8PZ_hkNm2J<*&lFrMBuVBCA%ecTdY82k=^~-2St1be>0IU+O>p%It z+q_2D#7Y*sMf5iVElxY9jAvG2dI%$5To9P%xeDUMINu_@%&^sbT&JFCu<g#O2&{Go zzLtI8iDvZ`K+OFDj}3w^#BCYIwsVp<l+0k>2EgTh{Eg}G{dm|dMV$L~4>D|k+=0b$ z%H=h$RuU*=I@Rif=6aF}_7A}&dvKa2a`NH1=eu)o070}z<Hkow6M}^F6CoW<feRJ! zW;_>Ue)11I$8i_hg{(xDOfp`K3Hv;Pcvm4;PN+j~;83tG8eB_^1<IYp`?MIi+MV5c z^|iQt|G+Ac_b02WrA(c6%V53)a3_?sbB}sHRRILpI6i7jBx&7Cm))9DD}lBBP4>3U z3;Nj=BIEjXcNH93ZYAr?jSHGz7ZiM=TraiSRR<8x)NQpKbQUI35!MkhNZi_4*r6)( zOfuLTnvcc{w0Z1b$xl>RMH5TC>6+#dY#Hj8Skp$^vX;EC<(ga=dFR9x4ox~=7ETya zCy7fjHD{Qwy*~5yVEp;a&M%1Zw(F2KIn>10NIE-^qgnc4r?AwF^7;FOYcLCp31S## z66Mh@6(I|k!wC5Fu#tsrhu-szz=unYBFcmWq0&Lu9sO9=zfL1T6vBU~MROcQen<?@ ze?OKU;WD#jbFFvg=&REzxP^Yqe)_qRB9lgiY*vQ&P{ian5(FOzi0|z!1vmN*rl|L+ z=e|epij-@}=O*V7{6#Y}M%U+~Uwe%b;!sI{t+`h?x$KWS!B0<O?E~;<uj921Lw<;H zZ}~YzN8N-LAIGcpNfv-je%op!1AU2vCc%tXprAjwuug?6;=YqCqyc|TGyqAjuwz&G z$@jT@<qkN>J&sUs5RY;>{A)QBcFqI!am;U$B~DY1iVOX)EyYI)-qB3giE*`1i;5Q_ z<rrAVBT23QQ9zfEZZOiF-Z+Dx6+;Mq5U-I3ydFM5kVZ<qy~95Pdp;SC%1x!vT!hkW z<8uFwnr~<vP#<42u9nj=bePbk4o3X4>_ILiZy&FgVne}R-ju&9lJ(?1rpCFnZx>~| zGm35NnKwO&x47ZGCo@l5fK*ft(IoE>@acX!gCYWS;<IO0P$&&-^>$E~pwj9p7%l$r zuIjwJt>ExgHE6%gXFcnXk*|Fxd(o~AVvnFDn!j!Ekm|Dx55kmcN5CW`DB<{nPQX3= z!E5cqqDXAJaLJ2?k`Ac+bDC}cFx@-r*y|W96s~}`)q+e6_!F`E@m&3J%sqN4^CQBj z2-YnU97kB#03{%sZ=f^xauqNx59|IL1|&FO-0ywXv{n=NA|EU+Jmq<O)Q?)=!n>=J zrPE}>S;TvO{QeGk$ErFGK$JuSF=FkElhtx5Fg5*>fTS)OLoK!qgj=R0)}U|EQZ1mJ z)aQP#wVWn>0pIg6JIHj2&3Gw}J!Ay{SQi3mu0PH%-m9QO((C)E1dOUI!@WrfWgN%D z>n*14IsVbZTHEv*FkP4gBYnZ%oL@4w)Kgu=g$$<~LFSV7KSkO?lMyj{6rBnPmxq+7 zT(`3wZ$sJobf+1e+FhcV^pMLV2;LwzGdUfy7ed<z5}QhSUM(}8gR2T*CUBsp0^6!u zwh>@+k5~#{23*7@Vz04v9ea7YIFCBC9y=9+OvRqpiHC%UAQ0c67dK(BB)8G_87p%` zLQp+Fee+@=XE9c04y>x<-k0QdGe&`=i#b_2n=89HUHQ0lc?mH1h>-g@qqou5Xj%r5 zR8-tHmn&z*N{q_90o4wAn&7GJKr1;KwnueTc9QnNS&WLTqCSb@s@O2;(i}C5<|Pj& zX8pi5aqXl#yEW_1#;H<iHw@`HNZs=4`gw$`&dT!6W;?wltGM?A*89e4->Gab<0f`n zMIOnfh8!A==}#IE^y3K{@PIzeKWT|qbb&y44}SSj(0eSW9xihCkmy5<gKz&v6U<F$ zt&1>6swE^z@1|ofIdXtPJ=VW=c9=R|Y12^!pw|3x6Yw7AbdQXNOHNn1$)M9TJ~wUb zL=bhvCMevA5P{@^c$GkfwZoDFAOhe?S~vn2uohUT62QryDNb4Ip;oa|CkX1iYpfo~ zo-43=-kJcfPjJkvp%EJ8U7GO@!e-ot_-v_!G9{K%3fst5IsY}N4V>ZbI6D-e?EM#R zoQgs%%z53VTF1VBfQ(f%3l;~bu-lq@i6{>T#w4D{J)NRuU{{`TN;8}sS^Pmi_)+EK z`so%YB%(vXu~(C>?x+2Xw<0Q^hFl7Dw6Zk1W%!(Lv%yhaD3ou%EV5Y$Rc*j~wuazC zOS0=ESi@m&$Oz2+V=p43PubqzJZ_b8FPoh&25TO-`ZFIvUpWRaO5{2GIoqx$Io>Y6 zq69HQ1R0XUQ=({+B-Y2)d`nAXgO^A~3ILJ>U4KIZ!K=kLFDf<JooL(M{Q%z2G8xow z@bmW1cQTA9*~COM++xuujMzk$t!1iijJ8tJsoT{L#;VmV-zT!$d#(-6H!ST!_}O`O z8NZoDFjl+Y#tt42aGlJB<3VI}+*7F?*Z_gnHROt&v)B;XKgg*h8)vC%mFSwK49O8a zv--qkQY#zwi}Sw_&THhxf=|iWClciD`V`}&{mrca!J}{&7?qMxy|o9+5}6l{c=G*d zd23D7et1dhs+EAh<6iIT9dGr#VYQjBJpWQ{)W(h%X+iMtD+l}&0ao?Eg@Ou3Qx_`n zFLh5jzK`?%WY)<;AY32<tz{r70AL6UkBBwl56-SVZxb|f&NCcA#Uwl{#&VCq_6S<D z*{^afm>OQF1maR7O70MiV1aN8c~6^#NFi~c9ACi(BW78>e>sx7n;_wB%v=cO9(^*v z7Z*amBI4OzKJdP4<9WWhgD?;m%jigBw%2!<E1`IEaR#vzl8YC-DM#v9T!|_SbqP|m zp<?pu2Jfy3Gyh__<qG2*+f<$biU>X-13f<JTRJ!#7+lvP<q`F1!a-N^zMR&}a}I{F zO)k(%$9cELx#!20h98VB1K@E_pe-l49*F>q5ShA#5NJyu(a&V%8N30O*k_((OG8Rx zL783DBh3fQ$Wfelo2)oc7C4UUU%Y!IB7>>B?qLmE(D6vVp+PItLLvo{3sFodjePy4 zoJs!eI|K%W&Q7Yj4zCYz!qYl?!pkdR_SCemE;_ZKC#8^2?R#eo2v^FhtYWW$sWjQ4 zDfOCiWwt>y`ii~cWYrM;q(~sTp|sq%GX+^!8Duikj*F{J{c{=<CfT}DMY5!pw})dc z$1KK;N>in(+imv*7)(?i1t_0%@0>t$6i%tuEWj)0v3*R3aPKP{S}v>~TDhV^s)rEq zE@Lug?z2aVCwQG60tl^0p-RFbv<zmwGCHGpYY;@|Al`+1JjQ+0fcHC7`%^g=w7$%? z9LLU+km`Pp%q`I)opf=uHf;a%O$pC}97m>aNN^<a+JdAGP5F+s-eHS~0%0lGiD=lX zPo#h7{L`tWH16&*0OD^j0(MUj1s0;!X9`2w-`{^Wi6{$k8zO*}9xFjP0L3ysSb%1F z)uI|0;~OQ_irmA$!FHnG#+B$GAs6WR9RGvm)BP&I)sb&(#^bXjFSrb?p)m(y?U;UG z+)!-Bu|@#&aDD-}^7iFl0AC7aB=Z5dN&>D0^mZZ|gCSA;tYL})4<T#5&{-qG>2(dE zX8h#51k}ivpWEW&+*{(f&S#J!h^G+TdI7%zl?Qw4e>wvwN57?l*&HCXGf0w$N>;r9 zEPn?T5-2GiFMo(AN$Jn*aJcY~T!P1w)w+qtfMl*+%;NBAC|D_qGfeBLm0~x!`|a80 z(@=w{Iyt(AU`bjBud^Eniy-Q2NUoobArhvM?IM8{bH8~wm&(IJn_MSc@pZuwU|8u8 zU5%Oq$+*#F87LPun6u>*)nu_xg4%hDr19k91-~;2jhlO88|T3z{Cs)sd?LOjp>mc; zpV}14AI*k4We_cUxl3Z?F>64pZ}{8;XZvNHl>41rlHFkoL~1p<OM)q#2H;gFn2}k? zPwF!nYRs*~Z)922+!l`!7!kzc&`7AHDeSIG7>iS8bxHxG;g^%{cN^HlKM6S&>Hk^p z{2Lm$ylMWr!~&>mb1je#e_=&A1K@5%xE209tyYV9DoE(Dl%Skzd9+n!o3&C2c(vpM ze@6K`Dd4k&C!{fJMAKw7)w_e7W+nV}r@YAwrk;%nwvytQU5k+V60rEKB=h<PTDJWy z{BIeKcZsmg%6JHz{zkU|YzoD)sqvp?_`N`Ek|j!v%VgOdM=!4H^uDf&Bs!Sq+uzTJ zuOF{y%wHT7JpxI^4!e8uDpyC^M5<KD#++ev+ATBqo`WsU5{Ttfq|VJNXztua;3BlM zt`S{(qedZ_?263k<{C6bygC`QU)mTvecIGKZ0pcpMve7=lVT`><tjojgkkK6NR9JI zHK3Xupv$G@3Te-5`MFzZ75FNYbc&q%Myq~%^fFAjVto=`7P(Gl1oUAU#^u20C~gs{ zfVt&*RfBVfJqES=e85_OzePENuU}Rprz=AGv}GS$56X&EF4x-kFKpg%8wr-}xu<zC z@~m9x*rYdL_vK>O^IY{aJ{u0D_2*JKU$7<i!ha`)(ZkXweJ=aIrTYR4X7jGLr3hJ) zMH6Glm@{keN9JP|LxWU*LN+7*9$7Z;pEFx01?}acG0~MjVlT7(1AL6nDEwYdd=#vF zFBnhxo!L7N(zil9(-);=%aOdvG1q^<+PWg;IRrz4gl<~^D)!ykXbHhv#Pg-o^rx+# zWCVV3wTVoFGTaY5F4H-~#9lv3-m~|-*CpP^1-Pl>Uq|C&YY7^ZE@zhBZ%`vv`v}J+ z1f(Nm7VAWlLj>E}aLD&Bq}Ar96`P72D(fZuFFQJ~XMHQ|k8Ip1%BpEx<c~e)*uDG7 zNK^{EZ(XoC>9m#RPv#rwn>5mRZ4l?DP|~$53an{4y1JIdhqrZO0BFaaVvTdfVJ?v3 zWF@PXJN_5u_z&&f4rKB?D-9{hy2qMJ&%?T&YD3&~$;~4nEq&ZVP1>J>SiZ8OT`PT* zso>|4_m=PI<aQc8x$jw3)V5YL)W2N#_33AGZ!`fN>U3+R{p4n0aUFySk5}GHhS{cH z@7Ep!6M6}Pr>9|6k^T)hlzl@n_y@8`sBfxg5h4e_J6fWbzT?)#{o9UyLm+6xfb)+d z#_q_W0~yy&_>CiOiQsJeFs2t&QTOv=c+FU$-v6m;``JJJi6rEuR3IzBV#{^u&|?<! zZd1i0`YYkZ7Y{$h?0b*72Y{rKLUN4fIeZe4-JoA!F*UmXR2ykmiGp9tq0ZwU39e_< z9kPJiV8>+`KQMh!cgy%QD)yV~K~w{E(vt)+%pyTjD-i}jHbh2s_;HIo4T?M{p$^i1 z3kiLx4rypff<b55?!BVI_PC&Wr9&f4OMkOe`q+(vgDUTLxHEpa*Qu7XSTm9h6Z_)v zei6sTnTDOq%nCP7)5s_I9@$gQ;V=Y}IVeNLqZ$8Ptd!$Zp1+JQ!R=>@_yUG=And`$ zY@fEbm7G<RH|~r|ZLbsP!D~YN%C?qe1U2Q6dZBH4?kpV#=ULP{HCfrW>eO=mA{D16 zc@|u2>1bKa)<JcqbyMWm&4nhbel7Q-FG+TnKm8$Hzai!M_KIi9w@Dq&iIK4k{mdKe zKl_moN-P`wC7W~2HR*(aOig$Lr*j8<p>voK?9I2oDGG1z*7EuH+5Bse9UrMtT%Z`x z#QRXAP9<fSn#hm@_R)PuYyO^Vr8c<wMn_*OVSD9Q{fv5!h`Se=VAM-(bK3ptkW5A3 z7tuz>_>6wVHzrOvE0cZe$4zkb$OX!097T<N7i%qLTBgjV^UIlSdYQ_;6FavQ07XzS z>T+kd99sN&xGf;?ZzDR-b7<Q@rDSjcw_!~INwJexXCI}87_pyj^J-+`p^--+zY<Nv z>0Xjhxv>dKBz<P<cz*Tuc@)U0Z)Mex)|@d&Bp{dkHbxT&)#98Raw`rZObQBX0)6uF z*|E*&ycJvd+n|YySJ^%8t#GR2FeDW@n{kt>8e1o)Tx63PF*YOM93JzuW&<>Dk%wEz z{tE9|d7qqQ`&c+*mMf$-(=J`2dgE%Y>=i0Ukko7<PM0S>e=7?j71S$I-vq8-4_L1m z*>}j%dS<C(ag7C~nrf07RMw};Vfv^CUL3*d*G^R6n+>Tp+EhkRGvq~aG*aC5B1<?1 zR9A7k5Bj=eVauJ5hC?{_o-X!8I-yLC7@{+%|6HuTecXv_e`j<1`$?9l`=GIcqwev4 z-X*ZH!~v|s_dw8tI^#lJb|V_n6{tnHM#cTF@1o<rDM{?+*;l!GbIW#FQt5Gwit;6h zFFAspMRE_U*P+B_mj$|0j@$~jJjbyet2>}8r?{LdAB%@SXE8DlJbhaiWxP-MIX<K9 z6|ToW@B22?*6H8D6C_we+QvP$_}ln*!Fppl@x1n&vH)hys&o;aD>sqjjniQ%soQfz zonh$|K$asD;%XS0+2=h(CdS#>h$eYF+`L#EJICQLQNiJ}_u0l)j{#meBc{B%mKFBP zEPGGb=x-6?^jNGDyYj-;w#h*Q7hsm_i=8@;YWTWUj&hYYUqT3N^}t7phrg`)6<USI zsY`i^YiXNbk)Gc)m@3{RW4ryUzw)BS`eeKjf!>YMWSYOILv|6f+(u8Wy0XSvC19>f z71rgfv(imvQs3V@NY2l**iL_?A&U|+%G;t4wM+?ClKHUZ9{a13eftS~B+@65<Bjfa zs3HY0g2X-r)`nNJC#wIjsd>_6W%BdPl@{0kbc6qWf4~FgVKLas;C}CG5_7SQLM~7` zTKfTa#gWznz)uWe$K&K!VIzcld7LU<S>B8BcccriO?5R_qAB^j{GsAH5>m(vQac%T zTU?%3yWbzxusi?s>*Z9JilIq8gT#@|Y}Ltqx+cLrTGsVJ$)~Xc7meD6W_I~drg$+l z=e6Muk6*Vs4WJN+PN4x$e}u>JWQ)&ytVvfv{}Nk1+bX1%bw9|8yeM@L(-`+L!r(q~ zk!fY3Kx{PkHu{Zyos?ZrDsFZmztCt;Iz~Hr8eaCGY@7D>7&`ens}pF{X%+2q)@smc zrUQ_M4EK5#Cq9Js4sWY=q!H(Yb@YM>KZV*H==Dm6IM{Wb#bx$+?!54uni9(00+{TI zl_v)kiQIG5MgDgV|L?p-4)ZO(VPyys0Qf{sGD1PQ>_fgvrq-6(Xm3@I`^}#DuJ%_V zrJHtDf&4XT&=*XTpqS*6@g*r`lO#{6`2#$=xp}ku=fpI->A~;w%FFq$XYQkiO833> zQ?)K`>ph!Dv%8Uy-@m7kuuCDZzg8li_O)NscA3Q1ORE8Ueio{7Kc+w#Bphfq_Q-DV zbKH-+R4M`FsaQrvvygsas(bnLW;8vgSO6Dl@Y=T~Wlo!Xs_GG|1g68HtLtOSf$HV+ zM|FwX5U+|9<0f$gNAbEs7EF5$0%fF)9YC;jvP5OEEHgFP$U!Jbx5m2%z;Jsj!ztQ^ zq(7S~GCqea{qxp)joMh?-J=DY4nfTLcSOjEAU%AUF#K{$I8saiZs@J|SVCRl-(dQG zzF_~vOqqZ0;pvhqqA&nrbr`~X_j?%1zSYXIQN1~Ry+w{^KS#A~qxG-HNf|s9akPRD z+WY%qDRVL@g%ZFNmQJf#(1hO8Z=jtvV}x?SoO;UX_6+3`mBS+;kCw&5Vpxj0j<Q~P zV3Bulk76~td=n!7ofW?0_K0$Ie>9f`M(vOkh?rp$)e@89Xmn0}sn#OLPA6rZ<|sb+ zbF^r3<ozm?Kr^WLPQ7$wsfG2^;)I8RF{l5nFVA^p-n>?)TyP&7)n928*rWJkx)WK- z2h6eF7PW7}U1oAgozH!|I$egH<Ke8bcVd3jWdr~jp>7h4zNWV}68$t8sN`T6WyniM zaj5X)tbq5Yb-eJWH82y&fBU<a<%-qfTpBgD-`MN_|8ao_`+_vEHFSBPUJmOqu#iy^ zlFewVn%&nzWdy6Ubub36Qm;;p){0x`Hy>{x`kY1)jJrMnCO4?;%-yE0aV2%}RjqpE zx!4S?k8Qc<o!$M-413XF)vbh(3V&5@Y+p)Efr`Y4Q%JH>3@vVbhiVyy_#@;C_nT_P zZP|l}sZ3T~0@W)h?|G#Nq*0d0ZJ?w~zemh}WNK5E79vTghE?{GV%9rp`_`e=v|V%n zZL1B`d!xA>TUtuXG3*XlnBzEY@rTr^%P8@d%?0N3sUX3zt=ILHe%?1Tn^HT4hSXr% zFm>o^>-mkx#;6skST6YMUJIVx&AKB?*+8VTrePrs$!|t8k&XsC4BeB>sz$gQDJ;r6 zp42Ikt0cpvWo?Y9`&1Cj^O55L6dn%sTJlto{Xa!*xTHtP7BUltJ>JZs>cIFV>!}Un zR5hI~h{*SAiL}JPJi~_V6z_W^Lw2V!t-BwE5NKq&98D^+dZ!)hrgX&(i`!Oa?2}HH zQIMUjKE*GY`Y-1O7Q`+4&M&JBoH|ly(YQ<sa}W*R9&_sx@RFful$26Wt2%ccZ2uNv zYmNotNoA88(Mm3pjkyr^v5K+(RBPidTf>A_)>X3~N5S`=#%*$1Mw~Ab3y8R%JD69F z;(HxdIE$s5YIa^zyf9U>Yy84n6sPBXB6h!toZZB5(j?s}AE=nfymX36B8oP@4?DRZ zq0t@r!zad$@c#PriDNr@`r9X`%AQ<7%y?OoNt0pWqCE9&cliU)Z|5q12=^MWr61<3 z@!NeeCox8>%H)%|P>6G9H9$P%QWn`>#o*RTri<zb9Q^wi)tj(ym;3Y$IvY}PdcOC( zKj>C~F5|yr%YR>N$3tqz<R9dz8?}N8sY^~09Th2O@ss)dsXHhcyppOv2Ld4wO(9_D zm+ayx+RN%sV{j3Rii+!l3nSIzwRN?`QK-|>FiJ?_k$vJLL)BMSyVg_f)5+jL&J|U3 zOJzd}H5E+!Q}%7Iq&5c4plrV_ji&PAf#soxM(65|anCduTiMh@@x`AkFd5xigM=JS zGN1x?<_TbT{$I_d7%4ag__kTg0L2t?PWHrC+jh^6iPh`WIYjcjFsd21M9{3J#hH19 z9@|_wC-Ny?Yi@MqQX^7|=y3<fN}Vg&vRl_wglDNzVmZ-{lqH!7hH_bjrEW~)N~Md_ zi2M<!P-3yWhESmaJclemId+sSmB88);X8wvNcRaTJBXXJl#!VAs5Oz?;5z()$krm3 zcj=SHgHw8P@`68&V(G%CqGlfBhxwu)q?aW5?|T?8-~+$a^{y+n^OagnV4WU}h<Nd> zMpLGo)Ii8hW^8XhGkf}<b~pb2d<yG67+lXnXrP>`1Muw>E&X~`Si{Zu^gyJx)a5lV z=;VgFgTHD>k!A@SHDv?E0&l5u0q(J}q~%G;FoCKlaMPc%OrI`%z@Ah>G@W&8x@N{^ ziVW=KurN&Zm3GqwJ+Gp*XP$*6oL?9E>?UnsT#idqV>eO+pGQX{5zpU9NU3zVl5Sw) z=<Ds-!Gt;ly{loCpz^O^0~ie7T1J|L0z7X8wm0Z_O9!Q`=On#5V1AbsS<*JlW%Ao} zXm>&_@7~Q#8nn5p1`O0^k%~(5^y^4+oZy~(B2V(_HjF$hlE^|CYp6#4h<aNmvtkDS zH_W*TK8;zZw-$iRGq~~H)su!@ebi_8EdLkW$-^jMikd*s3R0Vz5{SG+H~6RB*YXEb zX;u@cKO|@QmjZSiC1BeLlvXZC-4FZ~dRPs600O3|EWRf?8+AuBB`<ei7ySe`H}@$x z?#X`7WcDA=<o{ijH{V2p3NXm804D66?cpOJ?KGzI<^w2UtEKa(0IW0mNuB1#75o|O z6_vOS#<>Qhin3dE2!_W-PbM3;xPjA1S(k#udF@s63XZAfP@9dq7@!SM+kD@?WuN=y z<9(Nvqj1(}D&S?q_R5B}P<z3e<K5GS5Hz;@32u0}=EvXAWs?sTNP1^TIhbwo$<aA$ z+1Q^QGMlJt=mR*f2B?X{j^|1x^t*Gjnq|W@tB}%q#g${Wmdbu!cK);@i8?|gMfrZB zEtxVgs&Ps3em&Bm%XHWfY>-xcG@-PC(sd3rBgk2%qQc4~bGZVcjYGo_@g9+N!@mH^ z4F&hfDer(nXX~7+AMuCiCR*KIjX;}4!-1e3KLgB$O=&>va|4}3w@1=yJ<gpIL^A(n z5Hc6FcB^xdlhd%RpI>JT9{VVzLiTFCrThPut^aos!B7b_yH`5Z40JHytoJv^oyvhC zfc+kC_%iz2jYB?Ol-5p|U;7NZ5#Dm-HRgV{fYq+QT-^#ZXT!pz0@A)bXrLMj3j0i& zj9@pfx@0|OI$*#4%n2Qz$R}Bn%{6J?z4u@n0vOB?cu!!T@Sb?aE)u4imMfvBOFkhN zODJ=^f8#<iykbOA>WK_?rpOf*6cVJ!k-(IH8;}gaj|BL;#*9-4LW)A-eV2+G1+743 zmny?*t3k@_G90cJWxBr^HcpQIF=`?x*lF_^^PG(+pjXBKHOfey)my+T9vvlePs7$A zzocF>q9&5dthwKPm#S^(mwZZ)Eu(@o+GGYGzvQ6NWDU}zd{T6&Dee`98jN)<sjM+! zcukfO&*W__td>4SD*Sd%o-WySd#W0s3n-#dDPDvXcof=*nq6PFXX<*)f4eOaXuLad zQ&ipmf2#y123I776c4|Mfk6G_d>;-;JeRQw-O0IZqQ9lm<hB8hWKZdIw%6^KtnUp% zFXqQZ#wGQ^@gzry`<aCjb;qgbg2%QE&76#N11A>C`>B|HXlESGf0$pg@T;bcYTxW) zWu2<CDB(jVg&|QOXqPF3j4l+r#0`ZLOC!kzs@B7c@vWU1Q>4h*HKTW;iGSs(czr3B zxeorVOZr7-P$d;XFUZN=-IAcrm#VSVdQF{N@0g;oGrw{X6M`2bDS1e35BdpOLA9hO zf}D4+PB0FjRRouwVC8Z)q-;NsAR~(E7tc6N1<O9?`omA_n^y^eyz%S_bk!)SX>5N{ zVetXdQRW~Fz|F<KbpJ{cAS^AMpB$Y;4`~}n0Z~SK$JZ-;TNJLM<iR5)eNb3Eiyd17 zr6Lwh#J6k@rY-n@qvm>vAt~+u#0Po4J5|nIMY0jy|Mwxs`XdkwkkDZDRc4b_<}wvS zfqPvD8&u#SEyJ!^v*1ho@3Yn+i{*?N>|tSd2Ta%&IMLSGkkD>G=(s7T%z*vT;8T<5 zTE_g}E^U&$xiBPR<L1@pukBB5Ho&cvG`kUpoQC85PZerVcCI1zxgg4#c=TKVm>1X3 zxhzlM5%%SbZ?+dHbzd>5Lf9Ir1(M*X`!qKg(5!vxGliL$T+u{=vQRVPf4B1j)bL4~ zb9XK8kgl-JtD2Ype!<IQe%(4xdz2`jd{>7g-l2adl509Q>c;WV7+QB&!u#z#@Qd>n zS7V<(nV~kMAv3;yIpcCfiF^Y*x&#eWj{@$EWF>&(wEh?+7QH2(Vj3%Yw(RDYdUIv1 z+DWRmMD0>D-B%|_Pp48kueKl(3c{~t!8}|6xsgY>-6F;382~YeWJr<(2*a?Vc5nb_ zCY3>F-`XPzo2e=1?bO14bE~p`^0<l$@qc!q|7!;OS3C$h!7gYaW%_h2L6?EIN#a7L z`u2KqMJT9GMX8AlzIKgr0nVvv%WacFi6r4~oQY?pb@^_p+?A~z6Y7@8AZ3U`yE7XC zk}t$8i$!P;uf2R6wmQL`%yw;V_Une7OX2;*hJt={q$AU6XmGS}JtR`2>=}B#tD)|L z=}9mnJ<5_Uv~~JaG>TF$KZi>^1=09FVLHx^Z&hIim3ap>g9aO$uHH8mn-;K^4DYbx z|KN)6J>&5-ZJ4(|rA7fwHVtEh6Z07(z9>_u9xAfvuG;+KV`g=@IRMuEQ2lJ9*pBWz zLWV2cR?xAIJQrVaRFe=KS3AbkH7g!XSZY$hEFeEM=dq_e=Kc8^b*ii#P-(7YxLmGb zw-XjKuW#!T4-F8LhP8VX(T4S=$9OEKoD$dH_Fd#zb)`7X8A^Y?JF!^Mb&2V`8pL-8 zLo~QGMb6H_%*#-j-(g?yn*vfSivHg^!ivFV4SwEPUTF5QZHSV$zTbGnRix8YCu$Bm z#jM?#c%Oea+FLK+3i|2x1=aq@B&RslrX7<MaXG-!X>tl;Sb9ulZvd*8B$9l=rw(+D z@;gt;N%*}c>2or@q1oRTI<FJum<BU)q1b;H46E%%{OjF)mPC*wS2R}GBIT}nRwp1R zk^2mD6wwy$I~Pv5q4O%kUm9tW2oe$+)H=A9!!8xhP71&B-RBj%G~XWomsL9VXmXk1 zD9dgjyTuo#$tK{;{$eSOhEA=xIPT(9p}TW=;7x3N%`LH0$KE94N<U(Dvs{ICrFLS& zk9!`>#KBn&*&M`ZqXdNmAz*-c0T8cseh>-Ayb-Fj9uegS6$@RJ&mm%i$Uyx2ZQ^sj zRfi-<aRCZv4@G0-01_4zQk62Jo&c9dd=fozv&;8BnbhebktHVdGM&YQU~@8?Z)NVB z!+zCLf%hsz&#@QAe$&WcdGz|9Y4ZQ-@xbxB2kIW{+ftX>4*AqYy{O|Vm^S1lI)p$` z{X)!$Sz$EPH8L^lWzhb?SBCU@S*PV-a?f5!?l^K7czGc}S;s)C{cjVQ2H3J%HCp$1 z<KXbGLTv;5FCz*|@CD*4D^q+9Q2{SD6%DpYt`d80jbvqI7d8j$js=7TZ;Yp7M#S-W zhmbtChy(oOET@9oAT7ybDd7F*Joj*J!<2h^wUh1aevJ`@F1$U6$X#pevqhK5=6ABV zMmtDD;J4VnG*VxbD<<tG?ng}&w2IUWVG2G&(j?Ow$|;1;tE(aQ+yd)nDC6p7sxwVH zUoO=W8YIxZ4hkA%V%>_}j>r&JJE=_T=WuMO)9c#JCH}0HE0eyJey)BU)lm$v!4MG; z^D>e{Ne+t*ksD;Xu5&-IkSoeYJ+ki+vUBGlT7}@wrqXDED{%J!69ZQmnpd|EC{o1g zy>9lGSf_YRPUe9wf|zEIx&wau7XRz1|I;ZNBHeD$h~i{QP$~Hd7g*!4kFQYoK+`WO z5^b;9&(rnqILL0I+K)%x^^X5!j&|^z37^=6{0qiWHxPvp@RRYWYIM&-)F$CP0p>(> z;vCp`pNSL$9JYkOs?(A|q@+Q<EK;#{%dlJj&1tvwtc4)+gS-s%cPsd;zd2x$|Kr!x z(w}J)yS=EHwcmO>*H4rMt6gt!IP>(ua663ctCMe?8}<A{(O8?xo!)3(Qi{&nxiaw- z)IYw%u~-(0;mGu;HZ#VuJMV@t87gg&>YIfKxGEU10CPcg^NKv)g;`g58FoecfedxR z)49D3HlNSF9oIOY^U?uzE_^DfCG;|NcEbqE8>mW)XP)DZ?JVTJkH~)y$PCo0Z<1lx zv5^noIHoV16fSWaWwLfabtjC3)c$8~)hL;$k2%3Za~5%#E3;GfPnipoNq_xbsv<pQ z6<zG77f9ZN7O*v|=HV}|EE+}};na=o56H{bBIBn_?DBhA2Gin<!0eYY!3<TXjEpld z3Z@R1)!cJBJ4rqHM9bm-bdD0>t=Ym6-CFzR-Z;FjQ#aiv>d`Ff7B%)m0@lOP6XiC@ z?<cd>k$XY5>+@vak#Bp2z^M6u0v0?afvHs&=m*AR!0~nh8;8m&2&zJ%5`1#P#G+v? zo&GTMjOWFQCO5r``^#bO3=~NS^d;@F`jX<ZdZABv`-^>U4og^Ni*AyA-#q`IwC|94 zfSJ=TxEWmTl|Vn2;)&-gWV@5oG@wS2-u&LEa&5&T$DPUU_k*SH#7{MM-1Z$k;&tsK zMfwOcOoBgh6E;=r9!4m5BcWaa`@?xiKIv#g)ogv)8Y3{cT0PIY`k+FmGy^lJA%#oj zMqv{-WgtF@mCDB8r#pw(@+2>NSsxcoh8JMSAKkE`4vIUk!^<G|ce9eELnkt!NNePl z(!jy(uX|quQY_W1Cs!)1>Ml85iuOchwuqLTP+};6{o<i;hi~Qtj7E^6wF(h3Cdz_o z{1idUgf3LraSbb|@*5shr#d8jUW5U!SMGCa8c$kMv)??<b$!4D!pfqe0lGE4k9*)8 zy~lsmJ_00!o}J(+SiqJT&eqQoVkZUN-wQ4Zcuq&JM_uT|R!6=^Ev3QEyIWlr1Xkds z3`nD`3NDEl+f3S<W|@^?B*E`r^{e5;@calQHxMe(n5GFEj?D1mT6UOe1A@~WMhO!+ zt)ls;WlL6DIZTF2Uj~Cemo3fP>X=7yc9_W($t9k;f&~Gx)5&&z`<%CNKKH)b0=t>l z*89P!0BallEc?46j<P-}Q2xLNRwL_e!-)I5#6?3;iCi5L1WvR$6bm!^d3Y1Ii&<w* zAQ6!wk$I+JI3qzW{yCpM1Vm&eP9^tAR}(S(VXi+FJHJ+S1+iPS-gPgsR`{}@UNuo5 zx#?m>!8FHs2C&VoDZ#o5%@dM(e+(de_LbJ?m%O!$+xHAdkR;E`Y6N#K)|}v8!Ytef z{#*W;Xpy|NYZiNxom>)wr(c<!ZYz5)KY&9J#|t;ecUdH*Mmq`JWOee@jZ6d067pNb zVX`Mxfr5baH6b)MI-=TiPFovyJD93?mLJ7<eGlf{+2!4*0yS&<bWDt6{E0*M>uLY{ zd%nr62w;ZnMkbo%L-HqL>=9drb#+u?BsfxHJd<d#@cyHc-QfBLUetSoFSJYKj9?o* zV=)fmfd36*75FEz@u?WTF!@b+ZLog7_kOFy<d?Y=osdVoxsL?uEt__Gxwfe-H%dqp z*WQ58D-w61Jypx>>lp?b@9)D}=a*}>#)18@gsjWw@4*Vod^zvQgq-_0HeNoh69I>5 zO{c#~faO3bH1f~*s+B_H%~SB`XAL~(HK+$!Hbwe=OKW63dFyq=rET(e@X0^5crvhV zL~Z+XWb9t`#}{u@#N#Gkin!9*9!5_BWdfOo_^Al>qvqPA{jvx>2KG2SU!CTu1?MP5 z!!Ur0OQtdho%UvDX`>^zE%<ivnBR}-jMR|W1t;y5Gdf}CmkJT(Ya%QNE{fY%QeqLZ zDjxIBsZ6jaf`FN$X>@M)`}kva(;e*U)+&TJp_lI<v*)V!@@lZbuzYz+0Fr|u4J1lO z4<`(fB7eB$5qY?ktM+`H(6Q0XLL&!`^!zhDrctu67~}B@DytHC?ePC6*Y_X4-*6Ft zmj@t*CtK(<4qh<-JmB}_^Z(<OdqPG?{N#~B<d(oh;N+x`-ZkL&c+{Z;%g^|l?NuQA zpC7Rr2Mj@gqbhgm=9)bZ@^LIFK&R|*0x`TP6(*j8-ll2D|31@BYmGFJ{4XS=qc}yN z>YTBTw#HH)JFA`FjB~|VN<HFa*YJ7E8&W$M+jW*M1Z6jKQoV8tOI$;t5@0eX_hnut zFz`VI2nkQ7ATS}{wPV6@T}Ma15KsdZ*KyBcB*kcC3-2NuD0GX2A>8KsEYy&xvpACu zU`6_>O8p%r_0R6MUt*3#A^+~NDTM-TQMTWU#96C@U%&IQ4)8M@hFknuThWc}IeOeO z4e?{{p3j}aF=}c5IG1nQn+Wsj4?th(&ZnjCY1xK!X?8V0o0U-7yE~=q%;UZqVPpSH z5i1+pn__jJqgF4D*YsYF_g$m9&G_4tTF}C7f~0p5lrf>`*C^ot`LpS&3n61=5ZAEm zQU4wY{R^lN43?V*ll{yD9($2(dw;<E3mB&{-<_|$IJ(i;Q2ke8MuLO^@Y~th&97HI zY24twX1hG4M?ofw;*jyr&COM*ZQkUbUzL#+N+sukqo-aVQsO%a{p0fL>WeN5uHAkL z7n5%rg9I4-cj82S1g>4)ch(zpE7QFY=jP)QB4MAMPAZcN6l@l%8cpK(+{5pAUG5XW zqF;}`(q<`))X1R_8ba-(e0!CSfoFg2pMc*S&5H`%A1z1<dNlZ-8xw72wNdZbapeyG z_KM;EPF?P3HmH+hkfArwXrNipGyAw>dauaxd=)(@SRKppp4b1F?wn`-_%hbqq{)<e zSKcmncApA;u)A{6z>=nC1_MD(h*-f7VZt2DKnc7b6B|h}wd@TN#}0AKlhN2Xa(<xB z|2Q9-xQD=k(Pln~k<PdvM(d}SYIHblB(6zy(>ZOt2+&~`r*)2WSgRW`|2Q4uFy6Jq z_nqEj3~~-EV|)CzQ*Bv*^;UkSVm6e+3zFyE)ASL8J%H>>>=bFplI#QsmY%7ZF8jP^ z(4B>Tt=7p2I#{YPft5UlE|4&u<wIj}IA>#lqbE&;M0h4k_=AZ3y;DIdd5E|?F1@By zpf4S|`=qM<)p2Qv$Y<Oi%mQ1+waDB$pcx={FMUp$``@BAY#byY6?`*kox@?>Rwj+H zapBGxJr}iupbJ?N5^gIFEMWzK{^p73-Qk(=?@|!+TQ3q|_ad?hj_5danyoZR@$?@k z?(^372E(pcm1OOQC+5&bHIYeJ2UP3MZgGMGCSn3Vqqs>oRvfzRz&Dplb+j3*C*nWp zM(5?_^-l6V=(dAzL!Ab}5;^|;2fpnn$g*VmPfb|lgNe0|-vy8vDR-^LVm4d;fC&3@ zD%jY_>9%}Za<Hhw?b<l2O9xOo>7ijdlE|QM1={G_*QX(purs2~ST}(oGDBUjMNCUe zNmGgNXGl6%t86}d?Hj0qU^y(Ar_eaO4X@<A)K@Jgrt=aF-)n0i^@2x{!K73tClP66 zHmE0rd(R<aR)Iy&lq!935Q3;J>xbTS<i@lUu~Rgb35MnXos=Gm<PTR$17Lw+cuZZb zhJl3x@1u*&N}W(~U!#N+y3ozG7{^Ji#AzMtWP|X8VKs1^pR~C_u)VZPDn&lfYWOEV z$NuB{{V3v(0I@FqQYerG1X&=GydQ%b26@@&5?EGUEVGDdG%A3l#_lvxU8f5j9t%^u zOY>9Xtu7V5;^Er%5vBOGf!Zok3)L9`e*@-8Hsjm3^iru(&Qay~f~Y!C$;2N;-E+@O z_x|m37l{!H13vV|$<)4-T|~>74gZjUhS{beinV}I$l-Fzmq{E1TY?O?!60H65(ttu zFt1RLRs;_Znt&c@N<#Std|+$IZ9&iCpCkG#-6Ym&`70sh?d{Rb(0sMQ1=GyGWXDRK zSyV~VeL|e?A22e_7|PPg&<hW)h!}9Cdy9(A?-W=Q@O}``Wbk&ZG1zefX6P*nVS^YM z1wpfADukk7c8Lpz#Uud~$^S^vZzVlnVWfH=-Iw|Pkmtf2MDB|Ii1&}$hUZ~u8<H%S z;fyT}6XOLQl9heeN=_?cZ!*%V;CuR8p>B0@W`R^2GSsH4WnRPCT#YH{J;1@nsM6|= z&uba4=k_$mp%s`9TBoFQuU@JUc#gHh6g)0Lx3u{)ZW-KfoZ%XHe2B<cpJe|`Sb@tc zdQetpAqn*O@@2)Xh>@E-y0&72RtAe$SYuta_WV)u`seJIn$WuRyHAx)IoRk$XZnee zvWcQr%K`oyVer())EZe=v&J?D<7mSfCQzncOd5K0f`xCg<>(_QRQO&cZU$su>Xp!8 zmoA;4?ACrz&gqq~v5WFFQ1wWxl+x};HO{wag)yeGX`k#S-r>>e7IEM<Ly<ng;0B?D z6$Bn{elJVQH<Bt36fAel-hDfY{MvpVtc*Z}A+cgL#D{I|A)B2J@sIau|1TqR3O;n> zx|uwg6Z-Ev!KI54C<2{^a`W}D;}34|O*J_r|CRhf$79yC*7(<A!6}PgvYo!I6Diui znCS2r(m4EOJOQ~<qeKE*2RlP?9%WyYi@^N5A%IlNw6e^{s7BXzuE}Ok5Rx~5pMcUI zEVC?wA)~t_aEjL&0e2cm#sDb*<uTt@2>R-?RUr8`z_fY8zdZ}g@5{D`BUJq~x^)R5 zEm?ft{o(HeMw#l>-GQ$<^;UH~TjMheG7+axT`T-%8-c(#S!{Ew_-fY&cF$b>JpIoi zv@<{Orl51wE1vbLAf}moaZ@}i>epv2>C2&D5P8So(-(Fs-&A#8>Ef!D44$(x3H>?- z8w&di$@{M<rnBw3mi2PnB=^8QR$CxISqXL^a%^$YB(`~ssa4sl2%Fa<w)2Vj!HNkK zHLrtKNDJJBknGc&r&br(z8!Ioy{G^3+cW=ucQ~0V5%()|m^5)9y8k)qA!!6iw7TY4 zQZNM8&z=OAU`tcjXb_Zgoc9PIg1FY5i?w!ZHAN6F5BUxD+K;m@Xd5lEB)X0`{#dS> znQJj`obcbL$-}uLQWIns#UJsfKEsEk4r+6aoo<O3S}d%Oo8bq#i%H2T?&X!T8uQ8A z%c6!?R)Vzb@YOkWR0?hz+oM?oeUBMSMc5%tVQ_x|=$?bxW(#X_j9|W9XI_=9Fb?_t zYB?7aC14Zads3vK?ES|u3@G3Vc=y%t670->@$vnuJxMzXR%Z+!Fam?gb(u%fLj2AZ znfK$#H8h|T*02X=9<&~7{)$Y=Ca-TvXB%9%l5uKGrr%1gv#{vdcK1Qx4IU38?bGSn z*#V)lc4B!ZKOKc0N>OF)(z=7ssvMlT<h*1;Rj}L4w}`?^$&I5vjzi4`7yeAMMhy>% zXuCJh{>dMzkOKz=QoIo-yZ|TGoz)zU$z#S2^q(aA&f}e^0l4KqP;;u{xLMQwwG8V@ zBwL?-(mZlpdS|@#mEfblouLhmpc$n3pRQF=Nvvh~V2UI36{UD+sGUM2j^d~v@78}5 zDJR#4r4VwQd7Y6ZMiOc}*v|p+L^e)rw~jSz?@~jR^=&ZIOOv?#YO?&FTRDzGk}AQ= zNuB4h9I%{ZG*G2x-gpCE<7=zbQZ}+}{)uqkKWko&AF;4RPAX*Jt{+B?;x}=P=J>_f z6dbgxKdqN6lk{VeP%l}7Ug-O=`$z&mZfo3nJx%Dxvh|4v=!)a%*=7x-CuIqxs5Wg> zMprUbgO!yL5<*Xf$u*gZnKlP2tBLjvj@EF-L9jE+^H~$$?bXqU+Y-J;XaFVt=hx3l zy<;@(fpcMZI+ac`_16^Qc&cB)l~Q|?<yS7XNF?a70O>>K+S^a>NUEy;LrX<v2b~(< zXzBI^>|*oi4vM}ade=8&Fvsu|PzLPjNwsgutz|N5G4~yKMnJY3@;klH5la1N$^Z8F zyrMFapcfwei5KIst()XF9*${<cP=K})A6@L&7$_a+O^D06!#)uwTh*H9-eAXa{|s5 zToM*`U<lVfRnHLk4(0J?aK}IC``_KP>@**Or^HtJvZ%UF@4LFIouQS>t$sdar<d*F zsnEixH%ZAFdEP70lMP}rnTu1Vm(s<Lkl%!cF)WT-eH&@_^&Mcg&jrRM`|TFFFtah% z^+*G>$dW&*gmiP1?aSs1blL0U^J&#6ZtVqzvG!c{ulqWN%*N5>--VErwXQ;8=+aN} zHZ*pPFmwiuDH;1ZK2{me8ckhyP-m;GOm$<`nWQlFi41;^5I#FwIXZSe6?Z~tl;X2_ zz7u$|4iTpcAD2Lm<8NmoAe}-4^G29l;|{5CNJwZwWdXlb!M*s(m6tWXz|Jo{yag@3 z(BJ;zXp`)f5&j*DZGV=oz~|K!r_p3iW-qR51bVNSgSl<oiW)C59Y}I$KL=M?yj;(O zl$RfOB$h^!hNRgQteuo&g1;B!OC0=yj4;9Rn(MaeH@8`yC*7pLs}WS<o~K>p+*20a zgAVcf@V#6&JRYHWiQR}K?>Blkz5a*N(Lpr+u{~Z0K4CV`c|x>bWjbMo;klvGv((P@ zeN{Je;)%~TB-GWBq2<eJ|1a8(fok&6{z(mtoTu>6Pl~@w`U$pf0)5Rtzw-f4lx!8` zvMC;TXFRJAh~k3-b`&L`Jpb_V62a#FbbJI*+><5DgCQX03t;{6rfxi7R!BRfEWB-L zEF>tjH2iU`wKSYJIWI;m3QJ2RX?BHuh_on@4FvUyLYehqQ`I{7FdimKckR>rzbbvP z;J5How|l5@99?<-)Q#7_DihW)44D-KO@|Wa;3wsS=8$nehb(?Pt`Rt>1c~T6k!{^u zqS|6tR&QFbpKWs2$}J@~>sY1M7b~t)cQ2>YWE9(o!ATRa^gMf8k1mm8otEuWrsp;7 z)wDmMah786u1a}@r#lc!^IHI*Y<8)b@ffs$3ir!+&buH9-KA1e8x6#wd3hh9E1Lo* z%7NEXkwG)Q@y^4i9H4@rD9u<cqb9tZsQNC=uErr4zMk!}_GP{jDfjmRzUthf;h05- zrJV6_iu^Ck6mJ4qF#JlGTr;YRNZ#!hU)cs-f!Ks>2x;1rP3SQ0*(n{7>8H_78cZFB z-J<adN0X)!UQ{}72^Rec1)s7Mo@1J<BJ&H|7hXCkDQAs!k0BBE;3$4lx#s~Ue<P-j z%O48S7xHocun`>sG=b92>rDGeA)hYi9m{fER6XsUuRActtNJCOCLp}=2rz;O;>Qjk zHaI^oSP)71lAun-iy>4WxDptAQyX;6Yk_hL#0ls<NQ(9*4GaqI4!?PlbioLOswn2_ z!3@Lg<AS=2k9$gF_D?qPCnM09ZKuoe-8$5%Z{P(;hH!$n0N}IC4{zeT1>IHxqjefq zqZmM;1_Rnb4FB1zr+?e7(_fI`*yKge{m`&<mx#sT9J&j%8Oh`+kmTntDS$%FCXdEl z<<GS`Sr;nj@!G4u^BI1%k2?=^q{9zl;o08Jhc;PG=*+8|Y9y$RmBX&I7@?nz&rCMh zRCSCa5Xv>}K9yA3_2d0|nkOP=j-b>!o2<=8`bkK)=`=b)T-TOI23{ZxMkW?YR!sFm zb|8;@?!y(w=v1j0>y^da<wgm2mBieeWeQB&=xfj;RJ6LbDKut2jiht^YwKW9*O{VU z(QlZcF8Q0h02&k5W%w(hvcO>lY==RciPG1x0CaggyCm=yKp1#!^+{$ukb?h-@Riy| z>7^NKQp+rZlY>hi2Az`mXSlpSUOe~))jj!Nzl`0*ql5L`C97V)XwyWaYoq+=m^K2& zsK&g#v9t>lyZ?`?cZ{pNjo!YqHPvKJw(Xj*b4|A0<l5P`&B?ZFvTaY8Y`dO4*Z;=z zxnJ$~`#jfL=WnfJeGkotf7%TcUT6cD_6-ca>(rmRZ_rGPcIsTUS!cXn>{4M>hrdQ+ zEloOPa*(d5({VB2G5jLv^o&XWO#E*az!Syo%Y*VO2EvS}W)G4dtbMPzR$(advto-N zh>NP5&EW1n;+365rho%5$N`%P`jzADumE`H_EI^mjSD>?GADiqaTuIwu!aci8?m1) z>H0t<@8rw6T|wOv>@mTA9k~@c1oGblU1J{hY}dx}JrMKhI;p7}<hh*`CJN(%`pl{# zaVGZYMKTZp0zm~TlVfM%v|lS5>P&unJGZ+uUTuw4R&5lD8L6+}%iO0F8z(+2t61j7 zqnMrgMr8ZUxx4P-Vw?>mO0E|3u-UHO{-AJ=U(0yWsY(fIscb5q8q#rz&h|bWu6isr zcG*&_VjsPe0KC`CahJR7W60($C6tj+I!elT42HwoRufXivWq_uxVlz$`$t(ogB=Fh z8<nD-*d>2BF1oP73vPtSr<FS6l1U;fsOMLWs>$Y>5k{s0dCHX=(`;DdDgEfc^}Jyg zR$3D!R(f{4*@IA6%onR#EWXNmoIbzc^MX%ih;~h;Hw`Qup{+?%Vd&k!#KYGp3dd?E zmk^k?1;}p#1Y0loP@PjZ0BbQksBbahAzV)CIu60P;v&T9IN*S^u*t0jLhk4WJW#wa zK+h@X!;#I)bGJW5QQ|D*UGLO&GpC{wr(EGb6g>O!kanODBeOHLIehD?Tp&1wZR10d z-bTB{@O_fiocQvQcXvhWVQ<=q1&o8;-rgI1E65n^-&uE1z*ENqg2{&U4_iQ%yY`;a zV7n9+0ggH0E~_G6()i$iqzL>t3lvWf?{GStYWn>Y`P<%U8=uq0UNLEk*cN05v-%T+ zQLiC8SzGrp`A^d&MZGO^*e?-<S#z|on-JMTpjuD;qZDgi#V+lP-Q0yQ;MFU<rXCGD z^-E;3M>->tp~q%<=eLd(ZE|ssk7M;g=cK9`kdStHy>gJvMrPe(zvMeH{+xMMHvb0_ zzV8He$8|<zrQsq!A&zIRYO_t!0<>Yo1IMTx(@|E?EmO18<y-4LzFTJ;#)NE_+GZ(S zYeI&X%P_bIvs^9`P9-I>ka4MX@#8zsSjX=enxJ6OdYzdM5^##$G&=%dIU!|9hCgKG z=hL-v+k7Tdbed(k7FdbpvvTHh1y$w7LTN;raA&DZVG@J8;0=$Y)!ow$r`axZ_<{+V zm}#BCupl{w9juVD%SL<tsv5mjV+st5uj}?4_I`OvV^yAjw$D*jH=-pr+111IO5%DX zy=S?R+wt{At>dsZFG@N^OgKi~KyOg`_`f~rnI9xRCsWG{1aC0K3HDyCf;<U2Q<2WF zZvMmZDSy>@AXZ&~mOU5-L`%V)VMFf9AF`M&gx`+C^WS?3Xj1t%f#ui8SB38%V9q3@ z5Z|{0hWA3*;jRMr2)<3xicaFu0ZVoNkr3xKhM{`G+oi%@<{b14u!;X3B3PoW!Z}G0 zV?Dy%8lfPE*m>>Yhb#)9q!uacSVVfA1s25aK&<?)F=MSc!dWZrrqc)Hbo>=)O4u8i z@_@xKH4YNpO_h5t0yyO6h!~Epdl6xGX^qHh=c`l0d<0Qd`z|69h~96g6tuM)3JF;k zYKv^MCv})7Ih(4m(h>~MbeQlL?6TzecVzK-3x4Z5f6%DuZ<sN8A8I#SZs9MfdslwN zpe<{L@sIXToT@{-{D`{G1Uf$Aij_7~u-UUBkTbLErBtsz)UhbuC-g^Qrk_2BOFH^N zNo8z)l%1f_8g8zOL=+dSb$i<ml$Er$-B7}c;icl(<hRW(b-%PXF?p_!d3dTZhNqx3 z0--CU2L>?y*c`F2()iqfRg^FHiP=3NBp|p?-|tLhbVgO_7&qwY+nlQXoa=(~4^r$B zD^f~!QD8<WCGyv5f}govOJbqSJcsmn6irjxk3x{=9A<g82NGjg$c9)7^<C=4Hl%>+ zHWy88#~+kF5?|84#9E?}=6}aMPMMkv(;1^xSWq3%ud6O1y>pLtXc%`y!1GvhR}U5S zX4b>2!B&QI!*AUOAyw`!v5B0132B=yWc99k!uu6qRlhrVl|Tf6`9bgxxJAE$(SlLj zBn)lk!4d&`@S*+e3BKbfh2<zRR)?(<3$2yV8%{a4-%j!APG)wa4S$f+R~lu!fvmgh zCo{RGi*yU2dt_P&_hg1mcmCBQR|W6~F(OXbPefR<U3vm?I0EOB&{SHMY^s}!*xWtY zZ)w>}+oiCl)I|C*soHeS7E`>L*9Gz`DNUe-W6sQ`J5%lDdgZ*5(s{p^wY-;j*Rdx6 zXQMuGCbyYiw$B@L=4bBb^it<r=RGZWf#c6Y!-j($QYyK6nTwC4`^0L;ZY+EUEA>D{ zthT?%>5sV<l&2THAR(kGo2<bpi!-i}RPp(R?CaMs&a^W)CwI4Y3@F7L4*A3nUf6=N z?o`{KTULSM4S4%!MPA6`scU_QC98$kdsQ=%R3oe|uJ^g4W9HoAUr!KR&)|nwEM_g9 zPcsDs(^Upa)9+OD<wH*j%pM>5RGVF*E1`49M==)5eq<#>NzofS>ZBfG&)i%}EaQI{ zCsK+5Sacrs8P+rXeyjgC#7d#p+@*B`VIf2w!%w`1jadZ?VB%aTK`gc`h%2_-PV%<u z5inGyK}Q~48{onv%F<q^3X?H2#W`>Prf~=pMd#?VhMN}_w*{vC*6)rrc34%*k3ChK zX~pL{uv08$Rr<pWiVX8Ku04u^o(RZwqLbAQYg0GNEi-kYJy}wflkHW@yzi}`F73zg z=M(WiK$U`Id0_gvJ!t$au=xRoF{Y@VL=lzoNF{g;|M+=L{5eYjXk1(a8H1=*)&Jua z|D+_iZ~w=dew>ofFUW}t6ZiU`X^lAofpXjcdy?xW{dahqfjhaTj7kKf1l9J`bEr1* zR9{zYspa}qL+s5k2O7_4V3iC#@1z>js+G{o#WZ1Uqf7{^8%TF&rLl`%rS~ktY1E^^ z=kP|u*{UwY=Wd^^%hnt_`S$o}Yi+L3vPD?sb5(Ai!hxU>)%N7bcNr7A*25;>;&th< zNP0l4B==Rh&?MqPLH`ud01Z|y0a1!_ezmleX6U(F@P<|Ff(w@Up^(~GVF=ZJ{%)7i zu=^wuObLJ(wu7Nii!by{llgLP7eRx~LF%FvZLz%6x_BV)k%pX^$3|4$s*{N2rywAX zM0uSRsD(wQl_bmU5|!;b1-0J#q-y=A*n!mEsBZ=+{a00c@mcHC=CqMZPt(d6Dj_85 z;_$i?KwiUUU#KEa=v{u%c#8=mu?=T0TUaV=U>SDHs_6eTs^DXEnC+IM>oE9LkaB2n zkUY{Ug8<xnx*b#%1QfurT8!Agmf?O~u559|mA72`_Par~v-%s6THL)#@Id6)u9&G$ zWQ6&a!=daAoFV1qXlUJMqmzr{B;r>}0bP`+0R`*A)fw|Q2Q>kYqyzjq4~hoQMO3O1 zo=svTB0QHuZy@_}v0Ua^=AXCXKqN4XZ73Hj6sP@Q94ps<z!dN6Nc}T4(?}0s6u1=1 z-+0inA-)srEiw#&;6q(3F4HcU^*<mjB$;ebgF-}`#lzVuqwYV8pAOWlBBo<OBB?+1 z^`MV=J4|kRlF`FodGr(V*q3o}h1&=yX^lyjYn4Z`qOu|z@s^XfXQz_5*Gd8M1EGnA zDMfmZm-?UGRa)&+ywDRVRatfwOH7Rqj**M1_f2fEzh@*K@$I}9A6B-YJDyfV9^O!Y zTe{d<SJ}0Ry_(-FksfSmE|1H<z5i*56ufn>I2Kx|Y#tH`g%pyTLP<KRohG{@#womR z^MFlsNyUU;O+i(_-48q+kz9$qIL+(0@k}O?KRV4-SxHu$<&Imh2sh+_d|7|8u5Ox) zJXn8|B(5h#Z>viyT|6-wFKBzXnf5VTmcudUFpgau2)^J<o>5Z4TF{;?S8L?m+ekb= z=i*w^W=o+Ccd$%q_xkRE0hd@)UEPviGtuD0D6|z4byh=O^tvlPt?9fN73Vxh6$+W} zSI#qlq8Qr!_)jnUPtExr0Uz;Wt^bAakLgjIoO0-szsVwTGUm$ur9@}J-0V*o{VcQj zi>_(T>C77U!v2UW%Q`A3X`busfHYdBa1EOhbBx0V*a6d6X~)a=y!L~HE~Z)ms)!|7 zWP4Aup@bY$`B#rf)wNt+ub^ztS6kPqOJBtlbr-LYM*5lNt4DK{S!Bn@-;iLa2V_7e zosIr^SY*7vR<>u)tDWu**6?><fv@Ag-(*@CL&2f_&>fCFc0KVv9%e5*!@3K5l@^5c zUynA#D=S!sH$V<WDBBlZk9w~l_p8G>Msht+!!jz6>S4+Uv~Aw<ZwGxCAOQQzcQ$uo zn)=Eo@8A4@kBX!L8$CHlJOTE~@5VtKHg5N(J2!Nn1JShF+b!5D+Zdt+hf0-6)oxng zDx^w(&Y+2x*X6#w4FX`NC0RE5g88yG5O2Qf07<EJIpu->?e>rHI@fvvRc^B$!>O&X z>S}or-b^u|MOoLHY`S}f@nwKm<Gn{j8F$-&i^Zl0obiVDEgat9H6XW}YMx!p!5yhz zm8jU3e)~C-RTFr{4j{iV#bsTYc9_?Cyz4DqCW@gZ*HCPdKIF3ek#djc5*6KX0Fx<n zk85pf*Ni9kEz4MmslYakW8N(CILCchl3;*hIs^-<&g)>8X5U#)*%#k?7c7%Y#&awq zxt#Y1z>0efOjelAcaW*5(p|E_pbV$HFQ&?8D__7%AX~us^(c!z5xPL+fZ)t$*Y26O zIUC9!mt&HqQX-pfgev%y*9C%@Y;p4L{##9sUh?m29U(RtC2RO^SNtIz;w{AfB2p*` zzj?J>-E3uTS+ChA`#j+W5%ZYVmC!_YP=@pC7i(7(djDpbgg1fMCxkp2r_d0H>q=Ku zzU?qv2v{b`{Z3U>v+<?LW{)*?>kO~r`)vEH{UR8M0S4@Jb?9nf*t$74)9)JM2>^G^ z^dW(_<ehRd4=mV1jlNJO$kF@HFH&JVbPAOlYBBd+QSn&E324~B;UAI<V%m)go({8i zeP_Xa<lHHj9|v|HL;twbEv{THCo0y~)@&1jx1e_jh$nImGV-`{P~!ZL|9^%LjY1<8 z!C~{XsY?d&6^?};t5;kTKqsADF+wNIvqCkm&KlhHtMPF4JT#5rW%4VF+7wHGzl#mS zIunssAFs=Avps1~>u2lwlVZrVh1f5@hQ^gwuQLo*`R2>Jc<cL`ZR?V?)wM3mBOVxf zOPyWm=TCY_UDuM;wYud0Fv<j|#1B9NlEokvRYgtZw!cwX%0YM@(Oj|^f5(gcSoNN# z3DLOgk^+P9OOj^(a^`B^p>S6Zzq6IDWK06T&qtY~Tqo8zn?ns43dylg$adJr^gOQ% zt^Dn1xJ3}Y);z?}{5|S%L8hiLV~?`DRw4ieQCQ}kNv5bMZeG4PBMX_w%<rCXL-I8f zJ+Z9Xsssk(s^3UF1<A$!vU7F(Y(Yk1y@%8rI#wkmTyh!?fX7y>fYL2Q(+zn^FxK%k z(XXZYu+WDMP*;{R3cqO|#RZlYwr5LbJo+Ey3pN$vD#u8sp~-fOI%o4|*C3x&I+sbO z|1YGhX&$?w9{E1WZI3I51A>ny(>~h<{i6^5OkFuvU6=EKOIxO*!@f+J{R*r-rV|Rh z&U$eN2HwJ^BEyRN_-5E25DHQ3dXz*_q0p#@1@cQU;P!8P$q*FaL0}YHh~9?*xsOm% zIXfg?Puz=4FMZ;Fj_AC5XH$>F3fW){ZSO(Ys21Y)BS}U9QFIs$BgU79mfz<FG-HH8 zKh0D@YutYnw`T$h&k1JJ@mo3v`<X0R=>5Z0TA>V19Gf}*7=mW?yZ#VdW$-q>t>5mk zHAiGlBf}dcV7`9bF8{9onhX*tZ<<XrCY$nUTYe?=-+GT}VkybBIwv$+kI1b0<HxDJ z*|@>UHJSR|wBi9^`8x?{5(=g+X-kanxi-rAF;r32#%Xtc#&(07@-F@<<Y@<CHmsT* zS<UvykBX;tORrr|uTXEQnZt}D3zmsCfyPGezVQg>e<?WP)^7|4|CiNE7@dTa{3?DY z03HT5D%=(+hrvC;);+~^@^-=M-udN@=kWcrT&tvF9dG>vpx4nMuX?`LWPRzYey-(P z)wB$w*%$1>j(!?4C3v*kv=l}KZ{*mWWz73*Lp34h2+#e;j4qBopABil+`2f-3)w#v znNeeGpnHQtv6(+8oV`0LUjz7DScv3A$)W4hcDLc)p>lUv2*E^-F5Amp8H0@fH~5bL zwM_98__Nq6)Fsl5&XXgUrO_vH0-wv4iDk|bd8q5fAP$>FSsdypae0v$)16nU<S)Cm zR$X2cqWF++Llir~!h%62SB1+=fDKf7E`21VPHb+Zh}IaFTGs2qK?5eOwbIX<)Za;) z9d6beAdkc%c|y=ryMT$;^E%q)`TZrP=eva8^cQF`@0_bIw5s}K*C|+|qGVf<A5q0F zZ*z08D8a;LQV}!W!Z@f>7-swMFXnzdjFAE?v7R_E5It_(BGX3r5I`-ZzcbVQzUAG7 ze8Ny3SF_cwbC_kh3zT(8L(kuk<vMwCiA+NSaw3}vxAvPxij#M`1`OW0_W(XPQqsU& zWMtP*hsj$YN|S)=*34c1W{c<MSnqS((`@t_8KRn?Uasj*TG2lji@Ew4{<ys)V3cuL z<%Vl@4I#MX_FptOkDx>uPph((Py0F_%8dgAukSaOXlYnD+Kc^8Ye|h~vW?@nx|uW$ z6>1_}X&P*^$QM~Ed5V(`T<p)%`4}K{cizUsgsx+2_YY1&4<%MabY;z@@{D3NxDRh+ zw87VgIoOuJq3sWT{AY;~C#@<aC))zW_yb@y>S*C>mTaak(RK-kyP-v|QlVD)PnOF1 z&Fq=|_Yw9YGF4Jn=m#?RNnwP18h+^HcX#9g&Q4pIqcW+^WXLC>pAf_Q+qrRu!7<2) zuA=g+ent5PHo>ozPB_!I9EtY1bbLd$=ylvDh4Gm5SGlF-DMQeRrdts*Ca>?0(iDtD zlHTPYL=6kmLJ9}!SV6@f>M~qrvb}N03|`lXiT*8$A0=GU<4Lsc#kKHL+-VFF**mty zgzN~Ig_1t6ye5~;^6A}BOdSZ@`D<i<F%nR*a`u~8Q%~%$8z3vApsO0sqb4$#zAp`8 z=>;><PW5#IuZ`T{%)Y&ONV;v`xef!-X}gbr)m;k`#m+euWcCN7%qp#P0%E|N-Q-2b zE&M;!tF|2`?}Tn+`Q3UNka@%sxkI;72~XH}oxP!0J|nxK*fGOMg4)P;jOIihWU6G) z*RAOopTD48=idf`)cTkNGxERQIpJ*82ms9$^xI`qI<K_=JHH4^W@nyn`>>HPWkiTy z@LoO0xLlbWa`*Swnt#1FZ3fCt?;)Md%VnB)^DhsVx8yh{2+i`RQPsSHR{s@*I(0pc zi)z|o#(N!E2oJqHraiZQ;T6FWdnwM(wHxjYMe|Oh-`;M+aYInW_Kd`nJDa?n^w&{i zj;&(U*Zi8vjlKsw2dMFUcB#vp-+3U#(2NK$eX0>{IRBQHD4zn))1$e8>YNB*k*UPw z+seD$uR*Btf-grK+k@j5o)ftj=$5|k?Pg4;PVJirP-#gX?`yy|kS`XWk#`oej`tsh zfpT#L9>wusQ7c&lNkHyJCCnE>2KwD6ejO9})(AVW`#QZzQ@_*l)E8V|2h@`I8RX9d zs|ONHIjEzCI`o29;UAt*3uhMQcsXB?kQdHFc5l_0xkX*zdy;F8M26mb6$@{p+@kEA zr|C_{un<BdA_ocEllV*oX3)2fR%P?6Vs&5hy6@+Q7PZ7Jg3sU%r1owwcRW+9wm*oZ z3mo%WfXzSgX8PU09fVAP-IL@?_vtu}O~6>fDDk#-q1sL}`OHw0Mt5szfOirlKC`ag zY`CWT&a%flwtowqDR9anVL}s1`8~p&C7BO{QI(hot^dV6Za5ypX&xW(_l7y#Zoql` zQxkTD9-W1TH_P?@J;<*>eiGjTbqX6(U=!q%US=}Ig1&#vPw3A^=wCXcQBFq;ywh)L zI2>Edee*S4^xUHIhD8<eK$iV=-;c?cUHgYV8~c0mOQf<ny4?2qu(+_0m1d~tMv|lu z&R&NmpZ(qaTUvN3`60G~@DF89m-@mCZG-OY-qAv3kys+m$5}Q4Gy3r0F|^k1FNE_O z-!FMiZy5xbuonrgpA-X34w-$ur*{d)6Rr6K8;_#Qak)iobak`4#ki?34!^IpIhC}( z9RSITcQ}5T8tF}BP7w-%l!s$K6a<Ra$mIj9k3;pQAOEGXC%7mAz^+Ta_zaW#(auQX z%BBPBBEzejlzBZYQ>z5h)^NXG4B1hwBM$2K2D-bfC-^LG14z=RxnCxudUj{BNpR4C zG^&QNtvXCWuk}c>J*DHLhD5oJCaHm1pJ9b_0GhxFy&y)J#d~pr&{16iWuR|2Y@k@3 z!j|8SS-d((^8_I^DdeKzheuroK01$3CsCP%@Trj+pd2u_m4{q>XgQKgI+Jcsj17Y^ zLUsyq@IF%~$1U$z49;mw&gzw4stNxG4@oB!;QXf`WZ-&57;{wSN*rJv%D;DIg<VsX zcra)_UhuWTWH{q>d$dMjY&)y~Z>`XquVw7^ag%{fO*iT}k5UH0%)w6|a=i$wV1QT7 zGL!tiYSGbxOZMW%gfmWirkUOxVi^oMn8xIH=gl0-vDIY~(h$omK8Zd#%Os>_|8rWS z)f;>bh7QAv=LF>J_Y#*(CVZHsMLpLIy)KWYb_fui;qZRY1>{^h!nbveLIFt8Q@A6R z?D+ybhs$G&bnxMsm`}+`idQivs|2_B7VMMMMcc)p5j#wMp$ThYeJ*H2CAIgPDiCZ7 zucqj<2^)4jlodjamooJdtn=41(L!?{s`jwf93w90;V9-^sby4SoWTsiBpk|~t)qsg zkmP9aAj^-3cO81BpKQ#?*z1QJN75SsgooWl;RoYDbmnf!Dc)0hQV}EEG}x|^8{-Yk zs8F+X_na>jKX0{~i(&bfin_XV=QRjJ^&*%5%TmJ<22cQWUNmPrtGOOn9AC^UOW)28 z@0zpo6;wm~Y$IIWR4BMFP<!0C2rlGO)4~wF-R8oH13-F@6<%ncWN^Y0|I=lJv`fP` zC7}t%BPqW<uQU<*^iWM=zOQkyZ(q9Pkx-yYn`nZTL*8P5RswNMwqAxlp@JApyLtR) z1GvsP$YztQP(pY$LTd^z+55tOd(<?lYMsb&4ZQuofanz&v$8caumc9hxkDy3Z!trd zCS(gE*ItWbEHTTz$o_<PGbo8JRoO5KZtA);(*iesNr6)P#|~(=i4sjQ!nVJkcbZra zZS5pAMSNyb-pEJXh~!SWc?{MkM(5_Vn3%><2=RLYwans-^%9HYWV@VR8IRA7;vFr6 z4hhjTcPHL(;&Qu$pU?+`*^y|Ogv57!8w0yAVUwYQEo^O*Wf<GO3&1<r%z@VB_S+6~ zez;Y6%_7SQt?fUY@<3pG@i!LYIx3kp-L49-5@8n44IhP55$mnX_6J6H_rHYI{%#ap zsoj1Z>@Ooj>vKP$vI@-0rMl9&LP6T9GyGvFWW~~Zy3*u4`A{EbsIw_gn$K(-*PU8B z&HV~D<UCs^(LBj<2_U199lpiEnYQ(GTkQz2Ja7FOBqVEoc*S3Q=m>He9V6wgvH1CO z=?y5@b?Ts3$ko@Gv;@yTJvQmoYPW2F3y7ote7-##?{vQ{NPVycU1n|olnRW{Xk$rS zlmKp!5kl7tdfurpYJfK*x3a1d#bUDRk?vKVlf67R$ZEcR7UvF$H;lO5%?Ex$>{nm! zn>!lp&%@VNgAUZ3Xpd`XxI@gHK3){j_<&GOBv?^?{WzduA2j!^siY2=CGDNDKaB*^ zfj&#8tWz2r;KkAi7S0~I7JRhdQ;aC1lzR$58P5gfl@dy6;4GhaU|gH6mdO3^H|c3r zD1pMh*Zr?DJztZE7<S6<I5G2$Y3JUy45pjr#)Ydml0kpfJRUMv;C`ZT2q9@TaKVp2 zsl|ZDDu9`FExy5Nzb`c~fdhDE&3kH-?%9iADQUhwz4s*Z>nCiBZOWlRg!<VKH*Fjh zZ{s$Yr81AQk*Ja$;SZ;dn=y70c!75oLad8Z8Mu}ELnB86-`qS)^1$arOqneLxLz5` zmD!5DjcaryrWC3OvKAg<=)+=z=Vzl1&=|la2YHF7bRJk1oZ9~-Z3WKaG7o}7=XB-_ zTL#><pFOa6SUCf#w8LVoL}w+m7S*T)Uz59XK2>SJkI43Vms<2_x`c%bUAFPnKx;G9 zb!3O4_hAp8-|H*VMqyN~lr}1Xz&^vnGSXRQv_b83@lXhPpue|k<DUc0@UQdNUZ=~^ z8!H{XHwW$bmt!D1G$pzHyG?Ap`R4SHLl*t&<!W8Jf56r|JkV&8Avt<~SF*+TwZ%7) zA&q;ry0^ZzQ%!9sQIUmV+VBlzm9Ac%s5aqC04hI)UvNa^(1Y%4jmdI*=wzU+W(X{; zbI21bwEu$a!qNO2QusG)v|%w66kCS`EBsPPa&Gci+l}b4oGBON@7w|o<Jfy;Bd<p> zo5V<{N$7dvYH*r<ToX(zc-Dm!LmuEhdqHpI&dk*&@@-Iz>QD_W35Nw|=r@TI5F#`w zqwK}*)<&9@^slb%!LLZ|&21c{N~f^EY0cTMt93ri?gskgxX;~1m15r5r^+b@-F#KT z?q*1t(56ka$`HmC0sG2BE}k8+FjV{Uw72+6eY-gsE^`?9Y@zB0!_HKVQj}!i!gM;t zZFQT3p1W7H^Pxu(dY$D$37(7m`6gX<jZM<YAflod+LYq!5TaG`Y>I6Ir9U;tNX!%& zNv}U-G!*jz0VT8)HMxod97iVCMH~&b0%X~D0tDi;F)+xpS}(D{rT4{IvBc=7?k<h+ zUtN`9WSc%ry6q}NzHbgqgojyxf6b&T)5G2`_E7S~5KDh{kXc%Z2PBJeQu2K9y`t1( zAJR)|*mLH~Nc>t#x+|U>CfB|Q_^j}Hb+BBynP^2mhFHc+v0AJRb!Qa@Kn1QNZBT+6 zYBBOpzj(?RJ8ZPrb|bdhvVu_oHyg}jtwPd>Yb?pb4;?a}9SKhV!9yuj@05qbZE;of zdU)s|H{I3M)XHV-<Ta*laqX6kUaG4Zv)RI}t>Qq9#>eEa?BvX2er|}Ep71X?qzOS& za>1GiTmC9C=17<YJd{PGs&tZiD-;TU9`e|y(`k`^XqhZ+xX<~GYA$L*{)S==gd4A~ zP9!W*rZyRx3MNF^x3sbcV(lfQZQoz*$h#k>n-{e>p(YVIe~U|T)+Ds?vYt8iLom=$ zst4Iy_Be=k&IDd_k<i&oDGHa&hs&2BU{uOy^Q-ga@gG_XXT?<Yx-|WoWkui4`-OTk z?hS+ROz)%U7HzoSFC1$}FGfU2DTkD9$7l9f+_w29e!G9tz?2A3l`EfBCXk|EIo^G{ zvhrwCj_E{lZ56T~yfPZr(3Jcc+LUOTt`q`Pjc&|okUh}vRMu;IY&k*6x`V&X9gjcP zHkqbl3M8K#Mhwy~SEP*N4+*MIOKWWAkdYG$wh0(_u^L>7@^2%-59g_?1gy5Zw`8p^ zLRLuOoch}<%@-#3I0R0ej5rO+Yzvt8>NyU?t}jr|`a}LEa&>hb1Np?~>ECE=m#+kp zZNp^=LP02TPM{J(wJ(5t8RYvtP>6^Xx+FEWmQNAnzWh32w82Oq>&AnnL^tn%J|C>I zpi3d)vobk8g6CRMf4tl73gq}xaaKXY6^9A3<dKsrPG!=su7`egF3!J&lxH9BdC&KU ziZlt4_dH_uH}+49arif!@VZINO#*rG3hM&bpZSLj4p!-5r%P5jhY64QaECQv7`-lQ zk^X!<v@BL}3H3OjYbH>VNl(01=)afqq7|q@HYu}1o7cWM5C2a>K?B{K0qam*ot0cg zMKh#scfY)C>&g7iGmpEktM3bxnqC(?j`OCzBzCQDcmlD`e%Vy*IGa==2vW*3e5^87 zg-0-c>u;>VO8oZsV7q}UdQl25-26mUUH7h|M1oKOVyISCtky%y>0E>+Wi4WOjvW-P z28jb6YlhM($y(ghM<S97no10|%v`TCpYNYi;}dNec8XYOPdgb4XIB|IG1xFtx^c7~ zD5qa7!i4Xx%q?+a?bMV*Dk#A<kjy;2{7Jx<{6W~gc7C%jI&8Z3ZF?W}WTv6G=j>Ht z>I(kc9cEUUjk=A>Iogo6=m*jP4&)Q3+c>`}#CSP>(+}EkQRY`cm;D`~dE0r>B6zb; zSa~_1MXT=l%M5sQ=U&!Bp=Se}ZV`t5mBKzdXXcE$pWibS7-?x8HRXrtR>6JR-9?P@ z2X^lu+r@z#-o>esO}#I=Uw=M#{dpCzw6dCO%$WJ_f4(E>QHOfPc)$j3wN3&gSMBOA zw~e~Ky_PC(bIt*Ah#&?$HNab~`GRnn@j2*FIs53_Ff8c>I4dg%Z~vpcJE9R&g2YY0 zU3kl&JydkUA@5y`+&Ivllv>v~Xf!MO&kG)1q~48k-ZArCh(jDz=&hFj{cgVAa-Omc z#4vKEg`3hI=yC2GYIix6z7!rGj#=-hD=wB$tI{gMBN@`<ZGWJo;RO-D_eZI67di!B zSEp%7cX24t`MVQQ2)OgUUn0l?{|WZ>N{UHvjrC?@J++uW9iRyOF}^Veki#!a2$e7~ zIXj*mw${88elupSqZJlRA>xKUl9zVM*UB(vKSQudfOSa-o4-wmh3HUthxl5JD+w)V zCKOQKrv34#?*q7aiPbJF`6a_Th)^cOHJ;FxI@UPGIeK=M^zy+-Bh;x~&QfFpq2IJS zV|14vcpP{-F=z+u(0TSpl^ML_sf|TxlypX&daGJD3pL)_0iOSYmho&fjxvtcpdvGX zB>V=@5YBSeQ$?ewV&PrWA@02Fjlmb7YM8k>ItXVhE`#-fsSf6+)*z{6Yi3d_t;D3W zHhn3oFvXSqqW7{mts1E^09IAq|7vn+Y+Y!6Z>sEY;h2ro3fCY}OY(Ox>ie83i=|~n z{7F0O@!GV56bS}BD^?Z9+~D?2=X;OgYMm|dQ09)uUxHdWCTKeBZ;hQrkdl849^xBf zbB@>t@bn(~>T3K4Vuz(d{!Ih!zc+#>UO9dfLTSww@N917JZ5M2Gv9$DfChgEgnz50 z+D#*Kg*iiQ)kIjK`BHS%QycuQT-@y-4HsnlL;3aik>Y#(??Z@yie5aX4S^!-EE1Mi z%ZFJ4Cg;6quJY#4OTnQA{T5V%g{c{2F37#gX>;BL^y)U8x}6o`$UPoeyS>b_cRYb9 z+aV{?<K24=l=iFQJ!sDoW~P+HH43X>oM~YUL95)>;^N3<;~e(OVmH3=Sj+QvSH`{n zU6gndOtLfY-FGtR1otpg7A+yi;YfMp6X`54SGZu_O@I)wq5drVMD&F}dew-UU2#|P z8^m5JroGg<A2)rIh-8uQ=_rdhImFc%y0o-d6ASB0WUQDqZN#T3EhC8iadFuR(XKl3 z2S<`qN5_PKH99wSpW*4<`D&;f<bd{caRc|N@584S^wBxa0l6d$zI8!V^%6&V_v#hH zPbBD!6FkCgjrfJQLp7Fyz>}GF#W2Nr@rB=JOY}UiFZhM{7_;ZTA2i^P@s6Dfu2sI$ zM8U8*$qi;Q1z(7OXp*J~R1=Fa#FRnvhmD3tt8zDE{@&a$PW<<Z{$J<viI*LuMl~dI zG#@+v9^QI+!T+$uUHi%<tgnw14$()@i4lN3CrpR*Yqw-4DIX|aXYx?_iOjV@^85YV z&J?6awpzMY_`FkaL>>ZOTNf3nXDPBANEQs<&vYt?IS3$1Zcj+~y^~=Fi3GtqL^UgD z_cl|~y(3BMN8CrpOZZ*-^>oIZ8=qr!PF68A2@&K6Fkf0tj1KIZ1b!heZV}{PGf!Nx z=h^Jtf@lB4$CFB%NcwqHm;ahFJp=sX1`6ptGQSHeD6uEdK540+ox>X6ZkU9!W3x&W zVsrWe7M8O?rWV;ek0Bamj6>xVB2M64BJm&k)t^W`^k#*uN=(=cIutI0T4llbP32RB z%DL;5(RE^Tac8h~0WEx9o)e<f`mURNe+x1N2Z+$tzIag-%;4!^(EYU=7w#l%acPXg za%*hbcj+`vS<VyvKGx6LMf;t_Yq9r7n89ZLP{i!~<{LEY`AtP3M%a&4vC2et8Q=l# zYQqH}{N7CII}SnuNxmqHRiH3`ruJ!JLB>HG4r+)odkI@&JCsyXH@QgE<Jm^+LjW$B z+zr}UB=(_vfsZ0KL@@IgUXPS`eejyj8)-{x>v_jp8R91CH%H6+?Z^}t3X$Dr@2&-? zk3CS=v0s$rj8^)vzNJ~Ho9xLeC1vi5%+BeoFc>mgtKG1Syii8|Y*H<XC4cvn4Gl-B z9q5(jN5&ihr-((Io_7Mld;9k((_r#EVH<xlL{V<q7P^#WK@K=dY2=5aNxB*f<4tp0 z=n9U}D;oHH7)<DM)wfqk4C_}SEpte*W{QFq>HK)fxQPW#xo3;C%cqR8+6qnbsGh9F z8l3=l3*>S}+X-vioq`Zb6`c7CN)}ozTrX>0UA^`1rKZLGw9|Y$n2x+|Rv2cJ`gtPu zAHWZ>p%b{T)oa?!+s-GNG8BkWfS*UlKmUZJ?iYCy#eImKOTnp<^cEzdFjyn)CD0b- z7ZIRbJuz@CFpI309Ire8>4x%oHd<cuOgfkY8ULhsup;(2Jz;l}*Li#u+1(#9W=?Q> z-cPLv&qgk#0Mz&PnUTpmn&?xcPyP3hf`C{O39>$ISVeZggY9;+;aTe#o_pmzN|A(y zWoOd=f+Uuq@EAx2Ic)Q18T2=9!$m<ukVz&~a!RMjo*J9bkPuP6-UdtjU|`E_;Ak+A z)H;!CBMiw49P9yDkj$mcTU=g1-kh#qB>jZj07ThlC^bl7DQMCrckz^s5yeGZL|>V- zpkfr7IS?@Z7J+QP&dlHxQ~Nv~CP#7046b*SWyFW8co9bq@QUi=kJ{Kn+immi#2%d; zv)mWh=b*CyTh*pW2;W6t6|&9rkUNNZ@Ixc+$0<$WX)yUX8Q;MYKxXoz$MTx*<#>vB zi5>r-%8lbbFPrr-sH9Et0{|elR!+4miV7l{7e}IvEBuJ3i<iQm=K<o?unpnHqsAZ9 zyId;T1J-hdJvWI^vp!jr==b;cT5qZPKAO4>TDnoP4!P?@pszy%95^Ul=^6DD`If^` zloU{NBTYkhe7jy@TOe>#i>kfZN|WG`p^Nag3G^3oL;MQvflDZ?&HT}evsm|twX7k< z`7{{2r1`KP`#t<8qHKu)2{WQ@pN%~N#GrWw{ovoLeEH`JrZ+qH>ms=sYE>zjeP>N> z>o%3YY|6yesVaxJ%DO9bi*<TwE3*UPm^3JMu9liNF>W#*Q{VifF?ZwGCi)PR@WB{_ z5YgJ6uA4O*^Zcm1rP=v%e)?Y*Vg!n&xuL-#%dv}VOo$vSI7n6?G9hM#MjX&Mq-{`a zN9DP%vZi+$u;}Pst<w)tf)Dp=bBzs!5+&%oicDNX*`lLv^SkWD@Z)7z7qw$y41Qx6 z#)TFiW+D)_kK<_ag@1GC)7zKxBK#&uBE8a#w%S;F-O9Nu_Uf|azZVD63>AxSf`lIl z<ZLy2*VH@_KVyg6-O~yD9YVoggMTp?3ZV;(bPr>>{&)aflpYc@D8xqg@w}a1Q6g+T zKU@&k6U|lb&~!UO{X2(+FE~621E~?+mB4U&CHRepz!v$uA4WRNZB}`<a4*};p}lMP zlgR;`dM+BKI~T8ie4dCM#}(|7x2gj`L!yy_Hbhfpaf$L5RH?5MXJfY=g|zYgSppMZ zN<_ux{O8AuCz2Yf-vy$&dZU`D$pGMhWxt*niz?V@JoK3RxhQfzt%Q-CJ-c0#?gd;M zTl`^K<+vB;chM-4bSQb~C{n8|F7@I{4Vq1RlU`1lIy8Ia?#pABde8TH`vKwEKuj)r zrWh{vB`H-7b^sb6fxXE%5nShrnuBe=Epg`JohN7T!Ms?FucE2S!9t2;mQyx_01vw( z3)^@o3ikv)yrIx(i=0fE93YWo<EewWhPVSKiw1Re9b4UWv=od~E;-Xuds**8>5*dx zt9x9w%?!6S-)0=lo$c<S_g{1)LHfsWBJE9JWcB&PRBJ$rBXLsWI#J#!&NCaZ$Um;l z$TJgJ%V8sod1ZHL!J&94TJa(<-?krK{26We{LoH|YSJCsX0ZL3013~PNKH4_3ppPn zOzN3r#0u~;A_Ek$rp36=zY$vfOsx2P@)eeu^OG?mhTuQ6mo}PA_hnZ^I6SaV$xEy8 zxXq%j*zSY;og!C;1R1K=G}u@pU_g&H`MZ@G=?W}t+9!MnrYul<w%wAAB?r+gqNkEz z{34oZRAQn?h1>BvhuE5)A%!)*RT27uD}gRlcQ9C1naB=KqhELc*l?jxB#SBYurcOd zwA4{XNp?;IOUV~x3D?TEtiQ38Zdp9upC9kMzQJulrg+6AW}`#Y(H1-WPLkV5lENKy zOY!gG&LWaSLar9gX7#n1H}}kSI6)4Wmx-%OZgdz#R0MRnds(}opz8=~G-ks^;Q;DI zQO*xz@M2q%T~mu%vTTK|ieE&qS4`qZOTkb@gEz5reU(5`ly36O7F+*OJ>~K_Rn`*2 z2zHUH%JX%G^es8&y3>GEKDe!5pRX4kSJG$YrAdfCU;Jd<=Q+@aISW;FAn;Hy1Nu5O z*P-nczH5XM>4w_Dq5I|g2L73;)NH--S{FRP1K^0lA%&C7p?ueWkh(tk4mqme9w`xJ z_<{MiPLk`0C2BFF-XNY{!vP-7)<oxvj>}`u{N@gJj^ynfxbzYW+#*MELNy7<(}vw_ zp<owwGEEY)oEVmT(r`ngn;3b_Z@$cMERjEnc^AAH^%5GY3u+XLvkj`Q1UrOz`iE}( zl?KU|-2uPJ$w}$AB|ljrUT3M%cwYQo2i~6~nm7N_Vo8YbU0L|gTx#s%rv2}h?@ugf zwepWRp|SW?(O;X>ID)ETJqw7P{|j{IFE}g-Cf-|hOa2xz{^)%*jQ*rSs=40Gu~zz( zeGYM)VUeR3x}N)yzV{UFCuJo&n<#52h1qN_Aq$WDMa{o-X*=AcY%9gaFtXCVW}v|p zWQ88ux64lX9A1tWJbw5OlpC7C))<LLrG^_4gu^`9&WyroUd>h9X*9u&49w^YC_w)i zaTj}xO?LyXjx5SVV;)?eoI;16Tdm-$G0RCQ`oLW}FUpaE428(!<L~~`C^y*Gsi+%L zIvC&v#_2<!Js692q!R0rJ?HeNk#iGdLQT+Fvni`(2k?+-!3Ivhlu_(ben|a%*&`QZ zIX*s9l1oriXp*xJN3Q>}0ZFdVi=S?y;!bM>LA_G%>a3wEcus}8vy(w?c|2Fd3X(Eq zA6<UDUM}Nqx+}>H+s@NEtp8W<`5`3FZ|Ucj3|*V8PZNJflz4rGfZ4TQDw+V^#M!ex zBl8Tpfrf28UvOxkq;DRjbb4MoejVEG+6sH>F`OumAWav3M>^JULDV2V;imud9C|sn z`M43<X8uA>fosWNm$1qqr~JngCvoU!sx(@mGg5=1*z5OO=BLKMj?1VCt#_C<C^J_F zV12*A7YZpQ0N)Hkooopy4ww!q*~)RCJn}8?Nu3D1et*oaJUIjbu<F~0GPo1fqHKCl zkz9RG(nZe?kZkKBsY`)B9Ns)P*$C^F($EXNNyKKp{RIz@>QJ!aGck>CQ8w{|M8-mH z;@kpmjTEo{y!IykXq(n>ppG@Nka%>GdUb~rp3>Y#AEpGmsi~>n=iOsxg*;O?+muBT zg-nxidL7h;{4aq2``KPV!%<3bwi3t9(gJ`rB8d~O1Ubl{@g65u!%ji?JVa{mhkhRZ zG5z#MIU=Vm5}YSLl+&h9j2AcMIuN71fB*z&Tbay--ty)pbEC-s-fxl}&p+Qj$@Nyl zc33RajzlbAQS-j$!oaPb++<#K_m?j3BP4U(h#2a(xR>~SS!|R`xY2AV!bnqkObw8r zfvj)5O~0={_HR<=MzU3A35A9iPQp9EFYJW)=n?B8;SiaKfEz|!DUgO=-tJR{ck5!T z@xw_l37TWs#P=17_&R2*^^Hu9PQ5yb5(qaDAY856p@srUMzjZ2Pp-W2@GlnsD+mAc zboN2RX(11HBny_)a54;p{4}1MouxqSF*)Y@^OAD5)dmYyCVMhYHOf<EJ`N%4v9{(b zRgU0U$OwLpo~D2z>VbNobRwlDZM9_7_Q95$YH~^*FAL*7-x(w7v4YczvhU&~$Lo_} zaVKLG7t|?1T5yejJt}LJGB#)q@YPJdgU~My7L?!Bl{ERxXmZ>>E-9MXgqDY5<6+nH zCfo4quVjhgq(1=?W`Uzi2jKmHAXs1`L9jU^p{7|1fN~fk6RkI~99mz4Lp?PzPHdH9 za?9chANB>g!HsQodERsD2H&<a>{SWs5rJ;~|2cHM8n`I^1gO<Cgd77C=`V=`X8X<h z8>G3fk<+8M3IcTDqFP$k#UpJ$rjy0*ZI%CYsgJd9k20nQA9BQqq5DhPud0to_0P%t z4ViwU2%Do1@4c%Kb{X>HC$cdX3M(+Fo_jvM&rx)gMwZ{k6u^1x*GJFh=5KD&b&j8C zwJ5qXcGQfKlQu2`2YTk{GM)N7BU=8c$6Yb({4(U$Bpaa4&u#CgL^M|*BD!Jeh)th? zDYOG_!$R#a!$-1Wo{1!Hc)jN&Cu)-4)TD~Vphf=ms{Lt%EcR$_bJI3dH&aElkL&;5 zZcwlj!y!pI?)~D|LMWmc`*8)iDDT^?fAPBcesf>r^<zokg`H9|0$^J&pQ51s4Y9(y zsO~Z@$<$4%jlkcvO#h`+B!T^*T%2+;wc>L)7a%YcJix7les+p}<!TP$Il4PuO#q^G zZqpkO^s>H)!?%4Kh3ByOo8k;u=61`O=)R!^a5ndy#jF(un1I=~3(+xcxW(E4ufQ!5 zdE;>oTp7M9E6I&5qTYN3R{j{qDKt2ch@++bN%oaPLOO220n*Y@IJ&RE;B(QCKb|Uq zjIG5O&^GxJN3N=_ehMu7*BtEH(3JDiNg&;^{{J8H5G=%A0(qGtN_dtihxiq?o(JG# zKle9NCZ|n^L3V&-lNL{hY2AeMvT$G{{$3oXlx^paF~v**s5zomNTIlzl<J#fR`dJJ zBG*;)R+T_h0goSK;A4;A-qP<+gUa<U%5t#q3)kOou4nDZv=G#Uf`r#0)_GlJ+KffB z^<)Ly+GN}9gPr}^zc{s51;)tlW)nJIjh6f!St7jBfQ=>^VxgF0LHl7*JR=y<Vm6&6 z0`f)Q8C)TW8X80#iLGlNFEtLDa~R*nIhLT~wc<603MUUs98*pl*ds`7^nCmYG!0@y z^g|agZyY;b26YSnrS<=H!MQmhj3p8Z^w)n4(!od30wW1ld=)?L^*?oqbZ%?!?jCv@ zD@2Qzn@9WFDJ`d5q;&tNl_?PPe6QD>q(o%vj4^6zEGdz8JWy_XBK%Di&MJ#4!?kc# ziv@*IW!YDx%v%5$mY1MMZQ%Z;4vt>FJ?mklzYe+AY9W>?1)$i_YSDAfC(qQP7_Ku$ zdpM^4g|!#wTH`6&3|f}J^bFtxq*77D1ZE)u)>AEh^cT1rBikm`Q|ZKg5cQaF5Z)_@ zWMCvxOhyQ~iqaT4b74~H%w5=BIC-u$S}N<I#74knX*`5e<tR#`kSlU>0#ILK|NH3r z-x;kZjf~lhJe-3|WNrx)r>&F(d8b||GjZLnL-*s<{CAx9E9wzk@<D_IPlZcJ<6pj_ zc5{rOzO&RZU`?SRDvZMqk0Oco1lu|IZ%s$Y%TkkPqqNJz!f_CjnBVQnxfT`>jcrI& zVGFp!!CR#AhA>lDx@p27KfnU5R^UQevFl@JR-uPT21&0J_%8X=VG0(a-}Mk)Ngx+z zaQ0Cz63?xPll!$@cQ*>i$Me0V{iR3=oux+vaIA-{XWAgM*$3<=N)_qlLt$3tp~4Pu zN3<c;cg)aOx_!>|%*udFPPvb40QAZ8*6IC=j!Q=OHsiG;km~dQ$>^?dQ9Ss}q;p|k z^5MF>hfO!zOaAKnKH1f~-(r2OwjQT5G~-e&?tiG@>>zZu$W<A5H3(3j8I^oByh@gn zP01OvROYm8r}ym_r_KBEEYh3tJSU?^V#+2;mP~!!4$gxR-UCb-2<(g5u!H(WLES22 zM8ej-jq@yxlz64qBA0kfrzTZiq#D!H7&Ac`-drm3k{v7XZJo$p=BoN9Kr|71BL2HN znh15@6eF_}(rB4gB9Pt!gJJ?)cOJ1`3WEZPf`0+iA*V2%&Agm5{BfrrRj3k=qGEo= ziGJ&U+7$n%fc=W~8?F51yMGlSt#dV)?cY}z+#eb{66@o|7B-hSmpcv+|3-$GQ8Gqg zL6PC)Stx=c<z9za-Ob~vOdx|`96wgn;#Kc#a$>UYqAqnCMGJSEbQB+Qf>=v|@B&Sb zmqd;W6$SZ4krc!>DD=pF&)|%<pe6@T2RAGCg4A(#6$!wQDK4}fRZe&Oc%Dn005kp` z05(I>N+3x6N~}kht=$4Zw~Zqi?F(N(xkgxcRm#PT;_av0<)KQ659ZeilZ>e+$M~l4 ztf_HpKkS+H$ayI9P17hNo6l{mVOp?)(oI%I`RL!w^#4Y;fftDZlHr1kSZ{o9r@xZD ziB2tX>b*iuswA<yY>Xd$5sBKgoke_u^+_SeA4ZO6fi!wf#NDI;9tT;R%(!Z!BIg18 zA~Icu`6*3$Y@Ie8WgJ8?M3w~VjNRTUVE{LADRUXvWRIva8m9I3)v0472@;H`@rZw| zfytLzC_RgY2tXC<^BZE3<BiI3=qSPD*HM`Y2lI2y&(<^d1DZ1G0}9B59{2c(pqTIB zL@@WX8!7?fwX5hPO0C!d70is((VJ`{6Ho7p^$l+tXWeF&OkH=%mNqu@gY$o@8xr-v z1pd$2{!c@S3Th~dTnX6NW6M}{E%j91?K+9K8u9FELBrM1t(4L)BCK7ljrW2YKyqJt z5r!0oS9sx-PC(BoZT^f&!?`%VZ>LX@jGV@dwU<QgX>0;#Vs`)~LioE}YBz*I3iFM0 zN-PZQ7zMj;VEwzLTsVQ{t>KwsB}5@+&P4`x4zipcQcyBbEE5W1VZB?sxyoJ2$n!y( z=PEXE!4X}5GEqpXtT93su!_Fi%z`$Ugu(DVJi!}Iqt?KGBAZWr&T@h&*j|WILeTjr z?yqI}|9g}hB%o9^ipI=F_Ifh)gp9A3z=0}6P6+!jUU);xLmY!=W{{Iz{NY*_M^6CN zQwBNIeJ7fCF;-H@wFJl3aXhEAL=wp)pm31GCzn8j^fAnhJ+^yAk$3x6TTl7oBpXHa z7aCVoq^tC2Pk;9I$mxYTAPNEkdut&i2#=(oU?AKfXvl7r?|-uZVkw==8W&`9No`4_ zkJ~-Cr>OfVxQD~`cfxB)GM5D?3GulAxa>aA^o5WaLOONB4jW-OtCjIAkXgquxEg5= zSU^-Zoa0y@xNVk%U;l(fR#sMbfjtM4nft-mdU4%??S=nurqcWG;cdf{Qmg_ALD9<$ zemm0}=y)6JL$6S&8#oGh{o6Te%ZiT|1|y53jeXjOSx2Cc8A_5f@V(gnQMWYNrd-a0 zmNJsPdE{9=i^`Pa31o(p$qhq^Ipz>8nj^|HaX}Ji4G)a-udq+VCqTUQK#`EIjP7yA z%oR?>M3dkBK@N}x+j9<X?48$rFKA%4Q<in)hq1Bzn<mgH>CtSL3{*hH0~-mT*XW)I zl<Nt%QdJMm_A@8ZS5?&nq}?nU&M2+d-B%>W0+GfiUem^B!_fCYV?PQ|8_^?+7|z0R zd3_y!$!#F=2>bsZ!=T0iJd}I}Ic_)$X`H)umhNy&yj_qZN6@Z)$pD{46f`ol@<38y zT#}-6%qU};X*|jM8x@z#<Atsx%8*@_YI1yW_q($8S&9lvD9G2L4-pV0Ql2ukVscEI zNe4S#EG=2Ce840msb$UyARq`Yc4hhh$a<@=IGd$wIJmpJ4esu)gS!QH_Yer~Zi5rt zAxLm1xVr=i8r*^gf`7yFzk5H~*MBr8bJE>+cU7%gwN_<fZ~%855tC?ykAXB^^~6>R z;qUebgm(yBf`PQ5k~$75&_lL9?r=MCc2?6#1Ukl4mKtS}{lm9ta_W{<DxdD0()zZ$ z$XlN)7pb(UXG^SrY`Im-Xl_A7)UA2JNH+(MN#SjYUSFf+vJ*w<2x|$$$t9-e9!Gx; zFA0$QQGx}3(k#c*fO>kFSu5*cRk?b<$6L^7j<CipQ(UdSm+imr8<>j74cVV+T!?E~ zJN3cAJYE45&#T?nV{%#aL!U&h2?oAPCPiK=6hIW&lkzE~dP`T)^K`lTSNH47`KwX0 zqpzNow)O~r6ZhPL4}3gfyd2Cvf1%_%0n?Gb7(*3@N{`Y5IiD3|euE9b;4y=q>mI+l z(PvokzSN4;twlP?2nt{|T=P!i#hD5kjGJdGkasaD@?vdiDf$o{283zSn|hU;$U_nB zSX1itE*zTN$dIam^_v8);k8x9I=9&Ta3feazqsaggeB_ZSz5gW?NG+=h*dzg97t-C zbmIPo)GU``rtO7ksx$^3L<^86Br(AyT}tI~o&l{b-NuuWg*eWWlbp<@rlwx~`uOcV z3E#}ln->(*$2HdoyX1IJRM(^P7GPpRTHns!n}+WLJ<;+`;p%4$t32vP1+!{yU6?Dw z-AXToJ*glm90AC8z>~g&lyiB>S)oTlHcZUveHfe;?v(>EAWVW|iF!2svo5|`@hDM? zRx)~e$N8VQr<1!^X|U`JIWS{za;P;<+e`Y(#GQO*ykUXDVXMdf{2Y!mXd{|nE;AF* zRY5pf0;=CFY_J&W!v$Kwu0_6YE3!x2ZkF1CYfcF8AYVT*WgG}*gkGoWMaH96UH<-o zgTj(I+2TdZIq@M(0r2J0Rh4{=GmI2?W3K$=Cj_wHQSclIlc}Uryi_qP3=O3gTSTsT z-*5P^DAatAjQS`;c7@Yz5JzVumVk4CnNKk2O{WlC09EfbSVs%~Z<X8QCEeo{ILhRq zEnR=pPxhkPeN)0Z+I6?_#h}+>xL`Nph(J*$8ne2t=Gqkq(po?iY5W@7A}^aj&l+5z zNeqAs*Gjx?)r}VO$v;MjoFS(2Fgb_tKJ0$9{J}`H-Bv?~ltpNX+TF@4p0O{&bg9WX zYbe(<P-E22F~8?hsV9K72!a#0%Qj$4H*!Z6T1~AO3R#UZk6F}4HAaIADnJX_Ai~}U zI=K|-^q<!3J>g*1Rz|p^@c1aI&zw?UKLX~zNpgfyv2~0~GRh63w2B6Q4x^<?aQSY0 zN+7B_Rh&uI(OB~SWEnU#i6Nr#;lqb|-+Q-;^70wCH-*J|Fa<{3Sm`u#=UO^0`7Ggc zw3qnbU(P$o6txM5sdwHtv$A{k#*bM~d&Vy%PmkYTJM2<3!rf5j-5q-)F?N(T*ss8) zwwa#+2%9-ki$)(paLRm^n#~7s;QfL&0ur{Y00ez?DIZN3VKLuCb@|=Ow~u&fIUt4` zh4+N|1(h6`vD>d&x??Uv5LDG067r~c_QhomX&(K_hSr7RpD_18O1PGLi+CfkFq5E> zM9^hBbZ$(<eB8Sq_cnKd%{=jgj9)Bnr5TG&e@VnDNf7ny@n*s7mK)Cb2^KR2z-RS} zl+<<dn%y7<MacY6aC~r4I2N!GeU1~7E9(#`%E=RcdXuL4)VAY~maSg}hD4NpwK`9O zwkQ11{!=^r(*fg!R<ts0Q<UMNMmh-Y1QR@VYhNE~_hO8n3WaWFBx@-(WU{?b_eg7o zW7gaaKwOPq)yS)oVxL#KtKk?%6kK?+0|B!zjkEZq1yB+G69L%McR=CLUKsrMTqwcr zN(HQ34LjtofFbfl1#3*F?s<(p7h-52L&-bd&FiU5=5dxB*1Zn|qhG9oIe2UG)dg9$ zwi~HT(1My=#X?3MUChfg)CH}Z8(9SLLMy=VSRI9!=Z-Ll<uqCI6@qUoke7E(Z|sGS zc>KK&jKyad?cl(W1^DCNTp&>_-joYS8ayMf0y|KZhHi*=?}X=)K&*|@*_utZv*6#D zP#QckcV0|dSUpmLbB}74v;XzytITO%8EyrD0?#wTo^W`1wz=zU=aAXwTcu%SZ4*RC zWb8xySfQ2XYG&aIG;VkXh%bN%>;>`)H5`;L3!yCGbu!>X!>)l!v|iNi|7=*&2#B5$ znYolytXCEOfWufqD@>$c+%^})pY&jsnx*C_8D`*0Lc@_`M4)dMCc$%AN{}9bA!(9d z9iree1-Mql3z?5w$w0FqYNU$DHKgUXIp82ZAOEPp0S8*xqyVw>`$;)ct|Av}=ZNWk z4gy@~7InC6NNN_-<@K>FVR3&|mWkHa*SFZ{^nN4qj9N8FG;u8rXdzG@JK_K677oB_ zdNFePtE6r~XVV+p#Y@)W)9iuV%jl0l8wa!2$ia+)<hS9OgE-&o&znq)+Ep_aw?P@U z1Wd;31VwpZ0D=(<X{?WIfLI2c>4F?q>ZQMZa#x>tBP>_xH2{)F%U!Hf3t<D1U<{}g z{tOz4CEA#UUCJj`F4jqM|2)vr8kx&t$jplEpNPMqqY(~ky}@QIrsdZY&}b;;6wz`6 z_YNXvNK}50;5Z8z<1#rWYf=jpQv`5t6!j<t<)r^+qlDKbdcR-dhe}Fy6vR_ux=m>- z{3>C)`BaY$=874m!(E2SAXt6mw@C(#5-zK0Q}|&55E=<e(>lqb4dfCp_9)1K+gcK7 z1D+_6>KFEw8Sp2V%5+SENpDoSH|5UXMzZx%I$J0xC?NTg8}FFX1Sgfy_D=-=0L}lT zJzEp9fmg^)(rW5bQzm3yQSat;iAOOl$w1Vg(o{yBF>pdq#(}YycZr<>sM{KPYMt!y zGk1TyJ6{5_<^{ZX$K{FmwQ~q*Uo3rlX~HaN={j@d@VPxzU)Ss@nWze-&1b9R4ov9? zn08u8@J=ijuM8RyEEA$q$oI>D#ajo+34KA+4`&Jba&Gb2Lp)|7)gjG+n8p(lLOp(D zWxQ<kYSF!<o-~<~LYPDw56J`iT@VpCAYQRu!ApgGq?{^&w<4~sNrg!_rtcsN&=tt@ zllUQk;`TmQl<9s=gkFIsm@c(oy<BHkvey%if2iil`jmZUEB+31y%|o)?&hP*BkBgy z6p8aUwJP1_>uFJArC;&H{Du0(!(;&lZ{rSUHifoDKX$5>{{|_&o+-sP*ff>5yItWa z&3_EBxAIKR&8vtS&M_q^xbXGOJQaFNCB>IE*h}pc+D0@~14cRGwNqTP^TL9Oy3`Zt zs*Sqzkwm?(EO2(gY70d;k6?xw%e2U2mG7xJSu(Xk8Xf+^KAY|awhKXO2yoW<SEt6W z*LCL-Tyo`*{X-`7V*boVE)z)I<50d~WnN-#kHM^B+7RzVQ1u*11QDFv%rhwUA<eDr zbaK4dRi;VoL57?<_#&3$<f)iO^Exp?O<e2;fl@xM`>tSA3YWxZF7UvuMSmJz$+re1 z^NDEnpgJIoS3BdmbE=yn{F>o_E=S`>&}n3KWGx01Z|gB-5-CC7VCzO+HaVYM#kck% zQJGv=v!Nep!p2o(mjd9xmI`3c4Kmht>bx8h*VilE!OOC^Do*L%sUG`#ANeFP@?#}3 zhj#I`lU>&iR)ZbM9F-1G7wD3hGOdozoC7)xJZ7ao2~4v~PX+qg@S|PC9<p~Rb2)9r zCT}9r!7_~W$g3F+De{Z_y#3*v{w8(8(CD{IMV18S!q;*k(9HAj@*)ju-`w7geeAv_ zSr-8_{kZeIz$$rmUM9(MFTqdjaphIsPiptG2?0!kyiOonm(8xmb_raG<b~i&Ge&Z$ zetlFfI@oC&a_OU^x%5oRt~$Gn<z5swA*2$?^r~)8ZekwAWGVh=w7WTdUwb+ughhk_ z`|7mUY)VK6#_+8g_-2(Cyfc#FV40}ixW}h)?eQ8}vJ@&8cf;`8GV6}uMg_}F(h7zz zNw;P>&HP;?u*u^REumJE?vPqpzqY3vvwA1v=jsCaWMse|UBN$=<o&LwNzPJkzh14F z=KOhLGH6w8c3Q98|I#?SCni(61LcG?kE&&v;JNbr>F?Mng~8S~B!{pR%c+i~<WuE1 zCWXAfG#j-DwxXeW^8oTalq3UzHz{WftkwRW)6e7cBNfJ<dm~1334BIb*7pE8<3D|P zDewG_HS#dqnVjtG2sK@C6N5<;Tpci*lsi1n5a+h=Cr`HAl<|~P8_j=cx1CwHjLg3) zfC2pq9&^h?W1a(eRrE*F;6#egZ&guH-|qrO`@jiCfx6ozwwyXHDiP`^O!{Q%HA^02 z=4zu09nzu(Osw@bUz(~us>NZF*!Z;&4P>V?q=qaPVv~eTI)0<*?-?2`R^8b9s<~Ab zTN@-!uHuRFBt-NQ#cn96EKZK=FHqWiyt<sCjm+mr&FrW!Xol!yjoi%%dWDxC$$RL? z#ZIwXooPNYG3SxQEB$O3X_pZU)Hre(GM?;``giwSN-4zn!xTJ(FfEB-hw>Ejg)D68 zUp+iL%2Nr~!(RuDpTd-rB*u9<aF=K#*#kOAcf7jyK5#6FsAaVprbytk4g}9|Zyt!g zdfPfX>tG2~cFr9&B04FWhwbn~hf5u0yH6#7r=S@hHB2*&|NM>-jTX!QD%7=);eCPk z4YXQARo~iffNN$O2um*>_in)OQ@tQarMK&2(G5+R9GZcjH9sr@GGpFxT4u~=i^cb8 z!0}i@VDYGC?>BgsF>ItJJaOfBXHwjEJG4?gS?8e$%n)L%!kD}A_~y8^<)HS=>wK+B zI2=SdCB(B#deW5o?i_VBzISsA2)tV}`Ck_k#UbwUo0+qPx6;yIgr;|yv3Er-VyY1q zX0-i%zW-smTw!4B2aGJ2;zk*(wKg{zT;t>YZ{CIntthg++6obc*rMW@5s1MwCfGb9 z5$BKo0?ucpMJ}UMM#@B=ZBr96T3{5$n_!Yts|;{O*FJzUIXP>*FMZCtbo?^Tf3&E) z5p>76mkf%eB6mj_9KyDw5un3_>@wvlZ8YRqak6MdU(K=oYpx@O?gq@=UK9KQdmWx5 zeOdCEaLnqQ@R-9DGai+AgvBC!c87hwa>5lyF83&$9nc37eSF0h=@TM8m7Pa9j27Pu z=|N1xI-YzGk=vb+Txh*p0S<RmsKMSnQ{hNadA!8X^1QZm6Y~!0qhgf?tGFzwlhuxM z^YKv@;yxz2w6=|20xfV-6$WDuC#FWg2EmOOzDP1VPH+1}K6Wy&&35q7b1-*Pih(Ht zYsKTveZ+L=2TE;aRMl*L_tN<Lo$EWWhL`%Ak>#PO&(w_`VxETJ^#8!Cv2f6eu*IDc znQ=j#+ZK>}g@^aelkP`apEZhS8g9Wap`c!)O_D&Xez$L14cL(dN)Ky^J2UFuwGM5L zRwLZJ1jwO*SnSbp2i72`d;k8Me-|qG>+|NTUqxl*T%T+vDeIJ<_5d{BzBsGl0*%^o zjAR2;5_-Kup2PZ8=i0~X0J*1o>)q%fecQgRNBIoH67rvO_Ijv<#kWEO`wN;!jCu6y zGn5~anM_^ec@-P1STdMmShK0VPJ-fU9mI0+n?l=C5(T+{E)*zr9gzq?dR1BuO2216 zP*2;-*|YAX|I?qu0A%@MT~Jasc|QLvZU#C2oeaov2CiCFN87E!4!r=NNb?wG^b4e0 z7M%k+UZFqA6**$H$hR##u}7VOvK{`w<KzcaVj|jN=oB62krpgk^yX4VBUvl7CHuK0 zYj77QWNN(z<8yI;s`}odrrWkso@fm`Yx1lvp|RBFeo%SaTvjG4Dshonk7}}}HG#DI zZ*R6%5PAd-Urw$y5npX+yS=01G1M!=V8Fe|dxeK{>$X5LVnIEweh!?Q6a7w@Sza!8 zXYM*NJO>TN;C)dXyh%w_PVX!RL=jRVns%}c<D{mikAtQDzqmK+Lc{?s`>K$k7>BRv zMqGtp?)Z(>gI9?&fH>Ql6sSsbo)f7JdzaiC%u9^bN5#t6NPH;+yDrMO3bJ(u@qjFH zMU}83Fd&Bn(IL7{`xt);Dm(WR^S^Y#8*07Dzs+{R@|G+TbA+J<Py-7!l|Y)Y^TN=J zt|{O3<k8APdoDBf5H5Brjw|0+AUiLF0>lDO9%9^-nV9FzGp;LVqNHqm0LnPx*!43k zzkfQ7@`lhQ9fDovhxX39uXsUzB?_2b9vAUcUaF@-^=4PdcIh5uq8V1U1`!2hcz-T5 z>=k6`ksAm1Vi&A}hY!Z52$pcJ`}qG`-1M9vLbyRDkH;SB5)bR<DSo{%Aane2Wo?v_ zS{}RIcS2y>el^Cp2OgELo$=0w+5fE{@~OofB7;E5k1j<ilS5i~MQ>jwI(CHs9ajYf zv$woF5Gx#*4B4YegszCV>W+>TNy<n50e>kaSnNl{eXM#b>12(ZHEM|KuhX-n7w}&q z>|!Oy<c#azueuBFrmmk@o<JzdA;zhTa-qS%e|NPhP~8m#^e)Fsd=UFF5+jyhwbf0k z1??qx9Nf%oLh&IgWZ-+R%Hx8b^?0!b2@U8hxzXP{uo>e{0w<P<k!{5x;GAM~|K#E~ z1To^BII?4>W4}WE>wO4i&H`WX$WG^08d_syk$&5}M_rL{<L#5{q_rJ*>i>aQMli;P z)-@~o=gQv*{6!W<erI2pP_IRL^5nuU(U|DkzM1zj`}pQ<+kTTx{BVItW9XX=gzwW1 z8EYG==*kHhYmO_@3V8CHg98_Yr4OR3Q^l3b^_uwEY6YRE>W{Gb)ik8?8!nS>{*J7T zKc4TViabSxw+ow5IdbNpZe8NmfGI<2zb9H+NSi-@EEK;DnOTM)efl9NPB1U&431Z# z|6Q==VefBOk(wALiQs`bQ#d50b4V0*^78A*h*{}C<{(%^{m{4pc5_|Jx+xk)>O5Om z>dGOhUUH#)!Oo7cuc@QAa)oGidVJ3L4CR47DBnCh;2OsAQ58v4O-oFB{mSn`jMVSW zHjt<A^S+fP?YWyPxTr9GBDBsy-l?9)&uh9=|NDy~2r4%)Ph(9nRHjj#+Ma=`iPMmp z=G-uKQ}=NEu}cdEWZZgT@J3Eo8h(2u*A{xCSik26G7W%%@kLpF#*vteWLTp}m?-TG z7&BtL_#!V<_pQX<Sq(e{+~Ih-q97MyMiXKn*;K@e7UF6Nmqjn%5TL}{pYD%Uk}*qO zC{JYWX+9Fet-Pg@K1+vNSd}vCFarO8bph~D3q>-QM@s-VEKaN-b6*#mqr!HJ5Yh(N z5^9K66#MQx4%!J~&8QWQ<JsoNSr<rnhQ4j%lTD0RG@HFPqSZ$)hJ5aAa=}CF-f~Rf z8kCK24QuBup>1cQ1V@gI^%|M@d$?N<kG0+~X0p(&pxtKyBd9z)5#y)8o`V?6J@-Ms z%2+a=Q}#G>0RcrY>szD4=u?`-mis?Lfd4_Df-ZvtF{t7tIcmiC_jSHKq&jSNKerAR z6HBcOS@7mgJN`Jxay7^hz02gq16ArZSXE?_kPLy9Cspk1?G<d}eYTT@GAy=r#ZkW& zejO5H25F^)ZMou(AP$?aSucZU0Y7DLiFu$FX7M-@&K*(Y&{kx?{RZkNKpIUwpig5+ zJ!jD}=A;<G59N@nw&}`@v9&o+Ae3!dx_XcQP9MJ-7yq8`Pq|m%XoS2I=MX3YRL!qI z9D_Kil4HZfiMpCp6VG2j28^^)wxN}Yx9|OE8Ebz0t{`0re7G{aa7quuAXWMWX+~76 zT#gH5`-a)y@p3`amhaZRVA`3rC1M8eEJ%{<$ptEo8ahf47H!^#awelXe0YQ+`x96h zr}qR_IMWq*+D1EZAF`gzop;seW=;FI+uezZ5jjS?i@Xb;;%?-%9fk!0PzkCnd)2_~ z5O%^|?@6rKKHMA~oBVn>snwCySzO#ApwMBD!=CT{o@hZcG1IMmP3h6yV*)+eT>W*; zI*32eZoU13JV>reyVj^$f^2?Pn70jOL0)}nj&f1MYGgzBb1|VZUcM>_HDmJw?gMng z-UthNiG)(M#qk)mUQRM^=RJp>_oRA-ouau2AP_RMO*QbIlnYHfbBkN)>?<r-aTF1g z3%5V*2kFqepnQmEn*gmpb<pJUi_FOYoo0nkpSBmj)@qC)p5?dAAX9o{ii*2mj=#Gt zusrIQoKan3`p~2_NBl*-Z_-?`Y;wZYR{m>i0{(ALJknk6VOKVg1qlTB0~EXg0MS@{ zY4ZGT^*&_x9e_xJg`aj>^^Lgxg>$@eD8$;b#VrFyIM>REvG$N@gF}z#vGk1AtiSp> zUH{n~P1bVv=tto#UwofJeCefG^OL`pyZoadZZM#%zFs{lq3x_8#?=vqhTm+EzHzo_ zeUf*xim?1kZMXi$ZF7q)#F-F?!pkhN^eCB{vs$V7%u7#y!K0k~Y$e;_=r}3I?@XP} zJ_*;RfCI(0?I)N4>T}JnKA)1rM-v-I{|Hf6=mtUKi6~IxY+z#oHH<OJu7X^$(|#aY z6d@KVM26ic>U>Sv`9tmVa(a1M4YWZZtsr2&1?l4}1~cwwzEU)T$<yVT)=iV5tOG#b zQ-}a!(W(pDPxxHv{V$49*4J)pXd&x9&7!&AJ3ro6=?$CO4_$)22-CWJ?v6P}?%!3h z$Rs)h2rZ6||NJW<QGuo#P9#%}FNp2)n}2YrnvIgstf_OPQf!_Ul8b-2Kzmhfl5N!e zQc=OrfYHE_eb`RxBV<b>%4sz*b1C&UH|GGJ#+)v58R{AP(F`GxfGG-2wRgcDA0RLs zQ7#)*p;49wEmrW^DVAj$@5L5rf25xGo0|XAlSVzszIUdk{_TyG<#iIvQIC-9??nPV z|0&A*5TZ?Hg(*Y2y$_b?AbNBvw0ERMWkP|*fuY1uYLsYZ{F*$dFcy32C6W0BjTbMR z?eH@iQ15eB3%)x3%;4gKbIS=S>oD?SJq7YAw0{GWIs^$Zb5U&*%Fysf(8+j;Q4Vp2 z>U!rXhFjSgc1Kr#1^tQwd~*5iWgNSN?zg2UBcgMPd<r!%mdf~n!<v*zPvBibBA5hQ za-YIPlHl`q*Uv<V96ePfmUVf7W|)y|TH~Jd3O(e^{qwyl?5Eeq&DzzXH^Ku)#3jv1 zrh%nBBivn^uE0KT_PcSK30Y`&(yZT|=YHqOV3l4mQr`=4oVl#5ELe8#dP&@xh6WA3 z?LFRa_e$GR8F`Ou2fN^MFG`aIJw;6_1tB?FJ7wIG*ML>SYBJGh+v@33mMq<nwTtfk zm25uqyQnMyy_!#tIBpvy*5=5VQriGnYjJF=y$mQ?{1Prjtd2l(SBrUc(`C<8=1Zm+ zd{id?sjnDfKJ}BccB@vsaWTy%?f|g}6aSU;%KkY>to9HW7_?i-27XMF?D@^SWGOw^ zo$q29VqdkALr=?7cd3dezvz&g?tk#0ogueNK2bpzo$~h<JrR!kybO<dx$Qo9a51OA zy4WO~>;W@XON(6lTb#^V)ywriF#|jZ5KLtvHNXYjg$FRKwU`PGf1#Y$iyY%8_7{WG zezTbglP6YYAMlMBQ=N6sOt-DWC!3s}%Q+U9QlwA0{MmTvGyZ;qa$5AY^JxoClum1b zVS+nz`>i1~0FI{JFTZQY_tK4Pyi-_ecEkHPgh3R}iJy@b?{STMlYB24@{*j_++qwO z#P41H#I_||scRV1$1(o~G01-M>gHq?H!*@!-P)oE_jX&@m0#M?L1!_&__R(QGbjpV z0-}wgI4>NJxn->MmKj0-5R%8NIIHIf>_IiY{9KAI+cRkO#YUv%(v*+GT?HTE&*A(r z#JH}1GE5|+pL__8B!{3H_9iFwO~Y@UJV@9Ei`eNj2#V~+Zq}Jccyb91{r|cdbVZ5e zFl0keafzw3yLhAtu*o5Xm%D%k(&v@D=gg<|&F35@qfXsD%F;UD)@JuMN2GaO0R^J2 z4VUIc*N_~!{o6QaU&%Ka*HNABD;!Iw1(wC7CHo+`L@)(O<bF8dN!EL*V}m;2X*i&Y zl%^1;G1$}t!O{}PE(9e5r<VdcN1`V~d5&BOf}oIGsUWd}S?sy=r*nSt*JZ5Q%!p$m z<?IEGSY*foHkDxPLx>QbP)LNwUc3+kc9aG|MfT6RO!p3OYrGbw+6WwRnADi$$Xigp z?;fuC(My=JxT>wZd^-z2j*7uR_OX8zWpCl5aRGCr1<vuiq@BXw`=7usyDr}jROO_v z{!62o0zlJU|7fI{{iJ49kV?3ROQrnuZbEFT$1&Odv>%LNy-BI=;oc;RDVt?eX5HC1 z(dv1<FDEqb^}i`18{J6|t+^&sD;f~rL#}f1_HOe%QZQCe_W=kArQ=wZI10u)!umg! z+B?}n&<Q60QT5<)&6MCeLbo1@a+eZGD94Va$}%d7f9ziqiY0?ycCz3Q7qm0Clfv8q zVY>2d_4HB>(d@BRRHZ0EBG{$>GUJ_K8F#VXA}uVFL=UBGRN$||Vr!fCp+#%pDt$** zZ!oM<t)c?_^VE6Qb*`nv3<O`EuHu~O(ef%46$Bx?f1@5)dx12lJOmb#v_ZM()a)tP zb_54MBRo6EwNb9)XEft({Wyz;Jy=>3lWGT#);Kx|SOJJqoYo}+qBF{+4}hhf)y)R{ zv={J6S|+7NbPKgM8s!VBs!HN9iy?#)W{ILZ4GsxHb`-;laJ~w8@sFp2<2)`zqx3RY z1@>Y-SNu*o^aMzgDcKB>P(EY*H?9Bx2?Sk9g3h$T25)IOLmuQvy`Tp-jS@^xlA0Li zYTXw-z4(6fL3?rS_U2{;EK#G76K$U~6^eT+@ZTE6niMj{cmyhzC=q`4VWKr;vR^)4 zELS`ZL+O}rBQhw|7Tl@IHfNeucNe^Nv4*iQ)ngB@=a|@!Hkp`anBY?|$Ej<=DCI*y zqt<7-QJ00pdb)C$qdW$&wJ}jbIom*t@9F|zv7$dj3=&}X>dL_G?QV$Sqs|iY{b*5! zgES>_2@3)O*ED+jCFkX1l_2{^aT(dsw6SO~!$%G4$XbAej<MnaTk`xi%z~&*3IRBz z^#HE;R<fhLi$#jgsae!6fy>tT?Q7YVwDB}%jbVCXq7m!aH!}Z!SGa=%F;8CSJA@am z-|O-!N%oNF3&uy)-K3_(NKMy54pu}G2+Hus1-|Trmsc1xvZ=|8aLM@VVuTmqkgu2# zYA-WPdi3JG24c>ltL#}N5@i{&Ltk%*jg{nov4d1EqcBy4o~A1JiAgOlJ|#JIv#us3 z_BnBBXR>wx|A!6bhG_4zgjsA_2!SD)(lOgdkcC(ZW-41-(LId{%IfR(<2e=^{TimJ zAX+<|R}v@d#eD&6x-Pipsknv}(RrJm`!6jOKLK9qKA2v$T(};si>s_?c;npnK#;@! zJ5zO^Dylet(miq<+4w{7I5f*|x=87$IGpIzINXdMG8wVI*_n6r`1i%d)15ki@e_dP zE9Te-F@HW57@ipP)a3SQE^-r9GHe$oi2E(YVjj#;ZcdAZe6Ki@-Ta>AA~J%MiH|af zK|TCA&7>ZZ?O>%)`k&c)#Y5TRF-FK0?5E>pC5e@T>dax#r#i067`#dhIiQ1FqXh4! zX8KEQ<~f3mR^Qw|Pct}tdF(77H~sF^z>*ktBGXI%zA3~($<jS?7@}8%v)iq9^ML2k zyr-zOPbbx8?iC;*f=%*|TlbQpu<xHn(@cx!)P5IMvUApPGGpw-k?UEu@;HK$N(yig zrXVN;qHVFGF!6A*w1`RZttB2TK2gvRU@uslXUHaT<(q^|UFNXM2Hrs;Bs8};HJ|_k z#8bsUUI{bQUhLYaDwjCA?uleJ9yMrFL~iPbzd$~(CkJzJ2$4v_{6Q^VT-=$Minm{X z3dtjTT3?Jvq269@pEj@?<BRZJ==mNNL^N_zr2X%qslaFWn%Q4LV-|x=MwNLSmh(yL zjuLzSgk7SPQblZ;Wzp^TK3`&LjunIRx?t&+1Z`C+#aZ*=HLKht(O*ZwCz^{3^8B6q zYT;AGAW$!{0NWgrIu#}**Bq%c!u6aGlqmu2GEVD}DHHlub!aI?6woxJI+_RxsT{+A z<cbwy(zN^CoMas3x$xI)N(3}8cTyW8_tXskLML@{luGnDli1t42)n^VZVYRSr@j`? z=pvC8w!yTVJW?B#Kg_^^>DV``7TA)WU7VRS0oFI={`kn}n#H=e@^1+b9w2srj>W?d z`1&mRJTJOv8=S#ziBBaV6VH@0%G=CSFYVOp2x6@97HXe%WT7H}T^^J(Dv`4AYBOm& z{28-X&&ZPAY&*Yu{G}#M8VUCpLkm0mD-%Et$~%XxjTYY!dL&BBcv&7Qh_`-y!ZY+i zGCZhx7iAibHv9u&^7wag%Z~m1Jh|o~$!LBdI`53IJ`E!bG$m2oaDXCrW<R_r<EQGR zCsVkd_J$(<^Umu=^L!$gPwfp;)_~e`@4p-OF74=S)QFZu;Fr#|6V_7XM@v%@8I?2x zRxq3Eq{&rc31<NOCv;I<=f_%05`)X8UA75#ohn@l(U;4FFw#zuhuMTmg&sQH{)z7@ zpH1Ksm%px$<~2TxdzCvfh@GUc?gM7m8K>8M@;th)C^37W(WEFpN8CnUv!tpy!eFV! zm-XKx*c8Y5E3x4lX&Hb3p70(8qt*ip3$^lx82|P<z;njt&~%%bnItW3s=4OmqubqK zbo3l%1C6C>W&)TD3bJ$9)ViK)S3b-q>{LJ|uJsuA0>pS6uEeVP+7dJWUs4h#fvbnY zf$LrZs0S#(3P?4%TaS^VmKRMo;RtH+2E~km*-I$D?j%*}9hYRs>GWz^_22#V`qn+` z;7TLK?gBh5k<y)=Lh0B4_YHQ9eP`KzC~M@7Im}1J&jb6p{+nwM9R-Jz7zcK0GSkKs zMN++xG9F-bK6SQY-#pbk%<;3g%jeV^7g&m(ed4*|wY>-^M>|ZS-%x1P=tET0oF2TJ zF-NJ0>fxauqFOt>&Ydmxl+Keh2Pu=r><$yQ4nvG7%KfFY%tW*KU3}*W(ElJa={L#^ z1Js0{m(3Gw4U2O62~?G8ga3^O+1v0L-o(NiO)V|yTyivzvX=fst_6@`*D^9qQbKte zMK18cIp+2fa!NSE9_~UPxn7!j1i^%O9JWARh%e|c#^&k&-xi7mnkP6IsH+-XN9$S$ zji`uh((buV<Sn>M@vOVWFx~IcZo}8gbIWzA9NLM*hsx&Jcv70MwZ?kBE`9$l@9y5< z2@m%8J=~J&KKM6Q#rN>Z2G$EV$r?DXHUhh^Qfo)PSHIr_yZY(7QAyuoWJpC^O@nKt zJu0&MNG>ieIvtaCC^*y+aP`deW)13Lk}c4rM8kR63HG=ee@nv*IlC^Smmp^|k^s0_ zsSWbWs|a)Uwo{irHTu13egl?~K!Z^|xJeE6kC@2=SoF`qffVwfz_fA<qJ)iGV~*de zC&jk+Fn=uGB@6Pos4jV3MC*h$N1?$W%uAtmzUrZgJZY3FCNaNn9(iNgfjI~1X=!Ou z2HdP2|L%EbJi2NdvKxx!llS%hkwyJ0xYQ-z{4>OBF&t0Aa4yv*W^e!H=|1nZ?F|Jb z3&pf70w&XpK5oAHPoBIvrJSyJ=rAxaq-Yv~VVWzj&a@%8?_Y&ki=WcV_HoEV5wwDb zN-YDO8WX_@7nC2TmPauuZ+%WE>n`{ZasU{}W<)sKoKJ^Q3vS_Uy`K_mNI5<NJ$`#e zo4db~@xmS^7s)83W?RB+PRunTqTvxYv%l`Pju0nW=Xc*f>{njA0`tK7`~T-z&p?My zBvyOjj6+k}E~j`n2zas11e<b_TO#m7Oz!dN0Oo)6B@E%(gv&A#W&NDYV3!2<*=6p* z@>sN+uP=9dm0xN=iZn$)6}$v|4G>of{ECP;_aq2n=L8}A-MxJ1X<B;vm#t}@QXl8z znATD|dek$uBMLFiAT;O^waR++Yq@PN#5*Ziw8?ncrI7~SSIw)OoC~}3!If=fAcZ(# zUoQ=|O*G1}>Ft}z6tf@GpYzuj=W3++Wp}d^1T7$I)nCWMf=)hbO0H&>za~K`IXN96 z`eaHXS`2p~$)8B`p=I6kb15fjPr{H;!cNk!)*aOQ?=9UWq;+rL!`R1fkA~j!pErtE zi|IZ_I=z4C*Gr%WngtaF=LX5C7G3sNWaM#vhYzGCSXorU+%#$53Ib7}1}u;d@&~b{ zUt~jmXXadGGiF-B#Zi>5*wTSjBz{~tYXRPUX9o2N$=f->X<;8&W*wRy`l&2(Ty8a7 z3}C6)!1ehl;Q7fE{=g!EWBvB;N)&ye6>G|3`@$X#G|X?(S~{hft?;c;3BlbT%l>c_ zaA%?xS$_Ht*k(nc`?jf;o-Xg@rfjeDvlF3f;7~T8E?f;_T9-CV91V*&=qpNFp*hTl zF;zQlhd^wYH5!AEgK`-J+5xtWa@S)`pr(!jn&M?N{>K5IBK926T7mFYU#)Y5tRNo* zYtOfC5CD_;xP->ZL>8m#90;lk*=_~+o0@+0NaJ~UQe0d08U2gjqbSj{i<NAt%R9!h z=4@}Dto22^V$B+>Z!QE3D4y)%@*SHI=Bl8~<$T<re=~z#3|W7DFn(14tMNRDubCFJ z5#a%%QaQ;Tv*+Zrmaj>`5i>*?d%;yQBQcA*3orizgR=uD^B|YDtAgVw*xp4wUy7Y| z@nY#>pf-U1*~e1><5DOhi;g&J#+2@;U<WqFeE9OTVH&kEkA%voS(q;9{J+^WI0~`J zz^n4G-)}_s@UeKbUx2>`t;$PwA%=cpAurX##g>*9opSLvbCNyh*IVZjOi4Bo1hnA= zvADD~&V9hBVg!7yW5boCIJb+Ruq%3G^S0P$&}rZ=)e|U4Y1FX&?_{M>?)7X;9%qJu zB*!J^{w)^vgvAlS#0*qIb^M5hZ}uGy-=3G$C;BWq1^mQ}%>8+b5^E{&jlNeX=7|{Q zAy|!?XS3SA8zzq*F3dr?`=5yjw(sy62K`N=3^c<o4w&nn#%`n3)JOz&3H2*g?MMOO zQRv+_lGGa+O;cwp?|#C1ch$ajkwKbUgGz6h9gk5@jYaK3*YpS3=onb}IV2E7-jz~c zuw#&7Oze_zico;2aME@#cDk4jR1u=*CmyijrdJp!M#Y*GxoOA)p4a%zki)dNx=x&1 zG2ea-D7+JzMCBKKC)~>RRigkg%eGZYFx%94M&+L|?*GgDO+wKl#~9X1IR<clX$*OT z6{j`awtDzr?UMa3LdXvB0s4!+zufb{A_#@wt<pS0qia^;D|A;7&@3ZRNkGH~{0;Rq z@8T`OgwJPX#rV;hWFYPc)ZhJf#~Xl|4#&PkPvXN%MmQP*rgvWFfXb_NXi@oXK%kK_ z%*t{qu)J>gYqw-{mtH+QI$c%xuE?zCS;0YrSOSYe8WVj|A=o-yT`;|1Ix49&N?V7u z_TS5x-3DLIgg17V;@pZqTW~4?hx$dQR=Z_WZN=(fD(C90d%i!N$C~%BQ1%A5(Z{Jp zj{&LT)-sZc!R+=5!np3qr7ArtfFkJ>6EvT8q!k#9hQ~(Oce9XR8wv^LK9IyL4=|IS zu&tUWHgz*yOS0pM_<*~b;smad`F)ZmI$Tmc20@TIC?L2fGaj6gr-Ij~It$)jB*aJ_ z0#G~70k>;*`XUS(^?@-5tX4Ey0_Rx|K|80F=u=-`k8)^GrOk;hUtJZy^VindQ>I3- zf8=%klZ5pEDNWpzQlQzVb~D=B1=_a5i9+4US3KAh$L~Si7h$X;b0rE2I`!^~xAY|V z1##ds?9Cg*7wq$+8UE*YZGhonS4@7a_Mj}h%5)lhVgmF8)fVaU_vS^(8)?}hewK>` z*kEkd(gg@8EWGV%7F2hE`Y%(zNHdm8sExFl55Aq<Q5(+#y7*+DS15q6wul|gBm2g$ z@<8?MYsN6AUT?A_r}AW%w20jhv=Sp6ICQUPlWkUw_sBfM<X<PAj{Cs#KnHzmGr35= z=5bm{b_6~-AV;63|NYr*mBXtlv$ugQ*&7ncT^)l^32NH*3Afi0V_VE`yoS++nw^JR z<M(avV+TG>$j#lJ{jhus=NDZUeMt2mPQE9V=N<4L!xJaiTomAYu>}{Z{RsWRrpjD_ zTk&oY%e_}4kUNs|J5J0rh{vn_B#O2;GRi6wrAg)kxqQOfEz;3;SISBMGd3tkj{WeH zkk?4?$Or{<-wY<q9^tcbS`rCj$OqViynt>`*fr~636RB+Vw~eatbf#V^nVWNjgL%B z6jUB-R*$T~nfpkrKeM{Z0LBRzlPJdoS-bxfwnJL$|8lSEbeJ@!B6u5=DzUQTZs*-M z3ygcaFLg2|bke5YDTuDpo`Kwxzu5XYGSJI|1~6e_fegvl&R!7~;|$wJED(;E-2ifL z*osfLr=Ylt0#@&gHPbvRKUXG%-7<Gt`g8blbQ}1o1^6oPC#M-a)J2ZMGXx+$d&%Rp zj-LWdLSA}%KOB|)=HFhzQ4rNP)*OPy{#O3)RZ`T2R+M2klT?@LGrvrE<#pa*ia;a7 z{nSb2T8L{4mg8`n7QRctW`ORQB4B0%uLC3W&<v-U@5kNm%+PnEKrvNVJLxkZ{&>?= zMCcF9fiRD7Soc9dqa=Re{HI=T4(G*GH$ZOMF9V}7EMUgkARzTTnfCm_xfNzJ?ApW% z&#D|S!onX3g^~ghT^=M>&ov|!btf9)$8H+ox*djh+|Y*_K1IamKMfE1AmEvsdn)?( z5yV14)0JgZnbo6=qDG-tkNlHEOus&<eE8|PsHKzI2=q9X;ob7s5~H*<<?`+Wr>ffD z#TufC5+!%eT5D-}Ak{?FD-kFwSk)a-DfvAk1t|3=_a3j8S<IXOu}lp8OJULSZ4Xqh z>5BTE-8VR<Wr*q;J^00lYlCM*#)<3pOX}-|dQ?PL)Wrz6aiJ@Q=)s_iR<~voULhV& zMk)c%*B{p=oC*!@1yKxwD5Xt1&7>Wm$JBr0GkD%e0J4;y<31ev@U7eOX5M%;pZB6^ zHJL?i{Bo7PXHNE*@rD9(nyw1_+>U^Kx+}>dhb4XyaDoQLK)}^iO&jPiSJEj}=x{E_ zsDZ@tz-4^#pTdb}N3eRqdNgwCqIxPE)R`;SyY-)6<gPLqCW^2l%;DOhS>?Q0zysd_ zdDx#GO{^kfdZyytCnzNi`_z;X?EnJgKtiI@rZaY3qLn)9zT6OS4&GU8w!f6}*5yz- z&)CSNaQfdSN+-D(|BwYvS`-Ho0%nu!je+b5{-@^0Ls`+v-N>m*K4*1l=`igetZ@z$ z+SEPoSrZO*u3sL`2?RjOFS~s`+~O8tvPE-cL{ihvUhs)k$j~BkYyDZj+A$FC{bPl} zDr!QS#0eU5#l?v%$wThx;}h<zY5i=IJ0vMR&ZWz&9k~HAS3Y+@3Zy2cUk)I^74@e^ zDj)|Th5;|z{yfsr^wu2mK*C0vFx0KVas!*=D%YD>rFF>gL_dk^Hoxb_Vd_HdUo4;a zo=c2;Uo$fIOc2?p3WA4Yoo@_|j*eGHDgpW%U?F2WLekpm>eRP{s!Z?~XJbptI2e9r z0lTf@f5?5C9;8X83?!Z6f~E|mT8lk`mLq4fah@mDtK=g<soE`<o(qJMwn->gMgA4v z3fNk#d3Uvt@S(F_o~0)}oGR1p!{sDFm{?x1&pGMJ!;GZ*;V}rGOBKc-5)cjRE8i_g zC(j=apl6a2E4?{3zcnu&K{VN=&3SoU@tLP<i$77k*w@c&f`rk;36v<P{E7vDN8joW z`V3Gg2F!o|i91Zy<gvSxYdc+Mt(-vpd0zeF_*{18<;@?jmp@*B7Qp9vre7&^`q;og z!FP}Y@~3pC@6UX+YOeiwjV!1U-yuNK0T5duI(^RvW6t~t)V#m7@;VKC`1TGH02-`* z--1hn`}Bt(Zz<i>TCxY74H_BZpC1}b2-cXdsOKrweDO;Fx!0%ZS0+)g=|FK^om%(f z`uUh7nsBij#kE>IML`z${aORl&k4`39XGoTjlB0#CG<;KS@Q0%Fyv)Gbbq{AagBPe z52C!(7_T`f@~ei_K0`jkU_=dyInCS?;GgFmeFC7<tq;RrQWPW1f}3pfd->AQa@e1T z)yLrr2SP&O2uqGXr;Xo~j9Ws(Bzc7Oy8R@VITyLE+HG&|jXiutEr#6ps)}*yNu^9m zISG=3#Xdm5oWG>gx_AzF$~-GTT(yt4DN?|DKql4bszdvGp)8z`8<Z0|f*X`pHa1{} z%}<1NvJbO`(pP_W62^Zo8J{QPF^$Xlf{7A)8$RbaSI}dULdrP;)Xv~aPW+bMB6}+a zlnm%56Q{Qd9bCeCdeMG@Cf^!?6{#rMMwy!RQWQ@6DsXlq6q0i&nhpW9b(0MaT?s9x z;^rzviYSzetBLk6e4GfD3;XhA@B8L!aIDM@xx9B2B?}^Gq0K&m*zghcR*`UU6(Hbm z;+KW9L~g<Yi{aZB(ObY<@_g~UkzD-qyURBKtjIN~vDeu(c3G4C|11v<GDWg;O@bMd zc@W>17-1gVTxZw>Tftd?<*?)vom#iUgP(rV`uOo{<~KGs%NrURQlKo+%tnJ>HEtLM zLgN>yZu3z&Pym1M&!9`z<GgzxK^019^49Ce>&=2k|D2&BzKw4fO=2)KIOq(O;S$Si zY5L?@<E{;QvbN~cTqg3~e6BX#*G{(WrkOVu73^aQ$g<Kb)aS2PFr%K$3V?LjK{qR( zLkqeP2YNnTW{IBZHKi!gsKph?9i1A3ik;A<C#u~$1+z~HzgMpGvnfpA@gc(l|M|fR z3QWEn`c9IBetD6`T6OKn6!Pcuw|k;R$n}8N=SuOP7PaZt8ADjqtkVN#?3rNl3K>qL zA~-!sP6x|atgfzd<=)c@q{IR)2ZdTmv0v-ccLx0oJ-Zv>|C~?xwa|SI1%7!46nE~g zMiP3opVn;r)}cK8bW@O5#OfkttL}R!OheySS1tvHK1%Xlg^v=_M&Z>53Y4Nl06D8| zO7Wc?sHnso2Go)MLmXm5ixi=?_|{J!n_wIn?B;YQ_BsefQKRj1x$V;ymX`2d$`b+X zzPh<TpFAD^U1E4oiA>Kp1weL<?)!Mq8hILx=Z%?cZD(xR3NZ;g8(LJ-^f=FDR&ozO zbxqC_{bZa#X#3|gSa+8u;O=8UnKJRsHgv#De1%1CNIxeUn!_le1&%QXwA_U)TiGU~ z{BP2el+5fB+)_*OFjM`kAxjN%{z`?P?Ua7Ovyk=uFA|QJ-)XqlKD2N#bpT;E0#q<( z2nUm>ggNMl@_fXtHr+a;hzJb`Ol<5n%1|VYaCNY~1X(H%kM`P_NTFV`tVtUu_ckC5 z5~QwL-4B$7-J8RL%p;DN{(FMpgLG*_$7l6PTu7X7Au9$aj7Q;h*@q?B5@;U+Uhe`} zKW=!J30Pkc0$5)^e*E~QIdbFF#&c<IuCR97lKA^z6VUheP4xFkJv8dm5(rfMGyUpa z99#!qoT2eO_!y^0Prw>dLm_bY=WTzKvPW~?yAS*kGVn<r6r+bWlWdkYlfn#ZcxdP+ zq^;5zD*!FWX1e{r`vzcj@;9CvQ7v69j%{>)6;rMXP$3k(wxt&Jc*>WW<YvmZh{v~O z)D!C0O<wmy5EV{)qUs|cT)ntLLzA?&E}I&ekwgwr`NDf^`uAB{iUnRFSfU49fV0qb zubnuCmOtF`3z*(Y$(wLd92D~!Q>OmPPvF-@%jw&*XB*f;a5~YkQ)nP+$AW`@+gV2) zv<qVua2vew=Mh1+m!Z`H{!gz&vv{|-nS?d6TE_6~S`E5p>JEOC!l()+!S1dEVE=aC zb%Ag@*UCK$%9>ipt{X3@6o*%VQ)vBzgSX00at(Im))BE<2j7=;j-BTB)B^4_(Gm!z zl|gF3Uz%sIhckv`<AuAkb%>!(UxmC3JK?X|Pih#;b1Ia6#>UbD(;MQn)BnDbMpl<{ zUiUfB5pW?1=K7?Az2gERBzM4vn=<w`!<3po?R@8Ztt`0jS!Mmo7Plda&TrIDi+%LX zPxlKkW`Y7=&YPXIN{d26{e+Eh`;jHs_^w=bCwnE1i!9!ax|CXy2z{gqWSZTEr1K@T zwu|lYL67kz=WnmY1i5<#ThI%1DLXxkk;xku%FA35*Qp0hTB<ncvywesd5`|~q%xGb za)GLW5!cvzN%E-6F^cn;MK=IJKDC;dz9c|xrrKF<U|FAU#}}vc=KUTL`M*f`&rd5d zyjSMnIO9g>)UXe8Qh?DKVCeopWaHr4n#?%b9sEGT#XxR)fp$57%aZ@m0?12+ME`P4 zi9wDgQT8$Df$SqmSc|~=7ddXZQ_q@{q$;svo!maG3}lf*5lru*HF|oeEU8IEcNg5? zJUJ{2bK|HK9r<U+kMd_AOAdHQ?2uKSAn3~i|COuLc{hi3eJ0C3r>5f`h%-}R@eVg~ z4S=eC&<>HW*I?*RQJ(AlNvzf195W>Q;BE~PU~Fgt=Q>qS@;_?|vWE>ayYDxCY=AR; z>Plc0dE|OAc&gG|QdVcyIuq~WqW{^u;<6}{(kiU|JV>==3rdp;)*x4o<v+9C&K-{@ zu5g=P!8?S`hK>pem*qn)+u+)s56(<2h9lKtVBBl}?3~24M7m8Oygn!v`+!EAQqB4- z<3@E65aE}SVqCDqcsb`u-qnn<7weo>yMxF-AD&M05t*2EEhsC9Z>3d@?zI2kTm(5t zAy{lwPQA`V$JdXVeMBMnD^4N&j6rM`plpa@@Y2dD);*#IZ_d7+a#AL`_;r~zV|;Ib z_B(x8z6+wXsX>Ghaj#XA`&T)(un~&W&r&+ut|>{-nS6D&4cT4+MZ2=Hs*s0CHLh-8 zYA^-yF+OGa{G#ukpZXUmuyGnW@c8&xoi|g*NTFK#{{qiHKZ;J!HSi!Q_?)yJ?y?Ln zB`2@y-w>~A2{afPYihPThw=U4ol<QG{K*2|F1w?Q9}$bANq?17nu)=d1{=w_ksDL| z*+WZ}F8TE0TVbEe+Ar5LX^Az%K%K<lcO2UJy4C<9I!x;P)wP>VS^iyq@>Lh<r2<Y^ z+r<(VR2+tcXSWjxqx8%3e53kqgXw(Cp{;4`?;RTr1Me87DJ8o)N)Vnu)T!^&Zt$G` z7kFr)eJ(CByF&IBny6o$B#emai4-`}vmrUOk^p%C>yzeOvEGce817*;3)HpZgZGGp z<e=u|D!toy(Kp)uZTxIuseFfEL7-4nX?Ou}m3;kui|q=9O;+nM!h05+tp2NE4=w#! zocrD`P$U|+yT``YfY%pDBOQy7YPJ8_Jqc)VYB+>N!HTaUfm}T*4WD>@VM6XY8;Hb2 z4cX?(UfG0@`)Lnl`V{IEZ!qW!2w(Fg#2xh{+JFS0z{2deFzapzNJ`YZTVv*CzP1z- zUN%L+LS*SrauTIKe?8U#ou8z#jeyO&SMHmj?UGe_$GbsLQL}4p?jOh?YBr0ATtLMQ zN?Zn`=cbOF|4Dkmw_{6QHs1nZE5v5RSDNn-YAYm=e6pd2*Vxtra;Z)-Fb$Q=#2`Ix z`?H=g;z&1ia|)+tlSZuMCKY7?eEzZRt%;Dj^ty%cotB!&dZaqxr3RUDk^KAFSA-cx zAf|r$4$)?MZuNU=(by*742^9sz?$vae6kx2x8+d2-Rcpn^GXA5`lAwcZi02!YX5i| z1M&6W|L4xWCFXo&Z`%g$f_TUpA@(_`iFSc<Du8@>>0h~Ya3TK?BJ~;%VUn}6V-nV5 z62rtLJx(31{%{mh03olVD;{Tf+StGwj3wchf6{#Hr)=DT4fFYl-IrBnqg67|y5mWo zw*ruqlh((THB9AGr%f1tILJ$0Gx@eF&L$W8C#X_yw-|oS@>6dxjC|~&KptQ;`0uwL zoU2HK_bv))hW?a&4ZhamWtC^Jv(ebaR^C0OD8p-Jt>!B{e2NqTqDZPLdqGxboINw9 zW!pD3bh+?yUqp@TkOoq(p-IboaAYBi1KwxT=-q<J>hZ`;sxC07!PwH$vmWvS&CW?d zIW9TX9p4Ml(K(iPDHzdE;nLhKVU;Oo#QT2^#(a<nGA}7Ak_5y3wG*)Kzx=&@8O87^ zDFD9%!Of(y+)wh|ug~Y>V2F;EKJ@!3CkFX8ycgUDE{Jm%DcC3IQyFe~2)#M4D;#1% zIo&_V)(1^-gmlgx!`Sf#^rjM|vW|ZcCNZuC7`_xAVW9!FG`<vzbyF6Ur@>jK#fp7y z^qaH?5s?O#31+N^RoJ^(c^j1Me(uq)Y20e6x!xX3Sk>9knBQNbHncr!y8SyNV$;K* zBLFfmGHRgAQ6&gbg2$l~<sD!JXs|U*x<P}BqYoccd^><%a<+0N_{2@UC@->gR&=4l z(fBuyT6aHKBB<n9upS|l&bbW5-pg5*N2$MHC$fm3$@k;r?iBpErejJ~igP>Z&r98K zkb5xI$AeXi=D0k}Z>%<E?CS6&N75gbgd%Gf2#NfETzvz7+|9psn+6-Rv9qylb7Qu# z(>RT78ynkfj5cX(wXqx9HlOV|f86JJ2fv-q?96;G(w|E73<Zr5Jm2RH6M?{%hBeJK zqxh!(ebOZ227nWQ2t8TIamH~32)=FR=RLWdxqS=ze-u8CsY(dgr^`?!(PX1UKds`G z_JwCjwjc<J6zm(kpRr(wGB+?`?bZ;nw?`P<#K>in%sADfj0mMV7!NT^>JM<27L5#z zB?g~#`baubP=LeWiHY-&=2X<j@pe*$0#Eid^ULW#=!1Y2|35#Aru?|)p#D4fH2*|{ ztYJa?9*iL5tHz86asztusO3K6EYFYp@wdUcit+bTSN|kK2t5FYQ-#uom_hx!>?l!p z{+B<ry%G?EGUm&!aRJs0CQY%Sc4<^@JQp3O=9TN+d?y(N#LmWYblD%z&Bg`{Gjw#@ z|IrBp>QR*2mMNpKpi<LM=uRxcWB(!pVRykmJDOI9t${9vi%6UAod4&928I1Sp(7IJ zNfSs}l^goH@EoUsv{;GfLD50obvSf@55$F3$=74M#PsYAYn<eSv{Hm`t<o6`oEfUz z>l}mA7FZ=o5h0s~<0?Ce16vvC8~y<h{%wxxx0XxI@=Gx@$bc&*#@q=*vcxg%vN)Cy z9HS&eu^7wr1&sFl>D~ZUdP-31&fHcRUYJLJA;px97NW`dp~x_?YzG;U*jQMUds4J! z|9NKX>H#3b68eC#Ex7Yb8#=Inh4%wbC>Zy9jz9^TeWFYX2zaRLMSr1e{6P%rB=*q3 z(O&A^G>-;ef?fccX+2BWhZZBPWwHn|CAW=?&tId2&IQi*sw4>Xk49?0s=l<}$ymr% zMQ`u-K?I#1n4}8jYJ<f-Z$jPGl_q9z#VT6;eB;>5{IOm=L!)Tn1k{*+OK6)Mmap&b zMj=KnCh?O`A^$v&=3$`}4;i{!RTt>za6K3?GJDLisYsw??KE7l_I=98`rHn#gUORM zb}-~bba2U7BSpj|dOom^>f)=Q-<$cT&>})Xv-KM9myw~KISDEM!4%_TD-!TzLUlEq zs;=##4gMmAZuLE)XM=`3+C^F8cUAp%!1$11nY?iVE+Nmh12zcRc{D$pWM7+RiUWgL zy=pHIWN<E2E$SZn=w7Q4l5)`_+_fVCgF$YUhzp5Pxc-Hjv8<A*PRJ9QmeW0;#>)18 zCqZe7bzpUzqT8^Vdq4^lA?m8v7602Y__Gy^A`g@-*SQav@Zh}<QZhf8mCJ}RMku%4 z&t=#5(GnoEV2|3wV;bXfkg>9(82KhHAVOINhqz^M8;C^HeUJ(T7L!I@4*&FF2<=9B z_|Y@{X}uJvBP1DG>!yk&0eV^)%5(mHlIm@Rb=uWVV4pf$$HGR{F{x?j(;rad(Gp04 zQ>Q5pG2)cYvc--OppXbvo^Ai>aVPfmesJd}`1iE_KRd~r1B#LYWRroj?fzTqD}pmN z6*trj8LiWXH5NO9E~F-u3CXFI;S-!nXORGa1UR@Mk~e?sjdmSEs2Nw%|3Se|3ddmy zLlSwhnb{_dghn_{=wm<AcO!S@EH1yC<>&RFDY$}JMAiKFt0%Co$KdM#aT!E7^a&Bk zq{I;Q!lXhfM9Df1;*k_(VK`*en60qRNx-s_^18cG-dt08dHFh5?hzPLC!>rjOejsL zB=iE!IT*?L&*wpfWFEv1Sms%<J^q<-YJMV$w*WdoUn^#de_Ozr2Q4T&^Ql^IezcpC z+XJ;p7`-fugPA;ug+dMgC}cl6KODh_20Wu}shxxal|HnW*Ayv1sii}qaJNRi7%7V< z^1#530F@%-sV?NcW5#1QB#T5DhF+s?dc5`PF}~CNH^v`>qHR9*7s}`hV$zmzT<&DE zp?4Ig$=eDSk>45|G@?WG{<+@vzJISfhwpz7eXw?Me+leAcQg+tM&gqe3#sZyaDrG` zK2X5lW6qPP93?Pn3yWjcb;%<!rw@ztVzx2dk4nSdlH(60c-F15M0|$MsEBkd50N`R zI(rL761l+)fb@SxTm=a_-mm<i^s(r)N*wZqvMV(ODLf~^)LGS2d=DMeG<h~zQ!L2} z@2cAvgjYD-ZwoL9&nOClLp@vq8q_H5UC|s|qn_CO_eO#2lJoq($Bf5DOo=$wKFx7@ z#6+0y=fo#6Pi>8lT&S_;l-UF@yoy0z;+_4`Hh!0hPw9;Fph?$*B|8oIq^vReHvB{r zdyl4}FzVIBMPbI>&$S0HuO_Ivf7KLNrZfsXhX-4ifMln4C}Yi6Y`u1TY?w0lcIzuq z$JN#P*he;-xVk>OYHwRMDeWV#g)EWB62)dhT&7k&Z6t(*Nre-U59=Us=Z}Ve9yOs| z4;0F5;O)#I$vqAn<MY65;U^B)90`ECm}rR#p$J34aC~2)CPlD*X$G=I^vp2SA{x|< zg2`HYE0qJWfx1Ioh_#Yo*O#;~)4*%G?A}LeG=zX%8Z7!mOQ#I8#R|AOCipMjK%yb; z<rOA413$f~iGgjA)kekh3W2+HWN-P2tm<>C=F9oY@Aou~=1|OKJ~77GAG5j9n2E3L z@4Dg6XW(iDLi^{1?4UBuB>&GInI(mMxkSD#H2YoF%jw}E9l%SGhM3yWfYaXKg}LX9 zv*`3#hDeumSf$`YHMmk<rhpKI&=Be~z#GLlF=&t1jO6_Z!0706#%e-nR+V)0tTIgm zha9>6oCvZy$B3sgtr(SNrn-<x3dgEToarVAPju0;Qmz784ZqJ9^he)ELF^zYI6pwl zB%Z#k$=;Y>S7*Qi!(<>F<0xZa1ZtlX)R$=zO63N@^JT%2N7O2tPKf`!lyIT;;zSaP zJYUn9Bu8Rn|3{ZXiHO6LH12!baCte(oXdsiOM6($CL8<?1QYCLhT2@T3uuGUrbsBC zw#u6cfTa%HLtCfqlP&;q6>$S*m=Y{DRI~YN!^jK4;DS|IOdd-8Urs4``X^{-vQR65 zSD|QvE0iNeuCKaU?t?^{nSIb6pn?u>gCC9UHz}sExgy=9GWH6wRas~YQi2y#O+kx+ zAE;wUe#nCgsW*e%J-`wQ7(_fQ%87mOa9?8wodv>+<1)i<HPiq3vvgwsSP|K&cQ>x5 z%d~&K+fEDWLsX-rI^S(nMB@UpL%w0X2OM)k-kc2RLGwS8ti<=tVs}lRS1nz6OF+(g zPR^!SrV-ji#mYQz(fw<&VOF|r)a*a2!?_m>zyGxS{_E*iFF5dlC|w!gGMI0PFX*Xx z+kO>$nu(<fhpagb&Ao2%{absPjXt(R=|xpqtrwV>#KLjV1q2kG897~SkS3uWMjAq= z5YW1OIR5|sz8io4zAB`*)(JGgyPKQxyuA<+3OSP3eudD|(n&oq3R-OWbg4`MIZAgn zm7(IFe47s(!Am6ikp2~LKwETAGy^6B65q7NaU(uLQE{45f~xx<qO6snFHUuN0`HF% zy1Td4R8ye16K`d5kIcR>irf0Q0QE~ImmCvk_^q)h2K&~;D_~lHF>W1B14o->K=0mJ zEQnfghJ3~Kk8K5GK?~7}|8zhQ%zvMY5ZWUkN*pr040HcUB+qFt<rl_0onG+3AX^{q z<%uyAA|+6(Gf*MN8}!TvG)e{V;_5kn+og!ax$&Z`BOMp0Jq>kx<?`>n%U-|zm1q^D z823pSX`-#~@X&1FLvGTeRu$Wb>$(Aq%<_e8=JpTamk85ZMJ7~R9KkIILCgqvPOc5Y zr7)A|gnaKcCO@I}5jo$zwM^gvBrJuwk{6$tIOX>Cwr4vi*TT@#&u5sx1P1>f*Q)(T za%BiKIE*%qCE`)?X*knBFT~w|pr%LyehKGg&j3#Xy1nYVU1U-KFagT}mHgC1LP)Y- z6?;kY63MfzkOGbkoljqcPM22@e2dpdLjn&-uj$U^d?XBpnU&4)VZ=|oq*XI}>^U-n zrgFOu#F3_;bF{=;Zqm7}^i{j;g*f+`$WY1MVh=g=U*zs#<<}PziE>&#W6WPa@MO?A zR*|q8XSpq`=PDUCR9gIV(W~kHPO~&atjh5eqMPa4;Y+|8m7f*y9Vz;u2Da!RhwUDf zlE}mOq|XwB2W0$H&WeTGZGT#RdH02JjG8F=<|rwLe8gaD8b#-zvOwJ`Qy2-UOFzE$ zjNtyAK%6$o+JQ7iLARl7yuV<y__oUrwkzd|sP38Mwsah1BXSd;7MW50qRf|b|9I^v zCKNf0Qp2kV0egzt+H^ta3a6f4UYt3|=O#AKH^CfZ2><69KqvNhvmkn7T|Y<v$bH`# zdEOps&|il^$!~}Q#Lc5xsF5kEHu?!%H;Y9IqH^;dIMerFXWK^KJAi}n^K2<R9YUv0 zak^c%avqoYHe{YOjU_CCg#1W8K`dFSm{?!TEmOe&PcMwdoi?|VuR=G-+UU_rsQZ$# zU6+fYBQuY#b%)U`7O<o_FFQ9R9Wof5mbX3_J`d?-{UmE*QaCpNf&~Lf(n9mo7#_@B zx&HBhfj|h{|MLXHh?sJp=3|ET#Bez+`IAVG6CiS=s%Zc%+8!>-!J(KMNehogg+adW z;yCsTd{&4;Bok>73U@-@{>LouDSw#g0|=EjGPHm#iYX{eexON80PSAXt~Z#ce&1`u zU8018dnBuvdjt(ZkwOT?R+Tq4|JJ1bZ3Pko<01z*rU|^(M!DJ&i`odQXUSqVSx>tl zBaZu<<)!Y`cmMk8OQhyY_|V9eBVhc0zJ9$BorV@fXP1Ms>0aV*-muocFP~yv8;Zuk z%%f{>Bc`z4{Dw|0e*T-qR*LeLUN-14x+mbn4c{pqHVp{(ZU#z4MV#3U>$1faWC^bX zkWG?N9)O`_`W5ExYD286795D63tNp-_Df77JZ{@`plz}KIsgv%5hM${M0uFo!%`C! zm~r#{B+(>ODE?gLlX00kJod==Mo%&T0k#7?9={*poWC4_lyiSyCyLBalbM-`xLfhz z!w1>4XLc(qJnx(co8098L+{K6c1eu7d`48fB__dqPs#8L6OF)a!>(k!GFgIhK^2Hx zpD;Kl$%=+!a~tW$3nsTnC^L*4Sf?YDwC`6=$tC4)V}@?0RnMC&6=Vhyw)%hIr{s#> zc$Le)44z?Z*UzxiWco0HTMi=P&@$r4J6iW$yc!??3oW8>sznlxC2(&SN5O-e(B@bs zTcC+lbYn&8w<1t~A7DfTLr5v>*}lQncXuVO{fVflg+8Cc{`uzl`~gY|TpjxLBGL;E zBb0n9FZJHvzlQkK>f1&e8Eg#ZHP=KJPZ;u$7(JU+jEL#}1`{H(0(K<~6ShdfgoZ{k z=E9FUdEyGQ%@D-bNcy-eJ2+M$HW~39j0jC2ekz(kpF$@0=iO>;%Jll+jOEEKeJJZB zj71f^<;M=^F2?2znB8fbfEd$v3F0j+EJFlosZ-q80s-Ba#Gf{5TJmkw)Dl;n*6MO{ za(eKEOD+!N6FCA5qCfs)@jny&{Q*B~8fTcd<@bi<6t}1<EXgLjOX|)SmDwRKE%;?| z!NQ`D5|=}$<(;A{Sd21`&8dm|cwPse1Pa=mvU@k=UpIj|C5~_-d{yX70gvn=P~bAO zw&jp-)<v&#nP#^T;J(Lo-B53tyZmW_c<}+d5hR#xzsVA**$9K|`XLOT=`L=G30yLY zF5@lZX`w0&o>^L|m<0nJ)V?T%yWh^I7V7<ftB&~hqf@?KMtY#K!OT~=7q{h~=i{)b zV5YAKsEyF&4F|Mn19q+Q1pso`^FSJoA3@l(P*5x!JV;>Z8mId`q-B|SXAQ8I$>$>d zE7fF$Q+UTL{&)*hc2X{*w1;j}TW#y8U+w0}+r~R!F@oj*24^jdVI<H~$=&vS%5T}M zdoiQ!m;!he^)9`v`;;Na#lSmQP$J)HGKbf#4W*oJXFn$hC{-f*)5ai7;~!AbXR^N^ z-oxDFTmxMq@?E50i=Z2k4M#BWh$aj9S1#j@1}kVsYPO$y{z+muCq7mGqzAoH3rYcR zp8%RH!rIbms$>QZ38uue14BC0o}{)wY$fC98dV_>8fZ)wU(0bg8mKN&0>RxJi+{EG zwp>%7b7#en3q^#wG@T^8SkKAe6EsbU27%FXZUhey3MP`K=`-{A!4yh??s{r!g>b`| zoS@hAnw-0>t!MWCZ)(ko@J}dWXRS+<3-qUu<<KeI4TFZ`pqgmjF0N}4J;X1S;R$s= zorpBG8%76V?4!$I46E`bC)^6fV_Iam^FS4;OY88u_Up{CNNElXVKgZ-QM$*#o`?3N z^A&n?P^s;GAIW+;O_eu`K@v+$3V@}L9#A)BXRCDx%5pca+J=Qqh|}Lue)k&YND8WL z2;z34l&hYJc(}$V_xr*K6rQ1KYHSQQNK}^(Z%gIht@{T>4tY}k9Rj0)4vZmpQ~f2L zWMjGGH4iC=Bhvmh!C|P)18*Zs;f)L#l*wwC_BkRaNJAL%$1>3(yz48m4)*i@oZ??Q z+p$e)k;TLmrVl(bH^Dy00{pV;hpKFawq1h6G%8{~+q|qi7KTK;@%8(SeCaNCD{N<{ zUX(DUDA$HKAynmj7%5{fUZz(yeiV>qjrGe+yRjfy%@9xfuJ$d9O5dJ9?xw4);NY^# zN_j{RN73n2ISBu&BezjZT_AD*qJ*J9!rrTXc6PSo{sh@#t6Pl?#1z2=5x>Eq5+^xl zps4+qPEN&nzr>LYR99CA#BHv_bZ+vr=GXvuJPRVR+o7WXV&{FVxbblWcG^G!{Xf)t zg5sq3t7JX6@K6SUu2ke-t2}f%+@Hi%S6CWEN*q-3^eelQPpmh6@&u>COl&9Uw~_OG zZ7GgKzN|z=EET~Znogd1YkS_E#&`R)=97(p@Z_Jsq~>sQHHoxe+bG?}GO6=Nn)$2% zlgF`57v6X!ggjC-hL3fd^OOmY)II3(sw#!QxqGZE_8M7xjc~3e0C`d<;7$K-e#cwA z@TJAquc;7$&IqJ=rs&%@IS_^*$LU(9!4>1*N^qZR6)k^<VTHtR6%`0Rxes{Hn&&>= z-p|k-IsZQ6>_7gUN&85+-nO`i4c<(+g;r0g-$R+wzo*7i(p~VpTiJwK^E0_}E>FWx zKJGS3o4=sVO{{IU#!mXZZCdN6zN-7u!6B?oZH69?i9yFk08RJxT2|N|N4<iY5spM4 zPLhS-6lA;Z9x#60MYIX+#s2%JQF-HPyX-3e0@bih<bX?_RheV0l9cONGSaO=WWah5 zjwMOx8GI7@_TY|0*u@qV<kE*k4>vNFtINWSUzk`xZb-Yr<gWm<_e$V}w*_hsmgv~n zk?)WMm_<mF5y|U$nB(CLZOmTSS*yU;g<8=ZuT$Q?{lVLbxz9xmI^X60iixL76sE5` z1afQce_0>hNp$~<rRWMFwa44-7++<0b^rM0e=%5n4|jIl!r-b(Dl(PV7f^M>UA?nS z_Sn8f7)0*See)ZfB?gB;k>UTv^%!nuM54ex=iN!{c0v8?3FFjSLW(XzA1#b1ouPE8 z17<}|(na&nKzs)=qn|kuwnl)ogs&O5f_-fGHjLVzshjLKl~<PO3WqWa6XBle;q*p` zd4V6KV-2|%k+{11J%KF1?*Z6u53H`GP4azVB<%erAwbKqEM9G*knuw4xI+f-3tW0d zVf2%FHspW?vUP<D7kQI&rxiklLtluRcqsSnA$Rny^Ua4+rlUsnsIN;%&<tUYVKXPA z7^05Vf4x?EQ-9r7dX?~n^m7kw^oHG>g_EEPb#hCa3B4WLoYeFD`(3_Xh(?o6b<m6d zMc9rcbPVWK!Z7e79SBQC3W=hkw`*6Nt62dOQLMPf5At!wlUGWPm~72?bHO2_1ZR88 zD-s<g>**+tFuHNeRZh9+a5_+cCdDq$0h+PUFv;hAT%^#fp2&2e><T*ryYMpWxR`-l zmbX&`X5D(<O!=XIG7xgx|5j&6N`Bo6E4n&=pPr$gzj~o*E=2mwFgaVKA-^An!{<># zx->D7XPsCE;&VOL%(o+ugP}PtfCgaQsbvKIEoy=Uxxhe@B7K2DK|!*n`|hTY2$v~{ zXoPBEc6Qe46E~#%%j0gv&Fty+#7b%e{+(6ILMQ*a<z?L4eVhx0SqJvfg-hM|(-B5n zy@uugf>ZX%e{qsN5>~{|Bv3$-SOy*^u43eH(qY`Ef$UpKLe$}7k0v&A-)zETo{!tk zP)fK5PD|3YaVkty=^M3`ufJRCw+GTy6KOt(8sX7QF8-vAFTG$@iip%g#F&tcJ2^iw z#rsJ$?DtVVj;*k1+H_z<XM5=AtL)lq_JSsM2J`menGj_*+^w9oFqdt}6?(>=hodVm zAfm?PxdoD?0;9lZcMdGqRK7lVv0hq4YbFHLuGNu%(F8C0FfV`jJ^iRR8ARdi-D-dU z{oHHb4c@O;xv78i`hM?cWM(D{K$2%^%RP6~%}pWF=z54+hm+Fm4dQ6@tF(OGk9(DY zK+<;(Pqr<DYn8MABWmfIjr&Vr<TsHteESx}d%3Y1F^{y(s@N_@ge;!da#3n3^J&?& z(B?T$!4wyTFn$&OE&~@jw8W0pA_-iNXgOECNQo-=Q=Oa@!JvAdaM`8z^7jojKtFm% z7)<pkPOkaVb;ki6Gg0|TEgVYDn7_$R0m&FP&VjwAQ}oNK<F_n<T4{`P7dU-bw>5iE zhf71_*(xRbd314^w2;8os+_i#@~lMm7?+(z&I}~jjkrfKiwE5>TuO@tS~mP$1Y-NN z3dJ=<<oC@9c3`sg0KyFK1i%r;3*QF`$3v8&mbo{(j`C{y`qkrKTTi(3Iwdd#iKPus zJ)iF#C}jx|fwGK@jCRj(XNT}=@CGXt{~EH=AUQ%wKn2I+%7?um|B-{|bx|s|l!yVh z?T?5x*2!8i6I4w`!bPl~VDhQ=8bL$i1xW<R!(V-GDj3>2M76(KOtfKvo5xj&qle(7 zwDUjpRCv2om>GwNLQg;L349{~m?Gy3tcLC56Izp(bjj)V|EU2T?u(}V2>}MclB~6e zqg3lq-^??13n@8h!by#l5lCjC2UdKHU?<Lz4yK4ZeTfVa(VsT8gv8liLIjNm_^25x zlbk$3)EfOBV}*Qj#sF^sR0lWv@Io5D4y;vzg}(He%Qc;rh6bbCibtvU2BN`4khXH@ z=IhB5!}tu>3dEg#m=#Q{QZBjqld8IX>k)W+^f&7oCI&oi{qkb77TS;ZzhFfcGgP<t z>jPD%^TGXxU7Y#YH`Xg*$JA;r`U6K&7AiWJ&jK-$v77;yA5k)<6M!0X#<{r!nUpH< zfnX&vL;w;IV{q3-KGalI!qfsPV5ul)i{f%Lx0ABa$DUEX3Tq_7VN2`uTksJYmp^j( zcxxWUXN>?fONz8ue9A1|cMB5IG5dqD_{^*MABTf~={qF;()VaB>UDnjeWOBZcJ4Ue z?ooLC<0OP40zIk!XJi=0X#xuKK8gUP@D*W9xk~p!_fs7DKpf5&N>BzQ{V{{pVH^*k zNQmWS@$!DpwIdXLVr>5>`44Z`KSFUXiX^493#F`M2rqn@{hXehn+*c*D8@T#*e&Te z>6C;XoF0DH7)+5@SXb<PGkB`_o1hY3<9qYX+~z~~*T7Chq>i=64!MS(e^urgHRa`? zT(4<<3~De{t`hTqwK2^A=t#=eD4N|Z^BplgCazNZ!9`I|w#_E=qPV!7<fNbhhyG=m ze#Tjpy5v|^TC(>6>qPB6Ax4gFS9)@$kI`%Z8GAixa1R_QWeZCm$Nj;VmPvUe>0}!Z zx45>uC8puHf@q|}LTnH`=B2WQS~s#OJU-Q2cMybV+yrE-U)c8nEYoxPLf=%}h^cIL zVj7AM=J<;WjAD`U72J!C68VG{=%l$SG4T$ijT=)v?v>S=2{JYg&;hYn<Qr|vlow#& zm4%Sd{rP%Ge?u_@n7d0bT8DD;d^4`SC}NR64tqlx%%%Q5C-<3e={M^^hOp}nAJrKs z8Es))G<u=bNsH%Gcd!I;Nj0v$_x=$2l<DFbdSbxSt9h=E)azlVx00vVQxQIX(ctSj z{pG#ivz!(J_Y<F;=(-OnFCCSPP)GCHbkr8a>*eyWG~e;beo17y^{*T7@|(enY-m^* z;`Yeif02HBGJr%!lsy?9GZ(4?gGH*MvGX928^i@Ipn5-f#U75M6Sl*Q3}s@BdgNA+ z8b^_^zC>h|(1R6!?ax*IQ&#cTZ79Fn1RNVD%kf?eYLT9UFjd~`6Wt>nkT*lZVS<Tl zd~!>=$ZkO0(ju#ZN}yucXz`j0CvEj(F#W)h@b3`<Lj3aiYTFPjl*X>t*xzzJMb&Uo z{YuAwC>(yJP6za&1+xZtT^>YLC-yb+smEm}K`D9tWUcC;9_eeX7wUwKbg8q*(c@pn zgD^K+%%t&14xe5QN^?Jr8@jEyq(YnvxHpjETIB+>7DH&jgK0oEk<thJ%C{As^DF!; zP5(rYz?S&6*{!u=mC6=DKM-a!TMBmzV>=uZS-y`mkQriuxV$$IVuD*jktJ7QiW9v3 z_%P=87{}&9r|Wf86v~XVhYG(HA;g`u<4F|?F)aK0-&E`-S?B)cale%QGVys67ip6I z7Ya@i@%MJ|>#`6MH9GBvBVl;ne<0!VdmZAgg-(QeAFhc{6R3heeTL)XU!OW+$@6)3 zeq^_hWJrWKXKOR9=@S@w-1UT)_KY#L&jKpKB+WK<WPQRPVosFD|Du%m7)l#1{hk4J z3eQD7<g%Q|I0mR_^BzV(#^0m)s$@_Q=REqM2}uApYLe|56UsnKR|*nZ0^Md^{Nza) zu*Vu-ce?6ZZes)f>2U>2k`dYJ?`d-X{_b<LxfVml#eM0lHTi0*NO3x<WUA0%+nBdO z#)5-XHsb1M<6LTDU&8bWcYPN93<;b^O8tx_VSU=;G@b?1Tcx`=hwzPciMSojb+wqO z*Jz}rgol7VEzg*~p8}lyqegGF@dC)0t!FQLZw&ly$I`40T9DM(=lRZuPP5%gJci}j z-peKwiEN76wZ|Zz^jISI>hkgg4_r5(%yLo+bOgcF)OONKPU2Ujj<?)G_o)8>gJb`@ z*!LFNqA{vaP*g#0qE~xP-<OEx`JidOwD{8_n4vk-<f^>VWhJ67+Pi<dE?Vy*1HT6a zCal<}7b$(AT+B=|MflV5g)G`A0i%7@#m#m20#k2+nubBGqExnkQ2#)a7@GHWx@V=2 zi^-##rYZ*Kl#3^>pF$XMQmP<Mj15V2Urs$`)IzD|`a4m)1s|oujIaP3dAj<ilJ6XH zl0JeQa+(Ao?z{OC<^B7`Uy(r=!5w*D)+E~d;jDKY$O7C|4Y$QyLm`y_N82B2UfeIu z2ei`OK{M?lwuSHB6Tdh_@mL#7%Xr_jBa{xL`lLfkHg)d*;RyR(YQi={)I&BE;qxo> zQL6Yysli;OKE>K=)Z54Ej=MY%NQ>nR_QBw_*Dt>HthE>K)bb*hrbX28mC>B!7EYnD zC3R{zk=jKNV}5he*$WbzbhzDJ%KtXSSp09aj3xA)4Nw-RZ9=MN`@@#|SuTVYH=qP4 zNA;fJI0rc5*5K~vqo5kPer8JWZAKpOge&`!CK6Qb{%$ftsyDD*k1{J(MypYK>3ep3 z>C*gA{z|sv8U;6KOCW8nC6M!*(`c34$S}5YO6JS0b8vr{^Dyu1r#u!?Lk^P7SCI2m z9<oTsNP3LpN~tg-#8WBvwDiN24x3%0usJc4Yvf5unBs?gRl-ugTp$}E?dG=xX3H*^ z=FC<k{m8RZl2&S**Wn8>X2ZWjRlDi!>B`X|`JDTgt%IJr_6n!iBma=sk&cMdak4^1 z75kt`8lz~z<0}S!E|U0OuUI)hFR9QcDbrwr-jtnfnXj48m&v83cdH-v&sfW4=SDww zJR?6GQ{?tG_wWqjnj~v8%~QsHd$ZAOICB*H-3rI7D2_av3(43zXuvV>R++0YV6JJu z%}~U!SJVCv3)mGx{+D|V;Zh2Jeh@S0yVTPHDBqIx^H9*7*#n^qz?f-)5?E;ktN<0! zFO=xb`TTZ_QGGC<=_)7tr~_A`y8Ip$i??SDs#0fUK6TvRJZ&(d9=tq~^7xQ$OuAqK zzg%aOzUdZYAw>NF`Cv|~ikY%6NP$by=169lG=XZVt2ESHw*Ih|nj>AF80qMXPmk7Y zP7kW-OEV1l6}XPjXX~S192g=$wulX`ogYZTRbOoV;+v;(V0{8`=sE8j8U>=$c$Z@8 zj`K#E-}L+36Aq6N|BhZ_-iUsmh^DwU@==_S+P#R%xtUa@JAq(ibbwnZo?G8tI@VXD z%1WD!LL4Jf(iCFc<7{0`5+w3U;Eu!?F%{i1rbX2lzIZ7$-KbBmNZtYL^6aiXUm<Tz zKdzzvY$^3RA0+mYpQpB6ZPOy+u@74EI&CRk2W)yD)j9u%i2SRCj6kM&-MA9=jAriG zZ4Via=xPb(e(}AS@Oz^xOu$pIC@^QJrYIOD<mBfWip&y+1$;7;bZFlC<V4~=9%<Mv zjw{WT2)<iepiJIzXnE;AGP`}YL|fLRdM&isBSAHLD0i$<HxmYg&M?(Aovv$BzHVh( z<*-mF7GNo+j5a=86}9<>7R5D+LI>|6vM>9z>rJ&71tG0KF}q)Va}njAmFl2l<SbK) zk`RLZ9+_KB{JB-AxhoEEYhCa_=RkyyuNs4)N2$}?gKodF(SwiYOuQB*<VvQ^EnH^n zqJQAMwwE@^G!lzcH9p*{SASA<a=AKsHr%zk#pYt6Y@AL!yd75jm6ZOah3w!!sK`uo zoWAKJdvUQ{j*VmvuDp5X-g5^q&vzCcDJjBCzWe@pzhhkJcPBxAC-UnV95tLwII-`& zQKgzdnODf<^hzKMA_6gqO5%UG$8{4jk%QWz{Cnwf?!LGCzwVkZ&@>$n6z-^B-9E)1 z(-b-Q;;l?7n2E~;FMdgD3^CL%H4OrWyr~<COCcyUm%?qzFfm=&sH$obTs+or4I#cY zOL0{$QkDyaduj5chc4>ldNC!0g*XQRGv@LYiJ#-xoX|EG6iYUuTYkctH{gCtuuu{p zb76Fvy|%*@qqqx(51N?G%fejfyXi}*0*B4FdJ6^3pW7wsaaIGXs{LU>;IFXbI0Q1_ z{fDTnu<G~&*yT7%zm5eyhBs)^E(iPk!F~?ur>ryg{Wacb%-D~%D6rU%tl~n+si<?` zhvkHQ6h6Hj|6pshu2FX-NuurbDyC|JL(#bHf<DV56l{`IZSf@%Rw)NdD$rA=XOds2 z7awc;iRgRn3gR6|<qn>YPMhVNJy#a)8)o-+Cl+3GeiX{FJUTqwcFKLqvPy2|Iw(%n z2P3C7^JGR4Z`lZ7QP|A?Ye$=l=M`lDUxzN>zTFST#x#=DHuz{H^2TBql15*!0hm7R zeM8?Ojt4mKs-mp!8Pb2K2zb%7U>o#9do5pdVCtX%_vbKXN$##np;PkO;|Rs4{ysZS z9aDR8Y_8HvS!q(%#+eOThi)qW%&)s8oGKc!P8(N`A0_qKG<gZb+@>$|XXDJB@;43S zGpz`%7`8xf%U>O-WE3m0*G;)eCTEq&j|3^8*=OuV-dMt+UYJvwOaZy!9C~za27&-{ zfmW=5BQ6;*PmYDv9`}6Xg){9$d*JA~&%qW~f)B=9Jt+gB8(H)GUN~knH#dzKiy2YU z-Mmc#B*#5rY$XgRG(j8Dy``EgL_4g^444FPX^(-<*2A4+U5zA6Rit!FKL1K6DUT{< z&<Se)&B9b?XL*BoRLr14b?5UcWnng{SxXt~tLTOW*MSm&|KZ8;LhI|;Ww$f;vVG99 z$6og382{N21bo?Eaa)@`p=?$hhcn3ehfc<x3Htf#WJ`|0oV#$Zxv**K$6NR+8~NuA z4SSy1i3J~0V1hbubVO9Wwj{h^!Ke}~E?QP_*?X@Lt&=p`VFen<KI}gkk2A>-N1zib z>PwE6)T7l5P)Z$55NyBvW6nLo{&u3^aTD@;%EuXc8xfC1=TxG$F2w;2Yp~)|sm!^l zQ(Y3gO9&+&j2F8RbINw3rwx-FI_6Q?xj=xt?O8iL^$+n(j**|Wv`h>7nuxuW7;IJa zTxEY&?qvkpo7Xu(gu=_pDf*o<S?*s=4mWGF!<S87jL2n$JK0>OO|Ma%(YOV8u{T6j zr&M?s=jfT=uJAox41DPYb$-aWoV`z5I7vCY_O(#rFNQK<4?9W7=TC0;5u8G<m+VRO zmu~H6PmwXhej?i$VMSswidU5JGuQsqd0l<H?2INJk8d0+FyoeD-?3m1)kUJ4+i1Tb zwn81j)NSDR;_|Q_ggQo(ZPN1}Irg~<AnAF&2hpJ;pX=x(A+67x`5CT;g$nlKP&Z62 zi$Tti0zyf4{fa#TUT!2UKSl7@4U~yGssPOFk%ho;@Bt`ECGM7$l9Bc&=)p}kC<MC3 zD11p_4S~+8Y%gZ@CNC-;ueqx!2G70p^$(EHYhwQ|)C#sAT_n+9yIVN&em6oP@hI2_ zQCoz9fdXptoA&Dy-qQ%>tw!b1Vwp)sv}m_wU?Lt5c@&dd&+~1EG)5y5s_<yp!obh2 zfg~n)Dp&(6*n$t5sWTN0Z@95!;37<F#jM%oeUpz?5!6Tld2YJi529~Vb~g^yK^c}y zvYv&0UgZzL9(sRLC@wFB+sSoaZ)}HqZ5lA3%Z=?*lS)x!Y#Wupq%v91xP8anq816U z#SLuHDEgsN98@L4%N3rqrLC_>1X$g|l|;c>HhT{8`p=I<c%cK_M+&+L#@-FWC^Y?; z?;6a<=i0$(xr&4qj@*E8ul{adlgP>1e>pA#oX8+Lj6RZYo4w=if8rKeI;y`h>w_dF ztuI<j@rd|fIk?esdbH9f)#*Fm7J{bgi$sgOHR~tI;)_+3Y0xMl-3+-cEpmEPEb?e< zMYl)9M=^^HQ<xG1)bJK-J>vvk)>h;F9wzDQO+L&WM&}_Q1e1aUI7m@H2;+qe#%@D9 zXmj0~R@mh*#{5_zH)}#>iyUgK&n5ga;pAw4!tZExg*`k?$%ZX&N!$T9LMK0mBO!)G z2t9A-=VoMX1#WgjVl8Tc$h>h#ZRPcFOE44UTBEQlvo)U5DC99O4jvn7oSwCEjo;nJ zBwy|SYUMsooUgmJIQzPmv{1LAy7)t`f*r1Iq)d&D71ZtGPDtX@5>2RNZtC{tj|6K{ zisEBGoP>~`aR6b2a1=lBIJ~c7`9fkLm8sNkx&|k$k%_elriRo*gAZLv_BQ=ULfX%! zU)>=3GN;|L23Vo3r6TTCck$b^wVEye@u(|r^@rQ#|24d<FG>B?WKMXIoi4rNS9kv? zZRBE7HZ^S=vw;)CDakdnZ<NMf<M`Zh|Me`j*sW29Ymz#Bh*YA+D1zGfP=supQ*0<J zh%_k#4d)ZP0D`l<RF;CF+ENkW;v&V@7f%BD^G~DG!af?eXFQ=z2fwxfNPLCX=!!OQ zoI-XcS^{oL>j{Y8xND8fMn^JDN7`D_Kw*|T6LZjxNV$AWaBIGDu(3qai!3-2g!5%; zWiw(yj*U#%vKw{Exqj}Dg*SUyWzkRE9!wQB&>T*&CP$m7A%U?LHZjPI?{(py&mC{u z^>WZq#`Q@XedkvBhy3gFvj^|_E<UaG8ns66Q!$+vv{&E_2!@K`K8O|R$GUj)VTi8< z3DpObxDpnvcZ?YNWyJzyj1gIVp(rxs^RXA){-9_if%Re+8(AJQ@fTjmDYcd?upIHk znlB#bzb|t&bpE=W->j7Qd~RW35f9NmV$bb5_)I;Wb=G8P2nlCWggMO{D*ek>QEdh- zD+|7-kgf_ah%#;Po)`IiJ*B;&p}`htfd!D-$K<szbjH*iQBLy>4IrAMh#Bh1+#T8@ zZq*@v?GePN@y~};`Z@9QxUR$2qAjp3dt+~h6O2!_+ovp19;XIFkwJ&nhPUZD`mplW z7s`DS?gZt$4RY4onq+<tmI#>>R`lA&A1nbc+q-54l(@$?I4h-P%za7sm}Z0jtbvFW zmvo#ORFowCqiJuY$<gY}H|-|In4}bINz!LN?S606rRG@HoG>m5zTX-QDOZFPP#rq3 znrW}fh55h5KE&X>wJzXCj`CeC-Ozu&yD!D10G{vPKd5WEcGM}ZJ`PfE_wh5!wK*YX zu^)fnEx5J7;?v>*b>rqs59)G|oh+6S{vI?%l|S(msm)^#!PA%6{X|vF1wFsMh&e&n z6hs;$i+@c288%2WtskYw_Kjv21*JFSK3}l3(ZS9x(C<BhAB?jF8cy6|3kw~UtbDIe zcM79UN#^k7>rA;?z3Ykg3U{>Sizo0+r<Vi!-%b|@L8PpD=K7qEkBf_j;Px>s+Z^|; z(CxdF&N5KSUw2=8;axw^?RzkKs0AT@!ErbSWdya^SdV9Ud3Dl2DBr_P!`Vo8d$x=k z{UX+#d|+)@^o)dAJ*f;SqemLFq(~MG@<3OX<9Q<`Mj{8`SL{ug5tyCfgu2!A;Y7}K z<l3<c6Ir=FDF{0%g8@wO6MB#FPf9V7p-0QF&L>6Qdb{?l<=Ri+GVa*mowACWt)i^u z`wk8<%_#0qG!L6kWj*lYP7G*g!{0F=!I3JY6BogVr^m)BU(vob!+><*P5PpC90-#O z^-zS(9S38~S`>$SB*?qIns}eDQEmne9{<75J8*Um2_|+h-G|X$2WMSG0Q;LPa2!Jd z{GX^9Y9@4)fm<)#I%`yl6r_|-Br`P}b$=d52<mV5ltAORzcsyPVtu23gGKEMWWtgq zWk>?J2h)&(l#xThY~h{rI<cpTCZt=MWHiY#)9MLH>1OEV10A5k{Za99SN8_%09xWk z86yktgxrip`wn@jC$@Tz6%<P??YP%*hpv>X>F)gS^`O)H!PRBKyRZ2*<E4bU0KQcR zpFg%g%IWR-Z1bdUl0WND3MN@Z?t#ExYX6f~ur7`k?v1k{o};u+;Ysp%)cI=d@%peg zD?juWUVg5LhD+TD|LI<W9D*!exUdq3VcL3|>Z_vl-`)^{+o^BG^6+OlK`qXT*uQlc zuD<DPu+zhy^(~aJp(ktoc2VVS_yk**zf-OzJsXwv6EzHS7}hb763vk3lkXN5h6>C| z&hV%h_7z;do{IARBq`c`_oY2d(u&?%v|>VlN__hASF~#g=|brKW~@h0hgRrsvnQn{ zxxt(j48>w#K(qq}yXnE%VdBq_sC72)(4VxWc%=OzDFdnI=yX_t@O8A6aZ2LX;)*WV zQ$-HOo&sVk&6ky+QT*0fRgH6OUdQe5=VNnWag;VW+p0?KCRqq)b+bxEiWMsNESk~F z4ErM9$>?h$U?0YuA`oKja35nexbDf1;Vx0+@*7{~!_&K|OM0Of!w6EEa5v6%59Mfm zQt*q|6Rh=wZ%kvjIdRItQUGQujDt<y*Zgm!$OABKVxf<)W}{ckBLlgw5>u^QN7@CJ z2^@{mytHB1TqCd14vFx|qwhHCd>-)eD$>aK;lj3GVktCJlLnfRK-O$@+zPqmPAme4 ztaU2gqDfH&L``LF7<%|rHTGo~gXp7BIBCbl;)RaWf}=pFyJw?l$?*e6i#98NmtXHc zcVxUeoy9?+2VT1m_?}S1-v8-_|1mbExCrTpadvS585rbdtpC*kfI*MMZXVY?|1m2E zI6-Ji1q{D7eeVlNkIe|`;1bd0QDaD;#n1h@;1(xuokYeA45FRJg03?5ph({g4&n$= zP1T?NUI3Z+Ce^e_;sLrd-(~3yYyoZTpa(^L?K7(s=`X3H;FGAG^=iy|%NIMm{hm|F zG(1!?ALys{iKSRYLYY{x1?7~$B7~fH{3{vp`3;|wY{#}5Jy&9@#B_pr+36lUw!6?4 zwr?&eK>Dq+S@@<&8cL<T=m6^+at&6k^8*dX=Y9RfyCtiG(4#W|bSq)o)lC*3LwTw} zyb@y;quSospiS%8%2qZh&mre(h$%Ix5o_P{peCWiHB6{fAPrxjM4O|%r95&v8=aX( z_|-V=4Y`ETsf2OgqGLv#s+`w)*LzCYj4mOnckcoFOHPA#Hmix->zF=it9xPjQ6LjK zQUs`kZVgx_{D%BSiXEBKEU8h|PkA2Y9{KCz=G796bGBx|xUuMW&?c}if6{Z<V9P(u ziDF1I(sP15&>8?76_r0)kIHQPc3eE(9`=Af?x{1|QhD#iIz@FB$A@Rx%Y;K-vtmAr zP^eS#TG;aEHLWa9GOdv6Q{WnMS80;df0-K|dKGlU@EZ*~k9GE0%REcX8KOPtrTX;& z)aF$tPfdSG8llDGjC)D~j*)g9-XzclzE{AUXGCWx#Tyk(3}JlFgMUuvt%hXiqoeB( zyiR=42OGA!*&-|qDcr5MTj6ujXXD@iDha<dE_+}7zARVrkyW_l$oKh=_mJeT%NhfQ z=X9%wgauZAngBg00SF<B{CGTeOgcWWd$0vr0|bqJv5{B^)0_o!gCwz?=16(b0qKRj z78#@j2`px*U2%HiEgauDjAAD3@Ol{BtegRtDHI^xEeTq7tb+1v3J{&W0~e8HPufW7 z(>Z27)8gVR)kpqBFwbr5%vcuP@2kwB_xRs<00`VwzbQ~*K7S{ZzuPkFo$^}4;LYM? z%9ci%$OBj!r3BwC@YYJl)_Cb_v(v912V}N6ZfOGohLpq-1BMMgo5O87O)azNV9)<f ze3aq*vcx_iBWfKw_r;J(=FCSne!yr%2d7`D4bskLN5${+=&Tpj&HDZ8nvg&PYcZ+( z3|vzpU0*|{ilN&YLX8ZE%w>z6t;v(3R_B)BL3fUrmdvYGyjF(36zMj93>wCRzqjJk z{)llSwt^U1{QJ574so$yVkQ3%`v1-X2t)#kX@C1J{wJ`pLS?f#zzK8N0>Ao34mq&T z{}(EA;B?3?HZKghV!_xZNScjw=>hOdPn<<5M%^e&9fYR~VN}h(HO9EgR3K4R#>}d^ ztQj9v28f5kI2=gkenS4Z1nx#?S4Z;L3gR(2A${z$@|x@;Tw>SFNzAqJQY|44N~hNi z5929(|KoL0{?mxbPJL~MB(bjN4|&ATvRFF~#)0@e9n94DglwhO3HN_Q85iYk9-nuZ z{j?x!!t}M{p~Q|!E-Hj_VasN<%_Ae!^5n;W8_&OGa?$^T6AGKI8hs$>U;O$O)bIZE zp5RSGkK!(^DO4J^jbV(G1#5Q+<v1x(dV|p}$rv3a4QfX$t4az3V9$H(mDI0Y$Rc1K z(|9Y(1XG15gBpP(N%xcCi-%Df`s5P4N^|HyWU#bCj$xj33<|W2jTU{-q^L#JW3kgZ z5IgM$=otV&#6y(9(CN~8VHlEwmI#~lX#PX|)2^aOhbFiuA3Abms)$CPiU4lO^iK*3 zyh)+l3JDHOKJLfsGNYlQ<~4amx?7Erwv0~?Q-YoJ4aRC0kytsR12nh=D9Dv<G_`if z9V#;8$efuO8Aa{wdMo};3K)Z!^YniyhI2iucelql)nOLQvlg=hdGmy$jibz~?uvX; zO5MLu?2adEdRd=;_ugfimzt88X$d^v{bI*M4D#CrVH8f9->}xqMx#V1Gud5F6r8(h zG?j9EEarl@bONrHCHj!7$FUt+=k*(5d#`&C+io-nOq0bC+pmxoq8|tby!^P7HY-9( z)S0LpYki^`=B6%gC8wL5lfv`IjyMAc@e&=41|g}0VfSFpRaFmw7Mcq&$d`Jvr&fvD zgaHQFKAeQHg=f^;Ga{|Oa(Jab%@|N8%ZwI#5whFR!5gC71YhVoU-s0uNe$QV|J+H@ zakj;1|Km_oH2du{y@Qpltt7k+BED(&zk>&O;QmU>I|QFax8fikE!el-opGV;Y-)5U z9C9z^OHo`rywC^AaPeT`Q=Zo7CRxko=Yfn|!r%KWf3gM%T>!yhP)2|faSo%=qP*gK zS{;~Q3l%hI^&H+7YmPmp0G}AdZcE=mX)+8pfpN9G>FuG?0O*h?p87P&L56!87|oK6 zU+k&%t=C32DIl<9KDz+SOEW?S6PWQkNCCE&MWbh++M=^d0zSmzz`gRUo8TkWg@rw! z;qj#1aixtC(g<FhBpM&gNqSg_=m2PB{bGzVFXdY=5mVq?T@{FpxY};<bL65=@`#9t z)B-DsQ62yli~HW^mYT3S6?!ddE_^jZ3G^r8#j)V1Hn`&4$M`}=%LS@0$AINEQK!L= zwZS!^CuG%Yqw^f9Qs!tHbtb9-Tv_0~PYpb>!D`ASi~XpG?{69ZeSb}lhf{?SGaYW4 z!WPBB9dJU~sN1~Fi7YZ)aA|RN@m-K@Vj2cDj<?({o$4ma9Ms51UU!&Q6#7)x5w1X{ zvZaJLGJDr^FG5SkCmPVgFvx6<)U1@=A$`7S14}Km&~TNuzprpJ9FPdNGw}EjP66NJ z^iF{>bsEh2iJc{}H-G<E6Nr1oInh37QLoi?xH|~W3}QioXn&)dm(HTa%t`(Yr;7S_ z#!@0a=idseK6g(kNXX6Me{049L`U#c68XHNvcalv{K}(|fB`MfB+e3~j2ZTY21S(l zy{tOQ7144pw)7T|FOtV1ex#0zCIIh*Mu4^J7d1jd4owzyXriW0l1K)EMLrAW7=`wj zR~nwtZ;2u#X(*ReBSE!5xazGT%q_eJ6N?Xrk%r>9bIj;--R2e_awO?C!KJyT?)M0k z`Q?E@@C<BXLWDfh>#)37X2fa0{AFb%vq4dRWo#^C7R!;L*xo18;2!#5tqdH8l;tW( z$C>CpnGY~hx;)S4@b6QB@xb!xYQ;qRDiVcLnUpcKMm^eF4_dVK)b$R4-~ow-x3H`# z;ZeeB05KZsKJC^0>4n~2-hujTxRq~Ktzs1h_4}D)q&2gAdEXzehWIBqr~KyRJ7hLc zk4RukKX~bUtsT(@1&fd#NN?f%q)@R$4pF#S3#bA~{)EjkTF^qZm&KznMJfVtdPT~S zo{)4+bQW)-b2}ol7T#AXVYZshEn|%D3Mbx41T$<d>_&eu@mZzqEb)<?^ks&QHOCgn z15_A`o=G2?3|DNjwxD*F1;3a2KoQg|rgMH!0u!&)P<S#E>k)6Su{`MU+vMSL=dVm| z-m(qSW=Mc|+V%1kwO;!_p>Sg&B7WoJ;qCJ1&*)px+~dz=pD|H&b(%fVmEZ3X)(o0+ zCTm~>aisR*!;EpLg%;h0HZ18TjXlXQz;7V*;9+;{IcmZ{$7yjiAtr{{OA(2EWU@zP z=S%BTL7U+jD{-RAE($p!vCr*&gqsDb_=|Jte<KB{0h4##L(8+~K5Q12_#YRN@}gam zv+z1zGW>~j?B$>c#DuNf36~(t+f;TUMR1}cH8y^CHfT5YsE%1OMSn`x7K)j*C#?;r z{rL*7O=l~7cCp=PFBSZUI`oLOO*uOdHnzkKn+o>*trjs|^_HB*wBifF0P`Rb)&)E8 z_54vvK>^yFYB)L%buu~z|D&rGv~-e)MOV$DU-`>qv;PFoZ`wy-BfoAg+$Ul}i}xd@ z%#$|?6DbviuvVaap9qKm5EOhpX%CZQRGFuAWk{fD#}f&HOUvI~w`9r`6RP~M`DN4@ zJ%?muWTWX%(Vji`snb;RGhcZ&Dx)gQAjy!>sPrR4Qdiy~kFjTM4B2<|Cpx1-V6=77 zxV<g$p%lR-ewddYbNEe2*=USUBZ=+Q8gyg)QG@dt2YHnl9}<@FW{JtixObI5WJz;$ z{UpLfW(XZNcVf6#<9owUai-W~{!2yK0M=8#IR^+^AU$7fR&x6-yPx=NKcgBPXj^a^ zC_?X_oD7s4nVx)inVRFRTuNfN(+uFEgmY@5k%8D#%vI4g*PF=*gOuSuBHhUp<bm=d zrzq#uc>)juu||sIjE1y4f15AA4SBRWLFo`f5r%L%3j>PK8t)0e+i9Z&vt?WyEFmBm zrcI(4?Gg%gCg7SUPbo7G5r7neqv7{#U}GuN?F(xoX^ILfY0%;q=d#8gDH!K{*K@z) z*k%c%e%m)PmZ3&skp1u{+MJM)CtEPj)|)saPe)I$%95u8BIcPzW}BzgO2dUt>Ns3u zb0wV-{lnibl8aP50)~Gfz=23b2??FH>&mTgw}ob-Zk&Mp^2293O#(dMQiAu^yM~iT zqw-AFwe)Sd6L5S4ki@Xw!y`^VCl<;536NNNe}&Q8uE;Tg#e@(Dbz_l{4X$8hqp=We z=+@lu>|nrE!rgTMkH`$hnoQL-h_eMvcpEcU52QR`^h!upxT%lOjZz9mKbO%(!iOMn zq{3gH{gM%Wq!|1-NXF#|`@YaR90`z2pjQ1tW?>@kQ2T8G5Dpype@wk)K$OuIs6BLd z_W(l)(j8I?LpRbT9ZGi$-Q6MGAkv-E9nwm7ch?=yx#xc0&-uM)zbp1y&jTAy{UnO1 z$jivvJYg&rcaPwWe3q|4L$QX&hy46<zR-S`IXaQSBL{u7uVB6Wv%KuAXRpNZ|Gk^H zV6U?&%fKRlUvs0ep8dDD7>r{4tnWUf!QxYrTt5w@Z-P>6MvrR`F29|<!D-j+*a=Lp zQ4^?Dr~{$``^0QjYvcX5LRi8gJbk`Qpa(HjVwrr~^b8f#Gr3?DGjgiv6bFexgENJw zOT8rKnGjP!VAe~>01{gNH0=d>1|2v}pi){@AejpLvfeq4>H}8KSXFDIo(>`3aD51= zJ5#S9TA#E7dP7b^;~nqNe)v`b<Q8%oL(L>Ba4VPL^hXwDyfT$KZR=#Q4lkR6gPE$x z+`n!O7zox$ES+lQO#6;ircW4TNWqZgDGIV5TQ@{s?b~0OK#SmRC}{H$t@=<1@8v9x zT-{XT7cbV99r{ze3(XPl)=3ps)$Sy>=kDVswm;zx8kV1odB`CMMjG+maRL4gUq+%? zz<Dlw%Gm2<Zo~Q+=v6fUDQ}WSf#gw6!}DXzS1q;*zgwl5z#Be?YZt=AjWu;s6DmZF z1pLQGW!ngJ6X?XWh3p6IAKABv#;b(Pa<UPJz_j41_80S(GyhC8_fpButL>c8?iz7^ zCX`XQoaZ3#BeJ!W+Ex&l(8HG`<!?N3@C6~s!|>ac-_S+VYSJ<{L+4bGWf6L)4G8fp zdWCwHp!{P_Rd>k5M5W8Xrr^Wzf}iyK@!OAMk!Q+14D9n=VkM?1sxi@Ab<194dIln7 zz^a0m_c@vBbLNJhkax~rE9jI!D&b?|X@kwe2ppC$@W+oIB`@>%N;BV2not`47Z935 z{sUQgkTj#awF;f;redi2o{L2DTD^od%QFiXX}|+3p$aoTm7if=rmYg*AYc{lFhB;2 zXBm~vM67B*7IzQtPg!-Z6ilC`!Fi44u<MD~RqS8)I!jvgZEQI2g<<=lM04~tkf8>M zEC~Y&rrcpXPRQMMo)?T-a<I+-79NVo{*rj!u+))4oT<Hxlq<SvrC)(Tnn<9Fr%Xt_ zy&Wp%(WP7cQxNb@U!<huZluKT?MSs|8&SYNrIG3+o_6YTyE;&na%Z|8mB_cHt&wuB zj8n|4ciqSR1S(-&<H`nw@4BLs>(ZXLOYdPA*v}%}I-uY%zPc`|Euk$TB@=Go;UlfV zb?M&Owbb2eTsIYGq}OtH0)j}@BbI@MW-}}ep~tw~b$veg%c<n>-Wj1%7Zg{KC85HX zC|^y<Nl22vkS)k9h<38nHBlt?Gct!nt-l98gQTy^iR0sKNp6M8Q+l+%qcfO~?sv=E z;-W=EJAkZ|mKPgI8?BkTJMp^T5(REBE>GT0{8F}bF(c7i94TMM&PHzPbPCIhQG*yF zc)oF`hI~anLBYZrN+tT4U?}<!!CfG)=zZN2_yvm|m$O&<03^_hShs;Kd}z$28;&tl z50$Xv<uIwys2Puhx=FpD5)Hm*9e8cQnYi)XdU^@<$%`ann;$oA@emkSTJt=5pSK`= zhT4A5H;7k(#XOn)f2V!*$o}meO|uLoQfFIz-J{@(<5nr<>N#EB4+?HlA4UowhVN@d zwUoT3LZFGr5NwL#vcfd$<4EWeVn}PXz*p8clBLXwH1||xL9N6VOteq#Xx1$DtCGzo z)uH{vcM=b}{o?-~JAsw}tV#@PL|82K_c@We!r<IeFo;)T|7e*VWYe2zwwzjFwt5o{ z6a+feP<!k*YH-#+QpkKiOeU?T!w~=ZVxL;bcbY(Q^)ocI4wWgiOcjyqz_`*X!YJ=~ ze+oEO_$~=lc0mwq*2u3Fx$TVOZ$E@2zFyR-fq5#Eu;1+eB?30*&VKLr9}gOAvA1p_ z@hf(Q_JX(EwlW$doO@L9>ZLoz=cA?wsb;QWH+(e!2(M6!B{0}Bwl}>=Ue@trv?@G( z@#7uNg>lBRzoms@R#M>4PL{Km(MdX=>p1zzLKj1}Dm)Vx(32!P6UDH20bY9eOSJhH z4`qs7c%zi`e`QHSLC5itcHAvOq|WwL>|a(VUGt&DN#XZDyV`XSy%4K4+227&)g1@* zo8&O$1$)BT{Q)Myf}76#{uEA<>>F(kJKt+-@}<f{LJM(U*dwI6zlA$rZ*<a3K{kr= ztEr<Q<f!tuA#I3pA#9@#5dqqa^({D-Umj?S+}A}cU1iDnZSua5OimEoKZ#fF6Z%1W zlr#V4?N6KC7Ef2&%=#k;RBavi2GOrbv;~RE3BUc@r|517{Lgr2(DTN|E{(oY)bo;P z-PK$;gb4inN1R&~2Dz1t;M`eUppV8n)&x5hNZS&4#Lrz5sr&=&iiY2_=NZ2sEihhK zts1q~ctwh2UWi3|26Xe*dp6uUC$wF(XONhejef|4Wb9ueSm}c*d4!)=@l7@}Yh1d6 zgaryD-4KS&9=YxE(pru9ky^HhXJu|f5wul0rd6xA%c4y`h((@&I+m{n9;olK^*Q{^ z>9zAiwZWPCHj6}xWQx2`n^)7i+pShtddCpeBOv!1<T3EGJzH-42ZXD0`*?iRmNHvt zk9Hyp$}D{fa?NIhNA9@g%Z|hnwtv$XmI0*W{Fb~dL25zgjw_S}@#u*Ta^%T5#6{^c z2FHg8X7LYk)Ba)?N6Qo4$rU+V>{OV4y&iPj|FKZy?T&5kR%K{Wy=x`5&?(-9f`oEl z{~lR25WUZQ7+B9+ut-j*OBlExw`f#3wIXuMWo`Q-IrME@HoeI-gj~c!&-Wh7j}0p5 z`E&xb2MWi&?KBm-DB`to(PLF>V!7nDF_ml(zh{;Mn@9!zbzBRqy;x#UVXZGD=8C@t z%*(jQXqzC*>MC=vS2Dh?{*M1h$a?$K_DDw=_#5xJU<?0iZ3TPYTH*(jdS=Y8@OXx> zVc1!J#}9I{_py~u(?5P**Ng3Yf+~u1|5-2R*e^QWO%w+o4?Zn@|L?41H%}NuaVmMU z<Ds{YN<U<is%Y~_wSM%l{TaEMt<=5{H#SosL=It$<x4b124095!R8|+vT?aSjq!St zqrI~7maV`I3o8alZdGMurrWpJgm5B8V&|9M?;svLEx*|*_4hg6*Ypo}Ymc>hesYmf zL0)Fuq7WA6K8W`$i}=)N&ujRR(67IB$Twyi#=_j#i9c*^N0>#|7*C$OfbA*9-v_z1 zUxz2b&QgiaDq2P1_&U509-NnN9kjzetTIy<a6>A*BIR87&Y+&gX*3;&DIAIP<*o=n z;=flP<%#bP1~q(qItDzPggR<s<zfIFdwc_uJFa&cmLlp=kidPeL+N`u!E{OsJ*O73 zoJ75IC2A~ZkB{q=2#$4I?1bf?rlq$Q`B-9o0xt_*5(a%gGFeLAzWRwK5p~_X7wCM{ zDC>JQLE#3%)JC&1^zPTe0Uy7oTg_1FfL4YHW(*tj5EGnCfjX>kK*nC6zE#?ynb9gQ z@j>F@Jm<q-zOy8RCZ2Hh;O)0(zc;s~cAvo0t3IF6&gW#dAxW&N1XN4ogI1wlMH#!; z7#?n7OzCx70|_IA1(C<ntdAK6?LL$jOY&VHNjP@q<9IDg;-}Ce@sw&xY=aZd^e|`F z+YOOX@m7AT?qTd0;uxzK%Y3vyAIXVb?!Clp?RA5APA8DFpW^`UwQE2A)7tAmRg#su zO^O{K9=U~|x{o%!sJ{JQLb<;Unty^-0&*S0$9~gc->j-1nC_2%Bv^jQ^Y0L}QkZu^ zyy3LN=&e8k=t-bJH6W<W8*hj|o83~?+kH9|mWW4A?<kM8(*tYc{lrU5^}dJzf=yn^ zWc<JqMy=bRjK|BILaoJ>xcgav40)+e8s#~=)5PW9O2H8+4;7YxNi4JNjs;h+-&?it z<&Kc)M80Qw&9SET^?He^+#VB(aYz^W%?wZ9q2FV=aI<5l`uYb%>Uc%Qea@^=E=JQ5 z97A`c_8d3Y-NL=!MG^~yjSR>@dv7S=x2*V+*X^+in}MF6xcGD|SI*ywR799iPvw+1 zReSUHk;`WTZpt+l+A^YF!GHEbufO|bz5qf@xpgIVS})9jFvD0aFOjt?`ZEn4b>8R8 zqyp`}frabjpqS{?k~r_YE7R)iZvdT19PDUra$3_-GO>^5-Bz$MQ|kP-r4SybAtVvt zx*s7tOQ>i5B9`qA#lkQ{XSIY*RSq>pAjPF&*W1G7F`AMb+x%R7{B!2pDf1=K+H2#O zErf~Ta%wx;uY%TH>PqYOeMXSu3^jayik^E%rTcwd?bSm`A>z+e<=E%~c4oWKCCZU7 zjUmf{7RnOy+wEc2@CnobA#us2toxx&v2by!yD(h&XNvnUu_&LM673ae`k6}#`pPm| zQ{#DKO{e(RJH6+P^1!XYPyItatk?f#&)94HhreWT^o)fU%>U$&@$54m?)on9``hTf zJa!n3o`rwia_I&BwX&31o*7CYk3DQ=VdxuA1!{P+$)m|eczQs$u-^KH!m{%%<y|4@ zI={dF2FLw-g%x<Dc3Hr2B|^K_<>iCNYdFu$(mX?rZINeA!FjQZiB#q?AcN;q0m?Au zj_K2~<jkKr2E+TqciPpJGMe5y(4hs33iS3XUNGSd^*6uIP0x?gO5p3&BcsD0634Mk zn?w#;C89wqY~HXcOBQ(HPFzFr;DPl|&%->w)~qs}<ze6jKV7hPwJ3j&A+z-4GaE^g z@N8@5My}>FN>)}e-tX%CvmunvsAPe@j@kapAB=o9>#G|5QBBc8XYX(1Ioh6iElwfM zF+oZ%eN{^prNHfO=4B?;TVNEq5DURMD7BZqLPIM@ePTRP<rX+XmIT#-xFpCz<vF$) z=sRK`;Z2!zg7c@OWp49o)E#4mZkueEN`;?`ymqpsQ@}Uq_r++@LvJ^MT?sj__j@x) zc>Il5SY5ZFm#Kai@2$St4PbA+O5r%`#u3eqMq51S%--00r}&?5A%OI>8Seb9{1O6x zcEBPr_^A5(lS{6hQk|rj)*D)za23Vs&{|qc8}qtf_A#Zu=c?~Ybgn@sT`IC#jc~Ov zCLIz*DA$GMKy$!JCgUfKjOF@ukJ2Pf>G3feDy*jilM_LAtO|wi*8^2`b-i>9o+tz{ zFxxo(fl$^nK0&&c=}@xCJ!;k4DZ?k9uM)T?-gQ{Q4-B908B&I0aH&mg)0xTYskZ&% zA<O!yxxwJBi0e;GP(`ePTyJJVynw9`DA>IJooh{4y2cL;L7Qi?*E7tLlV+#Etk!Xk z#^ZSHC1%X<10E?Aa+Jy`nWU!_OmqObaG3G?1Uz@@Uq!f%?n)(<z77>x{EP1|%B>tn zOGKH6mpzj(?uM{sudpXve|RYgVvz?OIc8wDG)d+?cIpW#`6o7N2_oL7p(~w4-UE?K zIx1-(!qm+g1NkrRdZeVJ<ceU$Jq!_%DP%4FZ}0)%`u&9VzAJT=thb?bs-Dz6?qqAC zW^X>_^9~omtw>Of`2&?RWiwm;cIRH7E;7A6cAO3W_Pfaetu^XeSKmSX6+TJ`;`v?= zD%gqQ+>J;_F;W{p6c4{9sBI8Jd3*0W%oI5Bzd@K0E#t&EyN6VW9+?R7cc$+o9&oJm zmDwUSXGfDl;Ikx5p{v`kpA38t48`MGHJ+N?r*R*s-d4I&=jT24pMcC-TnL>?I~6ek zupevt-0VU0?lQM`t=f(+CwKY2f|=OZr7XgW#w)Y?95RKT;s?3@uqYC#$*-p{*pe~Q zQM#C(6pOOq?3Cb7fgh@PsAbO2xWSW-TMTRbDb0S1mph~VHZi<*%b>wns?VX~{XrvE z)ze1*>wzr%2S@mE1&{hoa@Vg^*rBz!D_!RC(tv&Yp<U9USd3p)8~GwBo%oYVZF60A z$|vT{-}!+k#1VLiP0oegNnc{^`y<W)S;HuP&Cwv5T6eQL@6)a>L!HkPDe?P|LXO{x z3!{1k`2Op|9npGld5Hm_G>Yhv)+RRzG#6PZsnMc?DkYhRfFlGN;C#3dE7eYD9n--X zKXuErI6AB?eS~K(H$&k;LPU@)stj(hWL2Nhb2EfqjZDfRewmA)5eC0Q>M|ENbkSea z=OP1TBy6Ep|G7ZM-g2VAw7Pq~_I{3Ow}JU!i~=5?An>-*TG|a`>*83}2w>Un;r!(g zhv_XnoBjHB+<^q4>`!L(d=>VPvPvpanb4NNjX(}Z=QN75tFGx;-HYs9ZtLu9TfOmV zyYo!75Iys{6|Cmvr4NKj{D_N8LWi$BArM`NLTcrBfA!L-rvLWLMd}}fT`<M-+t2Ou zXJP$0mrlVFMTck#HJYh&i5C_FedfV6-_O~vw|qP2Pv5#t^c$SdgN)x}9{mAiEHRV@ zxxsq*CPSzH2Mcvg&yT$dxmPtv1AVHisuF{0KCq(NMC+XmD5RpqExK;8XT_oSgK%w= za1x(ne)<Duhuqiv126Xrl!i|A7nP7Pgz!;^L|^y)hSqx|v2)6cEw2Ew>L`6ht|Swm z+ySrgXv-X^vC_+-z>P~Y)1hXePR62eK%rhKh5X9ieL2ih1RXwesCtDaEvTBFNe7R> z4?jGAyy6R$<Y=hvoHCX(jmZ1L?PP(hbNYF!u4A}Hs`Cx#c-9;Q?xmU63ff7ZS*}LO z(dOy+jq5C;huVy9&$O<(9+3x-&Tw@hkJH;z%|$>My7T5f`%QCC@@;~HqVeOh(z<Is z$9Kw5c_g%Xr04^ttJ5r&4n!go1th*@(_eZ<ioo7{PI@fj49MYkq;iF`uBSZwGiI3H zG=|UmZgr;4Fjo=XD(vPCVAuRbqOnkI56+w#WWI!=M@nKda=o*>ln3$;Q^jA?B*qa% zON118*+0<9xHe|pRgs+kwwg<sT;gsaG`=@cbh?HIJ7!<>Mf-P5l@-*$p@m)OfR<-- z$C^nI{FhDvkZ?Xi7_sssywQ}Awywuuc%>8>B8Wwm)zwzmg;)kVG1e9uH4`zv)Q7u{ zH@XgsRaTo@O|Tg#s3Xp(Atr$qmTX&+iD`;t8UGI#tB;CSQ$^whSLhZoOZtOlAmi3I z-<Rr2g9c1hDhNB^uC2?yM83tdc6)b+21Cm94`|Up;vFRWq(Bx=4lRkt|3*5(_*op~ zmV_}Ia|N)EjkgZXb=d|N!aA&(jfV125<s%`V9;}DJpCnmOg5tYj27G$?_MvZMXx~5 zAO0Fqt?FLRD`Fn&Bw6i)$<7++#=OQSGv`&VD3PZ4!lND4?jndBOe*YWY=mVBkiK}m zYlUaL8l)Yh%|=E1v8$?~8(pA~GaK?*N{O72Z;eB;_2!_`ChZ&mKwd!_BTHAJN@Jxe z5{-ksFQ6=Asfy!~y91lqB|4|`O2Ya)Ntj_7135-aGmI-mtT$~1E^|rq6nhh!w!KAs znWF6P#j>wwIP(h&uA)*8?Z5p7f@|kbh8R^7oHzSW$Yw;EKEZ@Grp*7Cd{%A*dMvlC z7p)#5_+BGEf1vR{kruX<M_(6@g?FB#xxrY(CM5e|qQqQGh7e@*6uzJ?*W3BM_EFTA zhVA)kO{Vsl-IX)o8b^gI54W7YX<Ab;&n^quba?8)F#h4~Qn!qmm^G5{N9tvwu~rz` zuX+)JBcMObe*OlM&fwJ(3Nc^+Ms^eM8aQ~9D3Fs06nS)!P`e$%gKn8Xxr{*<@jBoL zZ%+GlF^}^eq?<9<epgcparoXiAgcX!d|nz#@CTUOZSmGu*5H|M+r&vBM)77wPl#!; znlk43Fq!Xr@jo06$%IQ?hl4=%*0)M{=4&QZ$8@}YiO>e}pg>Aus7w3l-<G=TqXnht z%qhQ@$D3C3$q-|aNqRf7Rgt#;+`jIj?j1RpnCU7f=vC~_19-fnG__8yK~R&fN<Erm zm>_21+KWjrauv&<QNZmnLH)iV6$hdd59>`<6t6Dz)jEB&f1nrWL|gC6p`}2AqLs|& zw~P{67)1dMG_W+XQH*B5EBW1wc1D7qL;746M>9Wv<cKtx6Sd^AL~}FJMv6r*+Rth< z)y)dFaUFd3^;TyIu{n~I%|jN))rUO_O>iGfBB!rjWyCx%=7gPVvHy5E<(j|4P<TJy zv>pG=TmOUi#bg3mSt@zhXGg&N@ZVlm<S`G1BG~tpSEVSIH#u*b=H7QyJ77Ci122bk za^{lycUWdpkG83nU<0sMX+KGHZ@FGQ&LUhl6Mnn_oZyH8S}}m}W*|yT^&e(3R`j)* zT+kVOMFYN<)~YR7vNgCeB4I&p@)grtHdnwXvzKm=JPPJl9=(G7i_vBMPTt3h?$>}q zxkNuVJl>Q4K1!wBCVeftA`FU+4;*?J94N2JDq(EU8ErT4n%gCj>}el*Qt7#&7GBEz zUl*&5nOxN8(|vlsntuIl>b}tOzcWf!fGO{8oA`I@Q~^=M57i(D&RjHpWp{6&wmYZ8 zI&P8l8*A&vF30iHW{-It`!}Q%Oylkaj;K&v`qB+LqZVd8f>gIP9a;*n$z)7rAyl&+ zV_Ka`E7;yK4JltpdNJc>BK4P5dk*&I6cjp$s<gR!59uj!CBd7y$!2^nc0zg)i9M@& zNe`lIg3ix2c9ga*CRD8q9g||pdWW8Bs||`gq-O|t|NO(lAu>uDxvBIbGT~(+ycjB} zEb=_kmz!C(NI6%@#968(I;e%jt=3`qPXd<FEKK)MWMfh^KZYf95|Re4Fp+C2lN)QC zN)sElVF@L>hM&5D`>l_FV?7F(5$R}U3OT-p>Y}+Aj712sLsI=-+9V_BGMc2@$*&?6 zbynem{3WL<^zF!4yUsis79k+8>+Pv4_2_4pfuo}%c1w{Q62*a%t&g_F36^)5EtB2J zOo=G^1C&DHo+umDT*&lW4b7z&cNoIcsmzIm$oM=n1^y%f3!+pPKsXWOQjH@!%=i#6 zw9G}ayQOba-FxFnD;<->s^1EBaHyG2pQo}qiSY@+Lp%2S?``_;H<A_X_y>Ayaxj;M z@WP(oc7JfhRvo%z11$P|IE~z?4utmOj#nJCylcp{Dtni)N^uSXy!)agWyR!NeJhDB zx@CJO-Xodag>-P{FDNe&jv(}UNstUO&gb?C)WwW(OXsub@qMapVR=o6dHIHs4@8|5 z4RNch+hO^jaca4o1`J2fMN7CY@_iJwW$|Vcz5+NYS$tcHP#=&m1ytvU2y~x6P4hkj z7Ap+>BwsK85EU__^IQk1Ge8<71uW5U+OIqzTb_EMlG-!hM!3^o{6rXgV0vNPYj@69 zakcONq6)OX;a`TrqX444C^<qI``Az~H>7(}^+c1pcl#goB^<8;D$M>SQCntaA%ll9 z8Y;}7zEf+0_;pVxi>B772lin8N9H^&1^c;RN3<0{LOdycJq(G$Zsq_UZhy1iykS*7 zZSu}ca(TIs{?vZ~C}JI?{epUY<&68zjnP7w2v^Crx)KmRE7{{foJbe5Oc6)iv)IC) z($r86q%)nbMmZYu>0`9R2(Ff4J+%{=q@&`i{1>}e5%f^?eDT-8+k*doupo2?sn8^L z%eR|7H7`}jqMWm|1xkk~95Zzwxe+SG9TAO1H4({IW6gJ01K`DLn$U>nw1`o`!}8j- zmJPEAZD3bp(Xvpncc|ugsGp6jskPT1LG0#--BS+cR7&a@{U~;nViqAsym{zqihlgr zLwtwg><H5IvG3fn-tX~<&y=Yd73(k1BY-7Cv&Q>uxlHRyq6^j`VnIklIkiHNJ9L;r z(v@9GJ%`c}k7~?eqI>~cFfKK9_}s#<7n?9!I#2Qp^M1TUrO&98Zf*q0xM$9#g>3yD zF#V~(FTvyOwhP3K3t+-dsQr?Bxf*$7x|Y$4YmIu4{RyUCpz$~8&$~jtchlEFaab&a z&?hEA&z;A%;vo%Xq8syqT*hzcWV}ChT68dv*JABa5a#}g)6{2vW$4%&`^Ss?vETr= zES|HxcQ=<SCN0Y+@m%K=>Y|<B+A-3{#gIK`auvD!NC!7l2vk1}a7fF8Y_pJt%p&7q zMjTu2VXcp{c$!EYTLeMosg3D<V`8jbj)`8L?iOD97DZzyMaqHUG8d~Z|IX{b86yOL zJ#D@!2JYt(^aSzofrF7Eri=6f1-5DIY)zGUO{gfs*yPcqe98mz$84|Y?5&GcY8uhl z4Cpsy@M&|5X-1cB)?+YF3rU0vV2oP@Qh^6j6vA6|CV!Qq4PgO`mmYqJPZ4!**7@mC zG@D%dm$t{$EX(Qc5+~xwsT1oCnpp{;`Cu;wmHedFtl^d_I)sS`kzFB&{GyzOgT?JE zq*?3&z3@M|zZxkDqjzCMJ!H~gCquw=#J#RR<47NY;t^u4L(b(FYE&bM6L=OQK3zT^ zAJ;rX?*%1l0~_oJ2%;}1D#%R7FMqJ-eaE=z$hH36Z>*V}NyGe1FE-dSuD``jmYvSb zd6&ZEc=MNIb5sH`#&<owSK4U&Yjjd_vK-==%iBMU3iK;j_Ayw)n9B0S$DFKoJ-pne z66b36{C>JIZC=?*nQak;?C;~1@d^i?UB(M7H4M0h(+3C8E}I7T(;r7BiAq%+E+LNc zlMy&HK`)y}Kasyq)v)6}jVgt&gHltK+oUfni96gTVNtr$M&IJ-EL;D7Dg8)3Ksw*m zf!t_#=weJf{7~GKTmaBErq|Yv%cth}6E%jV&H^k^{Y4Bfjc;rOsqPcKo`^bP>>&as z_HH{&va=a3=)*e7_cEmN74bQS(_|K<?Bf+*Jyd%6L}*2Wi(&Q-n&x`SfbpB9RdLHT zlGx#a3gGT~ee}O{9ukD1ER3eQs2S)@L-I3O8y(5XrfW4XWeve?mzR#wNvmD%cIm72 z_&*orLX(PN&Jp;d1o%AY_H$)*-$gm~1K}A>S5O=i;i=EJRXOwZsHUnI0-C@*Xj4vE zM^nUvPo^FhRhj3jWd=l2Af2j;N!GZr>8%}2a2%}GDE+HmX*t67Yz?Bv+0FaKV;7#w zo>qD##QDo=VM}II?`BsdT!pGg$qzD(bCqdh8GM?%fB7j@mG31@k|DEojb$pnPfu&Z zhN&GtfiF<zaVnJJz+5d=)_`%5b-GyPUd@*FI`ur8FhWgqcv4ECs=z~b80Zgc6~q+5 z_zagN4$zmNv~|cVCG^9aJ<WHSQTBj!7Dvt1#jRHi*tHxlyN#`k@A_cQ=yG7!(!y<L zxKv%)yFXo^=CTt~tKL)xh^Vn!Y*cgf`F{r~n=97l4`M~l=C#X^&)}B1`$5e2HS79x zMHlHErU^96ou{jbWm5RbKiRCH4p+y++;-DDO~*-)@HKQfA7)dB10cBSdzJ%fcBx{a zhi>pxf8mhG^T`FZs4+;EI4@HE&`lMQrOn9;GvvZVl0~mqLa$m*KhOn8E3^L5e4IVx zqrrBI=rV_hnzf?f)L#w?k`J8z>MdIh7+-$sa<x-^AKZCRzlc(6n0KZZqZx0e#~@-t z{QkL+caG~t)-5ey@JW8thrXI9rQ1>eSUs6LB?Y|m3K#bb0-;J`<W<_XTU5!R$`D^z zPiejbR4bWpgPWxd)7{rzE{k$r(E(-1Wq6hhMYV-0nq3Wst52h{!(qGBShkpG6=B?; zu!Qqe<w(Egs>BhCrNRTmP)#^JChS{w8!r<6AeawPcNps*k{#|0ml$0>MK1uw!-vv1 z3U*$f&Qiq#p;LH}ZG3Ah3pji&KTMiicAvom0seTFdPfHB?;uoK3}agsG6YLdM>`;i zx>5mkprUV0i+VW3`a;Zh)b(dBmR+(Y6$+ey13>o3&q><yrC7CJNx!hkrO|2iDmS<d z`rvrfM~=bI&COl-7=n=~+t=~0*#1|y`7<ZL5}W-QbO7v*?LeV}&f_0_eLKs&>y@nj z>gl7_7ekEwheHHdau5N1${K=7L$qpDB(w@H93E%U7^)hG1VWV;=a3e8F`tOKr=<7x zc#2BGz#=-HTAvl_bk|-U&eugnZBKg=cr+uzp8bK`;=$lMb=C-@?-5vIU(o3X0vFTf zv65NJ6+L<YO*^V)YQ8w4+p-(AwY7zx*}$#qL*(-d3uqQ&P+fbuucoJII{2nNz)#iL z*)ndz_YcpPRz#%97d=`j)!*1~onQV6B}c}i(_)DsEScc36wgr#)AW<^4KKSeo4IUp zpiD3)@XyngS$PoOA~V1gq6!-6>*QUNd=L+j&!+DvQ4HK^RRoit^iait735=VnG^2} zRvFv)C{xCyh{d}FX)|VvO_?F=29OvKNQ3)!W6QJ9NVWBPJn4W>F<xc?JwD(oNrZ{A zx&X{v?cVEi)blQ1S3FdDEQ@n{mfv!g&Shb(KT)P%7-kCi@D8)KnqUidJek`pTP$XC z_<hnxsqftLRDnD~#4_DOTjD~}82wmr+hwAx;iN$b_gwMFGr5PPd#Ln-)Zzqb8!0Ws z*n@f#$1GEICs}uuv<%o<dkUGnR$c2KO#V8jFJm}!$ZIOs^$Z9(VV>gsH^XVhZ`Na) z`U(t(-+`DdC@enB2QKf(x;GgRF(J%&u(G=c(XWdS<MqZf@e(!(r!7qkT@1B9Bv!AM zD5i8aP(*RwiqWV^=LYSeu>T$zGv@H&-c3z4^i}eVJ&h2t?xe}g7N%hkW^f)y<x7m_ z6VC|JzUGlj9SwltL$=-Wm-%Abi`@tTv(RGh^#!Dp5#q=AgxSbLz2NDsO+XoubIIMw zTb?7gqHGzSD_>nz;7V-0YB7oW-MY>f<;@<(dzoMBA+cxeRXXLs^u>!A=GyBAB4^13 zL4d#5ny?Hvp@b|f6YiGr)(=Kk9|~TllxO#z!0wL%o8v<PNx0uAyOEUTf6Z|$)jsA5 zU!5NT^dXeSr3_xMiUR21+>axHcc+r%j8^&MJTlYOr;b-dB}3=KA_$}&>|GecxO(s* zIFw%3v6rKUud1@6veZ78L(hM{CPE=M6?s_m9Qr#^M!#eYx&0e`XTtmT3WM<!CzT(z z@|g??S%eUUy3=GVwCpS4lsT_a0kCGE!@fTd$9dx&&Gw4$Z*<bK#$b&L>14H^1p_6P z;l^1Fa&`pKzLmezArtK$SKGlv2HhEzoZ1c6$?{qJDo+?k3Ox4z|9a4$uzkTo235$u zh|Bs~NS7yevbOT8!Dn8CA>_IO<;IU_x(=nHba}1Y2ylm!S3`x`w7I?u1X16J<yo{O z>$l*EC6l@Bf8cES>)s61nI3Gu-^6f<WBnva7nk^xzSqBMNcs>lSDL-e@Uu2d3{C<J zIBkgI@Kst~vqh0W2Z%Tdw|9R)N21OiENr<_C5Z%PVkevMD*xlq_*d|jhqJqi3m^FY zM4XCqC#1QMVHF|W&fP(BQ45}|H$iky2v&03#Y~3SsMKF}<s$goC^MF?bmNDc!s`LV zD*YNhWy<WGypABCqb#ggfkW;~H!S#T<KOdcINY;kHE)FK6l5M@B_N!Kc&k=Uoa7(5 z?R05E*%hV$A}zyip=ebvJfkp893OzZcmO?jHZi(*9}L)2661OR0nhAS9WD;{L$D(I zJKW^E*H(D37XmQP=v21I3=+_DckE!MKpN}iw070mmaOt@5Vp`cAieZ4a~_mV`Uvx= z#18kwZT#M#I+NQSwGbr{<ycM}n+JXiw+FdU#-(Hyf)Ey@WxG)*!nM%{-`k56icsc# z=`hjgFdvFU@dQty;QxDuqSy9svr2hI1&_R^7RLVTe^Xj$8-_r}-*qQ}pZ{V#w{J;^ zQnSAY)AIASt^@PRS9~BDg6rb;&(ff*bkBER<Pj4PiH7><YR<`rq!7`WlQ=#T^vpV7 zqa7ND!Pt>ve|#g()}x_Q&b9=*+KJH66=}@WS*F2rUgk;>*)NL{OI`;8e|6q$%Hi6e z%fTLf8p`#WVzVXDVjn?JM;K-zij*@*@UZfApWxCsMMXs=E<yl1KBXiS?!*?+`3%cn zeHh0HJC6;)X+~jZjJktMt}d?TreKao1=A3|JxN|}O1{yDClsh6izP)iB?a>)^|-+e zh(=ZGEo={Z)-bBK;aW=97y&fb?6GbHEp$!V*9&LWxrZ*Bnq*xBmc`H~VaB#T&giWL z{&dC94LkXSAq$LcW_y?ZU6}K$jvom}4O=&1c`hyp);{NW%}Wews%Fye@}*r4p(5+w zHKv$><FpxIvHNLVHt~R2x4ay(<SIJB5hh|UQ@iwMcM%}Tu8FH4(ZaeYL(>^E6E^;3 zX|g$l86H3q)oU-&EcLuEN=c(UNV0`NuYZ#IV>J@vPQ~KSs_q@uS4tt%A#5ImPP;$6 z4S-?i<FsoPtJcZ?RVC|}CI50Iw1~>>A<U5jxaA!s-=+{EK7{T{75yP?0^@Yi2FHOG zy8!A+lFfmvFIA*8KB3M?b+QLo<{LFqpLn86F$@3Z6P3GATUADk7_O}Zq<eu=o~sAP zZr;1c+}s(N_Z;(bk8FN6NInci>S5tzD)pd-Tt;Ieji^O@?sF1+g>5`&K#=8L?N;FO zSeu;%al0J1@-m9m7Ev|ZnV)Col;I;^7sI3Eld<Z>t9jiHS21MAx%oX$s@8a>Z%ZH2 z#mc1^3B!y_(g9Tfh5<mf`8M`U;@cmn@Oe5RJReoS8H_d{_sv%B&b@*1wBtYOG`jQ0 z!8c9hl|lgy*glg(nf>C#zRe;4lXz2j%?qPWL56oeQqFPlYER*OXn>djvgRs89BU<w z5ho>4hR9W4BI}&AuwPP*d~2SOe|-ljW>9RLnqLPLm9-&8U6Vt*v=si4rx<2Jp?Dc~ zsYn!5Dld3#0Wt+dgr~3+#?`RhN;wjT;Sg~Mn2k4+P92Iq;4!`CKkU(Q66O5S;KSiv zs!E?VxxVOj?4Cdw<We9yiAOI#_2C~rTfp@=Z6@F)*xCO3|LX-T;afJvcVkK%z$J9- zE<x+f<y6=MyD7ao?MvBcj#B3#ChGg9Q!S?%3$O*s_H+=Rc`pg(7zLf8`gb(}cmSS) zz_)w*%&hWKH8cwpQagZTF`1c!P8`ZEoBLs5rPmH!rCRv{`lgWyj@Zu!o0;ABXnjK4 zdB^-OQM7pAWFgsv#hhlwj>g7Dgx`yVa8_G}juvJa;`I1gM)60Vk8}J9?dFj4WIi)| z^+fh8BHvHl?s3jzO-1Je`&<|c)b87P+?Bl1S7iI@nV1b0!a0rw*E6V**rt60?3V?! zntgGNaSpNm3@b%;oeV>cBMveOkNHL2Db7rZ-mBa@-w?W!F4~S!fC0Z8*9=%>*Q1f? z2C(O89uMu)`eGwWNC3=N;5f}?MGxj;rKqqeaTtqiOTQ(g8hUFR^gWg?XOPzO#72?x zsCGI}rkXOcwAZ{;e?RxK?FoFr{PWE@0@KdG@<7GuH!4ZreOwhIGd6_``51D~n7|0_ z67H=Vz%JKO8V;Y7GUXL}0BQLV@W=u-!J6Tuj*^X!tJdlGjb7?Ih?Ypks_5iOzL6gK zgX+lah~IG=JUlx3yZLDThg!1Gs-C9L7WYUqB`d-Q0R)}9==nRU)XSETx901=d#nho zAcSQMP))(2|GSRgg@%Sh5p7m&_?D5d@0VCzv1C2hkA&ChG^*N-?wxn37P{pmY}^V; zFq5+b1$zQW=1U<c^kSQ&bO^HBk$Jn@J?NeaE?Sr;Y$=wB+Pe8-DCl`e=q`w2YHq|Z zi}mMb;qxZLq9Cyk8J_e)2iKbKyc`Vl(LSAOYlF>blUr!Hz|wO1^_%^^QsM8#aeHu| z7R}}+#dPDuzPH#S%6J>S$s<3F#$nq0yv`MsfHg9b2I-NIW)Q_Pxbqd#_KB&wokMJW zo?|ah-(D@Obh=apC14Z6-2&f-agQ_3Y-LOHxEuQ$_?RB+qnV<{1W_e`I?00MaK-FJ zX~E!9-aY>aef$v8`3^tj?AI3>aAIy%I>beC(XRj$UyNqS5(Hoz;8C^(Fe=SZr97X0 zNcXwYN*8dW0cBn@AVaQE*B=8ln0LxbauPb8ZfSluJHJ0>x$`@zP_7Fk5V2FLETPUu zz&hu*3Edq(tlyY2V3I9bj8xUA%!_ykoY@{97^tO~mNvp9CwmV!LCyMz_llgPZ2h<A zl(xt^O?}<zcdfSUElly~WrpCPkb~p53Wci{jNh6smZ(_+f%}cNOEge5tfKYla8Y-% zIE)Zw{hS}z|9a0gzbE@a9)n<`ZNTQ}+vI`ofmIO{NmP0~f2mpo2%U9xa9uZHkafFV z{h;KxYtV*&Z_6~r`?Qeo9`pr+iv7zcIHA#QoRy+&<s$CvAXGe}5=rF3L)CSHf;e*Q zmAD5X6-}mimNe0rO&IkbxLRK}B}q-uB%#Bwks5OS6BILb_Klpu@Fv?*7+#hW>P{vo zC;mY<6Rh%k8EB^ny)fbE`76xfXg5E;__b|6Wk?du__Oc~8<E(kV_tLM(~yIwWl_3? zX3&*N3Col&BKZr^-qMKYj@kh-C}|cyLv-d{)23D*b|r>wOOweFdgRB5hr%vbepO4B z%H^429Wz{=zLn$4r_)5n+6{X0&^CmJWJ10$YW#W%!9kLxr@e8|?y}8kKfgCA6GcgG zW<=*-Cz<1zvqxGr>`tY|smBoIqmr85oB;_?z;V7jayX9Ps2Pi6-iYJZ)!3?Hk}t-( zfR%<Kur#gb9G$LAq2^o1D+N9oO<vcJ^Q}#V$Tp5uiX3PO)O2bw!?kgROs_t1n$z1p z#JOyTy;9Au-pAAM-SAH9-fZ|){$hw9t!3$X+EIL%<zqqx%`IOuUykdXgzI9Jmu2T> zq1DsAuZ;X=!WrHk7>Vyb`4i03%EDRJEz}bGL$u8J=gD0)VuB?l{HN=!W{K3*&y^8; zMZbB`CxvHzM@kjE>uEF!-%9+~8;ruY<cs@gQs@R<a%sKBETKG&mGhSih6RY>F~lZx z=#H5BnW50X1Zvp?`8Z59Zt+Kf07uE)$_sO|fjw#tkaDU1;lCz6YVf5I5JouM{1fKS zvXkjtNiugv@m&YhQm^6(=LRIw`uO=Q9iEFlVQ>Tspo?rcGI3Re+p|0?`#)=}1T((s z0%Zo$C}_+-e-Y+uLI|QpL&W%*!|mlVv|E|nO@J|zq{Iw;2$Y)$umL0h+I1MPH6v4M zVrJt|W0x>n5t*i(R3VJ!QbKi2_g%P1BsM}VwN*ep=!=*riPNAR=jA+E|5{5TNJ4;J z6JX;CuL`e+y<s1ywVNFE0MbiL8kf5p;qvo_Gq0XD$E8M4^xkvWJ_}sd1HlFY0V@V! z5x9#~Oem5V+7#ZLcBlO5UR$Qa0U0HNCC3a(-{UNDyfg_rW4Pm`fY?b(3uEzY-WQQG zNM5v7E-J2)K)f4oUm0t`VoP!#`Siu?K<as_Gym&g?V)BW`e~nsMZHE<4H5wnfMXyl zJVY<2KZ%it#*EsbKeE9n^#J<btUft8jS9l}OfCSO0Ownj3BHn>i#}0Z-z*S&bX$YP zw}DB%JAi}~#TvbU7HS=1JH|8lde28aHDnZ0N0yz_cz=9S%=w@%6-7+l;dM9P5Jm`G zYWLV(G<_mD^Js2g>t8VVi|fD@<Lca~wy4;buhr$sl9JgV=kHVkaF@VhiM^qmlJO*R ziQDWbO0WblmlVhJ%=@dztMbG|@uj;vi{x-l7~PW_1+63l%DcsA(KVW4Y*&H91Be&D z)a!$#Ofg9^ExgVR=%|~4#I-3Sm8}#=+?W#FtIFCa#rO;J`jjux?87iJaU-Rcu^@4t zWZwIYmX`TS5pQy=kgcLlLId$nV{pJt|0P@5*mt*-NiS#Z%x$ZlawY^txB;!Yh^q`m z<fbcSI-im7Q#2O!A0@20QN%zN_v{y@xaa`*4Sl%H?(R@3`Zcot(C_NTeF~d6rHef7 zraMS~OsA<<H6ZvuN~qx=@Y2x<{oA{BzQ=(d<JSG@n$!5+Eq(Xqyb3|#JiD#1{}C+i z-)$)dQd>}_MO$;H$Q*dpF1N96sOk-gO?o<gDnCW&yOC9=0{L@O;qE2!<3=k^npV4i z0icV=dh$;`w^Bw%lo-gv2j#k^GNk(}S|-w6i!1jrSgJ$%jKk&eesiBE*54Kv`n3O^ zP<);H9}9qQ2wm+ovC)jvH4DaKZL!O*3)+s7dN1iabFGTt$OgT^rug8u+d4}^;Kj16 z6Mu;ENm94v-RVlLNk6J~yL*j+6MBu+;%kqW*SPaP6Ua)b$LsS0=hwgd2WwqjRZn#u z+V-a6BwNiBMcw_f{;qH`2NWmr3q;J*e;r%?#r{@ICJ^WA;RbZvl|!Jj3o!w<N(ctD z=`6Tl5eI`*H>e<<XN+{a1RyRZLgK$f>Xr`-ABP{*_I2<27)uc8X5<%TWEAJ~*JOS} zMi;;PF@VPffJ5~=pLhYZ^xA&|c4bSu7XR@{HFaMhVsZ~5X0}6(s&-B|$zo5<Y-n6E zfc6T$tGaj>CK2GZqUu9T_6l8^(lvaH%=+6Q39IZfiYU2`6c%ngpKR41?pr4WE)nlF zy*_CIPiJZ4?rR~J0q3bc^(;CS7!~G-@#~0R!vY;JbYRISrx|;fcgW1n>Yn-yN%}If zuuT<|E8u_;;uQU8Qwowe2K5v=U6FaVC`yUjgorzbHqs=JS(1mX92#zkM&fz-AKG;~ zl%W|b*&R<)DeW^qbd?@1KX=kVsc*c|NC+iXc7oE7;)T7tFJk2ifwQ|*Z|PQm1k$P< zIn@Sizz-D7QyO0gXt;M3Y;126q*RGqR3S_YCH$#^hK}S32>LlOgp2DeoZKe5Qd(%i zn?bNE6W@h2c35@ia3%$0_yXkoBQs!c+mwJwA2h3{$f=rZINysn`mDB{byj4uG&M$8 z|6X6Zr5@Ph`Mtfo@DGOu_2qyP=@k<GeCyILHo6RZO3;>+Kv$ajnA^uS+FSQ87})*` z2Btz8X6s;LH}ee>8_KU96DhFp;1U0T8Vcd^RCLm5wRf`CpkF=6ep$^H*ql8d*dt_s zh5Ttd07O!(xu4Z~;pHC0OwQF8f#ElNJVP69s|n&AogwV(3+v~x+ZgG(5z_TptVm3S zW>5GUq@}W^6dDZtx?e5Of4mj>(bJ9PIoC9mXhc;CkvH4M$x<kV7`Q8`e+kslZGR5R z0@SrXeRnfmdy4E=(`7;cltHs}^ustd89WG@#{Q)j(QvN7l_}%=12oz*X9J^f;D_up z@1RE20etLK^A?Q>*tp}H5Tg!d)Ber5nLJc^PY~Wu$}{5VAi(h8OI%zm5pO#R?k1%z zH5t0xR|Y^~3++yETd`~@!1(;HmiO<BAsAcBr`g|1qqRGu4KXbOEhB|vT_?Q5laq6g zb*J#(iU~HHS7QJu;kC%J>$^$cbxRkpIdO)jp98Sg86`7vzwX@;MeymwqQH{EGmK*g zBFqw*N~rxBDfFnfpYJuF+1wahTjU4}A!C%uuLB-zeQBeH9*ZY_b@u=)u8^j^o>rUd zkM@V%Ow<@gm7RHjbJQ1&rY8xFRJ?DRx;?58WByKjA|mD?YfH=SjNa0KN+^7x;&El| zd3<fC<8C$bO!-4A-y<(3+N`Z%{XvUGDl8G&e^UNHWoIwwXi(YDp9>9m$HK?nsZ@Aw zHSJ%U$cYkQTP<*jx=cZ4zv?#}Ee%`9SG7@2Sxb-J4~^n5dh{R<)HLT@?F?){Ns!%% zSSN-g66{-xpJY-xFNub!gcMs1L;_o#)1n8D$pU!?x%t8-MTPb+#{A=aA~HuDr%Xh@ z_|+M+ruxe))D@}(dAqi9HDOBskZ-0=?_HKehQn6Xea~aIqw3PEb;xIz1Q)rMtR{Uc z#~Wo=nop+u6&<A?5QDo&%u`|GcEIVK6xH>hdBE!ct4`yTln&WPY(_YPLCD=k)~sqU z4R;UvCC2{&h8UuPm=T!D2&D+SMr$75uN0KiWd>yDg`@|yYU3Wd_>=#{za37zPzxRU ztNSwr9UNEcDGe+l0YV?3OSX$r4WTuiFTvR&oOyAgp4$qB<C(~v*iI3$v4S$8zg>6b z6UXdy=-y**sm^q4%+Mn|>{x8dk+LXkA5?Yd=}1Srh~dnSK)e{n$sq!up^;0<xwvm_ z&W@#D9B<_;EFgH@7oOa)GB(bW)h7wf97%}LQ`(4;+>`jkcU&X}^K@dN?V$j4y53hw zetzD-@|(I<qGVxUkY-q9eAxJ?+w^tC^m>2V@uXql-FjXMEX5#pCVjLZ%i#8yP@3K{ z)QOdpntD`7K6(5ZOXNCE*0w|;v-q96rl-yCY4{Z?=s$wwKmQ0PmBOdLPLl`pzW9Ty zP-N>&i4xU`I}yqEznjhY_m-%oAQW^;V*P+3aazw|En9Z4T4&m{Gxpty8lYjz2M}C{ z5K37vmLAun)R-ypcDtf-Y+x&amIaClpyJ*8<ejOD>@_zCyyu<T4HN6Q(VKBf#`{y< zE9eem!7?@m&y*t(635pxD<mG>JUI#$CJOR_ba@`D>0j}R0JhR*0d!fwiTz}F22^)- z+}q%2a-_-hr-ed_G)5NNyu*qm29}~KqAav0n7xqgLF7pmhmamCok#bwW-z7+ZcJLT zAqH2h3dw|0)-WsCzq_q?gbc=k95O16f{8ljB1Orj&g$RJ_^Hr2o~)xb3!Y6rFta~` zjYb;*hD5}yT0TugJ|y~txf7ibeLWl!Xou<oO}=K4Dl|vY7V*kjTQxnekEwIsp7kBy zUa*kwU?pS^iS;t`3RvA&A%RPY`?7v;nCV15``4t&lgN3ii*P8|h6mYVKD5~^Rsl@* zT1^1Ua(Lp1(jbDX`LNhwSXk9U2r+w{f4#QrZ2He}xVYiZo}Dqy#SPMmptzJ!EUNi* z`wYaUsP%{4jR7~Nb8R)TE~-a6%L(l+xn?t=l6g#qG0h)3MKiSJgAN$D4CwTVS&Riz z(Fyta`Loj%pV>}m<;T69GJZGQwY0Q2UXAmO-YgjY?2epaj1g)(_bHkV#S(p1_Ps8k z8iqFB)mz8yqrPnY!M9sFS$b@Pend{h|K$yp$Ff>yp2szV&fohweV$YaRqiXH!r+|$ zMi%h55-Cm?E37mVD&C27L9Zy=HE(5W#bgN+NCF(RcHA;x_hlb7AIPd9|BB_+eNDm* z-b83CEUP4>7D+%GI6rT_sXdzu=KLqwBry^uC*E)VDW9M@gWNd8Ps4&lh!zKCwn5Aa zB%qTi0_e}a6+iZwZGn+c)xlCTV$4#xJ%5sr(wv;eMIxHlR0052gRa_l`&+85jwJKs zJiko7OJAa>o)aO(p=@>fbN5GCGk{~HR-7xKn=?P)%Lc&hfo|hb>8YI5t-M1JniXA? zgDGVRVOg<2WEP4UK196p)%E0V5kkQpWq2J}e;9wR(e+3f^H7L<CZFclcAF4WS8;<r zQh0D_U}}24FBk(633KR*tsU9il$lV5XvnU~SMl|>Z7nh1_fw%5^WOH_$X((ZCz4ma zd@v-|2ZWY6EMW?t{3-6kNJKu7J7*!~OyOANDXtYuFn1ZMOK82!R&I2iVH_oR=K8&A zY-cWAPR%2~k7~&oTKq6T$3>`|csgJKnmX#mUCW>x4cPFZY8e?%x}r!v^7l7LZ#Nlu z9?-4OK#W38{La^VPz|8mIhlZK{z~Per}^aiNv803@802-@2Xt()nWr*&O=4<%U4C7 zj_ckzJpS`OJxs$gZ(UaV%w(sBb~GL|O)PY{G1*fyO;rKIDbkRHVCMWweJzAWgDdMZ z8|D0!GGVtDh8S`0L3xP%E>aY&2y@FT({Kd1Rq$U%37#>zWS9`&Du2Vk2Ff8HI($kj z85v$!O+*hPX5?lJN;08Ctbc{Fx}vB9`_V!YBiF3N#3&M}d;boI_4Z6w$w5O36|Gi2 zX}{T)7;SPVBpd!yNMoa``@hu;kB6@&@L=O`afCweKZHxo_IXKFI`jfsM3P@f3N6v= zqc>Yo$ldV@JzHKLN7n@wM%G&vWWK71UYK?-16K*)ei!nHW3RFB<<mt!urg6!!ghNa zuVAh!cL>9(;En{;TLn>1RI_X5THSBqVmNJZ&T*n3DN`9OVvl($1&5!J5y>Z_SBmBz zQob`@CO-V-@=3jdSyY93QuHmq{r2z(&_%*&_lVwdH)<FU{VV9O7F$rrLgc)vXLJ4! z0Qo=$zk<`sw?r%SYR(JQ1PBC_!~r!^z7T+)7^VT50Fnf2lM=xWump%jT4>Y6jBLw1 zxYjR*x)NYgrexp}CmY}x?mQgF9!@B*f8^!CfCS$QCJ;F5O-9mnE(I<%3bY0k79_E4 z^SeZC0s@t%o_b1Nd+jy7=NK`5{CN51H@_)2+;Br`19H|~$0d#}aQ54#H*Ngbu=dQp zW#iC*!`Hw5bydUTL>)C6{`Ft~Rn_t6Z#Q(d;hDTmr;V&!FP8$J83o!6B-zf)j>Ln5 zlkL#y9py8lgqx8|f%B#S8D`FKgP8*p?7_78gsH=2*Op>AT2&3kj_ZvKGpPW{8GM+n z@`Ye}qhQJ>+;W>NT(nBEAT0<0DEV;ImY2$&#qY?-K0U=71P85*CK*R$#rQ~z$)yi0 z^rPN4XX@y9&%Kg3P;#wOdRSgxvJOQjFjdJM7Os%VrfMVAw5XKEx)C5@C9)&|5Kryh zEk~CvlY>hZ%ZdHFB@@yM$}1S2Oge>r4WMtRu!nS=c$JLix}$O9#RENkr9Gaj)j6ok z5u_;H(^T!q!sBy>G(A#Z8Ix7pHp|AfJ0#u{APhhW_yBRZA65cj3Ew@a)x}`A0Cw$A z27q6*n}k0qL&o=)8}0%?qKR*Oskz@4TMyv|QqXr_14~kGy}d}De)?Idt*Mg{BS*=7 zU-_y`zG^aqn8tw<UCTGz^3H@f_uu9$OnSVhO9x1J0pdfOC5U9-Al5T*2SCXigaPn8 zNrpONli4~HnKZ?iV2A`daw1KMY3Qukkme@m^Qnbhyv{yLHE;G6_7AEDanjCpE(I<% z3RqrB#~~D+QXM-H%{}r6jQ;eeKfwa#8s)k8eCW`j@}2K|N51fdFQmo<)4$M<)5eAL z>od{C#^ZBdGmiD6DjxHtB#Bm5sowYVpZ{FT@wKmgO;!DDxov#LP4_!fzOKJZfeS@} zb^}SQknME#e4#4ort4DR!c)Lu62ZHXN$1$YeUbVP?JhlvI!f8$DlTk+XKS_&OtVHX z;p;KG-5m^h(fF(6_=?4lZonQMn8bWAa%<mMD8p{M6_Sih31+~o0|pSzuG0vBk4&YL zv>ljurdl0m$*mtP5Ya?ydY?<bzVLLqFgcJCNlFHk4rI~IA6@|@I-pTwL>i8lO38=o zWbZp~OUcGH*aN9rasX~%Ujd|q<OuIALgqUwSMmo8k-^ZN?|0pGlF_3VOn1X-9S3|8 zng7T~4QL=fZo!B^g-jn&as*HSiBVN~M3ybxD1TnGP-;42FQ8sXBi0~38gu|)(|l28 zAAvR6Koa_Pw4E1+WT{inESYoj1j&YqU6KF{K`4Pyrh(EH<R6QMWyAUn@~1~1m3>$! zotu}h`u^9U+-!eztPZc8TjQDfrEl9$Qb9iU0vV`loeunUvcR-UKa5@A?Pz%zoRs7* zE!{<Z8MrHuSfB=E$kg`C_rds-3hJI!kUP;bBxQY++i9C^ou!uJ?0+m1#~3tE%zi>} zbo}^nHQwNwB|dvvx*;zf3fS+topk0sjVC<$<dgF7!w<{Bg9r6H!ZmkXulT?N52ysm zf*IC?ad@QrrT3SQt8H6xDY5;BfA|L-lb*m91yxm5+RrFaqU84b-~WEf@*RN@^W(vK zxIpRSDDFPLP!wo4ki<@88$Jgk+W~FIzEBl*({(9uAt*q8jclK3$DAt%Gl!Eu(<39t z4VHadOQfcOd%kd{oZ-j=S}xDbt5aN1QC%b9P*ASA>u&k;s-;l<GExpKagxeoN9714 zApP$Aym$jp&4MHYoycJ~O|5J{;vM@JK@u0o(y`Ccnh`+~U3yscxRigCsU|}XdSFnc zBoB8`uZu|xvz8||Z<hn_EtTWTmP&o;5y_#XkHN`{<3%-qicPT9oe$#}y<kaj(6w`= z^YEeK&BMZC(2&M5==k0c3&bUxZ}QQ%h)XYReFLy2us_oAeYLXU?JctSugi2zQ#>ai zAxMn8FvLKB<mWz0kpx-;L6vz|acny)84=0vo+;PPA14Dxbwe9ME?BF^JZagGAe)$) zh9CCr*)Na%=`mS}%^vYU2KMhKGiOYbf_z%qqmLF=K?U!O<5^3bc6J_}^NDHMbZweW zA_PcU0z3zy{h<tiO3Z5Gt&o(ggFZ)n;?OOOVc(==paba3y;HE>inK-iCP@BHmX*S2 zNe^loniTo2TV==8K8dq^fV1he=*2!lphW9jwC2S%eXesUaH&wh0t%k#*q$jtA}IOQ zuYRQl73fdxf@`k1M!txRudl;IP+R+gv2WP^!8m8*IOe41ZR1#8k4A*JHi=T)r=NaW z!5b&;e({T6NKsLdnh3XHnK#36%(8wqJ@@QV;IpDYyMd(E6=Wx1hjyJyflHMFY`t73 zq6Pw337TjIGd*H#KUx0vI;knC1k+B|6$~~3l5*bU)Df1qU;?Y4GF6SWEIr4LmySJq zOBiOT*-8DFbI*bQ+86#JeP+(Vx+F-Ff>7V1sD#cr*+I?rC4wZoF9rQLV`o8<4Pz3x zbbk$Sft&&Bz^I<3<fNKbxKV0ht?V#B#DT@{sgZ_Iq*1bgN`jyT!-c_c*MaVdf-cfy z^mrMGbzi-vTrIxNu)0PSF{H_N$WIg1`PAS7Vp7sUcAo%;aLES%kc<PM0U+&MUo0!% z-YuJ!Z-T)NuY@pT8^Ic-IE+PT+5CtJH5V?A^27mrpx;MnV!{`eUIRPI?3>5PjO)jV z7q8d@BMn|;qHTs&9^hD(QmCpt{nV54I@D(f3Nx@yZS<H?G68D~6n`)r4g-{|4`W-$ zQkyW==aZbN)Yv)|=F6PTuc4h6ASn*8lu%VV6G9t2E-6ilpt1x>G~6KA6Dq0uCMBfi zWQFYCy;J7&9;=eH1VJ!pPl|9Y*!eiNf6E9C88RdVi0Ho+mJX>N<btI0p|BgbJt)9Q zXSQM6zF&CZ1^LZyexm@1ezfMeV8H_U3O1PLL;yhz`vG|{p3@z})7f+Sv)0$G<1$^w z<6)oiOmpHt_`wf!E#NPI`AY?HR003#Pk$=o#*LG)W5>2g+6720$l>06#uRYoM?d3S zo$PGKNzdH{OX<{buP-?YV2n{!AuTvqTlBE}&LJu6Ss?x(yBh{0u&)GC9FLmWJkHt) z)<i_4ybcT40fPFD9t#NvVsLg2=A*L_xa#13*}vp{Fyj%56Lg&l8DZT^#xkbPK*#<? zopY)Y(J>rB5)C&v9y)ln92U)^bN^*3_GlT~`kpDDGe5UakTUARYBe9cHwUw&;DYOb zNKp>}Qsl%*DPFQ%);#=(ti%2vCpLX3IWZb%fLa__>?lA<1TQD-h4g5^Fd6-YFU!>r zep~upf1~)jbqD>S0tVWFb6|>^ffsSeo>R&}Q`TNcbA-UiIpPhl;<S8+y!y-vS+{hH z_!~nKie*YD9>RvHOall0Y0M#^fXl2Y<60eWASV5XcbA**o+>kM1VF+zBpz6|LuC-f zsW{H$S*jozd-KgVbSAbMl1KUt8#+X8yX9t>d+$z6r*ZhcktvA+XU}+OQdHkh=f|dP zQ%ld6`LWKR6C`1TR5a~PQc#>kdJ@*gJlM=NkORO3$qlVmn2^$d`W5frCyjNOU;w>6 z0E%iQ5b+6=TIY<2=j_PDafX}bk1a#DefxGba&pdzxe;6nv<n4HpEHv<{7x8fviP0F zkRbh9jvOgQsXWrPYgf7NzWY?Qjb^^-7`82dWS{Yz`quKMm9xEF`=a)1lQ-kgrJrp+ z1WMof*0<!Id+t%odMv~4-Mi&K{^LJV<C6tPlqT6UT4n9tx)iwJ6u4+W5@#K(nD&C# z+RebFzy+XyGfZL7!4(c?i~zIik?y@aNf0`7ly-Pwrp%|z9@so(+A)yObQz9VI4K)G z+zOM?Ug<x6vebheCsRpw8VXvH17i+rUwskQ*~$>f?6qVWJCi?>0Rv9<k$(Y5L)4NT z1|cH0rlzn|W7ZCjIC?1+H~^7({p61EnHy8V!E{a1>Z4iViQ{E1oSXD##2hv%Q!{Cq z^sM>r<}wmwlD#G};u(wqz9G^G^(;sM)<5}_eE7TH$-#Ht5?@t?6mad4))#;hbf||U zuL7!ZS^bC0gfHJO<Gy&WbR0fHyg9kp`xgcjxIvPB9a$?yUwEYeOyusJLhHayrT}Tx zpNPuJH@C~He_ADnw_(HHMgXiN%wA*T)C7PSB_Lj;$#Rm}C+MZ&hNQniJh`>fcT~RI zv|x%%m^nl|A%t^e{DcvvAUwkgC=3fMhh*&ck353i?T>0vXmo(H!q?87tL=;7EK|X? zOJt6k)8Mu7(Th*xM-dNlMbaj95Qyy!cl=`^Gf^kXj7U1`*lslfB64peDjymZQuGBr zL;Frfn&i~6BXVfxPDzHN^is!lTINq%iKgqkmR8p`Tzbw<8fXt%2HbLeMp03bN{;Ba zW5<ruK$4}YJ5Cw;T`s?Ex0|%uF@W=FYtewyf}Hi`nKC<*e=1=Uz<g)XHBui+v~Qg( z<75M$V!}ngGa{=$SS|nlZx6}tU3(DTBVD?5m3zK)k34Yy11e2oUHC2HkzOyhe|ykh z`*5lp=E9W5M6=iIv;1D!`_>cQx?U8~Z9k$K_;<hiUA3%d0nv*uz9`Q;^Gqs?&DQo) zd+(lI3Vc=+XjhQLhHpCzE8P12vm%0<k4u5`rGOb2(4KXmKx)dsI}9pLJ^OT#jBGN0 zVCboGL=K$lcvz6G++`B#T4WXho>srVMq*7~DI9y1#Io`j0_t2I2|`2wr6s97xK|GR zbupMmn9Rre4ORI9GpvIdc~OEi9n}F0oHa>77#<+Q9H!w0Y&HrcWkxu};y)c@eR7x1 zMK~!rC;LRxreFHuWatD{V+iIkW8n&POcl(z<dZo4@qnB0ddN8gbR=r4<mifJvi!Hd zlC94^A$5DUN=MpGV->+vkckh2?$wCel$j@mlV{49uRS0=XI~?JY~oAf3?7>72Ax4} zIJ_&BcJP|-67LW1$sD*Q;h;WQcIcEWesPVw`OIoLc>sH0MY3U@JySP8ZNkfGLOJ7j z*93G)s=_ciEl)(enPC|;shiw#?{pbGwVwe<%nG5P#D_E61=s07+Jeny_h7d5cL0Cu zu$K=FNpvpkBDddhr`&b-7bGV)58+Txjcd{{FPAymgZ{>8Iqc0RJv%C+q^*62CSClZ zd}??B53(T{qY9mV<4IgHd5B>^Ak8t*3K#ni`vuyvz5qz<@NO%P9Fc7+KafNtB&?u! zb4H|*Ny<sCRV|o)%fD0rMua2av11Tb?(C+rG*MhuR;HG>_}m3XhF+J&uW5Q`SC#az z_S$JXXO{p%ebRVo8Q3J~MJt#3c{iUx%^-n(!h@N`(Wcj|T_X?u`$MvJ&06$)k96wX zS-uFV%{RaK-=wIhUvnQ~g8FUXulZ}My!u4@q((^nv_%T-<4n~FZ_{N@q_cpC=c1w_ zm1<cFtX!Y;v!DG;&G2hr{ILJoK5G5kvrB=`iUK+ue^!~f`M4Cg+$jL|kGvti><$yp z3gf;<pRN)FNQx!7-U5snK?(*9N|wlgaX{fJ7p_$*KVB(&cNdGVu$v5=FbNjdux0}T zMFioPt}hanwJ*Oau@Y=j3-vjI1m?*UIa{YQcDNyf3VvVJ8FF&65fy4?*vOM+jycY< zT!w|j^?5ojs#hrs%5Om5M<mF+odcm+3|*AZGi435@kTB{2UR5|g42t>1OWgpoHf<* zbL|o6k*GW&<*Qc6nn!*oN0%>=?1n1o0D}kF_`*@kk<54<c!(O9oX+k)M8<sKUYYjo z@4$N9Jn?tw2vskHp=3t^CRHL)Cg)ed5#np!C^vZ#J)rTpW8DFH{h6h*<n`53Q-N|o ztxoHMa;pj?%dh|VVcGRCjDk1lk)dM-%N+}DmJ#CzLdy(snXv|Cg>eD&K~gc*V@Hq4 zBTyY&vSbO~w^y>WvSjwG*(yciIs?m;Ab9Hff-)CGM(WI&<!pA&Gsjak7wJXN37TlT zLnGvsAvqqBwweH*Y6ImtA>mV%Qo41!G#)Pj-A(`D!~p5ZxSFg<+T1&SOv;oZ6@p&I z!Atub%c6OSZf4E}?7Zh<ac;oOeZ{O}c=lDx<XM0Be2G!OHit77o2}3uxYS0(M&%sZ zP;t$6b2djREym|}OB*i|Ca7t3IL~#@HRQ)X=SzqyQ*eF@_(zAG1W+t~sW7?Ye6PyN z%H{w2`TsBPEq+%bSc6%RpNCCb=gWf+epC7l=&#>6PUdlN&@QasN8|*rk2*9%=f~uZ zywg3?u2cS~vURqf@!nqZ%(Z`1yW@l&@43+}ffCJxyUwLRdsBczvg=$5xD@ylD8PXs zH8`ZMFtow5Lzi4B?4B?F3_t*H7=sZ9OAK`|^gyRG)d)xSJl5oq#qX?u(SV>#nSX~g zVvR-^gJ2i~2nWm{2A-;ehh*Q9rI02etyt8=*ObhlNx-55DZ+AHQV!I}n0gq}CoYoJ z@s#=VNR`z|;1iuV(y{{1xm6mZ3mIZ%DtJyi_zZ}`tnpEQ*3vqrsUhG&X$%=-N*F-D zFc{{BCaK-KUp7AVl&t>U!&19#qjUvru@5V%i28zN^@v{!`XvhhI_KUbQ@-)vWc<DN zNY`<rq3Q;v7~n+BY!i4PU6p<)O&r?r1v>XSS&OoUA&&ZB(Pnx5xn;6$`EF^d1t@~e z0Y4;B5g2GNQbN8>W3<|jt9XP`B%A?M$#D6gjW_*TSkfB;fJ7mct+M83>TLWxy6NKc z&p$8E|M}0-1c?gs;iBtreB&F++*?Tp-zS|t>&*rKv8A*b+4qGr%Y%P4#0WJYf*#hL zp0?#F@2QkAEfKE_jz6aFgm4*#YT@Ax>)-|H8yQOgByBS|8Gz0>aE$C6EJgFdE2d}; zy}^&Re}`s+1`SemJ2GknLR=%kHGB-?0wYVYOaFXY8(=$VaS)C;p$JrXP`xv45~aB% z+0@SBtnHrRI2nWKAbh7zJ9L@|eT3g4J#4zTb)2?j{1~Y*J<&e#0a5Fk=pC=W_68<W z{;J=4ZZB~A9rLjd(zj$l|02|i>1q^QBW<L^vr4DTlQaIZB<h@tmNaWkLmRmH%s#}v zW&51Hrg4;SfBV~V)m2xe0&_nnTEC;S;ZhIX3zq_)Aq5=G_s=j#H!GI{moWv%pP4}n zzx?M7{CrrGan<y3QhfN7G?Z3CRmw<@612ufoP+_C(106hdXhn?RUMO(;}z0l;$#^y zYo6?R|82=iG$}yJz+e-{O!t<BuSw5QBP18rfINQ2<{*T;a8M#;8D&~N>(r^E9D${` zMwmCQJatl^AsCDHDLAkcwxT#|{h79NL9oJ0WjvHo;6wGm4;{;D25&z>7NjJ~A|Q-U zy-6!bjG$Vldj&OyC0c$`s-SCMf{i~*Hm{fRZR;gkbrNfjsJKN#7LXi)k&a^k&h1?! zeFqMeuCN%`2lUM0hP;_r;pJz!nKoX4mY*fDj%7Bil9rw2MOkQ_uz3FoS-*6*tY5i9 zDvsAkJe&at27NM$qcjDol`#UDd7OZW`~<pCm!koLcmlwd&wN?Zxm%&~`v|4)PNO>+ zk~!dU6cVJTp{M_+KRu3jSE=TDr%s(B-}w3iGGqF5Ms493ht9tL77s7T4f8XU)1s#; z;dm3UqTZQVAqi8QXM)<3p7p&tFI}nb)Pe0J05gDLSo7QW!3ya)d4d!S7=%6(L^DCc z)|o1sJEpIV&y>s3Aw7tBLYf<2o@u;+5;;nc2s$@z+^8Tal?B42GkVtFJzpjiunh$5 zhnET>@T;F7y+=F7Jtg%{6F#eo+hk2(w(gcb&54-rWb-|9Y5tztQt6kT-&uYt`K_de z0ZLYd4a=8ei-SKt`Y6_&R!O%W-Q?OibL4No{~Z}Va=1wrS)2Y~%iz@HEGlGzFoEV0 zvMTAfX-~`pKD1e-g=BxT6A!%Z+qbX$(?9)_{NyJ;(G6#5hW|hR^FL+ElqsiKyK9k$ zd*f2z0#m>RNf(&FZt_<K1?)g!nJ$hHIv85efB?fM6k-3BK~l14HJEssgGLyPZ&=rl zA4nF!Na`YgSVN08dS&~@ebV!D(`4fPUxz8=GAZ4-N`jb;_hC@U0+U_0f46*y*|u4I zdW*lXD`q;eu7d-T9>`D&m6VLk4C&mtlRk(*l0-Fz820M%K*D6peLiogIm_k&o#~pi z%~NH3Z6^8<KltZU{(2}5z&}qM@GWCP&!mcPu*Vc;^}`jX<iLtma&Xy7NfaNEhLWSw zR969b5`*PBU=k3t7Lom#IZ`-$q!eP`ppL_aNXI_?B&%yTfFtb3L+f%Z18Ar!iM&Lf zr#aA>5;?vj9#Pl|-~8b&S^L)=vS;%#X*?B!z$gbXiE_y}1t2YoN(lR0B_K@-BA+Id zi))->0K>ijtu$eeBp7mwP@06wCh$D2VJK@dPS+N&E&zpxu^#7VKmC8@t+(EiW5-H# z&#N16ya6-A-;wb!mmA_Hw<sr_1p_9P_WU*FF(u$N+6CHeL5Dmkhf1QpXwsJN9fw(^ z1sYml17hpzK~yio5q^f68l`m0M%lAssZ8tvkedyV<N#Zfk7i?k94}2pvtxq1V`<V$ z$ADxq$*_@@++1_*+O;ZeB}k$rNIpL;FGh6T<w1eg4I))5^VQ;ayt&=*8|SpERJf16 zXq`M;eY$ITm-bX6raje(G`2+}`JsUZRo%w-rLnO=e)HRh<&{@nmaSX1$iTsa<a>Yn z9ho_Eh7879J55TzXXpp~UTCt6@AN|=E(S`=F1?H`uQj!nUajxa(@9-}a&|HbXWOr6 zvYh?z+H0>>11dlI(T`;H>eZ@t_v>H(S{?=H({i@%@2&H6?_CO901CJu=>ibdP4dd5 z0LKC|tl|p)3YajU>A-;dtQ?<Ao<2%eZ`dkjjg?@EF`MRN7j)KHaApva5HBQ2u_mAF z-dQZy&G$(rHo6>t*In}Jmi4;1EF~qGV6bD62066m1L?bBxeU1FbBGHdktP-4Ti|#Y zz<x>{I^?4q21Ia{uCA_5atjI=<Wq4RHdAA4Y78|4aB4tiPNa+R(0olCP!0a-jSC84 zF#e}pG6EIFnrf-pwoNubdR79ptJ;!c$pCnw(X=c?Agy5-P&b6l?K41zU3Y_YpFUMO zjTk1LtZbz#bktzkjsS^l4j5zp5&du`R;3awhm$eV@&Iw_+9RmfRi9{()l0U@>c4K6 z(u395$_Hk><3aIbjZ+M1Xq^az_*MZxfmls_xEU-qkj>148Xndlam5wuNd_kog&7G1 z!@mJhxY0FHd}%mNLE`s^NB*GJp6crxz(8cmgb5SmfBg3!%2)s-GE0_uu*?UEmVTWg z;sw1(ds&(f%I`Qbag@{%D0b*rAmtvcD<aM5G#L8_FIjgST6I2vKjLtv+zX=|Z0}rm zc6`kmX__`uvIfBlA)ck`nqGwF>@}N@`eA&V2G7HW4O8O{+)J#yyj)64OLdl;>m|~i zrF*)cdwpq9fXyVm*`!LZA0zf7<HOZHgh>p4ZZagNiKi0g1-}%geVd-&TmoL{y3Q8i zHHs;y7MMRs1s%mHrk0GVxPSb^AJx=%$BrH4zyI(b<nFufL|e{mo;YK^{6|Kn3sRcH zv`iT^c}@MyKeqG?q2)DETSPD=G+yb~?A#`fiIm>=2$HB4K5N!2AxNUN&Z?>^S+r=8 z?(ak?uj^b2v<C$^KD*APfJ=c-fdZCsGE5f+0_|Ot7LegHgHzAGoup_`5Alb{;F(!$ z6ORlpLV_{(Ln7ge1?BMG5;Y0#!3=jH)DHTN9FMh0hN+{$<ZLj>zPf5zzwix-S66|d zhh)Ptpr{WSPP!mA^33l5KxD=yHQYee3_2bB?ck+8=l;WFd9b<!IGPPJw*}C0m{4Yr zC7WRG30D|{@PY?H3TdUYolvt%V1~5mc&V)W)048|m;Wh87rh};a!5L02i9!p^#`CX z7lp(HTNFt{FjG2Am?~F&|L<hjSMHTg6DNrjbcDq?$RZ%VNq||mo9~)6Tg-^6b}Tu| zixc^G9Mt|xVguM@Bq@70ACcFdS|UqcSu3UcYOoF}Lp(94*m<C`=kWVpl$*fL4{4xQ z8)?$GL=0~X+yBVe$s-^ogc=?ge-sxE@+a0cfrU&6ryHZP7$^j<qu2*)!-fs=#1l`b zG{Xl2A6zr@T}Y6)*&?ZiQtDxue9p|WEm^0GRNB4u|J2T=5J)a{(VVnX3|lsybMmlZ zEaXN8IN5bRCLlplit9rv%94V(YzKZ2maQWTNBzFNa&*%s-6sr5YSzm1IoA$JPA`%z zk5k(85?i$&7QTP~{yLk@@{)dBL{1|Pbm_FU_0k9K&m~2H^mnfXZ^J{s4`^6a1NB1e z?8Dh_?-8l3=5{8(bmH*K$1elE5^3k=Z)bYg)U_=izZd8U%-yK`;U0b~mSanR-~V0> zyATo0oH<Kwyx|7P%EWHe2+Kcn#)JdF2;-Ou2<CuiZ0qKV9%pn6W4h6qYTDA@e&aO{ z%?AlEFXx+N&)f%zPRoVo^XAQy`|rPB{Z5`dDbGIptX{i6E(O|y0y-?WN5<?R!C)}8 zkr)Re9`4}N9&f|V^V6V!8ICwmz;W#1k9D|Az}lJ*{Q9J+V<aaZ3^o`>jykkD$9A8f z+5zLi&x<uIRZvaZu!id+z))j$aP;TzmU@4PY$n1aBm;p%iI`OH+9}7dcaDIu=HRQ@ zA{`xz5QgTz^I+kK4%tWy{fujqc+KGaF~cOUKbhl)gsO5(QXMZ?k>(pbQ&02DusjGz zaP~q9!!$HLu4yVeR$VCv-@qc||L5Oj$Ma7}`Sx{^oeZnwD1b<2Xob~3#A^&>O2@I2 zWb!w@E`8@*BVKHpm_)s`1SBf!NJ$S!j^$g(%djhPNbW#&6Ao!A9r#+JNvSG}$a}AD zl9wJ|A#2~;Cv|0U@k14o3=`>3U_|vsuq?Qz3JktqSVWb8^eE<yNIcji9eZZUg8QzM zqM@)p2caP)g<N-rQXn1~2EI+ae*ggmtSAHjDlv=t1~!Z>!CD-;ZrI@V8xMS4=3YA& zcgz%_kf&jGkP^yb4~>AI*7w%`Q$3qks!66@GItbHsj1I=s9!-rE@%|Tnk=XwYU4u~ z2E!k!0|)kzeF5a*p<eJMKx9hUc#qK&WpZ@mCP~!Sp+gaHF}4ZI$q0McxJ)(WT6<~- zF;7i-M1d&xOtNkl*1TDeL_g-oGP>^4rU2WMX`QA~ps5-Oi*shXRA<`^15igd_3HV+ zIoOW$z(afOJYyaP5Sg>Kb9~P+7?^|K8c3=&IP=88RGE#YZnNcCAD}N_KRsHsqen5; znLhm6U(2@5n<1HwN&qUpx8HV)<mW+p&h?f|1>yAD%=nJeth5hmmZ|EROc6*kZ+T|f zH6Fb6x{WZ5r_WFU?r_2HJ1b-2@r&2&Y@f4dK4Jf2|Kmopy?XW1zW3ylPs;J*$D1SK zD!mUfj_X_sTqp{lr?rn`$FLxYC7>0d^uefoO6BJ2Qs6u&U`GI)IRsm$SNP$&8v>;v zBl<`eSh`b9JB0K>%|Hz}aL{rFTUshg#{BZ`+iPIrnki*Smq}Bk^RQ7WP2$+Y;M^z4 zS93}>zqU}~V63Sh#*Ip0H5}Zfj!)v(y^;(_;vg1=Rk+&Pdd-UckSyqVJ3CIX3K%65 zI4tAAf~v%YVK`votb?|54XznwfIrshcpyDW;vB21m3?o$AuIpuH&VLvZON!R35#_Y z^if~#0|E@AbZ7#dLY=$GgxkL;Q~u^b>2cL0Nx)D=0*p2D_aZY7%+6s|5Q>3oFbo{H z?T3%s?y!8M0!W9oL?}Nz_iZ~auRgg{-g$9@9NLOCT(#K%p_xbvh9Q_Xpq1H|#7PSk z^ars9DGu-%!aAc+y$l%LT^2krN2bpmBcUAR0VZEnTgc$xAUI}9q<#cznYf+`g^?)K z^$s0Ar0bC20aeKka{K2#CkqzbE!jDk9aegpczkYMI<sN@+V9L-5k!K(xFiV7E6BmR zEKnM=+4NUHV}hYgfIc{s1R8<SagXOw7`z}9f`MQOf;LtA_DK1z-Huu#Um&0I58-(r zj;bv(Z8{Sqb#1+werwmIOBdaInY1MHMUcexd%UKf_800Xx$Y9CfNc=A?U<@qUxE?h zA>Q-4Mf+h;`tgTt+aAW#dDz;Y5qQwqzRxo<aoQB0vqzY4&3&86>o*DCCVn?HNF4Fv zUWqit0g(PnmMs3OG&MA8>%ST66=zJpT7m(#QGBBysb(|Be{&Id{Rth@VL3ECrol3` zI#QsIVR<loS{(bGvS$Q2&C!s<-FM%u{civM{qhDT%h(6)!MOICk<&rbX^FWWE(Okm z0`2;>rw%F)Iu1m3Fk<6(olAjBp8{mQQ^Sceiqy%<DG16a?2i-5;yMTO;b$-i8Q@|P z1yj%Q)9=ZW!+Va)-YrKl&_M|gJEl*#<u<87|7Zk*-3V~O-jjh*v|`tGIlO9>sv%Jd zW0+75@?b850m*kHN$gqN`-Nt}bpXRX2hsC&EU%qt#dvNQV4Q7F)-0TXG7b>J@F*qD zlpNpzj${m0-@*+NEh(0L&pss^9(_c@M-NCABs73MP_0wkN6`X|GkB#Ylr3GR&6X)Y z_-7gQRcs17aS8xR9!N|h2uAwAx;dBx^k+U?6NG#z4FKTc`YvYA{YC`pb#)a{S^3sB zdFiqDW$lt3QeBD-dm{nl4HZaF5TT*?MS#ONKvh0Sj<`uG*BV8VO_B&jBpj%bnYT=k z&pj|x#?Kf8faC)>V4kQWn42VKf@yt_2bm_S(9lvFRcJWam!Bw?hadhgIefTSO;XRC zF;h+CcE*N~WDb<M;FnvuCKRMyUF#u)glR62(qF6Tk*wS-eb>4k3-x3${%Uaicr0hi zmdS{e00NLEcxE6Fou=PU9X==rVO$}Bb#+FX#8ga5Oij~68s^+wmew9fHRUXm#aV35 zVB0lFJ9g|yS-7*~l4a0Rk==_+oC2q{6!b%U4j|!SGbFB|qaQ;8v#a$?8XPg8oPpRz zO`o=Xn`ds2Y!7^{H7-9j{3dZfxF|k6agQ<HLZdDOHB_5UL@`+eRbPt9p;e5@BgAP! z+s5orf-^+O>xn0xl^0)pO=_y^u{IJ$M~07)?|kdK(xW>Jo8TKsWnY~ULINBISoTl- zFxA%Yx$VoG3?j{JU!+v{Y+UNw<^=xQ*S@C4RJg(HV~;(iYRBw@>EY}(&#rSRa3LsQ z5Xyx}`D4;dA8^>f)9>x|$0XrCb}4Z2QGkO+s#N@Na~L%raEy^^3OR!Pa>idZT9z+a zE>SSLlp@i9Ljn>M1xmWWA3E^(i^0m>JFhI0VdKAqy=Fqv<7!xI8!$xb5AKGlU0iZ7 z7}8931Z$JFE?z7}vuBGJAWUaKSq=<X8Nra`=jM~gRF*u_6qUN#I;T|dG}HGOP&t~N z-(bT!@}OhAx#-yv1jW_*=|GKo8zTmI4v@#eKiN<(m76xo^5>qF@RrTecmmekz$B}* zg#ZF+)j`q}h00-0zkV_rfU)rEtEJPBp|Dz)hxD3dV!)z$uYicm3-4Gp9k3~pGM7}7 zQ{V!I<nX>SS^4f(*}7(*R33*!C>p{W04>2RC6rS!;7IF6X#)OH8jy{vkD?OyM<ll} zORl+jx=g-ih;-?Ny{Up&&q7cJxtFR{CZT3$$&3rG!D4KE|KP&v>TBhxC!dzrUR?-@ zm0$Nj`rh~cRt66qtnZI`vo4gT`B)(kvt1bkzD&|J<>-;_@R0wgXKr2&m_RaYWG^uz zK*okZ5ATO3f>q_VoCH}<N(8+juE66v<a1EE7DhaF?~({qaDp&q;ej<lPCg{?Hb`8y zJI2+1XUnFM)5~S9Ez@PslyVIiFhEs)sNHY`)&)7C(5+iHjbO(rf-1X~;`CHqpG%1X zPRr63W6JF?;^?Pnn%dX2O`*NA-+9m`O*=(D<VO{OxW16xTAgik&aE~*$B)-M5;`-3 z=BlxnpL!|)(#ZlyiyG@N`BhpiWhE!1th7Q-V%vk7rYiIaSn$O8<yT&m<44QUr+kv1 z)lt6ttsltvu~*@{fXN(+pD;G)K1}E{%*TEwv^-AP&gsNXO4q7>#uIfSE!b008SQ(d zC@Y44_7_e9eUxJu+rJoY;J|@0YSbuMw{D$qvf`zeUXm|=`OBIF`>XAPnl``3u5&4H z0VvRJAc=KhL+3%K9ZSCy=2|`7AD04`I0aJU37R>^0F@?j7O}8%N6c1Z;3A^H2i{m1 z!k_}i*8_h_S^OCMyzzh>fF$YI&N}Rglp~?;y=BrJcgib2e@ME(=s*OCW&&9Sz<i#< zBJ+4@nRs(^!E_@-4pt~Y2EbJw{CG{inlp3tn1y$`p8B6JnQc8eR5cG*s1Lae)5XD1 zC_iD==Aec?&U8X*mS}>i?Xfah|NKjG6l<$a?%yLhm{rX~R1EW=2{zb8sx<8#&F&xr zXU>r!^XE%9SR(Uv=p-J1z$6DrgeN%USgdtL9K<#^98|T!>VxMD4E6|;o%)ke+3>+m zS@r&AIlAwpG*xr$5twi4{v!n%4j^-c6!iU&R+e^D>q^2PL)23*MZ>zu4YyB~VG{>Q zc837!3F$bdfC+*U07-;Y9++uo0htyGfO3$v=UOz6G{8LjqDAkj3JpPQ_wGI9@BZ%Z zu~*1cgg4(yR!2?df>9$7AaUW<ey(-qED{~h`i!N71PEflPMv9y4tF3PH@VbrzZ0Kr zhCG-uS8OwEMW6`*QXnTA@1Ji169=GOCSG#w{=IU1`*tbn+t2hNM&V0AyVvL%-YEhe z;r1gP!4b>Dc0rItbKrCYN=J_#RfbL54E$WCOi6Re{y1NNv?js6Xe7$4lo}Rcdq9JX ztE5L8CZ3=TqH(c(X**?LIJRB-X)0_(yl|Xpi{^%1f{x!Oey0qa2e=2eH%bI(yO0)@ z9IcccTlUF;ok!$kX{|KYL?zMy<1|gMN}9m_aFJ5kdt|#DDLEt%Izh^vE&clrmF!SQ zOsb)LnJll7PV<{X3AV|Lb+e_=qMZGY({D9`)0a+5$r3`J^C{{>um)%Qj^3Q%Cq0bq zkJF}2lMg@qP>l`I6!>ko-6nZ?d8)F@FxJ_=Ywz8&OMy>|0__Hp*dchZaodh-uhTor zr&Uom9hU;1H3d=wsWX~*0cNOj5un}}&2^LY!zFqEiiW|JmeC-Uh+^c!(1vHUfCfVi z^$A(>+G@FX=v?sv5cHTnOFF;ysx<D|0Sj+n;4xF^M?Z>HRmv&MxE1#8tx_j~F(ys3 z)EU7HsJ21{1FCL~VEk(9>eI-<QOzl2n(w(@G8G=`I2e;daFUI3mJs!eVbCP-Avl8g zNa8T<UA%OeeE7m&q#9+<LfH!7pUGKJBt$dM)i6jA_6MZHpkXrZ?k{0&)+EX6+ei01 z^1%2DQbxvv9iW+tix`n*u_ZEUY%CX<bFwGOD}XtvEUA@cZ)}j&@9&gTWmu;bg`_72 zfCL#5<NJ_*T%{ibG>C^>bT(OE9PT_YmJtfel$m2?#tkE7!0?`6>S1ae@5JkHOA5|# zt!jlVCE7reoDm$8Ap^rTNt-rpk)QnUpGa}BQL`h1aMMjUVSNGW$c<<Lj94RO4*1<< zT$JgebIv=r<+3xrxp~|G)~P!y4o9YwSNc9Q9`5wTn|fyEXG%6ULXIR4s;W{D3DD$w z&GBL>-n>Qn&b}6#C~>VA-YugdJwtCKiaeN<$q5&9PV(la`8Rz$B1qzTS&m1fHP<Ea zU0C2me|L;(rro7@)uK(L+AA&;7_o0ADI3N<XViD&bPjhj!-NUcZuxCCyP7dP`=H8c zOuI#VwN&X4#U`!on|^q%jZ&Yp?FY1t)z>u0o?VAz+xneyWPb_1MYYmU6~+V-+He%w z0{BWKFyYeVt(RR#cS>=^VTt%L@q+xjKn*t=$J@(R$cEiJWzKbwWKSD|$u>+zAipG} zRy0qe+2hBIH+p;aKT0rLo8~Ie$NF+jCBH`okbw@M3;R32Q0(ri3&4+-<J#&&oB*PP zmd~j2%6|8YU;IMXt8d-9RbGDiWx4OZ`*dlBU8-UGu1(iHyA=2|DbQ{piIqt2Bo-*q z-yMWV1=n336yTu1VFUvyKKwDv>KQ2lWJR>dKvgXuCm#lc1Q&>7K;s}Agv5b5@gWS# z0`<IY*u=E5WVUqd?UN8TMV$s|(rXXxlza?=T+q%<H+|S}vzQ?1#_N=HG(^AwiUV{A zAR{j~PbyDVVNFsPDnu{=&Z6O<5dvN`4__MnoPO*;scG=W9!v#gRO@Xx`#EsZw08s8 zk6pWE*;7wT`Nnn9SawwRJ<6imA;NK97L%%S5*C~MFw8LNb9YIP*>j{z|AA`hPfdAK z#R^QUs&ApPIw+$6WLZE+=B(wQG>hsme4^`sAVKngwv{DKvi!|$IJQdd34%9l(F*|M z1ye+5$?-gba0EvIRb2rP1;_&|#WNHRS!5T4<eFQj$)wqXq-#;GZV1e5RTU2LRC?&e zJJf?kFf*&lEFlkO!txzGdQAT1U;YJZB|DM7R|@hAV65SGeP^U4@U_x0&RJnfk(5y< zop>nKalSYm4Q8;IK4``Hv7s&jq?RA=j;)UEldp?4QKIAhm}&v4!U#vl?%gGrg?G~s z*7k#F(g@&O29>+A{RgG{xB>;o1mXIcl?-R5iRR;wiepgvc*A>|0ng0LG^yZz8}{d- zQ6cM>K7;Kf<DM=d3h3u0)d<W5`#M$Abe#~s!3|hnSk_n}$4-?)#TQ#b`_cE|&u=QH zZ)h5v4VUdDgo&$cw3iHQHDD%Tw5uvb7>v$lN2O4HWC-SczJOGpYLJ~f_R0P|hvh_B zl~h;MNw@*u2tU4J9RZEdF$j<-dWy#CrKDoFoXjbeAPm8TyqWmkV0(x@y+kmXaKv*; zj#O02p(PdaVbwO7K4&sE5{J?@zGu0id;mL2#?7B8)j9m40w_fbhnl47Wgd_&M*7Y% zh54D)q1dPy{+XbanR;rGOp6-}kT|hI5Hxk_RPA?-jg7h{iTgp_d+)spq^v}@bsuh# zpnKy|;5;eNZXk&RlO3FRw$3(qd+(lI3S9aWFe4?ffjW#87^-l98CF#Y3<i1zP~x6H zG%uZiq$S|Zz&=R{$@OPL1*}GvEL<s{|K=?5Wfn+}snewUz#-DGZ>MB{Y1SFTNF&tp zcF1^GI!b1kJu)zA>ug>|R)%!y)JZ`SRfuY!&ZUKLhB;>}Z<ExvceV^;e9dp#6M85E zK}H?}vh#?HMUpF?kvBJn-SU^0WY1e~N$tMfl7~6l3@{G?fWrv)4Z@&a18~v^CSu@> z*)rtwcS-lL<0RO*kUQf_0unJgGe{doMFA4OBk-gOn;K?7ItrLHuwkGHS|YVc*}b_K z>yNfz52Rz#P=Q&?I8El#cmnwmqyvsX?{UfR6W1kC%IBfT0%~+|sMz%x&|9tuaPoBk z06+jqL_t))ZM+Pd(noSTV{=(xA!Qp-X<cUqZr%rwtKT{jo3x-r35OR9J#_R)6{)VP zk^lKW|8H5jVx_8bg<xo795#!+cFr6osPP#$L4bq;G7kTEWfIk37srospeQVh<~Y)k zxYHYis$6!4G}NLlScAqkVcG}Y5@-w_RLur!T(%)R^aQXGa*vLZ1L;n9%PxV^DB>CO z_mzha%E3*WrQ3+%;>m!N3i;5nEs#ERWC>HQWwD$#g0Otwa6A(L_2|(<ReH#<krCs% zBpMZ>vy2(Ta;$RQB}f6jZu81b;n8MQweJ70_a1O|UDdt+ntSI?FPfs!sCTPa#ZB(r z-~t#h%>+Y2F*xLrJQ9+;m;dJ_At5}11Ejn_Aea^~p#?XvL2kInxT)HbRjl4d(u}0( zbL;%SzqRkVb4QYmaBO6myQMqloPGA$W$m)+UYjQw#U9QjZRv{pZS|ICtv@$pN#;71 zw~SvHd>zxk`mAxq#mA5sqXg@c+}w}KSGgAt5y}*k<nz|00tmv8lO68r!<-C<4YkaO zDj12JSP9DGCua_xo;u2;x;;JCS~;T)-!wkP%h-QZ0Rtof&u|X2W9rnG7_jC0SJ~$K zHzAndkXGs!qXBXDLyCzB0;CZDcw2m}4(o~v*XrW4C!fsgt@@9A7M6LXRZ<1L_u7WF zDNY*`O#G>nr`q`o&bFylZB~!-8-?P0JVJ5IC(W;DUTKcWv*%S;U1fLNafb^kB(PYz zbg66D^<AWSit;F3OAvUuA#lQ&q~eL7MinEfm%EXr{7Mk`%|JjHB*GYuGs06o$|dST zKOhg8k;!A7i1-Na_}Lfikx}x<9kll2D2+U<t$1Lqop-?*Hu1E2t46wh&h_uM+y3sa zjk8LT(22<8%%ol0ZU2hp)_(CNY-k6mgN;O3$JyIaS6@e7Fe2=I>BGgg*H(y4M4}2U zV6KrifO8A=(~Z))D{YcUBc?p^AA8=4khaDN<9s&qwl^#-8O+;Z?8}$^;QMx9^$N4@ z16GS>rdkXGWs4k0fmFNset>h27QOx|JNpA4vIZpkv09iI*D{f5`0phP9qXSW#oWl{ zw`=N%(pB$VdqllNn0IVHY>xrQ6^|j2-QABl3w@A<@uDyMa96=g;$mr#_}+U1<jw9P zH+RXD53<QCZRcNlrd@dD0-JV98&X}CQD>0yu%N7<ZJ=y1Y_8H1@+UVjNieSI6q+kk zE7FL3=__BvQN!()#Ot7>r!x2Yi@*2_YsSosN)&!UQ>F-_ynWG2k2*1b!T<<$jA~FA zN5C97I`JsDA{}pNuC>7~oMPZfP~*J}m-z0coxYRFDC$#>7gr@|bQYM6nKIQToHcB# zR&THx7)42>#Z;By`hH-|a?4zLfhA^46;$}fNlUJJ;@*AXM->Z|jYf?2u{i_<Or_^4 zJfuF53t|yu@&p;3l@u{X(KX7obUisB5YZTtg!mBE;-<huST$mngv(ghy~Td9VVNE5 zJpl7fTJ7&->{?1@VEP~kVdSM!UgRX;vH|8bLKL6t<QI)4XLWcTjTwFKY2Ylvd1){$ zRpe7Gfev|Th{7nilNXic>6N!et@fX?&<tyTsTc}gV{s7LrDMhsuCc~R>zs)V*@1yh zD@$q)&^i*wlop2&Dp&Q;FUz`ICTj(sC)~?hr<a>&ru4x2CBYpx{y+TT-qZ1<jC|hZ zBM>Bclw6e~Ti80d&35+evG<+(Hmj)}55q<snb)CCny&=ak&DAk&txEmNhYp3GwJTT z@Akd4ot>Tbm9KoouI8{@1+B9YY(1j%rv!nQ83HGaNzw#3>#Vcv?Qeg(EnmLe7B61x zC&{~{M##%&*~{G8Qg$T>ypj;mD$i11Sm^yJ;1Vwu0@?8lNQw<LAPQ-aKw8WN5zwxE zfH+LMT{e4R<O&ufqa$KvyFPe0W4GP9)ZRDY&DPl3XzjSXUVO>xZ0p1K*%<JV7^T6k zefGrnzGv4=nqrArGs#y@4dU(vthuGt5s@4>ba!`Kl6^3hIEfgkp`$6Us{VL$@=rqE zjslsN`seNBDrQd1hzNKYqUa;tI^iJZi09!!%tRi4!k$7J*t;I-?C$L_c3F4pE&eD& z9)qNl_NaF3cspg`X*T(sb8X!D7h2==={ROU8-tWKAa4~-iF_lN1v5IusZf9AaP@n@ zokdbB6PAtZcG#w8x7qeh`)vOXZH9(;$2mhe{lEug>Auk*Py(4P<V!5P63iVZ(8@W3 zRitd<v}QZ!($nmW^JiMignCO<(*Sj+non@z%Wv`#+zb8tn83^?i)&w*+bI9k;E;Xu z-*2&pzI=xbaJX*`4hk;0<P!VDAAj7}#tiUFkj}xayz^^f$ay4x75C~1bV5{NZsUx- zFurA86ytobR@=Q{GY28V^y)xOL5KcSYy3$Br$e3?`q$kp*Hqi|^Uk;ZkFK)*jjLU2 zT27x;Gd~Vss<~;|qc(4HJCc5R!OIVV!Z;;6LexJhFM^-0DmxIFf#8Z@ylBxPyZ`?C z-Eo5svfQ?9n`>glK$UQmgY@M769$2|K_gB-jXMcyp4q<64h|f!cs+@9^0Z83MbwMv z*XUuA$6Wi*a*>gDOEfjEAYo1N@vLuP(Ouo6`5PDltu0;(>9sCuylYCk<{L&t^F#ur zI2tRhN1m1iQfUJtptP)g2-39H2H^u4$P5sT7ZM+w%)o3hHzFZh3{5OwdA`a>X3x${ z39(Rkd8KerV60q=1EZ()(7jKnx{j-e(>mzY=N+?5?c`4gF3?c4+Rf+eh0^y~%*5j` zb%W_{+pu$;9Xjpxma82{66H^pd3Xfi6RS81(LX%|L6h0pXP<3<_Gf=)H{X1-&qq0O z&_1P)fBfSl<D*h2LEsgHzzJiLGy&$$o$G_Yx3|~o>gpT`mE5Yng1ueJ`h-G2%ej6c z(?F}(lj8wROp@ZY*z*%kl83GwNCuh`BrPPVeK&Zr1L>@PZkOHq)!Xc&fBG(~o;1@I z-SB(X!QPC)eLJn5^bH`{t`)0o*{wgYOaJ0e$$*lOAl6mYS!?rHM|AS0)<4*X$z6|) zZD|VSd(BiA)h5(4)R(vrRfrGBjaG;_5cSD_eFvH+PD}<*DGXO2VpE&8*hAm>j_rN& z3CrTrJAr-wSP==BjwB$UVLj{+Ohd9^j9vVW>#gmg%dEDo-KtyKth@n<DecdIeBB8G z1cHbMNg)-SjsP~2^y;i4ImXZdymC&#qic<Raqmjo@XYfz(9Ndjyq73#gvLr9T1OQp zt-JT8?!aFrZDJ}@%0T9Ii4-2{`mJePwY~A}m)op`Q*2CogVi*!;Ti`V8JS0tn-D)= zIxL(B$iqx9RBg*>BLJdINsNhsL5R~=kKeu2I`?-XVXd?4uDj0u`mg`mCXR1+32HF` zulBwwgBtikfp>yw7Uoyp7PXgZ;-vAmVtAv+3;ZItM083TjdF=`Pi8y^Xo?wT^E}_R z%%5vBFT2>5Z(fH<W(vpbW;Mk39PYHuk3MScXPjv*3r?lKIE)uSyVj0=RCeCY$~ON~ z*M#l~eI5<)h*?sdwHHDXYY7u1R9Lxkr3>-IBnfu~qE$JT!buGQ??PrQ143&VT_2pT zz^KGHib1=S6z2>Q=CN8^#6##jBaJAx4&dW(L;#~%iJ9LyF;o(Q`MGEk7T_(BwT0z^ z^$MYnn3UlZ<)&eGw1)6ZX=47Re$fn&N+>7o6fvPJgaESp<2THDqP>wZ1UNFyRz4LK zF!0##kqcwKhB~1kC%G&ZWa_LnSBj`OObohgo|$Es_T~6Cm*y~9mL)GsRq#8Wv<|`` zg~bbU(HTAxFfTpi+w1qyTC6f<dMKfw<}&x0p%kX%s+;zu`idC7KjN?8r#fhUN$@5! z*Lpm&-gx7U_RvEQ*|KHJ?7)Eo_N{My%dWigN?WjCL18Wi*dLK$>9GWX|0V=Z7?Y$) zAnzsPF&olPL6QuG(qMNml>WTNAm9if&vA%QE{92SBlvtfH7BG!s;Ej}brkj_xzGUW zQ4;ku$S%horHw1M*<<&vwhP|4$Xezuwk2<Pvpw*Qe`9aYuvLMSbRcWz@)g#zZi6+R zb{eXvjC;3h8q=JgTR9s*yVKKs*qJ29j-cFtj8&PDJKZ|Y6pas2F9K1_k(dcE9tcX$ zd_p22d-qApJkIXxu+=}i$DY0OE*sqXyw#?M&>jsNbcdJJ$LBpX>M;2%y!3T;>icf6 zR$O|Q*Nwqj9EXkq8=8v41k$TaAzTV{Q$I;vMR-F*c)^q>qF9W_FhtD3J^l9ReQWLM zWk@gg4p_2}dS|tPS(+meHvIS(yr3x`Dka!!{oy``37CkUY;2Iaq-??I)9v!NEU^IH zKq9}{r%txYTK2xsZ7ME{no10)=mckwoCFAY3mze$K_Ri~<>oZBSCZmnA0}rhorN;s z8>^S#vF}rV`zg%4CVO4<ZL}Un64iW$C)Gv6JqW&lGYoHATPrZ5ZJ5;wB2p&t#u*v) zu$U!2(H%cXD&Uxc$jXkXx3+}~taaK9JH$Rbxn+m+vkHjK&h^jPHpY7s=c>dLwXVI= zxX?fS5BYhf{zuRHMO_rZH)4Eroj-rRZy48DQ9rE3-ME}L2xs{mP^Xu|NeO{M&lPS$ zGxW$vL_kpi^8q8G^~^^~*jw1vKE)<CPqa9~s&W`~jbLZM8N(=3&<6M0!Onv)Ez<JT zqBTxfe{YICM?JXaPD=I#-@usWDrTr04ON^qB%bL*9)r0Y6%gx#^4qdFgBW0~NV9gN zS?h!V%Gsk@US5Z{%R0tBYa&{#>|i%e85rr=0oIt5YQ(x#ZE4OA%U0Bomu3N}S^vb? z#4Crbp|y%Vl<apEqr*HJO7<db=wLmhbT_+;0HYa7<76SgFXs!N@*&=tq-Yjt5{of} zp{zuxm8GqeQwC6ic8YiWbB8T?m<70!ZBbBKpIeHf3Yv#nJ9HI|__2?D%pOG`B0RKv z_inp~J*{GrqWN2tRq3__ftL*eCyYsokdG#S2Dz?^D}@pSUds^B5Ep6z#ery#n0_F{ zIFf43gL2FyhSMM|Sw$f6E7ztM2(%0yj?#yRaN_WUop!+@Otc!U?TV|d<|nsXx@#{I zb_ho#e_cDb*z%v=ZI_{~HTLspb8%fwErmNN>id!g2XNk?dFP}7mGb!~1gIKDA%71Z zl>Wuj5T!XQslVQel!)`qFob~i9vyh%DSPtP?^@@Yl~&f<X)Peg1k76n-wcA_k|6(s z<W|-;-rn{HAGMYxXIb5p>7I8Pdy!OzkbOD(0F-ywh%boo%Bd3Ss9pZ#JB$l%nIcL% zl<pt4wJWyT?ccxO_HOIL8(IP%3zfhGqQ@&5Y~|HVX@Eo&H~|kxq#cVx#7lCU%nd-r zr17d&Z<k$tshxT8EbeP9QAOWKYvod8v}h1Ys#AcWDi`3Ps3?d5(1DY_2aWtiD8Mc7 zA6*DiV7lDeVT^A6>}PEXUaF{un-E3}X_U{&aTSn{4q;sv!4tD)&Igl*&IvO5SVW;h zj(&B9oBIG$jZ+6L<4k+&Dy((-G#kI<Y}>tgz10F!X_NHp#RFOQGwUpK@ji&ONfyT= z9)*xk$eV|wg5GGDJ4@!{esq$ywzh)v2H~bnn>H1M1Q9Ve`is)j$p(R-wG6dpc?yaT zaWW9=E&!q5-N6b`aRgNJC!S)L&$y5?+?e}JT#a4*SV?@%)^|w`1ed?j{{Aw1oPCcE zE_)0!X;vT|@QN0_45?Tmj-#4%uT>}6Gc>fHvyr-3ZV;BRHozv>0Gg&w#_)!&UOU7- zP6=*mYa46|mIIAV73?=+-KMPa!Coux>agMdgIE#Z`4NUof|#LrjSbWdS-KGiGv$r6 zB>^MGh=<9^akzEWv|77z;bk^s-X!K#+Sj`w)y)|s%^Y8~08D-kib2vZ-{!DCDZC5N zV-fSfUeYo=hHm+#J-_Q2a7+(n!cf9=rm?36Yy{17X^4e)Mu&(F40uSwi4k|;a>*}u z;In7Xw#}P2o2-xSy6Z0c#3w!xa1rnb!kE!{mYzxw`0qmC2rBKro89q$uZg0dt9}vF zq-*ppAlKv1vy`#~fmb^OMC3=vVKh<zeSi#ONcQ>$daOBtTjLan5bW(p3&J{$HbOSu z@!=}#+S_k;-?7Zz`MwLRu5F^7|JJwL17G=P5QTDwDM6aoxnhNNbC%4Qb8!U=(yfD8 zQqa6gV-DBXkDD>oCaRNHOn>}FNeP;#VXjgUZb6Qo1R|7Z+0jeRh?w2dJ9gP)-}}C; zMZ#BkXrI*~9hGKFglHP-KSR0wuzP(tEI5n$&Uo9~tYyv&Z2xu0C=x@Eu-tFUE?-PS zImAL#6M4!LmUV_MkDo=`>b)#NbO7wC$F|w+KU``DJMiu|gw!=#1vdn1N1j6L%0ru` zBhoy9mppG7b(D9jv@=H;E3Z!5>E|u9OW(BErp{`!DopDnag}>^X|nXs8!wK=E1*C8 zR3U}@C7(GL%2&HcF6CDS^DR+i)QCf8$JouE`UhLYo=pFcMB0lav##Q`(er)P{}D8! z#)r!4$=d_`1fG_$>Sy|Z_G|n{>0_vr<nCCOk0JmazOFrl2`4^>tK*6Z<E>%dT&oz< zf}o(&>c|s;wN(MHF1$MKeQrI3WINhffGjO77Y!TLK{bm)^z8fSittY{-jT*g&KuU@ zQeX9yCMoi87vZQ9eu^M^l3kA;riB6GdKdb>5E!)n5A(T3G&JKX$5^9Gbs3^rv>alX z6VfL0ETLA6J&K(N25iMoR@sW5ueR#m8mk$~A-KXEj!~G<4%1AJRSoPXo_$Z*E=vp# za?}In$CM@SdIuSxd%8Q(?r>HTW4I0T+duul|Fkz;`6kSK8`w)aj3#=>Hb4EOJ$c)Y zY-ryhYe9=siDs#SiuALNbssv2d2yo+*0kb`f};ttoVUkh$RyG>ba2p~i?6rS$IjwR zJ?0W;_K7*uO09o!@(>FsJfb*fkYJz`qq(E?JTOptujeQ=mH{?ktGBPgk`TOw5O5eN zpVnKQH5W8<$|2+&_Obe7;ZO0L@=}1W;`GxYvNEyz;upW@YooMDk38~-@8b+>Ng<ok zO$h=o8w5@mlN1enwIm`2qWj`^FI!7X8I>S#f+3(q-?0ogfzTeQkZ;t*Mm>`ov<ke? z4Ib>nJgp9)J6KXgBgDN96_rzm7?QcczCQcqy-(TV1v4-MYqgg1F0|U8+-80Ic7wtR znCtcI*lcU=UuqXGS!^}c2{(0;S(=bluS`P@b%T5$R8=v@NL;~TE@4$3gn%|dlm+HU zv7k<AQ!ts59e)<7-j1dB+Dgu_IJ9xSjUC2xL_d(DOIyiv5GLU;Oy1aei|vXJ-Ds_6 zo?(?}737dXrga(ek_lA?laX?mC~3ZA(GfN^!(51<b}X$5QUj2%B$LUWjBQxaVUOIq z9LEehIb%eobyd_09RuIX4xge4qP~MBiA<><-($uiDR35Tl$<i;;z^qfQ}p_4&$anW zW?0P_7_BM@cUDPhg9IC$T_r|U{TECCb)_QwR6T)_CnYTempW4qg*bgUjP!OGrXW#M zVQ+Z*b#}=`mpPn+cRn%7f%wuosCGxhdm+PD)s0%LP~768dv1Lrxl+)-i8>C0t*NvW zhhS;UE2V1(r7Z<Sao?H&B*k1KG%&n%WpIxiLz5&=V`JycvPtt#wFAF=gt-#>uNuy? zd(U><-#=%QE<BgCFxSAYxFcMXsKUHFvJbc1h;feEpvUk=ai^Yosy*<)1I`@n-MiQK zCyg01#wFHnMwCw*WmUSKBoJV1`3Rt^qxtHC#fJgH5**qvC>XEIeF;SvXW9dlz>E%7 zp83mIWKDrJVvO<;V;2iuzwX_92<JLa+A}M5*l<sURU#0nVZPVq`uO!&d6IpZ$=zt9 zdJI30FiosizChtwk71w1kxb7}+75IN+8}FU)7Uoq-~a0`>^<*%r#00zU?N8iU_P|& zPDdbc{sm{-JvV>GIv-tX?d4T4T=Ei%TX7h%p2Pd?FfPOUE8EEz^Ez-z98FhQqRRHH zI%E(1=m~q*hhC4M22Cw<P3xCNznUZubP5!M=8AV*74Ig4#D}4;Rgl1ky2^A`hwj#} z|4LdZpH_k&3wZ*kD%x8b@Cc9#+3Rb99@H86E4Ta~r5VzE(>Z0=UVE*5`O9B+A==@? zhwbM-|G8ay>7}GDg%Si_83>#(CMjx;27f7(An=-ifL8WVi~kX=ijaUO%O~U_8e1RA zd<**9W-gj#dytZqiwgib3sEINj9D0;N;kO!v0|S-bTDQA`L)~a&p-M5)-Yv`o%4pb z*xg_IqP2q5s>v%i)NA`zJ#F1<*I3=$1=fgj6d^acjZK4q)0oD2pbpLhQJl(Bh-Rg# zrkaX)ltj?a?NDNnZEi4S{TrUQhrWHQ?Ro5BtL!~!O-Mv#0wwgBqaOX#zaNy>k5=eS zH~kMAd&TRlZu(5ldP2*C`I#`U%&h$ABMOhx&J0pf1vf{esECn+Y+(a1aH5Wb{b-IJ z-EI%x`?z&%>9SNGgvv1cMPz#~Y^_>T&vG&jdxyk)z|aNG%aJfSlMXfsx87AvWp>dO z=h=l<oMvMu*P~5>K%y_?*-mcM1vu&S!d?aCE#?ShuPlnVO2JA$g*+%7_eXIVTz;41 z@;8S`WE%6BH^1vTHe6Rga5*Oz^2;X{p&k+KA;(wa->7A3t>7MwoKROeZ4j}ky>@<H z3jnJdQv-v}SYqv0Uy4a`0t{(=99RZ$YXmWd7(ZF|)QKa`0Pp6RGi@ANx809FhD@G= zhWS1w9FiJ9oAjI=+O`uX4+|+g$h%cLC&&ub<b!CCdryrpNfARD!F>Ak>Fz*7rag+= zvSkY<kyGeTMuM33QaDK=ppm8Vs-W>eUutdkC>VLPxE{nDF?h7xDNQ-!4})lTtB}xm zMCen+nj-CIHaTqDpXsn4eft61vhFZ@h00-yFq6Zyv>NYjwV5ufOmYZp3I?gH$LjEw zS;f1ss<JncG1<?r1CN)_cVlLUW<HKd?uS2glU?_gw_79oNi~pV)~q#4Yf&`^$W~R2 zw>SUc|FHWG9<bhLSNM5zHLR;~?GMVZKdQfj^lg~n=^Qc4k74jKSSTb9rtP^Wx7#nL zt+Y$tbh?h8lf%^j27w|!M|2Tm<nxrA{GO`^t%<6R;G-#swv6T5odmg{M}jY$NeF-$ zEEm$OeG;1q(7tZ^$2=;JJnZF?JdUZk=)xoCqqOT1Tr6C;&{nNl<tBFzKm0JqSs+jZ zx0ON(0<Q!FPWVb6AsZo~;@>OL*ixP)2%Ja=$N_-}EdPNl+}t2SG#-y(161D|uX`gB z_eyB*VN0PolDD-i>Ex>`lf--hL^qs+$r!A*{o4lY+h4m2=4y;JoP7n~wTP65=*)nK zIXQmkR$Fz~-JF+^;$(O<Ae18nG}u32hYuZc$)0eOBPmt`;VS*KFo?JujmPpxdMIfb zHYl&X^?UYXq?~*1{h8JDc43Z!4Y~3MDMCANMJfwJ)(H!6$wxkFldr$t8s;p-YZPXG zGKT^yqfcSp%ajA=2%<t8_eE5Txe?}d4I6hf#}RR|FKrLrz25%ulRvOqzjBXlTXWcw zhhbLIAY&2aB7ZO!(V?$8w?y8lWNI%)2l=oR6Yl*i1M`zC8?ZD7FV0^w-9GXs@31$% z=K>oyeT<dY$g>rFm0ulofn{>|i&#*<$!P>NrD7_P{K5S~|GL*tbi15w=$_=Zch6pL zi#v%>N}06al_F8?dOuG`(gM7rwNP;<WuScup}m5K`UN5jm-B7y%`lt!z5+l_deTWc zc+&gOfh@QwO@Oxq31V`svdYHIn@>NTf*BFd`kqUIF}Hi;I@^vD2k!~e=jl9EBXor4 zrW}i&c@z#3ycLSCI<HEEnS#=6*s#Ipjz^UKoKz6dx)+6!JNlbQt#b;Jb%=e^UKou7 zcggMFg*h&BU<K)n<!v(|CWmz?g{kkF`?uIPzHpmudzO81EHq`=e$MkcXm#1W)|lF6 z^+Ox2F|*ZL<A<y<KEznZqa4gm8lg>+GJ5#!fQi_EL!Ip~6oZWCh4W6eD=xgm+Q;HH z8wO2gyILSvnYbXN!b~p4KFN9<mR#{iA7^vp6dPom4&ls1JEbZSPt|31Sxs^)W_X9d zE$nZiJhibLhN-io&z|_jdfWC~XP7cfS+y{NhuSLm=o~X9Ci98)SW}cll0ykzx@w)& zy%-}Bd;a>)VMu)iM+v&LZu*)@3P}c|xyFsRi%+QI$b8dtlqQ;^GP!%h8{XjaF>>G_ zlRJe7w<=yic&@nLJ+kzt1c6@@0u1jH7c_vQ0j*j@13DV)C$46tl1mVHi4f3w{{o-- z{vD8*2uC?$$jI~|Pn-!ox%n3oz^1lFd)s^7YC~*-%_KmioYj#6ArI^Pi3+5EAV{5^ zG|U-DL&=1#TDjfsx$_CDXdGva6Q}W>3V?)k{!kj{47-;<Z37!Oy5oWB`f5jFY0TPs zd%L}^j_ANmP9#u&M{xN@h|m<u$%1%?k#6Ra>^<7K!|wU}zqbdz`foP4>v^ln41kbf zM?gyb)PIOJ^-#b4%6R-#`<+jI+D?7%d#q~Wc*}4uM;1+rOsQnLrov>|krNzXjzks* z^E44DTAm;dAVdcHlXmy*kK3m|d5itWzyB9*y?0r%AEeAF^BK%w<Z(9xGS7m@vk(ti z7&cuq@>EB%3<P$PcbN(p&+?4*$8dmAGi3A5odt7rq0K*ciq*8>;Gr5cjtf2!17d0g zN7YFLjTkPmU0z@6tm-37CWd6BSD;jfDW5?!Xe>}3riTyQ_j4To;i^|J_(uI6y!KJ? z*HloS<pc26KeaajQ!K_Y29wm-RL58e?tqn2G*|=$!BQ}f;4b(9Eb`z7kYknA);9YT zYn{IU$$J<(3DQ^7zXM3qySHqyT%X3Zgb7}>a^%}^;gfK$=X_jvbM#*^N!ptve5CzI z+qZ9b!b^P@;i{v*D#e@(5b$xJp``)m+;o`dir1L+p%G1VZ;-sqh4CzQMdo$oED{5U zllJIO*Vy;IdZ!)U*=rR;S*sd4$T0^9jZ!<Tx^JUZ3~aWF^lqyy>t>H8nq;jK6x`4H ze24-Mu<#BxG}~Ux<(}&swEc`Xof~(_C70RUQ|2LX%Ci=v)7eW}Lv;R_=7=1KmsQnR z{o*t1>Oc6H4b;}daIsRs4AtWfzoi^AzvOl_S$nKJg`)`0QmR1RBU~fF()JDeFjaoq zvNC@aECPSwQ%<IYWpIIVsxM!DTH<`#IMW0^@_%9d(~EGZtkUqHIjbLm=7fo;tA`LD zJ%y-a#EnWoIV>PGH8pnCRaX^E@ucOI$(`n>=A_a@4jiI+DjKsiUylH0>G8NB5ZLzP zPX6*G)L>T7fQ}d?CmfhqdZ+tRC_&(4g+PQ4Mvr392N5zMl6{eDQCZl-`4yt5A-*uF z8|Jk1ORkw~_x^aP^~!~{Fjofc3QU8}R+4r}ni!e0Ndq(3Gibkf=n1PWKVV~K&$dk) z*WiQz_popm83_G;_9?A+;t{KuGus*<Q2YD)Z74NlgSZM8l_0z*;$CP^`VpD=fsP%? zX_ksK(3!Jk*w?4`?6G^l{ta96-~(34SxXp3P(NwBv_Ax-ido$N-}d9ecFDDGvL!dX z#~P<jv9j7m8=%c9Eix@*x3Zs&qw`gTfdwo0MhIT9j6#ZLT?ZgS9(mf9{`_G(d|=SB z{V_H{<E<|)<|u0^)jxq`R~Ve!fnfd$tR>=vkda19Z&1Lw^fd$XS=|`3GtWKUuDSMX zn>xGEhN+9Hp*n~*62TzFML_g^!-H@=FP%uBBt?5rnIg+E6`|&^rp`b~LngNBJ3suE zZCJO;W=}bttzwWh8U%b?PNjYS!wFl3^VNUZFW!5es|dO*<6WNZq#2S2!Ex;^02fFS zFa2DAV_-qGH)2@Ksrt*ARE<rIt<W#ptCqkWaP4V}t?YrNn0$6ic+Jb4RY4eLJNDX8 zXNOg`(5H+vNXpQuBq{Wl((Cst!h{JEFlS<a8)XV7ZQZ)HfUAm$v0sr*>Gi7;0$SO$ z&W!{Ki8RhMmu32_V;D4M6O4f}1Tpfm$g$j*ce3^l3|n8%kS)D^joo|OGK;a4){sGM zs>_;U-InOvXR*|NWLo_U^#M%l#Lk30k*roQLBqBmbF^W+lb(6`Rkoq0*H+wlyX|2e zMc-p{=FGE;Uw4JIBUn;UJ-xQ9XMRo{Q-m4fXWg>ISgfYrS}(oa&e*cimVNu{FhDrX z!Thb3myN@i+#yg(G*sE4SflkK=yJ1R_6`jVByG=*PTRR<pG}+J&i+fmB|t&tDwI(t zXVe^6yr=F8a%3X`k_$9+QALOebKMhry0Dsyt|PrZ^;aQ}e1hY;MDuXkv}tzkx#zk& z@IzQb=<KAPo*vVFLD7;C9Vy00_l{?etAtXb5(JKhzzIXo8n_z7`srSSIpX$9gZk)> zD#e`q5D<YU0$k>BVmungG+J2?*iLwdKXNTyQO|yjSf{n(m1ye4)9i_dR&vUCKLjPV z^4K}VF_Xv%n`4%cf^ZY6DF<2g4R+b#$2Z&S7vqtuB4e%CAZ6e_B(WUIbmLHAh0UEa z&ML;&SosicW-A75d;dP9mVM+QDXOXgG0Qb<Pu9lUz&MEfXWOr>Tk)9P^|i0r{?*T5 zR}T`d<O{i-g^&<a#ZD<VWt+5MuD$z@K4ufoI30_?TH6N|o3cK53q14jPi++p;*hXj z1|X1YY~>*-CyrwkVGrE@kp1v`ciKQdQbOF=#z5-j^%#+)dtAFD?{^|*vH(@)h+<yk z#m-wpgPcj?Nv0~&Ql(`xk2|!v3uo9H-*SPSGJhh#i&H<?JQzw59YXsGacM2|oENVK z0zmzwpmZul#C#s-JM;nrD0oR%n8Xps)6YI_pZ)Y-Sz=NRWx;G>UYCV{(P{KC+>^`P zFc1-*)k*p%z~NYxcX~*DLy+SJnJKnU7^~sS0hU_-MObl9lIZ7zlo(v$1m20^mzOMO zc*R)p@pw$`CM`VO4nO&bj~(?!6~7_Q=j!X?a9%rwC*`eP)Ywodq5ss!%30&>#exKQ z?d|QZLDCsXktRvslyKCGLGIQ6E<YSbRa8v0Mob(tSb3l<LvRvLXudL^d0BynMU5Jk zRO>x7V0V3InLYaR<;GdloKc7OyWwuDMq^VkxD6NehmipdF~W4nH6KVo#K7+5c8I(V zV}?Ba!i((O8{TUxHgC7@{=a{*O@|J{AeC8tbF+Q)kN(guzU)$;GnzhrATw7N9`n8C zg{F?TL&KQ3SVNO7_`MI=I?fCmT=OL5$?SO;PpRxdMU$1m(_SU(aW>vgJ8LZoLy<t( zbfBZhHm=)lQ^5~9;=nfuDr54OEuGdfFVG7kE+5F63TQU*Pw%w;a&fb}e464*Bp6qm ze_H(VIPWzl8yg$#nrp6c&vt@GXJ@C~ci(;XHoT>3e`iETMl_|v>^So;B`ZPTNC=!T zCP@|1VAcSR2C=TuL@FVnBfF~fd{RRItRR9=Oo7~V>wr=HL^QgqR0zQs1blj++kW`) zcR;c&mTCdTE<mmbgCz3^NNkX$OdllG1T(_XNU8|kD5}l6FcZ6HaI@L9XV_lO&PZS) zmq4R~zdT!8m9n)P9<`a*oNg_hQ&2=DY;S$9eeRyGK(K;X_$OO@_dW!w6A}~VlRIvy zcMk9Eu-=Xii;qcJ^~JOCz%*dJFaz2{B}PS6;KAA_WA4|~Y~MSy*81+}08TUq!>FNr zZwL8@lixw!DiZ{pW>bCw6Fhl*gD<fp<|=*NN$Wn?k0}dY=cY-6R!y7HS;@8ya}}CO zyU`#G4^dC*$cM^HB!i%&U%mw-1lQ*Y@tV3CH)YH=ciUatZ#Ub;L5{#odxONhX4yof z^`{&}thFeMq&Hfd0>z+4dP`LlS*t!ONgcs|G#NTgUPM)#jnV@{gLt`m%BEhu*s7Y@ zLx#pn43x%!h%b0H(uqlW4F%vJ*o2@5+6a>@J*CVj%e5zITr)#Tl64=ro<>BLn5019 zsDr~#gk>rtU8**E0A~r*ATV2|O}FNSi*4JJkGV%LNxH=(rS|W`!{Y%PhuLS?BjLtT zyeU-5%RAmbGiJ=Nr=NZrK}FJb?ATE->lqmr$D30r-Kzxx(MSlRbEH-pgJRHAFvKy0 zC%y+q4iNCBlf%7tj{TsxKCq$Qq%HgT8hhlfN31>>vsU&$Ru1mw%%jb?q-P%zLYGR$ zYqhkZ%y-TDG;_X}MP>k#y2?qj?aKGP$L3ynxvkl}$-d4RcTa8H<Ym`zRKx%L!#}Wh zUH=ZNs%4E(g;;`RqOJKM#)MlBnht6M{Fmbb78NTW(`xfBztUDczrj-dhk3#JMjaY3 zJx*c%m$rJVZm6~%rW4+2baI0oJkW1Dwshh}k|m1e$g`KdaeiI%2*D;Q*XONPKedk^ zb5Au<HI!CPhMaz*?qTWGdud}?ne&O1+HdvEaR$Lc>vKIvM#$vuZ~o?QXj96%y1MMa z2OqR|;sH?ai)lyA)3BycHLvG!7FJ4Df<PVuCzMGl9?X)|={d3|E%i_d0<Q%KI9|zP z1K~RbNd<*)db+#O_Au@%kX*{nj0AEEz5n1=5MKu#lStGaJSu5VM>ai3JdBmFBMe8P zO8X@sCdJ5rjkK@lpqME39hH}j!&4ZfDX*m8FznXTNHl9OL#mlt58_AD1fja+;6|jT zA_ORh;tGf`UvV)b@<31qfghh#1>=CGhdL)J>d0H>DEcO}hh|w<tOq9%9Avm>7wy7K zMRs}wF%UWSK}jyDc`oD{99fV7qS+XZ6vU*-YoB~>=jvb{t08b<jLICd!eG%(l_e(0 z?d64NRX=hK8W|x%0hu_5bpW``=2Xvge9$^_du$J00mYld;$n)}zod!-BQdLS5l2GC zDvNTR(B^gMJEi02W$3E1)gCc?AY<w;b28Q04?=`NZJ622n$`+Kmt>PQ^@THv(U%## z^Hs%az2;QyH5ddddV+E3o3^>vc$2wkbqhvIl`^xYZyBGFmQGg(Z5YmBY|+0OHyX%d zlzhLM1Pk>|)-rd#)lQsZhjwhl#EBu!7#=*-Wj(w0V1@_0c`kzi)|d{pQCZPXF=6a* z^MYa8v}pyLbnxIoliOjL^_0SE69O6)n*Um(#MsMxE1@&G&`@aaTWly}J=+i2legbx z6B&<{912@CxYsIh&`^V;299!tL1ODDf)?c^x87;SYcDf>0JFV?*Sys({@{l#(LUC8 z9olbSzV%kS^MU(Ss#p?xFV1b=`<@$YOf%-9J{cIVjBV}rlqS|kug0@(^8w7^bHz3K zc#~Uj_0{&st>0u03|I~GuY$S5_9Sb<al>$Cn+^5Ft-f*w>s7N=!L(&@0<>+@AzQOz zyPa{tROJ@_ho##~ak%)M{;-N`LCn`rb&)Vb|5PpQmlA8HbYbQZOL8$uy3t>;SDu*r zUnh9K&?nOHUU9`0wsh%IHy?lU$tSG?A)ey3KPftA?$^n?l(qzcV?p4AGD)gXq&d<C z*(fMZTz`r4k04UIz7`-L1QHw;K!Ah1f?0wHa>hFdC7Z$+O?F5!)2L#P1_#1c;M!Ds zH*y@z8i#)ngCOKHoE{Qg56+Pdc!g_0%H%B$!Y~d4ljQ_;N%*pu+{F{sl)(-SNh8r% zIU@nW1wWFGd}~4INK92HA!I+FMwKN98Ty$*PNb3t#DW+Sxet#~A!$uW#SaEgC#xfE z4O$Z9rw|BkzQOCT*_izu+~?5HWRU<$S}XH2vPM#ib`7Q~IWS-q)esrAoEy^DWAPfT z3$&NKbZDb+YmT}KLF-ZVbsK$%lcRz-BSQY-a2A~*SJYx?9PTija;q*ak}{VMJTXXe zFyKs_DyKX~VRSV}vC=s44UCVFvbPIHwhTf=gaUdE@}L}Gn7|8_;V?q(tjlSj2!DAh z9O@-KXECW=Cui^h`2tlB<j|;>FqRcn6*hh5bbJ08Jb~pIBT2)>b2{JYT|pm7noYc{ zl{D04N-57;(p+kP-n2!Ftc!gctNwGh<x+z#6v$$l+P8d_^`C!{)h#|X?6Htgp*R%7 zIt-EGx1;Xma##eif&_VM)~s<i;3C#a_-PcVPU?pdMw$bPYdBs32BWeOb6EO5i)T=+ z6`eaf?Cxb8mi_&Et?EFRRj1ewm+V4w#2!b4JmvDJsr8aYiB;AHumI>AuCYFZA>$aU zZ@lsSHu2oEFyl+ua-8XW`ZNF6?!I>^>vY^&+uH1dzx%s()9>G8Q>RZQPLqK383!j? zz~t@Ig;H8Twdk=%X?>D>M{B+?h?pouUsf@>&2IYVf3!Ql@CEC9>M3jEd(F}c1T_uT zVF}irLCmFdm9t?mT2Uy~+wSMP?B3g-vN5<7pE1A9k3Y~FD;(mmp`2*iC@+~G`kE+4 zNo`hT2|B+?doA6Cc=3nSInwBdl;jb8#rJCCuL{w8(^}io(qbR{;0Nvg`|o!~R$AUK zed$Z~sZV{%g&JaRT^L8+x|Tu-0xuN;Cv^05BT4_vXFg-orcJXOZn(joefC-ATNu>Q zgm|e9D}7gjz;7M`Ec8MQ1pOT~xxfRiMIl}YuY$cr)5cE5JOhTN4@PMSt<Vr>Sjd;c zFir_{fF{T$i&kbBZO1TDcp;;lOu``6yc{S-?dy;ohCIOK(jey{ytrW_Kb);bJEd*w zFfKzNd6=3U1UmFQ3HdIW<;)>H^J61#nKWAb%5;z->4yh~@Det_IUD>qyJHw;tBi7_ zb;_bC8K(Z3jO2kb0R(}wnOS}yhB?_i$)@I<%H{yWY>M|uuCy)3HQf(FPl?g0B~O?w zzR_<u!#j?buShh}cDzP$jz>IRLp<6f+Noa#v8;Z&=Wru$FI%FVsnOo398BdfM1_92 z{8jtB!aEYm)Q#sXZFIQ7R4T9Z0O{EyB$GzL5_Zk6Szsis5K1tAr}u>)@OGH<9_$Y+ zDVz6kv`T`L%yVQ~=!_KRI>|nW5@0f%0dBo8u3T#{5S!VGrh-%_YoPT7;z{(9hv*6< zMV@&YnIfWPQxLN|XZ|cEgc$57u<k28V>1v~BKv?JjFE6cIp2sl5?;`}&|b3gapP?2 zMHgH9oKxBV#hyJhfiiJ=_Nm8g-7g<wTqpT{WIjf7(xupiT1Vv{`#OLAd}op(LTly9 zl`g3+;iqH6>s1k37=NKQKK|(ZFcdT=!?@C0PpWqzssELrrvj~yw83(;BH_<K*Fk&y z?w{I2w|>K7yVqNN|7L4Q@38iYUTaDuadxA1S}wg~*2{XhKU0BLy~%Rp=iBM;`LMnB z3;$}9F1pCd>T2zt`<B}8f9wzJCqKK#O{JR~o9)m4{Lkz!|K_i3+Kj1=JT!CkPv^$@ zc&COEs)eyD0UK|rchH=}Gcixxunz%(=1dh#+1oz*4>t9@^U-1v#hj@`5>X$=TsntC ziRAMZ$Ln5eWs+yi191VmVa*o1@28xr*TsTI=1e;vC3uPP^J)bsMZhA?g8<7fn*V;Z z1uryjJt!S7naNrzndjjbeI641>c3Hb5~5dDR@!;zoo8=;^P9aK?Mu4*?z?T%rcIua zERr-w^^3my)g_ctlpt_41SFt4Vd04<p0J<%<R`Y9gEQ~C>n^+e^2`0OuoG6HQo$t% zybKVCkVPS@2&oX^_yW;5dxGuF3*KOT9lf@C{WF|xp^d^2;qv+gL*mjx&p;>z^CBT4 zn2HR9yG}DNgSeL@u?%9|Phppdnuv5q4j{Lze9R$TXAh6|CJjTNrg?|a9QZ8QhsQBD zi-WZiNJ--m198$RNb@0VCIVN)p%7bI8;>yy9ImOhth6Si(>qB{wbxgEwsSB|`iV&p zqap8N1&Ja_91M;bRSxYCppckK@~Sq<S%MB|<Tyg^arSVSU09rQC}PFGhR}9%D`~xi z04X16p@G6&5L1#kF4Da!z(K`G<DlS3(hK*;WBk!ee#JC9G2v^fC`2pmw#xH-_@f)I zH-wa=x`ICpq`r}&OMAXV$d`#R0Pf{7!hso-=fE_3uEy21+8Zvtk{tq=@d#QDm#Au^ z9=!bMP4RVfs^T}lnR|i4!NIjq7nguXu`n}w!D9@jItvpU2Tn0y($tQ*W*nv*rh3@N z3*(D^^Ks<+?li*aS2mWzc_NvIVFikexBz>V35?q~cdK>LS=RCFYO6*9AhXUG<0bXn z8XMZO*=kN*0D&0LobTOG)u>}6sdwUz{ykO@F*aw;9CrgASv+jnvgKGwOL4zx2zWmh z7pe$;x@Z>W-{)g_6nmkyMk^qKAgzJYRB9ce`!(7WwC0s*9Ygq3#(Lsw2n%2(+L!W< zT~^z<$C?p1jbSh$*79@VWb7NqsmuUtVE-`teXP;a^=%e!A8(7_c%@zX?rSj*r7Wto zYV}IH<?FZD%4gOvC(v4<ReIn1Zm=7E=iOEV;jfXXUs%CHeF}~73g$^RUx=um*B$MR z+M)NXJ!PCjH>~=OYqi(^fB(yFxnZrvx({0`rl-=z*0b)H<v1fRv&}MnRaRRw4Q8+b zEp6O3uH9iPpImE~UcJa2SI81TjFR@jMs-t}p-utFTJs#f(%7O+tDqfj8HBJbESQ>a zGCd3)SAjga=_BAweS*M2Igp6|%2lCIjISy55&aM`KQgJ)nMs#le!2bl$3ONpc>n(W z_P_%V*law!9vOrKLODmiDLt1U@Zu0Sp-j>MrZt0ugAD$h>0X=g6e7;QG^k&^^Ga`D zWe^y(y65W_@QAPcGGmh|mz*8or_Gu{D!==>>n;7dciZ}18?2&%y)C>G%8u;O1F{s- zk6UUmYd`+p9kyxRW{@1DHQv#x6SbB?Bcvd63z>z8QK`f+KrY#hmTEg1s(rSn=b#-x zTT)(K!+U9?k~V+#414F5S6CNkD9Iy|=A9f5I0ECE0g1VPrUZ6*oZ~TV(dl;nMb}vS z^jSzusgkG*+9QIZzb9#3`w!dB?YnHpww-o>&GUnUFn;7F=LD*kBTVNYg;o{RPDh1K zK*$tO?xJg}<)(bl&(`rR`_wf7f|mjz!#N*1q@-MD8G$^<G}qg_MRV+o^B1t~DiNgq z5Y=L))SiqODz1L6NGSB!f4yE&2aZm{=Z>7Ur$&fe%#tv;%=}Uu{P^P^{mAb7!4GV3 z0GogKIZ1ve&YEfe`;(uvG2_PKh8-x#q!0L~`ueR326t*pyS1}dse<;?ve5;egii&* zfPm!>B1%J-dlYeEe1{=!%Bw4^Z9=o3A5~Sx!NLNj;Ob*RV_nZ;ipYWg=q~v&R`}<n znkVN4{Sd3Iwee_s_D-5=LprmIJZkuDU%SS}KDXZHoH7?il`lovDLX2|(4e?brs7^G zNC+SkJGlavAWwKogqZM@h`>m@^g`d4;(t>RP$%X)Qr&vQqYp2S4t*{mkk$tUjZJ^g zRr_`j2eAffcre!3Kj)^s2(T)d*fl8*h|Ms6DWDqda2T@*8$@$7$a!u3Weqk|(PGK^ zu~s>Gf?e>oYwX-NU4(mXGGy)AxqGL5<3GM(KfUK3H>=iof9rK`wVQ7GFnej*RCpMl z#CugdMt37mQFTL{;sb_IQg4ykr9{+S(yhdlNp{um|GwSxxzAzkn=-7Jz0ue#;Gwje zX|@}!Hv3gE*-oWk@H&#Vbxo(8aYoh}#*-LkQ0uPNYLyUbLIEyl7^#<1Xl`kiy3mVz zJ$qe9rnc&Ebk*CxQg+-ZM~~Hf)D0nj3F$(V|J8hp_8Up7T+7_Q2<@Cq?+zR|VA?bI z@WT(=jW^!t>vhqmUVia&>AnPk<AuNpWs)@D^;3{ER!B&b$q|_*O(~Qha1uelX*=p0 zE%IJ<hOtI+G@7*!M?_={txW|usGh@nvV3^vr1>BWna4#bg>Dpt1cge_M%2V?(R*gw zm;dSOwsz$fE6>(o#uc-gSPk=rY~zrUm@CDyRpgC!g98F920JZ=AR^g$$aeNYq$fCe z9R$@NiR0D*+q8U(jpO4b)B%GfCklkN%FurFBjN9d2}?|zfW+<tcKT(nvo22X+_SvT zx;i>-`?g)2Ptj|;cI<^oLcjs>FKvLnuSQ2gtwPH|mLrUSurxn8obaG4OdGaqGRKl8 zKqfBZs+$m;z$ihCmg4|HZlL>9oXb>=Gl=SpHMdpSWmjEbmt1kK)pGua$mj@ml6)#e z&k-Cw@|b^=GJ^Zj2}GRhUl~*sET5-M;oiHCgL-fN{NLMc-~JE0@g0H~m&sScE_>aT z_N6a;*&4?*SsKY|UT%tHmOey<s4d}=8CT0x5$#i4)Y%Ice{_XjWic;S^=KK_+8)es zWGZAfrj2on_pWTWAS+r-V_Z4unX&KVvGC;m8=9T(D}hWy2kqwM`EzW??3uQ1>w3)c zMC``xAe*=ku6xch7hcS{N{ksXwuDe0mGfe?_N4wt#MtD?lWoO{6^@_Qty>o~s8Pd4 zl9uj%V-R4(IKdsw?9i92s$PTem)o!mcu#wGdACb|!hzbZtY<C~C+8tL6&lMnH%Y_x z83BlX70gY9MjTyGhSL}A4-)fK4g)fXpsA8gojoaB{g;ikRK*1At!%M=_E?UYJ>D+8 z?sazN6-!`{s3VpGDYT<^-hHRt^3AV@{hU<j{PWMZ4}9PQuB~*2f@-`N<E_?4Kh=BW zDYV~T66;<-*%uj;iXW}c_)9LbCEIt}lRx+_RY5Dp$C_=`SQ+GSSw6%WN)_dJz2i4D zRAXD#?y=P?*4agGTnL!KBhuuf0S=QVUzUnLBB%`#?kR=%qwt3({rAXF<M5dh{CYw8 zYd$JOw4&UBUwiGf_VurS-39I1n<VEdO-)UOc^bj?*DI}*x&(m$ffLFkX+en8r>aiG zAeB0&1c8$k0ud5Z{iAy!Z6S%6Fo)v?X>4TrCbZ6Z=1ApWYe)qGhcR(1qwg_AP!K&J zb31Kduf_Y_pWpZa``VXov-K<Ya0)zTZ9|nHYzXdjKTL|;EaSZngkCi~&d=+}q_$ZT z`+%BoDggh1!@M$^jcxpVT&YeV&lXkzX^^BjD#N@jLmdVo462dxmk*Dz{;o#*={Fy- zAK$tfRz!{#v<C@FmtPrsaLP&7n5(D4e6JrBcH%>o7viM;YD3Tv2wN%$Dh?U0AXb<p z_%hN$te_D~A4<Xe;oyJ@X9hW^sS*<{4y2thy~Qqi{W*5}*>kNLCu1?W@Fq){&P3~n z5U7gNbHP5I=NAehy8~(;NfFgDiitJ?D{uY!x_a$X|L6bMf1yR{AL#Y|t%8Aj@AdDq zPygMgF$JkdGMlkloHPIuhXa(BYg4dS^uCl9O-?sX)^H?@j%<g&_l{8W8E8b5AtV@1 zA>po0*hHl5+k3hKY@GRIHWX#*_k~PCM(QX1Q*gL4R^sE@tak2POZ@T?_R{skdUCKQ zJ-UD0v$lWB^ERP%ETCsU7#W7|Wu^(?r?Kie9s7^QqQ=m)Y15oIlLl$mu3Zq4LoUTW z_E)9YR~7<!Ci<vC3apWj=;D^w002M$Nkl<ZGdlRFAalzw&(Uh|R@*!|eZXCNix$at z4<M8|Y@OS;g?UPPY5tL9FlO1`#%PhLazFB*8k{k7rx4DRw_CbuiZe((%=NZ;lkJ)t zF1Ll}&vbJ=-*?9Xwc*)y_KOGa=kQj{pebwitl6&dxcu_Vy`CCp`W=5z1EWT&HKF}l zYh$eMvRc+Yq!><ns;5r1nQy<&_H5f`T~9quN{xNY;@}SBaXgXYwmdnsALN3=hO&A) zxVPIjt=?q|&p5@JCQ7JRRIlhZfAtzfaXe^7l{42ArMg5xbIBQ-LIgJ?(j3-L>3>xa zd?GDw#Q2CAy5NEfoJrDqx$57$cds)^QGSY#=5iEQx|Setybw5{Oj5Kc6c6Cy`{Qjy zDP0KyuLcMdFZ4zD!4a}hm=kG8<$P}h3wIf&Wjd2bx`~Wzvq5T+f<@nly*jc7=N%D3 zuEVJ^t81>bkNol5?Z3YEu>JBE&!A00!U+<pfl*3<{5U?=^GoCSAen9A@WNIkpZk%p zXKZ{TYfGBzY-UxpA#1ZnG#_!kk@TJ#VmiX%?72D{h_zX=5+}FS5CQQzOJ>BuRHB6f z2~x>$sI4?VIA5S0Uf+Nk9qXyBVSdB-jp`hg6NPXul2sZ2xk1;q6rMoiK!w9s<9LOu z8I!P67EH8@U%$j=&6{W_w=iF!#^M_Jj^beoNiPX0<?7Jh;s8(cqCx#u+;_)H?3xbp zNzh+ihq~<(AOD2i!$#pjoLa<i08t0i`9~Z8`Nx0qCsyCkNM9KyIdToIx~VTiu7H~M z@sMA6RW&hrujL>ZXzb?LGvuRz!JLqWX4(YXx^5pMPvctvQNL*<=_iIJ&omJ&(pbUY z@<$+Z0*n5L)zsLO(@(dKW%I3j^$I}CTp+=|O&e?<nxFA(VlU(T8F>*?KZuYE6HU3i zaM1V_b3AL-EH~qnNx1OS)~#C$lIj=!y7cCifPm&s&=_e%jLdWOr2oP&@rP(FRXy|- zR665~)kX>V)YoARPPD?w{hijk{(1Y(&u+CRQ|m1@x5W~5GOQyVjJW1~3<1&*4r2y! zI)g6T(zR2qw|uPiS2S4)k9gA-O|!SW?@F7ocr5ZG`L-03&6>`-_RKTu?5W3|@G_e@ zEcSQtWcQADyd%FxQU%q65Ya^b@M3>FIe&Zz`=5{+?r50$Y8xKgSKZ7{XXUkU`10w$ z_kR1?)@|0`*<tlG9=AYzo?{1SKNdX)tb6Ey4PmCON%H)<owjc6Cc9wDsXPNS)_q^Y zKm(!7qbuj@FE4dmh331r#XkyZBjHte8fkAdx1$`3S`$V2RryJiq<kb?SE#P8wz&vM z>hJ>F-;Za@zCPQtXOHh~j|5vvcieDQ;!-F<pa=pdj7id>;FE@HG=N>wke^f~W~r!` zO1CEm1dhO2TI`GIbD@REQ<11=XNtsNaIeK*@1viXBHari3Bh|_A~Gx3E({{9u1(lG z-hZ*x)mPag53aQC4)!0VaRPt|h%`A8+-qxbuA<p;)f2Fp-^@8Oy*3Ry?wOc`j02HY zQm(wcA=t+fKWL8z*>s$$m}1GQN!EiINk1B*Y#E-OL{(s7BC<s17P$c(n0Oei5)Q8w zNgPCo*EBRF+=seTDYb?WU5g+?R1&jWZ4$18nC%-vGgFzf<_V2<;T31vd6zD-)~O(B zxC!ki$YLg<8i*m1!vvih<=G2hYPSQ<3-jWfl!}VYM~}L^*t;kjGLiSX6rTUSd+T@X zv1Jcizg(1qtXo>f+F$+UU)p<r_Xex3L5s&Xa^9dI=1<j;C%njFMbG%#kUUqu9X$PU zRDsm5&hVmj=cUGCj4`Rc(;g3LD=RqTYvPpg^xM-At<hKrIgKJ1)v^99X=GpLoDpzP zzTVG_0XDyn#lb@3>^Zi7^(xF5<&K&6X!!cpK5NN+9UP$9C~DWg(P!>ZgsT(GF9KE( zdy^(ja-vVk^t=s;{Nlxn3vn;<dFj>541q90^tZ6mcnMlB3qgI)!x2%$gzs3sd_I;l z?y}6`!9BZd)px&R58?n|hxJ+6dE;1z5D;k&W41g@pQmu9lVT6(fQ_*p_7c`qPqo3y z@z$59!%0I8CZAL6-8Wrp<EO)nGfc%WXkC=YyA><f*!TbQhqh~X2O7vad*{2}<xG<H z)D(~Pi2l(SJ5~s753PvaD^6>n7CvdYWD+bvj2J-eyMkR}Z6CHO=G^2(r`ctH@NxUu z|NUD_q<XEAy_;f^syT8ZJ=}?v!EQ?-Sj%EPaA<$8ZP~ET7M}+L(g>NTIZB&Cee;m@ zMc3KSe5F*HG)b(-y7Tv;rur@mEPM?hO8phJC!{#Ozk-eOir^-gjU79dJyd7dBab}d zd)&2uP-SavR=VPP9A7D=R3!+EK;VQiNgB9E4&GzMja0RCSAxK+9RjTUT9m1#@Pj0s zN1{6+v<SWX`93WALS{Nt*6po}s5U1ZMHu=wFd&XRk^bRzNv2!X%?Z2qedpVPGiKU< z{pV8KzP{TAy0tl%!w>l`3pJ3!J6M0L0T;<tR##qOEihRP<O3>qOeM1ne2(FjsR8W~ zTBGVIHkcS|ePxX{6l-+zI-xTWxx&6Vkfl7f@#K<Os9ul}b)?;nog>VrYhIMAc^#0N z*r*UjnknL$q}rgxIYMQX{npT0Zc|SgYj3&!8k;u1Apnz=Dvg5(?cb3nDP`mu7-!g& zZyu^-6ICH!RH$0?aICB9t_(*}S|bUSv-VEP%xc-PW%jji-eP<9vf)|#VJ1wpzx~_4 zv$wwWt+)#2Tos%IsPnb&CJ(YO7SxRdd1%t!C3sYap-R^8$T}<S$q-(=-eQ~?-x?k? zMpAWc0MU>x2X+%Cw{Qd8#WCu=Ge8ifa8=rqB&g^+jbr_!oz$4hlVyGtJac3i<AB$3 zIB@7_9gkLEr_})9S_a6jXI9z7b!%<Llqn1t29YYmHy&QR@*xRjPT|`~axJ1v9`0U< zkPR7^{=SkB@M%gHiuo>tFkI;0FxK)tT(the4)9I`DwsXv)aBp-4j$fa%fE25ZF+K< zO`@*{%G1`xJ|rI^O3OjAIv_e*j)NT5-HN*LmM))ehgmO&7|$`ZO*0owvUh*<&DJ^v zQ)JR;d^%47v$B25cKh~MzhyuD$<Nr2SZlAp`WpMlM{aUwAjO2f?lq=<)wmipWHm>M z)+}$c{wNVwZFQ8Ey+X$lkS^BPV&hL=VvF8*ovpp?R=l3dq*>D;%^6Bvc<`&VT8?5! z0*7Rx6;F5jZSCsqw&eU7taW50fNKsbd#^~qW-8B@(0ti(=A&1EXIVqIX)E7o?u=jn z&&L0F6Fk3>xMST#Or$hK(cUCowJ+)1bI*0B4Kl}*CMimLtb9swB?$aF5IA8>(vg*n z77SgFWS)*pTY4@*;8hI)Aq#>KQ@~jM=zj`h8$={&qlj<0L@tMUDPU%y82$^VhmVA4 zK=L?y@Ut>RSn^&b5aqRHHuJQ0`|$X8*j+z(+@AWyI!kqNZU>Bnya~zpZV>m&Igosg zGl!CBgHjxFDC;>%`}*;c*I(9RgB4ROT{*)B%f}!s<;)_SLFC9|n6$!QLWk1ah#ARA zR4GcAAg^=MEGd<1#+bi)@(Sug7)GqAd96*oIo~C%`s1L1=W-Z^O7^Ezad2ZpYrUPm zWWFsvbB;}zT5Yjv^3)0?IFeU+h1LckTdYX9@jNM8Zh953AY`2fzu$X2@0_6uNsjs( z(v!$Bzn+v?{>rToZZBpWay9$+pZR;&B<RrJIde|2f4KQ(yX?}-Io}Ca3=~3_pm4*C z5`xERm_SpIoy5BkRU%4gPbgE+j1nAGt&=!H@C(7+_6jaESj3Zahu&vqP2*^N6)!lK z#;HnuBESGRF-hu6g$#!eCzS?@PB}Z%O+pO|<*B@LFhJ85o@RUI%(LwWc0u&9v7WU1 zckN(r(psCsc`-V~cNni^VYDjed;z*WMu>2c95+;PZcY?rZl^I3F-}o@>H3?2K;-$; z2ZR0;b)#-Yh=-^^lKZG(FloQ14$aQ>4_RL)-q0R>*dF-SEtcDj^BQT^nVdVc2MI5f za`_))ZBzC#10IfZ?p$@PrR(agJK4fK#?3X`Fc)4h*WQeYUDFiya?1RdvZY5+1v)X| z`|ho`+Bd)TO<z0DIOBA?@xvdsMVNmUuSb!_<JW?ouT|by$1|b5tS796(poF{3Qbky zOh+0V?aQm5HpQl2{YHD9!)$wYZDiWvIh4v)aAsLe4sB90VU6W@yJNpq$MXaB{F?E0 zDrSWB&0)RQIv+tdl)~Qt^!$xL#y_tgg%<+fF;NRi{gs}I(-aaP^Cr?Fxz$CqIFM4N zcGBz$jxxE^nMnma%ll{^A2ZWZWC;Sl0s<$LNh+3{Xi!T+P(nVxqQ^?FU)>NWUh{>R zM9CFGKs0)ckVPzSW+(LO+8VuyD1IRj?nO#FGGUXy(t!;^jItxST#C0$sm1*60vpp* zXAl2mmGvLSc{Y+lPKdP>2=E}gl(P_<yYQer9aq`a>_sZWzP=Zey6&2}FiBIfq30l1 zP^L1~Sw{&7`#{16qP0*D>ZJ2F#1uFgLLJne@W*#hQ9mk|f3H0!PT1g9FGqc1XpE|A z%B`Y0Ztas=Y|g1O?TiZ-T03os0N+3$zv%!eWhVN>VM&W6mIaP+ho!VMdO`luD(F7{ ziK^g$@f&Xa`;eWZXXP73dK#}ap9F$@<O#xp2dznRUA}j3huw0^Eq2RSzv`QUbq3Oz zXPs%E{p`(l&N*k}Zap|(2;Wn6F-ZBUh*t1;`be-+mGo2B1(IKJdOAr%)aa=C4&SKt z()xu?P+Oz+t1rut)+ca6GI2_q?OxXnVFz)l6cBXC(@D)3r{6{3^!D^w2YoPO=7c=) z6$*1gR*V-vIS@%qoNV#w(=Gitd%-e8nA{Cp1LLD})hg?JezT1m(}Dv=ISax}R6{CX zXO(fR5D{7;!dhEf3vR$8Ch1t;l;U1l2xuPb*i_9cX|-cWQMAv9X#a^g53Z(BP~vbw zeTaS+hjn;qfcfd)yWhGw5ctU-e9v|~yWAQO*5Dq-nev=x${tbnH^L*4C0b97XV%>e zzkUQwSsXUhajmT`x3eyrY47;pRaVi$_`_5<;bR|?N@Er?z8~N5U-r-c_W#%qI>fr% zWY=8vI=k|U%e5>X6{4|r)Qck`qLCW182KC659Sy!(cE%)@U2#sm=~ya=%L&u%%5wg zz4dqO{;&Lt#Zw1?ff@^=gm|nbw~NEWD{Ks2S93#SY}d1UZToY3?bNd;xhbEjqwG`< zF+G~gnn{{NUN@e7|CZ*Z;{3I0;mJs;wUJ2XVH8HSJ!BWXI_eswjjl=%?MoWR;nH#i zF6Sx|KFTwy*NaLNr#~vwQbY*?F9LxR$|UJ9uzEafX#i_5%XOnR#|kMalm_;T^jzuH zs}BN>JVp>#0aHaabu7X|NaC?kls`C<CB_j?c$41+<R6VnON>8zUZjE;tZS*XtKW5& zO`1B<ezA0!?cdYkX}XzP$+9G7bs5_|6tj(kSj$&V!X~{I%@KC>6_ePo%SL2ehl9P` zk%JsT=wmSuGG_wKc!@%gjwBIRO0$)v&hl7>)t$G?wK^n_3CA$@{BogN1>*xxW)-!# z)WtPzLsKQvNf7lJ3vArP8jGV1)90AOdl^nB%Y@Hs@0HLCLJ{CX#Bu%AS3>BLriy_X zSyw`SYO3BVK3a>!P-;DrOW7}d>EG=3+itV&?ryvb*4aGFx<3E8f3&mDKI<rL!VA}M z<c;pUi=*0)yozF8BiG`Fd8<RabW8VE!6eO^Kizh$d(slFZPa1B-~vg$84!~E%S3OW zcfj`V?X>tz;R*VRpT;{E`VB%BK?4z1R#R*B()u*F+AxQH>d0e_=soM7vyN43taaY0 zXs)zpPa{iTkA#siF%lQu>7BGmYuB!I?^<#L{z8mZ^iApdN<ly?kp_?$q(EqkM{?$f zF4el_!%G4lOqg?+UnLK+?}*<34APoA?y!vy|J<ta^f_J(GdX1t7Nubx26NRmkYG;^ zuCU<<coXOnnMG?KUAm&eVpWV#yn@U>bCzBIk*hGbBUK#D6O2Yqnkv51I&ts4_u7~K z{mXU$lfFvKaL-|_xZ?6lCEt3<L3u}`R%6&7#Mlu=#<c1HqvX;2(R<zVp$n=o2d-$r zG<C@mYkll|JGlID<{Rr;*&v!U(x6#NrFNjS#i36ev%>XR+q!z3&6v}MH&Jx6&S-g& z2qpx7FNm~S^TYZX_ChH>zn)UK=8!xEMjl)BndWl%I@B-Z`qKVJUhaPQ!ynqdef#{U z^UYN5uQFkLX(g7v`fY*031yNrfPL~Hwu$bAd~{z5B?z2M5C{k?AW4m0J?k1`@)2A- z2ss>ch!g1y36i}ip|cNSQbw?A^l5bUq>>=Y@j+dgopJdDTYTX=Y~Riv+k;f?;YTX$ z!R0^3t#{fEl{Z@7*m*WI>2&Km%!cF)-sy1mkVNYwuii0SX$Mb6LVzkaFi2h&gon&k zbRJVohb@7OGkDC?VW|~0$ZKJUaHNFuf^w_Ip+sFn!kStetg*S)CQNFxmT^rsw!MXo zz<58xb+=<la?xhvn06Ygt;~Oyd`68^v?%HkbUJchlqR}W>SF~A-Q3d4-$mfngQ|hH z$XiQ0q+#fR$XT^&wf*#`KeapWyu-bjDd{x!rd)jS#rFR9b7mAKGjikZ9j%vys1DIJ zitr}n9}4_0kxnEi@sZ8*+)lDTg+{C1BM;G?NLOix3a@B$HRmKPIDNJ~^3$gwW|8!3 zltZk_;fS<^VH}oQKTOiLtvfA!w%iuelLEW&1caIPJcw!Xj45ow>{+&F$}~H4U=NaU zoe2}SO58W^eefZhxcD?1d(N47y2I=)PpwAvQx3-pvTl$WkIZ@QyYD_{lH_8zx3_nc z3Er{3EycaO5b!=H%dmHierK+VP?w+vD`HnpXkCq=Mac9Vw!=GjS^wJStozxuwsZAr z+x7e=tHe=F({PeQhY{M4R~D~|9A9mHxkl?@59Z-I7$zJlu%f{|Ns~k(h<`EFDKst3 z<Em}ZyeamUcV329Mam+XmJ=}s>~gZ5J9pcy-@VmcQg7X|&1&$xc+S~N>?1eb$iA7g z8MlGf8JP%t{A&gc_lWnQP=8Q0Rae#1qx`QTwYcaSF3wy+^^Ko1-Oj%5UG`8X0<>Mv zSalW+5;#DtVMBZX4bw(6YMd37o?)9FUS*SJjI)Io&qKI|Fhc7j`H3ObdMT-y%G3;3 zX*y0q!j6$LiR8g8h5UnjY6mWL)?6N)SRedaLCzblzWQpr114C4t-J9&`e95PmA8H+ zM(NiAXDM+J1WqWEB-1*dAo<B6WE3$?r9oZPOQqYB0s;X!2~mMJ_(g~#+^Gp6Mt2GY zycHh(ZHR>m^e15;1xGpImcP+=Biaa+rnKabq%Z?vSB}<Z((ERiG<^&X7!Fz0S1Rpr z5+amMuG7yy(-xg}neE+-+uN=I8yrYmobzSUn1#3r8;lZEB>BNGDc3w@FGD(+=~v>J ztOD2EF*Yg3*e4W21lcmK)tXzIZNkLyHf_d4YiqCM@Y_71)I}=|^ISMPLgU^NRb2r@ z=08a%^9@uwA>$B{k38~86+E6W@_8YDeWuT){Zi0+w69~I{qToBvM+w=i?(UgMrYV6 zkRZ>SH_!eA_ue|VumMkL@>=B*Td!<!=AKpfqs;TKqH4ZC%A$`>_S+Y0;mA9UgE-@+ zeM+5;9Y4kn^b7)P`Wuc%+qZ(_1_)2IN?F`5cJAx8{T+vJl!2DWJ1z8`OrnO_kuSno z8qL-j)2+IFf^{$*s-5Y@oC?Nj``Xpk_QVq$^f|*S#=$<R&s81rdLf})F>acV_E6&> zasw`DwM_6{=-ZRM7hi4lS6_qxK`w6uS`+j0R?Aa`{=g~eJfp+gw%Wd5K4vTLy2Cm* ztjB~5#{|q*j#cCA;h^!*_rrMYOmpb<;arOiRE)R&x^^3Cz$}@wgXG+yEH~hcfVgn! zy2p&Iv9o8*v-e;BR;z`}QjJg^xduh1pL;pL_$z3SK6mry(VC#eWV~E-!Fl#qfAyDk z&bj9?&@|?>u8zzD9$r#V*`sse$s_egx8WM_f>@AzYNEArm2&|1v~y0gj?D*b<@fhk zqVEvA4)K^DR!QJS+v6NG8y`wo_vW;1TGnP$W{$U}sm-AYDnT&fpSs5PJn_9qId|Mp zc*o0p(bCqdR{HAY4q`?n$T;PcQ&_h**#i$e;2s2Jau@CSD$UiG8|uFu`JFH(sTctX z)Owa3sjejk>9=F>z1CWJ<kDY2Olqi*cpgOvK}W%(qlZyf<px46%CvB+tQ1CFLHc@z z2#7rY_~$(PnL^BTou4txexQl7$JpCGbO};Ivw_1Lkh!_bc5dHphq`pIr|Kr=NTu-u zVak+541o%)tgNz@vCTGq;y4=%V^rVBVY1aEW6zB$pgIJGh~)VS3OTt16{1yGRC7Fw zL{Z3#2$x1m_E?a5@?G@L-+Ml)kDj7j!+jyrZ;t)P;ZpQUh+J{1hv&j`I+L>JpMT!I z@r`e=+4{S__ejiP4d)-7ciwsS=YRHRcK-S2yNhzS`xh+v+RaBGd~`q3t0RRezBm*l zz?50&do}804MlYiZ5@dy-0{Mt|7v4CQvIuOQNjMWsWT?n0nRikgGtIEy&s0y)p=Zk zsPB7VO!oC8ZO`s~HhFwYAjq7_QHjDA`TQAp5&~4Vjl-6&7H1E=nA}kgW37_2aCR+U zVG}R9$l9AA^yE!3uT2W$K$Qz2BBqLQk<Lnr@RFG6Lx&DU$xGK)7y?K2586R#55sta zpr`y{4sIUCRKM%lXYJ{4e#3S=vCJxl`rILd`rjSBkWd<@B-$gLcQlL#&m<l_4|3eW zQ0+uaj?pG%53$nW1{^I)IVN^FF$-El+1EL1PCIV?uY(~YA4*50%X<oET|3BlxDAus zTmJp4;ux#~6VL_o=Guoo@P7BargZTHWoj;{!Y?5df2RAwT2hqPNE(T>LI`nrMoAw5 z4+)0q$JX2U#nWxYgX8?zg?OfnLztN}AO>mL5}4q{GTSZPpR|tE%We0DS=KaJ+Awg9 z7{`2Dl%<^dgf&&zgLR!q?>Ap#dGxEWN?zc{bF>B&RsSX5YR>BXsna<xO=ht>ckXlt zJ99W1;K=dwk_#z)_*)5q6UHPJBO*aQdj75Kg;JwWdI$tW6q=#?;^(MwLh1prhxeXF zf1(%1pqh`45@yPOQ^+8cAY>&8rc2J0#NUI=LGqPIHHF2*3=9nR!z}TVsJiM3n~U4z zxo3|LLdTHR(G4i#0Ay}aXrRi_J2#huV96sz5du!&@=9Ls{DT5@03(N4l^i;#@ov5m zD$BD{<`FtqhnJeHaz=%KWL1yAjONphN|S%cf9rYWqa^uMkYkO3!9iQOYK8slzy7P6 z*!A`HIYB(Ob*x=^)s?P6TCiY2o=6Vm2=QvoiX^D2MU;PWRduiU;<!Rn^O42xRHu_M zL~W0*g*HVIYE*RZFX=zvr*pBU&z@>eEq&JaA&od}0G?=(^eoL%@8N#iy>pM*l2e^2 z5~HFsZ1hrNLxh|1FT>6K3<#ypWe=f6SZ!FJ;<+nkHN4-mVVxb^yw%2W_+(7p2#cyz z4D*Pn5>upd)X&qWPcH}`^uEL-6+`TmyN~)JD#3@4WJlbH4ag>w2z#<NcwoPEtzKiR zzV}_u%6i&r(?eE|*HAGuX&7#u1(!oRKE&bIeZw5G9pn7C1ZN>}V0N;y1=gU-hSGQe zt*yd*uip~5sL!PF{8q#G<LH3|dnr#@I14Qd&LCjD-J_?ZLF7L$FlhJR|DgTDKYX5X z!P#kyo5_=>*atrFA$uDpZ86q5nTF<IPPFXEL{ww%r3AIx$8A0XttAB<p*M_kcX&eP zBTKf*;~(E@vXmhlaN!QXX`S9~Q_nclwsx}Sb?Yz)ewa{W#E9t~F2d0)CDZ$?Z|8G% zVEuYao;}a1#&Rr!f+imM(kz#6c^N!=X)3EIXb#ETPOG*D2SibVm*I8{#{lTOq;G%w z+t!7^ZzT>oq*>A!3Ie&8p^#D*zjY8eVN6m4X-%GJArw-Io^>sS5(G{r2si>OMh?*s z7Ve@U#jm300wQyK1JUQHB#Glq^nC#cVk-0__&fa(#Xxcpfn0N!OTzBrP3Dy&W~B9r zDr>CcFwNmzm@Z{3IWQ!J6T|>)O1bu2kPQTcdx_Gm=RHzeJ&wj{yi=K;PRO4GM1*s2 zbRUAOOVk{_cFCj6pY%#tl^|YAZ}m_63LL=`qiBBxaigpAU&_lPx#rm`eXF3q;hRDN zkB|O@^+g1?>PUJT<LUV$2I<j99<|SX?(>|p@epS*;eC&aPl3pJ_q*TCnI<2xY15|p zx}^NVw;+5u44?sV7{Gw|LtUaW3s<65mXj>u#_OxpQN8sx|4O&7t)PY#H8vVYZo)~& zR^a}9(zLNwi4%vu<e(EXkiMhvfXwOodIxRSj(wKwPqW{RJ#9=j?~8o??nRQ$)xn=_ zNbnmVj`nVP)>4>SLHerWEQiOj!)u<gp|j6HL&%PMugqx37vmk}ub;+4)0id`5q1FA z(HhGoCh3(OrW!H|#d9Qz5wj5!!@*q59z1CKAl`TU;z3(~?^4Tja$qa(;B8n2A@J!t zdF&iu451%kR}p8%aTeTA`8Z3Jje{kqvm_2{a?ItJm~J#ixb<W?gi%1-I1G~@21myj zBoHWRwD?hIe&`a+8RmVDKmNFV;q(89_rpCdNNH(qVePoV-uHVSVvUf8HNI!OYK&_A zIaaGe+m7ci5MfM;6$$GvkK`%b69Nz5j^HVk7`==V>XCn1mxH-*nT?$|)}}0&Z|fdi zXR&0;2AP8iF-kx!27Ztxwic)*`#Ws&Q;*?Ff1%B4I?eZysx2}z^s|sCpGRkqq)E~| z(zA#Bjm*G>qoS%tb1lr{e4@ff(Z{+TGqN~=-^&TuTm&F;*Doe%&6+j#E)MQ3F-S*& zsub~SK;VQiNtzhNK@%p5izZL;`_g?00w*^Fj$Y_T#T2ldVuf)uKSrexdOHRP^68jA zzIj-mDxEM`K4?CbvtL7^`ZSW)e)b;;X-k^uj0%K+<54kY1euc^8AKQ=c(!D%M@?au ziUw}y$WK%eud%+2v`=c5&+kJ0^fn+@PwY?OkLR!3k*4I|1_XR0Jlv#jRKDTE5Ebsj z8pD@FN=vW~(~N)lmw!PLe4i6I@<b)ms+(@Q$*#ZtdOyuQU#MTAwJAcpo?oHN;*>|+ z7y5T3exz9=cO!34&bt?ENuFU=t3r<}B@74{sIe_!&6sd@?&T0j2BHp*6%#L5XE~=U zhCAX+I>xy(-Rv1VXj5x3rz1fye-qxw;|^sBoZ~Hx*1F(S+y2XkEq$QFO*<=buUJpM zTc3QwCS7)^O_|t+)~SZE9>%=a%ZbmC;ikUzer7r-l|0;S-nxbSGS=JQ=lCib5BmPM zD)^+9xFQ5d_OKx2;|sC$N$BqYS9Q@y(3|iJf4u{VQ-6k3n&UpboG~I2$1yR?!LmIE zaqGUt4lG}8EAPD1dgzxLylvL=VMSQfV2UuUgPF<2>pAKGW~i*qvegst=GhF{Uq{{L z#SRDHTKrfWWilqsB??S$SAw(aa_&Yv5ce6CEw+L8N||N-*tlVX{qsNllRf?9lbEo@ zt**Al-o(De4}auFt8b{Kb^1qsjJ@ETCahhdbuaPnuUv16p<Hy&t>76<glQ=PwODn` z>TsqLZ<)v$Luik(XwPVKxgDgfJTsqa&@830eR#TCX&oz`=AiFsmcT=vq*pGS;3`e7 z?+f%jS1?JMF>1IVr7G|z1A`>P?Lu%s3LYdVs%GJR;pRnO7E)<F(802D;;?)7ZhP*z z=iI@H;uL;s=V}2$rJI)mffL3gX~32S?Mvyh(l@VK2sko0R_z=O9QC5G^!tteNTm~n z!rLe!Ad^vP^lBts*z8V}6A4aUfT-Av3$m}R!xa-rIl>jk4r%`?IvHJrLBL%BfeG1( zZcvD5`)IB@$|spx6wcqse;Sg9Z;I|Clvu#)o^MoVU1gl15XJd}KRLeDqcR!w`e=Ac zqB%N@e4x5V0vKf^+$;uZ>(;H9W_-sUd+ag)RGWX7;2QU%AN{CZdF7RUJi+KZkA8~a za`c;g%t$o~Nsf#<^0|=kB)WOgHsoJMV?iAn#+bN|VO)XN*z~#6Y{S02&U}ad(utT# z2f@Yu5otQRa5A!e>mHjj0|uu+o|C!ymw~Ec+;o$3kfy*SZJ9pXIyg7Q-$7(okzd!I zt=9G2Gwj8fXNk%R&b<khllMd4cc+05<D@a7e2H|;ks_u{ndF3JHXFCY-MxDC+Z`N6 z0R&nX=!Nj0spy>%Vk02=TmA%yD-93yi?1mjskte3G^EG^bA2OSZJA89v}YOS^w3V2 zqm@tDx}`s}J($?l;^uoC{U{4!32k6^aOaJg9n5t(&KQ#McI!(u+hA<64aS>rWP_fB zba?LO8<-c$`~TT{4=}lo>(2Ld_vDBiW)KFE0VIe-FbM>h#V9ILR<tb1(#p2h+Vxw% zZ)NSScD<79^?O>`{;X$dm90ckOrl6i41h>5AOi%Ea~KRT04C?@@P7Yuy9Ui+1OX7K zYv%U7w{FE#>6|*DG<~Q~#>w9efhbo|OOy{=^bkPVaFiu2@nMLb`UCa$z3+YB9>of# z`fOQgi7i~X&_4g~K5yeEj;Ai-?h}u4MYRfbi|QBPa$I-y$*eo}gvTph6d>!NTlP_~ zl+!w)@<yV<h+GdFVwE)$?7*RJD`A`!boWwabg^PRNMxt|s^WaROiz;?eP*#8nQ@Vg zx%vvML;@=jNcvM-X{`D<^3@@tG|AM9EWK9X7|L*LfzkJ9P7Z6%fHqZj)6UDx&#S7a z4>?X{(3weN#*A?bcLxp}a6;+IE3foCa)Ra`^ALE;5IAi_(pxTJK42aK=LiJeY?6QT zWk7&<gH*HvX~D@ZTG|;^aP1ftqLZY>s25IBduO}*M<Q@6+zNMW`BEm1zxczeexm%9 zR&d9jf=})}EQ_xfDw|$zl)=xh6E%1T0>~GBupQmCtLR8d_C17=e@{=3EBESv*!%9g z&(Ad(K76<>TC~W%_{A@}qP2`)C>_Pit?S^Tz1{av_O~1V?2H%sLR5O;$U@X~Uee_0 zHI{mo!;iCEOyBJ$n0GV%Ahy)n+-1AA*V{D<X2BU1!YOQ=p38Ub)GL^ugM~$_%1L!L z5{ra~)~&H*Z&y|k9WDcAj_X%0xA6<Ew&BBuLVHD`K{Pb+vpPs1evu-&Mv_{Jf>PKC zn1FX~16Xg<(evDJL$(7)vyECo?Vw+NvLK5d<QF-4dl2sG2|>J9gvdY?L7YB7b8=_< zhKD#rP`a<jI`$v1Lu=RA_NSk;y(?d|SVyZ3BYYX{QOvmRr#ti@qKnX`6;{>Qu(8wN z9F4X8^}W`VuCip|Nb5?W3rSmxvyS>EgqH{g<_d|`IT8;iMdEgFrIbGmCUTITr%cPJ zKga_<OY>1oegDjU_`@H1I9WcN$*}-`_Gf?Q#sgGi5$tp&cM+Fgbqf%P{NKr6jkm~& zcoXN0F~olb9Iv5chS?4d%xy2kVq<cG#d_LN`D?K1gt$r~lu~f%u;BOd3fsK+NvoJN z!73+?W&8jY(UH_kV?`rUgpzblMJnlRB<;Z|BV|8O1imTc$#jCPBms1&tez!uw|@P4 z&a<0O`{iyxp3GeHX`Sm3$P-EDdJE_4ciuoC5<hxnb%o?>fzS?{xF>RbARXcS7cC}% zfOuuhv*%59(53q6p6dd!Bp9fkM~)n^rAwE(6+4-U6~QDis`tI`efG&ue$r&1AuOn8 zJ6v+%aK=7^H5GEcR_&BZs~lErO_@%RGj!{u6pvUHrbfW8K<Gd?yRou$_&~e0H}%>O z3_hr-BgBh743g|fpb&21e&`%cm^sVp|FG1$c5eY61L3CqOSvE1y4hNH?Xuz1FTe~r zXC^tvAUY4p55&v@OUSdZb?;LA)YR6xNEJ#f=t#A{!A8Ov3+<Cwun66C)R;#RNaD4m z9as+T0TehIkwT#fsBi?<o16$GA=M&M9gTJZNz@C3jKX#ISQm$4HzGQ<cj+^>eeq&T zHy^g)Am=4;48?UwGVVK*7+@iMUm*zp^w~D~vUhRz(J*`Z`7PGeUuCJnN|84p>=Ge^ z2*b=>JXVGX7#t-rhGH0GDD1Mb%CwD{R%?4x8$kZWL82d0933t#qclRb`!EV2qX6Ih z<~M!*&>S;q(j@!LXFg-sU3Z<&Gs-I0X)e(<cz((a^G-ZRP|voH?^2|#YDlS#8e49C zjI%CI^e)7hMFB<|5<N+X)Pq(5r6-OXnp=q7_1Ly0PuQp#Gwh-fw^*#I0yrXq2#nH% zQTxYfhawE9xWOK6dQfjQy+}-dc#Vpx+vw|wx^m9A8aHm7!@04s(bjQ3R#@v!H0^x+ z^AiGjBI*2W_k69-Q3!}o(4rj{W8HODgha{Y^e$8TI`2h_u5V}Y4r!lBAj~CbLY;IE zu#iE9J$v@pgAYDvKmPHLeTPxRkj}dK=tn<lpZ`1}G7w9-b<^Ui_gud-sm^DASwN0K zT}2O-4lP2AZj9~Qdjxn3T>?R7x0@G7Y~3gcC~Di$ZmZvY*oKT6=SY<cYk|b6jf9Jd zCy|jj6m2_(vyFyMz0lhC?#8-VAG_gLx+CqDmL_Y$fWtU;m`gD6E`uXFxK;_esc6yw zwG-;@$iIppq<$>tFBKGU+$QFs+gh6OI~iylnVe-#^^WS!TmwQZAn8vWJ-GlCy+xON z1kr3f$<ZpFe7JdYXWwZ&;7*@_&6DovutT)do~IYv?xoLK>;7F<jHqxW#A^{)x!S59 zBDRNII!LRpe5lpTU1*oy`VqKCJ@&gtS6X`yme@f2<2p1}<5{d784n=+INV|mPQrQ{ z7U@dqAJs{_?)EFJduG4wC*KsCNpTLkR{7Mw;?nEHHMg|*p`}e2jgYH_c-97s484d0 z9X4w;|AhG?%um73Bc6^QZyf5vri0oe24Pgf0lLF$%B>h;srxAKk5{pIFo8{lURZOS z8D%XHN|?W3Kw$2~+7IsI9I6*=;$<_fV)`^m!g@oysB5-o$lSSfw9+z$0hdmBsqUUV zZ*S_}a=>FL3D(*S96J^c7kPDdcG}LJJAGrUrl#gt!2DAl0>=RXtpj<Nhd>?z=LiIR zAriKT3k$Lqk03rKe<A-8yVG|$eSa%1EckCF>^mJMluh@*JyID|#}1G!=^g#u-~FBa z{ont+6G#dtD@Zrqc%vgXB9KD(0K-6F1vq(t{Le{+fW&k}jg(e$xFsTYad!G$)GorQ zLE^+25`rb9xY(Kxb=dCh`-SJyxI*Zp2a!c&y<`wLAki6+)x^jVHfrW&Ry1TJIx2qb ztnY}IgRt*<@dazzvm0g=dM+9VY%B=VbNv)vH8LEfqkKaC^*muBh$Crhw6vVp=OhUl zp@9T+AOev?Q#q$aICDTO1i4%SDT3=j6rz!q2p8RH2buFuclBBF@KI}6`n)aw?sshM zy+5`7ecNml$ab|XdXQ!(n?cRYV@Dx&S`h6jt($Js?)acx@v$%1&ciW#@X1Zq*aq(- z36YcpVaEn|QH+B{(I*3QcVagU!Ies4&8-CPQdQCx-ZkIu`p7MoDTITGaSkR%ztlZs z4Nm#?vDva|(`G*^K;@NDfDe4&1NP}pf7<7hF#izPo!-4(gbnja_;xz(g1_paG2`qX zRS~*>)PxZ>acV8rPT}1amRScT(mRUK;VP=L_H-qt)6wH1vaAXYrE!m7z@c&dM%s#X zgmzGm5GPQ!1if!)3_9SHUx1@RDfh_vJ-lT7PUNQiG^a}^NwAia<iN&_8>6zENaFdp z=Pd;CoTT%%>GKso7a{OkqGIyX4qI>{kh(E_tp)t8y5kA^R?|G0;j};oghc6v_k#xy z+V6h%J3l)^gpx!J6;5*NH{5W8i^yDr?n;Oo;)Sveeh>cn`$>X;`XEShX+<$a(pZZ< zD<mtzoMIq4dh&O;53zK@I$L@<{J7CNxL1xU5&GqqaCU8uJ7-CeL_Bfu@x<A)Z0F)S zJKB5@gd9B+LKK6LAKtUW4!^X)MqD@pA__}g(yb7QlpPXLy86wQ2BdEsX5qa*;M;`( z0WTcS=c5zx<A}DCLs_5!2ytDa28miOB9H_j#fVh$BiKfWwL&EzuylZMrmx@9%uBLV z*Rbq)+xFB`*0}j)&OE|UH^fmPW4s4qrHAmn2!!>};8iu_Z2YV_HsiWmZS;&QIZLb0 zo>}@L+(L3oA!1B85!hlbihJU^YY<h^ODZhFj164DL}jlnxNVl*cF(oeUQGWhh&q$& zD#_}d{%C)3qIScT{MYY%+YJLqwCkpuZgMWP4l-5W$el03oZ_{oW95F6-)V8)R4R++ zNM7{L_#0C@!lqtWV_Vnm1V+Wc7ID`2P&i5xA$~Clp4!KmV{Pbuv7ten_QrbKw`7S8 zyI{IiPoGLy>2PZNsFg_)a@q5s1=RBLkqcuxdUmg<yF`yC{41TLQKLpVktB|u^pdt< zflzaO-sK_ib|8=^lHLx~@^SJII0GRNMD4T~%Y{W+i@At`ut>MHwb`LVhg=aoH|!Z$ zrQ<G=>MSBqC$4L8eD>LA?f(1kx9!`vyHammU7a5=c+EA}xE_+u)d+A3@KL7WS>JT! z-Kl|q;4I{|pt!)sjvrxlQ^(u(-rZydIt7v=l*`d^M^b5r{)9E`ZnkYN@3Yz03ON(1 zuCROq+2hr@86F2^`pT)3ZOoim*0g=2b#@%VoH063#E^03z0WO0JZqkfm^p*9aD+@p zgtpR%oKg{5Cj>9z8Vnse)Y@BH9r+5O&bPZDE}omXM~-Fd7EL)0is(RT2o33@=tDMK z1V;sdD<e@Zh?f{9-cz03)^+fR9o@UfTKDX-##PJh!15QZzpd5E8GDgfonerHwkRmJ zvLVB5*ytLI)lIMoh)hnJe=VYN<E(yHvn_dgy|p&>SV5mSe*8gP$rQMYaAJ%hjtM-q zYKrr-GMNr5DDSgNub6D_`RGE6SBv<9P|J1zKXeriB&u-`Zz<cjZi7Aj(qs0({STP> z!R@!-?v^lhWI%AC59Q7&gE`x$Yd%pkWLE};3PcRBl?i-}q4KICyI@9*ZJ0FN_H1c^ z8(Yb^EVs`1NSYCAs6Ft9()F0p@30a?=*nor{m(D4#Lyu&<Gpu6C{1=fz&Hj~;NfD1 zT{=mimvP!TJDvm^IgKb9#Gl{vXQ0e)8q&wFBql^8O`JH<cI?>UoTRN=xBB^aGOm$# zc?cXY1WqfFB#TnofzhO)4lKP1b@IH+Lm&@<w-14^2y0Q&CEX(}<l1EuC*?3^kvDSy z<GgwE-hL);F=jv(-eT}K4Hl3P1<ZX8@8TRi{`li=oMGk4l};#0A4z%xGS7SMwb#0} zqiNHoy+Th*X$29D!G#!{&*1O*_Y;8teN^}o(|$Fkh_AV3zU^GH6AvL}+J%mUx1={D z#2h<~cC?|@Hmu%Z(=HuvRikCVK}eVSgThC9)-u2#vAY=JP}6U^5mV7?tZDW0Al+~k zNV|k6^;o{zgGg7!_;FTRi*6Er5vM_^kRJKF?uNz@Uh2yts_P-Z4<2lYkUbB1p8Wuf zh~UvZ@CXDjE(cxYFYB2uPO0z^u}*3V$ecH1Ni5d2w%C!)+idTeb=J0Xrybp~4ZWj1 zh;X&Lx%P<n9p_9V^eBr;ZRFJHHWJhBBc?$3PMK=ulcri?*eJM)F<brIc3b|;7Tfkx zy(K#+1az46iIP||6jH99BjQbxeNF@wpkq^+w0FJxGF$YXD<HB&Ac??M*&)setG7%F z4pL{@4y@f~n|G|Xtt+-zX<@N*kiPuoFWUtdT#yYL^^Y+364_lYfi(DA2y;5_B9Jt; zR82LRL>}ufSaJC^Gwg7~3hQZ0TR((U7hI)+qR~K)aoCGo9vmf0w?QbOGuG8&+aCF~ zbsafimwos{Hgeuvi(|;4kg-|<F{`?#xMZzR8Kn`86kJn`Q|~{Xxp$b81_HrY8-m&d z6OklQYpr$CN7bA^*hTFewcX%v`S&~o1cB2^kxZUE*>_`PVM+wk+_`g|Sjr<M`OcY# z!0|(1Fp{qYLzgxmL?nq&*u8r<2;M<^`Q?{=!P56ry-+BR6LmtE!@QvM9DyE`u0$(- z@rz&Bx4!i)UlbKigyF1Nv;1J#_rCYNra4FcgUj@0?<ZRR^F99HKK6=twIj${Sw*Q$ zo-)xYR+odYw$esItGPrVX;<12-GudZrEJgkBeoZ@yNgFo;IlA22qYn6xahnaxCQKx zqqby2;3iGDV!pL)+i1NULMm=j5my1G!8aq)HE!WGR#Jo6U=Ey>DvBfXN;0S0#zFE^ zAo$Y|FIxQcQ`X+m?v~9eu%Z`SZk<A34d2eT`x}*CD6YiSL_jK><GR4h&)=b<Jc0-Z zB%HfEAedZ{3_YN9M;q1!cQ_|+-*eAd{l@j^40U5zL)Hi3^kvgcl12&+U&XkIHUf^( zbVS?6%)Hd%GD3qQO(s)lovmiem%!oq%?fMW-+@?InTuu8WwK>d*T5>B3Za6MM+zeZ zB}3wN!yT8~yYIOgeIy7Wkp2SihY_KzN~F<a5(nw%<^#6%nRV8&j{}5zV;DIYXP^4i zr<@~Ag6;wrUoT-U8GMgIp1$9l?mSQk_4UwzWkZT=>dc8Ye)V44ysm-vEu<X_AX3rm zDk`C35InuWGPw_{cM!7Zi1qfg*^WOv$++pW%Q;AQ$gG)`DB-Ln+EB38znr*LDMS~e zSAO}dXCGtPFdpy(egZ+NjrTco=D2|#CD+i<;CiTm<EM6s`fbEHK7lOrQBNZT)P{0l zoSmwooK_-93ycsKAu-zR7K?N+qIaq)o=-Oqf%6FhS~#S8qXSg6yC!k8R>X#eppWrJ z2+^4cqt}`oTd+7KvAXYk=R3B4|9&sF>L%{d$3OmYyZ-v?UCBBuj$uJP6YF<AmB|qn zFeV{O!mCQkimhhC7~9?15-omUyE4P9<<OBTCzJ{?1>S7Cb{w$jbH`f(5vs^)8Ay*K z?Vx_5jzsRbZc?#Lx#|kriw;HGhGsVd4wJz}?izP*x6X!oOZQ%c5i~@E(BE^UpYIVe zC8U{UlFUUEjGr*kzo#JDC9*o0NDAxM**2z*tIq)&SxuLdD4d8N2e&vzj{S--!XGX| z5?}&R2o*R-nDg%3z0dYzG-K~`&sxL!wQy-#tr`MGCZ<Ik3FbQQs7vBtr4=@2-j#OY zZMRzO74xiMG@@Tc#pH)h5$79qHKlC%)0=GZBP;F5zV?Vff^d?#wFK>+#-gEHNEByC z#iSXNnEEam7PlMknrAoPJ<p1&=vxp-&V@whO?^;3Cq@NR9sQim)M7gz!aDbJcyJHa z-71IJop;{loC*g(_DAimvg<lqoD;9vcJyLHSdKyDb@D}HZR@7}=!n4yN*5x4Scs@2 zL=xP$7-EtM%zzgFTXAJe(DUQODXU-hf|ZOIWwYVj7EYf492qxojDR}-A(Jd*eDgza z%EIa-gG}P(b#-;FhpP>EZJtTwPA<27&bIdQ3gmxY1%XpN*Pd1)NtKfcUR`qPwDOZX z)fM+l@;`Y9oF@>F4E^-!)9ukmA9XH_5Ik{}X3w5|R%}cN3DIt?oaTn`E_3Fp$FF|% zE4%mJdtJOv-^4L`|NGx>ANtUTd=n-hF^Zo%&*(kxPA3GI^V#Xw`6{w>R#Z~RnJuF@ zG<E|hRK%r_2%L~D?M6EX1M6fRtzEWz+d(^esNF_RtRlXU+Xx}|+K`?jyYvOa9C0<` zSwp5{4t(2Iw`f)X0$0kXq9lha@7`to7-EPQSAgyzScJdwhL=FuWCkAW5g&Cwoxu_( z05~Gb`+EjBlgcv}0n_`r>~v_aw*_q$M^sB(0>LN-fg&+3p7<^w96Bw@_7*$1Vx?_* z__tU_TVcITjc&%<i6gZX?Ipqsi7Y?wsIY3JjbC_^U4-Sh;WN-1EQdG}Wvf<BA_mr! zv}I3jwx=InZcT8I3g94#3d)FD!=`+S#8eKIEeU&2L^L+@tbBNpU3b@IcH`Z1tr!AH z#uyTq_LexH8*`v-V}1BRgmpHw*q-M%Sku<S7Dq3s1a8WWH{NW2@#lZx+<CS4V2<|L zfVX(x_95l1<L&0=+W}oU+@uK?jNu^ON{pLy0CKdCXw!bdGEoUkN5S#yiOz@09JFE- zwn|0ZGLCjW^`sS}4|LHdKWJraTqN)pk?i9;D{80iAg7!Kt4Qq6y-xTiz+NgF!YO63 zblbLVCR6QNBeYh?h>_aud>X4K4A}ELfzwVT3I0N0)WLIIz7yv{BmbO-z==UXTouV= zYmv~xu7mbu*g!;*Tv%XEESFOkI}k{k7kqJLzK{WmC2$8sAjyKA7DHL_lc>cfKJf{= z?Y7%o#4xvRA$}-nn0NB?O@PQdd-sDyeeRdIoJ`fDL|(zJH3Uk8VN0|Nq!nabe?nyS zA(1YyhFwQ&=f-_DvgTsTV0H_1-3cvO#Z#CF1q6{5632N+Q!c;U4liF}UG+Qt%olMu zO1O^hfJkcZw&H3KYee@VF~4X%ik>|=(P@5Gl87XV3O9DImpQk85z?L3v~$)02SBPx zBilxLjvhsfxHujjI=na5-)H@pVLtGOKiIlo|H>L(UTdX@+*Oi*+EmFXd_TlZJ5*Js ztQsqIvux7U3vB#?Ycaer#o|SvDR73uSymlK`)t`$n{CM>E363-xI|wGX%*A<a6aH* zBoWpW@-2O+f&@Z*Nr<!<$b7ZgP4Agw*WW#xwnm9xO@w%*>z;|QBR-^n6{QNS_i(rE zUA~#}?sX}_1ZBA3(u?g&|M5#U1@TR}Fb}D%!~EnQ&gdT+O6|tKI~qW(pzS9ycw&sd zado3?(zLPGxNkF?5AccjAkI)PT%`;rB^4Hqf$nX`h)O3!l&n#r-$e?&?aj97k>6O^ z^f7Ri#2v)g2Cz>Q!`)LJ5K0=q(O*;qwg1U-VH|26(RwHSK@myfCQ0N@V&*z8Da`d@ z?hp9~|L~r_=OG{noK_+!G{N8rCUo9>rwtIw-}4YSF$hR6Njqyg*F&OdB9dhBEq9?m zu^isH*xC`)*%$ZScb^kSt5>gfBt>;xuwa4x)nEOUi^J&5j4+qvmM%Z9<U-?gK1V2$ zw+9F_d;~{q6IjR+*C;}xvM3ziQxfZPZxCR(2CWTkwrl-<n>p_SD;Wh64KgPb-O+U= z2huI04&pM!3KLd?Sa-?9N!HP@2c$eQ1zv*nvu2dKdz#v;q6RVx%uef30%Tu*UJi+o z!6*@jX?*QC5~gINxi2f$=^i;hihnK>Nun(P4dg@wD`D4u2yaqW>mYU!UyCzF)97s- zS^qMoyqDO~XP&W^`dwB5=RszqBTgNnbpW!LxBkKs8&Y?HO~TEd(f|NJ07*naRKT#x zgm*2#H2Z}XFRwtnPP#_`Tg^(I?ajTmZ1H9nu{*l24T1(8B>F-kRs^aJ!VWU8eiWmz zQpoK|SQ2a27B5ZP^|xJai*BD~r9(j4rN;)hN!HlXSiMWYeNdMXk(6jp+inP?eQS4H zs+&F_!hKY=z4s#@vf1<JsEPwFw6pr~*)Xp}aL*QBV@~4<7q%2cIF1-yjS+`Ywr<%@ z>qF;DLy^;~96tStQtPy#mMk0#cdgY*Gn_Le(;9H=WHIvafxY(3FMnpSTjtUR9L6i< zKM~9PX<R53{~I9GvIU5WaYDbLEi~s#azaGX!w)~~?IL4EJ9qAMPVm{#PA3G2eB_e~ zfzwJPh0Zz{kvUr?oRiuT`NZ-NIE4_<n34#BlvkH8U+#pGba%ANCSu}DcPhUY*=7#$ zeBglxeDQk*#7o>HIf+<Ya>*t3mw)+}ekO*(51v;PZm^%i<=yFnfJ0wxfD*V+F^T9% z{K?TaN8&(aA!KBjL4T1y=sA>6sxxJc+nemruEREQ*jU#&ae^pY9VzU~oLNR(9r7p` zJ;Fv`da1Q;Sc`e-Ms^6rdx}|$#z9l7A1oU$h9kkBkU5o2h_m0b_~hu3qpTR~W?dP? z{dVp0oCf!y!F?=SoO9+Tn7|f*7=pl1vx%q`hX6`42BDPc?zD~_TW!nYC3fJ2=P`V+ z$r3$XRtDiBgj+<Gh?fqocHSy$C)zYPM-#7kmm6kCjKJb8oEw-tG#dmLq>Bieu9kj# zaq)V4>Nl&<LF%?dKhzJRU`mt|k06HWAwtNVvy-xdLI`U_!-^~7cI~_2Al)_BDu&a( z99Zl+Y;-4ak900l3c`+_hp1h~o_XMD+qrUwC0h~GL&UFg{1Ch7idlBqRkK}muUMzA zIuH~;nrGDJ;dyX>pc-eCQ_mLN$xTl@xDR(=Kz$04Lmgi?8iHb^?QUyv_{v&jq^}n@ z=telVqpY;Q$-4TQ5Ss+XibwoPQrWQfCCiM48#lSk;$zFQc`<)OT?$V8lYmB<3Xyg4 z%Xtmn$8*o!oX}>Vh$Kl)=<swMDl2_l>8K7KpJ#e|9S;o7*RWyyor?OOb|PtT<?<c& zR5Wuw%{&CyA%sZM!m(`GGMCSmSyY)x6>%|m9G+?L(%DBk3|4waPd)XNmpkknYS-|V zTW)dvqeY7rdC_wh!q=KpUd!)HtMmC#9!HpjsEHr~r3Kf*!l}3iS!7B;;2XFs2v4+I zueM7FIZhQ?<L)E28<D$-myC&Yh4|)r4oXrOc@`BDf=9wOb^bit`}FUvyA_=n&oga( zSX=Acy~i?_&a`w1ri<Y^Nk1yW+9HI~)spZjD=lFh4YL-^SMS-o*9rH~55pKbQ~H)_ zkn4^I2YstyMev9il}K9#Q~O=@2W<N@i*4WHr>tq?ONR0o0$LEG5Ub+zN$*HVcE5;W z%y&<};%ckC`dv0*-h3-{!wjG#;_fJ6RY1r&#7sw1zrDa2NKZey%nm~!#Zs~=C{ZvG zT_R}%m(lTWzTpQaqpUn_iy)A$yZdsh9?jvy5Kf$q8g(~yD&j}yBEdc6?~w-{w#V;% z*pkgyY2aH?MWIc8*9@z@WSaFCsX!_cb)iE<eN_E4@)weRrnJ2mbnuTClS(m00y9it zR=WsZ4ro4Wu!%^TI(@Y5-+BmZ?eY|=NNDHg>b#*!>nR*<h5bh`r{B%j6ry)rd?}$X z9IfAP=`rI;7DMhD)B}#Otk(!+?yJX~R{?k+ba)8gU;QP7P&UWDYU6M0*s*@ZjJQa; zg5*SqksChv<?kmC0&25kE%MswhIS2KUn@K#%s-188Jv7xm44RanE$b-5by2WPb-lW zCYRjK8YY@tzqeDde4IQ4@(_3>1Y~Ak7Vd&x(uNHiOx&0mGiJOZU>KLL@Z{x0$E4Cd z-ZV5Hh?o;`^vENRI2TOk9?2CJ7TV02Gws74{;=JA^UVW0hyIbD*UImB^ABm|?<Wp{ zT-fVbxTWwRU;6aIgY;A&XZ(YUS@|1i9R9+A1`sTi^M&blcJ$efjr;Aw-IJ_l`bbL` zNW3oF&qO4NwM5z(A>|NB!=_(=N$}~`v3n~U1>KGy7K8Z7I@hSHud=f0a_~Vo6rK@r zDU|C(i5n%1oMKKG&q0+tci9050=ck*9o0z$fl$wP&<S>ODsJ>MfCOj1WPSDZn2(p+ z;|N5+ER<V~qF}nhckW5JL<Q2v@>GN{^BFO#OjnQfH6FEk3^Qzba<LtG`6cUa++$Tx zH^piTlIbUGH)9$8k7X*WY#hYu#B0zynsb$vkFP@<uGHIDc(~)@Di4Hk0$ru1hE9w$ zY_z41ue7EE=)t7nPC!MeB&vE64uy*DIni#M@Pn8aWi3nD!rSI?4$^$i(-MJ1TX7I- zwn|<(iO#ttJl>x9!?X5{uYb*&8V{-?TG7x1rsJnt&1I7<Rg6d=c}N2%G6_Q6$t%n; zdJeb?Nu8Na70<S<?;k`E!&4tbDp4P`7ov!j!%A&D<7vpK5<7YTo?cSqkA{;rDj-WU zW!8zvofTpG4!yHPx)(h^br=y#5U7}Rj|1G42x#IcU*CA((Z@I9m~l+*%ZYIIAUv!2 z{UuOwysF5@<J1;%vgj&3ToFj^?d@*$w6n9*Wc@CLQ8=}sT&|yc<bNUv2t2w3)@)lu z5Q{!X9|t}S^r{fXqlEaLP!!MmTQ-So6F8@NAUvMZG4wu3INunfGiXaB^d%pE_-Rbi z)gmjKB%qBGg^YTX_o{48$A3GmL{cbjZYRxm)Bu(IJr9AC3jvwgmr;X@FTU8%Ns=<_ ziWMuI10w<|j6<JzvI~t$F!=pMOBIkxr4yb5f)U2Q@{}mxZ-4t+H_RYnPI^?KEK<Pz z0G6-rxZ@7H;)*L?VTw7FFQgUT^Y=3i0<3EEGcAf*Bz>vV1FM}DJ-v(n;7F4eMq#vm z7qZJ&&T)|l&(5s}Y{#ZOR#P_uWSONAL@z};iqE5`qysF|aFgOFbYF1QHP*CtrS%`& z?Pn%|p4*mHFWTh2ypJDau@WtdAaEe)Dh|mILW^#+*w#odiE{7ThnZyM!*lMP7^lHe zP?Z(uNU84GOMZ@c=)uGABe-)7L=vEcR0t#WhyyV^a<U(!c7TW?2n1uMzsFKt&DOYb zg>Cr#@2z?5dQ4{Tw<4_B4Fyz?L!Q32G~mlXXq4Hg3ofw<*Dtbh3+CIfx@m~jRYAO< zJ4jj7mT@8Jf^@bxO$R&dna9@JbC0jJ_JciEn1P6eZ=u#un~3Y7Hj3g4c|!iLpdSuU z1`g8Yw(!n*Rz0>9?x1MgeotFTCzENA`Uw4zx$mu8x7k;|@?V)3*SQW-L3P~5&Khsy zueiVps-wQ3bGIU->lkcu=a>Qb5b8{JDt&}Ns+7^2pzf_Dww;C?x<nH%sI~D^M{~IB zE)Z0ROmW@>K_3)|(<Me&rX+5~2u+qIJJBsW4E&?^L&i;AjQO2ZBZ|zDIwOm?n(Nhu zB6A(F<xS%=;py{|>r|*?;LiQ>s^>5c^+C^)Fc6XSJQ4`XQx;uy^hNFgz#6w_OS`?Q z!taEKcZzIAdd9sr(VG3pca7g;Z;Ft;xcP*vyL(3c$-9&LML+(oHNe|lqdb~>6J$&` z$rb=V^;LPW5th+d&dyJ697O$zJfeffRe-nHiE_#j9#0#Qq|Paq+pz<p6bhHW=OK`X zz{!C?SPU*jCqsmV3?E2VTU;86A&5vC?84a8UDt^^l_8A#kXA@H<e@o0i<Y=W;b2%D zd>bvSh&y4N;aZft@44q5yZ-v?^NP3ukZ1GVmjd;#=o0ee%Y%M|ylXMkl|_xiLL2p` zxV5%)!cA(hi{`Xq4t$8?WD4!;u=*~`rIus&K-6mNoLN@P0i|t+_WMFxNQhoU?i$vt zwh=RDSb{?_m4`|r^TiVXlH$6HjL|o1YGok{Yi#UJOD9gqSm>YX$0}Fo*PiVu_z}o- zMG(`koP50K(H-x|C-QUD#R1FbY#Ae(Xi!QT>xzrF5Dpn-h*MvwhNVGtm1w4;%Q`o2 zwl$AGVn<fIV9h(XSt(;zMxtf(BI5GUjsU(381|P{+LY^Vv<vTkuZ_C!0!s`X0u=@N zfzgG?w7UvUcxA1!f%x>cWo*@wt+w=ctF5gOD`}Zh<}AXKzwjY7ja~{0bm%E9&LOes zSdW#W7<2t?bM4w&=h_f-V!T5*)kQlJ&XIi*NWwuZ0J&;!>#(o<%~$OCrO&|`p{~Rq zI(4{Byy{{r!xXl3mS}$deGhv8rViw@@dp@3&H?C;dXn?IV2K+!b|^&BDBG}VFa4V~ zl{WzdfBgV?BwouQfJa+*s@-B;GU9;MJH}fK6Y2`*BCoDfhz&f(a36p8@<-ex?F_uV zyAd|p{Z}3|uFB~7M320=m+o)m!uZn|l!ZGT1tF(*ag?N&q@yr$38QynyuMMH&**QV zuVmZewaOZT<hD@o^Sk28@gj03YFM>58yd8=dIQbl<5Xi>A=D=%LaV!U5@UpeY0X8y z!$g0wy$vzYPAifD7DC3WnfEK0eKdin`=}4eDFIK>-`>{GX(N(CY1Kh>1sC4c*>gK` z_@2M#A&`f_@k1aWZ6imHv_*>+`FTk%z4VfsMwOXVabx5{xZ}^^&0{ESA(ImKlM^8% zk-1!_@8TH!@|VA~Z-4vS1BU=Aj*L!x<Rc%kTW`J9MFeH;Tl0nD<mZZ9D4s3Pz7kSc z-L<j_frX&auAr|8!pc}kMIeFXYEMzW?y_qJs{~fe61I86ew)5&pN*)kc4d2{!Um8! znU0Q;W(ovNyN`vVMq(h~GHc(o-nu)RJ+ETQuxZI+n|S>qD`vwWhyrPe)xu6Ge7%*0 zy$KWR@L_SMKkr2^Nyu1k-#(RNNOh0U0zE~~0-wqmeTd*A#6$1yuWtjf0Qf)$zw|xV z*R^@5jgX3L1YqmjD1x~`28l)yC)1DK4@6Q5k)?V}dN2Fg&#Zg<W=nLn*)VbN_)CGL z^g-+-!FCj@53#t?(X}@7mUr8<J8!ok?Ckr2u+r%vN10O>VnkHLys{<J&M*cPcCN3t z)z56jiXq}$aF86aCKl)tbPsKUNokMI_$OyLg@h~Vw`*^nZwv2$KpKVRI}9%<`4njq zm<;qz>+vXBKt$l;r=PaR;8^RMEZGg6G|Dbmc$rm>8(}d_@u^(tUgf2@ihUNl*D1Wb zy**Sr{X^jt!X>JkI?l#S*ll|^9pwPoQm&|<Xe=^=)823i3#+ZYpw=o7N$hOjMw`=5 zFc+St?ZsIVEsVu}-gOEYe@Y_@d(dC<P5WWOB9bDf(nRIZyNE5lzL^Vnq{g3~tE#GO z(xgdln5etE+leGuxYJq@#%KupW@(@I-vj)^9f0IKMx7_uhmWuLPIxtAG<x)_H-+Ku zlo5k0^6;CiR7RU63|omgLm;Kv`|QA`?Y8E*=dg0wXr0|h8P_uR&&Jo3sW$J1n{3=v ztYUI5o{aUp#cmVj`v$+KjYv}G%-wxc8P&1nA3E?Glso?^4}m-c-Ub9jY|O$GvWN{4 zBL@x~uoqu^kwX%1v@v5i{{n<V<M3n?9f6Qhx?wTXv;1YTPK4T~O`Du3()mp*SFW`B z`g-RS&6_vR&vUx+$}7F>GC&d1$j=pTqZ6D#QJC(t3#`y52qbik3XqM87FewZtd4L9 zVhIpoJR?0NRe*1-f<l=sRb)pRI&AH-?KY9~U1}%OKcWPpni9@;81ak26^dbe;ev(N zbGYd;Yk7H<pOsWhnD*T}tN}u)dQzPmk8rDc5*6Z`6A>)NA}KCJuTT9>eNcLRGJK+O z75bw5!*f)CllvR0MzLP${KFt$XU!Z77KlulOP3QoMF7RQ3t<7hb=WDK$QU86X$}g_ zboW}{_8oR$%T_zMX@ebD{=6ODvBgFJ&mss|)wdgrxsy~d{A|N&CRi=HU&G)U4ZY|> z8*|CURx%n<MnvndyB!sXqDJlM0A|ji0#Ku!NBV8+x&w&Vy=3)Uo6$jnwF6?!CNg2P zs~jQIh2kKQQWEjLcrgfgai3kjV1~Wxwpms^1_Fs}WR5(^93$eJQu3#B;=~t(-$7b0 zzOc-`^{sC~XeX_>xYXW#&mA`M>Iv46YC!A~h|vFHN{ATVuB37{JC#24AFoHYIvR)3 zqoBkS?=gtNx@lu<#;iI!w7=Q<nsubCETO7*IF;jY?8W$Zdu)V_8a2#DPO7!0y(_FQ z-i=5sB6TvYPJ8Jrs$^G}6#)AJwKIruVUaj{w5i4tZ5YW|svzDvUWQ}cSEb|ITX1S8 zUD|-tu@~B0(>RrdJFP9^0E>VM;na6e<#>GyMLx5Gs7VHuaG)jp!=M2Am>VG{u=g$R zH3VTy`@F2cnlshDw0#Pb{7%U7u8o;A2ZuLr-pwY~3$}ah8r!>bqcx?vY=3{7?eA*A z!eY`Uj~HcbY*^j+N1w3T*|TWRK?Od6*V9HMsm!5chP(WHBFcAKfg<nn5IE@&(D)LO z@&5O}-$m`d``z!lK?E%tpZe6Nd_mE83>z3Hi&zS2>K?|s7A%?b);UKy=ua}^M~@zL z5hmq(=bd-jXFvN{n>caefTbb<B+L;K7gSm&tBfZd*!cwCG6b|h3SD=xE^R$)!St0@ z2rftyIK5CaaX7S`IwHl|D$%KecnSIrX?uC~ZmXL<&PI+IZpD?PCptjLzpuf>BAO6C znU@}lUf#tw-ek-6@3su*h860Z7tZk6@c5%vd&6}$9Hnn4A8>OBH{oo`S3BX{XIyl# zBkK$$C+yV+)h9zg4E>W>r_ANz0LPvM5M{~TZ>lg4T=H?a@e<uV1a%YK`3BM|WHw%? z9a#RTtM#Enf~B&CWy@{lqmNkz(cB*N7*j1r;jDBRM^m{7UN`XRA(2iDUW~nPhE2Qf zCaaoup;gz6v8r)c9b|4v`#D62%8B$MyxIn^k*CV1GC+(WiB-R=(Vl(mCEL2X!J6xP zIImRjCk|mG?&t_Nk)kGnTcvUq_FF-D$`&DBclFIPZN&IWkaPMC-N<!h=m3f#i*zZB zPsq%?+U$Pjo`3$Qf41dV`xL?SU;o>Gv8(UC!B+Kbvc{LFW1<%W5EN7#E5&ih30mif z69wX}&n??^yzRYFG+xqHF|@=knLo|8W94q!DlFDvfkW-4K_zZe3~o^hE?+nB+k?pJ z<SVbWE9XqLLz^CVA}PZht<46(u9d#iRKL^uYpO8MKGbuDc4GXh3n)>w>gzf0D6jX? z{lhrai=K6j8#m78&!6u)xYBXmx^=5>$jzNQcOZ@)-ia~m8J>kdf_$zU7y;pf-v@ki zgC2YK&k7h_n(Ko|oO7*dd!2u%!^E{Q6NB*4(C*mRU>hI&t?hW`1#8>4*OI;M=sa@7 z02UPwvN6&&w!~W7J1yRP$X;H)%%;woV>PoeL`C0KO1^M}K7On;$MtmDh$MB&+>WVd zxp0pL&2iNwA2<(zJOthZ0wR7iwnTW`cH3?C9IWg0>(|>4e((e5=zQS|Uohz{$(_tG z81hw`Yu2o>haP&!E$c})O0wemuAM(klrr7=p$~n?KK<!WyO9aa34;+(r4#%VH$1;d z_4A+4U<e46qSt|VgMHKHLacnT%dU0eB+0rK9h2|0zc6ifBf-N!y^F28rOkG4ZnPuw z+pMMx#2lnrToUicA^=ETsiq));^-Ysy#6{{`TIwS*JRZssdJNB57yhRrAw`HQk@mE zJDH&@iYGeF^)kTdMhqWjrKM%o3(_SM`s#b3e-reijvJ--nogk6l1aJ!;-*(!a`JXK z>5fyqqq~TpETk2fdU-rB5+?!}OPQW-2qZX1J9gU(jMIjd%dKhGHY>nlSvd$Vw*Oo_ zO5$`az`hN$aiz6&cFpZ~*qC{j+h~p%h*u)^2!Rpf%qtn$@H}ZiiMNU1h{zm@D7i?| zNT=dfzw@B|{{H2*?ztV-+e|-5A>IY0<6JLqYj{*Ngbo|l21!cXhk~S)RGSk>i|&|( z4pO-rX%Od8A~$XfLitfiK_G#j1bbFO_<iGle%;otTL%LpWq<zXU-V6)%!pE3wP`bH zL$T3kTvU^KifB}+k3pEnv))C0!mGuj>Zd;e%7>YrA(|&l9cfc%jJ7>n8aO+O_VXY@ zLDi20O`VXGu%@1*Z9#YJmJeKSQ>t6-K;Je1UPLN=E~c4m?Y4)0^h2wA|K~9=&ao45 z%($~*A#_$_R3_Lpt_NK9QKVCp+rXFCeNZ|9uhd=Q<>K@Pe;F&1$ldJOvj^6U5dL)& z&3_nxz(DJ0C=9q)ym%WPYsP5iiF%f{Le!Fsc{Qp><BK*ixcX9kKHjZ|%^5`T+xH%@ z)xY?qZTa2fmT7H5)RW_)xw_F~>#3=*@)={TWJI-%>|}1=)@-ev#n!3G+B;~rOzOxd z=uR7v<O>&tmtMsE_uuc;_}~XW=txocc7k=wN6$kb4}n1t2xCi#o%E12=48A<T%2G1 z>Q~Oi`QjJ9XcBGH;t|}5E+mRC;z(m%mg=;lC$5oPAab<p_tB4j)DQfV1tN(`$mQl8 zo^{uiCypFMXX%gnS6IZNz9zIw$k#Ds34c*2EPS$BCv}D>j!?QNu80N6trx_K?Qngo z9XZfsHIqTo^;th~Nd}&Y<474hmc?Vo*m!o7ckSL~na);FJyg-rx!LgalQtPHQ}IxY znaC`f2njA1yHZj3tEwnxtTeeIxR)rq7>E8D`n0~CQs*E9F8+5cCnrj>uL6UHvVsZ_ z4mG`Vd9iheP!OEc-F=os1b5BDzqS3(aS-g5jTY}|$66h*0nkDil#U3bb{eB^$Z(r? z%k5Tk-3?Yd{X#23pDR`bvMa)b^n@%aNAZxN%+wqpHEJ|37>SYf{vC%PkXG1B&+W86 z&Mz%UauyH%j)T+YI;hs0p2iS?l!m>hbC9Yy9QFqEkFL7u5=87EkT}ao^i-Pp&2!d^ zKhbcst%#&e>o(X|v1GSl{mXEcl6DcIfM5LgUxfG_ihVW+L;*&QyV~7}I)CORf}(#u zTYpqL?*pL%IWPX`?V=t9jA?-4^0-aDxYpLM*kkqW9J(w8BNB0hR~?8(W{ZpFs<f9j zAF_F=c{Y9CRkmhxv$ga#8H`@?L;MZ+@5Gww)7=&Jfj|CptEd}qiQ-BSU*>T(BP0+R zInq@B@K~>exR)=K`wi}4{K?$6))iTHm5~*#bGvu%rYlA%X}sp$aYEpAK&G)i_)`|j zG$(yz0OsVUfDU{0B6=E|GSEKU`>hYL$odzT+1ke*vqP&_S*)Yk%IOd4kL}DuM=Odg zdBJEax@eT8D@v`nuZSZAMq2*?jQ=w)O9DW1&A|F_oYfl~{In5CDo7VHst-T>uq$Zm zT_Qh1jC5LZ-sK^Xhrp?UfCvjM4mw9d=L<<ENoNo>H8r`(ZOLqZ=}TX7Vnw<ZxeG}^ z0^h7;A)L5Gk_Q*(NQc;pI8r`Zq_mJJeeLv#bM&rvy~{UABn}wzRk*OADbGL@<@)75 zzgfBR-_JY<X!(m)O`+2eNuq>UR9$ABg)t82AW>Rq{cs21AFu#I&bWe->Y|ldTp|#7 zkhdfCP1eYj>8rDNnHEaYmb{!e0ltEhz7|jsP6b7F3Fg2XP~7ijA=Vj9G5Tc7&YjkS z?oE1Pomq7e{ZHsyK#(;aqP5C6CP}-}UW#mgey#rL0ZzqFgn>l)tDZRhip+HCMDNs7 z2m>^WXhjGN5fQxjJI|^!Bu~1h!_tTy?tONtt^CbH)=9nknhsk9--`(^1V-m5^#Px5 z(rb?w+sqr`94%a6W9D3r6}Vd9jJ}XKL%_;u6XN)@ijd_JI9}up0ilBhG)u;9=f*~R z3=Y!fReKQSi=l%A(!-xLhtlXLK-s7!Dl!QnGKax{G$MAD!wc-DI}x$FWhT$jIY@kt zbk~$K6_#jSnmR}3rIS{_cb|Rrzx`Kx_St7G$!@j!+ebh4F&j5wyu(GvoQmfLE4<u- zA@dY<j$F8BU(c~yG?#{PLz4mw@z5qstHFrFC_AwAh{bwo9UbNjY^5irHr9B|aJX|H z;*smt?y#DLLt!G7<Jau#ht>n}j0%!{^sztK)~Ydf+2{VmiYhUg;-Z*v90hNNnG?Bi z3^eZ4?qsA)-m(kpf%4QkGHTQ)tE;QCb#M)(|Ef(v9Zp_cT<m32_^@8R<xI}2fZoW_ z`15)*2ILing5bxWNb1N;d;}cd4596OxNBU|oC+sc`#h;l5JXwE8xrg8vQ#$)VV-}^ zRz3Q-wIYh&&n9X~e>Z2XrLBZH0HInt!m$H;%L}X+qbgRx)(hvMVb#SlBV?q7W2?bw zl5`-B%cFSF{C2FMQMr!y_p}j70+c$e#1*7ar;aKe1??{9iKOFg#(elZ1l|||8gF4C z2+tx?bdc;PKlw>NXitlX2&AV$8fDPo>Z`A|1q&AVC8G|C7hLXhSY-4~&$9US!V53B z@rAW(*ZS_A{FJux4B;g5Al;~&Zo0|pSi~e6k?XW$T)+bQdQN%e-PsNSA-`HWqoqt- zBp1gR=xV$pvQ<%CVHLHd*4Lh7NtIqn6jEJMh?PrN5VOCF!(}%duo?5}tOhgA(m@jP zCAvUP$gc~W;Soc;vl{M4$;eUcLhj*f%8K}2+TUwC{;<S`U2&xqmmv})T+Q(`5~0tj z+f`LpDLLPr9(+J$7-t^fRQ+V@6JaY+Ch~FuiC;N~jmpcjh$C@C0Ed?!oCTNxIO>}2 z?yy74UbJWL{iStp-D2H`8mtt~%`gxXNJJm^LX^`WA04FC3U_V6NB-C*-+H@MPMZQT zTH%PU#2y8k=qK7Cjxvi1<AkXiLIg0nEa|?OZC$(He)G#0Y}bY+OLr6ie>g~RcSH`m zr9*Af0Q-LYgn$VZ>ql3poP%C(yz6qi`ld^*YGkSCX7WWxiAuXzqzE=I49zDPkZse^ zCi@>>{i;3r)RWfP+e1om-<0{l2S4BhlJwftue_<%X}k~WhyF=?rEz@dI#JJLM}49? z<`z<(s;tJB?$ntnxN=CbjjJ1ORp=;nA7;!Z6V?v_n{j<3g%sQ*np$idA(Dp8y&PCV zgvewwZ4#qBG7vrm^tbBnlx_OW12%lx1e<u*?VLk39K<%tR;z>eQDy9CH@COw!kVOZ z*A?DnqJPq)NiMY{aqgi1I$^?ufj;sUvpA1~`Cy3piv~lEbF=zB!D=R_)x`Bx|IvVv z(|Gq`q|FK*bU`f3C<BAllHmM}D_*o0AAQ)`H*c_1bCV_d`fLb&hT(`)x^S)u-atp$ zO?s27N?o!*hFOfW(K4kO8$NQJjhb9XuZf83s5Hv>mE~26$Kzff138{l-bPpfun$1U z3~=bsGSeu(cVv-y8)eQ%$wT05g+Q3FG`7NSx9%k+C2rYH#EYyviK`?9R}nYbCI3B# zL~1AQvdb<TAexj$3%kyWqcJNhbR8WXP6SDOb~ERvh=U~Sd9AIjKE4%JyL!4`e);A0 z@sEGpuDRwK*Nu`1<xr;F@`W-hPWXPd!arZ`*M@+|BVS9kma&*cqz{Xl-nF=L>+9>W z;bVqc-N@<o;*J%T>`AawDD<6h`e)G<k)-e`7SU}l@3HmEYOH!#l~oJ}dlqu7Oj2+q za8gKjt4gxI1p+l}!bI!b^b$xr=e$4|lz|{`d+`OkcwfDh3?IpXndIc$jD%ZC)5={j zq!MI+^M6>sgmg`rGR6D3(tl^xuVaK|1T5;8;{b)g5g{k?2lJHNzayT&L9olP)}}ez zX3PB#*veo0)cOwYvl#kF&>xOwNJmRfJF`Mi+7W3SeZi%66$Vu%-1Kf2SB#aQb3%Ao z#S?Q+W7gC5oX8)-qX0u3B86#O!r^4n7jDGnHT&%TpDeX~TUspMTa57xVuDBuz9NXy zP)8|rl}N<Xg*?IlM8A!~FvE>^&9?cAE=Jt06xlq=Ne7TPkM|&6MdJwBRu!aAq&e*y zU;8_I;Gy4G8_#J7?;5yY|M36(gH53QqkgCeAYF>1a_Uu=T)0PX=fH24+za*c3WsV5 zj#(H85(JIIN}O`hcn)mdVcU)z!b`eFYHuJ1b?nK2C~K}hyuZZ`?P{`q5Lj^!d>*Gw z6X+jF|Er94F6I#8rT^!<Hmr86RbO#6rrRsLP1H4X^i7Ngj0mt$rZ;bbuy%y;7uF9+ zCg@Pv;IuYr(=JaW1&F-yJ#>+%1&+OWEPoB;NcNkL!zgq{bFSW*KYi1adj?CAntPHE zLx-0yx8)B%WNlkETN2K-4x)zt2=|&k$2{G~aO`4&>B<yhaWZB*JKL>Ylr*OOMQp{~ zzP!eM(neriarBtc+FoIbQSa17P4pL)=8fz5dS6c)k)#3%@li+Cz>?Fhu@EV_(9!)R z|C5J69s(x?0vdA~TVZ_ZF3zotI7r;}o8SDVJ@wR6o|gz5T{>)5#Lr{M2<y;UjaTi+ zg>)n~t9K!c3NM62VRG|OyxVWT-EO(%7Uy1Rfs(wqj5R1+;2LQ@(7Rli3&LXOp8211 z3<9*Zi`V&@7a?0hzq}8yz-f&D+bthbVpB(qx1F_Ht!-Ne>joSLg8A7i+_e;f4Rgh; z?P!;+TDsZBPZ?<!U(Rl^7F2!LmiU0!og!)dN!aMR$yQ%d22%ym4nmfJ?6qUTt$z6m zI8D<rRV=E3Rhz!4OT<9M5OI<su7$X+B9h)oN9l1w?Y(AtjGjap@vob^=oNed@&rqD z((Ms9E!~ObxE(uf<%18~j;EfmWaEAtqNSH=N`FX5Mv}Vr(Kd&BvHUk?qTTS`_u0tn zueafoCSaHWB9XAtI})dc6r+40ul)QXU?_9$84%^9e-bx=xrbu(cV+CQWxMR*pDqTO z?m_1X@j7A0q#<J)juUwEP$1&+k3Yh91-&5E<#zMkbM4COIp`IxhKum9ldRornG@G} zShT8_#hZ(gr69b%^^gCXv)Askrsg*4mbPJ|N88uF_I0~<;kDVYa6*WnbFfsesI7DF zJnJ=k`OCTVql!hH>R1hV_Z}u>l(ws>8)oCD4Tn>Ei20t4D*+hTIzH-sAOc8&Gm^Hw zw97i{IxR6;nts3(qDLsJhEWN9L!)PZ{T_SjpZ~>fsUBhF7hQt1W~q+D@p5SRN4=W} z>OXG*@L`<@cTb9hw7$tuQE-x6+P{B)c=h!rH_pI^{KG3DFfgg$t@gmF%lLTZN#b@I zI^rjKa|y54xa2M(DXw`3oyQcqVf&UoYs-G~pmo8yP91Hu5{Rjx^sxfwWV#0zQUS#6 zWj1Q%e6IFHh3!dp*{&WAkS!WPUOD&$Icf%y&`D7t&nlFBywm7;pt#Y?asHlGB5810 zbCIw7&hcRA<lplUI57zLWR@jfM1TZhM0Xv`dhNB>I@jpYM<2D{{qA>eHdREAzDrb2 z*REZ=1_}`fE_sBsl!u;mNm+L0%$c69&SBE&=Mvj1Dw3W@G|Pr~fglQT!}u5R6uu2) zoPRh6ArSQkEp~dM`+ywrBNh>eb{s2a(=MpB)&&>Y6T6qP6Ilc@?lM+{CkDYJ-maa+ z1dHlEOct+wcB_r4fm1ZD(%6WMl5@hyb09pC2tPucgwhHO1{`I7oQ0NEx|Ef6(~_sH z?&e!C(op8%gpjk23um*6D$ed987<}_lH}BP)vrU}b<b1&qq;=(5e(#1z7*qJNUZA| zp)fBlns#+F{p{c(-m?CoM{LKFPh02iU6w!}N!I;z0!|!wbP}!ygs7eRq&da@^7r0u zlWxD$MogVzh1w(`j1F;yq##S}+a42eQ5oFCHg{+dCt6enFB=$eZ%fjab3p8GfANep zALv2+suUti#46<l?iq+2ap)8wMY&^|rzl&0tj|W&aE{UY=Gpu}APFPma^i@_(UcNx zxJCp|T5|{A|Mg%0#lH8w|6>h}he$hSWz0)o``Xv+4i2|XfLW=%)Q3_a{zB#)7bIRZ zM+vsdh`WE_@ho<#jhrAHxnocM&Fh#G%85_4U&e~i1(|xu1bb;!J-SICs}QyYQcA*t zoeX&>)k2We9!$0$JlJf#Be6yZQLH3gRFbyMz`=u5_p_3Q&@T?Zyw3jcFW<HsF{Dup zSINbzi4ckBL0pl4)H<O|q1>;&hqY($+9KT}Nkd5NP7)B(iItVRynAa9(2T6V0jEbF zqnfR8YG40@aA6YGnAO;KeMq0f8J9hX^}@AoSn`a$@Zdw%j6s+bhHuK?9F@_=(mC?O zW7$~gVHc{0_{mtAwPmWTy?Bf@GB<2I^0GBER!5_wnufc?w85SinbY55Oz_f^6Co!3 z$%HzcSllXG7S|Xk|8YK?Rw8LILZk^!6*|#M9VZO(!SfI}=OLi6rtuYsqX?OZCJ=oS zqEJ>==3;eqb#-p_PGWRA)KwyPx{F|vQ`mqI=BBGOMFi=v+C_^Nxp>}ac5Ee1r%QQ< zv8{L^U!|#MaibI_7s*t3eGBmvHt)_I2>9YVu!w2zSV)ojm{4!}Cw)ys5&~0jlguue zHQu(pFxvLLeAM?3<5ETuat$)ZgCY>T043nGt$cQaO`bN|t{8O*+ySkYLV$(vvCf3F z>2DR2CR<N&30ws7CkY{Dg#<gib+dJE++>yGYA_VQA}o{uu9nJIRgNBx{wRAOl2n3s z&Up=@?1ZT}a+|&JNyJ+c&X^AFjKMuiO9!U~9bgPItini3*S4(|<K0DDh%UlV1Vjg8 zxLx8cAift}eXU)H&fsv)lqwyCeph)V#0o?U;Z<)Zf_PI&<b=$+BOMVO2~j9Gi8iWz zS{gfT$#2)#;zw6n_Yv|;m8mIc7T^vyh@(*;zLY*WC@FB9RIC@1?R_?W@^HK9eRFKi zf~jzj&~?GAG}suym@l~ZLHrefJVkQ{`GK72`QCefVgK^&@7SJw`=b6tnf~gp{-eG3 zuJ_oGDipn=%8*%<r`j|NN|l@|>l7~cJ@}v1cU8(O=C#nyyM{+_f`!Hm5aG@<Z8d4S zMDDg&{dO#qa)`5lC0IwIoZO{@L|^LfqtAiBX2fxFPA)-d51Go4Sft{}dkCFq--}Ca z{f~ZZv%c^-D;PGEHX&ybuin?hoycj2P`Ed^YrP0g{Zwm;2qdjdB9e5;%3W9w^J`0h z*6ZH|QFQ_DE?M{nC~Lly)256c_N@MZzLCW0yy?<Cn2v9=l|TH6t$FA{E5w|4DJJ%d z=ujH%1;kU*Xdqh`x^BHzYMpF!^~Q%-va;4%;-$8|d7tg*?6BT45l4_M%=@S;se3Zl zP!f%IQt>%j<%!tAnj%ivomL`ArB{azom!KcuJE4kyeHhg`2_M1a0qBDX>8>ZNBR)P zSQv*2qXk8mI6pG3AT#08yI79=ute`f%uJdz$-^jK7_$<g(-}t+ZxB%=aXRe`hP0KJ zI712_@(s<S_go_CwFssVHh({NAmHmReaQO*FIs;?Uyvx5TpG@XCD2ES_1na$H8$^x z3+>SM=TTN-t<X+2VLU#ormr0&Qpm#E+tO*zJigY3PpGyjb0;_f<h!EuHFvtRpcafB zjXC0p*0g^+>GeB@sgTvT7+t8HOP1KstFEwkg~$mw6Z*pl!ccT5;vjP=2#`P|sSL{B z%M#^q%6_voh$<hjm5>`{kWq$0!2{9PR9B}pabWWczx<UQ+4!<$*ugDKVR9GX6;fsq zRNB4mB%Ma?<7UmZ8}GTtM$DaOWy2tjI1@@nF47<)1#HvG!X1@Fj1Ju}2oqt?e*RGw zsZGlO0+<CFTOi%E5f<#an)__^l5O_vBde|FF!`oS{GeKKZbTNRNH0+&tA$DqB9>&; z-l;^Vjh#HiZhrq9o4a5-XClFchCSgh1_(Z%5V){_@=27^dqck?Y>U~o{)hkff7{k= zJNc%zN!fq+5C7gi`zN2aVHMSWFlvHxfRrUzh;y`bm!mk5)2pZ^A@1%I5q{aPXZ0<& z+eC0v4OQ1{wRrSe2Vj73%H;awsiSS%%DvWg1VV@dgp-U1i9gA3Lk3E>xU9%J`w?pd zW`%SFaR~+c@~Ud<Dx%#p=$(^AF<hmN-hL}hb=kUy?&Ex|saAW-&6XgX%>6skOXIM8 z=HbQVd?Odep3eaU%pHeX&ty4S=km$2o%E8l=_d=XdH4Dd@a~`UIT{1eZ+1ZV{GoX; z#^7}_MFtrZk@+Bv#k#}KEV1YA|Ft!&T49wKY(TIXZV&S=$!Kq@m-!;)a}b*|=?d#j zjJDq5QPx#h#pYEx=WQYKf3(56!8<hdXmU^+i!<)@68cEeS4_qs#^5+>mX62KnWNvT z>z?R{edAu21DsR&7&^D|2+z44{8Z+hPdg8R^92I0H>O_CU;08KcESQ9OL)>Zl9LF7 zh#I*NUt)A3io&~p%zl@j#`a(WNkp6c2H!*4N+Wy=>E-X|5CpWCvI|Hr@-<h>uaI`N ze+nd7PP>6g5UW1Uuqosa*h?;-Zo4-fwwGSm%7VeU7#WF7L5vemh_ZGj<63xA1-5tl zVSDbWjaD|i!p5Le!TQPiEv|{MFZyF4aZ5|=Vk|i>Tf5vc?JaOfB(lL-NEBwn^MA05 zkAB9gM~?&{)N-kXH)hpvRlH9VR^mHh-BNjTpY{HlPE`($d<MNn9=Y549#+tK6DM&O zVBn&4aFV(<Z?P9Sn{3zfOD%P{(aMCRkggC{A)-2cs2f724RBPCpJI34^G7xeqOh7X zY(y9eu4;fxQkxs%+(bG{LRPes>#&r#i|Rln#0Ah{ua0y(VFE$})91jBMqB*IGV5rB z;{yjN&Q34Go;F5jiBe=l&{1wDLdAg+;uG(-3DZV!IO!F3*)>zGq*4SD1yE*Onir%~ zrgqS7vX@UV<9+p-)%Ml@{#DFTV~~Tq)FvOi=R@}IzVLY)3r9g*3ORK>q4>@T5i*}` z3Drdun-h82zM}B%t%q~KsV!9>-NUcH463AH=l%ja?4JuRnQSjl*kxOeNX(S+z*u$j z`2<VQj?zg>Ll~=F#3d9QMe<~dN^Q}5?zZHQ9!KY|71%>i!I>?D^K`WJh&}et|70H< zS8HV)NGwjW?`ja!^%7~LsI<DNAOmk+G<>}cHH+}cKdRh{r9M-|#+}Yf3Ql8I+@y1g zNK(6b<wGrB<E}7rZxAj7i2@G#4Rey(fPf*H0-wWaXAXqTaMn?}tH<^&<4i2hUhGA* z&YF)}1=bKbatpCu#fn)k<CpCWH_XtJF2~TvNK2NEwVuL})?F~fItxmzIn!plS`OI3 z&PL{c^xw3>>V!A*1@DYtF8T<5GTxx^t9}=;M5EHZ6|fAd<ttuK8<7+il3b+8EBA`x z<zMm;$V1>{Lg4kr*qix__>o};U2oS7&O`6PPxF9WxCj4SKM#=qIV&NM+n%8U^3xJ0 zF%99NtZyux;&_5|afVSQ)5}^X<ecwZS^{Onp=R<>n|aMR+qrGKbsYu+2g#RNaP4MC zi>7jbn}JA1vO8ugmu$7sHREka^-wDvLRzGuMHJN9IYIHFVw=KwNiW^^b4zu!LXcq! z9L%baF#VkvaCq)ntKb}+LN*MNAOn(}FRP41wX}13sNoQP(Sl5pq|I~GomG(6c3Qc! z$ftHZv(+Dn=0t|RQx*!!6`dm^1W`$6aTHa<KZ~QHI59Y3=^hNJ)bF#k4?bwypMKgp zcrJuEsw5pL&1+X*qJ?Qpc{d>r)kXbp{@ACimIHLFr%knlxMmouP!S!ym2$olE)jHf z&XR9j03#763Bi*JsM=m7e;^+$(<Na~ZC%@7_x|wrSUqcp!-Z)K#bdmSFp*S@w;COw zKyv{17@~I;>$0IEi)_KIm(bSJI8O&ok&HU<Cn7rJ6Z%y`+tPvy*N*MG?92c8zi=+w z3O6RB#(4Lwx7b(y<|}X$>YPwko^lb~m97XjP%HrJuoo;9z}tZ0P%ixiB1)gmW*0$A zb&Z~0Q5WxESs#5CQ1zo{zST|{V#CLyOSX}A=n}N_7eP{eBPPp}sbYevPf9G3h>XQ9 z`rFla-(%Z1wcC;3KVg-K(Z=Yvm2i}*NVlb7uRZ*=zqR-O<3C#Axbfr#Ld?dSG~bl9 zW`G!kw>Kbf8Ux2%l)slVJ2*UB!l?L_5J_W@a!`K}?x~|@L?m5w(MA5QbV6S`mgX7s z<ZX~GPpEgUpFV|m{~o;@^U4AuR7oE+dE_{6MfG=JdkhvKGX)fkb>SqJtjnKyMCT|X zkUFh{vyPtl*)ObV`wla#(N!|v6li>tlyoJ#najFp$7HPBI@56cV<RnAHr_h9_Z1Gc z9;5*J8RHu7ZCwX#=fQ1+LpPfKQjRWY)hHcDqB2Gs9V)Lj%KXwUm^vwb^iF;8XTQD8 zpVLMpsS%_sE)&FZ>bSb(jx~_K=6~`K$U`6xfjk7xK?n#*6HX(}2CG1}hFaQmvB(LL zW?c|&1nSHh0SAI5W6pw0tQT9bPu{=Mnj3rY#}lRB1PGUO9WpSXU`+4;lGTy2Cmwv> zdU`u-AxQVIv2dT@b_lVP;=c4KifhN)+*|Lo<=^{POLTSkS|k&+#SleHfB7@3od<X2 z;)|TSl7g!;Y{YQkaK7ko*zj^xT$Ne`gR&KuLjm5<MF@$4gqrKwaTl$HSpvx+!@FA( zqfXki6@DNj5Nd_;3wh*@3G;^4D{b9lk66Q+HI_VBZ$+5&9sz;l1PN(~58Oli9$-~5 zY>dsAJ=dn(dIx$(Gcf5r76TUr)-MZDASo(UBD+KEc!z$JHw8?HLjcm6U<cQ0DVS4G zRUewldRvpWb8~~exOly7TC>+$8++mIiR%Yxss_g;MEFT}Nr*MD5@$i8bZO2(8auAa zu6xgXn{yrKSXC7wcBlLz^jLQ{1b~;oB<FX2He*WoKmDh_=CIi3t*@ug&$If|KmDA2 z_A{ThNs}jKx!>7H#PeDzvXE!q{ENz$Eh7(v;$6V@FvsF5-*eVQP2|-RJ|^5u=idl1 zP826>0%ETlUp!>(Y(iwz@O*Qw5qc$psyJ{FF!A@!iarut$$rEfulv$pT0MR5g$I6W zC2%`Cu!>s7w=@KP$IdNw@BjVRcGGA6)J9&rkpA6cv65m&Y8L5LxilbfY7(_ZXpx*E zdy|DQx(`FwY08u-E&{G|%_Jf#BSZ@qE+n0(ehPQSyH`|lP-zFg9fOK`^|8J@5Fi`z zmG7F1#SsjD;<l^Zo$E?6g13G&-*~ccj556(<5R!i_OD-OJJ+p1R}{`|!#;~MhgQH* zL~9MF^2k~pMmyqgk&B00N3sBE=_<}V8v&6tock!|B*g0=raR#{6_s%8KzE}xH0`&R zo+HfteKw}H);{?8kK2@mm)Mi*e@}lwq&UIcz#Jl?DI(gK&(;6P(d+I{D#P1%r;SKb zkwqj8KJ{4sYM4BsBuM049s+p?<RNfwLco!KRgD$Rxf5F1w4SmM>s^+T90Aii*teT` zP9UBM0$(<)*xq&LW$4HB*&{z+=4Pc6uqC87(~FKoAw)od7EqA49?tS=Z|t%s9(c|U zA3S7teBf%hQ4l$t+ag53i5WyY>TZ3%Eqm%&j5VybLKfu$7T$6ScXWTfZTa<sHfPc# z;uJZeJ(R;_9f6=+4TlbL*eS+p(Tj=JE!HpJ<Wyx|+lgo)6d!eky-(ge3O{(KML6)F zMPG0c@gdqo$VwWkP~wCse45?bqbpY0+6Nx6{p(htB#q7y=DvpzQ0BP-0&x-`A1Q03 zzN0U`#BRRlV>aTlxmE=7SX7OrJ{ltiJj4-$45e-q$`KFp2i{&vew?VtmMXHK=a$8R zwZfAX6qwG)x$h^B*^ZYFT6Y^C`ijXPahiURrb5)UX|n=|9&r(hFc&R$QhywwyFzMP z+H2R`Fxzgp^Ku(nQ({FG=qW`9=THWfg7Q$fa0Sk@GFOrR*Z=x^d*+!X)&-KLV+X$f z{U6vh3$DS^W>vOrNP&P}AFm@ZLFm<Pg0=SrA^6INU1@<&wT=iVRZ`#1N2h*4{RI&I zr(QVOMvvQTZH<Ssx_NXUu?6*A1iK^HJZpzvol9o!=)4{H7uF27sh{{G8#Qf${rvB~ zVM7t&PS7_cc2|r6j?S0X+Pzr2`@~njZWUKwg-EPYpampSMQQ}|z9x>Y$`Wy!D4(}m zRE*F<3aT+v1b4c&rpD^(>fCCptlRC_v4f&Qq$4hPrsJC~4(gRsjUuPv`C3li{z?5? zPu|ZXSgCzNyn!$tE<|DsurZ?E?=Vr5vKgX7nllhEDE^Qh8&7Sm*1Y@$d-mr)v8Ih1 zyxn@xKS~geW95LkjNfQdAvp6`8}o8O<#@aP?$6q9F{snnig|D8CB``)3+{3TOLl3} z7ni%Z2tm4d2Lw~I)gReKn<ueOIMV+3k3VIf{fob_W&75tV)O@imGqZmTPN<#kJl`` zobdg$5lNcl<j(ZYdBPCRCy<9g9s+p?<RS1X2ngL2(i1r?Y|)y4+AZ7#2oAB2e7%d1 zVwsB8nKw!4An{y?j>^32X4--MZT9>V8-y(pv(SnV)l;;72!%LAObLj2AEy$g+B3H1 znT=Kh7pSswHV4g?LKuJ`s~{j?g(z`fbi*ySVb6BNM6lk)8dZw_Fp9PAiN|clCq8E7 zn2(MjH&V_9pGqq(mpCgD-KhZy)3TO}xD(_xozM^=<#NhCs(Ms^ue6ZOthYqt^j1h+ z;vg{6-H8K-4E1Z_;O15L-DkTNFSZzme3rxgii7w?C_X#40JskVNqR>Gh^gH5;SXBv zb=O(hgeev;uR`$|9TKci3E>cO>*atr6?}sWrSfkSL_|gkrRf9~@WfnDRNa$ZDciDo zzy0)k_uJ8ZnD<VW!-*>=ECDEka9HOefv}1TC1Om7x6+qa*)YVhZkc1(-#Occj)AZ$ zpgeI{f`WwtIjr>>5j7GqbV3y*OnAgMzVQt|x<Ch8%TlKf$G-mh>zsR_x<n$0ddfP| zRC`7B5|W+uci1aUJajo$83-laqqYgjoG*8QL7>qFz{oMxR>?+1U#64I1T2lIP0&pf zYzDZ(G<XK?ffMuM6swcKX-bxqT3PKl8-B~}cGdnvw)}@bpm8{(jPIpTK!tD;TACW| zr+@oD>@z?5H;WaIhWj8}Xi8hnrCh|#h#D;FtLlXOXPbuH2&3lXN&oci5f~wvI(4cO zNz$#=n3bhF=_Q@%c&O^E8fB};b5y?w0$z3Z%l+|g97T(~1v_254S4hJM5i|ozWhfV za2|XfAuw$xQ90=v$q0*#!L0e|k8Rbj{>|)Ay$uKSMYKf)QDolT+nf!m4h-MK*f?s& zki)2nm)ebg@;CO2pFL^&+p4e@I@G%RsE;UM;)$y)?z{Ag5*!%anQXR}z6NXRJ!A<? zjn1Ecxqa?)pS2Q>V@M-*7o4nNYTAlw6nsza{j?EDs)j6BY2uO#M3cYdfASE>Lm&@< zJOs{d2(UN~tasVPTSgajpkN_laICnF2}mENABA8MNWSocxC&9rfYs`7(W`HnVT}z( zZP)rkAi8iY5QihV=<HZlU~I6l&TDaJC%V7D7XN0s4Iehb=G-uiT}xSOV_}9^N)(jY z%=g@CFW=+Q3PAt>KmbWZK~(o6MEMRo0f%G}$Uf%=wIceldYMhG9mB$3>6W^LOvs=C zB!%tXyU%K*M}ZSE=V$b=fWMwo`NSa64!NxOImzVu7GNCyrf)nEP-v#a+tMk_cq5t= zhp6e_Q*T>;`<QKb;&JQTzY7ateVpw?owK{Q;-X;%-I|HpT{gt#+;x{-^1k<4^~4%W zlwrQSP(&W(BaY6biLguH>MS85N-xMi`Y+Ea7mhOPToMtinSM1OUfeseUiav)SKH#> zE<?N#k;l|fEL*7tNjPjJkuDeQCJ{*02^7~w6%%lfl3b-j<A~SIvYRpUT~vw4OadZM zbry_(O92fo6g&f0Ow^409XTd3AxYo;?sx46-~XW<Zal&{Y$cq7^bNc5#+&_FxU{&E zB3{)l>Q8uiAByV3chVFACx02VP}QA4;ugL5!+HH9E~BIAz@~`KRx@#^4H;Qt9Y@g} zgd^zf0bvxGgcc;DzU*U`v774a1<;JOIC^QM73bWg*`NJWJFs(??OpPFt3d>|hz_Dn zfJ*vTQ^Q_sc>FON|HmJ7-6U@twSdOIHUsGEULsN7?yqmrW7NXx$Gk%YNMvj%#E_1p z@P0t25s{>0F3twy4N<j39104!>`ne6e1g-6(<gaFZKW8D7ZIu4<(G}>Zyu5XA_%(J zD|d+#3q~2{uO#Cofmv?J(q_8a>?rz1&;I0x*0N=TB|6%yf{h#X3vJ{SAu_2At}fDO zVvcHqn?G#gH2d(U{@f}rzs{ch>2tQXiE)f+?>@vdrF*KfxXF0R=ho^N_q`C_-56}x z*{}(7;2kyvBQhWR*dJlSeKc<pEvAfckhEdsM6j2hgiet=ZA6kN_gt2Fo=7@HEu2p_ z4}m-c@(?(KAt1b7h_C*%x@&<hfP>>py1ax46R5kd3w<P^_8?*qHX<+*h=@&_QEOLU ze~~pGY_gUEI*}bAIgla`Bcuz&Ix-P0q6MYlmOlIW4;}^6yVd4iH_ZyGIai5%CGu4` za+pn?Gsku}>_c=9u`rOS5|FnN&V70Dk>A)j^dw5LY*$q|g!N0P2%H#@ibIDEI|33R z@2Z3HdVME6Tuv!O>!45=z2g)83nZc>s0Wk<CcEPzk}&7J{h8-%`M>?l+AwEaf$6wv z5)-u2WUe!4B#3teQ_P)kdZsN{WV1i^aT`A4LKm&m`7;@a4%ay%pCn>1elRT0f@~7K z5Wzko(P$BnAKzu?d*mX7RCRa800dHVLx=r;-+I7yZE1!;f&<hCS;u!7Vo>M|Wt62% zAvDevqr7V4Bw}~{91=Ws(r~-|kFLRj-FT31;);Vrn0{c7FjQnl8d&(@l%W{hRbP^^ zU*Gp@`=@{UC)=@erxQW{`O9Cnd$43DJ(L6iqN1zLLY9R-3$VI)RzqYjp^EBLj)m#& z9a9;Sf`^F^%_!~wKosD-aNZB-4}wLU&4rnlUuYZF?6S7z{UEGrUm)XSA_9lTuVCjQ zvp}{$oKV`JuRCcKMP-OvVP?Om+HU#3{@T93Yr8e?-C~vW_iBl>(l4tK(Odc0!&dvj z_gDh%Q-(1urX<-Y)u>IBpFD7q_LGZRChHkI@EkULnAO(S(r?s`W=D=3aY9K4o}cLs z$WcVft!m{|O+b&J9F5q}+vOWwk-wru;nd5OM1T@cJnG7bVL?ERDJC^0L<l5t1G{^y zY1Jxw;s@WcqZ`&(MNd2P4uq6PA}Hn3oYT#C>0m>t8>P|F(`VS-ANr70Ua`oEht}HW zHHYkXOF2L`R&B9<+E-RZF%Hv(&ZLMWAD5~N3Z<GC4mQ=>!IpX}W<I#`%K3KZop&%# zF(;sG8i%b_f|b*BA-bq4@F{kujYv|xG*LRm%D~Gdl6)|p;)>^!&qE*&fjk8A5ID^c z&;p%hWCRq{mvfL=U&gtoSgZ>W%g{chb`f>S;DXk2)?^mexLvVm7S_|+?8%2#S$_{K zDESjtF03(9JQsnG#PU|MBWd^k=m{3+gw0+!8ND2kadtw*RhhY9k?mdjob?|)NO%x+ z*5M)+@cK2&t#8*hD;Y7yhDcP6v<tKw%KCNqP-9eH0!x3&@rO59zkP8RQb3p(hu;eK z6rrXfE3TZ7Ik)Zy@{;c8wx$&;Y}L<yV!Kx@v(o-v8==S`CgNlziKEkJdLRfp*ukyA z(8Mht|AdX6HOC6D>=nmkzeEZ%V3N)OQ&e!G0+15nnLx%lb#dUTXPsW}6{j33n^SBQ zECpaic%W^K<v$3=r#IXEKmWb8A)RRbB_1zMx!i;^;Z@Hh#AX5xf{0e<Hi+nh0*sgR z*`ygYcISr|+6A*~tU&gGoiY>*5PyW@BiMWX4jaDfg?}Mv(usQb!Qa@|zy5XGv27c$ z%Gee2=i7Vlevge9D#IGom2ff+5h3{06HZ(KhABwE({T_2L0Uo$LH4S<I21rZch%h; zWv1?sq1pHI?<Ovs`kOd$LS}0xV=-<*x$W8n{3O?j1B!&vfL2@4{@M1@v&3I@U~!QS zZid}ZP)2`*V_7nOtbOut|GRzv&pwNZyCy3kn=<u72=;^9Ub5}K{Dn>X<eyj^QCH<q zpftIs87z@e0rJA>cc8g=_OftSYpNXOSZx%Mq@ybO`uYZlq=0*#v3Tb|r36zd<SwTl zX8jxrUTKZHsP_7#Z2?7;kN0N{c=<3kJVEaLj8P2<5wdB->D0~BUA=a6CFiUC<i{9- zS#G6-8Hz5Xj4|j8Hi@HpQnXbg*6rHhJXO?9x4S?7IU9BLwN^ZGIB+krWsh#LU;OYf zxbw{6i3&EO*wleY>VrTkgmX=A@i`^K{F{UbYVO4B_ugH^P1=Q1r`e}J{U=sZTFi)q zqfTukeb&d}*s)@XQ&TT3Ag^*!9be`BHat!nk))2PPN^$&(m>(Aje6vx<ROrUKpp~l z2%Jq2&^pE?6je*UkaHo$TDWykt9GTuk<c<POGeUPk^Tc8{F_T&ff*#&)lO8#?dlun zB6inltCnsf9H()Bs0p9XfSgNqPiswz3<}U$(m5_|jqUdH@BaVny$6_`S9R~b&N<Wj zj7HLon$^3lVq0>z<%TP67_f~oC869v0v{xhKyIFUlZP9JgeL_^aJUdKa03`{1NVk) z*_LHnwz{m|N7H*b?fd=LKJREGEQ$*f*4fgTx9xYAwfDRC`tMctomN$Mz0Eo01SA;b zM;?`nPqB1EqgiJwX`tT0+vRW&l`shF@4eejo_QiRO*O7^HU#4!DTxfhwLtCe%Be$; za_G$?2d}E9?mS6gIEd~w7BfoPnZAB&XRo7G|NTST^vJ_j*xP3Hl%<q<iK)rJSoBe+ z9un&ZMj8$!&b#q_HWT%_A{fG0Nf`+WEXaEpbQKc>6ACF@9Z@vYxm>8b^i8xEy}9SM zKcSG6iWB|^4|{RzZ62`y{K}7P!z+6%*<WPwREb*0;}lRP&E;xSpXa6C=IVROgSIH7 zrHj(G=&ZSR%`F$(s0pZQVeK6@pQUYiG1xVTo|KJ3syxcurAgu)Nb@Ox?5+QBtF2wL z#u+Eshh1~cwKj3WBnN^{P`yW7m0f+P0Q)qj_HezZr}r@(c@#=b{?1zK2JOKEzt%m~ zO25})%oO|W8w5JlSyHsEgURB!Em}Iyc5H01JsY|pk?143Ky><$OO;#|E_};z>{C(@ zISD#1LprN=jRUsgWhGWNZ;svgxzF2o|N4I#Ul!jdV3xQQ^vnCd@iiQ+OtXp$FR(&9 z-8uPls|o6@`f3%_d{MI=yr*YeQEv4EZFD|*^k`SJYj1CNNs{`g*G-8WtKne9LJ3v> zK!}5tb^_$;t5}={%7j<^ucxEC&@GpyFC1{8{nauoFv;eq2}dwb{piQGgN2!jz7Fh; zaL7Pv323NR9^hL_GXV8+>}27gcJg$)@dF=XkF{l1G<qUqDF7Is3U_?>aeM5}73>9G z&Y}n46fm7&!Df)vE!jhcK0==W5NDAfcMo;huC|@nF|}D~aiPthKiAGY>r5}Y+Z0l5 zjbYl7L>})PKa8l}TXA~SK$0q_5CJ50Qn_aA#}iR>FN*V4R6L(%o&tFa<SCG+z|p0E z0FwTR?bK{9Mp)Co(2^J(G0bA}eY05Rh#@9xcO9LZ{Wa11DHCVov`U+^WSni;wBLG~ zNGA<LjBdR1$TEH+9j$<-06PL0McGnIxA)rf53RSc4YgK35s!7GmZ-0{lP<f|UfH=7 zJ^W7c!%+k8VQy?MKlzv~_}Hhcq-K;A1C9of=t!6T!2W$=3!RA<gRM<9#WcQVAa7sA zg@JUhQIehr_`#$UA?=BgUY2sF@Eo?`&Y#)x+rMLJ4B0EFYzcAUE2#^szq}*ahV~Tc zgkI^oF?K%guII2PP(sG&teC6vQd1IRqjw~&5`hCSRld-PUjZOWL41<~1k#ip16c%# z4x%d2EISmpfv%+8{;!YPt1ou4I$UIBMeG^HKlh479%_>;(lLn$Nd{m#=<QpG#4nY> zK)*U>OD{gzE`RqqRy7vDidvO64h}_wdDAL25-;ZiC_sYMViNN-XbcB6%a<>=|M@?^ zXwN_YoC7lP3fEqDtzCWXRk&xbRaJ<mg7~Rkcjihr<gG6}_rE-l&6;XJWPhfTkdLBq znn9hiSoUQ|q;j|P;&BxMF9wA~Q}uMdMbT&8Dbwu5XVzm^gsP?J69G<QxfGT@Ew6Ku zUP|(#?ScojU{S<k2X-Yfq)zf)7B4Ncx{EHiQ(jzW>wof7tD_U8asORHyVfN8>_@l$ zt=&9*iWN<pPM_u*M$NNO{ab-@gfA@sb2S<{dOz`&R2zD^%{NDvU6NdYYp<mJ`}ceQ zIp#r<>Zy9DLWEFX)sox%5ois4JvU}@ArGM*6oGcpn4@-6RNZorN(64vxA_Kfc+&Ht zBuBT~wii}doGk_FSR}$di;sb5Kw`hi*v42fL;`Jmqs5b^*_H4AfK9sSLe!S4Nw}0B z5}~%N-S)5d+KbCK;)sL2kOos$h6FLrIGn<5xE8#W4qqN+W7P)G+!yc0SwpLB+_RQ` zGQi?hxh+0r5$~w%B<t-=AJkZfG|4@nQgro5)ki_+Z+19pAW0uv1cp>8ovY%JG${{| z-t4B%r<bQdo&tFa9BUL1`!1$NEUM19X2z4(B2DH3O_FFt^8?Q74w(owHwyHKQA)sg z&6qdECePkyFE{T1Bw^bmMnP#P2Qdo#WGf>ES}UEgSdqQ>#2TA9b4;BBV`kCPrQetx z+qP}nwr$(#*hVKEJL%ZA?Kifa4mzHEb7$_%Z#ZY~+O=xcdU$XZ(sf~;q<`A|ofTNs z@O$H+HDOhgKeX0pIa>E1>?`qJmdTDxwYbdmx!8aM1UUmc{Ba#2M#yr(@FLJ2*vDq{ zZXQ*qOLX>?!nu`jSxcSN8G;_(pB-D1uRS!J3u0th4_D#x2WYyUc+U^E(56PCFb(Zu z5{cBObK->ku>X-s@t75f(Tgg(@sOOV0F?Mp#(9m0V<T-<*2v6Z&z(1MO#&pKm+C#o zdOSC_T3&zomv5r$Y7^5afx4%5B1uR}V*8Gw+EK`0ABq*_E7b(NIg`y>7dbaM?=6?D zwcqHOg{e2S_+C3fV`l1TE*B!bDy|I}(1W;@l7kjCU1-$S_r7HJ)|cf4WZ720W2}2m zroVKbv08A69wAD+BRi=oeRReDuBueP;y);TX1^W*$e**?XeKGHo(azrCdzLdQ<b(R zbmluMyWInR?GFRCT`|{Y<fmI~^)p(VJ#+EQixEz;V>`sCjTL+U70U}g$~*-M4@8A( zHl?Pj_E8#WSXl<V{#|KuuDa5Fj9mu3CGV#fIZw3NcKo`D2{h*nc**lCS{o4I4uqbj zJl6MRJIj+f21vi0tm~C2{~C?OHdQT^t5>hmID5J+ZBQBHwGfTpRPJ5YL{gXEak#$g z-(OtI2|Nz|3-sH#{!NZKI7%(x6t41al@GbGW18cqN}H(R==H8ldv?=6gCPYTf0(Xs zP3`!7SyKAJrc>88dp2aK529!28iUQ)`E|jBxCW}O^t`w3v|L^ACZ1|8eoEWTMq^=O z9h@S9^1Hl)qPRpcIaoP;2^xKzA#7|n<<fFIv@q!X<6OtKq$^3q`R$iFu^cpLoQA<q z@`@MxaQqveJ+XK{=HI+x9QVS;R<>%lAI*PC!S_EuN(Pa+=10HuD-a}>33>7?7|YNS zBJ;L+{1gcVm%h;21^wFjSX-`<LeGM^nwWO`-&r%TU2UU7os0W)sSx)G(Mfp-rA!Df zli}&WiP194YMhoov(NsqyQTMouXFdDTZ6w62#Z4rjAfl^sD9oGq0vTRR1m_N&=qaJ z{+ds?6vZ@%)LG@)X!DQ2CBA{;i(1BHE%ky$HpQqx_?+e^$UQNiMRs);0Z8~(vGaeV zcHeg2tmm><DRGJ<gEf*I7fPMekZsS_#<acx2vrq%7Zn1(=z#?ELF3?f{jp~GQGNMV zw8UvF_oQXY+d>4nt|ec8ph*|@@k!byj3YInwL}gOUkh{=v+I3(zJBt%%%*TGiQ?8V z+kp_=vjtL;)93rCWW<8_M5jWwK!p6k8by)1@X8e*c9__d@O_3#UxU9)Fasu*&U7iP zk#VDx7vZ&oRx(D`K6w-|R3^lZX;%BJeLL%Vj1&c$@k*uOJ*E`2U9vv5GJ4Fup-9LQ z@YaxztNsRe`60=1@$>D1hXWVWVT;fszrV!?qe!2zc$(lcp>`S#?k!hc2K~UVw%5Nn z=n(<m`@D@leK*_oIUJ$*G4OW~ugidbh_+|3%l?Lz`@54%|3yY;#<=0;VSxV==Awa& z^ec@&Q9RDYvf&Hm+bcci`dn}~7s%OQ5?E6iKF>GD?8xw~BWKv6F_~{zrpl-k-*Eo< zr(G(8DDPiI5={0c&@z=qb<xR`9KA=$n7d?(=H}-1YL!SoyU#c>DdjW~e$l)Y(4bJ} z*YpP%>Qmj+Ln+hb;=A*W<Z@d=ZhL&BQRz6c)rxC}4c9Nxr_DhBQJq%D7M)<y9%Fj+ zas1AnII?dNk-dw?+9(#A7Vk{W$2(^AT`Vh|@-%c<c0e%GRZ`2}Ba62TM*obDc`4#) z0rz4}DQ-3l3hGF;ycodndXt9xxuUynLpfm`zfp)CL8tE*&b~)sJT@4a`o@4boJd&w zKh3lN+d*Xr>B_9Wq@u0XmfV-6zi4BsM2f+D5b^4;OvsXNu2uu`yD!i)kx_y{l<ngL zee0chA8KY1M2L1`A=pT~`MnLENybhC3~l>zxP29Uq@IF~ANXEjA<B$0fb=m@1){@U zqVOfr6u0DM`RaJew+4?B{RA!7z$*RcZE_7wZ9B?b&tQAK&(z1}R%jFM!KBcT?e1^k z_iD#Jr7Yj~Yif~6Pqf8$hrtqI>x95OohJ&b)ev*&)=H7oKIzx_833)i<p`_7(fgjc z$|NC)=4_i)5SGp6u?1}FOPCq=Pod^)ra9)eQ;IzQ8=hvhY*BCC&tFhEk(6%n(xZK> zNvdt$iOz?=&J|teayCFQHdTLtD-7ZN=zBox1M>Y{`c`N-11<cg$Lf;JhmtI5a*KE< zl}L0jZe>Lxuqxd_HLoi>L**$=!GHzu>zUGNEtgs39In(JDxl4&s={b0GYzcy?f6DC zfyNZonN>ufBkNu*FrBr5uM>jnq6vJb@cEl*jNo_yXM~^I7`sVI@Qqx;fr=;XNb3B0 zuRJ{N(3LqZzJEC8^egBqKgJU6h7CjnUsE*3Ar?#?xSKDXajjS?=D7c<;fg{(<_t_^ z(({<sTmhFH=y{pTGn#^K)a^0tV4`SW=j*z2_@8dKdYiIq+7@J-It}xuf4(@NN)>l~ zyw!`F9Lynp-Sjp)2HY#su>u{Bii-lY;^FS(5e2PG%M=@bac;>OrucfVOI#hs73PY4 zA?nkzrQjsxF={#WmX?kPt9V(hY;IoCc>X<^E!*5yEtDLcQr?k5Qxl03SC)>rkP-9{ zxs|*sf+(ts$W}9GhVGa3!-5$R0-161EOR%Rd|pThw93x&TiEhm{d?6$!?>h|qmww# zxvWU~>{Mj6q{Vwu>A9AA;aImX(PKJ-him|cO^u;!;0FrzW2a*jl84Heh3gx%0Fm^@ zR76c*4IdPjz#DZC3ob+zJbB~gJraFk(&GOHvKiQ#bdV^Y$u=zTGOjpJ@sr9%|9d}P z@gPO#?HM^9N6M!fp~83m=2`j0kKn&$K{5(dVDt!xJ2M;vdus*3<`s!LNt%vn5i{PD zr+z}LAvA3FgJqu9s_;QxFlS4l;RK<tuyk&w+aszO!2`IMP-Ehb8*W^;irrz7$r6Y@ zLJX!#RH{|=2UG?OP!~bqyUF1YxGmr_na1JVKfbaGG@8brzNQoApa%0YKPNbC@bBc% zSw5A~=rM-QtWN<dK7im1bkUCpZP0wa?$QK;@vn56X7Il?@?N!f-n7_BR;AU`Z9-|1 z`jRS(#hwA!&W44>my2OMp4?ZBSlvs|*<u^nAg3A-Z_!P+Wg|Q1qwV7Zm9W9HA5<%h zGXCKLp!tx5W!S(!slq=ez=%$vc&iBBW;g?_sth+nY2B8JfIAe*@UE(IFUdd~ZYuzE zlqqopXq(=e!~@JfX>t0kE2GNTEs6|-dLV{A*Om|5Qto>sr4h-t{CAeZ@ZJX<K-?yP zx>#4pJU6O-68Nd#d0E?go8d8vFIc$c6~i-|E4cA_JsD^jqi7hL1LymANW-68LFQeX z77q(5Il&GrkMt)Egf8r)-X;uf54Aj@aMrTUsM?1Y(otZ%otB_$9=pR^k`<$;mk|=g z(q9Xw6Y%fZ$ZH}5Mo+`+7=btgT5K$v(|$Hidhxy;4Kf1L;24cqPkb;K@>%V#KY|3q z$~R$3GIF|r+keky*YN|tJXb~uj8xp|kF%v3Gwa?3d(GqGP^-@i&4aW&DR(O((kTQT z^Al?W5pp}DgYAvI+j$+z%gdeKJcG%uG9Gl^t*)C*&v%PT&QIL=wAgyp1j7{yON%+9 zN!45F&d2QLV{#4>e}KgMtnnCq=zFfe8VXpfEL$8!&oW7<`ee)aGt1+S5l;z$<O+?h zY%JK;w0LV8n39{~zLYAvKRiT5mi`5xyh&bbn|gjcivp=g$W}~##88&J))hy~>aF>W zf3k$xlMYe=upQmc3^*d<v<DxUH3XZddYnfyq%!yyoo4E-_NYBx%x}zMl}pAXUw&xn zoXjU!Iy!%M2xqrGNB#4AXyb+_-wpHkE6LFi7M``yB-ywLlvdH-_<k|@mPyb?5&p_N zWTeCXdOdy}s#0HW%K9whHe4@cu%CyNHeJ)k(D?ZY6xa983s>K(Z>6gV;x^w4`yz}O zX-uXtCIR_}765Z-{Zefe)F@1P1I@Nk@M|XHYHGNV-eZPuLx0Z1m$&mzCL0i8(Z`wo z`EL$wwe6oZpg5{i*p?-^dfHPXJ0g(F4!0P);Qp(lJ6Ubxa5vxH>?_G~4b8*qCV;lq zSQL290su=bP)Ht&q)0YEUsl^_3Zq;b$NX&xaad0>Z}VZVKVw94N<@Sm(pdnT{1@CB zi4A>`th4yHA52|QnuihS5c-rG60HAlOr)wjVt<oK;KR_MB4|8E5PD)C`<ws`42@fb z86rdKIEbTrGQw{11V{ux93%?*maKV?ev}Sg@#+*-*Q?)JgS~e<y|o$=90okb8}hw; zH&wnQrTb@kr~W{h%bqa_NTdE#uB`tX@1^cnK=#(#-_CMIbMu?j4r<e@bHyF2U#QVn zzdou!Go3pIyQ)}b)RK_;@wq}(%ObFt`|&{tSWemlQZb!?nyC#rOs{t$k;LzCAr%3n zt;_397#CREycWPxz3Ko(s1tRt{=;0|s`u9@dHT>beV1#{jdt(e=F97+&)Oe;_)-;L zcUfJNCCXK@#*<I~K5Q>@QZjVNw=tVFD|#&4p_-#l>CU#w;TT&Wd*W)Azj01`;>m0> zFV}Cp*;n6rMA7=J)?I0GSyoXrc#u-&s5jm=vqT(s63by<Byr@@9K|lHLHN@v)w)|0 z(n8X+3F`U9IMBe0)6j<-1x)acy3?Chmjem8z7$6#A@OYevZVcDY+D}>yGG6H_R$rA z*T~_-cuiJ;)bhW!d`9!-8E%l+gvozU%z&en<ql0b?k`6iAC;5UULvHqEY5R<mbt|L z%2}<Y?MrSA71yIFIT9tgb(*+L^O=5O`A#u&Al8kl5N}^bTV)d${|mE%h9~#6PrRwB zqlr4d663vTNVzN(^burFZS9Da&*2^vcsUb<hz+}0q^;pgP~oEJc^c$BsoykCP~kml zoc_;4YTE-1$#qB#%fj1YCsYhp1q$12%OI9@DpRYRgX53i>6x!{OHk;~C_{(dU&@2v zi~;G=+x(Q|Zy=g=4+~H!ogvYnwA|TviT76O>M3;#^hq%~nP6vIgTw#=HSl_pROsb; ztv^$_<93Z=_6x9#*$_@f4GHKGQ9TVqxntMNxQ1pi+kqT5q(HgE8GOdiAy^I5{MeaZ zS?!^w_bj3`HfFY{lE*{C1D-b)#OO=%p%U9i{Yc4$tPiyN@y7%$AF$YBBr-u8Fj1Hv z=y6;oGHKPUANveyg80Mm)C_{(;J+nCujI~JuP(-@s0=u2<uz+Ncv)=7dRFQnW9i0U z_Au_#7HdPwv`a&)wPF$vO<^0}6<SSstsqC|F^@p7YQe@l!B`xEU79$V+;hxTo5n1h z#7Y)#_e3hLkPDy0)N0aibj$PlvE{1n1%q7=Ab9w(1ZWu7h^mlhUJGB-*sN#=%MK{6 zfS-{qpOA!~i+opeKvrmeKAi&s%(RQuqGZl7B;`{C$mwd>N^saxqd98v0xlxkyS50q z`rOZjiFopat_D)dbSL96d>>92wRI73iM@A9@WpLsN@}nqS(1kJ-&qyA?9d;>p5mYB z>lbviF6QuGUZoN~Nh#^VylnkOB|jtlzhd(0bK}8!tX-0VF#H{@ZV)=(X1@kzKIaJ6 zfH4dW12}v*@m8J{CzXy7>9D)}(M-<!VtCC{P1D(&x|Wudxz|r^Y8CL=J*Lc|jvP?Q zUCFOw57k060Y9%^C25J=&HJGhUB<5iaDj_vTehp(e`#koYS?M3y-z$aGQ)4RFh{iM z2dvnzc5w+8OjO;gmxVK6;4pw_OPaRMlLVFrcBaVG;U7hvI~kc76gKN?mWtc0$^Hul z_1hSDtV2Lf1mq+P1(t^}E>rUx0KwHnmA#Qtyj}x<oFiwtN%yghB-_QLD980or3xpl zS<(M>vBly7j?Q8DGIU(^lC|j~nN?9zio8==LfAi>V5#r*BjA5p3mm`08@)m<LN0Cs zgv@~6!?Ba}|7c5x)VFViL8W{r1w+$LBrW=VAYopYN^FE^^&)h~gt&xTv}vQ{%&k*P z0>d#|88WFr+DzIf2bds$L`I;>`n{WR7MdXuH3BIyLCEOP4-~AkE7lJx4nU~2GVP(u zcPSxxL}_m#2n9j<o9C8aVy68=oSzD8v2+Pl{4jz?8`Q$!4FqDdfJfP&w)p;_3}|48 zP)Qq`N0*Z7JuyiEAU<Bu4n@-39bHtyPX(7mSXa}`?N)=VC@oHkY&Q!<HypQm?+vm{ zCARFKF0wyDRzq)3IS|d~nuTb}r=;!C`CzOO+vfmAu|X_%pxMO81d|;wb+6A-;EGPq zHRjg<<gm?otMT)lAx+govrJ)0{Yoeyb={R;kl<<9XLsU0)VbI7Z<+|XjIuSWMOmDK zT8u*G!)3DLn+op^rOVY+jLy@3zzB)V%QnHdYgE=^tFisOkMD1*h&a_Vk{Xccu91%z zE{@r3kOsxo5!^^=YHgWQ0KEztIAAVM5JJ5I!8oORJ<D>GF~l)z-@Pws@m}<JQdpmU z1`jRs9gV8}WE&cg{K-F|mF#3m{rq`IoXzK1nB(;%2CbOAm^*_Sji@$o8l?WaW60sX z^UJjL>&TLBGJe<{NQAz)0z>A<&&#>7W%v@UKlIFTH9_mws9o_DHZvCdyKr|0!J204 zj>{pF-?wGUbBEFEcYRF_!xs!0weAO6Dhfa8X1=M|teYV*&#U-DvLW89(_xY5cGP}6 zUwkay)=A0Uvjks)0z1z6Tf*IyW#XpWpB<~JHM5sANy1_DXOI>KA(81*Ez*vp(h(Z_ zLVh8rn?)=obxTS^zl!OA)kh6B=dNK|fcQh8KRh!AD+>!!vA<X+nyJa#c0lLHPM}S; z<_(lF`oVrD{FyUsKi>k$$ezha6fv1Lxw-htR?Mhq#mXJXDC&oXzM&nb-yy7SlU=m? zL+eJFz#DewNk6auWwp4=<6XiRV&_?DHr9Bv7s@hkEc!NO8}_p9p)#JnuU=q&7{k^g z?>wqQSFn?su*x@_Z#IW_wN&oczR7Hg0?#;wTqcr0AE#2qd)0qikWm2$i8^Mqbm_RL z_SofP<&x%>&R;M(Pn0VD6BSnGNn%uyzkbLe(Pr#BeWT_6fdvu>g#nWG6FCI&!Q0$Y zZF1o!hnd<AMNu2~WwQ1ckTSvcf7GMUIFTy_chbk}bpC)JQWAt`fBS+iAA{4gfOg0o z%85Fpnp4pNkNFA3TLM?J%lsDF2QBflv=|Gz<|s`8zC6>PWj}8MCr$fe$iV8}<W&=G zf_8)Wh#W=*<p!bS#+sJH-3f`PH07kSF$8tS6*E_HOzI3DUWGsAU|gn8?Yb61JY|Wo zkb5#4h!qKAk%S79IFbL}^!!b^>LVT0<29F(tn|Kh*~{Ho?M^I<F6JXk8iO~=SmH5* z(rC<>ezG_@kFJWj3|+J!63?=NDGotkpf2jYwmzFu<oilIxBYqy5LTN_@o>KhAVDz4 zq@+^xz~-x$wpTowE+o;&qH3*Qe$?`yLTrvYdC$W3+UPw_5xmUa{wnV&Zc#=;*Ly^1 z(fI99NEaXTylB6L$f1K<^SiOBQ|{l<Ba;_g@$7;F#HPG?%+;6wmx68P3rJO7F~5hE z?*hypKI|j|yp4kUlnfv@;Y%j}y<^+g$fP;?4@yad`}fRqs|L&74|?3;ZAtdFn3a(x zgxulx$u!@Z>Ie2abgz0zQ#kejJyQfN%j(v$jX-VN+fTPT^E0s5d@0#yGu<Mj+!!3b z6Q0dS$=>_X9b9M4RY^ZevwgQ)O`%K#7II^JkbfeuG`N-zgMZX6oSc#_Pn-B@HGpuf zUziF;1`Rqr6|mC7(q!c$Ea`XgYT<XnkrTQV<RkH|tlJ+1*}gAn=~(Pp^%yW+;ZU`> zfz}L!ie8TSj$<t~4wBv1ARFB!X<{-~P#B47lpUdX%T|7}C3T3YJT+v!!%M{Tre|Uc z6E-MM6^sExBh$2{aAtOov=^77T$RYeO}i|vGj?yg5rSwv^drI*H#|)Hdc<wsWp*~Y z+w+<74xe;GSTCAaBZ^T~PQ5K@d{LyI+%`ni@GEuz&#UGhxbH{JNnT(N?lOLT(+kvp zPlqEeY~(5$+^%FMV|6r#T0(Q9BF~@)`&G+RFv2uYU^c44eGX6u6MYvjSoSvrT-oN8 z+G^op=@+9hO{O;LeYm)Vw3-SFOL&mJYX$Ob6SW<rQc93?_|{*#p;$1%e+7&Qp8Q-W zxhaCEUNjq%G}In4D%hg?L@-fLj#0Mi87vfQ?FQ5(ke!JEdr#@F<297=`Uvk}Q(#ri zT?g3$G6NzyF!JxI;^ydeD6S^}N%#3T6RffA;AB=OlO-x%ca+?RSJ*O`L!uuk(~%2F zZ{{ew^+5$z1-1dm6)v^sL=<ANNtZ2!qoC<DDP$h|NsB?^&mz$I=mBnh$9<73e>a~s z7wp5RkdJDGw9`5re7U)hwU%>0|KPlC_}INQ;@Z8%=+ZBygtgN&YM14ir6}Z@uHDZC z)L0JT_WB}qi$Lq}wX;+NdLdI~J253a{620lxop6hkl65so2^qJb311rbyS)}2FDX4 z{jgFDCR&RbzO8c__#MUJ{KU1fy>1bO0;2P6G;K=$lwl!0<{*Y~t^|5GI@Z4hJjHI^ zN@8jWlN-hqx6N$c!{$W<*%meoSm^&{u-$&GtZsi(pcV4bmN1m->(^YA$m!(V2-*3U zrO#73Q)w|R1}l;`q#jrkkpdn34=v?hMFNAp(zfbPL+Ql&22XWa?X1sB*vY5&3oWR6 zK_0<-RU_4DC+V=>@437p%h&MV90a1XW1P=Q*5I?Q^EsPfkX+GcN4KPI3z=n#qVaYQ zTX5`SD=~Wmqg9tey+2w!wN|UL?MF!wH!7iSTFrD**pUo<<?f7`SH{ky;G21bP^?R% zC+V1d{?PaAl4J)SrD+5VsKsQYHiQS0Me@OVY3@$7>KftA{}lGrt>u5Y#p%4ERMd5( zb(d~nrt9dZ$uQ$|h97C7%o_RO|E6<!X8IK*hFr(F4dtb<#_QNIGcql{DTPWXB=f%d zbrHi6gwuG=V{wV~Ha03~V;*F(<wT?)sFWRgC!bcf@cQaiW2}Vh!0Lx0WyBS#f!*VW zst`{jrSkF}z-xcwf8$&6+#mhw(4iNz`|`gV_y0LBw@<}FI&yG-^El{JWfU+*B#$Nj zj?UKMGPZB$dL?~0wINGBO3<h`EZi-tS}0aucG%Alrxc%}9iuQiHlQyQpYM{4&XCPd z-dqqg9Cz!lto@9!DHd+n8?UR4h>c_Kj~PrN6DQ~ZPlg3Tv#)IYR0!lf7ce7s^lfXo zhH`7(qv4G&aHWnNX~)zL^1bzEV)(Y@cc%CORLZenQi{hlr{c)a{E6ZM9zJ4hZSRsb zEsK;vXhvQ_%mhuKhE$Y)_LWC+=QG@cml8RNxEKWLPliju$Kh#6wUOag6@V;dzb3Ej zu!c^^_CC5j8H>^LGR}v0B>&9h0{$T1BUXx2C4kNyAL9pNM`;gEGv-U%r}hu(3#Vys z0cmWl?1ruZkTD*MZqu|PQeB=*`bP)Eo+MYjnTwfRdSh{*VV)!9=AJ3vfMuJFr%lMs zLPQ`H$ECi<nt03Y=HgT(&=Z1!kJOT&oy_ne-$PJkF54yK4^_jL3xnE6sI9Rfd+IA0 zPT<P=d~l`y0>u*Bdh>~)g?qgW(eKs?;`fQ9d!No7%rtS9GE#d2$w$_-Lc)QQT=&nl zmg@=%TlpJTrWB#V0xyOf(rZ9pcU{wZ^ckh%R_lO*cGuW(o<RD^`3C5^HkOCop57K* z6gY>Ztl&Rq+l?Iu{Mk>G2(Y1fE#a)RA;G#&bKlF(oo3JXz`S~sV$x)*^Ts_v`jMX@ z#nk7sT}9os66~?{5^9q?&SMLRbEj7sKhT3$m-N+Jm3jesd}*S&VFFmfdF3&*Fc95U zf;{1tP^PE30k7a_g|_~@?Yeu|m<ZwJp-x3Esplm3@~`B{MGRITT<cGLqE8DSK}9PT zRmOak$K>3B(js8X*k6<@@;Vg@F0^=@{T6xtHS}UGYOJOmvhfW=vys<xBb@7{ay?kX zouC5MoxYcrJHAUAg1y*f*j%$xYVC9C=iQ<~c=TCwzv-~{01;1UUkurUKT)hf0Y7P8 z?e~8Dy}Xn?<`$AEr19P<dfrf-<pVJqZsyvxn@=8os`2cNdDk8)s6K?Ixb&1bg6Jsk zOa*UhD<+on5;jd{#Hgso)*TR>m+mJGD>Cf;6qNiy27#OlNlTLnSJ_q*qHN^G894Qy zKK~xgt5aEsRFGB3ftjuj7vi)xgZYJAOW9zPY3JCGV`rJGu!FZKv2zX=$}%B@xsX-< z4{RNGZbD5Vj2cUfJ+J46zo($hMT=e2c6@-|u14P>atI7({Gnu3?d^{ls{&3-2rFK+ zhilPZ!V#j8#Q|d5K_Q=wZID5UHJd6K`?IxG;I~I}eNs^%%tmRV^7gdYTRt9>t>04F zQaU3aMNQfI;8?NAlg>ATp8J4KW`rUxHJROHlpAWYqFHrW$Q;p=oBVL;#4BP;-YA;P z+oWi18^qT7tO;NDX?>j@*KTsXdu4eWj#WB$9bP?bj*oUkbZlA`eGvPUk(cTSEFn2N zqCH$uTG`OMgciK6(Ay%$a<&!Mp?!P8NV)lM>IAg!A$i#F9@W!>k&?oMF#FtoZC}mx zDgIsuTIhCTV21xik|U5J_Ei-M(rH!CIPkqcVQp0K1%|e^I$WT?RnKZTsfj3fhehm# zwuALw`?K15B(};6m=-$G&#0oN5+vc7QgUp*>kyn2A{|JZ(>D~r9th`Bu1XG0r+aKO zJ}`t01ah+^**Hnms8eaDUkSx?-n{K`W?g^hB~1ReA3q1J8^fz*_;kd9R7g00jeKYt zRAX{Pz6DP3)6(O)1%JiYsLZ#6_GbYDDAH1p%QHU+si1K(eZcp4b#0CjVud<`1LO(9 zbD}h$Qe>sh`l@Z-tBuxc8L~NYZac1$j$cGbV71wehc8@--JikOSVA&RFH}!22LUQD zzbXWA`9xn_%{@c`+6n<iCo>AnX^Aqb0v-Ubgl>ZHLkaG@LcY4u4m<Jus=kJQ!|tsJ zaXkj{d#=~UR7<f{FEu73t*KK_^}r$n!d7vIlw33rE@9U@Q=d}PH8D|2YL7}~vL~%e zA@wNl8#dm>$dDNFfL1=KHPEAW@l@~qwAkY6kLr!7jjf`-^MGljGWHf$ukvg`EtDD> zQ0Rz!bV``|0DXd6Le2aAm9`&)8}&&jvaW5{ZNHo@zMOq*?C=DQyFP|31!Q$_@&<mU z_0=a9IC9Bji+euOLd^+iKuDos^m++(kXSz~{*ov_lJztUj2sDD%^SGzQ#FzjERc{4 zLoz;eH;8`VfyoY}|DXBeJ=#C8e4)&_A)_ezZ;jXy&={l?yeuQ%my~UzE+H4CRUd+y z3(QFz8Ji&R6S#NCWJ{Bk5|tAgEUswTJ(hktSmJNlzhk%Ko0R#7<nsg|)5JEG$neo) z{w)LX#Ac3#lTnwd6X)3qdR%1y*g~Tt9T}K{uP4#@c{M?r_m+%K4rQ0C;aVY!?4DQz z^A8VqsG*xv*}BBka^qc=p`}FAz|P!MLYZA{zdTCM9nK;$3I#R%XYQidquL9*;4Ah~ zGORwV^gPlj9gJu)9#&K77TD9m#B|H~OY_S7x+r!`HHn5L`k9W9Vt#E^zi=VEHI?Ae zX}e8@4j%kVOd4HZ(K3>p-5(_t^j(<Bu&DjwIAhkCc1p$is#+hY7UHASs5Ec2Iq+z3 zzV1+&m?p_^z43PP-2&QxS41p@0qC3U#?gR(&0kGlp9zk8D)`dqEee(l+><qJr!Kg< zlL0()VB!)t)CHlWz5`>w13F!0PT4gbmF5h`nbbJa5KczW5MJSkQ8sHN7|&kkDqsE{ zTqBC1U_Yo%%5o|%;27VEWcts$@HrH<KHK-%nj#_>(8B#Fv<79g#1?8T=3#yfK#oEE zZl#-`K7C8{UwRsoYND?%zlKRfgZt2SkfA}lM@g!FvyU>oq$sW_I(!&v%&o?I%IM|Z z>epdb5Bsd!4f=n>O;{D1vr;ff!f415U&+E;X48gL|Du!JRZ>^iuSfIX;A9+1C96sq zKu8U6reEk*ruQJLs|epjunJc4hHe)U6y=xg>BpJ-;KcJ#p1!H5b0L(a_%1L1EiaQ8 z1SKn>?)!O4dS+K(=NJCEHq}1dVYp>u-|M%zBKTPT*mT`WGm^_PWKFInr=lP|q&-ki z0GmNqU5DjcF)eT<$9tAMS?w|bKc+Zo1|VuXS|O3v6N+uK8RXhuq>B;zMo>0i+P5Bk z1FkGz9xtKFb?|opG_kRyD$*D~SVdo-9*;y1gyYInS20yzt1IcOo4pvj4%gwXmL`vh zlt~cJNustmdtdUrF#OVdR2<Yu83mp}c}?%mmXcVM1Zb|^Q1(z60+!tK&5@g&GuUV% zF!HSeAJeG7JEEgyL`>zOk-Lk$dMEFU&U+_y9Yr>!Y{;03U4zNP__%yfBeNAr{&U8- zj;Zr2<Ss%?2r_}iCd8A5TgE(z>cSvZk-;y!wS}mwh&%@)wK?yZTI}u7kISLHQhHmI z7ZVGhz9&Z~x*hc97lxbW-M7x^sjD1mVA%v(e?>S5X$IOwv^xmuLS<xIwkGz<7s?MF zS+q49Z0Iv~hJy-N8d4`B^<rf8<@K~>!q1tdT`KL*f4g24Uu>I-FP7DT>e}VJHUIpR z<_>hy*i0)5Dy+=;34^3GzsWTuKncntt&tL;lzky0U+3-F$$n*D@9&#szvF;aJ|m2U zeu&Q`tiHyx5WJVqw{WwHH~B+Rx2({Vj9-OpEBdrj{TdBp`>3IHAY0$s`*)n+h26vy zv&WtJ32-T_T)h8JdEC(Rh;qgqSz1pS>9Oo()b%TByfXCjCO5<#xv<T8{bbJv;ZEI+ z|G`EZ!-&hzdk(gEOV)8(d*Uev;@G^t7%*#%?3{wXu?UL184)`I1FQ)mI(!<{MLe`E zHM`g_*qPTTP>%hmd53_Z)yBw+d)^m81rSHLS8V%(yx$>Nv2g_I7Y;i|n?v@RD5B|f zGCGd(QS5i|#SrIE)<QyE6!wDpFG2EcM#<AStOziY>)ld5omR8>eaVvrZatS|*{j|u z{IU2d+%e!kkE1h;cN(|NV)z@*nSDq1vC~mV6$NTsWc!B#WqWoRUL`ZMAI<tW32Jy@ zeXfLB26<utq`4}moighF3PvLNikiw!T}5&*l>z^7w^z8(UsD_+q=@5R6McSN-^okV zo|SjTqFZB_?|c270+2m+Pf*o#qBajtXWN6}>N|QrNXMAYs)n_dL6eI8QYX>9udhd{ z3mRxBQSzlF5Zo^P?Vmm!FgmQkZci~}F%O1g@xnlEJh}hvW!VqCC(@l5;Dl_uy1H(p z&(6LK?#yk9v-KoNrZGlrqqz|IsSXa314%;~wo2ftQYAZa#AzDz)QU6lq$};cu8^tW z$hqa0CZDBmD+(X|k*W-^d~A7qy4iU{j8T_K#&3mTEnUkC*mGTpaLpwdQCicb#xElZ zRr|_M#~A`_G*rpddvlnQe25;!gEe&}<%9=c`)pZX1iGBGpVXc>eOroQFTgynvDzWx zXo$rK`4g^>68@hOfe0H}B4i<IK44cGrGc8u3l-Gw>_M_18`T!8XV;6?TDzKn28v@; zNX~Ia&_FZAY8Z5={BdaGyF*#q40YqPnd@uP-F#)tm>1B7sKH$Fl<`xVP^_L#n-6Dq zAb@||zr40&%UBdbE<$g+l5gFYI<CH9gYM-po*!WSP%>#pB(VMpH@cD4&8!=8=Q@At zt}z;(Zqf%E6aA+Kqv-Dh4HVmg?DrP&>Y^>a{ng5-MPjwR9RV+!m3<EW%KAe5xjc-* zSJMgnBT{S7myLH8%3pFH8+UdtPr#TG#%F{VD5IWKJ*A|3jW$>~!T!lmqFG(53_3t# zLdg_I-RhupWep-D*PN1`JD5$%06@KJS3@GE9dd;Uk5w-1FfKZj2<Dg=@%6~(M&mBn zjvC;8VDYxz`<eZ*`*h>O50QwoHhO%J_g>t6^1-R2j7_`Ulmn(PL6A)R7g;(YH87)> z$(`)bI!=m`0`yeCNUeo6OlmB&^l(_QW>Q?Ie%!}=$hKE@#4)DL55c&fB#~C~2eN_? zxP``5iEDtf6*Xh>dLO68K(1-rWoO!XlNYHR2c198TPmnDr<Ply+nFIj=QKlYAk=xz zKckTMWVa#XW3YUv2O{CL^Mkql`jvn)k&QNUxMZsJ6u+h!0VN$X`VZaehO}vU=Ky-^ ziV>{VUq#DHfe<FIja(_2dS*o@aSe8+Q!5mnYvsr61{p-?Kja~3b8T5CklpvoN4A4q z5<c>A88mtAv|xo~C)xL^RI@<wUds@rKVW@{X!t@?dGIB*<9o`nLMjM0IvnEYd!GX? zwmVXA$g2wxDv)Qy!DSYK4%9Gl_SmmB#2!hknDi~ft9thAb`u?#>kg*Ilt*xaV(Ns? z27i*p(C0d(@|CRpuruBi1?v}hHr7_{_$m|WCWacRKyCF#8m)qTBa$#>i>GWfrO(L* zO$>Sb%V7Furo2-wH!m2QuGfWibGD<d&=wr*cc*^N_I~`c#i)wXmbZ^XZ%n$i9=a%( z($$<LSfWvGUec<DykCeq<|%Saj9JR-4A!k)Q7|m52T2B%b|VJep%a8^Joj8u{YcGr z<eGa{t1LoIbx-XEC=;OJ=Xi{rWc?otGCnNR2UCIhP-HZWMIrhH6JNV{qpI6dF{jCX zj00iCC21i63c1hhiJ5qE<qrfbjar}$;=3KhTUQf6g-TW<o2r2mE>?%#wk54QyE<SO zqDrxe8F>=lJ25osMWsJkYVfcizW1_9Eofb~{c#kx4vwq;H3s(&DmoXp@7OJ>*L--1 zk7D=)P0X=7v!qG0*QKk8llvqMJ#FiH#MrXzLJ-l%kX+O_8mcHL0)-T5mZm7bI#)fC zUcZseqJ;gwbGVicM#vbdKU-k&M$x-{HY2HP|0<e2*1cnZK<D(~dCO#dbr23|P)?R1 zO&0?Tb>Wj-xHBn|QzJP}DJ?`7VZN*Y(eg{Xk<<5`udAx397j@NPyo&KKWR#!q`(vN z+wFG%_xS~oNbQCPpUcMlm#EsPUUILC(ysu0CjvT5;%J#91W0``#3g8^&yK^Xgo0rN z2|<Gy&_~xD$`6SLXyRMv^B6Z#fageuaWo;YXEUJZ-r#~@-4X(8vduT3&%YF^;v5MY znlXVn(`N0QYux&a3&1x$GW$;v=1Sgh{~&)_+}Gtn0Kt?&ollzOK|ZnK+58@}7mwCb zIK;*5<<pOmQK$<?AqM9CSsd%RQffm+g;?lM-Utz5F{u(oMZ&Wox`N<`vZT@+v*&e! z+ZnziIAN9T@VsO-Xyw=OHq4C#%mo&Kl#QMm-5Wt1y`Q7hXv1&JLY7RUyb3o=-wbCo zrX|;_A7x<}(vgQ;MSr?rC7Dd=Vzx|^Jr`etF-UGw83Z!2NN>XNq@j3z>|He$HE%#F zxi5QB@=7Lc2P0_~rf|Hb`{?q-4e1<U9tiQxkVxnlg5NM9q-kR4y6bZvpeb<H(aM&r ziB6x*SWLB1@3c6hzDWCw1;_w8##t>)2i5FK${|<kepRb+_+Kj3{|+d)TISGxs3SMN zJauf$+2GtAPJEJ_=8kDhbh8Ym&vwr3{`!6KheKB)in!xcVGMs@_~M_h8o6{thG((= z!rtut>i?@Jq_9@$9ulEZu~AEmC9ug=g+RauAADY@CPF)YH`3NSeY^~VkG$k44Il_r zG0*0Jf(?lJ%x`+3Vc%HF-@UR*n}!1aYjIdZg=OVcHEv}>qUxypGnK`;>d>UmEFn0= zsZ||EsFD?{*1UFDf=#1TN3m-g5|~B+Z4#!V50wTUP7Ody6E2R-Ebjvgb93z~z*sS6 z7!IXoxN%kECsA|(MeINz5=xR<M%|~73&&j<?6YYWWFeW2J}Xd5CK%Sv!QarbHl>Vf zVa>>~`HLyvjAFlD$+m~qBvS>y@A7!b={jC@3*I|Azx9lwDK~RFP)6WG-pIkkWoFCy zr}Zl}8lPbNkhls!y?<z}dZqYzi2Br%y%T{7zj;F4vyF;ant$o){o<ZlV2JmQs{XQ@ zGdNTDoSI7@{v!75K07<Cry4kXP%fSH^Z#Z6=(I{mC^sEY!!Ht$h)sWs=s8sxVprcU zde66{pov=oa1;PvY;%=L8VEqfs8D%uqE8GHL$+Hz<_7@uR399m`Gtm>E0iM}M4lqi zL1HSt;7%o0ij9HyuxGKkB5f~9{eW*%FkB>~uC9W#mF|{u5(KmJ7Mc2>4+Dg;86r!Y z<E_k2B={1|Y3m2`T)aV4R}_bJPK}k+2;bgG`{C$PLq*_K%pZU@{A`X|_ZNQPc@Ir3 zK!sD(Ux`9A`Omm>*wP6Kx_B(T*0^z52L7O@@Jkc&pJeE>lz3Q0NdHa8sAkgAknne{ zf&u~MH7=ee^<mc=5!dE~eX~g|Cu(&T8q5V;F*b$Ky|KM+k=&|kI6pvg40H)1uo(WM zoc!6=kee(3ZDEJ76pT_`l_p9?uNmTo5DR!^ZYE1Vc|EH>%Bp@uf`fpWJ^-_n%&@!8 ze>-nq%uyXiDBVczDpPftn<`4q_z{U#82z;(N#*ADGxATK2wS4WLh;}YVGhc%>;Eyv zd<$li)cMvzf9as)9U|nc^u$(;TfE{Hs0NS;dnEj}_VFzhGW7=az)26Myrv}N=^AYv z+WRo_T6S_jj%c4ID!1BTN5ecc5o<b?87i!X&>b*s+oWPxx-|y;7*|_ErYyVV-tDnM zC}kvcr61icnweMfu)v%KTnT&!p@qy6v;GB0wHI0^tzFcxh^LhV37pw-XG92Wxh|RB zA>B)rcs{_*MY858wyWeAiSaop-aQs>zI7Bq6n}$^EgFD2(#;Y4<j%qd=BmfBt*VNK zMvWM;ji7Fjra=-VjGro}WHIM)o7W@5^uC2^@6Djz=XseF8Az3UGLd;tMc$voX-~`F z%<b#fwOJz^WmXdizw;^UrzpV>)y}(c+-lg_K!WeM@@6H+-U?puS;60*HG!_wp=5<I zdL-PH&Jd_0J9SZYSUk-jP!8vx&e&c1@7TiNTlWUL4@qc|5CBVHJIGj)6=mDP$xtt2 zX5iXJxnkeK$eHPQzrib!0!CfGYVY!K4=5@FbIC!mQ;wk$nFT?<VxY2NER52v+yW45 zSC-gsl<9QnFJuZ0;khRQ%9y;r;WoA!Um8!*{n12~WkdFYNt94B80{moyB<QY<Rhkk zV)SdHii!ck?t_-#f{OOfAyvkUbgq}*@`!icZ|8`Ffm8`Sx-$h4LHfq+OLFE!<DH;d zbQV<n!BT1RM;ZhM4CVz4G&)wrK^)c^c6$D5)q`03FE6Ju{#`CUl5VOdJ{e*U9uBdI zDRFImWeY2l?|7+7oG`2?04@-G5ViRk{Vr7l`^Eelfw<z?{=#ii*+*>Y4lz!`g|YAZ zZ`k!!i4f(<lT2PMoq<jHPR(*#^D~+@E9?oWP1XJOTvH{UQx0!jiBQvc#kLSpQc-Sn z75m!~tU~^XN*s=xEpy68c>iC2JQ%E1n<d3x?yN<t2hR~&&5u)qwk36k`$_)i5Q}9d z^7t;_A=eU=e)wv&80(2>-95Ec=B1EQI;%QV3wB_Xt;fb+#a=V{ji<tudD{vGEM5(k z#qKl>F5tNWenWZi<(YN8MVHc5fBit_ys91DE|uxyAJBt%te|4O!_PK&Try@~<C>5= zVqN+t9zi57SoDEOlDa(<k_if4L}p2X_xel-s^QM5(jm+kq})zn))P=_mbv&b(gYQV z@^UowG{94$O<JivtUKSyPjW2nRo=$3ZdpEb^0Tn}V%I4=xj0sB8)E+V<$TW)0j%j8 zllViYLhCOO-~A}cOWvIqM&H9ENj$ve#;8L%4uJo&ucJ}#5bht5Y-tn``a)La;C!F^ z#l_oAMz@1F2=c)jquhdp4v&uLvve`()xFX@!oWb6hvP(E*Vli~qLdn~iDFs^n$g?} zHMoukKvNq_D4X9VD`#M!g6mbZBhQJ>tDAH<L_FgNk$a^HjVeiEIkF7@Ot~bK6WL%4 zSNteJ6@~|J03N~AkAV#TIF?LVfnXMgFbLKXP1bBy!Ly)FB*l!7d62QPVbi}{GVQ8` z^Rp>O4307?^VM!PW3q#?)b0QX3}NcVOP_-(Mq5D`NTRX5(I|Jd4a+I|1$_O~j@l9> z&fzE_1sQ~GeP1-xuMIuuvw0258vdiqfLwqiq*56lHO#2e2$NR0#2jX=Bxrapq_e7& zb7~&0dr~&XsrxNAyw6w&mJ;u1;D!Dcm>X;pm9X0Nq4(T{=rA}CrR^!6dFI7p-Ha9m zG78Dj22fNkR>ziH%oR`KCzn=@^#bcxl1N8AbazjkRRUR}BZ>QF-we`}f4$uzcFRIt zsE80f)c$$Ce&b9w3;vY(*!+W|rzfe0QZQ91a{%IbFLjMP@$>xRRrG6R?ClLv0p1-F zIT#6DR1%r3<Lix4`<q_zExP{i?T^;qpjqB7jR{^#$NIfXu}t@6E@F1|GcK$W4C%Q9 z)S;R4hdeCl3t$3X9VWU%ZB`4Im~=5D%rquwO)gbGqms_;&YS%=p4UG4<y!(T5Ny}$ zuv@#{s-af9m@jEH9DK(;JUDeJVbU<=8&ppWCY<?DJ=kITny9EXhGmWN!P9pS!)=Qi zAXE-NlY3{t6OGoWH2!fXsmW>RvN9>(8WRlNQ$eh5Y5Hm8n$sotO_qq19EG(VR=2z| zr)j8b8oM9ZRD0Mp#|aw$iL)=SD|Fe$<k~0NB)_68HAdw5H_@;Vn&iAbRuN3&7Mkz9 zsrh@)s=5781OC#n^NQo`^EuE+UcQY%LZ``S547`NvL|r(rfo=p@2=P=u-_K}Rvn=P ze+=0r7=x5CA@R|%&7TS4vG|s;tB`W9BGQM6U=uonCN9J3AJR5Yz!!q**c%0zN=8xK z5|rvg3d54J;d=MX%H^6FeRp+Gc3U%^RsB`%wQ-SYrVC!yY3JPYajN?*aVKXFYNku_ zqrg0q1DXLbrFI9j5gL>eaTGlfy|g14JZzzY0;ErM8vpE5wLf+S@Vr+iR5Onl@l|*5 z&zZ&oQL|<mGE+F*g?_C=y}#e2yB!0s_Y*uVSTUG=SGMmC5uy3sR<OWsci-DUzsECw z%0IOC7<aTE_*A@WPT)b%cEs>hC8c0*x|e+`R~&Qm*U4+}3{P-MoN_-vM3$bNhe)L7 zkjxd+c0ci=7P#=3)Z%esim-}pboBP}eBlnMEMalR#o&4wopZqGdlZ8eH+^hX&uUf> z_*Nfz{{20ts>S=K%G>dfVCs~NB2*ZZu$l=X3_voa0$3zBq}C_7>DLjuoMrc=2O%9G zAGz|<j7*am$r}iI+G$0QeF7e&wDe6$O=r*+P>3|%lx(b0E%;Jdp<AcjNPMX)Vr0s2 zxnIvipEu)pj%Xocmo*dW#Zyk!s8NsCs61F0O8rq{w_Yvuv)m7jWhy>Kh}yi>ehQQ( z30ad-Eqo-cN|pq@$o+Q>YFh`k4z!XeTs_5@O)wf$kj$#*7OTB;rre2gDlbCp2d1)2 z?H!dTZ5=u>=}z_-DryxmwUm~7ys_}L!CmH(?MQ~M`=DEPN~ZCzepdTMSzY^&O7^xo zhnA-rj=}7<EA1C5i398lY4?qm<7y5|75pj0s!As5^-yIS>Rf@TFbo5*B7({So+>#5 z@@2&@ceJ8>OD0;A@F6MaAg)d{W>B3ZkEi&~pkMn9q3SEU$6jjP>J2wj#nwMKEI-|{ zx$I-nGX{ks&p@oWkyJ1~dm82iy|8j!d7<#y2|Ska+qLx~0;2EMh5xpy!KMHS?KgV1 zK5sa`YPX)^HvW{AK`90_dz=kpev{iioq7NMX_TVK(1<5if$5?=JpaKBCMbmK)tGXG zyXPzNL;czbqdE9G6eq0bSnOGA!cZ~cCO@Dc@8=k@vf|L4<IqMzOTiZNTdPi2ZjOL) z4gE1^=okgaL6_w!NT>g_;^nfteEJzpYce<-^nHHmr{qCtVt#5WI<OBZJBg=nr1mh? zrE~X?)qbHXO3KT4soS#-05D2+4R5kbNmNINM*!9UO+7|E37WlZX=@J7j&Tg6%B(iQ zd41PkT8!q+IRHo#6f%EGIwyOcHhb3@9Re3-v|D2N+h<yby}}o@@?XhMGyJUEXBi*n zLp~VXpyx#wh%^I_L=0Ou3EH|5Q0T>^l|XcUJnFcNB5-5{j2ZaZls#T;iQ;wj6x?U+ z4Pt6hiR`C}ucul}ol#S@2((~idhfNj*j=lC+hjo1yjk102+d~M&!>6&XQYcFG2F|` zVZq{>O_TjX8vV1H+4mNFA2~MK9@RHmZ3PJ~6Yq%%T+>AMF&8vcOkJHsK$9h+%yj(b zJsA=U>WRarO}G!nhpdY(m$3iZzg|+uGB>$6(9sy}Nt&Xdd-zxrws2Xsmb?V{KUI0I zr^n&?ef{bET-e$0w$v{-;qe!@lHM@uUD;R-K~wfn^80v~8b7ObR8+@BD6Y;~g9Qmm zGrv@Y3i<<ymj*fjE0wt){%>2%W^ztr@a8L?@_P;*2QI>s@UuualK<ZOf$smCf@doc zWlg)J{IV%o>?3k5v?ku%B?FiDhTU^)dtMLx_FV=}{AQ4lnxIZ5=_h1*9JoEg0=FE4 z*l(hOAuL>0^YpH6lQOWN|7Fvt@XO{yAA6(0yfe<<yRf^>xBF_X_j{3Q%%jD=`7SQy z4-TXVu0^S8*dY|FaJRYMHFjn4yQcRLJUniiFUYV9k`WbX5rDPmw1M*8B`VBxIHwns zo&2Z`rMA{At#ty2VrA{$_zw<enUJ{t?efffnYft{_`G5Gq)aR}OR4gvc$540ykj#f z(yT~tb?zn<yi0;1$j|V;ix04mr+e9|%T6xKwh!N(5ajd55$A(To=w!iha$peZr2lU zg74Uno3!H9$GIhHNa9p}O|UJm9AcASLqDmTL#Qix!;yvyu0OT%&vv`1R_=UasW9-x zp^_BNE0Jl-a>>S}uq%}^TiZobz~$^8Gf^*JT^Sqm90I3wo(>oU!#;im>X8AYkfd0! zURXZSCt4sQAp9?0FKYt*`xtunNOavs%xDuOO0i7Tn!}ZjCi-GW$0Tp_+bk;e*?cSP zeP5ZYC=C6#ppE|cOQzVrTyJp@aDJjPa&4F_!&FgKH#(CS{mJJ9vFa!HlI>lto6YpK zJe)Qfq?F(X{~~ianHT;b^}{U;Hq(H|Jj5K;)#HQ15|(!Yj9V|hF1NhS<N=Q@(;Knf zCrV9C$-@l{n3h`)O^p+WUZogyHB3vsz4jkJAv})1V<BH)QiznJ(q!cm9kuv1;mAl@ zWcR{(YXG3LYrtmo@BP))tA=I8>ee5Oj?Kg#8T8|7FQtvi@r|L#BLb%<Edou!Rh>zJ zD4!cw5df*eUcFXM1p@mRg>2)pJl}>me8Vs?>0N1eiW<a3skpZE5SX|Mfu4e6&lAL6 z+giT5fzfpA#<C4UL+?ha!-I@%)!w`L5)o={@(<ZX|KR1@v}7lS((4ONA%Y%nhWcd& z_&|h#9JKQYoZ9v>=Bv2yB823oh9>Jpii^w3CTvy<AQz-^HPNByf3rn4et}LoOxa{T zpcS6cO}(_!^8YWUzJejnb>|i>R=l`-af-VX9o$_D6nA$m?oudT+}+)^*kFah2X}YM zH$8iwbMHTxcakT`T3JbU)WbjKjNFcVF*GuAL_)oTHfiFNQBNt{XXX<4qz!}h;_?Gs zElINqXOmI+o`S``j*B2IHV*W%QpRn%#jE#xB*#nh;DI~hQ{{ru)Ol9b{IL2Ba*Iw| z$p^V*+qRUxD?q{Ni>Nb>%bn<cAZ|_a5fg0?A`EAFS31vR?5=r{W~i9AlUI<2dfK*o zTCDA*yaudj2ES?2WV%3Nm-@wU9($B2c0t}1inbFefv3;j4h2J0pOfq8BbzD38SGaH z`7dl)v`Gp1)vxC^Z?jR(HZB!HcfU>VUddj1{V$`99*D4MbBxJeHkt2!q6dr)$CBX% zmRZUR%d&1;ko#4$CXnG#U8{aVZ~J+?M4-QBvC}bb$;+{z(MS>Tm5TIHXiWr7T;lEE z0B#&}5ISUPp@bYVzeix%<d6u(Z6K|yT$05O;&*ok4Jfd#C==z$Tps3yoD>u&q!vZ$ zeyni^7^5?2AO(tDH`{mY_mF}G_$P34U4k_hsf7Ax#e<&E)^w99VW_Di>%eyX^cKIH zQyG;xjwOZ^%uNO?fal9~3x*F{B$|TlQ-q3o)<r`_npzrm=B*R<c2;%GnyXJ0gTAKK z>kO`vZ|LQg{8~~}ghEGn18(oA>n_L_`1vdVZmyu}TOzxqD>}P<F#2+DH;HD5Sy_}q zMnipWzW%rk6dj76vT<qa;L+Z%=5lyCP(BK4{ZW}3v!;r<)t!lp9)0&9FKlvm{O6J% z2gT^rH%geTJvP1EHIVHZf_1Zt)xXWUCSReVRL4UNKI9E8fJ(z`M>-9m_?Umy+72{9 z84+Ieaox&uv@XO{Hy)x$gAVbwW_AaWgwI;<d8vi-TXw!)F_pMtbGEne9S$mY=(YHF zy@IOVBm}PBm))A<>06&<PGa;2huCs1I3lM=%3-wW9)#(}inmr&Tqv<OU_|5QpT63$ zR%G;MiUqh<v&Yz0I6k|*3PBc$U{NW+uy$SqzfSbLMB7PI2MnO{{GR05utl}4=Mhxy zskYuV8vn0Yinp15b56H9!X#s2(rIfwA{w*AK`~Wk1~tS5y9|i##rCPAS|>eYfWMCR za<!b6!=WD&o;9Kj!v)HM96S3nejmEu1Fp}(7J}Vc`)%o(o1WeqX{OteXC}ARyF2`~ zMc}-3Hk*=o<#(GJj8A-k6U=u{2+9Jp*7n9QtIZLegPh+}VWWNv6xAZKDh3ve6P`pt z#>A2~4(bYQ<;7D|HOFRzQpQkIhbS&kngLVNDzKNH^Gd%+Txvvv?aRM@k^ZoXpW|KT z{6*f?NM2c+3yl*Cwn(dBQ#DUt_Z1el+5eTlWB<(O#AoBV8}bW>uFGp`T8?WVGN*0q z+}d^(w{dq~%+wJhI+GqUnyd+`b{@)!kHhEw>XbQo3<L}O^NiBLt1d$RYR)ff6P_{M zn2A$kl!W|VH~Zw-{Z%tLEd5($-K4_Uql&rWcGwC$9S7rTCY#~5k0GqfqWc(?+(}fc zy^J}5P|mnhCW~#D`(OqrCbtv7ic-&Ox|=IgGtItI!|-L(_m4nfAu~!SDLMspP0+#I zbgffOr=<XCcf5s6#i-U%z^HST-2kE9?Og7PRe_YwWMvz7RF{`jY<bfiw=EJ#FKZU> zoHYIQ0=~3-{msQqljIdC^rE$#>iofPept2iiObG=;ZEc_t4hpyJ|<h81cj38j}Y)& znbpi|aLw($Zab+E4b^22RQfI2uJ0S3-tOvSWk0zj)!KU~0MYi--c0|8!k=5x(Sm4c z&SZPWM&oEFR&}Tq%^)@Os%D|gJ6IXVDadRv9beo`M{xd6yUu+^q4jvNjTq6&Xrody z=*<RR8?_SdmEfW|+rvkfD)+3?l1qBnz|>H{?QVRbDzUE|tfl_wZ+be+EA@x?7XRgT zkbt-jv?Cr%#|)?$Bl0H{rNbxxaeDx4n&mjJgx8IP`7OKimh`R^&CSA7X8ZYc>)wF~ z>6I>v-GUra*X7^-a8z~QZBd$GeMyct@}+S_ECI*xl+e9C0$>34oT$cB_}l-WwrLzp z#?atrNecOJfAFS40Poe6%)Sak&#ejv3x(`-{1f(Mbw;QOX=8ciCe5vn|KYE|nAxG7 z3B7Ff%i`(uuK_nBWX(NK6+Ml8f5bqb_Q|v7U6Q+aqd)c8+HS!d&;-0OQ+Gj|v}rWc z{!pq~7Cgp)W&*bNDSfxkeBZx+hl*g(_g2>ovS95^*92tiDN9(qmtuoscyrtg9yNT@ zZ*%!TTJ2I=fy<Q2{MMLtB8GH0sUO^Se=D<tNwuTOn|&=`(VsCu<_m$W;5af6EV^Le z>p)<>9!@h3o{=vmO5S-xJ3kawOwH9;(TVglz4ZM-ch4`fR7(j!So8;>x9oV8=c{cB zufxwG=EaVMo?C}bj~?lU{_MV7@*|GYBrsRI?MY{nRV0N!Ywvfzrgh%Ca^svqbTyq{ z0NkHqx6Gh~38aXc*m<H<_(kFIZ2=D0Y}bBvuy><MxpjMf&!@lS_Lt>tO@B|PbQabR zduT_<ZtO%hKMZG9dc67Dc<sV}IG`S*MDyd0w43QJ$!&Bq9bW0bhfZ-kP&U$ns4^W| z&;nI;&xW1eVNh-KhQNf+lO3SwvLoW`#*B}71;%)&i||><v~YrQnrgJ?qAYCpIW8JO z+<FvA1ybuw#XSNS+d^iLmy#gntZuErYhG$lJF3`q!(Q>jhtek%S_+@+hINQXL$o_T zTOCK^J$yK3)IjXd^}^G&1#7*<vwDS!yXCzmfvS>N=667xPC7t*T3ioIR*Xsx)JB`k zG5ujAHK*u@dCw*zT|3hslLowfQ=%}!=Jp{Vw()ney9s_t$oUGjsm?MH99Z88bD^>W z!Bp|W_V?>Ptj4lsnLf4p^*5aBC_)r64P~HF2l+rbz!en=4gS>(UteFkMLBPlr^J_| z6xZMta>-dQ&s~K_pLtPLxZtqg3cNp3pbZz>JC-lgf;4cZ!vE*gEducU+HatkhaQEj zCGje%qT}m?>BaDoi%ek)t1q|>`D=T-%YdX@o9edlv$lN}50|y@k*aXAfEiN1E3A&A z@(SP2X;lNIKz7=zUS<4oQCy<a_xUae<BB5YE)Q+#Bz0VDp~xoH)Y}n!YA%O;7~5W} zi7n_-n@od`3nM8G61vVCki)NQbMe-m_`P=r%NDs!;iOoi?Xb_4%>G7=>1-y!22Mjb zt@r*lleyE#UM$2+8m&$bZXa0r{}k`5bn@&z_)MNC&|iK^92Ki~8h%UklP0d#-b{Il z!?&lFRaNWS4l`#1>i9fuX?*WP_4LLl!{n9%v?WTJQJz~~1&}A?-J__?$=;dS4Hej& z^q$e`xgV-#wwSeR#7Y*ux93(Uk<Sz6@m_qdca`G-x~fJy2G!x{AOorAcNsoPYk8E| z`R!n4)ymhdgh>$@sG%at=|~GW`FK|qH-`#Msv~?_e|pEe8*eODiakx;os@!7rhFvY zKqBhwyZMOIe7amxWpzx;9Yfm4kE?(j8q@eu6b1FF#ORiFz}|6>iKxjeQek(=aT`X| zlm-fZfoBQ4`@Bc;D2usmOcM6uBu|0#zA+)fDleKD!M!n0w*|D=)j7vqvtb2zpHUB( z->A%bfns9dxn0CBDkSDVpu$VX?1im`FTu8@BRS`}_@R&`yrL*<5tr>f%#_ug^4P7Q z+Y;HE2*gkjWKL2Yh5GnPdf(LAU@>jjal05$yS{E1U^vk~YVr2MS_#=Evi65jF;M)y zY2y;b>)?j6p9@_$3EKL!q%xPFVk;VW%Y?P7Z=&E`l9VPbWm3dGqoqTw>f_S?I2%Y~ zso(=XpAt#V_nN4F{L$<dZi$7aU`|TmySn)03D%wyVCvr9*N)da&?)3Bx<t7uP7>zm zY$xeg&-C|GLoqRCXs!GAw^A}I4iV7fb#PNz2bZH4$K!(R>kcl}kG!(186|GawbaU< zo4wE-$JHImRnIxFG;7!-jdkF|l3e>G6Hou!1+C2a(|lJ-{#WkDeelbcD!KK!GHfsO z8!|LB43R5#pz1G%BW(9apDD3?PP1v@ZqjZNA`-#Y!_wHaCZk04<@whle>!?G*-Wky zIlJ>G+>Vk*Oi)L|&|dDRh2k9EF{~nIguqrDBo*+XoUNE#G9;LuZwGtlE?iBH&FRy; zHu$`e>Uk_>FFLNbac6XAKykV@yZuB4nJ>5%^kUWzVYfn6CY1b2^tGc*fpe?>aHl@m z>@&$=V-jTiHaAgaI)cl%=VL`p7A4bGq{!Ig<2;_w{Go$8K7(t50XNr{&d@O^R@WD~ zS&BDHbW%A-i`qoP@vw0iW(t5tpBh(>J+2!tl3=&dxYS&|W^-(`GV$ntM+5^?uhY~U z4+(YJMlwzkm^+d>P?+j2n>%qt)KyfkOql=+6a>5eLhH;1%g$`yJAM71JldF~?_78x zheXGrKb8fCii7Spo4QXOe8EJ`Uxtub8@9({q<T!6_>X>idgI2@Q!E(0`gjWW5Q>|A zwdbVnYM~_NO8B55B@uy0K^f)g;8s-7dHw&$Zb5iMba+ms*sLDkc#K|E%*-KKyBEkc zahGX(X9vdKM*B5>fz!r0U;pIU#`NK>ShN8_CGV6_m&xbwUyrNkw#8RFKN^f2P}RtF zi4A$yurXqSIYs>;E2i6JV+*By?$6wGE&q@TxK|qZoHn_GV|iAvG{<iZIZKXTKc0T9 zdbvDR3Yswz--vzU_U))Uu3S+3*vx1zh({#ckm_kFXAuQC229vjG_uR|4R41MvL62X zZ1%F!pe&RuWaGSuar{OD*5R(Op0`-Zq=;Af0#Duqf-*xTiD~jw&&<j_2^7XFT+^bx z`uQ)7a|S5=)0*lAL)B=i%bC~3J#JjCmD5oAWCP`629rUx<uxZHC*Oj(KC$DKr}D0+ znQ1$)DZ1|dU6p27Mow>9Idz_D6r3%hF;(8e2m&Zh?)(wY@JmUprSd0_>LJF81i~>d zXsc^|S%=!5r<)K|Ea{*EUi<STKPym2$=aR0Lw%QCrX843z;<a5_WR+83cM=SvP03B z+UCdzA{J))Jbw)LkA-_$5Fl2g8m**p?Uomce%3;5Kd#9<E&I!Lntb0D3R{x%=v;QN zDa*PVqTNAB_{%I08GJ0##-F<uzb%<Z$jE-cokhSN)Yx@6Z6YVXH{JGI!STlJgVe^G z!XpXst-so@md&<^Qlk%2Inwu6|Gyu^aY62lde44h$fZ3!I<gjQ^P4%f+f9)%)X(+3 z0_e57mQ8zQ9Gi7A)$TAw{Mjk~Op?VKbRVIamReja8$erpipV6#8Qx7069QD_Pjr|5 z2-}P$Gj-PU=Ksv@t~o7uEw658;Saf5Y)bafi*T}b?%xtiCgT6F_OWVf^f4J64+Di( zw}MPCD1Ju%O_&9zem0rmG$V65*^uNJvCCRK`-Y=aNp`YYo54duwMJ>eoXhfaQmF)S z>cab+4R2tx9S(y-M^61KXyqg(dhf|!n0Kh9K8&6le0BUAv3<y01Tq;=MsYU>{SjK0 zdd?04cH4cP48*EXGuz|t+<_@BZ~)~*eLxCTVpO+Kp>$dCS5V87Imr8M+K$nF*woLU z6%`?=jRUU?dw8dh_)x8XCyp{?{4kx*<+8P9P_gHZpOHWWdNYVEPp0<$t(f0Td5o~9 z-=@sc3)Q}BEuDGh(n)>niA$r6OUEe;qI<I|Y)-;Zk&4_P%{O9_)*D=?L!a!+cHrft zW@@usAe8Kk&Yf{wR-O|(XyRRa5%=@pq5DdGvh6ScyQ(!<<~I$WCk+WgAs<qT>XVz8 zskoY2vfrVcQN6om>A3-LXWDm<gEuh!2rP5sPi?o@%8q3$IUU~whAbtR&11}u(576M zx%^WnRq5;Xzozch2Yf(~OfaYF7fPS3p=i90jL6>56Fahi7pERvPmG#_3&gLVJ7e}f zuVIIOc%We>KMFdd55?|sp$^=sySd85$ZylR>(_mZt=2$aCSCJBu4;DPm7NB-wBY}g zV`&@w&aC%U%h0PxZtjNdOK_)un{%w-^x8Pt`rU^-j=7&hf#I=oGy<1;+u+wf2a!1L zYm@tWTyesrT^`>+q(gzMfUfX%UE&$lz#v63-!Jdo>L{R61ke)|-oF!hMM%0k38~Tc zaVg1;GMG&H@tZi7zCmSfAJlK-&<uTtX6^l`1C(vIxo{3t0L=uNFAu8gMKm>Y>!FAO z6ai)rAw!Ca&MEbr_xCjhcF&r^7Cy=}$E$bcsnD&m2hYGHamJa(NjogZc?B=<H=IRY zpB%0n@A^r8zcP*K%#eK{^=-B+;JbyVoK#eeU_=a21TS$5qoOHVZsYa(0e1(R`n24Q zF9L>Z;Sxw?*hGW0Uskka9j?3Mb~FaHsa^=$?)PZDJp1Qia&)nHdzExE&#x-J_yk%t zDApz`W`DiLRjN~oJ@KIyl7QCQwuW+!RD(nFljnEUCulqPd9IUWej0vvGpF=S8Fe=H zP7TXE78=v2=KjNt{yx>*CBn#NZUJ%<r8lu+r3hTVr1>=2|Eh&JBjgAqd_IdvXbiQy zRCPY4-?b*Nh8v_er!3u9sWrUU<dLdY^c}4`>F@S^vqHa6!e!mCvSGiV4$`b`SVW93 zE-hJP@;Eee*)0A(TBtCHDl9mO*_+JVXW&w$>U`LaUL$4ncA!?scaG+M{5yO(e<p2h znx^boBV`PIp^2fKAm`V`nA$#zJ#iX!JUv+W(f(MA8+3=N;MomJ3>~$d2Ll}hL;cAL z3)>SoTy&+6m&PMVttx&B@Y(%w+KdnhbiG5dN!O1Y2t+0tqOFIFiLBJaemY)$%BNB7 z^2|X=qJ*aI`(E9Qdu+X8u`Cvdy;+u~V65kHQrAo(P~`!BXQT6)<aWAl?_^s%E=uFv zOF5>}1BLvtz*#*cmXu?C8~j_za@aM~`{)Z%$Atv9>4KqzS$;J-`S^R)si2r!*Lyt& z53(Nr<Kv@-?l}LJ=%k8kyG#$gxj)>d9W+q-TuD@AB<$4}O4hC`ikeB5NI5$?YKJIn zkzo;udFYuZ!%1gViiFX-3+A>kpwXHYTE(gXpEY&vEK+l%c@lV4*xE0|D4xtQ7Qha* z#M|G~XnzQnhY88d(mX+SEvN#99S8Z*Ck?r;l^|m&C_pp-Sp_5w-s@A3pKO2-v{G1l zIj5mA*A)K@Jp8A>EdqxelXX(?C@;O1%jZ(;w}oO<ORrY^pC$Rvi!I&eHJw*cUHfb2 zb(!|<V?imu6D&<7yXZWri>V9Ymnc~z@1>w(27Y`WICSL|<;x24tJ=@uiP21nPbajS z{yAxE<aeu~*Wq3Txmq;<oo5?csQB@=-D>W4Lvh{gv5#lFN?Sf>!7(KBO9ySN4j(nK zT|tqW;VME2C+g=VQ)#Nam6ftKPCy2|zD|o6D~YsD<#=B3sb9%L!+r~-?8T~qNh78n zl?-sCXYJr&)`X&FvtMaxKsooQs0#HPDz_P5MlTyZib^a@nQpA^=N6qovyFIK0~-+Z ze$MzhW>3shX=JMB@83ewD{lI{Xt&tnP;(3Y9q2h24c3Qo0H;ul{&-3-L&Zr2J?NlR z+MiKYWb#iQUG8Z^<J02{t$ZmOWKnDdhy5~Myt8#^sv>IE8Tq5g-99vD5P*erop*Z+ z^PT^B71i6pCtfaP^%0J!7kAt|m-_3<H@plhR}4g~DtI6=RODgdLGfkqvxL%6nDXs$ z10@5O|CM$ozfWgurm6!f_{dJ)l-clDcG)OOR@nlf+8Q~QnSU?%>T+T=9ougSMsU^> zujxKM;KlTLKj4qW#<BY4l*pU!^EO_OB?>N6L=q9H8fD-Ip$K3^b^H)m1pz=6Ntr-> z`G*W<OX|BoK+b>n&^W%RkY`lnn@T_%M4Ke6to46GsmjmqUzjud{W6HHv`Om`&nwii z`(3ZHRiZLY8!M=YTr6p;3BUUzFZN(=0?Q|_6tGeLM+jx(^-*GEV1mW*=H+_2Lw9We zUBni$_S!?^p;S1D(C^Q6ZVLo_`0~bnypD(j-fkUAIbDr_Q(=y#x9DsO4e_69pPK9+ z$ZX@3-58@mjo2fbR@GSNHda1+vkTu(QU>9Epr6$?_0^r&n^jOtBOL(=L_>((DstP? zcml^}lvh{URTl}5srE@3#bDG4a*+#iw|sdnpIYOVdGE9!OIY=$QKpxp6l|&-0<f`) z{E6A{L96BSN!th1aV72PsKau$t0zO6K1T%HKVAc*wtxbeA6vTrPzcPd*}M{ER3RYA z`6#8inOx7uPn>n>3D`~JifZ|gC9wula%+jA^&-2e08<1KnVVto_BW&Bd{xVdra4J@ z4-*O>@q72$^EGRUDBrnDSy4*^{D(A<GP!*+6mmuSiYKiGg)90PY!bgB8K~w)?8%BM zQVCK32?@62a{99^v+%v<@hN(#4(o9P7Hf>ot=)B*9#{8;_tC83ia+E#Z8`>iP!+j* zBUK|m{7t9T9r{1%tQYdjSLBE?$FMMPs}oq?nR==9%Dtp3wEJnHMpu&09e>HlW@u<= z>LAkO^7e}bzR8!(fRr!}ZvBImkhno1)rhOu9O)QYSCUk_ohDp*4Pj`iQ=h_Ibt}p} znP&Bs>w~A`niiKSz7eB^21|1t9<*sXS&;z2b^3(k%A=(=H2~wm7GJ-m3c1Ho&Vn}6 zh<l0ummdah;AQUipTHa+*W}an`A}E*68JzGFMn8qnK$0e6j681Kd-!jqEErENr6&X zys9_jgN%u_A3&mFKW_2JhfGYDnF1@`wd}Z*%Q`6;TBiP{L2YWO&&9H~FJugg9_K~m zou#cEv&Hlw*;1+gnt`MEg=1BPZY7FYCU{ZM^bmTxw(Z#XKJfM)Rfn|)tx!V9HYF3L zc54WlOXMV~o(qa{e1sW+1&Sw#yKDwYQzn*0js)^kvNTKm={<6%B7#>a&KlOtdAqMY zDSq^&mtowt4+d()Gq=o535+QU`*9z+-fHS9zyWe3)E3|g;n|bJsg?ZI+-}0R7$i0| zS!j17hp|Zta<gU;$pQVuWkA0JakBb`DgI*&rF7ZXH;40I1C<}Ex&6~kh!#yY!c4T` z;Z#IbW+a^YX!6t3)8SI_V})l2cLDjIIzBy8ZKNd}VBg~>N2rKk$9k#HZ=xaFx8?;h zAxnr#CfaGgdzd=E5lY+RCuhey`{ju2UEbaf33pn#ElLYz?I+gofUBTX=p}@m_V?C} zLKui}FhQcm8&bVvu;)CBWF%ES1zBEuKbm{J{C2%F`?)Xgu@~AG8Ro`QQr$SjFlXVs z;yox(=1#Lq6Ysc|DI|-RCHK#lj*?tr703(*zBTc`XBXXJlh`^&>O4&-h>D7m2Q?$f zr^GIFv_Cbq^4n6fOe2~_1gJ826Qm7mBq$lpZEzE%;4*qy<-IReNTYTB^?M80RN2+} zaP!&gvTez1V8muYHd~R1@hev%Kb-%hR^?&pH2$oyAu*S2U2ND*yP^?jB`?yr`DgvC zw^gfGs&n)$u)I}Omdg%%Qm_B#G%??#U`v>`N24N&ZUtOfxtKtiHBh5T&u^!#ji|`^ zl31tBDcN6MyJELYNXVQS)y;ZUlT)%C80nWlXerE9WjyTwYe3$p0f@`_@vbbW8C4ut zLpGT3XuFibKu_{{Swc%;%}N_p$g+p9bn9FBWahl1B$Zr^c!&<7nRPa2MG`Ja#;Cuz z_t@rESJ4|Z4p0+S^Y^=2eAAio`cUZ*<0RhGf@aldtrBhQ757g_MAZP~VdS(~0uZV9 z0YzrigtpkrXd;yYN8BB8+9HFV1j(zKV^U)SbZ6Wb!b!Bh<|Bt#QN0%chvLim3D3Ya z@ds=VgrRX|n0dz)dJ*+<4jG8;yt$ev|M^%SL(HYxBx{|=E1sbK#P$I*g&i1!L@i<e zjBE=KzNCA#mo)Bs{D4pAn0{<tpm)dbtpkEGx$<Rs$a3sQYQ{XPH5q7r{`_mnlr>(^ zAHVEb!iMsTk#w*B*pq-FZ8c4g^sD4oq@>rgo2Oz18rXLGvEt0~gzh5C22Q&L<*=B8 zA{$$Nx#>Se?BGbgt0|jk*Vn|1zOO|Xnqa7OE{>;PY_YZtx-z9e$GU1g_Wq)01~EbI zj{u#y(vZbYL*2@n6x_@u8>EU9>M{zr90nRmy%Zf|SKsWU>~UrVa|0C{8cmGCsrot- zpR!eDhSX!X>=eaWP$hL~WHa8ECW5enpOiFaPg-vTYd~S^fWv4)^}MQs*k716VluOu zemS*CBkNWllh{Uk!SO$lIi<DBL4|wg%?G5?lBgOk^OngeM>)y}#DbzFi*Bi;uWY|& zq)-Y-X};;QO;eucDF9+$;GcJXt>i6Xl{mqjVnGW<s4~5pMy^qHU0sflf&67AzB4ye z+O0Hxa@i2_z8Q@p)31H9yQnvFyHe@{sAfwr6O#PrK|(Bg0tbzUv1*a5^PbQ5zGH(6 zR`UK27$Ux0+GNqLRbKabQ}ps%B>F1#oT8?b8uX0LX)<tSO(H)*5d$*#F#u0IZldr( zw;-I%Uz-#H<#g)JBC8Pg2-V(Z@J*(kYX{JhL(up~7uEUdC{e@H_KjlN&P;49Uy$H{ zh^<UHI5U|24T&=I-te(<kkh2)DVyosGEK~~#!(qZHyzb9S8dp6DQ7qaJ55&Cy9)#^ zyK9n+u0FX~4NwU5CS6!k@6)@BeLs2`rw51E)(|ov&Ohbv0rONWtUArBY}ae0z&!L~ zDzOo?7N(1+vT^ghEw)SysR|1GV^71`=5{JXW!C!TgGfHhG%HiX<w6XLWdX9<H%6(1 zIh$nW)HcPN_(*)f9|5wzTZ_Y+0B@E7ZMH-`*0r)+DksoGUN}C4R$fE0p5@ISKLPnA zB2}Ekn=+Q$6K@XI6vm(3lXBWIZM|}<fz4`iyM`+k3&eJ_-dNtns7}F!yL8HP{1M5x zxsREJ6n4&&`H#t*oLe3%v{@q8b0tbGlXZ0zz1oh8Iu^_CRxA@`z&78R)JWdcY-Ezq zJI|gcOTiCP*RcP*$U7A{pjrO_zH{q#)I?E-Vok?=_wzi%yg<9XNvwSCpR8X-Y(|E@ zhcpEDLr&~_t)GD11_D$vkzWB~oMP<I9GK4T?<<$2kvS!zahcgCywlHfI4t5ww5wdi zN*Wv0<9N3bsjLUW(Rt?9@w4)>8W$t3JVjg{@V;(4Ual)TM)b5Hk_R@hBgVdi;gJvG zK&88CaSEfB8d6n=%Z6^`$2Y0nAbLkKTDFoY9MU11c7+Dq?`8iXbZy{u`>pM2U7#KF zgmz)H)KEr?irz`JKjpEtcZJFz%d8MC+Eb%^QiqPYPzB7=UTjgsxn3)46~6+~#L_5w zZ2r)a${ahP9x|`O&3#xJMyOlS7e;Gs&Pw5UM_jIHIrnvPpi$k9@k2y_eBy$Lt|rj^ z2@+h<{l0lPE+b}@$C68|sM@d&V|gy}&JbBy+{~yF9m+Cr4J*%fR1khSU=ez1OmolH zm3yADD>SFq<*bT!hE@mQ6=9lV%Hozy=Ew!(j?MF<V-Ni>*a<~Bn!nG>G4alht$Fpb zSfgB_CI&BuB4OLY+8qJn1-|FSy_IoMm&JkcC(-{KO6w8H*;>EC_w@}}>Z9=*N4R!Y zh7b#GWAufd?Tn#Um{-brDNUksEWJ%GJB-gM2{A)f4>1p*ld`OJ9IrF_7IB%pJEWoM zGqYL6%@Z!}H@45Ra&_pu4C{P8>u_f>Xjj*)(oMBPCuCt-s6%3cnf8A^rBle{ZtB<H z{6ryV%By6PBDnsIt{N=3uDGp4Zj5*VGA_rn(M;Mn=ax)DzCzrRB|edr8t9+yia505 zkBviBP2D(%S00m|qqM5tYeHx`rC-xXW;eF{@ykz#$4FxmST9L-WGGd>MNwBgWC=}3 zEfYiV$=D!axZ(1+JRi5d*@<qsR<q<xqr2jeXLMyUmEj@{FhRSf9zCxxrY^T|#hE14 zPFiZ&VC~YFHF@$<UTB9+Eiuuu(Se1OqjdUhu|%jSdpwFwuiBl(s?~7L{eY7{JD!d| zWNM`Z)M@?34U%fhZ1P1k2>G%GF10LhJzZD1TXK^UdPo21NT1=9zZ~hj`N_6C43!C6 z^?RS{F{~CZx*l>mE~9u((gzHDSGylFb_F>zOg$uoGP-T2pPf;IcTAymExBWd9AUw5 z8BUx#F(_w8bJs@7NpJ^DXuD9GoVEVq#5WiJK1P_JH8Jvgzy3CXfb+t+!hu4$T!H1w z7lG?8Ti<{Y72NaA`ua2HBl;5Ax7T;0KdI0f+{CogK&3=FQwx)fZyjcJ@|jOD#f-^U zXKO`Dxx&DnfB<?{*6Aetakt>Bb)WMwNTmG;K|X11F8fEE-SFJ8XwHogs-B}V0hH!m zUe>-DjAFLh>eRfCsdm~q**KStBI-Zs*AsW{bXHO$>1iYlC4~IhHBKT2Hk#hVc{|~W zxyF1!L`ptI(h4JgwpdP$-flyD+{Z1k8^Jv(EhmGO!=jVIMp%8|y=3|ltKw){BJK@S zyP=HEd$r%(hq`&?w5Mj~$<8`AvjOIIyM)W7a0O~$*~5im?G`@Os$_<rG4k4731mV` zQ4}8q@gADBu*c+G3gCu(t3sL~GeyiG`jWZ=nf>)2U$w_lGY-`3=B1YP8v#waLxk1y zLNOBK-frK;LY~KZDRzNHN(feKVkOw0V>Wp(GT*oLaR@R6ClAt08wa-(%^pyrF$t-x zSP+jT2r=qC7fy?K@g7hKKc^c8yxum8af7GQx^HM8S~7We!TiC(9QozjUdE3A7?F48 z-DX?B5NAKw6@L7He+wPtFsO6<fX6w+fN9=Y8J=Hb2|a16bko&SZTDAmZkYS0mMe`C zO|l61mnKmlKmOOakTNHmTe(x)wE(lJljY_ORZz2CQHZ_ja=AtY(^kIzIl9^r8+a0L z9bNdL_m{_9xa*pBZo&H_vmUBNqAj&%y`uW}PZrX4_s3QnbM3j^xLcy+V!i5g0#H<# zYa*A=V=_0m(_!U;Jp?d7(USZ_SyF@Of)BC*OGVc3HIjNXI6^Dq&{PxVTa`Fh!!{0M zNiAt(!?)#SeZ3*oTv!W>oa*^N<!cAvzNuPBF)&ZzTcuuu{<>j<=EN#B(Sogqi$TSF zQ(HAkFizP*Th;jYbhdO}8uBd5=NqTyvLJvU902^#n@5dkr<ke;HnmepinwcFL56*w zezC~z#&4jblr8+bD*GwB$VCT*et}DhMBuPtT^CgBK8jtG{{5%<@y4J^9shGCT=Ijw z?dS0NGG=pHIR*o)n@^z}6Zer<Nv<BNPT|I`VP)=q&v&WU(;`Ov?kBBl+KGjgA^|9} zNe^2bY%UKFNr}j1-aJ`n0o_0O55@-xS|%6;N-^~1H8{6pad<<#n(yb2oe+J;$$`V; zjyW6$SaVg}#h+5Kgfv|~_uQsP$#hDKT(WZtM1vU=-J9%wXv~;iUD*$Yn(ZWmb6=}X z{CzijgPbq=5GL}(LJGBN4Eu}Yi7k^lm3DrzyjlKWVeJnR^~d-fbkjBQjjCVm9US!~ zwgU3prK?{&R#e=Y-eE@ecVJ0?2cM&v$D`#Vp-!_|(=R`lNT!?~3C(~;;35W2#fo*q znN}!{0R5t0lI+THSS_=;_=5GLGS4@I2CIfJ4Ji#dH-0arT$<wYt%nZgLiB<^BPrZ) zGT>W%?27mmX}vPF<3$Gp8p)OBD(ldnCdrgEpHGV_JEK#|n!4k5CtZ;ZP^=c~C3IV? z%DNRRG`7>qK3~%<XxwMbWn_00W(z2ZyCl2DKnp7tkKk7KK*&_*<EoYncfud9NpdWS z6yjm&nlE$XH4{sazaEOk&&5;6F{hi)jbPQ%=PwX|Jd-VqO~37PeDrJozBZ+FkNDhV zG%;xD)^?l0g+UcO>2^Cr(ls~TwcmB7u`|X_XQ^6-b$-#mm;Ki}y^3jM_b2Sa(<b(s z5-1xbFsP>}Bu+ssX%KQ(FIOM`N*G913|%}?10bVvAWzVO(_iP=7{i(_lgcyrVuxYz z^b42Aio8mId%+5FV?w@lv^}0@JRuRM{%L^gY74kff6{Y4mNfL1IwU8YfUc!k-fa<* z(x|MqP7~|Op)E9L<zT~It$MwYs%sw!%pGj>1d>$^Exu7}h%dEPFIewdCRt*ezBdEZ zlr@+7>Bvz@!6MwIRpZb+y+4{QZzD9c{CUd&Jt1FI0ITQr`azfOE~5WO6Thjfd%N_X z!raH3^qtgCsUF*dk<HzS=yH(LzfFD{8C*7dfTJo%<`|3x2=wrgp6?%WV*U?Uxx+&T zgkLC@opmMAiuwyF2ntRe%a+`?W;`91`OJrJ1~r#Jn6u)cIwj07Ty2L??#Qm#8Kzm> z;&rj=P6G^bv`XOPjbNj?)fFtCtiy|};nXExKRiqmb`Y_bQ-@RrDP4h^2`Mq0<lFK2 z4=!Qmj3f2VyI76n0w0p9jeIp7pR%D5t|P7SqxcH5p>d6?K54n#>Nh>QcttPek}bOg z4Wcv|oedRWk5T}0)MdyJpt0|_a<hB!Ta)#&YDQ_~l~lWHApl@%P%tOK)j9;k2fOG7 z0IW>ut%_|*R#Ide_W13T0SSCIRD&|pzo6iX#M@JdP1Y0*^7%mBiX90fB5hz|$!F;l z9=GxHrX@qhc)_a(h5aGz0f@xJF5}?nYPU|ODZey0i5g>*W{;I!y0D$M2iN~!UnH+( zM7+q~myElZ_W9O!qiyje%`-w=4#z(I``#dQe}6lv3}R*vJI&;VQc9m&R$2?AT`3Ey zIgn)(kkOm)-P6J4c(Dq8Zk6}wuFQj_H(?3%nG_Lws$>O|Hm9?2plG9J9Szt))pfrN z?nj41jt;c8kQWD6IRZDkg*l$&&9nc^|9~lZ*Tp3pFpcVVR8}qCU+6g?C8=7jn+0T^ zT-fHB4y(3ZQ7!WMew*B+5p8z&g137LA8o!I)u#HXwkYQHio)7GtNtg8Vp38DFIC)r zb^6tUAm6mA__YpW(W7VMyj;#<VJv}UQzAd33aCSeib6)P_yI6xS(LQDNO^Zbmg7Ul zh|l_UGJ{6T$gc^LdRTG0`|b67qO3iQ$ZTvRMQF7$7#HGxDFPTA7hq>FN|drX=|3<~ zc^{)x@wY{M9>~69a`DObcWoaW3><MkB2VQ=Upj`9FSF3)AhrS{I2iVvR>T@vraG|i zIlk4k<JCZh_!P{4I#2{kd_JS@5>N_1KLom!fQ72|QAIFHg%BS&n>npULx21kRx(uj zbRJvv&8#Q?{c`O-ciZ<};*YN6BI8NFUz)5`)Yb;ua&JmMCVz8aO=;p^v)=;p6qY9v zI?kZeW)$k~D`gl=7Xn<xG6V%~6$dgfY&^6Ruj8>!2y8a!ILV%=#flqYpN#G`zKoN+ zw?Vko1f{RV?6i%1vVZsuMc;loOk_83n98WN;_0&Y!(#m55<K}3eQ&~3QOU84ESn@6 zDF#9~;}6m0<oqYN<!Ms&MvEx$S~B@SDWtQBc^<Orx6Xt@{W3=<71V~TRdD6V>cvx) z!Lso}R6~OaO4BfC>wpc#Ccsnv7~)~_v^pW_Sav3KXh&(lZ`2-3TFrvG6W^UUd|fhe z^E3c)p;*zcLy6AsEKtwrm^t{!z9mcP{Z@6ZuiA|?@3h<3=U^{-|L%0s-}+0BbUZSR zj#9;*Rdgq}MKP0MvvT`)k45>iV0KAfvF(&vA)9t#dI|ujnwGCjyd`d7m?n%AO96X> zqc!I&?c1w(xcMKmHONBV{b_&immi!~NrD%>u*(Xj;iyEkki*hBI@=N<c7C_qdleK- zwOPT*)VN9P9vPD5Oiboa;;sLoef}0jMu@E#fsZ!DHDYkTjc=y}&Kuc$;Io~_>6Z<_ zWqA2JMjAp%uUF(yP!uo#2{HAa7P|XYut>BL!J)JBw9CX*^Ukn~;aU@9b9!2w+`imM z$v`0z9^wa5Xih0buB1gXfMi&7p%om*s(xFF{c|%GIaAi*2R^yHfTpbGB9bDHT>obG zgMxUi@n2d-X^$v)6Bj1o8Ox5QpAGZkDDEn$;i>Betq`}(hlvI4nsK|V569#NINnFf zL{D1|pA1s6pD^mpkfJ^`Og~Y{U^(-d(t!7dASVoMs3~O51iNyVq&LoG`kve$w!%Sa zU2}>83V(H_94g}qkYD*PW;<bl`9lim8AZBIvd|@gfqIAez{_LY3)S$l_k6ddB`xUQ z!ra7VM3}j<GHj_uo<JU0jj+85SwwB-39q$Dj@assF_m-Ns98CyV@06D!I50k+L}o0 zxyeQ&>z7I#;d`?+!fyH$-5%%kBgbZou#KyMDHL8(c(~W?ByT%LO(-#pJv@W3rOYKA zUMtPAeN<xT$9Pqs{O^tf;U9Ok;?aYIfIG{-{ghuxBu<udJ+G$@6Q4$iO+iRA?}uZL zI6*$Gk?{2XL^Mn?w_jLki$!W(Saqr6@LN$_Ir3NjW9cI#n8W)B6plf@M-xA+%<8Mu zc~ss6mh74wQOq?&xFd8J$LJ3P<JHe~p0BV!0NC^b_h$n1TUqZ3(iq}VzazZI|HwM+ zJGRKA=w%y~1rc`uyE-cf!UF}xoO!vApD5=fX;!6C<c_AS+d3cAACa8$&(vR+8&0uw zqY4M*#e8N=^+Tz}5^_AZkvNP8v^`gyM#dm526@f>tbrxVv%bCgjQoa{W(?*lJiIxw z@$qrna@f<0htG}lNALf!Qt1X_rA~v?*Xf+>1?tCl<%$X0B<elq0XNn5l*S*v2#{_S zBJ3qmkO;@3qN2tOm%bC;zsZDAztK2V?ElQEx*&hzFqlz<Mj|jiV<KMUVqp+o7`j>2 z=CaeYWR$95qiN&(8WH?>_Fkp-@=M2^=i>t?OQYjdT^vBvd_>#if52i+_%(xcq*>F) zv*W}|IOxW46#~7T@7Fv)+^{#XTv>m)Q>zs}k|eFkTR)R5CI|*Gdn@1X-OusyefYPi z4eG6?>_u5M+U~S@DVpL;Y}xSF+ndgHFp^ugY$_}qj9SwwPB>u*OJu<)WkwWbOrm#| zPX$#<1P@rsDPkw5ESK3!$zZ8|xod4Xf-7exCbZC{9WRxY!E!5=+I5lkHGGGLPpwzM zJu!@WygN3Mn;_}H%3hV2rXKntyFC7djaiYG4+~j>AI(G29oTIIN>mEKZf`93z!h&1 zBXO1kY3*Vb!b5Igw2s}urs+FJ#^8VIU$o#)bY{kS#8*4+V8jPp;o-B=1bp(!dcGxj zIWYPsQTOJE^+u|+yT<!Ks!dxL&FW9leSoBrH9W&V>q`(6-5w+=Ym;K<_*qgPHrZA- zboreGh#1;XDfx#7-=$O|R=fGi$F5bQs#OxtUJR>+{Gua|DD$VreX}5c^-nrD>-lJ3 zOu&(09>X}L%mxM7HUu9#g`LcR-Z`Nk>~oEhcNS(5B4!68v3DV2!e(L05YwaQ2XK5# z*=W|>M&t6ipLq-uKA@fqPhRj^99->__3ZUZBVqEdQJ#rm{>-A1g-@#s+(B;{%$2Fp zaqMgc_X;B@yYga`av<{h1tON|_|u4k$OzV==}dF;e{u4E{H{V_O6#2j01uOA1w%{D z702#I3`ma!cEh^S8rD@C=u@bb2vb2o{X&JUax5<6SfX~>9NWMI8XA%J!$2RcBJLJf zd9GDShWN}^t7uMub6#ftPoJqe=~YyoRr33dfSyXdmZ@RsMT%^<MV;oK+@^&ShcSuW z=1|O^E7Ug(`ealIwe5oi>_0!Pf+4BrUxe$903A?rL4z-5Je9@QtcA5-899`ZU9v^; zfd!HRt*Kxb7~8+`+8KuJo4t}Wc|Ow-s=}a*eJ~E9EYgeQeV^D*^7DJz^X)kT4ZGqs zBruQrF0`^KI<mRj@@R^>x*u`o@(cotAs)wm_OP{^uzu~SpYvL#Rx%D5>oU7NT3BRV zq%iQ@`o?ZHnsD;RQT;G9LKu5k$>#gjYNf84ejfl!gfq_Zzwbd*7}Jqr*snXHo;321 z=6I=wCpeUrzUw|5vP9O<IVjNGi;snEr=dzk^Dn9W9(qv2oI4>i#wABBJC~Y5DL;1k z``2gZnfcm`kB=o~>JQ-+jgT!;VPx$3?XJg_<GBo8ueUl^8E2V|?si3nOT?(Yx<;zu z3YQ?wF>b74rvqqtyueumj+Z>Ig;3ACT7PqFult*)=FPJ({01Px?gQWANv+vPjuVCm z<g2`PQ=M;Sr9u4Ez^4(aC32@Tlj<dpku~O0aM93~*_eZj7!gh?!as(X_k#1xEd-!% zL8ys?Zn`%vF=&?_92^|(wJCvPn82R23wnevp*>b}#eUl;<zP&Ia^)q=KpX1taA)sO zEa{TIpNI6CSM`#)ZaMc(M#OaCvHa?UT=r(*QKPpfEs%&McsQ2Zzi=ci3(I4RQ?gn< zI+gF9w)oZHqn$LsvVbgsYFKpYQTZl>>_ybR{g5`(TM%-doMYATsH|jVT_#1k-ER#i zi<+-sS2Fba+V6E(;_Y9y%Q_CKF#H}xSWPy^YmY#u+4ct#RDo1%Jr`iUzk}}dVf?5c z{&Gj!(R#i#5wgMlKVYXlTJ(vp1kdt2U%T5etwoko7=bhSBn0iVqKmxLDlC}GoBX<n z|L9h9pFqvDY~cU6>%8W+H0E>OMTe*F7^Dy3a-8Q?q<{Q;cdmApuC4WyKJAVhL(NAZ z`^G!RLu;=n?BJ4u^EYAlc83S{Sgaa#dO9uMcvNUsnO$u51;>L8b`CG*o`W6ZLOyQE z5dHOaNK*UrB2Kw_xk~1>lL)La>N(*EIPbd8z#X2O$JuypG8@BcFbn_rE{1!i1#(3M z@N{!%YMK-8=2m3n)1D1a1+a1+RM^_2y}CuiWBn=QcU<uDPcr3!>6D)N^C0l`Y_+W( zLemMH&lZF`<`Fncd*jir(utUi8)u-#p?hyZTp`b&d=m^i&4n;6fMBwCSgVC$gBNM~ zIu*^@ZK*bYAjHo2Xj36~Z?`+1dKE76(pS9jsru78iOa7~cXbhW&)SDz1H03?bz7}I zDeoSq)%V0a(PV`IT@{le?Ok3W`PKgxa%<9o_fb7Y5TtGKOm*qMg<=gMsuTnU-2(Ot z=hP~cmO8eh7|q60=xJphd~ELZaQGnB&TA&`y`By-CBC=}cIhw4a*jIbdHX|Kz%DGG zE4(J$?6_vG+21tl)x*HZxVx9>@Ermqn4jw`dIO=IPwGa#D)@0MCJIBwmV{3yxp88s zov>eu22sL^4x+aN{T*O1-QfRy3#@SZn_GSZ-7+WfgG=gg*<vB@mbJck%ku}ECoGbj z({_Kj-o<BBwq*zKUxlMUto#%dDDozFeps9Qt=sQ;96~nOfvp;uD;0FReZAa&m7acN zt2$#1c#M9zj1Tx_-TPbOSz6>N(f6+~>GIdJf)S8+{;vD<@D9hda9<LZF9T8^XZhVN zJO7mvqfZB<`?O!H{1;`uN<;O%o7*5x|6@O!|E-oRqDK0&=w?@lW1vf}#|I;=^UiBU z0%6})g|@BLnx%l9{O};rSLt4J#hm+_L|PP!9Is-94pZ+lJ%=uuze1?fwmmCrM%mHd z9&2uCFJ~S-92Ge?O%T4o`LHN$e2gwP>va>1zsWJYg?N5kokxvyQCA=Ibe`jLR+ss3 z(lC8?d{6yE_D^+Mi-IU>4-EZw-FWR{_=HjTmu6(SKUr2ApO~=2)}hqLcO(--l3vyh z@P=4q2O_`WRNE@NbY@n8bmL%xyd$B&fg<O=$^;_*o$rZxXP%z+Mc$UVi|*>kmz3h= zxZp=7oO9a+vsf}8Tm@!wsEpnqav+RiLYG){3GIfE8!m_S)%xewG?t3?)|*>D8hyv4 zL4Tai&{hgaUnvQar9__lSG4Ru-*Ef`ur?bgHv6I4Fz|Ujg2G(TLW#F$sUN+mfoyoW zHD!mshbvvS#VeQa&5*cvhqFAE{Cp_*p8)a{85mDBLKe^&L(B*KWyZ0KCg)*~NW128 zr+QsCI+ApAJ58t<&l6*wk{xGCeC=6{DfRu&T<#z0zo^)coU$8IJ$<#yhKNg=Nt4+l z&|6I5kQI|&-aSrOk0``4{x{$B-u>khMDe$T`UQr-GGlydClF|D9t`VL`Ki|$hmiKl zDFID&$GleRZdRHs^>3-o{`D8WUf${LgHLolgnEIPUaEH_d^nZ}1ui6>iI+Rg@3d*D z9&Tu^ZAgCVdh27jQ{?5y2vdZzcjr}Iq~`~8o>j+?m#3wk??rNHE5C<5Js=Z2E1Vr? zYaMzGR}0;~H+9Y5XKQCrC;Wa6DKOrUL_Yl|5SP9pUYuRT+aMw;>c5cmw*?qviv)E0 zDeQJa+C5(bgAO?qBlMxfTE#B3o2*mq_$T_mPJK#-%>K*4e!J?bUWr$2Wc!=(qXOe; zVmK-lb~X!8e9**FyzkGLG0^E4=B0Cd<FJLR+s==}c<-GOp3)QDAYZaV7$A%`OFP_o zJtd&jeVu)7#xqTe&LZTlEAg_776ieO_9+|24mzEo#F78)kGO|IeGWoFVoBH(x1E98 z;<)|RRDIt4TwQbuEQ&@#_Me;(%_EO<MHjpXTy>sc#ueTQ#kM60MxkLr^zsw1)*Jkr zGhfAe$KbAxW`2tA_92j^K-8h58*hI+o+F(9W-M>AVR+%;!a3~f$O3t?0N~Xp6SO6k zx;-qQ`y|&=x_+#e^C%Hvp@aW*Ca~MjhsypYh}~wTI^(9SdWRVwusyup8tET$2_90@ z^5>tO`cKqEhGY_P&sm?}ei2j0H9hvn@VKmowlJuW88r73%j0Nr1xUwzqT2^@Y|-MG zu1;kKg|*Z89VrHNyZfm%Zk~4XPVhGrvCfXaUeVhf1T`%LM)^Y#PW**PrJ*<{o=xO= zdAiV`!@b$QuCb9*pgK@q*i5%($!}afUfOrHPi6odFJezLq{^D%j0l9Z6?cd>9>Qj- zUAxI;@@@{RHwy%LmUMV{vImS@A0M3j_~8;M|9ND2)fAiO2mwYj{&+BKJ{|6-x+Vb_ z5tv4*n8;bm6u%$TKj3j=IREYO@*R~H)GL!)5<@cJSNQ4cBw<8V+<ZuAxg~`j#;5xz z_*Mz{@<h0DlxF0wgUh0CY5Gg6=ShPjrq|!P(&$Q%3qHarw!RdUiabamV#@mklJM>* z4!WPu8mxx=o^CK><b7X{jne+A0frf`RKxb^PEN1u8jDXW;~!C^l3t1(2Rt7gVI#qt zz8)kz*)_o_eM=%W79JDPzW+W+H(2O^fSco`={vEfM$L|d!1(L?ZzI=+&dxhdg_jRX zj3U+l@ea|z{hUvMmw^{r-B&mSf}XW64<jPqrAfU8Ip?(d&E5((UiNsLd!Z5V`7WIb zXg_)q2;=_L-W12kI2Sl;6}Rtsb)Tc2t%l57Dzo&wIGa3?U2#o;vO(|0L3(lVn)c3u zEsE#4BY)8v#Y=D^^*K|t2??(~+Z0kV?5>F7bcm4w@eZQY<k`Vw23PWIfi!6KdX-G3 za}y{d#rq$#v_}W_@N^=y?UNd1pIfcnbNZis4$Xabi@(4A`%v=yse17PnIc^XQiYQJ zA=*YF6R)c=I)#S8l$P8-Hzi+n;*Q&N_Zwdh+3nlq`w!cFPbioX;3DY<wbwfz_c9gM zY0yov=8n^KJyxtrFq_1kcg%J3g<itBIhr1ShLf^~;K`eOwNocV=(qYTP1YCN*~WsG zxysqL<Z>Obc-<vURbfSteT@eE6xi?7AVj(W?m~>GLPtPL4*v@_d?C9CQXmD}2KOr@ zR{b%*mh2K_oxAq*+WNPk{V%|PX+v!Nb-+%|UNn&#@(z_<b?^_sH;WDxF6=eZ(EE@k z^X{0Pu{%wY#4u;X1=Wj(`Pz9BeNjXBc3w^D7fZ(pJ7aD$TT@MC<*!Ah90<>}=*!B{ z!upN3=XOzVS8wC#yH!hVCy&dXydLb4T@ZQE^J(Z<O~*Me+a!iU26)F0UPKA(WqpLF zpFF5AvdR#L)-Fk@O%3&cJ}%ZfayhWcPxRH~3gffuoC437G?||nxyg9yH(TCm6ajc& zi!%35fByF&|9YT+7}VqJH%GkD$Pn^ZeJ<I*^9H}tKMgD*zk<o$*iez58A!YjegZ4B zSgANZoU@lrv<$ZCACcWg4p8h<;&I3!+x?2=S+``bnHc#s-2Z=VU3oOr`x{2G?=+Md zGnS~x63V_zvRn+MT)M=_sEHb8tT$T`C0htF=t`z8cd}J8LS&h-gp6yA$=0O7U@Tet zef@6g+<w3LXU?26=X}32@8^A==Xsy^J>Q|x{g?3a06W*-BQcFlKO?XqO~!B60=sjI zB_3OC#k~0d54kzj4NSL{`m|0(&Ic4`%n2@(Hh5u<gzj-V(8^lnqNju}lUy(}UF>rM zmyX7F+T|X%2Tsga?>jvJe22XnO9e-&&EciiMETx|<4jfTbCgVhr*n6BtK#GWMyi9- zk&SVK#ja15jYOBnz~P2>Om_kB8(pkdhkf8~M%l)$3he7M4En5usa?)|>jxihF!|-{ z_UdaC;O3mUaN*ie{`+y<)EN~=B6l=c>pliBKW<vK?BgsYQ_S`_F^Qyc0sZNsbi4FZ zYgMXrZ~2!a1ykThdQJp{?yUG0HfbQ^u#?{l=>w#+Gzr6=Srt3edT!ogz^QvN=vCT$ zGZg8^TlYclJbY^+3_G#4PF&yHuf&-h!c&0Q(9fHPDk8__tu{Y+_6`sjR<|E35X&EF z-tBWK3tpcl<gPi7AC7?vb8Hw<a=5In{}-EgeFHJRUJSRJ`l;YRtVIg{1WDwy`RL{r zD+=R#Yru;C0jNQ4aQV*?;xXFT<*4&jmyuxrLG)rSx;x)8D~sc0kEia;J`EHT$Y4Qv zPn=6fY6{f!LQ68lx9>zN3;Wm0`@v!0F*q6U)2NuJjo)YrNdDCA8|^pu3QlId-hBK% zsNda(FUJ1W^_7{!GbpR5kuZ9<TrH5rgT}0GyBoeKa>g&11j6d3?t&m9t^2dT<W_NU z*Bu79EK|cn9oX{(Wix<>JziCombcQoEqb@1C2_x^>E@W|)rFjr*+Vgb9fM0y+|@7d zdMArdjeZO2w>RUI=yt*vFe1&!WQ5CF@W4SIedDbq+REtyS46hJ*P;G8WgsuA+^s5O z@d=<?gAUYcyOLa8-%PZ-b=Su-1n7w*{Q1}I4MApd-R6`=u5#<}<W=i-+H>>1$HGgJ zT(P=l{^qS(mpZ|&z=qdh4Zf3^a{xnbNHmbqGA_q4I)}%S3il-XXSD0b(?u!uEL)Rx z5C62uyamLDFaZ~f#A{M0a@Xz3I8#20JCb<jH4%|I1F@G7$~5Me@_;<3H1g%IERMKu z4EP_&0|Fa<fD4TrMxB-JAjg$Xqe&)SO?;J;aqruPil%7<*)`YN-=DXZ=Yy^$WSulg zAsADMZWGaJ{xBw70R~oQq{YV^Cv|L~w+3_jr=^pR7j}@AdTf)_;F+3vBIaIf3_ks! zj_u4sto-p}scM{EO_v;NwP|93Jtbh72G(1xbrOSJ)9H{ElmR&S!~H1Fggl3mJ%_SS z+<jqL@&E%W(U(+tmc@SuJI~P(l^9!V@@7Z={Wy?7+4(GHmKi9IXR7}u5$`u0Kz)dp zi~?A@0CT21IAm+NKbMswRt2xCX+k-xT6|5F7Ivc7Mchh4$BRO*EvmQMWM5%S+c3u5 z*7_!DJK*b8l4OWqw)*Xw?OIkumz3=4dz^!FWs}rNJ&qxrm7JS8$R4oJfE3;&tbm4G zw+tT&`-+>Op@R>)X{Jpkv7wTTzy$Yh*GsW~E>ts#>CzWM8>sg}GRW~|(-X;togI+E zipc{fqM>+6MF&=0f7bQ6h5rKvlWoa(!i3wQkT*@b<FLIQfqyzSia-nkHP`xdtxJJE z28ZWSiLh>&a=N&zS2_z<uz|mS@0vsPs5?J_JvZxL9f9^s9lXcTsQcnosW{&iwN0~D z(x$*{T?jtwkd6Gp(*}!FMPbw1nTGR^!$m0ch@K+mic!Je8bC9$g@zO{jRIDO-~P_q zaeaGpZP0h~GR!Jl$U6W)>r{wR_-oD#%JU!nrhnp5pKno*8u<L#>^MZzGy1)Mqwpf& ze8?PzKeCW{Q-y5g8HR!MGlL9WE?MH>572+SuC8EW@$Iv~ph4!&T3Vvxj@jZ<Iu6u* zP57OZX0sP-=Bf-QHkHXMQ&hgF*&h<@5xn;mz#|S=@xpYblf6Xn(4-QjcS6X|WrXuJ z^}QZD`utUF96u!`WhujaAmY{cA(ijPhD$y*Gr--)zP*G>rjm*-KIP|u@=aVhGAaF} zeeg;xbntc__a{|Lje(Ga<=<rdF0MnA(vC)D$Hn_}w#S;1lDNjH1(+H@2W4O2m0uL$ z;^{PO6TJiN-XXiZ3r(EK1hythti>^g;#&Aca@P*|hL4l`Ii-g}&Z-?#ePd)&iBH8v z*h_?^`nvNdCvN7L&`*<><wrLjwA|2?iQeZV-VnP-NZ;R+3@rcVhB@ceIIM@00Ig7E z7T9e*j|k)Cj3wvjnQ=Pu-q(@)XfT!9(yplP_OIkHgE{hXyE)spmsQ1tX8opbmH!v! z+NB7rKAonAkP`*P;<_M;^MMRozZ$iaXHPve(=4n$!E&!4n;S#KgHvlR7B!Zha5mQ5 zdpna#;}9?{t77}29clf>cnqxe{jOBm{ckzN{K+~;Lky7E*v%nAD>1*WZf%La(J7=Y zqz8b%;;W@NCOR>73s_XU)&d55bQK_eb;1Lcpk{1TpCtt{&b~k));#GUb%HJW6p)Lu zwotW2__^t@!|e?=mDp#B|FnvBF9%G?V-%yqna7R<X~(qbLPtSaH{6N#3>(Js(sJ`^ zBn_H5>iJ~s!KM82Bp;eZ#kmsa3VP(m{$Q6HoL$cvKcS0#<8*^{T8P*qA@FviCt;*f z#IVDTvqF`%!Fr96Z5xeP9a-#ka@cQUaK@ffF7nHmkAir`WW8ftR<2<3*Fz&+wQ`J~ z$`R0frQWy2@k<0frWK(E!v(k2X8MU4r#5I2Y$LfY-M-6j^NokSH-SwrYVT7gRCB_< z%x9<Wf_!F08?T;>6Dm&%led|Joyi!}3&?l)6$psRr?Y7E(|R$8re71V0^E8m@RMWZ zAIbV=$1~oH^Jc0K)XH#(8ZS8xTZ7&-=@?bni#>FU{*$H_=Dx;#tWDr2X0~|CEQnjt z1I79ai?4TtBC}{(ZPCpJQm_=`mFyi#Wb)<19$%2HZ#Ote_C%-m79c~cfmRg?*ccwx z1$JOnC`TYK-N#4t4j-~9ti61XqtS4xR4jK9sC0h-)&_jXjtbjcpx6uZPBbA5WF3rw z5(*MMZ2+jIodKca!d(H;F#XGQk^FS#V&MN2zZ+)TVrD#D_sLq+mi#A(<Q-;L`tf#- ztFO+L-b4BfJkHPK><q|}$JXCpy`K?>W0p7RZUO`Ny~Xyj=#lE@K{3y*Ww8D|O+M#U z@<R)SpeAlGxY$8H$qrhpM9x7K+X+g_OGpBZc^_YHkgYXBjC-9;{pRj}$Hf^gF7=Q{ zq-d}_Mf<P0HAX?#mE=RkMMV}O`jcW#zn2B5X}91-^|Y`GO=L;URdQzXD%<_?xJbHG zhSIzJ#cf*sVzZ7fuZ?(jKQuoclnkPon>AOD@T=fG*%CX$sSYM<MYGg)9iviDk`Mny zQTE5T+8+mBV(2q(^juWA6W4!YUO*J<N6kG4D^SPKJxare`gN@kp?EMdonyk!rE&$O zH)=rQz#7^5;`y|+)r<{0CX5|Sb|e>XysizQAhOz(=-W@sTVm0_N_w{#b|Pwa`a<^( zM#riduYY>vb0n3Vq*1$+Ca(NZ7YjKDF-tdvCLV)ETkZe(d`DPu3|<H18ussVzqZz{ zj{4>(zJ%6ebMGly4cTe=+%-=I5OotKElXSmI%*#T>}nh1IDg5gQhdg+T6y-=_u;L5 z-m6ERf#^13c?(|xDI}36`JIL$+9+{pZ+_cQqN@U?pXff7<4e3(evvYypf#Y}`FCWn z#O}1=kL-uB_+T_Tph>WUsI0*bjU#4qlmy*&blKUrD<*2s15C;uSw6HsUlUqxmv7|i zOmsuHiOqmM;GvF|)nJC8;Sn}%T(H<?F>Zn;j}J*M^H>e-qy;oJDo_Ak=u+#st#G&A zrJ!lauuq}k0z_@~4)3R>^9S1mzI)u?Q)}%chigq?A-p<p+N-j8Ky)7&qS_~evSxE! z2?{eF;Yv}}(8%JKR36Cx1yO1QK^x^!{_fStRz_P16Jkhi@Tx~k)1h{;T?M9e8Rdl- zUeU~oii#QG`D1KhuWI2RlTW+9ol|^fZ<(k>+)(z^t(%SgAbk@w*$A@2oQoRL?a`mc zKA^Mbl0BH#J#&Eyi{J0^M<i1<xDyu7IcEF}Pdi_YFoRj2i6Gs57yoab1$?5)a+#+s z@}Q)oeu6ci^}%@qX0tq|ZVBDJ#~)Y2@NwI;$!45({0W)>J;BSp4ee8OwwNVmYj6NB Nn^Oo2BHZ)le*l{G&_VzJ literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231108201224.png b/docs/images/Pasted image 20231108201224.png new file mode 100644 index 0000000000000000000000000000000000000000..67d0257eb37ab2ff6fcd062ac4b756aca7dcfa67 GIT binary patch literal 609703 zcmZU)1ymf((m%XFa7}P0B)Gd<fZ!H9xVyVUaF@m1-Q6{~ySpsz&H{g)d++<c_k3TU zQ&Tn7^{blh>OC{nGaD)|D~61KhX4QokR`-LegOc`=>P!4Cpef7O?kyt0sw#{WF{;u zFCi>UB5!YFY-VW$0EmYssKTl#4r66%#Kpu+LBff{cfgaf`NpID1{{f2e~ts>{KbKz zb~aS#X~@=xz;C6_U4p3j=8V<9fi0pG?^L6!x{>c&`7-iw@NzKW^UigX#R8h>aDWBe z0X1tlVdnuPs__h=$nd%mGO~IxnUDyKFos(Y#hTig$(V$M5W2XQ@7f#dpF+wz4oGI7 zP2PRzQay!;PyyfZc38cM7_fKz0b9zvHQ$K=xe**$sSJsFYJQEMVBoHP;7-VIQRB)g zZgtqFJ*u()r2`bpw`fYh0L)cMCMma!1d$u~Lo!4>bKn3@Fn>E+T7XYzML#T|tp1{n z-lmud92$aUSggc>qvJTeVJ$=9lG%)M>3tb*K83qJNoxd0*{C#XB`I-JYRl<*8`dUr zC`o$Me>-yPhbTiDNZv^HM$f+fq)M5Y`V`1#J~V33mkyy7lJU6KZ5x986$NWw<R|4* zy`vr@tbX&4DYITrS>C_yXbc#8(EU_a>=NXI)LuDvM_<^bhO<DDd)`K!M3QyrYLc&u zDUeaWh!ttZBIN!gL)M7;F*1G8XA2>`som{OV9!HjS&sE*|6*27>x~#<0G%5H2;^6Z zp@)xBUP(GQK%T%}ji=fZp}u+pk3GtZdRJo+sS*jKBRY$c=#wEG!(9*jM4AX>fJ6E< zM(9C~M)sG=i9h59N*~j}E{v1nw^?)=y!{WucHF;}ZqRlkHLm*nnlT7oyjtnRgjFHv z3}ZV%qBJ`_Nq%tMFn+!e`PGGf!z74stM2&j+ZnkOIJSPD3;__f^349<;`aDRT_d3a zx8y=Tk=U4O`nIbA5J=vgLX<TL1zX#j1o=tvdHp!C1N;eG84{wuAiGI@ivIcy9PC10 z&WmG%QeOM!Gl^QeiHl`O8Xw^}^-b7oDh@{k>3h%@|Io%}i1Tod-OrcDsAVh@fB9fR zSL>OV0aLQBBF#dFBx@<(Y2&~c`#4h&cm4@2;xA0t&6snJeNeW<#V84OT5AB#t;#7> z#0US(b&^q)0lHCyU5c}=@vY#ZoceD(u?p9WwF1irpjdNfb8BJhTFv)lV$pIl;U{C% zJMd}NtML6(HS+uN7mX0Y?g_o3YQ!alatOw1bhU2_VT8c#ocTMo&Q_R?{*m3`AnsnD zM|{uPTImC>dG0$-FNNEE#KPguX<t5dUM<qGp)r%{ttb**TM^#D&qyW|CfESOm++mN zJMy2MHYBYTn=Ma1fGr1oUEQrA7y8prfEV7a6Q4&OlfD3rU}^ve^(H?K5;}O4{?lWE ze6UR_|613WA98v$i!JO%H}NMwMl|RhA?9SbyvcwQO~}GODY`_I5JtMVYS0UQk-CUW z5YGOu*$@QKMcwMQ@R|@D-F(gNtv!fSup54paDQUZ@P3Hhen$WMrA93MGx<*Vr>~#I zY2zaDNpVBqVo6zIpTu#0MU@M)e`6cs-($2#Xz{K8<`N^D59=1``GYAw%slUBF(&sH zqg+~6f=DrnY}`YPdNjJ9N!b=t=8o9EqceXn<Zw)(+(NHJLr7!J_DeItMugVXP|`w6 z4Srv;EXOG8F0J7%hvx@bsKG9Td;JaNBsAGVv4sxaf#*cc`ZGCzy?b&==*qY8N2ibH ziXV*c_mlDa5_&rvL9f~m7(MEo0C}OMpPV9`P@4tTy*#9`#ZvX;?%gg-DaoSgLYmT= za%;l85|$LspI;=t$MFwm?g@vH+DSa+f0_9`Lq7vQqx_5G$Um$!EHtc6vRX1MOuRt6 z;D=Gsh+RS%wVX0PkZmZ@kii}!MJ`iTTXI9vnpB6}1t_4%O0|GNEXhk2&KzAE^h=CO zxJAw_ue8*>@VEpok6J0Cto5f;)v?>W?0mEmT`6IL453`YuO#^<MY&%W@|#nptTd?t zbb*O-8b8W%G79<fz2x)CxJvEj9?c!*sOOL8D@!|+D9SWS>*gp*u}f8piRHV>H_C(- zs%La9Y}t%0l*|bhnhU0@Bo+w@a0^n(TGSkh4xq<Pet)N<sUV^2RH<3Os+j$)<rrZt zYclJ0`*d4z%W`XNmD||BF2*C(ChgJWoaUSrl^9hfn>)dpA(>&oP1u@TnLsbbA?8wY z?!BJYniYhLY=Df8q`_Kly)>_PaTj#*bOL`Xd3S%fKJ}76IfXhixu8?Inf=}k;HYK^ zVM;cy?%9eEy0AUl-sp4dlM22d_FhC|t7nN|OV?}eub!{o99p9MD{fi8a9FQURa05h zWtVs*xw|{SNA8HOgPt=i2}CEK#N|f9`W9RhG~Ij1!p4fsmXK=AZpHFyX>66Kt76zV zc<RU1pKg|E-8s{~+&<a+S3ja(I{bHdTcV*<p;6(!`KUwUMMZf<Tsf8+n;Ku;LfwHH z_V2~tn@u^(kIT|EC5<iCQuRhF#;cW09s0p5Ez3qL$}3upVrT1Tf%hk8t72$BU8B$< zi;3(;{f@isDQ%0L4jt#5B5Y~xEp0uyX7mk5hW5WrMuHFa4&ry~=Z`ihD-`td!hW(v zx}RBs#vCdgJI{YOz&oex&KzEk%x@@fwf5XK;;&mptU@*!H&vYzoqu`Yejq|cj8=-K zj@FR2GG=vPx@o8AVd-{=0x3*JYoBXBX}@&5T{~Y++;1GcTGrp0_8eB^wRw(tHuI-> zaeLx+mUO0h@_?mZo4x0~qru~^Pj9Q>tXfNT^>VH9BnVlEIA39ii)HOo^;4jqny$F6 znXX2Riu{kM*6iRO;~w0eh90l4)?ZnE$Oe7+(I=b~ys?90=bDZutCK9YR9>BEYwoJ~ z*m^1U+4*x^NFmc<ay1jpz*=;D1coTPh##fwTv##e^un}aZuDO?gIoh@gUr8CVHvm{ z^if0{RMsYIZI8Z>1y>JWEWhN#kB1(I?xI_K*`$CbPoQv$AmnmhSdtos8SdR1!1yJp zKhhZgW+$|(5_v*&!QN>I9*18*FO+F!oYvK!_-g>1qp+hO6er6kFF2Qe?Ty?~ad?^K zG*dS7;$^pCyMW%z>WbU^cKJCTF|+U`KdDGy^m14&b{cq;q#nCWV~Ds2uVWNwY&GVd zMVQdR=Rrb2Wg=H8X>ES47n?|_F~_{@dR;$!rte`F+H4TE7_Y4O{Czvl%1wMDpnbs8 z>haqqbwlhM=^5=MT`}z=Bb(i^pIPdx$n5W;RT&-DS2I1^Z5x(L+;-e?78#R?v}LYv zHj5ieL+6##1Fi#yFp%RUa!Q*4k&*U&`(}80*hu)sgk0*TlBE)FQ}anujE=d~oaA@1 zCM;KmrDil8O3kIlA*1OP(M`#x0_@TB5$cgn+5@`I$CF~6MKE{ucQ1+6Uk?TNiJy}~ z6W2A*n>@u@jNSCy7Q>imj#Zge5-UC1%x6jwF)K0gRTWjFR9(tL)n=O)^v`M=bQX*% z+Z1r+TZ%@i%@yWf?!b4d9FI1|tETlemb*nVy)sQ4!IqU(jir@KKh}O#?+-8htpIr& zys6ZU>uM}FR;`Mz@;LuJH!Zm;E?G8fb}*y+O;d5U%;vqAu<qA}e?oA~elfkS*ob|a zaPHN~;IujZy8V)d%7{8gSkJ5G6yjZ6PgIhny}1~(JT;xXw&cxuYU==Wna%kYCDusH z#`oJz8niUC8^7B>2rG+`c_=`|zwAN1tE769f8bFxnAy4UWp>7y96a_^*JC1=Wst#R zw*dlABWh!#=oo5SHt%_tbk0}YO<h=b5t}>Mly#ljwOoaP5(@99&jzcWwfLOqE?1UM z(od4CMK(;kQfzPTE3TTjt#51u+JFwA`Sm|-Sr_9Sa?Lu=g1bWf!hON>K1**kMSUH+ zY9_iSCwa|c53R0R3`8Klw;3&Pz<vHs$?$Bd$;4#T{ig>_H~w?C2gIxJ$qq6f^EdUo znS=eFF7Uhg8UE_xtK_x$*4+-rvrS`{lh^7R@%sCv)_L3Hg_OXd&(c-w)74s0zMPzZ z-0P3$+JmyQ#X_6y&2!W}6r_-rFO^_bfIp^;9PHMeGr)8hFtz;@!7OX{2E-PzGfwz+ znN__LLCJ6qnCp3eNY;LIaX|F#(Ad60JT8ldB}s)5Y^M;^(hNG@QkU_rjK?J9g|!TO zPEAaMd6Q8{=kf`80bva(Y4uE=bpb+rJ-uid2iiYsiZCNJ31b-<0QH9q2lxbm2Y~*N zAU=p60{?&IpAeJ)sDJ4p0f1mLz^DJ%$bRsDTFeLigZVdyiVFh3ew=;zAlGcj|FMQn z&xZOR8R8!g03k(T35gG`Xkc$-WbI&T<9M!!;_#t>w-s0a;8<k;5QN09@0TC`7tNH^ z9Mxo`xeaWr==BV3^o{6Ut!)4C1K@S#{t&H<9Q8<Ctt_n_xLx^3|7F4bA^)RhASL;i ziK7J{shW&DiLi~m5eYjzBRwN2KLQB}39r4OG50T#pZ|e>obi#GIy%~NGcdTgxX`<> z(A(IXFfeg(aWOD5GcYsLeOS;rxLG^uxzbrXeEYYP|M4SY<X~WLX6tBXV@>jpUp;*r zCr3U~(tiT|Z~OOk8o8SNUnFaX{|xJ6fDHfiFfh?GGW@Ua4=C?HT5fqWS0hVx5i_fg zIs1sg&&<xq`!D<dU(f$V{4b>1{~?)JS=j#@`d?lDU#PN!k-e~u)kjQ6{{PF@f589U z`5z!J!#_j+uc`R=JpW7kG12@8ybS-FG=2nYS@MmKJQA3R$SHmBk5%@s_UGeB`9c5i zKY&kiLo7ClA0@CLKte=F$ra+XLmfyc;S9oVfe0-CU?3DDQ_d~mbBy1{<QmdRTGo9w zF(gkpQg_FRqdQ^|&oy>uW%WvqHLD*B7az%=rg@^51<q@nDK9OGK(-t|ybwP$$EpLq zC<lg9W2~}VM8ZAPy<D9Ih^+;7J(qQ@5dQwHrgm85z{8JBg!<*p>^g&@%5CP{ISo77 zZTigqVHbFClYivIRW#^!m5jYk|5A16BE<`SEMGP4GQL?Ty7Bn!$=!8yRkro2e3^a> zF21R%vqS~HsK-C)wenKFr&VtHJH9DzY|<f~o=1%WZSr>}OTBeWTDlOHI}tKFgm~#T z<iexf$I}+uk0#r!GlRgB%+YQm{0u8MxvO3^#GoD%BG$I{S56zEo5Ibz%STo>r%t(W zP~Iag@0oAihz}-WLD9HFCip<2jR(~3Iu>r7<e~k>X43+a@X4$P8C|$7f@bsIWvZv= zwB>}eiuw(@v}aG;n$oDMj-FKeU8wusZmRO6UyMBG?&|2@^BmI>U$v$kN^hzry11}h z=k)i}^7d8hwmg5`zqBq)tCB6M_Afqr;<abNM89@&$z|T;^UWJ*dmf0oP`80@4p<nT zZ*qBT(#90ewVQ6Xm{3!-HjeBvJr5*2O8r4{KvmFdy(`gQlWm6gYX%pse7GfSn%R@g z_wUi+;o;x9C?p<8T0p~1s;9TEF}ynUo<#1_`{y7XrB1PJi5G=^ojKyxvDsbV)<0=^ zEp&W&0wy-io()n6`DkCe;1WA|ez_J1d22sB2eH}k%l&!FJ9Z&@=0)i$s#xT`^Ca*B z4f_b3G1$L;KgnC&&ECb1y&*|2${7@59?Jup9XiQ-y_U8g%y!lG?XKz(S#6V~%GG(J z#O;U23s_tWNVo|^cVvFw-01QqdLz7-7@0QXKYXlzJO#aee>^YZ>d54Hov_&O>_mE{ z-_48C33|%|zer4FaJ<4U@2lD`a<<pi-Td8UxM_Tt)5$dClRY|L)FbjN{K#I{O$rf6 z;X?6QE6e}!ba{I%l0L_+&~4Ty`BX0LqWy6^{M`SP9aZ}#`-#=i2hV;oe6amc_Ux_v z#ue|{qRQ<$h2qRiOKvg?X0oWqpmf%Mf|y*G*pfKl=KD3#z=Oop8#8OX#YU?S?h_IA z!-@IkV8S~|^Xs!0`td1AhL7^wU2XRqi1)oMCew+p>-^eB`Pxg_(<99d5B!noN;!dv zG|<Nq)rc<o`aZjrlX1{*qV1TaoYE#YA@%0A;;~UXIZCeBLhSffZ@J(mK<6FZ2cr2H z2DacVv<3FUF0b>Y<b$5)!|0V!r3aZueAMT6x5L>ZmyXOiJ8B<+cjo&g2Gyb`);*su z_Hz4YAh|!*O;SZ%eEjgwitevqi7Bu6HMu`>MOVeUz$pXmTVm0sBtG~jVrA5SeiutV z=^UFB67LH4t5u6{C$ILm*RM~}4(oQrphwQzR_&~ZM@}&6pOhlcmpd-;#7V_B*8Pnt zv934X>k0h(6WwU*q=G=gxphKkmlav{%J^tZ8Vaf~E@xQh^F3NXg|5A@p-Wp&Xcwgf zL;-<&e^t(YwO}U&A7?4SR%B@J0NPM4lqu|mqmk16r<z!V<-klE<F7v}r;;-5e-y|< zesK#RuUi%SYJeKJyiV0VMR^5ThMe>5HE=ynqZXMoc!K=X9IOYOBmYcdi}S9$4qX-6 z*mq3jNwf|_4peR-;Q3qtWa_6QiZkw{xg&Ar5$pu&lg+@Cvh-`{<e~*Bvgi?AAqLQ) z+ZQrkrxf>{-_5-jj-^CncauuRyd_lQdTvY8jVpt-q6e=8705YF_{2BdqZ29RuthMs zuTJ@9Ufud?_2*O%YX%MBq!gf;yr}7+)@YFovPEQ@cri3Z<^fHd+dtGOLu#kP8`l`I zm@V8bLEIzI<A)qv&U_<XQg`M8ruj%C_}m#;g9<UZ93#x53^BbWYZB@}i+4RquBp1J z*X+6z_~mI;N;Z%DMO`H^FBxw{9rq-y`q>aF0=Q>+UoN$kukOyvia1n>KKZndd|j?& zo8^#j?|$AYnn%2cK;~_KvcgNJ3jRW90_Gy3GZ0qNP{Re~6SUmw(t(Esjn~Wh{X%tJ z2VthD0n>@`;>1ory*#E(eK=C=tcBSKN3&V*u!I})s;bDo<`ALP%tRR~nU9&9>(Qx2 z0Z=e<>{N|6ZXFY)LAJ!<(mn1JO{gJCYGcwTU4FF0v32cb^j-({-0vB%e1rchrQkMw zIt7RHa!BBqLFtI24qg457FmPMnw(-gL*||ihS<-nuj~s0u75CmU9A2v&VRFAn2`nt zE50MOQ6ycFK(vzR>^%a!I^j}E)Z}EB2eVm?z(&xU(E@tJo54xz6AR9f72&ru_-Xik zIl?qogfI041qFHz77j}*Ye@Igd1ApH5A3H=zUl;xhl^1}>V%C)avU5@ehlwb_X0Ov zuqBuvk8Id;Y_MGw@%V*Z3Be~0rrk`%t5$Br_XCDE{f8AX;&bR^c0sA`V%cK6ojH;^ z*<fa01Z&h5&3uOdd2V>>Dd>QNM8CgLP((aDY+Hucu$H@62P$LqJ*%0yB1ypB?j151 z*N##Wn_z3Ptw3N=33vI9R_%!{cMz=!<FKjDwG8h5j!Qd+17S-cT<;CM_M{E=Hc3{{ zqEUF_0R(nf`cTpAy(g0?pBNFFZy@w?o+h$2?M1st0)#}`S+!cMYL(nohUXrf8i~IK z<FwWnu#>j#Cwgb-g<(JcR>n6e=C}n3*LgvuYpJ3e?3wR6Msnsz_p`CWd$h%To3S2p zDA+@Zp-4r~bCp1d$u!S?HuXA&ksng{wlmn+gxQq0Wz}1`&0>v(4#AYawb?w}sUzx7 zES8LakXL2uJLtA%SPCp?VeQH`LTc{!259bC@zQe4{?)6u*x&Pr9o9SKz%As37Jp^s z&YQ?E&O={~OM=f3L?^@(cZ~O0G%A1i$qHOJgo1H<2C-sFI90Aq4e!+pIcY{Un!zHU zSjI*Pw8zL1P_(RStQrkU;7=9KVEud>nSBYG{}w!~fn!~@NjTyC!qfNs>;;2)4AE=^ zQ($yl;Pegdn>YHe>2zN)5es!(=b-V(3MA{c?url}Q{0dlj!r=6)Mu9W9;D7EjWiA1 zxzp#wB-Nn4vf$n>NUZB%6L3H_BD#k_+hIqx44vX-{+~!vx<O$JBD$hJ_fYVNuu7GH zJ>J^h)M1gOjvXc&?TEXbfNXJu(ScKYJjWIR<z+KS)1M>RSa7^}Dz<H6yx1@Uzx#_y zhdU$b8@fO#SnxuqP+Nayy?%Ylud3WcmoSOoeYfa(%0w-Bn<xBvlKBkncjE=!v!5u| zk6@Htmq2n-rSQkGN||A2`OZg9AlVDozK*tf5cC_FyVMaBmnzn3xn}`g_+F0>V%GBC z$uSHaTtwXg+Anvb))Z9g>NES*k()<Vqck+Q@4KKK>HSzQDZaK7)3*4Z2arRg8ONgq zn<@U%>U*&$6uZh$%emt=mX=5~qf5eRwyaL-9vRV#MiFu7cr_``eo<Dg`<FST9NXg8 z;lI!DBK95_>P+sJB2ZQwq1B~5?ApMDtKSInr%!8!|1Ne~?oWMnR5x#gM##QqvMXPW z>ucYjE7?VHw`5`3Fh(gn56(8wF_Wi>5aCF0=Ndk8mBGrt*lY{Vvdq`S3qB1O+3C{A z-jg^F$fiSq+gsJk?ecy&zqG*C##O;Os;joS8=Rr)5Yw-f={Tu>K2^$wmxC<+_CCDB z;noA88Uj<l%6(ZXdQ-4zMk6+kUIfO9(Nefo9{%e{VARwGg_0s#6$?ocGgT?5K_@9v zvh^E?tNoj1?P;YkFX=NVYB6)E5&6pl#^F%8*0@U{8KG-D<uE$`O;+OK)9Lxt0uS+# zi6tg>%2PmRz+)C!L*-twZik5UofLcXE#eE1F=6H^-rAVbhasG)KVwH@34(Wj?Hw-$ zQp4W<SQ)C~<MHA+DL@&ALs9Rn6;n`(H#DrApG>h9D{)vMGeOT}n!n++E;8zejiRAX zYyaR0L3l(wDUJ9ODu7YKP`PV1y0=$CGj7mml^hiDrCuQ_v8aB#-XSzCi&>Y_iY#HZ zYcLLgkXy-;YLr&P$XdG2X3vGuFycp=RM*lU?||@Aq$NIZMri<i^|w_lkzPh!Rhzsr zS5<3#g6^XAe)eB?r5yfikH5piNG`q4ERR}=w{;bDn2H2sp;EzuW?64GKdKj9CK1j> zDyCwzchl`B@yFGL=8gRBZg$k06N=h#Rfoq?WA1ahOd^>Ql?CXu52BgPz@?!(HfAtq zhi(V>^Kw>DhH2INRxHM6&wi6A1_QFF{EFvlhrE4kQ4SYF!%2K8-dO<<^+IG%$`S&p zRmdKEu7unN-^A|nGKK2`OxAdKH96n;goxv~2f6Rxx?T>1V{`!^?Hp9-XHV$sb1-VJ zqo;hof1E{3?V`V*B0AMf-1P-Uo6*bNEgS)#GWV?6eG>1ayXBq_fa&k-Zo=R9Od`Xs zk}k()lc#1KkcoPd+XxX)kKn^pRf=rWU!2Z{o|V>xJHD;<Ga2TCQT-*=7OcxPE_HpB zi0KKVCX#qpLkgGft2B@gOCa{!c-H&VdDrtSaS>1=DYnM|W-A3KQpXnHM@;d4Wcv8q zzE^5L0!j&sH8HyHM+o6>wF+oye2mj4<jQ8(_<>&1*&Qn^nW-lG^6E<i#!_f<7liZ8 zq6h>Tkb1{J5EPcZk*>boZU)@GLye+vDS}9Vo}Q7}Qm@eYri+jgr#i2&A`yMFihB2X zvGA;uPjJ16!g{C?Qcunv=2I(D9TBH=!uYi;1)}?7U?-G&Xreu=ONO&WsQp-xtojnv z9w9p6hVKjtHv`&MD*2g?5L+tp{W1){eUBa&ROgcsi(V4}IG*?^|4ginq3u$I7i)I) zp~c_87h!5Hw6UmClK#`07EHZq>sCUdZQ@JIV6G7h@|U>F^Ttax3CrWm+93==i=K5S z4c+WaS@*E00|({+D<&wbm56JZD3)hYGIn7TH_jIIoG6cMePA}!N}hg*(z^eG6&bV( zbW0*j)v6j_k=Y=3#&@gC&^Y_AhFI}H``R23tWIzu)YA_QM&~EwkofiRB(P%9V|u5{ z-cYO_lulz*{R3o{)oHHJ%CH$wTW3Qrd~AsH_3g;rIdfDhSkbuC`PYyv1CRMF?)9H4 zzPur&8a>W{bJ>HxEWR}Y{lvrdbe2<v=!X4O=zn90h5_=BP1nJR?rFcMk+RYiD-o?B zfZPR<Lk_BGzbKw>j*mZ&B)7+z2>#?b+?2INjw#>NDzaG~`s5n=9Mj0#c7ANi!<)}X zenkAf_&#p?(ytn%1K#P|KEC5w+g>A*&G6Rabl%|vo3hl`gd{mbuFo|=5Mpm>&hn?5 z>a@9AG&^`0EG_*eh|1z-;(Y)+d?IM-hR*8RhyLR*(%-;c)@ejCJ8^+((R7Yt(R7hB z%1FTH?dke9c2h3i6C9mcphGv)gn|!PYvZ9UuR;#TKk3^!c-0F9i>`9A*LCvZrT?7! zzPzV7V9(+It>F*x60Dt7qnGi>(DhK4&K3H}2&!YnjWq9|y;`bhCr{6*hw%JOw<!cN zECI$g-jexf=4jESFcgs))J!b7(W*=)B%M3GBv|Q%6jdiQ(-ZfS1CFauDR;jE1+kMl z=_W+%W%UjQt+V+^%gVogW5~B`Kl@-vqQPzJ%!2R*?k62_uUIqzu`|*Xp*CTnN(YZ@ zg4HP!$3;0RjaU>ig*GP(!2oK~YI2#U8USAx^Rc*#tMIV5!3e*}x*8bbuKgQVHl3S| zz~j878_uF@H(%l`Q3YjsBArCxy%gc|D!9Yr<Po%DyMKJwO~7Mk&ndE*7g=vRU^qx? zT3ltdd0#7@$?Du_X)%X*W_32PV*C0Wx$U+x>_8zqMQ-&iwh?iimGUzk^(NIT`}sPt zwN_i^)&r^4>+Ld2-|_Uft?Z^}F|V%DsM_KH@n?Q7(lc+5X1Cn~+oPTS?Y$#V&G7J& z2yr#RTwG|UwMX8^mJIMsQ$Rs%V8F@J-o+|114W~+1X~9O#Q^<8#Y?h?+r3j5KY|F( zRKPH^cD=*Pq}gfrr!{%;pxrZy6Rr)rB%)REz+vHLQDk=RYu;-zdkcKz%WXlCY!+UW zph=21y%z&}NsE%rrjd=;W@Ao4`L2w0s#SRf1zeYifD8Bu{peyK1GifQ%?`sfE|(@C z{^cN{tZ$viMgIbQGK)Yq%gxV@3MTRu3x14?T-hV<RfyGrz?Nf{*#6tr`N8FCRR=4W zqU$9sg6!G&D4lzrC?>p&gX>wddo)h8!kEf!rGkn?)#J;Ncn3xuo$Z4Bdg#fHN6tmH zEHuXVM34wx!e17y0abj<MGW!E(|u^(A6ZpPvkQZ6*L0@dzYpi?+D!7T1&lPxy3W|; z#6!J={7W_zW(uSrr}Ctyw7bvWhTF*2N20HBLS!@pMzx+lWlZq%a2gOYJCC5czIUUg zVf3%$Na}}QCPBGPb9H-k0?er5Sn<YH;?3&j2BlA<7<qol<((<oj6fsX{=6QyD?=Gl z9sETm!~{Z;@T0+p5k!y?x0y@rrE$vTE5<+mdP9nXXM6wlC(*&WRn$lCI@v9vzWz+w zuHV!itMYQ)8%yoHiM_s~aw%v?{pVglN6!8o&Q``2M&ahj=jdG=Q<j2M14)Nt^{Yh{ zzW@+QR&MMLpUyIu+{B@VsD5<Rx84A;{RU^o1CZe-2Kd|H%uUCwUr*J0aA~dMM!{#I zS~gXqiw`II9*gflRQH>K={~wpTA;g>vWifr*ymUYbx91`wTTWau_JvK`fIVEyNqY_ z>;%Ljf<)y?vV{7Tw>kM?813|7F}0T<-En}}(pU*)J>`kOi!_)OzlXDlA;x+QH~H2j zM}@EKHJCoGbDargQ<@{CQQ<Wn;}{0%m2bC@gIllLJ<-=;Ar<XDwR5D!qhiv`U<Bjb zGXZAb;@ZEYlj)ggH<x5(!WuvH=}Q_0aiyXa@VmE#TyP>Pa#hFu`iRd~lah=Rfm@va zJ(b&5k|=i%y7aV1?qr_028GsvSdaR`_%&nm^aTknany?9dLigby>&Sdz#nl6nsCv+ zp#)xh4H55v77a6QGJAD;oMvzzVDV0$pJu5XO7CBktu#u$pT$1vo0ul7v!Kfy$Kjm( zwZMJv)Qy0&_Way&tBm>b`|DeCxBFTHrtOrp066*D=LT$3_}KgY;`7>n{{ANLN(DpC z84t~z;l*8q8)JeewCfg;!;;M^-1ycXDvvCW$(pI4hNFT?XaFKaG~;$|%5AHb+A5k} zT_&5<!lX0ugX6<4fe~g|@-ryPAt2wkm1^^YrtvPJt8Ly(g~y%vI`*jN*BTo20LRSL zoan%bmgs#g4j?2-FzNiL*yvV=6$p4tDJDj(Wku}N_F^`Zf1PKboxyx^cIXZiG~A+X zjHb)QhiZ3x65&5JiVGIv^w&Oam$LOtrPf_@x|;}VGsv%0V*idsH%^{Lo6CU<W~TaS zVwEn4R*iD)O@Pm#J~VJYlp2Hs&Q(UVa85G%xlPa$8j2n`fav{@GG)^c>I5DfMzl8z zDMhyw(j|9_EI&TfcT9D5Ms{7?YxkUl*<kZ$u*dsWUGDScdluU8I4qzof-QDh;F6dd zNauRXJY8PIHw?kzZ#-YI?{SQ?^~&SYu4wHcPY#7BJ8=&@<JCu`Ph@Omr}UZ0G;)FJ z@~#b+`3-Ifm*Hy{(hDv|wj#WaD|$|L7vvH8x@YINdA3(`oU;gfrdmX@jH1u6Z^JBV zVw#T`N6hWlAZt9#KI7)dWn3`h9BbU5LZaTauo#Frna_WaVvmlHs;J&JiBQE0^MF!8 zBs;Y(*x?3~6ivj#PCx;7B0KPjWM0%KI7!HOHBRjHSJnmMh_FZmvZk}!-uiy1yyxqn z&+TAe0<b9fVdKTM+5POky0Mcjo!2Qf`-16MY<2f!sOhgPC57gU;4gm6tx=TE&+Qr< z3qcJHkq}Hld7rkUGI%GVXjb8^a6sDX`iuHlO)wSpY4x9d`5i2Px=$VB+x+bp6&Jex zd42GIMB5P8;`Q(HE08_$wSVu?R|p-5LQc{UBsDE>FGEfsZk+Z-m!m^XkgJ=b1LOK^ zF9t<B1L2f7q0@CaiyCLnVYyad@_fZbH}BJEI|<h47B9w8Eiw89j!+XyFYzPnAsH4Q z{hE6?4r!5ubR-|{<EIf0o_YBTyt4Uj=&S>3HJk#o>*`y<TCz8i`MvOj<#oD*O<Dxa zU#toZ6}Z*nYp;>YJ+G`*Y{7p_M`pr=4)XeZQ5mjX7rufQ8eQMt?rqN&R%{=a9Qtk; zI(W->l4vT3tDat@e;N@2L9tm^=L2_o7Q5cAndGKkI~W|_N6f_)Uw_?QY*>mq+sz`Y zHKwI8H(9R}@xSen8l37~UR{BjOL~zFXbE4AOh~Ex9~V@YF?hE6cp_9c2-=V{$`&h; zO(r@y)7{_P23R0xyUhoOFgo+FxFiTkk_Yb^+WPjR1!TIc<nK;t7*GdIZK9IyV8ari z2`ggL<TUeN1^b{YIdH4AI=DT-(_(!o*s;5TvuoeoQMk-4OKOlk4OjFy8m;67m<|h2 zk5BMFnJ&WpuKF6ytL^&KuXnekFqeF%xYG5KAk;f2XZbCHzgBp)i%YZ3GmzwJ`p^#i zodb$eN(bj`H7P>D^w!4kl02Sc{CvGbtoz9wa$+)zOAEqeApEeBP9*Xb$KoXyl}H0a zy)}Rle@czw@yxZ>(={+nyU14VCF<a7H%<NJbG^N^V%0Yrn6*CgjV+!i897@h8Lx8U zD|E|+pF-A73x~gW)^Kuk3K?E{T(pVb>WIOwr?!n*b3{8glVSou-?-#c69>rk(!N&n zO;W#$A+sMeA@Q3Q3zCrl*q%DXM11iMs4*IHfRcWfT}V(;88?S-iL_QC98Cp`g%Cpj z!>ssH&gf#qqa6hWpHpMBxdFMa2jm3(UOzCiy#qnZO=7Y2mjmrC4r?!@xOpF+Yv6^; zR9aU+wr|B-d;tzXIf9mKxN73r<>6sSsPInZtscAnl+3;?@{#gOzqaUjBhK_N4f}L{ zourqt#IS-l$t)PQ(s7R!DbON5K(D*feJ7V}GC*8buwu2=3{2?3U3=a-yX;_i3nZK% zm>(disH7>|aPGMDY;Bxs?-d!C-~<DQQzUeXSynsQs`#*RLD+h=aDHo#k>xBM_{Lwa zGu$PNKjWX}Hb!>#_j0{im_6O!=fxX*>Fh~1A*5i7Su#uA<|09+CeyzAU2(r)b{cHH zMet)o|IE~R7dyh)+L>Vqn6M@xYXTw=;JlkRDkZ6Ri$?&M4_5Aq1jPzMnJ@CG(R<=& ze#aSi=vB2W80V8y&v2Dxck^uMC0+d*m|URUg~}iFdzfMRJEg;UdzrOn-{{*6>YMg1 zoEOU?nStJ&FH3Skuvh6THU#dV)C<z<S1Uod(~~t4d`M2~>BWbEn#26iH<rw;&%A@D z<%1sY>R5n6vkM4Lt;*9A_(d4MRP%ypx*F+^a>7i}H%w_b+!H39LGuyJla4>k7p&f9 zK2{^w^hngr;F=RTaPJI=>~=On^<Dq=V4~XwBWULOi$zc9Ah%BmD}%IpVVG!0<*^@C zhjoi~@MGV7a$cl<!@9HCP=`Ufyi2UBD#=lY*sLD7TVh?)zvt?f@`!e`O}CQ}td4Ho z>|AJ@!WPbi{hH5yT@#z&*8IBsmHq7TI8x@)D~?6ZEFj9tN2kp-<am?!J&kIFhV9Ms z!RHnGy&WbAi4rp;!>^je?oX5*n+V6xKRL9Xqf-riGug@e2WK)U+@tDBgnCUmgb6&c z=(_pe?B!Pt2Q!+I=uX-ic$>y7UZ5_HJyhp1cz1}5#A10f+HplD{>0vVw@qjvKcQ3m zD_HM$V~J*);0!75+d`spj$l3{Rg~sc*xIZl>H8<ImP;JJ`xlYf9@8AHCO*~<r|!#A zCoA$7NZh4VNBg2A=<3=b9WCVUey*N`K?ETf*mrs$a`%ndwH-)(EB~0rpI=bc(u$Lf z%jjz7N8HbCYnz({jb}x|^r`0|Md<VrJi{{I)rgC86rPk=<<_0SAoLcbbYS?K)pcAR z1Om1^3|=wnajvs2&jTfHp*vNZV-c~snivkm@kSsuj}y*aGWktL^Pa-)qx>1cFW^#2 zipNtPdwF*@nSp%|K*H*r1bcOI42_Z4FRKufo5+gX1`1K*yge(X{Ju}0tkutqk41q7 zzt}-0j&{)m<%YAvPsz-bgSdl!t(2#~B2;tRZT+?26K$Hhsv_@x@pG~089QMCe}&aP zP5b>^@GO0*jg;_ae6({0c@`vNgYcuWtk>#iVfG9=RP&^FB@fAY(j=Zo>BN+Hma|WL zYb1&=M#3noGo;s1Jc>0P9L-UmhwOsutVXx4TcbUjw8GD=VLm^ZYQU}fPn?q|yLja- zy6oYzg>m*>d@P3jODXbxYzA#2>$PT{HT6|;Q%7dcWp3$&=jLp=j~kEA(>#{Y#u*`G z7Z~^O%J>MTjqGB5b%*|FqS_tY@~I0;WsR`Sul&}6x0c2ea!Pu|In=XdXe`QAH$LMk zdTSBOZ${ZUDl<R2WfB~vwRx%a!^I_zSsG<@O_M7?GnhaGo|%|*t7FV$I?W5FpR*O8 ztpQeRy<KxXu~2lVe#2<x^s|mAVAP~!q^+u7N8e%^LDmNWLuWz9lQ@~_l7R6=&xt|J z9PfTXy(jusSS5?rCsfYXk6nH5?{@C6G(MXYeh+`*s?NdhlA+`Jd5PArT`{-oBUb>! zy>Fc#tR6nE;gQWgx=0ruy=^0z7xJ2@H8pKH0a0S+$Kwncn#b{}`k&H1TNf{b=D#S9 zyG4^opiR&4VQD_TnV0N2xVxNkX5~%-%w(Fu!n7<;-Zg{85{QH(ZEq(|hXc!7i=9D% z83vNH@E=LhxGohYp1s~6n6@~d=Q<rmYXW1{tMKI<&&NaROXrBkp!;39-q>NAJtm59 z)jhQ~2M$O2&$?bu^Qyshhpx$6g=gFxRIG7uK-L9_=R=bwn{~X6_a_Dif3t+f*AWX) zFgnFDm6Z+|p<UqqR?()XroIcur!Rt?O`ZIj;M<+ca|R!-^tQ_t+xz{bnS<*g0`^in zS=+r}6-`0|z5P}{Ngwa%jFm-tZQS$gV_1J+mEa)YgjoZ{0MQY?(^;r^ql-%MI4bY; zcwdeImALc$YtMrse7C@R@6C~1pp-eq6-PZH-3hM7lFmAXe7Q`ec1wE3Aw$Qr<lbeF z3D!Fr71trl?JBF)X*T^~Vj9#Gi+nl%h}qT};5m##1kZaR?AVXD<?AO+^_ElG%xlf3 zy;;4pg9^QbmSrZdlr)GdG7BhAHPOsZ9CMKobk;w`En-94Yj&-yYrz{Xn*?t+o9`J2 zoHP{?Jq)X1Si>VC&)K&Uw~i&znj+8Kh~61L^8Pewt5p4JMy^G9cD#>rmuRu_!yry- zcx5sphX%E9S+D0)zJ{7$4#fvSn^UXI7wiwCqCByWFv(^1K2dp>R#f0Cje^X_C~q$z zWLv`Xyf6&-9L<Z&d(>5~1I%KDu>8T#$bpygNN$hQ&SbMgEcpnH#aI=+99hw7Tceva zv#zHwCtOsfoP@>l#^TJd4A#0SNskhMZV3SObz!j{6h=sHhVyj1?YUrnX#%3EO04&a z&z`Mk$~Jc{f>HOfH!nwVaTnc0gYt5UL5u8ZO14%2<!I8#N}*l6XXvtWsPs!$v0wM{ z4+mlOtjpaAT0`mT&aV<}A?&@=Mn4q@!>wpcb%(!~(LbT&M3sZd92#;^=3~RXg{XcF z(kR4t8DKp8S=8`&U-GY4?sdugELjkrLf3Y9u}^QjFSp!8i<qaGG`1_<k6Tbehe)F7 zzftTm9k<w(KXv!;GpqV_wuB-{di#EeGPcrY1d-#Xl(zz9DMThFw6bjGtuPOjY|Q=d z%vbTQ8PCDWi6?L3I(~fHa}h-BF-ALo;XmW$49L$b7yB?sttM-LwFcb<|4Sz%%GCwC z&jT%m#0}?K{wpSTl1J>NHB*+BQ~W#1X<IxeL2=V*{f%6JRi8Ru*rP~z?nHv$2MKuC z-d1C8rxJarj==3YL4&AYWNwGW21iLeC3f3Pq3o|H2On?jQ`d>a9rS16>mqcVS>+hL zh+ZFV1!RJ*lUfhGqUdV|88WlmbuddxGIbJ=CLwjs3|(?joArh=#!?oUyLc_zBkpSV zpRd_Z_S&POxoRCo*)km+C$zjk^p^t`Ay!OPYT92nT4Fa&YQ`=}bi8Q)R?(o{pVA3H zfP9`P-d~dqgmi43o>W^-KwGL%XhFN0I0E!PUvVC_$hr+ug!HgmXY1=UtL7M8kI%8O zgJGhO*;_ALU9tw-Qxv6GAn332$u#N2aeu=rQE@FRkoc+72aIO-Zq4wZ+#n@}tr{8K zQZM89?!aBzo8<dZ@(l}~2Kli~^j|d#xSj(NnN6uoAUF0}EHnn|q`7Ae1vT)gq#!Lh z?T0mM@o81DFA|fxB)59{(=L9n#*`Br(A0sii=C@_28s_?b-_c#k1NJ0t+p;VUYRXP znQi%~b;Z)%>gy6C2O`~C^@XQDM6+hPj)m6I{PWjn58NDiU2NlYTJ!6D)daae4+b6T zcXxc03W|Qm{g*7RrDMm3yQ{PDo{vW!%ye$WWslH=keR-2503{JKJJxP((BQD95$gO z6JE{$yrIQ`8I{CL=OfQXc4~R;`wCq%h6fxi3fz@8SQnO_UKo}zBO9{<;c#o1bYvBb z&pZOy$M6&S!cZSO7o;$*yRblZV|gAwfvL7kA`8E!ChNKJ==QeG=P+*zM#W6NZp$ai zZ}qz`Q)jHa=2e*(0*I{9-EMSatWFz=FL+4NCFpy@e^9=kl}LAt;X^vjc59(t`sXtb zG;xxOoLY1*V?Vy6qPTEcaCn*eKi}ECIsK8ji&EI@vq5?uNQ#*Q-0JPcRxyu=2`Ix@ zRYlC+zP#^cAz^3n4Cg&11zDWhcDezHvDEl7#ZFYC!-@=6ypfMpeU75MdU<1Yc=oS6 z9W}n$I-afI^<)D3u7H!M!O<(xaD$B?E7K=X87DJ@82<~EDINVB${4aUmrjR0Pn9vJ z(=%(2%W<IhPr~-AoZ;Hh6y2LR7xRlMRH=uH>zs@227+_jLb7E}R$6nFjDErzXts^( zRt9AvRo_yI=5(Gb2I(7<YGshN934)~5;ug&iaMS6<@k@q(1GaU7pRFHr}tXT=NxDV zv!{SS;uEwVPoJXd;P9Snv(NO3E-hGhJBH0&yTf=2c3XIFN&&~@cfy(1qq5hb0*)(l zKb-L(+bleavKY781qB`b?3_aZ>r5YYT-PmWPj~+|JqIa&hrNMol<!SoQ`h*PkVT?U z?445iXM>trVW3tTCy~``k=FYyP%p!`&TGF6G=a*{`N;f7`IRb*KQ{>TlL+zMcVXfi zyWfNMI{sI{t|txWu1XXWZEv!wD6X-#u?$yrnw?#v!%^I<R$S#Lym1Ox>vcnyn|X`A zeyOCOn<_1m$JbvgX6ux69)V~@249*^M7%0LYrbwJUGyYLkW@vv?t|SR%PD4DsQiB! zPKP0l#4!!FGG^JlTzh;96?okPZi58gpDqVhZBQAqJjnc}j|WQy>SV1hU=U6R^U%Xw zzx5$JIN_--U0HQ6*Dh|j`#X=8*#gd<#lIDA73e6Uk}&}dv+Rd`Z#;;vk3(ns%vLI_ zT!uk=5V&3%+-H+4Rwp#vmSy<2>P_&M+AW?bOs5;RZ@q!rT#%Qq2@2OG-iTdLNy&oX z`EJ=jw;b^eW$RQe@FCDvAv$R?%OFBe+SFbip!?Kyx9vI$<mSS*UweG)c=*!p{Lor8 z=Nd)gY5R5VuJRe9?f9>t*fpB9Ke4uYR|h}%JPj1|ek<_EZ`FsdKHk(Xh;qbBxm6zG z*3)eX__1tQNH>@A7=@`k#VV<=&C#*P0+UYFxWS_|g0NCP@Q1}vrVmwjT|Vr(7qURu z6{%FGK;XE5(%sBf@o~Ax-fDBsbKv9=Q|HG-W;wNciL`4z@qn2AqWpAp1`y4b$W0{G z{G?aBIeZb!yLd_ec3D^@AFkO~JBaoZSftcbDod8!(qb+S%Wx{eO>V@Rz{b7tcO#K4 znZA5wXZe$p!%SzsA{!434gMw|ehWGG5rg{|)5I)12ctupSAVoCnL!p*yw*`)MKqD^ zKqb%ZxW+^<Q0IoqifOjudqlpLP1KQ1c)!}Ba`0y=ofWw=Jhkh3WByxccutc=N^moM zzH`WXd}BhNOB2;{hB2#+uHxIs=93HfFb47Cm0{z`XrK4M-0L@0-*^VrGLfi1=$)nt zD(XFxs=y`_?DV@3F!Cb{CvsaEcLDGwM1$F)=FL&%me5XbYK}Uz42AAodqq%8=YGZg z$Wv7HoEepyJ+4F!k=A0c6*AB0mOXukT&xEpTAs*kPJ)8%I#yEx4YzDOcJ`U3isj8? z{5=sL^)lyq3U!)z&p5RID6O8y9dJqkA2{gCVvsD5U$V{alI$i)%s9B4YJwr~ReGhv z)NbM+@N{YLPfE&ErKGkS)S@TX32XIGcjk`A#K*Uel8;*9eR1;b<mR$1r?^q@h5k?z zKcH(|?;PrglT)1x4?*yS^*NJ5H&@Lxpj||DC#FCfm`r0k{<DV%Ot0<H$!qUVRDWmQ z+oBzZUKjb^(;UHV*}K4EhO>BM1g2JCB4>_G>A3%WFy^3ra9tH^L&;p>cvvLo=}Om= zW6&$`Hh=%O<M(9=fxV@d)?f@DuUduTfq1cS)-%~_6wv#A)+?&6lJAVKDHbXW{L@k~ zYK^}0R_f=X7t?Sh7c_X2m_o=n`k!Fs0W1uM%WRfS-J~ptc{>XFN0_?54iF73ZqZ>> zyx96ML3>uZ<9SfKUf1~+g2O!*{6d;;RN?jv5W6jy=cLO$GbE{xnfP!n-AO^jKtzgB zCra5MHb^G!DLW$EbHAMusPBicnV#`7ojdrfjbqtui!i=28C?*nXB67Vo!4xx)$v+M z*S6cl?%cGjj`C*I!B7pYBMyNiD=3)yDG)nLY20y1?zn4`RzfU|dQBDKsu#UDj<O_^ zJS+&}wM6dgILW}w+R&5AswEb;)FFv_r_&$Rj@T3V8?&s4n$3bgJ@5$!&Gc73ccA+Q zMYT<Se1FwyY|SDxwRs!(I|5x=pFW@Ou4c#&uBO3luEg=h30f$IkSqU!!gbBBw%ijp z>#G3!yxf$}>Vpvv2y#Fx#%&BSW#B$r5(Yjl?A)6VeXKwe&nvD-uFyNy30EEU2B+)J z4DFrK+sNkNWuRZ8qjWbvYVm2hRRMKxM(!R@nt0~ib8CC>AyXFU_zksv2R1y|{+oD9 zdywCcXv&qP3|NmZB*&!byefy5clel>EBI11Y~1egnkzJ|uGsP#Y1Hxtu0jq;s3HQc z2SEtU+B852+HF!)``<pD!pg6f{^yp7P417e!98D%m^KGrtPI}NH{q#s{G<OaE#k&I zC$+Lq9fT+{A1cm8Kfhk0zMD2b%}BX@{6mF?1HSM|+t9k4kl#MO`*RgRx92|Rh}9}< zb@8KYV{GR0uV}459Umpwb^^3&4<8$^%P~?9&0+aSxc$c2>4>|Ygn+FWB}WF_cRX9| z9kB+_$y2<Gr`Nr_(NC!=!LtmVe?6?+=mM%}sw-JjV#&3qYXC$SP&m$u)^%j9UY=QX zRjb{{cd4kl72o5C@~>C&uj}0tG*omOE$k2%q~Fbx(x-aE={+Ue$6BiAIhN?TnyL_K zsS)Rnd7OwOdsXpgf_4y0`0g95ukk8m_EyksVJO@2eI{l2meyVsvmZ09qPU6oW90I_ z>MVg)_;Z|VEH3^))KC2aX>JY9QM%3KuWzdwbf<7@U6#Q8DHemD%P_=da?uKMvUb#J zch7U??7I7?%<fxfjxi>tTTaahmDVYNKc{8+3+&In_$fe6IHO`7vTdCTIL$rlSZ&QB zA5hlc7wfW|0c$`oRo;&$U2ntHy|a)Eo$l70M<<M~W0v9gIHF?ihX(j!ll5kg7Q(b~ z?j3Hg2ewZmn3-_RoSLq?k*D^RX_E_?_X?M=-!XoPc^RDDpKSvlHpIwRcpBZG)>_&( zpu}tvatJQx7B0_s0}OCfqO}MN_}>n9w@m~*Odc0px_HtJlIkzyR6bdeXWq{em&_mI zqah*|>C|E^wzxSR^+nGXHK(2QHf@Yd=%0LA$jKRNh@qeUrBjUa-2HSi?-hKLf<1{; z<km1Ku~BoDYyc2_m(>c(Q@`bzNcdRT`%GJ7C?<pFi<|B&7X!{swk!O}Il}9M^iP>b zx&8AX=AN5qc+b_U4Be)?veTveX~7rKr>~9;pLOrPxcDZ|iSiK|bWlB>^9bNuUysCp zY$R|A-2xwL-*kyny;;>>r8c|O%;aw8Z%tg__cmLdEgoI8`B=cao3C^m+tOY`3K{`= zSLNYxdf4p<oN5D_ux*01aZcSS%&Fi;cfOK7I8&yQt<w4)^0tOZ-LEbb%=&^wcYYbF zTz`fVsJm9uZ_i-cDI{cW{Hid+1`B98>{Da5jXFiuz8N`f*w{kDrshC(ShElo{;|8R z`&R1wwWP8HRH#Pk3<;YSR`#{Rz-V4^0MNutCQzJ37Uc7jVO7yo7|Qd6T!@d1fTm<x zo^&5s2gv|IM{WcQbBbYDj0d(-khfxl0mp~{s9vf7SrCbh5y!>Op?!~W9gZ9rnf^m1 zZSNEAeDo8QJkMjgzt^9uMlDm!#vwMH#1eOxjE2Zo@)8#N`_XQdP}*0yQg4G_Q<AxH z4wRO%MZLK_4yP#kw&fI42wjS4Q;~(*;oUy4W{_k$VEI@dh&_B)rwp>}urb;bA(L5m z_>SC?CQ}zGXAS83F#Li!=~6PDV3VNLK{M1DHI=Oj+6eON=#j~5NYZ<6`w|vr9v^^- z6@e?*>{g-Y`*i%#tFjof8~vX0{{wJ9kH4IojuwzQojqoo<QLXVz-B=a_uyNX`D?sF zH?on-cxOK=j%#4Y80Qpq)3(YaSF-3|(w0;4NU)i8kiV70A`_8l3zTjo;9R0)e&<9) zDWKi;QpkS3fG_)s4Q5KT9zK~D6tA#sMsR$Ko~<6zeL^R%D+4eVR2|MB9-gE9IH{hg zWUv05r>L2Oz5d#xb~r0(OVFsg>KXfwRT>WITOJL)AN!!|>X)B9&4c*%^1c00&waoV z5f8G|1F#OvdTjns>b@n>SZs8J&t4zM_!$F;?VqfhJYyDkJaM&?Zjm?yDE^jBo(^W? zma#+U_0F-4O&b3)c4BNn4?4?w&Df0_k6a7hWdqp>*6<duue*`azVPwV)K?!5<12!q zPkkJnM%M#40q6hi$Nw}E+kjmNYfKl6D(=E<#mShI!AvKY6E9ti)WFg6dk|oipr{p+ zz$<v$JgQQ`KP!%)&=Gb#(+Ovx5ADsZd+@AZYj?NlJzl~+E*cpG-SO-D7abVfy<?JB z^&2|M!f=G$)0xCmru>#GsspJzko^HWe-I~uOyt&C)X|_)4=mlhc{8{^h97fwy_?R` zHP9`dcQ_1gDd#-`Sq{(+Sb5YH9kfpZdQfsfmZ1-wHw>DBukHq+#^7|WSt!DD4B(4} z9`dMw@%`b5?~25>2?)?ADj-?AGUWkj=sHw8k*-%0BnX4->a1NhyA0S(nT5}eK+A!P zeA383S++)$*g2CB?Yr%Ss`BLHBL>r?>EzpGif=e6o+KAG>Xy1je|JfVp_3-h-6NCK z>r7h8=-kD%Z}}g9`dX7;KhyqQpYm0L2;>DG-97GNa2EhhhO)SZj5LI^9+b)V@FoCD znS4#kU|TVmK`)cMUKRzCQ(v(^r<T`5D;EkLx_Nw=MNHpeuI~D&*W!3?vOZF`;PpVR zItY*OG6-D%(vISH-S@xxquWs$>bJzB{k6lH-OuR%nFOtIPTmUR<JO0N$Z*8RxuGY| z{-lG~X`39C#|~JTb9WHD=nxneaOlRO+IFG*>K^%9or@p6D6>y7Xl0-996$c$wQ}hF z>S13Zo!oRVAN#4ZPc^uBbpWxQ_|E3=vaf@#einP+L&|2I+3vMT1<RL*AO6uF4YzrO z{o2*b1k(5svMX!&BjxlRXJ6(=#182b^rh@NQeypak@q>Js%*E&v7iGJw7bLmQ$I3b ze28~ApLl^EGdo5Q%(`a8+CnG625v^=#vL~Wkq<BBMg?se9Sm51_`$^loX?znnRll? zN5GmNPIdPn6}Ic{X#9M^03kb^4LI-K;dA>IcQv?i!3{s(A?|BBe3Hb;y8j;QT)(os z`4<9p81t!V4hZRaKso2cy7DiHgJmh^yZc`Jle(}S^-sYRcPgM3<X8ZR&<LD;P@^eK z8b60l!~U`Fa88**5Im4dWGoH58qtNTF~r48OOj6F#L6=ufge@h=#e`0nlg70Hj5R8 zHl<(7I0uXYrR;EKVzOgLPu3Feid|xN^CGW9S>QDlhxk!HcRBk*g7l8Vl^b`4BfK~H zr3<eQNAPoBEoDl*V)N0)&Hg30I#Mh6`89U)-o-z>G56~E*M=7f24+_?>f{F{m7PCr z8NHB~OZr1@XyWsZo!9wMx}W^yo%~p!0q5iXa3BF^y|Q-FQ%6>R>;NrnZ<~Qk`U}VI z>%6w%iUDVKIA3^!fb%P_<bB!c=YiWFe~N#RZ)I6u(!0Yupg;V@yU-`#e5`gj`y-vH zKw#u2A?FF!M|>;>QA3JoZ}<3-P~YGD(|6t(zWu%L4zCh$_Vpmvkv2<TRg&l1pho&{ z>QdkFhMPN_d%)Sg|Ft(?=O)pK!qq*Lqbeez)uo=Mr~qIq?Rx3cOT$O+f5^L}&+wX( z=j(?Qvsf29(DALp2hBDTd(@3l1I{<F>*dQAGakG_z}Z)OI6sJ8Q@3KPKl6>W6X-z0 zw&77*xm)`a<gl-`AAONs--oipS=|v9I`&`b3!$bQDkg6HjQ+^}@!g;PbhycG`19D* z9}IN2b@{#|npITG4=HtGSK%M+;T}I+c$<LpZ@qkG_=Dg1jTUgm>hKE+2+B|wMWh1G zjUMB4cD;s`aJEJd4OX7XXuMM@ZWCxcnpZy4%ZifuwsVh_I;IW4{;?z_H+{tnuw;-* z8cOu2fU^|9QZR$Uq=n3r$QL~Vx3QS>0|U<K$F-S;m9F&BMZeP@Jd!H6Ygep<k1UJ> zIah>^Bk#xph(|s%?W8zKwtrg-^rAxhwvBh3ZqJz<C2s^%|L_t)452tpC#6t|S9w*y zcfU+W(k_A<i29P0ACtDp34YADU;TOqDCvrnc|Zc6wh%mf0(=c$*kw$n;c#rhX4+oe zlq_0ZEJdjxsyRK^JmhGX9`;%lo0DfUUy4cAX^@bU(*<urFdoujbA#G*C2KelqhmK} z%F;=3^gP!kWN3DXDO{mcPS1C?)l;vkQO;hl{}_M<)$~v~t)5(M(zNX~XC$-<e-t=` zj(*Su67aJ~WH!0QY3BtdM?Vy#t#I0S_p@N;E7CPs<WTm=UnpIcKta69rD9U<lHKnS zuL=t`P#rc5Q##UZ?2BcSx#7&9)ufd*+3FChQC5GdYX9Hmu)oNMEa%I846lImtgPTW zUe}1$!`#;Og#qUU#tvVjsm>d8$eHGX;z^(PO@Bz2%2ep23OKXo;!4k&1)Q6x*foFJ zS3Rvn^zdMs1)RB{OR={t+Vsy2#*<NU_?j=x1e`DYx)_tx1e@gKwBhW}-g~XBq1@($ zd&|DuRpu$9LSK$n$IjT=FCKX81}vLtwZ}<C_aSzC90Cu4c^vK|SAD(ND|i#zjdUh? z4`KPtW$V|ESxwKJZckF+*r^dT&|EP9HeIgxHU?r5n9)ssw^=hAQ+WUV_nE_Q@ruGT z!*BfhZwAx;!@1#&n`^@fUMc6hpx5~=G~WR|`r!dW_rCrBu&=zh#<s`Rs$4Ju=l|o! z|182wz(AYHLBV7&NeepZbOBR~82k5PRGprIM|W%1B2zpKZ<%)kEIV}cBzf#Mg|0z7 ze@Wd%gcCR`+8+({@mv=$R%YMfEG>7Qx?pvoCrty0%3(mrK$Eh#FgCAtngQbi1=^}< zxjO=Vg~U>OrH6XzP<Av4S{ZC(!dN@OYDcNO`oc8}bm(t@bB{+?4Ne~B2cCRai@{d; z%g05ydZ~j+nG71rt6v*%?hCyH;iHdMa1g|<;P+RLD1$nv>l(Y%?yTL(YXZcJ@b#4e zSDHPz>SEjAn6iZga2~B!cXcb16AF1+$HG<82kNdi!bhi)+g-m*V(|s}I3Yoe<XP@Q zH8K^Ed}qM}Q#EKpM7|k__0NtB0EALL_4T7I^%dV=8-Ru+Z_BJ(?W_iEvsKH7CU}<j zfOEljJOT#jCA0EncoB>XOzRRnx4yKCpKW%cE%11|uOiW|CV7-C>&Aw=71g)rr`<G} zJ@mzWm%Zzx&hcaIkN=Br5>6WNQGnce8{eR;d;*&KFJ*qB3-*|%*p&Jzo=tyy!%6DF zdE2)^V7vkN0+6P-dy+i%<tb+-s!B-tQC<n7Oz{((q!z4pBdz_SV+9|OrPCVq0FUzx z7Q7n<g<(Ez=QSag4|W1hzsrxjaf8c1i#*qPEsH-=W>D6kylqjt#z&FW^8`xp=MBmY zxA{YC9@E~VB402s8|dfWVBv=e*?FEDUhw(hkN$XAJAZDtdi^rHn|ZAL>OF!k^e6NQ zFTFy*`LJ!zKCxNQV1g^8z7WS&1{@Y>19y4);FFK9P<}MKoS#2)f`Bu%vB*HTa~K?g zX9S#`xY8TMZg@WB1hiRX`nr&hKfDaFWrEEHtWV}0_gPf%wId^VXIC^g_UPymaNfCf zV<5_tUC(mJ!qtFtli41re^jJ)=1{0oUPrZ}KYQ<Im602mfZDdQdapy;F8&_h#13PS z7+~RdfUV#L9H?i{rPmiJ1#f#J7kDd6p9>rr_8r+xLqC8gglWK}9htl26a^i=$wwz_ zsL$4Q6Wa^u$Cnd$vu^$9)3dSBK1W%!Om^}`{L;ZXG@vA&?|k0oW`PD=Ou)HzI4^J` zc7-3gJjzbj<--P?mxjwX?+}1~VR-rVH@T_G&UM?Hf3cM|ss1j8qvGUVs$d7&&^3N! z?=Cxox3TFf=gti;vMaw{V+2&jfCA5=2puC7G#wwjq2|ujYXmj_=5K#G3phV_f^)_` zRI*En?YqHRT`7;$tRTmW8`ljuUmY$HaDMHL*J&dJHQhxUn-yEZXQ|;!H@fZ)cX)lo z2Lzm51p8X3S7?9!;Gg_W>GSyReT{ygt!&52;XJ~C^C!I5`ey`3-~R4*c+JSG(5f59 z!b(F*IfHjm2Az|Xlh*^zz7yV^yXOozD+hd(MI8M#xQ#$N6m6W)rzkG*F6j^7`+%DO zFS5g#04+3@+#v>V1-JC08gpU;@a*ICc{W}|m+Slh;uUr{OYhBZy*<hSB4iAX0@#?R z`-yDyX~?G!33ZuwFMs;MN10m~a6a=&`G~mom+DlzK+C&qchOVY$l`p$zV^MJ|D0ER z+#Fte{q^i{_C3xNhkvP|AmWgl0);UTo#><1xLD~%V*mg^07*naR55bv+Rfqn=UyKE z;J0T1XJs(3)m0It-~7sZ#Gz2hHr7tVu$a_bu<~bpn}EHw6kP4TjWm2YBJ4}aC^>qG zs+h1;d`urn2O9px!}1zSwfCe4YPwsV)Y`&Sr}Az473G4SyN^v6!!|2t|5B6!p^$>{ zDt7i<G2)x*q(7NqinKYCMwgKRHn^c2KEl`7th&|jnb(vL1yLd)xrLwdfB<Xdk(xKh z3Koqx{>UyV^~2a)2?>H%xW4AcWS){ouL3MQ&#jQLlEo|B&OhZHPH^?(24LAz@PhYS z`KETUPc$hrGqlWAm=Fv*zIM=lnJ18TtiuRabfUgU$~<03w=T@HO(%iUMHix8OF#+5 zQY(ra1rmo(=wvd^c*@OZCWcN}0^6TPE0x4<_04JHIMNIyZP8`v5FIcA&MszW`cz4l zUEG1|vKG`xvX=$CaH<UMlRUwiq?}POW7Y|e`J>O8(;Pzo$c-oRO#Yx^{S{q%ljKM8 z^2ppQ>c&@?(Ycxq!RWG(r@Yclaminh0;X^xx7Q_K@fK3t8Ad-XI|MvmQ<zz<tQ$=- z>#W#KC?=yxQW~S5e;HdmI*>#Za`El>HP?=l>2sYwWuAuA_Q90pDL8n}<N_Baz6xp< zaAxBb?Z8*`<pEL0Uir|j`yAdMKP@@*fBjC{e2`<2^}4ehYo-FurKCDnf1u8-Cy9b0 zmK7@CY`L_c&9P*49OEJ>rIeLDys2#RHGFTp{u?>}?3W5m5-7nc)JehgRQlEDmNwI} zFL$mTx-GsOr5X0Y^k&M=U}t$VN_)@B?)&Vw7i7Lyu(l@BPc?C;=biaXr=IidA0MRW zv#-^Y*Fd*OpXc1xMGbwQeOf*J@9S;((Q|^$H*Vg@lZ`)p=ck!3UtlAUPbQvz{xq=) z1I~;20q}e5Y_`8Neql$U|2<Bc^{bBq{nf$LSaGmUt+_?e1f2i%KmTzq463*z&|s&; zY<wEaoxv`o3@rH>D+Vmfdtl7Kj)RGKdF=%>+?DHlR#$kpsR18tE{=g417<F0vq;PG z#~;XJM=AMh{uqz64464sLF2G;!P9rG8r*buu^*kJ@BWQE$eKz+4i}nz(WD+u?4}i} ztbT-3FNZJ#tHS7L4#<{u-S6Ra2|nSBI#wPPWnj&Fputry<<X8NgX><8fj#tb?}s|6 zn>(B}iuCnLb=O`7|IAZg1INnf>quPuYnKYF8(>FnJ_gRJ>iOp1g?10Hjk=(h`a`N< z;G<lo*a>}I{F|4%+5jq#L1yLb=h`GYd$$R+v(Pm8u3YuplfaK{IZ9u~Q|D8N?VTpK z^#ZcKC#*6{dzZ(t+OQtdp~IQwRhKT`_`ut|<mcRgv-PHZ3*JSiIKnE4_RnIxOdnZ= zbrNKN#2~!3-{eQ#+@&h4H&U$QenTOK1ZSJF3eezV*m?gC>1ky(ESbx9)Yls!hy-ol zA7*_bOpK)M>va?A(ftaP=;$$eXj4AI7))qWFpHax<TP7F_bC7{-Dbkuc6_W}ABdfy zYq|J6$)nH7dmdoT{(|Cn?UfqZSe|L)&ECqYeYAySz4k;7+SfYq9g_y|^_R#&nLa6O zbmiz%7ZhR_UTfo12DBFg!FLHZ-{HoLa=M$b+EWEKdt0Ogf2H5hw`s$W%al;~3aFOt zY(thQr*v$O6(FmdNI(41kA`)2@?E)piB}G+4L5IX4R_X&lSSv*mwe@bZJ4$_+7mo~ zG?0LA^k9;kcf=A%_A&p<mu_%F3;$m}#%nQ7@)U>`yoWuHLW3I)i{2!{*4qZ64O;3) z_6PLaJP~s7lWW{@W#1J$V||qU*s){y6m^Qe+g2JkRtzfp!+{Ijsr8i_J2$TnI|iS5 zhrWS~Jj#ggM``TtViptB5kpWrv5^%vU6}d<h2|klKJgo1&5Mtvuu+4czN=rPEd9G} zlYEVhT_j~I#Uc23)R*kPs}B#pc<lqg46f7Tm_-egBpX@y>KcVE*`nI!%M1B-XHEh+ z7Lwqt2+EQ`OKeYo0{@HWP-s8VZ}6Gd5b9v#HmR2ZXKol6+}I)D%z7+4oLwaC(ryNV zxP6DSKO(pZ&P8^7K6mCtUfb}UVU^u<%it<&`ZMfkzvDU92*0wPb|i<oy!NR9XX+Ta z4Dz1kl`GzH&q5A++SgH-zEa!dl~0cOWNQBV+@Zh9YZCs336{I}Uwq{pJ6HA3Rr)!g zkRh@}$+A`1vf7nSyUo~jgFxgpf}{Ru;CWuz;7)7DDBF1Yf#84kE7ns#^hv<^=fBMO z<_>4yHGG^M;r1ICJs-!!jLp<b4>(KT_N_g9HP@#ESby=0UnD^5JDgXcRWzicmvhq* z|4E+;Zt5EHcy#F8WvBI}4?kfX;CCp{;ng=T@FRJ%fU{a?6FbW;nR%rr^r7u*eJ&FC z{*d<`ze3Ra3_qfH0=pV;rrOizIZx1crC}X;K~`?EVzptN`PEh4-+bfxwT#(sf9Kn6 zS1~OeSaH*b<{WwK<J8Bw4FuK4`tg+-pRmK(KErn}pMLRd^>wkKeQ(VTV#lC}X<b|Y zHCFptu@ByRH#hAKIG;Lwil?!TL=F`g$6Ihp7uBJ^!teDL`^H<mcIEn&Ys0_y=7r%O z{e$1+b#D5heS^|Y{6u;xM~a<8P=90YpiC*zYIT;H<Fw~nQmLO=A}><`R$HBxQ{*M| z{Zsa7iagpmf7qEeZHnAE(HAU@)l){R1EBIH?q5LdwL5E$_8ET5F+Ua?D83qx$kX8i z10UM3w3R@c&?r)mTIs<_0?4Kg2DL#ofalHj+})5yB0}OzOL#xCq)p6;j*WK--FaGG zI3=05oC!-`6xhZ$`U6_@3a8FHzlIm2MrS-w*7#Uorub@|Hh#hsOULZG8Q1|j-*#-e z<W(A+XWVg|u-`V=?1li&cbJ##w6R0m^_rEBVuXwrNyST>^}t&<adFl2yS0QZc}KO# zDWAh`%oY9Y^2$6WD{0eWh~3nW{$bncbVA8Q))J>cI!t4!*V^Aq@y#<;Ntd(vS}W;? z^4wgFU*$h_DJ4JCxn(`UWBE)6?N|DgEM?E~ISGWuC}&+)p68zRV*$q}^zkZyHu+o> z<X(MK5d7Jfx22Uq_)fpWbt)lUWI64`wNr7a@}kr0%DkTT_cN7`MQ7*}ji+3NoB?%s z<@C?FT1qLf56xKPSWbWL8rV5j)-?15j`3kgS+~lRwweAGj=#OK;5y%%FwSwX?IyVW zhoBv}YQCV))5k$Ce+tqBRNqC`xz2LzHQa63y(@kcBPoTpEdA2&Fb4~ybAe8eV}qF4 zLe$`vSE_rjiUgeB_$>h@sVH<xV*zv?R9{s-!>RVswHdL$^ohPZZ9`w0U?cEoni?+# zjIG;g%d7m)%7M?sz}+UFg_wH|to1Wfq-+%zznX~sXx-;7<y;u-*KsaPz5zsagZPMj zAbo<dJ^jHk-@fqnZRVyouJd~~*M^(CV$k{SaW>w(!0)a&KVDnAJG}71+2Q=T^Q@)l z|LEKDiVdcCoR0o?kf|Qr-yeka^vjj=ab%q|FJ7tf7k|F{umAL4B%o`cGrNcFxG{7B zK&@d;yNU`7Rb`}s0^^VABv45ZK|}W!YTssOm2_7RAIJC%Kum(|)LjHQ@R*l(L9!rq z*OfsX7lfO<m(*Hvmqvof1mo5SidZgB9Y7kPgW?G+G0_Svj^a3^E-n-e9EUem?gG?c zY8KhlQOEDb^C%DBp({;y?HG78ufxi_8`?!w22Jo{Gp-%14Hnw9b-eBl+EH7%7_2}p zfeHp^1DKjxxe^5CqJqg4<V;>8VsJV5z@$;Y$D?wXlw+L%y9bI5gqY-^{szqq3Yw(r zqS-p@wlg5;uJQ^zmaT=8ZoS(}+gs;FLs`15(`dbhk2_UeJZl5(C9ciRIx!%C$OKPn zXMFO>GZ1o!;I;LiI&py<N$V>?QDm`hVs9q>J3g|7y!x3wrH;ah?=IIR>e7xR^`=i@ z|7o&Q$b#BBMrN%je|1#WEnfGs<EscLv%Zx_U#Ou=%D^Lsk5{N`0<6-ZKwjF`6rTY( zcE;~b`bh=WcZfBu611wtxB8hcAK^V}Gatk5zAt`cQZ7Cbq`oY&F!_CgCx6?XNgDEy zZs=Jb1a0LJy8|0}L#Av}4A6VBGKno({l>oF8OZ8^Bzfpx+Dcx^xy6<TgEZPo9DT>~ z*j7FG*hb`E?YEvFkf!p-en;I!UAy>~v88et)G}~uo9#~=key@=bUR3MnU6v1Q3m8t zHm{|nFD>A&xhCH_v<>*GAo~Mvdj0Uf`q6Oz&9~Uue0{jZ>nR+7E?vHZT@CE{URdgF zMH=Yg)Y*kQ^#e6@Y!i4U;O-dNSijGs@wd6r#?uh&cs=v#OZ<=-fpp*7%%6+B9bb## z;s`qBeb~rd&jcs72wq*ge4RV5+=(S1{Q^JimLCrbAa%)vj}`zd{hLRAC~)`Q-C_II zb#^-6WXJQZVHw|AbeFx44A@5aRKSfoO|`_K$)>*aX+GLYow9hMzUtEURj~0(u8=zQ znZ5%2-Y!!A*xq--if*|{%KplEXeY-q+mf_Ho%0f-@AMJVkMi3GWIRLH-L}iT{90^N z6bgLjk@6J5*Puas(R12F!_nu)PxEJO;45*K-QklwYfC(}rj$G`_*9-p^;_UkEnzgL z{PM$9`1cC$A7ABF1S`j$V;A(w@F_b!pF4eaxbW7u`9WEp>cQWYH9m=+6>zS)kX6Kn zLu^d@yXueI5pdoD_S|`YtnU>VB1KF99r{j_H|L~MwZ~kb{cX_~UgyXDe)89UGc5Cd z@)yq$a6WOW0?ux;)wf(w#P|@xFKp|o?4nXX+M#Xws)eiB;e2^G|HhlV!}%3%j`(De zuzWg+(XW(IyA@&m?)D9KIRE^;<Q(O97G8wLF^*{vKx*&aW(Cp@;`h>#KI6$<-@nXz zq~9aZ`}&)25<vHz=iaokZmBsw`kLdFZ9RP=v~^JJu7TW%`zh~%wtw>p3xB-u=<%b` zS^gPEY$JW41<h&;F-rQ9O#{yCaQ^8153*DH3_;#w>~8lJLH32t1>*0LiN?(m>VY_V znNK!c;)cSVJGWBrufOp|0^bG*mD}WaE^q(F1btPB&(p76<h3gwfAHaOf*)W!$vd2% z=Y7)l(Y`K4xL8&iqc0b(J}6b+#lOxbfe+sMB|-2z!<%ov#Zwlicv^!Wl5T9f43G)E z_^^EplXEPKzW4L~=IfVl4*&k!=UTv-ab7=+5FiG*2#z+Pj(d_vf~#^6EV6SBpRu1P zbRlK{0CvwOGu2l8PuZ}M3A}YPD%BZ?6FJnR{>oMslyB<_a<p9~MGng-KtB77@)5J- zsPB@1a|do=^Q}*(0GZo7q6gW#&g#+w&ccSSumS`~!lnpOr}<V6`xb+ilm-{P>MR;~ z1S*_8w8(;)6m4@QB(`V{P`XjxS(2}8fmKuc3X|{|E9FxxdvLDrU>(KAZb6AbpaC7p z7hOwicOE&T9!eD9NX>7|TcDrqwhTf8DO7bR+UaYR7`Az30PSIy8-qNK!cB7eWfz*g zGlF;5U3S_1+vt{%jXJcerc3rwM}Vx2CcdhuUM0@G>;dOp$8$GmFb6U4oL6;Go_<(3 zjL_|01pF?_-9B=ce0?`4WSg;^3Q(d{X~|gBif*^FW{aFNaygS{$s--@Tl6x&NuLQA zNAsni?F?S#stc^7DM#`gp-~xu^Q-p-MZL0xQO81=NNq;H?8l(A3(7sq&gsS{bjUAS zMZbSnS(VJnp%90g<#d@tlH$f~lu+UwW>j4!%^san$4gO!=q17?W3*RnE{8C!W9G;9 zE%fPq?5XvX8v|zTxzp;hq(6lD5>NatxK?5Os&;_?BI9PpvEt!)(dXfN=5zMXkq7;e zY0<S0*Y>`7vbn@h9?p=f_)pi%v6eZQDL$`Wz04D?z3ej6*sJ+B{nL&pU*YM**Czqz z;?xL9VQS=1#Fs*}+Lxy_M<t)W!E5KXd1|htSHw}aI#s^p=Bu}hS<Zvc0=Gw=2g7}y zT*=M&bJgij<lEb))jT8f0LMAt`y4&J0tV1`YT7U%@_B@M2yFE_4=LQ2o!am0yG{)z zm#M?1Zad#c;+egydU$5Ve<FfwgX#f_+-Q^5FPQ6`JuXb1aT(*1uKE4lvn_t(=;p1P zd6Lkl32(9C<N`m?ee|fW%^-%xT>jm6-y6Qorl7z7{qM8Rxjvlo_gI)WZMvQ&P5CF| zAz!_(e@OAyCOdNWHg%v>1z0<r|MY*%gkIx181%r86ErKq{5{Ev;gbsD=%DU!VMkN% zdon-)F1<{4JyU^4R_pzS2ICAIRY1_e!383_XUX^I;?sbti!nO_2Lj*4y2*rUi$~8B zaB^ZtSze>Txo|E>q?yiAoF=pM4V-3C3vGXF&jpyW_Kq>T3!33{G#8n^DkDKZu7y{Z zzKb_@f`<#s=nOB9!kB0B+6w7-$!uTll2%@2t#{cHz(QvS#RM7EiL&|_2r$5aEy%0w z{RCGTkjd~r`I62;7hTP}M|qb?dut@^XkG&QW8M0C4R=W*tFpsL{j|v;Ul#(g1n9|g zQR##muE0{i{6Ly7RyU{{UdpLmGdY12w)b6<%H1ay+NA5|WMYLNnhmz+A3J_5L09S7 zL@O?*OvS^Uox-ME-MtT<#fcWElrr^zhIL5gk38iq{xo?v%0bkDQ9C4X4UF}z{_EW6 z*x6xMJ-YPZuQrl)>IA>Lj~wQ?16n%W@8u=UuD^Uc9d$83x|8osfCQhxfi3yyXZygf z`r_5#Yz^)#@~PtlUz^?2UV+_{q=OwI2Lufw#0JP@z1onJSKP?OWKqW2Q2y?y7v4a) z0copci`P~3WLbaRNAVDkHcsHoKEU>5{R)?UMc-)we&OYl`huV^wij#1*WYMQlX>p& z_C|yOUv=0bSm&z+Txi%9vJ0J~eaCFKf6$ADu$<`=)~T`?be5;}C@;@_VnRDu4-4#S z_uM{2n>+9vV}OyrPgMN=kA5_4zWpuU-+XIWTPL8my*7OG!8HQU2Ap}{?s59L!_YNQ z4DW><Cgb5v{kppqyQ{lT5^vq(J<i!BeTTNYJ)C`wA4B8av_8_a2=5G+na@#A_-fU% z?bKb`(4n4u6#dq%yU4ONoIUq?e*DXKJm=lb@W<Mrg9yk%|G|$1Zr#4Ydz^W##+~cK zA>QrmFN9}&)b`p6EMtm`7+Sn)BQ;LIye;&ogmJ~Exox|Z)$3gS(+2D>d_)u4CiS;Y zoRmY3d_Dq~q(UG8f0R`ll9vFsSLN~O_~SVrjzv$J*azFV`?~wTM{)BBpBbJdDaSV) z(-MH-oE96p)`IOMzMNx;A{pQFl^xFZd6XsC7hLhJIH7FE966VkyYdZcrG3yQ7Hyl{ zd|bi@577^<o;*b`W0in2JDi_C%X@;~9###|dUFwB^+|R0Xa=0|Rmpp%&eca<Bj9X+ z)PVE(*Lal$0q5$+?Tet(+F1h5$_6<wp@0qj-XK`aO_jg?|NiZ;yn1vvOK{ak$o!oH zCsf`DF(4FkQW5&IZPtt}WQZ)Zv6}>~uUzs+123~%`)z*k?|kegtTvNx>4m9cA=|0? zSfHL;2{^y^&b!!gG4D(^;C$5AHiUWEAU9aK4lVGiPF=jB8-C_{pba>GK%n={Z@opp znVr^$4X!$8vHpO=R*nO?p$jkl(v(MUvG;9gd_;g&pFE5m+@b7mE7-=$55#Fm${)J= zf-<0slT>z&`$~<EKKyVv$Byq82slf_8_@cRH_#kA(zNoWRs5sQkkR)sTd$uG_`b_i z3fl1kuPQNUZKHL3F{N*VFWN;8PD4YZMHbrpryqZU93Kp)d5`od-XHF#UhPr!n92k( z?U}l=zG@y-{ifrc!S4^>{RM&NJHuPw{#N>*Lj;@)2V4a=d2BLd9>myU<_>eboAjmE zF5Vn|@V)cHKl;9})M)-=WhPnC`gha8JnWg$DoXtYK!*H#a2`2bC>Q*ciaF^;q)4*N zWSvRIW3bT2)4HY#W(hk=L#Xs0tx$hTqQHP!`6D?k-#%4mRjafcj=~r)mR7)GBO#!L zUv+cnuVT&uYf3JbFl}C?TGpBVAhA*A@dSXbU8tq4)%%h~5f6PwT%?Fl@(t?vRnkaH z{>Y&o4Jar;+Mc5c`PRSvj2LO>o<)3HtHg`JEZ|I*xt&;a6{l<{9Y20on#nl6GNZv{ zz=6EtB_Pz=3l~AncVut6C~2z`oA!2gIAa%IA;$anv%{Idb&Z;hd(+)3^-I0hg*l!j zPdg~LIkSK>wW!^@G8D#_MG}yFZ=}#uF#fY?ggMJDPk6Cd%1sHu94kz{zUn+#<5xFj z)x0!2!;-B7&TMYJ>}Ph4+#S#(8B!5$TGmO+v(roMw}NTFx%)#=&`+df+I!Td+Qk%~ z3+Hy-l@nkBqgA{ti&sJNI_Z&zbSksk#VYN3bfU9s;VUr$G<j@|JxR+CoEx3dicP)_ zInD2Sl{(@>CGgeSJ*}E9A~Sx)rzsn`XFjMNa^Vj@$~wWmg)zsc|D2nd7oWF$N<{vt zM2>BaY`~eptG&OOc7Q0_Ws7;Va};@Hz9+4Ao^}hZz7C2Wz%IECmj@qb?xnHU>eH@c zK=bHFq|aR0ls**t9Va>}2r2WgI%C)<0i{`(&f^F;zh3WS4SWn<xDqUyTyv87CH=t) z8@ODfId0n@yYWQ54l|E)t$mx{dsybTak5s0sPgcYzOUOsUY@JV{-<LtdsqsshZRop zUB~qHHpza#Y1LC~tevBO$=1YH^vLf~Te~(}XTywf2KyU-FwJ_dYk$X!GUly-9-JD# zg8`|6&jG9Jmj6DOa`%-g-Fx+5jK=@*Kp#fpspUT-V$R1N&5x@;!x1n>Zx1~-qc5$n zhSQ~-*BW3x#%uOA*&KKM#x-68c##<9>hQ^@pRjItkIgnmhF4#C6?qqUo#wUSW9HAl z^E?0U@a7wD=j{%+Z{G!<4Jahv<6OhI4d>wWxNZ7iN^^!dpiOn|`d-&50q1}9<A0j6 zWYUXx96KC(34?uml6GsAXaL2<RG&1YQB&?tOdGis8`xcfo+R^qZHB>3J82iWcG8<H z?hKx}v)HL-cFf8LS?;oP=I&j7kc;<~S}vSPIr;Z2@=h062BWh}mztKB9ixwtDof$D z!4JN6jOiQ+0JxA;=IpvQ5XHjKfRy<C2LioT&sBD$y3oqCHbW2pB2i?kfi^ZsZhhsI z0d&YNnq8dAJFm(>7lUV|b`%4_-J<oQeg?s^^OxLNXInN<zSs^O)$hJCGUx$Wbs(i& z2RVbdb*KGGeqcFIqYRdJdn-7Zz=pP9aP_qw6`X_ek_~e9+6M!)?(((nln3Q9s5)WE z!ZNIjr}lH8KZLn@fL9!CrTiY1&$@O|TtV-ea@L*WW@p4s5J+4W4BAEc`bS#sNRXCz z@mJ)SChc3h(hDyE7;t)huM<q%-r)!1(8o!Ive_p5ktFFEnCDFjv7Ljjy7`j%?q`{_ zVf(zQCG}3{CLQRdonZ;vfQ?9Bw<3CAI35KL-D<3Jb%Kukm1VS<`tg~j_!6*PmTGqu zi0A=8{X!c`$2yPAI*yaFXw;}?0kxNh{@dx-v2G0YfHTAqzjTbgEY$Qn>&O#1n5ry_ z@@k3N;clKf8ALI#ZM&4;w!0BQyyq)4XtVCF^Li#3boL}~TG*E12}fl!crATp?rr!u ze0&{{JhzxcS*DL0#I|mZvzyX#;eYQB|8Tf{?zQ16f#P*{3-8?J$H=ZD%fS0sUnO9C zh#w<EuNH9TMUTiRZ~F@StZKU;4%@u8W&QTO;o9|EycT4m0?q`|@(wBV(gkt@2Rj;Y zuEmdw00YkW1NORe{Wf=D*Vt`+pIxXGa9%NBgHd!ZlWopx1J1krP~bMf<{bmhe3tm} zz(xF8oiSDxty$1QUwm;>zxoDknv2+6JuDlO__<a`Yrc{`o4x?rRqNWm`p616mp$Tg zQh<zb`QtqPn#|%R*S2OT*uWz?nZg>36;~nce<C}VNg9-tOTO$Wqj&P4Z+Q%*v1~7O z9Z$BMrA%x-@TylJRr{+S1#}eC8<n-_^?s_xBl-|^M=o_(v_CL#L4UX8O%;6XFuRC( zhsAJ(IyK;Y{`I%ABREg91P`4MT-l?h+@e;=q;0+7bDh^mtU*IQ{%D}D)X+ZGsY9Z5 zVm(#B*+40;d+;VCl=JEZZZzKHj{Q&m?N10e9~sU-<9XgUe3aeJ(%7VL+~mfGu>LI> zjDw!`WV8qm{plLP=F1l^5pcdVy!oB)4zKV!8W$*$xxT;wPeIis`uN@SLC#z3lK#ct z{EYUwlz`^T=V@oW%0g3T!3?Z@a{76Wy?tAjAOEAR`HtaF3G{yO{`<rCe&g4$$vI^A zrh<H9&G1J2*eQMiEnoex;>}5P@sYase)-GT^a!t^@D(9PsIzVCU_UDV8gHeF9BDx6 zA`2|bB7Bp8^F?+ifAqooywm!P;mk{Cd9?>N1s~+xAoeJ&jCnz|R_fzUcl*AN37mTa zOuu;Z?YCy{a8@61^+avzN7{DbH6G`LA06G`{qY|o#|OL$=*8g$e(cX(&b<z82ino= z{I%<}DeX$W<DGM-58nMb{on23jkn((cR2e)&AH*P{Mg^RkXGnn7bVozyS!54`o$Z= zl~1n?|KV@GG5o>zf1R7K`X;giAPiVsi(A*JG8;is(JY{r1(G<iW1SVR*oJ&)N!Jv( z_FXx%@7NF=L2cC;24}@NORZ#=u9V8|oo2Ps^aS9R{^gs^Pt*;&rmn%ZP0j>^N&?Qs zaQu<P*u(j?xY$u$04XWkO~EJ^0LsfR4TvU@EquPizpj$w4rlF}EZehuumXLb3{wYT zT(+NJicTUYypaZ7(gu`q#1%vV#MGl_srSPv8!JZ{fNv?M_U|nZcL*)V#U7mQu;UT= zt6y()49K^_^x2dr3CD?~mDhG$Hl>F3UkY<mvj?1+|LxLG)3_L;o!f{n58I9K#YGx3 z4T@F1?ehZC;bvu(!*yig&@z<Els<;K+TmvSF70@SV3#}KQ%fk&=Y!=RK?$uwZr2Yv zC{vd`w(yHQIa}+~vQ9KUI0`+3kwx^69wobZvs6em!>`-~oEyK<Rb~jI4=TqP3~sg- z%vvb#EO{e5`Q3(cEUr^|S`NB)IH5dG3Hf?M5@@kOyVM5VCL)yYRAIk~pdS4^=Ik_- zWg>gg9|?zfFCO6{V3S?KNgZc)9X<`&Lq1K1lE3U{pX0S31J16woG0{m!Pj_({E)Vu zbAy(C$vI2LPuBtT4|U_kAEAd1pL%+&==y_z{YIGlgi+!ikXD7vk(qNl>(Y<wl^RVi z_*UNooWM!detNz>A7}y8$9_Vk$*uMf1u_O&o=*|VTJH4=vw(9WU%W&!BX+OXh57`y zbX{AxF7P)PT+=&$a!#1F{e3stv602TLFmS_+qz_HV!)ucSy>&JqUeE8^xJx4q<<u^ zbzE_iR=?OXPdc|g(K$rbsV$X1%3XIG7pQry@gmn)%qPh=WfLE-UMssL>!Dx04j&3I zDfm3F8ooSjLf}iD)*9eT68RPS+%2G=*rxPL+nU$5Q4UVU@#pFvYGa>{V!y<PKG2&b z#u#kRzQ6frKl^E(()_^>egMo))-u=FjC1D9+2On2`5qfJPBVvd4ggQ*6TQiCd|dzQ z{lVM~^JN)4W}DIkU8jZr=g<CZ_h0_We>-8#fQqrRI8H@P2GItU1tC;Aj5XIcnf6Y= zE#?Mg3=mZ>%V5Nx0a`2D;M=M{y4Q9TT6xuZQAsG`prfEp@ai%7bsp#CapE{i$>e*S zd%#!G4mtR7R5=5m9(6Pw$-xl@nd1tpoR;f^Ss)6-$DPJr8#q*c>34@U_^ET6C$8^1 z?EGs1UkkGiFTV7r0|=_sBS+D<7WoiMC*SG!9lx3A(jvt7F<TdP2EIHmSS$*zpS+5K ziLbQW`RdLzVbC-Iv#JCJ2n-~=V`hF(gllEg&gy2G(Wg#8=mBSM7JwRiMxITBadk7o z-KW~#AgBY3J7Rsb${PtbR_oN@f`QZuJi!ZMhtREe1TMC;j{!b|f!2fPrrucfJ@eJA zbXUV_*vjfhdVWm8n%C`Q-n2fv?zZf5mCn{%-KcPPz1#NeK*Y7YlG1X{|9xI#;LQpB zOy2VCJbQbQewS-6ovM?RLqqcU0Y>bjy<<GSa|c~NCeOOiUhx$&{6WL;6uc+kGGT;o zmqp^%jS~>_lvzKsEsL-G9kw4Or_S<o3K)BL9?2{Dd%(v<)^vxnx{Ub1`$`Slzp2-w z=iMf%?2jypV>|Q)RmoO2shrr{caepi-L>yc8sA}@MF;+&+)ngn^`spP;MD6&D%eu* z9T!f%;%I+y%=1H|jJD=$Z~HX;-oTue_>cbhkB3_X->&hCwCn5^-enj3Cm-{J0(Z6u zkiWnV%%cRIr7vA<$g47Ht{M%?b*KmVY_p4WgV$kP=KZC&?%ZXE@~gwKlT2Q1>mX}; zpU!ZxvPfr(7f6tgeo5O!K7)!kuHPB15dc5?>V*V+R(-f3z`$ZtoyY4%?Mr}Xcl~x= zso^f?1p>|s{2;1}0xHPP7Z&tC;P}Bp!PlRy>nhU{<Qqg$9O1yp1>ctTbH|l@THV{< zcOT2b1G@a@)AJM5l7jVv%wBh@9Trh!4NN3yu*!kon~xBEK_hGvin1mhh~f%s@`!fW zsWjJMwht>&-?#15&O(u_6YS$F3}`$0kFfR?H9i(zjGjDrwqpf9<R>ouB|+yb-thS) zZf34NcXC+Zj>V1jjp6vIGrX_(_4=W{mDabQi#8~Qluh1dD3@)Xc7|Wnj|Q$`hecjv zac+3w>{*e3rJspys;^9Nxm04#g-xVHy>4*>#2wB*`{~aTa6Zj@pii*-`Y3n#m+kNH zK?BPS43S}xJA73qdW-={XyH%SF7e}<1f6|{^M$wB;e7ra?Z5ix(xGe-#-XH;U7*tE z4uRfx-}z;1eVo^hxI5WbYotFbL~DpYas8@f{hF^Fx1eFb`NI!B9KQ2w-_5H%)Lnas zV_%bcj6bS@HB<{IgU;?ezIo%u@IH^wiDba}<yQ%O^S)x|K^Z5=*I$#M*#l#0X!b5` z-u~n=J0?E*@Pqt_;u(Uy?r^q$Gv&soay#a5ZGG4mr5$j!L=bR|1+TC6@JC0*d;Lvb zslk&G)wYU%Zo~!|0{E^sI-Hy2W<Qh-IJ?W*0Q}3ZzMO#b33jlTK{&|2`>b?YN}Iw) z%I9uvA2a;ugLiq|&>B0Ozn!3U-{Bm?B76Fdv=?Yfmrv0_R&Ih_yT}hq@-F%x{=K({ zfB5&l$DGcVX!|V2ep^o!jMA{NXc@;c^c!O@UN>27DE(Z|?pLYv4%3b^xH=2Zuotgr zb{L6{wDfjvI0V8z8sfrP_lmC$>XN>)F}6Rqoto0OB;P#RQ}Ur89qP7;K)xFugpXI& znJ~69uIdBLIGQ|hO1?t}xX7zuq|mG!A?g}A`wc}i@caalg70`GJ^6)ZaVt7f3@6Z( zA3CM@9^S>8Z)rE1OsVv`?(!GW##2C1B{F4db~?kN)Ps8BYL$Q@b2>aTdulYQf0u^^ z9;;UE2a0UzQo$>4W-^w!uw;(tQz*O6y*;OY2!04bN8Z}Nv(U~d7maZWDzCDDpTNyd zW9^R2krEN8<6UkN@9-+IUFO+4tPlKwJbkavr&PPfr5UwGs9UB9Fd+~9CUr8U(TtPp zE^98@mpnR5*Lhl=T4*BJtv@JD`^he?$EeyfMnr6)2_`n4+EsC6qbv_$7fLf(!zp>O zSwoU{FEQU9sVEoiAn=v8EGLWk%w!uOa$;}ZCF*jO3_TYx$w-Hkn&&!tRu<nQW^(#d z1Y_}MPQca<qBYcNLlUl!bF-{fxXx3n-jKn+vQZ{|QE9GV&UIYhId5SQZ@!QJGfw0K zo6PB?MFYw_PCkwSt#8XsoA5>iV8UDR;N=eI9&qmcXc>fd*$fl&bR(tB#_VHx>H+%F zlZ{_#=bTC_Hcx>WX4UH}FI@Popn}i}+MzjZvD_Vg`R=>JJMa8$ViNWTFYt8G`PW_> zUgAlmdSbf*&M{qW@d}}0+3KS6prng3s#I(r`mHY6sPs^XS;5T5XL%1kE1jqC+Qq&^ z>ndY^Wu5EeJo$<bI4^0|uQ>{Hd?{rf%p@~);2PmEQm@~GKpz(_bPxuMA4KwVm8)BG zl+T6tE8wSVf$qP?Ui53PYu!<8&i<|Z*D`&y`Y2;hYrG!LxwZ4kpZ@fn1fPBF+)MoM z`r6t$PfA`QzO^;{gYW<L@H{{4zT)pW&=(m$aCfwGFPcgG<Z=CP+V-BVr9LOO&(o$d ziNXy3_n-ZryZ`f_{CAC08{x)=S=Ut=GhwC;J?B)Qix`s~lbzsQehFSY7jG5RVL~=Z zQa1SLuElg_E?l9ZQ~0<kOTM&a1FYsbnKs}&P5l)SS%AUoIJ>XJ5?*I9P!%FUf+KQP zV7&CI@9KzpB^!8kr*0N57^w%KC6P%c<@I_8U*X{^24(}Gi#Y9JAlj5bt0z=UFOx0` z$2P)hpL^(Nz)*Wc8XAR-z(HU6g>!H*xUFsmm;KQ*2V!{`i1zMkUim@!UA9>ILk&lc z9tq4n7K7p`udl_BN8VrSAfjxP$;%%)bO7;3m`vKxx^dxaz^!Pw3!NQ!*!DI7GWGIY zo!5PTE;9Oxjx1*3XTUi@WAt$0n@9YRTi@_5I#ZVLAS*iFW2Z)f)yhUvm+oWAQnsi8 zuurO;%t$W_{R9qbGGU$iIgF2)gi&7eI<0OOI|K2xp}TzbEgy|?;-G9xZP2XA*Dm(v zadHP*eHMRR-+({zb(_ggyI4Q^q!TplD2_=v>PR3nuPOl_UogNZ9fXX$%GxJub+e_} z06)@q3|cr*OpvtQBr&jRkk@kciyhECN0|0Dr#+NU7}NjH-kUaSc3t;<r*F^mfCkWL zpwZnJNl~Om%91R}lqE4ys!}CKPNLY7N@a_dD&HWo93}YzuDnnAMVzFZs9Y)Mh2^Tq ziY+S+8Ec9}5+I3z02)Kj^LU5O@AqGOJ<oF+K;Mf548<h--t(Mu_OPbC_S$=|v(G-# zD_-*%%IWPDvH@0YouR|H@|$8vT|$Ec5MLp?$I4mj$@)=v!i|%gYvsAZg9_V~<y=wh zYH!<xWt5Bhr~^o+wN5S1>Zb!#gYvoNE98!t`F8;Ck+&MqKZAS78`_!C^;EjV0|M~d z-Xb^7%E~xbG1rq$UKPWkW4!bmr(ArPqr7bcKk>Kz)^rsI-o>kIgQ3HjEq~6jLhr^k z_1}+g?ZfG^7unJAgjA@MW^Bf4_5{avz^6{I`{>*1oz>|*wi~#7_1g3ZPCXrJJ9go4 zx7|>TX=TdC;S4}wvLqSaX-mlU_Kn+ol<gXON?V?74|pwp?{3-``D)PZAW(ayvx=fP z?YAuZ@xW`-+D-OxzRiaNd78V#>$wOV$FunCG^ziTEFA(^^n@tjNQCj^kJ|WCI;6ZT zo4|G1X?RuNC}%w;H$UdJdefG<k4_Pn_;HqYVOZ%zDaIU-IfEmIBq!an+;M1cgx}={ zNrSpfc8nr(@<W?tP)Z`X=3e_-wudtUO%qKS3z3^aMRbe&`7;lZd1w`z1T0{bM2aqT z%XES1ctcU*aE{{{o!`0d;IxFp`8u{`&%q<pQR;N3c850B@=^{I6nWY}aiBmVt=QPh zY^iaZhZyby`zRmkb9J(TB65igwGqmdY6qTmu#H#4g}scPuJADDI!@X*zj+3S^RDS2 z6RPfS{3xa0Gh1Vyay3N(I%X?bLjy{I^h3ur9;RHnbeUJsE>BOe|Jl)FkHubO;2uh( zK#Gbmufm74g;Dlj=JnKf-grB-yOqY_M~~v9^@D%N&_C<Sa)gLx@FmRPLCLPszRu(P zeg{YGDYn#jl$FJn?}rAlM+!#;8*oZiz-9npzjcjO(r=%E4$AGJ?>mA_<1Ef=dD0@u z3WEy@3#n?IGjM%tXBm5Q;oLd4vpB;F>8IIJ<7m|{GVSq)Z7S^qSk)GgCD$Hexy=Vs z-5w+#Ql@Wt;wiS`VLKMf*j7Yu--D*bc4&UIuiE_`tf*HeD_py}`Azn;e&Wd|cp!0< zm0E0prfx#Jurg7Xk3okFg%9ZihWM|s$K88xp8@vW>A4qP;DHw(PGwO+^$*%8osfd0 z?_z9_I^((q{MdXfoX+O+?_QjK`uks)e(EzXZtQSwIRn=axdAiR3U9=tf`q=YCQ>ob z(s3!V?!MY;!75#t=XDN|JCZ9_y|ZrU*W=02?pE12(a02i5OXFqr1?LiODIFm!j8_H zXeMA|D-4LApK>@Gzr;gK^OS9h^($7BxB6-Oi-sdO%XKK7oJphLLt|`okZD(Rqz*gi zIr!8*X$wI^1_f2<^l-(mFw7zk9Jve;$wcvzvL%apc{CSc*6z7R#{$DN5JbfJNzVM( zR}~?^Tu5uU;hT;xR0zX7K~=PAhYOJBArolU41^}n^!?V2{rB1yY$P_m9M1C<&Y?9t zDv43nbKP>0XcNXootp1iKBBuwWSwjaWhftdut#w?GxpKxEcLcY=V5V3DSKgY{-97g zK*|7Jj?=!a$ST|ADUs+oEpynFr+JxkAZE&q_O`CsEf6(#ILia@2MX~m%BA5JoU(^z zRi8S@ZkiVnb9y>;ex9dE`zX()->)z%fQ$;2RjtG>TXfh)Dqh@0eo1!@!}g>Gj`9OR z-{m|qw@h1?EmQeImXwV{8m0ZiL(xfjVF!q`l0WyxAwzXrW#@2?TPu;B?`qeSWN{w5 zjs4#08?c-ikRU9_HjYGv%OM#1xxf`<Q7;aROYphHm+@w<D6T_NIh@twvTn#S0u8~r zE^f^~+OGCtgtog;dSOF*^PPTd<SUufP0QN1U3EBDC>sEQqDhd9y0}06?_c`T^!va6 zFKfO}W$S2uo{#oE|NL{IvE~kNfS}!0<UWg%s%)M5ciy%;W^-rzWsl7SrC;^_@Z9#F z&f%<o=Y>7rE%`{P_^N)DrHi2I4dI&GI?uDe?>Br+-?iH}xPbtLKzhGtC2tVA9yZ99 zWb<x1f7n-FKEBZN+m8?8{}1U~A%WHt^-^2oeZ5_t+vs@tK-3R)v}}~VoNIh2@XBSr zjf8LO>)-fVJ_z{Yi!V&CzWQ2xoW8wrh{ZQQ@B^QXz0<+yH%a`a&z(EWiD@tSuzH&Q z=JapTE`2NH@o~Z2G@Z7+^dDG`fBw&YXTjlIq-0{YKvg=MMOn4c9eFYV;yT8UG%K_} z`evMlmkk;gAkvW#*M|vPFmetI^U4~AZVYGR_)|&p@fsXA>9**|R306`ZLGz)3uEWK zX}vYYBGPoQ<m=#NCj3OiAbSS3G%HM%Fv>Xw``+siD-ar89Y?M(EW_`;23u#8d3C^A zUPrHnJNSULO1`YXwgC`ne4JXt87X~v!c4mG$i!dm*(+REhP$1I6G<C|4oe+pI>qE& z*vrr*OnI@Bw{tN6U7XM6$^Nwit}v}*Wp5d`l1Lo_Ck|q8TPAfAYLpjFI~<4R6L$8U zf-h;&;T#!4yDL>KXDD5u!=jAvbkuI6Qj9M+wHiClYRW3ln>fHat@8<sB!8<cd7aFf z-gzwBgPA?ZN*La^<1$V~;^bX}VBj{6QDtdfWm^LzVb!2TxE?i_DESsHbPoVJ%oUC+ z`*pB;FR#)Shcogu<fC?+BUjSZzpZr6){(1dbPCv^fhxGYXx<_Z;29^K;y16?I?8R_ z@}NVt>Fu+03r9UK-L1M%oN=mhHm||KgZ1AyOxLpp_;o=Uh6d7we{Z?!%yuEIad^ae zfnJ9%-%O~L>$Po(4{inw%D_xkPv|sug)_iY7s@0nYr%7eha(Uc`SBBb;{aa=XdLR$ zZCfpTrTd{#_|&uY;z!!%GWCJZ-8h}omf)kTiL9#Qr6UE8HqL{IAN!SGnXWzg)O3!$ zlWz+Thsi~py*JnzV|8WQbl}iIoO=f;&VJAkCxl+*tdmbtGNP6*2Bb9F>HPUiIGnFf z2aX=e$G>*zV6+^CSMg3b`B++mA0mvq&#Z_?b;yM_&q~-!e0cEug)7tH$Bu*FRj4@o zWtqI<&nzhLfThD3NBJ7Bz^~n8YYn!JSz>FDtz(t*7Hu1{M+?CLF8&aD)qyZL(pT6v zfMsyPN3C#GdTHHxZLscA&zvo+OiL=Hk%j7vu9b6`yhO$>3A2yP;<{a^!=nsk#ZuG; z9oPO<ULRKU1Ss*zUuk42_{mS%c#oYx8RSx8J%wm=Mw?YSVRW#flW}&*$SBkOTiUhh z=u}`>go4CS#&X1S`0!yXPsnR8XSQ$H&0f5`s(t+)Z!qjVFztWjvC2zv`;$79jr8}S zokA!aO4oM2%m)MgCW5`?A)dnTJ8%%WVJE2HYIkLSY<I%39-P1`Gg=Vp%ZD>~fb9Ou z?k~NM2N|~M$N^gPd99&`uKZO$x3cmt{VF`J1P}C}<EuDWZv*EVPUHQ&dbWqxPhmfL zP%`tkWSnzV%-{#2&@1<9zsUn0b!R)v_g&rWN-Jr#F47m1*6meYRCgRk=7A?^ciAe( z?H?{PkbIO62HH+jccaGPh}_UJ`lhxKi6luKmk;Hkt#F02TkSXjF9*BSOAYj--er=T z)*miYFW8$KIIgcr2hR6>2YJB2SV3Bf{uCOJ2315^N4cY-te2~lw;r|kM~)ul1Bg6m zM%M~m(P6Vm-RK}7%C@C__huQ}^$uHVyn_S%_*2JmII~>}4+7O&w_!*hl{QXmf*<<< z#|g9oj-t^mjV@oh#1<iZND+tgGfceQmSa0(6?wG|B)oF-3y<N#cxbgvuJUo-vu~fD z&b@tM`q>})uIXpS3g^7RK|Zslyo}|F2!ip3KqQT78-aw8DE}kJsNGS>*jfHjEGO_8 z&rgyEQ1kZSIoZ~g)usy9NbE<aS!U>AbP6DWYCKIty{<!As2_v!PCS`-P&C(P@vF^4 z^7IA4Ct<Wf|2nkHWw7v7nGa%^(g9QA0<$)no9GQ4RUCohNT<a~nBG!sj*)8$L;|CH zQj@{V=Jr?&#b+G<;U#EC1`9UyDqHo~ah5gk8`!x~xz`sP(K*?+yl4=8j?>HpQq3U9 zT+~fuNqy8q6LeMkYaL^^*LZMKTWU~Gv?*7377#74q4a*SZW23ixBeE66sY3jZ~Yzo zNsU40x_WruF%FAC)_5rBM+27_Q)_dokFsx}g#VP6s>RTFTXd2WlK5#nO_SyO!AYf+ zt_>C{KM7id4h?^HCZTc7b5-uf<6W8r=Q+LRo>9kjm+rHvqz^=mkBlQcAo&p8ln<Ue z>+C$z`!s+y{p)Zvd6b>gP8(W?Z?K`bZOVu&Nfr++hYu(^BXmx=EZ1GzhZ!ECO__7f z)ySI@iNP^$Oq-3(yhg9I0qU52tLgs9zkUA}29^03JN?Oh?t=^FYt-R5Vt!CM{Y_|b zoX<gq(XU7sx8TS;1De%sKN_ed)ajqOnv8*49jw2)?>5@@sIs9sF%-b&a@PN7(o(+k zH2j5fvMUTAyFKF5C+1sfRJ`0JIWlY5U;N@1r+@kT|6)4KID0vJzV4Zx;Ek)3C!bFH z%lK70L7Uv3hr9I2LXd`>1}DL7^tdQ&8~(~y?DU2?d7CqDlFwVzhZSkMtoI%-o44fa zyhFc@{gI2;TyW-x)OWMpz;zzFAI0hZc*Y?vgwijtgT0&g?A<b5zromTwdQ;uhP&}R zEPXL8G%ZFv<a*TLLvnodq>qCCqeK5VOQ>ug0iF$VGvOoZ>t;ZH%kqRJexSK@IW4j5 zmbQ(fbl<U6*{Ju<z87ECZ5BQL>7V{-+P15k<Kw`8ah~!2<BuPkUVQNr(|+DYy?OIi z+W8*7Te6IAj44lSTQzwJ*jTPb=EnKHWpdgi;2DLR)RpdgSmFFT_ka60e`6gQ2P=y~ z!}DNpP-E~(m>-U-$ueC8SsQqlsr&T~XIE=laZX_DY<MI<=U^uV0Ptlh!?n)JC<5r* zE7J5bvR0^0IR{q`te6Dxv>|kn$21*Oi$N}ClYo(svMQkiQO+81S7F*oh)2hgbQ%KF zSA8<sDraTrMO;lsJJ(zt>uO2i>ohZ;*WsC0qIG5pPkF_mk5={*Go|01VH`TaUMr?8 zBTYq@Pa;{ZgyHWRi-QKb?-4I9kH)L>uveDaA1h;J5<0kY0y>um^+Kl;M>TXyoAOM3 z`?S&l0xr48hBO_hZlpfjwt#dW=qm4O+Qr1;3TI`!l}Uzj4_>lJPhX4UwvNS4=bSoH z2ht%jFfonlaROjDkJL%>0FCqBIOpx`ORmZ`I4GNIR_7IFvsXQJy7<gveQ`NLImXT7 z!-SG^t*G@OgD_kHt<%Mcc$~-Rmo!FRK$+E<@^OOV8NG5)rqkFJ<vzF&R`i22|DhpH zD(Rv=yiQ2ErAvPOu)(?&Mh0D^s*B299ha}&ycJ-n9`JP=kRJ7+9+u48k^_wgr!Fls z%POPA70!Vtff8mQed|)KIQO>YoOX_k+EMN*PW8$1S$&VQDs2Xu0TG!>e+I_L6=tH( z<%q4--@;UO%G_0pjZc1U2QV1fNSkrW%0n56*N^qppiWz0CXOK&S6%<*U;gFk0(&>T z$BIqcyDM_8^AWF`H}3GTX^mBaho-}<^1HvqEoHPt(C)SxnMw(Zx@Ef!Y0tikG?**w z;d~7T;Z7VryI85{>Pad(xOMEsVPTt*5X#@r{?Njpo^cFbxpE^boDblf+`In(ADQEU z7jn%6lp<h-4f2N;9w_N_W|i|&w$r$cv-vh359EOX`avUSKVIcp6K3%#gV+Vm)`Rv* zE7A_<AjnTmQX;dISC7p{ytF2d5Tr@M&}U=G)30Erez~^}qr)jB4N%_)7j<1{VUd)e z?V)&%*efy?9OI<G44tPaO2M?p8P|bV{RUERS>{}JF|tL+O4r39U&!3{piMFjTM#F0 z9JO_=I4u(=h3!~-g3~aLKFVx$18_dfdXwtkx@SMDoL!l$J)&xOK#>o&Qb+O_J|teg zkXI=1hqPs030q+TunhkP4jsWcdLXM!{0Ltre`bQ8vLz+I75Y+Fq@ekHJd-|#55eeQ z-G&2kj~|qiKIny=IGcU&;Wixc>~hYe#EGaPwm-#wuJEw)4sd)GZ7<HqJ^OGttJBCJ zLRJ<YwhyABS2Cy0L}z)R2_M&KBg)e48eHY<9>Lac`T}7Q{GHVYz}5KlrGUGGbH)$c zxhI<r+Wovqu#~4V5g+Ju&5!&|(}1gdt+#SGpXcq1oot`O2Oj;{A2urmNjHx-RsTZ{ z#)LocKyUViXQFnK71u{t-K>*0@{;%D3l|MifPoiHg$~~Y)8TymDtoY#%QtgenY^91 zBGfqx3PBsDR3lmBR&p^736rM7>caW+JnTBp$4<)uznurB^>J4mYNP#$Uwf_NK6ab( z6701yy~6(5*REb7*DCvsKOIMWR=^P>&a{WfB@x7NmWm;_Rkp4=|K7#v;(M2;fA>Fh zqQw9JKmbWZK~zUSGkyMhKRNB#rY_gyH`%Kw)e!0h5Y@?rutHMj1ey9{;ADw$$yLSs z+qvf#m8;T5suffJfUL6SDjvKN1-4Wh6F}<l3^H*w)-$G^$|l#?S{@5##sc0&-_cq! zxr)|_e&Miv3(Hm_w5rb}qIBBOL<>$j{SO(+W=LRxu9WK^^I6W5M#dxXv`r>*#NK;Z z@VJ_VDjMxX|3{k*4VLTjLh-snWSM2&GeSW*i0Diqs>)Zp>U768l}Yfq^nyBAC^8ZT zFmyGmU>gL{UT(qR9EYmcfDl{%nj`%MJe5-pIcp!u<wyPQ^N?`naAusL6S~S)t>#yN z5IaX(X<{+5_^8zCKZu9f&<a7JN4f?8^&?wpu()H5G4h%Y9>y*XC(1TcCN|x&7A%T_ zZ}tNX!V7RCyY6Ng5?6Num}RWI(mk?fHL}<1@{k^{tNf936!#RW#(lLXWn92)KVI4c zCkWHxgZYZ>!j+|eAB5F71<>#-?|{wCfJC}@MN~N=doC>}T-#5F!ZY&Cqi3pTbFuX# zX`rfXjdv6hHu=PxKW<txI%nfd#^jyFgf3-1pe-ikx?wa-$6%q#6W4Qjq0_YYjL+1q znZp@9N3V#nKxkWH{_2C#C7g-(d1Js2*h>3q<R>N8oMUUw#Myt$oXL*;9Crjab414s z<c@PQP@s-99nM&tbq?oJgVJZQRCN^Rv2BSUU3#J`z$UqHQ9!#;g|wQPKb6#pj(zjH zMSL{yM6GZx$OU8Fb#CrYfAq(HH2trC@CWq!&gb2Vlee9C)A;aVA7Dd$WL;w+$7_fo zv_Z)@OY6AiB49b&Pi`hS#&UkPnV^&r?<Rsa&iOI)Xe*1Vup&F@ccm4(XPs#WjX%S~ zYWJ}HzVH8jK0JJc_@Vvbg*>vfIksjp+KAZ2_P9~rZ$<jI8~<i`N*!)e_QG7WZ4blo zox;C7Xv3s8ZA+b0mq&we{8~qH;>&VT3|nKmh~hFII=^t9xA(41C-~-!J{=#fxNCs^ znP;APb~<(XS+?D{owpcvvOvfk2=1{+C}`4VfQvn9d}4W6*sS~?2IK#cv;`SH44<mk zJmsT-4?3JRIE&%IdnYql;eteUocWr$4x%_#5vvZfJOw4)vO2hymey~nApvn{QO*Xj zO2<_n#VWg${e>}TS*a{NRM_3sJDKdXb65w|EWo@DX9rs<Rx8*noeMk7>Tu_=(qWl6 z12CeN6Rw@4%Gn=@vxI2|%Xo-KIb^F1jWp$5>FZg?qfV%nljXe5Jsp%XQ31`HZ4Gko zV9{=NRFFLBgdF&K`-AM|3vQir%2(&4!FUJ6+3T4}{w^luI@;t#84F8?v7LqeaWF+z zI0Wb*e3eFe<UbQiI-Qnd;u(Zwpi5aUa9|8)3b)b`XC^XIAF{oHc#($>7swty9&|V_ z;bc>ep=rodxm!;<8t?d2H0hO3K3n!)TdVRUe)U2pNCq#Imv0g8W<roUHjR7pgg^0E zZ#bMC%v#RX+48Kc<i}23e9Bcil!NqIw<#-5@^0P2Dr&BEBABlpsJN21K0GI-I-ZTs zHN4FSC6Gz0bl_$Xzx!bO5vtTZbotkHQSvI|+53H~zqY4t8|Imn9kTFVeQ5nQk46*K z2rsr}>FYM43=9q)`fY-mEEk<g<i~s-!c$HTzGNi>7USfH0~S&b4qECdxoOs$dmfd% zeLYKF5H#m8n1XH{#L_1m`N)<eoFO)K>^UnTlE#A!VCuYcKxVxfELRWHs6Xn(m608! zT^;GV_sk>tz*ZiXRUe~c<WmoR_!ob1dYy+EXW1%1`sCTYOmE*}<>Ga=xnWi6K~{3E z-S<Hm`=9d~F4Cgyseh2plywE?0aC!RYsylb)qdp}!sAfejT34OzSZTeJIYzTg*H<f zfnKtIuH~KJ^L@bS2HR>}zI-!VFzm!(zm+XF{OF1+zpH+%OWHAIoFwjKb^mUhg}a!k z@+e~3$-d4z@3Ci<c7nQGqJ7YMhpi}CYXh7Vs0C>cRxJ1Y3~`QY@+mjtrPw^)ySh7V zwCg3Mk|SW0w?{dNg`wr{vYrc_#Vapuh8yGUxstajF)!D)RdHIzdoveRaABN<N2q-W z<*sQWueaP=$J!3J*y#bkHccB4eGPod4VcjzkScp0%BqvvZJmQ|31hrV&~<i5kNv1{ z9oQ`Gz~RjPpttYSzV_~)cH=B22YRGkwjQBNhJ~HO34(P}wjsI>A=g=X>VvOk`o}{@ zj%MY%+-B81I#3RCbQ0Tuf|H^=on+QTa}{UCO;+8%`}Vugv}4-$2wS!6<$(yRW_CgE zD!QY?c_*uQ*7!iqoowHMLmEEa5=MvSJ^I6|w3BPVxk0*H#vDHS2yY{3H%6U2z=sl1 zemx1cp4_we&2PRL*!%Ma!4aIj^>8nfBr;jo<`r&&aA~t{6QIM|Ej4m5h<ud2*s>DW zH&U<_+9I9smeroFaIGGuLal%Pd>i39W#4}LZTg7q`Jk!o)Hjc;+dSNBMH3M1FS-m- zk|aMqDD&GC*P-P)`#~RljQyK&T$iSkDaH6vNBC3E4eF4zqz$p}`z;*jSEyg>--lrK z8QF3r*?<Nv>9L)91imumaBC#D_K?IIH>ej@eIGhn+hF*XltknKBN?>s^`Kq!Wq)fD z?L$o7=mOSFw)a3d)ApU)aOCrF1X_jDHq&jqq@Dlhobb}eXy+9S4%=&&ZgAY3e(oo} zZ~C{s|5G!EvpjT=-b{S0<PnB+pqDE%5EAFD*W;W7BHDi0d}g7F&2Hs0?K3fzSh#0d zXpQqg&o^^8YeQ&-^F(-yP7<pF*^n`ZIJBpsR(V$$ZJq_<1O=(ie?!`Xea6s>yh)Ih zq|zUx6zRzvoaOTqb{(_q4_?S(%Sjzo?~R~ML=L1keMBZsG#wVNQ7mY+-FV1T3dg)a zMT%I5@}t#`T*c*W;*y0Q%L&6Wlnj#mkhR7X=Cr&a@><XpQP;L5rjkisgg<Z;BvM@A zJb*N;<hK}@O76&Hj6Zag@sGSgfZe>modpNz@fNSu^YCb`N|<`&2{?61`pm&?d<ZFO zbktcU<#LuZ0QgU|pnMn@hcn}tRmP%zFwln`jv*Yw#TH_BT7T<Y@H<ZV8^+12+($mS zdhn;TGz6HtvR4@h6I%1sCD%Ee8$P_)I$F*pTY-6$%)HWV85H5${JBG0=3zvooUwCQ zm1mK+MS2TY<x$!O<)M8vMBJl*r_xj7)!D`SQMXl!dg<~dtFEsk=g0KQ6JEh7m*FX8 zJI!1JmgPpYQf^unqKjU$&5GAW-*%nm-k*_>u@!}cX?ySc*$QXk919oDYNzFJra#f) zjPRsgxiMPgiX;7u^Clh6(qw;C+|)+{7ah)3o54+Kl_+o3=|iAwAR=>h%Q}hOU$~bK zQ=`+g?SQZk4}(bz{?JeRurEp;>zXkxIdXJ-9L`UTEj5Nt2RZptqbY8wY5M9*UtwE~ zFS5wvGKu;T&};g<IJJNp`$@cudY0*{b<T!~!1AZ~nw=9RjKyAs$PWq5ah$VkCS?3z zWo#7SPZpJReylf&*%fs0nycG_oli68;jOc`*`DmPpZ%ffbD#Uk=`mJ0r@sb<GH`C> zn52L{oB->w?bE|^O6MSUqm198^v%-wEkgg1z<v~3tF3Pg{-eO$7}~cm2RiBkyEv8Y zuZLcWQ66eOr#_R9x9o1-y2jR&=acWunKRS7@4hoV_0*FY+gnCw^ZD}^rcZq06THoE zYC5q05aZ{YjAdDznsJ(TNN5Cb^FR6(uQmv_w+*uVMM>VQo`j)cJo3@N-~O%N9O9`4 ztTU%NpPHzY<4%K9-LaDdCsqcxXvp5b7?fQYR)Y>L0csG^*<f_GWi#z0=f`;AIH}VR zF)d-h#&8LRsH#HnShJ?Zf$Iv+$5sx{_jvW&iLsW@`|XtV%k73Jn6T(z#Fb7H&g1AZ z4%q1s$g9J^iKe*C*Srg-6*7%W!q5iOTPE^gnmmiA_bk*oW>9%D!IWP*2OSRbtMkfE zAOl12>Y#N}s^d+AZkdRLGRo1sIw9j|GX|Q)9o{lIoU$5HI&_9Q(bFN|BwFV-D9K+A z>a5Dmsu@v0J9%~5%D?oc{y6)jM#n~0b&w!j;ph}p6wAzHAS-l)SmKnsya>aIj&v$p zgJqm#8sfy%$xbF=79|BMJSk)9R@&@<tzYFVo#wSuFSsR_d7Vj94Pv_Pc2c$-&cZGo zDwx5wN{6UU09o3FrGD#hHdrs30po;Y{Y1v<Iq}gc23LiTx<a=c3<%E&iukNf>ri<| ze~1XI=pwq!J<>?MTTa2cPq*;<UgxqxEOFs_Lf7MLC$G97yyB;H*nG;)Hm1JjV~#kt z<^#yCyP?za2_Mp%b_r%_PMa8fh&|52L8B+-(r*HYe;J2n9)du)G>KcjP4ikQSn29p zaG~?NbzWgV9I!?AgGWB(-a4)aLGqyP_@OJ?urjw@*`AzybDL}N_QRq@nH1UXU5#^q zJnE74tg}WL_5%YSbgeK*lwbE(mx^1r=v0tp>+p~M@-I#A9X!mI8kb`S)gbA*!z=q& zuiWM}w*9OoW&43`w7;xG#>%npBNQ`KLl!uTaXAx*PAV$~!FO)@W&|sw@3GRF2S)D0 zjL;whUNx2K8Tq73%_xU6Fw`gFZ{4^%U1pWDt7COI@7=cxzR>?6Z)Itn+D7tmM-byy zo3`T+U*fgEr8_sKZEUZBz~gjYq76!`PUi~h2+9l$NJ4&6LXbqSb7S1dX99VXAuzxX zt$kGKYJ15>PU$NeJ!@-=-Z+e*hvETQ`Rck>MUQy!Smy>Uf#MTi>0jkBEqdsMvaIa6 zbJAQB=ZaU(Ne+M7E1k{SU$?DM&$K1zo_!A)8<a4MW_b_|I*-n^qs?uN{ODfZ?on_E zvvoG`a5l5A#<a{T=N$(Q<LG^qt$J)D*l{K=&A)A{<QVehW)`FTF7aWD8#rq3;S_xA z*b_Jd-I_x_AWFURoKhtdWfqG~Jd|f;@(ot6zWF+iUfStl_B`&72I??gL3iju%4T4q z*4P?GUX>GHyo{rFg-OTd^B39vfj!Z1IzPe3b&lffRX2OGC(-hfa!nDWS#Qxfgs7wU z^;cfUskvi1^vDq$q&S>;o5a3AbWW_b58h~7gq3*UW#438g}aR7`w~vtix)0VC!ZO6 zI8zVyRhCf-+NSiK(N&llbV=VDlVLv^_y&6(`>N^zw!&~*j-5E1tyAribzi*5A2!zr zp$J}>v@btKa_PbaR*s)%D~qSXPd@}Rw=@)td7mLO(MH<^j_(`D<Lo={#?Jc92JMAT zesNa6UHx6WN&r=7l!<oM?MdAF%)O+YG|SUb>UJ;NgD8uw=$Q^@+YW@392KT4WL!X- zBFWXaS>cQwTxS3NZR}&M1AQ9~3Hi2um8**g><=AN7&=}UwQ6@|y26%3S1#U|e*ULE z%eETdvk8ZD$#qCKG!~&C0JmaShB-&ijqcpmw1gz9rz&rpWh!;td0*+auCl=?x{#~J zfI((n?LpuO!f`6H;#kw+9C=EYG}=E}FEzF>w@w$|Kro-?-u>4TxS^M!Of&<#T;pA< zMYd{73t<+%QAhwB!nfQ!$dkdiqyfZh#}$!N5-ghwPWA>PFL84jkuCx9!LR%lZxU7I z%TZxkVXbuU3%@R_B-wrv39aJQMhQbfjIt)*r~fR&nmd08(&4Fa6yzk3A9&h5lQ<Tg zqlE_?gk0y!8}gaAeroIleU6D7v*qEWb;D${KKRP`9(!FVT5jGM`s}rJFFyoe18Jm6 zpLCE{z6T%8PB{*>am*iZHm@)TT4PI`E%XQULbGqPIIp0v|08(q&76iA{*j}}sT!87 z%3JZYVQC%^8VXP$b53V3niwEut)YicDX>g_2W^F?Ggexcl3wvwd#gNUJpv-^EYc+{ zi}0GK#8YIBMTr~c_>}Pswt45oSI!i$-n^(ok$Q}~b!C)y*IUDqo`A_u!y04^xU;;2 z!XPgMp|;7I!Lqox233{6_#4Hlj!1}R5!o<e+rcBw?k~LVd9dl3b7`Z9m)9liJCl!T z%MQ;1<!r(h-{e($=<isJBn}T@)VM!4#FcF@euWIgnyE5#9|*KB@tKI#s#*$z)i)bs zpJLhQ2l)HpTgGpeB{;^FpFX-zwO~7(rM=s{^Yf<{S2)X70Qm#|7EHwb>6>r7KK<#R z{7D?od-kxn%drsc(r+1<*Ez7V+p~KQ?1@kqVW~jmx9F^2>2+*bHobB`<ahA+kR0<Q z>t_=|yHSgD7-!qZQ}6cAGTr@CjgjhJ5`2h%n>o*q|M*W#Kl!<z<fFrnhF|Bv2Dckb zzp)7tx*k$+gP+ajt@_&p@(u8PrzR_>&B{t1%O-5hZRx?r`Tip0P?yv9k9HuB%0wRY z0oeX*tG92vAcnE<)yrAnrnC7f+unWVGoQ{DeEK!CAuj6t>}UVdbcpSA?y<;5^R;Ks zK70@O7VsO?;>$7>4!zokv>91wtG*)wWDe{7P;zZ~%@cb#|Fir5!+-jB=LJaBL1~4U z$qH#lRvT?As*Pf=Jk&^)gUpJn4rLD1K52b}uNAem+Dmx%d`*0-``%V3()dFxfIP1< zIg*C@$dMBloKHGL?Dxda1W9_$qv02>hZDfrDqtK&Dqc+ri$BZE@=~_>^qc_lbW{Ug zIl*<}mTWAm9Gp08XS<86ibBDaQ3medccPb-aNsx21|W3#wUe`RN_no!$*ZAv^{tZx zGMd>l!M@8*wt3a*uG7txMh(Y&lAp4<E?!NSE<dDK9m3rCZ5id62_c1N4r}VuJ$LW8 zpE7^0oR%2<al+H#C@uYPz_<)ptn((o65N|tdC9*{L>ua2kT&bS2Rzn+j==Cre65sS zujaG*B3&`ny(_NW>l!D3J-u`&5Q6x{)AC#46$;2Fy>wSOOJ}bRk3*iawc@!314W~g zGIaxe(x3stJjy{{tHUnmvyMgw9rD$>CM_MLOzJgE!jZOesCN$Ar4G<}kOyg#U!9`f zE1x{P7<k%|D!qOjY6~k~*9WncT#R30(5Ta^WusnaRWap_^O%K&qBGebi&e7tz{NJ^ zYvwaq5B{@t4mgdsocLTRsLVrWoFL`+j~+PUX%fLH+SNO?y-w;9{ZIz8jw3RuD!1N+ zVOvt3>by8S450xXQGVuAchxt;ojbNk>$KXWD-v}U`Y}?;`SD-*mFY5jIGx8C=TlFB zQs>L;5qpRIOs~^+_p;*fFdqVAOAnr1Ect;y<Qs=GgYGz-U7?J;99+9X`7W!YZ?a1H z3j5q{$GPYV%)G+x8z5xJ$~Fe|PXD-JI|C=_I-Icq*w9-ztgl|VIo-oRY{waP^l`tO zTaNV%+>wU@tQLfg0{;?Q6>Z^l_Eq+8zR$-4w_Lm6lb39z;6Bew$bW0(E7#gb>jQZj zm)cNT+86Du;H@FG**wa*%Jtd0YUi;-c#})(g~K)JX~QHW@3^;qq7Uei)mQl_4zGbn zJ{?>s%h`a$lCSV-Q$>d?CDD)z?n84&&F_K6-^i9^2PrjBiNhJ$s^jV*H4N^8p&<N| zHsuA$ITD|CgicVW_M2PKJy$vF<kRNlp@z;XoEU33omW}uyz4M4lOH|CD%gEE@^EMX zua8uyG>STrGU=W6W`&Qiy*FLsqkp$?Fdl!3uc#k89$e+jsQOW6y_Jb2b(~rr%BNK( z6W4GizV^y%_`i2gM~@$8FKD*JU^VS_Z4mmi?8nj&0WB<l6pq~UF=6?qU0uTAd@0V} zE7OT*o|zs${siq0zLiziN6w425i(*+l%ssS`n6YZs_vSO@Nv7D!x?c!?;zejEOr4I zYKIN3tWrQeM7qf81V0++7p7nQu1`+K;72~qt0Pu8Rmb(Ptev!>6IhNz-2eHTufLvc ze-85s>0zATI-J#<h#s*51vt`BV;Ul=jlhRnjND*LkMq#*9`$qTnbWjYKB5SW=qErz z2gX6WHX9Rw-?|DjG=i(xp0~dF2DX!r{jw+aqrk`>&fv7I7_?^=={BGZS9f(b`?0@U ztW0)G4W01E_-NpvBZtCQJDf9K0aw~{R}=u%X;|ThJsR0cNM7#vz>0?q$DTaS126P6 zHbGAOvk!A3JDic+E7LU|gy?|xEs%@nE~6(`r=S0sAD;g0ANmXq=X&5}Ut+MirXFlp z{6!9)`PVjzZx*<eZ)0+9?~fUbFeJO}#fwo-MmL{H7ryzuu|31f3|7aJgbpc?qRX6> zpUjl0x~MqY7C{`s<p>(@)9y$!S_f<gI|)NzISv4lbU?Gk1^_P9zk(S%$i0%1Hyz+J zzKAiHVwi!bTk2L@Y2|W&fDu!jp~EtPBP}7k3YADq1?O-o6)pBvz!*nzlg<41aR@1~ zgea7eh0`+9Jvgr{m2>=BZj|+$IvP<kJrIUzp7_Bz+`J~c@g{}6!n7!(Dpr}4N9(Th z3%4Dz2h0{4u8?-z;2T=>+Xx%pgg5Yu1B6O)7RF`zFVfcQP1T$E#ctL}-h9YsmGPC% z=2e_Iu5R{Wj>it#b<0`tH7^|(o@WFM<`-#7+TeF&t~!>2LGZY$Txy`9?rJst>~>Zq z$wHonvgquuw2?zF((Q?BZ#~4(*Icd(g?~^G`IvJtfER#jvmrVeXx?e>D|D$!7yqac zGIU%~W*t;+<=V8_7*b*YG>?}ajeA~RoTdyM(&K;N7VP>RxxC>Rpi`>T11W7KS-cg{ zjK&dBr%Fo3fV8a*oTb~eM(+K{U5}Hq^%il;L;OpA^TuO42V)opEW@_2FhhqkjVWUZ z+Owb?lVz+X1I&}OEhgkG9j?QNw#Ll-J7!!WpAX%9KxZ3JvL0(Fg%3ER&yJA{@a|l^ zo4mOL$X{TI+mQN*oJi;FoXucve@tKh(ZG3{xXn{`UwHR<)&9ctm9Ktz`rY6CpQnRt z%jF8^t2mqAdXxT`Im2Dr=1m?dORr-(eF&*-ihE97FJ6ZX^vOOTL`m4gL-G3XJf>Qg z!M#CN#pBq=g*}cR6rFRVo!GRzeF_iOt&X*t3;IU%%5?JSlhcpkaQ^HM{t!+$wh<(c z-!ZaG76pd)4Um)E_G;sto6j3jrrtLL_5Xc&+V*djvz{Aolz*KsV57|6#`Lt2v|WBs z=(Y#7P$*H1TkkP<W;@JVS2KpiP)&dKXMaYQzI8gzJf&^J>#x6_Ej51WmwuUjn-8!! zjJFi8-JEvs-ixl|`(v@qGUM5duer9()AWNA%$t%z?82sUew#B5+qDrDw!h{ndpPTG zjsZ*uQHC%X$f==p^`iG4={PbFEu-o785$;)Ps3!pc4G5jcu<LTNa<|qm67-GQr%}T zsN+-|=C`4=^T)wntx#eM4+dJUc6Jc&#{}~#3;1_o+~P=<8)%RoY0m4xb}rDi&OmeD zj%1Cj#HUjTpVjg9M5p<Y9=Azw0vIP73aNv!KGp``z{#o}!09N`(JjtQW>G$I=+shr zu8h^m))Tt$OI*_|4&`Zpq<Jt7JXIG}FB*68*ipoBM*;EZ^z7Gsgs%h9&Ur7ZNxkpj zmGCStekG-&El+3Zv|Z6#A9^cCv{~-bpmen9gwv7dhuDNItjNU9evSf?t<SkLQ|Bta zfptMWvhK^VRGpe}(rUa%^l)5TcxLz{ihP+EaP6vDogz!<iS*P2syfhynI}&;+Z1r% zI@kf9AD&Zxq~jhk0dwRkf97*Q5nUs{XkGOttLj8>QNQiD_o2adoJSfW;pwncW=_7< zO?k_`@&cH$v`p#ATs%#G$5>8>vjq5XK<Bc9Mpy49FX`q<-A1Og)ivs0`0yd0^~BD6 zCF7kt_l6&Tly%b(I1P`p!SZT~4(_CLZ_<6*gnB1p^K?5@ZpuujiVuk5)Q_CIeoOy+ zVtx;OOML?;bg0+JEDm&Jvxf6*Mw57<!+V4BH;CJ^>aKFP?PfK4WlLSf){rJ`I@V3v zvuAIdh_`RDHzIXXorfRiWMT(y>jzGzzxstQOt(&+p3Yum%K|^zBhPG`afgo#T)1!* zn5<0QagYzB?ZNTPpmPW9`Mw`P#4fR#IFoHYgi2%$vRBwT1f18e-I~s^FSHKlW5=J2 z9=noum5&cPsaewDY<*!)+{3vY&RdxP-^Ss51&8xBR!MKgZXZ8!ylkj?4R^M|IN@N_ z@>^YbjV+y6nYheH1MlCsGHu1->?9Ti#p#U086C}D&X&pR&EoWMx~=Xg4d4UYBSKU& z%tL$)*4318m_*sMy<C$-T1_b`S7Ou`{$l5VrB0>Iz^C=<z_%Q_U;$O?k_*q$X0S%x zTQIt0T9=W|nn{B}oYhV&lNB<dTI`jrpqZ)+lz%<6iawwdjnZ@3dRIPc>u~m)4m?m7 zZ3P9u^k0y%ge~#dx|25rIPc(XplvuX?k{bhR@m?S9s`-(I-DPW0*5cUnQd?=2uuj! zmx|1_zaR<k+9hO!T{{2HdprQSGTq>#7AH=gnx1&_sV++X(Z>Kv`pOX?L}g2PXk6vN z%XJ)^uYMgzFKy$|C!fr!UhS*%%~c*+&;t(MbWPPnP%?BlN7S^fOYfb_hc?dRbbjW= z7tzfV@Q-BVL3R?9IRyzurB=KJn00ss$M@I1@^V%dKf-EUx8>N){>j->l6I;7nNN7a zEnVQAICWM1(dm8u?D^^J*|XCpzxz`-zK>%c&~=>6I>3b?O5r4MpYZ{a(OVp~ez{tQ zvwN(&eMC8&`H(Mo%@Y7=r}9>Ph78#kgAAKVJ7+tMi|h}lv-i|<&y>R%8}9faeLr9_ zU`2<dMYz%>@LUn+YVFrwc{R@NgRHWC>=+LvT=7lCX!8t?;i7-ABcF!YWbRks<)*8o zk%fEJJ@xd7>5=Rwy%%z&TX_OUd1`OujZi!)C-Tr9-J(Rt`CS~&J9loKo<4mlds4eM zcC|T>MV!^r+E&{Hx7dZzwtb!Py)!%rU?1my@27ug`iW0HH|^jdn>y0tu;iyc;#>y1 zvdF>d|DMAcFzBt&3{9VW%d+jnUyr%Nd6wHE1oEKo(ql?=*XY!L)y1r>CVl`1K_Gjp zkl{}N+SFMv&cOM;4|jx)Foc(+B>Mwy3Fat$5w_Hj4?UXkMU24|gC(nUZYf*#Bm98C zRvnz_`?wORv{<MEzzP>Qu^Yi3TFhHEbB5o%9Gi1EOJzfDWS))hpzO!JCmUjdwsFW& z12=Ox1J8V;%tj99mT5cX94nN=Ss9==I-Ifd3{ZFrgsqUQ$H=Pb5LM}Z(KV<y86l>R z8~jv>p%a5|xz{Gsn5Yuk3jOm6<82+zOg`}cIWBRWSr0#zb5&76tNX!o6EKtCoW@F0 zFhy_9N%m)+udk$12@h`O<NX5B;!O_oG?a}T&K8J%jFMH0bF3per@~(`Go4$^AYO`g zYf4?tc(+$5&eo@kf5?FhRYsuZ9&OA!0E@q}stbeh#MO0`AR?j5_r2$`7m_r`W1M-# zD86JHF_xH>GE3;l1wX+`fjKNw5}Pc-DtbN3bw#vpTkd@hXWEW*ND-<wb2!t*W!pr* zL$Spb&T1)<ZaHIf6ZFjCEKTXhsxPaBW8e>Z&Ru{!I-K2RPMxnBD%?7pdz+_T(M$yY z_S@hiXsrU&U-(Pg8Vt|u5BWdH;q05(Cr^GxFtecU2v7c_l+wWUW!?&U`K6bpfAT;5 z6FwgHXvS_gZ{6U-;TQOj*b6wJ4}!nyE{m&>iEt`TStz40Z!GbJaz<m_Ztyz_ZIElT z$wi0r)LO{o9BK!P9-I%`kGogxCB~9hc<}GsP-pXXzB%*5Kl~%vQo|3Z>2Nl09^NCo znhzty66A)YY?l8`=M&>5ac@Z6cVGtPv{_ln-fY~v0k7)Dw=<09{sAOBkOKeP7!TW0 zYAlLws@GWrroUif74r?o^p~bvtZ-iDn?|>9-(;JZGik%enIE{o<jk2f`9{hM&p$t% zKK%^Pfaw5;Lo4M<=WQ&Sb@9jDyN+k|?Kr1E{)lSbc<uwJ?x^*4yJP<Xo;6*O>ceTX zHkzlbaQ;WX`JW_W?)WT4vQl&kWg7^rVNZGlKQo#!s2dx-Jk?yFODB*<O!zhi+;DVc zOuQYm0aIs$_;nIx)h*6CCxSY+?%s8SZX6;Qe!qgM^NJ)UC*{PG&Za#p5!5J1bdqH- zU8jI}HTvBkyHPIkX8yjnoVYCGpR3Wtqa(_)!e7Qvdt{Xw_oiuhy|*8<tPVj5()kq! zHcnvS#4$W31+Hdo$E6)nD$EOmJu5JEau=`c#mn{!(qI{3%C|gArxh-8ao9;n=T2AE z2@aSgze>xN0z_L6%G(dOncu;PupMZ7FMYiAPsgN8zz1CGR7b45I@!I;K$vNV$SZIe zIay!CAWmqi)uf%pvpiWo^#l!FFInO1J$V{xcq2|)dqr@Zi_oav`T)aKn$l-bHqDzd zHLoiTJ$r~tIa$uLJnL|F0x#bN%c-|IA*4~mg2INbb~vkFwZa+sq)yf2Dk}}*v8=Fi z%~`!MnC_uG7sG>%I}a12b>t8Kz!9djdaumNvF`-X!IxXTAhjVx+kA8n8a?|#KL-)& ziExzF3_c~}B!q6^n<f}_TsbAc7s7)lPyo-`60UgCrb%$G(j7QMYXyDjin<*A0*-sF zIvA`6Me2cjIP+0H@QGK4udk4H9WBaH8iZrryK33s=Ku1O@|5iXs17rEG|e)tQ$A#I z)#}~b$bj<Jsk&i(1UGf7-v89!`8(5{Q>Ul%t{&yVi!@`QD0iDZo_xLB55VnbCFTKM zQ)eQ&9lq9Z{;VQ9ADFrK?KZn1^p3jO#?zU*w^;dz!}%SYbK4l`Jw|6IJ$b;f)i#a3 z_%?_GX6)a6RyaGk_n``l0m024wUobj<r?*{eL8;XL`_2BWE*AFSsf4Q{3x$8XNi@C zTd=1qd^k{t^U~#WIGo{!I@yBmx5IfW%T4TB(Ojeguj&VPd2JC#blM>GTdGxgY^jys znyB)*qOA4M0{|{bts}~l>(XWGNZnQDaXPCT)W7$ZLp^fVww4pR%83W6kZw8b)RQh_ zTBzx=Muc+W;lU$%l6d3B1t;k=^g|oZMRR4!<Odn+aCVib6QfM9Gcci`GP3@#OV)#5 zdEdeV1rP1A{o+pQJ`QKfyQRi%J_3383HA|FH*q*yo{F5|9hiw%?lPrp;1}J#@Xk4$ zth^@1wi+i-KRZ47^wX86BtRMDWsJq3jfesPZT{V7Rq%DT!ua}2U!S(~0PnFUaX241 zm<J)4Md*hM@W$3t2O&Y)kf(c;du5xx%tr_P@ZedF(=WWhwi-_%8|A2tC=R-=DUx7X z6KDPDaQ?<uzLxD`ToLTH8rf0<8J3-;?%+FYXoH9DL=%v|4tO2T7hL7c@%$%W<U@JK zlF$CvzOeD-EEPps5d=K<D|T@D+N-a{;rs{==Od3k5~r_Y67^7pfvY;8L%y{0+Ar&U z8GGjH<csVTcj?lF>EyFGoF99XcFx3(;__M$oJiM$Ghu`=2+JQby~MU4ufOt29;_Z> zrL{2J=0ow5J3;bosr7J1Is^kv*b5z3Zc}pZy|bAppFDjk4rf<u$FneiMAahC(kpp% z;xD2#9+de&<LxtV(?0J&%Z}l2#%YaAZR1jaXu^~Dy)w@FS@QMkw9UKInQy)`y^GWN z-~arNOh5LC(~Rkq1Kg_5!YJZndxT;ztwOb{akK8E=)|`eiVTEcd>Xj?B(~08hIX?I z9LmkQ9ogpasBLK+bjqv_VME$F1c;qjL}vV;C1plRcyo+lI!DTr#^ri^&>V(}Uw-o! z2`S|8qs+LrxRocwRHD*cAH?=xXvdK4MglBbvIkb^tP-_~*K6sO=aQ2n`fAJ4Pz+c; zFp`%N%Ea~(9GqR9U>x_ho!|)?U@i(E43HO{i2*56_%&Z~C+mhtX5`nlWtC=NA%`M0 z`5x|YmMnm9I1aFmYXu-tU|_Vxn?~4g?YLvRUFf~{T-SmNXibp6amlICC#nfHnQKdw zyhZ_VDqH)%`;0g9K%PFD!58hP#^7-{Gj1`ooLg)y`$aTOOeW1KWjQYjXLz2)+lwnr zW!gFFy0TQ6*_IlE>`@&9N|h^h0LlU}Gq{v1nJpmUQaJJuu;ZtBn*p~-U?#)3u2gX@ zpfl&JShrIn(&R=;^wT*1C@hWPIIybxdj6nqeZ)E%Qhed3=oxV2jmvfPkG$fY*F{lb zW=o2$uB2?F5w9&UPsijw@Z=>)b>|Iv<<&mNLtHf<@>-o^+^HQ@2LYH51an@)HfOw` z-lKO*+iGP$jgoN~>1|qruc*wM6LdV@smp1@UI(u&f@{a`>NM1A4KoI?#9+qlg|tV` zD-6<<cHRmhOCyL!emv6GP)0DBlZ2-sqe0^~#$Hb^IGoK}V99{6Lqh79#U0EmUU~JE z>A(AL{~JD(cZgMvyWx8!Z!UfQ^PiudW}KzYIzKE2Jf#P1O_OJXbS8}~w&Tr&S((jb z-eex6l)v~Q<QAdZK5nsC;oW!6PVby~hcVa{uHR+O<Dwwtx;Fj%U;pdVcYW$p(^1|! zb4xCZ8lO2FJTA7ehm!)nuE&RG9Q6XC4Z<eD4JaGK+W_6rk^k#(S|>Kbv)T061<2V9 zMQY<_@uyGO6cL+5zA0Fhsdx#s3#A5!=<8^yNh{mHrDWt_bm35ssOTv6&2M+T^2#?@ zc<~MoP_E{iCXYPALK42gq@UsjZvnpZ&O6hy&ptQ(;1B#DdW~)~?#+TC?2%g>-eYdz zLLnde-o1xy%-9j^;?icsZY+@dA(tOT{vQJ3ebJkR`M!b=iTKDc6~XWR&hOm+@BiL! zR0m@ZVdQ9`y-%h00{5_EXhZLPWvz6LOPB8n<cHDg9w>1hF#$8IvgN>%n{JPL9h^Fd z#HB+>N3$!K{cxVnCmqiAH|{gMosVfjb)JaoIFd#O^?ne|vUZ*Z9cOA;O_tO=@RDDp zX`a&|YD9q{f70W%@y(lgrK`^lK6|zDUFdVwsZLn)RGN-5I!R~{)-6^*Ms~z#*rhLy zeH;{q>g;jwLc4e^W03whxtSC%Q>H#hM+e2dTSv%;aWy&6!CsC_2Mw-7mLBoyOw;*f zhc8W`6`t<k_^v%{tE`g_9fRVH4saj&0wZ!|l-^Ffn{>W9<aYBKZ9XD|3~nQfyizUk z=v8-+vpSX*o(Q$<gM+wCKEWm5%0jv!JdIp>bz~aXa0Kst!?8}CxEqAU`-gGPo5#tx zPD6tO5cNzak7w}-L)~qiklz&s5gHBg$%ArJCg#(Dl{&UAfg5K#?Z82UMoGHW#nlx% z(xO`f7=3~U%UCBqAh=6?doLdA!~qS3GT@4A$S?nhvScLf)KA_(AkH=-55lOGz)n6& zmyNH<aJ3I{8jLF(;#C)EZ>)OLiEJKe(cvmRL?q5~p^-GpX1`<PWRO=_O}cbQtg`9{ zAnM){_ioGLLlR}^s{3~ON~dM~08Y1qZhN7hH0xkHor*Llmv({&pZCxry*iw&$Jh&G zm6gfx5V)g`Y<I$u*XB77!JvI*xw<X+S6aS)9w$0Dr1K|#^;f5x3@R_N{l#76g|bsu z)FY1D3+JvdAfs-#;Glcr5ngxaRoiVo_#kctJ;5ut1qbe$4rf+H+eJbNPTv()9NwPJ zuqu_!@^B!rVi70fPWNTqUiyTwjI5p9xGl$UsWM1M2Pl7wRnqUBzr@xiOVbl4Ph{nV zdpNuOLCFl>9Q0H7Sb>zM)-8;~nf>Q3zBk=>FiHE}qD~?!x>Q!P%AYdP?$_Ct<W$uC zG_8v|BoAUd)UV_>pHeiG9@!t;KGP1>tx6>0;Ln`Vxw6H!JG+?D3vGioqS~<o<G=x^ z_PwFeQjw7Z0tdgAFMI{pvf>Cylqm|GM0p6W;Ur6uHE6P+ExCBEzN-4NYUendbv9#z zV>~Kn=@0c_ewlHV&r0gix@3V|^p=mmxorlvam_a)w(pttp$A8vqAte@=W=qF%?tg5 zQtJo8_^<YE+r0GddA5;Y-(ns@JoDUhS>;?zYyahN$k(ES_kzN&70m0CI-Fnn@=I}e z$KlK?qz=Tkk$;P?*UFBNkS}{|z;gAqH6}pjw8?9%+P}!Q8akY_r3Q{`w_m7-IAxQi zJ2pTbpspsHvLx))=_-?*S6?azt9w8nV4}BUx6aYBzv`bbv_rOiZAWU+Hvy<@+gG;r zxOj28$QBZ(pL;gjP-Jy8viBjD`enV^M@BlW2au!+$fJ&L2dJ)ao;#eWFC1;r3w6U4 z&d^|8g&Syc&u%~Vb&rSUe(cZHP?xXZaDL|W^vI)+@-TsZ%Q^rLy+!D-O6x(1?G8B+ zq5f*;+ynZXufEF4i~W-W<by}p!<jyz<pG$;P2Cn^+srD@eshcquCqtog>&a{8ng18 zmDW1X-QT`ek~szgT;!>(<-wscMV8e^A}{LuB5!%T`No@U#j?h$hP!#Fae@Z{tn{Ru zL3wKH{j)B`U+q=<gYs~{!nYLOeEqHI?Kj?={>IP#`1E5h;BZEb)M<4hgZ2Oeh7EV< zy0C&F@-A$~05reiG)vtr#&eC`N=n)?bf`b(H=CEaKzai3-YE0tdJfU}?7NI?45q{u zjzUFa#dWFVAt&7BH`2-SL9RNJu)r0)7O+7a;hA_V2OR#*F<TgzgXz+l%9G-QrUy=; z+4KbDEnSI(fV4xIwm#*3=x78XfkZ||g9<by_=|=r6CTuG0YGBOR9zVSKyUs`lL+yZ zpuH<vilE$X(O{-MkhCbUk+q`&%Q#?(vt)_9N??KI<RNn6uFoc<4^W(uw|!2%$x(0G z7_F|*rb7p3oo~K9NWJ(0K|h)u8sSJVi=ppx4t!IqrB*)VZYkv=vEYuQ+lTYKQN>Lj za@e=m!%h2@vKd{z#kWp>O1i;iz8Pw+&6j##m!JguFyR9N$<`eJDseE^b<ib@_E=9( zrCKuj5?CW+B@OHaTY6`<pv#PWbt>eGe1*1=r{XJ508@v9>a?{Pr~#mKvg*a0s{5=x z4=^PkN(Rs(wt3ze+=UC_v@AsD{rb`cvhghxEgBj>c$IbE2F8F_Wjcks<SQ%%HyNX2 zy#T;IP@C(K1t4iGHW;;oKicdHZ(6K!q+QY9Z)KcnzrVz|)rT+&D(zzdU;1O8bi!xB zuC}iYaABGBtS}DUP9JOk>pV)^qgvU<74OX998ZoBnk8$-)PT;}+wiAM#mA9$NrHWm zyjF?Ir$n~1!ujcw-!saW%u1z4UJ7(e0J1<$zt$1|=9_O$|KK0|SIm+4crb4k`3n9G zUd{iHe&H9U=Xt0ue7~KcOc>o2+=u+y&)P?CCN%Av$t&;5e52qBau*Ne&2!}IcOsT~ z!|g22=0EzwKh79%l?4c|z4|)y48Cc@{OQo)gVV46+83thUf_)+-(F>JZx?8}wWvB` zy_8kjnBwFpfp0`=;6}h3=G=US(xHv%Y>3r<>aN@IN8zF2ES?u(F2;YSUPq>z6lu$F zBVGl^2$)}O5_eH;V|#qzwMPYIYMXbslwA=x>r2$pEF2fE{^1|~o9X43U&`Bl+NMwO z0OcSHYxL*22yZWA{b!$fZaQ`9G+S@n2B&xnPpreZF1&Nxp@24}<@`9qW@RPLZ-q_? zb2D(Iv!yZHQo|0$ps{n3*ja4*8Prmt-2v&?d5~Gtgi#gis>_EP%@}(L8Sq!{J2<Nk zcg<kKP&ziA5IW%6$pB8L(4DcuS>?&zuQ;5g*VSARfaUB=1WriT3jN-%n{W+!+rZ0% zyoFCXz~;q?E+A93(>pCVK;xv+YYqE~1L%b?n>2SE`J61aGhA3YLUqiw4CU8)sE$9a z3H-IygRc+Y8|9@(8TfU29e4RsJa`;{O3xl&uZ6bT!^v&_3{FYQD@D+*V_F*BUP1YG zM;zEpUX_Q=OgkY5w5GSiIr@TpZnLUWhqH~+kH7gL$vYfKE_EX<9^KK)voZzrh%foI z43v+nspX$y;XxWLmq7#9U6;}+Y}2GQdAK(|eDQjOaCGv>gIZxegD@P}fFbw(cvTLh z)&-oYI0g%U=~Em&<P)xw0Cm%qi8`pIMIc4bXp}CYS-`=~`$G1gq^$ZT@79G55M@%b zoAcSS(LrUWFU{hX9`Wi7P+wX`p-Gd+3g_Zo`4!*g?6vLKo_IYSd8l#8M`YKD_sY~@ z9Vicj@#a@&J^S@)@f%F@a3JNwlI(Me{t8n%eGsDj)TweP1Ho&{#W`5@sUu%oAS?;R zl^6Kp^Im#%TuGlYkniYq29^wtmCK-|CXrR2=IgqS!&&$NDGh}q5%3yrJ#)zWU-{dA zd%A%W@Y0Rz=({VkbrHc2ujE{3)$`S>IDhYKn;w7ascGLK<hm87F7Tc71~LF0;Mr+8 zh}HRfpOw#d*-QDIw=dBix8cxwggsUF@$o-bwaRMABXV#6j+kMwCep~u)tC3~tnf7U zT^>r^pB`gxH6H?HA7_wS=jv4I1z6&BOO86|18%c2`tsRnl~)7T+_RcCyp4Q2z!5y+ z<Z!h!P{3;o*Kw+DAQuLjo-0&c0le@eIyD9#>SEP-og;LqsW3~IKJxKr)xcufhjkpC zL09;vu1tp#cow#8&3e+El`S=h3eU-}ZS|hKa}oz)%WzmWc%|OI;=+r>TbApvL|)(2 zQ0L95y{-1A!`Z$`hXgq}(r(mE+Q3$v9H?sqy9{&7(RXFb0~tORxMeGj!>zlfwcY!t zz3df!7(Lp}zG3do?cRp!U};WKn2Fzzar8rdpl!L8#f5XM>b-Og2kY}VoKHfFc6HQ? zP|!g@CQju<EaB5FHMY?Ix~0ZTUwLWTv3K8e?8MV~wJf$2A?R?{VVeiJ$R(>;&;hBk z4|7HD8V|9qva;9@^_^v9@zc=p_><*u);5F>2_TfMintVd9Z=+hFrBooz5ER(cWmu( ztQ^jM95arV*zwA*4l3*D!q8b2#qE0hNT1HttF%#97Q0WneX2Z^T~{vF8Z8q3u{yvK zE*v3K`Mc!S9$$TV+K=P?u_qqSq)SI{a4I~NgLC>OE4ivay!kNA5B2Hf)#2<1N}m73 z3vql?`H{Q2>7J}9D6BD<EfM)!eey-N<9Hp1^Pz)>a9AJZqk%Z!)em_WX%$G_c&WYf zoc2Q-T4wLMYgbumO}+SWl+$s1AI(P@*T4@M;l<jFzC^#&4dT^lWyH-z>h_J-zDeJ| z#A}Fqr{hmPmC0wwZsr&0X%k`nV3E>p@35uMnK#~Ia{J!&H~*c#GX3atr&!@E8su(6 z9n6SUU8|+^rTZ+qqh6>(8%F3dH`m?<FB}Zou@oa-9vt_Y&s-u?=7!2I-wDBAm-3u4 zoi?K5aCXEq>PlTO2*WBAy@#9_ge<ArPVdxvwa#3!VVozyEjmHfpOOdh)Mo-^3$G=F zSN((lQZ}%~9!#RB!}P>9ry~M;l(yrovaviFYm6dI+;|vF56@&Sih-#dq?5QXV0OzC ze-<kTHR+9ONX8-wf)5VswxVh;?7DGlsa|32TNXh*xJhoJio(ht`v~x|FN^Y`s9Q_L z*)PhfH(@jn;R6IdI9K-WVM_DiS`4-|X#u8nt{u>xFy7IwP)WgQzw$w$YT1;cb1~PF zdafMP-!Ud;Oz1o(4rk=%w-suPSP#y#${I*&(qbr{JEqeLU&q#2Jy_7tWHEmq=IZiQ z!rz(0zmo>&uD8x<w03DdJ)P=#k*39Kb?k%lRoyJ6z5jYKPwAIZ2Vm%Jq8}_*2)k_K zPnD0XrNioy5%M+443J&6&ktf)ycdS~LRUc>$s?wa%)}p<g>D9Bb}O85m?$~TrC{b* zEHUyr{)laH9QA<18J%w%oN+k);tC6SmVHwXz&=>rN}s&M9DXTtPn@d}RLQ0+9Q_XE zFy0)F+knZ~!fG(ihdI)`%r|x7aAq77hcj)eOpUEfTt3XMF;+2#y_AN*VevN@?)F1u zWHW4X<}tJ%gSr?SOdhw?IB{w?oGB5xMR0W;V##kSk%xEQd3*YY|M0&KeQt*)o!9v` z!_WP-pPOEM;l=D@yoCi1Kqi0ny+QgRKhlyh!-u4=iw+&@Vm|c7F{|`$6jsq+A0i|m z9_{*eoaMK!-<p2^fB9F_pWt*pu<yY1=l{o_v8~3H%sr2?1=rvFrC*#r{k@;&<H`GZ zvl+c$5zSWpGRy~DsIwEf)_7(k3aUOf&Q&=++>UG(!h`uz;}1rD=zZGYNPUo&2k$== z$O8$BFds<zj=W8~OdHym{LRWN?Qe{80<~?87Ghj$5e(Xf?d&(N_Aj$I!f(Ir+~rob zzV(g`;<(HA$zFQ-tJ6ztk#n9g^$E87J9Fj?{;d7eV|)PHw;_M-=l<IC_+yW=FFW7- z!v5qfru6+FcmQYP7JtJ3#~scyG5m8@IREy4{`U}A3r104fHB7D5HQ#=&aE&D`5K62 zyMt0;VlX@ZEYtc6J2vz3PsK55@nc%<e}W^*$W}a^VdhE410L_)!&zlfQMR&2VEPc! z(s|9$=oBsIU+6*WGD#ubd-<!$a5>a0W{2v^$ZjArIizD!4h|e0A6Ew*xmb|6C?JU% z_Vo_u%4@a`I%HjWrh_Yc=mOV4qs|FwsJ?-6T?a(85sLE>`uoF#$|;U$R&(q0bv361 zWx`FPa1UcAnL2}oA<gbFvmFPXlV>0&u4UrZ25$M`(`MuL;b3r(?Z*%H?c2v|)Votg zT=%kSmnWGFPFxvn-RL-XWvSP<pv6Tf<@|#`;CU2ZR+xIzQjuzSVSujV)bcauEm@kM z)(?5H4u#haS>tLVstSRa;O{aHXZcizT)nE?4bqj>th0Cc5*<34R&nHO=)69rzUbu9 zkvYIe@1=7u`|V1HPt97lL(izYOlC7&Dje_o1)!_jtpCz+w~TR>ey!A&X6aQ&4D}FX zUU$`&nC3yRx;3xsda7<&9|EnheS&RO;iui91L~kFcI0Vk$qy~oe$YDog(GZN@OrPj z%xE2!jI3Ai0#mw`(YAJYP}X?MSg$&q-5SCkfT~aZs+X2qlvN&t(8i=$+@?t*7b$0* zZo|M!zwJ)^)>GGc^PckLF|FlgT8Gvj`H&~!8)tobMnl%o)oon7;`*y!_|@t5)2F73 zH?HwPHe|(i8B6!k`4v|C6L;|vug&AXef-3!Y2V@f$bdl@6LDX?Hb{vFH9sa(u5`8? z-Jafk+m9D$7Y<I3JiZ?XAFs(<h!Wa8<!m9_emNe|2`0g7)Z-d^-MszQnduH~`H|x% zdBtrnb6_7zSZC_JZ4k`x>wVcA2bs`y_r|p4`h{tk*NWC|UZ1vMYqui{9nOlV4pyJ& zaAuOel?jAS09QS>v$@)8(JGF>^>!BIK`!_;ox`&^lizFTOaC*{Op;{OHFcRfg|3t% z-dCFPp&D&k0HGh~M#`Wo#%Y_g$~kA?BSPa-9iD?997<~3TT{l@p^gAY+BhuRArDv< z92R~k#=fNbjNyz>eh6IWsJgiwp>AU!<hC0t(0!M>yNm9*GIj^sXt*chmaV*|x|c0k zjy(~F^B%s6yaNZT6J1(fEJ`HJ+kF!N06+jqL_t&u?3ght2qM)5h~&I7U3l+Zwvb>& z@5LL_sb_IGpE?O0wwH2&&|6R>ia^_>9P#|5PSvxS!x;zbP9~MdSk-?32d55aaWIp} zp&XrW=YS4tG!sl$#bQ6MNCS?|b2ulTe*XFC7!LHUwB6_w_*$Ob9>WQdnbdRE23}@m z@~dC_IuBs>u@%M>S>fCc=Nj~dedO+d5V`ZGJe=yOQ#yM6SfG0_yOqSrXIbHV>@g<E zHSQoYl=xRy%0l@@CK719bE|{(WgPHs>G1>~+S`9{Ka)%A44V~{l{e0Gcobl0p}f#n zaD2Os#pO#E^ZMTNFFv0=oUOxZ3$`z8y<pIda)Om!8fjbB&R;x#ZhG|_uS|zo+59L2 z<9!DX#Nk|TqzJ3{NjsA_+dh%nIOSo#?P~2y$o0mx>*z<VwBF8}V>5^IXeicbw{6=R z0*<tVqkg^q>T8S_w(}a|0c7%IR$7y*@~IEpG#zcTEQ@CjdRBQ@er<XeyQL%kZ~W{} zOh5e0NhYe`M4;NJ3Z*X=i*OWB2K#_XrB!;Ric?vY9C9&AS&7D18DIy7{CE&jiIfja zZyUdf<_R++cZji2@mQ&mmHDKh;7E(*8V4DNW7g>OU$G&y$P|diq-^(X;&4B5Q^cx{ zi=%l@W)q+{&ROA_#|+6d7$Qpq;5i|ban<s&JcVJq<fL4=QkUf-@T#Q0<#4ui(Xy6@ zn97xVVW=yib<jeY(go7RlYH_eN`DE3iVMn&JY39@(m#_l52kUHa*Swc9+w?2EzpmJ zm>2aryb%>SnWRi;{gEYCoL$xE*vB^xR(aE?q?JdnVh&F_!E2i&76UMT%bWt(<<K5- zj{J%jX_md_P599nBK<Z<*>U<<$CkADjAgLzjz^p~WYGcktLnM90-FE{g=4Ni6=Q5u z?^T7SXWU8`mwn7(n4j2Wud+q|Ty(}34apRK8mebuEtY9em3!n|cSD&6?#*SZET``% z^C73`8s(+SGIOrDDi#vE_%p|s9$<#QXkR3zIQ6$3@9J=suY84b4!v}Le(#m?Sd5>w zDFEef*r0jcuFt;+O_?mhnqSN8fES!z4>*j~9aovxaeMSIy6&~`iVHs?sB_qr$anqr z2iGo~@PoqJ{J0!%XD#vF2_3EW5m@kGl)f4_2?u!M6OXilXBl|nzsEkR+bQRFZ?@wT zaI9q0l=2*7UQo7=ICM$-()Z#ieuZ0yamm+h92@Mz<b(kAhXpsxQJy^UX|A{*3Xpc< zZE|$I+dnT&7kFU&KmOx?oY(N>$!2|n1t_2U+~=lGe)5xSwQ(f!SaaK`O*)*V^V=3Q zjg03U_c?}C2X|5rKHU4g-~GMmOaJ<d)8T_hra$^Oe;A*DZ+|*g`1Swz*QW3O%%`Va z`*tz!xRV8E+i~h`W8UGIYnux)h6F!8-mLeJ4_ZMIra(6aJa1F8lIx14oo)=~eGEJZ z_k9_@!y-P495$=_w#l;O*pf8Ksxxg(8T5G_TAd7gsT&qm(x2)(+_z6ZmVG$Bty|Zp zH{ST>^wwK%pwqlnPKpcRZrr%Z0=ymU&wgxr{<-I;r<kw!aX@WYwoye#97SXdkWOTd zbDbhsUp<fT`eO>4m6hne6*?u%&A?SE-B7c_`L}=TH#0#qJ{=As44_n`*B0=fKL<{A zWA+5|I)R~B;OJbkBY9Y`(iE7=U`Mfnvu1IHbE=L+odjNI0-1_-<*QCJomAyOp?fTc z*$k#|DNE;-N*T1PTyh~S)6%H|Uq_+AxU4+W0Zg2Z0asO-&tS)gG)5;0O-|mxDS_>b z`XGn1ye<YOZ7DP&AFQ+o@69G{I)Nj5%KIUP#UPEsbt?rsZySto+*iurDpHHcyAJ1V z@Tg<Ya>{7FLaYWGarn|WU9oKaxK)QMqusj0O7m5OWma_Rz{zT4>R(uKE+QxO!9AR9 zhnDXr)yi-_fQK+TGU@C?KD`!}d{{R0fm6J35F-U)nAecHB43v?f5YPf2ORtVN`nIx z&OONSIu7iyML~f1W0fLH%UHiFtO~x*Rte%0wnrSVWR*^3tHaqiU%yZ<9RM{A@=>o; zY4tuhSewd9oQ9Tz_sZB6=H_vN(fo<8Wf1<*S$S&*ZsN!<9U4wQEV;Huy*X(KFH`9W zkR3c(zjs+3>z9SIjRfVI9#_vBbTaieA`mj0>{#D1<_t!+3<tAimERsd>Q#frlF4m! z$#&H8(UD~N8jPmP$U_ThkZB)y_<*Bjud`wa2c!7Yk~quHqRh-Ie$Tea)H(E<zj>0M z#bA7#lC67g#{k?6zBn722G2kJYrj6NJp0^q_6i>jWQFs@2LZRN-DaT1p3(Vm;4NO4 zU!5L3acbJnlmBfy`S2tw>X1Ts6`pnK!wAQ=Tl{)fR!HArmEU#to;Gned#WD9!H1KP zTS&A3bkaV&51%Cmfb!4{dRgUs=FPWof-g^p9)B{g+wa-C3uM|cOWDRK%asoyvVt&< z4{X7`ThrECSEhT{*n^st8rxlMLY;2c)`BZ5c<4M`;jGhnyG!wGi@?_Ym`D0*rB9`S zX54#4cB7@ki4-?nRb)=al?_;|Q?qDBQ<v5?wyW%jDaw<y*fYvI1`((N8v}wkqXCc) zvT-(la9fUsmx&2wj023jNTj^IPw30U$$aEVdFdQ5L=&b<-*ha*;T(J80~y*Na><w^ zGV&n_wg-o^+d;Vnku<o<`A+&9+M}yt?$a+Vu?5h+gVR18&TLb#hdsq~`Z^Iv-Ge!N zC`<Uwp-g20I(-Ox?%lWI5WI5bHd{A5H$BA)=cPFEWD*XY2;u3xPyYh<u!0`w6q7#{ z6MeeQRu(V6^fDg}WQ!P9^&dKXIB&9;?6xkhjLB+4%Q#Vi&&XeI6S}dcvzV<k^1(hF zoaJzSGTUHTO}3}h8HJ)l#3cYvLYzSRFz*suH@xz79L{VZaqP+C<#6T!7YNA)4Fx1J zPyd|a*c9S*)Vac0NADFr_~X88*;0d*(ykP>s5)ne>VS8<du!wO^+B#Q`k?j>ud|<r zmsh^_jeIch_=%@zpR7E$@1?9OdD0>WEykg7z~=zIb*DXdrM0Vzef#L-=~MaepeyU8 zTYH@G26ecC{0FGO2OL2-tSn|V#@Ao|+H{2NG#+D5>pkp`za7W-R&20T7}Qs3kBm4) z$3qKy<MY7pqAR|Ut8Yi0de$v9j#8fSPxvUCT}~a~K!Ja@y|N(0V2kDDwQsPs2is{J zJ$eX-^YJ`<RwwLd#hr5SA9|z<`t#76bo<R4*qgJwnQ@tILVn@%KQ{fybG3)_qQhBP z%F0l5FZe4y!y<U*wO2Tj9b74w62>Dxt`~!KR=tlnz(fJ@8Q$-3CK8xp6V_tLYvjO^ zZ3>3ZtfU^m+L2@#+ZSMhCr*<=qz{wQABGNTtq0B06o<2gEFUBxl{*oNk~G`C_Fg8* zGpm0i2IER@#$c7?chs?EMNv<&M4Kb{LSr;MrRG0HllS5dUqp@U1tT;{0J2SXez=g$ z7+&Q;a*_s}!dnc<YX;JN{kuc>PC<U^zi18t(lG#<hl3jGqNStSEJNqx(yTqMu%0uo zL5DrBXfq|&{u?8qJZ%^E7_Y=3uiP1v*%qyXeAtw>Egdsj0^k0q`#ha~$X*<rSLqMz z*Rq&~v)!$d&o~g6j(xLOg+69I+~Q?{6);s8><5myiU-rWjhMsuI_Jh8GSA8iILT16 zknR2WD)B*B%BTJcdf*nx11{)@Oz9E7h-XF<7Z1W-Olx3Ba7O2Y`BR0X(0UwcAw>h} zl_oL8Q{!1I-*KMHHWUoUErzc52Wc=ZS@=m>%fbYMi33J-D^bFHKRw9~jlz-U0#*0} z#tZ{~aG69x=3MBnagN9Bt2}BhCcJ8EGl#R|cE<AB?tC1W#b4<+9RK_9m3f5yYR!E_ zs3X&{mAcL0!ZB9EYAe#7fMvYj64`~*dgqSajE!(!GcTdlgk&vpRu-y1!>+a7uam93 zgVFI`coaJkoks_1&7p^YM%(v;&Bt*#5Ajf-;848q&lH3)8oarh`Ct6r?@h11`i;zy zom>0Om`{J^yQfco_ot^*r%o|0*o6$8hYTAou#YLs=-dEa`rr-nBw3~9Kxzt)`sWrq zx10Ix7ytE_rZ4?(UrPK}zWkN&scyK1$Z!1@|Jn52pZ-)<HDk4~fo#PWeZVdW7&tT0 z1<}Xz)AjlBKog48ZdR&fwe2iqkCranlUm6t-zG!r>n5}Rh0pduGWjr~H(#F$-f<C% z6$7k%V;#8fetj-;ZI^Q{w}jJvx&4iA!`<O+;&bQEPGA1=pYzt@#e6Tx?de?6tbgT^ zBah%{KEXCSCj(zzYMiDYN!y|dfM<b*;%$yQ_uo#3Gc?wCy(s(Ge#1LIA0gmy{-^BW z{C6{Ov8c{N9a2_~hZ9Ggu36b)90U4tPR<4D1i}u=;OaS7fa-*MSa{IktiOidDs)(> z4iJP>uhKIh!?0<(bpH67uu20t1P5zHvlLl2jzt={&J-K3xYEJVnW@n7Vq6^1FrC+) zDO@z^gkgIGR$_`@N1M2nO(uXSZgtGXt8fh}p>WHgQE^Gg&-zM<K_SYsDLOsp&Xakm z*eHIa*%hc61gPQAngJW}fngj$XP{da+-83n^GatsC8g86adeEyq^luy=0$GMpTR4% zNLAxg1{nk(b7AQ`5rzS`Q}BqZ<tq$>xFfZu5tzY^Y?~IzUZ&#ZJ#o}Y9%#t3f6+e& z=*m|))L=ab@+05YXX&c^Rozs5$1%iUW(%~a3$@x%{cth|PUQhiJ67>^&^T3nc0P1% zdkrwe;nS@)jN((*-Cx{Ss^d_QVBmG#h|5)sixZs2)n_?T=Y<=mCo&aYeN3-b0C)YA z9+o`Yd8`gQ@yH})=%jLK8hlXT)(Xo!eb&J%O&waV#J!D`mDY>b!9$(c#w;U#SFn3+ zyAZzHd5AaljV!FoZP~{gc{t!CPp!h$*t-&*K`Q6g&yr{9kJr+r^mbCVbys|*bv=hK z9)>6<<()Fn8$O^_n<3TZAgy{3ck5K*p-Udq0?Ax0(ON4#FwIxsgl!uMf7&?W#c%rO ze;tSO>1U_+u3cfJhaDP@FC5PIR~Se$m_C2*Ix8UVOows$?qk*8u05<=<<(yogr>7f z1&9%NT*Cps4&tlq%^S#Tc`FX*!@R1t7YA?Yt}76#1F5=^7Lou87dZRYa8SK{=FD{C z*4=6MA@+4;RqTNS`=HPK+5tOh@oDSig>uG`HbMK+ZB|#~L|=xlohx^z9lRc=)7dZm z(sT$omnkE>ZJs%lBw~qNYLH&E1rcfD>Y#o_;=!Annf#59Eky1<Xi5F1fHcbD+?IQt z(DAfm>x-&R-oj%2Ywxw&*ay>-Uy3W=8UyO;BO11L+{BSb>XETrq^xpARDcSAWSwzX zePs6Tjjg2D;@st}sOT0Tm8T9(_cEsw($$N@nfljZn+I`}WlN1XoO#NAh}XRK965@^ zc|Tyvnv}jm5Af_0xPo69gg8#_7kuvBGg(=D<?0=r&8Mg1JgLVVrT#2ID+XW5faT0k zVH<24k4$)Q;U3PfeEpTIVmiu)ED!P}a^H4Qmsc4~>2MB8Wx_@JR6t}E5xTRAy>Nx| zW%qGrD~l7)KAR6>x-Yo$@J~6amBo|SGT^E7OIznw7_Ywk3aj>YIJ2^t{R6d0HKD4K zfEzNlzN+7g%&E6!Cbj3;V&p20Uf<d|dHOW_q(6pZ2w7WjU@sUTmoNGdzZqe=j^KOj zY3N?muYALm#YaNNLFmvH+OD;e=96yg!s@V_0kr=LC3`2IefK?9S<}{VW<SlUb5~2Z ze#lQ8@9G(|bo(QLlsKvlyL$cn*|XEjU;XNIj0Y0OpL#O;CU5iAUi2w)O@UwqvAje> zfK{@(%Y$iG6klb<x8sIW&pZPihgA;nYa7Zo&1eUPf6BG&7JVf4<~*y$U;R2;dtj#? zee4L%@5ga`(;v#OvXFLeA`fC?gQdu}1bIG8P!{LkJsVp7gP-}!(_cFM^uh{fTgT85 z*@?o3xy17m*_Iy2X$A2myU06Oxv_VZ&vb(lu{Gpc+mx&NL6a8lDvudbHn8Wp3l-4J zCaOe8KezL2xySTGE=jXaQV5YzP@7Z*z>PyQH74z4c&Z$-4GsBex+rH^^fnxt#}2|e zFn96>eUir&Cljiz_3G$hSc(@jrY_C52*d<q=FF{gIGZ*|EB@-H<RqQrkY+>6zERA< zc5>*>!?5J73@zJ?-^iI*<>f)B_B|3RG4V-jzLLEW7Yys6+HpC?l&y0Izjpyt@YvQC z9L^ahP*%K*jh3(rX^W1#s{=)hg=5A#b!s2wL%+;7v|Em+80Xjr<{=(xU~LOl8{>Gk z7RWgM9qoPaDqZ2LPPtwbqt_;>Q&kVi0_@6FI$Lr5Ym+ln*}jQZRsz2>^dnz#2V}wR zjG4a#d&QU<_zT%2Wp*pNaZ{I_!rfq?V;V<MSh0&^g&ClcvH9}0b*Pfc2F&1cQQXdA zl5KWZ2&?D<ETJ_1*1->yuYlksX%D~(k3l4~ZfQoCaYg~x6{4@^B&p?Ku323ZIitZy zj`~i34~lAzQ~Kz5inz1^6p*ycG0^`NY_{9G<PAyfDKPU;Mcw4#>lP2j;!6%ThB1u8 znX>U2@EZFH^O4f|f|v0dal85O=FXjbyM(ck<-5P|p;CQcK%2&a!bPT@7dY*QPqdsF zpXz4kvG1xn83M9Ba_OAq_*1NK=GKUuQf_|T@y?HY75~rw{LiL8_=A6y2d4XY;Ol(l z2|h&pec$(e)AxK2+jC$W@;1aKRyYSMJZ>hmE^Q`n#v_Z3^Fs=$UD-yBfnByNVmz~g z|7YLseLP@)W%}bk`eWXxdX@hE{B(se)FsAa=XlHN@Bf#7fBMY#eui<S_6}P_dAHRN zo_-0(2<py8AvreA7BIz5YG@;{n@%s8ZXV{W4S}KSqjYBTFg8uxcWB16xsO>K1<rA? zHp#m>s+Dp*GwSwl+BUzl<^vz+e}2yi{YFRqK;T<%y*Yj5D__nSbU*Wog9i`dh`uvD z`sicR$&;t1<IHy)1C%eY#^UbvUiNZWg9RF@nu@}@MximpSkAirHvBH?>Boj1w&d!g zggBi4(Qp1n8Ez`UM&kr$F~l)Td`&<&_W*Wevh#2<=s>SmN4677Mvb?^gxyCuIObUV z2%fLC>g<iu&`~*Ql9Y4|mM41z7mor;qh8T@`I=iC3RJ2C+H_71APElav~zZv4!Whi zL*j+C5SqSnDltHJut&z8xOT<$+5GY^aTx$Ipi~j<l!f08_;!Q}S6P`T4FBxp3de|p z&Ibc%v}kbz3tK+h@u;kgbERB0D)@!&#b9~{5Q8QOHqPxZ46Z=V2i<^cee3jC;zN#& zqa3RY6rfq2^SZe7P+qu^18J`EvU4kafHylE^4JL*I$zP^;AKI+$Wge;+`&W!)$9js z{YO6XH1NxR!7{4!D$Zl%Brf49Yw4F3^9rv9>aJXOJCoXSWj7N6bx5aV>$v$B!-I4$ z>XG@pmqvrX>R{9CSqDt?l6YZtdD9k;MS1si^WWQR1PMR#WuB&up#iu{M%~^ThWK<0 z+n{uy8st?u>4cMNbs(>O!GQU7_zGL&t4w_`vYiJS(xdFGSM!M@fxL!YZs9O=F*30I z54^#L(>W_J$*Ww{A?w4l`1q;rgR||<_932v1##e4KZGR>UDrWAequAo*TJ&FRX0N~ z=jBYuI|sg2cv1$^pe}4@4_)E3j*G`2E#~?B7rrnppE!xb`Py`sX0&xXj>A<3(0u#~ zVADB19C-HZ^=aP`UUg>$<lX~35aM}^j^h$JIs!boRdQg3HwW=|8OYth0dtSneO7Te zAHl)5KhDXlNXEu!Kg)(z+Y1ci7$7>hdzUZjUc13+<z4&py1gIvz@#bya8#S~GQ6NO za9L^W%g25o)1Av~tAWFL7rg9XRs0S*Z2VZzPNC%0Y2;CHu6B;u5-8B*thlTDFgU6s zbrH^^t;wHs;>;pnaSRWer4Cr<rll=d@7`OdBi>7OUWcD&?+wb?;(@0Qj<gwt*bbto zW6PCOx>h{fekm&qe`qU~2@dWXt~ji@qDT2EAoat32whTFqEo~p{5T=V;rK*|)~8!6 z+4s2`REM*BITup<Kx{fIocBKZ_;ip}qkE4Y<F&;DSw$=63IP`QMF%<o@m7WH<J>!M zWo7WS8~1RIp2$`duCCVip*~>w$tyK7YJUKJ?@2RmmG*l5(p9!hcs<+Y965F@TWaj_ z6<Pr3aK;*xOj6u8g`{0J=m*iAIGkA(e1*NBFJHYrJ^2idUM6Ms;r)=Y>a5y=lyn7@ zE|tA=`-j(FdUe{z!0_?oIGhjF782>(l{rcn9k;l&Q&FC+2jMNli_Xz&>{slU*WF&k zkM+etjzF}D1w%NteYXjcJK6^@rEY~SYg}m^2P+>feEc}_IE2F)p0yQ@fnsaHSGs7w z23(kpen8V5oV)M7%@?uR#=^ISPMmx?j$XICup#-U-a<lx4}LA{O8sv8e(>+?yYJ#~ z{>t<e`)WT8jGe69ke7819s5V2jCLhR$0gb@9nR-)d@B!a{HfEY^WnjuC0(3dKU{(v zo|GtOb;hk9{1D>>ocOQda6a<r0UXYc@U{BK;(*6GTfx=<$2@3<ttY@FxJ}ws9&%k^ zB72>Ei2lQ$`O)dKe(-dx#4lS%)&Yx>RhW}}G;nEcJl4Ai<h}4ziaaH)6A~@2MtF2E zVI198B-w}R^L*BkcePT~wiAHSBW{A*7SeTTyGr03=$0RX$o`}QcG*ecX`8EGiepoq zRyhccITHdCz6L<ymD9LriE-`*Prc2;NM6T}iMCsCm~1_#vb;t{|0j8G`mEV?-RGU2 z=K<a5ZuEem8z5zpAVqN!Cz(<xla?&mUlLWxPF0*rMM;%Y`s`Q|9r-Vazr-I>u1f64 zavUYHRYgjU5{pWt#ED(1vQ2^j32?&L4fKGX=g#x|)?V*>?nO8Hwg^a0dEa~9bI#st zuW7G6t+UTQYSi;g?Zq*`(LTI5wj3hGMgm|4ji{hUx)e%h&K)Z(nBo?UjmWz+#si8B zDaX3auWBgWj1=gl?k82+5NUjajOF3$|5g56=fP|;@Pkelb&f?8W4w{crVi)GWZqib z;@CBB_NhDQ_{M^(!h@T(o&pQv(qHi?8#j4iodz`cX+$mKacDP;9@92iZ>-<8HRAH4 zwA#EM4s8C5^S)o|GJOv`siU_GbA30QxEIAkq*9a`S7K8g2B~_qUB~zrte_M5HJ!td zByPHBjO+T6^jTVHn<H`HA(QzR=*>VVP1m(DE#=}`!i6Hd6x7P!CEht^>8*tGE>Yr~ zg@P;Ks!7Ylxtz^;;+oG@xJtmrHBW42`dl<3E4Ug`4HbkjOI@^1lyx~rwBM_7b&s(# z$4$F4;7E6#c$>vGS&%`R+r3C557B&p%e=~Qzy{`k7%Jse{a5CO<iCF50&fdlW{gsJ z;%A`VI1b*uXFnen-^tjBw<8_@TaOh@CE12xKlZVy+Zr8p!6ZX$Ze06N%6s$1h8u=F zRVEdYy2GXZhg#uGj#1FIX_a5>jet5yy>rfRk}b>r=im6B@;!!qY;EQE!TR~}kAHmn z%x6AB|86fxeO;@=Sv^bYK0%(t_kG|@cAUSKKq;m?wF|ew5WgP@+{)bM;`xiyGhcgV z`mKNRThn&R#SbPv|NQgJQ7%n?^H=}o^vO?slCi@c9^S9#<JK&E<6B#P%gMK_GpApJ zP*sL&035=sRsOZeUNGu(ZMy2ZGsnG}pVjws*nd~9(I|E4ot3uG*;cfzq=t4)9o2MB z6gcZM2IdY47umkeX2b8Nyuw`hHR|vd-T=34a?Wt<=+Wu@A9#9th=n!Ur0w7}<_>NP zYMXZP!bN;t%*|-m(mJF=DIQAF)wHeC&Fed>i?v|8o2{-T-`m2d&Na%^^cNouv|_X) zWi=63pJ+6~+^qtMtUD+hT3>~4hqDD`y62TNRx1B34reFnG<XY>5`5rV$6(gUlTSt+ z7}H|~za3o}c1%2-(cIx|+PpCdIGw{h$frm&MzQ3zT==g+XH8&B50x%_@&JD~hjTUb z<YQH=g=5F5lUMv2s~5czJ2Zgtm7|r~5w{G{_&X55ArT&ov(VwMC&_Zvg*%r^Im$U# zuvKQo`^s{u%B33CI|#R<QhtummKJ=plhHUUs5mTp2La05j%+Ka0}1zqcCaj-`C-1u zI^x?ws;ts+Odt3mjCw@GlArWUhQ`n`rA}JP1Ek6<PdZHHQ@-RUx)|jq?yU@t;&2`? zbD5)O=!kR9ceZ<&DOlXXD0e$z7ksNT(&u_^yuvhY<63_C)!{p*sVws#t>7h62Wcjl z4x`3o$21$q=nO3ff9ykhQa3t#u>tTH)XOdQ<%Xrw)u68<!up&Q?&1S~@9!+0rXzp3 zXWy=^zUB@sohj-+aze|quZc<|c0?ZOcSD~^7CGY(A-^)ZCwP}hI~vPjVLh!QWv&n- zXp<3S+)KA%<<SYx4ID}HAZ}qaNNpC2*3cIDgw@8{0rUC)_&=I%96dI@dj9fs1&8H& z_M5wN8)q{e+Iq_4^c$?$dxQPxw(Xg=^Rc&Gd^j*pTS!dq>Bh+;I2{=4?4vz%5P#wP zl^k!fDs|rhS1IqNLv#S&6KGqLD(ilbVVj5{Wbd_8r%uwTvc1Q~ZLB)n%N7W%ipAko z&B%f(IQT=yw^@ylba+_Ls^+Y4zHn~ZhQoOitDZNqO^DlPY;@mdCi<w50}WZnxZdD4 z49HSH)oQ0^t52gnp<gBLb}qD&=nrWDMJnK&{AklUo2zVr2BaLm$Q>tu7%D8%j2}gB zoN(qz+r{~&j%DMM%`(tg3|``O=Ead<d%^&s_%MI9QGo?_@{i6Ycxcm0CXpfpdDAWt zUk*F)4Tq6-7hdH6Mzv%2OxJOsW5Ru$)1C&CtAiNSY-e>mD`|JK5_iudta4@#J?m=Z z^T*&Inexbk(P8_l)4Fx?mG84Mm@OnO-NZS1Y&wX;c+(cz2D89N+WD-gR-Zn!(jG*K z6clb8&a80$E)M7Q46^nfJb*pz%S1wl^L1?J24%H@kISe>SH#%2X-{}ca1w!!iN{%- ziLOvSi<9-}@h7H-;lq;9HmrC3YIm-Q_dh~%vIJ~{&at(}cfR?Ze6%nQXZB9^Az11y za3fRQ2XW!fgcV)sq<!_}SM$NZt8CNr_=&N?8D*$1N!mVmZP59oYSl^Z0l0yK)jgcu z+Cyjc;bTYnXfGfAWrA&a+lEW89Y*4;dRth1*rvl-NAD$GNA-=FV>nkIVp|MfN$&O~ z5B{SA+Z>pHtA0pooxjG`9;Z&e#>%7Ta5z7j!>`2aw5Eo@wDhd=vBvb0qElDt1L4Cj z&A;;EOL2Uw-zU(=zK3f|jhpC;k~2eivc9KI5NDl=vQWz{SA0{p-+STP?1#<P9)}M` zmaO>JKH=TElfDf4m9b97xdn;)Jf41ok6ZFE;35z3{>o2%4u|tG-gJ?CwR53o$ygwk zhqx6eL0PSDoZ=`LZ3A^o+i}a74(c+gMlJG_P2BxDX26ks0LZ5y_@ha9Xp|<A9-KBl z2HSJe#p&A$I-EPG3q#=|*G!J3!@2Y&-aspIf_LDujj?=V7eoapKitR=d;~Ao!kGkY z)vdB6VhE&nw)w5{Ad50BWX?t9O?{i?^HOr^S}@-_ES=H5M5pjeLN%L0D_;>z9xt`2 zS&+6dqd4n~T(ro8=cERvvUPrWuj?A`m-4)>G17o*aCpgEC_|SquZ2>o{}G+_*|!SP zpRgbU$>0N>((ZW{o&7-Gz(jZUTejsw<{z<}q#78OLL3s&ZY~{Vqs$?ib_=~_TxFYT z8FJ*ob7;c@^)i1^D_0Ql(lFF8%JANCmD1^hOOfQVu*q+iuknSu(qbCP-joZM2t<+9 z=wuk2#ugS30$5)XQNJMzeDWH<BoMfy8_z}bR+oV{dKntB&&~JpUa9UD659#{vpG6f zY;t63kQs|f>G%Tc{Eflbm2|b)ZVOrqOPXBe-ygL&u)>Hi3&zGp*S!I@I4x)p(=t?k z$2o25*f8VYg#(%~M8-FyOD$V(1y-js2X(@_krmILGj0Pbc9|`BHdQ@QUhA&gGdeE0 z%7evg^n;myFy?Kc-1=|#{zLSsIGoutbz>Hsj0bLMU#-vRfccB{A-19Nhr*+qR=(#^ zFx7_+FohlpNL$9Ox>-7$iAcaMhq4#8KjQ6IZ6n>5>hJ&k|2`iO+{=S!-;Q?9^s$e9 zZ2H{iK1cs<du1EJalZgxqeSlq318@-nY$14n&C3$^P5k67>&Qom({gnVA`l}^8Jjz z```ZEe9uXzn{SEj*tvcB%#VF``oxcZf(Pf1P8a!Rk`8Cb@9ytyTScqY#rw9LR<T() zYYS_YYi-zsYMpisyLZm2t4sSDxka%Ek$QH&NceZ?;@#1K{Y4#1g;z|e7Ny6GEKeYE zYlQO%w&r8|47bTUbLNeFB+v&V`mSsPU6KERr=Mnp^8xa?oh;ubW8R~GL;G~R9)D8L z=`3)^SSfhVhCX|3{ZGs3&7XLvzTjOTi!!3(HK1-DRydsR)qv>?>a?!lji70H?}Ww4 zmX4{K;L}0L6o&=bI5KFOmj_5zJDl%ia8;|m>?j0x<z7}V(2&u?rGs-Qp8`d42eYAv z8Xy^`m9)IJQ&Tz3KbKs4*m*63`OVOH+Q>3_B;H0egFx`=6pNfp++^_X4rd10q{jhE zekYR#D`6&<oU<ZHn&^mM9D4q)3<b+H3tZ|llRwU4Qbrx1y{beR<!c_4!}4(;5oXm@ z=%J@EkX5(kaB(PY2X6&~6Y$x&O4obw$B{V(8(p@UXv2#^{xi|V9(whvJcz4xDXtzc zsFk)4&!&m@8v6DgG1XY&#NU&0I0Lrejc@+EwzJd;;GUblwk$qv(<3;6F;0hbZPQXV zDo@5cS?CodbDpK)inDo$1IRq+#Js{7V!QI+_gss=Wo_8j*WBUkgx!1v!zF06xvX#* zjU$NACw0$q#aW4lLff*GhOn`H2t*cm5?=jfyA;b1eu;%I-zZR*+HwsxlqWI~nH2@- zs-1w50XXrB%MSv|zaPzP9l9lmx-WwsI$_|FK_*liuFK7{P7P^!t<7pT(n^}Tl~?Mm zdHYaD^RU|f)l>K#Kyq^3c4QXBTQ*i(eyn4F7#$8e(l<!c_z(Q0zck%E_V{%EG9SsH zUOKq;jSJp?WpCQstkk>2Ua_p;V5<%H-QCT$8XNieqz+s6&DEm2rh_hJm%T!f<?5Ad z(|H`(=gwYa<>SL~u<;fTv`Y?v3G!3*(fk++w_v2qbnIQabPd<U=6uj>_nw{bEUdbN z*61unVVmGePS__6-f$M&yu{ZI8944-e{0%`6MgfoE7NAKH|cQ3#@tS00}e&Y-E9#z ztgAjkuJW3b=NWIZ7g^!a^3^`Gf2o4VS2Frj<!?Ldt9@nrRkqqK{}q?(l0Ws|oZL1H z=o54f=-{h%(|S_)#e=kRSUrgGL{?ou5mYv5tJ1706)yOpZ<>`cT+4senKBRVNsIGT z82cBFOm;X+FI-0l<!s9eejU!>(I##G({|<!6JAT@_0r9|_e@*aH+jq61JfqHoNW86 z9_2UMBd>Kj`jTmx;om;tJge0&usY=eE1dTqd?XG<_i#@6pyLhNxt?Jq;=zIY%@UpR z!A$I&r>hrmOya0@wbE`JlH0azuLn>l1?!n^VmHyJq|v2yMD@7Bc_U{Zz+A*>eV%O- z-ehG{w&lRVN`a|94%=}#@LK&9|3;Eb9CT<)F2cvjmrt=T{LVax+04Wy-;6-mv<2!R zNX+B~fjH}pw&4orGi-<9>So6^2U%skn^)+BwXGCK_ls#S#G%u9*r;~p9_i<qEbF-5 zLz(R7EA1P7m6ZIJfn}%e#iLx(wtvvh^RO6VH<^&0;RA|JRxL*#0_?<j4sdWNh55zf zwGJ^gVY?=J<8<u%5ycn3|GnuD`46!dwI3-9E%8Jb$(?J9#87=_$$5qSCfzsLeJ9oV zF+K?C2ME)@1DmmkWf2)vQiy}3WTdg5Zm@OF>DOMLzW?p-P6v-3oDOlgjgNcRnl;Wm z;JI9cv<2Kr)9L7S`sg><OYaP;;IA-={mVb~W7EeTJDN8_)O|S$p_$-W-3%-e0f+KN zGr$`v)wb6B##R2<TB8bNK__bFaHg~tsn%&jNQj4WP2u?4f~C@oJc2YoaX4F{24M1b zy1bPv!B07p!U2BZhbRj_xG<#)pyX*3>VmJ3;3rOcZ#ZOW*h2|03_)ZG$;6emGGdUW zbml$rLzc=v?u%&WSmd>&Yb;vyYtQP+Bg?jP;w+si<KVOPGcYQD1!2c^8g{O=2@{)# z+zc2?e!x@nfN6Q9t1<>$gUbv0>DA)O+DY0#`YQ0*Klm`%dYN%DeYpK7PvI8jAl*2n z;j{XjnzJO{{PM*iC-v)DYDKY2KpupVC$Fn*@w(a*$ARjw`juR9uR6@-{Rl0{h>*M? zw+o<(>)+O0-#0e1R+d82xB|DpRTnMCLOKmOa+@N|BEulljLqVKH#RA==#imLBz7G! zVqlqpRLl&MY^(}*N8YiekHWCX*f{#!37yINSz7Bfj`xN|2OS^q!I*KY(KHXMWi1j- z$Xp|4A>>GF+(LNGf71}cxSA&*C)bX<=MHC#zWO6zt8NeHwDVE=B;)+3rSp)ic*e=< zjN3oofC6c*9S^vzm3gjS!r9D&#>_{^pD_dYH!-%@wVyY+a5!(_y2eLU59F<E94n#@ zSRYbXth1!eL*!FbE@E>nFhB*m65hPNo#YDV3RMnOrIux~xaT6>A$b46ul*0xcfRv& z7TWO9bq*b|AO7%%ryu*VA7gC5NB3wWoKL)!;vh9ntNC1+y7I2&UK#s?-8nYU;qR(t z+igFh=oW=HS>^28OyB+Pcc;Ji-~B!M>Nm3WfFDwG++m)lKlt=?{HYVuCFTvzyH!qB zn3wh!_V#uhT8693@m}!nhWu44W`=Sv;v;^}YuV+fS7jvk$^F*k#_`sa|Nq83h)pZy zT&MSv+7eR5%bwb+dAW^iE1Z{UH_YQ4@Fw$+^UTe8qwWp1hT(fIwmnyP$g-1<ksmvH zjIA^t9}8#o1>CA{nbFqRE_!d9l>R*x8UlR|!>jqA{e!N5?{rv;uB5qExObYr#@F=M z{q9%3oIRXVc%$)N?X0Ou4vlLMT7zY&JR5z3dpYR{vazX7s2UH6IT7v#LOf2w=HYG* z=e&x{fGe+!0qm<CH8^MR4!-L+vhrH@D9Cm=XA%z0JXwPlm&H$vZYAB7cMkAyHiq9C zaA(Q9_afowRi#<U8>g5Zt_D?u!*W8~8JpiYod9&Y7<umPr06KURwrK6J-Px;UEQ&v zo-2pzOcEhtS*Qbb8D7-44%0YQs?+vf{PUnAFsn$zhcp=|17o?zX~eybL?`tXr?ZU* z2UIX=>GV?vJ&AUb-;QK?7N&L7_YRho->1DgkbFucU2#NC@xf#}ro~~<fvIlf_Xa%4 zP;5_|F@w4$E)z#O!8nyNm@mBI5SLDP8wMSo4gi$JEkATPD~~wU=VlydwQ{BO8mDO* zmU4CqFWK-scrVA4lq$r@&^Me{)EVg9L>5CiB$k7u)~TA%*5(f9=xXR(+B&1;#nr=Z zuMvHNQ(Xl=gE=Hw=(d$*Uh#UsSQ<<Xq{}P=P4H;DzWPN{bfd#tops$ce?G2dF+kJF zj%Ahez%Pue+1>BRhTYCaU07xYY5E1~TiBW98=VqweX?wXk9~tz8rqJ|53>gr<~%28 z19cT1#$}xvrqhSLs1x&}C7i@Qd|3v0^H09zZ4>)h8;mzZ4$iSf;<kS5Gt=$k@8JW6 zY~f;_49Y13_}0mG4X5#CoH18!P=ELU${rm#>(z<nR1?O?0<0aOF=#UrDE9@|xpsyX zoxAq%F)$o#>o&Lwq+}0I$w!obvWR^spA-0ttRlU9g}t_KZD0k$PPQP}j@&xK?Ur#E z>nQG5=HT6rw}@MZw{YvBznSwsR>JPuczfEu?)tO^-Z!zwFKgVXf9k;lyJAAIp7`i* z$kGlvVdT$H6L%-#H5Ey8B?(kA0OtyN+fP@@RGyMK<wkR$J!bNctocu}cEfGj(1@uf zs;zNSWE<>ZJ8Ajb^qNi{EIIi|E*#^$pd(G;JaRo~h3P8C2tZo|2)GLFj?OFMBA5<- zZ8|jDhUo{X3!5wl^k}=U4QZRUZTYgdPZ@ZfaRU!5HtyUtT~Yh&X{cjSJ>5heWspX< zXYy@i_a{C;aO;G#d^B)3E0cHPV7<etWLLG{=0U>-CPS`H&I2i$hz&ecP*`o+y5OU= z+w{HXaTsrgkDb`Dx=bHWJz3`pCJf#WXX=3Q!#m1q8QS)4W|ef_BEdm=g@-fe`8eGU zws_gf$3)kIM-$L?>Z)Xse%JF#FNgCDR?}YNLCR*@z-@fc))lz@aKg6H!*&z}pr7%; zf@^haKW)2n{i^lVy24)Zyzc3$V*5T<2fMn#mBZSLtDTfz2cLVL8(fL#1B@GNt8ooH zTiCDO)jYQAPOj1>lQ;UO4D4spu4xLCi}l(M55m%Pi4{V=ed2zHyLR(1%2)bEe=9z5 zIO(&kD2J2wBOc4P%J?#0(mu@|ihC&&Kji2n+;-cCf9q4fB}^{aS1oBMs=W}iefU`% z-?n$Q-3R#ap!;K6esOjI;~?8YT2C44L{?vU2xue@XCFqmrN)cj#_|2=BRHK8<wK>m z+m>m@Z<en%%2D+IUPf4lPF?Y>9B<Oz-M|U|bARqr(?=gW9EY=Gyx27GVL$nn_EC1C zObS`D6>7_&+C<xt2;py@qU3@f@bK%oYOgpdK(#MPR(Uh}p;dV*KZ(#vxeUPSH!MfX z&3ampOFl`HzC4CM@W*y78G3>NFW-)BJCrN~mv*Ae{28iy0O!o%ESk`S=i(`#TuYr$ zs1`U9Mcdzc)p$Bz*VBwgmxZyE4P<hnOy+Ny7d(=u9M0NhAk*i_M9C%f3N639H=c5~ z4;oMk3cwd~dmUUuKN^0@Y9NiUL*R~*WAwNocA@=@dPaJcTgj3>g!a-h&iKxcx~5&% z;av71pV=Y+nDigE&!b=NZJQ8gP*(m@gZ-sJ{iZBEb65wtSk}i;hUIV`@T7O>a$4LE zQmv=hf^;}Ku3=Z7TjvGcG@AF7WxK=`?n{Os1TM7rg}A8=v6`OuOFU3DOa4e0`dOI= zo`AV)(gINGwA;l6w9~aEZu!%)Eo0_aRa}Lq<6AeYY0vo&to(7&@TOZ_Z2}!Htk-v= z)oEQHaxZ*j3U;FiURNl*@?3nIx9?1w^PPC&G7k`r<82+zsoUB$u-JFyvv0jdy{IvR z+ekP7n?Pj0Hu3Kk<Kv9ua_!rUZl6bA$e84geGBw>rknAL_Parc^S(n_q_KtV#&iN_ z?m=2wan4F=KVn@?JuwYDhWb^{Dmtw};=S!qx^BphWe;cOsBgQ6v)I8SD(AM2nVfI` z=5PKltp0sA{kvlbKLq@~_q}iW)Tchh8;1Ls!|<JnwK$w3+aR!H>#kSI7a8xGx-#-! z@~(s$GSR;~@6tvbgJw=gS$Y2&Z)N@VSAKi?r@!-0r>CBJYWj(v`0?q;(WCkBn%jb% zc=E}`0s!08>L(}$%6lzgt$d2BWS<r4S_s?+=0S1FZ->=ovHHH@-tPRz$@6yj{%uH0 zZGC`Zn(Opl{EN=|+-Pe=uo`-#Qbx{2y3h2Xm+h2WY3Oji%)=Ew_W9atuT4j><qv-F zLzxE@cFR})my2j^>uMZXyErhvNcltOEe(Hj=9xTHo@#+t^Z0|^uSHi<SS#EQ#?8HR zH~sA4{Exo$%b7sf$!PE%<;gFHOvkmO#d{HWIPtJS>JBQf=?H+aLmF@zhh?MEm(D^9 zlY_+TJ*jb$1ipMIfQhw(({x-+5H~XTvVnIMq08c3CB*!Sfnqh3*T4}+AcW*qzA{mR ziu^f9bn+)7UYllTsiRz{t43tUXax~ZoW#hG6+^_uiOjtY_5LuKc)FtwP4pptCvY00 za@#37_*8Cj6@HA~rTJ6@aT%fw^U#3_ukJ#dvrfD?^L6wxX<i+iFb98h?__Z~aT3<f z(R`8HG|K}ThH^MNsF(Gkn^l9n_OA|GkG_Iz`L-SOBrr($5w|jQke?_(#2w7fk--9S zmdiY><~vToril#F@Q_e_Fa-w;6V~Y4cwpO^EU$*Zb8cHyp1B;1lxPo@Jj#R4e9Kh_ zM(l$8${(92u5~AVgEZ#0uLD>*^5W4>cPB086*kThV8q!xW};7;>E@9a2Qa2zVr76h z{feqQxhic34j`|6B7K_yU)2qrN!lI*BH+bgex1iiUV{nJ%qP9XYjZZH8*ATU)nQ)s z>f!!I%3-}&kNwNLc;(%6SCjjc+iPj{M+Ge>?Icbi;-#^fdYrN#K4<i&!+FJu?r3%S zBfWW^)pjF|x&F<WIwZgF*#|%xLY#G198_^{n)N|m<6t6>aA*&iYn8Jy#i>8w&9~!6 zKRa#yA->E^9kvt0H4hT-acopCINh&cGv_WqhmXIxQhD<xRtU4oS?ucAqxOuXytszb zV9*hG3CG+SwnEstbswuec1_!MDn|{Vr4OK3N^Z`z#gO+dPQJ_*3OM&J@WBu4<slq= zHFs6#(ifMuVOdmLXU8Z$S1jLR|1~^w)7CpTa5j5fpSE&r=6W*@Nz4T}m8K**pu6uV zdFn%g$Rm$}5u{_8q#Z?Y`)EWK1u(ht4qd`ec&dqhpu|B2i^lZe5r_3DxvIUZw;c*^ z^lLgcr|p!(KwGS9PHCe(3!AfKaxZSLfpyZ7xS~&U6WChiEb*$ZI+mmn9y#C1wka|$ zZ`xQ&EBu0jT$BNQ!v@|YNjYGL+R*Kxi;BnoTp`0GY$FdHw(dVTZQcD)J`Sf7%54wi z4I_%9HGPo`5aiuH>>^L_&%b#QTe!wH7KihZy!Ej`h4L*9>avcLQ4X$hb^=HuykHYq z;e2s=>BX069=1+<c-3s%_ObE^7=3Yf$Z#`He9fj!pexd(udjAJyqss>V^<bjU~ln# zM-Jg6-IqO}(;q-w{V#Q?T!~1%P;>Uv7uf&#m6u-SA<8aR79Yr-#T(h@UmzWv86T*7 zZG=2sPlB0vS2&+!V5y_lHtFEuBU#~0j<kjLx7I-Uh`l+v29twTVQjyy@et_(`aF%J z*1ek_;$wgLSdx9a$IzY5;^4ELv|P1)+7ZiK$M=~x*e9L#()MRBdqHnSr(}T-@&Thl zq5|-#8^;qK?Qqsve2LZK;@JZq@<PV&VB1}G$BE3bypg}_k7Xnd_r-QB;>6k2-a6i` zf0YY0kT3lbvKbp5QaRw2GGB*IE}!S&7^{<aJj4SDw(r?azhs__fjBz`Qm1Kiz@vIC zn;d9d=lwZfb99UWy`THSr>4)o_XH0s951Sevgyj`FA7o5Ie9V4Oe0o_#w_xguH(6a z?RtW+2Iwt9M-icZ-Wuk(XZZjO8g(`DDw_~-uoCZ|!C!I5HoeEjXrxR+XO0D%u5t@a z9b7m=!KpD2H!4QKqhB>V2nIvvjqXVAy@VTkgL@9o@*8^cR1Rm`({}0<)UxbIFzX2L zBwItq$RnQvpLxZT#T3a$-oRU~K7du$MpbxIkAlK+T_-MST8?=mh-}?vrv6aRT8_56 zU=H0NEJ90E+*f~?1UpKZlSP=aIrVHg`6iJ1ck=05O3{t07wt#MrO3UVNc3)<A7$&q zssI#r@HYe4Okb)e2}_$ux0^{K*R~UjI+F}$Qm<&QvX~7%lRekmCX6bPw2li3ZcLN+ zrM?TI(;L3dLXN9(nVKnK!r(sViWxwui`D=Ek%glkJQTmhfu#^mDr;ctvfA<$7#BA+ zc3<*U3B^#$9sDZB{{foQ;JfnpTQDhu5m{r3%2YZrQ{Br~Uk~t=Cz9Vnf;`2;5|5eE zW08>R&HXZ;@Jl*f72YbxEJwGOgMPzGr*SDu_&1TmzAX<_bG=;QT;nw$tq26|**?U3 z>w^6n7h};*&717^eYk2~x7w&Va-}(rmIv#Q`8vqGw!D!C>|6FQR(5qW50)MK*M|aa zCAtn^E7ZApeNYTT$;Sl<(~m~qB_kPDzzCac#G9hS`S8&XaLwINv{X&2tb+&<*-nmr z*0I6w{_g)eJ@fUiWwoSRYS^!zc=E*b(T{wTt*#!YZ+!rV^WZUzzRgd!2X6ziNV1F; zdRfHY?Lzw-ejW6idP-i$3F_cH<F9}Hum08aw|@0+O;0}g<n*&Y`?J#_J`jAKJ#qK* z=G*ZT$9YTYFbfTQ;6NWj9>*1#uXO?4jqHd^d8`4hQCR-(Y@p<AbJq~=rq9*<tiHb= z+6RTdAHIJZ(yK15os+xib#?Blk83P@?8$aWJM6LVcD{A;o$q`n_0=?eA<w_?!gQ1m z1b*m4Kg_(HxvvZR@Vz*vdxJ5yA24-4a{XocUi5i5#!W-B>}Y1J4*o{RI$D}p`VW4& z7F|hYt#Cg$M|a1NK7u4xIDh5NZ~Rxkl1AMLoyH+^?Vz;+IC=5hhbS#LgAKazPTuUW zYy=x#Jb_CCQu)oJ;_axattfi#_2XnIt8$zyIl!jD^K1iXho!?gMJO%zh$F7Pa&L!# zW7<y7hE=}6C0XI+Lr0ls4a)=_NLfKjd>TWTDMuwdI56hVNtpa+#T1C_AjRRNR+**c z{?;0#_vVi-ki|6dlvA`;eJX?L9wms^UapL*m1{a%N}obxr5T1^jdwd@)Mkb5e8eZx z)ebp7_$E)qtNPIisiUcQk{@NWT%_wD%aw0_^iPz+Enq{U%B`r^uQ;P?VWDM+6WmUj zH2EqT@BuAuMun~X{z_{evh6`BiL}ZeTU+4QVOH_dZysU?(je62Tk@r6<uEkNW+&;f znnVY#bcJILy|p7$r@uUFH=gIgJMk}^C-Nt~5id<)l;6C8g<sFcNzWkv$w#~cGw<8s zd|Agh@jLhuvW=ZiUDM<-Ur_an&p4GWd+k@9+c+AuV;ye}&V3~WG<ndms9WtsXRzlU z;_?$+dQBd6m@;H=<wKjcb>XrKnRM$`9L_jX+!IM&<wY$>KRSg69nR4U{HZVHx0AQd zhSxzqH{(ZKImjba>}Lib?gh+%wY~`_4H9F&>OKKl<*e&A3L8(Sg!2zr!Cav#PJ{Rj za~iup{bSSi_kWP>Gk|62?zRH9Uq~`-1pWpNTUR=~ewv2?Y;Cc3KaRR>Zhr%w<cTRz z2gFT;?Fg%;C^hOK&ZJ8h_z=k%?2SEq`S{=7{jSEuJ^;-M$Z(|YxR(Rk9naqTs{Z*4 z>=S$HVw_R?A7(oS_JBrx<hOpCx!P*4Qs>EQ%V(Q<o!8>7v%l<}D;K6M)AecB20k3J z4tvw_jI&ZUbU0hCPWp8?TYjY<buJ&CL9VdUKqoo01&*qP3X|l;pK~hJ002M$Nkl<Z zPi)2X)YHmai8{Qh-PO5nTW0x2mXuS7<=$Lr7ecejIPgsR%MNMZ$!LDiBu~!C=l#H& zwngg7>Y*)QE6F$Pgw&eYXk(^>6FS<DJm`o<8#$_^hzqM)3N}W1R)JE7thqW*&=6MO z0|5p#tQg*~g|f%tyzkf()9yo$@Bzx*IC|+D<ric+r0l24xo%x38JzUJ&WGjBo<2Lh zdH&jT<gv&3aNtquux(9olRccZIsT9gY#yY^CQozkurm1~D^H*Q=JVN7V;|d4JjALU zKN@J8a2p5pt&}maFm#7iuVyZpu?;c9$H|voslB8btR3cKeGj_@1o_KufKs`U#k^dj zV^0QSob>nr=K1Ho702k2W5=dlJV?pD#Tc6HmG<X2r1~&qWRR&G7K|qy&fjIP;Wzn6 zo^8`{R_Q#<-q_O17=g2I#i&b6j5sI9lm%O6$d6-!%j}JQhCQ5L{QisiINsr-huIUG zJkX+2q)fXXkY-E(9O40e@VJWlm6u-PEiFDo!UXkUw&n1_P#%z5kF-1VQT>H{=+O6J ziFJs0WV}rMJb#Wa#WNVz>Fp}#v<nFAIqHL+JovFSk37ghu+%L8T={;6*JG`hw%<Fk zD`k;R*DZCUed|2;tpgv%Ccikvk66AQeU7$jJNwk{*v&^{8LZpBq<tW7m7q398F7>% zh_!Hd;G!PRvY%ewLc*^9{m=jC^b=42nK+!waa`6!#wyQY7v3vpg=&AKWw5o7zM)sf zdTn1LHsK1=*t>)n&g%HeSNubGK^r)dEaT_|>dIzvmA|k9I7H>OIF+~LlOOEP*gyu} ze8@23gEJ1y!c~*w=4r{RF=adE7p24o!6n$@s>(r|5m>t$V@z(-wvjj5ita=u|MD41 z3p_=PTgEE#E$iV?8wh>!cqS|zg;hprTuspS3nb`l4coCC9HB{m|FBbm;&3)o*eMxA zRS^SO<BUQob@5AHomzp9eVS7GP$ibnYKJo;sPN#o8=R-8i*RGZ5j}Fp+5W~lq<q!J z71h>*{41C26^s1lhPc!nlf7Pfh($>Q+&ayD<LUGfdAGD8Sa=Fq?01=CL@pz^s!S1) zJ7w$gQi`xXV3r&JlMEvjewQ^`<lK>@O_WU;w+vOZOJ35ik{nKwX9+vMT5e%M-jTiA z)W)V>SB6d@HrYsTVTn>gxs-Uxv@&<!rGA)Cbe<P<k~{HYG6al<LwuOYst^Q8lhbsy zBacipFJUM-fe(&8i$4*eV`6P}ph*sGbGA)iIGpJl+tFNS@}#agzNxmsd)wC<(~&;r zz0S)WOY3wN*0<;4aOOH=@&T85T<TScTkR%YDC3>2yAQ<Syooo6oPSvlQcmcw&(+@( zPg`qQsGAbIWHqA3WhH<21)(Oe&;iX2_bvk3G97*N0|5!b0^qW(a^Oxp{UU9}R{G0l zp85LpfBoSfOyBs%Gt;Aw9-A)kAb3AphJEmZADlk<$xj3ATU53$_YdM+Yj~^e-aTiR z|J_qp$0}DXRMHsTb9)=kHjT&ef*%<E#b5lz%pX7d+0XKEwfD1NkVPpxFh6|s$n^gA z{}2vnwoAc2d>cyNgMN~>pVib>-dnyaW8VJmfq>s0)krO!-XHJXbeddu5g@JN{ZWR4 zwU+6cgb^ra-gf);xgLbix5u<heNdct)9VsjU5QgQJHE)cn&|R7+NRaqG4=+GaN44a z<_!8MwCU%bdyX;hrs>$RN8?ET-uJ%GoM!uU1gEp(U+ZDlMfY*`+IfL(k!@v-Ys4rc z9Cr=I+d{+Wy+H1oZw-;u$F-HJI$A5_8t6VK$jts0E1Z3b*bZk4M}^9yO11*bkI);+ za{y%lXOf5buGY2S&6|OiN*TiHq*Cc|<kI=*40B>6Ehkf6x5F9Az(O0CtR#bm4re<o zt*oXDV<5`C0gltrNv?P(zBHaLc3;ndq0nr{p%W;16vnv4(tBkiZ{0hQwIk);4gsBb z-wtOdnC+PKwOEZzT`03UyvAfXjzH+Rnp0V0yiN?EQ?k>@gXcOOvN+U>!TfgIuC{b? zs{UH10pLeIrK#+mS2tSSff!$9gU-PtUPC`Eu7S09kcSUe>0A`vN*bI+AaSc{XhU(} zs3(r-6nd$smNg2N&xR?wZ{NAz9D}eSR&Z8fT87G8HX|){ZMiF#uWcE;Z+rA!xaQ4k z`Psrm+5tre<2{s5-aR@_D9h+>LHIs8eV)&_ZYYH_O<op*KGO$HmF47H+U;=W(}#ie z$(u5n*Rwb?@Ka_wer0MrpvisY0d8~ZQ|oOVABS)cwQ@En+f5v%IyZ#Zfg<k6uT7Ee z>gEmDVOIPBW4(`Uz^AXJl;eB3l3pj#qU^jP&t~6Z5EprLK6ow6d_ZD7TM@{&l*t?` zL(42oA6?E}eyOYQ>%ESsTcA<SZo7on>7q^(a0F^&;ubFaj`ESl!$0wp(~kE)jl-F; z#7=MHh;^?v2e})_bMx9|o`hbUUOkC(>-I*rGdMWy-o2TD8Ti4+f8=h5bJ_vmTsh^( z2QRT|;51H{n>ShMv3cio@W@`AK~<0B#SpnUYrj5(^K6-4$Jzbnxl7YaFP+I=YX=WK z%sy1E79l@b^Y9E6r`}rvQK_Y1n|f=ya*-`L-aN;LUC!WSzA^3Hx^CKr!+G2K-dclp zP@3pWnj2Z+T8=~O2Rv|Jyrg8otFX(-NgQ9sRZ7m$330YTI&HNFev_uYOG@em@#%9$ zxv0ko9U-8~eXPgxz!N91@Z9$`m#I&6PLYszlnZI)ES7vEffMQ(h_g_QSnI7YfRbW) z*e6)0NfXFk%7F-Wv{)rQ<Pa8xB~65RP=QU}v~0|hJ`Ou|^)nN&^_!V^@d2IPM<1W| z96HQLb@or|=nL{u9tu>rv~#wJ@MT#bY3k-1ufEKldwi^q{lp)A;skpXKE^~qm`DV? z_E^qA_is*5ic-QV4pdh-Up#wm`sTCWWPinN)4^j$vwee;kUYSmU7}?o8wV?1{YY3G zXCSaoc6IYD+JRTTUmq{L%)^jJpL&w57mh$f9;(g)mT{XUZ6GPK<c1#yiRW<izVMB2 z<wKZ9A3GMuyM3aTqK()#i^oDy_4eoL;U*u#^a07uYd5Cvve&Q^LT&5G_q+#Z?}3!1 z&Q#lgJW!*ZM60xq?Dfnm!P}VliqkEpuKSTZ^!dW`FHDadKFo)59%FltZFDx^Cx0IF zIbnmIL3aGLkGJo)&bZ~x3*UM^tG|4Jc$h)%o`?2k3{h<o8bzP##yZ*$M>0-AKpoEK z&YoeFH6J~B?If=OADJFGa+tQ6`b~dEHuNB6S4pA+?>Wk5l^h2)vbaL}<riNv0U5UA zKtI5i8arzoM0U5kus;p|*qInpVq@ImL$1qi{e#o`)t6qL9$`z31CQV=pdGbsmj&yF z=d`1tTsRkw3(_yMrN-;0Ud>*So6yl;{IegKe*6PJh{GAX(<;=JJg;!lS~se`RtW)c zw=l|YWs*5Oz$)T-z+kPny$wph__1$DS)@G3Fo>p~0*QHS8!c-cmsY%>7C!O7U;}0} zPqs!1g!jf92GY98Z_y-0WF{-mTfqXG_BFVnWlS8-%3{58k`)BxFB=H&!Y>deml=bP z3Ll$_$mFTXne^31F|l+wR~{dT1fE-MwNOh#KB`@#GIT=Z@`I%2j$<)s%$OL?h6SR5 z&$s}3u?!Nl-T+@tf0NWT(EM0NcXc=;n-2wjAfPVnOUecY59I4QXXj!6QvuwPTZEK; zxXsVdcj+BYxbMR(9bZ%`tx?S+Msq8}JT06ULCE!BE%s8;owB&Ai^`O;N(A~L%Ir!} zGzQ{@uGL{d1WG#qer`XCtW8)G-V#h(;8Mpz*s^#HZqG)o4hvyO9RO9HOTbWzzB_Iu zrlMt9#phw5w`44tym@P|j27vm+{^Zt_?5TucRR5#kp)WOTYs1ux51DfwZcUS5jeAz z*fZRNNa?EK2mhp*-M%m5Lhf%n$Fy!~znrz<41R#icscc<?AaC1!At&(*@VZ|7Y=9I zg0%I-xpiS2)8M<wLn$y+UeGI-qHN&JW*yF(aA0m?OO0|k4;zQkZc8#A#{zP%%$A1; z#1nmhllp0pKgW!VkaPhBHDg)VCf@Ko`uNiWtkXTWrB+-KAr7KjnD?GM`Rer5um0Zj z&;R-V&Hk^CWd)=T*!M8L_^F@%8RT~kUv1|=e%I5yj^7nv7TImUEb4797q<8|Pz(Bq znK2}K^CA5XR)ku%+KA(tFMa7tdEovSvVQtgpUy*S=iiPWKJ>#Mp017sM;40nSjRq= z&ssvyZPo(&PQzrp{thFJeXUXU2QAYzvr2iUZrmrsqWtdz_aMm+BENXoWT&a%)?4Z| zb}8SBZSS~up^frlcCkI%AN?o>S0}&x^2?bU?PB{lKMuHq{o+sa-6PwQoov;&Xh4!< z`O~eyGR7<Uc)J3Yllohk?@#V-Ejn#(9t5`Yto6L^cfb7QJHP(R|7BJ<>k#db#u+1x zV~fJFKyAF+Alvz3o_3_#py(8};nDGw&I*HwBZWktCRjK+s1(XciFmx%0pUcc9nKke zJ87fyfoKd%hqJ3b?HV>}Nlqf*EvwzgpA|rMdi=?^4s9Dd8%Y~H9S!oPk*47U#!#K3 zoh=SNWOUMIV_S|18d&IRPC7a?Wbw}N_@q`DvpNZ0t8?WZ+2Xt+v)frX(KIA4aa|Fm zUv$ekdL1}*(t0(IIGqT)53;<g+Z6%2b_n89x7`WPVWgYa3I>ew8RSu3%~t~q<JE6X zeux}69Z*}IMZ-MvkjX9)Ww7uAkAMf2`ZK;82kppmHGUpUpNCtJ=mC4nR%OcoAO5R@ zkXGqip45-J^V&wnd>v<e+i;&(Z>drI+u@eI4-t}2-kR15KB1v3oyWAuIL^v2Pd80o z>d9{nT$-Og%XiBl|JTul4h`##p$7z(qi`E|4HknhTjbt2ZBxgBLA^Pti&KXCE)UOJ zZH!^?(hbTC-gJ!kdYQp3WO}uK95}#fUzTq<WUGA;zfZv3>PFhG6!amMwro&-W!r)S zjY0{1<Fy-kNZD|2Uhn6joEK$>B)%nGU5VSgo(;ye4$W`dAwPL2#vt+9STSCXA#EGm zgRCq0gmI$nlg;KU&T(*e`5gNE7p7fL|1geM?2pm%Ek3GuM+YH)ya|q3U14w13pkw5 z^AKqR`zY^YweeO~s8<_Q62dc%Y6;t%t-Hf&4xG++ZeL+bj5k@)d77<UTs^scI&^F= zD+g^em9yI}9lq*S6t*MUQaR_!;e2-5#U9T4AKr_jn^%O$ze#61jwE$l?L^g|a{h^f z)sudK8i(^mJ~+3P)yw;KY@D{-xy)+kt6A~98F@E3s{x0tfZHZW*JfEqCfX;$I-%W{ zeDWvF*iAv?o=c_oC-;_F+Okm|3TXQ%jF{qZwrm&ph>QXNlp=U++UiWMVF%S-c+b(a z2CVfn?TozOG|fR=;D{@{N}`<<{*p=wO+^6=I#M6dEhM?OjI?F)a380$!f?b!DZ}8W z&gtZ^Zr!xs0hRqBG05!$0=B$xTMZ^(yN*0I?Rn(rw2!@ZH@J$_x)V714)M`Gh%_sY zNpb6`*L66v-N74YE=-S~c+Yf<Ny2)T<=4j@<-T~A7ah*Vua^lzZK=Wj&8%>K?wM~) zTNsQz!iVMDFF0)m^loeWY5^h3**4@RzxyatBiZif1`g*J>tmLz?mhbC2_B%}AWhjy zsq~mD%DQ4K3z_18IUUaKH~c(~@4f6rtsH)6&k3pRoOL4gUtF?7zG@3lzHKA?**<;$ zyWh)41Fg@GvC?`UuYx*W3?<I$PCV9Y`}<quT|9)w(R=0MRh*-5Oy7R~+pLD-10yGn zXTs$eLmXnVXR|!4tMZVxMOndX8C~Kdjyjxm*zUr?d&rL$vL%LXZTN`61R42l$I&rD znFbng+(wtD;o}sJ-j}Awk>eN+_>4i~a26_-mi+wWUZ=XssrHcVR@mZ1eHgdX!FTp> zE{C(_W-i-)ujIY!i21Eowv89gy&0$XOO)^N_dLM^jU$XFaX6bBhP#ciUdxAVKsh5U zp{gr>@&1*UU!u)q`zG@K%x8aO`q2}Qb8VKAU8|6vhysoTNpP*kO|9~-Bp57NP0=Y* z>=c67HxXu&Nkgvd(x}2!X$vQ*#AA~KZgxs`WK51QS#~_IFPuPLEaJ#i&Qy3!s61ZA ziCU5TR(oH!HIB^na5$%Y5J1ez8DXL$?u#Mh0k>&MPwwc>y#D#GE)#le&3*D=%Up0& zDX5!LMImd;?{ggd;^J6QHiAbtoI`5RGa9`%c@zDUr+WtNsWaFY5h4fYvI$Ae5fn^Q z6xQrQ#Q7^MhabzXkQ5t|!bjcFZf%op@^F{EjyP;9T!C5TBkt%heC4k4a#`cy(ndrJ zYqSk;U|mbdNv7(4&VSV-lLl<%Sn;c!n%WQx^^81nG*4_eqZ^hhZxa^wz};%Pql9AD zWpnl<GmKo?=Ord68?QPR{SvnMYKRb@@gZ!66_sF-RCe*hc=Ixn$4T2Qj4K?wM2%V+ zI60J)u7NGTeVL(7Ua#aXX<g1F1!7h<MY{4dZj+aK_L}tYA8fg=9Q7NVxlC;kC~O$- zVVIXu#k4GiV*$f$^c0$d-!Mb0JkVaIjUM)`W7&J>o*f@t);rrk^7I(YYx{cp1c1}8 z-SRDDaMlOeE3Mv4HXcVN<L{yiF7S<_q7P%9yZhmMJaCh5c4d)7+l*yeZDjlrwu>m$ z{wRu(L3Qkz3vs6HhMuwE&lC&7!D<618J`4mlOs<oKN<)C5S6#|?X^KZ>=PyCxZ=w6 z`@jFy>7V_x{~ZU`!+~%<boAKK>F54~p9hI=7(0f2`ykHM_3U0b)(Y48?`9{R*5}BC zezTBd@S=YuegnoW>c9n0zxHdtHvQi3{T>hGuTEe5;uo_3z%tmo_o3-WKKfC{OSJ&P z@$mTzZ?Xj&<(LP0P3hie#~FWG;oWgKBaQa9hCu1ZB-a4?U?AB4{cKN!4`P20!oY*r z>YD5{_13zVTAh06ygls@?T-DlD%a+$qmENu5UC&K9B&1_@WKnzlTSX$M*?@HZPVA0 zHqQP;`x|Zl-DSL2S>7w2b~4&uO9|Ya;tv|T7M(VY2Z8N8Ydy2V`M2-<qc8nZ3c^e_ zlB+Acg=JxAG&(IaX~KZr=Al+AqfQ!KCp)#|oIw=unV@ivBX^`}C-sCBhXn?Z*EDg6 zIT5m;bw2rovsP6w<)iTfb&AW0pj&U;b`r;-@h}s^3+Et^iQv^YBe#6$+;(M-M%R@n zP8#@j(qzy)>@aoMspM9)xa40r8`^Yi&`#%K9@5NhTKE%3ch2M~L)VE`cm_H0RM4?5 zt#(w~6zJg6q1=tK+c&s6ROgBV+`?H-bmdW}Hs)TdXV3E0a>S|K1UVPa%LvQVvbGGw zT|6!;gbnYF>$RnXIMs#vdY}-*L&ugCVYO|ozF*B}J0pvS(z80ULsM^UOWsSaoajqA zq-mP^(jK&#*lNmCz4_4xCJq#-<stpnr+F6vls&kTm(_gd<Aw|1x>(vB{KDLPFfJdl z-&vm3IL+VnQNBV$+b2GaBIndW>`b`LHj>CFe@$B&eVtka>^vxwb#@E;cE)+&lWBCL z<HKz`dX;nXfSy`_BCtPnWsv8T4Yt_2t%psOCSRuap&YI#cmFf_it`X2<H%UpZ!pI; z!vi?nqGKLb>wC4`gr|Yex}Y3YN7YZY2|Dks(_P+OCf;`kBpyTKoAaQ<`JoRpxIzvc zb2nKDT(8Yh7UsEijn$Bsrq@or3IE{Swg*QUPQzWMj&i{M%K4`)!;22*tZ=@<mKx`$ zv#esgcpjav+rr9H_jzRt74*^Vgp&dFh!|4L8TQk5oPYB&A4WKbV{jW=5U{W6jxDUz z<ilvL2t_PS0ZU3fierz_xejYT8h3?{Y+k|{^(G%x*oqVKVR+tr>*BQO_9g5Lr!%v^ z&3r^G56YlyZFF)c9}9;wGCG}BR?o44aZW6JlP&RHl#V%DZZMcK1*Gj)Th$S3e6Aye zt$?|!UMP`8W;;;H!Y}PFJPg%`w%n0nd4P+F!EK$+#1~HhiB~D8W5LgzQo&r(l1`qo zF?lx+lOfBJJl@+?Sw+zr*(fCHow#nXg4lBK{x<c(70z&tEl|!nGITmq7uPc=+I|>^ z^Wme@0agdQ0%#p^XgxUTsiHf6s$P<E1Bdfz9L_pOUw`Ax>G3Du!z$;;d7cY1*sP%@ z*2<Balq2ubs2H}L;b9REUCy(W#W%k8jcF?nFOEF%1P@O3@|q<Nq^LtWYi{drK^En3 zixBmxgVg$M{m{w!>i1vb0Sfla{^Cb)(jIu^5w>R0hKjcKs6MqR)e(d#Tz*KjU2#S4 zx1M{BEhP3&j~;)V4{GjaLP}pxJy2KWbgr^1I}s&g4eZrbTbH5z()V#V^YKFamcvX4 z`(t|<ztB#U9F(^5z={{OwFVKCvHM8Be)0`gN`Eh_o1b{{IQm3x>m~W^m(`tZpLNwS zj+5`|o4|)o+(X)}J)F$>!N3E&f#8-J@}v$8IV<|mqxP(gm})-vUOvTs)GxjGz3KSz z<KZQHNLM9Pl_^{C)F17FV<qy-n-Al4ILn81Z1?UxaX4>h#kF=yLy*3}x@fzfJkYgl zg;&4gJJ0HO`FI(J^LyX-p6RjUj{&RG4kW;)Jhe^kE$hlF9&HeH++<Sv=K1M+-~Dd3 zgxbz(@}K$4N2U)QKD5|ULz-GS2szAF=l<<j<&5A0iJt^>>C~m@j4THPH@VG^@dU0R z)0f<uI4Fc~lV(7HT>fY;(oBxvjqwZ&rl|qx&+>!>ElCKQb0k6!$O25X6|BSE9nL`| z$UxyZNB(Vps?8xGcpHyrc{0mLYX!vNT=`Q8QYVE`Cee_CW8qK?uZ7F>l&$h|h$R$~ z$4e;^BA!1br_E9Bng{O&=<-5&21ei-G>*kW6V#2qNp)o48|NqpZ{u*b-l&N<j~75? zMrOp`9Y?0`vE6e^4fL_jx0<Mz9lGD}K4m!gl5dZqVq{(A+>GX286?@!bs=w+t7$FI zgWr*1+(kbN9O36JITjJE%PtQSl%<2^Jr9wSh<WT1rt&TAL#W18a?Ep@lHzEP5SrhR zCvo-DDT(98`{;TG)3HW{ddo848?^C`n%mKpy))0LgQxQ>X%3`ANAgoEp$nqnlp?$g zUCeF8DB+f{#mbWHq7mG|?^T6)IT=$m#H)f?;K)VcNh<fDr)^^2;m3a8)yKKl=84bX zr7CD>nU8ea<ro>~n>w7mHy{0keSXFP!Q~vCd+JZpfXN&pGzwSqx{fz%x9r+qtDAX? z%KqK?zQKB4Hl`k_dl?_qn4w#mW&2vX4!r!5U!DsO_^7+anVxuVT&;ZM@ec)N!B6EJ zWo{0G{X4xPd9U$dWZ!`Lga7mYn7;CrFXz?$?Yu4ILZ63tF#lKo>VJX^z9GeUuQK2B zS6)iKdx9(y)(Y1dR@+F&&(9gpqnBPJWS_r*v5gLB+rAB~EO7zL*T4St>A(3qe`ora z|MFi<fBEPCO12NNtaUhl`qQ652kw8nH8ymPg)3W`cf=t$Cw7nP)$`zcfW0fx?}o$q zK^T3|GJO!-Yk_??=!^3~@UF#9t=Tp;)do}@cHV2=^wEsBwYN>1oD;Ca0Cm)}-;i-X z=1a^2eEVS6&fVF4;1c6;$G`UD*Il6ZwiUHo|Fvio7}_lPsupOCdEQ~LwdnL6CV5wM z*~9rCvclQMUo~dJMnTO(Z{eWAbWYg_DS#c4P8tVbPP8ph(>%wKNhc8)CVB=9Ktqw1 zIOh&$9SK+^FgmoskwKsEH0s`SkUZTWuTv%`RyxQaP9*r@<@(JFp{FG}d6bV*bXkv$ zX?0w4gHeuQ5HZ&3G}HOYGdP4cpOwaY;pIgqu@^Ov6o&@SfHH9CNd1fsPWe0J!zlp! zXD0E9w^ty0?TTm{{nm5m?TXt5q`q~0J1D3DLdmighjY^uxA+=o-TV4*twQhewyfVS zNPiy0Z<yomxH;VXdd`FK!gv0*w>+2_@y4kWc{H>Rax;Eb(^L-gEDy^HKK(-vPL_SR z(ZP<?4p%#GURLA0E`n8|@e8Y)V8sdz;8*KQ_<3+LllnxwJUF0(=^S}zA+Q6nk-q*q z>2Wx#lNt=gc!jeH09wvKBP!^0RW?_GtJkZcQF@nekKoERI@6higFxGC{<XDs)~5WR zWgYk0I%mCay_v^7v*!-yu4_4yhky7*cJON3wmGf@p9f!<nTOT7o7;i;<-xc)-(5a^ z?mXU`M`!*#tS<9|Klz1e?}tBDyAZgK?RsAkq)lL8sr9U9Ta4Q`FVVrBXL}6ZTDY}k z+INsu&ii)a9P<gRvI03PcAXYZ(&09%F)y8G4`>|LHgN|ZJA%`A8!N}rO_!xOpyjVR z)=l9sI;$x8INNI{&ycvC^4&Y_Kd_yZ20r8?GdxOoefE!bz%3KB;qJvu3+t9Nm)Tb1 z<V$=gj?R1k&aKnV^=zrJj*lhWzQF2c+HY9jz$!1%ZJgY4N4psZd}VUr)F<`Ex>JX? zTs+HyycF;9-({eai`#{BCTXcN*em7eVV@xkP@n;i?K|i6N8~SDrdJ3)W+NmOZqDI_ zgxDuw!Z^3e{K|Cn0-55Myukrn$)L8On|vcp*nwZ>QzD_+d5tT4OmBd#ej-SWM+Va? zC=V@%eV;ar(|Pm$L(@(^baw!!@#Z}bvC5f`vw<TYZ&NVY(Iz}#M5p38wp=)^!<l`Y zA3e^N8mv&>z{3JnW|_xn;uShIf9eDGXb?GRD``_Mo_%wA?i=iR=9U^qk7Z)9os}-S zM|t#_varupxlT^`g$Iyn5b)tv7O%bda`uwG$SZA+o^XXTTWXAc6?UU%8HfX#tjZvZ z(HMBIvWn=;>#wty^mEfbRuMgZ{E2BBtAn%cQ(%RbTxl@pL|G@2K%KhE%H-$sTAkk~ za35$tUZ^svowL0eeZKY<Ifh>0!M5@u4rlfG(u*&#ANG-~wBEpn3vH9dV{T>0<PDwJ zuG*HAvq{13#Nn*tT)Fq*JbxH@b|Q;!ctvQ~l^?@=458h@QgnRw?Ahs!ldN!l<)z7$ z+Q(RJ?N&h$79{kMDt~YhTKUdJ<U%sa=_0F>zx~Z`WuL`|`KalB_LAPZb6dt(2n3cI zM-`T(ZbQRzWt`$3(x<SolYGJcz3+dD2O3A=z1kP~P$wl6SfXd^f+<=FI;NR@^X&QQ z`R8BYO^I9B*0$*jAN`T(Lx=b%<XGV>eDfg6D4{NbBXk-f^aLT6|6vuOmYhbEsTXSl zkAPuo+*^_hI)x<sH~0!*B4fk0NeiMg9VAm)15-y(AM!{Y9E52qDny3CzbESdBG^Y8 z0$cHE|0;Iz+uMlrw+PCfnm~cctEAMezg>5#(L+g*rR+KchfOZZv6v{hl#zI8V`&pg z|4@j)UG}7o@~L<etDajXb(ahxx=RpW@uljPftwZgb=#&;aL6dpR>4BqL@T0g6`^c5 zSNzzINV5(nvl-XZ4z$BL+h~pPr|2723?U)AUZ<P~@8O{s(avrUMq4)pKNBd0RQ8fw zv!oy&Le2A6{Dc24Y=Eru>(#jDX-#DbQw%O0IIZ-86t2rAI+K<lZ;`7pbDpCZaH*kO zds|T>p_Mdl#nSw)w40>(gZa&X6LYs8_?F>C=<7ZglU3x)`h@i)2f0V9QZe#0=gZjU zLs&zRTf&LSlsO-bLwG~cZ=M=Q>wx%?l>UU9)G7M^=EpaCYW!4l{5!n0MMQ8njCn$r z`XQ6;aJGH~cHoQiI;)v=TIz__p<})B+P2K=CC9FC-nw)Dw9)Yehg<lKMygJ2IQF!T zkGQw5t#$#@rMB?u^vJ$g9V&7bR&Xx+BVH)drSF|@U#`{R>|zy3`R0{xDgBH8_y3uG z=XZWP<CMKTkav-c+iLv$&;N%!ROSQ8IMPE;n)e9J*FBQo5-t3i0t&bvZSkl_-z2}z zcukEt|JuaZ#`%D&)18lQ<4wtnY{m6o|LwnxgZ(Sh7r*eu=@5$toHy@#Xn!2eZc*U4 zOh1kmow@T^;BY^FSI@KV2mel{FWakk66@M=t+_ncj`D#Z-wpcKlHgs7sbZvSu~cz7 z46rrLqOmbNvL0)v+FL&A8HY35)UtT<GT&1=$Kr@9%mEG^JOod^0bd^_y}%oX+t|O^ zISkFxI~<g#{@!84Yeu)ae^_(IcNj2xIRAsc@z>K4h}#CGSI;#q8*4j?G|Dux!lb}$ z#7rc_ImLvl9AsnQ=ER52NXM{wO*4qgxVt%=HG&!#i$kXws|7KN%{+OO(lr`B-8yy> z;&Fo84(H8Vq{S<+v6$*aq}$tS$fK{{y6VUv?@o9<_n=b4G<3yl`K$*1XQd=GO}8-~ z(F=I%R9CL(j7eP&WP_NW`l9x-_SGv(Op4)8ov42u$Z@CxFAq7I80Vq(z{`iLca^na z@8@uqrcQimDSPK_9>wpt!0j8vrA+<Qvtd@Bm%6Hy)}eQ$69)!Mxs6X5dhs?vyv?8I z#+A5XS8ZFydCY_GWuHu*xt`N3+{M$J-xc{sgZTqFoYCi8@-C-2oz>UYgQ`zD$!b7{ z@G3LT4db#Rjxvnn_$s!G13>we*SsFl6R^_s8Oc0oV>%7GobS*;JMdQ*bA8B523U;d zZsPs4p0pm#8(SZ`_d$$XS2Q2mbjxepCh%`?um%n9qZ#4?6C83lIuhhimZsIb-voXh zgqa8B68}72TE=@`on~I?YwMmH&ioF-EW9}`;SaFFdC!l0d|K~d90%;}^>%cw^`#A? zPOax-d($mGro~nU=g;#Iz{~5VeUBVubtZc;Z}6+nlnGGE3I^`gg#%wYOL)J@1B5FV zuT8JL^7?dzRi^t{jk%N6hg-K$uFRTTjjWd=&P8&{w`z$dXd5qIzQn3l_JF>=9Xr@N z9eiX5`?TuNvi-#IOxwENZ9qVy!&&FYdgNG-L*ove_7(EK_`UB<8_?N4=<eFc0D9dO zRydz$%aH3h8!5{TObX0*=Nh=69i4j~{6#X_B_|jDjY&$%y2}vy+OiXsKC2J;QY)2@ zHUPddNwK{GkB+$D5em8<Dxh%KW=PX0aoEm-lQY>#EBt|#c4*~?)v}a7M?U(8UJ4e( zRE(krZtyxdT^w?0_8fy&X3$&{ot4qyq3%m29nRVd*ksCo$&7q-95Ao_>$Ie-tj}!A zvg6?4>ERQ{r>*;V?R4iJw$gD`JW|qUp!gU7ngkEO)YY>%CEqyp`gH2`({c13<HLb@ zO_ef&aOn-^)v1|FmvX3%sYmoJ7Z|90i>)lSFeuaEyoc2Q+u7n{6Z|oa<PTi5Ls0^J zq^(pP#v$7cCNQU7_Tz=;SY2=lK8|Ng4Oa$3P%{R&jw(lPDk(UfTwldeeVV<3U*MyG z`*k>jV~hJd;+5=v91JUi`V=vRC|*C-_bnXOSFc=Q;<SA_`q-n{o<qrN@M_(%&KrTl ze%Naw;Ncc+<prGYr*VA0`tmE&Bh*P(jBjweFl5m_DnEJzMcT~Kekor1KQ7!m*)2+J zQx5Ra!u=2LXODFq&Q8#Tggj~Dv+eU*{?lHPth4wu+l#ybAFrQ$EvuW4K6<nq&cKNy z^*dZZSNi~`A4;{fQa<2tJB$~;@oZMBKf=c-_wsSk%{<g{#|a;XFxm^x=9R6kZ|WoX zXdB!^TKlqWp87LSqSGTVPpb9{RLnWh<RQ+a3UCQOxB1BAS+;EXCgr-7G2DRzyQa_c zrSK23>U#@&6Ga-}I>bJVjlGJa%GP-CH>kK}T5_$^1rE{@A6-@Kf~^J;B8F*1rAnjl z5(N$=>`AI}m42X`e2z2ao?qJB=6B)HjABgfGyzLzXg#>(+;l2G=L*)#mdEmuhPK<G z(?CF!he6#aPc9SFDZ*5evXR75yjm;FqAk~-d&Ub=x)xbsNj`xkz`yN1KO$NIFBU_Q zscY}Nst*7rIX_FBK#X$mH0Q0MyG$aZk-~+F><l`V9e+*L6lr+B(&4<6v9?ySe8|aR zUCe`V+c<SkdF7*lv+`N(2y_k<8sskyl%A|AozUC0<Yx90-WJRvMe1DTHEm@mz{a^U zZEbh0!#=OhwHmj&l#N9d@!E!S!Q8N?AX*4gcgQ}(54d=`ItaNEI$2gY5<{41ODcVE zGz*R-1Y2e5-{>np9V74xI?^xMSHUfFa0TBpT-L-2eO}4=LKTg}<XPlg*JazvgPm{_ zeg=55jC^fh^Sq%R{+kdn!Z%wZ+B_XqtavBQ;aE1EV>zF!_;_I!<E_q9u(deAYwCvi z9Xn;=3vm29|ISzp8n^ifuSa+vbxGEwPuB3}1Dq{8`JRE!X6F9u9g`2WW_+pb@W(8t z#zx%JEG<HK2r~4DJ=({H9uO`dFlfsjN)kg<HvaSvJo?z$RydPg#v`8#LB9UAe?5Km zt6!a7d+pV%Y<9lv-008$`JbMS@a>Il+jbQ_Y2G8Ou4DHAOZ0=lz8#)<S~;9IGG}l} zkMl*}_T>9sH`pRojib-3>}Fi|>%ac%(?9;re~et)rl&vf!K@H{h^@}v_r4EIk3aTA zd=m=nw;`^P-|_oe!s>a}TJpS8Fx{8GQ~3Tkc;1b2T`M2&25sxA|L<f-{bzXL*u)k1 z)_<#f%@JKFhV5#r+3OLv2>yy}Psx^gzP)^yMLSpcZiw}N6Azh2bHSbC(;9=_onLd@ zFT54T(ZZi*==SeVlLu*Mh4cUTD}RHAxD;Y#Z|B{dIR{#q_|VFlUIPo;>ZK(apH<8h zm<4QF90Q~CNkam7y>^VVg2r8V9bTERl4ikY^oJ=~`Caj|V>?b38a0*XX7tyX1Pd0P zov4o$&Kowl&4isB69MEf-4#iGuup!BbL#;2LAEiqW1O$P6n}k<61vDB{~2HsuN;jx zPjI2H^Er&bx40KhIdvjiI=`V`ua_>h=_;cP9)Yt1wR6`|Zm=>mUHOlGLFZYXq$8hm zIn}#y!h80(pTk)^b<`wQho$;h1axob+|FiGTJ8nRstfVWL&}E;C(FvI43TFBwAzWi z8i$U*mdP^+f=hlJ$Qa}?HcOi2t<L8mI7dF?8(-`rI;*lynLA*%b(B_zkvEg{q2JYf z-fxAo4#*xTiZ;4f)e4J$9<-;_DdmFh-Bvg|OfpySQ4j9S9nM29trPLDUg6wjRIfjw zHyqBEmpaw?p&^%^Jd+MFw?nNJdpb4Xk$RxcQ?H?+e$69K^56E^@w(U+4rgH7HWto5 zbfxW)z2s7U@Xdo;53C5_nFn9>wv3v#`MWOnif7@2SAIDx`7I1`jq}3-(fz<7F59Vj zIPmA#yX+&M$VUU);e5+|+Ne8D9yai3Y`T4wSI#ftaOUgIta9Fmb4iEu#tnS+Hu5=T z8nQ4TLsDd>{zA{K7Oq^nHl4)be2Iq%yU4q1*ACi4w$;dTdD|q)L`8utgK;}q?%fOZ z3Lh*ybLMqcEATqox?R)5hjy|hhl6)NZ03q~ok==zt8GgMEgpDxD1MC(rhV@_-^HPR zYuXRp?dy1Ta6OK?br+`%IMO#TaoD<vz1iS*9ovT}PYw{6UpZ<>4?-s+{-v0PjYOFh z=Y(U$gD<lrT@3zl501#oO|{1(&wvcL3_zr8tuPqx6`Bown>qQgoZ99*kH~U3n}Kw< z*AOm;w(p;y{FM`#vI|_<P-u<3_G3d6oXw*w!gqeRHW5GAwC}_VQ?ygA_Cxf6aXMR< zw(Op^?>jW@KYo1Lap2Ijb<aM^l9eP`<qQQKxFLa#5mY<SA^93k!Pic{&K|q(ot`-H z<Zw(%NxB|NL|zW-tq(lZxBD#KzIHuZYJBS(-<-DZ+RX}}$N8`ZwnSgG5&q)yqN(VI zK)NYyAMz1Cl_eGG&Ks|u;^E7==>o5>9ed)j=>S_M`0+x`SIP<w^>O2^X~w`G`f-4G z=G18%q~F0odmt;EH}fiMoV}F0I4u5of0OnR9$fVx{%bgzzxnKQwJM3NEaGrxg|oI- z^#SgI4_#J)YiG50GMR0c=&SueURD;r`f7MM{vPz{-plZsHWqsb_dJM7KMzx?q1(f( zEaug|XTSbT+Rj7h!Bx)N*&o{poxErhDkk))fA!EoTS@WK2H&1eoy5_L!};v#H`vDF z@$46=0sx8bHnKID?X&HF#nCQU&rF3yW${76^EjM$@F3yXv18NDy}Q__+r7bQ8?Y(8 zJk~keGuxNNLmu_)J-AQ4@+zyGPfzD@ULSwz1YfE@Y$1?dhqRTY?yH=PvV0ZDz4gzq z`u;f{XzbXrVLJTC-sy8sKRrEtU|$^08)#3;$*5jC^!3mc(elIZI0`O$tjnZ$SrFkW zdR8CBAH1nxLj4LnuJlL-&Qz|ndtk#wK)kB4O2K(=|5<XQ$k1A*iCP#kC;vDTRT`>t zvNUtw4o&!}HpAA;zG6wktCZ~wpA;kzr{*gC1T6TulCJ5>?>}}@Iyb(`v4CvTj2rN| z3z69s_t;EyAAO2nJ;;r?LL#KhX{@2zK#5b|6I=B#Y01kKb)(Xay-R3hNs`l|l?xjO z@s2X?qD`9d8B=t56{0-MrR}LU+OcJoakkCz{SI|Q`)k`_NNIuJzYasClsDy-wBo7s z(NObq(VoY6EqtlL_C);ZCn=#D(Yzw5F$i{VI_6a!&FdmpC9FzoJesXEmiZRo*jeEc zlXh!Ks*1TjOhIcizACkKx5QRgO?RLY9l7gBxrG1bebC}ISc{#87DdV+7vo2|{)=l- z|AQ_+K#8RET2z<0t#9*Sjzun#DrZ6DngX*1Ep#_@U-~Q_!UsrNm*!4hVfkNSLnD9E z14Tv|ppZf%c}A+IMW~yu<HB11@^%u}H|Q^GTxgtix%%Kjr_@7+kx#VtRfPxKj%U)3 zIqqIMoEeZT>QK)Y$OJa)MlrXJ70w%XJhWWl%($oQoOI-Bdx#GLVZFDXYsL4NPOSMB z3uEb`krPO&gv_Tr6|_|6&1-i!mws)BorA8QzVn@LXN!qvpZx~T*WGF;+Y<iphd(mC z|NS50%^kiKF{s_^WSwa_?gi8Ft%tsUC(g{&v%<N?42)LM-KNbhXk#vu70UG2l%bCF zKl-CTn!fzyFSE+|x2Mnld!L_<9etDqF}sm--}JdZ`{UW`**Dq!HbflGczM<mR?n^1 zlINX*ah(6I1PWezxL<fT%Jfg$rj+@emP?s3^<|7j^MD_(>UQ>sXWmkc32iowitU(h zN1i=*Hud`<wtaDNhkiHxeKu7)ckBYj@6LhCw+!zY?pKDL-e=2Q-YorP+&$61O9^SK z)`0t+E~nKb*Zpr_`O2Mth{M^5!{#mQEs9Qb0xq0*<cM==OoA*t9mO){bu-x4HWtR2 zM;zi?IC``U>a&fR6R1q4D0K5?N<>;FR<68b-%2|X2h@ImMw;Bj;oN)KMu`qUhr{{S z?aPoWo~qHZGn!&Z%H)$d_k?wSS{ae99cdiN0P1{}S35$DL;5<M=BpiDQ7Zq*3l`7y z)K8~Cb$rV2D(iYmjI0AsWQSj6O}@d8ud4_vugWP+9cI#TK<f%-;dNZA)2!kqExZyh z|2qA$4FpKyNVk&!t3Xu0odxC0UR<2T*&lFh`PHTLt#D<WR%mrnc$LX``S9BK(v>{o z<btofifr1TosM7rtZbZ%M&T(Mj!7Um3vqP9pM0qUE*7cgQ8)77#8<s)VA7ARaaLyr zVGIr5_wptlkLF9zOwK8f=u#UVGKkyI&h6yo-pO|dIdtDuZKiSS)U>=i#ECcPwqxG` zQ~06$tP4$Rkp~>|Z&0pVG@eKsywcpnE8)Jjb)CV0aPE$92c1DC`q+e>TTZU#^Yx~F zEh-KK_*Z}GQTy7;YDLSF(MD`A`h-T?nCD!x8qHaRa&|{1-zgJdJX>GnM_U$8mqFuj z1#R}UR>$P+?Muw-VW*#owEE)D5L&rX&m8dCy7p`^uk@_HZov_qjB=DG>C0=!x4svA z0qfQx;`3t|{Z(7xJcKjNv*mH<3qLjO|HLOzl03n;&fDQ+)amB-6zf>|d-41g_9(qN zojH4TdI(3^-hF#`W5WkgL(bScGT2etesQ$J`P!B1ysplkQ&+A{Tj?lwvuEw@-8*<L zphm0*v=h;Yb^%Q=IH8fh8`t>o;DvM0=AqlQjeMBwA@;mwRq9qBP^mwF8AOUnTToTz zua7s~!fx0D`o)*>!MC00We<L+og1&Sr3M}MEw<KRmGc%S2hj6_m3HpV>8as$9ll~L zLoSh5iDq(QSrcVg)J2#|d5#26$-#v>HlK_OAA1?+#v`uIGsi=&$ZJ|0#la_@rtLNS z*gglp@Mr^vTh5ul4cv>orf~#@yvB3LK<a6nRBFQ#@oa<Obp;<z6fY&S{8m0;4ba#2 z7y!kwL7m#TWzV$rp@Y*NoP)a_IgIo9Amv7XtaFP@^&r!{;Idu8(d#x8Cvi@`g46lQ z_xuq1IG+HuQ+}yn(<uiir#-dL9r@L_e>j}qeB;dYEGu$%u(J8s@e}#jh97scb&69) zRl&cuq_aA83VqtwiO!Y5r(S-ItrO1WVa}sZvcj1U<-uXnLlQXi`(L_HeDX)J3>tAb zpJtWz^UuA&)(;1#Cr+@++mF%E&P3G~=Ac)4K-c6~%))Vp2RN5mN&9Tx&~X3fM~)oL ze$=*u>0f;XB<)XB1pnHcwo!73?lddLUw`dXRx&+y{E6v_C!fq)OKz2whd$ONl_=d* z2sEt>M7jDoj$ZaGe)gGXrj5L=didDk=^>on<#4uMLNBtYQ~Pbk5R`qDkFpTYnCG=u zUSXB<>+C7b-rP8x-5$gmm0AU@Ot!Hh>1j*04!&K5c;MoVCCc?2duo4+a`kK7kFnLt z)}5>v_rs(-cnrhRg1+$LOZyBBqD7LiqHV<4)2Fjd$dgY!g~OSxQj{NAo9EzC0kaUD zAfK|Hg^#bZNBG{|o2N$~JurRpJ@1)5pu?F55`M(ADwdfWhv#rXlC>Mlk!I2x#%u*c z!it=oSG=XK%D-?pnIWO`51ivv4rg(a-XL0gcp+nWp;D;#)GONu0Xa<b6ppws+8@s( z6$$z3x<QQN2?OP~bU0&^!7cBMRY_KsLMOhmS+lKlI7_Oi)D^JO4PWNtA30hUaW@^y zlw|G)d{L9c?24Ne4rj`T4246TR1lA0!3q7g63BOlDpR5)XrP|X(<^fJ+sG1Ccox{K zi&7i-tw+m1ydB_z&q9>8&GwNzuG+qZv&Cyax=Rg<OyzJ^F0BDMg`H_bazekw;Vdsj zX30jb?ivX#bvXDEsnl`{-I2vu$C`$K)a4@IxSgHgbigl}SwuwE0-n)^mb#nQtwz{R zQrRJgrAe66@ZOe4Bn6Z7K$Y%<n1`0xI63nu{9MEQk`H4CHZD^J3sFp~o37&lHg=}d zPAh#DzRHKLlfC0AxAkovmex%!l1!aLNJ}eO@H~LRo$x~*S!!L1KX@8em=U+&H}`{5 zGK<SdeuU2r_ahVrla}=<&gNn3aX8cN+wVP)!<n``w5+GOw*O*`%Gfq-iq{;DIWo_- zorykZ>jwKgL7q0P+2M>WAg^!pXcW;OGS+$KaPGLSDBPQ`)DlHSPY<%f*?E+5Y;w-Q zIQ;e3Pfa?T|L_n00EgC&%tf4!9AII<XFmJm)1gC0Q*NUOe&Ex*Ufd7aT48lKJ4Pu+ z(F;1w9?o&%ITq4M$M<w7tSh`N_WP{p{%e2jznFgJFZ}HE)Kl+eG2hnd!i7uIFZ`$f zS+*^3k&bVmX;1cOYYFW?SPSes4fF51!}*=or}%8~{9j90tDR;n>w=Eqa29{s7i_G0 zothil_UI!yfBsG4*G)Uve|#4o3e*?2b?bJ<ucWh>OaF&$L6!f!6<^JDH&T7ROL}Bo zncnTvYUn?y`?SexAhuThuL0FvL9)X6*MIr1({R>D{AA1tP8>xzqPm65<etXWG#xe# z*I0G18t--$4lL7XXawMGhpp)z;_9>byzf1nb@XXOI-FvtG=M&JlpiNu*Kn@6LfC%8 zI6FyS`Sr{isPI)C0s9Z*Br#mU;ifSP-@L_v2W=hWhB%^0m!I&29@>#Ce+C`a@)Q{2 zvKk4xnwAqx3rnZ9wM!n#!MnsmGVwk=w)0)a*Armm0KiGF=jNm0&;^6#7!AaXE1qb= z!DmoDb*g-(t!}it3|b~-sS4%*LE26#mUM~YUMG4v-94wwTNg}#ypOIUi?nepjC4C; z%PTPIlz4US{fZT613p6VQ!<pS>R@$f*~KGIaSU^<79gL{a(EV>u#Kzj&VdvO(bYx< zINlZl$}l##Ko%K&V4+j492re%z;JTKt#ta3_B_OzO{cs<8;;A#M|p*hn$)kzgO1gq zLH@If&Kpq6u64kb>5IAp?rg<CeF(qEVbIa+*I4^0we}%*%4wm=^EOuYMwi^T4Yyqi z?;#KF<rcqaFpnSdr|@TS;+`L!-!m-$wc0GB&Hx*ENGtsrU%Uq;iRws|)&r?pP1(8@ zr?@=p<d#qOYE^et=a+V!vX!p%q1*X<pdfs7LYlbDI}ec`KAP@<pZwyq?_-~!a7G-C zks(<*)Nw$s!zt@3<#XpQvzPP5X*YYE?R{tu`o@8i{iUjW3#XoIWr4Q!m~y;MXZQwA zwo8}!m?N*`?cVDOf?a$}%ld|0`+6cwdi0Nz5RY4w`!!ZMzkZ4p))#K@THnEG@BZD> zww-(+l6FgZ%%mg9Hr9?hlVa>hygsNng=6goy3~FT;Bnry1wCDVecGIl2jXysPq#>6 z$c;Ta06?$e0dF}AZ99z*hlz92RqdlTUu>hnW!+H6<Vt9Lb5jF~N>g8!kw;db+F*@L zp6U`<F3jOMoa9~(#aFme|Li{&IIW`sV1scw$6AB4@C{rbaV5U6;u5K+3f3#NVP4uG zHG{C!dVoqBw>ZQ8;G=m3Jo$v-&{i{<s<uvt^OoIgzrdb(yN}>>K5&>-&8)Datyc5u z(<8xh#IDb=BKH(q9=yUHyC>fJUbdn*A!rUYVY>{`)GZ?wLA^SuaK-d3KGt^*hx0RE z`+6MC?!UZ~mCjo?u}a=D(C&fd2T73@o3N~CEx;bh^NQxlmtKj(*^mD{#!A=&IGnTn z6<Lu^76$L(Dtd`LQF=R^-<Y2N)(foG$Km|siG{;iwe|#7R?<$#!K9q<C3}?dWw!Hh zOAWUK^5M-v^tfx!9%$M3)Q3{T2ia&IC|hJx4gk_#6R)%RbsYHaTm0DZC$hE24I4%1 zi6al5EerqT0s3WY;y|C*`OqFtVz<=TjC1$MW99VL;p~G-SP5M(LLVL5R!Kj>as|gL zFPEd&t#2M<)wzyd9pvWMgsj)<^%kq4-Fx3bdK3&#@}&dc{g<DA_StNa^2G7u(<VOd zvyoS5*YQA4-HS^b@}Zz@t9nS?BTc2*&%F4(?@#AWpP{X~Hl29t$*gehz9clEY*5F^ zR(HVz!kk^<{8p2Yx&Qz`07*naRP}%J40}LspPqQ)(DX5Qc|Y5GY}u^NC<E=0P~#MM zlaG>={z&@;Gy181qv+X|CPe>rS@-;oG|Q-@<P?FGxMF6vB#BG?0}qH>OL!4V3g#V? zYI`#8s@@j7+nG=`h@9c()>N@BW4RfD)<5u#D-M-VgJUA|a7_B)gE*L#Uqjj=FBoS^ zGY?~+wkZDrmo&hVFLC@7Gvtlci-k~nl?J5|71*{L#wph&xse<x*OGyo5UH|J>Q!OT z%s5^K(DhJN;c92Q*_3GnZM;^Ai@w^NWR!kz7UDFgL{(XnWV#`O58{%woi%zvZ?uKj zitU-SZ!`ah{m0?VgD!2(kDR9*22ORpKnpQ$!crnlt3*r0psfss;lZ{d(fLuoxh39q z#UOa$FvWw2;P5ukeOkmTyK<YXRKb)Vi)thgU%7)3m;z{is{EiaLd((jbrwTm$=Ir| zi4uEJ)>aGqpfLFL&b%WQ;pg_%@kOV8TNlk^s1*4*81=7lW6kn1V3NPcLCeU}fqXWa z^$onhIMR}@pjsDg-B?S)Jgea0f-KR+;wBM+Px~qyX~l`r0?KpI>aAz0*eWgnGnnKR z-sBlbZi$ypC{%>VF@&;n={WY!oQ>;tIHwKvK5eJxaZuMoBl#=6Va4m4Qugy16M$ET zbK;%1r#@Hv4rm1y$86fkp2s*Zb1*KCy_6ajwxg25KIe_p-Qp`!l>&*k-*QY}sDU3e zoHsA@37q3zVi*VWz;lfs4J;WMt7neJ_YnBz$+y4#!t`6e^-r>QvkO*g4zy|d>A&z7 zd60U1@G<240Z-~=tzoUO*_sU<)yJyEZrklRPCtz!Iv;-fpt%<GeC=!hX8NUH`ju(> zwjI;{eFs=bvxSG?XQp5Hh5vl|_{Tmz?c2A%-t@)>?xYXBKgT@>yFcVR5Akj}oZHsc z!tq+mYAv{gNlUwSQ&}t8HN!m!{k6*OSjMKq^B4kApN*j9PN%`5v+Gx<t1P<G7vM(& zU1{%|+^LhymmI4*wy6bbJQ$(w>tCpm*<4|x(TK$Nx^8ulo~&~?n>$;VKfSP4`+JbG z`r}BG70$o$t6y3=<|sv-lUW_Z07nOzju#tO9TerHuy3N1pplNF)kd9xm(IL)7|M*! z+&Fg4OXnh<H2x@m0Y~AO7AJB`zzErnA^jQ#(GF+x+vMqDsm=j|v9oh40cfmS=RQN_ z;J(hJHY=G)zKXG_$aDa94j@+!CripIPp$xU)o-@<AT1M2<c|YbzU-7Z>5LOb`SY=& z;G%Oz1_9b3ws0(x?&MB=nr=szEj7T`Mj)<CkO7DjTbYn!-YGiSlh>3DD_7;FE2rn~ z02~yGZ*`-svr&5LU47a)bGrz_7an!uYfn0&s>3u-r`OgS>Kgbl02Yy`ENgWteVzU8 zyDiSP8{<91m-2^ZIXf0?Jn)5hluNzHL$9)yrnEb~9pR=6?~y?l=Pg_6i^2|ywBwWo zXG3HHcRM6q4J=Ga9FY2<Oo9{nJg*Kq5Hm@ZHsvdXWnB{`%i1C8%6zr;LrsE|Cm)*> zF?J+mK2ik^uOlBgTuG=dGSEUdH+*G;vex$flCq7k0|$}#(4lPVR$hO~ie%*QL5cCg z$ye(u@{JYFAV^3WFj?U~?8JK7I`C{c7#f!=oNI8O=(qgX>3fuZV(H;0PM4vxn{+Cn z4gS~^9fjvj)?s+}A(LgVOwu>avv%zDYWoNd;LU3=U(3)8c3R7`|HprlEj2zu3uPJU zB-5s<Y_uNU^I-0LgAVTo4(Cfa{m#+pu}b-&y*POISOKr9wJlXCVgu?6Ot8s7pH=>@ zE@jWy3zx34BlPBJ`_3KHo;^FMTjWhsX4}DlJQ*ZjhgH*k^scj_^VG>Vr*o{Ze&om_ ze6Wx$8TbHTZ}(%qe%N-$Rmzl&(zs&dI_>5eRvuoycm=2P_34p^ad>Y-%B!cQEw}l| z!kw!Vesdhov=z$Bx#U*YC5Po)vcVUyWeS!DcFJn8(xvuMbs}XNizbSYHjwhlL`>NN zS7mRU<(7kMQ<p)Q0nOQR34HPoj?__bh-cs$_j$0QG?~>^`6@v1H}FwhwL+Qr6kQ00 zZiF>&Gy<NqC$t+VAofj)4rhv(P`oCON=i(_ac^D~$9eq*R-kU@fdwn&A3FB<wCC`n zY_q|~E*LDu4$L0G!HI6{tKMKs4IR#>*!JKFR-ium#1p_eP#gUX{j~joamiZB3Q6BC zyTR&u9nQ~w{Tr-+-8mh`xw&W0UiRD7;S3#Ktx!~*nvMt57Mh5rv!WJ0v|~RSc!8C@ z_7O)}k^3<FnWJ?etB%Whhm;Fx+DF<7_`BvF&hYWVbKhnU=Yu$UpI{GXzhX~+7=u^; zQU;^#t#Rs&ARV`ExOCy-^uqJc=Xy6E_Brs#As*uFrLAxPD*tc~znCxAA|fw1kTQ6b z_w`p#;&46%FK_S>#>eAuPEnIT{SEok|BFZd8&RQ)F3z*k`<pm=H?zgpk;fm!`OTi# z>?v*jCC}Q0<!BpPH7i=hXl~K2zsd^dH+fCadU})(2KwP1$44<CXl~5Pc<LGsXA%@7 zWgPs-b@?J&?(i_;J1@MzL#(~i@e?QbD5P7IQ0U~3_|Uc=u-)8*j>KPOQ~J<x|MK@= z%yt^~J;zQQ<3YlK%5NEXL^)u~zgRmIu4`9rq+GxC?DKr>e#i7U4(Ct6%lr0WV|lU7 z`cI!x9Dx%YMZQj{eBcafX$~6153nYfbJ!VbGQ!eb9gJx*npDAv*TV?QqeAD`;k>jI zL8{EG7fn<9^m>LV`o!pnTwqG8A#6c{XJ$j?FheJ4V@dn}*n86_&#v>n?@mv5&-Cp3 zhMB=E00tlcilj)8mMF=RWinD!R#LGNzf4J~iv9&jNgO#&Syjo4yh!po7FBi@St?VM zRAekAvMEK8wZsHBtg~T&8O*-+?48f&`<(Op{kms>>0t<hDeH9K-@W&o=RDha&i34M z&m~`EZmbno+D#glLLtVcm#!bnF^nKjC4oSa{!s292r66k*kAbbnrMD9u?u{_+D}CU zxA-FiXYv%?WS+<%47Y-$F)aNQZ$ysdHlJ|9cfQ~|iY4A;@k|6T)m_Uv32RD=9_1)U zvvN7U6QIh&{zaNjXz$a8SRbq1c1({xbU0J@M;PHT`T3co6PX%MUdNu7GBM(&U5w<b zwmJ=yNl}5=r6rP%D3pbWs(M*_9;XOBz7v)0oiQDo`4dK9rI#M<x#X#HY+?du;9#j2 zf8dj@)Z*&=R!ZRIO1+GdI`PhJC5)0QQ+V#AJ5McXbjkytc31sLzftB2q0(=ND!qDP zWKU?+IaN%H4@}|dkagFxw;Rp5oLXpFROT~7%P;@A72ZN=r%@c~ee5h`%QoVra)_?M zwTMZ*bQ)%^{GRQzumo(|Yv)4caIW!H(lGkuP5l$D4#!RrBIzBb(f|rR>rn9C^W$@F zHCO$L6={SAH1e|or{yf)rkL@AUToXtLXg-?^rh`+ztIdj^oB7<9v0cjg_FcpJoOW$ zml`UU5Q=JzwTvsRh(FE>XZaR`W$FjYoP!@bc69i{7rwv>XFk+T-!Afb-ctO#Klk^B zLx-MewB+*tdstkD-XGs`Vg2~D4mkVz8n;;fw0rdYcPKj_1}fVv9C<q0-#LAH_^sdi z?csO7^!voI#onqp-kQ2H{M_IDx#4Gj_TL{~eBn9X&b&=IQO^ICJDkg29$ik$Evxs( zv^e#Hz`2;hd*9jKw+j2-KrLmte9{|Yr=qR#h~s-ZMTcdzZKx~oukpQ@Ygv)+KI1Ov z&<~eto7zuq7wXV{_>oL$d+!^i4~A+b#_|2WpL+`TX=WD3$Jf+BzSn11(Fe4g;QUQ} zd{7}Poc|dPXB|@YA+YYabK0mQiz!BxP_r4G1=UIDe4X{RS{j}V${Lrw0~tAJs+UC$ zjKt0iM~F_TID;6JI}wb-89Me|>ZY8n3O;r?2Oe5(E#Ur;;me-m4*YPQnqr@3c+yEY z&z>zh&Q`Hah|VQ>kxvhu!t!gpPjc-AbWUrG6*qP`XXPIS5FGHSqejE@m6@%4)m@$W zaV}SFi6@;STyq(Hd6t%rN@LQoBXb<f$lD#<;S1iC!#p~o47JMC7=pIYFF1ESi_;*E z=s3El{7K-4ZodW;U=Xg#i|*C|GxBI-;!|fSb5Js6h0pN{XZ6;%^Du+FT8<uuT1j5K zN~7Ynm+^y&?zna`rYuV<qK;kT;<%tZn!v&DPnENSh;kfyzceV1<>gsE;sgh$LA}aX z%7Hj()e2{>m7RRrP%n4OSDAJG+5wlYsuU*aj#fBlz=mG6`H3(~ehaqKm7O?z;3s;w z+?O;8OC8Q}-hfj{9IWc3xP?u+eS~u8V7!hKVKu9j{UFvn4jN%L<4id7?z`00X};8Y zJ>?;5>c*{H#At)8vXxJHd)*xkCQSq4epWb_F1byxOh<O2JuQ*lw8?PaSF(_`+i!0> zx@|Zhm#+2}Cy-@L*$8j@;TbRKqWqSrcx)pqL+fM5XS~<8Re4~9jajbBYCg}xcs8#= z-Gt60<6MV_l-0tp=F^`Y=AL`5)m7UzHCZsV+83M*)LdbB?dm)$oG+v2jl9;gfy1{p zO5ZiHa9VGuA#j>Z>kVaLnclc@d$@UzuXnSB!1@h-P1n2*=IbGny2^tLZHRn`V&lyg z(m1=>L;C8q+pKQhHmqIGK$v};>lH_JT>HFIY>?Jrg08p>-#CP?T)xVx(0Nun-x+pp z+c0cgi_Y#{99Az}8`cgt2ew=tW}&r`!K5VR+vz&m;Jy#%+t~?}Km={w*OO(mMU`%~ z<AUJ6bZOaCyBO`Zcw_@0lcH80riyKZq2aQH5VjxIoiS%zlV5ww0bkmhcCI8Y4@}8$ z7Q6Zm7yR_q&9y>|Wa45o5CAMR#NnVQT8Wa!T3Nipxoe^5loks|R?%6Y)-4|bu3}4- z4LrEmjiYiGABtPOj!7EZVcABd{Iv`DLC4hZ^StVLo)xGUaB}Wu+k{<id4PTQJ-cn6 z&0xJn6|tk58-N67@_n3}ekkwF*WToVa%+Zdd-kve!-mu+ZOo?)5siI?EaHqDqGNQV zixNKk2+es`2H)UyOCMTp+p}}nxOEHat;yub86@B2O+8nGirr*!|K&>;E)H)UJIS^* zTZTRRo``dFiq*K*?>zjDJ(&qSmRHWXLKk<3o7nQn6UVW=`_!WiY;m(SXD6EW4FQLq zXG=cL=2p)vU-fkH-E(XKaS>-P`b3wzarROH;&hS^>tPiDap*L0;z~3&i!QETxjGzu z{S6$>tCN2nU%B@?6<IB%&<4*fPm2JDmWzHU*SFt#i@JT0w)!@2FYFn1?BvVa=)!!; zZCxmyz4F>f4kE1!HyDh&rG_h%H_}h+dvZT*13d81PEpl+w?^AW^+Qd}U)3cZ0?^LB zed4Wb>mg5j5APec@7V^K%9%5GLO()q)p$r<f{$A~&^Y(*h2iyA-yC-ASkJ_K&+rL8 zZ225p59x5u3TN%Q<+q&6X;U$a`^}EuH2aEzQRb3dHK>culkp=UBNNQmz*<DdQ&>vA z9@ox(+yFj1w(f8qX%VFAG;aftrICWiv``_~?N#mNK?6{>AGM;o=(ysN66BB)wGBq2 zQ^k_+#zEI_>6^sBNw_Er8$|$bl$5%{!c*(es{JXuiY#XDxI{4uAS|TV7a+Md4*A3% zy1jfXLm4n#ST1c#jFAoGGY^HIxI}U#T<OaU-n8^22-@zGT5=hiFoNw7oJC`RH~Y}K zwC0PtG?~7~a*e~8`4Peut2N#(hjZnXe%E`DP5g}Horrt%WtT_(xQ?PYsVekWe2S&R z6~>}PY;-<8S8D$);q%K+aFG<-<1F?@jyucElyT@ZJm=v9NnOPwsOIVIu*S<%=W7Jl zE;Nabt2h#;<)C$zjFVglPY*TX)BDAtA}0Bo<Yg)BSYA_#Ucq<7V?B$rry1)}7Hr-M zOKJ5wP$dV94D)Z^4(mC18Z&voM7nLRVdQXb_r`X71yQ&r9qS#p`Mqvg8%^)AZ#(}s zmU^_qx#NLX^C<-Vdf~RNG#W&U+cAdcd)?ujIN+>Ez=)%o8%mim&g%6#oL7~@*|~GG zV-2idme%OAiLj4_0mTzt!4vP>R;G{Q>Iz=8^H#q-!;d+g5A5Inq8Jv1DvDqk#TOsS ze=mLpOaJ7F6T?6L$Ny8dxOBml<CtsLZVW$%!}%$;GmFD37%Xu@F;+Zst={_FKSt5` zE#Us!`2a^l(^KB-{9g6#0eDdRfLcCnZ?r_^Qx3-&HUVzGb(@a>s>E9^B;ZZ2U;gD^ z8D4qi)r^~6<n-bTA02-F=YL`N>7V|0GyhH>rqbaz<00_HW>KPg)ZRSzHaLp`d5g<2 zdFI|^^!rxRw9(F4_1D~I%R)Rm$rm}q#f3UFbea3yE|HJ?5rfBfH&lJ-<@VmV<+=0y z-cXO9@<HHSE*F-HWxKqvTv+BRsqP)V>Y@Gu_fvN<lg?&+bJp!`EYNXIUwSaF_Gez( z2l{(##_csM`<2UbICp85lxgH#9Oqr;1k2Vz$Nm22Zs+e0RjJE`{h;g*4TKRK&cD0x zKmTXHgrjCQP9|3+yW%YcgM!i#=!C&y;sB#zw*hjZZ=<Ah%Lc@Whe8FOH1m7!xfir> zI&`wXD%UP=H_gUn{4}){79ER?jd#*r$tr>wUa|3uwT@wIpxom(ofr*}PUczPn{9%* z!dYJ299%wJQZL`-Or!$?w44>yNy=v?R2XNRPNWA`rzb%NoP2i2mglvsHZ-3NtZCAb z11>VrEMqn=s|JxbIw3ieP#s#x*B!X#!~82>JBv!W<Wt;Ev~*~v0i`ogKY8_u%A-TO z(*rbRqL9KELfZs_<se;ejrV|LbW$>qz`qsRhCLkwc=B;LWKs7?M^}Ayq&VF7R#^3B zP#$>|KKzqrc^eulUgf_3#MuL0@x^Y+ebJM1HqBg?lTL)dQXYwi&-_6k`hsS+FGZ9; zKX?#1fswy(+8P}lk;3=@#^AlMmbbxcgR~|C5+==fWw49`!M$<WA^}=GpLC-uXc_F# z9Z(kfI@biF@Pw+3Ddpj6Jo(s&Bl!xiab4j9RN94hXovjbi!bIYtY_J~br-AN_Tmuv zr~l-i;BdM?J-7bKhYfSBc301}r#JGllGS?E^(t>oWb$y$U?eN%OfV3q9C8`iO6cg` z`+mrO*N3msb-S-TNhv(!k)Apfue^D-td%)s&b8Z%^w4$bz3{?W<_51#xBmG-K>3V= zo;V4)GCMo~+aF4KZ$6Kn=DEj<&tu^uA0HN2omkvM7h5$C+{3eZIk=O5_hP<u@hbXX zhi&ns)mOzS`kGt`E1bi!7AKzAgnLZ!TF@=qO;&!e0?`%9((unof-<|pBlZ*CtlN|^ zbzuf4;5^Rao8(``mK@VOfLjS|n>Fj{)QZ{Y+ID1Wib0<>i?){q)LiobgB8;AI=koZ z(rIrTHm#o-*3QlkYvOReF>C~IHSMmj#XDty+)mj&s0||-L7cw`8{RWwAdb-VU3H+r zkx=*QTfT&(JOf*CmV;Yr7;mtA9ZKYmcx!j25?*rz7F}14aXE{>4%>fmYad7yN3#Qx zNXNNwa{{038z7t$3TfCx{m`g9XqsejSjh0FR=iGr@dO7+=63)jJmuNpj8kWs0I+=q zUP``h$wwTw?;6%@+cmK4*oHbzsZ8K-mP<)qmE$T-$;)ivaQVu$`e@~L9D*31_|jC% zEI~Vsnz_|>($C{Wn*!fW?BEnDl&9J2Y}1bIJUCfXlPB7WDcTgb-dNzlFA6Sc;a9cX zjS~)?0e6KD2HwWGsP5LXHOy+9tRO@*<cse7X_rK#{wX?fPM+Q3<r;FFWmV0FO&i%( zV>>dF2LNTUjkYdSJ?$t-=igpO9JZ0~lHamk!)ooUEOzAslS50!J~`u@lvQe2*$sM> z51GGq=}J~g-{9kio40RewKX3DatjLdmv#a$b(u*U3O3$$D{Th4wheVVi+4`GMN!UW zYY`t1+UKO72_Y>x7tvQphd<jgWF+DwD~m5vw$@$WUf52#%uv6n)WtJ&44HJR7x?Hl zVcE{JN4r~loMx+)b?9OzTb%d?g}Sf~ImxE=4NuaG?Q=mi#cVynfzLjU?_d|#=!0}P zKl#-DVaJ{wRi@#xWiXQxMX!ZJ!LTw`uHUQ`&g{*-d-s;%nP>J5FR(xPM{qc^{UhR7 zE^-70@{e$kze2MWZsHtm(LGh(i(*}wUs)=6?$?Fic<XdyHDCo^aM}sAXOyov)4nF! zGf8RJ${Y;*rcuDADq@sUwN)V7$^i4z`;xQ*P3EE;cEOdFE-U+*POL^FakywQhEru0 zdGL36i&!TaPFtQhU_yf|wnfP+B**Bw^V-gmY?paOU0lJZ9db?9$*n;GJN~JLP)N%= zt+pI>?gX@)C6J%AQQlQBkF0fgpa8DB7MC=x3rYA1P7&DdQm=9uo#ry2>Y@(Do7j9D z&KUyR*7&9o535>Uk(O;0kCLidi0oW-{w>LoXkNfu>X)okR`lR?@jhwyau(SFSHRV` z6weR)U96Xa=&CAy$GN&a8`F8=s%&5kMp|REl}AtNv6kIZ+yz5QC*CuS&gL$eM^Ri@ zXBNc**6-6wccPP-mR`3!$~Vc^BrB8h_Uy`;@+U%zD)=H8%Wis5rb)a#f9F(w)k)by z<uCZUcDy7i<GRgs9L9}t7reYq;u3pfg)=EZRv01!m&uv<!qMq_woNZPuX$zlSI~9- zM*ABljWA*XzVl>#$hB>>@o;5cABxCh9@Nk_dan9Yb7kkYOb)|S#$Lk8E+4cmhqEi3 zYtG-xh+5jEXtI|rW!!IGf*7M~e(Z-+w}}^r{28hoTZ0)MOD_AqC-*%sbl}E6llOJ4 zbIYsiY+JX+H-nf@ojrSo59xi02mEI<pRfziDf^Ru>vO}ABhTeQeK??A7b|tv$rXPD z`p_3sp?Do#his4Q=cY4&me#4s`^oEu{Gli9b6f`mX>_2Sawi6kM|pkAdmZzU|MtK6 z?}mT=#V_*q*c%xe`ex)W{-?h<{NgYE;;?1YR&cUV@HY9tvvwU@qq11~9`+C)3w!ci zV|?j+)I~uqNI1uvSLe@OVD5994;tfVq4j)X7YiNM&GDdre%P{YZn%vCZ{E9(Pbi8> z8*CXn)-v=tyS}MDE*vrb9v7pr{ClK-(9xFDa?9$2=H*fNm&<2ts*31QC?6x8g>g8D zyB|aA)K}wo=vFakyv!K=2IE`XEqxn~Z;RhaMkXz}NLwdc6S0JsvCS_@c#qo$;UA27 zkF3j#?(Od~!9RR38kRVm|LL#%QYyY2*{N7LCxe1nku6*s@b2^xM%YYLDOk_K_KvDo zo^rm`gwS+fJ#q3=PthumxXhQvLR$QJpN<RSuEbk8!z-suDjkExc|f|?u6EYJv<94R zXfGc+kEG?wO>sEU<efbZi=C#^PLjV&b|v0}{BwxI)kZ?wN!lT*gE;1)6$dk^uBhx2 zOR|l01E@kINMC$93Uz|&fOXPnP~PZ72QV};@s*H4goLd2s>`5sa5+WetQ<PCb>6um zcQQBuR}OK=yTS6156_lCkMC(!A-zL0$<p@0=2{x#LA5YdUd5{XI!LL?t(;D1<t<JN z<!`o=jF0g%wL-a?KDd&9^;Mm-PhKe(A&6JE7E<)hx!Ygt6&?)QtNTlf!$Vl{n>FP? z*_zMEf4}cK3xd(lm?xu@Q<aIk9)xHw=)3VD4&zf_h?A$PPsJyI`S76pbl$83UW>=U zjLt$E&b*BPpR0LbbB)!n7jZfWcN1sM8XmB`@WKnj=FOXV@_d>-w6^5q4Zrg{UrYlG z8^LF19NPtN_$0yeZJd*?ima!7cG@-Zm9OZEG9FJfx-u5)A`e%PM|{d?qu+I+epc|x z_HFp@4qkPWpaNStbh!%$e9@U$&umMo%t{X7(q@=7^onk;|AiR4AuWy+c<FS-V;+Ne z901$C$j>B=j<@6L=b4XvdRX)Pk)oSTCESKXJJ8;(*HxA_IhM_(i#TQOyRvz1*tmHe zgK66XTOs+-(WUTFLGrTv15%U)ZQ2d?aK3PXJ(F?tZP>hlwvh75c-efkE#469LeWU& zS00>BI*tA4;MB^s<*;7A3OSqX3pkw7gOdv5)YHNOZ7nMY7VhI{#xZu~@(mo8^EkA& zvRZy_SUbZ93>U5pbN8+eYjG&fBCD$ql?A_J9L}D{tGuma@>PG9v3!PC^sersfA|P5 z!VxE&ZB(VJ%b+P(ZUXB$lOUxxOKBkZNK0QqeC|1SSewM46NZb>kru4lKHHWhGmhrb zM*}555Z=7v=v!(CYn(qx_a<=&5$9A%9Ld#j_$&u6VmCR3RRSw1?Ys5Da<wjTtzA;m z#NiNR70?V{Jzuqn?F-hdr{P&O+^0{`nTY^l1Zm)fff$a_YdD)PvYo{yp7gsqIDInY zLZUbi<*=;`mIcc2&*!+eSQ&ikEgjCQhmAN`-Lud7h@xmD6p?x<Rep3<uXLp?aoRSq zaYp*#LHGGp!gbj29L`O9u{c#4Vfm#pB%jwccHj(7KVo^6758V^nq~v-+x9q|K@e5d z1Ik_xdKsi#8xPv{T~^JUX%1%}Mz6)`y{b(XqXsf&D=6hb7<!mGTS&6Taf8*#I-7NX zujirP2KHp<`;Xz9U!-e?Z67zv;e&kpchlt2?I+H$Er%=3{Sc#DP}v^$u~%dl+6;s) zkL6;T&fP1N=Uw`7S9JKg;A-S>^{fvc{g9%1?lNgV(W?bSP{R(`T>;|OAUeEtoUd|~ zHEm$V4#L5!1NOAz&~<`1#w89M_-~)4owyOXcKQLtZP*u<n*L4ul@rdf-)6^Yca;r& z`eD;^yn%E4=*eNvo~^^vPwyR`-??k}$kt6bob5wxpX6J8h^zF`gzGn?3j#fGJ`jwP zo+s@~g(i5e>td$?h5rU3MBuCZ0zYN~gr(CeGgHNZ{5`v{gmMA_s}Yf2FqTB|;8mpw zO&)G5jk}=m2V)O7?KifmeF>|6Q{Ra2&k&yBJI*Ge95;%mYO2@jL3D|1`HK7Wf6Z3Z zY48h2y$Ejea$)^_XmC7~{1Sjx(|3&_#UXt$*!J;bI$M(TfMgLmJj(Paa4p_2UXF!P zk{2DeP%lb~Z6xNw#Jp)?9U(+k$#ZQz=>2#(%xcRx$Dcg)3+&Vs+Zj>k42m?it?{*N z86UR&5w?j{=XOK<Wc~m~S5;o5CMqbxW4rIjD#HW6sc$WIDgNmCfgD9id5Sa2J3{n( z={DNR)#&Fm%JXnp#4yRvV$y}P;>J2r+mj*|l<Cke16quxaXpSKSntR3PtpQ^ZpSpo zd7BNGcO03kF)sPDJ~arL^_qXAU6N~jn-2p9rt>AO)@xSf2ADXrblmCBieF)q77}Cn z;Un~uI?gICqxdmPY@4%VnT%bjTgGKxie57g$o!Xn(EHHqIE&Y+k3B!Uw|uSJC0RJf z#m(W&m@zUsM`x@ewtK*&u5oP}v1<J$hBSQOT8Fb+)}YTS|9%FrBv<id^3iD3U&kyx z&3R{SHC8s4H^9tF(76~r<=Q;XcV>qJPd=AxORf&FMZtC7%EgcA8C=ZfSY8M8rArrv zKl+z{gyZ!!oT_|yoW9e!&P$*A^zi)iFR%b;H}em5snqrnjxQC#d6GQQrqcgb5XLZh z7I-ploVv75P2Nvl2jzSGbSd8>c~NxcU9jW0<@oXA!*Be?Zw$Zv+rN$T_<G<z{;`h@ zpZomhhM)S|Kg|%458PkBn^mVb(TloqF~S-?QoL{fKDGnf5k0zi>K0?fci%lXeD#mM zI{ejN{y%I%c6V66X2bBpbI%W-`1lVF&p-D9w!v6wEv2%WKESu|&}SY1U<=xx_q7PG z=8ld%mZO8eb~rC8;`hB-jy^?T`&V`MebGI3Vzn#P-e`*(Hmpw@qEAGBp9>(h&2`Q* zoU1IuxYNF+jeBf%zULV_uitaR-w8oFSJhuDod5G*&Sb!L%}G|D^mM!y>_oGcMmilv zDt0y0R%o4K;^>XI2ARV_D)CNaOpEi#6^g`}o{0zpwyfsGaO^_uC^Vw(99o$@Dt(Gr z4rd2^wTG>f_HrUk(=j>$l7I7hXmD{3+W^gqlMiWS^>Z~)<EM!wZRgp>OCEgM)>pZ@ zGS<nc_kQ_O{7$-ks?zaPV^^zxOjlkjT%P0stE^5w7df1fx5M_;t5#4uA^8DGXj)=% z<|41M6HUI_vsZ_+xD7f#Yl2WRspw1+xs?}#dQAc3uK$oqSvfHmQm3_@e=qA^mbF@2 z=YFmJ?J|qSeS$4#pX!?4gScR7M8C&B^30P_dFdf?Ab3p#+JI*fM28%o<-aBf>hD2^ zvwBlD<tV+dh_J1K)^>XO7^8!t(shrs{0z!&9z(aKetuksv-W2hSq83b_TyH5=t`Tm zQPnA?j(v6HI-R_ZF*WRVFVehn^=du_sJ&kWUdO?zRoWl}I&9Wglxn4W=}|r1xmo*> zs|#^RD|*2>;dU~vt($3+s|d+`%C>Iu+x6A$*ZenGrR&+R!A>zavtFq)X&9t!J7ZmL z5wVxL(avidp5BIZo%(>x`Xp{cryYFY>_PaHnRHsDFqXGxZ9cqA@Y8AZ^U^Y(`_yNL zZJ+uWd|JnGhA;4tB7<F@yw-}w3@pKai<N+`GM&FJ>}>WqUA>0Y#xWy#mxr8EEo-vw zieqi^R<`7L=hPJ(LTg!7xtXmsa2mS|*?d6hw9ATWdEs!&43siV>zLvTy_ea$_TK$D zoP6tsE!#KHepLNmxX+|nh2S)qUP+l_8v}B%j{^Hu&f_3-ALlC!0I#qDawiWmaMI24 zu;U)Q+`Tl+-o7!+Ebzc<B@S!&_b6YZ&S!a3wvtcXsC_3{iXH2=JUA@BekfD@aWzVZ zNv=uozw)$vfk_S$(1ma#7;ZcD&>_V#u}cd#BnB-Jb$0TDZE8;}tIDJ#-oyqc34*ZV zC_1#op$mLV^FkQ;sX;8~*p@K;Fduj%B~MxUXgQ*pIGia9`v8<0yQa-qnaK`)Agh3; z*KHkUH*Ul6ymgpz6$pJ~KJeotj(QZ_{NBRZd==X}$Cet~cI?Xj$H9qiWQqT9RC<(O zBFLXM)&~jjb`uBd@uSCwX&jQ9ckE=93XWP<qr{m7yRJ08C$grPI3_g)jf*%xa_5#B zKEP0xjW{LOF+jw%S@suZTd9KwZE$GI+O}mw8$ug*`O?+l^xGG3nr~%mkln1VCf&YT z9SIvA<X^JX9`kx59sX|9FP%F17P@vzjg8q(V~%Yk<hL@_L&H4SBA*UiIVpPp5BV;$ zQu_w=$#&KK*gazS;aeE#5xj@KZJPAFmIvi=PjpvW>log^0|47u+qT}u)R?Q#6dvVK z58z|Ms<YTK^#e>kfYjOSRv6jqnD)6G&g7Ss#*P=ogY9Ik5OLe3^B2y?;k+3>#32vr z&7dv%kWe0!!Tz@%R+O%Fe4pi&+Pmo02cYZOcX<uvN(RaUSZ&!Biu~S}9g`RORcF|1 z@5U8YYF`-6ynS}qPTRD9|MuY%PaYUP{>08<HT(7W;3~Aing8fj?wW8T`6R0inzkeu zN77`_F63fy=s+c3rKvZsIxOeVnanS?$$-qG+q#M+VGHGGZF&g@=IlphD!Vtf#Rr8y zw$FmoXkeK|r1aa{7dS5@GR={`M1FIaMFa%yM-yzbv_3=vapHxBcb1!dP2q^>V&PUP z5=0ps4L5nK50eKtiUQG>dnAgWfOD!OY0@Vpdr7U02+*CGq2o`(WnDBwqZo{lF(8X# ziLpFe9UtW&x`p?0IOmO+$O0YuRJVcB7V|(-hcoq|JDlZK)Yh>cCa=TmM0(T!V9qMD zg)Wg;Dz<E~^j5gL3PR9)9a+P%^i+8(b}>&{QQ_<y)Lmh=`5wo2ZkFPK<4zwC^B9C) zN~>Z^o&dF<PE)F#p0GXMb0=Yzk%|E>hqE~+12iUYbKM|3jS!fyIA=gZyT@||KG`a9 z^!uQEm6V+12^SsBgA4&&i6(Vio-LD6-Rw{!p0#@;g%Lv|pn}@H4`>tHU@Aj06&(|U zPg-7zYur!Suc+5JoT-=Eyhq?dMEG`i50Y|NS6fX+|HF^<RNVBU)EjYihjWcl#bZ6I zIUQ{Z{nzSsIGmX)_|d@baF%;RnguT~v{(yb=S_puZ%IneGc6Z!-Qk>htqH=Dy|zLV zia+BCemHEo4rkTv;e1<aGzD4h{PN3R8~*f9|F2xH$Jyn)@2RJr9zOoDPjG%Fb7RMQ z^lapJ9xpc>o<Ugcl-v|gb@sY=AIA$bzMHJ$#!uc)UYqt_K~9z%oI5%Ha_r*qCx7xM zaX5eZD_>!pb&I}y`|!+>XNHfx_=#cLMm|`+j(H2?6t_TgOOCtP!8CKh^^6xRy0hor z<$E)1yT;-M_tZUc{N!-r*a^N5!8~?$ZusmE{mAeMbm%_OPwd?@Y~QzKSi6Nbn6An8 zxcn82UC^y%qOZjAkxzB%^`pXMoqH7Q2a#?$Ew`*b2>OqM^Ktk@`;UWqS+LUA*Ww$? zYgmXiH#dtv<R0HEy2Lh=*E25myD09$(Chc35cjsA*Str;f0*gL{rxa`ST=3iYAs;J zSAO?*7yj43|0`n$C>1p;mnJY(N7E*t>By=fx2YRBjzBlseu2i@j<#2xOfKkj@{|F* zI?0@P==}5C71uko9&baTF~zA%gG1AnJbpaQ37{R5dlpJfhtw2}m|FojaT8Z}COOG; zLOF}G%|We>vou2CdGX3%^U8NRUm7tx!8mXmY<0?|ylgQ6T_=a;kwymQ<dGkBBYd38 zXj`2maGG>D_sLyXxp~AVOihGW#Hnb1qjOul5CU9>SvlqXSXy7Xt8AeLj$Q`cQ8%gU zPOr{ZHTgmY%f%jmATO1No5)~n;mzw&-llfiY1h+EX<EjvqPBd;Iu-cw!a^+_8)Xvr z($HnfnM4N`lX2#GKZmpSCXD6a0}Jy$%HeFD$<S@rRkR(4I6b<JKeode-I-tg`Kr-s zo(B6WyB(_z=d2Re5saR_U&r3Sm_1L3d3uZuSS;$IKk3sEod<oyIY3axc^skIxA3u> zyH%Gg%-8`uD4X`|;p)5@;>N+1g_HN1W(}me14z8qWA*BTnH4xnYj8Op=$Yo=MQ5Ku zxknCY(ukO_qpDxMosci{N7uj!>%B6J0&&VAZ|0Mh7Jmmjb<(Jg4U@RUS2(L2diCu% z=U)1e;fWvlG<bc$fDJ9UJ%GH@7O_1=WYUSqMAb66#sh#$=WbG7Q^T%(yK&n2a7G&P z+4%M3;GNbEj!Cm@cwlhl`f%#_6$WhV9lwKt)<#w<ulB3DqDK<+=Hx(JZs&m}Gs&NY z{`m`MhjZu8QwHq+ylM0B#Qt5R&%>Vsejeh{&M3aCvNL*Hu?A=Jb)1AAw^>ojzPYE) z<KWxNig`XdxQdTV-pAp5`_eFV<1%|Xvyx+`JDe#e=<95DU+3mhMLzV+y*l^LT5Jtc zNByvT;wUE`kb)$=+TbV!SQ81HgDrU`a8zmlgjM~1p?*YzjJ2A^2^9H6>mfbP;`LQO z+lvJ<=U^g`bka<(SH3wLuOvBFKU8!YoUoC!!ExOu=8=QCloiq$Aj78<4q$3<tWz1g zvw*4Z<>=#H2v#_+oL)Pu+OTby+rmfhcJCYJHsQ2fvo^K>^Hpb|?x6nSIm-X+x#3-o zy$24m_woMftK+1VB8(!hgLY2Q)k<w2TK6e4I!v6b7l&8A$w%%O!0p((mycfJSfnkQ z<soyNvXpn}42e;s^@g7~qP5FAtXet6-pkk7!`V8x181@OCp-BFB^1*2FJbPYXVIh& zf;aaZzHs*ZaQyWX!!|w|xStR9t>VGUG#}rL6STCKvJz(|bBT)zv#QvS2EP8<>nZ!K z+qQvcTb$0mF{HfV-K+3UKI7q6+3fFhoS*h%eQpopq-y7mY>Baw6*u<PmTM-U856X! zQ;0T8Ru}UOhA*+F_VG84W_9$TBTqBN!AT4)+osr+`Vbla@*-j{jk8GZGO#{z>=*;< ztJx}O^A`5>W}A{44{1w|4RDUpHe{@!t*c<pw$_%<JkI~CtSCB*eax{p_ZIXqq6434 z`=XU<7j4H=7r`SRw(mN>-Qq;Y^G5m~H(g#}5?MjMMTs5AzlSpTXS_8SerzY~Gp}B{ zLH{<zL)F>gbD#X=@HcsTq&u9=+k<?0mu6FZi_*L=$g<$N9_Owrc~Gq*-~!`U?No>j zhZ6T79pm8M@+7Xd(TGL`s=ro`t-1*<W67^xDTmN0+b_(M*vodOnw}{%>XDfIq1BX^ zR2Fc>5sWVQTk3G`+geboQ<h^#hPVhNLR}=nOZ5UT%_&q9aQI|aAAO)S)y7To_iSV3 zbYZm-<>VfHj2zCs4x#QW!;#2daD=9pTuVn7={yiRd^<moE(+5`WBw|i;Ojgkb^P;y z!`ZwX8K+PeQg$PUGnVTZysdCv!8S*IZc}hYyI82}Py(U$zL>X&I<jS{LM`AiBd+8_ zt(PoG8sUiE5+&4ohsnGhs`Ftf6^%;i^u6nKtWv7p32gji`E_1{sO1x9r&0O+)s`NV zMTvt0q+?!+UbG?2F_JNDBBOKj3!$ww3}repYDT53P`oFy#duA*kkIAT?#8@Vd_lD= zJ!h0KiK`M4V;cX(Pm2$M4zJ5`GL&ubTiiCKHZ<Vs`8;=6qbpu{N7sm(d=qI>imr^q z4h_AmjnDYYc#b%Q9aAR0-c&Wc@;6<YW*gOTIR@?ZMI6Ew5%YnIzl^ULFPrAKP3$Xk z-Ea$UAGmt$rflEk8&z>Qr%Vf-?Ne+)d5uDFx9V|RVX)l^A4zgfUhQo9tA@vC;Yv~R z$g4S-U&rD6Y~2Jll%P}RSmDUn$wajCAKx?*qrQc=-##^b=}TY4@pX{}8k?fmO&d24 zpZwHI!w-JqlWoo=#^x{J+#S&R59GbV<XKwYn@>#|I&ZmI)IKD&DnJq+R{ty4;@>Xi z;@F4Z`6jGEhn{72jj_nT`8Qu1e*M>fefZkTFK5o<8|LfS%5T@UJ;T$7j^KcPdN^?K z0OKjf68z2Io@e`!bHiW$)n5)L-#W?SmWy!~>hsyacw&aO^(qS{{Fve2`I(;`o?}~* zKmW5oXI1px;l)oqKO8u+k9klnii(U?38Hg(GR|?!Upt&rR3FMuTI9zutYva(+3MS~ ze7Ev8+#R;`a~lnv%~zRgZ(}^WhH<U*Q_owic@+ABeH7G(pWfT951*4|aM0T9d^E5- zoNdN*#8^>n%X&v?C(%2WatgQ_uJ%jRLFDpvVRT}dw>O8i!UZf0FvZ)Qo;o8{R`x7p z<)*83bc&hJ$&rpQ@z{84P;t27aK5(yO*|tuw(d7oE1RH);n~Sdf!9fvPA&24Op-rW zBFXQn)jE@_sn%KNpfMBrU{q;tOkevaIRUywemf~Ag0;fKNtTWU8hssa@S@!F&B527 z^w}w>r=TUj9iAPl6M83{*@w4H6iT<PI|CNR!?SdhHH{{mU8OO%A5v#JF0;B@JunG& z`vZ04s#QBK9grzKd2fwwZH+*e2z?JpO@>~{%K22Cx47zwv^rB}%8@wptM6*WOTI3n zbc=?LGMrH8PG_k>8V?QfLQ?cvmj!0rgu~g~mPZ0-ujEO*Is~Mvl464Z_rZ*1ToVNH zqmS;GH=lXbb6DWs#>;ri(zCkN!5cc#E9%j=m-1w=T!j~x4?Vm#kF+z;Aw3Rf2S1IU z$#j55TWUlX<kx{AjQeE!KmkT#JL0y!$g78T<!fDYt92*<%|J5014p_xDcmaT+1I7z z+YeJ+zwWjUI$q1UAs);4cIq&)vZA~XAl0L=;_)!JWvaus3dZ4J1P(^I=AQq^teiwy zO3K~yCnpYPb9TJSXoPja)yf9#e{yA@_T^z7;e4{$+neMkPxJ{c&z<ieYd`8rnatPA z*>lw$wj{8OY!{-R()}dPE<@14@2ZzRJM8(9m!Rjs3md|Dixe<oyW*f)+qC?Bka3&U z%{O?B{u+*+`@?ot@2y=wN1d&0H8T7KC)J7{Wzc@CV?H>;F~qhO@0_?o`LAY0Bu-yG z9Ox=%+mcM?9pKZ(n9ruAJDg|kO|!E4!f^hQ1G#B-U)VV8*}nrGZ$b#$U$HK2?n+)u zTUel7wrp48ILC=RK-UjEo;`ax4(H7{`8MIy+OU@WuyHug;&7gxzcS3+pC4wC*R9la zRF=b8++r&kC^ZGkq|SN{v8<dW(!1REcyA5fTNYKfb*Lv28MPvGYdVqkEe_H%$!K<J zegj)rXXS0THR0oM25+@x(6QNQxIvk|MVOQy@qo&14uA3|3*muDj^#|PSmaoXP?kT* z>J*;)*_<YOpLFr(+H$upX?yl-;8s?T-Ue~K!tJG2;_PLG^Xg5M$=)Z2wOhBdture{ zK-^b1ImPp1yq9n&o?)Nf6Ksib=;>#MCl4J;I~epZ0BRUe*Gg8*8AnWXu|V5!83*Y% zzy6J3j*kUCaqwWijWFj|<f%`tZr16n4s9E>fs_jo{)yBN<-PUhakloj8u@nZdxDkr z>?KXVT;u@)G=co3W4RG8SZEh+@KEhMuUZ~`<5(QM2M!;?QOab;mHt6e2%N~}K)@zZ zlI;WB3gg>2&JFHa?8ijhRwLsFgw6w3(o*kj!)SxmzhjX&i@@>D$y0F{JC5-Kj63)2 z*6=AWnIOQnm%Y8BW>rMeXq$C7v%Sc%H{PT!ZyXLki^G|IqaO_{<>9rsVkiC>s7iNv z&Gb!P+x6|1b!-i?b;q`06O&u{bv|reu$?rclX30eGEp;WFF<vf4?()u;=9;~4(liO z?E|?qnjFy{_eM3^RnM$D)i2y(eD?N<lX1jv-neO)qg|S%T?*5|gI-#>iX!DIFJ3jC z=6MKl<JvqABX06q<SY-h)(k)Vk>`fbJaqv7H6@8{N!Q$R*4yOZk~x!FK)Q+BUiwN@ zGKr>Oz?G=VT=60qL2_CBO~rx>c%g+bYxM{6<Xzcp*HciJ|08LMhe-0+i6&P8XnTcO z=2Al3a~3`nN!J!br|~4iR+yk5EtNS`NBR)2^tyvP`J0W7Y*qZ?lC=2!w-HHR^BYxd zQXuSup<HlYED6#hO1hCtRQxs0!e`oVB7&#EMpo@Lp{FQU<y7~E(s?teikkTCRHR+e zu@$KMXZx&dV|^FQNEdBPo;H{yu|<c?*1fJ3&W<-F;H&;Vkg`3tAR4cco!e39@^t?D zeZhAbqY;wS*V0fhT|QI$^@FgJc}rhFcRe<6Z>8g{#XT9it`kRE?4sQSl)N#KmM^-N z9pgPGPcl@l23Ikbfj|wGbF~GD;irJ5*-$0M*d9~73lB8oD_gbutem&MT;R-8x4;&i zR<|q@{z5tB)0tv?l6dZMimtG;7t%WE!S(pTPvsfeOXwR{dgOx3jyHGpquq^ef#qhD zV<~v!a}te~<$W*9o?9G&>%dWrfQw-zp8DAEG-TnZ<MeEs-rIE@&bdw;<9F(&;{%cB z+-RhJNWayq^pWZ?<0s*{ByaSYyj=5^fb?o^S#3=AkIwjmGNL}M$(9<vwd0Cd%M=~9 zg3s7k#G$Kh5s-0+{cQ#GA`g<cJvH9E9w`ZNd25@{<N?@geFq2kFVErJWpds<f0O-U zu@}cpH*d|ey~G!IEAVvsRjJxueEOx&3_tp#KUQ-sob9$9c~Aw9ckj4JrS8*jhff74 z9p;<|l}cdA8^k<@==Ca*{4Bli@$YwzHVf_hfmIqzIG^&ZW*x=S)A=l0zxI!QZTRw+ zzsz@oE)GYYIx<{m{<3e+lf$P!^HR3iaLYB{vb%ic((v_feq;E;7k-@w-{;WZ6x)39 z))fm2w7+S#D_YHVad<<9pZ|}4e)#mKJ~RCBSN|9X^<NA>_3wRt_?iFUr+M3L<9Mvq zY*Ys2O=fC4&~aZ<%s>3sKH|d+>hL=$w-1x&N6~&Pn|c(oiS+E@OoemT0hAU$qHhuV zwznU_*4eDz&vEbL1lxgL>mDcH_Zl{Q+6MmrA<#cqv$CbeKl|0cpUT}k92;&ct7i*K z!E`EDgI-QJoi;jWyTjSM=IN`PbrhS=JWixikuZ+#T-LGV3aL0yaq{T+G6*Z~?xfZs zWbi5H%q$-nBDiWzHS0WdwR2WCVQ@N}eRW@&(sM#M8M2y?z9$n{_$>#8oow;xpi$bE zp^a1=<D|L2qE173iJX}n*3&cPjPn|2k6RQ-TW7U!Ith)lBhqncoM8qhk#Kg-I^!g0 zClh@kQ*UrQ>+DP?PCg4vI6G%wnGFu|iZ`pOfG}PBI(wsYa2Wb^$Eg!XB}#KL-TRay zj$*In+jGy~9p}*lyq2AGC$oCA6Ssp!9^|upW!!St=?$Vdh{RWe^y1A`+v-i=RQF;F zy;ph2L+35!2LH;R2La%BP!k=3A*;o-4f1rI2c3)&s*DTYBuo<D<EO(ZuZO`n4})=; z6i?FR+BzZ+wL(svbiQlV90+2^=D%yDY~>|R^C_cgp6{Sj&jw}H9($UwcNny|qD>g- zYPY^pqP#j%e0BWdrSn<U7UvRqtcSw81xiTcq4UqU@Pc@jW#?svK@lmj+1@q?>w^l* zP3L!)$+LVq;FC`+QCt*It<vY-c<rR)QnrT$@kpoSWS?z-#*S_876*A3)<fA9PJJ0~ z8{@;MD!H-;b!5=tY?*fX9RNv8Jd-%RpZoNW4tsv|Z_wu1m@+74dkQwu1+R3(V_9LN zI-?lCyUO$3w=c2M`S!4h{b$#0aNku|Dc7V&J**%P+Lv7pX<E)YV{Qy*a5yheA6)6a zb`yDVwz)@~IWl2)!bCpl`2}akr_(r`eaLW`Z8a`jz#iw;4ZHSkXAplI-SaSGYCZaq zqRxJ{(Li>dTHrj!wz93pZC1x#8cw}^j!D2)Rv)e(Hg9BWmiyO-ncJ6H<&4Am9@}aR zH_PFS$kW(yt#C$<Iz{4;*O{P&aPQecz};r=%F176v7{=4YzUWngUzIFqaO!^dFTX? zASq*PF6|AO{F@AJ^Dv@Jy72d?Bjv;f8a9ZE4LTEqG-;%ZtED9!w3GEcRAdwhE&Vu~ zJ&Q{o8XG-cp@j3l@`}%Vpa{6O0(~YSjKn!Rc_uwHOfoO!8e67(rsjAqz(>_KY#%o7 zJ20%>z7uEPrVQBQ&mxQcBsF)qa_;=__NljrH{LutJoW5z!{Mi&E=Ou)<e{K_sI<aN z(UCD%o4e1R4rf>7e)HvT4C~mlc>hyRWosO_)X?GFS2#~0kL|z=_TyyIw&gC$(*f;6 zI33Pc*>_lxckg4hJRiC975jwn63v8{>f=i}Svf_2?CNA!Y9D*^=&%E4@xiAKQ3uci z?Fls<JyKu5qk}aLIP^(TMy@!TxbdOSx4!Ys(9prUdFxi%$hqMTli=`9+aSN%n1^kQ z<!K+^kl}ECD=WV3yLanwX0`TR`R6e7e70@feobAR=!gISKmbWZK~zGs&>h0V<?|PZ z<8K}v*0Y!Op(BUWCi!+u+M&j?yc@L2*j_Y81oh_5%{#2rewBw;*LeuEDf?M(bZZa! zg@!zvukt&NGp6cW9!P-v?7L@qn8fOLCVD&hxa?ud73QOxJn)NFsXg#vdsuH<sfJdM z7-P6a%CXm9&jW>RY;&?@+a}sIKhR<u7KxKTw%_<sEZc$Lq0G**mBxj$JP_km+U?sm z<imk4?A<ebl#dU7_Z-fpi73Q+*9O30PJUpjxGkL}-a2RkA@(Dj*ZHfPNj-Zlq9%1) zl?<FQ;>p2@_P(%K=Z*GW%vC;tXM&wJoj7%+{wu!m6grH}i7s2u1uz6rc>=G8yi<b3 zwPliW>0o2NVlO?}6^V^sdxt#y5<}_(=sKK)CPVm=Hhd?){1-!H39pXV4UNsfMOOOw zajX#ChKQ{!z;<1kJ{cN7qNH7E+F<{)y-hhLQGfy(wXsddaUwU=(IIVE$z$K)IKKLi zNr!Wd7tGY^Y8Nhe#y8Q)Nb=&j>WP4jpU!;p*3YOejpDkzW89;piHoAA-V45?_O_Qy z%wsZ7M{OMF)n5g2j4wO8rE3xTFS6umSwyjjMa!Tg5uWx$P6A`R7nQEXd)JT7N3V+{ z(T3nqpbxo^lX8J}zZ}lC|D6uGLGGXDQ1HG8a$jSwP{HP>9G?oUojIQ39EWp@m*z+Z zUI$OGn`A_tCx5lO+*g|Ui=RoLx(+`1n@EZt!hVmfbbpI{i&vROEP<7{c!f$bKh`%x z(K8Ew*tz|caU+K_@@IPu>ZW5S!(xZCJfO4CAg}rDxHy7ac=A@g6_<0Mnp2J(&cKAO zc_lzuu3fIf8N#tA`r2wEMF1AYc#+C}$a)QbT=3(;CHLlwUXZu*>f)XQkLhq;y?PZZ zE8WtNIX`0&ovAudkDoY}v4ws5HO4NV_`y#OKk?%~K_Aas$~v6kWs0$q?0P?TIG3K2 z5N=Br3axmztlE{Qx-NMV-F_zP*<}3tU2Cc8W;ww*y<t5M?43XMF}P#(^Sn{{HC8*n z^2#fW5pE49_&&qMbC+1Cux9w!$A6#}P%+eXrSnY|OMU(8U(Xn5yWbe$EleL?>pSsb z`i^Zohbw&l#syU_82Hz$aQ@aS-yDAY^FKEHJAdc%JSg82KZA6g<Eanle3@Hv<D9PV z=NyLL=f^(c!wlng>%-*YyH7iI^<75mThrDpeM~x;Z!oskXJ<R$>SpV_ZIN|*xpkrH zQm<d%Wrn}Y=z81rT}J!Cprh@wX07-azyEs+zx`kRY9{oVBr=Im5G$(=!3?gb$W~^Z zSjJnabu8LI+6g(av|vr^4rd#q-a#2}&_Qg6<BH>sPv?(D;(hXSFYX%D)nq4`8BBDC zvu#3}WCyOcju@B*wel|8I5dM(260Y?g*bz3=n3W%2L8>flh&spF;c9qJDhF3A`_jJ zPB9(KewkIi#jlLYWLlRq&R$4ln+qyLbky`J**w*Rwmh2FJNaVERn|Jc=nN-xo9zwA zEUdJA>TAX7IK-=SSiXIYCGpY_p0bf&VIm;EH30CongVsuaf#QmuUD+?2q|mI&PF`+ zo7~DFPV;pK_oTyF-NoSy8EtFq94?(d%;5~Gl!yF?o00*)gPa-&Ie5r5_r)hXXfN<& zc>o%RvuV*SafM5KbvUt?=M0WG3pW{(Ceap>4}8K~#vbM={PIOS`VFHkPuYeJ_i{K3 zE8c`sTJjqg-Rgve`@j$<q<PeN%AWJQEA_F{UhdXI%hmn6MR}8bLFaGOn*!@uiMV0I zhSXW>gp>QVIG?Xvy~v8!D}nDivK)K)EZiv`mDwOa-Ohzy1+D4S1>oc}yi)fk9L_qI z`a>XbSnknb$H$n@2Mo$*d~kp#Fx>aEd3)&2;tp%Pa6MQylfm*3f7f9q%8g&)dYU+t zs~;V|@wG2{@gscKL(jYVQ$LKu`6nq8op#!)&U4!=dBLurr;c=pL6Fzr*|+tbvy{P& zVcnM9am=h)%N}HLP*=N@R|9pzMILd{j<QGcO*+#H@0_QMvE7v$hV6UZE7b>F(BdtC za<tXM0|&8p^4cOR1elQBzIkQ1j>GxwQ}cXylGodw+{<fd)DvDjnDVU=Is@_C<6(oA zw}S0J+&aaN#jU^*cOJ*oTPIKP#CRvG<TtWvg9m9$GN#$%dG^lfVdgH|YTV}o4d`H+ zOw-^BPPE`;O{`Arl%+f5iGpwJg1T!lrX=$t2lc1!Z0pLwRdrh@e$=Yi;IJ&>kgRDd zY3klkwoy)3;J{gBSZ%&-qAC_won^=Xr#SSg?Sl{LfFv|Y4LqPiCr6k!y<p7mUxX4J zK=NrmZ*;+T`|j~^ESsFkkP{+}so?7Db=}`}Qce0w9wb<nv+LOl`HB6*+MRobHQRTU z&62)Ad#j`0iQ^Tve|Y=UJ2;$=4TqmOl2y(#v`gyEw_#@O8*D?l&#(ZQoZIMd))DKr zDpzojzV_``hc&DmaD}sd%xVUDt7%JhO1qMJCAO4F6ZI(%smQO~mcO=tLWgr!IOA}B z;)#5u&Iie=s}BrQ|13J=__NGX2;jfwKGdvmKEVfScHkgAc=%9#@Q*f88&PwW)!z!K zgIww?b=!yQyq@{3Z+s(t@csh_vj4J9YpJQ@IN!yE4wS{VSEP9m#e<CnaGb_@f92Ap z@TTK?JA0ewMI2?-;1bXwda&3%{Lxf&X1mJ!0*>?JZ@xKf+`4&q=J{u#Q*Se+j}%<R z<sUrcQ5QjDJce_ZJq}-a<y*X-dxLF3wnmrk@9zp{b#{mLbsF7HP0^MRtQWm*#MuCv z)2w<w%g6fc4|eX{IUGE62t~nUvo*9&PMk0{ZgK#Qa&7`ce#dyOI)CHUS7J+halUV4 zKk+r|SZS})!uPmdh_^emm9OeHU!<o^yg(as^~!lxi|-uv9oRoSw{2rS8dzIu$iEth zbrx=g3V-qycA{T@LfcdmS{~(a<)fh<1e)dz(RG#l$-=$uRasO|Z0DqTtqvNF5rzpJ z!$*&{e#gl_f^Ydduf&(rrXJ3kN+VBP#}BIJq{f26vvoqNz>on}0%$arl8dK}!KwV2 zMAOy^Cuse6L6COQsdTP|N#kVQ6Q;FACTP>9bBy2x>7h^+PVp*RApwFMn1J@|b(Lnp z1cbK6AbfE93+%`tY?{ukWrUGT>bUci2T|fMqD78yK@-`+BXE^0kLZ#5lsufvNk;v% zU1DsShl4oC`q;m3%TOv+&M~cu8{bRIQ2JQPPv<irBc0V<{dO6>D;$%lOJRzZv8CS! zVS7w3uapmLSr)OauE-!EAuOXKVH$dEqdPMTpE@-NkPIW(iX#@hrJDv8SlVAA$1+aZ zfu#~dVv)w0;T~`MEYQyRP$Xq250<+Wi)5p0e6<=RB~h3$zYQ2@OMV4ys7~i89>fo9 zF;=!$PG}N>LIUy_JVi0_SWN0&r$46J<*59<O*T`<lj~ra_z_V<Hr7ey5mRA{#L1*g z!u7OC855uMhCe{)l>Xm7-*(yYPxTp&g_xN*UQZl(Y#Rt-7nktiz;in)f5Cxx0vBTf z=BUDDJl6Qk+>LATtf1e@9?rZ$<qGF~kAS+Fwg8xtg)@a23YInPpksK0<JRJ}(Z>O7 z!RKLqtK&pqK~=A#&nA=3;3pr`;p`mGg>G8qEMt*XY<2gW|LlJoUVHUbbaOWk=UsXE z{70T2euNdy+qdn=eA#x@{$7>2$iaua-a9rOhjyL1SJz72uY~K+OWS~@_hX#zeHA;l zk}M-QX0r?}|5Z4L4Q0=jUnigsvrqF;;rZ(~S!{ELxz82m5bN=cFy7(KG|&2#bUHg< z-HfwYTw8f~?N~#f%=)z(hSy(xBdea>4($*B;QwGQd}H{VpZl@lZ~fFy42KRM%(i0A zI~}K4wlz<uufkr+;jFLX(Q^H@!#Tyc?4Q(~M?l*WFGKZ@!17?Swr8EUTy-}4!ATv^ zu5R`$ZzKL5UG$3x^g6XD^84&&k$m50ygk4U?UzNc;$QsU?=5`sAN@lbz^bgCEl3?% zar{zf-I?c#NgDt=hvcSI6k2%C=Fz#L^GTREXlRUVNPD_x9n2a@?;tXnGe3>BPZ({$ zoXps)ip${smeVt9bM2tUE-r%$CrBLPn}&BgM;&O&ahun{C&Rt$wb~rpz$imx;lc(g zD{#pGE99>g&Ng~|#gdiAMmDnZ!)@_EhWvSsrK(*1T4hi_(lLKI=Ijvd*lS{I7Ip2P zvdh2DSas!-Lk9vq4nkSsOokDRoxAYr(XA2O=UH5xCz-Nr#K(U-+hI$0+)?*3BWudc zbaD5xvJ!V$<TLT;M|c~1FD4z%@{kSN;l%x(<WZR&44C)*9L|<UaN(5dJWE@fDLHDu zk%2zAVx!Ft-7-V`+JKHtowk-moVQ++CXQ~mFuo`(jgOp-uJpSub+T)3>diP1tBT;a zER@wPE&2lm>w%7)K7r|SD1!qgeHH4p+lIC#z0w6ATEKY}*wm-`U|{MTc?~`#_th-v zDXWfkS9`~~3y*%VK?jt)`BYxqzFD9RXz$*y&~q|jBjWA)kpHY6CvM~*5}2^a;jFWZ zAl|A|RX#$>*L`$w8+yuVT=Wrm%cz`?+%5{1rEn=n<&{VO&~ZN|GpHx|_DH#NuY8u3 zxGYnHaLM25b?LY4L)}Iv!1lV)aeAKp!5<oS{_s!Y^rC*j656u>gU`zvuv<6f7kfkR zXU{O`y3Fd}^}fpQLjkutkssSh>m7VrzVgH1U&n`z!`lpKubeqYr^?=|ch(HM4&Z3q z<o<Tl1Dvqg>V#F*)#m5~bcHpvNxR2n=_ae3PaL~~z-xyctn8dy$3Sm2_6mCUZqDF) zg<IbcH%0qQJ{=V+by((uUhj~$kyY~RhwZ!AKNy`%^MG&V?UOj3FAlSJbvV;+=y2xa zgJ@OP2zcdB*A0YpIQv+ItvmEutiY*~V&Es|Dp6okvh}OpkRxT36jDKj`mrC??SNOu zCNR(_xEKfbXwM=^u~^^Bk?i2!YfxKU!Np0k2|AqJn>H}gA-+45vB1Dvx9x|LMdowE zIsg7}ctZ%k!UJ4(r@Xe${U|)%tFaum6^jn@P?p`{e3!aHe>lCCGTFU%ShMSiVI7BG zbzkY^TjxzCkCfl}OT#-j7mu=svRi5#IQ&!w=<3X^UZ!c6iy!pUbmL?{VqsW!*ysHc ztE6A~)+@tWCIx#B9m<DEeV8}{Q2(%=ZAW-cJ8zkkL@G>&vmYIFZ#7}|;GA^NVC_{s zS>pLuPb1Y?PTCDxC;l?8XP(1Bdh*0u*$(5t;lpt_>lE&NDI8$WAn+iVU)+$aJ)Chk zzxu6jQzxf~{Ra-Pr};)!NmB<~{Z$XjZXNWYmG$2;_U)UrQ`p7ZCr{#VzD(=_bz$eQ zl`pK{Lr;_te-VRUu3KKvMHlj>L;D&7<2am;9b<(x4rjKHu#K?2j6O;g9nnY@`AECK z>McJy`0a0hGhch(wP#me-F3?(^Q(*M1MCN@|4c<!6J^Z7eTKc4&#}V!8e3Xy-@%^P z2c9Iqx^v=N{VW=c!<mwxzWE>#9<fm+^{uz-l;`WOd>cCV`PkBaR%~ykjc}Y+`d2HG zOt28Z-)&8Ox?lR)Q)h>ZIN;~6vrqiqCx*QT4-U`r2FJ6T*7H!q@~m<!g-BTryu&uS zOvI(kO&A5@RDObOsV!0@%5OOA$w`^~k;*vH_E1`ymF-F8RXRx&QTM2~Ju<`u!=*PI z@L_#0#CH&YU>T*E-{=bB)b{Hx<q|};^++y0lC+r+P`4vs(?|_H&axz4kOzO`x8SW? zCR=w4RJ?gGX#SQ~PG9n47YU8gkgb@-zZ81p6^9MA@En!DgiJj*SNP;?U6=Eb4w02V zljCF(ReN8>Y;qmB>Zah@wL&G|B!E1~zX=>VI(rEI$OexY6PN<LaPX6U1^yg6*e|4A z>RW2yAj>#{9L*vE9}LneC33=|+Wkm&Qmsw)FWQ@$vBeq(W8kFedmJxoW4KB$Sn2h& zo-H30CUdxHa(9?TN}M3jc{M$C7G#}dD7PEoIvwlkBK9MZycS~d2&??vxl^moO)m|o ziE$|01uGI^W}1_kdFIR<&ygH$6j^b{ia0Cgq@Fv@QL&RgNvWrM7LP}+VSdVfM29SG zpyN0?6Yw+6xrZZ~H^DjsJ&*Y;$JkY{P$r!7@JSiELJ}K*z>eb!wo=5yeakaGo7(U; zJYBZL0$*85kkA*-$VIq>b8OVcQCw@^={u3pc*p8=DuJslyILCrZ2ifKc+tLjgUfsW z#Z}{h#4~S_p7`%&5kl!U`9(whn{^LoJ`Ojn)0ufpjfJ}2KuQ?vn%0XkN414jrs6L> z*?&;y1#b1b@;03`xa#FuFu^K}$8|V6$8r8-A<f`Kb-~yl{^1`CFMs`O!$ro<>(;Hy zH+Bv@d2smDOD_#ac<ArjsB-E9Vc$wE`!1f8bsS387yz2o`VB3Xs~)3>l|KNcEV(az z^wfu+&6Dxd!;=@qW<Et(I;Qh2tF(dI0AYT9K60yzi!69pzlK%N^SAOrH{Z6@PvjhQ zmc#j(egaoYJHNcaqA3?MxF@gQ$+*qiTz~d||5+A-_=ek8zWkNp8Y{|w^d~;cD(4@M z!&%=%=KJuY-=OAg_8n!v^0rhTi-c)6y-j*p+V>((9+$)C_kx#4(x9lV`;Q7*<p&{? z_1d<{1+3be=k+|y*uwU3eZ{>nSukNee-xt=>5l_Dk?nhWId0>=r)0k~VziC1gFpEF z-(UEhU;D2!p>oe+E3F~U7K~q^EL5FVR_Z>PGjn&O^@hxb*GZaABUd=-WOM-T0K(2C zPC4@F@N%-64oBQNlYn#OunuSMg|X3)rh&c=t8GuwAg)17;h@HnYY@wMT1OZBN=Ik2 zA5xn%Ggmk}AhH8<-xu*qOF78Sy{lJifZH9;qfV@)`!q8vw2`g&EgpKq21CKCPV8K} zj+E7gFpfFWYF}FhEYNhq+#PdSL4mN!?IgpBBab$iHpZ4(IXlE<H);9ktg4R3y?l!Y z0EtV5Q)mTDS=OLI{=!e3+cgnW=Xsiqa@CCw0Gw3HyTMK&4j$w(4iw>ASg*B{IElTc z{N-sC0|t547EF`(hdG>0@B3uhK=@$8^Zk3`MoRNB(ASw9`L!z=lPa&$K_Aq(GSy%i zDpNTQOUIUH*<0ZhuezNKDYGWC@x8GuoxxjkL|BG8B9z-W;nam^ZA2Y)JC|o+EHmN7 zCI6ORcZlkUH7z#K^eaAP^o&x1+q~+_r^3dk;YHsLVyr(tF;;F@yvHfj>QGkB>tQ6Q zUmyGkSNys%nic6Q-2w(1gAeuXz(B`<{KuAniQ|R)?sN`+>QKJ0MQx<?T2HULQ@-MW z183^EgEVP1U0V))V9?{_)zG)8v99zsK^PDDNT*Vuqu-w1^{f7+tK7W|J(teadu!v+ zsd-EHWgETBI!@2iAOG~Q`K2G@qhoAe!t&lslvE!7PNKS<svnqSz;ri`rpq{-?@zDC z;p}SR4d~Unp?=AinV72dUfWPM<j0<_vai|s3+$(ReQMar7n;{^;lqKeuxkdba=CEd z2W$>ls3VlKwza~Blhwz!8K50MdWix4s$ugkR#$IY#VS?WF61c3HV<Z|nY?Ld0}r_z z1e4e8F>bL^;R?>aOP6V{*h6~Xf$hT__M^jjxOrljzI|a>&Bs6b>gG6}<(-3nCe$9< z9fNEf;Yb5r^`yY+DyQ%(&t~E`!K=}PKiBG2S&Mb+>d4_7$8+gj7@*Jt?V<<pZj%xF zB+)l6wVU9Aj}%+a6Nj^OJsK@xU{-bIi|S+)JV(l{m4CSQrvx)k)e~TY-}XV7iBJ8n z4B;c$EJ-v*n(af5hAVl{yN<Id+Qk(s=Y}ah$g*nt?vcZJ728y0A9rjS4MFoBuQFa7 z-aU<@mX)~&4m~~WKZK)}fj(@Y5Bp5}52#WX+&aSg!83!jweH7z`x<+XpFT6Z{I!>d zb*vtE^6A4oDB+by+M0VftXHy1#gFUV%Onas)X|igWsb~Fy0zaE$4}(dQqy<uWe;ao zu~<h8sXMtUotEQMoms!ZL;H4-*EG+<$H|kYhFyF13<sYohqE@Tqg));_4FN_)mO$L z<n_az_gs;SbM;MD$v95gvv)5JQuZBYiyCpL16Lqxv-Y*Nr7B4~u&s|RL+ALLM~6%7 zS!nyP4QKO~o!hWz_@wAoxRE*k5a+1AtNKjGLE@i^llBsOC%<*#1p5ze8J>RTnY4Sh zebs*oDczh3Um;Dqv~U}KuHPQM^{sEh*KHid`}4s-w+4}J>TqaR9kIWi^5dj#wS&W4 zdlb2=n|<~52K9R@ud?oCn-dsFf1^V_O#`6C6B9QcK6RV4?%ri=p!587Ryf1@aOlv1 zVcljPM)B5$Ov}C#INQpIB5&%&c>ban(oUZ^H(bU>@8i7L$%BYJ`=1=1-MD5rvT<Ge zXdrS}feQ<m>reX*Cgm|i=jy#~)4p(7dh~(63003rxJF8Dc}AI~(eRoJITCD}a!ERQ zg;B=HYFfi5E&nPHzr>Hy1SV;;ayNNM=dY=!09ySKSiL8cc&!uuK{w-qv=`DE^IO=g zf8cENL>~MjhqF1#F5{3SF>-+Ey&cZd;Rqt|(LXH;?KZMDnQLF%mJR!|UKk2=M6vAB z*ytlvpj2Z^WsowhJr^yfaYho1Y0-7fO`&N3rVDH(H$mRUN#rF?-lU>2i_mN09S0fV z`0}0)%DInC^MKX|I#X?hb3qB3%$&3j1NUBNCrNARNs}ex3#6bcy(M#M<u=Av=o+1Z zlR$@4c5!$R7l1lfY{y^c&Sk;LeowFK(lM#FDZw=f(`W%?{wmo9#AyN*cbz|RX=_C> zPT1fEKWAF*AgH_rWj_G6%7fnTF;;O4jr*)frO_YpWkz}IWgC7A-N-&BflX@3W*uKo zM9OJaThmtAmfDZ3Xmib}yVrS^cOyitmqk6O$Q4dvTU~EL^b#4DQNf4gVue*g`xU<H z#HfB<R2qd&NZS4fNX(Tm%9D#$cBBbcV<XxYuC?{pI5K7I%XlK=nAUfQFKsetTkB2~ z(vdgw1L38SfAj{vq5)pVCcp-Ni%(qR(fT*TgY+34&TWOW?VR;DI2)XH8S8+C<NwKd zoN$s?a_23vH_p+q$}@9<40cPT->1)ia{qHJO_+ikLvY`XD}0c@o!!dLZR$k*^2=Wv z{^BqGe0cNd8#rS(W-jLUB3$MCH-6}cxL2R@=HfiC!&~}WejJ-D4hkX%(lQ`h&c$Dk zt^O?ul{%8K;!1bp^oL!EBR-yoB`%4}_!)l1tE11L<4*^)tCf40!*AeQU7q!sTxT0F z=Uwjo>^Sc#+l}a0mTrF|%W}{+;{5a?Z`b|N|M^G5i!Xe1c!mWNuf6)(@ZbNB|HJSD zKltMC`Jeeb<G3eMhJ9Y2H<%k=od?Tti8{tf6IXxjaGp@cBQC3sb?bX?VB0&#kl*cK zz1BYT^Z6|j-_pw-;t=u;OzqHi!-aPGOM0zY4j+$}YB^XwSeWJN|AXaXnb^~QQ43w+ z{5${fAB>z&P5^tu?c{CJxzimpP8eOeX~XF2`ZqafEt0Rp*qMkYlPEfazTZ!0FHV>= zZgvL5Qo=QOu13p=@Ent8KX_&brsMSvUuIuLqvh+Tcj@?6@-#BdupJ6v$`vMbW=_J& z*{IWx2{ppXhx<)BNz#~f@H%+#I-Q||NMw&wjz|sJEitN4#f^NeBXBjZa@sfx6DM-V zqyA_pO^YsChw6PD)#<4pLpfDhIng@k?s)FTr0nCo;AkChGEe-dFJ**$=>SJVHL_LN zZH#M`G=pivi2g)JF26<BPDCBms^|<1h_G{TBCgI-fr-;89r@`!UGX~^g!gYU$cKlx zb&O_v26QBx<)4q?!H150@#+BS^4n<HF{_g}n#gB}jR9NnCAWN9hB{?^P0GC5vim|Q z&n;H=njVKL`{L?|?t>bL6fXGi+Ok(Sy+e~9JI*fIsI1UO94MS)AIKADCuenLFpv2S z!pgI{u#;5jI(y_#82QmIlqC%*x{i~$J8IFnjjj!;yhYpOb0C<(A@R!WK3F!u>dEqQ z!gL7-q913FhKG5qqxe3d=Zb=6zv4xAeTBWwwp-AbZ`*;cGj-7I<Tm9}g9mU61Fn&M zb6<8^@amujo9LzSVhwQunEHeK;_ZA!Z|a8&aVxV<rLI%?Fm(RS+wYB=j8`}6J~||y z4?Mg#bXg|LHnK_)edPM1pB&cwz-NZ_8+lT%(@n0>V|W85vQZC}KNDKo8&_#wxpHHe zzdOs88XI{XehaviuN=;y=b+w$@~e1sM4NV#4)ol)o5O`m_xR}G7PbSxxig0h+O9m` z!{KZ;2C<3oM$alA^}BQH`f&32W!lZzVZ+w#yvo0pEi#y_sUP&GV{(cwLT6yW{>_LH z8`9x?8#{6D-P7;z!8az?hmNp?1MS|ldpys-HB8^s;moRS<d{K@S-h3m$65YmhePN2 zinK}A&vJ6c5n*D2R?HveFj{$r-bx^U(E<6(`P|r+b#0x)m6BP3#C043;!$*{JE1jB z+!R4e2dC-nh`d}&shsV=s{?>kQ5<JXG%V8*j_^ws*u)~Rt?Gw}_MbSX2pn-Vh{H%@ z>(B2Gge1}OQP<!Q4@cqa=Z25IR9Y+bZcgFYn_WB1Y}qlaWp(q0J^OK<vW*TCwZbOv z_lC>tkLzoVM{)Qbdiuz4@X%AmNBE|U+9XK|krzfNuHf*&#eMo-S2%xzJ)GBMh4Vok zvTPXK!<kCTq!8O@WzT&lQRLEw$OWz_4n49`h5gG<9^<2d3=XaTyPseW=WX@cq}nLj zmK}$RQcvKi6iN{VUF2)#=h%AT?NjfvXE9qZ9DH(^afJ+hxqzkBl0oicKC~&(1@>`| z_TDWuUVr7a^yT}W<YS9CHD_rXQ>V!QN!|GwE3BrCm!G@n(DpUk%s}Pn>u<*4Z2z^5 z?KHOV!M=MaEc4LNYsA4<ZGbkV;Z+^KMqSc*{`RR;(ZN&Cxur&HOJxA@RYB^43RMvA zl>~kka2mVn+!fAlXZ9p|aCP&lxzdH>Bl|PocGB*>HXk=lpQWiYXHE|nC|6$x-pXq8 zy*S_n=<{hGT-i1j`Kmv#Krnyp`+t>Jh2MPrRh;uHho_%rPwjPcI0|&sYug|rq%Y!9 zdmfEnv@3*EFDKrtk1$TJyu*s|UBiw&PYfT~vJR&+E1YMmOyb-aVJ!YjBh}Y=EuXf1 zq3d;YSls3&+fvApHsYD9eo?o^G_D(h7Oz8g+%6eOI(hAVwRMAcg%}*x;T}?%n*N}h zTeC|d)T}GTkbOl$&|7~BrtfuLW#Iyiinn~IaiH;BIQqG^05Gn_lR5q5$l+`m^-?N) z{u=02!;@vFMk1T}wNH5tJ@J9Nu^c*$RM{>!CTn|MNDDh}1;xFg;=L-celK0Fz2&M_ zm_vyErT<xW-Btq?Sg#EIX2cwE=5I+V5Lvq3V+X0bz|h7PVy*$JzC$~!Hz?D;$gJ%z z2z59+9#Af+hObth+!ByQRN7GDJ8!0`LlPUmm2EOz7*PvT_)S#|L+9VL!e#8(o+_T- zp8o;*;4rHJ#NlLu_m02vw{a{$lXBFxa*X*Zgu?Z!I(IzUPxb}3zB1liK!?6Pk!>*q zC7*eF{_OipJ6uGV_u2P=<9@bF2zY6*(aT9b6{rUybK78gv~eE7cD*V~2lH$?Rl)8q z;{!T{M6Be^uBp3hQAhtWl?VQ1>%xnn>nU=OKe#~N;{!JN13;DXWF+~_+m#W_{)o-m z;4k^)xx*yVp9(#GjHhxLUullFtN-<W<Z#B$om*D_rCmv*WR!B{?=;j&vpvr$O#J+n z!@1$gc(bLWP;uyVEh&J;9%h)cIF9j+ttrOo8E>mM{(4Zy@}tJ$a84bp`|!o37OPV? z*ln}8sC>3Xxyrq{3_fJuzi)XC=duxbcW&(*srpJkEPC?fiQ&)w>`z(c{4x*Lx1|29 zW2>n{hYk&&``e#m?&)|Hg79>Y1rE-y)W35c=c|iC>p#Y|zcf{njIE{W);Q<Vdv)@t zV4hJQ^a$Ye>y|Hv<>R={!||W<z48&%qB{L5w-{#_?}~5pWECp+risgWU~C4R*srOR z^K8lS=l}Z8hbI^>9zJw9b6FQI{N``{=5U0q$bN`#=xo`#rQxbA1zlw2++JN8^xI_o z^9XrN{%eQxGL+OnQpc8KQ`9i+%G&nb4BDLAwz!ps*FNO1><t;OGbYuJmSguLz8aH{ zt|_A&AKJxo_5YzUI7yf`Ox0!&=P&+)UyZZH2G7u)EjBzlV05l2Tqc8bBsR1e=yDOK zkR1qd+Mf5qiCq{C!DDITXOk&>ca90u9Z@>fbRxNzPgaQ1GT*ta6NDAB6AtG-xyZl; zzMXf5A36XVeI3s_oE;Q9DV?PO%YL@X34b<-;gf-mokjR0A}d#!U@E(Or?CQF2dJ`j z8HIP!8NQ>pYT$f2XFfZkbmHhF&NSkTSLSr!<guev4^=4~m_o1J$Dq_D!T3zTJ<Ifx zAkNYsI)$DquAI<Sry$R+n#Qr&cyk3VsK{en$=S<dY{*qc#T&e~vb5|RbQ}6aU7pp; zqe7fR@S<Z~y0fg#)Ojo~;+J1n+MC{SMs@(~$mFHUpaw^#)kheCw`_u|I!!w_SH{Mv z41YRqyTjGJOXb(e_%y3Fn>gXYvI-4sKq)PEX$Lp=;ghqxq$FgXYxz~a&f`cIEnR*D z>NeB$r3~Wq+-<ApmFDQd4^Ew0RZZzqKZNZQc&~-CJX0oIi&I+GqdYi*&CtN^-BV0w zy!ZaWePnj!B%CBZ4gvM4%o$8EU{epkcHV1%QH{EC=Ky9hOzJ~^U8QcEp{IFgF8PVl zp{p&}4s=-M6V9@cu7^Qh;&6{FM0n;fKF(~eJD;O?aHtdG#jovTWoN4k(F^%T`~f4r z#7k71tZ-ia{HKPETh{Oj7=vOZp!`Wf_YQKkQR{?u!a-H`74)k(oLS_YEj4!R+zPA% zHuFeNxdDV;^r16@_RB32?y_I&xpREM`Qq(iEBV%MW(A-QXWK5Q=#)0N>Wcq_4B+nJ zaK3qcc<0m=_I91&<8qsEI<Fnpu46DSzZ?c9d=g!O!?|W^$OzweShaAS6$&Tcx&SvT zaX23w*0E3BG^>>tZk;ZN^Ucd6XY(qz)_`XZZA)|LvS>Xk@*1Ue!PU;=5F1o}qs*%! z$(czb@oAspbdGwk4bK(tUU}MzwowiNv~RhRUkk2sG*0`e{9Xf+xPCSwZKf~)1lBW5 zxR<jy`?eFwA8yC>S3E}LO#fHRw>Dn6q6vSAL%ixY<<o4j5)y3-EWm0LDv!DVs`aT@ zKY8hwS>?QP)3)s4yy*!Ys9T0ryuMg{qBeVXxaO7`r%vaifrp=Yb~wnE8uG4sF`d|* zx>lD(TWey_hCbcHc?Ip@Wmfe1(ZDsVWZ8R|@@G339nMn}!c<l`Baa0lkBW@~EHCSW z@j9H{d-=K!XWI5%dsyL&lhd{}<%}YF`&|!^kR8J*+d(rhTn^`R!<p0PhOKM?v6n3z z+>6@P)#JXA@@#yl&uX`nhW3&%gm(PxZ+<%uiVq$>oDXp7v{o6`ziBF>4?*46dNuN? zzdjzY{h6j*-hAy19@t&VLp)bFZ`!^sdpKK$m~BE|z3Q#HPCJB7bVj)y#|0eDXWn^x z*s^{5@bpKXg@5Ix9;Y12UehiGn}$+4jb7pDHV)@+eft~X@8Ds!I9c!84z&ot36}l9 zO>}PmG2?@IbmG3=sgM4G@(kOoT;OAnz73|s`3XLLXhQL9zf*7Ily$<0Y{0*I)qZcn z!)0VS`o?Q%|Bf7aI?nr*Odtbn1_D_sSe`j-$9p}!hXemuK1w+^$BJ>vb?eSu!wY;o z@CY9t>>mx3Zj{hyi(eeZ#csJu+uZn<U?gd@le^dnSB0;*6t+SG$j#)nxW{t%nA2@F zr0t2vz4^^uHuE-(l)!jRg`n}5W*nR0yMx%m!d;WE+Ps#>_BD9acRdL0^|WLr)e0j1 z9Omm})l2m~C97pFAGRq4*C9uD#8+7fAiwC>{!6}FUMd^eNN-5wtU~4K6(IeN$fAGC z$xu8*UhlB?q7xu4n;vX4I$E=ZhOkC9Sfeu%$;F6^x&v|&tVLFv3I@=aT-b^?`(})j zA5ucQ(}OMeQWxcLwvWN`<duaA^$^8#b+~0Gop=xxPJRtzJFffsRWDWNCu8fnaFty= z3}!K{f-4QH{?36{%I$rR>vf>htg`Ps_Sk+d9{U~IXtrGNMVD*jn4}Ty!iQXjZtRcx zKgFAmJm6k%ygI|%HtC3{SJ-p-AcK9choRapu@EdLACdw)s&2+ZK#0Y1oACaj_yUH^ z`mYU^V>d^;6Zyy+Qk<<;T~{kfTzQwd6yuK>-q4t0wR1+u)*TRb9p@oLV!#cZNFu)t zQI)^Civ;;C8xD73N}Rk^mSEt{dfKl|Z6Ro+-{Hpz!uLF*b_6*43dc4{r_b*X`0WGL zzx}FQ_!kK}9`eYy`l-$iSfLv6;Bzd_eQ@<L9B&=P$q2TTbAG^qP0X-wZ?@FH;q08P z&yPa7e!4)MYkXhrNtIofPX*M&KlGS7R@vmR+pK3{%%j73xgQPGMm&_sLQUVs{p~xq zSj=;M_~SqRSHoAo`meIxm2dhw*4fRQS^v?0`1iuZExyCxHi-7mj=j~d^K|FMi$l}5 za)Up*4?wk1rW(3Db@!e9YJtjR@cMx;83p0kf@gGR89BD|4Kp3Sj>U}^p9^vvXV`AK z8e0E@Z%@nf8WtA1(9Av~?J0Df&)s7D;vUdPj~*L7`r=2kRe}%E-#Yo$@Wn5EarpQr zKaRushgpoZD)7?N2Be?4A9YZ6<!fXQ4+yk4;`_njyqKf!@4Myb)iQXfEj>iEu?^Ql z81Y+{)(OuB%TxQ%X7phguMN2<PdM8&?Ii6+tJe=9_3)@>-@Q&f9O(Neb~*b0@VTu% zBX;nWFMVm@xBkojB8`KL>3B`UXXWMIl{c<tt^%+VAyOk?AX*=a!<aAtyH_i`L8FN? z2n5~GdRhSZDdz$BS_db*0|@UmAX&75?hYXvV%;B;4rjYLrn^9vmC)9apRR-sO-IjN zCd(s-Gx(iM`szk-k)^N5b$bn+>dI~-coUdRF6ro$*G|#S(hkMEaR?!UlUbiejvZmr zt<{+7Kv?<E`Q${>I1ej}`cpgR?an-<(13JIdd>kpbs=nUz(dz5k)sfOA!Fwk$y@%0 zhXgBQ^a;K=oWW$AhkT7_cG}Tw@hl-gB42oc56{YLJ}w`^S8?8%G)DmWwb4iijmgB3 zOQL#`KY24vTTt&^Z;9hxnj;&9sfRh7r4@OQL7X*M!oIcDOdd)v3N^E8O>9BC)82JV zd#$6vvX(Dtq-;qOhh^wt{;od=Hhq+RhleJyGPuQs_Rt-jBqhja$1PlR3f(B2G=uuO zkG%=&sx~`x^`mS_i%gZr4%d#qbgUDjWDX6l!R>%Z-MaF*nOEVtrF~1Y^j_r4{$P#y zCVJqk?D8TF<q6N+8|P|m@3mvkRR?M$FK+*0!{EsP!!v*8^^c3jLzSWOi$_`p%SN5| z`%Zf#FL1*2L!DY?I%2$@jPH1)9i4I(CV9|pcp@(HG?~L6d`x}xQ^WK#AHzYyYx%4$ zG!KAELb<>zgV64DGY@{{IBBl&(ZI78=Cjx7wjDT}$%cs~k0_j+C~9=1J~-~P`uYyr zVqCazW4L(v&ajyeg{{*e!?qZ(2@c@Y5ffi+B0diCfr^!<H-=j`uJX~1>%*-(*u|=K zY>hCN70%NTcXi?nHd8H)Z8%P0{<Iq~;VitFtq4w^aZ3*N-`&q1(5smguxIql!j)nA z*2Q6({a07<vBBAuJSfEBJPSWF%7Q>?D#Ql`Cu3RZth3p@oQW}1$rry!+oDBangFKd zQAcFL+!Z%A%rHIesqOwf60GaxBru($vM0{_=p<)tPCS-Vvp?yOA$Ho*ypFS(cqe3W zIENqLipA(kS;bd4%Z5@A7KZqhqsi-8eaCSnF7A_#&glrz8|T1^Qyq!eDD;SNOi$4# z<M3Eu3!JI-n}@aAb`KkMIB(w0mIfP0vtO*f^ad+x&%AR6hx75_;8V{G2M!-j9j$Uv z-e@TB;X_jLL>Z<}rmeZiO4zUc<zKNC%ckMrks~9AGnEPF0U1Chm)frvRc};e;lINw z>62_B(H+h^cJE;#wx#4zUUeh~!1p#k&R0th{`_c>`~03`TbXyyoaLi|yV)A#0IREA z8HZJA`_^&$kW?O+;J?Nh@`07m{$9I$b@;~DUe4h3$VWah%&uV~=n5NPZ3}cX&ro-L zI6X(-?pqIj4coqemNb9IUVkGG>>T87*}>ZatkjO<0~&eN8cD{=@J2qO)I?w66;W62 zyvz0=TdBuSp-=l5%RGHtWl?nm7|T(*G0q3&^VjG3visMN`z{}Xd@3u>SGSegj>qiB z`U+<!(PdBIXyX^(1~>!#i@b_xd*~{mU3>u1u}H=%F%Ee~_o;VqL0qp_+Nd9Dachy| z$KIqpST#KR>@%@FUxU^V!hghuZj*^@v5~5CHBLMB+R^M2zk!dS`XFJ;j-A8vTh<Rx zv(?GmY_%WSh4!H?%2w1%wOBpP`j<M`X$jv5C%0J$o+?jWCo(?`;DKv-R{th6OP$0; z`y(OiPV+<uLj(;q;=99HdlpghD~k?i;$(Cb-H<oEi$^#!RU2cORGxCO2ygwVkU9tr zYJbtnwRu(k<2sy+-<~%el>{1#r48vCp#bv5RcmPNmcnb`iwB|-v?ueFEL<i}(Ube4 zA&iH-3*K{c9bI}hkSMVhCN6tS$<Lj2UC5y0%5z2JsuB`g_hs|;DLTliZ!u1Xv-)&} zbLpq$AMx1kgIprAFXb_xiG)^_>(cn-2#D!2*6p_Pjnf;`!6W`oWvmDCH+Du`jrc5V z{q{i`rWcQ$q7>@kNy$|FaUEMNQpH12OCJ`yaX|z&&x2C-=i<zGgz;hq3AQhSlhM5C z-^<L??qtd&CoyCB0d8#evX+{Z%(<KR=|Z=tCAYz4zDb8OMICb+ol%fH&|HQ$QLSKQ zu3I@Ws~cu`lWckchcoq7PGZ;O@!YrDP_D7_**hcrSD3o>qF?r{e2nRFRZjg*I{mum z=WJAHOMfC>Jc+NkQQafXF|Pfn>3(3>cHjOp`&RdU!@PyO@KX<jcl44z&Uyh3uq2+J zoa0#L+Ig>iPk3;ft47b}tdB!h(D&+a9&f2Jb~u+kmp~)2FocYGH3&GdSrLDNylF57 z&f$?uW#~5R**|l*AnV{VKN?uW4C|zC_v$<aC&cgIaCX7eSHJo%hp+taU*UTfYx2zt z=YLzbZX15#7ygsb@dNL-_!fiTJjfgk9oVjn_?06?l2=dRu;lW$_;;N5=+I?-6lBpU zsMw^JEpqAoqi~JWl}YZIUsDE-M>2mz*37NBpXcGVqd*^&8*VdReEaQp7-zBnGb_V) z@7bL`<uu=&_y!++e)H(j;WMB8%<##VJ~`rVOz%6t`mi0&-#O>szd0vu>QP*3AF)+3 zIi7bMVVe;j4sC_TZn|-9qv2RsAI2JXLdc>z2&5gektPTmJj<#j$&#Pt)TuG_zol0w z$#!%(f!-m_$cit2>30_XmtX#+G|(1mcfdFavC+1$JbHs=!(k0~rLYq*^SEauT~my~ zLih0LgP}M48o^{RUY!3gdvEsSSCZZL-9qiyx5mEp0$`?xGs9U;4LOocjU|${UbHwI zLsIms{A|5hvPjE%u>Bv{BEu0D9j0lE6sZW!NR%Z~Va>=g#aX&%>u#XCfktEB3QH9V zRsMXwC-e9F0gY}HCfZ?9oUFRPdvE5+v*pR{+`M`F;Y3H{>hQ^nFitw{Bz(=;LHDG? z`SBIb^-(HmN~=4ZU6ojlIS^$l1##OU<dqL-*va@>hq5?{@~Mdi?CMY*(A{ws+0n23 zcx}EoO{pZRUB?<paad*&j1C>33OsTab8Ta4M{96$tj={1+R=1JrU11-O22x@0bHC` zz>X{9d#kYg$iMXM+*cSZ*g?ogXt#<iPM^qD$7W@$GO$cL&2o|zzESxD=aviFMfiqa z@pdPwysN{>Q253%@+jPxCR>;AApsi?dDRB&aC{P~(=_?XKC+SUimoZ&?#vgva@%n^ zV2Pbch|uX-j(rbcBh4=#0YhKYbBlQ;M~9<jp~F-;wQ<kVFWr_M>9`c1@TT=GJG%Zn zn=iVveo)2|lQ+wz<CKp1-J->Ej~!Ts@NQgID<g{ck<C}Y0?$VI=t%r=E+-H6(rhZu z3v^}18sM>o2(rkpZw#nwoz|{2?tE!mJ`tSZBaNlo{-j+yRGZc->LcauRsizbWt_t? zQ;waoS@qHP&lb+0Y|84rd_$PCM>)Ww8~E=!6xPtsotAN3f95s4=Pi9;3)%znDElO= zWvJ}N%ZG>hu)XSh<n4-9=Eiq^q#-WvJH7RnKQ*i$|0pYsSzXAAU(4CSv_n^4v9kd3 zN1Oq!*xF)caG-hp)_vNt&BIRikX0S9n{%~Y<k!}dtMrcHWCioh8~28rx0d;M+b$f& zJk{N-UeU3W9A<0&DN9ZKEf28ps^>%YSYEolg2S0MW>_Hq0v$E0qiq}Gq~i%Pt90xb zW^^EiI(CnK*QxgpXwNTSb%pd4+i^U{ibmcTnW3|vSsAuW-5a*7-{wPtI-9}Hc}}OZ zGWB{Ej5r1Dc*3g=XX{T185>ty=(qnV%Va#t4S(9B$Jp^p*<^CmCP=jN{0GLi+LbrG zZ%I5&Z_eT$;WAD*_-XLAkya`5diDrS@69Lc@{f#&nqdA)OGyxijdIv~#naK?JYh{m z(;Jh8)ezK~wq!izS2pOiHlkCNddg(o)#eY~M|5%fu(*5wu>HW1Vap!&F~b2(WzOW^ zx_p-}gF8@v?X@?C=iO3+70y0j6`}1+J{kzw*tT+UxT3gZLmt|W>o`bX{nocxLA_%* z`XaA3G6`5<Wtwv9aQ4H2{D<e*F!I<xc<3y?&no#h&z{Ye8upt9kJOeLWJyp*P2ik* zy|+zEdyO1!Lvi&IUp;4K?*4-ZhvP3k&#K;99anuaI)|>BFMU#;5|9^8Zl`to`pw}x zuY4yC=aU~fjf2z=6QK+0n-7WHp2i2$bF>xnv{`9G;34>}OYrd~D{gM{8s7r1{O-ir zyp0e4>8a3Kr*Ht5Oj@zD$wP=7F$`8}Gf>vye4W+Bt}K4>)X9{0`lLXs3i5%VVJSJ< z{Td(BxzAVM<8Vf|FP%P_c4UD)obwiq@*;!wYMF+SD5h{~<hEt+vcg(k)YqOpdxrgd z08t&pi3zCk2<w9!*>Nmkov=-jSGPwo|M|Dy&I7m8r*SyrgrAwI72}aRKP5#k7jZdO zs&;fWE1cb$W7p2btoYvHUYESRQ7fENG$lvVjd=VU>Bg}qA^17Nb%H%<<mWDqEa)1N z&QH6o$o!6Dyt25*p=0e-#wp_~GE@UXl<?&w4xu=l<x_h$hj_FZVX9p-ZqtY;dQXKa zx>K$!P9EfjM(-!=>q`=7kN8zH<ZHa>0~X6VHZdCaaBoOmA7`w{o)FuSXRI+Rc%cmr z!JAo=B7LJI4i$)5GN~`vN<?UFNt}_`O>Da|1vdF2CUyqRwAGfWC?PaO;nf=(Mif8E z9-+JvgM3Lpl9Lr!aD}VJY_{dVh7(ztMljk(Z*w|;_hQpd)whnfi~(T5dhm$DS-pf0 zD66-GP)}@&h`#0ay`jT`b|Sf(L+5RTx+Fs{1>7Bz#XDS!j?i)S{1scjy>9flj{EWW zo?iNx<i2PNufB_9>A@RQvlR_DDZjjt<Em!bTiz<9BTMCOrWKpAbmiH+s<_%P-?piH zc?kvZTda1M31%R8>T)Ea{d9fwxSp+<Mxy0kmU{8f)Q1Q0nI=ERtvtXc9CC3lf74v} zrWmtD9<u8=^T9v8dzk0!TS7Qjfo{mPr*Ik>yfQfKGCKDXoCpE$jJ5cVV_aV7xgm>F zo11DU#)yQiV;m<%<9eIyb)N&It#Q8S*f;e+Xyiy6WWMAMGV}F96Ia<@)t`*58s2qu z5gt%t<|k%Dv5Di_MJ@Ae4K~ZF;L(;E6qNR7>*1e4Z6+8WM`bC^F^62`7n)jT-O+!w zyt3;2!yw*nb2E%-o<DXv@m1;tQ~3i8>Yh*g3l+vut$ab`{Cb-4z#slU|9bfS-~Z>C zYv~koZn10U?%|hy=|5wx?5bSe+-7X;B9Yogqx#pPD`V0tS(Tt)d-g74#b`vh4-QYN z|4+(Ml8sYRt0y8KzaK+>&=qg>@&@P%ZvyzHo4Vh__dE21+*!KAT>9a#1*d!FyQHOU z<@}9req*?C<Hqp$&wnoCnd@vv`1P-UefVF0<2Q!C_MiW?;p0F4@nQQ8_KKe1?}ND5 zNZOAa&KuFvv%x$|@o1;cN1b~wE!79couj+&cfKJ;J7GQYA<lK)GIS2_3ipMD+A>tm z`dr;>$H8U$z11-G>B0K-qwo|Bprnmz)jmTzm~w^l|NdY7jdUm$PTxy*T#3t}Q=LI| z9=#AnkiBeabnme$RT$HB9O}%~spa4?am1V69aA=3I)HR?`NYeCoW^4ZWSTfU8}DHw zG|NOrXOg1~w|sICK1;(*Wb(R)v!Oa!4D*3bZ&bpBDZF9K)!@~~+{B;3BrrC1u57J6 zgv;6Imr?<VEPX;Np2<+oL}?mJw*+sAYd}Wpd^0_rw`V%;baLoTc;)lH^rTZxc}oxV zdaN)`5*_7$5ZFerQBfCt2vt!lz=lS{YXvr&a_B4-pH4t^t`6*cBcoaeP*`ba)hD{o zicQj##Ys-KI&nZ1{Yo>874gxpapNEzY4jEIt~m2hr`m!m%`;&hXDQuy-*}Qt><@WU zcI0({q5R<+P*<brNO3TrLsnjGq}&f$-K&e>16B^#*{gEZ0grlsk2p!dE3du0QAh4$ zv%sh~>Gg8ai4we_&j6FN=?3}CHTTkpPKlqi6XBFW-6)^-Zg%rYE4<^xRQJ}QIFEsq zzQn40#a}$vLj&t85|UmkbI`wb1^yb8`Kr@gaQk}nA`Xjr_9fIQ>H`te#2e>2JcLK; zrIWKb;o!sI;K|U$4Q?M!xH`~wK>7;~9>Jvz=XDosOF6w)K2)9Z(m@%1iKzH$KYBTY zP-s=%^*;8{^yIze-Q%!~;I$LWLoM*Sf?j**c4s~4@aC7U`h7eYC!99mvHapkho!y8 z@{ug}Ep?@^lTwsJIznf}O?g=UAe&}jsl7YUTH>Q$Gw5v_TN7jtUBqUn3QrEaov@Hy zg{qhoA$s6q={B#i-(n@r91cG^*~P6oB9Mi_`x?&R42Gjj^bWkauvUJhi=%3pwt8g~ z4(BbDH;#6lzAh7DPvF&cx7nfGkxko|t~Q#jPidpB-MGbr3+m72o#+@_o#*wqg{fhD zc#GKp06+jqL_t*N!rHKBab;i#jnnx74rc}daX44mRXuRXjvkbaV=610(J?Zr8%Tv) z%OtcDGmcC7lNLB(Fg@Y4^Bg|%<eC`Ls0YP<?6@X1=CN*=54<@yI3^Im)zU|Gh)yPX zq(z!E%i&zK!@Fgq&B~el1P6E{m3^2GIZRhdk8xN9p)0a0so?=vIfcqG6FK-P`Kvv% zuks=98s)a?Ue2>T@Yu$-8mw~Oy!XJcz_uDZ0SRB$`#X18;mm%$ufKi<C+$i0{H+zv z+Sw`(jThXCfill(qp%0pF`sheKg3>dv6A)7Yp*d8+&b((a)bx6e$b7FHP}aYI4eqT z<Lyth9sATcoY@Eb%$YOgaOQ#3;iE@c-OJv`mRW?fEYKmL+R9v}-LgLU(WaXWFt4%7 z`CV4N?87;F?D-S<%DEF%%OcjIu4v=L<zKaR*f8~fg@>EB*#g2XF?3X)c#%Da8MtOk z4fwT9wBG4-_InSr?E#<V6Nei(-KSay>k@lG`<m>wT{~Fyy#sywz*rWvLI1qwY#bpI zY7K}49p|pj@IyMg(Sdv@bJY`}$pl>Rcm_}1ljNlnRUFQ*y!s0I*5Q1Lj}PwRZ3ic{ zytWEZ+9}3I=C$22P6n0D;F#l`^XJ$a<Qio^Gwj9j?MGMACqdr2q&%`;eTKs<AJ)lF z=|de{yXMv)7qEwg;iZ!=rq8g<GZ~ITLau%yV_k~VheWpjXI_6R4*Wgr+q?@tw(r_A ze01j)_HgFg1M}FC{7|oYD711`A^j_t*0wZdTnnw^r|VALjxm%BO6OvPCk3%jrsy!M zT3xZ(GKI@(y(TcAHx-opX%{B&m<CVPUYJKH+Xfx2Ryae+Rs2FgWg8n@q%}UQyGcuV z$_03mwOgNgr3Wv9dPRLq+tO%=_sIc7((MO8kyr96KS!OYnZYIpf_EKhKO_3~O9?>1 zgCBAY4tXO!dC06y6!(qyB(}Wf5n39JuQ;%|uV79BaGsM3xXNAaud-Vod!3AvNn8f< zjq6{JQYQF9mYk_G+N;<012nwJ;|gagQ8LNf*i@_K57UJ*dE4dto?^2t)%K`@8ZOx) zU*tq)=oLr@^jun;jGvUPQaj$#Cul}t@_H1>MQk7ujm8MDm!oR5-?EIIr_ugQFOZKu zfNLG}u4tx_ak!z%b6^rFGg(k~g}vg~-WC~cuZS0bAiOZ<H?2h{t+Qmh<J9*A;&kkq zw}*Z`!Y5A5*L{UkgUr(sZNeGC(Qj(6VBlEfRW5mQy^YmTP%SRJ@sriUj-MSHK3o|# zJzzhzjJtf`o{m;%<kQ}~B80zOc}IMewb$Y{2wUg6h+X$A4Zhn_KZ`vy8r)cB<*9k6 zZHw~?$E_ZYX><0T%&FU<4-)ZEXtE0=>5jkZ@S$~yL49fb*zffD_~-$SI1?{2^3Wg6 zxx$(8txo5@FehyyAi)_(;VZZhW;CCQP!%5;0%rYo-c#C(3{)<074LODhr{{Uv6B_s z@)f2I>0Rf5D=wX9I_B_g>a@!ks`KR^{NQ`Tzxu!bRrYh<vSmx=96qT3D}Uub8Fujf zmT49ZsArwdKD>5}QDfhZzvLU&dTCdjWnHa{_3h~)(si^?0iOh`>lVZ5@%yKsYRT9f zoe-sro-FINIGA-bJ5O}Ml8Y!Fu*HbFupHkxe_^=7H#^)W>?14;xWoAIl~=wUC$x(v ze(|sVVm_9v|7fB(Hpb2eK>f(!`~k}OA(NW*Y$&(wgT5OJ)jDIHcdqVuw&v(V7SFxI z2hjaUwqsuHM_+~Mwol@)erxm2L((U4zma;<nS2)5p65^886`QE*hsMMYX@;S|K{KP zFH^96UtP*99ZU+2&O;}h1(}0;fN3miHM9+`g9Imz-N9@Ftb?ZpXMl5WsQiV;`%H=& zo*0_O#$gb@#@0J8Cmb_=)QWfq-8!6|bl2;ft_;>etD(xCO5kHxyxNl2g3=K<3}Udr zDknoWst3%DPU9?Ix`P#m5tCSrSUft-><HvXc_%~fz@klm)YD^ypgxsLN0yy>Um0Ea z<h}S#<p77Ybn=PLC!^9(w{}jFPY0)n6G7chhQ}Sw(k-1<rIe=k#gp=)*GEw#E)!*N zr!qHPNZ*G9IuOU@Q-h639%_;}M%wSytJlg{E9sg&!B1cL-SIeJFccQcpd9*{xR7QC zZ^Pn!^a-qvPWiU5?7Vy^;-p)9RH<=-G>qn5rT4b84^GNyWb4S?ue*I%{+5rj8@gjv zKI7;_h8jFM_{8FX&4iz`{N*0qdo3TMz`cW72Up!0tet3^=J&vQ$XDfOdAizP{<Mi& z=>%`^VVS1xl2?bj4prey(>BY7YVf68Ht5=ydp&Pra@g%%{;UV)vlEaP2l1AO{CC?I zr+7S429#~|7J9{#`jQWI<3pWZUh2&U1cpve`_dUFU(z<H+sV-7F;2SPE4SyWw~a@6 zQeuT}L73joh`%55XuBnB^w((je5T2p^t@g@{juTp?j!8sx@XwT>)-RtI2?HDJOBj7 zEOT^$J|yo)$DDlB-efnRGo9DzHnYmokB??1gpSp4zIJUc4Bs+GFdR*+(7b(TxWNX{ z4<9bj*>1r>vlYGiz)HIXha*vNxWdNlIwh%9pnky0>gBACzIuZ_p!e+_cI+fCj^Ryu zY1kuleUlGLgsn1$WF~p8;IW=wzI=JObDvc_3wzlAnU5ZB#pyi5zWP&lhxxS|!yFFl zdA7;G?bTK}V;6XfV$bM7hw~<Ms?$09IO}L3q+X~eWo(CnTjz6c8Ii|pBRyFM>!>t- ziO(+}ed4BrtR8&Y-qb@9^NFLu1Xs}!Mx5eTkNJ3@bSRP>%>i9-VVp9v?a=-jkHDIL z9i19a3&cUXJdtHG*w#r8z!4s8BKiQ{0!*IZtK8G{flgGcmrmr@n7PyP3{yOS*tBIA z+iUEk)7UyZbN~;(_KU0R-|fdWZm^xiwjI0JPQ_LAZiPc1$6?*>PI>EP_U=`FbhpC3 z;Fg&msk_Q{7Bkett*pxTLGLUyY{4EfnXqN?!G-zrV23>F#QJR;q=o5Z&2~w&D_i); z-6GCj^%s4q3-w#dE1hV{;D{E{(Gsg*@7!Kub?-go*uhHsU9=Ol9pJESNgHGP3*S{9 z^&nH-Kg3Dv9?r{m?;*z(VCQgnKbQTd-9J<bq7!-J&4WecoWqIi1JKfqrI-qp?L~Yj z=Le1Z3TfXcT8+HgLmjOMQ@pWVB7ErNzQ?YRUgk}zZ9BIQ&+*~G-X2z)I>s?+3)+rW z;l~eG*w6jVvu6`=^aNX}@F2kbtPRRz->y6Y*uI%h+|p6uwr>~Sd58U^Z=`K?dz0sI z_By^2HhQOg%`;x%4DHyr5L3e~wrX(?=xbLlXNB{L=lN(QlK}hMs`CX`vYW;G3fcaK za<Wf;gDo}g+`c*N-?sw?{63ucdsyAP5Qp=E%_7-GI64AxX)6SIMPrqsJ=GO4+8|`} zGp1e1EpN|9<f9PY3DdBlhklv-4LBk-5bZ1kp%*S1OeI?ut#L?g;5O<001+94tW3(& zTEI$|zG>mZcC*^4?7N>l+6>W^l3#Ile$4wMhjZ~JzoX3UTHQ&bAc7nM+GDu1P|VYa zI^<5g41~AJ@3jvs3k~@#A7yCdOi%eFTca60k;xFaPKW#=3NopwlODV`Q0jtv*?Dhp z=|>y?#Vb%9hRf7%vn6v-CAs%KZbxHVsZKIZ9qr*<+eAoG{yIwUi<9Cl^AavQr<MNR z-;vIf8)oW1caP_djS$(2Aux|pXu^yE#xgff9_82MN2!eO#8vnzuBC7qwNv&<9DZCl zTV`bICmqfnl$T>-ZKs=nmmHS1*zB9Tg1k;&ZIm=jBRo-*V(Ssz3qA?kSbxN7Ch-YN zQyCogMXsuruJ#Z-+?byD8oH!+U-ShT<e6ctlQN#*MP23rHks@T*Rh|e2lpVv;)REd zgBdH?PL1k+lhJZb*~%agxt5vS<wTx3S6cDe6(CJRFU$9yD{ucb-G0-4!S;0IaOS!@ zoWs9xwkw3-gv^K*a+o)`z>~RM;3`h`3%|};>A6Uv=3D&?HkA4P4rj*)s@G#uL-t$! zVQFl!#7EDKPYN(Scr%FPwOqx;Phr(BFh3kWa*9|(QghYQ6W1Du@-y`Or6+YW!?$*{ z=?lC;^v!Sm(eSmeeJvj}Q}#vP0Q$3k_DjQ29=LDep}l&z&$b%1$Fqw^C~IWw>{n~s z@7me1av&XjIkx=pf?87QQD`@#*vIcjfbV~yv)S!UoeN}KLR*mio6)0wgax;>WNh{j z2eb}n7e9UFD_>#%=F8dU>kB{mh2ip*OT$;c`qkm$rHjMQ{Or#RpJUbYmaSXL79U~w z{rT8P%8wk*8`09U!8}Xx=(lmas-1Kni}l9fcve4!tKyxD`Y}#FK-u>V*Klo%s*Rz> za-TVvV-DiSwd(2of0%XZ>D2ysLZtoQ5bLFT?VwgT<8XEYYk}HWd$!PPBI-(59nRHo zS0}?n4tR~iPDtmF9~d%UpZN9FjW)oU=zup3sf{UzMlnfGx=!qLc6psnBf<#pg-xET z6m<xd!`atpeC5W$Oq_|l67EDND+ZCyy_7Psp|O*m0<Y1aIq7mcflT<}U0Dq}e5ECv zvUzyZ9dO0dW2Pv){DM<?l&#|vr?^bh8RqI>`OqO&GM2v6*$PbFj=eiaUGWNV%EHdp zPE~w%?32NcYcf3UaL%MmJeCy`Rx6?o2OSdX-KRvwf9XR#Sne65gSeMn1{+;w@Fm`= z41M)C87j{>#(U+~M%06RFiwk}yDdm}GKf*R<zE@io7aBfU)$@tRwq?HmOFzu2e;%i zZ<RHT7Pzx=UOhlxT9)wxmQiR+;xN7nL7L;E^DS?2{5M%GyYA@JDO$4WyeK)vagW!@ z#jA{!zpi6niSfsJhd#N|h9e8-IFGTN$Vqv@5s;NW&#NR}8y8;Dk7XHK!_JMDCmqRN z>$Hv&mquMZq^{E8YnRF{KWo{;xzz`BXuLuC%8(U_6pHb^%uJKter#f}-mlFoZ+(Tl z*Ye=G6s?T)27vacliktU3NqV<2q!LIr<n}Kr>uz7`Kw(jpK*3n)#enR<`=%(N;zIC zuC@lMeEp*XRS(L6JxNnMhA!L8Cq6wa?cw8R2M*u>V_O3r4%G+o(1*_EETuv7=m$;4 z;q0W<0oBEeSCHFR&E|(4yVxEBM@_tUal+bWY7qnmWwpAJOI}I4&1>v8Z!QgYmv|!p z$Jl{GyKywx9;457obpkt_E%-dV<!Hvx3!gQ7j*UN((um3JHx@l2XMHtQaK9*Xy?|k z|7rGA#!+3bFqf>Zrks+0j(0D<Gu*zzb~p3vTf1wKgAWJ7;wC?qv%+cwCQ$Pn3+o)L zbaq<}9p`Bml*hh6XT0{(<W$H|@`p0&6P9itz1&j&O-HQ6S)Ms)18f_d?2P`b6PB+J zE}TT^P_6Q}4I!KJkm!orx;I^X@Rk`S`E%Lfi8gPXqF#$cd*HAxI9ZdA;!k0$H?~Q2 zR!Xz*pCCl7?&X5Q4xF%FC$C`2LCB9ev~^b1*;e_0Fb1Q8)z_49-p+3urr2s_iq%0= zY!kEwKG+%_+|^!|h8wI%-MW1z2disnM|C#)R>=ca#j2y!b>#^M$PdGAv%)AZ4(BUu zXQ9J+3;Q^yuJ`~3CHd;Vb1?hoY8T9_F6wYqt!<jGM0SVsW(JD$tcukErDE(qGT0m` zC<sZyW|Wlter(T=Zr*20n(a88ce3xWA2sxON!l_WYSD&;uJp+l=QkIAbl4R%E9AWi zA2alKyV*u!6AyZH&^jrSM|s`Kq|knMme*pl3LQDD^V#lzYgbu2VREqR9?*U?aT)yy z>xYe%DQylMkS#$u)R3>wD#vZ)u$|WNzUw)*<Nz>wkG*(n#(orz{%gOvjKkTLKEfS1 zd?*jBGU>L@wp`$$>QLblo!GR&7!+r>^>7O@+bvgKZ9^WDLzSORtV+y&tMZPH3#X+a z1Y2sbLfcnfZ?n&$E1ZuUfe+5vS6g|g7us@2l0_Tux=Ee2&Y-h5UwdP?w{&Ybuzy#! z)Y!&r#~)#j`H%2G?9n}(A=`rjl`zCqoi<6Dp%*y#21ags7+(XGiM#cvP>s`!k#{FL zmK#BbSr<f%@qXFHlh!~&DKP$c*v=&a_<HEuZ%MSs>qo@=k6^{0P&iC1Cv7YQKJ42K z+=qc6Dtx1S%H&uEn+&i#tAFL{_@yZGa;_kNgb&l{@A*sK^g)%U>o@ip+H&!Dusk@# zEk5Z7FK6q!p@iq6U=t^h`QW+sylt`CQm2x7ByQ;z&p}?GiM1_yG&J6uuFU&5*J`3c zB`GjOc<vuV%i;^_Y#(>7>r}-qrg#8Y<-l$DFA5<Otc{|I2y?}MrT5>?^kiPuVLZHX zN}KX%a`Y^QsI#Mb>>SA&K&Yfp1uA5t+m^4l8y%vP9G5~_YS)<k&^m37y3o$o(960y z@r?7(mC=fk=h`w5SsJmr4JX3T9B2YzjiJ&gbotC~pu0$TocD@-^f!6@X-Bu34%Kmb zPge&Ijx8zoGT(p|OXG6mIeW^3Pg&51qM42#=*Ip?4iQ8y`#6_u(-+0zyn2t}mU}+a z_l}NHZfZ}bCvxK7N7%{o3QR!BE2<V!ADdz)<4x}Oj-BHKhFRO?TC8QCMmvBqs$Uge z&OA$~&T^XgUO!Rfy7K_xlmu80=T455xIw?pYiwgk8{r3`4(DvC!Nbe;Au!t=3sB0j zJ{ch71QEyVlk=wPKgmIV96o`qIDln}kZ)9Yk$dB(GB-bV__VQv2ADI~o!BVNh;~r7 z<CurT`8@bt=K=rq;k(~?b@;8{{;hoQ&P74a{XhO=pBO&*<3B#^=E17^@Z*7gIM4-j zdBCggLqiTa4I?_OmYDXBy4P<%gmafzRHHVxZpQbMKpUdj#*xg2+zQV5=q(mMxUgXX z|BVmf9amF=yurCNeD}NG8-D%Qe|@-g`4W!#Bg0R9@u!%3yqnd{yI5rK*Z=x|5ofb@ z_4pgn8)E0FK+i1TQ!)NY26!fIV$9ZMx5-$-v22~y&*6C6`TZ>xYIykJ$?e<ua5?jl z_#rZnu$^_jSM7~?lg2si*)!CX53^4FyIS_WP2Z4ww2#_B9L|5Aj|OHSNki9HI@*C4 z=nLZH^u8wRtrH=^327Q}3e>@Z*G~LAvTD-78GkmSzWNXb>2y6i*#g{5X~=XE8E>a2 z9u34vNf~PZVTL9tPT+Dl%Zab0JJ1oIAAE3v87Bvh4qq3xQ_}&Ntss;KWAurLuaQd2 zPO7i4EV{K4xUXhZ2a^uxas(S&!9l2#DB*S3Y2YPThwxmwt4_T1Dy`l@_Q_#nc2I)s z;!z(uG&6bU8Z_ZO+bY;;PlP_;?NN_AoPE_+nxe6c<yQxvPZS*}<OwT!kzNfv%DLN} z&c$0*<Xk)GfLHnKa@!zG1|3b0@>TXCyycbE=E$nEJN74Yj|K5dFFe7U9d_UE+5u2j znvl=@%4g8_q|x;kT@vqEdDLTfdb%2Gg*`EKNC{ss<$U(O23eKneU~*fu=D5?K9pS> z_TElVhlRY#yQ>T3zvnd$z|^ZS+<t`d5Qne^aVeGeel$>9us-Ff9`r3oxXVgw%T?TQ z-bjOBV=W)9#J+d`UcsSz%SLCX4={Y_;Hyj4#D~j8FPZtV{IpX`Mj63wgAiS*4|&!3 zl=2B}9#DaYB=qc0*{nQ`0s{4cXVt^vTitue`7+LC^Cu43ZBr&gw+Y#?&I{Mu9CfA4 z@-}%`SJjcQ#w$<C7&@LUKl7R<{`c53x=_~%z|Vd9v%{_3e5{RCdE0Tq>42hTBEJ&Y zE^wlu)rKs?8S`_!%&YwuFS^>(Ejp%$=l0{U<^zBkKeCRURxtS~Z1@00G>R;&9=?b3 z@TMyZukfbC+?L_Uv3)r1bhwcPhjS*VSz!%L<Nyjs8Eq{N=lkTneC77=*0~$Qk>kgP zef#$^;FBzw*}Hpv6I&3u;+YAguPB<|l?Nzon8Ie>x$xF->-IeyY|pVmdK>%C;v{#V z$i!)8^~NyE#|h_F?+y!0q8K9JaHgGMW|nrqwprU9Ih+-&^a7cLK4I}}*{f==W7FK1 zlghI?m9*EikNLA?v`&AuKao-z8Gul)g2(>Fenq@M7KxnWOpd<AVP1~T29uUf)AES( z+WbOMrqMHWs+}fZqb>br1fgMu%2o9yd?+~zNIQvLhIFUj&T=Cj>!%MNbUwL{dT_JC zd1{SzXNK3$7IzGb&mG9N8e7<Bd!CifI;iikviS1Fi<JBM;n0y|Ioys#6j_mvpq7yj zd+ZBSFQAdWl+`*9SQUJem8@^Pb_NIQA}ewa;PB;P1?~1ab!ci9-mn*)t(KK#VjCsS zv>mizK4dxf_S?f<9HleV&3!zi*+HFgf~#_XM965g<cfU7U)m1v-aw9Pe7x{74{M%d z`-h|0@H9_MbQqggJ;mWuisp_09?RN3{2tC#KN@)X;-&O=2M-<2mKt-kkv^nOAptwj z*g)RRXW81fq-_r#zLI|St>D_hL#72*+30kB2n)i;xKhf^PBm2SZ66~CwsDm$HEyz6 z+xBQ14(Hu_aX5F|@C+VdJ(pdM>wxGUuoB2sQCE58RNL9hN^NaV8=t06H&_n6kIS1f z)U~P$v<3Xxp5Em(RrTUZEAQ2xeX@1Vb~z8aC`a2c$0&}yY_GBc9=kIC5{~m_-dNd! zT^u;LZ&<@#*4)oJ<&SLwA15<9Og`vnS5@4~w>DgO<1AZ*+$R5Swg%zt2_Bk!V&C@R z<=s5Q^P_=Xw<;+iCEcz$sds{973Ws;FWc&#vp-(uLby?uQJg3$xdCxkue%oxdNHw7 z5Wz&SxmTwT(NlOCvDq&gaKCNYa{`yyx@c?ZJ5Y}{AOPo_LX)eUA=q%GJqUXFEjpDX zjQxnVWPFv0Kxu0NDx@%SkCLTClxWu27AbZZWTqR-5qsd2TYoC3dwKOQ!E25Y|1G~c zgb}>*6u7^=?%IN57%ib_1Qr}g6Ymp3vD)A#VB)M79^RE>oV&pW7qN9KU}E}@tfVfY zPv;TV@mk@`1OM20TZV7WF87GaB(7>x)Ijvt2*_$vUndz39$66$n%H-YqJyd9x}L;m zOpou7!JnT==_+$WAzR6pa_bq}x$=wH{K{dwU|(c?-;9IVg)y`}v<q|tIGuqZllcs? z9oE~u@jWf+jdtm}_^|Ekq2@|;XKdO>&ts4dIyy_Lk%O<g>NI<NVA_r3Tzn!AG>bWl zK0JvFhZ)To->zWH%Q<}}XRAbKqn|T9>qN+F9h6sb>0Hx>+-hpd{*!NPc+5Ot&r<6w z<23-J$l;Y|%i6e3!4$${w_PE<?s>Ka>1CSxCn(MMJT!-K>Bw99a`-H#FmW)S{3#dt znLJ>{eB$=7ziam$PIgE01k!ZSN<(<hE^bI(lswA=&^fo%U~Vy;d6o87a)gG+n()?( z^eL@y9eW6Cy!CO?j(Xdt4GXUNw99H=YK8N$!y8-S+;T@waXIcW&JTzy`&~Zr{e$m+ zZ}`<;`_<t&w$55u<Y6ohS3ey1r7!)5ywP(Yb1xZCrKZ_eXRM%j1SICy!@zm6vq+yr z9jwF;<yT94Qcz#@U*{*myl)&lyXD}0wm5aXv3X%j=Aq6r9<Dr$^Z7Zx+c1Lz`qfvz zGyLlR_^ZSBzyJM|so$w_Y_r7p;AejB&ksNMAN|~L1Shn99fL*vVTPJFYz$+!nT<jJ z$%T49n|hK)v@;i{El`K9T)9S_nBif~cAJyo?AbSmxA^e5^OG-r@r#r_wZn?j2zXs> zR<)DX^^83MNc-{(HRZ#sQ%{of-{!b+`}!0vQIfsOh5~JX#WeNRfB3uWzx}s=C5{#+ z5IO>NM8ydRgcA`b>D5u_Ou-33qhTkM2A$b}XB+(7bM4uQi+Q~6&g5<&(&%YDpA%pi zQrH+rJC_03dC|c$;nBL%fpVT^za_7$LneilMs_f>bXc2lL@&Ft6h56q`|7Q)yh<a3 zd5qS!%BPX4%%`0mHe~XogU;97^ZLIsnUnu@K1W~j_m$tSI%X1vp6rkVgrV!$b~0dv z$*Vq&!r)C>4|w%_GU((|&#wMbH?A^tFe5HknY+?c7<Hh2^1&!b={Pey$v{?JU5UK> zGnlb+$KeTIv+(08uvN}(tylVGAcc%_SLLh&f_yV&3yvUHa6C;jptO@vH<69}@);)` z8B(tBD^BAaoGFV!hezPml@Zd(eoZ60(SE=OkER(cZ{uuWY9dT$&cs&S1{)aDEMxVT zSGVPZflPD<p6)<5k7cCn@+YsI&nb29wi3jN$ERl6t$gGaO3J}~VJ(2Z(pI{$ZJZ~r z66|`54#+3(#w+(-?9f%tuCxwrc#J(YJt&J#4QX|r<X2ej1<DET<E*SUq~i9&f#q<< zfsXCSqRtm}n1&V^;;<FBx}e^!b7<4b>HbH`B%aNz>J$HcUZK}sHJ^;SIcGJcbpmcE zRnn>fmxelzLmS@1ALp#fSHjMC<G-KM9YD7nbP`fV;W_L?s5?3_)J4j*>DNg^29us~ zx|ma&RmZkjhQgN1=tdqatE^6HusTirFqj_^Gdw^iGYp8d53%;w=#|GHeh)t+>RG{* zd*L&m8E)+0BW<i2%`5)A9zRVRvWX)Td6j6pVwrL2lY9`ckNg81XE$)zP~Vw+=zQC@ zeOua}sZGFUbuwDwKPx8Va2C}vdobV0Du9a@e5kTG967Nc$0Fr2YfET(A}|BrtZ;_U zxc{N=3g?HbeE1KC^Vv7A5BqQ$y29DlL1)=#ae9+0V(*aMx`+K>f2jiu2wjmpO+#|| z@_Dx8;G?P!a5m#`e(u0#?1A=;eF<kD+!|(9?r`Sg4iA?2fX?zT$13L;9nNi)bDYiK znT9`G8yY6nOYoW#bR4MLXj!i6%A@pO4zujFPP7i-I&^Syv_JE$p#ukw=_eYT4gwv; zsRuzT-cZh2TZ?l~+AV+SQWn5vaY&c)s@2lrFnmW($=Bk5SBL#5e2Qs${b`p;_ku$l z6g+Xz;!@twT+&jX1LFgal1m4t={Z>8JWzh?v+S#k!+FcTL&J6^GmGwnNFTX$>n5*v zUSLnb*Vy;?rQyU2FJ<y$n_oJ&JU~GmM-9=d+!>iZk?kXNIDhxm@8Y1{G8{a1Y}m!B zeD`IyjabKC-IvvN$+D`kf!X0s60|+bIGoR)Kc99`hx6Y3`-UB?Qg-k0NFCWrZbXL} zGJ-RcRuu09_!=v6bvR$Sd=2|O$R2*jYc(zQr41-UKfn|nM%zvAZpCqnj|TeDKR;4) z^7JVtw7iw#b~ezGq#B*09k6|n|FluywLQ+{mA?4wYj5!I<{p#C=lF=?wrs1xumD*2 zrR%8@)}9;#fEvVoFzopf4sV^#?qRrV&rUv|cu<KeSnx{0sqDU=m4}1!@dJ#mF22AD zXWJ|t?~bt|fLKDbCimuvZBaiQpY%3YJnGYaY0H+aY5y%x>y(O9cK?eN>jdR0Q;9HP z6Wf9;vAUTLiLS8!KYHA|m%YQ$Q}NMkl`MH!V^+gNxu)L2)74Ap0vx+{<GiOIn&yLI zUp#eu_`(ZEc_2o)pj+wl%Ms2*#9<&VX{2Z`^2fhrU^`fW2;?>1pn4`l%ifb)5<q^8 zRXhnb=8$^DG$gqZRv?I|*wlaH8cetm5bijMBPsl3U);t(WCWmcH9Adh>sH6-curg) zYM<gAv_|B-H$A*m+36e%)xeE)M{5>(wj-T#@Y>r$TNLgsTQ&q@_{g;=(tdY`hr*PM zq!5aJ+Vk9-!8%2VhhA8MxVyfZ9#m3|r3Ektuw6JA^8T?Puf?N!lXk(xCVJlJ!2Dw9 zTCQ`^=z8gKMMQOr-?7&kZ&dV$K*LlyoNI-1!v|c-u~7;Cjomu68`AqL`LY^58_&rz z$}fD^|D$|`=Z@~Nq|(6{lltp2cin^pKc$fd8+^(T>;dVhW2>&z*XEGDoXj|lSe;p0 zW&kN2)M$~8=z*o74H1i@7fI(K^Z-)VX)h-8aNSErcwy~}MH-cL29wB7yU!T5)9Pno z2<iKBZoF~rp3OdAmj}9=&<HJvxroWNDs)|p<DJJ?CSrnIV=iXg`2t5zm!DKc`6k{z zpm;~maXv$gIm<L-r);ya=9U{cp(7lZ(VmFGS*KhVy@rbz^<C*)kvDe88Iq(`Mo}6+ zwoy@e-^M>MSl9IHUUS6Z49~eA<#n7DWTcC`a74DiQde4f(JL;*)%QAfF5>vs^o+k4 z_j7|?;c#Z05r;E-8`mDry`3XnS@Iu=qvy<p?I;Mgm1Se#4n6s^yo@iH#H4_{BDMAR zZnd@1Ej7XfjJOERj|5g*=Nyr5>oBfyq1)NBXNF(<wZEIiD2q6pH{n!OUw`Q@{pH~( z5C8Qg^u3&YAnSZ5D>TEgoXKDDm~#ra->Z|}{tEjcgoe7AwrWd2dv(rfl)52;SxHWv zS!Hl!m)uu2d+p+zdwh@L(1E?ftFOF1eB~c~h2yL7%Sh6NihdaI#gi`#fBt9w-0;ay zeKK36I>%2LTMswH#m0aft8X+^f3s2OKe=!l*C;x|{%j-kqqx0|3+w#m(YbTySfq6^ z_UOZjW6VMNqB1qx+p}tGY>Q|cFpyqG*3DjPHc}GL0=p4>f1F^tE}zEpM&YX6s-^^o z^FLhw2Y=_krgPwl94mla6=S1kVcH2;;5xOuwxRdBJJ)nJ+JH;gI19HsLF4dhO+jbO zG_SMDur>TLLsT4j<~J>?hSQpqAtk>+;&;&Kq{cxHykrkM&f<PZqwnjcYpnk9wf=b~ zVNS?=)%EtBC3efgiOdR|dGb$-jt<VJtg;#DXv`&RhoBQq3so20aFy3D%j$ISPe*_a zqO@)H)Y16k2<R?+mD4#+YVu_=9*5GnIL+^bv9Hja$ww&ch~Wjj>M(P{%Wd?h6Jd&# zZ5aStE&@ItgeOfTQ_!{2JLRyu4X=whNf|^%HsW;1xC+|NE)4{uwV62wT6BOs_4k$J zMV?G<V&6Ki<(aWpg7otzAN=dM$QB*bI(c~g*N?Pu2%}wzQ$Y1)h~1z|&*IXS3_5Mq zi86@Or@ub^iv7W7bRs+rR7q91x}Hiet>ICs2qp~&QR)qyK*O?E{?1Rzv+)u}$hf9Q zf#8QE#j8x7&99B<q^wmKO{Xn?Y=SfgUpl)jXYngToaLP5*Sy|~({yoe<+YK?5P3)+ z;e_WrOd(%%hHi8?*T4!suvcwRxs!)R+(!m(BO%{9&*jT|uWjTX1RR}d=glFz2^(Lh z-uQsR{eC^HBl0XB`BjD#KEHABMxT^8x;A|>)X=l!P^KDS6+U^_;q7W*>x#@vM?S?< zwgMxuQ_lPsajmNran4l^%IyOi6N`^3vpBAm0sh@~!9lGLq=c2f9?xY3WrcohPhPm+ z_NV^TaA(g!R(Nj4@w9^#zq^1jtt7<KU<f&Nuu319P{^>lyvl3!OE`}2@-Sj0&NCg( zCdb)KepMFHQbl}_CaM*5Yo0s9J8${A(ZX=(*g;k}<5s3JPEFx(uEHjNIlElpJjLMG zucS}mK)H&;`OKNCIJ))>JNe+*;v%msvHimAEDlSY#PVuuAur*bx^G*_FqzlqFLB(# z={!5^W(DHDgWGUcv#kaL$=TIA!_4y1FuQzvn8*1%$F>@NKv0KsZL5L&;Bb|*&TC4P zNom#dQZPh_&!8P0rA7AKjyR_%bL*M5Fg~zT^3l?Wk%OGcW<5^{SPEtTB-oysZhmnG zwxw&++6({0qXTs*4hNwe$wyn-9nRA0!Rz`X#u;~VTQ9f{4rz@bk}Z=T6rDC0drH}n zPprXAoGrGKp>F$~U+ZG(xvly`oQ<q0U*iG9{2o>~?>ji`JjjRrco5=8cka;l`H_uR zzw^D}#EYkf7hXD*Z4~;d-dg3{WRa#k$p^OJmK7)+hx7H}+u!^a+e2>~jy(T7uY>NQ zKX3~f`#c`Zp?N1$2J@+2f7F0FchL9_4(Gc*>|!A42Lqi*WYv3UO3y67D}9R#KFb6i zu3W-Vi^KUEPU8ay59OnQuIRO$OTS7U>t(bT2CAIJXxy^fX<WNG{NTIaP22j3Pku7n zVOZCt=e8ZTm-Do}I-KqAZJV^OvIVYr*!l*Jdmm;WJcMJPI<&z4?OEaM<e7`uW3y#- zY2P)H1AG_w=;7r{m#NFEINtXT$6h>^^!^iCP)vyJc%^dqN3Of9D!#!3fOF{6Z&AE- z`egQ#b}W*<5Sq5j$)!GHG`2zNp&q2#ho5H<@9T-anyB-C8)X|i115QzV=#Rqd6g^r zunutCymo_C=hta7ePCG*XCJC5v+7SBg|-ig(*ID7Dc|rUuIdA?<Ft0%w`<pC-mK7h zwQ2b2kDVO;{g0lczqL$D?g$hK)Q~!b2!}Wg)+1XPC%8#VTb7jECfVB_0Pi2_DqKCm zvx!f3I2TmW59twN^sA0-FOt8?UEFTjqEf<P(t+ScC!YNKXRuwY3&w8|!+Y}Cj}y#~ zGWjtPJ)rO86j>4ls8CyKH2t7c%f-;o;-DnMhk6_F9jJ0RSJjbDAvbTX`@>Yn;e=`< zOTI){i(_w|jS-HzkdCbQkIb}{acIN*xEvL+`u-9M1YN$w2Vs%vzagRyz@tWrXn2jI z6gYJS=ANT)29^1w(ex8uI+%4qblR|Qpmm2cvQGIH6?s^hIMNSvyBr;Z?5Mq>9D+%z z2h+rxF5ivkf)+$r5A`o^Vj1VpwRw$g<-?_S`7>Uzk|XKHa6h7x+mS{B-_p&Ke4JCA zyoZN%#{aHl_G5s&UP6(&c!h-(^3Nfetj#D=BP7AckLmpY<tWIKhq|tQva%W{sw$a+ zF%wNnLPY7bi~-&tjqY&HeM4Zpq528WjSg{fIMdz9gZQi5rRmt+{btMI+_%sWSNH>W z$cnr3#ktc`fHVsL)ma+>mLoLyajrJAa+i54+iWnFnp$Ij=hUCp9|GLVft(3xMnqKq zLX2RtsERc0R#No~sIZAQ*5J8pw#GjFn)+YNrJdH1Tn=aRi>=^9n7)F0`-d1au=e@F z1h;v+EXMOak>GHSVV@~Hw31)m=(}clAlyG1s1rD2XXMNFUBN4<jIPi#y@3N}4??w3 zp2f|`L^&)3>VM$4RtHsQOAqlW05vzmM+1+X6b-=wCA9Xs?ps`?L=GL!zAfwnBqWK? zM7myIU?1mS|MkCz4q1r9;x_#k*V%^Z=fC_5!wWCGM1JR>ycOUaJ!6hGZx8L_O&yMo zM~uMsthN7*pAR}cUhkg-J1HI3R3M|%=;BFP-#5<w*ad%6_%&v1J1CBM9xD5=<sly- zU&9XW<9Pn+Kl<wMkN@#M$pd-)2QK*A&LW;;$BzzQ_^B@pAN%;nm}Bk6H*-Haj=oi3 zvxoO(;F%JXvB~+Ad}TjR0s2w$2DMp=>Ncm}#|3u=zy0zDfA9yHFC061Y&d-QaQq{V zaZ|@F|5jDTWn!CCIIWe>8lFAJvr_oC6du7hs;@`;k@uG;{UB8;HR~(C^E>Om`OAMZ zjdBn`&c<CwbFF06VNebx(`~Rjq3&>&l#RNDZF-DASo6_y>&Qxc>)oAP^i|JUc?hic z=5rF_A-p^ox)Dk@Pa@+)BaO5BS=wMrYsJQx&TERvsgq>K_|nQ=nc~I)>MP@P4ZO-! zFzHmGVV|Ork$r5a(6gfmFBrEgBOUj3e&ns|tlP8>n;Mi#t0sOrSmnbBrn1eo$)NcS z^3XqQ=e64#q=SVgUqQ(VXJr<azd0IfJDTp;>-r8r`*C2HPF{gHW~Iqxo|<!BnWocc z-`8|<=*G@F&U)yVygI?{m~|i`6P<$lWjknhwX-l=Srsb3I@7Dum1ffky-N1&rA$my zjtnT!o~v^+$yXjS#BSihvv#D848mk!q70;^fg#?Nr^f5NmXF{zABRF(PAOOPr|!#s z>DZk3lCNl%LqVGE7Yv1j5pD1qOotQj6@6FIW)Dpq&hjdK`81yn$-atO8gVECBj3eO z)eqrJ@2jD`7KejiuZ2$@t|x<K<tpjO3_S-{_jpC!70by_eeqTM(kJzh>qi~V=(X9P zIC>on@8C@x_7!!A>R8c9B(GBprq-!n543Gqa?Tf6(!>MP*ta%78GEEGv>6U{6djHw z$%F)rD{CEAm1;NSJ&t)EE~M-!Ge16(2NiH8E+EHpl249Zy>G}on6tVPw>p-e9=d*| zr_SPN#y-`zcI87C>w*KGyX*lUT{hnOg9TTj8^7}>e`0uW;2=)4MP38nIqX0B9As)A zWO<TL|1#LOZQ^kC_Cp-`E4)pj^Y;4nd&7P{8m8mQkCc_ullsc!W)tm|+jFe0QZ{%P z{Se?96O#KlcHepX2Cz7J_8ny<D`kn}INQZQ&lw-B9fz$2df=Ltkn<`|qFclHH?Oj) zaZl~%yK4cbq_(YN*=<#Xht=%ojP7^>;cK3L+{Tr%w{G4Wu3uZ{V}*QVj91{@J9-8l zan}#i%eRKv`!|P$m0QCCt8^Bocz8*HU^?*b!8K<OmpZI5@c=P0N>N*&ex|Idjz(XU zeQbny>(FR&LcF%+N|Kz-A1q*^Y-m+-Se9jv<}HA-xjxAuAGiVsK&@hP!l@3mDfIy^ zI*2+n_YUv5_-d$uR5<d<Lz}21AF*L@e1cEgbgjhDe?4=Me{`rkgK?v?yiqn-zuTek zdJng}vbk;du()^su=~jK!@};p!wlOcEVD1(1-|<I-S7Q?RlzR~u5eytLTCT26U7Gt zqK+&L|BU>rUmw6=?>ZM>`SvTr0{ITJx?m?C4qW6RRfMvml{F?4=^zm_6HfBSn$WKg zwa%P9%h$&5XXVn~ef!x1+%L74#-J8@+J8zC`lE-|=$ir=-qlgd$3p!0;i1DvkmGsk zh`KJ`t&<*>x9x=2>fAorRaLG^zKOH?weSCcHwv~7KlbrYWb2qbRJZ*Fk*c1f&q!Mw zXPo>g9C+-DY4_iF?RDDRd+=~**s&Wuuq_5wASvk88#eNw-KbdkP}ho~Ue3RL4(Iu0 zXl#nZ`S9~c$XL7<j{GLhJPBOnnx8wYEWUB&I$PYFXUnA7;ne9<yyZY&$OHGHha_na z(LO~pb{<z9@Z&ryJoI|&t+Uxndfx%J1lr!d3Qpb(hQv|C9X}yJ+DrS;wCmW!Rm$QD z`z$)%*+KrJ$BqOhHlXee)(=nq5S8&BW$b{<htPfi=KR}l)5a|i&%bnZ*vx8cKaBZf z`*#nYgs(?eIEzqy*13>!9psOt89go)ZfLWuD+wa-A%a26n+*L<I$m3|E2KQ7&#n5E zY@nO0wqH>=vIT0g-s*s8eD?mZD2dIhx+_ZJuX<pXqStvB)HL~`bvK)3oukV_4)Xz* z-Us{7wi2{ARY!_S+Q9&N-*~Ph3kn>{Q+$;@fgd|aKxW0Ze@RGNCv3s1x9CGYC!NYM z(SoZQ10MCokq3~<7W-&;AQIF?MK+5kl1o}64BRCymz5{-C$aqi+sh;|jrR_cIs>Lw zo<*Vh8F}(83&*n6SD1-jo;*HibIfU|z9pCZgjr(~QDbkf8>5X**_F|CWyw}Bf5}%o zsq?~Bbn3c8KXPtxl^fJmSfkQOe9NxhCPTN=9;fX%?$6d4n{Wb9Ki$82O<S;hIAu%+ zQgP)VvuGO|iR<`er5`=6=cCzdi+0AiI?U({Vok&l8l1(KU<8M^v6~j()4kOMJOavD zng*IQ#_YtyjBy_3vya-grOtE{3Fd7@Gm=qQ<w#P$ZudPtXW~+R0D9k#O$vp5`BA~C z)g=!0cjnDBmN@}bcs<3Aa%&CJ?m3eH$x)~{<IT~}omRyOT<N(&Ui-;{^*VDF+JN3> zJI)H;*7nFp`ni^eoR#i9btUyUj90wviE{)OA=x(Q;IAeIJoGD3xct(m&oXYA<r^hF zFwY9-)LSJaPjCXx*%)d?>YshAA$7&VXa(W|fk1KJ>vqXKhOheT9?m$N55E{Z=BY!f z1)KX(gH(F7P0*Qa^AWwJ&C~I`iLvt4;kW<6Z)f`}X*=)mf%7l^)n6J;pZX}aMY|5Z zdKlJeH1eZUE3Z_hb{&2+M&^7YxDUP<m-YL@J<fr;O&FcHcpT{c(IrKP^9pZ4&M>!} z^MSI{5f*Tz-RG>s`49g2zlg*6)mOeVT72k70gvKr{>*1TJ$&YKpJ9x`0xWcFIlEfi zKG5<1GqUr(+(wV1vVC8$Q9}38j3Rz?@k9+gOZli%$Mo8rZHtHBe)+xM`@P}RsZ+yC zFTIqH1-jrbZBN>_B5VE1oWXieNS{prvp`J0x_`ai7v$4_H(IBjj_HpVMB4WWoqizq zD5<x_9|V`;phzs0?BV>s{jI-2XUiV6IPfeO9V-^Rjw~7QNrR3X5AUlyYZ6rhQ4kS1 zdB}j1cPA(2$x2{wdM%zFIxg==MiJ)9c;utw?FP0=2jU8}IXa^Zq;&-Ix5{3Uz7D&9 z16tqm1NdLYX|~KZ0S>qxZqmWQnm-$O8aY?~y2XUXWryMv<Tfh~rK1k)9OYGKl%1Yu zq>5ulo=neH2K1WhK?mL}gOhaz33fbj=2CgAK&!N}>9E1gjpB}iG<2wmuk@{BmzEWN zbZ*s_8g@)od2~3twZ{st?8t|7eK^pA*pW22#0N7tu>2r_4oLXnyu!!5)|iADM%*;~ z%Bh3em5t_yW6l%`d6j9oIh;{<<Wyf>XO@?F<k@qdT)`+jH#qoBS%+SgyKsqvmU=M6 ziAv|9Lpy_?hC?mbal5SnDgwR@gdDvP)SXUY%TVXNj((WQL?QC14?KG27uN&mJ#Zqy z*}Ue16f%*T5s_t4tCO?mGmV|jWP`BXR-#8`Qsv~6=jZ@lWmKCms9*V4XCqm;H?G4A zlhxhHQ9q^|)RTP5n@&>sj%{LRwaTP)*&WWphZeT9jxMBOoX&CcPKMDW0^HivG*6jz zVn2ZQd)V7Oa4b_E;tLLGf=`FD@UeS%)2fV*E`Xg3nVgUy4j_VORL`NMjVX^G@XD92 zp;xZ8axB{&J)8rEbYW(pH^*6fjl<b9&i6h*7EWChKjqNRN^rK|vFuiC=ddAZy3K~R zW7*NAH5n-{`QZr9@b3MNFMNJj-G2zj@$|6Bhu97t-w$EyBp)t>r+j3LdQ%@&t9H|Y zxDLFB%lCM4%YL$#@30@OAK_!AB&!4+d^#YTp7CJ@_DDlk4rk<rpEVr0D{NhH{@hjC z9$z<OKV4P^Zr(<nN`*z!C|Kt%B6BTD>JLsqCoZ?IFAW#ZU*mcUE2Fm!yZ7_qh0W?4 z9pk{}$pTs6by{aTwvyGeI-HmJ@Z4=2c6V8wxsnyq&mG*$gg|?yy`(LfW_9x{&gR9H zo5SMzJvR904rggw1LUck&bGF$bg`aQKsM`4JG37|m6`EaN+u;`H<qnsk&gm;tvw0v zA4riP7)Xj8WYPqT`UP3RgRf|kr^ThuLVwvpCtPFS;<8+FG#a1^5AfS<LOA~-RO)9) z!Bz26=}J|BUXdi~N{Lz%*XY9^;$>9@<y_ZkCzEDA`Xdhef;f9|25j2AW0>Eyf7o;U z#bFEEYs~W?#QkyKJ@?M=?N`6kw$wPuM^{+QN?+w<$pO4%)J3rmJ}>NNN%z&)>#Q>9 z4(B6BkF(b<TWT=qkAdZZhC)!!kjHi*D|}GCtF#>W*-yUl#u*&WJcz()ojsgcC2fUO zJ5F9}f?A{{A09l}4pUa|zH=ViyE5G51Bg1DkDoY^dR?$U$KX+kbm5`5mqhTtnm4$v zvm*D6*Ir}q<n6=9KG7V`)Ma5^6((67&Uq-vwecknIN;$SZNuxVaK68MKPxS^?P8x{ z_8Fvx$pH54M`(THL|yiBul7RRwzucrd^;<g-Fj%xzCFXiqX%PSWB>v@%^vEWC<DCp zB=@1d&bA`&Uc5jV%nheL;?^M4{}h`zJmj15=r-#^0TH0fRkq1lW?P>(&z|8Uq_^19 zyH;xZ;nFzIEJM9Wwwe6dKZ-p4oOMmvIA41ALJpto@4_CApEw4XHVu6bb8AzC)C}=i zma2w7_w~Nb3hTG9i-$}|PrdvC<+1}h^TVlKTZhv)u@~pnscd&VA`>^E>j_>Gh_|eI zkazzKew0fGVFh6tz6RgnI?4{$vC(W*o?M_GY&}uQ-*RbZIm`tw%^u~~R>U@@GBx-j zlHZK4xUzi=cl_i*A)w)bvNXgN=^%njcu`sKIm+J55e`C6o^1a~vs^h>s@M!c@K_ue zkfXQ9MPC|RQ6EGb8s3MJ_l6|2tE&6P)rY&1gC;^AgE3i^qsRC_G$@*$iVWPwjth6% z!vZ3I(`iTpHzpq*`j1V%Ax<5EdW3N$3~7wVB9CxQkDg<%>JVDknd5QeoP)Ti!+bi8 zdRr5?hO@{>51jmI11hhVUANUvH%#)=)9b#NFW4qX5{joWOo!|Fp*0zrY>8?~jZI_- zTO;VS+1$Y?zi`dN%ys&fwfSB6iLiUeL6}3Q;CXa#A>J-Sr_qs1OIfTMlPsam<m-DV z7mmtRc`DtQ$u#LcDX0z8I*m>*xEk*rPitCi(iqn}zHm+vQ)kRK)LUQ+D#>zuG>EUu z_()p6c`Q$d?O2KjZK7gg!!WSUL&0^%c~fkIwuv{!rhGW>!0-|KHB;GB&)@O(c+ZCD zmvhPmU~RdlnQpve_db^K97UiU=P1sF^58PLNJ~5C*r#xrzvH%P6+bydo%+(#>VbZ> zUu!s?y_d!GmyOBVQiHeW*iJ)-vu`nFj3O@Rj8)r|M!XK=UI$}b5^ljU6WO8(&xT(2 z+FiTX;k+;$KYFU7^V_NQvytt($!t66HX8Eic*?Cbv<v5+zFqcD|LH#&UVr^H+K&2W z%iHJ94Zra7zc9S~@{jR$;R53YKXmTcyT+7b-a1VZa@m-VBu3Z|rBw;1AN*tad@zKm zo#Nw=W1b$@-Q$q&z1QLFSaY4uir$>D72l5Hfwyl%S@*87SMPuK-~RV(b@o=~kbd*% z#EBF6zJ(9d|KeZ%i;Njv7~|W~jLpfE#cb%Ik1yU!^@oiq4QxPFDew2!*bhtp-@Sa* zn^r$x(se8I%n@bRb?P^jXX_T;xW+%1Hi_}(9lk%5hdQKL<~|r&ajx!I)Ijz=&+oRH zzPr`Y(O9gYpZdFz@_#ClKZXG6KW+5}dEW>uMV9i(>8ro{yX(L8cYY-fG@U*M9X<j% zv9R!L$nAjo(F?Sn&10Hy9z9-%nGEU3(dlX@l#UC72@Iv`*|bheSPv31IrCbFs+0R_ z%yE3fmwl6aIM+bii7tl76Et6iou@(bfLQX~V{&-c52o?Ncpfk5JWuG|)xxa-99U?w z4j}JybCVCq*)W4HJUPkI;U1?k9fQsuJC=GP%D|HWXdK1ha00nN+BB<mTs1Yv3Sb8a zQ7h+kwsf$rE>cg?3mv7E%4?m6PIPCPaB1+>$xD+hLLAt_i?nB4VSuB-RaVBwSq+YE zES_=yMJJY}$Wq~uNqA{L#5t(beH@yr002M$Nkl<Z)PXQ278xL!5EvAIi#>YKIVXS0 znQ{bQ_=84PMW+KOXM>%)_)Slc7kIOLYtm@ClL(j*59$6H)VnKqbzYk2Kpv=+p^Z$> zBR(4!^`TAJu#}vIOZqygJ-g~NA18#KxcrfqtVC9y#QT9o_i)yReMQ;E%uswg*fMW9 z9o2(&oHEfi!J&<)D0QJdD2;L{P@JB?2PRmtTk^?UuTM3QvvGBhCaSI<?;K1~hAl3u z%aj@1ftL<xIz#i}F0Pd^(njDabK`WTx=n@;PihcW_)`YrA-E<{XRQ-EKiucaW-Ke$ zZZmTS8J8QM!iy)m_ofB;oy1v#&#_K)UKh0%*E4p$tzYoq*xFSeJ{ZC%@}MXVW#Av; zV6m>a^~M~>tdmm998jImmajCl`#cDW%(PA1rwmc)Dh^u9>kbYaE`}X^8CwVU3a`tH z`vHR+Wz)GF2NXI=xq{d7+`*O_s|OAZm#(bxTK%@+;E4n9t=;h;3%$hQOyi=o4!TkY z(H$dC>fbV}9&Qa6-@VCd;k~R7+<_C2{mC6T(=OrWL3kfpQEzbi>Qtl#LjOLtcQ+2_ zyLVWLJ-?H^l=;}!o^8}G+gof1d!4n;TK>qRLn!SK`R}j?^VJJC7zo493|n&GB;ULh z8>Xp3A<3&1y23dh&2rT<`8Tmz*;o0mUt7ZQcZZdoyIGn29CG_0PMO#$!M&UL@XaEt zb2j4`Uz}QIKYjD+e5g7NgW(J7=Un!V6+m3sxcA7taq2t2@Wr)uN83>KhPnl8`UT?w zOwOEjXBXCLLrJ5~*8s!>aoOfoo20Ya5FFrK)!`g(frA^B2)FXVwV?9n`B8^+Q?>Ok z6|m>^J|rVm+OWj%lNG@_jguqizzQ!8&zwe1XX0WX4%CxwpK3p88;-sEy7N3A+u6lO z9gm+Jb{sr1Y~9TV<?i2NMf}^tzxktYvVFtJ;f0f@c~G$vJN02+9!-J`nY2;r5`~X! zC2LkOVXxQObNE|sslm#lqsQ4&W6y3T0dB)Wx#7&sgC>-2-M7A!qSQI*=-GXT-+28E zwu526Up}t6pDi(V;&6VbBM@amH6d*ud>K+6maSz^-F}zXQ?Ih`@NM>DK5*zDD{7B7 zRabjyT~+<z1&Qpd49ezX6u*Feg)KSGy#9JtIO}jupBgv{0XnuHb9oqP8)^TbKCH6z zm81#d3h8CW6i1F89k#H#c@C#9>Oy$ibtY55mczNp0Dbjho2(7L#YYGIaG`s`?|E*| zu<sCWMp)4K7g2@iqTfuMZ{E1YzQ<SCkNpzmv5>u}T|H!QOE1VJl=Ikr8JyU)diLap zK=1Ql{p^`H_!9VSJ|KFS)kAEr13x~5?M`QePd&QtI1Y^I7vSF;+x?3?0PrDzE4g$y zyO(svMLMeq)@4_hCo?Q)yOp3Ocss`x=X^Zz{MoaV*#jKTFS6HVIh;@O5bf0VE$lJx zcty1r|D*a7nIaP9LYl$2iL)(2=|Y_dBVWJ(SCR$T9|F3m3w|4(cHi$tc|xaTESfE+ z`i;C=T-ju$r{sf8n>MwF(N(($RtUyHOx+SR^tD5RR-`V%Ew~Ea{(`GkZ-h%8(o^Qv zvDmTDjW2-`BrJ4tRFrqpXvc^?a%X`@pv2?FWZotOvF0r~iR;B<yoK3PxFAgEqxBK$ zNVzLWN2x1}9nOLX)M0@$U&TyNkmp2$$9Y8qsHjmM^;5V>D8aly4yf4vs0(cWQHQe& z6P&MDXHpUcKfy;A1n!C_@bqAe;r$%WWh=lmenz&RT=LYFB%Z?6>GiW9<8n&I%H6Y$ zq9!7^RJRpFUxTwb4(GWYyiCKrW5PzRv!GPTV<z)g=FwR)M#+nZ+ZPpIrdYp~2Zt}F znkJ^<=rEoqagMGl`+I(6PkOydcy3k5W;$t|Pw9E>w8IaGi`y|jyU5YD;c&*;Ji}h{ zhV%iss-N&DAwz-Gb^Cohs`EVpB5$|%pz%k03o~r%$Xs%YaaC42^9>IoNbk7?POgz| zdWz?=5A|xv2+6P4{or1C<f-E9%ay;)Em9E9yK9_fJrKD5TKgb;>IZ4b8$t~aX^+tq zR~~>#!*MX<197^gM9qV^rJ&{*Pe0;tZi<w*UT=VGI;S@wPw(%m94Z44^gFF3@@5n| zLL!=xS-;|NK6W~&pID$1g)A=you7`S9G5DOc)WLRdYduxTW_8ne*gFXPx{(hd5cJg z>SsUux#1HZ|0EC25A&AlGFwNn9Ud}>qw}M9BOYM)5%x_YjCE1>AJ%Wv&XdtKeVO=y zaHHIg)%jQ;V-?32x0r7^C(HICygB!cKl;Y-FaPD&hHrAd%2r`}*`wEQgnagMpB;YU zC;q+R<f&6B+di*!p<RtLZ9_K3!HAU&UN{zhT6h-S|9{2j1`FV6qO|m9(`7UNr{Z=V zIpaLg!8PL)=TX-82Yw$2dzfX_`|aCz^6+K8`Cd|Qcmq$X-@{yEUSApw-ztkoJ@0*P zKg}cy;aI$BJ=6!5wuaPExgbvZY}%Yr+d%r$LdWwoxTHUu%ASt$>1H>=(c7O<#0Ok# z)c(Y|(Q^F&a_>!|KB=ng;rv_w%`Y>Ma>7p}4W%m;t<Z6d(U|&bz0fx5ahjl%Nnwl0 znp9b^<~2_on&7i>ak8P4&IYv{bQ%Nn(l~2`)r&e|k*@JNIK7U;nQNUx9u8%(Akr{G z&YRp)1DeYkG{&Wya-MiU9%%Wwhx0Ox)EbT&_Yd_I4rhoyRlJAucZt<k>)@DS!nMXL zom=Vb+|yPbTnX!dQr?$XS#|H;68Ch7IH7emy0l+8bHLlI6H~T1aDwW*+mDRQ;^g*K zI43NigheY~b&%>s84c3#ddAmI&`mi!YoA_u$+iOI(;=V(G%HGx$25=Ni3)JatngYE zy0;T^)Mc83I#&cbA;13sM=OIXW$Rl`h+`BiV^@J20q>%!eJ!~Mk2oIk)Ln<Jdu*wT zyU49AXeX{{*9q!<oI(zuC=KN<e(UT2z6P5PM9Rr5ZVOIZ>XVIfCe#GLZ4cC&b`%G% zG{I~BditqzymT#`c9c-U1g`7MiL=fE_d+&kYvR=&#Zk^J%^#~m3CYJ@cmPhhyMskK z!gpTGuR}*3Q?B3^UTg{|zv0;dn*u);w5d3BTlq>`{GE>A<~PJ~qNCV?nh2dA>H8tR zhtx~=UX49~%iQJ=r#ethKkDWF-nZ_vr#l0M70RPltW%fZ0XOsn1uq|^DW8+U`;xQD z*!q}BbCX}#kuK1CnkML5o$dEsxU0o`pFWGT50}&pwI8Q5^jf_qw&Jlr3M+D2Z_?&K zr?!7V9wy;;*`7it{Czq*c7_;^?mswe<262=@~-f|;{>>sxwO*uz`H?x@BQMR9;S|- z7~Z{fmn|(e5BrYn_ia<`UVgF3%yenTfVX_@2-60j&ox%`U1x>!#fvv_{_WzUgWG6# z%He~gK-;l8cvV-lb2xEqyL3da^2+7A7p~znHXXXGG~T&qJ8(FLEK~IAn;U%)9O`!X zv_F10?Z)L>!_6DOvU2Ir^9OM_s~`A#h|X*p;ct2xTTt<94h*T6yd83vr_49t`NH|z z@Vkrc0G?xIHF@*FLfWns_HbUg%|`>>QiF$kta6@Zm9&m!oz4#Yb%J|#?_QnIvERt0 zUe!{abKUHtOq>+TSUa_Dre2bebL`2S9LD7UgY0`)zfzYu6PXE;?W^_GdjYkfmj5B; z=Am83$(*xz#OdV4Jk^dDFJqcz`@&Ryy&Zricz&dA^erfW5jsev)h=@;p&ZU!XwM@j zC~!LV<kJTf#IJ9n-p=sRwXM5{9fzLB;e2%1wrBtFkUhWOednFw74~pGj>Fkwfxgam zU)fzXQq4xmrEKdy?0^$3(FbXMVD6hZtQYAYkDqv+74GG5Mk@gK@~F10#t2o8>5`dv z-DeA#*M9IieFQ6<aX24f|KnY|_aIYgD()HuHYifGz**a1aN1WmU%h-4JM0eUW2mJ1 z5!KLj>x9;8>#QMV4xXi@yVSYsnE-BOCGAH)_OUooZ42!tg_hrZ`ymQ}H*pYWf1ZbZ zv<+u)oV!Jc4(DyW<~fh!-M1K&*g<f3R)>wgJamVtxZY-kv-?r|AbSrV9(2-aDE{qZ za@*qSdLoMbo3FF7_#%5jUeD_4mza>b`bWK6Vih3NuVdeeLAnF|W!gM+c=n7d&X<N0 zFC5R7KJ$F|FAjD~9bsxB&A0^Fl`RhztxMpO(mUtQ4HwS6&9)wM!)~_NIehdm`JEWl z_)UuWlfJR^#R=Y`C%4n^b;*n8&m;5NaOz{M%IB?%O*EpXckxljZHsKF;dl~o84BIf zQ*;|V;*vW;S6n-%L|UHI@szM|>Zt6_Y!!;fk<NPb=v>574&$FzW*vpP@nLY?Ynu?` zzvM0+N_QP?f%2OR+C+4p*1+)$TDSj`oc8UNso5f~5m9f&Gc=mb79@EBV}D=|)W=ft z6J&x-gvaB|2mRLHby@nB8cGo~W(#w<7~>1=CSA&h9D+m_MXN-ZD2E1@vKCX5J!dm> zj2+%40}$FpCvA~&gzkLi3Xq~Vb~tzVfYuK%%4mx9u&Foaa;TvX`bD?K>klz~U}&Cf z>(|OyWa_==j}S${6!_}4YGl(xJ9n^@8;mHQ<sELrUxyf<JDqAfiuO2leBaYe>v<;O zq&CTqFh!S#-P3$5d1i4~onvfdUF4t{7~v7N_qoAoM$_w57wy`j@W}2z0!P=SFYz!9 zZT)QF@9=^?PSd!^BB94Z&u5iT%ih-o?NAL3lh@*)Skr{8;JjF2g|j&AI~Lh$%;EaH ztDBX(2_z~*&iwTI@kOQg-%)yt2%5&T^*aINk+0vvSM_`JWz2V`9<sg0>h0R&nFqY2 zcF1<w?4-qdDmx4{?{f4wthq2Kl>ZXX*wK0qFDRvtB^@U@hx0zLv`gkrKbJfr;IN<O z?4{$f;4I`7&vlL83QmV}f5TFEx4s}Nf%$tJ&a7%>1@JWUrZlBW0P?htfvX>F+j{7D zcd`tOx3<}jjY1KCPOIa=2i|5NI=qe_|L6$(sTbrM&2uxxbWUBq6W^@8d-o3CNw_im z*5Cil;o8+p*@xC~#PQ?DhfjU#)5Gc0AK`5&9L~(iG&1KWWvo)xa(cOr&&HKaDcwZ- zX_og5>gatFf9QnCcIADMXb@Di@_{JFdgh>47*oFf`kCRi*M7h_;KuO1?|qk#!@ZO5 zi<~}vdidfOzc_sA$3KP6c+iDz;{!nQ%=y8gK+4pL^nJ-cdxE&1J=X{3kk=0c_~8;a zr2h?~E<F~P8`3F2y~chJiA~G_XP8g&+6G|uX!=)J(53&0Ig1M@@ABbDza?aUev>`U zzxAzeu_%NOl(Vhc9zLvn=k9In<a;a_xkO!=9X|K@pJ43EoR?*hwpD)LYciyra6C+# zV%w5A$t1x0UMtatqzA)?U#H}Iqv2U#H)1EDY?*GHg^jX`s;Zru`id)@|MoABCh|7i zwR#grPMnd`!@ahW)`{83QPl@dkn9Y0C#q*(m$YH9pxw?vhmUyeq+CI&GgV_y5#2#2 z_g;79*g5HRv=b1Q4mfq;Yn#*H^g}9}I8WoCbw%+KPe0sy)|HNKo1tmv$p$q1AlN$T z3-W=J*$)rhWu?#bB423VwP)CM;J~ow;KAYG3oi^ickaw&upBQsZmb+ST=-xYhfYZy z(hGj!9()c!jdyeNC02r6V{(7t{JG)U<#$<8$fS_HSy|G^$|*k7#tPa+Ugd|i$Z0dA zPQC9A=f0X!9mOdEetC$qGA*ozUVND@Z<dw1R!`!YqY~@v^mSOr<mphYfauRb^ZLS0 zysLgJ%+-yQkCX1+t6LD6K(msU&hRczX5Djk3Vd@qn85?aVUd1ZJ>=;UM&K(BKGl^c z^#aS3w+<o)Q&f8Xbk0_pD+ByeUX@NYZ-!LZWx{~-42QNWkL6G2hfaR+=<JqO83lt2 zuDy?qf=iuwoq-cTX?%z;`;uN!aOIW*W`ppij~rQ)0qqq5d5Aa7L+7mJq%BBCy^~-u z=G^n^P!Eqp>tIlpdXP{~5y4~AoW(O4EXM@!%4|6F%pt##6M2mfZ^-e8!<htWTL<KI z`92R;(D&jZUw)3=I>>XomD)b$9?l>hYv44U%XSi1@7@~jBfl%1<vFra-xybpL!&W{ zfF`iY;?eab&;4-1oC%7Zf%TF!<tv?WwyY3Yp52={^;q3Dy6QO256>RNd+x8oN8iAg zgVMn{sr-xI^2qidI0hcF8rj9UYdByQX;WS}e012qbI-7jQ~n`wcX7ftlHlNr%GjMa z3~@OB=|3~fJpUq2V<rMTyxPT=mS^X+OY9uG58wQj>n<X4hx1hj0Q7I%yh8`dieOfa zZpnkLEv+6xfOIqoed*C&&_QQ9OsBo}kk!#wZsKrug@{h8-8hW416%E@y0kv4e{<() zJxX#9=oK7Ix3AwBZd`Z6keOlsu>*A6wx4wVIG6JZKINA!J@k{TIjPoR?4I6t84TQE z54xMI#@@-w>^*T-W73orZ4e(coaIaF3#@QnT;qv#9L~f;cN&LxIh<+lF!O9*0G&)) zumQM~Se@ZDwt}uL0nNj7AK++PRgXy{JvP(rNgIkCwKMrJv4R&DH{x<4XPd2^l>K2I z)-h=K@JXlPdmPTO)k+JF&?-9?Z$1_)`@v&7D?S3a!oHUrMaKj}oD|miYB$1x{1GFK z(gv|6(B|6yxzzz0Z1!Jt?CG+?c@rOW-Nd#Cn|BV|_8%X19XdAbc<vC3&+q38&);zm z=NDcYj=u0B`zSM!qrGsFHba5fq}K$qXw%q3$A=U+oN0$#S?mgD_t@3pyki#*XSURs z(nFi_v)(h1Bv<M)dF9Uf>%`Lj(Urk&so@Ie1BVZ1l{At;8wu1~%Ez)pa%CoeE-Yut z{++kag%4K*`N2L{)Y=9bDo-+n?j!9E`L!DzoHuUV9L~M{HiOw6!|9KFgz*FII^GZU zU~aXm!<niBQgoosxztwFgC8Dz^UT@wLr0J4aAqr<EsIrCV-s*)Y>=xil*0U(uyg(P zo2+nV4`=tl-n(yKbP?)+kIw)qe^3-}rH_IAo39O*FI?o~owuleTZR{2I+=%r^}*O0 zOPICljyCUA;|tZs;mm`lvu~c^0l*UZU&#K5aayARfl(PwA<G5cDG&2^c`PT#M(5vt zE90CkJSfxQe2`V=lsItJ_GFMx{w{ZoFN`pby{K7newFdkl}i^X$EmDvUR>OQ&S!^@ z?A|<_<c*JPsbN{j19DXLQYju4%KUnb!|DL4GC&CP0A{;pP!4erJ%J%frlc=PN-_zr z{yHo+ZQj_nj}()IJh>u`Gj=)|QXiUQvK*<xPVf|gn$4%DK-k1tj=(nD#catS{?xHB zCOvFaJGHP3#SSp0Rl66M^vBfb5x>GV;LtQb_ndsID0Tx5+yCr0FAQ`HDNF9V>}G0K zW@^|Ceef3_$wZRltAc2hNr;w!YhyWMq#FQv65gLGTQ6Ho(G1+UtSi0$O3d7q*LI;q z9#b#eg5+v^HjiymZ<nz7RmSnv$JpvRj<@Zov3RE#y>Zhi6!ns+bU&F=xr(ofPq7;< zqrFV!jiYpu#3siCyDf{URRCT*O3ORZmZUvRo5L=sch+C$SC&YPTNoSDudFklc*wlP z9H^soz&RK^x9jLOk<xDQ?cP%pBVz#5z3+KU*95FW($Jo4hkKuCeCVV+%stLqcl8^6 z^OFbLy*icI7JaU5rNS0C_3?@K-m;5(==0FI->=!i1jp{hwyBq?nS_;ZL&;M&J+8-l z4h`W(7vpQAl1F@8m(1d~&J>+oy9J{w`&ckF#T#VPepHasK~sfSU;{|J@=)BuV{4Tg ze{u+}4I8Y#Be*uUl6d+n>Y(+oFTBayN)29IrkU5yqVRZG@vdO3dhfY-F;C`)_UGnz zB0;}sy#0x<(2LKp{T$<rtZ-)TUk+z%UnPa@(svL?2<jqvJQA87%#b#jc=ey`@**0U zY6>$xHU_-DiQ~s#4w|R^n8$Wdd#Q&|j%O$4om}g5US{0<_x|VqiA5sk*e0Sr1iza% z1V8hc&kmpd^rr*k_MqZe0p3M-a@YCG8Cs9V85>ES#%5uP%JQ=z_>BO;65;7M<<p|^ zL(7iC)PWD5zll@v+uwSHdCVQ^*e0CMuMclC#?$%!vp@5*!>2y|srG?5#<l3hv7U!I zF8h=`HnS0Cp9uzxPZ#T%Fk&blI!YPnZR4{s^JM6eeUZE&odUEG?K^jzW&z7X-qz63 z?3OAznrqua`c7J7-{7_W-nwxcJ9uOG+SmTC;irD;Cx?%|d>Ytc_{KN>&G66u+3)e) zku&*T$bbA7{sM3Iz04biJHe9{F8Qk-(+=5LP=*$xRed9TmR5w^ko17JHmNdxD8JP% zZ4A}3z;47&BDK2OsQ4RWv!JM_mIW)Ee|P==_?5p!V_%LxSGd?IR8bYI1z>g2AY@!Y z9~aj6H2O|nfwMt~gNsh7zj7u_hYLL#*naQiR~o?^E1{3Y(Pds8non{#uP{>3+3bo; zo!Sp@^u*zevCT5Um?I99S>fy|9bfD9HO?g_jf=dxx%bfF;qXhRhT|`PY}m?c?OS+~ z=GSU<*2td@CK1#sXNM@&Kl&<&{Mu+DQXIBA?egI?oUThep}EKheJ(N~yLA4o;my~- zKis%<fmiieNeTQuCQ|Ci##8xq<Qcld*;fyoK*xbf18s%s@YV%a+4*6eM;c#rnOAwy ziF2!4%f1$^vk?a|j`1D5^17W5J-MRFN$R!($9RgoV}w^7XVM=|kdsNqz14ek5_gAN zIMVO3n(8WhHa?(pP`*32Zw_-zS{;O_hjOO+5WrGoIOL#$y{ysx*p%d5TZ$b_*b=ZK zn}YYOgyI|r6AnUGUX@eZxcZo#PE?<2IZz1!Y*HJs3>*MhX>_W3c%u&0M>S4mhs6g@ zZ*er+EdFcYByM@2C<s+ndCCf`j!X3~e$U#wY0BZXydVN-mDBunZMt^t*)lax^bXLZ z{)O-5>p(=!`Cwr(s1s?aYh?jpR-bg3@Pa)^M}4i}aLx)o@)_bJ=Nvkm#pQ?NRuK3$ z1Kb<;?_^sE-zji_S`J_wkZtlV4mnev$>0QS6yU4NQ4THSHy7-7JJ8PMHM&=h(J{g@ z;<d-%zf2zUiPycgE!(mIb??I$KLW@@D9aGI$>4rsGwfZAYl%Jb)`rcz;c$#SZx8L- z%N7K@oq?{F7iw^$><*s$!x8c5aNf-8UVK7%xPEB~-A@mjaX!uR>d%aCH1LYJuZ_;o zx$3slgycbIv#XqZ&B&*^H*WgH<vHrlA}gG?mJN_TZ9%E`<fQFE=Tq2YCK@=MZ?QGT z{d*45XX$jeQKuJayTn_(>gdw}RokO9+I0NxYk&9lUA7mXE+GBR{d=fiIEdVbnTHKo z;YbnKbRtp)0$DN2%4*-%xJ#YC^zLmOmfLXJ?PRqoTMhv`OM5ZLE1wG-TX8gRp1MD5 z*~ACprf@h@;?v0Mz_Sh~MCHtMmQ@pzXo#{$?xyc@23vM&+&XC;wq2>iwkOwtx6Q0} z(|L^X>YGy@kd*C#MD);fLS$PZZ7FLn{!0oi7N^4Iusxw~;aYs*H1Xu^w2e1`P}QUI z^a#L%Klff@8?{=R(G=H|mgI{b)GJL~@<m!ZudYZKyGj9>!vorEvBYD(VYNA&x8rc$ zd-R22@4;jAi7Rn9zw*8Bv4zU>!;uru^N~3|$iqXt>UU)xnh22g%F=PbMw}DLRq|iw zRmWFfc{O`KA3Jek*vcNrbF|Br7tL)Byb|zT?JP_t&WVJplkeTRJN)1W<#67Nz19ln zT`3FOJ?+l+R=R1^n`r3^;L8v8#Zk+L>h8jitAdZ8IF6mx!`r-}mC}P3+tsGCOn_Yx z#v27oyxw|)l{9{|$Bzb{JbgO#!?qFfDFb<#r*4NIcyTOXyQj_g@Krg^zHuh)|1nl6 zZQJ1<=<GL#+?JIO!K?hMEW52LllEvSyS0d0YV5*kzkC1QVK-aT^l}763&Ku@SWqHv zQ5M%OTppI_i#KoC!iONAXHxD8XXU7IN<sTu<qCD|gEHaI?X;Fz5ODVF8Q$2sGd%y& z^LfK!28WWXKw|?4;p$e)Km7{a$Wi(z;$885{@ghx(dUQl+t~|#?=JS`-bY_r^(14y z=(Q%}$}XzN#94h>9<Fk_&Ne5unI}K`0_`AQ=faL&-n(Tu%?cMk8VH)$)d)e9G}aEP zkDL_)pQKkAkPw|~rek=S81WK~_8;U^Wy&hJaQyjS!TRB?Ekx6E+N+W)&JA=kiCdld z_JKOBc1~o(a?%zOFGf9WaUzxNI^GD7$PAIWF8x)XMacBRGj=#vT<B?+!BMtR?M~qg z%17`kwCLckIe)}a4rkk`Is%nz==S`Pv+)$kWUusJE3C;S!Pu9QS13-RrGhs)XqxQ> z(tP<(*;dZNFfN~QSyy`hHKVX)7bSmBYkKfDAceET8?Bw@Ku*g@hqL!?Ii$lmb>*2I z&cWP>dM%6a*L2xTs>;{KwE!ZAX%(tI^`ud3PdD4BYyuS!lRd_GywTQhD(hJ0@ZOc= zR;x7}1Z&vu8uPF<9?Xdn@j1|ehzKFWwYUA+c-2mIcqA_6NIXqdsX2gV^a6OQLF;<B z!!80x2GWfef7%k66N3AZzA7sHj+ZmOxzp)zHpB$E&aJq>!*<CjQytE(vem&n&))HF zrD5A+y$Vg>JD-KD@bz(f%q$5N?`5*^)5w#+zmYv~Z}6ln>egH(XWge7F`u9V%Jv%5 zIGtTB=)TTbF%NL^^V3mFuXwh#@}?=Q;kNt?*547FeH09M@0h%gzcPNdZ%*4*=~5ci z?^ej7G)^4jF}HAy7xMV<**6@CEr)aK7i+F1tYyA2hjVz35SFv;8%OTtPT_19!Rgss z{^Z3VooJm?(qb6Q#c?>Fct(e_)FyQ!AC4I^?~*5Y__e?LKMZfa`Fgg|%A6GHpZnbB zajJb$cCb187mRV-R&%^sv$!sn;XROD5^pTiD*GgT;E%faK!6`A(RS<UfjT7|?Ptwp zhrHSJwXc7D_|A8}n+1i+@wKmgeYnJf_%D6wOT(AH{N>>&Z;(0ubIf0F-Iw1*y*gJ- ziDKxbm#1^FafoIV8_%!-$p1g}zXA3D8QWLCeo8(vSdX6;>`7*rU#{@oBIh-(XrARe zWR9V1*4!3wae>_e?hnJ6H_i^<WMRuY@0_Q8d}cU!@Bnj{cZT2ijsIo%!$17jeDmmC zR=jT;{)3<X>ES>9^3U`Al9$syYaiAt$MS|gAJ9Il-plFJc`b=H0w<LZzf7xL68F=? zv%qeoo<?eZdK>w44xRymHZU#MSAO?*;&8SCr?IzyNU6zqbsX+ZZ1{hvd-ovElB>=y z>)ln=?|1if_jJ!o5*lfckVY?%M(+iI7L06mZ3D*PaK!qLUBmvthFP!)97Jqjhu3z5 z?XbP!*FQE714aaEz*-OzECM}{&^$HMGt=*$o_;^8x~ly7e9z5a)r>ULHS+APb-RCc z@6DTe^5n^rCo@l;JlPA_E77p(lmJE|1%ZlRA^Ys1gI%eWP6RkzSoHjSPdb#Y!Z436 zyj2h?a8$@<WfWl?rNS`qy@hgDcN&vSwx)?QiNeOTET*J`cT!dEG#1+pI_sOPUQfX2 zTX*bi_h8+0H(OEn96sE(VBLI!ycA*Mq!%~0%&Oq?*$zM)RGewekPa0*#Whx+mO<P} zKM6jrP&&!K$%N_(r_`Q&_Go+NNw$mNtMKL(4uH7yV#*wgKN^U>jqE&@Q1S`SK}2=H z)#-=EK)2Xd&N!B2c#CFU#&c$4xD3H6)78;QR!X;^JYU+jFG}D|SZi-(HFXD*K`qPX z@Hwef*KG!s6Kq!s6IgHN3v3FNhUwpBlthm57En4bqO4zrCR#dQbdrc=(lvZho;`7b z1B_l^qJ~f*`3AQ3>fGH5xQ!*I)7(B0a=@<Qzbh6M1QQHs!*>+TJRQJ0$+w)+K&xr% zR@!Hf1b!|CBrWAwd-Xbt0zo(~3NTO>vK^gu8RaG+@?4Y&z`aWO`g8aT9ta)Cs}x+K zGvozc(oCF7*{pR-s2KW1AujKzkTwr+jJpfc*``!lIH)j1Xil8ao%f=B-F=;>zElE< zlRT#z53j@r-UckDEt9{r9m3Ymt4$jPJhbq;d3#WUI5{wszcXP1nY2S_L3hxug8w;` z&DT(xj$4<6hUW*m&<ZL)YfQSXp;yOmZ9DD?=TW<6R-bKW(uVSjqx29jf8s(0gjBux z-9x&(AccS1I31PnYUm37q`S)YwQJO+`1HjlV`oATc%<Z;xWNgy4N>I^53-GN7Ct<@ zdtW=SeRrE=CZ#utYxpg;9+M^Lc#nL6p5i~vmbkG)hhp`6+l~}>92+=5Y#J+PeeP)? zDF3MpRNTsgl(v-4C}?kTaM#sqxa7G_TKu+eL4m9L3K|{!NQOLHxABWAg~Io=N!rm3 zWZRAFx4DBm)*u^DJZWjH&u7!CSW@QN7D`!a-pDg}=oX7^moK|GGtoA(U1^%mUW;ZN z#F$DVfw!^+oXw8>w77<Yvxs=^>=j_oqO{!9<~Ji7nVgyL1{B(JRLo|qoj2hFdh_HW z2e{IH*-oWGx+Em!gZ|1mt(<GpQUhnpOYYFhIw~0$g<&dvXv2i3O<0d07aough(k!- zp>xvl?gX+Xs^%5oxy!fmRVGM=cm4>BpvV&#2i>}B`Ao8e1!G?Po_tGW0H~++ZfOi4 z{qR@;{*@Zi+WvO<8MWs*JR38(4RV4e$p!zx@1iX)2S)~PTBt2eu$Z|4f4n=eAl`?S z^PU4l;()go&b6;U@gxf8!&o@q!vY0960>Ur@Bk1SamgYdbW!%&Kj~U#RpI<~tnugD z0Tx;G0lk5p5;O&|7)n!x6ep=-@%*ezR8iY~INJy9+OroQ&RdNF&ky})=xM!I+D@0$ zH|@~F_O!IV$#Z--A3Q+c&v=8&G*E&k$07WzPky0~-zd{%tef41bQX6Oo3U`d4~6pt zyN>!GRT{|uaj8LC7bVi?^Xvdt3+J1$a6X#%BS#Krv1byO5@3w7#ylNfiwEVR&Q|4f z2qmKJ(MKOcQF}TQs-1gxw9PxWB)%xuLr7Q8p{0)n)29ne%3e5rI{p1d6z7MiQ?0-# zNb(FnQ0Edi^-7vhhY#sTSWLT)8=+&zo<pwQX!kyF?;3@(6eyWdO4^de<}N>rVy}-_ zI5RQWh78$(h4c2E><*#)a)S%qS-gTKsT&(kt`1`bUyhej7gt!op2kJeeNi~GeV_5o zo3L<xVAEVIoNI_fc>qyLeX;1oDtrXpLsr{brSZ#<YcNpGNTVL#dtnFOLt^tWULyK^ zsE4W}X={C&O1V>Y+rJqXahG;oxj3GwaZcKWb(7rbA3`tX7BUvOT`dM|N6bKw*UR36 zPYO|`sJ3FnDv59^4mBUx;0S++$EuQehzsoGm$FxxQU>u1uFxy_+pDN#CAjy|`7U~L zn*R!g&~!-O^LMNfx&@XI>sqag$~!a<y$d4JPSG?fSx;vkt7YMPPh&p<sNiCx)Q?;Z zj)9Xv!V^O%`H5aG%hEsb5dP&Z-&dbO7_xy8fCWcC+sA;FTs$g$<tJq<vTd*9IOH_k zq<_cXpqJxk5Mkyu;8k#pOF*IzX$JnSvh_j;yYeta2XC0ASfMXx@RA*m2-L_iQ(6X! zoHNeDokO_{PoElK6|c%$&z-EIY<k}ZHX(0b2v<fAMXIJ$(K6ns{(1mzvH01ZmIe*C zqNL}i;7wf{&uh4QLqCpOtbAlwl8r7!wJ^l*)`EQw=ak%XuIHG2tj*0b?{vs-JZ{Nv z0MOIsmG2p<aesN6wR}C(JP)}W?3FNHdRYRGKfYVPYs;B12(!Yj+;J?O@sm|9HaIJz zGJ&_mAwZxn3BrdUP(j0oAzawGc<>(-fcDCYN|$*O#L2tkBz`fz2{aQ|JR(55iq~}k zLEJQaGrF;fk$>qA8CwLd#2@l3!=8fUxOHk?AI|vvWsc+gyURCfv)}?VZC_$SNYg~V z_{z`AG<9INVYL5F@cIm5<Zo=k?W;uB@x+nC5B3=Ay4TnvkP=@wmfCT<#%eQ+vwr>8 z|94!9Js#XO&eA=new;t}!4GDRpo~)CEFCnSsVjvG{e&K{;>*v!Qq_FwIRUTohcxSp z_$n~I`P0jJ{+nYE0zq7$mJZH&HRSu;=RVgSfBcE;aFSl%_{KM4kg#XZp7t|8^Y`2P z-uJ#(o8MqQr`(hWj3*bV6ACvGP&E0LxxO^;HI*HxuPOdZv-+3yR&C<-L$qkQet6c0 zHFBrR1sDC{JCCr>nP5@V1r~J;9@4smUT)*uR6Bd-8VeAQqFDZNd*boO;nx**{?0K^ z*xYuri}yEv<JV9`A8&j1?rOW?lYi?cexkkeUGHjJFcekK=r}%OP7qQStwnA9oD$Bu zQ;~-6uYa5B@^_sG{0oSteEk;yHnNIlrAv)p{f~c+%17u%XmeN?0zo0F1*Hvd38kMd z8+?!A&(37PsZXdRlnp>(YUQg)>dLz)4;1Qz8P7B-Y-#|Cs72UoX;nhMEIG};H>kS9 zL@=x;);jU`kUtL(R6xtX8^n!HN(*IqO$Dr{+24#3c7}tsnBeX`5R0$92lnGWV^7<- zZ42A#Q31i&x3F9g?`1ml2xbZ>>)8pLe`jXP)SIN=<8}nxRg_tt4B}$_07V^?f~Qt9 z7x6u*Rns*lS+`D~<gl<4Y)5qheHx3S8*Ja2qS0Z=OZjGLjQYU7#ld1KeQrBp0Eo|8 zEY9G!b@{5kbZ@iuXeRjRlMzoLZGPwO_Q?1DK-+lFee~sY;Lu}|RoijuWej0IhTwLK zESQ3?WuY|ukCKmvQuJ8(!duHS%dbCd6`T%4f*Xqow@#mJ=T4n$$LTCCoH$MyPq*7B zDpy!}pXHR%4RQ2NeS?SpROx$ozzU;B?+zlTIH;@!pEh0)A?r-?2VT)?yI<nU=iu6{ zeYGrCfo<n*SbQr}<_&I9q741rx{;?;endC{zw%L`f>I3ru`^VeU9f=(KH*_99gC23 zMGmDKiU;}I_+6nbeDRQ9!bfWAz}F&qIf#(=%`5PwDe2QDqz^v_P14=x-k$v4e}=8S z#NW1Lc;Ik1%0R}z$-t37VLGVJAvZ&ZZQC(!wJ+PFD#g~WP&cQqUurk`CLPB-l#EWn z_)d)F8_VVuoQ5(E0jcji4}Vs15I^J!yl#6k?=B-Oi?YMTt<XJ#ud)<Z*(3gS6%7`! z?v-8>3}W=BK2E#2fUmUkC@<t02aXO*%p>hU!f-ih^j!(&KV^;z=4pO+Z{ORFpmd(L zQ&h%qK;LyN009KP@F_nhoGyS!tC@$syG<QA5;=2=ZI4U%MBcb{Gm1Fy!O}Mq9?~qY zD6>lTtyMTLAZxC3c-Pfy`s$vJPg^aUwSJy5F_%8wq>cHlz<ZPi%2ykVh4e*sYv4j* z76sz87C9)6b%&s0z_JO&d79)?;jCMsC6xCUE}*bpU}8mQZGBARuh7LGCn{8QcsXsx zcN0_ZZi`wV?fG+8!3+5KcHFX^Nx>X0S-^V(3jBE#&nlX?OmPS!_qiyYDG%S2IbPvy z_&^Ivl@ZoMwQS371o=#Ut$NQyojCG}X?wVQ6~0dV;ak2BaY>`XITkf!ZBfFvK2xOH z@nG%*NMHY%2WgDUjXMbOBRXG+<8!_lk2r>#hVX*#yJ;&-(B?VZd>LJV&9`cQN;l$( zhmnP6*2Y%05bh6CGh*?BCoOyNwsDYySPrb9aQ5K9sg1kZrk(rS=3V<pH_=|;aF)lP z`bOJ#@KC$!@L?7nH`7KK1y-r38*|s4R_zLK)z-<klZ0j3(?xtAKmPb*Y<HZ)b;1F5 z%WR7~B~S|tkxmK3F+V5+fuxPQLEK&RJgy{eqU@YwA<cs__06a3k2St&EO-iRdFrw1 z131X#Q^#4{#JYEpa__<w#XekMxzLoh5u#N(<wsBuH68*MajZLy^DLC=#zBSoz4zZA z8c55EgghXLWmdl1a6)s!w4l)6`yyi_Ev@Cf!$*!}w~#W(dh_rv>rCF27LI9@nf5s@ zL|Z7+eeJ7XMd5s^-Fx4C_(9*nIAkvP@;T|mJp>3bq)8`=!DH=(lc(G1=Z@PEvc1s5 z`tFXxS?lH+gOt1%cVU55!3T`}kIH|Q?<eWA7m)||zu~_4qMoE2i7oFjhH-1X3$5X0 zQ4*4ELxll#aEt}?6DN)__~(#HCInmAMO8RdpDy2;Mn1J313{d4u%Eo>PO#Ib+YQEP z8#s9J-Zvhm511#u3g`LuKwN6bAHuLb0V4&fa&=}Ar@$`AdCoie_k5kAg2m|D>XWd9 zT@X@%!=t$OJTg`yj@Z{BZ?^oGUT``Ag=ck<mcM?hJnFcr(w0)2JjlH8G~6~>W#&O> z`Pcc-Fo-t_uZpz{%7`vu3r}I%-?~^R9$7R`opjvSP(iw`DR1FqT6q~b`CelYTl#9g zBE)4exD8c7U()mTUSpw>W7U_LfG<fp`ZFX>cxdEz+a%>8|K$6UG)SzfxX{lU?h4IB zBe|vOS9c3iW$B?6C(0|^JlASnSst(n@4-FL-SL*Z=yqU64T&3TezlOpRdn~oFiTU2 z$P+<#z-x3cRXz-fb1PWllzzq6{5szY)^7mvQ?eOF8Zs$vSFRgN+7%Cp%|J^I18i(< zW~-yC{h2GUHXeAUaooW0gTCIr()rc^nr}4eltmP*wgHvVJvb51%Ww4)=PF9v^+4`{ zttybX$xr%rm=r5`8{lt%mqPXDp@e=5DSY6vJ#@vkbEgWU$n^*=<U=8EF>$g^b?LBi z-Z6byI9G0@;-P3<@YAFNt^Nql@AVsi^QosXR-P;R=<mzJV5!ij_>1R(#?m?$c%&)W zFEPg&N9jDdc#iQomd_YCOen{O`tD<;03>lO%oNWQe_A^DzzQLi_sr7<S)DPv&(Nh7 z_J^^UG#d~qIK)X?9omZU__?dedw#+&9r<L;1w-W>IDzH2<SQ)FP;XNhQRrqurE}b8 zj)<iM7V`paaQK6^8`0)B9xRoS3b*2Y!~12sSliC4ZPYyN(4qCY)EKY`?xruLclGhg z3Bz=uI7{F5&pz`9>=64ZI~p(M;J{1tzYjh1Q2W3KKA4@2lB@bS_>=K|!M2oM)rMah zW_Yjdl-7V(yn6XwF~Ya;A!Q!b%c}rL{kqFh!y3mE%k6*o@3r`@@u258Ji+d}J$rVy z4}bV0?I(Zo-)Xycv0Dm0QQ<6I=Gc+vUAktjE6*m&et+fsi;6PJE5~{17kTidA^*R8 zljmM{#Dv)SZ9Tx(!F$w{@?JUOIHZg=)!CqnqHnp4Zb4VAPd)W~`^uNU%<n7s@<yL@ z@qF8lo3?kq`{DNR!{5_>>6d;H-_C#4cJJPi1Is`4WB*3`zy}{`M~)mB+F;29Wyq>N zq-0Mwdc1Rq<fl8A>CSMzy%>r=+x5SStFnImIjTzJI1<k47S0Kzv{sf1u@aW05W9}A zJ^c-Oin*8HjaRY;Fhd$UIVWmbaH^b)A`l_3Aa={Cf=1<$LPKTS+Sby25Zl2iXoTMt zEhQ{h@Fk6}9|V?@Hz&~x_*v}=XRT^ibgzMczsjWc5|b)=thS5E@!j`7(2m@T6%WeT zO>ASG+ccj6>>?fXrE6FryNX6J#A%HDEsupW|CBSOCV~{>Q@I1dB9Qp{Fji5fAdP=v zlt}skvmE-AodH*swbNRb0?&i@u3yH=iV5ebW6!q7zxLI3{F$fP4LTx3ahs<cvu??k zUNq3#YzKB5-yADF4yK(TPIG|AtsA<$z+x4pu7|)~y>uO=`B;1K-S2Hb^kaXk&F<Y# z=Z2qG6vJ9zEK!~n?)J)BV$m&97V}sgKvaENd}+Xc>ZuR%?4YHK0|^f#iw|pH+-3rP z9v_USo;%9nKlpUy{@l@TU<r1$ZDFvm8QN$`=iqutpP2OdDw{3SH1&n{0HR9RfxOl` z!Y6|U`Gx#?XW2U&>qS=yPUL-dz%TtlFy-kA+9-#?Po;EqQg-V4ymnDRfyYn&w62pU zR2k?Ir3H26fF-`gm<T#}FiprqI3$V!L3)`^i|Q`u#I?d}P}O<KHWEc3N)GwK_=XwZ zUoPH-Z96lri!&Ynico(|-}AAJMNtbL;%u4x*%r0@Hof={V@2)`?wDr)gNS^u_%~>u z=dpS_w}3kh%Hs*L<Bo(G<i<}eu$QSv^A+aWg(Az_%e)p(>%q%!UQ<}q>Niz|urfhq zj+X<i>{Q^cYn-^lAdND`b}!e0DnH~23f{njHZDRriM+(_0S9!qD065_nEYdXTW-?= zD)j`h+8BJffdv>!h{CzGZTNHFftwlMC&^<2%3Em{t0vM;Lq886O?~iv`v<<SZF=(? zQO4n7<~oX;MZ$1dvk}X@NvwSJTWp=^+g2-QK=2OFMy>A_qeU#TX+P(YKUf#<#-+y$ zTgW{CY(SI0z)xkLGDKOTV$k}@;ty@k!}b;zaL0katJ9}1pgh}+Pu-m;oTUYMVr6V+ zuInEwS-)9MTva%abFiT9K2Dyz*e>G(dXB^Y<~Pq_O;202t$~R&%7JuwtFVr{+oH~& zyNqiM+tPH~vwth{ltl^Zf#n*M^&CoxON|XH*STM3AI1$1aHXxIz;w889mw2HfJTP~ zDvOX0elY*YCBBD8X|M7~=dI3Py}j6;<@bCC0wm){+LXJL&9#NI@+G6>&u5BT@-JyC zxM0ESwrAt;pSxJ~U$s~Hsq!F#-;7IG#qZySyb@a9jJ<j(drJP)WJuzK0>C5x;W;=% zINNh6oS`I@q$?o#+juII-0joo8&)Ri-%vWwZoy5|)?M_yleCQ+?F3e}^VT=YR_n`l z6W{ni5O?WqxxA*}IW3&iPY`&63O{+`1d73Vl#6?i>Gbd5u1r_%DStr)R7nHuffB%# zf1ow8`V4-Dwc?p$VR$31C>&3ihgYh<N|JI~dg~xE5#)sEg6$Rj7B7*;T|3)%?8q1+ zd7AG4D*y+cP)6AXvtt1t&Q~s9iDm6PR@Qg1Wm8-;PDxqITFu=N`n7hDtn6~~Eq>|W z*;#Oo9X+5IE9+VM<w^Q%Re%;>K8Wlkt$BM{m$_RW%I{%)p2ohHMeuD{25(~FThzPE zPCZMO03$r9{bM~h#tvujXMG|vaSJ<`_8+(_;~tg0WvvYlr6R4r;i3RycpK%)4d`$g zW$z30+b$s9`v%5FER;E(0mblwU6D!}aj~6P*Vb`lDP^$zKKl$l7oUH&?LW9bO6RRR zwoy;Yxt=R`(x>>6z*qkept~cL|EErzgs!)cKeO$~{dY5D!@`+EQs2m-fe&ol(B{}Z zAv^W<7|_5BjjRN&URIxNJ+=og>%Gf`;z;9H8o$?*uz1RgxK-K#gwcje9;|OFoXzK@ zmm&7waDfHpzY-TL(l?23@qypcP>4|FNcf0I#WQeiz*`z~s`3_kx@D?zRaxtse5{-| z-+-<-<~1msVRqmYB?5fN!4#lkDt_kXtz>F&1!&S42^f;7;8fHk8y<($Q3OZXL)z3& z(wa|=H`eBrqLXjQ05JfH`3I&7XK5P*MXYj?cB!i&R)ADr)r&F2B)$lnjIxui!xE*+ z+t0)fZH&_MqBaNoLvP1D@V?JWF2b{;L^_N!{_Jv0+^arUVWd1}-!too^#c2C&1JNn zI!SyHr~03mh6^{J65^9#(j{2rZK$k#6W65hPJgj7Q3~f3cRDiWTA`saRLCWYbc2*r zg@AJ&6|%!O^X8|B$=%3YKIczRDSY~eqGM6QFQssnA9#Z$`eh!TJEI(u18l>o4x5aD zUfhzGj|uWm{Z?}=`KxR<kCO2wCR|xKz_30S7HSc}j8r%yMj7kb&l{hMdvF-;c_!Gr zWI<)Om*M?ey$>J!W`I|Z+n;+Lyr+m{DqYPxO_zH_x$(JZ`uwOx9wr!TP2RqU!ucjU z{;tE_j-!jl;a3XT>9neF9@@1r&0~n*-Emfpxtw>w=Rrbzd>+Oc#7nzQ`g&d+e+jSv zm$h`|g)KtzF^?QtKg{p#SLF)}TJw>LZ;Ow@nR%^;2HG!mx>A#s2ibU~ZVf{A^>!P# zQiS>5ajm!mbDPe8`5uHvX*CSG`_P+>zK%;6){kRu<pBLJ0gf4BR0IV3%vlUjzV_9x zv@d_@3+-7JX|>3_%<ktmvcu}V?|om}yN`1=GI+8KHNLFO0S=yGxb|My8z#q;4DjvM zufp}!<GjYNl+}NCx-5ZhWQjSyw30r*@C(0yYqQh5ue9fnJ)g1FCqMbg_G9QS9>S1E z!vx2S@}WjI^X#mXRpiB@k<wxPS9s&js15*uyzaQ`!$I6%?@Qk6JpX#Z4mZ8dxQ2rv zfC~;Po9%}^FwkASlKD1P&Npw~rhR;+{l%Yup?w|KeV+NEySI0~^BwI|pZbw@1owIW z;ZOhF_W95K3G)YbaU!FC;D<iZ{>CT1KYq|Hzw*TeE#;Q&E;0>%^PaKzy6RN<`8pFo z<koqKEC1JbS^w*Z8F1@`xh{z7$n+&qEK?y6AI`t`EB`3U9W9$x^5{!cM)uu^Dj3~b zYo)1t=}fNh@Y$aNwhLZiXfc|>f`Zr|liRK&NSVk#RVyO=N?1E!R>`8GO~nfxjcIwN zOG0_7^(^?HO!2pb^DVbosc_WFQN`*l@VkN{XPy<ZyYcVxmWSWN7UKJ`bSC^JiXD1C zi|#<d3HLP^TYNWg()>oO1eYj>@8+YDP@KizXK}QX?460u?^QNKfCy2oxEAa<h;JrN zy;NK|u2ktf6NM%3)1}Z_L22~DF;04a_L=q-{1-j{ji=fo_)K!>)+Vf-=fSBIDq2-~ z=pt@GD1%mA%fP#V^4ZDH{DzH8qHnZCtR#QrC;#1c@QrV3%XHQbAUt?s9&5JS(iPnF zdo8{mWMF++PJaZY9(#StFDkfHcoHFsX6pg$NAKtvQdDJ#lfosGQD=`IYma^9EA1(^ z4c}s7K1<_Q;j7hvmM#h(CuY)dGuwf$GWiYs0guocz!@BaKf$5BIO-C@yS!z+L?KI^ zsE`bwc()+rp#N~oFFdbUyYlShN9E<(OPF5X`!768{B)4eZ4m{hu;+1IVEZtCUB=i( zoREvCLe6wT)2eSROyk?p3g3l|ZryBr2VD+)J<-_rUI%NH)WR2+wU@jnTw%(a(!n@} znO1y!7thL9iySS%RlwSI8CXYg<RHA-@ntMnPjg7*MJy(kS<JA;wR{~@>6|#yL0pO+ z!Z1JIg=s!j2dkJSFJ7%9zb!EVb}PF|VQCdNBUleQICQ`_k{!gg98pXIyTeZ&D8jWg zzeSsnewP0_hnso;#UgEe3Vt)4<+6TEV}3I(obfXs6-7}lSxV%{Byl}J&_$w6)bYG{ z61E6#07#wL5qi1PV9!TB*tWdo&G<OKzyV%2S-e`tkLiA_e(`TRi9<(CdH?`G07*na zRFWSPekV7#IgD>53TJ4EPh%Co4zjf-y-wYn#YM%^(j+Ul`&h|mkqVLG1QwFQGsqz( zKfc?Mmd`$TiCqz%?0oEb+yiW7_r~@;>?(k-rpXf*7UNhhS$CNXIHS{gnY^ie>T|Ij zKXJZYxWr=2+@|2WbvuWdFu;o<*yvc&s%X`JCnN|RSxTg?ZlGY-7p{kQPP7Ae??hQO zPoBs$=rxJ8&Ggc>HjNCMS-Qf(f!Es%M^LJ8Rz~yzYVvXR6b_)E(8FiAC^%SO;vQwQ zb)WZ&=ipqqSbSHL7E=->(2QI08Qem%UjKY10)_F$i`Gqvn|uu$@-#obRlKNNc~o-Q zws{BDT6_V9(fCCvoqOS7xOwE8e|(gXYcA_26tR!soBv|T*Ky>lFbYhi9g~lg$?&$g zYk6jw#0{>&(AllgEKZ_up4+;!ZQQQHd7@pxU-+39&f$86aQXwSa+MDgE^G{$SOb>L zcV)JHS0?B1#dX@%DR#3=GXc~k)eMS3`&|{zX`@tbP_aam#d_@Yq;!$@XHXd1HfP0w z_O$_5Qjy)3uotwaw`|nEbu6#g4qwET#1*VzT|Ct~dMj4exo8^%nK3yP{^5HNiX120 zNw4QOSPo@`%I@8J_lRZE*}f1@$!CfVO<AGR*##$YP)?L}Fz#ruPBK5wL-4>rX{nMV zhwA~Z%W!c>{eqQ?)XI4Ky%(ql{TEw?c@*y(7)MC6zW8Y&hLTvCz~E0V^S!_V*SWLj zn21lZxU~uQB)iDd&RBV=RWeb{I#A>bpg8VP(ZT|j2OoN1--Qb=0)467edJJ^+gz@; zloR14?i1`vu>IS9gs)s)WI^3B2=)1AkK)JqSi9@c0dUyKq8EyD`wIEd`UH{iss&1+ zs#MnXA`5paoL$7Qg>Bk2+YTPN3;E^5a;hwxS;$(ea85adWC2r1X=8n-uqo{-xy;k6 z;@Cz;&xD1lJ&IpM*XRYMr%FhrD>%j5Lpg@8J!KKy{+JKo)Y~^5U+@i0%)9eN=%bu9 ztl;<jd)k09pOn|T|A)3^B`4V+KV)FwSdOyV<|BEnj1<nsD}Lx8d%mG*QVuzaqiJbF zq068s)@6#gh)z*KS|$b{Njp5sMWzjW;rJoxDt)C6@}gX6xep;c2)C{jeMFztK;54R zxu@z%wR$f^QtfNXT=@=2a$5xphRMjXDZjjcFCOrJ$rIWyZP;?rj9@7hVbGNELMfaJ z7t_=QtUT6xr*+47h?IQRhK-W*#b?nf)CRl>2ZbatB;UZef~*yu#G7yOeWfSV#R6L{ zislt|CoN}3jEj_%f#9N5!4|$hntH|{6g$rWIee?W!mJ4JKX=QU)+o;6CJN#b8ge%t z2x)lJjU2`ptL5V60{boJb>SK0zH*uHa&^N4>FY`^1y7*4<g#!YchcD&27cvb$S-1& zevTfBpWC^$uoJMx6Z7*WKQrDE*8z0VxN-?TJR0V(*mtiUC$B?Th1bi=!~NFbTdv>( zD$-Tj_wS*Z-}%XV#uJvi2*#JLw+SqrCvJ0?;4+5_I$rDYf$trDjT;4!o|#)^kh-bI zqPg|NFMMtt7=IXVtsQ>@sJ<l*2nSw;`MfqRC?zgm(|6ROP37VEPFNYEnK%ESC_@+y z4OHQ*m9q+Gs?tk77*HS4JH()Vdtc+?N!n!yE<E$_T1}g`0QGwj!06704y{w+Y#!k; z(knCUBVE{V?iYOsh&l(E;cSExC!TBn{LenuzKjLu4i?JQF&sE>0Oji2+FRc8R@xTz zMqKAH&I{@iBRSe@_3m?umU0y@B+9G)DLL?}QNE3jB{T1o5IzNA$8gs%?t7L)mw)zW zf0pwbIJ<#y=CNbP<G1<8fBeUrE=C*&UC_-Ib)i9o%I6uLrA<l>Ea%dpgL3N**_$SK z7SZky+s{B;cicOJ3x1tx?;L&IF)Y*i=)Z1|w5`{%;5}Q)u3jx?p`o`k4|n%Y<KEV@ zJ5XbBkoW2Kr+@lq?F%TJpL+5eq+DTPW>fpYAN)l7TR-+G#>_9Y|KcD2=j|`P@aJ&@ z_u~0;?W2F=W9>&!MnCe%2f_pCml<a(uN<pJb}7sFIY(JvohpIu#8JIqum8Q|@p|*O z{_l)KvEH3w8pF1-PD0%|<53LcK5{;ge;=0`pZ-U`oJo~J(uUkEc2!i#(9;NoUI)HA z8MT8jz64U}Dr802iJE>-zo{WGd2{u_E7r`w=?vjuPGKUPFb(Nt5@Gm@P*;J3Wuz`I zh#7_REvy4oIIC#(V7y!SM7_?)XlDD4_C8KIz3-v7x9Kh0+eIeZSFWS<&@UJMRqaq! zR!u74k%X2**8wUM&C3a?bdX8y?8K#%8&ziG^|;1UL9Uf%I@w58J3Klb!}w_#8DbB0 zzDOJo08{O`0URbse~yEUjz0Nh``jP@Q9JqAm)M@Z(l#?G-_Ai~j>q(&tRE!%-7yA; zQ*#`o2*vf=JTpDVR$~;mb6eV{{=I*{ZMo}UyNypo6?|?-nw*+pazBr9i$jmHa>$^W z&dN!N<@G1NT`8M)@{vhgY_LvJztA=vDWgznciU4(osjag4yPEfZJ{2Pnb01mQ#tk6 zW9{TqPqq`!KhHoE>unV18<-?7qSW*-Lano|qxcRV0Monlj@2wUnQwRsxPH5db(y@i z!NaPcs4Jj$P7x7Av<zM<2JHA1JWlk>?MW$v0Tf=7p?M5kE%c(q5(m;-mOhw}S5(w{ zNK7eKYA|Dknva+C5+5yJNti*Ee9?KgzN1(rzLWJDK$UV>g{WndzZ`@ZxBrCUvz@Yc zX}|Ugj}3IQ{iI#;9^NI5y9`WcJ5IepPZdQjT$rD<(^6eHr3_}<Ied1Utt?ki5CVWY za9~RtM3F!wc)~VZ0z9;V|8An_jiQ*k6Ia{T+AHwMqnGO@3oTB{#OW5i5Cu3HY2ECi zj|zQdkV;JX&J}J4Dz>o&6cr9wZ_<9GowU>q#}<@NDuXX!)qnNcRTP|*pYX^scv$-M z`tvSM)?s{Tf{WJt3S0A&=Uu?sMmc9uY_E_nEu?K^TbI7qoD8{WvGc<pXq(^iCUz`b zL3wk%oqh3E+jrnl4$zvJ*21|gPL`r@b|ORFqO=`H;cI(PZrotO;`FIY&|sW_C~kf> zxdpG<qs+LpL>r#6orc3;PA3F*s#qGM=zi|mQ>58T`S;+5bpuw;PMnkzSS<6GsT*mO zG|<4j`OyN~iIW#_Kf)mnC@8ma;McCb+cTroawbYftg^Lo9z#(joh|=ZqpnamU%7M* z>qrh?y|U7d+_x9^3LNyMe2&7I#YU`crkDWD_*=P#3m^^?gceTXq(LT3(r_3sgJ6}5 zFfs+#diS0Qzx6{qtVw?jAmm?vh9wSh^N*yy_jD?Tt*^*tL3<687V%h3JESuoetr`b zlVlJE-VW`3=QHxa_<lDYj5NShW>x;CGc)fz4E$Ch!(ZtOWv$t=#4-;r;PKOSlxg!L z#Qfj}K+$i(e{_69JgW{R2$ljWoF_Km&zrtr%Wf=a`DwX!Sqo(>V>jV~Vf&6<u@JU> zDZ|n)gWm-0#s0*z5hlTHnszcX$m>f?0G@sJS@>|0`qsL5*J#I6ubW8X)JG{Pd)<h* z`J6m)n)Xg#i?UZA(zEmjx{gU(w45PmQ9!!d|HPsNS~ywJ!uj&0E68-*w%~(#EB%Lb z3;E?GlA6vdeFqgKzj;|_<@cP!Hj#%eJZT{viwM#<4ls}WXl(kr_n)%Kik!t?wesg0 zzK>NFD?9aBJdO3z82!f$WL_WNSRU&v@)~rkV;9CuFHNqo`$|RjhFKN|m`E)nYeq71 zz&A)s6aQ6_5@fuajC*d-$GTV`jLldlcRuMmP9#HiI1Kznf#3raJ+?aJ=K?gieEAa5 zme{4R8-MJ$Vxio+(a5<N$h`@6W1uPz4l1&z7)RKDS>I0lPn|lB;`<CTZ$Gry&Q1x& zPcDcIZ6Rf1oM0XFdPpJ66*(J)Gd`fFDTfN@y$A50KZ%7idnLYW=SB_<WO0!3n%!#J zekBH{lHJ2=zL97(+~(sI!qtSlCQ|(aw18hACHEdSJjqO>YnAZviArogTP|~}Ywa`f zsbA~DtK#KJ^oGkg_Mr-N+pkJM@$qL1a$;mAKKmowzPDd~qRx^Bd6{46Ot}3koX+=> zt<ucz$xj4K%P$Z9&9m?Q8n9$ss7n>;XMey0<rY_Q_NN@T7R0U6_)e_Ejm5Zce&bhe zlT1_cZj~;Tw!^480)+VwX?e@FiYoNAAm(lXhWv%3vU4@wkd6S0QWvy<zT$06>(YGc z^Qx>6&jPCq9`HB7MNZm|vgPFp=c4_9x3Z{T0aQ7fSCzF8?Kz8!eXf_d=&mCeCdfae z6IVhz?F1XprturUr16<=;++)UxKckXLa&VDY7VzcV=PK8)3BDET&!U)<0>l^#rAPp zHq+#}SGd4sDc56-Q}KB)Jip?9aY3X8r-TF4d+-8beR%fqpb-a9^gqZZ<fQTBBNzP~ zH*}+t&<wbxs3co($wCA1Q(lobbMmmv-CdJP$O;!#@GxGIh<C+}|7LtXd-*pYhnETs z*pO?;BD^L2`@7M-64n#ty<QSdzEwX(L-Vm5@>I|gFVV9d2rTgnpPHu_5&DuS<F#en zw=vFQZ*Rt6j{0o#q5DAD+PQ0fLbS{P;2t{o1P%PwU14aAn)HNaoCRVvhBB>q4R_(d z2!=7Kt#7;s?ob#dQofT$SoR?V&<_!xIKoOlO#2ELh@=na=|SP#-DXL<D4df*8V~t` zzhk1RW7<;Y_4Yf~YvEG)o2})ptNJAQ%qCFv<Ib&v2iNCP!}N|Dgk5<R49jjkdCB9B zajspv)IR&ipJ|`{lh3wYJ9j1iCKmqhz4yNMp$~nS@(V+Fr9YuWg`~90lkclx_0iU_ zTAm@nx4f;z?^{OrHUouw#|!!_vWsbsv5JOZD&7C#&;NXOtIe`w&Vz%0=I{SZ`zVJ6 z9y)k8w5T(w+_mnRV2-1r%U}#*ew}B-uheJJ=asR53zBX`zE_Sqe36&$7-`)Rf}f22 zx?h&-^#<Aj_WSDqpR#*csQRI}XoF>4=u_c5g~Is;yY;{HmtSsw@+bK9e(Z7PmM_HJ z+Q(5S|KKNnpuP2>2RTgenf5Cf#_HB@j(NkG7tXZze(!tR5C7;7<A&wK=m^w}Ffu}h zsQ2l5yFPBL{&_uRQ5vnUuDVQF57hO>d2KM)SO3L&cP^7LY%8xT^QYj{KkYP-yGsoV znjgeg`D(=}98@5wTvT~w!*`;j!bYKB!;dn8_f#k_w18IO6_*Q4>V&Bk=q;8poU}N} zHOx3`uPB2uIVo#lVRs=ZY;wbT8N~$?AykrdJg82b44Q^c;>Al?8D3p#_dWPvd-y{i zYWKhW?QMMH*7o96lu#VZrP6h7o&gsM7a7uy)sD}BOe`J|Y*AtigUW0#4Gv<dMQ|Nj zrq#8|X3Hl%RB~AsCs4NjDXl^&qZ3uj=>*pF=H(<c%1t|H@|gv1$9pQcX82vYc%gmy zi(hO{|K;a66zI8j2@4>nBiJCYl1+Rj{~l<h;&}spSLvR!3V8FzA_}i-ZRg$hx9|VA zf1+)?Yk#}R)_euBG*{{DKs$pK1{SGPtgJ<?cNo$*bk5)b`jA#-O$HOtfvk8Qn1*Ld zr9W6*rNr%r4IRAj1`r?AV+fSxt0=^tc&z>PU;R~k7VGUL_+Xk2dJYBr6n95iD^6<3 zJGcN<zEXJT{z2Sg9gUz;0d$K=au|1@DJTSwlmT$ot92-_;-Bj9?Z~CS@uF-bZ{yjx zR76S-<M+XkJnSWJo5snOmKV}f<)(41^VBc&wN6!R8YWM8@BAxG1B0~QEo<mZ9>JmK zL4Ji($Jv3C6HaQ5y8=|$BRs(YfcaMSRs#=l46j)(ex?(j8z_<;%uHa_vi1_E@^h_H z66-k>yXRO0xX$Y$10^jzr`Ucui6X*5QLNM%#7R4G@#hs>sZV*#wqaSUN8iog%LRgL zl_H)BThoN*0}Sh74rP>wkpZ6e&29rN$bof}yEIlQZMtbJ3oWN*)TNB+#7U*S3Ly{p za<GyEPbp(?CB8HZ|C5elguYoY5=Xwt*WR7LZ3QoRbq<*`OZlhZqpK`NIe{Gm*F7J3 zq-}lcgIEkgGZuV~pSp_j<sg=i+sM}it5V*sRXC5~7kZ2dg88USa{=Yl>C4C$tTs1o zZyPsHvoPZfFg4Gewu{BG17~VGZBT_XB}HL$nU&$Q&~h`f4JF{N%_xqDHHE?-CHELI z(q<MID1w@K^BX7s^XIXUzI+S!LrZN7hkotZzYArQJZioU{K;44kyeg`Xr(fN;@E>t zZ?J%O`Xm;T=NH@Id-sr@9Wn0OV3IS*L}dyKXBE!Vw=c)7MprneJpm0i%7WVj<xeG8 zR%HS7?h_%0*;GT?nC;A8$!+8eam&KFCZ_pLd@&F9#tkg)gc!dRkiror&=be+mB;9= z97~+avtUYrQnmy>k!=gIZQuz5rYN||39G5{;!|A~#%s9cc}QbHBOCk(kEP(`m%N2V zCPf2fQYn7oFF0|WDv^dV$=>5`Q=3MifG^xl+p#)jazjI4XUlD@gRwSefIpA2*8@ql zko6LNaDb<~MR=@Bcz3e2#3IiP7ICyt9;Z!h;&98&xaKfUCW_EkWVO%{lrr362-7-O z(Rv*v>$6Ao*|(4#H{0>yylL|$;@85FGS0-Q7l8oKzaf|PjmG2TG5oq=)ejO;7VpBs z*fJO|15GQ0E3mj{u*t_jgFY(FP47;mjkwg<ch_CWe`(H-JXBnWwmXsRx8=vs1uVp4 zf$@-w(PufkKpAxC@ZmOtm9`UI`@zE4e0zOy2Sya>Ku`{<?DoJw7p^?`L?!JcJ|0v5 zK}B55O_bzwVF}v+BOs&Cok#hOwK@~HjkpKfx*f$k?bd(2?8<H1ziFaO;G6ZLrf30$ z^)>Rpa^(_re;e!M-7MHUHiCyjEc+}MoXi)xRAr`IA|Q4uF!Zr^1*Nrz2F_~fO<kDI z$-iLw1eyomlD@`y)hC+&S$Jy0^aMLfX4{TExa62%%!umb9e3|)Z`-@=RTR#`3{`@s zkHO5~(UrmkUuj^By1*s!REqVm;c1|K#Vh#cqlJ8+5#7343u^$%%}CIU`VZ8^^DFs< zvy34f45EF9PV%qgTjV10J-+@&^fI0C>lgR{j?@Ye@v?rD3yx)^YeAb-U<;M+aj8Mw zm-S;Hid51CrqBGOMlSOZzU7c-5>B0((IB6?yc$vvryv-&`VgRzzTh}gRmKgn%D6`F z`K2somq5N%-brh;T*Y^mNmyQ~ho07V@y(YJ<diX?qx>S6jGdUP96&jPpKzU{6d+}J z6y^kEp%*!1m<xO>>?ll`+)Y#+Es0Dh%?AKO8O6TnAzZ$7MDwPc9O859bTCK`@SpLE zh6CP-CoJ&|MDE1!nQ!8l6wowuqD;%StwG_;_O2+KmmvqAUUD&HOW$VI$CU;{qlgar zmtKa9GtJ1n$SnQ#!28A#@2Vfss5W67KnCG{xVrSC@CN#Yg*g?@HEskl<2z`>ca_1q zF3H8aS(``789an6K103`LfFbfX`k__jd-{+J|MAUODZzB&M<egzw1}!QE$@K%X@x4 z^HapG{bn35!$vGoL4=u@7f_W((p3C|KKB|^NK4|3P_1|4IsWPA7Da(fpi)Bv299E5 zCmAj$F(%NUAPa>9pnwv9U~?bpOZxd<{|hH8pLA;#&gScQtJkx*o2bfA@hfcgIb*fR z9;KD_Mf~JvUk*d@K2kXQ%s9aDd@krzhX$5~bKL0>*2y=Nq~eM^R}{`FwERb%J5Dmb zS8_K0L<Ps;3h(h;GSj*tUlq;=-qfS4>z?tG@Qpp(%{u(&f(blK&l*3@zyJHc&-oL( zGB@$N=TQ7>Kl&-kZu-KVltaFO(n~nH`@LdV7E|5%3h&)H+G~m-%yq$)Ch(7oM;Z(r zJ9e!7y}$eSVlbo9{TgG-zw>wg1FV}L!Ri}hIb`fA+@b9P!}+W9Rkxy>POpsZ?|`+` z3cU3YDzK=@b;rF!=6vpaap#z?J;o}XUVGY?rzkwvU-0$joxT7nI9IoCTVmI)vZPx$ zU%7O%{lOpnVf&NMeh$U*QO2g%qObU=pZdwB(s}>Bz3rK2o^Jo$fBWC$aLFll3_SkC z<L&!C`2O~z|N4){I$r%oj8A|oPiSQ5oIv8g*18{B^2^EdP46Z1zA5<sQ^0G3DPP|? zJDLnv{=8~rW7t++SLRQSRVRV`Pk-lkR{oEl|Bq5xDnzZEUU4e8RPyLfL#2+F3Raam zUMg->Xvs*Hyicf9N@wdjiX#ULhF?cv<YdG0RHqjZqdzrZ^P|k@;J5@$zsp3o7C2l_ zB`u?*WqrT^|0dyQ@Y{No6|{YKKh!>f@P6oh?`dbT=sE}EE)rKojaI;u_+(weD%VP~ z612LCbtKkO;`SmdZ7Nv}n`U**I*Q8#IzpLHMZA_y4qn7Z<(bO5ln0=08Sv6Su>%>I zr^nTLIJBZuoS;z{ZXO;)6l-f5h_u#P^!f`Y+R39&w`ZSvs+~qSpJ#%4?fiMHyBFIg z^55h{)73)CtfKq!h07c=y|LZ@JrB3{eDa6dIEVLKSM$sNZkaTV!o4~`)b-@WkOKT1 zyz|efJZC@w?d?GQ=T}~aRqvYA^l@>R2gR3Vlok#!#KrFmSR!j#FgrsoH?Ov{CpjeX z`0@5At~So$vvHY8x7)$A^4^LSll)<w)Zou;by|hfp%CaQr@{lU;XCu|^_OSDrKNlo z9H6@cj#$PK(QnpmEK`6Yk9$Q?LfPayx9em8P1$RbUxSj~7Mw)uYFd5?Eb<U%5h<mv zR;i_A6?f^-c{rJghe-1a-ME`x#kK=taZFx>Q#|NUzN@<8*0P&k9OX^p+<;H|;*Wgg z6~#UGqEY2%xC6Pk!XbCJ#IL<n26cK%i_<6&UchzD4J<u$so`K;YsWF$92q+>%m51T zNefM4Jxm$A<OSWNsBD&>lp$&NeuKW&@iYo)l~a~EX$Vhzc*unwt@NycYWtxWc)QTE zF^c6Z5Wv4Gl~ril!p%J{G<cT&)>Ysq4=Gr536BkN<7b}lhGmg~@)tkbCQ#nswgNlr zwrg&4+sa{Sy4|p2!{|6xqkBL4;kM&#54A<=;@pc@+w;dSw%z;hLIH!KWY!KA+?eDn zFIhhhhQ*SFD-IOYMTsp;mjq|dTmi1~WebWt4j$a39C08iji_%HWk^8VD*WV8U2~{3 zI&=C(l!>&F=}m3-z8xrj;CC#XSC&YN!q}~=QB<22MYDP1H>6#^dK)(&x7rIA*xHZ0 z*n8Jr<h<>}oSh(wgVu%O0sV$NSMdM5z)q4=CobX3_C`B+cpok~Hnxd5@*>?N-zQ_? zd^rl|Iea)Hsqo{BVo^B!SE*&&pCE3rfZ^s@?axT5^{|I^L5RFZJ-Jez$)Yj`81<~Q z@}K-C{E}gjV?O&uIR;Y|EMI|_-vFC9@~iO7Tv+Cr_=OGiP)cA}j(EzD{@skNo2s9e zOdLr&u(?fXxP%V;FcN`A;1}s&J4%AeEBObH%FBtB2r_1?{Ge+5qR~c;>%oCzC=)Qf z#a)B`fwyyDEIdTTmOpU&HqRY!JDZD<DhK&z{wQ)O20%D05P4>Q)(`twq@TNj8-@uN zUucI~rl<gj91OMKZmia<Ic0##ugEpZqf45rq&@char#rvBS7K36PH(;a3`@$U#V=1 zjId1Bfd%mrC-70(Y+HZ+x#!|eVgiNmuHAb$tr}m_E~XMk`5uKT7`Omv+qYbq_;NRr z+w#s~J>kNoyK4^N7fu?azo1g(KXnqyg>0!tjyQf1R(4g;_H{*Z9L2XX?+tHyQxwib z4*kT#{?GEKE=U)d2W~D@3&Y9P(@#H*;`>6o=bn3z6<eSuV-4b(kK_;c3kN0(59Xc^ z{AumvaSrNz?ijLSbKF>{aCR<c+Vq8FZn;-^vhZ*sx5N&y>&RyhfmGqET-n2be%hT$ zq*tLKZvzRrXk8Em;NoKX^q=B}eAhzyI^{9{8I<Pow|%AjBkdh;I7uXW%3-}`(H+`Z z-!2TkaP};2Gu+v-A+CMK*zOOt+WYQ5*xrq78Cf`sNFbR<N}4<jv);U<UX-Feo+-%F z*nS-z_-cso4B~FPH8fEww%<(K<CTT8@r-1DZ49r`1JA`nUGZ6m3mQXuNQb&3CCL(+ zLaQa*GT4JHA*<a-W3`#9yBn+!QLuDF5&1@)@NO(+wLPWu2wf+=GcM=s0DtC4%~Qqr z?a!{7<N%L%#ZHw^tn8VRPhbPxJ|~$2!)S>?`OSd*tlN~GSFe$hv=0!0R`Qd?$!|4H zaXGMzJF1_T!bqJaU!f0l_YqvZlC6JIM+x#}^y|UWrb-vI`99#Cm;gxrrla)37^ccr z`AGL_hnA;|1nei2@d#PyP<?dyttW`w3U_JW@iDvzRe15OUj2|Fl#)KLy!W_;xpi*x z;`{!s(p3t-6~5km3VPgWfqYarFb1Avfe+>QvTcm^m-Q$=3tK?^N!pYdnM(Ud1m-6l zx;&^j#p~8_=tEy@L3&#(NCpvm_=#ESoD3&b(ua1?FLW0J4SU#OGZ-0^yC%v&{AqVO z4CCA=o{UX+xwdj_Bvu9A@Qj6lZ@Un(<81Tq1?^)8^U6*x(rm(VZiYE+K_aRT!^P*K z({ML97(+kl*xw6&#T|l^u3`|^L<4;#8Fnn8k?2cDWu!E-jdZT}o3wYF>UcV1SaBn5 z#nC7PBd@WW+%c}g7y<K?f@?b@YU+Wzbn@AH60VGr@BB4f9Qeb3=5~HFEPaAwRnrh# zX5gN0JSPqB9X1~mR`dMKG!r-32}7m|T-%fIjL&?u^AL44HNP39B4ZSOjzdzX&@QEs zhFsOY^1$~pW-~l}l=QRGxa<>xx6k6v6|M;1Ra?ybj5I2o@7n)B;@s&EXa}ya>sPSF z%yEN#as7}KSaN>;bAR0a@c;S4_#<}Crt6FyJ9f6e{kQ*3lE^Is-v%#mALPKOq?TtC z)<dPLzgNFHEnYp=Yx`PtGE~N^CRL90dS-_gx|x6Qv;Uwy`|NYjXCm$W;~)Qc``+*U z-uA!)4=}cz%dfXljn68%ZJ>6BIyW|d+l%+`GdS34q<OCszhzAHs`&Mf)T57U8-D-v zE$(-w`j99Q*B$#?<n$^*^2F<Pfnw?u8cIK(rD$Cxe++X0DC26{Qqgx9Zx8Lj%Br+H zrPz#cps9<73QNb4F0f4F?$w2%GpEnA|Mh?Q-!ebY5JR_Z>eYVYCw{!W|NY;~?zc@G zD*1T(KY!yl+A~L=!3gbU``Xw4x_#{XKi)q1!+*2A=RNO<ZfGqToPRjp7X8i-YrntJ zb8*1>>Pi~@i@4Scx6}AeI0Vae<7x|9Tko$7eP}JO9AWgO<YV|kh4Zie!p{|>!Ausy zhVG!tjzk5k3TKr$P7+kO*y*Wgi*ks@ZKHSMsUpO0{s6#a&`yAX4dKg!0CqBFhpCcp z?G+z~Q78-@!XT{0$DiZe4fuT>gHhcUI>F@l3QTzlW%G+{(LemA``aU*_^I~b_q?-B z;*ap@Q%r7&JBy-db_#1qwrcT*_wxU%;#~Z-bW+iKgGs2{@h#_OEU(1dMwL@iDW9jL zdT^gKP|;?Cu*`PC>5wT`Ce9%0WXv+!H>kuD)&>;zDwwm%gEMsNbdt%t%D!v(mb7!8 z#qEU?;HBFrwP;ieSW~@-WBoG-=96q^e)`cz+hq<Lnx<|xA#lkVn$U59`z!}Rz3q`l z+I{bRS6jeZXn}lX8x_s2ByF(s*4G?Azbv45cR*(yck3{Pc?7ou4H8=u>7aR6a@a|C zS)9Apk3{s@755x42mRbKe93Lc6Ii69bY{5Fma(cj@ys*r#5edIWfhAF_jT%S4#k<Y z*PpYUh(0#8IMoe_Jmf$z3RRxvD`_mFi+2V(z^(-k@CASAZXH=KL`{84Q|m183Cto0 z@1>xSMy0SV@d0$p%VphV@&Uc|;cR`Euw7MjDa_2zyMx?36JMpVSMT_2Bhs+Hn}g5R zQJ8@;3ET2nP8W5w+BHw{whfp@Ykc$3O0O0wXosW=6yo?TGy=BiOz$OLwV+TrCXhd! zmhz`?PF#Gko%SHjG1?1lMV@JF)z=z9exPW;FZxuGYOq*xqv&s^VW*;!*wtwB1~q6@ zxGupn^1Ws3W%KUOxUOD1xsV?se|VNB#4m#fNl9Cd0@Cu)&XrNwDS%?fcv>84)hR8N zXGsVC;$=Pfz5yQdZrx-7f_s-YB7E!S<u-O}q3!4JwY{6SwJ|zEx5n$D;5Oyi^RW-N z?QeS<`rB)))?dM8!6lTpSZ?CWbR&oG!FEpfO8IN+k)Jp~uQ53QJ@D5R&n<Q*pm4rU zp_Wk~ZJ)tMt^=%6EJ}3iQ~E(&Yanf|abS#Arx(s$#9a`zh~?6rL->Hk2jRp7irhtL zPUk-6U>#+{IP`L2l%@>5mTq7Pei=6lXI{k5@AkImz+FrNr4#wNz@z4oUk>+SqCJMJ z80WkGKyPD(bo$hJw!&S*O7j3N7O<?|1pU$0L3s|axytG3rEs1{*^D$oanGWXlL`u6 z&5OKLf><K?N!s(1FzIl8mgBu8mUZMJ4gU2L&fkG&;_s38)??LWe=b<^{pjMc<eKp0 z-68I9Pn)Ekyei)CY`XpfAD=TJ3pUcqK`uW&C`aYx6v6r`5P@0kzn8HVA`*c(#FQBM zDH+J3%IZBYl$imViti|-j89)!T;?FrG*lo;=Lvk_&cU;~(3qed(U7Zs!4JyQDf%Ln z&B}{hW=s2Ypk^Di{rTPJWCH>o_~T-w2lF~m6eSgu;$}O_#E^SgkBVEBC2gH{<U*A4 z*?v#AIm#R|rO1}tg&)dC8PX;pe)=L{yBM`d`s2rs(?`=L$$uvn(z{VwD^o%@;-#-5 zSNq$NmxZ%DrOeWr_ACl#7o$`-A3Ss@@+}Hg(v^&+Kd_&s9OIPNKE(pM%ges$;)V0H z^V1nSyb*=-G~*+X7|}?cl%^R!4fJs_D;5{@2{(Z8<daX}0_$9R!yDg#!g+g}nXk!{ zIH&$eCvj8f{W%OLeOBV4>UmsN?b^E=S+PBeXZsFaI=RrB%fwaze|VAv$RT-?1!{ay zpFMpVg)<A))bTy{-IKlsB83L>z4a3QCSU0*xat?n!pK7;PXj~6`Q0e)w<7bDyQzb; zaiD|+%%3&}9pwY>;vqbh-uiIfh_ZSUW2=pf0X&-mN!8wS-{JPYdyk-urd$*$G9e`i zaw0e)l`XZt6ABH5or^jzGK3IGV>m44U;kLL1c+nEUmu6B#u<PaZAcM*?I0uJ^C5AA zM<PN?q@jxDWt3}+D=N|%N3e6`7XJFBF;X=OCuvfai;gQQ7vZEH2GCj>`z7!P`6M3U ze(pZY_tM-2Ve}ihJJyM-0BAAA;=%;K$Y^tq5}Llj{vmx!NuAV~O5!k0<r}4CXfCf; zej%6{dVyT<Q<f7XANZI++XVk;6{VabeXdlLk?QJ-Ruhftvwsw*SL(FV2*w2>FGnZV z;ppm*X%9WESol1=6W>0^H>*AVsr?%K3V=LcvK;8h1LrB}Gg42EQ5};wj!+)*&q7DR zUg@P}RcYlJnh^H#t1FBR4_R{W@dn<sO%D8-zS21THxwzj4**g!7BuwP+;F3@I58jp z_qx&u7}M}me0lG=(aj<!l<kgrmA}xJLX>h4uB2`=zaby%DHh=A?+E8^0lF;qd$Qqf z4z-{u|HuuMahI2dF<guxkK@(_=5<==TODz|<Zcu%<tuz0o+pivI!h_T`nO~`d~iV^ z1_`{E^;`AP&f{FP^xH=K23OrzHmeIpkVm#BSa2N;V+H&`zagt6_PM`%H;NRH7o@EU zm)sdwOQSyiEqa<3&Y|p%UEN*lxYcommwk-DLR;Fih>6n%7MbQ4`)y#1IWz7#M8d8# z@{9B+_*HKL$@_p;o~=iaRN>4YqJV=ko5a>FDJuV-cEG)d8_zU_V=^SIWeMsjkK^9J zvp*1~Fp@{XSJq517cPY}i@%IT`oeF@Pu^a=%}6WzJr~1OE-Pon!Azw~`lTUFpY!Q5 zt1nL4MngpYI=0!n=U&0D{~}MaS-oENUgO)_?a3z|ZD0J-7vn<06qbGGj$Q3<{_u~` z|2p?CIbuIqmrx74wfByzJq(3>Y2HK1Z@#T*Bj5b-+YVXVUS1Ih^>CA&v-9kNvaOwE zk@@%j>F>2KeBm$JGf$%nU`%x1efLG#{3ga!4?g&o__=oOS93>NI5bresr+?8!7<_> z3iGVIkdHEdgkK`3;VIvRley;57G4q0(Fge9B^5gQ@REn{`b$E-^Iw#~wvFgf7#m9K zv`=X38B-cgr~p<EsO(g3y3@{Z>%j4)@}tii<Z*Y!E-`P@rHb<hWtnHWs8e&?^XS(f zYd`mM|FFI5;di$;-2VVX9OF>?lTF{u55D=kQum+z>}T7b|M@@1*yC6hEcEgHiBJAu zdl$;)gNF`s*ef$l<_O{%JpuAwg|mFpmCwqkbzRj-uPf@m%1Ey_|AjieQLU$7BzP?} zjWpAx#&7=8FQ$WV!WHI%Ny0E>s?y5??>ywiL6uAuOHU>j0&p_ryJ^d^s2Ef@b`sWc zCUP)<LL&?aQz~Fzeig&2?5;_t-yJ;EDm6?@=j(x9V<`VT{O&AU%2zhdwQYwFwuj&U zzINZ+KhY+!zIp+FNmpU=%}gp|3dX8Aj(FogcrTMQ4+?w%Yv#@PNA}<$SGj$6!lpxi z1(e&>ogiCo8`E~I0ChyJl273!u30swoW8r|->`9MN3or(t1z2FneBmu#=Si>zHyXH zZY@#y>$QN@7hssMs|?4I8zroS+lUp~G~w4!GGBl3LOc5S6Yc9?`75l1Pqmv^S}kCK zsSwxtW+#@F-}B)|+RisW&~9?zpjK}-wi%VpTC<^q$Tl{G3ADROT9s@H7Jt@@R}FG9 ze8|8qgBC|g<dMlVkJh_wa+&eAu1z$io<!lI62hs47Ih3IsH4ktG#6NHr|v25JmtN7 zhJ&A=^^5oueg3H@+l6CKqX;;YlY2KK$fTi4LVW_u2lAE*5`{*Tmy}8DI^K5N3K)@c z&|;bTfRf}9h{6)4mahP%)5BsJC5B39(<w9!_cG5^hR+$)njd~M;UO1GT%2(59mO#4 zLKD*1UQFA6(o??oZk%+G!0hkFS4og^0LO64;m<auD+%-RyO-&WV_AHbE<M~l1DE{d zVcV$#E6Z!S!w2x9<?R!eB<7FsslL&w`>87&M8{U?3!HqtjN*5Og^Cr-yKh^5;yHPB zpd+7(-%R{GTh7`FsWqbuH{#=#d3nv}(4Thi<U)VgmeFvp)Nck6Set{VE;S~wdb3_^ zN49^rqFW!CoKvnjwqa-B0XCU*f=^ukKp(BZoh;m7!eYlLPuY=rSzhH*??@x(!rN5_ zJ4EqOmR-GhsV!W-+V0xAqaE0`vyDRs%YkOQEx-#qIW%zF+rHbq_9$LT;q0Mo^DKC6 z-L{d14DbgJOp3^vyN!m)fLoiLd8;(PeY?_LyMi+N<}Ch{*;>BKffhRwOyeNQ=>B67 z0L=MOb`;L~LBGWAhKrY3pdgQ32lwJCfgLGR(BihL2>1Yck7Lzrd<Y5@a3Sv{b|GB7 zc%>abd4|K~wzb^{4p5)gFL^@u%$dn|k~R(J0Smg3zw$snI&=C01LrGk+qQjJs&WV% zu0W;`1XIYa@!JecX#2X<n8$_3EP3OQiE_w)PAa4ZZ9*k9Z{(PA=9#*n;Ur#4&8tB^ zd)TBd0PI_AQzfh5MczCAXJYL8@az3qG8teAPI}6I)keKLxieqBiV*ddcutm#&mYAg z^F*toaNyZ+OHc}W+i2lZu!y+kN?gm&L+GH}5|`sbfMG&lz6lue<(r?$CYSXW-_CjK z^%;bTR8&>rJc&z<`Ayr}M(TDP#jbvaE%T&@b;93K4#N+<thTMlB=}#sq-!V_>S6&5 zK9P&u^`~eXDS9Y}rG}i!w}?@mfaPTz>qZ$6xlTK@?Di8bIEzOR7|JUw=~%Lk^b(xQ zx^;2MiHa_5#^{gr-@J{oS!QvwJ)5EbLQqgJby*w3ztH^x%25y8Q!cudbI;y=M0H$3 zT9B6)Oe0>(5|{Bj>_nO20g7GWtkT-a;e8L>k7X~kRrb@)%s(<M<+0U}9^75nP?jw+ zCeb4J>8GBG;`$A5K;euZ=o!WbNdgUr5(HLgV{w3!OZ<TK?9rp`=r^8j`w!gJcH$0W z^R}(&H>8`=A+U(+gX2eO-rZ~Hj_ZO-^W(>}Xz323Blq6JID&&F6TkBvaFR|M0!zYh zm#-b~I6gXk>J+m6V!QXgdl?^XPrn+)0Fkprn)v<;U7>&KS5Oef1E2NPcMPlbZCjC- z$dFAeno|&zVy%7mzCG>j`}fAexvcDiK*}RU!jD0!$`=HQV*aB(4tXo;-*idPQFwo- zy9?-Ew!x~6ysr6E-|heFDth(jCFQ#El?6kU%SyRLc8lcTSRyR~f03OH_Ua`^<ZtU$ zK2bIlBm!4aBq%atxXTdcE{4*fFtPnsdzKY#g4Hf;vy9Pr*TBdqlXRF9&_=f#%5-h3 zJ@A!UNjtGbDx;NAU3nUM2d3?%^6glVFjr8wkK?MeKKQf$81S@yMi}?P_B2%z%UaZ_ zGV<~gS`0w>D4s)_MC$Owdk9bauIGZr^H6uCv?Yyv>L3ESlsKchwO*=ChyILly280E zoSBQDaCR4xW3HfJ`PV3%gKN+d2k}ja*`!WQ6YTQGx7G0Cg(MEj%BjvDYZcCc)oD7w zk;e8FE<~>|mRP}^#_e&&u6)<{rvQ=}kMhfqJn%iJ7?Fp}cDJGOyZCdY6r?`W|H`-0 zj`FIEkDP{Y<=hJIg|*y-@h|c?I2I4d71FLNoz3$miUXArw>ThO-jQO{^k1<eC#_{u zWP8brj&#DGygN_m{HYv>T(*pkx6Oz6j{m!5wC+0`FWUEQX6H>;j!Nh1hl@0kYrv5; zUaoKsE`&=%Z@GLP-uqpcc9+sOa}{3nWh$*Qe(Ch&?j>E7qZ&@6J}Hm!mXN=Z8CH^p zAzb1&LwlZ^M3Ix9yO3=MML+WZNb;(?`4YprBxXMIrxpVp3)NW7^l?AQx8P{)f`eDD z<Aj^myb4go9iIEnJTqF7S5!*z&3@Rl{TFyff}qpvpwhZ|l5v8E@<!f5Na@?_MSk)! z)c$|c!;-nLFg{sgH?(sSWnFfKR>X`Wd=y@XQ=h8l?AQ10z0aU^U)JyHB`>bN1v~1+ zor2Fj`*i#lKgqn;@sH$j9P^Qne5~za@qC7HnkBMs>k^Rd*lYFfbA?phz9hSR`Br~k zj@P$}^V-9DyL;7?6jb>jKdW$7r}QZ2JN=XY@t?Hc`JGRvO+NI{TjM6p@5;G1z3IEM z1MF^$0`}i^S9CNRu!vQ;X`Y_vq@jt=wq3_)jxptD=l|+z91nSg_n~5^>Z{^fDLRQ? zHEO|q)hOR_A2X-6FB^y@UHv)N&-fCWO7pI#kp`X47Pix5M04Oc-<@IrLW}3Q^h6Ta zXBQhDee|*RU;UT=b$j1?-`5V`eHgj#Zptg|`@Zk{+F^_tE}~rit>5~s_D7%jXEFMG z``h0ZJ;=R`zwbVBByGp}j0$I)hQ^BG6r(@+gYwvK_cFa=rKBOf7Cw1JNdHnkMBcuR zIi<>nanriMl3?A`a;yf>F%{0g{fqxe7^Nl#rA#w(6)*ZL9&K?NItWuLEPF>`w#Idv zuFRMT8l8G6nW{r1ID*uPqp%eSB4CHFz_6T#%P77JN2cwa8EoGcP=f84-O|pT!58CA z6uvw6wtI0S@$mZ};iU8<?HU$%^dw<oaoNI_Qx#Pz!L(X(tH$o#yEAe1z#1)c6n;*8 zF5o};E|j*rnE-lf@zJBtq}&RxEu1E=@=UAftNd(iT4CB?R7flQRG`V=QN&R;mCf@T z_4TYP5?6;-U6HIX*-F_I#CFnL(o6!x!dcfJbod_D<`yqq8hCKoO)Q5`9Y4{|FiCsi z>1WzwfBp6LB34`aPJHXT-qGIk@ej4J%~)Y$F*QBTmL#m3?Xb02^t9g$cF3o2)sCp} z5SRSu=&UDOtz*(jN5^X}6~0wVMsm_(-Ddcg^wPz;lNa)n7obnvKX7;OvVgMP!HiaG zXE`YG^rKI-r~c}%+X5~_HdEHk_{3b&;szhpO!ZN8swggNS@Dv_(%nm55@GWUpD=i_ z0r)+g5AV9Vm|`L!edS{Zr13`%uEGr*iX*@EUvCHbXg=WW0JRjtoi`mg*1)NF74^ix zui|2uc{+*od7L^*TZW|4+R34VVU>6CkP{pIc$YG#tiiP07M9mYsEa4>$&<T-XYoq; zbr-{ckQ}k1vYzb>_)ht2c?dZ87FI#Bf)Fl0u$&ysftvEEhg?2`RquHY!IMYqeBAaJ z%R|r*w+R$hDxFfl4h~=xaoLOlXXmb+X>WhZN@R8rkPja-K#esv>7>~#3lF+Rn8%{T z!K+GU<w4P9A}gU*u{`3ov#gp@R_S3~J3*P?v|DLn8gZrC$;;-S${Y<W{T_<}?wNcL z&CBS^@OSDO+WW5$QiN;S0Czx$zi+T*e2l^UK9nH`aFa0(KGxG1mK3*WOj{p$f7^<} zc^nyb>EhLP^7KV$Gt*{i_d9pt$62L0_#n}ep^G7`ynv*OQl8f9Bn^c#*3p+Q;aBzY zc-yvX9-pe5(2Yw37pcfFe40T%gI4Q9+_VE+q+`B{Lj2r?8z|RX+ri;q^P5~?VhbwD z4yR%mr(;<R-(zX4-)Y?@utd{tBag0N>G=GyQ*8r2d3T|_+Bk2!g{II&v83|P)ox{h z!-aA17LP^R&Dk^OaY1wiOVu4&@!q(FI*h^@8L+&naGqPafx;Qz?I@kcqtvjCT2D@g z&4jngEO|u9Wo;x}`R_Anc(18!O>FbtC%Jy}2X2BghrAP(c!6)2ZQ0tdi_c<^Jc<v< z!9XwS&2J*x<2f0Pay#k#U>{X5)ROtVlt%^AygRtMi(}zb-&ASZM*N>Y$=AH8D09!Z z{2_>}fQKT}e0-r+6HhGyVa8jgzEn6*sc^=^S+^SF3>L>|w`So&ihYbqWwVL2pglPu zkD`@te%HmqH2mu>1;5!QZ0q(VC8MOL{gjB9zh!m-K{-*%Z6^fwrOLt74Mb2@D4#R1 zmBvYK>6MpYLxA6lPL|O4^>ZQXCe~ga60Ccjc^0jO>-X#&0v6N-rhmP7&P}GM!}_jY zW1$s%TvXn=b$jB9f69~;<Ow}8X`!v?O2oxI@wh>oxeN~H>8o6XK6Dr#&cGR08A2K_ z6$zHf`gWv4X$a*9j*Ij^SFc`S;(0W_kMFzxzOry;T;gTy;@1H{LZyrl{9E6je(LG= zjVGSMoz30&Uf&lhXK5}S%-Fa|Lw%(kP<EC4$^&KU`4>ykEA8gMUkecra8y1z2^WI6 zD7yriGNqyfkF^qGDlMCJQKDOnu5gyO?2qi*O3_~ZU)4nl6FlTq7unBXDSni3%<g^L z+s@tF8E0){yy7bMc)K6p)^A|pPL~=Zg|o$z78Y)FNt41WWlp=P2(dOzic#d?pY-5h zx+pD;<8!V7xMk;k6g+&jCj4KmlLsP{B_#EW-~7cDj0R|<w{WAhfLkLMs1|6S^rnGj zeb{ECqnCA7vcNaPsyr~MUk%KaI6Ng)Pn&l`3Xd97Bsvj`5B#PZj4UWY*X$Tm0Zo|x zaov@Yohd4w`Ng7?b~~;c4iwS)e^&lZAp50TwZ+P^uv^8^oa?QZV<=1T1)rpsazh$# zLs=}D^3$v6QSp7ZCiv>(a20$yHX;vlGHH7p#{(5EKc`)oCvlR4h;Rk!fSZS3+cySD zz9a_U#HGtF?-`2_rh6hrUqmkp=idHHqdbg92COSLbEHhk51#RLxcuHRH^@BueJEY< z5^ZaB_{eQYHI&B^c^Rj6!oZ7@^N@lCcz(B)t9~b%Ns^2|imncVBBJ1gM=8Q0gNG=e z>F=X-jMB)ym`FsF9s=yjN#9lSg=WM_UkZv<pZ3j$**jNl_WYv=wtu0GXpErSCC7;> zoZT%7fb>bqS<7gtwHmdww(%^p0nB>t{Yn&yeu)CwdmlT(`^cz_{b+}a6x8{EvTGZM zugW)yI`tFgl}or(MDf03BA-W}>e=@pynmyK_2d>ol4VS;b)U4j&3$d(XvU5&i|6de zRG=}AC#`bPKFNOZ7W2T&8|a&)JxJ3&;YRY~EcrIiA=8^@7;l9}*4IFB;P@P54C9x+ zGIxTh^Umul!-7-NT4%lPxTpRHSoOVN^>Lb6kRY(k%Vuh&iA5C7@)O_t94&Z+Z-`@J z2sq8o<S7)4lhjRIsYI>=$MKEN{E|&FBRq9oi@#b%U%%$UGOk6~O}J6xHtU9p%b|!t z25eGa`NL=KTpE4t-}l-S&Ph1@DOuA)<Vl}BAZ?s6^U3zruYR?C{_~&DnAvfT`jvOQ z^I<G}@8=l<9hoG!n6Pm2Zdq5u^TMCB^xS*ME8Sm;*DJ+(ZQ<*MX(?<!j-{+$%dCsF zzxa#4Y@hkeXWF0s*`I~)Ggo(R#hhzDx|jpZN$$Dlp3vqbx&n;>4<A0vxBXFE_nnQl zXK^X{3=?x1=4Ja*4;6h=RYt;J@eggLXkC9_F&-ZhW5j>27V|sjo9#e3oVh1xm##=_ z<k|u4yDsS*Z_3=oq5fT^mrvEEOKzxe)+N&7qUWHon1n2IysZp-5o5})fBoxmsqxNt zyb~SVf#_*8X!zJiKiUpc-^Y#}Yya7={0h6_PPY3|GQaCx@51opYJ2dZhuXor4`;We z@<d&M;~W>59Lsk7j&m3Jpw}!&y!r(Xd?#GhzrLQhR&B1zomZzqWc8~@8NPNLkyrmW zE;T;=%fAGJRA=LZ739D`rciNe$DqGh?^b9gg9=6&j-RWmDsvSiHhQ=FtK@NVQxizi zP~mp|4hT%=B}@kbUJ8$_Si!<7vz!o%%cuiHXxo8~W65{o)C+Bl0|CGLgCA)RfB2(q z8{4`a#Gku$l@*YU$yXTSBh#tqaZr<qHuuYHC6(z9+;t%3JofytFys9Q{Vn)UJ;Nbh zCot*PpK{;2t3|99QnwIZT42^zr#jF~99@->q00>b?l+jgS#g%z)fFepD!!#bthA*a zbd!E6tgEACvJQT?IV8-(jGQ9s3Ixv;u`*v`1xFY&&|v|1Uq)d6`RD&M6TgS?b@Pt* zzqc)Lc$W(2+39WIG8bi@18KW46_6gZSV9C`s0sx~{ZvL#FX4^q$fk$7v3|TPa~JB~ z^$i%M12oS2P_MlsQsmoJ`b!4@-sjJs!|L=}76WFOv@c)6;_ItlYk&0V-)*<B;@-K1 ztyC&KHef}{gl92>&sBx9`N(hLnZX)7Vz%<HG?cR}kGyKVyKQ4y;l{hxuJX2gp_P_a z=E6&nfhlhWck2{9XNdp+KmbWZK~%;950?WIW0exb{HpHEG|JE9M=6CRBBaiwo4R)Z z;ox@x9?;5A+>)nhZ3|o-?`7&H?F1Z+XFkTYfHi=I4~CA^PSiGHd7@+m&N9k;Qp7?` zcQV%VI1{3{Q(>UyD)SiD5As541zx)WPc5)jNu00X3gh`(mq<UJg_u&@6WfUz>6Hfn z%wmfQA9>mKr2=9ven8*CRw#Ms|N7le$4{x{>cZak<|?UWlApC8bamf)vA(^mPp^8X z9N;T_1#8NfdM^6fI#l{d=T37M6s%YAvcrt!%s@kK<gFrW7~})fI<;d;eNz5RM36(J zG@=7zP&CCT{2<%b53vxnc>OAPOkjO6$04Z8ZSx1dFA8TyNGN{UHGv;zYMTSNHlT3E z;twUCd=%?K`3KlzF4AP8jNAh@Y6^TY>l+rU!Hdhd)R=GEcg};Cbt~OvY->lJ;*q+D zOl3l_Oj&OsJ6^oNA&<9K+SWb0@Q;fXzy@$&;sh0#KS5iR+WKyG%W(NkWbuQ+-!&E% zv~Zrnnq<q)-Ejjl!@z*5A-=>eB~|DX`Z<Yk0LMT9R~{G6UuCj}Wg<HhwsLS_SvZ%% zd4fX&rxq`@xs~fEoNwY^P^F!10jdMb!>;@}G4Yo+z`e^00ut6II@L~<u*R+UhK+vK zr$71u{?~J05QkKwiJa_X@z(x^_@g++AH@SBzZ*aC3U+_?o*xtCx>x=dt0r@mQN=5` zmbJ<t-$QJf#4Ai%cL#ljkF0PK$2_S2;b(+$<B`PtAr1AdAKWQq|C|=iSdA{z_Gl2H zZOMAuM!}ahnT*q4PN`%juI@HwX4$>qonLktkUp{oCNzGPfpP@hL2km&wo|{SU!Z<$ z-_<@Xo?HyhrV(YXKEYBJDzB^q86@@1v-K}sgnJ!}e%rSUn%xyFrYbYiHiq$n7=;JC z^HYXc7fM?BHuxYLomi@5RUvMk8E=Ri*^7S^&Mb^6f5btTJz8Wr*w&Y|a>EIbi+4ep zyh>qKFyxoGJxLojtSp0Fh&z4iBnxua+94FZT3Sz7KT@O<g||*K9!rN6p0RAp__99M zo;&(n+kfx?irQV-$)(K81u}w>CJ=21vR&DzU5G{D%nqaHpL;fPb|Z^pd-m?lxFt$6 zk`x4D2Y2d78km0|bFKw6IL}1k!i5(zMmlo%a9orqiygmMm$q@Qssm|LwXXd1@y2xz z9z7L>^ZvW{wq5&hMZ|==cxR<Oz{2@=VYxl0?^f^_(PMyH(1j_j>Mdmsjuq*p3g?ak zwDGeQWL)H{uN{V=Uh-<bQ|gyq;KC<KYkk}PZZA8&Vu5mLmLG~eU~`T$zfL#eM_KkV zNb<GqFc;VZQ~7EQsHqN417e-_)`AQd`C-h+!T|zSMB*)Ob}`-hHw()HoP398Q&-%l zsIzG_Rnw%^ZGpSxROPrMX3YM{MI`bVLviES!bL}k=iPkJR}YsD^+Ir-!!zb<1LU%N z_Q4~WCgu4K74v;SG3BoM=9_5}qv9mu@W;NfrzsGtaYo_Eb4WmcCber(#W2&GX2>TU zAFpOgIDZ2_vWWN5*a7;-T7OVDkFj{H9Plcfpw|e2j+4+TymCzRZ~3S5y7$f<Mzroa z?K<A0@FAPTp{*}#%{(!OujV<PkzMeaip#awgtlbR&*TtgW!Zv?X4tS4&WyttYo;HD z7e;-rvRVt4fi4wZ{qYLll*`WNq?x$-J#txj?nS=lUys9!yaCm_oOT=jZN^sS6C(!} zKTR}hGbw;2vi_u$ybli(E*%U@T*_`A=AxwU8RwC=_^5E!s?u+}cWy@x+NTiCZni>| zh@|Oxrv1S9$xZy%ltXlgn#+5JQ3Fkt3FcR@nRiGZh+MlqiVy9Fj3cc>KWG=F0uVP~ zh+}^x?pGLV-eN9ujm5qtcGp>cDd!^6+%!K74z|xR4x@cI-tt<@Q+c+sQ+NHl<L@E= z)K{--BsjQM{XrA*5y#Lx@d{t_u+Oi$=7ltA_sOQpXB^9=v5E2OS$Rh|Wlmo&Xs$`d z*cwTd!kPY&e#81*!ZncwAC3WBNb7A=8KG6Y<J(#0cb6}nrw-YjjPb)xcHh`vJO3vE zaI9NpnmHA(D9n7F!eC_ozI*-fZC&z5UBc}kFsflk=2do&K89uQZ~yjhXYS+t#qrj? z_uh}v`JGvC&73WAs3-2y(f8G`f^2K4`s+Ep(tQ=LSBmlNgs&~*E2p;vF6ej;hk6v- zsKyOa{3xzMf9p4YvwiW4Uy6Rk@tu~c&f7KEJ8<AYd+4nX<-qFg+jq1>cOQyjpyziu zc5;WUZKAi&j)lCKT?85b)q>UfX#f*;Qg?vg;@;cTxA^p(8^oB#DQDyy^;B~hT({B| zrKxjle;TM|jy=o^tV`RJalA~gJj?i-g|kV<7%H5V$y)bYUmBabTkvb>e}3&(e=Sz+ z``C48I+f8M{n$sdxbSrhD}VZ@f11NQ543l```vN9^7s=^v=4sdBkkV%@2CGN<JRaz zkmI%~^LMQ8WnRh}q)^`P_(uYK2VAc=|E1J@;J%*nli;<`G!pFhKmF;I-~HwPG#x-O z7mbrj>y<T)lE{gc9YP6dJ9U_8=rF8EYBx%}?sHbZ$0~dB4aBW*J6IV(;b2<bS_n@C zt?;gr#{6ZJE<pTl+z^)g0=|wfV9__ufdX%P<U=T&Kh!qwy{lcjK?jC~*$oE8TbZPI z2}4DQruo-d5svj1<<i<#-1ea$+lD)hi&**TM{tf#>cCxW-Jm0P>#hv1RrDTClHbmu zIG5OdehG`mSTq6031hduw4Bn*@^9miCKYB5CR~Maf@uex21sKx?zoMba@K^d+y&U7 zn?~jI4BO&oaf>m7h4KnvS~jctSwh+Dfj<<s?Zj{DJS)Io`_fn1m%sSMHqBt<&;$3j zNfb_-QIO5fa*z+--G=6hx?_a+s7q(2(p7&tHSs9LoC5}E4b7tj;0{8eW&dNjtP{(i zFh}D>ni@Eb!uxmb`W=k#LCO{dx~2iJsH^h&CG*g;18gOlWN`QE|I`26p8U(dY_mk! zjz#G-Cy`2voA~>(6V}qsUO+yQ--HweMFd>EOH)6D_XeKL%3S!*Lmq2o&TTmhQM8uA zSpz}ScI9Iqu=a90$akQnpiTWTI0;XZS**HHUM#asR(!-u-t#i9zu-kZ1aDzM7k`GQ z4#3Z64_j1dx>(W|dK{1n)QP;-HMSw!lkqy7!o>luiW3Ic#90A{OfcXzJ9vF;E68u) zO658{Zl})pG74vXh%dk+E)rdtVnKzr5M>JKRLB&6$bppG0+N3eGJ}=>=`*K;%fSN& zv*qa<N1sU>>iAhUSEW4=Li{hB#ihy%=RzkJ0o*NM8A7X2j)5}dQUIErLM;<j>bhVO zm%_R5<6)-K+pRhJl<JE3u5ga*fz}1B>ZJIFJV>X4JoEua`OS9kLPX>rgP&OtIlOyk zESzs)o#-TfiacT2HuJ9cwD||$9Lr}FD3>qaWI>9BI_hs5E_mdP<ZD5=oQ!5dDmTG& za@7R8GW1P${puo?&I@cSpJR*sT*@vD>V)f>@W?_nX@PgN76xBW{63Gu`Pxlfm@pvQ zK)arqAwGN~u45?8R%oXyDx9rB>eNLD6$vg3o;`C8>(>pq#Ml~l9Hy0zpb8kP9HQQ# zjXyG^y_cN2g8%1hSE##54yW5RkMHVDSR?Af2TOhY2Tn84pF-(8gFok)rR!KYV`Yu9 zJytiuqwKmL0=YFm^R-<ltm;=2)~a`TME)C1en=mF2wxyq_+CF{nelul4*!zP@O`L` z%7Rk)UUB=Ke2D7@G4gxh84q+{nulpt!}C16SDwT79!7-xvpqszX-pP%c@Ld=7~M&q z@6wECr<Mf7tp@izgA<LC@5IpZp9$II27EYg+JcpHDV&|0Dcg-@zvIv7CUu956T2Du zFJ+?#2F`3?G8Ba~7Dg(fV7^S|y~~KhC2pRlU^^2#UJEXH)tI5=wKBEJWV9h3k6Mh& zTf(;gOJ50;Q5_Q&xWsWX;sBP&r6gd&W*Rf>IHj)S3y3dlCpgySqzf<BLFxg@)AuQ7 zwK6kL<!fEQLM|xZOk;ne!b5rDv)0a8AO;^Ttj*8GZu2XJv$7mo@V#5UN)+){w&(+1 zKhX9iyVwyj3(d!<v$U^}C=?uUsatrHGFgA}`wO_GI>T@0E|krTcbu5@K0FAekfco= z%fDg?PAEqm%UwACVmopCc$6!iVX>WYkgmU+tcz>4b=$o8ms}PH%jY-c?1daUco}(n ztKG%8X%ldIJ@)dOtLbtOAuo}$(Aj?I+EsRI;Tr7dGe_IO`wwt%;qF+`h^h*S2e58_ z5c-tDx!?r3l%;SKzWC+NANgM#!d<-QOP@R#DGPn3F=kQ?X)UPl6*d$+v3gjQ-F$5` zwm*0SdT7<GPiC!}Z=!6zg>!%TVS#>N(RwfeKgSkczUCUjE0l2lnV0n|7QWe5>ji9+ zkT2GQaRyYCZF%wCD)!Ew>=c0yg(F0H+^e#s4MzsJK){doJVjp>7f`@(`?prleNj+_ zGovkFm2B?!7=VNtQrtM+`E~him<T0(FFP5e(8T0Z;-`>eH$*o{J|;r?vEggoM)5n< zl3@5&bgZ^W5U+-KiCt2RDnXtmt?-ODsv}-1DBrD5k+p6dgY`a`Whlx@U#h~Hv;~%2 zI!qv&w>i``(1VxNFrLjjX_C!=lPQ$;JuaA6<@tfD<IZC;uCh7CUl~)`%#JnOY20SF zi*m@3X^N4wNuGKzsp32!hG4`LZMGE7&K*=Z*I~WN(m@U(6Eiji@5pNA0hv2UAIH7J z_`9~!4{<=izB89&p?cyD7erQx$j}b}!|}-iJ5n6u7&$UZenmbfK%|HE9oi7de#mEk z%0&BxJZG-c70$>x@)H%uw-fXu%Kz=SSe(a2qp;;4sylJSwBYgu{A%829;;}GpYMan z&9k4)BmBa6)v`Orb&Q(10eL%*D%o0XG~*dEPMYCv`%z)8a&4M(Rm9D6d#*Eox`yGA zJLPPnF3im{2Akuza}#ruED8kyF&X7E;(6;5obn@vex?0Yn0!8bkJ1jDEDXPrCG{MB z7+}~3_Iwb6M0E^G{Lo>58{Q}dwlpYNMx4Nf=>Y3Bsf9DT0hP`k66{!M85zs$1cftw z74`N1a`*1Ro?X>_=eh6Ox8LtpKh>?)1B4`mKp5LV5Ev8#W`@Ky<w_h<sqs{5Dz2$i z`5%vKs;1(}KxQ(Te<ovGsSH&nIR8u~G2q~dgE22V2r!6;jD#L7b*tac+kNlt`<~C| zyUxCSg(dY>5ChEV{@wH1d+oK?T6^ua*Is)c?Gj-Wt(?#$;0FG?dTILFB)nx6;Pl0A z@1C9M@13L;|KKQd)m_R;V;W3!%)QnK=b|HEgu!X$_<?)%p%Kn*pZD}rPj|ofd%qWl zvy<LB%eLYWe<y)+yZ8`toaWS_4xy?cJ#L)6t|vwB7nGehFZQRG*B5*BLp+myH$Q4i zoRXcADch6dFqNM{4UatXNcU-i&c67?FC~CZ-;DIt|MJdvzAF*W-n**m*<;UkhYug_ z-tfR1x+AyY^FSXof0ftTuxUryZM1vu4G1jxyg9ZJ!nIUuEuenN(xBbaCJbyW-$XzD zqm4}Advc8I7(V-A<3mssbs*b@%+vUwZLRK=XN&l7jB<9xMszW}kKK+gy+H88qmO<o z4(CG$4`l}eS3bLy%Ki7>AKCxH=fBYX_rLj@-NO(6b!6e8Za3}Z5qw4Oe)v7z;iE@W zhGPSHuAX!PQQcD$P^G)0YnpPo8Bh8?<z~r#-0xTP&#Qz;^o+*HD>&ASL*L)`5zggs zZpvThY#drB1Uq+y$PcUKTH^yD5-khMHA=_#=9959KkpC#1x&$JFS*Ty2Cj<6J!;*L zHiI~X*!_*ouP~dpIn=5Q;NYN{x-#8e2KF5fzNvfPul{N`#FE&_>k2t?k7EQYIa^<t zC!Gse>ev(~_jOU>=x9^HZQjI3ZWw4Ad8|{|^bRtwbFDMdf#4pL-EN`=&l7p;2X>5h z-n?~vcjoLRmd5g7ENJ7v(Y>C9xqJ5>q6F6iZw5#9rNEI;(hroRm_)Om<Fu-?#}E@2 zm9PfL$V6>jkY&PHehzru?m)w9mXGgUpT&WLLtwj0P!W(*EH${uAodClG55aRgtKei zhRqD%*2A-r?mCKK6x!Q)8v$-Kx_D_sikl6yj0=s(a+1oIB|7lcM;YX)NUAY}gTJp> zl9^W;TZbroWd-M*M!E;pgXiwAB;9a0Lu;4OY#E#A&OG^4_kaIiAM4IO{d9MLsI776 zp`klRIIK|!&EafRd=3Pv!L`%Yq0x-ZqIuOrhqK0yN94Gduc~+9rNdbPRaQ$O=0WoK z$2O?rLWi}+O><T#XAahsgX=Rj>0tiIQr{MAQ^I!Jh?>1MBEd%*6$~hPqZl<GBVCxn zvu$W_OH&Waj5C#UDf5cBYxS^PBOIdS$xncl3u2+&5)l!6#1ENv(0T=j^L3n~?x86^ zHRO;m2F^GJ6wP5~FPXg9#>9z6osLwX!e(bE;U_SSfV8b(LWa-cXx+rix?hLq(#rJm zL}&2rx8Kg!n13Z{KL6Q2=^p*&quKX!3)|J`0Jl9UOX?V%7z-?iGp`YE^0p$1s{Po6 zT<R&Eq>D7OJxNQQyy6ze6qx(2(J1;2{5^tu@|7XXgUGIFTgSN$*b^AF2XTD3t;Q0Q zRdF`qh;mDk#n--}8#r>5WqZgt@-cILk-9*6c)KzBrFd+)RDrtbw6|pF23rRm*t-Eb z0ys;)i|1(%?8&~K=svn>!B8Ka0?IcxPVN9pT3~)>X{S8DbP4D0G!s=g7afq8XNky{ zM6@#)hP&i-u&8_^Y2c2k49=ICNLyym>=q0Y8yV2J*(Y_Wh)7DYae%z?<-kY$xguHt zy^9R_q0lj+Z^kz>(Y28ulVzJGh%(`8>0^sb4zdsS&@7Jnd9JCG66YjXBI&3PNcC_V zY$c2|KIg2%Il6?h^T=npE;`gZ(?PNDQ^Q7H7HIDBk8DX}e-(KVx@mHjBkjIml}z!_ z=lp_|>A7g|TN%Qs0h6%%4A5F0Ck=n3y^6$iCK7%{?I<HvMhFX?i^9^qJ(uEjq%A_l zzv6K2d5e(IW*EqzQ*}5`Y~0cfFi_R$kbU2kMas5qWps@ExLkMC2r4FM$Jxtw9Y6K0 zzkI+`evwW&sEI>ms0>r(BKnuMV!h-?$!PTjyiQq`S2V4<*MyKb2)5)albDjl`;ZBq zB8$~-$>+e=_sDm(eI3Fj7m?4NUZgA>Nbk25bZ|P5Y))D4Z3od44Emdnj-sdR7V&2K z=mPYZ4ixEU|D#^BE)E!rAI1Ohm<oxTddmhJxj<+%)GOM<4-wbC^6r})7%X>}PGrbA zb%`*@|H3bF4sAVaU(7HG?IgMVN}|BvyM2+9+2W?-ARyqI@N``%yY`vdGUtgbvF}}v zu6M<cc0&3j@lZ$bQ>Ui=$qQ&^*_L4hqFakNd9Mwzoyfp^%$B^-FO~-mM$Bo~X<vwp zA9a$ZK6goN9L~=i>ki*}D_eu?VkJ&*4?^R+aHQWu<n;?3&eEuks#9IdZ~s$M%5UvQ zapYmW$f-G;O;->4zqU=&*~*I%Tvw`<bT~WWNaelLHggLEV)RbtnK+!?#%ef@X5~qK zFZXT4b{5(SHSk3?#8UioSep6NGajZJPFipJwwmgw54{j)u~YuJ=b2BNobWKVwrOIM znTKZ$q!*T9yL6&KnbqOUi68cg{SH~2d{l6(we%_Ka;AZn!?|}v_wS6TEQd2^1<w4m z!<1{8BE-3o-1~y<i=Zf)RVS5zWJ=<CA9$&$_u$@NE30(~5n8l7Rba{m8b{STmr3W- zz8q-b5gyf};Gx60(OAApWBXuwKN8zFE7vI~b#Hx_u!Pt!^QvUhH#ZJZHIMc7xRJ(I z+iF~RS9Sc`<K$K7DlKTU;8T&!IGkDOvOt|w1^z-;(p%jeg5f9XsXAvL*<Ae@;oS6} zA9`Ej!%t1V;#3BxxcW1Qq=HXsoT43-$zpYOPrugpR^bha!lBv<bpVlkpc)z*{B!*( zADYFUv^*V<%B!|<C@ZoGR{r}38rjxJ6WK-wmwektX-mp0+LbHMNFzNouLqfwH{E9X zzl}_El^ux<DbYAUCGWlVooQu^Wu$oV;7BvgMNlbvOB>*{$yD`k>}Y_t)ip&!aVh;C z8jBlgLOW<E(;Ooj>8#Fo^3t*DB?32=p}ngShN+|aay`H8o1HLKQvt~Qwhw+fr>i`r zQr`JI|AXg?Ih>1+q?HizTU}z_K7Zq@u&N#MhPs$mxeoT`^9R8l$9kRdqIKjtHeG)W z^%B(KDy?D0tnRC<u3cnxv!9?I?E7-<+=Af*AALPz8~GatBLQLdO;<0S>JIJSL*K(T zT#f}jC@=I-XURhwfQ+QvQGze_t$9lg>(plrVE>d%)NKid&Ne6U)Qu-kKHvS`$3I>+ z27Ru!labE9_}=$*2M!zzyx52VP&i3#;kL8a^`v-McX{-Zf1=a+d@q^k6}||`)&Nt? zl}*p`*@`%BbL$LcX#;zwyM@9jR(?I}>Mgbmb-Rtn9(ydj`kA-9rMs6XXIG>f^mdVz z=8h?K)VoUT;GsjIr|rta33w-v9D^D><k-pb)^yP46rI<U`u}%{Mk0^HjQeML{f2Zw z5Zj1>oBHRR3@~s)J%zMKANpQi+8$%;a+dD;BUG2_5XTOtv2V~{V8EDLv;D<ie53pQ zPkf@g{pjua5V(HA!?zyp?!NnOwzfUieew@JnQb@TM;kc=ujTUwwz$26k8W>at4l?2 zH7@FBZEeQ};w2tU?p~H*X-Gd!{4f3UvUU2;dKp68G^cud?MI~@NQCo;|8WLXKFaJZ z989MOKn+oaC@7#|(m8N%THj@G1%sowd1hLF1xsP$M?ME&$-C02l#rNKiFR+~4RrW^ zy<X?j6w$$k?d!x+X)F^#diLyOx8>me?w$YD-|P<Fdrx=GjvSMCbd+UdIG~0wlx+~B z%(&=yQkh>xk%^npS{hGQ#K`B0AYIHd4$Cs1j%N2oRXMqQ$=Nk$Q_f#Fp9XU9z+NqI zmVrDU1*zlKSyUU{Hlm6*vwXQ6&{w1EGzyxr-waX-<JJj9BRV1I;{exsO3O4H?5T9# zJ+0h+KpN@fu?}-a{bFQ{(-Du`Y0;qkpwT&ukLxG`_um|0FzE;1bmANJ;9zeYd|hrd z%5$T$GXo4Rp3}*R8)f>_xuvss^^xbR9%#_4KAMckZyUN>fM_h<s7pD~cnu$H*wl%e zP2fX(RQIV*{Oj)PpZ|Qf14Xm}ek@X#MV5$7GqBZQlzG`d2s%kG4-HZIE6<vvBQnV| zm5zp<j%z!hJO_?^S$!z2&1e#q_*2x%p)B(-yj4*uE6P@8)Jdzn4e?PHCsCB~l0l-K zxL3Jq>|{U=ubte8;|KT-9L1@1hB`H<44t#H_c%4>1BbHG;MguL!>u*MD-$=+!ZMX5 zCvz?%&u5tMxF$aEK2a*bwxvz7wSjv&kKl-Oe_p!`kYM`~qn~LXI0o0@wDf~q4w9#c zFbOd*_%ev_E}cl<=A{?qHu~lrZ7=ntOyB8XF=F~H7!Kn9*tfrvebWygIoy5lgCFdk zc;bofJKy0Mv)4L-9K6i4AGP%^<6kF**tf%uOL>5AX(L=x4QE<4NE#iK4V@j0e#(Pw zRrX4|ACv=m?>0K&3vh;ky&2>F;Lh#HB+(JzK8Jp|?r4lb%I3GewVSy6u0-lu&MY5R zyv$zCvT-vGdm~be!mzXq&XFOHbj<KRkz_V)uBWH26S;Vaw(G~<i124i8J8g?KO<7d z-jFi9cK|$KT`=D0N?G21rJKCQ1m47ECYspW7K3Y$Z8U1Yk1}y$h)C*u*v`?du!uHZ zz_IVj4b>uH&O}QRrOZT@PKG#+xN6P~qi3Lc1~6%g(p~-_BkNdIv0?ibmR%8r<MQkw zv@&uu!1gTNH2YfPa2{kZP#>u(`3Y_e2!t8>P!9;v<IJ-drt%lOGmt4mz`x?;vl^hG zr)UqMDd!Aa$W9W{2$5(0&As_d(|)F@XS@z3oO<|XsAr@QvlSRN%X0XdztX6C3a_HC z4iEk5!GrX<&sk`FVbCsu+uu?I@A$)iIOHGNFMkx+{-Cu1ORkGg{U8yCa!s2=&$;Au zh&{l^H*A78Y*Ro#YLaaG1kEi){h7!v^$(Mjez<O8lj)g|#1U%0VOw&7P_b2?i&qWY zEvNLPWvag%%*R<kg`J#}H`dgCFGeTn(pDu1&u!;EmqUSVeasW$P*ey@|Bf#3p(IGZ z!i6-kjr$AlfueMJm_6Hb!4KQJ`r3!?(`kB-^cm1m-I4-%Z#_(Be*0tVl*w`XN7}u8 zWI3H3EX&9~k9c#fj`1uW!#L{I-||p-R440b5LfG({+4H%fI<fwCFx<=0phvtxRr|h z^K1e9tkXPwtC8vUL+V^7)Wg%zS;Jpik_WOVQ_5zZK^OZ_ZLCr9yWd^wJ0!A2qz|P2 z-diK_(s)<Lh34R{PS3Xo5b|=I>$Fh@{Z%!ruevHLtmHd&6_|K9k?H<@XZU#V-dp$a zp;T6e!H;E>r*QAuzN5Qm-+mk@)KS(*^HoR6=<lUZ-%uhW;#<d!t0b{Oa->?+%eu** zlATp)lSW#YrhiT*r}@-?Gm8`5)GR?6pfojK`{bJ{x>Ds}F49N7IY+jXH^5o8Wv-;* zc`HLlt#Vg1R6dKAiYC5_@Y6Dcp&aEGc+iyhiy)N9Qsh;6w9nvmJ`xuls-oz5BEG)! zuX0{IuQuhi{eV$<V>strWix2G3P<W^Zl&9^eX0`XwYb^Wp(k8{1I7Fy@hfT41a(TU z<S|>pYZC(AM%H;{T~{A3yydRX+tLF#up7uC*6Li+w7(}&%O{OnVZLwqJ!^-hE!mcl zPx~4t@)wrI$zz1G_8_$D>z{42$Y?3aCvC(lK&`948%HFt706@LnZhPhH0BvNt>EoD zQdE}yxf9DwTrCZ|g$Cb2VUpTyH0;{-n<^hY`*|X~obt!2i=XPy=fYLa{9vH_&KphZ zez*&9GSJ^b59O=bUVa2_o}bSme-u{w5G;9SUtaVpdRw<l4s-TeJ*d8Pj3`<aT!THu zioY2ghw5J^`W*+^meg69&{J-E*)7^2r+L<&fft<*(CVYek8m0srOp(m&=}omU$BA5 zx^*}^OzW0Xj*}#e^iXG6hVcB@yL3vKX@?<So+<m*!K3M5WhS;W43I8P*r`vYv8q5k zJlyiIbf)xbG?N$7Q~KJbaHu(kqYiHWag|lKI-K1;V?ATOamKmh_UG8}!2_MQOy9LU z#|IdRu<hojfDIh-*ak~Jxdn&XI-{O7+<l*Ym%%;bk*E;$Xv0sOtwayQy7*I1^w;F< z%drm<AM#UoZ9B{HDBFN{=7G2)6MTcHk8;+wm}lk40>9}c`f=<V?Hu)M!*ibU>{lrX z{-D!<DUVJ)_e6Ja-!^#3szdA>$I2d-lZi2}<r&ZAr(=lydv8ygoBa`0a<58eTkLPS zXqVKEWCpzr(C1y~{w-Tb80co1_StS}_}=%uuRC(&XzVU+$=070G&$uV#2Zj8yWXtE zAqoG=pR|L&^7My$P;Kt!Fd}F0TFh<h1|=opSosHad9N&c?YQv_-=#Wn;sks5o?r{k z3&@>zq<)^UOeQ2hdP&~9wZ?;Qevs8-I|Ea@#Jbu>JVz&`Y)W5Ex|c;8MAn@4WdZ%v zy>wNdV|i^%`D;6oKl&*gyKA=_gmRkiZ>ZDa*bV;(9At~kMt2?7zB8Y`3VnFx!$A$v z{^g5N(wF!i%2yuwO82`T{oU@)JMKu(rrUSueD=eU&$Ii$7e4>R*sJ&5b02=ZvH0oU z{Ifs9R&pDekh1@!t)X}wi>}7G+IZhT(pGNXN_uu_IQ<kH(Uq?vo~d<g-ZcUx!<wlI zO>I*7Xy70HlaEB0;_%{O9Crwl%#*=ZtU631TyTW+9l4#ojoNe`N$22<j?q1MN)UL@ zJB7751QoV&2$yl4ttsfVVsrq{*%KXwI)y!)(LHnaVt4lHV)xL0`GM|(zxH>#V}#-x z#pRc5)z3NrM(KbQZWWTs$@=(Jdpl|sdkJGXoZbFHhu{UA$wocv5VVnL>{v(dZ9u|u zD-8#9o9M76apqm(tC@a4$ivxGqd~W`$E*46P;?4Q8xIW!>(>rxVaKksD~1h<HUmBy zi_DWYOE`$C6IUVIF;+*GhDx0@4(zO#ppizH#)tLu13pGSWpKtA)@=tysmCTFp*>$^ z8LQE34pQyV0296@8pm>iZ<QHKs5fvL?v}s$7{-ZJoUf<N_-hX50n%%XTBik^<l?0> zv7%Qo3cz^==B>woI7El>P4=Vy(!c*qclxQPx-B?K#^C4tU@b#d#H7ROSu1HHY!4NV z_c2_kS8ZotdT^w}GH*LpU;7M7Liro-%h+qFIrB=o3EK`W{GhyQFE|*Gx$&_LB|mh6 zX(K$-@nZSaW=b(?6nU6OgH!yKPk9l;8`<-)F3x;gcIZd@vHaHFye_)dhW^Sah%pGp z0Z9bgu~VnIbI1c=G0@zj4xU5Lg>^*WG4MwU_~*7Id`yeZ;2L<%Ayb3237v*pSYBuz zjUo5l^y7o#xIh{mIt`D|f^xmLqf!P&Fm|0?7Qgo1d)tqCM2(=lx<A(g4?K|lo*!pV zCXI`#voeUB_k61ffE)agK1*z&1C>G(@v<ywYFn~Q+hU`UXX)v$9T`LdfA!%2U+0kd z0|%O~$0>7=$)ueuwHyR@+x9GS?Y@Zn9)4H1{egSI1-cMnA+64yxqv=dVjt$+6)B4G zKS-$9ji@j5g7|`qPH4ZP4f0uHe)`l|>ac-*nE6QQ7PmIgd2Sme4e9;JlLDc%n#Z5} zsGmQ72_1z#8fL<dw!Rg7N7&XP(Pn%+5N|>Ka8$xN3kL#DE577?<&xX}Fp-5=Zr`<? zNk4R|4h9P5Zy9^g!w3ZjHNG<nI{O2P2Q(aG`=5>5Hd9A1TLKWy<;9uFZgKh&9vK|Y zbL@ppbd=}=CUU9)zMQ32wmg2}jfOV$5=rh8jRSnR%)S48=Bpa4Y0$_=b)~XWdNHY! zF89ezCXUDeXXU{>I>R#Pvn=29llL09=JlxORW6TvxWe#V=}^-d4OJ1=JojCG!ZJ@g zdtJZ2u)qLJj+B^d{?H%f@E)Anp~FkvZGQ(-fzLH%kcecwvklVT2Z_`fV>QdT`{JVe z9oMP5q7TWc1J)(V{)QN&x>eK!Q3DfB#<Ep}x+tp!kpIXoc|=2_(RZy~i@WV!9jBvP zy16w^O%#aE4I4q--P)l2w6Nr{fNkU9i{6nC$+XIo1AXAoHf`U@(}=-~CKJ}*|7J~u z1^LR}C_82hBUzdDXnH#aDw#a{^Dw`CY9g=^*i2YbpE#UpZ_=;wDFbq>WI(;9+<-zN z@T8GE3=YU?=mECkP&g~I*3oi(#zEo2hy;7>&*vTj?hhlxmT0iG44rH|*FNzlFRVi% z>bOuQ{b_Hws>RfnYoFsJQj0W~pB|-ib*iY#;XUv?)UVnxNLlcd#`fjHi%gI{IzwZf zBn3~HOw^(m)sOZy;^jw2{WgP9N|RTvcH7vp$jCw?YOR}-)OYQ^rF-3hTUR2SV-JZ4 zM=<U2^*&UR2(*cmn*_eOaY$F7=Rv)$zi<F}Ttg$Dq*<9t*~*PFM!&!W=j;;lO|Lmc zbo2ClwZXZ3EVTHf?5obJX_gKxY%M`Mx#T#hbCZ&hDV!zfLhG$;imNuM6WX>99d1sV zOFKWd*z9fxeh$?AFtkyh6FAIbSEqd<S5ZFjF8oH`;9=>@Uar75RTVo)08X}7;g7nC z0G>K2;kO8!H#Lo2i4-Y%nP2LtmHKN379pgxZtv))dfL0H$Lq@DxzdF<%8oeYM|SUX zv~%4Fz8&pN^&dP<+3juJTVf7QMe({9ho+BA(%L{O&;ypIWe?U_{@6zBljm_bFXQMP zz`<)9kOofV-dOop@cCQi11n|bu3=7fAz1KlkE}n3e@&lCLHxqqH@*`#7f#~f^j>BQ zjpgjyth1R3dUz<+S-=t9AGK=NN*=TEDi@yQYwkJ2@}#LcGIqfpoOLf{R!q&YDls}* z8_@RO>vP*|bT0Cx{S>{X&f`5dJ+3`1qTiq&&ppINT^VPyh#=#RGt`#`*jT=0%{s0D zp0btx#(s%9COR2CTkReS0Ym4M@BC&;bhY|DX?<R{XFecD*{TI?(Kwu$oOK&QdFeC9 zzOF7a!q%hofo)iLz>;sdF3#A66u(TXjFinT{v|iIb95j2P(GBiwCF8AC6@%LDC4qG zlt1;Rt9z6$+xG@0_+3%Ep4D*X)6SE0w$&Bfz{^6?pOD|xs>=j%EYA{vMKA!-K)gqP zn<oFbgeTP}RUhHK^(cpPy$iw0xXC;7nuk;R{uOvD{W$q)<7sEWiu@>)z=#aV0FLyJ z)>C|_%h<+Uv0wbYh$~$EkfjqK3(IV&;aCQ_chW#P4XweUjbo+RxV8c`IPuJPx?6U# zRT#Y7?lyP!X}~v+XOH5eJnS9L`|qe1H~AY}1E&Ynr(e+{EBWOgtBjezn_>dxi(mLc z_xR&aU~>~RhHd5w>36^T;qHz*?@G{JIpG`3CQ;tscvhfGm#!4^G8d_1tMJRDd!?`b zYF%Fhf;`1m(8h~h3I7}qYGcrvuuG?DZ+<VNR-rj|v;ApP`K^d2pL{ZVJzu(XIXcDQ z!LvA}FI~BuXxq2G_2&}-ooyb-t6#^h!d%^~O>9|Zn>6~p2#)<D<@rXx^U~?^hWgwb z;!R-uguTu-jMhprpj6Z!j<d8a6(3h4pU3xh{JH14%S@UWxZs$0BV&i7M~@P5elWpm zZCgrtYyiiMJcu6wn)PxhAN?-cBVYMS_u&tJBzrV(#pgDT4t~p9ezrS$+tI90eCo-k z_~yuSk&z9IX>QrOuY1QsZ>J+rw^UG@V*`0?o77hITs*SX+$i(q$sO*mo&PTn>_`4~ zrH-#^Nll{L`K5t3{rA!-R=v?K<Teq`pZO;rMrd$AXzaqMbP9HGG*+Fx4))>{hLI`) ze`ZdB!j!prP=h@csmnFnE6?f3=oAzNuQf1KFm?)V9&Ti=60OiEJdtkTx(~9)>5Esp zop(LZ{jI<MYu&Ef4|mroa>Bth`yXEB<5$xN^ceVREU3iW{)$E{X4cDhbk-^}mvHF( zQW0Iod8|P>!64hnACQZ)$^1H<d~Z4<ucH7_ayBBDH;KQIpc|bz<(YdDJBZS#5M~75 z4iWqvG<cQzfs60V;~um&JO>kHwApcD*!d4!`X&&1*pYfTs4?QiM(h#e2wXL4tZSkH z*vD&zr~tPH*}Z3P1|?^SfYzz+SA1u$Gq}+Zp$va<X2WxjbWW6&k9y@v{b`D#J^De1 z^NLcJkNn^wy1NXEIET1)kUBf7)3%(rQy5<q-W_5)l4+d(|DMg`zw+5X>GtBppFqw! zKA@N{HA5feP@1h4bV(xq?GUbbDnr4S_e0!k{I<HTPH(;i@M?|``B1nvh`^)V+T)TL zb|xAuU)cy8%8RoC$DT%$&l;UtIiU;SG?<%wYp6N^R1WME2N}`XCWPJEi1NnE+$%rU zUD-CTvf4UjowU|l$HFl3G{fNanUl|Vr*Pm7G8lD03Lxmn_9SfoFo@wcWOx?r_T3}{ zi5c<^5Y@yYOiTdwf<xXl?5`syb`--nlSq<C7Nc1juUlO`x8FQ;XmyZ^&U$+IUYa=B z<1g|`JzQ4fpg2yj$T1F39F%r;;;i9Y5rYAfKSnsmn5KmY)ACH`G9Awj*jEOMmTfM| zm%iZ(XY0B8uuk$)J)uKv0Q#@zyq`VXx3iRSh%)5aoX$mZ-}0Vcz~Ou!jHP_!Mjd(b z#A({yJRkGghx2YjB4uC?2YG=v$N+W70V4l=#*mN`TXA4?o;%C($c_(vj%~&XgR_vW zbp~kcyiQ&75hrle&~_|7h%;gkL)J;IOGH-BE}-`|G5N*h&B!nYogXM<nfDT2f@LO$ z2HlSt2UnKev*m>!akz5nYIp7Ob(Uu?b$br(O_cK>4rSXK|D)T7DRT@u_~DavIM64Q z6Pyquq_gfB93m5OLNTaW!r{Dh9ld>>$Yz|)!$j7MGPrTTq&`qT>R5Jg&IQlp1r?Il zIw1MUL)(3Xj`#A-!@pkVy=jupGjtM{q(vw6c`QLK+K%v_bUK?${~-_jtAqMjB~kIm z!|;g<;YI&48X{|cHyl!sS$O;+vw#CFtHHf8=P$sx=UKb9Fw3*>T#}A+8Z&a}Gp{{G zc0C7H4-@B?u(N#vsnY&1=H0j3eGW%yV`Dg>25938;ATH&{naBH<3=?*5jlk8YLxqN zBICz(QfsKg^9&B6N8yq9>2yN&s(%(44v=3N<m+(eQSqdB)^vjB5Y0SXCXxb&uGF`$ zZ~!k4lb3d)4t7bbZ8!rJaCShQt*5{#GC*BI$`DYvy^hm4hm6U0%Z&rUHe=f%S?LNh zSuXXY>|trf6Zz*kKN?w_1;Da>XHd+0=_gL&5Qf2nz~r9Cr5k}8Aiydj@j{>>nCGIC zrMabnp!^e<q*>8jdBHog(;!1nh07oJeYVs=yj-;s8IhK})v=QSJ1aA4BD|c;^48q` ztV=sm|L8z<lm@)-T=7P~4UAA+oSFg2>+lF%EPpZk#j`CKdVGYX&rVui$4PqKt-#1X zO=Poh)b~1}jb?V`)u??K&z5k~xaZ$%_8shAckt+n!`bwqL62xASNiMXL-9=pMAmpG zZQ5UDtJSj3^|qyG??O)>N)vSD0(&(tLWAi!wkE^jynqg!Ucin7oj?$7G9v@Xs<uWR zKtn}9q{B04Db37PlkPg+{b20XL~>3|UF~MLzK&x}J*u5yP=oSkgsG9H+5_5cu@|8A z2<=+C)u4xQ+WL;|d^DE6)_uJ<ZuWypY@?<VD)MEy?WdkZI=EMkO6J5B6w^*hMq;a2 z4tAK)dD`kD{H&HbJJm+Xl^ppn|MNT|Vpuly&HJS1n*OX@p`Od}oXF-}OVmp5+2>V8 z@xG^cJ@W-gN&}Fz67o<G(A<~psF%5Gve90poO;uMgkOy&p3@dB37w>!EZscM5$PU> zGau$t$2c)(pF7MdGV_R?eanh7+&cNoo0a0+QHws=hegv?w)yKYL8#u}w>Pv;qO0R* z9_EAXjD?nHZ!884H8D4lAN!{IEn~N&J{BcS`to|>rHJ(TyjKs~Kh83Kn#D<`v-vuG zdi1mH6uC6uMR>|(^sRQEdXl=Eu5GJe8g-GfrVL6OotTzy4WpOCKayl(O1PHcxTIEJ zE`Y}(I5fH%L}5Nx!D{~kDnBJAt9+<mzR`i~%k$`YXrs<_Wk~zTqXdn!0y*ErxX}Ku z#u;ugQ{NmK#R1}KH8Aae=91slZwcF1<_i+?U0HDgNje%G4vnOXG<C&?GE|Ob>MZU+ z^c*sUG}K?Zg+?{eKhA2S_3NEj8fVOi9Yz%P2)3BLn(Pz_VWgb{quRS?e)0-DbU1gc zJR6wfjMG`0QZ7U;EK9ywF8H@=^;-DhJAv`O{emCwy<dUhYY_3?=g~F3_a6e8l}x<1 z3}N$_Yx&JP(^Hd)ZTqoD*dmVaHC<-=rCDgUNJDWYX+DIleuZbPOryhFzpfu+eYTbx z>Yjb_Tiw<T28NBXT6qWk4AJZoi*lovxh_6RKpf8WSqBcjGKaI2Z-=l}A9ZitSQ(4M zS)Kp*_a5*5^iTg3Ujf@<p}((One5*7wzqe$dF|b7+qqM6^he=T_f4bKGZVmV{+7<@ zGrY{H$;itj`OkRugY|uJ5KI8z<8U0|HeBb}&TBIPP4(@M@&oC_wEajASC0E_Ep@7G zP~mQU-?{VWIzJ-!v5$SMJO2EMj4hAccBK2I_y1B>(C%RyE}i<ypJR0GNVn_Q!s>Hv zp0yoN{Do|M$!u$@|4U~7iF*-02@^s(iM91TY-8T5CyzaQtos_<o#>bQ{`bGnw?Lkc zt)j#E^{;<@_Fca7&O5V<fO(}4T9Wa2`4(G*w9Q02#>oah8u%N(@f)!(v{B{Tul?7* zR?*I^a`1a0epK)TW%<#-zx}s=m2Fh^vnUsR;<#3wu5Rb3eu#Dfe8=+9C+HS!)3x%n z?6iRUiT-2VUd<!WV(+gFYSX=IO5Mf_|IepBwfyOS{M+R$fH4Y)ja;RzGRyMPet;)n z-#15@j)PM2#ZWr{^VryBa5_w2ikSBiJ_U_`8r2Rm?W}FvS5Xo!MKzq>^ePzN=^%dk znWwu=yZ3kR{crwZ_Y42U`?`}?F0o|<k$4zb4z8wfE?p!Fd4$f~GIVxt;tQtYW0Z)? zSJdJf<~n3`fNf*{AC3CFqkQ*`aa)REgmi)>#YQ&^>mnil4z`T;n5J=DA!@Wan|JZS zyIs5a=pD{Nm&6O(L7~yyUVGTU>}0ZpgnBtcz0N(TLJ!cARy?x|>1vs?^Efr>OhP}e zpdl{;TO&&oW7s7|Mhi<{2q+&sbmB=nrm>-;b!J~xoZ=ctSE;YjMJ@@uKBL1KUYSUq zd8P~-sdSG6C=pCTtwUT_AAaym-nBy<#6LXctTbQ}<Qcc%ZxQlVLrg=50LWPkGX_+f zF$lK9m(PCc)7>BZ{wKN}OeSmw_YstecAWb?IpB$rAw7hRT*{Xia@4CijU5cAgv3{z z<f-**ztA%f>W>a*m1*(8sN_;uD@n*djIk$Q9W*<Lqb8}BX@u)X0Ea+$zXL-zapY&( z(1GjFgvvIju?p2TU_RS{ZOna<=Ny1yglLGR{ZLQyS_k1Nqn7QnOb*F=U^pPOPVUt` zj-z;qG*6y5PL%UWK3v3v1OrcH$^B4=Ffb?RNG4c*IZFF+>xXN=o`wdC7(_$tnQfa( zq%nDCji{pjax+c>aG}(y8+eF|I5awVo}*44jn39Z2eUKK*2DB(i?{8|V|6_pkh{+w z2~$t=n0ED{<5oESEXT7m+qUgSFJZPrUbM8n*Kl^fs?~=)QHFFtWs(7yThRskiHz9b zV3Irl!GS{^Ip6Z`_jEhn^m?8_6JXlzbU064n}e>q*k{Tu3fyxJKH8q4%Mc&*(c#P; z`JfXHV<&dpuiNECbF+ScVMDj`79&lmvm;TXASE$$5ibx-pJ=|J<+(WQbvR$0hRz#^ z#@=%a^kOvwyd31CRyv$rH8H>*c!N5e!G=99z?c2!FHd!s&R^rq$G;9A>^5&_@@!O@ z(xHr#58mnM8;AbmEMIcalV#SRWMqxbp?P#{_O=EeX<^iLmT=Bq>z0Xh9&$Skp1E(c zbddfqAo*i7`<$P7<8Tf?Yv3xq{mHu=xrOKCmxuD+YtK%&<a#9y_Ye-OT2}73M=vBj z?L0cR!H&3;Vecc;<}BP?dk@BeFIr^ams*iVwNY?MZxvHb+lRkCJ(=qol+51aMg#D_ z4WWK;$@g_%iINunSzf^`hqI1u4|TWEKRTRgKsb?cI1?c>Kz{=&nGlIw!%HV3jcOi6 z@A^@mVFuJ=NncKA9Z%}ROuR&Ig9>NcvIBuau4pODH~=X-jtt%wuAad*b?Yn33#(Ys z4kn~+^g2_zNWVnmqN{YaNvv{m7cTa_t~L>JoEKh^#$R+1_f9t1zj&zEYekm$+rq01 z`v%KXFKDc)3-Y$X5*}sPrsH%5uVf%k*)qV9;oK`=Iug800sT3wq)f{Y5AW6OR6azo zuHs-xsF#(aIaQQRuTwX17nZc-U!(wrn62^Oy4kv85Rk_Fu1K+8FrXl-w}2rowr~5$ zg15SG=>)#;*#Um42(7eFw51AXX{{R4(5D>gA?>wo7SLz5VWR>^bvQG?cdIfdE_FIP zA+OW9=&Ih-cEl+Pz7P@IO9#AW|B>!)9M0><jZ~{Lf@N>GD(mftZjg{1(fJ~m8^HC? zL&H{0Uqja$$Ex)GLwT~e%(hsIY@M+<)LpsG<ZJ(NK;~<+Cpy5Rx1^Vc5|DaWKKS`q ze99SVG@gBg&UXS6a4ugVnBmxyPj!==FP=Ng{l$FOLc4m7N%=XVO4G04xYABg7If$t z6<<zg+Bj_?_5<|Zx_M`}k^L3-?BCxVyzN#Zfo|a=+FLVuT=G|XD8U8IK|@*c4}z@J zCGEuJDA2$q=+e6Ocg8t@?ik^nua#Myu*pm9t!w479A%^@I49eZ@1zpkR7&&nz8ub` z(Vi?k5C-xK6X@!Qz!IMMh3)eOlgF(rFZtczFLx&92zKVnUH_-ui2F*q8?Y^-+M#W+ z`gr>tX*kaW?-CB*fgx6epmW7>kQI5uOzO8bOzst2?Bn>qa`eT$q{G>IdRR-hMr-)_ zObWVR^YY-jY@@MgbhDFoFveW6)E{WBTsM0kEJ{TPh{HO1$WxjcN3}Qg-aHN><@Ne? zK1|Hnx~Jb&4%K<m0vXB#A=f%K<7DNTm8~r`s*K1l&pkVtT;)=B=pt>@xAi=97asEE z^&*qjOSFlUtsRA~ksf}FC(EpHlFTF1#;+(@=~K{QX`9eaot<r;lxO;oIIL4sQqxe? zg`0r2k#C9!H)9LvnZ5zL+X<ZN``ltuogB2&-<n2V3d4>+_=4jCIyaLP*sr!<ovX1; z!8QF)cx1iF7I^S9=k|;nKsvtMxPFYbJi)e&72RxEw$qp($pb!++`a&^<+^Ct-;+>X zy9^zdXD+eb8NYeHt&uUF^)X%HB@*f#`4pZZZQ+@K?Kef1!#wrlxiV$`9+%cn_}+(s zWg6l3JT}b>9L_!M)UO+M9PB1G^AT)T`yD@df&G~&1Ae%QLoI8YP^YC_{$_<4aIK?( z9}|rA?T?;)>Ra8qQO5k--@^Bp)*0l642Vz0HPBanhj+kq8<m3xZU^Gck5>QHDOa~q zg#z##($#Su{DKx|&Ya1%8V0i&$aV?m>YLyEGwfM=4?25q@CoCS*Y+%wf|RpN_lVAu z_BTIjQn|sndHS`aQ08yo_0l=4f%Jw5vMUEq=+`SMwfY}HkrLUmjTrH49`%7dH2}(V z`c>RZSO@hZUwx$eJkjD`{pwe{d+)iod*A!t*S+z9Hv-1Kc8OKzd~=I7t!}c7i*8?h zPdiardGf;RHInKD{1)7c9IH!sk=H*lk5;-+5MFIxwf5l{{9E7pR`=P@em1L<PoF;B zoj86XTVWc^a)9XOdtY}?cmEsi?~WWk61}XQH$S(C?_wS8k})W?b!@MXLD_MImT-Rk zAN+cp*9OuVo&L}}9?B%l3^wC``t$$PJ@(zlIwuo+{_giYOrQ)7aE1ZPF1dn-;wYb$ z9eE#pkAAEPKm7^ivsn|dA;eDw&(y1Hs?aM))O5>Qvb>`53)6fw@DG0bf246&2@Wt- z<T6fX*-&e#1I}L@IwrF-O0-mulxa=V9AD<qxt2&a(&#AEXiJC9wNAqbB56D{nqBha z%(KgXuOp<+h`4O+Jj!?i=kEvp&WE}O{`xQF<3{Htwic@Z06+jqL_t*9pH_TTM9y&Q zXqY6rc#()+1<xo@_i5HSr^335lUN+>OpFj|4rQGrSD5{>qjXTK!%DbDKW`yQ#O}hG z93AjFGOmEjoE<jljm)uuZQr(?8q^X<4K$ZJPcfh}+F5$&SQCcz)i7}>lul?n0O_kU z&0h@&bV}9$S48rUbCeqCbEY)y8XdXP)W#)GiXW9$huQoT1_g@O4+@Qd0~QqB9`!+C zI{;<)4jwgwFTXtObfcK%5%-v{(5;Ll>#Tued96{mjwCqr#&{Zkfg>8m!J^BPt3wxW zjq*_pff%zWpn0M}7jT9-P(6C!K=&xyYJB|v_~#fzv)xuE4K}iut@(7=H~jn%lyIf3 zG9_)@hDBv2jmsJ3Ah~Gkl0)lNN{EgJS_;d~-}=pI3^<S?8p5T@QCK)^G=|`4DJup) zc63f2tiX!lqN52T3YhsY75XnrvhDO7i&>U!it<&mF<_Z}S7v7^%gFxF5C7`<YZtpq z$fFY>J2!75>U(cD3hvfVr}#L7@5m8#S9Y8o6c?Sj)@6n^Gt4$K5T|>V+23Q&KcDyO z+|w62xj*KP^=uV`Gk=05_v=YJhJ*Gbj?U9W?oZ<YT_By?a%kx5(8+Q>s-YgDh?JvT zMoy@korb*hkcN>B5;kK@THCIaZ=J!7Cw_Rq^v*t;R^E8{UKkpS9@0!lM;zdJQh%JR zYGp`257V}l2wq#Jc$R!t+weN+shfI9IkG<Ll5#d{%xb{0r4NqRTet7(4iPmxjN{z_ zggbdGC_Cic^PYEi+a7pbZ-i@9E_SC+o<rZT+G4y0FB>)!UNP)abd4>_B!-;f4E!%= z^8g?7bD-z`h*y~yyL#2hit%pOKAqL>zb<W9DvvxVP~IzR8fNa}j5{Rz_+7bjt-Ek} zi99>H-M8$gv!9}!;Z%1&N20E5W9(0Z1KPH&OrmFKbJLSE-Gx(E`1s7VZr_nZ-PWC( znV?{QEo4+9eLW7z33P~&&9+<HGKC|Du83iON1P%H@Yj!0mV=TBF+YSz^z;%D&hwKO zyQLW-ofp`LUAX~&^_KKdzep3|#UQ0V87aXd@9QULD@_=~WgLyXufZs1uYqHmXxH8= zA4-PJupQBvK8Jph1+V$7KFs5j{CJnaA$Md6%yK$Q2Q?sP4)s1F6qq&mAs+?%(M8ZB zpXm#z#iee^+5ds3>R0uJ|F{u+?oDCV94WH~T-nPR=aaH)J4~BI|7FRklUVeP&EYIO z>El4!6*c3uMWdUY=yGeLA)+PQ78^#V=EHpSpNWt}K*h~I%QDL0Y#pSDWm`PR@=j%) zL4G06i)weNllAIp80UE2I`A{QQfdEEdlYLws8^!%(P!!d%e76{Y7=Q7j~mTN+v^Y~ z$>gnY-CE1-U`WM1CHOG;<iC1MneO|Bv<%^aGjN?C(Lt!rx2_)5cL0xjb%araktHW@ zld1BXKJ@BwH$u*P9S=c)KgkFEl$Sh{hg_sBfTQpE8yZW0>6%Gb(&QiaVkI7Nf*=R^ zz#6m{Pr!mZtDcAq)KO^!u{2cI>co(@I+iUvk}NQ8<gtAiei7<#Th|u5@hjRIjG(Qk zZC7@p_v$sVmcKgT)Lq&%My|M&{2G0zUpu!?C?4x%<e&7V9_6&_y4N1Oy?ZSKfA??( zonFqWwaG!{IcF}VbtbB~P7{KUri`uxY&hPZ&6;ZFUY@llo`n@kP~I@xOpSHdh-{u` zGTALOjC79fCC@UpLZ1PgK~N%6lJe@MG)x=EwwUE3&*#|l(C>+yK7Fz~bMiTsqF&91 z7bjUJJdX}F%^Z8`N2VfMy<Gv%)ca_|;EhN?EAE1Kl@mFm&>@_UL-gzG=-)T+!O$&P zeYcq}zwcqYq+Q(}9MIeO0PZH8XYeXAB42Uls6*1HD8tqd9DHxT6XzZEiCmDcR<}4A zDc`^^^e;W&{AftQGhP&pR{fQ_J{SE&^-^9@+>HIZ)J?e%2NFtyL_3?df8O9EZRHb> zg5BS9XF-ACMcw9Xiq%JCuoCu<D@DnceUUO&Z9!Yu_Aoo=HfA_Ra5xXLqD0vnW|{90 z4(CiJ+w;h)^g<+k0Zph~L&9=bZY)Q%+smqvyzpsc4f$rog>#v4$uJIQ&$L%R46A&s z{2-f?;}Icsi97}$F_NA^i^5Vjo{68W%94`~U1enR4E?tbXJyv9r$6MZ9x!iP{gHbe zL_CiiE4TcTo^<L7^^`OzhjZn(z_eeU&l`msJi!Y%%7iuddoiQPpeqR6!`T%&>aHzY zbvTa_48&4;bj;<e)7`Waj=<1%wO_VAXej>DX31|q;Z__1Ru?w;-oSWc3)_+T%)NYT zqEcOn?L*|HV>iF;<7y073{fS1@WehB=(c^w#?~)U&5RMPzxq$TAG$yv_y3M=mj#le zhoipEb)fn2JNjuHD_gg?BG9oUeLDSM`d7-cUM8*lzybiE3%2zZ9`|1OJiH=6pqriQ z2CiSmV0L?rt7hb#Kl_|QsBA0h$UmQXuV9reR4|LLN>k;j2^HxguPdMV{m;WZ*WoOU z3a0$2_u3{6hedSj#$5-nW!chl-KOrT=gtw}0q^0-b|Qf1pr`ax7E(Wm;IoXsfnxxK z_N#r}@n^o@4J=;lHZblvv~M?Z!)gRO6wBoRMD&`v%{Hcw;K2T)d3Uov1)|_oTHEJ~ z<uVQ9NcANN9N&H76aR{DQk~6s#lG+WW8eGkdwqA;U3V2yVXUx}-$+-k!*Cz>N2L2j z%WNrDpKqQ}{9n8dtKq!z>uML&1mLzW+o%1Og((X@^N3Bvz1xH;NBWSIGkrSJyX3NP zJVij&claLApW~4H#y7sv-EqfV+4q<1tPYxCyT&(m_r3o9&^TlCFpQT9Wcr$3b|auX z&olMJ&FLhrrdvC$)(W#AzuJGR|F}6+X)QluclT|=zQB4qUVrB4r@JqI`Ac#5Z(;jJ zeQU?~u-|%o5L>ovOQ7a01U$X<=iiF{;(G$XlGkH=Q^tuP@lcOC&i9=#jb{JoM}MdL zkAM6h<Gl8JPj|oewc(`!c;EZp_u~I~_~D1UpZmF=?+zb6j4g&-(58k6lGBb=F5Jc= zddg~oukXb>HW_tkI@p(v^<$%%cBKjTJX*Q;<xlQm`*`(_o(5|GZ24=(q3_2B{^(Pm zT>j*5|D$BIgLOcsv7kX^XP|)S*z=iAO_hWn6w=`;qkOMYFsj(WTbybzH^`76Mk*b$ zoL9)KP8`g@u5uX6A><qBSXByF>5vx_0XW>9J%71dU>f7^{razW@BW*AqniZ&sgoxI z+hr3P0uvYj(%qRa_xbWrS-G^(CHe~WB#j~tC=4@aTda=`X$NB}f0dz~xK2w46x)bs zbejwv?9#!diKvzcG@#RA8L5*<Rr5g?uN_p*0{<ExTGN?rWu>P^Vg`3yr(@%V^l>0- zBeX%sIYv648HuFsYvQCbw$Zf1^vgJ^tXpGxyDoZTd`?Yb6hTWeEz4Kxuo>t0lm;aA zni%7w3>e8Z;H*Jo6{rx2I=rJCX(OMM1v_fXkxx1Eyvi?QA;w}1moiWWb@XE7k*zux z^68Y*ab*<iA_LH2Ja`Mx^eWMicOE(1o%+kiyHEU|AMMUP_iVR?*~!f;<G1Sa&${_@ zn-pcuNe&PBCcS;90#hbKU*yfmEI**-yP~5VN*NiZv2IgLA~;wcjl)?-po&aa9>xna z7$vGxqf9;*9T;q(G;IrZkQzF(z)3U^lO*ey%^SyX0Spjm3n(|sk+-%3BbklppAm0< zbI2Ifz~OwE=wQa(z}QEm>FW;N)~$nv(i`N#x||=@Mfxkd)=7ExSX!X|)KwZ>WK!lV zAK}w^w4ND5qd>%F48a<AYLG#uGt8qzK%Tg8t~*I|l@8}wqMjFex>Up{@&Nt)c{F(w z2kD&l5B?su0o#kR?798SWBN8hAkO|Yw4{qLyl=WkUi)j$%`2?chxr;Vo*N!IoYgaF z@8BU^^GYw%v?EvW&iCdQp4Y1#&|{+u-R(Q~c87=>9%Mk1eW?(}MVu_sWB0?q&~3T@ zH86}DU}*hbIC}|4g3F?Z)84l2+QvZ8$r24tB9d_Wy8rYtPGGl`fV-4Q8$b@Oz_Uvi znTWVP*6q8MEoC+_n1x^NpG_BuPOy_Leuw~&*o)h!_(?i#J`{PD2>12dyIp$^(AiHR z)0DAf6ck-A(ay{!V0^<fE(b@{3=Alz7rOH&FLxKtT<!KBxwYGM%Qp5!V{(AO&ICsL zI^;YNZ4!<;+J2RH9dQdR6ZE5Q>Z3s%tEeyPqMo4r^O2f3oUdN&mT^1}(Z+N(>rm1t z&{3fS+D4MWrj3RAd9UvAU&<q0<1>v<5$5Ex{zrQ6^W)k{BHL&TSI@A<ng*OueHPH3 zQ%b?F5|fT1UidCBMMt<MQF_!d^1ZIbT8EU5o5eWkz@w@Iup4Pp7Z3ncA(iaajs(k9 zbcDnV=t^bc97qFa-jOa2XJFTs8f2rLWEpWE;p|6uj9PYYWh|`ZABLamf>D;`x+LFd zuQ;5UR5fzg$W-;mFq2!ZIPzmVWqgWO8EUo@D^RqgBGChYw|%Ls!QHe;pX<8M05x@| z7Cg6I*Pw&Ez;n>);Ji5_ZL?{U8i)J@@4a=<VP<|0+phg+^|iJAgYw|vWU&KJWvU$w zw*U;qL-o?%;6(+HPbka)-pMZeHD$&0=FNbWRLWSu3L0i9O^cE5lG)TB9Cga7`$~`1 zB)e%#Mv)T{6MlbIwyk@~xGA9*b+FE@ju8&%VYUp`rE5GEKCI`iesWUNefJbxT7Tc) zla?}!E(w2SS)VDifrs{GE>oUImSf15$0E8kgE!!16$G-Pu_8^xP4SdZLUgMTZ2+Ck zZl9rJ%0A19+vt9sQ{WL9u+He|-~qh5_8#f(+IJf|sE=^wy%qC)xD`HGighhorBv&J zbHX=EaZ=_fY0MYW<Q+xSy%*NK|LaywOXQ!$D7i8}#`g{A%V=Y9+@)eb0el?JmX(}d z&^Bme(QnYo<@D3j*qzuamoJ^`jz9ejgR?7fIG@AmJTo(uXm6vxvpqo~!_}n$2oB(H zoqZr}`f}6>PBaGVDz?)2o=9vI0J2isnXIF4cX{$QCQY~R*wyVlxWC(T%U&GMd-Gvg zZRGGweL?|oI!jAR^V)vN{;)aJo%HZtr<c5UpJ&E<MFa2*jX_N9<l()CG|FTQSK%-3 z8~y8j@m0F!o|p18ye6{~KVSzS)6u8()Tna$ymo3yXIkOcnG8X|lZX8A@NawOeaX~~ zCxxdV3zwXcc?YdG9L`P%>u_cp2A2AVUa(+@{(is-WqY1}V4N}ntID^X1x3rwb&pqj z*wfH_!LG?(COWVh1{lm^zb_5(qunj?UKx>(ssT{Vk0!=h-ReVarsA&@SaBZv%yRiT zVb$uajqZf9AMSHP#0eAglx|Xg70sK&Iq=ZMIvBJOEGrHo(g`#DGVhC)^&TvOb8|Rr zQ~1pl5}_9yKWUS()SmI-ge&~e{{~p-;Bf4+kq<|y<FC_>+$;VvlUWA*X!Dg5lDY%V zJ%F7&E6~&vn6@Q|Pf=WO9w&NsD^Zc^*$F3O(QUSA$C<;Ft<9g6dc3oblP|VYm>+o) zT<S}`bvU~xyEM`sZ8oT5<v7AYMDq0{3=ZO{Rp-RL{qTkjZVk!G1tObA83&Ef*wTV5 zND_JS>;-p#E|_^x@&zh+Uy;u}&slNic4y0c%z0q;0-5NOdONOkskrrg0#^7f4|~1@ zJb#*;luSX>_Fh~}-=`@=3z3W`g`N5<A4-6D%bPw8^qknXJI>}2f?}RKO`sQ{6*`<< zz2}6oG8T)bm`Fc&!{O}5u>EkN{r;Kfk9RYZCx{SV*Bv^ri?gc{<d-xH+tdC^ck2ve zOO5@v*UL5hwe8;gD7uS}GHcuTS2&!XCn!k&g&>r<2j1`iAHaKaV<=#Sjh0ItOWx{P zUnZwD6@POCSEZ=7(U-95`44d!8THT2VMxzr*S&0NU}<wWxp3z6+3w>X{{;I1vsDcJ z-^}zZ<ESg$&%gC;-9ztuS9kmEN02X|DUbFOXiCRl(a-2;q!mK)JVId`Q?g!F3IMO~ z+_?Jx`cOt{qVnb?+m_>RAgQ`neq_7`ZS<>MW{mpSW8dxm^mCu<b~5?n7H)orV-H)R z?!?B>M|gE|3diuz;YVW&8&<hVODFjpr#P0d{k8G7yw+*`<u8A^`<>tUD0`cKuhZdt z`0(LGr)wuVmVe#rUe~?<{qN5{(dN;2XMbY5(H0TMl}SwbOFg_FVpW0B%{(bPRzc|L zks!QYELZFtUITVbvU+oB{-{%^gMZXzyfl3E``V6{4&CCG8lU{1{!t7Gw_i{g>>w2! zudR^|SDCJm=$Mn??z@~Oi9q^XMXhko;?PWV3+c@7&-5w>Kj5cPVyA6dJ0;;NR2#-v zwunK##9&z?>H<r>=P~B~#)tl1_rVW+s2k*?GUwPf<MbK!NX4-%jt=6SakjHCT1JPn zxCmQ($`MCYFEjJjM+Yk+Uo+(3U<W5GjR8p_9u8)AAn<O#QTsdB?3yrjs7>&JEISE} z5uMI{K+vV|*3tJf=?qb6cAgyObI)iEBn7;jH5yxe1a3d;Qv+&gNrUH^gD~^zM6jch zrYlF3W*G!A2Eaa!GGJ;**{SK^F%ozNLu{T--H5jRhi)Z$oB=4b80Bl$Lu^Z+0<g?7 zigaR^fuV7lfekP-*rp8ei4hSa0g5#_ilSCgQ7`i412{3v!Qajj7$(-q1cVrnF~m_o zL+JYD(ShzVPP3zj4s>(u*Yk&;_}AT+|M-u)Ekqn_XDOL8+43mz2&6<a^Q_fb8YoB7 z(B-A#sc>ottC$9mC!d9ezVaHnS{LQziXS!8$U}~daJD*5swfo;D6JTtJ&jb{4$_*u zI{=B31P5*`e$uUX-&7RwG&uRQYnvtAH3pe(4dQQ_foLQ|wu%d<DV`bSFaLMoIK6A% z0UYksA0A<8gKO;tC+;d(Wmjb?e%5Jh03+Fd$gqyLDF*kvNL{4O5)~WJ@yURCj-@Ih z;GWMXE}rjBP4Xd3FtyD!hqE$#BcclgIl_PFCJvVAPu_SmhqKo{m$tsEL2czVpH5*9 zoeybyJv{kqKKZFUdN!{=VXZ#ocf-ZAhi4~}Z0ok=8ZeZzzv%_b5ALLQ`KM)?uf5kP zoWTe(J~}+t-LYqXcVJ>`x5NiGgDdo2#_+dI?0nBVyUlO78$d7-TnCZ=OYAj&`SJ`p zXQA6dG}*3Oc0mjs&d>+PpV4GGB>i}j4%qr|Ahg0rp1OLuJA0ZBI9?m*4jkFTV9J#V zwi)Px-bw@sd1#T``-Jv`l+GeolXUXWpJX-0_?B+>UiQD6U>g!5oOLi~Gj&zDn>+Tl z)gbTO5@U%E99}s$*<HDCtvhh|R-6&r(SPVp26*Gtbr{);lNo-vU5|89huN9OFi9O8 zWP>Ah$}(tM4uhISBBK_j*fNEsxJEd~;SA2^(|JA&4TY_7z{Sc>9g+XOCtU`zTyqnd zja))+&t+(6V3=0QsE5>HrMEORB00(KGt&ab`}~XK)OG*NcT(7dfhk<ydFFyzl1VI~ zC;ClzUMI>~{mtNZ9zJVefhNFABRpYPPvNF%)*suEXasDo3VwfC<(Yu2=?CPzIzSyp zd!ZZ%5B-r5+mJGhtQp}viqqL^x7mn(q+cA-(MX@}-pyHNOrAjp_UIAyo{r`*_lab} zK_hdJ$Q=8LiasqTF(q0Z%J0i=xPxEx0_kH1pi{jUzZztc9vY@!17G{9qASiE<V(k~ zHiWv{=MKKL9mF9;pvM}Xwr}B@*623V*>)Y&#<>lCwRMCzK=bep%7Ihq0m~*)F*o>% zbMO^Mc&VO=!&ydBRyp5wq)K}p`OoTw|J7fVj8Km0!B@jw=dQRleP`WLZ_XAkusrMK zdPPp4vj4OlvVwp%S%Zh3rsOk1S~-*<)r?9`?fbL=>}woCjaYB+F_F$BZ5;Okjjh3Z z>APZgaF>t!L0fgPw6mV#uMV)?#qrorNNA(P*24)|`qLp6*ZiFHjl&swx-YRGHdaR$ z9C!?JmhB3hYU@iloDaw0ybin2{?B$>t<u&IOu6q5-bunb>aEv4Go^ToZy!?23zebo zc!ACet@{iM^A*v2WtQ)E%;78t|C9*7qZ0teB`Tjk9M%w_$hA(QCH6(tL3fU2qR&13 zefon7-7`-<-W`ATX=vBWHvM?<8$QT0c<6m>BKgP>n=ADq4TIxlaps6UrJY5|R;&il zz5z@7p+3Lws@<uV>_f*`xyNK8&gY|dzBV7;Idm9(zi$uEH->laEgSyIW3F8ppnXve zXUnL=dwH!~ujj+IakRoC3<n8abxBh0Ii!v<9A<b{mU#9;PH`^`58EpApms?Y4)9DU zWUl8V&4gu>3;MFqv89oo9P%FN$+i8Ru=9{7a<uaJh=i?tQ=2Sja7iCkIHm8Sj*d6x zh<;ykYcD?5JIFrHHJG+9WThnzXEYOF<Xx4oL+(a-0&j=?L*ZLb>e@%5B__cSjNLPu zmdy5Nn~_1sN(`pajap#Jl4g=DXy=uFP#jkEwc7T!3Cm3%O6H6uaxY!f5l-Z}_d4S( zwzIg#_^bMV^O8nBn!eWuwq2jwznjj!yOj~$+m~gTeoWjla_znNc~4$#4sCw7@Y=|h zW^UuMWBb-PAhhq-v(K{I%PE6?pjwA;P0*B6LHpYB=X)o#dhFWNTt1o}oycC)i?ma5 zHBe;cI`S@Wuzfde-$9>&vllzksLFC^;JgF}%QI5X@B6rCy7z89<@hQ56GmSzw;FSG zZSX)=)S-@drOk@NS$<jV&_%vgz|6*t>xta<J453{<kA=8Y$i#Gzo*EA`PxtV)io$o zTGOq1rcDwakRabi;Dgc2L^>}|pQfK<D@eW@R8IfOq<yy{JK!xa^XJT|&Q<To0*~rh zpPzbq-=2j&w1yQ~;hpqoljXh-4>)5kbwfrXqqF=L1q%joI1^aLMA~*H%Uqi8gqREI z9A~MI=7`iWaHr&!ATelWpESiJ$;o5it_bJ-Zn3bj#>Z(>)xK<7&Efn?w$!l7)h@ky zxr4fao8uS*&+G^O&A<IO-SOkkMaQZ)?5E%K#y56vecRiLZqYt6nqMYR)uMG@6C^iq zhcho%_$zuBeM2#p^r{^t25SOmpRm#oyi5+&xGPTWdp5F~$E_E>_{A@Gk38~qJ~Vil zNZE^Qce<y0@WG$ye(@K7vAXC~3YoR9$fy7rW#wmGBjffD8Ee_szN!=ep8Q+e@oJZh zkVZ~#23IMP_R4_4amse&A^j&lB>V~nVV*j5ihZ=d(|!GGUq?5OcK5KIiNS04-}i>- zyYKzw6WE5MMC-o>=kboH0qt#N-?6V-)4F1PCm*Swm>9s}yxe{J+u!a!^5G8?t^ViH zyGM^6?RM}jB6W+~+y2&X{Z`I2hUikq3GQy7j&)yfgF5{1wC#U})i{~7^BY6hcNr)0 z+yKm~lYUBUFzTu@bu3a5^xUh%Aw<lLwXy5RmP&pF*&hQ2Df^X_-xD+r=i0-0F<VK< z5S=wGg4d3q3<Eau$HD6$FHSQC3`(QvHBxmp*#X<JW-!O|IGQ*sG^WcQ$DG?10L{1+ z4lyO9BLar6u}l(mH^*M555D8w-QWH1{$V%DOv>{Y&eEB?m)&B*?#0W&uugKz_I{3m zOpFbLP-EEW4)MLt09FCFWAdj{$=Pc0H8NJ`xn(;D+Q4$d&FteP?tVd2yp05L4@8ZR zF$QQGi5T6xZ##{vL%B_6dBG)SeiUM7(Ff=lT{d7nHH?fRDjXfKxrZMHDZ(z!%_y-U z)q&8{nL6+jKL?27u=1KjiPFGv*c>s!(XerlV&`T3#{0c^-9E!e)nOuTckJFxqz;Zx z=(NOst`5B9Z3cwkC7*yEG&J`8D4B=wgG288Q)w)p7g6SrmBaiRA!TGQvCniFIfbi+ zzir&J@R1%Iyrd=XEC%529oyI|cd+}~pM0+S{eST<x(&>ZZDoev?I<+#H7v=3(!<&4 zKa_*@mdDCmql38mvpz8fG0ayV@^*FlDL-t6Lsy4Ii!Rq`YlN7NTjk8?F=bo0=GU09 zJZa~1m$OQD4Jem!>u5g3$J|ac837q^st>c&54!iX)Yx(`r-Mg@M=@E2>E1+B81`(8 z(cOu0wV%Dljj*0)0Hc#2Wg!>VTZgT3EFHyZ9c^Y2<5`~g1$+6PnLudep~HEcJ%t_k zT)*bz3_QlDK6&Y4ck0@eZk7&rU}S=NLs!~E=od<ZTd_QKw%*dO(b;zF(Hzd^6Ccky zY)t1naW=0`Vc$2$a5As@)8Lv`7@qyDKHBqk7PdIK9gcKyPh@Fp8xlYBd%bc1&cTw; zd}n^iBu|o#>#@Pv?v7gybo<tC>E<r8Ee}i@fZj%hDv#UWg~R#Hd^FI3J_C$F4EM{I zrqLVMyNg%Y5(atRvwtUhI#LdDZM5H_D-#$V;<lz-<c)SXtYetHm=}?c=Z|0PE}Wmi z;e4dqw2f_nMrkv_ReD!@MQb24pbI_@a29cHx`+IU<7Y@ektmRHCdNiEx(6vQIs|<f zgC5?>N}KBt`G?Ro^XQ``^u(>V9_V)N+{%({3}e!(gEEnaUet-wBH)@)A`T@70He*5 z9K5V6c(D)t5~~&#h}vIvOAR8P%VkqMRp1AavC<jhL>?I+pTQBvr+q8)83^${LWm%? zfm=Dg8MOGW9m!f{*w!+r;mqT-z32>J`z}u#F>+teB`y*kR5b2+mGp`DhhD-eDyrW^ z)hF<VJPz#K3TlDP)4e7+X(&V>{xoXI6#W-xEHWt$D+gE!4rnREci>~2@Gz$ln8B}i zI9Iwb0}_!InI6>Pj2?2u1Dzx?%fuCJ&h02h6RpJ_hw4rEoEnim+h{Pz*CD;0Nm3`8 z^PxVBxlDS=*C1y-tbvF4h;2V;YtCHIRW_8N)rWa9U@|A~vfTwRZO752$f5ml`WBv- zgBRH7+rR^+Wmg?s(q8hQvrH^Pw;-fU*uJ3$osMN$hP?9Ht&QCBL1M>Il0FwM%6s^u zoak^?FZk2$Fs*q<;=H#H>FdTbaZ}c8FVa(;?1x~rL+o38?;)HxPeqk{(LKnCxMqOQ zd!Gq8&SB0;j}EaO8tp|32HO0~gacJ=woN8m#2Y(AN0H8Zb+Aqx_hZiia3fAf=vSQJ zj6**%2ELI=5&%<M%Df)oJ9x!jvE4!=Y3qc6brdJ>QFcXd^80a8oz6A!i$j3E(r9ZZ zLZ?{;X5S>-M4^D+5bZ==?O^Ag{kPHo9meJqKigRGGg1fLsB!-ba=?*-l<CvF_iS6L z7f|;``u@Ez@}7IQzL}pJ>@Lk<-!d^bwP2rHd`oiZVjq|ZSU`rGys%9{I=R<fJb$M9 z=2ySgUA}O>d*ZQgcjwMLPn~CpmUg=@%15RwPyH?ZBIA^sXFgZA0oi)^-W5&3k0;*x zJn!<}KhyxZN)?sYdSb<`T5uK9I8!p^U>&$0B2a^+>RY$$>~3RFc-P&pVL9?`IH7k2 zf`8_&S0sMHwA?B^^-e0TfMp+(J^s-fSu!pj{KBsu*@Cfx`AQkE2YlLd+h|>f$CPKj zx=wZae5T=DfVQ)*xRwz8xnQX!&8u#(EVL)idtv%>g^_szihfI4dibvBt_+h8*()BQ z3y@Fiwn#glomY3dodp2~iE`G-MLQd0Y-AtJcU0^b8!R&3xUN#GJP=q(lPC4ZXTd0h z@CutMdo_=<DsU6m^r-Lva$~bayjFbv+M((&ajo&&jkD3LbmnPm_OJG%(OsNPn|@wB z#J%lNCxdNxhOGhTk!M%8Iv#2~_N<N)-&USFv*g?Q^A22UTu{2hXG*$N)8^7X)aKaC zSZkBxChj+|6`ZT{wC^`=#4aIFLECJMZN5yezH!@$Y{dvIZ1+72LqP9KCgh<`_|i8z z(H-N8qx;EUx-=O*_x#z51U+e^S34ve0hsdCab^V!IR+V`FLi9EF5bMEZzNET_0|#U z_|EItCeYYx_1O&L&jj|w35|p)s`5-8ajk^9s&*?8+dFsYZ1%&wwuw}Q3MeBvC67;Y z-#-^ddzOpH)T%T^cJjz0cmiLwSr?|x@x2YBov&cO8ib<Enx@(Se<K^_3qMnyh1L5? zOGSLr@|eFL1Df9oHa?_3g(eNIvL-CkWTKe7>cEkSEsP5Z5MzSnEFaaIyv_syNq6r* zNPlAxj+1EGsf-Wl%Uy{x!zx7a9M%T4JwpS7Ccgd6FVK&Sc6)abz{Hj*j>nCZUzuE0 zPI^Kck$LMuwzXKpQCS*;UOI#N#C}wH(J!EkeC~6f>%RZw6ZC`EaCVKw*WeZq4?Xmb z*kxb@Ky%8-(qb#;6vcD@`&#<FN=NEcpkF13fB`+&vZlj&EB7}$>?+j72C+Fw;H2sK z^H;iW{Kcc)Xa4Aq+4|wxIGpdl|AFo;Kl_&M7WV&j9BqH2gr&tfk!xRUL*%+SoVDeP z);GiAmAt=sorKop@RdNmSz1eOecR2_mTl<-h}+W^K9LF9v+YLwW*IM@Wgl|4G5P9O z9${OP@6sPEWV?&M_V#yl_uc#Y=vycH)CsoJ&3v>`K`6aacK9TIj^oEqbjOZ8lWo?H zA3xrG3&-;lPdt%`={xSYT?ArNzlZHK-t?w7<=boO3BN%zIe86fVf7%vG3jIAqq^4Z z9<{j*fW&OWMssYY9@9sFPN$R5VXaN>wa=VnoS|Oo4+9y0Dh_a6W3&2^R7YB^{iw79 z|KZc0UjEES{^xYSGSLowlD$OjkZTz}O%n#&!5cB`0K-93I&2!eg*tdwk!Gfu&Lm9> zK~XrpcHm-XrBUM`E&D1Wgu<}%^L~hrZMe7cGtZss&Rv=Ae)e7O?SAF&|ATJh{zKhK zzEZ2RZoN~QkoYS1I;+%TZW&O<2YBI#^tr~6f|R|!sFTM`p1TxBXLLoVCgNCw3gc1b z<$1$q_P@ih5%+8C!>llBTr_8+7N8s0@4dwjb1^W%V7bgbd>3#mx^J@`pNoCm&SNXi z!p#^FDo~9LI~vOuM}=K}X_z#J9j(jug%YKa@ZOHp#^RCAT=C+6MHd!LrGJ!w29ym7 z15_Tmf2*{G<QS!t&)Gq`9hm%^#|t`V6kgIGxF~K1t>Pt*<eSY@e1aE$+W=U+eJs6# zuQ-ErMWK-=ojskUgDDK(7!o3a(&Aw{i5d{p`vsRDlHb|<{VZvF>YI;tAN^ndX*Wjl z^;F-qDgn#aK#_(X;w)XQuXOTVX6C?7x|GvYXFE}TW~j=fj%64-=<v(AlfhlXRys>h zW#2U7u0d<muQCw%fiI?!cIB*J;6so#Ns$?M-cMnaKT9<JlV^@oE_@`KY?;A`Z6tYt z+vpiw{JJ0Z-Vg)0d6qAZQ}(^L9%3J7_8r6NKEs~4E+4W^%0LDJ$hmd5t})t)WLjjV zUp1us$3fO#OCO)<NcW>1Gc0R1DqsM-o;!D@J5R*JJopW|=P&TYDQ9R5=lCfj^%MUn zYtErFb@7?)s`1A6(#tmPq3$rP&uw3((+KmKb?|8LJ$n?5i{Fi3KKH%vJh$hbE#GpS zER#O+({x^YZtwz|KXKWB4^^X0RXM^)-H@0KY&&se*Dc*G6PwxYZVGxJ3&@4?pg!CB z&WE}UZ@d>gz?I1`9nM#AG+*I&@yZ+yWA@KviwgI;Oaw3vj3xA(%ema)Vp)DIJ6WRP z1T9#;dg|mwCb6z}dk!4rLp2Px#-JJSH95tL8Yh3+kGz4GcH-Bk=lJNt8QQ@}w`JRo ztY~m@Y=k`}W57}WHrb)`aF9GB@`4DV5#EjP%qSxFx*Jr_3L73dQ8$b3bvqf`kT?wC zNQ;h;rsR`=Ml6eD+G-rm4BS|@xiHl`oQZgLiypX^cEg|O0VONW7^MtChWFqGvRpe* zRo;<lu7OS-bs2+Ye#(%1D+v_~Q4#))pFGnE=iy1dNrw!O$)OX8YIv2h^BkREStR9| z7%OWfBf_qOXQUG?2lt7vLf_S(lJ=>?8PtQmg#bWEJPC~~QGF}XEdRzKChZV8u1%Lj z@=yqsuPy%<a^8!NY0;HK&Ed@UJ_9<OG0Kf*UfDJy19tS7I+cGY!ss49A~?nho(bBh zI#6d~MKFq!xQmZ`7YCkzPw5M=U=XN$*k|fUu6~3J)Lp(7t*wji>b;YR(c{Rm`anZa zoob#|EeD3e(!pRp%h6e$y{64iLfe0SGQ_O*M}0m~R)49l)$am!n;QGq;6+~LB7H9K zlmUbWvEv6GfvfQ>P8_v2u>)4iPH}mj{(wF{B~Yk3*NMM4iGwG@8)Y`-kqZ38huf4N zxm9R9%ugQA!H4=pe>*XXzVteI0i&}thBWvHLm9L$)ZrXw5ipGyG~mM{62|oi`oVrf zn)WZs=I|c4>h3vKY>9*S*1!5x>4FpjQyi_IbxpK7yK0yobfaJ4Sn$zN9fvb|#0Y2i z<|{r&TopeizuXSR35U7v-UGMgqk-%Ah68M;T=fJ%`5}Fri#A*oU%<_`)<iwOa`ex| zedQ^Iacjz)o%GXTH_e9u{W#z}6FJv;wxm1@i(lwX4js-u^0_5CsJX&~t&aU;Pkpa@ z{5#*l4xH@HoMNA5qU*8(3i^{WjYT{vlCWg1CZl?tBz$oav*2AaSGa;8Zxml7n?I=l zxOkmc{NeE4A9XA`*j}8dw;mc($PP}N5%j{u#KvyNo_*{edZ@cqTjSP)8MqrMG|m7_ zxP`AcSNWl%phACS3RzS~_)$Rz^vamLx9<pE;v~{O<S5?dl0U_>mM$ogzcLmja?6t& z`Fc2k*JPo=zHv_f7{Cn<?{qlFomF));yL{m@Lh2v**vOD(woH-b+_KJm2uM9eiPx$ zzTSivu$=`?$6+0hv;*idI;34ppU#9qq6k_AZTCIjS}9ece<^6?sB6=Tk~IK9&gd&9 z3zo3a=7_3R78gO9rj8CSGJD<nKlPXGM*JN!SXXi954ufTws$tKocsQi``GO8P}|Av zVQjy%M5bwjdatf_%mi@2nNJyMzbe!6WApd*wx5^BwjJeVgobTD;l!xpM_12o!r{E0 ztzdL+*atb*QimGFxK7(d`Z_6!%-JVo#VyYQ7`Vc3hu6K>g}fE14y|;wQa5#^PGa?u z^}L9UH+c;^o9C`nohEq0$>WTZp!0zJDh^5U%~%+GHxR%fu2emA*V!SB=g@QNUxO5! zSaTaaNuMAOKG<z@(r(B{+=1i7)vnzH+yHO$<_VmTWxHAz`%T5eGD2hWdenV??(g%W z|3mVWvvRh~LX@)M9ei7uzMQ~-<ypo+I-ZGi_POQ2#X5^P_x3k|C5#{>pZn*YU+@!# z5X7PKdt={J@>u<K$w=i*zX*&a?BwC~+xSQ;VQBOTCr+Q~uDNm;LhL!fB;*FRgG4`# z!v`J2jtw1m`(aw~s+DxrUl_^%okzdWZ6E;S5E0HhS#?+rXJ}5FYU6??H^Mu7Xsr(C zRl-KeFL&5xq8lPB%iW`oexv*5H^0%HIB`5%cwQhl>7IM;>E8DCw<qAO^quhe#o=6b zPTlwAauV<2%FC6$_IGJBA%>iLwT>VuqBlJnKW>_k1eribUJT$HV<n&avLAcqx$X}? z{Ta3^IYk>^%1WLGAAGQT-Q9QNUvle7sHJl`(oGw%U#1_>;jF}$)#7-xr!iMQ{Lx^w z^UFhgf&KFGN!R>#tuP(W$$o7x^=s^Hl&F1$x>^~QkJGO1$LICL_a5)Q_=PWZ|L))Y zLFb;%Z@|I-)}MP@cjO2W%J_1$^PYR|ImX0S(D66)ropHF+z!cI3MQFUa^?Cr@%{YS zpZ!_v5ce~8cYyka({T68zx>O<JrWyn9sJHm2(f442-oEC7aZ-E>7&u}p6%CdBh^mi zLHWR9Q<C2?zkV5QPj%2*X|-nJ|A-Q*Z-1Oe)Awt_0T~MA|HB`Cdik^e?0?HXDrQu` zG@k8Tj2<q5bFf#@%QD08a}5#&MkZ+l*a7=ahG~e{fr^m%9rQ>V-}}?x5Vl5}9lwYS zjUp9D##6^mbldme+Woh``9E|=-}vV41bdU7ym*<=eWG?T;1pT~P-n0MBH`&+(&=nu zMWUo)An9bP531>S&MY(dY6LVVvbfcO(!#Ogtd7xLo7l?10hD-aEC^eAD40VSMn*vE zG_!tw^vtLo>m(iQ^rrb)#wH>;jpj5`Y>Jso8=rNy!sgX5wDWB=ZuFtY4Lk?LaY{nG zGU({6d1q9@oJ-dG#$m@9y3@JZQAH`}z06_bgQpDSHF9)F8Tma!B>7dMjLc_x@$isl zDjg|fWajF_`Zpmf{3}m15Di;$+PEP_{TOnp!!<YpAN=ybv&IPE9mp9m;ULVxz)=Q0 z=bnD1`{y72NH>4!YPSgotZC(e18<E);jcboM6J+MoTV$Lq@ymw?x$RIwhl%}I}nua z%G0tuA&<QGxoJ(eAkC1^AqG+l&_W|yc~}1BRhul(h#KR=F;Xo9Qw<=>K1I~~_l`Z& z4Ko9WwuThoCC{Y?XOWb58cax5w~iToM{IuZVk716A-ZFmOA0A}mPl12PCS~k)@yO~ z$iUCYI~ZWqm0P3Py;d%bWb_>v0>C!vV1$l@cJ;)`6Wt{AX9Y2yGNNdL8geF&NNx$z zIP~x7*kso7{V7Azq}>;Nbja7<s-|yFVB3z*S381D-;O3@!m_U3o8SBP&a~~?=jK;N zOs8IwwmQtrZ#m+(8aL_n1LB>u!trN&-ZnAR9o)9F+l|9{*~u*UKL8z5SBSLbp@+Kh z`|q|WbdM3vL;_DOpiAfCa9&UJ%l4gHVi*nEFeGNy0it{v$RKfKbae)X@)A0d=%Mpx z+1>(&^|oDmyNQiN(YXCChz{|~Aexm8BJMNWRKEI+!)ca}Z=N|#v<e(v&*020bk^xS zWV;$0f^y(ty~i+mHL2Ed-mzs9#yB6ELa!OAW@N|`&U4#jmeWSZ*Wj`_7s^QmTtQoT zpa(Z`6oWXNr-`<|#$NJ#;5A!nFv$kK4mx#O`2jPtQvv>{BsfD;dFnZExo*yxN=FW8 zX#Vh(bC!Mv2VU_naw;5tUYB!P2{x~wtBjm&ks{$MpC`XEW;$vTG)zF7T6xdIV9s;f zn)onqbiZ5AD-q5#RYVV&6Sy$UC7rCdFhr++uFU1Wp43~O_@8%{&qct*v7OYGt=`r_ zY8v0yuLj0OIJ3nLj-^5NK^$;kW`7drpppMNn~?(ZK!=KMCXx%Id>oy#4*AicYs4Pi z0m<YmXZr?>I{P=V)!D4hR0lfQrc>MY(HsI~3+>`GCB6Dl+aP@@Fsz;q3s;snF`fN> zX|GbpYDyW?Shj6j*!E$Tqh6~B)1r?u5nUj~$j}CqAb=c{UN1gcCv-05H=V*ouS2UZ zjE=_1k^@xicUpg4Usnfr@KHvZOxYjIW8{i^3}19b2Di31a3v{p($OKF%AvHWU+E^E zQI1FIEPMzkeTwd7>p0<Kf^1U}Ij26<Mg88KO~P}PhkDk-38o<myYbJ!cbz9~0<_wt zt9dfH3*Frp)jltWc=9jwN}1Ju<MctMbo{6noE;NqCx*mFz30F$4rl0@Ek1DYTw||Q z@sH#yB;e}@3}V0GoVoYlk?!8Zcd(bLGG&`r+N$kDCeUDgvx0`w3>X}Osy36`(AO*J ztfYHLOYc2&Hc!ot;1C+X*-VfDd+cW~cH~1Fki_AIxpSc$@>qwB`tkgQGu_jV|7AY- z`rSvr)}1|df~vR@$!M7>BUr=p(rw6*FZe}&Q!i!BXQ~Qr{L}xaaV6#6zTAJxo7!6% z^8?QiLSmHAfS?oN{p1YiW$qCW-rL?vcDz?lXdA6tw~@%dJ>8L8Z|e>m+Slzrz;_D{ z?4v(mLV|V{{J>Fso6Tua;e&hzmh$aKjkA<pxuw3U^+LG6h+I(q%2D-cw^rXn*wRX! z6P{UCV|Ehw+|-`yXy=s&DcE;C46a;xQxVRE4=sq~UOU+YiIgwP^4!A)jp7p*IxKZo zN{>YO(zN8oB3qetgM2s;$G-b#W3B-Qn?r|li=YcjfgwPSmFjRCI#SpC%WMAhXQ`DM zz&j^EmasFISWP#_S?v_7nJOqYks;1)l|$(i@TER!BfSoc{xSH)A99?iT=?a<ExMRG zn#Om^xo7ozCa)Y@p;O%3*(mQgn|Yslr7l67IzbYM8JbqjYL!KF1!E(kmmQbohn-eI zNcHWVb!=IoBSMGs1lvnEp|ySk`xxVBR^KF&9{3irTAF-h>4kxJN%Dg8>SryXeVA;q zj@MY4?^tP)Ez~Yvx`r)@Eyo!2B9YIH55x4Oj_K@!jIJ{v$-26%TYamJpJ9A@nGbQh zN^%~#2~O$~EdBA(_3%r3K|7r-CUK;%r_bGgU^{d`m-15%Jz9NA4{+xLMYcbhe(1%j zJ<i!@`ElnNRC4xD>_%)ZKlr@l)*7rv>t@c^c}bnGZKd24kd(t8i_c%48(o@yQh37e z)0-!O0+q7Tn798Wo$r(zXl`C*wE9G0VMDCn*<EBCl*<HCJpJr3^fTiy`u&}I4zO}? zceXUi)+Py7W2{c_lzo+DJ9(u1dOgeJ-*+GVJY(^R?)D?>U%!XFp|y2mr$A@^DO1Xl zBv%gC>Totk;}cn5_DCO2E!CCU1jmjY>%R2mFLvMl)}!6N{reK+ciU~Zu?56~-GPG# zfeSWK5=yw&o}09bDMx==IoH!4`fs|39~#Ok03|d$Xb7)*_ac|}&o?{l=hvY(6rL+M zE49PNaYDLU;p<=f20CqtZ`z#A`S6j$p{rZfC}&DrIhad>>TuQxU3LWhCKHEi#r0-* z`rhi_Q25@w^da9@+b=Jj@|C?&&euYIT3_g3-w`_>+e<scK0=XfHnqMH?E?dno_g}B z?qB}PkKug&etcY;8Gqh)-~IgVL&q)Wqkm670DwS$zx`DFChHkjXtQ5q-(~?GJ$kge zo5_IFY(XaM^XJcZ&(Jmu8q=rfb{d{fo;=xo-~%7%?z;2Nj7v7+h<1xyw@*2F>iOX8 zN&)q8ZC|&{$B|tjjQzsD;7+-@fOI;TU3KE&ScocO4`H|XPepli5lr46=bz|V5&tnA zmcO>6rGpPTod4v1|7SQ#E9zEZF9$InKXV@?3`sjvqgk(BoupHsgXFo)slkUv8r>+u zCjxOIW4L6wt_&o-9dHJR!txpE8eARDI*!o~-FYH~huQ!3y}$Cey7&K`4|S(-h+ZX9 z?8@Xc`hh(MG2+}?OLz*TIHzGyzCt{T0WDk|OwL-X<Sj2z(BS8w)0r6uJ>smR+WnX{ zZroSqiXX+`xy$k^3R7cDrKB;k7(rf#GkOyaXPsF(y~RO#IXGEIBpJ<=a@2#?u??&T z`EcQ6()wJZKQsy5DvkI!K=Ulkl=mnJ&gSu#j+#z;5$Bd4@vw0?I1DX&x{50xFc)0b z$B~Yz2B!}2Ouvzj@l8WljVkG9{!+H)bs(alNcW}{yXsIOtl$AYHx93Dq}I(&RX8fD z8VqI7Ag<u$EZGtUZH!&&q62RpN53D~5bL9d4|Pi@qu>2s{%LpoyN|DIsgXe<={-Ut zaBBm7odJzTzPCOtO&lQ%s+0+jIFh-RzL6P>UPpS$^9Td*S>8<{3rjdafYNP1*$w0L zp5_A^E(Nx%^%%?Ys*H7=2W;!XM`NfWct{B=I?|mc^69Z-Pcukh;EjCRj-;W>wnvZ+ z_dm){!<+P*i0l|ZLFx$Dz`JD}21DTEKGF+xierw7IIN2U9_7oTge%{aXCK7bOb4N{ z%gg+%pXM$@$X>pHMgAG+_&9^)%g7WfMA>VXK}|2e%A3qo&SI2%rX5II+m&bKr^(Rj zd#_Eq7Kd{x^&)@F?@!*!Q_ES+=XULL%lly+&J9j$hr8HXV&4`%!pGOL2hao8kPGP{ z7Y0yRV{ds&H+1)%Fr5hqcr>_#F1XI#*;Dh~1-8`~C3@UW&p~+Yg-rG=IY&s0Bw-MV zH;{VaoWRLzl=S4K+W&dormYy&IR98ut^?PB8{FWiHU_(62-t4@NY(<*nu`}M;oL#= za5Qe9jgPU65LYy`DMMF>@dgGq+vvpoAm9ezZv{WE$A~yG9Rg0<bfri|HLIH)JlKXE z_$kLOSF-&m7q$nlAWM4!z6>Oo5L=4F`3j+u?%~Wn*3ihoe4G~WRC%Q0`RQ0rM{gVV z$A24BMW9(mKQQ5)`4iy`UK#L01C#r=Ihxzx#R#J~cnVyl18!s|IV?)u>NCqQeUE}@ zs6Y7yHfho(Qu{~&_tZ#7bMT^V#_0@ubvUC}00#`IWy|b&7c9is=k>0z;C&L-b7dN) z@Usopp>C0K2o7-7+u$aiJP9XA+Z@iLIGf{e9$_+=h-W`27-ubK(+Jyq*53)K5%=xZ z+3et+0d<RhmA4Mcaz+QOb~tB1t&WOb(DBqeA4#XK3;sR5y|x`|?71hVFq=aoIt?S% z{#IUuy1WlPf@Og+ztK(7#K&1qEj;jVJWv0{`}9}6eu6_u59rj`9<IuVv+5Oo(aqr8 z?i~!PTg7{c38FY*kU68H<KQ)|(D)<HMpVq(j!7?U>F3~5y(C=(rR<jTT3Hhp@IVi& zL=GcA9x2u;k|@!Mz%#;I2eHKADFbZn6X8%^-~$Jo8~iwk;ElGI`fFJSuWekS@-woe zwq&XaN(U8V47mSa?%q7ev+KI=yS?}H>>Fk<z+f3*2Kz<=AV?6TM9HE=sVcIVq7>Ou zIg;bDq@-deRf$uTRGiR^QnHei?LXqkQ9?V>Ld8x+q$qI(DG}TOa07&e*fGHDdr$XF zulanw=e_PGf|+Sppq9Lu*YExAyUV%fo_p@O=bn3R7P<jI<*#y|m8|~46JnE3Doa@b zTc|%gaCysW(Q&pt1DCWBf6&0@!oCaiXHMa6hrD&WF-u-fVCK%E{7C;>Xm?z-r`>(y zt;kf$H-+CSugaw5s~%J(vP)nI=7N9Uq-+0MUHeG-6Yt{Ig&=~kq8sP1Ui~&Nwn;<~ zEk;d|Qi$ld>1F+Eaf2`pV?BJ})pq>&k@m>fzKCV>ciR-Q;3NtrWgC!0eDGu6C#_{W zjtM`g3;z6Kp1L;(Zg~%zFwA&SRQhW9-oz6Q+b_R;QW2ChCN!Q08QQP);ZCFT6n<#~ zTq(`?ojRp=*|(slEIRRRka1{yghSIfzho<xN%y_&?sgT5kSjQYz@0MjNe}S$(;nWQ z&c&}tb!;%M3*>D6gSAtqR33Z?ePE|t8I_>(JLG6py!vNe{lRzQnLnxWFa9^h5tk!z zwW8n6l*<IKxt2m4N4Z_}OWrbP($)CLf|K7U6Uh#^d>2NZX;16oT!#7w51u`P!WG=l zb1?71fG!a1=PVMV7*)AF)LA(TTk-;K>)X}LX3mv9*@YSqy5QNnA*h8!cs*@2KZwgS z$~uSAS&7!1MRDO;+N$x<aS>t!R_VquO<77sGIgL0Jr6_~e1SWPW9YNwt@`GoiES-E zaE1)x002M$Nkl<ZS*o)NJ;z+*lFt5X8hxo+mhieT?&8xLc%BpgF~*c$aWP8xxUw#{ ziicjF$ebhXhB9vL`nGWs3+9YJo7mwsj%+fF%;dabWz%-36J1Mq^u1cvw+mmkg>#XW zSO1gh2LChEYjVnY7Uy!DI@|WYa)@~WyID`Oh)0|e<^}Qt7xv|ujuS4jiVykYH1o`p zoQvYl$Qf{xg;;hLj1A+?W{gDxDxgKY%FlJ{^{=j50CoZPK!srHhxD+rUeb`4^y6^h zb15P3eO(OCCjtN|@j_dMQ&DNfHk1Z5c37CiVBy?R1_R_=WzzgxPPa6^b_Lqrk(bCk zFs7drVB)~A{G*)EGUaA$>iUyozkSIo9Ktk7PS0Mm1$Ts#?Z}C<Se~B_J;bOD3;*?7 zw<8;`jrHR=yLRO}=V%n`Vqc{hGIm-1)Z~fwt*<{Ah4b~-?rK+Du`9ce^$YHTv)IZ) zIs8icio*Gt)mb<TcR!~1e&GwALgvzj_;PXK1arered?3=9sZMc&9&F0uU&T8W$mV$ zZfbYlc_;DZ`L-l?HwJ*k?zhi+6=re#W?klIF<l97PPPG0{=J&Z_E<$c@=P@PmNJlT zH6*1oXILoW9H>3lUe8%Nr`n4z?Qchp9zo%JPg~Etz5F+uSh|yg(k6MA_6&1ODY{q% z6swPt!F?6cseEM4RYYBV6fm_KoRXpPm$InxYw1zI3W&9@O6z9h*rFE!#~fuv^<L}X z+n@Zzr`m7*)^E3ufBX-@;!wNtirqP+Sa&BHfvIE5f*k2}(WLH7UcckA9dRjhHM^|d zdH*}xZMWanzV_9xwm<p87ZOjaW_5BKad*3$oxl5T*w?PR_FC}NIK1$y?e~7~BP=?c zfFIynAKi)Pl5E<%u|4p>{kXo}MO~DeS+wkw-OA#dHm?IF$2|FzbaRF|k48Dl^b)N1 zU+ydOT7mxyxRy#?ZTa1x6_*;H{U3illY;&rv?y|6j!u;9{Y7x|9J;_3X(k~~dYm-I zO0b)t^<2WZ3Mv^KK!gelCs_(1Dt>Kzze~^x8pfA+u_JDeJ^6II=Uwk^f9F5{&)PPK z>Y2lArNMG<<_v=&6BXzv%I-`qBM70a#>%9WBDnQn5D{j(h2g>~llL->!i(j4h@jTS zb|8sRSXJOn5_TSCi(y;0Yz>^krzMLWMJ4pQ%^WD$t!PW6y6SMdxwzYiB1fw-1qlZ` z6@O0RRF10vmxzVWZ{i`!8}L#cTSlW$g~(e{Phhw6_me!+m13lXLhI$EHdZKnGauu` zs&CQqXub?q40cSIb66Sq>uh}nWyKlXfmpvvR|Ee_h4TPH=gNz$se&-rNu3PzT#OG8 zRIHSF8tiyU4Y{jMG6$7z3XTe`xxvSb`Gt9D4Km-Z#==G?C?ENsf1`cjW1oz|c@2!9 zS0Y%ZF!zF;aD+hsg5h4`SRq$yIsIx6W8vo&{DIr`Fu+nwRXucjd`5;yJD=tNwn?nf zJ#b_rhm%|l)7;25w^_EEY5DIYTzV;mE13e1|74)T<^-Bq99Af-*0IR&)br1Cia4$d zQ2w}0RaYx+1zSrS<kW419_c`r1{$uN1LwLx5pzS7HOHjpJYn-l$P?~YrM^x8v<5UU z+b-6Igga0v&}q#df5X6_LceDYfzR#3_CH`81WzZa)6)lEX_E}Pb0|g!XNV6PgDYN~ zkjBc+c1qdRpQ`>HZ|G>KZyVdeciU(+3TMlD?UnLZw6n@|^EJGW-@o_erQNCXzpaI{ z`SpEJdfPF<Hpg`v+m`XQ$R_wn23IQPwAveDupQw<>A{=#0XkNKOy~v|;dS)0X?)Nh zJBH6<lzbB?@7C&1*>(_5G_rkTQGa>150g|6np)ICn)~eO8TbY5gBzGJ=xi+$ks(&! zoe1}eOZ%F4CfmRqHxtmGrv;y5g5=>d8{uDTuvTTMkUGKtD9c?U9-6WPg@Ud#*0LJB z)&UyrfELpL1^g^#P|qx+(I2u~McM>@>mVPMhZ4DHL?N1g)P%pZkBU77ITX$wO0zI^ z8q3AAESxMWoYPM!E`pW3fO0K6laG$~)eOrzLQ4{)c~jTWpmd?o;!V2Zi9%7|ofzd# z{F+#i0bjZKBb1fKH~$e9p4OGo$FtZdbAstgBMm~^a<{Yqaa_fx$V~nmZgPVHm0Cov zJb0K(<rGNLM-24}6avRj`AG$XRmzH+jKm^OiHEXNKD=Fj&X$p4%qKKuJ7M9R^8=U| zLra5L1K5{yprB9ki6VnER%g&H&Ww+1qHso09fh-&xhigfXz3;{Wthl1t8jL^aE-I@ zKfVp4kge@^1%GNt{O}*jj!O#Y$UL+72tQNNEMJm;d6`ejN$Y?ea1$Xo{Bn5<vzFPJ z%&TOx4DyUZ+j6L5@`O&Lqq@MSc;*r=%aiWBrAO=9hl$us{H!beUmmaWG&}-0RHz1d zWMqzWE(A;G#CQBDnWtou$V%cII_oFy1xB@{eIn(C*3DMvtT*LC<EcA!RoN~HI7!lP zo|7$o?nem@PZy6-I#XxIzwjJzp|ZIY&Q`qW%q^xWJcL~tObaoULA}B`mdVt2CA{L! zJfqM`%2KqbJn{~m0J`AY&Ke%*U)uwnl!vsMRu(#a@^l@JOe;t~?mC*yxdOmXTfKG9 z-uAYe?<j>c^`(UXyKgsfBMtHhj+VbAFu3y@7io+ptu6)gqGhvO>-5ZcJHjEYE*QCe zTcvFh(C@1aNbP?UcYOEw@q_Kj$G+W8v4iQUC%)Z|9XT8s@jQps#A?qr1V_PD%9bC& z7$~DY0gQN*CJDD%@}uNWg!~R4CCtJzSv9_|{7&7wZ%7LHt(+(9UH`8qaqYME_l{@S z?-M`ayr(a_7-FB*LI{@zOdj{`-G?vJ-EHr6*WyocJ2I8KahCg&@>Ai2U|{l}H195% zC>A;FF-Ql@vZf65)PZ=u@)l8vchOoQ^<4gC8GO%2OW-1MVZt9umz8hvRlj%f{LIy5 zop%+@iC-C#m0y)rNXE_~)P=lD6~!;iQ$NpxEFRdF)kmvODc4K0G&B7V9?YR;4BGHr z6sgE%j;F(>9bf^<b`}!yu&$OW9xT3BHZRpFFa_MeXIv}3pw%4;=h=Z$IG^to&gRD* zpUu2D7DXv69Z6ftlc6d3s|siOm;9Rfjtk2w68iA$?h7BbUd}O!ANPtu<;uSA$G@}6 zN)S*A=fbV-!<5&xU|xspGl6^|UAS-~4;*#gh`d{}Yscf|>F_ldLpN;R6vct`X4)M3 zO8rabD7=W1;H7)^C|em`F<<|$&F@`*mL9Zw;nGjeS+$zg0$Ho)gNILGa59b6^O<&< z^D^dK?1gZ~=r5T!lbK5F+3-u<kDQBvN?h@Q|G1l?e-2><uW^d<tQNZZfL=49;S-8@ z7AoXZJzS|5e+-g>a;>O%!ueD2`UpI`I7@f|E<h+cF_8b^>ClSfMR=ApF?FmhOdmsD zJJSYc*`3C}eyp_J!_Uk+d4z(~{*F=g4Osc+EnVcD!m{Ypr7QZWZ_*W!Dt_V-?mv0i z=!SOeG-si3V&DvIpbu@W%9#$ewVSpepCB81cqC61NDPIHGa4-+jl*DEC>4eo+`2vT z&?lg&HSOA~cC@SDX=^Y9(K=T7Abbn@3lHFrbBJrNxheTv>W^ub8tWpF<s-_^QMOTM z6=UiwKK<!Ww$FU#(<tS3h8~<(?%ut-{qPU{5cJ+FJ#D<=*<w89Wjv@?VGw6;)|EPu zrzO2<7vN>A=;6Ld#;eDvFn0Wu{D;_CB3T}1H~jO@zlhTQE$z^u!|mZm9?gMtzwitH zeyrPT{Gc;L$qemhoR#kEVcy`{adZ{1UZfhY^J#S$%~)DUc%3}H|3T@y^yl8F$T^l{ zh9Ef?uom`V<wXrOm4($S*~ib|Q(2|+zy81eO%4)txBpppvO)73P%JynXmDUZmDac5 za(1f=+}yi%x%*&eya&inmHnT5^2zq-qqg5;xUD_Gj*(OCvdgx&n{U1uCAB-Uu5Sll zJ=DJb^{*pWdR_@G<jC8dCOg>4@SgYl02b8OMPI4z(te`ePZ)M^prqw*+O#=+{uqlC zIoC~NDoEhX>{H*bR_l4~_bdNP<!kw?zbbAN&Y$}AU(1A1VwXuP5IBLf(fuu>RIw$K zbQMv>v6Cq;ClL~4ZNFs@?gpFQ<%CwiejjG?p&$l@LU>p}ledDW1H06G;NXcijo|ik zzw*oN-S7X&_R^VCZ8l0Kwsx|@JjJ#Nl{%X7k0H<~kZ7%Yb_&Z9%E)91OIG0$etSl( zz`OOaTqrof>bLXjZ#jxL;P5a+6Sy6AnpGGFwyoQ?rrugZYuT#rvh`Ru@7T3Ff|2!9 zv8CcqXX8$CRb=X0M(Z#;rr*Swmeab_5akYNqfGvDLOkzY5s^tC{xiYtI=LNH1*dJX zOkCyyqXl`!wXWWM8yPR@SfRGS62D>1@=}>7-(yk5Wce%%L1Cd+SSDWwVc_6@7>n@r zS0==EMcT}A;6Gdik52{LvKF!SHZ{sA#Q6A(rQHQW;YOj~!GeOLTwR0_$?WCxm+#!( zHo(X}`P(09|MzeHtG02B(?{6~BaBXHqi_NrPW+{-)DW13$+`)bbn8UdVMKw-gR}Hq zYMLo5H_y?QE=IUepc@r-ZM9PflhaHr=3!Q*n+G>r@fCLCHP^K*>#&fXK9P2imK1Pg zz6y=rPU5CfR9j!^FV<$#CgmJri^wRJWNY1q2hKyE^rc~OBc3w}wQ*D&z>vX(N*vo3 z+Yqb7kO*$U->9>du1>bMRv@;$^|juyT#3Sg0fP8i{{;_x%Y>HHPNimHxO@dCV_0`h zwr7qUY||(m7g0D3oEL{cV}7((79-Mhh67_1f;3$kUw%=vX*_978n91GL(;8%EZ@4{ z;>$j0-?VMKgxz|ryewbd)6>4`{B7KdU+H`|TpZZ9EZ2T11*)78zUt@lCKV+Go4li_ zR0`tiiZ`FoKcU;02yDgbd>#E&i}x8OVOq6ljXsJHIC1}dZS+<Y&MJgCAPDC{k~nlV z*Nz@JOQyK5Kp@`8iQ`TtAXw7d?kq?k>`U+}02kQ8=nf7ofT!6;sKR*$<%e{$Y0D-A zW6Gt!XZy6YAPxdBg;^g;(wFlj+dj`S8Jgn2r)}GJ<`5dKgY17J(31-1P3#cav3&~@ z9NlebWeQF+xug@=cC^d12YT5@go#;{Jl7M7b*~_9C{5%q;nOy7@^0Ic1K*VXv5-O0 z?16y;Dx6WOdq|;^@9=zbQGAKA8N9$491N--r#qOZFCDModuk2ZO4)2aHJP@*h7NcZ z-E=sjZ`qfO?*)i__ckYB^_llBeiu$96Q87_mxRJu>FpCzj8GYFeo;85X2f?AXI0pu zzpQYkZzTnhdFCd=QqGx=|MQ1$Tm%II+N|EfEh&yr=u?TvB`NdQidq=WRk$k-JQvz` z>#qx-qvPxO?Y8eqn>glee%w(8sBmV2?;?fw7>lZo=?ZW5btn8C<bl<9+tCTObYfo? zpTb>=TR1=IT<DOOrC;&87BnfF{HmW-o6DP{-~geeuyx!Z9#?QfdpQQ!Z+ll5wypSg zSW6w~m%{AU%3f*e#4}?~RW<po<Rc2o8PA}RlnXw3g|qahqRzV7zvLtHC{Kg`z#^}w zP90u7i{Sj6JH<*kS0-@GQppk?=m#^a*6m;^nh}>hT!ojaxBWxBSdP3yKIkEPHlK=R zEl;%`j`b@1Mi^}i`KI--Pp9oz2;&qyo15arC@M1ASs`1#s5SHq<ATNnftBd8sOnE- zLmZV9eMhiAm=DbejnF2JY4Ap2wB2p*7$rc5=V=4|H~Wl*GeZ9<cC*c+C2-QO!g*HN zk_GU%RpIwLZn~}Ad-Lr}3TOMNSHSQ7mbI^;!sU}IaM{@Y;E(AFSbp1gxqxkUp0NRZ z9i19)hbOfHrQJI^HJ$TO+rgybOq|T=XP@?X;yaJFhd%dU=d1bU(7y$1;qC%TU?sg) zrGg_4As}DE=0GJ^wSlgML~HsE_$);}xbMFkHTAInc{64Rm-XZ6LW49Kr35sYxS>ho z5GlaRFY2c96+hv8H;uPr5n(Ex-BP@1<94=|U)}Dw?bdc1yLdKn9)U7<<WXoW3TJZi zAmV`HU(!nl9>}$Jt&>sm1EL%ZO+CH*I|x1umwu=acYdYD2KSetrI0mh#c|Tm(}KC! zJN*(DQ%P85iYc=uB{1e?DQ=&Y#S4I_h%%aS)~gnH-36!87#h``8I9)MyVP*<JV$@A zPt3}L7oFR%s27DZ+lI-!4lh#)rga!4k=}7qauBZN3mOnw{;v!*Aay0N3n7af3a!F< z77OPYES>G2y*mhbhp;#nIsVGiq$L%{)pwEIIt6o-&B(DToE<~u-?3<Rt^w~*ArQIF zaQH|q7|83pd?jGVUcXU}3tRFTsc#Lg5jP;OZ$ojs8FyW4;W6@UX-l5qdw7Gqu&*t1 z!!e9}+!3~O=Qa#6<Ux)duf;}TEZwO?9<>cV^X$Sd^|0ig28?UlcnQDXy!w*G?|E=~ zoL#ma%zX6d$#(G2v381GZ2Ed0iNe|4jnENy7GK2)no)V4>A@Nq*L*of16agsZF$-D zt<+Z|CHcDYX_dWHr!K%p!s_!<q^0ox&&MwQ%5d}GE?&cv7yGaasl5Tv-1Mn7kHR_r zoX;I6KJ81ph6Zi(u0YdSg5h=7x8&J{)glMqjcHk?^~$(pzJ!4%^EWT$s`_mj=3wj; zIE{t*nQ2VX*!4WVW*zd(D7$j;`^tityZGXIg|Xh9TXXn(uH85og3yTPu-JA?b*J4| zKJ)v~;TStMw&DX8AJE7)?rfG5`p+>)n)FhBxbE83DV&WjU0?cguFP^4JVRMjg}1Vw z*3F;!%%?JMiIR=Hc5r6T```b5SaL^=Aymr%z9^nol;`V;pO=PXbup?+U3;xA$t7YH zo{KYIBC4NPQK#^3Xh<EBGNt~TUCh?#=Je?^C>r;*&wlp7_T?{sg&hRz+RyyV&qP^S z*38nFbmzPP8u6V0-%ty8Zv5t6REVrsgV7p;SAl>x7r^h$jpCK#?2pQx(rgS!=p)ib z_y%FNf#b4W+j)-)=&yb4;r8*5eH_EVYqKD9{1|5vVa@-}2i{5l#Wg7NO2-TJUn-iF zXPqCo5afFmKpAAJ^7!SKUTWXrT#Of<f1y3`<P&kdp-#=iLa(~wnznWGwpu`<KbQ9c zT_3SPg)U>qj>}>dt&A&8schDD$5H&HZ^0nzZTG&79R)YzYkGU!Yq;ZY0NHxp@qSgU z^}T5O^ZvEOQ~$gR?#f$z`90+`Mt<U>A6@)I4h@vy#<CeAbD}qa0N|v>TOm?`xF#_W z8sGaBXNk>AVo{l999P11$6@E0LRl+dgL8CZ1c_+`atG!OSe+u0Ca!*wAOF**+I>It z-uC`q{=04M)w|o1FYRYL`lb-$8T>GL2*WJfB_wzWC<kIez;jp>#Xs^C%8l6~UWFAW z%27%~Kv9$fQ>;D7pjYw<hs?_O*2%mTq~!5qSpUhAR8BfcvRA3--m+;2`D$^Cn*}CF z<>!z=5o<EteRvqgxW2}~nFF9@Pm@PFnu0p{j1EtfZ)X(nP73YN4%Q`<(Sh0SrVyY~ z(L9_)+WGx1o}JkBjLCNM-F(wt=0%<gp#Jvi6@K~A{c+w*l(cIJ6)V3|UGikA`aOY( zw<2V8uqIc%pdcJ8uM7lX;1UV-^N!%6YY!(UC=r3xi5irKB{1$x*haTw?Z)=<qmQ+J z@?U?jO$?lCTi70<K%(+gg|C8dCTP@s7{=oy2_&Xnm8fKvPHt7wYO#J63k8L~Dc+|L zM9#Ri1E%Le4l>O}+(^vRp0oHMT;zth+Z=+;Iu<}~gsEMFf^KmBOh^BPSL<p!sN}Sr z(l<b;Vd5!D2x=|v-EubsTsh!PIDxBgGx?fr=cMR769o@IkU7e{Ww=qWkZ0e{mJ^E< z@{<<)Epr?}sUh7e;P#iTAud!v*tfM}oCn8?C@Ch`);G)o&0#Ffp5<`Ev+6@tIHLpz zErFQ1t{(OiG6uiW74UYG1_vH#*Sc8Go(An_UednbyrsuJ-a2?gPoKiy$4MgoSRd<Q z9P{+{TKQXi^xq5*p6O5NGth{xN}MS9O@ykj@m+c|f75$=)xfDpR}*F-u&p*?p|cM9 z8e_5-1v%{|KG&egn;?AW5522xxa($e5I!fX#oNxaSaI~Q3tGk>Z`(NxW(^8n<2bk~ z(nQFofua;Zu=jA2A)Zr{SlOdEK7*CC)-#u}QaemP6VxFlv`$z`=}DR31=OY^E6h%D z;LT|dzF~5-W9OA9x;H{2@*8*(G_)S;RqM0~0ZgS8L3u{uOnUo+eqSfaBi1M6oh{Pv zTNTck{HMd%m%*EV#Fexyu7N)a6DPcL?68=D_fNA>$a4suwybb2zEsI2C>c>PBzJeH z?8&6Y@cxDyMWJmQaz{aDd3=`__%AIRQZ1P5hsH}E5naY1F5q@gLb|m5(;5}qvyDhY zTsxLeZ%QKo$f<nq&caDP|LgW0QqZ-=0*eMJg_Az1l9?GMvutS>i4+tX_p@1d`S;Jl zw%HIu-^<DzK!S4FUdl)u=#vP*&!k=@Cp78}cOWfeIQa^_&l1v65Hg0w^#fy@0@oTW zfpn>{h6%B5qwH7mYI#;+S?K*&d5Pbp0~`gYssNqS=eSF806a@$EbtK?cmY>MQQ8xv zInMdc=jxx<g?CFdEDL?qO`hlnq3A7VReU=xyTG#!%O@9`lw(w&6irsX=B5z6Gzso- zFOTbC&NwHZ0G4Wh+tRyeuiC|N7dSfH*e+Tk&)_OYz9QaKBB=QGF8Lyr5&QhBahoE5 zr}8ZtG)uk*N0wi=3qR(Wu^+V9isDc=S<{Sf(uBOhLl^rx+s0KQBRO>F<e+#Sb>W{| z-rZ_wC6(Fi|1lf@erdm4Gxf>=(uj<Xgr$eHt+G~Vq-4VExPqp7ShaH2_r2q>zERx~ zHl?ey6Q{ysGZAN@RV&GP>fv`~u6NvcTf66`+Zm^d{?b3Jc6V8iC3+NC;9A12#KQjq zw*#1fq8JxxM%u}9j1}`k?eJNY?X+#iAe2J=m|(k_Ny;Ik8Fp(t{lvF8DCbD~`a_?K ze@NR#MO}C$0H|#Ckg>F*-_ji{A08Ax{Xjt2GVk}D?*Y+tys~&{fK>|7^KNy5`}7C< zzXU+rs>JI0f;>i=O2tEy<Wd<X?jr4!It4e<UeTFjc`2KV9z!$v=&mcRkao7~uq3+o zo;%uAyLYwimv2qGg{M+i`zr-oJh%b^VDnZUQ5MdERTwVu>`$qe6*gJ5NPZ-s!o`Q6 z`!yGNrvM)MXYDWB-%l$q+tEwv=r4=(GAv~h#jlp(RY_7v{Z2gbuF{yp(-)a{05}po zZCXYe%3%62F5V>{rY%qiFAl(a)@&l3vIKIRGP1s$$;&*dKc|?kT&rey!Q_|hl1p2{ zv$5PWV)1VbOQ79Z4jRT`7gR;Lq!WfHh{?aky5f1INEGMZ@Fw6D?s@uGl+Mc0&~Lfg zfd8T(l?S_X!u-rDW4e5uyp1bS7u^eU0c|_!l4}jTWD7<&ZhhVqS6%GRf;ZTeymLvr z)JJ!FgUZFo&zrVXd@ZBLQNDWFG~aVqQTf)lXMXU<-_l>=uZWj`E>cGpOE_1I=`ZCC zFXO;wLsRKV9n3x?;q$R}Mz%YCrX4<fEc3#nxK4AogjqP$&#Kf1-*xz{_@njZ@AR|G zn;DnZpg`RMey*S|ZKdu#5eJ==qdev1@0C}F?&WIneJKv_!fBGFyMHm0?mc+o9gt{J zd6v(jpLrHb=aARtk=NSfe%vrI7jeFxHkUsYqQbMtu;+6L7ZCExgW`%Ft57JVi)&fX zPw0tn%tOFXfK!f>mWgRsAsjkj#{iQS4mRIF`_=;C5&UY8Md6GL4jxBQIBOY?mV$#G z3*X}3#TDTiV%Oo9{^(z`a5>y|?O50L-f(^71AV~uG+DgA8e3zM>#w_2jIH8=jw{(E z<A&1#k2rJO)L7`zM;~dQ|NMg(q@99SjvzD6vk0-h{ru1WJaOPBX;BLJ|AmFKJ?hQ7 z(tp9FPYrnNTW8LkWzMM~)|$vv|LXtvKigxEJ>Gu!ul+Dq<L|+Z!X^NK!qVZ>WBJuT z$%tR#+%a&eQ}Xs_z3dZS{j+|({$FWvNd|fSDF1e$6yAYx(e!;^5C-S={dl5`M^K@N zoLr>Q%GpenZ$13j12><3`n&Cm4}Cc@`kp=4#mfBI=bml9{42kNPLV}Y#vJo>Tu>?O z?l)z=jp%*O;myE4YuOrkZp4j-{pAG42?q|m+MaysDSV!Phv$>+EV@7>&$fHl)v;n$ zH|GxYxPrvec?x~tp~DCBTbWd^1-f!OjMe*b4m;eiVN?6S2Y$NUfB!q%l~?W#yc5iQ z>}oTdrxe1vD5n16KNkO8O{;#NV5R8QQ5EIWQDv0_pZwUz7C-*0A4+fNS09|zc&J|@ zC^*4{d!?cSs1@}JaoRz+O(XZ!QbsEkh0hQo@f@IrJsb;xM7ITtOaeFHVqgqHwY#4{ zp?m=6-~Z`<^WV1H-}8g*1x)8pp|o+!>JZE%EA9wNvnY7`RYF%^-3~gApHd2lf0(&x ztQ)aZwH{gk>nkaK1^Mn%c+X(bsZvU-W`$xqm5kmx`Q7b+!&q{t+?+x{vrc_|eV^cf z6&adLNyU=e2K1$<Rh52ba_9p~tPXlkoKzUASa2)86F6NwAVp@CRb{1ltC+I``d-^$ zvB+k?bmC~|v%?5mgn54Z-oxa(m%qI&*QcG@+snNBcnRQ-J`0s=R<26--+ZdvU<$r6 zC`{da`n(1g!H;EjWfvqXlPFk%Lb+0MljwM-?P|rW4)D__^@5fwED{WZyDM3>T0DBX z{SW`;KWq!958-2WJndx8z3`GOEl_5MaN;~<$gHW93lh@RG!y9k2M@GoJv@L|=08K( z=z&7pBhZ%vedYr^7bqJ@5W=ufz`yk%ZMEmJE87jbufWpUsxH%huN)D#D#6oE(2h9Q zg-ZWB7VW?@&tzLS9e#H;+y3Ia@w^oT&jGLW>u*=#b>$+YJ<e_0dIt}{!k5sFaAk!Y z8nfOjFRh-n(zl(YYwI|`;IIxl_JEs%F!N`R;JSvUo+JGbG#C1z;l5uA=QT_;EW`RN z*J+u0z%s(;GA$d|tEX*$2WLF{d~64C@MbEUN16PLGf`k#6#h2{judP>aD=H;yWy|@ zc)R@VcLSMJE#|Rgg1$UR;n*SF?O2o1cKH=M;u-_na=urepoS5AoTNAr)nB@YdYy&t zPT}A5*vV;J_pEQb*kU(4Brim;Lg5^r!Qjoyt}pM+wpsY&G!{4~*z$Rt3DM=du4<dN zYz8M-GD3gr=tEmJtZVC8S@s0<_!vd-8X7@yh!CK%$wj?sR)No;aHdL87UbYT`7F0E zLrB0Y{;3DJu+<zJ><_Ux&g6uNDV8O#RXDqMz<R2fBb%hn3t^f0STAQnRxgtm@JD`5 zKNLi263jF2KAm9r6wmc9JdNKyUkiT^Oq68!(k<Lwn$$`ft1%#eQ8B?%kg{`<Y^e+) z0(_}2oFvI+-IA|s1HoPL<IH=SDiemJBI_#0lBMB7AipfY@(qy3`p*WoeGTKzSLocb zm5iAGrfkd5?M4J;^K^0xjcWDbJ<q~f;*v{zO$QW|L5wRZ80Ar8ST}oMph{=`ID1%= z;qm`lV9+c=-Ca>s2@_NS0DYSnAv~WyQQ!hktek<{`bsmYk9Dgz($bC~u`KOud}-bK zEXNTK@=Wuxo=(VAVrM}Z{^r833UU{^^(UwDS)QPxxD+m(4?426oKnUV&I1Q+XL0FI zv_&T2@ItS&jbJ6Z6$Hm=kE(&ZTZOaJ=Q(yOSgyC0zj^QCo0k_OdG6w2wjubV{1gBX z;wW%bfh1srqrW9D@>KS*FW5E;>}OdV?YoX+k#a+1F50*F19ADMETy8@OMa#M1Gi4* zmu*O%S~x3bm|hD#WtKoDZF3uL4q7UjHg0x+!*cv!dX?B|E8B>?rfHk(_98!bgH6F> zCgE`^9(2F5fJKRh1M^eM3g`Q7xV7DV0~XFK-c#kYLG=-fu`HqJFZn}?C%`_{f9r5c z4ayx69Eip`hhf68DXeX<iaYJlXg0yS^^m>@15ffe6?9HwUVQ%P_T4}IW;=QOXnXm& z@5cR_<5BUvNEaw#Yr!OZMqJ4pq$O^7Uie993%W`tp+{+X&L#Z0d(Z`m^6M+#d=oI* zFm;rMpcDQWGq-eAt<weZsH?*X?L-A_yaX42A*{<Y*^38n+GP-*vlA#!w;+%0+qaiP z&8}!S+<09qSI03P5%yljOdlZY^mX8nKBNs5&hBO$2wzt=wdm^O1-HMuT8fjrS|6`2 zynf`bO5l}W`}Y-5^15vCOfG%)M7HLA>ED~Ca_Zye8)Xd-!dDs!XZp6vs{#7AW0BUu zbDhFjzCX|61?pw^FbnzPn<L-4yJ&P!zQavjdW%u>PC3@si|2B=wv}yyqHS;-nN=k= zV>IpT;^i!J2Q8}4LAw+ieqM4EwC7mpSmz>$Px_a9&UbIO9A_6Ca;48GpH%=Te>;BD zKP%iY=MS_OPvLgVH(&nnyXqpn*zfhrypHi>f=R!M)L4)rXSll~a)MPfGI#CL0x!5J z(|yx83-RkY&~1YFwNnBb?$FY+Tv23LhGO5j`!>wD1|r0T;nl}@=`O=;*{=9JCI2A< zx^QX2U;Q)j{mo0l`IGV~<UG7}QcGv#EEmuY96ZUPg5Z@1?oP~(U*f5>mw(zeGxB$G z8evRY&-p()cU{ihbe!`u*2S$EMJ-*$JG#0E{EDl`%Th2eeORjF?=HSizb$?5KJ?*n zz2bLRQOQ=o7@Fps8Whb7lLyeSbFddX)tJ11S1>MelW(<5(ShSa(S(iA6+={Lj=~*h z_(~ZTW)?k-k_U}v*``r0@#*cnM3-_NcDjJVd5(n~T|h2C^CwX>jk4>|9bD4cI7(;d z>h3N$H&giukF;&x?oRmQkADOj9cY(r9cwq<xDR?m4rcdi-_FJF{KY}Kj9>e%zdi4( z`qR<T#p2p`>`(R;`-4h16<|+4{bc*%7awXW<m8*qT`t4I`4@lj7c+j!&qINo!nvri zpcYSFReb-e!v0Ku$$k}8dc#Fnm%{LBlYVdPp0YCbn?*-YvQWotcX{dJlwWa^@Y&Bk z*go~?Pse@N``-7ySlGG{CWZA@&c#JSomAQqq;Yvv&j~E(&wdGNuKszEEG@g2(Jm70 zjenx-9)}l89NAL_3Hr;3sQP;E3e~=4%V-eiSP}d))|b21p?2`V;r8ScPvKJXIJ*h< zv?qA~+Sk9@K7@|ZgI~QO*U;b9y9t&3PnlJt2X!z0R)^!$w$;eXb0I|Ed3Nuf#$&(< zT&Fz!<TLFI2fEsCUVPz&$n{frJUEG~vs0X>@f3>b6DQfJVJS3%`a<c$JU3(E{ENT% zx8pNf_Z;#N7l8&a(3&4)%##-Wl3&GBS3y+Yhk7iPx<uTUC`3Zx8u-M=KDzj+fBb7T zpb+4MMMBUz*a?P{oG9fIUGngPbb09q8Y?ctbi26%s4E{1yiPi_!jy=H88p!5MyaMC zv=%{1LG%QEZVzBJa_c+Z(f-D-{D*B6Gx+^jT{?iwVDU17@TFhD42tH9Vni#v^9Xx} z>2AS;DTH-+VT{SwB#h@Y<*Rh2Na~@`tKXyzOhixM3q~Kky1lRi3a5jCN_FeGhQVy3 zhXPWjE04Nh=ua7Tg6D*G9A&w6o5f$M3L-57CJ>-DVv((n*7$M+R;^04#$Cg}sBmTa z+6J5coDO1VQOTT62p+}hg0KUd6H=7|I%OA+c0jM-m~`U3zw@E{V;e=VOov9eqTD`h zA1|x!wxM}YX0>bo)n_1B832q<Bxq;uOm;k2A}~163;Szw;iq&~(<Ubh`~cV9WgRt? z31|daO$(U7j;$GKS8Und*3T@qfBL~+Z3mwGHo`0?LQ|%$62!aj)<?J%<@J|L4O#D! zLE%@8wpCf`H1LJ}FSl=D!8=1cjG#<G3__l_9keQiZjBF(Ig!pGNhmKod~yPYI)a3| zedFeKH3#Qx9Iv|DPBN^tEo~rf&CB{L0NH+ileUZ}tkRbY4c1xs`}htn!rQlv;VMJ4 z`s&-;eEaz3=^}}FM!}bI#XW5dQ?^ZFG26A8_{jm8{B{9JTAD$qR9WSLV)Hx?;JfH0 zw!EAJ_p@5jMF^x!8t(h0a2}z4E3XI<McN6ro_`q>&O^9!89@MXCx%qa^g-z+iyNcR z#vLE{>+PC%y`A=RE0BYlTT59~LaB26@M-vvE^&t2<yT$KM8j=#T8mIy@>K9NqlNf+ zG*4&|8l1xC)k(I69XxslVVXk{uD*sght8O|MkpelN)ro|7Co^YhQWU<2;rB<kDqQw zj+{i{d`)~*t$}VgFwk#i_r+#hnM8p@b=)>&4-xKJc<DJ7I_6j*b`fogm1YGD7tdVK z^XWp6{MHG-G#kYN^egQ;nbj3XR<AQDrRQlKv%;lD9U7>xQasLvwiW=-lbgKBNWgf? zle(Mmexh#v(tUUh;o+5jCw-J*ypcMSm!7XV3D0)T$~JW%Yl}#1^D>P$RmmUoGnAy< zKy2JZN@x!_vFO``$HH0A$uu`;O_;2X^a?qBqN=l*_2uzWKdX@NgM1DDppjQZBsG0p zK=s{B_s=cb%KDja_ATQuS&PyLh4U~jh5W5zL^l+r<AV3VyW~d-Tf?-mLY{t{Jv?Jf z1pxdad^R|e?f^8^sj=Sl@~~iqZ{f>CFpBMLT5oCHZ`n>w8lTdxS1B|q@3gaN`P8RP z`&cYtNpCuSJ3b4yTbNa5Y9--s70r&(?w&EeaZA?Ga-!f-NhmGnqjiIR6|O@Rfr&8b z3VaD=-PA#TO`bl<mgp)Ri&t46sE~h-ZQzyLr*X|7^qjJ+i~Xi<vgyDOi+m%W;4$e6 zhr+E4<M`pX>Id{uWe^n3lT5<(HL5>n#~J&DFe^7@X9sn&RVdNYD8!PK?fS7?m@K!H z`e{?@mc=dO6Fq$mIZpY--_}c6CrWkO)2ylAsQf}YQeNSo^>#5p<&4(orEtaq1wQ9) z1{KcpDDvi9oY$3)@(^wM);%|2;d}>jm3XudQmFV7bgtm9UJ0Y^mab|We^MR3+0H)U z-&ls~Z}-f(5nO3t96>Ub&f-Dvv*SRh`Qg?|+w$n411On~wMRJ|@a5;9Lf$*o&ciE9 zVPk)S_ev`O7Dd0iJ9vkr9103%+9O;__<5JVFc44@a)S#ZDLqkncWe{@;J4mp!JR9B z$%myKv0L8@U~vSkEk)+VIHoZyJb}FZ?K@A)wGR`JcO%-a$=kjIEQ2U~hOji;wDq#K zokOi|zx5WBHrKT)cI}9waZYR4&`Qy&@|5F)_^t&P6q520tDJb&gt$GN%P$1?fyP<B zs%Ma%An&SBUM}#*x_5cyQK^h<^}TGP;HG|dVO4@WJ8~31JpgxPKo?!iXBx%;SU=?; zTa<9~DC6uG&X;mPEcC^`0jzenrtT_SN3enz!rfL5DuhnMR{|5Y>R>F8sy)Q{A_t>2 z{AqK7dRxS5%;=(q?oC<FSum!6cr81NRpM11mi%cC;L(kcbAYnIS9y$Ff{*cx(ey<P zcN|NVH)G)(WixXM$8y8EywkUM4|IIXE+-&z0W5L>a_45Pnq8!1%<xcR`@U^2u7$gB zE-k{p*l{y}LU9Yb2KDjm84@mD$a^XQyrydtSO++&AHGwo!UI8JLxkCfYga*)1*pW~ zLwDs30HAouJVn5^A~y+_WX_s<=!!1S_bSl%z9kM%?M?g3ar89CPb#@ydG&aEasScq zw-apTpMuxL_dR_1JabjsN51Tm-&(9{FW<$Y%}v*VA9qJOM%#<4Eb|w1>*}4We;TQK zU;0K+L0d0N)h1q_tPe}PF5IxfA1~sI3{x)F%(38i$H}DroH+!QogIrRo}qUl1_=A3 zI1X<mZDg&U2M{BL^F8#~$2HL6j7Q-~qwr({gX9I~VA-)jjRwcqfrkMXBPl$ac^~wC z4tG%UTn}>8J)#TF6P`oDoL)ndp%MHd$1=bAf^=+wL-6NMf9!YZhZwo7U1+!7dLxEm z(Chk*fyefiUqv<`g}%jCuW$zb)n3$FS`r72Z^Ce##mh$?dAR-l@Bcq-JC@DzVvW|` z``-7qZCkg+u+4h*?y^F_;78i&jpUa2+$G@X>G~4U3cyQ8N{rNJRdJ<pD!&?ZNe=!? zn>ZFhGtij4YB{VFlq29KF1e5yR5t&~7aqc*_E5X+*4y!q{TURUU#GwAYX8MQ_y_Tm z9X(QbE_9ry0EL?K+qbUtJXcjU>$R$DwebpqH#y7TzUp_eoD1(kI?*bA;i#mldY4%! zC)jT^D%HaL9CJ?%MBQ=s>Z=FaAAS6f+P$1{bo9uv_SLU{rTwj6_*-q;j%^tmYTPQB zH2jZzY+GeNua){L!}HJafvZnDuPZsvD}pa%45m*-Pf5F~Bb+>YCQ9d=yTy2?l3G2= z(WA%OtFIi0Ollw7vE%Y~`Q?{$nCO)(s9)K}*5P_p3&hnB>*|{{u&?@$XkNv2>GoVj zCVwtbfYbqoD;Caw@SzXphZaIAixoDU*hl~>7F6IRavGmRgef?ytSw)xO4j)ALa8OO zIGCt(lZlVvYQlU55yl2Jp+}g(Z72f)13iMte*DLtL2&z<fB)~beQ&$B&7oX9%UChZ zz%tABauv=hixqIl7{=qFGgC}l&Zb{D8Bu7kJ|k>5b1<95Z9;8r(qhL+HHT=y$k*Wa z>F~kB?JO((BM3(-0?ovZvyScSt~x3ln3;YeRlbWReTywpj)#UhT^Pq5hzAt9iY?K* zy0eazRvnN_1ZNTKgi##0-FO{?i|#gbQ=(En0wc;(JAu})Hb%d)<0Rih4_u8A@8aJM z)x#;wb{sDmafC}N&t>P7|Jgxh(0#m>9XJvBlfx}Ym$J#{wH?gKNDXj(ii%M#9!hCI zE~Ez|q_2E{bH!!22vk_j3-!=4#EC~HyU>cD`#UG9tKeG4D)cpb+Bn;ze(k^dhwVFm z^0_F>)}qYyWMBPZ>bk{&MqzG-w7SmlAUAK@(#vhUBe+F5guk9gUfG|v8;6c;59w2v z30mEl&oDv>!#b`KM%#J>o%JYVx3GAiC9C7o1WND$CK}?=!Ct|@MGxuP_Og27TfwJS zL>nGvO#4OQOkDeo;2BrNg>9TRwEo~qnzIc1p7`|6gaBBb1SoviXS}3M%P--+l-N<M z<!k+s9;8R})UAguIt+0_HGo29n)<(j!ueGeXy%0lrSl*IhUI=g70!s3MXP|>4=4mJ zUBdjALE$`%A4-+LqX@;}hxC3ae2}mqw03X#>7QzQ-hDrycM4}jWLhSc!l#Z-;-?fh z7wo#&bu|j-&20S}q1`dBA3*6LA-H{dk=0bFB1&v|;yL)nX@sX&4zbM+-@8{{bq#a^ zeIhW^<7pceAtI~z7P=DX4<!ea1rISge(W^cJx?%@UKJsB%jPjAglpR-l+Ei@1i=ec zbg1Zd8YFFM*?b;1GxKamQ{jAex(*Lh+3aGT{Ij+)m(VOvDur{`vz>4=;LC4R=Hasi zB1hqjmGgowHJG%#uELpWSQ{rYy}~)}j;LzrAAV62bh$3@%0DQ>Z@xRp_Pg&1>-tR5 z4sra(?RZ8PT@lB3hZEv-;X$cbg_qcmGFd9n`gs<4RGx`T`^ny%GpPiSU#jqNQdAbs zPLM2vN~#DVe*Lq~bw%MI4g{{d@~w{xZ!(>HIJ})_>69#sg)ZPr8NzAq@(pepi*z-C zbGzv<i=j^Rt*f+?g9Z7XZ}L)<1CC27opT^CbTUf2N1;p_@lgs0c_#sYWLm%5FT4r^ zfj-F9s>e{T^l|G%T;s>@tmAp=RwGSCtRRDnS6a`?!$*`7!cTjuTozXABuyxb2#@?Z z?li2w_!IwJq~g2EMcR$@V#0dZxQ?M(_}6$vLHxI^{BLg&exHsN1wR4@-^^#0+dgED z;=u44+p3QUxA}$!dHOrbQt~p_x(rY1`etx&Q+2j|%92<*AU|NXH1X&dsB14L+iv5w z|5`>ZS}wOwCe=x7TCxZKHi7UOY`rq}2p0i?)3zm&@76&XMO^z#Rrwan>#kkRYgFIx zELgZ8VCTqL3GgKsbCo$fFi>B5?xcuS42k9#TixQn0PK+|8SC!8{^nRXPp}o5>H|ZE zBcACC!U<enJwALFr(H1dDow>1Y*X`VqF_Eg#evDl7YwWP1(iNkXO*R?H}!Dm$JDt~ z?HgbFN;~}OEA8=bK8(zH3Oq2$(XyAZSC~{T)dC>Zg$5Tog|jG%cMS0+jWCS~EnAO3 zC@&>#nnUWOP-5Ayt%W-lM8B6L%+JKh_lzHW=-@SJ>TE;uvV@n=m+fp|<!MGv5G^lC zRmX!RLLgcw-8A+eZe$MAsw5m6Uxy#etJ;0{-qr59>(;jW${j2el$@zdWBtTo@JK#U z;sDY(d}Ww$N&<gHf7UB-@?H4zN95NVdF3^Kg0b$m<52%8R=0isP9F7TIYyWDQdah5 zzIK@dVe%^6_qp1yfs-`iM`(v|hvMOZ!vj-on8UbP?nf?QF2Fp)wvEqpB2s(ev&b{D zg}#KM9(fWLMLOm`v^Aqc;`ilupcC$8neuPtu=OOu$YvPDa~67m37Dm+Sti)}ZJ$O9 zmxW&XRE>AgPR2v&(>aObv6jm!5p5%Ox?wyMLlpX2S(H_{ag&BP(sx<yOPf{-eDM@I z_oI52gyiC`L+53><=KYouC>gOH11K!p4xyrud1u>;GVuVhP$J2=2}-mJ7dhvboZ5b z{1MkSO>pn;u1Um`Gt3$L9bwL&dL=U~kNS1xn6_(Mq9>mv3h3aG)))d9zxdKUN6|D} zCy&{1d`LLIou~51Z`&w00fuEa6XhK{In|zf@c>)E*#+_P0W6<6PY3|Dgm%YbcqZ>d zEFkD2@~Uh1;5YPoa3Q~CZf9m(K2mq<kdWm+h6__)g%w?BDXgz{|Ljxuzth*un|urt zw?37(d=IYWZ2*ZtcE65g+;it9*>Qr~qw}1>boK}pX4f0^<RvW%WpHhJ0J6_1Ynf@P z#IxF>^7q|j#<i^4aRTp!uP`v9WM0c6pROw56)2o%7cq{3;N6LPjycIWaO&KA8W~l- zqWn3*87mt(SIK$T*!TwK^)9voKlJP+zC8El(;xjEcnx!<;dAZw+i!}pck_mgd@sJQ z;hXt+d9KL~dsk=SY<<MTYOZh;ao|7jq&1~FjK?2;tbO=jemDoFIhWID>E3(qZP#6Q zU0GqngXP5_hN8Hsl=I5S!Cl$rd8sR7=A|O_-@#ehu>XCL=c@7zc&p2i-j~v(7xV7r zOZit8tmrc;J8Ksg{HWuepZ?5e+9QuX8r;0&9rw52{+-{!()DC}>)rRXU;3rLn|X5j zPuCHYy}OdqCN&rdsG<FRk&1VpR#X2}zi0NB&T`c;EPFNOn_>0E)nrZGgQz|(&<9u6 z0-S~D#T~O=<^UQEWQRXG6P3;C#Eu+3nu7y(qR91NPbasx-+5cxdfB%0Re6B)+spIT zL0;%M>ZKfdsY|0Rr2VwMt!4KWY@zHIC}LP5zv0fI)W~f5_<rS;S8=uSr+I3ip%3Q= z-uXbgg~jxBo6!+@7E|ct;!vy>_ZQFQHDALcUK4hqpHy}=eg8tq|2)GP1*%u+!&#Ra zJwfW;!A|aKP?#DB$Yg|xoWG;&>)xZ(M7YTcKTj2;GE$Y$w!Tc<31DsMXM&0_;^Y-E zHp)H+u7jsfw2AGT+t2>T|54j@^G)pp1Iob2L_2kyEtd#Yq{_;LmLv`a5|!n;ilI+3 zw}a`!*@0#PpL5bl{2d}l&*;<T{1nVa#U@ooI<YQ;OsI!Ye#iO;B6o}bc22(43ghtM zBklQTp2f1|aNB*w75IF*q3yitiZ+Zub)16?Po2SppH4Q8B3%Wboy`G3>t+uOR1tXe z*wH+#_ZpPU*`|zjZG2*ak74RJiK1DC=z)i>!svHWcqHPrD0=#>suD#8>8|6{MA7YZ zkQ!mu%RAeI6IQ?b_B6djsRcI?lb7FKtDNlfF}{}_m(~NnrQpdx0Pdr3h2dL1RY~4< za0k(q^pg0rv%VR#5{6)@;HzTH3CRS?V2C8;xFydm`-4b)XAy8VfQvb{-2Suw?!Rx} z`Qy*G9ox3GZJa2oTM8MR{&`*9R7gIrfDByH6yl4Z2ZtxIPT#O~3j*MY_MI1A#3BKK z2|-0GCKVD|*{WckpdBw$U<QVDFij8kQxUBYqLrF1QO?aEs55C$X>0o|F--F6mCBxi zDg#zI;N)C7Q^D(m+cX$b#d6TJr6{J(^cCNw0U7xkCK*oDjpLRut@V7b)=)^M&cK#_ zM_;rp(w4m2{t9y4_?t2vpv%%kX3hizSVn-wQ=dn%w!q^<dk!c1C;2vqmC1~4%D3c6 zN7BMsS1^nhQ6A{SIhLE?*)~<#A$<t5gM{vMC>Xh@SLy%`crZWf;Zt0w$X|JhFaPzI zZzUKnr+aNaeO{&se!+nYMlRq;htibwl{bke;WJz~qI_8~sL3-jzVOWjjkGaw@u$HA z6L`6uAV_DzrR$bqn&qw!pm2WR9kjOsA^jBP@jz#-clJ0|&d2Z<KDpR-qHx~01<Rjt z23g_`kWnn;U^oNAltW(nSXH_0VSVz3m$94~8eNM!j;mSl0IpH#0Nf&U#*z&@dU-gJ z3f@Kdpoeg2;e7beNe&IXvhCcl9Ug{dGbf>MkpGaxiLV7NQVE7)Xq3e{+RX!y=Gm^~ zO0}o3%d<T2XB34GRp(L|5O>rax{oqJc)(fOHse4|Sf~a5|DXjF&iZg}uTeOc(g9j9 zGp!S$vj{Te6(SCZzz4mQ)hqA{v%jU4&{Iu}s(juP=67hadpDKzsj`nkl6CSBW!(0c zq~k}g{FOH1lNh*2YL!h|Wddi?i+XN9(FLF};Mb2loiD$c7&|$N;v&k6l7=c7wB!pH zrRJINgca8`Q1whj?9$Sg?a!9!EyvSGwB>n61O%Tdsxmo&zb#ofGcFC%AKck70DXJN z&JdG3Cpg}j{1TQ$GL=KQRVZ6#)ldH7SQq6g`0`*>6}*|K8Hup)|E_&vVI-2pt<S!G zz_{f5m~^p}NSHKLRhG8w@Ag9h5KExG^5BOs*q>E8%Ws84!Zf~h@n2z*3{A`>uFK+* zunvQk=eXs#WFH8x1=hIoG9M?xfsx!&h2nei#PA5>szh}WJ#JzsRl&K&=z_;QRjd~8 zArtdSTUH(cj=+qe{;<wM8-_$H1Bb3Fbbn#q;?k#MLFfUz*e=ubU(cFQ;Vf((s$y2Y z2Un&6N7glA)FHr-pD0Q>v}xKZU{H_LMSKy{cBL%G9&eTONk|!)uoKsI7@c4Y(`wPN z3)yN$B{Ji-lM$`!Cv~TRb+ZSPDn#!}f&c(O07*naR41D6EC-6JBp6bW1bm+9@HX6O z+_m=>WFhELxVye*nZlpS1+ZXC2>sQydtO6wRXcFBFdDzj=jk&ia8b(cYx1N$)0S1o z<eNPFGuxi}({HtJeeKKb_|YS=be@%;!51?A0=vA!I`POYT`Hf5Cs|HhY5><FdBIJJ z?BppX2tmoKY;P|qRxanOVb+oVRjs_+$5m>YJQwjwabqp(pSko_%Jr?wpGOqT_6-%u z;S;2{6Od2Qq{SB9rXR`E9IK5(Ur=ebW?~atW%stbZojqNe8cse7Qfjfp>LI$VMb=t z^%48Bveu~dL79UhroSw!f9KiP%UbsD_1Oyd^{9FpZmU%t{naDIx8--gcvWiuuKXtc z>Z@ri*ULP8vuSJ}-A~DRhd56}D`)I38UI~GMd?gqtNbV)tX!-Tjk9M^q`9+X6ov87 z5c7_tcbo!8WL_|KP*H}o7eCEdH>+@7R9>eKqpc2%(wbdv2Ev^|>3r@ieMY_m&82Th zd%)s6C>F{XcEnFJbn0*WRpeOO$i<Qcct*}nAyXIIig()|$!{qyiCAFa_uyj;WvpA9 zwOHS%TLNw^Lf2!dtfIMipD~v&=~v8xl(<6Juz3TA8LvZ0y#cb4&lj#8i}_!5CA#l+ zm0qz6xL6F!C*=`zB@~gyk#D*?tiO_5p*3`wviYdYWEo3W7YEV|Ujz&{;IfEm|KUlv zizL#v@~^crNq+m%<)s4jAnyO<YcIZZpgs4(D_G&4LlKSQSzH6GvcMY7rP+){-SzwS zwLRBgllD&C&1>alzJ#r)Qr;~$Xymc<jktz)pj0m14<FwXZ$%_~px<(XlspM@tm^%A z&tin2FXsh#-ooU;ws`I&h?oC$GEiTD{7!~PCZsM{>^PPIz`;LrDk(_WWKo`y+jnIT z=-lxT-s0k4A()*g<YAvumh-8M<!&P9{o%8eIYQsi7qbfIH4_^-_r#qi;=5dW+NajQ zcRv4zAAw%jb-Hk--EqgQ_!r-RdpY|ke2{<2v&I#d&Kve#e_P;xGyjN*$jQL193plc zN1l8B+4h_N>%U-&{}$>)-(pU913HJhQIxvvUpj{(!3$}E*WwifkV6`wdtMycer&sV ztnMqFwp#E~u?uIHiY2UqDy}bm6+POH%7DtCKArbk2Y)N8M5dx|okNZ|eB?;`-QWG4 zELQK`ySLqP%dPFhAO0|k#BJ?e@BV@I?svZ{JTSB?02x#ZcY%lBh0A<2LV_>(N1C~0 zBqQ{(`sb<=T{6-eYE!DaT*nJ#4SeYb;i5zmM?zn?>YoWC$hoqzox9fDF`yi(oOk%p zk@nC3`Tr8Wck8XUwzuDZU*y6~Thx*1S)h20{jI-helBN%*UEq|aSg!Fy<KonJTcFV z!;EusqR>w2!WTbssjoYW?D^cYFT?`=x#ym5r|_oW0fImN6F<@JzUS_?aq9*ayHq$A zES2*0|GpvozkU|48`{g@ulw<@U|`k9Mu4w;>JR>4@pJ#=e~Pl`EJ`_rLKUN4T01+j z@iLLhF(>p<FcF?cwY9lqo|1`7T&1-W5+`0NI&GNgbBf%!9dK(uqrA%BvnX1pQGDET z-`(v8|J|Qz<CpDd$6z3XY$cnUW`M!c4v8ZJf!mW*N|wS~fmthRt!2(I7-5wMAr0Y% zLFJO)9GK#N6vgss{JBhF!KYGpJ(kXcDAz38`b;n}+OcVCTZ@2r?BJpH&=($T-^K6D z^r_Qq6I;*rryJXyZ@Z^$z4G!lj-}uX0_AC7Q~-41u4@7hUYTIvi(_&e*B^TI5G&qT zF7s~#?m4t<9z%g6Y*xnYL2j$D{7iDen@^S14xX^nr9segBFKSV<6KDLToW?esRV+s z3F2pR*tMB$*xz$n;_$D(Y)jiIN<=#?gWK2$ZUBg&!ls8)#$cFmji4ar5t=aHxV%6K z;3VC6u2@Au48BzmYiXmv>cWA7syH}?h3yFx^arpaI?Qwbq5bVNiueImp1%FnueZ}L zzT9rvcRhzSA|L>hN@7>#l^&%$Pf2&euT(M)t+}nj$<ieFAIGZmG>Z{0?cdMB!?{?s zYjM988dTA|4r}@-n3+VX1dn3Xys1m-3H^#cPdq*kjrH_ic<Khk4sYU792wtRMUFTT zS@tO~5&9Ru3LLt)aNrbYZU=I*ww|rvZU;BLic^J;DpQOj1XK4CsHzO<$=}|#C8bdY zm*sj<rzo7I9m9w>iU4z-_W{a3L*IHH|IMdqCl3sqC459do@a02{91)GRirK@^u&6D z$%*_xoJhaItHRkjcnPCn*3*351p%ckPo#+>?FRUy;FapiD~#XY=HI{jtO2Sf|Ki<p z#Fu#Uw+as@R&Pw<4FBlb6SCp}NhZqx<82*!g|l=r!lXxq^VRRfr3S+uf2g;ZL2--H zc<Ph~2cBb5X|8R*>M|BT*cCAjoK8qNV91Hm04B|Y_>8iTXbm?A?&qO1arNT<<9z49 z!JSv)=Z{5}F#(d|<srS&fj+>%D0R8bSLMw~COStBpX3DKUF~uX9NcrwX80HjfzabH zaaB+|$(lt$J&R(;J}6x*A}E|WehOMVOW!%4lbt=la~uVdR%MxpSQc$NqJR!0X%Ap` zOjxA7Yw}A)v~Wg=G~i@q`b-WD)WR94ffHVmc9l}=j&(EPeZMxCD5+1^YovxMk2;o; zxh6-BGfTh8!%2zlFMchDw|b^b^B~{A4v4%|T&b<XAv3T^KIA1nNz8|$J!AMUjE9Iq zZyxsPv<vNH`C4Cj8?4gV1SOhQzp;!ejR)_3OHlrjVV;I`U!0I}+n+57Eb^Bzl)R~G z$}yD+rPozB+vn&H9wayj9cX!1*3DY469#SD&$GKmD>eBwca*t&v(8TVau8D5*)iG4 z0Lnnp^%J*P7j^WYGQ_r7!mn)+oQhK01$ccDKQ-k~aLZqrLzGj}S>GSUp?K(i$3lfP z@j<N%5cqk&VCw|Ue~C{y)g~x?P?+>eTV(`k*|Jq4YUM`?#$DYRp)8_q3aE}{@&e&3 z3qtz<V<2h8`78^bTIH&Ewq4~z=ILeqq>WfWhE7c(FHuHOhADW&vv^8>B1Vnng)c4c zvNfN413U3l1lwMqlQhyM@|C`kxm7wxhI7HK<H1=}5L)VK8_7H6kHXsnTP{H4OSX(K z7Ei11%Mru#886H`{hoZ4$t)w|01BHS#&~y=x!`vm<%^S$j8pWD(=6C~ioAZDwJxbe zK?Ho@(uI{6vTg6(duw~kz7-1R4nKSj-U7Ulxt8dL_q1r&0Jd8f1?%SVcJ%BBmWQpK zoF)ZyWNdM7JJdyLUZscgEPQ|I^Pg@{eDl$E=F|xk`MOU){)KW?Xv`tMO2;nB24#Ga z|7nV8d-z(oq+N4xob*E}4k9KHI9?+)2gr^VyYLR6t^$P@6GY*>R4YFRV4}<C?3dIj z^hLkz>Tk}*D}}Saq(7eN+oaFCG)*=l0NR!(WMPOtK*!--{=<_oY3sHt+ATNS)NZ@^ z#&+8+*U|UPujUIbGRQYQpg8@H500t2DRaRivk3tsz6JJe<WGaU3j4C+@`Ew_>bvP3 zOAP68<9mNqETb8vQt|{A`&h0N$e*P=e5r56U+Wz<9;KI@7YPRgm~)JwSWC{IZNuEk z+wwViOer;$e>Q?L70&p<k0Ms16vlqsVyV3DOQAsu6rSQrf3=Iuedbj-gZD*w31~OI zv_>)PWWZp7+XWkO9V=!D%kf`WAUtI+cM?Y7j7+8s6ooV6vHiAJIQP4f+zqNynheRu zF;qCs(>m2~2RCSIX=nX3>pEi#O1t&Q*BU0dQ%~L+BB&~*UjEUASm+0f@3qW@wrt(V z9Lxpq&Q%C;>=vLemrs)zChpJk$1rUfRJ2Q5HMUoL=M;U>hRD|iL3*r)FZ$3mmJ3YQ z$Nc!8cjF~4k!dP;n6%$1pUD`KRk~wrsLS8E`Dqcta+1TE&%)<k+JC4$@#HhOL}SkJ z%F!5F#Xy6~Y}~rDZN+WEz8i09S6sELP?f^FjJx~_=H)QoggI9aYyX?4S@b^>r~Ba} z>AK(5S1KEWf&*TJ->dKfZbJvqn7kR8ZNbIBGY665j?n;Tz`wLX8vmPCUM6ogkH8|n z#SHyGIn_R{6*J1^D4cm8z=~faFDakJE=p)6SucB<isrzS5El!o-KBTWwuwASN$WZq zT)S>#JFR<5Xx+Jg=FA{xf^q4gPy8Nzf*q+dC)%BN-imS9hPDk?iS9zExvIRb+Eaz| z^>0AoygYUU&<p%2jMPF7J0>YZf9lFBhj7{SFMi`U5~l2+?q%E7t?fsD^vBqxxHGbY zw41}CkuQT2@NL}S+<uz33l!Z4Q$bs0Ro6;lxk!SHAtLTlmw>Le^pKQ%jJXPOisQ4p zwfgy_?W$}d&($5*bI(5Ce(xi{*AC(~^X+fHuibgqT^XxC`{0A^#+z>9u-khXueOrj z@w&rRKo0f-Ih3{nyuLpD^Wv3TP5Y<%9k0K5Zg1@CYRX>9v4B|m`Fby*Qt5;{(YwDL z2c-ooR3a2RQk4G~dSXF5g8Qen@byCnPqd%=n?IL1#(RI{z3nI8|C7kc=i3GjNS#2x z5xGOYA?=Wtx!TsfJZYYnzKCNM^a*2^-mBVIxn4T)GEc`mEu6P(-rQbzaew>V=RV&) z_u%KCA$K&4w;elowg(<~7YgTlfN=sNM)Zyufs)0A|Ez}gFP!?qU+m<oxK<Zy6&d|G zM1gy!o#ImCQ@{ReQGTibRcT}6d-c}N4ltS66Q*DyK6)R8Woc9XSDaKRsK#=INDANz zQYx9|G4a%ou2!Ps2vhpOn?leT*|w>@{k`vLx7?4VAX}|YqU;!8m49?#oGq3JM_R{_ z&pE7_dqPsFsMU|cg}z#x^y<6$^r7Psz}(ukY10N6_I4&Xr%-0Tn)sWvlBEtubt=w5 zg%c<ouim+<ZALJB^}Eltr@!-9d;Yn{sW_8QlyUkL)c^AO%eJ;bPO!XU&(-aQJMU{7 zHgC;p^(0czag>D$hMQn&>riG3^W?EpZT~C#WBuaEsJhfp!RY0x_av5tc4{53yZzLz ztCjN^CSrC!6-chSma@P6_8MO%d~t;{sSyGq5ZE7ix3ih9SAeE16)F`_S9Gc<9ca5= zfr&JLl8QDUZSn(3pT_g)z^<=P1%Y&S%c7lBn5%d+j(#-7v8PW<KXWK<RsJ78c7#>1 zL##|5ZYQbpVcJJ4qG{;i<k=IVscmNkdY(z?bKm-A+sT%Py?d^MCa_Y4aZpgKkmJLN zRc;4zl~pREr7s65@vNDGG<_Dw@#1YQZcT=u9bF=fK$lvt4j{Bsv(T9IDOOaNhUrp= zzW&xtYi0XJwsKP++pYeWf;D&|$O*si#*Gq$Na9JQx8dSQWrlEzZ!ahE_9^>cU`BDO zP!VMTZJ)kmVO-|nEsQD*O)G=7Zc4+#Y#0#|o-*jO_Ua*MPkJ3<E7~c_|K_vLv`OiT zHUeW!Lt68`u)>)E1{$zz^R-=7&{(Fh2(J?cX~0Y2N}5p-?6saY(1-g<nMT}DXukW$ zu{lErVSQcAqi+kt#En9Txbi7ZElWONy|sdW;|gahFAANsBiM94oL4HGty^#5e8&gg z->!M!J|MPTzz2zk2HZx8&r;k09XWIspHb)AwkuFLZ}E^E@<ri1<N+weRgvqsXj|Eb zJWx-8Uti2G?LS5gd}nUwz(LZDk2ws}f>Bh#`%<O@KW)ckR$)M#df?v)teh{~zN_uR z_xQC}ZDyhfzmz^KqbqX;!M&^rooG@%{opja0o-zQ>dZ9$2ALFks11BCZV2EPrKF?& z_K!4F4d$lR`rZ7TkOUK2l<315#SLbTSZ^~4pxx*h)u!}86+3BZ;8JRd!dW_y6u9MI z#tDBByV3(;J$?7qSfLBbchcW4j+Fv{xFE%U{qLph&7U8pjk^QOq*63}+R^rje^nDm zj9liEziDnT&oiI-<5u_bt4w}qp`&o7dO373*iry0zG4}9H$UDBn;lM5iWyg&0OX|2 zMBLfFpWj;ShZPnK<PuII@5y)4M9BlcV^MS%zA{W7DGO(n&ZTU2j8UMMXU4MGa1@5} zxS=RZTqdv_E$dvM&@v9CCBnWu%zR8A_{0O><O^vx`5U)FpFmdIh;wdo4eq6VzT3ve zl_#b`B9{8v&&5zCx4cD}muKNlg|j=W9H+C}1RiR9cO6ABOde6Tu!vI%XTyo1G66bP z8ODQr852mWt1S75ig@eCr-B_C7q*Nwq_Mv8DR*8);S6593f{b?UQzb&O~tciP-@^( zS#KUaj}LA0-D+oC04GkW9k)v1O#h`^;}J+FR6qxZiO*thXW^{t3dbLnz_x?%TOT6x zzZ6N1Guf>p9*7|2i7OWldOVlH*|G}eisjfsnaD=++$<`PuVtxta(n$E7M%m!V_0X- z<6u=@rgAom&%mO)AQjHK)lfM;i>#FcOsTIsJcPk9Q<oZV<>0^xES%*xsdw-LJOC{U zLYRQ)W#9BQy~s*&$!qMB*5K64x_01{i_^F*qN&Py+j!<D{SwAK#3G=|fajlks{P@= z`AC~$r&RAYF0>5gYK`q7hc?B06k_%~@`gSJ-~+NVJ7Z07p&1mE1G+GRVJysf1Aw^a zUZ5Y5l)NaMr##jR4ibJY?2Hn~Yr<ObTr{+7zg47U06kJZnWpXd76lt=B99~=aRD9i zFE|XI$ioid&F?J21QFtxz9gM;$0{*E%Qx1dIJ}%4G*`Cw{mA_+Y;I}Wu?%uIo49g3 zOEs)u@<i4mf7@|P7asD1z;3%*t3*qG$`1ocmprO!iSD;*WfM_*;spnOAilr+LaBbv zd(c{_OMup}S(r0khtotiVUK&?liI#micfQ<2VvRFf)0&~q=C{ISyhW=`xOzxo1nJ^ z4h~c?KRB|EzK5#`7ove-3`=LN-9yV3ArAUWg&XJA%nz??3*Z-I#f_g)0uJ#&YZT5i z^s8z7w&##H<-d+E$#dly$~}>N{02Xe4>)g|(juF%xUbO~EqqD-RSQ1y2N_B!^C%2L zR+;PkO5V6tB{M#n*THKys_0`pi9v(?(+cLQr+>Z4fyGM}yfOCKjy3!y7qK-|;ah)) zhb3*gO%%<rm?)cJ5x`Dwz?jG}!b`UvblKpvU~{bF0|hRDk(kSWB&p@Q#%F)qzMv<t z*k6>#><SEjv|atyl6KVmiSMJoEz8kH-hLiD>rUf|r=G)z=45;Lk#C_)JON&?>>gX+ zuHJhS3TNc8y?dF5Kp)Ur!D?<^lx1dKB5uXCvQ8`C12l21hu6wvT~JkwZ+)CRtv9!E zdRh!Fz;p50T0F|GNaVzYv&T_5A7-~2^C(@VIYyI#X>x;+1p$j9*+mkR%h3O#ie`C7 z!mGiebhcoi%~(Qz$(4#(gOXzcXICS6Rewp#x}wOUAM~4Dc#J*kaFH>I;@|Ji335O# z=_W9w`O1SIg{O12)9C~4EqC3*j=%M7JIbeF;B#K#80<JJMl{U0{<>9KIFn=<vL3?M zdlr`pkDv_aNE*xO!}|ofh~NJ0-@@PQDfl$}Q5g-Ge)<DH-LAUoYGfDZ1fWoY7ti3` zew#6!__}^u&9xGTmyVwXx@0t)WmWlh?S07%iQrh}TsAT}byY?zKIKl;&KQ99vW*}A z_T%m0uRqeh`}EW8ul>jmx81vUXSeWUk3H6|xbn(&+ikbypxdMui4ax4bIi7`%dj4@ z{-uBR;TL|crv52uxsVHI_6EPKrtCMECDGHU9d-&wj;!J<SgDSg_so++mji9`^dxR; zH_=7|?Wrf9Z~wvH{yT9o`(r=$zV_q)&igRhn?`R|2g(X}4}0cr<Y^z2_w@Ir;8xD7 z1HlWf>c`6VKuJFGt{!H0p08ay(w=_mh4#mP{80PKm%oAn8h4lIAoWVHXV3NReZaYw z-6vz~Fqnnst;WLnQZRnsztb#W?E7BKn^Az$lk^jX^T$5)!E|6JB94MGJtq+=oSiUv z$t-)NsY0dkYH+FwJLys&(A9(?5`gI)08}y!46v#P5u8VY&=OU*1*h?Kyy5Cy?Z<xR z{cR%*VipDEv=$&7Fu0aMdhtAyQ1W#{;xv;01zH8CA}$1Lq#-9gV<=QC=hT5C5qPz1 z-m&vCR$JDz?>_T16P%MMPc|?Ba@ZThbe!M9e+52fuH3q#9esX(`{R#&q8)nig|>cT zu<b&@Ifzg<#l%RZ#56+X(J2m2VDP&B&bPNa-g<Yt=k0G-B55zNvUVIR+7X1X?W~k+ z#LwN(^n82zneS#$SK+KHk#Vd7WTH;8&NAz<4q8NSK=J1U%gX}|9e6y9M9T=3(JC#o z002_$oEK6!%T#TTUU`?cNv;wl)#dIxvlF5DSXxxu8EqvK$Zt{%u_`@{Pgw^*CzIkh z9o<0yysK>Zo;>-k6}igBD0n%5(Q;Mz>#OSM;X`a;IMI%wXg-D2&?$UaPcs=EZ~#@| z0e%NLBuI;i325XTR^~5|ZauiYmcdtr@;Mk=+#E1bQ#qhA%zF&l(N%+!^5BAk_3v!$ zM^FGxASkPFj`D$(@I}f+D;?#t3e*{d?OBAtMU>P-PMj5@sV5ags6?QR-@H1s&;=CB z@apkwofZ70D;b>l>{n-lH-1keWQaf8-tVUMDQ!5>?-zJf-0GfUf(00@4*lk;z7}E9 zN?G4Au_b+#TMG)qNXbr$6oC7MAz{n{5KootYZ>?!6avA=F<}1A^Ut+2<THqi6NSbx zCdKA^A%(M(DlPi0M-)V~xm(-a&LZ6M4i#})>85TdgQQ#GwBGtC%gjl@y36{lWSml^ z^$?E!Hf=vR8Rq40+rg&-n1Y<v;?jT$=O_w<4_;;;vK@@;K&fJ*zno`guE{qi%MMy@ z7aGKmCoNeP&freBD3;882W!06Zi8=K^8@e!(s^jm>>M<VujN6u<hUL2(1BAdtW35o zENX4og4>pL&@1`S`V>exkju~<`KpX?QaVf@hBwSi&a?yjPoi=dYHQ&i6Qmp0r!F*a zTEM4{)WLkXgvlFZvBeDk@%ZH4y_-W2c5ZK%Z(9#9k=`hhSal~Ve^hE|{e+?b1<H9~ zK285RiiNb67Al?BvsmT=9$;rOmWdMS;un;sE<j4*OtUg^U4Xw1QMZLztW7v<W?>dz z`&h{gQ4X?5EZia^+qSm5Ke&Agn{}{O`DT02FY7iQNGDAxF8v0T@LPTsnzbEh<6iMB zPNYS-fN>SpLr*Eetb~E^F1^9htV3glN8|Hdm`oQ1HBT?)$4s(CENubVP`0EEd?=xu zB+CwB;cR5$*<$tV-YtbswoD$ras>kxW1tb1ZeezehDSjQD)BrlPQ{Sequ7dDR1)Fc z-9%c=4Rh{*KJ3HSpna9kaY^Aj{Ug@R@S0Nikw5)Mg|qx7;{|w7xf%s3l^w;JVHl<2 zkggj#N>n*vJK6?zFKNZLb9A#Rh5xR81lq@K7kQQZLmn5tN<CCWYQd)>(>U@zg-8X( zvvC{Y#02=jg9~0R)Qzy%ILy1mTJ>-uS!Yp9vB2z@WIY{UhUgRN=kSbC`2%?JgnD=0 z<TvAqJD7m5XoNaDxf2%=YH1TEFXF=;Hco(`6295jy7q)t#D!x{Eh@?Hd)VNilo^FT zye11=VhK93T{GDScV14wJRH<MFW2&brFj%oHn;fFb(j2AWpnbUeEEzxm+!f-t*Q~~ z<h$sh#rz&}1lG_^wUO!TCR|3x$J9nk62}hv8@Q;g;<S-+0Asf}bzzwqdmCUP?V{Se z)|heAQ|>b?@2o!RSrl|fn(ljMk+W!uC?T~%86mCw=B_<#E57meC55x)${*~9!LOC$ zs_tk7x_9fBZ`B4f^SW^xYKJGs+VLrQhgh%;x`^gSJ4ma1<$%D$C?-y{C%*lS_ML~n z3f-y1fbPL<EZmLdZzm<TFLHsfN!7}!QG!wiuh5F^SNTdu;RSpXf7K~~fwr&?OMHTO z!VhKf#~Ook5howwm;dwKA`P(`dErkQvf3|7RX-X`0`sXtr66!am^6^o(5%E@UkPr3 zNrgNeAPZE!GbJRBc!E~(Ej)pXfVJy3x4Z7R4cYASwr|gsC?nmSCw<UQ(qB?|$t%(> zx31#IDbQF2p-NQ>)OzQyt!H(reXE{C<+ph7B2GSb33-^0H?=SV@BHgNcL9~B2;};n z{7o4A<r9Al5bd-vuNEbbrDFVbr_waC5(+qW^9=D`V_3B#PWs4;g<2HO!=n@Qzgk!x z8)Ok4g>&T%Y)in=KDYy1KryGnd43pq&^8N=28@(14Ek^OpwQ__&k%7jr!4Q~16hED zM}~L6kII@E-U`gp?0M!D@z;z6sNYQESXyaK&n<t0&(Ty_Bp8EV+OM_z+_Gss@8vd8 zKIyn2FO+8Z6F~D`Z}~gI`2iD*I~zA`MA@v*XLxVM6tF-Nv26FDyU6-5N<yXuMRpM_ zntNZ(_O&5a`prMGPe;1S{^7?dt-vTqx&ZRF4DbGLdXfcl*{!_Ie~!6lPhPMD>Sx}i zd>-T7=Ez-{1xNNK8%I2P_QihYpeIkBX<z!%!|mZmA4l0f(Kg`T?55k^(l(;x+`i*7 z;3os}Dzw?Bq;_~xjHvqXWb7X<aqQFj*YD-OeXR`P>R>bfT-|SJr@xI8*=I$Re4`<h zr;O-Wl5rWjS&TpD<85&YE9dj4Xq;MXiv_c^igGy%XDpbwFr_Om-DSXJc@|&k0H<7g z4;Rns%LQofCNAJoNo4~g3YWau%b1Rh&Mo3n6PZ=ljE)x@uvnf(E|Bl&LtBh`P4Mj- zU-}F?YEE*1*>mllyKZiqF-F^owYhSGJWyGo=oVuj<bi!}z`{9&tl|%~?P3)T+ecM6 zPvVO4lb`%VdkUqgvO>R0^Jo9PpKW{h?t}hZI9A>Ur{a$GvA-&xOAC>Km-4<aAj|#o z!f}?qfbYWIQpg2fdb+&8=cVATHSF-0ycj=dbW`*&_hWvql(hYi;QI6tl+Ca1f0YB@ zIEeGc8_*||aiNA?4?OSy;k$w-ajo12HKp_dqi>G_Xqmz;3E)zM9=@f33%>OA?w=Qo z_=Y|Nt8Z?WlrN>O%v8)6(mxACyJY%~L<mB4t>NOTXF5Fo_!I5#|GodD-Gg=c5B}hL z+D#nPImqJO`pqmhGJY({mn5xunZ|ZX1@`x9|0?Cee}zyPRKDp#L>4{?i?Ieg%f93o zrd%zaoIe~qaIn4n@+<AxXP#@1KJpD@y7{=%xaH<s+xy=4;~0eDdJwj?h|$6F!o-DP z_>2A`uKsFV$~qnWeBz_OzxW3q{9pofp`o>q${RbA)`Cu`oJ?$B1<^^B4XK5(;lA7O zOM)uzrj;3bXr9{;bMPGueICocDYjQ@X-Au8%g$+tbKBnQ+fV%5-)Iw8T#au%CQg*$ zq)h@G$2wMFqI?sgz+h!l0*#;qu~CiuR``)gO)}s+X<5hbG0L1l!FK}d)<LW)*5Nk{ zQ7jW050~44wetp)<5R~@w68t%P<!}`Ux`v=I|`P~_+u6q=U4#&F(^^-4GS)gasb^7 z#CXlVeeGtpZrpL-+uI1P9uA-wopP|I?z=eka)XxICr)OY>sFN4r%+rwXy{Pg`sw%2 zj;Hd?3AOdzL_XG2|IcU6XgQ(PYFX2kg}6$YS_x8_VJ8>)QS_1LYcD6DPOfDN5jZ=1 zm68Vm37jljC3FK9`3sBXsAxfSz;bL&CbKeo6{6CGd5U|LW5)MdrUeuq4EVyV^4a&# zJ^0!7zy0QKM)B|AB5ui3h?R+rk1C8Swkc@hLl&B`-UkmHNO|W`4sXL(-0rR0+c?^z z0R|71AOjpYGJvJT8V;je!-P_${(yBtB2+OD2o;tXoW~YXo{@)i%(M>+PEKDo4z#89 z7zdHZ5=%Vk(n4!F1#$;2F9j2~*h~Mh-~~70!T91r+^AHb3Q1#qgi*z__z^e8O}M{# z&xDM8q7Z-v%-c5eGL3_(IP`l@^Jk%F6}q*$T@2qeQT|ir2o~wmnSCG^Fgn<JX|Xp# zeaEP`Lf{;N*efVuo;rG{&CwoCBms;#oe$~0f0HHyTXLyC*4=-?WnEH#@Fm^k8v}rF z`CWLuY**p-_Z;vgUPnu01@3B~34Myl*Ic15;-^etvmN9E{`Ly4!MS+z5{H@ib~J5y z#q{zyMXHopx>BTcPaUYU$}FkH;YtOyJZ|MB$hW=!{q5TO@1-BghrsE)3T5z(A7_2v z9X)&+As1IZo42(I_|F<vSyj54R?FKVCOE_MDvxLr4+TWwtk!UTYL3HAPh&BM;+x6Z z+V%7o4z7fnz?<pmr@rt^Uk&U|#DJ0ZkmmPXb5+}g!g=$0CWdscD2l}^_*h1-=~ei7 zSeFN_vNe?criHYnXyxicor_J`QQ{218yeEDD*xf}E(D@{fftm8lopmK%&;h#(SP&Y z6pK0>u1Pw5BGPN2GeHN>lx;uE#Dk|iZwWr@<ag`CL|DaTKN+&k)3!dzM;!PJZ4l<< zFIzIHXduqFic>VuiBCyu9taq`=K{P;ih`>A>A>pB>5wP;HScN=`WbYivKerJ!&`W0 z4<eRgp#+~Qg~Vn+xq(Fb>I+Z1CgaN6FMbr+yhxFVQ5hejaHh}lk#P7?#st4xX7L9V z(>PFLK@<ync;GzwyRej#-c=aT2jnp-K5cL5JiH6#ZQM4HTZA}qL@B8wnX7EpPjHmZ zQT$Rr+lzK|OLi0ifNa~U81gQ^o7RV0S``-a<rb~BU;pm7;n?OPxNYs&6CTNPsv9Gs zT&AvC|JYys9Ty?IYn5qTXojRc%VZ=9XX^>i7oV18{;~d-fAa3ar+nIcMj0=vf7zBj zjgVnAMVANd4qj^E!g$34WBp;9Sy$>VU#>jTJcL*Mg$eM}o|fy~Qv<mY&-@geQygfs za3}Iw)Vtv5!KBkH7P%O&qTl*dKJqu;<&~x?+>&Q#m{JTR|LRv2D&NdFWt(b^>R8J^ zn@HM@qKdw5S<;0cR5**%Q5OCO(H^@{;qIt8l*#At2k$|s84rl-xdzHPaj6mi&UP61 z9{I(!5amfb_hQ`~g)=_nRWMcm1a`p(Zu$B0)wNAN7ygX|hi#Ly_!)%9zIu`c-we^D zlg6b#F8k&X^>m?ZibDaPc<fs!osYKXpL~La@mI5$V7ui|N&A{@3A`$t^Ui{g{avt1 zG0E5~twRUmJ8;VjQkG%7NR-0Q?a$o&sofBXX(YnyduSlICYY<A427?ljR?uD)KmE; zqQP9|Po??d4c+*Yvhy1n$s&dL;0|8>2HgzMSKJX%3MBdrG^gQ+i%cp~hfp?Mw)4t% z_3mBmroGp;8}{tN@)cQvN-95FP0P+<$kI9RNROi^)`I<fHwL$`%D=j+l*t|JM)4DO z@EIiXvwQYwjL=6lEIC8pdFcbpq$|en6{#K_wwL4knKrZ@;jbi|V@$SK$F#9_0%bFc zB#WNGfhlg+-m?oT-mq{UUJp;gogO=-?6+Dt4-F8nE40Q1;X!sF?gF@-8$$MEv8$KO z!_tM5OL*m>`Y+X`hCan-G{ixX9N)H#`>}3@HeGCwl{0e=`)L*nJ@W=RHCE2XrO);K z*qtd^^aWoo0FBa4Yv|9qpVO*Y89<-S@)B?RkL~GI@Aaeam*tLyou*qh$7k~<d^WE^ z!RA7bG@8Cb+SG|By5)@7OaZBj{Ic%83`h~4TxD8@{LpW*(brzD4YIu~$A09MzlK#{ z^<UmWNy;_cHkVFhw^}$e6hzs~w1cNTr!Jq$bmr>Vc#_>=leEpl4}Yh9^3z|!jUR`} z@3^Mje8*jJt(dtSvX=3c$!Zr4{Q-RH?#jAJEA<S3#7zN-Z%KYL#QJ;nvHBO`_uI<w zsw-gxW=u0(7r{ruVPuX|{&4J-ZZc27kYN5C2a8XsbUw~X0Ou<aX92&<4a2a;!U`+c z^br?(oy&2{PXvPhj)gre^2*{10fe%MP9*zRD&;TZ+wX`NxQJw5CkC{Er9Q5sG;o{Y zY#k2{%#LPu9c%e7uXa(oucHd&CmwyMO`bZ|4!rz$yZbII%{jA2V>7qY+rVW#EF8Lg zd}9h{VO`B-eZ+&e^EH!sw$v1^AHVU<Z?rFb;S153s1wle?5BR}r`oNz+=j~#c8<^% z=}+#S=-S9WC_?<*<LzQ_1j<#x+P75yyl}3e!`0;3wef{>dd-*D6m5UdIKr_*+2J7P z4n6bTXWC0IzQm51F%Gc3E4!s%d1XJewSW)oeH;#Xd*l+0pj1YRf7|ypS*PGoRw3v$ zfL!|LYT7?#t{B@co$Kmitfp*pT7BEw^^M*2*CZ4>)}VWK2=r5UU_MFL$R4DfWQXlz zk3HT#^pAcuZeeVPQTpiB*Im`tvta2Q!^`-}zS6HeM!7YB($6!-C)UOOsN3Ky1?1%z zkT9<Fh8oTnA}7nEc-J7~*wLdbCOMB@%MSY!?Zf~3zYMS2bIo<_tr(EL<t=x@Q;4tO zmmqdy#l;{1(ATA>i>A56$8h%G{Sp!R93BS@e-$nz;82!_2L929{!s=z6~#^{`UdYU zl<n+mRl?DDUZr3vC0Yot6I89bN)L%g1(RG=CSiWAT6^+$6pajIhdGq*EChP*kNs%7 z^F8lw6Kv1Z)kIEON6{zotU(c`V%Gd35Oo$%ZqHY-q(ZP7NTu{STxFbzptKn#eV$2< zE*#u)vxx!5gKRVov*KFH?#3GVJQlW(eDTXsIG@3n@Q(kNyEl*W^E&VQF1En{Gr(Y9 zxq&+&O57K5kx0pwY%8*4Tb3+4i%*U%waq{7$?-q#Y0k0ZHcgwx>8VmTX>F&rBqxoR zBU{!IN~IQB7A1<CL`mELkl2YGm;q)12K{`#&-)Gr6iEyf=0xo~^ZwrLF3)}LbD#U% z=RWtj_)cOXhJlhx%$!M7QG&H3c+uii#mW&n-h;S>7(khN(_MGBJMVi(yX2Z{@e7C# zMT9&z30%w4sSy;&ZjN&jD;@=UeS94z4=sG`)Kp^Y+gV(Cu3Vu{sZy97J$4wS^YOSL z@S9czQQUz~8&H-yx)cdmUrphhisHux-7DszOdt*MIf3<!EZEsy>&&{f6ZczS;)(=? z70YmN?SL^py?L+D<b=Wk>Mz0s^=lq7K+|*ZZBratI?VFBq4xM=kG6mOTfde1*t~H= z7{mlVwa2k=XB%YOElPoL&a#4Cg^()FwDx{!_s%wm5VIbq^vkI?H@(xk(tX;_z+@IP zk+Bp(eW7jx9Psi^KVNQAqw52un*|Iw-GFZ)lC&Mt7}n|zj?03ax;cI_bT2~1wac_E zk7c$j4xk+X)P#%gOQ4Bm7wO7Gr5EX3Jc>iFp5_-N0?bt*!HE>p@w9G=S(Y;2!9d`o z&c(0wU>%#bid|O-_^vGbN+`9R2xAyI1g`aqG$Cw>4-OP?45MNN)i}>s!jkZd2x0r6 z>q(^Ovnt0B^!4qkpckb$abAf5M$q7k@XwSN_$<GIvsRRr&wF7ojJQ<cEDl`enKV+D zMaL3Bl!xMxzn34TVVv1{+7^r>4JKXSQSlNw<Xz#vVDeqh*GyZ!)eU=RWd#i6Z)YWr z7gKjLa9XYiE$4z?_ululi*LJyMkK^4fS9Ob09p#?2^1H)x0rxeu(1hzXvtFQ4mhM= zu*C!y{1HMv%XaAce?H5uS#BOU&B~4=2gk5T;yw6UhGozY)?@aAsub)Dg<oDKK0pD_ zwTyl-_+A1%UU~VJwsHMxe3d)cH2`HXV9ve_Jd=tWul7pkaroFM?LozmU)|s*o1QY@ z)PgFOTtL4Fe5eR=X`ma-IEmo5d4!pd)z>7Gi{n_8%%5fg30|`Z7_zL|5|E6rSe7W9 zLp!ETS$di)(0G=1t!KXT%`?hn>R!dNb?Tq>W?OT>6u+uM&$nzkW0*V|GOrVlyQEcV z$PNAGJ9tYMKFQ=$mj*AA1{Gj9sw+n<n|UFLWGQ>%L)%$0N+7POwY)cHPRm1tz7K;m zQjZXw{~WdrU*<!urEnJaW%=R;whDTtlJw!5rs9Cz_NSjh9C3#R^`SXUovCnMM4zVh zj3ajQx9^DyC%!2NI>{D=ZSY+<2QwYMpj+rnrL0O`CwqL>qO+9KPOeotfl9mpr^*tK zSd`ko*rtS<JZ*CkLV?A~O4|*+Q5V#;eNXXCE%9AxqLPzAu4#8TUBD9A-Zyo*0l>N$ zJ}ym<vGSq#k&}V6IU=cq=?8%-XRB?(7r3`Px}6X{>q(k3qtu(f)=y4;gq>5qJE4<c z+Go#`Tq$OL@+xUF1A3xTWd%3w(zb8Eu!y=!9|1n)Kf3+M_?@u*gb~?r5AL81>0f@A z0XSEmRs3dhk@zKxkuETJ1XpQm9l}TpD5~uc*CH0pR2nKkwDOj>qz^*TB_GdZ0Oc{R zq*=5>eW*~PoomH9grY@jm$4ICGLKh0`XT$(Y&3&XM#X?uCQ~TFl<$-k3&+##?(1(v z;d}#2qJafGq>ZKyEI(Q2NBFsgF8yw`SVPJVwgrtGj*hcZid7_g@ufe_;G`l*^F{ae z0t*oOCdS8*NndOaJ@^Iq_95I09Re;__}NdF#knxbx56*!i_KHz^BMY1^P85J!|$Rj zfnUiV_y7Tedv6Ip^DfV+0PZT7VRSdqznx~{&Mzq{xXWP~5p2xQ)6(ZJ@*q5+LQ(gX zX7^YZ1z_XwAMOhs`6un#=Ifi^!47o9Pui18XD2uyWIpM#%*iMe%e1$}gUgY3*R+c+ z+T7lD$Mx;vjqF5^B1L&lnxW8LyH2v96)pR0YuIjBbEGYjIJg7~8;9@x^_FnGm819h zlJ{K%f|vwZ<q%(?7eeMfsq!g_&0MI9%Ew=i9*n&05|ih7E3T=1mfOlZsB8H4;<K!# zV$X&FuhY1WG6eNLIStPRPi;O5XDpVL@x<}qA_mB8JZNe~5#~faGRZ%+a3rf1rrb0T zTpJ?A>438wfeW0<N8OB5W%DExyAy1TF21v(OXVPKEcY3+6ko_jxG1Jwk&rPSv@B1G z)xOvCLx4;sOQ^p=<l|vvmJ#}Y$10A)9E0?{+WP46T}o4ENErDMKhnlR40<+fT92X{ zD_>l5NwF3}3J+;?WyH%&+-D%}FxGG^Ay48X;mgXHiFev4-9--bNiUcD%(LFl{*By5 zcG8ze{Z@$31~2-0?aSd6R3z_GcvpDyje8B601GgqfR<LwRybf!x%Ya?NjCV}v)lHx z&wTE$nXp;X23O!p<C<$C+siB6<3kvP&b~qXIcAv8M2>x~VKNa(!7N+O0wwv(yb}P9 z9{%(0U;fSPI1Fq1sW{eEeehyG>lnn3_SY4d`hW+@qtBdV^{rOU<Hw*I`b5TE^9Dya zQ98p9&S3l_UkO$^ev*3NK5dIUtk=l-fk8OB{QE+3&7K~n&o}8r8CR%1G}>~%0>|c) ztjJr6&sY`Ct5&b!oic{2h>PY;+i%Z4{%|{S^g!GF{A2Cbo3~=sxT0OMc{B9vN(Ax? zVTrI_;e37ay5J9S?dLCi*k)C#NyDzVVv-8}DsCJD@7cSj{rR8$8H(nk$oWgLkU!e) zf5$u8O*h`sHg4QRc;%FH7S85pIvwW3<OM-6uQ?x7)?7o+DcyiKw-l8nT?snQ9$vkX zf%T|dBv85?-N8!q?_ovjhLP*ntPdW){_xk?WN{^m!<*V2ciaSC&&1uTG(E(oracY4 z5~fnxfHyZ7XX9~B<u^jt_sov_AAL`q&JAKh)&FZ|S+y=t=vrG6_pMm#t{npXR6N3@ zePYZ2|2ll=DEgi!+8=-N-$v;_g7M}g?iAnqGw*35_;Ajcf;uTar@Vwr%qczhN6!=b z=U2L#qjeiO-Pu6klU_)0=AEnakLo`6=&`iFH5e@}U$z2c&|`s5UZS%3p1bdj9J(0h zu81_{SQFlSp(CgeS#RVq=Q=Gun#y`3^Z!qfR#8vMwYb#yi?g5qC;ucJo*U|E$?LLo z2|xvr73v_vt3>5M&rVXI#R^Yv$d_JGU7c20AR6Dy6l@l->}HV8K>__F%Sd+a+SQi9 zOn>GhztUD-v4u&}RrqNx1(wP-PnnF$O@$pdsuBV_#1m{hGYXszLe1Z>!adD^?W)VK zz`}TGd;a_1XS0{1ZOi4CVIjDbjj&KaGaz=RekB9%1#|%4fAY!poo{`s?b^1Tv@!W7 zFA41=3T<73I8ZyKa+_u9Dw{`$Hy=yGgGW#Z)9IlXYL{Mlb-VSgcegj+d<(NUSF|ZR zS}bqHkpt^R&Z05^a@Kp-?mfY+t_{TX2&ZKew=yngH;1uiRB3nsw-bA@@>P-UcfVOD zX=Ex9?AXcb)fCPS?ELN^-gpWyy;4->J4nZ-V$gdBR5o%4xmt_sIz`+&@Kz9g>7|$Q zO*#<QP6XJ2x|H5Ly!V@Fn2&k-?98znmpQxikN(kri;IE15oBcwDxB?rU0$X|oy&e# zqwv=clQWc;gUjPg2>f6F$G>h*eCzRc3E#HhnqVB-$+B(g=`@3N6?Ti6l3E1Q8DP1d zRuEcJE`|1%fH&*)4F2Crumf$xvBQtG1h7g^6HIgjPYQkDs#h3CDGcq}SM=^foapeq z@!Y6NA>8^YJl0H|&nj#kXe$`0yon+oAw%V}b>nGWmV%+$n9rtXyODWH6Q<iUU=?XS zd-GfJAsqz{@keyxmF1O_M5beTgjZKKD%q!D{#M#);Mj$K^W98rj9Z5c%Jrdn793R9 zQo>-LH<4xz^Y%~JRA!rp_k~09qwJPN+BSYaab?*I3vyC6(=iT7(NQQ|lBY26_wvK^ zdVKWvQP`1&iWTd^jY0h;u1(K-(=<=x&Mu2tQrj=f#(|FERlxnA!r3y;J}$Zc9c{x~ zt}g*O19GjqP<X3!4xgK9qbE?VFTy81OaGQGqg_e!8LTn617R&vNudG(rPDN~_P%p9 z_2@BN@0?@<LF#wK>J{N(QR4BLqR3KG9tXY@5fqlfc?kYCLfgLLvP;|gwX2{DzNm1v z10}41#Y2Py(*f5i3Z0}mjpA9JI*yr9=p5P|6mC{IsC1^r6Q72k$qSk-?VJe<c+@2A zLd$B*s(>HfIChM-S{7gnQJh%rSh|6yP!AyKPt&|J=*^XvjxY@2h10fP-yv?{rw*(K z&nTR|PdX}pd<X4y&z3Xal2DQhW%V@XH;+(U@L0G}FIpDTd?d@@tO8d2?zQndFuT0P zk8~zhrLFVNv@2oi(FlE}Or~v_saTa|b*+0VTaw_(ANnxTB#e9{N^aUx(&J<D<eM-6 zkw9+0>1xA)tbE`sv-*RqP+G~Z-Sg!M@<t{CRnAH`u{;(R<R$(xiA7bKu>&ge7vEZo z1m}e9mCUv^+lo9~%YbS4tNn=+f4wpnWJaMF1r+H;L6JDLQ;XHL&kWv3Ti%+wvp#LZ z9X~0VLj_>TBf=1iYiLGPW)mRZ#mYI#^zz~FWO4O3g%4r2Oy(hPh_YGuMFH>Jj0P~z zqqWc+G!nWaGx1>CqmY5$2|jtOyIxyP%i<)U$|iX{$yS-TiNc+Ht*H2lqwU8hHuaT$ zf-=N6HWPshQ2v;<gqZe6zS5Tkkp5h0=H!rgBDoB(GZ7$uLnqar<zolG<@Vrn4td_p zinXqORDj3NG`O(7YzGO);J5F)EI_RE<Y~a@AbJ7jep+q~BKJ(N;%rP`v%qFQ5$iN8 zy5dd)%V&K&Log_4@byj|D|<)}wu!smbW^+Sx*JejJ4su8P0GM`>!#XQ!LO39yW?Wt z;^ZH4;pF^wV03;vIl<)hIIser8Kj>gk^Dgm6Q{?ruf(^Xc({H4+fO3zAxlE*@e|r9 zoJ&bp4OjO=wiEGKJjjZ)ZHlAnbEK2BZ9j2Vv8X%iPX%?#;QLCac#r`N$%T;*oPs;v zaZTId-d64krBarfj^(LnHPKacHIGTmWJ*{#uSo_DQ!^FwvEBJsJV(A_+vL4*tP9%# zR*X(e#mGV4t%WlaJqxJcdB~v)Q8*9byK%+JwJcY^u3dk{CRPu!k|N4Y;D$eW$kS{S zUUe7e3Yl20``vcL`xG}o6M;TUSo4@ZLHK!-e|{{2_nZmVU31U3dS5S7UOps6Uhz3c z|K8`iukgWfmvFKamb5qICi-hvlDPV49+L~Y&r<O`a2A(6Otd2TLKC)B6(sQ3MI%gH z!E@m+OV}V|A$vR|H~6GD%}NE_X-v*vj=~w)5GE=$_vM<Q6LBZh0f_c$JH*0y0(S=! zwkh_qnM5f#L4O=R2~UX9ng0A-`%~du{b?!nC^fjZ?OEnni@~c_;A7ZTh|3u_Ek)^E zGOl$mtxzmZ>q2;h$}(859{GlHY!G9UAy$iCw2768xY=<MN=guXuQMmnCTTd%S9_h( zS2KSmuCm!P;{;fcbnf9LeTDZt^zThOLAr2;&C%uQeelV1&jUMjCYWT_KZ7QCRz2It zP{hzHLpxT%pmZiv^HsEhJ#{b<KD>0g9Xc}Bo_Oj-cuT_&iAleuC|m4f3=F<2BjG0< z`%v1VlebQkW^-S|nl7h_*Twcz?{XDtKXeyBAzgp^<m(}LAwtsNmF0|l!&N*8v*Wzl zMAAMU9tQu5+y%dKLtNd2L9)oqnpOZm@~x{voE({Eash_W(R=|Ub<9vmpEqxUU(yjW z>ly0HUk|jgs}A^v+#v3KE{YL#OzOHa2Kbz48C-0?vjAly`!lg(P`*3CSiLN@sVDIL z%;R5Y0`WlG`P}2}_FJ!KoVg+{=WLfERJs;9=52p{&6RI4!wVkPT~GI~6<AC}CX(Mm zG~V}Cx04vfX+Zb!Kl&p!zS|!+o66qTzljw-x8BySzWN&4gch4l=z|+@XMb#ci8+t{ z`kF8R>zof5>s&+6rThiv+)_;Yp>FM)obc}_>)i8UZ)e&3#1l`nr@r$PJZfna&blUb z(({HJZ)jIsc|~xmA&l}@R$Y;n^3khdDy0p0bAz$RW0ifbapoGXPyNEzIpMxbX0Bn= zZe@})N8a#Mv?eWk7@{{KNngOYWSG@W+n(RmzVzUi(fJ&1PoiIQ#rQq<-5o#9L(4H* zh4!NxlHbAWJZ!VV*VFM_VGT^gJIDV^ajjvUFdfT&VTZDsPJ_;&SU2Ne|B*-ACqMDW z?H4}u;dbBK?{61vUJp#bK^({8^A-w8l`{ao+K=I1?b{Fee(q(b^ybg`qkq8v;8)U2 zd^msMfBdK1xoij@xeU(6RUYthDT+r2WV$+#5jd#GW;29!P?$!X3WteOa0MNeOP(r7 zqY$H^JBS(_z@HhN!%^HB9LImJLi5%;?`-e*(9gHACAutNslAH9Fl3gD0fPfyD?njQ z>$u@gIja(O6eca<suXqrq;=K`l#;8MQQ6H>i=ErHL0||?Y!GmKlo<|6w1xq<jLD_5 z+n;^5effb0+V1V!+hPY)<Yk9DF0-TT3N-HIuA<oit2oJKg(x+}jY8HaE;sh<+s|_O zk@n6Xe|P)o_r1SeapRlYNrZhn4^e#Smdmkv#@Yw`?cP%gWGy>96y!06XF&h}KmbWZ zK~#cc;1R$2OVuaUB9ufE6ZjKkrt=tQUsmzx;5C9D-M)ann!;H^v~dfp^^iepN1J}r zx=V&U%q*ch{W=ruA>I$7Al4dt$Bq};_rLeOSQ@|M9q-7DRTNRu18E2|H^IM_R@O(X z!eJy~A^^C-opup^KlZWzwS5tMQ<ZFHwjN=28N2bWYL{Pr3Dz+ep_ty#F1_rs?0jtp zvJPKoDpCLF_kX|rtB-xGZGYyOc8MFPfitRxvXj4KD~dRuo8AYh@|<jJ1lnCjSa(O) z@16Cjk~tOz3QE+o14{9;fO?J+1ln^@+&6mZTV<`*AzJ^dK(&m%_p~l-AC@)m31=tR z*OQ6>2L_?xE}RW77SF(AJMl1G!-!kI#}7JqRbi}PC7#Vkl|q!=<Rc9@d7`zou$ZR^ zan{a3a48IGvcd086zG$eVG7|%hkSQ3`?rt5$^<x=k2TmJLd~S3xSoR(CIe)FoOKAR zf0nzJhtXL8ujP`?w8S<~>B_d*Zx|@OdnlwQ4bu5x70#w(o>8ihr#L*0Ya8)ry$GAa zseDP?nV;eNLlSzu3TMkQ`?&fi-`y^`^(K+TYlu<7TZKLY&w232aa?1JjcM@&eWDOw zjt?vSDcc5Uow2}Q=#;9@C}q#6a2B)B^r_J)CZ})-#Ekx`b<E7-15vADior>zm^jr* z$D)XMJ&#<;($`DzU*^)m@_Q(JoWQA|%1`Rg#7s}6Zj{dO1lzAXPaZ2xtMIbk23aAZ zf<V$RyjI%YD?IB*(m}75J7=)EI)l~5BnszAESwinn1zf~7SfTIq6e%4JSDN%l{abF zkc*$BY4hwyzXLPh%`=VNdYyezmOOKn?xP5#tPvjkmhUFk;VOC7`*Y$#b==a9Fq}3m z!jWkQgZKIOZ9tRth5hlAJi5G$;;5F=lBFf|N*!~J=vL@2_~>&oX~I|G>)V9a45+DZ zE6614px+e^@y9pwqR1JTnYQ_OHH@nmR9X(;mTCcRQHEBo3LPy(QKbLorSScQSSrd# zT%v8cYZXWNBZhoa4wH?d5!#oB*apP6?ah9r6jbIdoYE0#ah0wthl-^VOu;C5q-@56 zUu9C3{QI!-6zfFyDIVri`C0!}?_S*`GrR_VlTCF(+QjC$SB_aO>p(tKiWglq*-vP- zY5wF34&|Gs72%is#6$eITON>5v}NAHCEqWeXS&jwjljCFEXoNd@PQsa0i333zhoYz z&?S8;E#)Ro(zINbNkm(>oKe6NX8=Wwlc@GRU<24_pR`HCs-U(EBG33<RcOfjtQVC> z;vj8}yo^r*!DIL!`3Sq2R{c8B;N&Gqd5TNZluH_4*hnJypxj=GX|~}JTCK__yedm* z?V^w7Q7oK;D`?%mLTeLcnu#&2htbAN(>G7UFYV8j<#cbM^5w3rH@4eRIuGemgHGN2 zdf?16?F%@)i}Eb@Ri3CsQ2Mb@1K-UkoF`Fg<A6VIw}@Q)$8z#Veg_Wi#r4s?_UI#j z-S)n?BlSq50w4BcPH;$v^uyG-733ys*1dQXcj+U!&uR+7_&!Q15hmUOW{3ZThqeHf zH$Y%`iy=O};e&XmFZYct!W62`y!UNcyM?Dvhla6FFg?t;{Ur_GnUpvoJin%9`nigS z)W7Yo_=#7;TlXrQ-Tcc9zr2Pf;V<)eo>4ec$BTwm;i_k(4Uep8Td%#mz4?lb$Y~f- z(3hP-_9=^gVJV(w9?IYLB@PS;0AQ3)SgEs_u`bWzLx{ZwM?!B{{yg+4-oMX_?k8~) zq{7v&AG^E$MKY~Oabc17U7lUS;yrRE-|T0d@Kdor0X@Y(JqqW6vt#&kX45Z}&GYf+ zEDxDRo@(=u1yML_bRzFTTw~=O@&RxZ>Y0e59iPFC#zbSYKuUWW9EZoBgEj!BUc3uj zPQ<Bjrr*Ufe}V~;QH%#%@u{LEibLgA&TJ4!Si|cwOXCm#FDf9dPy@7QUFgGpDSUke z@`DQJVJ4a7KTaft*Q7QmmUYwNN9uzpQor0#GB^hP$`Hmht}NZKZYA;MA+%w@@5`3^ z?s=SX-vp<mV7~?V5&oRQSzP6vSrMmBf4S!(#rIX3cmB*e1U26Y>osQwzrp(3z-CxZ z*^Tgcb?hd*@<WP(49D0Fp5$1=vukmV$O4=4fW`vP?LgVV4yA{VGltaqm-y0BAD*by zE-0)#))hNZIBTGSOl#RZP1H;Hu{Rv~)?MpGerL*JAw#?M+K@@Z_mPc4qw+8K31`Oh z@HP2d`Z?~iDXe`Sg}2==#AwV(UYo5e*`}eVSk6<ZvrIBDA~KsCp)A{%`Ep4)$XwhO zF9R3yEMD~O*^kBu+vL9b+=>%^#<wV(nVl#j8deLlf=}h`O7=PlY4ejYk$jdkTuHI} z*(c+hfBVyq;&c9*whFqu^wNu??+`F~k{O$~3eM}Unw!GexRKL{ccDYL#X)2R2wM7% z>}>x6%)kHpzt?u{+Jzwi*0_Y-w0U#8<Mun-4L7jV9|N?qa4y<(LOF7g_#(|2{JjPc z)epQzfZ3nyJ7zz>#{HbqrOpex=TenZywX9Dsyy6?EBg<}k2`kkXwRSn@Z7d-Tij|W zKWy5tslD~Cx3=4FzYU+)SHW|zs8vRy3?<{)j!Tb}{DQ9^%z5r5J{LDU*$TM8k&>n@ zTp-}<{QO$DKOZWd>i;!!C>&5TsRQ|ikO%r)E6sZ6{Tb*|*;ze}lOno1+4kJF_Kk0R zvpxOvGwsnwA8T8$+uDBRzxeyO6xxbWATlyK5e@N_CweRY^hw~+_L??gd%VCQ6b1{A zgJD?Lu8^}$>B`sD@uxIEL+(`GQ>U_j@Ba4i!{2C6KJlG)*`-_B`+oX;?dq$pL0(nX zb$=0LF?4qe*dcZ<ZAuWs%Ps)x>-qdzb^7vjs_cFJy!`8r(sS`*X=$D=H9q&>|92Ur z*!jrJtTYb?m?FTzrHx-ER}52Os~dDkorH0q<3J%D0S#VZ$4ZkJqgcffViNZWM^H8^ z#IM7L(hc|A+wS;VKh<_KQ+ezd)&dB|rsJV9P6eD-^D^xb2FWVn%<lx&uUgaE0Xl%Q zm1yNU#(-}dOli-HFS0QJ%4MdcUFx}-`!)Deb~CY2;(qNbUuh3N^iUgP7GxzG_bo@s zdGHXM4nnwwu`;!|nWA&k7n)Yjhy`s31-1;$&QQzMqYR*2!eb|S_dWNtcmB+K+l}|# zgR*F>?Pf-91xtM{*@Ds;<=YV&fr^}AHj>bi&`sn_Bd}9$t)9iN4abhu<LEJ#dSYR$ z)wy-yH#;D$cpO-Yn+z0z*Q<wk5k{A;I@r}MhRX8V01WFkl(FM9Muk)BSOxQe0|!tt zA8IeCtlzma8~V9C;sD=d*dP7KN80;;=Kbl+_p?!=?k}8R5GG+xLy-=E$vX6%`L9ON zp|JV2zy51xmcGHpBO~qFtFOX^2o`s2qOoet$}HIvPM1HMj_F#qwJ6$-u{prU|IHt? zPyU-fY=;>XZrOYZc{mBeZsF!jolG<PuD?kKx^DOcMx$(A!hjz=7vHpVMmUsSkPsEF zwRm&MtOAJ>1~S_yj%MLA%mlo~8h`|(W8qYhFB9`VR<$aQAOJf@H^>Z)lAm>Ldq|xE zgNOBHx_!O*PG6zM(f6|T=DlHj4`69WhSS11_1Y=16^;nTLHU7a8o|%m|A>~rYuibi z1fSBzsx_<Gl+*7FvKjPmhpxu4dS1kY$kBtxu==Nr%tG2X7Oj<U>K^7O$H13=Q7oCc z_!XbzC2i^^W)$4|yc~MA9MZ1W-b!D|(DXfpo8(BR6FwCbP4s1lcr<(zf()L-sdQ=i ztQQqYDx8hmFNKe#kGuo8ggFy1UAktuh{4|M!#t8E0<38abbPQ6W1h2*TR-%3?b`e9 z0(9zMoY47BgWt2_7#>#&=c#rK<*}0*E7z_hUFgPaEjEbOqB-S4iRMP0=HS44@)YiS zjvR0MUpm;<ZrV&+S=AV}f-iDHV{aP=37nRMlXSEgc0y(q1ICSPiZa4dvS_avE=6I> zkU%{9r$QrjKpJ44*C>A|M|>rN*P=6o;jS~6f7mgr{E^nf@Q7#ona1L8QcEj%<P?M7 zNvy4=PU`dTIEy{BoI)T-9%7F&+b+r1S~0De^sIK^3js=m!b%;KLPyv+d6pjgwwn9y zIm%|zv%QjP;@5ZXMH3g_M@i&^r|<cx_tmFGag@*G&sEy3Lzw&rZe9ciZqgQbW4L@1 z_JpyLJ*&d&o9P*cQ@&wa=u-CrIyoJHdJ}3WbeJKjm#Uzvcitr}N5fzk%w|CEz}acj z0s3tf%S+a+Y0KfItLXn0z*|&058>uzAp=|$v|2A&rP7oWZj-=8%_c4J=R0|s%0iW@ zmfK0enxrfs3^#!w=^#}&1x%q|>r@(5z2~*%Duu7gD`D>b2<wqwX`EAh+9sn=<%`ea z%DzD!W?&V$!VY&QjtX}u4V=c>GoisVidro$Rr;8>N?<ow)pb&o!pIQzTgFqVsC90X zVdQ5y%vT@&mQnuDTLT9!DlB}AvMAij!?iMW;BLwMH-08?EK3wB(nP_jCHj>3=IR8y z6NV`h<##jLC0H1`;jM*KrW!vv8h(})Sim2-OQp6aWymx9PCSdF`~n-5z*&~#!V^Rb z8*eR#lMd!DkF<U*cc|QJN6!SMtocouz)b2%rIfI`99UV=)g}wEem#X7F;}C>OYDEd z-{FIYuqI|Nj4|+p(s_c_6pNQwC-5P@+vnM@-Fe+x+U;9!YQubsB`k0R?!X{kEtAlT zV(P7K^K^QeiBrh%;PEr<;20Z4vu1yuR=MzX0)rLtQV~E^d+NJS;BS9ld+b|(1AghN zI(iN5b^Ira80yrFCgJb;@->NC9UyLLo1J1$SRf^WhA<QEEJ}6Zm(0`l4ex`8ZO@my zEBqSQQdxWTuG)Y>#5(*Wb)uq&cS+}5UMVCA+4TJE7u&OKqu$t7pbluHl98|5w}2P% z>Xm*(Yi5<rXQOZ~E9d##$8Y-pD_%GkuUg**S*E&l#cB)**0rsdu4|XC8)=({kmsm( z`{0zD{L<f$cHC*u7WJ17QRJ*JRi3~Eq$0|qosEStS6*3j;vk2(=x(cA^<bHOFQ)o% zbwj8`@4}H$?syqxU>7_}?JnUyjV=cDO1<zfj$)q$nZU;iwrPw}&LThI$9d5-o8+=m zNQLv+_;JRaA4~UD;xAcZnU!%%5q8!M*TCoL`NK^5vucn$`I?q$exCNumPbnPD4LQN zDbryHgTh&!FzPsj@zN>o<GY!GedHf#w)Q~K1p)3n#3?whx-fnCDb=70jb+FS%W1<a zkYP1G@|0)VFBm>b`9Kj!W^f-lT*Q)^J^f-V$z0y9CF#l$R%VihWswe})a9xh4VB9b zWmthgxpC)~=0aUBa#CJ79Wp0s>P*F+^z6}H>YfKJZ)Xk*H2awSjj+;In%b-|Jq<<9 z=e^H{feqx|tJc>ZvQiC#m<P*bstRZeCQN26ycSk|y62@)jGZRh-UFlU=oozvnKN=L zoKl{ugSv`C-RY@t&V&wy4-dC|=beTp4-PN=eUFsBEW$8zPq>2KcjB3oLU}J=F5@vL zDCoDKn<zrlcA;bF>@0>9i<hjRFTz@%v8!;A0HP)Qn=z!D^ttINrUjKxfP!ASOr;xX z-ore5Xyj=&e-HUicmVg2&!COKD!gQ8mY%|EA1gn0$-K0pA<-%}0*rwP3F^|swv?Q> zjvw8}*l~Y*`r8k;Yp%MO%`1nSdz?7F4^0QYK#_M_=csVD{(8I{`_+!{un@Pr-1;y6 zE1vBWZDW7@$DeG^J^vg@NdFqpEN*w+`PO#VU3XC@j`yVp<sRfRag)pnM{|O~@WOk+ zqf)+Lur5GwaG}5?2?c~6gupn~ece}NK}-E}<9N>1Vk+SGV5B#S4578`_U${OXx0$V zF{SPrv}%6ud*9oxfAjV6G2indm6^&i(uvrb8E3vCtiU$&-urV;Gp}Fa#xl*R{E0gk z+`mF5ukor<eC>4mui~ZJUWb1h9&MwCU%6I!+=&fqD@Tt8AGxpku^n1&cp~jgS=@e2 z!>aAuwzub=d%k`5sqeN2AN&&ZIv+pIKhgf)-~YQzNSD8KWh&)k^HugfM+?#inecwD zlQ_z8HY;f<Ix}2i9LI<B_HEnR<4-)!q|&A6{8lGD4JaS_>Q|Ytcs65~U;WjOVC;AW zZeQtlNkg7?k`;N@y+&3kaA9HQw?{{hp5SEW>xFOny0~!2xrONKb8eykGlrsGt4%>~ zpZnCO&i>VJ|Kki+WY{u86_OUlfkFtv8i5cT@W>2Qh{^b4)ye?WLq(edI0vLEid6zj z1pNTy5DG11t0)GwE_EQh^^QB*-S7YDb`Sw=^pu0O63VSe8-Sfggw_cCYzl}nS%O{V zhJU!XPzkJ0WCwG?ejN7zF6*Ah{b^v(!g(eBnwFs?9)N-CVBP`#3){E1uRZkDSUE3- z*$*?TsK7tQri5qG(KGv^v?ClSO-)<38WPN62HL`4r=3A6xN$%h>o4A~X6E!gSZ%-U zzWdlPVhI-Aqb#RKkXyAHX#_$hkwGj&WP~mg5x<@e6m{7lqf~)yp5oj*#D!MQZYCgZ zGbrd3M*SeztB2Rw_cnUdw!)XASl8ixET@kgWZA<382X;Jd-v`rwe^h^O9;y0AUGB- zq<Q%8;r4+Ke4zckU;gEk(>m7bUF%yF{yj}t|I&}jq`*ZQT8UexF%(fMdDo%%Uyh}% zZY?t40WK{wdcWM_Ry^Cd^&NK+{;+qxu%rFkkAI?l>QDbvNiLh1EY(~D`d9=}x!H~u z+X}|9!h~K_HV*;MAZ3T+#5eOG16f&#yKqmFk7BU9Z=YgxDzg>eHBmw!4$ELWkPcNy zSx@5Afvd_1%Nlq|KlDIeeHhzLue3{>ic130hd%o{Dq*kMT=`%wfyz7#BQy8ja@k?3 za84Y`Cn4$Dq(1-=*i}kEkHLcq{H{G2i0=!ScsUEb>vrP>>iq~x(Yx@WzV)V?+vh*? zKzsDzZz446DulKIel3f%Ck}E-W4!ZECht4bH9yNLof%h!vv^U#>><q>R=#4Ij>f$P zR}OA{M?w)26^2dpWk)Q<$)~3)^AxsT;Vi$=&5lRto&0P=rYR0RjN2dPs1@MsqxVf} z{mw<<eA_R6pj~_aJrUl?2@7TMK^~m*q0@1!Tt<(Nw?jwqIm@7P{U-gFD<G3A16KKl zQL6MRwH$8p%)8ULc{zOWC~b3pTf6yUl!a?pk}Lg*8%~Sl3I0qWf0T6?WzS05m;UH= ztuf!F)fwt}?M6_ELA<UG{4Rx40zfbL6^7*nD!<H6e5-`xzX0sZY27jCo}PjagZ~LO zqMXFqYHIW-JotD9W{X(T;ZU^b-uNmV;1hvexJW;zr8jvp>53^FGYV(#X}h+y(4SY} z^**%IU6Z2qZ;2TANe2#EOjFvbusnchv*9N1e4l=YH)13MGvn}{|AMK5)JL+<H{(^x zU63wJD#$W+iqI%S`#1pEE1Zd(qe@S3a2lEwx1Jtc%*7imoGV8jDOhbbW;iTqO&7YJ z2j5-FgwHYt{!8Jx!>lG*&b|U?{l>t>%`+A<kc|5QtC)1nSEb_w1Dvr_?kAwtf_w}i zQEOH9BuL*!=58XaV$k|2$f#o`ltW|S)qyI26}_YmX(8|<!)nFqhJ=<;8W3`8LfngJ zX)Se18hOWeU33`EcJ3s0@Bkd4Pw2(LnC~QC735_d#T&|0ybD=I`Xyf{r)ouv*3K%M z7p0$)&Qu!PC!`O9{)J0i7wrNgVKPZ#ZmAz`$k#liv$&>#$D5XAG>G5EouD;663c2D z${ku$fdwxpU&gheo|C!q`GuXeu)O#*Liz-Jw0u!JC_~u{oGQ*$HtYUE-1Kx4oSGT` z!fCrbpWRh`i|c~NXX%PR;^pk_O`}R#VT_Y<k%`y14gp5p?&$i=i98j~TD)lCY~P@D zvxV2X`8dk4(^&qgY#twFA^^S?%VzRl9E<LOcKg+DiiPtlDV)tTxbFe8wRSMt22M?~ zhse~tw(sbfc4C6Q2^=q^J!BKa)K<Z7nNFTO+8+GE=fUf-wrA&d;M8~ko&l}ee_BV@ zx0C!@yqnP!R~2R67k}ct+=hOwuVZfc&QGd9eA*ZL=son}pPI5T5%4$zzc&Vi*1(6f zRmZva)Fj`1PkrUu1+#B36Ca67DJypP9C;=^)1<9<Z{<b4fKH_!@AIDL$R1iYD?fSF zEd*gulFq07EgZyM1n1ED%~3cnS+R<ZxtFy~xYO9Me6Zbo@d_reks)dOy-ZgF)oSmy zFI{V>1_z00U&?8-m6}l`S{#dO(fmt!yE3LNTG}c~-Q>4J1NGx0I1Uz#=1qqqA36*L zol)izMzjc)hnLFRr@o(HGM|J`X-y6c^H|m7#(|5@vPnAE`6!@M$0(8KEm%(bs8w%n z{JVH@C9D#5dZBLZR5;^O0|j;ZpOB2@w6qjGzz9>tOaEs-hq77apbBR#xlS_9(6UQ~ z^Q8WqJyjke<2h+t{kf~J;7cUs#_4fC2ORpr9ir_jmk%SOMNXENz;nZ&yY|*$Q8eTb zMvu^pn1sR1XN=`)tTh;ttYo7=C#glKL1%gj?p;-<5*Id?tNhwzRpz=$ALP-URYN>V z9y!jn6&|~~^3r{tb;HX7vFg#-1nOR$yYixcC%t%YT~M`w+biO1-X#eDfi;JxF4pBo zB^$h|6fgQY%j&cV6wbI(+<Ua`J4pRdUcCs#Wd?!5uc-%lnLKr=Zmwu!3us^Zz|MQa zS@<qp?=5G26PoVuB}Z2!DMVjCzK;@@kC}X+T~4QuvTfQgxr)=3ZSd*P4E-1d?pJr{ z4rF*_EpFXbL@90_;gR&S?x&!9pcsG|PS<_|A#fH@HL)xdf+dCv{_6ia<jbQ{3H)?; z@7sWu(6$5Xzb0jY75GmvUeDwWI9Z7j**-=dY`^0Q6B9JQrEE-pX#d{!)VIEdi<gy* zgNND`S6rI?q&i@FNYPg;Y1dzKV_v^eKXUtwb#1pDzqg(}ETgi>SHJq@_QVs9VPLWs z*=h*I*^wxl-}SC{g$^0GA+xbc9Node14m*oAkgV=Lb0z6ZS|M09p?3Z4GqpI5|jYn zPT2{sK0sG|)@d2AfCFSgbs`qU$?GF12tWOoe}zTr!>qO#LgD;v^gXp9y!3XM)wv)1 zg%7r0{G|`KtFO5_ZBqj}<uu2cUZpSb?h3Jt0gAw?0i6eT(W$QtqTD~1!#4X0iTyy- zq)u7i$YU<4B@9Kep6qMWPAQuc9Nvp;$H4L-b!i$u4zRHvkHn!F%CI?dPn%SxvB-$a z!Rsm9l*t=?cbt{D-^Lx;6HE*|`R#AFCmw$Sozc&=_q^vl?V9VZCXj#-_zgNTc6JPn zZ08}21B>Ui=eO-@pZ)A-+8_ME@3(*O5B{r6L>xSHusy~;VxRu>r`zp!+}?iezy7uC zIiZ1|xKQp<7w5R3mw{gi%uq#Tci!h$qm~)b%%U6P)dHTE+JF9s+5N^F1`Rx19AM%6 zsk5K??cWa4W#ST_$`%=!gz9tG6GU)S*=z+FwgzFPJX(xpi^@?47w($w=4)X{q~Ue! zBnm!w>>vY*(+EbRRPZqF7H)pmkGCssySXh}vku{Z9HsGzq-`9J3<6;sb|5E?jmA`7 zhT?ew1&98DjU$ru2fPH>-4Jl4mZlk8qS&CZsgP9SIsDQgmQFs>o}y7qvh>^8e8Zh2 zt*BjK=rSi8pPjB{S47r&D|yJg=s0rU32j+kOvBYd`9Z9wH!!pEw=mbg@5kQRR<2u@ zcc)0}B)D0|Kz%*dW|mJSwSyWJUE)-WPzRU#6z-X`%1ZO{yG-E_%HO_&Hx1u=)uL3z zo`-4Jn8cvp9b_NCQuv{V9*S~Vi{|}%cBcHs^H8~IImBxzsEs$6G@p9vsdn$Z_qJd8 zm0yXE<$gjzi}D@@^XcIfKbA=gXBGS|dD2?K-O1fB(Pe%oR7w%XdhzOEN2HaOgAwV= zvY#HMju^-s!TS1>fAoh84j;(!{S7FhU7G2TWeR+q!g^y0!O6Vo+S)wg>nq#39me8w zg~}Hca0-V`GJqi5ZS<Q24%P;b)Q7^6H11If1XYPN7V@$KQ>Y1!;JVVfR_e~wMM(>7 z_)Zv9T%6ZF_~v06)e#oH3@@oW==TthzU#~1*PlyQqR=Ev2`yy-ts+`JW_XvikV4YP zjILpUCBh9f6#sq%R{8P5KKyCpw&WlF_HVVzx4sEx{F(Nr|L#xPAq1YDGYY?TI&<2) z0IYwe>-%I5{N^tXLe~s-{3ads9luw<dpNmcxc;<^(yBs!lzgwinX@#8a1NYG30k=9 z70$v{lQGpM6g*8-SQR^8p04@P)e6qc(bvsf70$Q*;?KA1-f=H9j&cA+=xLS_E8rw; z@*hV)I&q8@3Rt)-z#44hB^T4i9OzMgd_mf2f~bV|suiW0hipv6q`+YW%bhRmZEH4P zf^{?k{}TBzI44XF!Kd6wfminF!?gVsSgfx@(Wt^1IgTK9^q$ZM`FP9>5{Ykm3g$H! zsQmK`JmT8A27$yfCk2*@Bb@b)a<jBp|LWtk>j_q|Oq@83()kDqXXpT!^;=!-LHe!y zRXP`Jq)U=gLH<-Ydq?t7=yds)YYpj+6B;UdL5K&AyyI#qq`j2JEA7yFElBw_P5=1T zA6A1frQK3*iEBC*+ce0_;GV)~%$!8b_oPLb?tKbFIG6^fWl`O3dq>G=dISvoXosbp z{vZZX#Ra)|N=r&}90_HTDzEt_OsSF35Fbd}p6WEu^XR(<@vFL=Ns1Aa%}cQ~TgqhS zQu;crtgJ;h%vpf4LqGc}tb4_k{l+BPwBsk3fF0G127DFwPUHIHg`QnOVHkZTYK7y5 zLY7>fyAb+MeNqMos}63p$fuC}GdQKcRS~UnQDv%q4iu2`iQHJDfOKUJ<q!9J5WiV2 zM_6e@0WnLDec%ulbJxX0pb&m05L4$Ox=UZ{ecPsKXJXX8#{PqJRbVe=pqaXaUgA=N zu#|$c>ORUuh(v|6S;rcL_#VbHzxcESX6fAeivVl&lZIAc>63XcFE@T*WFV>ak{j&B ze>#eN`Ljy8f=_-y9|unzr+-r6Z2l^F<E{f9n-x6rP)>^rIGoV2xB(X7t6B#XBlF~+ zbd*6KI7nS^6;^3W>mcFPWl0k3V#%w;p**sLb#SO+99cjaZ~)$r{WegT=u$&}&6dUb zv<`ee$=NHMPoa<jtE5T4O#cu?I(75bt#4^}Tz~TqSU9IfQv^%UAC^%tsVjWo9y`gV zyXe;Tvr*u<emx1P!g;1G5iUH8=-an{zkTVmp9V(w*BGlZ0;m1AlWo-xTc1wA%YV$s zdUInl|6&11o%>#VyMIC8NYJ!Uo_qMX8i%lTP%orimDatgR-FeGIQ?NvGJz*@c6BIU z(I0d$!8_eDB}^h2w=m?2m>lw>NI=xHa)W2ugp(D#qYc?F<fKAkQOCrAzM9LIGqmP_ z)D-}1%)J-|)bIwDrenyk7`GY=k(-v`24*>{c<#OeH&9%cLJw{zE58dofFw(cOAY8v zU%1Kx;x1+6Tgqo}QIkXJ^-mscnY@E95U)pNx{SO}1U?(4LiYE5wr={vlst-(`Wz~1 z|IM#6^#zXOQ<gZoSvbkQ7ZyvNumENALKV)_$Fqr`*_?F~VSF<WEFJ=vto~Z6^}gi; z$H<Sm($J;G)O`4;`J_D3R9Eo8+QA!uq%BWqQ+XFTQLAPZEfcu+bH$#UkWFfJifb#C z&dS==U)lp{DXFqq1%#7qD!{2PESq)h=UxrU=gL%u%PDq%cjiSf=8w2fA)!fWPrg8U z(8cOCE23~-hEGp<j3r1=t{Mtkx>Hy*EA~5aQ>#9p3$ht>@~O+am!$#+@w|H2rR2(w zwdU*YQ{LCl`ER-?`6Mizo+4@XWM-J4+$(45gR5OM?0{$Mnim|he(4zWh35&A&CGY^ z>=5G={pJb!%w2mAx9u+;;`wwNWizt{j4|b-^4z$uu?<kT#q>e04jJH_5C5zJmpmIB zysR4Xu0u*n%TEt~AzWGlC|)W@NmsfNbTUo1EB3cqHOuqt$5l4R;70x?-G~M1b=j)* zZ1}YvBQYjVfLT1mzcQ7l3(itx!86k~J9-J-1gg+}kXBf&TfPfV(fT=B@}p(QgiRN+ z;3#yY4ECi|$VrTt;=T^#kKk`y_a1(qMB(gsq{=?c7=Lj)xPMQ3;^D8fjq8?S95;le z^A*{j#4JQ%xF|O&oZoZ}Zt~v1LoAeH)jnDNT|BnRS>vR~9($yH<C_n+?K_^$%7A0X z54YQIyRE$w9l~Pxtun#@d%<`eV`b0)?<jowqTuHO@K&F3fk3bGvuVyHT|&_=kTWCe zGH!*(lyX^In5i<SR<GQG6lH`@eBu*PFe`&^+qS*!-sS#R?%jp_0I&P#fB8||n7*@J zdF_=M-`6C4t%9xbJA8-8$}rM*+FE7y>ZO$K3WQe=GwaJ-%5HGW@BbTlTqwDGw=f*a zcp86-yFGh$vx0qB_RCt!_+T}LkjvOx$Tppo^RxtcFwGo1LtpScMFYRf1HGr~Xvf%_ zNFKJIRnjl)*wNN7&ah6u_2{EmH$O-pu)2NlgCArQ#~a~m<@ydTQ~<pJzq(O%naluX z6DGRC_Py^v+rEH)=nG%`LOXKwaForPFWN+(INrYW<uA1ledvRsnaeNV5`L!)oz*w+ zNOdFnn~q^$&*WbQXV5td@f~_+LWTX!JoPu!J~TbMKKd^|s@K^v(i;XNJX##Y!ugB; z?0*X5&}voURKV)3nN<KfbMD~DcM97ok|ee)PwfU>8Tb*;#%&nCI{;E?r_y3zaF}<H z9N+bCY9rir=t!Gl5PT=TQ1AW8pN#tnt$1B7(JQNL)OI4Kue^Vl@4{h+aujzMzE_#4 zf7(IZXE<{|h;Zl9a+Qq|`C|N!(vI4(L&w^a-+Hn={Pn-V^6+R|LKv5lxx_EaffeRp z<O;vBsH8lx&;<usO3eEO2m?h}#VjpPZIDz#n*IAel-dsN-}C<WwGaH_FCv5uw{5$2 zwH+_M*tT4GW!rr5<|r*?lC}Jn&Ji4G5$d4J!Ayj_zP5ow{EJhqIJFvbM_wC}c<|8L zJi-ED9jL|<3%tpEP4_$B`A+-wU;p*QzZk{WQkU&8P!zx7+Bnv;ZY|PTQ%HAtmuc(E z`7LjGbNk3gKGNR#&Ua=u>&TJA3_i}e^l*TxrC0{Nz@tDQ_m-X{v<R`j0LKbEQ63qN zQ$<hc2^b`HV>n0+ol!0o%L)nK|L#-mPyX+J*B*S}0Tfwuz`V!SCSC);pgI=@Mlc~5 ziM~VOLsmP21<Gz<GraExp$o0x7jxC3!)2lhO~M>ygmeo`(m-%Q0peQ=e2(F();iKx z^C$w(DLTIzD68bRH1?U4lQ=24h38PokaxjHy)<ph*_Yk&dTQ<ML_pe*;k#2Q*1<lH zp?j4H4*W%{f}icf8F1T+r=6_nd6=GxXZ<dng6?)7KG>E+2fzFef2~atZpV%n+pZnE z+Tp#sSjx0B6BEK`-j*jPX_~oz;wR;_O8K+w(pi+{e3PC$Ov9t+8}(2MnZA5cz)&Xn z&dU|U3D1w^u`}?h(%-yIvsX9+2J~Av6C!y|XwJGMj_2$n1BBTxxK}_;n&5OU7S6YP z_=8wDzm0(gdGN=g)zq^zzkvKEm@GMd^aQ(5A7g+y*fw5#DYR&ZT@y&j9$X2FhrFX6 zz%6xj<lqtf(c_kfLH)>T6wWMDrmCm{@MI*(C^+Gs;yF;0?~SlBU_BPCBk)9I2f|x+ zPY6WX<S71<k35)`wP@R`bZz%khEH`R-V{Qi174T>m9hyQL0je*fd-)w>nat_r;Z(N zCl9~WP91%TNgXG4;K6FXO`QZ)VtG}_x30`PU%{L2z+Qeckd-HM8o|Fr6fU1Rt8Trg z1`@`)?!FN|3TyK-r!Eb{C9K(dgx49iOV8R&7(Rt|Dm`A2Mi+^z81)^$6_+<+Fl~f- zv2J>$v+=T|mZF5tjL5x-5ZhQ)W^iGf%V3)d<u+&CcrO8fL*SxVq-FNj8hJs7XZXGl zi;xu?H?>t8nRsPVX)zOSuFP4CLP3R%xoOF;FbZelG5QWnrb(jqEfZ+$CQhLwW{^x3 z)7PBFWerP&kB>$Py>1;#>9Iu7pKZBf5eLBHA$*+=NDJwvZqqy;V<N)$ZY(zlESbCp z50W1k4*wMw;ZwA6WeNLMCn9Z+p-Iw?H7spZB~I#*_)?8kVSOn$JJAp&7SFaT@vp*B z0aN9ud{msuBb6V9nVd-)@(t=u{?#w76F2fP`Hp-=z7-`n{M0<9K^2w`($BEW*mO-l z<?A#MMf26}%c8jWl8~poPK<Ec=U4|SwgQ7NliwMaJ3F{XnIx|4XSLW)f6$f1eEpWm z4B!-I(-e<R6u5${dPMP5a0|cin3rkUUJP%)bc#ua3F;k`=a6J=_qttkvcZXMt%vM0 z?PruxhK6+6g@rhDC_m1ofz-c)5eJnj1MG{YNc$8U2dZ!$$4X8*Uxu6%B|3Hfj$7_% zcini~D=3_+eHfvKE2RcF;X92)a0tK6jLF-<6Ik#$nL=2Vp|&e2&H55$9^ZQ8q4u@^ z=L^uF#9KJ?d)$j?MGD-hU+F2li1^@E-_zn+xhKAzO_ww#_!dAMTqjN68@FUB^9UU$ zci<r}+ixA#hD^c3QaOp_AHn$bje{4<lRvK0PF$v3rlHJbXz%4cTsV}Ayst@U<N;uj zH^t(aZ`mBuQ5*aq3NXIehv^DvKJtXhQ7ta#$A2>lXOuDnBdc(~#b9;Q#chBIPTg`z zN3KR)!g=RqYuhF^z+R0@lqu>v%fJPVGGrARbS*6@lc{jlFu}ez^~$#>s1v>lVeR-> zN#wT_&L+uG3dDM!iO{-DxeF%*;+=iKx#QfuJg7?@T=z%iUHt~{#JBh-tnG6gg|jX; zRHB~6orW$o7EhmOOU@qV*|^{uh4Z2)oENf^5*ZXLEc;$9#m`{j?51l|;63C*!hIhk z1Sv;qUK%L+bP~@~_ZW^zR5(v)&CI=fFE}wZfwEaXF{RR(fwXiOS&_O{E?x}J)1AOl z#zjkL!&-bg(WBg)e%%6E{V6^_@){n5+fQ{!w<$RF$1UZU2dyl{_1F6Kt59StXMELd zfJg*`S^}j(uVYxpO@TO?m6QsvmA9zCh2NPM?*KJd;dr@moZmfd7smg=!>_M=^swZs z!MX%2T34jdS?+mfozo>kpLN<~K}qlfTVZo@;3cxjc$y@nok@vNCTw@_JJOzg9@hXE zT^-fE8h8@Vj-S)^EH4SVX<&@0kfRsUKNk&w`{18+yFAUiKg3Oc6d&lGfH|@>z{<aB zT<&-VI&u7Le*$llKF)ok|5DKmPtyX`l~7JLt=Vu1WAk;4f#A=;9U6sTr<gQwwPcKJ zKu#%~rIn%=AxYgy8y%dH<z_%EdI#&2736jZS3aq-_k|;z2<FkY=r}D3XAB&s>2H-k zoiyp)UdeA_>_oW@znnhlz`k85oF8OQp%IkR!|l3ju5N?$`R47R4nX`ZQQ>^;EqV9G z{V;w9Z;?^$*PR?ETl;ylSMjxN`*X2!e)7pj+lCEmQ0N`WnEUN-e_LC-W<9V`7a6^3 zARr+)R#vvLHC^~Pk2WqGd`=<enr2!v{7{9nvWzP|l+mO+Td@6sawG+7d-v{ZU-`<H z;|o{?pySyWU);%FQcp(#ebGf1p@aCbcHjN?wGEp$uzH-8OW;;YQHBw(y}_2Uo$X9K zD^G`j=1{Vth&cqDV~~`;C*?WDxlphRC717gLAWZ{eN+F%7+UUUe=*1EZ)Fd)E3ddR za=b<t;!9ayxqk@*ReK#_S8mP<ekP@q_jH}6QK@O_QdE6~MtwVXzStgr{PFezdaj>D zpLZ3yt`Szdi2M2Q$S}zZ6>N^*9dpm89U!%!`<lj;$8+sZSpomeN4}XA`OB6M$0e(9 zx$;i;tnYi@``VVvFH3oBbM~9ku(GRiec@Co>y?k0_p^{c^NuJpV%*E3cdV;tH81=6 zqxX2ejPwS<2NFbEd^mskcm6q*p#N7~Q`llTRalna&e|kTA;1BQjk&L+YT$&mvmv}4 znGD5&hr&<>O1xLlb&z5jT0Sl2yGo{$2uS--AT#1?SKWGhdpktB<+^LyF$N$9k00yF z9pxaM8x}y541SLv!@|dI9WW)0`A8xTa2%ALVM(u*s}bO^v&A$Zmkz0T(r@6d7k0MC z*rD<%l&=mtNAUY3L-Mc;QP`4pEOLlv0~}(RQ(tyFZkHN@0Ai2{hmFxE8GnQ|ghydK zK_hgR=6mkHzrFY8eilJ&q&>auc{W(VO~fTzNVnV#D5Tr4tz<1_9i-ZYMDfM512F4D zoC}wod6o<#tf_oIg2l7SW@oUh!w46^p8h-dncr5hlv*YJZ~QmE(e~`#li4i=PY1}> zrv<RCERt5D<}(PhAHwa)S}ZGt>ALH#Yxh$Y8NP93GE*$W5(^<D;H%EBa3dTRB;N=V z1q#;;wz~3ICd*^Tlff|^gYPW6%*=uKQsC4Thdx93#ALzO+yD8m{}m44_eN2$ip^>~ zSFc^&R^moL#^MGN%T%&JXW~`-9K-tj5VLV(T=m<1g6k-=U|O-SpnOYVq${w}Q3)ME zo;WfPt%^Md@ulg&auQ2-EgAIl9gAA<CM}5v%V4>qD4;&79E!xuVnhEjHm%4FW85fC zJH>+atWrgqb3pDygaV^!ST~kK1%Hshz4@u+5PzoUy#TvJ+^`B{;!*+DHm!BMOOpoX zEpB6^eE|0}NNKp#cz0W|d1HLOYK3<MpIP5v8PoRd+f&bJ<K$(XXHtPONb#0cSZrJ7 zZ{15L3VNw)zDbX^sR&l2VL61!!H+z_=l-3<XPE##SIcnT!J}WIOd)<*;Jr-YEYBf* zsm||x+Tzf7y@i|U8j2PZT$z>m8P&36;0&$@xSxH9i`mC5AO29g^6mGK4vHH1&}nv{ z&$3d|T}XaY(273gcke#J_r-19ri<}|hq8}lwOag!S#ix^Dp^s_u|`Aqraq73Lw(QA zm*5>6+b~O(mo1aei8G-$KK}@w!fg2znwQX#s&rn@470n<FG0~8D^nF25l)GhBaul! z;kDA5NmD!%Hg#Yy!pmzX806Y6OW|zWl}|}$@GeO6G}cv9F6l*B9zDFDb8nk}8b9?| z-l=f5Zsgt4gD{f;DO+%^;y?Ki20EV2;}gcP2FOo^H%`%>bRi8&A%zR+QTXeu`wWzL z&y!Kpz8%<jZ(P3{z8|=FKl^=wY()Pno)9Hh;%dDd@GNKW3cYZ3NNheTdm%+=v+}a& zM)9b!bCn*bUz$eh*$Fi9oPH+h+Fy_k<<JMFmUg-z(Ry0f3};!=ycp}|^_N}NR&U<a zMp$99h*d>ecsigZ`^0xsHwQk_uDF(d+>Ksvymw;{`&%bJ&!AWt$Gyhk!^c=rbPT2Q zSi6{2JPMPAO$%Z?%4^+G1_d~+KcmQ_Gjh4^ewMYW3~^6|W%RxB^eT-7wC$;kqdeSa zQ0aiAdlsLg3^29CS~{c^m;!RSiW1(`w^!1r&C1AM1#aN5RHaNcpFwz{6Lr>`*2Bs< zZk82g9`U8V^u^)prU`$A--YM!z2{rS8%f3QDvG0=v_B;U>QG+pV900XBM<qX{KfJJ zcj}d}4#q-%whh3QMpXdYW~2pOg*j0xKNTKnE&R<eo*@_t#}S$*5&2#e&cu~3>$W3^ zHVoiY+YzQx63ADaK#yXb@{F-*=_%Y^1iz#u&li*OZh5_f53ee7wR}_VTR7t$!+sQ3 zEGU(&8?Duq{U{EZ)1ROKA7kR&2{{$fme^Hs){AxWo_p_a_o8$j(!aC#p}hVjvXw|e zRoW^MpCy%cVrrnhMAtUPn*A~S9;h%8Kjlt>=p3M*iR0rL<bLKa{-o_^pk&=UF`~jh zc#)1!W@Ob=>Q@?<hpK3yPqUJ^Pv1h_37X5&dpay1sSc=%HcJ^pAWI?gr81FW-1Cle z&xSfz=04EuH}F)I#~mhSz9b3jv_6>*gvP)0WE(A-%sc6`Q!L?!Cv+su>3XXyoKbX8 zx8+g;9x^c07A?a~&zg;#Ygs*^UwHgu!&}m4Kqunz(iKbFbu3@MWYsbZK!8kzJ$Qt| zNVm!^e9EnEh6@xZNRcOb7pvGRd`dPgJfxX}OMg!bBDFf~!uZfVQJ4JX(e%1dp&?!h zpGPKcb8A>m{ye7B2j@0Frfn2c?V?f^=l}~V<{jc*W5Tkr%4Z=yoL8JZBuC|>ZWicj za9MCU%!Kg(&VN<To<-SwW&yGp^>Ui>iJKn2q7R^fP6}4P$qVHH$YJn--Y6joL)xVi zdA3ijo~2K%%C&+%Gvy|R%0KkMAXy_DS9QALPldCSZHs7cWE6Ty|I^_?y2|7R^;10J zT={LUFbhuj6)Oy}#EI*`wYU^qvt|TYg$caWn|R}-9&9q=Yl<5@>2&3F0v?$N5ClU@ zP{@Ov15!oqs-myA?lI~2_dm=va1qhwF#GVm2dp@Ub)J<;Jo`>1d73|8>B`y?;14bH zEZiOxBkx=-beL6c&pfl6@!DwHwVRb+C=XRO_kCEkP1=CtKl*C>Mcr%E<g&ntfAX;1 zbZ0W*CwS`e5{ABQWVKEBzw$Tqfjp^#xh6(cG;`*;S2!~{hx`nIkr%QBWgcMPr2*XL ztX+Qz{q;yD86$gAc<Fx<h4VOd@8q0E_*vkD`qPj}gn#=oTUTI(mg<i8(hjFbXr8bV zO0|U!`M%=MH2kc*k^UW8*An(@6wcEaS<tSaN8_HN9Kw`-i{}-{3kUY^Zcly#%gdFx zw?r<!ZtJzs=rU5QdIH0Ne+etU-gMm?t8lj5(KFD0NH?yYwl7ZKL3!P1SBuOqe(?cT zA%CfD+_V;BrsF6BufUJ<9qrm{w^A16W)fmW)Bvj`mCNjF3Oi!vwU5-zYX^DVU+0=8 zm@WAR_{GCgCf;lp%6Qi3LS`wQ#65iIKopjL`4@kQj$%#ZJLS;B7$zR#TuXm**IjqF zU-*R&({`|$rP!13J^SdmMT4KoJ5I8)%E|7?CXC}WJg{w4YkBQr7AE_i;I+eAt`PNW z2g}#j6Lt>CogbvD{uJ^2FS7NtiBa@FAOHBr*~stF$fY)>TW-0TP4lkCMJ;=2Vd*@~ zguf!UE?c%ezazXvy_zzt#&xzW^$BaRjNWqj7TP|Oo$3XMw2wV7cJ0~~#q?UNoqy`5 z-V>b1bqD-JURQPSG5~+bN5_a7myRAi*`9s&+4jH#572(T$ev>dvVXuOm*ArvgBacK zUVY8g?cG1|?zRrykmD)a-SD!77_6epfgcT`KXk04j4lrC>t-Jvde5utnRf(~)c}}4 zXTQDXLExnOnt^^aKKA{`8w*X3EjYiM27cv#`4>TmvlcP|GqoZdP<f5OPGv}NeWj>8 zv(vQl90V!scsj_^;w8+K@CrY^8-&T)=p3|Z9h!j{rBb<e9Od$UOj0h{dVRb9r{B}w ze9xVY#kXxg%G5C|NS9!Bd<J&`&WdR<qxFol8x9Z_v1EII4qsiIK2RO}EyvnI*BY+Z z8e=1|!v_wwr=I*yd+wQMGW#)#m8u)*dFqePme4D(lqOWJi310;Hn0fN^c49c?0Ezh zT&e7>j#34XvvMkU^(j37(ceO+@xBjzpsm`p9{;v1vuCDTp<*4%fDF39v$zx2TFc6m zCxA<aF0<5<Iqnd^wM!uEOm(}Foj6%$>!7+<h6%fa%X#1@_uyZJvvu&BzxkW(YhU|X zl%87b+6Wv-J6IGKHqH&WBiXWLOJ=7wZrm7!vmN9x){@6@7h;;8!s{lGffu+<Cj%AI z6nD~!%{Gjd>nj~HL*rOR>BSDzcqG6**aqiARO}d5-CAF`Nx&ie@%#svi?GP}uDtS^ zwqfJN5gx>!^(EfKNAO1)Q|u_N(pswzh&7g&`*!bY&p-41wr3X`B<^~lO=9t`Ds?#% z6+>8k$e5-OzC6z$2+v2+cNTg&D{e7&ScGtB`dST!A?uEVXX)Lx;k`JrTpq&XDZUIN z4y_a433tIt`BUx^uf$#7exyBx-Y71(nx_hRzxPTAX)wwR@{^v$t4aauLrWNEEtd=o zvz&3N9oH&`j(&&@#V)z-+O}f-+IAcqeVY{kPkrYp+MUbaRW6n_ph^f~6lTlRm&<qk zz2(k|25_WO!dXOd;AuEd%Np9?>ZFs;9+s~^gxB-shw=JvJq+hrIKxZ&e3C~xj>4Jo z`n*h6+9&tWT+)P2qHyW1;&yQax^qyd2$_A{^5I`-m%r^U(n8q9iuW`-&}U#~X9yWj zQ^yln@a^1n7-htwwtC$rRzBFlkr%uxOPwt~l9TP#frYafE{&ega_$p{*)(w1fwo|1 zP5fkztZ>OIbQGMChBy_U3ZLM{!TSJo;iSnrESy*2yM7r~M!mwhtV;^75&DTw0>PPC z`&czmZLsQ~@M3*xRTY;A<WbACtDZ!&GuYE8j;2v4PM<o_#*XZ3#}DpdFp70IWkEhf zaRkQ6BpYpoK5ZM;se^;cGh_h%O6hD108$x6u4Yuq2_ba=T08?ddfG5O>abV*MB*ZB zDIUA_C4E(jgjOK499%gqb1B4uDe03Ip#!t=y0E5DgDMi>NZT}#;IL>tRw$uC>d2B% zF4+Oivhp-@%bFDUp`6y0LUV8m57PQWUKAxw>b(YRMpZ#Pg~DncgAfNKZW_wQ0d483 zHSMBn*p2<7&2g(Cy+|i2oG6tUK`Zp%_M`MyTJ&00m8M$FN(j0Nils2T^UP`d;$ro1 z-~j#f{zFW1o@iHHdo7cD>k?jAErZH0OCuf0r>v7G31~-?^kFZ&up<@``srQGMCJ-6 zVJRALB^D`&Q*kZt@`QJIc06t`lVRh~*J}KOy8OGJ=#%zUX!h}xVT@ZA!zu^C7I=1t zZ26+Ap`73oPA!jYH;Z`=4aw(#M1^xE2Z6^p(vRs#SJp+H6r3aZn<wEy%i_2%7wPvr zuTWp@&GwW)L3h=OFiJwwTi!_P;zoeTJBp+5Q{kcB`JR4-_8x!HJSU<+amc<blXys6 z@jzncQG;>uZO9J)<fEcg-YVWts&Llj1<%!Isk|^Pn<06VuQHOnQha)U8W~J{S(ei% z5T{TqiyvN)&2*F&_6sVbPaHpyRUFoxfJmqIF9Yzb_rLR9?QOT-`3eeW;pLzlq9upr z3GU{#BjbxuIHPQyWP(h-3T)x~;>LqW;&k7>ozVEn_Tc9}oyq6Oc%d0rUpbNEfLJ-F z;MeLOM5GuFaCHS%v<mFx<GpT`ikI+ABS-or!@_alKsW<zK*>+=@13QohyImVt9R$W zmnY^8Wmeu4*E!%FeSK2Odgrfoo<?ea>jabGIf*L`QITAcSx`Jnm-Vi~<{Nbqg)@^` zi%>!hu3)vz+D&bi^F}oQ06+jqL_t&uN`XN(evVIC=-h#)ie+hT9j-O5-ngn=w0e1b zIxh%5Z6CHD^6Ws4TQr`XEY+x_D238lCN8{AS*yH#`SKLrQg;-`n<_lF@K7?yD_+l} zz;}b>iy!S*ymCM(ob?=Q%I<yO?8ErEf`mp82aylw#cj*DADD1hfd6I{&T?7@#BDwb zdSou$O$-mAlx1)mg)@BmG?UQQ3lx+#V*W)RU3(E%Ha4&l>w419Dhl|RGI8W^WQ-^j zp;P%@6pF~WXS7_E-(k^e+gFh|$fWNO^6^UCE3L$}pQ}5S{bl(xhyW*D)%Y^-g+GUW z^6DH8$<H=%nhikbqnI2-fw$@MOELHuhCfrb1V2{~&aF)FqtclL4l@VrAeQlpSJHvt z1cpjrCY(3+Cw@~A-XG`gW=he2y5Q9;W@pnkCEqCzc=U3CSIbZny_Ac4VTRNLbKJvJ zlsv;`sGDhwkH+yWx|hw_kGJP{>}#VaYBdaTg-GOU=-+niINM1(Cqx|=>N-j#bf}r~ zD%;X{Xp0^1^BrF;zn?<E(2H%%$vqXyMFUPk6rJ?r1zk8*->Sm7`nUM~W?V3hPjZ~J zW8|<7d39A=gP(SlQ7T45E0jA5XLxKB&gqND-*(*{k&R~Vt91#d@Dn{pCWjS<K&0te z0zZZqclGQGzbIdMHBR5R>zYXmXTG)-!zcg<V_C*&6EVty4><-J!J_uSzTNGKZ$5}j zJjhsasJ;0u*T;n=k%QNM^KLiey?*PhzJ5aweH2%@P~@YVu>TWQ%WR)#8UDiqpKqW4 z{9oaoU<Gaa6e|VRXH&elzx_VsC;DLeAT%9}<Ir2ceB=prh?xr<p_L1SdA*<KoF<e> zHJ3XP+Dpd3wKC2LCV7zb`qvLV6t|yR;QG$hbO+gF*uA^%yYC(CeYh#T;fA-MGjb&| zIHT<;1FH-bms;&=%_@x+u1c??@;PI28{{00@ZdRwOQV}ZxU|-}Wj%+~elW-@C7pL2 zSt$R#gt6WK{=2{1o__l2wq?tf;6we<N_0av+;Bs?`s%CEoh)SnP5;@)+Hd{VZ-e`T zp-uOSQl_)tmS?HV{pd$OijH73dw^}<zO8);tMu#8Biwi2eeJHh?}mR-7r215-cLch z9$A(9gW&&AZ|1|O?O&gK{5$PW{{6pipZw$}(Wl||C;1Mx8*jQPG;#B-w_t7k6X>y) zwqtA}Ee{=Bsv#V!Hqle4P+y4t&@qklqwY<4S61ZlYAq}83G)NrU*Vl%#_am2lz()8 z=S=^vrwE-~5ry+tQ8?Rpw1QMQWaE?xN?;DOM3w?`ti61uq8)5R!Pqf*f%G(vis*ij zVh5*^ZHSpeiB`s7XKFZin^kdUm^}xuI%UA?4EbH}{_%FhU3a!&tX5CZ0UoDgp*Mpl zjz%aQ9%L6~I_yQjyjY7GnDzY5f89&_u&iSs^AZ-YJGZ~UfQen4IgcD-nKxGzaKfkm zVK)*y$w1hS((X){wWhWs?#oi0!7R+C$36Efe&R|3SfY%j3`6+3vh#BQbr9dfQ?$A} z?!CLc=VvhKzv?OmMKy@ov}qH#a4Dkrg@1C@Vol%FyYRL1{BzGCsBFW3(QXDvd)vKl zdt3We{3zSm92OVg&AQUsL4~5Q_)dlM6iZ><Ji#WR!r8|3d%yR4?Q@^|T*|f?cM7`J zP{F)u)8_bQR^e>jsI+w>Mcq)CzPM27trFe59AMfoC++OhlFY_d1%u)0DZQkj`TkW8 zSTUdb@Lr`4nL_A|G#t3aT8K1M05}-bI#|Zy65J82n$IGr8QyX`0GH0ZH$4Tm>1o`Q zAaE(HDioqSZf8(Vj$-NTGVlF6o@+awd$zss>@)2MbTc1rw1SNr6v&mc9ZWj_1;J4^ zlR>QF^bM}{kCOq%vA*kZCCvzrWl=z~y*S${u4<r9WphMX0KAr0SY5Uv4cR7K;^KE{ zF`Hx&M&);uw<P4GjtWp`fZcS_G|F-goO16VL}AM`%s1_ti4a@Mq;$f&Gkkjq9IV)| zzHP)}(Ty0M{H~KSM@kq2SGwv@2zNrkbhU`-%K*qZ^h2J`2tms7+RmcHp{*%!``x$& zBMcqfgiri`OyMldvyWSU>4WX6x7`izQQ-{DFVw;fq(Gw!?6cqnr)h&PzKGv-ly)Pl z*0K2tn}5*ZsU*z6f$GUrJ-$Yjpj2GLgow|EgGWxZ1ADN-A7H2Zp=E958h!kA3TJqV z{8t4*gmto2Nv7qrO1!lwoY$amUV$G)-<7hNw&ai=82ceWW^*0Da8~gQp<pXK3W+5w zC>X}4E_J7%tAJSkc<CpkF_{<d<}+AXaE1x8;|HU3o)`uG2{uxK22`G^?obHvXI>@< zZ6nfZDJrB{39b~*paL-J1Y#Sb1GCT)xAG4E#JP!b5$t}z;`{IszS$O|FeLrNAq{ch zI7j?ZtlV2>+nnvkBWWZZ!<bjS^S$@|VLF9VuiXKx4i;r14#48h!mFSXNYn~;%9mJ{ zkr<YlXfzMnuXW?3uk~Y{*q%v`+o`lIb0Z&=&1X;!&tn()VfI6~bnBbi%FRr0tX_$4 z(W*@?1&N&av2M2g<*)dy)(X~T@f|Iga1r1@2WD~Vq<zjP{m@}1{f@H{$kw(7ivfX6 zwUF$53S}ENi~g`4MXW;qbI(4T!GV?s8#ixeBg|DPZ}7;E^e1moaZ<Ehd`zo7U0yx^ z{PXbslj*lyDpyt$W@cSbuhJ&`$5l-|O+^Vqd<Ss4LsIFyjFm@&Si|(LVM@tC{mL_m z>$5nB1vT)fWVTPqWFUE2UJGe;)Win)QWwcP;flt@gZNa5AG`=D)kVxa_XBiMq(5_B z7F~z~=^?m9p5khGEQ?F$t$Zg6iY`hPt4b(ZHmX=DrFLZ+3(2@#s4z1VD3VX$F}$%n zinhzoXHDXV_S1H%3_hn#`7U(_-O%qziz;Wwu<Fx?{S@_Xs>%zC;9d5m-aBbNhRdO2 zY#?a8*_M@;q>Ux)9De_;ceHzMxt*12hOhoHpbDM`iT2Q1UfY&!;NaMzw*UBaJE@OY zU{qESPx7}ulIcDB%u~oS$J*aK_{GQu@<(}^I2IlUvau+KZ&|OUaIS`%O#_*1x3c2m zfU*dKs}9nptz_<*f)tafQx&lumZAJM*L_~*r%EF(J<@FI&Zpe@Bacy9op~iOT6W%_ zv)GkDNzX*Qqx?~FN;A}P)id9uITg_0DAvp!O$A@#&F@~3GxXu?o*s*qu4qG8HxI4D zEgZ%Vi)c$l-?D$?TKYWO!ZPrE`TCVnIA6VSC2A7dQQBq4@Pv>5O!xrbLe5EyN_u`P z<Z><HEgW`u34S_!c(D#FWcMn!;GP=Kt9o6(HTg9=@VQ9do#W{|^`8I)h?9>nsc;Ow zp)KjF6wd6gVj%i6H%=XyW}r^p$DP%DTo-BKtio9rS1MwW7p74-pTXa_^;Qb!Dtj^p zey_s2z&_F*Ig=S$Fqiub70&X-a>1iqr~*qRqe^B@>f)@=j0c1Z<YR2W$`a)J)r<#L zVZ1Rwd$lc=JDFgae9gKmytwBKJ><SV`zsB*Pl^OTaRQf%!|V}2nwMUE8L}f|2izN0 zDqTJBz`P8~d2mKkKxahV)`^%69l&!TTQ1<xx_|XU>Q35SAbCfBq^|mhIbQqX8r&w+ zCs%G-<Sm5~>BIVWlGo-e&w*^2tORc24lwE7!>y6LWsy&+l-=>-OYG%wq<!z17u%sR zjj(F9<08kSw86NQv#;RZm5$Pit4v*$6d8h)OaAHV!@j|~nT2KV)9=Br&LBTV$t=BK z2;jJ|CMKj2=|~v|z6PD-%Ka2$yh)4&q_KrdmbX>wFJ-g)b#2w!4H<6@pft5i9+qng zh4V?qncin5mK7LW`Qtx<4e$4Q0>9y2d7nNFV#s)c@aGPBW)eztKg}qdfxY@2Tm!NX z)btrQ=sd%oO;m#Q16?|1vAn_+UPMDw;rtjD&MTMWLWY%{H{SG?jEgHzlvf?EjKcZ) z+s}dW2Hc4P>BK&PyNumbI4hfq2;0F@`n)fF`9U^3`%Cz&vJl2rwAHJwzOwz?&;C4P zLnj6_6mUfX3cz$Zot!}`7dm?R<3izH&-b~eDV3@tIRgWb1}(2Lc6h%tHt;w7&;Rc4 z{%`Hi|Lo7PZdNXw-;N$RN?Tac-ul+N+Ry&%&$Vl>xelDTiWZ6>4cn)agZ}B-((##- z*{)dY{fZmT`~xfZb2-i<#koYdKp6A)|3B67N=eVWvl)@Gs{%gpiBGgIJn#TA{Jt3I z9oC?eenea^rytj<eAP<!ePM3~C&FxJ@_zLUx^h+aRyUy@<^=i<<10(Q=}m8<J>Af@ zZr$28G3IceqNB&UecYh?7_x-fzi}9l=kI=TSNqymA8MaPr}fxlkA-ejIxl1Ojyj?b zeBcA^?tAWzBHF#rMwn<_!iqWZF*=G1Eag=YWjQ@GY7}qPE(yhhVPEOU`&aqiv67i+ z!fLv&n%GRpAB~&v-ZvT)kRT4CaDMQA{$~gt`0#~Mi)<BVDz74pKyWGpWaL?{1;fu^ zkoO`zh~#QxPY2jt6?9ZI*_p^Vhp-$~Y3Zr*(>x?%J3kei^I6V!fMpX$#!j^55Y1ce zzO!9-+bwOwm0Q|LIuw<*I*sQRB?>~XR?nt4#?r_MHq$$}zwLN#TQ<i#bl^Zc%*@yc z7?yl~5yD>lmeGN0#Swy{!<H}{JVaqagK*HQbXkMfuG1q-%0;8hH4KtOyF+44*-6iI zDQ<*It;STkc^qM9_G6Um&U^1^AO5?4r)`CST5cPy4a1qHm-fGu2D}%=^6tHR+Cf}^ z9H1PYDtdSA+}S?(p%1m+`RBhAp=8gVeK6UR!KIC9Mp+5|We5{k9SEC>PVw#e<daY0 zfPWiGtHE~JRhO5Q8B3*{*>a#4c)^3pT9-hdK`|Z$c7zoNUEqrJi$0(W6l40qkv3Ga zmcU+k3ywv`Y-z5;*|`fij|A_Vq9i*H>CE^tgzBV9aa!*dFe|q*Gwwc5B1oT{L{STj z3T<{c8JGjBhjhGX(elu61axRzE6^q2MZa|pbhJ!4apX|jy?tBz-lN}Y+rIamHVQpW zQfEt%CS86wgawC{>qa&D98}?}5_$rmUW<8mYZi~vi1-or!Y58_TTZ%oZyWQw^`fF$ zTo;@yTZf*jBgV>$?;fUOT=70Zd$K;rg!*J>bC*r>-A-KP!c2SQd$rk)HhH#FQDNnB zGZiO`XphsRd6*Rd<KSuqR*@&MYJ3K|Izi{Xl1|_DJMO@R_><gQwm~M2tTW4Dx$N9k zMtgWKyuv6v|9`V^rugR_xBcx8wrlRcFC9q)p9nunf(*tObkAc{a+)@@7nd3n6X0$L zx?PE%zF`IyuF!CR4=p;$Wv3Lk2v`9kmNC#|lTm!;9^8+g`?FYNLVqjQ;U<QGoC+uz zq2Q>bsY6AA>O)1^vr#y&#e#J8h#LpW?4`3vseF~!$^S}`Su@Wnu#N4Yig3~lPtuX) zE@h`M!s9}73}9$`(tv}cY(7O?C;t}BgHBJedEn?FCi_@Idh!^S&tq6^L#L*l@<N-0 zm3CeJ*(-W_g)>Q!zYuVwvjS@H#gHek#OfJ3_RoI+tDr>5JAZjs%0dSs<^}9r4Voz8 zfws&)-wp5kZnCBi$ID8`EV?jUjpMVCatR3HG_L}S?WP|rYJChv5SH4>32yCfNT^Eb z;3G9dJ#eKeRE%jku8^10de6|72{zJ>!a4lYNe3s|;4=*TSFGQJ!uh(koXNyNgsdon zQ{VCd(tu`)QiO-RECz7MOEQ@V-xW3$K>F~79nUD7_v}5ylDlK=8Wh@EI0I~86<+C1 z*&qt84k^ixw6$=4_L)*RyE)S4i!Vaqyhc?@VBn`<<0=hE*QTX)o_u>8p7hMq-_Od6 z%dWUQLZ$qBHeHIp&?j*$K<Z6?1fM;H70h8Ke_gq;eghLfSUG92<#KWr%;uweCF#(7 zZDTgA3|fW3Z_ui%sKk-^!ev8W;q&C@Ro~iCJljtAlW(W)NVATv4tVyPR4(RfvXFYT z{GOCW+@|qypEd^!lk~SLn;pOf2HIYf+NRIHbm?KL;!r4kbryay%^7+pkm-?4!j<wG zcmm@&_$*)HQ@RusY1cf6FTFUS227UQBk8DWV_>N(AvZF!-g|s%q)@Op3CYrD{F{!V zbXM^o?dSr_i2$uY-;V$0yKh3_jCET0U9f36l2y<mOqRfRD*mMZ-A6G@V6&Uau3Z%V zC=<AJ;ADAD<7VI+Uw;T0>p<J}+_StBH`G5a5!`r}AczDgkL_<c!$Y9SOt_Jm${bz0 znDI39pz9WC%`DaJ@iKVk4W%mnK<o~90(JNb>|%ttDGLpeP$`qIJrbXfRaUOu`}!)~ zB4hdz9#1kH(p1q^AJ%%ChEBpirKzN57<qRomb0=!nkF0s#itqr)P{kyGkv}fASbR^ z6YFL-{Fb-Oi=1NK;6g<wiY%4u?vb%+<?^;}WVpTc+KbzA`Yn}|D#4P!^v@}OaGas+ z78f|sg?ySXUDZK_R!DzX$SNol!NI+MJ-&QpxuyD`BW10-bK$^2y-GMS0`#eO?^N{q zc_vnupJ}Jx<Z6GRafq9=PC|R9+?<kUdBpJaA(YJ%ZLr(ZVIdR7Dx8-rTN7W`boz09 zbjJ3Se9XHmW6H`sa)9m6Rh$AQe^Qxj``5p2Hr|9bOJS&GbMYsYiz@b2HpdMQSJSbt zU4c*SVO%w=99f>LeRudLKopno>K{kQBtNO6R0fY?MwqSNY2W}Tl$6tL2p_-8*Q{=r zUUdmdB3C<5Ho}9FDkE3*M6NoZiKPk1{s5ueX+V2EN7-x!=3(~TG5cQ1?J2^#HlMj1 zv#RkmgPVPyzW1hYTu*r)Bue}DzQVCkFp5|=OjRK(IG)}c#|=mKW8J*}rNiy1?`~_) z?>v}Q0dCx@FZ_O$NL<%YP<gwPsTw1>5o`H#rqq11EyqxS`|5)POrFJQ|J0qQPpfEl z{8pCk^6ALt)R$K${A^bmxYRR#{!g(7hm*35Nmg&Tysg=INgG+o=AVqWbX%#yIbD|c z5eH1_oje5%@?ak)J*BcijBP<)D<W!z9XH}bd<rtBW1VS`8Q#H*@PnD}RRezOze{<- z+MkY{W5Ey89T`Gd1RVCgPMkXdlQso`EW`-nB^AyOf4Qw)#Rl>iV%&1;%^BAP9`ba8 zKwhL<r#HXpjaN8JDYh~BtE<aY!quUnz*Lmrk9_N!xCZzv6Z-q<2VFTdKQ1hP>2LoX z#^XY&PDa-RD%a&51$|w+<X+_xIqX%w{jjg+nx-7ZG7GNl$I91dvt3c~A9YR(+Q0ml zA8UX3hkuxQlYUl=tZbKEx}|MJp=l%BuwfHExUph|hh25mRaoCME}~zNHl5UwPNYHm zdH2UsE>Xtn4Z!AF&bjiFxu$2hx#H^er1@%L`+mRwZr&>QpLzP(_VB}BZ(sTHSK1@r zd?f8pw=yHFcF_>S2I?M9u9&^(BKmCl31#{0Uj{B$V<6(H{FS)iu$_rpU9MiX<+5xV z=*EFV!*~|paAQk(n{D37l`20EZ_r^%pZc>uYmYwiNPBVTPFxl}4Gj&nb<oGvS6$QY zz^lNmx852BxYqKHWfo#-2>S?sn+Kf;lQiRzjSVTcv{@@^L$3LD-VYg9jB{7Z*dP73 z{@H6j^I=x7*`I&3?kWE(mEk`Q$Ua4I``J%@>g)sm^nZu~Ey^rXmQhPgHeQuoURCJn z<5@)$HIl)MK%~;V0Z`)<VHIOB9iNw@up7j>QVSzH3DZ=eX2+qDO@^?T4N1lsfY^B* zC(JZqR&Tka-E`l*ZR_nfBhazo0*cv57|RlOYo(()f--jZi`#ISvA4bW0@r;ic4|`u zt^M>3rw?YAaMTh<nKT_W<&oQ|Y!($NHtF^<(6uN%A!gtR<MTPncRG9HxqQ{~@}ExI zL=*zVlM04OI&)nvoT1}W*{%S6bo4li(TR2=CjNK)#7|}y&+mQjdn_}4flUDQ?Zt*| zSYbyAjZi6EG6NOG;>l$uZ^Od*H-6(c7%*>aJMc%{JAYSbu;EyCaXXBlg876+2~1vH z64m3{`dAFJ)*{Eax~EY2?|1XEJ{H+A!g;OJ_~8K}>r7l2&SN1KOOmII-LuDA1O%RW zDS{HV|2h9j<&HvBC*%@HJUUycg2<Wv1<Y`sz+zTBn!hxv!d6@>py+-;>n+oj-n>TP zi(sV!MdgJ8i1gt1D0sO#6!+Z#7FY9eH8F^Qw*Y!L_7ckeojclh>HMF1<YAO$W9+<+ zpbi`Zgx5c~3TFkuaq3fg9b=jIB!gJ%s&6;5ap600YMHc1c0$0gP7<6Xed$P;#bMuR zTE70-ysXVpW*Dt6aim+CQ`CbUcCT!%Iv^mSy{}HeK}EGo<EbF`yUKCf!5Hw2Vu?1q zbXhu}ZA{V}!-{<|lRzh-!!hzai=gR%bO1O8Xvar!^)QA4CleKPD%Oel^<^-9>B2IU z1x_g~sp!<1LPwONq$zAaaDWemRqJx*hq&fZ&kFG+K#N!D!g_Wf7Uc{1OUDsrya(^% zb#`9jlP)J|`pvTxD)K&s7Sbi2^%yYtUYSd;zM0olIA8Z;??TyOyZL{~d-EXAuIs+< z_P+P@%=GLFW-tSQ*a>1IL5QSDnWQL4j;JNFN|vpt!nmTym8w)KsfsI=l;Vm~QJlyr z@eeyyE~#uQWyOg_i?m2Wq(}iI0f;2Hf!KlB_ocV#y*r=J_rBND7y_7v1lmmH&HVap z_ub{(bI(2Zd(S<Ww@dJ4H|YYnR_hH0f~+0Aj8oA$O`up_JG6yC#wL_6;tqHUKvMw~ zz9)@<q6{E9I@z>~dbo@q=lLtj;Nh})=Vk^X0x;wkkVap70hN?XX38YUna{Ru*@|0@ zF@R^RIeT2*t3@7}B*f|}yyh8x=<c=sYW2c|jh5OJa}hwrym$~KbWD9Uv>@>{x=9m* zDpv!LDq7hna23mw<pl;Wv#i9Jxy-WLOKgP5uHsD0bijiG&;C?AO<T~}_GuZi9J3*J zbK)5}M#=8hZG!+hT9xojTX#)%$wgB?(Yg%5z=of^WBdWyXunk~Nk`uCvG>N6vthYz ze=5I~r&Ul=;+%c%w}N>2`BECmADrdjHLGT1X=sjRyPT&2ZSW>xFASZt<&$?S;LISy zfgWuoRz%ne3SJ9tX<?UvZ`^4hFQCoXHrybgEbh7K<}%Fck6z?HY*Oi>955d9mTw(+ z3iw-lq^I0xuq*iEB$7VeV+n<Y^Ocz;me?`zdEy)c=Sx^P-x1|5me&rnWkGn#w&SW2 z2ei`9LAQK2kNbjGUw#=`GlQJyFT3~d#bO`#P*ecalc=GI!9&1$!7~6tWZnX@@`dM~ ziw?2>Fn}{)m)1y;v&InKu63XI_`Z!|33IwD6IWO%bQ~SxQhd5?W->-lM4zTTWL}^- z%h4SO`fUIoK}FJsKb_p2XF^W5GEUCAA+dz5I)a0Dcnz8|2IqWr;IDYIJsMAd*AR+) z+EA?z+J6V_(Q=qyIUw(nhbo_H9SMNCiQ`=4sw++8kqSUGGT!)%hhHrNkyYwO*KvR! zz?rl1Q7LVn><80Fn9m$ZJnzhtgJavj@?G%631-tsAEV&&N7;G6e<wdkmGWvSryHyF zE?X7=B;9CA%X!apOvo)EE4o0MM(N|bGz-P><j3!QxV-mnR=F|o?q<>@Z87z11}$Sf z``5NK8-KbT<;eMtY#1mg)CoU(NLks-Ww?TN6PM1Eul@O-F>!Jx`#Ds=nfwAcFU`ZZ z=AQ`cyL6uspYD`VnprM=J4;J$C~Iv$@|@$94uEQDEGp$Q(_OX!HnNJ3^50yg{U?N> z2v3;|>0Le{jOeKof++z3Trp5%<&|}yJDo<>g(UU>`gP`AEP9DchFYavI(UrEg#6$k zK^$}`PdU?9^OB#>c<*W`fQ{+{8=1h$iEfs14`AIqg2m$i{xo}snS>`D>&7<jgw2XS z=(IvTZ^mkGjEV90-+8#~0_f3?zpJs5rR2ar$~i$8(nk*I+q8l)DRF2LI!Y7{fuV+Q zk?l#_7t){-lrU1F`9K<msy;DH8>~{xR1%tc4bbdo#FMY{LT1Q+Ues^>!uBrUtQ=*} zA}n{Y+UM*<N8bvTc?Es2<4UZYy8<{f(LA;rnvGE==&Rw25n8|g3)7jZZOb?HC*YjP zFl12L6F`a+Xu3aCF2&`GX8;4`L%o+L;ZNHo{0rHUaZEyQ*~EBg04rxFu9Y8EUYHFJ zd1L)KawJdW6)45)HF^{O3ab}f1+cu_T{iFDQ#P?8b<cra)MXPF-`G#3RQy?hR$4Yo zC!cE7T=NDG5VxsUR`v_7oBY)4Jjx%rw}xmgYPQz`ti4-%V!qeiT<5Y4nrsr*=HmD5 zPitGtU^9nZ)A!kQbQ{(~LE7wan{VWi37l4+Lznyh_g^XB`1Z?`4cg-}!?A#Xv$EAy zx7La6!M<3-pls5`B(iPQwrSo%D`;a^qOg)btcQThk?mYFCQ(L(FW?RPW97CoEI+UL z#kfemq212TP7;oSk=EV=chNuZD8uXr;n+(+riaQ>CyCslOl}%D!{);256rjuYxp>0 zF=@s>Y17taBpLLRmf2q*GSyIo@h6}0(tg!29s$!6f^W#P{h?*J!q{b*)pYj#n}(5B zyfb|Pvh1hOwy8yE58(WbC;kjSz^wXX|A+?|hmQfYwMR``ALjthcRbiWep}AQZ9gG9 zXT=Tlb-YsBpN2-WOrQ_5@!9k7;ryNNev|RKd+)3S(EDWo=Uy<6E-(`1wUdnMSfQ@8 zY-salnU$_>9lTk%xB6~FaoT55mswQ@8++YOj97Q_$0jBwKZWn+-~YYeD_{NUS7{Hu zWzX)t<<OzSW#8WY<tvYWHNfaT+&O4)_Ti6wq}*`e2KLF)Wf8_(jD^jM?I_q1ydZr% zOs|z~dGIEG(slUWO1s`cyc?puk!>Wt>!tU4?~S(>^9_?wA_+L#?VLJs23kHIf6gaP zo}@jD$1+(gLKkOdbd<fU#22&(c0BF4TAg?QzJ2KY+v5t)mGQpUb%rh}X0X6t<1y+% z(BJ183<~}Sb9=)azFxuJ{F(j4fB)b8x8>VdHe2T}zVuS$=q<P0Qa<>>50#()g<n{6 zvuYiwE6WG-=y&Ev9wEb#XH}-rFCovAJ<@57s9rX8*O1vKIdZ?QUax)MhVz_YZx&#E z;D688YkmCNnGY&V8U%3u+;9DlVF)dWtONz2)`|`&((wWOIRl~~SJ<n##`l*BJr$IJ z2Vp(SbOD+S$F-fU%-T<<YUid9l|gb)0fIrs*@ptApJz7?xq>1y$Ma>ttO0z?e&Ayt zEhFP&EJ<Qn(wTE*7T<!GS@wVAm6!1Wc!qcZ?Ep;%*r3CX$ova3uUP?6REfBZ=AZ&? zr=?!*awY|g%A<g~U|wDFS%rCP5huH}jY;LB1+}E0gEh}~AeLW$c0JIGl*p6HfE_p+ z1EA=gxp=;O{afEEt0SYhvDlq*$Bzzv@U#YXhg>^%fgk}j%OP!Cj(p_kk#fWS8_KW$ z`mdLV9)1|BTEKsVtUT;Dv1;aCkX2BBi2<F@jH3mJwImmiHlGU!dUBWWTFOc{59`AL zgAw;rCw||SU3ydy&kh4RGdPs4Rk`2;%9;CyCrGGjWr?{q;S9!_dkMG7pr+*;(-ORF z;~+W)ppDfq0z#hDO3J(`L=>c2a;%_Gn4bX5q{(NALtZnkl~o5hf*~kHND~J%(M8}* zJEFxNcVs2243I}~$hHkIe)iJ&^1`>jRi1kMF)W^+DIM_sFu?Q>b=!l&;HH6bWg%EW zWD5+M<?D9RM%uS@v$&>hUYr#0+ORDEAU_F8Sl8y+a@mF~lOVBt;V}jHYey~J1VkNh z7`8pEJJa;r(9rS`ukF>iRA^UF7_CPIw##VUNYG6#oq-nMKSRf(FK4Z(1)OIYpfAEJ z9RTy2ak<jT4Eyn8CsR%*E}W>ij0L~>8I*S^qixB<yh{%i(e;PVTiOU@wD;@7cr9O~ z9K>lk!Y4cz)KW>a9Y<lO4a(!vGaU(Glr;fln(vIqG}|Ks8|c%<zy7`Si*G0DBlP1t z6=3P!(%0vQKlb6W8$Y8f9q!o6YXIj?fa1b03Z_g&bzNa&gSlB}^=ac{$U-*%>t;~t zW^cOIprkS^-<Y2ygMk?XZ+K;f$*B1mt=*aQ*y?WbS`SeUCRqes16HSp^qB)V{A|Hn z<J8so7MIStIgqYU7~o|fYx{xsD2uYMv&S?UG+I`X9u9^g;VR224FfhK_cBQ0y;PK5 z{LQtzRb8%F=e8+nO~C<hR@pRg1^K)(H^qtxe60aI+Fn=YIb-!)2g-z_9XqfHA)!NU zkhb!MHt=8)<4*u*-sB(oFe}MU0wj0Io9`{8xePB+N%gEus2?RMF4xY4_MHQl${RIq zf*2bI@zqcBzJ5pe$bViyGwJG4zaeeEfx3dvZu(+=VkrkWmwX$E<@5_^2gzw?RT*k6 zn*%o6ZUC!e2~TjOF>x}f10OBBOq&787Ob1cQPB4s1e8UY9AM+u$lPR&h~X8pAsrlq z3Lw^YrBW(yDf4Mx^o6=^T4n&c$Oddzt}M~cXUoy!XUoac7s{=--^pe|JCjeFl}kXo z$V)&iz7L&AQ&2(6D=nv9e(A*k&b<uk_U_vs3uoN~S#C?_KS>b!Qo71x^fl-nZov5> zRt)axu=n6$tS{We$cZ><YkkRcA%E_PwBB%XgQQvZey|U9bDmpozm?^8o6~ms=~q<7 zYyAoCK-lm+l;*6w)v9n3*F#RS+2^|Cb7;uD0?;Yo{R%p_{37sdU!*=!{in)Hg64ui z=GKe`_@}K_nPghhjslo_Plod^`7w<Q&}gGxyUC6dPwlq?hE<NX@#Rx!Qu8D~Ydxym z&olVVcvEligM$P4f<N_V{>a-JPqqwgwDJ!pWpDa@;~^a)4@g^cZ5_fljm~JX<U#x0 zIX3i}&89xmr%q@nD+N!6(GxY^(gFTozyJN^;k(~ceK^ZQl)-<MEKNSmj|cgkUg%_R zf>K^R%N`tnf3^+%q^1wxy|UE}4d>|FjvjfwJpIJuxLG?-ohYko8(72=ZW;72?FCxR z(|0M??31OxG~|YBRwgN{d@kTj@h!J>*3Ez`fa1%TXQ367;sFl5CrnG{Dg(SF&B*3T zah?#~a2}jne(;jE-U7^)+fC;TWAOB{=}(&aOceaF0u0C5e_Yg`AXWfp+I$A2Jog!O z-wEJM=fEu>7`lN=?0X04OSbRDrN;L7Zthlph6VwI<WY16fv*70=<$Qd5;w4Y2*CN~ zz2mG*WD*<Q)Xb*6a+c5RZv~ub0pW@GH-*lSmHgCSOAc3<dH6SSI(O}#=AA`uKS%_L ziMU9&xl9Dcy%vtVc%A=*O8`DGJ)ZM7?JYs_$aYTs^T3I}Ib3GNy$11jE>8z=9_pAu zhsH%={}?o6EHkzrz<G1cY}yg=nx{tA)t-U~)D4m%*YZ~*OPughpHi0SHXtr<v|wd| zc-gTPJgQD8uiBpy0Gi_djrOfOjh$GiX?3PgPU#)_VO!6SWc|lAQiQVwHmfx!Yu7CS zOp9^JDtTcS$+B(#-ZHj*YuT}z<?w5tQX*(2$pxMT;~DR#y>tP9>)y@{L7hO4AxBMw z&{Er@$%j|TOCDZ*oe=yn_`3JrwlQ#-!)(9Rqm8E(f8JXb<Fd{@Bf^pvA}W^J0?uh} z+-t4vVGYk=VR!M;BpX~ED}Vmj)6fE%P&@q?o;Vf|V6$FYOJVE5jW~Ti0_fYVK@9z~ zd4Od|1AaB~@Q0H$jLqq9s#_pe!k{11CS#bP41-tw$+Mm_R<i$hQY}B+R`E?2z-Av4 zO9u|$U4{UjbnD@s3vSZphSiw_CvVDA0cTx3#9uCjR@N#z)3(FYl{S^H%&dnzK>_#$ z1h?PtzLqTY?7ew3jIU}xhMeJF%7ARPY_s&sPOwzK8KVs4sAYo=_B}N$`V{TsJevl7 z<B2ceGGGXxY_vRh|NZe_TXR(TOM3pW0B7?lUpTptnuDplww~P#*%hnjz%su1bhUCG z1xQto(8uo2{oF4AJnsb0=%>8q*zqDArLtp<c0PaOqxR=-{QfWV#=LLrK(5mtxKVX4 zx{I~#r|L)YtE<e$*v#?xvD4*KfAmM?w|?ulsHZK_^)wi~@4g4hu_MRfFWL*bqhqf} z9(knP_rU$E(jL!VS-OMO|G8L*KP}Z=!3L|u4QPvnTsOZqE;1*tZRDu*fAf&?|9biK z=Aqxh+x6scvb+A#T1<Hd*U{&QGl=&*_Sj?P|M(~W1kV5$%6<3W7n*7e_rL=WlwbOr zzkr^L{zhNocwk_V{(~{(GV*(RhDj#I{6o03Qx?Q1g+6J^RyVS&md)ZKTbSH*{2<<; zL5u$AQ|W7&`m0@7L%;T`e+TgV&uKeD<-~~-aSi*(BR^Gs_Gf=KJg|fD$q+`H%B0J< zZrcn`_2Z&V5PXWgNyNhj2bEie)sK2wPzP6)m0;J@KZL#JNeYl>4bflky@A&1<c$I( zrXQU@8{z4<oZF_qic5_@{q6r5W)Xzbb%7Rx2tsN>zrYG@tugIjw60Oe2<rGg0w<jU z9RX+WqilLjj-rrN35mj^a_V530S@4mic=j(F@O@RLJ`s`c#+1S!rn(mw~9cXMX@<> z3l7Zz0gs(H60mCqi%fSppPZfmNa@5KzzEFJgB6qDwF3beT!CzZV0M=d)img}13K#p zA;2<W%%k_|&R_`7vKCSBb5KUd-wec!LvT^o1NznVKHwhVQx?+J>cN4I9hZ^VvFihG zh1p@Piof)g$IGk7&%}S!p~Hu=^Qw$5NNir6_3eWGZrbFmld~~e!Rk)rFyTM(iBFUd zfAlA+H4S;Q-pr#4q{_UYx!+-{79nE&N$a*ArHkO)0(7;d@oDnjGMVRGbM9lHVf+es z%W59mGRtuKn^iCyw`G+l+VAts=g{Mgj({-aGl#**i$J0LmF2g@*$piOGNrGALtx(W zTBp)zfdM2pO%k<fua$+okuhikFe?Z`d|K=|i|=x_E+-$LcW2))_2v>^{28GJZen26 zPgLE|=;ddhE#H3PtL4<o&zFhw7fTo4_E4;GW?9Xv`O=a89J`ZyNPmCQIRhzp-LqNo zY+abYJR`hi3DCfMzmsl0Q}Og0>2I0676kS?0bO}B3Mg@TZ5=u3VO#=7p^<|E>rW}_ zVLj5W!Vk1DQbFMtxYk!|o%I{QCzAv18Gymb*%^Fc!cVp#1cn=6cHzqA3abpXqIcQf z@nh~xTYaP3_Fb~>gh|Q|&0CA6nt}RP9!j|_Cwbcl;B5HN##|G>9hq(SuL3y7KREPj zCnjt|%DI-`yHSP$1d+D&%xUeN^|0?lf30l2<8B7!Zn@6OWi3=1z!`wl0kl@R^H{gc z&cI)DSf-=!4sLSNg1X`zC?Vg{j`*3jjX-d*8_>mprmH??C!H`rnZi1{4>{KZ;4Ggy z=#WqR%Jfwz+=NN@L0dMD#e!oLz;S5MWoOh0N$GD|%e7^~>jO<^(<<y*Ov4R{Lq+x~ z(CkEwaVKY2&!*XQBG!8*6C*v93Gy&JnSnEH4~3u6DZZSwdIoF;a9+AHS(dSSUUafZ z0Ga`lz+`^PZ~-0Lg0!Km=25pLE5u3RleUe5>XUq2p@LWkzD%1?GVxTp@N4CgeVlxh zff4T|xpCyo*U~clU|E`XIXCZW{C=a#<JmkA5ACU58;Acq8>Z%ol5nkjtj~-y)`<a~ zn}iH4?fJwNHPXF38%=G-wq@e5^0anAel8HlGJRVIZdbH!-roF1TnbA&l|BS)vhIM- zzFAO|z7Ja0c14=V0w<WAgqugUsW7^{ZjQ-I0q4o71pwzW<;2PJ<(50{!rEac;mJ?< z0GUR<Y^P>aT6pOMh#=G)vi0ScUW)QB;Jjzw4XpARNA6|>l{EP}`LrFhb-)w&1JD;) z|KfAclMeysn^-k9Rsm;;#bJF``s9}4THso20p}|y$*;cpN&x3O-+5<1V}WK@xHt(Z zuX&hfE5LT&&7e;CsqearxVV~Pb7L)?_X(~r5Deg~?g0OrUkaUgt^&^RHs1>jO}XJN z{jPkh)tdcU)uH^ZPLeAJ!#nc4d}_NiPJS8#2qZ-|v2m#WkbM=o6S~7MfQ6yIk9iqB z=N!H?kI4C4H_r@fU0dhMjzrhQrA3`CvnWvQXP~dNFszJ}&6Yzm=<b>Lt*2NL!4Jwa z2Q2nAl2lnMuwnhpqQ7a~oaLL22nnIw8g%z9{8z3blRk9c`v5Ana0YaVg)@0K9{+HJ zSL!7sz-J&h=F9>X&S&YXoH*lIj3S!8&@8(8M8D17VNn0V_rJ}`GBz|Nj`;2-z>>fn z?IE%OTFsI70M5Rn>@aIG;ADcEBTCB(IM+;BW+KS*YJgBFYCXpKF16canv~;OhjuL3 zOl>7EP4TD?>#By8CyjdTFw>EPa!YP<7PPA}P(En*!`C)Zf7FXd-qBi>9U}ahuz=s? ztr`$sLI+!g|2vf{0tG``_+jmcU)Mn<Gy53GsiOtlqz$;whBT_agW)y$=N=O6hyM58 zdZ^re)84Xc>n7@67b+H}@?`)v;xX-B^6Vsp;DqjiTEDF=Pbc&FHdm>OfLDpFK100b zInmcMr$$6j?&eiX*mYrevld>ew!}wTLTUqg*goqK8AV<^3qCHev$U(;b*-^VU)PI~ z!$9Xu8SG&Xn?WY(q2bWjLH2ZI08A9-Q~t@3x^^;(w7AZX7pA7062UXUz)Y&clhRq= z=*ksc3dpyHiyX2Jc)r534vcUFbRAm_Gsf6~ycO_qLRy+ux{?vmQV!d0e)5$6`PIA{ z*8K8ET9EHm^I;y4t=*$+Hhuuh!);7*V?k=MQnGxb1fl8h)13xgO5TG7C2w{gN}gD* zn<$5Atv}bh*Z&)qHnHX#LwTF@y;*m(<X-n^LzjMMcbj-QO9C+o>rcShYk3Sd26UE& zm84x1Twd}!HyXS=IYS?GvV88dkF#ka{R*ox2HEeYwQ$y2u<D*wj(6HOQCBf2LT|U< zRPHHDjah!NZ;hq9fO9(ufqbfCiK_q07nx8+h%Aw3$FTNG_6M2tqb?0^c?L(ev3h80 z*}MN{#x?kCN5{{8M~t&w5fm3+(t<23YvIh&`32&#jOr_?TnJQor}CKek(YT3-$M@x z%Dt{%l()9wDif@GLK>bwZTql4ZFO|RDHlA?3Ru!Ml)Gar<?pt?;<<ECe=&^X@qWgs z=gu52-~8&M(6Sf6d8EAi-R}kzYbJll8EnX3jC-K*oj(L0&Q1tOA3;~gEpdwlhT!;T z0=+_?=T~sy`2FX;TmJA5{~#_lESGK#KK8MnEQb%>!k7wInYcJpf3JXZs7TJQf4oM9 zUO)JTLTofn=_-h4na#2CObc%7+5WRm>^p{E4FLM}uYbLK{&SxLO#CW9;bgh(*4yLa zLH*QmpE~OU4?bAl@s3--e#X$xSoLM&;}H8ef9^cvo&Iv;jfb+q-7vi2<Vf3BB;XtU zkx6A^{%z!FdGyV~T7Lh(?ML#tF6wnzeob;bw=Gy-j&bEf@uWvT|7dygi6^r0pW|Ei z=eqSBx0avznU9xy-}Nr|&2eX?TQBWDVuwPgCI~b;Q6FPD;&i2|xP*pUuFMb<@Y->* z{YJ(|ZzB<uCx7Q}|E==qqn`~X<$h&9{nLM=+>Re<b=g;s9L4R*&E<|e?f^Ht34R+T zKNYi+4=wNDVBMdLY|}5oqsR(*(%P>-uh(5QL|sSbtM6Y!@H}4QpuD>FqZ;H#^6y4? z`YmT1xi1|6oOP-3Kcz9cOjD+`VJZlnf%00*QjfY}oU<KlctM5v;{(F-gRx|0JFeD> z)3{_f2OSPZJ$&Ys4Zu3EgEb7@NPzD6K87Ls^cjc3Yj|h2v|gOWB2LTRZkHkff={!- zfrFxc7^f3$ySrl~!bj#)V3;QXFY}avG}f|OgS9)lJDAWdf*r6s18a$`Rc91uS{F%& znay7dw9YVSY#W++7ih6S4p8HE1EJVWr{X*5Bd{yjJPCj|M_#}6o$un`5Z4!U<}OJ% zc<?|PsFqV_&Yp=o36~iQvbu@io;`bLIEUl2NQdYyW!Q_Q^A!ZIN35AiN6Y0pVIZwg zFvym^pDnxKpZQOHky$O8?DQ<3jWhWqoHR~Z86=p0<MUl*KtaB_wYZWvG;asm@`<x& zX{uaXzx?61uBD~!t^Imbl}Z1^Rmre}<<pc!AW?y(nLwp8`J=uvGf$qZyC_KtJqyAi zuXq@~@{MW)sXz?B%U}l6f_^NOdvKAV<&N$`RGu@bg4U~#PPHi&xnTs<AU`)id-|(i zEPwi$&z7mPbY^h#&duY@oHH1w-XURG>aJk1>6<U<7FtSs_$M?Zd*K(tv>>wKE5D&s zQI>#)d}E#Y{0d-)ZBc&irhQsA>(xUZiElRO91u58p#$`E!0Y#|+YP~KE!;qjBSCFb z@+n1S)>!}QtSaC)00<)(BDg&xI0)}9QoeZ<1N}K)K}lT!=o(@<tu0xAd7OdF-o1OU z96MUR`@QcnSgmEAWQmS^ARxc~kS>t})YnD<XTO)Grs?;Y9VhO;EZ{7oYK2zi5Y&ZF z<+t!HX_>|V`Lj*iz!Od$=ec!b*qeUx!(|s8a|aU|g0-Ei0P<KScQVqT1%&@s>6m9O z&tR#{CV<QiZ`qBd*Z3%50b=Ngvw2{IanspR*WqJaVCaw0&C)KPbI{pUw(QypfXLwA zQ5y0x;AGo&ND*qLEp(G_m(C6`NYVHBKp%s7toz(N(8&lD*VU%2E|U*IFd0E*I7%UW z8Xy23v2EI{(z0xvQX}`)L_O^M2^J8_b}7&#D5Ld4@=4rUpLBYLE|C(8@Ww1Ikmhi^ zkssF2465BJJ>WBObRdtQJTxMIoa1NJilZF<{FndGF<BG9=L_4KK!9iSrF`%@ZII{f zfTcb&W}>N4<$GySX;PoJBCLWrwbW9({XX9|@mH`^xoCQXAx3i0#Bbl42YKhFQK5$E z`GRkZU7Guo_mrvDg*5l2vL-iJajvp-o|a#(aNRk`a`!FU%3k`4o%9d-Wbb8i$ae0; zS_>$eFJ-ohWF}jY3Cel1r7SbNGDaV^E^qgDh5Z0#*yw0#da)eErN)U<=gZ-D++McR z7xiFiD~$!ffFwB+lbKvsmR0I<9yxa8)mJhg=tbV_+O>xj6KwdJ63a`Jk!U=mtFd`D z?pX8zQa=Cv)`v5IGk~vcU(mMwMw+$P4Ve>%K=1UW2`rpnVQ_c3yz^c60G4k{8%~-1 z2-%XOA+#V|J0a=B`}y-{+2HPSHda0ijmKF&PWHl+%5Bpl$KfS?^T)?;$^aed4^AFG z2EaL$`V?s2#Dq}th*d3&Px93YEqyNWd9V8pX&^8jKYBdVil+y_S)gBeUV*RL_S62M z$6Cwe+ci3vNBTCw2fuR=Z#e0fzJu~s9!X`U4&4aVzC@Xq{)B$Aom94OvBYwCChoY` zrGomK)nH%lz)+pSqkfMp#66avy%Waryt!5G^wDRyU&1P~bGd7&ybtT<2XA{YE;SsG zMmGSBKytq@E#gWJX<PL|3DZ?B;H_tRwxgW5ggkR#OFne}l(s^hYH2^aFpWEni{&Z& zH=jLu6xqXuQ}BKTjRi~rFEl+QUxF#KYyg)D8Ojn+n(~m5gsbwU(y_L6@<AVIeEi`* zeG6@@@-nn0<7;&hE(uw9So?MZ2(l=P64JV}j2vlB5mH<WP&>9ZLSsx2Yk}HN8a}X1 zL{M-xiCT}+!nkTntAMk#a+$VmUVYgB0@5z`kN;-+iViI6`ZtXOGH(WO-p@548LO`B zr<C!vtdtiX2=ED=+>|*x$-`HN_wFhW+<vee+_^3C-#)_nH2?Bb<Q;JdPCLovV0NB! zM4|<tNYc?mo=MTY_Iv5nT(@BoprxH*5<(tIK>jp`^lIWYwtCd_+H>+53;x%<l|`s4 z<)*wsJ!@4D%LH)NB~{Prd>QNlSb+rxN493nGO%ecM&s&2<e5UOrIEC4k4--r09yL! z9$*fdsGBiKgB%l}i|Y(!jBO6US(jKVo@r}N`d9}}Aa|37E`tP{-7L`6PWC6!Y2X7$ zo<FvGud7a0xx?c6tWpEM;U@W&UX)p#d6AV0w)w%WJIk&c_oLTr#y>Pb65p=<xKOf! zH3x8pR5|*YL=xv#R>-%UlAa%WonT%xNAkx*pZoLPqveHq_k-W9Rc{-B^XolZ_xg1& zo90*3C++Yi8JVMCmd)%0a8_P&ld_r7S`u^)$75G;Np-e->R*4JajZriD`jAmO?^S% z)hQiUD~nyhVxRA|Kw1y|xH@z{ZO&D|YqE#7x8#I<WUu<7;IllT)v|yq<0XE|Uinnf z6yTN%$3w1O($GXhC&%o){kWUhy1R^S-j3VG-J}aZgPyA^B7gcob>)>bH$Hv!&tl<h znzlmgr0tK^6Hzj>lU)+3@;&W_?~*qv#AjFAgVZ#U8rD3wdbv7_dZ71p#kKNh1s~3C zj(zpHZf6YR*nWTvpTolWTVMMk0DpG?=LZFxSy}868ARqyHGuO5eK^}DHg-UJ=uOk( zhuozeY;*RjN@M$Z>8dP!@ug?WKmNy`1aM}21uu=@678Xf9xiv?bq_lIC}Gs?F$!W* zPP%M34;#%YIjWS{K*=^7Cjn&w`y}ewelkXjJXFt?jOt73Igat%Ebzq_Uc|-7OWBi) zY7EV^QayY2Tz<9<$Do_ogK7&a&Nfq*W8f){N1yrL_u$o@vJ2OvH{N(Kz~jM#2hzUm z=cK!Rj(s8BbX;x@54nmTFdSV~o|m70<c~Muzt>bv+7TlK${jgQ+qL{>PM<ALJ@sVy z;upTi>I?Qy<EJZ)yY9TR{NgYEVz8%Ji6cKUCV<~UKV-M<Jh~lu@R@+K?X4Xji@SN9 zz6Kq~I?OEV+eXw?Hkth2%fI>5zb?-`_Z)3#vHbXt|9Jd;TZRjGK#-3|ahtPq$1cVj zyJG>p1vi7P7?;n^V?b!$x9Wa!2iPF0s{A1EtZb1nHNJJCZI1S)e$<XJ4AU@mN)&E+ z4bf{seV)e&P@lbBe>dFrN${#{eY;YBEAh02r;pHw^Jo5t-wdccf~yCa#%1y?_#)HP z%y!`a@N$^QrSus<&^WCW8^2)$KRw%dIvej<AkPj7R!<Jo2}Jk`f&iZI^O(abzzt*E zt=)}BsM<21qDu#>n+-eD4CG{Ll(s>H%^U-@*~Kf|lMQ6|aQ`@hSa61c5yH##O}ky< zj|$9?7%-cT-2tt_$@lXJd>Ly1rL2c{b-;)qgc<GN6hd~$#$zWr&{%v2cqWWAka7Ld zHVLbrLX<?oY>K^y+5b@nsQYiak==@qmM0(kTHT!;S_u@7<9L0?Zv4A3o4k|r{u^${ zW&yi*?ZT33GZqS1Cos5oDa7ehr%_;s%QW=00hk{df)0*B002M$Nkl<ZPr6Eb<IB=n zG#qFC%!ltRr$-e6HXMF@$0xiK9CARKq9k1YH0APLU82O`m%5J7Liltu@U0-R%8c*4 zugq;{s8*(8(jI>I+C~D+Si&WMYQFSYZC*`7zR~aW5_LQ|HJRt;!}27*DBjjjT$+$X z(rc2Er>u*rNWfcw9V%BmBpvyUN?~HaEIOc6MRrg-htke0M<ypMh*n9!DNKH#+)T5S z{FS5SnWw%{o__pmWrczBCIs8IF*es@KyYQ15if^Ip@P`B+rhf^<iN;5wgU&tXa1}c zdDJ6i1MoHPDxQKV=g*&yAPxA=^A!|6>ErIOb{^8JwS3d!UY?i!sc(4|X0)BE+!*gX z=`YbxtSf0yeQE((!7DDUw~jZ#gM&`I&?cs7&&w!6y49FNA+Q`Pw7pdZ@-AnyE^G^} zqCCmcFs<139ykzLppSA7+wQeT%L}O^>uOy9$BO3Aa>&#5XGh?mtnzRyYPpx*D&@)> z2V=Hl%Vt^RZ{rUjWPPe(v<LT5c%_ADkd`h*1bS4ct)F4yvct6FQekwNmi*=fob){S z$cM_#`|cquG!Ed*<O$Y!9r`dfqvX$l+4Q9;fDWuAFVACrx{D22wvsmiXL9NUn1BGm z{hPr)`CeIp_VA-_HO`)7DL<PIZr#0|Nd~N(X?KJmY*ieTWfZ}$`DdI=62fC{jJb*B zM!i}@A|JJgmfx~0&2|jWFEd!p;Gb_STNGmAh@4PH5GIESB!|+brbIS#IG`8I7RXh> zcQ9ic5Ljpd2{ULIH)w;T3^I{lE7R~VAaj1SQ2=M%+APsVw1kc|G&ER-|D**(AqzGv zDMgw2=YJ2u``r3SxkEVXRBLfE%)QU}@vH?4TA+v+>o-Qk_r`60JvHp%8xGURTV8Qa zIyI<ojX!bI=GxhEzxSJ@;iUm{KzsV43OJjVZ<_jR_*OcH*3!G7bqwMOxq@{RGdqYe zR?_qiGw5eG`Q3Z5G-Cq~6zu`(-MTbEdCItJxoaJzT>Qydx)_4?(Y8z5o))MJtbv}! zh1JxQa(EH2`9e8$=3?1@@DR%xx6_w0(1XU1IPEPYN}AR)@|mBO`tw*k9C`KCSh%{n zWan-GXOzFBY~rTRuen@1OKsb_8_+%f>~pc4IB?TCml_R!O1`#lNj)b<$%^twKR9#o zayfSVX!?>n@6sK}Hu_5FC(TV%UJ1Q<Vqu^~9#fYBljqN!!`kLj0Oy--zL_Pi<9T1x zvJ{p7T`42)$MRFUGN2N0K6d2QSUF1*EyLZERhG4_y8OQdEA7Vw@RW59n&o5L%w=4G z2z;l17(_<1Ns^NR_8ZFini***6*-c&C5TiZPqZQ0y5Wp7>G0O@wsm>Ma`RbpK>5&t zx?N*F`+0er@5!H!{be~nve(rKu9#6eRT&_N%X9uIKh5tfeBjbe>20~x88me0N7nWS za3&mX2;P0`{pH@9?~8?V+_FfQ{4>w|%x5ydL>CC`xk;>cuyQ^<At+7`;CWrDHDZA@ z*dX_!8#7-hPk!ak%k<?7<i|l0=?Ths<~}Bv^oQyTv*;eyWo<W{)uAAe{n;9rO#Q|Z zm;5N}(zlXVWq;d$K{39&+V?;`%3uNf$!GQ2azUxwrT#Rl<gnXHy-*m9_yRcRjV}|T zxvSxgv;OM6fO8@tqFSZ$1iBj9O$D4AeNa6`S)m-zvRQW;PFnTivTZZ%1xwbU9ec2J z9!B>=58$7&`89yEG^MVyp&VpzLU|9a93H&mCV=N1=uB>wES-3%9H$PgM%&>41ASLp z*>B9ELmQ-Syh{G%XG&#zQ<z#ZpV)pp!X3?Zn8S+asI9nuyT%N8!=FT3zt2sc*ZZX7 zJ#|@E*>G7CZ9>(ypa6A=t{Vq3M~9w-VFvs}NpL9w5H<iX0^MRHGrWzC)fEEfCyA%* z-lspO6j`-ICD;B-ebIe8*c_d<?;to9q3~o}Q7LB}=*xHXj}>s1H=O`SpFx)$!D@C0 zeR72UV3h078#!lLB058V>)&Eo7Z$S8ZVe=Co>$tFZ~G1ES-@GHb_AZ-a|pnhJtIc3 zCX|9}KQ07Y)c_Zulh>vz;B1n1&uPo1y6&3WN^dVX+IMZd$)?YJu<poh&3>M?EU_*~ zZA<GPY~Y%zT|4Z9!<#&rr$Ek8nIFhqdMTV`sy(isShw;g#u-eSo<4KF{6ByAZ<+X< z!>{uKlQ&xcbDc!QrJY7L$Sfyu)oGQD%I0o#`{-@FcLKqBh&-j9)t}Pd-~-1K>a?EK z!<A|FE0Isi4eO1ceUg2KvRNY&`&R**Atsf!ZrfW%x1dXG9S`tk`s)E_`v}WpT*~t~ z_9$^YW;s2~TdVujHq=y*6~%}7HX-2)@~J*%xRi-F>(Pd)&)fG2W8c-t)&S1PV&fPE zaPDjX=ZxQJE6N!AxdG&#E;YWzrh$X3_8Y}t@B?frwhe<WE6y@ytU%)G#v9!<u*xp; zdcDJP$p`-YD-Hdw`6&nC5SjVNk(bKve)1nNrgG(pd+qd>TW-F!y!XBD0~p&*xNgRM zLtr%aOM=*K|8c!MZ0vn){~HUt@lcl2*6z8bg<spMDqZrN@<*qp-W-d`pA%R(p91sn zcMfB(GiT4@KH(%*xu?nmc$AYRj;H<Y*}ErWwByH5Fb-oJj~*}vAbsPZL(uS+a`50m zfXAJ2$5toaYCD$q2hpkK&~?Rn#9_#Z8T`>cA{4J?QR-fM*z9s}4*1KBZ9l6O_~7V~ z6Xo&8A1_Zn`6NI-MiuOnHb{T*8~@pF#5!24PhC_U-}YyFsRl5P9cw?8_?v{<<Z7br zUlNM`^LjaK!@RY#t?2vDey@Dt3y-qV=I62(+Bo}496o$FmhD<uzxwj4Y`}Suh~03K z$%lhC#!_AbIgRz6`QG=DlZ$zGkatd4*tYsuX{StG-@es(mC2G^F{NIpZWESnvi_Q~ zH%0YXE?@KVt(EnSLcf)^n!0<Vi2hwXhd-o40O!yC=5IpG3i8EbmP!yra)wiDO_hoa zP++(WA{&s*%2MDt2+E+40g{KEl*ADHbT+{bz=2V~K`V^P6GSs!g{t79mN6>wS&~mW z4rBvxaV@ar?%};`x+U17slW1TS)Y3_y$YECQ$N-imLs47=?&qZ*3IAq-2^qK5hmRz z%OlJxcW6z4a!d9D#&lz?D_}RlnBy`4=LH6MlPocq1_YVFwSd;0GbnvqP`(vjDhTHQ z1RY=sYQ(1+X$}r<V%BZEjBnpo#&NJdjEe&OO}gQmO#bxK-zZN!{<(4y-#PlV(f!8u zJ$uT3{$KxB<?vm%vy1g0yGf7XvVgpI;;KOq5=7ml%@bH@U1a7aLlS5po&B}oWea3l z2U<zD0B!1&&fU7RUK~JmI%+`()B&r4qjv6on}d3C=H1yom0at<x~ia*15@aQGE)by zb`*A)4o+(aXdOfLG*0VC`ECBRBCnk-kD9t|l_}5ij6kYNllh*&Z>HaSZwDkFCJnwd zZ-ZE^Ly4rXP`I{X$>j4`!h1w{5}4(o@tH^I(am6?&6DALzW!K(H_(vrJ^-Bnn!ok< zSIRfP^rdo)nbdJW@!bfp(#NuG@~fif&hK5c38Rre6z~k~Du_lLy>zD5g_{|+LPI~@ zz<uz~5Ot3)a?0tl7t5%noteG}NEs_E;_Ousq&{G7zN$c;7*u@AsZ^#+)SsXfgGh7} z-Z2;fJhyyR@uUv<Mjo&&OOxvRirHS;tk0yGGN8Tgq}?u4kJHr4EIiSJ<wX>52)01` za(VN}*!I-NX*Rl)FIv8|J|hRHXX~^M&g&$G(nvlFSi?1=rPN8ScjXT}Yi66nO^F2E zl^xc*)<0T-WI#q(-88@qX&bf=%N(914zK;j5rQs!90d(iC&S39Rg`G`MB4f2FFBwH zWimHI48D<UaW$jjzxiW7R)+4oEn$KJ;P!%Dqxiumq!YiL$~2Uw3+z&U`pk6MzHbk^ ze`8(A^6m`i82MR^7EOyb{b~#Rtt>l9g3=64PaOs5V$;FRbehiU3(Ul21&Xwtf0fO~ zLHnl66p+Y}vDDKR!n=%C(8j^6%W0ME%4|E(6_<t^zBz0Mb`8?jy084HY^Y(Z19?}P zw!B*h%kn)kg`b02>8r~I`AD9%UIMQ1&Ny@#(%o&^y3&AV$nsUnyGp$+QkRQZJ-ciA z0>63W?*apF{iAkgP-0#j!dXspt1RLX*D9=*-7-0_T7^EVlrwUQXW@O`%TMwH|8p%b zh73HYgAWxfqcqN|)Pc%8tMAt0@IB=s8#ONYNkA%b^1WF~*e06LjY_Zbv6VcWWdbAO zTtQE-+mGs5*EW<2+CoEQUmyL==vF2%cJIfs`C!=$m^r*jpP_VY92sObc~K6<y4!*! zV#<;D{Zsn|zp)@tFY>@8oRjz<pPWDzvoh!OnM>u&xrwq33#c(H1DtSDd3A8yOMhj@ zY`NtffBFyA!dV~AM_xUW6+C^kvt4^|O9ANWijtPMOu1&K%~!owPgp=czNAYH`q3M1 zI)H_<?GsQeH1kW3T8`9NeUSRo|MQiL6AW5TW>emq-*Iy$dG(uU<;a(QV}6xYo~4Uc zH}Z?J<pO}S100uZ9zJ|i+<~ORNx#z2@br_)f4+sos@^0xg#0{l>}V{U&F?mL`W|CB zulhzO^0}*{T0I({lqWNxi56;tdGhjczQ2qGiZX69{th>9VIp6^nKohDl7<<q`K{mB zSIM~Co1Zy!Bq!FZESA@NWqR^^GvKZdc~Xx$8Dc>CPTIRJ&+6(OfLB#8cvvoT;NSW; z?$Hec|6FFR?2eCc(utnIef-cu4?!6x#q^=Adk`nl`swRdkPBKk-+Sm?<(|X$vO>e< z!?w4Y*Q+3y<uY{uJ~k~oGlAa53X%(0<GZ1fz^P?TSxBp|zY`ze-)GMcRxAC*lK^HK zN7y%`KL#|V#;k8>DjlWk0vl2-*=Ise+fHkZXBf*SZPS-nXB>+lj{YM8x_}07CI@f= z3}Ietek;GLd)Ufscf2C5986Z$gL@du$7H|x!`a6?Q3m<XZ{;bg&J7!3<~$cr&PP0V ztVb`)Z5=RmnT8**!UC>uo=Y#@)BhL_1tzXE+_bs7ZxfpY?ks(qFn-v+lY1vt?RO}f zeZFOd&%Jh|?C_ql9KJR0n~)Lr-+psBynjzQyn7oixmd*lJ$+}rT25tdpA!yzW1U<H zkfjW#FR>()%Y)Z`lrl<dv2>4C7F*K%YZ|4+Oe6^f-8?tnw0@qw)vd{zB{L69*CY9} zP7^EnXr6mcUqXg5VNXRYlI9$G*A)n^ZZ?Siuw`U0n=oZFRtCYu(8QV8{X^NQofJf# zkYD6M=*c9}EX(Y*a(2S4ZF|zX>VeQ*n!}3$o;l|^{hna+Cam_hqQ|JyMXyVHfOb~B z|7g?RWU`5K%SW}$SM!&!O}^8wQdV82s5>c}$Mzm5dv8>pv)L5>ekD<D5%o;>6D#1> z?=hsQfHOq4MVOoXHDC3z-Z!-Nrm4<6U;iidLAW+(8?KF~t;hA>TzkEdFzq*{6MeTy z(=stPk`h=hU1})XY<=xvUd)&N>n~iG1aSUij7cUKKjIRSO(c8Z3-=RpQ*I5t?AKh) z*y>=8i`u@aN6P_tH4|jkyJK$UyfUA9cl?o60_ew%A=JZoL!0DBUZW5AOkUv|#~r%+ z@V6EJ?Avw%IFD_Ov5#r0=Q##(yc_udUkR7W`<XzbZ*|-*&&W=-Jrkepf@k$#%MI{4 zgpl5lgZH%@(#iN<QxE2~sa!&(g8int?t%XZuS-Sw-w#KI8CSAzh|gV#yQBqh;$%#Y zNITDF@J~O9zgH$6M={uX;N1_Do%F+DIC-DSGkyW*yEbUy?6<GgKP<@)9>!|{pc-do zkQDT3{YAD>R^J~#d8GXFfByT_hZ9Hueb9Rgt7(7gk^i9V+PyE#=L$vp8fj}E?D_3F zHd3Cqo|fgbrF%B7meoUg)ce|RQ4)EEy4Omz2R8=>p-VxoHGKiPj)rto7&je7Cwltn zr^^?=_{H-4^Ur64#lwKh8t2Kkf~UGNQ!n%SgCG20tY8n^aDaB<I9!8A_!$~bPdC^V zePAav-v~`>8B&mc=YOi4BL{DgiS>`uj2hZozv@%A)dlveu-|pn*(X2w$@oD&!<b!t z?(hA^-z#_Ac?TB4qtpiz0N^$;#^PJ`D*K|e8NRm;YkpqKhwWW>{cQ%EO|u`L%g2u& zk3Z@^{x^SIp25J)Iz4#cAiS_6F8q!iI}sjmRlDy5r4QYRi?6%i8O!M7$Bu_T4jw#M z?s?}u<<2{AFNY4@$oF89(CE_TrSOg`8kJ{aQ0jh`t<|O5a;|5BJPU1_r+mA<PS%J0 zOJA>#|9X*-{=d&dS#J63rh)(9A7p0L*&T&+8X~})Ap{!zdDsEj8G884L5Qv>BG~yZ z3JmY6puakRGrVyMTKUe3QlMyduW~8)tgVrjGJ?7So%)`%qtr?`ewYzL{p^%&`cZC) zN56l@7yo8_XUAj%ndjR4xy(Y~)&}K3aR6{vFt3*-DOzc+2s)#@`Tf*1n*t%o&dvh# zVc~s|!DZZFKoc!I<A<62j4{Z+<)&K#D93Wz#!H7x%Z-rJf9epO)`-4Sp^ZTLG_D1X zW7+I-x8ui;mNOTQ@tkmgiw<OZ$>UFb{AbJ0{qirB-G>jAW#XEqGo1u*oJAoRWLf+Y z3dAIUv)0~%>N;c%FhU*V4D-oTDg`blu{*MXNONi7St0Bp%{$PV)|3zL`M!N`n6M`; z&N`OH@`mB%0r^5uLBP3c2~|AXS>!!uXAK=v5G<XD3X9gLS~Il(wCOk*;cVuJf(->^ z6f65-6oOOCU|zr)X^z2NfNsjHTL_u9^%bNd)-KyLkN(Vq=k>=TV3p6zo4n^C4G2n^ z5x`uumNHl0g#rn?#9&|%D^~eu7Z&GTDB4dy_LcIPfAz1*$(LUSXkjLG1RvM(D)nTU zRU$3FX&93Oh}ywQKIwweM;@}I8#+6o(!uV-$`A)9S`9b=c1e|OM`1rfdx=8Iy&EmK zF^D@y2h<_a8LS;<`A&6afXSAsm}n_S+&mRv)Y8o(ieawo%w4|SfXeW4>X0wYxjbP$ z<x{T(QdLe<hunA4R-J5#bmrX@lQi@CmbKjck-h@#rjaF~@*3YPa#m3_?kc#6oAC0i zyt@ReN(-qaUr49auTOX`IPZ}>aki6`ALMftj1CkE0UN;>(~!Tfrb7zw!vH*K`|KfZ zEr0}^J1JWq^xp(OcA~)RztIl6n{b1aqr*um(z9I*e)I!n;Qrfbe}<v%R<szy;z-Fw z53B;&Nj?_vUwaY2`S^(mHrCluwy+VZK9z|gEYS|8DJBDXc$xwK@-jZb0bvELPaeU4 zEEWwTTirE$7(a9X-|%F<BaVO}(5)_Kx28jU(ni)o1Ho~@H8)Zftkz$gOW5Tb>0;}3 z03+>;%fmsav`rQGfXsO>Zv?<jd#vA^55W`u<Yx@Z2YE!k%~EUfVq6wE<>njRA-UPB zKLRnB5WIlzSus$TW<$$>)l66dM6bgCFcEPBV8h2+bya_rd`~?)=*o}0YCmkA-BimO ztDw9xqPF|13ME&NE8sABR>pD5H}akLTpOTjRJ>W&rhV_Xd0(&BzDZp5UE($h|3M>Z zZeO{|5<cS(a3-y(cawpdq;DSlq9*M(JjUNVlT{8-QJ@B}oEyd}X$u3zE!%csHM@gB zD~b~G!LWWEIm6(jwgd0^@!Yh`Lj|Vg0n($6$TnrNeF!26XyAMD;!J)MILbYF>S93W zt?=;(n+oaQ(Kap*=qFFUCt`DLM8pFRax0i~iOEvsj66P!obRWPXH*@Au(c$f(4q3A zd9rV7GFOhhawIy#u7i8iU#K^<bTLf$mG4vdhR)_;0exT!pz*?mbNT+jjaY$Wq3pya z*(Q(Vvyl<f#QxQEZU53lxpfZf4_#uo%IF4GAZ^zFW9o#wnnlvd1dDRg0&`?f2KYIE z^U=no2JJ_{S?g~7b6VHSfK<vRq9G1-BzTuM0{Qk!-oO0fi}52pLf^QRZ#T2)VFiDz zGh?yT(%UvASmoebUYC<rkw52Sp>2QSDhW3aOMMf@HdMd!Tfc!QX$Qt=9-u9;NE2nL z@yR!Jz(F~okGhTdkr<FI`hu2j@>AQ_2~I6$5{=1k;<69ZhjvFMpPXZa9(2#E_;G&V zrhCh~1e~$-a<VM?h8bCRRM`c<w<zEYp8_~f%`2zWQQ+;IYc+NDt(0$J#Up6{5(5+E zisjJ#!6K{cQfA6#`7DQh)8dkw^jaU>Q?JTKNuw*Kl$Y-V>eyb0ZAmA-UP%Y&Xua6l zD&TC!Yb{BWD)W8M7m3s>j+D`B(=vQLWHk@NX5+vxUFE&-A@2~UwW5*?G-%SJ;;0tE zcc0lOBi)Ela5)yvJXapL;dKS2xu=bGFb3#ie~a#cu`-B!iG?$(@w%upCzc~40@hRa z^zX5Bhi=LZ5XsO{{&S-Co?CA!H}2bA?!Ng300Y4k@*sUuc9JE}T2h7}kZ&4m&^3_3 zFnPg=b8hR^+H>1*n5_m`3nK~E$k>oLX%bGrxp_nw>DmUUk$7j=gz_E#t)Be2v3*&` zf_egvs0LU!cNKQD$YjbeeeO04PKGfeiQXv^*~IC&N_pyo$22EsKpyNzBX^)Dyg7vn zAXho*k|=<4)3#mN7NB4H)7GoLXdmh-16O;Z!(gqo8Nk_9U+Ue|YAvUA&%fG+YdbbK z;fZzmOM%U3Li4S(2yatn#wXd_5&eAYfkPE=-ZDx$Rlk;Y9-iq!;%-D5d0^aJeI0X4 ztUNI{{N+!*Gn7xS9&2@Y^-;Yt4t{>;ul;E4+dQm6+rR6>`OK=_=wVRAbxn)w)Hyn% z&rP%4G|+W+>ksi3-5^X{#&_yxzR39IOgVb=6k|QWW%~18bk70!L><;iMFHqcQe@0h z0cYzg-J7yOxlLVXg@FQBxy?^Nq`IZ4yqW%<0!sRnle{X=lyj~mP;ZV5V1j9U=YA}l zF>0W1c2%twk<s~R?*X03Tb@zU$aK=Wf{ROyy=)8SEj&V-uR4!ZsqLpy$XkhLW^ArJ zRd(iVSdYpPt)FT_)yMS}%5DX^ZF7!0GU3JdLs+PGy0VbxF>pf;nU47amudj#$1u1k zv0{ABd$4e(AC~9S*OPhc@2zYa=(ig=YAE|?%VPOV%cr%?B@QRNcz^D~>G-8RcKlWN zg;jv0;fj!7`CI=HK-kTckMS4{N+TruUyn7~=I*cdXQO3$YpIw|m?LGbJmL4P{7VC- z6jH{%!*PiIb~E0m;Y7Ccy%R9uF}_vTR32)?GzqBeSqt5x;4H7Ql1>X~^-2AoyK>+2 zLl3>D+<NP+q=W7OFAuRA!!T1*jwx2+SGuQ<6}{*X8=>hBhgMQ%W5*lH#OCwL9pN%) z>Bfy>5a?Nq|L78+8GJ<fAuGO|zfnH@nNP=u_HDP`RzC9KkHk1oyiM1y!^6@AT~Azx zHk)?Cx1Q5-6~gO|HTszeGMfF0p!?f*n1V8l)z|bzQ($ba{1&@&1)V=F;oVH|#PJjG z#F29P^qJ@#d-m*2`82$8;%ypy@Di@poX8lZzjm**hu{0&7?n6ikOuOJ`k#|@Qq&cO ziWvFk+G4$y5^rCL|GyiPb!Gd8RDbfRPpy9Gw|^U^tIN_AaB1ieIEpqEB2#7Xi2yg8 zzbK4^QIU#*neQqnlo<fRW^jpw5Lgv(blJOM1w<1km1P=Q*z{6w0(V+q_2ODXAI)?h zSg$ZhQK3T7>I7tUkU4=b9|wK|0I~goK>YK5fdPVmv*`vrhe2d2ug&v_j6+%%*rD>= z3>_r^<|NE|9%h?Fv0I=6on`RiptFPUYJuiK1>4^=V4BPR?!D)p__-NCk+x$Ld{P)X z<G(mFS*~Cmed^>%I=Qnf!M#F$8EEs)!JhOQVB@eJIt)7vf#eAq$*D7E%R}#fU-`Q% zWq9WY9xlrWg%kR8hW_qWJV$;P`0*8rBEX@_sa4ptVLNTI8c@+R+<361vGw5q%5t@J zswI+wK*hsn{t`#S)e5sZV1iZ9R$8UNI8+jBd~Ql&8te1XWXG)Vz4@!4hL+J$x_J~U zVBQOWI`QD4GPRA_C-ds8Rd|IwX~k!n6#z4K1RQ0Jzj2-~X{jV&<sl6?R7TpvFP5@A zvp$m#TDlmQ3Y6s_lJ=9evaUTqSfknjgkd31nKt7ub&$c?cfS73^7x;9xjggj@09LE z+|ZynW`hs--3>k{6ue$LPI=dk)x0_I4iLw+{Os}%t?j2~@NtQCy&Gh?$<_c?Uv6Z$ z$Y4XoX_0csXAaaeSm#=QzJkyW;9ZLBa!%{UHVn~NF;IP&JCN+vq8<{Z&aAiQCl7>2 zp#36r$flZnFRdzIAteZ}Ody|2@UlE8VB&yVKhZ8jvJ-csrD<fc@kLpM7gZnxZ4wJ< z>J!?@rq;q+nUlO&&+rSB&c=nN*KYizz_MM-i`H3BEP<_Eff*)Ppry}eXm2WNeb6Kd z49{EMHh-DiV({glM@6)c`iakDmicdDlBlmKcPyVNgM(<5SS`xCsQYTYg>p@vhkp8_ zW$2-MNJr|B_f-LB27Q)*unu55vEW?7_xvR+TaF*QREBYVFa}^WJOppRSF)^twFk*S zv)2O7NW^mT=y~K5t4^>y8Nm<ZC{|PM@=g{iPo)j3JRlo*2-y;uel+K>1Q-B>R4%$Z z_t0P;ZKqCB$UDj|k7Wie4n73y%}2`{($GxW=H!Q1vLaiuX(}`h$fqnqVYaz@SQ^8t zm`J+}Qn@#-WSQ_@0q64$dO;%)3$E*+N$|pfv-dC@`4PlmP=kf$D!&!Lj1??EmH~<? zFx?D19DD~nv(Ai@vd|Xvu_+&$A9;Zr(y#e3pWbJHL|FMNsy}?_yWD$Dp)8%H@Ehfu zC*Sc~laZAGhOf_*M{ooW3~!~Sf06DiNm#{F*?azAiAeuR{B=MJrFb4ISlf4KkEIcc za~~UE3}VGR$mTvn{5EZ7CC%^_Wa$Wrnm_UejV<qzG@#8299wo}x@CwwMUJG6H)U0B zD4z`H>LDY7L&^jWas{2ICgxG(aj9|oV%f0^Uyp3u*M-GZ_>I8sSCHtX5f|3Gz-KHf zcrVze%PS;5%Kk|Dco?eknz^#P&?os%UZsZr$Oq**dF*&5V8{3D#-$c*m4UhM3~zeM z4rNB0hxVlwg46h4ZkJ&0-nS?FBWUTALzaN=TN&i4qk!Mg&q}jhTmZ10!^%+F?ApCM zO1OPi3QwLxGr}*zvpzRZ)vq106}ff%*fBOPbR(4>2D&=}IA@}oaPo$7-SnNL(NfJ) z`OLyd!xvw80U2^3ZFnoz8=J?m&LWKE_ux~mN!9vp+Drf`?xoG?<EQXrc`oJNG&Txg z@8(|CkIS-cPc2Z`wnK@M<nzZexKWvXc5CrwIi<JYmm4$MujR~j{PYrmbg*r?a>dmS zMk>GPuTg^m<0|-VhV|*o&{+`7F21_|#=Ed`#&2c6JPLhlrLL7X6MEql28;_`xYB^X zrU4;nPx5wFd%zFIYh5m`&X&i%@P#r3ADlxslcrFXd@>o&PdZn?#`4o{kR$3AE=jj; zv$~42CDOmSZr{A7c2j?5PruLEV9vOdqmgrjw?5^i)R1LqxfcHBGOzsOHUB)U%cjWO zwBcn(;R^UG!Ff*k){dG)!b4Hw@W(&s;JypWn8Yi%k+vdngdwFDKk3hNbp^rajxO{C z{JQoHZ^g2CH-Piz($6w<`+jp89R|6KAdcKs&vFwl2u9ukvV6{UKgJ!m9X?q0vz+;T z_umP4T35VW1(l#1MRAN^el6eh6suY?d0#0aExfYM<mdMADk0#p0LJwJVWb)FtOG9d zxOwMu9#>izCcox;U;4m5&ACm_WCf{BM>?jh=3M(2#4P$3{vNxBGe{jp-``5VJAl=% zy2;hNCt~7IzF95QsT0UtXQN&C#fc90aG03582K^hDj(Y^{1|<WHs?fcouu_yM!)2b z{a--UMwwI^V{<eOZj|x<%z-H@XY9ArchffPW2A=MVWHdd)@vT|JbdcM)Th5i03NMK z1;4f(x`~Zk_s|bv%%h&mQA<-vNcWo!72UATx9TY1I!VnGz3}WW`SaN|M^l~GJgv9Z zrQfYT60Z-gebGExAD{L5Rt|&PM|;#dmuB@|z?uK9C#dCVUaay^ex7FR`L!=S84%=! z=U-$6Cu37r=CYDti2BmFL?bRYmbI^N%%px>^(@;a385=xvP0Q~&f|6X1(~I_z4}g8 zDkx|<Vu7y?K>wZ}^;ca#q4UvRdvI&m*FOy4jFmdpwEbF_GOm_q)eob4kQdu$t7BSV z-440psIFjE-<J-xeOm1B5oe`l@@;0kmxs8>_>zD%94|sKzeA*uSKC-U>N&bW%BNn3 zI}h4};|$XrMz3|{hB7?)@j2<(Rt6bIT|9fLeCID7OBk2Uzgxf=mtgh{>J5&cJY11| z*BuYmWUuqr{A}c?p{Nt<&N7DiY*W7Bm;ca&_fu1s%6Go|&GOjeUxrtvXiq)yHT!G7 z_K9-aZFiFYKE_h|8Ll9h-@e_)M$5JFbgjvztbA1KRa&&awyvd7El~O)Ufa)QvKinx zIxFw(qWsjaW$`X_2Go*r?%Yh#LiZAV{OQxD;*wIswO0V3<&(emfe)02AAUG{4rzcm z4462K@s3HNx)8q+R(^#mxq0)W&Fh<o`XRj~&&gqXZjuR$U6Ujf3-#0P_(<KWzh8M& zC&6qZM)n8);$LJH;%&FxR^I>q5AeS3|FxZ!`hDyJq@h{d$`U@VE1SB?$K<2QQBtpY z%U>Ro{tv;z*;Prcex}@1RtXwUOn||G)v1rV@0`A=FX2)zXZ(Y^hlrS@zQQe|^{6f* z@T@V%-FM$z-uJ%u1!K~!>ku0;@EUoAyr=BaOC2cne+~Ux(l;e<Z~uRPR`-!bV&N>{ ztdx&3OKY~VwT($8^*V!Ro~QGn6SOnbjfTKc?F<bg15_dJU`b$Epwn-x0K+@*Fk$Zn ze*_|9<w{E*6u{*l-3CGgFheB?NupvGKg)w1*&Y7!rAa_68wq}%2ZqUCR|c{xOEUpP zoEcW8>*64@F~nn9g444oNl(A<Quz-4cxU)-g*2;$vJ6GKbU2n*i$?S5jHiPrXF_JM zINmhYQ{MMu?=3&};Co6J1CJ?ua!vA^W!e0KyRToFBrG#5bmTM8<_b!q;IQrvESEGP z!IVkq<`Q}{dmdji3d%d~y1V?R|K)#C9(ezcl|_`di&*DQGvK{4&E|0oXa*SsD7;-J zZk@Htp@VhnL|R*Ct9GQ3pmyHSsyVz4_)OXgC-42W@wDMmUn(fZr3S#!*0awP;2kJF z(#q#{+AeXjkxMv%e!*5dMwKTO1cg=04{69K!ybk;4reO$TdeyNXO;}p*Y8FNf?*7J z`JM#V!ke$29%)cFz0i`|u+m`du#7An@wrD!6N{v>5#C&xBg-m5^&kn3{K*5u$(Oc) z^JmY;a(&164wSuRfPk0E3(q~rbm4R?>bK+eU~Dr!``|Uz>nK&k<v`siRkl?k<!#$b z_?)uOqC}j-&u=VRsPjbz7?;kUMo~IlE}$&UpnNQ{(a0=9(dFrGsHRfeMUUJ|2Qna- zJV1JGSV!3ejqRu%_-F7>x+;rWQK!C0)4G#p9&H^jp%`0_=1baGpMnbcmhcXw1!Dtj zl5VUFD2H(csHV<YBoONP{V>3g?boGE=7*GEcLp4^N8dX$ZN1jIsFM=%mwCv*g!U(x zE$Cxs;yY>S^6rG=d*g|#9XcK3k~gFHH~AJAG5@v?L8{Ony7i-=CLZchu)_`uojGnN zGLwr!Z@SjAz;`ccT7C!0mUr-xkCy%i?@Ie+%84>luUP9@_!T=?%I$_=OLG8r0L~{) zOqL<Q!A-a#7#*Ul<V!9Kc+5E<HOrhG`Yj{Nv=Vc}%hSg$&^EB(#-eo7=1mz$s@(gN zo)t(%b_F~jc^E)I#bvlzhR<MT6l>TWI{~}djARg`y@$?P&|Ml^7Wv!d<F*qAk;d$y zG7qDM_Z@&#z`6R~ZwDX>5<CB^N6nXc^A{k%mx)X1Wmv&#<bpu6&mER<woawD`A}vA zXa>}9sc^n0EtgI@1q6&#CyU7UD({y7qnEJyuYRFjJyStyf%i7<fZCSFG)c=gSkt+B z&XRoV8an0&-_~mjVTmXg|E0Ta%|FV9%HIiKFoWcMCYeYsz76eHsHe1lCn%tU;p~nD zi3H&x4CH~|oQz^Ao35DpwNSSY8)k_#K<_XzriYa}T}--mcOyUHn@+$E2bY$Kr~p6V zUw{bU24hYBl3(r|#M*9b=SiPGtuj@=(}j}$>-)>3U^CXubGUU8a6WnRd^vRZ=2!sO z7L#4XTel2F0$E`YzN!SU&FD%&w-D3xp;|}o*tsWtIReH`h|i>DrL%Ok9V@rw2M9-- zTP??5<@=fWGCIBwdeoI4;TOWlFMjX04pyZ>d#|EAN8dTAg))QGaoT~F3|jr$2ev=u zVq}Z5n>-4j+di~rRXJ4$P_NmBm8boav<p~6v6b`miU1J|`bj%&65vR>o44afj>esc zeciSlJ8-G7C7^|1JkgL>@<HH$rPQ6=)3yWCJ<6czG85yjoZ2E_O&qpczwsa%4r@|6 zG{5u#mA1!^o+)QeTmbCeR<__%SKo$dx6n&}teN<c*6>W)i1gzchT@TKRW8%_onyj_ zm0P;?fiG?U(a)fFbU|eCJQJq#DD=u;X<(k@f34uOL~&rC40gccM5+2;2Y`SZW%US( z(*Njl`0ibY$~*VpiVtV|A=-un;%JIXv|Ld~N|TAXu5$9yO1TVwE`e6d*OfNPE2Jsk zPt9H~U--A5VZ&yup)gnwppicokk1PM&fypG8B0;l(tL^M71-f9yijEo{Ea2^3VNh+ zfZi|`oaSv6x!FlLWdT*r(tFD<Z*UGRl(Uw_Qut0|i~7pEgc0-HOWLv@bEJ-WEd|z| z8QgcOfyUuAKQC7Et-XltULJu?2IOoQf$-1=Ig|)^=c<|x8Idq1*hL%Y=yW9oR;vKc z@!gC|jUKF>Y!kJ;LKEa}fMw~Wo=iQ<Ln{Ez%2nHbA8um~->|Rjf%iW4f%jYmoRRZp zxLWoyxeQQR!5?(N3EU|epE`r(YwBNKlI|Wp3n{sFzYXu#XaFLZa1^I%eoY*F5P$!C zBX}Ho@{#AZpE9Xjdtod&)ieckJ(SkT3-`)>t+5d^0ISH0J~uRF0-H&}%}i?P1|fZH z+GUN?I;{YdXLOqIih2b+(efW-hs&2PWCDE-9YO$FdfK<EN3U79(nhTVIi`<@hXtFF zZ<|QlKBKmUDl0-G>bTVb)w?R-Y?mSREN?BV<!rBO{<$Y_6u2y*TWBn!uCSfHVDCXU zn?oiuiQSaY&vR6|@EP%%f-<k!NhSBvV*SzHUd;vRwhz|_Y_65xZ+N`UyX0?OeCvt} ztt|5!#<un%ad0PZ&04_b(3J|}hL$IfT&156HME(=Xy{u{eYc!AdbB+E%(Lax`AY<* zt<ld8v3k-KLjwT5u10f@fdJ0vt<(~Evtxi~mC?<lgzZm0sPfg78a3PiplbRj+VwIk z9G&D*m$xrNsz+DX?V>J^`q3dqaP2X^eHRmvy7;JLH`}6ZU3pqJ5Uc>W&#BDl8Ui|w z&D|d$7RC@yo(X*#B6$k0Ly+1}*EXcFO8R%-H$=CbX;13d{Hs*t<iV}Yubs%sic&## zz8wW{?#AFo{)`(p<dAU-^84=Mxl`rYZ+?Z3=NXd>l?U<RyuGz>w%?~rrZzy?@4oBZ zNp2&5Y!}x*Dj}-$_pfQSWwX9~Pr*3PF94dJK2iSQ|NLhG$cBaoxj$Ea`IrATK-jwg z);H0QGKp`$Y1<|JO6}|CVk03oR-TQ-v_6bwt#YAK%kp~EGFt-q+MoO;&qs%%U8&F3 z#?O}xZ!5FZIb|7t3`@`_9Lv^zx0l(hDSV`B-ReF<PyNMH<=JPSE8EfA?z`_kz|{B0 z6{EU{E*Up(?xlYhe02;2m>3yme%}0$RzDniy?MI6HFwD&JhMKhuPX})pk9-Gp2)Mh zjVn>?T6NhfwlY3GQa=B=FPEpDd@6G4=YRg^kwF^6^~N|M{e^^1x{f`m58|o^5nYpy ztIz!aIz@oD;hWF?iYF(NHIz!9L|oRV_2Ftx^-qlwJ-m19s{Fl#6||EOr%#_Que|(n zj8`3NI013;)JgoLkC%Jjb#Epn#<DTFu7x$Qa?A$D!m<lsj{?==TVf0AkM(tt=WlP3 z*C!R`|AF*g8{%pf*6QkY0{oC4)&4+v4x9W5n+AUQAO6D-&=-O-9#)+9=@2+uuzWyE zS0K1dzU|}`5;9)~Y;;b7SXRCrlghS(5v_~^QWDO0#%o%}WjYG{k)h#)n?;$?@<jkh zkl0RYdU}Fo?)X^+guDc}J4Yv~!lxfP{V_X;9}x7gM>0F)11`f&2H+g;bkot>Ilz+i zt>rHeK2JRRe7OW*+)pPjIOwuc%vZ}~H?B9hA8{a0i(JKOqnF0gOUFHr^<?kLrLva+ z>w(?O2IJy`jFeS&>SewW#Twr>3}oi$d>xKx$+<|QxB{rMz#!@}prJF%i*o{~04C(G zAJ+%w-`#=*w6)OOG(KK_<rDvLdE^&=u58-9vz)@U#2KuUR>|)OX$rP?gucKo(8dN6 zS`uGfih`0sx@{e1@JG7VkF=JaTB&*+pahz=b)6Y-?iEHZefC=qzx7Bs!xNwjdYeY= z*j0S0<);9%mcD&hR%$6Ds3>q}U7J@Gm>mq5b)zBcn5JN}OJW2tM;Xk!j6-EvV9KR? ze&^9H?TYYBp5(3B%w(BPRcLA%b8S9}!^6CL_}qL)h$are73kI8E5O<TZa&~UCm^&$ zc4@5^y`Hs1a6sgSE*&U1`s*G92%$ow$mycR<xqmFf|Uwz(<LW4XFwHY5hW0|onID& zMwy@^?tx!$ZJCYKW^ng1%|L#75<r^4@&x|BPouC-0szcAfW|+Sz7qvI`m&)Ebcg31 zENkr>I@p5gBvw{lON+KmTK4b@?L^Cg`07TOrvCX<+6f%j9|KCtZ@c%K`p;QnX5MX! zfZATmlf$%WrH7rGvcP)NvQ33rJ~57_S}Lgx4NbM0bHJ*itJQ%MTk?R<NHns=iK><_ ztTXw=H04M80j(BNE;~mK`Om!CW;Cn|V99fpaN{vlTNcl&03q_~JoV^q?3UH?nT9Ik zz(+n*1|PVSH0am@_St5r$fSo{qB9gUUYec6LUgj6JTb-KT{j5qs62)h3yO`0?lI(v z6$Z&2$TObs9Xy3{3?<9CQ&?xBKrOLBTy|v!bZ!A>*|&0arAZWb%C9`rBJ(nCcvb;n z`mtcyy=M=r2u5-LLLD%`br*X@re)24tfupiXEjdi-5Z|ri=qc%D-8gPBBL2hr@ZxB z%ad>5;o9En_q7I0rVctG5&`8!Qi`lH#mWoTpFE%ts@Bc+9SoS@zr_shkV(i?1Y$iq z0HYmMAFKj?NMD{MjLYSb59TF69M3DjT)&Y{0%|H@0(=2Uk~W`54%WQLyEP8u;o5(M zTYE+^&2R24Q*$ILZq0UpCN1-ks{ysy55P@RorH8*t-H|+^kh|pXF)m6Jy^)4-EiNH z{O@K0LDw2iT&~8_-#%2H;Xmz?o79PUM3SYgm>u&bjUBi;V3D^g@NM1%iUm<>8+TQa zM>lCq12$h_gQKN|4wfvs6!>(x<<{HdE3X%jsLD?H82Lgxu}*5_i5zZS2sj@-awJRN z1iyCg*%!dN@|QGzEq(3VD<6<2`a7-ZUU})|EaBa;{{Wz81)NjHCan3b_bQ>aF042E zp6LlT?!-;jJaT%^zP+>~mw%(9KoWV<|F&=Cg<!m-a`Rv1li<!JCWMs}^8OaUVh1Xf zzHK_lEIwKwFVaweQrVd>$eS~4dZS*Xj2foj>&L>v0e39OntsvxQMOnw<|WJKDTjL0 z85CqKGX%N^0R{S5Cfdquf+n9CfKms_gfvOoRSx1keF_&<=g#5^WDAp4V_7NT_Y|I^ zDudQl+GluOW(q?^_UV%2)QRJO)mqeJUC*H1i9lC=!E7n3{y^se^%t2CRsP4)+Wt*h zME&dcU#lYfb|+C>HXi*CFh-t)Ba?Am?c9o<cE^tW4dARE*_0)D<PSQTk_76oVy&Z` zy1c?(8`L|XwIF!ymsrWcN--zNjvsxgeCg58(O1vJWsido=^a1K0hXyZ@@gH+le%P@ zM{X<usL6-cWeYgZ!w(cH-wWEbS#xy-f(YKL?NH$4YOcL%D4Y*$r|M5UCKPv>fDkzK zUKdTR6{TU)J`#p+A~(6oVNX<LDkLP2gavRGY_3mJJ)w)~E9+aJ!o=MeGE3@dlkyz` zAs=*MmF&iW-2?ba-?Xg^ZNtKuy+wLiUEzeWt5RH9RyV72Qi7i#j{vkXL=Yc(n(r?3 zf!$1!j5C1y4<GqJ>W0kGuA~9EjP6x|2K#J((*VwM=nP8~XeH?x)DqQJXVG05U_2EZ z_DQ9;;RN1zl_w5NJu*CSBA8fm@8`afzSMwU`>)cleiMo%P)(=$eI_5&9UPN9Dets^ zUnb2(;_n^CWftvw6u?<`8n#7>kp3%W;M!-^wTaiZKl>|r2|k0rlsSv;A2V@@Gpp1v zLT~~^S*l*Q20RCFMDL=E`b5_)*cf2rDD6|f&8gEA);6Y&pnTvL86)sq+n%LO=|j6( z_6h>}R2o_5oaIl;E8vV=w!7JR^E=Ak8`z9%3~-&cT;rmE%^^qIn;2H=!(r5M$euqw z+sFZVf8c0E+_f*-ptU5FjR#FNUK{ic@82kV;%dIKYzuVm;TvkP8+xXE7Rr}x26!mA zdxf#$cfa{eIgdPk<@x8!v16>}M8>!>qZgxqUI5QQbY^wltQw>*3Xqbh<V|VrWSQsM z$7IY#A0rQ1Zrixaz+EZa$9SX<09)Nd;6-<nGZ-(qT6Yd37pzp0o~xBKlrimY+I{*U z`Gg2F2}{4^*wTqX#}<}LIhPfM$aZ}Wcj+PxqA4%yims*>q=A=yBab(P$z+~H_LrcQ z6RP}>cr7n+*$~pG9M71B{i!;Oef?NA4OAvW7smyTHwd$UoZd7t5WxAFrvaQ9p9?r^ z;j9m5lTBY?1LePM=AOGAGQsN}ez%dMhEjIbGSya4+hY<<(!P^!8c)rX-}y)XE92oa zWivAK5@Wuf_~;|$UGLKG^ls`|9gE<67vQg<%|`Na-7u7CW2L%oOltuwxn;KQJQ9Bz zu4S$=z1FWGXi3U^<qSLv2ZrCA5H$`}7WGWjFmzqo9w4#f{%ZKZNT0r5@HvJTL?@jl z7$blB)1NN?H!d*cnP2_YUoAiR$WLZW>PqSzJGY^i`Au!h@~;1`cVyz_?Izas5^dj; zZki5sT%XfqXZ-`hOHa!^!sLbTUG=QqWnW-BcdV>Wa4mp8^+%s7|MFk{U*+%rH-Ep} zb=O@n?sHPfNmF%GH`GHU;ktr-IQTF+q<Oj~AJ*g5gL+hGzRibwMma%e-RbVnx>Qz< z(7sh=P}$O7#Tc_0YQ{|$yfuI!!z>1T=fF^2c;Wf-r7wLMS2m9#&t}V^8xNO<-t$oT z$VWdCqZnzo6TjdCgX-p$r{=)$jJGl~=~y4HQ@+=G_Bz4-(vOt4*E=>Ur>+;zU;e%Q zmO2h(5^#R}fBPMXRU5et-3-<SPhq&0(V}qkE>?6j_{<tKioF#r13L(_qq~AK0G>c$ zzY@TRM11aSfC`jKj+TO+1Kz1vp_H1QAe6I<f?a|?ZboKBJJ1l=6PwZ3t^>AdTu`VO zy9q-DoK#k63~1aLgwYV_`WU=p@n{FcwafPfIJWNGSDt?HrScS={S}1RrmgsLL@8Ww z6ErreTIy%3b2_mug!%yQ@npruaGT0rmaz_@1dJ|R!eS9?W5_o)x{1cDq75ibT7u@& z<bB2tk-X~PwiDXfqP2LQB8^!2x}O;|Tp-LmX)W?|z~v0|91MRBYob2D%a4BiZ<Js8 zyZ=dX3GoG%3Aj{1Ijz<3ia-PZtjN?Am1*55c%x*JrgW7d0~+#P+IVk=t#oxT;JdbN z+jqVvOVoXxY4kheb>cvf4|3){J2ION?`0-gU+Z##DC5#igbG0bKA!15!*}w?7|OW3 zVOpn9zFZ0;xVY5;G1ga3Xy}H)LAF+5brS)UFTRze9t&6+&Bgz=U;_TFspAL%a-ub? zIf}JAbtz5S!Mxu}8-E^4fKs{S)@Rbw{I4C5%YAm7=@Rss!_vgzhIQzDz!3lu2fE#W zN%Ceu=kP%tNcEz`X+>*&$+MQ*b|Db!k!9S385+c*5#H~CrVA(@u27821@aU>frNMB zV@8WRX!FXm&y^!DyufnvV^|&@gNNp5BLY<Lp6!o3X1N&UQQ6bpu`Rd!W4mu@;aQg& zwiT_<toK+jryNynaEbl`K%bqMU`aP+b>k;_U&U8T;}s@@<gIq%L3*}8aXKy9m98p0 zY|rgRk_jhY%3s7y){;N#!o1l*O1JPVajI-dd->9G=nFi`xpl}u%&#NlyeAxytbOk? ztVJx_J(OjFM4^jmHg&JEE)AUhw60?10UxD(@!iNr{(2dC@DA=-nE^VmM7cZkk4e5d zu-+v#td&rT=b0q9I0fK5jZ7FR0}R}^jsuv{iF-KU^w5_pt()&q>Wg6WJm<x7`TSJ5 zJb_yPmPt5>9mhh^Zz|~A@^WqOF6oX;668U#xO{nvcBFjiDf{;CD?4{=F59+ZLBr%) zkHQ4L4#7Efp{Ugv+pBGZ#~g(72mRW5$Z|{ho%*kUbLAyzmq7)5v^Kb~{)nO0h4FEf zQJYV=1N95dd=4K;eianowji+<iSrC_wNzaV|5ZS%0zC4Y<#zC4J(`|Co$)Aat1RGU z;;Zfh>cC!*M60~3U^BdcjC0VRfj!?;zT^z=n}%(;En}`pJLnMAm~Tki_bFy_0{>B) zy3FXrnkhd3o$jI0((QndenpGj0rnTja@N+u2wrni(mGMD$^Qr$;&yo(a+M^M(<v?V zG8?9AwMtLhPzEG?#-kkeGm+=UYkq9E5Zs9~%b9^9=WP08<S1>kEc;ym%v)h|wpU+0 zSzdbiXu0i<yV&?|4|&%T(%8+2{f&9DK8?E$SgjK`_B{sRJUKZ{$j-8N-wjw)vAHPC z+}x$j`7zh)!9_E!<>WjA^%tIfJ}Vy%-g1a`Fq#2*zEu|UZQ8FfSU*jiKA%HhxO9fq zA{Wmidl$-$HyvhhP5%R3O+MM@EWdf!zO|^1&pXn0@TzsM`A|<0aITY$0?SqYn-0w% z7g)#@bQ*mz+t<q<$`^e=Yk8G@45)8iUMaf*w9;p^x=#8i>X;YN2Q0t+`b7Y5WssYh z_V9h3aBkXs+NC^V`*qOeWJ0}{KK{RO{uGl>XPD&OREC@w1+ZV^E!ir(Qt46Y06nco ze!+cmO8@{4$Vo&&R8F>CIDf93Jbo;7wwcWyjl&6%PW3r{w!iGPfvjAj-;OV8XyAm7 zbw2|LJvoUFduTV#Qf5K-9sx1>L^z8)(oZ^RLWR)6%FXm)w`~FFY<)O~H){PPfASiE z1yT@?xYS_M8aWrh85%^MKo>2k-FWGRXTQs4&0mhcX+a11z_uI<XDvsmr|3aW5>OTd z0`CNz$sOUG<QL$Pn3hvN&epkg*pQg{FJ(sMMF+f<kD(y}h>?SwC*R)rojmL3gf*0M z%lHgQIOZ^$!$6g%{VN!4T+%@r7{3Qi*(f=9Mwptib<1=5Tm$%(JePz`oL>NEcr5)| z6HdLglYXrmi@Lti7I2350Gv%V;5&5GhiW^47r+_d$rV8HxlcQQAe5=IY{eba7}oi} z^fMo(PBqV<o!DR~SF!=`x_Tg!#5|apoT07Lck(@0TrHRMBJGx%0rV}f&plam4(r7# z%=KD$%AKH6&9Fvl*xW*gS_}Es_s#QAERoeTOg}&JP0qqA>JEa50?wKX^bc=iEK~vK zA*_uXGV{LjhW9j2o)Z_px(9>?AnG<w>^WXyMIS)(<m9CWK%-5$j{#}f$4FP{9!q@y zNH+;|UxrOg<c#tgV)cf)nDRezkwn|RJ8j)Il4q2Vv&9W%DR}y>ls{C;I|5l%Nf)MP z65aeTLBlfv=RG&<Y5?b!o`i2`=x24pl`?Zp(W&RKUhaLikpuGnz+s(Ud-$jg`Z}+# z4PMK4&C@pT*F4T`;%pL7eR2}qXZ{4kQa=A!@FoNHbIOt##;ngg{XJGLo-HR{ez}~+ zz0VZZ$NpCEm#&e{AZ^S&SR4bXhubHZoKnKNx6bWXY=i2<(NCxd+k@e#={nXyFIUEP zqfb;fQMFHYa@{`7Nw@h$`U_W~GKoD*-=O}{TJ9+~<c&IZA};vL@l<pQ^8=BtV6p9L zL?@Us>Q26B8RVs<p=aYst?=G*NEgczor>#9CW*#D7|T_k)pRO{@(s~A!Q;=dldG2u z=mwdcZrH87pr4I_3)fmB25_eTdqxXq<dcB2KAd;DN{HlId1w{`IN$w40-VFF4ILr@ zn``Ajm<77%h@ao@{LcTvWW=%TXS9fww${xL-2a|((@pPyJd6!_CVgDJ^L8GIEp_#F z$J*9l8*i0;wdO5}ziJ$z-Wq+L2A_ZSSJo7aRC&odgU1`td3p*R9$u<?Pem4O6IIWp zJ@Wbd{Brr)SHD)CU>^suhI{ULXWEEz`p}^pF@W32WQ)8{Kgs{vqT9T_{`p4%aCWuQ z>mBPKr%nlGyHy5>KiD_eem!IBf+5HPxJ+;P!WX_&e(#_De)%|iirszpU7?Z2fVba% z6MY<g6}0Tbg8bs;ius8PrS959n#`=vRqAm4gV)ROTYkpg9rTalN%~W!Xw)$>HaeJk zh5c%kgHA$dbP}C7>FBOb<40s5eXWKPGw7|Zu7C9Ne_B5KCy$1|egpTm_uhMNr2z(i zd-m={E^90+|G}-K(drpt&+C-oZ6^WgS%=p<s_ea9s2}Eg>7<4W-Spx7<nR7&gsv7I z4t$(3vhfB)RS85H&A{49l;b!AnFWjN6dg!77}EOKZ(?amr=~J)JRT}XF7Zi+g|=lU zW*mNJm_CF{Hqle?(CE8Sm?m&jFu_1YKh9c%s<>u}JKv0BncRyY(%)wfwXgMPHyyUS zqYDVmaqec&0%xU@a&R=v66C!H4wmm@9r~wFK2eUJJD265qm*NSvJILpzWxT7$sKd~ zIs?02GzBe}$C&wbbFofbW~eNx{AlTtK_h9n<k{<K%Vg(Ic`b^<bCix;#;z7LD3wUG zP8#<l4d#rS69OP=@zzB;0yr}O_7?z9rzyvWn2G!NFa6DO%bj<YRT|ex9iLlu07$Z$ zjjDpIUNc}Mb26Bl9D0@^?YyI8l9%@04a4l%Tfo_~g2<&8E@jpa*b?+MP8A-1h7oX< z$1`z&!tGf=I6o#F1RZAp*3aW_asqHc<;Be#wRkoU@{IR(2sUtmVgWrTE94zFV{&%i zd^$*VaH#KDmpAl)zA9LdnedJq^s!7AE3^qLe~rg`(=cv9ZPSV$%nTH3<1}91dwA`! z0G%yVd!L8v{>XRTSOz<A1xkP}3=RMm7qv!Vkf4USGP9f|+Yai+beW)a3yP!G^E$Gh zn!1wuG94#m<oz}uZr~*UI*Zs25&~?gTv8uVzLacyTgw9nP<MUQ;RH)W^!t2<<sbo_ z;cd?o7w|dC^M3L?NFBI)xPZ4lmZed61pctj+iTDAunMHK;D3%5WV4;R+<6JW&kjxS zMVAzA_N29-ysHZudEG;vv0O$IB^UllTqwF#iX<5AUn|K92CIb1&jLE~cFUK>5k-Vd z3G%p{PM$FhznNlnfcf)h#~M8h8r3q?Hc(Tu<0YQ}`}&`Aa3wb=44wRHfj6HIVHK<; zsPZfpdqgInBmJb$*iZaK+5Dcn1Kh--iZ;_(on*ro0LSn~CsxWGxW|~nV(autz?cqr z5;s6wcQBA=w%82DDw^~a8L|2WED&(ckMDJ9Ffp;frjY>7$i3~`wm>fj>U99iM||kF zwH&d+BLDhaodj^6);g74824e>xqBC`HMR|xVU&h`mz%@e@}WFdx}-g{3k@x21uX+) zQ5RQ_+7BpetP@j}&fys{kpZh`-!z(!C!ZvY10y~&{`Q+1y=m}M(Ih~YIp%xHi5#eP zBd}U6S(INHctQ7SWo9|F0Fy4(szaOFMr&D=kyW{`*5?2sgx3-;Ko5mTK5gF&OcFP| zRR?*VjjP6=!4mJnKYj-t1@E;!$~)6fag@(aI$}+$<xr1GEdxLXc|9n*-N-tv3H8(8 z#d}wkWHYb&F=gO@IMT<T)fDRu<gD(PvcV+j3l!_NN#3-qCarIB0UU>J0ki&J+Rm=E zsv`=+8yk%=(V~`WQi^E79Fev{!GN^X``+}TUiG&X^nd78y(v}^6{9wgR+B<ev6$44 z6q-KIyUrXo0gng7tvhFb%$}LGW_`@8S+j<xzE_{i12M`$Wo2ZpP662fBfJ0(-Q?)? z3k~vM(p@}R$FsV+-u<@nM|bknsqQEfp@vrg_~5}f%eI|)XmCy?$cG#w6COR(;Jgw2 z^$7;&!z^*!W^g538g^_g2O4QV?)<O*F<!2dClBu4PnfLF28+m7`Nv5elbM!sgqzGF zlc_{tq5PM4Xgp<w(32+^ed%PL{`_<d&L(I$iXP?LCL75SIR`zVY+P~m7lr{h?A43V zl>){@w{U4hnQ0vy@VgnRI#Ppcd4f7He$Dc|)yNS&d^Nhd8pbk&dP*D#h<DV<+ZYdk z-H8zO+WOj`iA!gUxqWlQ+{8m8h~ul4K7%yAi99E-ELnz5lxwbv*(8pgn=wz*SJ4n* z*brMM9zB$6*;Yg9u}xy>!`i3J-el1641N6}`q?=0)9QNC#7i3)TzI!G#V>kCMn+MB zMl|~bE@w1;{UHp_ZWtLuwPisn;(ZF4>2g-@zu3RG`;wi(H8?v^ux=p;@D)_iFEebB zt3n=c;KBWTo6uvl1H9JS&`=z%Y*S9%ym76&edAZ?kb#GWJ^L}V)fT+|3WIo)fv$Ft z0rVvO7lX5d65ChL81X2-8>)v(szY1l8P^>D(N6YFBGY_FTHCic(6%k?$}hrFFqNqx z(D8Z~buv|036>kR2z3aJ@t0Jjseev%)<Mdl@uA`++Gn?PaqAz_(cXSr-eQ$E6kiFV z*W_95IY$O(HVmB6!}+6ygml_XA0J4`8#xH<6-T)J8dqQ0Nxwzos7O*qLPPs8T+gvO z<Hrl%bw>`-m!nO#Sk-4OLTnJ6-myX>FTUJhRfT;#@^H0YYyVx!2h#9SWQDYuJVGA@ zQ^Wu8QSg>ef>hE_NboIwyciy(GpKTufDfsU)sr4bXx&Pmq5o*x$bQOKcgpv+9HX3W zX71w{oDHd=!MQ#R)>5`j5yN_By40n>puU0ToSbnpX!}qaoL$+eA>VLOnHZH0gqc%b zi|#_l&Em<wk3R1~c+<_wH6F+Z(FNc$GQoD`TAl4=Q#}h*!H4u(xGM}7HiL!W!eTAg zvu|*oUmSD`#|X!uhqENcVcs6%7xdMc=Te~XkI)kInD%YQh}3%tZJ+*Od3j|1oc;E- zMxHy525o!Z|E4{A(=Y7KIKXnMB2D)~-T=*6k2A6Aq{Kf=oZh{8r+ZHS{PEhO$kb;z z5<O+r?gnFwY5In<I3&z68SUz(>eJFzW<?pU-g1nVYvh=^t_&X(M0v$Q=zjE6c$s!~ z6_hJ#>{C0@I*Z<%f(FzVf8!a*5CHmRa!w<+V<zP}4W!%%t<opa*+LKJ3Oz?zAYQ$p z$F^e`!@XpaUF!%Pg*F4bJO+(JdsVj~FZ0aF6Agt*HYaPU_VS!#Ph{-~c^UB*4oH^C z9ca)AVaKU5)d4nu`v8M;@`QKXE5fm;lUfJ#a3(zAG9J#`$aGg7oIAJF%^#T`@kIco z1~W{CeRbw*t|mJgosUng><}6Ldev}IFpJB)PoJJK17nDbmwt-pWxhcnF3f+5*X1`D zz|KbZB%~;x%i|+FjjzN+ZzqFiqO5v}3eJ#&Prc1gV~~a$@SuE>c_O4qX!GW^bX4E@ z*X!{9@V(^jp{!Bu_@Pck(r@GzPd4%FUtYe~UAb}@x}jgl_)ojVBJ%6}`ETP$U{tTR z_ky{MJEZ9b%eZv!<(+Vm@tfMdFBiq>Zg8<hXi>-0A}<DKk;PFHN`OM1w{JZlw8mxR z2lg_Z5_qUX*o7aykDNix@s7Nh$jSIY1h=DCXysflOwoJQQorLboRoUN;|Q=h_+J{Z z?YDINO78NNM-j;$`hwnPH7jyQJjg!<|5Wx{TUq(NyY|cV?&qslyA#Jxbc4a5JIdY@ zZb*1`X^Dx6!^tsfkne{m3?1}gPNE%u-u8Y+@`-Mn-Wiwp{qXd-5_i5UognW22LJ&7 z|A!;5t^fc)07*naRLs43uqVlJ-&enP-*exyJ3BLbFK*)E-oSzk24R2@MVhc=QzS#C z!lrGIlqpem$X0~)hh<8(OfiD~hkw|Pa0E$7A(FO4n<5AV34*v6yNkVMkGaqH=H2(@ z&*xj+Z{7|T*a3EEt7rOk|GMkQ%*x8j%*v|n{Nca)SDSzOPycDz*w`qmtE**gZLN3= z4i1){o}RL@vQn0pmP&vBK<Vr6%RAGqudkQBzP_YcTwE-xE32iuySsGvbSHfm_g$S% zS)t6~;o;KZ-aKB-=e^~0_}AOlTShj!%W(f-nORyW6Z11=xwliUalJf!z09pFmBrO{ z>gXzS(=%oF$Z&b@eGimfLxW{tvy^_y?BSg68Z3(|%VixX`-TV0(CA1R*|nqef=h3I zZyDX}l;NJ<@~zXS%hz9ep<KLrwd@!jF1z~s%dXzuvU_Nt^lq$`UhqD!Z+}@|UMU-^ zYh_*BD1T!O7`nPjS8q>Q2ln}eg|f1?Qu+r5%IJ<A!DnfH9$30cFXfqjZEdw|ZftUH zl%c_)(&_3HfGHciAD^Eq=dX{K<;~5q1f5rwmdnQaW*O}tE(_3fe0r)}pPMVkAAF$v z!r%Vo@<TuNiE{DU)iO0Z&wI)xpES3fq$wpA2pk%3QjfGYjcqDCUBK?|w8N&f-w4ck zW}5=9?Y+9XLY_@<E3{`1ZQsw?mpa5{gEA<n4D@y9+TCp$d7+oG*UB6;n3<U=OVF>= z)l+ut+*w9PMpAbR>pW>LUAk13mzT>JwA)1*`9wU{D8qWXy1UBoV0Wz>_&dNK96@sq z+FiVGv0NLUfycT^UvFO-8X5|$Ew4d!=mXAc&{g~zo|7Jx4jYuTNx9wmZ5nawwv9R4 zqidbtYt+r7jm~;m@6cB3OQpN7!^t~<+L&4^(=)SWb#0>z3=NmVM~;@^(Xqg^4F9Z# z+MSfUu((iWXJ><pICWEhSBG|5nuiaT%Njff`qbB<EvOH;x`YvW%A2d}@MAAH!_)l( zec%k;H|S4Gt7ZDic)5D<Vmb5bE9LB|m&(lewK4<GEW@i%f;Q_947P(fN(*Tk+QKik zt9{w`@|NX>UI1i2?WN5(H`mj*`)Kbz+J0zYuyg_M8hyQoJe!syUAYQ(%ZKttD+BEJ z8}Oh!C!Sprw>jvhMgApY`i*U+Y>K?FOzK#MN5j+B$NRQTh2MOAJ=OrPLOb6J4=?gt zyoPC`rNyP-2av&4LadQq{##$)C?f@#2VaTTI<T%vEApCd16~?<>ZvmH!G}`r=7zBH zqO0;0uT4a?tI%etEX^&JiSc>LhE_d8Wo*wNyk7aa)8yF*;^G5O72Ab&=DIMqROaVa z%IrcZBRfXRu01;_Tpp%;;DsWbVhhcABQJHNE$z58zeHcLPj{7l`}dc9`*xJQdysi! zgJs9?Kp8+5N%>7+rN@)G%9JoWbnKyhBiF?{HQ26@plLJf^|0UMpI7Pz08ZYT)&#bJ z@8Bb4VcvBEbJ90unx3`@KJY`OPHnruXAu@9uTuxDYsIO1!)wk;|CDPA=|H-!z*}MI zH1wgM+D7t-bOaV*-Q0lJHdpdYTyoZ$bDz4QeSIgsluMg+Xul1fw`U3i4|%53)eCKr z!QBI#eeghU>0wOmfxk#l@#ab*PRj|oD#AQTSzI>YOYwwptK6V}iSar>tcw@)bKDhN z$1LwRdG2Xjb)+k_=vb%p_C0WuoU6E0dalqfmzUSd^5P186v?rUyyy&+*IqwgPMvza z-232z<>2ANWsq^!u4@TYkvhad5Ca7ClcsCPwR30BL`K^DNA5gU_UzjST<Qem2pqM3 zVF*#lC(LWh@bSV@IrZX8WpQ!2oVfS?vSY^>vag>6X)#h#sJA(4n^?cJnxC65<Cm|N z@riNd#A<oyoe!0ryLOUXSzl=+uSM>M&&^3*`hxOl(Xs0M#j?U!)yLR><ml0iX(DdA z${(^~9b;CIP0CGSv%Qv=m&(g8y<C=-7U{ct%I-b8%gESR-b1O<E$;z`bdzjp<Fqfb zp0QvN+5P%!ua!A;fjjQF16^ad^bhu=?L=B~wfx_bP8tiF^42l^+QrLddi;9XiwqbV z87)1?@=bU}u1Mbn_Q=<UegYytD`LcZ`ub#<U>w<h@IcwQdlxDUI-KQ`Pdvj*l!f{N zM*IN~`A@8tGTzOU>*zW=ckeE{_wA+re)5Pt*~Oi-a(?tie!q9`Sos0?Yj^<p(*v9$ zmU6jpHTC)iQj+uPbSYP7*UQ{8#n7)zZ;|p;5AEeR_vNqrd3otu&mqgvN$B6JD~sTZ zK8J4LSR(y0?%HnLZ#V|<ZhgJ#4(hSdAAlq8P>#}9NGA>+8;sSVJ83qdyYgA6mGA43 z?NY<T9KP|d|G3tl&99In&rK8g9C_m}`Z}j2Ndqb2k>B9i!lLxtgf?_AN$W*|gyytN za<pUaChgEcPwGZjb1aNJf{vY@est#@WngS?8QyoK^o{O7uO6We{(;{H<KYInh`540 z^iozJH>KU`Qm)F?O?1iO{?RhrH(37qPkpi+J+K$Op*v%fvLgTjn^pJlr-%E+`Nc9n zzfcy@c|tmA%GqUkWD(<*Z!7J5pBK5>Cr#+1N@1=kC|T=s-#2-bSIuor-~0%5ed${g zOH1#&EFW0X=hd6Vnex}5d;iE@?581Q)Xp-7-m4y)jO3Nq?JGX&LcS=29P8KC7U8c| zY^O!eh3Fis$jqgM+3=h4bDe%1StFCBZuBtV=;_`lJJ5ZHk%v2}Pg}<^J7Zo`pLME> z*(Zd@zUMRP=tbH}i+Yt}^`A1m9zi_y+NNs@i@;d<{os8Mmcw@)ETcO|3Mx&GT6Vn; zZ3VghZ2G1(-#D9B-}Rz;b@Q<WUjwHX`-gQY&lu%`pS19JlOn+M+mDtnzWvP`pO|-* zKVHM1(wqB+3|on1y;b;Reqp&h_w{d<+3VNK)FsB0#kn$t-7tw=d*S*#Dgw6F&{!E6 zp|4?Ab|b%fu&Ha?*ze#KY*hImdVn=sIY-0t^(SrI6}>{ckFmnG=b1Y5FnxFw+jwwz zs0_fTRoB;cL)K%zXv3^B{#2a_`y5%&3tT<g``wn;NF9J$#5b@A&#s_rcB1<*CP4S_ zX+y-=a&N|K%1-kDvAS=iTy3GX&FY5`ap~&SH}?6~j$2j+hp9T)@#t0R#K>>^$_hGz z?Y{<G!$bXLa{Nkp{^`G<56wZ_q4LOM50@i{4p-i=FEsoy0L|b3-p4}ExB9c4$G=<J zijnXOZ0+$kaOEzFQ}Z5usEhI9|NPg#U!HsJ*)laX1^u;cN6QnBf3!UI*puL<O-M-; z9GkvnfbRyxExx-|oNlqWCYclv?`=PGt8VDidU_w6TG<3o(1h^3{3OL%nbq(*g2ktF zk1{ZT?m^l$I-_}H8Q3<m2C<2JU5AF<WpZk<{P`EYQ2vbb{JHb+bx(QVfd|S@{nV$+ zp~L&p%k9rq_O;-Cr)$Q~+PL2-$zR@c>IF?Gwnf!9)U_oSc^b;W-^vU7QVX)rC6v#G zhOsnPOSy7+qCEHP^U&yv<<jL#>1)T19V`FEXFh}6P#?AbZJ>K&caSebV^gy-?#6Kg zE+21)=SG^hbBA1_%@>!ELD&Xk*t4qck%15fQH9<OthBrROFh5JQFJl&7UYD!igrBg z>+50M)#mFe(^K>1bAR&r^4ZURHvQ}FyYDW;_#B^j^2u`S*q!hUe$5r|lYA`-+wa?F zH(j^V-t_$K{ETdTivs>~`t(~=`i9r?NwotzfB1X9xB2CN^lLb3Q5J122R9r6eJC(k z3}pr*M@LvM&s7FRP(j|uz}1h@Aj6_hlBXxnt3kX@RtG#p2=8UKejF{U9gL^V<<dVk zQ1Ic=Xlp10-DLsga<Fd*XUuw;qQ3E&=`w+lIE6!K0p@V%*<ipFwr<Mn1I|Z&;C<y7 zhRaAV9c6A7CvPdUDyv8tjf|Z*Fh>|zJ%(^NtAK4>pDyF4&z9>ray88DFoQVD`gM4N zuL5s%LuV^>>SzX@B?eR#EFG6RpSlqKcDNM=wPloH4W!n2m&(Y~3#<-Y;;ylmGJtt_ z2nRTZ@+``^l67`rzD!I`#(}+vQL5wKvKLlChJn48GR|MUQqJO-efXmvDS!XJ`-kN| z4E?LuC(1YjQQ9n(()n;=4EEwMr)~%MmBGs1GMjLSzip+0;2?$0fI(0dgI00L08IxK z{}>d!_vm9HpdT6z0l$iiWySFZ9<5>#VFvx|#5$2J%XVL<jeTc&oht)_!!aZ-UA_zn zy5eXabm9PIc?@To3d7<e{DuJ7gK<9Uph3B^>$-TYZh-e{xp3)9xpr;5ETQ!3z|jcy z)HyyoHG`r-JL<rv9lLN4OM@0x>)n2AtV3^)TxvSSxyj_=2xeZ3Q(KM`4WXlook}J& zTL%^u9G#<1LZ~434Kf*lb7OE+=SpwcF*cgcCyssaT{nF!M#~BY^AyfOcv)xk60qx( zm)1J{g<~jmqFiW{XN{6n;Z~?K5I{GE<uW}nQ6{gBm$R?EUM`+FQ=b0XH_FTu4wr>% znFtxPEXwVJ7vPNaZzmdXmxs=lKQM?>fHHN&kSW(b<wM#XLy6})zz1-g>BzC&<sEs> zJ^{($=QaAkY7|`uck$8iv2W?v4Rxh)(*!ny3g{~DO=Ef$-sSYS<@76+X8Y7?Gnv!F zZ~4wX9b*U>Vz>f>&f@SQ6@(9|N4SO2=N_Rk`CA@t+gUow6sB(-@LQ8|yjuV8V`cMQ z_h3-d$KWBr1!oj!PVsL0P<Iy-dC+DakMYLp5Pc74^N@xj{X$lR#vYX~l|uE9Hp(@P zcopcy`SsF2++T)w4$(%-WP`Wy@N~mh(o}iYp<@GX+Dm{o7#NpVkXH!Y!QoLHT|;G* z!THdEJ!Svi-8i1dkQ>k#C3kZJSqJPkhJ8%~T0W5e(%4=oNmS0OF#^3YPUtat?w!1x z!Nqi(vMB!}d%_TuOX2hd@^T6@FVh}QR#yHH0UuKy_$kj!BbB1$&~Ekt`?H7TOEuwA zPK$pl_smu6u((=Qtx~9YYgxc!Tlv27g|fdIbqX=trSeD$rnZ{5t(yc%W4ho<9!m6e zfD<kas+>Hg#JuQcEYT<wJDuGgl~%&q@IfBr)s1u{71o-Xx+&jZ;#p;!>4k~RysPx^ znRVB)eIMDz%S;OKyS@W<Xt9j^bh2v=-d<%qT3gd`hr{``v*pywua*bj`R;P?&>@Ua z9fJ02XhVBgXQxBIqi<SH_=Gxj^qoC(x=dqOuhXV?9J>qW=K-iBzww{5Ap!EMIRME1 zyuvuU#Mt=isZ(5+%gMX%gNJw2$wd=G@6f{mCs>%@LZJzD&CSl0tBe;@Q<JdXdb#iZ zd&@3la^yGph0$!v5GViA|1HZw5*(J$PcB}#036E<%iS0zhf+To8^Ep4{(>&l@>6)U zD(A|omtK4!a_|sNRL8mMsE76-uKcyX(U5U4L=M4|@`mHs0**KH&ojyTz(Ws}9lOSG zD%l=7ot0(Q&p{E=aGgG>9wE=F(@DECue}BhE|+`nzpw1si^G>Ti*uLpNB#ln^eJyG zNXLfd+RtVtr^{uWBNxw|Ehq1}yX-%(KXgbRBaJdPP6cu*Ga@^vztcE8rzfY%)a3PY zeR3RU`%awhyV5rPu?`)_;=I8)UHed{yywWF@}av>^l_~B0AuBM@dLpeI-8*nc`r|G zl<`>t0FZUvI7S>(EjP49rf3*`@k@VJPQQ98e7L!eJY7K+gWD>>4C-jMxkjn{A<r2s zuptjK)|qaF`vecz#=g^`%Dr?(QdE#ogcYBWOXM-1w1gy88YCG%Oq7Fn&7IAEgNH+z zylbQYsTz4gI#@afSVFS~*E~^El2+8=k*oJLP1-qm;)V;Y`N?Z|2)>UT;3{8t;ExWI zW4(h+?2PTH4riQTz0s+`TUs&BN=wHfPsgbZb%^Lf>diifo*1daeN5ldHh=x6K2?q% zJ;;P`4-=`2X{U5}@UY!_kR!eD?IJusOTS&j2B<jIKCZ)AntDiwjZURYWW0}Q6In!B zhMqo)T;Lf=MK|Ro=?%V$?Btn8Gu+f4WUw6Dp~`3rq#VlZ(DrrwK*!NufZjTsdq(y| zUmhE)4rlcqWsNdYT}s}}L>FT&El9cOPAl`sS%Q0*oLOGR4xmrjuXI3Xf`fOppH-Tw zkBJN77u%`3?9_pX?mHY?N10yhsn@E*SigO?eO9Rvbn>Ut4E#f5>12wEZ|<b2?;y~c zwhDS3;;|gO7l-rlLuG6i4rki19`!1&7GayDrMUX6%9-scZ-%DU-xQWh3(59pZEY=> zrh!7K%W<ZcicBNDZ$93vyzOa(`Bo0Bxm0iZ7X7eXTP0U<cRZaV0N}Z=J&nV8qRd{s z46w@yE}F-I|JsEsIJ@Y>-Th@?n0{xV6rK~uS7nN_Df~toSeG(4^rdXub;F>C24I6e zXldG7XS3skz$gbg*d~LFKf?)(86_ZVfO@pS?2~KobR6UKyGl81gD!)Oa5$r{XkVwO z)X8KbW7{GVB<knu^nvhDU=YCC2h)GHGV!tjQvF~(vXJ)jSu3}sSCiMojtyHyg1d56 zI_Pk2W!%^(fgH9x?^ftP`W8&%m_3ReGdXd!y!iB2_&rlbNc+SSkCvm1#nQtu$Fagg zyX}MTdp!4V`G+hu*IT9}L4!k*)^=!f*Q$LFm*8;T#M%CpuY9R|?Q35xXV97Y`v!oq zyL{v$PnC~7^~2B{4=P$i`Z4l)d&w#OZTu0I+U~cnRHbK&Yd~w{aixj%)U&0fZDM=K z<F>u}jQ0u50$*YDc^^Snh&f~=eh2&ns4P5>n<#y)PrC-^pwBE@o?>Xip*UTB<2Qbz zy!hfv;phAAyRZD%kNsFVaq?st9O;b?2j>RV@AjwiP7C#SOL_a>*}v%t@i7R2@NPlU zfL?z~NBT6fTK@qqhtO$(i7$P4(olLX62PcVxI}=-=~qve-}&v|EzdstY;>dh33&YF zU;br+9rhxF4E9^W!E0b3;;T_cQe^|c&6HCrZ8iCABL!nE4eLaCAAx^PI809?7hnQ| zA4i7qT~6ycbTXnF{FMh)ZU|;Sa<v!!khfM=mxFt_M8_m@)VBSVzw@i*nP;9U$L=~- zKK8MXm3O`SUFGP}qd4aW<NMQI)#u>x?Kp3HNQF1QPo}r|r<QqZCD%TEYZcyFiMLi( zP31TM<8XBTZye5F`DedDG^)`YI`6s|?1pIsqjaj#!Za)m!*AYaK%p^o>KctIaI(6N zSQU5Q$2g}UR7!OKuJU|khQUPxZh&E-ccaWQKwZ3Y4ad?Zj51f2kOW4W7+KZ9dA*6l zb<=^8PT_#5V!ecN+lS(?GCN)FXV&H6_r9m>BSLurW5${OK@~g<Q3stR25^l;9e_q+ z#+cMFVjy*f_u#>Ul-ntnaeRt|(Y3SlIQtf7LzobUI!A~YXdP+d)kl<uf^QyYvGmXh z-6{b(!V*<Rc~KG+mcU|qY2yIVhhudWt;7L(jdwEa8n7!2t!Eaaa;<x?%n_|>l;=D& znI^(%8U^o%e)LDn-}%+QSB7vBNxw@tqn8-uX*64aC=#7nkQm4F#M*S~Q;3MW(V4<0 z92yEe<PmQfLE&w?*&#KiT8Fbrubr?Dhhjf7;lm?iz}q^UX&WLi#huK7Uz&+yoPp#W zfbN@=XQZ?3N@fQ1p)$*4!tBf(5pH{Nz>dWr93tA%8K~O%!G%seIyzKvt)+bALKLA{ zjQ^Kkd5zh(t7R`y=!fq(R(23I#du7#^AzW`&;S*`2%#rxQScL2@wDBxADbAiTL+S{ zMkYDK56JKU|3fPsY2km$kWTep{8cn79lD@p21)3$L0KInd_R%%>zyHZW(^t+;Yi;N z9~l+ii=syqt&V4^(7EWW+_h`dWs(Sp>r6)2R-&NOPsK2O&i3M;hO|yw2NNBk>r9qt z<k1+aBXPP8qg-wvY+pHbs(j(kK3AUk>gRAqUoRu{%U$q%2Y%=w{V<MkCo7gP+HIpQ zcytLx(tbWdTPU1WNHqpm5ztP^ctkmXP{N~QNFKJI$Oj%#`lv(UY+o@-I>suzrlYSN zv~3g5I1E*Mp`UzcIXbm<faM+@R-WXY1{D8n7kOK{(<ne<d(igaBfqy!aN%j|lcwf1 zpNDBGU!c4|Yvq=|rK@?IKr)SOZeIKJ!h7Fe)*d>ZNw6x=b>dWquRH@-q(_E!Xdev6 zS>)XE0`ja3mfZ(ODHBIs3?UM7sQ3zdbr>jBDT^~sC&KrxU&G-J|LoW|20g`*{zg`M zWX&s1ki9z47+`_j$k3^2qQy`s#&++;*~O$66MkbOgJp~emmSR94lzLYqj>amLw|VI zmeUj#RiVhgbOI`C>PR#wmH96)lcT~8-#1SZxglaXcq`vFZKMM2%7|*{*An8KY<NeS zTYEGrE~c=ZtI<U{5|^h*X88c?ecNY!l%u5wKY~xHGJjA>nRSx1_U*RbOdKfNQZv$( zf@@@$ty1f^j0%Gaa&3d^{Ix8p;6IK4DW6tnoL8TR7p1dl{1X71`}Ptt)H-?8w1#&c zv<zieM^Y`~hM`td__xAgOIjxcvEATb$DSJH=o_mC2>v_nJDIx1<lY7f*xH&CL^@)7 zFn})LbUwqx=R@Vd!9$6rs|Cx4@;-f%vUS8+uWc&yD@>^BaGuiP3=bS7!dZv2oka3P zaijhgh6<~Bk^8{1$awzpOD|<?xtrBZu8L8yG_Q7QE8FGVlwnR@+O`WuIOA}ho~{n( zd+)u62<08XR>v!880RFs=Xgm0;3^#;2B*%i^JmXS)~dAcM|T)u;!veuepc?pc(!gk z4~L{w&M7mTNPgk@=eb`kN6}lxoaCXL^i}HyR;lF!CuTR%iIkf@SI+7%e)+{0v#RI5 z2Z-**S>A^c-L{?hw*9ISBw(j4bW-WKJ5O}^<is_c?GI$!RX=I@MpCIWIsQlf0+R?R zhjgS(F&14#Pr8EB`R;q~WuoCAD|;FlPg*Buq*GcNf#g3YUu_t>=_KRLBo3BI9L@(0 z?T2p;(3j*ta*)5n_!~O1!a}~ZFWoaXT<+hwr;H4uyD>1<HWenR3w%&#ja6|voG(qT zmuo~gFEDngt0+=ML8YK|vi-%EzEIAcc^!J<5Jit%UY-YE#!j3Q@|W~B;2{%*R8pO$ zjPcE+x)IKq-~^!>*|`{)bkL~336`=Lm5As3rfliyA%7-C3%ksfBM*`{ZJ4|EmHo8# z2T|Fw*vKMHJyI@+imz;!9<Ia6vw3eiBh}?^X)WnCpi3N5@|%xjM4q)W!H!|1cn8PV z4TtmL(yPOnpaTn+-{mcq0ajdbnyN2uFy5vwY(+Rj103-~y*RjVIR6L#{-?^xV~1nx zIst3_0`FDb!uC=RTtvTiytLnoSLj2%ozOJcRfjV~&#&++cmDTY8s!;zlES=FL;UNL zOzM$lD^HWIK5x@{1p?AZ)mj@M1Fz0+`9>Yhl?dA2^q|r;f_{g-FhoT77^?{e(espx zPS!gSZae5)@9IMTr$mT`jF_VgC)VcSO;%p1k5J~SK@;%On)a6yAV!qSlk_<P`6;^_ zhuQ!Up6C;f<H|(-we8*Vzir$@hV-|zyM%w^A#Ndu{Mpda6yY1Lm9D~zPC~nATW!#` z2Uu}(_{0(P@X<GSI9mqgk<DUrsJqC&9=^-9Ubg<;9MRmS+e*OA%~)8}8c5jGqG7bW zX{_%J$2M46INtDn+Yf2-W=D9J7p=qDG}>P|xcc6*J;gl^XI85{`;~8$Ib`7s_FE7A z#&N-*j8kXMvziw>7`fIr$OH|m@N_swx5Y85J}SS7SFOW7U2nxQI$N;yp%n`QZLUm3 z*Gk*N#oE{1tX}BCi9EzOI)n{9%6PVul{50ClM2%_^J#C(=w)SAFX_7p?9u5Q{gR3; zPaDA%o6Ahxt)lyT)Ox5Mq+7Wb8n>_t7wKAkj-NH1Hy(n{eXGla{!N}5Bvt9KOb~{$ zPTa?^6>SM+Ze%)rM_M`d>TsT7?0fl{Z_u}<uqy}4lTSQWjvi?p&h$s<Wc99^`q2BI z5Q_g#j*ujbZSB%ad9qTj!W;kgkN>Fr#TUO=?!5C3=)7D${NW!gAN}Z4@n7gbi<L*) zMDD)@v@M^!MY6oE{atu&-%(4uxy<dq-wX>GAynZ{<+mFUHNQ<le-J-Qla!$;{UtKm z=gI^6j&`YOCnhG#umAc#E2qz#g|GV(IPu9(eyTi3FyGj&f%v4hgwl-)-^N`ax~2T- zJ0w?s79oGz-^5LRwlDa*TSvOj9QaAEo>=pWF#ky#JDmLDubn9r24HB@+BdbUO=F?z zH_;~<t}mUxRQ~a={S#K8UyN_Tm9f9_cYmeab^JI!2xv(8j&)w)SW4yEFj#(75c1qV z*4qZuY(2aUH`Zmnwlm!~xQVNHsN0LH5K0%v)6fyRNJq!xK~{$g_A0@C`akuP^)R{S zZVBf9@Bh*NT)y`8udy<CZ~5`R`s3xnhaSXkaAhLn3Vx9-+m&j>u^!$*>kvY{K^QBX zdDJGmE!W#$qF}XcdRsuO1vW)Nk3anV-{1WF|MHtr9vl^2>K2m0%{py*8Jv1tT8M*l znSoK_8OamH%Z9WEgSXC3XB%wD5tOV+qKI`qxy^wLzRE1rCZlopU|*R-Nqq?e=;d=4 z$~sOcXLWmq8OU&Ixr95$2a1e_N4Jh=s?f1Ew>-xH&2yC6dkJm-0MS1C7$_Hs_GQ%0 zvUMFrMyF(8V({_mlK<+cbI`6cIc^!^F=d1?IPcoEi)|pL%ltA<HaenCC!H!XR*gKa zTZm*SG89@uDb(qtG9aEBBLmbkpyP}B6>u$M58>ETah47eYXdsDRH~~n`Vxgi8FBgp z^9+X5vV%4B)e%3zlB)?|TcXU5JoT~i4}a~~N(V>f#VeOf4|UEms0J=HG$V@bIO~1X z1FaIRLkAnA9h}wC0T(BltsI5G4rp2iI?A_WY9wo@f4jqZl#X46RE>zKI4XIpOC{GH zY-Fx98P@oNVT`JF20zQRXitsU2znyLj6SzM6=i33RTzu_Qz?K<g&2Au)d@RMp8eMI z<qA=|2Z*eD@S%4wQ$0ci{&JZhqIn#HR{nE>K*y=eu-A!()9Kdfav}tDp@Z~S0KMVZ z#L3VeNC+cTt<z}HD#Uq7emi0n`rJ`qqMLv{1~+^qJv*EpMuh5U9t6fdoC`~<Jvhm) z$LZl#7-R75egxTp1N*YXOQGq~(|}m3E7utqXNh>0|E#~ehb?E=szln#cdY|dSnM-( znXsF8v~BA^qvYKzyNUk3cJ)$u@wqRTXP<t$TzLKUvUGi_jKC{9m_gseWP(e(HMVsA zsQBpocgqf=&*6sPT!lCEfrj=I9Tyr(9u9i)mk~YE+e1=ojCnY?**}H9rDGgaByxhw z{Fdo*ZClD!1h&2gs7`eq0uGYqm0xuNYb5J{)_Gz7vu?M_&|#n~$;27?s&hto9891I zaCx;{pD7=tsqlOF+rwq-PM`>v&vZJr+e|FH_kE?j`)(#RbSf+RFf4ThqqHj<asVf_ zG!ExkqS$TY{&Mj6ekLDSG6@W=sbIvfM@u^epAqIRt)0VZeEIx*_-XgS-54Xl3oJ%B zgAwWASVuSL;ABBZBUJ+yhx3(dL>Nvll->Ie;;h<%vy5mJ()A;6N0~?(qKyZc2pH%` z-s9X6^0bR4c6h7Gi0VML7g(oN8L_3KwW*uxeOE`@h5^LKf4&QUc`si&xWgySKMS-C zQ?FNPLAiC{<|X-cHhY@igV+4Yf1WjcJI{TQER-ibDqZtTIFcQCMP}tz_$eLF{tito znE#RCN!&aS-&nT%Cmz&kS){l9W885sPVy&z^V-6sm`RPgQbYuV=5OBfu$H&=vc3(H z6=ur?x(Z*a6;5c>q_Nb%#kHl8g*d*5hRGZ!q_GBQXf2(sGH1=FTyrVA%f?*&v4OK$ zhqKYn=gwU&XU<+I_uPA5wpY-x(zdr`PT90=$Og{RpFtRh^CDYnoXwURI&u%+ac3qB zLz$-CZ}6I?Gi8|{_#Cg?R^sIs*;0ePc=!GH$KmW2Up9$H#alc%C2&fhbO2eP4^I%? zJA+PQyWDfn-Q;JYlf11wfQpeb_U)9XpNv!f)8TyP_1C0oCbah<vxgXGs44Ykf>E8r zCmAzpzfnHxbQb34zxA!iYojG}Ry%nZBLLj}C&cPjj;qmsz(MCljdENjs{ExyINvMo zIGlTtqqW^Dj=>pRmE9?iyuMd9PEAjji|3*J)I_=Ofd`@cUi1$QRcozB<S~6K4(A4@ zb@U01`s+;Mj<fyP1m`_O106i9!@2Sgm8Abb2<qiv!p*4D*5Paw<JYd?a2_YZe1ff} z4(Dtg-a^oggT=gzIJCLt_LgHf(vG7)jNmNj-sW&_7)wIM*}Tex$c2g3GBJx|p9zv4 zqrn=P<hapM76Ri}zWmj4fe7t5?ikmWmS!_<uddF8H=`%fR*9x^e4!6GNpHlAv{AoX zZC3VdtS!+lI9j2%6Qk-i;vuhe7{kMZj5%RLo^L{rb~02vO`F3GsR*H*`j2vC0uTCI zr;BluLVcv1HzQrCZ0cz=nWy}3fvL<@E<9|@@I8lJFbS<MrxL#5Ij)hrjLi@$_tHy; zR0juf?*L9jB6f%NGP#5U)d*){l`fmmWCPn^6Wzy1@aSBOr%qmIFL=$08R*kb5JW%5 z{a^j$$ICnJJBi*mK))i5Wzi=^qIEdSgV~0KNVGVdMM)Y3&qnr=UL2&WclAAYCL%gv zOAhjG>#!P9t5=6aZJ9i!8Eg4TQE3wzLI21wvr?aZ(!*`5bOdW(*vF#}JE6`BzWz}n z_@SpVwwM0s3QGIBI<C5b<7fgDqEk63<(64<(OI0d&q^~VER-ME8HsQXtt*`~F+?Qf z0Q!h4)pp`A96{GqH<I5afighdB2EXck@d|usD!9Ty@qAXlziePA4(7YaL5myc?Mrg ztPON5VRce+&&hkr;k(&pXgAJF<w7mI$tx`NOe@zSx8Ai$A;}h0?Xz2TIBzR5SsSqJ zT48q|Zigv}_+!4C^S1Ba?An&wzJny8i9vB~VJ&4%ld^dr9_BUbc4lU=Jo6V{F7s>^ zIZM=SkG$U$eEsURa-HoGC$L*qI`9%UwW~t4K`pK2>F_E~?DDp=b^15$Do~!vK%Q4d zm)`-BGtOpgFjs<fQT8DHIZkbO$<<2oi5Ul|bAU0%AQNVva%M7+_tvGvQ?FRF-=k+b z0iwe>lcn^DYE#-bNr(Kq!Aoi|sUr9!$OAkaJv{_n#LOR_;IVndU3{&#ZdvA}I8G#( zSKiz;#_HSHkN5#_g1a@LeC*1?AyxxTG5);NIGjfaws_*n$Fn_EWF7g{GrS)r2;&2{ z8sQv>Z{<%~B67!e^k^lFzqjA#9m!`Iv;XzK`M=7aeD;sCj9;hzyWjOLBC{VahYufV z=&PP}s}AQ1Ln{9+f08PHDxBXX>G$}`@@`+5p_)8>)8Vv%+^K`pYqmb(nRZ@$Lv**x zm#&uI`@KIXufF;^lO;=8t@epee6l=15XG+D!{M_q-%Vw|ou5K;D@U73e)rH8X~&=R zDLO&=5~#;*k)hlz9+s)0_Jw35zxJ$lR&*QWwl)fx(R;YJpOe0wnB4LSp}$-_d$IiE z|KZolMYiU2BFq(i|Ls5c2hsOkd9FUT!m1@e6TsT4+_x><svm(PweW|RH~74L^Y*Sc z*K>1e%8&L?Kh{qZJD%VwhSuogmA+lU)A18wh3*nEmH+C${(JarE|(wp!28Ohk3CY3 z9lsO)Q1><nmZWW4P)XV?I7$dxf+N3ki5Pw>cw1P%x9c_}zqgEUn!2*x?JaYAMV;UK z7yn}O*Z=N+8K%sBtSIb8ruK6Vq3{oKj-tfqpwI~`gK0<^jcgQD7@YxTH<1q-Q7%1n zS;~B7J&A0L;)Qd8a&3i0A|Dn}M9++mm*>x2C=(3A>%1Gn36kX`C~uoQD=Y(7aa4gf zYE<UlBqCr$=P?)@Bg*Lh<9C%Im8mFZz>=jV3`msW78!Afz!`(Uqv57AxkG1>=^R+? zzzalD*fEWI)~FEvL_?D%4l-teXJ)IDFAgX2xhJGbfcbPXShj<k@7*I;C#OcH9bKB~ z7>lEqvSobp_GvIumQl_cHV)p|`wBd#G4gcLtsoedi4@Z5d}VwB_!&eY#K%7V@$$F+ z_Aix#M~{}%7cXSbAzW&i1?@wb&~ev`LrR$1QwO^^>pZgy#32S>X&hBShLJ#hwymf6 zIv6>!o=dQddUc7{c87B}d&ikhA*O&-h?#zd!O}gbbvQd=(K;})moaVXzF~X!?gO6c zu-CDpVdCD4V<-+P1TK@H8O!<t(ODRZMl`#RxXZZR2h;6bT%PTI)=L@~)NFK^ZKl&# z!ywK$;9FRn7R10RMiB<U*&ZE~yBp7{LSs0LhJnJqD%<3w-29`kC_&rki-ny@8zWL| zYx}?$&b^&`_uz2G2<{#Qj&)#mB4!c3!_dWO-NW)?_vPHL696F=Ar4@|D?d0;TAppQ zywX#~<pUi0I-#=<G#PAHPZcf=A@6MmVH9=;T7PR4b~f3M^a4?eFT7A*fBwaC<(1dV zAnm-5J;Fv%K-YmuA?(stg{lV98f`PjwmJ&TUg)mTYaR9@PvP^lKIt!iYp{DbnWKRe z9B5Gcj69P;lkzgbM7}r@p|8fTk*|!7ES1tA6$S@K;jcWFvMAI3W?K81PHdy7<*5*l zv@RK{#w=y{oI`rFXXF?LokSNdBe3JtR0aW)<y)?UvF+|KQnv-sp$;r4e`Aln7hZ$r zMmEKP3g5tdX#-%OK<J6Hf;OKg(s1%B6L%}!W&fQxoS9UKkqGw!bl|Iha~q`z<WQQI zP(bHd(moZ3^WMYz5-IOCM=(Z|{P3ns%xSw}1y^SY*Nd0ff``4%_Z&RjIGhK`<G%E4 zH^f#(11J#ydO(H0{j}MT`=t}PSe?-<qoi#uQW%sIkSX*`^p!NC?ieAoPa+mu+RDe~ z^A89~s~8HjQ#(kj3}mo34{e_4Vfz|DNxNzQ=(w{W%kUHq>gBgZx9#YAjgU66&)d2y zAT_NSt0GrRFqyDPyT~!hN!{?Q_1ph^E)TVJc}*VkHK+B<U*?HC^|_USq&3Mo@~-Kd zZoyM=t#C;T;fi8NeWvqh@i0FRlg2u#lBnUAMEt3FT6j{Y<@nxwUaU{DkbleREX<r0 zC(@87GKaREVJuz1pmV>#O(L7C!?~b@US;Lb<#Oj;$FnE+5E1fjGZE(oh<Me}(kfj} zTEmF&|5CYx0_*k`RD&EpT6XQ-%LGkr^T5#5U&jL=1_AMPe0AJ<<z=?iV5PwE`|eFd zRvnK;3IsV@{A*i^FN{bT3v5wz?feBMk7h`>Sx(-4cUIPf@0z^U9~_`ZEywcc)x6i) z{n{(9hVHvqO|y#?Dg)>jj@dk{^y5}J=h@O<`66IWxP9we&qbCWz0)OmjHOKCwfaL~ zPaB!M%DNN+J(T~;$of}beHEQzkqG7ch)83l5#xLvo1ix^00hNoK!`JK4x>qWW#u&E z@rCnem|Pz(E{}BY?CNl)J`VeyI7_$ID3B~Nj!va(m#?t@{IyKZ-*c}K&IjUfreaei zpZNnb&vfXm<A?&9z;umhEgjCYGn3`;(L)$8M3w=wSqxsNJV^a)xz@poLduqtY^8Am z2i*w!Zzk$4<)<f5qZG#IAu@V}NstQ@Ov=x}BN#!w=m^!}OxwX*iSVSZuYURKIGoSH zORjin9nQ$*Rld8B{hZ-_+DYf3^1z89gB-Fo40KVaa{RP^yRWnR>Dp)2ZB}`op02#N zpZhy}AbotJZUr$t8e>EZat}Xl@ooCCl&2-xH@&dpB>72$I>N04<3e<kX{0k3XlA`W zLe8Y%JoZ(d$rqtqc+02oIBDxMep6NCuMTI@$WLxl<{r*HgF2jd;c#XTXC|fl2qsb6 zs#}ie6h$XxEOBd%M7%myGA^v^gpvlzWpM8^S{hyW<3IAl<p<u$qzOS7ZjTe^kwAl^ ze2}fM;71+K>XGi_ESizq!L!Qb&;?pnxhkU4ppki8<tvkC|N4d|{ub-dtx_lS@^!|~ zEsL<Bjm0X@!sk#C+JvS&HbtE6;AkPe=*N8ntQH#Eot2hCqAsyPv|<nXfH(~3ct*!f z>2bojVoKeJZ#;l!)xY6M>8TEmz0f+Gv%QP<gY=~A0eD~ty>17xWK?-#+0e~?<ze3w z?z-%kU)*Or;hjn33IDc7`fu|?Ik5eAO-EX3YMb(Y1DTZl{jpDWA3s@++;eByv3F;j zdyT6zrPaD>2}0f;X^R`x+x*+0si~S~YqNaYdtcaOH>YbKw9lpe_j?HEcRDQB_bp!H zuyt@BhdF8DaHfB1|4cLS|ID9%smvn_=dWL5dJW#75YKtGeA1qo@Vgs$u{%zl(Pz}L z#Zp|OC-}?qt*qf$+g8pBqj9e-WDr6+w^w=B{*R6tJBi63x6K(Oidv_(dVM!_8MI>= z&S@DjuMXYId&isD^6CrJ1T?W-m2H`PqR;!Sr;OdmPUT&l=uQgY5EhRrjl8RNr@SUU zU?V|=od>=XXK89((b0IGe|gXJBz}Tm4PHB05!2-=3npsZ16{pcUB=ac!#IfIaDMh1 z=ns=wJ^RFykCnTK91h*=<4(j=w*gQexa|?n756H4#7ipFYjE6luk4lPPC)$|9L|6A zM}L%{B=w%V(OW+Bp%0aJyyG3ft$wO)g)HBqZHj)=KW*QC)0f*G2Gaa#;oJ7|ZQWYl z?JHB9+W?&wEWwU!g+Fe-%8yR?Ip&-`eFmH8GEwB$2w=NLpPVf}icjUPyN(mYhTjOi z;da6*RNw2-Qp(=q@B?esK2N`}Z#cGeaGd7kUG`AtYI<QejkcvaZGs0GPvRTlt-sYh z?Njo+`jx9MOuMqM!uD%t%K!eq{%^>uy6eF(!4;qR#b1oh?f8;0g*=eCwy3bBR{k{i z+~tVq;iXV{-masikL9)ZZ&tp~9LwU5;2Qq~?Yo-Qo8XMC;tD$PSC(v`LoTyr$OPXk z`5*tMe-dBDlOKJ8ZRmEh4d5LFYwTf?uJxx>dDH?B+6NeASc5NDX^``FA>Womxo?JZ z`}+I2wz}x|llNBgbpGW(|J}`B`q`hhRd6sE<;K8+Fmo#e8P<J}ccIV>!l3SV>^@;S zqjju$@75LbG|p}!7Id;H=#4a-Au>~^qaTYin%7?AOzNsL_c%(<ljm!%yjD)(NZep1 zcZ3be*VxBw9Yc2zWmo6dFoUA!4q$NW1(){kVkzt@<@QtF7>>(s20Ej%HE3s0Qtb>z z9b^jvVAN@%!&d=5JvWVF$lysQ(}|>TZ;ewOvI=pR7Dx*j(<mIHf@jHVq>u)#9e)7> z)Tre+UZ_7#3g9u1G(;LCGSWdbPB~~-1&1?H>}N~4c3d6K4$6Lf&`upAfZyz@P}bmB zx1yMpzRbeS;AB);ScJY);Q!8tA1=T8-~9b@7smHFKIU_kWvku5=LYIJ7@f^gffZl} zFkw?!5nqLjhjic(&u}!8wsm+!;Y1j<1Ha2u`)Jc%6(H%N(m_Y<!a!^f8Pz&8vi;D3 zd@x8G_H)`TmT;mkLt7(oM%nsg2TQrcTj##?Q;~ML@-9E}h|_BThx3I?*UD=z5!J?| zz>y<IGt+BiunyPrI1t?5u9u}}T}03HFqqh0!r>BG`FEqauCZiMoOB#T$Wq_-W0MFg z3E}%V3{>i&zsV$(d||Ydcw0_rMSAHQT9MC)(z*oF=qDV%z#>ee%!qYk3=m^ZyZiA> zj0K{$bX@uorEAx&P_+^01LeSe_SI#7%psIO@zBv?pNSv?;B1h;#C9}Hfaq+$&QfQc z&cYy{G5$~ouu^t-Rd^{|B*aU8@9x(5iBlY!&N$$*U(;zm5-@%mV;p6-2j}P>_CL2z zxwK0fEV}F%nrtx0Xv}vL@lg3$C03r+h_73=SZ`qGw})`)9Jjv-r)}+EC$H3Y2T#&w zAZzHWu?AaaP;C`Y9n+R&|8`%;L>*H`%0Wq%-*k?I4wO%2ab~ymSiWuVd+Rm74u!T& zGk{YkWDian;Nf%dYs(aecEUynYxm=im0chCKqfcjkuK;0cUTH_z*CUkK4paS8cvNx zCaSJnL@q9DmV?KR@bRyaIC|v?S}5>k2$Sdh2QWrB`w^5mmN;HKH_0B(LuJ=~KRQNa zigLAakO;Vg8rf`aWFT;O((adVIA5EX#ld$VlOXP4M}inA11^<>HtJY|EMM;@vd}$K z?Yl;~^ir5SK;p<NdP(?O*{9P%14SP2sE$zJZeXZS{p$ljQPv12rwV|^Yx))SBpQ*5 zY^U~+2S{4!!cFC0RY~b(JvY*Z&rQrDoo-dOg_=#9Hf5P6+*RQWEC3dRhc~vPJfl<A zJ`<Tq9?PrMQ31crm$L!3yD?ZI6KFGQ2`(fT@78%OfZ-K!4fv+C$SRxdBi3mhwNCI& zm9@T#Tbs9qrRI^>>T#n?@1&NMMed77``f<EDLhu0{TnmE1)me$ytL$Y5EyYd^*rs; zmoJaQPgigp9_7P(yW=>uI1kH+GaLF@pO5PaZa7QEaay|4MKJdsIGFrS0NdB>lhR9A zLYE4-r6N~xSR-RjzxG-t=}z2pk`*wc$VQ#6R#ov627#zDqj^R-I-IYZKgV9k^WotW zCr@M*jr>$k>y$qBd1+B;P0Iy-KN|SzD~-dM2|}ID1N6gCI|x?U5~G;L7IVu`u6Zi2 zUSfhz9=Pko@k|yu;T#81YOp3T<&<uo{L^?}A+K<sVIO|w?0pa3&qNg~jl!cX%>;tn z7T_KA2#Zh6<0>w<#F%H?Fhbf1+e`$CCv_=PlaJqNL<+Kg8P~~CCn()k!#$+$zULky zUHG^TlMFVLDW$jgn%D6`VWE>9il&^)Oo|)b?7qov$KjS57H{4}^a^NZh^05W5>Z<x z`n$?W90hN5IGar*J(-ZiDYJrO_B;{J*XM|A!&orlJ}}sp@Rk#&w((b4#(v@4`HZQ4 zplxYsj`7>cT)y|PDo-NUbnwAz(k>2X#`H`!BCBjiC+U<EYdBZkIwEb%JIBVLFJp%m z(%%+Ua7q^BKk4cLWg8UgYNARz%T;PP$>GsDoOzP|pOsVOOAr9gMrkMgb4d3}k}5lR zXesFzrVG{VD0vD%@HqEzfLI2PrIB=NWv343f|Iz1iRiu&9Ep3`27@g%`r$osQwLK1 zJ3$?~#Nn*oC7pN<EfWDu+77?{#)uyr`=O^kT7K|-@65-#4G?L!FsbOEyU_n^Gq;hM zMvqiSbPNm~B(n5HE_;OBA#13SdVMY}tFwzVpjUaba*ov4PCJU@cTKYuT^^cAD@aB^ zb0S$9Dx194139z05L)<j02&SQv9}$&(cjqC&p?tDB9~W~s3##Q{9to6ZUX@hXX)b@ z<36)~)LHo;JrYR|9SvMrr~k!?hc2dL&%Cr;wwf6+r~x~~XmPj8NE?PHlxtO{cG0&Z z+ag;l?A(eCWwp3e{CSYWzTgqM<*rHF&_48~eOA~9)a_+<9Xno*+<O;WeevC#0c0|H zYWc8GQ-v2xmDV0MWy`+)mVa+R<C9xEY~R1^Ls;MJ5Psj`U%iQ%^?6_;jd;svt`?b^ zoGZ_K@k?ca?VT2oi9PCmyfhMXg$dDFbntQZHlK2J5xUu?I<FJB)|Ij<F!HK*mYV}$ zGPx^IoY6ni3drLqhK_NxjN`p0cB;IQj|RGu!H8%2r~F<UhQOdWoU8rp1f_6zT8=u3 zI<qrj_D5ww-ESPeM%KmQ3?IounV1F0DvzX11=?|=9Xs-@g&oY|APQon74MYg1N(nH zb>REG2zh-64(ARZdbW=&(dV=U>^I8vVeoLm^JN^)i;I&4G!2x;*;3>9mcv;)qK;KM zoIm*fCsXt7`qRprwyDISww^V-@m^e9>aRWX$N%<^a5(=z_%Hf1{_Nksue|GB?_@9M zkAk=QX>~fM{I>wMrTtqZlhmQNaNX8JKEI6x3SA^&Q)tFNo@HdLECWAKXLFw*LfC(N zVyZlkF6O??uEal$UiG=peXe}`-}^*91nufjSM}a*{BIR|(XpG_MGy&Fa8w!2I}-R# znWLa}@qsEA!v+0-llO{mSDvKJNo+sJ%02RUZ(q{+ZWCLdUEVS^n`bAN%PTLQDqsET zSIa}}AYi{d!^*^`KK4|6URJA~KDN`9>b2g8mljgt<Gww7*S3Lm-LB&ebu@*(S@}K_ zU**9F+qUXxcGa@B(5_vh&;i>9V$$7^U-$$GcvxW{>u0|CZ29K1-z=_X^qVgiE?po3 z{(iOr<b%i99X)&<*YUcQWy;vpA7XG1fb}=@;3ntoLcT4Ba#Kh9`!-y+@VO0Ty;%{R zfBw5Tod4F}jN&9W>s&G7wjBTz#98_Y<7pGHVzTrj>~``2sym378^P(jiR148TL-u| z;XKBjjyIjMt;0HBUPgJ+uyMI%FOJ127~sp#JzriQCvtUQ7fZW|c4fA7m=DzL-?^*o z#sNEuLe)?2bBhF*e(y4}2MSNKtpI&1FncxHRYmRE!ZdXdjYVA!9~zH|&_+piKwKok zneG>-kpewR83j6n>z<14`J%&Cg~~xyT3DY>VwJf#rKvDm2tbF{p&LgF@9p5i>c=#~ z)YPACHo(I&Jv2To)3j9)smi-w0FFbHH16}PGT_z|(?o>L;HX-nOh4w}UbffS$9RT8 z{lg5JKlcm2P#%2$`!Kj>%Vna*=jIlYSLNP16(r(WanU$*W*A4J?W&~V5RbYiu}W~$ ziO9zf{xegCqgg}Fj|XmdIODcY{`QYJX_#p!7~yS%vkqrz=?5NGc-KZt+sTb6w~cg& z>m(gUAPk~ByX<uW1>pjQu3Lnh#7IAJ;zW!Xqop)vJatfyvd`lN`|hmL{wn$Mt&ujf zeCTKe=Z4ChJSQz$M~<j%Ke~x<_E`*dX-3P$35e9FPLQg=+ZQZ9?M{X`ks1M>NFUm# zBh55Ifu}<o?jRbjpM7_imyG5nnt*4{D7vkNdpLuBB6+4zK$kGcZKr*E_mzD{q0v4% zRTO2?b$(fgK4l00imO{}xb22f_ZviB^+87`jhu9_-OXovd#ZeOm?W@FKQ8Dbl9NT3 zUVgQld;U~;fvq;iFP|xgsDB5F*Cu^bgJFeL37C&;^CI2pzbdA*b$iM))+4++ob6lN zdCR(ESdva&uzuTJacN!;(_3EXYg_Tm`?Lx7_Bm<eM3Uv}EcRZ<2?@i`wu@29X<rR| zo>L_GYLtlmOImtZ2Bias5dsd%&=t8M3_5ak^z%5s(+<!|Se@+f@Y&|050^bpeJFK^ zR~*hb7gWN%ca%{%*5SO4!+8lO|An*HiSk@4huzDS$+IE07(#ugMEhFpd%_=?0swJ1 z1J^u;$d&Vx_yCxUW9jNB+s*`6aE|F1tOfu8KmbWZK~!Qzp7<&vTe#;rjY5?FYPoV{ zlK#Zkx#=sTY$Y(tUVT!*I{Y9E6?3}ZzWa*faK?BY0KY+ab&z}a?>356es<tA3NVTb zG;^Q%^ey?F@@!SxRhT4T>mZdE)ueo?Op#yQ3*2oHJj3UdB{8K#WMSIh^p!TYi+x7E z$YJu-LQRzE5uT(jpL<wN`hAmfD=+U%<2#>OhesU~$WIxG#uj4h1Fp7Af66mKCVw>c zth4sh)JI~=(y3$FI%t#^@|(Pq$uZ?s{t17@vBgzbT3ozOU!dYv9#v?_t$b_pnuh9f z<`2J<PuQSssA7T!^f*|7r5Z0NT{sVnQu1rfd}skVs?!-~8IHW1+Z@hrYvg!u{}Zp^ zC%;<@&vH<e^jCk7N2aE(XIwypl-+yx!-qRadqcKL6Z?3^DrlK@fyXo=9iJ|s_$tGW zpCl56$m$v)T=BL4i5kDsm!U-dfoitYxPsGDCzd+MvEz4TC5<#mThLBvcdzoO4Q!ue z@(l#C2lVOJUr+fv+0J4oPG`S!;R928#0d5WG^kE%yPqGxWhDw*V!iUpDUx@w2l74H z3QC^0?Q1`=9RH=d(A2)^IA(P99QiK-zw+(A2XHvk_w9?~8$RGB6Q#}g*9cGE)sH&4 zhw>Ds4nFr_-pTf1W=<3+X{5Wb$r$o(lx5yK3GDJ@R~Wg(*VSyt8HZKETUj8TC09ts zA0x#)vW=3$f_LZ6o@OaIvJ2(W301fB2ym&>NzppN>%N4HjO6Jp$1#3RGV$z|8g&n6 z>j;4Zr|>W1Z1&XQJgLK()o=zEz*NC6@(nsU-hS<y&%i&d24fsqXFOZtTOD!kEziQ+ ze4_-~8EoJ-5%TIPWhtZDachIV;g}-~>+O~r@O|Es-a{vgca;|^9V^Vr%L=={^Q^hn zoXMW{55fG2x2kf4sI++doI2ps2x4h3n}!c~7d?kd27()X&;-h%IGC*^TbNLW<?y`9 z8479m-`~tAKt?9<nb7YYW}MRD%(WjQU1+l1gX4f(YM>Vw$(uc#r6GK3)HB57^xiF} za5z)uM;?2;Joe%Dm0j?#D<oS3SZsBKxvhrIfkh@aoG5XU!!m3W=_V<-aPUXj=WqXc zb<E>lnbSI)Wx*u!4L|%Do~;a6iDwdIfm6f0bgdGXN}Fsw1Rav6l?|k^9o7kukyOg7 zv0Vp<e8S<pht)?ozm&<Dpe6`rm8}4EF8eKqK4*3t2$XB~X_x;icQcN{bILgB=Y;<n zHcK4Mp(l=e;4~P(Ed++J6Nc2w)e(8#wxid`cIc^muD|PhDi6$FL$~~f`XQhX>v)p) zmC)YiaNHJe&kgjaRU&cSMrGv4o#oJdC(2GH!gun02yH~M3>!(S=HA=(%rl>R!_hvE z?5U4#>F>8WoGGX+vn{}~^Kjd{?fp(T+oMH!`?L1ln_WY;R8aA4^LrIGX>48iIgmLk z>}Nk)Uik8t$`aopTAbnAL%j9llQ2Tr<QqcviCMq9!Rn$pfOeCib)39bk-E5Z91lNc z;;2^c---r*0Y1Fo6Yu>8@8(q2(+~aTk`c~E<-5IM9}eey#28&!-N*6Jam=w>{_4XC z=T>*x%F$^6rs{$4Dt4;<IChD=!RZ8B>r9T23I>%Pk&oiTnf@DMRr(39{AJk<LiJJb zul*e{7k;&Wg}>o*zeUnXU=b0{Owz2dIx>1DW9VSJrN*;g2hO>C8_16a9&x1&)oIsh z-&^4jeufWy;G^8%&cm|BmuqBs`wI%B;rvsdA$0<eFTV1XFPG1M?oSd}WE%_-lyv;~ ziSm;_`IF#}yfRQKG4kfRJx3tTpBARuQ?7VdD%_s(gs#fuT56RWJZ)rre)H3}-a9s{ z5BOcAQ>RXq_x-^8(8K!5m%jXs@|(Z;o8>dV^h@RLlPAOHwNY*loNXz$ihbba4_$ym z1eE2q6uU`#s5+@qIMgHJ6(8+zp6=#Ephx-|g$-h7Mpxh&rfhU71qwqC!GNxec5=SE zT)T3uoO<!)=*sVT&wE%|eyRM~7rsz_=4XB;L2-07oUP`meOCgvVCCAvn%a5C@7gxC zEt<z~`_k6=oeFBe$ZN+o<%#}CX_-C`-IkV}7&pqf8)v%TjX=I=>nv~Zy^+cCC!hOl z?Bx?DkC*43f3`gQ$iwBxQDg@CWCGNzq^+poyCBTNyb?%GX^`_f0sH+vr`)#s@3)AX z^F<H1`QdH+-T9YnsqriS*)Jfxs-h7mnw*Ic_TIgUmr<5fhVbZx%h^5*M{p_ocI@V( z7;L4%{ZX7CyLPa@2|Yol>kv*#x57{foWlv-Czmo(tn-nNL6$8n(a;x&ZuVnV14L1b zp*%5ZkXhAy$O?y#x|vJ!jPUDc(Cxzz(UCdN*@g3=2dA2Q=&b;s&VeopaG=bdt~9ht z@h}63`}*qCRB>NK0W>PKbuO7+BgIoANruySlVyD8GFGoT@Z8d24X2*R98Nw5b)!*j zbQ{Wn78GJAx{s{RH}`}xe>Gm%-oY(Acy4*Tp!4z(G!;+s%ES~yVKrKmkspPdrE3hD zMx^LeT*7&WRK&=dDwC9T?|a@=e)d2Ag>wIU-i<*pRIan{-E|zktF{$o#nC`LDz?_C z!$aI72<Uy{pkeHL;cpdt1(n)>c=h1WZym+k9nS210<bp@)9N^JLcj?Jqa+jY4TWqU zzv4Yg^oJ26*Ku^(^WEdy**0f!b!;v2(Ugl9&-3xWtJzokeSDbB$aX*cWJIvhG-D_i ze&kN)v`ZP;b|*^RJP~<11l_t|9mQ=0+8OPfk5vMu?c@=~x!&e)H<3K;A&=0K;T6ax zh~&$k&~vL0pYm9NrJ}WpVeX`c(f`t64mkX1;Eug}h%DWWVDCkU>-=S}CCb%#Hi9GC zJ%MzhN&l<kSBM_G6kZr(lH|aF193d-MD|0A7q7VuM~!k(@r%O;Aa$O)|F|EV(NIa` z5wOIW(ewlP&%S8%s*Yo~wo!>3L<q05oO6vW8_vD*YWdbPUnz4qC)Q?A%y2BbN8kcR zpC9a`V@te5S;dH<Zm%9Xm8FeBUHbYFPLDbAI=dL&fG#lxfkQsjVdQDP)<_Qz`kTC- zP4U4|2WuSK)Mc$sQm91RU$fm0<!2QI{H^0ZD-gJv&w7MG2Z7Ep3%6h1eCSkY--(;> zcy&<nP#*f*f89?$QTG4Hqk+X|I$Jh0vf-a@qoOqI;rUJn!y0<8z#|vVOfVs{T=pHg zqi%135{alyo;ZzwQ8>lVLo--IUjDy!@j68kl`=Y<eO#Sbu#XCv+jzvG&}57gnl^_q z^AXC4$$8`~t3)vLckK2<o!~EQO?1DGZ5=x~;gLS@9)N#Gn3xzqS?ObGdq;XhGlzm4 z(uaDLTN<9ei2OjgQw|85?bAA0y$?n_U%{AO!U^xHn0gvvQ-QBeVv@=L%^^*6ggas5 zd*4w#N6lle^*;aVi{$h<S!*(`Tfez8*%n_4FNcP@MVjTtVI7{9WeGK(1>_A^jX=n? zCBti5XcW+X@LQbF<TKJBPEOjf9TRw*_tH#S%5xslTE0rb4eWVteW4}4gr_}$%;(`x zvWd6QrcZIL&nu0@CuIY<ve}6&#~BS?mzQ;Q<V$3-<F>n$BV=8|dhXoCa`x<b6t6qj z4rmX&;WkS;vnZdB0Sl|(2PSUfEb$5tPcR{>d{&0-(c#>D;CBoD77wrHN&e=_{l)X= z8IRY>zC$PS5nFkoJye**$F|YIRm%hpU~y^SEC#;YfJyr!cO1#MEN!Z>iBl3<D-Wcf zbnBp}bg^ZW{lpa^S6G6nQR)htQJl{Gj6Fz()F%wqU15L@{PTr!P<=&*^O@79<Lo|h z@<diMxer|Q4Emt`&@8q(S!y{vaD_{CIM0-;SFVJYPTq4j4lVYpM9#_|=Ci(5b_l<4 zh>I(|lpB5+c@}5Cle9)C?<7Jy69ph@ed*KG-L@IoLk~zEhq)gdRELw8cku0u-TTOI zKQxa3a7r^DRKuNHtsx4R_g{bY6#CM1wh-Efvw0`q6M$g+r~Q<f=x>g@-RN(fO%0>o za#s&qpYVHl%i&CU){#Hlkbi{;=VkX5pJ0NTj|LjyY=oN8eQ5(|(MEoL<GF9)IOikM zaX91PW1B5`bD1&I$ZP4h${44tO+Q3-wkz1=L&pWT36Vzb->e>}tdpi9pXc-uo#)cR zcXcuWGC-He!@%D5Z}U)ILqBO~Mp`7P{9~Cp>|6D&Nngp}Q<Jn@Xl{QgXE*V7ZRO#& z^onx2mB#nBAvA|qBAc75_pV^mG1c9VLyF*%!99oKa2{YEXKS&K*={!?oNExk2K22C zXRg`}ATJ;G;BZ#&d;F2d%99VjpH);lpgVcC<XxToHM&{D*HsBq6K)?i3y!VBIaInq z7x+uLTIr<RsT^s)Q=iTuu%WBJqzG-)Ttg7)!v9Ui9!Jue0{TfaehG7@gYJ+w$_5JL zj9gzMxC35u_216jhnR#S=w|0`j8_9pDqPwkMmdKT>+?9Bt1Tt%GWj77>bxbLa2p}6 zj#Br>*7lJ%=^xO^^;1Skd+vsQ>W!|zw6CWPkx!9B{PvmSZr<6~8q5G5yugNM@{7N6 z-@x1AR`KMehlx0Zk3Zq-P2gR{F}lWh(YyOVIdt#Ivg^Pew#pj~n?)yqm<B0@rv9-E zPK)!bw7&71M-Cr(?)|MCH#?lo|7M3G)=C>NT9j(i_Mu6(<(D<y>e!y%wC!)Ne$Yz_ z!~W<yZr`}XKKPU6<*(py<|C2Ivs1`w5~`~sCpWPvl}V0|i+GZzc|K3RS;l6|s2pvH z07ka-{~#>T{;B{Aw-ewxi`B<HwSQaZ><V&fjYvLvCEoyYpJ*oauqk`oLWgwPc=ELo z(~gVzV7Sia*l2ZfLnt<Y%jkUhSe@Ecb@3m-Bd!#Q-T@)}2a^T9{0g|-0lR@mp_zYx zTV51V?W&3us0FS1ULF)>lUuLfcoMHsbYiB+>1VDOVB1cDjU0Q{&{_JhTc+8*<fZ4n zPEkvY;X~!|#~&?+nKXC2vP#g*F~|hl4}S2e`s23!4FXj^4_2Zib{=WPdfQ?Qa_T9s zoO-Ez@r!?6o__ipWhebz+8oA7{&PR~b2V2s@oi;OQ^ec61k#q?Z?mlJ*`=|#-p->= z=(Oxn`K#>?UUO2RSKHU2+Tgt@wyrsG@+fxEWckxC{Ar@dfAN<;!?!)|!G2WFHS_I+ zl)}CT)a@ho9rZZ%Q@XEW7rCImVZYE8!fuv#!7I37>V=Pmo4V{*_J5z5S5<ipS>iLz zM!F7V^A1zk{h0lJkMueH+Ub0p`#tY|cg7{7n<w}_)?fK6pQ`mJgs5|otx5D<37@pu zj$UMK1tUZhB+o73n5S>|4<+7IZ`%H*Vy#zMk?|NpxDBN)2Tfyb9`$AEAOg~Aer5$- z|5{cQe)dm38yR&kK_YIa@z6UTD!cdWRAoiZiE))-b?YL3RvzRoJeM--<Itz2i|_wk zJ~H<IB>|WS=g<7jpNDZ(mTOdphOla{gNRWdeD5sGjarj|OeJEI0VN-;K*{PwA?({& z=HnG(<=~!uWe-Z}E|k;(qWoNvO~Gt|K`S%$y}U{EBg-YnFgE?d@jy3AAdwskY!RS= z<%i?ULX*;Ia7y5$p#ZkeVC#fsmfF!%*6n2|TdSm7qQ^|(c(otw#Sv+=fl;vzlo}5@ zn=DR4zmJF+_d+s)TcuXQsyNDYE^)Op_XAHG$)e(|gIXt-(Ucy`D1dgdL~T;HTaL(j zMkPo$BWgWGLS@jrK9`m%={lT;i41ceM+ax4nT=XDBEx~xJ*1a#9{NEror>XZdbq=q zgQ!k{4QM%qqkbMm^tscolmVQYKl`8lC*>1-NplsP;y9o)=@i$2P@QECVpaK&AVxRY z=2Vb@xsBurO@yEKwwu3Ohx5Q7&UIi^k<}pCSa(0@8;1j;=WL>G`M@J^XPFmu2*3M3 zk1{D?B+Dcb$d>KWXa{|r2Sz-ezi<vb=gQHehxstoy*Q*th;+e;K5;FI_C6f6J21HW zpic}wYFVKtyIsdLONM80HoG656CZ0tbgf|UW0MB1s$AR{>RZTlrsN-R)HFbwJe5X1 zlTL9E@IrdZ8(wYOEQ$0h<IviD&wZw&VHu~|2+oOpEJ0pc>@L$d{iL%q)z!J?zTfO0 zj^o+rc^wH3G)8uxMbPiYF`(1gcN!&^t~234xgOGOCtF{*_qc-3uNZGI!|(oOGfX<n zOiqD6g96eqN<Yo%RsLUL#%P&ymD9nh4_x|b>mCNF@v9g3xW+T(+zT(4^{LrB_oH<# zq3*+w((vhmm*pM*Y0!8GmkOSd^Y%F>d2C-J{lzJ~M*Y$zzagoEW+q<9?<9zhdpnbY znM<t$*yJf`-^av<PF6nz7^4zen$UJIa?w61Z>D?;pif0XwOuI(aOvY3bkH3ITKI+8 z@-4&ur{QN`mi={TD-$ZbHBIUON6YQP;e6;vKN170I-8U!;D9uWp{hcN;efP28OKS1 zgZ080_ClRnA{yv$BAiFruiQxh9WJfY$hs>9xZ#JB2#c&-n7A~a4Lf>pcJ0L3Ctuj6 zvS;##YUWiZ0B7k=G~TuGDVCDW;m{e3!+DPmBS&Wm4ev*>3B&7X)C_?qpm9I)MThec z&gOoWAv#jW7%>J68b~iEbCg|1x!B$+{H>!#M}u{2Il#DgV!;WnH4Sdg0VXsCz{d$c z%k)q#T9yrF+i>xY_sR)rZ@J<e#JPq{$(v_pAVJ{C(;I*4Gs`x=`I>a#P@gGl>oXHr z5{#G%1gXvMy>+D@cm*$B3Kpli;4R9G(bMpleI>K(T$Ms9g(@yB4DF<^_@yMv&1tF4 zk$SDWIu?Cu{(7|O19cunMndP%%qP4`ULl}81Y1Sc)iWBp)c}OodxlWH+20#^Mh~ls zDdVcn<};_ymOGE#l|7u@3d(j-40QL{ZsIKT6f8Z!U7pZsdzHO_o$PgK@xFuX#m`D6 z03%&(??i~oKRl}rEuM298q#miviII1GX20EC+kvR`h1IfC=RWp#CC_X_sXVO^b6&S z`oSSSdMD569JEbxHgd*tq)86?h~t+|#p~mIl$Mu{+rzBpa=RqkuANATlan$uf;7Y< zAIP9n&3$MuTsWV4+{0NXy|P8!!}g7Al7QS>UfLW0>_0|6x@v54lF25X`O(24jB6*{ z?Y^{l(hINoBFDsu`%U0*E3wN=VlK{4qXe&)yG{^^NQARnKD80f@<UMOk1|MYIdYVC zTx8Pr+}YDOW?g;LT@D>N9EY)6={Tv9d}`p_fR0?nS&#H}<oYY8US!geEqzed-3xDw z$oBN9)XP{3T-o>D2m^u&_^3xY#^l8bBA(q+!#<yOZh^Ei^6EJ8Jli;&7cmrvnZS0; zt2BfT<h74J%?F3iovRLKC;yh0W+GSJD|p2yQt)=G3<DhOD@N=(ajUHIw?P56t8h3* ztfTMB>y8y92*Q5AP=`_F$x4v)F_@xm3t>9Tt41T-1Fe)TEyd(L=+BWZ?H}4A?aUu3 zE6pRJq($=O#vkNud4Y6!>>rtg_OXhvn9n@q939TmiW8p61VF=wHyqB$0d(&n9nRTO zV`s{icXgs>ujWj0JJDUEa=D?;K%ew|(!oc)=&X*3k3IZY`N$(5h{Jgmd9n_^RW_-g z)`_1uoQbHPoET@q1ScH-q_uPf1@IJGFyMD9*L)wCqyq^;Mv0J9e8~sxBtqyY{_>yX zk&iP5Yk7JgS0otEvt*wUvF0ItgoAY`r}%I<dhh`B*$I6H2tFCz!RiMlXzM{b`mn(W zl~x3)6!}KJLN`Swst>CFSBEn=!f$n35}nREqRoq(0>3_ZVTdg&Tyno_*BHZbov;tD ztB<7(m1pn>{nI|I<1uY5j%j-TfQ`TNufd;}($`ZunkIZKfyg4|LTm7s?wj<JH5{n! zG2cD5ryRWdMA>z4A1fGkB*GbTO1`Rll2;wYqn2E+KJu)+$G7}$>Z-rq`mgeK`(ge! zJKC;tQ}QIuyCxH;Z5_h@R)^`gr)%?jMI40YYtU?&F?NBiGRCh=lv7{(GV)YAWi~w! zCa4Z)>=zg&c~)_xPOcEFg`It!txL!rc`ZCj4G%%hhoWgOMh<?-uN9s?c){&y+}qo& zG5n5EY+m?*Kx^#i>U8d6La7_QT8FdtX1DgT{SdzHA+6&`A3C6c9FBSNT(w=`fo5#g zHi^Tz(K8&!>()fI&+-?zlrIfIB@X}X*QN~~E#XMx3XM3{YO;!B%8;JoDlZeXpq&q# z%8gN074$PftiG^Hu$N<Q>~7NZF^)_%4(G0}<ub<j`NR{C;Bc-H&Y_u#H02Hw@%_k$ ze~A0rcUZDz-#F?MiC{0RM|*`T;Gkpd>Xpmo>tFv``GY_B{RAF4Hn{Tj=l|oMk1fO| z-_SvAeS6tAYT16*mcISjo870R{JGT}Z&u11pS5MS&Hu)?-`_8|uld*Ty`jFGkspBG zqR`3{d0=|F22g5$_Y)=gr(gK<^389410PIp`P7eps_bXG1bq`##;1hu54g9POU&#S z_Pqqzpb{yPm(g$JX^#YIc>|aZ**;drdM`_<gIBwfenwttzvXadc$#H`eqg}WM5N`t zrq|Ug)9CiEmkGw*M;>{Y$&N2Vv*~jG{STA}9=IRbfXqNW(SN3oOqrlBtmTw9$k7Hi zFCMiW+LZO#+xctH`A)~yn{CzErs{#xsC}PnLo59c2F6`Hf4RKy+>7wVH_O+*`80l( zk@E1P50{UB;^Wvmd(r=ukCkRs_iriz`C48r-M=j_I!1*y_0@L*``?M@tr-5x0;cmj zzx~^r|Iw%aT8s%RX%#p*)O*ivmZZqwQEY%nB}3=%FbbBlg!w|OiaG|XdnWtQzn$#M zd<5t7;obYP9Y$dZqhG;YM1fjS8AW*7Al)_;48MvYDMQ#WQOCW))XrAwl-t2_wM|0Z z-Il@V9+$u^Qs***wIA2h02*fSsUN8`l2gIK-~=Akk&Uv7@v(+-tkIusI4Db{&onx| zB)0qcx;)5d)gaXITbI)(T4UQDt<JFe&cQFy(I^WRqLQZrTjSQUsuJg*i@J#cIY{)U zoz-Z`IP7>X!w=&y*TKI`RH%mTAko<>0U0<Q#OduCK&udG0YhsVW9b_Eew}5TiC!YF zKKSUP<&!`D<JqUN2j}G?4##n3r;Lg=I@?aC^6zy6=f5;lsM*FE^}_DEL|Q9_w0*<{ zWyQ0XNDj0O{^LqkDS?)uiG-sZ2Yzuhx>?6UyPuzY)rE6WVLpfh**&4%pIWD^+cTJ# z|3vZfaYme*yNH0g`|gv}(Zwv}Obq@3mimv4@^MM_nH|Pp_v_ygtbjR(LU#4qHD)h~ zYz7yFv%*73Dt*ByX@$*-+BWgGFfYLa(m|ZODnzRzDaj+GQVs=Y=AZYxNuRN8bV6!W zsCf0m5B3jf=zgW{^?B&XA$WfnN8@Z95Gqa5Tb^@5!n!O^2cl8SF6$Ea7hZTFZ66-t zJ#oRLb9S@49AsIu`(OiXCK%juC5Th65p_C9++SUzPdda218w|>Mi>3Co5(Rg2Dk{^ z`8qsJ=tpSQH`ue2XuR{MUM;UY{cM>ycV2HWv>(Z~Gaa2al%vuq?ck)qFAbKP=-)y5 zzLD!b^Avv5Zpjnwbr6RSDa&@K3S>3*UE(cW9eCw`@s(coHJ#KtG#&8bq*mteTnDms zS&pX^)$#3-vYO|@(6+l*%e9|oqKf-WHj$>*TR(`X98$40eVgBW8;?C&4*tkT;;@fl zM_*|j&N1Fm20MIkO(T=d=~2R$%H{LpWfF(;pmLG+8)LPH`)+rm@K!_57OwP=PbiQ! zWVtvB^aT6ou5jOhXZGx?dwt6hI-6DB*O{!N`&vMpE~=s~<Gp%qs$AjJxiG?(8VC94 zAgCmr4rgVi5%+6OAW?p=_%kul&jip2O2%O0aNd*#^w%C72eyNI^REMd+iGY~2y2|C z@Q5_GeS(5=hj;F6o{yj*>(y|&jj+e@=V`>K{ZGK`pBc=_Bh6DbG>P(sQ>xObKDWP` z$GUTEZmrL@sz{oq-uk@Jep0r->nUGYgyr*0LYjx)DZVyEt(#Y*2w%(F8u~h?GTtEL z;>aMg6C+X1poRQZCoUye<EV;j-?pyhiC5@H-N8{10u$HJn6$jBU?H!p+XOk<YyD-J z7VJMiq~n<h03KJG+8^E4h{-C(>wH9mJnrLY#8dBp-(ILIVvOuG8o;r~DABWL&ao}U zarWXpn2E2zM!CI;S!ljW`zh<CgU$~pk(CWPU8ivTTHld7@8m<N2jEj#q2du}f!TJe zZBlWtU%NHMsh3`&oW*kgLvBk^w<oG&vdC6id5y!#_7ZnsUf`oJ*UqtW1pagD7WWYL zqkTpWO5pqhj+Pf>8=4GWRY65Yz{l=kY=2bF^fO5!ud0j0IS$M^cZ@+?p})72Z|WJs zqSM)xE5hR*aCIvn`ipHx-`^kttNmb;Fa##v^-!j|%MwmsBR%b62N_G$6V#>LLdruv zFfvUZ%NPts(gh|;g!DLL<J$5(leC*eci)-Fa-9mH8uf@v<s)#FCcM!Ju0Cgkv|E`t z89d0C;g%T6Eyt%goJkj1rz?;Gog9-+!Y(d4(oVhf0_``)B*R`DW$g3n)@Z!n(6N9v zE)R6M4xgxUqnjZ}Io`KfP9(xv`LA3Jw1G{Wg_jkPv_UE7$Jfd@2GjxunOm5(4rg^q z=_IVrzw|PW^KB02g}SAN5zY%s=qk`sCuz1bfOc`7A`9);@}qLsXZAlQX6)Ah6@2}e zpvbS|#0l?#f2(r{wN0UpOR0J8$|nlSDGLNO9?6Gs_*<GEgJMEBSeu5t9^BSLy*a-v z-1i(B-Cmkh;pf~dS0OL&%q3m&z{(jD<g4^k_s>pyl8W|mTa7LzDcx3Mh$vRK)EHn@ zW1@e>5t_)KI@#;WDxLIBt}1K%Xtuhq>F6J9mEty2A9?hN^5ml*EW2@-y4uVBDe&Px zWQDRoN7<YoP$S4-PA8nK1(7Nb)T{Sd#UpXaFJ*JX-^hL1DbGPR^4#aaox*~*a>;_5 zx+O)Pn-1I?$8@%c0dDJq6RKP`DfQNV=LgSsXDba?>bT<3u{33Y4>f>)ZR-spqE}Z5 ztbs;Li|D%Os~IPu!z#LPWLan?Z*j_3@FYEqF}e$9b6>X67({jr5u{+7+2^Y~SJqZJ zs{ZObpZjeA58K>wDh=~!>yPPt-kx>bBu}2T$>hz7M;y+|KJ?w}Gu<^%b{}I8XLQn| zcO5`C2VUyah6!0If=6#SC@C%WhKD!*ut{&>NXs|nM-_ULJeB9)<i%}xls0Z)h1GKe zKVHa&j<NH6jLQ$^Ub%3wy!!Ol(Zi87=-!Anf&$R#lr1w;<b|)%t-1*ASx2TXQ@}M= zA5OC}Xbwjz{%11OHVthNEY>f7=oogZKF6q0f<p|>aNCvG?zBY24sE)K(41wp<t(d( z7S`ZZR(N(1Xypf24K9ifz{)098yFEOk97fy-=c{Qt{y0)mW2(f9jC6tEJWm&x^X7z zv^C`+63YqZskEv@(h=`JkI0FN5ckM?J?t(20fVVLI|g(#&zIQ>pr^;kY$N`$D>LEE zN*A}Gn$_Wqt&Dsc9_XqL=Wl(3exbv8q&)WcBjpfdnY{1#=lJcR?e*}7K9>92_eaD4 zo4P6%(xc+-@9p<_4}SJvw-fr-bI+FF`mNt$<p5hpVz2Gpv$y>8PyaN*NP8Ib*#`6$ zKN@ItZH)ouJNyYO+u-~T$-bw@!Ja=U_It|tofB8iLFzlO!eCBPWGkuM%O~XJY~=wY zEtf7#$40vQp1o`pF<XB7cm9tuF?p^0jlc09q8A;epE8k*tR7~?y)E?r$03bmMTXGG z+sJSyL+LoG41$H2M~5`XE2e#%#)@X2(`D@*jLRey1@3h|yH~L)i*lH*9EbCu+t_kX z7a^c;mPq=i@f}QM%QGFVpa1;l;k&)%Cw}55GAZiH08Br0aO&ZjA(ry_Uk}P|?{l^O z=CB=Z@Ok_6`@gn2&h`?vRksC*&xA$2ZD_~<5a4H<z@0n&-q|L5yH7!jx%ewydhx~b z+%wOYXP$m84(A1Q!-pSzq<s3XeY$+$gYS>e!Udn=Zd7=cU6x)EuM)1k=V@@R^=D%A z4FGP3{NJ5>dFL<l==?Sg=TCq7(_4y*1B8l8tGsCZJG<@&0#%4~q*cPQ{RIlv9t5FL zzOzJC`hgFRc^qEdjEwt;bUwECP`T^yk+Oe?2xRuNb)cQV0P2DB-6}w%PvNTK8N;0( z<8~Wsz+rTVGo^0P;g%dmQ`nny#M+sR>a@{~B$iMr>oua-QMo#Sbyl0${Tq#@=qAe9 zj~{AG`SCT4P?uruAmUnO+d<t!$D&5EN~8`gjYf@;KAi79_kC6PbU0UIJQ?|;kkE+& z2%(8ENl%SI^J;JkccKGurukf4+=f7<ZUIG9W7WaW!CPZH?E-D0Jm3gefZ->ZeVV~B z<T-(ZSEc0O9e0#RAAh_&#f;rO_utP}2y5j6%W?hip!+(bGZXcTQNWVbF0?`o%c|&V zWZGHkEShvTTuVoBzYboMk#2c_-loG@XZ4W$fE3fn%D@ed7NLW{$X45Hl`n8Bn9QRx zrm<<%vJPjR^zLgWj((Iv-ZJ9RWxG1;=ZOZN#yRJbuKoMiA8&`V^mKS=tngi4RN-L@ z4II@o@SJ6WMGOn~5OcYe3Rs88B^~*~rGhUn#0a4f`Nq9#6~r|{M59Loylu^}PZUF+ z$opi0&s<JIJ~BoT$IuoJ+u5sUyN~xFCS``$%HaAmA5)~A`-mohA{c3wM2Ru-GzV^M z?_xU}!ECg%r**i`+5oe$yZG4Lem*d`1Lxr~cwT4wi>nAuBl}e_6|VA(xVoi<4rmoG z`OLo5@}l+1qz<y;>-)_vznG3O4!>MEbGE$l-1Ft-XPzmuIIs_(?2O3+w5cCl@}M~S zi2RKMfRV^@#)gezH`3kZu;6If&_&0-zn$z+DUJgYxKtQD<DjFTnO8d5N1W6WuGB>t zKGS(#om{m}-<jXCrIXj%2kGauv6Bzt>~m@2wJlFN=N;vm&iv*zf?R$PC(|qIG>~f~ zV{LOC&If+@NsKF$e)5>lrT9kc!9@%>@SYI}L_%%wp{jL0GIW(~F{Y=PnAo|O5C5^B zGR`BF2P2M^BN9->G(1JUffc#6Of=EtW%l`|&uq~5_Ta3uA9az&sAStwg*1jYaue4R z|Ad1*->=Uw@k9hZ{HCG0@4#MYDhJXqC~Em2BM<zTRtF;&Nm~ZMb&&o$jMJkBhgcUA zJ{xEoF0<|>vLc2DePEM!c1k}omHtE9WvL`|)Ojx+I_2E^+cwo1w*)RwDO+?%SGUtK z;?y>bBMWSJ8=kT+8X0FB=~#~wMwSBft$riT_~&68v`6c-ty*V&UTIv@nN<2J3#6Z? z^+Yx(w6@BUuXxL|v`31n@QJfLQJpT(o8M%lBq$HB$#2R6>7~rjh)cvTyk+#9#-nBW zuR2Do%d<{Y`dl!C%RVFwWC)(YH88fgIR@esY2a+j4Rzox`+3FF^x(-)jlNaJl64h! z=p1J=@~I11BYd`l{mrx<I-F0xei{Y+jzrsJg^KNuEa7i(NpuD@v5#g<0T;)C^XG6l zv)z-EV|N}qf%B4&$H8mC&v8f^2!Gn6X(LkD58aC6r59ez`1#;N@4)FvgdhAOKIBTh zZFAX;q>(Ku>~lD|FP=RY)aAE>hYw~yI(eb?S$hIhlC&-T(vv8ew)3NbmoHvS8@Q#$ z2&WUUbhFCa^sCUip}TS|G@wl7hp=D7;Vf?-IeIisZ|P!R%|GsS085D4_PhZOp>nL6 zVVw8FxlZ!!$I0K%WI(6mN)HWukOdB9WF~CHLpYlJPH<mmi=<WL_5aJ>oBnvZT=#v| z>-0=d&rJ91`}8dL&Yin2yu1sqL^2c?#ggSPfh;nD9UE2xBZQS8hy(dwh~LC|6PYp) zLlGoyfdbnQY)Fw}Qd~lb%jI2W-}mlWdfz*r&$phZr|&vL@iGE|JTp%}&+mEasXBG) zoKvSxojTPCuWmtZ*q^6t5kz|7%Ai{qB7>Ai@|#9?R@Pj;#A8--VdQt!jUL{{aHfHC zD(lQgeXX-oJx)I2H@LIyE}T0J9;VS12jkt`PaI$;GwjLr%I)?$dAm#FBW;S@Jh%pf zGy2Iu<Kf)WMEK9r0B#=rWS$ALi#O-WjWPE)sB&6dR5^g*i~ir=C(oQM=g(bCKe&YP zd=3M+JUcyUpRBjD#t9A1_7BP~aGQ3l`i-*8K2N-+pF%%Mo1?3`vdDI{KhFtX!-K$C zX^ICK7>jUIRzob6&#xq+{-MD<BN@NAjV$%s(5g?(f_EO$pZVplX~9S6IqxgOnk&d9 ziM*+7qOJ2qlZQ<x{e}O~4@v89Wg0|5J0S}&ey!cKEgsH&>;s^~hs9QdGx{4ii!omO z#3--+QztJ$1UR9KpwH-{@A%}$KVDvb@!9Aw(xyfs@fZ#ShHM&$oEy6{5`*(3p>UL` zk$V+eX@gXOcCtNI4(q`WCy1+VC74Y;c^(^<G}|2FQtWw(Q|Z@3XrxWQUDmkADZivW zEYml9v<BStu&>Gbjho8`RvhU>qI_|(1tdmC4j%+YKENw}Zk|<c^sB}YkDkT7lO8&m zDDxK$*@sb0Y1mD>+r6r@ImR)(jN#`TPk2>^RObl$pnBG}v;CTOw(Y4`tr@oxWOJC- z!)s`ncU~h?c%HN*Z@&;e9@Z0n$;O%Rh?718?B_GUre^ye-p^*kjMtPY<SQmEC0A}% z;4uH@<g!wR_bW$R@XCXCzezq##+5(bnXYNtcfR-upS1N0TF5IZy;n}z%`SHi-Dhl! zSpJNWubx8=5f3!ZI2gEWo(|-==Q1HSq?=Ck<1WV39q8Ii$gU}HJV`$=f!^d^IMShq z&F2_ehm1aS3nx0F7n5l=E$6u*4RyY%c;N%SRhGJ6!xa7S$b@5U#^Gpvy*P?=VZ=0+ zbG#Rs36zf1%X9+K``HP+s^d6rFeDMHZdqQh+;oz}F`N^j>O574;jvv*XwdR2tqDjY z{Zf}04pS-NgZeSjOKZ}g^qEOIK3AuU(-hBLA>n3+!nXi=K!v}V&F0m0Ez?z;38~?V z6!1E*zK7MNBjx1l-zUGB?EmocM_$Bfhs|%PUv$hyF6i|0krzK1m_E2a0M79s24~w; zn3QX-tU7)AWMT~WF~$-X_P@XQi@#V79z2A%CE<-|yH>`%FTCRNeG}A|fm9$KDD?wm zNRpaorPl}h;{K^B?Z9P>Pa@wE8c;e%)>+Y}Tksw-EhkQ1Nmw#H;h%W&q4F1O-1+DK z@lVld`pSR(-~1!=NkTyC^wTo#iln+fEFWYF<$>LYUB)6jAV1j@u84D-D4F_>ZUY*r zE$<!`K7-A3if=!&o3<%oMflV2Tt!qvYWV){T{rS}6Yy*0_?yQuvVI@^{1*CcfBG?F zI6wdV^X0L}h9h$(jd4stMha+U&}z9F`l7sC--Z-n`l%jGq3>3XI8a>`u%HuM>5KNw zzxd0<^HxVcaNt1szy9>k7-O6uj`b+3;VzcXeg4<Vr#|zk^4Q~#v7sb;T7i2f4|U4W zu9UtKLQC%&`DP6%jB<n{bjZCp%IWK$fdf(TQ#(4o^rbH?fBy5IhY%guI|$Xg55<$C zRYY9!=n@Z&t_pP1c_^q8N0r}twHhN)#nnMxzsq#&eWCPicmN#Rx3xTS_;49uFgt$Z zCh@<fi1TdhT4r}?8NCtpl<P#9nunTa<Pg;^du;Nt@#Zzw^4{h8!scMi-+EJ8rp63A zjC6zybTqoHgu>ukH;>cMWg6o<>%F5=)Eb;svd8cyvcnP|;@vvx6{S+G0nx#N6qQ(< zcEY413$A*wRS%JBq{7RG&R%@l`3kS^#i4}S8a?%LRbgn2f0C+UAo?=Xj3Jsj)WH_e z@IMMI?^G7_?4F|o9w+?`f}G!OjLvRAc=*vL%PSxIXnE?z50`yM4$~EvGRk2828Kg% z?Enuk#Z!#>w1L7)<=8S*9vlc{IU)7a*xW;zYcPO!`z?kE8ORu~P828<#iMof)VS&7 z!vZ*;W1y+QiM}6ZT_lXaAcpk;+D6ZH!<e`U<lPK-9mwz6%|?_M;;vl1LV5=dD6`D0 z?cTKoMV3N26vUI`vlyc%XhW7tW5^R;J&)$Ns+4Jb&R~WLDX3d7E(dP5e|v`R)rd$} zb5}6mGkRE_Xz8M^c@CazKfT+<Rl0Gm=-4@Y=iycQ6Bouh)!=+{bOZrEisu2bn+J)1 z%EX8CrQzLW=56?sN>dmIn9R}WEd7jPG&qZ)$JlSf2lkf79z9B%u)!ywU%o-7aUCx< zXhOPC!IVekV`GrtMbXWq1@+PsR|PEwL$0PXf8q4ngPWp*Z4qynn{nbOp2g5}8pHE# zmc(}=oCgrLQEpRHai`3{U`$(E{Xqt$<|QAPzeWe^WEs+j{2CsBZpB}CmUfeWeQsKD z?K@%BfD@&c=jKHgQGli67H-QkZ;zG^<t_7(p3~02l8_?cNe@R2c&!21?@VhxUiBh$ zLdaDJdU460;>^5NdWETjiJcvv{x}0n4Oh?)@2bJs%osw);EWtugohi0^9ak9#)%Wv zvwjfc@A||ir&{4fX){EaGN`?@CXa#>!^2Dv7GsL5=8d5(J2D{!u+V2cq1xczfwKl@ zCki`Iu*b(|${75jvD$hMZr%Vss{yl<UR2|fyzgMw4Gz~}_*oCm24K#92fx&B5f4Oz zZ5YoI(<waV00hQjvIa(GfWw3o_%ZZ~#wcfWg(qPp#47@z9SFEFYr-x-`wpISLQ`!U zi-Q<2L5!1RK9{DGUpz2t8%tXmV1cj7cgi2$`F!P>IJ9ko#+uGF(g}6WTkso$PV=oa z9FgE#*_l5v1SVZ=XN5uwqj1D4n|dlm+S5s|mY(DfPYuo*y6Var@u~7=IpSAnz#E0v z{HkF}+S9Ng4F@37CZUx|dF^9qoic$V{9|S$jBNI<DJM^9ca42^(b;^4cI_mFqjFv^ zCuM)?5%S}Xbi$$0_{^EJgr(RO?*|RP_J!hHS!R)jnvk!Qo5GuoFX3BbFyGeT3=Qu; zPz}yNTrnmNsdr%H`?g(aQRF#BTl(tbtoZQTN9fx&5}HZ65ir{>?PtY2#7_<t@#Pq7 zFR>fBH14FXD^A>S)`^keCiGHq8@%z2M!t@2WFc@HBI*LGKBRd)J~lA8U5gA$9AlDd zT#o#)A9T`(-!VAS4jP;9Ab;KTPcP(yhYkjA@fB}k>k6|(Aq8K2QfUVM6Pd<N9=&-3 zS;~Yl^s^1`?4BM%FD<W$?8~4Y9QohF?;|(BfkwPp`q`12BiZM`4M#T;PDA~`KHF;Y zAG}oB3Vo&3c}RZJoMA|=(-*7pZ6uE50DZI@EXPAy9?Kg?LEKY`t{&yLbPPQsOO2U) z{Th8a#@vmY3?;^3CVGUizo9X|;ncv^8k{i`mxtGPmZR&}uxViRaDF#~^8#hY;5@=A z4hByXjlsF?>j62qb~Viz!oZw6tEV>ooCfEa#^5}m!P$7u_YBU`Kqkxdc%omDE^S{o zag#pngVbfjbLG?O2ob)6p-3LSk_=mVj=@=gLYtMZH7evMoG%?q>*nd<Fh<;D$$SRY zq~VYc+s5WKhlS)n{fu;=T=InpIlWcRF(AKZaL$LkAO%gQtfVpcRh=_TU;9P+1&pd) zv{&Co49<Eu4{eDtE8nJlolF%s=(RC8t4nHd(%_8pMjbW&_7D%=O#?sk$zLchJpWYL z$fSjviMIx4>#jU?8NWv7u{$>jsd0l?&SQa3Jc=x9<<+{ie82LDJgiD&E<Bj$L4bGA zidp#E>eq~FR{T^J*0%5^_st~AVkQNlPSV#lq3uZFpS6S|a3gIut{%V;<XA+Rq=8r* zrXS*3Gv)*O(s>Qe;A)nzaWi_^!ymI;r<vrpUl4E0Oki}=&>EZF*x40mhDBJ%q--WF zkwfYtdY`s^V5{F$9i-BLEh-$sDt<kJ$K3G;WaX(y6SvJ78CVnN+tioe%9_;0bhNF; zJQ#&`WMj6itad>*?mu>rm2x<#pa--b&cfkoSr+ACp6%KG_WG8iE%+@D-}$3WCO=gE zc$YLyx$k`QlRatcC4C5o{i#=}Pu`LRW-#vFy)#+H*th1&*;D1x@i&6Mgr^f=^vn*& z6B?ZDH+Ako|Lk;9lfKn3i8^acF=0PTm<{_D4{=%P!3ha<a;2y*EFa!QemnW0o|~3# zUWy7=A!&5JjxK5}{CQU9^soxE+Z7EOoY9@T&=Ji;+NvwspgH=WR&UBUn{l2FOworK z8*6NStHBvs0U7F<wUgrl96SXI{-#~HZyQe7NvpxRrANRIK2t9~jxMH*2L7x>1V>v4 zwa60a^lR#w?xB>`6ZE4S*7t({k#hQt@6#Tv+QaEWgY$L_&W?w|JGBQ&=#f`m{<K*9 z0FP9Xx_V6`P?dW1_gn5sqps`ZrmTDM;)U`%zw^JQ-%>*~4B2xZdagYA<kO5HU8$(^ zTFw7{0KbLz-y?DQg7<j$*L@u5_|x+KUpJrC-&OjduUTbquKUqI>tVizq(Jk`%yRkS z7k|H8LjT;db+A14#If?tZ~e!NgFf`3r^+io{}S|GSHEkIh@(X%%+*Eye{!#$BYnp) z1=ypf(U)n1g7wflG!)-OryE5#wXd!HmXo)(owOrQI3c+K=RS3{s@FCBB6-^m%6L7R zUnkU<4sC9d=Qy_;W3u~7J@&+-<=JPSE&Eszw+1ISzp+bo+$PPY-?3piS18%v&Cx#d zXZyIlwrPGU*QVgrWeK~uLxkede2W#D7s?NCqO-o@Mmxo8uf0a-xoe5vj0#^~c;SWe zxBt%HW^&>QLddaN8|6WV4|R4OSG6OyGOVrPTVpx%6j+2K<mk<6pnfWq|H(5|Hvcq_ z_cS<5kRB42;V+ySX$?j`YX{O|F&$74%1{Bu(D<q{tuUWupy<eE$Hq0~(C&R@KML!1 z6txaI&n`N>IhN$eDE({<=MsOzHrT<A(UED`>~T=SAi7<;r&6bfvYnlZzk>@6SZP?k z(;GQ4k?ClnIPokVcJ};G0IF~Xj%#2_3BnFpLx6dz?2j{BYn<g8?x4ntjS@!*Q^4xR zY#DG##bLZ^aJECP-(cj!(5UfDgQ@~RPhD}RVNKj<yw)Hq9xYn|(;5`g`2m*-r5$E# ztWyyAorm~V5cO&}2aekq!ly8>s+>#!<5fJGH8AyIxIJ*}XnFZlpD51|lV|I$ohTPe z1c7G*AqMewXqN4uQXJ)=91Xn=qV;yO?#?3jV2sGdflL^<A)4tmvbJ;}Od1?o+7MUS zkOw0qMWB~1Vf+LpJXSS0$0$Y}`-l^&7p@Y`&4h+9vby1(Fp6iFtLj1PCMga`T%tSY zQZS5Ylf*=G$9Och3|!_=K-@%9gR`6LStUK3HV(3xi{7LRax`8kkZn6VVC(5}HnpNw z!Eq3|x^uRrYs_0kjNg%*KYF}Yk0^&H6@PWIfdtLrdkxN8h~s?i#tk-bx(+S4D{Oc0 zuo<sm>6a474+AH3<K&I>B0U*4!;K=OhZ{`PT)uRnOpM(w8l4|`^jO;S6ieK%-58}k z<QH(nx3+`%IsmfH(q!^QIn?mt`__;ppGarI-lJiWPTU&kG3)Zk$<f;=$tTLGA0m{` zo*~Bg?I>n_(5}nZ`oM9Yd`FvS6+kv3VFCs`OV4(Y!XeIDqpfsR`PVpeYgUZ&8A$Ps z?}gECG}>r1Fs~^>OZeP$)=S!zE;I@VwCVk4oy^z6?~)e0hzEs*xHTVn%4<A0pkHy| zWP+0c=H+is>D-Af4|z{ITz=)}%JyIQD0$a`dgUP|<-pq_9n|t7y&N$omI+g$(b;9j zckncx7>C}vh&jiA!uZH=Gsxx}jj7Zd1`mIwE~yuFqx>cKM;@9+E^Hj!LLG=hYg;48 zGzx2+2<4%KbYk!}hI5xnIED!0i%v7CVOXKH{g{klUI+Fu6v3bgaYP>7#KBwB%hEjt z8e3@l^%w-Z(BKw0mr!o?*zTfE>0EhFaQ?C^o_iRq&<S@#3mUc@EgKh;j{}qZ9^M6) zGssvcjWkxpFi9HQ+Xkc-k;85K8*)edYU~3o8K5L-Lmx4&_^GAvtTlY99GEURQ~<U2 z4WIf_@P(qK8FNvNWuyqa?YA)igUi|;C~V*@a5wT!`Y|VEsRooP33x^skWgqdH0a=s z?6YAMvO}p6qmti-ZiRrRrp+}<NN4t=sgpDee}mPe5f*RT;fiIO-tv`c{x*sA7P?HX z#9PnLHN^TY0-R?~7HDkNOPw3aQ;tKs<}X}UsJULccrhN%yLRtR3}@p3*S6zR>c_`^ z#=$l9s0L*{Ag{6GwIMa!aAeQ^{qb;?wg543w)hoq^_g%Y&!L$qWWWhz&@A%np<|Cn zE~@m|#$Yt*YK1Lbtl0j@1->7{$bA`uu{c=I$^~OMuO*J3?V7f<JaOZf!E2}@x`Hcx zH2R)9eLA{@VMO%sH3Uoz8xjEWUHytSr%a8`#<kQ?uKaVbqYOO!(2*#s%3x{T4Fkb; z?gKT?E6%A0Z7A%<VAcTIhlk_tJ-gw1m0eK{+|<c>W{^+0wv{{~y$QRMjTcd{-8g9@ zo+}%fz*O!yo-z-L2)xM;`B4q15{DjSthSnDr3>ZTv~CLBr^himo()75DVIDLgiti{ zjT3m1ue1v=8m7irrs)7$oGWKLF+93#yV5`K%RhJ*u{i(`(GJL%=l5(X&lCFRUJPdn z@Gx@@vA%$e)64nNt%Y*^4h{hfEZtW`Ly5StZV7D$E-qicQBIyZn?BY_gxT2|!+92i z^E4X>3a1VY_Se#kytIhnuZGy*UcTm3N3?%c*GT>3ISs9}pnZgRvkiF6)inI(!IE_h zvMa9m!E@_tl|&x2=trrUG5|bM2h+uiO9VHEwB4YA*QANuhkE!%V@;M9`>BI*Q&Mzm zaMtLoq0*xovw1HQWi^BHKzic0?Z|ysCZW(HHf+Vi8QMW#aZ*Y!-5_^y-pN!3zMSy@ zhfZ}8(KsIh0dA|crh9ExDSq}>{#JSN(T7>N)Q3KT{$_e`6cB*HJzqTUj9#xE&ctvQ zb-{ITY0WDx>a)~@HWSZQ%Kyp(fB0P<@vP!3Now^)TYb+}I<9HOt_hR}d;?7G8RI)8 zm1VZax^+x?q3aCbJm3bXI=3Xe7kZKWCE&GQmTLac5xRx)-^~Ekj}6zOr}Nar?ci(y zgLDUU7h^MYygB(ADnYMP<+8lJT7Rp0QJo+Fatq|B<@!56Q&;=!&?C=$9vExt`kYDz z2dSg<)Znyc5x!_?xH<ySur%(>T|xj343@QnLuKz{N0BjX)K2I-qvW(kXUn4*gV~hL zy;y0_riiy*D%#%q>^{HV>yvwRy-x<KUMrGTAMMWurNN<fk|M;L+!hwNs^7Q(06+jq zL_t*dH!r+*+%v^~J0s}lcX2qmbn-;Gaq)a`D}{A}zYgRPGtlhBHIdZ=-AwRwu?nQa zaSD2`^0CsdeTEHZ0h}E6xoP7d*B-?-Ll2?wz``F5o$4skMr{v1_CM#%F~(7Zs+?dL z)ycjM8k}9-)I<N~*fir(bOH5mC;#0$pvn_@Tn}es;MbK3nV6$Kk)6oGm2ngZ0s;zb zh_2xwq4ik#%WLamm?h<`@U^lb33(^3vu6nJjp6J#-ZA#JErj}E6MK0p<8So*HXPDM zCN9VBjFvNR{t%e-a3*ZV%P*E)>?2`cnH32@A^i3iAN#rgG{xQTPs?le_q7qMC$Kj) zT6s@JYzu$Ozg}B;W+iJ#Jn?`&KpmAMjx7zfcY|=5|N3A5Z>&-r4gWdeyLZpt@`+FU z0-?cn^9;NqpHed4u0F(_N5$dWUan5~miwBn>ecn${?J3X`R|>7l5cMA`^P%gZ>;49 zbBItlj!jslt7XPFy4j$aN7kWk2Fkm4mI+JpTKT=-`@L+Qyp7eJPe1!axp46;hUOPp z4gLZ~XhKth!g(emmf7%0BmRo<@Ph&Nfpdwi3cixxn&wMA<X<;5ynb!8d=EphdR-@z z$n?<Bk99_~o#O}uKR7<#jgEfk;K6cWcsRPJdP`1_<7!@GH2>B2{wlhuW9VJjhxTDt zICS`6dGe_zvVT-JPJT1kThym?Iu$1ELykqnS$m{aY2q|<+tj|~h3|Z{ngm)00<gXE z+`Q!hpFPNtKAvwvm%!rp@{i>xVn74>1rrX8H^y)pxq@N+1~!=M*kDeaI8la&hgmtl z4Tq51<$wSE-$z%UVj_G~dGwLT%4a|O+49J-N7y8=dNxl?VmE;wLtH2hI)7NN{D%H2 z#1_mWf91OJx{AIBsnm~=CgtbPkMYspaMFa-`26QS2Z2LC91^XAl~%}TsBti$pj4r@ z6RO4-6>R2FVT8=c(b3r8;#yB0J?SJ&3EL%z3n=&lD6jiie)i0P!{yM{on@I>$O#OK z67mK%&zffQ76&YP@7_VtT!Z&OpWz1>(CEF{fuf~RQ}`6f85jVQ11JZR8At(yW!mDx zu1By0nNElps&<CLEU&028>&Mku^RoD0U4i6ee8JbND@i|rC0{GgRRR&8Q{UZ8o!0b zK}u_QYz=1O(X&;kHTJo|n;urC6&`WvU{Pi;t?z`{IKUbYH9iWv^>o1LVMlBS6(bXA zosFJGfav+yLtPEqppr8_y~rkWc)qekq8snpXJ2};eEOGvxjg;chf>xwOPt-H&?eI} zJ<D_9QUyW0d%$@w?IrUV$|2z?_-!~7W4Ky}F0^9nr;xOR5+CALMI(mONxY9$q<FVL zej3Zrkiazqb_{y8J}S@*G#JDV5^}|vcRik+N!KW7OkwG64KQe=n#Y^Mf$&_ev`0KJ ztp|h$F7=w4r~cw#h=ITs;>r<pIPEKLg-xL={%w=ggJ()8@oby7JWP(w0lrantefp+ zn@C@N>*4c7@ad6IBIKtrRa&rJ-S}@K#`LRf0&!P^3m%>-OMTF{#&0*!T)%!pmO5M4 zYV@oynumr8!*XofHi*Gxp?v>)-;L3E2OY$EHmRAEU&h!8oo`(R+!}HXN8z`6m4#02 zaA<=VaHzXiCqX={i*2^Rslj<cZ5RQoXWBXqP{hf;dEpZ0xpMK;2|Uc%*phlrVi3^_ zXF#JldFZ7xMZUJ3yk~u!z{x}l_bokJFYkj>WQ%ky4TyZ(#Y5O^GvmaOIBAW8SCwA{ zew~DoS0l4%bIX$^HR@Z2r?8lhamB@rzwJP)Va5p`=mpsQHdkbX;cQH6`*{ef?=8o? z{5}25bEWV34<j$6KIjG->c}8pI)X+r_}6$|=~P-BCm!GA1Z}VgFCh<{3;}VR&|rff zD2kea6Gz0}k*~{_jhQ$`Y&v6>Z{EHW0}eQ6LZ$<wT~;grQ<N|DU-Hnyxy$dsi=O}E zlT0!Jzst%rKslJGJz<qq9T<GNfxnly&uk6F3Eu#lv|sHS)P=k|;brlXf8^mNri*&8 z(S916JE7?gyzfDNR;*+RwlV`e>lx@NzomM>EZDMdYHPl{^M|rW`e<do<!Q{1rwHlO zu{Yl)12Qtbb<9=mgZvyg=e-cOaQoc%CgE*>;CBporssbY8tBq*G&seO%YA5oI%bl> zvc#jXSwHBm?qE!o@Qw097%V6C;p%UV4{2kR6~AkZ+R9&lN3KE-p})3X)GhQC#0BVN zE$?XDtTZg`**{b~2x~RI*R~e5!Z(Wy?dYTq3^2Qy^mEf7;|PN|GNv49mpe}ni}YK) z1J0a2%Sx0zF*qx;<%OgH58jfr!o>#~-Ne6!mFw58Rf97!X7Bz3F*rlzD~0&o%F!0g zw}xVwVp8(N@#8T#KTJpsWv22X#>(JcnyOzn;P9K=fx)HBm(QMsZ>9Z#cnNF#v~ub- z;);xtHj_r=L$PUp`-4ej&goO9kQ+T1tKmE1^6LTCdV!`?zYz}d)DuvHv-IL*s$oQ~ zUbz~b=*W>HO+Q&HD4&WyK?mFwT&ADr*<Ch&y>jtV-n(Jp?!6eC@i=h_a;0&<uM<?2 zj?~pE&loQ3HePjSPo9c*<Q6vV(=%M%%#c`>{)C%$qQc_JJZc|k2po*K^eY!Jkf@_= zW68Xp;ZEX;FKJbemujT0e4?SwNfhy@u~t3J&ELREyu+P55<Vx&?Nt{^>#7iSOefx| z$4+N?YTHnGn({O_YhVi>kW0lHR}iLT(#!eEZ4A!0=gSy6&l>4iYaRbJgtwFaBX`DF zR(meGp*qRTEb$zXoil{gn3<{}H5Qm0SI@Nl(uZJ3cH$?76#1Xib}>AO-bHyX-(lp4 zjG)dCdg|}38^!U1|KeA^vK}PS(CiHuFur-c@|TaSmvv0{!PN)pTg=d-$*11)GelEA za*zyoW>*muoSGkH^R7;AaW8{}*8C0_Op(c`+OPTEP!dkUbfRB&8#;oG;d;<f)@|Mv zS%FZlcyhv@K1T268pqiyv=6_7;GCe7II8Rcfxh$WpZjbXX5&mfGBr4>FH{*vlR;BJ z5L2(-&3DmXXYd5(G4)awid5?iKCPyBOohF-e$9LPEAgAO6(31Yohuf_aPtk{`_60x zH@Fa|;*7(%>@hfVZyC0E4uD!eFoe?w24}-#VIa)1XZnR+ct!kH9CJw<^1XD0uI<F~ z0<oFrUHu2%<}f@@<K620A{z^LGD*A!nqMo=;b@`0;cB*s=H#o+Oq*pa#Htzfv&i0B zuO>+a)3$C8E6R};PaAt*K@B+u7rcemOp|t5`NsP5!_#!qYSWL;V{l$#Y|x8G-S$V0 z;#@J9$t`2EYv63U*<e&?{M}@mYtvK}5CLqDHc|Wg0j}@$Nt*NlzF(aL_Ib<UPfsbs zI(T@23M*Q?CqdGY2+<H-XB=zpHFW1YBR9$=bms|H4Mz7QWeumnxQOvX2a^z;_AA6p z?_$rQcHbNI6epi@LU+=rhx&xPkpdMQ-1ygP^ay@<6~8Ud%VXpO+xxZq->`BHIj`)T zTSjkVVn~CtVVAn~Qb&JKFHnD%zSVi+*g*R`9@d-KaYV+9_Ip03;=WT3gl1rwI^w2G zXb0{T$oy?5hWwp20w`rHT7ysWH?^%5vu5C!zoc<RYnAWaWjlRE2L@;5w&M*$(A7!b z`7*R&Ee7Y2a_0CC$&Zb&2@Un)%P*82+qS12T~#4Al^;5u{oE_RC^+{$?8js;bv}>! zyXtfH>8)O*9*{9IxYW@Db`5RBAP>GOU)S<&8y$6K+*=3!*BJIkfAmMJDmxYZ&M}eY z{8#_rAC^6P_LEMVMAZRmnH6mD?kS$U+K$n8>+ARaE6wnYVJwA<PpO}Rk+$GLl{>ak z#6Z%%cV_jC?WgS~Eoz1wp^MzrKNVMLY2U7T^Io^=uK?kA3&PRCr(1niT=4nSB>gli zp1%LR*UP{BmtQ1Da6vn4V;_kZUVIMSbqI&8Bj{6GpeWukHcJ<XykFAj{MQi}?*;10 z^ZVD!6yiqyQKz@v45u>B1ov7t`TOp7e^`F^U;S?EAw#UJv0rtA%s>0HKZ{J3KV6xt z!{4Dphsr1ZlTVai`lY`Woih{V@ahcuj|S_r=gyY1XU@hDuTH3q;pu0e1V7J%S21>< z!#*TQq%r9qyg@V4jg9TI_B0_?3BN&J(6X|j@{G?tvg*}mGSved+EAoJ$FX{Z+kacO z=YsS=2Q<xC`3iCKUw!q5<uAYcmyuO_2?zN2<B!J)QP1#mY({RpY8_fW_R)`*fAkN3 zBO6Gr>!*Hz0y<+;Qs=gQu|ul=04p_Ifwa<$6;Jg;ht|Xt>T_X$mDE4^4Wi>`?&$dP zm%qIH8^7@zQEDV~2dxshN{+@V4K`XCvUHR8tq`pPWC+b#^W0^T9<3mefQ`dEh2Ydc zFh?BIWrF;#qenixZD)D%;E}R#Xlpv(J`Ik{>QCZrLcw^(b;TRc0lUUc1&A~1b0}oa z;0T*ADtJ8<kal<yYCHSV!aINxB<pAtA0zyNot=zf94J1FvKFrd>gr%<8tSTsg&JDK zkQOqkj9djeMjVJO0-W+P*aK%S`_;Ql*w(WgN<+1tnZ{nz$SsT&rx<6f3yiN}UL4y= zYp8TEXUDGLupdR%%@_>#p)oieINW7<JqT|%Ad4aZ%u~*ggDZ`#6Bz5pFs#jx&m8$) z!{B_4PRp<xyY}uYAN|<J%cno}>9XU{{?g5$+kx|KjMS3|s2P;uDblG>xY@`e8%x;v z8FP3J@5pt;^3z!COt&~GcthF-Z9CZZ5thKOv2Fn+%GjO4uL0P>rA+Fkfo)vYKD^yG zuq@loa1+ZCWzO5cJIgoXg{0)AU_p4GxGiWXL4BD<$l4xGRP?VSz8&7D=357`2FWM3 z9s?w`Lrky{G{zJjXCfmo(pJ*2dFX3pEZp{J?|c^p4SX0@X7%Aa^ASdYUS4DwByI1r z)?n;aIx#GUF+a~=IG@fzJZiuf#;Tk_Q{dUnnDl5i5A&B7r6Kdtc)N4wZWOB_U|KFG zPrSh_-SK!q3~k#%2pTAxPAML*lquc#jqPN9<}0nK@cGOoG#WxYtV8NbTN=7y1|#z# z!g`KQSRAdTUPHh<O(%8r-03nldaaCO2)TtP{T)2VmVs|QUQd0L3u%J$s&qL4p;BcX zM3TmJJ(8Ue()bf)k-Wu`Fw}{TYW$7S9C#|PdzEi6#=~cN0QlT*S_861Wb37YLj|zn zP;r9yHF(fS?J_&lt2o<cQNX|r|8t1%v@0*o+f&+ZJ@=J`ZQFQ%>!D+1_Ms<AZ|4+g zkP&=Ga_UnjQT*02R2&f*kfI)g<H$KeTudP+@DAO!dkZg=UC0jFM#WtEj#jFY=42mj z-~e7ldX&u_?%bIwJNND<JPol>nM~18W7pq>H<mpcU;{^Tf%v7zDZZVc%_pe4araps zjc2kQvWGIo6HWsZCQ4|}wG4dw7!>zl5Fx9)H$+k=Z9wow=mJ`!%nm#(^q_VFuY}Zq zuDQY3j8TiTn@JCsh%VFi3zV@)X3NMbL)7$8=b#>17f<4zKeSDiBjVaKF!Dz^Y9Em2 z{HFAkd%ug~4bH=}lo1^8x%v!m&4%<<`F9|e@+4Rr&9;ILHN=J2mDy@A$Sl23mFFsb zKGU%7<Yp!up(O|V<}1C#;0%t0(Ul<8=v;ZsKCI<4jpBiaT1eOC8(ENh25gk?!0VoY zqr$(`!6XQZc9ly$qrLgYC9Nu&)llgqp?wPjM|s|uYm_t3a$M!-tR78Mv@7u%`v~pQ zgO^@n^oJLvKj38yCC=RGx(;#u)me;#d+OxrvIAMPg^4s{3Z^bWBWY;Y`~x4hkhG&F zxB$;z!{Dr<>+;}z2Zo6yzJvOi+LSf{?Lc~I%g;Q7#=dfrKJCPtZ|2)$D2oHESdq7F zb4jG)$?_}QE40JQi5Q$Qnlgx5&*bY?CL!0dqRMu2fKqV@tAI!K2k9yrq9F?SUSs#E z6DN@2y=B*)UD;>AuoSj!l;frX!k|)`_EdiG+YL$XAZu?D7NZZDeE2X1XK1GKT&<-X zoC-_BoYIlyx<brv^-xwX(5SU@_pZRPLIcgW0fBFVP4W;fSBBjo6w}E!j}ym|xc`LX zaHWs5n>O<!zX$EL&G>5_pca)bH)R@Qg7oyM<1x1H-M=@hgp{Z4_tsIbvg)l1=I~C| zWax9lIoaP{xp)yhtFs)T?rZZcdK&NLehtr9TKERp>#7IpVD%68Z77Eb;c#DrGX~ge z7@M!%o<pW$aHdanZwd)PJ<Ew|`<FX75}Y`3KK+ND%+syGc?x=r!5RMHc{V}=fEb+V zt26@I9`+4&kfg4uVbH#@nds4I%D+rBp$G6db<mg^$`+?=?j){7c~-J;4c6&nbC-IH zKT~mVV@vpjJQZ2wn;4waVEHZ?`hlnAa*9JIArV|WhZfveirX|azooaJoqWBjy35-x zC2n5u%n4z5gH;d4+wNhrz@GIROFue$7dYkxd1_d~SOz|v_|)L6fnGVMK_29V_Yq}m zVm46v2_^RTfBjd>?wy2%p-*(uzcn~pQ)z^n#WPle^VqGMSy34Jq^y>wbEUE?2Ithx zilp-Bnb4%j@VO_b@KCSKM28jjH`khH#alcpdA>4m1f~^(bCX?o(~qgYv76T*J2$Y} zNM{oDarJ^~aOMN?8r(K`1`&pHQMS8rp!%`&<%ZMKjD2)~iC&N4tQWbvj){})7@RY~ zj_hjN%Hkb^C@=Li%gUFw|D@1LWh6@ZwXS~SVSPQ6Gory?Nn!mY9-df7=~?<tf;{yJ zM<uYdYX|M@WVi<BMaB#E^;?e~MW<myYbMh5RCli)+te~vt_?`ZkLN4JH1P1~okyGa zop0Xp<lT}sP5zFw@Au$c4bH%5J=(hXJ>;D_NM@@I&f4Q$31R%^E3B}&LmzPI^a(t| zai{?=T~xf2F&7;iB9Mt2_s~FB>SB!5h3s<`NUJ}{_U_$bhsswL3r_jRZEe%H*V^{8 zx#SblG`I~<`z_DxTc^?YH8|fzADAYr#xff~YH)Thofw#rojNsX{8nf8e5=8kJvsDn zR&Rl>b8_!wr!vd3<-fq{UudgR7x3|Wg`Y@f(!j|_i_nf_(w;RV6Cj&O=y+O#v*EuS z3+zM}>1+(nZm>Ixp~>={9NZFvGak+-egMz77s2}S;!7Hw*))(W<MkcpBD^26?Ue^K zIP+-^%LzY5r*nMOjz7#@SgkSjQJ&I%sVNs*(qH$+A*3^{bwm~zE=9xhcfRwT@{MnN z9UH-T#xjlv|K8vG`{nSFqkN05ZA+S;f082?@~*N?ta3E?tUuoGFLbFKZj69{6TR2G zls6gEP>iyo$@%><TlKCH!oblQ6f3-|k~FuWnRh;Z>l2NC_HlYRd%@dRomUpIJAzEh zfB5&`FaPe}{Be2h^*1v1J#yqQdMja6=;nU)@BZgy(`G}Hx$4v5in>2V;3;jl{WoQB z7ANv_#u^}ByOm=#$RUTc@H@ZrJLQ|-_*RU~o9TPpe@r8)<7~&kPD+@MdZ@MsJ)O0w zIPNy2-Q_E6{C(j<^7A|6G{5xHOXbj^gX|47M4zTZLv7vnY-8z7T9f3OgCgs1uC^g$ z41T3)b3vbN`Yc~6FQh3yQJ1Xmns1W6$@D!h(kUVnyco+pV=%r`-@J`&LPN5i%%eCv z=%gmiX(Mozvd*RIb9y{GCebeByN`V2BjxDB$I8~tTN&GtIY;^pc$VR7+C?h%w65xV zRrZ>aXF*m)g7-OjZXSNK8dv`ONe_ARXYJ_t>Q}$I{9C{ETVY5C5(-Bfqdh{nC`T@v zk(kAFD==DQD<oaM0?Vcov#B&PFF<VbDp_D&k2j57cSmj(h6Ls4o_*!me&RTyh;|^L zyHL31r`c?f4x|TyaL8$lCOu9NbLmuCPZABaN;_ezgSTp&(?F}xajCh6DVK2T-Dx^K z7RT|pwYyW8Cx#|)8nQ#Cwj<Tc!(~i*dYYFW$EMTR;QLS+-)G|v%2DJhfPL>b;z8Kl z1j|lA4-UW6&?l~9$cEA4VT4o>K09^at9(0v7M6Lw)yQT3G6I+6=fKG}Qb|==RT;57 zl^S_eMZ}G&j0HT(QpaiAi~L=@ZHN*Xks)?DaA3GR`^wAZ<&S?90mIUKmQOikauy~= zXWCjJapxw>{OC;AYBT~*F4O8q8LEa|jd>`P;td=~H=g3!tF*F!QQQHAc~r0C8aK?m zgjbwxBNnY5z%B{aW7Flz($3ZEEWbuLx;frBgT-mQGslR7=0K*-VlE<Nca`A-`!T>f zyHyn|l@WUmm4ESn4X@(5RF~%**2|Cy(zwc4Xh{0>yXH^<kjCrGF;~(tdT(Fn>i4#( ziVrt2I6K%77e2Q=TcfFT<b=iP)67zXi#2!^y3E5J&DX|=zm9mm17(&x{mynC#29J3 zQ1R%q>lk-IYnF~3VzQtQBhtmom&&Veyjk?#8rU>MSPKT%Kqo!5-uKqS-{RKE8kJ~a zv~v=_F88(_?3`5GW?4Eij{%_v8eYP4S8psgBHV<ao?%jC?DqAtID_FHS~`F7WVvws zWSJqKPIzD)ygNW==PuA1!K4H8b%ldCv4gS$(l938El-?zwVv`!i$m)yjx&G*e)BR9 zkJe!9H=fqVJUlGVXC9W3_C;}X;>7&*ayEVViZtG<1e(qXBXRFD5BX1++x-2la%mZ+ zpLzO;((%+Y7<1rZj2s%2{nS(bZI5`E@=hz>G#%pD*c7`Xca?s;(|7DeQO0Q8g%L5T zV`ETgJ1JTqO1evy=TJUx-nc^?@bR*J*IvBl^;T4FMRkWxp*@Q6v`lNE1AqqSN#aC~ z+#KWi8t7^pJkPSLbgI@}32SN%&d4Fsw+82K6|&%+_JY=30*bYTcBFm9PeO*MSkN}$ z#AVnH+*wD0=d<!u!!x}#ry+kljq&WpI30MCRQyvq&r~`z)`Rj|iIgjUC2KE~lb77( zacDxi@Lzpc+syVcqqLdtln?erPBckN{7XC2_R5<K%$htAPiez!P9r`MD#}#p!`wCE z#sdhtQqd9K3LA<P?G$C4@1!Mh8#pMt4#0Rp`jqW=oWdi&XsD?MJfLgnz1E9F{!g9! zp3<7%<{vZ(yLb=~(zRaU%1S3NRW>KtpJ1AS<>VBe_LH;_v4GdPRDKNuT-%9?NA8J_ zre3zBw;F@&Tdyaq&t;Y&ZcF$hX)vBpyf;li6idJdYLlOJ(cpZ8$tgE?HRRQveRw!C z-~&1Ux84FSKD>%$t4Q1M+*q$}M6A)*LFOY*KA9!#%7N6M^zlqK1CL}OF3cMx6j^oo z^f^edn@O4t7@W5yMtc`V9Q#`h&VHoly=|Pr&4YHgZN^z~^TzA1MVA;p#PUS?U{~O@ zZIi)?=_}B+J#AA?<*Q2X=*TGFuPYBd^e}M1=^}`4thZ;KEUEMw1)XQM-EF=*d**Bg z5gRZ*?Z68q6M1}`eo!1yw1>20oy}U@sgwDA49<MJeK-3f7!CxTqBYc8he}u8)qequ zd;5a%+hc@KISuT6<-jogPL^6@Y!_z~6dWT7QYMce;l}8Kp`J->>wk>_j(9$N=rF5# z4BdimL)wIlppIZbCP0=%qEM5LGEDz{kbY-<KL!N|u$E&b+uBwc<0STtJM*mOnv2my zkK9(Co7B3>hi*iD{KPqE2@jum<zeiEC#R<HaGq4pak7#D8@f-7Ch7?28q$^Rn8{F$ zsbrcJd+5aGzkre4{=j<;@6{6*96(0$v@hypl*A$I{zjMZ15X5WR0vQY8mv{)iA!IT zM)|9L=3Ar+{Q;N!_K~u`{+5nR)gDz;(hq3tCQ*2cYim%o4b94L<W&tX>P~f|JOH39 z4bFz!>BiXHgRb5;w1egL$_sld>rP()?v}yF5;%*&S$>v}9JzyI;oXd(dINd<ga7hZ z(W@B{^R@kPCOB++e#djjQUU1JjcZI4ji#-1Y)Jc4Kih&!j;#D?e)!%qt0@}ebd#!n z%MYn*iN2|NdJBCk_x+alE>AZdY1)4poaaHLd9Uy)c+wcSX>bR!z!=VilVE%yovE*6 z(o$6BBxB%_OAQa_ri#*+-v1iwqp#rUJnPsb?{Oqy9|eup>yTI5m>{agEMOzQ$Y)?| z`%U#8`_4?RQlNPB2)?*h-mX{g+viEsB$gh0p0>zU1Xp~Dm-Z0%B+3~XWxMfnNnIDd zaw2)%_T6R2VPyMmWURc)#};F{P*mzrpSAf~#Okws{*J4O9^iPlWZ{Je_;z)Yw;P;O z4-(j}9$qX95fHS<OLDJ=V<|UwcSF6AYd6ceAH9n1e5;IJy9|9-ymhHhIo4t<=V@59 zF2)1hdN;4b35Rx-F@-&K5`h+){z^D}N1OAq(yMTovbG&Jb%Mnw$)J8yX~K+@Q^1Hm zZhYuFQ|z;$(U}cC4HctfNAw6~D63lBpTqICq1x=z<4w$W)Aa3*@#J^uSsf_!9l1z9 zMFrY_!q)Op)pf+02QYgHSjeRyxvh8$KflRy-f}44@zPr0bbPai6@N=hPUfiJAjcX1 zM{Wb#(1!J_EF58_&-c+)a8ly;%P+l1+-Fv21$PxM7VkLe$BE$_e3OThLh_*FLB}`N zqvcWSYyX#aj2=q+^WJu-`WEd3P1F!fwZBm(lJDIE;WFdAKlp<`h#uis(iNbe``qVQ z^8YyfG2`W?ZH2!<AlLRGm=}$2O_Y@H{s)*EJ<d<8kL~H9z7c(w%8A=bNAI4?+n=U6 z15<_P?eAB9lMrwp;E=}cZ=L95+=ZlZ6IXTBIXs)c@%8UwaQ+j*X%H`+I&5Yvy>H(> z_Ru&$ShItP<GijPI|MK-lE*x<cn$kS^fEruJN9qX;0yxPMa8ds?by|-N`Uh6`s;6& zFMsJv<#&JgU!gj5mi@c;l>-M3zyoXIxaSJCwdiO!Z{CcKCqFutmPh*0KNAfAT9hcX zF=%i;eB>~DWbKY_*M&_-!+W^#J`EuaNM+J+Xa?MKn?u?O1?G>uaIZ;iFCEVurwgC; z6h6o3>ZNZZ=zAZ&<*xFYOr;~4Au?Wn{dGdmut7HYYD69xxf#7%_%tT#bSEuq_qfS8 z#{O>W)~#iDc)0A_vo{-YZo(l&T}b#{mG2Mzr+U|5ACR|IY3R=#JEZ<Ad<EW8SLxRb zDku6(zK@h^aPyXG`~*Lwho7~h<7*n6|JgqaQ7X(-U=(Nys1~6eQ5@-DP?R#52AdK| zd#2N)Vd#ojjt%Q`O5}FB8ay>k#QP3Ho@Du$LX<!kWtbh)pBO$;HZVxoh({f+CKxFo zJ`8b7<e|Y(;oS`fNRS$?HIAv&8PY=HtZ`cFrV5p4tHIgw-Dt<bjYeZ<HRe!?yV>N* zJdHiuOI`I25X_JXb;1FR_jQxAYLwy`@QN4H#rujIl5$o<S7MU_kH*);w&9%v*Vgcr zn2X?3+VndO%XPVFHI_Le<!`;1tb<_>928kM+riFELy7p#GGgG+Xzn{b(^MMT<p@d( z4W<)>qPRAClW+?RjKG(hF{0jp3zQ4uN?wKGwljD=`skyC*?6`bB(~&%BZta52Bc0B zh}#=CM=(;e^pr2<Jw2&4jIP6TSZ`G~OB1*8E+>5yl;D(x=9qVRAoaCgdMwXSwoCiT z9C()y4tMZ;*--ZE-IIEaVbB~z2{<skx7@;rdiu<nlyBTlH(-;X6drqs!FlA!esIN- zFa%3F8}LA5qdYB?n+&qWLyYmjY`nY`1qisrqk>La_I?>ffAztmG?ec&MkHK86&WkZ zVmtyb@(34jQSZ&SJ$)yw%2!^i(U^1~(^#f@9O?n5u--)Yj{`>z$74|M<58B~Nec=@ z4bP^za^)IJq;EoFr3~-iQ}$y3xO!uxynf<T8No217wiT+ZS-POF|d4vtR0I&IiXv? zzxigcNjqzR)w{l(9qsMX>v{<f2Rt3<eDn}-AgIXHV{Lwp&25M?I0ygSBFO$t;z!>B zt_f&`MlO8-Hv|nyn;P7`X7-V5YiPDE3V!jFK^g`aJv61GKH5>f^In=at%fD*BF-!9 zdYslt0~^G5@~HGDlbV;`d8B;vfG(9^##Hr?=j>Fg!j}e58!2B@934PfhI#wj4!tc? zxO2SpTv^NJ0-FYn$E@@-KTp6&`SQFpMrsGa;BrcXGhsEZUng9}hQYFP{|@R0{m`b} z(2<5;Ws!YJmJae=48GuN0r`02y55rGW$TXJcoCsoupvqe&Xgm6c#*EPck|0kfZMp> z6U_MDrY^lGUpq=4%2sP|PMOd-SS?)(Q>B{?wbrr`XCK~JT_|IESesiHd3B-C>&+j7 zGlj*NVWFBt=vgV6cID(|f!`W0T(Oc~J6Gf=z%4Q9ve-xG&NJIauVHsUx2<EK4-(Uy z`6CV!XIJ?qJ~_NvvN)#FxvE6uoi8{dyGZ2#Ndr(kZvwA!NhF!EF!PRY)7~g~Dqf&I zyrA*K&FZ9Cmoclf>8<KO-^Nb)<YC<-7XlCXvTq4qrBMyeoWN0`<^yGhun9XKd-~4& zlBX5$Xkb(x-8)R{@7fRNJ}{6cuaY162+sm>cxNy+Ptc!Evub5(1|<}wd`<sg*|cRB z^{EEu<VE??pKTV{kd4x`gAF}yZV}J@+O-=PZa1OeZo=47my$a;s<C6a!g}&dmXZU5 zP{#O)ym$GZ8@k%}3~k<wUI47t*K$|Y)9<B7+s!^^3K@0o>>1i%u{`|PF$|}8I7=(Q zB_=9fseySUKOTDJoTM+gdIp0t>D`!CgY&xeZh%|+f6F2nGRMI(?Za;h=D!mZcz>aw zzW&;4e7hdy91mp-q0+7V=^?%Zg1;$0v?jfAs@#r_*pJ>$KXByXhazW4*x)xsK}#Tw zXVvHf4CL)9qfrJ9r%s#%&l~6)Hpe^LjeDJVaS&^nne^nwx>xG2u-G5m(%}5Y@v@1{ za(3?96{C4%D0uTbt6+P1*ao#C^*Vib1_yyLV*H)Qv$?+<JUpC!y3%z7Ouq0N(QZDj zY7;O1(<3W=8J>MkR=C7dgR}e}z7fw2?xoib<V(E0cz*y$hM81d-|xyZU=>b*6|~ga z5|lR`Wn^rrT)xFJQI>_HX@;*WuQ-9FA%H8Pe%?5FF0?lZKg^>a+P<^IZ=RYOrJY#? zg^Zj-SCCKbtBmz5-%1P8ue2u|8d>Kxuv%B1%>lPyX@GIkD7;JCD^t9W=QAln=j7Fi zSC;vZBs>#7<GJP3iEUm2vxAj15Q*!M-@1F)%C*dD6svg?*MJN)1hntLuLl{4D>6mo z&`9K~&hF%39&5zr9jFAhMxNw7_e?@{xl|ch-L-b0tQp*1`ry4D;)&aK*+>x_IU%Zt zuCdw`oJ$Pgg9|FD_t~!Pd&(AcoL~RdU#4ovCF?|baU!4Cv^oyx0qJ?``V|I^cxB-@ zVfx_Ix+JZLp%^}r*Q}4<RQy)@^RdSgb(c0hEW?u${G_%)p38U8QU)w3qNX(sMreHR zYkD%Z%|%)d#*MAp_c0J<B^`1wtM-6jT_=;K`9iEaNr4wDZR^AzLWbY<J~RaG=5WlI z!$_78Ea0u16;EsETh>FfL&ThqEL2eXKkZZdE@iSZApMxU)V>$Qz**DtE8lsoIPz}Q zvk)2&f*|V*eEh3*C7t<sG&r_u;yrD`H*Ov{PyEaDZ-i&sI()EfKfIr?UxTF&5`)_- zU3qO!U|oHz6v4yxe)aqJynkEbxBXoC>}|!pYZ-4(BR*FSGWKUg7T2~M`FM^~-jRG7 z6vFfD0XWHCGOQlGaQaj^_u3D$G2{#~u@8l>lMg$ke{^amYdnpOUJcIc39G@rMDm03 zG5?yvZU11@!gwFvZlDyvrrj&g*Dr;&HK4Uu`*$6G)Ke4cj5ZuaFC9Zam?5M<S2wl* z#tHG-=jvF>Nml!L+g%!Qe5+2Z!<GE(q+Rr=^rKb3m)6}BSI|5{GfjQOmwd}po=Z<{ zD(mchy~@8;Mxe{mKi4v9`TdMX<-NUxy2^wf`l+$e9s5U)WAGo`)K6Hgk#g?T4;fPv zz7wO;%Xl~sqCZnma3c>{j!r-?zw}8#z3-7)@r`v7FT&g6CF2(KT4jMW0-7xfnCK^( zIxB0dyyZFduYHZiY4fT$sm^gT<zM{vzbIF(Ud~FTX~uHD@+*I*JpKe52QrZtn&VH! z?LDxotN=>NseRGCckgvqzp;EE0PuEFz~|P<Q`n+&aOd;;9VV&zAYXz6;mp~5Xb!d9 z`{#A9EV1cW8@-(Ip2lYF01JfwxWicZt6%v)$~XVw+p#h1Bv!W*_1n<<9(nX=dFAI` zjBInGKv*Dlp;>Gd?iJO`ekSVuEuY*g?<c(bajHg9_Kg`A>HNaC$`kQ;^X4sLFMq52 z_W$zR<=W+IW!JV{<*~;e!?Smy9KiW*7}+~Sm^+<2bZm5WxklI_Yyj?GqCLR(8sPPQ z*60pv)1Df+r9%p@&41qtOH<N<G9=Cqz~|@w$(38Ht(svOnh}LZnIV5V)>d|y+A+W3 zY#di<FT3x7tk5CVmG8!7Hb%D_|EX^Zmn-0vPue!L3w-?JAB(f5&vZJl-y9wuPG}AB zw{0r{ByD#Jmc(mUO)Wsa<8zJ9n3lj1G8>tz7r1s3D7mR@qyhJDz1nxCZ?HmU{sA6o zs}|88V7@=itUA8-wXZGzPyh6vqKLC>pGMc~Ai{}KR|EsZ;btr{fW+ea)dFbQPKZH4 zF9W1CaBw%AF^)ma6{)=#uI$h{>6K^n?7*u|W2#Hb)|2)_M;|Q*Hg7N6ZEZG9n1LX= zfI}*EkZ*e$qs+36JFIt<1~mn{P3vYFGN(pzmuuRp8h$0_dT5-Q%{O{$u0c`OSZ%0` zUMR_dMD6Spf`9;3SvNO&OZ{n8>#Wh&=XR>XFX3uL^z>eMG-BCt38R^rUZqVsGcN~v zrjcm%{7D)JTEntwtz+E%VM1d!X?zoQy<^SS&d2;5yv@Kg8qidD#gR)%?F3x@B=b(r zjp5ZiS*|e4Gr=H0?*om~5~+sAS(f#?+*IQU(3j14n{8&P@isbcm+kI3aG-45yd_~C zdRbmINqKkhiggK7;<N%!JJYQ<xt*XLyk+Z!Ene(57ied_(h~lIfwD_QGT;O&*AR*` z({q_&+rD#0VjQcmA3Js|O?UCa#d4PA#PiHJ_A}U7+t-isu&Hd>>;{5ve#Z<q%QWYq zE!#*;XEP#jIg9ZVR3%=KOBO@7;Lk%^k%mJ<q@^kxByJAdiUvuW*e))A(;l$;(D1av zAEaN3H@5>)z5tFualhri#*HWz+-s<@4Hb+o|8Ubp+se(eCNO|10QKze1ZVw(V;P`h zaH+a9Y)4`_JHgL(LTBg|bMeBtgl16KJ^9SDq1n^KA-ZtxLKK)GHg7TBrhH;MXjC4- z=n=jZJ`Rlr(whpc-j8)dOn62Q2L!3Jq#2K*FfCwonx-A?h`PENcw=;)RiJauG9hv6 z(v@<9vhPwqH?|v~zA6~07sxd)2PjkUob79DX(xm{TY+s`ct}6OT-yLtf+z3ApY-p9 zi)p7Zo_Y1RgMKFzT-hL>ID2X*<9m5TIbl0`%Bw!JbMvU41+@(MQ(5A7DpvBT`8w&K zXP@orw=s^`D-jE9&4*vW@T<X@I+LG+W2&CADk(^ne2DDP;OuVnV|ONq>59A>U_;3L zcr3D<%g_Z`Vo5Ikvn#hd6TXZ!q1Qze>3BGgPL!doyJGZPhZhl0C4ahou9RlMhN}S9 zB^7iAGs>*1S4Mz~K`aw}>)1HZO^A}TDYKK<&E1Pk#LY4&!tl~Ze9kV~UQaR=uukZr zQ>}q#ZWtBWmd!eBJ7k`Ry(_13MkT3Td7xoPBZpGkceBI`oF+na1~IguUZdHl20V93 zKdy*@Ry6Fj122uY5~T`G2H_Ra)F}mvE$SmI6wn;rMFP{NwyOqME8WW5nx}RE@C&}= z5t~+TKkFxL$+PmJ1}7&J^=?)%vZ2Lw1`2$XmbP*nU@Nd^)r>GS1BwjPn>0`@Emz^O z9a^}A&3h}By463qkD-WH!WQ1h=aqhyDRrXLRW9_E@U@e5Gq)#Moq&QzzY@9vhs$VC zhT_?^{{Z17m=FW!%S<lN!_n5%X^u%Ay*Hu%giIiB>oPKe!TIV4{mwcjrCgc8;27b^ zTNE;`q;b<WGNBH25Y>aM)Kf}$?6>SI2K2<>TfN{#xa}#A+jra7%E$4z1QrJrbKw6f zOW^bZJcu#FuvN+l<%!q^1HcEq$Sb_gQy%4*Vp4MS!sVo0i=kPC+a<%6=Uxf&y5EaG z=`}d!H!UAyw{esWU!=l*@X#URw$fiKkD#Yo2IczCHj8|K4tZz$7((P0lZWHuV+s2- z%=ht*wuynx@3O%sb+&<}(bm(+iS`?;Y&rhsn^}ppg~`VuHb=5Ab#u5(mXnW)ulN&> z)*~4Mixc6uZtCI8_dABlo`bvb;35Vy-^)jl6QqlgH|U~1xta&7qM(~wH}O!$D{mtP z@52ursx)oefVbp9`tX(Vjng);9@6_AHVf3)K7oh0A)XE$26xC<+o#Gmz7=AN1y@dv zNlTswpr-?rvz~BSZ!tIvpNO-PsY59v<I6EP-@$92Da_DL@IfBZk>$C+#fdW)VsIW~ zv*88$9^syy(%?+r2%T4hGaI=f12i_b24~w+-KGtxQ4P*j=L^5tW`a+e*5I6Pl)t=) z!I^9DEx!Y0l^aw67;Q6g=Ql_qE0?;-LS}4Q-qy$YE7mF=z;=TWo+NAs64nnn`OKFV z!e3K@+jliM!!yDGp2XEk8~Pjm)ZpCN%PK7<rq&EK24{F*xhyU;q<R|8D`7<BfkiwF z8+?HMvJX$JZJW22zx$tkW`(|$t-=^t#*G^k(<m6B7V!kV!cy4V^ug|9l8V%NlCI*> zpYjSgOD47f>G%&BnN8|$ca(?CUz4a2)TFg9;t{{)z2>>!`;cRa{!OWvHXu{`WBZI= z46EC=v$_sFVm(WmV{it3<&hJn^{^!Aq%}Cxw(zPjyC;L8S?oLJ(5)8G)s?dy;7v!4 zK0K(_!z-JZypL=oPwNud#x?R0+ICfm_cR*sYN^VURFI#h_wZWl$zLl^n)Y2h-}8)D z%0KQsZI^tTzrL%u4xU$~L#bj?(=i?W8DqLldk<i6K2Ww0TB9EwgSp$#R3tT7dbO!r zc+I|+RIlEr=nA^8-}`7kY*M`K=gN0)&+6UMy*-U+Tsio_pMjfegPPFEiouzR`P@@) zxVv|m1Y@(e^Cyp&^T%H!RyR5`dYB<3HMDkW;bCl|UWfp~8Hzp$LvuGyBc0Gy)qBX# z@+>_Fv~_83e}^D^Tg$BNS%3S5?OMO(FKJU9zcD?0?HI-|V#-1LvfJzra+lRl(^P1= z!;l(|ThtSg!Rlo6c^XzD?@6z&ti8bgS-O#)qesE_zKcABUpiMCoP{e8z*~X>{pSE_ z;>}0VqjFbiwti4+GRyeU@`P7oRX@DvcysTrU6dz30TUC4F*uX=Jo?Yz#{R@`K99k< z566%VOgg{x(uXsav}{ABMbCsFbq;#@#RoGut2c;q@e%$?9gx-3-#%7vYLb8p^~+kn zDwp9c(pb}kR*`?XuVWR$dStA@Z$7j>>O}wipa0M0?Af!`KEU&jyz)wU_Sp}Yefx)l zH+7fDLy^c4M+fB*@FA|i8S<Gl_dQ7Oc*ktQ=U(||{i?B<-{e!};5`}ge);k#bucZ> zjR=XMPFxA6r!s7n{4&k`kBU3JoE^Uopx4dKEU}7nlyDK32m^MeeCON$PktXfcrg2o z95`^G96k1MIri9I#?{E+6wbs2bdzx;eXvF=H!5$tocD!;@6F<aJj6=$P~?HSlB6Mv zI2M(5l|MH}?v}57=_}>W|Mbt9s9G*hJ@r&VMHqwmp@$wS$1tiJf4E_$mG+y1uN67c z!`ijAJ?5~jXezV4GbH9SOeYU`*n$>Q%L-l4c=AJNr@l=8<^Cs*p>%B1>BN1Rs#9on zN;4{elRZQ1b*1g&z6Xt`vDxv>tFOLVe)BhfGq!^%@^+(5bz{S4Xb2Y;?Fv3Ke;pqT zA@cl(o-aGt1YA3aeXN^oOZ!d|S+h8CQZ?nSeR?7+pugG2_pQ_Jr#?XAG%_`K;NDMK zc`F_HI<n5^AK+n|{j41wU;WBgmjB29;lGDS>R?-8Ai;PjAQUtz62=pBVA2ZL4Ah(2 znogxB1}uKqz#8~u9EDVrBVzkGxK^=O0?%SNn?VtK_~7C4<S;J%46b@GTskA+p}^M5 z(W?z?xf+W+TEmd{zE}9!@wpVwumMtw3~J}7XQGOdaI9k~pK%<8&4I51y24rCcS4Y} z)ZcpS-n|FLn2511ohtd6w;i1w3LmGFvTpv4_a(+}2f=#BC^%ZfneWY0L!#uUv3ZOE zsKo6iMs{-6TU^T+kSFjl<Ho&AYQ6p5JnhIWGfZv0#5-`usL9oOTHX{!5|<uLVR#rP zuNjO^P5>;x0ebS`kBm_5z}xa}ygu!i`WZyH>#uNc!e}{wN0o6Ox5AWb*l28k<<q_3 zP%rci%#>~2wl9I^+s;-zdH7p+Win~OxIr3M*JEf^v3F^=8&8ff5I=kABFpb~l)Z-z zBtGj1!eT9Ho;vbKS;tb&8<V4rp<Aza!<clkG?TC%v~4HM?s9H7xs&<gVNSX2p@G90 zud#79X`{Wxov?{djgn-Rx*}TmzEP%y-xEBV);6jG9+V27^UOmU6xS_XE+I(G&@ycc z+eITw+g>VbXU?8whH?aBC&n6#=bKoHImoG!HqIb;931JXYe5=qwh&IlO}V6R!+@+I z&#lZ%8ZU5+LHu<L_TpIsigg(oW$8Ep@-;9&eDr8}jNRbJ$7jm%<HsZ5^;j@2vqy|} z)J0{@dvRh1pmE+!E3K#WF5es0M&-xD4sRCY`YiM`PiH^NKxtxxrGmtE9lvrNPiMT# zd9MP!OlQzR-8SGIH|wBEJkx>p(xIy)I8o7v=aes9OMBwXt928umZp8)8Z3M+UQA=% z!w=jTI!Bso+gg}gBXQeawzaDa{9fhN!?HuOJTsjh;ZrVkM20E%^yv4y&_tAVdZ8CE zI6wDcj6f>A(t}N>a+W4czQPicv15w&1z|}rIA6Xrj-iiDcJ}FEs;4FNEI)&9|A8ss zgX1|hymf->#kspEP=wSNog{ALHe|;p2D@w=NNOZA-!gy@0=~&oGc^^-8ih)Ea^({7 zw&D9hHh$_KV3QwKdyo`4V2RQ?iq|3&afD1+F*svT(BN#1Ix!GrS9OgEJj;MIOwRjG z<!P!M_`UZtWl=mH?RABXGlK<;lXLTwFVZ*@Y6Bd1K%<7>aPq~gvCX}YoWlt1L{4~9 zd~rG`lPEQos3kVVSXA07F!86QGy4MX(~h)x_?fhZ^pS=<10~;tj_41h5#@(;)a`^G z%8?sYqE<DywhF*vT^bx%M%n|o{O1evTah!|I|1s+EwA&ZrnN5ly^>w(BX(^G^Rb^+ zL9%al0@daJ4l3+>T;44G+Q%uAjm5vfYKnR5CXP9o<tUqX?kal^9?B$FFAAX^cKS72 z{L+H-E*#X7dRJpZ2l8vQT)lc7g^LYv>CX~>Ujs9cFU#Csg)*8}t*>w8BV(ye>SYaF z8}Ya>?tVxsU)8$u1^KjX#0y|n_GmnH(?KUMx9r%9a;%4P)eXe2-wAmBRdkCeGGHo1 zMHlaC>BaC-8wNM#s+WU&t(@k=BnQlfmc#??4j!GLy?p5s`olUVW7+VGNpwRBgyt-k zf3=^G6#33#%?H?T5kvVVM&n5)Iqm<4F}ij^$9`M;VPp?@j&T7P<c${J_Q^Mq@h35M zZ(%}s3*oO^)gVu32vlBK)fHJsdhrmsK|b@ySPjmnPn;-QcWy0vSvh3C8<|O3Ve|+O z<jeX%{LA0tw}}@&!t%qL*D05n%0~_b$Kgfz03h<cyc2^d-z*!JK)L}5PMRCLTKqdf zupbW`b(Qc9Up8n;KGwswR@RD({rntepsm5Vhjt3@2x9}YUkkUKeVe7=7f0BaVB9H! z>h<Zn7{z&S8bgVk$0JDE8@)457lpi{ys1ex@g2Vfy`vKn(rtE@4bb2NLzd0af4Q-s z=`#3;(ZIe%4`<~a12}juZN|Oru!NH3bL9x5K_Q0ks2#t<`##})ds6ve!hv(eAu^k1 zuI2!pH67nL!KaK@7pWe?{L;gb)D@GwBfOFKHFSpMRSc(ngE!=?UubmZA_;ioGxd3T z8tB*i`ZCXvX_0Msesy7F?cKPw^lc!{<9a-v(RYzR^e>#&J!i!i!LX@vHFES~us(9| zNZEzF`K3?(d{!6QFJyv7h=EO5yWkxSv4)*6^uQFcwVmu1%zJ4o?ov;2Mq8PIZB+9C z)r>X7U9B0vshNjmh+Qz1Iy(s(e)n10$mf19Kz?9f#e_VQwmzGStX4m85}oiiyAB~n z87PAb4Hn`_J)%x_2#@tQTp6@Nsp>@1L4f049Ec-Vd@kT@WBN|?vuqehKc|PYd}DK% zXWA=mgRaYa%TtEcP)2FY+V+6n9%)N{cwM16>PBw0oq5+9oR!fPhrsA_f2<sSPo09W zmcE<!=mm@Dj*IZr44%%tI1p_<c#zN<!#IbqK{5S<Hh86lV>GX+2G4}LLS73p$5rUB z51YTMp;>wHt`Aq<{&+X50a^8>kA>O8>uMOC+(<|b5-Iu`^kfCmjVmnaCN$vbAN`=* zxO^@=qAs@v`sskiJJ5fZ(YK{-SFv^DfS{qdi*Z;&j)AmH2HJL(>y@(_oW)^n)4b%p zZ)id8>N_FT!$1F&$<0yQwYGm&t3X3epw1Ap|27lT<HSFnoTe1V-b^4!<6Y`yrn8>m zYv`7%a@38=ZL_(Crk#Xyb&d2b&4@E$^;>m{KxjTfR>2M8nl~m69;vLAj(pKz=|r@~ zDq|#DhR$gl*s!w?L)E^0yOG(@Ab2%w-HO4Pv_t5~<9A2PxsyMDpVr{zxuJac1q{xN zVLj-*!?(hyk?Q3aej(5A_a|~uSmkLC>QZq{TiQ1RzHkb&liQA6bn<|ed2Zd6B{<Cy zt6kMm+R;Iz_7mn;<-I!Z7r*$$a`NN}-XWFAc=+HU>hKaCnok9XRc~nE5EjxX%PWjz z)#BNA?{k>$?P;wC|I=>m`?t!5_sOt%71=?3Jj}y9%{6(iz?p}>xbIO@!Z+M#td=H> z+3N(qd#4z~_gmlkb~(=KE+^SPM4aNMpMJXR+_Ni{S=-;q_>-}$V^H*sepZUkVvt>c z2XsP+4tGB&DEq-7CbI|4l%(ns+B0GZMb~$1uCrnvOGYHOOBb(|Kl<ALS$_DvA4I2m z_~^sX*P5c2^9wH$E@q4Sh}AZO?9h8GANhrf02@bjOIz|7HpT`~$7(XGHWlgkf$L^_ zl21!w`HnWVZEYXvdcu{|I9t`#)H(oGdyI6X408W6oh=8kJ82ZY?}1zheUty2Z=5c_ z_G_ODjvVi}vd(@=KYoE&002M$Nkl<Z2UJ%DZi3G>bZZaPuHe3I2M-R%;H-_!amjYP z-(P;|W$am-TD3OaHNz_89DK^R2<hO(c9dp9)AsAiDKOw)?{k+cPpP}FRWCm1!}j}G zJ7RGD@BYabAc{KJR&i^OS|Lq*2zw-=N@*3Y*7U6yl(?ec^O0#htI(|i*`?PV2u>Bm zMTEgDisU?o!mW5Zz4X{qWhbrDPjhN4v%&Nxa+55DYr<hP+@qpp*%EAw8By9Q%ss%T zG0vs`8VOVa>yk6SA&w7*IhU_Vd>X@LY6lFybI@t0FvFmopDa1p98XvUn8r!r5C<xr z);tD9J7E3^llhoNuVj@3314Hj1g;0OhCRQrBeZ-O%??N*;%Uqo4eTDO#TxtUEKK8) zh~PJ!80EpB0x``XR(SkvTD>rhgA)&C3=Dd4bpo3m^8|6?#xS5ya&@q*8er$2*<#8~ z9u#6d6xP%1@~g5T%q~M-$LTWaE(~ijke+RO_8m+>dfUpj)-WIrgh>Oz6h_85q?w^n z+$2v%?_(C<HrlmocLwhlh_QU*_GsBoh=?6~b|OeGvcblMvd?fUk35R<MTi%AhEX;= zn<m~#H%90Il<>85+>4aqK&%^MiOVp=5k=>;Z52E>Zj4}5uRAG=TiYXpL<c;4pullZ zDc1d+(^jPo+uzz#+^Erv+m1G~#XRzvv_8kIx`#ArTbQq0VjDT3pdr+{8CJucQ|%z# zfN>MCmtE%4gU2B5GQhG}ZV~J47Mnd9*5c5S!z`N`Oul1yO9;DO-dl;Gs^QDY3wfqa zLJ<2fOWv=A-i*&A9L95!CR7~f8Po}%r-yZvzuGV_t~_u6Bt0k#TmfLaR-?1LA+PZq z;X4g4&FGnf(mBVn^=V>$>*aiR^g6~0_y$4VE3Htjp6;$LFm7k~j<)k^d$es59un{V zvoZOv7nE%wo$76DsEgL<Ed243rVZpTCucP3*d9J_jmWl{cum_NBdoh+`QCE;o${<1 z-<n>Y&jy;@r}K3{&b>0A^}sA2ey;R9`#grAA#jL?Iw)OHngy;od<Iv5JLC-mj4?LZ zxpe+6hO2?H4Vv#Gc36}P%FckF)Trv=BZ<hR^$tXr7BTE=02-Nu|AyjO<;H;t`C_|j zaHc-Oxxi$ehAV1Ir8JmMl}i_hzs;y<<KWg9s{1hJST{W^oqX!j;7knX-sv$yYB1rY zhckoaw7GDg_!wTPW9gp3**Id#tL4tR#9V$5N5btX&ciFzsp6Qn)L05HFA>%uak2PD zql_C5EwORc60!o98a!$=HiOsPqp-W=4Nr1Adj~%WX(4lRPodFnTx}DB^r|)uOif$M zvVp^P_Z#uWv-E%51#Do}Q_%{j$S*Po$iyUY8qPra)7a_2i$};qWpc|?lwc+tl+awQ zdwnAB*goMc`&@t17x^ri@l`V5r!e_kd0Mjs9$@o~aT&Qd&m@(`a6NfE7jRF=WR8<p z>4P-bP)F&Pvm5^DV!~?)Il6i0?y~Rj5&Bv-l2d+CS2uH1fnUS}9V7>}wf!rcPI6to zawW8<@l%i6gxmq_UfM3S#{@^MxO5Nf;4;R~TWns-iVlr_LwM_MfLEQwpn|Ep{hxg9 zQu7uc;z@(L`x>~x$29%gz-GcJIWVVh)6gr*lD?K&(I?KtDTkhyuE?;xdy$#_gvRjN z8l2sjxaMK&RC>^`XIynxLb+jKLL8~Uvg)Uo{yH9C&{R`Icu&s=P)4hBrD)GlCK#{N z$2k${<nlfgUFlYv9~iaR>aV8U<44+By5f{4M@Md!vu92*xyuHP7@X~koj9~#&g2W< zi?iBaRsBR6ro5Yj25vK{d+zj^OdRiHFk*k8{E{Y8Y40f8inIe=uYNy)48KF0-M&4- z1oTEc%MS*=7`u)6O=ZP!-CLvbi#xp67`SZyOTT`DSiI(^T;8*1Pk2-KQrYm{J^AY% zAMwfqoMG@7gEM`Gt3LuCWwi$>lZENWXFAK}5p;wxj1Z8Mx|}jVxnA1`-IDT0?v5kV z=Lkb}2R?C9)P7>JOyNnJkQ#*7n8Wa=r`#OI3(o~Tc;!=Vg`_t>pE&_+TRG_yPhQgK z<giHnr91IQ0ZE_GNYuHd>C}PrExyy{{I2P}dH_2zvC^>5s*WOY`%K+UgQ;|COY#5! zP2W7DKS)~N$s;xt@A6)X<2!LD&GFbo&~VkQ(}(ziQ=LD?PGUKCV07;3XWxK<q0&n@ zs2=o7Es3iQ&LDs?sM}(Vg)Llby86pwM;{^H<eu`%3r}V8(+M-nsjve>>V#}lucvKp z-MoTat43JmAfToW6=&8N_@x(Qp=J28m6HoFmrwkY{FN^rl<8(<_3MhiihJ6W*TJ_} zlE(neHT_dOnP^|@Mus}33=C{3J9ZyRe_-6#$b*LF^vDM?3nU*6Z%$6o9?+Hg6a_&u zKF2r@{7ck%3BBC(#&2HB_fGov)8F+IJ3UQdSCaOyO>_om4czv3^;zngKcsDr;JEqD zdR2N7HnOXi+*dqQsDpsuG_O|vw7OC4yTBr8Y(ZnMFCd?7w^>%UE)fTHV8?EZ&ckK* zk-g|_^qJ5}Je^5zRdNEW;I?O5P|E@BwSB${-1ZUuRINvFwDR-;Z{CKhcl*jDL4EVm z-@;+JUNtuB$m6~6qAJj?ZUR43PQLmY6LvSs#glK8X+mrGt&?ZH;+8%M0_ViwrLF=^ z^)e1{gXJ#z7bn>*IJ_7L_}Fr&XeR0TX_>ZRZO2Lj^(pNbm~2l|@w75|P203>XhEQ) zA7EHQo=-vRGw5cw#`G5E8D$&l!&AC9gBX<6L7-pvX0YFuezIQ^^sQbWy$?KCMpnpK zj(`G(ZN-m@Gu{iKI%0i767H3m_J5{#BCDUVkgH^ju{vsKF2+^YN5{(GmhJI!-o1M} zp<P&=g5EwoF_y8ra2jH9Xv11o+1x4@Prr(;W31bO^6YcZ5m$bY+MyHKU(hb<5{}hg z`tT<N@V<v_;~`(Dw>K37W>AW*As!s-yLXa@{kE&f)%C@hd}I!-VNn^8zL5-kp2<aS zl)r!c$A4VjJpM+U!-R1Ip50GA{VWFOC&RAdKQ|VXqtZj=fAa`2wJ+cMN;Y=SwvXRt zJR*HIb@f_pCF+KCyz$<d-Fs6%r(WK0T0f5pwiEyz*yiT1UVgtL)kQ}my(Xbkr*!7J z5nV{*<)sT3gEPm+pZ)A-2|x09_6*T(Vdy^TOGhtD)_&tPKv{Q0bmb`@zRzJ*-skl@ zUOhmj*59UbHC4q$Ey30P+E~PmyrPbN{Ph#%8~^t=%GbaC^`!Ovkt0XSM?d~CoXs9f zy`)1#3c5+fwOyg@>$pamkfmwHw1a8vYwxYlsWo`NI@bQA;-SJW&F~#(+Lp3h@qhK| zmGGo?JICIBr@hdzl-|wKbZZM!N4@XS$Ob@<qun3=;UAWBtn${$!4;I+u#yku7)JBb zrAx>p#=*!d?HTH$pZUyZ%J6{$DN1{RKtFusVJ0S?!7k(G+DIhop-i_viedQ-EkbIQ zjO%kRCQPNJZSMJ<C(<c5|G&W*^oXG^fBDPHzxjoKTp2E0Cn4xT3t}Nk2i5Cb>Z8zs zl6<DItO~}O2`DwI5WPav&ZafsDzK6kMZ6OOFuzc)m<h*2WP$1Keg^O#dg#%z7iL+T zyxA}#MA#QYnk7g$4)`Tf4Z7_>Ttk^gCf|8Dj54i*L<eMU?quihU|Iw4maUs1#;MG* zm|lS|<H;xv-ZZ-1Wrn^I<c4^g${cna8Vsc%!!d}TR@hqC)(cxSv>kjpT=F*jMV9W8 zxB0ZNw}v)_gdMCK9aMaaKjV41(U}_%uFVdk=4ajF(M`T~SQ-|5F8pn|4x&BQvJsT& zHSkTt<m1$Pmd<#F`#C#h%ADuaTf+{`!}6<8!!V9fR0D!-t&!Z=JGOE>GSa>XK9oqm z7catPyLs474!&4~9s?&N0W5vY9&f-{YW$#W<slgR=RW$;GQdE37SE1emOTxzd%0ev zul?Xv;?>TUXP$hD9YcqhZD-Rw3~ikZc-F5c)(&~=iPuNRp(k(`VOp$$@XazqX<HjY zqMc2foTvjt>*fr0aIWB>zO|j|V2($DT|weNOL~`n9ahstrEcQd`qn|F>BIpO3~V?g zP1vqJlP>)&y<`JGjKrr;o@9CSiQvr50;llwHlC@I1bukBZr!~fL;S8NKjX{>-l4N} z^GXdnJ9q8GaH5eG;|pyeJ#JxAL}N7tmWvp(C-IUNI1SKxc1v#xR^d?bu?;&h*eTd; ztB6GEBCl$&HB3MUMp0)Yh1;1w4L$MR6F1;Xk7bo+y*Z{ZO2#-uIUO31+1&B29(`9Y zmN8<7j^kao1pEWgVLUj}NYWkn2Idx*(vJ7-B#nsXXZTTE>$TbPldxMKjV3m@c$VIL z?)NSJg}>#o@Ex#w_?>NPT6wFbS#jz!%Q3z1z^$pf-^pJZzb#t@MOm@@{BxxP8r`ye z6CEao95n^L5ia5PFrR7^(14@|DxT~ZoX?-W#Y9Pe*|Ll976Ys-pgqKq-0L?CL({p* zJJsL}{Vk25RNcmaHO99CG5T#rriqGL28G&A{Bs$vT_c#H-KZNpbm{yxXs2L&87v!y z))UgexM#pekEoZWM(v)3$+BkVF7cZUsllod@*xBNV{oPp$ej*iQYyzXNYJCtf1M6c zG_X{qv8jIeL_Db6Xs80x7-N<&)GXVs$RI>Cow_{(p4}J=7MYyXn3By0d1up+%uFDP znoqoK;AeMF@8EP|tpnckxANA(QDhU|BORQ|Mf-%vx~4BP4-gmQpV@m#Zz`gmwu6UC zhIB#AGFjK=rTmbGk}qimkEA*M<9*FE#Uw8u);^$qThmuu%3t+8-v%$$m}MU&4B~d0 zl`*qS;2Gva&rv;a=Lk!*2rk8G>`Z3k_aN3b$w(i(0X#+`Hlbo^{2Z%A28pY>_u#_} zzz8vc5t=z9&`TW~`cuKG#y(-SVkO4r^XJbKVqu8E9x;V?u+zKs=AU~vST_fvG59q& zQC8YljUpQ+=wA)(v5k#lojA)R254^egtiZ~ojf(rs0=ETE}TCX**E;qLrl215o;ar zh{NDi3<pnjpc{PhXx62|S8k-8oWwI0a}PQ}6mE>owxRuL!oP?&^9W~jF*#`26EQgJ z4eg|>-e4{5wD6jTh5$o^=<x+W^odNCV(1=cvd=bjLU?fVW(*W^Chvtojh}(Obq&2q zb21w+$eSwAS1w&d#<)r2mRfK6UHLsSL!P26aUtE?67r?=>OK{>!TCknYbSEXnEzRQ z)9|4%=RajiTlJ96)Qc7|mfT{`fKmDt2KJi=%P<~`<}J@8bQK@VyVba=E@3|8LK^9A z1Y^r}1{&F{5w9}iD9S6Qv2WD~Qj4u}LHVcL)9e2*{Co&coApfO8QWL*S_oS>#evVJ z=h@$2l!@B0g)+t@Rwkr?QB>A39tLN;P&KAZGjO|j^;URC1M&<LaZ_wqtpU*R8lD;g zXJ!d?WjtplKhnmeZTHEDp@qI!m^5lsU7+ebZa9?I1^;@mH|SulvC?E<&vWq%Z-Rpu z3zAYD!*BQ(D;D_4KagBaqM-|M)}F>|P95{CF?8}kX`05(Uunwn%ul>je8;nu_cDI^ zDJf2*k%pxCyz(&&4$X8RKe~FEtXV&Z!5O17I*Xf$rEQd5@Q`=}c&^pRYBn4C2Fo*# zKVA;9Y11P|_NC7jr`Eyu9!;qUJ21y2z}?X+=pKaJA}{IDv^gw?TKIu7E)#?NMAGG7 z@WM;`kD83DH0xK=HFa!_Z`H$Dyj1MQ$V|Fa#irr8wCzUR!YfbN?;EymU=u6<b`GNp zR2|((B<Vl;fgN%Rmk%^7Ra|6aMf5l2l3wzOe@&iCuB2je*L6+3Y>>DP+F!%D7TmgW zDs-%TK)$GpDJwNnMMs4<Y%`w)hyJOh=PI9hwC!r8{Fi6-l6!BJp{t*_Jm=M;_D_|L z>%9-jJ55htjt)4-$~*Ta>4G-aZ{Jl8JoOmillsxSF|^sA2rHkpr_ePZ27Z1v(A8^G zbm(yvxF*Z-*ETpecxv-meXTO%9$Z3Fv0GC~POA;h8WV)gXS3AZRX8`<=it?Eex1#3 z38_Tv-45u$wo}*cfd&|~)|2*ke;v<WJe;$ti+;gArZzm8gR>l7`M;#1!C|{JZvtO? z?>jx4S061NL)1d+gPf$|!>|kR%~2UASw`+)7(&U{LBUN!4c(~TD+n5poCL1%Sk>Xw zjWlY}hf;U-=jcl*w3ZXlEvG3~*u-huZ&w*uVIf2QON)HKhdR6H^*D$T=+TD`mNVzr zP=1VwLS*VT;`2ITuDqKV8zt==Ve4>yK`#;p^`t?J%##?Lubg`w<1{Orn6!QR*=NcY zbQt+2;~V)1y!PV+^pO`I%){9_w7e1hmb}{E@|#Xq?$L8|bcC@5D+R%?{cl!7@Sguc zi2Yc8wD=0W`AB3{9qzT)epG(+qaS6`-H-$7(#IZsocO&@G^vH=-4BbgY|(lD!&Xs7 z`i(Hw)9<`@?Ce-k+lyl-<=y=b>zT>;x0N4S;Nx0t<#6qXl%o%FxT;UX;uMZ_r%s+k zH)Q+<?P+-a&bPl^&Z93LW<}W-zVL;zYxiy|0F|IOG49g_BEPDS=+Qefqk|&jI*PUn zdmH<_J2<3$AV^mdQQ&<J>n?js{^G@ZPpT#O(Kj5cZWtgGD)UvZ|LC>yZ~x7|Er0T- zf0FU*!Gnj&&wupi%f~+Uv9jHj>Gsc*squ84*)c<C$e$iHCVQnr)1*vatg8G9=sx#Y zRfY5|{BHH^@DZ?j=%nL#+H=ZKkT|_*@Rf$-m6ndGk(tnZOcLm!U3JJ+h1Bfc`B#C3 ztP(y~3%D`2Mr9rAv=>;e2z2bA!{!yj@u|x@0ikWkXOFN7eE7g{R%vQ8(L;Xw_8sNv zr=BSX4;_rnrJpgftW)Kq)vtO+3SNyT6Znv8prQ)76F)q*kNBXE@XZIE=}$Soj;|0> z<DdMu|2Vh`${+|0H4awoNK~d>R&Phy4hqx3tfGm07a_p_g!D4Kv6WTQ9P~RtUxLux zc{Upm@q7xyi;L_xu^i^$<{jlJ2B6D?mGFBFt#Vf-;3~xP908}2X}nnlokC9`)e3nB zrxF^U#<1uBQG=9%(HM$$H11+Mh4Ib&j7=p2#q)_W^<JCAvsZ?6#>IR!Tv-p};re?L z7^~re&X_z*>+_AwIGT?HEev`!yNpxj5(b}{j|M=Q&TqVWIPhsVCiM3Lh8~5A#>BJ% z-)Zd9fGne$pJl562)}83W*b?Kcp1VA#g{SsB3y-84-Gf(b1Bpv(oN6_3ZH!9J3IZf z8D-e!J;v@6MsTiT?=mU9sq6$D49{a^s_^k17_E;AL=`9qI>1}tw=gIKjNj~lwHHrb zuLlktDxdn5|Drto;`3z#-dmgZ?j#0WS2=Ux90KBM*}HpBId*6mV*u?yhoAy<2QMW9 z!f(KEu$4iuVF6T4+-X^(s_msWn!?2ahH<_e1lsxAQ5q;;yb7bj$h11RSr2h;d$vL` zSL)P_VCh4v7WeXo-`alSDgzAKVUgw6(x$&{1M@PihF@uE&$cb)2Y<!Rx&Pr$h#Rz% zxJysd?rfq-UGCr=Jb^b_2RjbCN#M?1yYVO+#3OiJHW!@2W8b<t_*L0><dLJ4F;~uC zIG<Vnef#$(9Lo6EL^ca>@<QIxSS>!}N0r1eglacN4{@O3-Fi5o;AD$DQab^|UCa_I z_(p`c?QUCB;Y{pwpiuW>B$>l7?WB>j#dhP1dVKNSB%b<rM{nR!h>?aR%(t#wB~mXd z7RY}J-q3@o8?QCJoh`4nQ#BZi&k4SZS2K8*SEO;h|HZes6{k)x3A^e2?K^2*rOG8z z<}1BfFK1C_m@qL<+rd2KHQUNOqzT(xJVj<vUwO%V?IgVVjb)fmot4!qoA4yhJXz+B z9xK~-4PnqgA&39v4S7<O<=_gpb82w@f7yHUAkVU^&hKSqWmaZZX02KKzV%YwlDb=J zNwjDo7Hw<;#xTqbn7}hI)|h1=?16A#hiCq91fFnshzUC|F!R4b5H?5}B=8_HNN7i` zrMK$Z_cbf`z0#l0_q>;t)oLxqh;W4GWxn6r?sD$A=bn4+x#ym%rT82QEM{D>a9-Dk z#Rhb-5tk!QimC9^!qlj=l(a_&$106=Wzj6F_(JK7g>%n3gg)@I1Gg)^u2VHr8-lmF z$d}BM2jVV)m#dd=QMU*m(Amf~tnTSdg-&I2olJD0a2}W+i-og3oK->_UlhlOGxt4O zTXR*R(t~RZ%e+GSD1TO^c#>@hOx2A-lZYU!m>@0;Ohy+z0LnAS>6FY4{8j!r%dg^B z;l;Y93Zs~=&92(?Y`iKB;Tu{B^{lgfI{4?=c8aojh1C$&q0bSLGPod&iUI2k*hG_p zf!Gfp^aX_okIwhJ2p>&4e3OUy-PHhX3MLR-S#ELGm47Wh<dIPXQ_h5;Y^Eg-t$6h; zkGKCVg){F6JdZ#%53S0Fb)BIi*8!P*h;=P2E-6g;Qy$7;H=%+8MahQY&Ds2G4(7ad z*S==|k%v&8Y-hrTR!aH~AJAt;2_JvtR#~t@y`rePbn$X?=FB-J!SJ;<iqC(9S}mLv z#8f62*7B92qmUtN@?R}|bf=`kSr-vb#EH4`-`C<IxPh-yR}ntJiF|qz-f`y4=?ruq zef-hzuS`0bCCBQ3mHg%Vh1mM$rh(V+-)mdmNT0kZ)(cwBgA;2``fF*?0ZA$5hzmi? zvca4}tedbnAvem(66F|aMf%8q*-E7T<QJZ$1gn)t!aatSFxe1)sM+Fb75OFk)BxTI zXW$Tb{QDCHTiQsurMP<KG8>ekpvRhA|KT9l?BH|Iy0Czw)H^h88hj!R_!WKN1n#VE zAV_cDHQMYsu&3hCHVi2LGv5bKVW1r3fA<cngII0jhB~gYIe7SB;h8w4aFz#KbbiR! zL8W*X9tRh<aK&*QU%a|9+q`8n`$X(W`!R3^z#vi7+2;Hcsw~q+Mtg{X`3cTp`U$Oi zsvTJ}VyBG7Cw-nrIeYaEKBK2la^ssZ1T2g)M537XFbZcJlSSct>B^l}A>p8iz7^LE zD*qOyk=<ssb}ohUobEN~$Hj#-EKd@S&<f$bU+_J&V?h>atJ%l~d}z5E%VyxSu2zsi z3{&L*t}tucd6msN?_tGXy@!@mILjaSBNX4vBS|C;lFBzE>%8}y(~E|#ba;`Hg9pEv zH*a8e(5{#kkK$h*CV#HbK8V>Uqj@i{iyRKkxq)D;oK-k$<-BoovmW`~_(@$E5@QJp z&s8OB!LS``;J4yu@;Daudv|S*d?atH@8)k^QU9c)|J6ArIL7Z>gRhm<Z-ooU)wT#n z@Z3v(eiui@1I&}>__HQhXsk+Zo3(GTpYcuVMZEB!rK)w|VVX6$KwYDK&`=|JActx= zkyUov_RyvdN7iuv0cC&NqB4N;hw#aet1Z*%0^f=X5#=Q4$yH?T$02`@bu+FvTv0Iq z5{6@JqQQ)EnUnD(MIV%L2lZfmXhrRZt}in0Wa-b^!+w`T9Oo!hq`o2>wBIaW{Rwsj zs(0e4jRazB+x)aw(&UpkPG4mkLdKj!rd?s|uwgSBVL$ywHm2PI-(!*wkoD6o^@(Xu zp-TDMdoHVoxtevZE%<))xjUjX;-M>E-meX?CSDik>s<p+8^1*zF#4i?y%VO;3-{*l zJ8|T@S(aG1f6S$Gr<*VQ`M-yr@mb2GVIO^s{h7uCy~xQ3-c1iQV1ByK=!LHOR5(LB z*~5bH_o!#vVpn%O(k^YARVeGH!$uc|7dfQ$s$b&^bA?@d&3CHP!@8$dQ=Vla-yX;1 z9jn)tXcM-1eUv*!5C+E;Dw`dHWXuE)G{3m^QsImuFftzLnX<461OI7Tp({T5K7F<C z31{d80;#qO2tDblG~T_N&C@YHdge{9Z@&EEg=UNm4*O6JYl!1G;l}lw&8-_(7#lDK znPSod*i1t?X)Ep$rdh>u?feT&HV-lZGSWPO731jUtp%6x(QbujnANx6{>;0D<eNT> zXJ0B|NC(QQ>O7QPGaf~`HSQ+y;LLE!`i@01`Ab}lh%9~Duz2KIY7;m5#J5Z;Q9t*& z&tc{KB6t|hnEG*6hChLobKzG6Q;s08>N9l>JYFMT7KXoWxs>sgD-3Try3_V;pRI+q zZqyt@cE&$nH$grER%qXFrl&j`K9X<6*Gk^2uz>rG55nALLj3Z@OIbPWim>6~A;zuO zn-6{H1I=eX`|0LA?|xVF<3Ij)n<t-o5}k<a=aHYO1LaTmErD#)r#tDtfNny*En9VN zS6cl>hvoA8rjKtjY~f2fC`9N^rX??EsK(*egM4%m1G@_sE;RrAU;GPPOF-Yqw_5Li z{}22?^9Tx6$N9=s+ZgXr^psN?Rd1rWXdk%1iUtiXq|MT8tpW6F)P*68FQQ0Zf~$k8 zvY#su?jrBsWo3uD3(F+kYvd)}c&~z4>*g3zBAb`8xoD(K?Q36PILZtik2ZhEHe(4R zNkcQ!v?*X@&XzLb)&qk)W$}yP>ocGEO!NHn&u46*ZqI$Mb|GU=V-TZGM!(o6A3uqa z#4czBLp<q%)2n^4hK}O3<6rkJoJEP);TISpe~2Sr{m0|Jh4WfmsDzQhsEo=ob~+nt zFct+~t<5z@gdu8HW>TF=DTf?n8d3#vKg+DN09rtKrt(DpuQMn#hWiJaJqWJP9zPKu z&I<FUA@OGhjdbJJmV~;&oeDjfL)=$D$>uL?-7-hvuoKd9ROPg3siYcY@FIb@bG$UM zg8{Q)o!yY=U8dqLr}|e`LE&j9;b{jUPV7Kz#KPDq7Q?83$8f&$o7P7Pr{=Aq%6z=< z6n&Ocm`u|+4u(yq@K;Jt!>asJn6-R{5pI`ITjsbuATJxZ9fb8Jjuc3llSWCaz^+i_ z=4$%nr0$4sos5(B92{2#ofgD%2*Yv(eGSW)-EBS=Eu^L8nhI$B^f^S&FrBb7OZq#6 z+i<TnmmN~q`9{Hn7$HND!NnpEMjxMG)XQC5mCP^;y_uzV$4@@m9Dm*8&G-M<k2d?6 zk-W_S|J0eY)caEN<f9LvAl?FeE6s&V*Q0RO!gff8g>Y`#TA;Y;rIzjDG|Jf)-{Mri zOyX(_mcrst{HT--ZovN>mb&85IuXHPDCD8#tx5siLJTAP7o)6MILoTb7u|)}M%E2l zcUu3u9M^iqx}Cv-v}GOd+m2-%mZo3%%JbAEZ31R{iw<)G^nd*LL+o_EnPtIunsaB* zgEcm-RGG7D4=|6SAlVu^ID78p(9uqmHSRjQ2Wx0&>#knCiV(8BIdp(s(}CB`7|*l3 zByATZhqQO=*3ISyVV8hgKS|qBTzg1kmP<Ozqy-yYC@e`Ux&u*Z;j(IHl7l-s!5#%d zaMEk1g)&ctgewOYp`|%Gm!&zEDYL8%Mb88-O_rJEpT*K{iKQ(=x=4VG-5AP4oU1sJ zcBS!jd@UVWceV``PSTYVDYi-Dh-dNYVY~9M4d)%OSr!lL-NW)&R?A=;HXXy7t}b}A zMC{tU;k8CoIFY_g-*|raAWCRx{>dkr*@qrs<F%dCAG><fPKi*xT|!n{<0UuH7K)T* zrloaPbMxv9z_FAFMa&RFLaY^SFSI=^8?^GPu>eAVLch`xO9m$=s1F7M%P0)pv~4@P z>#AUg?@N^wfzMu1p$@(Pu1s?UZSB}CecMr<<clA1HV*XY#j1EcjA1>N%l#;|hZgTN zgSghv!nr3F&cH&kdZ~B)OsjAXeB5U}Y06yC3cGEeDoi;{Kb9KMG^iwA39|892)L!l zVPHV{9K4Bd=|4&<c#8tJJWc+#0PM0f=_HoX(jnPKi2x}?QK-_OWpd`Xgs`>*tyzbz z_TZILNtDyN7V3fa_(+~|J<{TgD<PFKmVs|kOk3%qH&<@RLztu=eZC2ACw!QYX$fbg zYCKM!Y>QPM2SYrgOi#GHCp18JXTn0G5&p%2-<&+5o$2zW{5H$`!5DCA;i_+Gm%qxl z(k^7c_8-zNa1Jua>SLwJ9D~WtJNGpEjvPnf%;3T0@tL3y`wW;8-*So(>Xf(oufBBg zD$5to(Z6oN>UFf)h1F{OnGvQBT&O&DNuK47Vg>q((j0-_iKFu2%tk)M-AumK$5+3R z@=;!Sv9NoJHhIq^?vc*C@=7L>PM&-$ZCOR6ygGG4IKz5hwOo~8{Y)VEo<DUOE02M! z7SRoe<+c7ncJQyIYT_n6(zV<u&+Jns=&Mw;yKlk4!-u0Rmj9V{cU1j5Qo&VE;N}}? zU&Z~1%R3e1b%&wiSn{+_mJVRZD5B)IZT%9*$uX6l4w|(vzKnH-@l;mpK8iJ9Oun-0 z&?4Gyz_GBTzDYZS25_VG`wTo+rSnGmz7bYKIAK<kF(^QQDFZ#O9loU@+ph3T-^IFl zVvKrR0&kmffwjjh$xEvs-SMd46bJkgM}@Pr7-cK)-)7>`JsI@>tl#WS@Vc_-cAx+~ z3cuuKoso<a7EXM7o}gVmgv_FabJrgwf(TERwml!fC6#e=0=W)f&R51%^j1hvkQ*tY zpA|*AuyTp@6)c>`;rA+tUA;9+Kkj7i{H&8XrEs35ADc%Jy@YJwM4E;Q`tqYmho>6X zcDe}uvr!)RrEn?bWcX7CBn4jvB;tm1iS)v0EPVJh1)&Ti0ZOV*BNHCNxhpKAU_OWT zWKwZwAS_kHz~a{`xwXO>K1kX@GM6BX=N56R7S6;{o{<*J!?sJKHif+Bfva^!o5Zz7 zZ$E8^l@jZjxEx@0M7ce(FA*R{wc^XZgZwpuIC|i4^Oh%G-yAux4>=NifrI2?fsJE! z{HZ*jLs>L~HR9x5WED-g{FpFR+46`~g3-L?Pk5zQ`#b9-VOoFkmc!gURHP*}@#1rE zZd~flKBYr_?yG*wij&bQ@YzNN2ib@jYtK#F_hTf%1P<-ViE3p7aU@StZXr0~h0*dF zpL~=v9UsW!lo2UkTx;+iNe6kB^jWR9kv1;PD^K*IrA;4XTW#BE<m~Vm^RRBX@?)ur zCs|65e5gAEc?1D<TMylRAk60|BJ;YaF{yzgT`r}4OHbBeRb%iMyhHE0)>xdR?J!a2 zrb=6nJ=AR9kNdpihf#*$LJ)b;cCIC1;3Xefu1&Rjz7Ns;JG1h9_0g5|)$hOAXY*Wp zL`lF4(Y5wlhc>Uy9mxm0SKP4cu#cXbXO#u=?i8}`^Pl--bK#}u31ll$4u!{Zbz|sW zcuwRW?ql7IOx(*jU_E_O6rWgJO1B}P0J5fTc{X2<(7gcjU$Cat=X>1c5T;^Q=)@q; zJhfM4dEeC8CDelf4C5%}EeeZQaYTpvE|hE&%FY@fDTm9ijqfTe`%&d{70%MWM^<5k zsA!vDL5z4Rx5*F9y@y$`7Np3#K4fB-ua5t>Zle#`GTeOkvu|lGUSUrl6#LtD?u&tr zt~OqI=@hFx&xW5*F=6HEuaZ9&n$0MjUBz<!;wk(#GvTa-Gb<BSG>Kl@sVkOjLs2-t z?Y)Bi4G-H|_@V^NAq|KZ+k%#*rVA=E2E26XavAVYR>xaz>aO9_2F8f$EsWzB!#$>y zm(rJmzqoheyQ`!=_OXvPAOHBrqdav3_IJGFyP9{t>pj5G%1SLf!XhrKt%_IhOPB|F zgP~r1Sc?@-LoLU#j=vmBt?D(9FEx77J*l|sl%lUr>A`3Aabn`ybR3haSCTfALsUF! z?4W+dF`&v-VgH5)Vg8Rl_&=L3J@-Z2M?6Mw_Hnp)zWMBDKZEb)Pc(lQUBVCl@DDX_ zpx==nJ2n(x+pQE=etGG$D1%DeUh<U`?V4?;QfNN%`?U_sZ~SlSc+GIHQP8~77y)B2 zjJs@K!mSR?{7Oz^d^?NIfs8f&vYwwu+5GFj{_D-BQKTL}exmul@B6;2@ILX-L(Px; zr#}epYjrNc19NzmbOG%``jOwl(!qgr{Pm8tMUl3wFJ%YC>A2$~{`B-hteVwNsE=_k zf=#SM(5;+ptc)$HPc6EHe?a#hq5ZE1fZyoD8KNL(P?w;{F4uB+z<SUbunL@w{Y=t{ zu_4??DpEzK3H@1bH!!MG`7G`}_OXw}#ouPeHKXWW9(@#@)QRKhV0K`b<$f__Ai|-G znv5^p`Nm_F&$hBfp23S(vDv;(*#AHO#KQTPe(~oXz=6aq5vTK@MhEE-i?9&t!VOl@ zTk%4H?O-DWSOjYWNl0!qlyl~G5eq+R9X$oilsZ)5yaNIDJ0CgO^uyp(IN1qhV1&SB z=Oru-Ogn;%k_zflp_~CHP^h?2^mHJuLe}sSiT5sH@w=8bF1zTIQJs)z`gS(vxgLSq zd~E1`H!m5lIEke$@9iiomrBdzBeioF$M7m&9o*V*OxyIjvzTfz2?vVK_W7+-PS|iA zgqXKVb1goj_$1AOMQaHgmkM4PsDd`(`M!}^JP+T`;X}+$LxD65#JWfsYjC+leB?nk zw{Vk)=_s7_x16OW!UP;El$q|QJ!#b3t8C7|gX_wA$`!$)>buL^d_1W=7`UB_9iAP! zN<Ld59VGXbXAC987z)WD6sGU`J3rWb|Bw7w^Tb=<++4nSt9ky#mzontSoVGJP%}9_ z-@JJ0Y-Xucs&0Tb^f#<aig_4_xVN56Q+!%49^P-ma==5yzcXA~`|40Wn=nzAvn-vB z0*AOAeZy7~N79y$^-~_{NLLp6PPSfECcD&IrTq%lDVEt-Q2>BHVK5&DK%*?>+P`OK zyDaJ^7V#=u=mf!%Fv{cIghwklJA+vSzU#WAV9>dB+h}v_*m0DLoA6guu0mA8Y)5J1 zY_pwd{J0_<=z>JLQ3-to>tcngLs&qo;6Hul3|3&QETH@@QFGJ6jckOaLf1(cHyP_$ zPv;BlcGA+ZOXL)Gv?{j^xy$`}>Q3dIopcYU%4U_$wq2KTyVhrN;w~2~da!7`jl$&a zrK`<6il1R%)gm_&6_nlsw1uAQNo9OZj#!@xo962~+mr3WQ@Xd#RnAnM(MdBwU>yj% zf{g>UPT_1E(@@!LoASN!T$-9TNIIQ=EbGHG^hqbK2v~|d+Jk8*B=M@5ed4iZ>d3KX z@4@}GOkcQ&o3>1V{CQQ1$zT{>#w6PugR$$EQOu(>?n7xjNM{^t2g;<|4Je3j&?0Rt z%b!ss$Cbr0*8Oy((<oM49;Hw2t=mTkPgr|d1bADWZA;PKji^+H#K*Hj0K2BEaMo?b z#w~0>L5D1iDx7WUy)6A5X7j%t{dCqS3<j`LTZa-lgJ#ORj<%cK)m1o?pGq?oX0R){ zfj_Csyogw5yXU<}21eCBf;<U6xB*gbNg|!HbR{3Re)SEjqNjKaIH4-kL6l%G-&DXS ztS2%=t|W91+^C34IDlG)-w1{6FiNB31>Dd8M8!A4@GY(sQU?wW#UWqdGu<Q{xdcw4 zb5It60Czx$zvgP+k!Lc=Ez*T)QX>9*Ct|$enS8>tiER9w;sGT1E%6ELRrr0EvrWtT zls>~VP*#f@k0=kJWtFI&S>g@swgFv^5CHOEqK;*x{rF*>Wu&|rg~?tN&YPIL(hsS9 zg{pT!m4*U00CqkYRjgmRdaXH+kNrXV8Wo_s_wFu*JaKyOq0F?0K=EiIrX%g>=hjsd zw{Wwgb-xxSuHw)o2Tq*RhugL*KkJjq6muevQ>CD7_Vg>KqGWd|sgp;xX{t6Efu@Sj zqj)y&oFGz#^SPH!N69SATSqA`gFbQ8Df{g=GH@f!Sdq~V@6jIQdw20=d<nsH3mcFe zJ8>dPKWZfz1ZMN3oYI{0N|pswChaRKoG)ICJm7?<%N#><)@%1i+|Y#2zNg;hYc3DI z#ZtrzxWw3Z@Ic&ZxC{~m6OvxZhC_JEX`d`CwjJIkopDyzjKkL_v96NekFuIVdJu5& zl`FsYWgVS~Pw&&eVMR8LI}-7^5utkvn+7iemy@Z5c+;}|_-uNlWxIi&h>r;@`|je$ zc`K8x8`*SNOVA*OI1V<YG46Qh;FJCp*yJf%j=YZWPi))VY}CI!bX=vXJdzdRx+f`i zY?}UfZlyVU6Ga|;(8FIjqSy8GwSy>0T`e^>J{Nz^$_@72S|O@%UYMJp{~Bii!~PS{ zn+oSeTnnjiSAiPKEbyj+#nl(K&#b@*&zB#Sfkx`jZ=As;c?JmZOrSQMs%ILFNCRJ- zhEEN0ukx68#ut|cN)Yc%FYk@wTMw_EOrjDte7AjNkZ#gXC9sy0Ipjxm7c5x^c@FwY zrX?cZq^+Vat(>)PU&o#ky__3x&lJD27*}M4Nm7!2keLbRCe*Kg_z}+I%^oH^Vmwk6 zL(Y^7-~c1%I`FKrd3yX73L@%(37^&e1KbE)CKZVzoTXUqXqRhvp?RBuWu!d7ZTSr^ zr}Ua<-;sSRnR#ne*i?nH?x-g*9wQcL!}2R%46=7ZALErMoVV``4~lFOUW7~p4J%W4 z*dFDbZs2QKb)BJ~<5*roclV&JD9Mot2H=Cbju~VF;kb$;u7h_c<0JQQEt#Ks;C=Wy z@DZ%?Nj)XoAhS@Mk3y1gmfiO$q}TSyU|6K^Az}P!j~4BTxK`mTuBG!tkftc7<B+U^ z)Xfuoei37Zb!-$qtpE8VN3%ilW|W2lDAhF<(egfZ4^UNG^dW-WWu9vRQ(W#o=pBe& z1NsAT+J`j>t+{<5r0=_LMg8^Ey)&?Rq{(r$B}zwLJv2gevoRGJlVcOjg;!o?vSh3| z{gp2^)A+tOaa~kN5ti2p``)&%$)o~2F|NR9C+l>d0{z5Y6a3MBBK1om!joUys4qFJ zt*S8}Doj4K-@F%Z!e6D}7i8s4i?sBA?bp0Y+U$|U;Lwfd=TXMZEg>VjVLSX<UYoW- z8RU~1mC5&by?Wn`!KyuyxO}EShECdcNsXIdWaAbl+je(^Z?<qL>uh5DG|c$@?ce_9 z=E`+l4K6hUxL4F@%yI8kR#RTTaw&3#o0Bcr&Y;m{I^>OPv^EPrxq0PuGwS3gW1`o+ z?)6zkYJT#)^!=2*6wdDn7%iG}-~Fui_uUJw-MheSn*igHO-R6Z(uVs_xKc_v$nvPL zbv3IBI1P0i!x>h2&Xt)Oir5zjgXudK`tXPUm=&^rnw4R9>D!-t>Z#_tzx$nyd-XWM znTjT?eXH_=`~tQ_T>ICer8Qu;w?!QlxqgL1g|@4?bxY}(NqInpxN?^()7*Gb*z5;A zgwc4`eOA_@WGn@<vRoaGC&i25qUcm6g>SgQwK#EH?bucQ$^fn(sTR^>oW)pIU5`pw z`LtHEANk`CH-E}%;W3P~v_^H3=hUf}gQqvW=_wSh-x~{GWiF{oqdog?>$wjLvbj0n zCIj(fIY2Mpy|?Zd50G*AF7ZsjRSWWU-zoo?P7>}4*IqkpzUp=Gw>G>md6>7j>#pL) z@otSp?b`~!(F?T^4DYJOe&u??J8l=Ik9_ze%_lzoiCEMB;1B+txY<<B{q|>{ZH^o{ zLSF*kB02lbUJT158T&ZlvJH6nE%F8Tsi(jueD&RT-5IzO%lP1fq|^b_WJPTXsElN| zjK8Tv`^s$gEgM*S2n%ToOq<o(udjJ8$fCzGnSB?}caD$ysb{}Qqi)Pu8+9_tM?fbw zbib<Z;ufpipT`i;{k6XIg)cSdG5UMm<F9LehzX0GxU#bj4jn#_=9P&&;z#KWRBKpP zU|$PpFjhrM+_m5SR_}%3|074w`|;uY%m4Hj9ss8-Y89wUsO}GwC;}AuAv7D@tB$n; z7aL3{8B|M0Jt$37INM3t=`J8lqBU&#sIje>JiY^=bO5Fkfh~$1EqK`39){<jU=UOM zETJV;iCd!goA>4`qw9lV37gDI!j|DmP`;C4yW~QDJu-KdRr+yp$&J>GGE)a_4j645 zem9=!dvAW`;i3BsJ9-s$Dv%AQu$AxJC#@DPVKY6Mh)ZJ>T2+Jxx4>y5>tObsiY^sJ zGGvvTDz#OPnP%dEf0?fhJI}<)0gh$XGH~;nK|yO>8Me#I^2s!{I?>G3W#}qd=2$j3 z18h_HGn~eRP>W$px<naBB*`ln%HUKu3me@R0~hk<ySNeOzV8m-;iMH<6t<m#vOdaH zi?Ll=AzbrxOjC3?*BKb!1J-x`zz;R=`{iG5jz01zOQ&9<6Ka|RhmXXi#wnIX-(m0{ z%A)-9QFNkYhN&ex%IhJ%#aEac_q(tXw$nU&_H1+Z+*$HnVaN16YyeeOz6%VFv^o-= zuFkt_T**+@2#es$`j&navT8|L%}%eZs~N<ig<AF^PPEFk<K4EYuQ~b1@#a&X`ZP;9 zUZ8HB(N)P)13P^fxp|!at@ZEhQnvND9&u*!+Kt;00QT(L9$`t#W@%q{6yiMA^uXnE z#SPGp%WZ^1+H&T27<UhniSA;q-<e=3(yh>$ospgS1k1jK(KyUMQ)g9{L6C3ScD`E5 zY4NPpiUYb5(!{$o;6w%OneI#F(EKz@X{=AD9ua(8W_jnr<>vOq%gr({_hXSef*T2i zJLx1V0H9fC(Ia>Oe`tee>r#AMmwva6b#-HyuD(-Vq!Bwa-Pst{@1C}O(^UYq&TIqD zs{79N?L>l;I>NFVmU1cBt8ljb!eP6u`o|huxSxEinK*c)*@@CEv$ljOg|mW!90Jt% zs}h-0ml`fPUVz?jU1O(S{o13v9t00srpBFy42agJ1+n=@d939!^tNsVKitfE&&=xf z1FL<k?zfJ*X`pog?M9eag`+}BQ9}Mg8LcDmJ2%CI0QBS_Vt6Y{oA7Ptp_))W+{;E! z!??-WxdFPNO$<<{y3{Z&2VA<;xUX>Lo%p8=6cz^GS~iCTSbpH=r0Gy!g^8|rj)K-U zOZ*!C5J*-dzk!D3VL(p$Dw|te_y)LTCkj{AYo~1Pt}2>!zY%2}bf@+3GPt{kHLq>K zcv>dLDp8op&-?);JS6nO`yS1fpz-i#`Y{!gfeE+_LxK1wF1IN=X=nqS!dhTox7UP~ zFZ!CZ>cw^=PU>awV7|U-(~k1TAjI&JTdvka6yvM-Bc60ZSxU)_Pz=01&}vz_s)S~O z1b(lD-$vYLs3e*NC!0q1G<yyoYerN!!zWbiSp}A+hsltF$9w9Xcdl}A)4)rYE<vwl zExdc*?zAV%xsDlRe#4W5$plOzuCCxO*YRsPf!m)sg!ldUb5#L)uLorg%r%pkW==k7 zL*j>g#qk1)8m%N=LE-F5nUe^Ex=65mW|K^Wxy#Ud;qenNN8$Y9sVLRA!t+%)>mFlO z&VerMPlH3-urNcrDjFShjj>6QOE<SMDSG1JhoMC41o*@i`3OQ_wV68s6QF#B#jOfw z@Z~^F%ODlbrSugz!q9eCaF-yhg=eJP<WF1`&bq@mbNY01<iv55`}jbnUX`t+5AkZ# zQf3l%G7g=lZ4mz^0<=Dyr<u^*iL!4G!gKN@jx=u(%vYWo#c608IJn9i@7$h5S&c7z z_>2nY5qw|ALWF#!!z2b0f(<IlHo`O*<<R0Ei}vv``j$IvcDOx$>Q$tq?9@r>yQB${ zfxak@a;7P$aDD@dfj2Qht4odho3NQ@<r<zE%tM)!dwhloH3rtNT%(Vm?W(*GGDG|4 zq|wk2F3Na6J-ggoM>(V$u37qnCFBVA%~0X2|4%o#oknS)#q*+moUz)~+E%&BBo}zL zA5>YRQHHp(?p77fxku4p8zsCJtz>JZ%DloirR(qj<Ob6Wi{yJ~fS@b%ky=6KxvLl7 z6IOobjrTR6<3q~I3#bz+fD|}=<h?E=!h?BU$GsCz`9uI)O~sY<a_^%j^;m~-RaVr8 zSjRh2fNZi3#cQ7~di3vVd*WSO8xej5*>8~NA^618_-}sXDD53rHd%Go@<U;=eCxnd zl#lc`)A(VX9J@h3g=;O^Uk7&;7Knu33#asEe`FfoQ$YdwzQUPTmQ`Hw#coub74E%K zXQ?B;^O3HVba+Pq`w8#eqry(d_SKK!%^>bU+~9d++dlR|7%f>7*(AJ{av4rVqDRn4 z8c{fV)xsG*=!BZCwU$vh(}+nQH+W1u=yqWUg|k+Uwr`cM${k4)`gJ^G|7d;qT`VLI zemb7xI}bnemOD>jv7NL}6(sNd@qG|OTt5}v_@!PaxM9GxyhWK$S*lYwXA;AAmJwc} z6}KBkdoDn$8@6t5Mh+Zq_A}|Q9hWLvp1Cn%_%n%n%{_T^3TLycqXYKAH{ILNLif-` z>8|&qv{>jq)YZ@3=^OjF7DGPf=#obC2#TaI@s)hJQe0>n85gC`ZTiMDU-=>vZFibW zudo^so*~|~=+?5?epDH%7n-x3xQSdJ<DlAqg1SWxjl$XSnY@yC{D7OPNv}~hr|yNL z+D~8vD9hqe*Q(2|t&n|t2uE8O-dJaT%9$|L)>S&GaMsnp%mOQfkrEjd5FT=s4no7Y z^rDZlpA=N@?Mt-E4NoMTNL!(ClWUzKZ&m5+XZc@!?G(<IOTJbx*?y2$*&}5Lh5Xyz z_H=XYrmJHY&?gL)!WsGb&h5L+ZIrs@QUkiPeMzH0&9Ewb{nnK;gvX^KO5T%?J&qxd zR=U-8?2p9YFmlkd-~R3nSyc!3pHj~5QNHp`9RwT4m$xgWbZh81%5mW+6YkqN9jn^r z<3f%xlL}{b4j=|HaLi7B%HN-S<WHK9eB>jMCB~T4IDGhU^UO2f*1Y8{Z%w}}`;%8V z&Q?yc-zF)>Jn+|+W>(=XB6-y#x$xe)RN<^Kl}d6AtCSCf)A6KxZz#_=CKE2*x@q<9 z<b&fb^&*ZdYkZ}3Zhy+FC3@n3H~E^U%1Qn2>UvVj)c{I`^KRrM%c7B=^wIG_bvC*d z`R(8Oo#q0oc!ycFBpzHnXMT@7`bhJi{p3$#<$FAMlOBc9x)nB8LU&_G@#<+lwmao0 z6|tV;tLyiyWz+T)Ih|pX)t^%=z6zhd>JGz{Yy=#{&tHpY!|;kj7)?*wZ~Jb;tbVUB z`87cfDOQ=pF;5@*73I|D{^|=@d4I0?j<>%f?p<%(xEb9204_E*vkKSttG+~eEBYH4 zuVs~|+wQ_`Xba)xq%ADTi!j!K@C&13snYRvxKU;-!#`z2({tP|oo`?zwADxv|Hh8L zPEyKE!Y_NZtq8Ae4YG!2msnkXuKDl>KivHB2md(y{C)5HC(UDzKL-5$aowYyAVzlL zj5I(&@R>?lTfEfgtBMN1ul4#>p}r-L!PQ>}VSmHWgqCa5!2j~Al8%rDVR_YTKhF@K z*K~^2N)pdo1<?{lDvk;?l{;naNfTQ}xk)#z!g(W%N*8O(bVPG7vn@US&3m7C5{0vb zDswE~suH+NLgp*+N-Q3w@LLWu^qqOgn6&uQ(pNYnB-4>`nvTqH5Wl|)uqu}n5KY$s zrHxAq!vO?m-7gs5IKm>6S-tY!c;+8Q#&?;p3`C|zz}5V<K(&rL1-fvWpXr*v@jI(p znV#=GJ@nyh#~DAdz`YR*NDn(j8FrWj)Sk|shHcskfAc;na{vH907*naRQm6c`KzE` zK>4DAKm}R(lq@FJ;jq7#0RzIg#vocY&(hJUc%J8+l`#YBJcB6*pIyBsZ}O_aqE>-r z2`W8^CvhRJDh`9O70eMCI7u4{6ABUTgsyUJ4xhyis7F|0H$bN`hDF3#{5CH$NcoX} z@Dt6i{`dbJxK^5TS6)FO!sb$aL(T2G`mnv5S>i>M<8GqY3od(Ik_HT&&~F*-EX21n z-RoftF3EQAZwIPE(vIG1>RNXg&_$L<N(Xd|sSC;?o5&JkXfz!Y_>x}4K{_Dog}j%R zYokhO!1so+<CX5D!L1{`&C_psL-Um{Ki~WnodPMq^i*)_uM0)7j)t(P6YgP_b!@`_ z-8OuiA2@gnd<`;NdAYfI^8)2v*Sz`7Z;pjtXQ{7p*L;SVILWePXv-OBeMR?!-)!On zZK>O4Opfy14V`Xd1$~8?_v<{DrM~sI&J7spT)fw+UkfF#y4J8$*P<g<PT*Lst>Ebp zQ0A=yCo2dhQ8=>{+w$u|rw>|PVv~=t%U7D4lmm@)vkAdMg}3<cl)Q$oj!GZjrGT~` zq`S;ew}X4zf=Aaj#lN%TD&TEPhOe}$gGoIF+)||Y-BbFIUTq_Gj3tmTNZ?Nel$N5l zYul>4Ou7;`5l*=-KJ~`t?*2p6)c_M>wG39;H%$-QMQFy_hS%w%G43d&iAfbBungcG z!DWm~{5LS*Oc;~}5eA?IX*vc{(2C2ET}n7Py~tULpq;z%>q?!0dg_B8&Jx^#fjm{_ zX}#xC*I9NRpP7N@VI{qJ2bM=$uu>z>e)vEiurw%F`WO^%#GS?vaRyMrl!Y@iZE|+l z)OpH4Ib-pMg3Y>Grk$%8(w&0z&?%fH6aED*|DYl`QTix6!MhU3Q1Ve?!_yqlW>Bjj zWL#5#-$-Z1lb6`WL^ZcL6(|&hoJ3UUQSrPyPkQquK&i;mLbJ2d3{P5(OP+1L=|5Ga zh2_%XTH13$%JO<fICbz(#=^2fzFO|kJ6OEHWI0lB%0@L(Xs(viawimbJQn;Cf-wzN z1HMxJh?~4lQYL8oRnRft3>-<zu*LJti#niA*Tcu0Ac;k6?;z<Q^pVBL)*V>}KSzH& zvVB*x`{2=LNQ)BMWBH1czRj~}U8}nS68uokn=Bc=di6SK>&tITvwPp3>H`TT22w=I zP<1AZBn7PcRKLl9Tp#>1@P0RO8O6e<58*z6z@@Mo);5$pQ}<;#rQ3s3FTWf&H;+8_ zdiun&a5h8p6sPwG3Bi7FB0eV&#Lqte@_mK#b`;LY0@f?hl3xZP))6o`xC(6=_bw}N zSQVr4b}JUnM~)t)Z4ybajUP;<kQOxcT=ePE;^p)?moHxeSNJd{zV49hzY{NjbH7T< zltMZP4&XcB%#|uHz4$`&@X3?S{zC_W8M#Itt;Gi4rM<W@0ag)VeE(FMsjR-s0Bx34 zCcD|(aSxLN;v)#70KqrcSge8bDD9GlbPnuTR^MUS;bweZ>ciQM1Cu@=riz4LL~z(v zT#*2aLg^0gMu~gp_Dv@BZ{Q9@mqXMSgX-S!a{5~aAej(Cp`ltp`t6GhsgiH8d6>!b zr}pl<uW%MG9z{^V0j(u(@+a;LR)&af&8f@CFDQd;BNB4j1>uZ7h_xk!hD!UItGE}M zV^A(FF3lrLkmo!y#jHwZ<cg_j{W;UG(pQyx6Z!?{!i46daF#!TXZi;Dj(G9DlMBNW zrC;7VDAYxn^(-T`Z4~d~I|#EZ`Q~@Saa0=+GZw^wuHmE=`BFku9nk9PFkYJ$ys8&| zOynE}Pc4}|_eeVRfxM#oY2O;C_=stOJM#;@$djs$grWLB<WSvfU|kshvnbAVv7r)L zWt#Cfp$OW{`RvnAHV1aI;UzMTeZBc8Z&ApU+sz^!JTK0$Vr=|2ZSE#GD}_-Y7AL~O z#c*OU<p8f)Rls*@JoRD0l%bYwV+4{f7tK~2&>uWn4rS&jwhRX-*(-qi^b_<m){zqt zsDj`v%B>qwIK#8Jj%?lA4AY+NpPl5E*UEp^r_U#EGw0tjX2phSp<rH8Zl!JMpIQZU zHj_i{8=+0Ba8{1Ugc3=lP0-H6)5%9!sBquXbsNTT-Qlg}_3(c68xQ^olNj^}cwEJ) zPaR&<#C%i1k`9l-Rr<u>rIZTBOPl9ia7mq%l`~~UMwwxC#R>|r9*ih<Km2I3_r&pL zEB<)5Y%F|PO>RL^6qhEOd-L;~M|-J<HNP!*X*%6&Y5mo3`>jjAL)B^+zOAO;-gN02 z#(UGW@AN*;gp<E`KL@WHyEVZ?3D(Uozt~(jg<nu6t7fpmG|z4$=-%)~=$yLm#ah_S zja4?gr;7bhTzgT!;mOd!3T-I&0BkySRK4>dK&MFrNa~;~5CMhDat2m^+WPgb-cr-; zd;5>j3ojfCTKAz8?iVSW=iND0F|t>Od+69EIyp>hUFCi0*&|9`c%(c~I`K3=|Gcve zr!=|pNLunfK`}(t4H*+kS)=l*6jW9YBICdDsVADN^lQ52Qir91&JePIt5qgh$&^h4 zndq2D;hg*-&Y^zv4Dgn_*Un>AyfubdC+SZ&(Vq#C7U(h7;JOih^&QW?mcp4Zg0|-9 z+S!^{U-Q<!L1n3%r#VI!Cn{}svUkzmeLG?ZVx8FbU7cy#=BKRS7(yBEFF*Oo=A$3| zXcWO3>1ZMS#2enwyzAZXj;tX&b*!y^!TplFhorbK8G)icc$oeJZva3ZM)x3nJ08-o zN%=>Gx#K0rR~okI9zlJB23cAh>#tX%09UZcb2R924BG9PBwckYKa|Zq`ca5mW>?>8 z0j^P)d3Zkd*kdWTY3*QT?;NX_gy*^Eo@;*Vw|=Yn_+NaSO;rb*-8(V%X_en^dCOZ+ zz(3Qt8hCVcGxX>xWDK*AMa)OVxnth5C>BRYM~UbD1LAwBIf`7T<$FKM(LT;$45B=0 zLirwafkGGkgRpHyA0gr-Z%>kbH6nepdiXuGBEC6GUJt5Q!#HkP9nX@u^pXBiz&VU3 zF8uR>-{9L-hg+GPpJNi;w`WeDYd-atp91&Fo1<);cpe4)=bNAUsh?_&9Y01}VKM{s zkHfEAiRfNR>K>d}RpxV2b08~tk;9Oqx=Eyrv6(#Xr=JoIWgf+Kt%h|gsxBfj8ThoH z@+@Vp{TciWJpD}`g_TONyB8-x%xh&N+Ia7<&5h6%<)$&p^yMJs@85v@!Nkm&moGGb z`p19L{Hy=@H<};)(I0Jo5Jml?@QT~)XJUKXK>sZJMJ*CMMr2FIEggI<7yz;j_FB+= zOWy@Q9g@DKIeq=aEq_m^aF(D&iNs{1T6<(rSj{T0tE0GIf?7i9Y!Sj23`r*Bz+6R^ zVO{bvhe9zM$e|3~0)yCqZ@w{>EKb}SXVbvZ=ABQxp&6p~CYk9{@wY$+y@5fnjcWnH zMWHB)3E+_7DdgEe1>24#j3EuiSy+82mp@k(M=}&Sj=q1j3NoGw9+he;raI-Yvzs+L zvl8oK6IW^B0LTUx1qN}WfS}bHUqzQoLJaFnp5cT?=IA@|;X4oW)s2Ea@XS-+vEo{V zmz{%(J<Gd7e%TC)tKnsY!ezQDyY1ko=|ELVYxylMY}6|7WDstUIBi_uu>-RXoRw1` zwi?ZIkPXZ1WF44lF=yR$%h`4KK0)2hPzPF@nJ+N|qd4>s$BU#bgHp)mMU;~Su0a6L zOGuJVD%3%_Y@HmPBHbP0H{ilS_al~1R|A)?++gY5vF6wQ$A8(p<NMyzeD+IUVfXn7 zd{+*zycUaCH7+nhm&UJ{KY90Q76F8oOChM6UA@Cni5c=(Typ6m!%POdg9vyE72;aO zvev)~ehSMT;<20DNGG5$#VL~tU4swlLFVpY!<@yB)-eh$T69Or4X*DYjJecDg}~s@ zy5`}BPBdTm{BzBhzw`o|z2W;5tHVhKyt9;j#Lf>zpNg3&mNDz+R{`yjM^83~4<3nM zp=-0Z0-K5&J7*95klDFNZ`V<5Xz?Q*N1+bRgiT>5ibed238w<Z)Z}dQ!V51pXU?2X zM=bsnZU%-&S!#w~MyizJfFIn5&{n6}%tv~2hhG)g_8^ws*?Q~0YgfLXXON-5=PHIt z1QrKX_Ykrcv68-l(tqmmMZ(<0XK>RDL6=&7%n^2$lgdonUC*uU%-yEtE4Gg)d&$c| zm+jiNTWtzU5$aPv%(k`gFzU!dKk9abS|EEEPn;Njt`&~D6$A=Q;!$OEEoH5a(>&y5 z(x_>BnC87VKh;bfIMQrIAac_{XL6wizXlF_CIuR!WCOM+4X~C2k5hNGR;GQd^b;T9 z2jPt|D`ivAjJT1GEt5;KFOoH9Cu*j_<J~b<KENAxp_H++)J;iQu8<%8E2;IsVbka= z^yco)FljK?j8C!a_a3a}@r$RD7!K8}M}X*^V{;p<{06Zu+d!SIM=R8e@*;x*+Pi+F zRl1a~Oa~OeDJk$xC7c~`Sd7314>gFe{1KrD=V3YOj$a@A@yhA@C;~{sHXF-;HlBkL zFqVAfKM6~Cn{Eat+{mwD<qWK$eT0Z5@SJ<zsa&hRg7|>RD^60iotP$R(S%7uyqTYH zIl0Dn!-)g%6~!IxGi3*NtzBW_n}#r@;w_X&Y0G8_>yPi<`?f4*R=6^JwZ~O@6Ar$^ z`jU3|k6}24LHwGB{L4vKd6UX!t*Gd5;O(qbK<PZP4TUrAe3-MKe`RUp_Pr>Z@u`N; zW&PO}oWwKDC{X0F=0oxh0>>E~++hH+9#>fUB;E!u>O(-apXr6yr%1NZmN$nUz@rml zTH8)AX*Hz+bnkuyxKa3U(Y)YW=HNyIhK9T{kY#YCmG0RyXW+f~_dWSIf-{OPc>)9; z98q@5@5LWl0kG6LetQhdvzIe*yN!uPt(-fBb7+k^wT*Z6A}BdXNB{K>6z?!WCto~t z_=t=iTmh?iF%JS4<bca_(xJ@y^u2QBa(2jeX{Q#_^6ml>7^x$9yiFzf2j`@g;=>c+ ztty;Pzw$~coN=oWD`DEKg9T~bxb}ghlEZe8gR47p>pM}!w7#}?F*)EN%<?6EDkvFB z>$d0Ml0==@IseKjtoE+4F(exnGB_V`8EyD$TVmnNX^Cws5-0!gN&AJHH?HN}e`tT= zI|-6LlQfng<n+1Z=|qi(yh=)TuzV2M+(>#D-+OVXVX-8_9OOsFlp;?S!!F5HK`&jN zZzdRgIpJ>kx<83qg9H`!TBzO}bMs1!7T6>v)~4Xn$<bN(pM$TNDcoyJvtc3|2S(wH zyygai=DSEg6(7#PE<cgqhzI-GEQN-4mC=fyh}+^XMQfHfOcO-Gizu;?S9xq(#K=nU zVBe=LM5|Y~Vkx|r(ygc^YH=d+lTNTGpW-CGNzyX&>s=Jr;?57GYe;U2Cb;u4t7g1m zGLo9%8==G}GGqEQ+8)Sc;)6PM!e49Wjhj$DZ_IOl-^OMa?Ry7SgwH&6k`-ROC%IC{ zTc(0a7_4`B%=FzG%@i&*CONx4CgBX)9@c021S5)jc#?He<>Kl;^i@{eB+PT@%n;HV z`9#^w`(<dPzRA~>>#80cct=hM?y>Czb?cDT`Uf`QQiBy8S~zdr&1#Wt;d}B}WpH_s zvJhDmOvble*_i<2G79DeCNQ)JUD9$MrL!)yP!BbmFbwEN&WSq>c&BNIZ&ze0(?lN0 zd%wxo04iZB+$w&$ynVqvq4Q^gJmx5TwGUjX&5J6K5(L(_pp|D~F){l-<9b?#Oo|u_ zymqIPE4Be;9NmY^&|k<0b*nTuy1UtN>;#*GA7~C7KSX&|ZgG;nl9SnZrVsJD=3T+S zi&q_i*q=4Ws~%UsnC|M)23q^d%#$90yi%<8O5FiK_l+V#E0mKL6DXn1zw#0a=kX|< z$8KIrU*{Mu{SUF?x0!LI)36SQVjv^UAWOT#ttJ%6oH`AEg-3M?XUqK{jKE>tdkC*U zc*{iy<%+(^eH+o|2kX4zSih;a3ed(gZqbVJj{V65?gyrj$LDAtmfgO=cC33$SHpI$ zGwi4RmQ`uefwZ5z{o(YmzvJ+?qa~jM0)_Q`#evqik-zy(g|lPrM@}4XuG1&#V$0RI z!?Zy+S083?3RezlY~VgJy7)7H<>~%jCLvk5a{KDpX5U`+LSVe~C^Ceb2b!OTStX~t z$I?ji9p7=^hjT$oAaSz#z>W8|1wVa*!@5yEnqXX{-`H_hl!`wskX`k3?AQ_dncDlo z_O6QrWv?zjugY~VG2#A~pZG+Su8vV0%c?~D`+x86r)>&`6Jw6`<69YA8&@8e4Sin? zXIqT>udQ!oWMN}mMr6m-Q^;P*KpJhSUyvU;Mpm(H2DWeGsq65)I*F_VrM}d|n3lM5 z94yUgWaXisYvFS<H{~4hqT<qed-BOAW9_W0F0O`$HxO>V`QQgX*!;pT{$f@r52FuI zUbXI=$ltqnZzlCM9{SGj`p)21zV5hAyz5W+^y$;h=Rf~>(zZXMe5CF1u6Mo*zrBxS z)t$zN3yj^}>&TV3*0H?Lu@cEKNj($Tqya#^PXj!^))5*3KatJ2iUZ4?34zqJc#(%z zoAG;;wJ=6;W**8!={u=Q>qUA{{*x8-A>TVrwmy{6-9Ynq|M%Z(_b6LIr*au9__xGr zTm`drm6h}KIm(gNw=0xYz&k;(2^XZ&mqZ>phJ1w8@vZz?cyvc0?@$*ay$V~5Hqqrs z1CR)~f?rU7mOEDAuZ5hy=DXnZYvB8<lT7HqXuB$7RQGPGRnY1JbY*3^?lE3GfBJIs z+yC2dXXW)<Sv~NM?|Mh*ek(5J1{fz<@3yaX;6nVjEbZ&lfpz}Xfc>q!N$Cp(e=GTY ztxPO`6wbf!bMFhm8_<_oy5&QAAXamCA7Y8U6H*c+W)dni8ECer3NahI4coAjw^&}u z%&)VQdtnau=y|VU{jy9$IkaW8`5qX|CgM)ux7NJ0xLpTB3Pf0<DE3a<p&<-9yQXqg zMkDb^&?*{TE}<e(7<Ad7qDsp|m-!0|v;mVT5zJ>Blf-6uwQ8|Z)jJi(HfqHn8jj&? z%rsO7&JLPvY&Nh`te4vk-46(pX$gzWR!i?1%+;XQrO593o7rKNVxUz<Z5hN<Z5{@L z0d5(AO5-SG$=7FLQrMfFor36fjIL#x7Se8N=Vp&8`cW*goJ%}JIHar*h}&n&zF{3q z!NCN1s%W+xrmug(_~1bhUSN<R!?!#RtUMg#dx(=c(u;zEG$;VdW0i+|<Q@cN38Tvx z*B+)L4u#nn&K@>dl7TyD9vNV1)J<kfvA}%ikNjBk-{1uQ?3HWH>5CVzUc#3+gPH-X z12zqfAY^Q8X2dfa)ajPP&dLtmnO~KLc3dL}4+j|RuAseigGv1zt8A{$T-a4uK(mVc zq#wZ;JXl{5#Hbwc$M6MQmEzrJahArzRa{yoEwEMitziA6g~z&>aN)iHg|`FdjdYkh zP&j<@6QAPzH1&p}c<T;?PF!oSiPsJ`kr+_pNb)LW##xT6kad;LLLtiK%qL#|cyr>R z6Zq`f7mH^*QDL<$96ydPR+gPDAh_r&%Q8A~U|Y4#5iGdTlEOGD{q2aIS$0z@+lVv3 z?DdQCb902DMQF$h)g?z+s)IAq9%D9J<!-P*TH-A}bHRhxK4@kEt)13eGfu29v2+h1 zV<YWhntB?$c&@o|{#-MOwd5e}Wsr8XNcdSydDqb)4l#4xhvls05=Pr(+9v5sr*_O* z$(KS>f)nouG{9#4ST}ZrC1|m13wqGPP`pG*O?=(xxXjv)(!;hQ-6&9H=}g<kZS!`T zwl(Wr`mgqe<@g&PY3?#{uw(z;W;4p$A?lc}$Y4?S*%LXqRXLTV!7iOgSs|{+Z($KI zCEw~tX}p(>+eV0k08zyu9pf;_$0{0dIa|R4dY_#fXEUw|;Kyoc|1l;^7=ZQ~7yS8$ zVlgf`fL*0NGa2BGHgShGGB(3XfyHJNYsbyF7Kl|VVb(E#+Aw{s8JNA(49!o5=EY;I z&qxQrl_02JuH1`n0W<mfp{)Md1`N-Atm0t0;v?lxz&1=m*EcK7FsVlnkTym-@<j8o z4$Q8?@l3wv+`S`I!sb2nSFo8JJy-Y_ZI}1*Ecv5!;c4B}W>L^E&!u?g>O?@4)NQ(f z!{RDH36p7Cw@MqLgZJFXA%#74#rsn75RSqLzHoL5A%em9i#E8+cYpF;To5OH6||G@ z!oW#Ze&n+X-kQveAPP{BFnpeO(6zYIjggZQ+(3}{CW2l@u<Y1C|2a9w2(nkdx~%k| zuT(j$Redjg(|S%zW6ttr`J{s~5pH|b>ZK3CQs3jl@KhCf_Ae@C?8Ai3iBkJ!qDBFs zpF&qiXmK*hgvstb`!gxl&r)*OqYY4$a!^hif#syU4$|HHPCxROFI-IfKgz(sUB~5Z z4&>x@;w$(iuF2TTyV<RSig9F*SDvpOytkw9)pxY*-@$$O)+${<BjS<1)Z(fPy3M4e z6PNl-+>GlH_Y=qxXyXE7<Q)PFGUy2n2#)ovwUtWWt4su{Y*yLrnW7QKrLW@4u$k!Q zi*knWtGt}T8vHs6-;3ujG!LD8q}j87KN*VO7SDt<zHL5-^g;VHzVG$@d>4hY_d8KI zk8-AM8HY3Y;y3riwf*FttBQlOFTVtzxz_AId>H<=l|EOuW;MBOnie>14)`roHjA{4 zFgVhx=-Ra_xKX)^-|J&oIq!(PB=F+RKFxdU5KIJo`4mLTx0Plm6Y8%AXHhsqSjH)$ zsGyc3<@6Ec>qcXliMCT$=9=5M4w|Q(^5Om;vQ97ZhHXP%&bRU7Jde_Q3_sPe(gSZQ zOlId;#e-ZigMwmq>Nfp%DV&$+$CQIquIO7>|Ng?@Ce!j15n!2|aJD|}vp{3uw$BQl z#ErP(TbKy%8MY;z@CDM7ZaoZ7!ue)cN|!v$(=)u0a1Sb+0mAh8ZeZikYnWWMW?tK; z<g+ggX8y_YemzJRz1D?w9EG!TTHCJj43sty+JKw?YU!*yjrF)JSwBcW#$?pc;O6GQ zp1oM0?P%Wo1~x@@zW~Y<x!XPjAWU8uvWXmYJ#qUo{9!ETD)Lr=6;=;QWEt%N;O*kc zAXOC7<R<%%&<A?R<3(i-={59634>ngx9};wcasR6(#$$Rl7Ro&zp8L%CDJe(1+tW1 zh4U~gJRA#T!Y#b6c%{&!K2wL(J!uQ13g>w?{`Glj0b?9pE~s!u2HpZ~x@q8sj7O?n z+s3jgfcLI!%VbR$6Yp*F7S<{vTyWVI(~EWJk#JnoUh_s!>RbD`=3Bk*zE`leo}?x^ zpN>wY?;w#tsRQvSe(hi3UCSsil=J6Qu3;FUKWEItn{9`1t8wUXbK<GjGuCnN&ysuU z-bn|!m_?F*N*Yq6*PQ-*lgERldoa>BO2)XJ*1Uafo~=88s(aq^aUR1LY3I((JI$%* zKFfrt{+nMyHk(ZS(lo+L9TO-+tp_L7!YHeXX6xCjV@A^Uw9~O&Wn)$3%-Rb<9@YXP zY|^hZ&>g^#gNtRWR_dGf1qd}nSEqjQ8z9vkH{R!a7bPjxJHJh$T$(}=GXt-q$wg+i zf6}7aag*)QyrXbtY?}51lEU|rHf128z^B|)S(`!S%d=m@hbW(|J8e&8Gq@HfDlnD# zkFm<<#?{Nn&Ww>zI&V-p1|D}JPb{M+(C|g$5Mj%>fwcO1oj|<X+_-!O<DGp`s?|Oa z=qAWJ6YAjGzI=qS*jj~i2P!}$tXS^a+JiV<4f)kK6j&KWW1_pX2W5iv)4Ur(4$;k) zdJ>g<rd|8ba1;F0M4w|0$7-Mb>}Q)l{KG$t|7m5P{rmSdKl6`%2GW5h$fpOsXIPtO z@wUplgZTmA$inj9KWM)o+<lzlZ<(>8hvPfPlIj&4SF40xTXyBtD8SKmsE=6d{<Px_ zmc_na9IqX7`Q34+mfy;jrY*110^PLC$7k{9YTQ5iqd#hX?brTWEW`EP%?cXoe-{(e zk38~7l+MO6AJa6h<2~`_v$`JP6b22otON73Z2OU|Omi2L>$~^pCJuf~_+gA2ofHtR z=vv@cbF>F#+gBkkxT?N1w`+c^7$3RHCsR+>l{D4SQ`NV!gzZPYkG#=x%U2f}k3_Mb z_6`rB?wzo(Usf5drL&@x^{y+lKmYSTht94>ZgmXwrl+5d{zJp2O}MsloZx1+PM&MM zK8-$U2m?=bR*rGC8ZVkG<#C_~Zt<XU+cs9?Wyjey*$~Tjj8Haitj!<oFJKRpN4ath z&su|-zwYgQJOk7NhsgEC{rBS7{&S8ok9<YFpmbpUcXVuB*gnAu3w@WG&wuvw&0qY* zUxa@4Ko9%&?`xiU+uLHbultyd!@4L;6K&<EH90=ms0z9ctOsEI+j$5k?xW*xC(~Eu z(xGJ4!db*ekb|Hl=Cwy=$CL!xLnWh%y43?ge+3^IG^JInI~!)hcg92_ox%66R<v8$ zseBVmVG07jio#h%$3ff&yzSwKnq4s6xd}G(f*=+MJFD;xJcH!7o<=Z12jh|rEvD^! zBp3<DLq(A-S;CQ_nYZ_b@$_)uY=e@S$Y^AqHmc4t*oGrh@+jZWDzwXYa^>TI8wDcp zIg4XDDrZec#-KH&X-osBvp%M6BeeXUb|m`kMLii|%zRY*nTNQO;Du#?GHC&=A~ROg z;96#58LN>nI8s=peCA<UZTvDpnVDf0sUEN5qGJeM<roh;AD93*g86#d$=i_T!LNtQ zvhPtQ<LY7~ZaNg4#VK_oY{(!qWEh>ygnEi~2aS8xs5vRE`Dv-HgGte&PYY+1jKXve zWvQDT>R)sxyIcPc|N39E;mDrm)P?gbfxQ`8*nq;h7fYsD!ro?My4l(3vbv<;;?Yx! zUzb04uOK(D8Ea+*7Vzq`9iq6@)rELo#?omXW+V=UElLChzQ7BvV!3A>QhpBc-5rLv zZhOFk11c?wKt{PoK#F$Ly*`-T$jBfwjx2FGeZG0_b8IL=IcMe;o9k?PFpbsf2+K3K zxWpad<LJ@DbfP=x2<}Aqwu~1q;=dY&q4oU`O6L<N9tsVbzs~MejO-ZQ)*QqN&W=&g z^$VsCwmHgadvPO%Y3R~UIJ3~sb^@-J%hIwP`d3~&-;ARaa%08;zJmtvR^^q(r4?tq z$C&XJAGRsW809Y=o7eT^=_ZOU`_@n9jLVa;Y8;|I7Rh^#9q4aRp6hHrwvO+cs1I@G zMxwpUAe!b1K9#J;DcWi31sq!;(us$4E6hHH7OA_9lv{e0m#H-NYI{&w6`!rdwa%*@ zVljb$<Y9ekL1ejXGp6m~y{Ce!>4XQ6q5LnM^&1~;ZsYc3bpJjSGHh@)j8ad<0A-Pe zB19uJ7vAJeD$MbB#uD!F+vE5+)e^85w*<uB>Oj3ZX06DoBUIQVe|lH*x3ZR0IAeWx z?aCb*DND-sAICyfKU4(J_Xh27h4x_^<tFswWPv_4mnh%eJJZee8`I4;Ej>^;Z@`bf z`&RXU-wiX@o59(!W)S#j{lTr`zdrXvDB=NpDAklwm-igOb8h4?;@tO^mvmtbxu)8x zZVco1d@!Ej^6W!WXw&4L@|1F=-kVGYB!u(5aTPwi&tMnfCd;geXOf+gxl{U>p3%Bf zp+QA+r*O`9!|*|YJ$aip_Yt79%*;2^pqQTKtA5L6^Bt;ca1LKh-KBH|BLTYdq;hCe ztA}s}87<9#yeM`IK-&IA$RUgZoRcu}a3>0_1BK5hob8+Wu5xfa{R<kArf-l*TKtcW z;s<z$KKLeXc$m?}%>Wj^TQ_Gz-E~;Wt3+R+Ki3tDqkp^oKuG!uu39*2HR}dp1GJwJ z(lQ_OtFnu;Dp6=y2^b`4vFNIeX)H=7pu-)z_RwbZ;jG|ZeULImH~6-liyDPr2e<Pm zEUvR*q5S30u_N%fnozdw+SY2oPQJuZX&Oa2aqW}t-nrep^1_#!jR@N+oZUDu6Hc~K z@oIeoV@)_f@1{vo(!EyMcZffZ{IUsIW*^ph>)@;6-obzBK?0Xnh(p&^=}~SKFPAS} z%;}(LI~yG7H`0QMBEuJ~C9?>N<q;nH`zaLkx0qDaLgo0w591PJZ{o;<&EH98h3W7- zk>BFo8{5FSb7z@^y_>#o2Lq|?xVA{0kgsh|d5;&QC4UhQwt4Qk+CQE@^9tp^)f_yc z!kNt`kxi_ZoQ6w&;*J~f4qOf{l!>&U(Zcx_{r1u0M>Dxlt44}8Z8JtQi9Tsnknm?L z{msuWH=`IQya8q9h=UjCBJf!*{>Um3bM>C1Q^Z`o4bE@l5`#3fcuu+rhz!M5{Hkz9 z(j!i9bDhDNE28A_b67Pwd2RpTMuKyb?68hojVPG0rdz;jE{aJe@9cMl-}1^2JY4x> zTxm%@>3hG(dvwzvUOnYW9w`$*RjK#}RK+`u#9RB(q`)unl40ny-8UlNq}2OIg|{9# z3#_zDVGX||XgB$%vNMxAzJubSKE4^3RHzd=@w`u;+c5(8nKVmfn@|*mx*Us}EeryB z;WPSl-m~{a^ZLggZjQ0p&YoRc$$`F4oPih1BAum;OUIOH9k5)#d>YwA*?Aghq(k|S z<q$8xWEuQxpNsCR>>5p2iaL?Sgr9>Xl1}b<ur5r?_iiAm?BKKYn!e3UQim#ug%cT^ z3Hx;@)%yprrW`4S^U#)^%|;c@;6cNa;zQs@9tN&L1J+sSLmo(8ST!%8XpTY-OJ_E; zpq$8x$V!{E9y2X?3nbd&2Kq$~%Op21!y9a?qCaJ|v~7E|=p0tf+N0|~f@?k$9w{S7 z;__>H!e_mEAhP(FAH#bXzv34Dl#4pTvL2$`@@jeMCsIc0dx`p7R_0P!rP7&|mAx2? z9C_=r&35*_*s^0ge3{L%k&(6LbDBVKa`Ll!&pVaU9_{6;?(^dR!B3U!egvQG$GzrU zbFbk{`hRF<ZXSzY_^Jx^m!JDwbLxv<X!|I}B5iWnmw+dqrNm6!%jc-ae)n$Snu%eq z)>-O}@~57B$7FI`)9|5E=@RBj_=1re;HhzY@qgo+Sl1usN|fR&)rL~1Bw)H#y}qyh ztD3oAY~Piq6EXAD>m2-Ofx6YY+sQR8is$L4x{c=Lqsk(-smM#@VLOvPI$k8L3A=}R zcV#Qus&AQ;qwUFmLYzbzV*Ij!cD7}>pXKeii9+7TyBzHUr9Bht2M-<zuh;4`s}XU@ zBVKwLgRHy9ro*`SyL$dqbNnbP5}7!D91CZSkHn8w#p*o7ohu=~<JmP9&f;^;5&X8# zDM#Br)&zO&Tf$jZ$1<0gfOeC2ab@z3P4_VdaBP>{!at}F`wYq;k8!M{JIF6Q_gwQk zzw<lIE{yg>>Tde=pZ%GirB7qb2Okz+kxjUEa;iopUv;#v9{d6w@F)Jm3#6mA{MJvm z+FLz^{a@q<5|%$XW^zmvi)P&bkuW4fIQhP=8j!`Ld8$;lnDnSCbtk%n)L=}R!~E2( z9653%crhI}e{(gc`-gn!Lmxun{A-cBG$<QIhSWXV+n<G>uu@)Jst5U_4}74xhSjus zo^cG(#Gxzd4j(?k*!e`p$c}sUsjV@=ZR9+Sl(uZyit*NoT%BOHPE=;^L-tY$s|;hk zEAm?Pp@B8X&GRZ!yRUV%-?V)B%uh(1MC|8Q6Uwbd0EMfB<y~+_xUQYpy=`DKOpiJA z2)be-X>iRmE;Dc9yZH}({|}lke({UZLB02Tzc)0ZmF__%ZH6!+gT+KYFv)n*6$2V6 zxmw@Tv9}vdYw;hqoV0x>9HuZ9>GWGMM2sAy@nt_s{LRt#smym=DLmpx*gaRv7^weW z{+Kp>=T{}#A#6?Z;@mO2^ktip7Nu8dT>uM44Gvgku!3HU&Ce&%L;n8zf4}+kXFknj z#Y9#T{KJ3r58*Qh(P=E8ymucp%4HJCa}6Zz^BNHH@wHw*5awI-0ElaV`xa&L4U&}> zEPv1Y-~axVU-_?pnTkLV27_L0oNEsqWv@LVaGFAUXl0>QN)7H6wCRv!ru;?mL#?<e zl?ooM1<+Jst<1pF<z*=P4s6=my!FKK<^YX-i9xA@W;^(CgnpUY7G|=vo}ITdBd+ju ziatSb0G4H?Ele`849a+pFa$-Vu>+4Ci^QkkDW%EWBuKHL6|780U$E({GN@y~3uBbw zdsUHce0P`ior5ba7Ja8uOJQ198Ft8~t?LdIlBQ|eT4pU!IOCY9%Y@9|2CE`a3n%^N z$_!=JzPD_`XSobh1BUwM44mI%ol4%8H#lMT%X}jklD>`1ZzL1A*Q2<#L$}e{;A}LA zl9ZbVI$@Q_4q6qUXJNc<DyTBr0kr~%Wzm0`ILPc3@vLw0Tqhm9Nrl=2QpzA4o@whe zeq;!&g%I}XJU2LSftK!0pp-<2__<&C)#j<Ue<!XzR+^X2o#y>SGmI6q3g;zYo27gX zthA6-p(?KI)Q0FJ+}I$UAov~F;()=WN@Xdhg`V^y0}@B;s1L2O#FeCwA8`Whr9ChR zLnaBXe3t2_tl&v}Igo<lE57&zXAVO8!Hok@lhm^H(1HEU^-I^9zx?x0F!)$*9y;+T z%8%_>Sxq!|XAnf#&~FxtXe0Dv-S5nriu0W)pEo-zi4dq#RQi%;?D(C1bthHJF-V8M z8Kp``tA??h#atDb9fZ?9?ddE5-v^`Yx2#S4I=^u0d~@N#r6{0AN4JNzI-hOEmmXXm zBM!CvE2}OzFZJPfX{HCbtoSILflEc`0t#pS`7JZ3-;82*f%unBz0zDceU=S#@Fz># zaUw@wxwi3TW|8gm?Bpzihwyg1$2zdCZRY}CLT=HwVV$_~o8c5Fw7_)6+WK>1B?Cj^ zi)-7iG-+Oj7hkD&>Q~{-LwYwq<3@l2*1oqt-AwL1*lgLg8}}4j=-71uBn<(F5<zIl zG{iLzyuXLCLWT1bio5Z#1%${IEElo5Kw;g-W__6iqMqd=86-qm+zt$^J0_YIaBp(? z;w_Tj(CplI6ss$JQd1CUEXp(5kP4WzXf5qq-_iHr9d}W%T)r}nAH|(fIB&%Atd}~2 zA(g^;?rt-Pb%>lnp)&)1`35IMoYOicqvR!S#91jbC}W;2KR29Sb1yR5)A04pKpf&` z^%{;uNZt`Hf85HOy7=aG|Bu%s<2(DEQUJBE5yd`9diN@B3QqHlNNpC9F2WYyEEdmN zAd3GCqRq*7oC@&r9j{R+8{T`;&6zNyWjMYCUDk!dKi>>fFbEI%r4%W+KRLo#K$x^H z4SAY3IdL^kY9(|cZTdZB<C`ScS;G0C1+5zfx}v6k2>RT{gw~-0%|>YTDvCg+R+uE& zie<<S1St3hlNO!-YST)+nJ(xOAJV-`D{o+p0#QYP-8MR!$w~291DwKz?I!~!kPufd zT%D{{kkgOz&fR;V`B7l7eUX8g&`!Ksc5B>U`<7T!Aq49K+WOsd;9&aN^d+?MZg5R- z;tQ{ngzzaOYOR+hQ4X9vb2@Ho+`w)GzG8ooc)>04xOyvn=$l!nYy;!0<``!{q;<CO zRQkdc2_x={Kcs)Qf~8|3I_Ql;mFpD-msc)b!fFN!V{oP4YvWqDL?I8C{faLS>(uxv zGgLUcp^g)ZM^Bu<EynH=Zo!E%P_4ic?;YV*0DwS$zuDy*_B-d!o+XV5_!5eC6y94H zkX0$gGx?LJG^IfS7d{c6Kb1xHl^4#QiL(Ci(WAu05?=WxDewzTTR$Gvo_Pm8l&f?H zHpwasVV_`9_%MTfH|Q1L!W~75ZGy0#TB0jrI=R*<oVPOwdV+p!1b0sM3(2E$%dfBs zi+Of%SRZ&AYA)TvnjW_rQ)(nqA}-`hQw%+Azyfz*<K`%QZjU>0%|0H`r~T;y<+l8; zOq!aw#o$dB8&1+rmOp2{E#Qk+Hycr^z+O8(;p#BmmjpJ;M!zN8w$Iwg(0Ueb@t$B& za>}35Cvy!^0B)X1!_d~Je8vLT;Iz`MO<Aooj-)4_A$7v5C`~5$#z%vgsn?Ji=_aBN z#Z{oh&~%4U`Ih*tKG(QKAIVW!jc+kFNdHDG=z4uWR?fK9c+0naXY;y~Cz`{D_5uqq zft%{n%&tufcx*c>^jpig6T5ct4EPiOY<Nwu)t{8TXdDV@aY$Lozbli$R}WoERTfDi zePZy^@_D`)&wfmvR&}Iti<QYo@y-M-Ka>&r9B_kDdFb|LaMP|>I1g<ZWdcuyb1l*B z6jmx4#Y^C_-mGtEMWk!hynr%YEBJdTpP5>LU9j4U{&^UAF=;{TDu}{cXqU=b@&wy} z{LVI%^b0w;_t~Sp2=?lc`pGw7GMFFpz2ewD>IHC0m+g~pyKb4=9QKig8)#Zt4?LM( z@%bui_#QZQ{1;1Z<h^Bh*)m2I3n(iVUB;|Tx|Kd>4?fy=?rQcPKi+KH1wQes?~3L1 z@(BQ-3(6Tt$+|0_?>z!z-R4`uwa?w9dzW(Y<JBY2bz61CeOdt#Y!Turs3M?!^}KyL zV}x1!eoo%K-CV~AW)3CI>F2+Ue0eJ=nODh81zSfG)`4^`?{gfYk&(b>jM~;`>M)b9 zwxeoG_U#tTKVi9_iEsEMY}A8&qHZi~*QR5<9u)ZYovZYc`24gDqiZ+Tc&e3aSs{b_ z<VfCao*hpyY);Z}Z0hRaY2^AzjfA+LLaw#17N!ad+@w{!txYT#s-k3bPf3VJ;VIcn z{9B&-5E`U1HlP#G<;=*&KKA>WVJr%bp&W9xfs;Xd_Us}RVv_e920Hei=BqN9!AGlb zez|$*;S=eL+zf0at6d$>lmVUiQo;82XWvr*KJY7E+ZU;mg86|UU+Y1%(+8-SwUwz{ zy@P^NC7&z5>;n%UJ{(1O#{0B?@w*g*JCx?ojD}q*tH1K)FE_vO8@~}*LVlrP(m(i# zpTIg7z67sO_Jj(;GrYII(csDB0UF91L#{oDOHk8wJmt7c*rYabR1?M(BmI!E`A^*u zF1*ef7eB#~^)G$lq7;_}ydu4V!>jb8GEWz6Du(&OIA%i>q$<+I1x<$b!dMsml0Jq1 z?9cwJ`T3v!dE!km-qp?K#^_Mq`=0k=^}U5LUOzJJ#^wWm^Z|S|pA8?{hHDHJ$9~_- zs++@y57DP1;~-O(5_Ph9{)HD<jdh*;`cN((VB%pUE3b9G^32<wX@2-W`QgaO;?uGX z4MW#-u~btXg_hh~1NWI{p1_UuugrE|kqnAyFVzQ`F2(1&Zb_WD_ZzQ#&rz#vsGH!s zaHzr<G=djbGASqP`jgF(wR-}_fBEbGYxD0u`0v2SaPz+R{TGp$x1)4_^yCr7n%1#x zj<Dc(0sP)%OrWK?23jiD^;JE>YDje%S~ZU&N2_O&4y}0K3%9ze)G?DDrF6!CMWax@ zcdlG4kLCLtJHi+!J^k}Hf7mXHHicI{<q^Itp#k5@B9fD<IpAr(`+L9Jd;%9Xt};~5 z_A9^o&zdK2{VUCjH=1+q)30*7TD&#1VEQ@u_*$>K&)>>x;93RlTba|>PFuS5K;is* zEC1Cm{nJ%!_}+$|PNrodDx7L?R}51|q;Re>*};V~Yx*Ec;~;@<rpgSA7k{}lWCi|Z zl$JdT<_N^oOUyztJ97~KOK(N!*vs<V_0WLCFpg41ixl(PLdT#jPcO<tg&dWx-J!*z z;hovyCifDO%3cX63J3*$(#Z@5VRTy|TryLyDx-|ALdgbYxK0sW10*^n8nTK$twjwh z0V;^gG<|QLHM>?*Ur8G#ZJIJ~m-X9;%DB;`B@f{?-A*a5I|vUIUe-f*5DYj=$!>Yw z1=v|9>q$60gjpCYXOwB=(<z)~kTx{SDbo|49*_%0SL;0rDyhQL@HP+_m_lYYQK5mm zxuCwaRs6dQ#YqNX?QrS9%0sx!b3HB5jm8u{?aZA>u+tSc#&gEH2ZfmKRdm0guQNhm zLC4Z-I+sVEdaC&+zw+NTTNvbj>6Mq8TkOoc0Y$X#K-`sefpi=sjIb2M4n^g@7WFbq z1@scc@Y9Hk0P}PZZb#*es_emcd5^NUW9-(qhwpvoRd*UL|5K1loq=0vP@GzJ-z_tv zu8-(gowb!`-KwArJ<&P5;qjBrC;!7=HvjfFf4jMM;d1lP@rMx@_B2Nr(C=dAY$Kce zxjb|1u8QY{<`zQ93<CNBOT{)*t^<d5#{$|J`mWv;UhJ&5qYyX*o?0GwzfP=c>OvT! zoP~}u$m7|v`Od4>(9-f>J@;j1;4fzu*p5XjW+z9aCCk4aMYzHb38MVg0`F#cfmpL{ zQ*>xip&9CFX6cO3lE$UR3>}#k&QJu3gu!MOWzP8*UT!9^;u|EcE=8O*RcKY1kVb58 z!rrZDNI57^M{}0VdzIAUL7^zik)$pDq{;Y!CX5q89txuh{#r#@M%$fB$ZQPZec;2k zBprzx?>(gr@!%;OL*Mgl&CH==*@R6?Ppy>KF?f`Oqzy+c1PkqVlSI0<SY)s{$Hdjx z?P-)U3t1|^6>H=8Vh#>#l50g}F*sBaU~d*>esDS0TsnV~cG=&I?mo!C*U1*@5yeO( z5C+_~H5>5~JXU<$&UzU9xxvlF3%8oB4DhyK5x;3<0EII&!sK2*7S0>+Vd{o~vD8Ok z&maUGC|$W>APC`<&w8!S-o8RSTNic6JpA{Edx2kb`s6opRGqcqIY|eq<eecre6AyR z-FL3(pW1MV<vZJ}gD-ealp8!dYwu}2`dzpSE@4w3wm4N!865FOi+yRZ;2}U;F0!aR zD7MA-IXr?qO@nMBgqpv?q5>VLB@A^#V1l*r9T>q+$wLLU*ys*nFux8)uPT0|x17R4 zJG9Tu<OKJzW+wq%8pNkDv`qt~UD#F`+`=#WS>mq3dC#%K%|`0|(v9oQA`^~-_;KFF zU~LN<k0{v3!Wno&!@@!OTArD$`RfPo8k+_R=P<&k)+O=-$-OVaUkj&*O(;TIc6hG? zi#jJz+~UI-i(eLhilFq3(opc^GvQMQ)Y}5Qa1Lel4HU0)^b4DJ9)eF|p#hNgE9R3) zG3(fh;n_jHicGIFOk!WXdJCV^Y+}O%-Ow=0E@>Ztm2!c#q*V{%5ZuyyVBhdKc4<fP zE59EhzLvtVrWGgTZ+|YIcY`%I{On`7K$KW%E4U52a+UK6e0xtO2jwYRwsi_?2cjyV zI^~09GQM)v1iZbhZ*Dh7jvZy$a4DS0iXwtnuhvm6Ubz!@5T9-$&YwGnMfp@F?p!^y z2_;$AMypRKTv=Yz@GuSen**`3aK0U7_crRvjU~lz4UWv8(44ldC`G}$N>G<pkBwm! zj<Q+)eds8IX{==mPL&`kEA4k|AIb(k13In+dYA}z`RMlXJI#|=ah1Z^ez)MWZgcRW zCe`Y((#9<VqTv;I>IBOo$2n~~DKmIg{xsiy+Qbk`akb2!n8xQJ8$+t7(0IVXQ}E~H z^yF<6&Tf`8&)^e<v+gy3S1Z*e-U*Yw{K8j&ONDb*L4glmmdl6K2XYyi3wgrQPK+z5 z>K;v;cKj-nGkjEK!v|v!mJ@zaaeNmcnP=rK>yUEsx?K4f&UY0i_%dR96d$RFdTZG3 zwD#pKVw0E>8uw8+8-`2_k^YD}^IMjq8=m%HJ?eI%Z(vjNUGID^{#Fk+`}gevCn$d$ znOhF2z;XeTWmT@dM<2BSZf{&V1ML%5MN6<1FbX{55?=n0GLTOE>RQ(O#cLxdW45m; zgY@YUdh^<)!C+swOmB&Pm50Cu0KBU{-hO-ifRhs{oZ0wLg)_Woa1;0Nzf8bKt`%>f z<N<{<u!att2&P?X;f%|cDBqd1D1|d)7x>0T<Q4lvm1^=G`GCs8uTnUZiSNY^*`*Gu z9r{oQ#aTU~bmYk}9p5N?CH87K(^Cfbo6-H+cCV{p;*&gxwcS3ba1M_7X1}&Vzg996 z{Tnh#`cruLBJ$ZHe0&Ms#_UxygtB>X`;KPMiHDjU$gZwH89|nDPZo-gEGtdjheiB) z1h%?WGRl#6?f3T8>U(c2lX&s!Q54a=ueV}U9^sSUi%g*nNY`cb@?`fCxO?+@bM5?D zR+>#V7f+v}Z@{t{;H*C_nLPx>F^KP#i#^j{@y<RYVffZ5gsTpD?>pK=PIy(GNo}=G zO_+SVSU;U?Dqpf{DjoVW<oSZB+H>Lu0m4TewF%lH)2@=97@!R8ZxCT<!qW1<jaTpz zzAc|;6%O?|!G16^)bA9NbdL3erP7p6#bf1J>2)f3)2VVLta&7#Ko@y{7gZS$u1Zt) z58B8E?-TUr3$8TlVT{1!mVDevbH{?>!wqZo!7E>NBhHnDsaT|6y>N;>aUNo<w5>TA zg)@G9AvEj5NgeNBTj310>%XlJ3dJG3-_$`cX(N*{AYlOO&vWN4GrnU&Q{y2LapjZ7 zMJo9;9&wdV@JM*S3!~$9H%|V|-~7$U_qGkKcE9JH?`$4B`4~#R;q*W9ZO5UqM(e6m z`mKU%f*kFo9;$NS0ad2z=b;Ybr<??qm&orNZ`mi9w&8pq%4pFcO<P_M^R#c3t{ewD z-cm>5(a9NFZu?Gpt-7#IY9y=Skp7ts>zG$L>_s+F{`99m!)D63uz~)Rty~$rJFCc; z)JHdCdg4^0C1Djb$9Rq@m3J(I`Gxj?&y}>U-n)gX!%LU0Hvj(r`Y0RjoeN#P=RNOk z-uU#JnnPFyZ`!Qfg4@eU^k4A($jlbzL1gkQMhYS3o_4uf0Yy93PerxGDa*F_;=T7R z3VCT8;$nENfSvqUP?Yy`Oss2BtSb!-8wdEX8H30#eBnz`ynh^}=|BF*KMUOVvVrr{ zZ+;qCR=10!1B+RY+%NnSIBHkM_OxGCpC!(vCF@O@P@1%kTpi%mzFp%pbq9v;Hi|5l zcg3A8cJv|^_HXJ4or;haiC-sO>sW)a&Rc*uls=^0@H^VQG+|P1Tus;9yzu;s&A<6K z|2FPewy}SSbpO-;`A;`*c;fZcImWQKWOHS{#<=NM$zOEluzp^B@bR@?zdG2r;yG}w z0{5-R;p?X<z2+oX&-;Jx_f~%Smwq9QQeoVN(al`Qyd_dk2}UB6cziDd@T%(x{Utld z*4ojEbl})2#G+88VfN5LXuW8w=_e0j<2nK7`1Iy`u{L>%#=M)sm{zV1xb9#fvw@i^ z(;CJiWm(G+@-GV-ToAxigm;Qg-#k?m$waiwQL!pxQOL6s5!a^aF6t7Wt}kR3GC<?{ z>=Iqe<B|cd;y@CyK}9(lW><dv%*QyEQ9PJVW-wbEMbSyaG`{$ZRW@-VfY`Aiyc)+w zAaG$#a1`?mu3@%iz19iKb{gQ2v=R?1N39k!(B++RQclViT%fdcK%2TCO%ItvF^_V; zu?&+Ef7$gOygJ~u;gqEx>5-Q1PVD5CWuAOj^_9&939piFj@f?ml^HtN@-U59j{z4D zM`*NM9)|U>4!l=@SWnu^EagVqOjw0)mNT#s$2bDaIyQs&>7V;&%`@+MXLA!vqw6S~ z6==0^j@tp!urnRSVs9Ik!aBX*w8;$^lTFboOyoL>TW9A~NP3ceXhnQRQRct{7@ZVQ zL2QI`UI_pIKmbWZK~#N(?x9sXRZBjALNA>Y?_{jT)lxw^kv^no2hxVm1Osg$0<5?p zz4bi{&66mc{{tP_|MEZmtLD^~UuyQzk*W|8_ANWNH@i<9X^tLaQx!H>*~&S*X&XGS zuemdZ(qnSExqSB`_0^M&5%%rh$E^My=p7{@OWgPG-`^ak4fU8m`31++lY%ZFRC%Nm zXZ+V3(tw?a8#pXrb$tcDn=0jx9z8;*{#iQR3(y&p1JJtV)qkl%iGqNWDR$B-72GH) zcte4vPd*jSizqquWxgc6@?B-KOO>6uj{pf^<JWF9SI(Sm<`FtpXcGXFLDwc`NNpDi z7+rl?C!jrLvW-jM9qlJ?0$MM^<#%!5d+S4?LmnajP?448jKFDpc}C(XKp?!DuFvuq zzuD2It%5h-OS`5w@IB8o(+64l#e~@iZV9$xrR=isZ2U)9;f7oSFTsgy`$nN2D`k|; zx29P7G>gUN0XEe_&}7y*?Vgq(J(h%l&_^BBLA}B=mk?4fo?~;GB{m(|c@STcL%27f zULB}Y|GGD_gM=uPPFZfLaAx@$Zdop29laR^(iZX@!SD2X2Knn4H1$v4Xf`l8GX$S3 zg){gR=N5u`bqO{FAbp;FX91}r2QA{U_+2h$&0!6CF+_#UBk_Vm@SpGg%41B)G`Y`d z;7W*ZhUDbC1DFWJUj1v|brVDZk9USu87toxKF><OO_)ltje2<P?(HjTBQW9Mdj|uL zHGxU^w)h!fgBwfFXYv3h&=jR}uD+AbxDueg3yTV8`Xr@3BX*f^mB#A1U^1^xNn#pu zB-^bg1XpF^Rv|wFRoc9gq<%+xvHodL;%TKfuz3`P^O0tR$%bq2jKvkKh6cB=fgk?7 znK049c^zSCJyIYkfDu5ku7t@t&;ml=aKf)&^n-^Erymm6y(n7^-zfqu1t3}IO!64_ zHXHbj!OspJK3cx=tZVDg`f2Nt7vPY(vcAY?9v+~z?^P7Hw&ndt4~PFKk5J;kW&c|W zYmh~fD#Gey^$!Zg^QSK&WV1|=RU3m$PR3<aDv`{{*L>3V`Hr}j!-3QU{_UKEmJett zVtglFW36r&`ylZ{$5)DI+iof>u-&<NtGUg&lfjVq(v?x_l5C9&kes%MYO`Kd7%EF? zX;OZ##n<6xJA-N}#oAB5;Q-2dN!z2$!YuETpF2r-_Vj6Z*K`JKTXt+?gQd-)wgP&! z-2A0(TO5!?WDExpSFqxnLTP;D_;L6X7S6gX0=Bdv%4@s~q^+m?ktFvHqHo>2L0?-6 z+5=eCI}w~LfxQj~ZiV+wj#*(c?jDmMbGp>Pm+#ZKe;H<90{e>ONkqWRVJhuyy=b2n zS*>(!jEQ9|oUe1$RgUethh@G&9=}Q@!)$P;GOuU-P;>bfdlx`gGYp!Xl(zmB!QT`x z%;8H~<?=L&=LII?REEyuCSY;iRd5VsD6g(`gv)+K%QTQs%4TVp5BHES7I|0n9RTva z_-M&|(k?-Yb_k;KuLs@`<uQEM2^G@{e;0=Yj!O(9<vr!1PC{Eg)20e%07j7d$&Jl1 zhssoOSPE)iN(<Gd#8RFONj+<Qo&)(@mpkHAdM|~uLAb}LWO&nV+S!ig@BQSDH>324 zBP`ujK3FRQS_Ti}^uZwJ!R-`ow#IH;5&>je{4wQi^QbmMu0&02z|-)e!+n(Ffthqk z^BypI<URRW8u_qoy!JPs?9@-EaMslo2^uPRO`nmRut*(X6J^{I4UFJ7bYv%n1^BPW z4dCDqV-VW!dR7x=QjXZ-6p#x}@)Ftl1W%i014<Rn>5uW}jL8J}V?2UeIVam~OVYYB zt!0qEMdp&n(5|B-p(OrwiXm}${{#SFHrozI=_3M{Dh=ZKvA!mpF-pmr7=-Y1d*5Dt z<xvV}zVY7rv`nUFpBSQ&u<SeeR%a<6<wsgI>&JOfr3LNGjX4o`njX%foqL;IM~)+t z{NLogd9Y{6Ro|KQ>eZ{a*1mOBb=THi)%zl~)LOe+-I9=m5IY!2c#HsHW+u!4wqk-m zU<S_;F%UE1FgA{`2Z!g60m;~a5CT~?0}>z^)LM{esk^$Wy1Vx6)$;cDYMIaHd+vQz z-D*t`F|z)ETXo;Pzr4AeJbCiu$&)8fZfUpfb1S`bC2#>AdiqjDs}ao0FLCYVqkCQc zZS+3O_vQN)@-dNk$Sj8MK5N04KF$Kz6vh#AxcRwo<|Nk5oI%3Q6%Tcthri0k%{`B< zK=B>}3;=ZQl|@-1mcov9FbU8ldI-k$cHy>@0g0Qw$nT<FdNh%3YvUvxnUp*N--)u7 z0KR!UzfJ!3XXDGS39-FsHU3q9w@m|#Nt2@bzh(EdV%*|gL^7>;I0iCC&2Z5B6jsi< z>YI*2O1*$O0Ml4rmD!h3{gk|c$=>FivhtIbl6`)sZvv1(N+R|v@$2qU4RBoG9~>IT zh=iTS(9l{A0MwYxvgJ36EOa<lY215_#lo5COSIXMcF%oxGr!u<?z!tOEJ14*Wcn6u z<aq43@KPVn;7!Ejy7|4USO4k%>q#XtPTEhn#>NKNWjM(gc{Wzg*5A2_hD7cvU9)DC zIivU>K4m+Hk%qipeDTHh>%ac%$WRxkD=r{VP~Us+z3uVG-;#OZ73Z=fQ#KHvvNZFz z{34oUlRwMV3YG~1$KqS8hxSNgoU{R%*4X1W@xT{8n8Npbvp|ByXYa<tGf&i6Tx6a& z%iLSVrMy90E4TDI3hU=QT0HpP&&iDA{7Zwf8w${sF?>)qvRqwA>dHgQW}nik3;P;6 z3X5}Qr$eGpnw+0=4o_bsO#Eowt3jF5PY))%d~t?@nvb;K`0#J!e4}@~<L$9>-mzl` zG8}WQk&@@di&y`=fnV`(1DDdR=T%vFbVJGrT&3f2E=eA=neFD&OT2sMGCN*Gxwmi| z;NkC=bytaOs$N4mijKuj8h16XW^Q=~rSq5CQ%^mGoW3hMo4tGYwzpHCZ5Wvhx+}KJ z3sJ}^I&;$VxPUtr+KX%p{%l|68vB-E>ifj6?UK1M{Z4?~NvE8rlHa!Sid;{<`>`v5 z-;6)tm)yJC45`aEx`-+q(pB_a(1$W!7DnK6UKy|GJMR3S!D`{tfBfn8+rRzW*<Gly z#7^`rfA2^B9<DX^goZ$is7~Aa^b(?6uLMfhhJBQ8<uh<C1NW^gxytJ4R<uOn{GosN z)4q0)u%b`H*g!RyDOgmabP@6`6C#wo#v4U3m;s4K)W`BL$|)7Hu6BBbxnM<#o-hN( zFs;Rq)aDTK+|IoXzi+SIx3_Ia!6VhnU@xP{_5@!QPHV`20HW2kg9<@8>E_K_()r5L zwivP&j54)YG7?9hQX>$4AsnKI0jd0x71#kJGU1oW^~z(nSvXMjolOQQKI~*pMogn1 zA-Y1O{I)|TjJle4ER-DlWGuvULaGAHcoCcjupsXS9|aH@Mp=oK@^3*!Gzr7Zc^XF; zgjoiARcj0;01gMj;3V9<ZCJmn@O6N(e9Kcn(TcjPC9rS?2a6ocr?MogedJvea1?Y1 z66QxjtdooT^&Ly!HF9o!cUs=kd`+-o#Y<Zo&-7aQibH+^vrJF{MS3bY{cd`F<_#J? z$RMf0Sqlq<(G^S@m&oiAE7^Cy>aq6zzyJ5!);o5$^H{ylaH8!3LXH+c`dd<X*odM} zdUJrb-Mm&|0X{#6Lwwvg%rQB1aQ9t7Nv7jqWSfhVMONlj@HtU-+qZ+D!oE27`${BT z<u~*8c7XG?JscR#XA~cNy2h9Xegz^YucFTbA5|DG&Yo)z+;w~V+FyR9{o1emi}sbj zc&hE)achKD6$=V$ZY15bWfOiv_q6TY55D^KZQuU8S(V(LNzSQ-NmgHvQI8w`u4L@@ z-+w<V_Z+0f4giHNFYz0pkNWB_%y_nOuMA2g{wSC@*-f7Z;3a*Z(Iy_q@TpJ#Nmlw) zT4^n5orhS}v+wGD#zPIAu-Ru+)_b^@3pB&z>4azrD<QWoEqNL{dFS9I`tv;PF^8Z& zF8-mjb10I|9XsA8*)ngu3HDWvBREJe_P^e0IdlokwgJ`Sd(l)+SHe>k7PYlV8ni7P zEX9ZY+;%n}^OU-+w*r}YSa0Kd8E*Vq;Bi5T-e_OyXh2#UdHb8%{N8<Sh^@725d1c7 zV!J#F=S(`uBSIL3)WpL!Q5aMxE~WALv(v1g&cxbN<?j$KHCD2%5^fS$>^JeHt5o0s zJ3yaRS*=fR6wZrF_{iV113$WBxIjU%7$43&@O#q_g7(3hSW~YnSfk*J_T=$NT!7$O z00q?87*=Ua{syCPKHG+|-Wx%=0jDA%<%1J|sV8;zJyMbHe2-wov;4l5AZpuq$-l%| zO-zZOKtpXqCs_TYhPa&o;p8SU$RqifSC=1!r_78slwXq?CpNy5(z0wPk_eiAgiHGF z<K}yxUsr%ptC0FYbm)ZJOuF)u9eLN7NY-8Tr3-nva1)wxO-m5r#^>ofvqiH@d;)xG zrIXXdyYl7d(y4{kgwHfJW+a{U>B@yLh*!6`^JgtGNGlcYiREq)gqoSykF`~}&)BvP zf4sMBY3CUy5lgYwTLb;!(gh1=t@B-68f1JLq=HNd(iSyY5vEoO=VPV#UCTntUg+O) zRGzJXhg)>{o=m04!#1IwSdN~df1k(7`63G7JuIwg9c`H+#x|^WFkQ7nNP@sQc;jUz zEXQ6vO1!0Z;GTV%TsW>ewu#p$n?Za(?ie10GkJMv;K9FohKby|wh1>4x?H-UaHeeA z6&?}ZkvxQi^t9Op7CAkP)-w!7nb2r86W3n0p#>Y0vV`?2%D5}t*dApfRl7)iFL7_y zS{IAR$VKoN>Cy2+Md%8YE3x_wU#q&yryLh%SO8ZB+P-rKi;x@APX<t?p$21NPK9$# z+@yMPiK4-@TIwD-^jyZY?I><1;7!9!mI7}9O>8b<=bwF4{^z?q&$7>*JkIzu9iQ1+ zh7U1@fGV!SPb{9uB>m2I=G}2wc+ap6QMpE;e*2DFn5aQtz}ojyv*?wCPLx!0T*cR> z?00r{v2C5Z)E>E&E%zv#dmql0++RSPcF%9i?LOEqFW|#)20yFEajh{kUwuY7ryu)l z?;LDIx#Md#;!;C587TN2zW_iP!Cf$OC@JQVLmksRhhQGXg_ifRdR|2Kr7#s|OZI<h zINQ9Dm&rfAikWOnB7X1tZ#ac@Cyrq-*5sqLvcKik<^@*MZ<2v|15@!*aojNh`;2jO zck#oA_|DVp$&s`or{ZZ<oMH{K3<%eMHeRf&X$LRJqMkSX%_qZcXd;B-LO+hj9C$ah zhJ}&+?8MsBzT-V_@1kp6<oFpN2$MIN9EB0Iu>yA*GZ&G~&Y#Y~Uc!_jh+lZHIJijC zTViU)U)mKp)&&Z3Bd(0cxcnjCp0@I|!d$frrN<@k(C4o!w}O+a?zBUJW4<bcdqwuO z6`Zj$vWd9^+qc)^Qyk0YD4gM?t63Cx3{#fynKHym7+0X8P<gxy!SENXxK%j2<BK0T zEKq}sVdTq^D4fj;zQe7YVV){s>b(?VH9n-M;Lx{(*$yIy@^kqxpaK)eK4w3!IJSBa zc0=Jzn#zJWH)T^98f3WmDIA7gr6+0A_K|kMX~tW59DFEl0i=KMY<npuI(O8~M*MEm zwgXr@ug0z7D&~3HQ9N(d@|oQf<0uhVvlU+j{1BSMYUvvFgfq8)I#>gH4{V;@hrCO# zH!k1%I~d^yLp2LX*2nRH@fkND<=Th?=Z+o4x*1mp7-U>zmyhzRb>dHOdlRbjTj;d- zkAfLK?YJ5R2Xja3<5g{0?dJQk0*bchNAAAAlze2aeLGkEd)Y^vS05p7{zn#&tCDZ! zVg0G3?dLz90PoM`aAS5QkWOq@d|HpbQ)x_B@?5pM+xguYvP8Q(_fdY1%n!{w*Y0KN zlAGkkg<s2s<8`p4n}n_?lrW97D2Kk0wxJF_1;?({?+P2{kkS#1)do?njgBGvvq-2? zOp9~JKXGHXyf)_{=TmKx1+51jxHr2&Jp(5SXX=@qxAbA>g=4tXc*~>jqOcoyw&<__ z9dP&qK!1(PJ|lKBe?WaO%N$nO;v#piT-At2zqz^xkp_DuvGR}e5!0SwN9phX{>R(1 z&pt~!6tT!8S^$6F_kLgeKx^ortf?<}L32E{jmp^VrGN@gT^(ZkpYYEtYJfZG+Do<p zNNLZ|4w;LuqTw6i{#LG$d@Wa5KpDn!Ftony=W50?AD_;%^!ppdada1+<FJr#KF^>y zHBKL2<+F3{wa9Z5xMu`4zy&>ZvbOLNojio0EOG%U@r*Nv?!)tptef(;*12QI8D4ZF z{?zl={`H637ryZM_G)%oKY%NRb?#!twdIzr_}V5ds9tV<Uh4|JdVE%>L90<XD;wEA zlr@z{YN5Sgn1dc>!H;+zWWMdYXP!8BHJ+CD`WJU6t2AxdM^7BXz0CQvmGrU>cWp!T z1$Sb&@Sq>(BZm)T5&lg4p4%VpVR7Oe@A@{zu?cnuAnQXXgXo5anRDCaFCeQPhu773 zE&Qoaa4*G6gD!%uMmJZ==5lc>?W$;2#x30leU`e&ljzC7C^2<7`ldXD%|2B)j!g0m z^Q~CU7m^BGNlS4*2u#wohd+zMdD`LpnMq{l!|gMl`AmE6x#z<BUj6W^+YkKU547#u zH!&ArydH%|NpGZ89P;WQdF6WY@ta!xD)O)OH*hTj_t#4DO^sw<$xW_tsqvwo{h2gC zCLJ_{#NoTl!GXf<yIOoXA<H*V8wCyD*W({YCV!dLCI>y4jm*FXb>d@5DqOB(v5Fos zLgui_9)v7?IOB||-L`IHd+eTj+D=wS7GO>?8GQz?pd+|)Gl8<#)orb7WzKe5PkpD5 zD4;D%%N~`su_onR_?$So661T~0M{%`I_^L^1+bk#n6+%QT;qA!;dFu@r7^!{czr&` z_g!WhoJ5FF8Ck1A3SgFP92u(k@SBR>SbVB^=Th;i;?sEINrJTa1q9y+5d0`%v+}JN zL<JdxvDlF@mIAHP!qE7gl|9Nc4|{>|Mkwy!Gkl3d+4M<P$~Oix+l2BWzz76)RA1mU zg9G@mPU6Q2drn1VHAvW1GAlg7UvL+~<btOb&=J}JEOcPqxXo9*iVxeA#%NctjJt-? zS%oudQ5qVWLs4=@tAfSR_Rb&t!S=5Aet%oFX1txm&(caJ7vm%NrNl~e919w^@M^&< zZlhcWrz-esi_E!{Bka=67=o;RqIx>AU6)YesgPIsYP);)bgaTyxL_~PF#{~OhtqkI zt#ssyv%&x^)Q%oM0W+fQ;6Mx1!NV*zZrmI}_UimuESzs|r(ZbQe)X6CN&BPU`-8Th zRmat|jcw<oWJ=m+fK=$cj^gnO_xep++kw09V@uC#+CG@xCbnIf;Dr}nh#xRlx?jV$ z*FN$v4ZQ+<&C~vM60eqdlYF;6ZaIsxgFbZgr6ol5@e+od^lPa#gcZ*ztdEZ#Jpmr4 z;@8<hY^{pXQR%k)W!tDuRP85DD5QsMsRUp8=C*7PTXMnZ8tt=$QeR=+t=`B0oXig0 z(WfUlN%$1FnJ0XhzAz3>r8Q|%Ww{eC`)5tw=oh53t^F>%_I=yTG`4enbFv40`ki*O zErln)i7$N8wte3|q2gTSf{P5f(y2;#H%_dM>{rxL`W{8$Jhyir6Q+q+IB(jr0X}4( zE#VSSAb$I+Q#~)03NG|e5B%L};d~l}^VVCo<BkKD1}K~}NdYr96QEH~yNs#1wUEYg zV+n!!<ni<16<S=om76WT_+oY<s}FQIE;LvJy^AFo^ufcmEBLZQd3NqJZZlAlt3Vqb z2ER=DM_2?{J$IoEFU{Z?T6zZnfdF62N@sstsXV)PW&q;cf8x@+t89gnUY^oVQjF_m zdqm+(IZ2&h-kebsQIQYtX4h3e;iT{RRCraFe<_p!H}DB2d6B#n&IN;QpYqKw85=LT z@=RdDqr3o*<|Q;nO_|VeKXFPr`>7~G`cq+4byJWI+Mp@p1Fy6nbn*1J`4Xn!(kq;8 zHE|a~pYb;eXTpRf@slU{b$LNlgeypqPFYUn4LB8E!=W60%e&p_!tcS6wrUJ(=6$=` zIwmwzjIUR<e8x)1Lqs;PV6p;b?#fO{t>vDzx82O&MsO_BFRzEOgcl&-x+6oH?H5pm zA>*TMF23nkTFBc+^;@W=i$0up@4Y>zvtPfiKRBQU#GW<?uvUc+>fyFY6}S2%zCxY{ z?z@MH7F+rd#N8ocS}j1Uz3fA>Lf{Z)aB%?z!Pma>W!!1#J_M^-EHMV1kr2;vyo5h( z46HO&Xnqy2yHF{QRj$y7^Co;ILK@I1e<<3v_D}M$4cML-U%>Dx7vOX`G|9oR?ncr2 zL&02Hu&nSaemFj+Y~GzriwE)L!K|~LJhYi|$5Gk}-4%8=EG^YoWx3{K+obP_OVTTY zIB{^|y%m4$E{YA{@6aoBM*NIhq&0n|by8L`l<tx)ojnyL*{!>G<-o*2<e17Jxunjb zA^pm7xpV{MMEES*GL?<o0kjdTEv;Y78_=k$5sj_Pq{3WU6YK64Ls^WK(e|b3_PUoT zoK0eR{7)UtD;EKMma>e?D4C;hK0D9$YZp;V22w^5x5BF*XJwEL8@IH{Y2`>{SSENc zRXDTIz<A}DGp+KOT~@Y>3g^YeOVq=ie(+;>Yw~pg2_7H1cN|pwqFPHm4+w49hbvqj z;7&F9SZ~2BEm$x6jBS`7{ElCFp3(_SB}lYPZ@wl&<M09e_$)pnR^>kx$9%27IFw&Q zYsTZNA<AQk$sfmN-@T+U@$R+ECe49B`4lO`1BP*@ar=RLu>#uP-tmq{=?5iqX^AHv z_Ht*MnMF>M#~`mvPo6@F#{vcO0qc_mTjB>lq+xna!2(y`f-9g?-Y8=jzcXeEqqHCc z@P*6oeLleqxCk!6RTc%HQS*)Kr6`=mJFQ4@qV4Jct~5q){li3lJPKzHqt?QCd|fR5 zRSH!<>UeKqFlD>bDf1{~3ZGFp&s`>Cl-&5N9vVOyLYxu6SK%D_A{Ne&Mf#`yeoNsj ztvX)z{WJyer+!n{u46>m4ct}xY9r&O&l8$)*cPW;tzM1k@^aBprIYqLber_1HYZ*8 zK^aK8DjMu?DKA4tbUx_!daB6xdxfhEu@AXpRoVko+6(@}Ht+%Jx^)-h!p>b-lH>k} zt;{1Vq^lTM4PTX?d#SH2$a{Db{0e`}y}v4L|0_J4AI3<3^hw<ots;%D&)5aVokjZp z)CG3+JbxI=w~Ouksgo>zUZhSe8W2Cb*#eh+;YL3Rz8M!Y9wIwtQH?fLZe3P5TZ=AD z;)@4=`y_65wsm<Iq+NXz2Ed^&`H44xbN8PhAR_=@_0QnBu-&y;7h-#M;k<BFy1<cd z;-$tU`KDKBh;N~7aHTx$H{EJFpOl9>-_rO@I#3}UdH_zpD-%gKP(=Ee#hZ0cgHR@O zQ^NS*zpK>6z8G+LQHHXjqsTKO+*&w$2(U7>v^C2jX<TZMsc5*4!g-FJDi_Y3zz6Gn zQ8@2IZW&$8L3{RJcPKap5?O`w6OVm+>iKnlmXTZS5L|p+q^}R4nZUt96m_~_n8pQ( z@VYx(7iAv!Zr1Wrcj@lgvnPtcRV+Mtxw};!<E^ogE)qWb+0SJ6m5M@n#0Ng`qb&aK zg}2$4<w?*F<-#JF*Kj@yV>eZNg-cv==ki^7qQf`1_8$}(JPD04<)^lH7E|nu1lm46 ztq0^w`>`tk8A91<lHGKkZD9KrUqeIOUDin*jptkV)G}I`*r)LKbYVW?N%tGlmIhBb z-w4CQb)3=Up@P%+-SyhAVFX%)ZX5==qyh8kuYv>lzN?4hZ)8d9LOh2AmAX$ob+CEx z@+dk3$E)#)v9@F94%|&{X0A?Mh!6Nwy34sx!4DD9AtaxPYbcCHyjd>|@tk|Bl)s1( z&}rt{7twdvcBAMvPM$c$-1`{D4pV8nTW;AA|I=&PrRP{+-#I&Z5+lr+DC>8lOHdKK z3T1VS@2J~R3^Y_WfAy<hjiH)5>{OgT^14Sj4+|c~zhTbE&=??fq|#ID=u>v{vMq(x z`iL{{;`zl7)SakHaei*wDdY9JE_r{?FTzX6EKiY@ck{jZ5{Z^k<@R6t^8Ic4<%<tD zepTM0{gvVy<{e(ZGhz}MNvB>k|8lv<kFtXW-0#`FryV@_Y+SdT!0_TNPrM~o?wdA^ z!NbsVL2tG{UDjd&u6w@xy*}mR4S0?8t-AtW{(S4oytyQsEjNK!IDh2&&;ImJgYY6K z2L>;H`!3NaP)2bB5rN`j()2VZPrG;R4pTYFB-8;$MU;YaCd{;?Ogx?0frh5B<E|!5 zo$G}egf9gBUHBG!;=X&^c2-?x@n7r8$yFM2l#U=A`V#hpW34N7A)qCyt0-P}fS!q| z_!M3zhYo@&iJX|KMDn-p0A^tFQi$8-Rl=H|69nOuk-05U!nRyHkLh{~N$~-e7~FZ1 zhs;u;T81TF{B2s(B(AWFX)eDBo8MNz6ugAnJHja8)+Ga<44=5d;P*Zc!xY|R^bRP2 zQ;1AQU94B?nKTs+Sk#FLDQSe!JTt+8scMO9o&BaDWL)XeNsa9^h`=<YAS|${OFiRX zm-1K}i=ZQnb&@wLlj0s2J*9pgdeK^2y3oZ307oGmnqZKWF0M1dyrQ)>N@ta0gO-Cp zp^Fo(gg^h6&*97YHSK49;pf{PXyhx;9As5<ZM${*PHenjkZjvMdHQ5l@Km&WTCWpC zC;h@9ZpWZg@v4$*9IF&@c>MVB?vQ{1R{O?b+7nR-IC%GTZ?(m-lQb=1bgN+A#@VjI znR-2Y@L&dxvGFzdK0X0HQTkD@0cdX+Shj4rh59pLy?neqeE(f-5qA~;;(z}q?c=}s zn{CgIou$;L3@0wOjS2^G7{xW1w>Qo}`wDSG8*rPke}8-9o8HtOef+WJ0RZBCEsCEp zwy&a}COvdcT|L<GG%LfNzN@d)Z5%4$x2sHWZCe}L@?5B~zxb|i^DAs?w*K~=K@{dH zmM$<Le(6hJW-I-PHh=;_#e=&TY(KN|slr*jW-@^SKU@4d&hGYP2nBs8f~S2E<)()+ zxg}9$rb_o|1d3BfkG4q^JS(8d32BzhrCoO^Nc*$&-MBoVoH49o;`W9(p?UHUZUsn% zZ)<28SGcWr@_`P#91K-ZYq4({2Tm`o80`QqJ_IN9EAf*4MjfRg+uqEz8ejF~YuoJZ zz2J0=$>=&(zBiDseb&K{jQo!Pn0}`uqf#tNcyJ63&YzoUXHLzw4YcF<nlS`lvnF$+ zQnnemxKu)<Kk2k6hqZFnI(l)5)n;5GjIzqVdV~o#-{{Fq$ncj>+H2Vc9m$<^)&*-x zCQ+Bq&%#S_u>d|eFujeVXq-TCGP-yf<ueNwP+hFusC#&$BeFR4NmwbPg^%BqQ;-r) zTjWlNQH$4@hdjsM#`iLw+mLTgpLc_dqrjHi$oWrb!I4tQ&pe$Z=9w~lC$(X`^h&%^ zMqB^7L$oP}8g%gm&D)}*#NcUqgS>pBh|pG{!HD)DQB&pFW;O1aN5w7I8o(;(=GVoQ zHWi9X;Ve#z2V{ciBvDBwm{u^Z{Hi`xrpg`_b>c$aVV{>yoqQ^^LWQK3=b~_yiL7MN zlbuAHb#H*ec~1Ocy*Ds8)^_j4T?3PQ=}QZH$H40f-{9Yz1SRcCISTzMob6W=SeWeH zdprF?_f=v_+Aml#Ryj^`3#E%to-Ti3@*<W!m)fp9`=W4W8%>&n&JNt-RQL-YHj((y zGDa)m=Z`!OU%86H`MyjHBUg~li`tM*Y!s~F9h8htEehvnpME;-Ft%astFKV|zYrHM ztTqgNfLGgEmr^UK(`gpMJRH^ftVJom2_MeF3X&|S$_%{VTi(hzCO=Xxm`8!B4`(e+ zJl)zwa%Bpypo?dq2gZJ3#03rE5WnZJ2zSSpWxMlb0*k-C-LKmAnRwUuo=k<DjFrC} zr(R@H(uuBz&knIwcwp6N^5##XNB#({Sr1XK{J|Iw>>iY;&wZ`<w(Zz~f(@%4XsquO zq0TOC=mcCiuB#06OpCL))Q}!Vm{@z>h2wegPHW5!jY?A>v)Vt>p^6EtOjr!x%|gWM zZ`&CQ=lJ35VD4e3qQONf5-e7ojK+|~czL~@ytvd(;?H>o_hI&j_=TiM`2|=D9BZ&} z9;9E)Gx3|8Lbhc57T?zyr#vr1*BRncAI`Jv=+iyI0@lv6v(N;%S#+#J`4rl5d^0UT z*yqxg6ea)D!B+L(;uW^Px3nhR+GfU!^)iqNW4X*Aj&T{M`nbli3~@lheD^0mcxQ}Y zjG^>|TSDra_=%MI$=}m2c^WGJNpsLH2}o&vu#LQ5b{TF|o&)lc6(jiizPr8d4X<za zBIiu7D6MQM?!x~&yqGBcmUQ;OsmarA`ur)Z$tQtRxV@|!{{tKFi9_GHrM03#e;Zdy zG#EKLFZBmZ_(EN~biDV<_QGF>bILSd<1K<?yVN|igT5r?cqrLg7IodCJdSnq7`Mvj zVdOmz(aboe90ctPw0ZS-6>I*!%D8MBUuB_qiNy-fQy925i#rhvbg0j2#`t063j3pS zy$VU+BX7hwqvi>Q*FW<mbFT1Za9Mq+!t!ak$(CP4U3Y;Uf_sH?nmieH5$qmZ!M9K2 z+TN+3n58b#BXlSr;x0-=+E_Y`H8Xu8Pk3SQ?Kg4YcjA}KDZPTTjy42=PxMD*ArwmM zIp1XCww>^v3Ha_d_%@0kcrU|EDV+hy*@>X#2Eu^pGtly<yUbUT@Vj8AH}N~~^i^rh zIl~M}GW)y-172WWp`T`-=WwMFWjggymh6$)TeDlDIO@j}pN`4Wg|4k?Zb+Mwwr?w+ ze$Uf);tOEL{yeK<)<xKJB~3#3Dc`RCkUl{r2&tQR^;Y>;;=V83c*dm$G0n$ZDZT!} z+pGQkR_)Yv#I%uZ#fQXM{tl9RFnuezt7P!_@uuzP;R()>TsW2nbR8kTb&lQh&K$l9 zKTK`N&|M6DpD!8$M&y*yG0$Ttg|oa}cYU=3g?>if=1X@X9AEq#)_M8z8FqtW;mmHG z+xPBcY$|$+g|lr1&YZ_R@z}cyUEjpNVl}c6FYaukD8>>OGN&?6(}k5ZqvFp4?{7g) z@$fj~>LNsW#rdsc(pQmXe&=_78#!t+<Emr)2S4}|?an*zqzq(#n3(f6JFb1ro!(>a z#^@B-FRd2sE^ui%TaO>KeO=X_`5e0Ff~6N@R>I8v)QL#jTFjy{pp7}K9p$)21}dCw zf8*N^l!3HT&bdqQ&{9(NWs0YwJ>wTol#eqH#&wGdca_i6%%lCbfwolH>br86G^=|^ z<A+8AsdH#tzf$gMb|PC9zqte2_+z*gWGD|FTqM4tGLf>MfBtMNT#vBW^zn~>ygmBZ zqwPKKd3U?(t{u>Ep^0MaGEd(MS-kkGyD8%ebnlr}8W~#nMf6<mns<Kw)Ki~tFC2LR z_(o8?Z^8Iu6N?e^?a%-7U!X94HWuP8)aiON*4-$1@45dTc7mXMCOh?E;#nRx3h&&s zaZ|hF_B#MYm$T?cPM&Ii_L)D61^j`#4zxXc_TVPU$tH*6u}Gs5-?_C`%g)K<(KR=- zGV=H0+x!Tgqf4Q`D9@=l7x&7IhR2YwlgW!d<Y$%6__nnQYUA1l_08`tj!+g1**Uy< z`aL=YXiLP#g&f}ucb81`59Yzw;o(}SfCMrYsrwll6*l4$MpvV3Yha!lkg}7H@@#jq z2+f{3GtB|xmudSJ{f_keS*)CoJpX)q@B4lT`JHo?K$~NU3TKUSgx~S8zixi-!+aX$ zrf4^R`djhd*L}sm#fS5M`;-558n`DcJK^%}AkzJo+54_iNyVOun(f=S$IpqrUsTk% z@}z>NPveBq!C<8=3-=#{DXA#bigy}DiKyB(A=Eu_&z)@(1V7Cx&lH_x1O?#mI{Y(1 zq|;1LU2PuJWdMZaWX{zbTTsH3iAl^OOeCG`xKbn&cBRK~8IkFn)Xky%($9}uV^y%p z!0nWNmxu=jYBkGr-qs`Op;8B91r-NIK4cI`zN9stOsZ$XKJ7SCv&1i){r6ruEZa7n z6^YQrn{lE%kdnFk4p*?)dECNaXDzs-R`a$k%-8H9^f3`yzR0IsCluolW;6|S6s)o6 ziFST*CDX93T9RrZW;;3Ab28*9!EOtYX%1VKbwgpTRj74!JBI_e48ws{3*s5tKuh%{ z(nAq#7Nu5h+CZPsu8ytXq+#pi_R1lwwrgcmh6m#Smglgr9Yd)2`TzNs+T-8xUG4MF z9coiB->n-qw*du22BC`x^5V@pNTXVwOUo`wxazhFhx)dyctN&rXJEhwpLrH0|2#}< zW!rbh9f{}Sgl!!E)Z`IsbYQsV1f)B}!3G8W?ZAQkFu9?u96CM^F(EI;?O}ogS#^}Y zdN(guwAgz1p>`eE|LOnsOYLL-_BY#Jlo0B5NS;4STE7B!CTKLIc<-$P5@p4@xZW6I z5`W8Ww?_H#hDYDj?z;D$cHpkN+7^7VuAmLH@R^}qpF4bn70c;%|2_A&HDkkBS=W7u zf{QT9IW0?TW9ca?%zRU+E3TwD`<CD0yY<8g+=k$Hn1dCZOv(d7)8u7b-}T$6&t@%H zGI&rw-_wT_I>7%*{8@WQkP2tFR<5QD{Su$$AhR<lc&=d8H|)TJ;G|kWT8tYQ+JXi{ znU1n+5a9v*>a$j5ynS1%#Y}R6U0Uw@v}H@9TGrdX{d;faE{_s^F9$>GEKl&eeYC%# zga^OIx18a(zrM}y+lN&QhgNb3)#j}mDHj@3%f$uSA_SO4O{(M*^aR~%&@U!Y{GK^I z8_UHJ+DDcag%R{7?&?q|c~|j=6}lioIlKae!Ze3gEMVb$Z2;@$aaOhQdw3n|=O~<6 z(2DYBg;wUcCeo*~6Y>EBaq2XCnLfXY?OF5}Jg2m^#9PPCgo&$jxYM97!sV6~&fqnQ zW@yD{rZH3u2&tjJ>k6LuQTQ#KNjFiZkWRX$cKohyGzWO<68k0ZeD9til$*kw*ri|4 zC%nvuTr&}oC!2p1I%Ho~$nZMi<Q;mb7D-Bgg!akXDOR6Oyhmx8wz6wfeksiIh%4j@ z^H#xk>l)>*u+T;-fTb-j<G6TKusCK2qiO4D_yXJhYhqAiM|eMd$q8o^*U5)`$*aF< z#K2<drEI5vIKD!&^6_O0XnIa5&Uu;-G;tlb8XI=tf(5q{SBQHJ>%HqMM%(Vad*hl2 z%>aB?Arkrl-&$|kMy}+`E`(jd_7v_C=8?F^nVjv}yN~_?AE({}SnN6GNqa@_V7;TC zYtWb0JRXEPi67_N_Ta;LI|mN3MbJLnkCkcT(0*auzUCM+g#z?>1V6{#1NYt=C8oT) zLwDLMNVm4aLY?LHAgNuXyhAKhZen3)8}f?VwJp=Ow+#U@Z4;s}!!#j^4RC#uMK-Ov z&2ue27Pnw69AtnK$Inc*X&m8HI$%)bmQHA27Nw3KJ07L;?Tj%SvEtF1%1d0zpB(E4 zU8EO=v@?I`1RltA^0<CNooo)|uowMoyA#R73B5xnlp2~MFKNollkaC46AwLiC>FZ6 zGFFVSz_e<m3wOk0avvFu0;PG=g+Hq$rS6WO=V_~X&HYf8Y+{SMvX{#KEaH;JvR%N9 zTtk}+m*f8;-)3pA^C+C9%Q38iluevyWsEQlY10R-Dg~~}BAxt>2_SSUo4=C@!5eNx z;f#?%thM;!MF5LHbiZx$By!qBczvZN{3bUU2sdD~X%=)|JcE_<4A$Zth$COOT>FXi zS~R-~MgAs|FkY-!-7XSOi)ANx3n-o(3$Ma&=h>w*r<@3ImpKq|ehvjGGVCIXj4OPT zS8EOFLaXpx0S22RJc-GFTxRg0+Dgt9(hNNp-;x5L0opMabQ_*YnkY)GAOF1*hkj*$ zjV!v16=zSR=Z-SaD5Q66l%&1AR0P^DYkV<Z%l7JG@WX?W`>@(EQ9WfD|6Q2_%y>t~ zIh<+Tw)Vu^-`eiI=Ku<wHSJQYwJgJ0@z1`-yZBeuLj%#SU~qB~tHW88&AN%pPMW|` zX$m6ws`OUS^m7oivR39_7x0<A{|GBZTGc<}S0Xtk)VLtdB@z`~=COcc2Tv?nte9nT zdbQ)TYmf=IZrV;aVB0=EoJUY{*<XiIm<*vX2)~EUc?m{@Gxem-V$*uN$S$AI!ui_l zMZTl7ypF;dIVcKec+s%3uzdsCRCcjn`E*e|imI-!QA~GrFFrb2_JcSOdwJn^S%4cw zo@ndw4_E@5-%ZqAc{e@yNVbG0EJfu{(q>F|9HwqTqtA|BZ&)}h%OblV+e@!C9u!TR zzj&9v`@9S@FRywxE@gDe{1N)-8g~0Bv#f)Uu3=ZKJVmQL=bafp1hIzpz@N;zKlV4< z+cGR$IY_vcFnpM~#10nZxeM&*IFHK=cT7&<>OcjiaWqhn-+@ID+2trr)@yi)U&V13 zn4N0yn}kt^C`bI>jgRJ)Z?tRwbY7Qm!pMkMfX$;rOln0Nc4gG~LlW9E3@_0tZl9v^ z5l~yc`zsRs&s}{(y!hS1x_TPl2!@h>zIW}Ngh@{u5yw86oXx{D=1WK}UX0V{<*tHW z4zeATfBdZspLgQQf6IL)@+%90SqOp_D2Z?MBhH?P!g*pN3R>D<OAWqG!%v(`E@0t& zrE}vW8r?zRoMe&nNgjIDgHcl6b}NUpD+hqfjAQgQ`=19P|CdoX+ui{)xR73@E%g=W z&gt&)5-^wh2Ni$rh|&nkG1R$_u*EotI47Bh{hR;m->?{dg88LJcysOV{@wqo-E+^q z%z2%|YD6T>7CouFR4)_q0)*wZv4Ny98!VSkz6Q{j#Ol7k>_HUURk-cTrEpdk6V|{O z>HK^;2841)aUFca<CF<hJ}MJ99($Qb@dV^4>bopkNRnJGPB<@9;d~K!P&vj!>h|o} zlRRSd1TFS+*3hA4ifi&#jxcNvi|@!HwmJD$9csKAWFZ4@oW$WUVRnLk@k?K9pZE`- zXiuZ$f9u<xY~S@=--%n6+o%(0vYQe&*z3{NKNETbullgJU4e!+$K4C?DA)e^pZ`Vs zjbHyTctXF0tTj4}@e*>i%I6~}p*2>pe`tiMGTHg52lBn<kyp0|UVU#{zj-bBa8fdt z^}h;^lpS@wdG74F9MY{Ex{F<Ex1w)wXSO@e)_T6eS|)$MJH?`h2UxmjKw%;z__2+| zrQ~26t1Gh4Mt@YbPPu)%-gp*ItKX7SwL95nOmhdZIzijlGSt)b*6kK=eFGQ?`tjc4 z!sCO%fEYJRQcedla9LKdPQaxN8GFb>c~c__WnJ|t_J`;%SnN;-m3b4wnsU(yI-ODa z)B-!NKKUO$iDBX~c13P$-~HX+1#b{;6x)n-Q~1x;6$w>P+|1Rtwm5zHWzZ`GzdYLC z=-<J?hd=z`>p%J99}GjYL7a%#DeQ#aHJB70{O#ql8p&0Jv22}?2=ylv#iotd4N^At zD=C~kcxReMT}5kc<Pg2b@4mCGXLW2IWs?)0Rrq9DIjRB?ix<M^4G4U65H35b+vBx- zasaOjg(FrpT6t-a<itpyuDyk$$|4n23kZL9qF%Y?)=|rop{q=|cGU@?TRLhBiyh40 zb`JB<@=KU9X_Kn?W(N@_%eHgbIl?T%&`QV?#vXq%yZA8!9#N`bslq_K+p%TDUgFSI zchear&V6^XYzNZf);6<D^Gw-&IapN)N7~P311!Ir-ZE4;+glX0%(qvx*^V+6PwO0J zz{=#1iS!8NkAdG|Ru4VwPhoHn#-?y)=Hk<Q%-i~y#{y+tCu}7hQ+FsAVQiCZ<+w0~ zU|@QL_{D3wba1tbZFA%ec7eI_(3(hBF4OpQeE*OBWc!hy`A6*}?e(;lZcGS=pq&x6 zH?9IU;kQhEAGz3IU3-Q(%T`Ud#>(JxNDOUy__;$YOkALT49^S%3a_@g@b|unBJcu{ zN+o@|`CZ@84qW^9-@!`a2DYYLzzPjtS_lVPJWC6<y?wz;VL^8@%-7qKkG(kx=U@KE z|5N+uhd<Kxu`(Nlv+Y8?7f{HXR@l8&c=}YJc9CRy600lfH%~b#mRHbURwFcx<NwNS z&)@ky-_zdto$qNw{62K#NIS@V`~CxM*KNC9>p`*1#8|5u1z_r;pk-Yh#PzM`mhTDD zYUvwVg>Hh!43xGhhd-cjKKwkE$S97aEeC!Tzgd7{BIY)+OIU|Uw@%K<2<561j}l4% zg8^MZlLH#5pMKW{$j8yb_wxu}7jc`i$b?m&m}3Y^(xS>~l^QF6dk*+UV~OdAFYY8~ zt;$zMfYT?J^|NiQhcpc(hL&w#aqJ+c<-LQk1DW{k7tH)_y<GK`{>6d)Tl%(-dzsJJ zx4oe)+`bnJI()pt2le5MxJ;Qf$;!YfaL`b3DJFVo!Bor*4xk9Rq;K)^4XgFe*aXXO z)HMgZ1oy^;G91yE081+?n3!vQH$8=qQG}xTEBJBVh)WOrvks_?wmc6^GKshKrjHG< zrR3TQcq@~rsq-jFu4&zhuk1C@D%*P}I0$PD>*itdr+1SN8QFj3FSL(XzA=$5p#<(? zVYw~Giz2~SUJ2>)AieaRESKYvU(#1(Vf8X?()sL!;rb>lPFCc{f@Ulg3-Sw};;HUZ zx|Xsx@n}201w!()WD6oF{nfVRznNNi>YVsVlT>0PWiBh66I^+SBS@^;smsQ;kHVR! z<Sh^3wP0kNiIOkljW{#+nymH{Qt7T-W|*e#g4Z&+O_h4F1_OVHuX*@^mS!rxrI*kF zttnAlrN3N3!Mv7<%sB3KuEBe+aLW5t6wW(1v{E0v&QDfi39aBefWL5QPaZJ{;boi! z04GK&Bj@O2qhk}e<JbfL)ja{@V_`ObZEq`{EypUxm;kzHCEw7(Ss%_Se^n6JPwitQ zpl-AUV|^49)X#4U)LI^Bv8#e@|J^8@v3iSQCg}>VruR;t<*gLX*KlcZjuXwlhT?P! zzVUaWAk*5X7Sb$NGV6CONo(o1q}L$m)X5Wp+4vsN<H3E#$z)$zvVDz9{Q(}>>4UZ% zbx^Q9cJx>*!uMl+q{3UJY(TcUUi}ZB+_tOjya-=%LDT~i-F~};MS^uq5(YA95<l=X zP%Qi^sRTl}#hVMpT1Fo^awvlJuHCz19le@-yri4r&HSJ+%S+!O+{^Jm%Wik3I4*C+ z+G?0_hDJ_YVN81^t+ecNGNJI%E9_XBWef1h6UR{wt->k<1syQUH#4?HBP6w3Pid8u z-Hwc_x(i~wUtn?fekMb2+PfPIXZSy9lYgKqc*BdtSBFQxiv;ua)v7SxXvgs5JcTCl z%q7NF@x<q{!jX?l*T{ks(7rQA4iLP|VS`b4&~_fY=$I#MI02ahr}BNRALnLXs&H1h zwurS*4x6KV`9b)Qb(Egz1I3?sw~rc!@}=kH@ZiIKQxz~>Rm<8{z5QnUrSXxId?$8Y z5(K$Q0~E^Bd}yEW7d|B-e1rC?^u{;6dHYdh^5nlfDL)fZ?e16a{*r60Vu!@q^;=jF zxwSq1<YVoQeb5>^ZtSn&y}*?GfhlQeGhHKGM**~Oc@lR8rx}wjfd|Irz|cbxU{h3N zSl<E~`6Zq>EE?+JDXQWx-yIJsnu*LyD4=`bsBcwg6<X5Z0@hA5U7Ibqcqrcl;x)`U zwroV<%p7H8ViUY$edN~FDx8r!qli={piWj$g|jIwPdG9*KtuAiD_F^2o4-IfGMEZy zWQ9^VyBN+66!=ChC{<sv->7i5uPJ+!(zEcA{+Dw2!}lA%tFHYgs6DTK7yn|R@Zo#i zX_xNZK<Ux2KD=JUweiKj<D~<h?>=}!tLe+iaZyU#P&k*8vD!`i+kTPBcu(5o7s&Fh zhcRP-^E>b|G`a>E8{8vnx|?i_-8Ig6##!jk?n-b~3j2=F*dEqN0D(IFjK1sdCFD^J z95UBI#+z|ILK|J4Jjd>@bLsOgE@|m348kb>f|U*_UG{`I-gK15(|51%7{(0Kc`*AR zd?szcSQ-my;@F-EgRjaPO(WI~i?B!D;y!fLwFbF$JkN59{%sTcd9Ku#pXOtLq-i|! z;wo(L*Z<th3g^VAJd-X_x=4QO+Aa7rA^)Wle@hSbw3Pam!n!|vO<{=x-Goj^Cx3H? zm*I{f%1c(mc3I$-4?7;X>qLcgxiBIO1B&b5(}k{H;VcYOxIJ>dHP6D1u8xFRnR#mR zWaN)U4((Lo>>*&c?c}g+<N$Gfv%+~o3+K0d$IamX|9_`WUcn)_u%E}UiZJIYmyxNo zrqq3?<BhV`#*G`h0|eKYGB^@evvOYetH1is+w)l7nvdiCd*1V%?ZF2g%Gp*L=`FEX zTr{QPtrXdkRoa$3mM?{$<Z6iTMl#md#Wcc8FQbs8WG8w@aH;V_WkHkBmerm$_IJF( z59DwBn{P9>uX$&#W#8w5JOYw*qD-X>I>~N1&xla(uxHQi%=M)!(~3XkYpY?O%8n7b zmbt0Uan5J{%5=gXoXcPN7ehPx%-Pc=uYUdupKrhQTfc=u_H6sU@B7~N?(cXvmcpBo z+0AI`<q(Rff?k4C3ITTE5=QkDS~ow7(cAC+-pAXAf8!&8=~ig+Ru)1wZNz;VvbA~x z>nmKIKUIt1&dpo9{f@ouj=T2Z%8_|2I-IQ-1^8V9vopBo_`^T^e~{y5vKXW6_@4K? zCvHoe<0?ZAqgzv+)Y94czCN~{58D?;m<y|K(u09I6x%L+5;~LC$_TD_Y3eJ4H??Kv z3d><#43ICJ<|Bg4vv22Nlp}f^Q2Fb4SGp{DW2Lp-d!Av4`MaPex1=h;$ISG#;7EOj z%6oTWY7sud7GBdkCYguEtfx+%ZifyXiqGjS;B6}hdV65!1apd!kyXq$rsBI>t8jOR zKl=Ei9L#x7=vomH^rL5B3|Ajv`8}Kh=hgkLANALuR|vj2%HR0+;NT-4`N;Jj|B)XB zaWFGFYj2HfBUMA!U@JDlG@t^X#+C5A9As4B$Veq#2}z<ceKA*vLm?OH=q;R`qD(QM zuSED(;r!$S_qDaOrY9K31p`X1s~t1F!itm=x)nAs<(t0>#v)pjE-DjYKDx{hj$%40 z22nuSVM*ial5Pg9pA5#qG72{)bjDXXt<TE^n6q#z447W#AgMS}RIw)9#`pH>J5H4e z^>J0F%4?Tbbx1>m#Y+WWVCWc~`0wjh!et2)PH_A!0}w8MQ)m>p3VoLEL`ubR!Bp)t z#B941A#^kuJZT+>EJJ0toyN;HbmDIQDlO8s#2rC-IEu9!nNWMIUsdKaIMqZC5U9pD zd8Niafukm9HQ^2pQE097KoBOnTHQ_~++AkHa|)%`JapoOYx*j%Gtm?+!WSR6!V0aJ z-#U~T7bZDm>aP3S2S4=Rw_OiD*gp5QueP%=l-0D?2DS>LPKzRT3c*p__l#Lu^!FSJ zXD8U=LxIpk3>>T!lEp2e@v@-rK$Qg`Wkg*706+jqL_t&lMon>&t-vrswJ|bl;ZmG) zdxZjvR#0y5kv1H_%wOEfsKvS4nPjwUCx+W&Z+v~bj6cs``o(|TKK}3iUE77VVU&nA z1ofw-l3rZePB$2I(b?#A7a~x=K)=&&&x8hNDc{37T!h$l`~LQmKlR_WN8b3x_RNvP zvATZaqmRK5g;{HM;!#FV-`3qSE`v9P9k(axpIf|ns8V23=%Wt^Q~ES`nCGxa2OgEO z`jR$n=#n~wu2H%;sOL~0U{vAkYQFfe&t2j0I<0(SwQM`Ea56wVPimiaKzQ+mcJ752 zv#79<iG|xum#AaW6fgtNHMXm(R0gmJJRWEjg){wG%XHgN_deD!0+DT>vgtouwyoh= z6{l=~3(i%>o5q35@+>2Y6#9(mz3gXx8-Cks+rqxx&@=hLcQ$P<g|n^+dc~-UKie|@ zuzYq-p%wJtN)#cN@m<Z9Z@1>Ea9+2bt)!H<5*&j{tHv#NwOsl+;reNIvOaYQ8o+W- zWy<DTHsUT|4FfPZrk>2*Ghv}vQqebAL|ef@g4eKco?+4F!fE`GE?O^?Xd4kM5X48O z*q*n9+amb1>K)rEgiKxS^TH!#*DXJB8c}#NuK$8V{u<f%UKL*P%(61|VIIIMkbQzA zGI5t%o|SJ(puJSIdHFjK0AH_kwiJ1)ik?g`Z71G^FO#D#O%I0fl#ohpf<t=c?_Rj6 z2?F7O)LSx}cj6j33Xdw&$y2@wgXJ@>WdfCatNm<^z{WTEOv)i{;gql7q7-vH>9c+j zeD4%Td3GbJRp0m^4zgHAA90LwVXRQ(;-u1%LJ?sooENd+T#HMHas0qvp>Hf*_g;<F zE{Do-7)tpha}4l?4@!T)<Zc$9l$^fq1Zj@NMi*JO@4OWy0Ll{jjLU`6dbKCelU{Zy z&$-3|sJo!#8JF0?rw`{_w(sB@-}z(z2=Zx^;Js@*aTA3zX^z4ZY}W%=^0>87UQ*>z zP1A`Lvaz44Y_=^`cIc+(YhQgDrP$WC18ZO1L)gzulRiy6`IGcx9#^_HDTVXNOm5s2 zqDu|k7)75?In^elARpx#%af;ot;iXUGbfH8&!IQ&K-rA4S|Qa|v%2z`lxTz6*~6!m zt*rBWd;ZYj@Y4w<Ra@}ktgk(?uDS+KB)2ru@-qPWP!@7)_>m)rp_eO6PVPWS!%m-( znmh=2&yUR^!0<Pe2rN$Mw2(n7gP+TlZR?KhQPR7pXPjy)T1NV#zAk+GwCpSMoJD}o z|D!KH&m!bVPD5YCLP!?sh#-FLHzjWhhZburaS?V63+Gu5m!87M<*OK9-?(pY=TgJ^ zB{69&g{ynyH3VdUH;4r;qwzq|e1!$UYwZZGi<WF4E@?S_QpGp-2$uiS@Cb_M1s3oY zQF2^BY3>-O#a!yhnAq=lnr4xC=JGjU*P4#84@I*I=Q$M}(7AZAfA<zw)z3=~Qx>zi zr8VoEg);F7z~NDLaO)vGlE-p&c@cW^q5#6}`7UmflOOz^*TiCB()6W#rj+2KtX-wA zj;E(gWx*;lWtqJ%j8(DLC2NUJ{%1L&S~&B<h%-96C5HqaU=ir`uY0Jiht3@LmED9t zV`XYvNmL4YP~Z}iy2~8ml>-=24%uw>3}0MuwYaWgl-J>b&poX93LL4wKe$4dNl&c4 zGU6ofpp>WZWNhGF`Dqb_v%Gqa-9oeSPRd}EW_;Gz0);a^GdHY9;mo0dqvM-ccv;6g z)_E+z#9~cal8zLJg_-A|VWOxj?;3KKW8ETtWUq7Zv$D_N^*Q8LWP2hGAp~kPA#U8w zAYZUgJLf42XO)rix~?BsR~sVu;$fWw2O;F=zm%VNz?LUC6}^6~m!vjG8KJ`cZvE?u ztj}xD(@mGQAV%aHkd-j-*z@ePIdrEySS~f_57IJmOzZd;T8BP^Z1U`_&X@BFWa6*# z6>tyUR0bCoT{vm1Vjp%48bMhxi2UdLK{;?G<Dg1ixvRdpEmtFy?5GnqWJJ#rkvF=a zw}`A)^9I74(^4KuXi6Kg#y;`XbpeC?m8ZRs*0BW&HtE3kw53XBzDB0>-Eio`vBGyV zvRw&tyzdpxMN9U9G*}j50EtU}W&T~8Qcm#!p^(r6dOZVAMK?v@@1K<!zxZxl6P^N+ zf$^6s>nk`+IkrcB+wO)}``h*g<ac7^r@7=;MuzY$;y6z9`6R5MtNbe+u_(S4+>J8L zF4h@z0M1oa&@M0lUxOC(-#pCD9p|kY5?w}yb&fO5!JP7K^Be+Sm(LzeTVKOn-~$h# za7MXw>yBG*QaC$4Rhy`Edg6(1zQWl$6+bTPQAkxX0nQq)9dotZtvT$KC{nkgC{$)} z{M7JD{K^|fMpm?6`IUd!p8o1rsFzB-Ywh)~e?xotVb1wsAwRx>Q8;Ho9#WZ~gQJCi zq)Bf4sfO-a$zWTTz|dGe8u$$_ny8{m3&!%97sB}lsFbVxNO(vD9PqTx;RpWU>idE) zdR0BEe52SmOIA`}u>hVp#Pba9#u$5*1NZFNleUbalk%mR%yj`m9Zr<{<YQjKr8|ZB zc@`Pf!4N3ER5U8*x|?}^=6XAH@K`&}qWRNL|5f|cr#^*SiWBW;e)gwP+`bDsn_;fk z8I(D6c2|vA{8&a^hYS$oKXo+LRX1b8^wHn>{kZD*%9sC&1F?^__rCXi?R&oGd+`yy zKgNwJPBmup@IdRUYYgSd)3{n&$!>6#xEZ(51CZ}_&H=JMQy7FPXMf@IUu?TD26@fH z54YF6_7SYI@2Bp#*x>NY3pwwKxgG`qE1@m<qlTE$%UTT1Hly%%?(FzhI-zP;d3t}# z=auQ?Zy^^d?X%jl!ouHr<nZkEL$<GY*Pu%|R~>|x;T}BbA(-k<q<gQP27K>nB{BkZ z<P=hW;r5+po_PirD2Jj<e){RJw!iat-ixu_t|;DZ33VEtA@kL*ek}@l^%?v2?&JKc zN800$J&r6hjQf|f?aN>OeEZn%ew6cR_O`b^`PTNvH?uRH3@%>=PAa+D11F_v^31*5 z-u%AlU3mM;;BWA$kMcMA+1GuA7S131z>k4I1}|Dxg{+-hp*c*Fu)dLNP^1&nK_wU! zMhd_RMXu1Rn9^F<$ypkLR{BN?XAclm;XD8%-GEiq<M-be1*Y6c7_K3B4Y2y65>J;J zTKs6qB~i+NB*<PFEEBS`>At{i^KKszX5*<m(=u6@XH{<T&p}Iu<fOBddRR=8E&?5^ zrxB(|uh8OT%F4*NbmOteBqLVOd{;>=lT?6pa0`CqvLwhVKXq{e>LpIyR%Lu)5_Y<1 z;1$<emRnA?&@gz~`K^QBtgHC7o-!b?lPQAV?KE1I#~-bnoG^vuF_?)1TyV+LaFwEc zofUeVuv>o_hnDIp;bcB4q*sHp350BY7Xw9`fU$dex4w66^I_UzEtV{$IClYn!~4j~ z-~Hg=*6d7jC|hN}io#Xkd67KbN~DkGONfOo7}!=SO`|*lp9+mCYd6^bX!I6vz41LC z`0@6`KmAkfse=dGizknT{>BHeOr_ddW$AZPVOGm`xAI66UMo1rttM|Z@CvJwcxl+S z(>Hh&Cg9Tc5l7zQ)>S^ODpZ(@S1oaB63S!&8dU);?AO`KBL1ADh;uLVu$_I5FmZnf zze~ptKi~e3|K)#e|LJ2NN8!vwhJFx>AL8qJ<YulU9h=_#z1E_<k7YYFXnU$?GL1f; z6`oI=o{VqQSHJFc_`w@#uYJ=S+j|(ms0b^WWi=0QrLd))9e}L2u0SqwSbzr-dLW|8 z)_&opA7Daf<l}Y{4;CXCWwu(GN3k-E(%C^#-`E}!WPc59fZuD-Q`(oxIf+`tqE@#P z(&r-l;u?Ky1@Gf9d?%~t$m0~N_qx|vKgw2cxI5xt6e;p4X=D(gGmAvf%pC13qnB6M z=F*uXgzaJ9sdg?GA@(t0v7M!rv={wGH!8jpw4BBcX`eT)v~Ah_B-(F-Z+R68XSP?d zb=%z+Tejg3l<na;I1sp0UTZ-Imb-S9{+y^lcL>jyE-tVVOMjt^v565Zq&YZ{ekUIh z5c{2eVN2PmkWD3VtDz6)DF(kwmrz(=oNL>5Zb{iIJyZ}uK;cwe=o5VaA$wp6?4fYJ zy0WZ!&Y$FD>;;5uTp?_^1=mIMm)qdv85GZ0UD+0yS%C<V(Zj(jPyxGe36nI*lYhp^ zq{DYWl&=YDX1#{_+D)E_oPRV5X{2}KCb9|h+Z2ffo+@^Qkf1BqBI(oISu~Kw{7pJj zz@EaRq?44xQ=XLxZ(t?Yq_24L*t!BaIJ^<wf9X*|QD$kC`BU^_-fjt(H`KfQ+;Pgd zBE-pzW*_no>CbP#L|-fgdeI@|6~13eXO#=$0c=}NA%}dei_kj0S?8M+&a`>Hr)jj_ zP=&)d0xe!2z&AY>&g=2tJiciI%4hl$hY2ol0G(E-qtKuJl&kJ4Jh1*z1(eE`f=c)t zyBy=^SwwP6`KGPgpd%EK@)E~v#>p(&<SEarTcy_&lPVXtE~5<HdE1`04Mq1*=-q~= zhM@&(R(Bylem<MDM>(L?Hau|e-PsOnzf4No)H}2Z4u!=pw2R}{g|p|{vj~}6R5)Yd zoSjg>XS?@#6psbZz~Js1^92jpzN+<yGL8!84Q%HQ)0SpIi1<l9fn8cIrI38uLu*fS z0E?&5-+A}lv2YegOWE!VKO#?ge?RF5%jCsPT|98``NK!xhgX;&<2#x*bJvXif>pG5 zMnK6c9W6l@!XfTeILp%yA37Ag-iK^uovoA;2&r5?5&Vj4>*7al<q)lhJfLwH5?Tvg zY-60#g#gH^CP_@=a{;S#FU)2!$719pKL3v#elBjRZrz1NIb}Pkv&+cy?W<bRdxbYE zw?H359H=xod6{wKLVEz~n@6zrnZUoIR@Pni$s-AYzu*RhfKuh>8+h=tEvK1mvo_M6 zJI=wA7!!m~&}QOEe(o4Jh+Bx2ERK)4cs;t7@r8pXXPCTkV!8N^9L1QT{3X0I)A&3@ z>Fl=cIo=nU^f~^{vt@gMNtAusHkPJ}KJ2r!4`Ah_dY`~&Hx4{}D7c_kc!Ckb8-PFY z{39>(!9OkijFY^5a_776as<Bvg9>q(Mf!%#O#_Llpob(;D5Csy)@DhD_ljj4m{-1C zs)|e6<lrKQ<KhSkj=S3(2kt<Tb1&9F8zhm))}aY9tg^|gE7bAt%IwAX!Ja;k<zW=` z00&_9+0-R9t=bB8ERxNOpxz=gUkM9behCfm@EP2glFRxhE&1?s5xUWG(nX~O-skk= z$Op(aWs9Ngwu4^fBNJHDj!$41fKkja{+oxfv|WiDG=%?GUAX0n0+Bb$4m|-x;GzuM zy%f&K)f^ajZSEZ3kR9X0S$P0?1D>!7dENf3+^_uHKcjFaKVgyHty9|ZMwP4X*4y%z z>z~>ujUNo}7fl1Re~iEU!?x-Im&0y;anzS4>b71zA*GJ;6YI;<`BM&x1hKj@@ON(k zEpP4nU_=7Stc3tu2N;YSTIEC9&hls@0ZrwglXUnFa_|MxyKh#=+qh<DTAy7zn73hp zF@@A`WcP|wFpwfR&R_GX%zO#{g*)<0S5D+LV*!Wbi7@!AHsk3Sha718MJWc%zB?`_ zE$QS%&NrpMd~<A}9KnZRz=bbf7HWF_a)$>HD>(JD2~5Ygz{$_hjmh}XeI{>9GB-o& zOUf&R6^;{Gx}Z&i%K{>Ons_%q%|Y2GVdm%e<m?x2>BTU4qInsgryuLPk-HQC?xFFX zg`-=Dsc8(AxaV2S)D`EFV<h22BWqFqFh64~S-{2D<xA|WM1GycfI@z3c_X;6I)D67 z%2e)t;8hQ?fV4jTY=_w$D{iv5M4$8Bol{T#mr^(@?*Ws28Wxh;%6kaPLcZhf1^gX5 zerxsVxW5tEOzThQl;Tj{Fg8Aj8;0L%U-;tZkS&x=hT5Lpd)ph|_@?&IL$9*iNcvo9 zbQF@EHD>+vL$3UkNOIM){`%!*k-Jzge}oRZ?q^!du3dm#PDGHlrPZ`G!Qvo4x-!JO zmk&RMx9~fBg$#Y#pL}ZE<W9L$?7&i{&=TA;D%@dP`i&}2C1hxj41KD+oJSB4hvVoi z+(qTwR(uX4=(xx&{jNa&vxuDVS6_a*eesK5Y+w4zFQLRdh&zf~@ss`I?a8-30&Ss` zc8wHx?e0}mEAY~H>(qy&e=}#celDC?pI`o^UvB^Y-~SdyR<rHIiIeRY|Hof!?|=Uf zM=|P7>gwNxQ*#opaWSL*igD91dI2|x8ob$?9p~K9KZCyH6v}D)h37lzK2{vq-_(1} zv%sqiu^PRHE?HJXYwn_(V3+nN{mFA&oD28uV%hy=oxQ!v|GGTWur5$Yk~YE1-&Ua@ z7r)|2#eVPrtQwP)RWdpR^a!?xZc^5=+j_L~v928Dd`Ufu{L{4Vq#FT8Pk;IO_UTW5 ziaxV|Rq_|IqcFR`!O=V4@y=L`%Nw#2o4UF4TEE#U?^Wn)xVnG;f%d-ly)T9qpZV;k z+EbtV4Cl*iZtwWEceLAY-v=yf*^SB0Z|3=44mb0>>l5Aggi^2iYJ{8K>t_Ob44KE@ zwkvc)rB`U-{9`}zfp2>K!z3I?B|eB`L_*<~kOvv;JbdgDR+`sg0^9M?`^bJyjkQIv zIFPxbR>{GEHsXK-narB>HfG<lGK{k7;xGafMutZ@tAY@!Tvj+zriAP;m(_HIdM?wN zCTaam2i1?1aaE?PjI$o*Wj!Q#^Dtb7A#Aan<-2h*(ME_61{Il3l)a3r0<VWjC1URm z!*7;ny%awBe2p7Hjk+7=?d60p$_h$1jtVgcCza?9<SGWeCcv-hOJQ05jAb~kT-kv~ zsEdcOsXQQIR+da_=Qm7+^Ed;tLenY)V*T#vkF69W;L5gOg6O3i1%)l~V;(+5>`It7 zV|*0HZi%uE(t`LAcb6DEE|G-{SYO)n<_{t=!7ytCun{KiSD=X#XD_u!-~HX~zxjoq zZ)dTHevv~wR5GtdX)=tvfZA$<UnlBjn~5WZ4u5-4K&^Blz<_HRtOrKe{wfkxZubi3 zFg4mbRxqS3r7UetSP4qfgM*ceE!N3NJoSZcyaIODR?>`Z>vy*X@7}qyJ<m2870!S0 z=|5?=au5mtLU-T}yj`Ik_#gN!OL}_g<-|NBo97}h2%qH`e*sIb$;nFyVp^4tw)<cG z>h`Yh{I2%uH@psi&-esGfFT+g)MAm!e_frZ965(lMc=0D*R2ojTfj6*dlyNT-K|JZ zD4Mh|(fx^+7L`_7i}7Q}j<u5r0$MP-rTYTDQ^kLOAP$^>!xOQl#^PK{c2_(-OiX37 z^ki)%s{tnKDx6OrI}YE#(j4LP3ImFh84vt&P}Lijf|v;=S>3cDa!?_0dWHYZgQhg$ zVvepe>^H*YW!v~$USgbtK@Sd0(yK~qY1Ty;`%>`(rrms-`1aSgt9RYjE>6;)P*!Za zO&@~}jPf}rtPYSW{S-9K+3-+!_{P*l{E?l*8Uyzh!}wm?yq%Th2pS4L#HL(GgSZM^ z&<4M+YvGLRi)mKbFI><EG>3xSwuNo)8_65wQI7hCl`OJE;cUT@4SArtqg`0xK8NCO znn=L7ef#>hdf{?gIeDs$g5x1*N?=!5o@t?vxYXdC;+g7rnHMlwFMk?O-1)SAz#;5{ zlQ3fW&-5LL$=7@csXWYw%ZZZZn!kVfm4C)ch;aE2xa^}UoaJjZ;i@=9so%nryYLt5 zV$zhqN%JtL6yaa4f~8z5^<^8zy_}Wl%(mi2nL$9{kmpdiZ55?5)e|kfk_HR_m&!i) zOO(#?s#0!>7lkSLlyoQG=*zJ_frhl<OZ<@ER#~=n@fa5#Ejwj;DlaNi7+zc;aSBsg z!f*HHJ-awGa7&w`kIlj_=(cffu?7q06<FQ}-&o}jun6oyToh6`GB@CwM@XAyd!I^U z7qNEix{ZESd@5E4#IwHPN#-W~K+N(?1xgj6y42Wm%MKLX_~Bns3%$m-{^CJpO=!=O zc~{Y=JA<<*jwQg`?${IlEj(KNi;M6<zL`&~1j&oq)7DElH1IHdce5@vc5(n7%2WBR zh1rU>q5XOp&%(g(74QW8C2Bq4ghrPd>zM!oXwpinHEEXSDGWHox3BKVxWEMREQ@d# zu_)Pp*8yC5P+!JU$0jLn2)qSP=>|n(B!xcMmBToE=-@$MyO!;e>(~Y?f0oXKTHa!v zrIFB^@(~q~7UaDu$+d=Y@#3z#@9JD)$bZ0<5Soz7N4?d%a*x{)pFez<#m6Bg=UBX; zs2^rLQPJJUwZ67(>ThkxNH}H@?k8C&RN=f9n%c8(cjS}ev%*T<sjpUl;wgQX`ic+v zmHxfYo<7?i+Pty7b~{#RV=R(WhYsApoIl_&I42j|A+^YpR~u4Dsp}kvyD08GcO3Uc zxFO0y5HN_R&<uIg+xU(DL>4!PC)UGfS0bBUZI^IC73*!va?5@3e-1<jzjIS4oC%v{ z8}~xSGZ)cOIAg_Hau+*%pr7D~^ud$u%pLufufQwcio7E(#f@?V@T+jX1{_x0Wad+s zzr`W-3(g7WDgIRn`n8mH?&$Ka{P;{93WPuVE_w=2jKAhhpi#a2lwA>BM0FCqVz=^; z-;A<gGT!cg;Nf=1{=IBDy^{%|a&K9@+uy@qNvncSc<pN|SQK5rI^2U7XD*&0PPbS= znNp^3Sbkl;_4w)PxC}gBlBZG3S0MXj#7$iY6PMzZPvUtVSQf#p3v(V0sG?c=VE)QP zTNqUUBX=S{%U{OV((lGqI5RQFhx2N-I;%i*u`LQ`i7@<!2k+imI1AHq+3;H1;p(!& znO%j~uyFREY@#Y(t8gy9U%bB`1HNA2EEa8#8`TZa0xl>%DLeFGPy&R@V0nzGyUY0f zJGs`U8zIY|^72xJv-yW6Nfi7to>|8m3TKUN+{K150R1})O{D1+&Y?@`F=(p(k^G<^ z;Yj|r8x0xW0&A_x@d&wAJ#5*6#rgpYcl{G+Bl0jm!$TCt_uEaEzY~v_uKJ+_-fv*T zT)W@A*gw3)tK*Mf#I@}fI^db{iKmAKhTr+!1n`{5NARFhI42WiV8^n`$7huwXnYS+ zQewsF$`+48=3mg;)q{sw3TNVxmmqQl4|&NK`kbk&ZiS=DBuf1*zv|1?MmOh?vV+%( zn0DyOsCF=RUDAk%4=?b^KY60n@~SrJegJsktd!0woG)EwSF8$WX-YbVXAh06LEcv3 z%pxlbv==!<&w1J0O$z5xjMmN_doFDcx}$K`!g&X-#a4fv!Wo$!L!@uIg>xzhHA33} z4$R7U{;u11=T**|9JenaFE~e538+gS4S_;8<Rg8lApO**{<QtcpMI(xK7259cXwjE z<t<ONH@)f2j7R82z=`?CGMaSKqNMkdE5EDlD%@5nx+uzdN$jutk$z7DmVpFx+r^L$ zLrc<T*T7le?Y`d(N6D*<uZ)%6&dY2=4fdRyM^}POVt??mOv9Z!S|JSuHInkXb2arW zy?f8d(4=u39zqA8;@$k!QABry{N-FtJSm%s^NZ&%wJ&_`i_lXUF+TIm*V-Tb@gHM( z{N3#x?|di9$z9cMJ*fg#Uc1V7!GU%8PuCHb=R|y%hNl0AU-*UgyC3~sU>=Jh;m`ft z&$S=;{vU{bqUIosl^9TIKquUy(!~+yuykC;C1i9&Z!Mhl+boXdC$_n_cv5#Fgc=&C zW0_+9H;d7rZMKHpNaJh9JEOYV(Y*>@r5tZ{miwkJR?NEk<WDGNxgoo@4-VvC#JTD6 zw{A^r>z*EN@EY4xU0u0KnL>H4j>|K_^kJ^++;Tw#WlF>RGp*yysbi<xUw!Fm4p#hH z7K-$<efTivRxvkOzkWk@C#{X^rJ*R9T}-kp%g|kkb9`~O6{DFqzxmDW&;IOB+t;4? zGWjpIH?SN1@y8zzKX5nxcHGM8SKUKBW%oe`&)}r1uVJ}fR{w<Y@s)zR6o2C%(t!1k zh4YVp;77md6_zn%azjaWwAFMv6(;(~QQ^FTmB(p_>>3l4Z6g!y;r;vDAOid%+h<6~ z0Y@+hnpJ^cg|pK*rzKja%5?33Dn?ZrN`#rX)2RA^v1YEEIOthP2{auRSak1TCzg@* zR-6h$DjcIY1U4;?{4Q06xaCM>Bm+}uwX^a_hb|$e;>qMyYT3C}cIw(eSnZrqvXV$5 zS0QEt$W&v=Oy;@~u`J=YF5=F-EYo+>SO*!76MUJdzx^%)6<#gN#h1+Y7FLL4z*_w( z5b38z24tmtPSBCzwPAF|cPoQW6#_D2^YYLnCoQXa_kcWlc`Tbve;HrQ0L!2_61Zzs z7K;z^=mn7>C#XvE)Jqx=AL7MTH@Cv*8saR%fh$l`Fx6S|)dFRKG>Rlzag88}xLNzq ziznO81NXKMeCQvwJr6z5PGe#8Jgyf8*g7<U^@(jNqY;NHNX3x~81bv$X)mqsyrm13 z%rtdYlWEk@iS_pupFYhi_$Ln;yloxpBA`>*Y&(VS$a|HXpUb>UxGv?t?Ot?srENxG zagoXNzxt>DtbO{EpXA`fjgE$(5nKZ+HAYCUL0X!YZf?F7ux_>eZd_Er-v;qIghjdo z3}P)lr_NKqm2EvfiXMTPzU^J_Y`gaEVJq2fZ4^a-ZIZ<o>Lso(VBsu7-w302022=5 zhzD_C9TX6+lE3sAOF7C^c``&_b)n`WmVAc0RaM{UXW9DW0>&C9Y5IqDoA<F7kGAvE zY#n2w?qP)&fm1bx3TOT1Ir&{bj+OP~nfCm_=i2nS3vB|Sa)`RP2qH~8slASXW;+8V zClKqRg~65ZEHaUo6LxWLd@uV)^{=v6_P2dA`O%N0X@7fLXZwJ0`u^1mI`&DwJK$~l z{>R$N2luu!$Cj`lT+_Di*@3S?6wd0hu4%n!-z6^wFjyG)Bn&PlC%ei-dsd6jv*+0^ z$Rf?~y0&%K4&Z^$aEKq;h6stSqLvSAGLQ~QcMXN}?CeE+)3RlsvTxb7nQiYIX+I`5 zl;E)J!HjaA0sNyz$Vc(Ef^_<DzI17-okv*>y4p_sk*!|5+*VvX-NxC@J_KG#AUUP| zv%o||{cJlqPPp`+Isg+ONhc5j&*GC23}^%X13@Qr8kM-c;A}=wM0Uyfoc59CGs#Rk zTh~iEBqxjEu6}4A1drUdjWitPRTs~==|8}h{P?X97pve*j)`w1+Q;^+*nt+>;Ys^e zZS9Bh0?Xy@KuTEGS2MXv^_@^xIp*zHktgrr3osmad}J#<@uNH@4@(yYU0Q^{%k#M@ zIAsb-U%vc@U=p|(N?H7{zq@lle&;X4qr{T_vS0(^Ihc28WPRIy=l-_g)*V=WPNO(u zayEON14Z_>4V$q}TxH*`KJOSO50VsJY_l;H{AQt@OJ~mG(&!8mzSV8-f!pCbjKKnh zaxa1|01KD(i~Ad3cC1oScM)avIh2Z<wrtD6PjUOv^^;!V?8G(ov?9QuVy~=rFQpG` z1%54?;>V5p6_2*l@n1OUGy45?N1ltMmr(p3J$xkYFt#ByjxecocZfL7Se5dC8Mvjd z^l@NjV2Z-o?XDAyk6K-5<?MKBb)~t`nB{V3QIh_r)v|}7USMnEIjnJ}rY^O8cisVx zH)Y%*sgW}&6vt^pGsq>4vH;5j=-@NYSS75ncBXu-l*Nd;4i5pfO)Oa25O({4Wlu4N zpX1Oz4?9#o+Q(wPO7;N}LSeR5(R|UBwBjXyj0Fga{Ue9;amR`0(8UI<h=x}yXhUCB zBu~q${wL3rzHR#%#&H(_Uwq*ZmNo0z-rM(Pe9Lxm>TG|ozBP%kOld_N*iUhP!XY{5 zP|`oVeQSHowjJeC!*=q!Fa}NVHGbzcklRP=G9IzIyZW0kkDr@wFP>)mW|WNeU6gBO z2sEG)dSRRXD6)y$^;aR2o?`ci3Uq1rn&S&&f;jfz={XLj@-VnLEcWM6BuZ!VD4geK zRYddd_fFAR{0Y=kap99k^dS0bk9O-njYt}P5ywTT&{<a>apq<HbMxIKj=z-|d;|q% zlsM$0OO0L*bMdfnY!2p6LhzpNS&b~3xNe^QvrLJkdl=VrewALeY+k#58w)r)+dIGG zZTJmc&sN;=^wILQD$gf=H5N&$twM7go_y)d(J1DZFgPhiaaHcdp@E=+vZM(zO8xqF zwapS_RfLa!bp`SSS}zhOSY8sDieJJu!}vA}j+cPR^AF00taZAE5eEGSau}n}IH{LL zS5ItdtH!s(D~54Vwy6yv%ebS%iLkPc{m+5TG0(9rK0pIw;W2$gr7QSYn!VHp7S7W) z?0Um8ZIJS6kr6orLy+VFt$Rj_eM;F?gOVsJEQ5SY@n1Ez{<-+D+@Iy&gcrU9ug8y1 z69`u&3t#8e9^lod>A&}7B|7<((M6XBeWJ!y+6jD%XI}VEU*Vg5CUX?$HHPs`<A%s? z769E=8rx02OIqKEo3<lP(QgNvurJp|`sgmpm6ki8eG<}L=I3`oBSjyFus&Aax^U?& zJs=r~)5^x5{qC6rEq|{F;@E%k5ZhCdbo_K-!f*0E4PDGHZOJ^*z8zUJ;njX|rDk5V zbroLur-g(ux7l~$G_<%A?o!?wM_`3FV5A)L>ggc(F&`ocPmN^D$$Avspdq5loBH-G z5G;VQyIcGxhoHE^ZO`DAFJ(w$nOwGe*Iu?wPh+7W^D~aHgFE||isva7xi2#wdQh>h zRWNxW0)2CYaU5Q4KfR1q=LP1ZDl6wX$W=FemNU+x>6xR4z_ka0uWI){_yEc*4*145 ztGWd7;@l=O1o@Opjdu&hH}4W%=4O2@&*>-uvTp0`f~sVyKEpZG84gdcd5AD`Ks?GW zciIZ0EiZi>!s_;u|M3&;bD#V3_<EMc-ul+JwkMx_8)G<g9~7~6C9P0P$6!M4ue*ed zTc(kV9uU6$ijliG^{6(Z64XiB4{h6ad`_-Zs>XZjXdfUR|8q%4@(9ON=WM-B#(9|U z#+AM-!+6fcd>Y=*$t=Y<=Bd$??dY!8v9WRRRz8T8^DI(pXmM<O`Ly|EUe34Zkw|O) z&piE1`-9*6gZ8>dUKbaW2M-=>pZLTl+6RB)C)$BK4<L`!L3=bs)q}smTvx9Oed*uy zMdG{5TRaU951^NsZ6Es3hvLI|=MLtL=p26R$9}B6>s{ZD+_eTesQIz;XWdg;iZWit zBzD&53S%`3yu;A9b6D$AyJJfqCL2Pvka=wkw4etq=sg@zrL%glO)ToKLq;3ryfpDD zt~D}o46{<Uk@)Jb`Yn(5R*7Bu6~Ft<cKAjYEH7*#^Z;S1&nlTqYk%E`;>HZ?{&UF8 z>T#rZEsNK(kfN?gzM65IvZXNT>CZm>nf9fpzLcHS`eN=~t>}Ve*Y4e!Z@8$WQu*^w zeIZZbTtGRmfu?1+XsmAHuDkATw)L5_?$BPK4aVEvy?Zl9kf+>+Va;QYJ(eAk8U=}> z5SCA_9!tH*Q=vEg6+buq{M+^_J$il16wX5qGEAtQ#;O(>KuI-&Aa-?bv29{9{NUbw zC=b~V&q}3)JU|D*rjZE(TiKD&<%bM=VZeTu=w(bY=3>rFOd%pC-TrnEE(;SXNo|uS zTtY>olUJ2$G9wwBxN!1mI+>178KI0#!P77Ybi-Ae_e{{0m>ZLVT7BvTPt*I|LDMo^ zVKklL61vJTC*vv@WOy<_zdPBLdKFkyKCArf;Zguo&>eQfLTDB)JCk{d3kMeSH~lWG zxm@X!$r!K>%T?W2cqtIB0M{BQ%V>JH0Wvo`mvxTCEqQ5OChmJH=LwX7;!7*4t0=SN zGQucqQP6>ZxsUI$0$^eq21XiTvwdXR!!Su#+Ahs=&;vX~p#*&e?TzILc`Ynz1rE)C z!_})sVJgIfPTuiD?``jT-w(ApEM;CidX%lL(`^{n9p-Brsr2{C;0L5K!Bx<mlZ^<C z#M3g^gA7$Z%TR|=7E71n+1qwk^bx-$+%ZY)CJiMl)hcW$!4#sY7ce9p`8nZ~4jc%q zr<aQRwX9^0(suv%|M{=mM?dnBwhl(>q;;HCGX<yx1O@TtWnR+5&DWyVKm>??+r;fL zX)Bno?~BqXG%%{`4U~to^d+qWw(s8E9(~)B_%FSU6IXY(d)Z>GFVj^MY@3Ik#m6Ol z`>MlO$DtXP+bdvuJc<`-#XhAn*LQF6XFZLtVn$kW((XZj_AxIN#p3ef<b}A|c=7ZJ zl&sTjJN{(<{Ij27kbgRD<l=+^{{$=eS2=O|?D13W=)ps65o_KZo1ka#XF0+!2)<<e z4niIV>R|4cb6tCAQ7ElBSUH#oyUH#t;^hMcue_rcbfg;xbL->f(|)!jKY|Vw`s~Z{ zjR;nJ7f0LP`_{JV;R6V?C~Ai%+BOu%Dx6mh(Kxs&Fs{PQRSxs3c0<XPi95W3N#`s| z{wW67=^0kq*&eu!?dNno;<y#M@CzBl>P=zE?S)!|y+q-Blm$C2oKZMC!HK&Q`RfX3 zkb(Uwt~BhA3idejK~X}VyKuRkpL84e^|oVsuW&xuMlR!0gZf6H1>EsrNID9P^y1_s z69gt8V2odUOZLzy`1iN}iZ*~3+RAVK0z~yM^36X9*gIeHs91z$qM3=5^xx&lGd!Ij z`(P$mv_X6{=Gj36yr%Lt!;0(Vn0M21TOB7*;<Srq?!+-nS`dcrTPHyz{jwllbRs;$ z>eB+vQ(jiq&E&;z>9cOW2Oj%1W0f%Yk3e%%pz^lg%g3cz5R^1dOe!tElON>(BNQu= zi4XmduD1kr!eHIXce}Je-(Ah=<!iULTTni3*m(=S^!3}WVvMn3&pwo)&<_e{+oa$r z+Lbes0eKM$5HlCCZazE7g2iMT9v^A9qrlDr-7+pM+x}5?6JEE_5x`h<AqViCJ9{Bz zZl(WU$Cqi>S{=eEhPd{x+#u9(N#3FYm0%`dw=w3ixJfzUC3WRRAvOzw)Ir5-cIChq zXV@-zmYoD^83Wg&JoT)Helb@8zUO1MlX<D69YATVHRkElr=q}JLs}119mndzs@4sz zy0(h{YY_(=_Mast2`aj^R+`6k*zSEO^*4cI7C)sE?<lBfXRSY$^W)9k6ppVi96kaJ zSfH~zWt80<Dx4ixywY{}nAY+M>@F;M>AK`Bt~@SYx{!(I-aBr`LVKLCp%w;`mUw{! zc<sr`F&3u6S%vR&&paEy@Y`<L1l~5lGo6$;E&`A=!tJ=H0;yym=pGoR8IL^}^2G5M zbI!q@eY;Ec0&a>*``K>NxmWc!@}*BWMxMr^{1o@2`**d6Ssc*HdQ~@0iz6@5oE9)c z{-^y6@<aMc7c&v%HY_Z|QjeWwp^k~o8T{WnUKmT*rGd)Ge(2=QgUN7@#3JH_X~tE? zWf#jGQ{*SgTJDNdj?(qX99GTBO><KmG&_rx9kPN-=tagjPp7}iIHD53x{9+X)hrzN z>BgmqgQtSQ<Qc$FsvzA}zXQf=X*6mA?xdU0JT;Sl_%FOD)h<3JqHSNxu!WN+KaID7 z@raN7moEZOav*QVoaHp6GY+>%mG4tB_iA=T>}n4_^eTLYK9GZQH6l=k4gaKE3$tuN z7Wa{<$b(vNU@d1pTsjL*I9r80z5MHaL*ZN@Su_*=?lxAhATwP*&iEd}qRhZR{3YJy zK`w;PbBpJB`qdnaS02r$z@zR*UV$M!a&__GK_>HqLo8^~UsjH6Z381adB;81=!Uim z3py3ftB?tlKXQ>?9x0!dmSSiD3^loS;hLRXw6Cs2RxX@_KOir{_g29u<oU`ZQLgcR zGyfNF8Y5IaOa3ZMRoy9q%f47(_}6#C>)VZRzVO2YNt8Tmfeg^Q_~Op1KfDoaLT=uM zR_lk(47dLf-y~5k+V0XEJV?H+yq6t@^oz&_gr%>C=4cmx8{a&Ln{VXnGjOE+e79^$ z?*NNHbibay3sYSH*5y$Vg{S&NeJ}WoO=*P`euP){8C#d`U3lyl!Br5sTnaB;nTB)s z$?IpejqTs>!gW4rTN*aV{31#UA}bR?OyT2kjYOQvqv*%BCSlsA7Hk}c2&2ICM{$(4 z6t;rB+M#gO*QI~T-;%ydQ{gvg#;m<kgfCsiv~c#-yJRf*6K$KaEcfQJX)Cdlg-a8N zN882xxQaLNi*G&dD;jXv5fexH=<)@aUg7M{6J23mW<1n&o@4xV@ab5za*#0%UTqy` zSY(}Kyps>l;u=nON8)Sk_)t6X!lBF$*R2_A_ua=?Q7H5_V>RqtQQY_(Wd7#dX`FHP zi6_3v3TNtPeI2<0l|G*?0k0QFWz;18H9*r9<O#+<=X2i5BDb&;b{$sP&O>Z2=Ro>; z{`ki~*8bBUell)1O#7C%Jkh=lHvo=b!z!F<28JKWDdjIW2zlg6+xM;HQ)p~=KjdS@ z`$m6>VywP>X|>R|b@BGHJIM#V9Jl&#m7tEJjvLB%*2(eJ+c~htfZocM@)GB7#`E32 z<YGZwlF^@(JIu##R#bT8scVqe^hq37tIqf7cQi3{qkG2EpIEN*y3NSHhn_p!KKrMi zX@B{}FSUR8Ge3*WGaT#LFMs9B_*Z@}icgF-Ft{qCBe7Lio?U&rpqD&E=OBKg=de5% zJ{LZmBm9GZ@Kfz$ANyFl^Ugal^jhEE{qA?SM<0DOK8%kZJ(}Hdx}~(;t%sL*6GtUW z;G&egJbP&y1|0I6aA}Bak;NHzv&Vlm0M4KfIE74j_S{+Y0y7wUFyCaSqcZ8}D7${i zTcy1+z$y$2`gSXRL9XE0wv&!~zU}x_yv6WfAuyVml+<6Q)AeW{*Y;A*^tbIhh$3p9 z6P|_b0&@i0*~|9ZgbO>}${0sCC@#pCj$^R>-bX*#{^&pcAwHWA2WMI;yK`N9?cTKq zeAJn4m#}93SO4<Y;^NL-q0)ig40i0?**0SIw{hbp6wY_i4hPs}Fxfu)pZ}!&!5{p7 zXihjsaP@ijJ$JYF|M2_U0}nokUTp~ZPs1|m1U;p@0Pk{*Urr0+gZt&dspQ{+Kem5v z>iR8HIImLB=oHRQVppPYo@H>j%GQPT2y^%D+Jz9tP)dhZ*?A42&qH3E&|KBZ1SWJH zZczf6%3+l+H30UEZh%g#vQOgIVpOIhQ<D+7^5uk0Vvo}5|0VCugFMTwI=@?4nU$Hf z@B6-XcU7-y?Gi{WHLVR0%z&6NV<f>~7#mH5Ct|{maSTD&4u>cFhbJa5GiDGNAtV?a zAV3Qel90qAdQ-Q0QFnEB?fYJtwPj^hmOr2Gc`vJ4U|QH3U^K7l<@>$&?z{KgbIv{Y z+;h)8muIH4@hS+#i1#)kpXD0_o_Y8?$_NN^uxg$fFsF^%<mn-79tr~ojb1efrh)pL ze9X%-6sG25{x&?zHl3%-3#^}w(KCVs5PcRSCWa-wzWFFdX+uP~>_X#k@3plYW3w@E zE?`JhNZAN2&zZh>W-tgI240{0jqe=f3Y*V_Be5)jtqe^X%Q0{Y6Ac+nfp1EwGXAqT zGYGuDg*lzbjVpM;q0$3u4A(R{m3s~D&QNJ|oPm+U!GI^GE@-T0`#@&3&!R+JMEDF5 zFHldsgQw56jqJqx)BpW{*H&y=*G@AVd>RkYVLMoGAfBA%GhR<xcN#f(bz=qUV+aYC zM$bZkWCKd-s<0S#b1gc54Vk?sd6ualfTb7I2@XnGf^Sgy6u`z=@}0QykT&8^FLTq{ zVW}{fhy1$$L;HG!;&1+6A88-?#b0EQ!xB_zHXkL&9445JmJS|v7V^ZcM=#jaw*fmi z_lnpHFHAs_s|;vInf0GL%;tZzn={~If;P02!TY-juQ3FDP9WGdKELU$-`(!GYgZ<J zvVo4qeef?H?ZB;<{Fy^Opl&IP=RItFCn7{{;@~c@3l_7RJ2R-r;s~0{7l<`XN21rW zn*tsoF#oDGtJ>YW?rdN9!_T!p`O25#5jY3>q@5EoWe%~B&qLcoC;{h=p1@E)t1Y8* z5H1e~bso}-2Anw7i-{p=TqZX~u&rru)^lG4rW6}vL=j2`IpD0Z^-25Zs=>}SEv>Ax z3aP(Ubh6@sj;B|6lsmS?H9z)_HvH-x?dblC(3u#{Yl(F_55B-?Y|P~Rqer59g-euD z8k~)ZUPgz@@b?%7=dp3x#V{c`Hm=9ejU4GboIyF|&~?)|WQD|V#td--PxlE78fQ*j zU?a6l7@OH#1cS2^Xjx@pFE|AsK~Gszn)wek1Op=;&KM0(@vVdL)x@11nH+C3$Bwrl zyibR)%;-It<)AWG3I@mURl*E}_S{peC>3_N;KRYC_x=-ZimL-=O+8YV$~Vw(U*2t9 zIxi$l4wPvdQ+|4Srv{`VnG<<pneiS2o<3bEz6DuYq&UlWDx&011L8I~$<=bq+J8w` zZ8^M6y1etf-=;zW9j?w@!6F<cu5`6zpMFb}@u41wHMkab(%`v%9i`6qW@}ltp%@?O zA2l{-`6E2pm)VJW(gHucpt9;@+?24uhw`y`h|d_88I1Y7H#`gTkQ?kQXToXo<~E=B zWMg>Uj*nx2yEw(lhpiRvVMwgia8_^D^47Bq$`u@N6c1-MK0S+Ear3<`go;q+N;x{E z(6Dgi2i8ECg!_8DeNW*%tHF8m*6nRIGGJf^?O6}1;IE?x6_$N`rt#mE5Xz6^gzIte zvT@@U22^EmE~5_o$8+QDMjoV0+fhwIYXm)h><oi8yme8qXQ=#wGx65<;qrt1o%G5| z803L)8!OONKl5FcL!Vk<E#$dyO_vY27e_n;T+D>f7nw5-jvPR`dTAwf)k`{F#-tHl znOLwKXzn8`ZNFka<PzbdhYkluV^8a$Y^WqX<zx+|itR;Q$KY$bln=qf808wu<04+R z#_8L*X%knMomQQc2Nqa-FP?AaWhfAh)p}R2U^CLyYgZ7uhzUez!YH+ebK2l6BLjoa zrPX=jH<xGkag33RDSLhN3;8q6#B$+d>mGcm7aD7vHlgwJ=)ptn7@<Jkwrg9v&q?z+ z8h|UUTv3KkxdWIv<Pr1EVYPf5+7x>Dn^$_Yo;c@n>#271tefp<EcavRU|+)3d}c6- zp70uThz~k%0S0RKpCDAorCQ!AuGD4RKrjYp`Vl?q;+0ODy2!>=*Xh5mT+-k?&Tl5p zI|qm8vhb*zsReL~HzHNMJ8c6RoTp_8asqm#B>-29Y_@-KAinv|-#p^C?S`{Z!gGG` zUWEHx3F?=A<MSJx!MWaxe`S*|$*dz193Eqk_4Pfa!gs868=gno-9fC-yW1UiY(vK} zM4KK%c=2}S$yf3rx#d)j%y4xU^gVxaFJXDk)1Bbx(UqC>rtK<Fuog^~E#T8>_|=n} zPg0*;`?4*XvafP_onSmMp{(>bysC#JKXVMyw+@k+a$+`W>TqXpj<L`Q7G&VS=yLXw z!Qf0tjaj1@oN0$KIHT)L8=Psg0_8t>Ne|_K4NTGbjbj{x^Vv4@3I=ET{~>haA;MnW zYH*hSBL8U{$|irSub0u#b}mLc;Dg!voqja;0V8FbEV%QN?p-Q<>-Wh|ymz^V9^MzW z^Ou)hDdZB$kZ;MF;tlaFkN8ZSTj$Q;?Boh^kcT<r{cKwP8PY_4i5!J4@qFevEui2| zUa3R}b`Rvst79D__mavq1*1S)PTup*Qn{(TgrWb<wRpekku)#ES=G8etiQ$C{O-~f z`K7&rnNwbX2QqFW(V%@P_mMBW*U)VLlRl__&NtKjc$dd?tZLp>T_W753rAO#RD(Y~ zEvmj%Z<Ccw6VN(+Utm`T9SaC@vdlYEi^t^a&<Gjf3C+Y$|1Y%T{?=>o2kk-=QBGbY z;p|}Vaqlx5q9;e`X-OEPy#{CHu#-NQk+<V`IBRfroPs$K0KqRhcg4om;7q@R-tXA! z$}I-xd2<Hak$o@5DQhX-oV#}Iq%U94mNM}i4|K5Mm>}Mv;N1!3Z@0lY?Tf0(Cz6&b zRNq6rW6103FP=1*>*Z{mV)r(ZZ`_>TaA1b}h;4)nG)8~wQ@@8{>{D6huf5@QuX}yG zoL8=JMFxFZp;PpR1|df7_|p@5`XPz=Eq8pY24}m?zCM!I9P)>}&Az|y+nSCC;WJ(s zXID>F^&`V!mh8jBoUyQ>3;aeyu=Wc*S9KQh&^DnHk;X_vjyO5!w;BeW1U8=WsZ)6I z@}0I9o$j=?WP+g^%i7M;4){*pOH_^HAy0VOc9@N+AA0b6+K#Q;5+3pZ_v&x&c*i^7 z4V{qCM_Gk09r`vM!1!Zd{Ffc-gctGb7{!xVgQ+3fR;^mre(vY~r}n8&ezL7!w~koB zTM38qM*7uzV>~@dOlO@Pv}Y~EIJ{=f>UjF9pNbQ4GsgZA>Uipl!3TZTBAf%3V?3WE zhPC{L2u9bx(Dv@z7o5;q1IKbUq+HC#%p=-DNNBsUo-@&ZMp!BBDo@A8J)W$qc$41! zA-{U`*XiFp$iMD|ZC{<q{!F|%)-K+#|Eqq@{kqPu+W8#L5{}iCABGw+j=3?Y)%R<R ziSe56hi476#~*&O{mL)>a_F`md&X;C^V+s`%U1B^UJ}@la8w%sCyog|^~q0zGbf?s zSwdzpVezW_U)}Dx`yTe8;2X<Xr2R&ZcfzT$TH*_z|3dp5E770d{TyM#wzYS^``zvJ zZ+Jc4)2qM@wG|iOxTkxEj$7K67~$ZB<^I30N2U1={%f1hNge-EgL9PLTM!`e{=XbG z_(jOT&;ux3C0xB{xRikk#6|GvIdmt6xOo{o6<K6h6&F1VZKRqr1~4kx>1EbfnCPr* zkis{DaB)*XjY2BFcK#ZjH5yqT8%#F&>&mbbwQL(hZ}fGB)^d8-R32?`8N_lmKZn-B zqw-`&<&l8|&pe#ro}{kArg7G#a@Hfg4BzTyJU~3(C@0*{Mu1w5OQPjUJC4b#HBeEw z3Y!gIp{nw!2Pt|naOhb&663D#%Aj@$fju{HjbfmS*A4g>q|Wo_&5yxPgOmnN@u7e* zu8jux%%~!?&CAZpYY7QG@_-8%th2bb!Fn}Tow!Y0Xs#LtH1N3u!r3yH6^{a=^iV(= zYst+IGf?B1UPJTnR2yW_Vt5U4Z>SZ$+s`3PjcKLf_YxjM`k|j>FgteXT6^!0{&@TQ zKk-xT0+ziaCk{g&mQaCrJ>iEClyZ>E_hwV}B0Rfh&Mq%pl|X4_{q*XM*E4D74X_*( zqo{F7<sa)L-KB^1><4(&x$&4h6x=RF8D&6k{U(iz1U?kp(n9>oAL3Em>PBKbuC41f zw2yuGm)nQ`k6$2k1PTOjI~%PyGIpdiBlEPG7(=0*ouc{3%eNjqUkIOVD?6_9tpZtI z<r845f%0iO;n%(KO>O7huL2%s6Y)@7wRTOGTW`PPwzi9z|C!K6ZwBch3=Xs{(Sf;} zDqV#Kt}#J0f+840H2FJNwmlCGW6oqSuM%OrtQgywiPrePd-v`r7zW@MFX!>DJa^Wm zrO<^mU;e@u+Iip`fxjofzj2ZVn9+3O!IOvBEqKq~cH!hHVv6H=Mmu)^8DeA@002M$ zNkl<ZJ9v!_UuA=4GsysYl0ok<ou}T;SMZ)1W)e%!66J{XwGAqVY-_?Gj`Y-)$Hl8S z^bn6KD$a^uLV@vHCs4${yrJ>g_Ai3gec)Yf__f>G!Iun2GP^BZjZ(0HnAfAqCd!g7 zD8?F`r7u|GFB4qgScU#FGp~l!ICGZ!S@YWJ%^Tn+U}LGROPl0lkQAAxLZ0@)y`d;3 z2}N@nug(2?#)!|ov@OFE(Ir+fI6I`Bya;hvK>;X8!ocr_gIAc{9yhGPNhYG8*UII@ zsHFW2T{zhW>0}2qIA2H65A4cq+kt}(dRX}0vkU_=se=f4fPp-kjcr1_@Mik2JSa{* zBa^|q?ZoE}l&g;1`^y{7URk+mNOoY#NxSrF+w`|>Ic+u1EuGVMoN2#gR(VJ-Gp<v^ z7_658Px4Co8vL4{72r{KC9gc<TX0f?f8j6L7dVvf9F}iPbK8sAc=gOieu39AJA-qV z#_z}({HXXk_~FWL?|oAPfIgLmO!B2VZhEB$vzzs$&f)+X*e)GB85V#fDO;FF7cOgy z*Bee_U7NjRVLOj;?A%!=A12!7ZMU)c-!crb$VPz?q8aux7*B-5Ne@n6T}F8wKSMYd z+O-?WZN@9W@**o|mYfq$%AfQje51T{wSb$78i)Bb2J4NRx8kY1nzmK7w2uibfmvQ~ zkZwOC&5W<7*X+^5M|g7sZ-d)2h=?Iu+F1tw?5AzZ{<ih_{u)Z=Il@cqM`>KTd?{WX ztB@PW#^6`a3(EnI&?`!JG)Z7!|AB!?yrWS3T`@6_l^-KaR2jEgx$6X`c&9O>JYk<C zB*7Kv>qdxXc*%hQeSsUu%|*wV#kVrPa>#b7vCawBYv9Z08T=p*#pN~ny;H~r(;54D z7<n{Ae>MQZG*k_-!J`J`-osk_#p@6_##oN2!P#=1TwCjE7UY)fUor{)5<}vEXV#_K zfpSHIvmVaRGby>Ut=qT;T+@dl|7#!$vaK=S$#1qn=`AXR;p_<}BcSgEynUBo++V+O zUD}E?3XCx<7Y=Nj*%v~CGI(_J*kgwd;pKd^J#^=7?Y^Ze;^C~pIk*PcTMf>ZSqIN$ zPR=}=em?y=KQ6M-iw5T-Y}9)CJj-~|7o23UU-u|}t2RE1`p#Rl6kUYPg~8R>MGTkf zG_-Z~ri2FrZ!XWAyjI@M()$9NIB9U6Abf%bXT6=TIH<mYw=**I8t*i=YHSJ4?PI|M zm;kHrudst$>#M<;hdKJXMjp^Ea+Q}jtIoC`k>F8sBTQ|sGPfC-ki6A-O%aJjfiVUl z!<Aot6T>0*rZ10Ya6?Fmkr5_USFCUMz3T3^bLY0Ud?{hFn2?o*4tgCVS|?BGA#DDe zNuJl(C*V4U*YhX$fd?i-NdpRaD`>((oAoBYy%Zci*I?t-#P)qTOiNo!I$jBLd05is zsnca>tL&XXpEhQ*Wr+tdhnPjiGHJ~ZPYofcofw~`JukuU3_P5%EVmmY%kgsV4bF>h z8k`+(AV&(8!e%~I_DLUM=8t<+SntR{yx#{fIHTp^C++}T{SsM#3{qwUU$jYM(5Jt2 zfX=)0IXoAaFF#TU?|oXl;IA0+dOS{l;(I~z8xLR9OHd(p1Fuhjy8GwDTaV(MqA~m` zjmWR$wsfyHZX1!;l?~RP1nIO)-^)$Mam6q225G9FM()9dW@KJvwDgDfa{OOBggg4U zA9z&q?x*#rgVK_R3DjSLBVQ$brR(caUr?HInWL!d_w`2ES2(ZxOsMco`Jqe=9o2I< zrCnB?<#*9&Ivr{A+sruCOT9|_oBsfjX9a(?;{t<k0y{7W7-!K1dQ8`~;0sR&dwj!D zf2+=!tgv{W3P<<eHdon7U+Cy*-%3OBUm)qqv|Z(??`&v3_cuR1DxZQq{Y4(|B56!_ z^CY7h%SC@EgYyLPHX$_}Gy07yYt;`}`C53wU`U^L9z(6NXafEJ8Zt(nnman!4({EZ zvHxnqG~Is39U1@XF{~%BxY1}`<F%O?CqMAOy94*P^AG5Y%z;Jd6KoRNBy8)2ADzOa zg3rYFi!Z(yW30M~_f9%%Xw`;cU#^|t4?g>;7@XB79FyFQ@$9?5`z;9%V0bHe&qK!& z^C{}4m^`mP5~(9psAwCXPI*hZSNJLKB%403o4MvWG`4Og(_z9DYZ_ji%y;~($Fd&8 zI&Dc4c|yB{V`&Z2eyj0V!>UH<IN~WMljlu%{l<LVhr+R&`FLn>){}J<9qcN&vkW&9 zG@OGv`xn0OrG!*iNZxPxt~Y0lWNcu+fAy<hlQyaTq9?h1vmqR`WmMa`iJO#m6P&z| z^9}iEoPH5tedpj+{HwqE(e{-ue<`%laQueXzX1>DH{)r0d-zzxxjbz>bf~l5u4b37 z9V56}%6*nxMaQGyWa0cpcm?Au1)O?g>$sr)Y(MRH!-PgPES%vqbViUx(k7KTzzs$? z;W=pJI72E{8&SS-M+JTEc)I$jBq`GSllPt;J??3-+#n-zR)68<<JyFj{mKfj!YIAf z;cbtuG9G18LC47of5D`$PF41a<bR&fe4qd9=h{a<`qB2-<BzpX8#lGJY&31$W@%+; z4ILIQvKNOF7F#xNZCkf(PpFJ_YuCXK%M$B(!NPga!|_~oRpJ3vn+*uh5%T2sIX{Wa zxzXPLfe*BM@Nk~b3W@pi2_;K9t9om5N!11Jn-1yompuNaRNtAm;xi}J`#WQB-nDFH zW6|$4llG`r>9B#@Xa{I48t-IwMd=8GYU4YSAf3CONrtJAd2J*zrh?t01We6JrP1<S zk6w>{w#o*gkx50tR-<yHB0Zf4El%UD4Wc^Ee4d7E$7dsP0O%mbMx?RX*gV$34qO=A zTx}-xNJoNDFpXgsrehqDZU|4a+K{eT)WMB7=sQKdGML~Ax4XPUk7W&&dUtB@wSK-9 z4=(u>26rDdp0nlHaajiinF8E_wrTr8l)@~_im9uEcwsGXjuJ{~Wx!wv6D~2(nV-gV zjpT*`@m^)q`o)M&8O~B=;0rz!f|n4M^G7g3^UVbB8LtysV3;M47;O<q;?lBWjON{W zjKX^k9AQcL=JsFzi=S(2cJ6AYFJb&(iKaWR4r2%<(p5TTJ;FwTV=)HxStuQLW(s{b z$J0B{j>`Iv%LD8`a2@aB44NoVzNwDhXVMyB2~9OlIsqb3(nk-jd4#3VsBn=1wjF$o z{NP-JrhFxS+(Ff`<2q(3H>_ISe&rYbUHkP9f0!7~i!q8rdpgd<paNcxS~lZEiVAD- zjn8{N^tXpNmZv<tI*f$vl1_muoElFxte4S$qTROZ-u4D&QZ>*YC05v3mS(M4x3<0Q zdmhB=cy;QzVdEwSR>rC#KTgf1E<uiW5R(!{#i}qYwpU6)nrdKj0%wdtw=<E3aB(@P zv8WCl*dIl1)22;4o7qmWxyLh4KMl^9P@p|L`PgF_l+U1D>qYCoSr|_jGD&jDc%U!7 z)b>BWyIo+3`Wj~X=jeTOt#~qFQD|Hf4C>sFYZ5-N1DJ(ZyhdGdCT~kmXSx#_1A2)U z+p^E)ap~qjN!qL2Q27{9RWNK%wms#8?M<ad8MNVp?{2eSe|y{i67jO(yoD>)v;|9u z1BzD#Lt#$4ZVk>FW6cqI!Z*zj8v_`|HBh)o)+z31&S|UI&}{^Rv*TE2nn69^LSt!J z<P_OFbW#c<+^Mm)f8Y7Gh-F8HL>QUvgcJrT6zD08AlYD$4~-jahezOR3`!_)@chXW zY;eVH%u5$7XtQrzV&g#KZ(lgqhL}*8#YUXi7l9X<>xbY_qjQ~RRA&?j@oU?_dyND+ z`vH&d<x2-p8CcsUIBk0x1N(Tvrm?R6@mjgi#`s>GdsW`%3LMH->FS_1SAJ`3P)6n* zIr!Te$V;X06t4=pZNt;FCaW_1P3n4(=K_*<R=2PL%r&6&*0g>3eI6A~qsr(F&KYD| zF8NKx;LH_tmLa+fE%ISvIMe21a0W*;U;yrv4G8da4Ay*W=pimV0uW%bd}Wk)&7_J( zPoLWpXgpiGs;%6ztIfl+VTiCu#&J7y+KC4gu^o4`WrVkI(?EIO0kZMm%}bMt#%8QW zJZF*wxjin=;&D7od)mBX2ZIE6w)Q)DK#apTjHDu)Xq&>N0o9Ng?hviF@`g=Y%J>_v zXc5gv{b6z7!O0qtrq_xCh$DFXdfbkel5IKp`(bznrB$BbtVi$?Kb^EXgSXJ$7oNvk zcXeAwEH+oV$Y`b&*Q5l03_OHWnJT}M?EpAFa`;eWm`eH_`VtMe)W{-o`WG%pAECkT z#*G?5UPX`4W5d--rqO7uhqSyOT0t*qZa#8oNDNHY$w9Nq@^N<3whvfB`<_WZ>Z%+b zkW{=l;3$5TWm9i(Wqpj5?*yaojpgXdk3j~iR6I0Q7qP(f@uZKTt{&0E^^iUvPoFic znpm@TIej`4fbs;qR0b8V*2?m2<JQBvw|4UA5#-WI>V27V*_>(3DvBb#__kbyGimMH zt8Hmw>gDuAJG5_qjLzSC|2^&AB`Z1)XJjauM~CX+OkSyoPwJ2l%svJAsNPdFWjL@x zXJK%8?!vWpfbbfZSynsF1e^V@{NQQ(7CyZTM~D$Rn@!^ez}pQBt{0i?o}@o8uCpFh z*4;^7`yBCaoiDPt#5MGU%S@OXQo}gT6PGcDuy29CC*5F>biKjNe#CF(z3VWnGDAdi z8@yNx5>S(#=cohx8JPgQ;x+W-n|O)~f9fC_>MOwHAm6HDkd!xmNO@)0Gm&{%KIH*` zUgtCLKA*wF?GogNOIGi>`_8su!>YE3<>?xr95`waiBU?pQ>N`#84tUf>*S?&W$a{| z!~j2W@hmh7KwVjsCv||uHfQmI>K{pxs}HM^JQEjI1fBvfk>k9Uwv*77N6-Xg1+ba2 zWP*|sF$h4jkYk1(5;n<Rq=(+gwZkW#+{`QiJUmZGjToF+azASh8|*Uq;@%>9{2M>k zjHWmPGG&-AMO58{fj(;Ts`O^E;R^dza5~|P*@N$?29;E|R)_a@`T=o=A>6YJ(YBvz zL)JsQgiibpzVeKRUi-3h2L|eKz2igS3_A0q^0eHNNyP)wBk7Wv>HEBkKl-%k|H<s; zl`qL6{6O6^c0>1)mt^ShIO*jP1a02i2dghSX>GnKS$;R)?g|9Cr*_j77QX(l{g|FV z{?AdDTmJSh@>U>$E1z_7iRb1KHuE=URuK6cKFNwwpZY?4rQh<oV@<hST%z}(-*}(? z3z=<Nbw}x1Yzu9p*Y~tGJ-_{?>odI%O)NX8FZ`#DwiTZX2O0MD23dLNecn+KQ&zfw z;Rn-)y0QP#x0^j>del>{yf-gt<v7FfP8pnqNjy-F|2p|m<#u$-YvJ%DDf!lK@{<>o zFFwz==E5NjP3Ldx4=(gTR*z7B??Y-hVR(bKm=##;E70dV#@Jw7gEPEjpF5?FO*sqZ zjkE(AoawjMty|r;Z6gkEXSmcE%Ce+~bdyf=Sk>~@x4ug#zNMqE_R2|xQ+-NS(ZHE| zbuGGbN#{62SnP`!g0zDNYNA`Coa0M3I$W}3N%oPbRVCNi<m`{}!u(u3dgYfbTeh^< z5_|Z~Z+;UvAZ#S^OD6_HLRq)yy%aVJL#sw;h)vzA27MdOL-NY?6{?kX2gSlO)-B)F zN7nDw!#b*4+6-W)7@Q6Fso~l2u?E%B>6qNb2wiPJl!%YP7+bY%=<TiJony7|q0NeN z)8FtLHj2?wFJPS%+|R;#$8&ncD(oW*!+WJC`>o+Yueaa$jo*m#-S+J`Labcg9>;)r z=+J?by^+=TdK+uB)VabCXBvfv;XfU#+<eb+r6sIXd`$IiyP`qaCax_^IbcW+Uwr=a zUuqBk`NM>|IM$we>M0D{uWs*r$2-}u?hTAj@zBLks=;}Tak4xe-Q4jhdGxxQ_OOfS z<c>+jgC4zl2CG-tZnVAFhIKe}?5fj)wh+Tls^_}$MmqNVj}!|(rd?4d;TA_7_^D^c zI1o`7AZhB@)4C^nf8}jn$!9uj8PZWtbm7$)t_?;#%4EI6h#!n%6Vg@`*-B>W&Dxg4 zxArXI(VnDp!lREq(!Th`KS~;%A9cj2_QodX@Rs%zCkVE0-@&=PZQ8VnO#l~%59LJ< zhWOa#>=vTsf`95vJN)A>f35xA@BdyVvA*y7zYl$QP3paFy?Slcu4FX71*$u4{+1DV z$Z0$I&+)L<ea-*Q7@Tik%zzA{$o!rj5zugZJaJ&y0T|GjHZ~-UFg83JR$2k+2Wd>z zvDW~`-zB(gMAg~Z_!Js;a|-ha9vZP7zKpMDY>Z3fXGg1tt$BFJ#KP9!`@TPXrm;r@ zSd=HysVok|$??Jl<r;f6{Q1nV6e?heMT?}e1RJ|)hKcuM$77y-9c~ri^dX7AZ21vj z<fS3UkQO$|2piN5J5rbS`p)t$Abb_x3Lj^ZZ20r|ts&L2`g&Ra-g{etpnxxrRm~6m zfih30rjgc=9;R2A^ui<gk<|M1hp?s|;86psv>dj+7{e#Q1!IPUcNoJE4e(jMJc6<0 z44#*IIU7gs0&z$8pE%Rr`(r=RUjNQ_w;Sx#dV~$n^lV*boJ}?mR3OPK4q%4S7FBYD z-`T*UEEkT713%fZ9VTAZ>Ema^6V9Y5h@E9sKxmxIfDoZ<96k-|3ix!+n0r=WL|DiM zeA09b&n6A+b_yD)`8<Y7>+a0m4dQ|BU|GiIHS5}kfBqNR$A0;j+e#FOxhO&!a$I6G zNV(!I9R+yRs4E~n?fZ6No;fJQcc~8#vdkVHG7oXh%XBIVU6rhp7$FQJb=Tc@x3|3Q z0labNwF4Mb&eM@@z}TtrY9@-vnl)?im|abL*4x@*;)hL9r<js>Z*QdXt><0%#e3Th z{63DyuAQ<f$YSCy`QEy_5r;FYer_zw7xuClAV!gmcw7F`zyCkm6OTUHzKc$FJ%;ZS zM~}8ApZYp&<62t;Z;rsP6QtdX!Fm5~c4THEVKI{=vsq5(Qr;*Y4pX3!F~g;g{5p!~ ze9h8!9V$3BoQky33)?m^i#j-qDh_SuiOWgdGC@OH5=BN>57Ssj+lKU(r?&j#_qO?O z-qrT+J<Y&&w9Q+*x-D8ZN*p*1&frA@GXwT1LS%%7dM&HCWB9!`K&Okh@s)GqEZaw> zVX$7lel5Ib+e5bL#Q`2;Rs<&Hor7W!!$gkl4sWq@7uw;2V{P6-;;b@xG0ZHjAp-Oc z)tfnnZQyn=9`85G)##x?<P-+yE3~CWEFqjTaJ7w0jkTE<*&Q3XFiM=$0p(mr>y!&5 zj5vUa^8Kfx;t4+WZnpgbE(drLSA1(b@leLbm<qnddl~h4W_#yP@oPTL@9M0{Bjt4Y zk$(+X9hg=hk@%><nPtlzeJs-Ngn|E20+cHmBY{J!5yhL|WvuAZCB5HSPyYKcNAmDz zfa+yr!73h7S6~Q#@a;{5vx;Vw5yP@YlZSNhwCiw#PmO}&Kp9Y12O%{;wOzr~6kg?d zb@JdkGjndPs&PsTyF@n!<=24Oyd21?0mF+-9xYh8zOCJMcN@WQI)JCeMGVd-PvHrB z?0nmL`%c>XN(OoIH|3ij^23t#2y}35R=&GJ`yL~-(FsDq3?VN!-+mjDnG6D4{%R-~ z2fEa?2H`>l?*=cEF@ib>(CEBjvj*qYyth9U!98yM#K9TmTX%jdD>R@UIdmlHZr`~x zeS`7@j6fPs=?X89-obJnfMX|IPoKcxyk~bjeK%~{6fb3YPFmaNCKqYNDIHaAXDCnb zMm>D!V3zqg*qcX)9*xG`Cv~-a{z*s6WGE1RbTa$c@uTTm#oKDUxeciyZ7o+=i^r6f z1-JS5-~QM^ga&qLxC~|4W&F}aUcPaiJlOEe{=YXmD+kFqI+6Xnn+95z8#_AK8Ze{= z{ge32K%Z;k#&+<eY%pN~hCMoU>;zsx3sKYwBY<H|V~P?exB(6aE7CgObv#Ozct;<} z>Xj)bpcXQjwH(iRJ|^ShV{7X_^Wg$G)}3Ohi{8L4X+3`AaQlJR-H*Y!52;ZDh_Hz; z<~yzyc<bSF@AJIgS#r|z$H%t23mBRYox&)L@#6GYO;DOlIF(g?U|F*myp3Xjm`VMI zh|!O28hqnT$G#&D=rxErnX8VZQBC9PB@E3vL0o3QTN?-Bl}GraF+y!vzpGa<LbDo5 zxvBipt6N@(Y=aM~KLe}4Y1<a)=o{e4gVs_8=TuKj0<FJI2d~6PW@EL!{>%5=dXPBy z2rc-;5BXm*FPS7CAFB7Dh2k)PPK5kezkWkojf~i_V=K#c=VoP+x}{-ks@?T6&{Ea= zY`@j^uU#gN`PeB8&V+GdqO|yiL=wc)nvymKXYS0PU;Sb&5_+R5nRNUyK|YiJ&B8v; z4I#OW;W<tp)<e9Jz~ma7b!La<L+8l1E-TAPzT~Yj3*p8s2}g;I84u?&IL~4d!pZen z=#xX}7>R=nFDr8RPrh84w28sq_6dDsaHfyEc9|6m8l2G`%iv5|0H&^Q_yB*G>{ou< zM(odP(5*c6eG$8G#NX82a#OglQ;krdzXoq6APL`FOY!A5C8G<5UKUlKZ4UJ>DgDTU z4~w6?iua;<zRf#G0=i>xrai>qoVFniXy56>p@~q)|I&_ABcb0UZ_70kl1RI0coY&s zE%1VpzxBs_d|t5CvzMpxUH^eK7f5w<pW6>~?@ZMF_M)sxkzBMdPrvk+c;(D$HRWIE zLtmSISK9Gg+Sv|ZIOz$(Lj(I)X`u{sQZ>K%zMrI3w)V6Np#p@Z7gT{nhN~Z`H%KFa z^&w6E7oPnhpLNOe4S#MLoC8+<F-<<G_l3`HLO^^W6OuoPDqpT04g0iz@mg6<KQ|xg z#S#4r<R>ql)l*)GC-7IRq%b(sj@&r#GUJ%bSAao-v$`Y(KXo8^<Q$Gf7ntmGJnF=s z{f{NjV-J8s`(I@IGn<LBbr@y0F^M@R<6a%TD5>ZZ8ubR}cL?4qAHw;{sVc>{nwAV@ zm8*n&a)Y-Mj8`w|AOoz+n0Q`_r>;7_{PFzr-)MjKr+?BOWBlZMC#LV*wX6Nm5B+^` z;3j%Zj1gzn@CqJrlmXB4=COK{n7-zrF76Q-E-m@34EpvS>b%s8irMX3h9RmPe|tLi z6^|N3Wnafv!cazNX*D-G%<!=CQQaBa1N~!~fI_^(nMQQ!ZwcCl_V3@%IOk++A~M%P zCXbh}YRL_5E$=ETo`mBpEB5~IbDt-y#kRI(+a|`t=kOl?408GgW5sjr(MKMk+yTb6 zjJ4*>Z?AgQ{dgn4k$mUi89NUn<hqP4M_Jiw*CA}G(251U|8-{4HdJi~nNBC<yT>1Y zx;;YP&pz{Pd;Dupuqokf?cMKs7oi*80j})F%*!#Z;Yu&Y@a*J+_c7GM`@tz~L7h&0 z@TM%JzhfM%=eR4{S2B*bJr(x3bVoSjmOetHikl#{OY{HtV*AwaeF{ee!=o4~Mmg!x z_aXL0y{${yYZMn}>O-cNM@;Lxtn#NW3#ga21#MpPvJRD}yGe|Gl0n^9r^-dxX;LvN zY@OvZe|QCT-2*0g<t2FK@<sGxyx*Vw#*6LAuRnoT_yWqo!x~Gp;Wu{fx-II#v>4_) zvnk{$)3^&Fxthq^KC$V(6OM0HrcqaUUv&JPF*t8uxTK9j=nSH0I5L+^q#;wGs7H*A zUT@qR2$rIyh8a4Hx@$LVV7TC$z8YjPsEnM(NTn5KD)+sSECVRMkHSy6DhO$`md$VT zi2$ZRjaBYY9zmYQTZojoY^DlKml<S63oh1h<#~n1q6e5Ag+|u7cu%-gz;>S5DjJ^y z5IbUFolnROy+ajL63ST{kTKmU=ry6Dlg@(YwwhX!<5B=N<72RkNi0HIMt5K!j$AIQ zx27Gf##C`(koC(Ls>vb^N~5a^l0r?7X<Lfr*vKtP_!Jgi^>8+fhI!7zaOEIHBfcG* z--tKqq;b-FzgKxsXu27jh0bOW+{f0or*-+%WxjWIO983D`4TY_FQP>7DW43s1IJFc z&G)>z{m4)LR9m=ZLwoTQVKv~F6^rol#6*&K)(C1n;IHEqeTi75()1F7%NWCkUQzkg z0DIuT0dPmg9Kx&TYwAYFCGHLHFbAWsLI1^t9a;^tFo+_A98^m;JxAqF`K(_m;tU*U zrBgjm%<`FSCmqVJ?K|49{M&zrm-D}EOEF-~#t^HAOJYKTE$LuBDy8Xw;Ui%emJFT* zbowxTDO?KJc&c@RyH|W|M|!SDxrGkriB+XR`?g(ov^TJP$EDimF+L5!6V9|A+q1vo z8^gB`GTZv*x4fk-!Qe3)p{*ynBR2ed!%rFsq`95~DoM`LYq*_)H&lQ$Hj4{mDXT<_ zU+KPY|Gso4^D*B1Z~y9lZGZH|FSP&VfBqla+u!y;dujLX_9+7PA2~)0D`qd}QRWhs zu$;!*Z}&6L;6Zn+EheVbs>Lfauy<fblY=gF>MAV2qz98c7kJ=(nb7twPx;(7?Ie)0 zBa;NctFg)UAU>tP{Hk%sXWsXRouK$L-IkyH-Zt;eci@$G4zDU^yXUTKi<i%4`MiAZ zrhR;efe^}YN+&?k;LL`BlQ%FjBTKH~$#~=tlRww!$nYT3*o-hB4Kg7#Me9H=#sJ1f zLmHcH|1<IQx{R`P`qY&+d+t)oT!;d$S3HmcxKjk4Gg*3{ynthX-##<1(<d%qa3;<* z29>$9uD7`Z#L~Tlmor9zVLbQ-psN!Ln!QyGG#<pr3@}rAnW4}-NK}zfmS_Nt5z6AJ zsPa_)$N?U0`%Zd^znmFl11EeTe&rw2@Hfg>-#1hB;Mz8jP0A?O_SVa5<)%tW8Qy@6 zcYvL5#J4m|Ui{`^a2Z1_-<094d(69POMXnL-WNdm%uLLp{s?H-_IOZ+O3S6*E=A*W z!07Oxa$GR|1%q>BK7EI6Lp)Gk!fJ>Q&KLyXTl+yMAZEzR^60NTsi>hfd>6%&bg2Vn z3q!uakTJAud0WJ)kab({Y_m|_Z-D#p@v|5u&u8Lc+Z{XGazah$*q6#u51LTgRa8_p zFqlBtF82oKlc$J<Zw%)<qIBCoII&WLW#ypwR8G);Sr>kvBp&i{44IxTZCkx&T|y;E zc<bmtJH@m?fBFnq62lo;eU!;T)7$~PF0qpsU?YDu02JM&jM?zl5Et}er}1#!xA#TL zTSJHlJe=vT?Bk+e0Go$>yY%y8SEj^3!qVJB2bqw=3r7!$`K%0bLb8~k=$_wv6G$ji z7|hqn$zyo?>X{;K)~sEd&|#4!q)**KXJ}4(CvU8`GG2MDk^SKQgXwqIV(inSQV(Zq zt3k{5NhZ_zDC@4%7L|hzvNV+2C%gPl?`+ErpW1dvTgz<W7hvgQ*GKn4K3~M6{0tKc zBeNF}r+X1}mocOyxUx*@!=>uXUmoVvcw_842S@VCTn2V3>ZYjnBY&py>5s%gq2F35 zrx=tRJI+$c)9t;ly|>-B1i3~G=YG>bv#HFugjC7-mdC=uGhcf3)<a;qQQz_vi<#Is zkfqoB*njL2ahePF60h2wU(*JZRT!N$xX+u<1nMlkf(F~^3mBF!m2M`!dp*rTzMk#& zFPFi=MU2kZF)~kLa2`*5QFNmTSC$Z7gML!|X=;++&^-F7@)VgFUh0@xo+$6nlBH^z z*i~;<G3mJH>K-Q=oDIzdpwyX!ImCPMxwlA*!U@PX1?-dqE(BHFa86FrhtHhd7B5=f zHV~5KzI$#b-amu&1%yjef1_WN-^@yQdzfPYCO1Q6xjCWx4O~3U#0#FyQ%u?`fUScE zP*p|XeIMoC=hRv7`_1cwT>kKHKOrDZ?bp=%M1h+GX2KoXDtj%*{J==~)h8OkY4+1~ z>>RC0*YR`shTq`t#$biim@$Hf^XzpP5;Qn3WCDj6&a?+tbqq0>Pak2X;NDvCi+bv) z;7LCZFHBxVzxMvpsWv!K24@14p?j2^kG|I#oaH~W>-)u<%l^dz7?3_3Jueq$`@C=} z7R8f%<KeYWV|(+dr^(CUY`*<B(1!HN?Ml~wdo!=f7dZuzD{Yn0XY4bLEcX5CW=^Vb z!*7fZT+>gJxQx=|(aEEP?6PdrdIc(>2rS&&p?R4;rhl8JPT!T0dO8(9Dq($_O6Qs7 z`bK>A`8uhu&LuWpc7UwlyMLGuNasTwNt}#}JlA;KwY}b88W{&cORmUgr3dF~pHKSw z7G5Bozr#yjZ-u0*Z(Rz)nphPtoYcpo$6b#%YFE#bUq>sRRPOwR-+X1c=Fq3NZS;8U zWz(%RH&feb=w;ay)2EjPwn-km?727bk``XxiR&&2>HW=_jKLB5w`azpq>I6si9Yw7 zm_b|Y4bE{?BEPezPcq(MV|n<^nEE>SSRVcxj2RAMbeoH@d2`#eX*2o?MocErG{_Yl zYOE@a^l*O51Md`yS3bnstu*?pzW7$tCS8rCbdWktKYW-8SYe(^9rW^blQ<nW?BgGM z^bx{pd?xykM!Fq4cC-(E@Pm;%+9}*L?g}%dIs$1^(EC+-+gFM2@Edq?Vyo8!3>ES1 zJ&-%}`>;Foteh1KlNi-qk?xpUokIM_$$)faEVtbh8_8m6o4kvTtYV6eA<wE`ho8`E zlp2nm9RsSnxynqhUst+~FhQ|&@iIJ^7cn_O2+)g;y^gjgo_Ml7^VBnhmAni6aBVwy z<Y4>CpL~fv4(A&-<(mbcX!JbBm~?^_psQD{Y47`?A3-Nv)ef_<{S!}oz5SOz_G8(I zZw&qC?D^B^d#e~*qdy?yv#J{yGoDlKz|W(E)Y!8J`aSlw_VB|Gx2G{WyYl>@haQ4{ zKazIfN*&vWhELmt6E23PtF|qVsP7?H>01&y1Ag(UY*jzjE8f$vsp2P%k-vY_hhs!z zl4}q)R<o7T(JL|sd{~c++xV@QyD%G;)!&X4J?u~HOC66_n3c=<ZC={PY#Z~jGbBtM zRaIu0zqS?m#qmf<y=2$@dHFNNIYZ<aob_%#$I9b_v@y?9r%$%evEP(&uix>`ceZ!F z>${^j$(O3Mp5nK^+F_Wx&-w)B|DAM{?D!UI6#jz(zwz<kxbfp3_`tXLRVA~aZ>2DW zN75=xR4Q*dG(O2>GMnC)8|Gp#VX$N4QP@a78;OP==@cUijHA)k2P!fO`#Cf$g{2Ip zSF4R%#x!rQy`fY_1sJ#q6_f_)dj*{N`>tnD6(YSPg<aU}^m?Y(n5Hq+`<jirDX3M1 zHHMGiQRHCN`bEK|3=MMesz&JO{W8diAp>RvkM&V;Pknjs?CU5-NR6C&Vp<1ha2$Zz z5opL8$AGCIu4M;qsK+t|8nWrcl`!5Qj;?SzEA4wjTR5=QTg7V`XdGb8$gGnFaA7i- zdgVd<T!e%jokn<<B#A5WBz?r)B?hJ%11v`YVkc;PL*J`JYmD>=o)Ov_`-Ib3&7wUa zJy@dX&cN2qCTiSf71O@cn?;^3fxf^X?Gnb)s}sz2v!m${1EGKP-~3ElcmKWZDHMtc zl>1o>s^$}W?;Nve2I<!W`|23RcMNOU&`v`<xEa>iPrb*0U0fN9S;fZs39Ec%J;FcK zrIy^*Ku{hqMzQfR=QE&Q!4h@T8N=BbFujQr7nsh^{8XgmuMuY2@7%ew?ZnXX(SQF- z?W4c+VP?}9l!I45AwPJs!&P9AM&SC^!{@e%bguBJSKF7*Jw>-hXa0xPC1h3ykcoq0 z2QS92QXw>i$?bRU%JTGaHj-QH>^U(`&(MJ$C06P)Pd|%sg(c(+u(of%E$4mr-q*I= za|c1MH82ZHb)NF6N`qd2DmGJwvj8p?9O2S{;tsS<Oe8!7gLVx!$1o`W+|T`N+x`4E z+Ry&%zhuLU2T%+yhab-oXZX{f{A7Ffsjp{aA3bi59z58-@$}PaSL+F1F(i*s?kM~> z7yfetMniPOh|e?OvJFcI<%)`komg<i^Xtf)&>Y$euXT_I9R$eB-dzMY{e+2lv)(<v zSHJ&z+UV=Ivnk0KZ490o#IUz~q|IUDz{aLPj*+L>JdjpTPWDU?1lcgdL6wGIV8ZIr zjvl4+ygt|#v6&m9g7T^y64F<Zo^tsRVoG41p=1p3{L)1{l?jP3Ynae1bMd}hP~K8N z$Tt|AN#p4x4U&}aF@j?RpyDXuZs4fwWdjao=I0HAkBfu`L1Dt}uMJ>?(Ws@5J^Bt` ztK5+W_{-p|4CSN_@~&|*YXA$cK`Y<I>ynazJau>SP<f{eb6KB?loM{A{7<`s3<wN< zd*zScnuGE}qg)KlDcAfxfhkwZG!1FHQ*?tZF;Cu{+~=9;G>CH6K!<d^=-XBjMLX~- z4zvir6Bhr})pu1lOF)!Yx#Vd(q=?+dD9nSK&urJ8d?gHI9AmM4q$hRmueM!r%99=; z@UbvcHf^Z#u5t<}ep8UJU@l{lOwUY|wxz@tU$(Z*U$#E0fG7kxMeH{`<j<VG*jBIK z*cL8j6P=D8;qgoepe#!mTn|;il!I4MXx%vQR6=UZX`61loj!xjb!|g4nZzNTo?0<1 zQa5?mJiMMJuJDQDCpk~F&3GEETD=C;QkR_4$ln65Tq7U;C}Ru}aTaeM<q}WZ4h+u5 zSg%70^9f*veo4W{KBS+$+#8(t?ClKB8gFYd({?QHd8icUd&{LR5^#z>zzInW&MR0( z>3~4RHq1l;%7cI`oc;rD`&IiECpQhpk)@C*y=&KkfBLx`Rk_G!aqVPu!7lAEIMauW z)3+WVyo4Sqn>TN*)my-&<d{i0nw~AI&(A@OO1Tqh$5|z^Z_l1=khlm1c>!>{E4TQy z90xu%8DyIV=I|$Ni8d^*$Ji_34ESEWY-wAxWGS?8l!zR&9i%}20xNgID;mg_--r(A zYaZ_GEw1LwBlJS|PM!#F`T!hI?a<k0w&AN7_|N10evy?j-}~yj+Wky|#NbT53qK_6 zj+ZI#<X3MXUVeGU>1`2+s|?~j2Ok?+!}=UPeYNd9N*rQvIf2ZZx+UXT8WH7P03F1e zbvFIsAbQmBTsE&ou4~{NzkuP`eghcP1Joz1iy=2AsgHfiBs}P*R<%lszJfgrTxFu? z>%?U@x<aoc=KggIllD`BIVoPDi}|L%K=z3??;(>vQXdUXsV4WbgB)R-61U>pyrh$~ zcV7Ty8AI~aDN9e~MgH?R>9JaKKgfoW>)9x0YrFfd+uG(0gxYdt45!WlndGDH!lEqk zn%|VgZQ9fzn}KR%p1i_xV7$Bio)RpCzsfX=t$QIVk7oN2o(n&xd6}||a`_<7V?3uW z@|~NA$%7i63x>+wxY5?#MAps2e({DQ%I<!~^lYRM00U`#ImOJ|jRBY2qrZ);Y(w)j zIHTj@-8LA940J;H!HI}oez_sK*>Zsn_KUP9_`yx{q^kzi8%*d9O|o|d{rC`*b3-JK z?1#_n8&hXxl6g^ic~AYM@R44fGNh%4zf!~8%LP6!@#%9<>eBIZ@XI4fHvP84v-<$l z!%AR3T8An7gYw9$H)N*WcXY3b+b%7QS)R21y-ebU-|7oYPJ87$`zhZGkbSs%gn9S< zu+P(<n_u@k2427sA6?bE^fzfA3PSMU$n3j>LPs{Dr2kWIc-Zr<4Jg06k5i7x$<KUz zmpr;0LKm8gGCaTKFfD2}K4g}wUGtp#@@n=Ku$i8#{g3;~R2mJ@odNWgXBO{!%k9ff z-|7nv!^#A%aIi8>NI5#ZB~4eK!a>y|&qanZj>|WfQ3Zlc@>8A_y=)~N4gye>EuDfl z%l0{+_0NQ+@D`||zb59hv^F=LGB|8{`PScp1rEfA_>?~{;h5p3U+2(ydxP^#Rv~C4 zwY|9~jH|Yk#g`4Q=V~j;p4143=d*^|Z9BFTR%30(xwFw(9E+sxX@43wS^bOA>VdcZ z?HQbVe90S*HT4MHyKirJMH_<SrWM3<c0Z&sCNZCU;%n{Ke(l#{pi>9iym@o`nGby^ zb$8ri)4tNJM0TQmmci=5i(x&gtw9Co*UQ-OmPq-w9>^ivdNsZ-=eqyqqT~V7)+C&K zDPO1`$Wwl!Zm5jpC#Ss9%MANk6Du<{I3GTAID1(r4JP27#W*!CUF?STa{!z`W4|*F zdFjRd?XgE5C#=OI7><u*vSIE*CRAD3wr@Y1)x%S+2%U{Cvvtd6JmlAt2P?ktu%FAG z9(Ub&FXauiFMjDu*_%XXwyUf>)tLN_cQQ7d!{`ZT4SDbO9k*lf*2~#?2y=tB<Al<9 zIvdkH`Q+E5JG}kDx3_=(&p(77tqr33`tT^Sw_i=<%9msme3oobhN`EYAq1r>jdeU+ zitgs7d#>z_MErJ>wWH)KUDOw}`J4kb?E~sa^0&lQ$CqANL640{Ti^nm+cM!4Iapj1 zKA<2C?0&CJMTfRa=vL*_LFhSFRhO~4CQQV2f4X8I)h8qKGS`y3#bZ5c6dO?yAl>e# zkHmrEG^;0m=M%rvo_Y4^_NrIk-~Njq{fF(&yLL`bp2&lq{GGnq5zDPUtBFAq^rhs* zfAW9+TD2);XmI}cjUWHO2me}??>op>`e?c%wsS>czV&dRCk!g-8i5v~<PG9!Dw#AA z$EXX#sgR|!<9keM>9}Q5ImwLzjZLgqs<W+rZAVqHVPxv^5*6MU1yy|bw1;1&SHRWA zY8Yve0%mP_8k8M`npWk?y4WyWh96~0PUfBE36Dk;AGus*3J=DDQ6(3-$hQg|38c5P zo-J-DsGy{~PZ|x)PMHYjat8m#dN#(9o~dpWU;{I~9@8pj4*oUX*umOiIO`)G{oZuU zbCE`g3|^>*#&7FqIFBfTd}AFo4x5MHrmo;fZz=1jan|qz*3p5lMoT?Zoqf`nILW|R zT&WmG$t2G*{#4xC4A!8Z9XntoO>f98qZ2!vQ?~hMkfw4@xq7LqY>X4TNF%O;Rs-&5 zFniwF>!EgvB|-1Q!+HB#zPs%q;Ql!0m9YzLCPG>x<arbg2d;zMUt!l#y^N9b83Zpv zFuCKgn+se(Xw727yBaitGw>_#iHp=Jfa9@)(L06;=rO{CfHd$rpRg1v1{$0d^74}d zc=_ASru4SfkiTHbg0=x=$B-Jo^^sp|zxk^lA)E+?KJd<^GuqX_wO71^;npKCk$-i{ zr6~A5iYsaLcGSb7@L9BwXFbZ`T=h~=pTqlV6y?PY1Mj-;-WXZj6l?YJm041K{OEC( zM{DFc%7BR(Q)Y>8!|;6j{r9xjJn&{byV>CuItlzsd-l-LPU5w=l}?cf8w_gVP<%cA z{O<PkuRlo)tP^x5bFv%nwk<otPoMqlXWGX<{xNpveSQ1k_x*5NOT5p(Zf{JR8DmED z(Efexv!DJnp3l!G7VC>I>?T$lv4&~LOK4LXU&P}wVsp)gSI1G%^r)Q85;~1O(nK7% zMBR2GT=Jvs*#V)r48FN~_*WSG#@OL@ZsI*{iMHy!hm$+2-v3Y=e%-cq;sCoXj}c$~ z`r@{588RsbXZRG6cb!<%V1#_-K06;|iR~Af4|;{)j~%~+fq@Ql^-}oBc;gs(HTVqz z%@8ukjO51w<s1VPZuOELXENpZ(X*gxKFZC)wq)fnyk<Oj=<Je0y@4YY;aA$sjVaqJ z1_NSh9y@d%uRGf^2C4ZYgeswK7m2-kiu1rJrql84Mjj7C3;Ny|{jZZ>jK1WFlmu_^ zAn@yzXDm~I<QcrieLS4OcZ?o9R8GjJD#7AznD%VDQ!%uy=;157m)DS2<Rb6v5Ax4E zz{9j>Gjd7;nTnQeHxp=-7h{@f`ARlYcKbUDS2P21<3-W|Q~geD!Ux`iyn-W=88q^! zuUp+zyYz8hQG%bD4t=Q0TXC)|@Dy(Db82jsFRYchQcwFwPwQ;i{_E~DIE7ceYTVG^ zoIwFJj;AyCwz<@w-`OCG?`L8VnS)Y1hh>CAgnAj6vjoPT&tMJy!GJu)q{D^r%fu%p z?*9_PS>X+<!P)*LlcV$t%HUbb54`SYpa8oRa0>Z<mBHUx;{592ykXlmWG1UZsLQOO ziJC;<+ZuR-CulO0I(b#$G^EBUymr=Y*w|JQQ;#gETM%*c3T7hHsE39MW4&ttb?0ue zv-LI%&dALid>m!ZYcOhlmdhRdVa(~%Cr+`s=KgpYuiMxeobA_;m6qdY{bZ9giA(_A z84${4na2EIMfi_Jix#K<h{A6=+W}>zJb8d`r1cC21bX=%Jai!P!aj5z24|Q5C2znB zEBY;%8_*C4y*+GG_WceTG&t*#<b>ZK?IoMu!c#Ph;52(LP^Nqrp5c4@K0|T5_`>rT z$yc-`7>(z%B4mhFRWq3g?Ddjf?!l75n)mkmXYeFHdy<Vz@eJCuc@>-ftt5ZjwR(_O z+m-D`Ss>qA@8WYOP!5CVaV8^Nb~u-QTfIVkq}qp*q8+dDT}r0f*9Z|ZL9C|>(D@=0 zjT$u{x^HKD4W8Ze7`!Qa1213j!@ty*qx<cR_|$&roZL4b(#L;2f0R7%dqO@DR%8Eh z;@Z>4og}=*ggPksntF&fMxtb=vCU0rHT%tF;5u*dGCtSCmWj<PuJUkoSHIL%9ZK)k z+GJ3jY=VK2&IWonU(gdzgEJmf<AgCvs0}=yuMuwJni~*;TfM8~$qcd;9OBFRa*9K* zp#|^-zg{C702f3+tw5en(g*MfPd$9*AV}U*1BJ18>PoA5nOIp#_?Pc`>ucL0yyNGx z+RlmDD--ll48Ap_S1i{Ko8VRqc{;H)MCUZfAp6p}gUAUC>wFi12mB<ZT>FXs0HRLT z8Z-N*p_TrYy!!EjZB*H38S$!2f!xDX;YD#leWwrZ#febaCX1eY+vj1zprZ2dHnrgs zapZ*g6q^7`-y5UIsJX2EKo$<Oe0mT)$ad&t-T;P&D#iRd?0N<N;aBMA1kltZE0dsU zyK<(@ni>b=WpFmchcK0KMHvr8sB7@R?|N4<D)NwL5>L=mJpmW;t}eOtz5^=hfXBm6 z{V7}lnrG8E^=1EEaxYvaZQh73>trh1y!cfHn78HiyvZH!Jk<+8ekLd41<QR5@u3IL zbKlDjjnLKZ%-j6>@kD-mZyABjy1=tJpjDS2pLIt^2kv~<*P(yw)fCgo{ndTk!=4mD zNu@HqvIQW0B>;h;=vCuC^R3mgzLt*23i!mdUL6Z@6FGmAuYG6x<2iLw@08AUYKZn# zhxb&*QheyOjvnU1k063S{|V<U-`q^+yQ){gS^4!@Mz^4VX}m*k`?Sz2a!3y7@X*mk zTBXbq^2tBE5g5!_eldljz~AbnUZJ^&4LCR9lA$#?&2W;GcBd}k_}8)L8Jv!;(>|41 z#&}jH$ydg@)x%ktsoYh^v3}>z9LHJWI^h%+#QWDUUK+O?&t%haimx_T<6J$QA9&!e z5yM#`eT#=}=#>s>Bff`6urt8&W9R{g4<C-9PJK6qM4W?`;N>jho_qG0_VYjg^YpXY z9c~c%XkGi6pZO5u03E=}Sx+5Vn~F999j~l!SVNjXL&vL@>$u2qz9BCEV;q)gd-W`w z%k$ztq9XOB>VZkx)oB~>S$`Iv$UoI}mHaeqZwqlnls1>6OuQdwRozvL%_d*I41I`x zdnWz5VKg3n_|f*&KYh48gLknL{PI3syb=zFiW6~)S&0+Sj%{1pop<ge{`XdlxXY1g zH`?>hy%59o;NURhx8v>4{_Lymg%@9B*mQ}F>sGaY@DJa|WIg+1U3b#?I^V5mTQ_eb zOxgU<=^{>W((8#QpGy2_$CZwY?z#7#_Wkeuew-Ve%yiuDiKCFL!)f0TXTIQ(O3@A~ zB$KPl7!LxA4jqnjm!bRVY~YIa-tqE323=n%&(Iwn97DI$;H=YO$!+Qbt%T1|b>TmL z8@9sg7R^KH@PeXJM5NybcUcKYe%f~26HJ@Z0(6!|gjSu6-qQ1x&IPss5oo^V@y+}t ze(fJKwuW6UU%C;y#_<!!+Md08+wcDFCkSbBzP;-`?`rS=!21bbvrv(pLppiNWc}65 z$S%)PDms4G73b-HZhwLvD*d<S;hcdFR8|?+csU1y$V`|ho~B5lY`7-5;JPpe<Wrf| zI1!IS(zrys-<Z!>!Oo<_5UP^b2{nbcos~?k0SQ|e-`iO^;H=JFL1lwiFzEej$1n4{ z+(SmxC~K!`nmI1#fs<4e44Ghj7}Hu0gS#(aGZnJ7=T{!4)d-tz|8ei9OuaHvHXLhb zsi&~UbL*<09HM;l6Gt(YVIb7_D;_jH&%v1HOr>x;bL4XcjNjN8=ipg%gNCf2(%7uB zpqI4<HtXh~L4og*BEJbf`Mx*a*ue{{I5bp8jEB5;S&0o>7*rtU&@siUnodi@s!FK% zfUWor13p&`k(S@*VVX<`@Z54WfD4O_QXKb;DXz0@6J%!tIR?#HhRU+4A>s<Yh$rrw z-tn$>+xI-!&H~SQ;wxQ2;4-}pd?Rg)jy1+dX3(!t-=Zb>q&$V3a7kSG;M}<rsk=rV z>*gT8jAGEle<(!*4mP2=Mt(=N;tH@M{42~0#yoIu9rRMNPEKTa7)NLxaS!LQ<Y~>) z<?Z)=^S9dn&CaTW;BYSGnNN)Tz$4B}7?;r{8Qk(m9`Wqc_{w_^^+7k65=LkK9qc%( z?IAB{NRnr=bP77SLFNcB-AN~R`_4NskdXm6SkFwZ-k-;hp1}C*F0U**W&;ChtTABK z>Q!vOwYI(PO>e~Lg!esz<JB6|w{J^mkij9Boi;l1=h%h!%jxu7?xpf%r@dqA9n2O! z(>{R^m(Sk+fgfYJ+a~a8TXzzw448BAJl9Zp7%#&khYq$!|NN`%i(mMB`{OTtxy=N} ztBFgs2wKg6zH_MaYG!l|QK3ifBnDYy3%mSGZ^(XjRlI2cvOU_)#9hz-wgt~JK7lmo zUGy(n*wK5~CX^`)fB3C!&Kq~&!NtZGmoZRZUDB4VW`=gLA!LX{2G3x^Qzzgw5BLq( z%vEK(Je;q!g9nNC$r9#8#5-NEXf}o^S0gw`p)jUfYuO^-@L&)*X^duLf7*c`IVA70 zLSSS;TeE?9%)~Ue-0QYKmNTP<Q8)u=f@9n;BnJlP8+g+lWe47|^LU5PX2U@gqa}++ zFo2wC6KA10v;C8Ju}(qrL6+kUVMQGZ&uL_0umJyymvpeuLEd#!N!idgAdl&Nn?VN< zXdp3-Mh=a9DzziChdA{_K-So<IHi3I5ab=1555!#p#i1Ufb|xmGiBP=l=0>HtTBt! z!piBt#8HN?tJ4q2X*)0TaE9%Z8u-(e!iUwS1i*T!N#qGYCNF{YE6Yh)iv03i76z)E zQ$th?!n7ybC!lg)11~eQo`1pM96Ts<s(;cGF@x-siCji`af2-L^S6w04H#U#a0T4o zfIsHoiLnHO?o!&w2=U8?X3r;N2C^BPIw5)mFUzxM&a-55tgUiq=cO#uB;H><(a0O~ zQTS+(GUL$>PBID0B;)1ri!3oa(`KUJttR%nvN5!_(T8t=oAzkkq>Ga*%Eik}$~oCJ z#>C*NHS4-~gtQA9McBqiiU0sW07*naR0be?WB=sf-2Tz;_42$#pK}f)rh^BcZNGg7 z1FBkiBYk)nMK4AWkt)F`&+s#b06BAlWvRplUbAjpLTY3wZSwbP>6lznu6;lzOC%Jq z@7uQz*>R2-%xhvqoy}}e<Uq&|0l3OLDO=?N&sR5Oy+HqS;NX5hahc#K%Q)E-*_kB4 z^P3K4$>*6qu*=I8Nn?1c9K~>K$g3?|w?aFNpTKNevbO|Nk=NmK>uXJ{HgF$4c(A?j z+;iCsb~#384bFj?_wrPsNdBSC`X%{#*p5yT(&B8qj4u%LdUad1c0~ZRFXwC0^M(Ab zu^?YlcW5NfJBhOIrRN#^pK2>tugE03b@$tR4{wkxZ89<~rVAd>zq(ZQtZ_JzI~rpj zyn9!>bMcDK;7qv|E0C#c(JOHHEcoOV*H<z)n}={)8#9~$=EKHwCT{)l^XzKQMyk@% zyfrZA0I~jqtND&qVy+5d;F(yz>=|+Cs*^rUY-2Q^z>`KfWgpQSL(-oSw#@!`f{BPr zmsq(rZE(i;j7Q#8RvcWr>Wa47rTr?)!Zk$OZpy$5OhUoE_^w)jI$)ItaxJiVC`w2x z&U`m*aIWfDJ(-SHM?xp4@q8ObKbgObRRC-8#$VH3{o1>-(r%Epc@^5|xs?eH^fJp= z&gX!SZGRp^@I67}m_T9a`<a9ECwgsPfhMGdFokm+M>y&ea0o5<t-;wzR@-0NKM$)- z@QmMSGk!$<sha<-eCl5EH<j|KmG)KY9zG2s$hRxA5}612=3PFjd!U;FA2B#nn;XP% z9-2!Gb&Oxbtj5!`*)fU}dIK0PiZlGa%C`vd+S5(FYsyUnH8`^|@9@+G+Mot!4fDce zJ=OE8p4QoWpL^bFg!JCJ<>)TfLflLv)O+9MJ%747`>FEbW_>G(awz%s-{k{%t}7?m zB=^Eq^{dMB;yFu>u~UTSH|5K--RT5akBic6)f41l4KDJLvZH=mX34Yq-giCyQbt#q z-ry{Ve&f3iTp{SIoM(MK0$leebf12ZOmbIwRXsBColI>>P**&951ETLwjF8L8Ju|^ z+KFf&$n&l*bAlprmv_?YFB+UHub$TF1Ci5JP8D1A19CDbdIw}cvi?F?*WCBCtdDpf z;0t_kYFhs%|E@6xY~LiUv=*nFN)Kt3lW#50f9CCP(?}=(!2{FJ(*Vt|$}Sm2ZsD8i zJJf-lvlV&|^Qs??%QQCMG&pBGh@O9%F<w?6D7VlT)YoHhK3@iB`OQsS!_yRf?#wY( zK$gSTj_upoQ-DwhjD<&NzcDydpmd8p06J-Ke%k}@E;wH4FZt7YUMbaI>%DSZ{dq3l zv5I-aKBzNkbavA<^=BQJR<Bvz=HtM#f8XBrumAP`p8ERTDpm!(|NZYL+yk3KGsY38 z@}dqNd-m+*+>^1mbeiT#(nw<sc1szbZr-x>uLbkBk{Hwii#kT>8Kv`<!CBsuEqy0k z($1@=NA&|$O65`dzLUVNA{Zg;h4~w+T0T{Gw6K$|sN>WNb~gIrBAhQ45PHzQ?+-rn z+4k^PA89Y_ei0p*jch5({jAh=Pn<r^SnhJW|Gs<L_rB-d?FZibeduu7KeVUlKrz^! zefGKbiQoBsR<Rw!NPI626dQ1?dW!HT2N)Z#Y;XFmH=ws|0Ql=|&rAE-SO4VU_S)CH zq20?WVeLidSViVO0FOQPSo`H)`IYwIgAca5@4g#D^8$2;D{a%}4UEmuy#Z{3NpaP- zazYBz!6R-`OkWKDX+tq|$_2)2$Iy|F;FzI<oSyI+oa00SFQiQr8vjQBO5Y*in_zW% z>}=3TnV~GOzt=7y@A*4)=UuOp3h1r85SeAGBTsqAeQ-2lpFDXYwkhppdUd<O@hBlp zq^tWz6(`wVIr!M`r(17+*E<&gUp#-cz4XFM^z#FROL?OG(U-oM@T)pdI2rK1ANfJ- zD&_ox+LxnbGCZ5Sco?10SN1kMRNtzX^}%<<-yW;4T$x@@{;e6DrHhK2-l1Mc86-2* zd|9KA(G)fsD`%mQskmu`wE<~p)=*@BsetjE&1{qJWNMWa4~4MzF(%Q$A=8r9GG*Rg zNl@ULM#-lk*$@$d&GOTr9aIyq76YbUUp});uXX^=wwyhChGnyQ3cH+L<BA5Nn!!;6 z_In46S5dMpcQ$2c<TfUr?=|K{xI#w-r(UGi-PkwQ!Nz1K!l$sYHK8uxz*bd)iRB!? zqCz&qSi5x4;(3H`gvHKSWoFvoOnxo{(HQ7AD#spnP!3RirkAn8z;ZMIYxvf~*_qP0 z42E3-A+F8StA<)n4RRM4WEq=SylPlf&{`jlgkhjZb>>+*Y6NrwLGLc>>h7{CFf$Mu z!+1H(;(NVW=Mpl*Va;&{rt?;<Y4?2J_qSP_Hn-Eva8J=8%+%A8?<S%3Br}_a)VPYW zA9_<Kk*ASL1DWxeV?ZF(0HeAHHhDsLG_Lqt9-M;aQ+TS1O!>=!Wa8QKO_l;e4L$g+ zr}UGT{7xK-JNaoQ!Nd#?vW9r7fABlM+y28xK2io}2IP8o8kQh2n88hiYFBoU)%__2 zygFikOUr^!<q$Y&4GL=MrlO%hH;qSca28$?ApeLnic#_`Uf3?DfBhTZfTFRbO#!F8 zG>k%alz7P$69b`&Xm*)Bd9Iz=f0&M$7{(ZWW@2!jzjRT1=l6dfAv$)Z17vE5&UvE! z>7V>*d+zz?+YkQW4}>rMUVa&5x#}YiKhnPZl`pgO=%IGceRrqBRD4b1dFhPgRSW>L z6P^a1f;Xs8JFssLOURyRzsZimU;NBx@X#G^i<n%P&t%O?Je=1oS=L6ZJN1G^;uV<o zL|y$Cy2Gc+1lxuDrV+r&EjwuGreRdviNl#pgvqbcRhra5pe6;Jz*_KwZ)~&QunkWx zJ=yW1zOuNjTt|#Gyqt%Lr|dHJnKO)$0m@}PjLuR+FIH3+;ADb`36y<%&*P1aQoL+g zTeO(CtE`gHlUX3$$gP%ELr?y>^Rz~14bJ1|#_;+)L7O3@!K?*s{T4i0F*pNx-s=TD zFvE$TVZJPbGl3-84DB*T{4*#$7?X!tX108BTef08b;sN8!s#}N!gcu+#%DH%yKx>R zmv%G+Zfe;paHEvb$e;-j@m##gkMf(|5?8^mzabe1_@Y-<7Ws)vt{xP#iOo8DzA~JN zLu9+gf14+qnY=-F+LB78N1leKE$0>^b7ycauWH_z#<oy}PaB-037CoRfH7Vjz-7DX zl5&+RIIJJ1s)7X<1irI>vVC!dr~I(Kx9!OnD$N@5xc7H=udFFgXWwa*wmsg=wUlrB z3%OJrQIh;Z-;seU^0;II4`C*a%vVu-y}}W|hfJf)3Cj_mOu{T=V6}w7#}W*k!=vDt z_;oWeIP+BuTvsj_zxgx@>gl#|+qSlp&_Kqi4?U5g8oA{or%cE-18(_W@8(NPbR0i< zDj}@aU~rbtfi~w202iMQvdIKIP+4eV-{+>b7noc<PrF@-0oP4#;?38!&nTIE6TFKF zaZkOjQ07I9)NUMTp6fPkViL)fA>ajhC$c16VU(}MAM%*aHJ+vCSt)dk0o&@et7C+9 zkfJgf*#OkRE#<lYg3q%|mv3DLe*i<Z#$PvvF{H*Q@;XK_z6;eU%R{3{l*%b4d#JA~ zZuVnvwhx$(_xQ5KOOR)HWt%<#idXoj&<5?Ti~S8DMCg<4^H1WfVo0lvn>VNb(l`{Z zRC#qNGWXV7Ue913T*-JbI6wbf+puwC)8K3@=i*nnGynu<m$%Em;zQ&q7sb;#ynhUx zvU=SbLMyBw4c~<CtG^M(;&?u?{P4E}<*By!#pl779_--D<(%jvGy^Nme|gn9P+XUX z<qNa1wojfw?l8IF{aaaia~tua=OHK59ZcpS^a7jj1Uh#mHH0zm^4vbzx7OINOjD2u zeJadfFo~Bln+Gu%I)3hIJ8=g61O9jNM&!D8h^+0T$Q1RnTvw3Howta7W4O(w-x)wB zv2K?x6KfQMwL0Eqz89a?)9bY^yoP$>1bVFA&gxU+OqBa>5(BeF=ZOhIQX$(X@D9F$ zVLG1VdP&KTl&vfk-(Vp12_AW#E7gnK>#Ns2PfXqXE_@m039Aj?sOK5_WHGc}*LK}| zC-Iusu+nH{!ctvgm6-d1Xgn`IL&sr~x;(E7gYvEID7r4j=IayZ*c6d48t0CMj#L0S zM!B6#rO?nr85hGU_%#nt_3AvcO`FPg;xE4Evz(;^b=2$XXBuhS^F&rVf(!4(i!jt7 z4{-K*374Q%2B5@W;DybpuMHSF2U$xD=UMZXL4P+2G^V7U&Ekz^yW!`egME@;=d@i? zNcu!*Z%7SS8x2gJZ=*Npe<^ne=G2SZI*LCH2L9IJ#d~gYMn>_we>dG9c6AW+X*_l1 zM+{g=E2lxfOCt$_qr9uv{DrpExw|b~d*^emr1g7iR^i&ZloX;&_kHkedQSU&@!e07 z#NbRvSabs?(X+WH1YZBF*B=BclNo-`jeW;WgR{BUQTlEDwm%~wHw9%~EA6dy^=&=n z7xGi8dB`{Y8?V!>l9yc?J^`Y_BhL%pMU#XZvaic?cv(5gzl@=jtJ2Q*p=lC@#^&J| z(R8Nqy?sTTj7Xn+ea>mx;JCmkx|kLB^*lcUUteb>MC#LjBXWIGNl9Dv>G_G=^4^B- zKiiGElz3A1MCL$8@sl$1M%qiO>PO^<9-cBjTcB`C_rkccvA(HqGZ_`Qyzfrxt6Xx@ zIvXj1BXvr3yi;eHm;*+29`zB&HS*8c_-R5FAv=N93CsRCb?R6)zts_H+tw`!`)3=T z#fl%tc~(2}i!p{*LnXZZZSUzn|EsT(#|*xWhd2=58i@IsaiQ(R)m>*9<2tVPZ~}WJ zI@`H(XV`fC7g-H`79D$nx-M%EJn%r<xpP;>>E`EnT*tI02*2_4(@zJ_=Ak_y_5-mA zjvdo4VIuW?Kk^SkH`9Duj^Ma*vZ*Q~!v8nLT<YpO51WguZ~go9y%%<9WuHMBCxOy> zNhiQrX-vOr|I|;~Ym9WIx*qN7UpiSl_UPm7sjolX4jwp+u3{g{%I7)raC+Lx#Qu!7 z_rTuvlRx#3+g-cvz%zL<I?QnL9%Z%c5PLD{jCE-LsrGOF&CfHAeZ1ZGs#mrD>ZgAi z2ZMun#qJi8cJT22_J%jUroHMl_hKiRPbkP2h!g!BHjv?V|EunACr+M(&aAFt1>M&e z)4u0D@4*>s8{cB^Mi1J4+cpf~$P)S_C$rU)J#0UQ)^Pkef)RZte0z<tfNj7P@qTMq zjfLnXhL1_SZ~B&gypc@)HvUK>2x@(z^WO@CRpb5D&M+*Et&en!?!;AxLC4|V`_8;< z|BfF$+*I%)?cWxugWoDPICe#~uT7qQDJl6QEFFKDPl2X9oI$9`Q#fnv!Grzz@aVHR z#{D@lwhgWMPygwM+C$hY)~;JhSvX?i^oa^kc_nZ13Yo|e;cUJZhLlg<-)RQt)Xzrx ziU*hlFQTS44gA25zw8q`n!oB$Sa`nDp>ZK;VKSGe_TPC`&?#6Q+~pp^I6x?RRV8Eq zy@U1GjB=(@N1ifT6kM);n{p^)KD&n6nQ6qegY=Z@KJ%&r(u^39EF0qz!pV1f7buvO zJW~ktgzCVkdJQ9q3~j7r!**y8(C`v?FhuDk>4tlH><NbgKm3QH<U5sT^VPf9PD4Yg zJDIz{-aPzHL#v8|$2kU>b||A5DeVk3R(e$46+2o3*agBNTxMye!QeHNkst!rDrnGi zV6QPz`1L}runih1jIoIl9i%Y8<X)Kk#(ew6Y{M2mmaBkJPz!(m-n1^y(cr9bC_{J` z*O>u|#(EDuzRkz?=IJ*I1BI@66@ElJv0^bsyZqKP(htO?ksEY>6i-(}kwE!28>N2| z0ZY$7Jg<xGwSVvLwJi_4g;<Oj%J|IqN@EO|mCw@7&3gu5Ea7yZ;5CD9c?;YNo6B}p zT*QTgKzUM_6z)}Td8NXHn5TRd1AdGQPGD#-t_|nJnTN__ylAPH%;zM;DCMnMvb25r zw?EN->(@Wt7Q$olcMLhuOYZl#N~bJg2imbl_{g05dwwRZ@I}$fI|l`&ET*0vEGmE2 zE%lY(XhRws3~ypc5qV-M%WvNJrZ=@!TQ;K9vGfx|?g<P$^2{t0G(*7Xp*IZP&m28T zh>I5jyGxOluU*rA@<Tt<Ht)Q>&1I7)rSQIeZiw($mdm{BUGIeNYb67y!i((^v%Y)U zBac1O-uJ%uL0^`y^3TD8IQP&%XT7A0<;p9;Gah8$_{KBs4?pqS?W=e^?|t#5cJ#nO zOsWHIIo=6t7cXN{Vz@10Hqx>t>6}$Mj45jUok+OOGx4E((R)B1P3Of-s~GN;G->Vg zp7#S7-*|}H4Ig}aTlkh8EI~hy;=<(3#l>yaMnYSxaLJyl31|~|IG1_Azwo@Wh>;(5 zsTiEE6O(S=-g9_F(otggU%Z%2zUJc<h*7{gV_&93sSa+k#Tw5r6c}Ij0v_WhPn@B% zWzvG>&}%mnGZoJWpzffgLGX={n5S6!jr%{}vbp7rEA8OE)5L$q6J+K>Haf&Jd(}cp z!TajkcpG79_t=r+Z5(6v)#Jq9WafM(h7uYkG$Bt%uH@=KBXKIBllV}9(qKQKfx>}j zpb+0R8?T}!&h;>vLmlTWH2%Kwy-q_f#5e&Y4t(X)2uJdcc&1DTF48L-2m()jdj*EH zS7kV9lyQDj*Zc@wg-iKjEU>g2!3>;0mi9tn)Q?nMnU?J{{`0<!z?}@CfRsU*rlFcB zgTMibrZg<`(z=(yxp>;iE8m+AKrI|TDOzi65Cr+wGqL~%D8nib0Ah-bvfM1osf!yL zM7SCT;3~MaUzvkpb3WcJi`Npuftc!}w27L8(lc)^<<c+UQF$HjLpSd`c;Hyudi(8d z1>tOl2yp_&b22{>{u_h_Vne`eI};aK<#Kkc9Ye95N#C=PIIpe<Q9cYhaYt&Kuz0Z@ z$uHJL<eWtzK82zBIH7u0tzH{%8h}gs;0d{_p>KkigL;Mf%u&TP6j9?EJ2;?MYIE7Z zZwMowUWb`TM1}%v(TBnYnQWy?*EG*}8msl>KHiqCTpk0e-zW?EN#n>{XjpxO6O!l- z$ek$+fkzG<iHzK^VI$rm?o{nQ31Y+w@=c5c)IkF`kK~W5$d@q;i5i^k*Yvnp$bi?S zgO(+%8hI!M_J*fyvA`sMi7)qPa7Bh*-E-M<LBnwwE&Ns<04>nl!MJn@?}Iz}TKXNu zXl&@A4VyOM(X~8Aa^aMRdxL^~U?zoZXUaJ0tnP6bSvrPCx076})~`k`U~q;8wnh0c z{f%ubx)}NKecB*pYjEDT`=xj(Z`!gMgEO1BFi4Y*vbrG(rY8ufy9o22MuLmr>)4UQ z2{)$P{jP1B+YVyp-rO{h<kJUV6@%3iacbqfaD+De1+?x^f>MXv*TX6qbdmy8(ngVf zgv2;{hE0nxKA$1H#%1*k@k1KZkwfxxg^7Kf_|Qvfl+^>Sg3|-`DwBb*E?&>@9v;uq zMtOJ*{XiV6TR1syzvfjZ0}Uj4G*4h~zJkHojR>zWVR4o7x+`^z?acS;%gS40DchbZ ztciRlKD>vcy5EJ~!bH)iZ<lb}0CIO0lkIE@xt1l^8#b+HB4#DViX}Di2mY_A2hqo< zgT(Mh)y28A7WLsH@UD^A4Q$~IRu`dzu`%8?>fkCGWr2xfL=|<Mwz2A0nPjw)QkG+Z z7_P}Lqzs<n3t1%8thQyby=?If6)svAK*0eI0$+GL=_^f9uHKnX<$KG0%HlD6&I|(m zGphtUgY)2=&ftv9(O6~JGQBTti{T@Ha@9z31(x(%T<u>BU8JK70;LU3U2Jn^;$Q<X zh^W-rHt*RF!j%u+2N7J#(148KBmV_8Lf_Rhh4RNwJiJJ!>RN=Q|AepoCI~WRj|G3% zoli`kwq;5S;Xy8@@q7Lx59-#BtMaUSu6(d?c}9LWtdY-3Zq)PW4ZKhOvItODD?^qc zJ9}faS9!Yf?||d-vcqx%nE7;vVDnST`?p?j4U)RDy2RF{Hw0A8cwv4VNXT5xteinY zfjpBQrhsxXHCgi;-jR<(|L}Fm^vJv}jo;*3)AKBJjcoO~dIit8H;<B)_76n^D-zIB z4~hp&H`dHQuW1j0Fa3qRgV&Fy)7AT`At@AW93~+*|8V2I*ptS#c?{0dF>SxTOqP~R zx)^gz58aDar15u0f&RG}#~~oR!+SxLUo6sm3JBVrx(0fza)Hy8B&FZoXs6Htt}<CK ze~X{2f(5P%OrX~UT{o^zzN9~Og8s9@S#8|3F)^AQzdEKVTG{rHN$3M2!+mQWeEatX zrdRv}3#6^SVnPxW+FmiGSPMUsviLwz?*@0QDq}pRQPD{mC$U$uBGSI#)1UejW1??l z?7V34B0_L&rw$Ls_-wmVw|M;V$J_4RyAyK3vAE;jawNk6jsC`CKOwy4qA&gr|KeZf z{@eNoTork(-(Q~dbiKQ_)u-y&y}vKsvt>KhU{hLfqb<XJvmX!WBw!ya4)vh5jeq0W zXBlf9h;I4l!;i)B!Pw51&}rALU5|(HJ?*wT*vxv}s&@Cici|De06vjFh=#<<={U`~ z3Xr+zKl@W-XMc<s%+C@ga$Eav|Jgqaw@;u~FT`m`!}H10$MXB$yY5Ff9&KNH^y%nW zcinY&=qT^(KX9Nu^2j3?t?$DF`ZdvApTk*T^OlY9B926K6qc`p4(u*>@UPkmY>;ua zj$AtS>8POLRU9nEnL{u4IoM7-US@FZ5&1WHg=o@EiB$EVaPFPRXISA+jOgXGC;U!y zU!-2@q~5>mxP^hFuYIP@WLZ(pJNN%Gma`5bI#Uio!^)yy=s)jemG|L2u1`MxRD1l9 zuQAbp^BTIVHjGCeeI%hkfAk;yXxqMHJGztMLLo+V0jfgXLH_woMs&8;$(oe}M~c^j zF71E%msF=m=3iMIFwo&>#>a`_{F6Wa6E901rQu~yUVc-Z>ok^M{_>W)5}0<Zq-8Kt zoh$b+NpFOdQNn~Mt<F39-<&0mv&Ati(}`!GMlX}H$<J#U)r#S~*JCkUEfPqpF)w)u zlaIWibFqU_?I>jigDCeV@P3rmAZ&5-r(?1XdLnCZHt#87^f+Uyag;2xnV$mPW&2SU zDR&m-S_|veH<nwKF1<^$c^@rJ!<U9h%eM|O>M{`N>u27Xi6w;teg`%xW#i+-s?{J3 zEDoTZ@$%4+ZO46yL5#a)&u75uX}-p^9nk28p}?8t3A~u>Y&595beG~0#t!;5O1Rta z6%542)^RgDLS}UM7Y_5A!uV&WrO{iOs$@F23|)XluP+B>)=dvb6&KUV2R_$Rx@N8L zv;^1UG@S>^jY~@u0uz@B8Nxpen}c|j%tGmRcUz4O#wxnw?Qd)Mu;k?`-;ZOMxZ<)6 zJmTE&XC|G4hTuUA&f?Ki*bM1mWv#Dxp21*1WlCCkN|U|~_+B{tPTb0q;#`;<lyk|m zK?G3$y?79x#h(g0lx93j7a;srEneDw`(wY^{==_-tSw)(B;}jV*}NXclnJh-!#5w{ ziynv6$Gq)q<;5)N=Q|aYDm$nT{L)$FEwMmDD-C0G*wFYgw3RM*+;K<Se$Os8$C<-m z8v{B6Li2L6$M$6W@*(JbnfTe`EJJdW#{GNuW5`+6KJZU|nx&_6+LoQS5#C|Az3{>w zLPZ=($LGxLp+kqV!J;%a7Prce-qjC1^iUK>C6fH2anAN<h1@7p{JPZ1`lyr|N7f}W zLwM<)Vv^y@U-?S=)bIa(dyX0FvlvJh;F&$24MCRUiMY}@XM8_S$O{cZL&V%3X11E{ zI{3D2>%lLt7jGB}MkB%X7<!xlvrUUz>7%hAGy)c{oBzps+LG_t+0LHA>-*FU&bfGt zu58O!ySWrGkjXzgm=9opWvz}g(;CgKOQankFQ%?uMA18kkqJ-o(G_?b&n5O32Ipce zb>PSw4X}(Zf&&1gKFs1Xqk9%F)$uXBA=;d_ZX3q-d2H^9F+{EChMEy2!M*%u_yi7E z*u)U&ayx$T6tQjDv}zKA^NNLS<$B`#(hgh>J;-_G{K<CttTCP0`04c7cI`9@9A2iZ zHH(LJ47a3Dj4~8IDw;M_-op+~DA&`~0le10OY`Sm1&+x!6sS3iN5Qijl^WhenGAfu zoWXb3HsfU@0n!f5&jBdylxuh&7-EP4VdcqJ%9w5TR>O0MNIvqAu*8!J-X<Ak7L83~ zQT^Xi(s)PNkrU9au7bnwr02a?PMQcbuI2S!VP)Vn#0bV1+a=E^vODv!6)T<~KeA80 zPL?Sn?faCIp0-bU`8u0R(zC_jArD;xzmwo}kocmr^`gbYWj0<Jvx#Lk3%TyVsyW$! z@x)LY;?9BmHNxN+r+xqa!)+_=eg#W32l3vJ-=)L=veWW$%1^&(@$&p6veP)b2M-@g zNR4f~*bK#qQ{LH+@_F!H>Q>1~`*l6u4ApQ_gEL_p)^8++^Gae%3zN8!j?lFF5NQgH z^a6)AmswUi#s({T-kRe|yfACIXiq5$rC@0uBM(THq7KIObh(K4>=<D{<}-jWyo7vV zpPAJ{9bV-N5iDJ8C+QE6nHtGm)w7)CiLQpxNF9BKbk@~;#7iI%4DjS+o*og$j~|V} zS;cogGE8H2j0n)yddM#&37l}P30vXNyZIcGehwhqP<QRR4bWTMf=LSnH|kU7Wj<sR zgMjTpkHU)Kyt{2hIbMmUhYE6e%n4^u)zy<P$<FquvD%eZ2lnk{<p`^q@ZMNP=%htV zL@GO!S=O`k7~3E)NFMSN=gQ3qCIt@c-2=VGSx$<F4m{|D`v1e;n+JJzRd=4ZGPAO> z_I*)hRjF3(0!auYFslRzFh+nKVH#tP4esdfi5bt>{%1O(dt$;p<C(uE9QJfigrmE| z4z~@qvBAa$Y_kavyAYce&{q4tW@TknWmaa+=kq=9WtA`?6%z~^&+sze?`?NE_uO;O zJ@?#m&+W@<c`bwZlRiu%CrOQCfwgb<Zc=mQ(MbELYqz)S!1r@0oR!0Jh!YFqg(GQm zo%=41tS_tB_nc5ycVF>rpBK;+t8kuR3G2~Q7jP9tISD7Ux_q!*NFT~$w&~m>yDeVK zDlO!)Wz_Q}H?pGLPhd6eCWO+l3TNdIac3VgO#tO5<qRiM%D1x$XIv}kh61{a!kNkP znjFRY8KtE(shf?s+TebcG~i}dK-y3#pskmB2JGO%0?W%FOYkk-FF`)R&DXLuZO8RH z+Rp2?w$agb;l=ia$`e|g3x|_0){%drdk*DdgSuRRj1Yx0eEZ_q;Ziu$r?K2D_!R;t ztyDS-M`RG?*t9>=;OfLllt0!DVLZaWfw|~J80x*{sCxp^PW|o?w>^CDn`iNE`HB$q zbzR^3I8-TNyYvV`?V1umqHtz%ZkEY)Eu05cIKzX7ku9QdwtuC*W!S}Y<Xb3hOpCv? zHSXnQv+&wp;XKS_@8ThqAQ+s$<mDaGka7aeE4gP3(cvnf*cotRIL``IaPyF|dd;Wq z+T*T&-=#oc|MTOgy3buc^+}Uv;mdR?Tw%t?dPgcnOo<pAbY+*uOVKV)<l!~>Tzo?s zDteMf26)q?{2)Drh|;K=oUxxu9h<h5)fKV>s~$rSe(wqrfaN&0abJ2`9-l<AUn=X| z@RQ9nxklD7Jc$KoI`s75K|0D!>cTp<K6u53%<|!SrXHc?JX5#5LNoOS|2DpD#=bp~ zNg!j<q$NF6n{v`J>4hldJI1w)eIb3WBMN8U=g)SUdy7zYsEiUYjmw$uUX9KNv+xLh zd10`6wyr#tTdH4)!Z~pCVG1Ve)`)Y8WfPGO{3DNQvlYg^wGU@B!zDki6@w@7Li>_e zc+RsOlBQ=A&RTR*@8a3<i#*B+Oa0?#^_$}%+n(W197S2QEyh_}wrqjtIXS3Hy~_&c z_`v0zb+ZUd*EhWJ>J-kliqJqx@Z3K^YlqwC4q0E-9oXOM(nwj-ypFSvg+6*!!pT2Z zGNG$mo<|<}PJ4ij>olxcMxU#7>$~6mZu~iKp$~GReyn}+lb^)b@ZsQIIm=bI$_4Ts z$KY-_w{PD*R-LVD|Kq>?pRNYPA1aJZT(T%UNH<0=g!FXXUoE%a#ckx^um<EM>Rc<> z^VGQ;#aZvAaCVZm#sQ`&uC#U?hK5uc%DdGSxZ?KE!NYBI<L34)d?z1cZ;x@@MLHI^ z?ZvmZJMMT%yW`H=+lyG~<2aLUiZ)zrL^8E4*>uUez5kCtfLo4FutM-So9kZJ{>8ui zmyC_)Gx<EsUPkK~+n#G*d+1B;z@dE@8?0$dM^<4Rh0F{rT14CU^i_QD;K3+0SFT#o zUiZ4!F$P>fysu(yy*+Y}E~k`<79tb5*(?nPx(5#EHMqbK$koKsi|AA-t}bd73RnFi zJC@Sb+11i18T{xE;OgsEz9tT<{wW9WQQdhSKg-@FjQPi@JLPs2$np?%L*<9MGcX|y zlAuhEIXgp6Dn&Z(^-r#>Q-`#iwy+puvqT_HXfW{9LwJ-Z_Tc)(2fy4NeBi<C*`nO8 z1^N+;Yu@yxH{k>Rx~vwIPcK=j+fsQF(F7((@w+6%bH92-XyxM4&;OT>6sNDq=PX#& zxk1Xp`MvLZR`7Hn&wBIhhjfNlLBXYP0ohU*0=mqj;{IcW^B@f?L?lp@M8QktUIxG& zft3(BSDmCsCGscHc*tNXo&{9MwX3c?V?CBoG7$$23IyasTz&q^n0y{4j?Bw}fWC1S zqHL8p>q<dE%H6gViW~?!yXwYs;!7(p2aSf&-G}cSRM@%MVLPCcDcJC|9$kTBb31gG zKSU7=oU5@&Q^9wdfw`T#xH8`w96M;Vaq7cq1cu5|5Ylqc;xb<q<SGswq&g^edEk`_ zXDw;QXvl6FHEehopBB)<q!rdelm_C_&dfmv;3O~eh((}f;LN}n7_2K5O5#SiwDgv- z%kZ3Wa{#Jx(bIU&HaaNtFs!(#Z(5iSQ6_ySFN|`)r9A}?oAnVzJfCA0QpNW|tk`SE z(ZP1;@S(PB`_6XTPyck=`l1)LQ!t#PxB;MM!H1P=iNGVu3>lLht-_89bB{1VNM{xt z_OwS~{F3j|m#2p*`6Yt`?xYdxTKbc=W;)?C(RnAHTs|A+H8>m`m}=`+uWak^BlXAs z`48J)y#E7jGYXf=tvX5ZV1B|V{iq~P8|vDPVA+=XcZRpVWVF(~K7OOzl6HXAdMQf> ztJ8MEwJW>dEo<_j{3=KcvuWpcHW9oH3m=3pX3-S_W%$z4l(a!2rw~r&VZk+m5^Eou zL|uR5&F$yj{m<GLnGJmN+uqtX@7#eB)a5NqfIwT1KmK_8(igwjUh#^bVt3bD*uZOd z`y7g5+t6En`Ym+S&@1W2`T<<|XS;Pq-w6$OW|m&0ahI`(pCJagDq);FaOtm0?*H&V z{-^fIkNzDS;vHz4u~gVhds+m2>dRF@RG)1FDAiP^yBcAE_(OP+ZdC?ZPA5FHvNvDL z{QZaZqY_10-u~a*-&Wsu3(7DQX@}YTZ{LEp^X6;ud&-6agZhz^zrcqEZTGb#$aqok zpd{3%^32Q_%d<|gxrt#*S-ob13TJD}cT^KNv2NUqOhMYg?JT~*R7#8;JBh+uE82za z+8eiE`G8W4jLlDlGf_=|9|zy0hBBEwzuO6v^Cyo@u%sJ>^M++@<5q+dCJ@BCJ1b95 z!Iv(uOpm%gk6<=|#q$Lw3TCiQAD-5wN73ixGy)rcATc~kzGY>`A|`DFSX^2{-i{xY zi|nE2Bbbd~;k<I?(kMEHQE*}wM>r;*pgjc<X*7c!(u;D9Hldpk+pPl^+w&#r)xm3& zgbuhUXHQ2pNFmt{e<CCNjCAA&;yB|n(Bu1@8UL6wpyZw#%9cSSZBJa5^)<KF4rOt$ zCWfuDD4fB~B&Vq00_}=>Px9^aB*v_+5ln?-ysN&Bd+N_Vsua%hpc;TmP?s=`*Ya)v z3!qEjRb}%Gn@KKNv%am{wyP~%x26r_vsp!sTn>*cfb0e&C=20HnYf_Px=c8X%N$oC z?7Zp5wr+G3g>wx+l0SSReW*A9KA0SI3xA=#Okid7%--E?h(7bi+g_B3Py1SFTb@&b z7Rcbf_$9cZ;#J-rJ9;d>n0M^j6*m?7!=uK)3&@g(B2)`wCM#q%ly4m2{n!yK@|j#w zhS-6E%)wGDudGKa(V!sQzRFb@X+OMkHITmT#?R>riWL9|;R>Y=E^UXx2<k&Klro2P z6va0%xfIp(R;^wWLEgS2%3o;$oX+(Tl8k3JDdYt02?mJvt;?1z&ww`*#GxVSg}~5_ zgNOlEzo`7~C&JG#5vPT-gGJ$Wqazvw>01%RfsO_!gRonUY8%iO?QM!aM}_m#Pd(MH zXYy|YO5<2>Ne$*#Nf<TsZhE@uv7KGSI%fAXPs2}fSH<M$DlEyDI%x+UGw`EbiaYx~ zUk2@b^KfvWV*k+oXXy9Nwe351WiN@)F0dP{@Gi`@nW{H&Z9CFE(lg(C5*lpyz+c+# z9^Kk@ArGi<R#u~Vim|}$wO594OR;=YNBTTrGdyV<sot53P;h_;;m<ACKDzB#rSnC6 zK_11A-~QuF#?l7}_l#O(4xmSVp#Sgqh0Er2DI*;$a&jNv>4Wqm^B3Z3OxH)CO3R(I zxK461Rd*e(&<gM3Su5wrM^5rn-@Rg4c}IWG%9@i{IA;?<+EA3!;CDtjlu08e{HjlY z*8{6{BfK)BD3^fORTT@NFa4A1!*Y~88dk$6uEE#jisdXjg(lqq+C3U<i{i#~R6HvS z+7{w&0z`!;LHAx&cCd3nn{~rO+)7PN;0u$9U}@TP#H*+MY$ofeN9BQD&XL~hur92# zs<-e{UZsxn9+>*7>+x=kE_~AH-{(qwg}%BvmQXn)2YIg5-zCR$KF#&9sbR`DJBa%m zC&L!7Ippw4+70cV$%J{xpwd%Tx|j}lvQKj5h^hMLW`Z83ZT(SE)<Ro6KzknMJMo8g zp%ESef42>bC=RdT(YYrzpZPORzV!g}J>~b>#p9C0_msAKs&p-vx{Lb84Lr8!gLlb; z;70S(;j6+HO!fY9{P1h@>C!Z8^|#g)IDxi{9~Vu^k8SIb!GSG#rya^$Tn&n#4<1~7 zqeXu#oi(@+7SirrH3h(wt;!cgsc`qObJN3}SHVTa%5R6?3L|cM{FqhcRovP1D^U%E zLQh>XRbPFbsSuSnQ$NtNV>RzpEXh~7O}!b%yi$i<AK*v(>8f+;C-iXn>i2{JPeM|V znntx7KU<E=r#!VogwS(evSS{ShF`1RE1YTchf(|ZUL6~FjSSY+r_Wc0A+dzxWml(u zw@rx4g1O=pJ~ayH(=dpzc=YWxkHF-lURDT3;aoU1wQ+dV1Uyq0gjr43jV1Mq?-(;M z!zVA&{|dK#(RDW>7cssqi%&L3h97A`t$~`jk1oJ^0RM{_lf3Z__xC7y?kjL!fxhPq zn^IO$pEH~v!C=ZE4M|!y0Y#OuG2Bk!ib0vgl_%MFn=y@J{ttclL&#UGh(ca4g@5(0 z{%e$$JF;q8>*ufN7J#vh<7~$^$|aWFy!>~J=JPGL-qwEM-S2r`7=PFR!tY`I=FCH0 z<wu%{EMR>&b_cOG6Xg!7g>UwwmtuJ4O7OGDb&d%GzbO#b`Zw_f$cEB^WwmZqxPSGl zUu*mK?T032*{^0z6wj`*oxqskS~e%X`|g+H(&9Sy7NJi>`Rk<jVmB-%Z(UX_VD+B| z!wn1{Cfe`)?!RvjqMV#!9DMs7ceG#prC*G^=0@l*x_u`y7von9B)<8rhuWt;@wvA5 zsUz*oiSzNR{Hj;I3M+KvBjg1Y{m<-vhI%^H?tIxxGPZp9;jhQSdf75%RaYTnjf8Bh zQHF*_KoJ^tm3M8b>6o-uh-)CIftLP@K_zkQgD%TBDa4QahdQ@D<Zmj#Ws%aHb;f__ zLI2w)93Md6>eT$MA)`71-LASa-toC@)WdiS7|ZJy+VEQbXA%OwAb(L$ra`0eY!m91 zDweT51i-_Tx`S7beEYHX;AbC14&H-%ORS`s)Nys=Ti<#wG*_$g7cExqM`r2_h`Mf! zM4-kb*QeblOfL5E|M>Og0RIH<QXCue^B%O}4$c3sv2czLGb*gFuUJ=6Ng=PUOtUIn zC}4GjGNfXdGAbFC9Z2tjBi7EmR~abr$-Gr}F5oIda)9g-?gc217OU)JW+@h02-gbQ z83+K1Ky|-x)xCyiX5DDLTHy(U3|lx<PWdd{HU{C2|7X+Sl<CPB`|!S-MKIAfqe7cA zI$E+iShrz0xE-V8uxtu18PIZX+IFA{>oy+!06Mr<De3YFmA7tg<m^!LvOzG2(4~f_ z<r!xHqwr*lj|k(;DbJbhq%oV8<xv^qz<Mc4I|seKQvi^;Yw4|UAU+jlqKN0}QVtn{ z@EYFbm@4sHJ}=Da{OKgcV-%Q_#g5-jPI$$+u0T{&8{X6RDxg$WnC=4nFo~yg_<7Wl z;LPbW?HpFmTXDw!%Afh^HbK1}!5P1UTp63r_oKwfpvi%l%DQ5FG60!|`HvtNiV^QU z&CBcD!7XEu;M;o9;@1g@2vx*$z((qc7h0o!9rTs*vNn1co<Gyp<Lh`i3iChw{r}Yd z`h$Pbc5K-iZmSS(x%xpxuN)U%VKGgwIcN(J&M1fY%aRl5Kp`Tto@ltlWoQyuP1~}F za|N_Z)Scf<&(7GisMgS(ijIXa=<9B}p<TOcXB%NjkIGqT)v)oAMch-+>^wRM{STi) z;ra5H{}hVjpK1T@fBo(DEC2jg+nuj^HA*NteQ;n$@R5&vge6@Mw_o^$cej_n;_mkJ zlTWvge(Ym(%JbWMe(@I(@)pJdQJQnG?o9nsI%DH5p#yaVfMu9~uDFCQ22oDB0i<Q2 zM8VxjCThNpVDV=k_|x{~kAA!jpa8k$y6f8_>UR<8N)t1Tx@-sM8LZp(ofHr^(yBAg z!tBJ20|b{9UlxLt{A}aWhx}xq?fkWOwzY4*6~CkSTRo(8U&B4YRtEBHz&7kE1v?pN z%aI<DsZQcj&+;)Wji+bbB<f5%xDS8ICn(3%>b8Nn8#XNs{Yanku_({N<D^S@4Z;WI zzko%@I9A?=$@{`23h<k^F{6vZ8B&>-2@qRs@l3HagLRu53C^-{(MhaZPaR_t>MXnZ z;=g(0Hac|F2X0n4OW9^;;T6*;HfTc^*^p)8ID+n>eeFB~!Srb+jK<k%7)$qA2io+q z^XB1}hBoh#?>Ts((Hal}1Byd8+)(%tk6PN#N2pu13aeB6-j6JV7f>$5J7}#sDC^om zYhMSkT7ef>-}3uugfHp)vSl-6<lB`#OKV_TO~-s~v!*8>03o3tNQi5l^)4V1#(0(u zyvr+Wg7N}SZ}Y-5lT?H|U1dzs20i&toyW=<Uh6dj?=CY+NjlbP^<@+r`hcJCB7zxo zW;;#WHxS1R^rVHelS@-5yDs5gW8U!Mwru^TwqXaG>9LG%K2|&`h*Y=@a1O@88SFAi z!E0bZsfM6^_~4<od(XbM{e~ObS}dHM_>tbEZGcEvEu3SC$Fs$q(w{QQ!9Dx-qEs7c zH{Sl@^l|b)rE$YJ@D|r1NqVv^S&t`<pNOT2itb(HspYP;V^AU!zLd>It|h!85T!8+ z=i@4zkKs3(5x@@UT)+NCv>v0_ApOuCxGml%ZW*K@(2pU^pE-V<eiGL)_|Q+^1x)7K z4|J`Bp8tlX;FZ(xxI^r8J`Nul-89-3A-L-AI6TvugC|N)@@Y@=S7I@L`@m!DaBUyv z06^Cg@{K4eEw0d6rzj<7IdjX8bT$G1Q&Aqd0lu_6lhcN^FJR=Rzz&MdUuE(TgJ;Vs z?{WgojsFfFIDqx)E?kIg2w$^@vTY?GC6^zhZSvMSFs}Ul;J$tE74~Of<-uxpbzer_ z;@I?4#p0W@4&QQ8UYB(0pZmz+1Ej;IH#@Y@0bjtVLPnC0RihEP?+2J(^@%)wdb~aL z_;;z-K@{C9+Dq1LYP*ohmcS#N#1^L>$q_u|xqFu{d=Q5oec0|Z?<pUr)_@+$E&aE` zM~aYdu&I2rt)4hd8)1;Bf9Eq3DxT}x3=?u!;vfnr(<KilMeVOgSc$cWzH|tAX&7IN zv(%dtep9$g%H}yR2VLQ~(V+CEwN~f|x-)H8giV4+EkrNTM_r<B{65Kffxb&croNx; z>!T1hK9-@<AXEg-h8SqM!899IqFh$7ypqYt#o$yIW5!WNlTMW(Y(pN9RmyS6dJdKF z?4S4pH<25-8JcAU&kPgLrw_$Pajbaho3c*<iHyigpv_+1>tz_@M<GoG$eW8lOJBts zg`w)E+Hqe`MXO!C8<r2DA(`)7q!1QmGu^7l3Rm@BA&V~<C3$i+kAz5Olrwx+nFG3G zgX&8tpEF^HtjR}W$UCG-=*qmrm9we#&EQE(Xa&Z^m%eqSMT|xBr%^ate)H(~x~YLr zUghxH<@+k9AL@M<$mc4OnBcFzC!FQ>P4Lox<vV{K={pm{r#`*97Ov$KhT`BwpHKIg zcfObJRXY>c#PA(|!G+(Tr#egF?EC6_Yy9LUx8hVqa$F;YF6hso?Mqmz=|5k&zX#P~ zDZBNDbsw0dTPM=z4$>uUBO2l|{L)SZ>Sd!Uzx=w#gAKgm_(q=L0f-z$qj~P?wkpc{ zB7pU#{3?IuUcM(CiFf%!`tXVz9v@JQ!?(U}`)jokzx8l+aCFZlcl6(@ynUJLN->Z( z>aY6L%Vp#nnfKx5vH-Tc<D)pUJ~Kh?RmC1>_>6evo$&YJds;}I`BpShfea_DSR1^j zpW(q<`U7P(Q}UI3%Y%CI26_;e@{Pz7wmX2GL58%iv2WCvN1yW2$pv^}^}+PV(3+dF z3hyumDsE`5jK4f?t=P+gbcYyI_)Z+#{;CbSAuK+eU;nm1^1MI5Suj6u$e^Nro;$3V zwXNu84)lbdFId1>o~GbfWsI?xGKmIcjs->-^QsT{lRx=mte=l&94JrM-|V(++p@Cs z6QB5GG7X;xCt7`)hk6J53l(z@eD;C%vX{QJ-GBejX64y)L;1shwTW2A;RDun@NT;h z_kM%sAdU2c)U6Yfx<XJU(_mwqF~7PJ_ngxDH7kW^`^s1D72){w46ewuY<40u`Xdrn zp{qY$70wz3>Y~gI`<{C8skV~I;k)mCMZ2GUpf0d-Gijo4umNmgQg#tCoAfinzD5_= zo56NBMSp$hz>)U1fAjJ7`Okd;3+1D1;5gd;&A<IO(6aLHbi47UotZeNwC%*HBkh|H zKh}QlfB*f4r>W>^RD%BeyM7)w9-GinOlEWGy?ghx(~Pr}`^44#tlHjn-S*^vW(=c7 z#(Rzl96Kr}izkgvbS>w&RsDhV9Cr`M$o5Mr*Fj%!EPh|eBjbY(0O>%(IIlgglV;tc zMf$dFtIrTm`d+ur)DIdbZM=)OV1eWJOVJa!a<W$8%kShJAd%K7ovDM{x^-)pmq1i| zukZYJjo7Qh*`tg#9{9`y@tMAL>$UAASfp>*uo9eC0jwWauc@yH?bd64X}wA7*~kWp zz;QM0e=ezi0yin;RS}l$xC#^t=U@Gm_dct562fyGR-)%~9ao0QeTd(9#NwxxC6;xE z-v=P5SRosL#^Ob#a0CY7;e`rki6nxi+=;_a!s|I?B%WnL4xE)wWJIy9p!3(W@KOkQ zi3&86qR}oQtQ*oP5Qh1|Bvgc{RCMMLE)wPyR~2@aCB~RD;Uzd{m&*UK4BaIyS~96@ z)DMk}(}A43g&IzUvOCykAQlixsi?x(cQ!l~#pc(Ss~6T|X-tP9k!J}q4bx-Inzb~r z!OZ$8+*tleEC97wayg?`+A?~VpCIlb{&LcJP1B1Be`Y;lu690JAIo?hutbSTe3j0o z>x`3~wP~fp0#@r$d|8LqOPtv=NH&}U8X2J-qRP%#F4Op3g6+LbQMl{-rOez~pZe?- z2Fo#x!qdT3&DxCwKXyFgQl;+k@u{}<`diy;e)jEcXx-X&3fx@;#}ozzp=%5*Cb4QU zAK^@SfzPXglkb<|&yavAQ&0O|Wo|M*ttcn4Qc>_yU~<4}ow^j?!Lal?!A!a{Z0S&W z_RmgIeCWJ>&FZCX<GR(c3jU-2_@CR~f8=l5&TTuAZ#oa~CypI_nn#2?@)1s9^ctA? zrd7JMAj9jG%T97QYafM|gHXzEdi~Y<R1tRpxJ}#ovW_gDFxzxg_FHZh%`blGomf3y z)6OBtNyFBOgXvRrh!;qIfRXtbHkLbwqTn6(zoWhOwfD4N|Bc^lzralI9k2MQlwS+w z16bQV^!0~g+4xKU)i1T1Z@CqB8{chT{L+_VasR&ey)TO6!z>jWL4mc9cHrh13Wo}m z&Q3}v3biV2QXjy)kd4q(U|4=9A1sp_C|H*7J@G{Q)QA77ee};i*rr)BHF*9an+l@r zCv91Xn?8bJ7!37>GD*6XPQ{V9_7p#p(6<ABg&vjr&Y<@L1l#|Ozwz!idjCsN-koem z4xD4j)FqTW+ff*=!F5MBDZ{|DUkU|ja{vJU1Gw3k!KdRS3g;sSPvdTY_IiGKl+_zH zvFsn3v%bRzC=(#kc5AR~dQ;G~7I5d8BsjDmw*eD_SU7KE$q!|uY$|VQk(A9raVaqv z5%Emhn8q?1<=>eT7qC`e%w~nl+WIXjoS`xPjExC9uyPVN8(NLC3;2osD4q|u3&-%) zc@pcp)A)7<|MTFH_Oz~;kf)Fd@Yb0k`@?salIzaG?@o^B+GiCr$jg>91I=cKgVcwE zL5dB|xhGuOlZ7`6u2DLNx~M^(d&_1AE_vpg?b>)(UMqeQAszA3!)Urbb0r(YnU3%D z!)#?a*=PF*T13s<Y5xS4iRa*{+-8)rc~0TXH`quG-UtI&f!_RVpPr^?hiv~BTH`?h zO`%B|kQV&|N?=prjN&r9!kVVm7A$K^QP8d3c3m4mp*p0(*|dp+Zj64A#EpwEY+eFk z-=Is4eftiyEm(G}Q87vTN?$4c!`1>5aP}6xB#65r6mX}{wtWZpN8x<^i*AkOuhx$9 zpvf$eqaBJr5hfJ&lUgjhgi*iIZh&(=Zam!C+fX3Upd8eB-T*5|(~90^s`cw}tm~t2 z1}8gjWHKxk3&bFwC^AStm1ruwD~z=aI8L8BLHjxyw-_7PY{%ug;?%6HYvTpSmVx)S z7wLGKK2jfh_BY#i?7&3?OIRtJJlf*PCk!k97T!|!(SEqMe{*2yY9uWslnKJWjc6&Y zQ%+g}&nmBkfiL{TDjOd=(r^5oGYC$!9+%WD+?})13Vl+?=IdZg*Coe~9c`mqHshXW zC3S*yL!2DB7|;BC;G1ogSH?fesv#|H?Xy;_S;eM!<_(m<W_i8$NOf5b<ME?)tb@BV z;8`~UTc}%Ikf>~q+Y}<$CR0e_n@-a5O8XdN5cu?WpI{Y^5<ma|KmbWZK~%s$jNj<h z?Y1@7VBxH+h9Lk0sLIz`?J`dhDh+Q_e+3jJ<4ye=nu8DZUysSVZj+!1bVuQ|$~1;W z%Q2MB@#%clNj=*y?HqblHt-OlYQxobdzsKl(h=oMWRCf`c$x>lv)v+*(ht*b!!xyz zxuDw()1*J|t@gxcR!1Q}Md1uzmA8sNH_w{H3RDHBlY3hE7aqZ_eFo*!a6+RBt+X_x zSh0L5Mh7hSWs+|gi@3PeA*_Ap1?sxDV(!c1HGCI{Rk~#W$2Bwn$qX>C9$;n50M^XY zY%)8mq8nK&ZC^Q_fGV6b@CO#<3~4`jlDS6;C2iWCWd)$B2I+&N>bj$kyz!khP!H(` zx`%4NiN*IWzI;}mm!zwos1UqMPW^A?6%eG4F8wG9vARwBz^Zwg4a}^&874+lk{Vmr zBr_^Zi6c!!IZ7!1T&}O*S<~@AQl;$d<$}U_gxO$eHN2gxX^9eX>%HGP5Y2^m1ysFH zAOi|`UA^VZci&L%#0xG89$(k{3hRc?6~9l<t6@FhBcz=tu02lji667IeoDzGz9~EP zX1nR%r~ibW69)Rsclcyz3O;Q;W#SF~QwnDdPwcJeM^zklGO9}F0*Xxe*eigAWv;Gm zhw0yZYw&`@J87UVVSTM%N|=!K1PpyB84*wZdxSTWfVizV0fV2C$N4}g>x>FC4Dz_N z?tSqA`cXoJo($WaVY_}YPFL>a(f9Sn@53hrQ!%)J8OP`T>X#1p){7P78|ozW(HACf z{ZKbusQzuPiCRBhory#0%DT)rfjT6Cq7T#R^6T<)Ux7Z)v`aJdpELrO;Zy&{RVGs5 zY>GZpCtZD|I_YbArF}NF4X*6tkl&#X`EOi5LNE5gD(=Dyfh7}o@HXj9h2c6jPj<ZM zSYiaDCC3ZBf=*mU*-QhpE;O>b_i7c+!d+G4-E$u)<Z}nf*CLDX1FOPQ{-Ahcd30NK z0wa@?Cr`k)ajik$=%#ibV8yKCEywa2ZoTI{?@3v73GmD_&tz<qc1eQ$s$}cL)yVtz z@6TBO-h1zDuYUFG0HgTU^Fk}E&l`vUR|E<jba6uSrooxA@?KfQa{6sPywY-OSa!<& ztr$yN?|xTFZd-G5!PTn7jG>UUA#YuYI|U~^ANtxu?RS3Xce0|~m1g#Jx^%no#+%w} zDC^5!b{C4@&FB>_Mqz)7O&H~7>)6jg0|i%lK^f%hB)|X$4CmWpk9?O+2Oq&Inf-1s z_R!s$t51!$Y4e75*WE9U{H&Gp#Y+?I=)qI%GoScU`_$h**q(m+>FkMh6RQgEM8QA0 zabxOh_nv3kcOLmpT)?a*-=F)rceYz_SLfL1qMOb#=Cglwvbgvsh;ao4tE+0fs+?Us zLH?5FBvOGrU2cc-7vf_52DXl#<sVdA>RnkuD9>Zaa$5P3Q<_xwv<~-xy1~=ETNw~` ze1!1Qf~%X=m#MQ-*P?z#o}u1IU6r(^T;)}RGTZ-h<XQb%3sY8}LQj4VzviX=FvI*< zz(;q3!J7u1Bw2ilyoFb~3|<L;<>9w0>HP;hUK#wK_I(O_bw%jW6bt9?S2#ak62&O` zBz|yc1<WfC2fkMxHWE7s8*&uA3aT&)g;E)c6lwozE?qwhAM6INAy^Z9c8PTpq0(#w z>QE7?u&$d8I~zOjD4hAWf|-*gFy>)koF59)isS-J*-c>P$N!CS&R{Woj=`qFzCJ1~ z_aO26Wq~#hVO>t6usk*tcLkMzHS@P2*s=8t(z0nqJY}yb#d{D|#hMMv?=nv@r*cmP zb{Hsw6&s94+$RvAm`cUXObh8*c4vfqo`mCEpb@%hhZfG}rqv4KAA&Pa+^di`J+a)o z<uFf~x((j)+DX}{?WBBXXD*x<RIY-TI%ISxBX|}kt6YkJWt2=oMV;;?Ojln+Dwpjj zoS}6PZah1B%Pj+Okm?{k3<UaEOu1#Sx;*i!_2~uh>e3Nu?9hpcws8H{cIR8}Yn!pQ zJ571cu$h{}@#VOLa29M40|phD5jZ+LS|%-N#l4$g^~@`@2VQ({URs9F!tAF}5N1O` z%PfN;jGg;3Xi54!%dYa)x4025x`oh#0>T;?=jb)7uy9`0CeNO0@Bf28YF~Wdvu)?r z?WqS977B<?j?{8+XdA?+T(u5NGgs2>1we%?>&>IAZV5vNr0{GRq{05^<C^Aq@NE5x zOYxra_5r!7WYGh{di<o`a>wm$2w}#F3VomHVrCD*$$aQ(n2zoo7Hu;OnBV#KcV?#e zw|?t?Za3U`BLi}MtKsJv<+RJZG6}-~{JuBc7q>A-S!%v}-`;lM;DPqbzx*rNH1HTg zlsIz<xoyN5YL{u-w&V}t6XFEeZJSdLaCuJID6`6El{mJ|Ne0BH4jpXY`r239(~myh zK98@hLr*@{R$zIwiMm(<EvEx#`I9g@xc8{G<<e;VnIkNqtj^>M^<pO}O++CFP5b?Z zUw=>AbpPG>yF7-{_iTIWyIA(^+JV9uf3HhwmQ@(t&dp6DRTMi5Zry0rH;bRkDK_al zc7!GLCof?kxVWv~xDtQ5DtU-QxwBG(x-$Q%40cn)Z4!mS6zyw@<yHswo<}J*&_;Km z<iTH+E@Y@lXbS}+m+)EdS?UX>c)=zUEXzB48sYUM9WhJT*N*B^1DbIVz$tz*zySuA z49^f}Y6AapXO6UUD5WkQVFNc@atvV^Fb|rVbwURI6D1+hYp`jJ79A?IsnAj=$f$v` z%wvLN1@0e~tza1#igGt%7#OPZ5y(U;9cf*dOe>v%cMen>{D>PxJ@0wLS(Z7xOId0F zlJ=1ABw<Rz=rdtzpj7Ypls1tzWEUehPW$6Fd8>RYrHbvxK@!>5L=WY2!l&G7lma?B zQ@%$bPF{vhNdUqL)$j}MO;ffkt;fRIE2q4KPl@A?%i~ox&eGS-&O-`f1F(Sw%iE$g z8{3LaSVS=SID|#5{ztVgb`n-gGwDIgO!FWS6vr2%06wTsyX`yh<GpT9;Vd5_dch+O zgu$5_{`HT44ng}6{)u&|vHhkSvRqXk+^h+RP~N-95y#?3i(+wnjLiZM$NKhQyW!?r z*v#kJz$6+|$ihtOCzEc%4bILo;5df$&T*{k#n-M~*V7-=o&$v#^D(o!$}4=fezkDc zSN!p@lWi?!+<?FN3}lmOMG+<9*rTq{5Ik=Rmo<BK<I@-!;QAYHKykc^KC346NIg7C zJ}Uirgr0aW-&SdS;K2U$IqTW1P``RkXyq^y^EXeF9QrL6-X4xqxae`Ul5jdXyF`UE zU#p0;qe~35rm(t!Z^^Tw@TN}PT=6`U++&n?i~-t81}^sNPMFRN(2sJONuRapYlZ2m z1MzAGCmFP=JX@}kl1b8$<qo(?*<8M$yFra*2tCSQW-_@Rf7k3S0d#HSrcLyZ#HH?g zC5$yB-}Jola4(5dOkVDJ>S>hv_}<^Rw!L`u`nHov#bvtGxI*Dv1t2!C1|K9^=~mi4 zrLE^}^~1*bzAV%30|OrluVC0B)kE%`a2m(5={#06M~;uPNij>c!4)fevoWMu$P#M6 zXIr(O5*lGahNGX#syAgu?v+VL7A%HGWAO~$XOvf`xk5gOX{1|9XZi0%GO_QG4@K$B zWSw+oT~9M%T8u=xbFf5T!-?n`h4NyS(=NtkkxNcpEh3FhBY!EssHE{~9m|jT1(t$2 zfLngfIluPdKNv9}Qw|Ys5SL7|7sfd8r#^)>87?)#y9gJnL1ewieAJmZu%>Mu^8eI3 zFLdn_j!iykGi0ee<z%Ae=}*v*BWb9GlGpMV-pmz@3u+F_XuQ4+s-X5c%3#`<@hp>R z1Sr1}rLS-27KNecQ(3C&ZUAGAIVCgs%|!8yA_Rr=v~7ySd?&vW2Fu{2lmpoL$Vk@t zd=iE|LIbYe5idYay~LmfIEv?U!y%rWEVQJ6MA#}|ensfq(G`5|x&OvB^%qRl*Dk1O z^D%v8K2)Mz3f=oe7mpooxK=!2ksX_^U5LmF0*gj{pJ#DE?Lu4jtubf-|Dogb<HggX za2B4F$xI83xQa<!@fjcpReAPd6V&|Y;OM^d>|I}{M(+=Dm^%uM_3=u}UrI%oF5jdi zf9&cju?ybNNZN&Mo_Y#HrGlyJUb!5Z9UAEA$u??nYXZl_h)X=%j$v{nP3XaQ(zX%i zz6)=`oc#D!Y4bL??+WWZAsrvodsD9T{dE%GBY4W|E*@e0RJf!6qYl!}c<E{*Wyoiz zS$MXNr32&H){>{`Tjzn~ig1Rd-U0&cP+qCRInZ>pl)4r#;8J%Z+@v2&S-Ua^4$=us zOuR{N-j{)qJhJo(=3{@o9AgvvpaqWk;l<XG&wYPp`%6CHT7~mH_g<Y3XYu$WKLjQ9 zLdxB>Lrt=>Y>r!xVxXfNk$K=*L!7_*@Q0&twx7{G;%i^?+Vo3Dk(rbcls%-Y{!m9C zestaS$Rm%mpZS@eX?NXq7Yfs@v|VfA`Hw4-d)~l5Ojr}MpR-SM%ys1G(YRxiChbpc zOZq6*a6lb{E;giR^Kg9T2JtG3z5ncIA87yjfB4rKtJ`iCA(QAr<85zydsgOd-n1@s zJ25dEAJ+QGhCI+43}Ym=3WYO$HFTSON*J#kK6JEw^~+zQ55-b^*~+$-iE)h|{``Y~ z&e(NPd+A-bx7XeCQs4)JgN{j&&n{q`bz-vp&4>QJ{r%tnLnZ)JeClFy*RGwR*W)LS zwI`l@0t??W$f)a}L6zZH*0Pzq;%rz9V=^k7a+0>P25rc(z||a~@v8~=|4<nFKZ#1Z z5}(qZFj1AcKYw8=Mw;r))FCNT_3kj-W6XH+0C|!$p)sf{-PMozPI{5|7_Su0>WixX ziHwXaWqRu8+{D|7D5529!2-VpF55_8y#f!44FBlhoiP36xH=5<D15;b&JvppWKQAC zY}Oz`s-3X2pb9KVH{rRFxqw(=lG#|%5}D6e9xfkNNFPDD<)B$gR^hC*NeBsM4VmHB z6{`;vTT3BiPnX+k%@`#fR(2{8bt9nL1UD{or~3@Tf$b6m=~8|zZja(jT*c+;)mW~Q zP87~AK?U}cDA1gBRVmrSD&c#m&=VfZ;%PjUp>_(+s^~j5Fhltc4s1+zB$n5!zMHhR zbnsw!EmgFn(Y=K}Z)}L#aOx6Z0UhfyHbU^*DVCg^RSC|ZU?EC3tw@E*2CPC^WNWEp zy{L4vOu992DfC(tbt-}tAXVxa4sj|l8{aZ|s5q868&(B#Iy&n5JcCLZfR<C%xo~UM zt&(3wc{Xn&ZD%g^ZKQ>md94PY(#klSLbznYnXXA@cHJ-m6t+XhP^vFk-)_6__3f^= zzNPI0UaiZuTwm=hCpesC10R)l!Xo~(0<&E1f@=MqVAD63a;R94W}GBYu`V-<FbFA4 z&Rz(fblIZfRk~UX{JKGrW-m?^-h`>AOY2o7{6=QjH*a3oRx^m-_vF*<ga76I?eTAa zr)_6Rd90?%(|ok5?-{4`VccHm2y*#}KnJdg657dR1M##%nB=ShzJpkWFrG=LKLIq> z-@bQnP=afpa$RSsGp(`4SlW2)^*h^5_-I{?<+yE5yt-^le^CxDoh^1b_fNgzl{nPD zp}qh8e;UR8N$|NG+&c(6h*Ejy&Rxvb-rVlI^QD=57-EKTFUpuNefi7nUGI8V+koG! z^C&Le)Iw#|hV>ib(@KlR&6}BhhE}8(Co&WiEzcB68r#Vtl*rPdlLOK<QbsysEw0>{ z=O|W&fBTmoYTteMn{5xu=hFucwGH^OT!-Z!E7_}kL1!M8Py8yR+WE*6?7XB$+qCW3 z_G<p}iW~mBceT;Cy^Qx`xF^5|=@S!e)7C9mRII@@36^Hiw&BHthr&{npgfDaS(YWw zLRZJxnD5l_NhY|khFpV-i?wb@iXcrLDQsqtKz+^wP6bSrRJz7d$vZoF7E4t&xH>o3 z)?K@a_Jx%yibWO6a9D6b=iUuI=0URq2rVv!p3)u1nG5(qXBi<%-?gJFP$obx@QsYT zt#OHrGs<JX&9cGbc_!hoo}4&Ldpv@|0Uk38o-Uz?baG24-wy0mJoo%vVK4%ZbPFC; zpoFti0gG{`v1BQ}wpjALV3AA09GHnOPRlCn!~=014s#)X{i%d;sO&)aSqf+B&u@Vt zX%OD>TycooC?p8m3qdwG+kOVj2~LBiee>%l{uN4Wdo^Hmz-l_NXr^pYHY03m?JUR< z3dIL$1wQlYU`QW8+I5v|3s13bCjDOFY`%frh*+uTgb%53p2d~P%m7yHOIEi9D4mB` zCOE*LX@+n^Oh9?Y|E2T-U6`h2nMR3r8h`gkkDh4Pp!i)u8@FFm$d7MU6#rgzsWG1c zO|2f#+MPb<ELJfG4zxku>;GBBV*G9+T&o<k9rmRZ<(ALow)P`hI3Hv(=(-zjh=nsP zB<)Ge_5)T*oB9X>!Pi;(EeBX9pgRYPJK#0;O{vblPJ5*CoW7_&X4Q;KEl;s5aShhr z>p02KT)j}<YNO_9-HIDOxcj^Od;fl{`ss`GIW14K?+bigKH;swsp$a(3D`gBp2%gA zPMB?ErAVznq0TCYg54*=6FqpBrmW{9hYv@&u9A8Qb-9dzjpepTt`G?CHh-QA&)^Q8 z;w0ZGS1vFBv%lPc^^BV&YT-=fNANIw#o<@FBoQ~^)!mJ<z+w2c*0WmK42|Fq5)04d z*Wo3KO51UoW8b%w8!eUOy84m^)?)SJo(m#G#kSYJicBg8<raUs2Rg^Z*%4O5ELpaY zO=wrOm#i6WH^CQ{pg1js^IVj~vAy<(IHM?>z?0XPzxA=CK~X=)13G?U9E)N+FvL-D zeeW>^UR3~3pm;usD<NHA9A=_!9GRj*cJym-(<}hEmMk0k5dZQJBIwuE&39GGx`FdB z7I*q89iks|iEP|3kkm!%!@Bk__$~#Gv@JguquKX_M5Q0|f!R?$`6XeQWSDlMkY{<I zeWe!B6(2aIAJV#n@^`Kr9c>C{(B*`cGAG6$O!3lhpy<AMCO(@7m@FN{LHv9s^bKQq zlzXTFBJ(dUgx$JHdeVBeFw0aWD>wuoXoILyKSnTw7gHp?SS<U<(WhBY6|TZ20^h4Y zFag6#<8_dbz<Ka0Z~H4xQ9hDc>P&?*bvA^xvdS;RN)zGtP>MA$J?p+F$d|4hvX7_C zGsxxEhiy(i7$rQFCH>7G!dL^D#3QR&49Jnbq`OZ&`jQNTtpHhhCt<&J$DHyo$y8b? zpXCOYw75b{;1`b`^~zePqiDTwRp0B2;XI9&w1|<oysHV+s>P}g>!ENUV@m%CPNv`` z_QTRzuF#@*ilu9xKi9tAdu1YTy1WV&3Iq_{ed?hihu(Qzu-5m$D8xMWQ7lAoOWeLZ z6}n1hew2z!$%0klQW$3wKffoU{Vr|UCe2^f9TjZ4@aVLG+{+hirPjUa7^HIUuhN7v zVWkTkCTe){GGx;1u9SZ6kS_c5y!LfsS%XL7+wLt<k$zIE{C&w6|2*uodVEnW9QEFM zaGYknIY#Lf&V3%qhs2E=Ud)X&*HHwi)LruOJ!u=KCT5IBMB+<FhLJX;=U_-YDCf&h zXh)uf8}LOx7LFa7(hve!GU+>kR`(io^%H*@HQ9&S2gz%*R|56qSTN%S@^)-!oru>Z zjFn%1wLY9h*N^xBGr>*4BTQrvRCW9l9I10qzc9weFZ%X(qq$Fi`qSByL!E#M=`EYL zbTU%y!Q+@lSx3BU(Bl}_v9EhbIUfFRf9==WrcIlW0d!NLzuTh4A6@aPo}VwhzTCp- zp&{52#)Voq$5_RB;=Oh1q3qJ{L#2{<DKdjfMfDHLx{p2fX#0ad_=EN-@N*UesXK1F zJ^rm<_R_lu!wPDfJfNMz=uBe>4UinS>CS2q^4CITU+}h+Nq^h%(@*VbpMT)Nwr$%^ z#`T-f6|HRN(5d`~|MNfK|M?nd=QZt~*WZl{$m%1;cPs;<ry!l71#S0Jr<oY|tM>c9 z|NG><u)X-jFGit!4fS<4lLWRI4eQ)MaO<{f+v{HUYBpcqNcl(xRucUbV<X{n-0uo0 zM1-q4<Wn!?QSBNCI$91phr}{A;I;MW7+?S7Dx5VMk}j3E)s3lRQa2<G7)ITa6<4dM zkUij|QkX}tS2Httn7qq6HjD-s8fEHMMtTV@yFOVz(k23{_<@Hq=1-3Qdl=|Z_kt;$ zWu%(B+o8#1hVYZqE1Z3&K#~rqqap#etEs`0vNa;#_fdwOp~_bkf^n%q_+f>56)kq` z2tV`mg~R)WC?1y(ZUf9|70hcIMX5eWCs?j1Jo<GuKl3$R(-f|=5Wdoe14ylOwcK^) z#12gcu7XrI7B(Ia2jjY0@X(S{g4deDPQyd1VHFW7gjI&B^wM(FhA2}K?ks7dB{(3| zV!|0b8KOAIcdorMRb`0^=UEi^^I?!G-$y9F4ekts&~dGB5ro}LO+UFk4vlYTWn(r! zedjJ`3Cdvxzq&YBNx5pHrs*_T;UA<0_RK)s2(QanR3NJ;muaXND2p$YQ<Oy|vsId1 zWWlN5?dWAP8Q5|!qqnT)w*>!(ZXhx?b~+4KAAvI75jqP8RcFt!(a-#q?b^HUZ1?@* zyW4)28p*syNXN;A^Wbv)G*(}f%Z^x_^-A^(#DMW4Tw5R1Di|zBtgL}6id7gp4htE0 z3pMpc9l0r_^raQL@GIyHf^XxhoG@L>ln#PuZdS2={qnYkS<P=h^l<x&KlwmAgzwZX z*Ng^F1TOldk`$gUKg&}~0P$K1iGY!x+6<}-gYf3ySOHT=O(#N~X>&@`raK9&!q?-v zum3*PdCWArgzYE_nrW8b-u#l=+U<9~1nYouXEM(6c9ln3a$cmKwfNu6jPYUwwI`o^ zIx~+$SZz6rY}+`DHSDfkY!EhzA2sT8bmM5-b?Z&-nSFcOKYZd7?VUgS&RE0Q_P_P5 zZ(~h%vAu-+^ylQHz}(~nG_iHt)+jNozhUZsasmY~usErb@=}O-(BB1=Mf0gMCuYXj z0P7S>>Z$bh#ZP{^{q=wOKs&)kX)7qtB6yB%&NK8++g8xA)tiStaBZJU>F~s*3TNxs z$sXJHEx*Z5(C>IT?^!l=_#6VoIh4&CQ5vskxax+V)qvy@LYy5e6+wIj2RcC}6I2Qh zu$iPAMw~u%5d|QA=2n%$d0sXeBwlEVsN_FHXR9^jJQJh6x&h$4DHJt_Q8<q?>kn?1 zqOj4ut;**3%G7KNim>_>;-Sj$z!@Bhon-^SJ$v!dP21kUgvb!ehe4O3Xk|=(p7F!T zD=o$bhv1QH5OtQ>__0GQeL~?pgkpb&b~TA5`z*?sSrjD$T1e2QRAMO%%HQNu!X0G@ z<**3)lwN?aJOV#kg2LIIm{mHL)sUHbDiMkY`w2<728ciw8g_`2fvm7{id*w5MKUn> z48QPw+JiL0>2HNsD5<za%X`~LwUK(39+J0@<g5P3wn*)!t&u!5;o#c*Dm{|qp88g) zM@ZXc+Gfg>gi@CDX(Vp<q)ceqQ8*(6$uE0BvC3;bYSpauol=pC-33g(@NOZiY?iNW z^Vtw(kjc<q;XEG&*9_@IA*Y42a0?4O^7P3uHt9Io)^A2|X7z;%u!2YOLWqNhnTyKi zd?TGp7jfl+!ub#iVB7wdT|2|~4R0CTnA3a5+Tx6&N4a8Mp2kx7#PMU9SlU6nQI;|? zjY_!cX{n;QI^xC$8%wN|k22^ualBJF-++ZP{2=v65X1F#>%DdDH+h`PF;zH^(f8@U zc`dxyO6%hm+}33%B54V?0|qA~-I&(N(rw$fXQf807aaieXFnNBMd~6cBoX)o{k>K< zd-v>S1Dcgs4Q<LKmb^AXt1xp2bH6$z6NhAMx(D~~&$3TfhPcU_3TG$UM2EbDUvLew z2yc7v)Pmf>nf{wqcAuvo(xt{KCc{&I5+5`wPC`rk8b|&*g=O?4^?HFmaPQvT>Cdj& zcn$Hi#I4D<9>1|3qx~AU4)d=`^OIO9>nD6Z?i*IF!omo?D$K$c>{58s$!V*|YZcB| z5d-hZqsOokV!*X#dAk#z<hSC6Y-uc<YoKg?6@_#x4@Z7YlMgD+r0wplH{C(|GBd*% z!!QDtc;dWE*P9B#3v;r~f+ya)+25Hl{MplP4zg*`>2qCMhcEW=rB(I%Ifzf|O*+<b zmwDQktL2nqbt~k)6k2LI$k*Sq6AR`|RfT^DkNnN{Bi_81C!4G7t=u(n1&H!{&H$YL zNtx*q3TNd(PbUL2(Pz0SP}KuvAR?)gP6uxwwNB+j$dJIPg>HN{Gr>7;@(gr@?8k~7 zz(;P^bw(-L`oUw$-^m!2kLk<1EKRi?>p|XK^-%B^zc1JfX<WVpHt+JtbG<hgQ|ZEW zwB=h07#@&2>m-qRDgb<4hjH@Pzv${oegxl?i4CDBux)y1of@SyFd%V5w<w%tblhiB z*D@<VP*(f9D4gMuPJBxOL&&b-i^LFDsXxod$DYquTOj~I2O3}({J<VM@}Um<XAfy# zJk`N9Wj12R2m3EwkRE>(+xULy@aP@sc1h>z*J>s8-fw+B8~hnQd3JOPZ^*<l?=C@y z>7Thz96L+H!goAOD`})XLle?!GUu%T=EtkyIRlLKz#~WanQ8Fi^1CXi&$bJX;5BU% zeEXcY#Cz5iWpfnHT?i`6&?=6d46caKZ|EamQqTQ_n%BrV;*-ivTPFQjJ6B4{O@3*8 zrp-~OscEA03g^&|fEmUZTz%|eO@GM;<MUtT?gNMi|GrP*JV#fimk^bpdF2fk@zv8t zFEd$Zj^E0fSfhgqlW^3T{IU26@2%G>{;aP&r|v7B=@qSzYZt%Z1q-QT%LRVu?=CBx z?KcZg129-+Skrd==j5pA)jhPseOB}kM9_2-wpfKTe6?3Nr)`qHeYtHX__j_tT}||Y zDx3jYer<iJ=oA$oF?f#b2E59eXBp3)IB}HgY54Cz`}ViL-S+I>ot4$rmxfE~C03)~ za4b(LGcm|bbPwt;9)JAtjEUd%^FNO<(4A4}X)rN=zN@Lp=y{Hw{+=h;)g(2Sge*>( zD*Ze67Z{JavaNTiq2keTrG1X>#+)Enft;|yiFMl?aTktY5QhPhIva861pe0^dI)Re zHEsL$ow-U6ll0{(p^qOwk*h|2Zc48!&@<q5B}z%he({~nxL29yiSItuKK{{vU>v&z z3*?u#n{T?6IvQyI?tl3$Cd-$wN70?_Rj<Aq<ugV{i<v+kf<`ClBQ7yPiR$RdC-%3G zeeC1yGY>q_ZoBO^;MvxWG1mS3=Ren8^x_v`xOE-nK&QdP{i|Q|N;Vf9WlXB2K79`P z%S-Jy>`-K(S5CyvA@K*?^!>{Z`1E6VMGKd8Q=f7)+dIuPN4=vQ@B(SpMhm%zM&0aj z4A*iho;`fuAEq<H*j#<mVvHlb_Qq%x#ymVVZak0S+o6o<r4i$~l3L?OCoWtStSqC8 z4SB{@kbV!wPp(&qfu5WEK!tPv@yZImGTjp1`%v|z@7VirR_v9>m7$X^H5+SA2tvlC zr9`iAjxfS^Q;@LcIyu5B1RLKO^mL+9Y=77YX`Nan>R!W*R<tG=#&X1^#X24zh9M0r z=)<HJ@ofdOCWEvFclge-K?X~iHIX5~*c9U3;Z|!_l~B{<@5W{_b(OB>?vfUl|Eq9b z&R~C-xR&1mmkP<VxOfmut*=+I6l4jm9*!_zSGlZ0%kp?t(JC|5_p{cuzB3&M#dh#2 zWo<xlFF}W^HM3!&+~&J+JzcWNh#-n~xza`86jlf6Dh`|hRw?c<zXrN?wkk!ORdO=| zmKKq=d8)9{YS|9Je0;YW#_c-|5uJ5X$!bR+EOr7aYwQqY0?s07IeY@Yl9t7EEsx4y z(<&>j#d&u2+vO9+cPX^>Xjx^JmV1iH09XjmG6x1!oU;Rq+nG!3(8{3xZSQ+;o1k1O zLNB6ppRscSHZ(GUK^%x{XUT*i3UOf8qSrh#E6Fz%qb|L%Q&#YrRH=pnFb8m`aE;{; z^kW@o<`run56jxSgixSyS&x=+D_Cx`0j18@9{f`K@CW{^oy1aj{hD>DXJHaw(waCC z|I(mV>*76wOs@UF$M60rY)g~Ul|t=&%A#dumYI-F-%h<6$4+W03TMjD<>Lf_2agG} z2;o}A>I6#La}E}uqa8O~*KWM!=D5|+*QQHF^^>hH=OOZ32)!vR>knBRv(-Xd1|!!U ziL;4!-E}w0=qKA}Kliz~+<5al-`>u!xx=H6KHA>?_WRQ&oNa#a3tw(70lVj(djgBT z&cF1PFUKXxO*h?C<)M5E1~P{c+O=+7GAtl}>uQkpdl4&4xJ!7-Matm>j}t8OfcLSl zf1~})pMJ1?;|mYA!E@4>3TOBO_!kGEUD~ho)=x5tca=*jbUX~>dE;;XGhAxi)g~$T zvBMK>-yZyRFVmgIGV*pZ2t3nBTq)sh!<Z=ZT*?CM*)k9v9HK+Kh(+RAlvF2%+UoTy zaH)acszsEAZ(1Zn3c#l@C0~&z(lO#=az?tmc#4g_&LNPswtU@Y1TQ9v7Q@4|Yz9{K zQwl`VQw^Bmx76!2d7e3WrhV_pvu)|Bb#3$ZYng<DuE}$TrC{Qete`)wNECM95h%wm zqNqNF;_nm+=d-LXSUgM_&#;;UUvZPTAeo+E!b0N&H<hFVm&a#NBE>3or2VJ>mbdT@ zxaKo4u!zmA7Gmw}b;#8&49+vii`5Z%5HA%ZO#V?>(tj-Yyz<?Ad><t<R|UihQ{Vl@ zi)stBhiY3DPI&z6VSE*FB*>E-z7z(zqcgG&<Yhh^#C*!K*?f#&r@|n;6k))<@FWlN zNzITd-))w?wVU<aE1R=%BJH&VMRO89V`7#cD`#p*6Mfp+)C>yfh3pZqa&23@VPhLv zxf+6j258IH;|z)-HyxRQmO?wyFM|AuW2aE49&Kw-E-q%pNPH!VA8LMjPzw^2|2&^Z zf$G3)shiE9n4CC+4{)q92H;PtHmpzk8DvAP!C~Dwp@717-H?iB>d`*8%A(+RF3Qjo zOjumIeJj=-8&K60E^BZOKDs|%r>>mLJHv#`Q3eesUG4}@c3$TW-}KwGOT$YW4v15M zfxqx&JvwovZ@6)UR;@|&;hZ`poHWz(M)8t^_og$2mGXJowG(E#kJ`3vJN%Eni*l*J zb#N+e36HcOEqO}Q?s+hVl6&92y(oNFVadH2Jd|9K3h(%_P|BP1scJgXg2%xF`*C-2 zl$BF!Vu`V2kppHGV75bu3s~pTzNINAIC^V*t<R66v~{)6MJ%5-ZP^lqcNAL0N`4Y3 z`3Zm8jL8Xe<QM$VKlKEuPcsnOJ~xq&Iw5b%Y2LjcFD&-i4uG|)KE!I0;SmOWD2cTo z>E)JKg%(<qXWFE2h;!0Ce-`CFlftJN_>C+Y%4&z(H*9XVU9&!}Aym*>Ed@7M>zo&9 z&pw*Ah3gQQTVE%VuL<Ab*5JK7nR~I47xiRco5Kjc?+)=bC9X;H$jP(qAd_vAlv_W~ za6CaEC2-o6Nm#^|hxm7bD3f?R+ujWy_~e14JrpbFvKAK4_C164bC!vJah5WJH;pRn z>*kcnp#k1AaZt(^CnbQDGbK<^1MWV5`z}#qdeUFy3Gx|&U(g`(ES(P%Ps`@PX^b!~ zokLDWo`$(AGx$CH0y<2(q?Po%k~@T2ZNlf!9Ph-5bVmSTgL(p|{Q_VRt{ZR?$3pkY z-Bbl}6Q;|D00gP}FtmAFU40m7+jjz!<P4KE1;ZFdhd1Uf!T4%yzl#U?to%#)kmvdU z?1nKO6M3_4CTQLB9sV<mveG_TDzFZ1^UARHz2X=$=Dq3HS-i(=iUul+lpsKh*AyWU zDvisq2O{$B3f;q=^751RWinOPeD0I3sB^!iaK0S2aCiCH>~nA}oRTZ;-h0ou$FNd; z4&LR*(pYEQz<pmI@+t`+{IW|{TCR9q8gnrBbyzfJ8}JYw>BllvpKsREOI^EUD{Plm z%3wJ>3ESh5)|hw(R+fnCvkqCdOCvb>(1%Ytj_>SQc?jROAL8CN9v*qcJ#Xt<(oAZh z8D8eS?X8Z>Jjz^4x~MN9Ic|yKFW2HM^&GU%m7(g}dg&?Kczs){^!)A9EY4N$`}!2O zPEPf8rq!$caOw_x`rZtCo)o#pG_6<az(Zq={!gA7i|fQKzR<Cx0-o?yj}_T+m9m*W zk1>`qVkw*pFTzZTfJ2xNHc7u$Z%A{{BjZ2w_87vjWMQXpUa(*h?UC^$8I&^DR4OgU zU*c);;$`iPZ+d6qz7RjcBYuUY3=YJN>{MCBF@O}HLXOo;r;u$p9hbXF@S~4C+V=0; zpD|bV!C`gPHMkJdC`|m?ZzvNvCf~DrPsXa(ve&|U-}m0=Ddbhk88*?%<@qtt<N5hQ z_Ei3S;iM^HRCaL8W7#zXb6i;yA7wCRyV4)GtEn~C6Lu%JtlK3^hmmJ6%;DblDNP(> zTxpsb0NO^6ASX?nb5*jmjB62;n|^mZC_Sm)(7*EPm8&8f9m4h87)s}dANp4N;Gcbn zRk)+=P4~T}-TI>2VqEas|J!f3>lr7%=5?<?KD`zgP-=26S<bl-_oApFM&J`?$7kE) zk3Ej7kI%9y^<2i(>V&@e&2Oe2SED1)y4kYabI)trb=Pk}FM(c!&6GVT3ROd0f}`-f zP(waF=Z|=J!4BIb71{T9;@f(STmVpxPXnIqo;tITj;GY8sV7q>pl-=}R6nG9&loBa zS6zVjr7Np421m)W`XT9O-@bjJACtH3J9e;tb{wIOVi~f%tLH_h{Ol*kj}`+}Gobea zANauR_xo_pKmnxp%rBkjbL1aE@B8ZLS#iuQ4PQd*ga}@hP@=_{ZVIrFs``%LC^0H< z`3(w41LNUYP=qlP$v^YESh}-pl!U&bsRPu_hRSAr&Mt(RXxY3Fh8zFQq$U#>B#fPy zR?W*%3_|rV8I(kHx+?S}a9t<J@MIDy5mm6-09>*ou{#T6*!Y`)iTPcaw1U+=g=N+1 zN#gdfljt`UG@K31ICgwsCXCO{(FWo-8KX-tREoOHKqaHgWW<3?HwsGN5(b&G<@UXn zG%mHZE?wTMRkl^70#4Y>Q{TgB=)BM1hjgR?8H5&1D&#DyGew4XAPiS9^jv(E;Wl3L zP~k1Z?%implr?=7#KtKla<@Su!lpQx0^bTO*13aN<GZ=z088vAi5I0VX^3m#mX1`| z>viJXCGfm*O?%~A?{CXkN^}<G;26pR1*Et`LFp)7`i?vn3FISgWLPqDnT_97F6izc z%02S)oipYP?|@wBIVrl9<|>DTRoE`#rocK@2vQ!L&wz~RxjG@S5arO;4V&7>Kk_&2 z6CeFMj8ma2EX*BjSiT5Aq#dD-h|+=d_FRW_lg)*CT7w=G%t{$wamD+U<u0FTms1Vx zk&dw2aqFO>6zC|BRh*z0UO=1Jfs$wIj_oMVSD_SSMF4owH>%5toPACiq#4rE_oWj( zZY(&uVU%57@5CbVSbKyS^&vY4EcaGpX{Z(SYhUx4Sm8_dfBC0>*}lU}{V%`wS6EiP zzJ2S_N7@;bRNHp#NasJzj5L)&Ta}%ZRexVT`Gt8q5b}CnMKd(&4z~*Les`d6-9GW% z@3xQs<p<l|uRO>S@<ViN<G7t!(pKT?O-nH8(3$O1<K;(H`kl|x+Vcn~(!a~veYfG4 z-`bYnb2AFoi8hAS+o1y&5Hi-a#n3ZyD-#wfa2<<6FwpBf7?QN%EIc|n;IR!s>uel& zhUMCa4$P$78#k}brh{%eVH=FA1+K)PYzm?(GTk&2H$WGUqv$?^HTY~>x&B%#3$c)1 zYCSmMu%jmybgn{=k^u(Nq=Sb^tg5j}e(dp6ZOO{@D4e$=7+G($KVTJSrSJuhj80}y zY62-d0EP1jtW9yLaqi@WwstiXGjXa-?0E_W^r?2?Boj&J5d5gBK^4{DJxVdIB+{M0 zVLSH`9N5-|v2<RDtCfW)oQIiwbi)v7q6T{Q83ZN{z@%K&kC?WKmm1JS5oWrCmF6=L z;yD8&p3T$PV$y>YQ`f?gZ+uJ^<YAi9ff2w&R|njqV3AiyV;+Xl+Mnjb)#51(65o69 zHm$Om6bc8zR%!B^x>d%hI;FhStI1Mb-MxcLaZqpxWBkClgj<+Y*TPq(W*8`7;jF@W z1#WtlV97fVdX0~0@(!*T;mra&0Ne4RaK40c@&v9i4&hE^V_S-g8Qs~0R>*LM_DkaN zt}^Ez-Tnqa{sI#VZt|%jMt2+w=%)rz&<yn(ZBeIJ4!%XS?a~RUQ~F~*cD#+kr`N7u z3nL{L%5A?B)QA|1nLn?!8s-#BNXJp6YC*jT*D=yc-$xN72$C06dl6|C6`#b!)8co6 zl@9B1^N<Z*2<M;F(C1^O<|VGZapSxRc%LhLR3PuX?z(Oz6CVv^UQ|}Xn*fVIbiY#Q z%gFS%@=Yv|_8-`X!dVOF%@J^=b78EbyXN__z-|5L`&osvuxjDFkX1g`wt$Hv52IPH z(p5ibnnG!;V&2JIS8Huzr*(I5@0APY=w`zn(p<F<Xbl>2GVKh5E)~v-T-RTJJv>ND zdSi8XBGWnefy4M(-PpG}p}c?ZUMAcYAp<P!CYGHLG5Te=E6-}5p=Z)QjRJQJzu@PX zm|up^Xf2#?T(-8|KtHjRRS)G-qbqo&SjqOt=-$o2Mw%X#eurmq*WD^(bU~tU6|)r< zymo>5ut|s?S+%K}hXXw~-&GNFYK+w_r&;NSviH<k<OJG*;l!AVv>Zf^Ynu*UzT~xe z)^d9wFkRu38FBPH+c4%`uM7WW2}pb9FB`xmM)BGnzobTzC07QX<n0}>B{4E1&#YpA z;mFfsa6!K@#5o^VPe_M32XU2S-zl$(!3W@WDb4Y-!l|%Z=Ay}-zQVhC8}!2ugF_w) z=YcM9$~^+55>`%eXsjORJaFHKulSV)_t2toJc1eHcdz;|re>O@$j(Do4&qq8E<gK9 z&(ISSX)@%3g>b-c8=t|I(eykN&Q==lW_35Bbu7!MsfqA!C$Tfp6j>03e)zj}O%mjn z0eEiZCDvHIPZ7B_?Z7}-!{^eMk@6bDIx)Has4`a{SnmoabKkw`(&*pyDHKI@_)oBB z$E~RKu2(n<bn(9G+w6C(Z{^rhI6Gm@J5OK^O%SPQu+qxA#4|D9c?yk6eBb%n{z2Ra z6}*DhD7Z9Z{6yhfx;U<;;E`~3TfZXlSr~&J)9?&SEc(f`9qv_x@I&3$7n*mMs`bd9 zb)%f_7^Uh*xy$hzb(JvPy>-X42X_gZEPY?E^R4L8cLn3+Z(ZCj>}BP*v<y^&#ZNxh zgU}bWysUJ($i7c8y0Ua-GVjPq$_Kp5iU{gNd1Xp@0pX_V)OVg{S+r8|$gz7iN$a}4 zTay(h_?0f?KUc(0;pghmcEKClp8}wLrUDU#5NG1Xd{R2cWtr$9eH3&(50KvaV+d>4 zVGXTFZy1I1d|VgF7ggRWZzVnCm}-kEoR_pW-1qiA`U`WloaEe*UwD63Hc@t!u%gA~ z|KsC~8&EjA=Y#TwR=ip*t0;AnU6+~bnP7M2v4{SSH6~JSdid*KZz`Mbz4zYss#m=V z*|qvAano;>ok-8|)7SrV1eyC38qCk!s~>oiG@*~kb}%>bpyjE0i0~PneJ7mi0rDM% ztnDjCaFEK<rMdxA%&ke2$k!n43^;Q2xBTKba-j-mtzwt6!qaiIZW>$}WO!Y2jJjHt zZyJ=SY~KCMp7yCvJirExf8KWOxE{aPZ*SM_x&hzIPqyFvKYq8p?w;4Q*T3;K$S|&a zVKw_=+?lReh^6#e##OjA1@DRkV`CSan>l{r3tx<DI<0Nh1?}CpkCM&cMuYM0rqQIg zeFqlK)U_7Q(kjJDn5r+^1?N>9mg$8$tW$BAHU=1$!TJe5;oi2WVM^&>tZ&BZtav_! zahvkDn`El@(O6MkkymNj_)<ts7FC*-Q8M#1PxWN3rr)=3fAlGab;4YJAbm(jrllK} zD4oeS@R`u_9Koms`N{FT7znNi^<z^wYe`Yeq&gxQ#FYx?VH6Akm9wKro6--XaK7NQ zDThKwPKg}mqOh#Oc@YC<mCg%j_#;|rKrF+2TL2L%xT%C)rn?FTP+IM}fq+UsX9zu2 zLc7dgg|B5%L8le3j9>yqt_>gxXF6y7&h`pJm9Pq8DuPv1*&(XzGz|~^Cy&!8>@@to zL`y#!fipL{xhSjSYN#?|70FtdnZC0(TIBl9hG-*lDZ(TJNE?zfb}CPVQAM!>aBeem z=iosG>?Q*?zzDs7WTW)7ybgSNt7Vr8+o{VS{U!rZ>8oI-&|w}j24@jv{tjT17x@Z{ zI28w$!5K+iZ=7W5icBQ+MPP+({Un>e9n7R|19&g4!eqI+!D7-Q?}-a2l@b0gv5C|! z{4(vl{mym~0dXAVxHz8#<{<_GGA7F>tfuW@x}N$Xv~yRuQmL*|(j)Pq1v?@6`uEdk z4FnaWQB-3EB#bH(9U$w<#W*riXOxF$2HScp4?pr3A8Mcb)MwfPKB`cc0xXyHE<Vju zm}J5(3wo}@aKakKX}Q3wLYeKVZ(G9Ty^J-3Sm65pL&b?<gaOU5h{#ejait3uEgTm^ zTi3Caee>3BZ4I;LGG`T0TDM5Mr=eZx%pH=?U?p#Bc7rij7hJn#D{eQiXhiXHh$Y|8 z;KOzMjvehSZ+a67;YIlWoosua-rfHF@BLmZ^nU#}e!boH^1IsO-+jC-TCucUvw76v zMew8`Y})g5bHaZuBX)p?KneVAniZEU(4%l$@6z~MmX>QZc8r<rhrasN_Bb=j$Dets zJ^8)wwbRFrr#==!7t5d{HxkvtV^R60pwq&-8G3igbF9w6v6CrF-f?eR{+e5G-vS+; zJx|)_QO2{gE*9;p*3*vJIB;a4gr(&GLM|{%d(sGuDRg7qO<h7^d}6#k{lrC-Oq<#$ z3bo-Vs}+n9su)yRCvF(0kgU)-HKQfM1S>NRw>{6CV)MTltWCGmak4SOa`Ir%Tg$DX zN%FQXFHu*ea3;M=y74&K9(nY5TeN(A8{N7C%V^-0JP>dkQl&8tXx(c2M%l<<`aBy( zojQp>-NPt|&P=r}*RE;{rpMdF{wLdsy;uPpI!@B~i6@Qu(7eK(H0_`z?m6InHK4X1 zPyt5Gf)1@lhY|8z@vs1E_b8p+L{Komm4h6uW-_Ru;xnj~{y1$vQL2)bZ8!s><Xhn= zbbTkk5KWOz2^QXSX3*Q;n+EY~03&$t2&)WObm?O|^7IgXT|-UB3f#6QpQ=;;%{l4( zNUp;L=@u05IRq{0Q@$iGj=~w_@R&1$R_?`5-&aK8jFz@)NNuefXu@kch4Y$iObQ_= z574J*;XD8gZca8!`Wo(ui_`-OvZIHOA>{6lOO2K5*5C#P+DAE}MY1yn(vNjz-3XAv zo127Q!n)?kr=D!H;9%#CH>U4#MbRJwz^WI^sO6Y_JUE$z55uR=qMSQ%93hg;12>Lt zYO7F;PwT2kRFb6vVvl!m-t$3uvVNSi2`z1W?Z)*?=Fq0dKSC^J^I8@`{W}qd8!3Dg z8uvV_8Qi>e4Vx;;TWt^N4~XYsUGs{w-fQ7J!GP`v`!v{3UC-u-t|;=5?+KgyGIa?J zSZ)vdQ5DWw86P}!fC-?LxC|Nvr?z{QShl6h^=Uf;<GeR^(e8o$d!ul^hJoWU6wX@m zh>tM$+!f3{t*dmlo?MZ2X#c?sUZj`NEt}eMEZ2q6!*`_wB|P<619QrO73Vo75tMEA z?0%ZQd9dAd^G!@Z(0-u-abx*}Tbu=d!0og3<z55wRX14FqFXB+2ktc>tac*o;!Ivp z?bGy37mMLzM`Iy<2@CDjYw@qYVNKgMe+ef(8Nbh^MwLWNr9gQsY<SC^4+7@JP`UMe z_bng#_x0IN!jZ7RnKXRYrQ${W)(5Yy96{O7z~~$>pBZ;EKKAWkAbAd2m*yD*)Asu` zByrnA;W4g`NW<sQp$(u2fVV^hhN4YzXG=%^33&-yo_G!ZROAH8P)EQk-?{?JnXukE zP_1`W4nGkGT9*gu@<A6=G=2I$SHG!nM)qS>#1Kk9tv=;Ri9>REFg^aIL613wa{xu= zu%1IV<jj4-<cEB_vKGn<E)$DFAvp4#amdtP+e~+#OwHIcVRPx~&-Z@eum9$=8F?5b z=~TLf7t=Sl!l7T%Uoxo|IB6Sn+(zXT4w<O@lmTxm_i)LJRU~xAlmWcCiit#R^YLx1 zEXcF`-7^_-3GX7c;8mU^AfD2oaONHP_3x<{kji&zJvc3h@|hSOr8u<wJ!M?RNz%-t z7`lA)G+~S?XBS7j<+gk7qxhQq`~FdwqyzubzI}#AYJ8#WET3^~WG7g4VK~$5(lxEr zm*1`T`bIBmQS%%{f3I-%jkxei0Q2mU>e}htqYxRYJ8fs)c07q&U&w>ITONUv@U|G~ z&N`5%S43&oTl<)*FXg#;j9vYZ$s@vslI%zLOPzXWy&IKFXfWv%&E*3>p}_>pN7Ctz zWZFScpYkDTQM8aZS7GiSx)M~R%PG~f=*VICD{l+`;VZ~Aefuqiv)05;BJg#tuFTH5 ztNJtV)UV0*ZQt-@(uaxbnP=5^mp|d9!@?KgX>(3!t8})X7jcCKuB0j8rWL=<PCE1o zXWlyjn>Izcb@?-2S%`GvFJGVR)?L>Ytz+|0b}){v0pIY(`#Ye1{1?mUT)##1-s+aT zCy~2+D4xPQ`xsXIo<l})FDdl^pa1;l+rtk(oPBRJjBzh2H#*iJAo>>S)Um!gfZbR) zzu}E<XzzH(J2Gxs=n8K7@r#`O-V4uLdH@v0=Rc(Ls|px6-7~<0YV2sxYw-~4NVgaA zPWcHUDRPgiZdi358gLWE^3ChB`V$SPH2QK9|2Pxlp%3a?CBFM7Xkl#p6SxG^m4-Ze z0|rmJ)L7_v5XJTaWTCHr?UDB3zx<o_*B}1dcKdC2wl}}&Ev%Z`)V}eJhufdL|4-UG ze(vq<jrYA43cSdK^jTK?;qY!m7op2gUT;Mfr!V1P7z#gV_?7-j`_!jC-M;s|C$f6Z zjqp^guU)%_Nsl+QyYIdW*Bopb7`a%QknTZ>MF$^QH3j`%&C&Cps|ov~4ilb18PX;@ zGO#F?!EdQkgb$iwl<U@~E>jO;40HVW@#xa*lecZ#7WXNZWf)^D`v%*Fd`cPJ^bDtd zsnTL~KRN*2rnve}!wB_G>dDmSsgLrT@12}kN1ZRm%|`gmRU)By(NzZi|8cOc+JAfs zXS%AnPRId=9YC)XQ&}XF>6=bE9tcsU@<S<{wXTp+Q?V*Aqo9Bo>AK=xVgZ7m%A{fP zcB8-%2y-zVk_u;li6VNC25+;LvFm$R<`mZryweicj#Oo*#4Wc~$)(~~HwrQ)m0b?< zRTgT+>^B>Mgsw8y!*?<`pOYSbomJp!0j&b6l)U;A>e9BMF!*vAfY#NzPEet3LoH=7 zvy#B?6CMWu06+jqL_t((<F&Ea;9?2Ny^LO^jGc~+%%vs9lbM1F8r^vsoR-zq%UL&e z$d=6|4KixeQ&Ftq*|H0_1M1%L+3zY<$FNY+x=Kgv3Tc+#axTI0*};v6c(Z{!%jBTs zEDFL{Jd>wZ5Q|W<i&JOR9YBw>gx`U_%6AnGD)!CaFwWLaqtsfsVlCF~D5=)0Z+E@^ zzBa&McbvFd|4cFXpT^&{_1VLa!5nxImMF2c;9=0^voM#yB1r%Pc_`Glt7+(xGI&+^ ziY0JQZ!kb{r}aS;&eWYkma?j_E*fH!MjZQokd5`e#?0no>ccuUPw`-x#E^LdTH1$8 zpq}e6Za?5lIB`r|-%AT&^rjE2(x7Lo1+GZc_9Z<?BcU-nahP|O^ir?lLmWuoPOdD3 zZib;FmzS@gqgKJ-?$7SjD}MD6J;c4jz!)1boH==#i5uL^FbQ$vEw|8tj<)lJ(Vy!G zI9Q1b8kbUk^6&nkJ@n<TU=e*yyY~%mX!pGNzNQjv2<z(jWTSp!=}vj1>G^a>wiW5b zcD@k&L3JpJSb;!Y4?(vooVDoJ=eCy4THt;BV;^gee&><+a~&CGVuVg-j85(3frD)l zOUSWfN9gt3jL<p*X9~NNOImX9s7o4gtgq>9?|W0*_~sW;RxF(HhkO{f8pFfuz|9)m zVk`q+4Cb>!3kd_BFi$03W>%mJ2KWxjE}`JRG;^Acb*w${D2nm*Te1XyWD&wLoiMGL zxX^^lJ>hTqH<m9>A-v4Y;QnU%NZY$xe{QWUTfG$l6TfZCjpM+HlkoC0Va~Ed(}KnZ z$kR<n9)0{o8(y@wt=q`PamxnVVg^t1QIN_tjW;{b6%jn^C%DNg#!%oLZ$}P}qa>PU zGd0{X3_%|!_Ov5U?QN&_9BPwC&$M~xQC4X1MPBkIm2?@faG!Rhph3!6jw`Lw{&iL4 zWZnpheuYLYEC=Wp%6)(n4HO6PL3rAlgWj@mCT#~D9o_fsB3JUAQ)G~zZNh@3Y$lb% zwrjiLJLzXY#l7zg2<qsEY?Jgyz+?MX=`Ut&uTDrnitu$&>#Vx(EHi5VLU*pF*JYnv zV^IjL%8yFf?4VU80(o+!n$tEfLo4M|w<<iib26ggW7o-t*#-FHU$(lf*}1c=*tn?; z(%!VHM2v%0#4q8Uy$2rw24VZip(Abg?!9dTE+1C2Gqx^GoG6ojCw+1X&Y^oX?()i6 z;;C@{-V;xVkaqp8x6mgbl*?aJu|i91JD2W|1}-s>aUxVpST`QsjCGCut5$*OrGT&c zFnE`BKwYYUwy!)(JpJrxAw7=)!kP`&(k`_Yk*10kL~QUyp1uo@2LxRlO~Au0Qb8*i ze95!KqVb~;l_wG|yqbHJ!j}IMgSqqPPR4pjzOIF{{ilJ$=LsvV8rMS}Dm{}q{E~i) zNjL|B=64Mi<Pn0qe$imz&qk!IqD^@y^n?qW{rglnABk`K74X{yOeV+uN+35EGVS1y zR(pl>MJB=a>e>cN9p#O6xTKIztH07s0Hq6FlPRgx2875u$Su~5vcX}L<o4w^qF~ph zlsvua0z6YT%SmcQ#}*f&R^hBGk7u5Kx~*r!)V1qZBL}%5u#>2iD}--hjVIr$cH7_U zCwq+kKt8?->*h7<SGKK#i`#bkhkvYaE`)2qps=4Ou66j5JMrsJ-SEoy-8bLnQ^ifp zK8_!v>?08L3nf+>{C1@6UEYa@1Sd$^Kd_$~!yhCoT_&O1@e53{(EjbMv>1y&cfu47 z!KDzAfV!{HV}41xJA5Z@1)C}WHwj2A=#|?jaBL%_!6V=j5Lv_gESWg&k63WZPk7;J zpRbH557Wim0{Wr_xKWxvfc2Xzhd2kJ!}K{eMj{0h!fP5ln~VPxm4mc<WEh_3QaCGz z)G1z55A;V-@))X%D;_)ovw8R|!n^lcVb_v+b2UA~Q|^SVdI-<vT^${6yZC+jKE{gF z0t6F=zI<Q&3n=++d&w1r^NfD;Q)2imt2k&eAklptR65%(80=oc&m;<GmX5%8dxbMC z&NdJKw9M&0k~c{}U-=_@>n=F)TV@5RNb^_eHduKFO!_!oT+NanegjCvK3;s9QkCRN zg)^@Lbz#L{LWzSpJQ;$w-Mb2xAi;6M`Lf5Onegl-bp?IqlYJ~V)`7e+{j$6ncpW>1 zPfL$>hJ9KA#2n1rbh<P3d%2G5JyD?_>D;{Qw*V0i+my-lM}?`Z;55AUqx5eZ;wyVc z^x=bY8<Z(~LCIZ5N2h$Ny76t*Q{?E5K60<I6bZ@es{ROPf7t(#hW$|vv#-0Z-n#d^ zlc!xi`q+fOqJ9N4rx(*Av7nS|waF^0rS(jpM5tVQ_GY9cRj&h-b&>j$rjcpn+fn8? zalo_nXuRY}{#EBy-}S!g(8P?_zf0Sso+^ANr-_B6B@`U;I$rriNZJ>M7POsS;cOcb zg=xRWBU~w*i%+R=HXq*Ry~;St?#jerd=e|i4>Nw%4Vd+5eUywKKXsD5+WQigCcgfS zZzG)-=8zQUJC-cQ8iYvRuBNfn$_eU9ioLtB{dr`n<8dAK+0TA9R?e%CIh13RS5!LN zk2{w3o!8yFcgMZh-FMy9ZoB>V$O;<DRbMX+h{vv8o&yc)43w3g|0r6%nlzOgHF$^| z%{a`89&x1=;ArVAUTUn)Gqbv~LS^R|_5g^A`EwKFD2mZrFlILam5zHD`zZ_BFDaL( z%UH!e6Z-H~hTpqqZ*(g1F4Nn*iT!Z+=1OKe=_O2jfAI?sx6gd)bL~6ddJGzy*Ixee zSGM)*u4&(S<dOFEhaYP1{ncM-Z+^?Gao>i^t;2h8If>F47lk7W76a=*TRegx5{6G} zRxd@dT`Q!tbpG_GKhr+?(T@hkQO3t_yZ>$NXWiQfKhW{r4BOPo*}l|1%0KyD83|qu z{$XvD=><EWC+Rg1@Y6#gk4QfPV2*XQa`v07!|UP0Cn7_u6jl$l1s8FvSg~jOkRB#4 zI{vcnp^EsC2irdQ=Y7fku5MH>rS8bp>&m6B92{kXM|EF^4jqo$4&z;ei@()tkX=za zU+wV|h4a;6s;~1On}zeG2qHEbh>Uv&U{@-f<y!)kvm>}H<Fn&{TJ>22CwNxrBvu)e ze|G#1Dw6>5)$15vh7}8En2bx<-939gVYPN%#JeRB^0ExhVOkE57%U27??yufr~ZUh zk_xYGBedR8*`<389gsUH_HeVg5e9m0nB~lx$}X+KYzQh$omo+N=fF;QW%9P1)i5FP zAw$d#o%(^}dj{>|f?{OWk*j6a%8~%FGR<zC<ZZ)phEgT9Fsc|Z4H*qd<ehN1iIR*< zWuLRU#<8O@f6Ec!4J0}s@!9kpfEqWAns2%h@!3vVi$s?!*om8l7SAe~O-DwdLwCc< z)R)kZ#iJI1i%?3sS&n{sWuOY9E^ATIxfILaSXTp=n-KL!(xLn+V#TivYXD(l)rQS& z62bfooxp3~`t~-0VqsiGG4-vYR3E0o3LtZJRWMB_A1x`aR5<%B3IOOp<*UNX066oA zPz1Qb8HF(Sv8;0pLLP2Zrvlwg9ieoxQ~^B%tu1IH2vL9fM}OSD@s+RPJKQBU&dQQL zA+>Uka!#5if9p;L`CLbot<pc?shk>=<+j=x(59}_PP#G~=gLFHgmfltd%sB65zwt| z#yYiZrtOj+<LVuG9J-Jew0vC5h7@kZwTz7$^jU3(x_AXXmY}bT<5>M-&8WkEEx?x2 zS!_blG`eGJI{t4w^mVLc+0^gY@pgb2_hl>{zcx$lH?&*txTC%NRj+J2QGCo_xeOTT zbfKy65#R;c+&jRdJup&GKvu-pV#_*;pK{uQ{?oN2*OK{DpZH{Z>d7Zlo(0T0YmMxR zho#il?1hPT{J`FJ;?RD4)UqKS6DqUgoaE`CF^V`k#VAdo1>48X|NT4K=C|De2p8Dx zdAuFie};Nn#{|h5Tn4aHGD_pPwwQ6E$+l=+i+_a$>InK(>2qo31PZm&Q8=$&JDSbD z7NOgUTNX>jzzq?T`j7_eoMAby%Xiz%;dWr}S>nSZmW<LNFKz2q+dc_TUF8pW6(R?K zpBHUL-Y|QrjgOsdk9`l{>cecDx^{D0vkKn9jJ!VWp>TqtESl%41{sf7o}m4V(NUjd z+5b6&ToleXY{4>`(p@;*jy}1&op@${yKvxmo5kYW4Jc=9Kj6^(qfn&2c#%^pYzGhu z7`_522*s@6K;b;XQhGNLbTdvZ!o{0Q$#s*|mq|Wm+PVp_Pw5A{y&#i!3M8H+U-9@A z7GHRDbY3v<9zcY}FhK+1C_VKJZFS1#xcg9f%b$F0k}^8}r&-XROWCY{*D0)?ZEgzB zy4Q#@pfb&GCPttm%V#@_(wQ{PPrhNZhMEI_?*gk@B?Ms0I4>?N*gTWEnHk1C&(c+G z&8}T-#V9_5>C*<`i7IQfkVrD%l1fOMnTPOx1iy4oKeM}S+`6T$zNQq;^P%;$c`W># zc$^Oqv-TmjIqt2`NtPnIjL<fC-K{s{XLoUU8Ne2dgtfg2zo*Eah7W6Pti^(U*|u)q z9szG2__DoPJCO%KzEMCwpsLK&hci|@xa6^K(IRET#x0rrk)Dhr4cJaAo^)m#OQKPv z+J|4{oeJmW@F_pZ+f?ZIP$9*qZIt&Uq=oYZ1`fKh^7}OmK(qpq*Crfg|G(IK({H_! z>pt(?c>r)PfQuPu%nkHNhoneNp+w4zL@HJoCvqY!DbC8WqQw53Z~hjomHZ!ZmdM1G z9oy7QuVsfKDT`DTab|Y|=x#L7m}lI1$n*U6srO#=Kp+k%E;>5*p7)$nr)t-(UAuNw z?b>IT3&8Ejf~~ONMJ;Rm(&H8z*qYxyK5MmaaKh)6MirPq$|TzI2NpN-^5shxq0@CN zm1tX}cXDKc#0Nj`#3^k`UY2?JU&PAk!nyO%dX=%p49Z(9jd$2M$p<CNP%Qhv5ytkE zcTH!TyF=Yv<?EAMxA@|Lue_c;dz$`$2|9GD_EK%5`Wo_<r>P$&aQ2Z}IGguDHXq%G z(pk$OCu`)Kc)}3>g4Nn8FbKcMWKf0k6n)RGJ-7ry>3m{z8y3zkR_j8maA@VWg5(dW z(CXZJ2(R^d_zaeHA<Vx%LU6F$3Cm5jWr>kCPb#^h;PoH|kbEiLTLQf2)LqpQ);UYa z*Lx4KtXaSi0ajdG#sGl{r)jdWFLZD6%CN#sc)~55rL(j$uTtjnT7>wwefo~K;9Kp* z@vd$me4nowyzgPVh$TG7Kry&r!d6zzOy=p6CQvYsvFJX^Db18Ut)EjKwz}hG!3VIY zkpr>o-pmSL+cW8tuK3LMnHq>tuzdw{Qv}DP6L#3qcM0aF?ycvl=?WjjPx^`@9b0%T z$diACRSbcOv1f&psvgXw72#{S+FZo3&S4e4ag##(8KzG}(d_g3uzpb)>)ZD*zFbGS zz{UuiEIOmWk3uW5opjJW^p9)-F1claKslLv+BEYV6^mpN`0>xL{8qu;<K+Uth8>NI z0r{d%IVZo6A8}F&idJ<Z?RnLgH6$m3Gz#5)(-TJe))5F5$9U~D1+V0>96Y424X;|) z;3Y6CfqUD5vc))2I1^TVKko@kakvdm04zBctRq*d9*MwFvdTO8Tm}(G+baiv)*J&S zf5YpDQj*vOr|6ThlZxh|QeFD^r6?{w&_xHC<W!*}Rb$~C@FH#dvpzlh{sQ?VE+gqr z<Qr01*S)OHa|&JA%F8K+u!BQ!cf$MJ!zIG;ebN?AK5kV&OO+gjns4)HsoP=l2HP;{ z(rE9q5PUW~^d@$ji`b5xqqx{?orb2y^N*`_XBvJYJKOsKPvm{Y4Sf4+!bl!IZFo8s zZgOrNMzgQ9U-FFd*tSAJ8hr5%uCxcQ>&yoOG=PyewmIlO%4V!8ozwo9hv^sJ@bt&l zk!1&Nly}sp#xbA#)DO|Z8HNB&`tXpnDhC{$Gkb`)!w#wiyeT)j0{4sf);GV|{n=N) z+P#9i!0a7FIn_7#^{_^8E{;2&cV4XyLc=jP+cS<dupcjd0dpMdv+<RgzRywdi-X@M zN*`?98PA-)|KVI&U5Vp5c}in56^(nCSIQF}D!H9EMNY#<j=SaY^jpdwWU>lpxD%I; zSakE{mgCNhYpHYht2lDx2;&^T)GmFDN@!gxs@K`&m~G$Q%o`oUNDkPq`?r7k7tA9s zq;CEtR?cp&c=+(q7*4EE55M@gKHYur!$+C7yYC5m+|092&b{mCW*%TjH-pY#J7r@( zF!VDsGkkf55O{!r)Mc!1zxvg$#pQ>FQ72EG?0)K}ehS?R@{PPRzN3LU=LG#CW7^f@ z=^29Y^FviQi$w7C$_d)`SCRX)d)u^SYnJUUEVziT9>RL_RL`bPPF>kfzIql;3>g3y z9T(5?fV9#jhq||0jA?IkYRT*vT3O~I%>Mms9=>-MI*sL6KEI9I4&V7T;y&K(-h*pR z;J()pikI-t>&UG4iul)Ik5Hg-Y81}D`S*U~k(UY*E7LzK!sqXI*ja7uz>FIhv{acX z4F-nFeII5VVJqzI!0of;A`uf-e9Mt<d$x`rT>&=!qlZFMcq-5oM#2~rl&B8YR7hz{ zG|oGf&D&w*oiO1nXDpsgXJ^%e){?lb*r#D25Zyq~#^9mCRazCD96(@wh(Nc2DdbZ| z!Y27#T&1xM;X0E^!xj2kL+PhcAuGMLa$aWDGD0613ThR;3PdfD?eyCx&MJ0`&iaJL zq8bY)JDXSlGx$+>0)n#|nvKXf(rALTuKGBn(HFE~9#to$JoZ^-yF%Z$ek$zbG74{S z)#BAdmj%+^e5IX=W%1NHR<OcUu-oDJKD&#eh*oi}FGS0|f?`_>En!3%ZakHtd{*zI z-;T1CS0%F6ZYrIJP~`48bhKL^o9Zs!y4QXB@BB(P$3*@5eRfkv!M4KSyeynmE~pSv z0aiTiRRy>fDk^;}V+P8EXD}1m@k1x3(ob49zH~rlU5DRD=ODqls*SRAC1B^S!npF< zi#rWB-1^`C*Wd2G{?$M44zgjO`H4gPDw9n%yP(446%WgtPPHFwMIpm`)5w$ZV;ek4 zS2qN-j>XeBiAO+RwSid*sG1-ssKwc|){W^@5oks4LWCW(iz3#E&z5JE_z$VG`&hCs zImiQsdCC*+$}X%O)W1HEH~73*MZ$e7zogcEl)AR?<1d`)KKzj%>#ni7_~kGDN%w#_ zlMayRh;?h@#$(&@o%P&{FLwXo$A6|f`{E1TZWLm>83c@=jEvGber%<MtNh?W8&rYs zL|K|OS28w$Z~W!gyFdP;KkClC`dU`4_n>&XeB~B|!5<VpgLmUAbcX8^pWUyp+1C2% z5=t?AJ7alwi_Y!=ZPJOlUqiTP#eAL8Y;-UE55LkK|1W-;JN)5ZzuUd>`Zdtl#eib2 zd*;M$+O(8mv7+NM9q`q4i+@oPIHuETjqB>hHLMhFcdvc-Axg0WSVSJ^cI?zT!#LKF zWwIW%>a5RHhsS4mc7l7E&*&c_Q-C~-;us&!hYxN`=dDQ9t)w)ub05QMn2>H2KfJ>z zx$mQJ{_d-{sl1)t%<jY8fqia{3P>!OhfruEwTSQJmQ?JtJTioT=Joru**o3qZ{Xkd z+In~V%y9;TD5^)X(mwY_ckBF{-TcL?-6|UruHAn~UM>s)049`QGm(MUHYmrCClfaZ zUe)f%j(C$Oyr!^h--bWfQT#a%q3A`mmBqqg_}V(9=5y7;Io8d{xJ-h54)0exN!iVx zBl(k7S>-*AhwPw|4Fnua?>n<dpT(7opo7Y0`XoB3G31d7XRVxp0^VA*G9iOZ4tyQ# zsBCtlj}-?_WUX~pQ#cFFfAdUVM8)Px|EPNnQSo(C5>>rde->GT(hxL}WA=4r;k=B0 z?KLc%H+Jm8!ud=$djy57i>OgJ)0fdUlC6vjEmZOjqYS@7`#X2;e0PKmBeigzqzyz- z0*|YVb+A3bxq|F-@y`Bi4H>q;BF?$<7pRxv?$is<qZGu7hDn{7D37!zDzaK0PO?|F z>4*6mib?&lX)%0=LBDCzzalT)_(!=LnUu-Ci=J*shxP5Xn<$)7=0N-7$HA4p+d-?G zkg-bYn2fAn>ZJN?TsC1*{Q!4Ay7$?|*BHCl1jeeD-<(9dAe?ann52<`k4h3ZompVP zL{~bt9XI+NwLem}*v~QP$$;6)0G^6)8i-s;I18EdmG|g_bpJGmD-ZEBZIl>X9VsX) zYtg~UHFX0k>i1OHqr01<$BswgY`-VYP%^Svnr6&Fpge2!`s3Ff=U#m^@wC*?wa*j_ zyV=~$Cg8*@LZNRf!QDC<LH^u?AKr$>_xY@Fnn}-b@ME$?9?DZ90YDOwxAbE|ki|0S z=)H^R7tWvW4jny+!kPL}j#GzXy-ppby>ai6b{LA({rOk%|4tvUbH^-$eq`}(+-ZzX zcgGpaJWk=<;CU5AX(WRFabqxtp}zE;|M{sf?=2Itf}=MTqlf2nk_n-X(7nGmFlj24 zwD1%3Mfhiai3L)W@=MEXTD+*-!77IznnLj(JnMV$D-gtyxQ2+TxBjGpE8Ms=u>>1p z_BnYdg(c5Kpb4g~EVmoT%3e`2b3-?ctf4*Q9%u}A8M@8T!~d|IMNtC&Qm)!p6_15} zyfriP6|KUtr?df_X}?@+>`~*4^mj%kamm|20FG%2m>2uHf@ZMq5=ttcOkdH7Sogfn zyFP017_U&oL?#5EMBNe}I0Xur5QzudQ{;beG^iAbHppSdA}W|^+ypa5A7!$O#j^_M zwGG-O<I8pSa9Cevyr~~&_EnI+k)y~*+qeod^Kd+6`OQ8GV)OIgFwQ6vwURYI`g&G^ zNw3101Rg3w=`%I!i_d84OnOU?^b_1EYwefvC;b`?xfM>eJ?@Fo{|~?$YNXVAk^&|0 zi7KAL@ZiDloaO|tg!cBU_Mf~{1}h&|-Ae<W&!R89WW12MhZTGYtGz|!8()~Y|1JNz zTGw?r`YNI*Yh&@9_!ahE3TL4yb3+8vR@8uV-0Km!n(`Ko1En%`GeDZ#xT;E;;uHHp z)9ULvd2nwV^faUJmtn~zITby9m#|i@DxpulF<sts4MC(wl2^E)^p=L?kd}Rnz^}-K zdZU-=QwIUmC$vty<r@CrT4N~3Qq*C_oGz?bx5>oFiR*KCBxxFq;)C!+-YY|lM=E(m zJ_#7YD@kAxi6`PHuV^<>HmCilbOysl2NRQjWDK~O|2kubMm?Vgi##lv4iwJLQJTV; zHd*r@!P+LJx0~9}bpO$(et15dEu!6KtamAA_zJu%YwnTXkc4OOw%o`Z_nP>^7ruad zyl*oPxt=kN#zVRZaKT!mFBNX;9#l3vCdpT;+&lJ>)>=N3L3q}@p7_{gzxPjqyvU+W z+TZ&}^Now5&Nm%DdF;U*=SwfY)Ez&5JUS9-;FoE-P;jBh76wbfI?l7rhX85F=~w1= z?%s~R#kq8J3(RNb0r&F|hT}sw5R9cWV?pV55Z4NRm0b(wzyp7a`Ne<pr;L%<f8^jZ z-EaMm|1$<Rce-a!Ki7TiXFrC~)m-<HAOErL_{r@U5D^(3ez<U#eU4bfzlk9dyCKkd zgvBj`uH7JZ-zKo;#R$VTV*cAuI-fXk7$7cC7q2^}PT2^fC4rl1xqHH@k~Tlg!|atM z!IyiDYb=>Y3*l`Fr^4AV70wz>NDqxL9h=4o4&G2<EMI%b2QEIyThhWby2DkcrlF*U zkj@!24D?Gs>wgwSzh50rPL82#(@^Vrl+unD)Vu6u9<+~BD!=<E8aAK*zJHv;IWqZ& zOZs;g<A)H^NbpytaMrk{IvqQn5~NLtIx&&iWH&2F<m>{XY)hr4%|BM*oDPn}B_4p$ zT4+yTr-QoFa1+4^8mw*&^ujnzBcDOQY)2T)BE<43DNtM)Q83G(t^}&sQUNVvm+J_2 zRHuWoF<Tbn`suJrAr-_blojR~wDVqNuw^o?_jYhvK`DSdng#SCia7^T4oY=fp%4;I zDMt~kG_pk+m4iAD-+8(UDlX<bMmZF?!HEXvMt;JPMowUz+`G}CIH;VHR!%TQC7lt% zSU4)OP3sDjWv={c(?nMzg;^`7<vzr6tB4k+0!D>T69VFId3InGYdrB^WI!r?KrD?{ z`iyd#ca#Pw+Z^l)$4<jTOLFVt9>NHf70MDmA)nsSUA%q=3+K;t2Tz^u9<aDTO=TcE z!u>!wK|a!7d6LiZp_!j^6b-E#Kfx*5N|O@QPP$6~6@S8EJleN;SbM0<z|qO%67{qU z4Hu)JQZXf*11Om9T))-*<KO;V_xdZZb%*!uPnkdmRH{w5aiVR+$-0Mh6}a%N7-<kJ zOhY^u6byGFV;=TBP2po1O)rgoXI)7HXT9=C+914=ck&i-b1!L#V>%Z$<P}{>h(z+_ zMunREHxF;9boRY?mm<%>CWAldIK^VX6dQF&(=poGJau*#9y)}N;t&7Whob!b-gm#- zy@rxR3u@u>!@rc(2l940<~=B1XS)yM&+22J{6zQ6sT1t{tBVdT7gV5<B)?wu!42KT zo58;!Z(zasPyY9Rj57Fjl*+95(~k9t4l2|W7Ts(<rd7IwJgr+??AbB14gSN03ob$K zu|j&~tv9<Hd}_X;B|j_KQIs;u`RG6VZ@RO;_BSc-Vt0o@#g&V6jEmy7t2_GaUfKb5 z!-Rf_frbia-I=Uwoy5dGiq>Fk9kCLNZ`%v6uoBLugLAkQ**%9#iE)TdJ+|^OhJpJ1 z2m{)x4Bl9~*<F7dAI>+HyQNhuI8oRfdWHce3NYKzIu=0j0fwkhNtW~sQa9G{UxmN2 zbLTEmZ(4h!a6YsHi%8ln6ZW#=fve>e+}5BL<$8~~E<Uf=a{1C*euBST*0H;$x|wl0 z`5RZe2bbRJZoPKCTSP&)LWjNzq3d%;M}?Hd0S3xgc?^!pbLw4XLy88?;5j#i+vXr) z8?q1oX=~JtxFb!eC(_C%!t->}NtisZa(nY?Td#I0Zw%6zmcIx)pekVG-^eR?RXlj) z+Q%cV*5*0!Z|fjO*BZn~JJF@UDxbXB9HVSzz=W={S3294ge{YjhC1;~J0(O#kb^HR zi#@f{h_V^jPO@yWmUSo-4c$;d0hGlcjQoLVX(x*)KGvsqbtAj>cXKCC<HPwdE@f06 zBNxIm#1oJ^>4J!ZBw96t=d0bTDEkh@r3U=E!-WbLe;Lg7vO&41GJuqkky<$0Z@l`- zE1A@teF+O^+G)90qFj_M`S!R=NYw+%F0E*<;Z8%}Y^TpYhn2}QeVqWDqrMoi-1hz) zWU6A=4O_IJHDCSr9X);!8Ci>@#3mYl<g<BJ8Rd-|4CGxj)i<G&j6Ez`)#3(xL7HS@ zMjSP%Rj0#}3o_y!3uRg=E9f1BP9PH;_)8<pn2Bxbl(gazq@C!@Gtk9V50*!>eATg^ z35@0Uuw9vNa3$YNBB>jdQnHAj&Z@k1|AYN|_oweQFE<`lE;?CKmPl0<zOkN%7p&eT z`kc#eT?9v5X6<I8Im05lI3u4&S)AaPveS-a1<Dbe$x}Yp)ycK1SEvL0^`me;ij2;L z%QA@{S8vl!sFRu~$n#~1aub{{k@umaheNAz79hl1;z=idQfBGxbHm#*TzKt5_mIAP zpGtD*HBGxe0nR6p<BuwwO>KQYdPqwTaWqHss*4mAaZ8#v6)uDZ#4E2Fj6Uh0yq4L+ zd<Tc^VGD>BPRVFn)m99HOpz&m=6eS}&rTi}I2V`P2)Qjv$%n=@b)_+Fc*%fd1ihsp zM{|#n2cPY@y!ux~P5bp@1}CNYGQ&*(k?AU!{mOWJl)hc14r8k!mCPtGlaDxr03|n- z6{UO>k^Uf)pd~%buqRm3S#|{-VanZB@5*EOJhH()DV)BUmz0&hwON%9?|es&=9PHB z>M=0uHu;l=gE};aL0P0t9g?u{=wSt>_nZ*C)p1#fmy%e6hM_2cea2PT=nPR&II{`V znl4iq53J*_bA9m+bYyJ6W{czW+xGP?P%1x5aam)nw7Ss3`Ay-G4GZlTU_|56U_q&_ zLn^$*(6Z8BS|@f;E=<8KMPtfaR^!H#kDz}~!!{u{CqNX9yvfnuhzGZ(^GKa@m7a~J zc~Oyg0j<Cz?@eXjoVe1xPUVdEe%VrcH;8M&GZ%S*$K<=oW5Tq2MHlg@a(X4a$4^Ss z7}2Zw_57O{hH;ZPULQ?oc;CD5j)-IxxzCg0YO}o7mu;*1Gq1)4@$}c3o2DMA-(KNd z{LQlw0rrT(nf|aH?XKp1;v0l39g!FcB_H8<JD9sjkG!gI-?>Q9C+Eo$Rh%U3>0tHB zKY7o!)kB5UZ}<d2?VWW}r;7$Ce>|zv!quEN;aJb+Ty3uE&~aW6^CBPgc%>gq9anmz zc?hGGLws#FTD01ZbfXno4hqueCqCd69-!ZZ5`h)}-qfA+9i<;~4r6-foVug5?(B!t zJq0H86eQu>n9qOe(|<c~p7u}A)&sDuP6h$qP<HXskFDjB2c?B{bL^o^H%@4U3~;`p zOO4O}?&rI=-g+zjvGaG+xObHPiB+_jDDEPm^Be{@&T*ZWTa%98qToYjTIaUiCpj9g zJW1SG|4Zw~9MvY=C>moG>Q?+e@PQ9>&z(IRy+Ya_Wz+CYr97<>d0Ty;eVw$E3)~R! z4qtuy<+sLB@|Sa9;W_TqSnc+0-m}o{emp9;bzi2Nw>=mp=+<M&1!Lkl-kPA}{QSTC z!|wIhFLtL+obG<>xBe%_h)dmzFTUJ;;uD`>f&N7I{EN@ws>HA0kjx;l#6sj6eS+=c z?aS9N@Y6M=b;jg?NO57Qp#q0t&d<~*?L`^w#)H+T(H5L*2$L~`i$9jov>vU^<l%jO zq<TpI1oVF&5dWWo&EI;dF=OEp0}E(WbFMT#c$P@Y3Bu(A`Ac1e{>d+1d^6*A5iwkt z8fm6&6Ib1fb?8^}<yD|y2*<XdRk`iKa}vX=1>6E&!>6|%1=3!W7szNgGCzQ8jmI64 zz)wJY+xTX?7wi8&9&KbroqX<dpWFD&zxNxDP$82k2W<S=P;27wNR&q&G8lreTaUm% zc*z_x)f$nSfU*O!GZA(eg32CGrww8<8-T1(2L`$CD=i)I)=b`UZ&y!_@@#Og4u7-4 zwW=FaXv6(lGw+aL$zW23WMa0R&S?@sFH_p^^^fc%*H2G$72qn1j@@NwR|`c>-^dCw znc71|ik)}-U2^rE6X{q=^Q<COcs3NvukS>ax(a_4&IPNitfYS|g@En7orFSIYf{VU zy)?B0t-8V&9}{sWiq3XasA`$&q}kOVm1qu%%tMPaKf$$;sVorx)_Coh%u9uzia;l= zrF_=ih;`;?DJo@EN>8WZ+i3M!=}M|_gs0LO^ioc5taB~XOfT*V{fFR|GQk7VQp@XU zlqIIWi)HEJsvFk10nsQE_}Z9Gt6SfTr`EPR=Js|I+jn*6-@4X)_-8)RJ^zu9bVDet zZZD$5grO$wxDh<&Z`nQUR6V6%Dcr06oG2;$4VO1FDL@Xc(Ya@Z9|1^#sA%|_`_waV z)|sdaPe0#UiK!UbiE9a!Q}W5a-Fv$?&RyvKDaz05Z(Z&V?>`tmF%L2dJgv{oS3ycZ zc*1-jVZwux$P?ec3=B-}A6Lb;lHIl^Z&^Qf%nnp)fCZmeX4+#7UQmP*S6bSUc|VM0 zmV*!BsC1IgmY6i?(niIT6C#xf@{R4l)9@%F!iC_AKgc0^T%a?l9Zlyy0iWo{Sy)3X zGU&f{9A0p7N6YLxxUg_wQ21cQyZ{UeWLvT<DvF-P(peW9r_P?~&YpQbeqiN|5fsKF zz=90%t*pX%oHlUf(&g^=KL5Mj*Z=Y_^O=;E^Qkjv;wCi1V=CAjj8abWSz_>(&WdOM zCa^A=p$$wjdtcTs*P9oBd9k~E@pbBZsr%V~_#52|zxs2~^Feo?9d&PBa?=SGXC`)a z$DTVtCr4Y;I@x+rIp{=Eg>!FexZ!4aI4N1jO~sv?_qsP<dk}xhvvUV1FYRgq9GOhP zy|MxHfF_g?^ccXGGI?X|UU!RyjN3PmP4m0E?N|rySK-{zrp<}nl4VyX^CeNKXO?1I z6nn^*18==~5ha(4Q3vqjjN*BRUs^b+A|A@}6+Q=NmJRCq%*JYYg~1y#^4i;ObhyX{ zZqG1Ko90Uq222Zgy7gOEySwMlbqlyaSmKKV{mD9L)6GDX5b&Qy)7B{*l>xG{O6<}z zi>I;xnX`?Bg{d7ZEa1b9mPXl?bqaU5lJxCt&w&Yzs$B!$Jo+<}64P<owmfWET0?ne zvP8Sc)e!<w+C-Sp$O!$o+pb+iQb}xQWnO;0p+e9T-4e=XluB4NE^}RBP+SU5^E3_I z5M=^&OL{Hll`-Qev~3fX(TS617Q0Ad`$~I7cCDarUPs|PLi+*&vGB95`;#4W-PoQZ z-Q2O0-ORoN*(@h~N7`6I+n#Aqk>4=WIPKC+1J9p-9e%+T3;xn|zo5T)6{;B|*$ymc z@aC5yq`dlY=F?64*XLe(IX=%~{cAjMl1Xb3jAwZkEbV)h=eovt3;B2Y%vpBgeg-;2 zu;ifY5AMND8DQO7cgiZ|zLq=ozsl+(M~`F@71=3t@)O_0x1mTofx=f;FJI1AL&_N4 zVz_I2zWkw16OW07a7x~bI``o0S36q2*mvqj{0K^U7pJT`#}6TkxFTEaf6Y7az{B0p z@1kth!r4y%-Tcpqv4?bVVXj%`gKDT|8&@H@h_(EU>wbN3FB6X``a<J0g>x((kt52l zD4gXx(#bc=$Rw?!RdnrSvq1go`&CtxUu>+am5mmM6tVhxX$Ne1{<fc;UcUy0Ykbi( z#ilv?qTIGE+D=RZ>dC9x3Q@%i8Y@S%UcY|r3a*3>GiWERa#dbW>4->1wj=56)yaqW z>+AfD*UonfE<_&UGgiKAnV6nI;oNnnsq5{0(PDcuok!I<IQNi2tA|+uzK`<6@YD%6 z;LyfMK8bh1Gd1^h$$ef{D8Ia@Y)c8mJ<!3yK+9sp%{aELk}rfwu)H@Br?Q2MX;!#_ zY{*0>rOH4ik}gp3yiB0DS*HZ&zBmiI1x#5h3tZ}Ej7(P6jS6MIk{E|ywPtqcQ48e& zrXNwcT&@MclfNh>#j8imeBp?k_77=;DH9o6PJby^qFX*=id283?9!aDYKw(AfchBF zE-cYM6EEq70X*Bf<tms}-X!FmczNWv<w+Z8`5R=J{3SH>9Yjk?Ul{|61$Um?wZCna zu|X1o8gF>SPqP`v+VD|058>)%gT<S*VHeWrn=vq0L*cx}C)Co{KGUx~R1`VhWN^iQ z4-1%D$A)skju0s{#JrT}medk}E^)%o;+cMfOa4q#^+7aa5^5jnt!0G%;ZN>(PJRii z_q^&4b20ViA<e?a3C}|*<NA1;byKiSoqnCVE1BIZnvvzgSy$l<PgK9!(iHA3-|&qY z2j|wV!~@taCW|4kT8Vug6rtz0Bp1g9l-Qg1yx?f*1ve-Zfm>-AdiSxlSeEYgM;@sL zeyZMDogyEp<J61qQorPF8tS*|PZ%xtR)YnP-@qPZ;7wnKsyX8UFEXd1z7yXnCseU4 zgYw(P1tom)90<9-4oH--bu_I#-E5}<<8%Sceo7gU@f32&`HywtUyekz{wrPDeBKfR z`Bl84=qs6)bjp3=d*8-a!iuamZ;sF`?MFip3^mf16y2ml7GA<D;6%R~J^?>l&LF*Y z0^OY3lp77&W9I5E*diaPpSJO&X>6;;*N5|`fAK#LoTv5EQ|o=fZQ%fLh{#~h#MiCx zjPrR}=>ePiI!~WsEbP};mSL2It(!Nm;s5t{*);qn{YY*6ZlAAZs7f}iWu22cFR%XC zz5=;qJxXtRM%mIM8Ctr4^8`og^Kpgi;Y1diS$|m0Wd4q4Vaf}-K~pcF-a+>lKlu|s z85g3CH^k90rduI@eflml-ZsADRmajA3-~3u<1oWb6Gbl8vFa|gC{{Tc9-*T&pMwVv zv5(Dc;ycz)b4Z_5^Ml{{o!{yH?B9Mh^!v(J{*=-T<5J^D_wol`?tcB(eyxlWn6phz z7AG$8g|B^t#)T@iwYpW;qwipGko@W+{9;Z$kA8}s`}+mBbv__%5erILXGJjarU9i~ zJqf?>CGo#+j33;~K~;l$E7K+?JQ|j<F@1-Y?zUZ7)3Kub;8*Qswfr!&Y;w5_2kDDb zSGFIGD9cb&U6eGfg%_;bscYp~Sx(=|+`_tOX*5dNABA(nbSqu9V9o0-Pg^6s=Y7qi z-t*PJ_kmmK^jD^ER&8RVcTj0ZV?(opN`prLPOwTPVmbTDwDWAwnNV)U{5`5ki@pd< z;LChYw8A!|%aw394%EtdO6wUIQHAq1m~)bjjVV$$&4f>1G5QQrq3H^UFcsdewCGn? zXYwjz4Of`iDcb>P={Z5?sB+Y_o-(|L_cFGEP30ey7?j;ftDm$e`27S{A+^Y-{VEF; zLbb9?8NlC3z5*&r2=1k!LRfbPUU%b%M&<7^0!|0%GP-5(-iBxVoZzh$m-KHI)NbTQ zQ7BXStM;=GS5Ga&P9}n_45qQsYRN0k`2+_1EuTtr@l*+8BLHkblfPCdSl9Y4G9Rs+ zRoYvAKha)bRZ6&{&}17p>OTn?LkEjcf!^cza8#gJ_0mpUv~0Ev9`_MMGguE#qHz8; zo0dKQp&#!)__2?5Q~2Szb|0$~`qu4~$qr9Nb?6U1;*k!DvRJPkK1;i1NnZTQWRL;V z5)%s-4t%#k$F3#2b#D0>dNPqHUe>bt0Sf0CtjqKR<*KW+vLpN6x4zT;i+}P@yBqjU z-G_?}2Yl9NPV(2qiS)P5ArCnB{7hNJ#h23FJWZ3sU?cM%ml_bt_r({be5;7nmNas7 zz+s)$V5S7Sb#C}1lQ^=#{laAG<{{;|@1g*8Y8zBPM2fWGYy{Vr!Tb1mBf{`D_=wrE zO6MUIh?5gjz(OI3VwgtKjj{T?L4I0CyNmP&<y?a2^Eokj4C!xlMVng6FU{d4%QJ?; zXUE*GZk843XAT~ZV&lZKr@N2-^iOrqzx-l1#Ah=4ZnoVsRPDa?^>1{a{q4_&Zm#P4 zX}9gn&)CQDF`7-CfEyVEUM|%5nU#YBuR~b&swnj{{#leTGbm%179QYc<0{snZ*`~t z%TIJCKK)~SUVEEQ!m%>GjN<ne7KP(GyOS@Xpqgfo>m)QBqJmhf3iE@O>HtvgY~VL@ zjg9#3-M-&lyzl@E3@y5`R7K%D&A=s}Ib&f3C82?xswaygj0sg9X{me<_Z4?;vgznu zKB31A#oQrqKv68s;ARLauh0-2prG(xXOlzcKU&n^qJ1wdF_9jc!*}Ww?L*p&oV@7Q z2h;+S?hz)@t1EY?Hx{XoGdHh4M1i>6&F#k*+IAPY*xVDv`!o~piMtGbvG`tOBg6;y z7N939&*ZE1{~8uyj^vbSmc<2-FnyRy26JM;;umdTip7L!$}^7AN$XrE)x&=AK)F&D z-~fc=6((J5YnjLp?sF+sxHnIpl}%~a)oPNpZO8sXuxV%TY&AFN#SJNuU1OZR!dbaS zyY^6d=>pXnie*0qTjpHo70$ZU@RND6?cueenid%N`qX+M6Chwlk!ekvIoDbwa$%M* z+O%Jw05Z=A#n5R3#qpAg5d4Nu?mg1&K60$vjy$Z5s)}Y*o{b*TT1M*@OL6FYhYdY1 zBa8MPI@s;Rx>Uc}_FdwkMRiW|W#VoA(tQ=J*aGe;UcYdGun`u2o}>QpNAJW4!J#Y? zU;9Fpt18qbfU+|d&R8nHO`gY3K8u3!AZV!sQ#MI+E1=|;_2|Nv^nc)HY`C_upKzja z=<u-&&~3MwESWE7>Ky=)tE5xOefi>Bv2;PYknRwJ$%Dj$2F9Zih%*Vm*>=e-r;EmZ zig)wIZ59vco2d80M{Un;tYf`Yx|07YmP+1|l=oeC8(DCNKG!dT_R<GD^UM*mNM4c6 z@*-#OmlL3uKJJ&G(IUKb4aMz!CQ8Tgt*v_^>0Wp$n^jmtPunpI4>Tc8_>6ja$fWe* zn{U7;BaC16mckeXhy(VeRVHQdWt8pa4W5Qec`bOf1X30_d9$3e_|2#DMK-H&D_rf% zjPI#?pD1y`eSw8}@x6EF7Vdx!c6;{XZ&76pJRVjieJa+<?GMAFRHfV(U;AF%867&r zqQ~rR+WSm*3Yps!&MMI5gXC-laTMkS%y$iP=#+=5(~42`rHC0E;5|5iDU3%CpNpRj zucwqe(WFVjeKAO?yfB=M%qtm+8xhDa(fC0Mg)X9?!ky~1iBPA?3*-}5`$BGmm+^>^ zG~V_-ztjzezLhMH$!5+K2@0QP@k-i|fo=!17ERydGik)gceYo7hsIn*J+fIo6(7S4 z%ppzc6bPcSKPtWO0*e9_Er@Mc0|0KNu<zpo+xU489{weL-2q$4;2+@}d7m3Xpl{{T z-WZ4cxC9NK1m|mx)G>J2?mXHx_sOBBY?RByF)rhI)Ek_>qaPY(0SMk-)4c{|%-1_A zoH<p54b!)0lQLvuQ#vaj%*(c~OEV(!&mXi%-d+bt7B)U6NL<B(v?VY4G{AWje`w4R zB_b)Mi{<rd3h8HE6}f>N;Q7gIp!UJ`nI54R_vw%N_<>n3d-#1`5WILve)6<`FBx9X zg<mZyq)5qQkWctqSn^HF-}+5!0XBG8u^he*G?6B+d{t1dY-asoVcWgeM;<nxiS`H` zr8j)#Ulem&XfGA39=-PUVSTo`A#TzTj|izVuL|3Y*~wM7!U#6J%6lHXZNClEc5QsJ z8KYwRUZrG_3)&f>C2I1?u*x-8BeZ%oVN<%cuy(C4P^d@Z*cT(1a`k=HB#=x`eyz=0 z&kery<vV|XlDK(?Jc+{D@JH%eK%Sxr9U1GCOAWsatno*Y%Q)44%NrTb2n!r*++=d< zq;GTfg~PFsX4b-da}>h~Y33M*1Y~A@(vfj5`Tjr^&Q)!dr@x!oZ-#NFIB+g%+qFNl z4AMp!Q1#6ig!0|Ib-nw}cfZ+v>C1mYzl}1QIh%2uJL|hyW17?#^&-tHzfkd!{PHm9 z97U>~?~b-LB*g*0Cpl`5ip{uN+nnj!v;B>RXwLJs*w%gNFaPr2VF7%9^atS$%IN&e zy=6wJTfZpLZIv{WUVe$F-{fm7pljry5s~jSB$P%PE@;Hy99Zja!@S?c9C3Pz{g;;1 zspwuqmkqQpczI!Qwfo#>KimEB7ru}$<}O{j6g`aor9X;++u!}K|1P=<Hl!y136#$A zlwUo1j54NjE}(DejBA~vaLVq+3y)H!jF+kFd{LZ~-~T7FG(f(8Jl}@Co8*6df*)24 zXd=(b=bnwd94qEad2|8lXsplHuXxp9&UDIG=_&s>C$SBv*K*$AVLJ6ax~_Gcu92U0 z;660!^mfAovwTtgG!Mz%`1@(X{ZWK9^x4mTcH{5==6{z?Bf=?_T^*#)>1^JkWa&6% z3OT|PM#+SaG{rDAL2WSK14J0cig03GE;TAvtDvowWLO4kTL4uDw<UmE<!0aQ$+@U5 zN^#}2ZGNQn<2D40mdz@h-56;S2AyQ}W0p~S`G-XLOB^jCEvt$VeFyuAvI=M2Ovt?P zYs*yzcTgd{6kg))DvEKMa$04V!eoB=VU)A6j;1lVx@B3CPGQQ#TA`={Or@X-FdLMg zQK<MfuLpeIuR_|!rGQqcYh7qrq;hqI38(`Bm4M<RY!$xZ=)~O##Tv@As^3yNQ*&`u zAuLD-tdUHbXZh5`4$jXTj9;rkOhkEBi6DG^SxXB$?lg9UwZ{^xdeTk2RXR%(6{`vZ zTe`wS1*<~ebe<9Ll;3h#J{8%n4C-gej#PnRXY6M;6XZKLw=cr|?Q6HX4c>p`7k;7J zd-_y&6`>+uPV>n*Sw;AWiz}O2u9=S=@jTY6@%uwQDmfy|Ab>pQvEfc-e1@9NKOF;B z@hRVy!7g>9RnQ6wS{F4Au}Y@0z=^#6pe7jvedn9s>i*Rq|0}FRucgja+^WoR!e?Ez zNriRfVSPz&mE3lKu2MH)YaRJcp={x7XZouihJRHWSq7EjS}ex5F?E&CgH(6|e;ajS zXD$sKe3`%eID(H_3*PcIKkHWhl-~NLU0s9Ep?{Qk<nDcZomvKXhNTnQDxEBNyO1D0 zt&HO7;6tSjfYPqSM~jeEvIaEmmlmhuo4QNsxW@k&eB&XH?8KL%8x@{9bEZ4}+?np! z$rIfWbbt9j_#54+mtW$3qWj{%{*&(a{^0kcIMb)8erRn+`kK~Cdl^ds%dJ(41JOw~ zfk2|A>?(2Yqi|Je6yNBSXD_=ND@PpIszBTK$&=mej~_ths941<2Cgk`+)$}LgTnbJ z%3G9fOhR1<V;BjqDKCq!)=&UB;9kQbYCQ_)yWOQXa9Po@xx_TSW^t)8K2E_=($Wx; zeuR7-Y@06DZzz+8hfwI!rXJiyd3<}So1WFe8K2SM57D#fW+q3#pqe<fIHGM)9{J%8 zN}~CBEVfqJkYT?IY4Cvj$d?7ih1z6~wKVivS-FcmL|IMU-METn^{s_&7fR0QnJE?y z*iaRB8{2WWF-!X#zJq+ac^~*%u7e-p3s{iH@3)EqC!@$8am>IeZ9x3U(sn_6nqcuw z1^Ofl4Wqc#aHB=Igh=)=L^Lhe@(Wm#k2cYjU-OQ*n@VTn7_OufM*mK-N}Ist%6ulz zeH`ODXsHw2Xk%%kX(yWsXRVo4IBVg&fL>h%bQI2^yLo}Kd09mGXoSwkPxq9kek!S- z@HFS(p<9#cQ&dVBKk|WgA^;Z`<Li@8zL!yg3~j?_`0j%!oA*ProxG#{MCoK%P?)Gh z0eI*};oOT=R~7mW-??`WmZh^S!nkk%4z@@75n-6d_NE*rapa@&^D+Z&CxpjNp2Xkw z_Q-R6lxL6#uL;9@m9y$89bn((6UJ-TZm>}Yn+BdZ6^oM5EWi{|q<`9bc(dfNW%VnY z+qZ5<_PHtU{{07#Rn?ct+s(qc)vK*dT(v5`bnzlG_#P~UTO%x3+!Q1eT>z6!PNT~= z;#;y8B{yyA3Y+LDFUF?Ev8sNC#bCZXq5Y;zlrR4Lp-U;8$uID*I>P_5a^Ekc{6td= zoz{1Rw$NYMY35Lgg*9X*eYtKwbXBC4vhFyZJ%fB<(ZxO~?k%hr>z-w#H8u>@wF+o+ zB5V2T;6C;F`uX$e>kl6~lCc2Phga<9;6+aR5z8tc#9An5jKqRmAI{tH<Gp>yG>h(T zj>h;0YtF=vR4yL2pc}Xo2rl5JHMUmH3yewTDDUj-E-1=-YSXsuUmBFx9I0jG5AB6A zYlXf_zj@%m94>TruwXaUy@X8pz$}vh7MvZ2&}wY~`71EM5)6m+o+|-W_k<Zq8uyVL zqgX#43AG{ihftHkpgxYV%Hp+Pg;#n2oB8$edr(c@2t$}Hhs4hVKVE|*SB{|QRet4N z_=0Ow${0OGF(MB>TNaPxfIRCXRCtenmCTO?002M$Nkl<ZlylOa_ZiQm&S4f8JAswF zfR=k{(TCZ$+3z+UY4Wm_##%7vM$9NNMMnG^JYht^U2vNZ`AQ09di+z?L0WDsiX{{m zkT5Tv_}#2mksH*DFOA#B%%k_@uXyxG(dss3_O`}M1=lv{VGe_`5w>BU%~fBpy3jDs zbzEaHDkC0o-9V7MX`Fb{zy%)tq6JW7s&IBOE(?aee6Y;Qs(cw^em)~_%sDuSd@Bd| z=SiCOaoX5WTKFGJ+PrJbRB0@GC?X8;3!nRraI^DHxcs#`4E=iEeni>a$4&iNIY}oZ z(gL>@D!i4SDzAJ&Cl1uVJfys7*0R-ZtRIVzQC{IAMDgXi&Z0<eleaPkxOp#`Dvs}S zS|0g7`TMRfZtnQ0p#I4`>bCKpPX<vHIlP9x{3@5NpS+_|<Lbn>)M15lO<KeHaQYa> zY7Ks_iC<xf*QYVVLERdbfI`HoC|(>O?Ayd~{@I77`dVH|&Wn(U2bH{=M=%Ai#46f_ z7(&{leaWE8z;>ULc-E=&;1~%IzqP51t5OlBfd_bzdNhroQ#XZ6V4D|xQ7vN8|L|vF z+PgxGXAo6M9Hld|-?k+GOMsYa4eDDQg(1JGaIO-E&ZYy7N<3ZS*zY=~^y^?@*$$;g zoqe5>f%{Q>>KA{x06nGO9<8dttuPzDTf@AUcoZf|NoXkUy8W}gIWP0xe)HSk`9}AD z{l(YVbnbHI*BX^cqdT~XaNOaTP2GWW7&pXo{$58If!lWNgLzish9*|bV-E33y*wtK zuj9@yGPNRC&iwW$44&l?%CCa(Itt?h7zq4>zyA*?JMzN%q>X8Kp$<ct?7VH9Ija`V znGX}kFQV?<cT@8l`PwXoVvJLqPnS^<hBTm|E@7uiXy(C|MLmoPW>f^>CoQE_7F!(; zAFg!&=pX$r-S7Y2?`IQ2zhZMtckKA_?vtPVo87Pe%CGWOS@{-r4DF%ZGp+p%ca(LL z=Mupmg43Ren6^WZxID>`d6OAD?f@Ne{n0pzMq6>MA{H$pEBZ29-|2fGU>m2HPWm}! zR2L?{NKR?IigAOwBNrR|BH%uI(I_|k%6g8uy;jiM(AhY*c)G{C%k*^N|L8!Ah4X*^ z-~J|@g@Xnvj?)VB^w~;%uS3yf#~ViOnYmTE=}f=%`MqEaga{qVR)w>1(`jsJBsP~) z+-yQJ{njHBKl1kTe;Lu$4c12ML^v@oLm`InCVU)590z_*aGgTHO(I}+GwGHVGNzx? z>(|Fl%Z}bjz?cIF()lNCR9uRO3SG;rAZ)m+a5Kzz9uE8!KDvoek>^Cd(OK(bm9mCE zq#>wKbk)TMV~64Dj>0lR6Xi!5o&t?O6#&9fA!2%kwL7Rrxr-9j&vK=WFvU$gTpe}= zPi3yKY-qaQP$8=ou%9%jU|a&8%HUY9l1>;}Sc`{#qV;oK@GPO7RVnQKlt;MYU>tE$ z@opSDK?jn>TPidh$V*S@(<>{i8<f%tRm<*YLFTE_S><ySF2I_gY;FocH`Lw3lJXvK zUjF#cc88vSzPk@yw8YXJ)Vx~#=(|USzK4UKr4=@c%S62RHZOqPa2dk7a-7Y}bV*`g zqJnFZPCtsSUg&9|OA?gKxEF9kL<c+s%wz3rr#6XV`5S-nm))1X_$OGB-G=|P2&_p7 zqzE2b=GvaZKh&p3+ND<`0pI$Sx2xmCYM6R5ep$UyuPWuJ0~NjUtqSJ}23p3^;%`lh zJ?hX68EqeK)ab&BZcMDlQNJ`$Ktp$}p5<M6(|oN<^deYUmJ5!uXa*^G`azV@bmZhS zZ~G&?`EXNt!wZr67DAkPwoN%mv~Alqo5DF0N@hpK@$mgBb*O^W`10mB3R`*1uMzxo zoIoLWFX8X&C$V@Q-?6iM^}-w7B{u$Zv%C>_{Q-QlL>XPxb`fP_v@8NbS_i_ASVgx3 z8gbv4WHE<wyBXJln-9oO<e{QTnjZMYXS>;t?k8lvn@2%(=c+CPP%IB^?~a{4%%YU? zhq|IJoE@m}aiS%nYb)g&*FpEjDjO?e5qbGdT*$1TJRAYPU9{&Btng9N!ieD&I0h~U zN0kQ9d}P%2=qJ4o_#}O)yKxI2U<`VWoZ8imNq_PhLJ3%tRrv|*Y4=(#tN7Lr`t3V( zyzF<hxHyIX)xG44`x@|F*LoU-v+fw;Lyrl->Ixn7D)_(`S1;p__uBn#cF&=18;bua ze2z`bW8n-R?81TZIF`-b?FTGK-C*MkEWaPz?Cv5{=Xs~4xBM(WhQA@ai&t7)s_1u_ zPz&7=WiraIDU@LPbe5g`WSPXA_E(&=#X5!MJ#r<J-Tpn$A}dK_yQw~@-r3jHq$%L~ zc(z5!RI=5yJRxJWc5o0=3PvX^P7IYRF8HnT`J4*pC6vvc`fwgtINQFd56_@ZJ;(_T zZpY}4R5m+Ej`G=RB9iSn8_~gQTE9AYwf-g`f|K7B+Z7w)pq1}d_`G{~YG*e-gOxKI z2aYoFu&lD3GGKK{IZ8ULM&;iiffD=S{dp9le0quB+$rS0mb{9c$P@aH4FIV4NuLvW zW>RoL9^bfeojMwc<?kc|_A%t)2#a#@0ZqMm2*)znUM<!=H~+iA=5$xC;fEQ8^MOP3 zAyPuPmM<KdYuY<JAq*Fr^uw%t(#m{p4vT8qv+_K0O$f?2_+2QGp}<q7UwY#r1Iq_Y zHYfSy5mz<%gqJ@ePt7<4sdCk123&!q!uR6EH-O0IzVP0WV@I=@rO4TbTmO-<)Q5P4 zk9<km8w_Ue;ve09Y7ZL*9zJxql+(mB5A$yEU2xRDvWp5@IM1_adlg^G_i2=8&paES z^ZG$m9@!r$qt<bgvoWk&9Qleok(JB%2Xuqh^XFd60_Vw7ry}3AUY76V1s816&%v|u zmu@<WFT3uoix*?Hu642#ryaOg@e2?1Kgccn&!#}4eVLAMt&IFkRCgL~T%>&7v2zaB zBQwB7(#iAG!=p-P@J*AFuXRm^|NFaq@j~#vefS|q*}MkMA33nI`|(3_-Hzr`BQg34 zD^`Kl?Z&oh{ZmGM8ZU7}NFCu5>c%5n0&YGT!?B!E^R|Zx=9Rn$VV{`D#(D=_+nPto znYthFWy13|@4fR~VD)esmcgfo6-CM*t#1l$VcFwA`p8eOqzl*v%(RScJcShl0~I{< z9hSfSMINf16&L>PbAtzIgkAEIkkCcoMJul!gX~N%RPc}v=9xAoUNWg5K(Hy<lDNU> z^EN+WSd;#FST{fjUU>#iMJE<z32b8%*iwMFy=uZtWBj@Thl&)YhiXNMmii!kz&E~c z;k3^U6jr5hcG1|eD(yWzF|cU}L$uHJH8<dP?1ju_JZhh-TyT8WES!1B_|e?WQ(Qbq zm8*9tJNQ>PhzHfe(Q(}XcVGucua6v-Te;BFvcZx*<Y^wZ$sBfI9HAURt^DnEz2t2V zOTfiDyfKV66uRfivk3{e-t8C5s71LUKU7>IfVT0RSB4TvR`n+))?6KJQOhUaZ(2AT zqhb}GHP{tarK%`{GKqNuY~6(xLf*VpKI(d+{;WR|04z#1cpwkf6*Am=>(EhW)g{j* zWO?O%#i@A33&OGvN*`6}v#=2ycplV8Wz}#Ge;QQiAnpeRN#5omIV^W8qxJM&hs6%9 z6S2|FnBMbCJ()E9JarlQZCyG(vu^ooeOIm|3V-C9gvqvr3ADAv<m<Sq=aITr-pWu? z=d>h_eagbw`3SVMVcGABfqCU5jU5s9E+RMj*~dDUYV{K3H89*8L}L@f?Mwa2%lj;* z3!h`#^!Dx-eo!toDvRWk9}CR!u3%{47)1KCe!%gkZOXQ_jYU}9lKt7&{uHJ2H<@Ql zmz<$Y${dNP5tn6Dci_g*8oR~Hx#yM5T;G*D>6N%Wa)si1{zk^hP>(qR$!Nr_*nJu< zEhHd#cD$;h(6OFhYk%;AAM8H!na@OLVB#vD@<eddspBWc(SE(9g5LUcjIP@XmBQ*U z<Xh+Y5+=C7FB(y)a8@S~_Zh9YTq!=|{Y}h#wS?6(#+lt8V8G;lBEmMmQy8{==0EvN z_e;O@ON^TsGg&51VVGsfJ<0`+hW7+WaoZ2*$im@i!z{xS9ZB>=F)QyUi~7TjMcFOA zMXRxgZJl<`bG6&nt_w|qiCl4WBS!(lF?#7It3KqHC5$p`4_Y_h!i8Mi<-tSSG3waQ zo?2QrYv8GDdAdhm_fHq-k0i9GXW>loHyMN>6oO;x^LtUp_cF&jEu4*OxMw@Od#u8l z_;y?H79EhEw&}-|Nj;~Xi~YGBk(2gGgxUm58S7>Q)HI4U-E7S8S-!$aWsIAQY5nQM z(hfj;9rC4929|hhX>7-!0JBx-t2zE>$isL}6t$8Pe+9J6yu9A~V&<JNRca~xRG_KU z(;bFZu_|I!&T4%d;o1*g%~!ZJX{5vD(3i6Gx{Y;}?PUT*gbh&<8;e(jqY7|OJ27{z z^;F?(EH~nd@)?}%z=ZFngXU#Nr_xv)ve_Y}iE@(Xtlp82*K*lWjnz)vbWJ&|vQ~w< z$_w3X*zl#XgK_aSuDGd4kR~eqGFXRZ9x8~<Ln~kN)}4oCw!Vcovuzfa4codKz<BXz zKGq#Ld!~EHAjwUbM(LDHBkhHwixDlaQz^i9r{5@Opr0$?(raMFKv;MWJgg6W(k<)0 z1ce-o0_hZn)HBLSVeDkXqitHkQ3jRGc1k<(MLRpSz56r#K7IL1UtxlN8$MELsRElJ z6y-NwvqqOss$Eps(+<Ex9yE^mIRLS~R47X)7YY`z5?j`4ltW+G`hwDLvE{KIp)@>? zbvEI)PbZ^G&_h1gYJY*wd2tErROsyC07dJ%tqUejzMO37Lc{kCI<;`VPdiwEE<WF- z4y?}%lBfgu)I&;I7Tc$XZK=l2z#z+Z8gm#6x~&Rl;~76n9@_!s)$+o!yE5%z9h>JA z&%?B(ITTDMv4Gw|M{)-@9=B*)3&e55!D$ATS~O2h6;F~Q5R?{{oqO=an2Ci0>Kr=7 zcRPIMYPpu<;&b?KJ>Tv8=wa#uE9eJU^15;06+Z7;o#^%+o`aXc6WR=cr!ZDk!o&@R z@_=x%(Le0y@H{;AfE9VZh*)EhX?&JX)3rbc4L1FAkt~ZJsF1B1c@sg#>A;XL2ypXp z|L%Nu=`ssPD1VQgKG;oBzktr9T)y<M{W@tI#=KQ!uWeHwa5rz*5s%>>;dr-u51XK( z)Q!JS_{GVvQZExDtSa3YX#;um)|*$cRK0^Mh9kJ**o8$lG^b6EqTHK8**y6GcS4-Y z4^gJyyNMF+N_U%gckxZPq`MFJ#LtgyC$WlxKDs=q0h;tzTZ-!!lzo%RDiqJsb3~so zauDg$_Ly*F(#f?cpPhUtLo!gI1j-28Or7#9A^ik6gL>Zuq;YJEqyZOmG7Z0xhYn<& z%qX+sP5}DK=Prn?U@fopzZTAnYq(-{3Y_e?%+&?5;3R)p50uTpweDS1ILCS$YhQvm zXfxE0b*?PPCZD9M0XE89CSx1QN33y1Q0}c^;XH<g^NwBnqwt%6x7}oM!%e}c?;#pi z>K=u23TnFs-+OH8coVl8I~dq+n`MJWJ}0#A@{@dVlxwVyCWqx={RFz9&D(EZk)iO5 z{0x@S)IIHFO`oc^8~G)4OB8@ePhD~NDdT+xdw1aPqup+lv6#~n2^y2kK4+|7?6D54 zBQ0Z;)he9LUu%}RIjs<StEHYs>05#0pWveOpk6M&iNcw7ua9Z1n|GsdmLo)Spa?Pq z8I>?ukFskmd>J3`22Qbvc<7nKQ8>#De!Zc>Ig?iE&b;Mk`9ylhcOVwd%H+L!_u)F^ zP@l$nF4_doRJO>%uMAGKa=y>vR(9oPapvTy6It|@e$^+?CL|O|l#TL*{3V_23$&^} zhkFXGlb@yklb)NdE#L>I{ym;vqC`V9Tc_vGU+B)g`U-yWpMg%e^<faMvf9s9rA@5D zX(VYI<Y%~js|w@m_(QA>h`VlX&n!yvZK90aH(v2j%eUHPrC;PTfCpG2-Mw)OIk|?# z`yRezD24NL@Z$?C3huzo%fN@T6$IQI+zt*3(}E4lJwKT=w-=->-ZTP%o{1|=fk9(V z7g!Q5;?nw&!{>_IGE5rN`39I!C@Jhu3X)mLlTDrw5B|y_k@~bgTfE{ULL<KttA2t{ zVHq+cDL>SW@Xfc!42b<5?IjCm%1HYlWdiZadKjEdXFk>w_a0F=CtP{TJMQyJkQ@zm z|Cndro7ys3;Zj5SWgARluOzT<m5*~+2m^)hpFl#7J`HbEEygijkT9mt9zEqLQ^Bav zf>}5ac>ud`bOh1EOa3-?`$R&6ily){PK8I=j7&^h$tHo;tNm9m<IF!_>d;U726)5B z8n5XqD6ev!##Hhm=<}02>$=I8=H1FK@|=BqaU3X|TUuT^7TAil@l#fQLQ`q)VI<%6 ze@3z#iR+!&wTKm1Pu|NPzD=4Q#umPjhphJkMojJ<^QFI#4+e3?rPYnO*CC#%dUGLd zds9k&<Cu5J>^=qYdThlhXAifJZefLQ-W8M*<lee%hq0O>JLBv=o%JVA<h1@Ak0dTv zo*j#OcuhL5^aYKdOjuUY!cguTUw}S)>wELy6i|-3vt-hsg?rcJQVVM@rIClfz37r! z)pm+R_0mZ726}nRPyYQepqihwl%q1Xhjz-N!G?iUlFyrer0MHc7@;*+0V`7~57QJJ z-&B0+%K9{|`17L05fAHUnEAP5q*yoSN<980<3O&6pW{CBv>k?~R*!9uv=Z97QhCkQ zF+dAXTMGSEI9nIQC4(QB!ddX|JR}ImJ70;43&SY~cx(8hjzC_~U4+M1zVhYnJKy^@ z<94i>8P_zwz|Na>9~dJo##<`ZE?juM`-z|U3HG7d4V_wUUfX>@=Ep^27u(<cW;0H^ zbIjpJZI3&w9~HFD&jdW+?5+1b5S4&e8Bh52_Rsy?&vifl^FQAmJ9aGfBRw2bX{{Zj zHx~9BlS{8=;cPu>#IefwUHq~q53t2Sp0-@h5w&V9Uhv%}CCDOUyZL!_5gK=(dzfEF zcQMg@?a%*j6wZIp{m~!&F)kI~?p}ED#qJXy|9JOt&gWlvfw_3eVo+ip?U!)CQqj!S z!zKX=nKPsvkg@n$F8MJsg8anii4G$^VO-1cqi{%%hHHvv5xMak%-bw9|24j?f*H4n z@s5J>Xozq%kWi=PB1DWhna@jm^<6tLy3rl1vcNI!(>*rJ^mO6==t2AU%EEaahRVt& zEnY^FDG^5l3upaq+F5Gdyi+9`il-4IfUY!lpuE&g!nhV7ggNn5LO9TMP@!^8fmzJU zAi;rNae4Amk!q))C9a>gWHU4-ydDm`OlTYx6sSwNs#Mh%k=7CGD16Juvb(0L1l+;O zn*!3tVPi3ETpp0dY|UG1YC9v9#acrfFB=__etL3yl&1|xg|DleDl8SalYAzufb+eA zSB0doyw@L;f?dn$J$!C$2ce=?|J5q-RiKO48t-lN!q6&OWw7ZRZcaMv0LvE=oj&;K zCc_D=JH$4nv5IG<jClF36wfL}#ZS7`if5I@0fLsN<qumWrxWj)?K_#QPItGU<#Rv% zlimKaXS*d5FJSpKiN9XyZXHN7C)m;>3I_vG%=o^P4n-56D~v%AFgKW7hoS5-7%VyM zutSNzQ?A3fKTvTr?xF?Of`}~?ZFhtFG@aXaaQouF{y)1v|Jt9U%)lB9i`{H4qry2L z;X87G44e)`rFzvf7g?G7%H4yJR5VK``Amhfb+d#rb4?{4<+cM;S*r3?I1X#=_jaSe zo2ITD9O~LcKHtT}-uO!h<NH|V#X^8QYzOj-3ki)!){RGJE)H$7<7eRa;RpF2Jw$g0 zzOZwU#!#-OJ@KKBWh=jx)y^EimI9UhNb7h=Oj)<?Cz(D=XMJ#kdo0>%n|#7LkAhPk z^{azD_|Mvbl3Ak^KZm~uPBSQ%PM&$L+r=hotCVwt0m>Sd<x7-l3HoahA^%RG<QP*i zuL7EOq$0^r)`r;pFn+E>8~i#`KHG`3@EH5hzOH+gUF$bc6r=QAVjy&teYciY#=Biu z=uP4VVibgiQ5vU`sXu)_YLzicJ=qq989<JWuvsCW<=(l?2BOQ9VPt1_^aMNV&ajw3 zyyi=Hz!#wtd?R)7iM+Bvd2wO!`Ws8Qx7dxs`DnKdxZ~yreWQStXL(K=M6u~4Vv$WX zZ{E6wRW>_1-|D)vFP&kt!ddD_3ut+~21)k6o+Bu#RYa?BzWC<bDCBN+GrQTS4u$jH zy)1YwAglPaegytj**xLKC-|aYx{te&n^(K*C>n3weTbE_JR!GJ2ezk7PEm#!#(zyT zOW`@jLe&HdIIcoZuwlv=G$jUjP<Bt!#y@FOID?;j8|8{u;@Wod3oT5ONfY-(<RAKQ zRkrXd*C>ZAaN?7g)MfQv{fcraiWBNV86mGM;ljw1E{OI~3TMO&?^O&|J4%^pH&k%d zJ$x1G=ClhkhaSolr~^rA!l4{+pqjdahuySlWRk^5czqIox1&2|yLtSbkBo2cwqxPE zbN5~>`0=C9>{Era1dWQsMikR3%ZWk&6Kub<(8a|p?PSO9*=+u&{L;c*q7^-gPsKyI z=|n&U@S7-diGt<t@hF`2v#86MYQV*Jk{D^4dUcap{UYB*$$bmizyBcqrpb4m_7Og& zkfqSC#W8Vo(rWuuj;H`Orkgg-V1=K-CiJsSNE_=Tb16`Wl3nEBrz@8)kuUr>Ihu_} zopebX)7XxcJ>n?8SZJ%qkcYNqd`%M(3+L(X0KSRkL+PL#R_R=IQu&)*m=}7xd9FU3 z#dj}C^@DsCn)swKeflx-(Y;pqn7XEs)ApCUTlD`fh_2Aaj^f5+hCwhW7F}(TmX|+$ z<2!&ZpTACUv=qLLHPb8Xa6Z$Wef})?$*<HUu**W3_GWp(0o1@l8P5VZe0%QI*Sc3< z`5v1&p5`;w{Y<b}L|~!To+ItdmSo!@zRG6IKEn$xBIsUavHt>TFY;rSO+?d_)1J(S zG$9al=0(~YFto70&1S0)@f|%1{SP16NBd?GnS4*sXP;mUGt(5#<eSQo%pTIDKOCb8 zK3Q<JC3%d1Z{<s5%DkR(Q}?{9v4m+Xi@>}CPOr7GtdC^EQ$6<?_vH!i^f`+MrAs{f zu)?bH8lrrKi?3~80O(<~c-D)u$s_z<w|P!uG#o6e7^dfp>@wFrUE)-dRtfne9{K3_ zCUt>qH+Jru>;slzmLcVcJOyrq0O4dRnM%P`G?a8vypl52L)=oVE8lyCvrt1zajG`6 zS&so|>J%mMER!ckwP)!~nZ+wHO_Pw6x#|hr`!v2Wed;nmz$Nc2pTf20f8#MbusvC} zQaV<?$(Zo)zShkMWy>w!ui^7caFC6wKb+9Yelb|tJ{hYkk0N9Gt97QlvHuN@$<up4 zq=5s!$1{riyhuS4M;slaB@b{{?s*6<bV_-Au963qZ8b0xHQ7o9=`9U?#ec53@kf+W zIMbNEA`GsE@i*u*dEtH15N-nVv|mg=!#Km|;%DMjtyRXv7u)KO&ClfWW|ghR0hOQa z$FjDgl`F85r?6A9z=lF8iurn243D}NAb%6DX=;-}AIiNX&J%T5^scLlWTO_}5U)i{ zKb{u}+p2J`ekK_v9X|lDAL;9HfSWi<mBQcr#X>3s8J~h@UP$g7#%skeKoM<{9LdWE z&d`cm8>~kUz^Akmp3Tj#@md{cF9qsT*&TY5Q9(0K)otJ+Uvij-@P+L?bt-Jrlng33 z?gb+AR(ORK0O<Ta3g;9(?T%F9)XOv;Ag46#`)B)hBijek&)ODMIHykxZJ}>pUykRh zUE+RmT9+C>fK3CfkM}w##-p#GzX8z8afbKK^VB^kKb)h#@x~k7*S_{u#!)vIL!dBY zd}18ioaJ+#<Xl=m!#DW)NI%0r^Rb`FSY$Id0898Bn;19_T6I3Y`Ld7m?u-1<`m1-p z-5OFxVd+Z}On&vxQ=fPLY&ld0I#xb%<S_eg9FE?@F<>p=l_8t@5Zhg!nsImWtIyIz z^fQi!j`D%HN+0ianV_o-6^qVA4bNA2HTY&+Q(x*ibb{>6lhid#u$X_o``-7yhhfiU z6#VnJV8Es0sZ-s{FTad+tY3AJDgVM=n8z3jJhZ;18q*a^?oD~+)1!yDwe!(8@AE|2 zp5zFPWTYR3gCZ#@q(k4FgLP<!xRAz8@tnm5B3ZHlCHfmlQ+<R1&hzDg;t6?7T}2i^ zc&ibmIu4CkB$Hz4X&yf!lz*B<eqUJcY2j?_Ova#o1`ZK^H91SC(=$YaYLzSOTL)DY z-QL!<Rc;Hl189va12a0YcUFv*uTZfw2m=nd>QR_lV5&%*LK&(6OlM0P2OBD&#u*?? zFd<f<?59E#D46F^vTY~b5CdbTecdcd!YRz@nN>%q>#|@CMMA7W!9kZBDuDGzY6sj_ zfSveCD;2IXvVu|P^xjJk%iS!V6_SSQx7B#Qvs{L&<W;d6Q-3DAuDbZnj>lp<(cgjf ztd`JPS-PUBU^Z`+F<v87fvMtm6yKiBMTT^6m(NCXS8^1B?rN{)i{Um(>rEe-4s3%P zb?U&OTz#-w2o9+S;yb~WKKcjtlXBCGzpgWyB0Wkw%20{~2itaz_1TG&YTqj=tUGbG zBan|2@cPjPos`Q?RvasTS19dlum}SO2isa|Gv?=WWavsg9A?+pBQLz*cSRXEjdLZz zpgybv%jcx1%8han63E*MB3EstWjoZ{=<`(Nkoc-3)4vnMDTNUo%g~6*BHgEqvH9U- zCgAh%ioB_djafEA`se@bpVMibLs5#~T`X>gnY70jADPSJT31^K3RFAG7Un1A5wg6K zhEY^PC-04)O(ZFg8yh-SmnW?kttYj{m0xs=GECfA+)Mbb+8p%(y?j<7WIk(Huu7Y3 z0!Ddk+YVmLQ`-0$^eBp3`O{C-oS?gj<K6rBvZ^j)sod29TAq7|BEkukJgg<O_-YAi zYq#z)$hB?=$;5*z!|=Eqagymlv<%F()>Z*y-ebeXyGyi#v~QFY)4aDW>n3C#<@*x# zG`W2ScMrR|4crf`gZIH>C%WUO&rsjx=lt@OD=bPZrA*s)5Z8qp-q``UQmw*S8RW{S zgADmjtmKd7GbsBGqJ&y|Km%n1PTZAXP=MNSqTBZj3h)^=rC{T~iE&*4z_%#9WFb%U zh!0*qr|;OrZxMGCw{G6yb06f$+RpCyN!(k^py;POS(k^-quF51+$$`KN$Pxc8S84= z)46l^*=TRBJ9_d2vJGA|BR-3Vo50z@R@J8^P*J;#yN-Jg@Tq%=9i6YOc4uCAmQBuB zxWSbN*kuA^oy7+uS6Bd^0~^}orMIrI;oMCukJ)f;*Y0jFR;MHQlO9^(6E-a*P$rGs zM<(NHf>p3?{`O52an~6D-=>{n8HxN`A%E2}rF26UAZwJ@r3fn*B*Q2e$B_loSWW6$ z!;S64KeZ4gjuTrZwJJC$QxwgFI}x#tl%DO68;+jOe8*{=nlx3rOZ#IWs%4<@edZ_1 zL1k=YDEu7R3@_L}YE80enJBBD_OX`1mj)CE<%DZ9w&fL+wXymVg|uNfwdV!pBN>8^ za?aW%f9P!<`Qz$mhH)LVZC5wB6U8#0fNf_}*HOOgxO(#*iyX>sHjKod{R|tFj%v-E zN(3}G*iQWvH*|B*#-RE-%4R>!+|7n8yY}F|U?={=k>M`xtiv}*7;t0)2Y%uuech;1 zIdSf_SHmEu@Sm<iHZr~+xZ4Mmb*uT+z|nq2{=RngI(&1rJ9Ok2i<$dT3bKfXOlkdP z>P&h;Q)wHwKk$nFrj>^yEDnvZs1kP{#Op-_xF98@SMYVQ4SG?I8@Nwe#DDn2_E8kv zb8HB*lW5>&Jmi#hVA&|0KLv*CJTmPj?s%M(>O*`lG@3xJTmR|L2`^b(@>qDnaD4GL z>9i73W~y*@!<#4;K-T_Lo-+OzvSkGKGOTM+Kf}n&MK-#*p0B3#WqSC~0puMnZs=<& zo%lHp6IW>@PjO2<DQoYr3Ce{F=TgSA&p!uH3sz^`h|o^LYt%^_w7VFh#k&2{Yp=f2 zJ^$kKQ8<tJbw(5`($zdl`B+K^0(7fH{_|{9`1<STvsmd@S#$fbw8xJ;RYy7DHii6_ z!#WKN25DN@%MZ(J?mNkZ;K-2!$VmEfEUS;x#~)`56NNLhwvAfF_2YF5P-)t~QmHI` zeU|-mBfSX^sf=eZVID1=H->MWKo^umvn3FP7(E>O(n{@b4@(?<;xTb6Y5mf6TD+9Q z)S-`&E4{D>cp;ZOTAIqQqDFDfo1_yi>C<k6Bk=GdiDeGXxKV+hlt1RQq2F|)g6}~7 z3By3HQ8=dpt#iXj)FU01B22C_$VDb!7u~FM@+81I&OKDGGD$ny3hhUE&lBmb6Y>RK z;+R*UdF>CAkz4pEywt}bT-rqGOVlVTlRghApE0Fkqbau>$cU7s@M-eZ@D{K7NlGYw z^v^D`o4?9+{iXB36<MfdGi9;Ohu4U2zpizr<&1KR=eB^Kg-SUI5dIV%!N{MKCn&aZ zgcb=&T;u07^56jPJXTnPS$IL80Uwbd8Jka?gPWf21FDloS`<C%YLuLPBH^|;S@dl% zl1`rEJ#nNHOxDM(GA4iG73UC^_FGs%S>m?xRh?8m_J@N)n<x(zzu_v51;>}+jXvHM zQu4;yl7s6Q!1cxsfynj|_BW{=c)<G1L0I_1sNAPcO;b?;Tk$Fm`6Qe$_`q9XRvq<M z<5S-J8A0^>V^Ei*NvU}6)$o8#{LQkPS(U#4gl^svza56z%!!z*ZN2?PLbd!I1NHT` zLLEjA5SdW1g%|jy@9VGTDAphKPMCQlUhb6#j6w%;kay%!@k)Le-4rPwV-78xrJL=j z7Wh-(<ZDdl?zX+;L!qh<wqNhlP;UERpHm->3GDL?x6W9A&%NX1p690d;_=h}@n4<7 zIdu^#S#SveJ)xgp)B5Pxu?)9ruIJ{-U;6Tw*m(Ie@<{))%)$7xJT*>3A**2kb2z_3 zlW#xspMIu0b@FuY($Xw8`JrXquChw;eG7U2t5Brh;|}XI3_FM@-3Jf3Y0vV2yk>nx zrt{YN(>Tf_b6+CM69Fo{xU-ojAL9T!Vf?iAAfCeY&~h1&(8;+dybZ0Kdpo~3|0tXp zbBU8l{DOLtdGih2!Rbz;>0QLj4d#v<Ig&A&naWlwH<vJ~vCI(%Tg$rjUi^BjgQrO> zoBa4BN3!7OvB$gV{n#WwqzD-cATL4(D$+Xe^ssI=PvaE5>h0!l#jzdLDXcNw2@*fl z;s?=&EUJEqTp~N3l<zll`s=&@w-k6P3THF5Qrn=nHS(><w8q}TGVml#F_tU6Fi?Bh zUu6&lPwS*J&)O14MW+^r9x8}-qg?V6ig{cMsL-_|L~O7*Aj&9|j^lJNZp@@x1jBZt zyw#1y6bd?(b7PSX<*q=#whE$$eB!EglFBa2ry@<IsrdUDsXmUqSK+Jxa-!@c+0WI} zNrIaSRR><W-Ee@i&Vav^!DuFE6q8J3rJ3o|u`>zO1w}85B9ydFE=BTaEVjgD3@w%x z#|o(62EL|`wei?=lw{Jua%ibqitVv{I-o*A3u8Mb>7+%o_o+uGDU{Q}fXZI|P-;<Y zIaE4YC&pKauX5dZ4^XbE6j9kJ;?f}&Sj6*QAs`Hu;~te))vbe&R(4^iY&Na9OE>FO zWwwXqD_(QebP=T|%6=@*mKVrl1cl?=T(?FiaOy)J>~_rUv4^5#wu6#C%kshwT%1&R zr&D7xW=E0o5-zQRaB>6$JY-o_DC_&y0X7tm)B<ce`XMyZeu}Qrd<vzr*3DWATR$qC zcc5_o{J;3!D0vp=7vok#5Dbr^j0m4wj}em9ds<FABxx0w806oCsNp+Mkg81fus*a< z79Z<*JBrh7@SB5=W$JA^7Lh8#hfq-ZdAmI8;7f(Gu4;rUkImy!!@3uS12`uR){VHB zhl)5i+*A3Y;@`20?liQlR~c<1-ry5970J5yP#HIm0)GXVZW!m_l~%|k&UV0Qe9qR< zgzgy-IWesY;C1e`*mk2smFH8F$O}6TEyXFvHWX2#JTpv_{is9uhjUB?6<-{zP{#Yz z_Y(N;KtZ~bO#+S{JJlUKaguVPn8NDv1{Sz?S;Vnj?a=DmHijIqeHuphRD4QV9@6%Q zUnKll7f@(J_+{^~Qoj5)itg3%ZvQcrMbjw3QJ9Xw8zP7Nkw-GvwP=2_&W1$Y8otsO z@BxiGoa;BnQIO5B8R9;6Jw}m7v{F^D0Aay$QpTPaqD)wI)55#mtLNBxd3vrpa{MH& zfppnIZ25^VD&V4$N79xs;jDu5gNHY}%WvJ|6S1Z4+2>F=@1LVy<!$0XD>6;FExSt5 zA$gzna)piGu3WjrqyTpsJ9l@_9NI-wQ)!Ic#j1G?I&R!U(Z^tI2pPJJ3H8Mb7rVFL zx{4fuuYo_rN)GBq(r`L?mp7of3}IVbk@u+cQ517paZJykbY>GlSch7+zpyQqqIrY# zPClY=ChQS~Gx05N6`M&8qti^L$V>W|mvTm&!iSXG`y3|X-@$w=PN2JOp^#t@3ygfe z7$rKJXQF9#9c?L_LhAF=Vj=H=uUw&|qy+|TYMg$+b*p^Y0Z#TU_8Iyal<#Vj8x|w! zd&aR^ansfDZTKF?Klv1W*BI_JHrO=f(v=&?Lap&pIHQEtuetJ0C9|b~<8rm%krWxu zg2=Ti*Sj}fe-rmFhxiHrD`(so=!3ZpylnsZ3WW9{JP&1u3p!eQNQ38IdNKZ=ogkrJ zuR2LC#pfz#A#miau7s{%zlD<V2Al95=TlG=jBuActc(ki&|8xGY+lmZK3F#sVjvx6 zcCmRUZQeSRSB&pV>(%-bP|&3gukz{RLl&imnMls`pUoN1_*6ry#^eL(b9De}|Lrc; z*1K+9c43X}!k+b`<%+zJ{(!4A(x0{S1Q%r7>_&NLeEq`hp&yc_DxE`H3*s}hu`Y(e zQ@HaieCgxb#Vr*c2li`e%)(v@lSE)<3VGlDS<)80oCGO9E?v49%bPQ2&i1sCKGmLV z!^(ZrM<FDg;mHN|KDco1e0Sme`R>J+U+4}V!qQkJH~5;93T{#WrxrrB^t9h{5&R(v z=X0;U5{qoD$LHp7&%*dfzEAa7Kjdhh`Q=5qOTooE{BZfw+aR&T!rT}Ww|)6aX@kYX zXUO{*<YRm|Lnqs54(LYab@oBU09AKlYOtpzt%r&@a9v<<+Be}_U|Fg`KDjSG5sdE= znf!%Tmb|_x*truXcp4(j%WAfd0__@Zh8LRxvz1E#mQA8@gtvXoed?{nvo1x&H|B-R z@Rj8ecR^V2;2^Bfo3@0^&iLG<K&%MVDsfucEJy_yu#|_~%U?N?C&~J2aRyb_2N<{U zNbpK}%VJ)@05Qin8Rz)SAx$k?C}S9BQ5RT!J{6DL4DgIhtMsWW+cGfxOFnsOKL+KE zVCo>6IOOOpRlOINf@(gzmyn$DVtQU)mcrQ^{-K+j-j)nfu2y{Idi>8S7dX?#xhltO z<HjQ<_jOG^hM8@TL2&aYbn5H0$0u-vP{<0Yr<G7exvr*7*?WGfmz7M4<q$^B2CS~> z8~gM|2%U}EV0tg#wCC_(gJHOBoGblkTplEDYPs?gXA$Us25|B`zz#T;rSgx=HVsFL zNZxrT_i)=k4#FxOu=+e;o56t;B)I1RLi?`GN+I03DA>x~{2_;8tsK%4VmL@_p4Kmb z_;K@V5Btkz;hdMP?%$ct_$g;!Zz9~|I;czH6h=apA1ZG0=eg+TJHkT<?~U05GQ7X9 z*Mx`6z~a_;{!wc^Es3u@q28o>#x1mG$7hwk>d1VFL>>1qxHrr+txf?;6kri%;@l^n z{=Ps(&Jbdh6vO_sDV!aj+jgX*ln5-Z!N(C*_4k`?s@k3O$;N}UN!z@0%PcY*&T}kb zxfgcw1(I$pKlSPVjJv0ISfo_Jdw?A9Wq(s`2OR?zwSFDvoXqm64{)EHS6_Lx`@=u{ z!_1M#8Q?=2M7;Bha-pa~b{+$dH{N(t3Ux0$|3dfczy4p<cq+2Ic&AX=df$f-6y7E6 z;|^&S9(Y_t-di^k0dnW+ug5!|E41cW>Kg2Sv@W*#-6N$oKJ1w!L{+91{A9ts#mu-U z{0kMhYB*$=a$6dy6qXljQ}3GNn%=T|U0STMxUl8_DU5|QDpBFDvR{3Z`W$^gYXq3_ zopTi?Y|0Jc+GHXpsawa9Rn{t@zmL#PTJjg3wXjcekVgET<alS^Pm<<`5hwD4dfAk5 zVo{}hXBkq*t>L}{S!tPn-V4j|Y|;a&(afasilQkp%Y3Oj$Mt`G{9q{X)D+IGgK5`y zqH9CndN>%95n2QLcTzYbkW_H0JX9(A+=){WtZuxcaCUclt#Fy`M=7<PNzG0ao=Yf; zHc);YB+VW-bOXjRmY7JRe14-<v%<*Dkz83*r0FMCCB`aTszd%vkSUM~Jtv$h4YZ1u zaUEppg2FJ%cN?=uE&8;~)N*u{Pwb_KFg$gYQGT9LSdzDH5VVSjvKXl)tyI?T#BG4C zB(Cz^zIkY=Y{SxzqKC8>UaV7Dl~*}yK8?o0_CAB)=mBaaw3M$}DJv{(nBdWuQH$$c z<f{@}g|m}kJ8R470)W1M%lFL))}1H?NNYnjZ*dV{@2w~EH*fKjHlB7Mz9Sh*>xTf8 zKx@AVbF+Z^Sb6K7#DRkN*<skJssLBeG^Mfb26&3q@XW5g-LB)uyKi5`ztT_sRCnx5 zS+Y98wUhCX9_Fum1QppnJ8{t6iULZw;x9h!aB>OO<PU9>PMmJ!q<aJhK-Q0nTNQHh zh}M?+99>57rh5%Lq`kZMqj3H`Ix7?)_^rHs<2JBrP%1sSL%&CQ2I{FJXrdBKg_Z)) z6<Du6$HJa>+o^vQ&MLe_*Ts}c6hD!oJnPCsw;l41%4Jt@=W%af9$E@#5e51?Y0V~t zw3S6RlyelSa?8PwJlKeldIaYQ6v}>vB2HQW&che-!!k69at%w*SX6=oMxOXAM@hvy z+ocOMD^bR=(F6HFZE6oLmgq`<%15`ahA)F*9#S?Z&UWf5@GZ}dX%>mN8m=YdB#JjO zkMi7d*=5Lo!cnok0F6eVhl+0T)eo+22=*U5)SZ0xOt=5g;cgq2q4$st_fVj#_!(wb zdglTvj;7d{a2sD3s0egKqI}u@p|Nh}<sHxf9%R#?HC$U<c>N((-J{)s<44OHTV<ij zX5F?}mrQakM-&BcRW}5@bzOtpfoHCFSFVl%dpn=RyNQ7cXK5tQ%6C$urw91^Sexy! zImUxK-7Bx%!$NQm{$@{MQ7<n*SMsG6iK`VqRG~oOZ$j2_$MJCCW_O9r3NK$;=uV$K z6NU2x*3t1{oOVMdplN+-i7Ia+akFr8_3CXF5vK4_zN<TR0{0>)G%crXWEDEDvIsSX zbt&5LZWZO-Yu|XKyYRh>_;uFR2n&4-;#4^2b6MKb5Q<_I+VVl<uXRqlRRKH6qS6$W zlhZr(En5>0d42;$inJ_OB~FNJgNBtwA5p+v86j`UXZ>V|x{&8G0V2#c(PTpgiL#-G z#Nxj`=d;g(hLH_*jlvn;URYemhdCz-=OuQ`ZVG2v+RsztZ<jpQz{SzCpLtGVu|CP? zcYc9kb{Jf+VuF7;COzBPF<EO*&vE*V$+&4k={yAw(l&?TcNcb+siU_pT|v$Qi@0-G z@w&09<rSRBYN=`)UZ-w6lr~xxUuDtY{Q1|r{m<au0zZH%oNJQJzzbj5%0&A%)B2}X ziAn?&&fobC3TMjkBAawhp<q-V3}dP*?X~94hN#q??tZMF6&4;;Fy2J&sdPSi;xw)% zP&f~{PymNR8|9vV;_P$U2(;79)D^9b`E%lRU>^&hz)b-yB&Y2(eU7{kexUx5HJ9GH zgcUy<dQHw!zFBCaGL$%J1eLg|L^_c}f9fXa4t(oZ99lTfP#=Dh>(O{2v_ck0qbx{3 zFT?By{Q}5624=|9MOkT{{UE5{9N=s2E?jy#xn6`uegR;=B;W7Dot2AgMyxut{R*kl zNT;wT{HsOvT@=nYZ(Pf6+ow;Tj{H<PoHMB`A0T>ur<TK)y2pC`!iDZlKGl8k125on zdOwRCeBosp@|NXkJV~c~S468!(Jhqz6kq+`cT?{NvB=(u4ArHW7Vg<Nko5M~79xsP z?xTo;k8WJM*}chvhrZcoX4te;AI@wVxPgM_2uTi8saqA!;w%1KLOXABQ$Hfr0{UQp zn6>HZ;x9qcq;KHJwM}R};KU+yz#|nvO(ze70nlRg`5K=v%hzWcbc{tnWKB}=vPZMP zw|2@)6M$D<S0+Ip$_Iwwp4E!EPd(N<^A#gOL}5m`lx@m1+oa<f?*SB8+!RiIoWd`Z z>G`JGNMs>N5@@1eQ27XJ&4!nwFJtJ!J$-RmABw$o-?y!_gh7(DTi;8goW7D?sh2*U zd8!2VmD!08VUgvQdO)kZ=)nljc<myLdKMScr#=nJqwl@(U{qIxjEvJ@!7LCPRuA`< z&wKkB?hWkY+m6SO%k~qI3(ER_Ozi?rTe!21dag{`!l_Uox8Pb|c!fHpu#tu$YhHa> zM84fN7*z(+`655<QZcj0-xB#g_kDnmmTz#%GoCHn=>2=jop{h7p#f2HLfI`(DwD$p z#*GY-#&uSXz-lx#&%CWSv9#x<PvP#K2Y7@8;$(dJyXvQpSaJJz2{XQlEGtJ^SOR=f z?&rdfipM^0>L+tl-&2Q3Z!=BAC^oH&!O8pnU4VJtpDjFNFH;ll!ei13m;2->?+Lyk zTsh^pT(0=e!`M9@z=}*2=R&)`79A74{j?}ti=y?yuN>;nXWm#B+@+78&g>`Ke8aJJ z(I+wL-t@!~g?zy%H15+j4HsG;#}_r;N(Aan`IHzY;Gb~gOA6Z2R)w?18WcA3FyngK z7nL+bp~pM>@1i01rl(@-D<<!mqcdh2D4g?7nPM92w{E8yd;P+v{<cp~?XXmp!Mi~w zU(1}M%B7rkQ~J1kVBRACNu`T#zS(`_8{gpkI&%ZYhgy^nt}&KrESraWR(#_d-|U`y z?z!$$pZXLoA6{Y(jXbB%-8{DDT=%|<G>Pop8h10**1PmCk@s6e-|t>t_1%`d-s9P_ zsw40#XY~TgQ0M9zp*e<D2`!)a6`gEQV+&d*@szD%Z8<Z(BZAk^6ANVz-x-H&ieC&P zj<9?oj`9&GfP=D2g?FQCxg~Y1D~=jvHJ2Igr9l-WzG>3FffIQ0T0dM(9Qi(ZRv#dr zM#<lk#yC%M7`;#O*y!T%BXNM|R#a0j??60dAyU!OmsXy%&!y)x?|Vo+%v7<FTEzan z^(Bu~8>0W#3g{^xgDjsi+#fY?Pe<Wwg>klu^ZK|Wop>5#b?E;t3TKtHDoAA%Cv~U! zOjlvxfJ(*IU3R1NllxVK*95-UwlT4p<+E%g7cLUky8~D)9cH5Kre61NqW}b-Q3M-e z0tFD0REvRdusc!-?L=1puZk>%x~p7T^QcHwDeA;cTvRM;{Ua{Yq7<)ga)%WrVGr@0 zY9py|6{uxV>flVe_&KnjHMjEV=EA14jny;<w>NL{-97>4>$8@+<|#hn;e>ioi(hcB zPPZD6am2@bR&b{w4uu~|c>r!>G9K$oU`tPr%dF<95O0EC0k5J@7$6?{sEo67&`pLk zv<#kh5Sxuy>*ulncc5T=%k6+mWwHWXAD^bPbFsq_KRZ#a&CIhD^VJDtaz_kQI4FDA z><)ji`;Q#$4zZ$pj*0j2zwv?Y$f?uR6Lmr-BYa_7-c&32i<@D(7Km~M!EgC$ki3P5 zQHbyjdX%zG_ML4w7|zClbhwsz8tX#4I~C&k-y~CLxq&in76qv;E~dMG_B;Pa_pNV! z3xy3<pA0ZZm{^yxSq^j4D10!(o9WD;i3)z-%Qs?UU5j%RCR|ktQ=ssXe7Kjq=CFEJ z$$txlsqeIO*6KRef<Re7DXQXn4;H?5tP9ZG4qd-r`t^N?0%#ZuK4Cjajg>ihWuQp< zQHrktEQO9DPzzKoGgUsX5>Lg_2A!{~!kO5pq(^`+0!t;1?a~bumf?Yie4f9+xzdkv zwQe19KmhDjCuwBk;lf7lZHv5<KDK4~LB*7x8{1|a$h%ph;eNrOPhba{tJIepDo(-Q zp5p7~Zub^gsKCefHWmbSDhrMt>-Mt2*G??;+-ZJ!VFQIMey!aQ5!|Er#NzP(VeieJ z{7SO>zFP&L3P4q1-?wh`GCdnfQKn>3B59AzF^7vnk|jqlLg7W+JoJkr_~5_55w;%X ze?Wd3Izmr&gu_c%Valc`E+S_*Gd=7DKx5ykPz4kUDAexH=X)}LRp{yI24^s2FrqK; zt9x(W%#$Zip4`59?zwRxK$|@H6EnlU&jEk}v~J=`VtpCV_kAqe0aQ=F`f4_6X83^H zB*3qlDv*?gD0f@<Nsfgx?l;D^tb>Pu#<PHjW3;2G;jJ$KI3LD38<}etOAkxgl|~(7 z`j&)jfor5?BjLSEj{wn+0-nEyk9syi0FM2)x#fm{KFjF`ShSf=QX5z}KY2=?0?s!J za6W;B^CZ^es=3I<IAD1;V@N8%q$M&n4zPubjM)X+*Y07OHws>R<0L#n75Z*o7;j5A zBUoQ=KAj&{@i+IafBUWB&;IEBVd*{=2ji2p4FGj2caN67WXSs+(5B8(F!aFsW+G{y zsr!MwS~wr_?GpMJvQjS!a4sM`z_YSK*KET91mG%cK{JaRb(w4X5BqnojiMZFUwKBp zo+Iw|Jna<SQ|~=U61oAL>2vi<{S>`^h80GAG!PLW3sjIF06cV1ZK@m#I5thR+MeL8 zh`s3X6mRB?`L@6~Z>wODKYi%vaFmUZJ+%9Aba@P&7N8E8!J<j<5t1-Lp8>$FuRg~B z`-wvUqrQP7e_Hq0e+n+k@tXZu%0t<x+k1EJ4_7|8I-I(2emI8PhXd4OChoQ|@>BMX zAF&!Iz1GSCNq%GCop%A8iTBwrexA($^prXh1h6kuFw_v&{=7n-j0F$)I9zwB@y2I9 zH=I3xo@X`wDf?RZm3$p{dtK-%;w~F?^5YnG^7M&pIwda`>XwdjQG1n!ij_}&5#9hq zb@TTCVEQ54X-wmqB}cJId<7}r6)YVTA#V{qz!$R{Onx+Qn!Z&~*?CSD2$su4Dv^s9 z<g`J5zP5#1EXE)E?tEK;x`@wwD&P2S{7J(NI{QevC+Y|}5&n!i)TgnQeJ-eu@Fs?R z8O4G>`a^y`^FuT)bUIjJ8I~T?@9=v9NPgr99}e|HJJtbppL2?*R&49P^`zc7ZePE4 zHP+Fe|KjJcaK?QIoAVnRfX?g~S~k;_l`OKgs-SJ!B|ZZA&O6`XervdR@zu;B-0)WK z<&|ork9N#XqO|FJ69IYLyE8jnxpW1+qi*mae*8GVJo>$fyN(M)zrcBVKlWO<`2YYw z07*naRBtUIA7x;RjL2cfYly;^M?3qFYwr?b<{YJsgz>z^EPnDdlv;STlLY%`M8DBX z{?LFo<<UdEld+T$J+5TMtB<0aWZXHcHsXUkY~jX~M&ppP{b2no8pcrH5`#bG5`zo! z%(d(r1u+OjIajD3{UKwII+sk%BeXdg$Lsb}f{|kD56eYS(UW!ozh;n|)UW*bOTXRn zNPo(>8<{}cGFQ3n6HM!2i{;?CN7Cokw(L>iX4e13oe04Jgp(IBNpDq;WM{gnq>!!} zCR6k=va!K(0Buwb3G8|CfP2%Jhixq526>>y(d#54+Zr>Fops*&x&oYa!$k|B-DKXG zwhKKQd)kunuv8v(VLo-6oKq&BH_^0sEk#asUFrL^tb1*JnzqW+&plSj*5}I3Tzh=4 zn+}q;bfV_EO2m89nnb+{-BCQA=bto*!E-Ccw^!;KJ@YwCq&|pZe2>g6L&q@7z>oWE zsHj8yGhh2M`ODz|X5Y(`svqYy^4|DQB;w?NLS@zNJyk&IWe+yqj&SPBe$F+5A5b;# z#HSAZC!@JnpS(`}mVT#<sS6*e3&ne`ldi&(MxH~vF_|K^a>^Q)jjPbwiX2*c`vZAa zUPSHuD`&-1R7x(AGHTUCrMHg!mkiK{p5DHq=0h4rF_%L5UAN`Ag#904q;CD}dP~ov zq%~6hb-L<<aT~v;cQf9zzmkGnaxnj=@f7f^>;RlI?)oe=R4e%@joclXw$c*axliJ| zj=;D<Iq!DfCC$`Fi<@i0q|4!${d0ej7S0j8IY(;nQ99-PRS?}Zv;D{|K4ARz+iwr= z^EQ#7t8)hDBZ6bDy{Zma&taq$>t^KncmB>#4PW}wmtyc#ZNz*$dTBp=?Y(u;+l}`h zbL=GZG0}YV-BB%PC9*!Yk5+!hALrbbJ$ix;TA$tev~<x_KJP{V(Baz6Zb_Qfv(L2_ z_nQAvpXZ(v-}#Eq63!o&N-G$Us9yrkc4vah9vT&tUKj0zsh<!~&blefoP~SymT;vs zreW=llXP|-+kM5((2u?jzaRbRyF%sdufmb0-RiIFMR<q*4;LYl>!OS-TO8x|_&XBW zRalQ*{?hNXZ9mqXVSYI9WgorDUpC#pYV^K8z&V}#&Pu6f(<dPrJW`X};#g;~n+hf< z3pEtP4#f_{!Po)AA-NyY$l@+^N}DDegt%A7d@k_jgbo53NRHsPApR9u{HiqinpDF~ zq05X(K*JdpQqx%A=<oRei`NqXZ!5fx`T*ZN@ej)mr=X#Oth{MKYUeND?BSs5V!RyN zZv>dtwSn#(W@l&9;S1K)1VcB%`W%(*vAlkvTY^O_{|pp#6`0l<%5vy3LvU3W2U>9o z7HB;zu)GB572iSdq$>mc4C|Jo1|$|{fYAaDaU}p)yU0S&fyq3iBX}q%sp4BcK}qW? zU^({!j)E0}kMg5cv+@;Kl6T`d3DI3hZ}|dzF02J5<zE2ZxRodO%8oFtQX>b-EKd#= z?hXnB7&o-Zs{_4)=B9D*m+k@!c<Uqnbje%*N~;lhUBR+c(0L92%`<#N>)-q7pBYvG zS&zT@`mh^-;TE951{Qf*r!fxH1O`3?rFMZ>>DPM&(9t?ovE<h}>2;<B`zCGzc4NI4 zw-!9`nSh46#Yi6>U1$jC)hp=*qWjD`TVONe*`t-=|NcM!6$|XkqYZ^vlQT2a3efZd zu;x!Un0mDn6s+*4|6ui0{pWw;IEk{(1>>#%qx$&f-j6vx#pkIX(-VlbJ_S3c09!U` z1HS(5Zol%=EsTSz^<aL_Xs628d+Sym=^G5zue#~ztZrC`x|)!-acq~?;pA?7XLD8; zkx&*HT44*k2^y_p;k?T8$Iq}PW`YD<7;xIO*8Ljk)+wa2SJttXY>PGxTja^t$+Q@h zX94F)${BDTfW{AQ?#U}t)Dh2|AG`3eZxE2SU8@fp=#aqo5+6`oLKePufB59-;RqiY zyvSz7{%Nd50i$iR^L&u&5t~eF0I33OZn7Nz>9bfkA7>&&2>_fouu^{SJ=}88ypNwd zhovDtW3e{XrH1Y!1mvw-`y)Th2ZTqPqJIEzUSE4idzj^8Y+6X}8$SDmQvgT0I{~z@ z&=i6qrM&51tuN(`<-)MF06;d6OAR)BcH>X^<i+9e44WW(=^FvG1)DbjonxVjzEO3^ zN|~$xIL{5YZt!aRjb(gWzkv_u!?abN1NOKn5@b@#Wh`DdnQ&==tcCMDE)Hhz<8%5k zeb0eI!^JmGx3X0U13nVZ4=Qdvdo-*Ah=23{`}**$fAgJT7S|tR_#B?rYIy<>k>3>H z_+H%n?4{qfoG$e&pp!;*M%Oueai_5l3uh;Mjv?K>4UDCJohS!%jzyn~B=xT*jTujn ze=KM11f@+D5uzvBK>c_SrKPM1_ul$yHAh-vs#ei!+kviRo&Y%GnE=aXHd9z*uL9Kh z3br7#^={2m7_5_d>wry*z5Mp;a)mc;_D#+3oc@e@QMyye^W>RxfYSI3MqgcQK_)-@ z2}erT1b#SfmA>od4XnoL&$Yxoj0*?*&2l58n+N(zQp7?X>Y<`K!KZJ^T*bmv3+JP_ zZ_tOceUbAm`?C7c4pkU(w@+|W%0A=L`|n49Z++pjv<LcW`V3Iz$jNj8P|zRyNx2tr zeu&E&KT>%6);+B00i4gB=UIVL)=!RJ&~|prc{sn2*BH%zKj822)5o)kmQ4WjkUQ&7 z0@f31uO7Jhb?t)>@Q?n4O{7D}hA&amN4jt!S`KT|vemuy3Kf33sJVxAv@-S0h8e(k z#|Zfe06|>_D5hQd&)tvI_vSboG50gJO`DGKTX#l0Oh2UFjsU)}s~(dj{i;5kXK7cq zQ|Aze0LdK(tAqk7A!923Ia}fhVfL$jTf$B772c|GK5~-!Bp5jqSW?<-y;^OSpM<2h zzkT!wmpXTE^SbDLd^o=~oIIsV4f|H>l)6kqv3*!q5l=YqgRP6CedjyhMmFQaTW@_P zo5cmp6OUNtVZW~2lyN`|`ds^xJ6PsldiT<B?Bp>l^N#?q<DLlX(2WK-pTl3SfU{$2 z>4$vRPtw~uV_D3~{LD8sg0QSxIq+ZS$AB>6BaW8VOX^@m({OaF(m~IHdzS!t=wT+T zBXOD@%4aA`hOpc~BVmyzq(YNN=td{s^Y<);#Fu=Fs}iMDKIbRsnP<?D|6<S}X*zdd ztmaLY>KChzvk3j?^V$HZyn2rI^QOtq{By_=GLo|<3UW$bK2CWozj>RsUt50CD3d-f z4g=xQXHu=B_}-!CJMu9`xp`@k={usvr0;F2KT%4M=YZD;EF8dtIq`#+s@+84p2+pT zp35L{Xzj?b%ILgxBR-soV%+eb3mLOvWgh37cr`xN+QvK~Re2MK6x?|4RpZ0CObZ|R z2XFL^mRJx8&~Chn9Xi%WmCJL{mp26v-AnYuYN?EaP!h#IAv2<ya+yQw&v+%k=vzfk zd+vGA0flbT!EFB7_K@37z&ZIzH^OLoV(c!*@R^KL9ZFxyiq`tg1&>Y6O_d$q)L|bR zrnPgPdCPsPRxXQ2<-YS!UcL0Gj}Rh^@UAQN$N7M&jBup?uPDS*mz-yL$+f?b%pXHT zr|Ug;t^YNC(P{}SY0;?y)*WQ5IgcXCU!DuB8<MDzP1R>Fd-wC+(-aWz)92-F(xS8@ zoG|<A=KyEgb8RB=P&PezwvM^*U;jo+p4lIH;gj@3TpKraRpGX)+#ApER!({E>nUYg z@>j0C?3NX}<^iATrF)W!Udn0S)R}c#YsK0uunzN<Ds9lUmle?aq?CoEu908*M*|h` zM;^Vz;hGrS!?WX^-)IuF)L6)M*B|}SAF;{*4sS~@03gp~&8>1<KG(>~$+xj*=jMj@ znVWs-Km5}0w|?>`hd1ANlQL_ZVm-*jPG)vqcLt4TU38v$_;;V>)!&O8MpO4c>i94X zdEFW28o<qM+mQ9=As&$a0K%|a%`UvCkEJSEJCLO%S>>%;X+o;WA=Mv_luObOulSUn zZ+}6U)aKcFN*0EaMi5*5^(Y)BYD~D80LrKoiD&*@o{_;$G32@NjAi~i#>j+x?>~~+ zN$PvY{PRToSSmmChqmbs{H8AW(`7y?Y>DbQUJ}&8E8TOCbCbFtPRY9HhIZ2l^~gL% z`F%Hu?=R#d`2GF}{nbzPeF4r6Mjv(b!Ndyf18k4Cj-OMTT_#UdfQw)!WdVrk{N2q< zV{8ee<w93l4h~udIT5olXXlazomY1``&z$?&)sAph{h}jFpR}1ma=x<0+j+yGZSOO zAzrOGi7So6Eb7PTv{tb2d_*U%wcHUvR)JALQGa&4I*gac>ev~upd|nj0FVyeg`t+k zf_n9J`PBfZYOS4tA8-<kc2VfUQxI+uOK6o^e^K2xv5Q5^>2uwH2r~LAzd)j|s4gxp zW+5xECm1XMEub#Hg44=nr~CulVKEyZ6+Q%iebw4Jux$EB_RvS9{%8dnw4nBxfP#xw zePnyD#iC`j)3iPUbTiNiIGT?xJ><(HgCB*H7t8PK*Mi-qci@9S>QC^X`)QVri_$EF z9XJ871^D%mBsl7V*yq)Wm(SCh{0mhw@BqkdFgUol{>&GDY&h}y>%%(bnmK!Vm;gk1 zxVSJZ;Wv3~mp+H77Y38vD592?<03bJJo?=eXom6V;Tk-|N*zA;0Jd#x^5H)8YB!V1 z=mR>zFdv@nrPM*otOc(Fzx=uZ@vU!v3+u7#__ZB|2loK)$?X93AQ)2MGUY+OW0dn* z$^j4PqV2&ti7#e0M&xA~(9;2_{~(1-1>eVO!vXMo96(gW>)>9%Q!FR-0rn8^#ElZc zmR$k~)Ilt<naHSf)~ocbYazN`m+H86qg7#V&rZTifAr;z99#bCh`Q^<U^jAh0_23% z$&&dAI9tC0<ko|h4O$H^vB9#8wY^r(`gt}?*BooqiyyPHo|W$&J|GpV1!QAe@-;(c zX@6qd&5wKCY54J~U04+huG`P}QNao7YoFGk<m-nNVFgzkfa6#o??zUBQ1A&lG|$KG zmTZ62(dqMVV7dFoa1Kk%X}}--QY*^`SX?TD^FR05;n?4Jm0Xee`V&Cs#o^LrK-k5t z;Q+7w>)ZGcGT*&RKkw+7OtMgLf;_I@XIyryZ(_l^iFNe)BlLa_01!QyE5P|EAL5H& z`AnvfH8}~Gs#{vh_Ikr<4*=KvaQTBrD8%96$njUGdtL=&b8USK7Xkym&;XpR6BlF~ zfW0;GLRVMt`+DOczo)}FtRj!#gLMM`&%3p@)#g}NA#Mr4FQKss+l4agCTMmRHy~Iz zPaQZsyz&|!&VZ;cGB)WqEbAEN@VsjQ&unU}EDhiO-ER!v`hUMMT>Hk2Vfo>cw85GE z6T`tNtU38W;z0oD>3#IofLCsoIAu#ExAN~5pgl}|+4ih|E8j7~SDVp2Et*AQm5(1u zE0;8eyI88pVOd+k8>G|UaHWo@Nb0FS8=#~)MTeaP8Q*)yJ{MT^)ph%Y^5OghFD*}3 z0r05iH9(1VKDrkRXX;yBSKzy7pIXyTVJ)l0?4b+ihH3O<l8^l@^G3?zq93N@Z5&)< zoH~7$c1Ru2KJ}rirJ>{D24zREScD@V>T;d-eI2D)i3R`ueEiRT9=0e;N}2x7`q<)^ zGFvWm-H!&|xPEImrVnSv#2GA2JK!upEpTl6cEP9s+-!6l@l76m{_0!t&Ch?9aRVKv z|58_MSFx<N{gY3|W9mbo`tc$gyI48jxqUxwY|frNCzDFH&RnMsTAMdh`w-na-NwSl zvC_A2j$wtrmvPv>%S{o})W=6jp`2|S$V%V!A6&ki@$Jy@qkztbW9eLgcrr~Jf<nf0 zdCx%|FXGev_Vt_87e4yfh&>2c?Hdkq>lmjFI=4uhZpxx-m~r}?+gP0Ia>ox8>etwL zg>nzZgDj+xzLUPyq`rOPri7sJEqqS9c-ha#F=qhRCnswIKpn0zkGM3iwH4bk-40c= zj=Ub?+TyXk(&@V<nUlB)w2IF`0kSdOYq9yUNk1q(>G!eJ&B7(>MJw_rPZx)`KK~Y$ z#z#ma)W+CCntY_NHwbxG8IZf<oO7OczVkM9vwQgb7e2>aL~w@3X}!dw9rt;ha_;r( zM%isXSoz+cy~mg6&*0CS%{lr2-`o(mKS$Y4)10U28<chQ1R3TZ=cu-lRG8`wrzoGd zb;ku`c^(wctrb_i=v@*gcFH8(#INv{N%EitnnThW$LjQ`{-Umvm^@7_y^!K>;)JA} zkuV+Gjy^{IE73N+1dK{zM&>5r;>3G?>Uo}dn_PPt?5CU)sRR1LtZU;o)^j$zgSC}| ze>q6E4H{QaGN<5iF#(at3~rJ_y5WiY##aHBmaS;2^O;9Pc!U`*&uXq{E=lVnu2a`? z*>%rw^vP#+bif&QL#x#h50zZvnWiO>p6i6Jo8ez!L?A|NWT~J?$+GgWL`)y!*ejsf zX-YW%>l|PiU3JcFd$+8HrR|f<yu0E=e+e_|@YKrXm=?`}r21>QjI%8Zo*K}P(Y1LI ztI;Vr%2$&~=yaVV*zldaH+spIxcTQf@j8tpNgZ{aiExoi#pgNv+g7rPqR!btNyF>p zM@A`-_eoXZKJ?&RdX$?+uj;oKJnAF!(20&o+keuROe2+xcAaua(lnmKgtFhhP7nlo z-DhTydbCfo4<fSnsncBY$2#Si6z%vVD1-e+n$m%)d$Y?JY!u?=XU4|wd?)SpEe}KA z5bL<dl}~RgUDc-o2pJyKm2tT4w2e-EjM^FDl1OaR8j=42kL?4vcRuC3X(!+udWq}Y zM4FDl@*s`6&xKqtE|xxU-TE6dsXnRcg*>%V7T`=9qAlekoXEcS8&#IZKeU|hWj@_R zpTb10q@~;=z?p07(6L)EQ6nsBBC-tamiZ4CaPB2+1#NQQzN2S?Ppy`hSvN;dcsMsV zJN(Y?{0<)@zMHYow~t+$E5GU+T@(9JyV>Ceo8-D6`>o&lEjEDPicXe0(2{fVdaeU8 zr0bWp;y>uVzyYfq+i5>8iAFxr-H(g({XA3IUf@tiM+)`{@wa=)Pl)*Ecr0f0f}(nH zs+8%)r2pb1KaKgR1b&zj_zMG^w|3Eq^;XYi_qpVvF$;?7y+&nq028dTQx){mukof} z9t&(6udkY}^4w&;QX)upaB>Rp6Kg?0s|h+dmRJBJ0DJ&YXYdz!6n7fy%S!?AP98lD zFtR?(vcOvh{5yWs5Bo6Dq+eLULij0k9Ei+cP}xCRz;pr-+f02fNT<6C2jhTn@FU+^ z>{>1tz6SxE9|2MoD9a#c9`NiSF3;V~h4h`!KEw?OnX;h9%#b64CKFis5YW>S*+EgO zS*@G}vCYr?eVxXBRe9xtd`xFvmd#g+{Q#QapuU)uui<wY$jo1$!Z4qOCUQ{*@@ZMj zSF2ZnNW(J8NSR%PBX0(C%VXZs5lGF#pG9zh9(c=y1D;$AIT6#RrelWr6bM})cTEV& z6^6T+0?&d*g4f0s=r+zI0BXIyk8e>dRe?~4U04h*GFf`-C;s~IxBsKRJ1kA&rhtzd zJqFD2qf-KsYq-(a1f(&!6Pzjw`A`O*YrXY^MZ5#$B#Y@Sd>bo!KPD;YqGh3FAvrp^ zI?Q7&=%&G~n>UA>{QS6pn*{gnVPOp~f=a$7t?$w3nUi$Fb)BNF5C|+t`H-83?PHQj zgg!j?ldpBU1;0*0l(RI{4fW9aRS%}vOxa*_!;O?f`?0RW@=#DfzP6|z{ot<ifhOhd z#LGHW7px2G)sJ(ns$&BE<fp8yPbV{i6drC8XiZrg8tVII^ujt(2X%!)v7#S_1sq0B z0`bbS{C(Hk0$Mo-U?zbdEE05HLAEO(D%tEHuV<ulr`fjd1bgI95y2~a57(nxJa_O_ zp7ss8f}mz2$Gx;$KN>oX95ogeq?0$TGA$>C<8^pHd4>*Bzy2Nr7(IL}IE3{rps{|Q zKZCm#U2phm>=G6T(?5A?*#G&XWJ7@kRRN8!U3)YvJfi*105~5zI2=BTwKa_H!U}q9 z{2BDzbkQXOAT@M&f{c7yK|jt5!_BMfxI@`9y!O^v(xNk3M-KpxnI!7--L^%RSd;2| zTwmhrYmeC^dW^0uQy;kbm^uOIgl;Q?E#0xukLsJ7BYwk`oFDfCIM#aq!5luT?=KHW zj-5&U?42}E;_|QNbCfUsf4Qd(ZUJCC!#e#bDC^<^GQ^$CvD3I?04R2;o>%6nOCr<P znGbDkV`;eh?e~W(Uw?PF{>|&dlX*TWNWJdSeG6_SrU9Oh9Gn`C@;fk%<+F7I6Kb6_ zodfR%K%bc5LydeyWEa4hb%+2;AS^sw5Up$7j7;or{ODu)KlrG{5@*_-e0k91QbyZU z3T$Aqa-n6simK1q>bGi9<&<2x`1AEWH@hCM;n$l@B|pHnMg8t#Q$=thfQ4<GcD#pv zWeThJeT)f{^ig|e4pJ5^w(-RbIB42s`jy=id;ph^|LH&2#gV+pVi=;`dQ)<t==803 z?%d8Mjh4oK>{6e~u$FdiAJKhA=A(hq@*zCW<4^fEew_8+d=Ow%i`??}j$DmL-dUUl zL?nO$+dtW-T)BLO=K#+537ob(^gUaAn?S&Xo+<L~vUfok3upWj&+ArWb`ER$*N0PQ z&IB~KXqL}9G7sy+{#ae}-p!3W0M7PT``Hvd?nWYQ+;W(<{<Jdzjz!WEaK3u^au#n# zPMqKk9xR-(DA#3>>8wZd?LSEw>Q8rEH*Q=HXe>~zzkKHzbQ8pP!CK>@X=TK)qB#uL z*Z_FKhVaQ#r{Ygpi=-?bEe`sZK0IyTH2kA&Z$QJ%tgF|rB1_%P;QJY{d#^eGKlb;^ z!oI%r(JHK^p+NGTdv|fQHJ7p+WK%=`&wg#aEc($?^0hCv9b0Zl(TDTl<K=aHYd_9d zWt%>OY~$yedfwdP?FjmwY~)Zl=UqxC2Rz$HKc$@a?%blkA5U68aJh^AHX9{M1i1v9 zB9Zwvb&ek0yK{HAdg;n={*^OWWb@HVHi@-t6C8g9`sXR%G<`w2)G%jcrJNyKEx1^L z!Q#sY&mGhY1r2~DFG$jZkmy%#kh@)L^^3i~^N9;|^E8d;mSf9XKJu6+@|6QVv<xn0 zIJIC?N0%!WBn>go3NJbp)@kZazzw3hmr%>!H2yO>e{5r(dyHgR50Sg`EC6T5{PfAl z(>xnnjSe)@*GW}U{^hJp<-un=4-%(YN<|q|s^Y=4Nk=Ghs6JF)`4Lx{*=J{?&^!z` zjrk;x_SY~DTdDuVc!}g6PUv8JJ_<9q(;^<(SbKye#VEdH+(2Pg$yM<qjpB#MqY887 zU~J#NfEI6LNnh7&-b>caJU6fX=MhdVBYol+^NG^a>OVt?XFLgSNiUPeC$0VS2uL^B zx^CsM?G*i{i7j0S<w^Z9zevn}0tzMzcdh=a4H#Fs_)uLa+L4`)nsRh7x#AI39pgwn z6k)=OhQ%*EDM_eHUe$QZLjh;wMpndi0%kr+(i4X+B6?ni=bDFUV?Ot1`WC;^S3Orc z^|a+rJSEYOQ5xkydY@Uh-BLWZuaRAaThbKKdO()ekn`5eHM}D%eL3+WbK~^BoOApw zrz+HQ;-e>M0oMYcm8Q-iK!0as=@QGuCr8xK;8xz`lLw=Kl8IrXqn?%Q)bp+bRo2R- zB9H2eB(AAE)P<5|-Rp*~$Ma1?-&CqKT#IL-mL{^7mUW*n9w}}G38(1?T0dpKV4gm+ z@9O<xjS&^!^;lep#TAD0ymE=502Np9<(!VW9~n`?CR>@J>_kdCB))DmbXOJm(l#B# zwgKlRck4zf@U)Nh&M*ApKQ2Nq>2L2=l*RK$*VXNCSZ?|zM|@b9xzF$a{_hW0nN#Eq zXXZdLLemI{vbfF`6LG!%?tAaD?tCzO`Ded8{LIh%3>(KMB4gKfWxRlXZ8HOPb9nw} zH9+7tPtV8LaYypva!1(rxcs32&SCKd_=KmZ`HMwW6TU|&zRzIfl>Xzp#r=H}Y{_8r zWt05D82U8zrxN&h3H*ft&KoR7`@rp4s~#s>0z`cwv$L5qB-JE?b1aG+)LjHIU<EMa z-o|Dc7s-NTQ&=fFa0)c+=DdsZBnz0M2YJO53$7`E!zHXlwO*aVYFH~e!NYwll4bzx z8~~rPh|;Zv;F&%Y9Yh5b1=t*@Y9Pc47tqZ`pdhIozJpZ_W`Jr9xYZI&e}?k!BHh8k z!PW((c?sSL<i+=Lo-ueb;$%KX$+SFnf$ztM1d7eWdx2K@^QVQfi|;Jf?f&J_auH7f zB|ba~mP)(xEl)ld*cOnKAHy8X<3E{ag5>h2s}BKB2Rie#T&8s*x}3obzqt%}T0Xn` zs;mU9C*aeK0w-jGm-25~7tLCJTW4BG36u+b3Mg2&(iK$II?hG1gRoZK*0r=f%I`Bk zApk3H<g<Ce<OL9AX$jB`OIAOlxStOzy!GRMZFu8LKgFxj)3|R~9rly2AL)Ada31UH zB>-UDQUG>2m@7+lav3nOEbdV`$^_%cRI4(;Px5~Nn0)KTO+dQ)k<k*s@)F=p%1v1W z<TE*-49YdHMFZMQ0Lla?hMtA7oVvVla+t!wi}mGo0B7n|fZIV`JsSgH6nGa<6)1HO z6V$fu-4q!^#v1^>dwF&cK+CouA5P|s&lC+hHMw{5!m<dW1k5Im7V|6QzaKdWG|Rhs z<WJr4?BvtU2J0tQ(r&uIQ}otyz^h*qj?Casosy0+u}!-Hvj^*0pX)kfnL2*vZaqrx zWM7Lr0cW4-j-UW&ZEOMakiUR9<f!9nC+6spoQbdOyxxUUWFpFa-02|aDJ)0*z@QUn zH@VUlk#E3s@>frlg;tavD;xMoXEOR2eb80HIC^v7$T2K|FAnD}ygD5F@@vDy=MExg zC(Z)Si-1%B&JU6EB!KhrL%1ryN*RmPUE_jr#M#nEshd;+&ZNV7evR_4@hbe<%A?`- zH2~n*@!{+%r?IT0o+sJ#fe-x`3f^vF#lOj`?i-tKcxdIIr95tJXom|Autr|jpZcL; zVv5a`3EDLIWf7+Yk%ju_28aHYw*Z^9WL%hk!bJ5c?fWEU$6xKVlX!)!EMr&Ag*8B^ zIw8=FRl1ul^Y@T7{qE7zxHAHDiY^P#T6x5!_k?dPUzdlwA6y@9eCP7;{=a*7Sh&qc zHTh0!>WYc;B<<snfHM}%CyxTQVcED3dg;f}75l`z$pX;4XNEG;mb^y^VT~Vg{OIOd z1DxG}5N~(0N9)lnQn;?gGY^O#@Cyd)b3ANk9%@^Bm%75HzxMV2SeAEM2!`Yw)&)@n zoY%*P$9ybM5MFwF_V^({D57_Q&HLEw+mEHIfb#^KLF0ZL&32$~NEQLBxCD9z;H*z^ z-Mt*r$2$FCm?S?rt2So8t?o;mGSh}<=Voa)jCJ&p`xtxNR5O8NK_>cH$WnLcn@u$B zg8F%g74N;fbHib*tY-jY1*+W;(^ZYYU)ClR)DOrxw)uLr^0QC8e*H$udEvF!V&S|e z^&yywJ|GwS`&hOjT6K<_VG+RDS3>96EIoJe)!_tytQ#rWd?ul~C2xYc=99WY&X2IZ zy>qL4IQtgP2`pmm&#ZH0l6r*a`p_8lDlPI~V{Ev38J8OLiN{W!8V(*ln6_OT+^T?a zBTg%m3oBLKV4+8z*RNk=(+7Xr{B%=N)>3dt8SQ(OOX>u!`+`CWA6&T-!1?Ss-RfY? zPTGpcL-Z+|(a5CAEC2LG(42q#aJY2kQpTa9Y=9r4F5N8i%`WFj>Zf`c24OO;S}6Y( z3-W6>uHmlaF5~<Jo9Bmz)40X34cOP2Prx$jU~OZWs!+cjOLyV>c^!-M+3>s0M$*X> ze5jCd+0FD#`i_mwJ?IvjRhHR4lXUr^_x3qYaaZEU3bkxLegd6kfj`dMLK){sq~<z@ zB6^O<iBRWYbBv$2uic<OJv*Er?LIbI1m4{4dYv)+b@YD*OYc5rg+LTo{jd3-VU8S* zEy~`O>^VR6!yo@DoI>n;=1qbsyyR<24{5?b={?Y{(9DhD5NwYc4er%n`xq1?ss!2M zg}(}|B~X9NQ7|fe6K*{7kItKkz?@HgVE9OalGzUTy9ad-x5>0;gUr#D{Gtcj?WsyD zVd+3Q^m-1-koMYvp{lticH-O4OxdVVx8aav(y{jpx3oX|C=w7(Fwt!TbV@l};t}7b zlU#H=TuCxPrg4+me;)B)n|wl{BGrTBRgyAK^X7qhwzQ$r3u2lb;fZJb9M*OnG#Q4N zlCf`5Xnk)w`EcLBGI)ePY1>ZezZ?hs*|+66=kx*GnxX@qKC}N)E;)>64F0RT8Mo?5 zacex{RC*)jKQWZ6Kf&~VpabYf4roa?dFSso@9nmqlBYMleo}$qrRq$2#aE-}vzEH2 z2{>teq6bNz>QKkHX#K4EU$m5`e3B_0VW(yp<<~<U>Mg$Fx(?)leDcq7ns))Hwgt1{ zNhc60brapKtkW-a2^!ZCXmn69{!3q$`mqkHZmTYNMqQ8Q4?MH~O6HEC^1z?^SuaJ; zH%1Z$ea9*fpP)GX%7CQznS9B4+L19*@H%_hWnOWsj3HnEN5!vvBCW`!<W-cV!E-Vw zT2vbb4XI<|#;qU?q53A7DV>VENb?+kY@jt_H2&lt@oOw6P&(eL3886x58Ju1VFUee zjhk_VGm~{5D^F&l#BrWibzMA~U$vnS%G};{hxH=h%)(M3K%$Hkl*Dd8X=PvaPzF5G z+{YT>=YQycb1$={_Sn8xHnyGptoL2p=^o?X{@(8;qWpRI7Mk;)S}*IeiuosN_!~EG zWS#$;zxkWYJB|cbuzcbS(XW<Uh&*>)A^uGc8GE+FKJKb?>*He7GyB39jr+;eT8uEe zExV6Pr|3Q@W^W<V+3tBhj_Qj&v%g6@-<iRSCH?qV6zFA>{P+w%efp^celQ6HaQ?4< z<EwP`4g_@gj%sLeEez=Vov;w(J$=S#a4|3qm_O~R(zli!5V>9ZT!6%do?w-huN!oN zH6g2k#Cco|V>=5}os^4LU&-AUK$5P24%vn#Na-|9&~!gORrfN$2)6B|Ll$)23&TgS zOghZM&B^a33nwRl0nS*c2M}d(ZU-(sK|B4*>QX}f&*5WIFjQZc1-c=JfNQl_6r7Sb zLD&qC$Vd=QIxbGNl(wVMGFqTl_XcI@>0rp%OF6onwNO<y0<40IGGu%Q;oey*PCISm z333bS>UzV$)mLx?rG4#L;M4lFOb$kZ!SW*@Ea0nEwxFf?3$}IZ(>`%By?~?uq;5R~ zkp&<_7kciP3MRNP6`Yl}ma78P^58(}*X#8^rIoH_G_DJ8Kd2<=5cdx7t!$Qfl{gbQ zWTl*yrMjY<63gi`>({u-T0K1sfa3!A2_H(Dqzr4gUr-z3T7&Z*z?Vl@U+p5@)a$Pe zpZ$>^9p3t}A0H0lpLYQe_6hauhZEP)iLLdgEPn5?*yaP0$V_WGH!++L`O&F+ckd00 zyr!g!3<Mkfcnnak1$6n?WbsbfVT`%~2%(OwcQ*pkc=(Hb8FH$LjX=73>n4D@XG1by z{Q{e(6ApnQ-9sopL8VxztvyR!x<R4tnNVL}=B0c=6Naa4^FY}P-de|r4;^)o<x}cZ zUiG2vE7)4D=R;3`$-1&oH=N7})TpP{i8?2rPXHL4yr>r*)<-sh5=PsjOd9}nRc{qf z9-bg`&jLo%d>G9&M*!!h<60Z5>+#<lV2?>9^{y54Gk?h75$<oEpz~sx8%&C%*ZZqX zFyRLh(f#l%!_=3ujpeht$enFg-?n=JI0U2h1&k8VAB+zN@pB#j@Ad(E4^tjpQpg9J zC0L<uVvV{V%T%pUfBe_~?(q6A{usnv*ki?urSZ+{0M7FOZ+lMQ3mSjQr-&N|2rj^J zow3220RYD1e4Nofah0F#a(#_A4ptY3TUVEd*}LdBzLfV((?0f~SL^gou()eNU+->U z?TyQjUHBCrA77<z=(_=dXYcE`-OYdl<UK)~q`yUmg31CIE=K)OrGVEaR&SdCOj?}G z-hVXQy|ai89p?jH_yRxS<_|g?$uZe?YzX9Ei$N_*R`^io6F$g!^9t>pH%l&l<~)3; z_f~@0@rU*18m?#t{8bBnKe%~wxb~g*hClef{>^aX-3P<stbiR0IRBw&`v8*<@D|D| z=T72V{{U~MU|EkvrXLoxZcqqx4RPaFcbvEas$2B80i3C1#~Cyp{lj;(bqo*XOWXwt zWgxL<mBhuU$_<I|0N3r%s!gzsH1IE&Y@gydsJ=-rR{O+OhvdgEfInqjjj<?gOb#Fl z=r+b?<0P9G2LUXP@KHXkZ1<r%yKoPq6(<~!o~0MMwG2?bggmvJ_oISGu~4;t%Q}!g zA$1_{Y(AibH3o8TS?BQk8^D>x(ggjqi!8WLzhJx2*IZnHr~?!@<1TqWTJQ~w*|^h~ z#xmNscWf&G>2}i>Q7?`I^+8pcmE$`5;aUNKBW&cxZIkV2uX=;FqhHF_L;lq_b?KSq zqkqyxQv5~(bnikZwP3ZsvtQ5n);7f~GlbIj-o+Z$adDarkyEDt?FGSkW?39x<gs4o zw!JG;0q2$S;mk(W(bK1~R&IcE8(-Cz=xec>beYRg%mw^SU;E%1zJ-qu$K0%@9v$bR zb4gd5&ECtiAUWEJh}L4^{FHI_?76dSq8tFMMqh1*{8RS|aE42ZmoVlNsP_UE&H~Pk zjmLFyLVZp$7P2Q*Wh9^QCmH@};p{e$7GWP?0X54Qc7%<C6UUDXCs=S+SxWD-$%W3X z;%i>_IQm@nZHvc`mxoK2v;u!j`L>1&SR3m*T0RB3ZO1jAFi$rUxTk-oJH~(W<M`!X zn4ilSbDr{Q;TK&aUgnd~(8sxN0;tcH*LJi-+Ico^=kDIe()~Pn;&uf7)LTEW`8nFj z7Xj;M{AeI!k+c*Q6~G@3;%)=15oF41T{JDVagn4d*T181uXE#{dhXe)0!_KdY!q58 zQP0aK#wGi08szDr6>)*A-cbG?E@yTW9y^%mJf&>)R0a|$mY_za0VPRi#HR+g^EgV> z<=jd5H2obNnEjZW*y;O}M~E3yBE;igfpwOcur3bjsDLE+HdsBcR4LasnYyyiu<lf9 zIkx=?hI?;|On-npte>98h;JK0h?k5y?TRW8HA(`@T^_9rtw72o{T8{UO#JnK4m%-^ zltA@Ky?7_BIvXU7I$9n)v+LD$pU;%(2CkB%WLpq$Hj|`NFCpTlb*+`S=H9tka`)Pl z=3_E1>Pg0++$W-;MoNa9EKSAC<LEzE(Cy)pvt2lr`rAIL?I%Czm?GEhJkq-a_A*-@ z>rEECt{)fv4_{nyU3zC;q2qI}^NhdfPpnzpSl>w_v4}{$bzK};IQz`3lM!bG+_Eg) zZ1Spfq*ov&ajY)p$dfdLMOLPgKs$<>H`YxBMp{ijjGMO|Tl}h`8e_^r*+ey0DOoG_ zCUYW3x7~0sJ>yzc6?Z&yQ!)9P_s0UxMl1dri<E)7fj5idFMQ=JZ7w)^|I%d#g(`cC z9NsD>;mWAjpA<>243J$w-#oYd8^`rX`?Y%llg4v3apLi>1J80<c^K+7&r>g4yCLT_ zbtBzQOOpA?3;(j7W}MbKnF#`AuJ+}a6c-(w9Y>-t#CHx~s?U1cxd`b@<J&e`J1aD4 zroKpJyG+|mdu3is9C_X=;QR~!sLJ<}{x<c3T9ezh;`i!nIh7DxPq}`(eEAZ-oBv(T z2bo8>rm-G9TQ}9$XgIS;oXeDN*YL$JesTEaU;gE+*;J0gC0xTP`<8!l>)Q2vArm9~ z?Tq_;oY7s>@1yCA;<Ss7VSG6J2f7c7FTf|6{5hh2s7`($4o8U{KVLdw3iV>rAF=W2 z#itVZOO?Rb|NPs(z4e>_)mPKm_Cex>II_d1qpMEe{``5>xAP0V3}RY7VQoj}Zg|cN z+)2?oL3cHGb{$zn65m5QPUNTgP?%}7G}Q`gf<?W)nWq4`1VpD8m;{jGOO(NA24HRq zU~H1ct}kI1paPc;jInI?IY6%il)#ym$4>xL1>yu*kMa6^{72rtReTdqOC))-9CrAE zuQKkUD6g#q7!l|NBm*#Yvadg6Ej&%<;2<9!0(}l1?jXCUvv4UZG<=0Omd}7u=Am?y zu{4b1V6AnLeva+TwTAYboloKj2ns%%PC(0i1rM}JD!<PYDYLJ|N>h;0xDHCj)m4Ks zQLYEz-@`JQw}4#-hUJO>DWhc(ko0wA2RdCr2(CJST2^U22BdW{u4OI6!oT?l)N4sC z-I@$kod{eiYiVmq>u#<2YxS+W2|)%ew$=fh`|HZP0fMyt5^&Wo@IwHh{d`dH;^%*4 zIC1f{VT^RV0nh8_$e0D~|Ng)H%i%sBP13ir8xn%c0{L2b-M)D<mVj;^c;6Rpg28HV zECS(8*AFU!z`Jr%hRVu15J=X)XMD{P?s#r`KT-)BsUOQ&AEpF!hnD&s;1_<ZYxTnq z&k0Zmh@zhK4W0=IlM}7+wQhb2s6$S!Q?blN&d}B3URlTG3Vf(n0?NA3P$zsYfGr^X z6q;U3*LI*%DsSDbSO;4F3x4-{w=G%!PH^4Gu)JCUMNZ^tyy!gqdrsSds%5jy=-b)U z0lax00Gr9^3VAXe4dA?D`yd~EpKB2<5WNDh^A!Hn5Bm+<Vi@5Xa^xeZ>qHg3CA~W3 z1{Jpz!8S`A{jdtXjH5$)0b!=-V<stwVVk?$IHDb4jj9zdW~uN&eFb#c9Dd@z`TN6X z|MB1E1BdVmu)4Lrgys7qKB$L2Zs0HW@B!RvO#2o)Oi)g&pf@&jGeiFY2)ltxi&d<Q z$Fl(84GIA1*}M2hegNQnoY(jd@rJ-OytBw<nM0i+KLF?PaqCannlF~jG$s3)JGc1& zgg|@0@ZeJ>=)-~G^aXqbV<9~bke*37O6LSznMkYr9$P0H!~J_&kS<UM#{$ZoJOjAa z0cVjg0c(9wqf~BWxk<CS0^p4A*Q@V8B;EAz#^+u`PRP*@3{vmrA%L`k^)(XX8JiCC zv%}rXSBBsFKmMQL@}J%u?qAW>27D2BH$eUbbumRBeBs=w;Uw-z4joWOv_|)5G2nZh zH!c9BwWxJd5M}~8TSk2d`YNcdM)(u3%>KmRXwid?$sd2nSH&%jAfO$B4A4MsS~jce zg3hL~J;(CiK9bn#nAUfzfXvSj&x-OvzMEKQ4(QAjAMl&OBK{DsHXguYc^VLH0@pg@ z=#e_G#b$v3rSzXXS<WWiW7_W?`tFkeq<$z-WwwrbzcXfi*tpY=*e|SRLsU>?g3Xcr z^wpE}U6#<|srSi?+y3!Mp#`gH9*bi?+;$XqQwQNsmpfS)C>!5hH7nynBVwZ5%E5l{ z4z8$Zbi)}oWp({gANi@x3|d|OnO5KN6fywB)5RylV}Qm-Y)BphfcI^I0c-z&vE<=K zoAit4>Obv29`gZQH~s80{K(=#{4u-vD6jS>TEN<$SzcI5m}Qin8-{Ky9zT5y|IPT% z_AQo--9#o%2aHGPhrt|=u)@A^<!XR`!GB-1-3FY^rvc9JplsxWLZUDA5l8#UbLY+_ z&wXsd26Q)~<+BauT9(y*fPFMd-|zy?y8bwYMYb-0CYj@uJYh=lOQQXAV?%h)je#rI zuF#I}#Zvev{-zJ(R>PQ%HOf#oFX@+c+?35Ht7Q*w`aBuldFLJ4$TRx*y@2HC0^_25 z?IIpCmW&Zry+1b-Q8k-g^k;6CjU)Kh4aaM*U1WCw?vO+2Z1F1KoN<Ew*XHMZ<e~0W zX6N}>^8;LJoW+X#a4h3(SCAiGrSHACo9{57llIZJJ(!_Hj=Gc?LDYvy&5vh1@#rA0 z<xXatEWeUgZv7ZtL#NVrIT>R+-smy}c_b-mr5?PlBh>B7;6-{nC~(akGU;r}f0Tx# z+rW=>B&r1Dz_YZxBSnIXs&(GWJj$;kRvMGY1AUlvk^WD?r_b=AlsyUv8X21;tUV)c z^_iY!SDq`v&azV_El`fllYGqEwoJd3@+7V4i5(i1y9pz!R%T_`!*W5o=<bfPCkB6z zw5i)qI*{g%p{Wabk%)0~5vgaRpzA~UA$I*UULrQCMM<46z!`enYy-|UZ%7vEP~){g zAat~qc~oTXl~sywBID=8-^4Yr_)o0xtvrh-pC-KoNvT_}=Z<7V9@3Q_v?5#U-6M1w zEgoA}h820^*I|r+mwDFn=WKZU)9b8w;~8>M_C|6Y7rGg<sz2=Ui-`FsuZo|#a=uuM zM9({2$E)NFdzsUc#KX5@dL0&R^~{Izl2c@BKiBEjQ&W4C?2YdT8@}X;NE?w|qKvAg z#)uk=3uvzVQ*HF+OhlxDI#s_ebph(Q*N~Hpp9$p--Pi#*yB1E`5JL`ilk)X0$Id1| zaC??hzczVfPuZIc^9Vu-Hh*Y$b*ZRbE}o5DaqZwM9|HTF1A)5!$UF#L65KB)&4B+l z5Ptp}fz>{6!_jlXottsTPg<GF7_M&mla9Y|qAt?QJ4Uy)PF&O=L(7peCXMOsQ%k>t zFQkeXx19Ss*QZVR5n9J)uie<LYxS?!VU6R?3FKif>&mZu<sXKVm-WZ~vX?IBeoub6 zOh&ErRm`lB|L70@aQK5i_=Ci8!#nQIm}~jARd5HMDDx%Oac{r<_VA-W`Xj^7|NJjx z9IpCuE`{L|h5&24edidwGsk56p+6&Dw;B6TjOTBw9X=oSU3X-w{@DUv>JgEZ+&+o! z3&m=Yipv*D@k!a%^QLPryZAPkmn_j2E6=B~K9#`tDS>U58gyJEkf@JN--D<fhaG*a z$6R@EWWlu~eynu8m#$|&;N`$a$FJK02U>=K(F92V*v_*b{k0K0G=DC9e8t*{%_aci zK0vW)b|d#<&81cIG#~$(0&5Wf4B$+>X%>1~Ixk~EtFOV`009mtmQyfNfb19+OqN9} z=DmO&cI1LyS{P{=JUcswMb<+WVSHqe)~(N37oS?Ty4ZIzZ?m`j2Uz3@s!Bua<GgYT zDCRTe;ee5Dm;4>zvf~O(pKBGYMXUqrGN7NYQ)~5XIzcrLCq6Z3m!+N7%DN~JK-4vb z1Gqf;u_9$AZ`PGyr9W#zut1jyf{eOb(7ITl+yN~-wVmGhs3v^|c&bGiIhhu8v_j*@ zm*>`}3vpduSPt`%Ux8QMlqdtOTa~w+qZV*l;|h=|XK9+oYXN@qvn+z1PAHrxr0gW- zQOYEr<qMd!0F#zWV7o7@<U`=tc*@}^{M^Rn#S&Gu_b^s<)X`qbKZC{Fk)wx(|LuSM zm$8&KA6;Cin=bHHsRt)W)?2_1__plooMCQ!C>QIIH|nV%{4S$2md!GGXz{J?>_<i` z0KkH{>i-lx2x{wEMmkQgs?4-2%A$U`nIecTz0_r!fLqVCF~Gtep;%5|``+TU{D9(2 ztdz=<{3FABln}nPhNK}<PXN5=nn1D>6M0r<g3nG21%K6H^+RAs8pg4l>b!L>sBV09 zFCSDPKfz|}cZ*#ad6H-8bf8&zc>N4H=+|^VK4;x%a3W;cOD6#K;bB#vlzi3&ci~ZM zKCPV#xY#v3TE$ut{TFl=XcX{L76ldxOEBqV;%R%coIFbV>HUe}w7gMY!IwJYJYtHn z`>|2`kzMGtiwMg-j%Bd@$2h>Kn<ZYq^&7u9ocnu!3%)GFGCITC5V(qXFsDly>KAM2 z1BciYp})fS3x(Imvh9byPxlxA&a?tHfUJA!VbAKYFt-B0riC*fIXkwOSNd7R=o1)O zq&$28jF;+2uPWMZw0fpp1A5-NfsQ}MqIG>{xbQmuWAOnk$gPf2{IrECH-8BW2m;W4 z@9qOWbT&_!_;42=Iy`&!FxSR$OmMP}JOR74f=Qo`rTrTIFrLzPTzO|6fK<SluVGIL zh%0LVVlAoR)eQxDTl4~p?&U|rL;St|;lKLV!@Ga@?r`m!w}-W7)H5G8+p`OBnfkIX zKY!)~{V)Enj{vw$`ju$<0eoN&fX&0Y7Uom5E5T@(RDb+Y$NF!MOAYHAUC}yI_aD_S zSe9BmsS9byIeXO>G6_as1Zkkr!Dc~m+l(;{vyG^aTHolWc@@Bzo{SIrsWWUaFfP%- z3`ftL9}b_yV)WQaKwvf(chgqXOFkB9oo?<1aM$GsG@k-EyBW6#xawO1XV0IDo~fo8 zm(%85T-nE~-(KRUn7-}S?K`ooHje|i?9k7#{i^)>4;x}CQ!CoGK!es8WtzM1M+0x- z6Zst0*T(_G*=V30#ad_=8zJbGmax@k%#X1bxw`olAI{Kx<FlU!Tc>ZZolqu$>{z!a zx@}hXE7T2r++!@NA3a<I<a|_aJlF)>&|<qvlm1EiR!d))I%inKD*8U-v#-1EWn9^N z<aoKZLO5DByK$v11Q=-dS;#}^_RSmA|1;co=!bbaV|T^{>XTZh4y%01%0|`uhs8(u zjlTW?7S6};r+qB_xMOnUN}YI4p77^k|0(Yq^pAJgymUOW4&79AUSVAOO&SMzkZ1en z8d*Sj72Tb~&C{jJml%_d4rkAtVe<?9rwt)lV%diMC#UFf{yHmSq0H~f^-IG&ES%2( z<R9WgxzlcP%9sD(t*i*0r$o8|a0Jg57M6y$zx^G;HyJ|?^6|c7fXDc`MrX#Te;4w} z55D8C9KG?pNt^YflY-p(kJsn)8*jc&y}%<oY_V`8e-fw9$lMMc(L#C!*H&})9t3b+ zU|hcVCO(|0pFQ-gGEHwe9Dg!CoLI&^87?(OfOATu@FA<*l_eS2znM=oUcI-7{^5Bp zy(N14;{}iEN#>KISk_7%NlBC*Qj~luz|T3mh>cE5q-br+Jx_zZrn%9VmR?I;J<Y+% zalGbOwrlCtqX0Rn<rbBA9<fABeOhMnvR~klKR2X}Rjy??qmKxjx}rbq{YUaN|H{{L z_3=UaA(WGJ{Z+mpY&blTlbLZ&lgZgX#?8Ehv)?F4+2k7?>g}qhOQO)01L;cDGPV3# zSmOCiGVP|KQ1b+&?v2~hnU8t^=i6b8q|ZG1rbP9k)#jzXlYS+EBUrM}m%ek44L1tS z0bTa6uQR2FD7}pFAL}#na~@hCP6F&=l26YoG!n;<UPw#eUCEQobMG9$)E2{E4$~6W z%ajZfs~$%#jcn!6<O0nuGh>=VwI*n#JrUB*#>?}@qBq;RVP8P~6303+rq4PUn9bkl zsNtrQ$cPiOHc@^FHBt+RC95?FVfzp3!ow!6%#}fX)1&DrN&DDiJkxdkFl|w;bZLSH zaFn#YiUxYY0dX1fipZ=eyduw<4^<ryA$q_w0<w`9<|^LEy#~)RHW|HLhk0m?0B18Y zZSrUthhrajU-HYHa*z%`>%Ho+6{e+$7>&$96#x2%qvH28bjOf}wvU)kq^?bjUMG&v zSfe=KkBcn(1nYz-iEBLDfbn{mq*|TJcL$rzLtQZ+BUhZN)JiK8Jcd=r+JMH+y^(SH zOv{{nOw+;dN^f{RB&~Me{DS}hKmbWZK~(&l!|+S{W1j8@;ZuC*?8$ha?2#Sus9UiH z=lJsHX8l)w?jOj;OFOFlL)`{4I=D6{xsC!6i*wZV;gA3LkB4u5^P6!y<wtduzcO<k zA^za{(zTf`Ed`sM(|q~MUmkw;XTO{^mpFuNO&L2sat>Q{-t}NR&z)DJ=D9QQdt8@Z zeUFD93QoUQg80yrALMqYJbw^6&!_!(2|XY8h3^#B%O)KCd0`Gdjrgeq{?a87!1=4c z{u>M$HE4GL>k~Ok$8Vom9a(i|+o@dS(DkR&x2=u4Gs<C`^GO!Ao*4wPAj*tjy904x z)>>C!PtZair!#ys%1PG*X$}Bp9tRxpm2m+(ecc}9<5Rj<Z~$@YVA{RBdb<qRyaF(@ zPv4mgK5GCJ0)OTvIP3jwEVi7WyEv9d!Cs#WhzXGT!99UgUwhTsvpRGjA9!<M^O-=M zKyLR}D@du8vmf{q7|wy*{A#`O@&kd70h)C)Adu_g)UwXaKM3e74*{^DVSMFOV5V*- zaH9dJt@W|MxxlVzUDOI5`=wexR;U%Q*1&>p<>Eomw?6Ktg{vPo(i&R#4mCId`jEzY zwf>ZoptRQP(w-nMCjiD3OjKC0h~+|%W(p8d`tqk0uM03`<Ih1e<pgY`ILTZ22?#l< z_q8F*xyUQmordK%UH7ByMAq^g#tO`j3Cde0w+PoV3NWcVGsr+4lPB;!eiOsOlhxt+ zow;G*F+QUOjRjFj_weZh6%@Sz%%ZLZowY*OEr`J55iAw`aG>C@`f40?ZWZ9g7GOP3 zVWCx^lsdB>R~Pc*1VP=IhUaAfQvE$Une&w?^XXu+0P_}LiGZ;#H2TK^%}0>e_UU}o z@??Tf8PzxI$9hnAHgNf{2mRiSRoDibGpoqz8RgLRhp)L$0e<VJGuHi-p?^riy3xu> z9;T@SE#Mb$eWHG<Gs@R8)ebpTPMupPPSOOTz3=*Im=KEP4mbsE>D!j97j^g<A8hnZ z1JlZjpqa8)DN=sQDF72aBVk_Swq2rsT8<e0n2+FTO|M0^ebyK{r#1TuvWhDab^rv4 z%{L&l{Y%TgCZm8g$`rlzH9v$Lw+((=a1T7Hw|n?No$W%)Xg2|@|Gii`PotC8&&hxC z_lD`8`s?rw=sQjs0O=kA;4CiEzpU)TYIGXkvFIT{z#go0CwBWPyA$B*pMWl7b?S!A zE&!jg&1b{?J5TZ9jF0mpCjpFcjd2{{2=?@MC;*7+@N?tGUdlHkbbCVo2!HqQEn-1x zU$lQXfAJK+6~GY|wAPJsaN(Z`Ep;taRm-b&(#`U*%UO89D*M1uKK^x_G7~?OU;7;= zy2{ZX;6Hh8-~-x?gDdaO(w1h1SKoSTnA{KiMHzJ!BFMRWj7<bq52WD7CK?|OeD-j5 zc<&ouAKv->w}<ci?z^-J+`90w&n+w`b@yREuK(E+Cy(ID0E^UV`tbeKB_Ew#U!lK! z>W9RpkUwv(z-0W?rVru6i}clN0-Wk9?Su+WACY^mZ8rgt+af7)Q8tlj>2O`Um@%zs zcu1ga+kRd_u0d-RTI){ek)#WkUG)2V=;NmVQMd5lyb4fwNWa0lMqr$>kJR!;G%bFM z1)Q}Shk^?>T@x)~F|NA_-&#3$;R14X(PTBqgYn?UMGNgiAj9_MM{)&?pYevrg#F^N z6S!o+uQ)nv8Em`OMaEd`l>FRmP^a$W&fx0RYs0DY=kYaul8^r}4%v6RI)JxvtlVwK z>P*_VsVTRvlivBWce1Ga;$Qo5>W8;%h{swkvT}i%jY7!eYxl~E&9H}jFz_L+Dg>O5 zpE-?w9uwBgn9eEftMcMH_2mMX{+aRfHg1jt;`bxxgY?I7*@awc!N!@q%`1HYv?4e1 zy>;U{{S9w%96QZMYkgq1FGj7*4j{W2^jbNYb{YTv^9y%k;e43<9Ag7GQ%KX>X7fQJ z;*y)}Q$O&F^}oLT?WfP2J)5!Ed5Ch%!Z~p(zJKj4@njK~LGu94SFT}I4d8s{G-<Jt zk4p{WDSyjWExFEa%+YMDQCw<#fW`5H;lc&{Ml;^n*Z1|UGTZ`O7MOP9$PbR%R^0r0 zgwDPF?Qc`Q@wh5E%v%}u&3?#o)3!@m<$(sIPO{-bn=ssu{@n#!XR9T?sxQ29o@@1v zhs3X6PtVvzBHNQ6_q~7TegNl3^N)s$pF2OCIE~f1^9s^w6@PMR7*0OnjiKhlS#s8P zWX<VC0B2=3I!v1M71EyxR1{><W9~?k%OvEXH+5a{z26bHJ>3a76O;p0rY;H$HX!{- zBO6dQh3m99hqQIva_Z$sI0@0w^ar*}h=&Go+=y~bU+a3VX@}8Cbg}sA^k5>{5QlVW zbK%r*Gx5}DhZzGB+;}2?lp;lF<;YWM*={-Kqqx*}`YsjGB&JZA`jNbd!@a+><re06 zm%gsW%|1!HPL$A+&r0pzI@Cbv@vl7#aUYI&E*=6LhaWlH=F4P7PyKhpy85AvAE9nx z=u9i?w6n-u`t+T7vx@8jE=oUnc;b0$l*zAUS^D6O1h?a-3^ufsL%PP1Mq;%;rm8e) z6a5)6B`1waWk7;TE-9oks&FHDnb-tIb}DYWwtUh`rqWeE@*|XfHpMdB7Tk0v<Bz%* z8iqU9l7<KOp_fD^ti!nBxaHx132|xhKZkw2@>324I7`EHoT1-DoOCG%&yv*qp%5_^ zsnK6$B-PG_*ZJ=Q66^$=&7kU%NAy|FcM}Jl$YulaeO`bwkK5eAu;@g;&sgIOwB_!& zOHM@F!3RM(C|zSN<uecdeI(#ayzO$xS_;t#wfgW@xkhRwzgBNm_vY7r^dq)`xGu3x zOI?}z-2R6%Q_Jo6Qcgcm6*dB#d;F$Xj`757=|WPbwgG46OK$3CyjC`r85-(N<!`%m z4#gwFcSnB2VSMgm{2pB2jkS$T=OkJ=mwct?c&~AcXGdb+xcwnoIH%%v)C`w9H7@0- zVh;b)zxWr!<x7{cS$zUy0AmUqyRom)hw~KWzrc4mzVVH348QnGzcl>JPyh7r$}6w3 zCg$5wtlNxl-TU$259@$=ebiC?7*AB07dWC?pA?UBruudi{gaaX<vmZUBKw!fY=mUR zzT{Fxe_k@pPsx2Mfghp-#=iEouWfzx*8rRy4E!+&xH$6Y?c>8uF9Qru?eqi|ojSO{ zvW-?6b~Rh47~h68xIH$yKG`6j>?+dXdv+lvG^Fi7&sT6$+U6lhxd$)~7%(86t{RTv z^Y0K~tAN8Jd;;4MA9vvkZ9j68kK@tH`KqRq6`9+Q6|}E}3e-NvdQ+fIaLt9JPWJ_E z_W`;Iej$l0u6=$At07A^H#ax9DAWyy7PbQ7rm-`Bh*hq@pu3KOxW+lrd;)8UY#axO z8Ng-1a?9jGTFYkLXDD+)J^dyNoH>y=!bk6%<Z8*;WuYao*2T(4cNhY)@}_$Q%OhQ~ z2^eQw!O{T8=8Xlm-KpuVAHhn&z8ai%hi?Zn0o7P=G1%)0V-eumG6<TauHaRE1=H09 zug&Wamb_jEU?vai+r_p#>StTp0+|Ah-74F1SZ?cC5WzeI9j!CtDQEo*>kdMoLm*n- z)w5WfkTwf?z!~+hKxcqnbVt_+y5ZOW%+nHV&)%8g;o|ae`}X~~lPFLZpVRoYbp4=} zcI1c5b;Gc#egNufy`@iBC(8oG0$BPY7332%_7$foKy+nhSpp(A`C1v4!DAKhc%3?P z)1<#*EokHs@D={0>86Lg=<_-o34}?<SL~(lgg)*e&=Emb>(PyeO@NgN0MT8z8(3i? zM$E`jFv~Bh2TY<JxhrnHx;fyaPe4{Zldd0q(ub&esb#wIh@2_E<x`K<QO~i2BTRrd z;4Rnc>6q57oIN^lB;Ov^`|?V;m$6Nj|6<xTa#bdlQ?CIl0%g)bmzDc7KBiVOtFR?3 zs4Ryc92BVc6;s`CJOd2Xy~*l|ZC)OjZ~<Ot!-P0aM76?}e>W^_4*?|MZ$jS5UtW~I zA6awps@w#A?8Ar=Kw1F*!ms>;;por)P59z%iCwsj*tLq>3UFR}Itlo9XgGQHAiyY_ z1E5Ni_*&Md+^Ag8wygS$M!^8wmWMkx76AfzL*O9(UymIQU|oPSlX|R&%gPF#{3s%` z{IXit5A-woC)^b*_=+7?!ms+8I&VnOXOa@Jl7|+qg1^Yt31C2H!0OrivjBSckTaH% zGe?HgXHQUOB~t*c`DjI*#T|8_59dujKKAVC((wLw?jlnF=Qlr#e_~`aiL9~a*7d^} z9~^VCPYRZewB5}o0LJsft@qy<E`RgV@ctiPO8;ZKUS47o2$|aVoW`AmmX=46-@g5{ z;Ynx#I4?iqZHakwm%d~ldO1NMwg8*8D)r~)pcYkbVx&%KTlP6wEO`b%w$1}Oqwn^| z%F}gEuDMs&>__a^>SIx85cS@{1N$j0?ggAz0OZDKFOzI!PU`{z*BSe!55>L4W2`t2 z@b-+ZDh{wYX1}P+QAGE)kUgUvb?-PshVct8;4B#Hm~-wG0Ou?iNJA8v%tD_0!;eAe ztZnhe^;>Z@qlNR~qxc)9pSLf~g5SDUYe`ql0d26I?*N=n18yHZc>=)MaR|;VFHOgB zQC-cV4tdyDZ?Jf=KY9QC_tK6&|D!*~2U&T$g}7R`B0!PF^yes$MGOC%s~f|EyR(3z zZe%^e<;(fu7~|s}c_E5r$^w*pY_nOgT1V8!1Ax?<H*V5*>`PyI9G4p5%ZiI|NW)?- zAJK!JHAvy9=k?*{H34TnW_#i+x-^ykyo2HLN5=et3h4_BkQ;sDFY%_r{Q%B~7>Cnl zl|7Xhxlo^uMYa;_Fl?(iT+GeQM(0ies=Hb3SY%yxz&ZI)YRl}#fuQ>;y8Dpt5!}3W zD;CbDPXdtZW1fnrSICX8Jmr(RfnVSFSVu-{6#vHc>ugpm061e+&zn1LoXML<_3fnh zU)r(h97lFD9xo1m`lnxK48xTT{+kaTEKpvq0yvvSkw^!bnx7khwv(GTZ_;nvWE|Kx z97RT_PM<(@=yg@0De|-2@||&lhtFsmx6#=}@?POXnXi7v4G%UENM}5|s$+{A!wEiU zI0Nne(LiU2%D_?yvMYJ7Z5LeDH4&7n0oFyB@npJQ5N>!%9HZ4${u(FD*Q27?u6sCf zLbpfRaSljIdmBBM4UQx=pGKqjt7poT7<H4lbzQ!hBaJ*A#o!`+hkDM>HWRv>)r<I` zl}9Cse%Rl{+MGUnRMHW#DocSz#X`l|8BS!&(Ri=trMrr`W-rREWS6-%aSL#^UbxOf zo=Ydha?vuBq6`_<>e0OXPmt|WkXG4B#+Y>&pOh`YxZB~yOUZjX1(HyMntmv&^gM<n ztjA0`3Bs_OyN(}*d3O8G8gSz~3{ro^NyXO{QMK<rW>n*`&bwa9r`Mh5?PqyXqVSR< zeSTvMiiA`_OP0#USkkKS_BgWgiL&*HdDt2~s(cV_a;{MR649(|PCo1L!b6^!#@Nb* zn(uMw?<JLEq?b)*tvyJ~IQAPw#Cb`(Mi9wM0*P1UOqytzX-k)kQq8#4nQ8r3Oc(ve zj8rPW%F(nbB!AU~I!N1Omk*IPG3HsjRzI>p;A|f<#=Nj}z&b_`@~da|b><<ExoLy+ zKlC$q_6gT{gR+O2wuSqwC1~7r9u2pQ#+1f(xcroCE3C`0q+(p8Al<HPq<=nsX+?$A zc-yZdJ2G{R;usRcp41O{wR3dCI`x0+i$>{NDcl&9mf<v_QU1NJuuMBQ>Xe(neJq>- zg5At63ulS~4a;VRx(o`9WX?LY6ocw8ZOwTmecO!nNF9u70i07Qp{Zz;d+H6c8Z&+6 z7ygqL|K*%Y^bk+I$$L8tYBGud3GVvw&;Hr}FuecXd)fST&E(H@wCh>d;(1G$I(foe z%=y%>{_3v|U--fovUbrpOL@nwriMqXg-W-2#^3uKUR5`LFK|R<KPevNOjFoV^iN9i z(x1N&qrKQa3`SM7mt3mo&r7EHDY;K2@I#cq*l&OBx3_-npZ;nVMS^Sszye-^Vzv(l z8wX1lur9Vex>c{1oel&JS#<rG4#irK!QVx#*08=JZH!%f_{wwzEH!A^!9&{ordX^_ z2=H)iznsZsCedR7e`a`XcQ3$)lQ}zEJ6{JdK_`6%3;td>c$B=%O@FUTv3i^VEY$i@ zOHbFsn^=NX=UyPKW8mS#e4q=O`b5_KfzNN;xDgOlu<!_=fk2?3vTg?K^mYH>;G{LP z1At(&gL}!y33mZkme+C%2%DF{gJ7S$o7PFJa?<Kipju!~3#V8?QdZr0`0+Le92c&T zNd68Wnf&Ao2ndL-D+<Gnv%$ny83|;{ixY!NBf!SA*?5GzU@_c*JAfz)UwQ1-(54r3 zl)nCxwe0d<@WFDa7y8%~^gP3Bz=jDvTRzLC5^41<@O}5*-2k=9O&alQO?rVu7xXUR z4Ntv7Pd>bt#{jv~qi~c4J+1KML3#5*Jn|GwtOY)9FyLKT3yfPw){Q@33Aa9s8xRv7 z%u|bU=@~z|ja)oz6LEWit~)W2Z__Kc`d}rxNW9|Fg*<u&&jR~`B-Y(CuJv82ysQ@! zxafBxC!GKq&`<|WYyBTPek}T|>;s6g*ojp(Wl+Y-+H%ReR`R|Duor;b^zx`2-1u-K zLNHFtN!zo0nx_`dkvX!IM>iH09^pm<oy{Z@I=;RoJ%KHG)X%o%GQG03{mM&^Z@7~^ z>rFvaS@<xeR?LL;`jvMN)2cfu7wMF^=~v)4a)G{W+-oPaT%->e)>sH4#8qVYlnth* zSZ;41+cos~Dd6ie*4~IVvQa)By}jg~FgL^GFQ6p%0!dn9bUoa_`c{tAb(aM*0D9pM za-RSF|MnjZKk`rh1N0O?2~-$K#6orc;p*^UeosEecJ@5(6x3_lBiYr=%hYUq#m8UP z8}wLM1#j}<z+2ZJ;NoHl@DJdK`af|R_XxC8d$kTYvxbA$h$4J!VHv%Oi;IPYCwz!& zoe!Rk4Hqr~A|7E=44{`1u-+ge0cZR^J5jfP&m<6+4s)~j@&9}e{lRh@!1UAw+zA0_ zYuT)SVOlboxuFP+q$3=_`RS8K!#m%+0sZOW)z`m(&uR2?pJib~3lwZ~6}jm~g0gSn zLS(?gd2M-qn7es(xOem3aPQV!@>oT0=K<;Tzi(f0?))p+tn=*?Q7H3wf&1t#{;{vm zGY*gsqTJ&msDaG^RRqz{?=|$({yNt3>N^69WhP*0e8AKH2`1+o1onZ{xqYNR!??{) z*8$Nt_#y-;Qirq^@HQ;)0nPv;CZ_l(EgvF1aq*4e(CKrObz+#O4c)!}0Cy@!@W*=u z5cm*!&mxFwmp^q!`ELTE2aJKB?bUwNw_$7x=K&7wpAy*t7QL3KUA(CgZG=xjb-zt; zTbCM?tz2px8TQfUAzx|XI}2*={Rk6(8Cxj}<YuvKzjpQda2jy?7*^#|SU5YrIy&bA zr<R+0M-)z3(78eMgw26l0FC3w;<Y#5947fFo||EA3K-YTE!(S!s5#n>mgt+qef&i~ zzzxF!3#9X}y@s2MljUxvv8vp|Ukc3?bnGAJ<{sdS`9}J$Lx8EL&z_=BhPRAq>M1;O zTYV(uB|L9s!0UA^xYzkW=4n1eX}{}uye%8jBu90u#3kR+wfV*2_6K+3PUA3Os%0^b z^_6}kjfXIpuKdW8v0;lo?!nw#`u3BQ&$>)~BTM^{^l6+k&w=T20e&|U(a|T%_;4q! zUzk5}{3Jf*{b(j>*x0b&bm8rSa1Zskhq=%ix+LhVPx;%oZ?S3q2zNNRaACt?A9J&^ zw4^-N2kpl`#J41x761V27Gs_d6a4{idQA^+z4dy0PCG8F<MS~Jn+*s=O}=hgr5(|C z2|8cBa+Qyy-oPEk3C1dQ{b0*eVJequw~l$rXq7(NI)3)_*>L&2%fkvE%5;oA?}rMh zSLdCXXHw21yd`q@AscT3&dAR6wm|El4t1^S%x5W79uS&1WR$w0>^zizH$pw+L24e( zsHEeazaGvdMes>G%)^7AvZ}Lzc^m4v)|C_uoaaS5grQnGQo15V+gS25o;)UXNN=Zg ztZQj~+-VlrRP&XtcX<XKIZ8cAkvflcGjswJxk;EZRG!j|oJd#mL+`iqAuxH`rsQuV z_PQe<B3l@aDj)e1H{~ZzcjLiBVi?i*NXvf6L>$V_yDouphu~A`@P9jEi)&bq&2@B4 zN*<L?woGSV-Sh4#N(Yp^`O40A9aaG=!zz!@><ieKR`(!U8!e6nP^Ya2ckH}M)6CN^ zBzJBZFM1x9JyCkz@KKk96W@m(ob0Ak8q3${*E8c(ye_+*tcP!xt;$j|Nb1Tjggf1e z)8!obNFUwt==EA{Po4<pzZ`5oBY-|S8`=^=R{0nGadXP{KtIs*3B@oqZHqK1pLhHt zX$~&p{>NOhBkKd>J8!8-2IolOZC9=fDqiM@^^l-&n!BVWiXm!1{cCxrj+Cfx^R)aD zvGS|BDSfc6n38f-omJgg-`20s)DQHAIZuJihPP{I*7bIn0~dFwP0=m>N=M~U4l}B@ zvYT_)m0tIW*PmCC@DT2sjCx$t8+9a0ZoGc3FCorOaM`*27X5ud=OnhjHBI$(y^nCb zw%<tKp%$2rv`mv5X_%(kQ{^j1CQ)mksQ@^;2GD(7eylki<I}d1f2g8r>O|2pl`>TJ z0?w{g9AhWgv>j(0MQDU0XTr=Pf0I|MlZ0Y)#2n!(Ka`IK!ZZ3_65-@wP$V?EDc<1m zfBfhFeE9m;|0IS8>a<2_Vi95mj~`>C#yr`!?ppebU;GhVY5Xj1=uSkwmer5RJ7>_H z*QkFt`%gF`f929-^9j+->XQ%hO}F?0`F}F8?<a=s?Zwko)R)ODwfyJE|Aje)#UBRQ z7ta6Fh@VQ}&nbaeIRDCT{93HbR9>yj931SB9R#|iSOzFst-G@Vf$7lc)H8q*Uq7Wz zq+JNQi>Sq!ZV0q|aq_wPgxBhcr%zi!K40n78aM#7g9Cm+{lJy^%7Y-EmaCI2e#~Q> ziOS4m4J2BoP6Fi30+a|?`CR^{SWvit5hPm%;Cg^H@;*Q@fg}h2y?}Tdx<cS5Q0_lJ z=+-;xd8}{!z@Pq`wW`t@S6(})Ch%7iD6AE=vID>~f5AM{Iap~`C4eTtR(!FjK_2pD zSoy^*`58~}PdW}D9c=7?v_P|9mU(#y97<oA_57vnBGCG{j}J$!1vAmX{Yczf5H5gf z-T@jZv*~pUAn>fOW@YWbB?#z!25J|b<R!2x7-_!pW0?fx)B)?$d-)PDv5aU!=xc$i ztmI3&0>b7mPXhctv;LHs6B6&`$B#7{riHCKqWnEvEM<bCZc>+i;L-ezqn-v}3XoJE zAJn=$G9eFTt|j*YXzSjhfOX1-et9Sx^}zVniTvtb!g9-t@>xJ1OsD^A%Pa6A4*@VT zS!}>7yvUy$5Do{{rR`z~xjqEY706ajU6-sY`G{3Laxm{q_DHP-v2xTRKjAEoopcCd zTOV$KST6IkKGu=(6yT2&FTrDhRNGL}LR(sHW|+TL&FYFW_1d<eW%Dy$eP2Xg%9Mwx zU+Ya730~{UL_KhG#5&Vz%{<ft^+k|R8OxIZyW#!0@`Pk8^PPAqJM&SV%D#W_QqWgD zbjT-p_zd{Qy+`_~F=S6UbQ`kp1j}A55}z>v)yjE|iSRl;Mg;&e8HS$u_;d0mPiZ6V zEI}90PI%R`K7pQKWn<mBIb*-1s}n(pOlx88KmPCji{Wql)2~ogCbgv2N3)wgbMsFD z9C<?l9TZHN#Qnu?C%b7K$ps*oO!+T>RsJsVjg6a-JAknF?k(Y_;M{PCx;hTvtbJf{ zr$nq4(^?KDa?a$o&<}iCKg2)o?7d|`r1jzAo39VYPvDCgpf?LCTs#Oi`;j^UXTf9V zzqDQe>IYa=&*77qO}+g9danSIV^zFMu-C<;fHOZoJmw@<7;%fTuHd`%(mQv#pT=M9 zTYQ+4cFA7KI2PY#vB{<YBMP!6AALJ(;rt9g&b)?y|K2=4XP4+}-R$$N2sS#>Pu7QA z_woTe7YpjAb>c_-76GXjuG|{-QGVP-2XIE=0L9(#FwgoG;9P#|3v9M;DeLAn-U8@W z&gGL9+Vms!v+i9aTPOVBUOjQ~llDMKZ9{$-aGic>6W1A2M~>r?;+0{BkFD+FZ5n-E zKX|Z+tARN-+3^3%X5}IJJIGKLWXaF=>DU)*O7lU+PoEUv{E!XC3EIgy{Qv4JJbG%i z+i=uRb%<-z3SMg=di(ZW0OxgNuMg)V@!>4U54-#)u6-za62KWbn$8Um0q5&j#>T=K zaCF8mq0_f#abVfid&}>cpJTsngnS$5+SRK8KtJ=j&*82bH%crDx7;u`9=Tfc@@gNn zOEegn-n)4RcQFrmv*!^$#xJs&a++}+CXs>VOCR5^)iMwJ_y+*a*8!Y$6?Fjr#7D4( zHNODo@(08EVs`9NN-DPPTsJt^KDe58d-mL!^yRuC%3D{af!8dCM=6z-W6@fGe=T@V zo;sC{KXo8hR;KGe(&uPrKVG{AsH$rV`|#6%zrG<8`L+D)M*>phOn&q+n;UF`GG08U zPn~-(mrd_u=+1;-1WM?*X#cJ*l-m&bCLJ{G8Pr|Je%(u*(o&r<Cm*v#SIcsXIzc}6 zK?H@4;OojNA1cJ+{M+C9M%?#&=B<kvpY>0_x#74==4_-z-_#}LMP9ZK-#WVd{$(ty zuMMxfdY*RdM={xu!;Q`umeW=HrLzSr*@mIVPgh=V|LM2Vx12n2lD9ap%BOC(&|!o{ zT?#m_3`ZU<$9lQ|XK0bX{dCieoV}JOj~;Hk9JUdDwwnN?(aL&6kpI&sw-D~D{_9@J zs>OBKZcSnCX~*UPf#lS)OBCC<lsSxIKAndatUjn`2~UKIUI`?^k^Cxcl6h}FcG_<I zaW5Z^!QABM#)LzIwDY`;cLg5VXG5d$LV}V>qT2S9k%5-c<W-JpA7*VH9OiEfJ9Uqi z#<B!NlrR1{zRN@S2w~G8J?fXhB(0phY_wC4hH@`IEjZ~~9I3be$vb6jButn3NnG<G zN}@MH1eN~OvtEYMC{wq1$=LD{2JgOcs2u2~xmUMo#k5T~)^f<Jf>0;aU)rfh`cK2T zH4pFowTFpb@uXMb{x!9fOOmGDd9-+(dYa0;!aK;?vl+>-mo2oR?*I01RPJy|cq><b zZolj?if3B&!!T(?uM(lciSMSJW2W=e0-V)T(zH6ZYf1VK(M_D_i?k_IWNRe#$rKz_ zHC(hZCx3Z_!^Ej@6}sB3PqvTLbf;@@*JVepq^CB`I=XIz$}sZgf#(96J(I@q%~;SG z0nSYiDz4*al%Uem4=2527vWWpoJ|8Af6=EVA+MEvFMcasD}LQoxhdtSpe<Gu!TjW~ z4(ar|^;|#d#_Lu;nJe3t3A2xJ!`O9Z$fsSKuAXPyhO}uTZ|Wmqjh)1kZs^+&5zl{V zPobD}Qt$NZgMr(Cb7Vsy<frP$ywxqz@Z%4)WFe6?W3}rAWt<IPi~tmXG~(x(Xi7S? z43BV1Kz>{2=YQ!xZIXI9r&4E2R_$mfRcp46Iy>K*oZLP9?(hEI@by3W6I|WhthH%y z2>K%CH1ilG<V{=Tc<$W!;j3T$&9pVwtP@})HV4;ey05Y?%G@Ec*_rc4Ux(Kc<3~r> z5vtfqb~^$;>XM>`r1kWdbi5FsjknT-m&t3Z<s$rYB+%G<nIvBhW1mv_R07{y0%KqM z?XPY9XTS2Fr*pOwv(xr9{#e$~qqx|abiwUn9y(h03KV%0KY(<43=4q0fX6J51v2;J zLv{tgXoAJ-K|m}4*-Zc|2LWA5*a^mOD|7_goSf>C)K}VdQDCRbh{ZiXD2s0w<m*^1 zPO$nC{K^1G=jBA&0bam1;Q)eu;oav?06<-o`U>b{04XPo`hI455D-&qPrn{-SLoo{ zt(3LI_2<W%9`f~d2Q6v4=yAY`H7D@};QC-Es31sfzJi-R6F_q}as;L^7<AB90MO3b zcpd_D0uZs1h93t>Eohek1bxN)Al5(f=|W$iuLdQ6bwFYV69-%W>Hl+?a_9AC%I>S# zK9?`^>K|qlaMUe{;R3tzDiEn0^!w~!ESRd?W6er^SVvm_3AiW+>%YqAhZq5*(UUo> zvn-dcJ3Q1Q;|MzFo<UIExbmdzTzF<Mgq|{1w#xZX^Kq@q5JBFOa{+<snAX4DZ?yoi zK;=R5bm8fO9To!e$kQyAlk%?2v;vlY=~{LzngyB#djwsb2su#_O!m3YbQ5BpPvKP= zTBjb?O?W3WCt_|4_*`DoK8Pb&uDcBn!DjQ&a@@0dC`aQfquSW0iK)-Kb*2_y)|>qA z!l$RSolv<EWZikF|JL0mK#4$ubWPu7YaXU|kzhPGWXL$W**7aHeBUrNa|peE7~tJ7 zX;?RwP4L}cwG}o4<O4bRTrgSQY}*1;>Wco!Gx;N)1HS!BbOEbu^H&cI&!!PP>o3{5 z^j?78XXer6YTqGU-I?qG<W;|23@$9;{)7HumAcd7S<qSE!7f-VyLGA#a5<8>y6rRh z)$#!WWme?mKJqs{6F2+A@BuINFVV7){iXl@*N4CPU;ZM`DTme`Sp6<OUI1`@GTgYi z0pNTROXIT*a3&r3Zvy%X*xJ)_!Icwv`T@XZq#1w8v-clk^>{Ym;fXWoETE5WE#x;G z(I>f}Q_q!80nYgU#d1{Z=)1R9hSxsx#&BF<Zrlwy{DYI@Iv*(%a1H<=pu~g}O~z;X z0v5)&_gSD_O&%D|TsTEts=qu>o(MwV2|uuipM$Xgz<F(ja$cDy%G7Z5#H+Z}V6r>~ zD2tz1U21IMN868!S@1DF{5N2Uy}r6MJf@94c<^MnKfgL$c=Zf@kM3yHCrXFDQ>EmK ze2_@mB$)~VE@8#F1kkw;ntS16FYR^A1ugDX+zjxyMcZ~#9>4#LJL;$XfO@AdyET5X zZuXw?t54g&v)AV385XGX00=B7)d@vm-?N3E^v&J)$eTWZtA;bf=~rJHCXV680&C1I zz{B|mj{tKY3`h8YpVq2wqETh=sT`|}e#mAQI;vHlx><lTvO%{e=zC9}JHyy$TUQRm zv#O}Ybw9?1p1AQLJptfbx3q8uaK-{(|He~%9Ipe;rirDi`mJ><peO~z`kek6!1=~a zKvlqPU26Cd)d|Lpy!~R^p#1h5E{Y9vvF5m~CHAFD?+0-H0$)bo>!uo3y2{IVeeMwc zsDmuF0l2kro(DYk!-3~sdv!Po;OvJ66>QbBGDgp>R|RF6dDa1EH``_aoM%ojUTRUz z<1E<WOVGJ5meQ{x8$VQd?Sl`{xwS0J-24-8wy##Mmd|n1jOtuhj>Gc{SXJK!j6Zu8 zms+P{!5wR4<zZU#lYz(xI`$*$Y??n~6UL2d>76}?8;@+Tn^#n+%0-UddRATESi>TT zO+`PBIQw803*|$DfHQD0579;H);yK3dc20-tkM<*W^In@?Ck7pHmpwq-tH&Q0RI6) z(u0v6eaqN@Y~gi`S0q+=3q))4%a`8e1D!L&Yp-9R{*ezK@Ejj=Ze)GfU(lXapQekp z569&zmoCRg_G@om4B)(Pe@lmNXtcV@3eWackuNmV2`#j~$zoc=f{Pa~vWdWlkKtLp ztTs0e*!*lb`uG`RbiLUX9Z`t<-#)5cRKJ)85;@oNs!^ZixoKPCTt-=}2cG+=D-WF3 zp=7r++s=dM{6|akG<w=nBu>k(a&PGk3*Al|K^W5FCRTq$SfVBeE|XSH<cE7Zg7l4? zk)@j)0eMV>UgT&5mGx-sv;X3r$l=@Kh9@p;Z=`NzYR`#l{3^FpiBX*p*YK}GNGbgA zjCN~l8UaoAGq&ZlXQSE%s-19`ym>@;mte`mXK9tu8SlKeK<3fXB{WG5$|0ZOsG?PM z@}ye}w`jzdXMcu3IhW+vWtxamm0Gf7ol|mP7=f<yKg&Y<Lv9|?p-z{6!S<E#oq3Rv zeW@}S9b9|64La5nW9%%~D1N&rIqsm-BInfpNOz=4NymfexHpxc*X>Ac46a8>oZIL| zi_gQ-6yh144C)*ZkZ2>Fi|#nqI)4{@wl9&6vNWDDuQG%>fw{}s5Ov9H@|3ux|2(L= zYsL4m8yynOKkvCpG)_MEF29zho*BCz?E$B*;-S&wqZ_3+#J7G^Z_a5;4>G<*m#FvD zJqep0RNNXrQ`uGw{iwr-bN-~2p894WN9xXV=Nv{Y{fOT#ljNx!O;t~Ook~Lr{<g0T zBW6#}xu-SEe%^pQNBGs2YwqkE%5f&~Tb#7*ToVr6Z2Z~Y`FZ{Sv-ckGo)*>p|J?2E zZtuOYEJcc<0vgn)hy?^}(L@o!_%m2yi@iq08e@&I##o|QA{LZrEGVKx5KubXd%4^D z-Yx(4`!mmT_abeH_%eTAJiFifw3#z!&YWqVInS9$m={o@yc@c<@s&uU11;ait8qMc zhy(DmkBhO1G9o*MsDQKd9Q&CzG@x&-izFFHCNAYu0cYwgk<%wOGFCM5sDvy7+f}cf zqdwvEXK-~N9x4^YYdQ3y8#y%hCQd%&MHf;V-0K2hIbW(WUI_vIT92F`*_LF^hRcw- zhtH*+Y4GRRr0PREzmcl#Q5NOBxrZZF5?*Sl+(Te8b%#9NSrmy`riVr}<#1<Y?(i%! zjo|L^>VNy-zNL11E)FsKw~urecYjPi?;^?jAO9f|P*?wu`2WY^MwkB=3XO&Hmkzw( z`R67(uI||=?Ba6_LAL%h_6lhj=z|u^cK(7!g2d?@xYr76FrU5*6u{tqFcZ2VxWBMn zcSl&8E<f$tCtyt6OulKQw2%?Zve6WjwG(k;HF*foDOgDZDhTCq0Kj1=be-^O{U`_} z&?W#N4SoD-<uq;TbS6<7^BKMtqFRz_32Fl^m^qM6%s5V-v^KR<b+W$=AXk0_e|>MG zo(`C_oq#$KvvoCHt(J7l5Rep*Lst@lXIho|$+jJ?9hdY3tyMLFTS4XIkGx9LG_+Kf zPpy+2oCu&B-;PEw$vmbL0tgVO)_-O?SZGS$1pvb-PdgRQKI`Bo*rF`!0ayVr=w#7w zrmIZk8Fm8Hw`HOKS||7V2No1IoQFIMa(h^2>Ofnj^3=7ii#G?@cx*&KUBO^GdBd33 zJm(y%2SO@KEqj%nM`S`CTgzfCa9g(%E?PL*c914LEsdS@YEkMTC?L<4y?~R0Bg;r@ zY~^P;TizMWpqtw%b0@j_XSQ5cu3VXS!vU@ZmrT3On{~iV1nt!0ngX3PKNW1Pn;z;z zx%#xO0B{SEW&<YlNkGB+X*|nW;8tF|w_KE)d?*X^Y<xj!!&nL9FBy=_=R35FM^0Le z3t($8Zk`7XbQ40X)B$wW33brCn1Ac6as3IncyAcxAbs`3^4Chz$)Sq{mb;*?gF5xm zfs5^eWiQWy!@g4v(lbw5U%L>cuKG?I($x}LAlfn%EH__mxl3Cb0z#I3HabLJ(zFcP z@|3=`TvP$^!}Ul1(A%sZYd6m$UvB8O0~ZZ@02URU={VRGu#q?Gu64AvFh}qVHW{QL z19^0@#&*s!*aaw;I*B~2GYZPT?QzCCUtCT)?@VrW55gc2_Y~W4Gtsqv8=H9XNjMw0 z1#o5nX<O(&-C779^mP(LI&evP6>z4;Qis;FaI*z07@xpwKsRA3`Ux1@hadJ0gq8yb zpmGBwrR6d}t`^P#oL6nfJ;rW)0MEb|ET6ddabr*0ITo}4iQUjoAI$r(KGtfb9N59e zeOt0o=f-umKlq-X#HN9O#(lJ+CLLXC_$l}P0M49gi)jI%v7>ac$zgXliw#3@G1N)> zD&UO2YFZ^G`?OieP{65R^$c7_+&yI%n^<n%)Qvy<0|2Yz%E-|}sHeJlkspA<ZqM?f z9k}J^ViW-PM*K{#Ur~kt>JH_-4o<QeEfWvhS1tSn8Pyl{&&3GqtNM1(!dakMoh2Rg zq6L@(NZU`LKd2%+C*zb<wIEgRd?e6t0E?LpOt}YR-8>v$yQ3#fD+jR1#z{PNY5<%6 zZRd-Kjj6N40Dn6>bs^*=h>0h95U>(jv3ghc;Kg>`y69p~e{^&l7RS}Xxh-qUn}e|S z(SpCm6L4O>d?j^;FD_`C1)PTja7KjwL!NyoH{0Qk#xHj)5h)jeT*2xwlO~ptTBx!( ztc9~Y_F)5F`HaSsp6V}{Y(2I9-F(xH0hy0G;X$RpU?BnAq?1_DPV2q;osDdH<_2c# z@SVRAi&__=CeNIKWh*W<6l(n=!}Z#G|8q8vf~iXuElK;XKjqQ*3f8p~>`<d36(xhp zP)71;+7zIAuz113w3Sn)O-uV?n-g~-grQpZ9JyAoq`8}Te&Mua*>WuRr{SA;5^W86 z)4hbUQ7)uoT9K=Hhn|-8J6KqC!A`EG<Eq3jPAvPhBTZ^1V>;$fU(9ZZxs`I)y4?lR zv17)Ti7ZxW;jI5=(FRXO(;t01dABXtjc(hwtYxFZow($fHWiRNi^aCH%?}yw1=#O~ zNWMa0p=Ce!WE1dr2VYgJV3A@-Tw_oLXm9wkXAo{g^!JR_x`2^+w%=&2`K0ZJjBD4f zF0<y$#KqVs^be3AZY!uG@Tw+gU2or;0~+@I+X0+!zTpORtzVgm9(0ai@qb7)b}*iG zZuG_-WelM6a29dYNoD1cwmMgeP$`p6OW$h?ra1ydG;*%boA9*&63R>c9y|W5x?aOr zcW!q`C(n4E|Mh+1v;mv6qPGNU-&NjwQ&jOJ5)R3Sd1#2F;qjXOIFIU!7I;fOj6nPf z?AXt8pLoPTkp;p$_6ge3Zn@d5ZNAqPtV!y~l6aD8iYM-UxK{#k$6<bK_j=1KZ>i6w z5m^(Na8-WhQGJ1==~*uRLLX@u$MLPqh5ve$+vZu`B!5O~-beYl=D$h$)JJg9h9E8K z5zl*Mo`9CY!9%jX&!UF$!@p<f^#YuwlQay=bvONyakcE<$KtJ2T1!?kS_AV;LUkdk zQjo4`BpuGSpI%GTa~)H7ZJ80+BfJ<Qmr2*_8mGof$ToZp0Ej?$ziI{yMmXQ{w^688 zovIEtX@pvW8O0LIxjjWjJPAquq#T=Yt;7SiH+gUMTOwYoGxig<8~gnFh(^VYO7pJe zvjLptH}QEccddT*&<c0(XIjk>b?}-9l8f$zuG;70gS2#s;-MUp%SHsce`)g)eK1gD z))3{k?OR+Nq!+FAfY-KZS#U_X)xI^+xpyxSUJ{0WLVfqTxzE{WjJpGV@;qVSxQ40B z@i<2<L%0mDwHhU7$*XcRUX^)`(fe<58@e!&aP3>8N9H`}eQp;8e4mAIWNz78mcGl` zmr?nKFYX;1DP2#MUY$#DlO)4G*PdNm_qk=3GHDbv?MzC9=frY>R2Ne9R{`THmN4I> zR~NNRTRweHP7yEiCBEh4{3t%4BkL;XFvY!XYV^%>Q}#od$35xE_c7osU!>R8$)tZ* ze+ZXNoA2s<ujd&Dv=zM9^E<l~h;G#C&R+LC>*-$)C2&uyyT4Gh^4hy@-(3u4btp%b z>7j(YKg|6S_|r<@5LNn5%jCUGoo4f19~~Ec`O631{_?+%wTYXo2}Ek4q!r;PEKThg z`!R4Bz@$k4%n5u2tEzupulqB}*uM)aRwv6$4u&zw8U(Fs5v32&I<c}Nplb+t>$MGr zaq`(SpE?V43TO)y3h-$GW7FegZWsXLU;t-3JtyWCpfm(sr6FjADPb&)1&{^gw9>V) z6CjJ53VK8*N&=g9k`DBwVTV-*NP>P9z!nG;eAZQlt}X;HToDz_69@=s2SDfqRDjyS zV?aW}3Hr*P0GH_)S3p^p1Om>nR<gt8orR`M1!n~urCZ}SK5`)>U3qNj282c?@+j?q za-5AX!0DuV2YFT|%FYS6AblMeP@d#j3vWN;m9}Y*2DEfF*a46-F+Zj!knbnq($b>V z1%MXpwfxMB6MHl4y%xmsWB6DfH=v<uJ7{r8&>r&Sq*I+UO~FxtPUA~Uu);&IKfp6I zVqp!5_$($}fdRo!%h$4UP-9%dUjgZWnuJ$QJ{NR0t=1KXvKRu$s%5&91=DU<hb;>y z77miM@E54GtmH=^+q|et%2;be$R{tRrCbvhdMO`h=o&-NTFYtqFq}Y{5e43*<Iix) zt6DZ!9gkiDKxnz&g2BqhyqHISsiUN8-p#ABZLOgN)U03XjP1m5bbCK}(OOZ9Zy#zk z-Um=yek@aIs%w^|^6`+5mQM$4(zisVTfvt)(6+2C7vo#cvLHm>RCvosuv%JP>mS-W zDqZ;&@L_gVKkr6=4C6wR>D4-88-i7(bq*PBqkitAqU(EFf6v>IU$t;m->8SlhwVpo zo1&gcCv5>T5a4#xuKHQNE<Y-mFR)k_fJmSBB%gR@Sl*xfju)4Qp7Ue?3&CIkXZ=xc zMklwG1q*fuaGo}EY8k}m8~w?ft_3>Wtqp5ot<f^LgYN@aH)ER1<8I=10a&w{)}C<y z&ST2NsaSKeAz>dZqch<ZJktL&yu@cH3w`_c;v2cUe*Lhai_HVqb_3>3WPt~Z_zqp{ zu+ReNycfWkoN!NF>_&f)LEk=Z9J(#-+WIw=XP+Tu{A2)UK;ymuc!-!XQDdBzGVqVJ zkNnfd;x~Hz8W;a)w+4(TLr0=7!)hL>IrJM^$1_nu-n#S9GFqM6gYVW2>v!W)gT=b3 z<MER_l=!xVPErXMlPlU2CRFv__L_wm7RUCoLF^EM41oogzNnr2wN0nbK#%uQmiAMY zm)7pqp?&C60A>L8)M0^x#=5y$ITIgUZ9(U3mgYp2GSj__zH*(s*fwez8en<wFg6OD zT!xLE5a8Ke&ed}Pw{2SioUu?DVtY@&H4JwFS@;TADG*B*DaQc1RvsSMR{7P0i%Bk| zj2=6Ny2zvnn(CYN0_p^{EbLE}5A7OxUA<}zI;#(777Dc%B~4BH2tq{8E(XiHC*&2d zfO6RckE_?L#YM%0G6HuXgN6b8Q}3kR2Y^-GmxlSauE7b547IOXvUpMWJmS~~lz#NP z1WFqgRUvN`oU8z6%8~TCR;|qjzwV+w88CJXE@zx*dW2W=#;<2`(p-13spS%UF}qkj zg1%_vxY4w!O*>RG2?Zyr>Zm%5oZvyf`-|o;NZ&Da*37tVur03bx<ak8H2qA-c$Bt= zHhDdIwtU&jG6i4S69MG)Q5_)OGHhfd5EogIcgu1Qpub}i{cy|H3;}0kTHTb`Ka!4V zQ3_nvvV=wlWu+S<focKg3CLxNAUE1=>l*nH!QA;nK>0b>bc56_j4jsSQe!vm-eGfe zi_!Y(x8Jf}0rVnEE%|Mey%u2Gx^*YK;{IjLN@P2<Oq#3@NOeSGgQ0aXOsP^v@~#g0 zo@$kPy&6|8wpUZ8P9Z*DVz5Dx0m%{c&7j<~;K*NjRkpSTJ87?1;EF?^?Gv!9A2_^P zo|{kg$a*&&kZ&fDhGXG;2f&#i(yD;7@=0Q(!jbfOZ}L5|qMYQ(Oc*3@bD2N#=bQWu z-GlGiD<xm4`oy&B8|BynLwOF*^_^0v=^3()eGI|V@KFf_XlaQV(CaW?Q>=WMlUh&Y zvL@h@3Iqjspgl{(rmltz?WthDV;9pmE%RPeuEEouD0iQST{tAN&)dGXVTdphFCnWe zm8Vt6@X`%!(lhO}`DxG9)kd~y%hVA$;Ag;km2-Pv&y@#5s1lV%PF_kd@hb%%)JOHI zx$&jEwSi3Eh|1six%O<ZgQXR#=)AYisq4yux?@%v3+DjNzJz{~;Zh1|)6rj#nhejR z#V`FwZtA^ykRLB?vpi}U<kBcr6!q379U}ZH;oH9?bQNb}L5IL$tl=*&<*+`kLNq{g zpR4ANQJc6mf7}o;ZBG-v!*<(B?Y%nRyp2BbPF>3wkTH$tcELkA);My)&kU<Gk+cHk z=n;Z++weTDZ=3wrJNq-!uQZHX^{@?E^}Cj%&mw+;M_1cGkxIRxdFweME!a!j(S%8P zrC+o&wfr0x$cxwXJJIoaZ9A5t;%q-r!}H8BGxyH3qeqErLj1_3L3?rwZObB($eEWW zm%}oz?@iyM#`UTOGMyHf_MN{P$9NKyay?RJHL<4rYB^e$12)sf2<#d}`d(X}o;^~w z(#y}WoOQ3gr-Zq79F}yYKs3|zsAmZijy!h+aBjZJ33%Mpj~XfA^0ijduJKY{ym2hn zmwAI<cJ*VP<=jf~SpSr9m6ZJYr5JG={(UjDa|D3%UqR)*JzCk{GgbJjS-sn!=0Vnb z3h!=1E0b13?mpn38gQ<1YD?(uc~zMYG2}fEy8re468PgvK)wERJJSB#%S?5A^J`x_ z@SpE{KXup5`2>owBGxjLd#yIzw5|_e$RsST1Y5N>@(}0>*vtgZ27c!bz$-xN{#XHZ zGT|MHTMb%tz$$#b3bFwf)AhuXYar=7_MCIe;U}M5#!a8WM0s#oHGh6tdee<%@o#@y zuKnQ;m?S$;uGUm`*3;(AE6;e_ThqWUz5e?0tq;5}9f_crAd>)JKY(sOncc!?qIO_@ zf<Js{XZRIZ6g1O<&5lMeRUpv;qIt<mDA!K<>xOWBm<&w-v>6^NWuFJ6a<;{xu*b2f zmjlJts@Z1(bsL#DYC$Pr@5XQPwgq<=8D!8As(j~u;Dc<ig<A_I10Om6d3k4E1g`}m zr7L(WxG5m$V8*g=GXN*vf@lI|mWg?=JJH>PptkR|tZv<92z;BSyVnYWI>^x~N(<%y zf8^g!zXj18T<DI$iK*%8b9oHlhrouDOY>MK?fqiWD%dX_-Bb8n;L%>--1mI|AOc+i zto*`jUmbd;Z9cS46L1lb)^b;%(~i^kmWz3JfFl^|=TwIA5R_5p%x?yn=9-KNTnkvr zzaXnFBLcFMwga3tPwJm~kU>}zSKU(P9-+;>z!mHy@8)GIWtYvqcxV2MubkymISF8x zX|L56&l!Y4M7|to>E1;>)v8*Vp8Skwmf0tq5P5#@Up`XSqW`9ET;*wr8c$%_{8}b^ z$cwtBY~(>}VD;I<xB~%2^joUjyti!CSr>2yP$y42@A+lUgH9;pX3WHja$wnjW!usl zZzw<b>}SflC5r;ucK|q>#|lsb&>~OEICTf!JjP@7_lT!Ht;|0DxH9d?qw;JC7HhX% zeO0;gl1s`4ti|O~xeLU*h$Lw3Gs{Rl@i%(nq%vX7?BqG1hPfuMw?bz#pQSsTFz^2J zzq;2BRtFBi=O;1{P}~W?K7zVB?}5h$ELMJ*EW_E2S6^MaNn4#zmhmM{92Z=ap@#so zn>q^i?Gm)4jz>qZ^s@}QxfhT$9K+@Cq6N!Y?|ex)@tiXPcDtz_OGT9T7V61X{G0B? z2QwDV0M58%!#xmsFXGn#&VoMXH9tUB0oDC{1+rm-?j|<F%UA}#qwx<c;Ec{ODDK|l zVw~3Rgymi^X&=B$cQ-(6_ZEIG3Uvb{?!z6&DBK$jD1$pQJhOKI06+jqL_t*C>~Ros zL|3rD?t>+<U~<Pk06X&DuOEvWxB}U;Ye!kT%Jy(@nK;AE&S>M~lh;sA60rW}GkXD7 zCs+se?Fdl4Zq-(Ja!~~L5&*|ThP#<3?m?I|>Mp^08h?&hXZ!iLfTjNY*RI}<|KM%- zxSm8CIUF|<f>KUStKWFbT%cs%-kl^*y=TYQ-S~Cg*|oC_WN~v4c^||CNFL>HAFd|+ ze7EYqfHR9}mK(aicUJ>ATYu<NDsV6O1$gf>&J}R3bxU_Fv5caf)bFetSlU1ILznIA z`e4o6A9orfC(j7j+yVH^QfTQ1@A}Q#%%*|s0dt4a_qZ@-`z2r<#X;(Z(Y=T1qXo#* zHV6HpTz8<$wvPg<E`Sh`5QeFfQ}%g_4m!tmB5XVArh3vEGz1qxq@_y^t$j^0*1iD$ zlz5)S8k92WfQK!79kRY_Lm7n|hE6Pp2l!=DIBF(*ww36)ZK`yvfG+&(qCR!4UzY{S z8FOdj>PNk<i*<t8x`6O28{5ZBI^kby`t_^VrEj*~pF|rnnvHjRCVOVGR&dcOZ{*m_ z#tp}^B}>ys>3*S;4esnSY|Bj}^;o%N;z&H?sYSKpn1u@#KyF`|arhj3TT^b7p_a;4 zeftB`_qqbkKGec_S3YN5y=pZU&Qs&ZIhM`DGhBdY>#jU<u3&<TZhLVBv^zf0eOE1< zwQjf0SY8oRWC^9jSI_)yX6z*3+y&q~iLZ60O_>tw=0LXQhtO(^QjxYl|Ee#JH`cCW z(@)y2Bab*do0}Rs+65q5Ezhaj>L>X%rohO$b@+=1s9v*XMHxdKoHc7QWZ?(>-^+%d z))o7K)M4}m6{CHl{o&Wm&i896Pe1+DotTTL*<{poEr+HK>C>EAnj*~?Le$AU@Vt4$ z2FkAwW0lU*XXtRg$U<i+cNZ{SXgPZDfO7OuzKHuh3ug-p($On<RUQEia)m&YmG6~M z^ojE2Y+dnr&q07ll0U+*9tnf~-tmaUc-+3@zPZ$wb_JY#z;oiaeN_6bhL~f{8il95 z_%P2>Z;uwd@na8JF=)HsXP7qKTD}5##5YaKCkMpaeoa6o{RCy0^a-oPdQ#(}%E(lj z#PXIfO+KV=TJ0h4%3P~(nRAiA*vdGx)h|d{=js9?aedIk7kY2wmAI9cR$i4c-tpf* zKKHV%J3f_@y!NJfZ~76c>9mIrxs^tMTA!yaCH>T0qsVbRjM|o0Ha`qe^1<r>&b;@F z7!;K!wjb2Yh8byu(<YC$Ngi!EBsud-`t7si-xQnYZJazvZ2u^OdLs?RRwH<>dGoC_ z>f(zrxT)ND;#bR~O0woKBoF?P#O)4gRlOik7~l-q)&kzBw(~vZhK@K+YX7OY?S_?m z1)MV$tQPjs*N~ML8TY3ktskCE(mb^JGBuysm*g@pQYR1ynn-l>Sovw&f+l2rZhU@H z4du{ji5aq{=T#ly8s4(0&(ps9lEX3-$aMAA_q9wbb+2gz4VC9wJEwdpy!4-@V|>~@ z<7$9#=YVtNtr0`yn#}V!wXBErT256iO&&}loVJ0ylOO(uUuAhvUJ*?F6IoTzn6jq+ z*0K^Lc3eam+g3H@EI%!swD<C6{b<UezN>9-TQ<^moKkhg@UWKl#p|Xr!Ak&V`T#d* z?xQhR0OMMx(mu++x&n`tNTiZ{npflG>o8<3;5;Ck2AY55-qd{}W=`ihJXE1E=GMab znUUaq`KQYNP$@Rd+(YnMviA_Ed97+53e`Ur;H+Mx{W=78mDM2~>hmE5yg$(W68O_f z;E;9tPs`@LN}VcwuaAyzfBowRF8kQO1PmGm5N7APn+f4i{6P){lnKC$1>Z<E6w)<C ztXu)j1dif^iU|VW>H_+>0UbaYTnuD_rA4yCxm^K&@MnroLcz4bOis>y&wI;QCY*P5 zEdK3v<-6~FPuYg`s@9xNa>ve^U0(jB|45YiSN*zt5fD>gY!KG5o&`tu1GoulZNm~* z>*x`<6c`QYYiDm`r+;FB9t*#<ZWKt?dP|_t!vTPut&<}smI4hGfOeuOFo~TXV4ed+ zEsE`w1(XH(EPxCwpf4~ikUf6<xX@5;0(Zt2FnZTzKgXgBpR~y2O^-Syv_g|Of_%zK z0M;~>wZ9E)?j;>vD2%|jaKK4ifp`c~n<sa(ojrSY($Y<Yg9Tkp$g8q(QYv`7m2wfV z7EI27Fq1t8Q@TCSnitRpK0En5TUQtY`SNdE-zgh6ThtYa&-4K;Ag7OM2Oe+y?)NbS z98`8Pk$&IP&Svteg=m$XGSdp(GPC^R*O`1~a>P3aHgU@UT@L{p-?c6>1RAu0l~=8; zm79QUz+K8taM3VY1N%IK3k!#W4{!tTjx(~*K)%$UHsA8@phQ5lwFnlNiC&`%4wftn zt!2%Jmb=o@I$S+fP7cmm>u47q1e3G^RQ{Ha@lSj4OUv=6o|gQ5_Ej%0w_f?Hl(jNZ zzHu#qZt6xteKl_fa52zMOj__(-hCH$5Ddcl!MmVJ7AxS__eVYAk>#nceoYxhUAVKu zuL-{K{`Zt?F8w}}s=5iJJ-L?WoKmjV0rNZUh$G6&KK=>7MZlsvId-6*|N63*l?Bw{ zcJQez)m8H)|H@8zo&AbeloQW*@*Svr?8PrGw_S5}zz*w&=?b1JhYT^e*t4fjFk+R8 zzCQ0QZ!V8|+Eed9>mScOx6Hrp+SE%2yw+1eG%fYjVTY=Idh9@0of5!t@T-+6Tbw5E z)dCtY2~buhoCp~Hj0-O)C!hCZ?RI%qT}E{8VN*N+=Y==#0vH?1hHO*H5b|o9*dMTJ zAE2sVbifKf!5q@2%=hU36}J&v*ywcYM(WhgF$|jVnLU!P5&HPGhl6Y<yXr9mc~qEe zFllk}!Xgh~x9%#s)@{K}!e*=$=irx>4fzJvcBlj0sa1fue8NvnNcnWow(rAI*>-x_ zLVVqm=Sg#?qkptHHti1Vof(j9pFV(fw2zj9An;z?c&x>`mZ;DkS;kEsQ#wcK8=f|m z2!dq-64u?l<Xh0%4gR{RGpm<vEDLX4UuGUQFBa7UF<F)uK@#0kcqktMWUZnHkpEp9 zww7(HHk3X)0JO0t9RO%6lv=-=5ggM>*><b3c1GW{a_tr%i~a$238ImmSbI_k0i3Cq z>X9Ic^_%L;nM`tRn<f8#mPvuQ+ExZpkA{t#SjJDERfgcFnbjLg20oM%|JUOWd-cjS z__D_$m&HH7CeT8*_k=H>xg%5lQ?}?O;OI`RV>fJ0TRmQ@T3lcV9Lraom<xdGqJ~?T zv@QtlYNc#G+#pw<@dD1GEVaH+h64Y|7mEfcjk;qSt1snsU0r1?eU$qI45W=xryxr< zD16G={;-```@#iP+iv~!YqdRP#?&mPnHV<w7F*<&j43;qrRPN80P!2_1JO0gWCU^> z%9sL$Qe=b!7$R}UANJMiT_5Gn{WiYBaDzkl1{lVKaL{l-b=ui{Wdg6Z*S6(}FAeT> z`?8z*x?<T9XzeSr=CC+`1-O<^E*vNXYgCQHt>A?S5<0gBmpq$UuwAoeb(swC>&Ah$ zKlaPIMNu9QO%}s1>3Qs8VPgx{?fNLTZRr7=iDPJknO^&8y|H+Te(AGO-_{$mXs?Cy zWc@~yj`iEVDU)_Wt1nIpm8#eFaqe4CU1ROX4>OkBx;P;p#3U5|EN}xSzWOY9#zF=0 z)^@GMZ~RK~IJV54JFAAXK;X$m5yu7)h`ek!ckZZPMD5@!g*B^Ip|2atOwv?;lnXVA z$W=Efe$uiIRh?Ch^Q9C90jpLnOCL33#xz{B@O1#RJ4nlFXSqz>H>6DO7|J+O3$-@? z^1;u;@=6`eP2^)9)rIN;g6CvZxtS>?Veoo*(f(9T81o6V)x8{?8)^4`z_od-bt|+b z+RzQiqHuZdv$l<e30M(Ot4H+5OCQK%{?&H@RGN2{mo_b>QlqF%jFKSRfI_Cp&+z;W zA-T*#A9cv_Y#I&9JZVXY!)yN^Jn|&B6~rUFjg4RAG>4K*8tN2jMK!#NoFPYg%EkKE zS|FP9=pkhjT_n88raTDS%Dk49RDGEc2}ift1ST6?H%TS!HcrcVbdacm%*iWJd+3MR zrvCbzyyURlrJJ%l7~XgEN@-h@C!2@#!PG3;8^v-k{cv5Gr|x@^e>{%Fl7=^JI8wKs z`AFS|p4Z{OVL0U(o@%L9u&l<f`Bg?9JZmqx_Oi)JlP5yALTiG1>JelUH>D)0_P#BH z<~}mwS^k*-*WuAJZ~v)dJh$Cf7vfTbdR_19bD0gO+@=#+N?NTpUd?0jW#00$y;fi* zOS+DMd;<fm&gG?@cXI?hBdmw~9Xyb|Y49$K5&1(|^C;^!HEU^;j1xVHzMHOT+9y^$ z%9lSWQ+0^Bqv2B4?b+wF<1AEr&M)=AYx}CIE8OIroK`SBS7F%@@@iJhMa_90@~l4h zE&|DgEGQix9i-d5s<MbU&=t@5wQ^L+9RpEoLz`>I;Es=wt^KrZdK0OJv5nwSTMl{K z=tq4HE$*ck8q!s9d}ds!H9F+Ab=)yv+-kVMPydj5qwE{~l9t8^CalKyED|Ye#wCKz z)|dW{&G=RMLQ8oo8hNm9lR<wxlcry#-S>dAWokK?);%AvaY%<WqZ@}1I%;_c;qC{V z4?#%x2f1GY_fi5)b9^sj{of9LsO?nmTm*3b@jv}@z{kM=Om;4I1YQqflC_1&(}<C} zfe?t|lWbB65Jdy+Ai|%M;C)z8Ij|Kx(U0s9CcSPz<YrG!nuZJ;S^5K>o%`Vrl~GKl zdLMQ=PB?lWJFwdM_WRylmRxgftgc7ToLQdp!4D<K0xTfE@Y;XK#9XUj0XIS4O#t2* z<N#E<`CuoV#}Gg_Hx1JFtd@`tjqG#;U~RDV0bD^@eD?xa2nL!*0Wx=bjio4Y1^%2w zYK0^SJc7xxV70C?>SUS5zX4;EkD!Ovl;Z(qwQ|!f#|A#rZC8%p@#D*S0Oxm}b}Aiw z^<^zksr9TAdp8jhI5obVq88-lQ@~F55%MF5*AC)+XL(G-8eQ-?05^G2F$6N@$vg`n z@8T15H?ngw?O?#NHD7U&0ZqYOEztzx1%D-?thEdkh!)(@y@fIpQ1#RCSc)PO`Fh8X zE(7?efb)fCot`vITlvaob+=I`np&QkZa~zArhvbBNgVXZI0D<=TPB_jFBl{^>od#D z$+<F7_U2dcRdB*|TelSg`GWpF(`|~hwo;CQC;|w>0f~HW`nsG@KQm!P29}@vS|+|% zZjM$4q3_ZZY)~JxHdoKo1@%cQSwU9$)Mdt*uX=TP&}mPIK40|KH<cSNza0K?4<V=z z|5`z-*V%LmJ}u7<R_e`<x)6|=Z~`qJy3r7r8%!Fy7g3&qN|TQ~vb^x4AFl(gge+wv zK#G9XXnc?NKK}Ec-dBG5m5Tz-S=REc+#Ub8kaEmloKntv&wKJkLL1L8%CGma2fg{s zYhGOzTyss2&I#C99+r_Z5FC5cH!lWsazo79AOHIIe~;z$^%*1z5UYy<=cc1fZ7cLA z9BT<D)7*dXM?VBmA9;I1+`aqx&o8(9=IY2onQ0lR{#&M5*r0uqo)+H%!2*-!x4H@$ zl!YTVFzhCr17QT7Hbj>Vk9p&H<$=$6eC`i0`^2LzE*&<N&0Sl|;#;t0A36&ExD)a< z!T>;%ehfI>^erxgOhllA`~8$-to!lBymJQ|f8tkl_f|HcL(hhcVsWD%?oDDD?SL5> z07QD$Ws!qxH}~rxeJA*<SFJCL7p*DNrXLNEI376z&XRVlas(dz7jWFkhHV2NEt~)C z<m-<`w_qs?;5>ESEc99TJ`9rKF;iIh%_P8)D>OQYx37C=S+{xxb;Pd`MqrIS5jP_E z4aX-nwK?#k6CNihdkK%(DLf)0+Ub?cy2^r^*OZxak0}!-PogcP?jk>w7@lZ@DeHi( zfL>aw_5-lqwQfV%z5+kafL?t7_xfT{+8^3k1`IGuTSPhOOV{>OR~mZ><8L>=J+xDM zDBo^omDPW<^-?QmL1=+pdxr`*^B8{HNiDos&jcN*m!0_69XV-A88c;C8O#Q6`<WCe z*#HYnWV_aOkw4uOurP>D>UTIkhv`Ez>2Pu-0EJAIt$?$OyxX^IV<W$f$bCS32lpG` z<fww-TAjLSqkP%E*hdSvb(1d_7S-D!v`KClI1s?mVzPWqMBvfGzR?Xbt*+*GJ$|Ow ztX|FH#H1`v2sp>32EhZkL&QFfl=8Fw?MCi`#$EUf7DS&qeR>wt0vO5{Ax*&c#rDxU z<_41c`7C|Y#?8d7{?$8KFdf2zuzuI0AB2lF6KMv#BCgiha=uNu;M=?ttMVZ%*bO9~ zE(kd$5mYlh>wy#g)DQCK;){O21ycnwrcRwo`|B4Qlp*D)fGlGBFzINWs|y)o(oXH5 z9mo26<GM1DHgY^)PuPBGH5HIMZIE(o+anSr+k&Z^HnQO=eZB2W58#ZP3_$SISz@K1 z@tKy!mhCz$jW;v45bQR+iTtWdF>4SZm2E_eY^nEL=C>7p=&M(+q5Y@-rk+oqK9#<M zuQ$j?AI4>-C51M;W$B{3<*#+~IsoU*o7UqtWPF)3XI3m1YhdD7e(EX=WPFA$*bXP3 z0L^RHtigTEmU8$JbE7{2duc<{W*{Ru4BN6!9&M`q`mAeRS6Q)qDRrZ>%)=r(@~3SS za5g>vjo#M3jNLVeGI!I!3OGlAP_1Xen<);}JUn~T$i~Zj_Rl%>!29r&H{N-{L47Ap z?=7E}jyh;-(DQ&RZ>ubOJy$r*kr-_q$TQx_Txgj_d(`^azLQ#;j_pDYgPWe@&8Y2# zkMhix2JS2$egShh*HW(hc%8B%Zvl^Z&w!~C<*!FrtC!7RTR;Etj(kLJ#-lB-;xa!_ zmZ{2EPDxi{#tl*UV!TuRKr2Q55k6V5e)BVQ<ZFI%CqD;e)cWO?oOL=%XbN5?E#nch zx#m?pOoTu^G^O2=g-*uGP5R-;@KQp?Ev<;VQbUH+7gi`uMo}EVxF&UqHlGU~@Zaa0 zb0`<v*wFN^^Nl1z8k`%s8P~VoJLarFm}jW;D0awKvW5<wO3SjBU(2aCzv{n-?8uYh za^EuO>+sOzmoPr6uer*N@r|6nzRiF6Pny2<T~oQ+X9?8uW&4j{TzIH+o;sdaUp*?Q zT<My2Eqn76At%hiKQdKy-ZTuK@|E4D+>9q5B-#_rwl&Whe%lw8U&PD<>v@eqeSu!W z^T2j8?lCyma;tS#(Zy&5+9^Bao$`%L8Mo8|>}hL^>+j&gt=HCphOXfgm*>)yC-c>` zKDp0Rd6TbRS#0^`S!BX}d!&xlj8*bYE`8rTHfM?FgPLz;?~nc=ZE-DQ=Xljh9U0p$ zH2(~jf0nt=y$^BDl)rS7o@LX#uXDD<N?Phj!ZoxK9=^0{z9Zla!A8G~Q{&clFMUn~ z*9&mwzTW^{GTGlNZ{$vSr94fKJj#iOWhnmw&ZnPw-&;77C8eFT?&(j;;+_KW-uyJx z{T@SCow~<h=zLY8L*w+G=@}vvk!{<o-CeAjd@n`5o4^gLcN60NSNBWc|Aqwq9Cei{ zeXoy>Z{t$qr|*4tz&n9X0UiehT6YSj3UrMbKeh*i@}1U>0$l<20Fi1#F7UzRi4Mfh z$@hYAPB;a>hG8-N*b81%PI%JkVR9GX>94-|pXK_?E-Nc<yA_M)sb$77$CW3&_$2{i zx8n!#D{pyIS-@`Qy2hAw%(3N}xc=~11c3CFH@-fAq4&D05O9+pJM-4s$+MkmER;D9 zU_z~13PIfo_&62#a`NOcl+SGiwgkikQ{6O9Fi~*ViHZQAos|}7T1Sq?qF4E7acl<` zkk1JjmUoCK6Ei`(QEcKQAG##aT3h)rW-V{J<Wc}B{3MdzYaj8j0ExN>$izJyRT{cD zG5-#vw5Anw7F-z0#M@7G1!m2&R?L>2meqot4xTc|fmXGU17x6FoG`|Zv^4;Y$tSFh z%miS~cR*9#bpon8$rhA1p7|LGP+(pKv$w;G{&x+dEOr0k;6zKX*J0r-;H<^#Tc7y2 z#0~gBy2?Pk((*N(KRilb*{fdy)-DLhPYX~wDiP3jP-Z!pp5<kEdI*FoXOCFL;V0B1 zz$tNc`QdxZUVz*@3L@w>W)PcwZDKLNvJ@x~%(vX-$#70sI>~dZFY+WU`S+Rf-^GMb znV5I$fdeb~6mYhTwVt(H1oZ_zpZeO@mJ^;(0q1YM>s{s6|G6^OYA!NJ$FKs})}a9V z%+_^{qU@z@9+Z=Z_W_0}GdIN(SeM5E06MSw{O8LsEaE+G{Ke(v;tzeOtXi}XT5R-& zUj5Z;UssNO<fHOlp!mXP{#Dt6+niWf!>7EO*AeLZ8^7_N(OCnp#~sJ_KmDn4+f`RZ z_VZ3Wu{{0-|1W@$?{`zL-hTF3d=B500f&~C@)Ui6#}Rz#@bI(F4)2D4&|@B3CeNAU zW%=+0e^*xCa&yXG5YT#|T+C-%zXjgSvuZq){5|HG&+5^QW3lL-G<$YvedzCAh_&=J z(K*Ab^M19UKBaz8Ms@HH=#0$Guah*dw*Y?1vwD|0L{3cKM4jNA@bc%D!=Cmy${SD) z5O?nZ7QS|DD4W)8E=%VFhz<Y%1aK4>&gOQ2U}!%77=Xip0GF1_vC<VZ9_YYapUQle z-^F4D;NgThqs!m{_{|4!K7ik4DAn}+R9!#`5IG8p{%K9LYE@TRvUnA~k>~OC0)R73 zhntqUaCLyN*025ej5hr`$pC=eg%4-+eBsUOc|HL5MQr4S{=1o(V1vUy<?JSYq!{@K zIPc%P3v1rhxIfVs_+U1I1B9Ib=#MOf^MvNPfhM`O-4hfS5Z=YchAX<t`~_>ujM>Mq zN#P{EO29%~D`<fHz1_AE#1u&m3jiKiO?TtVchAaI<-krBA82R$>=B3-lyur4uwvWo z7Z?J~0M3N5`~(d2^{vYT%W@C*0h-k<`lsj^Ahhk0a?zE5ptO0dpZHTk0+Z|rK4i@3 zGIHW%7EPz1cVkLl>SU~%1d41=0X;Y1ref9dRV-|b4B$LsG&(@L;CxbGQ{6*|<k!iP zezXCcX}1G7ucZy@Hy9vy28$rXp?GxxVp$h}`0o9FNkcv0MFpI@aZR!``Es+s5u*Td zo3B39S=-~(8QMKJ%d^Y{X|*(3vwCe=vSdk_MZMFPuKlBacm<sU_EPAAz=Av;f&}Rw zScL0Zx0dh&%IvvwapfV9>*U8TQj{V8oM8G>uF9LTFg-V^Q@-k^U+K7DV0}~G0>-9c zy!aj_o_)r~^_#M}p&RM-Wdb?CuRf?#$}yj8Lqp+4w?#EAM|45ZdE<t4)Jql-M^7ei zY?MpeX!~dzu#+}anb;?|xROmAp{vV>9n^^}yEc^xSelQet<oh@wT`9@=i0u>pPP)P zO@N#2TQ`*rYgcBxVZS5b?AJNAB?23@4xv?EQ1Vd&{*X)R?W**%eaP<^%3>1!!L=Ai zIvGzPB4W5;OZv>*u)8!mU!83!%a*N3+c;<t3l&rFD^6S6FO`Q73<PX591mEPtXK7S zpe$RylttFH)Q@ibMvn!QpA1M_11Wbl=RogS)DUp6oTNlsryDOf4AdgqvC?644`ZBT zy(c_nMrBX=n9F1u`OCjWBiOu_1<x*AfQ%;25l7BzES%vJy>O8UVU-b^_Lh+>WOd@h z+48Z7bA+g(lN%4x^d<kjC#gKkU-h7k$aD3}Ba`a(d7@V0^>2bi|6|El6Csl6)qkPU z#!v7zK3w@cw}fv9);dSNIHVAna9zWi6OS4`3n<(L2;+sSQpq8_<~WdgqCnMiWJW&K z{nQETkMa3iLCM-K26&|Z%pqg`58;L=C;8Fx(8tNU0VvA^ZZjkQ$wkeFcTJ2M&UTO| z6>ye6e)$JS1WvnULue?|%avu$g^H<`=6RKO0@&wrD7#84w^hECKz&dH^@QumU>gQu z)^?-PYs;bMoWw|>4bR!@z38;(eNisjWcbg9w(y)hgk>Y~zyfQ=6td%23O)|^<fEqV zy+Pq8JW<n|cNzaT>`4pK$xqr0X;oshkJNw4)5TcpTv+qH^ejW!A#BQ>tLPf<B5}ib zMWD(x@wiA7!!}omQwfEK+&8om#`wnTUC(?*+fiL=xOnTrgX4OCRZkDnPhveZk}~l- z?CbKX=04YEFpZPx5vJ8gMbhvfA$e&JHK-B~h5A?-K+6=2+DN3nOFlv__W`U8rM^b4 zhPMq=#<t`3=jwxDd`A01`<PIT&L+C=cy72XF7(i=blL?RyEL8{g@a7hi`?aj`Q*YH zRqqW@%fNftFcM-&I^G$w1?9azcr>Y0QuVQQRrx`{aZznQv`Tio;DUi|O&h^<tGrt< z*@f`>o^xnPR(_zF`${YE<hyw$$##LSrEWjnS3k~-KRTFWRarFYH9SZs3sX5WPBlyX z$(KlscPSkDUKcEzuOpSaLgq-?j1@gnE-5zw=b-@3&&u=r^bg6ZYlm_)*}KP}RhRBD zSOQetxaY7f;C#;^?_CJ1>!Ib}I&tr4-yiyZ3H)D|z@MW|A8I?*yKFkX^|h}axa>Xe zj-ORQSFL&lE=P|Z6Dw5x_G(om0Ox=~@Yczyoo+ruX5b@m=X-&%7KCm)9)TezWNw=E z(l7i+89il6(*F`JF|_J*XLjjmfh^#C`0>Y=Q=W59xdcn-Rf`wF3s#$0Yza93EuZpx zEWoA4MQ?b0TqnrW8Z2!D8MIt<a$*PKa|PmA;5eNMlP4{WO-mqH-;^!TnN9Q>fXz?n z1=;jz?ZnZ~Rwb5>lEIK2tDj0s)5({eq4~69-G?QYpYUkGYbWhz?S6tB5X8YD!-c{4 zC4Bw2FX;iCU-!tri2S6lWv-x{t?p1je|<Fzd^m88)iS`fzJT4-$-{}En<K`x2w+N& z#Vw$Nd9Q<n68h#T8`m+>))Ln8vaHQVJ~sxyT)&=A`T?J`@|}X)lMVRNm5yl(>bnr3 zwYPE;RP+#ZRn`@B*B!;c^5QRF6qg!1u%dq3lOE4A{P-dVdGIF~qNQ*xC#1r?G^L|F z4KL_v{^EM0xej0tzgk&qdF}8_xf@MA6Iin>1Op5^7z^#c`}ikiv#eRPuv~=e1<R!c zQVpjcT#pK7*TJrI1gl(-Z~<jFx~a9d@v=xkf-a;O&Oy<3EXL6gWHU7SDrjupq;DMS zh2TTV82x(28{de9^Jz)<-(T~Za?>w=8Ed~bP4i;9%GSe027zlq9y2Rl<zv}N(>y7^ z=s9t%Q;&S+Gt1e3|FXot>55;JFTeGz0W}O8eHVb`I3K|KcmQ9I-?0GnIqH^mM1a<x zygdH==a(nF@P!Gp89@5O|L+B5-HPSWA<JFM>~XVZl~;Y{vsq{`;I}{ek#gy0KN~ri zcMtjUr|bmtEO5d2=e_+M<)M$S0Q~#^_WZIGpU@uaiZZrN>aN9nyGUT3m2vVb9S-G< zILi6&xUih?xGLL^z4XOp@$Y`8N>$((85&4At8)T4%Gh))BkB5+uWnR9pj5fLuw&ZF z!Zb~5#`(`EV@~}GEc4VK7Mk$2yl>A&fTwL`?F!0nP-hu7n$7fv;J4aM_^{yBnlD%o zg(z?YPRFOUYBA-ApW=OcSv1<Vt1Mpv$UJOBnR?_Dd_Z%pRWj|4`Ec&FAHW&YTJAYB z$#+t>cOM(^t#X64Rb~9dIrzvOj|&1fcddG=g{<w5me{0fikz8DU>!NG3@xL(N0&L{ zrj=3XdVdDsf(|>N>2K}sEoJG>4Q1VKzUZL*1e^~50&m)|HX8u0Uyrrx>}j~w7)>4p zfdL+nQO{%~lSQ8a2xH;AYQ@^JVE#&cI3Hcc;mdnyr)?bX)ejAwQ@@mrq9x9Dd{pD# zdOx~%U>6ew`h`ANKkIgZ(B;HaPAfC#9F?;B!FRt<7B9Fd7S1lrSa&QxEu6cFQvqeb zW)g8?l^?obyKbH>PF-%KA);>g!9r#qla~JI@W@G%@jX7dj2Ms01Hk4!`CL;yh9}Cv zHe`b?HCC*`1;j|&(Q4rwml~8k>Vy8MUjojw9Zr6c&2APG1)SHfV?h*PRLkN111TfG z=xWJtJ*WH-Nc|kuY*$wt%a$z%MCYp__!|!3Y(MU#i$sXiqyt~3-98gUS&J(U!Rnc_ zXJb{%=56@R?b`s(_BU;Ns3cUpSpe)OOrDnV|M~UTmn-JqQVyFpuMA|rhAe(HV3Yc3 z{-R#Wl=gKGzKvHR6J1Uy-wBktePcftF3=O@t#;>Uf(GK*v4Eg+;cXmkZzsU^Ru)88 zVkv#y;uYmq_;1^O0RY>zv;jodb;}-nF|P#xmfY0ov&zGdm{(@uK4iw&F)T9nD{BDG z7qd8U3*(0+xbJE~Y%P?x(N}HWwxf&#<Q~N$1H$0FGVD`kvBBa1<ZC;?pPY9v{#d|R zY3mLaglW$NnI~Z#Z5wUd0;7p*x%A6Knz9F=(EasMj5Ao4E~A|sLw_q}xs7sPgwOSD z)@|a}Hc9<~2kKUz11w%4=uNmqS-Nx?Jg_KEpYPXAF0R_QQ!Pl>mc=C*S+ISq%Ru6Y z^B3F}-_L_sXt4YzPo7v?1>|mhfn;>e`r|}2pZ!D4_H7vp72CG47z=N+51Wmi`(*=s zv3!>FEdQRv#W5SL4qR!h<SUGoWjk@ljvG_v9)1{kYGg^80X)h3h>g3-$jyxDvgsm= z9;8!`dX5iaQmO}O@z`qRqokD=5dc?cm1Wh0uM0$#PU0wELnUr~PVZ~h?r<ng=~RB2 z03jj)RkreCL_w7HY#pu#@mtWt_iZAarEH&6kA`-8*GrzUy!77oRh{QrpxUnmlJ}H3 zq|>HZC#sdHb;>lfZuf{~CTH0{m|DFeR@!cLsLHhs;kn8nvgm13e9kXz0QH%L2tgh5 zr>tD?Fkah#dY8j@J=ZmS3qG}}ME8j6eGOZAk*>X%2bV2dDQn-=GHUoY3_6fDExO>n zF>5OIe2{Jg!Yi{--2iarwR;$--+em(vAA#3Nm|hL>jUdzD4Slch{ts{i)+eW7L<j_ zI~J-7lD79W2;BR^I4uAa{WZLYGIOj#JL96NWAlUI5+K2((aIq5X`Y%UZzOZD+-ueo zB64Zv*ZX<<EJ@TlBZZ#D37*^Et7p+;gcm(X8-IJi+1OQAm9cfrglZkAfU|k8b+GLd z;_@h=ny};}2e&QoNDTh9&xzS6m-0?5&a&7>ZObPyZ1?1a8;u02l;p#5Y2!3HoO1TM zer=iZrELx9Y`IZZd#Ia!<y+rDgXjLL8?<^&>60F5@!ZAenrg!x&vJND_W9T3116PU zt-CeP25;Lw`)~76E3X&1lT40!4&mGzH|3ykco{jU{M_5GI$v`xW;ul|>2PfwPdw<` z4*CAz&s5=qxb{5>pZ2QB3ABA|rIwBxe`jn1FM`dj59bcX=(WI%XBuIdIPzNQYS0nB z_@nzXfA-hTMg20bmA!4R{KcgiV{PMD57S3ORtx7d&iW$&&SAM>yt4lX|20py)8D(H z7}?y-`}S4aj<omp)mc4lH1ZxuS}*P)$o;SHm%#teB=F~`(``F^Z;B!o&R2ez4eS8; zY<OD$)rpc|lP)9%0Qd^93Ze?04dk65kP{JGe?eKTTWz!jas*cmtA(a??QDi%9rli& zU7m(t2H$q-V;Gz6B^*AQ88{inGzBxY3KiTD_|(mT*M~pogmS^BKbySW_CNnqzWn;v zhF>3S#WGd!ss$;{$4-Dk!COIWc@!*-r3@XGljA{rUTY_+4?;W25rEa1tfCoqNbTW3 zP>Vx(GoM?wY>ySO7R6eV`bn$l*+vSC+EET;6C8nDt?4?kGSv!b6BgTc+=9b?5+4g^ z00J!){`u)o33w)u8QB5)`|0i&Hu4jcb)&7M0AI>Az#;<~WhO`>Fm4{SM3!}VwPRHt zeyT5zmW^fTVLI}g-FrD3P8l24&!t^C)vu=(T`RC;bweOKcL$G|bn{*ieh@&6Af1Pk zUFm4SYx*y}=xaTI^P5jQ70?Sm-;}kMyDm^Tz)-fjtnhPlf$Sc@0Q!P}($PoscC3{J zQG6z7O@U@Y?E7I@_33Iuy|e=kc$kTo1EY>I62Rc4pZ`*L)RO+Ae|ug4eJ6nGtRTbo zZTKvwoYXzRGy#42GrnM`pXLvuTzzjI)ep;{)fZ*khYhzfFe82iYAPtHZpfSULcrQE z%IsNhesekgagPgM|MH?2mFs@?GXSQ#aN|R18qTwE<ipMP+G`g}QqF{xPk-{$(pTSK z`I*m_c@KU_()h^v=V95rD0*hNcF{n-w19pq?kxra9BYyOrYAlD+4N8Pg1T-*_V({y z(&PT(1JDYHOPVB{MG^C8*hfD78Ra=|c}vpVLfw4_ewFnRZQZHBU$ypjq@-oA`4fOX z_aEQh1316yx#yJm*ItvnDDT0PbGx_@z=pgl*X=C6cvhd3m2Hys;BVgemU7aQo)jKF z`r-@9ikoldIc)%S$Ft?<!WpL=ZGD#)^~XcG3}m3|q})1Yy|j*`u1D4f%E)J(UIw4S z#*e(~01z(y`R(5l@Ni=n3r_&fonuA<tg%t#VCo}Q%Kbo?1ofOeK^mBeV_yXd_A)Bl zgB-VR+))<X!j}U>MwRJD&%&JsdFvyX2^f(X6a!`l>H!u6vz**B@f2`oBd;ZkS7Sjs zgLL)Hi$y5u33O)zFXVFoOH?OD*7NCuMwR1+%qS!J*98IDxw~TrR-->yb$!{mXA|u= zo1x-%po@+C)~sQZw8N&C2~);Wuc>>c0{|NfSFW=Wj57=P+>3?t>g8+j;k>L&ntDVT z3xGRpgchS@k3tb}rl8=D1sfLdXuQiV(%H9pBaZk<7fWRnLL`82PG<I%)6RTOIr`WW z!}@=G?)~MK>witX#hRJ2(T#?aazWOB&7AAPN9$5U@VRwep;90#W|*;Pb3zFKydN-d z5a98+X*0@5zK$6N_!{6UIxP5r4v=5tZUn?!y>c~e%JBGa&Q~rh5XN<Y3l6kj2!}Yt zLjzbI0+7YR87uzvT>#Fs`BVAgr{6%r0x;Lfp8XPfLs<$4!~&QJpkH~cSiT~Fv+guH zY2)1-&#z9ZC6=;e@<k-&RMVy{M;`9auzcByGHvFJGETsG2$M6cTD5S_{tTIAH&YsP z<!IW{#~d~{GQN~AkG^}&Z_43E9uc3>wxex*vMsWW4&cVa0|3suY5SKg#r+C^vy<Y9 zQ>NngpT!BS+L66rPE<P7*_afd@$p9;S;o=!+|_a2vX$ks`SVk!5mcQJLxd&)D|yBs zY*@Tv`4WKYLFMI7dq$Z;e|l$!_5a7W+)%Dtu_SG%?v=J~0dU^DD{g5<5-&g~kvr+X zUvkPR)F1PB@L0?^;uBY1QMTJ(pqKV7_Mx_4hBXa=sQTqjolMVQZ1PAz*P$x@og8Z7 zZM(OXo4Z-OM4pkae<(*mXXU6L?j>xfXgb4(cg9lPwq3wk4xN&!W9pkf`)76A#g?0H zz6n5nHEqQ30L~L9jz@O3MbtqSW-LF)7}gaVs}AE5&+*pM#f#BB-FWmZGiFXt|J;rK zYfUB%0VnC02O^WUdfz8N^-9JRy7C!E-e=F5m9{AF1*!xc2tHyXn=T{&0M4dszFU!V zRvztxyyLwo_^+mEl9hissO8lX@JT&f#8WQDCJ@(6Y}y`0)}~>I)P#`e6|N^WqgK$x zN6~$0=70|x>`*q1p2t3sN9#&`Y~O4^ftB9u<RPK!vl>TU_uKZ%bMhdE{!G9$1)KMk z1xr_zYi?XpZn$kl>0*C?9k|7jPA8jej~YItOc_6-96xVbIdaY<#)N`q$QK>6tOM#m zD=Z)Ub1)A{k8q?YKk{Me#In_E@?)QDxp>qzDUz&ZNR&o0gfPC8+WxI3(*onh&q9O2 zyvg782KoxIJ(|n*QOe(p<-fd;n)hDS6MW`2e1r{dZ|71YVeO<`cyi&t)@vh1PGqaP zENTemM9v9s`hFSV7ZD~X_?)k2q{VedI=}iH;--{1;nDE^sDo9;$cOpGUd9UDw5$7= zXVvGDu4%XD6bW+5xy_$J;GIAG4j#E9eoB)F*8N0m1arI4zBejl+A&p6Sam)1A3dP& zwck+>9a~rTHIkJ+k@=|~>W$BK;4bUpU)&O=#*Sd4>xa(Cb*&?63jccL5ve3DkqJk? z=HHe#&gRlXi6(B&hN*A-yJhR{@~fLyl{JjJHf_TQgNI{>4=Pi}4l5@eIVoTMSY{rU zWxkB#K96YYTrf!aU`ep5Yg@T-;p(z<H7<wPb7Bzv{<KMB%5;7YJaQUiW%~oe*Pn9* zIjgjDGLf>1h38H5LG@5pd0ghrn$m=BW0{vGK5ur@ZvW<ng~`Lg92zE%AXmfYZvt@D z+=Pw+`9E{Ym@;OB1~SemoM&35mXWlK08i>Y*X_M!Td$iidB?Tk>_hS%J@B~{c<$KR zo1{~pMm1e{(fyUiJkF_8%)EC@Xp|g@TXj^I8un4jPN2G7z;PU8pDO|9uD+K?0q1=E zMU>3fEJH$x7o2g{AHk(Y7;YKQ&0YLy^y)6&_I@nC{to4ct{y_bwr(9l(0di6wrGbI z<&b$j6mcF}lJ|$YUjlzr2^^|U|52H^kBQTa-s>ZP^RGVifdD@?{uv<9usbnvkRXVp zYXm`^e3DKQT3OmzXe}G?3QI4+9uFrv0yhfSiHZQJV2~ELue<nLScXkVxG%rq^<~+0 z*9O>W!5;x(Cu_!c0wwq<sN|$(_OZv6zx&i@64y-wzx3*VAPoUQKQXQymmP?}vDQU` zlmdskkFcYWA3quP^HHrO(^&J|4dLWdpS=!jTR*=7ipG~8!)6jk=e3*9xdkn>*c6n~ z#f2NRWg<t1>R`lAw_ysJqw;yPpuGUNvJ$Y`iI2#4{^Vx?@*ISH2*6pexcaKa|0r@7 zOcZR^7q#G@<>I7W;LCEhOdO~hzk<c}b8&$^^I@kh@0OWhpz<Hh1mE(p+?1>D?O>I+ zE<d!)5)c<mx6|Ivrb{i@uEmq_l&7o4hG$k09Wh_S0Bn`NIwYw4x=St%j{=ylVN*oY z5V+R*DgYsADcJZ(Ms8Z%3WS>%C+o^d{<dRnrd%vj!Fva%mW|=OS2xU~ptFbZ)Q47A z$6#gl4;Ots?*yDbdBF>L&t`wf#4<`)0H_R5P!b1Mrt5RlFzlWk0Obr>m5ZQ#OW!mS zj)}xxm4ss_pT-Li8CPDk{Fk2m#gD6s$N+vofxn@J^YN#in(I%z^rbz3vw){%C!nl; zR~`T&sYC5E^;fXaL)wP-UVW&8LNtW?GXS#H%kAja<rjS=dEAD+%CkPGbyZ<GT7ED4 z#3#$)52@hv+s=G4K7_Z1zJDI}l&6-{*~rghB>>OcpZ>J)WgRuHJSLCO)5`L#-}!EI z+wfn0``gRa|8;4AT<eQz@1)Keug#x&aL!x)u{^l3_`dL*XO~-Xn<FTu-bi1)R)5To zbwTjjMV$aE$hle-QcC3eS#Nw(Iq?ZkH2Lx`SU4}i8dI6+(nj4=j+UJuzN6iC;OvAh zo8mzaM#~TeyaAx0X+1EHmZ|ND^=|Tck1OMz_+WTK@33IT=!xfBaZj-m3s>rCpH9AF z7+uDU8&-x5VWEYz@@XaMK$2`TShhC%)dcBv0|f8d4%oGEYgu|5IyZO(?k%R5A^nlD zmaQT&f+&I^4zQ&Mp}3;JH?p5Guf+%O(#7krIGlp-;BkOny53P&ocz&F3M2sXX=QoR zsJZ3vA(MD_$HOTBl<)Y0C*NQ7o3diZS_bXAXg}AN4eRigyQ-9FSU3l8W_%yZV`OA` z+g@q;<zzv?c^~cH+GXqTbG^KboisO#LW4&FI1eBU;r8KD14OL!B~Sg>@UMfmeD}K5 zWj|KVtQwFmbsgPkKiw7Fc*5D|lm{GlQuzJSXWs|ld=<bo;5IVxXPa#sRxO?n0?t}D zcf)73dUg^*d#{+~!)YoO%zXy3*oC$7P~<so>I^n=#KM(!(6|Oxmi;IPdOdWh#HEIS z^I+P#VJtF@!X1t7F)}fY6%#Tcpz?KkZ%QsS?8KtBt7|jmHK<IU)>=5*%u?QQp(0qJ zJo$%wC`|OSyR5`w)VifhjbVU}gW%12V;(HQfE>heKLs99HeT<?Z!mx}VD(g7Ka8C) zj(GGbS)3r5<c9o9gS<H@I~J?t$Ih7>8Gj$Z`8#avIS)|S4N*<VMT{&+5-05td{fcG z>mER^<x7`m@l!pXK)XCzmn3x_8vWO|u=+9#de1rec+OO)=GaENx(#4uJm6^C_W5dl z*ZOkt?`}*elQX}z3EfyXYk|9qO*mhHYoCdYTcHHxk2-1C-p3V77L{KwU&^8~ZjH8W zra#(*Z{vw9-i(b5JD8L{V9exl(!`m)qvd+_&MoDloBjvu-8GTD;{|;&yC`j4Zzt{c zk7Tio95A??HS=in1{rf~#KQf?)%fB@FJ_@<GkR_C`fL1U|C&t`iAo(OljvJV-+?I? z-9W8azMOu15DQHBQJ*x9KF4>s1)`l(4}eI>ta@!*?bk?t;jzEmcIz!z)URWlG92)C zY#B#Bwd{+9VFLt3*N~L`?p}WUk00iR^KVOC)v{T)Beu=9Eqz_cBD{TIPu))gfDkD6 z#S0g(h`pQz<^jlOEIy~F_@PEE4`^!{=x@Y&0Ow8YA)$pcd5~60OfvowBciMCc&)bk z&yXI!4><d-J=!o8aBl7_sHD@xRp5zJQ}eY)TE>KHsWi`dR>3o3wfr_Q?g%&&H__FH zN=I<izQ`B04?XNQ;UraA^u2eMN9|J$9}q2#SIx&_7WKaV{VU7$w=FmDJstxA$NuW^ z4=xXX;GC3Y+b<?DNY?E8*PAfFb=BWUNT%c){_BE+I?w>lyh_ZbJ@L+v(uQ-dc;Z<a zP^)C}9Chdw;$Zn6ylUUuA0~PadttLFINLFGht@1~1y`C^^}ezZ9;$q8V$o&lO0veA z4nI#q#(h{=QQj#p+c@HemJ5pH(Zlo-mN`M%P~@u-hiz)WX4)yAyO86r5m4et%zyHm z>mIo^@?q@LO`p;2c$4vQ06l|R`%Kn99O0WkX3gt^N2oWqzOUhp+?Hi@&`8nAR>p0V zO4C^Ce2qhxG*aA0Cbd6xtXJJ?aBm}RXfqb3YTH79@V6P4OP{*rH%VmDm|^8_PCce3 zNZXPHFk?r)rfeSgo4A#qaMEPdlezIQTs>;Iq|bvZu3uSxbK4sDs^QvD?Rof+0p$rN z&MFhxn?fq~g8`gT%E;Jr132HXU~T!{<u{=FcTQ{K*b(KgPd|yVAZ{8h-z@s8iw%!0 zlf3)z=PxbmHZtDnb@=+NFL_2SM{e3wdfE@3Z075@4}R{uy<*+_%h3SM=RM^S=?kRo zShqDCP^Pu5@tm8Sm9zbWOex`m??|6;)u(eaUu?ofFY>yEcMNQ7zlJynIQ#WstsByH z3|W&+LMi+DfbkS{PyKZ+XB@{O*0&f|McyvfD@Ak`g9Y8ZSPlXGn>sse2!Qk1e?q`n z{u^Gx=<oeeX67+tpvdd@0^G%I&GlWp?De>nPp?P!$)#F;s5~@9bdTxYi|pSct@{Jq zFM+#~zz%RXU7PlvcidIjyL#U0v|mmR!#MNL;rQRwzv{#JJr`!8JsLL?EpQajkAc2m zshbel$l2Hl@YzT^pb$(JDC}myLyw&nr3Fd_AO(unu3H<hRjaEfzv5Np!B0LjvfhOi z(GNfNv2yKy|B%TKmcV=_@8n3}Nb6Z?+xhrhU~AOWY2^igVjc^xzPkMTD_<VKNYF_O zr13Lm0MgvbC#n^!7FcKjLGv`$Nh9<1?W7y96gtu!qD2^!yY=`abkeR;WgtQ87<Ux_ zU3OsdRV})!A4T&fecd+*Dhl2?5E?ysYFWjkN~>eRD&2kPpG|;Iuu8C09^N6~41lSH z^J^Y<QU$c3DLCB81a2?1H@PtraoqgSL7!=)lcuEmGLfx*e)ZeDgNf}RECnZ)(R}i4 z`Ujw^MW=a<k7a0^UprxWFt6szL%ynSYc?o@ZwFK(00cI5tpohpkV&fH9ax$t2bKDh z)-U(u!wySY+p+N4g8K|t?v>43e)yvv!1<M@oE#9K6F@{>l&=7+x@6fnIMFY*XX$1T z08fI1>0o*8gxycDJ6TW|N?CR-Uk;!o@LD$s%%B&(ER%M?FQ4Pko7a8go5`nu^XFgj zvgAP^+wv8R+Q#SJE;`7IM+G^Zm}|+5ZZqK+js>=EX3QJxBXbr~kYgWYIt)v#b$lwU zixFjM7-?m2%3##{R_3~&knY*9eszxz=TERno;uwZP~GycdR2W`t2Yk#EXNF_pdV}A zCXLn#TAq#PM8-PkB8BM+NLYuh+ommj!E0T$IJ|QqM0r2+^=~LAo^eL<|Ne8ITQ(tI zpUdl+FMmaONMkYl)%U)){P2sP&mc}v#rLKoABGpuJ@X|mEhj(aDWP@QMHiKCedvP; zV_E8Q#82>dpquOYj9od&%X6`CesJRk<HF}YyUhQMewQ7HIzg#E((5F)4qVh@4}oag zBEjQUZ?u+v$Z3zy`}aTp{8&r3ag~8_ERXnhhiCa0Xto|nr``+GV3mv<qk~XOnUbz@ z6ZD?@qSMRNvrneX;mI*EbIJYt_#7WA&J|19{Ba+PD}!j8CUgRvuwf+egc+UeIQYuI zJ=1PK;MUOvJZ)!VHCzS+a2_<gOrIy<Oj||U1zf~{8F^qSEx6+(%{&X@(vXCwE_?tl zU$%jIJQ3^KF=gBozYHKTK+QyfioT;y8+TlpI1s<9&7rJ+z2pYm6tH=jx->w)=Ys&o z29%M2u2Tn(EQfVY#M-)F`PQ<l%Cc<$z*so%&~I%Qmenf{l*uzD(+1%jfb^UMX45X` z1@cJSs1IlP+~2*cY*?|bth{vv3y`z00v}rjjbdQ|7ZS0=-itt8Yyi;iw;dniTUi`i zkNX7bY=><ibvB=OQtkp<0?tnaa6abvlare-eCE9X&R5f3A``*}bZ)?AT{Ojoh5)o} zDyFq9=xiGh5ZUr%@^V1yW`IEf=OJSzl+JN%7Km@%0qC%wd8+$q@6a9R2xe1+K%c|< zD;`9fF^o2T)K~#${Si7@C7c?hd^p!1izoD<JJ?WfJ%DrHeuJ<8o<?1wuch48H=OAr zJIWtxXye)+_%lC#h2j?g0?zu~*AJoXKn{3}-xl(t=H}C5<fi=Au-Tk0HD=77gCFe) zEO2PyT+2X<==>vNwrMT|9D^H?#~yZg$bOIZ>N~%=3c&d&bld`00Hn!TS)`w$Y`8%6 zSWE#JU%q5nES#N8jt9IR2?z}SPId$xY8)r)&pz?EGIiAOq|-%R`s&YqRlfI=%ggkc zv++?pr9A4G!^*?vOt11L)VHs{x!kh0D`HW)_L=%&)@{RcPJVEiH+4#A`I+#qu*_Y` z*G4<hqv@kYlm|_nUdAA=_W1TqH<aHYlWi<+?81GF8!Bq4+)uCwna=8@528MJ3?Lu# zhK<ej8$1e#002M$Nkl<Z+CAILHy2z(9+y(?Y<5SvkJrMPe%djG@<<<LdGP=7<K~sl zewEJRZJWwPS6@*!$CXuQ7J(lyVQTryDRV-b;N{Zg^UDgp_OTzN#U-1yAKt_!d`lNE z&6hr-arH4~EN)8dSJ4L-LTuO6$^C%MS`XW|t92I5;>C*qk2eu#H2uS<EV?T@!}N{o z00IeAQ?Axw`LIv*Ypq*vx{1YUthmu_7c24=6m5$DpFit{|B|-XsDZzQ^XKDQWf_a# zBWV}M-~wb^10X>hJvl(y`}vLBu%nC);LJFRdLum=5s1TkG?TC<WGXo|`pT2`*dK7h zmqsIB?F-JZk|V%y4N@QUTmyVm!cD+>f)dZIO9CHCGA!k#_vtGV&*y0nc<1wmPs3Y5 z!Z(T4|B3IPgBu;%BQ*3$rRKi|t6-T@uuZSyrwRfoKWOv+C%?R*eCb=isO?z~^@A5N zO0d%X-tmM}9#GEw%j0-j^H+gG!pU-uR*E&Qa?L?mgvUl^v96}WkuUpRkCc$?MJ^Jo z`7)>Vy=Mi&ulnG~^Y9Y=GY;wbo=e+~N-H7qOw#J8u8MyDQ0^5_@g2YLj*N{1&9H7H zubaq<sP*A&oIde~WgE$2yI~B#FEJ!U8m1#(%0^3OjW@jSV;|rc+-m?a`vWRlbUt+~ zX*RrZt-P{m($KZc)K`D|apATvfHPmuadsXdLp9x+e#kYMGC%pX7t&Atsd+aw9wgO_ zF$`~9f8@_Mkr8JPuft2O(G|<zYs-x`s*bm+@kZJ{bfALHFiG5lfU~z%*QC2?>#p+2 zOMdNTnb-q3Tb{H-c?vtoA$s5w617juSTUs_7xl1c(%<FQJot|z`6}gCH?1yL+{8+G zbJ$Lg7&@TrVsD6@8V&V&{#TDVvP>8?3=!Ej+Ar66uzjoL{L9}iE<d|^ej6oc%OW!D z^>ob0VdXhzKD><R#1M*jZL1W~M}k^6Z!Z7x<sbBlRWIfJZ7+E`p^^(^UZ3|)V>8AM ze+b|#&(A&c5oN+S+}7E5BP-`0w#}9!r5IV8a;pObj4td=xwbqVEK{>pX*K%Lv{`8@ zdvvhUvuJd!VIQO`GwWIAskPuzo;APf&_NxP2frLvhg+~&`SxRe?i}6cnKMw|k|+9q zzp~*)%E2=)()XTm_Oogx{se#31HUlqeQaPp@Tt##tz7fl8_SZVE7QLpdH9_2fFtLY z6Hhoczuw{hkn4kh^TB#__w*{SpZxc)mMgBT3q`MZ(eui&N6+ht)`gqSSH0=Ik?@?E z)5=?3{i2?CcXpu+4&_i+?mzzgC9n?tc_sSeaVYw8Ur6N2tAAU*__gnp`HPm8)yys2 zi2JB{bIK{qC;sMXr)NxmsOkLhr&pBAsT)^adqY{tyl^sK5}t7UQRSo)jw?@m>?yQA zho<m1-?pf%!tkW`Vbn)G{Gq)c-Qilm{2Sl-;T@je+XoMS=mX2_nNxeB{cq}D$Hia0 z=)k3KeRC#LW5;S8GdRGZoq>(MAeNu%)=i&m%$>~a3y9^!X0V_W_k(TJX;So&EDhre z+<4eA=u^p0_g{dOvLJ7JEWYmAa@iL?UzS{ZZNNR#b8xN;2Ei#OZgzNs$Bi!+eCD%> zw(#n!%I9ABiZbn}qsybtJ-5uj`dN!#JGC1w`)T>k2i{*cqonen`wT7HMvm0yG6r&3 z?e-z;lmGq|<*)}ov<!!?hi)rYVYPF`H@;SG`st5i9V7sum5{6QT0(0T`ww5dDEyn} ze|yOVv1olDK;6-7R5lYnTu~J)UUl28<tLx{bot#CmnVHEboxnFx%Ttf(@Vbg^&TJ2 zuRP&_WdtDV(_Z(6GW&!RvI&|zEn`ymr8mE!Y+<7;EuGCvR%3bBEqcV!ANfD-g%^~$ z4|ynHNVOgp4C`9FxLoty@02Sq{$_w?feFDEfx&>y@cHCdys{jA(n+EDA8&kJ*@#cf z$Nj$-mZKi=h|&qTdgV92Q7-=H50HvLu5M4XeD7N(0WzQQ(wCK)4>$&pVsQA_3V8V6 zpZm9R#aF))Yw9=u;J@QiV<(g7*FE}C=#mz~0C3S0@g#hI!-Kw<D`1W_H-quk$FzfS z%g@P!E?ge{+;huukA6%U1Ay$nL0-C+Eh{%&{`2zvPky}Y0xa~I`E)hvq$i(MPCftm z8Q8l)orfEVZDPYBc~S5F`xE~f3;r%P40K=;>u?4sP8ecI3y;xb>Ve>bK(0U~!?1Gl zQ=d{E1PD83>eQ5}Y2S<==KuQCr^=cI3(7Hn`In@Be$xHb#TS>KeCbQ!&pa!`r@!G1 zJwBX2_41dO8-DSNY@VbJTRzG{aM-%!(E_>-z6|4g`&$<k%#Sn;qms8@8yK$z?MJzJ z9h00L0Qv%_)%^s6HfRY>UGUM5mN~~iF!%rP=)a^syYZkFp?k{Te&7RT-b1Uqf)A0W zMK@e8>C|s|u(?!D=1m#Sd)ULu-@Ns028mDTe|^QvBcr4X|ASe48bCM~m0akMujgO* zt{#y1ednK77X9|R<i$Gcp=F*6Q_^tSpuC-An4X6^Z{6}I;QZhgaQ@r#%fjofi;P;p zSU$amNaUzK$-nXo*bk4&)cRj_N>@331K6kjHeru?*;C52vrnl&uJdkONgUXR3mB}! zmo3@E#05*!0iyw}*vxJCK)_lz;DT2M@6Hx78D|LZ<jF~Q_W`Vyu$0^mh_vLE?SPac z0Gwx(p#ZT19ZaKx@!<>TD9|eZLLb$21t2sFBkR{~1JJ=rw%=H+T}QAPt6!%OPT+{J z%Jb1<=9bxmYn@PbYj<xdKUn(9a_!BFsEhc$>l_ali2rGP&Fh;uahU{Yy*Q_HTv@$i zW7)8CBk2N=<Bxe`7n>EXI8eq<CEmCZwDnF9nS?mwv#d;1`2_K1kWV>oS<_Xz7A>bw zm|BL=FAN&V<bZs-`5ex$*+7i)+_R(f$LhBq^6ZN{jSlKV2Lco<HUE~sV6*Npo^<we z%drovfb-`+{oZo3fHO4Ii?n;3yO~7VKE&ENlVadoc;u3^H0#2apKS|#^$~0yz-lzV zkrStu&ao59U=}w!m<Z{XKyWTU!UI)PACWQ7x8UYr-P-l^Nqo^k{}sTQ`kIaP(1AY4 zk`$1U6DB8h)HC`F0q3qR-9rs5&pZ9Ja_p>W7Ek&1)z_8<Yc~>3kdXy2CQ4atN4x^n z%UCRR5ovJeP^{WnSfZV^PT6+acj@{=E9Zd#9tb1gg!;c~#YzCc1!XRv@x&>UOFw|) zxO|}u`XUtTne`y9K*-}!<HsKaoPYi6^6jgxDn}fBR9%p!y@n*YQr9>OFeq5kcTTCb z`7*%RZIq`z701$7jR5dH(AP<y;f;TwOc>f(&SOyLv57^!&;9JG4EpBZy0FZc#pZ@A zs&?|Z^KsM0m&YA_Si<dq_9rgCD)AMk^}@xZ@mQz5;M7wRMqT;NZ?7-Q0a&a2qnY$o z1Ik&)9$!W@?d&q%f8m!`;ES0rr10%Bk%iZB0IGgr;{vJul5K+jhSDaSHDOlhuj$@d zE?#&eR@{pN{%SQm7Rz=moRuFUNgYr&qxudiC-$#>^-jw2ryCcSTNy9x+_?>FVSGm8 zhkF=hdBlKmWoq9#R$AJ<q5N*w@}#X#?7e^@T3)VOy8%n(h4if>0gcCI!n_|j?&3=< z9rh^K{rhNlNOup3N8Q3rpR#)Os`R%mHVlVf7vs#IeT@51^wX7(u7aowaRovjX*;=r zzW%1)UC+YCV9H}Wfc#j-fsDT>Xf5FcCs4W61*L4cT4x>C%_pC0R<2-E(~0=U9>XHC z7VCoI{PznCB5L703YQvVw(MY`t{32}@NDnGKM^8S(u6K|997Qw%R8T1?ja6cQpr)v zk4xy?CE!dvMjvgACaolxG6+pc$VPpfv?_S!^I8uo0cat&mRfBLc_VM(&ronH9qWvD z=!NnO=>)R@Z4aLc=<uV`nV%GFL*wh0{!jVtPp)YL=lp=VQ_3;?rc4-#3yqO{>fgU~ zZDy|lKKoy^ysP}`+J&WS)3zeud=`MSU(hH&#|M?gmU|0UlE_Z^apfDs=7@rENBp|L zLVWwG#HlCSNUzLYTbHDevXBl5Cb*a0`%9dJ$`jM7ptA3Ij;zuq^42nmO!DS-2}4Jo zeU=v3Q|?TsC!ZnNq|C$GUn6k}sK>(D)#b!7G5!mJqPPBZk0Cgmg&W%p#xB+&=RkDK zq$eHvIK#tF3xcQV3eWN%^7W7GLND@GHv9tKG8Pqdj)gOAV2#v-Yn3vD!eW!ZCYW-P zE=QG>f{-)r6<{)@Oltm`TZ41yv-(qtsbfUUa{%Y)jQumZlYZK3^g81dbs=$$ApIII zdcgH20Mk!ia&^*~G<sNhb}XEEVVb5OgJE19;xdobQB(IH*Lf52TybY29_<S*maN`d zzWIv<^*MhZa`=Su(0P23LV0<t-n66q*VRkP`Yn73$)S6XXP^3j^Z_Y5+I~`}toxQ_ zYc`iJfB&k4^Uv(5<H|#inT1=5@nr*b?8XHv%H_Ygt>?Y&HJ<m>M^dEdN+e#hB=^!> zwrYKuzhn*9^~o=<y%j?U#zQ=L+e-nQYcSqM=m`}$@ZLQtZkWGJGQEz2H<nkA7zp9r zfB)ilWjjVU9w!|)w><Xb2V|pI%hAMaW9(BbPs_UfR~dmC?XQ#~`HX9&WSRKOWz`98 zdW;2l*IK)W3&}`@bLw*H3w<YbCoVB8bF-25sA==KZFw+X);R;&hviE`<l6$ysXM7} z>J5A_2Gt!=)p<%mK6$Qd#WT+SYj5t`qhbG0h}L}6keB}G=jGl1{K@PoaaVDle&%WA zm4Lir6@TavF(8NEKb#Bxn1%lp0A^=C;n94ZR`;-K8<96(_~CNN4=ziz55MOP<>4nj zsE5SLm21iwe|<sjA8^Fn@`aDTyXW2g7ytJpkmmJ1W-IN$A=3Q)^p~SQr?>jUBFh*5 zi2AdcuN&X?zK@q5|NP3k<o1N)jxO(d)62?u3^nfVaJ>8O4}ZFR_2NtKGT0fXJ*vFz zH7}y=s{Pqr2IR%r=e)EmTDszPL2TEq`APkP|8_5W-K<%+zMS^-7xa2^?=NRen_Ry7 z>3_<6=HACX7^CCji!M6w{kOgeR{;z{0n{9{>83(pO~BX;^<}c`Ge1>z(v_X+0RhGV z<O$CCdCE|HTnfr;#>&;r`!=zIxqf+dJt1(mi^-dl;918!pq!15)lLA`-p8t2Z!JIk z>}SfAmwcCS)fIsNtste7<H4l$l7IVrqG%0z^|voBX93Xmhv(lvR^4`6`N(<C#cwo# z0kq<mI0d@D9Pt-_QO<hRYkNT5-;eA4f-8SjzWdMbD_wl5Y@SpGU5g0bUHIe6%TT~O z0qPGw<7wsL&po$1^sKY*j7%o>-~aeW%a8v3-(mrzTMOw8?mxI(@Rf_=Ggr%mk3Q$w z<*(oSKER=Acc7!y>_^Ud4xa`CxX=#>pukWD1anV5xjf~yuLHEXYsJ6$=RYss`@lby ztymxnz&J3oT%Arl{Vi`R$3EsUN%JeOepNZ;dFPcWM;_I~!<XOi+VVd?`~k@^;bfp} z+7Elm(*f&W1~B0Q!yS*y0i6HqV;?PV{;w8r-df&x>Z3F8R2S3<t?>jKQ_0K|gHS<0 zCyq{1bYI}4*8y24z{I)le0P~L@8F8*@29$E@uKp@H@^Xk$=gC(koI9`Kee2RMg3hJ zw*V^q=R4mXeciBrW0^c@YOLS|zqKZo4_z<_I%=)1HLvnR`sJDUUq1SjQ|^?s<@MQD zzOsy=ET8fE*C)(RzVL<ey^nu9*VZRpr9AzOZ|IS|E;W8jIr$}l`XT6PN3K70fo01} zS+(G*R=9O?1;&ZohO#hY9T8;la3H7kwSz<BYe6hs7fj4k4(Ll$3*Ko*98q5M@qeYR z^et;xsQ4%JO;;=WzZKAa&6mGY#<Pi;$Atjxo4dNwJ}3_lhbQJsJ{|N-nmf0={4<}; zyA`+HS}uInv+~{nY(R1AH}bT-kx$#2bKdrkJwBX2_;)WT3$6ulZVpIC2L%q*5z|sW zrf>etn>2jx?;ODH)>`_5FML5+d_9{6qD$soIhn5El#epCPRN(^Jev=X8b+SkWRo}n z|4G_`x8V+d@l(sRvrd600b_I*%VYdLu<0M4xi8&>uS@{jKBLN{DMM%zag9S;2}T4D z5O*+MV*$(xqA&pOz-nm^n}PyZ-txPRY)UtbMYY+qV}ONP(hw@vM>GW0%1!$i-Re-* zw6FX4ZNNfy)k?t0{li$O=`16$c<kHP@K|&(X*g!wq;lrm2PS|1`Q@@(%O$t|5*oWp z*Gk&B9h77LA@m2s7<>cf<D1ycY-j>FkePLKpOah49-8~vcxCfO7T8vGmobyZmJwq* zvHoEZgZv3N%cqmX`~ZjbHQhluZf8QbVa+xctj1#TKD59pX*lKJ$EWvwka1tq9*kw| zVEUdRfY1HV#}3M(PGXT4X}D3DWqSHk&g}u5KliEk0EhuNla6gxEmvJ?)biCzR1iV1 zxtnW$S~>@uMVSu(D0cw3^=IFKefUY)13$yZPGX@Eu$eYIpct}H*E7d~S1$w*v<%h4 zeFIj`{i)}=)fh2)WZF;bTR$z03G1dl9hNEA`sQ{qMb|+a0f73F_RF7fW;yBbSqi=U z+s}VdZe){1N`^i_02e0V9pMJ3t`^R^)EF9{(Ym#<E|Y>m0*0gh)O8Axwl>y><k?LF zmn~UVW>H_qvDutfynP5GFy5B}vyHJ1$S<dI%!EnhaZNk?J;3H~Uv+hvbNJjW_B!!) zBJPoirs<G)79HSq53B4;u*9`5?nnN{;#zAsi@;jYs#m(%P`4g2XJ&cC+?kRo-@opb za?QeJu@+yrU{RSieP(=355fu!!sR&+dk~h;6_EYhFRw0L_~MtA*4evQSbO?Ijwy#v zuE6e(Z@H~p1;E~qwukKGr%cS>D6AL$=J*qmrhh(u`DJC{npMe1Tx#HM!f}u7jAN5T zrY;U+GJHA~`X1}{?8L(P`m&hza}@n?tc_V@7UZw;qaZw}yEFTBmc#qiuM3v5Kz04D zb>*fTZ^#&9>eQ($_Kb{``q;ih%7gmX1@SE`?)+lsN@xKhqXRC&I|*FP1n{OCZUXq7 zz@~p}Qb-?S{xVJwoJAG{hg*N>I1P}S<QjL;!iDk2Jay`n0NgI}$JaMuEsNdz7-wj) zm^AHI&^OvyeK@aOrH^tp8dbOBDnLMuuv+3%mg<Xt&>l|6?Eho$EdZ@9w*K!$NOyO) zf;37AC`c(Hh=`OZVvB{?*o8spML<+QR1lExB9fA#fKm$5T?aUD==^^_YxZw*^r{#C z_ul8d@B2P;&ffbM6KmG2sqd^=qhHEq^F{%idv;rqqJ_jG?JmnG^B+o=y5U;&$gMsF zkDapo0?h%OSsW$L3hwcdC&~?8;sW5TYwn|WdhYh1L&n`-)Mp}>H~<@Q$FHNG=pH|j zzu-aNo<8At7oL*M$b~R5kOkR~zm$L42%N&ve&D<wM-dUH{0D!!R@=pap`H*w&cAR= z-kmmur7xm@;Sb5pT(rtQ8b8<L=PPUG^mbE=%dA?3qVlT+F@=dINqVsxK+j(`?sB=f zxKsh9M_(4=#Y<cpHdc<5t2=1Xg<=i7^!P}Fb|!=m8qOYxLMc&a4B<jP2ulpm@5Ct% z-tsg~tcStZd58ZP`Ci9(%QFuvS#`fL`UnNz{1Z}&mjmzIMUg2WWr0Js{6JHl5n-g^ zEE~@7#8ZSe+CRy#A6BL@mA9SDmyliklJ1YIHrm*6Gd<qgwJTfGrgi+9FD2vjA|<h; zJwdKLSuUWT6!m~5P7V${tNM6G<Hd7Q+@QQ7`49OdiWql^L@vrA(XCj!*(S~m;BL)I zr35rqbUH(dQP>z^#N&i`EJ03Vk$DQS_}PHv?UQ7UF*JQM<?kBL^a-Ld0OrZcUhzm$ zJpKci)R-JIsgWbIb!uEmnT@?CY4Yz3@-OE_s0(loN{ET8n4{g0i{w0dF=74&+qmnH zzpGcVpj9g)`}MyHs6|qZ35L)7IoNfU&xTcsTD7tTRL&Y7G9VHmEaZMRb*XLIvESn= zt}`q;G^^$PeT-1&>9@<)+gJ0JyC1%8yP=V6JLhux&*v$69r6|l!t3u(vP0_IC{x#P zj`$8EoMwILKZN2z>@g1lv-FO?;0G>wFx@X+vCh7n9Tul@X3K0nL>G(bjGY`@R$2jY zR#|#|CZSkp-suva`vvK8A3Y-#zgJlkRv+fO$b?_JjL3tB^H}2bj(*NHoB^CsQu2H# zJ*Od*wQk~Jy@wIqxa5E{3Qph`o`1y|qM;weG$kOuxT1%iC56qX9o7GlLjy_1sr%<& z5#YRh)f&6K=TqJ$Cl5v2LfIsD7ndt#ul0G@@@et+Uvp5YxFd$dB75$&zuAN-GyN`y z#%+HeGf3lKc5Va@PrWoC4mb~R!1??fWBZOh{|h+B`1t>ZpQud#owWW&T>muc-=_aR z1voR7y7Q6e4ejR0p}bg7N);@$9M}9Ta`|KqZtMqdyXJHBEcq`AnvXvBmd&33UGm31 zPGM}F+%>FQ(_Ve%LC0c}KTm$WX5B`+@wR`&v*;84(||MW(Fgrsv`a7fV+<}it$%i% zVuCcB=e^N44#GsB6`%{i43qTZn&=-E_ysrv=*)p+06hR*0EOy_+?E(X8DTI3fJQI? z4etqi<b)2G(clXpE3F#!Yae>p%GEhP;EIUcykfbHdHy*|l=clmnw|-iI+Cmf3)<c9 zf9T$hD(-Yj<CsA2Z^wOZ2X^k1wrEo;Q9an8#na^e{cPn|Q{2CsBhW;#khHOG8}P0g z$<Q&K5M7&>{UB|-T~=6HPI*g~a{qj7Ua?HTTL(X=ExR=E5E0A|JT`HP0O#y(-eQ^J zuXfF~wrAr;`Cl$j_kh5*QdUOVpl+)z7Tc(&9<yaLruiM6dHU4pt=E@-cfgr}&@tsF zt@5*Y!UWs#^G{ZwQbnuUw3!1I1X{gdzK!qmj5^6+QyY+?u(YY~5J>1+67q9gASt%3 z_e*=IWVIT<0%$i&!*kf(cR7el83K47kuB6~diNISd6m<(X5Kt2D=?nJtM+QrOuR#T z-eY^T?V3p}WnH{#HS79XU-!=!n%o<8aMbP%8(h=6_@$LCPx0b5TN>+iZfF<Na89!4 zT3qd5J+c7k4p<ieXNJ!xeS`x78Hk`!OU1`DLpsSy&*3Ab{T;M1*(SVc`EuJL4co#3 z#z`;YGqNyHiwp^p8-Soo8Z@#79XsoNYRg@usMCywbHcW*lB;vJ;fEjWt9J(opceRb z=!oSPn36@B_n4nx%P<Z)0G!ztomR4pe0O?L6|Yevf6o`Phz9LJnLok2NMUIUV)|ss z)Tve{W>#X(C!g5l0RtVth5yu%){j1V-iEVGYODZo7VrT$%mNMdj`Y0FDL**s6JQy; z2*?Bcq@G4#IN@--BRsqXD5d_O0SS=LJ3iD!>``ad;z{RMU$eX_HyptD>`z8{{l*_a z?#nY~`T_$W##2q2czl>XAwA-O2Ffl>F3!q~LqU6X(qxYh8{WOIy3%PS--JQ-7^!5D z_9wtIApZ@I_KpM2{qMRnerTW%PBpNk-NCu`oznCC2#7?M0o@&7QJmzp<I~SrwZ=`{ zfB(Dhw5>n=<P*TiCOf8Rm`D-_{>2a<Ow)J+<V5jtNFxJMctE}7Ir(*el8q8~x3L1+ zeh3)glPd<W0-TS@WX{g*2h{GR6Cj#Z_ILrD1;#6>GiY+EU;qw%a-?6)d_{upQ)m#Z z1Hz6UOtPPrC#Yh`WKH?vTJVrL9KcDHJ!PU{yLb)R43tH)K;JWGIOy`E4)H^~RtJ=x zmS(fUXBGIBT7a`swu{v6Jy5rWWzm7DxUGo^)_=|f<wxdibSUBeJ+k+HMD$2|E1Ll4 zOqsQq2jHym4z$4^<r^&(0Ou4j(D`8EG25~2u;tJec>rgCV`_Fv@fhBaI#UC{W(S-# z(KvGGgqz|>kur-kxupr5MU!=H`zKxieE1_nEtXCIa|V@DCIRB9C4VUa%M>2a*}-PY zPRzJQfb*qQYm+S-_TJ03N`P|!mIch|J?1qWa8?{>>-eIKz&B2kKdE*V@L5??8Ayf% zG^bX3mqsRoPOEH=$c}VY0nX{AMS4b)7J2pjqyeB+PT>bK;R|yzV{k-Tyovh{`h+Q+ z>NIr>{?Try*2lG?5j#y>9i+hAfk1rhF(1&OUa2%mdZc3;t5c!0=jU%zXV~&hJCrEE zTo~bF!x<ja*6ddQg@!f&U<TExv|7{)Ag9u#%qS~OAlRy@yC7?lrTyx!usK{v?IT*) zsnRgXQ#puMwAtw=Jzol?Xsl}C0@mu%OPr=ji<a0peF_&VrgmPSq3Q*7!{rm1)(1)* zGZVuwyR}6c&PQbrKdlymbL7h7=0Du7H$ElDDoU$fR3<E>IZN2NKTG3YZ3VWbH*el- z1q&5XI4w}f{x7_&Tc)TrELYO$nYipH`)TK1)pOCUzbvv_-lI{F2g>@58Q-YvREHfH z7hMV;c%<M;>^k))MYZUTTe5YteY|MC>WyqoW2Q=HAJ9%vhOXtTYlaY+)DAVzUEIU$ zm4@@UwJU7>hK<tPmDaE5L<<NRalVrwuL<X@XsS#CoC8q4S%CA;rw-W471A=(c%)eI z;@&Q^$eBH5TB~tU==%~?cNU#YP+XW*ktm3#$n;K)eO4@6?g#f3EndU{ZWV*41t0KB zad1VQ0&G4d?Pzuutya5uP<>sgQYCaALPpOYWk9`QH^4EOwmGf?O(}eyom6^g)B`vt zsK2BC$SJu|?GZmz)8VZzibxKWU*dv*lmIlek)mVk=1np=lc0PS)?tP0c#=n%7Qu$C zSnBmbg=obDS{GN{%dD;Elo{<SEObzsD+(YsDMscZ-UcvQw{l?R@mIP>mLuoS{f4k| z`tkVVaZ*phtLVKa>v8fTd0bH(5g-!o&nL%oJ&U|ihq+b)4m#_`Z#`}?i96a@ej_4c zk%e10r7*g2%~Ac*f9%<J&>nyDQ!guduu?_y+WlRw_Jhj;;3pnN@!>&^bR!q|7~LfY zoB{bnoM#y#sjJ+_J__QuireEC53!FLz#(X4QAsJudnzwCUFe1|4r=KgZ09L1UY@_9 z)!#YAfof=qX!dwxxzSU99`hwR2r+xh5W6O>=z0862%xaMmD3CA8M4naJ}F$YnKn`& zn99-lqISR++-L(eM!?)syzQh-jDeHie*d$5G<>2*-Kb$LyYBicLo$jO`}ILY)Goys zK|a*dkQ@DxHZ?l%Nuvl~lmKw%0Kv12?L?>Z5gyAYeu)zY?a6<6x8$ewHfr)be_p?O zd27|EI*E8ug){>n35<Vu?a_F|VJzZ-^)yy(JVE?XUnzf-1OnhJc_6%=;rFa6=lQZ% z{}+q<fEH_qOo{={8cTF)e5pthf1C#-j0<%HQhk9;VQJe!CK(+CAHg?wfp&<8E0{=m zchU-t3(o35*)-Oz`Ni&s;fIHb@d|!#-h0SCpS#ZAmoAjUTGcJ9wn}qe2QO3DuKkB? z_~Za8q}Sr&10Al?m{j9S^%c%bg$#0PHg?+gwn7Ib<0_OYWbK<X|0S`&-zayCL3m33 zaIX(d1~}h?NsZvBKgzm)5h4oD+faVGP$VulcqaEACY0j=&3pbfYO1&E__?L^6;>#Z z7S$y*oFn9As066LjQhMEcshZCAP<za6Cqhuyt?K#qyQyci#mnpgK`@4IA6#?Hax6n zfsu*Ygphao3_mnbb;;`#gzLSxW3luY%a9ni)Dy;4I0u|n@2G>!BU8ozYZk;^HADeW z&`^bO|IQz;GXk7-&~wZGz@dRozNhxjzoIc->yCHZ*6q7IKyfY5wr+8iT~@P-71AR5 z8f~wiv*3ICaMXC`Ie>HD=X(89t;>I&y7=ssIg~N}8DH0L(Z%QRQTTo@KW6nV(;_{^ zBKN<5bKt}O7ry_BtX^n-y~<vo=ijFPKLt1se1DV;9WmCa%pyhCo_BPzR!tjfT&(e@ z+OFx}d~46YG02j1rVy^3b{0JT!0mqh+pj?%erAI{936k$zI8Ke-nhP%EmhoplnKBw z(t4h*9Rrc;-l?tKed|rp?LYi3Te-#-d><ADc{y^-WSJfgi;({ea0V!!HhbYe#Q8@L zXuIEjZ-imW2iN(=Ywf{1yZn*&zw|uCq|ZM;xA>j69ee@2VN#A}V-|tJ93aObXl_$k z6F<POi1|!50FMA;vumQZM`j<kZQJVFJ%G{4H4XvJ7*H``<G?ut3J^Mf=`z-^i-3YF z8>^G>S&|cvJ>XBDc+yQu0A|sVWG_<K?ie~Wo;g6yp*`=mq=W=bTGD8nZ5C^K_kC7L zKrL>~w+rp#-o5-9S~82qJBAE(lMFnZKWc<c|6r&e*2F=0Y}?7G$y1lN23jVWlfZrY z{4=)X%ZWPqJ)Z+`0Fe)lnc${Dcn`=mb<jKZv$TMr6R`4#>@4OfQBuI<D+2LK;LQ#t z?6tl(UhiqSZEQ`ZdjEZj1FF2|@Q-2l-D_I~qynhX*_W$Z&pN;SDzE+h%gvjqV>#<Q zN2~ij0kM%r^c(@a(>{3LwU3~K0Ybi_#jIO@@{+^jnAG<*Tc$L<48_mm>hxPZ_PAZ# zprOC#Yw6!7+cW`=$5b{{Fa(dz20PuDEV*OIu(;Wd9cxzG7q7fzJJxRqfE;Bj`KZ;V ztu?*#{1yR#;J!Ds(UvV8_9gn^853nD2x*{Ia)HcY1CnyY<O5wDAZqJgz2l(lFW-J^ zqhEMlHe(OTU$BYC*4vIRyd-lXVWDBgteI|tg!jl9@|jWje|+2o&*QH3>%`}KWJmOn z(~Lg=&(kMZaStFY+QS^I2Olx#!Y{xipjD|_HQl^~M+UzHDu3~Yw8vHM@QE$SB?LG( z6M$T(eEG<meIs)klLicM4P!u8_|*2X-c~IptHXNrvZbP(m22LIK^xo$Fy=5O0I4wO zqv2*zh<b?MsGi{$-ZFT?MFY8@9TtFNXmt5d*&+vM83LdezBmlHw+Mh3eE)p{9fNri z=t(7iugsd|aRMH{ED#;a;4S4wUf?6z!yKSV8u_K&{rr@#JPb7Ty!<lv!!8OmIS&eu z4PmvYp!{)tqhv9%yWH>2J8a{M<vu`#@5G5bl4sK5131H?1=qAU<da|W&!K@;uWIb+ zqv5<wrfC3+0o*A|`0H`P4?Tw_z(Rm%fF(5RS%|nu*9@|0zewM=oa-5mFeUD7Zv|R6 zhz)uHK*fIn&L@r}X`v=j=0eiy)bK1;sF;9X9g0T_r(Ebm8cd;79~7_DXv1J!CN;Ej zXD1FFwzaEtm}v?DbH(#(u}AjW1<0H|smanQEy`%HOeaFw!{4)~1>nonLMolW=DSZ0 zQhw>xey6jXd9=WhR@%6lBVC%Wj9pt+^vazQATVOp6x)APn$)Q{OzxEJ-*wEA1UR3R zRxdVIvk4H=Mtt!^6JLRqIOHsB;}#%7ex>DnK$EhqYxhdSIj1zL1t6zUdo7h^Af&|O zhkeom_;VJ(S(A)Z8t5O~e?*$tiIQtH-7`uSGiaiw$+l8ZmRu7ig+S(%(u_^5J}B++ zBbJf{=2JSLQ*oRY{XR(-|Coea+ooF_a31pROSV#n2Etp|%Lf^YK9ng31#+k&6Y@>6 z+3WTPRqjl5(qxmywep@WeI_k{oznp0xNK7w6mXnF6G@e#0|<bZ$U>L|r4S96$Y5av z4d(;<6P0gGc(lNlRe*B=?a<*6*27v{0Z`y`_N2lquW0$6QMsNF;JjZGSlRKgUblC& z`c*@{d}HKz`+ns{m9^5=;e*2C#UI(YRwT$WCJv~R8M0(jebg=q^=0%Gq>o$&dy}G6 z&oC!}rgJ`NGi~3MU>mpYkc`MawQN5F7`pikCoq5}bk>wSZ9)BVMXk#fRdr`JX3kO@ zIeUrak&R>D?V>Pf-8nQMnwT`9#Z6seGI$1XRAU4V)J>lOt?wLedLp&xq0TyhMJ^~1 zl`TLtpvq~q_V@2o*d1>7IeX4r-ZxO+D;3Ub*H;ZYa;8cfXu<le;)y^X)zPxKvs>F5 z(vFi`vTlP-{&}4*8YTyv0sED-_;k)nN>jIG*>diGr_B7k`qgB+NWgubym@?#1HjGr zh42o@>prvi+&oud53^Tx$v<DW!q%)?D>EGVWWQPA#8Y;V_(6Q~ADj*oR{7RS75e2Q z)uGvk_eow?s7@cVGG$9^aZ2SVpt_`h=~DXOHl00ezntcb1b9UskKO#!ZohlE7Eeo- zDrqH3mryu>f6799By$29V5!@yWP+`+2W`kPZJ}Nzko(Y~M5}mdMddM@>TOs6q25qV zGM?r;6}XSIJn6d=bS}rL<tqfN=eA<Si%D)&&iY{YJSFCESX5IO{6eFoNA0LIrjMV} zq62{QUYSQJERdVSvlREajG|HUrh3Uj67{>Jc6XG`qy^EqhO;suNB;RFchmu8%s=Fu zf9^uQ!*gU16C=S%&Zr-9e0zNI7GlM}!i#=nIK&;|i@t*g|Nix*!UT{eyo1arP8PWo zS$N@H2y(BF8b;E9R;N1zh=GSt#|w?cVnIU$M5PBxj}MpB|F?%vwI6=k=w8yxzV@>{ zTU$;o97bSsL_;hI_xGD<<1|u}#RSn8#(|`ObCJ>|Ej4w*53=<adL}~X({KS8g0|2; z$GmuZ;2Bj6Y@KJE!XGq|4|krSkau|rY05)*Ex(?=<eCc)sgjKXd*&3@<0Upq-WeXs zSs4f^5--n#JVAF<)~@MFP`x{&`h!doJs_!TI19K+C9_A^<>$aSx691fLv4QwI$FIC z<ltZ3yAz(mzWr{6jT|w_V{ULo4Qti<O25XBqwm~#5D(z=20%6Djdz}BawU4TNO?}< znYfm-cbqCS<tqZbU9N~eMuT%vaggNV6#&ljJ@WcB1UO$A0O#PBFbbp(_0ks-bRD9J zco^=zE``dbc=b&F0O|=Ico)WREJFCaf=DD6QT%!suJw4o%t{TOkPL9Xnl_wtTq2!T zXOga>dP_X#0cVwy(;4K%i690~GXy_)<fQ$e1O9lFKUW4TT`0T1fG3nazwTUC%=(Yl z;r8M|woK{l_Lfy7Y$|v9RlOho%_>{t<}XZUG)h>rx<N~vcY(_>Iu+rzUHfgw=d)r_ zr?3aQwy^Bll|=qRntUs-LBK_Gc-l9)hV$J5oZ|#~RGtqw6r`M7i3j0T?3)1L;}Y-u zG5hEX?c~wHqPW^s%i2}7DtfyIvp4|I+cL%La}UPg`VhOfvBVL5JT>yb+mOC5q_c>q zJ{GNi$|Nk32D5c6(w|a)hj~fT^R`K0`NOej!%nDFT8spE4tbUosJ{$;$Zx3Uo-@V4 zIEQSy5{cIVEq|s)@gmF%C^MYPr^fFr#CvKgtFU0DMPva@e?`MtLI3TJerHd@ertY1 zcaJ-R6u!O~^{$~={98AB?zgt^`ycJ$d%FFphU9O<{qa4ed%heafA>B1vfH8M9y4K6 zM-TRKN|gO4Up}wlJn$7vYN(#X+_s(ntKl5+;=lbDQxb2y`=OKBy2X_S5c=<Ms-73- zBv6q|MFIXN0B7)k2CZ&!Fqtv?;J5l%<x9eRAfkicwHr2DhaSCrTuU4O+0edLrev|? zUK|K+cH<p(C`ofUx!XFmv3qXq@GC#Gg}wUpjf2ivHRh*Ip;3Jyu1VYO-bT<?ES>rJ zg#@`^Kcgp1wU=bZ2Uo0c0sHLzH+>QHf+P47kA7(24}<#qWE?;TpoNYlIuHywVQW7H z0w|0ICO{Y3mPv<Yb5JG^iWDj=+l5<fxwKCKv@o539||PWW(B<Cns|86<UdgpJ0_%A zHQ}vya~G?9!wsGW^rEr*PRA~GRQ61XCx<2|cMTgB&q}|pH{15rKRd{TolGXg1u9gs zj<5A~Kl?R7eY->Z7|3wS8g=R-K>8kkx9XdjHvZ)oT$2@(0oh~%ghSQP+%6zZr;e}d zkTVG#2OGZ9x}{}QUIC>K3UIsk<1ul-dB)K9Y}W7()bM7}03;l|$6<J^s^%(CPyqRd zaZq_uzc*~*n9np&Wukb-`sh$SG<b3IhJR#JhP>w>9zZEV$2Ou~6DDa;8wBu;c5P&T zc(?PgZu^_8rEDnU)-GIN)1|4qFJYeqT=qZ3PY31%o)xQD$vVCAx~~w!&wlN0a1Ca* z#io?zZ-*COwlZ~smiZ>x%zgjfz@GrXg~50R0l@%y6|Zh)P4Bta(>$tj`%r%O>aZ$6 zb_N-Mar9FF#?9}#$FAyjtNT4J5c19T?Hxo%3-5py6OM_NY+BIBDtlS1XmhX~4sB#_ zm-MV;rApG^{+mC?R`Z}c?v$wlZ8vA2r%DD*4o+N@((W2O#Bz$?xPG_ZVu!YGb0Cs< zvkEYHbo4lXw|m3-IN*%7D_tuCjMSPu;FrY!;ytWI1He2MRkBH&9j$8s)*gcfS^knG zJ+9RY7TDki9&kBlfCETP{or6hG?lx*`)(YZpDn<7+F(^+<qL-?fVMJ)QoUJN9C=?0 zBP-_3)8qk7F(wO|BIyHAg_dn(3IjkFN8JH1rVawS;-7jKIqDb_eo})r<be-);@1}) zB;Pkb`>d6%b(sf4w%)zxZaXG9qMq_$azNa#eDjUl>Smz!<W*NW;O*@}EN&tIs6V1| zWiVJqn&*#xJj&zUr+WC@^{pKkr467vNje(%3z!UWM14tq(BGT4cXu1k&`z4<#WiC@ ziw|V=i+LLWWVFu#oheKF^S<*leXLrOt3CafyL7hAt5$lsk{>`Fwv#hxVp2vs1$a#y z@X&c9n#dp8qohOm6E~)U_@#a1d8xbFS;6ZYI(;1Cr(v@uXVOrXNsYa`6D8{xsXk=3 zVx_alR;kis5HAfWA1Z6G>$Zgz7dQ}FAE(Y7wX?^Q?4<1eZC@`_Bd4_>A}yaxvX7cB zt$;4f4**p2QC=uuk)zp#Oic**O(hkbqlb0a=z*hJe9}$^$w!{TSp_^JALs1a5?5I1 zY(<?fYZ5ovjO~lXU$yHg(e^m5gD(%OO;+B{TqJNWx3n~~iAOAAC|%_(nihFQ*W?k6 zYPKfs+kMD3uiLLf70Ouastv4A);yL$69wE!O^Wv%O|)-!t+Gvt+kKLpN_<E<AW&Ym z3a_i)!YUOjtw}{nTfc9seY0+n_^lK)!AmI~rPLPNlmc*5t8FV$sEl24WoyxK&Ni<5 z*``b$<!u1v+Ny0gt6VL#W$z7q(N?VZK1`a#CPn4)OuZ>wxVUw=xx1AtSx)^B@~DGk zRo{PEuLDIt9WHyp>+B*8?9*h)ESX5B1y=yiL*hq4%c4HQwbukPAZIx0m;*=R4`xKr zuual}0B%5$zX4`?>Q<>@tr|42qSBI$?CTwrtZh)8n6zM?`V*~`BiqWS%bH9G^zPP8 zhs4S>hCXOY;SyD^j;mi`)-_<<6x*gc%7jfVp@N^0-RHe(Q`82lEu+loJ7`C#6AnBm z9QC-84%%y7r@9r<cCbhrXycAu_Qm|gwsPAp%aJv+J=D6X{7Ms5^uIrSj)!w16k%;? z6L-9#w%?AMqXpd=^DU>^SNbTQ>;W>6AN>)B6QO(N&+N|OkV5Qdr_YetF#ExRh&bt# zk~e79EKqSsCILkRMv~7&?IPJLjoO@A_|2j=F}2DCdAX)~1#4QlETL@BjD@xa4d>Xj zyJ5NF*0Op4>_48hz<w0C&f*vgx+F<GroE;Z=}$5W$nUAcZE+kZ*lWzE(sB=gGv_Z* z-Vxx;F9W?SniRLpUD(6K0q3=AtU$p6J}%0pae<p%AuVS}U<v?OgS0wG((|qzOj=C& ze91z!XUDC41>`cL<<vN!RvMYZiTPP9E$IDPfT0|*B`X$b@k}88_8qod8qTFkmvYcK zjq(8}X^&Vuq5K)#hW07gaX)oJyLt{ElNpbd`c1N`)vJUvE|e#nmxIEk&;pS+PD+yr z1E4dzyx8@$dgUtFVJ={$WKu;UFa9VXKzA}=6-`3QTillE7ah*4y1aGEW;>X;U-TCD z1uekw(=x;1_Hm(8@&eFNKsz*wn05zb3L4Jz1LPgrU?sBcbV4uh{ElCL>352bmwfs2 z2$Jzqh&}h8knIpQ7OVF+<VhYpohUJnjrf8Kk7IYxPQkdN&c!YjLjY8uL}C4Tj4tFJ zBEmn_AUNugJ~-N!=-TO_LWSTe6k?R^e)Sm-ygVX=)pw7ZuC!X0mhiZ#LmplX@wD6* z5k&4hFC#*T(}6_tukuLlj>z1}AuYn?)#4&1gxo>5=Y#%9m*NBA{6k)xU`YaUrN5Js zjlJ5<kt3THMzsLu!J{aM2mhq2pI?`Etc>L&0-OoUVqcthT*uNw_PmWzB={pTV&8x0 zn9Fl6*$MVyCWNOeFL(&PT`uE*GYP2wrcR|47<N+R9Xfi#^5@r~q8jr#pr!FWau$oq z<3tXL^1JU>+Q%a&6S-X>!1=oCu8h+hqb`=Jd<P*BEl#zE@qPvpbSD^GRa524;epz% zfLRUd^da>rd9_%~xGJhIo_IV@=lQgF<v#+>9wtUFnee)$^7F-nc&3ye5y3nE^KzoB zNF)R%&j-X~#)Vl0)Y6`N8>F~g83MnAM@Ev#<pJek@Ps9v-~4DeJK#*L%CA4=3vLB2 z@FpZ1;`4DzOy2MjUh>0x9t0P$l}BEzvFD-exlw3jMxPJ9T4@J#m?4LkKG06%W!hDh zGyTSUV;Ab(Q4f7*yM{XGP;)`T=`YftCmxScKks}p-FD0D8LmT%x>liNAx{e8JRcDO z`t^Io^IO0<2xwGiL#FulMFEfbeBB7Qq#vV!2a1@opFBGN`?+*L@9j5UC42pnTX?7U z%u)EGd|2Fe&^gZ65ZC!~3-#OcEuQe}JApI~aYZr!W5tPo#?p-2X_HQBrzQu#GuAt! zT{oeP3+*E&%~At46NkcwJQIiJB^0D*TYix}-M|e`OKJN&fOf{|Kp_StH_??0a6ThC zSOB4Hd@K;_`<M^5Y;_Y{x*(_E|8~dN;yZ2Yzw6;=J?@GX%Gd|*y!^ZABro&d_3)P; zBDpZv85|GI!D(n!a_HGj*EhEsRW5On!Z+^E0cUJD-|hbX*M_sR;lK6^JKRsc+~4Wz zc*8aJ@ZDYiAE)(y0&wO)zuS5~?Rjn4<O+M?@%#QT-vftA6ME!WfB)!xw|ad@?s=GY z9rPbO(jQ$`{Zbp$H^iIV57#JTT-W(t+pYx}T<`mDGc=(u#QmoLXX<y`TOJT@aopR* z4+p&Ps{=qUgtkBPBa<4V&&_%5MMWMO4jNx3W;j4Lz*IE+=rH)jBtq8MN*iD!{&VNd z<+fgTXd=yo0iccs9`KGyK0potHvZW@kL_pf56M6`pbK%FIi13aURuR&e*M*;F{Sjs z|6+no6o5?URY00Qx9dPQT;i@>_WBL2JZ|nY3pfBQKB4WRuP+SSn+^&<d$auwu4Mxa zonC&$E@{{Z@3vv-VmAj70pJcaX@VCfJLg>UI*Vw;_3M0-?b)=^fhe>IdySv$CN&O8 z%cp<G_6`&QQjrFEV`9o+50I?BOgc2_ey7K?Y}!<t@Y+l6@03QW&wM>C4mgj{;e)G| zELC{SmZWo@qe<1}?E%Vnm{7mgwzcinwqnxh^2%#&LWGDn3n)ILK^=CH*(M9$g9a9p z>6DhQWU08l?DwVZxqZzVX)sFzQsv$C^}bfFUVW!;+^a9!k5i^N?ZicI0)Hq&J}n-2 z(5f_R?tW(u9bzk{{N1<K?h}AaS!T?bLAH;Nxcy_cc0c|1sg_={gNE}<ty*cgs0t?V z2~F74nxW>DwkwMlNdl<h8;csOgp+ST_sbOKI@v<T?O40k!FFVjJn>7Jam@gR1&acu zOS|9CB|ocY&Jh0v#O&Scn%+;0pXl#6%<tVEx48yCpgWq5*rraEQi}`H7$qOXc~tyC zo&X^M(*0Lp=_6yudifIB3)fv|J2&ZoD80|155TX>kIEg|s$G4x>@+{=>CPNJ+-AN% z%uUUpnVF=OueOgrZZ(?+eh!iS?4PB<?V2?V%m}4l(nj;1Izs&Li8PQgcn466=^9)_ zJMUd9SaO0a0Gt9cv&chu09Lkqw~!s~$fV6-Y3>j1dB5$~0s`8rfJ4v__<PD88Zjac zv_E%UD`~>+iu0c~0p~yt7oxkU77Okl^d5J%Zs`&M+4uND1d9dm29pSAm_i!^HuBi* zg%{%{HD0^*7TdCNrROsYR70M9@XO>xc_cmZN4^2i0DxVFbbU**xL)bn*-f6XfP@^g zz(m<*)`AD&;SCz^XhBeq;SV&zNB1jvWzs~xFu8&s_(HymcE8T@T~kka(STXQU>~Gm z5<`G<f)0||myk;JA%hh!n_b$pYEzkn%Le3GX&Ih56RWeTYYfCs>;A+k*$zK;&`tqZ zZj%=I3FT2*RM;`iltI9JddXy3$^J#sSQZ$WM(@%|lTEQ{;2rF9Ch3ry{Ry%oorM2P zs{eVlI{|>~jCCsB)H2IHGj9H#<+f6wGZQo|7bw3+ZMO~^Jg`p-2ghWGyHI}1moJyv z5;PRiP}1bqXK4)3H6&%=F97V6OeO8xbJ$8}EMqs<yGoO?^9vse_$#+`_XeA}N$r)) ze;iFrvcx_6q?wk<Ug&VUWe{I+qkjC_*6!IUvXoCvx>9P=n)2WgOQF8w=JwrXR-u^t z8#(Mv+pzv;mj%k|x^}l&l^Edsw*k*-@$-8JVS}A!w5DZtqh&k0v0WFH`R~(6JQJsV zX%pwpwsX?DmUO6%J0gHB!SduU;O0rf1V{**c))gc<k#){qLE7%DjuCyJKV0p6;{8> zrB3VbeI1jZi8^F-<)-!GYiPTVsgr;4_PZQx{=G0fdt=;q+a?nl09#Bp&?4O}d&AUu z><?y8+skegWLp);MUwS`7By>FlN!~+^WTYl+`Rer^R{jFMEe{4?H2WKgQiT3*Fhy{ z)k>DJHg&J?_Y>#Nu`#n|S`PJ-nAG5KpL6QNsjt)(+7Bj@92Q7fqT#$ppfQWB=`#w< zS9!xr&C2By5S8x$)X)Y&KK!JOKBPWmpR~Ah=E-LnwdiwJ{YQojY3;RJud|%4A!hc_ zhvV(AG-!#9!!tY7uWAh{m2q18jh||35_B-E>VE)Xl@_3}>OR`Xm=OW^d{!DA5fI<= zlTmhB&vQo_&hk%Nftih9RznMdqW}8*#XODOCy(2hUzXXrb!#M}g)Fc7BuoZjE();u zJm4Irb2+pnzeYNZlRUK9`UBE(-o4#&=>We1(f}{2dg?%#-fz?nhF@gc9Y?tW$kKMQ zfQZ)kPXd2SmM$&R7^T$43GfpC>BDJPSpZ=y;^2W~6ds?Dc5{*rh+F&18uiCVt-9nQ zvldurSG`SE`^FfMg=hL6+D@kQ)S-i_hr8AOZ`RJH!bOW%X^qQ*MxM%?0%H=d_JTIj zHQHRgQ|A(BF(px3^tNx+!I4P^t(+#&IVe8R+5iAR07*naRJEW5y;^E>`rPu5(m{4| z97tg~lcYtiwhz$W<x0<a2h-q<%NRGJn>S(MNB8>Y9UwNc7<}rI`XCoTJi_Ri3m(4Z z*FT;DFG4&qKm*P2$RXXxC!!u4Vddl(U<T*)&#(9r*rw>BJV0k~`sI>{VvoFu<t1eX zZF26Pcw>Igy6GWJ^$AA2;@-4{%WcGjdG0@_4t(wVXh%h>{sx-VRyYBQGsGCnyKVyI z5ibc2ze1c21}Z#sA3c83Ce2!<1JHKqaKW&pl)8{#hs4&dT+-^-(87ZgBmW{S0-VX4 zoBdF{EQ(EAxXylDvs30jI42{dl{-g9t5iCl4lFFI`XyTQ+<B$njWSL3>C}~;uY$R= zSl4SR`!!zx&Jo~2=?osX#P%Erv~_59i51Pyf+-Ro%5JX~Vkdm_vu(iKl@=0l>9jyo zC~sD4TBo#?E|SxqdH!R49sHsV5-I*UeB!Kq`OQzZZtGr4)S;F*+J%Aza#{WQRjf|! zDlT_X9{Bxi%-8ml%vWGC>4-FVaU8PAVhXO&RhL_>nw6aIAwQv%ARz*r<6v_rF!@z~ ztTEo91Bo_%(mY$ceuwA@d1pbafOdG)sZ!QzscevwC>~-SGi{N|ahvaAhz^TGBR;ce zf`~?!RkRuvrC1S_gXAXg#DxvvpqmS2q#MfG1yR>0)MiYcv&w#!J@BL>$31_@NhKXv z*|2&kORt6V>EErjwOjW3yXLjaSixLsdqS24-U2u;_ID0AH<d{Z-Gv3S;E56qEr4W2 zZJN`=D?W^|B=@?|M=lnz%Tss~9>=edeFY>D&t&vMH)=1af&(R2)W!Tcb%^2BqDSLc z0B0J3zQbpE`<hnm*kiXgcUcQjDJ<=w-|!XOm*4zgi<YnVn--Fn+EvQM(}&bR3vx{z zz}s&CXPMN9+K>3IAdk%h`xRea2lX4;A!3WsphypD0sq~PzxD-7-gj%;$W3WD*sOfQ zEBXui8SiV<ce@>D8ZpmOi0izJ2VVOQ7u5ykC$3e@Sedpv8Q{#>M=Y!YII|P*r1~EK z?bGVJ&*_&;E4UVPw5Tkg*v)FF|8XH!E~FCe^ue1@rpTspCn0Ay7tR-wBfwdGGz-*} z6@9;RSb;GI>0>B8_XT9hC=PR=EnBts>kIi(@PE5we7!>;)U_P~c7TTSxDf+&2yym* zNbBDYI4eUzT3q=4A-#Wi5X=9QZo_$wzaIGN<G<E$b{o$B3poD+@BRxP{Qnhj{&w*) zoBM58fCF$YU#7$#mJTK{y594IzefxFnMdx5`=y__^7?LeK<6;w-g@Ct!$$KTx#Zw9 zrgA20C&Puf{{-MndwR!1&)TA;E1ZNb?OWLccXYlGaxU19+i;%W_hk=2CxN5EW3qy# zC#E%+bTCP$b7E4?04wTj03`vlT<cHZ%t@_SGC;#0egJUL45V@2FL09QfY=-eNW4)z zXLUdg+b+vDXka(=dD`g!;C-e+L)pDdWhJXfTen|WdBJY*@CWacf41B*Argp1N2a+> z-|xa;1yK6!_U+;my?cg_upHXz|5x4E7y8)pnbUo{3Qh0>pN;oJ16SzTXMLXZiJ1d) zn*5O$z)7}*Vl=#D)#}!Lz~4N{-Rsxc;5%+r2Ts?Y+O?O{2~dO|&o{nOz!ci6@Ld3? zIzMb(ckMsG!EYjXw@WA6EiH1&;9lh=r?krdsvG~p^R{Z{Ob^E7`+6OISEhCyzaRea zgSJf|A7x8^0M?k~1Lz_PJ>DBEyU<~a!O(l|vfXQcaazcyYh;V=L}{ZRI&@GA4%zHB zl~u7SRUL4CLRzsW#gpUW5ddugX{u#b`5zYWdiYf6_zx;9CJi`Lko240b(dWxQ1`F8 zh2zKBmjmAR#gc;pV+#~3Vb6X!#iQ9Fn&0fwQJ{hbCh91CySLI};0D-3o{=fagmR!f zxrQetD_v^0zx$5Ib4X@fUJxLTW^4pf@&W*W`hd$LS$ksqc)y<U;fFSLFxw@h1*5VB zJibAIbB!3_{NBS4NyAw-oMUy2!4ds9@!_aL@C4cbKUvTKJO%W`L<CzvB9PRF38EW^ ztWZBNkwcz2_%oB_s^c@y#1|~kHh)iMH1=vS1I+_~5hme;MV0|)yXip73NcOiK?0B0 zELrUDp~>x|i&xkjMdO<ESj6Zo?P=Vi$&+pL%P)C6G{(@5c0ClrUmOG7<c9{n+O>;q z)*)JeKllMKfv&JEFSILw@#Gt@pE5#29sc0IOCKE?cy&{c`>h_g+gi03IQU3ex`w}g zp%q8nW1)w#jQ9xe0bG!McoDUM*u)0xrVI<*+RAcYQ(I{Qu3%eOz=?QxLN<I4?2#?- z1T9`1PAA*O+VLU4_^dR7eNgZ1o`8A*jV2A^G-&~`bgS!>DWrLI;;`-6o+LVDekFZA z%dYU5v(hf8d^9d*K}iOloes<+5GRv*F-Ykh5h!%X4(?N&0<8*`(#h*ObPx@rJIXeX zZyg-BX@Tt&xJ^~ii9^b(%s@zUc7MWgfzGL|U||8yg>oq|En>y?nVxggAF(O1@^V&Y zJkFjyZWS_>v}R@N!b*26ChR>Xvo*?R?hIKhqb3fKTb;1gK3_FkcIyvWk^tueht62N ziq-A*#@D!)#ADjo^37P6a|Y8XrIDUOlk`Fvb6U3>yStyAJGR)czr89D6H_;A(>-l% zZo1v7R1Y+~E5Lc#vc-BXO*$=dom9D8)1tj~Xn$)&hV9k1{w2$oItWs;a&^m{LwSw4 zN%Ow3v2(t0o}#V1S9IpeEwdBZvJ13i62ycv$R_pF0Y%D1a>9KN?Odo>vUn7oYb39c zCTe!|ljRE+wDhXGksJ2aR9mNa)MeU}`*bKLZDcMj>P8^^0hQ_TSiAD!wAr>>wwF~K zBzM^2JuW-G+f_$c5Xt6R+n7K?`wC*HVf8CqY}eP8W>(ArPH&W!>P9UPXA~`!q@|ik zVdkw~ZS~59Hh!zx{=u`RDTLYr#iguSl_JIMx@xsNmWkToF>c`kX}K1Z{G!REI>KaM zbdaV4g1SDVP8s0&lqQrMZU|_ZMSM)JJYup7b1nX-K-4pE0w$v=1ES$|b^n3=%Hu9A zg6Kd!w9Ez8cD$mF)hJ!UY595E4jVFKw)ih-i8$nLX;9aB&Gm~PkG4ehQ?3COnj8{y z{_vipz%Y8Zy2f${u*W?;X0&ZTtOJmxQOzV2kih|J)qUzeliM8WGFT5SuHm+-9UZ2{ zwVk`RSibzSLoFN5?24idWf7IO%)_hQaUoHd;%PG2rD-#H_&@sEtva^!WRhe#@Cofo z@0Y~KqZ*&>65#xc%B`%*tyJmKN<;4zS!i38G0&WM%B~2&8QEk$DlNhTI=On=)=et2 zlUAv6MUBa_i7w35Fo9=5OYNf;!A`6G_yUdEILekq+&x;%-=nh<3KlM8#Y>iqm!Frr z%G1kKX*pow7=jM075KDIY3|;&O?~qrD_fzgWzU&YW4AP-0eTq~;S^4P*$<qu9EVP8 z{E3Eh*peN=CN3wQM-QOD{OeC`oNA`?7g`)96U`K_YKxw8rJ{D8#Gb2-@pt})6nIW( zXbQg}U9Jfq;t)3-1ED33o&m~;N&dw7F0X|0k1|QzII5;Qem(EOSFEV~6?G=0uXL0z zz+Zj&GwP$0M&4-qbu(nlOq;u8jfbsvaS6M(<JIy5m5N98lK#p29(*_;=U$Z?hzL0j z)CF2dGlV&3s|6m8nDo7CtcFnk_+6%09_w^XO(_zj_m}M2AiY5IS=*J6BwM#X+Ey*Z z{*lX<E0cAW$$|oTvM3n&54?Nh!+Ewt;c@r1zs!mk4#0~q(8tPj&E^Dqcl3Aer(mAU z)~j>aiQ#!uotgW?CYv~WO-$q7z5VJ7F4V1BOgmD_X<R|47@Y4Wpzev5<?D9K4(|$q z)nSo6@{|0xQpM7C(@o7Zeor6hSHO=xnrJ`#xH`GFUtM1-P3MLUYQ{<;CaW<Y(V`RC zr0<6#q3Jqh%YIm6qduFVou&cA{#B&0n~J3i+l?)1YnP_RkmN(pKb$bfeq6oj_q_Wv zOl#DyQ6W}#G1*f{Uz~9taEs@}hBwtTmGy3&TQK6wMYdN5-~OJ<ojsFvX;Iy#e!Iq2 ztka^h+)X+Zuz3FLF2md>YJqvsgzvc&z?<2+L>kUYD_%ch709U&2|-qLr)%1dxO{t^ zIWI@}N8SVV?wwo&K%NA}SQbTslRw=rTff(4{jkL!RW6;^n$*%FrUq-Y|3}oP4fy06 zf0s)pxbAM>P|sCj6c9b2{NTL)@<?v(;??%`{IGyhTMGis>s<=j5GKllC;TTTGP#Cx zpL^T5=U8-}i8#f2NPcip*$@%*D3{^6zDJCoZ5y`k@%uVe%h{E+WlBTA9H@`+jQ+;Q z+j_w`>wJ3@#S=>v|8itGrRHxeJf~Ej2Uwg!AUr#t&avppP7KAxJRR*~+RD>XHae;C z9rJw5YjDm3Z4Mm*i_y$c=^u!X{@JrYXF*%0xS$!Xg{-OH5fM&@_#Vn39IBq`BDG0s z132uFF(vYHRtv=J=7u)`?*QM>yj$2r%WK;a@jrE>#pgm?p!Gt0QqO7M&sqChAGGxw zgY1>m`3x^U+0#muDEg~N{uRJEQD?<qkG62ZeCOkYAIM)!j?TaM^Q%7xoY8Q;$0PVF z8qS-x?hsax+i`*4OC8$x3pXfIFu#}M@A>(?XP7!bW4oXh_cLl|%D?K+P-TplH+Rmz z9M!)P_CgZdxqGjVxdAgnyY%Ow{*!<+ZOZ1Y+cnQlqr)w8yPW?yHR0|5gog8l&=L9B zD|0uEWzqsy_p+*n37N?4))@Ed8*ca8Tr$%)b<AML9HRHX{oSVpWBfBO!p)sLTno`* z4)R;S$?yLYfb*D%Q|-k!2YWKujQ?~<-}o-u<Z1sa*D1anJNDeBQ6KrXeM|}*k(Mpy z0hnZ=5eW!GCxO|D?3yS7UY$_KfIq-BKG`(UjXFAjWEv~LWi*-rqk{>JGY&>ZnwS7O z5s(J(1319;JSKAwj2&y~lpe1C%{L1S+hpad*RT$6zwOU9X<|3{?jEk)h&DAK5}LC| zH2`=*rYdk~IKM3u5>Xo6-<SR20tIx)TcT}RtgYnwi?k$39}P(=BpnER08~Kbefi93 zwr2i3pEv@1^%^(HGAO^xrhjdto_^f5Z|Ioe0{|F67@Y+GLW!z6Wbe%ZPS39OYo#sS z!6#2_6?$~ym(p;~=$-BTRWEhGD+^jiYU_y$P`=CC{VZQ;4RGWJcDmVii4Oo^_m3Q9 z*_9VGQ-4}8-)SbCceonx_(VaSs!xn#0}g<`<<qCz&vWLunFc_=HqZ32vULJT^Zxz! z*luY*(|e<>%p$>FO)lx2SwOgDz&irJOFJ!ZOKWte{K8v6V#44Ljd%b^%#(C_^>r&= zt-1rwPd0As+uO0@oL=%&Fn<BdAm9cQ5h*gJb9xhY(`ctwqn*bWFB){~X0-(B;;@xW zo}vcRf0bVrF?h}-8#$%#-?473&HeO~AfM8%1NePv!eozUn<nP3cDT_25;TO_(j5+? zOXc7?gB0WwSwbG7G>N;Y>>S@M&=|*JM!(LTy?*$3Lqfw=W4dYl;*j6xMK^Bt$dUGy z%yH1*VyhZ6BCQ^N*tMW}58%9b#&k=M+^L-SKuaW-fVuD*`9q7Bas|Ku^aRkLZXz=P z#_%SJ1HoX@M_vF~;qUd*RKG$dPH-oc&mj*!U<n&HNnV2uX6OgF#XtEWt{ZzjYIWMS z^)TOl@r8|f{WbSPTA0<Lz5`@u$dFNVoOFP?{N<Os|Ebc3pZdWEUZ!4Fq8klNz=%jI zA3AS&{)M=P^D6?JIT#XvhA@0^q(|MNlAz&>&3Qm>KzOv2v3CvaH|x;AnoXN|7;HHI zvUI7pVQ7SBR(nLg&|YT1iKFbW<&F6g(!zuZ&nN?SbI_*IUQwq>kLQ>V$<d*uWxKkj zG&87km@&};fjSOsvLBH)-=PBnfRCgRV64LtGiyMrgZVHM;o8V(C8G%_U?z>Ui&6{V z(T(DkZER^e@7%IS=^>*9Wvg9)voxeri)ZjazQlqsKnAD=Y-Yg^VBwfRs6z*}{eHLV zMd}PzxO9HSA-mTC1n(->!t=}5@U^q-;7J|iDlJYll}Yp9fdm20M{Vy;9k5!gfNXK+ z(un<(=n9kEv!{?Jr7s2oo&z@LmKJsA3N0m%nph~_`RiBPob5l^S=p0zkNT;cx0p39 zQAOs5X)Dae|MZP5SiRVe?oHHIZ~+rCY4c2nZdM_G5r4mE<0>1sbhgWGO3|o>#X2{< z!77v}@9#e!Gt5>lmyKqDnP`fi5#ZdeLl3J~y`H}xFz`A1@rUn4pAO3u*qk?iL3{Q2 zcfGCvP(S<Xv-ZOpY0zunlUg!!k;=ZNK<@`TbX5^(VMly?YRG%GSqHKm65zaV?|y+} zxpc5$)}SS;dgNM8s{GV{FA;z?-PEgC(K<K2%IVmn!Nk);KD5)+X%C}i0`cIQn$@jI zwV<iDPrH2H7&BIjyGI>x#uNvBA5vd&xy&ozhEAJhD>iTS2_TpulMJ84D&HqGal*ba zZA+G{*}W}5Mx7WHR93Y&kGE~3ZR>&e+XN(kI(NQ+pWO}~?ouAh3H-Z7^`&~rlAa!4 z+thy#nKMgeDw)${54o#csF+<>rMmk;JA3@1MLKY>u(Xxo2U9;Lb9yagfcYVFL2NXl zaePu*wOh7qRrSDjcFsVjH0n5zk~HW;-HxJuncN~{{L&V)@VR5>4y9GZa^}uuEo;<> z1LMb3FW;Ru-S(+3iTXdvq(`HMR#1Q@uFvq1uC2^ME-nJ4om6PnGZa|wZrs%Jsc*-< zHffw~P15*9Z7Xd<0Gu^x1w2-HqQ#XxZ3gRJDez;f+MoBAEU;a>clber*>zYa?TP!< zgqt?QKMLz9Dxa6-$ZO>?h4ehp-}yQ$d7YQI*AjFvC~^j)y&Y6LMH`f$a@?|UqfA?r zu@WUpcs_iAK<VKhUU&v$W^v96a6Y0P1N$@)Nl4hCxO85`#pR^oENxKj^l@!Y1wrH6 z`&YF&)CnR6a6;Dh?Afh0W}h!M6e(U*zSS;7$;6C+VD^VLUjN=!9g#NZ&K=v;#_ZAa z6IQ0YY*h=)7n-23qE#~EoKXPwi)2qcWx0}0%e+j`a7I4Jh{VwI?+NM&&ie#C0Fd%L z<4I2B@{(Y#4a+SqNCAFBSmYK**dPtM_F%g6bVHcP7wLGt&;yUlU$7vmHl0L+NAKr} zm)l758G2MSaTkGjq)WWvivWNsVxFD{@RxY`sBR!bTq`XHk#*g7*yQ+uWY?=tYT2-w z{HXDzR;tcXmJR^xiHPCbd8ydB@^9!QJ$}Q2);U`*P1H9&nx&+|Tfh*^2IR<^(RT0C zP9B-X2ye`C%J%&e-J58P$6~$G6RpsBM2ihC4x24A949;l>S2k3*{xWC9JXawqO^tg zx!mzGgZiq+Z@WSZV8r3x1&;2tk0vkkn=(an+Fk9m=oJbtc+mI2PZuek{eIuI)umQN z8q>k0u$kX)l4kSj*gfNW?U>A+S=!AP+4enJ_&gHm!b9b<`K{Y^)#851H(=Su?TPlz zXA3<)yiBLQqfANl&C=3eBW>aB+xN!9lqgZi?!C7|j7GDG6KC1#)tg+YAyGSfZ~)TS zYR5HfbeYwtaj|EKl8EGycVv@qL>jq47VxoQ{bqaf?a|5TxyVWv&1bo!-Tup_owj}V z0T0Pni9&hoo=(lwjfb+GIBT)3-mpXC9PK)YnS;ofKCSPh!hgeB7aNNfk&L;_sVt&8 z7>WgX<q8?(jF8jz#)z+_J$oMfMn($d&8~hwl@<)NyFrWad2(cyCUsg{zb%2J1UOf= z5(1oqyqq&kY7F{fvA+Xw?ktVsP#FX5&Jgh;R>dLB>5OEBHV2yYP@f=w;XdLd-1H|d zx1JY$`7?b*^&JBCC!MfQXRg*bkvPpdN!uEYemAF~Hhst5gYg3cOBBqd#gfatZbF=o z(`c&|&f9C}l}VO2+vigQppH3>4q6QGdM|&WF2;y)>If|*s$_=-_PM8xzu`IYI^|^5 z@5Li7+y$C>&mVIRoSV{^8BCVs&Veb7#%k*sPsZ|2n*ra{{!re?;#ubBKE8~_AEMG5 z5~Dp+KJ{TN1vs2S{a#8AR#YECo>&Y&tvci&w)(SZVeX6+V3=pHz<f&J^C`5Q)#slP zzJNBe1J3lJj9uu1NLO@3nIt~ak3O_bxX|Z@GGNS)`5Wf~3ji^>IIDRIKsRv$G>7q- zc7pzw0M6v&#}z+Y_xqm`$>cHQtJzictZRqstyqzQ{_M{HXAT^^|M8dHUzJMb?Wu=k zmQv@TU=HBhCCluWb(=hH4oIt6wW2*DJJ7jvX+b|$uRUPwi$lx$yc)DGue{<iyXUr> zlE1e9TfiC3(pUQr^|)GI-N3pjZv%$v%%iEZEkR>pz{zTrD%hRf+8basZub1|Y{ck^ zI(%)7WJ-(E*|OLZ5B9Jt>s{vWfA0$(jvO<|#(g<mpyv+HH}&W88kJ>V_a<qymeiqe z3+){p9EZF9nkLpsCM6>G-bbVDs~L0s_PO5o+9evly#Mhy(K*YuYzvEL0L~BH)zum| zs2v6K-+v|SuOhm@o7Fl{vj5-_wrb7#xE<k4!gMMqk9R4rmtI`<A7Xm>?IF_eUE-z` z4r)$<LoRZNx42txZe!OpZQ$2`^=qrl_PyHwefvT39PRMQsWU^`U*AmS-P-Hxt@l4| z`=m&N8#C-J&DDbX0r&rHfb)0K0KWafK9FX&i2nO^-cIC_Yd<%rQ`6pl@zLnjAO5!K z+SAr=+UoB|zyHQR*o6MQfd6j5nS}}Hh)ijG^v+9GQ8NDTb}1(7(7?4H3=x2n#=(?> z0%Q|4QD#de%{QHngUZ-W)I=EYnNIzrz&sjkw3N_{P7=^T#{&QiP>r@0je%?UDDE<K z>sg8FHLXy&^3wFZO_QF34(`!80G!e5q5(>JT?Y)*L1veDUPnFhu&tLyW$}uaSjT<? z{n`5Ozq6qNoU;l5z&rqSq2Z{xtvxttvikvWe!tr-o~Hv6<Tlu=t*7npn!vt&Z3|!7 z%9Ag@ZIgD`K}{9`L(`!Jpj^}W&_DrR0q~(Q#^jL(>VeVY9dO>S$<x~%Zg6@5TA9S6 zbxMB7Gk$Ace}gsdahKDxV#YKZ^Fkl*8&jz>P7XLfUaz)q@yEt3e8aQ`AQu|Wkyi1* z&K(U~#){b5Kli*JDo9=)Z`{a^DDTiqx|9dNBjpJQ2+({&+Pg{OH-iYkfB41#q-F2k zcJUProW74AeMB10E0kXWZ3+Y6eL#S=m$@`O+dlEMRT6NF`{Iq)ZSjN&4v4}RfV(g` z3Z1;7w%%V%vdo(BV^ZVktFQL0c9>FN^2%XsX~l!I;&(=E+h;IvP-(Hkoh6fO)++BM z>(r5*>iaysfp^?to0cteo<^N7JV)y^z2X3<4_fYF#TvnNJ7MBU4r!Y`^6BRu59UN( z?|75TFAD>J%RXLFsUK0kaqy6^*rI0Pfv(=oHV7!{^Yv7x0e>%CbBzy-s0+w1vVwoo zM(#^it7f<N>xWmH|Ji3Y<Nf!&Y#ErL9f=L+YE7H^`#}#qV9V#KGt*$pK~K@`fUka$ zC*%sc0vM_T)EsD)Ng8cU2EfXtZSBY@bWj$=LH&&;xjX|bZP}xTHR*P%r%Bx%aIa25 zUcSOXa_TtY*#d`*uy8;<MvlwZs%Z}n4ub+TqF-#&#!g5^0l=XX8mTkHkwf-spBev! z4?roazMVViV9E8KK3k*ltEp(bj!}--RlY+D6t$WMK=jpaU2U^uk%1sPCZGW=I~H^R zmpxzNGm9^PYvctWOOL!Bbb97l#ns&N`IZ3ZwOXKJAnWmH@<SoPOK9O2y5TX7YwC$> z3aap_Klt<ZK=O;Z7wY;^@hWxGMwa%nOYQU#P3TEq2k)g4fR;jl$|>1mPD+wJ<m1|Q zTq2ic)1i3jGU~uK*;0mtlmc3Wv`SdWTRM>>uv;MVxwA6)aV*icZrr9amDXRHT$Wph z4ra?KZOPMWUo_ES@D1?GL=2M`q|JeRXiOhHa!5e;KG{b`qcejQD_=-F(x6*3cQ4n{ z(n&iM_xG*e+4_UKeH<T5V;r$Vi3u_Ta>RD;IBSKA7qS9H^9W#5-4=L6{f+=<;yMe^ zE7KUAFKKRtvxLe0#2@F`S8G;Smh1w@bpW7Lsyu%p&Prs<YqwOr#>?o0>^}GY;te~p z=b&t9ivE;o)ybByXRht2MVGK(GjP`DwtDAA707YRmtF(PcK0c43Z0yrU~l$+M*Wb& zsoa^Y062HJsfX35Uf=Wf=D<GEC==i;jcn$M58eNy2Gn6N`tGnnHf{baOQl7R6lmmV zK$}Wsifztjm)F;%vZcqdY~3&Rk`_vmwEc9yR<zN|#qKZ~H^F|RCMhfsh!@C}GAioM z*&r<*WmMcJBu5YQ?PpsRHk%IC#Xh~upX&cblBYYaZElyAEbeJdT=1=ZsSovyzL!J) z9`1az)vZ{;-w*oxH2ZPmW^aoGT`EmIW>TQZ;VA*myR-mCznLYAXjGfeLYhRxU7Ol9 zt-&RsFHKY%@wyg_-29XlnD!+k$Q;KmD^k3;<&q}JEe)@-iwhR^a9ag951k9pq)wIe z6o1ts#bu+rroW%CV4*ae7g_;nY)6YFXdVN>NmQIX1=eB=awFhaeb5%|&|xLt0cY8Z z_I6d`jBGI}W#UU2(+-C0g|-#Id6&$F6fRoS+BK?YO)d@jq5T;tIyUavtE8ykgb(Dl zt69U!7YdWI{u3u!qRhsyNW~b1`W$J1D|H1>C^7ZU%dWHxwBd5kO&TR2ox_L)OsSvn z!xS}v7AhKeD*`iVp`=aG8t#9m4&VHEg(e?ccj}<Qd>RMI?z8?xBE_UUN;*ImlpJ|& zShSQ?%U{UDQg(}EYGR`_xiK}8Pvd}UG9Qvb?H!J@4?bS|izTS-b5hk70)QV^8%)2s zSG*}&te9&YQ|@jeM2!r6Hy}Rz)v}Vz*ND%jv@1pSe)j<yA4-rP9hj(zNJjO$0M4|B z$g<0`+pE>UKSnq2HgDc2z<HNs=&&@-^QlY<DLt5?5QyZdv?_D8muNWC((7SLwQUCv z9I}n;*GXQJG@cURs4a`g>gm%ecO5e7Ah~42+Ziz_XQDnyT6mY)f%7Ic)V6wEgDdA< z7!xRQ95N8|L)y`J!9hHP3NQX0excb5CE0U-0t+ZEl}&I_DA++8uMb}II`{ybQ6Oi6 zUg&)U^58G<HF%C^0Y5zA3+G9Mbm)TuV61ma#M^uMW3kc?F7>c_uDU|_mj->|KqJv~ zZQDQ^s@kgWengYn$Y4JgKpc7{ka8g<$%p=;q+?g|#6tBcd;Yzz1S$tp4P~Xp+_7bK z0n5_(_Xtwh+O4wfIq^H&6Vqy~Rk4_LX{9zo;i;3*@X>_tZ1GRqJ<W?t=CQ8VR@E3K z$ToR9A+U1D*v0mXw3KnxD&)6LEn=FVx<@8n88%;O1Uh=&e7O}bqyt<Px4zu$M!!+t zdRVliAHAiHWZiFVo6J4E@$o|SRkY7q5UeUK=7!}po>ChSD~JWlw%GU?tCZi<9_Z%g zms+igMf{q&dHnck>pNm@oDWymuV_tlcxo!mS1{9ZPHo0M0q+9_exf=RXl&Q6iCtd1 zveV}giJrxaf3lB9ed)K@aBh8FSeW$1Lw`z{04GN-CS%-+R&Rs!_O!sV7hf7?d$eGS zYa)6YNh8^JQ2?sR?N=QiFmkFu{r~{CYkHYoUZu3Zi@v`1LjxE1E%MT;kxVW*mjc<& zLdhYEDD-VXw2>AZH7fj37beeHVRM(R^*7Mb`0@%?r&=il-`fCwF{AOtH_PLuHt>8? zlPXqHrca`FXFq`R_{AQN1J2C^ILjde`u1zr@b@b{ac1dx_;-KqS2TIu)UQ*lHjF$V z1H=+y;@2hFV+;Pcl-UU_LX4Tc*0q><QmtHmYgDbInisV%n!8}C2(v0<rvJceE3d<y z+iRgm9gJ5jWGmhuA!o5<R%vl!)Z~R8rlbzN?b`Z^_&cY`{UxW$?De6Oy&Q@2Spm+G ze7O7)w*toV;}?VvPl(QAlRp+0-u?J1UmPIpZ8tQs{CRRXEqpnED~3{@v^~^c<lo1a z8e@hwiFjj~VT_><V{_&Wm~cy>Up^e@PCtjtoM4=$^7r^-@(|=nX=rZg${I4wc1q(P z!03}2r_fF@)<V<SO>fb$$)QvcOI`U2?Mq-l4ER>Qd>o-)@)*TISjr=k4P{FGRH*ON z;gsH|rgWu(me<~Z_kZdXJ=OApoY;85E&|R8Fh%ERJooB5apf4Ek*@~Yrr)h&8><l8 z<;C;gx(%DR*$ub!^v3|JuRimT-P7xNTmI88zxC?(IRpZ}{8Ue?Rjs1#e@*Zr*_7__ z;B)S;RkMcnZ120p%kzHzZvp2SbHBBRpMKrr#eOY-*Tk=8`F--QtO7sB4exJr7A~>p zUVryjX-EFTVTDzr+xRb<&`;@5!*3RZg`W6}*ace7e|!CD2mPK^+&F;5`?`0G`7nD? zhp2rn4Nx5Ed^v57O^E@}aZj;}Cm*`Q+O%vOfBdh6jYo0;7u3}cMvb#UAAaWJ?B5H* z`1jVEueTmu+W9y*^7H7kZ`jwfLthX*Oa6;3XKXtERX1zicg}khYJSf(y|S*o{N(-C zwA~$sb};U{X`lLBKl1<I1~@+?d7UvQj5l6WoodqX`~t(2>2vL|7v6T#+qJsd9)IBW zC>wwHd)Fh++X5Z@iF^CS-qxT_jX(4oz4&(m&eY@NrZj#FqDN`|JAU1y#-hHj`u5Lk z0+kV3K*tD#p+QB{l17f-u+1NE75kx_04oy`>O}Twvcx@;NVd)r7n-gB!E`!z4-Z<o z5Y6Fv)BiTm8x1-l;siXR<D#?bE$!blfPr%F-qg<aX+oW=crm+k*l>TgL4fn{2k!HU z2&N~X5ui3>=InOACYQKF0-VR{P&eY=v}uzyzWsKq->sX!oA%b5wr$}8%Ovf^?|)b# zQx7Ku=;UyEk7)%kgS3+pwr%wa=^&gYsD4<Yz^!|=Jr@mU+=RZb*u2k2dj|+8&BVxo zFVVw+fOicWVOetJcE8_zFw_?4AfhC#9;MR6{K>z6Wocs?&QCYILV$B-*N%o?0M78W z`@4gzV7Z{x*Y}1tc2tu~I@4P1ZnUdz?e6hT>i3pS{pbUqNCSA%pip*{MK*OH1&S4S zz;FNF1P4+9TCu}@LW9;e(gdyCxQWN}>0`ZZ<Bv;KUP&5Y>p;C&xkt8cueiCR!1FuY zZ_>U58!8}g$L1|QQA92PfHG(mjeJyY*1}r!e8By3XyD^9lNt=x;NxkP_ZdxQ*iw5u zy#RWZJ9bZxC~da=afl-}nR~qRj>oZl)+}k0KkengB$_-%c9yed&0={96|n6(jOds; z7PPYg%+bQ9)65}F@ZMv_dpwxb7}&j=%LH-?-43v`)rvo58gLew;T^y&04HSuNb%U` zpL={nHs_O1Z04|Gfffyv0BNC(!>yQT-Y0G7VzKSk^FIC5W(mB){0Iv(q|@p7=i?gA zf0LH+a@j;B@01(hFkN{@$yw6=eV#sXJAEqKXfa`*-cgp>b*L4)641zJ@D_n8&<X9h z>MgIa>w1R42ZOGmk3MSOfAy6wvXFQDq1j8i@CF$|4x)iauMa=6k~$0!_qFmpYvc&m zK15L1I*xxp>YJZ>+Afc2rmv7$f)P(W<@KAvDxfZn8>Us<EP+5CCW2@icbARzn#}@8 z{O0Yq32<Ji0jo5+RTmV*<%V*Nz-2V4Ar`*7R=Mb)9l;Dnw-;WDYd8ZqulwN#=Lr!3 zwlVN^8`#P-<?9O<nmm#h;$>h;Iglq75^#Xs+#?6R5Tyl)oNceN9E~)<fxw`8Do$z; zEHL(@4n|B!&;fn|P70LFFTgpAo7G62O2Cimmeel7WQmC|@}~(58o2<@CuELd+xnf- zU<4e?WBE#Cx9oY+TPgvo1XX4nOeI~krjge$5QmpZ0*(*J9<$0WMS3e-wx||%B)^({ zbu8V$@}>`M*P=aZZ0;^;kt;$>W1KmC)D9ooZ~ONgv7MWBXjhQ}mQNbaDJ}v?SNxtY zJX23dUwjh4{aD>w9Mnok+HVhk`i|`RX0goKnIsTKVNo3wzX8NMR%u~X3YH}Y_R^Pw zY{SM4niz|I)1rwMp6ZmTV7Jr@iw^r_&fw|sfAjp@QtvveTRwEcqbGl2v*t~6ty%4V zRZJnBt{v{M+BNEX+^-CH)|M_`qH<7q%FnQVA8MsOhwsi=viwK!Ot7umQO~^cq6~RB zRa~ngvq7}uhgH5EpLpEO4;+-XdIq&?>7>Dr)(!b5EV7VFVF?X?@~b@?Ak##+y;|g4 zyJf4=lID;4HV4$?5#Q9~bc&~Zu_EsGhqc=M^4VCgZ}bmLeje%4(dx_80j~e}FYU(- zo0LLGD@>e2-jP>tbEpe4f0bS|ve?9=1u}cJZEdCUhXsKTrq8nPe_7}ChJ_psa7{?q zV})dkH-|Kbb4r_`Pn))$<`#jx1GQU-i6`vgQ=?c3Yg?<9zyD(1xAyt`Z)J9+fB-{* z97-$Neop<;t;$}3G;suUKB@M2oA^O}r>{kmh}|AI<d+XX1-uDWNgS15b{gylRNcEr zlk*nVNdr_I?Z_t!7TGG9BT*`T?_s%7X*9XGg4L@K`p%DL%&>KmZ3moH?u;{H1bVs9 zUNWBPDZm*=yYtZK4`eejr%c(%B#c1MR05~~a#N-bzz@95BH*EA?f`!8K6%hST|Gx* zjV)HFa1l4D;hMovNAnO8^!Q6<%q8vSqJDi+b$ZM%KiJwG>Pz*PR||IRI!GfKy)u7k znUV?hHBp-Wqt-6<d?NN}jIoG(Nak~rv^6$QUd(vp@haiKw$e+jaR%w05&zF!q(Esz zhYkciqD7Pg+P!q<j2785q_!f(3TZJ#2QSNi0OKidU<#E->_Z*^aJOvQr~@&z^GP;j z^Xg#H{A|^v5mCA6wLFFVve@KM4+~>wFVdoo>ci?aDr1>ck=cbJ+9FJS0&r&S&9$mj z-X4Wg&85Rjb00nx*Km#|w~EbW1m-zF6#dc`a;<_v4sgi<XX2$D!|^_fk0$^u=Uo)m zU&J5#p@vE^M6F*ZG=z&nONtR@B^-Maqk~Lg-#AJ$iWF~QAp$C*xT!gkLF%2_S7P$m z;3Ihi2vWP_Pl;1J<M}{omwvx;13~So+Lu@dH}%AwLTgMwd@69i4?s42@V6d6`EkAw z1Wqc>FJ>&WDf52vC#8zyvIja{AwPjWZ;2EEWO0Dti-W$3o0@p!maC+_jMnN|+bRv_ zSBK5;IP%C=^Mf*VkwH6pJPoCz;7T7G(WmV759ivx#4s`K*|E0bK=wtLX!&mCb{jQi zg~wB_ST4KsMzurE4=wTuto~`kUVqoA<)sc-qs@zZYt(lRNOOJl<)y6U71+!TE|L>y zS-nvvIX+$B@36=F%KcYMR@Emfo>|{*unDtQd7#SWi&)3jbuE>~U0NM-c{`_efJMm7 zTXxwy?|dSemYsTO3_t(e-D>+;tR`p*0nV#_12{MGI0GGUBDm<VIof%R2=q|z#Onxf zo;7okjTt-BJy*WCsNK|}mfB45Qf1@786gy8^Ns`?IPz<slVGFyIf0cv?&78541n`| zkEee17~rgTR1;DSBBv|KbfC^_w7>K50G{+YDib3w44&k?BC_UnD_Xs3*mhTqKt9zl zM0Ii7o&z@Yi-n4kz&beZ>dJ0X16iSdZ~$K%aF%W7&P~q)&hW#X+8gJoXeC~Efyufj z9;GS20Ohf_vA$E!cq6~$Ex7mvFFfAEIuvuX%&#QH?0gr?pVitlsNiEr-`S+{X5oL= zz9btqF@VQK^5w8wudAniMfF2bIxy{grYuM!r1RbKbvAL<Qct?t#WGQKWf<4+nx+%F zapyy5x6Q8r=eF_}^An4oAmogv=i8W&SK{Id8itSmMy51&^GM|*QyQ1cltv)SeFZ?6 z$lwEjGrvLcD!xlX_nsexqupn*F_p$LZURFlrX+x>3z%b4pRaz0zVrlObu6whW((Aw zk$iYt#5=~}(r|XbSqflhw8-ONGq`}}wMtAhs=WblR{jIoL1xGyGKO*pv?1fV2-hkr zKxe}83=lo|S6fJ1?YvQ+L7S@gZo~P%z@&x<i#s%(UwZRB+Yr-&j9!q}R?QmOqxaqB z<Co}p^qU-Tu2i9n%f||V&DAPj?Aor3xmNzX)|RbW69w^k(fASlEPviy@n>B8Yk>2f zKRh%rIpEBkjNQ0(YgM&6HLJKr?96$Kygh}6TGcAql4YwbpT?@q8`t+;fzxI$lzF_c zv!z(!0ycj50KERnJ@oWzHgoQx__M51BB*>xIm@r{3p^$NjQN{3s%xK5`r7^d8Q`2R zPcApf(LyxTyS%z>6tMrr-)F=DQ?#<b9y7!>go!LU;QUv^#)-awiw`)gZpg^EPtszc zfxMx;j23I;Zqs7L-M4m#Ztbl>!)>8JPt1)(z;8B<eRId`hGWkc+s1#zp=sTrM=w<~ z>RE6Xmo4e`k&mgISNycrwZmI9sW16j;TrAu`fmoDCrp`X&u9S%hslfyBM1J<EDKui z1BQI;@9z<RZ|l^?um9|;&ui~UerCFt-#dix_rm@=0q4&rer+$PeZiG1R@gon^7^j; z|KCgh|MppmNn=Kz`?3F9uHnhxC?k_<2`In}cB%l0xIZGG46SAylM=u<v>F|R7RYl- z9RVN>8i#<UY$+uiTipR|D>c5_+C0_A!}B$7<ZzolWKay;4BEj=dRjj6s9oGJO#Jq5 z-zGcEZ5`;zTcV`(95vd*Z(H`Gjp^M>VP)S_jV^R?oh?Tm>-BYLFp@N(`ckF<0HWEB zo3~J5>oR1pr4>NMitSe~Ja3D>`nyib-ly&EnFLm6av-m2^J}cx-S^A%#B7`V*6Xf8 zM4|w4G>G?qIyMeCpU`CZlV={cH8N{~Em`u5#^*%>o7+D5jFqktCg(>401fWm)eg(V z2%5Cme0^^E%sAlukhWN32O01@9MnUnn!@gQZ>Rw0a-QdxTVHF(Wv_^iJB?_4Xw+w- zJF^3Dqn>))ew;na-%+_~U>H2qyRp4pdtXocMf83C;tO^#A;C4N0ZI0Wrp~Xv76+UM z-*cy}{qFntfYdeEr5Te`+n?#A(+SMDS6h=a2q?g9QW=aCAd@J76)it(2}Ao;H+8U< z4?b+E#VZ^d&QDx<m7QUbAi2S$!9|j*;{u1-p1ebvplB2Wwx*Y+VWzaQ11w;c&!aL$ zQM6J3U1ogrk$pFMjDrRMet?@CZda~W4e|OZr(^JgJ?+4*9g<B=1oX%I%(A8V?3Z6T zEdb5~Zo9=bzme;MvNsK&;npLS2Y5?4!+XF*{2<HDb6q#=(7~>aKwI&7^h+<<is>`l zU$94-QrklI+qL)KZ?&Zb964wJo<L#0pE~G0r=0}}268uHN4ZH8_wt@Vs+IF4L!ui1 zw0!M4*5QdK+*bIH)2G|WKF_#(K@Z?8GVNfO%9&rZoT;C@_xd2(Bh6!Esz!_EqWb}V zM}lKtf8D+oU`$>K<8kQP0bbQ3fM-Bh24C=!I$o~UWp?MAZ$(+MFZ#W0^T+BCMLlsK zSovxsGb7Dz>mK(r{E>%kqkv<02^b7*lpP1laIG&7&p^5Bv(H)8*y2b3yY95Dvf+$h z@(Ta)>%frcgn!g`%GVcq^h}=Od1?39<5n#eSHC-Z*y_cLT}Ig&PhJ4hgDDuvr&iR- ze|Bl1!Vk1eBXb+bHSxnEXn-CDyo7<@MY}Y$f-PzYFi~EZ1nEy6+(z9=*&^PtT?fwX zJ|)1phyddp0$9*A1~gU&ERb0l(EvN9l`kIXR$tQe5NNz@{T}TC(PY(fTfx$~Wd~Y= z`E$}%5|G2hl0#ORSg|GEJ9N><K>UQ#O*)ilyS9iw=h7)`QRM;6&U4nFKsl?OFSIAy zjwINJtEW3HXgHtI!DL4dACT?oW43$KIm=TZj}9=Ct;|$v^Bt(s;NEATKu`jl1t1ra zM(w?IZ}jq>zj}%FoAQOg&Wu{fQ+fibvE%7`{K=<)wfd!H7O7@a_y6HH<89{RIXYYc zz&y18&m5AYGuE@^jaH?201BtCSY%@tOi`VE$|n;^0`c#A{y{e-fSCs0hR^&?dAqaI zomRir6(0Aq{ho9C%wQ~;GiS3=13vWUfA#C8UJproc&{HEh?Z*_ElQ+DGf#3sQPJMh zmLhxn)vHp)dUxykSCi3p;{<!~t^U3s#e$~;&RsiM!<gBPH*{{m;$Jpsa;UUiNGNN` zkkX~i-7jz$`OKI}iyD$w-$trc4G!@ceE;2Xo6(O98DR;sosDCs61$o9Ytbryp@IT| zv#aa`O6Z{7oT~Sm)PKJD<rL2s3nbLk%Sx8A8|&8g@Z;w!w9n=)l$;1472wPym`Nsp zGX1M-ej_QG(E^H{()R5g+hl86*QAvZ0AIUPkSXLBpn&>KyP&B2Lp*E&O%$Cq%M`QT z(#jAi?miXZy=dJAue%O-y8J7w(|Xowm5?^}WugC_Ak!b;N`siKxqvo|TZo7<<DT6y zd9=uRTb0W^?tO=otj~ncT<aT?Ivm89S|C)aiv(6jptI_G7PY(0vzGBNyH6$AXKUx% zrVSgdc&U<>Pg>5jD}fJ6PX76$oNA^oWcgBM_Hc_1ZnEV&HoCSsi^)Zc6;nHuT5Yk$ z00Nbp=dEPvHEG68+qu%V9oD%D0%_3-O^{|c3lyg`InR+Jmzz`(%Tx{$6Nv|h;j-X! zMq9s5YsbOawBqksnN5><i+x&<Pc0BSW9D=+Ig>|=Qd+1@$yg5_Q4T5u(Tbc?<Ed-R z)wjvk{~?t}8ktSVr8>(8ANWH)Q>cAPNgJh)Gg)ELc;2^Hfb-9*H9ow^a^%Wl`DJ%8 zozgs`@=w985XImCkr!Y}0nVocIJ4sk4QD_*QV7obj_5|eyb2WX5CL!@&~xM}<iX$Q zF{SSBgHN@QN;e+2d%%<UM|z?y_9&i)_~LKKUhsl<ccd34SG+j?G9;^TJo4w^hkMT# zjK$$GmSA`u#@iknZ7+^MU@z)J9IR1&;@KzCnw&CsIWMeKk-YZAo!9zv;_>=L8ft@` zdgAc3@WKTtcy9eFJi<)JbXylY+^x@DP2C(q@Q3GE1RjxW4=!D2qrME9scmE?;mTS9 z9F^w0r5o&%DM1UgpcY-TXOVq*&x(H$U6j1cD;<@Yg3vx)f91tizgjWR17JPn@xuFa z<VSs=+=CqjNJ}$z+wMd5+VFY)EO+({_IS5?l0V%ldfKC2Z%vnsN%27GK7B_c)d{?Y zw5gBoAV~ioe6hrq#5A#cb**oO^Xcpv@#>=qOKs`u9sh^A^8l~1Xx{#WUP4W1fzXRo zu_B^$MG+M%Dhf8#*NO#DQ55WAFJJ*HqF@&hMG$N#Afh5j@1YY29RlRLf3weX2nZ<e z-|M?xH#z4#Wy|dBY`b@M*1guMszZ3`0~}bS^C2uT5m%BeS-L{)>L&Nwv&UtYmR2V4 zRPUxt25|n=-=X2$v198H){~DUI1~j@xeKJJ28Lwxc$dBU>c=*D%1nP>t7>`QG2`B2 zI-;<6Sh8ZRc5ns|zsKdLNuyOeFNjobFAe9T>$-+>R5;G}K#C;B>q2}-NMu>}d_>Wl zMJsI3`(N`yHoTLqN0)X^KY%j;B7TD$23Z{O?e8|_k0tKEbGsw0nidvVFh^e2ZP;o9 zW0M*H&ZjnZRuCQzxompKkO#N9OdA516+ZXEj;Bf5yptnD2o;g8`|u`w<7bN$VbE;O z+_;TfKPd3LR<i4@GKX!LdT>xbi8=Bvdt&HU?yqFABG&!llhp17(9`>*D77%wl{Y0b z=7-;H{G=HkrcKiZ*6P@L3Ho9xa?^>&M+fiGaPFr=1AT{u$B@X4=OYf!D=!-N!<S@l z`g|MlRj8k3Q%cxX=eJe=6v?mqQ)rd5mo+?7dF-X(%sriorzCz${`1fuYJQNvfOZC} zZ%xtyj7q?VC@Ah^t0SU(c6qrdeu&bwmk7yu8y24XP7R&s!#E&Yhi>oC7#m*GhqB`< zmRaAa=roWm+P;V;(at;sf8Kvl4*GKq=X@-@%DXC&=RtI^GY)yfq3q%L(R(+kar*iG z{I9-{ho~wY+^al!9XPnJgTAF5`dZqeZ@)J}rZz&|j{`Jrc$f|+yF&nH(fE=7<_4U3 zz@dYEdtL7!WNwdWYu@+Rz=ZjQ7RMiLPd#`?ZZ8fvqXmfr<i5Apb-JSL{E^)y4Pxy7 z;)15}5#fctm&(TR=@(t=_xsv#&J8%@;nE8_+D%tq;(qyh?VXS8=@;Kj++$nzm8b8M z8P|YAV9w&qORi76|7OJAHgLb5@RN1#{ZQgPATa=aZacY{9=YqGXY99J!27`fXCfmG zG_qqC+u~)8h(lxgxTC{jS#H3YcZU)d|9{6}lHsDOdN>XPj`z$%y{&1KejFZN+;aCL zUI*~=_DhdhO)dQAb|b(1TINxn@keMhquKo5IQr{LuD#u+&y<3T940jG>8UxIWGi;m ziJ|X}RQV2Zy5r~ntAI16TyE|2nBxGnGf&*t^G^o?KKA@;Zn}lM{9W+)(Pv+=q3@6M z?EhVm`kw-vS%f(EvYTasR`X7^>2D5r$m$<fGcJmM{MSut%pUZj11M-<B8ZsCU?K}h zga#p6tLwDYm&yb%>YacZbXr>`t~=y6N1Ydd4cd`_uj{3i#G!3G1LOf{yK2BoRwdGs zBqy0mm)f*(V{DTq+$ChYw|?t3vQ1nuk;$QV^spJ<eC>c5rX{X?X|TUr^~VhRxX)c~ z@_`2kE-qhz!glMZQGShv^RVl#6BE%=2or%yGIMa+op<_szUKb;qfP&MoS&9kre;m6 z-uOrXoQ?fGaen&vBQ|No$DtFWgVpD@_p#wz!u?>{qsB4EipKG_L?!?@_#m}PRcq9? zUBV9@M?TTtrV88+9X5b{e!KO9j}tbW?>o7z^BZ1~6*^sLzD8yYVv`zAUf4-|S}pL7 zE$*^4Cvyzv^xBh`SwH?@zY26-r!CSol!xk#_0geyIP&uTgZJA6Y3Npvi3v2J*9&Yt z@7}&vuSHAu^YZoA*{n$uy?p6JI4}}TFtpUsxMcz2nA6YHVRyaVKVMr^zQ24q+Ey)? z?;w2Th7IkorpMdjY13o|psEAnTLjqNB@Ji5Wj+9y`B|;jWMI2G{VZu{GT7K9*-O#3 z^<r8j=j83p0;;RkscSdB@tSKDlHS@SOKjR$tt2j7C@u6-R!w=VE7KbeAn5(XPd>JH z9=OjnURfLfG|w+t>?>_@T*mC#_ShvC`g`bLAq1_rU7En7C5yZ>pdmiW8nYq*p2$5P z$_K6McoBd&XA8`jDLL9G87`+hH)z$$f9J_=aLuDb<2wGWx9qDygT4GQD?;rPjQaop zKmbWZK~%jtUx4zF?KCi#dtJc&?8%b@5HCL8H24*nVW{r!_<E`PO}0QLMdG>yC<?vQ zHE0H;1|;RMMnEtQ!NWc_1Fxp-JGeGA`N5$foT&vEI)wOHJecE`ZQ2iYx!6Hj4sZlW zC-2DJP0tUsngZ2u$P^|@kQwBq&T+?Cr8;%|9bePNkGC%e3~>4|PqI;R5NnTPN`<<> zAPR?OLKn&65p7TMd)IKDKHcj9rYmsJM!Q3M1c(D@OniieKH3+6Vaoj?X;~i`#r4c} z|FLNkCOGH~sLVoHmS_RYB6SwY(5!S5B%+CQ0w}%J>!NE-=so%69lwDe*_M7;dn<R! z(TYcHjN<bANTzqm-s;Y6n=E5VmJapWW|eAI6=0kqjZO`Gb9RVd0PX_4h!a%Qi$=q6 z_#sdka~#VStWrI|#7Bt$IG5K!N~8jCrTUM#2nOz$@qm}K87f@|oHuV=ZyAfWh)&r{ zuaWM6Gjofy<PtjMEC9apY@f`TWZy5It~OkUy>6FDmQ7jGsFz*G75TMzS6rqs3R`xL zG{QyiZfs98Y**vs;FIXCRX)x7bi9(N?2Dhimo4IVg`*eN;d%nCWQt?A=T!+y)&S~H zZrseSZWk6}29A8kM*ko?((ACpoKNXt8*!(VELPZ_yP>z6)gj*B=FPH3HG*8d`Pm0H z<fC_#N7+{w;EcHd7T1_K-FoG9*0xzog4pf-@3l$VtpS*sqW0^(=U?^b^Rx?M=Dc}c zFT&(RkCi2NE{Y+4%A_9U*lQnrU<;&`yG4f<GO0pF&~WB0?KAe@0RrGXW^&p#ZEC%* z>gLf+p7y)8V6WGE^&65=uWJ;X9CE~S2le!bg`TJ1dRvP`*$yPKUANbjU9D}C(0)Ad z>QI~L+aTrHqhRt)c_WKEy|3j-ks`@%A02J{U{)cIy>Z8Fu1!t4*FN>UVKbU22uC{s z=v=0JIhAz@Zwv45e6gj8XY<vMJo52-E^Fjb)LPS8^{jJ?Rzzj*jsM!-9yi`nD(LVJ zfw16V$Rzeokw?-%P6FU86G7@jIN*+V#WnauyBS;V;*PVM=kN&LgnFSLwZ$xcHK<b2 zZol}vM0+({VDp$?r};f)5GME3g-|z`h}Kn}t~oVK2$t$F%x7f>JCC%K@rza#eJJ$_ z02zR{Ma|mQqG}D#+iV?(_uSZ#RwgY)AZ~F1&S*HZ%SH6*14vCgC3F@;htfedSIAVv zTYvl@lM@+Mt9ESxP15{UxqBIVSt)A9A>w<7Vzojas7J$BO_MhKdbg(y9W`s$@;(?) zAzOXo(M8g%YJo7`n6Y)W&DgdE+)(d!Nn?DGcD7`x9%w)>;J2hS)CtEz4<;16?eb*N zHe(T0V>Z>bb+V_rSen=c3v%eHOj0p<llhFDvPF-XA7lwycPb9#Tq73Uv-={+mdS=Q zyH1K}(YvJVJr)-r51^;sM7%)@T(TknIgfU7gz{9JIuM#&0!tRmmx+>sqP2uT=TcgL z;}BidUz5D@2XG|50$isEcq*qsaPeezjs?KktEi}<{f{bwe&zf{{8smRPx&H8$W?HW zZ17m`;u!V^IMWP=zKMDo1y7`b)QAR;RuBDs@N_`HS>6cl?Yn;6H_w!ix7#GhLw%fX zT{v(?L5HYC4=+O)&%UTo?H8dUMEw7K&QfVYhDl2S$<b4Hc9tz=#*={u4o=IjQ=dqW z{!Hmcj-<FHDHeuqe&{_-1b14A<U;mP_YMhPqAsF~D?*tq7f{^yh0px@==zoI^0Tzq zBiVU-)XxH=7x?o-`D%7V6+7=FDH|vbctL{S|GLD6fBCydQ?Gg%yXKr@q+vSMewnr0 zpIvlHLu=B2`GayHv0Jn}%bs}iM}K!zy)-xF;qM}<q203&L-qgd&kJqX=fAoC3r=Zd z(7-t9ftSb2oW~}AekfmEyPRQ19Dzo4NGCVo+!Da~tTrJ!l1FBp7+vc($bqgUfN&U1 zXO~6Q$$s|_l8K?rLm|ceb~)ojYh162r$xrG=lj;D6Z~ECeF0}Z4f0BR0zuUA*u~Gd zPtswPf7qvA|LQM~IIN0YaPl$o%OB&CKLgIc%$7#r_-XFH^C?FOaF&Tb#$zgH4h<Zz zFW?LVJn`H#@KAEf3-vqRABx7@fHQSC)MEmBtLD7)fO_On#y9%iu7$aGzn*QY)`u}? zYRSTOzQAVcQLM2XKv4BL9C4~L>px_y>c}o1L-y|0!N=b`r`+HT&dXMp+`aetM7QJ2 z^K;uZvBu(8oGa)_go<zUY+t}RiZ+g2KD<`@ufE**&WY%HgY0TQKXg<WTZpbJ&uc3! z(XeyI``gGL?Fj9O7q{9TpEtupl?~%J?+fI`d7-`<Ghz9p>CXqidAHhf`U1uP4mcA| z;gKJ&0sImlazRr5s|)_A;=6<+=wj#QjWXFM(~gXt^a+47L@F-L)jR;Vxd3PCOk76Z zM}to&Rj`b_xd3O{TW=FJcW`rI@)P${lv#1j?K}L#fU_$K?4cUU59mC1Fo%l+xIbi@ z_odf|*@THdCw!o>JNW7Q6Zc#=;Cy*^e?}e$3#i54{v75ey7zuK@d_~Vuv*m;_h>j@ zb6a1(cfh$Pfb$*)V7oWq9Iyv`EM3l_fqxA+m(_S;#LxkIX;;pgyTC5!c3UDLOb)a- zKH3!!Jw4~rn>?@Fe*EThR=HAzg#S)g-fFYwE%f^nk2^|0>>kV{;Yk+&Zs%Qob3zOF zV1V-x4eQz~&+N@>;sVUYgai&?|BO>w`E_o<`B1}p1PA(3W1)X{-FrV`0HQd|IAG3U zf9|dKKDGYOz3Q*fB7gqTyY}+-sTK|X3BVaX+<ey~9yhZ0+Ozjtqy5;9#sgq0plj^@ z7XjyqvfF$^uLlyq_;s>{-R+WdW0DiUuMhj!o*ejw-=p0Ofc#gkC+1AXg?{+{J8%43 zn&kf!;C!_fk*M1^Os(9|t+RycAdSyoWoCcx<H3yHC5?FR-JIzIo)v(z-R&;}SOstm zyU1a3ie?}!AOId99oH$^Zb}$BBDL6lC|s<?2=IeHw4G`2w+e6q#3`fgq8<D6v$T5k z_ea)V&wd^Gsf~U1X>~XOTq>Sk$*z54sQX#^+pqS)J-r>!<^doST9iz1dwl+-`vGu% zu2TRv%F9+Wd0HmB%dNXzZ6|cO)H^5lxSuah&V8@%Jq{!j4p53tiV5VcABIB%3HIn2 z0)6l9=b-a`qVX^jhYz<opO4b&;Rb1<$?OOkliF@~&6`85p!kX%(uX^=cQDaGwCr%W z8y(K&&kt~$*TjuUjV#$+bggp%AL`1j#l>B%`9+=oA}`zQy@&3%-^Pwrr@q_DrIhis zD67+CR^hM{n>*<PuI?s#zQ1WgSlkB~0MZO100zi6CL7SK>?rN!rf2Wb-rYCf*qI(E z(;K(EJya$kWY1gR-W{!5dzzFJped8U+#ebw^3HqsjrKD9#{9=ot=n3=8?R3sBDrsR z@%`6B-m=eMd_f(DY%fdxNC#OiRj!<9dE31KkUr71vjae+k3Y0zi%NqH-mn#t^jU17 z%3<pou-)ZbgD3`P<zz?nqP~5tY?Z2U(tG_9?;CgDt+Fj_7xoT~`S_u4*_Q)fOvo~W zu#5WjwWA_HWN4qe?GM>QB~8-5?ad*UQjv*Ma070<L5D+5@ca-zbO2&G;4J#k!sb~C znXv&#XK?_{?fL@ayY+v}!IC(xzxv%O5UQs@bLuPnBR$dryg+OH@`oR`y2mv=Xf!`b z-rto!IzxbQG=i}=jrJyS7K+TCP{zn1yw7b?qyH6`*+OYX6P|h<w@CnVg;f_BSVAAP zF&M`24ltQ==g`1o+67?su`92z=~|2dkS-~C1T;jxoQH~sFuIA#U5EPV8Vym>r7Xf= zRKsP(&pm15hrxG+uBTb*NeryQgp%=k4zjaT8sa-P*^));q}92_D%GfNDKZ%WxPyIX z8MRdiO=1YC31qN$s`!1>y;a)%+Sa6ll(J-wW9!yrORJeGz#6-mA+H47130TC5I7J% zvems!HsDo;84G0=X?s2^Q?ab_EG-eV4i)~2<4&=|(`vvnnVZ;Y{l~s-OV_agv0Yjv zIxu#<Of9V1WhF`pa4ua$_>+KU&=q|Eg?y4OG61#mX@EYkYhUprk1bif%&va?KKUzX zB~r8~DGg_UYLH0RGE_ftZF{v>^}}HC_E#Q~X4GuU%H%A7yprAG0;`mc0QBaEH?{8P zT;?>!U)yB@;*vhsOCuLKg1=1if?e-?0up;(ajl)ytc82;*}tDn`W3*Lk`b`312nJ= zKXv-=c4^OB9O%riEyid7)0cV0^U0R#6~J0F5hAaEz@&$!3?FRlGC@QZ98gpYfQV=| zRo9_*Lv)}f?xnYf+rT03sP4$Np)`k?G$BjKJnbm;$$>d(XCsT0pKAyUNM}-er_MQO zcfxTV*S!N?wI8NQD@y*thkVgmNM<xK#H0dunA6BFEu;L>#$~YyVD#}DuCZF`J8=)a zIn*Z4oE6ejd2sMA3sa@b$aI9Z8Pc8%x~aR%_gw81x&Pg_JUO(uh2L1SIt{IB+c1!Q zZ`?Q=qCTahfKKp8P2&U_p!u$AzC;k*1#p&N%ZyUCYz?pU2`G~~c#=<b)oqf?U*HQI z57$T<b?&grl>|1Q@BGp$`{)O0y?;N^We$F_eKr7)d)VUxCe=e0u8OerUGC{opW9+B zf|C&das_e%0g=&gzNN)UR$BbS4gc{w8$WxROf{8tlNyE958(%(IxHRlDCoS3{DrJz zN-YnweEUWlBEWgs(#2M@R&6UUGbWU4?7SV(O@8sCeR6ew4A}YBvR^bVSnuFJ8s?Q{ z-UJ)mlpTwM4GN}O?E>0qAUAt^rcK|zRt(}m;~bkmca9eFveYIPkfw2p*ICcImj(+m z@RL8}mG~rQs%xv4ueQ0fW@~a?SZ23$h!-|_wE!lOj>^v^+{=n`!PF1KJWO){RC8WH zN-E|?r2Vb7T%xNKl#b+jm-0twsb_osUBg=GZpf6GphXK+&x=}W*^=HCvUmeR%>k(F z`f`Xs^@9GknhL6#im5~dI6HXcT%hPeuA*B6CZriX@CiPwSDl9b*u~``auvH%?0MvU z@V2MCXy28*^1$2hK8}jtL|e?uT%M5qI89HF<Q2ew{F}6cgHv8r{Jp61fqs-A@x*|$ z9znAQkGcQ{Tht~~M@Vm%?4);p;LU`6++!M4vuiJE<7oq$0yyK>X;In4E^ud0zQc3n zPGN3(aF}Z;mMK-#?!AtBAIjKwtx&I(Zxxlh<vKvE@4x^!A5|~it~{rS)AiQKDfa!; zh3@Cbx@q!HTGZ~?1<u5G{PLuN4)tquY>ns+x<!)&t>4REOJg@^pJL~E$Y;NKI%qKW zzN)4A1jX+CXdXAE@nmG%xoM+x>wK#0Lc8pc6UdKcHRR>nDGThK2yi~Xoy<ZUS;foe z{+GsSC*)>J)?s&t$vl=z4{|Db_p+z_`9v<hI->DmR<B-YA4qHRPrut+Z++^%TDCmK z&W-?QU!L3FB#$`Bk3#U;&4frM?iJv?TK1chb?9oXYUN$diQnaoGRj3qDBtklaG3+C zU$c_Og|Eo~&Lb!I%N7Eh&uDXW$Oi)MF4P~F8<h%=!yEBUH-Lwv_4QAG*vLq`{^+_@ z?K}a_yU}iDyrMFrIPi}gQa@(QUv9%A+s6sOnFdCFGPV0+U~I!V)^JuLah-xJ+L_qx zROH}}F=Yu84I<RRX2pr4r1!Y!T0b6>=*kwI?|nPhGS+T#ZzYopTBp`^jKdU}a|JL{ za;wE)#vQH|E1tjf@q~o^@=m8TvHChllGN}Y>NB??b;h8NzC1$XbB&ASx}Dd?DyOCT zHDAFOv<3QNpmHx8&NrUt@xgb>(03>(kAXi57s-*!6n>O8rZncs+zYO`4ySB&TmxN^ zMl2~2e-%$s)Smd*TD&D*#yZ}9c)e0E@dKO9%%3nVlUGV9C=+F?j&i_awg7m-FrM|? zP)1QX5Jg;;ZdX2juCPfOQ|hIZkG9B;^A^A6-c4<KzLZbqVF|j4jGU5hwMCI!(AS1t zI_guT+{LaP9K7(f6(_ib%e7eGi=0ZIaK$y}>+lbo)QHPbN&KaQ9Wj3n>RJBYc;`cV zKH9#I--qwMS@vX`C4vDspBve5Zr`@KJ<$86#Jl}n04T@c(>(%|J4%x|cK<&B=e8}H zTK{`*i<9(UFsCN%F7Rv0@5j&ImfVH%j6GhVgB5@NP2*#^+<-H?uA826k+(U#8#U}j z!_35i+~;Gzll|Q%{q?~B=bNwTVqH3&`KM?wOYw#PM;r$Wp5CsdU*`s#4>hbuaG)<_ zH+t9hoGZg2i{cGtG!Et_O!~!vQw|0EX2k1zdHtsV=jU|z;-EL*_qbW0=<6EsdnJ{) zLEg{qDy6!`8UE~l4RFTh`PH}FE9Do>-Q_MkyS-~K`^`RIW3*c!wn@%{L%-YiXy5PS zHF0~{4R^Wu7#^^Yab%;qiFXIO_$L78_eXqb_dWiCCxNE>+b{Lk{E>xJTJ3+(<!bnn zJ{dkNXJY?{y|D%iMPr%9J6RwcpbMIf0LOr?3>IUsCN(A1R<F^PPEA;uIOdU{0}RFB zP}sK4L4*QT)wlx$alK9xq+`#!z?z=dNx*C2KjmtNfa-BC4z#HwKCvQt&*TCv$5NVz zbsHQi$HJed*vJR_d8Y<_^5R?J^J>y`$C$4?P5|e}&g|geVHs&pV`mmkOY&5u(c#we z+Uu=sbq#0<9Jwtrd9i%fO#AN5*KF=DQ~fEO5E|ZezyOln-}@+`y?j^m;~c;`t^2Lk z_~cXf0`@j(oAaoro^&nh6q$9v)@IiFEKiR?Qm>CkxJeBF=lj~7<iH%A^mYNSVQ{0B z=m7&0fb$a<$d+}+QXl*j)+7(G2mmj=UOhWoW=Ja3sJT~OHY+bnXU?$kZ@zA;=Fit; zkwJj$5(_lJ-ZGl(=j(8_+RaYzd_H&86}I@--`tD>EZHbfjsXMOzLY(*!2`@UG;Gz{ z+FyTzCCh9|?8wI--+W`AKl{Awz^=63pN(`rVN#>74sb&gjR`e!;fofMX(sW=1s|T{ zNGD#nD6B2)$tt&^(o8+|hU=}Cv}j{(X8i6@m=$y8*bmY~oH}NV(+5CI$AlaLcBWQL zvzy-<ig)p2ragT{S0At-%U-S2*!f|V%9{_8B&&d#3`Wq@-zKnB1p;Q`@sYm9r*`(O zx5y-h?EL8-hyNu4v`4@Cs{K6XOKW!4S#HmmcjJc+wXrY0<e&>+Fy(vk{rB0C(V>B_ z^z3PKf12!kfre%s&$6>*f1LU;N9G`2l!i0BCtt`T4h;h82DHYYEcFx+jDdDFX`5g1 z*y9e6d4Rw9MS0zM@<|~crAeoqJ6#5vT?Duv(WdR6Vx;33uZ4!sUwqMldT0T}5(72w z;D9q}W2=1fNe-CM$J?FBb63TA>?!R%&L^+xX7jYD6zbegAJ|f!*qx;g#$Y&dswAEF z$WT1NxcvSHa@m9KW-})K=w<6bjsopaT?}%k1qY?g2ik+&shkDclQtg*6~%L|@#BM8 z#ld~qOHQ+twnxd2&v^7+GNl9YcFR1)?rZ_h3p1sKxY;UJ7vNm3thVbFRa-830&vbj z+gU?rP5$}Yslj%(=&&SAg=owBiY#fa=BT|bth!y=N|jOB?v{2mV3P6-fCN35R@g1A z59&AddWYm|n-&|EEz;qGI&`qOz@+>Iq#Z8Xsj4wD9Z=jJx=;%^0w!^5WJcqS??1FT ztL7-4?K)6wiw+#zD6<D8m8JmtBGNz9R{XsAgY3~4<rO%zU0Tt!Cq3HSXcbGQd0c}= zy=|ZW^sN?oil}aDP!He?PgG%Ql&xYt&bZn8nQUpYTr==y0pqekD~)OnGV_B!g+H0- zL|gLKbFR0eYaj0M^7YvdU)X?mUs3+lALwAAodC|#%EVq8o#btoU9E$Pn!EqopL{@o z^HiUlz@sPbxYv%X-^k_T{Ohl=#nRrTEecBJ2oMt))h`uedf5uvhP*s#8&uC^x?r0$ zs+shl<%(7=S~$pz*F{~^_HjrK6Vq?s2?t(e=-h#hS6*vd*)_z(Ozkc89$=XshlP_8 z#f!+aQKs_*9tB`XZI{xz`-W@n)Rv)b?)~IIfi_xzq3$E}{6`b8-2xysZ_?yUuAth> zpwR>1tnv~ja&zZSvRx`|L%BIimfCI4h67ia>}}P;Dkh#v$`%=BBQ8GaBs*J&`?_B( z&h{Dds?$o6v^p&tG`1^F4VsScj{VBsR6Ca}&1e=(e6d7;bE-@)tyJIRb3lcGO!$gf zhfHZ2^8%nU*7|nn35Lkg&fsWEnN%KDCEf12>|*s<VS@4L4?o%)W5#*dFyRNd2Ly<w zpb=k)W}ECmo_%~%JGVtkkMj@podd^?R_zgxD8LylC_Vtr$4axg(-C12ZKDn^>h;zj z+bN>Uq*n~Krq$oNHkaBUY&la7lzmC<s5&P_{jMCQp@z)-&Q`BjVAV9PC|kCi*UvCL z<^Vs9k<^dSMzl+=W`z+xxsR6pZnKvz)pN`P74idMkxl5romjMzmB~jNYWCx%3|ppl zMJvH-E0S#1AAiX1`UclF=HOVgjRWJUt6~Bg!}_D2Ky-Mgs%OiWF0&caeiJBO(#pzg z4kj+>i=mY|?cjoJG%J+CV3LCc1GV2eRBg5vEH-c0Bn|Egz90<fKzkHENowEKzN$US zQ5&aX)UWy|J#(#U9ekOh?cAwlw5?zA=?AVU{_Wxk{VOD+@k}4nSi5x^XnTIpa8|vc zj*24r@cih;tAgiBb%#HH&4a{+o<bPT{S%%R6s{;XSd{C12p9YZz&ZFQOzbUOE3E3h zr^y2%!mENJyNNV;Cr2G1*4Te2S$`$}Jk=lZN#+92^-l3nx8q$9-fAckk4t<FC>!B| zUqz(DP^a0D5dlCX_DegSU@eZRqj<a^lvhBOC=#O32c8m#Unjl-t&a}=!sahsLsa%i z_tRxhTZ?VVYoHO&l!d>x?|+$RZ;qJcH)pkJq_((@BGGu@r#UwKi=h2_-33joR^=4s z3C({m0mVROLdlX9ce;Rw{P9nw$v5t6X(4|w_7A^CuH*7M@1*+DNKSYEfxlXmRvUfW zldAKIt3qnB^}eEIM1RO{pdpG_alQV@&$1Q0)Z^~a^#nKB0lNl$IK_UQy<D1id9B~A z=c(^dAHWy^%}FtU1ws}aalzbyn4)klW!}g8D*?_jsgVnCJ`0l?9wx|R@I}4gN?-c- zI>DXF7eJ1K&IY~uskYV6^M0?-b!S=ufoj;Brd?vU*4|Epz)R<6ctdI=v46l>FPtSI zjF{(Pc^J!e44@G&K;p~=8TQIY-+Sa0QcGI*i%wD=s2`Fy0Ou(E7;qjtN#{rWGT;4o zJ|!}#f&442Oldg3@L`an3Jy3k27p>8%CF;of(QcO9KR#0q=&qRx{Z{%gVt~rZuOjd z<cfui55J#h3uT@Kmn^eC7qqNnC1h@hy6t8%;IFRf<Jp0vhD!H&?7Ls*NhardxEkqY zt?L;A{0Ia186^m};n{Dq7Tdd@|LA^c*ScRSjp(SI4_=`)eEeQvxcd{}tY=O;?==?F zm*2zjI6POlDbp9&Cu4u|>vAfat2;5aCmcS*ufHTLd_&;%l5?5hBXuW$vw*?WRmr6K zGR8t^Hs{qGD@oVvaNf?svH)j3VF#gPhCk@@1i2>7K%LJ464x5_dHnQI+P#Qkn`j}N z1Ic<vo_A}U8+ZjJ<RH)lk9~ZkU;4fPICBlH^tBoTi(he}FkYsQ(qn~FO!^|7;_7!g zbP%ZjHyqJ<lz-tjt}mfpAKY_bQ{d0Re3BDtI<}oZ`1DKndSs(|Ht4B-iD0<_=i6_( z(mHiKHSunL7Xx2?$6k8lU4Pa2+zv9Qa9P6J{|~_V!n04ao;O^cNRtcZpG{7_z@MdP zoI2+H!F#>u=0JcmHiR#{DgfB!v>^Za@R$A+HunR}3$(xB8h>;!!1;;$di}|i0)hSx z;C!fIbJO>yYvfN4G3U|dtSkQX`tLj#`{7_WcM<#jrvPWP<;Q<N*`vLu$F+9WX>H;p z_WRrC;pY;EMgA`V&a>w&a{1!mNgRs^fXKP~pxhanF?*g&oAmTY#~#_xUV7r*+^_e0 zeaiV)yG?Ljem?x*iz0CZ|5w0y#mY5yjuxZP><8m`bKpa6*WKff2U~Gs|JUDK4WAzx zIOXyF4k`lb0Ep2cV9S}o6hNRKdZa{QGS3QVumzZh#xN6aP8(;NJQF6u5y$G)s|611 z@JWel$trHbFJHdg0kWEP>sp-?np-}tD3;Rp(+w+D+NybTZ2rVawsv`jItpnJsqqIG zLPMICUBfNc=48uoiVowWu?Hjq#A2JLh5~Lbf)y}2A86-YaRJ8Ilm@7Bz)O>VK<rIo zcG_WwS!roruV1{#vIJ5ChLI*(qkvnaQABy7(*@YOarg&rK7umn)l^`U@<r!bSU^tY z`VGW`WSQ5PE<04RO{~>9I&FBx$|+_Kup7Ka2Q0?V;5icl0AMC>uBk}ps)R9dLW6=< zCJs{yObF4kL!&e13nns(N<%HJW^GGmJG3T~J7w;IxV8ygqtk~@_yJG}I8anu#7l@T z47M;ELH<Y+kQXx(81KihJJ$ek+0q!JJfWA#DFfW{RjRw`3=SmRkda}9^^9%68w5Du zFMrX(I^}t*myxfAOR%AVd@wKu07Q$6{DsAhY%h0Y$|p(6b0H0GC<Nr8fL7AWRH<qu zRbDF>Ewc5RsFN>Dx)7fHq6z6Vl0K7s4X$?Rz$FHN<beqx0JDSNDi44pX!3yvOjcT? zkE{UTdY;8!CFI-p8F0dPDk(OO%h#-_#g>9H+wi?`#B48D(tv(wi%l}1*~YeVCPDDo z2O-F>$`g87?AZ*+ulFo)Fo-KzwydpMxX@*pF!5x9IIw$7xEOqezgz>R0$8ytfe9HM zHhGBiUP53G`J#L=bKz!1lotFYKJvvi@(EA<AVK8?zK}lP8Cq>6r8$ndm-PDeRfgF% z_vfiP=x>^BR~{G?vT%YUo>()Pd&(Yr@2)j1nTJ;5re3PDc-b&u#7qcv8XK<ARa%P< z<ePZ;#qpdx!ZYeS`KRrI=kVV7totAvK_iv4C>xh2>YJ_!??8d#q&*={(%>C@r9FTq zCQO7QUfz|t=u}H-b(F3d8#9n*<f{6%OZ9Z87JL?GTE^1N0<Lr@TiG%K+LFaX@+q6i zl2wILS{htR4j9;@;VP(1a<oOZ$T#X>FM)Jx^Gch(gtUf>S{?zjv^BH=I|PL8V!&*& zd*?uccz{L`9|09BGqx+=vfGwcP_jVVg4PH5&arwG>R7j?mnv<Btik<~@vD6_^?h3` zduAC6HVbSnEs$K>-jii_I-hKt3#2<Tt)ZPz?Kt~*+GjRv<!n#4R+$?1pA)+&ZOOOj zdUNcD_QT@IY9o|QT5JJM4Jy{Pt|xY~;)RQOV#9v;$VN;aC5`IsmbID#M3bapEA3nX z+j$(Q&SNP>OWDAi9(4ck`szn+wTxBEebHt!fU`^rF!4jaD4(8}Unh{Gh5PUIWZ$6S ztO=0VYR5D<!XCT5ufJQNe(Ab<d)sQ+uusZI>ncBrKcDJ#k1PITCpT+uFAp1PLq~k% zljWe{EWlavgoZP15RS<bCOs%a*Rq#fF#Wl@(}mVGvfn;o%Fov8fk*t%9JFJR8)U7F z4$XV)j-IloS=R1*=2@Gpg}xw%$RZQ0yw<1t_13;sb5E=1!%x{aKWY1<!n?5OmvZEm zaA5%t&3tWdrA`2-iZpCn*N}GeVC~k40n8C!e`n9W{hn>zLEjh_|2P=$%+@WeN9T)N zzDe{C9SGZ9i-+V7M@~;Uwu#+z{<(fXbkvtN_|wnT7Zz22vdhYAGSKIeORTEe=GjY@ zSf9bK=>RC1^+7UJHvpXJ7myRu3j~Hqpl3_Z`KQ1D9%@#qXb;_Rl{CyW>6iOL2LwJb z?0uPG&?Hy=591Kpbjr=aRrw(v&$oWJD}NFv8!WR^1rSEL$@Ayf;BUr;u;LMu(s~su z+ttUnNwlq>&iL6rp7^c%NztJ)?0&)YL$Kk@g1X8Pyg`WpICm-^v`Ln3U1zUPmr1KN znU-F)s>Ua&o)6EIhzgq6B1rPsv}i@EQb0VA%h-}-FHaid8e%N+r>dRs#SqC;dVylr zOnz|+W}jxwvn^_C;Sq`fvt<(*ZDY({aR6^J3*&l6A4R|BfU|f{dzPbx96<r9KQfE4 zWSLFZZl+3=%UfEda#lj-Y|xA+W3)@u2Y^nOXvsMT`%!)@?$6N96YSSluUS?0pE;mX zZKHSseaLRkE?uk6V>Zaa3O&o-x=TR(8k;+NmZeoJ<LS~b=g_9A&E(Kj3eW9^Dju~` zR^5`VdfuY@1)Sl17!xZUIR}}bK({=h9tNjpGyrnJKT@nmgm;Psrf|=72rloDe}5lh z^DyBtmmyB^CGkk{1*a$CT@>A(_j*iviMV6`B8q2x;1vO>EAA9OfO8<6@{rKU3*ON3 zb0@Eq6%PR<cdGrp=lKt9$#NEUIOsN?bvpG}fzGw{o;1|YMd<`i5kaoFbV(nSU;U?E z*sw2tvavtT^0<zyTgk3GyD20nFVsDSbv|l4^41;J@5NElJZAT!7P-2#wAz(ryI3^M zS+d%meB&E`-ndSAyY$Q>J*=eC!}|;W%5lx*qJ`Dps$F)fpiLi7Q(tgqhuY73Ul^A- z(2bxaq>Xy_)h*QThw^0}5PS<L*Fl6!R|O#P{F576b7?Kdj{Yx-UBLP}dveHkUJmqi zk9I%R>43eXCd}30i8DRe+2ZF3O|(N(yBl)EUwFXECF26z+O=6S8KVUiUAvS)eB?MZ za7Zq|*=;!Ujwr}qBp30oKi6yc=wP!}i*{>#_xb2aHfn6xPT#SO4%m{}4#sATfoKbn z|0pV%>&dcIEjoKXm4?5IXmXPpk%qG$8Ym5C()QQ*h5uqeEHltZJT9VSP;^l~>vag} zgD;OFC+;piy_waO<~6m;!OAEu`l^jGPxajJZ#B1I>|)mWlp|zPg99cNuRd<W`Gbl6 zE&$H4ww@w^A#&Tb_(eWh00{XCVR;wEap9i$qTD#0@(gG27V;3KIpT-;Hb>=;D=gde zfX$_fYd4ygtwN|h4F@~Z@6zAUms3X=U+>a^zvK1G0-Y9l&N|VmtBnibCozUJcW6xf z;_$C*#TqTf%C&ECgdNwoR!D=ax#J?-IC~>n`wt$WgE_-_MSan5mh)UdU({YuHoHRs zg*a3;>$MR5{9B{NFCD-q*|@4x8!Mk0cFV-6gtGN06;~*0o-t<k#W25S9H+KOw2?03 zpgbBE=hZxdUv)Mb0|+Zn9_c?QXI2osb#)#SR4GEE$Ks`?x~4k-?&x)Rt8dN}(b$AI zc&}lM(?%P|ZnB6)Ax@`>zKVXCG7)d62Wkr_Kgx~yDugp$^L9tHAeS6`?U5n#`cQ`h z;C#Nv^H*Q6pU+>pLj|1oWbhy{izl==Gj+Dd#n%LYi^K57ee`M~P;S7vx6CY@dq%s& zyZv1NHUm22E;{El>v8?%32*;D0Ox(vB=OuD&IbaG4+J>Rkm-@m5pUAUm$i{^4@~4| ze;4a@zDcW&m-(xM0nV7^z&yvkE;rzOAd?!08g}0__PR&@^kB8doF|>z&0nFZT1R8E zzw55Kw3DS*ET8cHPXW$1-2R{+R7k}4q3wN2%S0OcyLjm7K{o8e(1-l50M6J4NBbB+ zAJ^)HW9{*NJ-nURUmkdtC1s2jXLR+~%oV<P_ocl6{e8nt)1jT0{O9(B|4E~VDgM81 zRQ|7k^EJ2ivmbv7iU61f!9+;H(U1I-E*{e=P8}NfZqDpMFF4>#8cZtC#svtX;YO>F zNiw1h7zF^sq?Sp?DjgV?D&Q9zfZjo=A?N+3jhlRnD9^B|>K%X@eZU+*A#CHOYC=YQ zD+Th>!O^LZPXI^&B03AeF}fz~M>E09r^!Bcp?Oan01fek8=#TSshGA-7uF;dU={nG zfVKe8$$CyYXk>ebsyt!Cl1VGtbp^Friv~2bqR~sdfM9@;q(hpx+cn89DqF+2JDMHi z6G_)v6TJX=`Lv?CK@AsRCw%ixOtb=w5Et}smKK#ymL-tIq!ES|D4;<YGy;$Y;FWTK z4`GlaO(W$AAPlgM>0_KOU;^caDG1&dQeKh;J}~$qEi{Gz`8H{Cx?ORixm#F+26fR+ zBV|I`#EXdmz)#AKJVS$PhU)!ht@2RzOo%CG(^gwRQZ%jeOJ34sx`c@hKqfp(65rSA z05jqtkMIJXk`J`v;RygFagtB+<C;bC$35l5sx)Otc@)vaA8;KI6`BdpA_s?4Y*X1e zNG?7mD}Ur6l%WPL(zbA!75&IyS!tVMpBV6;d{9oL4V}abpojcGGhk8y9c0MZhj-9L z8~{*+Wik(6MXbvWG$Gf7#~<M_(IB6$2?-AX=C&zM96-jjm1oEf`DD^aoq;Akahjxs zT*5!+q256Q<wJS%o<$T)X~26-qfn;Mfo3thM7A+20WUCff&8<ro&^<l06+&k!x0Dc z12~fh!h6}P4gxyk51ECQ7*r=bO{E|DsC4lIzW}?Db7TwudDIpV7xEVPt@6{t1d{>4 z_V7Gg^lkP!L*7csTnI9`L1hLANP9q?CC!*eq{Th_*QLh?-P8$}B|WDT063<sp_}r; zGrZ;*^bwvxA2PwfRhOPN>4dleoCO?SD8RY((Rvqvlik|tuH33#061sr&_L~&$dCqU zxil-0sx9c6_~pyXB9g#hO&(*gfJsB3NeSuDz}-7!^Lq7W0nW0wy;{cxRxT#M84YK| zj7fpyLbPGlA}J4pW)?BjE=Zd4uw7c86-xl-lN7eNfFW#KlXuCQvZf}_8kIlX&Z&F0 z+A9slBZn6H^7YFF5-he=8#67bV3H2aDQjhmm9}(gF&D`ncBH&G;T4;;YOa?r^qf(z zy|t;^GLFVpZCGmy*DSWJ*;}njO1f1|O;5a=y?nks@X-@4lRE@dtY3+}>l}e)0-OsA zC{vo43u)D`sol`AtB3pU*NOJPYtO3w2%MI=k}U!@vNh>U62B=w>eua8-e4ym-^%^> ze7uiM{B?@>t6P;nyuH0!ck9qP47jNiUwkv(rp=k@?P2|zwd~kNM_84#N**4wJlEcP zr_Eikz-4XQmc0RI<P4z*;{x?ilFOj2sXj^!e!c(WR<%-yYrWdSk4Ar~Ev<`H#|m46 z+O@5jY`d3I{lv}J^Q(2P01GQ#=e0E+jk!Lz++?Q-1jhAv=rQ|d(iE>tKIK#L5_5OR zwJ(@ShVltC1lXiMpp3&zZMWUf`C_}E{V5@Uz87XJv(XcNwAqUm3XCXeEp%vY(?*SK zk`C%Tww}Ngxfu%=+Ko>>tt-i-KIHgRnbNuC!V7d|_SR=#*q{+3Wv5>z6(o<>b?j(o zG;8MX_<DWRD0@S;^L<f6<p5y0N&O<cOIBMzog-#==pX<I;PkMPwmm-8<0dVLCWmMG zUZzD&KsmxY`x9@%{ey1|v1Qs-M81i0hYldxrmeY`cQ`|KI8RFWUL~8=)0QrhX8#6j zm|n$dm#?HU3(Q<A+mR2C{?JyfS*3a+Kv{K`zOs<E($iKmaRqqBJMB-&f<>%L`mrAO z;>~OA)!)YnRNpKRx01BR86%KG5hK5$Z|6~t6%jynda1*#P*nF8tzToK7yM@HWlknV zfHQ~39#%Nj8Wt%VX=RyB-LleVY+WPyhnead)K1OTjv5x=%4*>Pb4r+0k*NE`+qV(R zD*&c?c7YKxU8A;1RY-vIa%nhEx2o0Btzu<qDi>F~Bzx4@aaI%HG&)PXtzn#@HdK8q z?d~5lepkD{*=p-x5q50k7eE6~$f=J_b_<YUfT=bJ*(B`NP1|kdvXwSx=1i+nt)f+v zU3m_ggpq*Du6d>iXj54X7rt%j+lp9Pc7Z)MoIM3NirkPVr9q-{-X`jXWGTro!Pkvq zhu`=MW9U%ML4edZ1s~oAyPqg7{e*bjN0f-a3-y5a<SljqKJkajyY8Y_O5Gi|v4$TH zTz*MhL?P48r^vH|D|$tq9B_8R)V51zh}XB!tL=}SgEo5M8rKT5RtMJg8~BlI;Yvv( za#bs)+9e&DX#0Ku_QGQ)K$ju?>GPJ^*dJ6r^4qaBAfNhLwX^pQ94W;NjjiRH9$wAP zIq7gKQb=PvGNJ#KYc}byy&rASvP}2WuvVH~ci{<6f5_Kvd*Y3+1?YzN?V8rK_9xa+ z{h^PB2J)nKaOqkb^uZ*z;eW+hM;T^3LWcRt#drDta^gJu<m;Ipmans0*R|$HSMht= z668I^Y&L7r8hdWoM7XHFH;<j!vaYo}rmClnKc4@t1A2#yoGLIh<g;VzdOGy5hQ~+W zk+mt?9vb|W#zNU%k1xNljho8I(HMrpbnQsx=ezHx+J_&Fv%?$Lu?sr2^Kl$`i`}09 z=d)V-D`zE(H2mu(VoL}{cr=?CFK7qSE{(~shyKX(pNJlfLsf?^J*&Ajz*L5=W1bSp zcRE<`{m~QMPVfb%HT4Au=;1?s*cWi_*hV0V!X>!vekC93-xSL2mIG>1&yWvf6yNe@ zZ%MoTx7ka0;if*ip59c4E=t~1rzt;qwJd?n!$wb$ZS5cn_`Uel+<>#$x~wfWAOf7z zq~Y9E?{Og&+1dVekxiVwR82>cHE&$ij;U8saqDfwXkUCMJ^pwWJtq$GjC_y*2WREy z^GOSA`huXv4}jgNMQtmq!zaB7qagHgfLU#ID4S?8kJ(f7Zp`GFHbI)sxPod6FFW%@ zt5hM?c>}AEq1Qh7P6u$VbU&Cvxm5=^Vw)a{L`E*R=O!+P{)0bB0M7T`sDpEfRE}S7 z4?GAt*0VUjV)*MHf2(mvNVBC5Cu}WK8qN{|D}y1LkRIRg%iAMjQX9kgoo9>-;VXqm zn)%f~0W{~)oCU?0-2&g~ceZN$>~Sa@ra5%OzkWm9Bun?ASh>_Y`5_=qzuxuel5uSg z^Lg4iee&=drSH2wa>uCzkU<vdF<*xBvjn2Lz>XREZRqy$bAF31(Z^XUirB;WBBWyh zCGGSxJNdJ}`U-LWl`o}$N4Y4ce;Hs+<~kcYeuDiV(+6M|j|k-2*AXM~yi<z_O;5d0 zJj3)zUN<=r<}Yef-K54%9<*coHio9@!5oL{aj+b&&u#yaR%+XX_kSbcj0uEh?K?Yf z$jH~9ye{R#J!8s5=Aw%q1i)R}qo3dXn*e7BZgIw?!ZSA7QHR%aTisEX4*BPw0-T@H zL65J!{gJ2N`P{u1FZM@Nm+S6K9NPH5064E$wZ<;hSwd(6<C;iY`PoN$s}Ie;Kl1l_ z*6rqdY_fKw;;@N~ZR7*FeviG7*r9Mz3z?MZ8#M9{<UfA?e*v7?5kb1R+BK@!TQ58+ zyeG7s{*Z>{pLAis5TgF{{r7Sf%j^P<4kiFEnw2O`8ZJOQfG5B{I$l5;Iv_Ndab*NJ z10JG{$b^K+KN_=upL;Ze1-_}npiu-^Ln9}cF_6}iCge<*3n*>}J@xCrl^SUV71)Ue z*y6PKg3_$a%*?d)(v-pvCO24ZB`wl~UH~h!bY0Wa0l8pzx+H*=CTfHQ<OIY5R3o1F zm;8`d?x7QKI@lAI)`!v|{JmqwCjjUB+qDv(1YQ7=KyAMPuIZg0Dy5E(?Wf*J)0wJg zz!oq?xKVbT0j;pzO#I{>JH-H-q~n@uQMW`|@C9DcQ7V~4`2b4pP&@#?!~;-<_B2|d z0C|9^Xw)(pMT-axEip%$)oV4V-lQ-^tT-T}egW{{9oo9k>E$neVow?1m^k4lKnCUO z{8A?fpuSB5a6o7PP0}x^@Bo^eFbp`V;fHP5vdL*852OQs>3>-OpsdykB!GSnbff%& z?8x4?wg}@FKpXjDfIu1G7+MhqT8c`$9)Ja)aJys$-jEh?5gwU}#vxwrOo~fO+nqRK zjcpb-SZp9KOyH;olqd2|J_@OPHcK0mgD~L(@<X}B+F+C)d;^>yZOQ<!l7kn~MB{l; zfk8Q%v^z*F{$@!Q7~G*T$rjBx4>9cky<(G>FLjWH4q5<}(Qd{c`9nrnd;xgl8vc>D zWbp+$pbMEJEMcG<J|f#J8u1QoXtwynPx3C0{!6(Mp89}4uF+<b55ESOXKNboWBGvZ z<P$oOO}Ck>v;b(38T_hHT;3>C@<|y1+LNz14DooG>KS>XjG%$~@1V74WKn@dCF&Yw z$Ak-+;u$<+F@QW%=Fkq{?OOG^hIi!G4_Jd{l?D8xEkQdF(4Truc-|47a`#D=2Bw57 z(W$i+JwbzbCa%)d18~lhga!sCH8O403N6a5&@PXX(v;L96~IpZywIhE1x+xqyXkF( zFzW0bIg($skvk=WI|Q_^-)0-vW!w6-yRCfHWGhu(8ukS@seKKmXaJP3UCg~$>w|8z zP<BacW2Y7&7SE$ym2KB_X(CEnr%)laulWKn?O>3oPAgWyI@dqfN*69kwffuc#UEa^ znGxXZlag&a?aT)4t!<;$&aVSSG=1qT8!-BHTel@sc^CM#HQO>*$X?$T?WoZf(}G2% zVK22*<`>Ujd%smKo90p7_;_zk3I%WrEyF(cmQC8JAq{8EbiD2$V|QJ1v$bp1%KhKg z|8D#7m&tlh^Bg8o1qG<xbG^30H9g@#<oWZZGN;k=k^5|cKzCmRkR}#pb>KJkCco+{ z{gT8&E=+dx;|o&MJ7}t`!xSIv*~@BHt?F?e=<E9_KiOT6J*swJ?X+m6&7eMEcd+km zw^;kuEj{QRk3MeSPnqiS9na4wa~%AqK0pb5A$6X*qozwj!PHK>S=7$oan)7QgbR~* z54g|Qi0{VRC*OZ#FZb%>Z)R!7Pp=oBQ<}<?4?uFP?Ga7vy0gM$Y}lAD1S)@Og|&-C zwaczQ^L%T2RFg!k!^e%aS3Vu#&<_VZ?i3$4$ksFqt;Lc7oZ+6F%Ey2F+pL`WyJvdc zBEad;Wbzu>j9;MLQ(otl_iO>q+qKwQSd;t9PCwf&Xnk^&!v232tzBhLj{exP)L&s2 znMJV@Wm3KEr_Ere4|b<rqgVW;JxeK6)UK)-^1N_UrVX0*jlk6{I;#QzSchPOZ^AqA zP)$ujW+?15X*i!+qQ27`Q$*jhUE`#}TC~pX=5NciaqAa2tB?;6*<Io%c9>akOsklt zMI|koYw=ZL<UB?O98_>%0YcC?)&lbO99xmG(q_+?Wz}j`wzTx}$`hsmNK=DOG>&xz zy=uwyQTr#*c$XHmcPP#Ib7raS+-9}w05})XI7++_I1h2y{gue6%=IBEmub`Cr&|O# zud?~G=UTOzRdg_7b@h7!EF`Nr0#ec1M01U{RV|=@DsIhh6}0oAxDIUG_s~GvWCRGw zap|GY@+W#8{{7zHL4=%x8=kY!C-_5up}t-O(@x-Gz=mSuQK;v8-g^-L3jRHurwL7J z0Z2~)2_GQsC<NZ4G%&m1&Jzi7$LV_;qL)eHrGq?NNB%;FS&$>N;_!IjTS(WF)|;g( zq^<k<=awn(Id<eDRrb2mWG1OXnc_O2xu|QCuFwIJfW>RIP=afJVuJuUQ;>@Hmzhg! zz_9P)Xxxr*jY_EsU&NNL*&q;YjrvI^$nD+s`A<97I1V(0V5ITTpt157%A&l0#N!&K zTiMddwnpiqT|8~>3iVy#{c*CleDP^&tKe6}vzP!{wCytOa?cB2*%pmIi|HWVd%Cr9 zIm8dLK}m$tP;k}L55~^0ag*oAQ8<`gEv=;b`24n5rmGe%3)-!CsF9vx-7k(8&ce7G zxt=VLbLhyQ6LHk7oi5P1hLmlJTE?=qHgA50&6~Hx-^1$*FF4hjG->4bUfO#0)1=>} z;XKlxwQ3b?IO7*u`Nesg;c}!K6)0mVz-BZ)cdFiDzKPEi0k6YH1=ACRt6M!ypmVy$ z;6-ie%C$B}K;zs+D|qGcU)Z6U9owJ=O+q5A$-i-E;P>vQ#W8hN?nlXQAjIX-We|xB z@(Ly{qM|#Vh3EL)AiLU+y%r9p!x!!FQ97Woa{1EQVUkx1hU;z8^hKU_DcRf3Se1o0 z0nR!!up+=TWiOK&S(|OZ`ypQrI3owVQBs?=@bSFfF>b~I5Z`d#@rs|tm_Sd^;uqiC zi@u`g(F4zX2%Tf&rYy3bX9qwwj<2X>!d+Az;YQ!ePc@kzYIj^+^{s%-0dNM~+$=?r z7l)5eEX*)Ru3o8(&U7fNI=01TEm*eK0??Ulj<I7JsVwwITN&6$n-R5XQQ8hB>vjLZ zA146kzBhHsl@*1N--sQ=<Tu3f)9(xH<H(c-2LxUtQyPqS9sCpn;&#sKDZxA*QKZN` zK8+>evjfl?`})Fx;-!9JMgtR?0L~0FXy>RSJ5+x|c=^*k5kU*_MYoCfUIvnHk3V?D zr)R+r($+ZE&9NxXB>D!?L&N9w0b=E1vtnG6w_xf-&vi|?Kr0FrjEmfne-XncNqJ&{ z6aGaa?_QEMHaVkXSX2*z4*X464}V}U{w4;T|H511^&*+PI!`ujeJ-Y_j|y;Zb>eY} z_gutePx)oKU3GIGe^;w|6&pVIiG)7@XAacEF<*K6<;Sdgl}d^Cxi5a5KFcl_z!ul7 zAp;+=`dU<u-M<lVhW67tUuR2~g?8}b^G>&0ue~(R(q6yh`%2k@o;vLhfBtU+oUgh? z2c_#^JLV?C20d=b!hzfp@gqI0{C;2mQ-JfxFTb(g4?OK@6xAHz{a2qlp#AJ0CjV;x ziGY3r{5OE}%GGPNbF`GV1N+U`Aw0~~g6?HE-errl6A;(1ZY_K9iF<{s75ZDTpgD{N zF^+>UhralzrHZzF-TZ}1?c)FR5~d@pM-9oaL5~RluDY+c{oen#fOBqB8YtgU&vPFR z>WRhU)BUFWUp|c6Yyjtlugf;3z(g8iz#4#0v=W)L(CDGvf~`y@;P_!MfwmzaG!t>O zDgmcx^qKGi9swd@MuJ8i@JYMD6O&=ULI4~<-vF9z72qt5Q6}_`v;#JWiO)K1eFju4 zU!j8RL?t<G>jeD8;Q`VB&s@_}6Kf`dG{;mt!a-Z6OjrQGQK*1`gaz304p?~t$npuL z@&ZVUKLBdtg%|LFeDizfXI~0D3X|dfIy8{D$X~2knqPL^(40WC3m#%um3*Qp319&~ zIDCzK1F-QNJ^>m4rYUI$paH*lmagsita1W&F(4-#2M{tm!&C|2G95KwE408rH&LO3 zuJ8v~ingoMDNvRCQ1+>%rM;zhqzU~1+klZ=1M)gBNLgz@fxnn{fX=QJsx-HtWf;jH zc4H|&w8bbn;=&HtHmy_>9tXHgzTiE;Ab#Sq1mFgYh&AeY$Kn8BVX{^wefy*6Awkj! zav5oyDsJvE^FbNGck=1Lr06MB2yNtoeh>d}ta=lMvO$|44S8r|;OpDxSs9ls!~48S zFB?rQc&GOsZzL1Mfegmr^V22(06+jqL_t*XAYWWdU|fEXEx`0-X-V%?+W2Q!wN(=c zK7bho#Sh9Cu#?3A!lHT1HH#|nfO-iKO4`Uef<m1mKk$yl9m*JUA3TE(d?+`59cUFT zlpO;yz;ntPxdzPTIlvcjyS&N|^%Qz}$1iz7c91<B&!|Jt#zGVPaU1ZGQ~XlyfY}^4 z34a09kSh)tp}rB8JknOIm*ziph-Z|sgVT!B+Z)nQI5gvFTS$XEAtU64e6Vu>I^i{W zhMzdE<H{rTiuy;H5*{si;$&d~SwN=9FR~-=zOY8zfYdl-BW~AdV`vKtozdJ1H?8m5 zGOp#U?c@N?NoXl&ueG%+Ws6w{@D(gtT8m8KP`12zwBtY;&P?nWM5D2RHYEfi8F^&G z84c;}8+91mdToo$RHs$7gbodqj1_`rm8bZ}RzX;WnG7cwsZx3DW^$^0ESw8J^I1w- zB>~Qb#b@Lp0L~8SC`sfHyZ6UcI>K64Yi7j@29p<_;r)EA+O*atF8bNNoj*~ga<(`R zD4(5LjLFtSv3$`gc6Em?nwVAc{KZjhlHX5$8f~9V8Ry!tz*xKCv*dK`GVQw9%wmo5 zS5$SauuON<Xl(afa*GH5b<T9_@l0QpizWz6zNy<0;LO(j0@}$zd)Mc>?mA?zrH8ro z(LOfeXK8Av&IVhO0<zRrVTR+>=56hktFG1HBqb)#e*v1ON_+G9A+KpMNal!`+^CGR z9dMQwzvKgXLAyTz3W(qF#Em+^#7h$3;9Qbq{n|?}w+qfZ)9Y}Y7<F`>z})dV$nuq8 zZ~FkBwhc|tu)BvgEx+C0tA{k4TYIoxk34GM$)pDINa89wmuJ8&>Xh&9QN_%szK42+ zJiAP}x}@r;%9u3HIr${(eER7EhBQ%(T!!rJkN#nT4IBG~RjydkUg~wXzX5Q*<E5u1 zYm!vSC-tXgqhstpXLR!S!^VuVA)|GGt^h%0S&IYZ?T!n(S?OXWY^4@9dk=bEznKv~ zq#Y}5Ja+!5XI6g%80)!kA*BDpm6GQ3<2QE~C|1Vr59RBI#~!nVDnnugh}$7MkPbL& zuv<t6Kb_vZl@2`Y;C$FO-WeGSZGcR{Y}0}U6Au=K;a_oq-t3~F%mGIk>tMT*3^SEZ zm5G?!nx5*>&0V|Fp8jr>+K}z8-OM5*^%=gASL!T_inLn*%g9zKX-Kz9tzorGSJ;;% zzu%%s_qS^n*vt(p6<+P7$`J6E54%X_%$((YM#c1sZu*16h~-HM(j-8k{=`~<4Bw6{ zncgn*7J$F=X3w#jb*f6kxxDfwnNoYg!GQqI6bf2qL_{pR1aPxB%i)>JmoAme?X;>j zs;Upy;-xhDb}C-{qP6PgG;|m2gsLCdp*C#oMq9HgQ|T^~hI1u-(gj$AG;;*p<N!o^ zU!t@Gbh3M^(l+gw+ODzD-vOLyu%rBn4F27@REgK&Ci-;`<S}y8A<r^-4mnn)oo|Gv z{BZEo;|sT*Ui<_;2PYqtt<$5+*sp#m2Y;@o{@jBEAF+Qz_!GWdMgou<V%I}|PTxbs zx&agho`*K~AG|>HMuBrL3>{-L=4IgdZ@U0EA082`_!aMWKhL+}qkqv@4w=}$OD&Zw zlN-lb)rzI%0eS+xPO{|VmsuG)pzare#9{ok|5#+Ur&(<~t@&YrqaFt_#BL9NMopMw zpM5vm&S+l8+H$y{m_)yi^Y3t}_Fpok`tsqp88S<>An-SiZlB*eRa0g1<0#px#!f%! zO8)f&m`2+^>bqI?)eo~0pv*qO{g&}!mo6QwVZ&O{>xdBD{WSS^dviztoLdWUKKGn9 z?gz4I+C4D|ikGL-WURSM<8As%b~Nl%n-&0QjZr1EqbJOe$&={^r$>E37iru!tX-J| z_R9a{Y4fF-92OH2fHMO;NLI#U&EYtdmnHN$)qF))UQRN@q{9H;8TDhrTt>oMbio09 zmz{o`>^IMqP3$0-0M69~I5U<czDzWn-=F9qas$pJm8E`v;D?i(O?W_K{f6_8*Lf6b zx8wn8yx(?uVk-4ZUi>Yg0@dG7TVg-{9sq^#^sm2bS5CEaTQ~ByGJu=v%@|{g4uIu1 zKAE83uyC`#*pScDTOMgmqyZo3p>>smUOk~5@k{yJLvfO9IR6=N_LkWLhy3ix9^n6G zdv*w>G=fI{)t%aEkx77u{3FM~FMRRD{l_VQPtiw>e4?KUV<CDo(J0zDB+xaSHFwET zo6jteIudr>g*ZGTdgh7fhs%)7C=E|KH{gulKoWp+5*qy)+whU#OBN%*S>vaOYu*b( z6OM7d*MHH+VnA%d48WPbQxE+;{-FcFnX#B2`zO9Y5$cS8Si_mP1C>td-}<_*{{Z{= zv$5`%Hs#@aZnNgcAH7#tc7AsgNV+fr#`e`>&J8#d5U~02em$*f<%)a7^T+IYc59#h zh7DsJwr5{_{9eC~zy7U&^Sd8^VGlm_l4k?l>TYRn!>8Pix!@B6UbkT%jY>TJw*k%* zCjTPs?E9R44n}<WslI;#mB}ZE#C`VVw|2vo7g^T}&Xj0IjYyR9e+qDBxAs|DG+DM{ zmB-wuejR&U+Ph^0z~*+p%cR83cR%W8LE`6!0ytBLZ@Tkg`+m|?D_1tf&37DgM1wf0 zL;l59^A$JsvDxz$dRR=941W4PDPtxdQd}2Z-P17Xf~#ItW(}XZPrI~>C*p7o>g%OJ zElp}%OIb^J>Vex6@BixJzXhBD_5t{DS9d+n{&U%W7S|Z8{?m?eg`AtznE&b^2aA{( z0RRCy0rnw`G{Ar~fLH)Ktds#F(KR?YB-$wS9DM*~m{0*yGC40Vdyd#o1~AK%<`7!Y z08wc3W@&3HAQ>GT&ytlcfE>U#CNbE8kCx%8)vJ8c$AnEgtv!BdAshe`Gyqx>M*)R% zjcg6h0E_{osAO5n3!oq!4S7Q&w6p*R0N-Vr1OZk#V5odDpd;Q``<A?u1_L61(%U`? zhvC7zemeQp^R8>OJ>B$!CQk*W&5Bkqj&Kh6DNcYvfch266Tm7o@gA@kP!;|GD&r6S zlFyQ|V-5I-*$Qmu0y?6lOeaQI!l2b#N*a`egD-%do8Yy;Zs-Tl1DK}41(XGhM_ZhD zR!A!h4PyAkfCumbUIM}v639|glWy_?fETpG0}u)i3kW!XCjfO>DgzEh+^sZ82ib9Z zyNZi^0zN_uj`*E#qLnn6fFmzB*Wgk)bH5J2LceHVyZlLR$T#`qJ#hfi07MZt@&fRQ zgE!Cxf6(kA59AHN7KdGG1|Mi6AR~#mL=z?|pqV(~CxfYcY$FrzuzQMM;zlkgPwGTm zmKy}F!f(J=-UEj5u9$!^fLTnRpiR9+bZwKy3JU`82LHG?PK1@TJwN*8xoh0YPXNTj zVi5U**T^p)!njO`FQg5Siu~~oKs(kXW(Po=PwFS&bqu)TH#P}FSjw1uqQwrNL74#B zVyhhx26G&wg*{Q?&=B0qm}blAl7Ae01`yvR8fin|6CfJ&6F0QG26$Azu}KPV$v0p$ zn#?%BUg`&R0XZNZ@<7>gPnul2DG>Q1e!%9qy+HnG2Z$$@N&J#WWS2<<tACU;JVNFu zAKDA(BR-eAHcc$g5w!$3Yhozcck9qJAAaxF#4vlkfR=5pp`16r@*!<V_?TCKa-Jm7 znHSmDAX;193rPDoUm=C%aKC))0FYgJfv_9aYXY_=$I9xUrBdaj#a>A79sHv`3iT!j zo6*Wg_yA<7ZYgg|7s@{O7MV~<EhkVA8DzmigLl#D+fJ1SAGp&IsQv+*rWH@M>cyoI zZN;R)Cg5H`RMz%Qwr;Dm;MPflYxN?9Aq_sd(l2foi(Q&1u33Y<_9RQMQo(9fsx0lZ zqB@8t!&YU<rl=+nVZl;i0p&HJkkDD?@=ZG2FkAINvRVYdIj=p`t&cURTF2wQ^Z5sC z;<PDYG9%zCN1v_Qnu`tV9PyilB<ctYcTStqQ3m-JVfu9wBdXs5zQVz0TIiH4l+&SZ zb!ygfe*Qjpmh24!hN|o}Sy8~iBZa5F(mp%bC|L*0l{dYI=S+fvd||^IIiY<8@XuBl zG?b8+8r7;u<Dj}G)9dYzxwF*{VJ94I8?s26Do?b4RX;hT5c#9;Qsq#d@Dk!?K`v}X z*RS3HG6j3y;-x$?u|oDS|ByF7ehDr5asZrJq@b>uY)8wEuFNpZm^arJFJERw1RSEN z%z=osGoWKEN+>H1C^{gifRy)UnakQJ;26H6JzP}%R$d1z$w^+Tm|E86Wh@b0k_{!V z+==(njup_vR&esb0&AEMDt|$QU})fnGerUQoH`l$H<gEIDx!9ug)_zi#En<yiBjRu zQ9Vx-El8Oc+Q!Zu<qg@AToqHFcUa{bR;OY$E3O6T*~=G7rk81KvO)1vl(hAj?E!Gs zLYzP}WDCB+_xNxy%9Z*@`aA=q^_@N{ciI9Lc%c(*J2(K}kssO`;)?4I;Ou6ZoJvtU zc365ft0eO^oUM?l9S&<{R%eOo-8RV|Z7mDgEJQ#k^$+=)H+Qbup=_D(NVCG)A;4}K zuLt54Ab|tTPC>*P$@A7NJ8ZQkmWvlG5a3+RHJs7F4swNTixJA$ZrO*Y9Vd>R+KI7E zU^6C;)@jigR#&Q=?z{zX#zrXNSd?Mm&E;P06pJA&P_J9915h*9Yr$c?!d0+}(yGo; znr?=M`nD4(fk%=R+EV?cZ_j6yvhxXWmYrzTIj?V&E%|{)Ilx4o1Z_Hh<m87dz4y1? z%Bf1nf~L1Bk0>T(MW6>h!vg}j6B+WSn~;>t1~epGe69EJ2uFS7;49J%sYQVmj1;}! zB8up-2l8+{3~|TNx^}bVKX&mPAn<_*l!AzKpjm;u{f`63{85}!|5#)nkC7PzY2hBs zC994!X;{r#HIYey(wLtk2lNa2RlIAopg8oisR9*Oc^!%4Ld*1+2372Q9sX8G*CFTd zQ~8Pb5`%!)cpf(TSDQZf&v8^PU(!xIs+t{HH_gj8gbzFkSS;~HJW}FlH$U?Fw|2*+ zC%PGfSSFy0>pfcJ;#EY)e4VK<e9SakCY#P7rjQHlMxWBGmhxWRi^ereBM;Q`o%D4s zDS2cMdZWGn#S~k%a$QW0N0O}iS4I6^`_p7jp;FlpG2fyk)Wam31mOJUr~a;W>tpTw zb6b0QVaH71GYul`tbf!e>`*<YKf#m+I{~Qs$a{X7zoA`Ox^le@*Fkg{D>L`X6J{H# zO3SuGi^f*5takLlJL;V0D+u7E-}V5`EsqWw&K?PiR`M6hAjlX*!x#7(*hxJPO!7t7 z=z5L%hhfsZUX-yWK@Vf>YH2BUns$Sw%2dj`V}4Em&X=^8hO?V`A)WmJ&PO`GsOco} z#l*Qbb@nnZ<Kr7vmRXHzQ09O9#{G^5a`FO=_z3=F%m0sM_Vv`o?&VOv>Hs*mX`r;V z=uCgAzKs471q$8xF32}N`CfLKv;Gt<yEM)}wW({Nd%G9$3!2Cn`E$7q<T{VzT=jo> zk4cSw-OqPEP=fG1g!CxX#)KS>n>gM0;9AMvIG?zFc$-PMC>{5tFL<A5OL(dN!^e5L zW*qGA<<A#S>1Wi|C#jF)uw=FV-nMaAV2Fpvi7!gTMLWox9y+mcda*_=?HA6!RR@wZ zwqh<$yPbpFYmV#VR>{9t8u_KQNu)tNLvHnw#Z$%zlnwneV>0sZ{3Qj^0FX_-^f>TF zGRk}AmS>!CKBWAm3t|7#8wrGb{SB|~MKrCFUEVGNt=6pFv-{$x#`W#kqZ$ePDrO58 zXV|BokJEfEDApuvZ1e6bPwu5fnj3Jgnx3Zl*G{)bdwRQ8uDwj({QJx~hBhj^z%kz% z{>l?pMPrKG?%xVHBVS#vz1^nIoSVo_)1wc!6J&!KU=|*IKK5H%px-9qEoL=v|2DuG zn(uk!dHZ<OS6phoE3<7Ux3tC$4|Aod-)79V2?AvoNN#Y*%PY^^?<N)eLG<-c0nS8+ zd6t{*d?*n;pe<%v>ei~RvH5oUb^1)vJI?BA$J<hwT*D*??oa^dFUL=?9``<;NaJYL zk=zGoCSLrF3uwCf*1ieT9t26%*)%BD9>`tQ<vi<fa*IE`M$7rSUJoSd6?OLbV;fro z?HZUiV~zvl@j-+r^S=JvgMZdE{!^@b9{e|e^9LixSik-QJ(4;#tI3qcBN}t7@7mYJ zgUx-P|6lH-F<8>4@4c5Z`{fs0vyTQEa4gnz1f&7XVbVpz&g9QQOEu1bK!AV@Cb3(I zL4F2FOn3oSN(!)GtEPi*3b#rVE5JHHAHX07ujQ98H1tIT>}=75hUZik0AI8f*9*kt zFrAG88@Fk41)u~iG2jTz#Ni#7Ivmo^(u5H}2oQ?=&~cJ3jVfRh2l`+`dV_%GB}<k# zm;~VJU^)F!)cFB$K`S5{;fd>(4?am88rY-B5k83ogrHONL82ygc{LaTMDUJL@i7Sm zxQ8Y{w=LoWX#q3>%A(x~7zyx8z7RluU7J{GqK!)aFd@L8fR$^u_mUU1v3Li+3u+*M zCK8&>ThvK2&||V%L||)a0oRlf+s~NzZWj2uC}WBEE%Ok7e=c|cTG&MeaFhnHI(+Eh zAV}PLO&9?N$xDL<8a!63YRd)K&z&<jnBUMlfNg9tvJD+AtYVR7IfLqwDo=O`a817H zh)IuO0v!YSfL=fvWQhDRn4?UQJ-|}(<YlTb_$4g%qw$X%Q3jMVfH@lATyNQ;!>g1& z<|qK+0dpubH^HGapec6H5X&&}0kjjYScw4WqxFu1HfSe3&x8ENoi_0SP!bPi%qK;f ze}K4v8Ss(%r=gSEb0)vk69fiX0k|bzKv`&TzCb5HmHhFH4-W7Opb7vTz7Q9*K?`6h z@&Y}vS(5l5Ol4F41;i*E3qi373jBsapyXIG%`O3W%K`}tGia@2qJ=a7kNp5f050*H zuu#Q9MGOFwFX|3?puGTW-!6aTjb{L6loi*|h=1w`_bea)WRo^wnM{OoX5lFCA9-+o zC>(Va*+ypZ&j+57AN;xIC-qW}_!ZCxpWNezwv2ikgW&KGemkAYZ`=;j29nN(qw3g} z8s!-FDk}KJ!T{}=25-_3+$`Irn`Qrz?dpZqhLud=5LC%aezd9?I0p?6%A616aEKs- z;Vm0v!X<N?Wv<c|{R*-POW4ASTXGCg6%O(eNGaR60CUt;w3~NI!*Yjg*KQI(kgaVc z`3t3rRzNeQK?0s->Y6jbX;*~aMzU=ZyULrhWRqR8i^gPrZGF!xAR!Fq;gkZ(KaL3x zQSMUtWNV_iO{O(yIsq@~$f$GNd$KOx47|l>(JMl+UnKAnQz`=8Rc86MowZ@@y7tt~ zeLep9OBdOtci-f+c|BnMAx&l40)Sb_0LY`fDJL9@SBd`8J2@sQVW$bQj|@>qkU4&t zG`i4w=<ua1=@IfE{z^WPYak=!BGh%lP!1x%8HxW;C;6prpy^6KLLCYw3qtu4C(io^ zl_Ov!d4ulQL=EXU&?$fs@HuSBlwT)I{-d<0+kkqchm6MI&~o<n+!;@5YF89zXgg?k zLS4kpakjL2lLe3#)&P{c=Cf8YkV6U4^7Z_x92L2zze$5a7I0YvECQITaMT6jrfq;< zm|w`NF#NGVfR^}n^#|)@n~;fm3H4R97w{es&a<U&@&Z4(=a+lhQSv8}eNooUM)>?b zg!1}IS;#-~4VnCI!8FFEER7+w@GR30`3lp&N+!Lo$sY?hx^_N`eo|EwN=s(9)ZgY6 zE6Su}s))W=bwKnY&j=T76s(1I2ar{UYgesR`=h$9@}i%^UN@Zf3V=)!fSjq!5dk#X zvsHJqGB?Oh`#Nb;Yw=dvyl&SYK2mWMud1Z#Heu-}#WVe)Va)b=%$gxLC1fv}!xYJj zYurJf<PQFmu9v+)T-qc6tSs#sTfK6*rEA+|Ssje%hi58`GcOJ!Mka|?FmuXtoBD`N z8dq$>+=$we3Kc7OKR_KqgA~C*R<c#+lv^JI<tTqU1q^1cS>t9(w#oK$g-R8yytZ@F z4mcA5ZnQIm4lzj}zgjWYiLBZ#0eCw3AZR!X2$%CP`VG7!i0I?qd8K>ZAh-Ow6Wj3N z_o3SHAbb*DBxmvv{zO9*m^OrGPNV$#d-oTv6aL^=l%D%RhTRc1aYa)vCm(wr?|DzW z9!C_BeENcc+DUK12pNY99s_OACypWe4miUH&!1<U<oq4GXjZM=VAEt{7ch*2+t5ZV zsd|wjlMv-niVFx!^FERo2^iWb?x0P?`-`B(xMIylTeWVJl~0k0j<Qlzpwh)I@~0R` z+`|)>)2Msom3p&6wx2Pl0k~aWCO-V|T#v&e2(d-sy=~KVD9cdhcvvH?(v%YH2-8iJ zWtB!KGUvVg^6OECa8SxYZ%bEZ*(UXM>E%kwj(xD%OFFpd$FHGvmo!~?wv)(IuK*0U z>w1Mu#cbNV%_?gVg@Xb^8%f&`h~YQ>5E-P<M&rmYV+Mcb2?l_VHZSz$;g^M_xNir1 z3;7G?$%xDQbUkGOHbbUVDBJWjnLN>AS;!69rwr9TDlg$##6x6~v_1XsCQ#%gdKg0U zJ}y7rzy|+>AWGd+2wtP>ZE6cK?LycpX{CMck&pu-QNxB@g?Lr#T}F_NAU7du5{j>4 z+GV0=v&O+{yNhX&#1CqQCS+7H7snaGMfptRFT~~4#_{^E(xJ?7(Bv0;%Fg*rd+Oy$ zKT2PK5=H1!Sv)1Ym#uzRWp1>EOIOQQ^%~8)idyyba^gW5jsHWN93<HjAwib`=!K_H zLHfDNA^42*uebVlYN1^hQC4*6PxU&-exAO-ex13<x^!&r?J{vjujOApJZQup((`9L z4`t%zgS_aTaWD!MG<5JF59W~6C+5-o0{hMCB78kBE<2ALDhR{BKKyc_D8q9-z+S(* z=w0lMGH`_iWQ6vVF}%hAA%5M5Y$kF`yiOPW9#2(P0c2MBs88~_l^**TR`lbD*W=^H z--WVqz**+O{*EK6D7u4tmnZV}w;XXs9@)~52J>1i)*j4}_Xm65WT&=0aW8Ld**`ln zsd3cd_3i#UZ?r4B-)$MogVyO@o^^xCfO~uD@a>kz@B7OBt$;Hb;qbSc?|Rt5<v(Ri z4;UZ88x#inO0yjIZv>n-tL?w*p=WH|cauC12m0cWKn^dgR=MJzy!?}ZGm&!;<qNM3 zQ(fDC4QN!awhfR8#B(m~ZkWZu9SY!_n_j|V{^HGn4|91)4$Ogr4w3UiaXoLi+z;5? zUzl%x_{qU=<mx~U5dN75@3g}k1O=-D`P=vTp#simQlE2Kcj0|oeQple4CuUH7Y}In z`|`hhNarS(^vUpHIn$nbDlu{A@Gd|$z)c!oKpRAbLunF#lHLJyx+ah+YaxMFKG{>l zM<WiX$2NU5Akn;~!&<O(u_qX7LNYl?iMBNZ7yy_77%{mdO$OXd@<LA~LY2;LP59`< zh!0u-rvdW-+L-i0vuiagd`3n_LUTC)UUZxRc*YND5)a@74K_d)KnOrLG;kmy4H2~9 zVnFlgv(B+X0^tZd>V@aMGmk+o;t3sUpc7v30eIx&TXhv@K>@&oVT&#KVNwk*0q=@Q zV~ljkANK$^8#KwMEC3eQuFdrP27owp-lRc1{6a7ECu>CoKoy>%We#``$jih8+5zx2 zByheW3QW4_m?<A<g=gyojH1;E5J;E+?y0=hF;%NtO$SCL+b_TTVk=gxaG-g;CbB6q z)d8=d0nLu&qOz$g03=kpU}l260`L<bfGM&Nmn-xlOU`f6<F>G)yun`pZRlaKfUuaH z01#(j!6A6$-vI%I<vC!_=FM7w5dH8JKm_wDqzOL(tk!5X8G6Yx&vD2HG(b<5H2MHY zkqy9L8Yc&L<(EYiDhM_|iGy-Qru<rQKywKJI`BoA)Zk&Q(@1z|CVl{Icmep!_9*~) zwA9O$EAPNR^$*|_Il;jz@<N_)45ZN7ByAk>14sfuf<NpeqajRwg6y+^Bw5irXo5zx z@>opB)L~i<<ZE2V;sms#(Y!;v%7VX=seGDn#WDxaNXLOZ&x2$~^24x+wgg(0fX7MM zIPI$2$QS@H01pn@c}CfxWr$3|M=sFrN8V#_(aTPaIB}6z!jez&M8`&cIG7Q>ag97V z(BzW_QsX&;)1Y-tUPu@4B*;Yo)A19+hVAh17+@a0Q%)NWuVovnq>6`ttExZJAWq7I z)&v7-H2hh35RVm4A%U<ZG_h9_0&D<16->SuPy0lL8wTL|XUqIHO{z9#>5$R2Tcl}O z-fgs^{TwC$;I(RJrM0^&TlHR%u)_qvn1fKV1x5ip>sBBRixvUg6C0c^ip0x>3sDiS zLmR?C9DBRSrhimM0CP?w!J%5=hzkyiZ9W-bVjSc#EF4fS$fXZ7@GF4N11UWG7NHJ0 zQ^xFSK>p$VBRA^==%bGHl<ph&l#Tp)jQjVAgu+2zXycf$vXH<68ud(s#Q9Qa{8RP; zkl{d80C~xWcuc;SkdU7Hkw52wry9s4By=Lzv>9-USiNl_EnV;7A!!AE;0xfGwuScq zqO>J(Iu0bs56|8FKm<5@*{Q&IkG#<L0cQF^IM7GLxF~H8ulNIv0M2?RezRChxCGz~ zAM`vf59Ap~{a}{^n*L}h)4t^s;2-D|-D(E+0M5#<(j^|u<6s(tFn*w(+7w^N5ijXO zJnyQDl&7kMm#v#6k%p`v{wt|rEP=KzX;B_=S@}YQcc3EB<5K^ux=&lmJqw*If=FRo z^uY5l;U_%K^GP{~&dqAaHfWK%v}~s(myo8i0B06X088n20i0<QSh%I$!#{vi7Bc9^ z@@vOI*(xc%i0f^u$`Ic9!V+O4+F8umt?lhAHHq7<E$`SMFD(GLsK8^iTEn7*+5~8% zdg}wSKrsUnt&?rj)yq~}snitFslHMNvT+C_d4?tcYUCtGX#lP$Wob7{>s|+(tz9cE zLPc9DMRroPct|-Q1Mn5zI0y+}bnj^^e~bY($z;s>%r#b4X39#6KaeC(;RB`cRX~Cs zgpcX~hw^ULm=DeI{NiJo3T4F`^)YIf(R_q1785W}0T8TON!61n01iG~rM`KC%UU^2 zcCc|B7Evfxh4p+XDJ|BiRy&Vs<|JG7d^&4Fd}Q%EQ9qqb(hGG07Ad3p@T-sB`!ijN z6&{XUI1jmyBddFSDLsW(ixz@A(?iZlGx&A(CBp2f_evvIf{dqVpW^h1(aBPJ4)*yA zz5*d$F8EP8iTpttp(G$~Hx;iUg0jTLKsPaaOp+B3ulHWwk$+DjikCJe^o=SI=T(R+ zkOBWg8ZJy8EBVz!c;RvAj%%Fa5AsC`L=W`CTlc~Reu#mz^oBMn&Lj09md^xp<;!D; zCOV0<6qYnROq701#{X;YUSqb)&ikO>?|EL^Gxi+pNo>c7W5>b4p{<iZKq`$?p;D-A zq%>6G3lS1kBqV4hzEn^NBtAe;1x0NjO+<>+2<1>n(+?3+K9rWGfGS#O)5>vDdu)$A zCwpwq`91Rg{jas|=b7_s$A`pz*7NLp@4eQwuG6~K>Dp_rU2cZ)$&Kb>aq8)mXA@T; z!rQdP`S3YXs7IS_(JWkbI5V#RsIzLaw(z#TqwRVuK>wp-PyFm1tGxv0ft`90U9CfZ zi4LlC)IdM!pU9~V^nul0C(hd;uJbc_^sAwxuEVJxfJp%i&dBW|5k$}?_KxCK+bX_k zy$_tU0h1$%lh-euD#zvl=OV#YRVQI^6lT#r!fhI4gO{C3%=Op>+Zg-A$Ji=-I9a@h zQ0;#6SQhisf9>M%h`DWZQ<l+%M4`6WEQ_@rFL5D`J~teoaUe(E(Rm*>;wbu_hov*7 zYQGv=NW#D`eX}!hgWY)!Wp-NMn?I?yj_{Lfv+hoacIIM9P#%Yb#D;aseYM;;dfY4i zH%{lqZ;ar3OkLFovpaF-U@fZ>Ok0+5LRUCj&{BtU#_YidUO9zYuud7~cHwow1b15S zlE<yEM62zh>kT;b8??<ER{f}4tD?6~EqY`bTTh+n*lyJi^;Df1DhnnzctNKO$TRiS zJo`gm(-qEJ;Kk6(PLX3Xo3w|s^7AkK?9U&5{crt7_<ecacfS3>ehl!Hwh?%#!`aGD zj;B8#r{v%NhqD5HlmEW&eb3>)_;df^;oYyY$Mf%Jhcg+iUj48ByPwT=5`VjkCB><u z-<#F8KI-;I|J5Hp{7SYk`Tgv0CX>Jk`xpPpUwhFu72@sN`~!dR`woBhC;r`6-6G<& z1J|C{|M7qD<Ffv)!vB@MrT_Dv{Hf#i8jxA>`-gw{gNHx&AN~9BNnAbru^;=>Uy;L^ z597zPHHGaf?#==j4-WpwOSYbQJ?6Cowv>52NBt||c`b)C`2Xks`=^IL^Pl{eSp=H5 z^IsC)o^kMB{>lIJ6&?RC0e#u+m+Nrm^#33J>Ms`0PyG0wI{d_szs5tgJ&<}C)!#+L z3`%B8jo<uBe=(iKY*C>R=LAy-<ETxOye2Vipmi95(YbI;Ys~M9GxOfOCd(0Ezhs@1 zye8|~P7~YD$3e)UWI!NZ9@|=Q6mb-`Lr%V~#LRg+*S2F1O&==Y;HyI~`54=Fj^Z0l z4mGPEAIW}>;B+7y3wXspr=iZJj>*JJvps}3t9>~K40_O~2mEoK<HOb+;y6nM4sT8t z4lf5DX1_O`m;REhSs59e`ZZf)aE`n&tHP%9&^gCR5V_DUuJBU_M|5ysoRs9Vs@6&? zI@*p_vKY+5=S*e}K7%3n@dAe95q*vlD{FPeoFU>k>%m*8YW1qY)Wli&btMkQtdv&9 z`J0aUP}!~2y*mxY=i~f-=%G)v0r&Apy64m+?8paSRuhMY)yc|^&gi_3eLN@5%5Mtm z#FAnY=#%4<bEpGu>ET&9Z~)MWEi!r^9g&qITe*s33nuN#>s%(X9SlVWXwWIU<$%J= z<9V{yatW^{pYoBBE)2G+gQZWpurk<cGWI164lA*nFFfK?8k<rVICHEvwvw2f;!G?! zm^pk38yp@C$g3>apKAdgG~^o_3y;ywI9X4euHXbPJILcem(v>GR+F+dG~@xV?C9#L zI4jx8rPxW-R@nGE@<EX3GK0WdnG9WyofKz?(6yj0qKfCedbwM0G}Vga*&kUwfNww8 zP%c(Ovl(p=UN#Q4BCu;V)Uaf`9or#O_biVd>#Pa@J8<B)1I@rl3)yjkMUT?Szt8Z} z!>-2>uKaG@;K|{w4mQj|ivMT+!21qQzw5!IWnXMC=Q+kQP&O@%j;_Tad@cJ1tL2<| zZ@4?Fv3yi8qwDi|Et3-@CYXHMQ(Ft=;a1MBZ}m0yJXCusHhy(h$KSf1HY_}Fj9J-y z(>4roIL{zIcnD%*l@)Dd8$O~3f8npm^iLU%gcX~s6_Jj?%En~qf%nx{1j3&@Q%>Gw zFcC8uxB6@AnXL|D?EpR!IuT3$Ab=&3$5}Hg@kN?Azx$o<Jp3;|^;gR4qfb13`0$_p z_o8$A_f2_~Zj4erQ+E-m!<lX1H@Hn`$kg(v6AZ^QX`)wuXtiwB7r+9>gy2EPy{NY5 zCOs=%`+3Y1z9u?)kZ<9_n|6bu@zM67iP1;OXY;2b^mY8C>2vfI(&6W5?!<P{n=(kw z@XoeyiB0fyyz4keGY4w<EY0oom_F%PCz3}$!=}9n;_a9VoEXX}2i4R$8+=<=WO*j- z-P744QXXx+6~}!uA^gfqZreO~n}%|1v1A3ikN<utZ!6*d?!4_WllI8nx-#{z_QN=n zuVo$^*EcC|Wv4GkFYl8FPY!z0PK8;#wKzpbF((e^`||KL4<4_k56m_r%A#9<bcJ); zkF<yT;jI<NFLbZzym1s~>f5q1?Mn9E*B5G&Mt50jEN}jl{lyFEd$I!ZkvN>M-O83@ z_uR}L&Tk2?J|G)_PO4Mi^Vg7q45wjHpMCT2M4Zi!JoND4!K@g*H>)JCX8Rk<VN*JR zBcVVip%>H8uRiysyxH``wZo(Ktd7pD8a9UTfS?x6UUSf!c8(q1xbE$z^h;^;pH4q% zmGfKj@!YG%OKH!jolavdwMliF&-h$)W*<xs8f~Xy8<{K7<^6e0zaLP{9^Waw9LX2w zLm#H4id^*Cc^<^wPW$wD9L~NAK`M^w``(sS)!`M*Zevu^xzSGt9ld_ft$PmdyK+xH zKzH)dz_ujHxqP;kCMWo$BvYMZNh^-ThoeMm57?9V(I(TZGM&N`dil?>i03*zTw{tf zSEZdO7+TjPCoGJ;7SC>*o)mNi{G2<+=X&#jS9#V^;LS<OZ*P61T;QFg6P$%#cuO}5 zt?cM6+&FLh0IoREJJkji$w-lw5x2tziBIuX9+O5YxaTjR+KU9~r*(8bHoWs3=?5mv zOn!wBJTD4sqBHrD9E|1Yw0_7aQ?t5S^pC8oUBlzXz4Z-m^|Hv095A2+@5qkLO{D!Y znu+T+R_sVJxiju2!#NMnY<Hs_O8erK{>CTGL#=s88Mx%B$oN1F(&7#Ew397EPUhuY z>nhCjCDh_*`-WyNv|0Gp7ZfR&rHx$H4ssfL?i)FBh!^&U-O5K}0F|YYu{ViRQN;&| zKVdZ1%NNC`Sxbm~z+#N;r(<tyPX0abq3`Lpa&@%J9k*!Y)GJC$-s-N{m#xt+gBLdf z_Iz^P6sgS*N5c`3`>i#XLkD<ctJ{=m%XR3`cehqbTQ}DcSeYkp;Z}XnCoO7|R!c^` zC7<&Uq1w$s-`MEAk}br-kvvPjVSO-*>iyg<*nKl4RTxx<{i*;&+xMJL0^6AKDJ^BP z+Lk^9$aTj+!NcL44)Jg<W8i-DHL~?V3}J#})sW(YUzrd8lJ|ASWVMOmfV~Xo$&I#g zU&bdfpwtc5(~mX(hQv$h(V-hc&UmY1u9n-B)9^(PU`8Lczuu|J^U$CU=a2l@ihcdl zV0%5dQ)T|Tpz8F?vD)(C?`5A}tDb$-%oZ6|DE{GW4RJMNw^s_Mx74u0`Sex;KBV{C zAOB?M!ym{h(>G@U!M8#%-u>urf4p0j{GsoEe;uDMmHQRc|5A|O7xzzOWjtB+VIO$^ zd$T?3$sWSr2mv0?!oJ`9=x-n1_SX9k|J-}OJMHMp?ffg{>$iUAp?rhp+v=P7N^yLx z@>%R;>zcp+4}SCTv5!A=_`dhO=imX6kM-#%zFxt0E4I)1sh|Aw@pYKTzDj84{VHi+ zVf1d(&i##F_=Vg5@W1&BohVw3?Ca{BL-r&zKr+#?FD-|mE+OrEmBgu8hgXc*2j^_r zz;R|}u(sdc!}4+rTCMq|<p1`psF4Sp6@nbM@L5r0e?X2?`AlYQC!upOAv9^?w0<F- z5C<RU7-uX89;dDW9mi!?ymAr--UsUBw{-?Sw$pI0TIFoxl;kk8(%K4K`%2@F<4K3b z@h6?*QGi1p&QfsQVjv9|quGYTL2+(53pjS|NsT|9wfmW9Psb;Zd+Bs$`w-4G9W)-^ zlCl`5<XVZE^1!z}u-Sypksj>-?Dg6wa?sb^i6=80R-w^{mASSW!GE{Q2tQVY(>X^i z+0ZgD#Miwk(_A#)b9joLi!Zw1)OF1vsC+qam8E?v4N^GP4FG)5%d5S%`QRMxWIuYP zQ#5vd&QrW>y^ej%)+`LwJ({lNb>NqS)HV9jO==BV$PWMPxyun8r*rahzH_W_Sks9K zIfvHeOK@DNZrJ^o^4c&wSA(1L#)|zu1W379F)hD|1lhMu+!Y4{ddi2+hen(Rp=%&& zWf^<%DmwjF#*~E$z?K|jv4uqkcwyj~)Ehj~HM^~&Jorq~x5L?>NuXPDA7zg|;FMpP zJA5EgS#r3MgA<%>(;b|g5pkz>zw4`!@s>ImnK^H-XW+-FZkiL<QterH0k5De1p1;k zbjjF(UwC#;=YrMX9wg8M{YcA2&a?FaoaD7Kn@%{QDof5DPQYWbq>SkVeDxe0^Z}Mu ztooymmP>GH5AddJ)giEOI0TN2an`wqf1J~7TK%1~3B1+J=MRs4*V_-Di<9X5`E2I` zPn^lOd~7Q#cHDavo@fE@O2Ermy_nK&9lMlCDJO_+2=K1n)#03TSMx*w4rLDOe$Xp} z`rEg%(j&+m>SG7;kmp}nsB<{)@HYI0a+1bAa+B*o0hhExqE7mkoiO^C!9C0qq)uLw zKLg|BHE0NlPL3lB0^^hoWjc#I;tJgS>l&h_C9<3!4*%Jo`Ll-~{p0_Jh{J#V)BpY9 z=YQp|Hw7Q;og+?BacYV);nQ}qu}+{$Z}CRf9@A&x0sjQpwlV@VN`lm3bK#L6oldkS zIrPIoCb_*OZ!TuiKh%mOah+hpw{hk?`W!^VU4Da$9;ZCVv0eT`XZF?I6IXC@&BSQ2 zd%|Do1SYyDk1ZVd@gU#Om$v!UcN&0e3pks#Y0~N#F&;_T?z$n)wf;<BsU6kVcu-fI zNe5FIqnA4M@eumztp41a3S`m-vXLg+&l~RCu<IZgUUSU>uMO$G{)zPs19duuPU!_j z+hno4Gh3p@u577cRqef;zj<xV{@}LM=+-jH&pC_kUY$+1<nm!WedU!mWS{Rioa>NI zTWEjc>LPjeb|K2{eD+fHmceK8+UAX0`9SVlGOo$?7(S*L))L0i(lYI>JYz#vQ$H4m z^QS-l@Zp{Lkly_d-k&!iB44)TNy$W%v;`En>Iuzg`(AiDAME|Y^}}Z#{#2dl-}&9& z6+SuqK@7ZhNV{1le#-gAO?xe$?+W$j(yzRb{jKSSPH)7CEMLn(3sMxZdu5O|>iq3X zaZ=~)m&a_0l72ny*gbE_gZ$`Ip4y~dA#nD7w&e$u=Wcmeob5*PU|RowF;4t9<-;j& z$O8cT!&6Y(&CsM0TWVM_ZFThruH1k4z?<&PL)i4CiJSTqZG?X7L03hOymZ9w@U8qK zNiK3(J&R08o7{cYb6K8`ZO^1PzkHK5@bIO6hn~>YhlzU;Ex2UZHVZDcKe&>%;s?j# zF)$JJMWLkN=A`X*Ov#(JztsVKa@3Bnq#aXU6K3T!Ug6i)<`PR~i)_j<c2vH!oA6FQ z91zI~Xt--kE+Zubp-BfQwq6Hz_N!*YvIO_i4=j)!%fa2w3lIAF%c~W|uiVir`M{Ri zkRL8eOX>;j4V%bg*yN8oPejqIgpp-()^3vXrDw=!uKc+Xn#Fj+xSigNyTWgd#ck4J z=R`}IkEfAm-Ub>cm-gb=HcE@l$I^of{+v@UOQ>bzdIDKWC2-*TFF%>qVH?8<!IS9Y z!xZTa>s(?Yf{cyiN(wFQvO1Pi6a0WGc<pTraYd{&Fk^2y>yK;I$s78o`ALICL4`%H zPRu~F!9Gxl=38f~18{So&(?+$XZ7QRFX?Di+~#S_;L82*N5+Y73Fn4%C-N=q<0TI+ z^(=8K|54x3^{iY+PycG%I%RB349>xUQoBYX_nUNL`zJaH{U^_2X2%w0an!h$Pp()- z`CbUsB=?S8?zu#=`g2{K=d^ifoS(=h4lE4Y@m!I|m<yv!Jj_<c`W$nTj)Ri#eBTs` z+!jG){(38YV0wJ0gIk-BU)N~md|ui1Z^f;<b6GgCtsdM$kW*|UZ|Lo}_I%*a_-O2h z?0^%(i#_Ju)4#d2$c{hBx8l^n;+JQI+EV%{m?m!==qY~-ss6-={^SPxDxGmy0bduN za>37?h1k_n#Vf(Tmc#j#;LqYl19z<cGliXL;G0ncuhpo01@g8j?mQuF+uz8R8vo$G z{R?%fS?OyvFXxj<mxh`{hf~eot99;XvSzCXj-b6Kv6XIKqc@S_?CHcM*YI&fJ^JXQ zby_|6Z4ZXsS!roi<90^r%*1m%p;w1hI)ggG0tcswu?_@JoSP0#Wt|~MCuiA{aTIb? z37mTxj{EO_Ywl*xN|R$NN;&d$PMmG%k%jXUuK~$8Hpd!!I^g8vP(%-n?L6ZYH3;3# zK=AwMz$tQEvMMT$u5N>n2{ZXPG{-SA4n_`llLr$qus)>p#1oI#5yqiT$DEhrY~;X; z(><_OGV49r1c&q6^6@9SAg}Ejtjrbg4X*)19dIdA^2yIZ*S#Wxr>{Uqw>o6_IQ^cD zW5C{*KHR8Gp2(}aYykgs#(7{x6-PjABm)mlS)D3f(WQaqg?v2GN<GdZWy#4%-wuNZ zu;TFtw{pOU2M2hpBQg5)zyf`GMt`ryRVL)+Y``a+aL}1FPDQXL@K*I24AOb^5xvNZ z2aa*JVOtjtS-Pa_#)S{%N(T5jlgVrdsqDmC(R(=$Nlfma$bOa8Z|LC(FLbfxG>GFM z5sx3Qp5uXxcvA-C>^3IRukrwge{txtC%7H8x$p%>d9#0Yk+W8vkj{z9xoaC0a*>lB z=}JBDFb6CipUYs+-pN<<s<;WWNs*NZ9hybY8D`euyy;u%%jrj_N1KcNaq@Zyv{%?` zD-2lcSW4s5;aBbj@~T(L9^deQvzn4Fg_gmVIr_qfz;5akN*>qX)SDa8k-cfRtvr>7 zD%v$~R?s8oJJ^<0@`Z`oOdH2s)2E<p$mYED>+HeMKfCwt!=rJYoWJ0~N^F9|Ad^sa zZdU$|!zE-=Au}M(K-~u{19Z4thjS*gCY{ws2H##IlsCh0d{7UYm{qocO9UIFyq>GY z1(+P=J-?l#4u-%bUlOY6J%Q^@@)c(N7A;0|kDo;gIS}P%A=(oUjnL7l(@A-eG(Up$ zJJY3{7S14^JW|r^&r|Mm*>m#V!>|9(zfe18r+@TM{b=jr)U{b5UwSDP^+}-fZ7U{D zo9DL2OSY<u3=v>Up{#e9iNL-KOk|>SxW<_VZ_*czt=q;0PN)NMp&T0UC?lzpxpdb3 z#Fr%i4dtC&U}}F5=E!y7qrchaVC+(yJm6(%p5{wB;tAp-MbtLTD39vP1UfM8edwo7 zKK3quapcS)C|eQbH}TqUdGvqUuW=4?h!?7PfxDe@;SAR1&ZKqs0X|HO4*Z9_70^rc zmtv~JT%)DWau&3+>UxltBKhms&OP30OXWEa&z^ra&f}-!{LLQDd9&b>4^r0QyjD0z zpUSr@!kae_t<&~An>USYMP;S&gZWrzw>62Z7t$W0A&*1*)U6=0iq{qw4`<~OC+|J? zy{Y2|`<T}!#Gdk3nIeOJTRyUKI6oSP^QS)X@ZnwW`L1j=@jx8iR*h+G>4iO*Xxm$U z^kp32gQCxU@p`rm`(*m@i--4S#RO-%2QuT7nLPB)8Dz44GtS@m)4P?%^J!Oahu8Z! z<D;9TmN9wDr{YYW8*vC^7?wWZ;^E2cx%)`=CGCUCY-{p{yVJK@-P}Bx=-cNc4(C1) z^x*J?@SeSyec00*M8<D#%$6Znve)#*IIQ;`+H`8Qw{UbgXMfZW-t+du2jBYbd3c__ z^_0Vz&D3`4;7V4yjV@akPU$&N00S_#nZh|bH&T4fSDMEwpxc(|A^F;N1~{R9MsdB# zk2K*F4XOIeAvrF%fl0gz2?YxNq8;3=`_h#6rokE0Ofm*e-x3&mfA>wAqKh3WV`%d; z62epN8wXz<o8VH;>TU`K(m^Zl+~utF@wAT0ICQJu&=}nh-^ERtJ3!=EQTm?tKhb>K zY_!skwv8zXeD<PwNU%dupeG_{Z0EG_<6}d<{5<$i00!@tEb%L8WSRW5GZ2ApnTqFR zPECxH9R08!`fN3j!7&c!@Rmfqwn*{q6EpwO_PK69k_7ERS{#Un8l+?<7@p*pxX-!l z3f_r4;*s7y2Wb8@@5hid!KwOkgG|F*Y;pz24F};doXQ7o_l02R0m?}!ZJS7;Rvz5+ zfzS!T<mXtP@~{1_wp^QL9I<U==74lObpY+9jgb+9FX6N4#4R4D!8bNertm`sKjmrS z<~nq8%L0|@=uz3a&nZ7`<5Pa=Sn6;VJI>~LgJ{ZD-y@$iurP(G6hP4=e#I1K;>)yz zIgY19G?N6E<e8}b@M`01dcd{~SHzX8IodqIa4HPi;ye{w@WMgT_KQs~hco+cAF|3Z z81?%c?G}#QHs8$Zep_oWXL#CH2G`h*I0;e`oTa&Jz1i_A%_*JE&1_F)fXIG0rrWNr zJc%4Ul}EkR9vJ^~8b{m4Hz^8wS0?-upy<9w@N}Hl&TZ(oTmx$!@}Upk`3mQtx`Ti& zuolW|!WRsmcM#^`->U<jIh<czH?Ng)hw6VV6lZB?8u<OIfz$o$S3wG`S;s)mzxs>6 zc>ACH^j~fVqj5Glk!bQ|m8O+Uozx{xn$DHO$||#Qg688~f%OXQI7;v8B#~3*Z4W+} zJU6?a@|QCC<G`zfC}}zd&R?BEomQE6SfR@CW-^O59>CiQ0`51ZGjNv2|L5Y|(_Oqd z&RQ!~pUfVE9BJ}!I_WfZAe>{IkK}XhwRn@>okph|ns^q+QEuR41+`UKef2m_CjkuH zaB)^~M9qYF2A)Qhm*a4@?ZV#X!m6<C2;74#jy_InTWMHf{pP&xz*%XPl@;UUun)CK zG>5W5lf5(P{f*(>VkUIy<AJwws{7!P53pV6KC_%;I(Dnmm4Oc>N`Ex_E#u*GUQM<V znJnb6vi7ZSeV}qZ_UL1Q$wy_f+MJvm$Q*Qd085r}x^XDZ))Vw+Qo#x2nxoVp<jP&P z5g7fBp2BGGSkVlRvNpk2?t-|nLxWi3xB1u~X9cILEjqw-#e4F>4X=X(*$REH*>hB| zn-Gg^YjtpR$)P~*mUW!Fbn%5JXa8(AXDGz(=nrpJ0jm$}hdp#3(KtQoaEYwj5orJ> z4;|y*b@xaP2lUUz?Kj;ICWbe5X7E!ysXK7fultPykFLe5FC52ojAuCaV6!Wp1Lxku z8jfW8sFQo~WAZ~TdbfwQ^5rZ)vENyx{7klWfa49ZVe19dc>~V8HJ<%RBX@Yc8NHJa z4f)kKv^j(Dj7JX*z)0i3-tgeOj*1uM>(vf*p^o<4%ZJzf&?|`jC(PiHUCCHJLI*AS zMi*|^Z2FlTR_|F&Nq?o6v%SpmWP2QWJwTvyvUteW2V3|G4Bb2I+iXR%hep~44@}s@ zZ)FwaBUzEi&P$u`WILRVcsse|q*K)4EwY;Q8~)}IKwu5#<IxGv6Cz6;II+TH>M%Jg zF}1Vw5%#OI`DGI|q1*;u8in@ILbjF6?@8#O`{Z_A1w!8NQs)5r7Y+3BFd#5xTGgAx zRvr`dA`cT?iPXtB;t3c_W)nYh<H4EDVX_mnfYNy<&WU^f_q^}$M}GKUY1WT@{C5t& z{<r^D`B4td8yl>QOQPb89ZADTCz<3}<jY(#G*4&bU?q|uL7H=Z8{g~sVK36_U<~f+ zO<clAlZ(R4JsHZ!DMapvH$2eR<actlX`J9(=_rIxbOvtV+4VT*5)Vg@ltnH|wm&JO z=%j%I9-SP0T{IW^4%g~e0Lz2=Yk~$zc|tq#T!<r++LY0@13dIWOkiCL@~~BWlvvWp zO(#|Yt7~9(TcIuW5URnzrcTo2!MEEaoak;IG}LYq--n5*dz>0WPRUGOy3tpvb`BqH zyq4{O>`ia~^z&EqkS{W6L%V--VYR6ys`CI)8=(#GAoUIR{(f23001rLNkl<ZWJ`^A zW~;5#S@rXL`j+#_%XUM4cvL4+eSK*2;ZLQn4lnmVFmD{)^~Su#Q>VR>uLX^MQYSEP zpY|JZI6v~pV~0<F@-v6;%<HiaJeaq!vI@A)#k3Q3GPfS(p<#GL7;n$zgQ8D=?wP}5 zk3Q1X#_!JSi5Ii=MRl1|N-Z>0-p~p?y1x~N^R+mEAIV34?Z<pEa@?O+8}G@At~OK3 zXq4J)t^XG?wn_QiymlcUMf}3y(+_<%{p&sXfNnm7dp8HZ{vI8+6#jht4}G?mw>xfM z55LdfO1@9`A@u{<O5;ji$1bmQfWPp1Ju9zchPlc^$(q6W!w<godk#PJ9q-K^&fXSc zL+B(#2UD-cISj)qJDh=zjW-`X^dc;lhMa*}Tuf3P{w_Km`c;PtJK;r6If#z@G`T-j zU;4||qr^~!-0D%O1%SzqEL#rubRVSJ-jyds)_6F}!O`Iyou^zNyq$+d7t%Mi4!RG| z)#>87d_WM{)zP*?<y&Jtgv!s{CGVyl-dqQEcnyvc3@@VRuIDL>BZ74?rzzi|U44-= zd@S}>IVyo1jilI<pj<0^Ai5<A8LN=QPr?cCsjJiNhv<!U$|D(9-qXC(ocb%Yya<_l z4(FTM-YTcqsK|vS3~)HN>=JLg4cYNkEU~>lgw9>tOgWR4O@bh=)#(#*PJPTkWVR~U z!sYxTr;;|S1f1b{h0wfPKcRDq#26nPPQE%Zb91Y2Mx5X}S@jydCw<$Ix60^-1r!Cv zLdH&3_HMtJxPm2abd+>$5L^s9VQg`5&uVA37G0mJKasMq&c(lw&O<diX!5Xtj|7hE zBhT`!__1RUGJ%~sR1|eMCpP1_C0U_%zut13!V69PjIrh#^XVJfC*UX8zzMnDIuXBB z+`g;W!K~wW3XYvAaV~q1VabuGhQ=rVw&4vjx(P^a3)F<EU%6ftexuu5w#1Zg+li^C z?KcA0IYJufmQy&Yy!zYN>+Lw5GgwHQl#j<^GbH-f16;|A4(r$s^KEmuN>L|eY^Q83 zrtII$;cP6O35fMVxgO**&XY0sQ+UC|-u2_kCG`$(OE>yZ4(9?la>_@PH*w&hgI%6) z$|9=|e;He9kmL0O`e@M3>xW&YuL)UH@V<IDb2z`cZeA;;=JHwqXK7~|_-59?9kx?< zs)Dw@+Foto-~6Rty8Y14|4((ISke2XIBm7%96LH(PMb8}agh0dAP1FI$XDXPd2TtB z(&40&x|9xwBZh;<%1=(<u5gY6$wZFR%E!?-ZgdJ(RO-0qbyyR=OjbhIN@|@7TpVT` zob~{8zB?Zc;%r32gqOqC<dt)lv--JoP@G2&!5Oc6k77<QjX8LZC+VO4>}T7dis#sE zhZWuEY&i!7&MfrM)%k83&YY{Av?ss&`Os6~)9Hb)(=U#7{L`yFXT9<xPxl<ogn={I zs?^WN2}TLF$)LN39{NP?t+>7?y1vn^9`JH6M{sn+5v+{x&Dn=%JSZdaoOeDf#JT?N zcfY$^m-xURT$i#+>DiQ_vhg6m7Ag1N|3DpWk7ipGADPox<HJNBJ}aHYyXWYx6E7UL z(+;dMGco4ybKFWEtGx~4z|ygFc(=nD&vZl|g7Vrcc;O>Y?I%3Dhf7%~ORK4Zw9aLN z8+@@3XAWojLGMx~<MNc}JZ#`}hRf<Vxb44rC5~k<^veNChxk=)WPdW-zJQglHWZzD z9a|jUZ)DJ2**J7!*RutU58gdnx!9Y$R&R=P4IclTYF6D^h3wvHT#gZrA-W+OJ>ZQK zo9uKh4le>89EA&RI%aPsvUQ~A%-+aThy5v?%WqJvPG&t}dAlns`Ytc$6g%<3&MR5P ztu5kk#uIwV84q;c71+7v45ve3+KbfXRbDO6)CcvP-KmT4umknQ8IN$b4GItB2D8s( zyOO+gBM)A-9_SUVXW&mhxCAh+OFukYJuMICy1L5d>@y2)AMBy_8C&Wq>cDZH!>bHF zmQ|CFydlo&=mf6rp_-LD86D@|^fl$11HM4a#B(*~7qTKytn%q3Zi=yGZb)n&+#o8> zPSncRcA%J?nYiU>J048_A?$3~<OhApjqGo38`A_ok`gNK8qk{=osYvAvKiz<9DEBN z?4DQ@Pjpn;vh*Sdp$<NimrmAlj~BYcH@&vJiZ`%uYO`WvO#>Uav7@QG_^C8qVU|mG z(fJOYh=htbN2R7)a}%lpy1~gd5RE&HXXA4|&F7Ti@X#WpuLOG0hwVw}z$LzXfC#1X z?s|gz>cVZ%u;<O(W>Hj0B%L#sjk4X*tNc0O34)f*#*wp_qE231wk^n6d9=S(W`V(n z!(=Nz#V4OMtAQJrJY%4u!$%IXHZSb`UxaWXJ%@N_ZQ+);4$UOd>*#-Y1CC}h<y;!E zUs2OG1UgEeHj^WK%D1_4U7C3?Gxn2v`vb?GZe-$W{Bp@Q9G5wbt!`FU^clGDfj?sp zb=un>&p$UGfxVg)y!U-u_Ph&h5Jw+rQ{zDHEA!z6kL5Eqd_5lreKa5UA=iBm*cW;B z#NMmK$w9{akBHIftvCz474*4mgZ0Q~KXZ7;cfRXzUmU=k;%J(j!p8{a&9W&E51*d< z;xlnL8>@XW4|Fdd-tn&Q2!G+N#Tv!aZjFBE)yb23bK_bb{(th5bvR!R9lUylm|X0r zbx2)-BH`SHw8wGGSZwyhBTvS0{79VC4`h$(yX$a1e=)YR9L_$RdOHqh4r)RBcJo@^ zR(kr{;gi|7PG9|wcfS2_S5|Oe$jaziuKJn7)<d=DI-GNz@#Y`6=e>s?csqx49&V?6 zVx}uhc~_gQh+&tBE_rKv8<L&ujH|vjDFw0ZZ_Yuk-AoA$_bCEbJMY3*kX#pM>1{<V zfH)nyQZv!VvW7J`#jCDW&jT+WWb4x6zy3@GP{-N84K})p)-=9L?u(y(_;BeT|C0?g zd=1J|^p}KNmYx^ig_`Rv+tAu1Hr$E6j>L`^6=LWe<G}BbtKLk^E|1BzVWNXZ>|D9Q z=K@;dZs1ov@7yl}*f@41pcOY4r*ln$-yMsMmXEj=;zpSB(q&H@zjKlX%I~_GQ`@T3 zp!=HLKA#0T&%F1&Lp%5EqYraKp!}q*N^BziE`$rg)+;^Ahwec5P5v!VQ=}(Cosf{j z$3B}U;Jd06C)$m`!^RUJ%2@HPkLb0Rxfusz@LK&`930NFQ6gw*gKwPD1INCH?lir) z$5%!YZTICH`5N6+=t?8_@Y07jlai#Nv1OTPx)~l8SWYNST@+Uh)3ZbWo^2yKrb?Tv zU7jtW^dsgo(^n-j8H1<!a$1!NW_&bl(GfG3TS79-wWPvhWWf>5rLdr;AIweDPGSe< zbcUqWbPKbP1Q}KbY*AB=iEwDgEH*Jt(Fc1#s*UcS3aO7`kC_9V%UmHHXcm$f@6v3J z5QG~w<!tMV2~F)Khx3l#a1w6cjK3fsr|p{=p<7$3@dQ_GZjg^2k~0@=_q)}JF~`h{ z#9eGzoRrVZ@26bZ-6#NWMUsUt_Z&X*wQ@LD8x{T4f3Sg<I|{E2cjj=uBPG5JNWC}< zXBzmH)xez&xb9Fvs#E7C&VTclfBE(!fBhG_Z}Q`hJzl4#NsZOVf^8M-|7KM)2d~D^ zp1~$&R^9nHPCwifj5;b#Yb&Ylu^mGueVkmJZFk2h`h_@DP4fDs^f&`Kn`VoPS#fF) zX`Q+JoKZSDj;zmTs|b0nbc=>e1(x%Pvx(D=1Fap=m3#m%aGXIV=T?zA+aiL~8LSQm z4UGz?B>sf$tkl77ytY=r1Bb4awH#pMki5`*@S(Ng$zvtdwM-<p6O~Tzp!2hu`D#`c z4-HN>gDidCtvJ52Z*}m?2M?$7?8)pyc~|Q^wF;K3Z;5Wtrz76{nTV4KALMW?POy?w z+}q#&_N=CQqz=L+WWsqpvh8vf2adzn3h?SU9XOtB4bs=3Gsxgz#WXkp9S<oO)tgg( zU11#<a@-0Z=Q9}LOtNwtPzM3g2j?GMa#+$4nVscB1Dx^$V-IMyM2}mqbchcHDNdln zO+(qz2YttFQGPkktxTmi^d89M*#m>e9(|&N6gcoj$I4xP^znjEK|I=caqNAZIW?@( z#XJ2QWLc4omi+2~yaJnXz2%pVH$1UV_AZWY$su^K!ZBh6?&x4XY*<^S=fK;hM!Ct0 zx9zm%OlNBzplo~OlvQTn>Tpdyv~I=GB>qyIP?uug9wa>#yR(4jVpcd?sc|`R+ZkSa z2t1vkOJ^OF8k|N44y%muC6M{q*q5zK3=G+vmDU`<?5=Ss1GwPnTNb&eukH~Ze0au# zZ96<vftyYR_>#E}XJ@i#r{J@~JnXkFZQGePfukUU?NzR5kqbTft)|Bp{lnv$93Okb zg~O*Wk#PpBJ|^ZG-zax*yByBwGEVt><~Vg7h00+ZEf3sQWT<oS)G;QDRI|eB)I@-z zJ?%&SjsY9-SY#ShT#dIf4vc&vg1amPqS1-kj%5>`^Wo=0WeT)1j80~@ViFNtjfN}v z;fn3SJM|IDQVE>Afm-y4&`C_<x)Rk2q2whqyf@<<Y}?#PHFgshTVmhUK_S6!2R`!j zJrtesW7~<G$_2cgB$cHTzBZT1ojmyu4PnZrm%ZM+H>U#X#YS!-6m8?L$H-HsYU1$# zcLUy5a8(<jTQ>nLofD8k!c8*KoWve(d4q$V>5)y(1Q0kO=B!*=Hr2~8!NQ6yaogd{ zWJ_M|>MV5t&Bd!Wp*RaPc*-z-^Vj+Uwn-B=_D&vUE#v5iyoJv_iEzj&WxlXzyWO-$ z?<woFg|o7MpgD_8?l~U{!@1#lRi*7nu9G_m)emo$c=gu<GZSPFxyRWo--*N710`*j zdIz_yAKr9t9L|t~^HIJ!oD-G8NmTl};L0E8@#nK`1V{IqvrUD4rfpeuE{;{Wtop-h zc@D>(*l4rZ_m`gh+~LX3J(`c{ef!~_?ET!mv^h9}TN|qm&DK@R;hcQWelgz;_(DFA zn|A3+9vnZAZMF7(${h3kYdMDK((8rP?OSOhAO7S+Y1=$BzI=GI?MAXC5WUhcT`$jH z`;)BiOhKk!c=qPu@kgILeCAV+9p090(R>u~>YF@Nr~Z^D9a-U=<7T$%P`Ve-N1xA! z*X;fL$xnPDWpV59o!|Ygj5FhKj`M%ouCdEH)ylOM&f1d;hxcE8*Wq8d|K0P^z?9$E zhVmBZb*}tMoAj}%W10(TU_y%B6`}yH5+7dIMNS}A=tXPNN?s{N89d9rVK~wYh`Px^ zg1w^ysQ`2f$F!kCWrTPU{}UD18E1e~KXG2Tl##Xp-Af<+t;3bS^BZo?!Z(2io_Y6o zAHMKIKM+Z_-NhbL*0pUmw2oMR|4xgnehD7NZ4+|QJ9Qv<cDyrtTF5(A9o$Js{;_T8 z`H!7%`>a2-HXN|x3_yWq9+R8UPg`&dNsqm@{SSX*zmo@=?Qp)GZN}7_!gYo7AZVMp zxYp*E$Ax>VLmjJr$`@X>WWzJirmgcyosCwe5=jXRNCEG3zarB9w#`0g{x%Nh7xnja zoqkdr-oUnFaKi5>tP=FHG|175`AME5`BTvod6IJEF;SC!@brz46Xd}lPmW`Tg%oeE z5C&}ND>u`xPdhf(#$hR&l;iZpw7c3&1(bg3T*l-5XlCXp(-~{8$dx`PH07vO1V1in zt60om5SJ@_j6Ecl!#RBvC%0og!>rBC_$t7~Ip<M`vY2_cZ5;bBI0?qm9p6!xYn(X8 zPCX3S4@Rg^x;K44@{xbLJbm?k&|AE|4pRCVd0q#wWnSo41w3;&zp83pGa+Vh7S1&A zt*e1!-}u#0f$Fq}1zq9%JAdux+SqRAk&ecP{5U!}{cgnJXYaLHX_F~dW*T(>#Q|l@ z0iBTso|71IojgYlXRfUne1PsvS*2@22lvxYKb1+(3vo){-4&l4VH|_Dl8~;&wW3=0 zU?PaGr{cJ~&hZ!=9MYVNw);Sf!`q(1&!_XUH3N8q01iB>TEU2O=EU1hO->_loK@R- z>@0xY&S+a+aJ=i}ID|N9ZGR#E#s{9W>r(auem1l?Hg#%NM4I$+=Is@?@}mP@K2A#x z+&6|_det@22fjE9Il4{Y?fcB}9|at)aiYgb2ak@DOq>LqYKa&;(dCxSRuE4`@7wWr zi}NyibZ^2LHcCg?+75(%Z${sbWd#<8@f)(Dmo9bq28Z|}JNn9xOxxkhPB<Vh28V&7 zmF*n<Ldy@$<l{^vuT^NAh<H^_4!YsMwO=%6GrJ(?*hd_f9!P`_a?_y$&JO-U2VS)B zc-LJ9A}QzSk<Q3K7S3hm@_b&2?gNettio>b;I#vk(1csS<2b=MmnL4>!D02Ua<)pi z4$;sRwnH5s_<ds@TnP9ki@Y4e?1Zgb>CPD}e)gE2Z5<5u)Gba>ayEZt+`PfDZMkws zx9W%T1vB(B7!Mx!`-VYm|FjL$|IIj@IXW&H&?GNo<OI1E-hH%_qxX#|djULKt4*=F z=o@W(;7=LMAZ~Px7G8XWkUYoxz$zDU^gup%y3adak`Ep>B~3mbG(-d3)&Y9T6#b`T zZ}e@FF#}olqwV5knmWT~6)l~>LATQ3^ah8AOz5`l2n-#&_aMOv{f}k07!KzeO-e@_ zm|-*3G^)<e;6sFeqI`Csn42`}_CR&ulkEA=0GTsC?W;jP=BzlbV=JxUjg5;lB6Whp zc@5YVR9Do%A7}Oq?ZZuYGO&lsUs)@kcmylXxhajpTjRw^?~&6IZS<LYS&|nTt!DX6 zthyo3+!vxS?7fq|B<q2^!peaNPMadoucQ119%wV?M8BnzYqX_RDlDSA%D42B*0w@g z_^#~bDG9l&jJYbk&TREI!B~P$!$<EClV@TZRTPQA6PuY;!el|L)Q)*3gXqLNly%PJ zDt!RC6<;#Rxr6j=^Q|wjak{F#1V`;EnOfd~HOcLDc@CDuaY7D(@EhBrr`B04ly}o( zlSBLs=;)9#j)>-R@mxp5F)d(Qh9aPQaVG(XBd@r1ojj?Hr7eBz3%#Y6(AxEe-o^<& zeE_~k?+aJTkoXZT`ZB3RW!^dg%Mnst1Ck7$><eD|&tB-3ema4^xb|jGd(rka4(B|B zO=jONur)}=9cd3~>FF=!qsqa3Szng;wiO;gC9NT8wH3H4YiOk`U&zGT2mCmH?@Hb} zr^%+y<27>cHWkk|Q}16$AM<=3UL$-dW3YaN(SyR|!^0|q%2A*&a4voFjps9NdF+w2 zExtRD@kaJ<_Ho2+{gJH7U)bZ#bGM?Cv^m$Zg8K`f|Kj0^M;|}j_qM!!^_IKiRFB;G z$e(?tXJxs%9LI3t==Xe9I9vJs+*5g=o43eJxZm-vcf>)?QH@7$VFfO_ZF`k${m^0P zM=fzUzvJ+S9(+$6&Tp)qmH!0VPQK7MM$xC69RZ|ZC%UL@ZNZv|cUhL97X9Fcf1Jf? z($JkcBqbqqPMlXE1yQ5L=gp|iN89><C;hw!f1%a-Uk^&`Pdg3QI+Ot08(hX_^9Gl; zWw;DK!O=ZU!`H=+e(Z4OaIU((DSn=L&wCDEjKg{MZjVUuCQh%o#fzQQ*0h_;R(sEe zmL0o)aaHO4JOo*Jf-X7oGe<@dLm+wC^6rPmsT?-a2-ilLW^J1tuKX}{90G^>w(M8s z_Mgf;c0ab?)yK`MZC`lP7R+i>51x<QloyPJt5ET~f_mj2uc8*7O69sdNr8Xzj7;mM znfLVxjD~A4hMKlQBO~sV!&&{*zw8yxb+!hM+S|XZHh5MyCvr2e+MaH0k!WE~M~XvJ zLP$#^N5cuLbH8$e;&474CQmXPb+Y)v;HfYu6W0qm$VK|UelMh#DTj_nl*zo=+wmK& zmP}}M-Gq6+G4=XLycOa4TW_jV-oWjqcWesLIXXteS8S~Ikoa3SvW;c>#jbX*!+FZ3 zI$3R~{L9j+dnh=Zb?C-Ra`-bw&_6XjI#6>2{23pNWw~#3=bRt@@YlxSeDaWEX#K8# z%k*OW6_7odhtj|FtN&Y5zWu?s9zOKPe&iLP&Z1tbftOU3mnNUxpK0KmTLZhX{whhS zg-UbVaPC)s=@)N*<~RP2PHL=9<#Z9c3N%g?j>YSF)l^f>nPWg;RVXA~0hrp!(Zor@ zS?0q&yOXtQ(W+?9E*(!DMd`#ia5#%NkoGD?4n}a&<hNfl$DIyC;E?L7>d-Q1;h?=c z4oSU@i5sWQ(^(;Da;6j0={V33IPe4xa$A0&&!LI#IEN!g@W_iMJ~&A^QON|40R=od zT>0J837XYG__Y$%hrnh9C!NGW+<Ygz>96UUJ~%<Wx`cl;;H#4?eCW_OFJL*nIlErS z>hfpe%*QJ|1pSm>I(|B&AAE9}ap>%=1;FFgVPZQ@i*fwn+rWYo5zicd%7)XOLmyuH z#An#5!`7sj9@v8bzk{t<1%H{-I>K6YzV$C%9+T;oZ*X$LmUj43_V{C4WUaF=aVLYE z3;~mub5?nAoEo~wXTU;F>`;KmB%K2t9=4dmDDU9N$N4&|SJwxRf)lOUPs$TsdQ#SG zTpCA%bh41knVfafgc-P%9h;DMF_`r8wI^k2b()pi216XxbS8Lk!qJRh<tToyd`Fw3 zTv>3$*LH$m{FJk;KvEY%mjeYKoT@F;=u^4ki~jAKjo-eV5IH^6Xx_xx+C!UjGb{CR zWuN2gnMf<g+HLHC%noJ9Ugf9nJ&B+znZXF^5!t*(el4)_DP!qm^*TEll&iq;Q#+;C z=-vQdxw1JtD?9ZbJv#Ex1pmr~eLNo-;ij7kksmfz8qo{g;$_3oiwA7r;q{QiLl%__ zEzWNfCw%<&r+?@0Oa{cyUA}Pm>|Lm9qo(`<-umd)<YWfB?3YaWng1kmpv9IisfTpW z0i_(5<0dl+JmJSavviPeiS^z<xgP@yKPG!cUajRPgV5RUQr=vLhmdT({FW{T%dH=Y z4dNQR(5-~YJaDIATh1w3XVTlle@}Yr@Jk%tJ88)^{(GM|I#Oz!;nTk7dY4sFl+g}# zY&H)qORH9Pa@iLnR7a^>Jui9#fHqz2Y`F*zm6ynYZ5}b0TODq%lPp`oR=Rw1FKhTJ zzoAi01UiJ+*UqS(p<UaGUGE9J_@NPOCiS(Cp;k7EdmPT3n5}EE6FP-Un?wI<m|S$) z@-KIZIG(qL!eNXK_v*Iv>L0O$^0>}ZF5(9Bi3S2t_|d`S3;t%NgUQp|+@M^@<XPEd z={3D6Rhf?YA!vGdN`{ipeetAh1+eti_IAKh1}>5qkf`+}O@<Oau_*wJS~%coJ#8d3 zvBw~~e#--<@EE$=fvnDEKdZDe%i)}MOr6!9*0Gqjg%g$j9Qdy-lns3dnMWSw$f?MQ zd{@R8{g5y8<!9OsvT6&}DQ4CWxMuI?8)^UR{D`Ajn>ky3Y<;0X#*{S~^Jl?;g#%Cd zu0d?`YF2Px${S&}@USv_Pq^{hvf#;x{I~MazZ>a8p3MXFFXf}m_v9N1-DWNJI8Io7 zBb|?I*_yuiJUF|VEj+Hr$^8Xy>_l(<DB{(OBf>KtM(>Nq;PA0T_I&fk?ZXGIzVq;d z@5q)Kaf;6#&J1J8l`BNWG<Nfxym%>CPIbnJlb*VzOogd)i45$#(#?LGbo_zlrGX8~ z)OPNeVfX;+N;?Lb{cg8|K{;uscbXSf$|f0j6zhQI;K}ti(_BXl4P@&6xw)TulIQ?m z$lGfdvnTgvJ=T<XY0%(iI3~G#(>_P<J40cHhF?5k0fNfE;CkKY!RNAZ`B{*nUJ}p~ zB~LE4zRE|U7lM}8%6X)7lB+4=2i2=nE8yaHa5pAD>cPIw87rqEc9N*g;t@J=wa0d` z`suvEW$Tz!7VVZj>LKjMf>&lKslcV#Yaj_d<!5Z~R9q9MO}L(|@~-)?`pQF`DeomW zCKvCaehLX)Z{a5z5_S6g>39_)_bdb7t7LjNxduo3To8dhIgp-wh3#c<1!ixXA--=b zAmbW^I-|$_=yHz-a=CCv$HqRLSIk-7lR&>{2itC>R^qP5<Va$PYHK&o<v@JGrW;fV zI8#@o<(SCE?>dX9dfS?mwroBYn7EW}8spqgyR|<yhnH#3rUJL@lY7ut6Yj?LN^i<^ zIH-W3m%Gy}xo)0`KF#Ve-+)x+!nP5ajL6_)c)<huh4PbN+%<ei?RX;h)nEFg8E0@f zr|oj2jEckfLwjm0qiqRJ^T~_mqWVJ)XxnVq;v#ywnY5$bC*L4Jf7wIIp}0d+nOuAJ zsl)ZmDW|;k&B3#z2;rfbyhJf3l&1f&vbp7!@@aXjGBh@AA%jtV0-n?NF7wF!!0-ut z<lp*}1M^k;C4cxlX?R}|^Yza>e0ci*{yz`5;>Wn7&|+?Z-Vyj2(4A=@X7YO~-1WWh zKfLh|dh_KhoN3_epn=zEr@mYcRHrtt&cF6+zn1Y=x|?Imo5-{Kue&}@7vk?V{m;a? zy<6FQHU8L;v{y^tGTv!AIN?s=zg+xZ4*Z67{(A6pn%+yVzaI2=S$@6beYN(7tiRXf z{h43+xx+_4@v-vNvgwFBZD@Ek@HO%1;If0vK-7#4t_`ts6Zj63HSAdt$l*K=iNt0? zo1uH~c-WB%K{9EqRfVl1=uDV65N4vb2Jzxm(@q8^uB+%0B}e&?+2Ov2JmFV#iI{}A zmcBwS{VX`c{M>S&n2d06<9AP9I7WAw*++NVQpwU!j`ANzi?(IM!Usp4YY`f?nd~g* zRAfG%)upGps*xbPn#W+j4noekT!R}d_@yuM6sYOFu80zbuTDsSzzj*w@)dWmaR%ad z{+hYhVCYf#led%WoSQFsf~AwR%EJ&6q$P8I8Wka^oecO$w$iHuGLt9|RWd8YQiBPi z+o2^IosG1J2QYAWGD+O}z8<Hg(1&Pv%XL6{#+U~?g7RoWuF19-9;YgL=$nA%!X#XJ zb?qE6n?Hgy?<t$=<Q%@%iDWDB;n^h}Z(2R)c2@8LC8dafgky6^_*_$<{NuF6OKuX1 zZ!TL;$>@-e^mrz-2UfBW+Y2uN3Rnp=y>&Zvmc#jC9H$<B;mbB;$RD?V32u&P^nGj$ zegTb=&b72?F0?!_OMMS7plV+M;?M$1&T%+TdypA?m<#SCRShjFfJ@&ip>J5MdW8P1 z)WvHaH0JM0Rz^dv&8ppm2lmU^tN!~+Y#t-d5l6s{d`#Ad81K58E!48LS=QI4-3l1l znqe&O{N+4^yc}nIKHxO+XA7e^5Uhs2J1e8_%AU-ZvkgcKEqu`RrF?wwq7M*WppDQE z;t#&%yAJ>2cYIH_n#v02*uC<wos%%OG1vQ-E+zK?T+1tPjSyE+iyJ)oTUa?Y-zuAl z2LYxK#d*9BqQ<X$5|KCwOBV>HU2NGU$2d5(TQWpxi=kLZuIU+;$j){bMh<3nQP>hu zDDtD>D%WeJ^vEuL>LGscxepG()=>_f;s7CV*T9*}Fbh6Zk8wwR)HZfJy7J28H&7$! zM2jn;U?!)4=Q<v9&#{<L+-x&4@BH&XVCR!JM`<-nZ|7(5jzenF#GE)+N9VHkIE^DQ zcm}`NJ~=b8q-}m=zLB`=v2h;-ypei$?WV;9DqQS44}!~23ZyH3-RaNLHVoZ4k3!Ic zJ3vCtb2)9}I5)whOcqRY)8Visu{fNktrexsNPIJG<YT8NG$06?mSeBn6>X8XoCap# zTq_58_O)`FxJh$8HVJ00crNs0gsL#$YNN5wI)qU!%;2wWroM=);}Md@oim-4_oXqS zvRrAmQwQ{GTmPD(@?0Ej7LVduX>z6Pm0JO&REN39m7o5$Ur-kGTjz2+ndmuv90%xb zTYWfh`kuhGZ4Yx8PT1{FX*O!&7bT^(Rw$2*;9eAlmEt?{7XC;uzb}H$jWXGpUYs`e zA#Q9R2B5Xc;*3Ue*7m~TA?TFbayVz(sFo8dZD-tD=;a|HJ%^*T(+-Z`b6LRTdq%V6 z$h@IQFStWjkV|6*pT6lv7M*x7`a%{4U4J&)DsnWZ549Mo5A~@hW!*A`BnnoNWC)?q zMaSjpV{@YnlLBZCgax;ZWySCM=dH%Cg~Pe#vutq~c=_+M|LFfcJpNaI_HZ*>RGx)1 z4Qvg(`Ct3vhx>o*-`Tfk=Q9m_Z8gx2>#Ij1O>Nrp!FTTO{=L7un*XmJfip~J8aUIy znFhXDHSp8F{IiFD`p-Vv!E8sa9dH}F&ZL90%b>Ue_Pi8pOgq7ZC4=D%f%}22Ou}zw z|3Z!(&Vx=Ov;2+I`F!>aG^XaD<izUiC3HGLfH2nv`c|IoNk-E`2)S8-!r7IUzAbzv z1R8x~@74Ir*P|0{`S2I+tQ1KmGK`~Q&O_VEE-Ms=#%%o&@E`_DSS#zXh(CMcimz_S z9{dvV=$J59l_NZLf)^&?;24#ER<4_7g~kreHq$SYC80c`kwbD+Y-TfZ0tlZYM>9{n ztj!W9Zzd}z&e6er)Ng?5uq__)<7H(=BkA}QstXqp!m8Fz<}yLEay~@MLv19TdpU(B zI83b2@Fu}Hox>OyCwj{}tergOUa@V5v+EXP3pa_v_FN>P_CUAQYxYLY+X#f_$mA66 z<WC+na$v_H6dU^a>*O$U&pwIaCFw^ya+gdjhn`6WH+{1E?RY3o_>@ucHs*vN9GiG> zOqqrj`$>kWUnNwWby`IZ3Pc-^bmz^0!2{WFRZ2+<Kw-uiXo7w6!BrFKI`QG-q^bQ- z&9aXav8`~9WgYa};XEst!((7CWWuaW`UVs4ta2ywl6wRuM~=kJ+X&=U|3}u`Rc7hn z`^HS-&c_aFONsL!f?kB$BvQ+k<Y!l2ea<P9`uW}g`<n7dTJui+h(39fq3w&8`n6H3 zo#JfCYZ<xETWi@i;}*n-g%1ydVz`wLG3|t-55;1`{jgyj5}f6s7dfNF@Xns>&5y@% zV*JSaK5+Pv@BilyZ_b-i-ne07dmOxFCGQTk!Q9lbx#VFHWi97XPxRbC)?DW_wu^ta zql39F1gM7Qz(ej-tI4+#k0-WAU&)p7MpF*@jVr%-%21h7zI5k*{s`z#IId`}Y7<xI za!$dmP8F^S34U?%#qM42K>lJ6y|zc;4djp@N%Fdpr98TvIwWrNK?pQX<&`x6LuqMk z<!_2~eB>w${xrny!^2QcKJt@+q7q^SGEUy+l-8vA8Ds<FceigVhHeIY>wK~=^n)W1 zyR-p=-|2KNZ0D22?Qm9P9M0EmGgCe}(}v&eY=x+0t*-We>1Od+yWK_{0CYj*v}lS; zn<b)gxgVC?wT*zo!QnX>r=3;7C)?sF8R0(((S6Ht$4uEkzgPJmQ=&&<Y~1y!Lm5tD z(#KZ79Y6jiz4-%`e{Bex*Z+WLhnsTY0^2z4V^aEU3R&PBN|j?A&P7?dcPZZX06Mt0 z!@1<jt{=2=9C?xzR*JzNm<e<`eDC|5+XhdYukXRgIG<<Rv)rX0SPo~!leVsK8z(v; zfu@H7{zn3Idn5TJ<uvgv_$1<03^+gJQQ}x1IV1>$kg_i)djBSRFirA{#!Jl(XRx1g zI4e7GT~v?<s=M7eDa$;FOnsh*1SvERTGFr7$sE1(L%YT?bp%g)hs%A$8m7&PP29`_ z%^O+SYdrgW-lnk~lX2+z^flh-)Sp*T%Z`*S`=*<zS1AW&(J~4jIX69JsFx{ZBBrlf z`54Opwe0BB8>Aop$dA&<S23^~q)7hip$_Mt`<XL`^Q)`qTQcR$;ruOG?B6({U#Fe= zav5vuYgm$S=5QW8oc*3@;7kK&8n`13{LKIQKi1(q!&X^1l{3K2sFD-PJlZ6xdy>Xc zvj@R-Aexk92z>MU+Nb)KSMm3ruz4T7o}u6hi~)Wf&cQna)(o;ca5Xs!{!9*RJ0hUL zd06LOTKGD-vRd)lb%R{IWzcIv(ELd^nF#(mB8;>X>ZA*fOW7)<4$|Pa4GCP}<Sz^v zGI`}&;cy=3Tv3D%TlkE_+C;?mEk_yfM?Z9x{0<H>lcd}w-kchZnK+p2T;p)gBxEKZ zopXoK$RvZj{R^I;h<usYkQ1_`+>HD;uLYir;=<pQ105=-nPf@ByYjPowb_$D$)|KQ z@)vh9D}xA-Gd&`gGFX$I(MIHgH$2rI0z{tz9@qySODlAmzdZOr;5eLz*3bx*Og5vN z{EC+a**cxcA%YT;-jMrFN>ffPqtGW~IBJ=qt31Y5X_1OXcBKMWouhF2k9^9qThpYB z$T0kcPIW*hXohNRL?-&(PIPp@4V|Q-zw8muxos#6pkZNn#&>`@o7wrmkeLH3^ipP} zTt1?w!1>50xW;D?wJ5K8U?MzD8xS1M9+cP<8K3f;%hnl+*eYII-q2g?xV_ievNDW( zHv)fjIMZLthr>DegIxYSktcH$QrUAA*l{4B=+3_8vlT`ZqmG;|>(Ig{9Q1D0G2Z8m z0=big5#;c(rLECA2*Qhx_;z352sN-%9uT%1o8J!>$;P%&$o65{IQq!#ZQBYQY<-mW zD)vaP<T%IS%*n2OOTG0fGu}A2A-$2+a2)1vSiP%_Q`c=JM5g#9TAo(T{hL4hLx+F; zU;g0XUR!eo$CP7P3$9QLJS!)Mux+NV_d}LoMReKEb>(X`UMHSCbL57jBA)nMFZix7 zmezY9bL~_U$;FV`@!H98tj?Hy>fty!LPaJ9bskKp5h6jowz_$6O<as-(U`KalCvD7 zZ0n3pu0?gpo^-k`)aVBMV9&31Dmc-{0?kdCFD#2J4F0-W7>`@SeR3CA`C(Nb%kav- z;h<h&*S*&Jmb?0zZLQD-pL);`JaFw5?Bbet7oPi4ZHk{2<X<TZ79QfAFYmbsNZDLD zM2`iC82WxSAE(F_8m?|(6Z`ZQ&-ENPYx`V&aX8Cg@soZ^4L*D+pj#X3ou9xR(@+)W ztj_nY%(8`@K32Zl+V=0s(+58#u-c4cSxx_1wCES>uz6&0U#!%*4b4+RRI5ptK5jwu zM0+ljC8+!{sM_9GPvtDGz@$D*-Ao>OtnrDTYx!FPdq3?PT#1gI3>_lWaeb8KB))dN zA7&(a9@LzqA9)PUJ&zvUf+^d}KBB2cO}xl?Fqm`N`o3LMeW(A8BedhZ+#8qdK6Uzp zHNKHQ?VI4L9F;__mY&BBr37LZRPHwHiyokeUplRYLo*ByeD6kYgJC1eIRW}15nhzr z;sIUsFmQW~^ExI<xlMm<%#!P*wf#aTx~yKK_omrOuW_MYLhLh#hmZQntWd5a8nGOK zN?-%Q8Qk#Qyq<0KvQ?z}=kk4mTY1CgV)A*L#<re)xU1g`%@aLr-6dXMn-$gYx8Du^ z#mZ_6=r}RpayIT@XIu8kGusD#=p%Qwr3U;j3d7EeqTDEbv|k4Q63A<x{?y^A-}v7T zx1xu$@D0+y>lM;BfUT?F_x*=A{oud!4WN8R@=OE2dku6!P{(?=5C1<+Bij?)@2mj; O0000<MNUMnLSTZHt$BX{ literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231108233708.png b/docs/images/Pasted image 20231108233708.png new file mode 100644 index 0000000000000000000000000000000000000000..b10c7fb404c36618abf764c7e7d6a7aa9b227e75 GIT binary patch literal 181616 zcmV)@K!LxBP)<h;3K|Lk000e1NJLTq00Mvj00FHC0ssI233XBd00001b5ch_0Itp) z=>Px#L}ge>W=%~1DgXcg2mk?xX#fNO00031000^Q000001E2u_0{{R30RRC20H6W@ z1ONa40RR93fS>~a1ONa40RR92tpET30KZpP<NyFb07*naRCodGod=wxMVbGr-_G4L zJ#i;(&N=4@3ro%@2qJ=>-XA#>g){3ZXSmZt)H7lL5p<EDfJj)<!m`W4E}Pk$^K6*d z)4AXG|9z@@dWR*=a>CBCU7wzJ-cWB<y%nBcJ)xd*IgX<`7feiZbm@>vrF=eLCX?}a zJe^CU5UWrFg&HW-!2h8Jjv`ksla&4X6s^}^9?R8H>E~a~Wt6|>#ANz^$g5*w$K#xD z<r}g}al-d`IXWuiQXZ~TN?9uARdJQ|sBA#F{7ILxJQ9x|5iFI|pYBs>m5#eCw{k!M zzkCNz<!CFnO1iCtQbqjdZkl9NbH)w^ET5fJj^$Y1RC~p`$x71pTgsAqrglwII#Wl- z<hH4Cipm|^Nx5B?N;t~$raj8GR63!80p%v1OCqFoN|emQcXE@n_8g^<$2%Nz@3C|M zbSZfrebZ?^vk(e3P^f`I4ZM#vkfWrAROj<OW}23NQ%<@Pb$(sJ-h&Ii)$J&st$Z4N z$pOT2n~X9*nn0aTxh>^!fzF1@ax%)!+Kx(ORf1CiHJ8f^c3V<){CFq#lXe02!b)Xq zoAe}UON9eqH8F|ga@hii8f0y^z`MoWTzHFykk|B2(g1^#Y2^U*SrX!9Qck84R&E9$ zDVg|kmVZqyx=P^lk2%C*u}~<)Yqo70-WO0l=2QwV6l$PQ1BDuR*ER6w1iAwuf(pNR zoOjByvu}0C>z$J9qR$1nvaqTEp+-%R%jFVARyko;Dx;i~6ZE;V1{V#dtl4B2%&^8& z>X;vRED+!bV(0m3BDfseoraIjxQhL)>3GoN*qN-QY#)(bZo%NRu&PPYl*n#gcDXGk z0VDz!EbTxEO~^HhW{wTM>Zcyd2fRBjThbM-P?bjl>7?Uh&Y)A^Jy2QR=CA9u*t;o_ zL0@Fih@j<*`9inMX$qlG1BDtW)WCaN1CUYk%VpC}px@hEKd7lwd!Uy20i#^PRLa4I zH}$BX$Avgrh<hfbKxtQ6rP`F8(oCnc197vC<1%RK0;&Z&NiL~n*bXdeI;8@hbjAsK z!#<bex08N5>x#AsTDJ$cNRDk~1N=FLP?F`T<d}=Z9o^C#h^c=(0iNRt0NCyECSuKA z3YyK3r_ZNf(;p)90Fws)j$GuDJ?{UG)IukVvTN5apcfG|>~A0tFv907)2Koy)IgyI z3N`Tl)qtkOx$HD?J}T>W+I`gRce*sm<`aLjl;0_d6XrQQC@|~wDUUyEd9$Jg7F{hE z=T13p%~0CuxF;L+pvkqHRCJ$01f2ooG9ZWHEa8~Z8jJ8+q{<qSHGBdI@Ml>>rCy}i zZa>U*tj)5W!_O^LI}gY+GSZmqQ(57GO^Q-?c2@s*o&!&Gy#|u`59peou<eeDwXL7` zjB0KP`vNMH@S;H$o?a)ekKi$Z1Le`Da@lplF$3^F{_&5SZ@#&qp}}yy7-R7<=Gb+< zs!)<b4HRnNgIfc6bTps%-eIIk`KatZIQ5F;7|=~AZ&G<O0*1hWR^{@EfM6z_inmx^ zxKmqg-KN&BR~t8}SC*(l2VpdQj=Uhuu^^j%(Gg7~cwksf4J~lHRxG7u%&jSvNbh>| zv4u}QDT!kth0t0s9IG!;MHBJ>Ns^#HN1dD$2{AZNZ7E?sX#UviK2X2!nLqwnwPNfA zHfy1FMxPV0J=yoJi{wl5?oK*>Pp47<ckj99p1=O}ukgXGt*r$eaHndm5UEfDg&O$h z)PRA*jz@^tG1IZmm8D}Y=Dc(7oglIJB&=tFx;*kp!3~6hyB@bM9D?0!dS&Un@BGh- zPknLS4c~bFhd+%icu6%it5nisEBIP3YFU9w;8bMBUL?TUqzij!ey&V9go##6BjToQ zE1r1zj0?_HeS2hlD(Zp_);P=SsBn3mWTYrytp(Nsy8QHAL0@k2(;1l-7jtP8*0at! zvu*3%Wp~_zEE+wqlWe2pQWRmEC6K&1lk~e-IOdLf#T8e~m@(sLKl|DC?c2lQun|5Z zj_zXLRVYrO1`0J$sDXD;106|X$MbiQR9AlmR5OGd2{0Tj=YpgXU@ip@lh_z5tF*4? z<Z+XRme*vq?25j&Aq1NGd?IkxVq|2Xh@S-}b#3t;Y%K|j?AL~W_NsJ7xn1f&{WHJ) z{g_cBgA>N1TLyTEuA$o$L4a1$(JvaL)SxSo%t<@O5R+F0j47?FG@{B&FTCW^T`OK| zdUl~oWnEr4b2Qcl&m}<<q;w?I#e$T|tSRConM8LkffKXdH~$ETMa~S|78Mm;d+oK` zwrzXlkw>t6GZ6|RXj5;6W1$8LHSk{70QM)?{b&Miagt7p8IZZ`eAaohmAplZc^5*L zB|QxVoQthX&JY*+Z+`8WbUkX`Ub4>r=Zn%=JBGT~rPmb21iI4v94xIY%kK@QTC=KW zuac{;@=qR{DK4rEgf-XdsBF81lrXX?VP{wmBrvSOQ_vTtHtSMx46QBI(z5=qe@SNI zJukT!-ZW{!qNYPC?M<^9*t~-EluBa<=3wR(Gs103M)`~^I^CX|d>eOjT4BLp5rq#Q zG`M%~MfcpV>YLG0XRM57p>yw;&Y{cI<uKTyljYrL`2GI2wl=<q6STZrw{AUj=#c54 z9O<&e1Z&5Q8#idspvNA2?BKzJECn{$EcH?dg&HW-K%oZS+ZwPm6>@`-sZ<90Td&vq zE*OCPE1ZyEejz0%Xxa2rPI=<7T%Jr86vzk2{|6)(WGaG5jb~I+uuQMq5e#<uV6KvI z#J*6-PNkKdRz-nmDwb$yRMA$!Kwu9K9hNxmzz7<&Mgc4H77cVDsc4S5hF8vH)y9nn zSFapDb+QWiRH#VSH6>E649lNf87!i)p7!7nD&yr{+xGbbb}WwgnoE?$CiwIkUr{-e zvNjasKe;kfkSsjeA(O@h4@T9Zl`!0t2!1{{E7OYV+>0iyu5_dpCBVqS^&(OxJn_U6 z_uqd%JT71i=z_IZUw!pC=bS?v)*aC!d-UirZQ8WCbLWE4-MV!n4*gYkS(8}dSg3(Q z4HRnNbu}PNr8d}n-Q8oqfK0(2#A1n1DByOB@hkyJso$SFH+M9bWKKoM_r?IaQY7vl zRVttsQz8s$vvwLF27ifzGPFa2Z%ph&y@L`J3oFs1@|B`)<!7gym`@NDAWM4ySg+Ue zV8@I+x{W2lf#Q$~_=Lao2xMoeLXEgmVQ{b+%kS~SP9r3iISoH~YO9wQr*`eCo;Fbx zp;Y$xZLF{Ss<lmpeV$@e$tZ7A?xfr0_QR0#mUzs{+HT7te{x8svH_nPUYHisU@tcb z6c`AXCBq?0O&;CD9jt%ix$3jWAmYZ3nh0dhL$UBO<rKxRG-%fe)RG0Pas+zmk&TUw z*jUY<Kfk1;WaP+^rKP3VTU~eEbq_uC5KrNEi3#G488e2FupYZOdZ)*emsEG14=a?U zPy>Y;=sGoU6wbZtf_c4uh^e17C+Gl0{U{4f{XVZy*kcSGi-Z`DKmvF)AXV1p_=K@` z>wAV|cP+wwjNkg^(FGiF;s}??$4R~NKjVXYO(hW;2jf|_zrkL*Ms41y+TtLt*G}N= z5$kASh+U2Vx2!;dBgK!E4Qd8GxXqGz4OMBw6Whp5IkUGdU)ralTvc|XW`RZvI0vG| zafcWFI2&v9WRn)j9copF4y(o{VVzr|G_Bh~iVfns-C0pBlbva3p6hI~Ubl~#T_)gx zw;niT@QzilsisyZ9hVtIUfxV;GyoraAJM72mj~g1!BjIDgyk(OEBnl6KJ%?_eXD2B zp1>_muWrBn_J9BPe}~_N2{zMDdMZpXf|_;f)&ac$FjAoRvXF(e3pG%vfkF*P4M2jS zyvFfQB9RGV&XciW(&U*YvT~9O0;oE?C3YGNhWZg8gQS2&6VL^N@t24snllZ|pb3e* zWjgH{ooN3N-y%go_#03OSX^aS@C8jVg+bE`%Qi0Cn9hb^JHwUUVO7D<o=tu`o=Rw- z_JX6rivox)QO~AaR>FrXN%5#*XWdvvTb!b>RBg68)Uapg_8F(lR4$eadvGqz+$rR@ z+}>gV>a^qaxKgWDzP4a%^TDVu;tCc82Mrn$9ydlgptqAw#sj{fYE3F{P#AG1o$}(f z(k-s8NZ+wwpAlAgtfU$-I6CifwRNYbDuNjpW#fI0W{s0f1auQ}r|SeyJRT1QgQh?* z!JJH=KHXf>^Dw!ZGiOepK7AH1Uc7VX&Vd65!u|rcaK->I>@xi_kx1Z?qw9Q9p(KSG zDAd3QxCU@M4~L33deE283<i<O<si8ogQ2wijt1n8bpqn%IbcqpW;_LbA?ciwIMmv$ zw;pJRUK0F(2KF-0n-&Nj!s$Nt+`7B(+qGlw@CnnqUv#DFUaNMl-Tl-<dzUN;A@OA* z67VCGr*a*z6GUWQ;<()KuLz-$;5#0-3lTFyYTW|F-?1$kYgOH=l@})21va-)!CA}Q zmWc$>5PMS3Kl|K6e;+jJ{IOSDpuDj|%ND=z$Rp?Us8v;E${h}%T%ck6KJj=dlP|Qv zG>-Vq0`Id~EUi%xCk2~(bjwD3+g@AWcj^S>)ij>~xM{Q;>Qbn#HH-2X^finu9T7Z6 z#nRN&v}MbdS6_W~^XAQ<EKdph_wOGtU;rm{R+wWPQUb<&9dC8)&E|Ux$3hJhYM@X9 zZ>#}m1vm3YgM4p{_BMBrH$#9qLR`0Q-B(vv>(hJiyv-|bd<1u4vgSlXEPCH;v^CM% zlCG{Q#WxfIKmk60WFDapK01*%+&DTy*S`iOv3{1FjI1KiHy%^ZEIj<1dk-vJ(Chru zy5ICMHE0AnU^T9?$D{%3aQ*gY=EK*b>V@y56%qdGb;Kxe6EMNzt`b3ZxY%!bI1~FR z!3R~pcMtMqRazponax@rho%d;EnnCt_R|fqeSdpmn9JSstkYF#Ifm1Rc5K_RdZpUC zM^%-GV+}T3Xm0bn*ingjmZc(ojI%`hoJuntusx`MwfG$Nx+W4W@g3T+r!T9HxvO>1 zQUZ;+IV6_rE)--ML7*>!tO%3A<0qed5;gF%&pykY>gsB+7CeqbA~3#mR^S=;lRSd! zh4&>G*U%=N!tn&J0cMECu0qxkKw<PzcM{Wo8Lm0TLU-_^zt(UGy1yU&i0ik1`X(>P ztz5pHd6zi+-n3wEk$B<uds_qf7BS6-Gk&nsC2SIIf^}QrOJ7!X3YgKga^$GJtI+!G zRy?_KT4^n@q*H*wD_0%<^W1wsblF*xCk>O1YPyP?5j*!Umz20_;yzhwOc1Ui*GuyN zoJz+Un_GYO(+AEx<ARy9`m&`RQw0-?*!o3Yhw~Ff<U0lPz3s6~?&hi!FSoz;zWhhb zixIMzdAn4!v2nrk4X-R6Tv}c;W0LCELxsFCchE|v0_A0@tit6Fp>EXD2Dew52F%W= zwVU>BS-(Hskj*6f7nhd}AEgEj_W8VNz7(-SG9GVh%3#G-R4SKXrg8_AhxJF8RY{vS zHaD)`)~~8urJ}O!VK(7+(qm^#QRO8H-WPGlzWohbcdc8q(Ur>fDy{54dW36e4^IFQ zvrl>bqI{sKNrx)0h_rc}WUNi4;F#qOc&&Lv(<Mx!aLhIR`%=H}kckI0HOOirKJ&~o zH{N(7tB*eSxzC+?>ZyJE_J#5N<R?Fg(<`QdW~vBUqYMUmLF;!hfi)TBnPvt6WdQp- zCS_&=#N-jZpQrEe9fimLry9u93(%K^dkhk<p8d;OKjx7_2Q@*{GhP;p(;Uc!G~Zzi z3wcVAbHqeCvRvw$`Ga{Xmz^E}TIQtFA!W=l45y<@D^v0IEDW(_{i2LQrq`WLUy>+< ze{Ky3dqg`R9dmgzmiXt#7>7M^=ukzRZ`-2&@Y@{+4u)Ey?r?G2MHiJ^aACx8v-URO zhRdNTg*(o;gvHVwkJ3pZv@FeP!<%CKgNS(j2KC+V-hau5E*w6#KO54D-zH#{SiC3H z0;&T2Wl>Q^I*tm6{L;e?wy;r1O9Pe_l$gXtQpt%+1p=NPz3XP5{;8k;>b_vO_q1s! z7ugDz$$}rwO(|KQ>8K#)zwO;i`k~$yNN380zSjRtIV6HEwjL2&Q4n4}YFy|@$LAm| z1+(u2!NPcpiZ!fXv$)C?Pr(v{xELd=Anh3PmN2`?Mv4x5>_Et?@XnF-%krZ{qguOh z<?RoSo-ws{{Fv0?-AjLQdue6uurGXB4IF~$v{*O0V*<dcSalzy>^Oo8T8jD>^mVI* zR|P_Tk5#&N$-4MWU#K2EMD^?5_l((nhmK6fVt#g4IM}@5_PZ-8DrU@_9BXWS?bma+ z-1Dc?KL2sgoYR!MNIFPTG|Tdrjl--Lg~CDPAvm;%;Dp+uKOniF{dH5zx}>faEYQ~= zD<Fpv*4=mCjf*SHo-w?dHER~eR<*UY@VNE$^#CMT2=vmckyJ;cQ7pC$L;NnjN>3^U zUrCKbNc`~O!=%F<jufV)r3Dx^=nL4ti!2JSysH{uWPrYOYOTf5ln+z?_5c+z)KC*0 z>DTS#NMgL6y69dnsLboR6pkd+o?s{clPR-Y6AWEzzdG{Yl%!*Mjyx-zy)QLjV<KZR z0@o~f6zNDA3#JiY|7jaWtGQKe-ge;G=Qcg`(4M>QTG`SRWR^$IF`Y#yr6_0LvJr8@ z!K&1FRNe8L=SB>he#RO7wE-wgP2=e-k~snXOp19Vd(?`ZkFc>~*(`Rokbd2<g^M*L zIaeoUo+nS$l<A>av(Eg@uO8X5nN12bN>C&j0QguG-;2DW`yag#!rtB$O%KoY?)IB9 z9LT7>&zm^8EW6A<%Z+7~o;1S&w<KCxii-mABwH`w99kwa^2Y}`R#UXq8}vonT13<U za$|Dka~3XmYT1gVs(YR4-^Vv@?6ki9_dNSt+q(5C5tGk`gdnNNV5=NbEqM0e7IQ5d z2bQGGLN7m)=IZhh=bwAf?OwBL`TYCto&ST|*8lu=d(#eoX%*f*4lP-p*|EQJ^aNke zo~2_(OuzYa<t{b<_jjs22WS*=DcxSX($ML&Ki~tQq{YdLN7^+AxweOV)3o0>-v2EF zs0I!>hu;N~akT+=%km`dA2@ITTj=uga-+5ZEGaV!khnQ|^k~lWn-U(=x4`%kAE0G- z2kfpt{pnAWCb&-S_yGCUuYSdmrv##z;vG}^g~;!!1|V2rOMdJs!VmolM_~XuP!CO& zgwf20Jj4=F+A9aQ@(!&GcEU76u*3#ZgLMAIPMqX27JA3@OcMig;nyJ$hk$Cy!JP2* zk2=IEoW2h=;DT!r5S4}kZqperzNF;Z@wt(5dDO_U>Xsi)yy&vgp>Q}7?iGzP&8EM& z+%D-+BA1q+`w7rxT2^G2@`G;Udl;VPq5IW_HSvos99asVrkmWuLQ+qh6{ZL~JwCLA zxK>oLI2}fJRLj<w?sc3Zm5GSbP;{SgPcq$?AY~SDW>G|)e^Fh-LF?iB>SK6Say*m* zPX`YB%JVMKB)c|N$!G^q`a8usi2df%j!NnuCq$&cWX-RAM6mNM9-4ArB<URYAfJXq zNm)8XtFgMb$d$5S`vZZHD#9Q)&8NyF1l@2VTE?>Lc(N4PFW;0+q_Q}qv}&i0>3`LQ zPGvwomj~|B%CyhVPQv1%DwBz~vOuZGiUfGn*vy_w0HP}k-cwyE)Sj+PTqT>-N6(%4 zho7JR{qOXjeb#`Yy2DQ_-EseX)r|N!xNp;*#jmbZ&26frRN-}UV2{ASo|%13YQ<(Y zB7{+w+NDaFzX8QsT$)0t?$;}uX--|+^cx~}rHVh&^1=akgg2O7kafwDB`}?6f7yKS z4}bW>nl)>90|16s=7bTmYSk*l0%OOH<(z0o((CjYj4wRyym|9(y6L9h{N^{m``z!Z zx#k+YYr%zcbM@-gK(EP;I|lVTopvGOyRCs7Ju&o%MCihrd~izt6*M(>fKtsvXnLeU zQ4>y0cqDI$sS}a-1P!0&Y3>z$`yCHQ4;ll*Z}D0__qTXnxc&arfH-s1PLODP*d(_| zGQAk9k~_LNdPa{vAYfBt>)v=9tfjAgai@^*9J?q@*|F_;SN}At+SH=%o%_VJsWV56 zR6^>dqXEhR2d9xvYsP6#rrJ^&EQORm=+5X}+HqHDrUBB6kJJKDKt$bFC2x5EPWS1n zF2C%;$N%yCrVV0A1iH#9SM4g9I6~@WP?&MSyXFUBH0e+r0}HI}6s}CZL-=n4&)_|M zxT^$;29GLhSP<dTKo!-My$9Au6Bg#m2M!7DI&oG8D?ipxj^z(~lj*kRCNa5kyL`A@ zcBy_7#?Si9CtV|kum)Id*l}RlioU~#dxrE;K36Q!?7{Dq%TrNV?I5*|#zbpNb75EI zpfYe&W20K|!v4GOQq2d{gc0ie^Ll>!yFIS>XfPPI+LE&FC~FO$I_<P;KdyRI%d)W6 zm}-i814Wnt%L*l*8#saviH3pCU|CW+6K`zw7l*}%mVsQ;*fg2OVA{sq=qe3BHv$ML z4T4{g7&iCfi!XlVl~-=N?KT!2RaI5J_~MJ)A3l6I@?n4(K`}AW5HDZ8eCpJxb#-+{ zE^S^v)~|x!{qc`~JZaLTFMs*V;627)An`AL@e5dL79u14HVFdoc|(a~&7u&$b2T7+ zz=WJ7OUHg{AT!6y8q%X#lUy9=j!esBC~(S67UXfpfXoGMk%S>n?e{wWUvlAHp?BJ4 z06AzL%j9m3riA&Ux!L(F3Nim_H6R_yayzz|TZ!hDHgN!18wW`)P}%KCryOsBbwoZZ zQdE^m%909W)TCJ$Eo?FENQ=|ua_5pN=kx;{CCz)LzA3u*?DLE12vB&Ts*aBh=sbAm zu$nAa(&Y=|S+UJN9J27>0MpET(aS!zuwjyyhE9<}3(bZV6W2?+phBkMqbTPor>S54 zYVXU7>qm{MrZ@YwzF4{ye-z0^3TSv}Ba-1ZiRz?5+}BqoWd_5L!<u1&b%mtUMFQW8 z#sKL7mF@R<-9>}u%vtl|%7aZ!6&rW41Q@Mt(vAjTkz>u74Vxn_ZxYD@&an8Prl^X* zAcs{{HLcljaQWK3FD@8RQC4;Hb*fic))fuGMl)^kSfQSEHU`qoEkLE#14x4j-q*J- z`_ZpAuU&a&@7mJAgA`_Oc2u1@dG8|+R`;wHC9XeXO&H#H!XT+FlnlNSwROk37ng)a z_g1HkQCJxGP?m`+FOu`nTbg6BLye_p*2#WMx=Cr196{3+o>SO&k;>P_z^YJ$FfhS} z-Tc_cKKAvmfBlqGPJstSI6P&_6r{mdU3Jyu$&)K9E0Ixy$4@`~G%h&KIO7b~4f7(L zF{9{ReAJ2+D?ss||NQ3|d0l_~^>^KM7qV!kW9&Cf;v`6RBu<WImhdjJD7<paH2`^l zGznE>{K*iM6oh7Il$D7k5-1+)n@8?zswQ^{GAQ&b`c%Zu#M9}R=f`m5E&3-}L-IiM zH+C~qNKF<=R?1Td$GZl^z!|+_g0=yT(7cKdrIdJ2!iY))u_$b#!Io&6i8WCTZ))g| zv|zpwnbI8<v~AZDPcEtHQ8sFvbPJ5C08u&@CRkj@64^us9<|7&iY!%=Qe_zxNoT!0 zr4YaYiL=*&NtHgTVOU@3e1T`O#M5GFH#K@}-^U+ah*KtE4rS#HPz`8cm0~cMqu{z8 z4s=dVxRj&}#qUV>P1iRMP1arINSXNHloZY73n8!YoiV5Hh37;o%U*qTxthO7HO2xk zt2_3kpM8GQ&Rq?uYz!l|HS5%t-3qm?mTIU#5Tf0!s;1wtVf&M@{SW;WxrAF>T$$NP zR#jC*io%J#yF^|=8=xehPN}+ZiQDU$Ics|9@R2HkCALrbiVmz;RyJW&^~6!4`wChK z7ApCvaXO7(?X2JY;6tTV)o1?eCsau=6>Bl=2M=tf=4$&M++fxY9w@EBdSl%dNFbyi zNvrYK<$^e|qU+}wSpfADpZElbh%aauVwhlxJZjV^?jvnREX=ZCykg;{a`x=myvtMW zo0DVuIDr4Gv(6$BBf*9P-n3~GkdNQ#OD?$t<`^Y3$pXNP(su{&$5fs|WT^o<t6-cM zIBLk`qJ1)HdM|xh1}!}r@}-Xg(wg_BhntQr+yFEO;hvB#NmXLvyH3t?M}69fgH9($ z+F14g215tUaFV08%BDz~_L08%bt2tDl=r3v08|u*pelXA2SCD2?%AStZBYxJX=-U| zY-rt4)1%ku@%_@RC=-*8ebAsUOfsfdXi_yG&|8EP)xF4o7kA_)oX)<zYVB){r_UaW z${6yKNVW!Z{HeHI2>B}@##=Y4Et^z*!{LU*yQfSZfkVGBV~eGeYI!wsOZWxSr6WPt zbv<NsmeR9`<Mwz%VKsHe@LRt2$cFW5;%s7~^u>gmz&C-~SR3doI-V&YSNXn2x0J%m zkyxZ`Od5fH9m(XVUq9{#%1Lp2E}!`dZ%EbFmR<XyfxXI?Jofbb-`v&f*;nzNv1{+H zP&OIrRvph~Lw4qg`~Okg=%4<@FQ|Sc3dw`x3JmBO7}~pZ`k<c0&fo6*!?c=S)gQS` zMZ%;kbLR3$|3Q6sZrwbnwMi9MIaUCnaWZCy%PUJRJ}p|mM{U`vb{tN|{M$Eg*|y=e zv#<V$nlLiu#M#O)fd7qbQrO?U2Vece-EEoXQ@{2(HLSO4OZdWdDwe|gC42HoO{cP% zRh#O{t4jy=bx>>YMf@~n(i1hz2Ot#f4Sw8fzP$j#xBzm712#Ac%EEdM88QT5HrUK1 za~xw2_2{FIzWnmbKl;&+h7B9Wi@eT#lR|r%o%&B+fG){`uYmEgWy@~8_12H*fNq#& z$E0Eu%qEvkC0dB|f2jc)QxgtN=%5~kQsfDY?#_npNG|5SzL{rC<#ndL{1Zz(iIPi` zZpJ7um@Q9^CFqPu$0P-)=L%`kFvZa4+!vb~MtoPIamVthAAq<_wzTS#qXpSq^QxMA zNBzV1J=L#gw+RymPM9!m%l7)8|8(h&T>)EF5(VhRGK-)cUC?~Aul8&u3xH`{?hu&h z>o#@NruC}6K0R{m5VVR&MuYyagXs-z4ti_rSD^Qf->o`$sCC@rL4Ep+{>LM0D$3nG zdJe6ug4HHLCXYC30yR(@k|xkg$6}s<o|i7__IdoNl)`$t|A4-3tCZ}<&XU4;Wm-v~ zV;i+`t~~l?`@qTdc5>lI5GIUz&`~+a|JQY19qD);sA5;zV!2o}>%rQJ1y-<$6Gqhz z8*t(I=c$)g#+wozkFVeCQ&s<7>hRvy1<x0IT*Jz0vfcVBe?T2-Yu&QeY0E}tP7y=P zBA*&H(r!(zd3JI2Y3Ha&sk9~%kK#zhkbbW{{nVgnqso-IJVEL|jD2Uu>T~r+o0q<{ zW&57!{vBaYRgXS>27hRdDi3MoX0{FVrsa2_Va*+LOFi!K*MCy=u2FmTt729aXA~19 zR|bKL2%+0jdv@%usH#?#6-ik^mD7mvK}_rDAR6ju59wH4CrGIbvUcP$jnPy74ltQ7 zF<|_IAN=6F^UmXr;Z1?bd?NX1`4fZ9hI=-za5REzlPr(W{{HDtf4bp@8`xxtr}^w) zj*WJijEoeT+_}l?+^5)_<TEOqbh-v|)WO6@B4@O4vThPi(!vG07bbwg7*Di@0zx&i z8QU$|79F56?f+4ILH!W$VfoK^Os1nO-9uM{`71L}=%Z;KJq?C(X$%%JBx!asm=wq} z!5Tu+fMhV3FxGVWQfb@kaXi|*71C<Cjjc72jv@U{7NZcYb2XqF7i!3gTt{tLtG@B2 zm9H(Y@6)T-|NLs!nDN3oCK8dwFR7buUcd7|i`T<e08kGPTef>KmlkXJEDnw^@S(RM zT1-1pueOdB`>HHAt(`lG87V6-0wYE7m4OHZ1@BxbPteC2ncIK4^l(G!>$gm=>o4qV z(}58`x%KyB#`m3dN`N(}bW1umBpnGTCei^PLe40j72#Tw>7*YPkbL<F8!KRUainhR zR*bk&j+QW)Kqks21%97c*h1FZ+EQVBIf)xbI<_y%G(emoYZ5PAA8{)ze#RxjaU^+w zF(=Z2yG}r;o^dmNY)@EEKNx1guzWxE;6wYWL4AXmKJlC%kFqtzQ$`9XrX9DxMzyBZ z#w~yU=55t=wWkjnpsK+_nVdu-WnvGG-)8jg?MmO^*|Ya9dh)>X#Z@)klsAH<yfi!U zec_Vn(@UnZu-L1z#R8P*ClI!>#RB^>#iE!FsQLqI|MHjG@}i1MFH@LNr_$^1pEvlF z*{<n*V{Y_Pjtij}=I86TZQix(^lLw=g0ccw2pK;;6{2}^p`CWMUmySfW?FX)<@nU6 zKE(ndq|>~EpcrS-MtuENNx(yclmw8N0F-i0WUvzs7^Hvr;fLA%5Id~#<HvI!n`czZ zdaf#Qj1(I5HM}^N+~ldb|5lk6?!RLV<mWW3?iRdsi9ip^iH92D5i+8b@du0XMIdIM zZ!*y_q!yDB8M>e^@8BI!FU%7^>Fd_27Z<*G)zvfnp`??>ftoj)VVP#uk7>p+1ak4T z#bTjg$x}})^SS$+ab`J#$nAmfQDDeJ01iXYSH>FLlF+|nNWKvDpIZa;pG3?X3_)7y zRCE92yt<?@oA8}|?yQmHM2nZoHhV)QW5%jMLu)o}J(x;hoy_jD9*m8}A%GQhyZlh# zT|3o|ox3Ma>49$1$W(A3jO>FIz|D=ULyDA?DEvH#o>l0qo^i2nPD<79Qw!#AnsLh6 z-O6MNh?(vD1xvcsmG|luV2+66;b@E6ww2uhqWcc*9W!xIzy6lTilCZgHyx&&NGQP? zaos@g@}O4^HaDl849~QV8Nqs1Jw0zraZ%~$@fE&+4+y8vyR{P44dl@K2tW(Hktz`6 z;*9cXqi|Ese{O~U-%_KzluTPNQC2B4)yW)#;qGT8kFE}yM^9Sxx-KdLb{Ue+Op1w7 zaj>RGkM6jv;!Tk%IIS-(I?xt7_0(yqx&m#MtVxqR+^Vi-!ntQIetO=8Q)Z}ORT}fD zfL^NW#=u%;>M|`N8Xhk3l;#a4?QFnuxdVaJ#&s|MY3`n-E2az|?VfvgYc_MJwe4_y z%aD(JoY`5zjYAMyJVPhc#ut|q<GSmVX)HeTvu24YlKG;170IQLi7pk68GtE$aWPXB z3C0N}u*&(H(P)Wd;MOp*#K|+VoPYtWabo-7?|tuky?XT`GLQ`V{`R-O#qJvGXi^4f zVUaoV)L=$)b2FD@{Z=_ju7&WHHDHJY?Io?o@(iyxC+SEeoRus0$69NdAf@7B_CND< zXrmkRQ9)EgUHG31mL`8fUSOTQVlfFTKpS~kb+`1D<R9;Nbo`{j!3g9j=|ZfRPWik6 zEo?ldF@TXE(yEfSSfYFP>OcPe1?60L`ni@CAqtf<q(RToDFB})A5{p)tp;2fZ;&QP z;%nj1A+`9W4Ou%Biev^4ml+atBH%7T+8ba=t<#Xe&Lbdhi@1+}E0@ckjH?9;qB}SF z9((k~e*Jq6>#zJ(@KIg?0`?}dlFZ-s@3Ye>3&Ni3iP$(p!a)ue?1G&>S#J9Bg1vX$ zUN#h%AEy5O8xvbvCsy^8UEAYL>TiG9wsTj#+f#I~DfXLR-!-uRs4sqXY>(bz)yqb< z=|svK1nXt?;15x%Ktn^bV~agM6H^jLBe`Np{onug(ivx8a?Xdt1BcVSnR^1+?nDxI z6P92JlS3hi0FvqI9NjK6Q8;c5^OhN#BFb1|<^YQ?^9LAtT1D^h>qZ#Nj0lcZPjm!; z(YcD%6I=JHkv#{0`qIp+uN`>!uR*lD+qNHEw{FHqKh*u|i!qQ+CnPyxb^+It@{zOW z)IYzV;o-lRf4Z-a?SDLC6q03qn)0&?6ARWbwMAU*(ozJ>pWzEA(#Dl*x2#%U=2)9o zzLtu{*n%MD@fHsnq}UB8>te44(NpmDl2t1fzk2yi|E9`lHYCz~4@n9N6DR_|t{ILQ zfDK0rC_=UknwsO=d>+8bTOC2vh`4|G%U`n1@GZC8(x*=!UMCL1XY8;rhyL&X{%?ca z+&3p=hy0lrAAkID)*lZZJQ#Q`VDQ^id+w2eq#U_A5}ihY_vPr=vg;Zl)|OblY~4L~ zJ&F$?l`bAVmNkKMYJ18OySD^RojBAp%TC+^iwqn0#<lAAw?8~==!lPBGYqfcjyD67 zKt_6ctM@QFQi^vz!v_MhFQ4BUHLm-l)vh~!|EJoXR}V!JM$bjescD>Me_0a9c;i#v z@Tu>dNg>8Rs|JLRq0PanhQn&l&KBDad3^~%A8ZN`r8p|lCW2_$z=o}C#M7NN(bFo1 z*H#~1wsdRAJ-)TkyJbUz%=$EtiG&6ks-0=1(@Dq)(=vWO=6a+Eu_YRN_p(n<k(xSl z_ycoa+PHCjNolsGxA%%`&$#+uiez&IM?LXq^P(5FT=&^I!^en6%0K^k(ry3sxXSFk z<-hB?VQk7g00U^i#f2J01VSDUTfH$AmE7?^)Y_CO4SS|fpZ2St9Qx4@7Ctnu^y16M zoPU9@w$@t`5dbkDE0BON1`L+YNjDYdL6YFt#RBC+WW|v{VfkvQNP}JS*?QGBK$d45 ziNxOVdioO=z;<^(1*grGYWwcJsbodJzQZTaPy_oaUpkga`oqC23S1T<3HrHJkDjwG zx@hrpFHC-AsekGe5wdxh<l|qABLZhxbRiYS5;a-Wr486@Ys8cpBl-=N#z>%^uv9cI zu2PCiQ2vuH1;n=A-e14qiFwmzpQc6+#cifA)J!EPv;HFTrVXSB`os9&rNS`-uwj>S zOp|atIqmG*d=&_7)VlD&2CczPjJa^W(XCrI?729y*)Tx6a^=eV?z`{QQ%_|}L{<YE z18LqeC!jBmL5P4Q_Mkz77`dIv{cQ?%vOW?fn5v@@sdFI9h;YlxgJZ`|iN{X)<<DL? zu$vihZ7GHhB4NV_kv+!Ry9)hS<F3>m=lbW^P#;VleepJR-#sf^n?qN9Vi<3-$+o4! zEDvE%F*}0>f_>kPt=3J`v(Gp1e$gd$>(&kU>5m`&pW7}fMm8yvHaI7(3uK<a)Scbh z8FqzmylManY6mPddYB~R6%yx4=m@l|g=TSBbLzr?L;8<phs2F90!N~1s*h@7?Bt5! zBP-HTHGg4aCL8ycP9_0(UqNDiP+T{bJzk$Lg?tzhsrC>FFU)c#3rhysET>p~`_@t8 zC-;5%g&mt#*Kb~Z@RqMWURQhB*%wNUY}*uDvvN1^FM0aZd6%lc+%w>%g_~lrIzRwE z+hJRHoDPVk6>J|;)r>#LFd_3e(}mI!KN!_-fa=qCV)Ghj#j6b~RxkbA+{#NoH0Xj$ zRB!locFYq-F~<IWUNqAP%@JQ4Oq24Puh1u5<)G)Tx-b-wp=pXKLx?jTY8*th!yOs_ zLOI;xcpEh_ax!Yk9dHjCsQUG-L&87|c?&ic@c|2hM5T||pNeJqHuGrTIcN0=h88~m z;%OySYG5xB75Fm@Z4bg{_7m2w#SrPsL;#5dT6Y-j%38(bh<zH2jaWRc0ufOdBd-fM z@ayc~_rkODtNQouaq-2H85(*R;6%n1@-pWmXG%mquWJP^yG%G{YK4xL!ppo>MiOl# zDF}b_76D$_JTYJi(FahmdH&!3{ok*B?Q4%b@(AmWo`3%NE3do~Pgvjo{`X;R*$0Be zVTgH=*G)zy3$`U@^)N<TU@%YLk@<d$LKSW^r=+Kg7J#~-C2{^r7(YHV=PY+wWp|Ie z!t#`{kdwy{5L?=s;n@zJ%sgfCse3o=FDpG!BtyEarLV;2&3omFE6xuWiT^l_+RR8< z=D?n3t~`j#yPXU4FC-sX;1_rgsVhD@b<K+U=jI75paeV>k4K_@g3|Ft?IrA7;)PiM z{2I{fJd-KmQmSjpvv!i1G|eOoq5P>3_Nk~X@QKBi?QZ1B8BC%GqE>*)`^5~%A56Ku zF&b94t*}U%%*b8~B_*DW-6lju1Dk{CGrYAM4X~((*KdT-tB+q-eCsbp{O+#P|Mg$5 zuv4Xr7NBVn&1_{=u&5*xOVq=l%i83i3Kg-rf`!v33JlU)@MA*$rDMbT#^bT->I%sn z$QIMBG>A}Krl!oQZA~V!u3F0)^V-^yTfVjIsw>yt{!6uMx1^KFunM^{i|a}dNskUW zGJr%*E@^kEAeBe?D42{e89#8NSi4C@X!Mndh)mIQpCAJtrIh{<J`WkPKr!M7k#e~c zxC5mgY2kFTvAG#Em4OS6BTvTZWpP=rS*H)0I7w=sZLp9wlaR=|rPiq=QUz0`5Mo4+ zg%vI={ql=c*nw~c`EyA{oS7Ht76)Bk%MWj!wrjiBjr!09s=SEZlf;X)<#Ex;1f3+1 ztaKy!fUX#%c*hjb(VF-GWFB1K1_(i123{V0d6&1?$br?yfG%MC;SYcKjyvwS;DQTa zf`R0p{NyKax6oYH0h^4B?3yg_z=fAeUcqZLF1idtA5-BAkvrA^jbbJ@z$+s{COoWm z#C*Zsmds|*)g_=NSZFXJWN<J_b#D>q<p=MnVb~%H;wTJ0t+odB<RcsKQF{6rVk1)= zQSoHF4afN^>}19E3Vx?!0Xlb%oH@(7exbQ;RnuLaGX0W!|FjTu8-h@F3d100SqVIc z!0<75>CP3S5UUe4fKnhGr<pLytEf`rCiP0&2U}a4H*XZa2m`A$)~aH>2~mck+Nn%a zX;~0hqVHiP49(;iWjDDrTr&ptImFUaaX2EG%GcK6#H00aeMY(=2%#6ALBkslsO$gb zA6H-Ylb09Sg5niw=s5M!PvBC+9Vqew1E@$o_UY0)@BP%IY1QP2;nj|97})OU)i+Yv zP2oh#w!v}`mfj?rM?|Ay5Zb+aDROT3c$hekk7)suOf`OnDywNj*O*Quk{DkXjoi7d z@|LeJzvd&`?gWN6;f0IM2xROyNCVsmv9WBFHOQK0=|nZYUr_{cW$b9^6YiZ~4z7&Y zf-Bfa%}JsLz!)U$;6NKe08#{ovV0S~a6lZFc!Jo_1)PAD!t|S^5mtFgaTcp_r%B-} zODYi{@W*}SJ<dHtjp(0>cw+%?Mzp?K!JvU3ypD+jOk@!3JEal<s}&`09Dw&)nGjx& zS$F0re*#*7#DZ-HaZO=)hMziHRhOu+%q6^@U<?KrvOsr|hLcVu<cgo3;mNJ86hy9Y ztN{oF6hT(QKk>T3*EdZE5>I@C(3}9qAS-^g%pLYq;;o4jC$a-EGvyMj8zJr4EYfC< zWMOjQMeg8!3pbf$jZ;j#aj{ubDMHdh=u8dJ7o{f}#z95{;x#6r+>=$0g0F(7;(!DB zAuH!tTL;4mqo7rHM=&jizWRprZ|T~Q6*+aOL;KZ|S9YFx?j+EcF~V-1KDX`j2jOy9 zSQ1Ymhz=o-;vES(WsXuVeaS%zrmx6A4|^7VBzX%5hO9p0QKTHVFx{S*H*e?mNhOuu zkRM`c<pvuz9W0lERVjqyR|7ak(5ta=p`bo=nOgLMZ`bz2&p!Ri#TQK)Hk9t<ingky zOE8k(nu>XS9#_j@X>u_<W-SR`k5GAFZv}+vwVg)!m}aqzER_>ht^WXEEZ%S^mWW5- z1uW6-+KDu?b9HcEYjxSs{yk7FE4B=PnOeI6W1T~%%@Wxp=n_v`)jg$S(K%UFci%m$ z4>qj4`AgS}(_0u}(T=cyhE7BuwLs8BvZajG9@0VSn66AJ>GAmj0gGMgE9>G1T9|6| za*}on`~0Y4pR50p#RpceT=M9nb!VU3{o>1HclmG_eJN{t9OfTKLaxUjxpAD&Wc22O z47%4(Vf9F)_6V9rcs#Le(s7GAfE5Vo1X=}MbB444oiMCynwL!>GY<F|jh<wp#qTeH zk;R8JOfOP-WY<XCs0Nk^3y%s4Q9pK?SFoW%T9I+NSsWQde@@SU5d-Y$6|DS4zQVR0 zw7KPSA@ru?s4h||R0TxAWfpkBJcqKNMIcb@969J}b*_uY;oShRVM*olv|y;?Nqe%d z`=5`WKgqB3HSx@4p5+Ck4aV~ncA2+ORkGFCyeFQFwzM)UMtQ&B`4_fq+B|;31U)<? z8D7yEO_5#G3?}8m5pbfLVhuq>dA$6C84$4>EA;5S%r;pZe{dfLCQ?=1dux*scUU~y zV^{?Xf}Jts2mu{D02`$+;xcKsQ^X<y88aj<JSYMt4~`KQy`*;UZk#@|2WmFxugc;) z+~bG?H4Iy_j#qZ7OUBgULqcugkC8K#>s`7@CzVdRS*ql+V(Dy<*&WFzV?Mv%hgq$S z%?_m%AteSfEM)NgJoS%9Uz|93Hf0dNr5NyD*$fk48Iy%@+-iWykd<J%<VpEFzA2N{ ze|~4$owvXE^b^m2^-Gz{K0K|cM9qJG_p;@?S`I;1eV(lP%Uz3JSrohFf96!w;mlbm zEiz<rS!nx^%Fw>37+h{hF(#h@CX0Q0si8xv7B5<T#TC=FqA=j~#=SugmOv9Gl$V4@ zmHAb=Q8h%>`sM0@x${1I{rKsVMFo=1co1$Qi>9++<bUTc6H69s`p$PQKKndTC$m9- zh*HI*C+78(fY8g9HllAHHAZ?@R<(KTVvi@xDrM#bH8pDLwBBpi9&j>o@IcfniVcl1 zfv$@uN}qW?{?rSvJotFc$FAu$d$#IX%U;A<y-EKCBHj(feJ`7n>c|DAI64^G$^2Lk zEJiq!nfAaWIPG@(fKOTquhufrfl8;c40P>+1?)q11|-Yg&!m8k-y0~w;0h_UY(8j- zl-T1B>9xAFi<n!nb0Ib!e&#*6*6`q81G6o`O-X`()ENKZv~}e{bugEfT*VHXtWa=? zskJUVuq-xj{Nz%mZ2H7}k%(8iT<B`uLD*k#)YOwfU(Ny4b?eu%N0SjvgSB|ediL38 zM~oQZM^B(b9^K7l;b>}rUQHK8`Kp--ncE{_WANCHckLSW*rU7WJ^o5tYjZcYcJ|?4 z-PLEv8T<FfN+MM(!z(V*tO-&yrkpNzV#Sn##zDm;t_(a#sKH@3!Zp&AUE9{LYpbm6 zQB@=H9Vf{wmL*6oZx}_5UZdgPu~j|#(3+h)_l8Q@E5=n-((}S|2lehHnm@3X6d2eT zWXKfQNrjPPGCr9<fbhb*a}=)|DB)_mM|N&)LAD((W(bOgiJ3by<3gh!-x`o9T@slG z-6fN>@tNa4>m1d$$BYXvnDOeXTmSx#R~#!jX8gF%OzW|FRcghnyKpue2`9?R8=={< z9tm6Ml<>j9khiTh!|afbgriBwv8?pW;-<=7f(mxppckHA8Ec&$EK%+NX0u5QZ>nm- zH+=TYM;=)B%U^8l-rLt2i`$91E3Z8Bth1F5)r4N@l+q@@EOz?SANL`u`TUKSo_4Nw z+kh4lst?&_YjUg#z}sf^+KMeBM%DBkECYv49E1g9*ob%<%`rl|>c9MXf0Ui(<sMI< z{64+o5*@ixxk8H<Z&<PN`Ds(b|8mW&Qzuu}Q~)GMibx`d2FJIhUYGk(<EH(x{XgSQ zaL@!y;y7WSNfsa!F;?{~oP8#>*n_DE54|EF21J=|$77bCWztkyS~ixFB}R78?`v+0 zmIU?Qj?AguIk_CdECE!TmD#!M=tdGqv%StboN}LNkhY_u<m2Y<clal#T`hDu0Pa{p zVztp87A#o6{t%!nU<?fN2q`pPqX!Hc$T=a;jwAHu(r7o^-#&T&3o`Nb3;-D`EUR^4 z*o@19WsB8qw{BhV{L-N#yWRZNGiS~$V#AVGm#W|WW>@r}$4**pO$l-9%V4uxz;DNn zyR0zWb7NaJ9KzZk-jmjW0I^I{j7?y&m%X~KuC7P7IvE#|saQ)2Qxl890;{Hj>elaU zNN4t6cjK9ZMyvY0>ib_^V#g2N{N+m4KxI-P6u8hQzqsaU71LQK<RIV@S&}AkQWgnt zQGNPVEnm6~#vK5L_qAmalo(PTB|S6o3&;1Z255AAOG(oUT}6@WhcXWvse1QQ7hm2l zo$kloAe$Ju)vU98iMIZwMJntUrEgg+&McU$xlvVQ-6&8S{k|~WjF_VD6M3ij!a#(A zeeL8aeV=`7$+B0~#2G3aV9JhIL~ybH5Ou>BhsF~_u@j{uMT+DHbfYT_MwohL>H0Y0 zc<|4yt5(*3=|3h99wK&I58S_Q#Hi4O3BBoMv9?q&jJ|`tf7J42>#zU!Gs4(0#My{m zT+B!}#CTd`@Pvt~rd!dLCK1?Tpa5vl!-b7z=FxUYsonn2{_0Y@$dgI6HrRG07D$Xc z2j!^ffpb0ieQTG0T1M1B94}SwQdVe*k`;a!8o>;O(T7$RA01E;rp@9gN4f#R;=_lf z0k-dp@7TW8o$51dTDV`|5}KBH1ZFjwPZgF|DyAdW>j)q8Lze?!@Kxif04i{6<jH&Y z?uFk)NsJE=?m%&I#IbejR#3U$fd0gUSIz@4C#3K}Z@A8WpC0g18_)+x2P6(0#)9eB zKW%yP@B3@&`hEWM6VAL?SY!mkwY6Y#&sDFsHpH5PffCpP28ACQsnIv9im<%E*#N9& z95;JyZN;p~)3{Fhv8dX)>%h!e{b5|$433FuGL;ox2-YAVjtQTAN-cbT_kDkx16P3u z!ks%)^PYUVy!gD<*2>~CRu70=8Y>HSvx%ntWvug~php6Q$CQr=wAjm3*OWCJ+|+PT z^%=+~*_z~QYq1lSvK{%*6a0*}KtScPQUL}s#?B~J+2f{IjA8@>X+}>9u}L)&7L7vy zq+k5{upT|>b4Q3xKXkhStxXBE6|z&USP29f^mIH#W6_M7eOlSvJL~@T;G$Wxrva8e zUr9345@an4dSX<F{QSZ<g9~`h3VCE{C@gL~os71+AA4lW(@!>?eb&TyLOt^wjw;on z7dMX{JB7YRuMUNZNsuBv_&~OzGBRyOHDwG315yM4nBGM<#oAC=NTElL?7m}blgkxI zrjpsTJRp`k=qitd&OdL$<cSj|O%(YvW-VALp;r|{Y;o{PtP?jN?`3(F?ZWY<FrZAo z+fB>#JRi@nvJoYQByCZ(>!3PNua>>iv~qR*raiAUH4gpkHQ^rJ!R=UETgW4=PL)c{ z=g^u2MWJ;<SCD+vv4k!Mz!bitNtXd&Y_C`%jENRN%N^nXvGBo9J@wRu7hi<gtwCR& z8u4|31J3sW28+-z7Th7*_p)ePoD8g7r4}yOo>0N+?!jSWgfcP)uvlaSjGe%s+U)j( zBPAhdBqS^dJxlvh#T{x;D^{s_^EaGxVeQQ6kw7sPRd6kMoWnN41KYursi;VJ4IIj$ z&GjRy!@X|`14$IL)}qDRm_j}CjQU8O3Y4m%V&7GtoPFtqqoB@-sHlQku{({cd+*)v zxOe{RrzTYt%LH0RBSRWjy5dGn#DkP75`j>9U|*1gi{?%gg=m@C9P{KFz4=z|GAEEz z+{AKZg`4n<eld~~Y?1?0F<e4n|HPI_7;2!IKyhkeGUL#QL3gD7fLb_z>+UVS?VB3> zzLNXqCaY>v<0lvQ=?yxfe-$nZb1DQbSAO*T+kWutmjJgwNWT_Ln{f&T3RbpYfw%ww zKmbWZK~&HeNhA~OoCC~d>`YM@D+kJuz%x0^DKOT_I=0VS^x|`SZvEav`*xOYT9;{R z-Hs?N9&H;jrexrNZWNH8NJ*92woU!@uYdm3^_SQ5p!c!eq2EYP<s0Z<V)zRxtC=$b zPd;`ynZia0ua)37?=v|~R#s&{cD0%^QLssrlhSFEl*+;%oSg|-Vm@)A24+{V`3yy| zb<|UOIqE^j*kd7fYfK$FDBDrJ`bv7y;-<};nhrOn;@L=~W<Xu_(D7r%4~xGvMD-;^ zUM<ry8PGz1OfoXwPo~i20N5ZdO<-UcKMX7efc?b-B_`9Tez`*cYv~5Bz4qGj<;&;H znPaT34CBj-CsPZ)?Y9b15r#r~HwqiEbe2URtJmzVKbR=>)K%AIyCMBciw^;m>8Pj} zL0Kp2asoK|hAkGIaax=$|LLBm)@@KLRzz04wr2L6e}R+H!3-R!aQx|qLIH$@Jh8Ok zn6Z?B@Uf|<jYU_m_kg0thqm2%>n|2Ao>Wy^cG{c)|MBf9P*sw`l5xYv19#r>?1B9Q zpLuTi`R9*=4Fb_wOiamzi5F;<Am$f1uM=x(OV%rh|0^Ep6(43wZsHY=$E^lT&%pRj zrhZ}%qtddwsGg1Cj722Ic=^@a(&NiW_e+~~-b}BOu_TVJs;eVcef)f^x%`3F=9WXP z&As(j(9$_+VLC!{lREc2*Sb}+?!NOMJ$szjvmaSln98%}7)vdW<x8eemte%@Br_?$ z-mH*vfc!mscEA3HYkZz6*fW<i6{RnW;d}PQ#4ktofr5hv)IEQEdF;d<=Um`NPzpex zpN4l82N6tBDK@1?SL{&}C#dp@<euGa9$#g~gIj_W11S~DY~R%M;N0>deO%R5qL*>3 zHY~#7jm1w4oAjLE!9%SHYSL~=R_M#*oxz8mp#HG4e$(DXix00@W^db6ba;PtEQUYm z2y4&6rMr{OqdxpeHEf`sFEdqP76bB<4!wnbBCb~C^yCX&4uCsKj|~{(d}Ha-rHG^9 zp8#5zT_Dy(1DkPOiDycfVA@V7HSO8H-^0n*ns4}GxC<|aO|ozg;v!uh`~qcLAtJbM zX3E;^@%1)FZ<%z$u>+7qpSL>Us!1gx05C2Cp<I~upL*KN8M6W}E>LT~wF}uGD++`c zu_2*ZguobOu(LD+k;G{OWZewWbSjB!KZcdd2{LRy@`-L+caNR_<i<z;y3XtF_uxJC zU-;7W&)%q7Vyd*nE-mw4bM57Dxhqz0Xlh6xfyR#7#xs!zXSDKNdZvxaS?ru0TlVCj zwPhs&dPSl1TB0eLy`d5cH{Qn@z}XpnfR4k4T9U1_NG2G<4ocP)xxgUZKuH#dyVCxU zH<eA$b4&qy_x9J;4TX)(H6u;x!ajg*2B(BIpERzWvCGRX%<`|he)y06EA{Y$8@}-6 z!Lq&u>mZL`Yy&;$p(Q~q1K2{96I2@z4J0um#;P$BtC;YKkcRC>=)-K`gUXo|Q8H8T zqDFcAAG;fy4u1Nx=ds|8APY}1!sj9Qk69625s8n6k^X(vxG`n>_9j?#qtxC>Q-(Di zj_%l0pNN&*ch~wJ6+=IBgDUC9bdja2(t~61SR}|Md?#{%YlWO>eYQBOipA9SE$XFL zQm-!Gv3#X!YIHTXmZlRSJLS*X%rzh#Hac-TksQ)bUC3%M1RX_m1R7YkrZffJfjVI+ z5|MM^WE#R<4uJDAWCOG`$xAQ2gbtYdz%4ppG)%C+tXyJR&C`Vo7uMI;vpbWf$R|_N zwRhLI{ZFR`3h^)?^Hu`<Fy^MAkk59<A!?#=*RY&n!y*s9B8ACli`k9^WeT^&7%!ri zg$d~0Hvmh@>Vaf3UWBhAK|KLxp-0d#m4b~(Bx0#d+R^@mc<S-7oIakxiw2BEy~5qW zf7~+lnk%QSTce(P3b*@9@BYJ+AG-9c-u>Cfu%)WH6j?MJt)Dr7<zclb`aesEF)7Jc zz=@-8ql6S#GGQZ>oTnBZQxGxY5K-ZYP2t|QF;9SpxF*68kw{JqcSFmGi+x~7T1hPO zU<xru!j?+Y;H*!;jd_<4A{tl3#WW%vN*K;)5Esn!Sy_F?#LI&(D%rM{G`+GS{8QJB zeeAJyFTS{a#;JX1eO@<HNxA_LE0jdf+UOi`Xvlb&AVw3-p+Ffqpqqv#r`M$Iws62B zc6`d)a5%Gj*M=KEe}1pQ6iSMmNM*x*H_L3;DoK_}fwgu9=UuF?E3Z%!##cWzZ(A(6 zzt`Z*_rB-fyutrJ|GBeaS6w3E`t>i@R@Du==p!mzDvTawC`Zoo0SGb|QK^QO4bMNd z`{~E6RV%7@?=Np^tYHygA|)Dq$cor(3S*4;-V^X2urs5t{jlm=#TwxR!0Z;0zKm8e zz>;+i3|=amWF^SiNff#wxx!DDa5o|>jqlvK6Zx~z`yzRUyX7Y63p^VWE!<<Vp`nRy z*kT4=K?>d8g{7N|1qdQAoMWIa)7B&-Mpyd$4Z(nYs6N%wC@g}{8?_)V=y6c`h66aw z0QkUE%ukbP8_O*yC*~IfpFe>pqJ5l*t_}VdUZq<%#om<r_U%VdCluE#Nx*GQ+_!a| z`tCQM``M4zvw!x83F@j(tMC3)%{jk_Jqod8hP7bve%47~s}hZo6wH%YPowTNRGdxg z7|ZY-c!%Z4OgSD;y1l7heOUA&W0&QKz`QM}-2UB#|Hrom7{0U%l$90{)&{`{y@VZw z^y*E`@`z==g)OXJV8+Z3RD@N;x1lzRB}!0law*e1Sq8@q8)*nyNYTscq!2#;>-9sY z&FaInk{~ogauK6EF?Qmn)=zNcl7e8ET@nZ(K!!OB(YJwI))Wb(`*Gcj)VgOM&)2?n zdf!3P?SW=GTacM1t|PEqv^-AAfCX~X1oJ$G#I&iQnko=!&qqEybi{CV{<-R=o5ni! zL7!E!uc`b8Ki>BDdE(p#6KJL#xly5u+ELEO`H4cWAS4Ms*PHdZ(>;8ivS`A0C>oBZ z!q`H`Q+UNe;)Sm>NCz5TC*Y5}ef74dZ2UNN+DugxNLqf|9b|4qK$yVz){UY&2#Brw zj2us<KtJtTf$j($r%X_J++NO~KOgoNMhy%$h|5iw;MUewjIf9X^e$SoXxp}J0JGtq zxd}XXt*<(6r2)#QOxRx}M_`z^nq%$!z(KBwle@<fdk*bQtX`sBZP*c4wgUI~JGZH( zCWwYRTwLCGSkRGe%+ndPYXY;Z7(w97k|b^Vlw)kDY=jcfte!o4(kS@wBNwO}A)B>u z%lg;**Z$%653P7*E22V(YCNT?YE^X)_E@hUF`6b6zT5=Z6kHr7voxhF8kCX?<jbs@ zc(NgcBPzh1J9byq1Xv;x$T7iQk2`>`>62~r=4!1g{X?h-{muPAKy7}&&0HA`kv&r2 z_WSL3g#2m}4AAQC#Whk8{nPgi5~JU6S#egtX{SiJxt@NJelCKsT*$p*BG9Xe!v31N zf6_&zzrdtvkLMIbWI>3qwW+hfyaal&p0er-k@U!IHs}NFVb1&YSJl;R!-odXJ*S8T zQQa!kMHi`?zcM1BHo3jtZF{n}{cOpCMZ(i#AtC9<TY+MOzIl66DA<WYuV8CsUkX>7 zDsq?2nl|M>zB&7IpRF7@$}aEbFA3urjOu~Um+xhkoJiZDqSmsC9_OB?diG9QVbd^F zolz<YTcEAOMP8u+n3+mDCD0Xq5*##{>`LEh1k03&4tn_T;lKa=@0ec!zyk&hIRE_f z`}FAp`qG2XJ@?#8FTE7IXn+}0ER@8?krn^|a-S$O%J;nD>CRxTgWV~Ul{T$rq06fQ zunzxk#PH!2ySFv``p3K1zN}hzt1T<l19z(Letn%QU5(m!`=)&xUsH$n;d&R9S1^{q za77_}E((`nNF!VgG>Z|V2^HJ`h&yyxza2ZaW8nh(%OI2$oM3Z8Y(dYMbK1XMcW%Tl zwkX(PuU@KNS-k8^-?$LxLLfIzsabh~Q5A26i-N@^MfgIBwd(YR4<^8ac#ts)Ph+c1 zo3;)fUJ<Ftjbyn`;KR&`zA7A!M-9*?ut-m%*`wddPj?eUun3@$vq%H#MwEt<%`;?` zw*W1@i00#mYQu$cq(v#3ABrtYYjZ(h7<e>qam1Rd$+4PYqaEz<1?kBRmRdHNHQiGB zgZY6OC}PM_GBv!iNmX;ECXPgfw{AfRL$}uKG0A|Ox>%${7DQos@4*Xih8R72su`z7 z&N{c-_%Q<9KFh{c^%b8~7kxC8@vhI<@ioh0xBhU;>eb9*NjoV@P?FXG&^1V$`??e1 zpDguNsF_-1rc&%xy=&FgSCswm2i-n>Lqo8}7b<PVFe@gGtRev<26j`TEi`77I{O^u zj^I+og%d6PnM~{TJO{~u=_LZZU^{h96P{Fodgxk#1-=vr5aonjl6LIaar)_}pLNz* zXU;hT7to*o{O1#i1dmQR<rFY@`}Xbk{P|C;P(lhlZQ8WDx;nVz6J<L2{?t1ZL&%Z9 zq(B)|P|n@z{EJjs$;3w<Y*{dW(Pyq((7mR_vfasaXy(kB&C!=pzcsfWxbcQ<*IhsJ zD_<IuXv>7c5oE%#I0js4FGk3w^mHGc0o4v|8Z%z~{?6^J{i~@n4vb_Qb5yyPUomX= z?%hw%Th$UB)!efF(BZ}f3$|Wy#hi1_52G$hrxN&iX6X3?G7ei~hoiBe_|u0tb6a{S zw$5yPqBn;~%d-CZ{Rc0-a<rdqL10g`Tv}p^I2<W7XN7RQY5@9~M=WsbNYIuB0%f$6 z={(?>1~s}RKX3`+%yYx|8am7+&EFv%UXhoH44{GXDd;wk45GE?qzM{=Xx(q*rtY7w zd&-5Z1|Sil@ggVszx*R;NLE38Au=|Be3`Y1Y7+;<5GR}wXC1r|IF`rzkt_Ry#InVc z@Y8Wj0(<odeC=EP_8iVES`<}I@8_T0dwZSL>sx&*!$H|>sr_ppQ-)Fj!vu4#v+L3a z3uU^94tyxIGN}ZTCy+C>yFS{Qtnx-u7<J+=C7p>maKAyPxU~0q=cpcih~u)oMQ)S~ z!tN3vL{b+Vbw8l)7`|vBbo+Jb8u;fHuFHKd_=<`bbuYXuo${7jZkaS`5{MfN1b6M+ zi5*rX5`pW5QD!HGapT92n=pQj4%lbG_`)kwK}0Yo|J=$t;Zmb-gPI6#QN3y86)M3l znoLnq(o8#DO*=KRee2n~wxz|lxhLCyh(A!w{C#p`v%^A>Osc6*&mxFhAml;+DpDe5 zsTrT!ABZxWcd~xmv7<m{>l5}cx7Dz*YQWIqr{}GlG-<T(#KPL5=kwO}P~Z5^Ggqx? ztgm11b+-*1P<q)FSCv+XT}&#GEDEqnlXWA$j2*$U(jUy&RwJYls~B3+BNA`zw_0ps zMeg_PGsv;M<0tinVjJF9D;xk{OnD3qJ>eSagH&Ln{?Q00pOuGFPWYk7@YsTXfNl!; zNCzGlOf@oIW?p9U1%Z}MU`VvEu+jy9L+*i^s2{i_QC<|vE{1sGKbXYnlPmx-F*Ue4 z>=2-#PdbP$iEN|99j(I<KXJ?pAcoBT^D{W2>HC^Zhpz`5v?^H~I$Pp$K8gMINOUL~ z%5}nFl+EPRub=wrmj`|IE1Op=P6dN~9=vx$MN!#*e6y4c5FMqpKP;m!JF(DLs??^o zbsgGiafSEX!us3)c<8C;db;f9RD;Lub;3a>E@H^6HxL;zM9rC_mwAaM9D*QC2MwaK z<cz8_O-xnG4J|Rz&7>cm42LcUz<Kj#M9MI}`8J5R;n^R>3ft0UfMHRbXsiWv*}f2` z&@?%{nfOG=D}(c|pR^~&E(z}kSdhvR5QvA63bAKyOT|2XZ*3pffWbnl#0fY5U257) z7BsqGK;3q!5gFMjhbb&?u|=fqD#Bw1_E{bP5cF-wJYKBnrOvu&^n-tX;*-~o##IoM zD1Z+?)+%|e$|^N+a#<);1_h2G3&gdcY)~Vv1e5WYKM3Iq!UjhZDiZGQcFE?0JjMKm z_N1kS&q0XEG}%@UJ@m-fal`rz5DyPzYUrvare;jb*A>EXssVbKAt{20n#>AhYT>ZC zL92>nTBH@4<kB<s0x}w!NBr`^ut)k*x*qZA1mK$n0BzokpHiKUd5biW>XIFCfNJ9F znDVYpS@(|iQqgh5@Ic^P0zgZ^!hm-*B+D~yl87YE6)zCTB5Sjh3J7uZ>M4Y(c<alV zZHuHPopt+}xmwewsn6Xo;CqL5Y}t$_in6(XUSCx+g@s8h-h+rqS~@_!P88m^y~MgY z_-6d_ELgC6?gOzG7L{h>O@6y}Xg_aN)y5ZI>KQB#1by4A<ft>}sO~i~NSQeEsh9__ zYbcaNDpdCm({xhpOumFSHaBv4odo~7-1h>aKrcb&P}wX;V{8=+g*ZV0O!tK$&I_IB zzOc)*R9=h&PSeyULECli6X989UV@9|i1^|#T^|NSTwJ+4uBLFPnZ6G{f~hHNF3d^L zt%`B6izb~*ItV1q%eYb7wyU-4!Q9Z=wQA39ap;lTi4cCn&?>K*bMAn$lB&P|tp&ZW z7|D?xzK)=-j(F8zX3SC!_ILnyq0nuK=2)`D&$5tc*p6Av^=i`^)q1FA@0Rjy>r}&j z*@a1yQOSV9V8iwFyja$bUHah}Y(<A*wx!}O7hC0+j5LkxT&)yhy*D*LccHQAX0m)7 zywXR`F+ac+21g?BgHdGH17=;gGA(tSh;mpc3@n+a4Bp)Mg?0<_k(8_~mtl@61JG#T zP+#(jelD+c9QFE=ck>c&qKTZ7$g)UXmrjoQhkQtbA{UH=Tr&KV#08##2k?P;gcbt9 z#O9b|2Q0==5nSd+G)#aKNQxLfOcpP{Tz&rYy=!aY#o=xT57hkdwiORQs#;M-w+HAO z<O@<}IEVJzUHCuLfvpx$sPEgM{`SD0AO1M{=p)6^L+(mXYI=X~m;OclziZM}waqc7 zIi<o=$EpvVtpc8SD8LqkNe_maG#s@gmg-a~KlHw01&1zJCT=W!klQC!aDV&T-|kW$ zY`P;{EU?NsysYV?6tbzY@v+AqJ8<9tNPOz4r;Z;#UP>-nz%2327Q&`apJ0>9_qG9S zCNXU2$O=s%D0Fb>1xsy3+>_3@nuQf`U_NCJ5=7GgZI;!R?6PLzQ=O9GC=ilmJ#hcL z#~)w4ZF`cPH&e+SYgVm4bf97Qu<kIx%!VPkdS2UBSrKS!sd(n8=f{s9R#l}E@hpxk zA#wnCI-LsoiJoEmPPk%d8EZVa#LFOHym^!Q;~!sn@x_L8I^p+a_U>t3yJlst-Zkar z><o>B+yel&G^?NgZ0_Je{Xc$f553lqCC0+0up5MYouQ_NX1=#oT1fq^Ye2B^EvP8B z^<1s}xsIk=?Z^wcGwza%2yFC;IdDPh^fn%8yle+o9Sg>q|5{KZuuo2O-`AzU6%Qnp z9IVsX<rNLIxtQ{*q|c9x%p<Ppp)PTaj+k2{-A)D<F`|3M=_(v8`++bKWdF_-+yLW> z-VQU)^mNc5_IoH<x^!DMU6e@r*RMM;YgPqz!mPNX5H^}JEuq3FN%r!SktPKsR|)x& zn9I%{nK$SvlEQZ)m|TcRbjkd6*^-dHhq_(YnRwi3Q+sx{{_*bDetSn~>y8rqu9TO$ z$BydxA2+Fq<CMS1wPAa7=b=n#$$+o?n;Jb-1tMvq*mbePIF;vOz9OCj^cH3&eKHr? zBqh<gb*|u@__h-uijfy}t%8EPMoPm8CCj5}ezs^>UMVy^md4b9tAgZN>ZC)U`XCn} zKi=d!5EHyx=z!s|TUAN7$D{(jMMq%-dbA^<T(wIQLfJ09c+Q0v3urUGg*70WR?0e9 zHRJ3)>$qjNY#BrsUsiXZzUC)CedNEse_?T%7+a)mq~EOWWf?b8Www0F4RUbXjZb!B z_*Acf>gKObq6|_VN<zNQDCk|*MxD>Tgu*o4b?1{_EA`nMrU>5wYfQ#s^{R;%ugOQ| zhOj;>9F9i~m{u@3cRbHGP&+0bDO^5U?!@#@Im(UvQ=!tdxb)QgJrh+YMVHi9@{BnA z(}<jptluGqejt(cd4~jaDkcq`0eR8W3AxC6Sje@Agxs+2LOhL%NAFN;TkI2pas|8r ztsKBre0}`ejp1Z+(Cxoi6mpGOx2o-?n>YUaH-q|@NIv2pj%pzjrjZ^PY?&HMn&ilR zekSOWw_m*df0GtRL)i7KH2=m?>6rBMxe$$WEhONSam!?fauL|2OjaPUxf!dewr<{c z`>zi?@VDAF*5dmP7DuYjyR`h%pH#zpE4FuT+8P-)V9U#^dXF8dCQeb|GMU|r<c%UR zrY%?{sUmHSCAsLY=O~}eT!wH|A?4NwIlQ6&eULx)Wc)Vz^N}uXF7iiB1aLOMz<6D> z*VR*wiuwF5oJFIn#X&CSjX^)#zB=e}+t~~ZYV1rl4RhPAN`35_>7lT1?q621CYVv> z)m{l@u$ig3E|SiX?kC$YP!O-*_6Hr91G3=90$(n@IP8)o;8LKua~Cu>9lY_zPvKDu zTBToSVou39)z_~pcHyFn)c~zTFvpHX(+z2wv%~GTqD#8N7<AD|b$DC9l1tx2>yTdi zsd-MfF|gWxyZwJYIk}O~OH$51(J362zD5r7ijl;CD3%+^6CIx&9X@(h<dRE9##6gX zLfu|o-1^OL>}NYNQxbVeoJ8lZ=<DsNb%aKV*O}1%?i=Igb9mz;?(h`Ju=oed2pod8 zG0lw&H_c8@dfUPJLu%>rE&ut0Jr6(DEt+8I{lT)pppRcx{-vAM$Wba#qI|`wdtd*Q zsqrEGYd?CWDzBE!p_pScUJ+8VvQV~e^vRx99Rk_OygvWc9Uh$wr_#3yp-=<wSOZ2H zVWM$vq!DsS4?>Qd6|)z=y9l)`TyWn$>I+{ud(gmAT&ke%LEnt}o@g3~O&UiZk0jXs z#N<M<+Jr}q9y{!sPh37^m|P3n@j8N{>5dSQqwcq-Rrp`1f%m)y^hnTV+lG0C{iHv_ zXtO-;x*NJro><Zv+vLs`EquEEC;t^?%V8i%*79K8jkit|<l>l%@gxo!W!RusmW5Ks z6m$YIL1`ZzuNxE$6IouM(JrTj&1no=EV*t;s-~>ctN2q)h(!oRNm%Qp5=qsTRL{*n z{N=AlA9%c9n<tv})K^sx|H|jxH-1X>Dpl-06;N$#<rs>n(c{xoW~wRE*!eli`UYWc z5fFIAL23Jx0(RO2UCQ=J19KOCCs}yiWaK3K_QK~LLk$=^5d*_{n-RIx!&J<yWVo_1 zoZLvHRBd<Fy?ZYNPWa4{^&8^C-ex?yg=Kz|&@p}USl_W(mKMZiK5LwYv$smlP_liT zwhvu-LDskANBEm$P`Fj7f%mEg4D5C2jYwo144%D7Cy`FGMVOjAUETDhfnU6N@7`Uh zbSyIWuGQVjr+)EkA{~;Q{gCytP)hdPWFWx=YnhLr6MrPzd06Tgv*S5QfxGRvmt!}X z%CaO(Dg_=?mtG`cS`?hKsBk4(Ld*&hG3TCpcmDi$zHQt4mjxO<t>LKyx?g*#y6iL+ zOzm%6t*qjRw<;Az!evDURG;~k&w{=P0Rk32Y{hRjIb&2J`RgKd7^#x2&h)6#N~unU z@aEL;Wcc#JHy%?B80a;xbUa5ZBukPo*<yJK0Li*vkBF(8nj6YW%G;vJ(h{t&w89Pl zbQp0k4&RKRbWF2DE-vihQKvze5=n<$9azC35^2(qQQI*oMz%JRd9%b#f`wzD2L9<a zU@%RiSbN&~7CoIEBP>^n)pczNuitN-bD`Q>f69M;ZDCt$D3++Z<Jar@4;gyVWh$1< z27L)XJ9q*{>`lPz(n6j@KneXW=<^$qOw!fRCupZbE)Ggw&bXUWm|<d@0a9XZ!FCy0 zaTJiWeVAG7+@78LhmC)}H@Ib=Kj>a<x9u!e<1eUj&MLWg>Cfgq_jo)S_qu((>IPhX z>D3;q)Ex^>?>~d}SSp_Opi*+lniQ<eF#eFN$&AVZkF^>gUm$t(CRHi7KiJ`2H1G$z zLJD8^b~ON3+7T%cB{4!7IOvPCj{*&gBDPAGm9U;NU0N#W3uFrHLS5t^gH8{{x63F0 zOyV0RIDo2J4^d%%a|Dkw5pe0)W-OaQZ0_U}DV!8);Qg%u4KQR0oZ=KYgsT}9Vwu(D zA5jPQPXF0$OJj-J=BCIuzqY8ddfL?4tdlOG<4UKNv4kX+_vp{>ia47QaAZb6I{c0r z7x~9XpfO`4BN?ZfNyZ!l6Xhh1Us<o9)@^UP`}gbq_?xms=Kr&I9&mOQ)gPaCUvJy{ zrfez+X@nA*NJl`bpeTqU>PNAIA|hD%BZ>u35dl#wpcDlSMWiN>5J(|`kX|;)_WpXm z@Bck_-o7j)N=YCjZ$5AD-a0dP?#%hkIde*RvttdSts|X@n#=>aXL5@-#44Qo9$RTQ zgD#sR7Vf>{KUZhtzI4cQx2NUg!_Pc&#?c;CtqealTmW!k+%q(Fb)*W~S1FZ)^_TJ` z6?gREp1yrc-*``Nl+ydXZVQ0EI%x%I_Qmf$s*xgPLbXwd4GI>ye9Y3I48$TyKMrF7 zNo%kTQ-Rmb8?8}IBVK(Kw|2q=qe+eXT?zSMci3I=xVR&=Zq*$a@fssrFK$`V@K<M3 zIxe-qu4w_ft#ogV8vrlxB6^FW#%%2o@Yo3xNc{SoqpZU7nJ=id>l+t7W%l;kHf{D_ zeO3F7EzK=0VpG6R5)X<=w6*(Mjd6Y9jczsi>buEZPfSNnPi5eslnlqa9T)KkhAcVR zt6o?h{>9C`k32rz=^FB6msez6$1CRv<7%7j6?N{ReAF51u6GNY-#-{Bt1=ul`Dkx6 z6?TO~v77E+e*fIxUwO$-%7PPo&RRR5&U;ZElEz?OZP?^V*KhCKj{F#VXA6|x`i-^# zyf3L>o&?E}B+m*a;_V2K#5J$DEZ{VfV#DwC;n^ddl_-Y{I}>ky+ZonZ7i#79IvdO6 z%&^S6ZEhEiW}$3ZAHH`<LaMCaD|iJx%3qy->A2JaJHG|!ek9pyLQ3DW0!tL2l#_Os zU5o&;CjQNFHK(d-)HOeCo=(t0d$-R$YT?u2?_bfeb(2^iZBOi5b6D&D_S0{Eub2T< zV5-V0?C?TtVeBAtM)YkdPjCzM<vanUq6t*4R$lw#jz=D9AR3D;J~T#EpX0Ck_|*I% zL1UUHRhw|s<Qf~jUUxc`8FKmaSx3@cX4W(r?y9J>A>wOEb!S&!@`DSPt$JoK)|r!# z<XPc^DMc4#y$riL>4qFW+Kc{|0C+F@*l+(;3y?dU5lE})Mka>>iNnc4k|=Z7q7h@o z5)}<gbYak$(Urx)vje~F!%x2P|JKli>$R8xGDp5`4O=~Aw+~z`i>5!9y7U`w+|r#p zw*}~*mYXMX)nF#PENd}dw-JQJ<s6PW>YCK|elljttXMWX;I@yNdsqMUKQ_Zd66r*q z!Yv)<x7Nr?X92@Ep9-+XU@Hy}M>>U~HI8u<?nL;JM3;h{C~DV4JXQ%uMx0?&_WCvI zS2wP`;%fW+=gVy7P?c)mU%4)<sQSe8<TOvF3_m)dL?RlGB!>FZgFSc}@rFZq=P8SX zFhexmK8L%;P?a%zUAQ~B;U~Yk;?a3?lldX$=Qcu`X?j7uidB2_@3$vCQ4&G#Nni6_ zco#j`o%qUNY@vxIW*FXh#Q4o`o;mIG_Z@dSW89HT=X@?lCZ2ZUV48tfocF%L`pP3@ z%h+Z6nxsdv-0*r=UvqouM5zUKK?~@<XTgiO&;nqrGlFS)L08T&VP!c6rQiwssH=YR z{;z$0<))1tWzLod?`xejY5bSIEQ14uCA-HSkEh*!0~P5VcKaQ@Lt$`H6UodP6jBox zu@ZAQ?Lt6Rcv5z_g@KEjbGAP~P2<Ude?7AB>Yt73?ynr`4+eASTc!3>qdz^-cz?qt zZ+yT^_qX?C@<vxE9vjM-LwS$8GL+3@faG-KUAU6;I5J6$|AzuqzIZfQKi=8Cvh%O^ z{m$)i9P_@DDqQv1tfBq<?5O&C+xZdz?`>avC%-S_UHtbLMmCqmq5`B$rH$6D>fwjB z4h^-=JglXv0Yxogg6%k)-T{Wbu{voQM^2Qf_pRr)!}*)1R&T7}(p{w%c>NYY8bg09 zB>E&jx;Q4bRu|Qm*lIB5HcL4R3=VkJQOBsSUpD>wS1gS5`Mdh_zy0O1hPwSf^id*x zu^^lE`dQM!N3x|pF<ii#`A;=QB#ZYYFenv(@x?gMjn6KXOJriWgH4!GLI}>g`!BA= zivlawPwj25Nn~7J+ZsHrpQ#!@GqbbBxiQ(+y)E6{Ltu$qJeD8o&l(wjZXl0ny*C@n zIdY?$(8eP8Xs*1jdMMWC2-qshJ&|~>dXzid)p_Za7hQej_2-;?fy3h^vP&Uq8O<W% zEUcmS-c$nMz4zO{{WsT0$dI-f_;=+<RH^vCbZI&sZ+iTxwg(?>`Pe69(hWTTo!?#> z0lH))rM-%o))esV6;gV-)B<m@1@veb(Mxp~E#_u*SJ+Tig45ZwnRA_gf$C^K==Z-~ zKiKbUZ?|9f^B4Tpvrj$+ttJ^Nd7QA0$gG&no7vIN%NFz%nX}A;t&wQU=1kBRC5=HN zIWX_;zvWjfPd@&XuOsb=tC&r7R;b3a8d4u`dbv8ZbYt6KTDenIv4Qf?P%6@s4z*?b zTce476;CT$z4BM9Sli&flglmb$gJ1ti^ZaThb!w!S2nqmggdLquUxnI?2|u+S4yHt zWmBeuU>v1nt<0C2q0|Czy#?R^w30K#f)Ne?V*$BvVRtfHpGuf_-m&WNBlm3?BVitL zX|Y*)(+MiJJ-u?!zT(pMn@W477I>#yK){vG$xpMM!rN_6n#Hruh?X=#ua%4Og5|&$ zzUUn68S}^6UT`?ZtXSFpt6wf{Y&u}pY!+)BWxiqEsO=fO@jYr{;q8ceXyG%E>u_Rc zoKQw2ZHAXU`{V;R-SENc8r$<P*7T<9+(s|q#wIA&M@DU);qI{wZS9DsqUF)vZ0puo zWXRs$9!d9`HJQL9f8)nK|IwDIlUtL04=<ei*i(;Zn(V=9cSlE$XI#)UY@tlXT@#FU z4pub<T#mYV&p$eE@ngpvbXqhV2?T;~{7v@kJKru>vS+tW>FxeU3qV-_U|CgSw6g~6 z#1Th(yL#!xP$G>h9RHFf8~*&K?02qoKz1Z(BzFxjLH&=Mw_hHnXxq=|J&TeRPFl2Y z1etsFy`|$)3+$2>uzW_6Gi$w;K=l=iBb*0x1)H~*EzB)L#<H4^rm|Jlj?aBL&@<5T zk9)S_Me4a{2Y&I>_A9^BJaw|DL&=2om5*=F=zs6&vWM@psYoOp47wc7Y&6m9_2y!! z?z?Wf!PeS(Vz9zCZ&9F2r3O`7r5T;7D$g9(d5~v|KfSFd($*CV^*egnGaZ`~p#inu z?4yo8{^*Y#d2*w_+6dM%<(O`_%{lm_y1@4rEV{?-u-hw%CLVJI9ZB&StIBHJLy4hK zG8>K=mw)%t-(BA_bDx7{E?z*M;*@2$o_pE<5&-XIAADE5uFwcktRx6qDyx<*QElxR z!x_wGj6}5N-g}mubkZS*OQ0j7xMjqb)tg8~lx3h=#E5NyoN-Cd@pX3A4SKh<Ew#Wq z*8+4x_+3l=(3%2@cjZE|=8o1fXJLlQo#;g~R#1q}tANLm%&7@e)R!+C-P##iz0#J5 zjGB92PknjQ72mei)p8pE|0X-ORR`-StMuWjAesVwlc~7Voeg+x|CxXPikF@(>u#IX z-dnl4&C@2D9N9^#y+xU)*0oQzy)@Js>G!m+kN0fJ#{1M@M|#?%1J3{AMISi+JO{d5 z1VJNvn>%YNUZK)G`3vV?wPp3H{>~NS$G9S9+LlR|yZy;nGM-FTHI_Sa_C)_+EE4|l zPp|&VE%#gAH-~FRo9Oh)2}AMnp1m{t@_Y7MmfmjHwSXS*c)h|_SL_{Oe^oT%Hw;uh zTq;*J*zNz*?^YyZV%%@To0Z7mEGXr{!n2%#CSiNQkDXT#j{jQmk-gV)F8^QeE?q3O zz%FQkk)7~$v!_4P(b?*bP1tRm*Wj{M4&4q3@weY>^^I>%AJrT)Gf~5=zw6GIZoL^p zdM20#A?pj%Og&x-Lq?Asa$vmZA;Sznc7T6^ITY`*_M{-tEt!ltJ!!iw{J;aZ-gom) z>pQki?HlsHu->%^`zMuXRBcF}KiJYS(KoMuTW8q0a_M0ImSE3DZ~GeCxu<{iFE`(R z#_=C@WL?g@Jx}m6n>(45K!fmb{OST@&p7FmxwJbnXcFZV<A0Z7^LZQ<mCjf?WICh% zO2h8WEM2*1YgcPQ?MlCq)QuX-xe;@h*KNr?@MMVt-uWLjlgSXzm@RrqgecaBx)_v{ zIEhmy4)JKgj`nL&+=<8I_;|wkqDOQVcl*S!)<0~GEMKofG4;&CxGmpAtZ^$Sc|JK* zIq%`NCr?nPd<aq!w<~XsmuAcr{8N$x6oy49$Oj3RcsRElCTe6}oFKC+hsC7tDN3}h z!&lr;ytA}ZYJpwU0>d3unBYPY!~Z!fUS(gOw&*RpU=*VP!z36}oYp9H>WM1ad%*X; z`Sd_9T1&ORzIkQ!r0E~KKmZgwViyayk_UFQ3>!;^BzVQ7Q-X{YJZIs4nSg>eH@UIe zgRZk(LObNsshEp!COI1vWo!RS^XK24?p$^D)W)hOR|Zx^Dp9%es;#3{dXCLFZrm~! zeLK?wy^hcpwRtH{qRlf;z3ANYE}Ymh-XVT842P^H5kOq(K!z~ZIykq@?l|tavzM%X zraQJI7wV{N$S0C<o5P;VXZ#haFPbhN<-#*O53Sy^Vsz7Z8RO){^Hkemq%%o}(+3w$ zZX+6yLiX@9vWx8Dulf$Z9vBSz#$qvcibZROi-4}iT_T18y&yE)BZ(c*mwVnD=xe=| zXk9UgKusGl$rJ`iTUz^*IU}1*+YBKE*<4wFcl|9lZ*K2khFd0%f-HG8qBX6w#nY03 zBzmL%Sx1G<YtQHl#hZ6@!^liZ`=u7xMJ@0@yPv)R02QUGVLp$cp=X?;6v5ABS06sx z{`rfJtgBDv%ycB;{n^i+|Iec`9tMW8q7Dr%i3&B4M)Xghm&eJ>l4*<YXt4kUp>x7H zt3)zo$28yO%%!s~pO+wm8AtoNO^+;|cSmN^l9qw~vgPaDOCrrFmGr6p(aJa~5I&%O zsU!MgB)WWcbkoYj(*J~ynSJ_ie*D*Oef5V^#!XRq7jRFq7;*-&bzoJBdRZ*23VLde zJNm=D?WU0pL<e)wJ%7OCa!b7e<=9lE-Q`TMGk4zo$Al?7w<Iy0(Er7r>&=SW^|SBk zZHWWk$)68E)rbqY;<(uF_ruP@^}5||AeJ*D%hN!s!I<;<Y9f)q|03W$^3L6MpI|5W z*}${_PqqY5d2vOkv%5p7GUYOD%x1I5#aww?)6)xHc;r9h&i@pXU5CwvvuK(`+{1#s zhRoM_S%x&!1nOZC7PgGdf?~^V`}U=Zm0IA<w15Rx)&n9g7XH;zN+kXfep<1U|Ki2A z_O7w_{e4q+zv|rNz44mXG36}>9w^A2&gJc_y&^0!vJ5P7ECpWW-JAiE@egMZPf2Cm zoF_83+nu&_xZ-v%YtDVCZFfC>ZM5Ts!#w^e(V@Y+)&#p%qtCW3k?$C%{KwY!j|yz@ zs^`{j+t7w)v~8$0f5pY$KJM@{CQms?h9UC<2~M2PrDArs-x`^(dTYp@nK$y2CQcg~ zNCo;c<rHh$GRXwo2b?pJRJ=ZTVRzDFd-#zDmz=xk{RbS2<jV#>O#pGzgxm=Lzbe<g z;LxIXd%=6YW3LFBTHI_75G8m3<$|(|2X^SAx*DmJgd5{FuvVXe_vL2I3d01ySI}1~ zPec<-JcjjACaxAQY|Eq#7w?;n<(Q5mrLwsbS$8a1^ZVOgT(?%(WfsARFep#j#S=U! zPbONAlu^j9lu9kIXSM(o0Ghz?FOUMg17s4<laB8VsEaSFJm8>URYl%RdY^x)`{&<Z z(vOBzUWJoFP59x`lAtH>!Z^0#5i$aO+2Ilr+)O43lbXrofpehP?lR+Q+pm6oNwn?x z!|L4SFR$<a$C}B5sv@J-X7cGHe2!Dbu5EU&$fTBR8Qiipzj?LlS#Ml*=`TNf!8a%G za{wP9o6MwBkSWkIZx=eoh-Juw$FKZCwj4o}D$8mQIq<0d&Wztx=b~(;-&7ao+?Eew zR^>FkK1a@G-usWg;W<Di=Om`$hWG~)IoRGe_DcZ#%5Joijx<vX?jlbPhr_qtdh6wv zUw-}d*RNf>mJ&c>9oUE49)0xDB}<lQd36zYHFEEyy6nnqECOK5W7UsXO!c>`7oX2K zZH*aJN4(W6Ac=^{ffsfLUdz%YuDkxCVj&>bZDUnS2u{{QV#`GUM<a*dtA_Wke2G%t zr51RnS^&5NePyxMTBy~%TriXsQIAUm$#sqD2S1uTV;WKX(&f&H&-^Fzqwn@~b}3)b z86|R{1%TFLpfB!kL~+SbVY~QrwlZ~=foV=xE|H3uDzi1T_})jpGqJAobg!@Wq1EpD z`^RiiwwMZ4se$8E>yhQ_#yVG;>80BSHnt`<zL<I6KF9p=h6m0*>2r2lxh2z94zJVc zc4m}`%MF0vnr&;;7>U8GW=q{XM)}!iUYH1by0%4gnY;@>@YIq}EiPo%DTgPIf6b~| z_wtvPm@4OV5q1gPF`ksVGrt%XNK00GNzzTZm%Qvd@tSB+AxUOdr`cR~Zn)uwrAwF2 zm@(sTfBV~ye)OZk!9n8dfwjn}|NZZOpLNz**Is)qh|3}M<5`W(??hd9N*R`KTgDiw zo$Fp!U0YpFdwD)*x?En%vVlo1%<fPu9yW5#_ubXH`b9mNhU>MMU(vuqDQmbY3`YGM zK2iE#YJokb1*{pSUQ5-=hTvJD>t`}){Kds%A+J~MJ6(O_TT^Gxs7z%BO|$9FJ67Lv za~SgA#h0tbKs2#LBrFX>>}@;PrqXDdh}Du(k=S5HMfy|gulxNM?)vlP<LtfD67j@8 zmgOFa`C4VMxvN$U9pp{Dzh!lK_KEeIo?q3~x;fstKKY50Kl8`y?mh0{6TNnq3`wQ{ zaKD*269h(iHt$Geb(s`P*_^gUtNbIG=}gK{?tRD4nKJH>zRrw7;X0p(x3wW0_q#IL zoG<9`1kfQ%=k2Nfa2E^7646vU=prYozW1df<=gvSeb>CPj#G;;8TOa$+_`gCu3UN5 zRac#P=9!^T2xb?xEK24QSi51vhDanbVZsFPST6u`Noz{)n%eE`T$$I}S!>G3EH<we z%v0%vL?&Y*k;Z7>=EC0I=FB_1%q@BxhS{}k=-xXvwzmofTRo4BAhZEFVOK*hd5Ui5 za8#L{UFA}Kr51QsTY!0|rRNWRfnsPmSUBo(_)^JinO|H)p(t|1(dsMTXsl}NP+og1 z*Ybzky8nEeN<~>KMpm0LYzdGM2kT%qKU=;`nL!&tj#vjuB?5j&Yi#wCEB_o)4<5R2 zWbE2*&p$Rdyr9M>M8w_Es8$_eUwvfFI=^kny54ZNYwHqKZ;t)NH-7nxZ~d~$QK=QA z5(Ez<s;El>La;;)xI1hprnsy+>-H0U$`MKM7;fC9%07I?XX~pbWA8vE5%OX6YqNpA zisfUM*YpOAOg{SD(r08D+hG&l*=hu>O+6yRy<*oQgL}oBzN0S*<4bvLA9&z_<BmJ7 zwzhWR!iBxPz2)WQRaI3$tcKfp^X4IZ-hco7Sr69tqp_uRxZcs~zV*ToA*Dns6L0TH zwQNb3XkM7xyq=DV8Y5WkRLKFi5kLL|4IeyXbX9GuGFtDu?>@qvNx(IW?%)w#7K(&R zwg6c0m}?AX>&#oPSn0`93+#3+AktzH6<IOCto~o9BEuk~Jot(ey$Dfu_IT9?KBzAF z*84N|9-GtG-r>3F*X>U{E)T0Tv?V20zl9utb25Yh29V>*9qSIQy79Jeb#I-2%H-zY zi|e-Bw!*XAG<sBjO0_qt^l_u2hfP?J49$OWYtJ_I^7F|<ryu&q>+e15luxOgm+^;{ z6Z2^aEvm!_*}!m;jIo(w(oBhkLK&fgxWkE?O_x)wpYnOf`(~V26C4{GOl4De+ccnc zsdTow#&36KZLU;xlfP$R+maU+Wff9wxy)10OMcdp@o<)V$Nv%l@8s_cl!C8%HFx#u z)eQ{|C!BBsXC8d;L4?wW9(t%|aFH`_+_-Vuwr$nb)%)$YAC=IMto5Rc>RLOwayvUa zCb)U!N#{L~j}7b8wyix`bFgV_`^A^FeEqTtWv+4BmD@gW_Brb2-}~?R=d7Pxck~G- z&X_mv>2R2-vGDp#uJvSPXIHJ1U#SIl!xn(v4jUzcS@P2`W{9DYaJ2Hn$d=LJFIVSZ zsLuQ3{&{Dw-Q`}hKKy?_TDsyT40>5BX57TFHZoH-0{mfkl*F1AiLWj5{QCdg{n#(Y zwS*2RH!2?NGJYR!UaJ}n6|Yns(^U6q)i2F(KiS!_Wt-|+>5Oj-Ui9%xe)W?-k7}Nw zQdY&R8l>_pE@#C`LA-(BHpHNsqJM?;!YdlJxC~6~;biTQ1JP|(zRhd8hkD{Jn@^N0 zS>E>9;%Us0O<$Q|cW2A1+;boLdnh)T&WSo|##()oplaN^m!-Y$jd$?}21kL<XfzrO z2B%M-URhZ=YSgH<wzd~ucmdY-w9`(*FbR-GNBX6gUP349@WT&>C)Vhzv6%{L9j;wm z)18xjED`g0%WY2e+@iI4W6OunIrf9+`Hnh4Eqq2*mSwsI;;HaJJXBv%;jKAP&6rkx z?l~Xm>rs`};s6NS3b$Lvt!d)4!<t-+t6cVAe_uJ$cTQzXxs+Pq-EM&*<6A&q-PP&y zg(U2z4c3z-SJUbCeeo+Q9G~)+Kdtlz>eg<^eC6xQ?!0~fu}x)`36p6!ZNw}@WR!6v zY$|p41HWwVUs&r6?d$QF&#WJ~b8yTM!%%HutR12TCiq_nq?WGR*w$g|*^r-BwcmAr zxVdTE#Bw}kpadr1Dflk}C_OEJ5f)L@uxkvdaFGM1!kP)TYK{d`&J<H*<`<HKF`;GJ z=AoBtSzL9ba5%(@l0hh9SI+KEyL@(sPql4sfBM;{PCM?y<Re_ay!CJs>`ni-fB3!W zt#{$OB0~l~L0`&%w*!6IS-*b$GtWG8&_M@HnKFe#t>g^)vI9?yT$+=hFWZqj`f&H& zntm@v5$S=xY;{BSd)FLs^$orgPLVa8(T&RMP+kLf0N%k4<q#qv@fcVNs;5biOgWU> zEs7%?m^t(zt+6dKE?8rvV3v3L-TUQBwJWv2n`;3uPBW3vT`>ZN|6|R?>iL=yYmftu zWMDX)4mEMS`pl<|qmOP%gnAOuiiHa^|M&Co)-IKfisU(+S8>Ans??^)%Rl?eMSZa+ zCXEj5la4umzgpciI611yf@+grMUPaA_f;>A$*&(WH?CC9f$?8C_lI}<>A|Vf_V@d% zvT)N$Z1~|oaV1M!Q4ALtl?*`Z$JCfwq2*<W@EbVR^_7uo)l+Y54m|f+>)8mCm6|o} zz}R3u83n?5K;jxZVC&t=>CM3hql$&y^J7muVokLR>v6Jbr^NwM!rqefXWv`i_8oXn zZSqS&0IGI$1vmWUlTU)R#~gD^O-&7#xCh&$<;$0Y&@*Sw)beWfN&3Nepq@La2&T=b zZJV_<juSsH?eq^<RMfG6WI{Nqs#TDwE@LWh>uei>&ahm}aWa#4GA)+1AE7eYEL;5B z4Ohn+)_O<}pDO(?wZNXz0*r4N;v{ev%|zH=FlU$u%O%!YK~-Q5hS22{sjfQoV0Fc1 zHB+WxR*-R3PXFC+m)>-<Fq#9sGLf~Z=%9M}fd{Tn^ej7|#?jE$7n!@pwIDJ%EecU> z<*I9j>N&7sO+Y=}7GJP5KG@;9_|xC})|b9h=Bp#{a5^U=(ChOUZYIUA9C_4-s<A~F zEmlGZt%?Y#uc4G}ogoXf!5Gz?#`r0lpRw;O!}Q}CnxMwK70bxXt8u+Uyfj46POtdJ zTC(i9{zxBoNI5Y^vL+@xzL%xpZ@-tl_O5$fKoqP+$jlCMX1HNw&Wjf>E-Nb=H*TC3 zHRFE+<!6M__4W1p?6Z%q%zKdoMupLi-%PuQ2-{vyj<qYKXLx;wcpw63XbR$ul7ZFJ zJ-|DH$_!SImuFIDp1D6q4#RLU^o03m?2R0LoGGPJ3+$0CApM;Ft-+1$2pKN`Yy+4X z8kTbnlq^)*WvHW$P*+|)sbQ>2hoZ_p_10Tf{qA=P!C6wNb=~tHee9=A-qzE`kM_>r z6u)sx{nM%`r&0m6wn1$>Jh=YwipO1vrJIaR%WY$84!r5QyUzL0$I_{k$K^oM%p{rF zudWelR!+MZ^r8hu{lHV8S2$riM!+&zuqviMiB)aAE4Q*IIvpZvHnI*QKVj^IrrHVl zls9iWQHp^WB4^e=2f>iNHjiIz+PZP&N~{t=aUd8Begy&0dGGPt5&-YyPYn8s=KZkC zNe(HXyStknhPE^NoWTzG<(FS>ZEc-4ZCXo9i>^TtfHfbiPwxI(ykCiehSP95aYh$q z0Z42Q7_K?h(Ci_$H`JwfFf<Srp;IKTQlfTYqN&E@o*~C@H%%0whwY9S^ZZJw)B<~I z3rP32@Kv<2P#d;Xp9H|HBr-7mxS?>$w579V6h8Q@lhxP0G{NoZMO|XB-}uqhbLT&; zo?5uzmRo;O=}NX3%K5^U#Di^PHmRnR>UXO3wJLr{?ZDLLX9psWEepN;vU$MNQ?LHk z4aXmG3Q&lzTSj3%D+1y~A}(ZVxDNbxVB2INE|y3*u3}#v5&dY<!hZb`Dplqp-nTLU zuv>Y?kDU?=;|)*17cn*zQ2^Mb93H|#IQ?ZFBByQZ*ap|^z*rGc8YNoPQn$ojvMtK~ z_LBGA<*$i687S3>!Z<__J$m$Lbe^&O<qVy1>(;G*{p(-p^i!u!Wwn@_HRuA;(pBG6 z$;HwSV+R970|}Fl_hZHk+sl$r(->#e>~^T~zQKX+K~+|Vp#}44g1eY51~SW6F=Ss1 zONKc!Y-TEewdJ5d5Zp?l3^Kg`o@$m-WlJsadM%)F4epjv@=7EV0OAZRr@$C`75K9f zP!k$r;#AJ#GCqI4YTq{T*4tJPGbj>?UHtWH-Q%9BuG_LY*PiYgNI%>^JFNm4wI#2* z53z@4H?B5PE7!Je-I`Z}p36S{&5wQL!cmo@1tw8A#vKR(ZpmKEpYYJmu8xI}PG=m1 z92D1f7!e5%EOX_YVTD1mjte7_$El!|3YF)K#V5-)&oc0qrx)XI7bAaRrg_RPFpPnd z%WKE6S49P9$pYauk;JXswDMOW)4k$f34nLWX9iG7ATEH4Ao}#vPk;XT=Wo36#w)M9 zva_@Ex4-@E9e3OTAAHnNM^QWo&8jeWg2cO|HoGoUMh#VFXfba<fW_Fx(KA-}c&c@% znmQk$7hRq}JmYmQ<+K0*KmbWZK~(DLQ{yMf+@8_QG?yth52BOB8RYdi;;;ra<5~Z# zqqkP=0xgh-U)7p2+=o-~lErOsR%YOk4eqgK|LjX0_>-rG^R)hJq9a#_GZd$q)>*x- z%@w%@3A6qehM3O7x~8uecVE3zyt7a=$K+;Jlx8CpZy5RHaAiiGEA8+0Ent1zVo$Pq z96T|-i4I1;;<7!HBl-f;VF02)UBAQcR+oIk)7w`)_wSD;liOCj{IuHiEOtN7<<$F} z>T}hut>LsYs62D(2dDX$*&?mc?3%Wu5vu;cA*X!y{4baLsxq;J6XCB|F&Rm8wOnqB zaflYON~N+yRAJX;X>M4nvcp}SaZN=y+TO{edORv8wx5)j!Mz4J%g)TH2RyfWY$(&u zdYr?=CuLUpFkp){urmYGi*1s_ZKQK)uat-{PC^=rCGlRB-a7zn(I7sdOs1egY=y>+ z`1<ecccWJo<;?6;IENsv)4{|N1QN-McBuiZo_p@Ofk5ESJMX;myWe3+xS^@Bys`rC z94+I=@nBJJi$^$o4>7^CKP)YYVJFjNMx~7*mUG*k!11`|AR?z&%CN`0{e22nnJK+Y z@h$e3FNb2JZ0(xsmCUT~IlLq$hvfKXl2oH`zl?Tk*E)e+qg6XOBUsBNwiZFi(3x^3 z-fk^-@(M0q_=Aj8)GpF>p5*gFf|x51RLy!&Vz?AuT~@GiA^~9G+X7&nyPW_Nsf?L% zstPX1vv3&ldC82H66;7wBDJ$#dV9r1;%CX`#q3gwwn`@>9wf8{;(NMUGM9G}a9JKM z3<377?6+rByhb*~RJf;jT-tdDTR?vZzOV3m)|V)L4meUiyoCC-Awm;>v@oS08BW!e z;idl|J&P(;)ub-CuxioMPqeiz_NY)Y1)X78N3BSyKc&(K@9(SJufjQ@a#i2Z+K%*w z&7o|j?3(Z2aO7bpl=&)nQK#Q4ux^!|#Wyp08CFf8S8lJvT8E|opf@EmWU8~hQ?WOq zw^`Mu3(KqM9LQV*cp8#rH#53?f=akeS1z4Mmz9@i(;-U68CJrjT>hjxVE2`|=FfZd z!>63b3a}k3C7u5}_&IimqTV|IygRhkh&lkb3=$xd9THqDz$u6e<C75?4)@XxLEoXF zA+{g-(1$+ofe$3pDXe~xKlk_dA92JH6DLj_k>z`G7jzI9D-sfU2~bMfq0EmeRxliO zC(|A@Hkrf=0_oxZiu;R$d*`=+Me-mMuNd7FPLXm}mgF-IhZ~o*oRq<U5JC{ngfig_ z6WvY3>EZ*3ONO8&K+G(HY~^t)ces370LZkC<fM=#5y%t9Rh}bD&S>=I(9EVpTa?)c z5Ad_vq&Qu$ia-fQa^qz2DWX=8rI|<(lMc?>f!BrYPfH#Y0nz*~Nh<um?)fi|moB~i z7GR3TR}(SOaFS1K?bBW8EV2~KL@jS4{(&sYa5vUJSo%86q>AL#(6S9L&VB4YyZ2d} z(GFf#_+9aMn*I<`3U#LXF|~tZecJ{*I@+QGJ!-<(gFf-`FP(V8nRc1|>Oz@1<}(=+ z-RA%dHTe@oG?~OdE<~)NLO>d_X4z#}e6g-4Rn)bVL*0*bZq|1A5}GgV9qkPbb=jN* zU}Z6C+on$MRMWvab_#X{t7c}T+Qtxr;JnM@+_H5;C_GeM)+qT>8EQG4n;h%~X?s`L z3to07zap?oKLce+$eGy!!-X>FOps*5K>r!}^X%EPpL^~(?0qpq!T{;6yY2#+&OiTr z?e}UYSL>b4ZkW$3mP(J}C!?vlTGdnqAuH)rzN1}$Ys4@v-oI0KG^H3ZhS?QP)+$*} zGe@Up7KDl`-Mry2piOq%bK_Cdosge!rLeE*xILSM5x^$`3)2`zGS!#Gs=TnqKy?A_ z$dr6Uxx|(y1S^@t><YJP5*6KAY?Fv=L{Jx9P#(<VAs5j*(NZn^)QpeRNCei_Y^Kmi zoZ%;J2`R>*n9c4cA}k(Ha<*73N;%w3HRPpA>AlkeHdDMxF?+H;92m+{EAuVO{RNsz z4lx!G$%go6P3BW!=~2=JQZ6;Py6gUj=Kt8=+?p?IH~eTzyEA#eCl~~yiG>vLs+cR- z(UT1Ks};*Kbv5IEf7@SAIpHkOH=Yo>Wc5MG&gsM|molW_R4PM|nBV;7H&8J6U?><w z2~x(@9j8Ly9C-u6Kajhxum6%uzR}gy<8rtM2E%>5gD7}8ZLUm4)~8%7Ei+hT8QAc6 z-SFI-w`|<HZ4*sFfyKGz$ZYrcefbQf^cGq`P}kC#0%f)6m?@;dFbf{=!P2=U;ca8V zf(3PTb*%Vu67;?O_S*@LbioA|0L;VF-?vcyZuE%sAwgFw$+DHzscfpOTvb;2^C&rI z-JM+t!Jpx~3ODb9f0Uws<V`*JQLGR<C=aFUtv+O54jpK2a)bE3mAmC$<_}Egk@2D` z%8G);jVi=_*)((nN+zOa?v*zZv}XBA#KlgIDMBRGB$!x&BAY6n5;-<Rhp8H|U!XMb z)FfRw*^_GMS%NG-lY?Fmx2}kO8jO(?rc@k{3&efQm)kL=Hr*(<Sjnof<X1|&dkaW^ zvwrMIFOV;&cj<R>g>NZh4-lDwgdw9>dWIu2l-hXzf?v&j{QAn4o*734(ms{S=Dn4{ zc)|=1CA@wj52^07+R!_+W^M1v<%4IP@qw#<c!QaR=CHnF_`J+AB|(vp@K6pa8p&h| zr2qTh|9;a=H=TOwsn9M>!LX3r@hVuM%UPL?+y~U1gld>Deo|v&)3rbO8LD5wVA-hV zmZAPQQ5o!c(fA_z5z-~7BfPK6V@C!QPsLZf^aAy<L`8ce2A77d)tBD<hCWJv)z85S z<L6nkzntYHQfRqs*elB`us*u*!VAZY8ABk#f8GDjyZ?6AF~=Np>7|!4(BcUky6!<q zXbOq3CL_x4S5;Nario$Z>+4G*DU%_q;ljFar*9}<sF?NBMHK|Ka>_zVT|-Ut^xdqj znYJ?M0&52lCt*neP+$`NHN%HA6X|?HSQe+785VNm0^)K;$fUfh<sXO~plYHns?vE0 zEhlzYYq#_*e@P7t;$eu#gvio6oOW6wrVM`8DjQcQ4oRIUkZRSCyY$GU2+X#$<rXy< zc=1KGX|n(_c3mo$mdG^%*QH^+)BDn{%24+`$sO4WNxq)$vDqA`8q3=fhQku1W&QBI zs6!8>H~;2ump}CEug1(UtH&o*RmZGjMO7gY@5|@#*z8F~6jnun2Guqg>h3W=diH02 ze$5}IO**XH+mKG%(g_?zN=c9-hr=N5VJ1udCOjzKaBsTl#)~h$Si7U=9-^rtoI@xr z54^!-Wv=fH1j@d7>9?ZM#P!$xn)ptKA97?*M<x}wISdy*1Au>SW1Sn~V0YSVj$E+J zxn$|WcoK;YZLl{cS@tTWx7Grzl)waQL9|w+(n?se1}xU?k`6xj;8RXHrK6+c=9_O` zvt|t-{i#oV>eHY745n}4NVqIW^z8R=f`VA2-;$|W<Ivi0jx)@2Rc*cBW_0IGZ+}k` z{>_J((ymX`p@8z5H0YtN_w@y~`X;tqrM@DLmY^~=@H3iHy`3sHD0YkPGRN47!i88j zNZkS8;l!ilB<tT`un5;oOdEmZayW}@O0C|o@R7&H%$Z~2om2(Db|TA&44Iji!vQHO z)I$DQEv9QInae^LWs<+Hpmk1|Zt{5Oo_kL|?szqGs>&o-4;JoQe}v&${g?mStNveZ zDqY&8Ex@OhBnk#}0qeu-4v0raJ~}6v5^~y7Y4q5hTl3T}{_ypd{gVfsILcWY_EorI z(e5Kpo!Yf&_0oHkJCzHl>NLv|xioIArp}ms!8xBg?SwP2Fkn5zWjEX`jnF}?g!qNN z3TeXVhd{r%O!8+xyB0N+kAC!{@DI>2$d`_$s<lT8kG+w9OcOGq5JQ3_e)&sZz32;{ zdurbNNt33=LMk$luBa_DT+-)ReMzS2@2qm?@WB(PaKE&AdGBD)*v3jNh1L?NH&W)F zaZd?=-{N<q%L2O0>0pJ?s6vZj?AWn%Zb4s51kDcJvA&_<(yxC5BjE1do)b?zvAMaK z@J9?ihGBWIjLvFBA$W^**i9ZQkd*DUfqXF5GH#c%snLcuNi5~;>xmNqskYXFl-E44 z{n59*XQ7xdg@r<d`oLliAM3Mh^$ymLV%{i$!A0!My{+4N{{FzGhaL{ZBT2WB+Gpb7 z-@ZaMG>Cb#=!BA)HG$WHZtHC%e~6sOpR;+Vk<VsW=TlocmpuL?XGhJPrmAbWMP_P< z;Dqmi6|rfVpwvQFh72Wl$g)+6)k7ecw4)xPVj*rfYo|`~JpIh-2OgX152$_0WqG)u zcWOPXH~Q5^oY1>gzOOl3I`Iy-fM$0EeWmw+H_Wu82g*c>Kk*PvPZ3)_GuJk>{zrej zq-tuYa++y0B<y95P&yvXnBFS?38zmP=SlTHU6${v9Npa97HJJt_kHTT3r{=dBk@Gm z@AYO_3#02`6_gdJuVij!5z2wS^fD;bV~_r4-qZ7Mz4can<zk~DcQ7x=W}$3YYUsl^ zzI8cKZ;;n9O~?506KBnweap?aef<X))|Qv2qh=<VcewII|HbY|#dC}y{9*ZmjzN2> zt7BXLK=;_jN%-q{<HhYUca{M7Eq+SP;{vfrn$fgEvH6fg4k7gKK9j|@WPu6B1*&NV zg27n?92`LwwI~KT&mN(KwY>rL8mNqKIfq9uCmx}l&I}^lP$(6RTg=)nU-uS5R%mRE zX+jvb|MWSz$%0R72hht}mLYc4SXVb?Le<78TOWAPOeJDGiDC>QGkGiPUUn=(p>vR} zUcX`jk2nPH33&AiWqTGa-Li4>S(kiGRg?>a!oH#fYCVadn+%XG7Lo<MtQhMI#fXhd z!&kxJ?G=W}t_U1+;RP>#@4Ah5-!tJmpK+KeY*dCbD*fN>TYxSk>$@br>u@&`@2z}s zoTkG*!UZ#*%SBb+15e!dr@7aUKHMC8pf6A#a`^MnL?V+$c<bzH-{$s?9zV8zR&sVl zY`mGuzrXpAX=hE{|L6m4So(OqbVfYH=CY#E57U`QW<4H<wPZ#g63u_7!%bAsNs}hA zKnD6ki{N^h<3ZL)TDwJR_3A{Obw7Re1@Z-b<ME`==fTk9)KgFY;upVoar!f(8~4fO zw&s$i;S((hL+qP!c5IFDhZV4=O>C4@G|qa8EYR$Q$?60<es4skd<?E@%+TB7?Of7V zi)Y^cPBBB|Av!m`wo1`lqI0mrC4C!HMQiT(E^OgqC|c9X{btUJh9kec{)W$7_~~z7 zcG>(VpENC>YMKd_x1gRDRn?W(i^ueMssA393ZsaBNW9e87Jw&#!D=d%+q_xGK@nPZ z(R*vCmCU8Vt@T=c3UkS<7;Mn1SlvZxrwJj@ih`8g<}wfto5+U^b;4nei$0dGt8g0j zfaz9AX7%E}R(M}bfDD5LH2thD1U)IiU_^dS#MoI8X>9Iz=8nIga_VWSxj`l%2&N4Q zS;38L`DcwN4wRXe9zbqXj2+I4Yy84HaD@MYoZZY=9t)9Q6Cel4zHR22r>t83Lj36k zDuouU@b0>I;niL@Z*dSw8|<QnE@k`XTYztowA?M?DNg2bXbCV##DfhoWE?oU@;Og3 zXN1(i9gqC-9}BNJ^i2Ph_vNd{VoM*2CW+GPiiI=X?KqZ;cW)cow!X)g_j<FcJg;Vt z-{;VSk2NyBY}#zyv~}B-Z7;1@wQ<vCmm3X)a9i7!HLF)<Gw2csB?o=m+BzP1;Gy@w z|0o?E1`RCGw@6pDB$-3j&iYW_Kwm2*&uV%lid@4<h_lsQfltPGQQK?s<S7*uRsZ<= z+(QpII?|s>Cr#YGL-B+QcM*P+ND&!4as(<A`h;E|3K;mKl>xH1r5$p>nm^;KkZ5;4 z8?d2~gF{9*ABjt}7ncxR6un8j%@!nQoo#U)0?;K-T{N{~hbbF{a#C&<FDmasN+uE> zua`!k?55^s!uk?ip{uLwzWeU`_rL#*lV_Bik2&tRs_JSQi<UwuTGX<v#3OWWnvtV- zq3S!mNSVun7KW^ZT6_AfnCw<nDz`Un3+M1jF*u~%SM2oSw`a)5D9k9S$95`V@f(P9 zA#v8dOxCHPz7y*p#C`G=*?_(tkMN?@m-#x}1OISKkavKxrd@<=VoqUYZ9NX{q##b% z>|Qr<;iQCgGW6(E<I1Yt6UJH2Igo+~wPooIC2EJ$E^wR9S{l~qS3`g8vWjdaX+*0H z8E-a-vgLW#L1n2$*0hU1BxU#7)s)erC$+46^r<=f?XRlJhToYtC}dRJDdb!Fx4X0e z>j-X!0o4(*1!bcHr0@YFR={vNShJ;aJy%@&*-icP&;8t?eVLVxKtinL2+<JBhXx{m zS!_sku2c4&#Mb3Q^}f#Lrg1hiIndR`ywd4$zPxJfWtV>wXSb+)9)0xDpZol0F)>=b z`eitTV~#!QTi^Ot%h>TC=-RdG<FO<Qz?dOH#Wk@7hIKnZny}rt|Ni^ISH#f}<d1#q zV>4#V0ER(Oy-o}TPN!4axFZ^k2mC(NsChh-&f{#7Fs!JZu3xk9Lm&U_9sm5*BvpkN zIuT8K%OK}=m&eGtb18c|SmE>rGok1pLz3xZUJJ-|CH9VOfnL4#WwmrvV_^|006g}& z8RTG)7x#A-`jWGTTXF`}i^cJ=i6Hdsv(Ikcym{NUZEV?JxpJl4EX?J*@B@9Rt=4&F z2TiNVlP6P2+-|VN@#JNfU3UI?=iT_rUlMmA5s&M(f>}v3lg;Pp@g&}nXW!dN(ANT? zSG)$8B;IA~8}P-Ew*fsVv!g4-hXP}EX##=-g#;8Wpw!1=8ib4sEn|@sLnjbl@I$L9 zqcANJ#yFdZF_T2i$+G-);VRw@03%hW($-om;78>FU~)iYZOdn|*kol`1_Eusj{?Z5 zqxa>f7EB*ENi{VRq=Fvpa-f|h3&fx=WQHDKN5$GIR1i9y$;XoRR0en#xioj?L{ewN zAe33Agn*+;IXkSe@VAEYx>TKS{Nej;U9?24Y88%t7<Y?1Ql(eUKxmRe%k0wDFJ=B; zTY&zPu~d?o_N5S+kmx!#Y>kL?KxazzXI{Gg_AiGWi%$N;_^{)}`tdfmk#ME*nUI+s zw7H_bOs5)Hqf(t}#e#5M#q_GGQ7Jl>J(otYS>}GIS=65Mk+Unx{euHNFTcF($JbnS z!2UBQO_)gNm%Hz}cj1CX3;+Ol-P#QhAHtIplUtKq%@S}DCTITq`QQ8A_a;o301^BA z=RXgZeC@T@qUi!C_<XDu6Ppk=$)V8~kPZZVbT4ahnXW1-+`*uK{P^)})@<;*Yb*VY zOny;RL{%H!&2V5#Zz@EYwzMZ;z@x9<u!gZ^Vak7PzCH2c4gr|&!F)%<1~9C7HERYW zyf00`mZaI=T>&I?3ta@IvxB|bcfRu-pqFVHh2DGby;odu#imW0gy_5*KRDW06yI<R zp?oTtB&y*1-uFHxB6yQQm7j)Uo=9zf`qQ7%gK+_k?Qc(aH&u1HvCI>(0WYPyzGU(q zO)?oHY5bABVSEMrBvdIJaG;Fdf+GrBdj}rD<epuewpT_l$4VO4tkqSj1w(2Yxh#Db zp<5uEafJs|Z@;6b-`>@$+PhV62wE7-q}(cHI9O!0Y(nJKc)6?#`wcoj!d_Xg6KyYk zKqL-(Ei}!ASFKKk!_Iy8k;OcR9qmv+9H3_9M6f%PB|MvhS|nom9(1i^2%X`MC0ZLU z8CY=^UP#y55*TnS-P>{wD6=&q$G$yNHe*sH<u6($GYVdh8VskxRB!mO^ndqh0lErn z{PL~LoQugB-`P5386jqdo_g`#uYUiuw)mrmf3VJ3)#<Iv#?u3a>4^2@a$!%n)3*7A zP-vrywyKr$RM2Sr(nVLE{n2x6PFF0R?(G>!N61sv)mEK<{&`2d|L|Bmv1--Je!uU6 z3ogJ1AEXBKWCJ-xVG1^eX3?&%AVl;TO=h_b%74clcd(8N;ewH6=b!)lC-@CP!$g>; z;4xsYk@jubvIVq;AftlHdH5x^AUazxo>;4q!DwH1^u*)NOegS7X;PVZQXE_|39-9O zgwHl3!_4FP=NF~5^DLg+%hC?zxA14hrr?uk4AxT~&TGU4l{GLI?|l0^AQO4gC&-F! zp*sgad-c^<gJ;M?^v4F_o_z92fbEbu2fzJ7-$D*lQp;y(91;~{y@XbxN77SiANnZ0 znbgtNc28?7@|*(>H~@q9Bab|i;7GEB%s2#*3e@&3RAKjcWIN^Og)~ENbt*XEtU^ps zRpqjYP}k_~j;7MG<Wt1OUGW0CI?{Xi<G`YE9I@7G9f7_!9K!>c0&G+$GN2xOD7yT` zjxC+rlB~@+r;Q)m;In&UJrOmOwTBcx6>=#bJ~iN09HzrY$Ti@W4=0N-%;}{xIAaN3 z6VG+8T<b3PsR^UOWAP~Ia>S8lvvlir<fCCGU8-X+yl}ya!S?=GcyjINiptuiIR~nS zy0onSdR$OLz#T4Gu$=-a#R7S1FScF06GC%ktEn7SQ{TRFO>-=%0=U=LoVwIRj~aH0 zNzRtiZqNdJ2&ig4gX27zwk6ZZI_yrbkyWvW7T*5g{NFUr9GrDzQ`Xy?bEOpC8q;2Q z-*}&GOKT)K;Li6~ta)}QF{n;^--&0OanXr~oVNAxO|fL6GFXoVT`V-@YOE&0Ard&K zXfWtSM2s0E<Ol(BMMVwv7Y80NhYl19#oF51$}57kwbh#5f}NU@(|I6k3l}bg{y+Zs z;|CsiAkB96*=M)3v}oeblJM=f-wv&V4uizVnJ>Qht4&Q!ybcSM(q(xw0pn~<O%?Pz zpK;8dcF?o`xYbop)D<Ck6yfwZ@KNI{%O{*Ulq*)Qda<{+cT7X2xM1BOBJBp>Zx>Wy zhp$UB>Eb{ay*9uOUu7ig#yxu0!<~hOf7?|o_5+}ovdES#^R@Q&cJk({(+?;YoMSrn z&_fR`c>0;QUFKWN0C1&E=<alJCIqySp0!Xts*SjYEpNdV&X}nLGIJbb{oxOPKwlcy z(BLuG-eTFi>0^vQ2Dm_nfFG8z4prZXgIW9-yZZY3Lm}la_~h9oFJOU`6kkAJt2XR| zj24cWaIRQl2(QUqxT)H-wd2O$tbXi2P0e*vk3V7ZA;*X{(bC21{&jCHi(@$~iXaK( zBC{p8%nF%FKtik)WO+fPZv3+$NY3K-Diu}n^kC~YM>+G305K;ZIMCb-%WO~_WN;oQ z>~-kQdpB=fd&K8Hj3-~!pL_0sM{=3$=+jSf`J9LmQ)ZrigWOtlbCA?Q$uQq^x<O^I zoAL$svEi^gU|+gAdz)cOYO4f*;Xg#hR0tf~QraC`fWDK?yXk=}>Z3kqC&*uRNcBIt z^xl8WzrJy5cHe_*Y!!r9zyqZ%5i!F(X-CM24|uxU>_f1uNM|;w_su@ymsj8J^i(s! z4VDM|6=kWuTq2cBgrk*4wVBRAAwjZ8BvD@OpEKuRkK2cG^696YLAOHlgl2(WWpGH& z$_dj_iv;N{(8~_I#G!{C`sY9Y8Qh&Yb0$7IzVL-F5IB{q(6{TZyN>)}j`7#QIx%9% z*49nG|NZYdv`Du&07RSH>9iw-1|8V#?&$C94mHn!NaE$g9*c8>-OOk0PKm=32s+xf z46Wa=ZcM{uxRSjs?GS)zZoRTggMu!4ZGbrxtqkg5I>x8sL+UTbRlT!Qnhy%1QD5U3 z6@UW<ZYd7jg$$AaKgtS)LKS7@?+S<^XEwZE7a9euiUa}?Yc4`fTpkY<ruC>KZNiI? zsBJon5uWrfnhvMXNN<o@2g}~ujyMXRTN8XyB0;(a*jZr)xCV|m)u^Ugo6!kMg$9#@ z1FEUM@X#*$M_s7F_JKTt`{N`WC6rHCO?dUbf!6!~-TBxH6^^Q@pEyUIeuDB-IhWdR z;^eXQ8^8W_B*tl5nKH{1-VRWdfmC7kgH9H!cS%%ZESSd%$bxq{ge{IFL+xGF&5f!| zY>qH@1Vfpa@v?Mk%I;aTVCypr4*c{d)r3Y>9#E;?)@94mW_I+U2dTzd!^s4}!z<V* z0{v1yOM{4}#aD0w=RveA{<Z*pj`OaHx~i2d!9*j%R%i}*7qw|A+nv_}221_S$};F% z;fyEOomv0S`M-T&{!Pc7IXT#vPPvBQ6HVohM^c2c&u0xhTeWYBCt{5qTT-$0sdG;J z>=!S%$mOi2FC(FLdFfiX*Kqk=&eTvu#WF^~nMq~KgB552IPETSz;?+;*lp>7bQ2j5 z7J*H%#)wB~OItuFDkn9g1=af6*S-d^div?7pLymPP?jZORshl1LY-yq+y_7S!4Ebz zHbRY&=RNq~ga7>JeXCcmo`V#Js<6Z>Dupr%Q@G&DnTXK)dc*O!2&FL+fD)p(FAFXb zl{kwe0H2hUj?&Dr?>lAZHS>EWryT;Y20ug%H1VoctAJQOz!_(pLAyWo)Kl~3&EpK5 z+)+mz)zZ?U;c#cYG~YvK2y}t{te#?JOXgr6TMN-de}Nie$F|R;$?SuCkimCy>vlS$ z@i-pE>B#7;`h&rtfq{*iHxrP7S*6v_q`PA#%n)%9^4i7XuY1m%Ij5a=8oVzHBziHJ z%D?9mBTmLO3!=!Htq`I5l~}m6smf|}FEEavx$I#U%{5xT`knRHd-d73a4Z#}5ZFZa z$d!aMXLe!7fi98!bJmKQuwm0n|Cl>!V6b8O1a-)Ps<tAPw7K0L2|(CfpSF8Ewv2%* zUDjNALNG8*Sc(3nFNFL0B9Ty_GT1V4k}+<g3W!6DOfDszHjzs84Ft&0hqGPco?4Eo z5O;f_GMtHoy1HYno3YrCY7K=|PhV4g!^}Bz2wOoTp&#l%U#ovGx@-xsTXE<dRaq%` zY)vV63z>GJ`xQzepL93Wg%T0;58S+)yzKUtWm(wb_^sD3ZFXr36kA>QJgY409G#|U zSHq{XWF=hHx`7g|BeAMu!A*C6zb(Gt$PbToRCbv`=4v>)%4U+TbVPNwN0BzCyH)=t zwP|gqiZ*@v+%J9e^Opwk!NSss*XHoM9L>b_5D-lzP=xLuC$3WQSn6Pb7V<)OBJAlf z8v|K_W=j3inIuBv&6_v&^z@7#H5Q7>Jz5HlvwEa-<Hn8q`OkljxN*aV4Od-t6$BsY z9qYjeU9_sHMc4#55kbQmkqXo|Ph}_pPg}`>{vr0@j2rSzj=UotvIVP+cr1lmO5*-H z1G#WC?ewu8EX%;lmM@ORBOYf^LX_@JX@>yJgostl?|=XMwBT81oyCL*vBUD^%TbLZ zr2NM}{&Awpf9`XiLn48ILVv>7Z?|FxedT3Lm+(x=Ic=q*cPJDQ8&fb6X9flakc1%L z-~+>D!aLGIVJ>w}bcOGJ_q&H3b{L0D_k`q(*g}t9b!Oz%x4)lFXM*Kru}IV=evOQD zHgnfs|F-$I-^nD9DJHTPyMY=vVoaaMTT@qyNdT+A)Rq~HC8ZGx$@{*y38f}F;z@uh z5#UD90l@-E5F9u@Q%#tF&PUpo_qKJLJp&d@2w=!vsAg$x`eF2VyX)a(ilQ?lPHJN* zTUmHdw(yo#m8c^;Df-Q5jV@VIyJb_A$^`?as;yI|-)#%x)K8od<#R+Ia-z44;{#Uc zi1vmWXLNAG9e0}X+~mU!RTIXnz?0B#|9Il(KCezYG3&%u2r;yYGM77>u@gH^{5J<= zO^dKLZp(ZKl+M{b=z@kr$)EnzGk;$-W15;i=ZH%$Rg*`tFepk}8#cc9@A*~Xq0JB6 zGkW^I6$i|QhC>|V>68yQ9>r8vrD9PGSy)_8r*POst6R;F{DIPmIb+?aryp{~IxKt_ zYrnMFIW0g#>)&wW7Fu5VLW+Qvs6P-S$mQ@`SS&a3o$-Q}wMCb=J#p>tzdH5+W7>@I z`CyOXi7U6OyF27_R7d->otvZakV>KyxI%@tx%RI==(4N+@34c8N+(zwHkB7qjwQvx z?`d^asJ9Ezb~2oiX`&b(D38yZN~fG|7j(()Fp{Z^){RPMatMd<m4S-#Bab}N-PJpK z)Hnoo^f4$r1ooC&ZozEnqKhuVSv|xS>q=B#iR8vrXfm*U>#aA#2tkbjYy^;St}sDk z$Bwhqbr6Dy5h<cDOpUQk0z1meeJ#_EzTuAzD&@?^+QldlhgkGeBjfZdl)EeH0-mz? z!lh624fZzG;DJl`)}8ZxcK=*<2*5D7M9C;CEBnC@e!!{#ZH?sNnrp6MdEkya?%-1~ zCjtx6P3I*wUcRZf1%2bzf-ZQQNvGulLyXBn+^NJ_K;_fkc;k&rmMozr^bc4@K0nL; zB<jPO#3w)b$&Y;GBZArQMq>8Iw4<`JlA2RKqJrm_ECyNGhZD+LQgr&?%qg=_K}1f# zq*9CYWnE<0g!<j6_|7g9Jd+_W_y$doU5glrj}n<DtFoZ-d06;i<-*<DC)YLlvPZYE zfLNAQ3j<Fs7jm%n-sFbIDb|{YArH4|Gn@mpvh=P*`y5U<o5*)|RM~89JY6sdWLD>p zh)AF<GbpD$9*y`=*W~R`-g1e4vf8ljiH9GVx!-|m+*noZn&mt$`|y*i@BRDKIR~f- zO_p33taYVL(IOP%Ccj%I6k?(T$CC14CFymKo;@wM|GqCi|GablK=&h0G)$ho-zPq< zT542<M<N|L?K5Z3RGl48ugjORLO_URvEf6#Rm_lVBHb6<#Ulq3jI4(jk@=q0VhjYU z$@L2t(RcX$OaFIS3s@b#@D=nvpB+wA6pBoz@N^t8v*XJt<y8Zj&JA4){yg_uf-8)g zqMQ|B!;dMEJrN^Zu48B*)!&-&X6x6i=mvm0UsjF5mLFaAvzapviO14Dg80gsL{|JC zKzInn5cCc(WwfEUmyubYS4E-`mq(^+u>}5K!--_V>nXTP(@_W+0r<_e7+29=hAu(L zku^eB7cE-E{=WO}%XtVd7z`bT)q(F~AKC>XK=dHdFcO4S#lJoBYJ{U!<Jz)WR*}W0 z2bwX+P2rC*i?SQZDdXp~Z(T5Ba(O1#OFzaJ2W}8>Y~v=ZliM_%tX!uTFI#l>spGAD z_M*)W0T`8IME^hg+0XbYU>;Zk)<RiMIN^kG<HmJ&cf-$Nc!Pc&-$_f1-&C`)SntE* zC`xxJk=<#7S|HgM@KXvHkCReRjZY5PBl-aTKk<oAfW%ac9)qU~{3^2~3{=0Va(C{{ zbY(IGiSfcghhvAz1H)L(p+HETkvX$36xm8l7mAY=jn>6WJGWx*U~T{m)P9)o=z=9i zeE|-L3LFS}`iEE!&$qXUs*n&45^QPVA@Nc&+(P>Kx3Mi0JUo%M{8~tv!xaQlWeLjV zOnO{NkK5KCsq>a8r&j=uXsoan#Q%$@SlxHHj08_PA#%9Ea;wJibq5{MeE1=%rcBwR zDi<5d#p$l9zCM??xnv?@s;VGbf*HGy5Qjo_Wj-NNXuI&_DV2|_8RJ{7`(De^mo_h5 znqR%8|GAe}+3wo+z{x7uV!GV6iIZ$Cqt%v5b$4yT?g)AvSVX}TSZ;P{F_gOOv~0#O zJ*ZqKQ)L8hhY*9o`U_B|?vcaor@4v3tG~_3&2XNj|Jz%Dmeq}0Xj?uGGf`QKaofG2 z5Na#PBb@1MoX|jYhP28I<u~5(&~;BP{@bM4{(TOtP{EMt$S32(EK=ctoRJO=Zp#g} z+Ilwk<pu*CYoo^>b@G)L|KHfU$#f^5&jnlQ^#HySIz(uXLm^~tr>7BLD}oN7TDNuG zwZHu-3d~dz^u?T)b-FKo=}Y^~+K)4ccaYE_u>)eEqL3`DCJnekS|PSa9B~As9-5E) zdWaQ1g^)j!3HOhr^HAM;?z!i8zx&<gmtX$rPk$QB=5e|n`9R;GY(NGJ!>6Bqs^90w zlKr5A4qbBB{nN5_*^F}dgn6g(j6$c|mUSA))Y*ULnfYg*dhYhN-8=Sn2*7|JE56gG zPp37(KTr^ip_Pw4_E=hmc@3u7d@x#^Lw1U|@&?-ttRlP{%#dCRMP|$Q29k-8^`}4m z>EVYTruXngxoy_0S?8X6F3c|7f{7JXq6pR}xSxJN(QmNCoqHSaOKZ^cXaTklJn#Sw z#s0W)<B&F=bka#Uj?pYHuRzhf3l%QHEsw~w!;-Y`+={&$xk2YOseg6h@S2zcmzSZq zPTX-vXGb!V_IT-ZKm|Zpn3m8C78%o2?A3X^mE%IjLU1gK2mq5gg+L4t1T)+nF7G}Q zLr%lz_9nt{e>mi5YD93Hh^Kwo82lw_%egcW(Gyti=2+44xc#HYobm1N$TGJrslw@j zrx!TO{F4u!ji+5lASf?@(~R;8M|pKT3NMSl0wUgs{{d>?W?i|v^W}#h9$Qx*IB1Ug zz|rGQI)2>hZQ1Mpuzc+*)z_n9wb`<=-bA9->tW$8X%Idb9X1#j`~zDxx7$p+G*iY* zXT_o_2ZQ558JY-FoQ0l2g&}HIkFt<oYE(+QxCMq6-fg-EgT9DR<U3^3`3i(T$X2o$ z!{N@VY$Q3D^A62j^qZ$v-#+{Jrkc?<XGJV!Mu}Y?3$tn(jQ50x+N0T_vhFpBXm?<+ z-MHwy%g;RhjIoX55YD6$8MnuU!zo!q!JUhqY8e1<nHc%mY)MpP;+ckq2Hb1FdO}_x zIFLt(B(}V|9q1S=@o^pw7!Cnd9^ezg1&!i1sMBXY^BJsuvG9br!QLQrWDR)SxN(}* zflKBdaz-cX?z`{i5`+#D6}VwALK8Pl<-l)NFmZKhwT6A#lvzG^MPxAPtVJH?3dh1O zmyO{iA~1(pUg`G)VjbO`>6}Rfr@gA<?ht^HnxbPxi_?O%EYlfTu^&BJ`wnHC>!GgE zg|DSQ@EhN{Jsu>_d`ljom+)0%kqG{+etXN!%a$#pT=L}VF~=N(sF}*>oH?l{Vt_GU zdgP?+jTgOB?nHpYR8h}Akdq_2K{!u6Pd@o%l$@!j?$*4*s~Sg7R`i2Ar6#*UCK`Y( z3@(fwJu8wkKEJB0^5=8Cc>L+_jpwrXdXy^T5eh*n$ZY`!`0?8J*q+I2ul=_(&_8|I zs*E-yl2ee!oG8Q*=GTe*Yu5C#eI_IqEgkCX_HS)f<C;B$YVqO|A*G^ysaT&cZy$sD zs2%@RHmoCsiFLYEccf$9lm1mJUV8FBN1lC>`p}6gK)i8s258aQ@>SP2N7@HvAH^)g ziLHgu<Ya#1gHJsAqhB9!^f3pFpRQV(rGit&g{ysLU6~p;T6z6U8fww2k7ZTT$l?M7 z?Y*=Mi(&v6u`}b)l7pign+?KI<D<Q2(1*2BFlbpO@v7EKTOt|q)-6!@8n4r~x`9gD zx77l)D}B`RR?7EbmsUsjfiEe(Rk#pODy++pfW%c-$k_1LfBwARwe-kyn#$2kbm8ta zIy4ZjGAcqniS8{4BjJl~wQXG)iFW%uX8mt}{F@_>I5w|hJp(;WRROoh$phe)_+6t< zAkv|D;#`&o(Dbxr%_J7Vv1Hl!vM+r8A`lT03aQaXn=<>iUKFB)?lm0>@_YK3XZ++R zKLI`wAVZEIr`!V10Jp=AHuD9!$w9XfJOfwB0dKocJn;nTK|Dwim<7W(BMs#?-~fsT zUi|A{|KcjV6EU4&Z<`v%9eUtVgNb=|gym>O*zyvV$)0z(d7G>|;PeHRKY-Sl?zXzX zy<)pV00v)aZat|1=aBVdIfFJ9>jAW~MiHQe#Qs}rDvFQ}!TP^pv~Amlb1Njzty{OS z%s>YM#t2k-;e{7s`$UP{OgG}|7E7mAl&<^DYb&s$^RK=0t(^gVc~Dn|8q$?9D`H+* z%#Eg_!upV^%9~m&Z}B9T7$llYE<W|%+hN$sTQYJAFFX7S=wQiN9Dg-7;4Z%1rab+< z2{FNyNAQo$KcQKS&>hI1i~Z^i56j^ySpRtnZdFPnqe3;QoYV_YOsa|FXPtBA(rsHd z5A>SPKF8!zjhd)ZNwsXz3%B3yb=eab3ghPD*`@06!veS(@W5%{f5Y_9HCrZ3o;<a0 zQ)|t0&#R+P6joIPYJQcmH@8gO^u#=cQ?2S6JX_Ld4SepWlJUX#zD<)3IP5r8*(7Sr z=!S1=Ta}GXI_X%6n3OSNS$x^!<qGZ`Eh_i`cyL)+hNq?S8B2W)?G-4nFvYQCPhWpk zW3wWp^hlmTOqIEP$7y>*?D(G2l{eP{^e^4T=v{m*I-c~{P&gT=@I*2Rr!%p>XVKjc z{UjS~9etqPQxhJF#r;lSJQ}Sot6%j(x5s98#EpTis%vdF-0rS)w0!lVD~>$ySk$d@ zhP%G1i8u$WiGaSbSUTWwf$!48`IJog0v@;5ox|8XiJR!CR|Pd>76}XeMTntb@GCk7 zf;zZZv|NAq!yiJ!xd)O3jbfii;BZJ3qG=Q-0crM;O(J%#tE<B^5(U8-uUoec@gxsI z<#eIw>T=s9ms}#NZ-xUak)We$zv+k0Tl<_X<HU<TY#07kDGW0z2O5#~q$gl=c`biE zg$1fN_W|C!ckd8@i`bxrr6|JDxG;HqCtwfYVT+J~kHm*TGF+S}z45l-18_6y&=?xA zobcFVkMRllw0K29TNo8<x(I?1PEwYx2KVbZL2+j!o{cPeN9RZ0^LF;NOooclHBl+l zf^jm`=h>kGfG(BS-I@-ni{pMya+Nd1LGpHLvO7F0(ocD14RjW8%9v*dPd}<@6so*= zGwbN@O~xW(aU+T0CUlCCFVt##lAI)2)I!kmt)%TRBO1sgwhlN^iUQn-i-yB^_C9$0 z0e;8xcij2hKOY%b+tu7SzNfb<n+^F*XR4yIFC2?^hdOS%Gtd*7cFq|nGs_ZjbFixZ zP{>l_zN0r>`Ge5bKTVi6ON|{ZE_^ToN#<In&*=QmV`|k)YSuAnnE_<nekZCjqYj*t zTGyp|!s>;!_;WTpwk=w@+%t1p{U^>%uoUAfgRCa<uqHW|PdIdBaj4NUfk9Z0b1b|_ z)Aw2Ll_ejP%R9TaM8XFjd$96*^~^`Y*>TC5^NHlWn2J<)dz%!mm3H1%3((3|-(?2G zXQ4k^lOL-;Gm#6Fdsy*EJ3H45&i~85f80F9bl2NVe~)sbdf<*lvbltR?Yf>ySIy>C zef_Puu8o<tm(`)O-habSZf~v`Cp7~z5ppBK#=Jm$cPPlME=QJctm55%kJs;sM<LkR z=wPHK->4~1aSQ9B!IfSC(32&X$QxT;v}$ho?ah#1SXIarG*(OI^s}5n*-8^GNEVk+ z142N}4l9zZA4C1fr=_Jui$$pcHv<ZQx{gLOO!SykdSl^Sq~G+_`OVCb3yni~cznuX zpM*@^ohz$yZ|m5&wQckGQR54ZD(}DNryT+?*nkv5PlEU`=)&<KS&C;%tI+h!aga-2 zeDTG647AeUY*T47q;M#Nk4BtBv1Y(`C3C*?dFP#nX%o5w?2|O&>Yf3l(K&P-*pZpt z4wCL<JGi(LPBSy0bX^Ddb#PbLpY!Cd>q*T?x{_@5)RM~U`g4Y)_jf{t-o-40vePRp z+?Am%iB}W)0Uu{z3d~?j=hMN+P%0E=%@h}v5Cuf4JY_A{7O`RYah->?eM=j`eo4jt zAvA~5(6oxBRk_P_c<kwzs;p2ao-k+j>^UpfMb~Y0D{sx{W;MQ1)dW-jo(q*!m1FSR z<DNQAxdLk4OGABKfdlq))YVGX)ApIzFlx!-#RJbSsA@SI6C@n%itCLDE#81P-@4hB zg=-<|k&#Nr0N2VnhaTvx3ctK6x_U)2DcW0y9ecFeZ<;Erup5>a%S1fj^`uq8WhQcY zrfAfa5E4*b80oBAI0eEbT4Xq$$#(a5adp;o3_heX7VWoQkrypAqWmkqzjaS(v$I>k z5<V1Wkk<T8w>^ODQ)yeKC%gK#fBY~os;7Bo!e5*8*XD74kx6Hw14&n|Vz4tC@9}lC zha;WNj&&J(GH~fvzWl+X&u*w`l)g$Amf<5tWhhL5uTIgP5MNq0T$@5<Fl|TO%Y`#b zCsGhIMLdzDtaso8#*!Cu4?B<@s8I36fk_X>?p8YMLuaj8`7-LRn75$Y3<c8^iLHJF z%BC3xE<xf@{bAjglh8MKFt)%1D9Zvc`2iMiV(5RNE%f6b|CkJQDGr-Veb=qp+}jZw zJ(W9g9b>sTM83m1l-o{Q`751k7p+{g;id7TTJ|~sE>3)CQ2phAUJQKEheCbspo0!t zym;~Y_3PnH;q&wtWs8)bLjbafzI-aq^YMz{$H#`lVZA{|#)ah-+_icG`)k*%!O{sJ z*N<>BtmK!z@@4eASbHEhJ}sA|#|*1FkL*dsQuJqj=eN27x=O_w>T0~Up4>e0B)4&f z^v+j%mz4<37)}=5*KY^6HgOV*R#B(DIh9Cl-l(QcQ^`!$C4u=QMiK4;<S`y8Hb!Be zV=JTKT;I_DVkX=zPN*f<LM~7tB)Wc#iui9ge14JFy8J3wrN*}eIID$+mOit4=2Quo zWCVN?a{)<QvghuH9(m&5NB!RwqmMsI1jtZDad2i<m6xeh!r`xg-^H<jZG7|C{q}uf z<%|1w_Pa;b;JM1?a++wzgOszUmCc@5=8P$#A!X6A@__3!0Dga|r9~D~E<&YB#H57b z2_mNx07hC4JDg47zCb8(0zX{##gERfo;gEJnPBN{OT*~iRcx=3%}{8!*Ev<VQu_Bl zTR;=HSKmf+(``torYAE_pQQ?eXvKz^dHnD5ZdtnFp4xp9?&blTyVqIn%G!-o)Zp7@ zBSv56P~Rrgh}X0(9~x>yJv#WaYi>N@=o1K!E7+P(V2F-iDXq@{op5_uyS0k4R+s4r z0@67Zs1G_k&S)$W@Kq1?icu&eSB4&}E@RJ9xw4+Kp2bYbEw0u`dZPB#uYMK7Uz|F8 z<ttwSWi?aF%NB_hB%Q?ln#AFb!+QGlH^gk1J9jSb89)u{pc^gA5{%OpbXRU%6`pxW zb<UX+O)}y!AWyPqyyYI7JA;~<ugw0!i_e{K)QNV15t%oDM?k=yMI>L{Zi1J((e)MH zmYELDP*6o?u^k?lc4w)8tE_y{C|sp=m^5J-%#yHvme~+D=oZ)Q1u%1l`4Q;L4(+JF zq82+N*|`6{`v|2#5!^3)ZZ?bh5{AE+IcfBzAf4yP>T#x&cDojM6=k<z3{xM=_EA)w z17+wKA!^QL(#Ft$;GtNuS|mXCmJx3RT@gA{1d<V#-rBAZ50JMoI~cAia=kQ5Ps$y) zJ5x?C<V`_6krn%$SbOArW$8dwvaB){aHf5R;^#6dtIC>cszx`CQ9}tuP?s%jEBm^# zqZ{ycEsqPLVogQW)3v9cvMn@}T)Z6JE3DdC$RixNRKl&&4m@Vraf=|uxg9B+0|R79 z&~Z$Mqj5}Ch{z=2%YAM&7{y*g)NP0rBi70)jW02qQ?+(%Ub}gpqu#HY>VydzPH(8u zhFf6xq0;|1)B+<rDl}6ko|M3nbXcr@@stAanyHj+D6ZQ7_T)9oHs29*FLl<n1shUj zwRW7aU__K0Qi)z8-en}ZT**G))|K(D^?6&g@rU2O`Iy7baH}fZHIgl1v;LpG_kg$S zst&x*Ik(sM?yGw0T~@c{f^EPR2oRbRzyU%@NC+e$kdWU@LT2WhOp@O>Gs(w5$fS@0 zgpv>v0tA9-#s>E$+p=s~y}thLyZxSizW>_$-m52Bwq?h1Y@)5Fb5Gf4pIz2oZLhVq z+HwmHtmoH$%B0Y&yG*q>lPfK<iWfQ!B>_JZwjQjG)fHG5imNd#Qf!a<o>kX$Ga<;K zizbK%;XCLqh=SmJyy&sYGU69)yDSq+*UDi!p4I!@;SEeI=+Go|3~pPVnP@+L;2~TN zcuR|dx<0+G?tbUT>h~mnLHE%zx*np*f-WOU#6)~;fB*M?pDtjb{$n5e7z+Tec*QG_ zSs#A*;g5XeBLv6b5mcF;(#%e;Zv-H;hE|zq2`@t)Vy?I@lpA9!5~~G_6T}$V8nrVn z#f%?8$|!{UJ(+SL==aJ$fARw9fio=9LI=<-Lw*UROnep7Dh(OLrmd7c$Mz>DvEM~& zM)l$DL0w`|B#Jyxi4r|kyEIYZD8%>~CjE*oL0;vIKcPGP*B??P%383Z&9VzGVlLm3 ze8}aZG1H~MyQf%p<#rS#uHAG&$-nnI-`lumbKZ3xy#1E?^5Ls){AFY7Hi?oE^Wr93 zp_)b^Wo%r#@%rm`e&^OJ)^0F1uY>m5FquXygHR)dLqgR`9wBJdGP!Kv#`jnjt2z&V z;qOv2lPBucnIM|_>o4Rsu3!1eEs13+f_4xkvwcRTb?4{4uzAb2;mcnl`wc54sA`aE zqdw~$rP<FVJJT!pKibJ@SV$u`Isp<w^4eh{PuLdNCugGm$SpfRxAVxCN7j1lR~OTR z@rK<d{4sjt+N_^;OVf|f*Js1(gmL`waO$9O)sCP1z<dAmW!qm4q$xuwwkc!*LRl;7 zl@x(LK5{x>b6cW&Bw55L3axUiCZxZ^&`GUyoiQa)5G;3|n84eZj^b{_BaOqs)lbZJ zHg}*MsGaeh(U~<BmxU$?{A^sj?c${)YiEv6E!vRx{WgyCY>ypFTb>i3>j`RRrV#CZ z?7s1dV{4X*qz4(M{s?B844+K}UW|E!+tR>9J9XF7Yz%ro``OPDftf(iY={9<gLVRi zGrJG{@gM&&tM|Y4TfaptDtZS(OGndRoRdd)8Fx6LSScAeAU3jP5ww<Un9P0hlb^)7 zoBZVA>nJPU_rCXCbImncR)%llKE>*%=$|=%G4||#m^y2`aB6b}WmssyWY-hZD)t-w z1M#B=iOXq@kJqAT2%Mm2IWtp~X^=lj+&g)p=pj#pOg@W56-d0ypTL=1Q>36H5(lZH z`m&feNpwuYS;WZ=RC3>E*Iq<V72pb-hRAAMylKhuu|>z-*@KhLd}aI9SD6=WU>m{6 z4b37UWsp|eQ6eQVip*gB+iu+XzdwHTTemD98;dO(OhUk+&Up7?6y1%hK@EU%WE=^g z%O@eFvE;UEt~H$IhSy&w+d{O8Mlov?`>3$^6iYN|cmKC<hCILd{qJF;N7bCO=pPCv z=?1IQ^M`+94`_X!>eA3@w^R9CV0vw%GTGk!mtXlEYw*~HmnQlao5`%{5VY1M*dO7M zgZX1dFk746?+4A?frpz`JNIip_bb2pi@%+X^#dKyDm=*vdInrD6X0RRySO{Oun16f z=6Dhx%B?uuZGrl*Q?%V^`^|QIsN*=KAwytGSwWw%$vvD8n$>HOEb$87R>=8`ublCw zrUhVlo+3k28U#f?i_a9s3x?a5>A!f}OK;uvIl~<YJ<Ckt2;qYtSi?@|;!fHu4kq^O zo&DjDZeH`YExfA>)Zcm*^*LiDUw}7dEJZw31dk)lma(*~9XobFViAQkBSX((lT2JE zx&}haE4qW|Yc9#dQ8$mA44$USLW$K~s4tY2=%at~Cx3GA;6d(@hoau{mbc*gjoWz7 zBAT0e6v@LUxTG>a#si=`?L~WJzR8s9QaaAN^nke(L$!PW06+jqL_t(1mYQOVg){BY z5FUSs0g0LEhHDR{Sk2UsAvmm;bZM%D4z=i(*2{8sC%r=DBl-e54~bPD#d3w)y68?V z2>1*QCJ)vpNUZ#skX_kN5TY&mYS&95><ll8jpjzTZcvdR+15oQATyV;*+Y<b5~;S~ z<Bh~7aqNn9(OZ7{fp6a&zxUC_S6rOv&q`oI)bPHC;R-cUek6w4`G{7FJz9taG?253 zt7Ok5r1CIn_=8f*6kAvjKtG6^$@x2W9(ZiuD?a#cW5bwgSBG<X+Fp_F>@@Xh^PbP} zG(B*VIGJ7)Z>9=}otQsW{^<vQ@xZ}<9@;R!Y?GNRMlG*hE1T@gXWH@lWV2O|!g6tL zpUvh9kMC+OA6@)=zyHVAUiMl51``<&9RsRN3&4Ab0B}H$zqa`AbS2RaH1pG)UqA=! zqS{g%kj@tif^u0mb%J`eR*Dn>X1Mi`YXbZvZQ{E<Q)i9p!M6*E-;=y|`fc9g7Ic9V zs0MU_lI8o%D%3*)r`8phUVGE+Uu@OFY=4q%lDxo!Jfjq1F_>8G`2tS!#$%5?0;S+x zh!OATqb3BWfAYuT`eY+@b7(Nsj(%h?w6$ArRLFpxn_ikF0~8lZ$y43+*g}(t!=n0K zR0rJGkP3Jay7J>6|M*wF@)hpz7GFWRjicDBU;S!E3lW*ZWnUMyV5|$|4k!BjJOS3D z^MX8f(8I~P=^Kc1s78deK#YvhMg5lLa&K-1Ffoz^2(T;?%Ud17psBB7{ZE$l?9aNm zN^=N``U*A>79D7V28+5+3m9BeXRrlU#z>hYy%0wr3{Z-gIU)ZNKO_@*O*?3(vlwj2 z*1Kk#V&je!hmeuLXgOmgDPP0~c3j`S<-&A!y2eH^3R9|X!Q_nW(p0FrZn#i=F2abN z>XNCD6*D7k5_lts;|9!=hyeNoG-MB8pFkk#%dferZ~I2s*#Y@MSRBfGs?-~v?yx*n z=JU^<c@MxYHRiq9ebe{vEB|X|`H3Z4(-nUr);7{fT(ncIYN9!7)F-X#v^PKQ%<eai z?lrcr-ujUb{VvqkBXl?>?p-5OJ(z$9+84~~vBvAxM?gl=-0ltaE00YhSCsI*th2JQ zGz)wsLoHbFOcP+q)0tzZyxhG2&vOcn)yP)k=kCL^{pEGCg4i|ffC_L)je$-+jwtVk z{<_thOT|T%`PuXm;FgC#FcZjP(_jm~yKGo28M#7M6J7mbDnqSwX=huN7gaumZlp6# znw$wUr8yQMfAId|9Hu)$pVQaeVFg!PuG3x=#e~t|@{MnNqb9oC<Xy-x3K({j{KO|d zfhjc${%}Ub*+Aj^!4H0rwFlOlg}cH0T@a%rKA}lC=aiuCojlQ(=Z`Pc9+0KqPC^2P zH&YRzh#v(3j>Tt?fy?u)TGi+uMal&BWWh=XS?~h@&}I3%WjyO&%Az71B}SG0<0~k| zyCsU+nHqAmlpKr45%d>bi>ic(s7SXFLaCyG!l<WVAABp7O<;8sSrKwWl*>p|qH18I zp_vfxFqRU-X(ZUDnNCKTxOMTCMa>pozbf7rR2D;40cnscw4Zks(8H%n+$@Z(`D_@) zz`86aMzORFdLooqgoH(4IP^e9{$l)&jIcIib#?)f(j@WbX-T2n-fi_E_3hKLoxeQm z9?&$Vhu@$yc#9##IkDDPZvMpn^7j^R^OD1@WS^Dr5`mZWgM4|$sg5^;`DA<6nmN=y z{HPJk=YIWt|Ice*`MTvxRuhZ@){01LGJI?U9J#F3DP+gsp)UbWlo51ib})u|7&!`R zl$YdSN=QC}f?ILhu^Y9TaBV$`yYT!>E!E;CPkOjrH}gz+pXy$(bHL|xktU+_kY%x@ z2`@^`2m41az39p*?;8YsO(C>nzyQZ9VKl=W?(Av5ub-VHs?Z3{6HqtGq2yklKUEE0 zoX;e%6a<g)lp$4GUudn?C({uSNY3d~I)bCVPc}LQa!a^o#-856`W#<gjNh<irW|3% z6bYZ0nE3lI{@rIj^BDp+V%toFZUkTATM=E7*YySr9JNm{Y#_3-{sgts<?tbruG@>V zhkxvAt&xK0m}Htkt4K2Cgie7#Km{nAOQjUl%@55+BgB#y3lpq*alKJwLQPLmxC!3D zo|LzA0o{@W<ERoP#~G90q0R&5yHu%r$*HcPJm#h<nR-g~7G#q0se#T4byV9)P!ATX zk=tdbL7}a(%o2B6^<*ZK&YHGkSh)TYy^4v$Iu60GT&j<WcRKU~_{z2y6brObQC4Z1 z#Ww4m-2>IPsEk^dR>H8@GZMIj4g(7(U;tV;O_@ek$UpIk1Y1cz$g&w8ma<q49bec6 z9zR9u^x#wE_z(C<!x<fU5=c5bUucLrd6Y9zny8$NhUc>bpxOA&-Cz0I&40e}a%=O; z3s(PhkoL>1IU;nknP6+aJ%7ye=QHz1+{2Gnjixb@Ui|*w{)0EX`t5*{FkpftC2BMa zfXKY8VaQgP0)_++FhgHF*EGBW68x#96NXWZxw2FcQwnSY@H<Zv(!#{U*lCIWy0c8I zYfl+k(<4lt6xgHATxrD45mc|oAJnbIt!D%dl%Poo<sgq~nnI96=~t?Zvz?X5Sn<m) zx#D}fZu47q+(GIkv9VKV#)DijVV9kBpLP4)Hy=5^Z{zx{yawinxX@5Iolc18&aBqc z^v40BPmfegKlb_^<*+{2H}%o++$0hWOnVe&a#@BJ8-q{%)n5`qa&&A_z1b-B%NF8f zxaEhp;^uqbJ@-Pn0j0KMU%2BU?73d|y4RgHzzWdhQ`!WY6Gld^r5H5?`r`cY1=j;T z%%vxTo^7g@ik@Oq&n?^$moCj`)0l%MC#P+81>UGki`k4D{hdg{s9{Cqgmw~cLNJiV zbE;6tF;6>5-8sX=(;wFPpmTbjcJlEfm<W-9cv2dnafG1BOFR@Y76Oaols0(g4qp=n z!K^f^`Mx3Y;UWO>MVxTKci94Hk{9vgC858Q(y+4v^U2aKf~{z+aW{q}E9$EeAq^p# zmRLn-E`@hhZYe}+4yw^?40jc-Ea^+R5XH45iQmOzJv+1%q;ji+&a&{>yDiOJ_~1Xx zx#q^Y&6Qr1eh>_$lAO@@Kpa+X9AiGl>_}!9HjC|$PY@~wK>!6kp9fxIlv$!}!ICwD z+0TFD6W@IJ&#wH*MI)>8u2E(WKwQ=&&<yTvlTLjqu%|QCW5~YoiM_^9cJUwn`QL9_ zcNq$1zN&^p>JwKn*`ziC7M+nL+7MW_n}pF~v+d3$6*5E5cUUHs>QhiLl^7eCJ8=Sy zZgsZK@&y}tu$F?6lYneIbkSw2;2i=`0&1Pl^DgLhA<kFNlzgqvp2@L?w0pFix0ze` zs3yhNpRRK++PvfT-Gjc{in&3;bltEL#)3kBsyWjzG7w<nX!Gd(5C3Sx`VCk_CRq}P z<&n@4>O@yYIt~^?6;1o43tz<PB)L7yMhNu<A9<oE=7bT%G@97loMT;uObh`YpBU#R z)RzSbxELPcQ}l*6ya8WtBw(%U;O6=C<I)2QCjoR+0TuTcdH!TE7>ivq8HaSRKY4t1 zPSAo*O6|fd5{0kaQTY{al0X&egu9*cl>{IN=ZQ(@;0Ssl11Bf5f!Da`eo^1&3Yk`6 zXX5HAfmqQzol9y#6(g&^ZwM_pmq5LED+!)flV5E)$0fOfklmks(3pCT?pT!X8qIa; zt?JS}*U0>o7HE{HZ-J$B)v4!#$=Q9IOg-v-N*Pacak4j_CgYFUW4e|<`V`XB?L#$A zopwsU=<e66Cm8Q)uz-gGS_Q=shnbbyY$3s@&NnNC9FAm_qxC&s{-?h=T)*=*?_3od zEPL@5RKfLPt{pVzqE@w4pNv%qJi5O<b;xT?C0=>Oo8NlFySA;n0vM*;(|fryJlsF+ zk$|Y=r_NN9Z2YM#D$u+FVfclV5znV&J=F-kx-GkgWF))rdcxWwN3!@Ln<Pp({B=He zdM%#wYh7#Qb4b}xQE@stxMy<dc0A%;y!PM{=nkwMAkf%25|$E+w(tG$U*G(ux25BK zvSEBOBQpy*U$tF$Sm^-V{?zW{Ts)7>k#9fOX~7&nyQ1~jr4$)PWPs>?@$+98KYjuY zbFET+jO|S$gB4%)t3o^NIW8R5s#UAr``-5wwFAxwdfd}#pWO$~=XxRc0LTCkI(0(p zD>X5K(2K-UD86V6Tj+SjWG^3c@|XyoY|w^Z4c3qFa7y@q24g?Zb_5_x&bco|bj+dj zH@HDsc;r%ju2X}q40$q}oOKi2xK1iJ_y~~)`pO@AAN5^njC`9riI~@FCuI8>+;6!J zvO^FdL$`VSO4W^&*lnpTj|7t=Sc4p72Vh-I$<_OA=j(i7VUpc*x``4g?R<K!dH{?q z`?)bnB8#aZ5e))K#*Tr|qr_;55i-ek8)@;&W{;3C@`G3^fm}=MW)yyCA@W$f8?#61 z_y6gq|C^Pa+IIbLl%G$e6FGLVYBuNRYS`_y=dJMrPHiGy9S@H^ZikKR+i&=}kAC=f zVc`hiXlln{`P9=V1xe5wrO{FFCIBb(#K2XcM!ba;^p*1cbL0z6r(82yk=3XCh^3_> z1mo?-OS;|i)13$1TTfq;XPrYT$jS@~=a>%#CVu7Qcs;W?ky*lmi<p3j-Y0HCfKwTh zEy0LNcjvu7*nfEM=CzlmpuTE4zzcWwdz5-~r;qN6POF}E1^=C2{5Q>Zs41bW2otS0 z3`Qm<W)|zgM~@zb%Ch3ikr*qu`Qp^1)y}A+v3kc2>)*NE=Rg14^njkq3bl1+0`gy% zEtNaaQOPqjWE6|>$tZ}0*%QZHGZH_W$nZp9#P&(1nO5tfU1L%zuv7?9bH1I*KG|eb zIR!D1;mPvo`=>q?=|G7VlrOdHP*8Om1PLN!HQMNr&4Bm@4R&xaFh$14Lv)nNK8n)x z```rdA(tYa$|4&ioIfr^E|wN`S|BIfQC|}7LXv#7o8;5y({tJbx=T;(ST!8F_tn^R zpPG8{OGbp?$`WTA2@;nM0tku8uHP`GzkT;VJh1Oyw_Mww9gM7e3n#RC%P!BgT|2DL zMzt9<&qiY^zW+hLa>8FWxaN=k=+7>>;0niPH{Up$YCQ9%$x4ZmWlw#TiGks~X7q^u zlFt%#JZ1zQ!PZ;opwmn|EV^Vm!2k*kR-fh#wTQumJUq3?=lqKDEv7fK1*ZU593vR) z8`-w;@)PBI31luyLezo(SWzUScqYzvVtoVg6MNfV|JGMm{nC~k&Jysw*aIcukc4Am zbw{{hsk<7obKQXFyhol;;4>${=-gD8NerXdzW1B|@(sjX1mbiug|K_~op;U7&ayop zdgkH5A$)w_`ZG7`P~GH*V6)x;_0`MuPpHiK8!x^d(E2fr%Q$vsg#KX*d8NsvRqP5p zIE>e8(~1VBkE63?O5w5N@d`j8nm+w5h=D&TuDc%Fooh@$o<P;K1Oxuj7(@gC^7Ble zbUv*v^+DZ{A{Qi`of|x)1eR44r4;5G8cJr1m8(jl`psJ^2lubIc)hWH#8{R$BDM!+ z=RuK|*&on1!E1Oa!NV)GKv^crbP=p6L03ezMYl+OULJr175d;tH=oipa^1bJ@}B9S zGxVx|rYz_0o$LYdo9Z#GggDu|;BgYy%0!n_89N0G*u#gO1jPU>WEq0BVPrV6*S~!0 zr*7Z<)eSEhTz!QbWu}sgQ<cVC&<N700_@rB@oHnvBEHqc{&4=Ne{{F;jvL<c{&)Z8 z#+BOxFUTePfn5oU&>iuUb$rURli3yFl)TiFyCTp_{00sA#e6})$_v=lGOE=vZ=`WT zv!n?EW<tVsQZaBe0MY*5?e62}_!mzI&1Z^16`|D=gRg$YTR!pmyL}WBn2;yM?wh$6 zOPK5p9M49Xexo#EeCs=3d*{!5AUj;(UA2gb4w_lDFrDj)FZ|XyJb%Un7{!4On!!d! zU--foh-?LYW$71T7tt0Wm^fL`SGJ@2@P|Kq-F4RqC#ig#Fs_3_YxCyba{W1M+4-WM zpB`X(pOSjCfd`!HRU3&guw*eCp;TekXQo|t1IiUa3*vqwIDouLr6wgQe9<XVpUYFp zMP>+<Qu1oMVnLD}+N<XyNByVX=RGoaijtqsiZfX>*#;}=$1)8>)=}cSNbNW;#|e|s zw_@2XfBGl8|M?4JOA2FK7Z+Er$-d-`Msd^_C?<081mu^31i^?Nt%uEZT_}?FE5=>E zeKM)XnvIa!b{f#Br)ts3yywsUtv!GMMxviZ1Vqas0Euc>tjR@tdwOEWXEvt-Kzz@R zvq_c7elqpR+TOhrcRVuwjo}OGPI`Lj>cNWBm}<<V)7hXL)+(*>BlX#1Mp)0X^gDN; zHh0YU$ooF@OYiznHr`L14GDS7m-!k*<XI0e45)$@YTOlwA-QT|5R0QfkBL4(*&@$t zR%>}<7y>OMiycEWM+uO2lYpiA>)tqrzf=%AXN(BJ{8%$v$<#%gUpA0i>NbygHVZsh zmx+%HJh-1`OW-h;C2qDgeQ?}VUeNRwF`fdy&GZtHUpkQi<+h0O(u@~*Is*uvO^Z+q zeCMW{est@tbOwKH7EQ3pVm?o#juR(NY~8x`zkKwgmtAoM+>3T$>XixU#W}2ZdH&?b zs|UIhLhv2u%yghbV2n97wix$X$B*K(^X=JkKLj{1>^RG>vPz|lEXWVC;EirE9oj@O z3iU9Vy9QI-BAv{qGw?3AG<fM8of0}zR^=i`=TCA=<tUtws-sejbIM*VhKU{XmKB#@ z|I)*s|6=;cq1FTUIGIeC`p3bQ>xvg{H@0s!)~z&_ju=BFOrDt$u<@*S$F-W#3>;;S zMKn&eg2xA>J9=qB)lc5nO;>I0Wjy1Fly*KneGe?`W$9)#90DDR?*b&b)9FbS)r?0_ z3T<#}u~9AYts2JU1AD%8&!b<9m1Z_xm8^z#emGuko=D}>W;0fqZAO*&?9qCAJ{^=Z zyYHHxJ7T=_!t37n&bQw9`gi!ApJEjw3O(CT;EG378mRj-B*3QugKm)MON5``s^jOA z8_XM-nAh|Pgi)*1*&SB5mYfn^m5ln2;*=1s%Tc+`EiCcDm<YLsm^7OSY{B}|W7l8( zx_giPS$f!vWg?W%7&*i9BvMu)7v@T4Dj(!ZsbdpI7nN4YtfcNB2x$-reu^IKlC9Hv zN9A~N9l9+!>sm|HsxV}sm+g{>#ew+CksS%qIYWhYbPnQP5i<JS)#^)M{_<=t*HbtX zMGHY0QTQ~feAXX7pYes-1KpV*)`{IZ3Ry**fC7Q%ObK0#9|9<_*7Pe?W0{}=B>|Hk z`G8d-y-d|Z2y%&PSLve3BN&8B{a9y){Z}%po~24h-Nh`r62b+Lc&=u!tU0Nq3!!|4 zgmsN$sE$Rj24Qhzqr^lC7iM$xXKwJn^SyMroUQt?O2s$Z?(vDK`|fNNGXBy<g{_;0 zUvhD5?FMT-dj_YCct#Amz&N;NCQx4r=1@uNJUQ*wzjOcm&$;b^o~A()T?GhyQ2;@P zT@MdyC2}h80DJ+X7$Jm4?V)40-uB=>)r?1mH+YFsvz|O&8qBtw7RwHEQ_W_>uTF=~ zWH5Wgs7%<i$Lx4x<QLxjv+sP%FRos)KJc6r`y=_D00X7-F@8^a7M)eA)l1!+if}3_ zgd{ABJJgugd0~{ah<u6m*7Rj5By6^99(CAI(ZDDvxeJKh;zXR59yr&D?^1KNXT;lp zGm}{syZq8?Zh!2r{bt%I*k+c1ZiId^gQRJt!@l9nc&=fl?Az}8!KO7Y%_rl58z#jp z4xKfv=cI=qsJfcM=eh~!viv6{z?w#CX;nwnpc;5sr__QS+Yz!uFmxA3BjQ_eU)xwA z;PN7G-EqeqM~)o1SZ%bhdhHtS!^P+gj?TLwoy!4z0hHZAYHWi9?L_s2<&{t+HtkNP zupb~iy+1K!;Ax+bKpX^NR!gEHeu!F$w_PkRI?7?$VFm;O1`{L(`^${uk4)M#mW|7Z z)u`-QA?@VJz;Meu(hr)Ta-v@1z<V;=DG+FsAGxQJ%1<?AdQ0?7wG#tjv{<$t>R)o> zTaW$WADLB~Xd<rNh*@q5&Vi6Uj~%Z(c7N>~U$t@rL(4bxZ@t9Wahb940%Q4@QB)O? z2JsE*h-fcK7Q)moPduNP^z3EQQ@-~!0V)fxsfe&#^jO%=gY!RU*8>1TZ-h~;n6lNb z0v?XNRbbA6Js}UG<#Y@uiaWkh``+#^fBgraTCyp&XhUe`%BiC71i^fxmb8kES+`M+ z`*vb-chi|N?3vX5UCz>hW&iUJ{^})LuMHhG<6vBoeYL<FCQ{h%DdvvvbYN2|ayDr} z3naVZ5;|NR^cTP)7&-N~@+O{09*e0~Vy;|Wr$WNuV9XAHQVn<tHhJhK$^;6TERv|1 z21$MSoF6GX2$U1Dfz>mTE>PX9y8Cv`jw~B%*N$fjag5#2gV7vR^|sk8jl}EI(O3WV zAAbJrzZpgOo)5etz0_I>^wd+Ty^t6`=T(0`3Vc!mtfYQ4hn;xNP)&%acvwfqcW=7s z{`>Do*d<a28Cd#-=z`AZS(4y4)5IvB<>5-LHZwQ--uJ%u+H0?+H9UouBLqJmEj#~> z=cflw&R&h{6oLUys9mk_Gm`xXRiKMSqefpTer&Q9RBLtO<;mQKpAEw{5gwJ8OH5co z#)6_$v<k>4{JdJOlgvc(z#fzrWYY0bZpn!#c=_dzsj2^T(d3C?W6grD&^-RgqRJC7 zT1{R`q!0-qNon9<SMA%P6opj2I%l+-1{EEjHO3F+GnUZ|D|WL#lXh6Va>9&f<oPrv zWX+m8>lxM9J$F5FqV)A;uX)w>cfBof*$(-je6{DWsHi_*M6!=qs`Hdfy~K48`l_M< zM+Af=KT#OyGMdxXSBkC8`SfghKwwh3Twq7VCFNSfsU9ATn?rVk7at@92j8q4iQ2B| z+YV1ZIN5w`(dOphy13ETj8gS^$IfR8Zao@5S`O=(b~!$Ev=+=~$9K0IQ^BjReEqwB z=2xJ;Mv#yw;d;dv22|O2F&h|GA$kf5<>zdZs;geq=)58z%PIGW)xiu2d}5vwFU`ml zvy~)a+Wh%y6Idp;qreamX5dVb#Yr%Mst%kg*i`VZPv!BsO6)D5_-cvLN<U}g+0oLH zvC_ul2TrUh6@14g@HPI5UKA25tDOj9nQ&k%vupppdv@OO$}3*w`%z5zak^E0XulrO z&hcE;`gtn%NhdbsmMTC;3CjsO;1UHgh+uMj;!9ut@}9kWW&36baw;VeD>E5rFro?q zPCAuZx^yW4H`wE7_3G8D)~vqZf(v*GMc1SkGK{#a%YU9)dHyr!t_RTCLIVXUXvC(b zHZxqCHbZpO<YTrB4jGxWmrcYSFPxkd-knueaFvx&mYlqYzXSwLY@kFH%n3&b7)}aO zD2y*rb%YX!QQ$+p5Qq6NR)K_z7133ZD<RsFSA<;7L<bG7g1n*(<d4S?GbAIH<A@~b zwvA@lsFscCX=8fMn3y$YrrYJ&Mgtb1j5TSz-Y{n?MMTxMn?<H&hrp)I#K_@@1Xn>+ z4lpa>sZxbQm1cg+=F47r^^(`V!nkCkk&*r7-~rhEC?UTzR@QFRIMDV;@HA*yY8Ig$ zG9uBiL3>rWOL$q?l#^{dH6N^ah;uiDKlUY`0-4fUpn^o-qx1mLiA;q>F5@}9Yvyaa zj((?XA1W@6R+Ri?f6(yTRxA|{)5i`}{YC=sUUw#FP9+ZSGVD2TG=Jf*f9O|kyy0gM zpxZ4conQo&uegAwjIENw8F(n6kU!W+MTk@d&gP)2+Nm)w2+Z>h*+v^!0gzRpJiz`2 zF)1C-1i&>6F2UKDUXc|vYza4=KPdsrRO5wC$!AlEe^VZ64Dno;hKh@?f9X&C>m7e? zIH}NfV>u`c+;@;j#aYA2l;So4)>HmJe)Y4LZNFk5TVN{FWSQ2Aot26+V+1J(NnTj; zi|+hM39#1Dp=72>aOj`_9hs64SNGj_AH-PijD+%;r^MWV;;vh_ZquesklQtD)(j61 z^KKG}S%w;fqcna<8LrE@NYdxik4+E2;flc#iNRL$fnPW-kORhff^_6>VA#m!QRCH9 z$<*|C-FNz#LWyJw;nQ=xWR^g<AVOl?ptA;h5dDIHj*vORD?=>>eL?E^3c0xJ8SQuo z-BoI9rXeI75{8+jmUqd{_pxA|uNXw$s@AH<#|<0FwGB-p1YWCAZ&a#5W4?TNmt|L@ zMl0EL``TgB_Z)P?&_b+NL!%Hgnl&T9rz37Ono@%T8!CiIO-kHO8BWZYi}^F@#<Eww za`1IOX<U1i(O-;W^}3)pEH_ih1o0}tKU@az4zLTN5WtKT#7v_Efhg=G+C&-#b0EkD z*%v;QnWDK>7+)<D|JZ=c^VJZ6MumaY>II+!e5z|15LqEHY&L_j?9iwmo_XvWw|y!a zd?YqFJ+vgAE{Peu6F4pkJ};V|a$56Nb1KBgw{p<k|6prz-{>#@!f(Fnns<!!k9jUG zX(0i^`CO}7$+82sK&l#cVL<sVgc4DdGx#^D)mbGWGJrBkm&FOtquT)RN%_K@3KwTA z85%njd)%q{UL!~n;)45Rm~HRcwG&f@3$MRYe^%9tLR7I_h-!eW=P)VuQ92#ahHU`; z6GraZm%ZuMyT3j+erz-k{~e|h7R%agKg<*oP9uuvozkeW=iog?yrpI#Z+D3}btdUS z>~zk#t-t!-xjH;40Y+wJ&TAzY=TKjc>}d42pa0z4e7V@)w|MblHXnr6LUdQIT*=l( z?5_YN)-?rp$cbsN`5f=|lxYaTok!=YMd!<XetQ6dCp1s!iJltr!v)cInA}1}@R!9s zB8LRLXmR|}N9u_vH-5P0+x__6H=I}|CD9KcxuT~-=(Cg(4}?i1TVm74DlE*w%A=8< zX_O~trdj)NTkTvtmA4WUF+xQ0c#a50Mx_~58^<2rTc4PjIC7*mGh^9K!7%fNl?%i9 z6B99%U4hSTXGGgVfFN>U7_^t=fmGt*i`p>dNmDRfWv#FQYK|E*X~V&T8Lqr;4ptJm zs1UWm1Vq+tv@O3JGiC>knN{K3ax?w*0dGqyNZfm5U)6Ta;nAg~;gLkVXc>#q0K%_B zRVCg&OTN-O;+28xJg5)K%Qc#Ca1)*+vMHxT1Jn9v{N_O}PdZ7T-;sXteN8%AYApv@ zDHR0@T#l^BilvoATqC}7ea<-W-8=t&*WMovEN`S19UWX2OC$?z+YK95%Z}N#czw?C z8ma10VrwL(4>$)O_P4It_@935qt{*eCZc1pq`+>GfRyXBu=UOM=S2L}U*^L~2?W^( zz@HVN;3fVjP)H^%Vp>UTHJ7#LdOBM$a<X^=tsPAC$LuI)rdca-PXtLnHoyPqop=3k zvO4*aS6!_t!r^&Ov|I3lv;y|hhX)mvS!&7Px)qDJ9U4D0xIFDS4KvO*JnSOuCNjjv zYxNCgvVBIn?X;a4%Z-=vgPs1=xP_x6I;3-^uV0MEC!O2iM5J4q1ntxUE6%<TJ@gPR zMsIr4o7S#fyK2=c2rw2{S~Bi6UTd4Rh8bF`WoS<HDl!-rh6t_oX>avjKY#M#>jBUK z(@c_RkoBYxHwktc6DLHHCnP0r3=BEB>>S<*(=$=MwH&AWm{DmPPOVXmMezXfG}bN< z*urt9j*RcywSVIHp>}(6(O3!Ra^P@gYWmpGqjQtfZlh(k{G=b{0;@ls?k8ZN8~TlQ zRI_mjGFxuOcJiTz1r^SOY+4k#?KOo=5VHfw9du6d49Tnn=b1y=#axE)R=80@=kXTF z8Xhre*)TC@q)G!LsnVd^KX=Qa#y#b*MZCYXX9RY}Zw?yOWk%xy!?`GLt{MKa`yG4N zZL<^2V+W?9R&2@0k`*i04v#F)C5Ok4&y9~yV(GbZ+3HQ3wyjydwm&!Q7+z2}35}c2 z_4j86=sN0#E<1@ro-S0fFGL#Imz5so&UwoTfum=hI)Dinb|N{TD)EHpi5qQ$fECUC zwY$Fdy+3b+2R2;ZNBH4bDUS8K11)W%nMu`VZM$mKCS&vC{_N4{;KTK0gX=%|o*S;a z>L)JVx&zY}l)LqYU&zC6hU{Pz%FdE}Gr}-gDytSjWQj(A4rb~Zs!VyYLt@l4Qq6~h z5MH9@-Fxdj2M-)uy>i`!n=dLX&JJcvX;z>y$7+U;-TAN|wGQuoh@FKNZ(g-|-A2k` ziuOv88j(6b`r=$1`6eDy=*Q?4KF6+l)Ex+i7Uy4j$txzle+OGQMSeB#*n7bQ$l;1{ zCa@xRc+8mDGyON8`Q-0>@MCH>B&ye~ey7^>g0{Ro7d3yL%A{+ahKWFi5pG=>iA+vT zrZQ=0YFxq&oRY9$peV2;HaEQo*m<J0W5u_pb0&|{Nc6ItKY5Y&fCeAIbFvyNGmUw{ z3<=sOYbAs$fgEv`G)s+U?l*t^i(mZAy<or<8=CL`^_N}zvShlyeB|ifgZuaHy!)Ya z%v>^%xnTL&^3p)8<=4h*&UBs4%?IO|98Q9c@0FYWeBEq1X(DLVT?nmd2bLeQ&L+!l zMCJ?3$nnu-i(U?OHL@zoYNQ3zsN({aGJ>oT=8X^$C5v3lHZn$h%m@lbyjU;?OWt5E zDkc)?$V>&1<*;>8-SG$7xkU#O<DcC*cDFHHGbnv3X-qCLf=dnS>Y}qLKQj<a$DKCv z6t6k)7(Sm-%5S<(vjyb0gQ!|>)N5@v_$_1xa@i8AiN2fIv-?ne-c4G$?OQJ0y6Hl8 zPs(QtTh?E;B(>RYgiN;uhF2#i)QcQep7-i^*+KcR#@ehj%8G^)81?C3|99{H(vi8l zmTWK+{qwEpX#Ysgc9T#9#?EOtM$0_D*R#vU%wc2pXrexy+Ht{k@A=tZx%`rsv41=u zF2xf`Lck69k6hnP#*^46s8AkV<2&7G`MS)JXROcYqGwbnN`8l@RFZt#n11lsx4wDv z@k7V6iQKZ{@X|za{@84_VkZepSxUKn-J72>)6oT2Uv$yiUS|vn=yoWVkg~877gNyn zxdSk80_cE1lCs^3Wj5&r%gE6S+?{J5_=7)vw>7k9(e^o+iP;<*-nN@=(1>c2wlkgC zeQUFPApWJlymix>OB0=NdD5HGB}{jttr!|sGfyW*lIcZ~p0w)Pt%xHul>`}va3b>3 zc(y{KOJz9=`<GZ8DogJyB*_qCBwZ*m_j^N5hv+gnK}ueLUry~RKA^C<y4wK`>2bA! zB7?{Xs%yE|DV+iBrE>>Ny-z&t$-?>oFCCs(bH=9}DQRH`J+a_kOZ6j_`Sg2SpHhha zdan)(CYa87+WVc7g=;_M`wPnKz9Cvtg+w|TWp<h9zwiTMrs3`&n${o=o9|Rx$HosI zeDI<B_Z@kBV)od&wU=7<mYcr+O~<PlMtk4x<Nxh<K6B;exwqbM*=X9_(rR9@eWP2g zxb<1%vBz4CwpVeZrqSnE$#NK0jdByEtti|0i-U(y94bK;!J1mrRM<$4D2;u*jT3~# zpc;k`P0SmKe#7cB@`IVM7`Fy<Rw)~0V}8oCvZ=6uhS_T-{FY_aQr2AFv=eqRaH9~v zI*C~Bv;uEFmb5FAW$9$Q-<Zi8@hwL2<)hKXLo+M9<JoE@(Q;90hAzy#l@|3NvE{8k zKkZ@jZ`y`C$SPov#gNN)+Merx2;)I=+u|Z&v7J`rxd-kzvUmL06qJAa(aRf$<4z@Z z;r2_ee)%<h1jaS8gsDfFK;%xfjh!g=I~cP&Dl+<K9NC5U7mVh~QSOy+@>cguzuUb! z{kK>0=?}Wsz54WWKG~h_8)x}TF%0xVNbR(2VOu)4=r#o(6s^B5%dk-2re~D@{Gb2d zhIu$WTwS!uH45cei4_s{Z*E3@p<M|oGk&w|hjoi>1e;UF!CmYEo%q0efBQXe`{i`1 z53r(0+ri*8iQPUmvfVb;49U1`zNu;_6=W`m4WLePq6V&0x9<J3{^h;yDyW+8abslT zvekQ5R;CC7lB!KrW`cIq3J3G0R^ZN$&#=CeNM;iGSfMl^TV|@47WP{QY|gp@&pM+F z0#g7Cq1vvxNG#GznZ-e~aJ*a}SRG3j#Nxq>VW?}xik1fhG~Zmku~a@j|9}4PAAb6i zUtWmw=~dOQo#pFi+oR9ALC@ujPfCCxpnOLkIe`Z2&(d1G6_UjM7D0nBSYj`|FeRQK zAM2;R(w>U?GQVV5475&y%@n&EHD=&lenCTuwdAhuc%jx>=F%VOPPy(?XYTbbpXtdH zhgS{$DaG{ekXdsNy*oOetO-#un#Rw9qZF<T>*aB$K^;)*X(nU^MJ2go3WY<2l&wi+ zZAGGr1#&Lpr>J@OkaS2GI-+$G-c$OpQvyHalMIy9EtYd#E14nS3}q7P*y0$&X3xY| zNitb*-jzTr>Sex36=)~>jLwH9E;w`JhmSnGd)HK>oEu8zM{$B|J#^QP4j(*}?Kc*$ z$gaJxuQqe%-~aU&Cyr2EtOP<M)pn+hiCdbp&f_a%ss6e7)O;gu`*;e<;G?Z$KOv$j z`(d8=7!J%H+olRZwGm_ix4hAeOBgM9U>^<`T$49aMZ@be>Wd7w&&cFsslI$7k8?&c zOvYS7H^)sjIK&bLA=!_JnalEYlZF^BM){O!vgkX<X69xzU`McxwYXVswMu5uo$%}T z9gmfbsjN}nU^v$m?X|h&Xug@LS88p?al=%M{nW5o4%t-=ncMJN80`o#mLP=0@rQFY z2|ts>juEARVjpD$9SAypoA|z@-6*#vjScOI){ml6f)H9?f9R%fKk~<yTzHk~XImBH zr(XB=(f*|=qtB#jVJwMrCu7Pu@I8Xfp}u1dGB$c1fb2A`Q&W~u?FsfSgF|46oqq7e z47@k?kx$?Hme|WGs1V5L0ip(*1^0V^BmkqqMx8wIa9W0imz*!W6dR>(QfIxob!(|B zAeG@cSU~YwTF=%I-(-5hkim)plz@tw4k-2I9isj#Z7^9}cI7b|ckTVw<KwsPseXIq zmQ-euof$G>>Co|fGfcYeWKi`g$6EE-L}NP9noS+sHCGuoUUtc=-|(8ZU30}N3z-~I z4v3aTO|a2o>MB)pm`UciL(Tc37}@pG$;R|<J+l+$J4pz+D0I3>&H|$^cF|QkjvqN% z-aC_WfVCvM+xxZ`gAriag025jaX03@{*nvzxJf|klT}k^QuxVR-O``CUo`QmeDw1% z3;aU(cahz|;Y8+0r7~Av{8RtyFK=4Aqc2fv<9(D!vnY>`gHz}?8fC*Q)=DdkyB_}G zeY+pHWb<W;n<2Ihd{rFRJu49d4J}l-K6mwg{z`gM0{r|{;j}M_90uutuOxx`)wB~p zVeCLK+*kDe6v*b{R50R(o)8>)BBiL*d#m?!Va_w2cV9jE+be`yy5xm-biU3VRV(?H zmfD3Rs@8Rnf_=ak)RCM*8|Arvw^IVw9ez*lqc#d8Y7G7`pkD|ThQhomlBxQX>w%7K z_Fait&?VVXP5fjjSCez0uj-Fdb%O1bMFB;6nIVMHX;*UDOgs}hMwPmuX>*NWymEB9 zJT)^nX(g=D#lyA6{GIpQx%<&a+V0$?SFK8=2m$YwEAy>bz_Mv0@T{n{`I`LN%a&vc zQMNDZdd8jKJ~1(2ODkh-X{d|;fzhrQhi)F<F`6F<qjcFPP8}rHkF%wlvRA=7(2Azu zoDn)@uTV2c69U7uG5^dO$&tPQD%+pR_GhDf0`(f@))Q@eG^!`CpNX6(utTTiHTgO~ zgLO3xMUlgL5^)k(u%piz6~#qM2qBEB>q#ORpnf#*JFMkW5bSBM**+1*rsJtW-x<s_ zHVy19HX1QIiLGhHW7QUePADrSrVA-Aa)Zdmij3F@Vpb;0J8Y>$o27^0R)t}W#Z+W; zKaq(;gI(5W5;4|&Q?Xbc1(6%ZmLc3HeLGj1Z%;>eROX$T<E`>ncbQ)H#G&%m4HsW| z+0}kKN++_LH*U$9MF>C)OLC}-gE}guSYn|w!k>xYOcV%=eFelk-%rKF=|(5^xJ>{Y z?DZsUE*ZK>UQ@s%tYjC$yARLs3s`Ev<=9K7!*K6`I_W*tC#ODq>MJO$`WgoTd8w#i zVTIS31u?^MJsOFfdcumizN45f{D`7TIQ{Vcd-jgscVzwnqcFYk%H-fObPA%5#;+Tl z9eTa#V-0tz-JXrj9`_~=xzk4)1G!bd^7HS0%NyU7j-~r^Lwv{g+KIGm62M2h)t6f6 z^X{FeZp5>Fs{2_6i0w@z2xWdz;iAhf{L#@{(qYnRx<pBWe}yfOWj-_3HvRr3V<8Sm zj4-e8r^l#MOEt>Rwk~J;UgwJfOWKWJ;c%3rhTSk;`SLe?;|HIfn|N$sRWWcIiFC-O zrR;Fh4qbS6MEdNYQJe5~?R(&&%@@N^DUSiX3SEL%N*GyDGCVJ>INR1f<9shb0<78~ zRxu~hf&y@=%3v~(jv>^A1UF1V{U<W9jD<!8imC~U6~xCo3SQ+!5+%Vsim!?Qvm6(m z>pLfp>Xn5DU5Gv^$Py%_FUiIUtTD>bQ+kz&$^*d>Pe|%b>M1l>m(znL<+}>a(C{mU z3<}nuzVLu#7RMA?fCR(mbhK6SvJwzO7(~g7_y~H@bYIU{`G77BYJ|IvAP@;DEByvE zN3~YH(wK;4=lhKKzN3%c{DYegAK$lV$-vSTLv6qE;3Icd8ntZRShId`bgVzO*1mKt zzC(O&S2mMD(p(y0Vv!-RoRP%3I9`awGwEeuH%zXarq!-a1~c?a)_1L95n5AAIV}bd zA+(k756;^oMe*8c=8Rg#s3<e2cqR&SmNA?S(&7m$!S{%@Ol0;ne7#X;hd3*;O~=N& z$P0WI&mde0lm21ES_=Y<aTT(sZ^n5MWYlciVL)VZHf+O<h%>Rr>KcbA0D|79tqg`V zZIkYp&H7M!X!g<haCS1^XC~@KzBXl49J77g4g&mpJt~~erIPr5qLfTH=)L3VbSxq6 zyJ8Cg7Zmfe7|9a0BlK~8Vwh5?L_CF$H1=R^7^w^jH(90eLaz<?13widadHY{eeptn zU^iz<gNa3(a|!c^+cf(M)w#s%=YRC|J-eq@EnB?p_>S^)+plG>f7u(>uic)s`U}aC zq*;KmU}JL%W$8I1OUc-@*=gMKGnU<MQ4h8dpk{2Y2VWA$8V10CXX>iBm_rI6JD@`6 zDa_5Wn_yiuFsm#axau7B{cc9}t3dmdJG~14n5X=4q5xmL-ubY~)h$mwRUb;Qd1Wsz zS#@sKM^V)X^>H%USiM!tW=pn96jWjjH_*^Lbol#U{obEVwI1Aj+3=QY3hi(%+n)yV zg$oI@Zo{jVo3&bF?zj=orS?A9@S8?^KKZg8*MIo^|8@P+ZA$+y%?v{?h3_qZi^c=& zf#<end3tR+2Pd6QSlBOo1+3ynR@S^=$JT@Q?VEb!IJ;*OtP3lQ7+Y|QsVjRJ`)k*& zPAa2%>EKR5y2DR)-8rc8f+95=r%)nQ(9j?lk+_o?BNgj^@4J5a(>ML+;|J&0jr800 z9PUW?`7<<W&{!!uy2J|RlMg+5oByVFq~is(oCh{Qh9+cB0FTva(}EAaxK2+Y6)%LU zivUd0{mQWmc8W+qgmlv5C{nVDrX<u?o%fDHeHm``HkoyPU6z0Wbhn#d=jnV$=U8w& zjc#fX(nkvDm8{E`ufv7&x~{lBBDRzCQJtQ0pj}!^qi~RxhAD&sMa`rdOnID3odq*` zE+J5aizE}KLWz_t$4mP$-IN#=NIWowvXd!#P8R7gCgNAVi4IcY;(#}h*n9&4&!|O} zz5Dk({K!Ll_w8X9=b6fpvDLA4n-&%F=|-lKUD>b(Dqg7^Gh5fad3ikP1y&nr*GiOO zRMBLH2z=t|>t)!x#7MHuuS6D-O$JT7R%4D-+YJbEDlGM9`U}~HKa2i2-K@<ALO7+7 z)kQ{q^P*BJ@)DjMbLu(2nUDGTq@5I_(pJoz@Y_&a&TSW$bJw-)#$3CCYbKvTpR7Jc z=t}nerte@*vh8dFJDM<X{GjFG#t=B3=v~3usialNv9LSPpBK~pbOy0A?$K#H#*x$Z z{B{^~T&wOv(Cs*mC$W|ZUlN2BD5*8sYR}=m49|dJ7g9BhPaIvhlgbL|E%bvELdaP> z70+a4d(K3H-Na2R>8CTXOg5KHL-pVoTt>mLTA3WQ7ZM&=F}$UT#bIW$saV<!GJ%a& z+HmuwWGok90GW&tez;<$<6|X+*>=&fhA$ZOJ@;7awi*l1iT*Es_u<Dsel(w2^zL{3 z>Q7w#M$uFYS8Ar&FhF|9NTn0XJ}8~eWB?`wUF>Prfo);(;2=)U2pJb)TUF9CMM1LU z7uZ(Jt32ddrOxc@UUu$weq^FOUDDq=V^003QyD5L7`Jz&%a!jU=);S)sT+WhV2vMp zfFugd#(~=HH{JHRrhi~;o4a+zsvtgT<jTcF)beV9myDbOd|-Lfugr$Ed80OIOzv&4 zli=c!(ck?~zjytWZ@|kaCP7u$Og<6%s5h9b^c9$g6*!2nuE7~={&bE0H#}z)NEWOc zXl2m2@X8(EI&d6sKZ3lbSP@ZAv7L>jW2@Gzl=z!;k&GI2?fFemU(vphPWF^K<Gv`| zV2xk0?W#}wt(6$e%pPkEt;#1eOk`eRx!&@dQL^Zz`uuwy`tCgs{^;`U*C*METV7H{ zid3SSrmkM3hZhzBrf(H?5LL5`lS!P@&d6~gt^;x@Hg#$YbmbYXULHLP`VL18iu%|a zAf5TNS9(vMaH4_z<n2>m@9=lM$HJY<=M}K)qkguq7&7QYX7b3|MrUTI(8nT`i$4zy z);WPz;kHpT24OPM=YV#>^t@@|Ckr_szPZDjsm|0x^DGu~aZxX}u{Swd**`rufi5)H zmz=9i-1ESX?tkb`+pBEYx@PI}!E$wS|KuJw>tFDy;a9F2bBwu6VV*7?OGBS>R3wpT zxE=v=ZI(21>1@I(Af0;<IOdN8dt{4AOpjShj66IcWiM68mgO|Vn$fO%Ep*Ch&mBmo z){hy7X3+#gk`1>gBy%1u)2mk<x?sf&io@0%{s|3}eL@2p@>0PV(sdoP=_OcFZ6d(7 zeZ;s@|8OQb#%|+o%ZofBO&h6rs=se&@nRyuEGzX7azsS3&;+0zhVMZO>|-uS-H}eS zg<QU`ufLS<C%zl1Te@Fq?1ISALNqwcO|@9p4d&C~eB{<cmeQiZCWZL(@d%5muwBPT z0!6k*s4Fz(34BH+n)9B$j~+UFV9&lim8o(-Xv18Fh%>g|vi&B1elQP-%@<O+Vk(tp z6I3&mlUQM~WI(tPD0D8L3X_%-v;DjuD*aAiTd6dv0%FL?)=bHC8fSz`V-|tCZ@8~s zue)_;`N~{<a=erqOfQY5j!*pX@lV`$=<gF@|Kj0wuej=U%}TgzbRC<|7)Cl7?}KQd zE670OgBG2STNJ^_l1YfPqN^G}J8%d*b|#31zz$Sv*jC5Rp#z~E=w@2VB<;a>2h5-R z2MQ)Lh}Svtr$4H{##_3ePT{H)$SYc%?u<sw0R)JFEvx!LoZd8GpPDII(r(|e>tF7B z>|5rdBh~btB`XJ0dB-Z^Y>M<BueMlWD6lEW+==qsiJ)E0`HlSe;o#Ul$86+&>J_hl z&pUs4?aD1_qmRkuIk@>!Ae0xY2)@O#z6*qzSS6hM)EyA@r3Dw@Nx)oCN6c7!;mQq< zZhrip-DzCb#F$AEP+u(NN5+PgAq^OYNkHF8QpM;~b$w0`8oN=?1(j#KaKT4-5Z@Uq zF;d*TZ`aMGvHozB?N6}JWz)h;<VLYfE7KPaE{RVbo&NOSeRB2E4NHes(FiaNnn3ZY zKfTy<+LCip_|v-~os-W#NueU)iGdFi0Ca`PjPXc!&5BoqpHgt6`(36kq*{+K<mgO* z#oZ^SQ$XQ~k59dG#u84=B3Hd^XDS@}Nz&*<&bryTEtV0dC6!t2ZYL&Jy@GWvvcug& znt?uyhZGEgA{uSCPHzx+sqNHv?%a9zJ$GV1HMU}4>H6Z`J8ykp=lx8-^_!Nj-LM=} z&02e=e=r?dPH45jTG?VMkF*qrjy7erHEz1f12t}<Zo`5lja*Cb5-iuldPxE)qRWL( zMdd5#$g?55#B4GNDg@0GD$MNnQ=T8$(2sT)m1D!LwI^<h?f&8T(dG=k2<@CWMP%2< zc3igE^y{^`i7Zj*a5aje*||DlnEO-4)|G44t=KR$x|~H^*CqC3dil~7TQ+W9xg4L~ zzE%sK1C=y<1&+g5pa3W6rXp-<K+<{;6s&X*4bRj~7R;%>fITdWv`Qg!R)Xaz|LJal zDY5^vVFipZX~ghdLVX}Sj@b9~lp^RPC`%OCYLud;hfP*Hi3FS=q=z><H#<|Fx$Vw7 zu&sq&3l5Kk<@w122Om9leE-y3V{q8W_hAs_Qz*W`#lBpS^20tiH<ZQ})D0*qLemgK ziH=@6@*vX0-)!49`gIrx>f5Y0GBH+@v$YBwOq5Fxw&sJ`Dc0f(UMu<N&coMS`I7_r z<%<T_U3=B*3Fy_IETIoinCM4@mt_e$mB@;&l6WWdgX$m+W;BU;#gWv5P`Z+H)uH;H zK57V+b0OPI*wa8(mw3h_<;x(@<2q5cu0&_l)ZK+&0Wl~7&nL(zb;ia@FoqM^frK!# z1Ec+;oi{zU|DH!4ziajOd})Ji=Bi_hF*C4jrwQ(6^}ub~lSf^zX#~v_KE5+Y%!xyG zZQ3XmR=n@sA9~I8Zyd-kLSsS?c(9#4I;(5TT`_-?4g`>t6xOZ&Ir^osx=VH62!t~b zayLONIPpR-yuHoOeDZISjaadfL95bCxV3n5%@ymf|GC#1Y{Lz&6-Q;$DFv=Vjg+dc zF7q7KT;N4br%2gvs&C2KHGee1ve>aPh`V<@@`Dfm?v0oKWNG<UBRSki6!9v|*e%a) zIE~rBoy$LdckRG^(I<cJOV?fY1|rl2j;J?iO~g_FqjPSXaIU&Wm-|8^z%n=_j9WPh zH{An1PUvWT)IBa!S6?&jl}yZ)PES1PK6z%NB_C4YBCl(tphzB9x-xQKrQR3izHS70 zG+tL3gij!KAE^sDaJwVWbHU51A?jN^AvcqqqeOV;QaBVWO1zo*6AwOeZ>2u5a_vZ% zXg;|6&bxQsTyM_}EXr@#w8~2OM@}4qHY`~-gdVO?OrUs;v#}QhH1vRONGyaW#$qHw zGIme0lFXv0DxOWN5`?(GNI0}xPP<L8#W?g&jK7Q+THrQ|sj#hPoH#A*h8y?UF54m! zA8t0Xc!Tn{<zf5MZpB*;Y(mU*62U~YHGjp}{MP0~xa-8u1M`PkxnRZiwaeBmYuh!q zIzLp*FI~K3-G&R+Y~ETZmfEc#a?Md<XAKWpNNkF8SL6U9Dno(*nvh*!1YgtHP*eJl z1WJThGr6IN<YQ$Pt0(C=atf7HdI_y@6*8&{Q^ZpWRpTRHA(tiQ*p$OyK(S>jS5b?R zA3MzA002M$Nkl<Z1N&MfpDrX2yesc_ObzHcDNL5vDG9z%P>)jh%Xs45G&6f*t~`xK z8p=8~ed3{q@7ufo@oH_pS}jjkCSy3cB;6%ThY}gjN;!Qcc#Kve>!))x%*z$6bT-|z z+cY+tBZ!v?w}X>C<B0h<3Ts9f4wkiM`ZZ?cVnN@-4;;*=mn5vx(F3!uz3#><HoeBM zGh?HRM+T6LEgC6%vC?6%yQ&8|Z4sbTNfyMrr>YC2t)0~Eg_AjWOLvscq4RdLbzf6? z^o8`vf=iWCf`qFXeKP-oGhHv<Q)M%%tgkpx7)!M8+VhQy^T?eKu{qW3z^J)&)nJ5i z@PJ7GQr?%oA+|;kpPrm|t5JE<ap#lMhuy=E`d-ai)W6~7FL}*7-}dvXmabIvi7-Tw z;_Z}KK0pLyurx_$z^dr3g6!jfpw(~-D)=0q>b})Snk=6dSVU0qLqB6>1XI#J-?;lL zx9`5?q5Nzz?wNKvXr=9I-ujBQuiAtPI*PH!i9kPfW7aS!o<{=AN9i>gSv7R*`~Yo0 zlE0`?s9&p;i=_ej75@HXpZ(~~JOAYB8&;;5S8_v9Jeh7a8lGb_OnxOk@wjo|9`lM# zKmGo9{Fk+hHw!A|kBJZWd!7J4w*aRhO#zDPWzO_1j=ia`0I@TmS|(mtiC+HRP5o}K z1YSSwPA}&ZPlUx5wA^{J5H;uz>C$+tFD0LF53084k>#{oa|MCwhB|P`ANX43@7!me zaF;oTw$^Bcts2Tk_;89Rnwa1E%D?>Go_!C_Rwm+UKb;Lnm-Q`P(PyPF;&-exf!vH_ zmh~_b;wsv3yjaqRhVotE)nl^nR}9s(Xzt)X`6qM&yaGwXIU7FNvGKErS}i+)%M8*) z6Q@`lSjC<g85b8>a(T9Aw_Su_D@u6{_8UmF+kuVZ7?BG5#k$dMASxyuEPGO^qE$2| z&25E?w<cd!NEWNv>CM+}8CtV+(W<e5MT34|vzw`K7IZAcQo;lZN)y>y+1Rn4c!*U= zw+D46F&<PHCIG6z-@>F8h0&m>*6Rma9%ckPSv89zy#kr!Pt5Qnf!kzii-~j>K*Yd2 z@*(SD@`j)#q6GL%Jr?mxy{9jQt}BYJh=_V1*}%~(7w9iAs3;9sM&wsE;gLGxvE(u$ z4EH0CK62N6x8HX6_aE7_v)GqRV2B=6`iA1^yx%vRPUb-NPBLp|^5_CsfRK&FV(BDa zfRvWTtr@Fozk!Jm>&i~s&7@L|iWB*XM6B4V$6EEsb1Zj0<4zS1?4De@c-2q8@y!=* zzbv2W&tpmssWw<qq)Ajs|516>Ji+)qp<g#kwUAcpwD5!{CKdqF<J@Kx)KPl1dq>|F zAlIEIzg(P>6!q0F==<HQ`U+ryxx~JocU{A&yVa&Yy=&jiU;5@JM^@UKE-9sowPdb| zY6tl+u&~j`zsU1!3!62!nK*u6&T@*=M_Tn6>*$_V+{?Z1T_1VR+dfcC4>1t1o!HOG zHooYBXbBo_AP~zAMQFw9LN?A53jk(^=tE96<dil%XBWD2di|w(OCtw9!Gw`LIw8PJ zmX`79-}{UB(IDx?yj<jD{5QY<#=ae*g2veme`UqUitO7Vz(Bd~*i*arIjec6AU@OM z;RMl{j0(*`uz)p%XJjm6$rF`FfAfF5asB1-{JL^}%**$sTkRU-FgN9SRiiPLo!y(i z|9jKF^?{Gw`1)VM)RQU15|CO%>bBy!uJ`j(-ZPefMcO!10*{~R_A|dHA@qY3hOdBq zXv;E(V754Fe^85t7(rx=s^U~-EEm>DpHr7kJ;_MwN}^Pf;nztcfljRj8EZn-d8&W( zQ(l7mMdOOq1*%R|P+`X+o?LtopysIaMmQ8g;7DAn&gv*U31%WFTrw&=%^5X7T&rOV ztR^zvK1UvT?7{JgL%z{oxq7s3AaiWu(1W|~*}HEyo7`^Nw4peXuUn0Jdp=*t43G3B zk}&?ha`Ln}S}~%gM2RFMR(+rEh=q@dyNu|I#XJm&hb2IyTXx9CEd`4%vD<<N;9U0A zup`%|`k8jiZW9TJz6z~&-FMre-9&ZA$}8$0@&x#7umBf@@%bskwNYxOhz-7W<?_*i z66l~+Yv=n$mMmR)`4yL~9$InY{v&t%!(D~B0hEBNu3diZJAT3_<qXU12KA9OWu*fZ z`2vE4z%Tm|Xx2&%pzgI+E6U`gZB3iN_cE(RW>>wbJ6~Z#tOtbHN*9nrCr)%}+!jg? zU4*ZKg7H8$U&1v=Ld1)<EXM94@l;9;p_BsJQaT9ysRigxSrh3Nf6A|r?<Y-sk1|!g z_`<@R`h!l(nezPl#Kgos_ua#aGCR&qmB;US;I?=+7+YB~<LyK?=o=&ulgG+&x<7%@ zRv7cLIXsb^zW%K3)R{Zz<!KTe6-&JBmP;_%cq~z=G}5es&RLO@nw}_QL+UiFLT2Rh zi>}M3M_+d7EBmc60z~Cw1P)1I9!ykBnK!y4mD&}fGZOaSqHO^4vjz{<mcH$_7tNI= z7JoEG8Kn!hN8zIHEI0y;^aH~bi)-dnb+mMi?gq-k3P%w?;ZhKDJ%>gy+Kfdz!fl%} zojLdD1G|54$Ae!zI`hD`OP7qUNJq&=Zh$~A4J?AGOT%rTxwq>^z2ez*Yx<aN*V1U4 zgI0d;&bfSY=;fEa`e)zz^OtP895s*Fil<~Z1(j4)dd$6a0<cCBx3yk#x$d!H^6*?F z{aHN>lrP*HY761cak9$B)6lb^9k3#bF8a`q_TT>5?^$-#vh2dLfg6A8-9`ys!Hs8` zY^bVXWEny@W|kh(9q6NJ(z>%vz?EX{MGGZBfTO`vL{&Paujo1KCgEw-sv-?Qw<X<) zh!bxH^LIS-rN8*{?`*s-Il7+B!s^*RkZn+_GFX|3{RGAu+<jZcnH>IK|MfF3-SH{` zDJenz(7S<XsfkW!+maVXzAiO-Vbn%y5n-*0oME)vjg+i&i2#ZemPq79wWq`*ZG@qR zfJq4*)6`ZdP7j{s0a+L!bs|8<rJCPbiUm;u+`NN~gE#^=OCA|i{`V5MM1{yBK?H)1 z<s20bn_MGFfe|QHeTG+szJijtB#bPRM7#kcKkRZ)_bZb#<CSVTl}VIJeU96H{PD;4 z?BBI}&;9wn<kDqhi^c}L$ex@!f}K=opsdY}EbdEX%?&R#)?K+4Gu*yX%4eTt(+LoY zvgufyh1xcu#?n>-_LtgWet`xU9V~$vkPxuh@v%0RYKo@|coRX^wb_4@XG9^!MA{OG z7U|YTW^!0FM$+?bu~LTm(qiAWXJ?{zooE)u$ly>R+iyB-!Pdy<`gUx;<iZPg3=J%^ z!UA|6s|gylbab$kLYA_`!NtNS70;p2D7(A&KIYFL$6EaZ{p&XqM=Gbf8qORdffW+E zZSdH_Bv?nZxC}R|eyFms>rEQjtXPsXTV6h&ps)3C)9`Np%jkh(6pm7(MUlP1qzm-9 z=9W}Y5j0pt&cI!#knfYH*p&rdDw9&wxl<nu;vfWEV0SLHlo36d)Rq4J$(yI1@$_UR zRDO{{RGueP(xChL2r1IPcG<?Ym$Ra7B@@+pb@#r9Sz+J3_kmmQ_;z)A%4!?6=B(|t z*z~=$JQ>E_VxO7sOA$Jet<PQj;9@SA8AERj<1O)YVgaFD7>R{mHI;|YXs4E9Rh?<o zjLO{f{l~vLeY|!1Bi}?cjJ)*gf8woMH(t`Ld831i$3~WAjUwy*g#KXCz?$ISOw3-@ zqKJ|^Emb$Li35(3S%yqz1aub+sxtru(6R+>){{y461l9iyh5iepk}rm=uIgA+aPeT zU`HL}7){5h?VH*?GdF(oZQq!x>|L?0kQkf0`sIuAB|lYYqJ>BFCx~br>$jk7H-ezn zbnCI%Nn)(Ur;ml@3A;WM^O~_={ki|X{enxkTyRleuEdfGi!$jH=E9_Iqd4vGQkn*8 zFykDe(aEzQt9tcZ9D1Zz>LVY3xrA{6$Z<GV*C9YGj6lj*vTo_v`XvV*-Wz4i;T6LY z^9JIUO`?cF!@)#h1aXo8F9DLBg=|%(lyi0oqN}N$Cd2yt>|Pa4x6{2$2)>J#Itv3> zW5nZtebyXtE7{3?brzS_Z(kHox0~KPO(Xz7elQWXTVrd|`{ri<;p=~W#g1#M^{}s~ z7J~pA#Zv1!D3ON_dWNk!y9S(#T<2T@);)5TRTpy>#Sug2;PG)~oNbM>OLNA|hekFq zfF#Hv@J0uNXN7wJ@D@%3I-bEr$dk|qiX$SAkYK=89hD@=u*%%x#qJRd50(%sLGI8g zTmz)y*n-MX#<<f0^sEq6WK4utfnwPcmOZdrHlmBu_9OS<#~+%j%uGxkD_5tX86%^G z(Io@L{=}ZW_aC1;FgZ1m&KfILmKH4;#`dMrZW4qjj=B-2m@Jk=Qfz{d{CL@$aJ7L8 zMoWo{CaPMH7BqD*GiYPm1V)Pj)&fCK7=IFvwrx8B1QptfIEzt6fGrfOUaS`<+YP%} zvsuSAgLve}eAo1mV%y?+YBxit&DvOGw~R*Ja9hY1V%jj!U)r|q!j0=Ur?46|l7(E~ z>Q(F4t==$H92GZOFUS*j3TGO-g=sNXSs10zfkeoVeiB(xF}ZZ5Z&V&0|Na-hS3W#v zwvE-q(*59Tj1e_Rj2zxJn3!s(Zq>sKlM**&NVy>zU?2Bc8EB+<)U0;9jW12DT1}_K z5ejQ(JuqD`Q!}qe@AR|YQGEiaA`?}Egxf7Pj%g2;g!=l9A4ldRN&K%UsbxDZAv}s^ zQwdc7w|Kjg7Q&vob;=F(9WpPhkS^ntYzh+9+mexR9E>$S#aNUP>|gjl+qd!XhNWwG zH8VkQ>AAb^y?y_oeO}o9+PDAF4r|G@R~k+x^Y+M+OuhtuwrNVClyzAO#NR277R1XI zvX0wK=i&|)OCjp}Bun*Hn24KsuN@2RIGfJb%Wg3}FgH~@addjy<{g(`bnSr$=7tK( zVYV*3;3B-+SgymwJ!R&=o0Nd7Ikp3`r~!29R(6OM?NF3L8YGiMvsf}bx&yjh$y+k$ zL<Mu2O7DO%f}c>KzM3|h3lS_N<{1s(>Hgiff9JL@yM@C?=k8y;G@l<ZMiys=#tQXz zZESd~=G6)R)b<=!PnykEy<sE7H_J_LHk=<frj8m7wtGIrz90D;f9icV{`AjYux<mK zt2nzz$1}eHB%ljR`>ssVsUi3X_FhI@k2<aF5@136q68L1a_*8aFS=``hdUieU1Svl z<{G1J9FQbL1y4O=>eeIQ{PMq4+}a!8e#4rpHcGY9fI4)J2&lO8iI1?FSeE1XMC|Fo z^w~E6k(cSFx7$Gu?gdFaV+p$EdcvtLgyWSSM)fRK94N*``6MAconY>(-~ZI7{`sRX zef^5$!0h6+u#gT*HXe2+?NsH2Gk3^5{-{|woc*7_{kIpczlxVp>47mdE1<tF=$%gL zV*WE$=>>K3NeOTlqdl*+g#csyBK{*1(y#H=@Bh`E_kTM-65q6S3pP3?<K&z5TC-Z7 zZ#J<}McJB^00WuSK;OX7(9qz(U|zUBAWSnwA_c4I!6X54xrBjbjY?EY%7KTeCFC68 zMg<O17+<~5FbehuzZh28u9at}XUfy_l^NS^<_qcm!F+!yi$PMgHaj^*Ft`Ipjvt+! zoo=+M>48itpF~BR%vkA^kttaDLOh+tJr`F(<Pxwvk$NHwaKr!_<}F5iLOe$GKnPch z4jF8Q&`j6kql%hGiQ3>Op-%0Z1MH%S6GsSB)^@-e4Ln7gs0xVd6SLh2x{NxR1=+|k z+1fge6%j^|+;4czhD!h%WJ<gqy*3{(`U}Oyqf7gW0|e)Ao6*)yFWI!=!V9-<Te5gr z!bnJ9I5$Y*Tnx6NtC&xEN>MpZq*DbKAjVK-lkm-uHD<i5J3%+3{QJM~!(F#LQb-mM zzi;@(w`Q&=1W;U>E~6xY0$Esq8P{uUl&X4OpiUt`CKS|&6<^udkPXYYfAe?0f7hLN z|Hg0p20j<cC0fy7(SfKzmRD6$?{_bRnW7&Rf$!WS+-$90`Lj>_pBrwt;nGVlg?G`Y z#CF&yP%#h`sS@DQs}(0eQMYW`pr7=fcV6L#XC#Gs)Y(}c_^5_T@+-towJDv*!`ND( z3Q`D^ZbO?#ErPuhkADA_Z|!{W4lk-4IQB3uPlb}Pcx7KY4`c<bP!tETod%G-z5$?+ zMTTY=_u0&wp7mXT3RN<$+^9XAT&n2XuwN|svnwJP+i1>(VY%3zkD3i<-MR}d-En0Y z#B!<rD|Wm*YxKEd0Yj)1@F?9Skp^8G`i<I(ipi2WJ|<Y2329SpQ9tUybLmI;wy4S$ zei@V?G#l24#Y}dF<ebO+=NOc|$^8d+;VgIC?ccQu)q(YHpR5t$flb73peIUN89-k& z>UP+wV^R+%Y*l7k^K*7(3fFVPuN%h?8j+pZu=3iAwp{bGH~zxta7oGsvO^oP4fTbN zuy2;uu}k$y`Y6iYh4qmqT<b*d!IYd^0*o$8KBi`i{;*UG-3{F%y`<C(O6LTB%8jz| z!+-kr&c`46#b5hCcC;XKQP_9U?Leqv)E6d5mZD@GiYT*E_A^XC4oTtwP!C0bpJKPJ zlT}t@DyX;DeQJgP<E)0sevSrVKo9@-PyAA9(Olos>hKyPJruC_Sf$$VY}2j;lLy*S zd1T)MjsDoSkN?4E22x9~Kujkx@PA$WDWsQLLA><IGi=$vL-un{fS;@*&Pd=z0w%GG zuruw%CqDU^|C|`8nE9H`Zs_<IKyQ4vUawZlHtRY7A$A!2r83$6Vrg(-sK0+8n`V(P z31r@T=Y5QVgftL`9bivlM8WV|NjH|Xh}o7%r;7P(u2{%tV1*G4v9ExoB19qlJY2pQ zJc_GI6wKGk^K&!hYPnLG#o;xdkCle{hDZ8QS_=>oy->{I`36R^W~#u_oCpNS9E5X# zX2E7+2_ssdxa8qPO$KzTvACINcrAEIJVIdwKw&U+vK-5fveZC;33Fn6Yh{rGC};ON zNGVRFa3S+^Er?1omW7ViD^3;)*NPfd2NH{786~RSids$fx;Khhw)jakl^onx9NNC= zq7Cb}E?Kk!G8~U(M~9cJSh{++v<O8o^H+FknWJEQhoDW0CUqtXpTlGbe^wbI1XXg2 zOF;|6DOL@IJ0Kh+DPprB3~L3W`j6HB;s1WFdZdxf6-G8Ldd-J!Foq0UDf=mfnW)O5 zN6<6KSHK5?iuvPpon-F?zussT^1@o(eb-(8-~axj*S_|(?|jF*#Px^)(D{31QH(BB zAG^h%JYX0Wlq*X|?Plv!fAJR&-2dS3{=x69T(ugTCCD3;M=4J!Na^^fNv|?;PueMU zee$$0I|F)3I<;0(`Cby)5z|&1@W95KkEkFs!r=50$QZnd(5i@2*mP>FlR>|z;!I<T zfGV|SZRbM|+;aQPM8mGTGee`v;xInPtyIo7k~R^tvcow{a*`5)D@x&dmSksQ2VZ0m zGOI9<L;#G^nK<Azc9L={em0S3Hz&{i|Ji#FFuRWH&hzEmIiMRk5C8)b36dZQMo5$> z(vp>fCE2pVuI<rU@@iMs+T+==v}5}luf39NYqhq#pY3mUWXYB(*-E4+QH)|HNRS{v z0F4~F(Yas09QOCG^WN=?*WDmMQTBK~7aI4~t$Qk;I;ZN?sZ$})`OyB;fl6}cj$NmZ zPesF>S8lo<BV4Sc<FU;0zBNhsaSap6j_Ru$H1tqh;`AD)slX~a+4ZxlkUKC&?`AQ) ztwr+GsfmN(D5k7JV-qL8{k?A<KC&;}7V2Nx&c65+TUUo7`BYahADL|HWsEcK*=^=- z3mFt+)tjB<*h+Y6v^H|GkeiCuiizQq+2Lck;@RMa6<e;_dczxUfBW{!ccP(@K)9L9 zVUmo9t{fpmNBFF#909lD86wgA{HdRsePtbDPa<ma;UfG@9!!&<1I&FbcM2&F(jb#M z;a4R<745wvA!Muf?7oxFzOefZKYyoWfT#=-NV7AF=mkoOF;up1oh~<n!WOcxqUca0 zoGaUTwt*pOYN&J0v$!ccWx{SQ32@?$`f#?IllsN#^xxe5#XtS4-@WB+%U5oSwXZD2 zyJbt269OzeW=3k$r$VRqmk;l*zIoR#e)7Ygjd2NbfP?HJ!ORJux|E0P%>ODX_0J#W zq8Tt%U9gl^^ZB0^3tuoD7%*G``BODGJzCxSiO;_In%6IHTLvo`4PsA;Weh6oP)QU= z;ZGPIu18U0g=nw@qc0(iXcb}R+dZXNqcc3Lt{My&9t?SbDT<#_RQih>D4{+Sl0IV< zipRNzM=FL`5DbSBoXm_z(4wkHGXzB^Q9!5k!~|4m2zg;V!{uiRS>!=DR(34VoM;Py zaM|oaxO~;-%pAo~%cz#|8bl?EH3xf9Qdndw7UQ&JhNQ3>%4IQp2+d6txS_NXo}MaF zC_LzQ7H6yDXUnJ@XJWC*vs_`ywJd>-OoEfLE0(WJ##0>64F=PfU$*V4tF9UxT*~r^ zb#OYKNnm)GL4naanlZq{#4T-U5#$5X+;LpZ^(7Xf_+?QJN0$^)=<S?g0k4P;6ptMN zJTu^awZ`g7cIq)l^!(QzdG6jPlhsTu7QE>Ly9RGtQ<W5hg_k0+tc^<gB>F{q1d0Lk zVib?3f~0UNDL^2w|K<I^^_kzk^2#g!{qOvarqbq!X@9&DrXp#~TLJMI94!m|XF5iv zP%*PAt3)b+PyH{SW@q6){hz;|(BWFtu8Au>Y7$ZY4n~la%+h!HT7g@iE*rjk`L;4( z7gy<;vr;zST*+awijD0m^v@$KQrt8E2Gv-fIbe4MnVO0kA*7Heh(QYB6_StH;_Tt$ zLr*^Y@X)b6`-Ywv&mQRR3nenuM0+TN0qu5dLf4Qc#M>~`1v9Q8mkz~h1+0?=1DQ+; zLlz}wnw2V3u~a<DR<veR^(c(C#-Xwjwnb&PbM(w?B-B>UhlUQGOeZ?FZ{M+I>DpzT z%g2W&xc``ID*Ac{FS%sH$`z~IQyrrd<D|$=&Ft)KHamlmIG>+IC^DX%V3Tk8%I?YO zlMg?7Pq8+2>1As&ZLxAC7uEcroN5nb+5^3Vsj2LV_O^Dcf1b#XYLX2%sfXGAL18Tx zju*4FlSihehEa^}IB{@xd>GxM=w)lKx%1Zd+;;PuRxVjh@1uOAF^VMCI1t^$)Q=e_ ze91LBrwx!=$yo;pk@&+I5;<?<LAZ6Ep@sj`Yv^yN7lE*rXak)fU(hx6KXW!bagdt= ziAzh4P(^Q`qqmzqI<8jKjG5Scvhq?j1_4!yaG8M#R4na_dwR?pY6cNoFf!xF6^I3m zRLWIE0K+;p1;t=Xk$E0iE#aA_wb12qwmkX=U;JNpANkfTZ(rZOCL8XYZtqG@<;J-& zgcIz;hbD3(@iQ+6W=^-=cI_{I_&uLW1-jh!wwSKbZr3EQAQ)e;wErT35+nRfow2(4 zSu7Y%SL&JpwpF9yiCh6|@$Ccc(T);Ep4h9AjTf!Yu$aqYGFmS)l|u@~Akv-$PG>J0 zWD<=@9g}C7!&6%Y&?iKhI``NxAgT{qwrZ)%{K-a|>q6nFP>Qeo*O^!5R@lBl(4}Nt zVzNXkgolec$7HTRBIO!J2tfsCO|680PjXKLeTYhk&gzDZSXKiZ{((?JIH8<~g>}xR zEahaDUNCs}WlOml#EzZXcqCoSCvvkKqR3B8!o};QT#UWCam+?l18FV-P4=x_xqj=0 zD{uSQ8_>U^1&{$O8(22DWB~h2!ubkPKql$V!Rr&MgT{ev(Yb*`F<8z@I>ml3$68P@ zEf$%YFr{Gnsn!uIpzVRCp-c(fHIQ1{<JRmaamy|V$+!|aGpF{CKmYWz`RpW(ynOBI z!Obhthh^TxvRO<{6LuKCn+dpdDQ$zy*s4$Tg@A}11;H}O-QW0LcDDF|5B@Sop0Fon zbuxB~-_{0nn<b-yI-27ai+ELfdaGgi#E~FDRs-*U?=Szxr~l_4-}~U5Z@mM1lnI&f zl+g|Cvn!rT2q1-RNXixJlCvi9Kh?5wl-oSb9~bH(%IA4p@Z6&wDitvhqyW2Q%q4=A zF>YF?G&K%@#U$f}T~a=`7^mOZRCD7v%GC=Y>}o}^v^m(>bM<9g5$sRRo;`AMKbI~) z@{{|1^uYJZp>qFnj78V_2HM*DqLuJWtgSX3$;C6Wunt$w!Xv}le0BQE*v`yjQUxqP zoKp%`Gd-Q~=j>Frj;ZW{QmvAU1fnahO!2u`{L${wdtR7Gpr$`LGYy_I@p?Mn8Q-6D zgHJ_dWH357^2XkZ)^_Y~6m#)%Ej!xT*_*!hu38E!BnfWgokE($D9Nzj6N}7NMlnUo zw$51o>~uB|jdLG)_~gk`GZTeyJ<U<k>||l&SS=N7JNEL-nWIywaN^@1`^?U3cU`*v zN-ll}h4PFdB=Lw2Tw804-SsYW8)l&N218TAsw6K>Ln3qBm;Q2yX}xAoW`uZ1&i-7o zKa&SUO87$OtL(xn{qkRuWrv(-I!Zr+GBUAceao4$4tB_$1C0d>C(PB+%R|6FJUY_T z*NxPc-q6DTA|2EK)(dfPWJHAG<jIq(R;^lOCz!G`BVZ&u25c=RuFUR~b}mq+fsSGZ zmJ>$^QP>4&j}3n07k=a8zw_Y!=gzE4hTEdmaB?P<O62pbRqE}%p)~Zn8a-Ale*Nyh z&O`>^^X3nwqaC8lPCLwMV`aO@n*Gaw|F^|}L6ia)xg_YZ*u?lWIzh!OX7_XTR35$w zuSMqudde<n34`_QJF*K@DbzS?BMvM1mJYQ#2U9UWOEJ$0=~z_C4u#N|9_1I5f+83K z3D+5T;=GR2Fm_qt!bFi!OY>jZlu>?QDjkZ$!L{&48pM1QsU0+3%T_MF)07SvWImD= zQ6iR}yq4;4Vl8bkTY;rh3>vcBuXYq>>$xoFeh{dkql{J%^H#Rv!stn5k|+dm5D27) z8^#9*R^Gnjb^X07z*J0RtXRHg%cgD1maIrb(<IAU$tK9EyW>A><H=$V2yg7jR4(xI z2dU8<!#x=yh6q{#bAeAdnc(!K#<iPWAe<EYrQUD?8p;XMku0iiP%WAlNfT>E%~;fc zI!i<WhIYR+J29J1cd)$Lc<mK|K8{IAxmv7^6|?IAnwr)`*Vj=vbrfxBWTC-OnJPyZ z=e09u&iwgT{^HZ0{`9KVD*@AVhDvBUM1tyA7Z)xmzU?_nidRyjGbCM?7=+whFVm%w zz*Rf0*tTuk7r*d@8*jU@t0My_t$>1&Apvi0`Ay#vhg_N^<%3Iifu}2w`)m)D&ADdW z=6mZem8JM1w<?7@>B<y^-8%qfUNn}ZwVk>>0V<h$@)f^|7DB0AYYL$^S0i!5d8I9~ zWXswm+c(_$*4KaN{)g{<asLw&v!@?@{K3N~N0ObzV650RfIZAWXHPVe)>60@EU~v9 zZci~eEk_E~1cz9_>LNIhX-}8SxzWi<On)$|>|fo7eeTK0F~~8+VIQ(5nJJW}x`N^5 z^$cX1S!SR<5e!bz;2;u(f=bH4_MEg3d`(9)=>#)HCXb^W5Qs#$zbMk*m*OVn1S_N( zx*niRePn7vTg>@DVJbdTtRFjeh-)jD1B{%SDbL1+kC%#5q5Nc_J-+gjzx@8IHeY}9 zHM_FeLNd^4TevB1qF{{Hn8JpOg+kn&uMh@;Z4!q-SZH!gw^gG-T{-PqbD>_dPPfMA z`6`_Cnv3Wq#+#MJpPpN{x)BW#;S7<DV)_~spn%Xdtv|G#Lq(X$Ak9^cxW2QYw@8~a zpVmPH2BUP>%Yi++pF4W|=*_q8Z13--ciaseR!w1;m4`IU&xdoylKV_2GIL^nh%5m* zGkkhv&oj?g^X2uIZd4s`&8H)Zyo0<-T+Ti@AH$Ddt=_{(9he$OiWBDYwMt;!(k;LG zq2K=U*ZxD_s(8FDQ4LJ@3}%w?1QWzkdk9VY^gy6(qLvvC{N4Be@(sJ*7-7OC4R+NR zXJ{th1v#&mfo_)bf+Efbnrq4V-xdooy1Urdxp2mhy=Z9DRn1oq!XM)IdjJc@vafUS z40?oHbPT7;Icz!|ojh8b4b;*-aa29ozGcmc`9U?Y=r|TZ%hedWwrrEQ;SEyoL1P=e zVA9r#*s*3SJPo8(9$S6n=w<4>IumLo)T?-^qVQy+(VdrN=1zdtK@wYG1cKdFl=`{n zhU@KEYhn@^l@6|it8!q1ZA7jGl%^jX7jDX2znmx0Ft3GK?i5f8Xsi@w19iCXH0$HY z;NTkcp3=#5F@(l*Db}9cc*(}CTeh!Uxr!5+(wJbn5seS@Epv!sxT5`9du5&gN>ga6 z%;udOltm|f9NybVvb7p9>{aa7M#UV*K(pA@T`j3*mUAt`77GJ}3~lHTYN$Z^k`V{A zu+<#^W$rhKa;MLs-05cygz}hnjdiac7}&KAdI4{SC2(CSiE7dlVP3*9B)zJw5r{ih z!y8}{6}rOH6^y>W|HjvPx;yWD(;IWM`E)v|9V0Rd$Kb@YfhGm)f1xoMjcPrBia8v* z#$i?xM?VNr8%-r#z+4C^tJ&Oi!CK($?|jR5@A>9~Kl<U@-uCm%JA#rKXz@UzJoV!c ziiU8FLr|-;#%K*~yjwF`T8n^Ku$!LXb%U${ACyue&ic$HB`kMg_GomXUf8K=e9$D4 zxr>}*C&UlG?#7?HY3J*)l_9l;>Cq>ie)##lPqFcK^!WbWPaWy$N28^RQcHJVW`-G8 zxYFL6D8}-^cp#Oj$K%0VFo(KSG#=xi8&kINscAOw(p{Jcfs0k+A++%;sic<9Dj@Vy z!>HkGuhE91)5f4LbV?0#=5BFMGoy=$77<b+)a>)D_Tec7?*4E?X<~xAxN?zdDmNS& zJ%Ndap3&jyGp9Ic6o>_5mv7ja>F(Qg^PRWse0^7@7er&5sDs%niK_pcW0)f3MDBu} zVS1hJ6^5%J2?X^pYr?2jXY(}NXvB0O=J!%-e7b->^&s)kQ~crFvRf3T=~N6gBcGXo zA_A(*)C!$eXCnLZ^FMhmQ%**wBgH^v$9rz>Sl_9`)wD9@RDztMw7IvEqni3bF@*`I zh@tEMYT(FohxYH@v-76w+q=7|GjkD^45VSQ9`^DWe#B!5Em;fFHVtdOY6+uyi$!XS z%&BfM#00!@`HJd9@xE`}(_T$4*|40(!=6AWP1mDMt5d&B&_!H`FK~09DB52XSV9(@ z>jZvXJBI_9z`FgW_kQy`-+b(z`(KyZ5M@s#S#Rr!PS1|Db;c8^V7{8|TpwGJ37vTE z<RAXYXFmI>FV=$TM68_+6;h$Jwxg`1Nt1Uqk*h<aCe2rxywT?Nnde+7U8^~aaNs;F zndX~*o9JLY>Gh{S5kL3>{tIQmUR1`D=l47WLVy<hWHA0ue*e6$Rkj<ks9On_&@IZI z4IJJxQ;A~WcRJR_Y7TXKAqi?ym{4HS1iLGT3ZM+b8`7X%Sgmou6fM|{4TFEKXq4Oi z6Utfx8K<ELdWA0YbY+|4zI-Ycawz(PDaK+E1+!V}4CF)TgN`~dv6g}ZyL6#yaCS1w zOtUCGQkl_#xMaAlFV@bnOQ^}r6sjV@-mbn)mu<f6(klk~R)&gkZnsP%5`%-wmM>r4 z-qy*sA4SIGFFM|ETx%l7{zWg84IQshCFlB_9&zG%3vy2n!1FXddJ#o+6h>awG6vxF z&O#kJhgfsTx^`6?yE!^KuP96hrUQqbdZ92f9S_FQ|K4!T7R}k+LI;*<4bFg<{4ZQT za`XtP!Et+fdgwyBa%^mj!gO_Y(JZ9PUoMw>_~8dPZd}i4W4JGz6;{oRgcTT3w6`A! z5Q`{h&z|L`qf91aB3#0=*(|TBo#BCvbH|m*l&r~d^_u1V{k;!9aQ|I*-odLozpWN- z4lvhDN@9UQ=z=f$;k9#1%(;f0`_Mqwxq!K1IgItax@m&}I%3|4V-U0wM?Z9VFbB;0 zmapBg{F>P}O|pnOa{T3?!!Mm0KJw)5hw;puC~^c2O@mZtIocJ7aLF@5sb~d7c&<!O zWn%HP4hC}tNDZbOrH6IRVmOW+m>?E(um_HWnWkbghvo!NxB%Mhl!YBwk#OzbNcKo0 z#3E=)vX`W@ZE%G`p;XSXmmQrRpG5)`3%7ALePVQmT^MGo6T`XkD3>&Hb_&^L$CZ~{ z`MO)*ym9Te)vGo}0%`6@hJ;I5L9IZQnRhWc6K<$g`QMnCx<+wK%9_Vb`((NVfhx$O zKsDGLwi}oa8yW$x@`ny^QXrx`uaaRPqbY)QNhla*Rv1U3WrT9US2W!g%N&08Q1xh` zW3UG`7*{l+HYq+{D>BJyn<QLEq7Dh91_l)jOdrp&RK0w|#=#ZL;N@6-GAf-=N4f*h zH`XPnAWFT)3Gte#Ln+i0o_Qb5Wz9L3ysUre)+?@j=CP;l=<W%2B|!xkAR<2wNV#$W z>{@aTOB+mQE<mX@U^u*i76QjoKK}=Q^?&{4Z$JO=_qN{LGa4Gj{Cr1m2FjW*&i1Zo zV-F=;nObp0$8-1H^P8Xh$nXE|pTz>~AH=W`l*Gs@9SvQg(_IOy<M8sQZ1_1hZ>!C` zC$O}EE13I6Buj4|<f{+3Xa?Mpl}ATBj~~DvXnubPklw53nV6V~#lvmM&RDQx@=Wc) zllwaR6O~{o$Q5%gX^1Uy6|TZCUFAq7R^!4NWU}0<F7mBoJR$_BLyKE8>gWkY1x83F z<BKd<S?6%fk~9900S!%Eqv;%|$WSyVR?a!wdK56WZ@EnslTFM3xcNLcQ$%3Gq!GJa zv)Njn<FlYXyA*9HF1+jO>F-_Ix1@K;z>?+52A6er^>0{rX_S%$<DfGb%<);YF&Sn| z86`_X9ORVgS#9S@i`~?uE@&@cd7rszSd$CL1ZB47^_q)U3h!#CPv-Yt{T}=3k4VU3 z&P&Gw@JDpb<w_zXXF>$BYqHJi1==C;#qrS>o_-D;W5kyIEBY?kwpNpJX_7P$pZdb* zNc`y0qhI*K7oL3bNoXGz4E(_#{J}r{(?9+A$3I4@xpCvh&wcK5OO`AlJHVcM?zvz6 z)n9FELl;`YM5C273w}ageDTG5@4ffHfdjyE#%AZvo!4J~JyKA**tjn(iQtr1%hzI& zi+NV8SaJE~mp}UGqf=8;oM$6Je|>p<MR&3AizT>NI`eyEu@uf5?lg~SFyu6v69w90 zeY~w5%&c9i4deH|otv*_$ESuLe&m6>@BYT)_deabB9!Wkz(=`O7E4<g$ef6llWmNE zay%X9dMWPqC^86`@3J<EV&j9e=bTXy(?wc@pa(xHif#u7Y+;;g3jmCPv>|Gm%$M0) z;y@586WA$-(U!6>PK<GLCMrBVQJS92qxX=T4Q40n<y;-^`<6Gp?ZY4b*y<IRghT0M zpuK=*ei%a?ZuO&;Ih_Z)WqwIsARYCaqoMN~2PC0wZJN;FzVm@z!;pnYzbJj3djz@9 z%tSAAlQWA-zR|$IWh(}Hm;ZR?2gj#|kQiW9GgYibVK<^Tu4L4gin@nuSP78W@g|H- zC}mg)JpJ_344F$Wy)?is293iqL|Z+gaNO9LV6Gq3Hjs8bm^<lMVS{WE8yJmUjc{LU zDqRu?#ClVkw{H6C-~89-pMQSq&K*K4mPed=a%7h%7vprTWT`R}jGzqHdE0gG`ObI0 zR|$^ZaL1CFvEz|=xveeP-ImGb!|7ybV0ogH3?^>r-1pc+|I@$!rT^o%zOt-q6SSWq zN<hR+#0u^jfLR}{AYz3&n3Y_`Qt6s+@>_H2%bXK=(VES{HG$_oH@@=I_;ztM{;3%7 zV#LB9Zhrq$)iE?_dVF82-Q8`|GE6^v>DtS`_=jJ?a1T7|(BT7zj~^NvJA3NXNtQT; z8C^%kMou^u%neWS%g8}{h+#ZCF*7zZlgp!NIo50uHIb8-$ODF94jIbp<Y1bgbJzx= z4Bv%jI2O+IngH=UnSemCfm?^T)TfwFRwTDcCez78`idQ!`}&q3H16%{Wif_Evr`=9 z?!9!Tt-Z6eGo5ZD0m;I#z#NX23hd&_m>wA+WD1ozdWe{heMzL)GP8-PO2^nJo-8)A zZgb^PNkpnNV=&1onAGY#>I|6YHy~p$=J$VE%x{oh2k~l<i=_i%vR<Tc5_Xp=$R{~g z^3v0L$IeW$eCI-dOSfMh=o5A#Ta<_zVYSl$SIb9rOT;CYT=LjskHKF%Iy(ONkN+6< z3Ge*;=Rg0@Ll40eKk<oAP=JF64?<H`uU<`gV5O{#DG!c7y7I`8Bfs@qzqM)8rjLL8 z<8bkBeB&Em{Nfh}1_suwS!0C<j3~sVNqPDmA<THdA86ALfB3`E(b4Yi?)hN;DF3Sc z$kbR_aVQ94!)y{`E!<$AiX?60oe2{f6+Ou{gKyq+>viv%<@9B^u<yX0AOHA=M@|ee zZYneRGowdx`O&VvIP&U5CYWmD{^JPdsU@~|LlAo!i6oO?np(O+2o&gOy1;N41uT#h z0^nwx(RwX`vF%*0jFnRk8FPd;H=|9)v!_NY#mMNHa!*(9x>Z-y3fa{wmVfw{KDwlH zAf0F*?Bli~1Vsp#xqq3Yq`3+8WR)f|C`F-yte!IqP(Xt;x-ShHOL@RR(8G-{P3dp| z5co6fUkcKs@oF7cGQ&v93KK3D8~Y~ASyT+0JTT%T!CaA};N?Vs@}lU8j-%wmsu>BY zevLZ1+4vlRwa~Lir(fE;_sw_R9_qw?4$=oq`e0-Y6FRt13ZWIllHH>`+1F*IlIgPB zm6ZfsY|1r_V^=D+HV!1&W>ZZ+!9cRNo$2!KXP@7C_0@DjAPozSaa7%#a4Vk+a&&^U zUC@(3MeEutcK!OtKKEa~`G<RcGO_jMj$C{^kwo~x=&YdX+Kz=BJoR`z-22pzpZv|= z``B-M^!KjWc#CxV(9zKmXKLT*e|}gWQ3S2yn_b{aWX<0woPBIQ9qUyec&*z2YyO-Q zw;@<1^2NAUk8OS$?a$G|y|4aP{PqgG=eLkXc)dD4dIH|Z&ML+qHgDXj+ioMVB^?`X z+OE9`t!A}%<V@Wn>Z%muiG&k72YH*Go*o%FGcq!QfrVTyOPboDwaK=2L$n-*5W{hy z+7JxKVI$bf1*hQz063{{l&^&71V}KHkbF~lk__0PeG=LIVar8<s))9P1p&W-7;ptF z<PE3X(ez|15_AZZwVlICU4=J}#c`2brBqBLW3GUtO$^yCAWea|?GXeod@$nW0#yZ^ zzrhWD!N3+UgS0?v7JtZjfail*cFeq)F6*2OXPCJ$5Gq~{<d07rdhQU0!lFnamUOJ$ z#)*1n*+>{_bRjYX_Oc;!Mgf_r{K~KV3Uz$qi6=Oq0xSLNzy9l&Uw-+|{_M|Sr8Wxz zlA|W{4iaV{;om&zBRaajzn^*im%sew@$vD`eC9I*vY=rm&XSr~uxg&HfQdrld}_#| z9Vh11($Ro+0&ot7oj7q~!-fsK5;(s>=C{LwFh7exufKk}#L+}6i`LU~;An`8f@OUT zF%YvOSPzvZ81(9hwzmzmL*r3%*t+_<_uT$bx~@>29Xh;k|G^h$bK}UL_Z@ux#l5?S z#!tr+wNzV@O&_!xqAAEa>Q^${rgbwr0T{EADHRH?c_fV3?bm?r@JtzyNygbz&<!7@ zQXVD5F!wwqGOxe+9ha=TET64r5?yb2-CZ5YUgX*dtkyXCX?;U1<`6h;=Jmv)YN#NG z5jYd8BWFTR=e!0q)MbFv`#9>$ce;DA9=GVP+0#km#MFFF<C$?^hlc2uJvp0Zv)#lu z3K-$u>nPWhQCbi_n=K~Ww5DrJI7m%K1muLaY~Qo>MH(fJP$pRZ?tk$G_~wdDP7sB$ z6)DZZ!j%<1UFRSJ>L5d0<zmN21_!htMj?%Gx4#Vab!CQ?agI|JzyziiCn{kyu=T1d z8FWVv46WL<Ug=_kB^oZHv*|5;RJvDmbOM`h6sVSyfrO5?-tmEffx*A}``<h8<k02U z^-hJy1M#We{w_|(jZM!a`qLBDK(ZLP_O6v@4<7yOpM3Crcm9tbyz|#sCFx#D8cwF= zh11OUs0XMa<i<66!B?Kfz9hAyN;Vy}79|1|cWl@PevbFz>Ud7ni)O$c9{ZCautAX> zGvO6y0OoN43h{fqR}Tgq9SkAF;;|wp8E49|c&1jUqVSxIbc!=UN7*HTQ?Yf(3K%&> zq>U?EQ6)e@H;CFrINh~u+2t$wC>e+wU*M&1nc~qAbT5OJC$D5`yHNOXu9X`zN0psO z{Aqn!G5{9~W~ua;rXlJkF;4dqj)4t|rVD~NwSfqho9QJimgyNdH4->d0H?U?z-evC zh>T<K{9^r%EgcmPXFY9A1X-~1lLplR(wYn2fCuN`&AY&B3qT8S%h&m@O3^ugM8CiJ znX|rZ_aT3-vWuIlCjt}IlP?^bK0QfTC=pw?b$tkdZX|%VOj|-?20BnmwoY^mDPi>q zTb-Pogm+TkUAuOzTeog-aPUiC`Vx1}|I#o05*fiM@dL@?nCkO{n<7t!`|`>s81~T6 z&@<0GvvuoMLQrYG?6S+)QKr$DZ((yA!SdI?{`F<cmVMv@A3(wkjG-I=FkN7HB|#WA zOx*$(sI05AMQl|6r}$Yc{fkZVBGakq%qs*^<l3pO@#}<_w)Kf$O0y0VAyp7sW~&6| zau}$>hIjY2ORn2|$#x{Wklu;h*!1)yM*)~bmP&;)XHK0SIrGGGPt4?|nEt}YnL=^M zp7XxAWGYF+GD!uW-6;S%K}#tp$80vwtZL2XwKv>w1B!>7FJK|Kd|(w!$EoMA%oXOu zogSR+D{A8if=X2+cve-|9%9bSy3sWV6`+LJ7%3r~=DXKx{^p`2F0ur+;Fv33)PuB7 z-qRn^3%q!bh`W)R#%TAF5E*ce@3b{f_%7ori-rjE3(T8Din)9|$~nVCCKKm^OQ4k& z3CW3};vf?&I&?P!Jt<AAKz+PCwC`o6m4c=*I5f;8m>IB|4GXLsT|>@?WT_V53KHUD z+9(#!DKR3r!sy5INUDH>Dc@w0$Fi>nGF_eh{Y##C;;B{J#DKAb8{_h7w+mpgFYM`z z>0+=NQ}=8$s=SGtw!P`V!F_-Ex4&JlcWk^imF%lbPv?^D@s73(yANH<qp6;7_H3bC z8*l6E_{(qn$Du>}vC+|)UM8|6ZYt4SwJsHLAvR8?3tZPXneI7dYe<{5+*1Pq*$6Qx z*Cve!_!}s6P6`+Ea?uR9CGq+A>V=r6<;kmsfE*-cuNK0SQ4OQz2tO5L>6qgTf()jV z!pSf?$G|gPM~utyL2b!0kwz%XDAkUz@l^JGI6;fOCME<bsiiER+Y?|EG17Q8oztjx zpllZc)Cd>u%a0xkn=%+zmXecOn=)tx6Aof*iUlrw7f1<3oKt^PHHKZ+NlhQ!EE%Sf z=~SgjY={tr;lxoMYk!()DJDts)%lHrpvFZdG_Bz)?22#X1*L#dImpJN8L<&-{wHez z56lA~S^V?E7Yng;TB0zoWaAwxB8fOHQc9I0*+Zj4Pw$Tuu-_YO8|YoPWdkw{*ena= zA`2eW)({!w^Q1-rAbD0DUU75{;%J_*<afR6UC1O@*TQ!x6090{1jW_@Jb`Bt1N$T# z&U)(9sSkbVL!3v1h~Iwu?YG@_8=ojG3v1TL@a(_;`@e@VzwdqTvy4cS+-X>{vo?VZ zlZ(YN<h1aX=lu3DfW^XFqI<6t!}I$+uT?t!G<|+_oeI>Ny1R`Jp&x889Eq_qWqM0v zGF_Bfp70TQOqov%yA<k8qC^_AVeRfopwyjAb|+SP9AITnpmJH|=XU+F&e;Xnd|+Kb ztU9-<Gf86ep8jH|)(s7(vahf3Q^>fmpIJ0>R<fiBs6#vI&#YBi%#@j3BC<y3u28Ab zQ*@mwB|S53+|Y@bQg=~o+UnNvh`ZuknXD;>wJLsk7KewzkN|#$6|I5e6+gKv<)4{z zz0R=LijzhrGul*@;Xgi*5w)nX3RgtGeEiV#%s5*GYX(-d2igkLS&Y_d(-&<u2?C)@ zT6sCX+b}LgTS+<E5ffRtfmYN4qsLE8kB;7W>rG<WYI6Q0O(ajesyNb&k*U)sPEX}A zyO--}=f;%vZQU}w&-o22XJZeKNUqpKrI+1ohxwZ8=V*Y@xBH1_0^{XCueusYDMMYP zgV=>?DSCwqywJKqw>Dp@zV9s`KJd~D!zXtidS+z#<=AB#ZR;;}_Vv`TwVU85XCW3S zF5eoQIWf64+4t42{eSUH&wJnetDUL-&XiQ@C^Dw;gEegYT4`J>r~%wJ3*#xAcTSAi zfi@}&SR-Z=LIXjr5k;@sUGoC;?SkAzH_&-f^=OLc@dFd+ISaQ}{CMoiyu2Pv<O^)i zFvi&JV|5bOHM4~xSmnki@<(L8!c)W)BA{Z!V%v-=ONcg6i?dRctXHF(5QJ5*L!KO8 zfthLr;8GO%fGePag_w-ya~2rbL(u$3Ygn;!!faStIh{nhF{CLr$#WncB-X%Y&npmz zI1#8RfQCyWe-U~KuNiafn2Oo~V{&FE^J|a>7bu<#kD+$vF@D1<4u(XU&1B81Cy>OQ zdw0H;kd{{io*y_r#L}M+Pa~p$&OHxoSw)y-&KAax44>YAl*1{dSfFcpf7`N-Ty1u0 zlJf)U?CdP6XS4(9(^eE1hDVLiaAx&MIQmntSco8!X8_nxU>vh}VsDtQ2&*9$c%bIQ zr7w&t!@@uIv5yhuyWjopBab}tzyl9_``h0}f(^SRwe{=Qqu2!_hZB<vAuMxo5OG?S z#w0rHZ&K!~m5P*M!z~jXt2@sH8|OUXUc?s9V(A!;wE(}0^yjDGLO7<B0<U#FtPXrj zep6MCpj07*75CLHL0Jln(v@Iz@QM&fsHnv;6H-~RU<5TOl;Z#@p_qtHj!A_gs2z95 z>FOQPOjqv!W6sbM53^Q)#pxvChFNOBa#1q2S?efiBjFN*W;|-jNxrO{rC3|T{zKFq zvtk;7`AnH_uP{50hFJT;mqa}@tm#Z~G)k*XeZzvb1%Ghh*r7v*jvqgc)*fhpow%EB zy2+c~xrX|gJg6q5+N0%=2d3(cFh1~C44mC_`hkZYJb3(2|C%LRw{OD8-T29o-OoQ8 z#2AS#IL5T6Rs`-UD%S^UJC&ASRh#Zm2CV+s2bD(T<j82SRB7vgi3<$VCy1svjFEIa zl1xwUJ@NEoPqHt!dE1rT+Aw@@=&4g9SHJZ(C)J0^ip9DPa(O^{QDdT2m8)ulOcD_w z+e}?u7>10TJaT+l|60YZ)SbBxWqMJL&P4da3XAS8S4t`N2m_hl`<*X;;VYl}&V&E= z_*i+%Elcx}Ecb47FU@4@W8ru;sp(5S84nK!vv2($Ha)lJJA1zP_|^?OZrri+vh`ci zfgUWtsZ|=)FqCb~ff{AwQ;QR@Me%>|de0wdep&-}9smP7=Xs$F7<yr(!DyeChS3rG z<fkcwSQPJRQS22z#LhxINM6}UrMLjJ(f|NJ07*naR5!s&&eUpo7!0C#0FDY#;h*Yn zW`B5~;BGmE<~%ZM9XNA~NtY-Eg~hV<qwQar)c~5Wk|V$+Ik8R%jU;`2l0)~(r3?L0 zI8VqBL*EDhA~J{qe7jj%3Q4jKAys@b(2oix=MG6xCiMY@=jrcODk4ks#+MrtZOkH4 z9WBBHuOc)fD!k!04+|7LWZn|atLH3JUOkWZ$sgGA)qC|k^MS3V9)NkofRX)#gX5!9 z-J#UP$%$tldNPT^dZn6K*0XxchT-gZC6;GkOpcBR<B8n#49B>U9l+k;udHz)fACSB z#)*wVk~lp{2$}MPeX@Q+IE?G->*Et7))*&TlkH*BK?&>EfBo0@?%n&fuYK)1-}%lx z_uPX57byb<m$l^%m4eyZHZVEjNQx)nU^Rw5$Q^hKCobXUyjnK{7H-}Jzxw0){T{I2 z13(j_TC?!S_51zN&2L{9Ne8>f;Exu6oEFFM1i&m59eO+THx&d<^rD9=DWj9Wi64UY zL}Ah^`;<z9vqZu~IndrRRRA$7?$wZ)5y$*k`h!ZuIi`vN)9h5-+Tl6OLrZaecatlL zvhb5E2rpG$DPE8%>pQ}+o59Qg(-U9<M3RIU8euw)d&Te|Jz{SNada+UI&=C2;&CwN z*s){mQ^0hw+=QwCoj_v00a!6HF~PhIdC3Pq_(A%eSr_Q!wVNxd9#%E)wZ*d-yg%HZ zf@lfmGpK~x)6xePIw1Ak@x3Ge_;=r)nwh?A)8%)(`;GB|q!{Y9!1j%!-~NC95eq#; zU`7OFkdr=~^C`N`Zv+MKX70QKXGs$?J_rWmDa?MRB5mVmMl!L47%)l2v??X%bTo+w zF~tgXtoG!Oe-ck;-uSjR$;3xBaOja|&yJkhcGZ=U6`eJ1Gi{3zPZW)TLa|AoTy#~m zyw2!{yIQywV2aF2sa$9*n(1|EPA}r9v%gt9C<vqy=D4;Kj7Qny3gn@TsM!C;M}Oza zE3f(bcfa(+y-%#(99z0BHCmsE_j5-NbGS&nCzhS4cCTSZFcu%E7sm5Xzx2!_fAi;C z*4=X3weQ@t?$-ABI#9P<&L*_G&FqagsUqSUx1YK00Pk6abCM1{T|TiC1IGYBSSk<U z$TB5*aP?O+;OyzVdbqFN+j%_~%7D+C$O0eT$XS2~Te}-}F3<sBp`;eH1U4T;85xui zM@j9aR*sVf9-?9G=&JExpeXE%9qXIcMVk1M0K}DMlG$Gp(F6|sQ8T$zSVX&U-kq|a z`zmfKrY!C&2Ymq>5Q)KNc%`(~LHg#XgFGsPfy>Vt0U0zNAeDif;#vyswK<-V<2mOF zXkN<OjHCdS*55>qVl^1BMeu*M5PuZ=+S1hXqj({nXMR#%$h`DJ+&Ie$HJdGQmF>xc zCnts{+5;WsXno+4rGd6kzCK$jaw)omgrQK3^PfoM=}uc>vh;)n!amufrI(?GI0|fQ z6yu$g3ciSA&58m%uRz-37=R!A;0Nelz2`me`OV+_P10GqbSZK$PF#>I928&{yMU1( zudI8Bh#!6ou{MIs)3Syf!<*STMiH8b@OXc%{S~)xVEh0ruO7U$|AJAx=>E9E_H&(m z^{2yke-uBs7w&oNYa<bdm5y4Fi`Gv~Ft{94&T7N}0}maS6!yw0r(vo4?#3a^Rj`s0 zX)-KW=QQ=y&Y<!UE;}4{Sk29^f)D@$gr~A*<g#6;90crQ@JT9-mZHFjBB`qQGB1dv zL>81X(Hm{0T$owI<5}Fo-p9u#fAE9*?)%~WBWKSbeK~RB*zoW$FdzVkfd@uQzvEfC zawYh~^p1HR4%}!q2p?5K{haGs0_XROh0G5p8CPG|F0As^tZI*{jI%QK!-28t?#FkR zrV$=Rw_dR&jv*29=Nsy5eLd~{J*88$6|x9~5LAZ9D$C5tsZ%EoQ?+QKZT-d#ZkJaZ zSn*Vxql~m}HCIT-5{XU>jgpP%D2;%qF2ZuU9vD9{eEQJIn|JL}n%JN{Rhi1prnte4 z3#Z6A8LMQg2TvZ$PiGUewYAGu#XCC#9V!$%_(ahpfT>U!m2@yyeN@O{lHS*3NEclz zwzQjCqp^Asu<t8$SBilRCyt=?74xZbJ#@?VpYQG-_|ISZ<WoO-^4eNImtp6Mvpvfb zn2tzgBAq?yY%<S5ty(IdUJ{9RhsxuLp_lIe$(Me#W7E&Q^R8c6y>vq+%H3I^d}SsQ zPDX?Hr7VQjk;M9LL?HEK9T<+Qe=vW`b_hBy+*#sq5xqijWmS+$IfS%TlPfLn3m{CR zB8&XAQkg}-UOAW+^cvLs-gACruepihci<zlZ4GW%AFI}|Q__%hnWd2HFxatXE<!%0 z-9kgGbTImy147MW{puF9WX-F!iVGJcfpcKZ!U>F2eK_I3xZz8qLr{u`vyKp}Z#KQ! zP`q0XVpL$5fk5P{YKr1CqByj)vH+<-mJSVtJH>^}*;haQx^U8II<JIY8`>9F{y8uU zv@Y=c%{1nITM}t`^+&XP=K-KlQ_s)j!-dey=){qi4(lena5>%IGq8SHC00e1v0BT6 z%Np|0a=uh%l1<}4>0qe#gyAuA0WhU1>}fzB$=X(;<O?J`9uKF1kx0WD0cHh5^v556 z9L8yCTm-^FpMCaOX5uV=fd>G-3%g|vO=?hBU?5eb0AuD8`I3?GW|l|fOGbRc!_#Xf zf2|kuF9=Ma!TVzwWJ`$u)$e~rU@r@U^x&<(yjSxWPCE25oK!G;i>G669{x}S@i!0N zN$Y@uH$t8m35Ls{uQv+#%G4K{&Q~QqSBrDd*<SQ?{D-j)Ltx$ASVLQM#=etiDJfX5 zU^U=*^5>TC#3yTb0GX=jbZm`Yo1C2Hl;GfCA3gi@Q%@jg=Bxn+k--5tE--j#8G4-f z^z|n{`N^Aaz8OEC2nRzz52fwO?{CBN1llKy;`xa?*8-vs6jD@8vkfhvyrz~M!Nxb% z$%gh1Rc6bXuJ+X{RtIGBn*|3Aj(|5<Per(*1#zDi7?hE9SfP0O<uk_*9zjV9>HSO3 z9JuFizjgDiw`{rnS}tit+tKY{F_3g&Gv?)MF~kBGb$549sB~I<P?Cw!v1cB9G&epo zxNhyzRfBK&!21H7rmhtzj^>~G$>WH)+EQ&NkDqz?o(HekxOw|6*T&bRq`HM(49&%G zVoj;bLJ&+uveVp2s%BtDf#M9@)Y`;rOly|KUR_Ip6%K`HGnwWF$0%q$KRXkMr8lkF z@gF|*r9b-8|Mtjt?%96pk~N!`O&^&^w0B_CGCMOJNpiX>8bskFR9t>V-{gs0XJ7l) zYq}q~=k7;8clX=g^zKYz&E!~Z>*lMk*?L1MP~=W))V*fv(+Ld9h*$^9($h_`4n&B+ zu}Q4;mjZ=&AVJR+ifA@SkHK#5uzI;jcnz`D%NONdGY0JCO8Xk}+0zR*kJtJ}`+)Hr z05mlRz**F?P0Ex+Y)m){ibk9OR#F;ClQolc2d+`Ss&lJ`LvBNHmmEnkqFjz}O3;Ds zWPp)QlT}-3e9tC)BZy@1F|@ftlY%I|4F^V#BMvUv25z}H_yK3iWcM>!I&PRXc`&5H zrK5$e6LAa4Z16cE=yFg#O4bTssraAPfc}v4`2C6a{fkAp5SVl0a&djUFg3&e(xE;3 z$4^aV+B#<Pg%y_!M!TZ3mFZF~hX@~Ogrtj3+D!R5nE<7OmGVS@%()}Z0Yms${{H!& z|2aFj?|kPww{PE0j~K6o7s8t%m(Wud&CprGDJsiZc<ruTyEyX88roUQdiehP@4w@Y zJBUsQd65XzmZy<mG6nI7OLhd3Bd_pjLSB05CA6<$_QZl%!?3NUEe&q3ErI8@iQYT_ z!*dV73->(sspa+j@P6RM{MMEJuP#loD@Z;V$o!T0pYwy^#{WP_4`T&RbZy0o<Ko~1 z8bR_RgHjlTQa_F*D;Qy(wp4`hb1mS)&v~6ImDssU(2~_SWo1V$@EzijIH^fng7lOQ zS0y${bA!Jzq}-M=Xoc}-NkK~$jQPC#-S1kvb`3UOesuqRqoX5UZ_?Kw4=Ir*ihiis zgEq)lc!D8@Z_23Y=8D=3;djA6`|f?B{jCf9;j}s`R@7LF3@WEO!Bi!)jmS1_0shEe znhUC=c|rqA6kA243{m776IPrU3BbYz5%U=8EI;+wlWUf)+;q#egj~9{_O1W=w~zkt zp%trEbzQN9q~XC_lO$S+L_v2)kt4k>+EOi6w6s8Oyma82o!1|D^7)7E{b4xsXr{O8 z*4uAevw0mG#++B${rFRrncOY6zafy01a<_D>>m2=SO1Y!(vBrJhd81{3DLj_vrjKQ zZBQMx#xmCYnHoV2HPF~5;ESJ5E=t*&4Mp!zXeTe>mUcN-?o7$bZJ9Lk;9RA=YT)wU z`otgI{ryY7@!db297zqVP4zBI<^!W`OW@Yklj9SEE85XGnaZAxc0^=UF_3-3dscG` z_Q^w!y>#fA(c#j8k%zu^&*zUEKDlMfRquNHJFtSsRkQRRXP_~3h_Q}HC>^Y^oe`WG z8$+v{^KX}L*n&<UbwS0afvps+(TU)#CQ`gzta~jPupuA4>tSI_X$Uu@^gQ;;v*`iH zxM`27fE}9QI<D#V0<lO-Eya=*h};?Sfsd)6dp7#j{DN#SU~&W*)Hsf%df{_La{zO% z_`F0IBrM2bmw1FpLM%5e&{|nk#^=P~Wp_X`DLG#v4M>Wtbm%|#O`}g>%nyXFu8=$% z$l5Hw1M)q*WPM@sE(YHMHve_81m{C87((<IW~!$uqx(*B2#d|PP;at*ZC^Q3%ws!0 z%z+0CcEf>#sIxO%ktLxwXBYw(w6zFFkFbM*tQb1TC+fl{XeAyTY!c%b*IaYW?%lg# ztDGZ(^>V}o{{8NEznfJridU##L1ZDIENFJ@*g+!jT3|>YZVC$rm_;*5nPi)~z-!5l z^Z{dQ5bpl|_rD+R4h(_7x763lY=M6NdBD!|$)AGXzZk>zcatC9?<YI&)l0_<afJax z+4yY`3+TDwq;Sto6Kyr@{3ecZQeL+i)J(jI_UCX}!)1~|8jWbzt$<v9UhY<Y@6~<e z!C0W3We~%K*wAsrw-Ex%@R2pGusIf`ZxVqqn40{X`qG=|j);lYQOqw~ea%&W_N71h z>}UVu-FM&3@ooU<R-T|1*`cGy0d$xyenS!v1N}Zinq_PJHp_NSuot*Uy#(yRcrhgj zVo?ZkAu8uoJY@-S?+2#g0})Q*ic>N>K=+t^bOBUhVAVLg?V@zhDfG~s6TwKtMoyl3 ze$Sr%jvf*IY!UmS8#Y{e>e$JH`wnbd-4kk~RYftYQqpi;jw%~c0QNH(v*bcg(ovm( z>+jsv)7DWKn?7@PWY5d{?kgAWYJ1z#u4Q#@Kp8qZH8xthac3;m!Ll$j(A&}0dGg@V z%B-*`8Hb%qX23B_jQUYLmc?p7?cusT1BVD?=e5B6Ht{|=4|u4CLkozaYp!LNQ%U?0 zo6Sz7GwD<$m@Su9_FVGu_y6wpO*jAP|MQ=QhQ}tBR(n==2g=!Wv6gO6oH{h!KiCnB z7TGIIb;ZLSv2t#zRGJ>xl3unM6iQEwkByB^U3n>b;(P9X?CE>~{ZPr(;*q4g2#4e5 z>5<{-+;rgB-jQ-XnvS(yclAwgyzQ+wUvoPJWEY-esEv|a<+O9ka{r>;Ysr8ubDG#% ze8IN%0u5$?r+R>CqHH~jEMTct0$t4oaT3317ejU<d1W&1FiVWhSYwkxYN82>*ps1( z?t_WckoY@R%2)3naW%R0!{gTg*J`&UL9sZca`Zf+VS2Gifb;XFKoJbDUM*eXl~Ylz z3Qa=eg*ay1%22)B8#y(j&wrf{IUmLg!LuOzf`Jz6+)s7*TYsYS?6XHJqj{#n)8+h{ zt1plDrz^2ysE(CE<cpFpqQVoaaD)tv?-0iJ;f1JE!6R9+{JVem@1QCq3vsk12p$W8 zcfuwii>y&@yzxd<tA>V#*yx4S!c%z?juOqzojc*0uuL}d7)30X5o_DluO$mx1(^L^ z0ASbvlcu4f(PiV`*Is)qb>tH)nXJ85@{raG!P64xfA#zQQO+OBAY0<Lyn3n44{r&f zULLS7Wzbe)WJ27!q`@gQWd>^{i?&$q>F^)6)nIasRWeceO7gHjJd7euOzkOL4k6vu zNNFig%WJbpT8}$54F5oJ1I^>RR$7%02SP!b=YWZ<5(KnQVO<I9g(ZL<=)HgQo8QE; zDcqNsAO<MGCp_reqq4Vl?OO2AW@!N6=c_Vly7^_EAJT-?um7vx?|p)*puwyqDU(IW z5A#ek;kYFY@>RnyP(&+Wl*n><X_;`=E`oJ|S&Ti&o&*QB&~3IkE5!_RDO_ds`gL*c z?<$mak1=LAlSzcH^%5MHS%}P>!51^h%;__ulhgTlXOipFVUMmYLtF`X^5w(zRDAjB zrQ7b<$@MpZTyfPiPv3X{eUqbSm*$pH*mWD%9oS#ZRSIIjkVsf!36jV@p(a0a?8#Fw zm@a3TibaN7M_W7n!+2-D!>hNvu?FGYMO*CQ7%(98GhNHXM1MjB(5)@gfrznEEu^DT z8?09ow`_gOWxs#bvwI)-?0^1^>4zq^-I#12EU(zm!J=%uT)?Oarc#k*<#Lm$L@e16 zFLIsb>~XFfi4R13yV-na@it2d`=d-FvfM8h3C`B5+{naHo9Z}w<0FA3%iCwiiqT-~ znHL}7Ld$EfxfUJpNR+GS4b7Vs;nm4zC}}h3f_`6n228eo<g*s{hxp4yH~`*LpTH0` zx6{19;uT(Zy8<gi>c}mBv={nW6819gKxL<j@4On9l2<E54NFaw#fHg)L98b!Sa&*R z++@#$X>DqdZi_|?Tkpix0#C(iFj`j~UlTh9++fB65~R@zt2iPN#cnzPI6p`H##hE2 zN{Nod0Md-2^qT<ZGWc`Rw+W-vJ-_F%K(FP!aL=P?&iO+Y^EYAj>xaRHb#8KYc>nQO zE>sFeJNnv|ZMr1Tg~7N2q=Yf6oj0-FFiS7a_Hi)U#Jo^Lm?C@*rU<!Y4D*EV!YnnX zrrn)lDl8e6NiA3+b6f=blz7m$A}*X5?N;F7tZ-t$SQ+E-wtGp9h-?xAOqztViwu7S zp6qxf3oz~Q;lnWCUAuN6f`*7#U<)nws&91{PMzBq9)NkgW?%5t18xB$e15V9<A?P7 zy`=E?!~N-a;b3NnMP!3Um`Isun%shOOha1|(W}F0rQoKaE<53;7_gi^yKx8J^NS-f zQihkiaib7HHp}36{~RRYHqo)v1ZL4x{>Hd)GiEOe%G4I#m=H)3Mi!?>PH-H&n4jfD zIC{>^)xPzuZ{eq$s0fgnY5dWxVAL=E;xFEH*Ik5wNT3HW0N@NOROF^>7Q6ZGe*J-d zzX6>mgppp0Xa$U<$VvCGOkXP2i_|Gnih#P<BtJ5B470UIPaI#mq8|&!T)`SGm5UPv zM8T;@tcv9_Q8M;_3rp9me8&e@BMhu@cS15SK9W6f@)$?JR;^eK8=uX&^TO3&S4Su6 z(A*)T>k1f=66$lhGCzLk?2o?vz2WhZU-*SzSbD_<?XCC3+sFG;nPeJvj%IZ#vgwu` z>#y4uZ%<<SK2?v0CT8>FGuy7-&UGbXiFued@&wvVMyHui!?)Nf5(8!eQ7bY?oKo#M zt;Y*hz*#8G?rS$N&|yN2V{A+zAluBhpviD^wisqHUzSessT#pPA}ictc}d5TH(dXg zj{kkhq2n(;x%a;3ANpbTY`$-GJl$Q(C(4z45bf|hYWd7h>bc2cX>eHr;{x2anu(>d zlX;MVo5iP4!0bv^a$H6!rocr`tN<%q1se@am!`3No{pxl4fW#wr=EN9$sJeR>O=<( zj8)-n3|PsnG8g>(nJ{2~?p{Ot0~hy8Si(?u%n;TqWd#DPuAp5=3j7tFWD%)i-@T6Y z8}*bx8f3)vsL2oYY<95Z*uH!ja@N_R2%c+=>n3D~LLB4NObqO0z{4NlF7RDKcs5fO z7$vq>$HJApj!!y5MmQT>nmpo2!A%`l>N6}GDL8iCKtWd~sFBSxG^K!Bs|s@+-^|x5 zfF<0hrhT>cUl7ujq5*8BRW2?^KfF;y6+_dRbFu(UQ?d3Fdk;;FOwecOFRb2hN%vr9 zG08D9=JV`UMc}*8H7GJSOPE|YkxIff8Lp5&k~6Le_hn5CcZ6RX6QvCBW_YKqYgx6t z_r34^qd)qiUAuN6j%MM)l7-O@%Y@OA6e(bEgXqRY@vyu`w#+gJLQIbAH{&Olx4-@E zJc&*g0Poqe2Y^p~>QkgiBG7A;wqV1m>bZ`_Bw51dV>OiBA7~Be!F$PgFdl&SX}-q; z<`eM#*ZIJNoCm-@G4DjUsqqD-${F%A3zXvN+(>X7t`Wt}F2Q*xC30g-BY=j`UNX*s z&5gc>5L-OBL17&RYXRz@8~E1z+5l_53dD^em57mV;ob}tDWA^Y1UZ?Y-D}36hJ#Qu z#GUQWKKt}T4@e1s4u!dr6mzo8n>XKi=bZ-+9z@lEDHnSggn&q38eL`@f8YRqFa(tF zZ$0=+rII<<64;!GEc~?*+Ki}*F#eg@qlwExmAY`U9cw2wtUu;E)7|T@Tt9T=FlOiX zzWhSR6+6;luE4EjC#TLFJah8MF-|c?<7w8!Gn2E`U_t8p>`rpOYN5ow&WY2f_UwCM z`=*Uc)-Io%m@Y(WScWQO3miGZDDw=ujeRLB(Q))T!405Tr>~YU+`IMiE0*>Q2C^I~ zt5;&-<D;iCJ#9-@4r0d@HQ|ZubRv_^vaO3sL@oM{|L~2j{?0AeZJ`&-r7}0$MB7pv z%_-&44wH?{VxSajlWkpCyjIGRAu=xf%^*K*=ryC~u@TWA<Jy=|Wd3yPIwUxlY;SL4 zVa%PcrD7owPmwHgU`~RUtHJBHz2TZ|x9+<6%|CqP8-M$)&!0Fj(ziU)y)+$8)<Vg8 zy1Qd!WGWCX_bug^azWR7maDnyH0Ka?;0XOR-I<oBilm2n2=(C}FE#_(I|8wMAQOq7 zJ$<&fec7=?LytZF@Qy2Pna$5+lHGGNOsYhS%&TT=wHJE72nOu6l;`mhoFC$SdPPr5 zT-#gK1d9)PQTOo&^HBxaWYQZ;DtbsmS}Z{<X^sR~j*S6tFAF?d;Q?u4z#O!N*gl!Z zoQy^JpN+VXB^24gJ6Fo8R@E{&!#QGjFw9rujM)MuN4dQgiZd@mYoB}WAtnvFq?$<d z-6)J$G?ip`2y#OrJZXmJz8z4GsPWq@yw?6g2Blz5H?sMhtC4+GT)<t3rBB(I+sW@z z5Eum$tqyYBx6skiId*oWyR(aVE<8_*pxH<!n>q5-v6)gy7Lz(68?Ra2(U&=u8%}VH zA&4Gy$e98pmufweBIRT~Nv5!5=$)0zZXbgAK?HfKR82!g_+iE#S-k%G>)-K?cVJYK zMKElV{J{~@AtF(L<P}HP^NI(83mE&vFniU-IXEkj&{?Q6?3Sa$>=AzW!yhJ1n-d_Q zhUL3vu>v-pUWn)MJ`=)J+W+eL%`-oWA7K91`5~0ui{k%!o^U@{(@zh$0p#$_3#3Ot zT8BHzq#54Gkj|nD(EULKm&<WIH*5eCOJIgWHlUr9i46n@Zm}TSCUgyijgFvMC?Ou# z_KhldWd<wgBl^MvbHi3x9}XiPY^=z|Xb^nK>H0|WK@y888^nr0GI<&rI&$BA_i>*G z8~Gpu<z^}dw!H3jufsALO!puD;UCO`DKj><Jir-42_VHaoHLJCHVfowtw9;Q5YOWQ z&-W|_<Cd@7<EVXZV#x>)*O}MZ3T8?^9bFaO^rp?vJ-d7Fkr&7Q?(F(?>!SJa*s0NR zP71`s<<3ezFm><uzuU39;|+J+9!(`@XD8zvF-pdte(b5ed-q+oe(kk8x6hPEYpEz> zbaHIGJ)Ep`$3xw*v13OE`Z^Px$*Ei+oC)Vk*<gEY<z;Jn`v=B{$2uzA!_%WL4IRJ) z@Rc`gFT~h+%VEJ!Ek0Z10`Jo&&OZ3;o^m2|{p)wemcf-!o(Rn3iwTh<oi4}~W`~X* zYFpYF?TTZHpVPyoa2+NcmnCVDpq3`$)k5Y!-TKl^XSF{8&Nwt<vZDD5R11sQX>kMi zJYO*TjlGx}hDj33JJ!DYj$gUy>f1-gkNo33Uwe7??$c+FWV$0g1HpJY$yuZFP(9KW ztwc*)o+%^^v(3#(YAIGRd?6C(T@^s}P+PHHs22j<{76Sl=W^ga8d#;`m>~%SM42~; zw(DwF9FWE9_ZE*;vn7z%IjS-L+rMClqXout8+Agc;&V0_+_N#L`REH2=p1wMMf7`H z;9KdAf!gqMIAEBt&=XL{$ta5!!N@Ss(TC8{NnF>WbB)v@jO2-(AJ{Z&Uo;xIv<-Ny zqcs^Y<x!E00c*ENFIJ1j6Y`1BoyKYQy$g3RjrE92!LiRqbwqHRu2Gjph~hdl25H1} z&7u5+nx9KSn|v-<DzDtao6S!5^>Fo5h?9cJWD0_t4rI<edn$iAi!wvDKC|)C)x9ga zbG1TuS7$+T9L(@5Efm?9cA!<lI$I}Ie6Cp}Ur>|eSr8b{>XuAdvcRg}@|L%-CjQD- zzVhi$e;S;IcJqWokdC3aBhw8A%vXjA(V_Bg72Xg|5Ke-mL*j7XpLfodzktCEh{ab5 zFu!<Si03({=<}j@V4mj!;SKDfVzmr%@AaHSny91nB~ZaR-tM3c(u>G9nhu5<PbT2O z_+ecJ!>Yt=Wzd+k8G(F77(o;ch|#=+bN&a^A`@mxWQOfn!1zS^#wPKTIDTeAJo!rF z(*-zh)<v=w4zTNFI3XLSwNodDUwGjKPMz^Y=FGIo(&SnmSTEc8SU+a30em1k_%6{& z_9Gwp2s;-{9}QTw_c=21y`AIrw~7CQ7w&oZ>i4(2y6F#LMVr3ZSM>?^VFW8|1NW}) z+0lF5@af^nvlGXMPA3A1WrKsOHmo~4F?wS7M7dt>=<aCi?m)F_d}N#}*Vr(A{;6k% zhtFQRdi|<Z%it*4>G41%%{2%J+#(#G;WFX=t`mobuH3q5dUQO|nVy)M=DPK+w#>F2 z+mF0(<m`*P5o2@tLZUsja`~#R{+=qFsa#6N6Nq)nGng?swfDIfIKhvGW9QP&<73A{ zi9{@wg7u=KQ<^QtLy>ZJc6j*o(q#i2-ob_gv;rLvuBX8+uvuWCO{`g3o-SBq#=`NK zvv4m^#@Za7^3{20G9eq6ebB{rM*wD1Q_-%~ecJ}Q)?f39H$J`Rk$?LB*B^c2zWoPI zwRgqZJL9!vv7WB954Lr8X3$tE6{gt8j792UtbRZc3KcAx<_gq4%=&%eSYTo#uxd%N zf-#bG*ZA1%(*9LDuDuBflDo5_QBL0vMS`f#(OciAMZM=x!$qO~89#Wf{8Q%1_+K!E z^NcY+`~`w}Q4Ai=h>0F1YMi#yBHpcl+0K@Dk10IMcCCJ;%K(!TBW3SL=J&jAGX`v_ zT1U>YSb7&aCiQUju?zQ2GMWWeEGS;{m0^AkP4U9#N-pFV$FdL(4>AMbk99Wb7-MGf zO~F%<L@JsB-P_x{um-@yGc;2jdiI6-<V+<|&h%ui*uEv&)gCI(#N*rzNeZf$2(aWx z%=EROk5-*M+r=4`%HJ#ue)^F;V<XdS7^5%E1|AC?Lil9Pi((Ot2U}doE)G9&0S3GH z$}3M^p~!E0+uP9Lg0CR7WZ_G)P<*IAnfi-C6m$N-#r%HA^T7B&HIr}Def}qZ$c6a5 z1o8Oc{bjol7;7;aisqtmXeeevJZT>q3QoooW=10e0Q=+#H?`&^E&%xXN?aS-_{~G^ z222R)lOQ1^MHEu7H8G!Xgi{4Ng;^21_=gW4=K5!>NV30RqGr-To^kcnSEH%NJsccM zgX5A5>F^|R_Al^oyv<BbdJOm#TV_6hztPO^Rmc0}5Api}@I>^QMmISM;qCxT4#P{j z6}T<ACbPD(qQtToijr!}AT{gDCwl@bk}1}lwOn>~s+glu*o8fP^7N?_!^`@YUcT-! ztbrXE+E)sf+6M+>nN%@f4wkCOQU{hUdH(5Vu|~oeE(I!BaYT||2o=)Z?VE495{<@L z4BUq5@nk%f<nr~v*z`oXP?`xu+T-c$*z~cN4|he{Hg4F^H_$sge){D@`vzC9&NyW( zEcI6M<$5fB;_y&*dV2MB*P?*VvcAZiN;U)I+yKX%!)mG@=Uh89m~J!doKK4dT0}Yp z0Q`(&reabXa1qcjudzEEjwGTTNQt*^zHR&F8>Y)#n{;+$?8FN%?tX6H?pn06Z~wl1 zBc~JTSbHW@VsTL|ad#o~sZ<TNB_jncunu4eE;@BGQOXr+$?kH#Fhx^WV%J}J!?w-W za>Embi!FOs20E2r$9<uAqNBpt3v`V&!F=co!Mypg{yPYHbrrW*V1l#*(bVL$gVvrB zLCdm;Xg<55tc>O53+CWr?g}tAPaNyBKGW0Vm~N#jF#sWsnW=TbJs$%mKuP<YQfP<{ zT<Bs97>xC5>PsAnlF%tCdobKl*5JYXAgW8C8$2`1WI5T%yt~Y8RL34a@RPr|FPN*J z4Nh-;{WUkf^Y!I;mAaMda65@KIW0ylwf1H0uI+<Bw8G4zQC_bAyyN%3HXtBO@i?2r zP+?Z3rkRX~l`C|gDiCfJvFJSgA&`DAO=A)U3=AZjPb7i|-T+hK38f}wLU_UetW;h} z%;P24^4b#K5_hq$7aQJ^?EKf3QrW9NaIqZyF#cGygS80_NXxLjdhfmWA}!$JDFhOz ztr@E`HcUidjOpT`wdn!^X>jX1{MKuP@Ciry=CQbh<Drl^*e6Vvr7fIe-@biFm@y%V z+8u0|Pk`aztQcKczkdB~x825immLT4B`?w>De|IVbSs)xfAJT8@zIZdlwM|<MG5&t zbaHXYyt2oGH27EjgaIo{8pb7Iqg!nPpEA7=C<bcA7+7S28;hb?oUiCsO`4OcK|dIw zY>#uvGPWa*4IRUFM|(W8YUwJ>Y)luYUOM$6M(9>;*bq&pi>UQhLkaYWW(z-g=;7YM zzRR!Lnl0sG?TD`e#n~(tCD`AMB~$UFrbp$fj=#e%v0Rejis(W$H<3NMZ)p7F*>x+{ zE$bgVGj`@w?$l&y>Y5vNX1Y4KCV@(%V##Wu^!P)Ml=Hbe?s$VPO5%Rucp#7D+3n-o zqTjlMTyScD=F=bUJ~qBuxIKZ#W3l`&nn+hU*iFMQS~0WAN<p)JI*ZYa7p^LuA#7D^ z4OA%yN-)=b$6q=$#0_cVCr%#O{oK>XjvZmvM-)UbSc@;ild+f{Pvvu5C{tQ@>9U@l zj%Xlp)s`JMUHAI+%P$WH;^k63#+IAmj^Pp6vR4i5)CQu8dV%g=Yz1r`aDk-+?6n#I zub891VCTuS1<YO@?iiv-KSZVG4d&AfvsF1@pr2&PFzkjtjP;p4=gO#<IuNCv#o^K9 zuhGXggl(beMR7STvI3?$Ua|4`YS+wH*vpK8jGV}yJ0Tq66B0suW2zJjrzAQnaW+1R znT-R_?MKHy8i;lDcW=CUa{#>rjxu5`rpzo+CFU4}hC1j^O&smvTm-54vTl^TCB%D$ zR>E<ir*LA3HIx@WU*Q2fJ?GV*5O2`>zY>=!6BkC}!9b4TE@S~0AqC^R1bWQgOBN5Y z{IBNs0zHohV<Fbyi+x=zyd`m7{g8ftOLmLBdMV70Yaxq;(_*v+O)Bai3Jnbnef6tf zg~QQGFknnMqPUCtF%Ho#yRA4r(OKk3-HC;VMBsvi6GB{`ywdD!#PZ3&=oh9zsK0T9 zj42l@T^6{;aarc_2}qI!0Z51JSm~mR$8lcD!1C8}v7`)P$Ov`<yCoL@e(l$Ojb0{@ ztjP;VqTpJp&#Q$1U>*bWo-KhbudfWInJ7?=NwR1ItU*nLU<`|g3=hr$OY)z~7s}Jc zR7a*#En$9xy0hFvpP9o*$z&T>OifMB9^A8ce0V(6(f|C3v)PH6OkYPKkwcb1TV<!Y zvm}h^*Gi$5jwgCpypD`?WAMBqT}7>$OPM(}gwP=sDumGDlCc^b+>>#NP?jYuGi)>@ z4({3C5o<@z|J2MA$@XM1S?pTYO|2O$Siz%}s^Kc#!~y+Hmu@5lG{|aP`CSVaxFQw? zEMg^0z<C4HUcIM<^Xj#pg?LZG4Uzm&T(X$zN1=)fd8FQ|4L#kAM?;3-qZAVHSv-z1 zjt&;loykaeYI^eWW!G(4aRW_Ws$oqJ{X6Uw$b<m>z_uE@6DaM_-XfNWx5KmOtc_2N z_jL?}0@3Vju```PxwNtHaYfbw#!*f!l)O4zm}gN2>~D?>OX^=Yl-0LoI9*^Pcwh^5 zfF`-LjrLPP0<gmvr<*_Vp%M9<j+>iW@m&jP(hwm7NYlv%EFl6sx6g&{ZV@XWScbO( zrfOa}m6StwufF2(O3IzTVjQ|c3kG2}M^UPQv&Tjb?%8+au3dpHuBi&3){kc9i33MD zm5oKWOE+)rTeU>G7N~6&F*6wtaQh&`#ub&s&>klT-q>rgyp)}frTNRoC+{oc9O}uy zhG-IKbQ}`Hs|bc;#>8DLI#FyGL+(94`FdH~0uH(i1wl`Tl%e%J$q0DAvnXWb#r3|n zg!o^*g82i9*z&qy$o#+sW6clrM{N1p^6EjJCmeo8FTnYz3oQfR#V9w+(8JD=0>sgp z4k`u%W*N$pUSsziKhc4~(WLYjO^qK&(xj>3G%!fCkx7#$A*_1oEWYvyNV<<FOqazj zJf6*6*1K?DPJ6?X_)5t^2A&iH59#A4FN#Wb08loYezBNlmCVyVk*wAFVxL|_zX!kn zm8>nK^+_XYP-re~pBz6{gYZGTgd@V}nZ+W>L^8!?dsR--NK?8}&2jA$_976L&K74f z={7b#*IstX+O-_qj8(a&u~Or>%yf9F$K80HE#%TEjB#-6z8dAk@Vd2yO5ynzpTFvw z?X`mLAi;iQMOTB;UfL$0^=M@BW&O>`eOAM)EMePdVD+ZEIQ5yI&ZRn%la=xALG7&5 zYY2NGD&wPL`(J*kueZB*N$>P*mK4yho}Dh2LYSxK^pC5pYCY$uxOMAXP}67OJPEL; zeX;iRLd>IijD!hp4#!f4{VrXKg_^v$u*3@WS}~{jzUGh2{A+>UwoZ6wDUTv4`z8tY z#}PPyZ%|e310%jeG{#EWkt;UhY7uS^t1s#3h6+OsGsy%-&4Evd30oJEDP2iR7!8%* zde;A>H2zo5zbFItApRTiELMSwEuIaw#bSB6oF9zn9wdGbSb<UtgiUH%t8;8}Zhfh5 zOxNfoIIs&By6|o*TESTtI`&EWjmR#3qw~~>{?65Vla(p~oC|3%Hf7o1{-o`I4M=c~ zk(hMIV(Am8M5$yf(n<(csqp-tJU#mSBTsimIyddSHo)njTwwnbFXkq4td~0mI@fO7 z$nqB!2V^ZqojBg?it1L<oOxu5*k}jPSY?#++6{k8@%UsR&~b<bgq6VoRmDM|`3emM zfIy3Dz=RXR(}t@*SpaZ+WgOzM-0?t1;1DFsnI#Ai;lSV_NBrhUu<2dkcd@S)Zg~;y z{9s<Xz|V&yWU+8BVoMhOMEw56;9H`5U@$@&6ZSy+(B_zLWUG}GDpt5rKV~DAr78km z*fURhia_FewKk6xz$*r+;rF+&mmTnYrH|+oIPU7zt65<$U%q_Jnl<oU7_faMx-oJ( zj=1EDhjJ2V-3J(cW(g$4BA6$)T`?`-D-Q9A<xV;{Qt&_R)gL0DCJvaV<<(2U^DGL$ zs!$`Nah;3XGt^jvrXwSW#G_T%SE&SZ#Yh%ns0x=b#yQ2u-JJzw(bNkCi%>E$fl>6f zcz4G#tuyPvOsWkPi^=SGN1_K?d@TPGF<q~T-bpNhK&sN#nOV7Z&D7o(ndNl%ce7nj zDQLGuILbA{bQopePS+apAoj#$=_!`26grpn^$rY@9A|^s`5d1bU6bhv#Y1_vUYYv_ z>iI(M_{n3*OmfBAl}xU=nKYS*U<{<ld8dRf4`s<=IKb2MkeBCo!OGo2=tm2&C!J;C z=E1N2bAblH^Z^ge5{goKD1~+(3`~Kd54@4Qw!uUfxSfKFE22@(t<me{QXUwN0;51E zQc^3aWw=zC`IAN>v^qAMFEPi&;t-co>xv|Vc${Ps?RG?xr+Lm@36a=^xCKW0g+%+= z!FY(<l7+QmOW><`{aL5)I!2EMmlfNA=Sa)3;T(^qX8~|s?q|SSdAeN$n>aRNXbaXk zKFV*eyeM6egr~Rdt0Xlql#}1RH(7g=h!Ae=*;tH{gi9825r#meD5g6bVWqmN2G~R; zaQsL6zW>#4aW~XmZ+*v#8`qYOm;cKbzFaGmP_?+?`YUgH$L)au);NL5QVF9ol}Z7l z0V)Pnw6c&Kj>H@Tp5F^zi082wl+y+bV+VQxYXpEmp62l500s;gH{?`18>NI3h+{OG z$C4$kd3Zvd`9u`b#}6bPOLIOj;r_T@B7V<;01F0svAnPTeEHfE?!9^uJ@}SS-mB;F zqWC@YzqW+HbeW?Ng_igD8H-3-$v7N*mjl*Z_J_n60WyAM2?&juC*g=fztF1iZ2Xj# zWw9+lMfl=zmZwld*e#+6mZ#`X;ef$R6>D4;&}2k(ASoDZo>(}_Lzj6Kv7Y4#Bo2>p zVqy`+z$_wlA&??@aY@!3A$S%H_dXfG{HF)tdAy`rJf?)j^ux$CD|aK`)=B_NVbMhQ zwR*WyL@%1^5H35*RLxy6!U0w;X6Bw;ZbM*ojNDq*0mU`ziFjmcdMuGla~IOgj5;nE zOO#RVEmt}_+9#$a4<0(S`jXY@Oa?AVpVlf8NZ?FH#qgw|n1T}$K@_c<GMs@H&Yp!h zeTM!ydq5RdiyZQ&@O1Rh!9&|NZ%HROB{3sYcd_tHekK%;Cficns|X`^$u|j(8>)nO zc#FsU_9S<|N8gNp`k1bDrG4UJQc@#?c{Qy{o56NtaWxuE$^wJ#W?jpO1`NGX!oeu$ z9>j^9LY#KvWO2EaPNLKupp~RP3(Y~*3S||Jh}F60iPDPdvICD!A!2o|NOCKz2GupB zu?{tnyH(l$v|9K>%>T;NWPY4~3wgyBpi5dAFyw+i&KxpjXP1Zb>5+P|T264*-ffd8 zO~(iMHPXVqMT|aYY)E>llWKCcKsjHICf%jzI>!_!m9-(~Uu`SYbA}z~1i9qFtuiN$ zv|nQRRr8fFH?C-ghh<vQ%~w)!3<jW)pQ!|oe*c9>zxCsZk*S{kr90p7ddvbGdh$8s zRORm2J3jIYU6*yrWIBfGxJ@JxE~CE%Un3nDFto0To3;$LH?M&IvL25<{*=YI*mM>f zkbd6aFVbT0ei*<1V#~7_{9@sYl?SG4j2U(d^Mmj~@+cS#*rqiQL>$p^&`nSmehh12 zg^jcWNCHWO5W<m2!<#7sshRSWrDiqtm(3sU|7tMvp9aHo!B6u837H>w{zSZDSVYUK zDW|k~b0Yyp1k9uH0%ve5DuYCpWa0cWlpUmw9KwkScjl7$6_tRDgir#O*&^1}jq?jG zYw1#wnx2BAKV%UI)kt2#*eh@(f;6jQ{>p+6^p28rxky1wPMb$$flr0eCxzp&^aa7< zS$6uNZlt61J%(gS5n`_8wHd5@Eo<}GldoWf7vl3Ht3!0J85z<7_@>U5uwljpf(<1W z#bPGWi~>z!dO?WHC_(*nh?$zgzfln3o2sT0AAEIEOt^YNt%lf+>MDx$j@HMNinh{I z4{a0b$F=cdwF7|i2(Iajs5jsK?f0i|0oPBoaf7WXL7{1_AnepmE>GB+*i!|2G;<j? z`$cFAyiO=7qIECaw~A6BFwApf(Nl*{cK7upG6~Xl+*g1X<z$8y@g12}YGcD=EYrIN zdU$m*8&_o12=!U0&oeibD^7FnK3*EjKl{K_W5XknnNqSXzH;3qU8}jhEWpMv=GtT7 zXi?VnO3`qViV{_|wko+s5#)c5u4P=k>MFu`7L0qIA-y2{V&z#Zo!1JU#VfoJZpuu8 zyhzp@SZd6e3W8C5GL}i8i5#efVH!_(EdVfb<G!SThs7%_*<h^7^Xsx$h=u!~UZb@H zdW^g!oHF<`wXX{%;(hX`;00<Ein@C-od=HS@>OsH(o`=Q-dGV3gM)HwBBKQ|4j$<| zf^X6dd>9?z^o7){9m~|Bw)vGr*aGEHhDC=#R`i0J79t%L!lmibx4cZOsxNX@DmRw3 z;si%22WgUoMJFGdLrC%26$P8SK<YGzbC!btY2p5__zl23*5>xKaQrxMz&w<~El;&i z2H$4_LV?6dX&fzE<$#4JLWsmeRRJ0Z7OhVh(WLUyI^#?`O--BAge+wg!*u|23y7EA z;k&YjsT9<EKsw^=XgjskpKC@zp4U+k<<fNj#(<kG@f!Vt$F6nhG`U7^Fmr^}V%mXs z4*QjI(Y_RD3XXarnwI?Oc#~Z-(NtIS1fN+t7i+tBKQo)pEnTq;+(7CYMwy~o;XE;T zVMx(PY91!I01a}=R+Xw^81V~!R4aEsv-_qSZt7g#1CJL3`I!|3v&~%(aJ@H^#w1$M z)$r8uQB)7Rlbxk{W!<uswG)L<l7%zIiL$v^IkUDOGqT)CMs_5QVy6vp>SHB*B@}HG z|DWf_KN$Xba<p7LLerAzV&z#Ze6e&|lJ#CMHXT31^Af?cSiZK*h099N=OZ*0mk=Vt zZ0t!OJQY8=uwTe40Mc-Aa&MR}>97e+p!xCOEGeG;GAtHuzy|4uUo5-@(jUe1`#t3A zfAuHZ;x{nv;vsyFG3rIDRrggRPaCier{RK<G0$ce&Fx09zXq6#YD1m%D~B541a8XA z7$=(6wMvdvEE+|+cisXKRsjeXLAj!lT_X{_iTkQBj?Wqs7o&xBpe1eGU0g}}PI@}X zM#+^vT}-H3J=;xM=GO=3lx}kep&8ap#Ki)@gT!O6Jgt{`np69T7s|O6uxgGUK<tq4 zl_MFFKkEsbmGTERHdF`ER(Kzk*Ya8M)k<QGfbd`IXSaK;D~%;NP$`W2@>P&36+RbD zeX7<`654OHrsM6E-M=y5S8k(M3n9E|u;Y4Q_oFYII&>m1TP_ufeM`G`-f>H)D~ja9 zuz7wKAO?$6r_85YYA}jsYE77_dwKtX>u$JSvrzT5h7UM#5q&OXVHq8(6tFLt1Y1@t zTd{A?z8~Fp|IfYk=VRSbp{~%2B$@10&^aIi;zX`2ij=w48@+z)%K{e3XJ?*x;L(R3 zeISCJEA*ce<rQ1kZST7=+SSHH*s9ME6;5i|FQ-zwSNHbM_po6+KR-8|<_G_)33;u` zf3fK-2JewezX!j!vL~W3bqisk%u1K_G0xJ20Rs;Y20&UoZbKA$O^B_kt#5$wm%;A` zz;d78i}S-<LP*CS;`xnXc&`g);s5HD#~-NjIK~M(ggZ7kpZjH)G@XXBv0(<Gj>3qt zt5~)wV_=e|o6TAz#}^#iMt~(F(=Z-jwJ9Z0GrK{+IfDdfON(EUEUF&R9y6Eggr~-3 zRRlX0C0Vj9)Ek^$rG)=uf1g~uN~t7TGB(&PuX4uv9b*p01iY9dJDZIefW7kM)t-Kj z*EIw-o0s*wnu}M8;JB>3pp0&Vpdn~zcrNWH^G8r34tpU;gaI=<6z9fX1AaqD7qO8D zl@;ERcugD0YI&R<DwtP5Wi2^2zhtL%IYoa(`ev09u$EN+=6)6}0Pd=Jn+`iF#mdy^ z)bYKCFs;6R(<L|Dazn5Kag-;xXhI5A97-9MTX)mBSZ)u6j_f=7)Z<Uxbn8v4H?Ee> zaZGyEs4a4nnc`fiGgz?BQ2=JriSVtr-unH2`rbqL|Nrd02b>khk;mUJht2GgLF5bq z2_%G2vZ7^M&hg}v6)Y$De4o3&?|lAS4rkpt`_AG1KA)2$2g$N62W2ZuNJ0q&h%8ug zTv#@}oc`bHdT)4afL&P30@FNZdwQySdTMIw*HxXKzU-<i@FZ*CvVO^Y-K-_UzzaV^ z66j~4QRwl+(~OAm$D7;pk;1OlJ*L8Y=EY~toHM7Qy2dun<@>WYkmn(;z0`cYV6YqX z^Xtk7{W!a(_mt9K<@8j3U(+#syUl{0rK<XLPMlNd0a{g^;47EtAr{fJJ;4-(?aL86 z7-EKNk<Kaco*rE9?%b=KtfyS0Yc7uE^iCp?avDwVn&Qy+bR%1iV4!sft1{<ticciS zDhgapTlq>jWl>wJ-!079YJxQ4r6MlnKxIE?Y)<foRn}?ZGD6D&Fm$r41}%B(ET&6| z#ec+y$}NFK0GK;llZ{eHS8$OC=M-xZRMipZT;;9|sN)l+4y0%+fpl&p);0%8l^_I4 zV{1=}1GGd+RF<^tl9F}0szjQLOU~6&TpISgH3F12E(U|`)dk(zy#oNo)MrOW8VhuM zvt>+{2;`DQAX<L506CD8AT1o-M?%^w_M-J}+nDeII$Hq>k%yIxgwg{QPc4PUOLaSl z3YyaW*J3lehhyV_2m>%|A+})VT{vfA!?@?uPj6heHe>>Jfhb!(@3Hh!Bu7~Q@8nyt zlY6{j*0V4#zp$8@7*l6VlXOPHvs4RZG4`=6S1+TO*Nkdp<^e6kLM$Js4xc%5_I>x= zH*Mn75z|M@fWJKUH&SLlK%T?He1@opg(R6WXNN9ele2IgQs0q?4;wXl;=Cy{E}UI8 zp`ORVs9{QB34f)sC>4E57294`vLDIHKZ$-Uw%?2Dsh;||_WSMny+EyJd2RKH6gWHG zPRRgZ)GJ54ETAtDhFr0{^DD2s!lE2pnlNF)rI%jHcxez?%PB9vQ<<FV)vlcEn$lC= zuIatWTb`?j8ltMzb7h;Mtc#9%w-)fhyw;>csRL|yOWF7j`&GUjB^K-y+M;=?*;r#v z&`yAj&0n}qca-9#e7+#2m}%As2A6<J=$PPSCm&(&g17{3Va-LN-OtpgY=I~K*#JFl z1wmhes02o5*+zp!U()5#q^rvk2$2NdCP&ikS@EEW97)%>UU1@4jvZ1^o>Ala)WSu< zNvCaZ8!@(r8XMQvlNU%WW%Ieb^cKrXECgPI9Br@(HeMXGWvyPZ?+LO%K2(%pe-fnv zT%f9!6=1M7EQ-wwE<w;KKuk*cB^Q7@vFP}mia46u>KdFMIFnf>rr0yn`5np2(}3{d zg%<4M)3Wb!!^*V>_8nkvH4^jjoVSt@fZ`)YHZX#H0TDj(_Y&b`6c~luE?*IdycsiP z{28N0zrN(P5hI3}LCm1H0~~D4!B5(cu@qDJvr$i!N$l)NjTxNF$Yx%Fn!v1c=gz+J zTr;%jQV9mw)VlN}h%C$JcYe~+Rrl}l;XwIEUVaBv0p%$g?}@%EWp7fP()4y5=^F-F zNmo5f+$o1R>XlP<I}>N~qC4)mgFO`{PMiq+6Hh$Bl1w+>d^2OaG?!C8r(KnrQ}VGy z%5OnATJ7=zm7rUGa;a;&B+8F6_+KQj?oCNjSS2F17e@=aj2j8r4^TL&(%}FAKmbWZ zK~ybHn~`fmfR)RUAmE2uw`s)1l*70syBNe6s{pXT1_(_eFf1nmCUgpjaU2wLS=5F= zroF&Hvgw(q6fRh7;SbiN^-D{Q?Kmg?0&g@CP!?cG@u|f|7rYmX8Dy5^LxRn9Fa_Q^ zCknLAsa}E}`EhbN^m=!x9nT}!CeI+-7Ycv0-6AG1r}CdB2&|(?!xM{RK#18{UcuLb zt1wSI(sJZo2~rX)%LJ;qFBfb&92Bcp8Xg?1va=EU;v_|$SyPA;%Hx`%M;Cz0xpAy< zUa6XTKANjYwa9JJ0+v$-9Vc^zB*PC$lrIc=z5zK}*?~j@;%|Fm<nzQ@79%)sHm+_Q z6sfMPsivXHRG%b!fmJe{!zAMwHc7CuXLE~O*+5>AgyI!Bvv-p5ek97aN^D3<%*#gI zLKHS^AoJ|~f6ZTTv9~6K*M`yh3=fpSUs;o3CSfwos<Tz0DyDmKUr!jDJY6xg=DaH} z7<J(^7UJLm>2re2E)!$R<W9B@2P+{p8bHB*xBXC`o<6X?7Tr^Q`m6l@DyOIC5+!AW z66ozXqTn=zi1Um@pa+0;z%yiY`m({%*T4StkA3W8H{EoTPE5M>)?4qn=N@)(W+e?R z#3`XuHM*udDOwYUUeh}za<x3AJnq!rDM5*y@||?eRi4)=76`B!0^QH|ufrr@hm%zz zrHrskJk_E;L@(%9#96U9E<KtA7|4MZu6)~45=bQ4gNx!9l?FCHQXmnf!~G?nwCw?4 zGN4@`lT4(GQj*+qKXqf<yKxKhS&bzs&E8mYDP{`?h+6{5D9;A1G%4i1_5_;pU@I<< zO`?OQN&wK7Q|eV)AGxhV@1z5BBs_g%cxAz|c5K_WZQHhOn-fhkv2AOTiEZ1qZ9Dn) zx%Zy$|9-lAch{=btLjB6=4h8Ss+LY0KNy>c6<n`_wN^Ny_&U{cHxe!6LQae^DAF92 zu}*3<tYw_m+Ft~FiiK>m@(d~_+%y4GgThcv=|Aa|9yU^fIm?ps^a%vSP9olsu)PSn z@5I5yEZBcM{<@8^9AOeNTygvk8oLg68a*_TOD=KEqwhcpxI?J($jqmeXWp(rd_gw+ zjZj6xO-q1hkqIg1YWh)n6yxaqfUY82N=7V&eo0DGQg2hZ8Ojpxc`Xhf&ZG_W2uI_i zlCNojSj+24rB}O5od@Y1s=~T|u5dD<h}-kNckVt@lg(jMu-Y1qe<ggnPZ9qD`9Q}( z`eDWbM~f*%30v1YJ36#t$ZfTWq{@gWWlo*i6*Xv+Ha`&@&cuo9R8V{aAu|M_<NrRM z<`7ibi9|5#Edd#Q$0u4;hA8k#1nXa0lTgSg>sM<|Mic{!<5h}_B~$kMKCwgohQ9=( zWWB+*b0G#nRLLMXX+j$9bb%;P1gUC2=uio+a;gsjT>LMO%*r@bXf%;fIkPWXgKTZE z-Y2FcbvFI4{bs%|CTT=hd?5x0UmcqMU&YDRv=%=)<jU=SqtMSxXCQZ{RrBQ*)iHcE z)kIcO#_z9N1k#H{EsY^hGSGjF8e-{{Hjm1Ysm4m2V|9YNG?K}s3&Q3_kjl}~e^($L z(nN`U8HY$E1)<ZuMNz{elPY3!();fg8iDT#Tf0cjFv;jD)V*6<!88Ec++~B>yD_9M zDM=(hT(mAi3rCv}P<lWN%teCV_X0uNM4vZIV_kPKx*Rv_O{B}){V0D2!s4(o{?+^~ z$5IwdZ?WXnhKDWDRg`DAj4Cu)Juom}6~$JaENZIOH{g=?Zg8C0&ZnGJ(q$Ytezoa@ zGi|KF97G4k%;e8{0q8-H<3X{E6RBb2@p}4jBs_|VR4oec0R{A8raI2~$cgQ(327wA z?F*xto!tu+d!Gm_SVUK4&;%0fX6`f+SmCPdAng!3$~I~sRtv=2JZnO3e<ygV$ywj- z*DM!WG2hCoWM2`@4TeY}%W}5jas39Zw6F6O(s)GP>ZPj&KmFdv>@j*>YIQ#7-Mabp z(t%|3P4iBW_+!S4>~=}vrr<t`me(=nEH&SEnOVn&Nv&Yos>)+t{?JYr;N7O7tp$Ei zOi)bbxQ1B`&nPYyj(-W<c*r2hQ;B6I5##Env@AV0`0p%7<+c*fMO9a^0wr>KSqvTR zsij@jt!i~_ev7u-&e`Aqy#?EBjS-p;d>#KnuX6$I-!D9d(-71-UYLsQ;0Ffb8X9KI z0yp4R*rZruU_wc-(Z~$>C=CYxqopqVYEz0hYylIi;zASCgX0xW#+aIQ{3oywcVl;T z$<Hdu@vnREV;%^zxPG_scnhr_`Aj`-Y~{Y4=(RRmUfXtwKb+y%F?ZwNYx~-DTH}9b zvZ^nddmi^`sVX8+DQabpGu3IaxOmL_w9RUuMiu@>pC)F_lbeiKOKrp@+HWAWHGEst zP+sEmxx6+HU!9o+FYS_J{#1L%_-t-A7BT4DK!bC%TxNT3Pd+f_5oRdgz-5#^K=iqo zMfo{6aXX12lz*EbBw{fv<4;{n0A1yHZbxin>}g&Ch^8}s7MH7aXy9-!Y~%0YoG#Gs zp`d?$dY^2#LEL4W8LS7nQRcWxgNJ$X6X4GkNfQ30jjN7Bv%zZSSbFY@H9AbAB0KLN zJt~ou=mfcd#3W5G-J9fe9wC!^IGl?C0{mp2c?3BTq2cOnNtQ6cVPd)3(tz)$kd^^H zwyN-s?V`W!B2VvOeY(ugZ4JT>k$Lbn4ArOtzff$)uJ5-u@#{b6<q)$Dv%{*0l(JRx z2AOr^^bBD?YLMCG6I~{H-YmlJ1%FqInXG`NHYCdp*C<RzgXeKu)#+^UABVo1vHIWC z52CF__?1|eJT-8sjWN3GK~Uu~q#wT!37h?fY=(8g{V@XR+i};Pc`jf-)*I}*$48SJ zEDfBdN(v&3@0t(bS{fu@UDPsU>Hu3g%ZrfT1Jz3-nT&Q&EAUu=SO?5>IuV@A*z?Jv z-#;Vx^I7xji57zD6MnWuZ{YbFS^<Ful9)%mrDn$W)#cG<g+=<zO<FOhNTSi<C}Qvl z?QXX+*TqdCA~}yH$aSf}Ggn8ok&1Gzf+^u1NcgQ{m>u)T>bF>#T#W5M1+dK1Lw72D zAdTF|1!Q9Gc-^McrQ>0J(sNvfo@{!ULKE>|6>L_YeQevJf-m39BI=86@C_zuXBJC& zJ42U?X8i;tTn7y?ts!T!jq7#UQ9N5_OFn!0>gZmS-lYDjyK%z^X~>6vR~`HE)eRB~ z@zcl2(#@16_;+`7Dc}|lal)gYWe&U>T1;K{lL^XUcuuzWi8PYHuGa8qd_hv><lA$( zQX0muGI0_3tJ$)iWV(FH8i9!Nf|kqNn)HvcD3HmLKAGlVkf*fl4ZwWIj@~kN!5<?> zLYN5o5rOLZQ6W)u*i#;V07`os@|;_P1dT!fq|bJT+u8g{t}ns_me;jPU=|Y**Y0kN zDz5zAmrbMu9t-7Go6fHYE-*Z31Yl(Oz49;?Y6KwK646~G+MryQ#eB0t_Oxx;zlV72 zg%aR*_d*gUY6m)(%6R%f0x+fc46-&e-^cn>#E$7#QgZTYpDo5!dK_dg5|y+<G>h_N zIOvG1C=g-jat9N*&&|#C4*aWY^NlU>G6pU~;O+~5bgjh1%y`f2c(j#S^=kE^4K_Rr znrclUPSu`E?-jRyZlhUe@C2@-$CUvtsV5y5m9!<lv(K!qR=dr0eFFS05|`{QJ&nJ3 z&m~sIER{dmge>wkLC|5=wpN;;sbdtbM};orK7|U|2}g6>`##$=8Iyr$;J_L}+D^a4 zG4NyK6I55wJh1j9e8zwWZ!#=%-vDsjaf2Q>-&~sk-<=Nw59#;ymF{5#*?h+Nqeu<L zx3!3>Pg43Gu#E}D587+AzsM)o3WL&=`(z&Nyk`pB)8z8bv7?~QOPaGto(k;OcsVF| zEHTMtwwo1*$dG|;gVe&L3hflBc|4(~CHK*QpC6ur)ZQ2G#NxJGhL_!|&(R<PMcXZm zP1KT=?qfIfyb1a84Fh?e#id{i)K9xq)rB_Y%<usaB9^fr)t+=~caNlqf^Vk>j`;8Y zZk0N?qv1j<9kQyB$iQ`AwUp*!vkSE#=40>#TsF(=9ILb%JS|m8@+t{fFV8&<52|5d zx@O3DOg^5kUnu1&N%s&Z<S53-39RJQn*xP($Yjm_lAstbFdxId2N|&2`cqs@XdwK} z<@bMXTyq8U4>IUsqaU4?A(+Rt&nm>j&q#{;PqrjOV5-%|EEs(5`nc}6X}@4-#<Q># zZ3Z5uJ3ilRbCrz6<2D_J<1jT6T22^utsyi-paOYvL!4D$#LtDpArI`<9lsZ&Uyyco zC_s)?nAHUxE*82eMy0N)%{^DA>_UxE7433dDGF(offnYTGDdldm66*7H!_#%!C%|t z9#RXDE1jPKi2PsIM<H+3Jl>dGB2*C8+dA@LC<YowH-UC>T&*^Gj~qv2tbtg8v${-= zj^R@BHN0X!tK;i)_RWB3kxg)<fv5JwQ%lr)HM~}Xi&5|N8%>Q0JNkdH(@I8fH``0n z;Rl$C9)tw6-T1HkB8sHtb%cn+;qe+&n!Fg=*l4*~3su~hhC_2pweF7YLE%cfe@#=g z?8@-V)mOXPm3}_8coI}3tGykM8dk_~Pzr>bY_VW|vFQ9Iv^k3sFZEjse4<G$nezHB z91qCf-9?!VXK2!Vbcw!Y6XcylR?nnkZNst0e>$7{B->Ttjjfmz;{qic34yD19(^YJ zohk+;dBJv5I;cClw6j;iS%LkOUP<hf@Ct-hpBt*T*lG;N+2&|<Rv}Vi-1cbkiV4|; zTRWV~xlBvm8O9TMbx$rpY_%l6fB_e-SiU>Nz_2!gc%;+Wh{dt;v%pLjQV7!m77S#V zvf-{WxQGJbgsL2B{Wv`<*@W@Ji=~hIVabf3Yh*`Bu-JSD*crWn3LSQ}?k;_olD|82 zIfl3YTgpo0>+%kBDi*hy=3el7HLTi^?Pd!VpZVXaq8%Z^hOS2IfdW(uo{-+LfH?@u z+bTn)I@8t1vn1#@)CbvcbeRN%7Bg|B&0sza2kl|(Y*6>|ep8cC{bJwlXetLHqJfhs z1EkL`&_nDky{p;bL(_^u6mqBEn@b~Q@XF%iAe>P%#pmXUfTpJA$e~dV_NJ(`!~L97 z@0*2hMjNWbQ}W-MA)ZJ6lp7?ck$WzeerxYYjWJ*yg^7bBbcUXlJ>XWpwC#)A5f>jy z0|V)kWd<PL&$GPId}GmbNrbhHR`z6trfa*3ipnOZP&6z>7R*OTp#?PxdlVK97_Kar z<!IvpT$?aN^!Vd6CVYJRs!(3HQzbd842-ypi--Ct8`dl!mI$a0ZM<Q+4HB=dX7>-r z0Qa;R%+FK7&!UREOc_<yE@Qoebba{^8!c8?m?n)e6MOUb{I$X;V-+^Aj8I3-wS<aO zlfopB(gyG(X7&_xo?Y3nG8I@IU_H{^mth%<i<}A%lgJmul}!}|O@z}{nnkLF766fS zvdDBv8p0r`@A3OTEFXc3ss=Z3nORIucEbL%ahjL5jy)mn$`r%pN0(D~rWs;d#j^^$ zKU$;++GXLc=d+$NXKpYVrL91hPE`RU=tZ3kGdT|`zP1lR$4wU+GkHGUbnZ*J9N07O z=zlY_o{wNA%^yoQ4*Kw-9Gw>YrfU0K9D(LdmjMPrt>zB^-OK4P2x&AWus0fh_<=Ax zgC#4ShSKR9NWry0U^=-n&YSgZ6x*)Pd(NzIO?U@~6#~aRHhY()S)4mc$kj4V#tDg# z%?h}OgkF1$mi~`w;SrUn1uV9ytmD)#^ppf8{T#RkkQ-1tx2aZ|i~t1w7+`o6=MF0c z<aF7yYr`~9|9zlY*yVi#3V^B4=flhhY&AKTXi>)ZUup+Jr#vrT78Fl#8vjU_TDpLL zq&yqr%&mN;ir}dWNH=236+Y7ysLDPkjjGl@I=_~{cOA6d8Y2ReS0=MLxzp?duGhq) zaswzbtnoDrb&+GM3_6T=mcOh$24D_xJ?(9McNH6WEEKqX>nZVim-NCd`GtSpPc-O# zj@vl9&g4<2a|cf8cjLELkyOJzOO0QRFu3e@R@B&iyk;qLdcYLfxZFOmQKz#F*jrP< znd_(4%p@<LjwU>AHr(Gf{xL26(r!w|AL~_!Rwv}(oUk6nvY|7amqDVls0uaC=wEDg zpNMCb$dC!rttG_iIHwCRH%IDlh;=u1UGu4XyD+I`>VuaY0-n|U2#i3Y0`+7=iApR) z#8QLscQ24B1;1GSE$L3ksruuTkH<GIdkLm?l-3^e(v+Qh+CksRr_Ab6ZLpGjucy!n zs6g|$$=tZfC>JNE6@}7f0KVJ*evpDRGatA0O}1HF|JFXhZDGG&ZMMF8&!LJPvz*Rl zTiU7Xa^G0icXsU8y?TO#4eo|BvG}7@({dNubdgr$y8xaRo5wpvb_?SxSB<I5oiHWY zx!qS321lUL)8u>*O&ubvAwg{kq+a6*5ahBntT&oz){px<EAZnP;YouJIj5LPR}!=~ zn+_?-K7fb@O>#HKh7BV-<a;CY6~XGkFUnzHiX5kutqb|bz0h3d{_(x#%9w7L?PSL( zSHEq^Ksz0Lh$92!@JA>OWvhn)@_iDxom)w<GHwy`3JsVnNr8m=yvl>24LJ?;&t708 zDp;i7^qFxz-nR;)tWx~|l4tuN$nD<RFE-69pUv*dIrj$2nVg&q+KHTl2l*qp-!Y(5 zbQtX>bj%nQ^;5-(6k20WWjTL29ksi>zc1fHPNL12WBheJ%|qIZ8%CsdX#K0BmvHd# zSsfN5)hEgfSvFMlhaB*tV-mX$g`7U4p)I3vZB4iZH#i0tN@+%=tb0@C1+=nhl4QZV zJfN+fy^T;<lx8@P=uVAuHX1R^R3XCHL93h_%qN<q^q<11O-p>57c^5xQ7l`ILarK* zja#LHUx(ShtkMsUow<qd;=2)RF#lp=X|$3jsH@fa)J4x}6!T`gq!qepG0&3ZI30yA zUDzNK2*@fP5!PiZVB`D9-?;g>xpTGa=>XrcwHNGg?T%UUNh^ZO%4C8}Km-Q&Wka)8 zaHK`1<3(wR$^QfJ3H8N0$7d8Ih<1)waPxe2Bj%op3Ued*qdd);M-2V;N<?@lb4FO$ zbUgS$l*;7t#=AGNUasTuOHifZmXRJJSm*hN%gqDq<B_#2tdwT?fi@{YsT%zlM!hUV zSR8d=tB7Kdv#*TiXp<C!swX9yL4aa0<O<2_j0eK3AC6zceixW7ki}~*M_EvD+{%F^ z>BehM4<eOnU=)}5{pXXO2I2HnwMsW|c`k)3ug_>$oc9zKYk~YSn_#JWQ;rfCGCs&b zR8jpVHGPnDo;E1yEBsNXRCI^hCH+#L(b_;>aJBtX=A`s71vC)NR)0@m+6*-aNca4B zO(m^@ugYfc;T?dlkY-8<H^LTRfA*(nwmoPb$@OB}p6@;#veaJB=)99FtYjDu*2p)a zNilu^{af6LuKFh~i`#o{A2Tct7yVzA8dfrTE_MPO+dCXCy0|ULnO+bATL91}7<q|m zbyu7F!9~nB!c6LMj=cR;O^pHaPP~BacC=Nwibv<*_%zz-m%TlIt^LR{?6x0rNL!;X zXOi(M$8#M}4eEFy0|c+0GpXblFcZ3&IJxon{BrVf>6SAvtX5ryY&vxyGp7^%ZqecW zSq?n13)bw?p}PuRrb5E~rB8(_3^^Bdjtp(jqW!i5&mZ2cZT>4%$f_o)FxoaConW~Q z<0RTQRWOzqCYp>R0DHWS9$(f175lRTj@@Dpw!Q09c<1#@^*4^L_J`3Kr9#lm+s@~` zCLNsHSc)dd%rX!<YwDdcOXGOtT3;51?e3M;wbgb5;~c@ugvMY{mEkdpVu7CxT0dv5 zIcIpOJTF1#O`kXH@r)jm?zOLyiENy4UZ@-WjzAhkn`9a&1Ed~8_9osbSav|eA7|iK z$Kms92e8bbVIMTpCbV8b6xno|is)h!%_=?Pk$3tF&6<izfNI5$o}${MVX7xYExz9G zWs@#?8A(lK^U>6;-9&;TlHZZ=3}<**EjQk0C28ju7c*U61#mq)gQHDHt&smWXFDF3 zGSFpvzG9<XP<>TZ-*3b0(LwWiL?o*z0|k2|y3{%qG9L+f?2-K0(&I1g_H=rYgC^Q} z_jgm-#Ed~b#NbNu3-!9pT>ZPrQKfS&9%Wvy**4f|)HwIE(i|99MSX-;JSXm5m;3<k zU7g;qi5Y=Z2n-rL7dpxA`c^$>1@1l<`gA+Gs~R{Ktf+4T3GF)l8apm67;#uFnP-@M zfQv&DpTJG$Ba$mkxxDi7r9$(BOJI8cm=}p2Hg_>a3Cn*HrQZKcGTVda1l$_%wl*>^ zB<U`kgcyCOw$iQQ*%;D6o}S7)#ud}2z_4b>lLQa(1=FiQ=*kUbyTdw^q%ONelgLY; zC_!qDTP0F3^n6FG=kmYX19$>q5b)TtVo4gZj<mRecJCk_CGpY+-|W76wf-5^h0Pn< z(qG^{FbQRbl9+=d_Q}UVK3-9HnaLW$ZB<?E6J38|IpasL2uC{WzZMQX(39rb<F`|f z$h!cxr1vOrBIx@#5VrSgYOXt#lEQK95lqf}LxfsHZ?Jh`S=g{PNt_vsf?kAmggPhH zyoC6fDW&`bD71=FO(NcshMBbxN-mLRw0`yxRkY7;f`x|j{C@@oP6HiD0A&ColstYe zwaU5FDqg(S_TArg@Ft$mn6S~&uG10SGa{lgJzYPj6SW?n8Q)sMn$7RBE9ia41r8v} zkO>|a<GMG6rO2`OmiqNF2v{g!Oa{nUM958n-GhM@Q>rH2)2j-;NfY?>L>?~Sisb1X z1@P3YeseX2Mf)V~DkswaJr%B4Jf|{Ze92>in?n3Y{?C}$->rXUt_<A&`~MI6fmc8T z80`3eg?g}9=HR;9evGR-bH9+cI&EP(v^D<UFg6H}%DjY6{+rQXgF!BSi(Di3gTLD2 zbff=wVR{I7h6t?~w|7U5j50SRq-~hw_+)4E|N5OEN_<`Uw8C*+|Nn%eK@6GiT-y`$ z?}N@lX$6;iql*;z+HsWsBCm7)H(H&1oO|(qyQ6g9ID7<kv=;Cx8(S@`pFe9&gIKjE ztNq%F>G+?R?mZIvaq0!%-M&-KY56nnA;QH#(}|qGPCCJ8YO=1ZBJQ;y3*shu6mY$q z;b*nA$@<@*!rBEy>Z=svXrD5r3BA}fkfOY+lA7XPMI4z%;381h%Awy-7or(9?J3<m z#!sa6`cI$6gHc`N*A@XHO53p`H{)jO|D6aWWNg&AU@rQ1RvLV)doYVp(h~`6JxQ@X zno2AJVH=fK)$U{jM9r9v7=`w18j%><Bq8PB;ztgvl<_#paczYS>gkFHUKQqR_x~>L zl<+@0x%UdCQHf9c@q$070GrD}*h)UZbfFmD1yrpUR%2#SV*ZOmoRb-)mRuipH#nGa zZR>yI84xCA*pPZa0{yU>RbW&RP|G@6DMf|lMrGMnw=#vb$pnT>S+L+9yX*$y&T!_w z)oS5~%3#Zz*K_}kF$GeDRv^FMY4A2Q$0C$cy6c<U7OJP_mSE7{YYQ_obykR&_XLW- z-xl)Aww=TWm<FIjI(TAeR}lYQKbJoDF5nup-5HWd9^QoIXN6D~WM8Y{vhBD!m)4kl zXEyZylpa5l#|kbe&Nchj+buzgGN1zQrRKk(l#TG8)2VgT4&+318h2>Npmt{7;P)j@ zD}7sy(VQlFdWRwKKpTXb&PrY>K4Sc3+p}VLTQQPZH|vIiy4w+ll@Z>CW#_$5@V{xv zNyixwBLm$Iy^TZ~Rq*qMe{=dc`ed`i<Jf}C`>cQE`faDlW~faTqf#Vse&<&V!&vnA z3ND%fR|{KF&ys?-_x=B^QABuML)yN0I(FgCn@LkB+v`7w6EvVgV`$wC&dkIiL2{CA zD>91^BSDEUYtWwOCqP8*x!U=i=*5IZR&OztIaef!dV(U%N<(g*cu{QJB8LmY2<{DT zdt^zkDZjj@e$QqAysI{RcwZgI*L0B}N&A9dKAz#fv<Ln3WX?(#d?kB(6m5u<6QsRe z)f5T(511~RI}<5th=zuy*>R`aYOXMWRMNm}FEmz<*c6N&?T%t!iby0&rlfz5DS{?G zoL1a^quCx%_lDvK1(1_NV@nkrau=dOPvsi3WmY25X$`!OQfU9Rf-Id-Nfbxr^B`rA z1-m7HgSc43NGh;q$Ppn4AyA_#M~@t+tE-n`^D1_X44L{M!Fqo=cHRvKe4hk#19U4L zY-~gj#%ua<lhX<royj6d%Vvcl7(^F{waA)VT6SD#_|fW3M-WEi1w(HYN`$#@K?l;K zBK0oLcmK5~2C4swoVX>$V-j}k)eRrqpOQ^&>TX?ZvCfh%MQbVns=t^?Dg*kpj6v{f zhZW8aMmMKd(+w~x{My<fZj{0-t6U5xjlq!;YeLp+JxVNOjDVul^lpxgjScvD3HW&| z6O7?Q)qBJbzws4XhK?zFudc4X`uV>3acDbA75v;oTvR)Xl!eNzlyM_ME=D*LfwF$E zh8fH*6jAOO-EMck_}BHk-f`Uy`$+x~=x5cU@-++$Y;?koT2ocE7?z$1a`YlB#zme3 z6<nBxL_G*aeOR6u>n3-?+4DAq%VGCg^YhL~MXeMuaZ^GK`WfzEVN(;Ums-hlD~&g6 zjt`$F{UNvMsPk1iWVs$fp_>rbZMv5}v!muY{aUJLE4v?PHW6_}J7JnY8$a_7OAXs4 zKGF|#(jQnwAQWX|Yi}=pKC4&R&qeYFFNcQouM!RLV=-y`m>CKaMS^O$G$D`M>6&HU z*C49m=i5vGMGl<;w8P+0?;dylJN!_%9<igBIT8&>yRvxf<!Ba6N-#6^oK<oWMIth~ zOty#xpl)R~n-8$<8)@~xoAP^wY1LFTKnO?ws}dZJBpFx>!GwI9L?k+`PGYl#A}orm z=^M-?@vvO23%uq1aO@m;@*Ctot%Cp9&-A=6)oj0Xzv#Qoi64^W(>BTR^GnAv^+m0$ z2A5bloxL^*QhXGa39Hu?Tn7H-Bg~Xu0f#B2na#B4?6cFiFNpw?<1q&zW=|dy5e+Mf z>h5ngg>7nTT1B-II+STbmsH>;iKOC1*HOdmjaEH*0yv6ZHLb)C><#=OP38JmAbd>x z0q`gN_4D=eGxPH~1Mm@0U{8pvwsE*#2nH<|Ub2?LcOHc6TY#F0D<<}(i5yHJg`(s^ z)qI#Qk@dXU_P=gB$@Sd!e$8fIsWl!D_*k3iKES_e1t`rrbUiIE1V@zJiN1SZ@Cn#R z$wRW?+(v}&N-Pg&k{W~~FM~#a6-OR)`+r;m%KUjhpC?pJuG8EneUOAzfB!C|;+uo? z1~dZ8m*K>ljEM(P!lJO+L}I`gSTUvd&4`~i?I(_%q&td@FkaZd%5zBRYFGfFzGT47 zxvBSF(3`2^(^G64pF_gRs76aVW43UBx9^>D2e!^Hf>I;X>`Ns#lX9o>#;ea00j#f= zTe_P7<+Un!D<>=lt=iqZpSQf7@8=d;Dbf~AL;okw?uQ&n0`K43NkugoSr2aeKrr%z zm<Q;{B02lI%VLK~Xy~$5Om??4MPJJ`hChfuw}^i=sztb*_dZW01ws6KUWXX>y(wVl zxh$u%+gwiozQR4<@5)6IISQA2SGnr%lxliFnnoy_LqxrwLt?w5T9uS}eu=^ixSS4R z%}6XpSlA>&Z&!{1S>2pVhE52N<cy(6C+FIhIqd%LZfH9Ip<gy-Ru}X!UT!XVc36Yd zh1!F(A-khLf;pu4UBCEd&wdNe?Zu6Nj;V3w!VEQZ$2LY_%DF;r^?r-796n@@heNNn z_3bOg2VPBRP7o3DOzQJ$dC#wqlKl2KfXWZ<gTitNhhx;P2Lls7#|jY22*+cQ1|$Bx z+q~i63oxTK^t%&(+^RR9_)pf`@0`;uqGIM1a$8S09q(QqDG}u7&R<9ABh8nx{v=M- z8lb1Ak5&*uK$g;DWRjFrBd#k~$_@?RUr-d3kGh35d<EII@VR)tTnl+shGMW<4=&dO zdwM)PKYLg-0seaxwRyYR`73*D6%wmSk^c#eq~7I7=C{RsvGgiT-sd4Db3%~uBYr)L z@3Y+}C9B1x5fBXzEV9^$GS1N~a<Iez9YiNGiv)zt-l@#Iaug+eR0%gRSA=&IxNVHq z<*FUUG65WzJdfqRb;JHsGx@}e<ND(Eu%;Gsz&Y80EF3i$e~=QbY9h;BF(o>bM6LHz z9lAgG7_gT@mFY*Z@n~;3Re#tZiCsD0VMBX6j`YB<q1x3BPe$t2CnlnQZO1qa#O^oV zGrkOMhbWiO$)xiWM%bHki2RR8q?(e^SOqr7qF^90z2U}8gS}o#Ef}Dgps{a3lc(We zv5117x18N~@J4{9)O_f!zUP*Ent=~>J>)yUb>`df=gCmH_}vKZYXEa<Gii8uI4lf8 zUaSeFpzalrVLXKddvx1O4}bz`8PJBrNwm5e&oZ;J07h0nxVZcBjy?;21Rja~C<5LW z@~r9;zNZ|2sgBJm5x(|9&IV?2*ozbuKqk;D)JgSP5MiK4kcP@eUv!*T{%y?tLg=-T z!EC`wJW9jnq6!@TnI@X~B!pg0vNQGPKkc$IWFj2HgwHbTx7$f*``H_M;YZon;rY0H z7}oboxeN1T@IC5vMO43BS2-Dj{G<~d<0s{M*Ot*)8Av>nyPVG#T{tytW=+SsDtRjU z6s4KbH|MG6U$1}Hxl&Cu*oYdXNeo*osARHHb_&1P?F#`kfIl~OzA<pq(A)^w8gZ7g zAeTw<z;I%{-VpG(ggm-I$Osck$6lihKZC!y!_0FM{agtvcen$GML&p*z`#)czI^Qb z2n0X&A^t)tdY+Rc?0T5y#ZK@U#s<`xI2CTL^BLcfbit{I=;k2E!Lq0G1PMjMmyLT? zmg${@ob$QhLsn{*M40d1h2`~JtqQdpEQks9`hR}`GQs<W;SY|~a5@n(4jU#&8B(l) zXnKAzSZw8eqbwHCG0NbqP!;x*$A}kL3X>AB4k7bre00$LJZIEKTDNZ9ptJi1fnG-( z$Wn;h<-`8K^Z7MQSQRa`unz672$w%q)PqxB0b1WlyfF3^e`~(V+uo8&jmz)6B|ES7 zkv%p4z4yJ4*wb&@K}a@1#<8;oj+L=P_*c076J=^aqB48n4v2T2V^)YpTw!Zwk+fE~ zA{D`!2yrO}C~RzXFB(?*(?F8JpRKpKQnIep1)lK;r)Q+IIqwht0E~5C*Jgfs+znxx zuJ?nCE`9{#CCWnL7Cxy3N(V_$b2@HEC*7(YXMWgyjQ~d*Em@1j7Xl(TqED6ZV|7Hx zJei;{yyFPaz7$5wI4|W<y|U<xd&R+im-I#c*-vLSZB&^hDpxI27`pF+F)1fH^MMsh zYaO@w;SbWChdv1O3VCv;@jFjg`ALZL1Eb7so-W7#$9JjUNej@qqoWt7ry{QxQ8H8C z+bu_SNx<g|BTzn2TPV008JRMJ)gGc4<}8ruO3$`Z0cRjfDanwo4JY3%LpU<nF_gUr zx&k>`)Rog3k2m47*jkT4<ioPD!4YtaZ~OEcU_NCwj;nyl)MgbO2s874L{kl6n#IkB zF|s2u=jg0^Iy%u5^fR0|K+K%Nm8aVq^F1psmdtRT-;D3DN^@RwwF-^f_PBWh&13sb zBTL1SB03z)QVXsgdP?HhdVecu8VZmXlgyOiiV+9-g>w(GD#dawY(aR&`d2|rj~eM@ zN_qgQrI0ci)QUqaw)d5~b2farKNQxn{fwf@7!AK(>;&KR>lD)1`uEqzi>fx6Jml=A z(*V4q_k^y%&)dua(V%&Zww!gckab~l^#())eSm;GqoVTxB|9X-x=Q677YS$M7DLac z%QipA?|u<N<gy~nr{6V-OQ<US>am%~W4mYuPGkzdDR3Xb?nR0;Q?xTn46!h8eS?Kk zgKaTF5`l+9^#oK$&0V!pu~S3nn5eK_mq>7FIbV*N(I#g8r2`+sywAt)j)n}^XSi?h z;&`&&5DBy|%MqAV-k;$Z;(=yB_k^6Y_E~MBN}FYbh=D-mvb=%bZTvXCA@*E2Zs}dv z%6C1FM;Ufb@pTQlz4}u-QrT*GRbgzTfm}*LdbqaWeOp?Kg1LOcv1TK5*LU-cRY*id z7gVb?DtQPohI|JaoNxowbb9(G0pgDIW_luMbN*ajw;VtBX+366pbGeK=8`PPvXO;m zP}we<;S)gvPC{FhNJKhr#`*MjIYi<#YA_|O>ZfzP_+91`81j;638D}X!Gpy_j*mV> zCCQ~=P{hlyBCr`cjA%z{piAe2TcgrbK_QIl%1JBHNJJ9RYof(U(w%mP5ojRJI^N+> zEWiqXy@*K;$(4<lkkRI)mAy%nLs(={KSG_w`Hr|d1&EeU?jT|q&*8z-A#e7youDWB z<A9jl&v4&W1ZC2Gnb#j6rlx=P`u;L7^i_2w%6PGWNq85gxCFQ8GnXjHkb^PwicEEG zWx=XIDPzIZdbfEPPMHzlFRgSL{PZTp$Q67XZyEHw)O{R*l-KR|0#$M0nUG1np8x@B zq^P|z@2kp&6vZKI{(KL$E)yaSM+%k^nq(5d0#HB;R<cRYqYc;;?(T{6lu#h!B1}K_ zt4cLP5lkh;671{Clb>sn!amyf(2jwaDojG$h-0Gb_KlH=dsConP`MWcc*8_Rp*Is> z0hlC+taJp^VZnnkV?Wwv_(zz3cy+<~ml|m53%UJt{Qd;;IC`UCh*dyxztPY^_D4}s zglgLr+8yso${V@)RIE>R5ZY=}lmnphw)@BC;}YaJ27DIg%V4x%gzCo(2}aqiVRM0l zIB-9?9j6)5{GpUsU$LQz`IuJr%g2-{E@{vPUy@%!S-XM$8k6%=q`*qn&!5rpclcSh z>CxPjXr@gY;#BR5Hwq}L?;OT0zuU+&nRMcBht26`Wnoj;^Ic+Inl|AHeyw<Q9K}ef zyUSrSPal=~mw#9bkK^Xkk0$)n`;DqB799~U^%uF|NX^$<y|YgFH0EO@;8Rk<Xz#sf zMLsLB|6C*pqYS|;^s><??<0O>68Mq8N`_f1o{)qMvZ<*I19l!NndBFgmcM^ju1HvP zMLKhF7&v;obm<Ipg&26sJd$`7Q8HyDn$NuSVR;Z5XEq2P7Z<6NGuj)Fo3(eH25j6P z=^!j?RfQ3ixo%SM6iEJYSe#<`u~{g|eKZj;mQDt($#vE;wqjJZVzyt=l9TRH-5!X& z*>vxx#{N=DSe#tF=JJ{jL9kjvstyqGPsBnouexaT$NOuCclT?R?+}W${U<SlFO3<$ zx!Rn6l_fF<DH`U_d%28x#quY>SO=NmK#M{eelFF>wZ9e3Z^-7|3{UaC+z7mk!^-=Y zAkF@nN~4>C;5C>CuHM#nPFtT4qxgXH_X<=^Rx7|P5D|lh8<I3WYar<==X)dyk($#$ zrI3qXF~|4Mzo8VkgC@(~W1<@rZVzrmHGW06Np@b;N%nQ)cJe~VhnTal;@hO;X<ox_ zkJfU5hSuxyVK=Q<EfB`_(;?DEQrjP`RNygTK}n2QCrf}Tgfar1Pu^V=ZldbHDQ-<j z$^?Z3UiEHz@77kqyF6TTs+~nDdf5lSMI>^aHi?;wMQhUGyDau-;;Wp=jbzBr?baKu z5u|K+Mt;HV8w_)qKc?hC3j`I;ReI1ml`JH_>KffT?*zZ*2oH2ZZ;;oKHH?6@rDzQn zjJ`s<n~sq40ovK=Yi)$FwfE{=SQts(6U|mE+JsEV0rRh>6oK^FOx@AgXlPab?&8<i zJB(jn_?Y@!rt|10>EoSrW5iK5&<G=++r@tjjA$;P=gIY)RxVEOstY2Z!m04PCSQb} zXG79E&5WF=Swn;YrbtqM;4pUtzZL`wF#aQR&NKyzqaGYyC&RLhqmvO`B%%52CHoRQ z5yXNJn4C=wVG8J+{o)RC6H8F-3=Ai6UC0m&{y;ja@JXSwp(5=vqEC+2QJNEPnkS#+ z5@st)0s&^J3O+y8LfLXsaqU%zsT19JVn%|^Gy<at11Knd;hGj;E6HSCmkEARH_%{L zd#;(MIis7136okelZB9)1f3G8XNv?L7GNZBU!gg#g2kY4QIDY1mD1N+6OyIHvA5u@ zZZFoI2oX7u%tfA#_BEOQc{NjI#Bd#^NX^~s1~0+vSeQO-3OArL9zP_$@xFKl{dl>u z#eO-AnyYBw3psV0%$(X-m=S35omp1iZe&De^?l9|cHfo~dzR@JzoKs(G0D*4OPK;I zXD98Lmu8+gdw7!MGx(IZ+Z19qE{vugs4YET-%n|OZ2I>1T~7+b@mBo`Es4rP_``Z2 zrEJfJ<PDMP_yM?K_L3i)<a!@xl=lO`Mu>T=G>K>ZhvpHSo2-v`tUO^t9w^MJP;!_S za!>z#**Bgn+NrCe>xPm?&t|*bDdh5DdyC$715}FlzyY-<+=8I=rn>aQv0GmZ7_$<D z%m_EoA`5Kf7#Q^*c+~h?UY2M=^@#pU!yIoB?BnfEBm}gNKw;H<%^D(Ly8OONX^*hB zujh@7${+(#C9U$C3BzxeGMTV<Rqegg#?e|&c4Y1%@RxpAMm?Xi5`Z8D!<a0X=o&YF zG0z`<;<S)=1mat=U2vu&7@`1O+sie|+>I^=SFSVZQdLdAU43`dKcjTUc%4W(d>8y- z#z~b+a3JF%T7iV(V^ea(r!PiMJty<hdw%<har_^%3#QEk=^Ty*o#r#m!z%~8%jUFl znaHajI;np9%Lz9DH?_I~B&^Aw!mKuGOT5Dw&9A`^$9&&0KYDLJ-zVmVZ-v;rI_If~ z&WJqGr(VNZ4xazw3CyoEq%5(tHNplEKou^a$|FXJ(KQXc$;;nL82uyIk>XL|5ab{+ znj{hXiBg4)rqr5PwTvN<Lm_m*4nmx@s*tPYiX+CDG64Rb&|-qsYv%%fHQYdKCVz;6 zh{&(_h*DFkPp5|5`ksa0Sr#*ZA?f@}tRhE&$LOYj)k4OhXk3%x)x|KekDJ5E`=z0y zb2J3u$x$06Bnvovzo;1Ypmzh|;Ab~Tq<5(#1^{4b-cF}9Jpd~Av?kz-mh|y-qc=b# zvi*40$IKZBSN0{A_gZLO$f_99xfn_8{Ey%#F-|-`OM*CLL0b;$&B6gm^5)!_tUWbM z;Go$c;iPDwA)L@NnVhca!my?Wy|*25zWdw9j=&ZDgWRA8jI1O((8&!b&_+sLMOpf1 zSesaMBS$^OpOHbAD|F!+I86t|bo8wIiJjF3b45vAUvqi4*F$9sEpd+{m7CO@Z6Wt6 z6DzZ0x*J{w){19-+#M_)hfZw1Yz2Y_(~oPyuh*d-fwyVJO*?@{232f!gN~nOA;v4T zW+j<Wvv;RhX`?--<g@-|S^Ga(PZ6GFRLm~nd`1n0)w2$wVQ|L0ZXS@rpGx+2;bZf7 z<=l%T{i10w^de~3yOr`1;6|yu`PC6t#^X$D_!*YbY+AAMev$Q4{#D;6Kq#RcA}&B` zeoWK%IKA|`bAeTMEaB0_e~73CY-{CeorxuMT_UjE+>*;hk#W=*<|hPP%9SLio&!p@ zP#}RI!2*{;3sZzEtg{ffg>;=O`LTKOdn=gE^u)g^q@35Km1?<>h#rZ6Cg;XRuZRR9 zJ+fV4?Wwq=vK8h)&`+Gg5HOjrdSx=%1N1)c4fA5l64U%obCPNVWPz~kEL7s)%+5i9 zWSgR{P=UADzDDKP`f-jCou<(W@K6=G>n7~$7~CK@T}q%ABy*XoKfqdOZROT&L68^L z+xOEv|9S5wAo`tKxIPWl&#UWx<T?iYgmw`6tkCB%wdh$^7QXq3!CfVL<+*kT$5~5O zfc<r0%2|_Lamf|l1gJ)qvG7(29+60a%=`vJ5f+Fb{Tp5)6JE)Rl7Lr?kZ@3L0*b8} zAu6q84OYOMmVpg;SO0oSHcj~u8i@iu8c*^iiV4pcCpe8_L(wF!xQF1U7o?gnpHX%w z77c8hobS1e9!rJGc|5=Kfos`B9SjnE4^$T=W{y>>07_Yrw?=|>XD{kZ#_|rv$`GB7 zXG(38oT`JsJ(b1yS4rlavTzULi@kDLX@AF)C~MQtM4rbv(|S;z-V?1k-85dA1f2N5 z6@De6HVq$%-)nVMC^*vQau}|$<^VKFA{}jo5P7n}$O#bx>UMQ3k7i*KyO1>sFOp$Q z%2FE7zHL^{1lGYzSPAobF{n1uY3`uf$9A>T>@B-gZX7m+J2-S$a+M@?LbEEEt}d!2 zN|v?#xr%CfGI@`HYo{`n&A9*c;N*aWkbFTWZm5C;SB#A9x|mwXm{=hb9~}-a0t@dv zua3j4&6ES6cmT@j2XlL<N@}URZGA^VGk8=hsY=8gr$Q*||B#qcB$PEcsNP9Z!6aqW zamHe&i~qa=%BrRbbg3dPP(Ix~zDI}0fj6{<Z;{;=VuK0L`{4-X5j?79>c~MtLsEn| zI59#+XQPBcVl4ahrQniy<;$@=lGEAInO$j;=qB`eTrIapt0httc+$Nf%>&`mV-8V{ zI!!_Jz9W;FDuUKl#ANzyETzyg+E>b~cyG<U4A{bQTb-B_m@lrIXe{;oBHMZNUg`Fe zOiahQ?^p~mp1e0PC8tbb-oT0sr(+WG#EIbkeTQ;eyW?gT-+q$5=9{L?*D?H`ukB42 zC*40=bF_@84=WcBz8O15)UPnxdeKXK>x90aN4x>N=BwBii&Ahqc1-<#6u{@CnxBhh zy8yi%E*Y87NL3K031kMMjCf)%n)zZbWON;Gb&oKVX&aAR<4x*yR2E4MMSqQUMK3!% zr3jHorMU2<$dbrxQrU1?PG#gJsQWQ$D|wHp;8_vHkGMHqyHbUbyk_vYY7d8N;HjX( zFB$v<ED&TJV;d6`Pm(|?l%n85E_uCbm?bwPQZpzdO=!2CghJsGByLhC*i&|u_U(<H z@Yd}pDDPqi3`BWZW5tDk_`X^FDNF1H;|YDj8D5!9MP_uUR_2f@!lQ{=9yU&nj*$2* zb)bn?G<a|?CKB;mgHkB`1{gC+OlHX}@Ij5zOsqU)-6qVl^=HXdm3t4b=Jc^51UILx zb*utDrVdlbF&mk#)zw9~=QZ!2J?U!=a`x~c4f7dvMa3DiDbkHlZhQ~>i8nusJ>F&3 z4kMrJ=<FUiPJ}c8Hc2MZL=aL$Ciy5)i+7_|Y(Cz|+-7hfDOxB?G8E#WcrsAQ;%2{d zmu}g4lM!N2S^?k>e&=3gAB0Dem{CL&aUlU<Wid5)Lxuz?jKg@Sb-5vxC*t}@s#si3 z1fb;&>wmcpSEYF%ct}X%Xphp3L8a@GeJO4+<y5DqG>5}&l{oSZO0kt9k^$5ig%lzZ zV9*Cr4Dy$#koYlU`f5(5A3B~royKdj6E7tu?4p0XL=)^JD;ZE>+-9#ROKlB07eNX? zmAa~C=gN3ZY<1vT0!A~3-m+`%7C32%qA;<6hVh<DVY-EgabW5zl*6`S?xU4pU(H^M zq9d4xs7Are9o>|o#rwjdU*L1tf_#eS2^{~zo!)CMa8P-HfKOiFO}L_g$jumTwf^|F zXbN_@J;oDL5U>&(;@r3j9}|Y0b#d%|JXTQ>GS8Q!XaH+OfcPgc%p+T<<P#Up7e-9G z(sWgd&;y&0An5QW16oHyig-$6!qpW-!le?h)G%XS8d74O#QHwcaha!h8P@$!Hdbm2 zi8->81!QAKVM*bjzwoaj9*G!$$~aDuFxm0Z*wNow$5$=>1paZe3b%!((M2m!k{1J? z3o?tb3gWMoUUmlK6pzq>Rh8gFHXDQ+C?5pJy#*Iu)N{2sVx2JXH$o2XxUGb>$n|WF zVDcKXGweKC^CfKBwnjWEPmlrDigyud(`lqvpRY>FV7n$I0P3nRaNqX{5(^Wq(*`ju zU{bFR;lVP&q%b1*+Y~=t>i-P{+MO=;`;4}zQ3MVMb%1xuhJbzP(7fQ3O~QppYizaF zFB_et_HUA%9x{{<mQ?C=`mlah_tVZBWnL~e+)Z3d<`%D6ij06n2Z>~b!L^~XVr2mm z&0usZ0k?QBl$e?rGX6eTD}chWlm*q0Dg<+uSx(ImppWpF2r89u&QCImMN%fC5(>{P zR>+ovMw>q0Cz&l)918`w7BEo1o3Q=W@fZ)X2n-FeQG3xwFVmM+POGGuISm_d%^xL2 zhmul<tf<^i4o7VyBA+cP6%qn)7f^$2<kj{_|M|#|snOFM6-agznguba-Z4C&-W_(4 zl)k~aT48%+b7=D@uC6;?sN!;dy2tcv33|^rW?<%;hheEEu`9El2Qwd7$~~ENVHMN8 zKn#-LW!Pm>y}{DIZC?Lgn|dVf5H!-OGIbacm(bKsL=n=>WA&EhLt*r|vn&ItgP_o5 zLi0pIBXJxgwD3x=(iiVqQ!VHnM%oXW1_#eK=V1YD4lX5OWQ%rG@YQz3lJus5@*-R7 zC${8pxOlC}L(BEIt}P?Y*}&(lrpRORmU#mC!j`ivqjsV?P#9=%DPC+PK$aQ=JgsXg zzhpKO3`l6=&D>BR=_r+F7vV{z<E$)6GEc?0)In4>Z(H^PNx8+;8n~&Y(nw2a;%TxK zhKPtxD@g06(YVU+{(KKgR-rURV&91xnkX?j4p4;8{p*beCZUBwCvFp@ktZz25KRKV zn2vanT%)Xq!)9U+4DMzP8ycM!4E8H@iHsOLwKQjlh1<9Mr@Rox4<PNITWy^xAIOz3 z-pCK%-$gpbq`mR(5p6&cg9`KYS@W1JG$k074$%3#5B;;(&5%?(m71sa-41rOwTy%O z#jNo};lc}FvMSt3>TxR;j*yFP`c7N{wa&F%EoYF}f219FHE$mbm;YRQDIt&}4YsDj zjPU|I$NMrIa5r&WhPl+#EVjlbZlO6OUmt=qt`N==I|*M#4Jo97*0?Tl*&fmdM!NW` zP!fXt-#8ASH?H%+=5JlLY5Mma#a&V^8tz-GrdZuUoV`44knDOSzZ-b4qpmJN{5qX` z3Wdk!_~}6Z`&k@bDkZjBlfbLyc`4XX&q$iK4U2Wd)4nVvWqkCUbre*=P@6sSuR+q_ z)T!y2B~0Q1QmWOuU4Z>lcZ@D$&-qlEf$LLe=*f|PuHffg+>|Y+s#Y_pJSUe0g`|ui z6|Z<gBJMK_k-v((E(~e8u%Qmh=VCr4RLYmX^!SJCo6+_KwA$>|#S_?6EXBjYhUd?_ zgX01MMsX4g48<fwsJ%T!4%9JhJB0fj@y^70t63Qg<l?-#llZQ7U6lQHz<p9)V`F1} zmXs%ykh#;lnzzFXHv|S`Bth#w;bL~W6BU030?Bt<;km?suuAcH86}WE@;v|t5apiG z^W0R!tQu7k`%!U;sxeuh<k?@T++GKis}}K-V@vVPiBZsdLmSj!#(-T3=l#ird*%jy z&u8oysuwz&WLaV!H<M)-CoLNDZ;zke)=(eA0v(}eM)L}r&3dpuiqXN^+V^cplL)F# zm3P`0wpTo;5bv!0N)&BA?!Q_9x`76np(TVF>LS&7K~Zki8@{8tu$LcMDFlXzcSmky zQ;q>0Z_jy)oHvy(Cm<$2QLiwl`}P#D8EnkOZk*Yvc)i2s&PG>;X6aZTqxJt`SiH1d z06Mi5Wx4&rfBd6;_EC~!5g!`OQa)w@_g^crXqaCpv*zIMJ6c354&+5XnhZ{D4fm;s zrm$?Z$iF<=jNHxi1XlY1q{QW`ve@cf)a(tB0qB3CFD)xAez!R3<f@T@#P1f`mjk~m zNk6i5L=Cikf$Qz~aKj;7t$he@sSX0B)ifk*D{C3a<7O_(PVz}p65M%&hN3IVE35F; zRy^{_R~D~vNl4KV5tt~Vs(RrRBB|W}jrH-kqpBt+SM-`Swxq%kHAP3ly}Alf%}&S} zVo!<N2y<xIL}mE?)Lv=!K($;|R<PAQvt4+P2@C=!!FcPkRIGQ(@eMcR7Ni(;<aM;w zWx2_?0)ZDFSSyQev^b7HaXIY*DSqA#AU4zu0-9yt|1mkD^ErryaKWD|YvjsK|D$>V z@<hE33qCf-M5NJJtZs?%yTk?~qy({c=3Ujr6O$<*;nVQvedV&C-<^WD_CQ=;U*EHl zQdQ@NQ$6<V>?mgZ!j)+zf+;+zWsG-*xiKAyT~q>5`Y;Lq%**xySZMkNx<RKtPeLbk z3$)~=rRyuuZDqkbZ!$e>+%w=+^rqwcMs)HW7@5>U^&oXQm4hSlc1aEWrfiq`0Ojqj z2P<LYiC=1pT1bBe&IIEyt<DTuTM*}9Wt%SVp;mt$HO}t!?xjn21ug<dV>kcasBw&V z@s}epmZRlr<K-Jz_Cz4#f8r${c*J#Kx%h6(W9X7-Vtu8Y_zL~wxuwVdVTuy~@OZ%L z(;8rS&rM~yZ}GBPO2BYY9_7lRpJa)KXsTS7R?T<aZ52EhpSTajG%)JYGD^Q+-3hLS zd@MSR+gH@W289dU6NNT?)s3X_1R~nDx28S}%n+~~E|<2f1u{EmrneBxsa{T#Jy|Ig z>#WFdP-mo-Wv0p4TV)6CB+E5MFCC^eEeLAi0@~D4Rb_P^H*?M}rYk3O5fnD07591B zCam+P*Bq;Q1D79TpcG@5*SH0V)dh%+5^Q|`&1<aD8$RySUcT?;Lujb9_&vlBk|707 z;pDpBXj#n4ZU3p&pV{-W<V>vyjSyH7-L)T1El0?NySf);+J>9+GHHb-XN<vUW=T1^ zNa-fS*Ybe`ngY5X-zXqWWA!!vN({>dUlIThzB)4+ypbV**(`0*&lW=P4FDkJc8Mtl z32W7(9Rc|ctopE(nmM2f>S$wN3;|7IrcX(y)hPZy0Np?$zZQlpm}o<lCt29KZO67< z+Y0_{Z8VyTC--mJwd$qitCp<r<qBy}x+9cHn2e{k!XFL$0wNe<MCQ!PkG!yP?Yb+k zykh9=2_h;ooyguvZpOWkAw^1od|QEDF$qeCm<K4v`6B|EXL>V0OrtTxq$I`<wlI)v z_vWvCGx5^%Lw#u`Cb29B4F*~D*%K8m$i~3FSY2K1+umXZ)mm{c)w5UCafwbT4uHOV z7WT_9xOUi0mK|j4>+5krv#$;&0@g4_Fk3>gwfnen<4&oEcOPZ|aKP$atC)xt)tarA zogQgT3Wk-Us<|cuSfEn1dhB(7=9y={{`Ie8@*?C57A#;8mhSfG%<?++Tbz&*j&f^+ z<5gGQm{^Gbu=KwY<o!t^K|oO~NsM4ph|%K8nLV%VUbXu5-3N9g^YKJFHFEIqF%=`y z`#LtQ*-!|0_J!hs(RCNU@9Gg_Ml)~2N0y{{^`Vz`Z`yqEB^OqWA7R+|6_5{^EHYz< z^vTvkB1EPw5vzz)cxC5>z69)aTTiXO_|0u@dViV3%+q*t$sj`pGhVZ5<C-7*F#quV zV+)CnbPHfx$#X&EW9^QBH=hheD)yWF-YMf}{Nm?k)(m>SX$&wJ3)7zVAbWbV_4mq^ zE9nbF3K2~_lViq=Vf!<7jf6l);vlbF#WU$lHzck~yf07X(*8|3z&j#vOAEM%6F}bk ztFOL_;ro}r`~~kEubUJE;FF*H<V`o-gqxaEM@eb1NCJsi(vGK^bXO$)rZ4#9ycrUS z2F>I%6&{uxHW|NYG(3!S`*B9xP9M!zWU&)M?78g^va~K&`w&oEh_R!r$Vm!P{qc`~ zoDN{pX=wiV$3JF^+ddRJfJp}^01Hl8t{ntm=@+F*CBQ5I%pd#0<;XmpbUf?JCUTkD ziW*j|HVjW`ZZ$PgoX;tLI$y^U&L#|Ht9kx`r)xve8B?d3Q8MtVaqZeMbEf84lS=wB zSVpqo7dso*iuj*#Ofzh{4+2CU8-R1}re|a)!fGEtGXn=@+dLf2t2ZvW`@U88-a9G2 zuO`<Xs0j_P2xrzd*7_nDe^pyYdzG)y22@wqY#Tjt=Kp-(T(pp3(|NGh6JE09wFe$} z;OVEI27}S0NGJ9Xa>*ba)F=ZJSjnAz1<=Aec}}Z@TN24u73^qaz2qJT4hO)+PN3_c zX1A4u9<9X46g<-SrJ0_@OQ#!{BLMudk9~~ZVrY2#q;v&Zv>Uf`kht4hxQQ+YlmqCo zj0_L83+J+a5Nf!PkFtIr>+z!GJh=k9&@oOlRqzI)%o+0d#2MWO{aIqPwi*#m)EYv| zhTqp-do7j*g36lh%)Z0_3@v)^WcNZ3Ko>OcOAJu^M_x$j{YirQb&Kw4rQi(*jITNn zs1Ai{qTUKz)MC+^L19zj!@%`Ne2GN5f)zRTq}RW^EZrI#GkQ#9<Pg)6*tvD<8{0Qc zm@`oZJXs0C$0r_V*%%726QJ*t3tFnnO3-wLNKHEhdat>X^~;DVnh0%CkALREbI0HK z!NG64to{S<3XYqYd})=ZEgeg<imWFR^(51oib5`1RatZ8<!1aCo~x<t!2kY#|NHH4 zeV17%NGIiC;^2y8`0I!fBalUAp|G<aqZJk{T7>Mfu{`~SAT&B!K^I-DqZm3>&OIGC z9Oy=NRP=kOBJ{j^mL|CH!V8<5n^&)1&8r7-@kMXkxN*{?Ni@aKV!V2l0VIc0M1mCZ zy7JHiU)|(xIDnOcN~9Bz-QQ$RC3Z^FKAFd{v)Sz4?}>z15r*+ASV@^YLIwmo3cQ=r zx=m6+MMRNI;>>ja@|VB7Y}qoT8Ug;&m%cP-&K#9qQo1eSBuX4$(~t!GEcbZ9*5s8F zT2Y!vT+%H8M|JOtMQn4iNV6pjVZKHz4Mr%zW2!1-A&#|6UwiB?kJQxGZ`-jw^H@5S zPq$_h)8?JYl9B2rmc|+bqomOWP%`96?B=5h7R;#>!l!mHcSvWF(LmV8f*Uj(0r@eb zYljY(E?>rjr8>l@U%L7L>vI)y>8i@%mtPdy_*!8fOMP|h-MZrp)>X*mUwQ8NAN}m- zi(Yue;}vAZvU&5H-^>=aU@+chBz67z^?0P&${Q8DVZ#P`_jm5x`M&qP55F`|0Rd90 z+7{vNR?8pF!@7C;l>_=-ctMn^uZa{*?DjtTTA>7k>3slh&p!KXd~~~a?<VE3#~#B? zg8q8Xd)|Y#Qp3VgTgZc!NfXV5;cnUMCLYQGG#PF|x_tTBl_>W$y?oDI$=6mi>}t)1 zd=2k^%ZPWqO|)4g5DXT*n1_~dgfkUIq#BV1ZV}PPAAkI>fBh>$OT&?o&u@F%+qlXl z+&rhieD?up0oym^ps$>DX++r(QuM0kWoizls(7SxV3&_!OajI@p~V40Qw$Ok*$bgH zeqhs1x+*FL5AsDL{z#~%p)OQaan6GI(b_83=KyPIjQE&oOJ4@BogJcB$10!oTa(z< zsdoqMvX*r-WJWSoqqPVU2N*sky~8vgnI!BnG!r7eLO$z>R<nYLX=&a5)7!moG;-&b z(Zd@)ab55OZ`uCFI?tZ=gf}$oop0T+Yxj3P_wVbLtYS;x8E4J;#3w%Sna_M??%cTy z<i@p#I1)hOnKNf1pbX5xCy6nH9gIypWy%yhHmr`Mo<`)@)waERmnVQqp;vEQj=SaY z@@gS4ykgW71gIpICcr+JIB_D4Fx=6os{Q--V+unvb?Q_)DNt}^?^GH$rJV9&-MGtv z?l>UBt1xhw@F@VyFBa=qwlue5Re1RuW?##o*^?vZ%r$|C@%m+rd;HO*fzsWT)=iqq zA#2V6uBa^hc{CpxW(X-tjIj>v)rhX6DXEZ5yqi)^o}>W_z+wT|o?aqls(~{^K=w*v z!v@?Ryk-2yhypn2$uafFj%X%h&MQU)jyLIg^?AbKz~EtLOrAey(!A-D&zv^(+!>SR zOq(%vde!h6Z$NGUZi>fQAd*cFaIXOD2%4y+KG?xhH%hUhDSvHNTLgwX`$5n{VwdQk zb>~U@ytxpgzl;}^xb)SHciujzqct7yX6Kz%f8%v#<j{thb1ItJHnn#=myCVujys!n z?(_JAAGq=QTfh46^XJb;@(@;ngRCf7kQLpEaXf3*tX;cy;k{Y1WC=(-cI;T()Km!1 zq+<X{J>4+CIG|X_OY9VSswQt=?Ev1a$^&~Z(hi$9Zyp|z&6_vV>Z0@P#TQ>hmra;3 zfmRwN1H)<!Q>+u|=@xFf%K_y8hL2hid6|xGU5{Z;!?+P6>+9Qp|3E&KjLx4KT`<ou z;l#%_C!*^5ra$d%&|^4nxB>Ef&pr42=tn=|qd-body;kEP+!C$<m$<ezC6Xi17N{0 zDrRBK9=onT0ZP&p0R~%y&U&yTF>=9R0st!85Yde)01QSEV}t;sqGZ!!^;%=<s$7V- z+79MoRB}gr?edikkxCDs$O{gz1EAD|98#TL2dRgc@78K(&@yN)OM^(@MC!-If+v&9 z<k%>Q2PotNnWXvC@6yjd8A`UdR|E#X@BNWWE;ki*re?6`%-PFVy?+1twJY{Cc^d{@ z_fMbs=%+qaQ7K#AB85_%9YLdJ6RMVUO~glyC4?UmFEj=a3YR`YG_`toptm1Tub;{# z{2OwBx5InXcPe62>~!hA2E24!8qm=8;?*M+8t8Yp^wLYQBp4%&j|6yr>7|$G62=b3 zL4p=jIiXPKop|^6a8q3l6gglWdngaTC+9b5U%?+pn?TAmu5W$x**qg?E<Uq*;XKCO zuxBheM9cO`d!iZ(1;<E0T<J$+)kzXZjT-gUuYQ$vlaN(Tk#?2all{%WqCN%CLk6N- z<m)aYkfJ}ir~p|+QIZL=O_ltdKpc1yh;))90&q#-SgN7(B1;i5P~|djga#L@PqN}O zCZ@fQTw#BEij_CYQEth|EbL_lBD0$?cT*UqMF&B_#F{%E`rSj%J@mY3K_>;Mkw<ni zEDut1t$*n$N)MustWPM<Xd8ZHwrC5HUdJ&m^}xJlSu6$=Q2Bf|g3*4U`M~pwg0c22 zEr*8My7SI4kxJu<n#%g!+qXTkcgNbj`>KaDeEQbUzyIdzBh^*tTofpV4o?oCBCo2W zc@R>FlS2B~v17mZ#V@i}1LLCU82;JMe%9LBN-i!PUZ<Bovl~B796*F{;poqbQ&CFj zMDfJ)ra4>Ko#tm+GUCXyqUA`L=5<aLP0>fZcWeR`4^Ej4{EcsX0~JO;1*bd+i*?*^ z!wrlnB@V_zPlPP}E)P!KY{iQ#bQ0y96KZ6iOvg!BO8LZ!KZjbrPNCJGB`X$qI{YbP zL+>89oIyQjE?p^cyQHJab02&c_NC}+LT>2oV=|{NZNddsv$rE!3b|w<ne}Aw8d@V+ zrj*dvL5H5+NWGOswW&$PJBmgv%D;U+1Qqj_&J=|6!3Q6F`Q?|jzl`2rObFF@YWO0+ zz2nG$rs}H&3~;g56i17Fa#ZC|dPw^MC6(Y|m@dqf)s9IKkFLB@mh#pFp|aZrL1vey z0vPrEb44%8pRy*DB+4awUD1~w0E|kyaK&}Z5*-qeI5b|?f0m<6DiZTo(A2`TTn7s& z1q@^l2YP4=CX|Y-cy`5_Me94Z#70$&2-F7!(^+E8$6mr2N}=wlbP}%z^^c|E?EJ~2 zON}^awXI;u?Qw?NwLEM+i}w+0H<6YFHG^LE8RUWe`9cV0bR^93WjlX!XA}VT`RW#2 z6u#kxTy-rQ8LoTn^)Gz$wpZR*UkHW&<?~;-`kmKQR#fq1JdyCh1|(9&QSMqwCxvvb zvrH1c=oKqgU<b2~xpoqxppkMV&_Y0Nf|Fen-DAISz$zDcU&VKZ7>K;Ex;M=&Km{!# za)TI(Af*fGmX2rt{N(C~mTh`=-5W2g^ri~+lSj~)#F+y<q}usHF1zNC6kBwvApWwN zxs=9_uK|*1MfCjh7mOG&l6_<L?c0Yg!zqGIJa+8ZY15`jt*oQZc~ZoHxFZam<isI6 zT!aE_h0qaHm>_~^1E-qEXD8QW6u)etWB*Df`?K|@8W516rCA>mjRnpq%_-29dMY1y zUf5tcqMSIw!&(_*7^#>PCEk@~;WA}$urEkGh{|*N--O@xx=0l4&*j+NL*!K0En?9w zzC4s-!K8AgH7$y(xk>hk$@|Qj#=Q?c%CwQXbLU6rUSM)j1S`$<?Y5_wVq@8M6cYE6 zgTR8QXb!A;V5=e35^o_dmt~f$A;I85><5-TM`&qE{_uxC1eo#Vptw{l(Q=NUlJO)B zpvX}LG=}pb$ZJQBSoW3PF?_Z!6y^)|!E1XiubBS?S<Q;z;i~hg+LXf|Y&nuopi{p@ zdn~0(Zi!2xrg1Djq?~hedw=$8uoB7%nu;slymw^%8SQJ6%b$Hcwl{uZ%Z0<w9d4Lx zhKnT_$YtoNErf!RWGbG{Wh$eUR&NTl7g0|ihdbEdoKZ5XPRgB03W@Z>0C+`}SS(W( zdB%i&;f1s)$H4AXcErL9O*o3KNyjta{lO1jTED&!2;BPr{L3}hTobOU>d3^Z12TQN z_o1Po;nrJkWyIEw9XnXTA0N)e7hg={(Sch8nm7SzCX@qn@9*ML9+m?lWkTSHg}7_H zDK<0DXM>DPx7{Nmn7j((t*&JEjr8t~JAEOOXtLXR1*QGQ4?z-H5)~?cZJ~1BHN<1F zXhj9yY4p@}*Ih@K#5ceB%_pCHl2b;=vyeS+oTV%Ah@j4p2LjrSM2g~w{h=vcOFmqR z)>59M_^h_JlH=f`TU%Bdw5Sk!**1ga%myWN@)c80^FLi*Gz=1Xut=-NB8!A`qG3ce z9f@noYv<J{y{bg377IBBt00&80=;TA$Y~~Jw(ra?eSO_4EB5bg>hLH10nglt)9Q11 zdh;@ctd})?(P^x8zyd~gmFRS?z+lrVKkmmYV@{1XtRP;LW~rf|u>f<a9tb27_}kz9 zma$i$FEaeW4}K6AGyr_02Riw#_tgUC9l@!PT~ea-Rmpo}sFS!T#M)HdAc?$6m@Du@ z)5#v`ish8A+(MBE5NAxqL0b3#?O0^Vc>IDbotsi4g1mI<Q;=%-&H5MDZ&|rH<O{a7 zwy$5muA`%E?5HuGN-r1;EMaQO)VDw|6bu2HoKk?D6{T9s)|nQc6+5ok4*(8OxI_VL z8PUbf*a6Az04#!zlYIBC?Z5tYcJ(TH@X{kkHhk)nX4Dz+OyPUq`ObY0+?UIzKXTpQ zfApgtudJ_U$TwCwin~u7!as@fWdI=ycVGiCCYE`_Lx&Ef(gYA!*idXl@Zm}qvV9Ww z&|e%-y;5Sauv<zdRYczt0DZ-QgOJb=rFWt_IAYuxb*6sBYb!gl@xkMVkD5EqfWNi? zD_1yWr2Wg5TD&SN4Mo*eE*SJuuxhUMQ>4=w#*Q*@k3o6MmoG=Dv2-Q7xsgIwF<lY} z35oi^>c<ABiQp{J#6BEF<OLY0SgCsQumq~7KS)pnSyVgQi{=e`gjwqzD&>mRAmrzf zZ3d$9yro|sDsz&PIvnd75hjxgOG`)oT0Udppr}OWh-{SqO59MsiZZfUY)Mv@cx(1V zy!~STiZ&BFhyDwa5?S-gvYlW5#>%_zYL6cnKX3ZHD;74?*0e8OyZSfxG{joczI@%n z1;GX9nJ|5VOfwgS9%K?qIv&VnMIN{b8=O-l<yu8%ML^6Lv5j#D+V_tUyl&k(%wPO= zC@4l0-get<taG5%FIQQP;wnAa$@f>Dy)OZJzR4ndmSu!<couN1!e9H=<qyRCKsdo& z1!H@ZYZBxQlR%92QQtpxTSlJ`+>u(z@zCHg4TJ0HEvpJw`g5M<o%@$O^U6Ixzh~!b zyM&HP#`(keDj9aobY77l`N<V4uOd{4kTgS7?DZC<8>RC(xBv|>EZQ~=BIAHbnGI_X ztY1?bs!W?;-JDsbp#h?&AAa-?fB1bmn_9SV;q^D%R9QcWk0mPw$Q}C>XigHYzWQp+ zAoMJ1mw|<(Xd!$O2sF6MDbkGE?Ni|{@!>h3FCXTLsyj5G*DUlhVJ??Owej8XZUd%0 zmSh=&NKIA7QwUdA2BKloX&=fPB2Z#cu53e()RKVdb>~=a(bA(vI>WEN@P#iR3EIYD zko>1V{b|;0K`OYaGC%~`P#uRs?3C7r2v4C;TdEkMrj<vdGtq#y1VTn4U0G5sLit0< zIVfO%l%u6tL?^GEryvxkPk?C_2}@j3UMX)o9qlQ$uSMUYUP5w;KV=y#wQooNqQsQd z@`}i=%FF&m9>wWrg7~7vYsqkdwVQU_e%GF-o*m}(T=KCSM&EpcIq$rhtFAud+Upiv zepNn;UEvAgqLv}3$+SO3FR`bPVs2cBzQvTs9Eb_}(n|vBQZPZJx1`YYMccYz^8W63 zztgElh$5@GF|7{yL^3&|rcNazq4fNHkmy6Q@OEvGd0`4b;@F41@&i-(hG|(#7E372 zAQ)dVi%WNv*I^rE#nMXY$K~(A`m6eqP6+OsHN%Dt3A2n}Eal7k>LY_pn`g}ntN(Jx zpVvRRNk(Q7a1AHr=aW8R%2DwxJ}%PB55X06Bad%onz)?P*k{y&C>>Eh5T!EW6JQCq z<xAol)<t}QY_zI=?m4ERZr_?W?)dTlB~u;4M-BgnTRuH%)ET&OfcB6tlu9Q0${{cn zdF6QHjW;qbni(mKhQ0URdr``&XUnDe6lhTjuLpRrDi!ZD<E`j<!w3%f1p-AX(x$Rn z)+%l7XlG$_1SrLNXACH?W{!L%`ubIE$+-kXQGfPB6S3rns=}znx<zeOu`4!9k!RD> zrcGfcC1OA>-agB=fWZushZsr%=@`w}zFb8xNS7P*I-m{Gv@Lzov#aWW5>=~9#VL$0 zh%LEuq8F%T@rk&Gxx_i2hL}Tg0<C^f#i!&C=Y6YAuj@Tv2}`fISiw%G#Z+aA9ATuA z2or5wdDsoxphFI&1f?aCmF4Q~8`oUCE6Ir23SBB~7B6Xh^l2>FsxxPp`3q#4hNs3< zjWE-v=SPoXGj?yrn@<(+G@}=N(rQSUrXBm2tZ07t*~IT2G%v0+O|2##%co)tqPF*! z8dHm;{7lv_9uca8K;C`#-AEu}&#E%4J?SVhM_D16jujyfanc63-^ZYDm{(%$Ir|QI zP5O$pG<#GAgUj+&+0Rk5hGnqa&~6}U3+dzS`-5B`p;!{b#E=*iA$_l*WHQbO<q%pi zVFC$%oo~?I4NZT!^H0zH;YG8<sz{!j76lSYCR>6&ydEi-h%MftuQI`su_`KOX{ML( z)a;6c1k$uTuz%l+&kyx_63KM7y4HWuB`m-7zd!%kie*dL{OQJ<u0Qwu^BL9Z4R|_I zd=4fW)+N4*Rqy>D1eea>&wlo^<Hn6+3=T#x6I9eNq7X-{dtabS*-H-ShtZiB%Yu25 zNRcQWD>Ou~2Yn{dj$g!7gd<hqXgZma;V*n>b~Gu4SkaPCPZX6Ldkmm2DvW^gLRA5- z>SV^D$2wV;U3M9E23m{(dbiwii`v1Og%Wj`UXMlhd_jf3SjiIE!Bb-V?5BbigubOA zUXW%;w%}tbA<r$=8zg*LnoG$`C7rH+;e!6UVSvh4>1Z((C5xLuMh%qoG7%M)Zi~^( zR>-)HP)Y(Z87xIc^d0hdpgHsE(#qCWgmK8!$)>8tm|!*(l{Js(7aLMv08^Q)i&u{q zh|Co-@ntKXzT=l`7B8+12gCXNl0W|Wh41{(>~8k@gB|Uy;s&>M;uie4tF+Zv1}U5W z{qKK|3z|C6>5JJw4;tlh>I4<+Q$uShh&YdS<Vew>VGUmUR+W2{qxLS{!(|R$SS&rB z)@98r6+2m3$z%)0*YURGYm+h$BV$LdR9`5#Q|Dl1z+(mv8;l1Uosdgrqn?T?U!||Z zQ<08lo6^tS|IGb&-XC8X7aJB|w3SjGj-TbAN)gAhfGbA4F-6&jk|)P~Vw2eQm#N1Y z^ZLsDD_$E}5lwhJ^)qIfk)t1b;;DNde7Lfv`qIlT`S6E6SV%G*N|yKXh5~6EiDd4k z{$)4q5>;VUzs-5)o%g9veQLsl3D`hr+pZGaSBt01-Q0wpIKZ2;Z{E4iOC?}1>`JVE ze$^v?c<_#&-|?gG{qLXe{@vmSp4+l!eT6r`uQrVFYSKye&ngD{v6S3Jn%dpR6N@2J zG9`&@ylCgmV%;*G13MUDz{w0YV{kA`kCi&0RH#;I(Tv5r_U;c79yIw7mJCQ>J;tQy z2QOkPCrG~9w*tVJ%JeR#J-N6kB$#DjKP(7&Ea!RU&U#MvKC3IqeR2o=-jxFmQ{>dD zmtwlcMZko?h!)NDtYEM*OpaDaR0_4oa!pbaO`MlXBJWCFm*VQPon;5MHVz8-bL}l` zeZ$JS=s;O@p9<tNxnyg;5YMyi4LjZhC?suSsp!)6J05sy`oxLe1!sBQaru~O<2FD1 zRQkb1jMA#AjB0%V3*6w`NQO07nR)EdN7-qH`l6sNx#SXNA8Er8$wY<;|37>00cY1$ z9{R4+`<&@Bnxat~jied%?kc%g48|A?214Mz3nVZ3J(9-@Tz;fMa*1D(7Y9N!)fli1 zZgP=qxk|Ft`)EdGW;DIG)6dzby#KfMnXznBtR%)(SsLxL&pvyvy~?+~w!UJXK$1<h z(78RidXWDUU6`In^Mv{3Pp^;s-0C__;5hS&oO35p9yNf-U63-aa4ScOdDN%x(1BN- z*`#T_NTd!A4z@O@%Wlh%4G{G(&fa!{izhOvbUc0N)dQr1zW#&P&)qOr1Q(r!iyaNK z17>5<W^3C5-68WWLW8AKBJSXVq*)Ew%fb_RG88}9Y#AL(B(p|QUCHHFq=v`8`Qx93 zGRe9b)t~#^XWdx+iQBS@;<{|HVEiQtBHDj81u#X{F;OidFNu<flZ71?S4_SVm^S64 zv#Issz5lfl05&uMPIiS}*z$bK@#DoaN*AnLTv=Ng2~BhzZ0|Wdk&Y$o9!nw`1K3<a zCr<!L6j9zy!*CwPrW#}Zq`%>T#wXayoMn>|<1_AXNKPa)d-vXZ@0Y&xC9-<32TZb6 zJchY~zXy--AQH2=H#}AK+xyfKSRS|Xgf^mr)y$&_3@AVng5v26mYm$cD2OsllVww8 z%Wrvtn57+OF4nVzeEsx!chH0IrfGjeCmA(8s3uxvPnIGNO~Hmas<Que#zi?7ims2c zPb)>!MQxag#?I%Sh=rWFbXmYJRT1mT=>Qb7iHy}@HF6RN*lM>X?RFpHR+=ppn<}a) zD4yXjE0$RImTYPD4408fhbEomGZeb(Fq_0Xv4?=jTQk^NTOR%OBgEf;=u(KPOZ+}C z7>MgPS|m*Cb#!~r$%CGsvuwHEu3;Y8?lB>O`LapuDLtvsh;$|kv49O@f>=+e!K_vn z6o-kG90#%w?-DPJJf!fLGy|i#|90|gQWsi4{jW1kyb!|zfDOJ&_M9YIrRYP7?Owk( zlnFcSP9u@AJ8f>8$6;}#<0+flVRr>0W0ODo;ZH6fyz=rJFUQIh5C`zm*_6}a6cm%e zk2jA*WJF~&OoYUb!sYQTp^=dSog&%}k9NMiquAyk8$+t1L^Uq_$s>;)I@+R~w!8nw zA2+d4$8(~oA&#_QU1_no`N#R$6ccvoJ}MoGnaOLqf-~jdGtZ}QxOnnk8v&3DMQ=%f z<ECd2*c;4ldhqe~6K$oHWp{u0WA;jqVuvAD*HqhhEU{-#&u&=~Oh2F_;3YofLX-rq z^cC|sy@I(eP@<x-DAZS<@`y;l(|JwoS|A3a5$%sO9%MED)Tcg$wF_4^ZQ6uh<Zu4w zZxE3I1E?=+hwBun^z9dc(y2!3M@1Ay-J|yg2?O8+O+?WnF)E~!1wW)zI_3@*ppd~7 z&BjGK%evv&{F`O@@P2CLj4`-?ia7%MXig|2FjcH+g9vCjhaD4RxeUdc92^bxgtHTd z7p!D4s;_7Qy`@qaC%NEw-YWZFvP1jEDPnM?a^529Ir+~iV3kR*A;uT0a=8gyA8edA z*wN;R8>aK5L>pwQpLjy)9BCLt@Xk8I%2%v{;%mh7H{5XRrR!9{BLp}cJ-uV6e`bky z)k5XU#jQEK-`MOEc!nBF)*HHFd4BWeM}Pe=;0I;JM~<YwCJ_Ec>T7m+YBbK(&*|lR zwjIzwk$;F86zUs`DGVp!xk$sTa~dSmxeNphtN0Y=zFCq<x$PhXW?S%xOD`}H1gOhY zmN57KT?>pDxlG$zDGIj4cBrAbgQh#dvd<bhH!3lV3Q7xx9K$GkeVzblBRVmWve@va z#Jeq=h#Q$y(w=yB^XAr`*6TlT?cB!s78iAqQz0u>_b`FvgP7(bKs>_ii|ES$NmLSo zPNUGV5uQ3}!^8c^G1b{;M3c_q!qVkS$A$-<-uhA^k-X{ln>OBXwG6GPn%4t%=5Xgn z{o=>DFakn4&MaC5BD0xOCyurbboP6cWB#nU_Ck;3a5Ja5*j`vx0*9B$r38TWMPU?k zDm)w>85-_7-4+Z4XOz}dRLxL9?V}@rhOm;uI`DU=h%to*Gawoi_nv$1`P}C|XNEiY z*0;We)%~^CUTZoa{U?QBT5I-#qu}*?K{JGEk`!d<m=w%w)X41FZwrO7ze%Q|uBD6Y z_4A;?!Yb1j9@UlP5yBbuaB5aRRq^@$Y3j_TI4&6(-D7mIxI_wKVK*H*Nxqpx@?^`Y zJ<sgSjKm6aHh)QhtE#kgVWp0_$MeDhGM*fepcq3F(^7-J$aS31^T5VWLQ%np{6>a2 zL{zV*bmfv0FTRwEO{mUp6^kf8sa|<+T7@Ruk%-q}izm{71V~R(&*2K3!qA~47(RJC z)_g3vdtXQMvFktiF|}q%E*+Oxm6#?ZFi-$`vB_iFGwE>nM?bueh~-4*Eh{S{0Wb(0 zeawHx7w+5viZ|nj-_vrvJfN=H%^JRid_(#VdTX#}F3TnyjiIqc8Ou+0ixZO)=ERCt z*O@oGLZ88GYu*Pj8LY!RGvjC3lHb!%1sXD`FH;CY;YdLl%hsp73NR!Jk*5AI4Cv() zQL~gPsVuR$t;D;C8L?E(@C3Xbk6U0gn?<U?Nr?^AlJXMN)TA2<MZ`8*9@7#wGO`oD z^gMz9a?LZ0yfjJ?UeD}m)|Q3qPpUopEd4{yoHOb42O8%8^tmmqZEdB+B_I35$E&Mn z>M;@dhe8A7Q=iNCi{+df0l}JJK%fHjr>8QZ+FDP>$0LrMt+t%RlzPGi^T~WCt?Z1Z z6WKK0YclT{m6(XfMq+zjd2Q%)_uPt_^l0Sa@Beh$Q_n>Q#s$2jQovANBLW0#PM7@0 z8DFLs1p*Ud?oBt{M35HFSsJ*BfBDN_CR7&C&J(8Y+I;lw9-$W4Qfa?K(Sz!*Q!nQi ziyPG!1;MxF#4|s<|Hpsz*H3=#ub%tz|L%Y0MKuvcOt#2!krAK;teB~e$%4Hw!T$|2 zD8rC1cs6jJPO~SPOQBA~iqz?9YH0k(2R<^Rup&7caT=C@Q`>BEA2!TVWLov8>TmiW z`UyEf@I^R)01F<Lq2?)b4n#A74~ENj?Nu|cxm*?cyIYT{-TTzYkV=fI@gDWU3j<F- zLnPfIl`QTaP$$||5)DVz>5LFQ%b1)<O-7*A#omC5g;iwI;)W<dozZ{lN!1SU@C48A zc<HgHpCnobFTd)ltJwWDVU@4varsY4zzm*D5yC91EU$+a<rdtGU7^M0H{$5P&&mv% zd-Vh|1NEfQJ$Ph?ff~%e*ZHt_WROh_#xxHFPSISTD7Yk$2AZ*)C4<|#Xvu7(2n?17 z<JoA&o+G1h6vo_YPiHNOc(Q6<^(EI`Qa-QTUhP7~q6!pYI{a8{(SL2B$2x#hBqF{Z z8FQfk(hPtMf`B-f2gXJEj;()A4GoPSKI(}jvMz5jSbQ=Ze(aT3Tt4qLH(bAJ^@@}- zT%wLN$C<~)np}qZ!bC#S_j9r^UHP?Qe#lOOfP{1gJC$(E@ABC*IR{vel?1tBhPefD zYoszLYHU~_=oM;J?gGy<zkb>p&#b-vI-s_ue&M|Gx!=0)+tz^n(wnamzz`Tl$tcnd zU_VVh^9`69KN5zS^py)JqPdOKmUxHbnMNu@EacHbBMQsDkv5;6u4k%(xAkelDgB%V zSYg@)`D5W2x8b1JF#ncM+?|^_``CRy&P0<lOm_)!g8{EdCQzDf7NNyjZ$Euy>X!@j zb9zW+co8Q=RJCQ}X{*cbF7mrwem2gGaKfGielUsC0uCw%m>wh{4S%nX<n);g_%wRa zn<mT^FbU=oh;qUTTC1z;KKaR@+qG@;mQ&yV;oK9alC?#B?QPDM4p%JUFLozm>DK4A z1e4jOKmQ}^{A%UMsL{#d#fyq(&Qe!~il5xH<^BifbamDL?O(azI+5Xso&|3J+O%0m z$A^j2mo$>VXK8uaM?d;eQfC5$pl$@G{~QpW6Yz1?1UNta%p7Ozw^Q^irZZT^#mHfA zu@TTt@2SJ*5XX_E8ENHk1+uX9cJ%%drUfqNj6I%rYM{`e!9$sB6tgHe#coYyaZ`j( z&?W!?r$8Mk{BpUpfkS4X*dNa(e8GUz>zo(~C)03|V$2fH#-X70Mwif0g!Z)ZmlXi9 zXij9476d`<!b8en$Pno<(Pyjx!HRNjGM_}X#NqN#bF96cz2HfQJ5y2p^zJ?V;n3Ws zC3k)FLmn%3guuS8h^H)KS*mNCULo@1#d3~~KprykpaDck7;+#3=-^LJGyuZ7fTOd3 zQpLak_ErCcv2;As+uNTSk7h<gHefHO3hU}B%PJ2ZJbdYO8x(39>gNEYP_vE4r3i+5 zQ_=2~EDA(kZUezlNV!VxLZXEu6aW0@KPQ35-FM$@Dy!f0^zZpfW8ni#;OADe%erf^ zRKktf4k(>4Ndz9@bk#!3@uQYR*aM%Mh+_>cCWnM;<t9xhI0}t1>(N&jpWo0Ux&6E? zrqKx9(;XLX-W&mV6)|B!XTWbj5qOs0Fb>VAV6Z4!SVCxU*f^ifBX?-AQs0=bAU}*# zFbP^l1{E}=Cyk>h>!=qMaSjJDOEPQoVAr#9b>X~Ow|?vseFP2c=*$_DGiEl;zVb## zboBV<U)2>9*LY`6c!SmguZqQ0SGy#Y38Yk|pN%-n_3Mkj^FV6ze)WHZ-8JQ+HFQ`o zBLYXG{dw`J&0C&&%H?n*(iyZexXFRBO%sH(wnC8BpEKnw39w!p<_gJoaeA>?QXVgH z<xrW)M$XP1;r?z1o4%9d$`i=m`~j=i2knYx#gE6sP1+oUI!s23dNtcM1rYx&;|G2* zCl6FY0nt#c-IRQJk#0Hof>@EDK#^n9L?H5e3%!|8rhjrMP#kDl*wlKUHD|H4_nx-y zc==<i?p8B3SLg<3@)UM^V%MqVY4%B^)c`nGw8$zEX?RH<)(JXqWSyenVYfV$+;=cL zHb%DUn9tuGi*GyGYH_+YT)T1E@+Mk_DT?fY<)36Nn4}vDKXpl7b+McyBVYoXxpt<T z>{5jVMFa6u1c4+9h5(IeQJ)4Bt@r^0nb1hkkVc@&>a;CvYK)JDtl&YQK>UVNR;MF} z%LhdRGoQRfw)nIPcluRtI$=>D1Wy||lOv0a9bfpu7Z8OpH{~ZH|KY0C*x2}{2hZZG z*&dEGNQZ~>I6drBDT90@!mSFq#eT=<aM*G_^hQ311f_H#8w+P1!7#$-;zX8`jGjO~ zYk<X-Uted@l=I|PMuQ>)qKoX}GAay*i4rhr1($>2;wq6&<Amml!sbZKJ@x{zP%*bY zcyww`%z@Ptqz_a>WoD6Dv59iX(5K=_r`P9k7o_8c-Q&l=*<MyzRll-|JnS?AORWHi zJ<+gntt4r%loT0RRcKd}BTs$ppO9^C`saU9o=TbY0)K%&AgN)8$5eT-a#^4P)B%a_ z?CSjKPk)Svp2->&Gb%p(;SZZO{2*;DK%LJ>?<@(h%sE47PCMfwBu$DapSg&!RoY== z=Ui=hx_R?s9pj_kc)~k-zI*A4%V#%;d!Sv#>^2Cq_6!y$1OUgJcWV3Zl<=UBCiUfn zEiMYpOd5$qHkKg_WRit%cey;oZ$a7+;ARgvnezs`{v!Y2*f7L<^<^v9UUeyO*mCSR z8taa}(>q>!?b3?%0_c!!V!dc`2wos)22JNXBsS*~Bg1KgsK-XWAt_tk{FIeluC9Up zLr0xNHn-WrF6XZHj)`P?@#@vLeBf394xU%!BI?j<PA@q<MCKBt#*5`#9037~Gm2F; zE?P8p_;h4q9QU@G@bZkuLRfSMsA^KhC&M1A-R1S!MVTbH6&ii%HS5H`(_Ahd)ic!B zJu-aN%^O6G!#yk@1W<tFcf*O?fxTqR@AtDbz;ReMa3tP6uD}mG@IWLIK^p$YfBeVq zeeZi(Jf2$PXSDsdothiKyg-Ct+Nm2OJHaNI$Yku8WRi|kR=T7~OIVE*abJlRY)m?H ziJa9FL0N{0j?cv-ECg0ozP}P+Px#QYMOeSBsprOZMq#=znA2aiT7;3w#*Az-6AMMg zhR2*%gw#M$RXLuNaA`K&7QG$@A8ZFVC$l~+O><6FCLl?jqU1Lr$9w}vtk&U$WGbC` zWnmfv7pVd10BQ=Q*Jh>mfG7pgbt5&nn4$vS5=)1?c1L+pr5%#&C{%H~8c$_k-qT}E zEWB*Bno%UdqBV2?C&<^oc;w;dcf4YET65{_9e3P;hq{TqIl>Nt63ruzoPXtP;h9M@ z{}>9r?D^EojE|&|aXSJ~k62WF>Qn13Tet4d|IZ!iP$6MYh-k~KvFy;A;DUpFoStwV zhQ0`ift4~9AXD{gddv?}Oh_@$x&GE--tdN>G_c7M#wW^QmsgxPdFt@d1AF%G9v&VU z>klEZ&Ym@Q&H6QKFIzRUwni95r^R06iQ5t}M`CHylC?Kqsw&mujmr*n9Q9iZ!imt! z&%V&OVqxLJLYfRunSy6SAq_JjYG~;PvI`he3alwVYOtnRe4%%MuQ+0&kw4X$JayV_ zBw}uFdnVNqjXH}8Z+YLX4GR|WC{6`7yD*<rFx4eJ)Ebe=i!PRPYXr;%qG!%TZ~`tl zRk5_T>R`>0y~E9?jxQb@^aRSB0BS-FpXhEq-ZB}RWJ4s3-O9M3N*zwk_6Z3BmeVRW z9No5i=j?|1<%BQQ5T=(S=n7X8_&o7FcpYC0rwHq;M~yX+&6?DAdKAI5Se%j~2^vh| zLge7bAAkJ)l-obR3n{XGXgYspFZAltzf6Oud;?--NdUL32%gaoW5FO<?Gh<9IjP1% zy{FnhyOkBCs>JWcP9&4C;;rDo1<RkYIStA5La1P#=RcKEh33oQU-kQS^%u-R;6%?I zBf+`(XQBpl_G5|NJ9iyEdL(8fh#(a7c#_d<NuX}9yVv4ykZ3EMh!v<H9GyHV#8e6c zDbz0yh-RI6Os?OQ|3!xkBD7TspG@&5)v+aIGVHEMGU9W2EOxg_NNRHkJRT$&i<|w& zR3eMfs!cMs<(A!YbKAbdJukmpIkVO_G5qq@?ViO8t3L8UV(yCz4AQb)+0$xtV(gc{ zek_y5jo4mNQuGP7nRWVVL?8;(SGW4SJ)9i@hHEv6f(27%SRM@uSX3bRI&BU&%qy2u z%I8(ydCFU)<}?+(_7XGbXWx@mC!X7~j!=@BIjiiboMOaG@j{%lsZ<0*J``{I9)Lu& zEV=-FCeX2_1y(dWC%@<$_?16hWG^;<RcxKWJ0PNrH55q^eDTSr9zA~YSS%5Zgu<o8 z74dj-`)fO%dG6`u%a`JCcJ0;INOeJreTGLRte4zzg{l(?zj#AYV_VbiU+<`J6-^9| zzWDIw4}A3_un-ov#bvQ)5?NqL8fD2QjI_<c{;)2l!c3xJLwDKvMkxUG#b3_FM{euO z1;gXEbSm!hA4$dA?Uu!h7m;w#W_6IU%O<J2r0<LrNBV}-I?HE@LCL@2;>Wo%0s@j6 zk8nZ}VnzW{g6fhFZM0T6*?a{)Yv;|LQCU5FdN4E`0!p(5mar{x@c7{q-|4vR&fClD zX9y?&5Cmo!4sU(#dHmFGz4=yOh0mmOte^}VyHkv;Bj=IpdO4tXLM@HMruk+QshRpA zb6*BbhY&n#)~v66?Q87*;x&LAj9J#kYp?MH3xPpr8XOCj6*e-PGjdMM6!J^W1XQzT zj)L69_%-F#JOf%K<xHyK0rm2Z=3hSCJTOvJH^&n!J2W<2<uc|P$wDkM4QDO_67gic zvgK&WL@eMIP6g<7Vs}@7e(-v*k2sHBNJZEXBa3;R3<Zi1y}^gJUJc~7+`p-{?PS^9 zs_X8&wRT>W-DMd+*}r$|iRfh1Cl106myfKeqB}wTCprlm_RKPTSm7w#d0pT}iAE+; z5wL?LjE*B@h*1>hHr#<6NEggAXeldsyQDUz80rfkqV?0V2NJU01(A7i<Aw^60MEPK zj_WoqSiR!#?)^h2o4v`@s$1R{SkyqOH)Z$BE(y1D%;bLh-TRL2JF2W6BNP9`r$4!3 z<x1)SAURG`-|3U{Z|2XA0MmcH!NeRI5KODp$9ys?3>Qc20wlQ@pn`PBk+p(1n0Utu zDdf7OXJEYw8bSN4Eqimy>w(_L(=Jvu4zj{I%dPsNIp9LGHRR~`>nvORJXQFKqTkA= z#!w=FT5PFU(&=^_I&_3&&bxNKmNKI8M08$#1Bj-scGmFlFd<huIy#<x=Gm@}uINPc z{de4!HZryIXVy10)Hc?NYK7XeYQ@GC0|&bXTY5_iiuzi*TAw?-;Kn6_-2hTN@n8r5 zC|uIT(Mq0>A`PGudUyriiPw=4Ss9o4(_Q1u$2`ddAqhrRrk@-~Wu+T$ys@aLh^mOZ zitP=nj3r=pjLP`VQT|^n=jI4#XwFZf2_Xc|wGbYm#=Gu)SI=A4IM~}iF)}gSJv482 zLtse&kMq`(tvP$HxV#u368sA^=qJb9M|SMkQ4%P+?6xZj#}*k(_$wr165($M@WL*u zHe}LUJSG6;A<`VUGuF);N0L1nG=6OT68rxC`|k(kk+fs){(YBiyqXuw4h})~q3>=y z14KPz*2-}jEP0zCRj7r-?lw75ur;{2dtmsX2b%BwcEIDg^G`mfuDD87%u=1F)y^$P zzW3eYL?Y*LItU;j!-2Gw#amwZRe2rcMxsC%iKyM}vod1BH3(|HKnmjw?yxd2$e?f| zXb%x!8S#kPvw0i1$mj5^UAks=eVy_%Bt}tv?X{MgOi!rqcq@X2G7`?5&%=OG3ndAR z7!#q8FHj<q2@__bf9gc_lEXEKfL8co=cNd?KeXOK9+r{MS~L^KA#ay1KrjVeCP;{t z9cKcowroKGKD<lbf0Gzs8@k<uDdN3a5sGfymP-#dH$Qp*k5xjb%KSz1KluI+Ox33w zd;uKJjsP<{%)XIIIh}E3#h${)1f(!;78NU#<S`9ESS84xFiX)80X*4^#bQKHj3g39 zd&|AlW5YR@v?;PVYhns3k$2#Gwfl{5S|-#08Jf77Gh<=TShT#tf(iK09KG;0HP1r> zYGC-roE>l7;i2$@5B}nn?OUw&?82r6ci#Dt4Od=WTwIC@4v6aM>Lu?LrM<KL-f!N^ z{{Q;*>sGE=Syo(z8<I3ZzoDc)xaz8vn>xEOq>c>7UfuNCf+b5-4N`o@=_YMz5)WYA zBN>G$>0IL_+9=J20wdyM)}Y;`n-BM&JW(#<udClkk7pD0tLKCDPy%u*MQ?ZrmNENg zp2!au%Q-j#CfL$&4G_`+y;3AmssI>d#%nEISXEkImG7Jhbrw~=yheZrI0W92D_KM7 zTrQSuJJwp^D_wo*rE+mh?c2Niifga1xN$5uaO}n5GLbd3rQy^or(Y~Dm~Kw~ZD)QU z1QYoW6PTx-dWy`!@TQOb>euToy$thLmLk~L3a@O!wIp$xdQ>xt(kXc%oTD944eLVT zN&$TGNo;v__y>=bM$<KG8r5yrs?ri7n=604s_`xEXdmo<h?S9cB#2{}oiu!2AC?*_ zo{(t6>?}IabEX^;*NZ%01m_Y~<iaVSHa+=_y`V^j6!%}uL&o~XPaSK`ri_x(iusEc zp-oApa!#>YLkPuOE$*=z0hiB{N=phh9z|CiOTV^b$D}1k-k06uu{ksAR$Q?PvJE-c zC`$*)Lenhn#rdffaz8c8V&S3@7^X6^mpC=woI*-@gLxrOedS4!TCE<Rh-FZB4=O>y z`{IeB%?gt$>Q#wf{`lWVPP8<-%6gI$pZoCLYgVkja3<I6>Dduro`IvqpO+IWYlH1v zm{f-gD9I+&_@Fv*csx8YW^=`gD;uk;t;N0uYp(NkS&rvW{6ic?D8$}GZ!Ab%)?_^6 z@(KSWQ%K=9!A}%D*?i`&3zI!XoAvK-#HOHWe#_g42>~N{L0Ng=_B(EG?`mGOXu(|{ z`NX0{P19jTK{qwE)x=xD92Cb#QnP*cyWeeG*jQaRg$mi1PGxb$qzMZ*HXS>3<m79o zg5ILBw(-L+99(kOGN;Fu%qG$n@@TnoX$eBaTg_$)pD|TX+c9Q>pil<IqLCwqt<f+R zViPV;Pb@}&kIS#TqNKV?z#h~E>!@8n&3fL1ZKjsPRMi(h-}@tw2MEDsQ>XfbukfPa zGp=gr$TNHn!Wd*-9&P7h_D(B)B~r&^=7~oi8y}un*|_ZVftF+>(Kj(TVhv-u1+!}R zc;SV?b$(O0;aQ+(3SzVbZ9>zVU@AX?X7nq*5GEQoq$i$ug7arLZ~4q0A6v0<IgxC{ zURlVh-W{RMW@jJ_a)JScDVfS*Atnzy*0M`QT7d9qZu<^<caPm;Eo@w*%F8moLTkol zi6<428G=QIC1d2$sa(=-%{tgSWKbp&>d2ASV@JovCNY|}`dpX4e}kGo4}~XI-}&ZV zFdxGDAP8VF%zmgj<`Cfi!O++!8?i+Gk-ZF1j2M#UXV%CX*tt3gM`$EehNuNNoo9Az zdV2Q!g~fAbr8Ab^*3;Wwc%`pr^t#)xcUB1a@ej@h7K?kq@JL1?XM?sxD9XzeTmXh& ze+{>CNt^Bizh=|qU7QIxa5q38%DiO8h?3pX#-=g4Z7tPg(q3C)VAuB6Up;tDMe&Kr zY;E0wyWao7{Nws*IllnPSrcH!l)zCc2R=Zp8qHaJ;D<x|)I&cW-StYdON~`l*j)Zt zEZ*(+-PE$5oXq&ql6qE_?)1RIX|a><Aqs)HlQ%So002M$Nkl<Z&&xg$nXNRa<;Ps+ zQ%JQ;r+GAIm~9|U!sRwu{8QvvAO|);(`?y!m1kW@50>oOb<6Mhr~j|GxGGrS#@i6N z7`P%JB`u<=iW%h}`}jvw>EsXZ`_a}Hw?6swlOO%~UFjrA7$hpKK%|gi!&c^4edD^$ z=3Yz6<xJ!bZ#`VQq^4*^DGs~ZWfRa8K2TIP8b<T5$+OaDX`GZ~LUo;<IB+14Ng+%O zIUJ|b*_jI$UPEXF?le+1q7SCiHXS$Ge1hZjpiN)7cyi8+06=TP?HRKOvg2AB0TC<* zBZjGO1_h24{6qnw#T-=k5OX{UoX(CLaGgwV+46K(Z%=466dsHCoSw;%3474J^5!+7 zr_s&?iQ!~h>xo9vwFXfzK@xcpZ!tkgkR{cg(GdNPse|bzfY%dgD?jw150R0EeYn%@ z2*D4pT)vDa%?Ht1*|FS^rpuH0+W2n13jZdynrIKN%^1p_QsaH6+YdY3xr7gWdzG3@ z+1PqyMWAA`BokI^JQv6B$^y(|QQ>AUTBWz|+48gdZ~FYFEvr_jzTqwR{>!ia*Va4! z@{4NC)w)yDZ=GuT`TNPZGK1iiyv~<FXJFGR5s6tch`daNASiBv@sd$xQrPvg+M-yV za+UZS8a9S-+U-8wu&B{ph6AN)C~6pN?>lt#=;XSUWu>JVYnJ%9aDphHsf;?b-ImER z+O*yqG{!$f;3+nX`{YkVF<L}BVJ3x_G{FtDDIkHMg*UPtBOqEqwK}aE;Z-e8YeJ0; zcm3%8t0q&PqS8S%cE{&GRZ(3j&`-4&QekAyvam_O_(H$XbBQ`ZZGTyP>)%ekyt%Ws zs^YKz;fgCRmz|v5d(;CzQzIio=%q0xhX6}4r%j)GU9xKdM8V{uuXbweqi;In@TRBu zI{lZ20J#FxXcVPQ0f0Cy5NEQ$A*~}vgsr-^%3^f`8wl-yNs3ou1f#d9VEi$<BkjhE z&%Z=ownrX+1Z}XNFsHnTYGrr`t13oRGgr-Sx@1|))@GYwAL|<1y=B++^*4Kqyh+*O z$T{FZc|kTK`y^8GkYx6Nud;E%yN|WRjvouAlPQbqR5Cr_bl-B_bqf|ZQNQI3y91<i zt(t!$G@5l?U;wHI^E^2)b)xyv#j4pXp<+UN<r5N?FbqT*z5S1Qia}UD;<<_wC&1&h zt-NG)eSJf5pg2J)=V-FLq-;Dk=AG%6CjqUjn&_F>{Lq#{<*!~lTRVqv4WN-wzSKVj ziu(0$Ilw`h$|30Ph7B7?nRVd60UG?+V~_puAAM@}{CZhvJY^FLW&X^LXtb+eVphmH z#2iAmS9Fi)9kYpeG~&u-;&i2`P*4L%mLdmhioRj{!;%%K#(+DUjl?<!dXM*YUx_GB ze!_~thLwwd^&hXOo?*2prfld;H5!pBE{GzyjS0?kKxq2}777deL<&m8<35BCbH`TO z)QIz<<Oy_StY{_eAQ5a-*nk~N#k$9bTe~_gTRmS!&7z7+3gY3=<mhObDitqE(KSPA znVUTAl-KfZ38la;A_lGSiF&}N!AQ%#fC2B+_hP#)f;7*_ccw|#L<D`rbb&xf2JOq@ zNQ?k`K!m^P^HBD|2jiPxy37^mj>Oh4Uvl$pH)0KBR&+tk>r^N8Vwn2!`#<&c>xGDQ zW0Jj|$x-#=Z%;n{Xur!F{J+1l_^R8KwMf|t)!M7nr$4VsXACQA2$hD+rJfR=MZXaz z|7S*>I+2N!_a5Gt31cErZR6Ih&&`(TrOv#?G5pL~;yH}?%u39o#Po>c$}P;BSX<IK zfRSxxd0K*A84~v+tD+7Ed5V%mgO4O96X}@UVb4?FObXbbVYPKN>n~jwEGlR{(X#*0 zeqkG_7Q7~nkv=EcSN5wl*RL&}U5bCYEp0uu=Va@PM=fbd#(<6`k65KALWif@Z=P^f zObF45@7U%Z8%2VcRGCw$RMFzaSKfS+yaj`Mm{@^c!kED0fKbmE37VigW!84_cwUSE zT16w3PNdR!1ORG6ggj&_kkBq!^s>Zk@jBR)(cr|Ms>@PZH)GD~hQirpmCI}DE}QF_ zT~M`ZR$+Ci<b8$f%c@Xcc&vT2<+WpKz=T22HZ_}4N**TP&d`wp9k*b%W@uH*iI%6H zc~X|EIM#~}5l}b(@>Pk{!Wzcpl0QfV+%5Q8@BD$00|ljpB{_Dgut3B;(T6cL-PMoc z-bv0S@|SQoSBN{9%{ct-$_?wT{mVb~*Vig9+vMTsP&a-9vJH;4$XTMRx6|48@;!nW z#8{P$Q!Odw<rq~_TkS0lj3>gQ;c;AS1v#L56BrT#?6wwI?0z<d!$cD2`GBKt)#5w< z<kM?!-T;D3upjJHk!)DGGrj^%y`kc|AW-3bWQ5f5gPme?Ad|umv_corIOb2eX1<N@ zU`k#BeiK-QN^`rkSS8`c0BM3qgJGp7JRVo^h}yYd{ot2f-~QR${z+dr>akny_|WaX z8bVic+tj<J-gDl6o;^gf_!uQ-%3?=_bgWsu_<VQ3HNUvh-?T<%&ElT0*pgVe*UZM` zZQNo_i+YyXG{+V;Kc>PV_3YEezx}@tKfkqwnbfi$pD8mWhB@e(DQ00JUy6tcFmOZ_ z!k-XkfelYaAzrg``3Xfgfd#bBxPB2Sha7fRuqT=1cEL}P<e1M*My7n1iSuW-+0jKO zQ%SeWjo?d)m}oTm^0t>!n1KLA2(>T^STIDRVw+%7g-wAutLNl=Ih(_p8cjC8(xQgg z=Mv8hX#xPMJ8HI{V;-)7J(`P=>hMVazCA$<&s??%yM4&voOkJ^bCxVa3g<!SuAH!f zbUwK0N-mz9!y^DZn18wtK*98S;{<x*5=%i*A0kfVaF&I%fx)zrDF;)B%wU34mL&kY zt0hG?R<sgVGEzGLD+zor3l9h4j$u#Ab>QU#r*<}*WcT%#^X@YM@~uOP(gjywj{JlW zj8j}qO%3u73eabte|C6mD3Jzpiz5<@gKoS)^%Ux+16u#7GVWZ=9vLMii#QEgJ*u$W zRZ|;xdMt)5cl@*n$jPYe4P&d3&baWAV9P~0ywr<ciai=j&cCo>@rQ0#<%KFbrgrUU zKX~Y>TW(btow+SJBc{jWt<66_ujI!WIAHn&feJu?%p6s|>V`SCLRTb{=o{>l4G3;v zdT_VyHlicpTq5JfC;-*Jj;?KW+Gj7CYxlXZD|Z*#M!Sc1?tN|Pip4YP!O=_|m1-VP z$hGP_)wAuH7ju(@YtaxR3Prg=3Qf>QP^w1AA}8oZf*s)i5Fn@ymnD&V%n(arjY~mx zGRVX*s+y1H9(wf9zkJi*(Nlx)l1z~Gymswc<w7u?#+Uk$3*#^~vTw7uGTw&#u`r2w zg-Z2^F*ymbO9YBzRk(P;r;74RPMFqQ)|N;nFy8=wNFhi{Ts`~T$*=wGQ;$A;=&@fN zO2q=Q7p8y8S(tDHS()0L@Wk<q2-)Nj#=XaDC=Y?9v6P1!22pX$kdKmSMFpHv@vxd0 zRfB^<j0GYr<TQn$^5(LBx1&tklDd4ZVlbAC4G0ZS&{SRv4VFarN>$a&Shiv*dtiqT z9~NUOdJ6p&@@{ow%ZHeYO3kg-y>ET_qVl9Q9<T@7cC{VYatKVKbG&3y@hHQ>%aLiM zM>G<%Raq~r4dBsGJ6=uo^=1=^h~3(eOoZK@_kHq@kRQm>%5A`|c`_X%P^#bu`R!sk zXGcH-60kHqjes8-IiNy|jRGDb<q)q8MpY0S5`{<*7Hoh4RDnfyQACP>_91Ja@)5ss zqU&pIu1#Am3Q5Mn?O2B|=X0k$&p-Zr=)?px7@1UW$!f|8C`~uwEyD@Xh5DL1!SI6h z_4SxT6F?p2c=z6&Cwoq_XA?&il+9w5h!?O895A&3NUMc5Q)eonq7!QWzV@F!th&Zk z#zlVE;5Anpb#<1gC3|8(b&qJKHm0&s)jt$H+TqN2a|wr?wN9iCq3wh(q%)3V+qWJ2 z)r0%)`*DfYS$o%AMD0-4XvSy5;r=acKW{GpJ2-CYpgdYS1f_BbxNxdv8`dmbzbvd0 zPd@k5@xv`>1Cv9cjvXy8J-W#rj=GYDB@{WjZC9vkg4{zc#tbcFl4uRe2pMefSJl>R zylR7>Y6+(+!ZW+I62m{OP98bgex&XB$6prEWQt`@IGciCJ~j1~NAw>X2qIvB$7vh6 z22<Fj>K{yyptX3xSlK>^s#jkf`}==r{lQOWB@KU;u!%;_?k=pVQ2}j@O?|-7ZwJxy za+<Yf<1Bh6&fv1vp})8ZkZ1wlGD#~X%sWE|*>vDzz^5Kcr^6HQ7h+<<SA<EBf!D7t zzr4P&vHtLW^~y{8M@Er9aoW}`5M7oq1c_7@xc~%3mMyXOLWyR|mU?bPgB?|4BWk2y zO^m6I4%Ob#J2cQ5ik|qBKfCdo>t|`FxfGjcR0SkRkv%f@AEa{mFC_lWg`ME4sw&VB zp>aty$T^ImXnyFHY}avwi_6+)SQlNsV5Dm>HDI{2?$#Zx^On>Hmcbw7oE~HoDGox- z2rP0U{gJ&Bd@7>x(f#|ZkqFpz-0eCYjjy@!hT@tU#%T&%&8L6oG2frxdC$ck-%BI# z8}W&rMnFTuA$I`z`Sbh|kRIgcTJF)6n4IeLS1!wznnuZjxsu(P*m#V1jsTo7ZfxJY z<EGl1mES6XVt5poG#9{c0U^<7nR-s@)dd<HEbvD|k#IQN(Rq65vehCip)Uqx!OP(4 zh+!`fP-hcSSnL?Qa9aK17uz;H<E&df=gv>4IGS^hy7Bt?-F+=T`Sreo%}XBJ?7nHE zDhmwm+aKG0=)~Rwa|?>2vDidQd*KV))QwkVQU9RO&KQdjc`J%k#mvsfp4s)U|F-sX z|5L4BLViY{j^iZbb3qhQe3;WOBR)+8iK0CxxYmA|w=8)2bo(pYUVd%ocBjMUHQe(S z&K>bMa)XITcJkEe<JnTn693XbNr7N!hdnVAd+O=UKCl1w_uX#A&Q#D7m4aRY3r+tf z)ZmFeHJR-@);WG?vS@jb%K~}4T-Z0kq-KlsHKEZGHAPxU4Pp#NG&lAbQY8DeklEE? zK|*5xA{I(M_Sorfeb3v{KHKU@#R!9MgHES$7j}CT_J;r#bzFGmYzZ)YILvxl_;D5@ z(MJ&ubE$$r4YP*|%^_(pEPf9mtyI@2gwq;}WQ?TOPXcCEY&uD%QeUClU#JHAnM(F+ zabnV=&g5o=4?<8Rlqow`Lc;MRj;TmUO|mV~Dnz%ZTlIFu2K(c~1M$&8BRrW(rT~u- zr>E<)f3{)%!dZqG6rl9hP;25EIRbqYA;}c*h<S465fNi{-5hYx*w|QKU*C)wGxEQR zmPL>b28YPo@ElDWmh`mtG;eA_2<|=By>IK@4Rfz>1d&ICSHzA)WNW&E;#(d?ajrcx zdV2bH?k-6tGfro>a*X@kcYWwXMTL^kP~Vhqli6gsq>-*b^~G{-kAO)y1>{VylPNVP zmkXT8?uz-NKG70}zG5EChvcUzs6_%Xi$Jy1B=lQ#w{^zDQG1Rs8CD~aIr{36xr=5u zT(?N};)IVRl#wi}-(AoEL43_Uqa{n0R8>^AhfbxUnL`H--g4XRL}|`%G)l9Ty~vRy z;F2<|_!PnMc8^5A|DB;HA5@cL1&c0M9&ihpjS2V_@PFp+)w5<Ed*+4RFYh#7-EFTZ zAR%^bNm=8~8&5sAm7S;42b<AcUbc8aQDcMf*94JZW4nHls+&`nNcMmIoAIAN;;C=& zSD?hYkcuAXJhW(F0V#qLkVrvB{#n8GHJ7altqzS(q*F;hnmT`hDsV;mq6tJ3M3<o5 z74&)n+N2Z-X)ylU_MLSz=B~PIDZh@jg`6I%zs`?{BPbClN~`hSv7xqppWz-pIdJfm zy&IQYEs7en&>%N?^%Ur7Xyl80H{q8v_VX=BTeL10G&M75CTab^5aFIr|Kb;((<g%1 zJfu|tNFP?qVog{rZl7Nfh!jo|D3<D`z+B#U{+F{Qz%n9f!%CPrOxz<0wW!HaRFsWH z!|`!<Pn!xhDZhvC%d(+UQGvp@$c7`WMe+{d0_5|$?2aVdGkcvAlSE}V+*rO*A;wi0 zXV~m)d$B#-)tNeVVgd@?-*0Jc9Xs7I9#7blNgJe{wMpCyMVLO^9hDny-;IjKVPCPX z=u@9vIHL|Zn=H@}T5ViF)xxd`C6}Co8vC39LeiHr3q%(JOq_aXFrqMuIQ@vJiPmY4 zP@EZLz6`9qW>xQj{>*sBnQ<Q8zJLC@*;VUm#d#^<1b<1Lyi0&7t@p15{i*$ja^1Z& zE9vnbH!`J{u3xlbncQ+ldDGW3e#x&vuKbRB&b<HP`FnE&UY|Y<jnYVAX88b6wTPqD zxn|?1Z#FkgwC2zJ#k^n6HR==?@9F3?5^0~^?UL}T$#^Kf<H=VVmMl^g`Z=vzntu4L zCuY2RU|zspFOs=)=VFc3aq<)Zee}TLOgu@je={DxsKF3>a!FF!5CKHCS9Tt3zxPM# z=n-#Ecm1qtM^!mtm=wN+2sVk7wK$+|y?)WUb!s$DCTvyURsn}9@u^U#=C<opS*;2~ zPkgGTEITlG^k)ywC@wAg@Q36Tq<E>RDM+UV_wAiEfnWa=;(u!g&hIOL!W1-UK+*Zd zIYZG`>?$d$5byzt7%`jj&V{CFqAOO>`YJegIDUBBo?^RyPUUR5c|<kuJv4XWY$3qJ zPGQoym{pyvUFnH*Q2A2fbjP9g)h%oNONdznZDoH%w?SlJL8%nMbej3o-`ILf!sLlc zB$Jd-D)^^kLEGLo_Jg1F{_3gX(UDSXTI~9eQqsss5}}Fx6n8;^ayxbJH0GS@rdj8C ze>{5v%!)^th4kTa=2456svB-<c<|>Z`%f1g*rAp-32{Yl3=(*3lj`dchT7w`iBBL8 zu%l~by~Z<^LSpuygvhX|1omKe6{3l%IjIJF)wlk6=a#2h6Y&|TRE67JZFQCng+_>j zgS8eaEh{1Gti;5D7Y8sBAvM}qpZl{fHF?XZo+L+vopxE-pJwWKBXcT{MK>MtNzt>c z&!!G~%0WN`gM<L%j6tGu^EZ)R$<>m}Vl0i346)h7P{5(e7F8~}X349MZKn~T;qam7 z_gB@`+GijH>*r9dr12*~mO(cUbAcR?%Du9!97VKJqgG3&)p5&hA9NQ4sngWDzoAiP zB~z{AlM80sIhPKd@zcfA_x=c=!_$q_x)jc)fJ82G&U8-CsHT-~g43xPpMnunVm8S( zxDJgA4}{fF&p^g7a)f{e;4(H(#xvG2^2(!IulOI=$ooAySkmk9t8|ObIG99tS_{o` zC@d_jomIDO+jiQ0`b0aah$YBAt&mKDh(xFsF}{e2S;s@04&V1cQTLc<Vw6P2gQ<9Z zWw|VA`h~1Ugb*W&p@f=Msb*p=J6CW7A(|w<Rk6y}k#|Q;=9E9E>`7~HPsf9s($%$P zSHDjcgCo2cABC*R!m2`5S{#Wge_m&FM$^yZQxh<zAb^hQ5tR-zrC`G>F`Pj%h>v`s zpobJ_KyfVw0}^qcXuw<urFT5?OlNaPd1+<1ZD4{(;~4QIk}DU?6XhUG61bI<ggSNj zq%&oA@uwUUJ!5-c*|TBZMlhauXQT<rK?}qf4D4!dXvj;Y2=7RYXb`+mU)hbs-a4)J z9t?fw`-xq93kQcw?G`5#7cC)oV|OTtHranpdkV<IVMl=?G82UTjLzzs&+~(xwzKIY zvK-Q?IA9Aaly-a7=f4oV_4bNXy7Pzk?ce&08tPUZr;L05b<h9)##1?@)=Y0#@8L~P zMp}<)&p<_JQu1Di&fmzA0|U-V{KW;b(AhfF`~~X&`SKO-|KRO-Vc@P7PZSP?Twd#Z zw{4cwQERoAWUSs~77u@GhAN!4>gv)@e|G*Qmn)x7rE&z>2&PjQzH7yviRtpa6X+2D z`Yi=U!AnvIEx!tE&>U<MBvOKo#R^SL5oOorcLn4}k6L}*Du1mnmI?>mzEk^79ewGL z0J<I)Mn=K_33Am=k*tt`f!+fLg4j7{GyO@!)39*Kwb!#|#QH`a`&~uXB6Yo?H^1wN zi@&{hMj&tduc7-lO|<?2$d?pG+7^bUYcWO^1dEe%fmw6<kv2r&fScsR`~{<a@w<x; z;nO(=7KCt$`&`xn8VzLq`?u{MI?yjqNG(%Gefp*YGSHb<%q6g>ak1X0vkv!<cC~kE z=Q!$yYsA~sP-Ek&qc`#|-`w^O-|%;~RV2rKnMv$@l1AEESw^r*;xLJe4BAqcJ?Hku z9j=Jefqe(zomo_I<qRp`gw>sL`f_C@66y=b-++7BnpJb>Ef8GHY8sn3{MxHym8DhJ zUIAb2m)HRpSYg8X6Y!9Z3rH}cGLxF{BGzD3$}XNrQiS6J#y}|mfFT4JuWL%m813y# z+blEZ&o&^RZmX-vow28@=2Unqf>I52!em)hbTHB1+3(IcYzd+YJ8cQoe4u&Y)G+n& za!Dw{&AdX~)6F(W^>St<*ri6Ae1*G0@WrI=iD&nH?Hebac(MT57kEt@7Pr@8Ck6){ zV1q%7xeQ0vS_C|3RU?;v(-P6|IByR!Z*RXaL_(UFFx0@p0@+iURO1TgpZ|5m{3f+; z+o`|%Uq7xW4;tBcQF-P6^~Ib2`QM)|$rX+c^*r+E37c9{Qn;piHik)F#u=Z$Y}#Wb zAP&=kzaN~D0~Q;;+FrfD{kQ*8x@`T`|M++NI=UkPcVif4N_Z=7<vy%1p<FgF4f%J6 z$0s{a2Os%`TD?}4l___TICYqCA`pw9AiSYAOU5bU426mAhdu}dO37lh49f_NAVOp^ zqJ=g=0$?X0491y;FnZK4Wu|S_^((iJyy%G8L!<G-+mBSOoL$^dATlksrxIEL4|w<l zxRp%&$f5AyU}+*rrDM6=vg>awm{l$EzDV(!=9_hLoNCPUg)>in=Z|OJc=7x_Gy)oP zzTO@alk(lfHs+j~=Ku}hlD~BtR=MNMD&$<YVm0Q|zhu=wPj7fK1jIrf5msz4r&;!W zj7%i6_30NsF!wHZxyAY0#b4@z-87ZYEGyvO6o{9uT;V7zG9uCOaAe=!18Xi>$NMbQ zBdV%Vb)tRj-fs`SylpA!p~!f|$RW(wt-jKNQn9Pd#0dqAhT2Gn$<81SMq&x3n~vA0 zHQ*5^RasB070LT+L=@2@stRiEy8ZN#Qzsw#nPhxPPxg%tH2&%5)iu{EYm(l{^8bD6 zbQzoTr2s7egb4zIk0`?53q{6-D@_0&CS3b*W^nsp$Wn%z&<a+`&mpwcZsmHgY38Lf zYwe64ak9cGi{I(+so2PvDw6nvdFUcA!|_wmiLl!Uctwe5^*Ou)L!-N2+r44t)diKr zk<=iI1O^0}`p2m-m9&t6fDt3=A-pgFj)up39(eTlW6!ucy5?6GC;GYrBr9~d#=;?@ zDEgfRk<^3_q-s}&C#?#d)Ta4|sg_8aE|hY11ej5QoI&<H4zY(c(wsmT$CfWHSiY#X ztF@LL*pUGhELLUJDo~+jFSscjR$lidZi|{fS5=e?FcDu5NFlDf4;6OShcKOnk_#UX zfhBjd&{luYd&fsqanZ`}d~5KPms;G`85VmW34@1emV{+t&a~ry&XLY~|MlOR3;dbV z^6avuCG+POT(UMecea{6Q*IGa8#56WKChfECLHq>NXjdwQG=%w$p|WO$fq5s%@bfK zGIykbJqP(52>W504pN(;mR`5Ieea33J*QlD&q!zgq38B&oO87V&*E+?yeBqWgd?!1 z$>_-8W>+#DGmLPtcg$|T^72byC<K{Iz1?ifbOZAzXP{k9%|-a;doF%|PmchA0?2FN zgP@)<p=PU1NaT*GqVLbc=hTB!zsaYrf#1#F%m<NF#(E~x6IrM75z;q<Gn0+11(r}a z=Jxwf9q!!o?CvY>TFcG&(Ca|sXV#cMHwp0c52h}<p`oF;xB!dVjFD|Vc0`!qWRyJ_ zH5pc$pFQ%UpWF8}*X59=CSg`B1lK2xf)TU(f~vL($&7^~Cem7D7hs1Rz`vU;JRQvu zbwpk$7$6yUcwunkkYn4r)pHjwSA#=pY*57F%3@Vnt(kN!*ol+Hg;HQyv>CL9A3Du& znXm!%(tJ`rhMLH}kYcnVHgT#%1p@8W+B?BB3_0#6MIuJ9+2^Qq;_jJ3d0Aedl?+ra z_Rsi*^&IO|ksR(pR+l4{O5zV`i(6ZF9$UI@c|l2)3_6o3p5lZGvgeS1h>oCvnnuwy zzk{Hu%r00w>8UKAzxI;SB})>$%|%Uf)#?6dXEzSaz(bN$l~!La7e!Q0Bh|pGiT9?4 zXxgGd;zF5VQ*-h5d&}T3L~dcVq)5DPSS-c1jF^ekFA#WPj)cc&DlF>Cb>@v43S<LV zzCxi=EHtiVV^%DmnLSZQQ;`EhYGh*VIUy?L8*fncvn%fZQN<6w|8h1n)4*cgSs2CF zFqd)oY(@;?=*(F?q^+C`B}4H{$LW|&^_G@Q_<h-?#u<%^+^g3}tFUOs{R!3?#f*d{ z)j%RGARvHzL8(I2HtW!Er;&|%+&-7vft4Ao9y`Dq;6*_ropRYk#{&@25t#Xmy6l73 zboKSe2f~iHW#E<8c;iyfhSG^dCJ3E2>=wdpVm8**9e!<BX-Y+G?vpN;Z`G1T%bO6% z6DsY|y!;zL?hRjLxVVrXZuxeh!Kd!?xo|MW$1{aUS`8a#ijv5b#92i7lafqgdbcYh z**mz0z^EkU1*SMBER6W}y{Yhv{P=p|8z5m`1AO6$hg&CniQ-t+>M8U^B7<I+B^t~6 z3k&0hJv$jc{zA+8WosP^R7%|R^AF<nJ1sn!%{H5A9(frz6bF4P7tMXTqtj`%b$54! z#<~meJ8ElB{_LTaUv3TzhfAEeIgA#==AyuiN$icd%j=(AE4f+NAkqleVhut$&8-#* zs|g`s>Cp_9md4yL%2tvfLDwDH$Qkt-CR+YlHK#__rgT+US_!3efr-C*qR(9YQ<KLh zsx={6Qn<rm$-8F>RDiC)R^Tj+rMO9AOzEL!Xt}PvKEd0vSCPs^o#ZypI+BB_o_(EV zj^c1G7I&qimW0RYc8yyzea8ML_t(v;QY419TMr&Q{DU9-z~S~-ovyn2`m!07*a{T- zee-H+N-IhLq;xiCpH){<T~~6QL}~EEiB*(Rzx?^gJ@-^8TV^5w*(Tb9E$74x+G#6O zff*{!wqc5B!KiHf=Bm*Bx)2U;S?#~C)8?|DzKdCA`N&s(5R#TZ<wIAU&ZZ+)#9Jal zYnNI!3MMDj_y}<*quK1(kt2sro>*E^Awn}|RZa)C%_0k9lLtx1I(^Y%^~ax4O^sK6 z{cm@64>&Ml5Bh4tNo2{8a(eBawBIw7c26cG)GV0{m{jM$fCoOUy{&)q)1iXGc*P8& z3iwwnuUWmmXu*8tb18g(gz#}wimeD#BQzd`dU9-H5+6jD%TrQPA`mQ_9nuX@C$c_1 z!E{wR2yX$N<ix4U=2t9SzxcJsU-G(wk%8F3=MSt~d~Kjgydq`)g~xGo-nP@(*=J7~ zX|KJ{<7~QWqt!=5KF|=^lc)8JGH$=EylKpT+ie%Gzl$SqCiUVRQ$B=9Q#WX~3f#nr zNqspdw1#=zrDKwt<WT27*GuX5^~8J_D8`O)tUEH+H4?NH;BXL)hY4xHMhftS5JTjn zfW08mJNfi49(&&x-|rv~tVYCCKW%TtISqzafJ@+fS_MtxJs!`TIdd$z7s$nHADt`+ zCDlu>^#1yxw#T2Ell6F$hS%vNLlJ6Ep7a%XqT~s%I17V?+Ne@9t-Ma8aomTwN2`;R zU2GBajtZ=hX~h6*LgNhDE=3yihQgw~@K(Za=<(~9ULT^@ubD$O^_|cBa86y}_xu&+ zhrk9FbaaC2P98X(8jU+rUM77kGC`ChSJoMH6|gVY-_qB%t84C+Gr@T9K`(FLHa;FE z!h?~`g<{d7;$TT2P+wisxNyOW^=lTdT2)+Gg%_DSfEpZH?^cr|$rJ4!UtqX<Oc;Rj zU^tpAR_-Lh2+2KMP=-1*4GREBXxrI0O#1o$MML~M*hzw|BcVcuu&X1wtuS3Xckg?4 z^MP!l^6G1sWO5_l`@thMGjpH){0IF$Zz>s=EnEs#>L`9C0Fb4=Nmb5N<<;x%`9}Mm zov~<i+-3`k;G2rfSz!I%cdJH*tG2&#{Lq1((``m*!kbQ&rHz11l_rhA<VZRm$#tAe zJpDwM+uK=Glv}m7X5pf;<ttUg0##nANWzO@Gs+aF-P7F{358R|MV^Y%8Vku0fHhho zXcG=!Q&Z?FNW_Y#FL(@pH#^q;Yp=Mp^JxF*iD4t_*uDRF;cK%N-dZ2Y#@%jg{n*(` zhj;IHPlW75z_K{A#l@?xz5yF?+$&(`A??4zE=<PZVmWt4z$9I?7kWlmM?#7Mz@~7? zPh6i4HD%t3u{|`8JI#B}q}Fe<(<~BK&Ke#ICnv`(Nr!=E(47kgi?WF*!TO15VWi@2 zzayKDHt*ZjxW94UhI*5sG#km$Y#7a$e*5%^a11t=#Z$m%fwC9(h1HLrop|y2?2&y- zv)%w}z?li9Vtz~$=^AyVvV)0a+V6Fhm+4Go`A(oLWnU&wD}Iw6K7ZfEk3aYbXz_{s zmv)7o?s&H~YfmInfr0{<GxU|oD2i&#eH>$hBQ5)z=dPHE8`#X6x~n&A>>nNrMI+<m zlg{yRq?6w6p3$D(S6_WK@X*7>mE{eqR$PC>O_wZRQ&C(DWTdz5IQ87#@_r+S71n}z zzK`8uJ9xNz>vlKkB|QboC#Lmwi$gq=M4!X@`GXI{yZ6F(ngBD685^n$H-7fwoP)OQ zhU-^uxN>DGrpQZ{Oi36rkP{mLqy%<*JYWRy7lp0ZbWXbikw~(@e#r*)tvPf4{%?{` zY-%MWMkG$;9$Rdp$LDNXcfGoCV?!+7(AT35A69$!rdwLZkGJ%UPpWu4mrDCHSr1#q zM#zR7`>RL0>`$Kx1Z-7R-uVq>D_2x3TdwBJhWS$6okj6@U3uB6V6Ylsz#h!p$rZj_ z$S_9$M9j31BV<Q~i&hn!<-g+Es~&29$Qf`aQi(k;?4GxDmamS`9mLzSs)50Y6DNHH z+;>}tEk^C?)$aQF(qW#({)#>7izw;cgZ}@<H=9J13a6<oFw8~s`m}HfcvJYwuf!go zZh%SlrWMrF*MI*>Qgs|{jmIVf9vlP+1DH%r#<Awlq0)1@f&mX6_+*X40_%lmo-Ubn zchTGuaU%o(wM0HmZr}PMZh%2FcW`~m;Y?><_|@Z{j&^rqvY^mCIx$}ARRwH0q3J=n zmB6h(S6W=r#S;~k5>8U~Y~E1hJO2gp-*Elnmv?OhKtA9oW@J$HxAn0plF6hHae!Qh z%gH8*%T1VFdv0?4!0vssnrfPEUR+pM@^^ptcUF&QaCpRRamFLjQ=M(6PoLiT+K%=U z$3qj7{k?rHJ*S^}cFT&UCGWfPs+(7>I`PV@0mGJd7NF0rUVEwf@JEUo8v45i$GZAS zXsilQZEI1-#EKUfc)ZgD*lKfnp;@d-_ADG2hhT99o9@OjLH4f5LWq3KdSqkQ3?M}; zENlgoM4HD$$$_Jo4W9?B3j+3vnd%$=?pn5H>3{tDu6QrxyEYwG<6X+NNcK9sP8BRr z4NdBn57`r`vhJR;mR9xJj?shr2Rhr6p-D&D@Fxs!PSvF1nbBl6JZWidPCohT)}o-J zti(EZZs71?!dYEEd)8IN13^nBF6EF~llqzrJl@R~LgpsKj=(Ga>FFeqhb#@NXU==I zzU{zCkIOO8+I4vAu9Y8Oi~bRZ3}f%kSa-WWlN|S3M+?0xZ@K|gCc%m5Ge)2n7`ykb zA)0so#Sm2UB_^%qoGTQ_7$ljmTsMC*kLJzXVBTrc=`+>B<_*8+2)2qQ`?@-n!x&2p z=ZXvJ>*tR4^~8oJ;Sm=%He7zkbwi`Qr%vo`8#vY0({*6ao()ykSP@z^0p_J90Y+Gd zGv=$gX>DGVV-BSa6c*D*!%<ySe(jazxpj%YQ|Ylj$ElW~j*$W~q9h@`g2Pj3Bbth3 z0)?uqRQ7mqheBrzq>CPj9U`-wp+-i2=dp|BT^s?%pIja})pe|Uv~M(E4S0+ExulW9 z92R*sXGKe#OC$?}fyq?p$i5>@>zY)BE#NK5*{o$M7jOl5c5cHw1lW&%{Nud<*sfhK zy}EsWTWili&$d@yIKK1M-Sg@TJNsARqFz!QB_`MVZ&yXdYQx4w1EC#1`I&4+6q26C zYJmU%DB48eT^x@;{Hxz-0<0NcwsZALLm8FE)z6l+Sv}-Lfb^npHVxWg$7PAa1lg=c z8n<i$w7Ug?>3EKiGR%(s0T27NpZTn+pTG7SUvF+cblQlIb)T+QnIaKVS?Z`V><Vj2 zypugag=f@_x0H;Hl=OBfypZ?pR>zJFcJz!*Or(-gVz=Qb!S=6zY{;Dm*}*4H*MdaK zwe{I#B+|ZY)y#$l`<%I|dWKXh*2<!EhK-QiE$rKwILGdD3au_u8*W_R-rACi8IGiJ zbo-%stLFwAO3A&|_v#LNWYXfa_psTraADo*RRBDu<AQpq^I|!VMgY-vnxvVzb?KZY zyTZPi(yd8o<MB8<Z9q4)nWxwo=G>Hw&vrc0(M0D!x8X_^SI$^?#oCpt*KU92x&7Pr zB9?X!4G`#}ys5hUy6Q`k+0<mHXM7M(bSIe}w2%9n-o-^Y0BA79q`|V$A~~9f^N}91 z8BL%4gz~#oct~6wo_Qkro$p!44T9VO(gZ>ey6hv7h`qW-l@#kWgZf<vuwd1<z`B;f zS+kn^p3+ahsXZ6J{vk$ynTV?6M_L?qI|;9%aS~oQ0$y)Ao*_33`7vVYxCIxHZ1Q;P ziM>1bth#v(?w?tk%O3~`>Vx?r#0mmaz*oO;VSU4bJ3n>zss7F<9(!c>Gg}9aww&1Y zS`{{S-on#4b^UF3s7o(V7MwF}>W<rHPL7QA_KSrWJ0N12D9LrEOe6jfU4JjU<DDnK zkQo*se=KGz38IDa$kwO<_f56}TRfgX7biXnTqTN@#pSSQQ5n8SmMJoXofs@6E6iD= zPNy5&`0H;{r6r9&_)hQUCwC8xSEO@AGHtkZlZu+ir6NG5UF;qcn}wKnHL7lgx@5Kb z*oW0bsG_~QqV+_2@2*qLhX#gv?XgfG7Ac4&Tp2>vI%cJe%C?iqlPBZ9ex#$Q*j-YV zYg`(vuMaF=W@XQ~s6@Pq$VfvUoR$<;^fpThvn@jT%ve&s`if--U)<-+I>tLE_CIxO zqxVWR(j7l^xD?Y+hppFJ&~)w1!u=uhTQNAZN$x~V)ZYtmaIp>l#St)x7F5<GT?mv^ zc;du~pa1;lYuB#5=9+6v!53LG6biMrwi5Al-MV!J1qD24z8cy*t-gM{jj^cS(V<W- zxnNDhRoC25ysDB1<6E<_Y#P>fG!YURR8n~XbTQ}b!Z|Ywv7^EE#U#MIkwU|0Ev*U! z0$iv4umWZSjC4Gmjp9EajjL11@R-L@jB|pgLZTftw}mE*f)qsCl`AZ2AMT$8GwZQu ziwjjSsHGV@Ha4t6R!kNPFVTCmN~OrMzF6KPBS4tGA)}+M9RulDF6At=mzS0gw)c|h z-0v@{nq5^^S9Y@FNOC9|$tHL0*)xCb+=AMYJba)T5u-lvb{e-4rWYu3`5ZH=s=n~~ z&l#6p`@lclv-{~yW0CLye|SPAsw@1na|vHDVL8C{@!F4lz}MBK$Vn{WA9NmRTMh%+ zcb+D_M}}US@y>VFTx}AQF)RDJb~ANV$|(+s5@yFs(q2^5l4VU|SVG*izXq7Yfbn9{ zvIUHLH_H~)bSf7^U?9HqnsusnMs@xC%MwO++O|a2G*1XH@F_bR+AahdslADERA6=c zB-||fQ|s5*KlRZCy*&#$PN|k=bzpD&Sj))qmZ6w28qcO(jv|YtVtgVsK4I(a&m1_? z?)F4WiX1cR0*#9+R<0^pyi8Ts*b9QtVtFIB1EOT}stvbX*LwJbwJ!rvKKe@Q#->Kq zcQVpHSmtu{r;J!>`TWZ^;(SinQ}&O=G6f?naPLKIB$IZ|7l@Wgdg+NtjG?t#w{E@X zo_qe{FaF|&8*YHMk!^a@rcKX1_uNAdJ%j}O&2N75&O7hqx~Ty^lk&a&;TVog-tgh~ zuUflC!Xe2@Ql-_Uc62OBYb=!*ni#FHlw@<!f!I*<-rXn^$0tT6C&#D7abE5B`%6np zYinz(tE<b(%4m=Ic4#w38-qhV1T_Lm12bmC$(}+4hfrL-xckVCeHB)3EZ_^)&h&1) ze0cK{6Q|oVM4}_KFGO1N&eOfngY#BE&!h3_+b*8G3nP#s+Su^$cs~|c#k0z<y6UR= zGwbjB#=mDtffJjoEt#|GGb>k(tsLy?INI5^t7Y%LLkBm`yc#5(NG3hRxdh}$`{p9C zx}ZT%A#N<NTVX-wo?v~5_~F4eBe6S|8gV-R<_F*1Gd}qzpa0Y9iZYZ%o>?=CXOv@o zle3WD5?AJ&Ya008g@Jf?Uir=wU~@SmjS@1AB3da@^)hb|A9DqA)bXIqI}r-?q_VGz zQ@*~(^wuF?s@-LA;Y7#->?zHtQ(yS<;;yclpdKs<l5yEx6{0Ac%ToorP%eQEAmtc! z>Rne(xM@zUnpLZ=*oZ*jdGO)fm%e<zkq*wOUJZxP+dX28S~5v*&Jwg_Ya`>S$hgtl zt@gY+`M{5cN=j^H<<`~f>J~3{ESM_+MrPpMK}$=lSKM~<mTx^1uz87ky6vGSt5W-7 zR%fp@GvamCE?ecAIgfx^B<qrrN)eDxd_K)yPqp{r=Q%n8=Ju`WWn^{%J@X4Mynv)j zS|KRV$jHcj_uU5#-neli*O7gpc_yhgg=14M&9hKG5D_-gXok#lvqH`(+{}?Hf~>4+ z+4@zYB!>C|;i&OQHB-nIiH(%#1WS7IsZBkPckMsDb0{o3FC<`1M<bbZ%B+W~sDzdy z0dw;8uYdiz>#oBp+iVZwIL*r#X}C;r%1c^E$gA8|b)@I?1Dgsb40eZm3j!<u=#%Q2 zjWxDR*Ztqe)7er=+>8pn9tdQGFM+IK*lx26K)Ys=r=i~bmjChM#~*qGKt5izegBS< z+R{tcT+*<1v6F!IW6EAg-qZv}^l?e$t5mhBsF_`{e)i?54WVo(PKtM|vs~m_ASM!< zh$8raT0v}3;b>yKgyaen5%sGl+`F6CMRGIk#f38~UpC^+W6`G`dAz;(#6RD2Pu=Vq zBSSqBTojt%RZgO&5xEqaJ`Egy=+SsL-uKQE;J5Zl79HZM`2)n18Rn}=jP-SMRdN&! zn*K@bHMF&!o*gkmCXt36f5+V1Ie~aG$)+p`#a)E51PX+Ow@c`7=q{(`i^T6o<*+P( zXQL*GriCRzI+={-Z1%R!pV>XH75M7DanDz0&9b$fl<bGwULHGfe7LtSWh9;1G}>|x z;&FU3+clZ(?Mxlod)(s*7Z#>w&vGwaT(y2}?Gg+W=Fcr%w08K^$)VoXy@w7JW||$L zzPez*S5vd@%FC1o;6lcyFJzyv6R3nXT_nM81(0*`3M360#u1s)B*UYlqsNXNYb5t| zeSJ$y3)Gk7LSOmHR|q*ygejlTw`dX8gZTnsMt#@Z+{}^tq0Ocqm^w|pG}W3ko(H(d zk?WYzV;3ln#M*E%Z5S?gK*mN0rizV2CYRp5{nh=$`%XvOokbp$(Qb#=R}gTMSrhGx zE@p!fh@rbwYf@r<;Reoetj`)bbXBAgNybwJ*fvKKYSZTAk=BxoWx{RsU%FO(@HSXU z_g#0-9PN94%VshtNs<=PBibd)j&7Q{1ZA1?ed^0p*Drp)dm~^`<CCEUD;8F*y}V>T zPMI=WpeS3=k?fhoaXXrh2wmm6mTA~0_SwiKC_)WI+Y-o(vSlG4DVu+pVhnKN5j8N} z`RG%Xp?D!dQC-fv-+$+a)~&wxk;i`c@T1M~<X6A)l`nkhFPoa0qDI`U^U)gdl#8$& zK+OdPA@4i^&aXF3Xc=7o%mQVVqFG~zD+Q-B+1BTT-BG<(&HIIpGQ<4J<GR7Jb&4t* zNf#w{JmA8*s`+^9$s4Y{+2i(8WzGNtXzDAq!N#X_e4&i!I1FO$$QuM+l+EMv9XNDg z=e8Fdx$y;a>K8X=N{elkrE22_^_fo>heE}N4y)tGGkbQn9om1Qw;P9!B1f*$W+{!Q zUEy$%GMop;QoCNA{K-#`Rh0W@R$FESQzzRFjt%b}itKZ!5DZ>jB-D^g-MYF-`D}>q z;zx{up+&ru7!;h~z@Hb(xjq7>)M%1n`oakt!0qkr5McZx4<9~^7W%f^Zi_@nm#J2- zUTxAp^Qp<nNmSEMKKUeiX{@)79zD8#{rWF{@rxt`oR)*R69P#=q=q!2ujZVUkxXL4 zWi^Z}KJ;6keR{{{ZKt=jEiP}I>8nF6)ZO3SSX;kx-jZ3%>dVV#RnMp?^7+b&ijlvm zkcC10FbYWL-QC?QSFSX*=;lwHhr<N+z*+%kIikQ>eS{j^y}fhG6V9>0l*bmIQN8dZ zA5aw~D(h17yzV>i3ib5lYHLN|q*piVEI+LxBgwf)()yAtc#*96HYFVAZ@u{O2OWXJ zk^<kd1}82b<`gk81<GGu(AP48mN7=&q*T^Qpf)?1RWZ#W!io-IfEa;`nxHY+9mGG= zVzm+YMK;(#zOkfwYRkmo!!_yLpf%-Mx}@~x8&t#m|5;I)cDtW=?C}>~elB6l{lh<f zqq?jD@i!6)2g!0J5-`%x6wLfVhv8j&**i~wwf;)4I~JR4)aPli%y(X>&Ck7ja1Vb# zfhNgs7#4oz5mOy4l~}|B5q)%uInN|g|8eg(hkD08`H4@ty>3wmn}yd|Y?##>*(~9! zrCLa@NXhbZRzwKLv(Id8KXH;M;h*`$2dhfBC++lF*)8*+A-1S%uU1!Yw8cI#e|TVi zTbnw(U+vzRYHb-L)L(DkXdE?l&XZ9^sfcSLlI-psa=CYpPwuj+j;x9kIC?mh88Osg zPjB1s(9(v5^o^Gzwq%5LVBec|ytSwKwqN`>w?+VZ2I+!2(rm=jJ$v?W92y$>_P4*i zaN)w<UWrryWi@~0P6~oAqVNL`JaFjHp}+t8zeo0+n3(wf_rL$uuYPrKaPYg|{Vuz+ z+z+*e975Eo5K+}6lje04#-WMmOD{gZ<(a3pKD$MQGIM>i$;{f{-^YgT@`X!o`}_y~ zfA-D;POjp}|2;YFY+mKCN+_a05CVY&3Ivfc(WJAnea^-K8yjQb%-KG3_TS(;d=5k# zo1BeBPy|GlKtd4-<+$3sJ30Kn)ipC(2}MA*!t`hL^rm0Ge*L=Z)vv3%s=Ct&z0#gk zB#xLH0;v6j3+4l|i8ineHmE;w;zTkzq5WiXPD-U6TN+x4@Jt%it+Q#YTl4rsX6=X7 z0nf&uXTYRM?g<m3iBupEBJip?e%#nEwz;chRgZNYYz(1p2)^(wN-f27AoT!|u!utB z^kKhhb#ZKUgLW~6Cuq{?lKop*76F4xT>dofpnx>PsY$6vxTs_i=ZvGrg<O-CUE)7j zJ@3&cdr08kXj65`Q5T<QYI|d;)pzjFAAa|{fo%HmXP<fX<yY?bf4}|74}Kh~AbhI0 zGf{^iz2(gMki+4)-vL-b)gmoYtUzF{hj-c0z$(L_g$qNFU-y!M$|q*{pqCgE6L!yE zx1sqj_ddY%>&svNihvsPDJVnc?nDJBv3odRzbq@TtXyF9Ze5cd^X4v?_R`CVX!e*< z$BY|0(Lpp@C<-I4Sjz1ek0vEeU&xg9GqwH9gvq8Y;%#o}iH`d1H%k^SAe!dJP3v); zs%&p#ZWwKE-iTel!?cPcyPKHi7>qjB)wjJi?bQ)Sk8^n?qAm5qmDt=I(*wJro#S`; z7c2gMQ1$>!38|E(gO{AY{r21FqW}Hh|Gj_z{+l*!dhNB>fYk{TCj9!>zXnz{3J2(m z`1|COPf{La<z7spuDRx#sZ*y?9tg*L8n{)&MfRn<)-STKO*5xWfBf;sUzzpF`gQBd z%S%TbHT=ZE$A{WOi8U<YW}QiAMX(%;30P!EV&${)B2Qtiz>x|#QaM_2PC$26K68%7 zoBU0iH?P{bN#?pHIsS-RGiyfM)T!MPktp}|?dw15Y+?-tY?Iho1)qRkXI^01TO|rd zehO@bTx|Y{u49SZPRFS~m*n}y^snpz*<+3Xymq!E=xc$nw7lA6wi37@*@j{z5pw!d z;`|{@m7Oz$m>5onlPwPgKOiN+V|FpLmN;o=<k4p{D^{_$Mx8I|8%<<}$tDy`djhT` zTjq4S{u^J9G&ejk{neMAeSTQi{$Kvm=cH0U`j~_Zua(0r?Oy;E^tIoZ-P40jk4Ox) z;*A9&GAP6!N!S6G^vG5IG?6L#H~ArJya>Ta(s^?ZTO{LjmsMA-Ub*UzcmJtd&+ez5 zKG`1%Ku(}6%+TQynn|<El108OC`_P92Zm6YKmYm9EYy{kR$O-J6=fx*(h>+QO@t5& z-SR|K-#ne5sREWLkW0g^K*-sxt2t?GRVrDvX3c>2=9&2m_^aEzAy&6OzHw_iNX&yh zxK+_^f4DUoU%qa$^aU?r-$SStuPoWT!oEQ9aFF)^(4}j%!iv)AhK2@wjR;eJ&N=6x zg$B$vY}f$KA>9&P`4_+V1;qeVBw&P2^uTM@tZ8g)?A5Cml~4?+6mc2lu;R4hqM|ST z1X2R+8#iv8IdkS+fBM6UWgqx`B_l?ToN~r#r%gD0NS`AYzVPm|e|pZ9VB=3;Yh$!B z!Cv>Q3(JSbeh)mFr{q2;TN~$O(nx&;9;b3VbBMaSI-kc=no150d85xh8Q8Ke<MK54 z{DUs|j2SvYwtNo~Xg2M|%nB}!^dDjYm@kM5h15An6o70JV=sOvH#o?L`jBcqql5NX zhK$i+?+{F99KNodx-UpB_hr3_*0y9c4zJ=*)3z-UEde3sNZ@;*8@9=i!y^|hU-i-} zRnbIiyfM?O)6fgfHdR$I7k-`++K{kXB|W-)`Ac6|v884H`ybqW*L_0<3><gzXt+8N z_vLn}NC6`M$V2-7{R_a-b#~5cQHCMldjt<<4sN}58M%%Ppx+6>LL$H87;sJwe@GZW zDhm(X&rnGj7K`hfnnRVrmUuIW*OqAf&)aS$3?#Ou<yBQMokTRwEM2OF#mJ&llptJa zJK7`hfBa+W%vmpCzcu-^$>UBQC-`XpGFW(l-aHZ7660-Y57e2V0;dBFU2Z!ltgpRh z=pZv_kh%C$(;BJSwBh9cxntqIcmJI&7`TZ5m`pdCnBTcPl>>(+34ZEkvud_UVsAq? zGXiNnZ)$so1{Tx7-UGmxBH26dyo1y`di3ZXJ$e9aycZT&C!BBsZo%u;tpj>N*`NLF zXO~}oIi^@Y|M}0sJS?*SV+zCBSd;||J9q9(K5D>@(2IT;^rez}?z!i_`|gQF+xPtd zm;eAk07*naR4Xc~rkrukMHgLi%;-__g+)y&>}hqTz0{P*Y}~k|G9&)MFi~{a0<qwt z)n=1NZTdthU=x>UfNG%^FIwbC#!F0kIKF}(EL;2L%jIqp3A#It8EZasv8g2Hv+S(k zm1x$9gwxA;05k0@J8Rq6J9)yE+U$p&e@OBF1EmMRJ-`!I1jB<CBw!(HdKr%^&1A|O z#iN`ZHrTreHpK|?$C&ETzJVns&2q8}p^3(pJ@S-${npZSw$W?)j2S5#IftsL8t(58 zFbN|zbmEBPj{5g+ef38-{$lOgx_cgfc<h-cw71rmvJLU!XA>Y8w!f484EY3kmVS|n zrX3!u*^;5{DYS}{!nu~$98eg=m|Uc;^769P>sKPV`h&i<NPA;r!%u&9>&tUqX>DzW zRxnrr46VV3oqxk$WSof?y%2Gvsi~oN@19p)b$NM3DYPfoIJgiLaDEi3v#TUL1QNmq zP<BM(vGOO1Ioy}y?6}}!>jp=rqSW;5Z@zQgrG5GniVquXu{@DGlZmpP-H$waR7zGz zsNG8OEVYOmyS`NMc+mHNA{LrkPDsd(*jtSlF#;i&cLPL0H6&w1ULYCtU9n=t>eZ_O zKW<@R_@t9gq8M6eNNmQ88E?Gt21Z+B$Bsof27R$o=BmoURF1g(%U}NT4}bUrnL~yQ zyXmHzZocKG#~eEf{}7=lpXt=IOQ^gA={XroZrxHZnV3nl{hQ03rYiY#fLOM4bpw~s zaSAJE`6d8RR5FgF2+G;!ruNkztO$YTCVQ0E6Px=^W^)^>d@a>AmFJ&tSnI`-A2Uet zMZpG#SPGH|y#eXt)|C6;g{6`!jG90FnDbQ6|2ur$Qubg=yx^|>_V_A@6U<fk<Ah<! z{c#)T`J|QSe|0Qm^9mVyk}tPc|1$s(0h}4WgiDFAKSU6ZDK8CrTo}!;t5?QuEXgp* zBvJ>F*F_eg#db)=twd&964St##Y@*rpXF_9^?1FB>T>TXlZ-Ej_`wy4>A)mVb|m&P zUz<E>@<}Hh&$9BIw_d;ZuYV4O(LOrUQG%)+UTOb+0P=;|uMX8O+fcIAAj3<B&69D< zji?<-`!&iutixa7x@K|<1^AfxvuYE24|B6<TQm_(fNUOIg`J)w1`b)Yc-f}STj4V< zH{%Uq2@)rhL>)!`_ODsJ`L<vFX7Qq>et(c)2uB}13VuPd><Ctg_oB7%;z2AU^QTSi zNE@`7>7v-sqe*soC6cuXx=sJyRX@G?dMb>kvh4;_XEUIG|L=YI3sWW@PmNHbPgHfn zc-+{ke6-q*k0_oWR6PK`BAdcoKv|Y=LD^%DIR?B`4<e|FtAHZ5QM}gd*|Rx8>g6uV zkfYjWJdyCnC3w~ke((cAQ&9=GqY%!fWjkU1>g%@t;%7gf{?fE$JTYeU@weacKW9ui z#~<{F8I7ouuvTTm&2Xo1r8AxhINdGvjc`l?zqp{cB*t9qoFFSgd{InDE#yLxGUepv zbUem2(4I+U-KOR>OIBjW-@}+;>124-nyx`ti!)FOS3Px#DJ_ZE&p6=8abK42>^H+F zD&IBV2VaDj<sbeRuO#{2HIuiMuSY%t$&}NBH7PpMbshgY;PDRdXn)FqX}+K=BN4ZM zoalO)9J$0OSX3??ZTZ|?+nwhh1^|jh75DB#V*bTQ6D5gw`yP{Ed>9Z&vBVK5%eF+f zghQou>l(Ny6DS=nD23I22vMe3vY~q138rRDq!j?CKv=)y=k>q;Q{|e~K1X6hI$m?i zS!UunCRoa?aLF>eYZly?>K%>%8^M0%b6554S(A=7zczC=GexoD!YvpW&c}vh#;Nau zW=Q6FHt{)-I3<%KGgOY0)JZDm+|D<snR?U;xvNk!`3Fea@6^wiX8(8)AEEwnUiiz; zs_Yk;&);e16mHRzT$v=QFQ#omv)RFehcd5kZ;u{v#GtQz?HdCI3``^lCLk&`hKE6d zkpaX@mMs6#4}UUi*2|$#__E6`yZY*@cQ!EFKQ7n2oi<D|^RLNC=AsMF`|`hkv8Gce z97Ha;{PO?#?d{ip_gV;>KkW)FoV#t8RTeKCWIa%jQ?Y!;oflu;Bab{11_9NPc$uS) zI_l(;PX?P2USD|Og)e>SOJst(1%AP@@h!L9QdwDvMKs{u+S*D1RT0DPY+yL^+;h)i zqQ$c&Po8|;b=TF__6>#tFe*eBtDOM}FyQxwLqXi#oM}gUb4xm!vXU;}UtW=DyVf%L z{F&u?Xn90=Ec+lC-eT*THD#c$F$3M+P&9?>y{A`gmva$+D^k`*LcTk&U9d#Ro0shP zq2%ej@F~f&@|m1&_aWPM9E=CvLf@%y?C=&ClkO~0v_qova_B-$R7bL^J?<5yo&77E zY<pOT8uTe2t3R#Mk1@CS4e-mey&}b=+#azdOhvJ^VsNdnBwmy$ECncKS*{>9o+J`M zgO`{#qv?&e%dtE4xzoM6RiDY~ZzsDix)hehWBG#uAszfn9JM`roN(MR*;M?4#Y;b2 zzLEz+dx+MsYwA~h4<{dd@PTTESh&$O8onkzE2gvXZ9X54Okw#+VQ^Z%7bd}EY9-{L zg5q5`q09l5bhr<wChc2ewBIo${lXW%@ZbOa-&3YcVR&$<eE#|8b&%+EoiQ;U4Arbz zvyd%dg6Ia%IOB}ZeeQE8{XWHkVaRy_SSPZ}$dMzjz4lt73-O43d#hsUgRlqi;-%Hl z5^J|tTyX^vC|TcC`UEf0Nb?h9WhEFkasBnz4;nOx6ZnF19Q=kckR~1^D<h*ujat5Z zIk%9YTP0vhzW46C_uhLiwPCJB{TN;a{AiWLbON%ot2|cORBF%@Q!njlXlQC{Y7^NL z_DABx{t*X;B=bUHi*{cWmQtKv>IphzBlQ)_=SLEa-SAp23s)Jx*B{#Ga`!s(RCDxj z3?me7r3xOK`?J3euLE$BLlni8?T*?N_&RL+6Xqb$l^X<f1<Z*gavui7PKW%V_I1d1 zX^f9zqt?QW)PqqcP8Cu6r^S*;q>KeaZ;vvzA0u&l#~TBoAlm@Te&(4BNJfRU5avn4 zQ+Rdi0}#gv*rH(!Vkxt=al=zj#n!ARa`5JWuhY1(=EP%h9+x|Jk%FPni6@@OSHoJ& zf&~k-l%gr;`cYtJ_}R~Xmhd&?!%_LTnA$$|)Kl<P>?huR_gzZzU2v4<*~B@VU(F`? zc7Sbiz-hijEy>RVCmjmF06#kKyz>A#p!bqXF2VkV5hVsMoesn@1`Hcrk8%%SX7HFs zk<L2nELd2lPMx?*jbc8PQK1>wyFxcSv0uM_cy_`)$y9p!R31^R<N)jeh)}<9cov)j z09LmmenJUcg3M?(!7c~@1nw$>;3~8M?_kaNp@$w~#s*vA5}8QJEFtrg$sD@qOiFgA zx&QwAp=|&j1~hWiD7(o4`(uhV0VI~|7XEi4dsG9hSW~q%x3@I5m1WB%`ddLnwPoRr zaBV?fFhNWf#7U1oFIQ8k`LE9?rNPGZ$4x11q7G;2h(YG8Gl<0iWKde(2i7NQO962p zf<Nlaw<Fh_!{|Q&0-Ll8z~*fdu=Wr=W)TUst@Jdor-Q&%6#wLq7!!m!TZN#zEib<q zKkZ|Vn(QTes-P~XAFKCis6Jb32$Td|9${H&0JxQiLDb3<^!20>63U*{Jy!k`NwI}x z8=M(4Ti<@C#_f%mY<t(P)#smU%1UJK8aoTLZQRKL4?Q?A?3a)=(sm4OWHusb3ftrh zdiB*;`804P;QIoqk%sTO>n?ONk3IGnj2+7fJ}6GOMTIDi@OC&qw<GluaE6bO9IE0o zq*}hLowVa$mvvyZ=HvAPgaXfkm(kG-$ydMnRl?lk)PbQ2@-Aac0mO?rbLQY2!a0|| z@r`ew0K^?rWeb&EKHk$mdKcSM<08U%69ib9=|{^Ha}Kc{C`h^mM!<=F@Emzr2#?7- zPzo;~fx++s65NM`><h9&kPkfY0Emm=iyttNv$&C4I5LY|w{|TNwIFijW2TRZcw8PT zK1Df3oa4O+1ZhWEb$OOZkg04sk!q@I=$YvuJem^rPg$wJF=t|e15<S+(rk%BGo?(^ zhBb?3y)e|6ap8(CF+BJ@O@YA3E3Y*D2N<s#(M;Y*YXKp|a!at6igHbn>xWI!e(3nR z<k&8<{Xv)HHO$&QQXVmqKQ0m7!j~JDTrols$lOK}B^7ODP^|5X^tH{R+krlPbnaP& ze7$)ej^LynIIE1IwoniY71?n$n~k+cXsIJ0D9055gJ%kbu?j4}j07Gxn>N)w`mi5I zyOd{()6?U$$z}}VFXk@0!xti_Vg|v23;qJAFom9dJ{U4nRlXe(UjYo9kA;~iEPBR_ z8K{4dwfgkw!;P?Uz5-qn&aW7(lVCmyJ)s`Gq~E4acK4xE{wYOw*Fpc327J<opdkU| zbdJLyae~T%0l5A4+nH4{S7H>wLgqo7pmt_y?b1sx9XD<q5fAh(9r91wj{N;R>*beU z#(NUJi6JW-mMhxGe39b+hinhPEO<9)fW(PKGc5Z=4+e2EA14#&Wp1u>J_<m7h_kHh za<X*kQc6NI5HJ(R+S*z&;Y8Gc%t1hD=vnnTfVwapj31CiEVGAMBCp_iBx04@lvagZ zerKvB$%@_9O%1{|p+w>1z@#u+7Tj_ODwh9}*fEe3%ZSa~S7s)bZ5ZP+eT}2S=~<sh zcAq%jj6KnW%P?xC25cR~5Qp1f`xry3E>@A;)^->jq!;o@yE6YvdRDH|^>kCdT<(8* znjk_JYjefuM8sday3S1$(?7kccM0g~5LqOom^=|AL<yoWPlfx!)v3&i;lOQ9UrdF5 z;}7{!-Qdj~kH$<iYuKrhlB{&3@K2(kG~3#?VrUvMuf1MB@7?NTqK%zx2KDWG!MP?7 zl+|CkCqGNzhV2s?9f+CF0b+*8^`a_@lrv-P4-dysv7(~lFMs(9((t#w^(~|tJ`i+8 z=$W~lyC_T!ESHZ6_dGs5J}x9<>@8F(({HWti0xbPFaEVJL-j9i>dqez`qJYCk%B^W zG<H=mFLZiD_yc;C_rcK^5?0{w$Yk&+sa#TLPdl%D-*cIlz5e>^kQ8D{pFVw*)zXH2 zuc>&)!PEl)XJM3qRb>q@7tSF_E-A6`O3<6Alx^aiguWV6d{_@6a#>j!B*g3x)f|aZ z<ckcQ$--h--5{(7=3NDDl4It=8-){Frijgqv$AVNpfu3l6n8n?Ti0zhgrFAm7a<EM zfZGZB3Mh#6ERric)iPKC;HJj98Babo(3r6SZ&f_OZVa9y`qW(USyNhJyg_x<CxQ|; zdJ)U0hx<9Q|F7_VDmZ)+$frx9yfqUUF&5r2*<r~+5j`%-XA;mG&=IpJ%SiA?C3*Cv zN2MdJg4f=VKk$HUWh9dfVp17Qg88%foiDmq|K}Qv)t#jRxhIS2I9N)QdYmgAz*{^L z_oeO5gBk3dZ9!g&NAZX2+R{ZUpMEA7iJ+2>RE39}dxkk;0FjYc-j)*j`nzZfq)xOM zW|=^&$|`&^(6*8{u6oQk`65`3L5jWMh8wzd>!!u{BH;Pl$Oi%hP!j73>?e?q5vKq4 zx4&`AH^2GKuYK)nT3$a-zCoQ6@1i;Xg6xAHfOYo7uxUrDwt;g3aS-wzsh2^bUl}C0 z9?XtQ6juJIN3G%0>U#`XS*YMCc#^<ImF*sAqyA~VY_Xm~4=DOVON_N9$V{nGr|QaC zpg?YcYv>7=R8yh^47HG>6L!tf!orW7Mpu6c7A;bO=zQ%`oUM>^F~h+SNBEufU$23O z`Xg*`<n*-EN5mhl6cCqfsBK{>C4W}@Eig&AD?5g@u3xwKrD><*LFXX`t8+!HWzgvp z%-As|=r>LR%n`B(*Hvy3i8;r>sZ<guLXt-u9!Y_dBa9S<1hHjz&rvC<nrG3JbV&3V zGNtsVnmenKp8{wa^2LBVit!YiVFy`G`IkkBT`0EwfaGu9)Bij<Cs_+hxgEZcPk!U_ z3j;+t%uWnY7xW?P9hr1A?FzAlWyZ8MnD-ZNcxBGOjA_9as82V?l!-jc=?O&Ruvtr| z)V;HW3YrNe7|gc-0P7c_Y@BmGrMYwG0-S&@axK~;#402xY+CUqP`OLRWlEx{CY~!8 zjATqE($|Cu6aMf2{tqV?YUX>?&y$m#HRNBJM{ge7N#{yBY`jUKi#cJ;kRf{a?v2q3 zD-Fz;RG6SJV+NhU2f2kzJyEfk929`sDV$JJ&pRGrj{MY0IN_(}aK!wIDI?H3X3QAc zpwH@fZ}I#P?g6L~-l0TTph=zQL1xNgIO+-gpqDt&!rZ9nTgc(0P?#8&FhiCz*tuxN z^yw&Ygl;W;w#6fs0XvENCOi*5lQEsTcSaOW#nP$vM6_A_gDJ1fFvqTipG%BiE2_vX z=#&Ye|NNis?$i_?Q&ky?B$`dKdh`hY1!oa<!vw=ATuqT~au6$EAxY|yXHwN+mh77= z`br1bUdVNd^aR=hF=dunPA0|9j*OXfvmEiej#=j&ek2nTkr`9sB=LD1Cg#YZpo0e` zh{kMuapU8NFK%1XiJLZap9Du-En;$x2eFVqCXh)o!$Qlk`x(H_#|Mh>ip7)=k%QQO z4pUM_Fe{lRqJm~GX+d8S^g;Ao2AUZm|0g46)B05pKh&c=<x07l{lWeho@0jg6|p#x z33%OcT1gA@F1%8M$jl-ULAww$N@F0FIVg%{p<BCf1J~ubT*aIgE`8&TH$M2_gSXy# z>*qiJ`6r%u;>s(p#0?ML%g3Tzm&Q;7d>*c=tec51+#cDQ0tIGnAAZ0cKF(+za4)fo z2ElHWc@-pGhK;eo6bn4&CPr6}9gC4e87`4jg3;=Qd07nxg$wMmz-qZfF|;4-CC88x zgOFL6Rtpj6EJ5oj9*aHj@p=G?Vk)_Q{d(eALdh%`izl&NJPZ1;Qx>BcZy*5YBBB8y znoFxng@{wxXiKuKzCF;t40A2mW^U3gcwrf?^<aS^V${lZo2d<J*Uy}NLRD2o9IcYK zwJb3B%*m!tFH;gkBtm{hOhfT%(MH&-;0|2Gt|Rh)uJVufh6mqWysj?d+V?I%Z~lZ1 zm6%cN*2hW&ZmEO}O2i2kgcynPo{g5{V64kTqL{$R%Y&qetcfKZjZN(9B74TfA_iX7 z++rH)4e_?=dREUE0+g>N+twc0eC$yJ`t}piR3Y-?bs?=U5QYq?)A&L`rdK%9CR6ET z%tkq*aoC4tFg}1qx}_bi#Kx&p+umE)gEqVUmBWXWoIH-`q{b7Z3Z?~w93t|S`VGTv zp-fmJ@(C_>_}~GnSoK56<HwI@p;wKtXuopZl`B^gr5~38BpJvat1G<fVWh~x4?q0y z*=L{4xrSRuM84pH3lNKmppK+V{TMJ}$;iqMMnB5T>3`TVd|P?)$Lpp2an~UW!1Oqf z$sp-0iGJrNgTYbJS62n-QymiMK>Jt0lH19Fed*6aF>WsmL*YisP@V^|6amq27y4%` zTD4@yTMG9UPl`RTuRQ>ZVPWOBzx^#V#v~Hm9cB%aCQruBfPJkcGMre&umzU~OBwt* zs=8F-*MXgCvNhhYxv?fgP>l{kDqw5%oi031F{ly=hwW10^Ix3met+rFU3$8jH#c~* z{$oa&bIvrFkGa^|OAKpx2%iS-B7!m&fOVG@Sjpih0RvnXdOMD#Mc*WQ`$&u_QR=Js z2w<W<2zVtfeO3Zsi4(2c>#N^l?!SBfQ;#loI(tRq?vij-Yb4&(94jg58NmQ5-G;ig zy)Dz;Cg#Ct>4+OzRprh&)}_)bF1hrWaVN@%2$yp-O9W7M7}q&L$0qH?dEqr^7*nxu zSt-QBi~tohaRz0e;e4z<J8^CU?eParndK{1J@ssLQ%lwrXeuoo#O_%Ahe&Iznp%Q` z3t+=SrAKHX@hRVY<BhxTz8hSGm<fT7ISy}!RV+tvIz}i;g6&(CB)%jVVX>yGri=Op ztOuhaLb`<lS&Lz<mvA(wIbrPheDXyA?TA4C`@jD?apJ_UeB~>!VoJiCx%~h{Uul)T z*dciY`G7|HoiP9`Nl2)SH2GvQSK@?BuJZZ{v``6&d`6TqoG^qWhEPY5^4eFLNde6# zlM~{5u<FdJ19tP|=vBx?Zz&#&J@B!6K;;AY5hi}{CP)hjm|c}>Dk?`Ddvrp$qmUp1 zi^J=%{zR_wnhLMa?MPz7WtuiOnshBia^x!>BohA6!nQT)0Ud~E6lq=d%(F+8l$Aw@ zE1gYr?R3P27szI=0_`Y%MAAj=>6V?c5x6bX$eASB$kXDn{dIU8ESBb8)pkbywKH@P z41n2>F1l;SC)u*zE#fPC*9ZMxbjgIKt*kN=PaXcjqR``yEXihiWU}72q&w)Z{V;|% zQn|y$UQ<zzDP<>f6wlVAxV61)i$9n?{jBl-_Ju(;T}*q_l!hd*N-|3{$!!uszA?N0 zKi}s3|1yC5k%DEc{>vU&Od;A^+sNfqim^V77P+kv!9V%fliBx|b}lR5+}a*Ea;Q1& zG~*7)ZqOn*XMBE{qPcJ?&t$PKq^jxDr$e#0XtGjEpd@%HTH;%8y%o<C*fcsAKcQ@F zQz%T34OlUk;MhEt!eqk05u=f9fME(?6@iEhucjpI`pq}rM5j$AYsN%mLTE1VUc_IO zz6uOnUh)7)g?Y~b(3VfT3CyGz7;05;#fyXRL%;gfuNW!_0!;;jfqyUt?swjKCmxm{ zF_$RJP-$BV_{xdUqD`EW^jx7`e=^3z(C3`F7#bBGtwh7IP+spU9*aG&uRXw`7Pm05 zBX%3)gbcxo7f4LN8EBYG3E&g%i7OIVh+5NOO3O>&QzB+%-3?nC#rmg^giRAc$;z&< zJlFvDq1Alt4fFoO!MO9aHMf-bdY*o&nKaq>!p0;19ul^nXdSsq^fviHPChet?eP82 z;)lL|Izul5!_H*FDO+G<jnCurU=*MAm-x$^CV+Z2m1(2zhK@Af`hLI5t~!x;Cy^vk zKFga?LmOw@MAF8WH6>Z6CnnJ@vMztp;oIU2uby(rfFJ*CP|yA{@hJ&q(rkoIgcJu# zj!!rgma`GKKM){zI7|;pYHyK{sPbmk@{46>4+@ue-}&&7C%Q!v@vNh{qP+L{XPI6- z4Ew2PeF@`=Ln@+<0k=i=1!#ZtqaS_y+uufPrB0YFIS490{NWF=t3qc(?;vm!SOzZ2 zbD(g-HbCL5<w3)m3A1IP7gJ}rG{WvnFTKPrCdkKJC5OB4a3PL5{G5=8go3~Xnn@~m zQJdnf9w~X?q(c^f>38jAP82(_l*29#o<%;xhT@LRfS~{acYN=A-@|#AxfPcbEV+vU zI<5>Gs7$`rsiUZZuO9Ul^v|$Ds0}X3qJ<XI89<>i+N9#K*aIJ<2e4jY(MxBFC|a07 z!g^Tly5o-DEL-`3SGEs9;P4{;qNao|2g*yp=?t)%bfAJxv*i(N)J`LXFUl6{h-kuM zg=wR_Oe8iwGqqnNnQhpbWiy<<Jp-bAu1J8-Zl4AVR@Akd{aS+~_=k8M%b%nU@S_=r z_>uSB;ZIZ%7Q^T?dRDqwCN8ppY05;~#9CQGlA&%$WqfYGPvUn+*@>X<AoHysl$~?Y zk>S!-%&jOL2nD>}5UOl8o=J)EToR0Gk8RDmljmJH`T86B_ULU5vSbe{wqJHeTiMbI z*QVT1?0e5!%Fxzhizm*T0XQ2w%}6jTE?Q(qQDPD_Ia>eJlj#*7Rykek+gm#kc4NvU zc}br?!6LS-N7Ia?Nyl278c-BpbImmbKgSja6GFrr$dW}|6vZs)$_lXv*FrilY88Gc z#yJalc-+BbH4|>kdN3h}iD^i1O1A7|>6c3+q-vshV2Z^fP;C-9iv{DSpMDyiuhJLy zDvIxWx9s0LKK5ws-)4RC+Uafxh~6(?Bx?iYU~UJ{Vn=$%9e1#3&!miz-n@A;`D&}B zHv*p&rWq`{Xg)a#v}9_X+^7hxt;J8Ac^S~I_Rm_TBU*p*mnzn9*!BPlIwo^W@|Zyq z?hXG)sF68h!<IUXLOb{E1!Jo5hFMc&0Z*JTVf-N{%VV1tHaN1f!LXQ{$^xO_1Byi= z=(CwR_z?j~9VQ6dT(rFD<+po8lCf08(W_hEGbWg!gN@stbRxI0?wfU@eI#KColR%G zZVl)m90Ul!pIB;?<wsjc3LXXt!*Sly_NW~B<2QdUaLD#6YpBHG!GcY?MZ{Fuu}%8O zEjuX_#3Jr=v5l&9U3CxhqyG%0+~I#byWXAd)7rGc<*udAnLx3TcqSe6c`?`W1KPcM zIBTj9mWh&vb+soRi(-WrAlLv^TAQ$a?s-N(KWv<G?h7~rA%7y%3<m=a4OaGHc~vO| z0KYzW<Fx5D&U6wBf=*p~op+Y02}hY{c-ZaN;n!YqBs1Cg%$d{gyYD{Sjo_jvkYUK2 zR8>_Ge5MvNRcv&UNqB5YILry6FhmYhML1@+Y&bC5L>>s8D>p`^%#9N!OhCJd@|jH9 z20y1TvNfR(Vd?zjDuFm&eDOsbnfR#~OeR$wXz7pzU>z`epZO7;&Z+=1E@Qx~N>}Mo zUtrgc7=cj$qlnB(F@~QTVQs)CmsqqQfIe#p%&HVnb^ItsRa!YmE^&)4TA(BW%fV(c zxum1s5vLC{3MjT`UwQyZL^UfO6(x6mZ=RRQRpDnj?#4u)B)&UHpdHFcRrV(w4t7h@ zt0MMTcFskNPyPPDiN}u{H+CE$cv~Z_?3mfy+Ja3&B9&}tW&3ln=*gg`^tn>m1dhXa zmISLx*$R&R)?+Qv6mBaCl*xh*7~0s1`TWH~MrN8V&27`4cdcIKXle3ysfqRKWzIf_ zt+p|{ayv0dlu4)9KS+~Mta76@p_T@2OSZk+ejWyAbR(e0Q5mW2TKS34CTrptQN8%W z@@JlWx2eG!@O6vDw|xJ)Gmbr820NQg;H4M}vfraSfrFCE0lxO=Wqy1MpzDA5f%)a7 zqncY{Sur|CSZ2?kSS0H5`^uUcHr(~6rL$&cPCH}3N#orkhvS|dXlpm1`1Xd-G=ro^ z8b-3mj)P?F_9!DZ>~>@sWI5*reAqI(@m=#8Zz>Wu(S#|JWe5qk)!Nkf=;Mx6YX}&< zIh78L8fnIzgy(O@R}#&bfET$Jl{rP33VKhTIO*8q#$rx|@`lw}Y@3-uVxs(yfBb`Z zzzVu078+ra%rcc#0?Fc-MCV!-3Qty!iYgJkG^%FABp5qCSs}*oiXi{6XoO&_x*${v zql|?2Vj!&?Sj!iHoSF}ibjSiQ{R=26`hu70@y*2Q(MKP}k>kP(FC>mAL&bEAB$_&_ zVP^Od6!7Imr-4MvlKw3}{f{qw@k`<ohb^OZ`CxPzRK{K_=N9Y|*Q{B);Jx`+pR#Dd z{EnI_KryA817xs^&G>{pAU=(z73qadEr~`UdPR~PVRLo|Ik*^qcwYdRKpT*oN;|}K z*g9*n|1P>m*2d6H+8mUVti8(GDr~LYVE96qM_D`}LNJx0tAq!oOaKr?0hlor;c^ji zFm(+F93F3V*G@S1!aL<NMx)FUok#XX@HyCfTT*rZ&TX#taN0}6zb(r*Rt)NlB9tu| ztTxdTO**`OCwmz>@Pm1I`sxSouZ%Z1gWk2?;HV2PGebuZzlJKQT%K<4kp|iIHvZox zP{`v2o%vtcw|)3wasZJS0iSG$A-i8-qsBf(2!bxR$Keec7D-*++W89_SFein>e(rR zlP?+snIF+x^qE*Wc_Ap&x_JC#+<khQTYl1|#FKvD56e8JHf>5Fhjb$5_PSDucH_ia zxU_zAq<(W^-dl_B?dBYPe6Q1|gpWG`w{O{NJ)j%^vAQpi%B|2B_A7uAF6u0`S}IlI zK$K0!va<6AlQbWt?d%US5`t!f4}ZDK0R~e?#F>pch0d~Rce2&IGjsK{7rSQMk@mQ! z{}HvHzs7Xyp7sem``Frv1rJ1E+b0e-_zjzqa9NjbT}O{Ojsl1}s2j22my^0J;H5lE z!zjTs*>S`^9iB`+N#T<dI4Vcwz?>-W)t{g&%p6dMy|Xj}BqKP@n>P>XnXtqZR$h%j zrBWF=2Tqbt=MYZdABk~d<qWkmD++9*fg2KQ1E`C~jvY&m7SNd&QzR&ZH3nu(+y$-d zs&mlHa3e#@jhNTtGme6VbG6FjE+r1iaIVy|tE!6m2T>1L*;P1{zz}20{;0_|7hWNV zkuW&8gyn9GJ{R$#bYb<Hh&#MK7~-bQ=7Z(Q`X)y*je)%_Xg3d}B&MSjXl+hZ2ECXf zupMB1lWA=L0R^6;kq@h@w@#igB3zocsCQyRE5ec0_F3~|n4Wz!2P)(b3D{fab@*8m zj$;@dX>6D94cteg(*zkr8z}lsT4U<Bv_JMpX!B;8)gEw%k!dDl(dv&|b*UonwlT6# z;b;E;!gIG5z_#6RNS}!<xfp`W1VmQY=@n-pneuuZ`1s<FefD`nj~`>&+RTRa8(Q1r zGV!vL6d51^8>UUtkwmKqco_CfJngLMWWMs1?m=hQd;T=9CDAny=z>I;N<<hcufH{& z-3Zt_)0L@s*}7E;w&<ApT=Re-C8wS_?Bwx|F{3c`5_D(Y1{Nb7$V$IRx^}o^S|^h~ zL4V+leGAy;iiwj_3?~ljR)wK^$mI|F6X_&A%(0djvpu3syO4jI>efH;NENHr@pPiB zqRa8enW4k5(Sx$`58%{JA(aTFS42T*|CfkV?4*ey6`WI1mJ?};P0BO#zxL{X7&Uc% z|NGxZ(fym>{08|Lp?UV~+4vTJ{p(-HPY<??^O7?8y{hq_Tj-DlU}jYeC&;JZ2SBoZ zaMe{;;d6!>1k)AbmLd4wbkj}Do|Hc5c_vmUoZ07`0lVj(doUl^)o^IFim#M;<&{?u zogpmZUv|8OVydt1m{~kONP7UU5*$KcRw+PBO!MGLakq)u*U1IeM@A+HpU*EdI(Ao+ z6*C{!1H$6a6F&0bD^EPU%HtjwY4?RfHSwfSX*AXri$$ucYKYsDCUj4-9d8bHAd0s6 zqVZ<0V?);-n}6}&6Fns!IAk)K@&KF;i7Cu3H6l8Rv;ms~OMzoJU7n*keQe2qKS`!J zf;M~erh0LE5delIdox*q3?~9kqRqTEYw7IS6;18gKv|@+dhn$eneLrLDay+r09(#_ zkPg{?ZZ;FBpsb0~l~$dbL_OvRqEZ$7V>hg9hHZtaI^&*G=kl~07r`s6E<siu7&U0d z!W2J5(LlmpH|g_xjyTd>^9`pfIOKPCE@m@5YV{En#ou=I=XxA_Le-;>u9!DxYfF7N z84bA|-BK;#cV4Z3|BZR~bu!1F(0%+VohP1ZSVMp|5(x~i@$1D(E2nOj2H;2pU9uH* zI_dW?ZF0(Q+ahTd!_9fX1pIE|QMsJn*0yG7+8IYmPMTS-t(pBsH>|Wh{`#(!y)HV> zl$Anp$nZRYYDiuLd~tGC)wa~9rZDy*GgnD^4*C{Ax4=vF(q10n*w{lLM`4zQ;DoIM zb+U;k(lD7!T!3e)f)CS%j*r{R`uBISLl%JPZpBFO4`CPYNxa9-KmUBzbP-YkU4F73 zFow`<3Jnrt7Eei5f;CPS_cC?T8g@DckPBB;$-H6RdN!0M2mdzacX~<hq6}%LH54-s z!X9vDQqYwspRpPS>N4Va=_DjPW-<f_lvqWWAA7{v6Y%0^G#(510~C%$P48Os<*%L+ zX<7T|gG;liF6mh3h9n!!ID?LEv1}@`5k;@KengT@*|wMq?Jye(noPgJM_&7#i%&WQ zOJro1tSkzW;CI{!tL#WzvVcrB$4nxd@;N-As!&-)S=0Iixmz~38unH%m8QXskkGA< zUdpUlzWC9HgDq`dx4$7!(rv;dGhw{2X`TZ-6PQq*Q%t+)0m4!s0JDz3x&!^r(k@Dp zl&B5>XJpVwOjaCVLd>fw(5%|-#G@CC%0V3?2vnkiZjWJ(h0u^P#PAOG9cZroUcg^+ z)GvSbsxRH&oe8wI)%EJ$<BYS-*zx^VEHcxlniu~5;mYNW>69Y~(WOhH4UT7?+A?j% zntSdEjvL>1%9OydN3nf|GnRBhih{H**|`e(04bdkwL=%xASU~EObP5&u?t|G0<}!m z74(Li6V0t#8^hhYnDrZ1KlFH6OS>!OYzg@~O*qjUf0Qh%@cNLGtwyMl+ALl2KXVYb zRF_Laz&7z4v8N;YcKn$yzUTkB3rj;SH+b-1MS5L1<~hJKIlwT|wqDwEjsM&dhcW=u zlPcO`frb8=;AcI0^k5itcre0ZR6tpD&H(W5fB$<d*D;PqL9HZ$;sQwC)o@UTONy^p zb+N9@Irh&$vM%@+3KWQJS5+1B51Jl;p~Ai3p|BK*!Rt#Q;rIzMD5f}o7UY5-BVM@h zUl#OOb_@8iFBX;r??Wo+KiGWjx}FKM^&gLKYKypoj+$iF9m_gg-as;eoGc<|)>UF$ z;dHVo?XK@XB5=u7eb2p2%xH0^!^X;shS8Bp#G_tcNVlL9c%(f-k9^LwkHjua9K{g2 zq&&Pe%XWlp$&igl#H&<Fb0<8OJ0q<I4d$Fz`z10-Z>Y6*?Vu~KAP}$w6hz7gRVXi2 z71PdpAeoAKJYJwJo=GLLF`rZRoMNnFt)dF1>oPHk%vfDhjwxF#YWrPkl3@@WMDWGI z%UbjWg0ja3E?;P+HIzzajk)HlVA;{Xzim}RTe8$yxnZSAL=8dqs>hjQ$C@j@(D&`v z&GhFNzxm3hO)DFsvC5>WY^={V)hCxOSo6$7?hzwu&X`hq(m2z*k6p~i3PBc8q7tG? z=4v#<pWDO<qHx0RtRc0_4V`;RO5C0@HW*AHNVlQb$(ZT0BX7N1jdOA^oaj>79a0Hl zz*izMuW@j;x)<3YSYA%3lB8j<l%p!QEC?h8#;988!cV<%FOM*DRGYf=OU=r$VZyBV zlCRH#A;ao5XD_S$rxiP70a&3IxMl3oKeI#+I-*{tXH@}$**Y^L7Vyy<1E08T6Fi0S z<0^y7)QLoaU5x}aE6`E^@fZCw6EU_R<Y!^3rNhth091YK>b;8jd*}fx8m6MGkjm;T zoC@h@^Hz+A#XSe7%`IC~>{wb=#eU=x35eCS*0$DAN!a5xadszkx`zxmxBhaJ$*g_y zk+lgH^#Wa5qR|X$OmLeWd2QTXcfiLIN=?`Bm%h~PiqGK_B8_6@&#Q{cbj<A(aVtZt z2Z^|(NhJ>ibZ6E<U6uo)F|S|-5XVn68D&d`413&&02H(EfFaqt?=E}liJG?dWZblc ztNWgFmKiz1c&yPE&ct?>nXkY2|4w>9wqW!y7}zLb_w0?Q&C+>h@q&g$^A~L1xG9r$ z_v$ln_|e1Gt%{_Q?m!@@^CN%>`PT-k$koXjuuF~g2%bzxNe45zEMcU|E6umR=Z|k0 z^w9lF+S;3Z?%r5C!<XEi3=zL;`?~t}F=tO1ymZ0fY5y><%&D8Zps}Uhn@PCRsggD8 zk}KD(eR+1Kdrvd*v?Goi>pOm&si<OwI6$i<0I3-KVXSQ7QsPd6&Js~elG9yUSq_H9 zS`#3wi@<1`Hm!a3xw7WgY&6mw3J;ocI;+1ax5tgbndS=c$^<Y+c+4a7^EO3as#Jbx zYu|Q&H<GVB^JDNywbEkgml{>lRnAY#$pM(Tglp)w=N({Yg|GJjYu6`kP5}i$Q`Y1` zR-%tG(){EI$}%tr#6U7QinTL>?-55Fp(FzILJB&ZyJ-l;xXP*n4oFPj&}^fBCa2?6 zP7z(J-Az@+O9xL6h)C#Q?^UPn0q1OJ%)a`{x?69VzIlDA$5Gv-d-|8ZIr+qK2#{=~ z3jjO9Sb~~(G9CB2!!RXyUv-ta?uMQYSNib>+ghSAw>uyqso>>U-~@e{IHowF#OqXE zS?V{bcHxvTHf&`DJkd}(39TwsV|6b|ZxVLUTvD-$BBE>*g*A6ob`BBFA=yqy{lwNS z>&l&wC|Yydj!hdjJ@sUA;bNkeH~Ir5M~|pF_bhQ|A&5Q+Jiv)niWbwZdcf)Phv{{K zLBjBfbn^G7%zbyh|Ni_1M-KOX=E9SMC5|`WT5;F!-dw!I6Y%$m$LeL6WDo%@89ABZ zWCa14naMNI<#Gk#lvP#ovL?VPhSU7;Cngl^^@rb2b2zJ78U}RfmNOET8Ztz}GRGWe zh72>8H`L6TQ!{&Z+pHP$*R78^-8F7Uc~iTqesSvEMIZKf#6R+=%2Q4*8$aF*9K<Zk z8D~Akhgp2o1+`cdwk?CEWZ^$hf-hAznTa}5ZHbMm%==5@@4j7=j<=w0KBCrt(fND= zX?K`q5}|3V`q&>@ls$G8*-{Pf#a<M$Tw_htcmxT6gu9XhS0w3)UQ(^0p6}(6+fiY{ zia}zv>Y@_3E;Yl46_}BIxe6qI41nLuW_;{ohb#coBRUL>5W+5EF0R>(3M0WVa22>c z_uO*{9*H#;W?A@m>vBEgr*kMu?uH;#{N)iix8dRjq7!~nYoKzifyXHT(}s^dLd6>o ztR4_UCn5qe<xlaUWB*xJ={RC=&uhMT^#k{AocB&6VFQTZBGdn@O!XXD@fUY{5?*4d z;rfZE2A5pI0k6NYHXd((;?WPY&K@Qe6t5$%KNArhOgf1m;@Y&T{+8=E{N+!n3qCXI z)Jc9KAF&}XB8PE?S)7G!6Q42{A6QVi0|s03XdVa-msN!cU!RR8qZo8;X)qaV6zoRD z?I|;N-j)|<c8O;Yzam{L`<-#RsqL9?ds8sYbk;9xhPjxm2i6cANUb403fSon$b$N` z=gn=mzV*Sv##1Mq{>%SYfz}r?_{=4po_N&UeDmV<8{0~V=q!k9UqH}F&P4-_6&F8A zB1y_o=2g~=z~M>wy<S&^`S$mNiR4kCk}cgk4~Ry^%1=FZ!8=MaO~OMhRBA5nVa_<c zWZCi)X1!vjKEL>#xgSQ8rM^J7bh32)hUCT#Tjosv@UMNcCmi2>%ITet9%Edc-E1$3 z2+wmJt^n?DY6mT?a3-Cubik91CtI7=EOWj5OsJ)SrQS$csO$I>%)kN08|DpI`pq~o zCj)?KvAhH*oR_1a(j4nkUdjgnGu(k6!jNH@@LMR~-oFnA?#1s2Hmmn^gjl{i>Lg#K zVP(bpQ1w5h=sv&jKc!Wl&O;b-MwIyxktR6-gQ>SLLdd?DKoh@PH?9Ic^{EsP4wz2s znt{@apfVK3N}kneLq;n8@)PkFA(#c@lTSWbYY?`}CuNgP%JjT=Jm`9$z%{hxaLx>7 zn|w45f(p7EE<ZW(OsxN4e~&(9-h$wwg>~M5x1EIxG|FDM6LAFPX!$C0epx9_CA=QD zgAHc-_BA*CBINYD9({1R+ch|aNS)wLcPbSPU<RG?M_RH`({<t2#F94`-`68BZsLG* zFK~?<Z9?S&;UX5xbBKDy9>4%_B9ry8nyjnTm^x&#X*M~k?R!Kb^`hTXPQb&4wGmh( zW<EHynEFl44?XH$xS~@{#p3#{T_;X7lTI=IAe;=hm8{#w>JYYEOuOlUB+((QCs^sG zE#`syH!WP)Tw3P1?DG}f`^gxQ=)p;6nZG{fT(v%iQbgiVLNqM6VkQl666Pvu7Q6>k zCyzbelStc;8*FAp1S|}v@ZO~q2Ja4cpu~Ld`r~m?i?*^xZ~3+b@@*r;l+EIMMTI$L zv>AD<x%BG6Z_OS2?B6%OJZsH{b?#JCFq<t+$2%`y(DK28x)&dd^cm!zbYa&M$D85( ztqU(`g{UCnERD}}?gX6?CoSsFCRV)ldSd?Eu8Bx1lezvqORv1x8X^kaNdz<}`$pK- z=)qcJ*@i*<IRGxO#E<qSqAKa5`FoS2Hx`h)V?Bz#g-Qx#3ONVD$)OCuI^-+>;2N~U z^hy=cVDOn|p2_kpl51hQ1kY8F=61Buz%W`A7t(-$x9qRLi3+%!bM?LV-eYd1&TYFP zvIAkTi*4A~9@t?(MN+ZaSrmndD24(7gcz^Wk9Q9`WT&q=mS6`tPu_INn<fZ@2c-)V zF=7gg4Ni&)0s#las49{&-HCj3^T2Fo>qCECP*yskrP+xTAS=7h=3afvHmqG6PvVc> zxi#fpw<dV+-Af;NylK>N)u)|x#7PrO@4iUD5_=(?CH?^-RMO!F=}}D!ts)uYdPKe> z<PQbQ+8UyWDsh7PHXBE|%V3T*>!o!wXZ0&7SzEW&d&Cjd=bUYN^x(ZDZbPA)m@s@y z##pH0&_018Ks|Rfm0GvnJ?FI*!B9`PcWu{RA`db{;+hypdohNuOQp*F{xTLTtztq{ z&C8d@=Fi)@a&hX3$Nzrm6%&RYIoOAY4Cc9!oPjR%7%~)UGKU{h3I0CV0f@GE`;-G= z=3#_Zfk1IW$DY8^xsy5lG&5>s*A1WVI&+$t^K#uAvsX7YIRd82ZMtl%cW!*OZN__Z z`VH`pJEq@hr<9F3!Bi3Y3_4}`g2-#76^>F*ytRexm|Bx<tWji~iLD{esLL)kJ-Z>X zq9OM?O++vjDxtw7(LXc8umT7<@&eXLYx@Qlf8~4NPzGQXUwG3(0F;6jg4qy=tDOM) zQc|Z&Krbf<&2V0h3dSgz3G-cDRjqR<#bB+R;Aezf;T9~YC8~?1yL{gk|38R(fH{^9 zbjNpqBVz2zrrs=)CDSfMT!<*`x1kjT17VpipT82LSO5+aXt%pepch6Y8Zy?^V2(H^ zVY&r(%?3Rp5%=i>23LDM&40e<%@X&~ZAsi#;(hzOZn@QLtsn6Br<X3BzdE(Wmy8Fp z&Yo@2s+qH!Uw-SI+WSi;o;vW9lg;RnrlOR9K|VrICJb8$#=U8;L|Jm-IBJcvJ*K)# z=S<7ybTqR1!^PRQ6CFX9S+V@>yYH@yw6vyE^<||;o^_@<?syd73AXU^ihWlu@lwUK zn;u~4JsVEM;V?K6nYI=jxgFt3UzhH(Ab|1}^u^E(dhocbkz(0B17C0nqk$W?$!^}d zdTV1e6dGu<Wm~oozfsnO*`tuDlf>j8$#maBm^?@#En~{Z{?4df?951qhpC^=3dtm) z494<Q>;YM<z=^C^XVasTId-_IyRzoJxivGVH@-Z5(~^btv3P~UQ67u-Ubr~1c>c;q z9*G@ubm!A1^})C3h#{<Um^O!RNz;}s8<(>?M_sfo5J^|LL!nVe8mPtZOFBKQf6ywh zm+3-o4xrODn_198+g241JMV!*7Jv(w%6o&m@KdxCilE9{(IJyh0zSE<Yr32e{pyc@ z{NsloehBUo*qO*#Eb-#P#8#}md-f{yqRK{WjZS%%`myjjFjX9d1{Y8EsRufuFSJDB zcH)s@?25dbjTyh&Y+h^DZ!+!a_MZJi{xF8HH73)RKw}~-NkS8#&BK>Rn5G~u6~Hm= zswxW_E>>PM7``IY^zUn~yRKiRJ^1ufOWc{>P8NdWtGy+amz`-Y`Ru@%FPa%IC8xi% zdgI1=_G!m$*d(jopBrDYXzt(ciJU&E&)DO;oIJtRs~@7TUu1M1f>UWag?p52$`CfC zl_ksDmN*c`aoKEaWet1doqu$!_|WUjHaVQ0BZs*@b0Ll;fJP=0w^pnO;V94D((Gc| zO%E`p>=B5i8X>G$Ms<4Q34E-*(YSb{`Tc0loDcwiu$Oce{)20e;AlME>T$WpoH%gI zX!GGhbLaoXeEw1|4nYE~X*Y`z&<X3Rl7L(5E|hOZ7UDzFwE?{C<W6Cj%YuG*rXzNv z*%nC{fMmsiIbRy<KGU^xsMBfYxDzTazO-V_9P`3+ZLhw$DwbgW=y3%qW0}nJGwP>K zTQRV<=GZY66V54Jx%BymW;_##tz(CUE(Sj&-^f0FFF5}*rb}0X<zu5KFYc7-MJgx$ zic2)lly->N%c*<_#k89qIAp&tIA%eAsL-f9l)eCT0a_CI9JLsDtTHjNIN0Tie3tGd zGo2znCEt(k*1!pODR-tG#9z5o(+LS!7LTohdN<u&ymZj@fRYVFLV}}!zOjgT`Dydw zldBiKw=i6WJ$<XEq@uR(gt@Oqg1&Ap_trRJqG6#{<?JHzl*`6uAWlanh)^O4oWwrC zI!q#?z^t)ox#d5*I^2y<Jh8Q%ZHq!_?5z;A(Pp21jyd%#&%*cn&we@b{0oZ~E!fhq zsZ%0WYT7Fk8P~)2*G+wD;lLrj@ss;ZnBpBi%ql$bJq^2~!psw4Z@5dJnxsj3O(5iO zwXa@RGH=<2f4o!^iMM1Dt(_{5zVLi`yxq;v<3*B|IRfSr!aH@j@}L{De`bSI0Ig|g zG2s&NZ}fUlKloajjJGccB<w(9B%?PDFro3rliB(@=~u7IA5Ay9T|T_Xd_nA|0`XK7 zXIkcNE(eCsL2QXxr?4(&vM4VyuJzls#DfJOWMo~_1mr9L%k(Y;{$*Xb5{adgo$%S> z8hZ+DOE$%nti03=J<1FkX-+%0Waa8%k3A86_0<oTyuU7)tZ)T;W#YBVR>f9t`tZ@` zpGzfQO~p2NO$*_o<Jt5JCbBgezY4=GcaXqbR4wr=nRXC=hPGlq<;dwy#DFjdz0#~= z+D#7}vH+~_3@CB}nsO{~QnjBVr=Vt3dn-7sA}bL@DMNW6SwhIzk{;`uq4#o$!UWhN z1PA8`$|QXXg^THs>45^x=o`TwTUyNT{-^Gt-@TD+$$t3@XPtkM!&i#=m3idR`c*5| zIZSsrFkA<Z6hDMRR9<o9Kx-|51O>nmaS{Zsw-(AO9b`n9CiU!XethGQRJ!?zCtq_U zQ$);gBuvn<*~a$R@Dcu@!-MBtc+A{4%uCN^UYWjj-OBoCG~{*mXlahV{`!V@=D+&D zgU&HyYA-yqH)b_4mkF?c9SepiNXx>6eNGTzYg7G_8864@PwNqhx!T*?0-3I3j&YxV zHX&HW3z?-nmW{=NhK)zic_P^04TB_Akg=ql#k5@y&^Hco1nSk>oOnvVryqN_xv^yV z5;JU&SSPVU&n&88GfNWe{Oj=tL(HpWX6E)W!{=5gqAkLvgl#EU6|pa*^U>^z^avhf z=xz_v{}2`A2e4Xn%Spv>Eb^Hq0lg$@<9`-Lm;?wkZr4!8F_}t6h}!1$m9P;dE|Zw0 zjvF0VxpL^VSB6e~VeRX0)-~5-As8g!OT4kcm<GgXcp#9Dalu;1A{AZI+CDhz$I%?g z#Ahc6CQhhxL0@ZfAZ<|8b)hukhwY#38dChxp$86G09GhfP=vPOq$&p^w(1F;0ElW= zsGU0bKr*Sob_IrQ35>AV--ca}xJ3(7hS(kKgoOs1Ee`#5^WY90TRc7Jdw?M(b<{-@ zt>WSP&Hw)Dy+~u*_20ed8`nERWx`~-9$`j|sakp2`gdMm?Qh2brY{`H##)Hu$r+9M zLP0kxg$N0-V@#}Mb1i4OskOO0Tn&?D*%vi6;MaeE`OjaLVevZel|_M+k?;Y?Kh9K5 z*o%yT{<uet>2;1d`!wgWg}q;VDm8P)rde;UNv2Ai?vhlhWaYB>%4IEco>|?q)^*;$ z^%#AUVXrz2wW~Y#4p)>%vXLWkTr&UwKmbWZK~!ME@%{@hc4=JUY-uhj352_q^}6aR zQ&}PIO}vKXoia;cuSN0FOd4#Vb4>K0AI<&p0(4e3l}RR?!C+Y@=M`V7T(HEwd4=<t z$IQtm2)uzlo7S5bo;6F~lWi8zrJ=BGt~X(#L%S-Za}kcc*q)cVy#edmO*35yWM3vj zUI|l5v^4=;wll!s7|(2xY*9)J4s$y|El0L0&%GXNZR~O=GBB|Y<T}Y-OQo`IvGBtH zU)<r+N&MnmZtSsQW>{A<_-b?I6+K^hv**;Qb#KmCv1-}-+4!ooX~6!O-6#X0a3qyz zjYk(Yu3NsP9v5P%l_yIykz7DcX{sup?E*E}E7th@!D6?c2;^E?{Ll8lAq&7Vp|rb8 zLW%|1l*t@;$%}JhNmO2+Vo)%^tgM!Ng;=E!OrSZDy$BHsL~ya>Y_Ea7EC3V6k_BLV zhehpEOov(z*fF)Uuy{NjX>~pQSbb|_=f1teLr1x?=;4H#h`em7I~ji<R$5XLB>F6@ zNwP(GXuUkKVKz@a`KB+Bx#*HHrC7RR*qTX}h0B;3vIOF>QW4r_RFvI&IBvOR{JsC{ zE)7{xiHg8p4|*6Ylsbub829-@!$+DS{oR*d(PQ@OX6iIEZTf3lwj}+&Uam}eePg!1 zv2E^>*Lw6#PdcUcf>V2p>SVU0+ZL^S*Vn$eXKHIW;M!0YUX_iUbpC~ABr&;gKo;7S ze^9rLYs4F;2;Ec^e`OqZoq!f1D!WkowtJo7iKm$FUpMaezkc`CSDwA`hS1T+RHYNq zB}<x?FRx_VgOajTq<zJAzx(=`Q+j^xYsYu)A=R>mih3><Z%aZD3B#7a!fYgtG=CnH zB_dne=Q{;fp(sfNs&t7#pC-mksMM~xvH(mK<ZzRyv=N$tVgwC>YNaq3%p`pTDn~$O zB7lsXu>nNn4Kl<lA9tb|e`3wXRW<LvKKSRiOkcLFJ(0r6DwAw!A(Wa4(G-@a{p_+u z3VOVWR2*U#pJm)|tqZS(etEWSvvt1H)@w_P$B*>DAq&8OZUJ`-Z>{Ld&%z1kin|4| zxKLP6ASns}=hTKg1U!?^PXK$yj2T!^v*$+N{{0+GSuL)2ta*p3ia!td9w^MNWHcG; zRFbX5#cPORhi5HYVivx)+V3fgC01c6YC{K#!VR24=ZxiQtj*yL2ZaqmBq=Z4aMp~C zk3RN}-`($_hh8}IoUxzz3`VYEAmecQC}v|I@g(AE@jw@mhiC!bKtH%~ECeNih4?^) z;ZamN4~?c5sfFY;z7o?jXfCZaXP#{qEIj@nQ`b*>e#^3@b@6P-=`4*zJFi{lx@+O) zXa72H<nRq2EP8IumUl}`Yo$r_GoEhcrKg-a(Oh*6+s;uDJE2>aY28V9n3~eKWg8h~ z?)Id3_-GHX&Pyiv<!5GI;xwPT%#0o~^6j^}f3SS+g7@F8s_Zm$#DLF#vETDAHm+Q= zAsFbLiLMWYGh&w~qbdKO2e&7QWQ%CPikVEcB#IiLquoRvwS-7H{x2XdKEiT4S<r($ z=FTNolBE?}e<2PAxlk!e@q7WQu)Ajx5Il>{Pu4-W259%|Z3gr%Yi_>qo8Nqa*JG1n z2o()qtUWqz!nmW38Ya4NN@kcGFau?ZnF7zLPBuCwct@Pz%+%z}q%oA16Z^#CVdp(? z$O7=rUw7Yg6>&Kh(3d(uYiy+1-~kJ)5hF(Eb{q)DMfBbG4n8pN$Y40nDC4tB`(Sba zFak<z3w*`nba;XxFVUU>V3tV}iHtb!%0!JV3?zOyzDZb#%2o%)3>)6Hq~t6j488T% z$V9>`%uDvc>A)l9mr6Fm9ARzjALlNS0J*4c<iXpquw29>Vcs^Hp)+YJ%FNgk%+W`8 zzwEN^b6zvgP2Ke7YirVV_$Y_{uBxV%jZe>f+L%S5V7fViC75Y3$>oujiN}tXWk4-m zV{oKhxJ)LV*tYF#vaxMzW82w{?d-;OHs;2*ZQHhW=eze#)%=;NnX329(bL^ex9e`j z=72GhT*P_XX?m1ho4!F}3QdvzqYyx!Y0b$${hkP&IR%$>6oFV7{dd-2Z1D2>02&nm z*GH&Y;T-0<9?CUR#83>g+`WvNYZX}bdSF{ga0swlN>_gU;(GfWn&@aK1NuDNluZvS z=wjycSqgXJV>qtN)=mwa^WUMZy1&eoZIk$SXR)pLSuou`CuZ64TB$^z{Z79N4{PhP zem;_n7<7@OjWSBuMta<o4J0rxjwoMY1L=O6T2jRa&70;sA{x*?^7i)+JiZzsr{v^_ zrWMW|Js3_r<tR)qt7cpT{GooxS`;;m6>_(+Weef;JHDY;WMPI>Kl+I4?ApBHcQ^2$ zENi!cziLIC7k@}3YBasSo7retG**oAw4+_={iza&504a+-7j<Xf}8P}5tJbj{zM6{ zX+q5&R^17u@Uia19ksn<q<v>T{GRWWXo*ZT=NEp$Kb`5Uks^QA#`k^{x@6(keBXgw zx1v5c&x6poz{m$(Vkn!fMYb|{ORgBy!`^{%Kf$kmwmEPIL}tpiL^g#*r`77a&SN%m zBd%sQ7W);wCCULWZ55dDf)F}Z@i03eXMN5jon|P6aC5zHWhWA&uY+|uyJ;<hOR9Z9 z**0>75Z>3KR!7{z0SPU7CgtqN6Rnc->y&mH`xDxQcch4Yk~^q@%eQQV4xHpCuK-Lc zQJR=Mi6kY8{$zo|L1rU<WLVZyw=cnJmf$tXxH?rye?Jd33IQ*PaCk#QLkLc?sk6H9 zD~b15U&9F9%>ft;Qbah7v^E@eOQ3616^`^@uW#&zN(=8#It3S#4`<`KMu92YIJVg4 z=_4o&OIHsC0u%y&&)t|qtHeyC(mdzIOeO>jTDDG!cC;Mr#<W5<BG*k{s&ZMZ`Fsx& zW{JAor8O7t2hN}roW4DPU+cHw1fqWKHjW~1R(ty_4ui~!E-qg1JF+1`*3PncO^rA4 zQtMF~mHqQ!-Omb#NLbGgX)W2)_Hi&a?l;Y2M21F5Gf&%r`-8U;Mneqn)=pzGm2;>F zLdv#s^l_qQZKMd{aDAjnJeo|u6}_BhR@G0E8xh$p_|4YIVUXc-*h&q=p~?}&7Q$;g zt*I^Ayzi;I!1QUYPBM|tAzdRbpFn+4X`?T2$D2Qoviffpgq~0+sMxNB&?wdSg|4A| z;M<mz@)jl16gPWC+d|2}u6}yM%PB<x>d(pA9d|^I5$?@oDUapg?5Er?WeFhpmA3I{ z_HG;9u)>y+jP94y4~VONH*zO4u%J^N1ge9jrD}`omXTe+8Ti|UiA}q<i7_MkgKxgS z@GaO&azalrWd77k)d%nXxnB3L+8u$-L-LpEVe^<kfqLNLi7lN-q4Q#ravHhUn-7yM zFf4|pFRVpS3p2gVP?j!&JfhgwW)UBuhLKe3f{xy3K{-a#De*SkcCv$u_H}h|?Iqw4 z>o@TQ_@QFz%#Lbe1_vvN*z)ipgMUJ)?JAQoOE-f|VYuxsMQkLZ4Q22S8>c>B5cCti zpq2mBUJPZrYMR93I1Tet3&8=yujQkQCtMWnvgY#C(M8Uu4G#nOPxnETp{FQ=_g#N* zi2Dgtm!GQj6Mz100`5Uo7wf3t%YH%vwIWp~GbWuZgY&>|m2o5<aj?xiQTJQbG{c?Y zkuvr2WJX;HWir!RL<rCfeksgaHyHoU?d7iyweo<h)$0M<-&@CJ*!fsFo!mM(#sB?k z24;(h>peArYM7|(ikZXXYipD;D!EWzk%QuH)4JqDjn&bgJP^5xsS*$mi4$Cq|3gfJ zsy8%zRjQ3Eyh9}Gf)ae2kLM!IZwGQ$7}8u6kB%&y!_l89Efu-ce@#)S50ie8S?`$) zX}~f)P78K#0nG~9-0Pt{i`xunFQL&sv>@}CxCVD|$@jEPF!`}?N^oDaEEQ16vMd_l zXoY+8<4!6U7*Q$z2XRJrtP$6Cj-I0%75QSb!$*CgPm44ZBlWf4IKZ_Po@u}xZ-1~6 z40vCj@ce1rKHR)b=^~)7y~pDKI$_Wi`M?*+Zjp!u-V;?7cIYx=;>+BjU1yNN`|5wA zqfL@DtvkcZ^nhG|LVfg0Q5HC$>Tf?5A4T(a|C_NGm>Rr+^t>bsOG^+PklnLyEkGVD zs$Q?EdaYfdEAZ(V<HGB{in#+6r$sw!nAB>YVn4g4ZF=Sozdetf(u=i~gP3piT%bjL zyfU}a&Z)jsv(wZx;pOK$fb8dNy`@vDB@vE=x`gY(t$MB-h8PvRg#8lws{FO;@MrW6 zPG^<<{t%uTP5HO%qtGt6R(bC_KN8lF%8F@Or~Tc>(+0cEA;)G=1f;y-9@TY=*Vd+{ zp3g%BbxhNgsWRHm`0cxQ*4pP59F;?x7GDBUjn8CwYlLZj5DnM0v;Cg>2$`2qMTiR= zxdj^4rCic<)Ud`)_~1zN(jJ1Ln*w5gWj_`kH3eVTyv}#OtIucRD)ENMp3IusHIQYf zP`Fo`5GbBT-(4Hz$%*0AfY1-8<^mT^i5h~fynmSC;QPE2_V#!oJMR6kqqcCrnQ-&z z*$|XJ`QNCfl8_(zQ$&h*Q;0ZTCv0FZt7%<@F$o)#v`D#lT~0%kLE;p6yXck+k?+V@ z_tF0NXN)}nD=W-><}}0;i#Kogp}v9DNgtb0T5+<j-uu?^*jl<495o}wP$EMwpQDqk zWAY>D_wQiUJ`%39aPd_+S~e%6H0<&DV*2@rOgaW#B8fKJ-Qb+`z89pCvk*HIMf@<S z+5!~>iBSbAG(S-Dim%(6pOK+#LEFQ*_byyQM?n0)veDYTA%*W|fHh8vS=#%3taOi( zh0l4ai*p&)>S>7c-}Isd5Tn=HZDtbFy=Bo<5zR4{N;H(6k^M7LyP*`~u)?F1WQc~z zlx>=3T14)woOPSsWR$WmADKcj2RiLg{*jh9)1t^Xa#F}&vGi5Vf#ZOSxDiS*T~Cs4 z@kI(*uV)5duLIZy`vev!Vm~Tl(4B$bE{{^U!^@cg*V!=0|AOLy{c4(;lCYLqw>3t6 zxjdGr#|vzk*x;U1guil=mf>diS#T&O*T{9HCL_v`9MW*PXAy`<-!Z7*bwwgG9m@dU zJQ>%M>GX_0=xjOC{V$66&u{6)7dCl{TZ2_S<X(oPe@K>{X%+Rg^nZya{>%Hb{UPnH z>?m{o``m!|eJtkNreVe|LQ1Ip>u+7AwsV>FbO>M8AL{EC4e>5fs4A3*lMNwXmc=w+ z9BZEjeCLHQ)As(Uu8AUlH$Fw?3F9d^#C;vruaorNmnk+I*LNRS-CKTUYn`pUB&?h9 zZXM9x`&Egw_y|%oC#&e_>aN)}Z44?B0Y*0+`w$r}>HHuxXdztY(7B1a-$5F2?<3wV z?IwG|19iNjb~d5@gOBN1(V9`?Zx=t6k`7(XVGe4QX9r{O^H@YA>f}TO)M@yzXFR4l ze&(k5uVCWjWZT-Xp3hfppxF^YaeDO_mYq8B$c7l{XxKFEGCJz-6i&pTS;bp+4|hk1 zInPP#J)-|YiJ`QX-rYOmsSjTYIkNZKy`1v2r^vp2TW=<M<0HbcY^IRI2iY1i3qJQC z&r)Gh8&(TGPdMm%Z9-wU>HWLVR1hobnYAn>5<ga$Rbcl}xn!9#9=`wW>+kH(q&Bsm zYYeSmhdehGLeWuHASeBK?4|9KQrMRVMF0qB*@?4$atO4cef#yeVj=jv4H2xF?J*;c zU3!ru)3I-f%Wv%L_Vw|!<$X6%(cc57%)5uCqOKky(F%4HqWkD@hJ3pk1=fB94(Up( zM$-RscVt4NrL4?qJzvs0K?jZv-aJhTb0;l{u(`vJ;>uW@NR!BYYdp^Ij@n4;^$$)q zDOk<=i+WAJiS(i0q`F!+!C2LLaTerroAQcyUk5lV4;FUN#WP*t^5ZS<ed~7l5U?Oa zfB5BnBUVJA7SQ<~g8ifOrRb~5#u8$8MeGQF$@gY$>(gGkCXmW#X>Tv;3Kp(0uO-OQ zPx|GoMRRU^*U5rk2%Gf>Fq^Qt96VrR<f-gK_$PEO*jgqFR9&cNOB=jtE+y|`i@_v3 zfJtdIePA?+{wG3Yhu>S1-`QNT;!a#-+xvbno5#A-(3S5K@1!<DXc=amumPqwysc7; zabEoHh@@98Y&Y>m!i6)C0}_G!+}P!JEit8Iv?{V8l(`g&4#S@lcXbRu0&jkjWfNRV zYK`0xIHt?>ua<A4egbPYHg^ozeD0b{&DG8CV&35q>e3Ym_}42nv=xN}(^enxJ=#B5 z83munoFqfFNG@g?9dk3^wtm^XDB8bI{T<UlMMC+ShX=VMyDfd>R@CP+#v?$Z`ag8s z{;7ok`E|K46ZtJ;=Lz2Fx9S@VH}A7M_u2Zzx0LJFbB8=g=w5shqe98XDhhtwmsfX| z#c<z^vpan)xL^tbGZBfx6A3`kn)2zvOpZ6Z1E=5!`2Bz=W2k#^T144-naCmi2chhs z^V3(O9ONFiM1N5CM4jmf8k;uQ;5N~^dY~$fz`55M${E-}C1EU!m{Jlsw{#;3BUzML z!s)tnXm54@gyi6anwzt^ja;OeHa>$v)jxCDcgd5oL=YkPwdWndz)|NMj;Sb363n?2 zPg!35_UUmnnQ`S5vUl@ZH_7w1nDbfI`i~x;H3^c>_I=xYh!T%pde!{*t4mvf-JUzo z0CC$XxJ`0mmnF=?=_9Tx;UWOxNa0)r;ul7I^2nM(0;y{uIt$RmRT0+tOgyvN*Y6$K zl&qKRbN6j+b#-*s!OiUfbbbA);j&{jJVZC|T!n+s#tX8f8v0F)tl2Mt2L>J80$jwx z@^8q(py_`6w0y}^E>;=IyJ31eV8rkN*U4Hpa+w0K%!dx)PeDXr`orIKe$0j&|AkRN z?&f7Y8jmzUlc<igeB=!bI5kip!7_6OP7zb<_6*ETn(8#JVOARlYTHvE?{6X@96D?X zNP9;`h$3WG{b+a(#qZ=jYOp%7^<vxLGTIF${(6>#ctx(E(hgM@=k_5ZLS0YNq#=NZ zt<}d?75i!&WBdd`57YALK<XESx30gKpyALXH1Gw~zc%$bUO8GF71V8@3#=dyC?rmS zoV1WQQ72C8Kpv?evolQIq_;RlR?jSfNGNVBpQG`#JCJja(W&>z-xR=dq8bdvDA*bS z{L`uaz@CB^SRhRi|C4__xmtLdz#(*p*V7<`mQ_jy5AATzfb>?j*IhSVo~;>-Kx*Ft zp)N2Xi8)kA<)0?K*S{OxE9?>Rvu<wLe&ay=;SKu~!K4@-agsp=dhu~{YF3<OB<U*O z{XFNPP6|BXlCjiM8?7heruXBJ6rvRQ4WCP+zR>smWQSM*cPYM^<ELcQVD3fxcO!Q~ zbD)r@b0!B2E@2$GLr;c{*pTeoY*k-rMb@aR=T4x$zL9s+16c>NV846Tmu=@}Ha@DC z?4@-W-P0cJJ1~h2OC9!Kcvt^J+xzVpPu!t)pGYeH(e*bdLyR%o?#POFgRchz$TJ~5 zful^9!C1nvRXsbqN+1QWBh$qJHPl1U6Lb&v`5K<=8E%vD(@M+tJA`f|>4(G7nU^Lu zONEO!m|i~5o83Kt=z>YKp&Mc#_`BlNM*h90`1Y~<QQxrb5y`)?TkZgGK1TU#fFo9l zi{h^%C&z5af);Jz6djB0$m&|68M8sk%fwgP2eaSL#LDE7G7r0^ob~%YClf`v433^s z)stZMy`dMH1i9}Wv*v38{`hd6U=VGdnVru}Ojvbx2D4eN2}SQhqs*_#vR>>%vv`mH z951DFcKyUQr<;9`UzpmjMKXDncwMSSEfid7vH74?F_kPPGhbG1sspMkAj!e|z(CwC zF~l0(TQ4KePTAr$E!V?zc^PcC7mg~W01d*Z$s2i~65A3!|F3$9-1!VlA0B2Df^>pW z7v|vM2nB?v>%!dwKY8TyWN|vl3r~vK#N1*$7KgTPQ@=)b6jMt{?2x*_3<K$H+r-_c zU!+EtuH)ce5c-kM^`4<@g78o0QHF{^<<U`B$DKzvtuRxYYiZ}nkRbonIXtadmt9!K z;4ODtl9hjjz^a5SNqAOw9}#|>gWQeZ8pLW0??tp-eeH#_eR3mXK_3c@{ILF;6-uIQ zNe=qY$PMEp{f%is^3TBZVaz2xmlz=C=&0)+IZ)JgpXOih`XxxYGB_xK5s-L9#}GRK z<e{Z-1|AJ0Y}^Z>`g_drI7_2q(1iTZtk4R8AV31OAFM6d$^0wpqg_YZxh(T${W3fQ z4|V=+`%Q42N2B#k_puD3f9M-QD6+^OCG0w(_jK;AkJz;@&n03qWxja%r7HdEw#(ML z$+m7Cs{OUx1qU1HfG!6E!)hI6hWi<!=lzZ65u0bra`$mz{jkhjYa=aO0%;yhr|M*8 z1Egj^S}yG*VPw|m6PSrY2|RQ-4T7_a8wigL@5;>dz8wjIK|ZvO>$+Ip@cMYmVSV)4 zNQG!6sgKG6j1e&;)WGyrt(M(M{?!?!;k+tyWbImp@LGZ3)&{iJD5&2Dbh0RsQNJI4 z>k_6HrQA0FwY7jQrAxHhrr};I<zb4o0BM@n+ud!}HKb2aVogXLcoj}V%`3b<rVt*W z0Ea-1(%c#>6xG|I>%$#ES^FboljD7VXD%k^H3JLW6Is6u78qdsCJBoqgPxTMwY{+g zjmmy7uT61OxRJvAgYmJO$V(`Vd?1m^Vj^9fL?~HYNROL*ZScQ#bBzhoz*{04dMxgW zUqWy}ni>?Ld2yGWZ}$1tLVS8qK5cGi65y$r;j*j)`p(_9Y!8E0psc4H0YV@jNC!C- zgWn`N(pM%cn3Tc@xc=cr4hd7NYHS7py^(BF>=D?uubK^4#3o~?W#v(P5S2DSwERZo zU!oOIz~_x($NrBwka^WgPqM1(^Vea>wM-S=&V^6IKzx`evMUCJ(E3W9h2Z0|Njo=3 z5boW}Q4VrOK0->Ofw0c##PB@rMkpeFx9y)cm!rw8=fQ76_VsKSOhOMk(=j=hy#I~M zN2wZo9HU+{$^-l?^cd0Tq5Cgt2DAi`M%mr6*#mpvReh+jc`b~<Dug3H8&5A*&d<X% zo9YfMyddtLJy5FWf89yp%%hYGxrYUuAltknA|=*buw)YYP&Lc=6Z9gR{{m96)P<`5 z@v<dtCVDufR8<759P1m}U>kU|+Wz?t7piCkB$)JhliuvG3~mV941y$;v9!NjZy`u~ zE#2s;vbV9f|Li0F6w-6vC`H+&axwvJjSD6N?;R)LspRjm<Xq+7Ha*E7{fCLyVP7}h zmh>GJtKuPE=@i#9zDJoM<q*+a6Dy>a@PEDEotqV=6=%7x?vErifWia3o?gpz)jz-q ze7m}GNxc8M%CUe_$vEWil3_SG>Gumu3)9SH(9+!-*y_gdt$vQ+dzLEQ0n#EvRDc>P z+fl%IDN=6tpilqYsg*6CL*Ge(sk%p=HJ_i0b%VcZvq9+sE>#VK?*b;{tcR&45{bK- zNIagJyt)B!UeMm$8N>J#92~8($#dUTIwpB#1MpfHgjsP0R-b>|VD@iw6FT++zYi^P zh_qicu8FB<CA5D{#R<d5)`rm6(bNQCumD|aaDV(d`CG{BYE%H~W+$lWp%4nylz4UD zc7Y+*959atP}m?)bVi|kj41lvf|54~Ezs5bI^okkC}qg~Z|K_<UIv>BLpsrz)2BJ# z#*jl5Dr&H#wwi4wa0V6+U1Y$R<t?-@+}9gZpnWvJ+SH2ka3K@i8x{LNW_w6OKu~Yn zmqx{4sO(&mjIAuVkn?cRx3FN@@z{y!b_aHRqM!S5dbzbCliD%LMU*Lq(g?g{Es{AT zbCgV(Z3Rtq{N)(aOE@XCy2Q`JAdB1A<APecsKTBUx?S8l0KUI+s2pMeJYeFJt-c$x z-RUXnvU~ze@nK#?8GaJn@z3GESZNFzaJ~pO_!p7^gPigxI71`jb+ESFImUF!*~$Ov zAO>4%|F0X6a0v8v{RXCQS*{`;pa3*9_22g=o9;c)O3E4-4P&zR7c#?3T|(GsGU0D+ ztx19K8)xUNYK7Lf?$>W}l%6{EE^S@$0*VRYm3Q0>;-Ay(m-juwW#&L}UH>FGLf}Fj zM4iHY83DP$`%S_@tBqr=QKyzrrRqcLoKhL7rN9JeICT+%%foH|Errw-5rW86KTQKe z8m_5CK;{IuTQczL5O+hHju`5AT(z05FqO!X6)cj$fNFfL!?_SfeLON$_dU)F>wG_8 z#)ryBAsU62!k_d#Nw5s<fc^{YHg!dn3LSaA9t+rX9AVj#mRJ8oP$Fp`4%6cO1bGFY zdYpiCvn!A_VoVTdDRD(4kioN!{so`6_NbSm3L%bv3x$nV6RRVG?m5eXD4Rz&_Lo|M z00+Sf!kLUsxrpC5&Zy)+IJc;bykW9%DF!b>tertq&EK$0i^H~n$?7^pDh6`S`IH9e zstWdHY@-bQ7E}U5?EU8;ZI=vY488J+ck4yLJDV5Mq8rW=X<bQQ4&73fvbEaVqs^e` zauN+nE(XpAGYG~Y85D;%<vD5AjLrfU3Nh~OW=L+-`~076x>y?HrpK0#^jWx80|DG9 zy+ok2@o1<7Ls*?b-lGX;CMBTixhWC49a36&;umt1e^2ZyekXK6YC-z6gfMCjS`>xT z2|Zf?ntO!lShAkXnD#EKTN@3FBzQO=RV%`5-S_Px*9=-A{g=~!nIB#k4G|D?_er&h z<TjYF7^-NN4gO8vxiO10QcHDB@Jq+j^1$?7u<E+HJ}w-{wH3K{f<Y|nMh!UfNSq@a zj|^3g?ct}$N0Li7I1EdN6iw(`kK8>XNErHdiH;uX5$LFM^=qkZ8NLf-LAq?hy(gu9 znkp86hLAwRo`Y;H=O@M>+%_ff#-R-K3-#)+bH*xmu||o|)bW*@(|{<)T$@CjDp?Z` zsKkKn&W(L^yqoxDVp_=D11I&Lix}uSF$O(18Vq4y**Z}jM@G|I9Eo;ml!(B-@~Ez5 zMX*vSb!=z7IKZGHB>8pW;73lY9i11*dNs~Ig&+kx-`%Ip8YTwGMKGIM%NFt5d!HPO zBtS2fNJ$*OcDL_*O<9r<s+<7AF45lq8H9tRvNK&aQ6!E+c0fiL(xB3KfN&Fr3-z9B z6d`Sg!W&8O2)P-!SUMRxaz$G<iP*+!xaK@8Wc^*~|Av3)nT7j3b~T^?wXa0PJ=<+j z`@iE}82<6PlcWq^ZB;qdnLGd=xMdWx?zQ!{iHOhD{!r<#P~qNdhltBxJ1p3T0hS6w z<SE1gu~jm6K`NzUZW@|20*={~Nh%y0%+5}fX1AJO+Jy@b%~D2hA~hsrDV}+{OjyIJ z{dJe~RnNu0?hsn~dMH>4d5y-w@njALn~SmD)Nx@)i}<q#t3EA;of;;^9kz!F?tIGo zkiFZZ5Aj<n&tb8Q+ogG;Y`gFV5gL@xnA4p6H=nzVt-_j6Qv22V6Wy&>4LJr+Vh$0E zQiR}HlaU~H>#$jJ=PQ%n{Daq04?WT$(_}syZht0Lhtk;-3Dy+MCZVCiXF>c6OxG<B z23$7ecAR2@^znB+5o}8%;~Pv8naaaI0tbnzG!rZkEJ{aUg3mLs@<F8_bKENQEQmIf zyq43la!3ZWXsMmY#1)dgNI!A7ZK!yF@u5h(KiB$1KQt8fs+Oi6m1<Trc;6?P0WGfD zk2xY3LRXY6kxk&OQIk@$(5{T#Um=#zxg8}X3e+Mh(s;ZR*&m}$XZbDUvziyn9~8Z0 z_?8ESs3;*?PEkZ40Co#>Rb%dY|EJ9_-;*bvV@y=K%ck_?I@?6j+MsKGv;?U=sD7ds zS%DcZFg05+rzpr@XY~gR47Fp&R!gH@#z^{@G=b!@^N9b7)V~4U9eWtc7mp8Qiuba= z<@fc`^*q3=1^%?=AZV07^6WUULVA4aEe(3C*2W$kPt|FvMriG*GgjfTFcHjL_7Zus zaM$3uw6E>YVhZr{=()e%Xz<A8^EI?6(J_D#5@huH)|Aq;OZ;0s_Z2hOMNj=0%2fAx zfS`XcD`p7Jej>?YuI?>)4SzVL1gt@cJvZ^1q1j^=U{Lov|Liv__J50?y%CD+;6_}U z--BvQi*V|PgV9sA#mws{M8~KFU!(^G;b>IAlxl?mshvG({uar(IzaYk+?N?q&q}lr zQ|~R>7U(MjfM@nF36yRW4N~0u)keNwJ)EH#S!h-Qn7n(tZFl!GfjjPCamaPg1-`+3 zMJoXw6wYM{IXB6>f7rB@t;g2a=Tm{MVeTOtcZ&IeE{s$CpB)mENQPn6bcnL#i_}7S zST)Uz!}nP3-SAq#GQ4ZOLDQ>vz|3Ya{cIvR=B3!b_+0Pmio@>a!Yp<axg^GO+eu3V zM)RmjzXC4;_hlo<MuMi^ezMh_$omkZbSC_mj(`csD0OMf!v>j6^lmY??saBB)xlaa zSaz}dpChsYK8p$<Il3amcaQ_Q!y=|fkeX2c13`-`v=|mXl$K#4!mXhiFA0$m-&f%) zEpWUiIyyQF<&XamL$wf7E+u+(JIEi8K`8&H{~we2T{f96xe%IMRH+0OIA@TndLM<l zmNd_#y${Iq2~)ag0qVIhXeZeKl)_D-G;>u`xb<HjeL|D~u*#A8Qgimi)#EQIwK}Y9 z1BnbM?LjLim9hP6S3R9BAg12f`xR0Y$^<EBw7bkr-WBsr#fDVJZ3`s6yAs?CGHJ;9 z-f$6w&3*XbA1zzQW5{zp!UQ3ZGTYDo+?&>`G&U6QBA%Ylz`iG77QQ)nGHaU^1)u@L zAGAn>GvQ2d`7aRWWw>6>{79Cm1yWKKEt5*xz{7?94}>gSwtqc}0;_r4nur{0G+T^j ze~ulH<567bRRz7ZyIT=h=M1|yZiUh1>@On)9)MPQjG(LsGi(cuiK+;4y<T24ub?dr zsdLgm(Uf%y)1jyWK>xJmdb{fCdgP}JIpd1}Q2HOyqO+bvM~wi#uh_{s)YQVh!GyFl zNaYp*iRhZaA#x255J#njNc|N~{YQzZpt_+&U422pG&B`ce0R|tSQ4hr0iV0rT{vUx zTy$MQV$<Sva29H4eFt}PP<bjYq63cFg(Gg4nwdEe+x1jg1qC;)3%tPNvvwDRf%z@a znInP}tW{=%LWM{j*<i@*NeE2|(<S4^-pm0kV;nNatCUk;57Aoa8PrbF_t;3XnnrMv z2oPh75ubKWBT&Y)XZ!K;eNZJ=ZhGwxR3kvxKZwN`(^1+$X^df*W=e%hOKqS&><$Fi zx|c~@pJs|FwN03u=7Ua;UK$jG*V&W`m%fc_=I55%QF{3nQsnImSm*2Jl9^KH3C^W; z&%Kx;Uugp*Jy5Ap+i=3%`Anuz_QBnZbzzYWFp^J%$ydt-2<3|}O9q5)uia2a!xM?X zphT9TppMlLq;)v$Nfb0CI?=aJYVRT0>5Q3femiX-U|UQ7_M0WpwkRcy`XS@J8?E~e z5}{p>0(Ah;2!^d&Zxrs$hpN?sP2gf5LQBAgIi|)sK>0lBoxNzy@=O)?-DE*Hu&=H; z-hB0%ZF>i=&t6WR^_G3rB^0++ylKAwxm)EYzN0pWu|h042m9WFrh#1p9Q`iHGoDTc zVM_>-qAbZlDTg(F@hDfwM1D5;+WZk)1SbJqime?s2*CK#oeO*)MrNt__&dzjo#{F& zy<PzpY6OixpR2=iA{E=A4ZbWP4Z5#fd5Vc{6bpV>&5a)hasFj7+)G$s*2fUq`mO|~ zhevoVVCCzNK)Z;cJs;P0oz6zWt22-ofq7gq?nDJu4^|+}3(>@`aGE(tDFNSHVFFD9 zhSM{c?;vg7CNBE1y40CmtHYg`##MWcy`bZ|Qii|Kpv$J8{&c`rNvpR&0sEy6m5a12 zv_y)E(ioYPst!zrzq5iig?3>TO9)T?OW74r%t~e}kN1aQ-arTPAYhDWNaX^jZ-Oqb zXs1mEBAYl12SNrsKR6(RBMN91$T(m)ovWxI5#Gw^7EfD=)7&<u316qm&)EF8rZ#T{ z!^#gjT7}gj6t5j^*CrUpcyf>j)@lo_WO#mNdKZD{nq*SqadOv;4!zFgC)b3q1ea2S zM7%$1D%>{&&4F(VA!N}D)|3IzdG>vwh*)fJcm-INKV7}T#IG7lK3X$zfu^L@H8_U@ z;kqm+)bW~$-doFH&^Sopz|2BBBGDB`Du2P72t_5oB!^^cL)9Yn99-whtFT0{AGw0T zJgW^T1k(`(tiqCVp&_&oAvH8}E0k~SRgr>hU54RS!UDcBnF*a#CNz|Kt%)!m@F71% zuk9_JTlwqJ`2YH66DBz_`GmXtNsz5sY5#c#N~eHgEmKLw4E|!zp$$#GL=IzuYK%TV zJYV>O>uY_4d)KMmWlD}mCCuB?P{c=xY|WFDY6pZ2y9cl9(oha05QQIe^nUgB0!xFm z6?@%Pb47k@Sz#JstQ%ON<_1dBV7aHbW@$!(HlC(D(|+n@Tpr*dOefV;3Dp`#dK>IC zI5z$MKA9pbs*<E^+2yPV)uY6o47By99#)tm28Xz$Y9279sh4KJoR**Zt&t`dt&mE4 zta$2`tZgVbWroGJ2@Dh1EW5yBY4h%cN~^;=6EAHrT2Gp_(3f_^PHLgD;_C<oH<+-h zJ#VW&i37DPj_}F|ZXt(s&8>0+0fvv#8%KaPLw0-NPr+W-{&>m)E@!eBPUl$ehz7KA z92{==%n9mr%LNnT`YuE<q-GEAYS0s*<2wpDD$ScQRq#`Y<w!klZNE^ce4xz4PS5<A zMe^nb6ohIDp|TlK3Bs5n06h|&!#J|Np0R!GC*cJLf({kXIHA7~8I_iVgFO)nqaP{d z;@ZDHu72l!Y{Ljz;(lkBvysOgvJ6@~ir%ceA6N2+#C$*)Hw>y}%nUQMU$(S@YX;We zz9gE*>$YOrN7#E$B0MZUi;jxh`68G)hTXSxQ)(v}&HObJzoTsY3_hSm?wkx}GVpfW zdYSb2hi?8Syp|5>U-!rJ-ftTgXi*)c83j11%8~O*`NgYfC6cdALy{cR<P`pC4S(z( zo_W%UsWVpu+5Z(Ja|*nSe_XiO3S7X(DMXa4RiX3i9X!ZUKt7hff2)E+h~+pdXqW$D z1&+@w{W)<~o-DLb_pPQSVW?vS^o;+3=MpOp1g042fk8k^kA=~PLF&C&M-9;SpwUhr z=aveUAE+6N(<o6LL$N`pSLIF2<B83xiZ=qiu}AG59#Rzl0kP!ASd&E5L|f#ZWApdo zuMjT6FjtXClS8JHLZmQ-sp8i7@?W^48x2kbRKR@kg4+c#P=g08<oXXup1~oB&I2B+ z>wD-T%C*Y;g`d13^=K8L*)iEz(xssJ(6CE7LC-N;4Cf%nZuc1X>tT{!1l)@>oD5gb zh!f<X!{iR>X+;pZ&A2X&Gy|V+SRjXk8rI1TJvz>KkOX<STr#Kd-$efl{yUGNMM@D$ zn3u%JPT4|o4E(Psc-k{b;cdOjGG)bBm}Xf0PXXO&u%^E<=5Myp9=j3LIzJdja{-h- zlBKIp98%Aa?F_^KOn=iFvvcuRw3y|bWhk!5BGX{%_;lK87OT}faQbQrDw-OBF2)jw z?EgBQ{tJX*Cm%K{!YQB0F8+o@&kwWkb57w$#U#5NxYM-OmFxFMW729jTq9K`A5IJ? z{M_R|31j{!dL|`75>0C3ajnkLUzulG(!l*M?IWSZ6>I%Dt1tp**bE}%6#LOsFmowL zgPEmfZKK>uJ`LC*t7$aU%%vRC><{2t+qAx!&Wp@_6rfq<$MUnB=AjC}K(_15*oKFt z+3}k`a}__7c%^bC!>jeefni9&3+>f-YbqjUDlp=Q3+{yz?bW{p`F#HJgWrvMCqGn4 zEUj#VH>&Jb%_X9-X3nbdd&g3s`2^EvR*Vuk;PB{1=urQ<pL@cr4Y*`sYNW_<f=92t z%F<k6nL&{^q8GQAM#VCS{sJK&&w^_kc-W0HQ<n7=-%YG|C(`=0elT0cEuJVV>UPSq zz8shC|COVJ`o;|+qJm4=6pezHjA)8nXu!O{RaVuA5-^WtG7_!eWyfji_`LqyPO{E+ z=gGP)#3ux|F+~`q7^Xp=t$P5Em2yx}pcUp-7g0r0toljC?ufk3^W<t~p02VMo~n7a z2l%6moRV2dssG_wqzyDR{TOl$!dG#1<Ud>A=mA%s63ZF``HiaSeZ!LSPN-;r9_bO< zSM0ULS?D(~vq^YZg8+(^{hTRjX(d9RzuNz+8|VI*0}ATy?2V1T0;kZ$*Nz%d7AhVZ z{dS_t`Pcu3nDCn!-!M7s6^Kf1Gn7ug8@KSLl9ykiy<*~+4duZq>AmRIj<ujQ?B8zL zjM2ODy)V=(d#5b~+x}S&yPYZTjC(K!3HSL3{c+pF=23i&eww6|3wh0l(2XG(wQBV9 zuk6_`M$z=(`0mwF1t1d_^=D4&i>BBU=I}(MBAO0-M6h^7+#uFB+vOV2sxgkE6+A&r z5)8qBRmfxq*f`+uT{p^VMK@2kjjfC>N-P?i7d8}<L?6n$2BJF=&Di%rk8+IA{eU^4 zch=aYHZ749@xq<e#3U66R!XX7(sJgmA*0MsxtGtl$fBPy03P4m^HxE5{nB8;qMrjB zXS_46@Bj{1lYVkMIm2y-YzCOvp8cl=QK!O_-U=qxp<#^&GP9qMO--^J3roI{8XP?1 z*T5_1PP}D14dN=RzN15?|Gb}(TtVKjj=YsBPdW#Oy5{`Iz(z#4XYR&nic1W<+>ID@ zEZddt{#v;g+o!ZGkwTf3p{^Z>9+|DURoip`iFPy)5;_?o0Uoxi^|Za6JH?1l!9BYq zhz^S|K{-i7r$78Y9@=pcKHEh}Rw2-q=r3`gNEnyBUQdb{-5~J8z@UlWmWTWyS!VYn z+*nnww93`3FKCoN<=~<}e1(z?MjB!}O#>kU{N;kFpS%6czjtCsEpJu8E_3T~{+dHq z)(uNGYLRb<3<^h%0}_^;@}%feRnwU?y>Nhe)AY=a4bFPqlz@%OqQ5OX{QH$3;s$6X z)EepS|D~osPacz=)x?!!?^Rhvqgt&~r|dT8ES8U9I2*_I%qJIs#Lz?hyiMt92f=T4 z!m#?Ij&P7B=F-)WIfd1dHpS9s^{PkNDkP^4h0Nw;*A!<_4gstI6cfMp+x!{ZONw)N z?yB_xo}E$nDfM9~1C9v4CUP7ZU|HB$E00Gnow*Ak-`KeU9+fZDHJ`O63CH{Ox0!~F z)-v;3%HkHbZ%I527?w&AL<rD_cv6yeZ=2eZx+dmXRfuTA!>$}yrOCIUu8c0TFcKB3 zMSt!Onk5s=6*!`K&ujX6-4XYm)gV%f_+sxD7{=;Qq)aQ#BTOGHNMmr!ce6;)xiPcv zr$?{Iq5Odqso%NXe);_YL3QYm@rlXEn80l*yW!;_hs+C)D#3m4uU;C=9;hwck^{@t z9YEH1xmaUE>AhcCx(LxsPOXj-)6`BkqmU^PJ2Q-5=wFDx;b9bQ+%Dmv?)86Q{$@8a zG9YimKaocXB!IREHTJ5Oh(mmf8imK9JN>w1UI<s-{!b0?mS1j+Lv72AsKuxlz!4s= zB&WLiBp~)rnVdU<bK)bZxWkDkB$W(lWK&fiv!O`iY3|IPnI?A*f;xyXJNt$QjGY~$ z7X}LRl~BZbo^ye)4Eqcg%2AGc@Vk6t7KoJDj+&4si)|YpyGKCM;4{#pgL_IC)%3lh zK><6STdX`WBd_$1@)>?ffAvbRHgb{c7co5_P6^b|QPp}2HM^h<d@^UoW3>6ha%ow! zU>tb3k|GQiR2S1C*4Cf3V8^@;^x)8HDvAX7*M7WlbW-#@MVffK>Vfjbp^q;$4BuLl z*wry;5Iv1NgTr(_jp#xs%>B3q`)jc59WtDk+@<G{m?l=D!9n3Wx@A?r<o<&tAo&y& z?sfj%fvS)b5NktyT*VxnEo^b{!{U|k963|Ph5@dZ^#%}v8UDW5%&*6&waX-w(WCg{ z=%#Dj9?^<d3sV!)3nJK%r@S?sbjS3)ZwB(+9Y;n^3(WIy-vp9)vM{Dw<PC9-ptyLv zjEn|jJ|~`J*EZ+x1;gnMaXttb8AfqCbWhw0h2XY-?wXj^*!)XIi++kLRa*1!^g&L` zXFn>YSZ9Z$1KWkVzkpkqBOr_Ek9=a&G%Z3Rj+bgljMueq8E__fJR*UF9$)f(?jtt; zP=!Y`wz%w8%tdR&k*>~{*1P#Wte`0Pc3!95xT5(T??#45Y~rBGYy}_JdtO;m`$Yo2 zi9bkRNDeWbM*-W@Sn<txyP9wi?GFQ42-Bo_;yy?D2uMoS#H{hr84e2j)&?y$-rhqH z??b5*^}^0HjkZ?sv;J-wTK+83GaC$6%yZ%-cDDHH#1kn9{2R?yeszRV0h4pws<7?^ zOyt!^siMy)R)Q&M&q?_5<s$c*7UDHosQNua5D!2=K#%W@jj0~mYBrL)!O=*y>pzI_ z0oxc6aBZBexBicVX6GCgItp!LxBW_=tNd!~7oshmGs02@5)Aun3Vx(^UF|#Fak~2G z{YRS&*whnAc#!kqTCO%laIK~N$HWKSkLtk5egv)ACR7V(v=bkTEc`2;=&P2a?7Dx8 zw&es{;WsxwjZVy%N2uwEPs&-u;$jn&Fp^tCGA6b2RA*d6ulFE}g@9?x5OmBe(yzZt zBLBlMFeT5&^=glI<NnpVFuw#Kdkf)CS?BzDs&Fx&`O~8sOjA-XTY{pt4bnG4f~83W zxUZZN-8~#6z&vDw(33X&X8DqKQ0h=>k#<um0lD@NK%`j)?>C&_Wob;Bv5U4STceEG zV>sa2KWhe$kfdjPY*F%ix={#XQ)cB|<6?<;Wgu2G8V-eFkmn#SufU3aNS_eDg8uH~ zb&Dt?vYYuw>?eOIVPtcIgd~AeaGJ@iCgVk_6qeh%LI|1j@J)C$5+zlG>dTxoc*n`L zeUIpwuqcy_A7aaTK8w~Hyt5KVmVvSZ=l>x+5N-2Ya$tAekpzhML$k5a2scR4%_p6d zK0~u*ztdW?k10K}YIzbmHFnc~xLHwYk+27JD)K+fubX`fC5Fj6Gl@_)H(eecwmm;8 z_O_>$z!`%}*ywdS3WVQn+?dsL12(xyZqDKBJljk@gOG;<sbQABSVH<%W4v=5`B<O6 z(M)LIaq}Y{qC)H2kl-gPVK<}x__J-EiG)t2BjqpQ01z0m0lEGt<!^f^Ko>G*FT~Er z_C{mUA*n@uNYDBjb^--Br5sWbnnH^_Z&m8q8dZ@!jLF?SF8GbL8`-9cv0gFi7S#_0 zDn5%vS4sVB-yC<9x;Hc!(wzDD3tB5gtjOChGH$sCPw%D#bBM9FtdMFk42+jaW-CK? z7^_uIXCC)6UNaYiHZk}zW4@M8?b|N6JlRWjYsj8Uyp;l4F9c~mvRl`-Dl;GccB4Q! z_SHk42AMY(=K8S2WN9m=y~lR$ko28^blNBj#Y&sPwN{;&Aq)8CScp@zN!`~VJ`LzJ zaL%x$ANa?GP120CGoq;*I+9}cVKN3zhWC4C>&T%-1*H!8W?lhQ(`@*%Zmf8QN5doL z+-<zPn_$Uh6+BcR<TFCp4br$R8H!d2c)+~D&BJ*ubntD^n)ua<Py<aDQ*i)56r($) zjkB|qn#*BxygPhKh45cRiPN&xaq+J(^?V_OIz+VQB;ThB9Jdv>mvm!4=jic@(FWw) zWfdl2N_HfZmQA`2J5F8>pqQUs5Otu&Gd8KlG`M95!uONHgv2=epy9l@lBF$PZg7O2 zokqsIFOua<rY>l`g-@r!q>*#CrNyx;Sg7>l5EvHNV)htoQ3GChxbb+2l6DZC|Ih<N zY&()>oSL<=weH+Pj$Fnj9$=<KLN3xL7LjRJY#y6)Yxq9&By+4f0WcE1Wy@AkUyK3- zp?8zI))QF44ZC0aHLjw4HPit(cqJG;&ldO}))$KWtDeFamps=&M2UH&@*`&;OaUuA zU$94P8?PZvj<hzLZmSh_`A6BpCkriDeh&_PeTZXb&WO(Po{#Zk$|P9KbE@1?=)Tcx znTG*CH#k8kd}*3$k7J+Q%c}ps5CRRX5r(Q&UK-}BkOFlvuWg8_rh`RY2QwsaWTl;8 z%5I7#DptbUMwYh6+|Ybw8<{rUi2UwIC6XxoELO_r`d)lJ#!eJZm1#^cclyUvv~GHl z>jqoXW&pR^q<@?VsU-er44mQE_cfY-IA=P>PWsv6)4K-T>DMvIFSo7#{$YV#b9w=9 z+#CCoP53DM!)o#N>U5v8*l@^_kF-+0Rfi!31G=HTLW4l-6~kL%4%0~Ono|kVa40`- zM~H?UB8Nu_oPZyvqTqGf^L#Zb=bxbJulQ0ARa@xR76BtPC~n=88xZe$eLKc%0R;{R z^RT;Y^1ERv@DBsaGzUTqSOj?`E$&nbmvP2@;wUqa;Wr@ELl`?3Sk)^9;U*EBne)<N z!w$s;WFTPrJ$$BR;|SocM^Zt=XK&p<p-b-Ic&pnfWK%+#lSivIL0%}(Oak2N!^d29 zefd@}eoWS>S;E`IR1{JAoOH@Vkw)~8mxSN$B<q;bYA*=jIqz|+L;nPknhX!v1|o>H zoxgc6n{$ye0J7P@6<X8b`qRB8WHqq8ytvL+gupM*Z8Y4S;&hrcj3B<Y&>Pgs{kB{! z>U%_mG?%26Di*3&KxloWc83%_J|+0Y_aFiu7A`{NgZqRBPHt}kAJIHfi7+3pkf!k$ zO*|m$uh1X3R<r_^IV3G-uTIb<7u|EVo%!g9A;}dR2}0aFBg@A!$-o1Mpa6z15}I~+ zK0AC<?e{_7Mkbjd-qwX_qVM6)v<Ed?N4KjtgF_LnJI2*pW_s({l(`3rY~pxS+1#&c zBYvF@1F6#4&b~_=+_U}2EyI9vPX-8CriSkXA5H%X&>&|zaPh^mPy_he)fgR>XW4a) zDpEs1Q~Tq4Ov+`CeZ3zE<_nz>5otj>zLuWI&8^ryXl!5%vqTA?X8(1p2fhTCf1Gwb zbzDW5=bmlETYZ<`H&w10hZ%!IKlc^eU<6i>KnYc~;EBCL2eU8;O@nCjzLG9~Yv164 zW1v85x{l<34;aSzJ9{SsCYb=hP0Bq>?7UcOaym0s1eR^4C$8Du+dD9uc=98Kx&68q zQ&Z1KRv0f-7-wJ!U_e^coK)6)9;Pvn-<?q?qy|tmnO<{@f(H>Ff^~a^1b;T0oeI=X z*fPj&sEBnImQw!Pzv{_gp^vw<)YQ}e;9`)f<5z$z-L^VQi<y4|j7(3_N?w(7RA`N7 zS>mXMp^H77Q+o6EX^S(Bt3&kNS12#1e;Nn%-2TY5#{6$2Yw+^UG9kUwar214?6elE z+Ac@Gu{goIH-69wW?|rTsgJpKo<+7}#-4*Y$!P#CLE<q?#x=d3#&oor%}M&(err>G znp_L*400Jaj=DO=p!03nS7W21U`8I3@WGAU4z#^GP0EM`{S=R?Fr;JvI9<QQs|*g| z==;oX-+PeEg$N`^aWFLZ>nnhkE!Td%?y>6r&aCzObqwN6(eD*~8ee~Px!mc8ADC^c z9Dhe&E75!xPBQsjr-*mg{j6+zdFI?hg}3L*k-!tr+k$Fr-BDF%awuec<o3lF7#O66 zw3x73b5E{Ejsf$!D$u|D8>r_FZgS`8>zw)LlD-F243;G<-%2FoZQ|vL=8_GvG8hDh zKt>PM5;W8FY@pI@w>8?g%<o4c(!Xg?pnBnpuWZX5K`IT{ZHufXxsS1cgG`sn+N`<* z0;d>zgA`KDyAZ3FBpP4^7gX=hz#qn`ukd021y_wRcb(7t`3Y*Sx$64*oL$zG-debf z<+Sk&2jGkbaGQ*SvdX3wmq(1&;CPW<Yp<xHmnzs#g&nd1X=e)_t*K{`xCRzJgykCn zAYOiiGDXRcmHSss+V*2V*FN3lqNPd%XF>O|mY{W2lJmN14b^GS53dWiRjXo3;&}4n zrSpwb;d04<9=L6;*+d}?)|zOJ3BW(WFv1~7$lU_Jh=ntM>z`({{?c(39MGGSy$@-x zNd?~`7F?$IQ;?&CG*7h6$SO4-p~@QayV+=1P9boF$5@r3xpay6KcDvi1(%>AnbzdI zIr_1D)K$gM5#Xs-vD-!EUn(Qwm<pkQEG}|%u7Su^jNVM>ApWn_Mj;>rlUjueu|2w+ zoqQ7{q+4g(A7!Brs);Q+)lfFHqd_6=hSlVwbLV#C1o@0wsU}MnMN{H){r!>AR8|Zc zT+sTKgtPvk^zK8JtZ|>*)IPwtn2jLVmoEAD!E!)Gkr667tsNirE!LwwXfFwco{RI} zbqW=!;6~)ciDk;kS?Ndeui70Y5|a<AU&8azsYdxT6c$jfmgs$j4zqovlL&q%j!-NW z4x8<15on_^9PER($wxJZ#?u`^0;uJpCqT3z0+(@+wkn>mN=okqS9zhi%wyyG9Wz2g zT#uI0p;CGffM58#J0ZDj0<Bqc1}-0hJt0fyxztw##CSHuiUyeEBG=+N8vEQF#0!c_ za>c+H1Iyh=K4>F6M!(fR{k1-!zmY{m46A+0UYrS-#_6O8c<C2O@M!!F@f&Su;%|Kj zKGX*7)dZnm2PtqHR@3naU?&DQ2huuNB#b(xi1*BVb;qLD%TzH#UDN(cj{I|tH?f-e zx$xkb)`mJeFud4QcY0EQ;V*4&!DH7Rj*ZLA#y!SiE!Qg`6(bp=QSC}h%K|#-v!e(_ zxv(wa+I0T|wNLm`C_Uc7_Z}yU&}!(ia5zPn6Nb1`WNpVP6DfiSD>W!10cRk&T1*xX z$^>p5+YgH0;9AY86zvvj;SWALzg{Di48vWzaac_=v{yilK-^DVS3XyL1wmF8;mBqt z^?Imun&cqeES0t{@~++wL$xhNtj1)1l_{NgfDtcZK4M=f4wx*p^09t=whwI$<+_-` zrknUC`*(ZCalIGN*#e)@II=|6Up-t`7MCxioJ*sGK?9V_@7{)VBo~t);!L)MEEW6z zk1HslLTUWdatXy85CmFmC9)d|efi7(_Zt{c(6Rxfli)6nBt97v+O36GhF@S0JK_PL e-!$x?xfZ-A3P%~S%cKSay`;qz#HvIL1OEpXB~kVO literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231108234643.png b/docs/images/Pasted image 20231108234643.png new file mode 100644 index 0000000000000000000000000000000000000000..95f8f2b89f554536748cc15b4b992d51a0858d9a GIT binary patch literal 64444 zcmZU41z26ZvM5km+@TbAcX!>mySuv=w*rNYySuwn+}(=1OL2FHxBH)S&pq$G^?ljN znq(%)WL7ennH{PiCyoG%4GRVah9D^+q67v8fe!`-P7nPB1nE)4@dN{d7qSEZ6eIxv zLIo##GfNv&FffVGM0F?)<&m#h+Ho;4QxMP+FdZ<&Z2k$zT3|<_H7Idlx&7ausa;JJ zdw%5@f#bAN=PiNPlDK{y*uWG~N%&rCpuSPyU-dHju>Z0@;rGFHlg)B4(cugQb{DTx z%Lz3PMyQ^^5Q+d}5FsmP7?TA7%lO4)3%o=}FDnHD4-eb`%jQFGV;vG$(XmfB`)vN< zN0;U;gpUM9ioL_?i_d_$69~4Y%3DiH0G1cQk)6hnWT^3@5%LT4l`z(X!WK1_obpzO zQ~IL@dp{jmi9(Bx<QFh2b;3!?EmJ{+U;MyK5${}Ru<u{`J6l@fpOA}%Z9dudBahvt zS_&MRyvnlJO2m)-{?;4TG8`_I!ziE8m-+5jwCk6=hI^EQM59rf8aJh}oME_OXD*MJ zY)IYTk=HOx3H(L)PWWf+j7W?sb!H0kC!f{um~meQxGpgBajn|{h(Lt+bx%Z$@~Oea zkP*tLS$N8_*ISOa-xHYu{m<tCDqD6*@*!%U+`A)GcIlDq1F1j0rk(gw^=KMWZ;PoA zQAz~LG~*HS0Vxo*qCXg!P>tAtcsF&sy@~Aka4gHQf$XT36|}x^K;zGOF<?LW)ne#j zqEuIs_xBMdFjo_({)kXty}yn>Dv0{le8pGC7s!Bf6(uwxgFlA89u$M0_{jhbuQZP5 zMUG6?PxYN2c=O2!!`Ly5lS0cfIvvJI*rXk+zslpY<7lnB5x-6htPihl1_53*5RGAc zCs>qbrziObboZAZ{@?{QML$Le;h<MNaXhy(^C-SK{D3q819wnh4kU^D!$<5M`RV7D zJP?x5-a^N}T^$UT@Z&pBRR>S7wY^D@pBRVt2PbAwAg((@Vl*m(hcsj~5y@+a8+`@u zH+#g2x_7@xq`FP4uO`F^5iV0C0H3M2ZzAxd!Ki_ujm_Za;a<Bam&ZuuEED~FPzP7* zS(iama_%C{LWhKFsid@VujqT<roit46I&!+m@u0$=3M$dIS`Z}COYb_fpKnCO(DTO z1ZJ%hj;RgOjlu3xoOS))3MtNQAmNEsyk@KuSl&N~wQ{wx15nrLe54SFR#*a_%#iM0 zPqW_u_fItlAIqrPK)mh=!{QpaCB+JG#u_vYl7%q5`0d>JJB`lPFC7D;yCcEey?&24 z-gR{{`&{$fcbq<ow|j6!Bc0R!e44zv#N)%`<~3VUga!^GyhAAP<`m|bU?wl&J2!Xa zVx9Jct(BWCPkvxq&PE0XTf=Vjr;uPTyjv%Jk38mmLE0hIU<XJy1#u9cL&oSK9}^Wq z?9=$yy2gJXWJI$#Ky7prK>lDv{=6f^oC2Lc8FZopQ52ABfKLf-YJjEjdErN-0o)R} zYv5ZBIPT}-ZcPUm9dM3rzGlzX9=Iu}jUSWH0Wrwf!s53mX#J?Q;u$F9JK>N-C=#@B z5e39pK<HRvme?l=ETyOl06PiWF#jJ$C)gJM1`@XzxdJGUNN-`LgfOdou@Ve!RMR|K zR@_K&iX5y%^af-)vE&@<DJvIDt>`RahFp#*#M{p+(cm%|vjZ|rP!XZEwUo4<rH4qD zY%0*pyUS|1D`5B!tTmt(!hQNfIq}T55FI{;?7(m$Wd}?SV(y+?;<@u}1nBqiT=Bo+ z{19U#T|#Sz#_iP*{$fa-8>Aq#B*rPi`DwGzu9t^6wnVyt+_T$_DK$kjLr6zPM}7^! zD``XFit-{!8pl79^#>3}>?rwEfI6c!Lq7vEqpHMl6c|<(78+JBRU;J^CQ&F+C~R6h z>X=wgEw9QS&o-Q7!r+9SDxW2%C$%AEN32io7B8U8O0|GaAjL}-&KzAAtR&6_Xp#5G zFDtVuIxfY|r&h@<Zx#Dqee5wWHy^D+SB94;izlC`l&sLCEU$E-usLPHN|Po)_cKXe zTev(ovxu+2M<KtQtITok(aL#_dj5F6s;onWqFlSIevYCHvrN5&K%uK*qg-gAX2!tU zfz8ZX#R_+!xp2B#auK%>t1z{^MZ>vx|MPEiEmAs~N<z9$wc3TRm9tv9E)jNe=CdBR zPq&q~EVp*Hd5yo=#d)OLWW1VO(_OQplA_Ax@+Md_r814V@mf==66wV`#NA5Ieb>`l zvxBh^j1kb_wOK3dmgWsF?t)LAPGD}O?(PrQr(Oysr;uhQ7xb$(b3VGkIBHmcOet11 zJzEh%7Y=9J8+{&q(jgZFzKh6g4J;9C8HUXRHS;x_!%LL?5;hGBhYgC=wN<rUj!9Qi zySsyY<SuCXXt^U&@o40eSlsYmNkVFar+W`s*jN$R64UJ1ZCT!I%xsek)Jz(OPJeI> zWLRd|b<VUew@>!=8$}GrglmPjC7DPUnHKF?jX5V>R8~~RReaT8)8MOLsNdJX)LPWq zY|34JT$ZUVZEUfVZZKUjTdiv9FbY{|SvFl!UD0h6KU+Whd4F=YDvm7X9)%oPg6}x? z<G9<2(xK%0q08L&2nSjx8wYQ$86%U?;XRVc$k+Wp`w6=Z^G6$$m5PS>VPb5No@X`( z<IYtso#(>NFs`Y)Gl$os^BbyLtvz>*IP10%s}N0QP1Wc4=co_d5BNxM(JIl@(b_V$ zW~|OkH|-QXEZxpg2a1!?dgppidM_RC*RGcn_ZvrVHVt<cJ%^R~ZQkSF&HU*;+}>E7 zrJd>CJg+iu&A#)#(XYSXp59kqv+Ha$H7j&0lELM`<NN{O7t4C5ny2wUGz=sREDf|{ z)D(oLT602r%zChTe)aee*%7e_%LStf_W_baHg>)_x@Ta^>8FS<Rn#OoSh?#wwqA;( zxT3@Xi<k~mYM5vS*P<ID&_&rreo)HIg_S@}FH9@vMfW2c=NVHQXZ1&gWny{JN8xi& z*_p4kJ^DWuUOk}NpccUV4m}RtMYBfTr1(spNbx-akIQvoNqXeVNbjFPbR{XH(Z+;# zN1<J{$P@ev_D+-6-!KbkMY7F|(*{Np{l@Wg6pj>l5@ZGBh37JFy^%X=&M&i^ma3LM zyzKUD7oRt?yW%!UE>RNTvWi{`l8Xh#E=M$Cr{j;3HDi})OyCw_^i6-7*^YZ=<0W?R zc@a`jnafv6*;$<%#wJl}&oM8%UpI`L8F@K|HXDa6Ca5YulWxb^dPr;pwGVpRK9X!w z|B8JlKBK*)E1`X4WOF?JVVO27GOJa*Dyz@>W@+fKZO?Lv)sFR>Mb>;GeVHqq&HBd1 z#C7F#pKISa?7(FbA+^mI-&F6ueKR~GY&3jhLOyL%#YTm<sre*1M&C+$PKuPQ>8m@# zQZuqXrOs00u<7)Q=%&<DA?8@dDD`M3?LJ-S<4KAB;wyIzsgLBU(nBFm5=wGt(z?!h zlec(_nTMgrVi*(6u{yI_Qk8d`)l3;2MimB*y0V(Ix?4r4#%%L~(OKOu{RPviHbpFj zmg3PGE5-SjyVpB)jz{~FRf~pNo84mBUfCv&5Syy%#<Hp<;Wee2y^)3f$^&2HceVQ8 z2HMMw)vKbbJg)uc7Nu7urOTGh&X#mqG?iz|Y`%+$>p$9XPH>OeFQ(U(8!=B4&wV-> zzHk11+kQz$Vnmw5Yv9%R4)iT)z%R|#+gyxUo|;ZsTk_>Rb#RV%o6RMO5^p46<J0nx zIar$6P1qe6f|5heIuxMdU-qKjRZ+hw*!L<P%Ie%eot<$de;t3S?=hFpHqPX6+&Flh zhSS4D)Hl(yY5wC|+Bsi&H+5mxMPTJ@U*2`<*m4zikXUp-eKu76tjqVE?s8@MB;zF6 zPGrNPE7jrVzVfPx+wR6*pe^3{V17NIE&JkkhkUdCv*51K0H7~q-f!u>wz#ijSHs-E z{3O3w{GrudmjVBP?|nx1HR!%zr*vdC&3s}q>K^hz$Akae;{om}e6oYg&+1+CZf1Y4 zr|b2@>I`Rf@lER5YU^%?<JrEk>$}hD8o~O<rS5s#<b|}rq2JO~?9<g+ae=(Nfc%^A zbKQRV*<z9X_U1X#A4GUy3u@J?I#?ivtUT1#ohz8d2-wv2Qv|b|<9j@&h@)8|$z^uU zP6Q>xIoMp!$3u$Vqnk6Fe~0$=72I)oG!$Xl7r}N4L0z5T<1I~D->L)*VqPelu;;X- z^e^wSiWyvfz?Xxs!z#KxlV@FEK!0x^TE@Y4(48X8R728CRu+sJRE7qF1jh#Z3@U+x z5<fW3f68LulwhC!fkS|Sg;;_?{=1DFDF6G!fYM)_f90Rzg2A9bZ>XT;o&)hets(Gp zKK)M_oE}sMCZr6Ilmz9<#!jZDcFq>|E^uTue=%VkBs87Dz`m0GP2iGBq?aK23zjMx zE*i2j+{X5{^oAz(MyB-cwhn*kfbqI>gNnAME{25ewl;Ro-0pnD|Fqx+mH&bnhzb8` z;$qE5tRbsF2(WiDC1j^(q-P}Nhb1H=<aIJJ<5m(8`!_o1jgQ#E#l?Y}fx*qqjoyug z-rmWafr*QYi-D1ufti^O)Pm00!_LLfozBjg<X=SohmMG;v$2z<gNvoT9pPWPhDP?^ zUHFKJ|914B=U?MAb+`QAp6s0eJuT1#8UEHVFwrwI{D(FOmG>`{Tfx%Z)J9Xp(iX%s zP#^p(jLf|MwEzEV{<p{f!qoU*Og7g43-iBf{$EU0XHzGDy)CFq7ykcUu77v?-<AJH z<Yo9f^Z(++zu5c_6vStKSYC$ztQkLS)SfK?Xc=)WMdVdLIY`L<d6GfDl%VuC2c?8A zHscBbFfc(dNf99xckokPD1UU(6(5%RdXEuF<^W)d0#j}Z3#HgN_zl+ic-Xrc3e!pI z6xu+>9lC;u5Q>a>KcpF?=ylP^kzci^HC8gA<FW!m2j6V%^LP3A@`s<-rkp*ph~Odq zfNr8KWCv(YNGovgY!dum{&j6Z|AFB`d;u5dT?_wL3tR{gf?y@l7EruW=#2i)KWP5| z{Ymi8@%|F|*Bc;b0okEHe<8;e)9HVK-6%*8i2rHQO{8EA&AFp!t<VO?^*?x^u>eE7 zp#Dwe@5oBnAaSos*h<!a{uj`pzpvxde+_;P8zRbm4twrg_`iUhJKG!o*ZdGbQ?Wv@ zawGb$N#kBQT>K9UDpVm^4_hV=UdFi2xZB1znk&AqWOeYrIN#TvJHG+CQKFw8#&tsR z{^3HVn1Lp#;q&d$@W=?0Ga)i#zsQTFT%nRg@$7!qEnliko_e*OS$fBGn#f?4+t_mm zh(&i7sV%5Hf9Lw+F3cbJ1G*Pe-}}eTjuB*_5P-4)y>x2k;z2#RmfUi9gS<D_*;M|% zZ9PeX6rKr1Xu9Ge&FkUZHfsK<zB+eT1u>Jt%jceL?cnY&<r5??H`9NnrBIBb@Tt>b zTUbR+jTjv^SF_%19un}Uhy6TB!i3|xak^>j6z8{Iv9U|$p6rTxeA0b=)U>&@zlgAi zMDKPDm31^eUrc&>`0J~;IBycvsi)2baL5yKQ+MSbF{!YJob%T<6+&nNijkt0l4B8L zris$eZE45F>e@*|*CjvO9Gv=`nYUHHb><b4vASwHZ=RkkdDT*fLdQc(tTx&rU`^L@ zPhL-`-mIO!tcZiS`YXDWC;uOjE188Zaa8N8_~Nxco=Qne%Nkh+9sJ5DLSF|HY+EpU zjVZf#DUXg7hMt;$L<KY$*6B5l5uuKUOoflLe6o9tLEAESmVtkl0fX`T!d0r%Kl@7W z3_m$yMA-f248a8~K!vv8qp06{Ht;u>D~uhhD|9MpxO5IadF78I(#<{~<RebqVtOrh zazeV1H?1YdrXsy^UqhxTC0-5#*3>*$(x1Oquz=)I!+fe0?OzMo`cshhYoENpn+Z@% zNazO<7BMz4uIs3scV%2o;jk2Ura`!zu#i)%T<wp819)u@EGcHos++x?{A%B!$u7FV z$15~Rei2&c0!Ww$Twhe90vL1ME7WLALqZ-xwy8e{4^Y7b7Qm^a<PP$$!b$*$zB3Qf zZ^YaW>kh<DftIiK&)yBz^IvdWh5`N&Bof!#55<z$?sx=8A^KLq5->>db=&$*_DMQG zZ(xuGJslmJmBh>a8QvA4$uB0Z9Yq|<HtT=B$RAo_f{_&}k@lTWUx=}k*yj40V#(B| zYee$NM>K@lc?SeR*U^3@vd7C=g3Bf44^c`nwmx+*eeQse5WMi1>Td^nZxG%pbgwp- z$~H@HLIN03Qfth&f<Y`?&96mFBEk)TApfA?1B7SPZ@$yMqzqU(jzf^g<ZEI|+xZa0 zPRN8@t#@_nv6F9;E$^}gpM>z`X8>J@0CwbFyv6LGq9;XC?<X-Pm>3}BCuRf>6jrr? z={Kv!2O8l*YiOF(6cNER4tu*sZ5yknX|~5PuAS*Eg4#AA&?k|TOOi9l(iW@2;CsH- zLP<@{T+o-MU=kLCE%*sqN%i>ist<cz#8*igBawX=_Hkl5NwGK+*vkp?O~ZYLuHBMP z>_fMyC^~Kz+Pv7LxU7kfP7+_0pos$vG2snJE{2?|eFCD+v~!(@$SLX3g|_;yiO^X3 z1IXASTSqG-O;J%|g$;+nRN;K{m59jtCa>M!$+&#e4BQJj$mNGFZj2s{eaUuc&C{UF zygiz4u6<(rnDrUGX%jKI6N~bf8Yc%ipN4%S>OzUKA^R_kZ)Ibope7SAhj)D~^#Z|a zkV^|j4}ac^<ty%%to*W8XSJLW`ONxgW^AL@Dp39tv@?`{PUji^=hK}-fVBC<Z$5#G z=8+eyBmz*x(=y{ox*lNMM`2sCc`TGDuq56N*hku*$tg8C9_ljsV_Z#yVgb=&U6M*a z8oIL|j#$vs7foaDiK1;cgSTosDb_*=O-fzDP1(=3pUFbs70o#hZ5O6YV%TRlk5<mS zbRj&IG)Yfa_G~w%U#X@5ex-;plKVs!(%(ZcPE<N96aZPu$j~2;vAg26K}?l*ECfN) zg;oa>N4>RS7(yt3R;(LRCht$4fjg6)fgTDaE9XSMedq0qO1052O3{UUf<*kez<4OC z(Za4J7<81>27|Ts{cCr&CCLd^jQ3_Qu=%sMm%4^!Rl-)D+ZYcWY<qdPd}B*UWMGUd zNy>$}UD;G*(3Qy{+#&$<(|yxtKPM%%@%Op?eYnyH4Rzkcr}Zbq-6l;g_cnUVG4&hH zz6tu33N8$nmlB<%b86CZKmmy;K_n~Avx^hV)i8ZHUHqt}WJuC-Hr;m31A0QMA#@-? ziwf7D2&)W3XO~T`;XPMBL<DBm0m!hlottXk!Gh8*LQxqpon{<a?x$w={u42>qm@pq z2`*DGEsU!)))7dJ1wqE-C69?;)FGo5(Abi|JY$ziyY*JA2vu^9N_^14SAlPLPWi9R zzZ|**Ma8%z_%dFep9wMcdbLKft!_k2N|AgHk5cU$np7O#8|xe8+;((~$~eP=;nMH? z+MI;@$TdQ@{OJClP^l6zJoxSyAp~_H2Mj21ULwSDy+Q%81q4A7;t|JU#6rD27opAQ zXk`?v>$F68j%8GO>`JK)v?Ddr>wyWFJXek5CXykYhxKImu2?xUC@~{J&V&@n4-=HQ z6FnJ(=G44l?nGR}BtM2RLJ7HsfBzP@<6pd5a>;?_h|Z8=D~`d;`Py6eB+1R)1iv%t z`~YA~j%p;vC1v#Bjb;!}@q+9VxpeR=B}@|)G#Pc8EhE_i4wV`2NBv9n_!Z`F@}ckd zHh<fy-DqR^%0Bnf7+DW%>~&x@=R*oUQjkp!9T%XHu>YALZyH`w9M&AsCzv!y4?B!A zHxETd-RNVzX~2vxAed7{>@ZxY$Ow-fp#`~TtKy5B=B90PnJUz&8=dVk?U6<uD?Nr; z8?n-<uhwyALw1J%UA;g!aLJ~0K~qh-P0ozGR8VV0lN>7+y{ilPGbudFhm6s9`m93g z6u%>P^?Br)3K9LsgNBat5sZcIIJ4q9%nSphOU&K038}A%V<V)<qM}9B=s{89U#%mt zZ{%$6Un&{`_$p^P)5~Fg^i-KDO+rFK%HUiYp31kjY}-rGueV%+@sgGvR6Flqn_c?> zDJ&cTJXQR2DQ5I7hVVFB=uzCw1X>)Xt5T{Y_y{DzO0mS-z*#wBKLlw;kdVZ!?vN5* zBS<PdNld4*SSBEF6=}sI&cmk$l#Qe70qC5=*Q+L1PPvkgZ{kK?^5}wXEG*X;+Qrr@ zNXUutpJ{0u8p43XAq%1KlmX%*BGS_QPJvIuG&z#w$#P8|DiS4O=wC5*CPf`x?Da+B zWzg0fCRL2XuAbs8;tu*eJ~)weSJ;Jq2-tZ`*<h)d8Pa)EQ&ZPm4dSE^6D1DF(ujdL zfw8;WScM2tCaHmCB3~x=-b(Iu^88{ms;bI)!SYdex_pwX-dfg|)Wl`|HhPizJ?3Qz zh@znKv)3TeRynuEO3*g2$TT?8JFF;-m5<YOUt$KHcs7_=ac2Y!-@}f%$d@^OABBD5 zo%dNs#Ier<D#m1-`03KQsD-o>NG%cIjIQVt9aKINOopfB$xo!$T$-mx+ajs_Tj9|< zjXF%6UxmE#W}MP0fi2wKVn!*lQJj-k6masZYM&G^9XG-we((EiGZLJX<Zr@22UA-> zA`o2=7*s$gknD`&1Scx|Iy^}yMA!xS+bI!;E*r7ImhpL6G9qQ9xR354`dC4z4E>|i zu*Q5Mmq9Ydmt4wee-HY~TO%m3#%8f9lPFAj^n!n01jME^VDm+Jr2k^OXVx`q`ivgv z)QZezW}q7*#m~}B6nd}tX~DsEeLRymF^W$3`<O_n5zKh==}REgS)X++u~zD*`Uk}y zTohPJnDn|p+vjtjTakAdg4UDcaP3F;*d)K9@M|5?$a}@;Gy~G32=?29z&GU${N!J$ z4~4LcODil(=39>61kO`c8H^XO)`x;4{jrZe!+kY)e|@r;&ihG(V?{YXydt*9`X}L2 zoYko^Yv|=VT!`^2-4jZrxCCx5=S`k^EEVl#uX21Mr;&la%aKBmy9IxqAs5h$w~nZ{ zM-#D3YtT50Y9K|U#9~;+Na71jq(oq6xQWDa%x(!VDj^zu%(fBBXuIRyQ)$|wA9o0( zO&?4&zh39Ud;QM&ezI@~IxXiLP0^5~)m-q|4)uMXOn;3M2|KPi4q;*R?UPOO-+zlm z;t8)gsviy|BM$bC84sNr5eFPhRa|K8Gbt6v^pjFl!^kTCjJWjpv}#`q6NNwZNq;hI zYeQT>bTvs4zUx{h_%MlNQhoR(j|BlnD(p#mM<qPLQ;#}PR>~|p`+P_?C=5w@zB(Nj z!aBm=BX$Y7OTZA<b;FO5-`$Uyp7TQgadRkpYI!VrVES7r(5CbBjPb-UadN>*M?LGw z(#0+|L}0fvChT1ZwtLi+ZK6P`L05?1EQDnEcLFg*6GA=t3`}Hc*iNX^id(XLM8eC~ z&dqzM*F`519mfV@eOLOZc07sJJd?|g*KQ;e=WRD&%60a~qsNN1>zGx-9NtU}vcfNG z91@@R*PBV%8EUqm<J{G(w)<(<-^6&t5LRobtR4j=YC(r%S34*AMyJ{=4p*99dEfO= z_20ktz*V<L&dRTS=CXO+o#vd6bjr7q*apUCP%0)3i^WCdDxyY<tdZa`;~Z+?k6faM zTR|8lAc(cb{OR8%<=a5YBF`arKiW%f&Z<IIGP~_@VYfO6g+cq>Yqja~z(xw#6lJe4 zA`vE%QRV+lOmtt5>+<)Tqo=hA$b(3;DgmN@4#&d#RL?JA#N_=)Bj_zN7I2-M8)(h% z91q|1&e=eP-m=Z6+H`e)S0Qp3lqr#%RqnIls>yRW_q!Z)DdotP?x0PSX-qxj{lj`B z(ZYd9(6NySIXu)a@c9R-N=+Q=QP42oOy|#r{6^MLpxTp}=60+b<Go%PtSXf11h1s3 zbC*<cc#yBCVz?|yIc;G_vT0&MMHU=Qly{P@C0LT1p6g?Yd%;vCnQh<Mv%&o>QcHbl zq$Yk+D02gK9z9*Eea>vwqp4OSah=qF3lE0^r0>&S@^Mx(Hib2RjY(e|7@I+wEFdjM zDt3H`3-A#crs90T(H)V~@-EtZS%4P_ivshr)UM_LuUaI)EWv^{iZN5hScy|Y%msfJ zSCV)q7E6A;Cj0De&c6tqTRJJWU{q0%Y|sDGm#y}j$z7g_2W`?!0dKY<&qdq7>K6@y z_yOs?=?W36Xx?k+EYD-AX!KegwYM7bZ_<Ld>oGBT<Q7UwGV_735|YTG9=|Q}VDg$v zQgT~aPo_BjykvX3+g>-7M37_6qz~fz@N5_KJ;$xZxKph)9lxvMms8r-^n4NfT)Vme z#s7UT4Rn`Jq?iU9CEB?<>{#4RxCyR>P*MYw;#BxAedatV2y~o0R9{kXrqD<KDRZkl zI4RUPTh`qWZK6S7J7dYc<^^tpiy1If+#>4}s&k&LxG+FVP8dK~AGHuz$3hlX_E}); zUB;`zjULY7tLXL<c^4;k8=en101~s_W=*Uf4vAUG712xLxFcoEQD3WNghqncU7tTS zOr^=`VZ$~puYGTj6raG+97AkR5osPbG|M(D)~bubH}hU!8@kD+AG(Aojomiw=rhf7 za)BS4SR+Nn*>!f#H*@S4(s^hU@YFNmS|{(T-^6Qg{l(s0k1ty<YPcocSmGB!?(R%5 zV#6g^jkPyPdXL45AV;8tun2G2Z!+E{B3vaz7hU?jv0NV$X7}f(;;C|V2IVh_ilah4 zsX>JUs-#jPe@^Qs*+1<bwIxK`+yO>`Kp?b)qhoEVC^R2gzcklHs>x$Z4P@z>TJv62 zGULwZk4weRt(RrR4i8-nLdwD0Wjl<4OQo=+mf=n>0UmHQ&L5ewndW1v`ZYS~doKOP zwt36LlZl3L{sMmQsF|L&(dX&+eH{8SKcXQ;CTy`1;-FY}51>hAVPoSY1C$D*5qzle zd!dwz3^w~Fx-%}wb3Ilk9vud0Z<lKj?Aq?k*1TtRp%dx5kCOEQSMA%SRDuNlaCW|V zVn5#t0N=6vu6Z5DQ`yk)+HB-!7@^kNz7JI_-!N|XMb~O?@@vWm|7sy09rS4NkXjs0 zc_&^tVp?&LMrOzk_kcSv3Pfmi#5Cnn*??SWjz?MXOCM$rB|qcdiQY74`hhap_dGy? z-yy-faR942>UeunkI|XQh7=p7)L=ClE5KtDt>5V#zq&S;f~>Gx^hK<GxX<gNBZOYJ zH6>U!G6Ooqj4dXua)!`co^1URyMopCnI$;g-Vd8YkJo=c5xuJ83Gen)F{s1s^oK|@ zM4}@#Zmtx7+e9psiBzosP$m{pFGD3p$5dbx>Y4YT`6u8rYg8$nc4O~Ybvtcx>=yx; z3jiV)<mh9WB&0||FMTC(oU9-%5mgRW5o7irlIWsZ2nH99m|4i=b-vW^VbPfd1I=EK z$f(HAn=!*BQ2FMy7Vk#!G$!e`O_rCBRfk{jt~5}%?N+IYy367kCt2B#r(jtQ5{V>x zua+_Ojq3H*TYmC!H;#Zaf5@Z>bOzj0=0o|?+m82SkirIj9=2YFiQmi&67st3``N?` zT+Z$SYG0%S9ZcAr5rR@0TfS{3{hTUHnb5g{WzD5yS6su|3-=|0k=Q-mMH(6|-T)NS z|Gs*Q-rRm`8ZwH0izY{jH9pa&P`w;gdz`M1HY!GA5UVr7?<%)O?dy``L3!Z6=O)`{ zMn$J)8sXw}A7*U7URwWyrO0Y(iZ*6H5a!FzNon@=>Jj)7teBx6Az%qdJwkcP*mEIj z(X{M)d*$v^>h$_c<y;#eDhQYi4=UM?>&+efEw>y57!4$Xc2bBay25*7v+KAZbGj9# z_Mp=Fey`^(nu?uihK>^X4NsUP7B)?Frz8UC9%B*X&`<306=OTc$}nH9z~S&!Nnt#$ z3tU$l;Y5~WJxG@QOq4CZOoz>nv9Sihp|n+ydgAS2GkQ8-Ts__7Hsh2wuEe}J#_adN z0NE>jHZphN*RQj<@$$K>NSp5s$kiP$a4k?LJW@@S=^{)!AHjsl6L;GV=y3ZC-5CN0 zTT8o9OkonAf}9KOMnIQ=fRVEXC1{n@Zx&76ZT20(d{Fo!eeGAMQu&FLxmf)}1)`}g zT(2#3C`Bq2)8wWS%k8Sl;}VSk_vz^2?Pzvc<pIT)^RSDt^zHgmsqGB0_*cR#_XBhI z<HbY_GweXO<H*I%P({_pfo3%sd=A()#P$^8L1AO|k*O1b;vC4rii~h~ezniiZ%Y&c zAIPpeW|T9bpGoodzg*6L==FW&!3UJK1ss5{eBIkoS3CXe5}}G8==T1?c#r=oUlgTw zO&0B*@ay=eChM;Vzk6SJ&TY@pje5%$(}R#GLcDZLlCJcdD~(dO67aKvFJ~v!UF@-_ z*e4{bmMTqD#Kg`98DkBKq$V5C(|&<g8_|+$cf%SY^OVfL-C|Nj<$0ZW{x~NrS~Rq4 zEh`wC;ffYIP5A+$@|d_CPxyWvONMo-NxqYd3K#fZCKkmU^bN<7)J~K0mA|22Bj1+$ z&=A|Qn2mRH9b_0wq$W_uil89HB7=Ihl1*o4D`HMHWDQTSNGGB`wP^pC=WS=(<1k6# zFv&-N;JkRuL?&i}PaL?UdGoyIGqAT=GVUup&Y!1u=i`||iT1qjK6Y}XLa)C<jA5;* zQ&AI16F}tK0&9QX=c&;DRFb2t6D#srEz6G#-x7YsS6U`b66Z8~v!=G#Bk*7*Ix7#n z^YIvf>jH8zavX5*3S2?KA8+=(8ptm>Tk}424b1oNb~r{GB!4Q^E7*@ek1;VJJ{>_f z=Fi+so81myGcG0Yl--Hl{?+y70?)qsPMH-FsIPcFf%Jz&I9?`<mXxpyA&XL$D-po` zEg3mgYgFrQu;QXfK?}hs+$XB%Pi-_6XRs+)Yn;jx_pRGR;rFLKT{zQtPlF9j`mUFA zo>}Npw+b=I)w%M<<KU#MV?jUI&TPkb_TDRh%|VN-wyPe=M<2s4@Bsss09P<-%-I6e zylAM<#yFo?iy*8}viLBBP}O{@07Gb~w@moyEpGd{WmeDo)6fund`sU?!MB%tD#wl- zbdmlcNDiY^#ovgDuX8o~g-Jz7jYFRm`!GeQq0tgP9~L~nrpP<)Ot%p>HbWrsKfth` z_A;&?>STCcJ1#kpFsznd*(&?Y1IfjCv8Vg=7Mr9{AU3_ZQPOYM0aYkP=6m_sL08$s zg=o67_!R<OA=w~v<xZ|AV`O0CCVafFWWLRYOFlEO-$d!Qe9IAoRU6XdTDXYEcY8gX z$)VV;JrQ1Rt(+n2Z8MLo-}sagz#FlXn_lQa-ffZgboy3Fdlf@>-!?gz`*0s9$tw|~ z5!`M-WcCxyBE4EFO(r0ho@!qhTA{~qI<mB|f-H3Cwsg37eA=;o{i+YszP|XFDU+Tq zz54<fk|hzCNqh7N+GHX_`_fb@kV5QqUP^?}m>Bob)A)8^&B?AF?~|eJ+Acg;sib!D z&|HnNFVNrEonlKeLQVR`>)}SkY>14Af~S~y)%r=~l!(3q$T0xyCSucE2;f)DR#sg% z47^Bz(cEEO0B$21beZbHOl);8^9#?yBu}-pJNRthXUjFWO`l-iFhQ;B+(L6ts$kro zk<W^Pclo49q7`jY7GI;LOB)g<|NOx8-D5G(u(u+5f0<LY&>XKdQTb6p>0(zXrS;+J z)Sv&(SI@0&lq%5qerjveJiozeTa%(@WFWejYstSaqFvv_4(E|mO16Ycq}DAIWtY0G zuqJ+g@{_~-i{jG|$HqlW=T}kO&gW7peFK9okok6o(jfo6w_m?zvP#!t=Q7sa=7+fe z9Ff+2e5rKt@Er3Nb3gNqOhW_%nyFkiaYCJwy_6qfC<eKcXb0T8Ig9^87QxT;DA2Ms zrktQx?iBAZMTHH;ie1H6DE5X?EH}W79>|3-q?peoXpmJa&WHt*-dawh!)e(EY<9jN z(>c9SKCqdRD2~1q_+)zBn&=&y4DlW6NX5remA+}46BN=cQ4<mh6aCsQ&h}+);j9SE zn?sUanNZJs7hrXpy8T*A;v8I*C>0mHX|dgQzkpd<Gz}grr||Pglyf%)4>_7PCr{{m zV1G|~$0YeQX7udcIH4^mcCd@XqerTuOfzlrfQyCi`_n<BqydKAz*#E<<Sp({1eWou zVSz6&=1@}`RcRKI<hs-rC9Q9CZ1l?95;l7>=K>Lp>dRZpFjA87E6d^~FO2J4!E{-p zW~B;{hVuLR+8?0!x;On@y^0bqKTb5>Js(^+=DSK_ejv?JU#vVTlaDV|D?5YX34z&U zIhmBHC(+BpOS;iw*81g09<K`RW9+5}G|hog8mBAQ4r_$RGx$5D^04XaYe}*|FS+hb zjqC-T<L$=k*3-iQv(StU`$hMk#jNfssJHk}#&kQsu*kY4&;`)I66+o;dRNDhR)tUQ zSn<0qv@+Z`d@A~}u#A156GjAlKXtfqX2_MQ$TYw3Fz^ShAI;X9Zf0H$grI$kd!XR9 zZ~ioj`93;G9BkL{Ft~ExL%^~zG)}<ZE!OeS%@-{Yq8yDSvKdRd!p6{_xAY}p&O9w# zdfPIh12^0opjF27yd6Ri!6k|iiA{=QM=iV+i}<WPoFRNLRq)Dq*oP8s>M-%aCuX&h z5Cs(C7H1ed3VfMfG)7^GNSe*%4wFh#LwDSXjpR(u(i{ltkzzwRBHWJI$<-toyuavT zvBTwGi?Ko>V2iTT@`66}u<E>9(7w7JW55wt;d4fTmliDW*SG^bswb#kbIrIF2OxII zWVk;8(;cq`E)**zx@tw;Uw#^To6n&cbxeKh4SnPU`Kr7wO!5VkgA;SnqaE%2!pA-? zm`_^{&JU-m*s|PT9V2`mNKWf-T)lTWffzJnMxH;!OI&n#PWf$G4PgVLc>)F6y><Nh z?!I}Bh^{gGh;`eDaHfA2pvL(8`21o&Z9j`onT(e~)N0>({SA@tR-|9UGTJ)^F^|VS z@a)AVv@VEXag7sKUFQ`^$Kl@N@nQHQXEBLq_pQ`E4+{-K^E|hwW-tmbkOYw**OD9& z$8+G0yrIfpB+su4uZA(hDD0rz;q3c|IBG&SusnFDEd7F&-P_Mj8xfW*yetf<nwJAR zgn%O`Q4ya8BmfF~Ef4oNj?-l7anzrui*&UgNlYI}#&O|I;g-h?VcDL;h6~j`)>H&g zVj!#k=v!%!R*&7=!-Qay+a@pPuT%(M(+ET<B<%VXl+64**lzVA&*$A4a{ScloPiwt zYmj>Uus%#9RK@d&lNeWkY_J_?6y55J>8?HPfb)oo@$i>Kq{73_<Kyzfn&xUtbWzT= zwqNI)G<@c!8E-=Z?}ic~4wGtvBK#uQ%C}9^Z82u+3CY?0CDZcQ2OBsSUKp4e-x;B@ zrH$6w1oA9zAZ(gEF#oVaG~tNzF1)=g1FN^5IB9YGF>LF_HH;f<b8G`MeJbACO^(=( z@7wqmN9mK@G8U|rG?SX5mvfINM^EEBx?Xe$kQIz?h6wy}>gr}vnC8YXo~9~n=L-Uh z5;W5KrYXE#pvk6z1y|YT#ap}fV>Ne!za6KlY_U+KKM;3G%NRApil;PLRYW;iCqiXt znM?aU=vl<VaK$XyWfazd{lrDFIKDTLOL0Nki*B>e0E7F}WzOv&H2CSc`YEqm5tFo( zlew5^${UPGuea~}SC<Q`Gt|F#qM-DCBf`v<DPwrOB!<UKA|{SE4{A=FFZm}$xwGbk z9N7(koK_lc&=LcW$K};iMY1@?S|jYH7U^bGC~A9*xs{}NEWV+;_a70tnuRd=1*nJ9 zOi(XpYoSqjhP$lT3vuKaAnh%(Mg{Rcf$t~4gHME=w|KgFP%Bq|E}>MJv!Nr6Jo*&m zG&;|E8O_jyR3yjb>w15C!BGz12qaW4IpLdreh~29Y$s8}(stT_FPhW>qD{7jhsH>8 zqKm-t@ig`ax@GPoFx8q2eYpWC=3j0o*CYS>QcobjQDC{Ew0JtN9ZPc61M_T^xMVD7 z_gt(YVl7GWA9lxc^DTsIes9puIuBuP&E-D`rg7=@#v=Q0ro4um^u-{S;t(OO4PL3h zdl-_cw~uDzQ6^gOhBex*Zl#)MZ3_nL#W8S+dm)CN>{P9Dsbhk7AW4PV59h44Jo?nr zvA^J`hP?~omTiYJef04?$V1kHP5ICUlve8*N2zPxcCsaaMjL!hy6*FLwAKjVZ0~WS zwh)ZVC-rFln(?r^Wk=2hxvL}+Glr}Q1_9L)GmkH%hZL;0jp|4F3E^mn8)1rarli;| ztS09OyR1@)Br?53&fzk2l6owX-$^9n!(Q3{^yR)e1#r1r&p_@1j3Ohg&&1Y4k0BxE zgEh$#NHW(hYTy{p2UfW*2`+c-;igkzCHOPtSw@uwA@T~sv18jhpRYkyI0`);b?Cn? z+$ussB_`_y+TEdPklTYKclA=zw!Q$M<e9;b3sbZ}A#dPrgOwQiwb^B<{+mm;+TnbZ z<#;^5idq8Ec!2?vSrsc$of4M_C;GOq5z&F7b<vd!b(le@!AASj<MXQJT2k)lG&C>b z$tYY+=a`VW>reHU)CPsLg>!LT@$4*On@&Z3u?_F9Lp|tE21EmD$EDWMpqPsnGUr7% zP<YERJOnYu$IIpir^MEmK@a7!kh|<*a$M$02@FZbRP~fT@P3eQck3f7A3&uI5qT9$ zITX`_L!vhlQIKeurkb#yAwp8nu#bNg12Z7P3+z@{AD(K@6EWnz7_06G`bwuYhoz$< zWQ7EN1rwjDP!Vvk3pz9VON#lKEiZjKrFdN*mJg>}Fq}~xk)_Kl?;JrY6+b_lx*3Rb z2APC8$eKR~sVT%8(Q?pX%B3jjT3#7YafR4>9hH5b@tV(aVNMI{a7JrS<@qa+-nhQz zRv7W$xb}Zz9-CT{N>i5LCa!f*HB+>wO@tgmQJRyA=)_YJJa0L`x2c`~dOBWLJ+_8; zyj138El?Ss?n+Uq4edT27`?8{>rGlDN&fA`@30Ve$m&zU5raxbS|EoWwxVp<$pXTw zk0tKaqgTWl{@<9QPhx^n!5QLveMG%PiG5-f!x_ZAhUkdT&IO4j;UYv>vP2mbgjW(f zbtv{z^x5I$Kb&ygh7o~k6QX2zqJ2bBmA%W{(WA+L1I1RKCug98NV9%GA1to-Az=}_ zKo@xashzDXio}g>1hei7Ka_qT1wL=Iu^`6G+zxs)+rT{D1#(Ffbjg)cKC!-k@E;#N zdxBwD*s23kHo)Z3%LSJ!GKosU`3gDstXsJQ(A~n13RjZb$>Q6yJMGUA{Ru$wy{ux2 zj=w-3co_kgjPpC5B-9(rVG~g=ic$isD!h*zvt<@@<gw0RQy{6xfm+I5fg1&J7v*Lt zHjTTPUHrk!wsAs4g$FiU`V(9^dhK&alrrz}CW|v!RUkCbz5V69jXYRDJFhxW)b>`i zt`mEdn@S(?=g5K!{;wc_h!8&}b_AW!4ocXQL(lg~mQ`CAacacfihOpG?VM|&I7Lm( ziQLIT7YD?6|EW|JxjgO=Z!Vi6#XavB*y|o~f*O?VM?r65?D9TY#2*+WTLY}77rUuD zb&GS+lOR)U^nr@GbZJ(uXO#2)xDY6MBw1Td_0Q<zQZ4{WIkwzwS%KWp0VEJRJx~O! z9n14%_`M|!4Ri3U<TA;{8712ZT!ILxo(IoWk||{zwwXjYu$|U7{2~y4-Fp_(#KvkU zM>WSGRr%&QnkIl3tvci)v?FVKzi1d`-yBV{K1KF`Z%%&(CDg`ALNCXuq#*bA_7vQ0 zmP&Bv`+vsLTqA_W0Cm`Jl}_6(I&ZfX=wp6)xSi`D{&@Z&*g=e6wxv2!mZva~Q~0JQ zuvJA+h&}=G^^n<hy}3r<^R>2utNhfdkHhD2rH$gfmY5CH)&p2xJRfBHiGkvv##=a6 zZR(G2R?beWEJtETA3!J3PEH`AR(WzAf*(7K#ys31?(R_ZQ1_2dzuPJ=hVa~Qv)p$= zkCjc)VDF~ruBH&}JMO-UMPi%YPi|B{8$9%+@UrHl3!7Bll=ztSuErrsbBgSY*W5+0 zwp<1$Bi|%XZ8G@tuZK;!g+qu{D1es|;}OLo#v!E2xnxWvM$p8U2G>MmA57=P2}dEZ zHf{t9wyF;k)iffPsQ2$aZ2E~GOl1D<C`aKsDu`z^>W6NyS$4AB-ktzJ+5p~0X{rsD zY78HD!Wm>3o@<Bj`?h)l%f05H@ZAadAGbcyYSeTicXyHCm#wLmmM53S3{*C*l&KAe zkd-Pyj*gB-Xb}z=*vfuoSOr#|dsG?~Jgl(?VY?i6eY`Osa&GxsRk#S;983=RgMS() zR9#UIQdnA<EY}VW_WXNOG#?Jem8e%m+%7zzIAw*?{!NTTB$i8=svblh|CFn<#$-h- z$J4;Ev)#g4sjvr4CefUj4j>s;+B5KtN|;dmp7m`uohGmpJ?TLp!^)RqUw0&ThA4+j zg=-)`x6|poQ_WwngAl(A_q^?bpTxY}N#V2K$J@j1Uwb%Tc$f91n!|_PEHg6lMz1Eu zEy%<ZxN6t-d#U@ZYNblE!*01;{TGV*Ub(SL<choNu}_$b2@T}Eo?3$n7h8F))<OXj zj|qPrY~Z<QbHxNHtqWeFV)M#~5!rRq(|-Eu{QTa`dm6Xvsl}*LN8pRW@fSWE!^PI` z*73<CtI2)*`i9k-K_o>L`BzfppKi9Vw;8_Gj}8D_P3RGy?Hvp_;~&R3qdiRk1%P^D z6(z|s+;QHrAOqOwMA(^*mtgnXD{-7Li-Yq@XXpxah`RvyLphbwa-*8W>-=c`Fl9Ne z0akC<%=>x_KU-FdRy{xlZ7Jv5?JPo1xkvO$6@DW+QYmp+_uabOO4d5`qW9O8sxOA= zwv9a$+1^G-+E%4ED`GySk*YMOzml4CPtrkwRAN!>C-jKD4G|+*ee}t-V@~R(1o?Gg zf9Bft@haX}Ez{4X$4=i|GRTaVA8Z~lIz2z?9na@V(aa_?EEh_*$2ZLA7luE^GskMw z;y$OU7U06D8&;VU>HJJ}z^o#6V2&qErMnKa^fQ`sCSbNA1bPP}WpI|@DAg(@B-6lr z!xK-850n-y@0Vmg<r3i)kxBSQD?IS$2{T(XBnmI1ZhCkV;PxU-qHquzLJg#;Zl6g} zQ4z9G+MBL7mmfA4#0ajGQK_}iU98gmXzbC#hHV-o&VkiT{N;`4y6NNA*6LXrrUn~u zuf0I(7YMSVY^q$|Yg$f`t}-4s|BWBv1^6uRr&-G_M|%FYy>HuyJ`G-}YLf0?QL;Nd zjCJ+7S9%~}8S4EBCmVSCd{Ui$eX>^0T#Czv0q50zE^10eMa8r@)l%Jd&b@na4U)h# zUR3+`t1s_Y(S9nsCeiaskKWHm#Y>(imA|dFi*9UNkBWl54{yR8hWXWvA8k|-OC{3o z&S9K?dv2uB1$%O^igO)~7IH)Zf}-+qGjVmbi)%h6@Dvq0fo2#_&Jyce$PcWgK$nzh zV>G>#is9g_4jESBKbSf$KQM2GNfpx84D2GeE1e&j>!9c0c5<_FaC_$hrwgP2Cw3io zYB~-*pZD8dKijqJeFfbNvx?mE!$jiCBM{)rZ^bd{unq4@_8_U(*j#@OC}C6pL+{73 zY~-0&D{{>X!}P~aB{vIIj&PG=OzhP^O&3aIj%V@lc-<*w&l6g2?#ZH&%P^7(n>OxE zZm18Hd0#7AE>xrvNk9AE{N~twy-}ynjXyVSJ8NWl|Jq8CD#HK%xLbHG{a^_bGa4@o zOcHIc8(Xf@<%wEnn%qk1sGgt-8A0G!WAu6ud(fN|)EEvCzc{)6@_p9#$Rxvqi+MxP zZhS14aXBnZs{Q>vI^}U&hrCQ~_fe=LHguc?vM)uMI@Kp(B7ZQOq+&{Ik~h8}RJ173 zB15haSLnVn6iw!B_7LB{%`l{!noz+WI8@bk9u|s5k){pu{XEnx>UpJxHCxUW6>X!S z)JBfouiD#VvyMEDS=p$8XN$FzLkD@z{52up9?i<;ljGV3Qq&oY1nE-bG`u%$`m)5* zlx_X`9S1>Yo!0LnS2@Wa@>yrdTz|Hzx<y4^f6~`uR*vV)M8Y5Y)wBc7s={^I6tn&9 zeszBJSN6H7<_p6K_r2bCg5C+a<)M?Cxl-lYv&L0yTowFSj+Y5~xKCdAbPQduPVfZ$ zYp2;hUH6`TZr=AT*gNLigrX9@9HOG4!9g0YcTtuLEb}jM2K!U)?eJHWLt?q3j;lV# zj>omDBucT}K9h3&TRzWI*@67Hxpidyfz%;$h%7lcLn_lPxA40t+$my!CF2V|hr3_u zSQa=h^%lU3<hJ5p;eweI_+<)noQFdd1Z|zxyq~D>%0wFUPUcEV!KX+yyX-eRi)Mza z3Kr>I5H4(b72_}8uZ9SwE47<U;~>t8rPj~wV{10=XjP{D?&j5lyASIpQu!?P`EdC9 zOl>DO++_J_yw#6tzDJs}K@%&)4gI2f(XG2!sEg7}ygqEbhEhOU>&$L-OI1bZwqAT& z=c16$vKiMSre>>sZ8OGscHO3#&EzIxBT)<bb&Rl0dpa)Di)`92X;}xYj_8G2DhPwP zX$@$g((GqaO_5EQD9ly(?8AjR-``inlYC>L!!ntBqBeDO`-Zd`lFh|+o31hYP?#$~ z<K~A5PNcv949RFkXD%nW6UEdu5$2sQk3B8@e$jpt#Z<c_rE}dr4*6{7#dq%b!3R-R zfF$thu*+ywtFxiltNX%Wt(5;pndvvlxeNb#ll{S}$TVg}duKC8S>iaM1^`J){F88Q zAx)Y~6vo+Xhu4D@0q|5z=z&61d^D;9iOw`zz3OwDo#>+8vhCZ;1BX?}xnz72F)uR# z$O@QE^F1w^{~4O+ygA>axc<Vp5Yf(`N0WAbBqmfQ2vA>Bdja}4(Mus$Pr{yJaHAQg z%$pIS{>QK~!PXeT6JNYA`2KcKU{k@xpivw`6uGrG7w^yfIP$L@lT=Sm4pcizn)DQN zklb!3{zKW`?cjMQb|XYJb|@t`{Qv-fW-RCIs5E!kD4Z?=trR*Gn^l$Zm~VAZiSLZA zX>CS@6BNC;0!M1|Gn-LY?-NDFyhE9={sw<*S+4^_$L)-jDRmpEXBIP?gzXed*;9rK z0t)PEw+Vsvjk7v88iW1uVs$ptuaXKjiajzcW)q1!uY4aD{ZWj3{M(fj6<;dxR!r?L z>-B?QT6Uv&WPp#OItM{$a^1Vp0-b6w)1x{~Rp%r|B@ZfpWcfwQpl%T@JIo9#-6W(_ zMNo0|$tD^O3UB+Gy&oZqc+C@VNBZ!!-Fkx0lz^%;6{v<PQb5CcA_k5SRKFwl-;QSV z^E}q$G`A<;ID9KS{CsdZK-x5TNOu{Lf;s4riUuiXn@gK?xl>9AnTdyYn)TFfG#4lL ziC)5pZegPivt>kt5tSaJJ9OUlp+AJt=f^TwE#t7#`}KtQ;g3_t;ERm^EKz+HigS@2 z0I3O+8mkL?x4$_yQ$$Ry80#eCMvIB2yzY)ofw7+TR^2WaqYIvMisF^Oj7AP5U}kBv zk{U|kX?S4lWt{>lOA#wixv+bEtzI#NE6k~`$!YKGmOTY85*!w88eo5Bb!=t_Du_~j z{fX9mUPUzw<M8+_gyX#KO^wT1`7JT9Z-GTi^rAo_L<JGR?Jk=s9ZUO+CzEo!uXN!I z=w4V41muA9(fWQsVjVS#YF(LxjlEc6M4crf9(Mya$yxc`vC#X8{zutHlPA=JVIs;B zXlsq^E2MTQXJ3v#YypM!Z>x8>`7GW{*N@tPHOQ@6vnSlQlm)2w)zVXR;1Hv=LV4-x z$|Ho17M^Ge8!VRADlRX&)Lm3EPQO@&1`kNbb&h|cNwd*(K?+-n2~|9>wuxt)^`S}Z zQc>93tGP&Dux=CQJcLRza;KH0iTyStP2@ot{&?v}GPt$ld@pLVAzvZ^g^WZcl0+K# ze^|Q8u&BDOEeI0QAvM&{-5r8-cY}0;baxKj-Q67mN=cV=r*wCx-|>0Be_Z^SYtG(h zuf5h?Bh}esNby{80}lbKKh$XU<eL{wl*>*B^AfW>!1oXQ82*P+y@xrXzpTR!r^OB# zv>c1bc3a0w7+3pM2G*Z%DzF`0-l*2WhguP`ip1xShhsQ3A%NmomR@5RloFsatd+{O z?XC9VSUF#2oG!DU%Lo=<nZGOYI-Ds*E%FZ2Ty*4@CdNv?pjVpnrR~CR%DDeYX_^o_ z%y%Q4FcF_!)A?kj>-TzFBHXxJzhcFxMtR$`%Wdh0IqG$9O|+uedAwwy-j|dUtHu+Y z%{;{^f)b{dU|iUjHY9U6QmD$im-^(eYg<bq=1@+;6{YgwHqY2%T7@U<I3Zw-eS8EX zS>!w-3FG%Jwlm4A#gQ`1kNiK!XT79~EAX>gTS_ZJt;Y<)Ldk8EY6nMZRy3?iPRhIV ziQ!;_*}9rC^kxCKkl=Oq?dTGgYL8Br+cga0bedTUn($OLVQ2jxsHbGN!taMVUam$* z+c(r0awUVtxOlrL%)rPQ3{pB%JZhAuR8h$qV!PjD6MfEiVCZ}DwI<}w(=TRSe|xsD z6Ep}Fli?YQPnj@=qWBR-ZsA`EhEV=Oiy>Sj*p0-=3|K324x99dDf&9%6it-5a|!Ot zC?2|9@sQB<dTsV2U5`G*YxQ!0ulfjs&vmKz{KMJnXmiXK@0-s0p35ck(Fo7npJ6|d zpty3Q@5pYyuPi(8-<kfIHE<YtXls{x9#IfRCsVGm@|wOCE3m<L=lD7j?a+(NmG(g< zT|N0mW)Dg3M=eLTDE_RX@53g9^2;CwdUPeYq2!9*PT7M4B`Tq8I9$8PLagtb$A0<5 zu^1&*Gk7NAg(o<b8I3a|q*Q|UVB(iIC_-CGF+0-Hpye7O0MYyb|LD=ieVHc+Kj153 zN*==++9jTTrCZc11OJI-LVq8_As(|Fs}`3~X|Rij2)6%G(){gcTQ!%(#ncUc78VAd z;ZiXwsKTdLpyI9WFU)612WPOzF?(%Wc`jACej@FynyvesNK!^!!SJ1d#_cK{?|y~N z%q_>^la)yk|4_WDSrnj4Dbn85N_MKT&|eWc`oW4l67K>bbS+bldqaWLcD>;PSJc<z zU2UcGg?rBDvtb_H*5N3sImzJO1eEFtb)F<K_7UMF)~wN_<R<puboTlv&nvksPIv3z zQM`I(j)<xRe=%HEI&<aSJ?5Q|^DnZraKCBsy^1XxOWZe$aWo0&H;R6CIyeI8+pPJ& zCo-V=P`L4cD)@3FaI;~hankyG{9v*HvrU}HQLDaqi5nJ|Zm>1|>BU=bi4gi05eglO zMwF1(xs0<~GdIO1xllWw#86T(yDZAge(Iw1P%|SoQsG>tR0&yy*eHxX{KHH><gg3f zNFJro(Z1Cy9?3cf-7=+tiq&&>PQysSjI?+k-tRHGZb7Mb{gcMxQ-ly1C6OhF@5H{( zaddOEJ|@vQ(8Rkd_C22q!x9!3p&zC<)X(ZpK_iWC5TREgA(Jm{JnX=VyQP?Fqw`Gq zf>F#KJYpKJ_6v}{wVEScJ2L0O!8Lq7y^xEGV*W@IF44*=fAver6t5b59kGX{lC$D; z;C;0lhk4is;7WNLU1Xr!?GT6JsuuWJnyq{yxr87tF&b7?Rna;?<AuV==WfaYl{z~< z$ybis)SPwKjh1B24WAzS-B^vAhn$E<aEEKOzauC|T+j*se-*9;J`9F>rB2cx9wJM} zDiZE)ky(z@0FrFZEl{T|MCX4wfjsODioM9qShkV`7v8NQg<pJ8wYR}$Qk^GQWax?0 z3YjRuT`#CAROZ0|k;oU3r4jTkE(~6@oGa(lu27whpP^l#mGSlUK4`uBh?8nOS&llH zPZxgwwS6p&Z+^KKd_JW3+dx%NywibeJ^S(#wAc=zFb$#a%*y5dbDi71h=Xh{=@``n z9iPmocF;!l5NTYrzc+^{Gkb6cC>Fbe%v`s+F{TMj#2Rj4*{d^yl*&;0{=kVz;n%EP z!AtZ9d!fI`ll3%%{oyHv$|YD7u!U{Fc`OHk@uadNi^K|tj(%oI!l4pH`DHnkJZGDK z#=T!6t&2e~V*|djV@W!7RPvBKM6ds=JgN9PD@^9S#m{*XgU<*pf=(X=pSJ~I5X&90 zs4;21cvShI$%)={mz}qL`MnoE>Q2~%0ZkCc$yzuFngd<2mx)R_UA@Rra<lFY1f~EJ zD04OVu!std9Dp*yXY|QFbw{H{^~U|;1LI{#got#4kb<z6CM_BUnv|2@(OXv~!^|b1 zL0XBgpDL*>wR?VuE74i2X;*txp8W(Yc5xv>*`!2TrakQq%qaMdTxoN-iTa&UpEP0+ z3UHH>6^Y45E2a_SxJ_P6Q1~T!a0ZcMUy04=-|(r;*kuBUe}UB<$?;*jO}NI2Bn7Wt zTRmG=rt<SXI=Z(T6D=w9`?$ha@j%ZD->lemahQm-N!gSE1k9`JsUSWA=dV@#kuMeS zNwTy-I>f&3KmV5BDtq4|^qe3aI>dUJir28N!WktM(kCJ<k>pEAQ$Yr1LZJMV=t0r1 zxPk_$&%HTYf#2b7sNYkV&HhDNcLYBxwH0q@I`wzbIu7{s@<E$OQn>RE;%xv8R#uR} zU%7i@XC5b6*K;+MPLDo-dHw=d4C}NxVJvNz5N&{tAWq8A)Ao3vH49g2>xA;n^VRAl zB|V`1k%8r^Z%|Tw$e!AlS?67C8-|VfoP(PLH&AGx@n<BI=)fS(kLA8yU_w7N-ge<7 zqnq6@%9qxQ0UR{*Z!zTe1nqXHO|;}~2J$E&L->giNih{e$uMw^G6^O?|1f(PuL+aQ z>(*CTNPOwL(q00{zfl5~CGzAkV%f91z=xm{hX)3mSGtSM$_1vD$5fDxl9J(c#V89y zx^w|pB?evLYphr&&jn6G-K1re%R<QzUCKy2#8&%uuwFnxIPR>FwUpeO#=G;u_{Opm zR&Vy;W|Q(C6;Mr<7ZXsRt_?V2;33i4Qz7(+L*o<qtN2nG@}DTLSZ+d7<9A{?s1gAo zstuxk71r)1;*%XURtjZGg=`UGs@fp%wmGD0ND3Lr(x((yT@4*59V`~Ve{JWda#|?Y zJdRz=o+PbP{<klr&ys;tfXw_Brl$Rmd!d<s3EGETRRz2|PgRGp$7|Gwmyx!3i2XNM z#?E{Fuw9MmoF4W$Siv3T-Ju=UTP`2&54JualtV|Pt7(sDRu)YT_cNfaOhKQN>}K_# zeqa8=vomU_HexjsA>~zbvoF2ZKQ0kySQAgq*a_5Kuy7M&*mhZf0DAFx=!?h~5QUbs zMC(YnDkTm&$}s^(DHCLj?rOu+W!10pRl@3Ver@;PCg8)*Ds641^Th2*CeBinHGq59 zWqj?!<?bN*zCw|dCp@s%ibr()Z7tc*`iabTu}f@`+w7Gv@x1|`U!958s26dvaqhaM zsB&zuP+(`LGpjyeomB#du8t8cjnx!!`Ma%kL!4P`Gq@)oU@I~x!UKoCh|&M1PQg;% zWTlUKym-A?I+#r{DT<1q>@_V!M^<6dN7>!WqX`uym%_A-*by6~dv8gPAwo{{i|?G} zGhBE~bdna%{lWMl;0~(dhjvMHR~1XNaCrJ`H?Yu%u~_DWAim*IgBRno9nB^FO`g$A z%(s8?nMvpe^9Mwtn>7PT8>x3Y;Mp(Gi@c?uc_}!B{X0tF>53kmK5ezjjN3LD*Hyh( zZ{9h>SK&c}u`<|c>y)RN=&bqy+?rn$*GSfjNSd?%ae-gD7>tvOyo7?C{~7%wn|6p< zvSLw^)URoB&~B)+<Yin#zM>Ygx!w4$V%6B032tNvp#yGmGRIFGx2AvV<BDFE*++Iv z#8EO*0~aeq`=?h1H7ndK1Zqs~CEz15_eYwDPo05C9W$2FmID`y-Y6qtUD4T@C*gPb zUz^^WA9TgD-x=SAZZ+MaaNEDjXtDV2tuR+*{WJD|0~iTwzPR61ftco4yg{QJoid@# zY(&a@u80{n#jSErZTZZe!EB^{BE4u_rgoH5>^Y=PIfo5{Le(-cz$3o_OvqYIZc|nz zI8!R(A;{SEf_T!Paf&M5YGu*ZK?og<8NjQ+&wjKM7GJwL7rsG)OD$4r>nqI7oV!`m zHk3pTxRB03a)<00C<ZN@5_uxt?_suNv#R3PcTB{c<T3yTFgf2-WEXpv`?g6XdacDl z(9vxHCBOyZA2tXGgtW8obd~NS<$<V(|78Ktu{tc4Ve4rHi|mNXBw|Go22u}dw;jdc z)RTz9U78@R*ezqda#@FjMDBrqZMZfy^qAn?j?p3IQ%GHgjbczuQy1#9(irp<U5-Pn z*945*%pl$PWd9ARb?04wiELMzija$8QMlhw)G6_rR=12Fw8w<y^HDv1L&KY7Y~`s- z6tvaiIVLpKGtYmnUR=SVW1IhC88iAP<iIlBXo4n6&utA>?}v+)@x>~_zjH+auR6V? zg77OTgxw3*>(nqArP9&8je~!Gg8P+?((e&22ak;qZ|{`*bci7ib33d-iZ`D1qh(qV z*?{mmt=t#piF(y8>uj=bswf$TY5O9Ck#3X<tmPAW)GrD9TY@|=NBGb#5$<J<%I6jX zQFs<pSuuq-z6!<LfMkX2;iOb~C#mTJqFLd#|3rK$%`bGlSTVzPSVGD4tE>)ivB*Ah zdeVV3C`EpHwkJYrzu75E*(MARMS<tl<XnsU*-p=kO3&j658CQtPU+#WG`HfF$3%Uq z>NZ2=2#q;hBcTs0-6$PpLiUTF&yQaHofie98P#xS+ir96y(`HuHATFl5pz6BhQ<TW zm^UH*$X8zwm?;!s5t$RqWjVsx;XE=$r-c)%{<{Z$L<?nuiLPV;=3+z6j;0$?6kDAg zqmLA#CkL$@9O!C03BE@E!IcSljm3+2hm9sSuy++J3CV6Bkv9n<4=%wU{t@ba;a$;+ zQPuiG`SPG;CWaDgfoMPFzmq_A0qAKnHZ%dBx&v5kU-%khdNW<^=4T{Zu6RNTHuBZo zYNo#N7F<`Jc`6vxslg@562B2T`!Tu}1N-uin@^15qasxgcRcM!nnHC^cTrx~HCr5A zhuvLJLkQH}c%t(haUNd}sp2SnmD^VSh*Y9@sj7lFr=c1V&20p(vRe;A@8R5d(bpU2 zd-E6Wc6TI456Rq*Zy~bRuFjOjN?ara4LDYno)W>m>Ymb#HoJP&m{3#q(v-x!mwlMg z^g5$yKSzPx7Jyb4e);D~Dy#aho*Mc2-L;e!eZ9mj9NpSw5Bap&ZcUUgJ(ZO%$;R#6 zHGZJ_g(BF4n^uZfloJUmKE2<BBAR)wP2wxkQW<M)SQ!89jf%xuO)}6mzePK8O{Sq~ z*7o%##3%?p!cb83Cz++6L>`p#I5*G6E;aVF+8n5;^6li!V@P26L^P~|yr;eCoRNG& z5*hhp%4c~ZB0ozyMUtzpY@-7R05N+T^>=;jyq0kSZ)t49Z@!ElQ1A_C#|CaD*E)D% z=CK0wee)B!5CUI#fEvS#lwyx-RIrhq^+O8H2;oULMCu_uX@BcD$E*pD57+tK-+c$4 zI20x$UMKNt#mzAFc$9QCFngou!AibOAD9U6Wf5qX!UQS^z7|RFVy%_1psfB&>6rZp zGf!}-2up!E1V`*`AWJv$Gv3HFp&*L({08yKP}lR4ElS!_TrDuBu!tO0cmCr>3@Aj2 z;f{<C!SF)77zoAig?BWO%Dv3GZy+5xGNKbgphc|3yp)Wev>=x*^o(;Cb<Zx0<%`gg zYg8_nj~v`XJVev{41eI(3?xw`rKEfj!7_<$Hu7`gG!hFYmG6nqo6hF}vhs?1*M;~? zX#&%gvs`95$#EhNHa62$Q_4Wf{9kTvFRmQIZ2B-*n=kmshB0^3=n^RviY&#X_n&_K z(wqB-y!ib0T=DwemtxydlvM00TJ;5pDqo|6-#<7m%eG&QEHo7ic{Jf_e4W9OLo9^n ze}*Q?)(O^+<SW#3ryLh_BEbxUMZUavc8c1uS`&~Jlk6AiAd}%&j<T7$XGaM85U1=L zTNooSy;!6{Ebdk$l4nSkw~<gXA^1EN)ocXk-k9I8%=krLj#u(#cOu?kPmz+O|D>(h zA}4iV%K~Gf^9tc^rJPPJrk|2VQx#9r)M!&#z8En*`3GsTh%af5ehNt0_+YyDBa!C= zX+lhBbjwdZh>(c5K?lY^`v3s|B&2xr`o8gmmlFN;k10?liNHz=%o0LhZbJN15cxbg zNap{g;?wmxD1a{$Syj;4Mu!C*PS;tG4qPmHhlP3<RFRur&SdEtzf-A81jbhuP)2IT z##5@TIKR^|-u_CULA)*aPX^>CCWMlUXt(gr&Jhe~3cT<FCx|nA6)5v@{LH0yD5lY4 zp6!Qk74j0^K&jc^85|3+skcFqtS~9zzi2Hv>-VsaCk(SBf48NWkj>fOG3YdR8!N<c z$`>6~wf=+1%5veWxB%j53c$uJX_-To`!NYGF8q8A88|a(;b<VaWP?vK2VF|R*54Kp zgk#t<d)p7T$g4Y_P!wbzh;liP1C7*;a6ms1ysP=9K#6+>4oI71P*dc1^Oab;_9G4; z?h9QY^Ux)#v4hQ2^WTBaDztp{hUk?qkU~Gb4pp(5k7rr=p>RBLdiGU-?pm;7RisSb zqG1TdMpgP-4}O@JF-|LHB<`F$!zDzuh0VB;iS__AQrP9;g)9S@izZ#gLK{7NO1bmv z)t}buvz4hzw^|qX(zDrr>J?kky077bkNYa+Bz!}oblt&RPX-RKba;RF$<d?+wz)RH z8*M3up`6m$pLKDTV)QU~2!$#!K<%tL;GB(YVDK@%5JL|$e<vJ>TM;4}mP&35NlupF zr+>_Av{Vm{e8<^IRP{%7lhCy<e~6Bx-a&kO+4FwY<%k;^jQRQPq407Wh)NN?duR7_ zYQahi=O?nffCft&#v1K?Y0dNYIw`ty(L&f~^m3i%OOEHKyh)M{j3!Jb^K8}Bz;wRz z+X;HXV<)a+$B?xgiNN>$)3=3|n8MwN{eMj*J@j$3d)XE~w>^n=vsM4i2m{Mow2#G| zfnZGcu_^<Y9QSv$9V860p&xM!u@zHBFGWlkw3TX#hSXim|70Q46K|RIhVit65J?cp zH;Xc!-8gWKmk=Sbw&3mteK%8!<4{ArZJ;Gf<~AI<<e&8ztUVdszO!zH9~#{HH$-+R z@We$pYbw`lOixQgKDZmRGCjG_Q^#&b=xl`M4&I!d4CbuZ3c;P@eoD1Wdu9!7nCZi- z!Jp2FkoaQUJk+FI?0B%ui^EWW`*-j7B<jL1=2?$(wdMDkmazzM$WTLe^c;sN2EJvD zoJ1mE@+z0&N_532V?=!?Cjy0u^}RQ3{ibPNb8j;W#va)~_qIe5eEY^Y;IfD=Fk-%y z<b)~~Tt54HLRp?LD;phL)JsP6V*SMh`LRs8_#2&~n(K&&{o)^y;u8QxnY2Jp<8!OQ z`%^8INI5DCU$PNJfv7DmwK@X|%n2G)zST5&DWUX!;9G7sEiH)Kpu+@J<Yl4LgGxF_ zJX9kf1)4j5Y}t@x4i#@A3v{o_1v^>ycDo)D*q7n9zO9l@cB5(9_4RJG0%D;;pXWP^ zxhA%Ojt)B8-o}H$djFz)ylYSLG6R_U316|r^4u$LcbYlm%e*cLL9nL#vz{|MVK<A; zm&JN#@Li`7?oWyOBSe|m-YfV*&&jD-3{(c&b2;oX+Fs+>&jZ{!y!#x_!K)4RBzYTw zswiSrLro1;idv_}VEGDJx+f6opkg}0R>5(u*jJK>j|xlC<N#@q7-bQa90#70<nJLx zM@2_5r7%rn2oLoQ3bntuHwUR;duB##SG!TF($Po5`nlzz1PlardjgE&kcp$^LJdPi z=J%c^1+UH2boSE8op^Z&i-7^r_YJ}RDU)AQmLH>N4U>>QCq_)YtvKABx9;{cT{t<o zIUBj3(!kw+$r}{cih#_bo;yfC#=RJ-qR<jm+}tcx5H+x+YNTxLs3^Ef_2Z8+b+45Q z3w6PolG*}}dXIZCUYnf=U*e~1E8^eaLojFnCunrzQ?bLV?RNYPh0+e{raqMoM3D#1 zBk`JgSRz;}uyC^#&$@r-=#QsZ`GIbz^H6RtcRVx|3J<yjp;J*?PR;qhSv+r(RFNud zQ1JQ0c#Pq9CKs27z}0m|UR@p!Vk9g4&VwwftQp!;db4T>Rvu>gfYT-HtK^z1-5E7E z8oKBBdEFlYr1lr*3ZnkdG<QmzHXnB_>`Jzb>8V-uq6$@xN(@y6o6%04$)HZEWDE-G z22ZJ8uZOc35VYqx4!x$qUP3}bmkFufRc1YTfM`HaJ4NzNY<>d`<$?R3^zsKAaacbC zVP|WCfjm901RDUvqa|>}Z>GdP_bOTrXU}v#a4WU$xY|fXA2Ub&kK_^x63>%ILnWoZ znkrYJ65)@C_$bBcC?%L-KP-uzfPDO?WWr2c*B0fK-#f%2KFX*k8`W60GF$OW?bG{A zS&4I%7}F#fLAbaXf3=)0NR4qgWSXOLzXb7uNr3mR@5_`l$YadFiBN(+I3p9E78<zi zLxw^0)A<|8$jQwns}%uH)#T}ube{l2$lie>Ypsl(Cq6b_3~u(_=A;i_{(C+|X&=Vh z9+ayRfTZFv`5ON>lqYuFR24G^@&@8PZ{_0tpc23(uOiaFyp{?Kq<={3*25t_Xv97@ z=>L>rO%_woavAJwePo}z;=b>B&wNZ=HpE7~PB-~7Udqlu2I=@-fMEA01~23QJ3TaJ z3U+btY7-vE<0uTQMy{Ji1Y%0d&jpHPwW@Ujs>c$SrBYzW-CAS?M1}u^&2cm|$bbD6 z5EZ0vWK!IYf(cWyWRk;J)I7%MU&+yvUx<2|-8v#?fVot)|BEOFIiZ?pFGei$wTI-X zq%_UcP?K7b2mnfvXHd#|&Y<Ol2G#t;{D=35!O!At<$ocv?}jP?tGbFtzt2YscXXT~ zQLO;k!diNn4ea!oh(mq09qpuqUvuX1H81-b7W6yhV?^ESU%in7+@%V(F;8uwYnkau z_}e{pOVVk>YcGoqS`)RH3M^E7XS9e6EMBKb;n7!1YWRb-92VnHgydwha`?f9SDptQ zgFfj5QT_x(Qe9zlCCb~MCnfdV`wxV8cATk4;u$f8*fO%TT6@^Y*5~mk3jff~0n+61 znU<p!xL%1>NvDeIT?^{-l%J@O?hz72^DqehD_u=%PmyU#EkwLSwU`=kfbI0g1X|9a zs->8f`0!xL=5J@UrEwlP@XrI1nP`YZ&-$rS!&1taFRe>(3EuAexLQcu<}E)@y0k-b zVL2)3(oT@P{UFG#>0_;4I@j>2%0Bw!Gb7ye*4EY$)Vk<a<L~ekcb#G~aX%Ey{vNFT z&rD-~_PjO>XEl&)xuafL;G8-7$ndN22RcV;Mf$|w3ykQG(1Nt_dz5yQmRs!fSM9fN z$2hV$rOmS8Ca@>}HLTYEZ3>@qaVb2G48MunxVk{qm7yGC1-lr3pd++tEluwW;S?NE zchKU8WS+J~?<qI#%V{!numi&6YR|(bm0|qE$U#B=E2V5r8!7i{$*^+!87Yv%EIPkD zTx-sfw%7G)xD_(gYt0Q`I<HGbxOP2l!MsNoY;3U3biUgLTXo-o(8!MGFno^3p-TH- zHJX{+!71~^Pm89Jl&W8n++$0yp6tSGB-g^?ZGuIvuK(17G^B#bbPgx?_x0V0<Sa*K z7p1@bOZCGi{%`7*P}kB52k7<jp>Amd6FJ7E3JK23iy=sn(d14-kXe%b=gxCq{tcVY z)4}i`m|>q?&2xrlNAXblt4|`?YwfvhKi3vZEtuF!PZv_-@ML=KeX>=dpt*85*o347 zls9;VE}v0Cg!Cl3+c)To#FK5;el#ngR|DAq`KK9ToKYjfw@d@{h0-U<dBo!2j9+5C zIT93d^a0NAs0bTiBb@f)Ehb;Sh%sA*L9kGnNYlpXl!!{9@E8K>r6nR@4)Xs-v6GEG z;l}U%SC<{Yilt!?T3U`XK$4UxMN8=vIRsG?F!78(GL&P`9uc%nMx6;FE4N_1WZ-9K zh#-#O`eMCz*LpD4kp=_vaMXcXciZ_4?nhimfLHs0!KO;%nOrQv-}H5ZgZ{op>?89| z66p<&L$c}iOZx1_&lD!ex+%K*t1tawoixCw%kWn5#*;6_45kYwkv1ZTXTLBrg~N%z zqV6LteF&el3uAMnA6p6@!oQB-+KW&{-Q7nsT(Fo7FB<wd%=eoed}k-`8MLq^6r)OY zdS3emK9)ZF*TgaY+o;7%MKSk30dNI?nKjhCY&wbGrjbTFF_Kp4H<$!WXhwNCRDAE< z-*x^gTkeVMl&QPKX^@mlH6S4i>BFiwrbO*;m9Wu-k=Wz{Qv4DOv-4OPu}%|i&0yL| zclwwd0=wY#Ogp0*!_mVOlz<;${_Cc{ulIhlAr`!@X;LXCYXuil9+s(7N)nA=u)J)z zFc}{3Jjcr>6(-P%xAXTYI%TMd@+bKu6_M$R@ne0V>ml`{iFZN9qH>bqClZ06fIOb! zA@PaF$fk-oEI>Xd@cvn$2JlMpJ3r&MxdNV(f#D{ggw9m}m%Lburi6+NzfEz4@Rm1^ za8u@I)NNvKl$qBM3!OJY?ft#{;3>vT)Su|(An~4|Z4p<T-)h*+?ea4x@!=0;%6nFg z>_PhR-XO<^U+{HTv%WQh>RwFcKc`2?NP6<69(k|`&B%V;JlD}eD3+AD*-P=-FyeWI zO~LW<`TRS*lbP$H)5H?Tfw0_fBr)^^N;?q+swV2;tk^#Y4d<`->-JfdnEB1=k0|i1 zhlNRUJ?{{VD|8=!+I#T=a~LvS0Iv+cD$f}p7aLd*p~UgnT2K`b6;#dF&PDY}!L-a_ z3UF9h^GDgi`e^KHqY3KH%Gz5b(Td3Ft&u?CM*NoCCPo`hsW+jzL{3yfRYpYmxsnJ6 zeM)zLeR2>qL5(9H<Bp5Fn#&vPziwzsn$2cDu7Bn9vP-xx2u8TePLW10)Dqjn-rY+R zqzhjmPM4*ag6xU0WZ8F@$hv&pOIMREtJ)W>@FqmhP!}D+lzmrneW;sJoMo}*vY;Py z`h6p&myo;kg!d++wSXIDo)6k3#T`Dqw(|*5L(e5S+%diuG6cbjwVCUE@{)Y4s~7~- zAL1>rPW4I%a2Ya#EI)?NG!<u|pU1p#e(JMe4ZpxRPUm=t!}I{>X*H*?Ttcv&zBK13 zKSB-L>X@^--nOd~#5GXt`t{tdmQIKR+S3h~h>QyzHD@AxF_&l|cT-+Aa|kjR395Ww zk^!&VUkO=vyH6A81E1D-n77p#4km=J5eIdoCROoDA`A;Pz|NG|hs?f;<aoTLJjC}> zrpmaU{icgP6KfTt=9&V0(EpV_(7(rWFNr~NUACm!hP5M<vrUSejj_>3J+?S1?UEo> z;pU>t4w}SNAeF>>j5fe&UukD@<Ow`Y-nW^sNQK_JHn6X{@=~QCo~!+m(gm~z=~{;7 zW&YI7PHEVe{=(0RFIeitTfk&KPX(RgY~jzv6F1Usq=u3#(?#*yPl;Euz&LB0wO&+t zj2FLux1~K?v;-dRWEmk_N2MQLL-~+|Cf|di&ve#1H9VwuiOtqC!UX6;m09Y^#gz<O z);-xcR~oop*e#U_*rlEUk6^A{*w61GdEfpMD}_kqTtkR`-Cf+PIodSmM3Sq_ZqH6Y zCcgf%z9<oiLc=|e)IKLtFMNIk^o%x<wp^AG!d}j%J_n}Os<5_iYU#SpdTKkC@yO|V ziz4i~S`L-U$=jBuVz4pXPZw6jeJOJcgwV|){_8;H`8U9lC0&ab^`;S6I?kHh*PA8V zI7tS+Zx>6vSt&y@7_f7i%n!*OFOVABzR#M?4TDIETX<e7=UBI6qr40lo+jgt(Ne1K zq8&0H!G%AiE$E9eFGO-yGSIKO`~#n#0LGJwDDb*zMxO1vwH*j&Vy8fwGt*l$QKtDy z_$t1a=l55QxG5T*>k)_7N++~i35VZ!&*0CcV>gIm{Ltj2GU>YRdWEiW?vke$U_JKE zNOMPoy<LNi*L#j+FW2)1UxBw<4efMTv)>sZy(oND^B?m+Jk0CZ_0yDQ8Nu6D;}{?_ zm3`1B*8u?gFSL1TfS#G%G!f;r*6YrjiT`sH{GeX=;A`vFoddjs$5h;#q}W@Y6h)LY zEh*`fT_2e$KX+CKM=iAkWE|*=;UR(&KqQiyyUz=^cnz~i-9OYAP?;g30eZV$^}Ofv zuCB{l#o)*n0h7T`mqVOwxL3c1l7$rChy=&m#_)uoHx<ZY1ql;NLRfaM(?JczAdTFP zWBoA5kcixsVU6Cd%~86ZYChBOz@k^9+@w$88J+)vZAExDpcN0StnI|#9*FKOFU^U7 z5P6pEF&@ACEGYiI=BksFnwrU~3uF{otb9M^?K)fj;g9bnRvi`=>3q=9a$Z}Lf6uwn zWE38_4}Zktm!c+af7?YhWzuuf#pA(!9460ROiilUHY|uwdRP|4oQ_+lRpd#nJ0D|7 z-V-lSS`O3sc;{Xb2Eq*AJo*0<NcSag91~T?okJ5)<yM#5P|z{`+uFqp-KrBCRpeV3 zp0A^eZe|9#Z)-}jDp7dLoLs%sIDC>R1x9a2Q0AxG(%vR)S)Rw;BivB|K_7ky*PMtv zW$prz5Dt`$Lw84WAKg|RAmQ3inIiK`W~M`gEJiTjIv>rP&({f6N@Q8i=Xrnr(dNAb zRNyRt;Y6epKpK2nf|nAU%Q0L(9imCaE$1I#Q`}U@!aCd%8Xr~)@Alyg;z4YCbUCmG zbiqy$!;;d85iE_tMNxf~$tcfDXsAS8gMvS|6GoY87<;vU$hqPFn-!tR03k9Y=T{u5 zh%A#D&|N*&$(OKpnP8%>U^c-7*Ax}uB0U#cQk)(8x33~%nI;UuwAa(W$hOtk>+)n* zV6-HLg|akLx2L>_tW@pL<2}`pp>hbwnmg8qF?4tXGHe!u?stjbb>1h>rS#O@uX|-) zOapngvt`B{GIxK1P`9Gk#=B$q&ccAYF-mR8aj%uTaeH>yG0k`X_Iyt8a&vZ^jk5{# zFL$H9Ot)(p>P=Ws;ZEEESDHLEKTgTW%RhXlDXE>#AxIQTbqdzPK*<35cG51|iFORr zwCdF3UJP8l-l*X(<}+k5f=K2s+ej**x8d<XJpv-4yZ$*_M3Qsx6Vzp;$(<rO+7>T_ z0UxxxCbSU{w24m)P8;s8Jok>7@P&>D0-@iZWK)w;$?c}g@vD|wPjhgjN35mkRTSBT zB9){SvkbSfYKH>)r9Nr~GxPg>CLk{J7_cn><`!m$Ezy&PQAWR|&YDhdAZzPjrZiTG zeFwF^{qSKsb`Vp6Kj0%{>${dU*Oe<*9lPUOln7_%lf^0SIPEXluQ5ljx+x=ua$wfv zV7yP2!W+I!_r@=o=bPPYUIhh?Ea5QO;ykUHNhp~g^sFRUhljAuSelD^<8Tsi^^Thz zYDv>3HdG@hrMb>VJiWM9Ljai)dVr@GKTKVb83$H_oy=ogv`*tJz`It#R3mBwt}js; z*qSh1$w%DFA@i`(>q)mnBTx_GVrjs(tb6sz?rQJey+N^lzkqBA-M+H1>y&2&@pt93 zsYW=@o0D%fD#ZH1$uy0g<0I7#yD2(vAtt|bKW_~E&9rG4W<CE4xZF8AvG6?}nisx4 zugLt);=%NLxrBIh64=xQT%JCz1X-Qr4LnVXp!Ngq3!{Pp)emx3RmHd_3XYDa)5Vc( z>j0Jbl}Z&=#$5z-s3u6m%CLODOiQ>dLEfE!(h&(JmewF5vy^nqO4f{`8Jl5Q{ky38 z!fTGs$Y+Y0q&8N_1o_}`JsVwixml*n!#+eX7fb$|ZBJJXr3lP?wL8f%(7}>|=bg<Y zamTkK_%Df>F7}_@>pSbZb!~?%S^g@Km8gxlN<6CCIFPnTM?B|C)F=Mj=PexNZjW!f ziiad%&6lCOHDrH5+tp>Yno5hO10xz!oM9uD3x16IcO%pKRBOaG$h3?v+C=^y>qI_{ zEf50S0KBTqNt%NA8@|sBfT|Bp*ZZ>H{q=SsnmAxK1OWEZ+3%O`y8zq1$X+r4;BNzR z<DvDN)CspWmsBZSs!|2M^7u8I#@{5w!~!kJ={2oei2S#+Di5~{`l-u$rhftVQi}FQ zt^Q~4i(ha9OKS49E`}L`K0n&b2|9}1G#e>9obG(E@al?0c9`X-^M9=+S(A;GB~_le z6HW<zY}mmX2dxrX7Jp7fg~LX%bJmLW4-2CvD`&l1cGB+e<1U&0Y%-lBWpWPEoEjZh z!ZC0({TH1Iu$#9L?wU5cxMj?;=%~l%hK0ISxj?7J(W1FaMna5|@KLON=fRQX^199a zzVUNfKYQr$-!`0Uj)B&kuW!l{i+|E{D0~DTrev#*E9tyK7AxQ^==^R`I8yr8pU*7| zY;Cj%daep08G8U?(@ru}7QM&s<>B(5OQ{|(P!(D))Rg>E-@e&NRM<*0jw$c7<;YR~ za)VS9b>P8Z?YR>#VShDDMKBX48RRWQ<a48>>%JMXXy1!`Iit`NUA=QN&Uc>n$`H^B zyvt)2gS@)$Q%-*z*T`fa0u~Lfg=O28H6#yhD~Pr(=}eNO9x$08hktTiD(X$ptCT$W zNdZ4lD-r?c!$#X9rR#Qo99C5JVLJA3r?*9@;z}Wy=g1~2SX8u^J5KtM1U+2okhv&G z>Yo0RSv1rNBDrC0{6_cJrVw`?3_4T(#|OL@$@_|ds@4irQT804JFV^g`~lfMpqXFc zYZ@6;-U%w|dGJ!aRHWcF+EMLOhSK#pgBrR{WxI!yV`2SC{R{UV`>~E~7y0@@jC04P z!qEatM_;@mY(WNz1?e&`=))x_r)mRj9VZ^)5vT0eyz(AALoD|eJn(1H1XKG(ASvp6 zRsJoIj2t3MzxKnWcjEKkDz(w99Wt`UA%XkVpvDQopPs}a9nzO*ELzEj9rx>Oo#dWW zJ30mCodr^&(#G$Hadv?LL}#kz*d}wGF5O2IeByP|QJI5T{yozz_B?xCfNxL|3*(Y` z8kEeFL2?-8n8!s4|MP6)d}=2_SeQ9x8+8#ay@=3UY-9i<nXHFJQ<Qn^u`I$OuLbz{ z*2()IB}M|<)%Rq7*`{}nG|jor<xhY~l^q}Eh~iR_tX4}20}KKaIkKynR-eyr^i~k1 zcx&pTs_lv28U)s>*3n#hivId#y_twW(H*cKRSP$VKC;|N>#-7tDn*o)!v2o6(SFY` zV^${0f!l$@S%QcoZSakQePN~Y?M+QVxAVh~zkt`@_-bc(j;nAL#M%!WNzMU!BQ8lA zp5v;<I-rrmRSDJ8ck;NIlGp}Z_bh`7Y0QSrFT4#C9y4-Wh6j`Ri^j167r^UfZl}Fx zzT3ZORauQB9PfDTCTf~ar4^KHb%X6OQzDmnbiaV{mEpGYqnnI<bJsdoJQniBr)}l) zuUVZ0Q{1oYTb5Do2ZTGY@40Oz#)s@Pvt*)qLd=At8R?ouD0@`rH0k!duaHSE!<^X7 zkkReOyT%8)gFYk#d%<`kf14sa0@jTi1_}B$!M$wfJBGRuiwytHx#2JbkOeSY*2!?t zj#wROG_ZtBe~{r;7eo2>cfwuQV}2c}Tn;ZWipp;020SMMQ#2q$HYb7%Mdn;NN;WuS z67dFpDIF_8w)DJTbE_wiL$`u2mCH0sg7@-E)pbNLnFivv5W}-)A0lCp@Y#o`@m+m> z7fX)ic%50|tE7tnme&xUyQR{-Z*;G(fMb?5rb^?hM=`0WpIe@|v+YJ_$C6wGBq??| z?S^R7&~v@rV^3h7uR`lQ$9~?GFA`U?$509qCXq!e5t!d#XhxR(a!G8_B@C5;V|EZr zrbZ@8K^`hy@)=OICrO`9(r@Ko7t1-TV~6K&q3^$G`%QG*=b4`qsl9=aBSjYm8eJCt ztx-y}PzMFko$FVhTQzEy<N{q$UK=A88shoYf?~5{8``b>2)&JFqy~Ayw_KXA{U$Nr z5-g4EwcMtFiZEKgaUv+K1nsr2I`XB;{Gx(3u~?uy`DE9?Xi-BY!Kc%9vRI8`y~OW} zjkCGC7n{BL^tr5l)Vm&c<W3P|w5%Ojes7O+nI@cV=bg{8t(P)P9jYC^TEs=pS<cf^ zlm%idVrEG@)-EOU)jFB%&yL>72)pN$kGX*H<p#JLjDdIV^{2?Z#m}MO5<uttj-bgl z_62DDg&Iyu8=WFbI)y@a$mDJVYGc+*PXHhFkvQvSVK_zK5H@cTAX83(P#OA$om)@G z&Y+x!nxsAQh_Y5VI*Aru9bbet#;VLoC728;@k(tKO#Gc#Pwm!FThpoKGo>UCCJhuy zQWAxNg@I+DrB2lDFGs=l@U8v6HTx9dTl?fSH$O51)~=$qIM%iQL{&Eng@z5PlUIrt zCN&!JPUPEYnHO|}$jB;^(grtP^YQHGIOKNRFa2#^@LN>+u`JGGnH43k@4c&E^llgS z`+m!cUIq2NQ47o}hQ%$$;&uQ8=1t2y+Z2h&)&|x3cnZtgf}G~vR+%<P2i2Ae9*O<; zEAg3o;&(jXDEw(;%upP%bkY`WxU91G^I43)UHV3X*it_(p+cix>--5C8~j5WG}RVK zHmTil=lh31K8GJK@)H9qx(NVJ91WDppwWJhXjkgfl|(j9grzech+<*kKY2@;$HvB{ z%u78HOEMXBTDB~0cJ^$1mXVQ}0&Zz1S(`wiLoNzyn96HfI=ZgC^lP~VzlCk33U=v3 zJ(a~yG(0VyCN85sJt#c{ueg3i9b@lw?qAiWyfA`Mmt~qLUx`auEW+p|^vE&)Ivvm0 zxWU4Vp=Swtd^QoM8@9JM;`&WXS7)dR<Q>C*i4uUDqxq40#;~9TW!ji)>oNRs;+hXl zlk!e6baf}iUkCadLX#1~$z`_)nS@JT!+o4B#HAkl0qvsh=+mgDrc31fCx1oc7?=PF z{wX5AjK8$M#4y-=S@0j(N7w>M`aL!O04q$5nsO;=zhmKNt^Z!45U8B^Z5}+;nzo-` zs&C|t(8-6eBSnxPa=@HW>yW5+;7|`+0hfuDCgY&-0SVV1`1i!wH{Ih-fIEr5)Kwy+ zvCOq$`&#4{@ug~1e&=V=Ad%Nt-^IaHAsiNFA0>kNGt$qAnreKhqaV(0UkNpym2*_j zwdtftxNPC}x>4SitaryNT`iF$cYVZ2&rNlPW$k%Qp+jzC`NMt_rxg6X_4^ViUhn~g zh712^iK58zuvd7T@^}!rg~2eiVR)S5&&#k6UVc*w)GzMA2!1t_>v$vnp7xd#jakN- zbG$+&t29?qkJGD*1I*Y~*+G<}NrC?s^5<7*FaC=<F%mK!*eGQPBUhhuawJSXOiT=d zeNhl90xF!piG7j;X)8+rB-MLB5!U5ljY-_$(@LvS3+|*aqHYCFZu{4VR6+bC{s^aF z+D#+juqb(oCj7J(bTUYx4-~SN$7xO)3<}nJ5h+^qer2VKii*H3XX>Hk0&Bo1HG9(X zx6glwK-^!^M%**~5CnzYwzKXuA@Ct@@fhn|#9#bFWy4IJR0UB09u#r8eTEE>&G74= z^Dr>5TBiRhZdqKYq&#BiD-+IF7IWo#Y6a;})bM>3KEv-^H+w?FEh^U}-Tg9)o-L+0 zB1$Um(&Ni7-j*%|@5u$T_&z>zs8N$&@8ws7#84kRTtt?QjFS+MCWpP}#fTUczCbVJ zC6{iN62Obam%nnIS+mP$u0*6F)(Rxq*A1t}uuLPOcP>RPE{I38AF@zARr(`l4OI_s z>_kny9vr^ya9GR4@m<QZwB+{2c6~-*kOAu7d4J%fn56WF@VdApu^Q=idbi<8NuL@8 zMOvEBOd9@z%r~6ZMVbmmEr<9U-MwfqzdiIiC@KVEjjtZwT6ZGh6->{iOiX!v@KlT| zqS_V7>t)O-S~&c(G-W+oKE9^Bc(`ziu);YWdPNIWH9Tj6=CK)qgKx;#tK9!=kpUxX z(nM3C5A|bbEg@&`cP0cF^twew)Lw__#7}}WF%WbStm-K^^?+W#6=?0FE33w>84+|r zu8W3ylK|`-<yG}APPcCN`-<+<<AmS0?pUL6O*ezNLZM_NONv&8-h8QLX=&-GKi|&2 z%H5aiwF9a4AG|rlNlbO5F)U1y?ZlSKjpJ=k{Ilp}@Q6#!XZ{uuO8AG4+^CWYp=rXS z2lpN0RmGs2zp?LI>beiWL&r<oFkHu*f+r1<W=N<Qu`ZaugXpiBTaXV7v=D7H(Tvjp zvt{kWsU35S3VNN=&*A@H<8_%lxp$~K(no*9rao$7VPoUr=vbeV&Wl9ClFU!e2BKC| zXhK6{s{VW^|91K0RJV1i97Qx8dq)V0{;<e(-TF!5w1Ar!pO9DJyF;}pQ4*@l!TgFC zVdtm*hcs?WZ~(%2_H_PA`}vu5!21B0{@FMZ6@NO40K_FP>NHK6LK6fhC>$tEsH7Y6 z5@A;o<=(Q@Bxhn4)QoPq#Fk<zxr35dL=y8;q3PI_QyP^L+~hczDoxw~{O0Jrgz<R8 za-oEGfu^=F{4m<cY(kq%C1aEVIunaZ)6YW|%~e%n{wSlZc<)5=;*TeU8XAxYC}TzV zzH@!Y-4;%EyJssKAEhkI6ZmjVSw}KJAwE#p&KN_0=T#CQriNDbt8M!^KjkYm^moH$ zN717olP_8J2c+Um(TW{LQIf+0T9bzF!e;5F&~kKM=xt>|*f@tMg=R}rd~JiP81^#V z3;}u!0i3Y><Y*L4Cg-F9q+B|qp78#f$&voyrUED0-M!4jCfqO3nCvgDmS>-pGU<Dm z<UeCQyBe0cgsN~^eX1vhA@~%m`Nxp1*Yk(u9C*{%A0D{<v|MaCuDJs8%qH-^BEnP4 z{(z|o?hFh&eC0?T;iBj-jbl!YtWf2w$Sjd^N(d8Hs)~EXwUNE!`Aq>8pG>ELe?iLJ zR7g%jI%&|Mrp>Eygo#(jxnEt#ql-0r+`1jZmcMx_K;AcJ=9<(uAGSGJ@SWoQ9?WSt zyasYxoZ(`OgN;nYlrR%rg;vFotI5kYUMTmz2hs_4k(X=Isdhb&RnJnI$Fp*UQNqPc z*v%M%4|?n@>AIp^XfG7iEh{DRR9TXcXgzmAd#-;nETNg)c{1;^KfO+8)Tv^$!0ji- zi$x_D-+SZoE1Odzm$Ot~CtJFu2xs5so4-GI_J3xrOkc0QenVjYZ)s0P!vhznwe!9Z zA<s{$T93NJ2eUWd$JsL@g{6`S`N6o<%cs4zq(1V%UHtXq!Pm+m5m8WapZq(Y`+>jD z7v8%l_Mw=Ii#8SOLQ>hEdhCaIW-}6xFaLJz1GLwNhqzP-E;&?LcC>>bS)%kU>7I%C z^gqZaQJ#0W?>R18%G2X~?A1A%vTz2(HgDnD6O6F3Mk`>Eu^g!?4z0@|pyR@*7R%wN z?xoB(`v_GipFe>Z<mGeuOc&pB!ZQ=Y8Fz&H@Gzt4H7$DcG%B#Tm>+f$YQqeK*Oq_D zuRIZn6zt~9RYxBlh!3aD^6CkI|4@lnob;>P;yk}usW$BKk8C3}uJ-IYegGWsn`UY2 zhK~fbHupJRtFg|&@AKfF{<$}ypjben&cf&qm08}TTLy9&<os4%H%xy!zzI|4+7fMe zZv1G=enT%iqTmr`UaP&;QBVb2tqHR}PK&BYpS0l5xH8F2j-<D%g<6`k=Nx@&rKqC= zYH|Ps(PXwv$!wNh2bG0beYarhyIPy((F!!0@lRn&@SoqI`k_Uj$<CYQPxOE5poi<= zG~|gxy_r7ioM~9NjJn&X{NyG>k)R%47m3_PH{5e&>9TzP#ZXafVP-gyid0^>VE=4f zs-BrVF7x`~;rnAsor*v6lE)CW>UYu&4y_3ayj0G?4DW^KaCD_SmJp2v5PPb=uSa7` z+{Gu&1PG9-WFUI%JQr#Dy{IDIx*nH+5a&YCi`gI~N{d7@Qe!Yi2tkc50#n811ZL;& zk@UbiiO%5jyeB*gJT6!@)q)`o15snUq^tIem@S5i0$$A6q#1s^x>J{~Dc+38KoJZm z<{ptj2p4UvOvPDX3B~rKz2rL-T<&*&`K(KZ6&jg-mY%S0VE^iPAp7vXD2bhu?I}SO z2dQJ=bISYo`Q%z}jxwJblfIg-bXkGysx(7;V+6CmjhKGuI!Wj*Mq{EK60a2=H0qC3 zsP9^Qv*i05iS(&D_Os``8i@CVx^GcqZeA_V$Ls^A8tfEJE|KY>LBV0r0S|WcEV!%g zV@1%-l~qD5jPam5yun$P6P54%pqJ8J|MAP(4dt0#3yf<u%rgDOq=f>nkBp0qh1E&} z(I;;UcB=r$ykLd4x3BUN%%_2MvbYeBj~bhmR`}_ZfvrykWC+sSB_x^_i2U^alElbd z6?%)82;R8O9~UCB74>8;9C}P#v3{zDZ`{va(YBraIF71I%{M(??{GVczp_$dW<oIc z_%W8jF&a$s_d8c&cF>W`ZYP~o-~%u%Lweeeb0TUg@NC_Z`b^5c&V5sb{9qIyUM>wk znGJ=BXyP;oS~%b(oOp6%<IE9^f58hOSy7mJ8LV$3+@RVMc@O&~Yn@iOLJ9+h09}4Z zeb~TY^y^>vLezCQHFkXDxvBTCs)edEF+q0(q!k8z--d$3RF-7s%G@F)VEI9=A{zlh zkog%#?hW^|lS2_rVMNqXx?#LxC$?*}%iX-t?+j3^?~IZ)XJPcKaz$ZI5%~-bD~XLS zgr6^4W{m?W<vw%kp@|Nzeo=k$Bvro8hhhYIo|H+QJmA{#)akn=fgHg(KmIbY({5ZI zZtNcXUeJxn&2oZ8S@$E>eI0djc+I}Yr*!pEBjnv>o<I^@Fq-F?d_1U5b?D9?B<bN~ zkXyNv@|Fbgtjq3T6NfP9w=Z6GeD9ik-A(CkVGQ8>$Ui$}9sliX5AE8hSfSEK{-%_; zx_5nL+RArCzKC#LOhHfsFRi=hwRP_&y46x+La8dkTQmpQQHt!4($NRirlG*&@ESeh zvSkUuDOU-T?ToAQb|LEfG)U@dA;yD5L1XmtpBghu0QY(3l7;OZdw<8f)p1HO?&SK? z6Om6qLR4eR(&4d*4ETb4em8=yh8an0CR574QZ9_8?w!c3*{|Xw6)EfTT$4hhRTGcs z@%X%aY_#4>%)I$IgHu1fa9!629{xKTCIO3044Zh~7+Vtg!YO7v)VA*#Az!X{)vz_& z3z7zXxbGh@#`AQg>`Bk5p-~u>D;I5l(-I_CR)OP7@ZxFD(aQ~oqUb&EXkr{!(qBs6 zZ<m~R48H8OU>W=Hdu&vvIlkE`j^0nOkT9Jh!^^e@Fw*P)a3J7F4WR#^ic1(MPw~+R z!`3E-z?USYs@%{!DVnCuHVLDAn>Y3Lv?>ev8`Wbx!4gAuu(DOL+`jIbh*0{mNz~b6 zHd@5ORm)WJ!H4JtZU)-h#!F#-4uQ*#6_!O^ycP4BC#>~_#3Bfm5xcBep-O4bj&6=G z=C@3KD?OR*J8*EK()+;Mz5%x1;t6Anwh0lCeD4`)A~~<}oA%a~ZwMzQ2u)gl3`a$N zWiYnwV6Y)3*I~V@?-sEx*U6~Rg%N}iXV3izkz_~QDIG=^N+_fVU-6vIgwh9TU3uq| z#OFB(L7e}N+X?8CQLYTjSnza<_*)P>O!^*PNf7zAB4pZ5v^?64T9?zS!hIG`I5L+w z!iPefD=+7okB23;A}|^+Dk(3ljsfRLH-q0*KBv118Ir%YLKaNt)s24dupCI=>So;% z@tYwcGCsi`Z9`QkAIaGudsJFbE>bVt>ef7ueuNL2Qm4TUy`LEHPq1MnxDB0Bl*MIR zi0FpH2|$7D+VhuA<Do#I;-z+8OeZAy+vq^|#mAfcI`HA#IVg9(ZR3;60?lQ27FM{} zffpa&IS=RmYDKTXs>^cGaAKmt@`<7?mqj7MwO(ZZB_#n0G*`E?g(3R!`Li|=Rav17 z!DqL(sN(L@UZZkv59nt&=#On3;Y;j%i@wwc;jq~O2y<kyjO~Of<83JuYhyo5Gr`Q# zo{jJzZW6;B+?<%7E&`a(M6TmB-9?1$9B_0F4V)fJ9%UqozbUMW|7LmQtZQj0-RQ_o z<q3)h5tLsisCJM))^xs8kZfR+QJpE%>?RZc^D8%ysfp$a#)6&6zUTE(bq$6W6mi91 zhr4L<e*jiNslGDc{&P#9l}ez^0}pk?3J4`vP6;{Ldq{9-TY{n~^I<`U0Ul&KsFnvm zL1;o3&01R<$;YktErXw<mTNAVz<m-*>EMGOFF$r?QaJ~Buuow}pvAHt5=>6VAi<^} zQ4&h>*vO;+bJLGs0yAdJFtJJ`z*KK)52`CgZ<Uve+<(<})Rt_UF-(Ulo1(x+L9=e= zHOOE56lrij$|5oBfB&=ClAmd!k<wKK4U|fn;7zKK2vsK)4H=j@cPUv8f?kH(KlkK; zr2W4@jNn2pvN9lb*bZk_SzRZFLrjNel2u#RVwesdD=sd^J@@^cZCGR0T~kl}_%*V9 z4kVmuxuKHA=@X8^V~by9==caS`I@RPr5qY>*V8c9REfX<k;A{9e;U`%x|QmxDy(>8 z4b@pe<Y(yP^kCAc?SV&x>aF>A{1uNqvlRPvEySIFdkAHfwdmYl->4&?pL%QoZocDw z9JpUG=FDG!n!0M_kO8f&+=9-Xy2F#(5B1gm#{S(4Q2AvIYLLY_oN{pU?3;1ff1Hb8 z!i%4borERNJz;>y;|uP=>1SPlX}`J{x6QuMu%^NS9;!(0{o7rbe#zyi3x<)Eo5y`I zlvh>Y^%q~lvEz=#M_*Q<q(d&jj30>*^O4^P7fhRq+veVZ>t_BH|Mi<+kU3-4IUkib zK;S{f%>WOfBdVG*vOD6AJ8#4E>6g(BJBXrg!?0=NYi+FMsAah6$1Z_34?I-B5*Smb zPK5$LNmz*WXbyZ>=EDjS13oyyl|a!x0g9+M4}YG&oa&cMbZ!^JrRR-g2f$H=SP`CM zX1(Qk+ZYfDBC#Lp_&K)H=tiR&c8&&!FmKAAMy)Z<zoF}780&uRrr3V;e-h$Ks(*oy zx8Hudkv)?tM*CG~ep({?DIDVTdJ52%<D*lLLy@U+55DL&06qV53*&NV{vOB6#DD_| z#V~C-qExML0E=oGiQe@0w<s_}ICX44#2Tbtu__hXaHO`iju6N=@j3WRf(-!}3p(Tx z({sNbn0L3s0Q~5M_&sMJ8QTh9W+z-X`#xOttJC;hkzPua<5ySB$89(KR+z#tKNX+9 zi$_;%!T&pRi~$;F9)A@6@y~b2Jk=P1Jbu(5Jioe{z;LZ$5$?J9THN}~yIA?`0>Yal zYAQFNsB<4wlQqdD3-a=_k74$Ll~`~W0Rowbj#QUcfi@?R8a^+9;%q;Hd4thV#W|pe zZ7!dBJZ`@K1KRMcH+ce|o0(OF*FWBfK|PAuzSt*tLdYrTPq4CH(B|t&#_06A3vn$1 zL-B&Vye8A1i%-jI(5*u|=B1vDEP+K_9#|aggf=0NQ-X53XLra-F&=>qDd0gQLW9!m zjP|HtT$fDsPtjWDs{jSXWIQ&lG8pUY8FBZxC9v})uvY*N33v$&88ixbSe1*`mie$M z7YjZFIxO&za50NKUFf$K_qE6W&RvBVxBGR?rl-Lme*7GJu|p65v8oq40@kwyJZ!uV zu^k$eSr8)Np?xt5C3(Dv^%y$r(4DVU_sUi&0o9A@PD!9uF1KnkV#+KS73fg%5O`$L z$n)L*oQAIJ-xK4Gt?bkL+`Rx>3X8}>a0+_P8mrk~#Z*Mec!U{yBS_nXnYS&*h3AYS z2@*tAFis;#Mjx#w=wOsE6BtZ}qy!rZ5GI3C879Zct2Z(n1gs_;I!CUu^_Y3n4LIb` zA=}aPCX;RSpT6&sf;?=bF>ah58*(o_qHhUSe6&uInRUg=AW&$RnT_9*?Fi_5<DRwe zt-|a(?m>iQsaibYh(T1fR1yTPV;v-rK@eHNGR@UdQ_Zv^;Wysxz|r{l-Nl^CDH~tX zkXOpW1oIHBr(MpAt1xlGacmEq+bBB|by)+y4m_gkg@pLcdvMOAF?itFHHap+8r96o zB@d#{s8i69>Y-*+6W}2$4|$<va3J()c{TPW<FWOV6&Q8K?{MMSCmGdKf-0HIF1r}R zjyf4DUsymuLmLkQkC0(JV))hR<1zQikD33^crW1$5AxWqv-UX*<)6Rm0*_`Z!ri$m zC9qcj4_iR$pybl2k*XLEYwsaJA^;-Lp<@<&*b%J*K&VckaPiULLweMxzddR3<)k&e zIG|@X&N*=)frmU9QX$p3UqZ=(4;g-WQ*LhhxCJ~6<6%GuyAO7BW+Cv<C`KM26DLhz zN8kuP`ws5<hb;ls$-D2qYg~y1T5X$9-CEG0dd%R6xAZ4N(U}oxL;PJk^jLJbat0b$ zeF?D>oa`;a5vZ67N3{~e)&?(Tkv)rXgq|5M!+9t4H-?}MGzgWaiUAthPB9${B(^OI zsep$wX`DcZ7!T!R$qS3A7Ib7qTT`#JSo8drV!<zv)xJAceY}C}K>_^vy$RmR7}|pK z=}^_>rI5|a2pFKyo+=92J*bqD3f>l%F>nGC4?h&ouPSE@m5rPkm_UH42dQeZ^a=7A zaej*(q;B;WB38E%{_FxX1GP^U!c@7EuOPF*k%y8eLIxzSMc^Ue!>9A6wX{($#D>Zs zy5@P2o!NzUK9vRlnEN#S*93SNDuv)9z`kkSRx%z1?Qp`de%Mqn5-a|BH$j$QgtE^* zh8yhg32+?XVN@;bZ!&1xanRWFu<H4{%(=>$fJb(hq4;XkYy7D@xXCSn)+>R%3V5j4 zG-_3p%5?ByfrkW3OU#GBhd_iK>H0YuiupTW<{dBK<go|hz}^f_#$l0{R3@Pd)h_Jz z(~M3n08t(UCS-&vL7_#%V*@$_LQ()ksuy`mh@}zR;*7X-wVS@r60mimI<hnE3Y1#* z%gcI~3t~c}Xu2&1s3Qrld=+0^HJt(~i7zPU20y$QUuOD^-G!qDaaf87>ogo>fG-Ne zx%aQeh6;{)IXo}SZNN!C>A}%@O$ubh8Uuob>FE+C;~^tbwGn5cH`;L!bjY?NMD>jJ zXXj?)si&VX0%orRtEvjBKk@<@Xz+Ey(uZf_fN?*gQE4g^ylF5jBhrzp%YqotSsVo` zihwVXppMJL0`Zga7>uV^S2?Pdcohd39Z^kV-y9m1lS`pE_M%r_0H4L_DO0x=nHf2F z<%4w?-fLglZ1O0-<0!vp51CQUEs6HI^oq)+jYq{AKFfn&pFbY69(b3=tDp1xckELH zJ`Nwy3$LxCs<q~Q-1YcMOr3H}3!l4QlrFFYQVo2T)ITy{Cwf5!fybv?Ytfy|&*Tw( z@$_32bgM3Ra0xF{BK9(du1M7J-3kojkwF9301aHxVGtU=dXsING#x=%4$CT6z+>}r zUMWiuH@PLydL^(|0S_bOS$1-NRJd({fu_udK!{~MEb}3uV;2iN%$glc!b_p#i}J(w z;gJ{K!>Pv~!T}b6h3rCj+>VTOzP26E;Q$Y9Ti~G)i2)t#xMaO9VIspp*#dOy)(!jh z+OPF$-Mv$bC7}9HJPwt+43SkwY6k*;MxgUI%}nXa=|M(q6;@3gQkU;b000zoNkl<Z zgZ*Vvz|K9vKw!S3k3j?LQeFZf>duo?t3()=BOInJM~J|~8^#}IFGoo181Hrbi0;@Y zzaI5LG8_@b<KX#eZnJWQRp@iEU{b>gY($Mchwdpi+9;+?J0EAC`!fShO&(i(yEb}2 z@|ePR^^1?=@NuV+K`Laql#`*{_P#RSZpUvhOm-m}qI)e5$(y9~{nyd!fDshnNg9_9 z!n3O@kZ9PTqXZoEU@94jO`j~KKqiPGu*{)QzI^69T>I;($mRV){?4qQ&BmBqY{J<m zkH>wFKF7Kx@ZcOck*ovIQ27q;m%wG`PsHr|-ls{$I&**iGb$QyvVp8a9{Tj|iMKvn z%Ylmyr)6HhnGAj)<Kd-RB_fX$KF^%TeHk<;{e-HP9tHUbRgs}99*$bJId(y0J$Nx0 zm^<!&1{a)m0{bRTco=AhC|Nr3J_Cyj@xd0hvv{zv%najEd<bnkUgsG)%S~<xv|b79 zRlp;?*lxV>Ml-#;z<`2_**RSVJj8rh_Cp{<pu<w^+7^hg07RpYIENB<Kl~=X3}&Hs zu@C1>8On|zU|0_eIPBVj56yO~BtgOctdae2M%*d2i-Zjq>GFfLGH+x*(qF{g-sKWd z8LJ*NnVTkclL}7tZ|mCDna)Yj9>AXr<HK{#M&TD9BbOt?D%OADm48O~kU<F2tujH- zAvFj%Z%R<$kp`p@1_`TYw9zCPj3-|B7$0p8<7Z=g@LWb9RhV-{AtjIyv!O-m6$3C7 z3{2iC1RchvgFr)I!<m=Ji$|Y$g!yg9hP2DYu;<=D-;X|`c!+9?T-^28Vw^)4W)s(< z@vR8dg5}6>S4;!(EL=6?xA@@wRrFHJ!_!YbNH7_}kq7n1vQO*iMYKf@FerUv5e^)2 z0;;Gc%asO&_3on)W*yz%vxsW`y>bzT9Qjk^=5@tOOBT?B<b2G$^I;q{tUpC{0tJ~_ z2xb%`RK0-$J&C(-x(d@~+(uwofm5cOi-nKe%YH&a-Gd$-^H81H8&#jLHXx>Hg)%z^ zcv8s=KS9c7g42#<-Mm5;^nlVV+V5=m68*Y$rusKV!{z{L2$II1Fa_g|9gQodUy25{ z8>xal(XWt^)0IK##OCnMu?nhqI$_@fhNARsMJkOTFDHxOrW5KK%IKA~H#e@v2IOwE zVhQZEz(d03+H0@HiWMsih_I1OMXPJEz(b>53qCCC(P(VS5s{C;gE)kpSs~Rf%h);j zFraT1&Y3WjbY_HfDB}c>sr2)oItd9eyBN?R;K9Wv8Jr1xD1Wky*V<Ve)r+QS&*!K{ z`*a^S?R*KSoUKZ0?b@|weihZb>Q{A5lVZf=M$P&mjARELM$JDSLUitpl5`~N6DaFC z5WVKkL6G1e%#Pf$R53Cg4W#L#TnEER+<4b&GGjHE%8A`V^lk}<>Ifbjm5LK}l<E|L z4^8gI`#7$$j=hfs9C6ul&_=|tAjuGex;;msxATGAcE03x-zzVgb~<jJ_n@OPVEr{s z!J4foY~PWpvP}H);>$4WrtA5Q#xdmJgR$m4dYtfAr%wCev(E@BY2aD<{yR8i@S#X# z=Av8o61@NKcc_}!cGuE>zlMVbjU;Tz#_Mmc#*l+JlQr+RUr7lkQrt|t5Fh#u7>p0r zkU5CgBR?k}(X7s>-MYb1q4HLWBeG`Y5_CWKCn%sns>cL1OM8fUToS8ae-$GSJA%+d zeMSI1dz9eg(tlH>lY<5s(K05<vK6Z_eCPn8lrVbrEW!FOzTyBV8#Rn4lSB1iW%(9# z=|b>Dyy2yKrjkrsKI5j>*OsGG=dJ`NemuVDd7Me$Hs{_aaPH}o*l%s?pSHcZyXBU^ z&X>Sm3p`Y05<IuuatjtMTGVLsVcl%4v1z)^hXj&kJ{pA+_xWk*?(tI~pc8JG{|W__ z4}JDc;`~z%r_mQj(~LAI;U(Z<nGdZ6IMPScPBoJB6@|)0Znuq-%{2lL?qkPx*kOn5 ze671z8o(iyTWxKvnMg1lOd3F^y5VA?LQ*H5!59o{&m4~e>gMa&$#0^4z_5kS(v~BG zx^%|UAoVQ(AvQvRz`|6AL}-}!R%ta=aPKoPlR{Wk<Gd3|z1MD~;UlAva^x)g4GTQX znt{X;CgeFmhh;ekYNA>QNMcmq3_ENX{xtJ?7koC;juT{>yc`Vh<J$hHJ}K_f-lU8j z$W-b3;xF?JN{uChQ`Nb?KY67XFEpw#QaUU$oAO-S{=V{NQ8Km`Jfs1EIYVuSe`2c? zm`gB1@p^o;5#pWso6i&Lsb_IdmcJcpXyc=48qx<M=H{t?%9o6b74}_^6?+k7d-2Hb zh!2SJm{0a7d=KR+#$zUD8XWPsb6?q&akt4Ifj8T$t~W(N)r+h~{4}7C5fmrMs7Qsw z8>VvLuG|u6of6oqfrpAvAM^0x!;Pv%Y8I<<v97l1z@sJR!;Frlv!`Wz%#(+icdg-l zqu9U0R{Y1=<G7!+y^KxSsaW8lZTnjt!nVb+inriHy@bPfSP()3Hq!SsoMi5pV~$q; zVFZ-!>!ux-fXY$js<~pMPEmbpu^@6=9dHcF`U%i|)gP|Gn{<yX@<i!AN%u;!75mPf zkA}Xz8Ptnzv9h_4p(nwIB8iHfkT*&=k&Qpz{xnrARD)2obSVmA!Z3~~8I&p<B1nk@ zQ??vbtw_Z}0Ag8=1cQ%BwIUEB!6g@2sa=%+hZa7Fj-5KDgvgHHcW*pOlTk7bDsdxS zw-rI^=k|Mz@q;;g+lkyVC+V0Yz;`Tmd7eQuJWJOx>8Fyj(tVU12E*K%ZBXIfy<{cg zo*V?r*W#aRHsh3WBOA{%m$cfyX7Z4_x04_J;I~1*V)HCG<Vkt!*u1w|cHA57^(C;^ z0}r(Tb^PNwO}#*d1h`la3p^y4v|kjwfQPoN%0+9P9|*|!kRt`MA7=F6%f`)fpT}>1 zIhpi&2)+bIAz3=EQFInnFj01n^npo%kLCbKddsu|(*Yn-y*MK)2`0JSjvIHZIekw7 zA5OncAjQ78fs>x)B<W?)*y*Le`L1sZXb4cK>=bQOb!O`{z>%Pr^_Iy|U6^&DPM0(D zaAfO2cDNRAPdpA?5)8t`1Jsrv=jZ<k@5yJ9)|QHf>JWmEB-Jlb1qM?j($p-m5<GvN z|1!!Wg~;>N;?#);0l_bg4M&3jhU_?GG-_-+9N?jQh~dx(T5&oAU<5cK9JLCNFk5)& zkq6PGxXZ2=N*lg|+Ln^k7rV8<WL@X7zo_Scr9;PVDBHZ&OmJs1ztjI(`<+|+emnhQ z?uBiv1YF?33Kj5B8ZlyonRi2i$p(tjcDl_+bKt`Q5KGqws6S4Ut_)B&nqa(->t-#) zb(c*xw58WiqeE{#K?p6%n*a~}R?^yzzV+L%AE~v36J-+xsVGy21<_DTdF<P_?;bJ| zCVfp?m<^%NaLwbFW6qiPGYFHyP&@ChcW%wJZrwU#tSL52;LO$&*>;ZdXwQ*Q{1tkR zusk!W8?b8fQRqc~NKxw{W@J;3-Z=1<`3Or;kg+f}7X$_gvJfGzWp^QOld6apPcC{1 z;}7r4D5VL!uworX98f@jQcb4AL)DACR-|4@8IN);P~pVpaBO*uN=3jU#d1V>@1l+! z$aFkJ=FCw8>?r`VHS4g=-OGH$WVG1+G`)g!9a5dR$t{7sp#)sukygtZ6^|V|)(9st z8xrPrv7_Xs%!gIKGzv4uF%EchDcrn_e3*f2?_5DcwtNb=DqJ~z9P%jaJe)8=QBEa5 zEci&@wxA<@oen-^fa(AcM-7vt9$LpW>Ds|Gk`rUIdnYmm%<sw9j6=IV^dQR1!km*H zM5e58cOj|%EO?WE*93to3)P+KNo6dMsB%@34qidwzzP3+<>gp8X{-SpX1vV&eb%)E zLvFhh^_=jnjw5J~yi-yUL&Y{l2rlHY66Lyv!NC4>*UR*H$;J66b!XUV#^fMt5(*`Z z4TnHSn2d;kh6Nv*98P(*z(e=6OoxnARiC%tc{>gqNMk`}S^0HSTPp#>|M8{lx~;vR z`#x?7e7yu*;L)T^B*4dw8)x=51s?((cF{2lI_z3P%}*bDKf#BL$b7UG_mbVXVgA1m zNfc5jRp8po#?jWEwjPpqDd5rEIvsS_Z3{kR^d`nbLd#jC*`_g>M&aBi;WlvKz}**s zu#c^XeTfTiI}iQ>s-W_zcnW9Z_A?%2$#C?ylYOwtXW6o4C@LyK7V9UQz)?x{<EO>H z29^@t#(<FEBa<_BHoUzOpI?3v)jf=hz;dN&CqjJ(W8Yb~pf2o1gO>~y-D9JP5bZc* zu%~zj1RcgEgZ4ILChl198rFR!Lp&db^v^^8?g4r@*0CN~7mTG4spm|xoChP^ph@8z z#v?+|!O9|lB=8`}&?Ik;YDMAH6}KafmtT2_28h(XE6*wyH?^%2FzuZGjE%@nHu|<z zBJSJlB_-ejk0upu1^2{>6Ag<XppkCxp>2T<yGW>6;33w-fDf+Cwye!**O8>}|Lplo zIU6YhQZabXe_u2f*__xZKy{3m4-bWl&bRD`))tId(2>4YmMsX;dK&<7fQV&7H1+%b z`|odNRMq`<mn496#_vx-vJ(TZk(>#T2J&!*(2TlV%oX^Mj3o&8rexoH{rdH&uC6xj zuquDmhbHth6ZYx7=~bX9>N99m5@mFzKwUk`{^uGrtXPZ!sxP7x{t+UQ<d_ptbjft8 z$8u25IaRDmW!pMJZxyl@A=+Wc6_)lFf1sNz@r!{4Qzv!fu^^2{2`&gwq*93()r#FF zXyJb4TXm%SYAvS2Feo}kmCcDiJqgn<oo<Ri_1;_xZQg|7r=<vez7dh~uNcC+mL8N0 z3?-YSPMwk2xeGEnburso`*(X5thu*z_qiqDmOxu90T+0*P^%IUQoBfyX|XmRR`p_m zhh00PYRBEyf)9D3`TR6WrSOY$2HUw0tU_ftpVN5v$It^f^%VDu{ZN!s3py;|X!<)H zcvxX%!H0bX2{9{-wYH$d2tdA%TyT{)?bo7b{1}POra1Gu6X7Y~921<u)0^jEi0J?> z8g~T_Ejogr!`Re+Eo=6D^`3es#okbTSm39!vrCfta>5z&JHdcR8AKe(^`GFapHD$| zx;QH|L71%3mvIjcy#5wM4<1BAKkXxH6p^c?<Dp_fM})4gF{)IgCfQO=gVaohLFd%t zk1zR@zvDQ0%svQHHKK{$8VE{c6skN%WkkxdceWiyN_AuJYiv4rT=!Laimu)5+A}ss z6TBf{QU0$NP`-3ADp##U<f|=TE1w<h@UfgSI~SupV^VY&IU0o{M;UOkqift_ZKDL# z)@*;$Hr~j6i#@#rT;S0{4O$^LX3QAFMo74c{jk78b_3RSK;Xj)Kf5;IgN#Q&?1ut~ z1#$^Oym;-MQj8ulkTcx+@aEee;)vn>Q*4I=K3ZZvBv6}z4+}ujUqSh{;KOd)(Y4N# z8*cC3y%|KPixJA{*Zxr3QAS!!(yrozuinKUAHEtn`vh?5vDac?)?gwvf&#g_XfBi{ z(pMflAAb0uqe@|2sH{}p7Hp_IESORtOU>8iZ-}DohHDU7@(jaWGwLYMiE*hQ)zbg| zhY`$fXF{9%Idg11RVZ<}#&VI%aw9mPS|mcIBc8~_@Bi`y>XIE$fUP+Hrw5Q3A$t)d zaEONytfBEJ)g)$a6@d-{3WYlt@Q}@hLPFTO(7i3_5Zj^IW?x?RFRE1ty3&jc>({Nt zhP&sY?8!$FZ>Vp*Dq<Pr_UeNUhmUrE$ncTy<?imbL9O@td()lN5A^BN2c@N@=C$oN zvNx51`>wlJ3An)H8|p(J?U6?w+2}@V0f$`+bO?}009pW|Z7USDwu=O$*`|TVeTzQ8 z#;raS<yGS1bH@>&h=HJ>Bv`Sd6P@4OcDjIVt`pI53p(uDf)UGvNZ4tV-Lq#;?6c24 zKPUrYAO+PEVGo&)Ig?S)JsXn-orRN2PBXP(^DOm=mb$t+!#L?(Rn|?*MHlIv?V{fq zH4S)u{BU$9wINoCa150MG`VM8fDUJ!#_&z~#_mEk6pr9;s`}u5y2{G6wIPyZnDbHw z11slUeDuHJEXO0eqH{aO;z+R>a*wU23deDOB~USp2LT6dH&o`9jWU2ErCN!S8A%Y0 z^y$}!Mx=jjG<sG3W3@H-<j>b*)4~Vnvg_FJX#e+>JZz`=2M<A~V~#`DpPq(5hobN6 zQ9syy)sB`fT?!2zn)^<a5!H=C<rfzhn|!r&-uInpwGTa8ZMZelj2ScVzyl93is~1p z4erdnRgPMkmW}qQKU14lvi**}PnD~i+!AQ11YF?JQpu$4*9Ug=(MOvP&jJj~erRo( zk8}Vc#zTt*Ar^dSEyL58uYh5+my_1l?;8C6vauA9^oXI|hdyvCTy?%aX!|?;n6jv2 zw!><v)3P0h1s(RcIt+DqTC`6dAOay`b!;c1XXu!op|w&=&oKwT%|98&ip?McamFpj zBe!QJ_Uk?Xm-qW`eDcXBjUZ0%ZkVG~87L3wOL{)+wtcrOszo-BJyf~H#&+#7Y~I7D z&Cg`0XsViMzY%6YFdrj}${kkkZ_7d;L`y76wFzgA4U>uZ!<;t|CIjOOd(fwA5~GH7 zqU{FlH)J?!fd_v#(1=ukL)Qz4DC%rF%VD1r;qegdZxplRz6b6>_mX`Hjkej~RIGRz z@6Wgl;Vos~rZijq94~=$=W!F!?Tm9!Fm%s~kgGPXHnL{T8Vnvh*wlr-oo`Afo_L}O zEGGeN+tN2((;COsCY0ZK^XB2T*IqO0*0^ued#DWbtQ{r$ecSI{=js{-+Y?i&a#3Dw z(s^CGb~TeKs_)bBx88coEYqe<v!}Uhw*<ac0{;g90RR8LA7h>X06+jqL_t*TT?c>^ zMb>^3HfM5@Btaz^Frpx$0)|t}5ea7i0Z&iGQxp{gdZHi(1Q8TWC}zbw{SA16fuJY~ zNRlLJ*_<ZT|Gt{7p=Wkxb7J=u^j3A{`nsp;>sPO;Y>EwuDHQ>q&!@xt_wP@!v9aWI zIw>Y5MqhDpaoP{I@q-;59j))9qM`^F(pazfm^dm_4*K^?-;=V(k%JUX8aI&Q9R*~! z+jU&n4u?bE8ykLBf1Ayw?_rw@;h_d$=24?PaN~j-7s5RrkG|k8EG*RihaGkpB_$<M ze0+Q$9>ObQP@b-bmuT<aZIt)xXLRQmPm{fKJf(GLPWSbAKF~JALpxxj?XYpdSlzfc z?J{kGZTHzId&!5?Y+!%NcEpf}AEEMkh`ercdlg?^zTD*Vcy*iIZuaNPVDMLlof4yq z$mc4g7v5e$K3f!BdU_9Xdv;S{zK05ZIpi+zQc+P6xm+%C6}hM&zaWr@*XtuMm!Y^U z<cYj-uj8^iB{`YidH)@9M)})@cEId>a{;Y?;2u&w2B{vHgf88v?G@Kj>kBR+XHs%K zs8QKfShHpg9ewoCfp^)wH>IV-vst`&F<o)R75Y6dEpBy&p<MJ8-+lKT9eeDtfp@+- z%RpZE4WX>k4Bk`J1;0DEVPNC_gcDAnUcGwJym|8iS>SiJfB$~!-Mcq!-@aY{F3~^Y zHxaH63M3RqqesBTFOLw9a=r%m5e^zONDspJ5ra_RhX&GN2ng;C0l|+Lmz8{kBO%k~ zE~NrnONyZkdf=8J<gjzzb|(>EcDsWdP98|vZ6zPZZ3bmCNE_P>&Y_*I@i&j%N<shw z{BapVVr=7w0Tk}k)KuM(A>5kIlxOOZlar&vQBPn2^5t+cdD^mqV)A#;!>c}|ztVCj z<*-zGxZ@;>YkLg$l1wge+3W#QVe&<0#%=0qY=oKmhO_a^@C<Rm?PE4l<Z+Rw2;_iC zh}T8?vK38x<^RY_sdPkJJDu6LITI8gx!g=J3JdshGkGZD&ee60bnv~)<))&7BJwgG z$Xj2!91t2m;cyqZ`H?zl>ePqmgp*F>=ZhK#o2*qo((2Jyk+&c}IG~R29C7i~@|?dh z2^mhwz53K~Z6X(s=Z<$QBO`-SQc@yEj1YqNdj9<RbioA|1m3d<QLE%_eoy#KtXsE^ z4nO?x3JumskKYvRP=h`O1lMX17w=?g2H`7Kte~TgI!b?RgvLc4ciwp?O_?%9V{FPs ze+ROG^xeC6r;Qso)+lzN^^*HT4*?+_6?kU&q2YS)!3XJ^Z@$q#E_59D;aLd?NQm)= zjSHP2Y(qluBZeC`!Zz)*QP(ysS%~)0pSudFUHeuPOL^psiSm;VyZ_4{1G@D>dUFrA zAr@xf$35IICd@S1dT-i>Fw>#HMjRL`!GPNuX5#CJ{3o<*gqynQ`VtTR%NKA=FMWDo zGrhNe1toP#peb?ZQPX2CC5mfCUR|!gQ#Ex!{>aOeXKZwMa9hcSxkniM4dF1P1GbiO zXu{#6440FheEth6Qc+~{@$<4}&^ZIUQnUDcaxtNBalFDJPE+V79BwyDIk<BN0Ra*5 zFuB0xV@U<dH02d>JU7Sja(SIPccOW(%x6sbS@83WWYYil6|EUFl6;)DqQ=JWR3b|$ z;yQGq*jBA6Dy=EmnGD;VQRL3dAXoZ6zV?%gzf_IelapPcVp98_NL~JUH>DiYw?gSE z8yU~iyaRZaa2wm?Y2NV}GiK0jx7|hs1qJ%|X2MM#k!%wWU+^tjw9wDb<Y~gJw#mop zR}nYTFIcdEMvfe*-^0+d5RMD}Xe(@Mnbz>oa;@=982T8zlcgDhsmU8STk8dX<b&Uh zwLWK^br#K;Ge;Aa{QUeteM>7#!WuUMLOd$*{P6>Q<Bd1;j}1RS5D1WpQ1StPtMtRf zgN+~X!HcJ3m^3&zFOM^Yo}9;`eN{*|UO9l;xA1Woi$7TcU`U3sQMS3l`5_FQhxM}h zq3H;-8WY#}p|c4!#xGo26E`#;a}PV7@@e1FH^^Ztq)ncDdVJkSl-Mzj?rbucS`;Ny z+`!>HRT9OMPX|d5@-^ie8_yxqg~8u?As+70X`%xLY0%_=@AEt{^zS*VnFbZ{Gw{)n ze(k7bGD}19d7v(qR_ORHe>zP#FulT;n<X8{M{)ihmY{%O=rT|i%5Y&y$3-74`G``} zQn<bzCLJuzViSzK_6q#j`=5{L*W1SMR88q$sYsC6?Fedq<`8On+8LD8qZirvU95=l z=H*i6>J^l^;(N;c@jJ@?<tLtEDx35)JL7EXa_e1`(6xI-imPy3JU58>*RNksJ$v@l zU**l4H>d3EZ2kV?IpF<=fjxZqaC+&bmxA7HJpa7BJZjpsDRu4Im45&Icl|z@cga)= z_xLTBHeG<{i{EbO`)~3vHsay89?qZ~<nh*9Z_%(}!%F0ZaHMbBwk;hva6pG+x-&O7 zSHExg9hcXj?WhOx3zrVzvu4erTW`HpWAoc@zfr4Jt>~wpe$ph&l!JJv^L_W-NB7@< zzwy?;LF5nY@hrp$0%ai}#G@>PN(tY)cQ0Le<&`=Hevs&}aG`@RQV>HtU?U7aP+TT1 zeym7qE{8LQ-uPr4ZQaLTcARr^oSW{t{w(fzayeZr&q6TSaN<jZi3+DhM`E?n8Jc^9 znaeux!wrAaaazMnb4?iTjoaAPI95Na+r+WjCOjs42c@t6kZj6MMLdl(?#EXtv2zTK zXmuL(DPU<w@?n(N=Wkpv59q81qnHvXpPvAsL&k-{2pyr-jeA2j;Kl_~;PvoSijN5b zlLQwN0iU;svOP)k@8{m9+eV$pl7#|#`lZ!$$|>EcV{?|qU>e0;7??`Y<e^x?;m?Cf z2Y2FbCL*RBl#5PRlNl}pZe{aP^VZGi_19n5&%}yFdEC1ezd^rGx*d$GM06WJzn14* zK!*(<P077^da4?YkHzL$YgRD{VIs2PJIY-71HmtxvGIG@>Vk`@^Z0*KY@2rBqEy+> zJo9(oeV4Ai_FAof1iXPY$i9_$;JseCawQ#eOfV+M1HTKTGw&gOa~O=xy{Rbj!1PDA zZrzMmkPQNK<dH`P`GvcgIB_C9`skzKg7kZf`k;K+p$6|2>bH9JYU<OckFGcR4D-H+ z);To2xd%Z5aX~s5^h1zJnDoG7#E22}+H0=`us~eIgVYFhuo_4=zWCw`T_59*JRs$T zo=3};EseL>f<QzBgm^@Rrt|>(IC0?z+^=6h{li0tWypom`M?j@s`r6=Lq3dcNC)g_ zhm)e54$AN~r8#f>pvzFKC^_<iBdL3*WF`zuQn;gn4uq9pl;%bq4bd<*{H*@w-f9~J z;0I&uP=6C<!VNAaUZ|b(+cL84`<aP{lYC4(Ze0Ef#dnIKzRB%rM9c{+?O~}%zw5|l zk0B>dad^0Vbi@X8GuXpMr-#exHh!9PaG2XyNXq4-La&py@6V@~URy<OZj#L#O+)&p zQRik3$}h;(9k0jDileOe;VNM1h9(z&sfM0f;d>Ad3>H4EJnAPmC=X?sX%{b-<zjO4 z>1RtQE<R3o-UgdcEXumyHh(t#G4+9<XlW;&Lft1lRO6BcQ>Z69i*|qfKK=FHTa^9t zD&rkw+oNNs-Ic?s<4qHIdZ$THSXFQEZ1LVEvqCPu_@VfW_Z^txH-m6v5O2?(J%j<* zYVeHkdxM1G;)^fVLGTM5^pO|hfiyhw$RpM)0&epjqO7VI)E)0lxZexN#xKA8qTg*( z9{P^Kg9p=xAAYFuC~w(lC+cd-fo<xJ_M#rZ75x+p;-eo!Sm=BE-h1!SC6`>H>ut(6 z@vQlpFtG)Ja0m$T2!~1q{m^+_ef8D6Qe&_FL8Ifs4;LMUAs+Zq<AT2l!w=q&57@YO zI-^<n5(I=vO;jSi`pIv!Yfm0cyzvZ5i7%uAZ!E92U?Rbtt|1$tHaZpK2RANsAjWOI zhkscY;4tZ}(7?|atK0aYBeEKEpRww5ip|@?5*-Ke5KW_(zCsCyCs2nbX>@1oAo4lb zH@*|a^*EEi_E};9lE)Gcq{oGh5uF|ENEgU~As#kPyLibjv|<B`<{h!TLWSqLSt4=S zc|9n>$%LaYmsh2*aww)!Sc%kARLH@8f`NSSMU8vphgC3K3xBzoTH!kQ%kuJoSfJ}S zV$=w_Zsc(72G&(Io1cDywmkO~*`uPV>s^zn-Bs7&fmAiyN~O=+ypjHT_buA}!D1@f z^H+&H9EnNPVbo33e#G_Uh)*aHUKI~ui9zqpH{aCn<EmAw=(yvK3mPEt-a}6#EiEmm zC_JNIfBjXj&cJlb&Ye3;kPedod0c<}^?Lfj_*J(JCC=lIKVH8hp?RaOkeW`OJeej< znxuo_hrR?h>Q`L`(<?J)&eZR?c~{%DYp3zSyKVeTc}tcop>xkYx7zDr@)x^tARxq} z8lUsoXP>Qqz~~roflL_kVF-xz-VhW+KCDE<!IBRwwREylAX5X1iizc~ZAFhSSV6HY z{k&_;P}cp(=c$-v)*&ch-2^5qEC#VLVL{pGFwBK}LoSS;v911a!{7M9hB5cXtv!qV z!?}$gY(qATAMP{PE~S*r^*n*XZBt&lbJ<&z*VacVZQ^N4^o6{<*h@~3isP>$k2jv< z<oTDwa#}+;j18R%9{-t0ux<rUr?`D~R_4s3)r;Sy7D)*d)#*rbHc6xdt|Xehcojvv zGwGtiJt*0kO@%DoaPwuB#JZt8T0EtK4&E>EV8X#}biyc8aamTfgLp{if)c6EMPGdR ze-slNW13rS_NM8NQPWdTCn$E-2Lqj!1Iw0b60(maJ3dyhwVId~t*HC`k5Y5i1E~%J z@`v9Jo&gNrNld3e55fA5;r;#LhaYqp-uqAky%4NiF$C87ZX+(<1$-c2x(3Tz!x`v6 zK<C8NC0rc%-Fxr7S`j^5`0m}isZE<UdH^@SITH`>7y1IU8GQo`h*JCZ?REVSR$T@k zL3oFO2QIV;(pnIb#~ypEL@|bVl-2eU3B^MYupl7B!vaQiI5Gb_dh}>5)j+3aBpgP{ zfldt_XsACr7<4G`Hv|N>ArY}0{_`LE>A&Ca<BqW@lMQ^C@25v64kNp_kXY4?d{Hbx z;SX$+#*hnRqdq1KZmYlPfK4X|8^-usZG#j1!WsBm2Lr@0_pl4MuBL=Nt9c5AmkYB{ zWX>PU=m+m+O6|ZaTat!Rw3pM{c%X05n+lpA&Z-_ZZtuaBD~1GUF}0iZH&}VI2>V_@ zw}Pi>zW8wm{ru{S)GU1~wT`k;v$QyhI<had95|SARSp&K$`p@}@nb1QVX<TbojjJi z1`!S>HM%U8a`>2WnCTTGNrA122Y1|P^OsA%(9)1_170|s8j4@hp5654+~;WLqF2es z(;!yU^4tq~T4+j@r(Zw_u%8T`6W$^7K0f{Q(=>kk_&|}s{^5ro*2_N4JB&1lkKY&u zOgz)X#6&%a2ND)L@J#U=#d2Jf7tSD#$va%Q@k3dqkpzU9x}knngL|ZhjrN*%s=Q@e z^D51a{>Hq=C<D@u2@@u0Y!DV|Ac2`Wb*f+b$Mq`@4xxF-y&xdOqnh6V{D|=bKIN2C zG{Jz|5DEN{tr8F1TQ4K|u-ZtAOHaS>K<#nF(Jx!F>8q7IRpE+e2?tN>c(>5~|G1D@ z0uS&!eS!4o5KuPk&<mXz!eAo|wz)#@jlb14kipLws~diXXqa%TpCfB4IW{gOFDoY6 zS;2H!)=qkH+ZUAFK8_x0HH;GTd4S+47&mX)mEU<NdAQ^C@aA9Wh|R!(!2=hJi|qp5 z_u}#AKc`eyB#qj(mXgwUQieB!PHobZlB0PZou^l9tb34s?j?RnMiJ{}fOL5L8-Q5} z2L=P=jW%F;tdH|Vxp=nbGK2&19(?ElI(^_kUU}rlQCF%F{&DT!#{}eg+WE$UpnXW9 z_!)qFKpD0&2G~FFzyn%Q(-05%;dc@Go?UwBrFtVUgj)^XPdqF0p5i@699;M<7=!#k zJfMJS^*7<wY2$Z_a?lP_FXWFpp<jS9?fK`Quft}~o=tb%br<d1w@?3OtE(PZHG?T) ztoXsZ4IK_B@P;l&MtQ&nb;YKFTeohlt|~}AjSvAL9yR#Tu}**P+_`~)A03UAXc%{> z1O)N$1BV@O^OTE&B^ppHMVQmh5|GWgv~=Zm8aHYHC3rGv^Ij+I=RFzv^=`xE@E0Dw zzj^THSsT^~!TuVY4$~XFD#pgsGIr>Z6q61^IE-!lLv6ri?Iexc*d{!*<A*;wF5R(v z^T_`DCz>QVc&a7c>7_e<c!Od)M$?^b&Y`yMc#em!EuNNXb0RBy#<3)Wr5emL>@0nV zVlj!^Wus+3Z=;nT|Ci2a?xx&Lzti?z85FG>>Y`+xBhO*ojt=p$)Qop1rIb|KeAY1D zFf5NZFU6{pA|@S7K3H0zr&QSX@^p>fNK6k%{s91;F$OGs>8Tk`!&5rAZ_=y@z4!jR zn((20V*CiW4y4nzc`wk8*Ip(p)itL1puyCA@}m^fqT(wb@Lo1)(nRZTAU_a4ObLL9 zAj}xNUmy%tl7To-HiZHu!Vy1QI^@x%OBWi*Bog~lSl?-re|6gU{bN-eb^}G7Or7C= z@x>Qu?AWooEg&b5zT9}@jr7D5PgG02%x@7k`WP5UYq8WA<%j$IqJF6JAAkHoojZ4~ zPADX=Muvb8j~aa7_@QFp8Zu;vE(JemO&XXu;0KH!ydfX3jWooBnYdO0qWxIP;pE*v z(P_lSCNZ(#eFdTuXxfXvutbEV1?(TK4$v*v52I98NM)X(I}-;F$~ImxgZ)BK7j&$~ zhP$+TG{D4xZSJ+BILx?FFJnU8xVQ82)r75|k&{14`8$+yxlXq%f0bfd+UeYOeds)U zcb0ZA@vs+BMobsVifPSc!A*Pj71E-Y-y+A}eUzNBm7-XeBc8{c)=iRm!!g!#@i4AD zMU%)1y57Vz+MT|a(zx-dtmL@<jB_Yo74TF54_eqZo%6%9fsTi9W6un9xVXI7>YVSj z4vCKE*YyCl7?>tMI9W?L&>n+_X|vdV1h8S*wwLG7j)gCgr+5cjXL5>GkZp6(<rRX- zyhp$q?)&e*pB{SXA^i-k_~Y5Z9}*HnF05%yq1H6;!*4Y!D@!j2MLOhDlM)Y<hu<E` zKv^(&AJfy*^&T3STEcJL)Dv#_A-?g`i7NRAm>{oRyLRclI!vC>I{^+LJD~>3yx2M& zVd$g82m+NwK!`_Wk*h#D{K#*={dW5K=bv>4haWsT5<@5q(ZD^#yw-cTHQBJlk6|~q z-nQ`o>(reWlNcr+zUa2}@|#O3#~sU^Gk>+P1UZH^FK@f4A0<Q;@y1p0OhULrvGI~# zCN9`L6CDmZKy%@~v<uBPos_YyesG(PKAan!terQ}YO?cdieWtq9=557MKWV}WsAM3 zlX|!5NMn<a<N74i?!qWq{LxzK<Z#i>-+rb&JNEEyt~^L!`*_YHm3MV*o)k~XQ9LaY z9Z&Y|J;>L!Go|yg**xyp_pM$<t#<6By=M&MeL1+@MGmbG0^)&XvmhK80Q7VU*9$rv zsGpW{Fm4`5M0h!`AtoN4cKPPpuhFc)SE9a=KcynzW(ml~X^+sZcizOyq2o3=^>jM& z!N)4K_XplD{8sw*?Mus+Ez|F=wE}pCSayp2Ch#m_tnaEdE}lQ~!_rl(GQqQs6xW)r zy4=@Xa}9m_?YFdP(<YrIe($fo`YK(1xu2M!J|jkqpts+CJFHGhW$S@$%^}?|1PJ*U z#afh!KF1i~15Ds&riRd8h!F%Ti+~W1$|6_6bohbeO9E#=n6DPthFF9n8}PIG8=~T1 z!V%3YUZNcMV!{**OHz1B1yd+?kea9%+M69qi$7VV`}u#4Izdm-JTiMZchWZM*)fSu z@86f2r!e_&uuclM#m-YV4u_wFU~Iq!WxSk3$7d?SQ#BkHG=aTAYT&00TNp~PycZ6{ z;k6&y4V$yzzmU%G0Kkf$ERN9<nU)8>rvx8MAV83~6C3x<LOOuFdC5+T_tGdeeK)13 zB0j?=nmVNVD26xV%FA<6LJXf763cCkOQbmNI6W-#-4mC<Qz&khXz&>-T#OehOjuFW z$K(Q2DmWajfE8A4{3Tn6X%e1lF$0b!8(MLc2?!Gp3{;wUup0-zfqY=+(J#OHiudG* z;j>sc9{+PPSqfm_M?(IVfk4(zEBOGtyD8`QUv*4JLLwb8`4MXMH~+pGWh4&@#%~9M zXNL|Q_#F)%1kFGR8>>%1_z^#nK|WX=bJ0Z?X%bRe+(>y;)*p4mN6Ax9Jw-UzX!`W& zdS_7VtlF$uGp+22vr!Czs%$x-=}<0+1j>anDGt`dDxuFm|6EJ-Onk)q?|=VGLx&F4 z5+q;)zfjCge6a<A@*p6@qdX{8QydI-FwZ^r94%V3NOy+#0b3;+hKLwHEBUaJ5Oe?_ zB8UffsI5B)e5LTlPEo8!;f+qCSqoPZZ{o}YCX_y)!@wIcvE<;sG5uMBQbfBm?bNDi zDw72l6B!o8^7i3gCL>NJ49dZxVNUC(5eGYZrW7oJ;31gfIQU{-0otMCVZRH-n}qSU zmvHfh<Z-Mh>Z8ruGU%^On`znVEj*Rsq?g8YqDQ`6KwtghqukxC>B7AmDcP3Jx*T@u zoD@s(vAkt`LJAX&9^^fu8)fkhu31a~+$^E?v2rLnWqhSUL~h(57usD+Bp~7NG6BKY zu>ay3X(<QSpKU#*!p{dfAIQtcZa1fWV9JAZ=GkZH7S-mLur9Cx{=szC&Np76O*0-R z4=-(nX?Nvy)b;NB^*$x#Z88QwV<J5lybt(Ylr~5rpZYM6n)cw`!|xhxLVsb}2HUtz zyQ^a3H((6PHhG6)h5DGX5oY3<v|<Yal|ev=M`ci}hBW9@`uFc2ARmT27{Y<h$M_jZ zhan+`oFF`ue3<k)Ew)u>iGhukH*v3cszvdtm|wSK(N90Gr#x2-55D;{arB8y9HMFJ z%fB*l;3KVhjt1MA+jyT4hc}1r9mm_3+g-F~Lms8^o*1z_#o^Er5u$|nB#Nfp`aGE} zyS<d1Q%E^^1+-<`cG|Hsg9><w>s{k`&k;U*=E0duc?m5aTE=Iz_?VE`L2S6ZnZpmG zRcn8uC+1~PqN6Q!vhSh^ZGWXUJv&pYV~?UQ3*u?FCtjZ>n~&|&K`?k3t(%DimeK~3 z4gd5A@P+;crb^&8ghLfir+{q0&&yLPuuUEqtk4k;ziv3)IQ9ljqKaiZ)$r6M3xfa- zs@wSQhv={O-)5$&^tSK4X3VD8)@@7_u>}D^pn)PF#G{TLtoh==yegCxp;(Hq2}3rF z1j7&zLo$ri1L1~r7~7BzlNOth@d{j)Z^V-$n)fo``zXcb@HXX|IM`$L)JY8Q6zZcS zn)S|4R8$Dr1TRzM2^dV9u&zDbIjR?zWur%)UrS!rr@&U{7@W;l+TAxCt*3n+p0$j3 z1?8PVF`dFE&^i?p9ai?dePnNnVS@1V>pxL}+d-{cCQx@?I(ucGSV~jbJk`SI(D>r$ z+R5Kg29pe%YDvA@X46Brc4FdWqZK=O1y3eRZ6LMaFEB53G<aKcFX!pvJwE&-gQXP3 zdKqqz4W1&g5)R<4SlR;O0e`=g191*cub@5H3G=DxPclJcT@=hKiK$Tpa1PA+2k)lb z^}p-AK6*}jmYST>zedZH%mo2Kpl%Tm;!(Hw>(Vh0zWnmb`ZCoq<iXg6fS7v_5hM9P zSSa~Gcxe~Jrq)Z79*9!;;y*gAn@NhD&r69`SxhKmXxUG@Xn$57E10ncJ`(_FbmZn` z(zxOM_^Z`J?|;6I;uDf7DLH|fq$X0+X1q;2PS*9M>y5&AYcnPU*b}3W35}Ebw<)9q zca~QDz#rD+plk2_nsN&hSuwU5o!p)1?%^G14@+tm|FDI38fDo7_T6COp~(Xz8B8|d zhQtE;7y<uciH0T|ELGO0$AWO+;&_4M>zT}eaEu;3ny&l%a1kY&7qAv>=-~W0`&ruj z?2}ptsPlw>QpX!7@arYArdoUqQj{Q2YX}JOs5PidF9?Gl2FWweJTo9oz&*$X2m}ZR zE|3M>8yjvzJi?I=LsSso>b8=OgKnNt;g5Xm0Ahov1Urke<if^Z|28HeI44%IpR)T` z3ZO-H)*k_(fbp?j2xKSPVE0jk=|LZ|6aN6Ol{0xN$Eo#8SlPB~ypGPigUeuE!Q|u8 ziC^$u8GK5uEtNVokEZl2J~WSuIPoN&|MujQn{`ltjepfi@$RA)qJc0do4|%%2Xl?U z24o;i&<=nO2X-T!Gj}!}al{e+I?Fic$Dxk?X0KUIzurEM3bt*fW&_Wn9*@l+EWZ^a z2nYfV3jrY>_2hY)X$#o+ddFD_ST_$c0b|GqY%B4w5)c!|kQ8GZ|IoCMa+vhmjj0)I zEXK;Bdff_d)CHnp$Jr^Y^TG2oe2<kX2NnAW(=J%?0zaNsfu%_lOF$H#n}U5haPQUk zm=<9&pdhhe#aLE49d%qH*;rB3|8dJ?fy;DxQs}a~zF>mUmY1j`Fky<P&FMwFvc*Mb zo|UfkPz>=v-nu*{8JJ2z{s@B-qmh1KPY$^KM8vC?4Pt|+-beS+?Ewa2>IVW|-a&Ky zLzDOnm_-zKSO@C$^c+e$vPb=>oYX=P5Cp0P0U;jM0%P@Nf`JqU1LdcmeyYz#fE&h; z2@IBS8{%MWqbFj*4e3B!;|>=We&#|RkuF_{QvO)$evlCO+k<;U0MH&>rydqf$9HbV zx*V*70&>G566lxAd?$lGS-yu?*Tk_;Q`)wVB{1yYf4~MNMfsX+nEcH-Dv+)ivVpuo z;1DM_mp2;Y<LNUqGilY&D_N=|M5B~PSTBP1EcuYuO`fO^pF86Isnq(yOY23wq!NOF zAW(G#gm_dP!y3y0gC+<743^*GKr9TXAP@*ML;|+CKpqVFFyz4y4M<NA&kzi&+r%;H zO<JpsdYF5-VNegN!F{+3^@cIT199Nz=JQgfUVMbsyI{eIHcB~Y%+z0Kdlr)+A0H6s zi>GaSnzHIiDxK1Q6))S(*J+VnFNtMaPn~cPeq9fqUO{<W2I~9tvoomA(MPlNg}wAd zi@zQI(&TS_MWFDnowWAOTPX9#@2K;H+o{vof7I8iO1%UDL7)N%2=S-@Salgy53)Rv z;;a4av(MINH(-#3!Qg6$hp`QTFeJke26J!haOA_}Y0`w+hHSv!82I7dgu#w<p)KaZ zq|SgY$#mXv9hen>oIv7XrzI<*Xx5?v*7@M&vb@xH%U}6)SnD|I(s?x#kpi7JNDPPv zF1<XKr&J71J$fC*$9g}`impkllfp_KtVDw9qC7E&4gz?#f6igW)0xw#?PXU{w@DBA z6`&8DCP+;M0YM-H0U;hCfE+5f7}Rlk<&#f7sW-fWGy{I&h=d^_2!k>Ap@hPakx+l! zTho+<k(F>DF78?LG(bcQIe<UbvVb(q{QK$T^z!~5dWTf(avDQZ7ev#yzx3jR@0^s< zVi`4S@gG(r;hj!-B@5CbA570+ss)mh0(TzGm@$J+I{9QizeWf~S<mTErM*=^9MQ4` ziVSXpYtZ2C?(XhRLeSvu7A(O%xVt1c!GcQy!Gn8n8Qgh2=bm@p{eS%M)3bYPb=6vH zSD{XtUE)5wjbHoqB#^)6DSE9DsehrQL?-(ROsfDWKbzbo3q1rZaR~c3tF1n_)4N0_ zO@v<9kc<=Y(*OnG>DMO?T>4pcTof6LcX8XdkXK&UFDDD@40Ke3*v(uFXo6&&aqTlH z%9CG&Gh#p~sB{#GfdaaC_!nl?+xbtK-+gJn<fiF%sR$J0puThI)m*dd+-9N+<Vb@H zrl%00FSDfDSn5fb|3a$jwRTx{+sK~8%~@&5t6@Zg%mZNbK0Jv?9}#_Wkiv@_#qW1; z104mT5z5|Lpu=*$?_UWQArhD7s)^`3Z0WOpstwv)smKQCrnO+su8mjn`2$LG@@u<n zl~yy4WOMuei2i>0K70sM_7S<+zzl5#ji!?t_Vw{<cwX>}FP*4Y>_2zo0UmNtK)}sJ z$0MEAM92DmrXU()hwta186Ue!%0Cid@Ya+B`TMpH8{@&dV`&}$gKUojR|JC-hR=rF zzd@lS=7JU8Hm`i7u%SY565PO(GX>Y95#DKuK6?Jc70Yl)GWggHRS+Tl=aP^At=Y$- z{nMk!1_CBLg_uZn-*B!j%&%hGjE4ZJS}-Amdp~1~edm69*>w5)lgHKZC%pA<+QoyC zBy7lJvC!4S%Qq4{LU)4=|GAzBe~k6rdYoXX-QC8*&dJt`t}g#Qk(H$a(z0J*v^c(6 zDev3<5^igf<%n$m;IS>gZ}E{R-i@b`;rvJrYa($UdN^{wwm41-XAXT6VmJzD*y&HC zOEEhhitBx;7c0j|P$|n(7n2_qedKZCD7g;nrHTN8GwFRxU430i1<J*cAml4C4%Wt? zXTL6M;fXIlKM5eiGlncXvLH$#dJ*x`eQA(RA?xXd*JgUjEK^yL9hT7!BB!_=n$D=M z>(HVY#|S2MmiX6vN%x`V(y|p_z3{IO0=hPqCO(3cl@#{Ka$Bgka938x8fVPcD^f5C z%PrKjVL|;3EDEK-Dridn5|psY8Sxhg7Aqs?ZRw(c>$?(S0GcVAot>R7B8&>Hv^Yex zFVb675=>S~m5T`x=9W%L@X|Mv|BZy<luD#fj1Ve~0-W2Z>6xnH4w4ItG^5mVrb0-q zHs`J)yDKR4g1W%KuhsGpe)j2#yK=OW`ksN^2}d1Vfd*{US%gEaGT>m%BEuQy`NvMH z348)%4+b>%%4Pr83Qufq%!UV}_TdqZu19=kMdnchwXo;NGX};N?wH9hFvDEj!E`P* z+RUuKzIb<Cx_s2f+!K>*MH8m@j14-(0lMcI6J%)Z;1rt1DAzo#&Ua=06w271Ja=Y} z6nx~+RfUUM?C9VXT07B6TYo5RaT|4}VRc)~@NF48ZQ`mo6yA@~&lb_=CMG6kwp^W} zV<%a;!t-dpP&4fG^78VaeJ`(gm?GGO*@NA*Bh~Nbm>92|&*`*%j~tq1d>=^aTneOd zhjR1w#RiPhV1`g&8{j0)(qoAq^!nm!G|on~UhK!OiUxYEjcP*-X*+*4b-Q5g4wji~ z;#u$cW#g_N;^tr<!f^p0oB1E0Xv5XbC3caW^T41OgHvnptxn@kTN4kC9zXK&>%*&0 zLP9@dxAd@*Zb3zb0>v+%y<G3ZE1-U3>AQHrNOj?fQUJwCZ~3?^H#$0c^%IHWPY5i0 zUwUX`nwsD)UYETikVV}CkZx(F(5dzf)nZJ(KA#1H5L}PX;JJ7{{K{Nn&>I7T!mu~u zbyV81&k=@qR_lGFSxyLD?nMalH}>(n&~^@3b;8xo>WgyJu4lj4%#E|F=ns<zSFtUb z`^mc389kj_Kg`NIPv{TliB#BUEl3^$2}&yprK6bWaIMoPltZ$R9`N$xih<JT7hK!Q z5goFW?sExMF2grU`dbO&FCmob<|-U;_iZL@&l8l#BQy!<cgAm`-G_*6_M5Oo&O>-B z<W>VBLWH)WX=VXoZhv}8Zf<Rd=TVu@l5E%W&9dcobUCF)3bI9eai$w}?_LDMAbdhA zgK=))k|K*^v@Q}?BmQFrMo+yaWa?X$qEYPF3{7La=|m2V?DqC#r|g)Wx+WXCkF38A z%eZj-sXJLdVur>?5WUtx($jq+AKP+qC;6o0#r9>DB5s}j6w1d`{@zULU5((Udo-P9 z=k;!rl71tH7n1omw?KC0+O@5^DCC`|Zaw^yzj~ElSq;Cxl@Pf(0r37|K&OF^JU%jl zjN1Quwo=<u;7G@%RrAfWWDIqmA2els#|i=(K?FwB-dA1+9TStB*tj@d|C{3&B6T=W z=vN6Kl9koig`L}Tt$bT9?I~tY31nVT@j16H9yU_1i`^wol4=znII9k4zK$Ap<2~9m zP7`f;=c>nmV7{v&r4kPt1*z~gCL9gk%GE^5t`L1TXizBl$E+!blBl%tIfY+wrlil~ z>AbZAG8ZLq-bym?)4H!uQTpa|wHkoK6Z3hy+Kvd}5J>qMZclUZ>t<6KwXZ1GN|iHk z?DBp85x<G_rlhB*XCOPnd~25&U1RW#nt^2nLw%hg??q!ggIz!Id!{#!$;$Lo&=W*{ zP>7*pMYmdyQS67J`5kM-SD+rkkx$JnHp$!DFo`&5<Oz2k_TlL=^7FU)w6Wb#B`jT$ zW;mos6RgMG)8(oQPl>r6mjD(afwR=SF@j}PW!)zPf)vaTv@eCzudQ&uEBtiWxPo8h z@*eDrOpt<&ug&9>=a$Xpl%%L#=M8P_DnUYS=$JLxg$9-!iM)s)FjnTDcybw#9RZt3 zg#otu59w0U=<rYkJLwrDRBZV!$=<=8{_O4^scXU8758iI?tfn$luCZwS)HQY-2;;M zP1?S-;Mc%6L!^6Y$c=u05KrwJW^_<bVn#cl*qf~}Y^>2#_N1W@D>Raomq)tb@ckJC zd_R>+UMGWJinpb<kiuByz!j`ecNO_S3V%C7%*MDUhvrx2+2sWu2utDa@RozIJ>aj# zX{KMLtr}s*O3t$YvPmh2`t^R0!0Wj&Q@*hJ;yv@HNn2g*JYPj+l>k|U72+hNf8zwX zy_Ra8zt@K^J(Tl=I!%qm1jW)F%tSUCo%)6;I;+&gw*#&h%PA`V-szZjFC6Jj_Hby^ zx^-j9H@W%xgm@5EHqH8oxroVG7rx|)T<=kcS61vZ=nmwn=djhsFm2Vi-#BeP3|85c ziPn+vMJ;_}m-f~O7QW=cANF1PI3?mDU#(o<8Gp&B^~ShWucd;=l)Y(cmr27o$oTiQ z`j+6{1XEIZ5o)GNAvrnbqXmRiBn}i4Zp^D5yZz+I#Mxf!2H&GZLIdQ(znbBlYEWW1 zr?us!B)DV3uqo*OiCQj%>}v&sa+2eUwdFRatDlyb88NQ?bVv@n@Ktv#+cz;FUAGvT zYyamxK&)fL#@Z2d(h$v>0|ki+I95!&7OjQ8;A<;K7>aW2(<A_TJlo1qKsQzIGZ%B? zzni8HUAVLL9`mk;!|JNw*B7A^Mf%*5v&|@GQPD0LKLyD2^t8tl0P<GJwD};z@qPk6 z3bB+&!XYz@x_jNh+d3j#QEw=kZ{Sl<@(&j-U9Lwj*8gI}M9aqsyn2XX@@e{Jf<pqy zrkG+zWsRE;)b)b4kLQD4v%W)kFx?4N8981sPZwsy=lW>B^OrMgtS&=f&J_A``G|vS zcVK(6@**S;ZsRC^-Zz*<XDfn-N1h$tWRMoedN}HINDR8zWK5`0JU)mR1~_Z08hKlK zcgM!6zF!`EKYXg*k8dbogPM~2K}fvmvH$+{ALeHiH5gFF;Y>Sz$`^tqEKl>sCz`qT zTf4C%rdf=OowN5(R=VU?E`p1Xd~S~?RqhL7$3Jo2-omo=*L@$GhwPB`kxFAqFnz)6 zOT_XxA1as`6h&4NfR_ptp)3NfZt;*`$da=fx1eJrKl*)<*vxp<?OxfaOmdl9ZLkav z>h>9erUp0q;Z^Gg)E=5UX<e@?=ROZw@mw&qRHUyDnX>Co!qFz6kT2Ngab8>TvGa#) z4FbimBnzKnNs51=J||xgf$^H00rGG+h7E99>?JoW)J<3ydCyfkh3~*VFMZGQcJ4(Y zTUJfC)(l7~(E(nK39kwK>OlRI+2Ejmn4d)H%?4#6mMT}IS}zWM`m*Cj*rrWR8PXNJ z=FOZjh|YzH{PLWt4D=0AXS+GCk`Wtctu&0XDphM8TWQo2^p)^-h1-wWIX0`m+}&J1 z`#C_9C!D>CY;zDknKHrbxvj$%X86#X6Z1wk2q!`yz_`g7UKzXv|Is&iGu*_Rj#!9o zA>)Lx71IW8Ae`f=tro%}yZD{CU)+U8xem?4;@I_sSLU=YP^G{sGuqX`Q%nrMKlgrk zy-v=to5@Ln@3i~TNtHx`$im{?Zm8}S>~u)zJAllyM3W?m2oKqC;LM3f+RD85(AN9= zYoIZRs&}&10&>LSIolH*?HN7*8}8PIrp?~-d}BP&1eKs3_{`KryK;zHU9iO!$o!&w z3v<SUjCQfpB_$=*zi#I86G7-@XEdc>9&9dIfCvN#ny?yy<m3!lDkUEKghV0IQSzrV zSDEeqq7s0lbQ|@jTU4pfT`aW<8)}8t8I3+0*Oe$4xkKW9<Pp9N@{wYbL3Dg-tk{1L z8rB7Cwk;EmDjZ^JEZI)H(HDw+bkP$2^&^sx-zo;hAit`vKcb~X$gtK*1iEEKgVlfA zUUTIt7SfUXf9AgO<!UF#6o)Xd5lK?gW+8c1mJINub-U9XwaD1@g$M-*yrQVhfF?q+ zL_%Ytiqj?}eW%iGJqr?Pi7P-a+(ai|-@2P-^0<nw${Oa_G>NO579{AOBtG~YR7vFF zdlGTM^jVC+j3A#n1EoMEyoQ_s@f~cB3sk`60EeTd^Ks;J+MkGV>8C>~xElD>o(<U- z%?m7^uuW06s{-f+l4?L`&9wGI`ucR$_)(U+W~8d1Kw=mc)}V{ztx)IB#~6I}$bc^- zyh@gp4%Qf{+DU|0A{tQ_nWRo_lI4<%R-n)&DZn8>NF2IDQG{L0-e(V3wf=O_N?CpP zGVU#yr@c#ni<SSm60tn0d$4jZZj(ri_r>kkuwIgnh0N{0DxdVXj_Zy2XDe0GpLv@1 zw<p^~<_|WK-6TYOVz((F7H|XRm;M}o8#xF1*#p>|!0HIRiqV?l&MQNkO4cWLaYz<6 zob8O+K6fHNba|Ac^qkiahDu|Qm}b7IYSYn=3Q>6f?6#*Tx5ZLGWaFN5yPnfOn!vx@ z(1VYWt2gVaF<W{bXYa8kg@<Pw@CPa+DG!7r_4y!;H&|{N_F$h|f2eqpP0Gl*_+a_a z1qdRo3aB#Oer{lXkI_}#M1R7_>is@9jUGJ&)MJB(2zwn@0J7TK>0}x7Y(e+3i9LX? z{z630vr(4qG;QaDH2;UPoe*S?4nz<5A@je-2+w->wAJ4^F6V!y%2$Q#o8}~B;LG0b zK`vCh)5)K@U+mmnS@P5@!a^z|-(-nY{)9I&9DuJjnh<Q4&%#NdezE@?7l#!7XNK5` zWzTxL&|%2a%lhLMESDbs&v15j_Qy|dwhWLz>qaV=CM@4g?@#<!sCY5<ecqoL4f_f- zk)x38WcWxVT@|1t`?#1Ewbyp32}K?C{X*C!=+LQ7mGRs}_SiAoWmBog-r}_E1F0gT z8m7LS_hVJR5%$^-g~LI8$KeS#D9(UvgfW6T0_xjDguuk0+|tH!)T9EO3zgt}=YZ)e z_POJF6>3I+Mp2Q$ntj>S8lVT35Xf)EInNgl4(eS$?DfaS#Vtm<s_%JOBEg$_2FfHc z6p#4LYRVtnvRUmQ!$PaFu%&n_#DR-T`1yXqD|P@Cl#~!-6DT#L{{u@kyo9dQsvZ3P z@gn$cwng;7sA$8j5sq428E^Mkzg0D-Y6ZN0LFw(W;3a~PT;<8y;MTvlR8FSJdL?np z>{hL5BkkYCoAQZzcQbTiZ*3CZH78h*jak$JwM?Bk9o(?RaHT0qHaQGIygezs{B0Aq z`C;)VbHYkh^0ZN9eb2pG?Q>w)QkQoRlhvRWf4zkyx!8PbFH>fqV2$V&qmI0%L%G#S zjWT5Q%xL<Ud8In-19$t9m^qdHYPlY(`7dU}E!~!EQNh5*JA-+{&EHF__f;XoXW~Im z5`tDfhl592Hkjm9`T;6rf!GVYnknQp$M-$A<{NHrn6Ta>Za`4KGNi-d+xldJcb#m= zwwvD$9kFfjb?7vOduu-(3p+6@lZL!QKp%k<3j7O1m7QVJ<j#h*im)Rx6`TXGB|ned zVcaf&y=t2zgh+n89`X~>RT|?diGA8wQPozYy?!0JE$ChmpA~IBrZ<+3rulD|zqbbb z824%zZHq#W?Nm`g(?7&)uagzx&Uytq>#rWAi)Ci)T~}I^BqQE-h+}gVdjJEi^qI~w zOrrTe9<__rekdLs%SP|1xG%VwQ`6<*5KB*LhkcKXJjt+kgCe@1a5VgdH^X#98x0e| zx{(_(x4$F;Nse5-zUv<szKxBnGI^%|jhOE4`?DR4_G2a{x_G23JhtKD_%nYV_QvMM z2wJr_-csh*dv#rh57klMPC;XF`l1P<Ut?hO$NWRid<EHt2dhYt7SQxPSdNS>jz7pw zZ4%}Vx*k_qAH|FOx%_TecSiboeNVSxv9l>X<M^VAFq_+`tNHHTE9JOWY+2_3Z)}=) z{TtrUOU4b66Z@q`_bh|+5)AfyPwHHn_)=;y&pFvWSJ8G8`P9R}s~8gcCihX{dTzd$ zs*l+%Rd$!@Un5}Lyd~pfZAuL+aNlIZS?E5tsCp9f$#?o$o-zl)MUCKdP@++yP{L7y z+Jrpz3tFQig=Yciv~eAb1Ss-|qy?mA`Y4hUkLr8O%6TDDml==J@S$N?gv_@~;WN}J zhKo4xTof?+MX&)KHJIV=sgsEXTngeZ0fg~WT$reY)a~ov?+D`yip<eQo;)0$?m#A& zgX*R<w%=cQXAbs$XP1wg^aOROg&!0ulmW%hgfP;P0QkcmN;Kfh7^PsT6@R2d`pZYg z%oRXntqN4S3?~a7q^Uy_es^K<*#&)O=|<jWzV~%=b76SH`E1MO1}%2@%aBSwC25JY zfcXL@X_4E7;2UL`P75&;m@DDB&O4Lf`RMqj5gfwwXsL0ywD3)imtyv(xum~a^9Q25 zZ80oUlB8|5opcKnq{M~KpE}T2>E6m2YlvM);(PKW!iXbwu)G<ud|_BBtPX2a7)H77 z^2&I{;zQyd=r4h@?DbG!aFuAIVn{S{1nxmNlBFbkQzc;$S5Z=8(kDsLJAR0hn3x?M z`{59k?jkvjfb*x$^al>}S2O<;-ZzowE~M^-X$BuYyD-p4aerKHncEcTw+5=T9q#1^ z>-}kzAUTG$;?;1B6lZH}{ldG_=DG&n+8`rP;SY<p@cp=7S4Ahb<~x8Cin&TQIe={p zu0VkXS-4e$?-=*I{_IY6_<-5ihAHf~h<<FPaWDpo1X?x@KW3a<cqHT%^}f6bXtrOC z@r5yv9yR)uZhL`teY>84{%KNjJ-qJxz+sqB3(ceGE_oonH~_Ug4;4l99ZeITLR7uJ z<3F8r*icx_P_4Yo$WI~c!phcaM72WSB7UJ?HBeo1;BYqmbxd>Kidc3F0Hh@krV*G) zo~<S&!&k$CdpX5g+S=h`ut|gV#44MHzkwNngM8U)gpRLHrCcr7!({)ng|3>NHY)(5 zw8ej3H5^2SYmN!YyZc9xm?@19yIV-0I?cenAZr#Cu7zX8$jqI6cV%SM{iJNB-zS{# z_j8+Pr?mk*KT8~PQz8o7x2y1t;rBA;p}k<F*NrAD#{t&gl;(8gLQ00N%H#5VhxBl# zywwcB6Dmr+_Iyb|cK&LM3Gvr}Ej!FDZqxmL+0JZ9xNE9(oC7!*N@{9!d1{Q<NaUT( zf*8bH5k6yy21!{4VT62nkoSs+kVB&97t$UL(lgGpM5WHdNHL%;vlTTSiR>vtD2X)S z*u+U13lkry6XbtJLChG2r~WKH^0_F>r6CU~J}s0Zt>3;}Oe>bsrGh3=Jea_@)v2uH zk)mEp+vm}pgu^0)4mE%c4AH#CpGcS_qt=6=T`LYZD3T0E#Hey1-^5t~6xRdEBwLrJ z(fVttif#S7R6$`9)=)UraOY4}h>k#v^gh#g-`VpVy)OHAWPR|7wzEAGJ~jvw1(cfb zeJHM|qWDqk>3X|L$J&feIm674@p^wMT<r0fd+X$yIdvVl1yWv$-Ki@KDU8BbB4y-a zPR3y`rp+@eaqhm4yz5L?&>S=eS71YtQ{<ZDN+=~UhI}`Dt39N<r`;!hTJ*P&P^Xd+ zDBMG(ck_1smQsPl;5OPPKf!GeaIOZ73p0d+N}@Z*KHcRIi$232phbh3C*@+<UI6d} zdc|j`Angml#B6BD^<F=}GCbaVOBH(k=tjO)tE9RaC=AuKTs>V*&H$)+Q&XW5u^u&~ z&2`)0%s~(mOS-k&$<?KWf=;V=4b`pqxulvvsVG?L#M@uEI!#xv3@2&cceAi-XRWc3 zw|fO`ZB={PS@yHmi)oehC3bCqZ(!Rtsb@q7(4)Gtz1xMqNb9KO_t;W-4w9<=(H#IC z3jrpZsy-ALH!@r)<;J4}{hPKe5v2|r)WMuUGe%BY1%PuL3kM?Ui-NbV(6?*SXq*p? zr}8@pm9hrplbtN_+q0BF!X$K|%ccvW1th)5JOLn|{@O1`Y+Lw;m`d4?bP$}h$n_6) zh5vO}s4QrWB_+VN2FO11b%kG&GBj4wXc!^$!Mrs?iVmPqBN<@pv4*kAqQHgq7RE`O z&W`Fd-0`ky1!BtP`#lt{5><9lYRE%<ADWF)1E48^E3k&(qQ^#ZV@#)*lK->xcmDdn zY9&!-pG$|rB(7<I>3iTzBZJBVU}-ekb^^!RZ}agyS7K5hp5W#m6N^zu&bQOc=3szp zdG;_mqgueQN%-Kh-qq3GCX6#${;I_j@7Nh_#Q1SNEhJfB4}CRBP_hy9F)Fw<asHz& zQO5vkk0nxyq~gGGx#%z+LvRHd^pamxb_os$6e<@lu~t*g@H%M2_z)44da*JdM}}e7 zO{ozCY`#<q<`_m`3Bn{`V0Cq5h%>Ng&*DF(KAmghao;^jWC{Q?Pss(eM*WV43IOsc zkyB$sj*cc7kMjAGy6oKTzu)z|S5{%-?FOO3g@xqIQJ+B{0;GoW5{zSQUPQk0&q}Tt zrphtiYIOl-$y#9Bx5&{0#YrNzcK@LZ(BWjw1JxE=*LT*{0$-MQM5^?E<GpQ1g~Nby zh!{JPO5D)Jj|Yd$ZXcqJG;Z>{kuQFpHZx=K_n)0APPD?p0ER(EGO1_}9mh3MXc7CX z^rH9O?WIEJJFY>~ppT+;wK}Tc3S;P5V|~%;fbJ6zi1NDaFyP|pn;LT_pYLPOd*}I1 zswR~sN@N{jV7OIpv_>_cb4&v#``Q}uoj!g+HGw#Qoc&ww8j)op9~zuB)S*&|ejE0m z;qFSnXeBUD&`y?NkS)qpHky}Kyi;e8mx`fA=3xU~%u~0=T8j?~1D`vsE1l-+L$J@_ zNAtcC;L-8p%NOi7CNMslx9&%12C5g$8lo}h#gqW=763XzatELO4+XB2s=$Ozi6Vfj z^2sFj(4A}$T_B|h37uO02WBa4N`nIOU4X~Nh5N`4>*Dw%p*_!7p?`M@-vAS1n+iRQ zsR^betjJ_ClzW^073Zt`Sbh!TzCQf1r{W5@*ft4kBJLJws2SNK$asMdRMzSpy7JLt zn|NZwyJ;gyv@&4Z2xub_Sf*cDkPWb1>K{V6oZH3@@poGI9W+&>5H)8Z<%z69LJTHO zQs8qRhUc819bwczvp`M&!Zm0r(!@G=t-bEbQbnq7J9=Q-CTMd_31$G5hey+^lytC{ zuhzXPJRUJXkS{SspD%~P{~S)1+mTA#^G$9f_XdpLDQ3<u{!lW*u$$!@hmUI4N~r+{ z><?N>Y%IwF2o=;WrHTjZwUdx@+alA7bA^v=GUz`I5sfxFv09tBOBNhdUal2Ym<@wY z2dR*GK0ue`Upf0nLQpIaCOt?~K+Fgzr=HcyQ|a^QV`G_^?TfJ%lpXl%76fGSxk9w^ z@|O2Gv0*^4fIXC6g9i@&ALREY&-@oPueCZnUju)nJ92WC4kby5!y%xVm8=kJf8K0> z5VHk@m?Vh7B~bp^2dvc8zBw$c1o)grqrru3S1q_nM?kCW_ttKUO*)A@+%xjs%~|P{ zyE@H<Uo+B;l46#a{026NL=?IUo|!3Okl}(r0gpH55{vmGdlU@)TU#Dl7x3!f77(E} zADkhsT$01$^j0*>wZVD3*w2>ZR2*rr?f<dGIz*v0-xiXNqMVi0ZM-$6MX@xG5i-)r z)uk%;#XHM~MPEckVdRhRGc=~(b3aqVpuol90&^U9*{)oT5ZZu@7j%WWyAoWE=}tBu z%F&#BxzRK7e5C#p;w$}aVEJr!dp!#2aoiLPSJjX>9d$m@&@Q;No}Q?n`r4S|_{~)k zvLgq!Re>(Oin{R<6LM;3$k_OtamDi83W4M8iS257tM+7Zjj=Q3?bw;L)-r?T$_bwM z)(|+jy_q_Zd)J96AXu}P*>{X5me|jw@*|}LS(pS3RNzPB`)683vY-=rN6kNTi>>P` z*@-Y>^2WI6WBj)rBd05TI7vM5hYw0b?k+-`7SU}XAxG7K3A+J&f0=v_CT9jdaTj(> z$%1dtFXuN=SG#&j4MWfh+gSG_h0fJ(u<{Prdrm>A^V&&prWC|gQ$226UY;L_6U7kB za5Td6Y|FT4+=Py6+zASeOaMMvk*{A$KLOUCYU5htW=FVke+ElwhgkR+Rq0_NT*k{k zreWyR)#7i~&T2O=jC9|fFyl)HDctQAaOQELt35N5-hv7@7Yal1oOe0WrE_O?9@8=+ zl<rBGd>U-hqK)-a(B|Te&K=|jthxMN-R%3R<lZg;Q0Nepl^(ikDy<EZ@TBTR8s8PW zciEuiacJSRK`+~hDj#n-B+x)z_ccx7{Y-dv0I54Zutbnqi9>|0^FK{xX@t;2dCIeP zyVO^l{8b#QqDPE^o#Fi5leu@&QY3q|QIn287g_bfOGje7S8T3vS}Ff9Kt%xz<c&O9 z;0i&|#h$3T@1)o$0v@wE0U`d}?OP?^3xw~3^s^?LQA!gcqRp>gw&5Oq3zlwX>1MCA z*J^$<BAvcrO3*ws6a}_M1vwcl;s1W?g-@vdkyGu2Cxi`G*0hxD$i-oi<nso-WtV@U zLq<AI!}0tDkqmMJv=ScB1ARr$a)Jx8M+xn_CHO|(|JF?W5RGYSu?y+Um^0znPBrX_ zbXoN!CoA=~?@Pf4`Y%1<`mG~~j*<l<s^Rj$HVO|On3j+%xB)Xfq)yUp;*$-GJJljq z3uxsBW*z@FHs~TvTfRQgPxTyM4__i%4NlC9N4-cT1%#5&&wQx3g<T${#xh_-uZgW+ zj|iyOTz=VKEwWE`6}4KnKJXK??k(gqz8e^n{QU{9;vm?U*-z|I?hEA~1LzbQ<TW*E zgDYe~4b6TxZ}?M~Sdf|K)~YZ{!vYLi-eJXR{N`V7buRZhS%S2g-NOIyKB5zH8Qs8P zb-b9c`66GA^RfjPHXZ0Z%+fQT;D8Q^U~j7^t~T8Sd?xIVe}C0RRsSJ?b@t)94*Rw= z!%RuvJdoEEU>$jrgJrp{PnM+*q#x51l6meqV@1UcaI~nCeP)$GZtm`kR8)m#;AKA) z4dB{1BpT+64;tVv%wfB{KHyrb5~(r?Gc#}t=LcnTxsy8=%yEzO2ss1P3ZW2iiMdie zU#!V(cT9+a%w_EC<t0#wN7I=%7^@yx2o$%at0E{Un3_Z8J2&0;3C#{DB*x?Tmjgil zlYaolU{RjT74&hnBMn+g9mpo)?VFOuY$ki*)oyZCAN>3osKqExOibKya@Ki?i9y0s zVPdWLHqUT}klyDxyMX#XUJWnx#^SlK^{Pl%0P%rj`w~tHqxH~dyt%!<l&^;!p-tNW z!!W-H)VTHsGHG}Q;E8%SKdOm@=|B5~e?=ZuU&_u0-Ouf113~9h&+D_ZQI{WYtzn}a zZbD`zkt!mkAqn>fbRbm}!dDK5d6pA?pL2_cs~L6p7ktkq`?=Vg<3(wJ`7BRS>nrr1 zvtdfU1=Ntz+rtS9G6W!G9}&m^?pG6C^EeVOHQ?0WT&B&Vz+J<^o~5g%3VI1xcKoz= zbcOio%FjaRjk~Ik`KB?=A=7IB_g`kFAbNu(lCGoX<?`t0Wq&gmD{WPuLTDb4<n-f& zPnGWva#X*h>Q|n^=f~Si0=5_DzW^<7I~rm4UYdryJlBf^5CXi;XeG##`$mY6Cph`* zq&k9Z@_e)S-jZ7Z4wnSD!VV;|{Hk-Xho#}4AS|-K<P9*eSHB78jGlnY$6=Zr`&O0m z&FPw1zi#sVjWm`q2xP?rjI)mIc`<OKVe$Zxf-Z1dws~xPe8!W3fkC6!yEg<jb~JkH zr+`K)5V)I_zl)LYt>=nQXEi<yFxb+}+9@roR9FKb&e`ibAT&|_tqn&*Ly42XRhcCN z1{~Q#sovH-cGmmzmv&kK<rgEBpnb(yVjiBqJviQl)0io;fr)<aO@c6e`95;!qW&FC z5L4x}$;EA}caHD!zs0$tESPaww9c3cLqKB?5)yLcU8prK-~QTrp&;UQ{8#eRr%xUL z5QAOzu`lb-K_YOC2K&$xP<_a$ga=H|%rwiCRa8WGc%3K#S%zr8WBvXi1Ntlv<X`Z} z0~8i-a(%X9(!taW*+av_DXUHk+8l|X!k~GsaczoO{Ar<-Q$TwXfo}vA<dl?@NMuDL zb!G`*FKK+03<`dNL<KqJ3e7>7sz!2Tr2c36gFu~+x0Uc2`PvubuMtjF8^zvLCKdvA zNZun4%*}PB<OhW4EQ?O*F!-I1AJUdhQ;1jmj%rE7$*=H^40Qmx2o9ElqJh2?L?>>7 zbP{<QXMSCyMp&x|ohHo(0Nm#QCiIO$zl^M@$CPYrno0O{gI2ZG?v{i|%Bw2>YDp#~ zXpq-8gHAQ($_$$LM~FQya@u+o;NcF3NS)DB(HOxhvWNZ3z4$4F&4BXC^Iw*YJ^vvE zDQPwIDie_ItleD~NDu|Td$m6$&51H)IWOM(Da{|hz8hsgRZ&qBh>*P#-;aGQD_hOX z#(@fH!z5~{H^zTyAk}p>>`<<>R*wZg&M7S*z!L~LO7lp4O!s4Wxv2Jd(N)}M9?|zt zI5YbGTSer8aH3Xeo;U9Xs^808a~o&HXJaOVY_MO$Fj|bp0AjLyA)shGUVZ%3Ziot0 zl~BPVjrogvFl3TB9d7dB3-<)_fQ_Pb?<<hQNMpg&J9lEe1VONYB*oiqU>hh|KD8T4 zMn#bbpDJ!OfSj9VSI!ttOM!ZSbGB}-+aktdI%N$Ah*SY3h}fSpK=)$Lf0V|M-eD^h z=Jvz;jQlDHelJhd|FErM93U&^@byg!Lj<=H$VHb>rEA+i`OK2cY9#_8gaP*X?)&O5 zQyCd#(T`r5_h@EKa;&Yw)B2Uf=oSlUv;AFOs-rCgM?ZEZzG|NG&CANrr1k2z%$-l` zT?0}gkg3R=bzIS}5XU)4Cg;0I^1Jihk8c1C(Gj~R6wl`{%Ogomph6<z0dOba;zj-( z1mdVkL4@9xI31y+W<abnyvvA|VzNx<>|h#3ZQ%4JHMHD_rJL!G+HA3Yy_x;(>8g+j zH+SRoHSDPGN%Mk-*q`!EU7pYuIQqPzX-j}hx9)vicE&nHQ_UAMeS``kLLVr9(&q;h zJxfmWJN_-WtoSVs#JIR0fszS;=m>niyI1{-v%ep6#J4dYGuC)s)o>b9TI^8iQ1krf zvgI-g!c2}`5X9H;W6kGtz?>i;HfwxRs=iy>K(n&o-Hb*$65SV}SN-}vu4)x1o9<K~ zg1$6F<OV~#pz#h*><qB!e+mj7n;jMoJE<6<%jpTmviR=0E$489y=py&^w;n=aKESY zXdTE|MM)hhkm$8R-0-4G8Ixt-$CEfGaleo_dVjfR9Bx0zI#8@<kq$kWlsItRMN(<L zN7t4}yMUKZL(9BrPHq=POy(ec2#XTseI^+gol{PZu`CBpI7SMWeWfMQk0S51Oz)Gx zIF>?U1V=$pV{_?9^eI>Hq);xtl1QhSv&5|Pvk<>(#LFjNwN6MjWPXO=97`TE5{sg4 z#)9dm{rASk<_L#>zp_wE2CDomYu|a|U{${#HX>}RHlkR|kZZ+FPSAiy!9L#%l!KE5 z#BEDhe$<&b-_1G~VljWbzC6N19LA{zidz!X-Jql3f^%ve>u?D88!BjX_<oSaaHok( z%M2LCAA9M;O{4oRA(urBgg}DKU#>L$Em#9I4qF0m%DZ1S@mc*6QRm_s=5GN)W7aj~ z+gt<=mRTH5^l&vxjV8QParwKnhEzGsq4+n|mpl0Up&}Y=shq#Lv6>ySeRSjlB{HYt zT?YCYR;&(DBK7-Z9Dn=_o8-^}U@jC3J>&Qd{*o4@G-wxrtVFWCN1BVb>%?9zkv&`I z3T4#Om@^0SO|$)t)+tWop__z^=4N$E;!Wm%TS9%_uZd7=%^ZFb*NcN`<@>mlY9MOG zWMH-h`-~>d(*644pCV#mV{MIq_-j4rk#)nI1kwfwcs#xWS*;9*UjgtE4^ekEi(f>$ zg7k_?uhs~E<Og4jyysjw^#J?{_khE}bg3T#TA4u&VTrn@<^QL5jF1lzR#p(;Ac`_G z^j6h~rKKq>D+2bhNCQ)!&|Sno<2iqGy$=N##Kmmyyfb<OV_Kds%c=<Uiw`(mh*zj< z9U0jn60*KMn7QkKo=R!ff2v4U=+}V<)7ml(*eP0mpHK)<9ZWr&(CW4T;j9gN{9}i; zh9><;^XuVQb#1fE6%L=lE49>w#E33gS3i(RN<^b>sx;I|A&^T-<Zxytu>&xyA#yMs zZwkY?Pr04DBqiww?C(_4do8RGhcA|RnXWBxnr};J`dVn3KDJM)HS$%Ob;OY)G>E=F zUCseM7W}mbH&p<jfrOi+0{6!MsU(O9?WCkY-%6As3K#j|aZuFn)V7JZUHcIbekjzS zrecXdHN+?2Q)cshoOb;tk8m-3h%e1?VVJb2-~|5gl+?Rpsy$HLaj31i#p${w69*ri zrRx{L2cJNzoL<q9=!XpH#RWq@2-ldfHTEcP3V82{giS1Y(N(NV-w^q@%r(sxHyz+R zETf7)H>_<^7*VY?>qtiRSs;-Pz&;>WR#w6WADdf3O~jc%)h}{<0|a*{;~ol+gvi(4 zCxK!LuIAhc@xGk3wxs=hUnFl@<F6F}Fw}s-!c@S`r@}p#ep-4<KBt=>i-V<N-0ZY! z)JobWi3Q4zv7`VyA|jD7bx`G8XX(rXhT;2&q7c+was@Ty51Xwm^b0BU$32TTU?F$! zH+=cyXIV)lH0zSVo9B8NYR)?!53m1PE3+!S9Oi#Zab#bEIhV_+r*|%CH&zqNA@I)k zACQKT^sjP%s)N^+2;kU$$!PIDU8&rN`rW5OPJ}M$)Uc^nVYl2;8`cD`g~Ghqd!f7U zYA_ikX;kz6rx+F88BlA0VHRQX%``SMr1yhGG+~FGq3s(NXGFK7SkgOrd-^_$s$wzV z-uAb;J=ftkdy}&lga$<zjW&}lcT8Q!Hy7jVSo{7&BIm-y{7xph3L-l-1VN}!pRnMC zTI2l2A@%X^^GfMM7}J4B6=CT_j(kh%EM;&GeP6gmB8Ah0=&cFh_a`XbEtJU5M`-RC zwKQE(=V;D8W%J5JZ5))TkYC-u6}iL3TEku*HD8MmP$5$qu+$WXbQ3<57_aRsQSh5n z<M?l|5Rz+N-_tg@o+77USWy?wL@M`dOAO5LcbM#8ga>4L>~rg?klazRn+4f-QZJPb zvexE~GzbAMi5o9sVfkj!OXnyN=OU`Hca!hYd~Jjf7YYrXo8|UgWH~rtNx~2iz5+SB zsWgBfI`wkHR7OO>Fs@PATgmsv`aAzeg7Z4{0U994j_AnvK$iPMD@9gW=`%Gzq=rLf z7vX+6(?pU5o75Ut_c&wSw|oJ7h`iHNg}9|+x2TK8E%PteF+MxLeZE`}{z9p8-dFu) zxTked%q`WmYX-J$fMOsG33?=S$UGt-lh?;&0AHjLd!nvzjpsXI_%s?-Z0aBA;UAb~ z&uDN?4MEK<=!je!Fy&3gasEL+E4(Et^DiI>37WkNyPSxcE*(a)fE)_clZ${Vp?G8} z1uPUiK58LV#NR;zRAbJSv=ob#s)up$QF+u`2kBZEM_wf=*|JmR=nTAHQ6khp9<+A@ zT3gS6uARtYK<qsbk-CnEFjZCntr3A%#OsS{jO9|sesh{FwUqPHE*Gn7&upusUJR?6 zGGuh5vzOLDij`(*XZs0A<ryb`6$A80Bw|_{|3E)TqCI(11sl!^2K&bvG)`U<r>-mj znvIa|y?m?}sYrM$hDIwOz?c>JbSGRp#*BVZkG8dG_)2PR^4wbBC)4qbmQM2!4Q+I> zOTL6*Nj%jjb3{r49mi_H8whr1Z|UD&;{r<=jqJnsv7jcqo@V_eP}0?{E4FU&ijZ}j z5&3Qb0doF7@h!rk1zAf8o?DaMxW4fBRwqK2cc0L%bd<Q0qN5aPKm(LiUV+d%@_~U| zTI|57W*~%H`)JJQe(Z8_vWAb>(_3ykP_}wy-C|By!WNC>yHaEFKqQ!H^7nI0WU;65 z_is97-^*CGEHCiktP;ULx}kVdw<vaH0x(`3BG@x?VaCs+QQnXFl6Iz@Q?nS^w}0rf zeEr-R#Bx{|o-{gt%4z-;sqU0RR`5+q_GyL+374dd#;}3$k;wM8I<s4^{n~kVIaJ_= zYIx!LRKIMSu#CI2{?|!Dq5<_EP;ocWx-ITxbD{AD6;fe?B~t}8qiOQJ8LlCiU)s}W zhpvTi9lr-%ri(V+NjU9tf3#ry6vESh<cG{BA3aQU_orkG0Qtehp<hmx_kT1#PPw9R zUQLSMPW3%6CeiTsfpca6o8kQj$dObt`D7abR!BJ_0<a^`Czui+s1-B=HCR7b{{A{e z%m}%%j8qUp?}&5(lKje1{QdAWNC2`Y1)gq>YfGgEI>s9dqqZ)x8G-9T%$D&Pkg=Do z{ypIq6YG{6uZ#Qjt%{bO-e<dMdJMl$lSBwdj}VFvq0N@6051ZAm|`S+GiFdXE8g}d z*9<{9plz@+?0+Z<9SS&WY%D6Wxv1tH9d78ah)rnq|MM$*P^iKHe8e_TYr6c~yWv<& zd7zF@mL4I1x>cbmj>-cK11yjPWvUPIW(C5Z(rA0=c4+Qn%mNr8;L1fKGSL=QMDYjL z^c4q8U?{v%wL2{TiCvm$HZJdNmzwOjO0`Z#lp_D{;z8XRpkY{?Eh_f^p}hXn&sh@S zwe}eHj8LxYKRyo_*wG`xQ2yjU4*+~FG^d79xDhJA<ov&_P?29?{_g`o&;;FN^9AW) z|N8&{iAHt8|F;Ebum5`^vy}3`{eb@4qWUjW^Z%nOp|40pxmfgV^OIdLz@MV5noOOP HMcDrXmrGHp literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231109002926.png b/docs/images/Pasted image 20231109002926.png new file mode 100644 index 0000000000000000000000000000000000000000..ac0cf61f635c199a74e4430dc59f67b550a06ee5 GIT binary patch literal 38517 zcmZ^K1zc6%)-5I7ASqn}($Xm%5+X>0bayvMcc+BX-O?Z>jdX}KNSAcVTL=I5e)qk1 zKYk}R=j>Q}t~KWzbBuYyloX`Ukcp6?prFuXq{Wq?px_$8_8cNSc-<z|B!hxNePu2t zrX(XKMy}*wYhrF?3<V_}mZXND{&oN_ODjG$b_@nl8mSG5lG85{Qxj@Oq6#Y>>T?eP zB7=+3o6awv44{dd8FJ>JtEpV@zAfR4t0X#CzgJtz^Q*WWyxhFq{O<d}dz#I$^}Wpz z0qQ(KyP5}K8j4&kktGZb>3yWUf_`ik3^FUc(F$~twr*DHQxX#B_k>mtx=V|2p=E8G z<dZk1557$4Uav?ops0z~Uiy%-;I9Qht*8oAQ<FjEL~>`Rvn1=Q``5$4BmNd8{I0aZ zK&bF`rOn~vl{!}s6I78>leP>zl!Y4k=<^k05wtHtp_$@dpAn&);d|Pfni8%t3q`G9 zt$Q$s&eF_<w~g-PIjp4<hDHdw!khXdWIwSgW^`x%@hw>QO<8!h^9h4dy*Mp?O#MfO z{*sNUB6^BGLr+^yUH|jYFXVs7H--)<B<a&8#^8bkE&7KHyECA5LNl)xI_yHxDA4hK ziAz4eu5;37MKEX-9W(FpQV{6zz+}PQc=C<jnoEYZkHP!%`3^Rh+(7o0?1qnVJE?3f zj=JpqY#L0oGTB?k;Yh^~sW8<N{;X`+2ArWJr#0(cNnE)o96#a$xUkL3UihGd8a~O1 zg$fdS7t4$ktva8wxrz22|7RlohB(9TKX=1dN)kR*c%*8i!Wk$o666LnsJn<Ky^^Tk zgIEwzm4`_@X)$Sf=$(Z^Phkz78rp~R&}o{-d_-~(HEJd7sc?T{KUnQ%Afz3O>@A>^ zK}J#;io-Iz7A(QI)|uju*a7eF2c1_{;6Ff)g80*e*kd&_hmOF`AI=C0+D?f*fGU1N zkkTy*HfTjL6pq~1Oxv$j4GNk3!8ue_n?$6!wLwIPl32i>2R|_2nHx(|3^tm(99#?q z)m?}ybD02vEqYnaAKy`onq@*fBg(``r!guq@3D9Saa8JH?0~TPM(D!`&vmThU5rwW z?>&MDTfY~xjswRO+{7DSZIdsgQNM`4!~I1t27Mlo)Fge&hTr&f%BdUHj;shh$zEpx zif5%_3<KpdAZw9)=v^<<5b`?R!Pk+MkiyS(RQz#oPFQP%e{62WS-4o(h%wY?KctdL zl$ncNn_!&Z?PuSMU0he8J^aAd3MJ|Iu3uP%GWVtonzaf?ooXhWBw_XQ^tpO_Gkn{( z!S#V)zAoP@Vy~K-*PFc4eCIsgZ_a+96b!VF`w40Y=ui&#51Ur4M3cX_6Bp>iLN%o` z#fLJwjaWN9r<H8CC2uZYZo2k`T5&XZ|9++4m3bcy>Q-Q7&-aSov^!8MgaK*`<1{ZG z=1Is9Gu%~@QiyH3(8AYYf3%Dk4m*UU4l+1@R?H`Buh>%&b4LUBv|$Q9q`fD74sHCN zQ2oh_f7E-FIcS%F`%lo%o)mUy*db{{b9V?fdNg;Uj3F%fk0O4E#Uv7yI>W;0!LF9d zz@lA?fTO^Yei0v;M@blp7)QwwcP&k*99<^HMa9`Kw883t+~ikB<r=Gyhu|LNCCZi< zZjmcl^pp?VIOoO7XHimgp9r^c>oA!lQ$AUaSvcWq#$<`IeC8fQKYKDC1O58x<hR#s z2$5mc)z4o%k?W(Lvns<a?I@|{D?<|6vQ$TyiSX_T;~_C!LAQGnvWCQik^Nz`7k_>4 zn8ZzR>4RQ3|8Jo?Vt+|i>N%WN#AjXVqVW0*p97U%%}Mfz^T00W+jQ|$#udrc(Ry^a zvZbX;WW3UTt*y8qCLm))=Yn-BLme+PkhLKePH8W5orgW4Il(-EG@+`@y%P{#5*`*_ zD_bQS9xk0PoiA!!IB1_#%Alw!l)%}aY{cS#o2Hnhpews1YeT6=>zW|^_9gucE}5(V zO$2*PO|Y^QuUM0!du~aIMZs<{Q7(f@W@)pebLFo4w8C_Z3R4M5l01oGl5&bt!&^n= zBc<grvzLtN!c0NQidv$jpEC;t^SqUEOL<G|r>-m<rx>Pprz=X@ROm{zN@}O*O7Kh6 zipZ3{mMxXOnyH$2Z)wMAVyR;BY^E`Pyi#WNSw3NYT4|HIW8vnL5mQZSCdP7druKK$ zGkE2bnmSIAHVUSb?q}C$<!2mcHr6@yU$~_B<yu~QHn@Cr$&OBrE>+0+{xVZG(~ys( zIkh5*S&CcAwfN9y@nds#Fd>>D8V;(~%QBm}Y5k+~;JxcTq%+y`i|xg++q}^+jET`1 zy^7^e4;@h4RUDygsTNh8E0M2`><(6!y4}0wLXOCMW-&SII3hVS^c%lbO;;`V&pq#v zwyK-iu6t8iT~YnjKKZxo`g*S*trLzO&gTKy1RUB?LOxVHs*vj7@vdzS&X;JMN$ECR z)*Sa%Cf3RC-x<~S?fdh7%P`NfX`g8Q(K_1IV-Wf6b%bU_OR|w%fpNhviy_D4qw=!y z_%b|oPIbZBnc7Wte9c+S<%Z8cu713(F0OB~k*hPFH~Cr7&}I-a-}J+HUUgolUg}`+ zAn0Q6;HMO(q+2v*R1vBDkpFIn!*jbL=WVAc=SaI34pw$vyb}gSgZ;m#Mx*XFH#QU3 z>!x>>o|nJT&kdL4jPf|J+8TDOaB4pkbwqMWTc6lI8Ju2HU1{z-uP0u#j{FJJVA4=| zNP38U$#+SLffAz<!w{qO+S=r$Bim^!T_;C}WAxUW(HPxB-D}<3wm&B>$KNlOcJ8g} z&doZv%X3@2hP@hvK6>+c5w;h%fAr$Ndwt*NGwl;|H*$ad=jUB^jg^K*nNC>>v;uUz zpBVJf58Zu@{RDsY_tNjp-)qIbQxY9({uI(_(n;9)rPG_jhJr&>AsAb<TP!7HX^p_% zErUowFI8%;tSZ^g!cF_C`B)0e1uH(ZfNeXqijA>%A*L=8SAt92|GC0ccoD+*%=p`! zm>x{S976`fte)ubOhQlQXi{!^8`FiBE5ED!-<Q}{*m+1JVY^}LIF{JUbWdoL=$s=- zcwJ`Z<Objex;A=om1PYE>l6RjzgmA6wMTly)oye*f;59uAm7M3{@&nwk72?Tojo0i zG)*3D{^9HUuBf$lj<=IM=Bno20$jG7M^Bcszs4_99b+Y;WEI@zr4$Me9S^9-jVJ7+ zXvF<sG(wq0(lZV+u^#rwCP``&^dzUFH&v{VwXrzVk4t{8HO2nJ?WAttz`)Z!tkE!h zHc|EM4fSfgwY&6EU~8|J^%d1J!<V=}lm{=4nTlRqv2xn)`kSXuice}5{*>2yd2g<7 zw`$9AOxQ{|!Xa<^{o@bb2u{mWD<hZr{Y~CY$M7wuQM9xcLsDbii`M0cjPSvTrSFRA z%PLkX0u7CODY1GMa#OO@G!1xeEOU*Rde61z>idny=Ovb9uk-PTG6oq2+h1%lwO{QO z>CN8pRZ)A({8YZoCr-vn2}@qoK5X!kYBF)xcb^SsW876^f0tb0)nYMGg7UQDDY4qy zcXDd3Wnt=*jWY%ZHDB~*j4N8+5Gpkl4pv#bnZ7;0J6GervMu^)R#$DcUMSxs-@qMW zRZ&@AQZXmGpj`E9V5X;h%g6A~yV{ZWT0iP5e@gu1cj-AaEB;+n{KLG_(VR(>vHai% zr_XHCqJInV-m_h<qw&SJ_4xZqhu-Zh&dVeBtG6F9STUwZ>IBrCLw$<sNQ<*|muF*t zjE$!*%=z%_+c_q<PJX6}mZ~S?6x4Koy)`$np1A(44?zJpYg?FJ=!Yl6x{BIq-lk_^ zUsn4P_T+>M?cMNoZKtVXwqYi}{nFOmIEpSlx}K4)RpW+Far<=n`Ph-oS27Dn+tRQ5 z_D#RTw~`7j#t-@`Z*&BmnU3dw>}Bkw*oZHgeND4Fy(s_Pz-M!6E8LRcxHY}_p(Xoh zq)o9=??z<()i<&3kZIq!Kh=fZZR_f$?@jk|8>KFr-E>$;w*>!8=-dTf<gFDCOs1QD zAC10%yVQ0UI&{B8`5iIZM&oPoN8@~A^H=BBy9bK{;-9nkvL_ZR=WE<Iw)J0~y?-u{ zEj}FU9JY)e$q8@!&i#(N{=HC`r>H2bcrSWWvsrpDTVT7oe2B4ujvCs8U2&%d74TGE z5n<)r1<GsyYHam7l3l_6PXfNUy-5<)ady>O<a3rosHx6}%T(PfS4R}THm%j)D7&RG z2;}MTBCT{HI@-azD;n}X6^TzN1rV&lZ_<-L!vB$flfmm7db@?!ucFgAdhiu0)X&TN z1#53Bs42pY)n!cN<)IkBHX;-pG!fJjumugCLeRwj-j;-Z4h8%8ISdq3h&dG8Kl><v zcgSBXctVc(`wkl)421yx!v;^cPcZ-58?Nya?7z05=D>GQuilEu$bk2^h7QKYHjZYt zPHUeTwZR8ScG4P-P*8X@kSDZ^GW9Vy|E#%+x|6#6Yd%9;Yi4~TTLWWeH)}h{d7uQ` z_`s&Mv6DWzo3)jVBcGcf<>MZFU>ou=3nlsEE>4z$l<M+I<YKlC#^hYgtjw&GLdfLg z<N^*xCVa}`lK&hI{u87$b8@odV_|W1b!B$tV77HIWntsx<z-=IXJKb&0(&qyy4yJE zyD`}~QvE&2zs@6W>}cp<Zs%lfYeNn>ufBn;vy&htCFDZ?{`)&lV>k2vxsr|JKeq*L zkOlG$3mY>l%fHVJ4i$iW%BN)RW^AP)Zf*^12CgB*&c-G1xc~q6&Hr5SKaN!YpCj4W zS$Y2R(Es@A|2<UI(bz%E)*4*XN$7v(>z{-F^UHq@6kvhe`hS?>ubm%11%?(v7GU}J zqzNIHeUrxm^Z3kMTu}wQgH`tUX9ZrLgD2!2JjL^ThN2{)phTc##9yhnLGNcGEyz#b z^x>yH-Bngm>BUS@!G3d=;{NV4Doy-v+4$XXMp;>UCz(X?;6WwIxAbvW#FX(GMDj^R zKkttoZkSxlTSnbSt1g9ZBadvog(|(jFO7Q4XfA(QS})u3&NBT~WrX#DS_J05KVl2u z9L7453OM>~5}=S`|J&m^%u73aivRi*_%M$Xny7KY<7Unsn;iPTK8P9{;idiH{_A5R z9STj`T+n-8;J;rx7JRJ@``?Ey0%I=k2VYT_CFGLz-_I`X2hUvb-v@<F?q5eM0;{H} zNXD=Dzt~0u7Jv4?83bYq5lx&={*2{?F`0D#%LP99M_B$ZcP&j`js%Q8Guik3e~d0- zf|JT_9PaijNo|Up<?EdToA-@V9JlS#FzHJvsecV|1!Ay@xN4aHu$KrW;&2A<Tc^VX zjl1QC`)u<H@7oK5i~S#zrr$F*N%j6?>i#cl624kF+nF>N&yiTG|7kN6`rGL8)eH41 zkvhv+g}dvmY~*jeTNzY;?vH#+XTcetuJ^@^9)|M#p~jhOb+2WwdsnW>IUuNi`geNB zA?AYq*RVw9ad@0}6V1kRg08OCW4>`Odr^hsF{NJ^4t|GKZ})04n<-1Xy1!hO_$(UK zQ)fQeW1ON>fU0|Yd8B408AHkxj7k`v$!5PVLp#>$?pW<|pjqv-qijFIIZNHdZS~KD z|L63A`Lx>{CNxIXs5S^9;Ic|}yZhZY=^^l=?KA|P1p6uDJ6u-Hcg4yQ!`Z@miHvFr z`n)dtsoPV<32qPfm(!jET|_U<Vi)7=?_?;Czdqc4%~8nYW1w3YOk$MyVlf>*g~KKH zI15k^e<1m{QS+FfH%vsODI>{`uQVF%KKI8_NzF%xkl-^c&$L}Gm3Cp#DP%lH#(j?I z_ry`ipa=0+`Q>;1qfp0DLGBga<ya9)q}D$-dutUfhuGgD@YR;I)wJy;C_kEN{k1C> zxZIET$29-8tOphWpHq=Yk!G=SK3pq3bK}Z~Ga@KYVv&{7%64o;;rqI#*;-S@Wznzi z2?A2k6!c%b$q^UfFX+Vet@gS1c$&;>Hby?4Cxb)e_|~Z1<7}J4ZhlKuO(#E6dn?mb zH~cJe5#q`I`x3yr_BofIF+nbE^voYa_--t+STqQEw{m+EUeD+yG<BlwkD7ehlU9pq z2K)6WZj&>&+U^yf`*Ss8udb(0;D>bEJi=;>hr+$CPl~I)wRv8KAN*{Hm?_taVAg5o z>H2UEZTRDGu_eiCAfD!1X8;1pv^)((;4(UykhU|@>c{?9F1H5_DAX&aGNk^?KDY8y zMQ_CR7n<HWZI8Wb{oPAEu!pKe3mL4{YcN<Vf$L{{kiq8hL%Vr)6y*=SRTQLw#~>|R zK1uI{^SN3@_{H>lJw`Yjfy_%Ol8}QoK<Z;#FuY<bG%S25u$;=>p56m8zgr-iLY4sU zzN0`#aRiV3@B9>9>||s57&-!S$ta@y_!+6Pj1L%{h7)-*4C1HT<GCdvNerskrD~OU z-@>2Db&{H9GkahBFkK5Kwo$UQ*&I&GG3<-}VS4<G{&94OAY>{VQO=?LjhB~jm=;sz zTHJ53R;7TS)Vd#SJn2r(P?8lS+-QAuNbGiDwb-n>F`6xW&No2%P5k|Ah0dTDl6$?= zs~UIe^WHG$D;+8J8|i%Chd%~)SHER9<}E9q;?TavY%K8PwO<P);C0Az+e|Z^QtE)! zwHTI4UPzPJe!dCUE9vIQX2jQY+BqZR2UkM|hE=ni;n)LNc(H77PD?nbh{TH|{4R|| z#NEl-tFnZvibB`oK~!B-2!%U~9((2VliV)UE-<W1cOXjOOS58Nl(o8_hTk5xC<alz ztJGbzhh=HM$~jpQeM0?bsm?s%xpH3U`pp1lAop6c^PbA2<L2<2)%3U<=<903K8Cnp zG~#gJ1Q82Oj#4FEruNi+W14q*PFKhJ<1MbX{+#`yk1iO?1Dt{;np2DNG58**L1Eue z;$sY=u(Xojob9X^Jqc#w?MjRnWwp@py+4Op72)B;a&J^;4}of}-<>X{Yk&CT$yucN z#e!b3Z6aT;g=ho3N=z2WNBN^lzS)qL{q;dW;rOoesm!4M_D~v!X%F)Qh=_v;2VnKQ zb2zs0I`}e6IkVb*g*{ftusN6{=bj>Y${uNJTa*dOMK$;kTh4kp)<JBEsRqOPOz?8S zF-PyKkNqWO$0o)q8LJ!li>;5g?N~v`PaR$g1v5P{`0xf=-v>AdhF9!|qm}6odGm8u zxuZ!SR(0yu$mt@IYZLTBZOn+h63YEGl;VjjT>h>+eXhnhVj>_z^%zR-JO_<x+cW?k zZE7y_>>30jm@MmlxeypdPVOulh51jBjxg$dtOYhptr~R})3UAi7eBu<zKwrOp5$CG z4u&0n%_{=Kh7+3w_pVSO^TqYocuwCxcd6$RZ;zKekBaNZvKCq;akxkG3sZ{ex|7R5 zR`_UId?UK)Ty3;OaZbfu`=$lS-L5kRRjcL?2>qeXMibU@SzRV0S%UmI+BIYbQ8KWh zM6)EW3vv60Ro>Z1{o*?&iv|a>ut|k@c@4?qZ%b6@<%pgM?8q3=qzNp=lNJ{&#|YgN zm2Upp2`@MVhFmXU4!Wl!kJ7Xda@gqCx1Ou&e1I>C`+FnQ&>nUJwo3nCo@$)!AGL*i z<F9QhdWKlOK5OZEPDJXt&z59FXmGp%La1yaktnMb{mYzepBtH=dlCURCGyX%3AFN} zD74oV7fYhtb`zwnPU^}bPy*1vA|+kHu18Bu$oR}<4tig#f4+NZyQGau%=P*neXVB* z#0TS@E5^!J%HwPQ53O2=(-C+%DH36=6le!)QQS*PG4SZm%&@CN;?bOsK=y^PM9XH> z^ZFgcW4GdWf-Ui<B7(VDn%wH7;G>Olp<8gt(I#nY1<2)8ASsey+T6~5{i8Znp~Elo z6g!nFMZM_5UBLXuY7u{!!CcPi)2JXKse*-s7G_Q|J)i4*GZ39`v_}%F?VmmR^aPw} zdYfCqKWIrClYq@2@W%2BDt(R5!@Vm$XIsQfrJmjwcM!_?-cfQ#^$xuPj#QEIx|5K@ zBvojril$E|j^g7?5WcS2?qF4ZsB?q$Pm=*9#nShkAL#e&$-8}~+>D|NLJe2Dd$6y5 zrRbI29(`So=M5S52$1@82V>=v_j#~Yx5h}OAAK;EnJS<e1)mv}9)G7`c+vRRKtkVk z9MVs!FjMz>`*q26nxb14G)c+qc7)N4Y~Me;a^BqBV`}B21Dx~fdHzG&o*>39ItA6( zlaph}D4qI$p+t+dH}huz!3_A|2PAS=B$R*BrW>uFow%1ji)J05$i^r}Jr-2Ni-;oG z=5W8Ka}K>x4Q7(S(3<G2lVfh`xw-ghOJXmdI3`8rZNzoNVfy{GO05+gGW3qIv5YM( z2X~5&OWG6I84wm;>|mJ<By0?G+_kUOuFX{&>VL85<}|_*74W*Uvm8n1oVhvQV@k^% zjK6N`n)w!Bn&sYG7ji7lEs^C{h}t?och*l8qke*kk}sMSZu-S$aekXwuf3Icn!;G0 zJRz%SCYD0%h27)<9*eH_Vz>9LVx2JQTsJP(VSl_f44q<DU7h`uJb|}^=LjT%OOv-j zaOKiz-x35@iYOz!ucgOnDUC`?Y1QI)J*?YcyG%w6s|Aq8RL60IGx@bsg~O{%KIcJE zW_m)8BCg>J|1M&rkFN-saXG&xR?Jo#O4a%&>dW2KuQPI;Ocp9ODB-)8GpH23@61Ki zRUM03&^`WelG{;hcrgDZ8Fi1{yVq^iA6}90c66!Dvzseyq-p7;VeT*LWr7p?&*+hO ztkeav<EIGSv@`H>7MNxWjnx{4$K=SmhW&(vv*Z<Oy6(n3(cPg`82+sAR-QVoq`VGB zJvWOjuG|OCI}<cHR>$29OCCd0Xi4h_El2GfOZq2uT`Rk6ZMFbtn*X%^>fBA{bM<*V zj^EWrj`Zd;+3$2}n443TtZ>5GKE3$h4wFYSl_LT(y_@{@Jsx7FT}%<>jlGH%1?!^s zi4JcK(9A!)K_LENzuwDhk*qIgD)ucSkZHh6`(3rcx2e`>BF;gqWjB;gvv?LgAw^53 zCGVl{H}=o{xkNhsO4>3%r1eiKL}@qJEPfzEXq6JZl8C_5;Iy21={zR+=kA(`U~=<& zCNVkL9el6pBAuIX6Fqy(r(zT;t)husDU7|l)6oW6#jIz$)mxr7uIS#ECB(jVV}^ZC z^#@-J(6HJr32@M{3+p)WcmJJnVoXqn5Wi**k%nZ(-{j;t5~VDM$3?HMq9@l}r4tfd z2<x3@I)1&hk|D+ZwE2$qrrs#th%R)Ufx~zZw^k-GtbctTFNvRu9H$x~a2kz(mE1_8 zpW?+EV%<O2qrSn30s1JTD+9&GtDnPgpyMJ?vWXRt1$vyk3*qg`U5{5f3z$VKsNAJ? z`Fykk(B7`1293{)N@tMrSAckGUdP}?Y6_Ez<2I=;gy}Q%H@#r$f$aS)h2_iRB9+AU zGxhuKAM}jfCVZJfUSZy3ZbAb#WwMGUkgJm*Se{V8AYNx*m-qJKK+eT=uAQ1(k?>_N zE_G}Q9dz)<2Ueq&afz(gsS<}hVL0y~8T?tK91mQVT<8mQnX!X`1l-!Xr#tWheNH;s zaS=8@YK-Gbu1-)tk2dSLg>=qseKAv%+V(sh;chF@7bHV6vlV~V3T116_Xy4Wudsl1 zeXNSpAOVFv847#T05<4OtCQE25{-|PLOyPOa&#Xa8w5!dt*%XV+vXG&y^1%qcgX7@ zLQgTm8a0#y{Jw_;bADK`TMb`y3lI?hd?NbeRFT5HMU856JXdNYUE=GzGIgv9E&U^^ z%Vgcl#;#k`u#@$)OEmqMX88@O$o#p4Y2o{`$?75loovK8LD<!(!GG*146$Pj6X!p6 z6qzs!tk4(3V^)+e^1mgSz%7ZgyCeX!AAsVx`O*q$iNm8dV|a|H<qfFtDpm_pFL9)y zBugkI!U=LwBXw3~hmx71o}n8dGWW~nMe#Q|{6hZN$JnS_blKv1#MS(1GD06O`)wzk zuqeJLotS%e&~C_2&v`BE1A*T?I5wpS{V6XrCRp9BRzqO3e#<)`wm$s1HBop!Y)tWp z(n2Bla;+~p{m})fkWk5l7Q8fE9W6d(Q^?zNvRmy~eQ>e*v>3=F2ylZ*Mcd{R2Y$8A z6P`Ed_q`ac{_63HP=!dlyq%mGZ#HN3d{qZlzgRsFh`7%iQ*TT0`E$MH=R@I|GFxLb zfL$sch7ElaizuZ1ykOR41=@1-O})b}*~$`?wy$@;SPDi*g&(|LH>>|3gW*w;*jg1e zdjQe=?#*i^NS+jd(SQVqCrGw`t2}W^rFtukFa9OkO%Bx6FGlZB%?EP?y3m4|G<tDR zg5kOK<@jCpSw9*#e9puw==n{xL0Lmg*#76nvd@{GKp5sDmo@tyjOFe@!!r7h)I|dH zrt8x!(>O6ocWbB?5O`_?Ts^xFHSjEX2o!Lw7n{HAklp-fax`tw34e|umQE_{kk(1C z_GQILtEKwILaW>KsK*l0HcklJY&8*E+vNw&M~j|9V*j<{FzA#(iuJRF1F77W%dnqu zt?r6&Vxvx;sjrG=D4fP>C!DcD$uZjQn|i$7-nE@$&}{0`T{mV|JQ3VJg<5Jh0PK`< zeaD`rif-sl_qUg(aisuerWpoecT3~Q6>EMe8OQ%#I~?T`xVz+aIwEPB#%{a-)FDgZ z)u-2e2K0zzvtL;nA@fmPWT-=iw37HnkUK`;Bs3<yIQ$WMbSMB~h99jRQn^86hf1&5 z`rdxLjz6UJuLVm1i=SYPqC5EoV{%nKs2|gKA2t#cMKPn7%aL$sQ|r@OXniskEp%I4 z%F|Mmf^j#hOWqbL_@U0cFJd<v`vk=snAeNlHC?8`ky{Di_UH6r2ixIPHoTJnZ$JoW zWUU4ZVk|tt*Tz(a=N7(NfweqbXxiNZr86?4sjr`qMRy-l!-9cto~|$e>=bCB8gRd& zMm};A>x^A@V+aRgueVWSrgB;)r+u9NVoCQI!Riq|*C0Ruf1iM3B4hz!azMKsB{HbW zddo;DlrH-|ELJNBi={u~w!kr(Q%0|Cav-ih10+CdGpikK4Jc+i>jVvYLdCg8>M1dK z+>Sq`;S(rld0%KyMU4glNLjoEk_e{*NPVSo)nEPI^kz|E+{mUdlW^^i>vB(7w!E4t zeuG;mlC#Kv)XI@4J7kmL*Qe3wuo{G){#)o~J9o7Q=J4k%Pp>sgu4I(*&4;6(#`~2A zUrWI{Y!F`CqsFQ7#9oiZBk<SwOVi!aiNK~jye@u()a>ycy-~y?n@kHPoC_WIsOHGC zl6kkNS~o}Z;WpjLv2eE;j^FLSj7Pu3x5?7+x&CD`!lYT(FRwb-8wVvCja7r3i|O+n zIGkl~B;gDQ(@dF`MSwioO;lyV8CZcGrSoPlP3}7f)v}$}ZXqf2iH$kQ6J*>fK)~da z1+`LcCFw553Ijyt_w2;Z9G2j$Ya6#>+fKKC(fe`{a%;lJ9k2yoi$YqB`&DO3R2iMg zygm2I8(?+=Jp;JT=Q^WloDo+r#6hLSewturJ2yqqnFVoe5ij5~PxacT6d+DdD7HfO za20axaLCmV1s0;NABag`;h9<V<)%y3xE&t=p7ltBnRSL#kCU`q2MFlT?8*b4u1P`B zotYcT9s~T=JQIdPm*_7mtX1{?RnK?wWg>x!y4H3|a}VlV<tpWj1v75y;g8%b>eMTO z*gkvpcHih-5fgeaBE{#gf=rpT>Lblq#n73`hs?X~E|)w<r^cPnpTct&7G_bp5_Zu! zFRJNzbH2~;O7Ma~l%G1~uvuu_a19lFBy3Qr0ig-6zz`z-7Yg{vm;P~R2h@z3JR|~? ztUe%eSnZVg4_VGBA1$?wEX0rrFAd=~Rv0c{;WKOVtRfxixbl2d^^-!5H{Kdd8Y)90 z2muv&L02W9L(Bm@ml6z!L(WoCKt6f@L)h}n6us*xBe~uCHeHAUj#c^9HUYNZY|$I4 zj@100->w+mm6^$B@^Qu!oez`7Ur)VNlt`L|5eq>_TS3&7Pk&imZ~e1CB1bocNz0@+ z(#y1ZgDqm7;E4bhq+m;<Duh>3M61Sr<em&cqBC9}*cyWbx(<2>6*OY?ZgqU+;<@Kn zvGj}!ts%C5?rg%cvdx6cq+F|EMt$9bM9`zoyw+qS-QGH4FcZtq6}Ppl+2z2(0dcif zf3ewlkic+s$W)I*wM4~!#!nuZq8LzMSsJhaaW)7>-C^qn&x<@E8SldV!WD@D&k~8C zKh4Veqc885sLm=O$QTNfHjRPjpLf@m0DYm-QiO0M(eT9UEOjx%Zm*tX(38#&7WV9! z`*r5=61(Li*u0<slXQ`08J!3Tg#tM0Z605)4bW}jS-u^`(sFyhe?&jCRrw$ccMS_; zo73eu?M@BU5i(!9Qr>iOeaG%F&zsftEKf@SHSu%G^aA;hL_YxMD4B?MiOJhm_v#bi zYFB$imq7GuFZMiYy9`eJeYy#16M0WS<($2BR?)GXDPtpj&suY^*urf=f=r#|x5)T( zDGHJCpHzLE0$AohCwW|u_}niIgV-=mJi>q2*gZ+G{uJaA4pglZ()z$CK;&Kz6V26{ z#=PCn`i03}F#D`)Nj+X}B}q+}?Q|SaL7|xdaYg(#5e;1iW277m@#Ha|pq``^xLLp@ zFpj&^t^5qk*j#)l>(U*JhIeB8xg79?eCT~n)6xX1WWIOf%^UG@!#r(7INe2C)?`Tg z^IwLBab^a;XYzYbDX9KU*Z;vii>SafEV_KWHi$MlRgj|;OV2qE)0Yd#r3k-T@QGi@ z;B}-Ny!kzr_1p^(MLtD&(FBMKKDP&(9OUuUNUQy5L@!xublcJ{j+SjvxdEGZYV=aH zk?iDqXR6=bdsfz-+?O^B>R;^d&u6t*d1y*jV&I#tBdZm&g~BY-58TN8TFv?^gPXcA z6ob#9;#48glpGnPh8(Ch!@q3bQ1i(k<4B4_VW9^NRUZAkHk%ba(dXk)EXo3I6ELM_ zZm-C)I;21S>~aQ|7c$EaS4R{$8xu28h=meV@wYFPiXoM(c%8;R^LxEdEKIVs0pOjz zwFs7X9`92{VVo<CSG$5}-38)1sP=yYm~&RbY}5vpga%0E4Y4sV-aOGYbl#m}EBh^l zcx)<T4TG=a6qm*kcu@Nn>|Du#<m~INO#JA1&-{h|Ty<}_`d6=>jtaZJ>@^B}DX~Y; zot%S({NU9eOJQO-1N`{-gOETcQ7v)figzEVOtZZ&(vrAsbval-30w>6ol@-FZm8=n z6c#vwuDDXP&*3%^i?P9W!rXL7!IqG;fTw^rWm)3zYmkj_r0YvU=q=*q{zQJnZ@3Rq zn5`QbwB3s0WIrU`U_ki$q7ed%fR4)2Pxp87vjA56g+$C42MOpG6vxwQdTA^hbL4zz zoia|+36q5SbMbGL{T(j6q!HC3O*KGZ?npmfdxAUq$5?IgIIqUj(IO!3K3v<HHMlEa zQtlNGgOdP2pqqJ;EFK^B$hAEd8trEQ2V64qt~tvfgw4+tK!$P<>os2ffgg3U_}UPX zxb`6Zw`73!McVM=yC$Rg7xNHEecXva77F5MiRnauScZ_drgWu$Y|X_-hXh6=2M=et z;Fn>p%ignp)Z3DIjl?T;+j=$z5~e)~C#dr-qXA(mji(`O+rL1U<GeQ`8hnOGSWhh( zNkCy_mc+A_;pk;4xrvE=qV7g<`V=V*p`W`g4%dHi`OgJ6MU<QD>tLoZjam~V_ZrPS zi|8zWjR-uZL@TgDzJWaTZ2FWk@O%u21*)nx8$o9Z_H~=Bb>H|7k*okkXf<CaBW>7l zwNscqb;GPykr7L(CYn`4bb53I3YVa>Mu%lK1kMeABvIN7wRoKt7iT4^FXBc#d2T!T zDS-kn#iR{&ES#g;!em7}mcu~Ek{<wRRIwi?Ja^_Zm@5cMbp(N(*Hl90G0r5z<w*sB z#$1d2eAy&yNOJ9YwHb=Vz2uh5uJGvtsyX(RgC3xc?02W=LAXU{)9-?#P>ff;F_KR3 zV=K3qE{Q(tV>r9ntBe4AKB85@8>6}S*d?qr-#=Tv2CA9IHz046L+X?1UL@a!570Fr z85zvinTwK29m)9`g{Bv2)E11N1DX&qjclOx^7I>yq5y?a7E8YJW*OG9_hn}GZgB)8 zZpVv4`TBK`2`MqCmQdH*E@vhBRK0n;2^C1H+8uV#hAhq%9Dg>$Uc@wfDf3d@w&s%s zyAmS!QlI-9LaKK~9_-I#2-AbnNf-bUY*nJPZ$S_PJ+p6nI7S7ifCBOYjDD`!*>Yh% zBE`TewaWfO!(^uG5<So}UKl-3s~kD_Q7h%XZI<t**X(3|KQp`c=~ci~hKTv~$*&-R z`|oP^Dv}T&FhCAE1->1xcB@X($R=X47izLMcXB<J42F=Bq5AERKg4(ZgyB{Q&j8kD zFy>x#N>Kk|k!1PpH@dmQ;^$Aus9MM{*lSFp<Ka&kO|r<J)c{nw*_O?M$&B1h75;kg z1((gjcA>{Egpl{o!|Wh?`@TbpUcKs5Y}0D|1O}HZWF%>_K%{w{sS*8XLodp)LPfHt zvWU*|AGw}J;ImxFa7^dnKyT<WDt+?XVMonmb=$20!XE|B_+CSFB?!%!olUWP&b!o0 zZtH0Ixh@Cuw1ugL`MA`Oi{etV+OLU2WP)jqz<4T*yo8KodLCStFvxr<$Ag4M&&#xr z3t4x0=>9--iYR_tSc3k=d{Po9g2K*xeOc6zQ0Q<~bgN*Ig_%ti#hH_R<g!{?z}q<2 zY_QQ0`2sGO=KSufk2fHK!u__q#2`1dBMtSCvi6{&^F4!?%FYetuipb>nys9KP<?rX znZ4K|AKa<ar8<kfY}>C3JVtzh*pks(grOHqM<#IN)G3n)vfrdFiC)~4FG!fsC*_)7 zuu<?{C|!yQVqk6(Lzb2_4$Os^)|heNb4r!CpudF_8CY%C-Eo?adBzZF0pQ`?mqMsj z5CIsBhmijr`U`gG7XQ6P*X5@GbFn@Bb9bs(?Runpy0n8rt%)wA{mFPJ*#HCtSqU(N zZ$JjgEXjTLXr&ka5U@#3&7V~`Uho3WB@%MYH6W^2@O0%{Jg#;)n2W$=)HlO{gy&qr zE0_`lneV;Ar9LC52^1;QfpA=dG#0@4gQMdDEI0N{Fb8Qu-OtD%XYY~rBh_Yu8UC~z zC(wBJj8?GmE>A`W*t1v^TtFoa=^_B6&bN>STFfzI|F}RE;q1Cdx)_vF1BU2|%uC>9 zHdhCNYRtwd$ICQo{o<Yp`v|PGC2%7u4g<}^&unj|{2TDB+`~nOA*Qte3?W3f@7&-D z)UnZU05#DbOHt{7662{IUwQi|<KKY94GikO-mCezn>FGBP-)iyn0d2q{j<J26{NI! zLVkoBJ(y04@Xo^LLV%Ys036su`O5LrNF&zdA1J8Bj$7YV8*G|)XsZGAzBPQTa{cS5 zSpnVVU*)R<G7AQTp1e<1gP4%qp8!&WP>H;QG!po~rW*q*m<_CC&S9nA(AQ+beXhw+ z(X~MQ``QVeixa8XyaFeYk+)s1?Yih}aDQ_SJ<aEO_`+m3_4DC$iK<+gP7BvcQ?~6V z;@~Dgg}xFv>8Hw(OJVjYDP)FRj}=bW>$k*sgRR~<DQPuNM!-KS3Bn~^_r<3_t|UOt z5VDI4oKL;Au!1O(>P-&DlF<nP;jdSK+L;4XeMvL0TGrAnE7*>(B(L^sN0EnWh6U+Z zh&U~%;ZX@N$>&SeSbk5)u@rmy-tXys+Z_1_n{|6#0J5e5zyz|tnzphS+iwr~-+**1 z{PEM{*p%P^5}+dW*rqsdR{AWu2GSt)qmNOqPyr0(6)5wF_hQ4~-Y<NJL;1B^T8T%@ zZSy)!A4t0)1uRb)R4{>h$bEF(r3d4AdHB?LFp*96D^S<{E;s!#SgN3VBr)@yb|wr) zvjm0A(8||xBAAtzv~G4PbXvqg*gV(LeXKCJVPXU?QX#VGgeyp9;UG_37kmtd*v1bo z5Oj8wK5j{qQ$l+xFAOoayxw2_DxBk$L+W!rtp+2>r1L)1@gpp<d;UsXa6-9k;&X~v zDTYPluG{y1&p?-f*+gC#q)$LQ7%GM-5NG!UU@H{r&={#|V%3L}l&_(HJEbQbd7cS? z4(@ty)Z5C{xM2I5$5<kOc(ymI*m~TBBI^t${97`U*4j9#^J8&QPXmgJ`b-b>49Gw; zu+;0V(i+caw31jISb^AQ`<<azgW;;tnV<wybf=CyL<QL48wiD}N%1st;Q<I3eC1i} z4l%-i8VQ8F8g~_es-0N92M)yVKUy=@XmzVLTWW1mCOjG=dS>C*ji$tkPHpf#jib=x z=u#N5SQ~U+T%FJAJ?Wx3{WY}ZiZk`tw-Vj~Nn0l0Gm3S&&BjDt=(T4U{WYZ*s8~~C zSpU*O>~SJhg}4rEI(D5;WXKp4a=OA)o<rI;0Jmm0Rp|S0yUZ}a;vmr32pv<1PQn-Z zCRY;4ttemX8faoPwDReB*sX>(j~N*#&rBduZT_?aRC*ce2PFdAQP_+zMBA4-K7a)B zyVJW7s(f^D1vnxutLL$mm`{3{y;CLmqWrySAbzL<X%1o-MZbMaq4Xk9OB~Y8<%*sF zEhH2HR%*i2Wm;7&42ZR*KI9v@0RKndOnvqBW%Idnqwxgda5x~V5Va@UGI;Dof4R6n zs_&RK2rQh`3YWPnfv*Ul-+*&bZH{Iih0MqD)!QsG#A@rNfG~qJ>{|AuSJRV#LEvgX z?8I<<)NWRN+c>5fc(E#7a25cN+u1Nrkc+$=n;f?k_z|^F4+~L!pLJ{zB0Hc7U2h~D zCRM>dhBFa2n3Kxce|3Lh#`z692j%{r8U^w?)gbNKDySfscHHxCsL*(l1;Pg3)J|ZU z^xA)Ws-`}cFetG(U9&q?oa+<)jCZZ5v?zB=)&oU-LS&~%_az14h1r>`q1wyesabM{ zndT^l?x2araH5d$;be#fZzf`sN)U@FQera=QhXb?-JJ~0jC~d>2a8pc9qyf4gh$e9 z^*g{YN9qzD5`9r%Kn4oxaOA7t7ESiV!T8_<m3<4%3mK1n5P5#FM^>Xl_*yxl@Ch3M z?bD@#*PFO6PlZ8{w3StV#1hivFQ5ZWs~`>n9wOo}K#$_k8_afF3k$6YbGrh{b=sc= zfU=|01LMRu9hJ{dHb*SI0Y@3VOCtxGfZisb9V*=?4J<GbYVH&<vKzf2?5V@r0!=v% zDlF--XY(AxrlVOT@&cP%7g3*3V<I)O-;oPqmV+h+%?ZQaNU7QyJy2@v>d@>z?ac-Y zgwT*NvI5lGbsMix_4o2lU<t&4gy}x?T^HP=@ZGT(gDZde%>~HI8bK)dT$YtUZZe<t zt#Ch@q&dAybMG^a(hK%H5;Ty1Otb<JSh<wpAP!lzEBw%e=_c)|hOpWDC)>F(>3{m| zxTF^2C~OO&hc$i`DX<3_+2Bp;rA5xEs<mHl67PY^>*cxrR9OD|w~QDBtT#qQdM|dL zO_!^dCYxjEs`{j4^1EsR%)xH`z8i_93{u;$TTRFFF6MC2D~fZR8>g0@|1iy#C{I9# z0nHC9{s_Z!Mg)aVj=1rB5fhoTW~xYllq@WZlNV&U#J~N>UGNLpUK}p&=@32=A5chv z5PC}bMXL-1HBrB(BUeo0&>J>proPS1Ypnoe#qKB&$hV8`L61q#*;kcfWqLAfIF=W7 zGo%u%+f7U-P7-hRvZS}`J^b!c^nA>nI$P+lC{$Tr?);__n5cwVmtSu8hHbqz(&ZW| z$BJF8@EMW5m^cLjw3hqH2Aic;R!#~R)P(g2Y}rrNBex*8To!<^SWnT9v<r2civAI& zRwAJihKFoN|8bf)q<%YI3de7V8FO@w{fKF&vgEuqlOHw)rDfYeGnMn&XVg9H^WABV zX-HE5B(+up<@z^>=Mg|<MKPaxqegX>jnDI>S~`wWG}sd{jaz2HzK^7nQe(+=cS;7* z#I*aT!yh(Cp(jg%wFiwlAdAB^T4c@f8sE)+r2{&tk;J=kJ0~LW>?Jk?mb1u=89z^j zP%Z?3+fuJHi`zlNt^gfDKU@1yny_%#W7InYZ;3M)kfNWbGVV<0H~uirXou%#6*mVG zX)G~kp{n4J;O%~`s0UW@4bK!*2yu@l0Jixvi<is3l`8s&y1w_$Z$L$%R#Ke>lnaI` zJmbdFSa=l>Zqd~Eu<7r9+I}s@;j~X$t$;zm-WX2fu)xpT%4)pc{P?Yp%(u)4?Cu64 zV9rb~h(A}6lL*B9vE~$L6&4Czv(iy?JN28dMuwVWw$jP?UCP`*bvzxob}AY?P}sXs zgZ~(nW#BS?bUv4OTqv=NNYbzo*L$Zxjo&~-5Qy85aW2TZdwAO>d6l8y6MZbzA{CGv zN5`!R+WZD5&;_i?siNd0rSK?zqL~jPj(xRR<oh|<&+^M;szkloK;*$$_r;>3cATdS z(IzEh#0l<w-CpFy`~VN6qaYDJ_qibA!yIWcZba5GlaaT<CDB>;Pv|9V&~U>oVAHq? zFK6Rd%eB9P-mOC-k|Qk*a{{MU3tt^Qk)QW79YL*9f5|7rZI2f~o0gG<zFpN)=aa|U zhZ<Abk0RV(;3^uDnx)B6p*{OQ3d{>cs;pRN5W$O~b<Kk!!&;^i>-5P35E@>(`@|l% zxSwv~DR9*hyV#Xz*}Ynd2f11c-~kjL+>^Gm8FoIbtnE5-3f4%gW?>#{TOg5^+^mA1 z0=S)V5GWWhvBnBs%o##@2+9CP8Lrc6b+dQIxI7R>bPj*F?}#U7M(@D7Q%xE3nsN{n z)UQum>Hx2$*Eh8fdZb1OKG_06FzbwMfwSIDO>vB)NEujon9s>WM6xC%+s2Z#)d20Z z-q+>EII{V$d2e`uYLx7s>gNGc{bbW~KB5vyY!Mi1>kSC#$z`k1{4)4qYZj2kiC%z@ zkBk=bzA2hb(e)@E@P(^nZh12h6L`TIyyN4#Gx6=sSBkS4E!#8?c2ssb!HnPn!O=Uu zVkK_MZYcSmHaBH^dyJ8x9{a469s}2u-EWu(lS|Gzj+6ThE*s-1D%dy$op)8bVG7MW z^!?G_%Ucw%FHEauuds1}&RUdnkoe73FJA>SXz++bdBm-o{j9gHa0<o=mRbSIPSUFS zCBB;5+Jf)HJ+$z6yiRvjsdL9iboXKQ;ts!nR;&I4wSw1#dw^|dcps_>8b6<iaVrd# z0jcbZ$q12DH~NfPt%-cT?eDd3??87WnjGQbj&wFLMaFOljtEfHEGS$_P+KlOz*4Tn zg^m6KM1uO2RfI`hwDCypfs^*7Po?{_DgB49)&OW<n6Fws77NhX5V8wLx&$Jrf?~n1 zXDvnBA#6TlKtL$E3pOBaj@$KkvkU*v%El5qcghba;Mtt&L3@|1)Y~Jx0-rMQJk4n0 zV?!7OJ<h6(Y}hSNHU>VEdbX>Tsk2RPsXG~Rl=ek4irOyVrJ)RO`(csCJ?Rx(^koUV zIPhKsO~2z$GFf#SnNVE?i48J}SXCQN*WZzT#ju{QLsG|QXL;A*+4jdSi5HHF3rjY; z&F9!M&671ph#O-a3qAV6P~)^H`#W%uAh!Tm1>@;c4617M@ji}!h_eUCt&z!DJW>de zbf4NPjwMKzUfB#nWO973DXFEBhGifA2xQNSO5eM6GL5X3Hha)5o$itu%$XAfx<@~H z0GUjFF7B{XlAZ)_$7LZl<T7bVW%UM7Sk3QXbCYMV_R-cf(}s}W7QAM&=C+vXH$Es^ zyE&7OL|Cor4#7~<<z?0GH#)_elVSk(Xt@$jv%rbHEG~2lFfgn`P3K1>QcYIe&f_Vd z&emR3>E;m9d^qoXi%#k^)&Q_rDS&T4b`BXE#g4JFI~(0gms)hfIIRz%?`_^(EiV+7 z`qhcn(fyBnj{tJ|H)sacM<*%3jx8)sW7z>swpFG2lmb$|oqbO~2Yg13l+jekTEds@ znHKa^4<+_?8KpTxSh57J={Q}FuOC>o^ShfLHOsL&5j5EndPDdHOVwY4NpH`wWOq5s zMxApXilM{;Ozb<K;P(u}xDTyFxgIuc5w&RwS5Qes1BejZlErD~j^-ML$nB4T#jaMY zOj8SwNy(rnhqmp%xDIbAmX%0!yzqxseHkK+X7W1rG8_CjRewd+6?^~UH!{Ly^Cnw8 zxX%l!9<5P(h_vJppr84-up}1(p&%SX&EgSOM^Zx>4gndhqP?g^5ZY>c?DHmyP;0}= zG^VzlMb6@ipS;NnnmJ2Uy3;25enrD0jGL&aLBP{26xq{6R7ousOlq6P5mnKZ`GPs6 z3Nvvxxuo?3Xrx9!u?Nlb;VZzIsp&m8L95ujaW4(EPq#*GIc*l^(m}l~e*ZY5FdQta z6<DjZ#}oo$=XdLv2pf|qs+i&BzwG+O8`s3iTGQ&7wKGYluqsB(F7F@jZTu@_4t@XV ze>c!Lg%HqbzIUHP|9yK7BIS2uCVzVz$f2d+He`H7J({0unCD@$zp2mlV1FUjkI7BL zsQ4O}9YHzS<8*Tb2h<H}ml3%1lp8W0qC`nG{k&}yic2^XumhnidhOcMwrHn9^C&w( z6!2(7)Ei-H&^crD30WwFGq`rkG2CEVh*4Eh;CEnbaA)e&U;<Up%V!KE6MG7gpgE~p zsE)-^kKR44TUI)^V7=J~Nj4xm_H(#w=CBm45sdY0$!}EzzTRjO#yqvu65nwN{4jvg z!vHi#-m$03i(@QV0<{xznL94wAp@kA|AGz&sma+)h6!jG1#yD}s$TVD%1AjIVs)t- z=lJA`2Dc#ZG#M?mxKk)z<3iA^su4g819KyubS!!Jg&jwE*%CzWwWDN$u^DJ5R`QxD zaBfiuJu>s<t`<|4vPFp`rfX^Bk`W1MKT0sGF9YzzVuXG9!ol-m9}BQkoR|5ou|--9 z74BqrqC}40z^?_S4nT%NNjno#r{4GUvKdUU9C7ptmbGOV2kNgQ1`DWLsPatHn(3mP zHeDB)H=IYrq?#)|g=YkKL}JcFo=(8NyGIA)jiM;&g1^*1SkDJ1G-feU6T$!hwkoLu zL=>jL=K~KhWuRSrY@9VNq?eQ-l(kjqN#W2d79X3o^BE<|io=1ZpmBsuUF?Y5S4~Y{ zK&_AU2_<ahSHZNZZw}JB6Q5g{IXt6UMdUl0UB{+z&YO)*{*qQa5gtl~L@~V$N%dug zt7+0rP=e6S9%S>_cUjEW73=$9&dDUuYVb@CTUS@=2e&k1xI!93(h%Bu4cmhGp(qy? zx*TO2=+Rtez;8vcmCu0DxE**fVfUV^*q30ejx_6d`B0XzDf?g2cYScq1g*}+30y}l zM?!K$#!P|eA*a&k9M2Z^();GvDTeuHFm3JJE*D)#1O|myR`C92aghu}R&h3k_r=MN z21yeEJ#AC?E*qgAu;?{AWi&l<gDo4CYKd(cJNqd*E6F50J`iR~YaV{-|Jtn8N$f<O zb5Yw7TfnRTmc-`tpiZ6u?*P75N#?$L=R?^c3YXac!~0L%Y500x)q6JNvvH&$XC^fl z2S2wo5g1q(rfc?Bb8NbGI;()PV8VQs(c|H4xe~8yT7V&aM_Mt56G;W_-DofyG8$s{ zq|k4-S{F1lLV5uVM`VuPpvVk3>v#us3N9Sg>aDI+SGc3nE_SyX>YTp!JGK$Dt!%$x zu&MrAF7|{0UeX>$?#m<e9DqZA#`Ea}Z&l8-u4iF|yxVUW--{qaltw`c#?HFmZwa8} zW&A+Z(s!KJL$NKXPF;I_?LPuT60*Pf7!XFXRVRa>npzz|->RH}I~?<!@NK28Af4(O z1C<!k2#-<d$MyOGg-naxfmm|JWE}bfq@zyd;1<3^1h}}Kg)B27zGGO$44_^&PyA9L zp!>SxVxV(tHkma$a6o}mgmE+qG@$F7THgnsA{Q0Vhj0rOP>I@ru7R->!Cp68wFeXy z>8AJItOh}hoEB4{&_gujsrI{7-vcSSy2?erNHVLD*KzZCH1vm8wy~Icqb;Zi7#<!M zOeZ7eX?EEIz*2RIhkHUZoEY$YTV$J9l45_;^Z(Ndm);SIMKuMFq%SnLEy2L<8~Nik zg}HrE4XBBz0!E&7o!>ooSr1K!${$WLT2=XC7v=}bXX~4=g!`@}452F#8m2x;?1Au1 z+%rX6K6`8}J9m(iUZiC+Ub)O&vfCz)BeX$^WOa?(0ML3|<bjw!4|L@FH_Ey{6_dTL zf2ELILVxre;g|^oVg1XC%GHW!x)<L+fW9`)J?K4ynKBIutvXL-(L;b|G3d8c$XekK zvJzM4zi`9A`uf8>QSk*XX~ipO*F9=y_jN{~H>pB@3EVvE6ve$y;Ns6&M7_U1%`$>e zYVT-U|KTD1pad%H;wicO#zoKf^+{J-X=BM`iK&bX3=stFXkm^}%JEk%#=}V=N)4eh z?#H*~mB95VjO|V#CAdSJ0RKMnesBk%*?*F0u=BP~;Cl&+Jl`GxJhkDCUjj@f?gr7s zb#K>55{{tHV1|JEgw+Ms=4M^L_=(9KV0=?1E%bj89NsM7*{yc1cXi46BY^JVTGC_w zXWt#sKS$iSKAW}EFYmnRA`JM|i3okO0!>`pAswV`Z$?Ziju_*jd54a0X*rVnu!FZr zA{W|_#o~$nDwxiKq4g1l+yM~wRJeZXHKg_;RD@a*KW6uH?E-BC_ztZ+nv3lk;xHRZ z-?B=79kv{y)2!`~p4jYMjL(7=tf1)tFGV0oM#qQjgCYdhsQT3;JnMGgIK6gU;YONE zW^`Xx>64of3^JR6Ng^iqo3x3bcKz;+x=%WSE*spA%1$I3csJnp6&Wfrp{S@T1Vex$ zCbmaE$n=L+j(HeltgNfjkIH9VIJZ)#N#z50C8%N98T`1)YzDU1@3?8DM!y^WDR$AU zJb>H*62qQ!H(b{9Mgnf1CS^!@y()GuKt3^_cRcAjva=JO6}ZV(&|lIOYdts(6i$54 zjPjJhXdr?AAm%FlZ-s^q0WPpAC6DUTzPLz8tv=Ni;A@Ntn+0c4+P5FTj~g_M?A8I{ z#r?5)Ab~C<@wWrcM`SDJvtTS;{8eNHrYVQUu2eAB_~)>&aa=yDgbM5tMlT-wdx|eH zBLkZij-SFe0EV4Id$x8VgbjfrQ8NbT2>Kun=BU<8msW!)@)RvFa<`gCu+whr)2jmX zT?6L-Q`cL7McH*x!-}I0pma*Z07{3XbR!6eARrwgog#yDcY}bGfYO}<(p`c`hcqJH zUH=(<^m)GTd;jY~E<$GR`<!#{z0cZft<#^xw@{sR$MK@bv&R&X_iD^GJ3vXi&d=s9 zhPM=N!o?8*M`v{w`kng2L7wEF-ulDSbR!WgO{e>=NyPzQt%t<PE0p-qD=fB$H*c;= z^CBj>!Y_>;$5)MFSqsu1H{8DR*CXF*xN>t%{HH;|ivvioVKzCx#-$Y96XeA_)}4d3 zQOvPx2Iq%^oz1i_uaE^Yw<p*_?cr+!946Gw;#vznOqHBX&%@W}>l?#&(;uj1*_!Di zYXx2mP)TK<A^AW+Mq-O{Z(_i*`4PrR#uSGJz^ey51vm!oJnF>td*U!%>r?=!)A5%d zzo92*ldSd1Hr=WKQUkvm@zkw@=5VqW?f!d+BoIFnG9<cPKoj7)dDG?-w2UYrk!ClJ zc_0<ZsDZDKv9AF|R0Y<Le8KA(D}!Cr8>fK$f%`l)xeZ~vkT2l0n|*2Ur8yd%?-WT6 zBJA0n086CGoSf{NPT>mqj}6+^Ng=9E!hn8K7eD_;d}A#AqsU|-f>MH1fxht@`t{9t z$~6VDH6SQF<(L6b@Th>E&DUFGa81$F)SHRu1y{9ueZfDS05wW?Mt{3G$6Dt2&JEn% zFun)dR$Tx?H|5l7KDDVSPLTSXO~~x&&P(=-_ug`iIEQlUIcSN;JjKi^|713RdRe0X z+H70A)SYN!|9p*6U>EeEo~enyM64l+(>7{qHn@}_4uyhd#Tec1n9b_|7SYX#<7YnQ zU9~iGb?I29qnGpoAV;5CwDpaK(?aL=^^>1xD>YTr>p`H>7~JIxA2q(a6}t#DH+|1{ z+NY0hu600gkNC!M72S1JuoJ%3PdoEFI>KoHfX`!<{~M~olDIa<&94@tiJ9O}{<hQN zzIZY@(NIiQ)%NK?`(2o8*ehay_?YGaG2D&?!$&K)o+&FE(F8yVNt6|4d~9)~Xy{W+ zYZN#Np_pYP7)giv0MY2)lj?7%H|UMr&Az$z>enqs+l=bH$=P+AZS?%%_^jxLt8WK( zZJ8e4@X`7xh_)|L%|j%00RqfS)a8XfQKVLsvU<bK9dwE;F7{HdROquO#9`iRZ8W4) zU*1c*bI|rqf<Wjhv`%k3ACCV|F&K#CX&LaA;s1hP2_Um`kS%{3@>_G1KfjQ2M=L0j z-pOK|a)nt5U7hcJX?Fl3zc~rRnsC@~XPj?Iqj>8VR1<ct^VIH6+c#abaq+eQMd!$U z;j;^x-ORaK3{bu4MuJ<lptz}C#Sxfa9Vsv$Gg-JP7MVog_gM<l(V?4z*p980X8r4? ze&8TC{gd}bcG^t=5b@7C6ksisl7p641bLFq0TmvxgEzWZjXqp*GV~sovd+gQj=AX$ zM$)O3_tFi>o3jjX+)nygtm52Pp+{W*Td%yGiez|kev<kPD-c4q<LoT4nlmw|#CI6j zY$)BaCPcHNG;ah(yERRsoR&19#wpDNlCyHiNEJ*<Q@pOHV69QEz-U$jqQ^p_D)Z64 zXFS+;eoCrr&6v%6$;f-a0QbN?ZYOj9s*65Vy;G2o1$HkLlP%=Y1Gk@L{$?$C9OP}& zeuFkPtmfpdipy-)JXF(7dp=*4T?!imYCzpT+u`zCnvErm+$m$TsQzAb67<EUgLH-_ zjhU3w<cdH*^w7yN0_ry38mNJ@Aid=P4@A<PI>r4y4hJ%Aljc3k3e$I*w5;;|j-W5q z-7zr-yehM#?bjNBdY47Vwl&c>T<_|v#!s}libm*5hEtrXPP8iV!rzQK$m#BF#l`m> z*P@7jY;d<uVvzbf&9dRURQ|kyw%&j8Pok(tCJI(vv)>~dAg0&sgWCR832@`?f4dY& zVK?;ijlNmonE}{M1Y*kHN=W(aT2}$N3Dw+dfQTK-3;5$1A-w=@J2fQHwJLV7XY>Oc zL3Pi+8XbQX-%<-IJGdtdbh;+<*ZV=Y#KYU#h1$cLyqIq1QHasT&V8MhCftf2>_3eB zoSad2D*K}`aG8P35}%dkQ=Q;HBx@)Ve5b^$rvbPTpc1fMPkNDg_bx#F71Y<Dsl+^1 zNe-aVnR}S0k`q;2d0_!Hyw(7^M4Esj*~8s2K*9gIlR*nneD4hKNVKWGH@G)+Jp;N0 zc10cUJB|*%NzE8gB&_|TtQf3s4V;NbO4v_fBR1O-`A&C4{59zLf9)}dt{(&z@Zx#= zvv=MB1NT_KzVerJ1*S*iA;2rM8=4AVY%S%&-=(c}kI*9%UQxFZo1bm+W+rke)f_-w z-dpT4w46c=3~bxhjJFZ$=HEf>Y#|6<CI^5lRaS&J3R38VM!;keqQ#515GhSw5=Jh# zsw8g2F5KL-Q1^q~%gD#6<KBGem9*JVcG?e&v`n^l|7-<dDd4FHeAP$rdk+Y<fq<j} z8rc;&`ATVCkIl$r3k0vQ6cAIDmYOhI>3*<cpt!!II3misd4)CIMAfs&fj6+*!zs3u z#Nq4>%}v!m$~f97h}qPDrrVc3{A>O_C;wm7MI$<BXxAzklKp=E0GJm;d96QC)2dq1 zk|iTqfCoU7jJowM1iOoXF*Z?k$vHL56Qcq{omJ@opfFNUbcgMA-RWu``_2w0X_EP6 z!?P0jjzKKXU8gEQNV=T4?eY(PZiB-2HT^vJ#_vttuMXKq+Up4snh!xUwv&x!2S|>B z0Vm0q%>T|2&aQ`NalfGxr9CMsF?Wv2Yk(gTsLJLrinp}NvDU#(4>uT%tZF{)dxqY^ zfdh`U1i*xS9xkFe#rs4^O^944+!`s=W;DWaP|W}&88PzJx%4+C1MBraKpWoN_PfI< zs#CVVdd=&c2>NlqTWz0z=TTH-v=w73!~Q!Qa2#H@bA-uQaT?%2<welTwSNh~?`K!y zLG_`gR7ArEO<^pK*5?AC-I*o<XO)G3ghuteQ0oCeHJ>)PUBC{!z91{wYp5n5c$nh+ zDsO+^JeOxQy<*UK*{k3bLFdc^USM7E6_P2RK#kPG?=JVV8ujr$1=#LIz$hM4S@^Ur z8-!`JeLrm^U*kHchW>A72jzfkVy3{lph!#ygd--<)GcbZd6pf#j`ph`2^dGDV7is9 z9*<G|xj`g;yDkqh*bT9i%=<`9vJQOiCY9oHPaiMun}7b7jRfFgO2^;-Md<!LQs8qS zjSUb))14`jT2=o3O~iHZBz1epE`lb*ujTcBeWrYbd+ZMEN3O2kVKIIG<2|yGj6MY{ zq&iYrRBBKcfOu#svq9_Lk=%|WNeHUpl%zp#gdKXM)qSxvsQ&%t4=3Tyx7gd6WuM(Q z?uNzLlAyBBosT*uR7`HIBpnIHx%N5ton5B%FS`OOlKi^E7c&lh<IY!ydjff~-3eV1 zB9Q<6@!>J*!^lR}Pc&J^!5+|n|MdY!!9nbcVqM4npC8#~;McitkB8v@`}bJaQMFF* z{LdE#KUCoYzg87=F{}OG?;YR)VR60nzb{<`lKb8RQkY9F#HI89b9W*raY8q!DN+9U zP@;k$#RKM`^*{7ph2bTjWCiM&OaAANDLKLQBvhN^{d+kvv5lZ}z1)^hY2ym)5WwD+ zbLLi{)=M%pGWkD$`2h`8W;VB3^jWmzpMkzde!aE|tMs_V9^FvzdtTn$ftDc7-!b%@ z2Y<kjl4kbrn0lr|DNW{@d^?_RkIZvTYt1=4z5TWC-;4j+2>!%u_D23@;GbDix$TJ< zeGXN;GbuJ^;IJ=IfcNhk?BYf=s=EE)PyhE$hA2HE@CnPjcnE#5KEDTSs*GBl|4z&h zjM6iY4zun*msyH?3^rJnpu9Q+WyEokCg@U^0=J6cH{Tu9%mG(!d@|!k(4XrG5UIch z?`lbtdHDBd4|!3L0_*Sah0r&E+As#dJUvhxmT~s+w)6??$(sXQt-oz}mcIbw?|lV` zctKz`w9sd&|NiJ2L=2(tBGoEF2Mf)Tho{n((O#~<5-tOQWYXjM4GXY8tNiia{IsT7 zC=G-8?=*m=V}=8+DcWD>-`5gpf?yS3<zju5xkKSoNNIdil#!GYs#bf|PGUW#?@wk7 zK;km`6nL{gy|O<}@9h^a{@zZ2$Q!WUOUnixnL<*WH~C0-Z9ceyozEM9@2dmseem(m zPydYgLj@Gk&c}qs90MQj1TJ6~iaEVQYIs5KZ31jcL+!2NShUYKMM-;9;wt~WHV^2z z2y)q?^5KpFKH&zd`$;hCOy(1kR2rXJN{)XXGLv=4_Jmk~SUK9fD&TmS`4H~9VKt+$ z`Y>OPxdRglWYIhJX43K%@S!LM6r_H_=-X-^KK;2gFzZJ2l%9-_Na~`c^pYJ$cBVD; z_s&oDEC-+P+-0r!XB~M;J)wlEi<YAmc{W#W)t~jTdT+O#S#)5vfeoA?039ko;u;6c zgpECGUz-l4KEe^<|3m@LSg6eG3)DbvBbr8e1whl-v5tl~0+QKyklE)ygT#Q+#ECA- zK$PYu_l~KgsNr$~q!N7~BdM&g80V<nXk+$aJfuCpiV(*r0bu1oVZ-IyM}Sp#u^u?* zimHXpUGVP`7LfvT!(lMcE)Oh^=~tMaC2WD76&K4l&e&1zKO@Hk;g!A>xdwJ(RmcQ> zDf-pxCi*%6aH|0NIVp6uZYbz{Sk5(~-eMRStky5E7n1z?o2=0J)to;?CE1&?CUiY2 zMK!~@Y`6a`iZn>><JnU{#9If8qGZzQ^A|vUvH;kue%b{~j~fuimVp-U1gOzoAr+8- z`SJWEUm*td-^j#|Tq{Sp&CckGOwD(!>kgi?J})TkW;h&>rZ{QcX*eA&vH*PlkqYzC zd)3w1%Qb6-Wk{<V&;Ye|oOa4`0Hk=S+w&dsyxl#jH^Tq>T&wyv9;9BKcNA9txJLqr zWep;WE6ZT#eSXt`HheBxQOMNi0JuX;(g)S8m-ej38-@k$TB_Jh4*wZ4EYDa}h;6Xr zJh^&p`?EFBT;Id20`bGD?(IS8UGA|)WPieWy`*Cuuwg3g`}jHlOIStxLwd?H1->?r z+70NFY`ju)-~|;UyVOKt1RY4D7c)?0SAdRIl=$%2jP=+5EF6<X2o631s2iV<2)=#o zv(M9T5*nG8L$r{y47mL3tn1t}F7{VG_JAdLKeM}Z%Xw7Waa`k7@=HJgN+AO~v%|BQ zt9pj!v&ZZyjmuq}^Ax1<R1B9156))s;39S(lfZxpp>AKEZLtoNiiAx(L5A_%&}#;` z?xOIZDhh0~)&T57KnouO%1F&etJxVY>BoToFtiD9nMvT3v`*M?>|0QOy2{mB0(@(R zbSVTtH-j56qFM&cD~6x%snWPzEKpo+qY$AGV|Mda3LxeeD_H(aHYLjDT*hY^Iog|E zQ}R#(CU!e{8_!XIQ?dR;VyjXtL4dCRCHOfo>?u6>ia4P$t^*`WA?r4vkL$?2yO+TV zC~k3I5;!|pulBQqRb6zW$Q5s$<z%IB`1B(M`r(3#C4|f`RMwV1;LMN$yP~^*-o+D| zwGyBm5Z4<*i~B20m>?jfs9KBP?+LrrYCA2(zWFM8`$VZVlzXDn`xp?>Lxc;1`CtE> zZOg&3>lCM;vs{_1D!KqpGgZP@C;gR!3Xe|qP`BpVfaEalOjbwCiiIJzao9%Ka5dpi z&Joc^&ZJ2*AP8GDdR#vQweIBZQcqcBkVGyJ78s5kRex9;$ndWNe9DnJXGfY7Gx+-i zhb%Pr1z=891r)o}z<Xgmb#)p%Ir!7_i|x@l0||#NV2k&38rwLaX8)U<>#<auw~RSu zs-<x?wZ*$cg7qxni<~E^Lf_r?GbldAj>!Fb@;&{;C<O@bpx|E^kW6bXj=lv~?HZte zb$MY4sDz<4Pfm)h$NVipV|TBas0`2EO22v~Gx6T?lR{r)oKNk~168O{FVX@lWOXR$ z&mDr)*NBD^h_02k3e=p=MFh2lUY4a@bd^9@d|E6iP*yo+5WGF|xM!A1+~Ba`V#9hG z-Qts&D&jh3=GDc_)d6Ak;soz}08MT>VOtnI;pyVj7GMYV$eq2vbRskmlcoOH;HovH z9xJMcsLFIObK-O6;qOB2BX)qZ_0Dswe07EQ54+Gc;igotBi$JTUcfbd4<aa2M)R-c zFx|KH1L0LwCIijEnn2#Tk3!g?4#*NnE$;N*MQ&bUP;JAwF5SN?le*YTWFCc(=Nzd^ z>W^(3lx7)`NqWpX&pl~THs4v1kKO05DNGf*SXeV3#Ax<F`?4y2DS+*Ih|!UzWreCv zsGgLh7~aYP5TAt*zhfAVB2pxptMg^wTLP{u^LybcW~ruxvK~9+t?|{-UneI*cIWK7 zA8v!Dgq~!$xuxrX^Y4l$0o4cxG1gukWq)lh(0Q{u3sXOQneq!v>Sj~$+BLh^Kr~jR z!<JF6l=2d*HC{VX>!ZG~Z|f^^8cTdnF=#FCnuB@S3&ypYaX;VnLf78~B!jQV=ZMF> zQ<5*tK+2=aio3GsgDJDHn@u0+0@kaWyCZg--O2sk>4u?4>mbTKrO^IqH0|%a7%828 z@f~-j_K0;9LpCH!E<e$ZaIU^VVO_rZYp5Mp!|VdDKG#ySzH8$55Y-3tLn9h-=!~*_ zTdgKqAV!VxA3gnDmwB$jW+k#z&ij`}<*Qq_A1vp@@~;=SDEE=%wV%bbeT&m4ndBSw z;dj+P>JQWz5ZWnC19DHWem&=*0;fahIfa7ZPrf8qeLw`2S3zR}uPrBotnzNfq>JJQ zaIAUE_sZ+uGGZ}2{T>O8XR82Ws_h*npV1FN3m~gJ3{*yC@9pU15uLZKMPz#?5yTp8 ziW?vkEhgay?ZsOFqWQjSMxA0Qe7O_8p?h^2w}Ds)6Vlbt!H-F^QC_G9WyIwAc$sT( zmxeEo?x#t>5C4LyQlH=x9ktCvxPU646Xf!SU0~Sm;6?8zw^;07_nfVZqIJW@4Yn9@ z5b@I$6yDsx{_N^=|04fK4R!N^isxn)+r2MVLYYW-rRvX&avmpw(#?!&du*Supr1G+ zzh%{OV-vMyu}c-5u}-xC5+9gC+Spsu6H+_ntfqOXEATGCXA@+%tOm6j5JX&w>iZlI z&c@Byq#X$r1LNfi$()LKc^}Z5;i+uhz!bn5UNFAPkR7JH>C-`Qf$r`Lw;8AhG9&if zmM{0!yXgp39B~#_TD!8tg-^N^bH&m+aMzIfrSvzSDW+<Vs}tXw=(el>eqO#7LuUo? zFTF;GL7Yml!)&PSD8;Q&)&&GU6}lKpb-W=GY!h|J_UtOcf%S@BvCxmJ^6n=dE3v2{ z5Y3jiI47#CQ|+kLRzdAiG_h%$QhPXI{*2{r$krfO-Enqh*lL#UyQaLO7=RKEUj?~U zAsP6ZovgoLf4Nh?1`6NqPfIxn=W{UAR@F-c_B{JK$240bfFpq~IKEF}f9|;3MW1M| zvHvL{Fn}1(z5-}H-&!Yvz}tdk8J>X#d;w@^>U=krqBgEx8_Wu?rtsCu%YSN>CbxeI zu-YjZ1bGOo6!2*8uwHyag|*{OO{{~w`0yz0P_lE}7SO6kp4YB#(XyxPhr1boe?JU+ znItb6>4@VWITos&$WHeSq7kC4Wj%G&W%70`@f(dr&*Iw6<BR0V4Ldjcyk07|{~rHH ze9=B|c<gwF&}9>J09JL`*Or03jONZsJI8_e<nM>~Io)g_Q%2~VEGN14;`>Db|It$b zOSzJFC`Gv5C+YUzK-TCg7@o6D_|^mEp9`bt)kp(I)<PRW(Wrl$>~%zHXOJ_l-9=Pf z2^A3^leS4igZ~UrrhGvaz7#5=+Gl=75g)RSEH(IU6JBvgnggj`w@P_>l`rabQ`o|r zX{Y6JPyt%uM^Zd|K#Y_*h6<=@2|r^Ad@HK@h^l*3yq>Ps)Q<h=lVbAQ)f}Otn;k#; zX|2NTgnccUl7T8WmNC|rbLrDmn`x*}`&wubg-zpi#*Nhars`-ZhiZ!a{i?MKhmwVr zX4Yp`Z}+pqvujV{aT%Xkz58O~e(YDPZaWepTcXHnVqV)<GqScCjEhJ=oeEJqd9C^K z_il$F{@S#9Q*(`T{5yVtieGFAImr}#-sIPnNYV6+c}J~u0+}b*+Fi^&-!YSCUUVCK zqPNt~o@iOAv6>MsWM=cd;}P>B;?0VsGN8I!+PK29GVMJA_aU45;ry%FLx6Xx9qZ~~ z`bilqFb6Ya9^7<J=6u@C7dqtZj<Yvwm+lc+6oAkR8Q%>93syKW0++w`aWzmrOwuJ< z%+K`iV>;9zlW5UR9X=K(olFBp%SWJY`cln%x&fk3a%xJVMu-yD4yC~@;nnu-TVgMJ zM^oVQs0)~}30lfc+sbxxj&q-MYbYp$&5c4sO<6lzeEk(W`JM-MTe2^7sr=~m2yF5v zTGI+0=iK>f5LhjHyZ7Q698*9bov0tsm`;zjdxM>aPC}h7?S<31-|m~((_<xaynH+~ z;xMW`>h3p~M*^HHcM|%HYr}Ixm-hG$AN@@ImFY#=aBS2pxhDM7o^M|wYoIOr0FLN~ zqrya6WteiH-Vs^C>0E4*G>?tWv+Kw&DYpP6WV@5^nN)gg{F5rG_qdz+npIYZpng5h zE(YRH?rbX{a-Kof<TLd9K|l&X(qqO0IPXwANi%luhdO2w+QW&o4@z8tInDzf_=C|j znJ#;>;E^4#+%MaOXiI=DGBXh*wYB3jL~9X#XisG@;H>YPm6J9tCWsKzPIcLpRUvdB zc<&v2$~~rcLzfVZWu4(m5OF`)e@Z32J=#oG8wK_3rO6CU7_Y%6*YB9Ri)8QiEqvjF zzWtBuH!$ux$WmnRZ^K}HFaC*lHc-eG^IM;eJt}|F`MS>U;<ZD-M($}whCs!z(}!C) zby%K3G!b3iaw%H)Jo2H1qFc3l3b~+_a9Q6RsHHmKZugkIOu*d=rLcCw1%Q{Q^>)_l z%J@qa*0h9lqw0u;*9s!|spk0+>_(|yr3El{wsTn*x(p23Z&Jw4JA#dQw)g9yrH?Yz zQ>r<_=X019<ULOAl4lpEqYZ@>7I1q2%?t>U_AJeySxd@kJ@N-0rqufIlCHHVJVerC zvI@Z&3Xg1iTCE4h0^W?whVuq?duE@4<-!n@@x~l+dCbFU;{HQ`1RuY$;Z;?wA(L)M z_`*@(Jm&IIQJL3d2H8K4S@5-GDM()N;>63W<Tty^7=3F3ALr`y(k$QwV1F&Lgq{6l zR_y0);PNtScCBBY<lXlk!7p}}3BJ`wD1Z9)MRG>s!OMwC%fzD=vLr_6!SZDe&a-2@ z<}0w%3;jkH>6P=%_p?|BR^82~(IpG4rt~o`WAxO(1K6?UF3(4}9Wj5Kf3(J8XWJ4^ z-||pq2e~uTgmCn-Lgr&F6OnSvj>{!hcMWChY}ic}gOD4ngw1g|&IhH;fjh4^%bw1F z-FLK_FmS;m+E~lfP-IqDN<j~Lt-o3^s?(GAJ#8B(k<t%2>yd&FxZFRLGXpIag!w%M zVKK7n6(i?5yJxoTu?4XGKuEDt*h}@IZ<~4J)L%cKeni(2-gGm`UEmh(%~fxSHot7X z^+hx}j}&D}(I@+UtxsMP5DMXazfrBibCYZQ$=Ljw2`C9xx7@FsMIBVWDOf3c1O&?2 ztH?g-8GC2Yj+KRB9D{M%4ob(U9imUu>gA0~^DNI`s+eS=5qjG;UHzl;D5Ky)681Jp ztZQvwyG%6U4gvGnE5@!iqbQV7P_*J!d{%}OerzB7qC<S}Wl6NhiRnQAq24h#N(kZr z-rQ;Usf>P{FfBjJw0_%E2*lA~!W}$Ygx^RvXnvK&O8Ss*{phvzzz^gZiDh{tAp!u^ zk<{{nF^0q=jQNaaVPMijL~0s`ot77rNj9c=f;&}HZWopOFs;DGL4Zv}`dQTe*Q3X+ zp0~q$1W79rI&;L<i`*~FRs0iU5fKaw#;I^!Err#f267pLJKE%{Cg(P9axoeCyK491 zIhH>yZ7zI~Io^<9SevRYb5Gt9jzVmK>2l*COgB*=>dXm3ZpYkKRd{ZQhwj3h9j8Tv z=A4zEJ+B#$>it51Mb@!2Tl)RYB=g(kezd{bsC{xkL@(i^qEG!Ur_3F=Bmb%u5w$N& zVULmp`UBbnEU=#!-?!Xe0g*?wVkuEw<Sg2=%9>&c-372=w#F3P2c7CYGHBp|tlrjq z6ndfDBLb<}W$9GQ&Gypb<cc^j8s4z&v6#G|)ws_}nh#8CohM9h+`6+J{nh3!C$N#3 z1l7-l?S0)`$le*blkrp60VK-F2<=U-vS~xFs$4bO$d_Ehs60<(-B|lX@wp?Gahh)D zT#)BZRjSp5Q=3#lph(CyT)pqW{^&=#=(&VB;By|~7L&dGnRXbgd)}-V&@RY%#07Q; zx)%NTc~il>;d<^Eww!|r_S70X#$@JGxHCXmdMRWNK$FW9pN})Zf2bz4v&VN>6G-wd zjMN=eRF@~qndK|zlkn1ar<ONMdsqg{pCc#?sB0#AeGks+qiUzVbT1Q+JQvD2A_@mB z{(hwTWYQp*x%Ug)WHU`w<wDcC?j=wQ>;+y5U!B{pO;qIZVfV9Uh?z3VOLh1-#_!1o z<CJ9K_nek$EyOPp)wuk`#-)?e^Wqh9Tq;k86oPJ4Tfd!%cOpPq%3k#!QnZRaYV5@_ zn(okwa<XU7<5N2TfYZc-tfZ(Nxkd}zUYAb7YIQk6>mY2zJT<gTfWIiqAW?1TQZ_Wp zp1y!xlMV&O$??Mw6sQ$f*hYSV2zGROVIf~2A1<OF<ae;cX=JHh#36ZTqLgXCXKDCD zCXVP^oWo$pByeANKj_8~L+YvU9n%&?Z9V8=b*^eOnCVy?xZ?;W=QhEF3nULgmA<D3 z@$7LbOx!a$LWz?Toegg5p=W-50Z;T^crs7}{=f_3)hHQ@Q;h?eY|NW?+XNEdgXNoj zs6+|`0o+YmKehL-5nN}CZd?*Dt-U|{?VJdM1c0&VpGT`->+8SiW$%dZkt2(hH2F}7 zuvM_rkN9EtvW;iCB8+YR8_rT~Kd_+HV~J_#+x>Zs<!witIOPg(UP(T~d*NZrzfnHe z`$;qRsV{oP9>#sEW;PO_Fy-rq*#{1q$IMM9muLX9T62r#n-&1R!rO>8pAnZ_y4Rr` zlD4-P{4fF8V(jBx2>Du2$`p))(Awoee{5Mo&bt3@Mf8MC-vboaVY>YX6ol`yhviiR z4aj-ohQ4Uct7Rm&sn;|viD6rSu+sne@kDocs9ff<V6)KWm>^m1D>*X(00f%>Og#9l zw?Bm<BO1FzACP5?0qGRQ#wJb^i7*Ze3^wt69ZeB+MBVW2l~GEK);GOL!*D^g!gpCr zEJ?##?m+lD33&E8Hrf*<YybsCTga@F_&|j#BQ`sq39xN}kU7yiJP$4Gos>f!e0M4) zfD|Zk*D3@Rf!HXMOOCCcAfh!puN|nx$ocKvd&qX>oRB>Lc`rke_#T~n{OlGz7B<W0 zbq@D>sI#rYtWMJ>Nz}yjPl*y=D!;$cygF5DIE}3ioJc=1)3ilxuA6Pe`8?}|zMh>C zwu^BeD#>D6_aynW#haYEX!{{!J7Sqe`6dt-#5{Pq-wm)#b0A$hf2@iLa4N0l^VrHP z>&C$~z&YDb1dx~TJ#48@9C3HP159;&tD`#0(KL+udeoWArlBdi7@+~I4-54DLf$XX zmF~@}mCrRWLLa?Kc6jIRyC5F0F3TFX;=tEYf@j#tO9M6VHQ{&bpuWVXwb_|-;N(AU z*_%Uv5;fSQ8}oA^0MC#mT6~YbQTD8_4}l$fAlv->n>rGG6TD4ZsI2c0@v00VqV&O5 znoA{ZVUl*u>mBO_jYGhuddc{razi$ZUU(!xDn6JB3G)+7VY;0w@~?dSc{?E}?9nFg z=Z(rqv_ei-X(3jtOvQ!-dPaeP#@H&X1=(xD({q`AxU#^01TE+B8J?&JiW>HIc^>qk z5{fKT>jNq^p+4HEmVIdT%A_EBGd8@lJ@m=_WwpoKiYRKRA95dKAG3PC_6+`lQ@y{F z9V!BS@bS)^xddUGco|%s;z(j%RA#D&L5Iimh0LfI)gdMIlEIYy_J^DHxRp)=59%q7 zHUgO8)U*y;<g4LX)hpjWS5;57&lS|h`Jhm@>qEUik}||n$>5j;bPkVyir3fj+V+1% zXxSu=p4PL}e`r8{R4pnYA@Z8<+jBGWqe5JIh5gCBrKh?J@k2y7a|F$gux~jLbzV4B z=im1X7DcMGT{TbGW^E<24cOm+!Y)B>Y&GwL)x0A*m(ML9EW9PXlbYLp7tI{nv($=2 zC(XNDhYS9<7v$P-XHF|&9h@n;`C~T1h}ntHAS+9YeMnSqg!;;N&oeleC_enAsAt8m zz6LB%m7k~z^5F!aYdv|-T{dDq<R12!G_lYCWE)y)wyT}I;M|1Ugm69o+b`iMdq#2S zHWIAlKPYW(TJPJi9m-93o0rv{`L80oAu{nIxU2RvE3czFV-+NdsIVG}XvAKDVv2b1 zFrp*DS$5qASAp$Yi%}^6WTf=9eL4UG)hQvUpgi=oAk|Qz`_-kC;EGhAzCbgtHB~e0 zWzrEZy@Agr;WM72O{g@{gKOZm7Djt^SW}E|J<SB|fy20l^R{5kxntg}+3&t{Id4G0 z>{pfkQlK|#$B@*%;`Cm}$My)9ms5(j86DzHc@@+NXl;@K_>Szd`P8^@IM%E9+#oP> z5rN9K94qfG<$saUQ{bgW5qnGh=&*(4PEoO*4;yv5{-Ph6juez*(J{9N>&s6HLWFu+ zE=S;+jb<AX_oNxub=8bokd;9?IQ;x90Vmgg>p-kXFSG5hX_#3Ok}3eDzeDA*azMaQ z=+XyA3y*{y?{rWUJ!Rf_^+?fZmBVhp_na}NjX9zCv4#`s5EkM+R~0u7qWjS`{`XK7 zN>8W3=k;U#SqV^8+mfJ&8!Rt&RHPc`(_{Skcd`y+I-&>=+%vC4gr2Br02s^%Dzo?) zYIGy#))pSApcwQ8x2T_8fbLvUqu?IsPbNj8R6C=xw!#C%ymqxhY@BdL4L`~`0cy>v z{A!9^okOfF;X?!uy{Jo?RQ*daPIjW31BG8t?Y^^qkM!N+eh~JJ#unMwwC9AKn%OEh zY0!R`QK7KQqWZd1-8sB!NE%HlUOSnfPBjJ~8;U3OxRtSX8ZnJ+p#owOHUk-Hi<0xf z@t2~V6}V6ZsPZ{9BA&D)oqNIbL7B=n)qGEk+jUtnL9s8*;ixSBqEBHD$mego3n#=c zBSRLKZo*OXdkffMJs#AxL)_vJODY#n*kTNg7W?`Z<Cg`Bp!>R|dc9M4N9yR4_8N42 zDZOwR1NV?AomS4#m!K2q*&5LMIM&M6QM(%_HKhxUSS<wyV&&pT9IZE18(|~l>I@fl zmDO!orWh6$%rSiHRL61`G`l~|<-U;o@E#S9(PrStMzD#0juviVdpRr6cY_SVVr2j) z>n3;`woEiGkD|uSF~NfJiJmetZ$Bh&2?`hYH6a&p!$RX&Lj6IGN5wP-e2=Q~qmA2c zvLwlhv1AonSJL*~+^OxDDw`J&!;^myTFy?jOfcs>g-&QcP4k|S_hZbnSx~n5uQ%Sn z3{gts+`h*6-9`&~QkFo=?i1bKlO_xag=r?hPmbTZh8TV`>=a~si}Bo~RWnIeXiXAT zixhf22ot62+d}1D-y`QVM)_DW_o70FdP)(xDO+%~2A4qbx1+l#gp)wyCl;;VuLlem zIgCqMY(BSSFuKeg@1V-gZ{HKY-_thVHTFO;o65E~;EC2)vsdu+G42$+ZU-^sGNrKK z;Ny@&@cPY8bCXR16J4sB@`7xyt<94qF^V|VcjF;0=G)YGk#<P&*G>j$2*qQFB7`l3 z;*zZ}O<o;57&}IOL*9hMvO8E4GFCFYX!OP4Vd5pFTib2LRSeMzJ0XYo3a??j&47Wn zcPu220pBy1F2bkL_cqTc_Ic!E&%K+=s5<s6bNrNA{t!=eler0+2Oc<xDC(TI5+B%5 z5+n+_o?Dwc&ah3n)tD|fGYspfN_$KNLy3s6MX6jB-%8J;pl}k-4@EMwKGmA-?(hya zq^_LB!wRv-47&|~GyH~?pqsE1wjNn5!4w#{yec=_Y>shAG=)fgMbLv_)~Oxq4<o8X zcA=&R=xU7<Hc_Qo$3b`?W>sE(TiwCF!oI$~A2>TK6GJd6y;PchljUA_BQ<w~3$v9A z8{%sZokVL-`)ES42L+UcdYob_!GeGgao_tz5SAE%D$V^|A9f*CI}QNobMwm`Pf3}k zUD<N!Z;f!ldatX?jDAs*o_FCPwR%u`#3oho%lCpbI<G9(WYM)q83T7DO6Ve~$t{V5 zRRHTXTNj{APgyS8UXhABrTEky&j%0SeTFqINJMQ&*F@O9EcLM9w6G&har4RIOqigk z#BL6{tr1YPY}5|#=~e_;_atF0fLdt<5`~5EGHE+WvB$-ouyMuiyV9yE4l4<XQ;Z6S z6v9k%S+MVict{jBBe-Jf5NfnV&t;sVndf*fXlrOB%7^ejNtnf8ed7k(9ru*3SYjQ{ z0My=X5}wUa)Qd@gIxZyQYGf&F&Xm+_ez)hN#2t-{C!-O-jVvOq1RHuH*=2Ttxo;JB zD?8eFk~k5|=*uqC9i6yjimt6(D26HFvCgE?<SlR(&hihGq(53dd@T)xYR%2Ub19|f z((tOpGLP<<@e1EVye{oE^0_(7FGFpeSuM{aLFa?6^(f(#)5`X!*~Q*;&P<xT0O{;e z|5#|O_1=P1H(vU92&-_{6t>vzMN_xRs|S!mn<RsdXr)llC>T-mM<YwI@;P0QbAujJ z(FIZ{3T-b2kt}p#-V`3AlGZ%GIDVV95M<Urc(?tQp?rcyWdE&ct!kp`&%i34LN}(L zNyoKq@ng?YJVSH>pzic)m8(MTaeBfag}lOrjtCo?28fO(EQ)M3vt4Rvo)m}WZOhtm zeOsa2EW^7GhlHL+$oTJP$TiZO@6#(r!IX$-@pj)-1md|L!6U$Y9Mc);nsXuVHb+#= zl0cQ>Oh?y%CPfl&!~6{T@_zIdj&1l<=bU~Yvgr+#Y$GBU*8kD!BK9ztkM77F`kX31 zLW9z~lc0$3iDy?A8%|dX-}kRDAV(&&l)4}6A0}nJSgago%hW~`b%SNGN2*wo@O~UE zgN-jZks-*743cHBlb7a_Nn2ggS=JgCRm_IBY?BtBBY?&)%;B*Z9>F0Ha12N@OOHQe zadcqfoaw_~zI<#^|1GTK?)qoFCX^P{5&#lj_K-O{e^PZD;=NU!fh?}KwBN-XV@Hj= z>d~!GHryRk`U#Ix51%q2Dn$7B8}HQw@%U2^v?tpxqDyB}I}L6(=k)}UsX^pwPmd$T zmE=-U^9mO_vV4~OiEZVd3xg0djOj?G3SmePDM3-w$~H(wcamTxFGc#_3okB+>LR`_ z*U;9dz(`QFWWT9sQ!9~rzD#vDnQ`0mhGUyeY}2oe4<3cvAHklq&@qz`dD<uv)^Gt+ z!~2-lW9>LuepKRq5{ZZ+!Nmyi^wAYYUI~aIBPo5r!w0R1xcO<HH#ccYeW1}F?_9s- ze=Q`U2WStE19A;k!~J_~Dc&|-zm4}yTj8u8_%w1E*U<~Gr*JZ>G}pNVU@dq)chM3j zekWmavtKC5_NzErg>pDDDY!m7+L$|~pFB!eB6rwO!|@FEj?znl>xRH=dv)TAY?}fe zQRrKZ8-MJq>Qf?D>%c;Pk@(2;zV5mma2*m_-1NLnzK!~0M+N8>pOp+tozcYa&^)r5 z;uT*}oIoQ}Y!4^77D6$Gm74teOw4tOeAGtkUBE|yl3BSgm;yScBsH=SqXTgeJ1%TS zpGtm+LWNP;w4F(hT?ZRu0lJNADUDj1trVTU=(Wd{a57)yYK}=d#Pu{nbvgT@R%x*! zZFMUM|De)(bYio{E#Bd5rJa%6te^>7@9+q|h|#Qa8nQNpN%`E@XHo<XP>qWVJ#I>g z(pmgAK{gCxTh@GwGowibZCC;(-+N?N-90?2z@>h2#~4j^+g65hH&>m;pXb3fUhDZr zuVsy#Q0Je3wsX>Agf4jA?|!+^f1uBV?YBMOZS+yofciR9;w#<Ei&9I*C0;r~KNlTa z4m7{aLBK`WE?w-2Le&C{qHQXd{SWaHtJj)7VQx{xSY@KNEfo-D^pOj`Js#hvdA%~P z%~j?rLSUa%%*weNxe$zXtC<McVa>g8A8K~1W~#QKySlAQny*6fL98P>fw@bKK#Xq- zv4FAlJx*?Bm-*SIZD>_^!ozJ|7!2F6)SIo&x;AN~M;aNP)z@UGm6#zx_=s<3T_JLd zx2e=%qjcw+M_V((3<Ryr+%mI4#U_%Fdv~q}YTh-zkG={$dLw@ypXoyA4i&^U(0{fG zv3!Sf+t)JTodjFtkJ}5RErRCUG#@cbLS+>>Bw>*+{ACB&d^iQXIEXPVy+*N7o(P1i zWbRrlBsqen$8pusggGmXw%im{(a^bOn~)V(mp;m$o0=|i<aU3qOF@L&?6%k{O~`A` zZTTwTtk4BEIJX-T?D<csuv$2XPj61YBARou$?l0F>JU3k*(c(7Kzh{H6wu4)FGC!L zT)eePF4c(fEKbBRJ`Ls5egN>y3&UIj;#p$oKl*x6(-Rh^WVgUo@EPN8#;?fvFdN$f zrCMpK1~w+05Mn2OYTtF&^$B$?)^f-h9ee$_@nUDyrc(Xb4lIsPc+<xuO27^9`M@#F zL#aamdU`*tW2L7@G3BrLXrui8k@{PWIu;607%mwW&;*K9VBLQ{JAafC{Nmktq{TaQ zwG=koZ()sXxU)*PSY**PJu3tdD5%VmAKaiaQ@IqIv9E`~#-~FjlkARSJd)$rAn`%p zfT`96F?uKcd1dXBw6NmV2OdM5L@3JJENELDaRI0SXyeMmY<bit5$xSK2hm;e_tDu= zK7($qC1|1~1PzZ75c+j)v|U)UC22t?6=%q&`^y(~2&~l8QWSmnGwhe~%P!{x#MDh| z*fHj)2u$Je@yv<XT~ZJ{B&9_X_l^-`{~@fsB%+>P&`&<I@gtf#aDb?N7U}*p(;ZMZ zTmpfZTLS6TTN`f+jFg;hX#y{2b7cZZ7#;>W1w84ivYHa>2qRk)?D5cHpb@2{urf%- zuHtChp|iE9e;D8ZW0F4=<ImZVkXe+4Y{s5<?qzr?$rhG>%-34DXU(c;#vAEN&)HiZ zaGF})NhF*(Vow9ecRUIVv?!s0AP5uYdv&()^V}5}nti~sd8`H4C+Gw|g~f_d%O<E= zo~597=Z1n))!ko<6D}iU+)9#koo$ze$}7VEJ!}bnzFt14Pzf*$X>x&TG-+MegV+K< z_ZC9)3;dSicDfP*tv{Ye-;!(<B&ZJSqLsg#*Mpl!a@@Lp$B_HcCNU?mEArqp_h85Y zkiyw#8gNz4y~ash!eZs1TYmr0H0nrXK_}eVVDpAO`)1;J9BR7>`kmbhmorZ*>{suY zw+N}JmR<8%gpiy5qpO&gTAjGsnk=gy+u3L82kSp}U@`xEr)iaDwlx<}CdbG8)H7Hj zk1B`TDh7tv<8WB*!XLUu-KE9&U1_sKD=I_H07+&N81MW<FlAt?O2%m{Z-8RLM~tJ{ z+vRC$(GrR-{1%`z=EGr*d?&FB>R=}+s?mYvxk{~+-`KY0%GS!zcU^wBITV^kilnf( zdy#k3J}~iJ@cRTQ6cLldzRwEc!qSrVigd8^!N)3meY9{`y1bZyU9F~#LT4Ldl=5DH zJ!*9Uhwq&zP4j-iqmW#h7eBs=V;&TtTDFQpcF<cmgEThEP?<sJG=Z@5zT8`~K3fN3 zY^HtIXj{_FP@8L=Z8A#XUt8;hj#SGluzIQ};D*th0z?KXnNU_c#swwMx!2w|<hV01 z1&*o1@3pfxBa9~Kb8LI7w#sR{*kOcRIz|G=E%9Hk4U{Im%Wjms4W*SJ;sbv8oP9d# zeSItHZP@qQ;JYth(V@n;8K<_Qv%+Q>3oDkslVFMnRK*jJJL*N<iR%_GsueWnmCk!$ z!&Sy@zIX-6p8Kk#2)gN%V5lU?0@Tjua(V_W1uEe|{o*9X&*o9yB}O6;k|)RJs}DwC zHu!Q%XTc(ukkVjHac!}ab-t)w;i$uG0+jRmg}UJA+dM}^)VP78)%5Lip5^>Ze3+Ce zi|=dvOJTkpG)$95+OQG|z$|0;B*smFurqGA;G*f@VI`{#Gvk~f7JIOQdBjsqG<O2p z3{FGtr(L~4Ly_TS=v0Al#N0vK1yyw(dI?x#qr{xl2IEoN(U>kk@W1!+m<ODy$bTk< z=8Y^!x1Po6#SQWPm^}KL2G9^vi$%7U<D_V_T;N19$M#Z#j=^TYpw`~*;@i7V{`@je zA&<FIdKqLb_}%~l)Y(g}i<Xz~TF+Wr2<Q1VpSTu`RJPwNG~4i=U`C;iVDfZ)RS?fm z7yrIGtqJbc<1NVY!%5HkHX-hOYa3JdEl<Y!y7+~%t?;TY=BbRa1rv8{lMu*r?SkYA zlkaI#qh*1b&k8BbG-ao9n{v|{W<3R+f@S;^Qa*ud^;D}RfJ1_qJy9=UmTHOxUW~V^ zN8t%cgADj5tn8rm7?%g%$K9NfAqeMDsbwBNG<;-mkCS`1@fOX+<4m7}%P)7X;*~<S zWh8_kT)WCY43T{0)Qk03)6VF&+u(qS&R0j-79|$}439Ob=G>uWuvG4g0!G@quGDIT zz%W`<*i?smtNM5jjjY4qOlO_w+if59W=?j<H>~f=JTWV}^C)Tw69p|uX01p8vS197 zwhj`>fPp<Jek*fIJ7<}_3~!HxqQFh#A0L%&b$-IC%2q=m#51B+x`(oY64zSr&8D#Z z#ZD%5)-X8e&t)&w=?Af}p-W{wDSXzmJ>;`GRaw401|K*Z!8J@*tN|;<Eb%Ejpju8S zyuPcWLo}~#Bav<10GpPMNA3z;h>VeanLB=>l)Y7#$_F$lHS~iPk>e9xuWst&^!)IR zvz&3Mip$-quJrDwi=LsfqrRMrl~R9I{RBm=I&cjR5WkmHfZWa$?|_A!&4AK|re!-9 zM4vBEy__CLKP})SHA~Gz!(!&^8nr)-QUgQ<r$2K_RHZ0cY{2xDHZj`TcRj!tyMTWX z4J)wllP1Iz=9R``KmaSwd!Vp9l$+_hfnVDgZ&CnA(LzpVfWeojlRrBu|9%*pDwL{- zv$GBk?YgfiF#@>8E>^|BIq=>*0bloa1ViiNam)z<oQq}tr`KGO#$B~=e@8q&n*fja z^4QX?>hjpH&y77n9mFWn`(=r@IwrC)7M&K!uFB>|aV8%Twks>FY0qmyf|^up7xff& z`gqTru!>|z<$gl-11%O-IQaw+Pz(Zzf?~z7l-APaw2P>0DF-mOyeQVp>RR67SO|_l zP0)X+{EYWb-CND@t!*o|G(0U(D4dk<oA6@ikh=u49kw7iX6ACkpe{W-Tp+yHD?nW; zC{EP-*7z+Fi-?tNCrcVxfxvdhDO+j7A7}EYBYU}Q{>^YpY(F^YDiU)-0l9h<oMWM; zQlF`Oa3lO9_}=+?MB!Xy9CL|VW+7+rEN}_jXi@L#=eGYLPr?5_$0BX=@$iw>L<?8n z_1mPg!s0Qn-mFA8GsRs*v(R`lnx^L}{?%VJ;mnF*&@^-bT8<@f5;`gZy%yc8)>2?Y z`ZT~mYc^d8zTt@E7<&f&<(8!%Qrd8tPdC3~zUXWtmQGB571&yU|M1@O3jvk8PpNz; z+D$2?*jref?y=*<E$Ej4vUo=@emMX^iY9>%>%|@Kq-R3s+bv##DPlL`i6c<UvDSh9 z6`woKqRT0Uv>j%(HJlfRgk*KJ7!N%@t#$w!EYl{tf0c4QUk5fu*IXOy8Z<!b5u5DY z>fxwj<%7Dy%AIQCd9G$$;P#RPh$+b@U8}iO@kg{a_~MFZfBEJQ8BnGWHqS(HbgiK9 z_hH!Y1LTC}?u$Y)v|Q?*dMdw?{15~Mz4#{pY8^VVk`f5iRDBq<WXe!owLNz6BhmW& zdRNIXFuJASm-)$$f>(AgN{^IgoS(A?u))4GD6CRYqjS>xwJysJYZkuUCZbt!<B|vZ z<8i<+ULA-i2L}?K+|+*$YEE!oRim!3()BXdaAMAOXGeS$eZkFEqg%_V?)BdRiS3f# ze~rvI2<B7u_1sj}K^jF(8KxTki&29NEg6&^CI?{JPqxu&5o}f*@$;ai%cCnhlrBK% z4x|pA-LME2n@?5BDVi%1_m0dVjK<t|sGrl_>&*{{7bT+N{MnTockQG<{w}WJ1$gEd z5u5=ZkT!jhSZ=_DKxdIgO|ya+^LTse#miV#B(r^olg{qq87iG;9*&f#<zMkl_B|Bn zbDtYX{~ksEFXqP8&56N~Mxx1iI!{Ig@il5C4Tu>o0%oN;qOPiJuH$;3>I|%}LR^&L zD%jIiU37`Z8W>f8=qn+H!<f?$TEPtJh9nBZ(|*K!n`%C@ZoR<!oG2HwVPnvzDhJl2 z>OdmL(1#9sHx;h$hjjjECOqF#VG$Mp`lUNOykHv^2dReYknz9XwnTr4T?w-q?y*_< zKpny9X@QKeN!Ym`kRz!A0mV8#`yDf%zvEhgB~tqqj3lytewwbkYfou|{SF7h+$}qs z`|hdgBN9$ed6YQ9szMSoO^1zd@dMdgAbe0Ose(|iI&70ug8c5+N34h*FtX-;{Zr{P za675Xb^t)mnMUON{BtaXm~)HsT*W)^A7e!+qZ<#l7YA^v7!2V<Xvq8NL;^fXPjh}< z<F7<wNavx~rVFGHNI4NVd|S_Xe?Zzb1wS*4g4aeb#+i}DxCE16W+a|3cZ*ud6f%zz zCs4&;`Fe=_*Xt#N*PGJF`S|xPY3Q+9bHPfR?hiZY<?J5=ZA4(r`)K2#qCW>t*}aq7 zlHZFMP()|VMk_0xRJ&zc78JMU-V^3}j*J>8V9-2$kQe{YM+A-M%3zjrcmXgxIo2p+ zsofS6c7=z1&Wi^N^(MB+>^+--iZ^k%RWbH?Ubm#4AnC210zi`0jT;~IS2_nYKXBul zTlt`!In~F%#*_$Xkd~lu;Wp~TLb}5&Kr(cKMPhN`Za=ilm*@f_mY>IBetgf0LjCn8 zQr@*sasB$=RoUq)0#$^aZ!5Z=Mkj+p{+A>H7=KtHO?x%~C81g+gX7;j011E+<T!|u z>R*|UNDB?t(X7Ftgq@Wu7;L15X974M1A`l@yG4Vmk$=V#tRhq}AgUZnW|@C}CUSuT zoeM0V2Yk=+Xa)W*B*<oO9ZD`Zf#lT>Ti<Ya{b$`?$2MsNONVQ|Np1A6^2&}LOAHSX z%$yU!9^wE*|1B4wQ62|&-lkwpch+&l{;O644Yn9Cy%M&$e*{igo_>$7d7|5zuYCIi zS~4Jm(1U|6Mv#gz5&?KI7ckUGd!v2vAE{ap5H#h@`^((@`?A@1C;?hmfE~6Dtg0)4 zfu;u7#BBf{h%$hGEDg0H6;0^+R8x^Y2l|3pXeu&)(h1P;QPP0%ATBY<_%j?H&>@(| z5y2sF+CcIl%&MmBf)$yBf6r?iVJ=)4Zs)r@$0bHUKv<52F#7Mjv>~;40^-Ae7u#1T z6r#ThsAk3bEq>#`C&Lgl`x}lHR{=?c9!sFqEB*j*itoACN^P5gLqw56pn9gsV{{aC z8j)<4zj+`)qzfpl7>Hk}GW}V`Un8KDN>nmPK?S$XtVkk|zmoxJj!=^eFmqrI(A-b3 zqj24ir1Aqc;646ag*B_WBcMc?1X{5Iz|GVdLp$q?&ZBZw9wPiRyPl`WWhIoo7XSC2 zRHd&Cpi!-YmRtFtqVRX50mdU>YHA5I9$dA>on;3AR~kerwUDZyd_X510gipFufHVm z4F($^Tl2^bDpE;#rRKmkr1$5YKuv?>E-+Y#43Yl%nP)eR2LfLJu?g&b&yc(%AgW5c zOU6HhA+X(;-4p}fw!aqP0HWO_l2f%d)6h^**2iB7eCZ!8gmA8dc7Ay<YyFsl(1{Ux zitg@g5SH106rX6+;NB=LCS?E2{ReiO<5_P^i}kS*Btw+dqGamz;1e1=s8&A^))Lmg zW73%S%?CW}4rjNgKY=*%=&T5ANV&mj7(n*5k$#l^xcslI3ru(f4_HV}G=ms_2k&mO z2vk~rYZ)ALVX>UzT!<9%xSdVTOdyX%qYcesN>NAVuuvlQ=H-cdV6p4^y(M?ufBFcJ zdM$w`%NtPJOoHV4YVk+ZZ8ge|f1h>_D4rC6$n>Ym0SOD_S7eI4LF18)?^6K$QzrqX zdTq}F;Iv&MI?k47po|IKme{pI=6odYXUp^Et;3eF@a-0)TPYxjT7sjDcTcL$6E`WE z$4s-5f7I220`64@seK6Y*aj4}YyZbv%Ye7`oGnlM`_?Vg9x{?%$H04jl0MbN0G#Pt znw9dlJB)W8`UsRwmY|B@wp)}*<t2|qQ!G?{uJP#><nS{v+jYSx1Sf|NqiX@;c}O?q zdt~q+cR#l!;V=p~LeT_HW3)DsKK~tMU!?4mh-ZWL?_<yi1>VKYHwl4yNU#JcK|@+@ zwqQK!1v`li+*a#`i^Dg7zCQ6>({jl-XZGMGhTUuIcf3HtB|Jzy7XXXTQs`#iqfXHV zgtrK7_?+)_BKj7a?|trK%;=im#6U2)N=PwicbL}ge`AgW3RLMFgr^|_7A+HCAYYE; zhJknC(liX^IzI%ofbn2un19D0Ba3_qE4dcj7<oo^Jt+zy>Jq!L{yDHUDgb`whubZf zlfdm^Bj%YxNyW&EJRIBXCx4gF|4P-Ls6DRvB7Bi2pC5v5>KO3pTL%k&+o`nka|LKB z9iMBi%oChZzG2p`8A8|UEr&Ow(!*H`?($4URMo)`0lV)EOET&U@>sIvSu=3pg1he3 zZ|?o?&uGX1Yx8E}+22RyI!KFX<XW%Sz(LwOX+c0cRR#{0JCWD}3FeTRXsH<MZ2(*Q zCGy;t{z1vYLSW2&;-Urqb2Y2<I8x)*`Q-o{QZTOV_<iZsQ&_m#6mG9tzWcwoNr~bF zW;T|P1)t!zf(B%oP6$?x7u5?Yqnp@_7K*xl9QtQqi}<4j6ZHuxaKS!UALqm=CU;uI zPR&54S_h}v6$8;G)mzr}qW?T70RY#4*(~+TJOA^bct9WOp{z`6tW2w}coE#kYQNt> zq4NUv-W^CNLP@n2$IV6ylaHW=ev-zoU@j%#Xv0ciy8C$6tTC0=;g^6AIY=K|z^lfF zSA@a-E<_Jh$W{^Z@vA$UHV573-SiPa^tA+7YddrOwQDFPNbiyIXrxDbdwz(fMTu`R zkUO~%NZC34AFBOd=?$DnE&6BlMIbJ`hTEGjz-cK+Luqaxxl9yxuaA6{2RuM@e)9kP z;B5g;lCC6ResK&?{4G}fzl#)97@&Cx0nJNO)<1C;RBSSoKD<#MF9EmVh?7wn%enyU z(MZbZqGlLVCK(0qa2U2t-2Zc5$jBB8ULxOQ-|x>8?*Uy@poAOT^b8)&=P@7YRl~7+ zy+a*ympTqqZhU!vD>ooM22qz07vJ)?5D{7MfKm#g&&ag%tr@Fqo}ltsSOa1kpEb+j z-^;`DoI+Mx$+3_BlmDKhh>oRSOCLrm^y6$r8EXlTX1iacP5-T-z!(2dB?_)nk&?yu z<?aNUj@HR&zTkgX`TtWG{!QAyzEG6~VNMkz@g9JP{?Fh1^DP$ip$0f5iJ|tZ^1n0n z-!}kX=Z1<zgKPpA6&0cHCm8?#UJ2WT160XC<Bahijq~rg{^zp_i6@=7-yPuKV43kB z(f!{={rd|E$a~}w=_qPG;*9_Mswq*1r9J@7xE8f%-h|YX4g5ck+kXcVd>sHi7ygF7 WZPJ9_D-RqkuE|O&NEC|cdHsL>HG1s; literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231109003349.png b/docs/images/Pasted image 20231109003349.png new file mode 100644 index 0000000000000000000000000000000000000000..94ebad9c6e98a0a7a3a3740fe073fe04891ccbeb GIT binary patch literal 401571 zcmZ^}1z223*EQM@2<`!bcW`$I4#6czfZ*=#?t~!0-QC^YLvRaDfZ*=#lK(I>naOwW z^Y+tCA5K@*soJ$=?N$4WoQxO}JT5#41VWM!7nTQspur#zWI60h;7%26^;-}K@tvuV zkeq~&5LnL6+Q`(x5Cjtc5~mEKqA-A!t{xp3IR*(U4%Y@p%;pn|ss`E>sYHtgWp%%X zrFJs-@U<>e4+5{5I{ODi6^Rp8&l0w<Vyt78j`C8jPx<}e_168?sP`|<^9+{l(KdS+ z&}EE96$i{T2&^2-@C6A@CsbNSH!>X(p7Eu@3PhoXR(c{P0Re;#j>RvnrA4Tq(zY$| z<el*^Z@OfUcZ4V)QrtCGFG2?FH9yeGN1iHDB2aed+l*v}cwH6WdZ?GMr-C@6ax2t0 zG72kgb}2V1?A>&rLb)aliI*TVW$<^(6+;1}I=-MZVUH|WkmJkl_NJzoThszUix-yN zs6!V?ru;hw57I1_;xR)bue*Yq`a>i$8D&$yr9FA)uX`u_#NW+Cp;0MHiXKy$OVwSn zGL}V7(53Ef%dYLG45|Y^fj5Q@--uErO^iYL^P2S!>3>Uw&<sku`Ppd`g!Bd(Yg1U1 z^0wANmk~y<QE<$(%R`2z+YOcB)dqAAl_k3bc^|cB*5xibyVO9&w&aGFVLPE@4Tg&3 z<7^USxIB>p&2Xsfr$opq5no0obUn5pg7fP2t~mA_1eUodKX!D}Qd%#BAbsfUNRU6D zQY1ZG_{aH#tu3Tc?1fmW4Poljr-$JiIT5c)EJ9^M{!|1f5wIQ^;vVc-uPEZEKLaeH z{4jw#IVxE<l_Ou!`3pTvecNCT3N_P+6gWFUgI1jGa#v{E!73L$K8;9tPae%wB7%w_ z42I#g01=wCuL-`eoiBZTAaX17eFwk@unTT@ZmVh86t8W3p$tF}Hge2<B+(nZ#4cek z{8waypupB98a}PcAb9XE$DofI1Om;i4FY_`cs#xw*q{CIT^Qmb(2-oFpd#LoJOnz^ zm-4)}MlP*>^8Suey^MopKpY$DFh(NeITrm|7?Csp-S10%Bg9dN`#Rdm9!d$zXg4p+ z_UU5!$>%W{7vaWtJK&#5q_oiwuQp$gL0tO9HHqIdVK-t<IedFzLsW<yXRG-W#IaI7 zhJtYIm%a!dQtG7}f?uaN>=;=IEXb-Q;g0%n##qfix3wK*=456iL|v`%E0IW~)Kuu! z2<7tOAmdT!>b4T;*BrWf5JBgtZb2o&j}N5~jFlKFBs0MTF{@eAmn!YeFWY(s*9QW) zy1Z}jJgTeTZ*fj@U2=GSxY$I<A7~%<;Z^0)Bp&V`Hm+O=2kY1f^Yo!18dDf!gADFN z*3K`<Mcb{x&1K6?x89%?dp#YUm40XX11Qiv&&s~{4Y%>P&+38Hply`%+-OMXz#)35 zn>e{Z>tw#49mBpzsSzwTFiV|8P`-?)&};9Q6Jc|{f8N)C%>R_6Lr4i>sDq;dJ>wgu zgYW~w$?q`}0w21dQ`H7e1LAEbZ=+lDSA;Q`CExF`pCVCl1;sAVFuKvJ#8T17*FvD) zpo!B)hvpLF1i?lTvqasB<H(1X3bB*0_492o+QB#Z)RH(y%H+bhhIt4w#Ri+@h!$dU zp&Mq?vf_t{QDoxmysAZ|6HUl8A2V~nR*Og%WXO6uhI|1%9|7?mbF$|>6HMrrswzra zXsJHZ9~PyrN;-?HxJu#pw#`*wW<or>zi<#3uOQn%2d=?!pk#dd-iy7ye?s8GyYxx> z8}}*S1D>xaBk2!}R#^Nl6~ULf)LEb9-u)2e5axKXoM+X=O&nDyRZH&H>CBXrD3bb4 z<GqILPaz%&3koN+dkNBLzJc@&p<rTLiQ8QC3AG9O3Al-m@^5$jf{TN{1lLGbN(Kju z=ZWVD8Ws%N#+6XZe&mZ`>yI~JuzQsxn=Ydzxg=>ttWEA5!>_<fHS>x{l7}pWIifm1 zUW`+yN!B%|xY#UzuLw7XS~0DpS=6y&&vja6Izo}Im>^D?KsHW3L9RhTR{mISdCY{B zCYhhkKVDW{up}!jpEuW2E~kXE*mmm1%zlb`dT+YCxJ{9wM7_9XilP|1Sh<i$uA_9R z<lRi=gpRoln~}Mq8U9RT-gt$?EPftNUQ$VuihaQr^oX$<DIHB2n66!^Y6h!pQccq# z)Jn#9()Hr@qU?g@!pbtczK&gtTdL)~dxKMoQ$~1vc!^B*C~KNznm!jnb7FZMz1UkZ z=b|I8#gyiZ030NJBn(7#)>5k<)4Io(0sFW6a2Jx7S38Si_qpH4P$s_5XqPW%{^|t1 ztz-#eN;Iqdx)S>C*yeC`>6_~}sla0*uUS;KT9#0@RNcm&%IV7G{vVXx;uf_tJGCDw zs>-W6Y~xQQ*VlV_$sI7XF|r0EV=&0S<8UEjkpxx+jCbv@u(2Ys#U)#@Te3V_7+J>a zC>hlE9r$wgq?)E%wNJFpwSMpF)(h=<AEFl05^o@tZ<xPnHe?@vTvl2ZU5cf`rovk@ zQ?sRltv0K++>kYQGxxr#sJ_Wcs@8DcXra8JO)qf1Y0hx|<Gg0Q*x}-#|JDBCf*7i( zOE_v+A))P%?_Q@JrA?vZj>D8=s12>1g^dU2gr31*|0c=zu!pUUt=RS2>D?vDvJbjB z!J=$oZig1z!}jG4?MH(4a860<6FX;v(@P&$n!jGw<1Jc-E<iRIHB=lC9-&`zT@#`p zL?}j3N2tHIG-9=9I&Y=;%F<~czWw2Qgw~PPt=4_p)0xxB=+)Bhqebnd$=98-oEDE^ zk4C-}Pc9Ff_M-L_5AKKekBwf_UJ(x?kGD??4;j@Ks;Z@$r3nx+5YawD5XW;`2dW1# zzA8H6I;J}6kxFucW6ha?UyZ)ve69QH`NrxEi=a#Zy5KjVgutb>*S0RHxH8&_Vn0eN z<891bG;W$t#L%43qJ#38b`mR@XnKD})P}wiVHftLl$i=Hgc+Y1SICa&M%B;Or`AvJ z4i8Slai<R_d`o3z{Ili8=O*v;8r=dt7jERs-j{U@bM$2jX!1A;$4~-Jr<os811|@< zHhN#lOX>~Q$3EG<TUQF(Cp>0vH+UF<o59GJZe$$S(Hrg7kC~#dr63R|%O%e{djHrJ zwx(o%KgnVG(bSWN-J0zfdO4#bdYR+|Efyg?|2{XNfPd&@KqYECW;a1KYL3PLVHQr? z(BH^%*e!z~u8r3nOhIKVTP|s3cBC5>PpLk|Jm+#&J8-DyZu_NCKX^9wqrx5OYP6-R z_|oUrUJuI~l4a_;s3+n>+7r4$+8ahT+dW^?<VoR4wSom{ZPrIqU7J;FmJ^&-oDmjj z<I$8k&JZ^9a|;8f`GYOaE&JeYhwn&9E&7CpT34;hA*sQGAxopO$;*lsiaZUC`w5ZS zW>Qm<q+|_PE(|{!QMD;Ge$@9Hj?arMOWx*T52X%L54O{8(Y4>~7i!Nwa8;6eN-W4< z=i$YpC47lr)HrJJ5Nk4W)peZ>W}?|sW>$(X_h>PjC`Q06$HY@sP?A!1F8!i1**K$j zSY4+*V_4qu0Y|Q>V6f8c!}R^-!=>`u8|%UaliDha^#bWG>4vv~7UdQ7#pOQ)f67;G z4$O3yZF}iIDb<YVsL$0`EQl;{J9QtK6rC0p&6zgZo6@P#lpW5odCkTx`nKTh<L|K_ zk1s0JV;{sFdA2h+E{{B}-lw22qD&Fg@~Ailc@@?Y7G-EH&qmITjVJ#6;l*)aV;|!@ znMD#VR!_vntLFNC`^Ut3?0QchjLfU_9eyglId|%HMdkC{E%$=H^!6q6$q6U&hvD0r zug0<&`f1#@OWP0Q2wK?4+6Gz{jT>G??bBtKW5-q<L}vEZB^?L0O{c-zarsx{hkX@y zn!Jv5C-Zarsrw05!b>I{NjB$KWv2~XR_E6IEiv}n(~F;4GLA>uWE-{b1lHg62z?8j z_WtoyRq(BCUBy_(ct596?7G=SlYwxX_h~}&;qz7QTG7B{vhnEm@GGcm4OhM+*K35+ zkne3|-eym#mlIo?UppRtnH}OS%sxt<nXO!|y}h%p?{M^7_(`<*>qPUY<@>P||Bm;M z)2Q3ip9Q(Hvi!1-f_K$hC5N;5)~m}$C>zL#K~3o856U1vOlet|l}jg($pC0<^){4Q z#`Y-&TiDhpj^rexaxIjS;RrPK_1ATx){V10f=`?J>M6orNdycy`K3TBg@C3;z}||g zv{!j7CNU3;Metp6e9Frw=?|%#-a+@<SpABcU%wxAfP#EHJZTwwTY;P+*ic2nNLm_1 z4P3*5pdfHT(7+W0@Zp2N`}bNDf)e!NultZ7P@pLY>Yp|;!1wbj68Jp#`TP4tbN~nj z_zxZUxMV{9ZVe62eDV7lvK;sg^iDxYLIU_!(6=)*w6Zs`c9`%Z3IlGy*@&y!gFskh z&mRa0dD0VL{8>{)6$cgR_gwncmh`#?)_R8YE|xaW<A8WvxPVJbLkC^3i=~B?J(mkF z@n0>tfa~Ym48-8SnmCyA601ndfrYH?48iR5jP#7eeDGi}n8(h*h)Z5r^q=m)f4syd z4h}Y43=GcB&h*YK^wxI93{0GyoD7W249v`QKnps1S1Siy7dk6@lD`M}J&v%Uy}q5P zjf1JR75I5vT|H|@2VP?0=Lh}!`g@*+E~fuI$;$qpWdRFhc>aZfiJp<+-?4$NJkNKz z<V;-*EmVa~EdiMU&){R{VCVU({r~Tm|DO0qPnG|AGO;i*|Jn7ApZ>pHKiV7G30YeL z&vfAXZ@>QO{O6DVbmU=pUiu%R_*>3@-30{A2hYRs@22s=>nA~`0{e(>DlDrAd;?nc z{DM#h{!sq?4P3u~B!z#=_YDLR07(eHQ*?niNQ3sl>cQ(>-v7kSA;?(S3E6|(eS~}< zP$l;j3mOjs5AoGkNT`+<2=6N~F@C)aO3duG)tG%+Hoh{Ndt5teSwCwrUa@jEHZnH$ zs%cpsId5aJ{*?3XwYU$||9oen!IH}PSU?riM*r_dov4|h0X*OT-5_%u78r!JmNxN! zxAB1_J%&IB|F5^ND2V_>_4rt|&i`%$0Uy~4^FNp31BDv~g6<a;8u}#hzgJ8ta7Oq) zCjo(O!V38cjE6*rK>oib3V{v?!~Nd}WJ;q^YSt@8voMoUvD8S{rG%0F+0%E67+6+Q z|9La10Oa5A5kVc%<@Aa3gLA{ltOWL<OV<zoXUQh!P?Q4ob%e(5|12Xj3?maX*J}-8 z&-g>UnFDZu%<VQ>!ElkFzup4&z|`haFI+AE7|*v}+y~M?{lKw4>7UN?jDQ?18_(w) z{%mIS2AHR6<$3mh^ArI(+DC0W{wd9Q>gUdN+jCa`bT-L>YH!@&*==8bS3UYQu;Bxw z1^e#_{WUFCI-rO2P>M3ipK|&0+L!(LNhy0)?D2oD?<;I<LI_8=xS5$B=D?@_wjE3e zEIhPN%P{5Nd-I6CgB`zOqqj3c+u9@~q9fz!;Z#+lr#uNH<|_+G%No26w%^K+PB<^e z2D>hc(DE`h)EJ~XxOLZ(hbdN7U4$v;Zq#At+KpSwH{CEq6;n$L?^04N9D$RzH7Ez# z*v%)XPxby44Cxr|v$`X-b#q1kEqUOtz$-{H27Vec>sDG!{!t7HZ^Kv(HZcn8>L!C_ zj|S4Rjt?U^cubDd{WN(Ohi|*7s1aKvCq#M4u6N&dt)(z$n+@<s^REd~{ko#DpZi?u z6#b(vMUg)B_#;V{XZ;4>W%8G6;wGVgROops;8$Q*jK6mt5OEzA^Bblr(~5;L<@Kqd z0P=Z*&9?eQqlxojd&8J>2CHgw_8$M#kGIipZw!iVZoPFAqz)Tea*ygG6rV0zVn@7` z%dWkUhGNFb+YBO_6y%*3S!m0Oh*PWO2k;z96(25yR-#Af1@_L{*Ge&_1kdp*w31$Y zkBTL@9~cZ7MK3BnSzB1PNy#O0t92eG_(QQEvOohVe_6|(WadFzlKj)--aC`B?UJ#0 z$EUnHqmXOF%3<nMmxS2SRNdrcr?IGL$5Cj=@til1pM58sjYVmxT_;D#EIWjV^Ly|I ziV~P|%yw~%FAk}Azw>Fc6X1G(Hyodmkmq>1s-*A7cd0kfbjic3(3>y*K;nRV8lrnE zysXUW%uid?a)6aSBh2J~z4S&zf&69p%uh&z)5*!am3ll#$4_I4t*7MGYf~i3eH5hP zeH2=88|f+K;p>EdDl@eB(u-%=%PB*un3rvgDCe$uFN>v8@5B|n_)uCF-+uhHnf?c~ zmP6~2BAs?IPcW(JA|YCe%EgJNyvwgN-`dg;G4U-b<CklD?s5+sid2pJSW)nf@M!20 z$UGX=Vi5>m!X6_P81#*&aqW6*KwqvWi&M(s_5*xCs%gz<pWew|ogP%SQmI>#5D>bO z)3z582NO2WdZ?~;XxSq~(lBr<4=!bFRz%l!9AQcDTll>C=@}v+b&y!n*C&4Wp%3Ql z^k2vIe1Y|kKh0c%0@rV*IS0!O+_SfaZoJxMv`x;nX!CSY!|&xF>#1JL{YF-_FdxmL zYu1fL&o5cv{ZvI6`I06pT(%i2%J;Jyp<>x^4CafggyPmsU-TJqpN**@(2xs9kU50> zte=MC`bni#FsT3*Kc6amZy4MV0!=@?eY-XL_fe6EpA7yOy)XBse?o3lf4hn-_MTb| zWvK1AGLqn5Q_)6r{?q?tqpjdZj`uUBKYI#2uukdG(QC|j7T21k3EMj<-P2Rts=a*k zX@p~p=;rnE577NQn*3!C`wWn<^3F@rc1LOWLF$u!aYEC@`!SgxXOm$gQ{9^Kc_+?B z3qZS9aHT}L&^S~Z?Pu+$kpxs_RqJZGAlIEE`MR59fyo7J`<PrJR}FAD%zwT>05a;? z9S!?eJ>Nsc@QqeZ$8fPiLZVtYF2#zR6v|mYYdr9CHrUMDPOP6M6^JiRSb8x3WPY?6 znnqdVez1_KaaPePz`NT{NNFz(B`(v3m>C-4$4NmzwNKz$TI&6Cz;>L_n`8xz+X<nc z$_#>Y-n+S_0_&%yQHi0mq@+u7Z>;B4mZAr*^5C!QG!9pq?r}qu$_v3{z9G}*jnAYM zVmu6}s!HTN6+HV~-5-W_K3^b89JR&e5_yHjdS87A!-`Ba($XK>WH?~mDaIViJ6LS! zs{TeLo2_OsizT`2sgR0ELo8!1%YP$YXSXbaKD$R>^mr8+jh!B>mWoC_UHyu%Hl%=` z6!Y9WI+qX+o>oDjev#>+H5i^M<-B}A`E=i7-4ri=>!cZJ=rnX4X73j7bDHv9_>A&B zsk{I|@slPkne_;x_REj-HzLvOM`Sm|l$I5bWK~ki*Q|AS^l9heSKs>N*{@k7`unG@ z4(Ux>4(SF`uD>WcfRQa}?{8id-8`8WJ$OdBDJ=`g-&yG2b+?GFAQJu)7eR2f&_GmQ z5M-zc12!p4G;^aa!C=}k!9OmeS;2dt$y!pyqg6yl(s2o=5B}vXEE`;;I77yLQ*3LY z-$gDd%WLU5Gj-v&CjCTSS+S#TbaGpN=?#v+fFG7jCOzcFAj0?9>WC#2^ACzc2AD|7 zi*{|Xt@xgv;;;sD4WZbjBsg@6PfsbG@=a&Q{9QGLJ4sV@EvGYwvKO*nwdN}tI@O(O zBNG=SxY{m@B<S62T3^XDbJLm!N<>HuI&u5=+>@+Oc{I`Q%BeFR-@6mW=iMKY%6MsY zA87L3ehAifQ-hDqC={Z>i=J5)x643)&$V$-viWXFy+l_#*VRC6RNr!8Ho&o3D=<I7 zTaQ&x2}U(WsYIqPoleUZ#M`udW8{?jRINz&sC*`-k*n3e?P|Id4&OpR&O=SbeXu41 z?Nm(dn6})a0V8OVvz5?I`dx_Qj?Dcct=HaVh35}3!##^x_-#$pvzSFP=@23-?FKp= zY;@Xs=Ars~_h7u6kmv>M_VS1ruGKkw6QTMCB{9(}LQJX>BBw`biK1$k?tJ3~r@9<0 zd9K-W5A7ojG#TFycHGJ<Y4Q(?rqq$xTeZl_-yhd;mAj!}xzNaP3KqvRsHf#)CF}+g zlzm#Tz9Z`~hVUIVIzxy=-O`9UfJr&9)GbP|pB19^Aak>|A%=c4u7bMd#6Be4y_Sco z4WMjX2uB2ao4DB08BaV($z{vD$7y}x;$n^CH8UI{+-k9~m<Mw|tQB_I0%iV_QYN9c z#D<mw+&Z}f2Fwn+F@~0aFA5q4vMdX!Ekw~%n%5U=W3rV#be{J}4D>T;8+7%t#bhCQ zW^>*jWPLkR?}za|-IJm!dJHRkz?msw-zcO+h;r^35EIXvS%$(S<(BdO5dC)Ur_uVq zU??*Tz~6JCT*)J(06@iubVLI)-Ozmu84!O{wXbGW8UBvG^m?%4Mv>0vY3!Y;^H(sx ze&?57GscM~_HvoYr712$>3jse<YnqK83Hr^*xIkX(XJD_^^(!8JxWGqd1#oeKc=|{ z%*Zf5z!q*_2*v)CgCs4`vfJC-<F30r5WxUf(F$)#7#BveX)iNXNcEsB`?JAM1}$i_ z^u9kwlK!mlx^!d*x=!)nVT&R<GEF~QX)giIkf`;L?Av_VI*YZWo(v2FGWV^rCT*T| z8*Y#vrgqCv1)FUaWa`KcHW*F0$;OwK|8$J;18SF2U!QhWf$PF%;ISbs{em`|<V3{G zwJCug@3OaAE*tn!O8(|t57)lXCCCBRHO<)5D!)ZPY`}1@RLTLq7RgI$q|5!-rVPO{ z+bV3u?K?^P>!^uY$EFZUJ>#t;A=2{=mfV%41;@pueuX*R@g&FbIQiS{<7n@mNP#(y z{-*PH5{q<{^w|9OiRO!{Y21c=UcGAQfr*msXKOVj3T6$l*UWZ-zhNr48~}o$B}WGO zKr~8D7SMzef3KkBB<@WR7U%yF!|(D+IV}ERpFV<vmp&Rsy(04Ny}JTJ;hhY&u%=R2 z)4a;Pi(^oAjN?(y+Kx{1&gwn!mN*c#YdfB11m=_9^9#R2dIOk?VW!luq9hO)bSDH+ za^NECKEB;wL!*{MhF3wJw`ZhtzKyznjUb4Z(7KB?aaxsdm?blWtnJQx(S~{2B>$#n z5|5|?i~4d1E$E{mQTujWSehIJx@~1MZPF>E(~GS2sci?|fp#s8JhuuhubcGfF+O#! zwx=x8+&p*Fs-tddfi6hK;|E`~5NZB9C<%qA2A!YMOBePXH@K#0Kc_UOKFr<><hP0= zR}sssUX=~)SBP(Q+LP{g(Y$}vexT;%aC6t962WZzKth-!E+uE6$*RFD%R59fKcG!D z6fv({tW<uoHoxo=s1x=cs-RFj{-`}JAs`JIg@@4fa7cjuKL^u|0pt>=Qz;e*aJ71n zAGsXq`1!TD9AMRkYA?vAMSO(Si>EjRo-l<Rle1d*R5LwQ7={|yRlrD-Gx=@c*B3Bd z$?x4uwjI8P=Ey`=GfWGzbln-)kor=&u^XhiG#lW%S1Ud|@DFgG-!LL%UI>LpUy)ch z%#lsq6_rn-e30{dh6}rwUlzX<6eS$vw-#8~bQM*Pcd}TXuNmP<zzVOg*pNwNj1=en za$Qq4$<h6q%C;fzC~hYJri$JqpslH~COF=t`L%{Iz<vGd_%(N<5yfS`<qYK1`q(y} ztDyh;?w&p9ma|!HgWJ=+3-XONxK#wmL?n?2KCpjtzFzNuv1E&s=#L#POMNUb|1XuZ zQEs+Ui<;iG7#7kuY$H<*4+~A@>jcZ(Z5H)v@LJXL@~Hkg)E-9&<%XsMA+kfo<I2#3 z?4geE4g8<g@aI`eg-i*c-mz*lUpui6ENuPc?s<P(k47WID^LA&-NwthFl<jBOZ!-r zbyFplyE2+`kTvJzvSF$T<8X=Fk!7wR2<s0X{GHg6jyXN&Mckev@zDY?7?kw%@nll* z{T;ua%)JiU7m1gS7}V?E&#0Nx-R@U(B)6uU+kI_@k8D&L&q3MK;V`*0-pkz2tZTWT zX0hbdhRK?#3MnIM{Z<cPS$C6qbFM>6z>Q)3bn@#Y?jtf&d%=918uRV5atCNmZW0Ag z(C4CoN@-PBT7_M4f%9@=*?#=`k2Jwmx_!sE{vp-`GItrkh|6R~X`R)wMq(DIJmM*A zNF@p+oF#B03QWg%s<!h!m1lO2xK0xRcqun=LNW=}vfEH+Ksd^TPr81&riTf(od80< zoEX<T2$>7b`Q7PjvMPIJg`;2$WTvHD`wUO1X!akJHf1U(dY&k;VrXDpq;%Jrv1En< zZTK>d%R-+Qul1AM29u0NhCgwO`b%re9!!aFwcXlg{sb75M-Q#$g?Qg{8&tsZ1`@p& zWj9Wjr8u<M_Nb{oz;HiB+V?$1H(oVsDK4$V^r*%i6NpuNU8Db(9ik=x3_`DAL-hyJ zF;*ye1O&sgje+zalOACjTC7*XSKT;ePE=f&6|`L!8z#5vf*zhw{Xp)_m@Y1~f2=KA zx^jh=cT*(xLRG$gQKF!XcdLi3yS9NXiC#q+0(}(!ImMVJ;`V~5&dMiZPXINM)8Z8$ zjtk2H9_pvl#0<2!(2H=BUJZ=t9LE;4w|nz76iKB~-3^GCJ@dP@mUudwtw26;kkv5K zWL=zlR9nKS<@M87{&wGk0f~DzkdW@sx{(f585^SdV12HaQzjF{+o=|)x~-XQuIWWX z^ODfA^i(HKc^UPK@2@n=p)hg*qh*hX+{1#I<T_}~H&sSfJ+l0;`PvjaxXB_h6v=Gv zX%o?vHT!e|W~x%ohZss)iJ+qReH-QtltiyE(;w^`X`b1!-g)~fGjB+*=hV1lT<ejI z8EJlJegftc05?*14c?c991+*qoyeQWlS)W5^C_CHv^kisE4i(@cM5SixZazl$v;z* z%y)x}WZ>B>&)P8;)(h0wW!-0C$UpIQ&lUH6fFP9Q=4*Cqs|iTF!m_NyA98p$f!lAR z2>>~9_Ld4Pz&>^H%?JaWqr%tIRh>0Y7_*5{pe659E1N~XTIo=62$dcq^det>o9{k9 ziN4jMBMoxtDC+I`g*}=1&gPQoIF$G=HJ_oYxi^(EU>O<yH4am6OPf2Z=g`!l<y8uw zGBaf77>3ThC3zG&C(q~<8q0ItSVb6!>FW6{89ve`Q~~?@_i!~zEa`UbV4@6s6?c}} zC%Sh&8uh<M&9a(U<?5yuui`hfQlQr!U>Z9nQ24rtdOUw;{JtE3te8i+6GupVdr4Pz zI<5N%oMUCuxcuQll;mnZ>6@9E=_}>U4O-DcRPRK=$#dvxWNJ#_Sra$Ow*9SVCXfcS zlhAl-KCv&8y?#tU^{YHvv_3kR^D-JT_Zn-QYB(X4#IR=hv`6uHFS#~tdD;<vTI#&o z?_O%!TME*()ITe%^u{*5l!Ht|Zm|84&susQ&)u3q#w(q-$6^whOAx?xNZr#CK2t0q zA9ZLOZ<_^hI82;-E|1(5m+5RAVj`1p;wff=*f7D|-Y1sBvw>`mPhsDnrC1UpV`=B~ zk5~myi$9c<$wbW%L-oUU*|kWOPq4lHZnOV=`M=CC6EMOv_Ghlqmkm7T0=e<XWrK`7 zDAd-;4p`GatJLrj=4b7^_!dtt(Azcf^Apn872pA6+G17Rk7@DJnZ?=p^iObk9_h}f zRAziGW?OA07UeHi%#4|zYQy(f$(pwFd&i|VKV>{h=<b8MiX?#)2KsCza~-3?E#4+E z8%avSTYS-zXaMK!01;*l2CjRwg1m*WJgpQO6_5aystGLNQ&DX-0!w{F)-h`~*;TKQ zd}2%3ZK<3Xisv;;%_VSXEU&o<EpPa72Gx&AL1dL5>W(>+CMPEF#CjC-oByhneun-= z9W~RWV-`>=i7)p>+i$m0dYMLKxDQGD@a;n{_Ge|$F)&ifv@Y9h?BOGkm=5WZK{$W` zh@yc@xb>v-iRxJ)n6cuY?yaTgm!=>Mgns%x)!TcIz)gMh8Sc1Zrt*Bu3&IYt$58pP zsm-Y<x$H#}N#U^PFh^l;usJsQ!qsM_;X&PXSBL7p^K!?6g}kgIYJ(43BRQ)aE0PjH zt9<p4OCI*JAD>Fr(pLJ7fYMXD-0V0H5921T6vqbNae3N;JaoVK{ylkaUdi>5YII@x ztdP)jM@Y~3WqQoaAzE@bpoM=km%be2fS!kQCrFd{=99`5AtU8Wr;vZ=y-xMG+bx(V z*W~703nDSNIaxKb6q_=<yV$jxGfco)WvaCb>R1ow7R*t9u&n{4!1yeMU2LRmM?rnK zNOP{o$~?Hps><5X+1f*CdI9!MUXz7U%WtTKF`y!)h9Tqyq2l-l3@6);n8-C_!kAC$ z6(}1L3-_Rb_Cr1f`e>58jU~@K0MWJbM9tJsTc_tv?i1l=O&Za@=2i>NNYq0aVK3?n zpza<)?7l?_rMUfe4S-1EMfIVHj3&Z+CWJ^XPc8uK=_&{HKvvtVY06)WwfWjB)GKW3 z$7pQpN989|Y&pftSbL&#6cjDLC}i0q#3goZ4yfA;_7#)(<VM|>z=HU%5m*KSjC}p% ztOXSuD=vgfTL9+z!CcL^a@$eP?fzVe7=y0QaLf)na+laEpEs+}ynj75I2<o664nP> z{-Gi|O-xYz0g3-OgEb@Tp!&CUCu6ABIwdY+>L18LGSbPR8^RDvYzupc<GEGx_7US- z?>tnrgrVY*DH#$r0bUB=hfmG|;N3+~LKC`Rj;<!EV(hPlqMP^AwKS%^f8l;rpdM`F zIOybjf4^_VWP1Wib54hMiNo~e`I6SM#}!Tly(Wl4%zLkjt!0`Y61Y{ie_Ac%tldVg ze>rd%5D^=yFN6FFa|FY48>IsqsAPJjq~#J2>v{2xQA#h`AdOd%l<Z?czAS1%A!B4X z8yENYJB?zcvR6S-ur^oF1=?9z=P=7VT(PR;xSO<#ZPq4OX~@5Pa*x^@usZ-!G7sPx z-TQtFa2zStwC9I?et~;}R%eEY)T@5yue_rdCn35s+OZ1%bzA1jBu&X{Wi@Ng_5E+M z7`5*i4%lv2o05*bf&%kh9WQHp-EJlXB}hp~L{TZ^_ZJnU7q2f;a~{@C8a!UkCg54O zGSU93`OZi4;w2(%i1h&42$jII*J8r}i@|pz11`l@c_4{#nrQQIb_==%zyYG@Zy3jV zd>Z)P7!4IrYE|l^fdNn;O$T)2RmtF6<s655_0z8H75~24@U8v3)V<7^APKI#W{;(} zTXS@2P4h)@{MIv^*b-Zu*f%*2$yY<s-iLX<96b9jTU8dFXC&A0#fHCJcc~T*zyyRI zUEKBDCFMlqWGq^hfk#RNOV30>T#Y=Hmzi2(pJhtZV&y)RlB1Gv&8d_6(?~+J^VaE= z+z3(3bhBMJ#c-KS;d;846WyYH3gaom`2hl{`H6^c7qKc8vCt9Cv6TF^Bc!Vk%2`FT zct=no8ZN=4t)N?ggV!-l)W$}kjH_LSt3ovU&mXbMw|&H_UQ>L!h7BENwYfx|pYSTQ zU(<8zBru}Pn%?7+&NaN8MbdPftdl?UaPiK`{CqXHRyufH9#{Q1I-$GfaGc2fpSAcs zTg&)&3o^i3d=KjvWVS}r%=0xO2)LD&yzVVs0oOvJWj&n8WH<d$IjL5w&28Y}_WZ?d zzDyeR3zz^|O#}loT^O>8Hp-In7M@ZiHaJ@{1|G7KUJU{ciYlRUhvds7Z0sRi6TtZ* zDR}L3YgPiOoczNLiB?*b!enPP``?%@1=RHN8Pol}eXkpRlXq6uS!7}zk$ENE@ClAs z^S%_1WhN9oY%>%+tiPrDb)Zj`T#T$~R>|5IYplXA3Qxs-6;oOhAURmiEh-tGZHgkX zdb7}GI$A0Do_~XK-6!`TW^ReIsO7LsE9E$N=MqQ3rV5L6iT4tYO5KWtfSe!WQt|z9 z+080<OnP%)do+ua-c)NH8HZtBemW}jX*mkgm!>quQtojTC~~LaxM=K*`0N3U7xCFw zsZ*LxF`@dhaZ_GqRE5O4xu}QdP_8j==QMO|n}8&KI>x23hJXfN&_k4fSh@tJrSwgL zgrI1^tDo+HRl<m6Fn6r>D|4Ujuzos*#CqOnnPB<;NXl|$mc=E7JDhLXH6u&$PAjLt z6`88{?=1Q-`Zx*I`ri@jJl6C1SV_m68oG%MB#Bsf?0AmYPzXaiWgxy?P?8z1L4RcB z{z2RI60`XXt%RHu_Gbd8AMe_4)<Oi@`-r?XWOz=y1vI4igGkA<N2%1U83+j7nDs6J z7gw%8Y7LwFH5+Df-6CisiQP1fF#3Lin?0mTQgzbQ+MHPvRjc_;?48g=Z;JSlLPb(@ z8Hc5h3_)w>`wC$~#MC#Dw?gwzf#O%vN3|mX$zHDqs2MCXUQFvzG}b3~5V9TG?`@iK zoibnA{dYY1E~I^$&QjAIdcAii0U}1fqP9J7RfD{0VcsmRfWKLKaUUcxXO^NiM0tN9 z#Nx;u-3cuP;QS4+9ZnXDq-nUDo;LLM+v5@;++T|3Wy)Jc#yALK*3$1ZX&7DCwW3>1 zttFO98*(oem986t<f{wiZlb-Ya%X2zxzafHBtD>1dq0ZA6FJMpPEC)S!r+t7<@63t zcseWEGFm$d_G<~6CEsRKB|}qGV=vj4ypr}-VXVVd@^dN3FX_?U%Cx`qBNM6YrTFX} zG)hUqRFGqk?iG$EX#3>7aNSLACcaqILF#mbZsm___cFgchn~$p{H|Pf=Fat<zhzK7 z83P}t5nV9VkKMfi?)~Tz(kdab<5x%jk;(+mkVi(lCXaN?1nTVUELSKHIo|^|`t45} zp%t~=-QBZES$>HKLf+OJB=#QySafO|1o|*DF{sq)3Y3ldv9I`X_%=DJhSVl@H?N0% zm}+^WN*5KA;zp0X0n7XBPueZ*%}BiIZa<=?#_lCu&{j6!@O2`Ih16Tv=I+g2oY#h} z{L`Vbe3MPPgU1E5#8PWS(NS<rgq&27YyF<lKDHU2+1;DZ-{I5r_E73nrEkw)UU6PB z`;chmYxSmpaCUOZxeC?pD$0>KWT`JW1E)14Gs;L!+mIaE%kIe(Xs0{5K5uG!Qvtkw ztifeKnCSxC9OvCrB28S!=vzS&+AVNv4{os%ZGz$bp~>EqX@Hs`Ia!aJS;)Zlt5W94 zc`_=dy$jpYf-m)7;cI&QizSOxPC^tteubeCW6WwP%h&&qN1rv*H0NpHC@)3*C)=vE z1Ei|%3R8VYIyM2T1JBl~d;hKd{)mRfc=RHB&>`y%F%2?+?ad>^r(Esai-NjbPZ#wv zl}3TVj=T54`8+GqVu)oV`MUaT)wxLQb|Q_yDTF*t-kKOuXk#x<K0<xVjwF@m`A0hE z=uSyW)?6ZwT(z#$?Xq>U%e1R}1=d-IX7C=?K=Jqt=Xx$n?qZ(uuE2%y`gr{YSsFVI z7n@>%pV1C$JEEq2sRm3*RDMlPt4cmmzC}&jD_*7^Oe>*^oNV#lFGr4JM0L<IZK20S z39rEB?vQF?&8}ifO3?Xk2|T}YOPhCb2YA*!2Dte7Xf@QutSjUHjRK@{EPxMTJJ+QK zPL&DZo^dnZ)6IIP>f1$!n9$cuT_N|Yfke5^$4g60PV;r<6t}mxORo+E^boj%OuniJ z5n!}9#mH2QpcPaK(Ahho2dR$>&NN|5jq681VI821gir;mVk2o2Xl9sNS00%A?0%|b zS7S5#9P62>KvnW$25Jc3C7jz(&Y$091IbZI|9qZq2ERt(X^;DnG2XNgm3u)GSHpX9 z=4;31)X+`3n*_v!cSFPIV|L(i4Dll~jCPkns!eh`|I}pl%k`wk1R}EQ9%oVsy5s-6 zB*2!cy#y9XmqVn2fF6VgsoCNb_v`7NVJtm@?@rul&JddcS;j1!e`&i&QK5d>%l-D@ z{CgYE&mtIKqtq*<I%e78r#qopx}k}8zuX*?nQ`VPl=vSRYu`C?SY29L_qtaiC;CGg zXqwcuwtgH+7_5HbtZC_4u2B1oyQsZVDO~+z<7?Zl5)Kw9YFmSAME{fiSio~##kaKY z`7r`Q7%EM6c@0>(9S4R(@e)=?W)TUqn$BsVxNL(NJuV#q*cLCJGXfI}$Z+~V5Cs+7 z3GB$&9<1W<FNw34gano3*4~$|H9zTAt8!O=+b||G94b@SY*Equokl>Q2N?tUzTV_K z$Bu5I2MOS^yefkWZFX*Mb@2PUZvZf(o-B~P78@9OyG;8n@ID_CM&9)|;YRN}DAF-_ z25~Re{cgW6NaeM}Z^$PAIU)npRMa>_&<H@D3atR+L}SQsycx@E_q-pR)%GR`;=ULY zGVBe-@ol6?cj@AGUTSsKH5Y!#eE#<dai%l|W$QM(<_q~WpIbq*jzu!}VNHM;UcesG z{BQPP-*^GwIZ``7=|0rj=gveX{f%Vva=6;9Ad>J%Y;6xF)Q0`?7Wf(ei$G;9R}t|0 za6(=+Mv?m&b?Z3YZvnS8Hot3Hcpx$PJ!m$Ucd<3%;-Xt!i6nMg(vsAU4OftV6EV+a z79r1dDm@O+G=h+28J(H${0s(TseA)8JWhM;w$q$nuGP;Or7)KCvy5_lE5+b+I#992 z7n9+CbV%ZHwfpC=N<awp#;luc0yt#My?=svD{M>a_nXrHXZ2XXu9!n~8vx1s54eN+ z1uJIb(bP^j=Vi|Z4VP7a-$vgTFoU(GlaRJgetyVY;#zLIWD*~~=l_-ZjEzC<0HF9w zHP0WCf<P}!0^nWpEn^&%cqTGbv-2^12%zSvr)NV9L%M+kSV8XBi_V4_o>xrq;l5D3 zuX$W5Ly7p)*Yqi069S1g>ubPbkOHEiqkbpd&!I@*{WG}#{3QvnDKio|IXUp*LIcXs z)uQvVL<XN{*P8K2GMOyjZLUD*@ZezdGuQ|~#35d=YOz$&68&ogq35!pNLE#>KjaL8 zn|fBD!_Y)PGT@hxQVH~!9H|2X15tG|YEsQkhh|=2>imL&J~_ymzXq9nKBHnyb;bNY zORfYar-uF$D3htBg8caLV{}Fa0|A$ViNc|gK5(or3@{}0|EC(uH=hjHUsKm}Gr%Il z#4{TkRpMz?i2>hG@i)uX(qS>jtY35s=rEgJm<lT(0Vz_si&>)R2|jiCYI`-kOBIU$ zGlwAVXA3KrnggQ;X+!$^`!l<q8ORFP>SbeMRUsQ{Lbh5Y#Klc-zS{afm0Q0nlnO}z zu{%Qb9sm;>5d-bNciNpG%ZJx7tMjIlY_V=o$w9wwbGr;K;xQur-RI9G6%qmcFV}l( zo{xxpebzauf%IRpKqifc;%(NaY)7w{<m7oowhgjB%N&5Vf4>C*XM{-B^&juhNPe=e z*&tCs;2cH&=oGT=RBij8?*bgdnEW#bPsRJy4cHb|9N*|@bl0;1icJ85Movt~bFTQj z*jVvHi60&wCNFuxAPn^Ic-Ge2ALoOA4rCegoQupITd=`(lR>zA4Two@SaKWUD4w%w zIo#OEiHPUD{;2>EI?^c=GO3gR=JAub7BX3GZ}Yeq7n>-MCGuvy29~rI35>&WpveB^ z4-3l_d9G;7ZV8M7io!s?gM*Su?3T$q*FWvgb_+5jTbvFzp8dz_w?I5G=6=76A%+eO zp#FhX1BeWE0HN3)r>sTQu;`?2QtjNj>~)WGIuY{hCImD9RmMqJ92EW2Mrw7QA%)F$ z<+D!dLG|c|bBY>$PbUaiPqiP7l87N6@Vs86z}B$w?Uaztjf{*0zg_mIL8FcGTKhsV z7{UKUsqK0B5$rB18c?cMCm9_b4SC7~Y;h37vtpI-tDBpjY^tf>wSJAJFf}y|o7V(1 zeJM0hv<(%3;<ri^J_mJ2(OwK-U-if;^?Kk3Mn}u9K?pOUkN4LJfa51yBU6x<ACBDz zTnqe5f`T-s<kFU-W@e+|#GqTW+kTRW{%3c0^t0&`)qK_);N**uAO$GO1be};7JyW> zv<NTLl<-bVOKDZTA1}>^X7nb#pKgs^532e$E@!n9DmtFj*a2vY1NfC&NVwzk`d2c% zmx``iNyY{n{ZYMK{8|fIA3nTc=y<692{18dR}0odUH%AohlBw9h}bO536D-q#Xrw8 zoGsT}$D~;h`6t?xMFU%`G-p}L3RjB^nRthYRt30=i8A%K=P!J1j@z!oiy%;8-@MWr zy!=t6KeDn3>~Xlu(aw0z=3Yq!yD7jnR6X47SLoi3a_!T)o_vLoe&GN0Kw@6e=A@F| z)g{Q41DDeU`z-IFjt33qX6J;^x>?J!fX8F+Uomv`KeDxE7flP&HezJ?ie{TeJkh)R zydLic%3F@8#Ry$<f4Xj`odNzZ$?TSHDy1b|+V=6&C&=?n{L(7`QYq+1Ex($z+%xxh zy4@B<eE^Q8TBX(zdeV8_-TIK4?0Ybk`wttIt%5xOZP@sXA!E|N_MfZl#0502DFEck z1!$iEWTiOI<HaQO49XK|9A%%W7hMMjQunk6TRT<=nNyhjeIi&W01=Mc5peQRNi4?j z`D!G;gNp#4%Dhe`0s`@8BCnfwZr4Wy{V%dG6e@9^9YJOltjE=yG31*n`|Z&!DGU|X zuD!d4Wv>{3qgl|vI<5qQ?C8Naz30R-21p}+w$`)*KC`!2Ehi4a{N~x~$J42kdq128 z-pZSvuJwpU3g6cQ26PJqAH2i6k&le+J6#ECQBZF^-dzK`l3W*J+3{AH7jM5=L_`Gg z6s-mwAQ{Z)Cs82{Sjz#ED^u0W)9(vE8>Fd#t^bekqkAU&;wQ07;o!P4eV>p2$PzTr zXUGv*S82&-POg`|-Q$B%Nmswl6HQD`8a_STRs);vG9E<>*2S^iFKcjfW#r&|IQiD5 ze_+veIitHT_>%eLFK;*#3ChnR^f>w2yN9G5`h(GWiD!4RAcC{IxgjxqAB99T6jjCX zU7>~L>YQ;#oPGrFOi(1Mj%8=deY*P*Q@mMacxVG7z%{bGSOJtRq9K2}h!=(TB9fx~ z?PrigxntM&;eQ<9nBKDwWzzf_94X*|cC(dY4f!d<lHlc1L8@IaZ|NkKId9iO9e?MY z?M$hv)+<{2)%WC6XJ-IJi+#LaULJaD^^?OFI+(wc6R9-xFVqX{UuQPn{_1Ml21*@V zBw!wF3Jq1IBIXDxgzNb!R?I`z0zQ@q5Nmt!>Q<(y8Fh{j=ot$)527jx5YZY7U6bF~ z|1LG{rUBf@>3od^HXJJp1Y-GNERFZaQJ(Ynz9uReAOsv*=3|uCQ(esc0ni9opQWAs z?ET_slyP+@wz$_rSwdgnxrZKxy<MW5)p9T6555N$Y%9LfKtULnx}+}AS5|LzHlqvA zyd*X=KdzL?4uO7KSqp`4Usvx##;WCh$o5zG0Q#F)PFL7_t`1uyXgV=Td3Kt0lp#dk z=p6$l$c{fN>_a-swH(azyJB4J6)<VKVr~^2^dKTgh5YwS`^<V#p58uW?|0@yo-UHF zR>#kPV`2n@TOhCu3w#$9yx}?Nd~ujHceOVywF3G|<n+^4>?`E$laJ{qfRa2Bvjt!y z7#VPU*as#Y0M}?szvS!E(G`tq4l6j;biL#beXK@nT{SL>mn5Zg*cM3S^`rH^@``w= z1+@p6YbVnuhb}d+np`&BqO@C<`;e7|7ytMhL;FovX%RxiNEV_0s<`39&1vrk6+OM| zs;m9+oIp;P$zmEBnoR&pqq{t|1DX##WM@$~tz@^Gmymq7xwSP2pg5zeQv`Fezl@Lh zmHETF%pSF*N{xp7`}yH2MwNDtrdxEx3^*ID07v#!-}|zLCFY(LO%$x6qN1(W`>-So zv<Fu|^ikfWRLK<ZcXz!qchGy(Z^<XaKU#s&t!TSKXB6yIbl?#2!$=k%ik|X^Db*u# z-9U2%kYiZjX>~Po5|e&_DnHIXA(7|BxGxSUAM%6Os+Ry~Bhd=uQErS3v%;^{fx9sw z6ig3S;}`hUx||psAvAP!Y}X(o4vXpma`uq98FB&kSIV%lK<4rGJM>-$aAXg?=j)fh z0x!m4gXQnl!_xOV1tFD_7Wg%$^9*==*@!b=@QT5xk4iDLZS43AexP6pSMzY;pVhDr zvj+%EPOi<l4>YgEdIZE^@*JCufQS`4TuDTr0yEfj+<xD6b^v%ZUmgy*Ko;FwMG)*z zA1pBH4av!#5*{~yIMG5jZhlwXwaf$?_}gB9gC=>`hp)p!1=^h)K-68Tf|uUn(TwjJ zzqBR5Tm&LJXCLQYVNUAChCz&MN9O5L2X!pR9=L~_=-3RiIyE<!lmYoz6LSL}^Hm$y zYFo*^GS_0Wqdk55jh^vX<~tb~nQ%_Aw2?#)YHCivyO!TpIV!yw4^hw^r#T*=$Z%k0 zVIjZ_#m79x$E<q)Xln^vI3gRJ^>%?a_Z+m3Jz`G*_J`Aq6W0V|&CyavtcU9xX5SML zCc+EL@VFu_R67R(y$V{#&wAl#flu<MKY+Bwvh`v;f`4gU$60SPOGX(#)%rI3iTZ+T z=Y_X=rzW(Ly2sQZ5J3qrQQGVsoqTi5o!$B<F=mD3PUjd!-9MH(HaqO<o$aDih6j6- zM?B_rRVW9*Z?Vr?;C<RhU}#+_Bq0*(Q99<L4u4th2W)4twuPJH&O(E=3c>4l{{(Z( zBv3n(@n8GNg(0_(EmrV?YcFXY1NSjo-}0Wzao!aOlWE%Ck8JtoC1l~(Vr>K}hQ`K$ zX(i#-U1z#FYbdDiEpePmuz14NY!WSAM`B@P-^;G@0pSrJ%_IzR12DxM0r002<7IW! z8}JXn0^G=D$|gfq3Y46-Zh%bd+)a9R^?X#pn4O$(cRSs^9J>O`TP6^h0G~#<Sf8Fj zI$`Q$u=%75LAq59(arWI+QbiuopCJzTeU4mNr$|n90EUiBNMR}1~Oke^$x(g_(7`T zLcAwh;r<X%QnltaBkU~OYaTYAPJ+MV2Yrl3`OF<uBHovvjJg}nu?Bn0QwL_d^aq)J zFA6KN%*3>Hgs%@{UigARf!kh>A_U#vd@@ERfgjYrC$U(<0@V#*$Juv_Z;;h}aj&H< z-x1Vt0wMl%u*;a1qqwfn@4I*{T*e&0Y7`FS#FuGBnbqwr1~!tno7BEZ1`1a+fRHQ( z<ETvGthES?oxcXpr{n(=cClGt*hTl75)%P%=7L_uTl*Bp=J1?-P%{7UNnlO6|MW21 z+UCBXKmi9Q*Wq^@HZ#Sx&wb)uxo-W4h&&|IF!2aZokk5&r3em^+A8f#`n^!WQ;x*n z&UPFGVhW0j2NCNXnzL(cR=YY~|H88<kYyiyYBwBl5RM=7CiSIRX$Rkk7M;`eS^I8c z!#XCHI}>)};(;OOoT*DM9=gJ~+D~aI-YCvzN~t8;J0t^QQdenLMG*HEWQ9P_&c?g~ zmj}G0ame<nY^=#*f7xGPe&=@h2{y>N1*x#Xl7*JQQL;hW?qn0UR4mGCM%6g!rkS}% z0;phce-qT!7@+M_%7Bu#w_gXdR@G64`o>Znn?cKhfygn0>&F8sddK|{cMNt{vYXCZ z51=!_H`wby{u^VkK>uH&9n)~6f~+`tx^FCM>YDhN@W$q3nCUrH{p(!{9N*fpAsn$W z`vQSy;lnn`5>en4iiV21PBKb6udzuJ6l0~o$RGex@!q>2Vv;x>lEWymMnRUFALF$6 z=SiCU&<mjh6#ir#<+b=6^TUGkl53v|#vI3cif8Ky;)g6#_4$0+=qYyV&$1weN-{kc zQgeUQ;;xVob#;H-;lAy!wy7FI7o?o^Rc$uSrVCChnk$aU@SU*V$1J29K{P!TlOS?| zVlkTvndT#%9n<_#r@hAIPZjJhDPbYySY;|}YfYn;&YP_&B^ne~_rKM$Lrlm_ULizY zZmwdhpQ;|Bp!!>?>r%azs#IuxB+lkNZrV;~*?gBvz~f@G0&|_#HUr=yQ(4<=xJaat zY3t2>Y_K}KG77BoKgnli7<wjP_EKN6PT_Wv-x*c85`aY75}%mNv8?*C7w-aHr##-9 zxIx<JfC8ax5XXMJqoW`G^q6AZ?z$r1+?#0Ix)Px{gxqvK%H2lk8G*MAPew+jh3~Y& z=>%|Smun6_<Xnrg!NI|;jbj8Hl5!!bV<yi$M>m9ThnBa<y!B71>bG;HJ+<UY6s%m( zKR6uU^{n0q^<)=X%1LpoJGxEeO7tSIEqTIH3%ulE$w9>Q6NVQ5uzw}sYGz7*gQ(0T zlkU2O6Z3MLs<}Ql0cBLLyzNTOw_#sAOS{7>8!I_mp)$<=RmwI%EhYdvvW&lWE;1Wi zE3t$%YVUQk3S(b7lbpSOElG<gM?Wa$Gl|<Fgu~HYHS4zG3nQGc%XoXhkakA5>~S7; zOFKce0Qgyb!{V+Y+ir}(d8~Ye6p`8dSD0WCx(8_oPuD^)jm=4b51-QM<iR@j9ts63 ztW6|F2nL5{gn|PO`Zz-%wBfy<+V{be)o)=jV9dNn3E#(~#TIvDb2EEEKMcH2G#q<e zMfrr(0`RX%YG0M-Ge7)Jz$_C1(9QnyR(jgu;cJOGEgX-0FZxL!%S*0ij@BJFzN*wN zo-lFHQqJ_+S40QAQ)XR}Z|amscz6z3?j)r1`W8U+wHl{#)0!gkepq#VeM#)N{hj~U zt2E}Vh%+Adm&BK#C8g=)Zp3b(NteHlmBU29N)YITPN%m)azJ4Maz|+2u1E;h7kYPM z;1Gl@8?99#Fj(&f64g)y9bEQ$`~R`^j?s~Y-4<@_j&0jEI<_lTC+XNp$F}W`ZQEwY zwvCRR-0JU~?~Z%MxEcAGAC;=T-@VqH&zyxtOyZcw50m+sJ7pX7Wa8Dgj|9BUVG@8l zY5Q1t135&#y18G;8P}HEfY`aS;e3cDcCIb2&BpH%)!-u45(WL)zqmF6<f3wmWlQ?F zzpOKNyVjV5mx3*9z{tBzR3it00T~0rmJP>96nNz)B~X>BFNlu-<O&ej>DA`|M&RsR z2S}A?A*|a4<x5e@{CDu~x@<<|0~xj=`{-bdyZ=2Hg!zHO1kQBVI@ntAIV8>m8v?!c zOqqUu%y%&?8Lkv0;B&7@9&Y^%Y-@N<w8S>Fh$a69*6U$W;}*C_8JC5mF+rW9BlsB_ zfki?=gpJeC(Bu<p$!k{zpEe52(&$n0K^3?AsPCvP$S-@{?`?Tr3;5fgBGq2_i<1Y5 z`}(O<(ep8L&(o|9^GaY{r2+*~<>$x1y?+nSL}YU*V3cN$&0wn33D+GsazX&2U}nYY zfcO~Z=(=4GLt4|$7yh<+LG%GoE<xARANrYS4n|IYSJ_)~4mu88=C8AiU5OFPMKSJh z@@1W|>7I^|iO<K`ajn*?rNB(Q-Pwyk%I2#f0R_Ai`pyD}wbOug!LMdY(0Y<K3ABG_ zgAm$(fgj;a@)?Pe?1oi&VUQ`Adn9W+0b=jo$sdor4CDXc&d!{Y9G^9}JTZ?(B6`aj z)gJt&4fBAEJ5*w3*DGDgDw7}D*C_e|yIIad5g1T}OI8aON=8DouQ(%&_F@nt%z0MA z61)KA*-B%~)2-Ub{dGcBIylKH-AV7zhmsh+EAD-pg<{F|xqTOQ)+nIHVonQYnRVn1 zwblepriZ7WcKN1Mg*i}PntNPSAm>|qj=HCJj<lre2n5J?FW{H&mZgIUq0gU4PO#(= zm$n8vmX{_xVw;!4nxP664j-oc!4suGuN{&q<~zF%*071m1XHcOzh@PlV43LugV1d< zca`z-1mzg4ykaEamSkIezm2}$wgQ2tuE!HBKmUnEwI^YTZGVM6&O;;bs~LNsX63f5 zV#LC}ieIr<rFFMXDWL;iU)-+cllN2}9Xq&qT{+bQWg@$4>25Fk-$^VPBx|N|G28Co zm$7jEHn*p5;Sc0oO!J@0ZavQ@+o3HA+!%Gfx@-P{z7>GP7@xbVQgI!!mRuXGSjbn& z82r;6q^}GgX8TMbUmtAxtPCtl!EA?N9Dgt5kDpV&E%=j{oWCKk3Vz(HN-~(^XGNI( z9z3}hg$^W!3k5Cw&pZ&{D|Fp?SgHM2HmWU?60cjSF30uxJqptjZF{E;=df2g3<K6i z>+w!~*{V_brw$Mf)vvwze1!J0UAc`Fc+~VwXaFAmnY;vUJO2J|Nk;4VW1gI>>rNk2 zHkQVIcYjSw82A>nkUB-y+27?+aKA&2zA`t_FO&;5x;f!X1E2n}#puK?yqzNo4Aunq z9YQ<TLib;gSh_pnl4!(u8CLB7?%oGK`~ULzYt+C!)24ABuVeL7DCCmp1v&aXz_{@P zIDL)caNFnN@UJ?Fw(t@x&j!yBxNVr2Yl79Ph<z=R!}a&0<P$^T=7D1JP-Qu*q=Dd! zC4e3OAm%pe55ld1jxCw(G!E6z8Tls=DB=01oIv6MC7cF@)WEPch_B-cMk17y>m*f$ zoAJI$Pzb&0Y2^|<{Z8IPdt$f#Gh|YVZsNhFn$Fwt+FKwAW<2LigU<8~jQkAy6$fN` zoqB{xaF<*MYH)DIaJtXEHtY`CW$worlt20#=fW_^i?eq9vc4YFaJFSLcXQ><3mR_o zhNEm^wX8>4;lF{YeYlXu7$~!Gn)cpq+u@We*vom8QtJ>AA}85+e(y<Bg?7|m17cV5 zdX{gdkQVO@n7A{?$dQ*1&gETBz(;X<4{Whq`rgSLk3`roJsh5W&g#2?*G+KrFWiiZ z?Xw4<taei!m{q(Nk<QzGR32z1mKqMb;Q!wc+|1HH!|dEun5>Z~kXr9;^vxK}*ZGXs zJBAl5T-vX(zp$Fd6pE!i%{!O=O_IJ@YG48PA$t{u!NOB~56Mh3aDiN~eA$9(A!ATc zMj$IRJT@)H8%WYUH$Xm;Xe;Chb`77CX8lJ?zzq<VMI&Yr#|G>@-hIolISb~gEKAde zm$lDCO7Y7By|&LpG*TvT!(l;?&0m>5ii$$Gdx7m!%<6S}sdEnYEkpCNtq?^`?0#Ic z$~<JY7YL(kg$lxakh3YzMVye+57T&lZx&hp<?Q^;Fp&t5{>grzEJ;5Fl#A@<9IB3U ze77bY{am_u^Vz@-fJ&QHq|*;0zsWRZBOc+PJ7_tAW{Z++k8+_gWwW0#)uz^SH>OnG zCzW)n=qo+GzSp=qHciO|`mF?X*i5>uGicsM;+jfIJBxYM{6I$gYN^8Hzg++XVZWON z+8IkUFn=+&pO7-yT&&djH%dYKkl=ryp574}2=5WrFC%P*Xs=}dTC>pC|Jnxo_UGY# zUh%2AK;aDRj}>jTkJSWF8YNYN{%?FjSmz(cT(u4QZNsPXtrUL7(-&kfb`A&;@nENE z8r4<nXbSAaYFRNLzlJi#u$0aQ&khuWaoFGOb#qtlYbHL2(b)W|#rXyWMH#>3JE)z* z0f|6sg+}5)^q;Z1Hv`oi=syZ>|HZ*PZKyJv&W_=AV*3+ZYcwS6tFO7X>$C{fDO*>a z`zNrh_t`6Gl*4?67!Aq)ZdQ_r<NRRF>sMqGeqHf?9Em8t%idvf;QhsgwPcrUro}A4 zPv!UrVi0Cn7M^vje;`deOl_rDCvP@<lD{MIXrJ~JlxDx^d!u`mQv1y?9-q$*GbU6T zDni{tGqeu#iu1huH*lA1R4Gy3!9E<epWJ66tC<qE)6h<hJb>b6`P$w<7vk|gj!Uy0 zbq&446%Ncx4tfnw+e-cg<=^0+&G^<NkG8<25phWv;m}VIEL3Si-E$Kt^a&}YFfb*U z(l23MZg#j53snmMb-x;~uv7t$dzb?e0%GeQ&Ek4j>N+D*x+F;jazfA>vd?exL>U2e z5Z0bwugg#O%YpwSxPQMh0N5G$=Fg`78GDHPb+dF{mvW6<#Bwo$z_8E0^Pxr8lFCXs z;K0ta&x4nZMFvS=GU^8k9(8Qp^gApm*ntCihQ>YL${_+#ZNRawfTlCPf5Jr`G`q}& zptzPEXpCl;QYdJ43W0f7p36iaYQN8Jbw|uNUbP*2jBJqnQ*U08(`H*r?)l%mR-I3Z z9(cOce;33Ei$P+|o=)eJW@wl-Rif+pDlMqYMpm51C>W(w>vh0&s#KV!m!6Q)3c?Ax zE*I*4psL=>(koYp?we`_vn!L7RWDjKzPp%~gJqUdl)T_c1-I}nR}|d|2QHMWI=45K zhFQHD3@z}sux+*G3p{(C`GF%cZ>^sr1X2BWBK!T%(kUTW$Nw`|rkf9c49!?&#T>3+ z2RB%C>hI&kWNAdwZku@0@}(R(?-CY;Ty_o+|1%I|4~7gX^t=PEOb6b#11nO6dvMV( z%?UpBmo0#Ww@7Be$%R=ZcA+e~l;gXmmwAu}6-H9tJcwxGWL>p1g{3JTOZ2}GBRMj> ze>1W0aKFF%|87P9>kpUxQ;2Ej9DK44CsHF7hFF#`o6C?vs1&p5A6}NWQ<T>M%e1I^ z8@gM*U*7ao$SiNb0n9FFv>=98#*kzT8P6Ys4uEYXrP;Eh^RD-6m7*BUuJcC17zHgu ztE4tu0Ruid#*H6{hyh&!g+cbLIV#`?p*zSf@lOU8riZ|k^AYBK+>~%^*(6E1nEd}1 z0{~xjZ3xhJttJu9zC!g=&#1;Z+@0YlJjin0Vo`PM9F^Ee=d#O2AqBcxi=`<}wcU7} z)@ixbR;=QcD4DaQk;4n^F3WmcKS{K@Dl#nGKZgxpiHZRuxC@abr5f_e$LvNWCu=gr zM601j=Krs5^uL$!e=cT*e})j|DnnI;O1pgrzQ;+Pzl<^5B}phgYM507cx4B;YzOe5 zlmY&b>Z^2Vj{^-7`gZD`lke{+cg*!Z5XAW98Vj|Fi}3-yto4kbR-ryX^8-b3Hh5E9 zpj|@FnEd}Z)&IRxCjM1zm_A5WR787-ajMoBQJ4(?Nf}%Gp_Tok6-K>wHA0_fqkUxP z$W=)=WTIW{!~94_RBkRKO((FkD)of{Gffeo7l)-Ou|!d-v0MsB<hyDuzy~@GE;KRj z|G)NZMmX?4{Ru|Il-hNW01WAAt!Hm+=>Ah<Gp)~>x@;R6I(Zax1UF%{{zBo>^r}7q zZ7NEj+1J*q5}Wr40pxm&afE!lG(mxcyj)sfeytn{ist+saKer2@9&R8XHo6njsIuz z`9YkC8Xh8TOKTrjCv3S?z5bqZ`af4B@DKhKeGvGwyjg+)O(G1<{Fg3_ZKr7gR>NMu z#dPgaLVi9Wpu;-M>eLqiiDCr_%~AS>p`lB%ZquSS$RAai4#J-&bT`RnlpcaeK>P9f z03TVy0Q9`F<8pjnY3Ox;$qg~tiQ1^B|A>PyK+_m#tp6XQHBOl9A4(8rzu#sa7Q=Vl z*#M+6u=LrUfQq*J`^`w#eoCvVy1FSp-+<GjhJiOmQv^^Esk!+b%@8OH0>;=GW7oPH z^7Hjh0?!6L<mmJ5I(4<dEOZEn&}ow%B28eU-T?0+NqVGJi70Flv+pFGZc@No6c0G{ z)j9lN{6DV0IW<r;!;3J%ql2EeX6pR=y=F0OII3(JcsBpt(|$!9WQU2r?)mCAY_}_{ z{dio*iySS871TB)Sp|Ue|L*yGJ=ec$XlQ`U|8YE(1q8!&fu1UG$LoREv;PZJ&!vC< z{Hf_>g93bOEOy#I-&?<!4|D$KbCLmm40_=lUOtkv@_Dccx$9!_qeKH&!D#sMzu2i* zEqo;J_Swtkd`;UUr;kmf?b+*jw>JB5S`~^UsLlb?R&#!@>dRU+(d8DZ_jZVC`7*xa z98EH)XsSiy(g_f%u3WLMxb=Gw@@yqWSi$5wx(D)$Rn4mV<>j;#u+$tvY23*&%ev@E z6HPC$9!(|=_jANQ?MVpK`(9wjWmYKzYM`vgf3pfONbjRILbfuZ#sQ;S{T27{r(z6P zF6<9|-D5#jcyhlyb9J~N>t2mfZ4h-eR3Cg@EM26vMFv33@)bAvM36dnidRJEi3NnM z=OGtXtF#{M=3(w@mqfp)GCWaS3%4R)gWXWw3UbP?ze(~9OE2U=!~wQK+9tq0!V=13 z%VqoZYKp*PADhgDPRlZ;ZQ4||DsdVO*!9W9Q7pGDn`!^}@rSo3mQrbCbSoyHcV!3C zQUEeM$yr#WuVEPs=4an*%i7C~nX&Kjtx+1`wqnD@0`vzCnAe37qwT^$9~O_-nVoZJ z?)d$))J}TPDN?AVF*1-oeg`Sc`HYArpL9=yta=Ms^r)Z2epbkVLP{pwTx94k9b<Zz zJV}G`YEO&=T3wOI&*rn6f8|cf94vM#NG&<vcf3tf?(!_YeVeXucil;<HB8r_N^^7} znqBOZST#0Czzarro`t9t=9}azuzZjYf2K_=c3G}0{&XYR9bSA+!AH-tz}o6^%b~RN z<yAky@(%fiZ{wgsa|I_|J~>lt9ymkURiZ~|-pbksUJB}9-coQ#!AoJwlWc)ob`9`W zijNsV5t4qjRb1*QM^Nk(Og#--M0niHgU*npE6qctf9N-i#E((UGu2Q#R-D(F>1wzK z7!&*dZ?{j&RV1TUy%^`ZHQU(4#2qfH*Ry@wP5^x8{!$|w&`nKeHVOdlD0Kd(2cMkx zXNwb+DB(?{^K*Z9XPWzQ%zmRBspDhT{3X9a;tnw;_4R8Y0-lsqy)q9)srnIaXTZU& z5NK?o%>NID#(|OxqJ@@KEbTOeju1CVJ=s;t#|RGq8N+2x8!{Xhs0~yfJnJ1tFm)j| zpB@qJYS(?@jq{tdUl!;Y^C|E_#+i}PHLwa6p@#}V&QRM3qz0Mog^S}B^Z5wgrfjvD zA&c6$*=BD<(7NXbwz;|>R|L9+AxM`C1JnUhKN9GEar3TlqzVg6w#g{FR%%+!O=<#a z^7kab#AsolT7SnFvOEtVbHjq0A*4KP&~8e4D!GPbAvYm-4DR<rbW|x+#0*i!?PY6b zmDAXo{;88@ecAMH%7iuRaP2?4U!=LxH;=$uU+HmBZ~1v;H=j5T(c~K5MygcADiI?_ zCT!t*igJZG3Z{+>M{I7603mgsh?11ZuFeG9dR2>_Kp>9MG038j{bRuRKKdT+Q)WEn zuTi?X$;*`jx<xy)zs*i=xO#ZQ#Hn)wSHU+~=nxOaD=mmFrY42r$}`-I6OZ@r?zZVy zV^{NjQU;Z6EcO?Vb(sx^pVcZ&m|ls*Vy8>eOCF*Z%9gJX<-NZvJ@SU}c9qi4QxT3< zMepRc&!OIv<wzl<F3C1e;^E>VNKl>vZe8zjxcc+66XP_ExOo%Ket<D{HD{NLTlxYT z2H4<0QClFkK%WzOH{dfiy?t9PJi@SD_iY|#enraPimRJF9{(zk({sjJ9*q5Db0rX4 zKD$LGLMOhIZZ)zQV{oc?mS@Ai1m~|fDpLoYv#GV6Nis2+%aO5(b+-orLn?W6{1NdM zBhgMH!nMY9lw7vQ0^xgyy-#4xt9CCq_kA{2TOwbz`r@8&?u~ZU3u;GUo?SKLlhqY< z?;ag8nhX94R<}27x&55HG%Z?i=7&QEYn-stKO_x*LFa`7`Wr4e(00Dj26eDKnoLhf zm}~EmeF2W}rh9|ow+pI@!QnQ|b-*E>OTPiQdFuMtE&=+1lnSG!<UA4aV1K}ZHfO)q zB#<k(oc{4Y&<M_{A~h{7>(dMn2{hx*cAk^2Uj*p9G^BY~vb_Qy6rn?8VERo!k_q>J zCrPD$*>#Rtiwt%I1(c25#On;(M!a1-ViMf`NSs3>;mF)T<`#Tcn4iNYlv@NlMuowB zm{31Ijc|Y93Z%j9Yq;n+bDyXaVTCFgiAjZtU=Q|ZNI*ByzLrImJ}iNfD=aD%@nI|B z&ML){Xp@(#C)4N+A(8Qx?tpxUL9G1l0-{rN-0M*%BOV8VQCmq2vP-TkP7~W5<DvYs zNS{hsJV8tyMhTt@wudE7oum&TKe6yTLj!6PJ%V8(v*S`#Te+u&)5nZKX}VC5*&_ZZ zL=*WB;d};2_x!^O!POj&AMVlU7Bv+^9Zy+~8q%O2AQmu~v4|_*#b!E@L5R_D{Bu#y z{NNPE@huZj%Gu%WNlbG2nYpS$ks(1*bznk~dGFy`5rc+hFbGr(;dH{^Kt3v;0tmmK z$$TeFiVV2dXA`i_rrKaCjTpwM00?lVZ)DEEkTy9ilMV!8S_bIPw44u<^m_*=OZo~w zXnQcfC&S*0hlQ!HAxTgNn3rA{y4Z*r+hoK?%xIiQ*>H-9-1E`v=lJfryYDA2H!3C+ z>KZ`W>W8^%*KQH5Wk!&$cKNCWIkJ$FU6J9pc_)Fe;F1;&=OHYBdbXxIli}I6=2hni zey;&<Zw;*#2lm)2Ux`n;A8GooQhQoYH;+()vswhKPo990PxZZ&R^Z)JSN5J2V%D>? z=K+>AY4AYj4s&2))(qd-TpQeb*~zkvt31K7RWEiUL2Rx!m;_T{(WoqV7Ejl_Yk5cb zuuThuP|K^9tIVU0=e$#Mi6+09-jZOlTqXZmoOF38s%hJB>-1E@N{aMZ^=gnmsGndQ zxdb}&f4&1Jkp@G%F07%(!_SX54d0!%OFzTVRySDSIh_nNVm1E-hv+n_qt+_7x;){3 z7h1O+rYPSH%Jwg67%;$NF(OzY(tk(d-T^@q^8NH`yJ|o0zYWrsNl8f=|HidJ9Er(r zd;3G?snuaWDh-z84(Ot!0$HQJN**5I>cW)cdpsx0gz@`-XaN@r=IfOBxuWf>IhUud zGY{H3E@V)I<oCSdy0|~*N3&#6`N;27t8$ctf!y*@Nl2&iDAwLlv=QJ0AZy&#dD?0I zw6p~&iif;BypZ7HFp;$6*mYnQD;%uxd<zRsB!X@A(c`M-1(=5xu!i}jYJgLA5e#Z# zVVnx_KZ#K+rTSR?;px>C6d7l`q!P8gei#pf_DdLTa_S_4XFQ0-arw5$3irGi7_`x8 z-{nCwB&VNfRS2+}>yX(yEaCwa^sy2v){EgJp;tJZbJ;|7#F;Cj>tQY;<ko48zAhRr zI;ky>@b^@WC~JAAvKYihW0tR=(v(c(-yo!5*T}{Jc94Gp474$?z&C?k(1PH}bd70y zj)JMdDl}&}iqZm-xZ##SjKEc|W(|;89za@xXpr`>D=i%8$Z>XYU4uQdd3cTtit96U zra6{}mIRz5MJxUy89iW}IZ>#Jp?$GlILKqf$kP#@?c*rjj5t?<Rk8n`CG{>(t~(X_ z9Z0=1)BX1G6ny)X<C}k8L`$Q7jge(r;T`D%kqXyT&-PLF1oH}$H{Qu)@5k@qvVms# z5GBZ^wU9r>f|*29E?@-La<aX0X>#7p`?JqQS#hCH4Prgc4-Hw4&~;g&P13(`5hre} zaUz<vB=mPFcDW8<Q^M2kx!Sa5Hotj%QiLe&DF*-m&0s=qOmJ(SeX?yA<hGQz4HDW| zUh|n}zcBxL2a;j86Ys%sWgLV7bw{BtmBkuo-vX#WpJ40vS=iU|j@a^9vn|Bb;3IYl zR_~!rE!cg?`e6z)G@fpPC6kYq$;fzrjgF-V>R88+nV1m!Q~ndX#^PJH;QMb7#7KJX zQbdsi)F|aM7Ci9OMgPFV!5!3%5GFzsx(Q=4>Em-81J@NY&&wu_g?l$CVZ6E+V{=Wr zu7?94sLnC#bTrAL3Vd?n1KoPZK@>^1Ss-ClgM!%=c1EBnvgh;N4G1kp519f0Deu4y zg>vc(-j`VvU0z|>Fzi1|fmCi23bQe}LD3(OKLk9B*yo7jm&6mPi&x)Q*bZ~W5H8Bm zHsDuuqkA5zBMIJtCK*K(b77!5o0QsYnaWVmph=VCTwf6#bMDsYHRg|{i#a{j2#Esp zrewB(5p=P$*gD5bP78mGq7I3|YH{eup+R=G(cm4WJl_c(<Yac)2>tb_aOGT_oqXnH zTPS5s)u|-)A`R7Z+7cBZr>1~noJDg7K`@AKy4^oPQPV3FX8^6DKb_j2Ce$D$Iq`mV zNwr+s{xpC}B*Jo4&A4poktt>jEA<;RT+>!pE)QU!*Hd0T>oIU%)+_|j$*Lb(wgr7E zcgKB1S^E7@Q)iuL%d<JHLy1N3N+xus?NMdWr7|}V4WedLN1?;`UZSwH7;{4if8U@# zuc?FMBD$=g?$EEM0a+oV%GH&o53X8A0-&<gllSQA-E&_syfQPOSy?3dnzziK0YDf4 zxbhD_hVKDvSvY$+zarWcNkFWQcX2{ZX^Y22y(Bzqhbh}Db%Wmu)ijXj2<KW={`kqg zTAwahhDoa*7G*$>Xakb9dCp%>e7%3mOD$fcG4`|@FA6I3I7`XNuzAB+tpmp{a*-0t z0$ubPP#rca16NBgK*inLTc1Q5MLOlGo@*q+vk1Y%$W;abS7^9K+XjA>54c*6;a%fs z)e`VUJ*KKwFP)F!yjq(l3Fe#Aan>4g>DUkfK!g9nM>;klf*PO*OAV)j9O<)o*K|cV z-cvfL^;WA*n07ME+)-on#4q1B5w@9<0G?`Rfp7KAO2!iyZ7{@!IVBr)MVMX|!R**8 ztCU|;QyZ5O6gcev_HA~k8+<!|Hd?FrmgWHu%?M;^o1-Hp7>WsjWbK`0wU5@|qs#fy zAI-a>;yqD8L11%nxZ$6ny&rlr{N%ki2*p}LZx;<As#5jo_1*IdeCa1ZVo<(VF^4c? z2;abQj6z~(xQ{Bwi}asrHRu%<bVx=|{2x>m8110~MM!)HT_UiprTKYZs9X_R#!0~P zbJVP%9rntOz^#Lf4FU3D<fv}w<&N{HyNj{fUpc3$!Bw8Cy8Qcj1=!4Z@{5XAo&vd& zqA^Orx)=tfv;8UW@0n)vrGo_%Y3W6O8=3OL(>bo%UotZyC3>E9`JK89G%ThKay_Fu z6p-RY?cGg?0e`ejd0|2l@{XIWawsfl;|zyu_>>l_=p0U)Gw`6w!cA#y0W!)ybxGzf z&Ky#%wG~u9+U-IgFDcZ|!6SJPs&CK)APy-JN*E|TQ&!ic63gA$=K%8p0~1P{J>0Us zlVgj@wsQC7?0^Vm4{JRoMY+CTOd;8m(>g!tB?&Mn8`0!DDl7e(a9EtQll3veowHgF zoCi2Lsyw=c<Zs2GE=S-ne&g$1qcJd!F26yixYC*cN)2IL$y+5I*P9ZZ(aT+!-ITB} za4Vc??HnB1lF%zUlF%_kNu(%}&jkwF5>zQVy!qG;m(i#k6c@<UxV#_8{8-E1V0GRW z$i~IU`uT*9QgCNjo4f`a>dMt3CKg^`@Mp|>C~?$f5+B-JgN@jwtFUKFUaj{gLdf|C zUf=t|l~f?{<ILUD@~y-^#b}u5;`{THY4yL;2N3@zrzpoiGTC>ZKV4~^CN`n1fZ#5k z&576}9n;aGR?zn32$7q0Azwt*-ezk3;yrL?US><FX`NnhY#Wwr5?t{ggsMsvVE>2! zF9_(s0hBCWch{#{v{yY+Y=yQOH%)6CRk5a&9er}h+Ygz-cxv*rz<HN3RjX}Mo<1{+ zya{l~S1Dt((-9UNQ7hhQoM6FdOMFIr7wGTMkzF*yv629s@HOj&S~uw{COK~|XLEl1 z1Vk=a$5dDOF_qePJJ=Q&U?x|Nr{=S|c1c}2do!6QH=(Vavt=b$yZ9?bZ_P5%VN2!m z{1bH%&#L}r*mDOq5wZxZhM<s1jLzhVUK(xK-WYwe;*%ST!PIx#h2*&%B`cs95q~F( z<tL3V7Bzkq2s$-SiT;-ys06A<U}i!<8bMY}Qb<z~HO7yXb%#R%VyPr8!KN5QJa@Ul zOp)g>NtLvaIpRODh+GcjT5u&-+FZmfewzN`Tny}X%Ls|8<|P(UL4qU=B;EMU7<-nT zWl&-<Gy=UgSU^|#RCT;O8rYv+P@fH%%4U!`O@hfI1_Q?9EYFz9uR|=Y_vs%mcBiyO z@$^=93wpf2CLOZ+&G`(C8n$@#3UykVOdA+n<32mC83edig&o(5G80H7`e46x5@@KW zj6z>`Q@Td?DEjE!m(ZtuW$McXmqnPI_I&lR{(9$L)twkI#CBo(0YUFI8M8DGW5Ekk zO`ouh`A%9;jmMza#jF}Zr()Xm&><U&m_BD()pYQBUY!h-xy#y18iR|OlztZabq_#p z`b1L;XS}XBH3`*KxYV1aw`Z6{-`utzwmtQoo#0mdV4BU<QG<C<@!1;Me8bo?RQAc% zb?h^I*<B|(+%}y!Z1GJwL*HaSUGmm*DPL9=hidW)?AO$ywQ?CtcIl{L%Czlnx@cS% ztQXITcKLH5N2ZzXa@Xi3cRgg<{oz<0)qdph@)0Xuue8iIO{an)lUyeMdi8VZY|EuX zP@?qvw(xNP^maf#2CM0~v-{DhM$x+VrW!g!s;!5ex6n1!s?o@%>2sLT91GRJZ?npm zat3zeKGPfvU%O1cZOyn<RNZq%c94Y)=gmH6-;KZ{oMv~OJ<KP{>{yv}`(-hAueE`C zTHiMMSF1X7U{w|%G^YMD<h<+?+>F9Jg)B==>a6=0mzLdtyvbYEQ_`jDibT81c)S|M z(F~W{L9MNcx_kQM#|0UV(**X5dMcfE;|UTCJ!5?3#)Ij?$_?w^qychO|DqFED4L~j zYRWIEHAmy_fzyeV3Rx6QqFmBrXVepzUt}1;6((zqlBSm~OOEIH4<cC`1}kL(t=^V* z=?#~CXAHb^P>my3nN@F%HH^@vtwP0{$`J_Yvlq~>M}UgId&v`rd+;IS8rvPyH#uMQ z^G_}z?o6)dmDfMK9}UM!kB;WLoHQ=)TukN}-o~3hUMEt#Ip>)m>(%f9Mq1ZI+!)`f z7(dSK^m6WSUv4w64|04{r25LgW1ygs3$#Rb{ynmqvs)MRfLx@gXrmNG2!>?q)||82 z?TRmzF^*rl^mk~PI9b0=I6QoX6r<|$d8$rGNT<-yb!fx)z3+Raka$Sc3N>qAooxVf z_*XNn>teRg0k!lKi0hTO`U963C1wV$?5a;|W4rcK$~)-a0x^wU!0H8)m0F|tggr_` zE6(rEh~Ml5A<Wp3v4A4*vM?)D6f)y34j!p(X{dE3&i7wEJ|DnhG=)q~c}#ju<gf<l zwA+{_ivJ022tvrDG9({F$w{lo`h*;j7(!=hZc)&{szMm8??TaW?#WVzh1=>AxQm4K z??|_#CHxGMh$>=USQOzej{J^k-}SvCP)E*npvUsE<`qu9t50czAjTLwCXXs0eo-y0 zTm?SO7wd~+;_E|ncvDaz+wF+JMPgQYSkSHHqQg~aOzjRsZj6pzm(iE;U7=XfeId*r z&u-OVs_ic;&+aq0i&7>)pmgzE7(_LD2y$Yv{+3AV@42GmW1La_R(s||2b-B}P1UdD z*{2Q4x9jGn9oSxULt~LLnVMs3h?GL!Q3mCS_K^}ndbXdPlr>#!8suFS8!k^(^~>3O zQXas{jEgw3bez*-aS1L~hRDYWXMhW-_O+uh#K{hf)#|Ed5_BKf$K_+!1oA26H}`1A z0u*j|SX`iOmWQ``(&KPkb*1Grpsq29p?5FbrSf$*!laV&l_Qt^p0>gMsaz&?K|WB8 zLs3G|6Wcf;6|bU>O*;-}a&s*-ai_>np~(LdQRsX^5y*r~8wgEAmgQ8x@cM1qkIr~t zue!5U4M6{?;q&Iw9o4yutMz;irqyUtM*j0x@;=nJl=JE?-KEPU8|#WmC-A(6@)^xd z#t*w>{*Qx5R?n#s$A{61qH}FM@)l#s%Vk6;V)_fio8;VSb9qo3=k>Cu7I)iOqAPY| zbfX{({+vhsdCvvzwb>Z4b~?u&(16}Jvc-VO!H(&ME006to;L8a5H8GSx|DaSLwDaX zXdvQjWrxeub4WG*Ig(9ZU`IfaUjAHc4o){7!Ld#HVz`9RcKu01i&`=sUSdFxrRP<A zzfs%J3<&g2wJ0+UcCY`jn#1b*$&cf6DSx}3^EEEydpstwenA%7#jN-GctUOA@s;_Y zhfyt)M@kWVyG;ad(idwmCJ@_As&nCxhTr{_J;y*N+Wt#f8CA7i*$BcJsaFzywB+>Y zWnQnvSDjitlJ|+fGxCF~BRG9~ahg8iMs3A$vY;H(<A}icb;TQ6&5{p@kvw&G6*FuO zukRnNWjyvrsP=4V-5z_<=r*a1aL0~aKFO)d4l%AN791w+KPAzthfXxfA6l|@yUl+0 zjww0i`+$_b>hwqG-eKi=nnWv#^hwV}D@YE0{H@SaJ(pt|i8a<E>zi7)PdWMy`8Ce9 z{U?!>N?l@;OL~gPxv^0->FAB!G`aBlCqG5ZR23)Uu-a(l0>`6)?<dd8$t9P`-omk| zx{4Xk%e@F~N;Zv_mc?t4gxT0w&|<+lRk3jfJY~&#@jtd@ev?RN|6i7F-+bsA(j8c) zR}TzVjR1t{rh=PbcA1BWfT3eNHiDPRhN;_pl9?C+z9qhxWdiPW|AzD#5Gye`)lgR} z-_bvRI8vg3ogh&sgHY~BJO{`;F9(SqCFvjkqIvp2udLQh%y8|k51NP`Xj6ryO-cQ; zv`WK4x(t`aN-X9k4HY0^`C5aH^_O8oJ-rbe>-3H4QK(pMRqCXnt0anp%t1*8A|kPs zaFoR-=0RDZ4zZut9-1dhzZEo5B50GLP5NzI<Vl1*z{iy~Yu5{3RM5sle!T%Cba}t) zd!2hqU(c!P`#!m!u6qiM%{-Eywl2$oIxje0ja(OgF@{bg?4hrEm3SX6IgpuNXL-uv zV(;RPLjmH3`Nzi+d9J78bSUMLLBXAwJ=P2@S`_SXew}0EIQN4lRITppu05nxsIwgB zA?OJy>>K2;h<<)p#e3x`zz}(P6<2nM3jrO%H`6x;u5#PxZ19_2o9dP-L4;LJ+OTG` zRxLmzA~NU3TmKdw=Qo|f^r~#Txxk?y-5MIC*$!l4Ws-ZaE9Ff{nLBu!?>*>a;}r0R zue-|=K_gpngTKF-BxsWo`i>&Dzve)xTTJTdtCRbFu`4Plk(?J0rATQsWpvo|XE{ED zdX}0;m9<=b1X*b+_B$PUk*X4UNxj~mkhhdUE~qqBUu-qh=z5;ZJ6@1@%6eAeiV>@l zb#0?2&=$&xC*awo5nu9EQ>7x{6;2b=Uhp!r&WCff@C?28x5b0M4n88iLK^U<RzRi+ z28V!>vx4-g88>j|D-aE@1(gb25iNuBk8?J%qkhNAHkGXIyp?HcbtyrX?Dm)+v21F> znt`$jju@tJ_nm0$uuZVCO(&ly?9yd90<>MsH56uPml&mk-)nqV_eVeeq8pg%QKA%L zQB~o!rAgKGPS@qW=eDSsFRvgVuJDT#$8z@Y9-@7D-qd>C=psIUIAdsu?o=K}<(<f# z2%TUcV@g3hlMv9Fs8$=q&=v%ICDoI@ybf?3^p$MKp@rx&u0O1bu{LJd_GDHwf547E zzOY8aycDg-k93^tlCp>tR~YpI^_=5hX~V>^-ey)7l>HkoM>vbdo9z=|Y5Ddck6e!V z_Ln-pjq#69ShkK^BeDZohA?%kcay7T8A#JSb*-vy^Os7bQkayFGc{t8r00LisJvz0 z<}$Ky?Ceyz*yw$z$XCJFu|x6Cetqog@|>=qnM_T~npAyjNm{3hN*#FI9^xNa3tpSP zY9Lm~dw-qBa@-CYn={?~W3ngUI<YM)d(aABo!nvDqvqI@g95C8>r9xu^M8uc{y68& z&+&SVe}5l%Qfa>zYC9?CBd@ZuYkM8GI_PAB4zrwo4s$NK+IK!g*g_zm!H3ub_*K#~ z#KSeU%baf%@w5&vav<?tFuMb>;4V(!C}DdGjKz73+_Zz2(Ar0Vog?583wGbn$^MM) z2S&lCBqo5!H>7IxzJTGMX(@%!wNqTtG~gE-{Dl?+ro>GiFIMxUkFc``jnpl^{BFzw zS}uUJuU-k{=?=Y2@BK9}f5Ih0TksE0AZ7(x4DoI37L|1&b0p>u#2m`Y<KLMFNP+$v z%u1DVvI2v`f`2Cpv3k_}Y80=YIwS$Y&j(GX^Kjm<K;g0xTGKPXbtxiS_l%8&0tQ`F z67JE!#SA)yRa%PvJ@_Ai3ND}aN15%7f0$oBTWD81w?S{$=+FvfLlH2F8yPgu;lC-4 zCeC#Z)ju4494;RwC(MgNryGY%tWupd%Gq?_Y#3|jjMbRX0!9aKj1QjjA$X3`<_}i% zex;g*w>iFsDYNeFB^Ft|eyw)EfmB2^e^}Rb+|MPzOG(2<fCUt?mj?NPk)j49fXx;C z04FsvG&CeW37wOorI2zx?g#6zewzB?ce?7L4|{pbBidR8mhrKf?Pa;{ZMje3L2$MC zV+h<P(LT$16^&vdUTyh9PNe2ae|WNZ^b*r=+M~OyKlI`yh7`E<=~`yn<dj68Aw3@F zz*VZ`hH-TDvyxLBo@!5PD!r|K*AO_B6Yg9M5z;!(A$@pF7whuS5ZQ@9gQ#5<R+6@? zr=-9%L;MVyLK2F(ehMjAxqM*W540#1$2b?pQYu8TmIG6v`L@_DPDj7)2=Pe*IqSWE z9fiAs#-kNJZw(gzTeAKsU1D*@mFB_ubwT|8Vg;WG;W8GfyNKLI2_~cQGzxZFFz{9! z9{JYkc3eIrHoU*6cK&4E7jDgkFbGgZi@IRw4#DQ-eSki8=yl}EtnpFo<3N7kMVz@! z<G9r4(>O^?c5tZS3uacCR7g;R==odmk5N;0-{LW@;%gQan!u~T=d^=hX$lPcJ`WE8 z%5jX*-l!S#-F}hO9{@~4Pg)>m^mRT2`3SW?wbed~TC`$hA6~(T;fCxr*?0}NHva-t zVo8h`iA*V++(H@_5d#PgQ8bd-<Y2m(kh9l23wyOT><Hr^spltZ+UKk_dyQ|2EN#qP z$jgFG*-iNKQRGvt<pd!D?i)RvO0rO|QAOzNnS%0{mD8et_53rQF6vo;PK(Oo*F`#8 zGyb7E?s`u%f3e}$GmE~;*eSWxb7mH@SoeJii&dZF0|Oo{UcH41_>#8GzV-AzFcV%M z0EJ7YusQi03u7JZry@;+hA-%1h{o%B5&qD@nCEsV;dVE$?BF`2RK1K}Vp5+aqbsS( zgfISv$xvth#_}ADF3$A$WiQihN%+<<meH?0B4^3ZS@{mNU8xxf#js}RmZQJY^~G*m zu^nBEx+To=6B()MkK`?#UguHQ(lxV8H>3U|1MWgipvFkdNF~pNQl$!6C;JNzdztEL zKrHB_wLs%~)8g1$tYJlJm@fgetu~0`*Mf$F^CKVi2-jF1LB~pq%~$)@2Rv@4*UN1M zIl+T?EwB|Mi9zR)iTWc)XAsAykJDlf0;O@{0C6Z1EA%;@N|A6)<psw3?a@W3zefa8 zCmMsA+Khc!hSvl82AXkj1PHfgOT;&P{HShoI@Vr~$3YuqYxbLnz@W<q2E=+^!D)>J zubWcA^%328c8>h8{G6Tk?D(C?%mO*<H_F!Jv3-rr=gZ|W3T$e1G_XL*%tG*%On!bl zu-&9}vji`Z&*QX*kcW`5K(lild9N+^ZWb%)#CxD=$H4bnP_N*uE*xT@qKX@eFP6^7 zwSnk<{%efj=D|;zc$>GMIKc97s6UEAEgTnp&@=aj?8h%6J?3e-9owM%If|tXYOIeR zUVWLNDNV((HIn03TsTqM&QN=M>fdE=*Ac4xwB=#0cgbkYhZzk}j2gZ}d(GDj`%Tzd z7)$;^4L8=)8i|s2yEbuhv#_srx)I5E$+vG}jmgh)hGCn{N9@X+MK?N?o>BIzRlL&8 z)5f0LfnsT~i8F_9Nv2oJLW48;P>WOyhN)`cn|^C~{WOH53B87?K8*&K$62_8hSR_l zjs+R6sLH5u^Mul^{aeC|TdpzEZv~jba$By>zh~4*v`MiE)pC^l8GF@&g0QV#UP#)U z7Li0qS)}&L$O00vL#3bs@mZ&Xwsj+^h;lokRMae~EUzzI4zgqAC-Y@I{ZBSx4VX{+ zD?@5B^C^R^sRqI$h=1Y|^OX>1#3i{bQXLG}W4$<$z+tu3Xbj?ng9|WeN2rzv^IA*W zeFB}Xu%IwCO`zU>r0*{&9WE(I@hZ(yt7_58Q}L}q=+6DhiWTyw2GywcxTiPHx^ndW z#_nX=B|`O3s~_jYLi+6KJgvY#Tg3<Xa)yE&U+g`;+Y%{K5r+|uz%N>?j1~3hr{I5( zqMFpIg`M>onkhHdk;~$RdU5(m;ddhEWO}ooks_x`f))}j5}xq@i`>#jJasdTSuGLZ z`)k2`4fMK40At8;f+Si~k~_&uE`NR$r>4g!EA^g;A4VjhQtbgJFqG2OL_&ejVf;r) zUY09<%Y|$Yg42dOtT2eO_sEcjN);!vxvQ|Wf81n=pbG|5>~_77`N?V4Udx4(@Au>8 zbq3~Y6NR?l>lt+X3)^2&f>;8tQ*&?%S7~C_`s`SjgjdmQb$#Y@)qMH~k?9G+rDxUg z)$W5rtB277?RZG+?#OsCS^kPrM)$aEhy!mzG5GY9y{s8S4$ql`nqHq<^cO;SA-3Lc zh6`x1yA_aDaXq?tUV^@y<td1JPdKN<82N+gBF^k$lEwzpZ(zZZ!MO`nLrN_k0{Fa{ zK^=ImeR%Ww!Y?z(e9ITEc{YLiSKLlBnEM}p9e1Fdc8Vd0_Z9F*#*bX$6>7yu3LVuq zJ~!w_^&gw@CbzyW&+d!sEEmgH+MG&CNc7sB+fFGy$Q`IcS=XCw?izK7)A4IZ*BgK( ztZ0>%b$tG6b3kC>th=jhn#k*~KV;sQP;}CzQdx6oNXVxp%iGg+%UrXFhzPYtH9oCc zso&mEB%hGAFGtB!-v1m7e<$$&g2nYrX5u{t(RMFw<#Yx+%BCuu3K|5U!vS}K8ms+_ z>M>AOuU3oXK?DxIvW!3X8<V{2)a4#)e{3l|qFrv`@#aGSnc|@MT!4g-d)}%Yi6pgB z5jaGVM}YE@XOsGIq$t8=SJ&&@dD`>Zn-n~KMC$fCwgBIv7-z&BcWu;oyvaUA<?9h0 zyGJe3CG=7M<>I;Vcw=~}@*zNmmxTddfy&QRfYwRF^Y*U@0`6b*kgj_$TROA|md%d6 ztZBf04CdzFHM#+%mnE<y+@cA*TXhvFl{<wZ$!(;ce?*eU4^O#w0h8XooP_5rV53fS zlnR;tBWnwifZOFCh|M;LN`~uhSxByTo3VpXfI%d#jRPN2fO14+Y-JDz*H{1t`5~1V zkzhiC>2J+(#-@jkiC=X~k1YfCu9M02U*{UOKh#hvTx~B;enPD0`pbqdPh0plEXQFX zqs751e#46{$+?QzSPeuOMDY2JS=tP{t!b^_1hGkY89Q)X5Le*_Dd*vfnXynEfiFi& zxPn>iSR=Z)#U_bp_<o?MbnGuVQ!OoTBGUu>-g-Pqj7ctJ)B2sMSBAgCm8r^YZbtCV zMJQn~x#-IY?oKzCYXxqW7fL}#NOe2mZdavy@ceU{DJGdaEQ`-~xgP-_BT;_wU6^v; zJ5o8HAyBLL-vKC=B}XNN-&b4CR6$k39Tz7ot#i=Q)aK4DM!6wBH*>6m%+20T0`bpN z=|w|hV#(+^@y=Q<W76#q#2s$uH9#tGNkMo8pp;8ub1eoiSAIQ{vL06Zfs#S}u>Y#Q zmtyj1_4CRatJ;4<G}?Q{noWr@JzJ=V`Lpd6Wh?NyI~q)VFlCT^wl!VgnF_!>Xe1_^ zJr4^rk0N-YwcJugyIkXJsZ3_C6ZRIWD&jQHhUa$Pj@;J>Rh!Li`w1!zI__1?GeMsa zalbf0T6|Lg*91wD-Ww2%dz|t6S0{7iTt|7l1*m^f#v?0AUMdU?eQL{6Ud;H{@ng&L zKC&IV(0t<GoAa9d>9|ys;~cDy(AeIczRfr~9cG)V+c$~1so$Bn`#J!6i6`5S+AlA5 z$8Bxc8enV(cd>j=iuEoSJX8?cgEs#(&2l&i2WFBWV8l}>VznlEq*l3xOfnuS?dHn4 z(ON0vffbx@J@j2(UOKOx>+eTKG`A-&!XNF;z=1a(vA}j4lp*ze)8)@JP78WCh=#8f z=)H!XN$*-Tj(*+Eeos5#!7=Rk@8IC#|AgsZuI`LT^q6ow-&f3?R8<^^H4Nc;=Y)nR z|K|=SGJ8H=#A(;7S=t@_1)>}`HV0~oXb-`(;UmB{OSiqk42B0(SD;b~UanDd_3zvO zZY=eWZl6NY7n>bih2vj3B0`o(vvj4M`d>~9wmy-T*G^2(o%qisPQCELpWq&&YuL_@ zjW-VAn(fw*f-eWEgCj!)7V}3NlP!|MxkAmKtvGmG@4~8tR&l~+c&4-f$@RzB++TlW z!eUy(E`@B0w33Kw9TzPjOsD*1)XVq#I4@tonh?O=DFXLEaJia?z-%D+9U{$aXxlAa zFQ0)eGf(v!sE%ak`<Z@sW=MHoXo1XjH?c622B6p8pRgIrjFL!gQ_UKv%0cGHk{!mP zuMZ=ccRi9@-!W#ac98GSKbRe%RFX41WsTtKVW}(#Y#vh?^rPMHunY%JM5wjNskYor z`JtkIhwr&=gf4HVg#p`&T8PUyOP4~7WKe&7wnBO$h8AeuNsQvUVWNc~QW3Yq43)DF zM$Q`ydb?`WK0*laHyP%ik(cHLSR)^2<re=$;0*pVKn3P7$go8u;DJCiogSFee4QJ5 z31+^$i?X5mVavP3ZS>~;u;#MzonuCqy+*CW7TnqG83mm_Z3MH5RlT5jX$qh-s}NQF zdA`dVjV?r>eLx&eOdtX-YDO;F;WDh#_?4F30FmwapzeIRfshWaa#|^791_u}=C6=@ zmz$d74LZO54&fjeJkvIvh|Sh5<cJ~%gTC&zBDjA|K2v?LL<IOTwQMz8e2mt*->d>7 z7v7f+zCK&9tg2aOBs2$hYfL_Yx6vc;rWOW$H#BT`B%6qmN+HB6u=tHcE6_qRZYMWc z27P7%#Tptzy$n`9qN4|$JdgVCXuR42w~3F88RejE?`zZc{ybBUxSI*sTNTNg>xrMW z)<;#uSFya1;Y-A|Jr5-)#rReXCqet3egGR!0Cn5Q_(pE=nalExEc?b^w_gErRE0%) zgObkZw+nF^@h2L{iU{7A1yDjkI*zrFUa+|o#ClA)38Zy9^E@ZBcKG?KPCMDd49xq{ zsnj1Cn~slg^kRP_n821Qbz|+i^<u8PJIETJ8DOHKhuH$(_NrWuXL+QV%NMOer01!2 zf5~V=SyZN*<F7bjlTmd?#utR-%M9&h6FLPBY7_BWC1%mtR+rh;+}C7@gJJWGvezsk zfsqvb%o6U%%c&#Sp5af`N7?x54b-L6*7S^BZ?WlXU$puQei?rj+()2RV!K=iPODz+ zC%b!G>wWhV?59<o!$<6>2-2*2#qzKyQj28SUa&cUj0`e~iDKqO@%6HXhl&kbFo~OU zY!-XtgQb(_m`{dxGXjfJAasP#BAhrs9QB9;;?*nOZ?F{J&0+&$((RlLEID}QbgYE= zmz+=##M_$tg;a@50w>CdVvx~UqgJVU3!^qiO(+qjchFIlM<0`!I0BIn6!=>s$<BFY zYJFKb7MszCqVb<{hEln)$9hwzosTlKn}waRztegMf!y2B_j|gkLKXWjOjV%KY;+{o zS02}^6aILU{+Wn=2s+I$nK@qXSgUD8n$)(wj~EAK%I8?~ZbUPUj9KAHjC!~#;=iDA zlCFSFP;ZaL{B~=Nz?SBw{aDyfW+zB@b01*BX`|(lUb+)lX0vYfu><TI2)H2r)CnlW zI{bYy4N=xCo3Mn}iT~HJcf!9X5?lxBahTzWLp<+i)h8or=YwOQjS97Nzx?dk_0o^c z=1p@?UsXALKGZv`O5tsPvbgJ%_l?P--9ErK<yPUa&DLL6oFEQkpl;DjaML*gA@6N$ z``u9APIlRdQoPuRY>0f&)h#)OGVSC?Y$!@q#&03d-GY3pC){mXTucxqsrP&+TAf;_ zH-wxDrjRoKgg;0Lx9^L`4x+!*m@U;IP?SE}>BjuJ>@fD#M3vF#K(d=>+#xWH&;n6G zji7;bXm$QX$DI7YuaWZzRbipHQA!=Tc`iUw^<ea?#Q+5(CFs9XX#-8st8FagmdkuZ z$=~;8F*npOftBmes1fWJjYSmIuC8~pS*tj37l26QS(_|Y%{YHgcUo}N4Cb@ih+H2J zCf(h@Z0zU(PqB*@?t&(yFysWokU_8AYJik!4a_hJd??Jr8;Pvj!)N5J4L#l}J`UYn zEFt5JX;kn9Pp$wI4?u`|<cK({AYY;(io6%8w!Tftl=?jBB|S?IbFV37zI<x9wOTQC zvbuvU%C()E^#v@_gI6ODghhFukj|0zF7vBw8NgKQY6zJYLOMzH^m6ifB`LYw#Sy63 z+*jRU_=_ThSZ1<dP2~}~cf6US!zGu6OV{-H6+dl?{|)woe502ptYQi_UQGy2V>hKV zs+ctY^<{iA!a-+8=o^rf1W>2yNCGTEpE~p3K9n@n`5Y_X<Fi8KLEfo?vG$ceOdrDE z8<80ZYX*tL&#C|2J#KIqxy(ySDY7)z#MZ~=LrI1?YPS9Y0Rz_*luh~boeJ5{#2akd z%iD**uTkEN5}Mh>K=oGktVG90GgLlvxj?)EkamBj=Jj_r)qJTL{;J%a>-fvG(b|JZ z2AwWM)YCQBryxb@8{!Z&k*^=+6TsP@0ukgWCFU2(5pNlQ@XDdo$FSM}u`qIM(Lf=V zn<iOyga~mD&Bldth;XD9RFv7~k@eYxA>^29TI_o2TfF!V!-zI6#Sv)%lhN@K1Gb{# zSP3J={*?ANX6M2AQqAI8$oz#E=f|E4<9@1i!X)FH&x;y|XJ_`;r|S?f_l90B3KXg* zI}xj?5$_R3QeszX4<wv$&@LhoAFy^QzG;UBL{&k}=yW!!Jaa*~4NXJMt(q){@`hGQ zLS3B944wnOqhJLb93#8uK8Kye6tTEj!{N&5lO`S%`Sa~yqv@#Lr_3j%A2mYn+&(f6 zHs%|-f{w?dF*V0ieWl9#@dbt!2!}5_-8o9MjWD>tW@D{DFW7E{fzo61uSO%b$<G4@ zupR$jgr2;TS^aI~Z|R7O8LFg8T_xTbCoZ$u@kiUOfJA<qgW!*t+IM9Mb&n6jJ9CgC z2@;Zb^0Niou&fbd<*-LLs;*D|jKvxWSkXT(&H;^etzOD^ZY&%}Kb0s1VWQUsLb^X* zcT)Zz0QW!$zgz*<GrC?7$-IV<Hb7b|wrtslw?6z9y`Suksuhai?9NrVr)D#pGeyv; z*OPc@;?u}Z;F2<@9OVQzY43CS!tddmDJ$-4To?W+VHnV(D`tMa4*5#nfyuLGpjn;U zxq^@;eb=bZUA$CVDD!^(hI(VY9QZGD;HCp0zkj4PE^XfM>ulo$EY`LI$`2chfb3Fa z@P=zSAi!<(=+U0&LWK%hM<RiNdN+D=h8Q|6lA&uiu&7o_1%2t#r3eVnPckQ*KY!k% zimjNEB}-n{GqfxDO?i@2nVB<Z{^7Psje5k05jR*B?hljc&EVyLmjhl7cscOj=70;J zNROrMx^d5=cH4(hu|yt>?E54>{dye=mAZ>kd(YsZwv8#V#f>?=IUn7<6D?bJ$KIpS zxVzy47&NE{S~RFe0F9e(ZVZoZU4gsnHAOHb179LQ*}idYf;!rGaigchZaXt<Fzt?# z4dv!KE-nUZDVei-_a0Zvm5zX(?sTaQs;(KFY`kNk+SC;+RG7y9>k}Z#<Jd`aB~*Rf z?=gcrr!EOJSm_vU{^%%1vXZ_8AeVnM9gp@Lf$-E!xV6IFXnB8Q<jodjL8%mi2yxMo zIC<m<&PF7oVznA*(Xt6aIc_dx3)8i!^kI3DNJ`<oAHl9zs&$Wl_AT6cdwo3mNMi*1 z#NxpE<#@1d4;+olfsrpxM9-e>C{@P|F`XsE$3|h*>W%zuoC~$?p#zP8B%I#167?H) z#HqLtJo?l?j2QDI3gis3l5%eLi6>4w**>Zg3V!pkP?p1S$4fIo1M!PboXxOuF-jN> zdAnuHCcOXg`<OU!EVg{V41))a!LB2z?B~{)Ib{eclrF}6l*CKEfOlS>jG+@gM&^8_ zuzJ(CD4Z{w1#z^Yw^Eq8U`=x6VSyK0lhc1vAC=b1hK-wStoy^ZMT0~^AcOmw^x9`U z=gO4}_3GC{@z78uVho=VK=625S6%|Js+mfdddmJ&1NA_lNhG#yT!;D%Iv^@3m^Rxg z)A36^6r%*3q*i@7CzAO>`{b#!IDU?fEy`6u%T_H=`|cXZl0_Eu2<vL>kPlQ^Ww{zZ zpp;=W-kJ6W;t3M=?Ee&UW(j6li5v+@ICXF@o*y|5Uo7|z(Iy*Ob?!?opYh0-B^?KL z?ZDe_zK4e%>5S^^Z&B?0JK&DSk`vS-7jIlK8Bex({1D3=ZmG?w9J2{{@7<3OT09>b z)~klWz58L#mrIe5xg<tSd>&79ZGoJbImW40ni75h)vDLQp~yVwM}db4L%JZ7#KSDu zq_SQ8U@K!qj8_~lkdmB;^*{W8&0Bur{36Y+`F4e3o5`l7Sf1?;ce*_JNLzjOL6Jfk zoAmpx1s>5`dCZyJXx8KbY&>|0bEgnmJ<tZX6Icu&up|y9C&uCAxzjju^c-^MD?vcH zDOIX#^W{l4_9X#j3nr7tnhd1RhZ3#Pkztr5YmEv306+jqL_t*a#^><QRT_OBZ%sbQ zmLq{Gj{lDc)IT$F5-t*;FLP%@zK|G?1~qOYsLVXCy@TWNxiM}`U*w>)oa07_<HYuj z`bQjd4yi;tK%Ul5Jt2=R)70M_kG!#I`Qb}|9BFYl9~O=dJ;&hf8LuHA@d$<v7>4;P zcAygNR1P0K1T7lY;@Y4wN{1@T|AWB;M`QEBc+`KO3r0TkD5_VjK=6%arAA=!+|Tf6 z@0XDjkQYn8|C)}qidsiZdaR12#hoVLlZTBUJsOh&_|j71C>g&A>o;v<QcE<`{GQ;0 zklcAtr+$4D4=rYMs*fZwE+A6;cer$=ET?qxM9k5APP>5pKdeHX#+`5}B?}6btb&#; zIEHSaAPV^;wd=&_D4aMIhLd5DC|R~5THN2<g6>%<*{dC;eOcn7Ty|m82x@-)<#+gY z%^|MYLs29z&5fMfhx#?@V&j=isME3?roH_VissEqQw<tdvDmtK2Y%WUPKo~(;7~%; zi9Kl3vOQMqjX}9;buee%yOgfYLFri0<a{?!AeY=zuWE&IsJPNn@0FJWH--Z@9RQh@ zn1F-Rr{M6rGifG);_kl^g7~()BH#QKY~1`;QvLfLg@=b*l~)0B?jV)qHf`FtZ*R); z(4j-A{`HBcZE|)ZpshrS5}r6+eDlpW=-j!pCr;k5KmYu5&;7sQB878H&S<XZ`TCdI zFV%fHoslZPH+VVV<$#w1UJm@rIUqGpZoXrVAI0-irl9YHXAyZ~KZf`1kEK5xL60HN z;<@opQc{M}d9ogt9!WcE-{6tQhvCEpA3XiS%Xqq97v!Oivh@T^Rpt$gK1HL}J&?Oh zExa;qG9IW~nO;UE^})@T-CSzp<!mRf;y&pR0J(ns57@VFKk4E=lafAmV{0XnluMD$ zR@ZLQrB_Ltl>#91=Fg7?_3F||U2aM+v3yq*PL-}Y-6tY-j`v)<6SNyvlN^OthYunj z<{%*`H|}ru5Ng-D6Iqy6U{g$71U9Z)ja4hxAWyOC1aBr0@Tf$kSVNFQo`yx5fD5&X z<&rcX+66pua0_0ZIu8xnK88m1sv;}mDM7UXy}I<pciY0zjq2MYMhQ^NN<Sva*t2~X z_8mNedQBP<OwCGQC<aRj3bucYFAnoo#IOk?(c|$4k(G8S11vurfI{Ggup-r;=8}N4 zV4%20;#};o8(#|{SO&U!K+I<N>OcQMT>NFUYuyO%Or4C0FHS>zP$_&c_bc3YPf4ma zvSpOeOpgo0=)prV`Gd8%rQ97@y=E@*<OsIjWL2jl@tRB=K`@1Y6{kBysZ@9cH2g?y zm(82E=n;cxbe&z4I;~PxT?vq2;1~)C2|?{TwFy=gvFfOn-yAzC=!)$+mC8O=rzjh# zu;>rdnY1u`z;W4U@astS&y9N;wxpNqI>;VGX+hE}iPe3ZSL3U1Rv=TZlC%#w0Ug@k zhmfEE_A2vh9E&1>AS#*KI<mzVb|xHCU!RHFs#KzRg4P6hC?#cyOF&v;6qbB7A7e&M z#4bwB`R6Qysc*f3PHk&o`I6-vQ(MuicUP1wQPlFzf#+1d+U;sPudWIX<3xfDPK%ve zhj-#L$8BUBX3hGTcGc^Uo(S~pIsj`oA4Kg3p2W<zCZcFaCe}bMQ|0{h-nFPz=K)+y zFNGoF#$nh~4_W}y(--8Qq##|x#nx**OEV%RF&;lswRh|GowR4FN2Hr)7kRvA9j+Te zSyph7^ID$1Lj)?<t;IeqsEmIgs3O_<i^swBE6}j<LkJ@vSo!WcXx;99>%BfeE>;M5 zA33lK|Ka$Ki1kC4o`dluUz~&x#1A0t0-a@lRjWce`%G(<FV(tFAKQm1Ge1X#dz+wL z%LdlYqYv#0f^+in`O|o+OD}x&-Bu(A7eH64^^O_-1Pb~^qub+sQ18(}xW9QFt9mPk zLu$O{sDi^!%Orbed1EJllfV${6D=D1juREqs7YmQ8YU3*+KNvXZo;#p2jbv{uhFZ| zP;5VyLPuDW(7ii>QjXP3oTo^;MBA}%69}D*BeD7EwfjqSY*hh4Tqx}LO+JseCr`oP zXFny#S^_K9%)@OZ^AUh#&FUo5Z2Q_yVa+iCk)of0JWEea!PZSbV#Aj0p1Gz+zZKN- zkX(6jPu;pSNkO%5m1)`G)M3Y1hLL0IQ=uY;e6kYjsi*NVo!vh1%uFN@JiVt;8?<S5 z53&am^d|tBnh=jY6o#5d_4!PBLNS2z_@VZVkS&nBVP*E!go@*z8s(EFDcW$n^X43! zq-y@~A-$2)kG5Uo*v}n1W7gtbxV;Y5?cbh+Dy0h3*;pDb643teqfhZ*hb|~uG(W!s z<FRAaLUelMDeSutgchB;V%A#|*dJW0#XAC!>QjB4IX&zJAb)GDc%T0lIlwoAH)V)E zxZkX8-^zS_Yk}W9Ha*$RB!r*8Df#ec8bvj0u83L{orB(n4ekCJs$<`@2LVL>R<vJ1 zo_4?f`s?QM<;y=iXur^tMm(B6efpna^Z$IF4?q0SbnMvicO6u@Hir)%{-1BNw*g)b zcsbzZfR_V*4F_mIpAK?UX-X@~oH}~YB&SB3g<rmBDi^!O1Z6L7=C3<$;^;XcDUDk` z8s17z3^TJ{9BA_A%x!!#hnl53j+rPvPo=kn^pqr%o^a8;GQ5Y$<l|><tJ%S<KOAWi z4eLl_-c-`ew62ezHGrF0L-k{mk`ix{5@StLQXG#2UMKOKY!Z`n=8>3ak`ozkuN9wS z;&mja7)mM9xvNuys^X=qO5X9AJzO=DV%{oFghiXgh{NWAniWlEpCFUF(4FSJufH?V z)ODm29u|~tl9Ml+t?L(<rnRb=0Kfd^wmUkQ9VafEI6h8gqI4aqJ0+C|FO)Yq+I+wC zBlF}_1I+h(kD3?}W#Y}Hvztx7&drTK<!Bl`(B14kecmMVN%*-7X6mGO%--FHsW~ft z#G3S^b7p9lRwk=Ypt-eT3p4k-pG-W<VJ*y|dYopZ=uT1gnWFWKu{>z|kbhJz<>M6B zwI18U=HUm4KX>60e{Y>PmoMx!1G{%HLB9T`R+CQVRD7~+r^+yCapuy|t>(d6cNjmP z0;W~hQ6`cDB$2$-I7wzhR4tjn)XAiYwexUzO*+^v@jR8|g;Hre;$8ijX!|rVV_&=a zTygRCNHGcIuliYSQ4<tYHqG|9Zg_IHO=Hj9Vl^=-(WFKmFx{F~ru9BwlQq|^X5{4A z=5mUYU)fUGXGiudH=Q4>Z~T3;na~Q&&C*S0OgtZ|EcLbcOs5~LSACQ~*2S6~KW#TX zdJZ#dH*7aamL?TODmkW2Y83l?w;9}{gUK5l$ltnoOx2pr&91|{&E&UcnL#6`nX{M3 z3+3a%LY0|^tyD4B1T`k(;XGC@_o2LYK9O%>XTnTU{CSSWcTL68MUAgth?zd;dlRGL zZDZ7FQD)KH$tHK!OeSZZYG&SwLneuZi6;taX&iAH;0&qcwGIWv+kv0PzD`Ln$w{2Q z<g=Z(iOD=WM>6MeGUF2x;!Iq8oSn~c3CSjb^HxWS9lW;4Kky+M$nDh2X3nHBCYMiu z3Ggjsx;`<^oVXb6^n+$fTB5mlW}g|`zl+J1DZu2(U(U>!v&>v(`x0#%*q2<xQpwX~ za!{qFr^K1<tG_jUpLo)&+Pce0m#QZmyQy&|E$Nb3H}`E*{+3+E&o|iQE>_iiylA~S zckH;i=gvFLhW*F5syMxvp;KI!>RXKx^4<0$FKwkfGleK1hc()q^rVea!{oL4DZxZV zoHwV!!Z~kZ&DU?eX!2#vYKoStW0wE8$FA2*&SK(CV$6OsamZsPH``p~wkBpzM2d+c zpVQJ<cRKs%;y%;uf!Zd(zks>Des>cVm&$RT#_s{~jAL7UPP#;*%G7s&sIpv2O&~2? zO*rATCfoJcy+;3zb0YgZ$@1IbktLb;X|68{doOlm3?fAI@OvROa*uhe>1`&^$Jb=Z zTgr@>`l*TJJWfwl+c*{zBF&K<Yt19A8X4b!ET-7)jm*+5CrzS;E6dTi*SciCGgt@J z+0ErMd(D8J-OStb7n^8R#qXl@#1m%r3j<k?KiA(n=8M%o+O;q)I@-MO{A*^->P_UQ zR>nk@dD*-_d6X%fJ&W-R(%SMl*L-IMvg@BSd{~+O#Y>F?Z}4*9@8JNE{F^v%;vJha z+bpb7>Ni2ig;mR#<6q3t%5W1i<hPqfhaZOO##aGsUwrY!O$$5<RHZFLQ=~|dtJ>VC zQKO#$k8UthfUFyw)p_^s-M`J)n=plV_j>`zRjXFrgdFfT$;$yR2fQ5ca^O#MKtH#1 zXdjeH;2`$6nfmNtlQ%HXgjQ-`HlB(!+-7ReM}Q#NB!?d|{T`}sf->bW`O7pgC!@Gw zRaR~q(+OV2pWbU4Rw`w(W(hI(bscU_5y42|<}58m8*P>1u8^1420l;M20Pu^KnlQe zcAHMZE58hNrLvshzOx%--neT?<pxvFbU2^3k@n6V<A5)$FZG-`w|}(>%@Jq<e6pKr zbssgWcN{jc%E<x*DyH!+?C3`GSc|&!XPm?M1(q`lHXb&Y_&k}3R3HCshV*2@8YCnw zHpa}IG1-h5HrgBxzr@YIY9;^^wcETjs+Y;+=Wj|>ZDdyMJ#ImmPe1&?e7j^7fjn(! zwNoa*d2W}v_tyL-*f+@BRlkSXxSzlS3%9Ma^$Da9RG|$mv+!`Z!#e?B0u%VBXXLKU ztK2q`n^~?Kn~wnFvAwHIyC!uAtmH6*#!WNf1YQKxu#?G)2(xv?r{=EGq1<GbHPb%- z$pQ&!q(S*rk5j+;Q+Ezcb^|UtlGVSA_Z&*?<nW}`MTTIT$$NK7cV8>s9V`f7JBu+& zXdkM@iM$nP$!G#5amO~BD!BsKhkmAbxqHo=6`L$DEI`2WB|XkWp4)DQJ=uu>aVF#A zU&_q<WScY2Sxy=&7wNWqJEr3Zrk*t4elyQ>>@wUOJ{d($=&{<!`UNBloMXA0SIslk zN)|PNEH_J*yr$Q{C(V<iCYo12_}WCVTnp-vcJa#TQQf%P!m}qRUPlH#GNF<()|17# zC(Q(#(&EpW4__N$3gs(o0`gThKkU0;5}3gDQEDuohnW$5+L_G$zNScpre@DM0z?_g zOVKzYUG`wSGu~B$s|-7L*<L$uop|S=61Wf1=!{)OiB|PXGB0%f$AfYSBnmhE+cY#G z1nIMd++kjrG1uXzEj5`vkz`V0&zpCi8$tk>ed-%xIuCf!Tu|L2PJGn-WogOmhcxzE zYGRaGIQwnW|A~I)=-EpyUO4c*z-J~f5vRAC;XTMR3QzbD)V;55U-RY%^G(C151Nay zd|9IM)HWu!!JhTu0E~9T>DD!#bZL{=vomKc-;*`wL>(ckWCGr)q>lh#eAF2;>6zYK z8?u?k?FXA(CofolO%-aMh8<sL9&gv&P{!0e&|{1_%`yb~sgDG(9^1Lp)Z}{Yo2jT7 z^wK;N%SU>V;H<nn>!p&`WyYy?=WzNkP4k%Rl#S%GKN?h)vmSYx&lr}?Icmpt#sb}p z(fDJ=bONZc$9^=GatD|o^1ej*yUeF6H#?xA@+l457s>t^_QWH6k&wyw28EiLUu?GH zP0uxt?MnnE7yC5^PHbCi9=gAo`F_VfJKxheZ%o=LvuW`xlbtWsa^){?UV85<6V30l zMc>Rfvp@b1*KN*=MDjB^!X(BXH3J^I-(=6^ZvsOqn|W&w+to+wkGN)8@9Jw2>GZHF z_XaNqZafEWIu&dJLO%<M=g(p1_z?(OzW8U)u8qiBvo<QzNllib#jbtyuec|mgwH<v z%+uET_3K*?(4L5!@ItmO-+S*pPs?)V%xUcd-Ezw<o;df#g$oy~a~@7r8<jV2UdSe- zV~56_>fdvI_St8tuD0)28+_k=_u;X}9{bfa-iKZecsbzZz>Va<qC3js*2kYf={^H) zWVPP9GH}3ZwDGG{+I^JLLd1nbv{m;aW`3{)O&;ru$y3K5Pf(DxahOhr85a)zgg)J# z#J8JIqV1EzG4thtRB5A18P)xK(xS0#<w~@Es5>sCXUD4_eTMd}?m=*J3O!*<?abFv zjkc<F9;Lbr)TGn<b}Y7U--fWTbBvec2-?k}vYfRQ$1GNLkwok4sMk8rD9M7{x$>a$ z?Uj%>cTTJ3MlClR9MxXsaa3lnSpIU#0aZ^;D!l|RT!f~rpF*r}el+jc6ED6v0HFo4 zQ0<b+dR8AX4!bsdhfxDYV#SZAk(8+*R{XRURc_1YsA;n{mFTFmO8wP`>aUkEW71>< z<SKwi`}CxGAniPw7}^?(z?UC>geM1%MQl(>y#LvJl*;9c6^rI$;IL7)KLTXO%tYbn zwhgFPvn9@(?6|MfKumvq3<_jRr~0+jy~RhW39A37>g?D&bSv$$W2Hu^hx||Dp<7uj zloGL%SI?Qw(YK^pET5!BVe{H=@YGWiu<b|^-u#6230v2v?MkV9C(&W}MZ7iXH9Yt7 z+la|l1?#u2L8&|}gAOs^8)SJ9K!-ZA$*7>d@snp}sVZ}zDK?F^E_ZC-j$_A;+4Le% zypt*<6%}n7+t;=Php()G!53MwW<jM&l~AbQEuaK19VBsFQ3YDR32l{1=yW>EqZuf+ zO?*+m`_K`|&K2{}qFE<gq;hPfI?eI=tjQ=}JU@a>ieo#JHulaQ-Hm4k4#Q`QH^Bs# z!mLl`qvQQ$sD93|Os~S})TLE5wy%8>ken2TS??~OQ=3#w7(bZyAK8}F1o+b-h@skL zD(Uf|EkNIdaJ)QvIPD6~L1Z#jc{682xw{+UnNg$AvTjxD)m&X+s3M!f3qR)blbHc) zmr!*&>e#k+`x{t2>Tt%knX1E@E3O#JN2w@-wn$Shp1}*l$8cV*MZr7o!@3o-tv7Eu zN<vB`&K}-_hac{N?{}U=@8K`u*=GkJkPdA8EMM98bStdi*_xA<->g}Iu!?mqm6A-) z?K`&N`0<l=9Em#$&M43o`-f3dc}+=8LttPKHKR#C=U29D+1aP%QHTz&{#YRGG-(ih z_5|uzzZZK>CE}K{P4L2$(P-JIDs7S`vrjedeGq@)G^UIlk5{Q;8-tuQA2A6-hj!v9 z5T9jxkOmF7L{P(=?M$IfPdcEP`W7z5rO_VdGYFRbNA`nexS#r8iBr#E^Y<$;u<uB0 z*>@4C{<#oRv;-dR_yAs;Fn}_)RQ2W9RJhV-y3uOna7NY=tnQcSWRx?ml%Cx}-ujDa zTDmOf)Ze7hnpjA{rLa>N(5)A~T)7XOpPq=(!@8nScB<4fpGl9xo}boW;DDF0a?^Q? znf4lb_j&+XSy^T}G?LS#&u7oT=n1dUwrpN3pxxPfE9B%*<1;eBk83tHuQ_X+wJeQe z(Rx^?e!Wawh`uz=za2Za<H+&j4#AB3Jwa{Ek~Ie^RI1E*oS*ZU-sibSs7|7E94BnE zi$AtJ_kboXmRYpdxQ(_gTQ=>43$(dfr9n%)PLl?=g%+S{G*?2dGe#chk8Z=TLBsLc z(yc(&;&^AyJUra|Hu!V=xz`MhN12N7VSg@P@D<+qa1N%t{XTN@dnAB!$0s!$7f&2T z^(qZ%8#n}A28~9ShZ<w`;xEyiPJgn~MsR?}0;1^+dpGU;_QR@;2av5~4XpWoIm#4} zD=_kqoRmFJ+t+H8F5De&8|nS<a^S{t;9mhix><U5=|b!x5Se%(+#Pk@vtMv9$_^Nc zl8^S_ca!^P<aLwYRFT`ZZNnXR++lx6sbN~|<$&e3+itt5+L^I2+xa83Wy_Y<E|5EZ z+O%ot)TxvE_Nw#TxpUE@M-NY&JZ4iu)N}t&x{zmX0j9-^7x(-K`K#$$zkWSEY)<>d zV#|~%19?yP_t#GeZ}?y2fHqb%!GK-6c47Yf`4+5~7xQM#nxTFB_Wz4b^3v?(02Wrh z6}R^2gECJI@^a&E;sE!lwAaSX5r1p=6YM&?eJ!5uKLLw3oW`ivCZTulcF0Z;B@=Cr z$wt=3rQhP|K_l_wNrM+>&7p0q>eiF5F9DO(_;5Ts^clQ5>l@?^t%`4!e1%-ueX(f% z0^DA;A`jYv<c7=Hx;mThjLp`DUN(()5P&>+@)RHWAXBD5I=3K*Bvim|&6VHTjp|Bi z(%1$+f+NA1Goxnp>efk#KnJG=rsjpVe-<oKtRhH<yb23U(1zQjoX7LDY54q%uaKIx z6nZ{09HXA@gnU8FNuWqypXte$@%1O~<C&ooa6B?I@|CWRHEaGu=PSOHXQQ)^MA{zn z3q)`L0RRF7sj0N7cji1MPnm(*b?c&O^JWN^vzqicZnEjHW9cIFdvXYNhZ*!7{4A1V z&STUweNd!e9@lR`Zfa?B^Gn)r>(+BLd_qc~_vrB$GT;${2<db(K~4&>@FnnPTPur@ z4nX0PE`G7?+Q)03%aZ^|aZa0IJy2E!@zdccpE5o*{ygTtHyuxnn2NwccjA*T-b1yD z#jL$aKZ49>k8URoWAP<7^&R_-#w)K5LCU#PShRRCYSwFnawUsf;3bK6_x$KQkVC`% zzT+O>0;>WdMaR}HTX2*Bq&qnMNfInd<)+DbYU5l9gXoCy_S<hqXlSU7Nu?Ke{l2j_ z@@&bh$O1%c8!MMn5!?T?*#`E>yDvY7p<`Y}Y^I`U(yjw$On(k}>A_r1D}0zXz{Fwu z@`dQ~=o8p`F&SBkRKu4GK1aRsg)LB(n34eDW|@QO?1FR0kKU4F=^=dlb8nz<mHOz` z`2l2Mjbgn*D(9B!r#lM*S1|}Xycg};cEaXeCz0$&8<dS&;KeBuaC>Rml_O)sFAY&S z{?N6L?D5g5kU*<cS{zkS*%oH>fRKu1Ch?AEXA~$-cWf7J)1BJ4onE4cWA4f$cy#DQ zOdj8rFBa7Ebf!U&<?9b;q3?+4xR8_`-+uES)VRAWR<2kBO5CAoll$o9oNi47CTnsr zkTh3NUvV}OfYjVQeE2BI$l!h5GYAFsC>PU{&QyXxKAhLSegOm{15xeHJ5Z$XAF%-` zM)BoA`X%gG`yFcE*A;OHL5&7o@cOi|sC;Wqt~cTY=Qr1ulWhN}z60>hs=bKwEr7S@ z%%PpgyTJD+wEHQ?GHJ*hn2BqNY=NfJ+kF&X9zO+l++7W=>0FiKu$F$=IQ8RXvSZ6P z&N`Wz@#3p^ZRW?gl$4d}3gG?upP^&Z@^;Q}lh6KiRz2H%a?5#n;%1+VC+yK{0Z7dh z+s|^Rz%rbUXIW}@N(7GX+lv-WAHtdB+!*o76!h%W6d?fw@MNDci4JDweT3cvUq^Ua zA$;`Zd$d7Yo_1WhcF2Zh*h!2WJQnYLxeQgBw8oe7X2UP?B9?F-m#6d3ij^vG%(Abz zR@rsZC(w?2kzse`0xC(CoyP<q)r#LAd=MBEjN7YJL9t>*Sw829UQ`7L<W?#Ca4wu8 zJ%x)ST<_>z{@sbsVZ_*}h|E+1O*(eK)HlZBmaMez$aTj8n6%-!?YsHt`e+~8V@yTX zB2_VO(OleBz7P#x==+K<Q#hW3vj(xM6bpjB^3qI1#l~RVbE7%V1vsm%^kg4>0j=sZ z#Jb(5QN3AvOZP*qnxN|Kr7W$!`hHBkgl%h<;K_ayuz7z38a>jBztvx0f9S=HZ4uXg zr#bdh?X&=-ZE%JM-b*hBZV(4<ywK&}TVpb9`u#L)fcd)AZ`+1k{a_OlwQtYgOYjY> zy>a8l&Nq?1=XkVk-TJ0hy*_#Jq^VG$!c}dqSFfIljEww6^=kqySEZ-q<PGeh-&Yku zN7JfRE5kQzme%0lU~?yJ!gTH0)x7rFYi9ZK<t8jF?DrM+8>#4w=2z9Q#Y=Da-{FAz zi;kDfj2SbGY@ODsRm)H!_^L6lwZVO8J|rYaNzxm<9Qfbjz_*o3n*DFQ_P<5+O-8Nk zo=Lk+s&J`E7tPvv(@p6Dc}@0wmCW2FR88e`M;(tgx01rmtXIdF(2#5<Ti%Lh)xJop zzUZh;Cz^8y)|)1GmNS0-`Am=gub9~QRI_2@Rx^6SB(r1RA*v}$<xGlqs`2N++WxZY zepHIIw)L1^x{LaEPCV<v>fqUHw>qdRnWO5+B&kw8=2;o_r&?`<;_MZbA7x*W_SDj8 zw=U_ze$%ibRa0q0E`N!8%<J=3nafhsvnqxxi#FtvV$PVE&p%`6aEIURxlQFdUCc!q zW0Xz6i{WR?e-<t<+YYFmtdVNu>FH5s^X84Fd(XjU^VZ$OF<A`jx3=`C?tWm)O4H`v zJ6LBnQ}Ld5X3drZmPcxz>Xo{1TFh}Xuya!*8JohzYMMDqHk(M6L8_fL**3cPWn*H@ z<%pwZ$->2EEA7E0uuk=@!*$UmzAzL2d1Vjr$Kj3mnrx!O4w~otb*25stfq0h{$@Yb zPo;isl?anBnKj?eG*!!%Fu~bNn0d=KQPnloEMR@ZM~^jUFGjffz@<Lwsaw^mULEXL z(IKi_ed(M<pNAUfTK7Cezx!}eYwMBCJ_TF0z2ddnqj<|~=b2SbXMZO|95atLt7QZo zW(z5A#!vms#BhL14OkQ<P>nb}h2Oy+PBEcDKE~fKlPPg$E3^5;Ig?Dgp7F7l&9dby z%)0fP3;|Y$ue3RL{?JaUZa!!h{jlAt?aQ{Dom(VYyi3r%+Di5I^ptS(^?MUd-pql< zFH>RDzSmfDJSx$qv&~^LomIO2WIr_}{*qb0cBxsmYK^%RM_Y<4lT*{S+fj3O_omL4 z1C}=N%-Z2hyJUV?@~Np+uA~XhQrx`xCDrEbGpSY6ZsUdBX6U0$Oy-~vQ?cG7=Hlff zbK>|(GvT?H&B8^?4J8(>$||#PT&gWjfAA!3^WNQ`S}inE)W=FEB0Y(0Tf_%zH_{cY zK6J`p#BT;yVJcU-WPda9xOwl@{>GoGxc*shF|B(%Yff<TT3fKTY^tBL?{{umVj7e$ zYO?ucHkkrSnQvDfv3(WK`M++%2J_95btaZ-)9EQ(7g8h4p*?%dBUGtg|NU-9O`J8V zbs1IBQ@Kv1rCc<7HZ3sC@44M%qM3y3Me3UMM-$keYCrknQ7IO^<P7699%G{}nGI`K znjbc8HZjuE)??>n`5{)={^zGU+s$G-wxo8Rdd4jH;5EY+M5auo`sS-OKUo!OnL-ey z2~j7^w6T3m7XKWkeD%&|%l<H`SIhDw>rcC2c5VFDG`#C>+RVJgyfOQ0+Ph8T7~5dR zj2veUo;YRK7;EZ5YRIfyEVon2Hbd>=C}bW>xA^>r4rWt1YNN{4hyHDOEYrgQUMeV| z&7ihLn}o|p%%hEKQ03mws@#vAHqTsSHoNxfJ4+@rk}jK7A5JnwIgbNmKlhH7X6woG zG=PzAqT`~?(q*gJx0~5LoC#d36Jx_oyN8}Ivp-pA=a+1f+Bru4r^H<_BdKbih2IZF zO5J6q%$jE+V-noWCr8Pj#Ixq(NrO#j?wnM|&u?CQbG}`xV@R>)n(a5W(=}C`Ht~Ts zcscMlaX@c6|CJ&9hqY#Ty}N(YHspe`Ma<qwFLE)_*Z9pFR;^m)0Tl!;$PVNNektC} zj%UV>9eY)qGiT0hC=vOK;A2EYgvpafx;_p7Bd0Zg6_EE=jV!8zo8rZbduVjidcAYL zeECfM`t?o!{{79YS+mThO`G@wNLHu*SfJ<dpMj9{5^im4{;`t0sc#eqWUzbZ&Yebm zH*DB2)4X|eQ?zJNz8JT!M1R-#agV9)-Mil?vc2_qIq;WpzzabBWvu-31!-f)plw}J z`~~yD%fn6fz$~Up?RIAKu4A4JSUR_D(FC@JJkiDE@Cz_^-us|ALj!WM7v?yjNHXUR zZ8A-3R;FFR!sgvi*O=2sj+q%#rkgqQmYT?TfhG<x@w3gPr9dCrc<RWoL$e!C*ZxyU zY)~ZAxoCGKao=7^VjsB6bQ0@RF@jZ-XgBU+_(^l-_)+uY(l1Q`0*eA5Z>!eOe6nn_ zIdUd~AOT?ny9=e03_3Mf_{9gNd<i=7AUIe0jz;GAxhNA68D-{u@u?X<aiZCE^tibk zA7jpi9WjRvY&26|dC@%3;!(3^)fRL5)OnLY4+xHbnluxBe6M-3V=I$8R}u3pZPs1p zgH!^Sau5;07f~lqoizJ4FEzEw6gHWV)s!q%&wTUUR&#`a;AJ|6(Oy=KPN4%HZQw1) zmPT;v^U3D6Tg#ZbbsjQ@PG7dR%w*?Ikf3a*xfsBcg^BEwE8IyiXAW;Oo$jk;vIK^h z!Oy*I&c)E_539035dp}x3*Rxfmn&<Emb%C6I(Wit+q2gU8~37F^}~;Bo4^f$6@<M+ zn?oW$uMO^gaeCw0r`O)Qno3%)j0N}g_0y_cfh7D)N;Q!e!_C=K`^}bh-<aD=7NSE5 zKa;mm6*KFLmF5^hiRh?!+B9^)+Vr$|vuE|!ra|R0v>oSf3YD#6R&GB=yPSz;#fpVy z=&)zak90~BpAcovoIP!hA3kb6ojKjqs&=<ov}ThzN=HKR{C*d)qER~+@z3&IU{o3b zlneXJV{Mw59C^x`aj$=9qDiU+Q`M=YLs*NzCs`a!p}oID+t!(Tt5!4>t5i3O)^4>< zh^&Jc)gjbMnLLO3+Ns+)%Rxw(`EdHnCNx`46I!CWS-1O)rHd8;nT^lG513~jZ%ezB ze0eZ(s<|8$Yd-t<V>4~W+vfa*2&X*JMEWeKcvbnlu_;7@d+zG`dO;MqX}y}x>!rRn zPN2L{Iyo}B97!98r;nNAd)J$eP4A+eLm!hhcOld7`RQiYsR$E(G2R85at_lW%gIAq zO|RCCO-Mkn2@EJ?KKx=0!RIuyWBVpEa?~jE^^!FvGAhQLKXurgKD@=udVPwiQ@ext zZtY%kjC~qQXDgPUcCKl*aYm`XSax#k3G?o&qfMcZoThrS9_A#GK8=6dk?J3tPW)qk z611f2EVFs-V$;0#-R6!Ob<C!NXJjgr;HUD~f1aE<ZJ~UX<zk!Wt?bCAC!I7eKGTa1 zu>wuw`yVsg4$)B(9|_*nn7DXmzv<t(g$X18*`e3-=G28~O9tJ1k&a7d*QUj$!QHh@ z&a7q4+8_6s{YQ?O7skD07A;uHwi3W(8CtW`M3jqu)$C9wNKGT#iBasI30LRV-IcL% zRe78clyo)`7te7X?=wHH{l-)dEks9BK_+j(>gMgatIhs1=gj430<&%&rpB0^Yv!AJ zl}mH|BydQ3ud8+(F>$odyL{ymGjz;zX4B>!CgR)~bNc8{X8EGIrZm%h{N);Rlx0P7 z4yfxC(r8ce{Z~hsT*28)hsOq+y~o1Yk6Pzw88|M+oH%{l9NY5)LHt%GXF!ng&s4~K zG;f7D5O&ENi=@q8I|SH10j&ByQMqca4sY;s;BVr<ze)w08|JG*T0%VbO?eqdKX}L5 zeYoo3H8(Zhor8S$*1IP5=D6k9Lya0WKmf|qAldAD?z!hY_cz-GfmKl25pi*Go~BKh zFaiDg_4C|cd$D=*X3#l}C%Rg-YEaxiCCE08=vzrUSbsK1?Y=~b5}>1<tBzZ5z4aH> zxX+zCho_%@+M~L!x*vc1aWrVq;Lnob&G#2^Ky%xzJ}nh$_pyKfeo%V#FRBHgM|2Q$ z{>#eq7Ubo?f13kd73}{uhkv_#?trL%<|yFO=>isf`Vn4v^9wY8qz`&^c>sB{QPI~= z>r^UYqayL{jCZkM!3sRm=V`R<bUzhBX(x<poNTD2QAK&#;zjsy?rKEEB%^+f%2ea4 zggfr3fgB;(S&ys~N)=J>SFWda_A~u7PXm-g!O7)*Kf^n#PVKyryz-n^whC7|n^`%j zD9V#+@udpm@k2W?ecHR&wc`NWc9AOF!AMB;#fh*B$X~b!^5-v%v7<(#YQ@sDf2Y#Z z5EC5%zAVP#Wh-&u@JR#*X2Go`ilK7l+i=HSccDzVa@e+IBVKxb0`la^MYZ5eh=@!? za+)7<&_?A8FHXQM`9mx(5+l!H*3_vub{Xg~=xKx&%7ZMvDYV0R7VpiPjfKlrAvrDz z`*!U{bYcL4v*bcK(o(QkDEbZPhgx@4MkZ>*rl+tE{i&!)H9%hzfw>>OkG}n$M{G(6 zRYAW*<Hpqx%vSrekE9L?sqr$O)U_Rcsz-F_GZB$tr!i^V3)ptz68euDkDApgBZxK~ z{iq6z^jKWJbOv92{T;qu{5?$=X2sn#s-r^1N~lSCGK(OVD_fHE-okb|TBA-q;^BWk zsD)B_R#U0*j*Dl{;GK8g#CL1gAU+|EW7Q9tg0f)8q2nlAC=|Eky#>8{JdUQ#>VfXt z5kNjBMP0(C@7J>r)?oXAvq+|$!cwL4<2LqhwW>96XQeXOwS6<DOnDPIvgPL3kHPs% zmzX~bvW0|T(7^tvRK6@#IK@};nf#DCwKFiO?n^#yUH=oFn>Gi%diO@7I(IQGM<(Zp zl(jAKQW>X;vgYWaZEMl!zLvO<9E5(u#$e>IehA{2RGHMGc9p9Nbd!<Wic6t-bTk%! zy%f`4e-AaO^8MtXUdWw=s;ATmm6ESdN-TD6S&t7sT}(Tc=TU{@tV$L3Y0Z03@RkDB zHm1~3Wvfr>?#iWgBV$lYo%Xq79aU}jopb&@X|B$pI|4mUee6`#D^m@hefB9n|MW9z z)yLD^W+H;JX2Zz~7m*&21^M$8Lz~uZ(Y?!q$QsN7r1G7Vh`l>^V$s4S*t~TYq7zb) zJAWRUy{hbt-x@Wsf7doleeG2gED(a|xOAKer&@64EC|V)6+@nW3b)-_oZMwg*-v)0 z;`(FNZ_|@-;lyz~GhzZt(q3!dr#d66x>Nlr#z~EyWN5iE>}P^{*s@{?h75cLn+~1D z6xz$}-LAP+(UlgxY=BxGi_c<!`p9Nhe(@llD&tXjYsy=g`tf4)rOC36?e9mHEQDd1 zT6Q~QB2Lr(>`Pd>@gRB)8H@YtS4R+ON!Pfc&E9yaTQ6FRPv<WMUuU3h?OLc*t_*6_ zu8vG(nyrUaIBT|DFkC~+8B>-ltBkFFcBpjXe*dRRx{}j!)RkGWt`S8wY0aasurrwT z)|*(jW(^YKV@Y2C{DZP$_rc>RRHzv8(|&009zD^laUE+iLuN1%q9d_s-8wAcdcEz? zX|8So2rX3vRV!EIx?TylWXp_M)84?j%jc0bPXXG~KaY@H`Dh*>9#8b_iu>x-;l7JJ z=i2|nvTtc;at?aZHtan$t8z``dQ0;Q^SH*oG5tOGaD1Ji`GHg6myt|cxRp77a_29I z7VX;O@lI`#S^C$>G}A#79WsRBY4{ZexZ3VLc{y-nIPk9qAl)pE+_??gM?8(_1J`$^ zQLt%CRGa#?JNZp_Ua(*R?!W(jPrI^Y$$}q#_yKaTa<c~6aa^=$k*9g(%a^A;r8V}) zjVJP&i}B;fWAfz5o>)pyV%)fKp8LQ1LbMGUbj6;TekheJS(0CzVOIgIe}+z~aa&uU z*8-CT3edta!^DXbL2uypx_<ropj4c__I}(r4$w=x?E^Q+=swF9=>I3E@2O_}t3~9` zpC5+~9ilP!Y`>b$`_RjQe+mb_fA|3ud7vGNJ@m*wg`|HW9Rg~&)wLUZI)RCy-QuW3 zWDd!TkgS=xUDGaFHU_yNCLR(Koq)L5B;?4G2Y$h_La5EIv*DFJHrYMA9F>Hqs8|FO z<dGr&K&F%ZK?T_kbGDVgwCi$jLiPMg8f{b+oEY7?Vq{;=l}s^L=Wsv*?$@2oJHL-T z03_|+r6gX)`LHM?(8&b+(~*tNP10#QF(DzAw$4(yQ4d1?LWPl&PI$Oo<c3#AIuaA( zkPy!!E*Wt#NeIjwh@2rgk(D+m<!mL6JPe~_ya474%p@lyvJXj6j$l%uTWEib$dRo1 z`O=13RAe;Ld;<}bBfE9N5I{#LX(`dT5FUxBIN7LVO6xGeaeR`_#`w`rT^_FYIkT{T zL=)Rb0VQsf33So6Tg=6CSVmwWGKmghaur6qw)L$|LVuQR`9oW7Y74pHG)h-0hi#;% zX86;|MCAF)NFsokHE(X({-fg@KGOh@jYNv?ATcf;ksJ##Nh!#dBPVj@$N@Q?QM;@V zKS4e@7ZGj3Uv6ZeP!ZcBS~%YLQaB|gk^Bs!ZMOta=NZ{(drnR|;^-tMC6xd=fsA~) z^CCx%Y_#7;sDa~{lCajnMqG3};%F-_Ix!w8v`?3t;9>|JrUVMyh>gOzut)@CqI{K{ z&DgO)+k9+y?gIG<e6b$V;J6#%m6&XK!SQD36o$OJ5S>CN7TJ+CD3H%MM#Nuoo03tq zE$PfTHifiY#CJ=V;LtgPc!K1;x_3e_!BWj9vfVoP@zaH^z*fR*1$F@Yi{f$|*J-$T zDHd7T&g|KO*=|`Ev^~agOFN0lafs&JzZ{)N5YHdEa_4f!w2C7=0)Z&~Xl>Kmk~3Dr z2<KL#NQZ)2f4%T~(p-~|eM-q%`x0I+`t{rTQbYtIE=Abtf;iVQk>(`Y=S-k2LAo^I zOOIUa*PI01#BWhY8;dL_Auf`?$D<Jw!@0(BnmHHyl;by;wk_kMqi{a_0x|_>qH`nK zpJkuLC)2?ed0U8mnuYUO_A6}*NrT{GGS}K%Bnpj-bUKCLoctY@l@5IPOx?~2U~PGl z0+B(J4YqHSqAy|N+I83$9)}pBf`cA^#LhEHK03@)KFv`ESriojskKbtq+S%z3%BjB zi?ONft31dS9Ar~lTd1tVmup-UK}Nm{Lblxbk%QyZm+@SA=%j_^q^2O5bAwWYh=_=z z6R#Y|kv#|7PS+~}Ohr4>%gK{oT=;NYUkReiq0L1s@2?pUR}%l?mH2oim%BVA=UC%I z56I2>W$QJZ4sBzi;;fCwV1lG+oQJ6iNp>Fl((b7C%$mo30&wkkVOt3L#m7V-mg7G< zF&T*j&_g(n^AcG0;~Eft?yR*2?8BEy0c>M3$4?4*lP?d;vi2d#2=;YiOf)WYEy$K9 zHv(xN(w}qH$0r6fo5V2_&oMy$q^Qq1E|^7~p5`0C@s$e&IG1eiXbo1Qx#rt&rSZ<a z_tVRP8^{4K0O?|OI;DXQy*&*FXH227Z?2fG5WpWd4VJ7$AQyw1G3X1uDh>Yb*s;UY zya59SV91amp8K2aLO|og4?pZ_mZbicELnoPC_(URLC+5!Jm^WXg+|QfwCA4?F7fSm zsZyovmyw$uImmhN!3XWFo=Xx=2W?;4^Vzd!xw()Rzds-Jg)309bm`LE^hH5{q=4BR z{6Xan{~Zn_bA38+;DAS((G4`JZzb{gXM^TJXlN+PmMx2Nl(f)UhvGDjG~V4|<Hn8X z*s-JaBI=GCK76<ZqTTo2vzG&24tP26yEq_ExZ3z~{YvNNh(dJ)8o&)1!3%Ec!Oa~g z&8Ho-vkBIv;{Zk*RlC6^a3g>!)yIk)(Xj>NxhK;;T)Rx}%e1X@ZZd2;e@@>uX_(*Q z2d<pF<CSZj{Y3y$Ww=r?sg)igy(&jJDG$Z{vn0_dF~m(GF&)M+9leV<&Lw=1B1aR< zW5Guj=i^5yPx43`UBO$#i)>JtOvdt9vI{(r)08wu3Zn4iM%a)}ft%uoP$SCN2?pSE zKT%?7(j&u7b^x7VI8ZHXcC}AD6raU=Ri&>P)yb2M5Qr>Tgerc#SN=ro*?9<uF8iT= zoja^^lT6%ZThM^Oit^dMu#DxEt1QLIbFX3B(^(-MINQGUU|W`N%uV1%UcS@#KzRjF zs`-{UO3C@Mp#p8v1h&{l^Vtmu{5fs=*h&+URv$LNkU)946)S1ijgp+?E<u%aN;(=U z?xqohl!UA0r{!I$_4Mq|c_2R6MlpX9K|DYIOyr%Ueg*JoQ1}zDpiHU65Y;IhBOF2W zdhKV&jnhYpVNwzx7U@P_<5gigJ)2Ow)B@Ku3qZP*(%<80TFC|cn$#GU?ThdzI(4En zSKHPt>Fh|-ch0!A{c1<BGbU7u4YoqQV9>ZAXreKxah}fKo&LNRLGlsKS!(;tK~5YV z+A+t1(l{rqS79<&UW#o4Y>S+_RF9`V-Pl&DV%2oLpl6mao_{ILHTg8J6jTwj>UWmy zQ(e2t@Ua9lf^AeEx#x^LR||k;6WK=2cTHSQB$LGU6I4#6B%2EMXJ6=%=8|TpA-~nX zDn~JT(c(y(>M40j8U$D|TG{z8nZ<M@F@mmaC{@Zn_Sf1%@6JlYF(d9<P)&1;UZ|Dt z2tn*sKWxHd54Yh{QqKI&%E4>PSoIL|=}(o}56)%1BuVo{3Z?A?DBAUd=`{?U@y`qX zYaZL0HTHR}c|gr!UTdAu!JKTTidH){k=-8bRlk6BJyHG6_^?D-+9h4<T&Q+eJg@#- zu(jK)b}8kRujnOV>QRS(4h^C|ouIid8?Kq?LkV-T*GfKGo>?AI($wwknr+t$5%D60 zfVBF-pX-;eb%ex>Bwy=9I$u06%C6IL<l{$xlNNtPiJe2#cegE;WVN3b8#{LRSm2|Y zuS1Kbr8t#oNgMm$#;`mee$QGUm;AQj|I0F`6z`{(1AmGGUI6kMw#6JdWThb^e)`cq zsq(@k6m8q_np8K>tvonq^kggGNZ>;D?AdRgMrLS<z?+5*8{){3Bc52Pj=u568=m{? zT?ly02vCNGhT`baqt2K4^)lSxxPb!)QXOZCr`BS{isAX^pXU!Aef3;F=uNIbNH;L) z1}6np{!t)H_0WkCR<B+S+86x8YTVbS@ZTM)J`h+e$x_;D^hh`U73$NpW$FPL-C(0Y zWJx<-8}yPwK&0DTLGIkS?fh9xZ-oLO-GMe#apJ@Ys{ZA1M|sa)4tP1><-jj<fSWCC zn+2|M3uZT4MjI$@j3jAefeCKR1fU7+P>eol$jSm1N~?XCHpSZL6DgtkS)kpnQi+e7 zHkHl7xGPMh#Gk+P+3YUu*LGgEKqs9lWUx3H&rU8yx*lAwEc-|sPUUph<2t*u*)~w> zOXwLlgOXBGQh$r0kt5p0a<ghnaJ7%<By+L7<c0RPf&?78*iQcWkP*yf^U14t67y+$ z9H0%nc&d#oPpZ<;>#9?N17L_OUjb1pn6f^u1~a{y!LlUjBLb~3m&&zlboxVd>6tBG z>ACGS>CyOh;bIi4(hwz!7C^8C6>KFeUzwGTiERU%c8G@5lr(~AE}BTUydL}8-8oY; zn{A^u^Q1|@nJ*C;%PTdCZ4*FC=*9BK0=fJSy;^e0R{h`maQCn6E7B=y)J7hX9@U?( z`ay%1;6Xa$eF!>S34{!6Itv9cpH!#WMke<mFih)%yrAI$Mp&Shd=Mw)soDZp0=rx& zvz<PqM;?_GEC4A|_@|!J7}C6Al#1X;VT2+{o1Y7y5TIoNWdRp#%kF(AaQf^y)UQ`t zc%&UKk_@yUhf6|@B{*fOT-_+BSbm5H3Id`OBx&hLt?FKV%C?9-YA2rv{P9;CZ8o*T z$!|N`B0WxwZ3CY=L1}b2b+{rkoZQb9^-F0oB-f?w0P;xSHrEh=kG2Z&jnC{D(^yk^ zyjODlCKi57D~6OVW*Uy$biQfu$)thIe>*2R+vr7J`TYn+YjX0DLl*l|aI$U$LU|}< z0^0)Bt94QLJm_#n(}F=ayk;WJo^+P2cs;Ve>lv@{1HOdNSXjDp3(YE&MA_2xvaZ}J zmw)=*=jU3N6r*x&@w`&W7ID+srDtqAd(R<+eM<|K<N<59fVqp`e5^4b=|-)?k^&Z^ zB+*F+;2adJofQZg)7VyVDmsP0nLmL(QD7UY#@ZV_S4Nd@Dd+kB6I7uS)RU@2CF?_M zu$@YJwSFnymy4mGS(C08W6s)X^Ke{p<+6FiF*QZO4t+jLBj4$Cien<kDVM3mb7=wS zC7a+$KIR-z8I0pNp?f3N$=XPV#+1NlyDnJ5SUAU}mJvxX`%s!yJoQL#sxbR~B0}74 z6u-Q|%Yna_16}~~I{eqddHj<P5WapL?w;|UGkLF*?teW>02IAILx6@m&>;o-_U-Gw zz3I-=r%%61N{b$Ttz_44fhP1Gjc1>I*252}IxFs<5Cj;~fe7N``9{+fB#kD?#6J_H zZtDgkGlG+D0P2^@lx?10lc@YHHSS+3_umjN^=Y>xqx&r2@vl&yE>otAN1D+MHvZOl z&&YF)f$G((d!lqLiD3oV9L;D4Rd!TIj~?ww>%H)Dz{>$I2Y!(Q+COsBNo72p2!cr} ziaRXsmD2qQWbx9U8$8<Er+O-XigClmC<ekM+Q6pz+s(D?g=wefLsW!vKg=$PA{W%f z%{Vh!V8*qjWD2JgmGtwVO`4uxNu#Zsf)k^=j4@Zzd7|w`&nd%#1I(fJSu)+lE5cQb z6?EgRXx2v8)*zZ$Bjsk8QSBwOxXV<l1URX53t(|CDIh_gz62yx1ha}m{1b3QNt!gN zbiHLzUeU5GifeF!y9IZ5LU4C?cL?qpTt3_-Xb8dG-GjTk1$T$H*!$ie=biWdQAHIs z7gM@>^cX$n(8)lmB)RaMlZ*?rQ<2nI`;*0|OxLAgq`)Zc31vH;@d1rY9q2F!JtZ-H z7pWkbZEdIx#w@|0N-V~2&u6bzbd$vCy6j7*t+3q6TeSKNTlHldVvWdl7Yu3CyYUms zp6D@t|J*Nog2>0&Mos!_^{}Y6iu%hRbk-#j+_-2hYb%A9XVnR}Q@oTlZos$dB2=e; zBoxVkN<C=ioP;2_AP}LB@B-!A?#%E3U7q5V+G(9~Rpdbo82qSws#ohjM{AcRTEA*A zoepk>xA4~OBw>cF$qY8*KhUE%xx*=APc)vEXckiI-`^-z>g?Aw-bJ##&&9ULpzT`O zVeMXNSJ)Ue;exH5VPm9_Wb2jw9sQ#eXbgLj+l=Z`jOE$-egu`vfy^N|2UEI@@F`Kd z3{04BfJ2Z?J%2<s&aTd`$+!Z8o~6PA`!nZ;Yr-<bqvFI`pcYgX?P7xtyudg_q#f*J zM^1LV*I&_u;O+W>nkSi<nHQB#smL)w3RJs;N@(IGDo$xtp4Z}yo9J4S)Et&yty#*a zCHaN<^im>fKijZYO@wB$sm}@gcu+jbJS&|-xqk~9bS*?R{4_hBA4-q8PTixf?4m0% zNRJk2|Cyjw-;20zO;Jkx!j62pOaafgx8t*uHd8g1iLgTG_QHzdz~0yowzZ8FZk|Qa zm7Oec++e6OJ$~TEU;C+g1mWOckjSa3qkN=`*y5tlGigwEp4$@3KjWYWV>!Ny>TPHe zbK~6Kc2+c5C10U#$9fxNPPNz!+7An2)#=g{&BEoqSQ>Y}**Pv8N?s&#CCT0u&01%S z4YIPMa92|FW{A((8nkCAeOavTaSbw)-qTZ_!-_6i?3_<zr<z_St@(6(O^R}xFuIkg zcbne*!Q=4e>Ebc6=--g}(RkPS1G3g)LVTe@Pry~CCL*WON|HP3%b9r#h@p?y^`8et z^K65Lz9)1I?4!<4x6@@TlJ6zYfcvl$;04*_@IGHlK`0S}xA#*dAaOSD{olog`p&qe zfifqL!+;Ytye{~gJ!r}oYv}$RenBM{Ymr)N(I7GCRlxP_W=6qssix?QRVJt1#aZk5 z^7FgNxipx|@AZ2&wmaX6@kRHVL<X6k%1IRPKTwl7o;$wCWd5RfkzUgNg^7-yjJkC1 zE4Pj@`G02t7+B!czU3aQp6hQ!<I1Ew4!n2xYzW-1*0vo89IQW%J8zg>Zud{I|Jp-T z)&@x>dinh2u3rtI1J{74fHIcsvdyZ?-F8dKTm*}I=dlYQHxrd(&7+7jzurAz(^AU( zYL#f^J>qk%l9E{ucZyK|xZ_%D#+8SxLKM)Kr167$`1iRlk5}w?8%;xl<^X0br?0y2 z<){~4_`_V-LC$NT)ud&))@Q9yS5H0RPwq9phn(k<#iR9>bU8TEOk$*cFZ#fsa_riL zMEJo$5KaQAF+O!t4QZ@n*D?}!VvZ7eX+6A_kmYjqv^wpYZHLj+DKE%)7!Kn`Lq$<k zit>hA`P7O{;Z~wuzpdg-SV=;cRaGclO|n_~WsTC*NpZQZT2N_H(1nX@V06*QdC@k1 zhfEiX4M$ulg@$}F&b^P8P2C;~3g@=&&1kAqhM?qMb@au@g4fo}stJL8LBlB!InvoN z<2IA$<0xmRXCs(b?2$sWoNw;JBkB(lupE&-rQ6t+rW4hGSH{T;mdc^El2Y)k;r~J= z-PI_8XfyYFV_1|-)lBh=G48$zud&&h_jC|uDO0>x)$s1+sP-t)(qYz*PfZ0u#UNL? zPlvgA*zm)g_zf$yc=u=B&D&DHs+%e@V~thA%l<@qj(BsGMqpg;qwiUn+U9U>FJAl! zHvMCTu4ohUgLNL{(Ql|uYiv&|rO%IAwJRo(;K#m}GAkQxr@%OhZ!cgYYsFz?mHID( zV<N>sFYsJlpuSAPuu%3V%?4=npvrzNS2CLsB{GTnYrw=Gl9b}zu^v-T!0_HrOdXz% zA-0H;#vq5*DA=CXEGEKvxLc>atVa4UcTPS4#Lj7Jo*^Z0>Uw}s!*SolJLfEB#~s5w zA-Z4V`&}aTj(RTbR<}O$RuJPof%Sb_vv+obM1bw~e#A25AK+aveyvM3WvG_UA*V2Z zA*a0;T_}J8Tkhkmpkz*4w$45{FGHPkEV$52TWX^s4WF!`;Dzk*_685X&!535_l5R6 zfiCbNH2_g~;GLik5jHY_u69Jg`;Pk+vCev<qutrBlakl{EE*aSi@O(nlQMA&tn|$w zjDq}exQ+&xWGF6r;TA~P+P=awvdY8EJPDOiy>bMQgW3H~Us|1#u*w7URw@h2c^(b^ zHnl${+B$IHHM;v6NaganB0xMXl<QasOFY`QtsTx>wU&A>%$uw7GF~6?k%r|0mJ-WR zk;sI+hQQdJVyjol->Rj`>>I!E&ZC$*JifHJtvFITE>KkcF=E*Dt)RSWf4I^+?zMX` zr_8fU8LAbnk$<qW>&#O5f~MhFCVZnkHIYSyuDboS6XQ*-e`~Mv$xY{9%ypj%qQ|rn zv0V!}jwv|~Y+SZ@&dX!za9??C<ZrMz@mgAYbCc$LL6Zvj&ng|%`}IvDIz_(6e4P64 z$4$mIbQM!xw?<#oRImGjgFrYN?$g>Tf(Nl$i`^v7&DVPp355{_Rs~CD{NbiIe0S=L z$_DT$_U?I3a~i<k;%)rC^VZRj)AjYWV!r*CHwXO<LM)r6TFRfLhn_UF;T`)Es!ETz zZoX5!SM83IvZ=~%Lban0^DI<xyp4q(9Ij;q@Anz%3M`(=XQvIGWhRcJt>{fW@J(R5 zW5Y)sbR4e#R6o3@$D1(uzr|O69y|4;02hwDvGap-4tOG^XHyRR!bN5!B|SP>{NWsb z-hQ9si&r_w<GjBK*z&r1O!AMgulhM3={60*uSBoFP`J(>h?}o+^%e_%Pk)kL8Bevk z{Wmx8?Xfdfi|V-Hv5sregKmGu{j1<dXaE$8*~PoXBE*@3PlpATB4veU^oARh8W0`y zfnr67dBUyo)T_;zOtnW>`_f&>0snnbb>W-P9Vs`ZH#_2iGr7*C;&}}jkNb<g*p$|4 z1}HqI0D|K4O$RT6OA`DMpgGERqWM}EkeEsO*mixFSW3OjaR@tz{mZB~RFN4q^TSq* zdP3vqZ#vt8rOaEZ<tnTH`(CQSp^TWIy-ysYew$?-CPxE){JQkPSmwf%WnK3GpOK(% zL5IVB%inTXWP(G?WF}Pyp=xYKUFNnG;j*st?Aeqd1tgqQUHFIJP`Y5#8Wsb4qyKC9 ze#sxp-%CeAX$gnC?)<iSU4BHgO~l*VG2UcsEwn!r4|!#kMj@4OJS*Llx<8f~2ABbk z;Rdje0^)fl%T+EiXoynv@(dMvjS5|0BFKi_^PDqYTTI_pZ&*y6P`XGI)Bw$pJa8xM z3+B8H<~Vm^OBrac&2&sSI4g=})3<9GA)%J*?N;va8cf)7Q&I|;Y=~sWr@8B`fL_T$ zw48SL`}4;83E9AxQuj%!gP=^{zfO+s2rfyS4ws7b5#0XoR($MD;5!%ayP;P8xy(?M zzMKicuNhy(6s<3)P5(G@WSr=o@y_p?%=je<HKs7=3}_4fw4i0JtNXlHGFc4Rw_!x0 z`?9f{4x!4XF?Z9@zDKeS-$CPXSYv(^3{_-uat?WO%^+b62u<Kc!ToZNR~bb0NH+Id z4RJcD-s*1}i{)e<IOZYE&-hg&%km|5tLZ|Ux*{|CvvN<m)3J8%`+-(EuuO~lLury? zU`tqwzpXm|zrO&8*X|k+j9{MFd)|J><}b@lf(64`c-E^i<O_)tc@LS8Aa<4g)<x%4 zIhjl;z=L)qovmcb??z2UJ#*sSi$KV)?J~l0K?4leN~l;ezGpo0n)<YLx=02;(Wn*l zFNIEHTrg(A1VB{t#rDtU%CJY0XfP`I*M`T1UM@ucXjb=FvAUnFa=V`qm|oc=%4XG? zjhg2^^|A2t6O^iyh)YU_Z%O3s0Qic}SDU*|I7`4rdrH_HJc0H0zIgHMb6_t-gx+_` z%_wwD<yKY*1IyqSruOZqlV<+r|6G{=af6!9DK;TM?pD$TI8L@^wc^~ZMr#}bh2sXO z_5OKonBc?SQqz9)npKAE!g3i}EZrgA!!v6q$3SNcR4HsFvP^O9e4fYP=4U&|VKbix zG|I*)AIDTNO$_qNbsF<EtBsNAtY(Ti0-fwJr&dZgci^oiZqGM1Sh`aTy5of2Z~znI zo|ngK!ZTN3iw<<d2m1gz8;Rp$af|D5hUDU%=U2V~s7n(_5)P_#T{^G?xwRJ8C^!3q zR*C<QZTs&@e0cu?jvde@<J{qJM{i4j+WKhO+_)hzE-rVbJmJJe7gGaR1o1+jxt~f{ zL3uqFCGKwn<Jat$>2Gcq4B}u2kcjwkf?<%p?_%e|Kki=d@5M_Hi5$<D?<5xSEjI## zy<e^sO61a+MhWyc3v^)?*?k@yZ;lrx1aBh>=CindReH-CT7NA9tjW1D{<;!nj)wZb zzb=5i-Er?RsRdSS^O3cV#d*5`PuKt0iI2DJKNsjB@#8_DTslv`gl}l$AV4ExlWon6 z{#=%~{9a-0xb*1$jDv+`UPs(cZm==29LMK&62Lxj0>+SV4*0&r{Z=bmPx@shShh)W zFp<l(2c3ViT#pE_vRg}^+*=hR&?!l}2B`w$x9|P(b_U}LyzkG#3$dytwX*@E-9Rws zzyt&j<3!;F1)<m3k53A!^LVZxU@`s{1QTWg^AnAG71$w7Gd<w^T59)nzTU0KZ8%qR z9-6oO@6+|)Z|d?T{n(JG8IPk$a9g~2;=z<xTQ4Qd6YY%`TZrk^etQ!;FF-Wp@wk_o zZFApxXHuqK9^FtNV3>Xcu(uEHj*#LIvFO8LYN*lgMw00qG|%-h!>#<XNkw5K=}!Ho z*fRxvdHtS_zDOiZpCuI+NTLn3%N=r5vi9ClDuW8DO$K@Chfm%C#i;W*hW6KqSfByI zZEItDy3*)A-j4BM3dQMWfUvwfR+8!V|GO{VbRS;<dnMR#^TifV5Nzq+oJ2&2=$S~| zR4WL}FrG{-8Yb6QOvw(==!<<s9_ix|{6gt(n;J@9d%c(DQn&3Q%z=`?fYjEdf9~~J zvY_??4<R7pEqtTwDEqY9KTzbkT&nWrOF&dhLZ}H)OUP9sd?gp2E=KrFy9r#DDh1zd z>QmvsU!1;xyUmnr;^|As_beV~DzE#q(<(ZHIAF%S6YxEmTn?dKUYS0_4!_3|frCZ@ z|MI5nyz9}%@}0|b{&V>MjGzDK5Z()aJb5S~e;A`_IOU`v?a7|5vdw9V6<Pp}DV{JR z@RGW>lzBKPOnDU9H8|~vhhba!dBF}kGWNwQUf@A{D6yL;0lj#~lSLNl$tWh!-=WV& zi&T%;H^`DE2VeRM^7ThGO6BlUxzfHcw@W9}-kI%=Wnv>}?#Rp*N?}L_&r_wp(Pemj zr3C*4$i7?`QzzscFq{v9zWkItnO3cr!fW*c-%g+dH%REppN3Y<)BA#XwmO!&_}$a# ze{Y%NhIAJ+$@xlYJq(qQ7o|)}9}sP_;%U<)00~?6^)pSi<JQ;zq&y(yBIzHu#|z}Z z>6c%RK|gQ1Muz!_<~H+xaLs{<f?0zWU*FJxJmu^`0x(bDpi;>B<nRCfV0s*TTfWH) z{5|JojHcyZO5_K+@K%d7`K^+MPe5KPx2(~T<FO5INw|D7%G9}<a96H3p%DwA*k11s zE$#&?964M9HUiw(jp39^E$EQ%!^r_mQoyQxtvGe{{~J<4T@<LF!M{O+`6-2O55~Qt z_Om>&Y$$>yMecTj?LS|`3B9Rn5bo7BjXaA<FOfz=qiZe9#ac<)Wx#m;-gx+1BJ|`f zx7}5B)-O#VQGEGuxk41T7{&f#{Rd5!lJx)_Pp5DkgS;n~gB>g7Hf}o=s?R9%Qu&BH zlH(PE-C8K5R>(gk^(4P3_4c~tg~EBi6jnh@%?(&6T_6+{a2sR|G2F^dXg$IjdA<Xw zM3wm%9)&{Ai+bkO<JGk0AH7yixAXPW3tAPk$KBS?zcs7LF#86IKiC?;f4os)=k{Uv zOYS$wIGfpDfk6J=N2lQa+c~fdc;kcXG{tCsG0<PgNI3jfDM9{7z-m~{|AwoS$a@;Z z-q+2K0E}otL4Z&FqpM5!fd40DVe&FSa1OJ3^uM`tI?}zMU|%03_Fo;oqkJz#R<YlH zZ~sWb+*1QAa%EtWr_W~g)$kSU<vpuL7V%x4TQrnT9mgaxP3?8-jrKOM>_Fr%5OrgF zFlo2#T@Yn2a}C?lo=vRfWzkl-b`hD^78AzZtDfSBFQrrp1s<gdk_i+MbC`5Fg1*ab zdCS$#*f~B|QmTJ6*YTp>&d~a*hW6K-t&v;I?as%FH;&d?qbm{->nTa$PYihyZy3#| zlYSh<Rz-j-xEQliQ<dd3ZI0&}ygcYE6wIcP&S8LhoXaw#ycpMi1ncu!yF@%rooM-J zt%e);o(YKIxA0W&n!@)cv^Svx9u$hz*QK}4YT>-KI`@o~x+CiyrV3&1Xk5N=6kQya zXP?1A|CFzLA}+m()3hvdayX2(x|?u((&Im?km~)zH1D_mTow(+HyYPkA6q}|y7%vf zRp<^seeVqXh=(NQFB{;)QmK$RT1GdoAWS-%frb;1Oj1S+E+xqJ0w<os`<>wWz&{45 zPF-eT<KZ^P2gdbSRaBY5_Kq?@W#V{K=BH#5HEsfxoGk9;<9^9OGbIbc715{F)1Hq* z)%u@6fv<cU&k4QD|F9W6^*6pKn}XQ;o_u(ARcA(8J8s%932S$3db!?)G&hoSZzOp% z?SU4(mI=g3zv1^>-aCTt(AJG4D|Wz7`elD2Hx4k=;T1&<-z$%>HUObWJ_cbHNhJ<M zsM;IEofm*j1DaJHTeyn_Ug=+e_^HKG`xk?DU3l>pj<c>8nqr<XxJ9hX`OuF*eZQt% z=`M|rWT}G{V_`=$Q>pTp=#-f6_@CQCnQUDl=KyWFT?gmI@;rveHJJ1KT^hb#?byP= z#=0b%Ct=OA23i@64u>!ysuv}u4(GcK`{RuHP`K<1p>Y7T{=G$KDwAGMyop3StD1EZ zod%W`kw;gZ)2XKMRlfddjw{2ytCLCc7BdnWvJndev5^L9U#gpkNUEg(c%f`MjMa3p z$ade0o@hGWWS=CJ`STwKJQGR|GkGoXe$@$biL%DlS2+gS-h$a8b`8!d+2X&=vG+M` zl;-f_{2m9|Y~H6Y1LI{#JX(9FZYMSKIBHaW;x^Y?L=5m39n4@9C@^UAZI<IVZPoKd zIb1EBWaK?nUj4?hSvTOU2Q+eAoO<z08tUJwn)LA%kK*?DuSe<xuBYbZd>}woy2_*@ zzv#4kxuO(J>Id-+9~yGLK#=qcfJ?C9WIO8;^d9YmU9K%efvEIgTACm_-pxr<D%L~x zPx&@)8Bal+5xc07n^7e=FV_x9)CNdPY$X<E>(~3u1!r;xSj1<IAHfV>9*AA(UBxFu z+hU7+&UlgcL?JGe(t4@hVz77f-=uQ|1)!>mWYe!&Zqc{JpqV@me};XUG`g-dWN7?N z2>7#D{LSDPweR`%o~%{HG?`4NK@!sm=-PT?gN~`WV|`TDQ7A4RfKid-ilzf)By22F zc%c^KSu9J_yX}2Q*-T31+VvO5m7TowlrCW3pYKk^YZr+?vVT9P?R!ylmR;|UIY&}M zv^QcEId{u7p@)9~DsNMM_%~!1Z&znOwwTg7L8x+mFw-Q?>iyiSdQU9)*_KB+J6R%n zFy&@HI7FmgtG5{5QEW4fG-Q;5JECXg3lw2xYtiCOhpK2F(nQ*N{a9^Zyt1!Mi-Fk2 zptXV;hrW^#K;F5^bFxyK2@dDJITT+|N6-{9npz1efioRX_-r<sEE<tO3F0yF3Mzn5 z(o&G~&fqdk`$9)XmH=j6#S$S403<9Um$an{=htN#XR;%Z0g}hVU@Q=^9PSy7I+?9} zy>WAq9M-;rg=JSwpSvbo)&F9ZJ0m8vR2SOi*z2+abh%Z0nJ$?1ik^@Z^9s|-1EgzD z19(srTzgP1_V{2|w+X0T(KDKW1Fj!&?<ZD`dRUhWdbcd3h*z=f=qgnithcL&UKQf% zo=He`GFFx(n6m9+V@?kKeg=1HKFqnyHESsU6*RO#Yg&z$#@65qol9=r*}d9@Lc%Ar zQH@<T3W$RVg6`DZzg?{}2S2|D4;)Uvi52EI-|pYq#B-`(sa8Hy=VsgHzAlq56b#C5 z?EP#VYXy>6N9_O9L?XZ3%Z7)lnCWd4A-kXNFNcrAvSKpwEEm=#<H;@l=#AVcq5ZV` z2ZZ`ML%>_&)$wIB7=_um56*%bcytB~{9j$?ZibuD-N~q_;eeSYZeW71O({I?fOFnz z^4V50kd@@=w|mLQQA#HXZ*=%(Ux#F&UL2OU)7tSoDn*Yq7F9xmGRVi0<q&WRZ_^Zy z0H?yKI$IzwiE!w6+;8cPpHOwU=mcJ{G!~Nq*W)H^J@{1__-{%osVF#S@l9;shX*MP z9qP*4E4ZAw+K*H*$keM6)k6nECQQs_y@lyk0yJ}W{drI&Cxvc{%bS$r>zt5xc%w`& z*yH_FDCCpUsD4E7Qwn6Uy#H(34k|lQ(q*v1i`k=#+>aZKBm7CVkCjCZm!6hqAuMd{ zB#e3qafh0;+UyHE4*P?|-4JcoyO5DqojUktHj;vlqW5(!#k1wT3ynbV`zO!ud*AK| zmZEhlzvo|ZZfH1HaymZK`~%@uynK@EeIsDgII2cyieRc4s92{2k8)A%=rbjZ>B>6Z zPq;NRXsA7*I&s#Ei+3-eRo`%<QHz}lSZnZZ6M)C*TF)S{IlDde%<*{P$3s;jA&<)D zbBE!(ClD4MsiW2=!A_7$pRD`Ik#$JhWe#dM1Qp=KbfnnF-DXzW#e7+vX(b>@!v-6f z@9o))^6D67fl~PE@#i3W4|3W|fP@${orW9-*S{4U7SEuAMIoOO;*|`6^@`e)ieHxU z79J<`_{pNu(La-%7*FUL^PZmrL@#BWVvKU4?Sxdv#7wuWH_s&$V=tuvA^4F#-BiOj z6Y;eQWk-&Y!-~;uPe{%`YIj6`CDa!+uB0BjTA|A8qDm)~d1e7Jd$)OC=QhW!ponPO z%sp$v$ikOZ=ZUpxoT9n8A{p!wd7!SSb~#c$;P1eI04fX5QA~BT&U4s=hOEYctbO@6 z5)*O<3|ld(`<(m5k&WXv06+NZCu%2sC`hvBFvAyFPv+%q<FUMRBS@Rj*5$L3djQGK z#{Yd+@=rjGy8zeef2&oQ_5oWSB%fa2lKQQi@PTFbfxox9stsID3tpdbrlI4GDnwvR zgHH4wu%_LF+<bEoDP|f)SM$moRKDR~<79g#vu_saP1sKhHpb>mZ?DjxmP3~;9wiP| z2Y0XbSZ$<}yEB@=FqX?eyTAcb=H}XxQru>Y&Px5@4fXe!O^{>KPacmk?Rv#RO(W}X z=EBMu780Rhcnl+uu*eub{8mAapBc1=zT51Kg&r-X)b#4Q+`V6?bBOm~7ehDavkON< z3Xh!3;CH=F5WWsZ&S&WqV8>y}nmU!~URK6^H*Pzr3LSXC2hF9?U}_|niJiQiZ~_^S z8sCDzIygMHVJ0jT*MU#9nUGHODi1L~S8cup+Nh=4p?;EhULE-uEh)GATxIF&Ut@t% z<g1bP46)h{cI0^ET`iy%t58OuGlA$%gV>FEgo(OI;&O*fp9^P5{2r^c6MGXK%vEK& zdEj}8VN^dP%;wWA?07X&6xD=^8M|9LJ*~||lZnE-AnU$8+D57bdzQh;>eQ(VPoek` zNg&djm^=F4n&m$q;^0%tXU3A4Vna3fz=KOAl2XBu*%boiZl5|w_dyIk7cvHwtmA;v zA59jxn+Q4YaT-jSd?4=;x0&vs$W53KdT;Z^JD0HH2O4ml$ixUx32YW8%a!s!p%M<4 zYQGd(S<C=Ab+mGku{+BqVTib&Ahg>fy1?zM$`m_PDw9EM5H#WwdQ@Xylpj3+RbpSA zQYUa8d<;?U<ur}#FzSUV$zo3!o!XrM;N1_nM%MshH9AAC4Qa!&*Xy(CbnzO<0>%1N zrd>X3pm_-xXxc?H-=T)@U)E7i;}*Fg-P0R17ppeqw`J^hM&y=7HMYJqzT0%dQWao^ zZl5|kpl6j*A5|8;G?^KKoA|x1nrk;cnRck~n)*E@N5~s_$$4M6<<pU@o*%AqqP5I8 z31AZvJoX}Yx#Cb(Z8ho^qGG~kb9XW{fGtjg`3uCVkV4NhJ(Fri1d;v&VYgsoZ+3T0 zm(?Ittp2pWY;Gp|!MyiGc1!{;+~_Ns6Oy7RSZ@FuUhBeg6Gr>GGJZ~dAy3^85<fyG zkbh#w)1H-nQ3ci53vYeavb<=+-*)Ttk-L^AYh;JisyOS>GJ#fwdyi*y=0sxw8G3`T zPdVtg=Ipuk^e=F%Bj;u60WJ`G#UkBWh1JLB3UY^FL9scdQ?|Iywh+hrkA<#GiV1-_ zCy%WwwU(7QYtGxF-*Wa@vY5!oaBFnha5iU!f+ixF^%tC@!Q1&stP&`&B&~!czY~&_ zOLQkf(YU@#>qeZoeV$rQv(=gKIIq?ME6SdD)<vtbOG}KVkxa2^7QSrWl_mj~0ZLSi zp<StKB|H#U{_au@dHxie#~%$L!NPK(FH)tHG;E4iq-zco1_5fnRex$Jf!Np|Gcmxt z>FTUzs8lQU*Gdxr;07}MG19*uxV9t;IsC}}SJ00@i<b8Qp2z9tP|4+deGNBASS;PZ z;8o;Qmla;@EoDMMDVBgI|1pL={qm*g*L9?zLn4_mBES3)MY#mua#LMtyRYj2M+E?T zi!#C5PB#Y`0_*(`qIN7LOx1@qQY=U9Kj`T0_1W*H!s>NkN`dga6MNoVJ-xVLsS2T8 z*@m_xX~?GxKJkEuOT&J9^xqS2vT7G&;oWTJT;+J%aHRNHjrq>`Sau0Aia7<nv6XCf zgOxO{Y^FU0soi+N-wlcS1pek1(c^rYt`_<e+_Ge`?6Dz5>u)*zX9CZb8SU5>@Y3Q+ z&a6_?yOLsv!LSdRtSAP&X1*keb2%a9`?4zkvWUw(i_2B$oW69-RY8l>If4eTNSK36 z!kKrfqAOh)<+p<=km0+A^kw^!ex$bL8_cSD%r^oM0B-tkEeBS@rGlG3HhLB*F{0ks zjWfl~9*MDI{k~qaSvYcnfzcU}k|&ET&?-V%J)1OTI4?AqsfW&L%fS(eMc)vfY*4}x zB)D@ObO$~d(nN*CeF(|KU-zW<;BQKd_~MJBJG-RkF(fUlL^4V{%7SjRLvs#fF~_rb z13P@540|_@QT-?h4oVr2o@(S0=mR=z6P+KRAju&e_oU&z@A-ihjc9!RAw75Dc>6p0 zW-Jv4ij=%`52yPcHt5UikxU9QAv`TaDih4kLxc*q*EWuP4o|EqO(N+5Bu_kx4QF8i zRzsdfe0;gqyBF4lKE|e%u)=Z6^G8?`?)gAWsX#n@jgQ1Hd|q(!<$AuNv4ezsVQM$0 zCNqdkZ2>@rv{-UKr<6CaJDix!lFXnppC+dxw4HT=Pi1<>XSd8=l9eyxZKKAEy-jmD zB|-c#Ye@baU|y^=lso5uFc4BG>{K$LHiuXF8Gq|Gv--DPE+En{GlMdV1)M&|r20Ja z-5{G5{@R1ryH;3^=5s%D*#*q%rNkAJ6{?%0y4`mxXQ-M(K%Bp1DxiEsAda71#OA|} zNms}l?`lS{Jvui$C$HCnwCiqXLsh7wy726JT*Zj9kIn;xxytI2C+Op0lcz%GlI8}I zGvBK&BtxDljhJyV?n;sLip3MwLe>(#SIQI<$>=r)l{kbQEb3rJsiWdQN~t8S8sblj zul(!!CvS35^~bhI;8mx0&(-{&PC1U^U%b5G>g8PyEKXw<qQ$~^%G{)z32~vF$Z5h6 zVYD}dG|^Lu_7J%w$%LA>OT(cXLk|;a&nL|_ZRoS1#)n-3XOMWWqWJ<Elq1f}7k&~n z2urG*a7a?9Z7p*5!WkX=Z#A=%1&CkMQ-uF;SY~TmU6x(V+e*2RmDSB9B=6joe?1wB zZ1{swR;Sk!kRFOwUs|Ice^_)feRe4?)itynu04?tCvK0NAJ-fF>80+of!`an;QJN6 z={Rn<1<=@_iup%Q!|_g*-{W|<%kpx$f<XUZj)qKtI6xjJ6t&Re`n4Z6N>i9nM4BxT zinP8*EGM0VCebOZ^Q1bhsGz>@z=k{c;AF9x@Id}_K;qmld}5zT^a@jJvf9Ri|9Y34 zpvFb$)oK4m>ZRJAqu8GnNkTzixII*kInsOH7#ae;=?Z@InL8l9ytk*)aHj?7;l=;D z%4i15TK7OWq6Zq+KWxJ1-I0LD11_`iRE&yNm)&ljAddfqdAdjv0<m%SIzWNzx{A&H zl`th>CF`S<y_f!gVJj(o!=88=PQKXU@)2OW8$d(0WeVb91!~;qvI~tSpHCR@Y$&`# zQR0f7_>rft10Yzk5+M_xXr_?AUtM_n_>W@>Of_x6v)yC)LgMeNu8i7shpyIZD>7pl z9KApXch7}3pbjA1j(dKUryhCWd@8G<sW@C{AsRqR$j@G(aQ1enb>R~dj3eZ8V;7XP zBkFj$lA$J1{aQQ_gTDhn(T<^cLyKI~zfy+X3=Q*~4JeIBpseUi3Yl1eZf9R3)GGDj zr2wSUedQ(tgbpUD8dy@!^VX+bW7*eebx_?Flq@_y2K*!`PBM2q{DpBB&i=m)b{K|S zvkxB_u-ApR*o)otOUd?(p(NhYBMBW#P9tjMhrt$)(G4tj`5mV@>?kTPdO7^wUT*#7 z)~dgspv8YD!?nAxu^QRTzQG%k;QM9;e8MY{z}qJ=O?WR-qBLaTC;NM2-=%vDk%`D9 z1__ZsMgqTL+^S9jf9dq&7S5O1GFAv&Qmi|+kW<C@E<N0DX*PtCZYIKN<=>|D)t!n4 zxa3T_0ZuF-e}LKOJek%Ltm5_7?;#QfdgQe<Q|(V{evOTjL4}O0$FiMm_4?U7yDbzT z8!-FvxO#J~Z#6sTve4wpie%~kB4<;S7m!6=)xMIXZklnBC`JkjJi4m~R0}_U^Px!# zAztC1Q{77K8n;<d^=4eFfQpV@3TLUIs<M=`H--t&j*IVw*^c6oQOftR`-HPhJi-18 zue=qsS)2C!=psHq^n?7M;KC)U0f)8f%hldc*KJ`cbCv_!#5`LUi)cqdt*0xLo3zAp zvsIU%piVHOt@tt3gvt7}z^pudWMxP84==TX^Z2iox&tT%enF|r?xG+AWBw;uJ|F&D zhC+oLoQNVTUt^(S`HX-@s)=tN(>EUV7Q}7K4Lq!DoPnR?zC?nZ@w`0kG~!HplQa<W zMLj9-hZ&K>pbh;s`ny=}YTKU2I`P{Q-BsZO;+CZTXcmXCs_6TOUxq!r@#LC3^X;I1 zzY1CSY<LxcsOhtnkf_1%40)(sj5Cc%AEX<TN#@$!GhQE(15%K2C>INi-vHWc3@FF7 z6N0?}26Hx>7;zpGWXt{IT;!|63)G$Dv1}pIU=oeW86t^9UL_cxP63Nt2K&S1An_Q= z_2Rd(0MV;CD-~djB#9iK0h!pf-*I^(K}wxCu`jz(Cz$0-G15nC$wKz~ks}*edl0;p zpq;WKkwdv8--bX7deg$k7kD#VW}Z*<0Md(Z+nA8QUut$OUT*I<n$YoLL3B3);%TyY zi^GX%w(+5;?tiZg(rDH2c8m9A179AM{&=9l$PM=$w^3ImY%VSDMX?x74-P5+q4m1| z7oByal4hf19ZVg=+31e-tGe-K!9h)MoPC~7gVAX0-`s=iBSKcEW4s9xrK98+X^^T^ zA{qt7MM+9eX@5Gm6szfIJjNr$^-qs#vYWBY;LXI;sr-<ho^I@MqrJ+}>Zf}SIE0R9 zRBQGh64Y=oD}@nmSE@%!Mb>h&zqQaxORaVlT<Ga{3Fa%b<ZTi*(D2X#RF9@>6od+8 za&z{6PZfnj^Dh>(=wxVxtUbgT244z&(b6Aait;aX9dW@dRmG@mUng2(E2PpS1It)l z{8YW$PG%Ddk6;}Wzc2|J6<??G*9mskcTP*g%bceAY)LOJ3eP&)Y3|k%Kb&gdteF(= zUrP>8{-!T;(%(X(nTQrF%4qby?z`A*!!<s+P~s<{*Me!hEI-;jlB#griNiXj7S|;g zK}qz@`IPyrmf+D9lif0KLbnXFruh`^TZQ%$VJ-_~mH9Qxto`CAa)~?f=Iub3Zz_aV zP-G{peouFFH%DAh$L`spk9Z1(lb|z8#r8Ta1+1<C@yAbz`(^1;uK7!<21K6P_qo3N z6Ka-YjneC&zb(cz>q5UvNEG%f3apxiDu;V?clfI=vH9N)RTkYi5yXgX!yP&@BYm`H z@TopIv`OrZ8@>J}zMNH=*s)ZkfRLH*U*%CzYUzS(^7uzWb#wkhNoAkRDI?2rqYOp- z{y5;9kG+KQwNk=O2~8t4fAmCm(e-4p95w+zacr2iP?URdv}n98uB<SgRgLKKq~EZd z=luuKBrxQo6E5rFyzfXLqLRLrE8jgHCnU`6OOmsLGI#eZPd0lEE9UPrpjH;pW~I#I zI{le0B1=IqM)eVa+Y_GUX8`3i?M$XYrs>FWIibbD#^D3A+RH+v!8zu2{U#g2?j?YD z@xB0JTNGA-PGZTa<<HftRN$_?p-8m~l{`d3egq2qmm!Hv%vT4w{%+&Gq(7T4ksof> zz0XDPLg3ReDI`18>=Lw^1D^2XSIKXFzLR8{YM&#GFF&45C3m%_d^EysA~t;d5e7)m zJ$?z(;J?2`2@bvWIJj(8?JmrP%Vwad+02TyFMkFl6wjj36B7`8LmCu~erqEvnF!0% zO%A)fsZ}U2ULunuK$Y@0v0%R5IZER>uwb{kW?ioLf+@vNiHg>9DwD$yM*LMBP3Vxb z&?K`Q5P&PS+V9aHooWJCLR=3_@if{Az14g_(Dr%XK|c|4BcdEp?KVL=CXtx0qnE*9 z44Eob$n9A_)v12pMBAlT#FWdi4-K<X6I-sEg`+SfQT(=?m`al>htFj=Bjj&<>p*we ztI)Z1^FtAnQ4Kkc^H&%|U?5bPbiQmvk7T^+K+;>?_m1!w|MH%}T%TCi%)5NYOLS_z z8mO!NF;RCiGZ2?Th2_pA3<<}-vaT=&NQGFQIc%X3)^H>YX?z2(Ai>#;zjVoRxehPi zXb+*@f4~wCsy=nRec#fqv)q7Z$nhqiNu**0D+0qb0=dT;Ul2+3s?#_zJcKUCLB(*{ zEryR}z7H&KP@X4qyPS}XsQ!t3iW7_`NQYmpy4gb&CokD(&A!3)I6Q>krBx(Q5Lh9o zw^sc+pgPRZrnK3-%(1=w2fb>!*_F;uy9Pbe{X``6la*4PBsfG&y5@SE;VzA>_WKv0 zHyGE|L%FnGORdoYrF=oeBDbam-cK6;F0_>4R4aemHtnBd2_2@-8}?`*I~edr?#Rv! zpW|7LA^zz!R2NspLmmFOS{^F!?Ytu`5FAp%=r|r#we%Ge2IV}0H#zFE1xy(HyRB-* zCQQKWwe&%P)8AHk8?l=WaLM{SSK~9D8DgD+>j7r*68)Ec%(mGEy79*n;b4mvqj?L+ zc<qcSS_NUy)4}X2a?gapgzzz^!=|hy7($9wK(m2wcn^=t=0ZQ><nMkuZY+YpHZkJv zzm<YwbH?e>@b0PsMG>dOVj8IE*1|aQglj)4?DV^{`pe?^MTuOB>0#TZ2qK14{R_b) ztuvo4p%Z|b06=pjKhT_@tcF9`upFKk!o)8|i+%1FbEVhg{jBM1hQdFl$D7^Be1}<w zmVUu2?~fg1XB$p`keUG28lfLF8KY)Z7f<I>NPxs#J&j7SELB%1#Qg(8JHXMH@*(52 zo`svHZzVniMo&Z(cT-=S#Y-G&P$4h3x-*%^+N&f|$uT>u^FPmii3NTPlHIlYAYSQz zkQvxTh(0^%?bJvqjpTan<36*G@2K0SU{Z`wfgky+Bn|^$&Lsoz)I^`-hPV2Em0yL@ zc@nC5fI~v+&arzp9O=7EdwYbSm{20f)<6FdTTU!74Q4}5gyjZ(pg`Dzvhlb3S*5cp z;`+^Ux{b2M%`PlIFx|=V9!u8anfye6@P{B|Oa9l0my^I&3#&8KO=Eg!0Oo!6gB@BQ z&Mf|<?YJh+q5XPK-hwmI^|>2c-njd{*yLp8+-M?QlHKN(*311oU=^iMk);6Kljo3s z{<Q(~yz`yZZ=(t$*=ANWwW1Ousa#sf87unBSQoXmpZ-?VvUACu;d0VF%jGMR)0;Fa zyVVljT1&mePXevzeN%LpP-dz#%pNV69L)|Fc)xcOftuZsu-_<ZA|1LsAYND6!7rw| zkl#ZYDS92tF1=0j=pnnAf6|Yvfzgg|DmhWY;|EaW9Zu0=9{!eWk#M&g&><h(^!SG7 z;$I8PF>+PY!Du~y1_5UE)c*ET8a@O;0x!fuo<y>{hbX~pv;2(nzAj6^y%ncUs4up# zpiS<c;!^AbwcvWufBj&xr`&eG4y$>8uAfvngR|!CBGOJ<gv+4$9mKzjIEkXc2yL`i zLz#Bl$yD|3!Tfu{4=QfHEHEgr8I+Pj{x%!i-p9)Kt`~Pi>>FNG_9mYGFYc%FLF_Nx zVrFz_eM+6)<J&OPktPE!a`5JWiw81x#K3C>!;{(g*PGM_M)A1Z=x?~!`MwM5ha0by zh3G@$-qTR3WWPN2hlm7cEED)I$-fnQfsN^Ojs!4e$J04W2gP|s2!l<h89Ec<2!k-( zF~D}`I6N^-nD0>*LM`OdR#J}O;=B=g&GRzL*l^Zb`NTW<Am3<MH<SH#m>V2yYBL}_ z;{G*L+VW8!f{EXq2RClKqJz`S{B$a-0A^1(JcJQ;7d8&$Z%hu)PRspBNX{8p*pQXT ziOyNkpi?0!n{wH&U1Y+<Zm!H`uHqW#6hhQUFcYpH)Hd8NF^T_S&-M`6=MzA|#UkAJ zAL>j8^#^p{ul0z+PlMocrrYdzx5`s;w<&F=$Xc-8Fdzp(c74g9vOQb6!?<grVLaof zTVo18lFH;in$_|2uWSk;j~cJmeRo~Q{(?~zAS{Zov(0z-K2tsX8bMF=3vfT249uYG z7Pn?)Qt7iyHyRX+RDZh~W#UWKski=dG*iNN&;bGs*K@^XFqPMa$l@h7s+S0>rH^lf z?+OaPsTDQTCOm@`LEp3jaGf9}(6PRxc|E=d#wgs_o;33$H$-(cYz0dgZcW!yEC0lL zLdFX>M=Ep1_<Ou8aILiyX87mL6%7W-3sFYh{_F4vO2NdYpXHMz<sZE#NGgTw;IDs= zr!S!k3k+Cm52&twA+>^&c(QvgSe)-y{GQ6Rl@(4LFcd3|?K|4>X7+s1Nqbm#`BpR$ ztl@prk58yW2FZb`1rpnXWC+UpXC93w2t(}4iETwR6ca13-glh6Ok#3XXd89K%s-^c zf)M6r-_sON&g?oLCz(@C!h3rdy1*+C_BSbbIVtzAWDtC-+eu$#=bx^0L{e(~-xM4~ zGBZg6Y!K0RSph-#pQL^9jDudS)$<X1Xu5o2bbc_zNc1v4a^}T88EMlhQC&bm?$Z}M z-hP?c&pYXLwaQr{z*VN$<7ns>lr`1maE%+TnqcZ>95k6HA9Q|OBx>U@W)@82#0IxQ z*cp5CovIj9krZWfkKfl#;Hf({_(aT%TD$KPN1+u}rR(70QOz>_9eK>Ri#3%gYjFA; z+Xw;Dhk)M|S1z+NV1F!EJcmFlKHOg=CTlS*U?lv)kY0;D%<p=@Xmowla-|ucw|$zx zvu3)IWF?`Yyc6V>dKLgx*j(a0ol>Ii4d-U36*kqo-cz@<k#BeudC23)t<6y?Dip4} zk^?Je`VGV~L&R#yuI|7a@Xs|jkH(EjwM?}KVzI7xv0-0zvp_xiNbEjD8Hy?yU90_A z5LN4uQ$l^+wL@U6v|%cHRt8*|B9~>K64k&^m%E;@JfpsctMe`9Q#zv2%O6}z?aClr zPxQA~Y!4hFqQKK*|F5<Cr`5-n%tU{bQFeqpV3VUvOWudFao8;3#AUPOz*wQBHS9yh zHsnR;Z@lLEu!(mApEd}>*4%M|#`U|N$)Ak>uH=$XJ836XykYM9JQ963C*vNSMi?_m z<@(fW@Spfd{h#=lQPGqhQ|hWlt)m|8RfR*h=$~&~nMp6Bo<zi%;y?Na*8il)hmNcG z&ZOPzmKo^N>zFHpvtag7P*C*Ee&){K#Dhk7i1lpAIxi{Npu{gs+@KTdQx}d4kx#e< zk&0#+0mkOb(PP8ml%)P~mF;&K&PC1#;~uFF8NLzw<JnOF{gIa*-Ukyd9dy)s-oa*A zEf89v*ZMtCXh^XAtQsJ%O`RzW9~_nBcGwf%=L4)3hCrDxl&gLnyr%+b@5a{eE1hca zlZ8yuZ(ZU49-Q3qaNU4Z`4t)lRa3X~73v?Sb>z=p*gWM+pT0j$r3(`T;2urkYNJ>e zOYB&qejA|>DC(l;fsm7J`kvO9<2_gP@A;mscfZuq1?Tzs)7#tCvNx>B1&1KE>$buS zxZP}Ze<<~eZ##=;F(~enLg2hk{ZY~zYSPYdg9$KgZeRI)Xv{A7>O-1PG7)&U=9Pbd ze|jM-t?j5t4Kq3GAdLLI9o#W&JG00i1GDtUI;7WD^8kmDtpN8SBDTU#WxY++U7SCN zO4MAnLKpW30+ujB24vI?;$^X^iQo4Oc$Uvl7@EX0(N?0Tn%`5cN(UIhl>NAqD_bD+ zJedDnN0IC#kA7h}P1JhuUcs%ioq<46D@_0W=v(G=C5j|9L)v-H;JH6;`P-`SD(xVw z{CL3_=UseUr-=Z1R47y=_&ML{^@?ar9Gst4X2VNo!Du%?<l*I*GF&znMc}z3g3&IM zG&r6Q9PbHQui=nS)+<#zVFe}s@|tO@e*9FC*?}`Q9W@$6F42Q-2z6)oju`xe)RVgL zN4Q8LGk>E?-y^L{-ME6V8Gp_}FZC=0YPS`192+(FN27c&T;_(O74_8%rMt$pRjJt= z@)Ir#=G=(pbL20{ARBD?t%<o#7UP?e2k&FjS<ieLed`6hJ?YP^e%O%QVdhr&;R?=x z_OeU+9)d*(l49c@Tr`T-#A+thT!1}Oj%HQo)0{_=#6zYHZ-COlz5NSrOs@40xiBVj zg?NOt=QUf*;fzRIc*P>`s5}!;*)RAVs;$Z~*r~j!T95WY8)_wL>|FetC_EpCT)CX^ ziuM7rXz<F&6uU_1>*Aln$TIk|{16@+hm=8Eqvw%RJw(H)6vTcFU|Te`o7D$=#{c+U zL5x~t4VDq#+}r+}oyvaPzMiZ`OI<pI9O2s6=X<`#t9JDg7aD>mFXVCi^~2pk*<FV< zqIBZlXlyGM6GgAoLU9oLw%RQ&G#k^YwF(YT)Ylt;;GcJ|$m+o$XptLf^+!mMFLhI_ z9N-8b(dqYkG6UtSs(N18`L>K3Tt{l)bwqi<-w?u1(av$1q>gE4kZ<7k2wiWp;HGIk zl@ARp2PD;1$z}PAg+{xXiv~2=9Sj>ECPLC?H4u$ECA`C^*CKqM^Plwtyc;=)D;gLS zFq+#m(6z)xXWV-KW<2qxizXibyR!Euf(w}MX3{1B^oW0zWy4g`xNHz$V$viTvPOR? zz0-)Nod!eTCK}!yT%#saFubPKe;cT~i8@^hTruxpy>w+IEN;SZA5!V&>Gb=`;m{Ha zzE*dx5rg{Y!3a6@6H&yTKcR3r%!Farrv5Me4sJ;1Ukdh}NFJX<H&Pk;CP~SwJod15 zX>^g-;PmS~-{1>n0jH8N7z{EdldV)X<}Aa#meWC{f~{+)KCc4t9}x5y5d~o=TL(p* zhJg5wTKNyRzq6|N_=y(UCX)cUn?yt3l3dK-mJ+|FNzH&+Hey}X@>C;2CXq+oW?!1G zW`0CZyuiER6W}{QZ)4Op`GRZuvr;C|1Hu%lL<<ij-7gZ#q#v~;LeTFZxB?M{IW&aF zFi|>I|B%^?Bk02J_wLPQ&1wIm8`3L(IXEz>5zHA}JqeP-TZ3i$Trx$c!JNDXyE61G z`03|kVtst{+wCs4^Td<T#ob|bTDv37m5?T(FYJxjE3X=e0<9Y_R%+QK_OUU|JX-~} z(ZsS-Bu(%c-;_rGvu_wmzcZ2z8D*u^CoIjf9>%p;sA$i&DI84DzSdak_;%QYkO%<$ zRb6Kh17pQPugnlh?MC`^e{VH;ynVVmU5lErVEoDdI@@r%h@3o<Yz+3xlt>+lT^m&= zX?cFkVo1A7Y3t|1YvYFF$*k3Qk=A1lWjQY``KvICNw!TzsfQJWCNLlj9U5_$9Im{+ zq}Wr$CVsD;=(X8i#2{9k$l&FdO-sXr-MWOw@BU-%i9DvItNp>=PnyX=t`Io32M}v; zKzjiL7N@%9s#k$E&q6|#T7zKt&|o28$43cW4D~vfqjR(9K*wZf%lSr22W7@wUVJUG zd9krS*o71cZ1}mC=^tw>;c{dw!?MZNZ#l`_ayXa{4x()B*`Es1?RA@Jzxt0MKv~29 z?*4z+0NLCQ4W9|V1_a1`(2xK*z+Ym5J-yZTMB!cCtc|-$y*`3Ov+=K|gN+ZZd|Uhj z8$Q=^AN)7muoq~Ap%yhjHqv0Lb+XbpQA*2D`9Y!Ox&P4zjO-|Yz65OuJPNcCOA7z? z;ax7Y+~tb=LocUsPC^CH3c~jtrtIki<M6rczooO95n$nQ+IonN$(K~cQ30hsA;Y1p zt@hwF^}GzKnC(Q4Kr0*i+^wI8;%`+NNpZ&iYEwu!;c>tcR*X!H2V*WHURN&Pnx;Iw zuiima67ViZQ;2%J>|)Z;@l)oR#C8Sl4r}3!gVB9AOdX>0ZT*vh%U5>#mLUQ<^Cm}? z_=?riNV66C<I5f@E8@EnGbR{HYWNPdKe?7(wg(n{9?A=kBw%k3veN5Dw9H((TPkR= zEON*e_!g73NV5WI_Wd|Ni%PV`tbKXC)GgDPtUNEHPUEW`gKN#JI7l~1<G2-gipz|y zjklWIeN3GyQn5**PfP3|SZY-oMu&}u`zh2Dw~;BCo1o&jtxU#lH-r27+!hF-mAI9A zdwdvY$HFK^DVpt7ue8;@UDqOMWB92RiH+>qwOz!+;5s3DSltZL`2t7Ed5rnwz@c(1 zvw?+=1tFC>P}lSOcF)qxVy(>=WEDQG=~1yNa{r$_Lm<F|L$~@9oyL0v!kkTkS8^mf zyoC%wNuUC^`Y1a;Clw{)CHc1N#Ea&^!h3^Fy0UHWZ@gL*#96jCdN~w!2_%7-qr?ri zt95_YPh)&-vHEL#`IhqHMOe&*^@9qNOQN5Cv!R{)UEq#OP!86X^E&D^{+yUTIiZWp zFe_m`4!&pJ%BJCV6hvq0SSDQ4w~6YqwH>@ELW8eDFTo0@xVT<CJH?rGM}6bE2T11z zc<o_v!kHz+V%qu1#T4KKsrCjCF51GVvFMbFmSB?OOFs%=nRnKta5&z4LyE_K9PpG> zHrNI2O2MC_@$*+X@ClZ@KUH?Vetwiu6+5VK$aCtomh2Z6!KxN0h03s)Qe(4u*5>9g z7E0&+yyAY&<|h=x!a7!1uU|*?hwtlze1%M{`4Y_IbxGU;%nO5diJP2pqBiurgr9*N z;k-MTBvR-*IXqG5kF3GEc+rc2s{74cen{S%!?*<lKZI!fUaGH74~P1)*{q)p{%VB; z6<Pm$pA@mYu{5LD8Y2^v?+kz|kn((7g$Hnd4053t^oZ$QiCm?Esaid9h{G0QI5z}a zvyyG91d*zSmueiQy2D7jK~bgl^_jG*Da+l7uNp?GO%YcmSQLXMGSQzu<XqAufgkDs zjKz@tfr<e3bLw$~-6<d!wTaYUtVRm!NDo8gYsj#9)M+fZGa0iPd9)t*DH<lbd(8Lq z^<hRqXiG~Rt`2Beqqe%8Uh&K%rM(dsUAmKl#)%S{h?#Vo41M7K!6s0PhJJe33L}0X zmlpcDO$9BKK0<83Db-p5&<yWN6$t9(ou`P)<PdtuYIj0puUK@N9E~jCD4UFCWsn`F zU!5<v#S)8BNpRWBT^L7Eb^+<l-{!xa@>$$yr!6Xz0QuFC^5R_|VmcJf(o`fQ{=t0> zFB+FMYbq`^-|>-`orW-^I8I~V)!v?_Tqaf2(Qv{3@9P!f-|TlnWwXDr<`eZ@Dlx>O z6@N;P798o2bKt&Sq8G*gKWx2Yc%D(WwwpY$-MC?c#<p#>v2EM7ZJP}nv$5?oMq@O_ zzWc7d_WF*!zTf$i<9_BGbLcuRx*~5x1XgtOigS97%RkfBW;LJBC!ZE0etgic4p*t| zN}n*S%cZgVK|c+~Jg#EEFsAgmQgpsB1u^XRR_Xi}{kg0~%Ewl2{yXBwjQ#U0Ux1$P zb8dpU+4k|MO!?+9F7Jys3$Hp&It|-@vjA98M=`9lK}7`W@Di?d!|NMYeyn?1<fHLf z??k^vPmk~oUNTM6M|%pY-nT-y71$*%b9EGh1<Rl+G<s9>U~sPT?HrJnM|-$!OD1{| zQ45=(B1N}}o*mz<-k`O){lHI`ZA9(e!KBlw{P(5MfxUe4kz{^C<g=}io@G1nd*Lrv zvbSayk=|%W)7fGU?{uTGME#jeqvMJ7Y^Gswm%+1;DjF%BC%6upjE{*soAbeKyPL@1 z7zc2Wi<p^Q8=(<J5{5UFx2UP)2)dW+M1<=-{<IZ|s9L}R2m}%#k0-j!Cx&0nQ#%n+ zJMR0VrRH1J)MJ>)qI16>2O_qtHF`i~#}CeZ4>a)_g1hlT=Cj4%%2GVa#zS=;bCFA$ zOMFgHJm&A4b-x+C-v$^)G#Z%Mh{JZChOJm&Bb$cFX|UUwZaO9zq?0s#my$&Bf|Vf8 zTy385_d=0}t33p^0}2mjt9}bQd%rW?7q2R<+E>4NkUZa?g?;}3+WVO!aX5=aC@G`E zCruaFRvAMrx*mMY$t%UWsjok|5XpLOjx1~R`Cb4IVZ&>R_eVr>FlzbN*E-_kR}yFQ zd(v+0PH1Xo%>I3b?q9cY$&TdMSRPPb?{9<(OMaR92B`4KHvUh)Cxq**snM{eLMvKo z?%!a$KX1Kpw7dR^Bzj+ol*sjgN)o^cfl16P1HCj3?J3{}L+16nvG5DNeBO)aQh<u~ zGDF0hjS<Jx`}A}gz%XfTDX3{=ukL{HpE{QKUnUL8tX@&q>Gt+$qMEwFegp<2q#lmr zb_&)m^wz%vF=$fBK4j|1sm_PfyNN!k?u(2`uat<3<&1`+h3a&>&Q$U^$C`9|vyuLc zd=!Ck5@K-I=yqi$5dC%vCCOi0Cn|O#5f?`5>j4J$ly0+yV)3B`470$b29T-2hkXGb zf=^7Ikpe6BmrPhX$mR3OCOIkT1vd6_oWMt)Zja0szR|QU0<t9nI?XoHB>`Z;Pu_!L zM|xXVMt}WR{fK%!JhNJjZ(WD$OGf}Cux1BVjG7ZZuHJrSg?J`FV1-M~sjze7o}7vj z;#77B%}O9d(#Pp}#~Dk&3Ev|+s#t1h@~uW0t|SucKn59V2VpoRUIy0WDr|pLh1opJ zISLjxW3vis&HSb2ym}koN~P+YgG^bkEpWiQz<GZ}Y0pV6Qlzw)y@y@Bmp~-fs??y{ zc(lKlF2LiK5wLu0Fi(j%UAL718#?S^bp2&MVXT;Fd;+1=xK&iHTnqO05Q2wP$x@~; z>$nX@_BpIjKOxb*+>?#>QQyKc$E-x7R-8mpD9hK2S4sWh^Z`d6%x&ieY2^ErkfjW} zNG*)A!Te3$6}}$%Ij<)&ifT>V)|+S1ELjRJlSVZBN?|sl9V84dUXcS*-_(O7Sth|` zlsG5=1lTa}#@1oeiL37#QzZz{ytQ|U2t-sV#Rzd~cF$m@jC~Rbb+)iKyp-?caV7A5 zcEZ=}T*9Ku^$A3?Pa=alz!iKFzbR^)8_wj*f~X_&KtbvXgn&WWeyrbP<!kmgt3!97 zSTtR#UQOU}lP8y}<T8#0fBiOip<w|YpUehhJ5iuv`cR66!*5Py>i2-3ST-KQ{r9xM zIzw1eIBTJNW}H(7_iWP(6}uJ;Dl$!Y@y~aqT3PD-k<1XKO)Pg&LzJQAM*g9zS&ZX{ zJIu;uyJ&C-FPx8(RBC>n;?nFfX$XeETbsW4wECOjCuhE^Prf=GNC#H@;x&MIrd|=j zn~yHk*7wPh^(6n|69(rP<JSgpXoJ5DQ70b`IKE%X^}5AH5DD2({{jOA%}u5DFn8_d zM|{L%Hn1v=%Yh)a+}`b-fth?yr5e%}V_W|D(x(PHsvLV8F|lCMU?pH*yNf}a&evva zR{`M*?y`g6F8M+{yIjU!qZuL9NK#HYANh9`qRyWS*g>9zTaCzZ%U;M?$k{^r5o?dT zrzcd{k6?LW?Rig~1=Hg>_^Eptp>*Z-gwd=4C<a?`dV2+d7Ff$;+r>&dB;L?r*H340 za#d-JR7NP-;_Tin`t+4p23qYwt)Y`ep|)^Sxhp{i-crn7s}#;ejL<-fBrtpi^^sCO zvKW#mCc9~iPo%?j!Z!BbzE3y(zh?4Z+;(t3fIJ^48)oDA=9208h!bym>&i1+BoT+F z7hX`{{c=<Qyui3DmM^cSaUgk2CM^MRvC+gYEZwKxbj+6kRXzaFRB{cV#~+-3%(TUW zVayp~y4xm!GI{UQx6t+SzR71MvX4rXW*@xZ!TDpNQjcY_(Ja+y9a+(CF$*+XF80em zKi5m)#k9MLMq2yqkD$FIa*ge@3Ch@P@xR@vP}#@G*>zq+8}t8%1Cr>E55?0>?ziXL zT)%vw47QSzkCD#zW`y{e9c?)1Rk3VmJ{oKzea#qhuw2gdaKeE0?b_?L)g6oZ@N1-N zj-JRo#oq*K7x?K=RmH@$qzodr>W$-Pgw_NBUWiJI0lU9uPNr!nh2js~-7`80X=tgx z`E{B8@Tz8Q6lu9Mqp=G@a;av$V$y3vqRgflJ~u7N;B=g;$8Ah#5d<6lRep9M;KdVo zYr!q~${&rb`BQKdv|4WQh4?S&`@0d_;q=QVGlr+4lPH_n78@DNsjSJ}pcwaU#@r}s z+dpvIz8{OSh$SDx0zZkwhN=U~m2XLSHBU)+<9R^{hf_nZL~6tiV=z}BJ!!YoXL$Ji z32X4`!~_F%Co~8grl)0JjlHWW%J>3VUpSVP$0N<mfjZ&Q$dq`x@0bCzB#`26`7U9# z$E)Wi`=vvboGARBs2HKheZdMxdj)2iMuI)IRC?rTCOKoE8}Kqm)7pvb<B2H5J*8G0 zXK<^N0r&A#Kip1{o~LhQ;u>|9s)@@MrP|q<?^rac5^Jm$(b`D%M)2x<S>(eesaOh- zg3>ZB2Pn5p*2l24S{+Hf7e(#`2P{;=KfWKntI_8Sw=eb>ZUu(4qNbuxD;?Tsauh|p zLF7I!P3RzVM^@|&>-T%jJCIXh>6-tB>S}Km-{H-uJ{Ze|MAz_730TND9O<8)W&O~J z_O@bfAwnFSXXuRX?$Q%GA@yj&t8Ry`Hg-s}l>xP&NH*rW*9EgE&bc|6qL26?yvU0e z7|dfcIm!xPj^@VF$XhW)PB*foKlGd+ma{>_;LLUo?a48D?<;<zOAY%OE+}C2UPFD8 zonaQ`LK2<Xt2dn!mh*zlC=!r$$7?jV(6k(MwDIkyx8T@KvFkav_O!|5o4G2ZM@z1j z=0G4gM!ndRbyE`>Ss~8CY1#C(b|Z)Vvo!pI?G=IPq%TZH;_232Qs_ay1$~$K7G{&@ zwVd|7OrY@hyuwe<&X|*uGr4xwq-}=`I-J3F-CB`}i};21ORRSZTv%`7)8biMBC~G? z&!!t7$CyvlZ;KZzcRaclx6qMGo_HdmD57&SERPqbc1kTn15}v;GdjbWy8r5R`~Tzt zxq@P7s+eZ@k}AggKxd0oCY2V>{abxwtv*wp_f3Qo6FZUf)F3{2vD6cgm~)qC{<O6L zL#G^&K)-Q0Mxq#hDDoBr1Zw%Oz-H@|;wO4-ca>AszmVK(O-94Wn6&CM{C_iwK=lNi z`9$H2cvUwp9%Q$Uc?SH*;<;WIT-Dlbb8TOLq67p49C`zk19?`DGB6Ch#))RAXSHhe z**5Z@Xb%unr-&nR<eb3&Ta2QRAynNeM$zk-2o8v$ab!N?^oXh1Ks?=BNI7~w;1%Vi zlzyHDYJsg%@1ORDVuy*=<qI{tC}(TTD0#I@qG4u8cza!o>&=P5GO^*MRh(@s;MVXY z?uYc0XAd>;pY1JO^9oikSDlVzYilDq$2HByzH5<IxmpIQX0VuuCgN+-mb0CBqZbnQ zw(1{BAhz7Hw|wr5F2lWU{qVP?615*&y9(Rsy_a);IRAOo10_J>wG-)Hqs3tf!=C@d zECkMWup@#R@JG8nAGYaohG^%7)1Dn3MYT4n<y@=KfH1I#y8r56LV?kA1M`f_8UBm; z*1PG4ulbESo8_)lhdeVNqKO}{(D2cYL&V4h5hTg;X;@yue$apBaUkGwJj`cbPzE8A z{h;Lh;>nEe+;JEaFa5^{^WfS?i^=s$UpA*1_286apjW6%snOd2LJ-~?Q-ryXqc=A2 z9EWi=is7$RfF#ey-N}5bppzZKmJ+U4ZReO?(w#_VlSKlF5%iP+DMX?=UVP>0Q@VrH zq>Ko;$Qi>|R-8PAH-F}w;2H_xE9>>;nT{74s%(}VYV1CL0vKS5_LxuvI1oA-(<!5E z{yqya!=Dx9uE)BQkjvq3fWQcKdd-`ZkeqvUFM1$$w)h}tE;C}ps5Kc?X0Z-X<ks{! zioG0sL>su?Dbph%_po(7-Neq(wd~L5gWQ+%XsFnw-)w<|<;wJ$N=I?JU{JoF-^vRQ zFfy-5?grDnScu4sJx|DdCvu^r9vM3s;5jigKpg76#T7;`>r1-Z<TjTi5>Jtj+l~_A z#P-fOrAG>yBWG?jflAyBwy?R*H=Da`BIb6uVbu{odEXuD7=@!#3KTNOS=H?szYAvr zW5-w;+krPE0$2Jre(;8Qk~YGtRThIEy$mBC=-04uJk!W9gkmwAM&g~QtfKUn9wx7E zy-RO+=AkE0uVKNxRRhMG)dbUVUh#CSM4x~>??gG+Xn*8qe9!Kl`P(-eNFCl#H;JC0 zH#5-Hdy|8t+@wv6$b<b#$^4_k`;oiZ^VjGs-p?V8C4;dx>x`BY#&`Hks9zA!Bq_^r z#bR6qo&%i!Bbg7T{<n>lerwtaV7QG~iRDZOA2h3uC!Txk59<WtyZZJd6IdQ}5=#BQ zTC{}(2Xmf}d#~Zo*wb$ilQ@|Mw6th6Mk2tX5${^v?I$VhuG{svtSHZX66=#cCb!|T zvuW-0xZQFlCVBG0yt19=vPGPCOxm_8Zl+d)Wgq3$xIjZ^wwUUK;2(X}K|5gpHs@^Q z4P%)Ak;V{#)>=IKaW<6_sqNV`C&e1mY3orf<V6c0n7^@=d1PNpYbykIeyukexWr+x zW;CUJ#0rt2hPNkT^=WT`@kE2gitSN*l}uXhdo+Dg-KWvbAlBq)@~kbm3mSoRJI@VT zb+O8;@*6uG);{_f8J_&bet6%Veb5zG=cCT}=cUeXXS?SHR-_<#W-7S8rTQd(A<2ep zNUe@SiRHBTfYRY#(1><Nv1dcYvt*3EV;`uwq&(c6vshi8O%g-NtTp64sjAtUskkPb zfKh1Zb<wc?Skr2_Y!X5Zw~NH|vL=bbP_i`(X4cYMX#K#j;d}p=D}@v+x;0l}6p-mt zL)n8rjrI6z*#tSGrL=}o{WgPEEA+-36m#WPjc{V|-|1x2H(2QW2x5O!scm=mfOaK2 zKmR7Nulbkx;N~O8?NY%uGX!^eJ-$ruC_TEJpOG@V1yAE_skCVG*g_10h-5Am!1DcJ zePpM36A_avWhtL;+Dogm$gQd^<@au)Cl^e-5@CewV^*uxd|`69!X3yYwu34fQB!FV zbk8^AdUp`qiCvUo?zsG{QHJchd^vN74H~MC*UVsbPZt6y4)4%T5_al+J`6Xu!5^LP zg&)o6V|?#uR$9b#plJ-iGpeM)kfqvRho4@Z1`Wl3e-0t?+l+Q>CMw(T%(rc3mXx(0 zwx71#V#}e}_(dn<Uq?kNn9aaeeB!3RY$~gdT0NTQ6ZSe-wJq1q>RxZbw`-Zmc@*a4 z>V4S*ywo6!QuH4(8M$~r2pR2rvqpq#`t{OkdP@mmt{#&V^6mMl6GvDxBy-y?TZfuB z)4OxhR-rrZHF=aYdpg}nCkpeC$=OOzEE25P&;seRg$2%8dY+M~=dt%%`NbNc5r3G2 zdQl<C1=6PTdbi~nc5)a}QT=5@%GMwHe_g-DAC8$+>ovkRc58)n+jR%lmHPNY3Dik6 zn&k>sev_(q8b_{v@?zL}vt||=x=SY4qd<K`<oCk7jKlLc`GDSO`=me;h*xCgTh_C3 z<?MbrU@#&nQ0X}ZN6z;1m2Nsys}I<s1lNlP_7I=@X<uPJ--)XQd~SOBc><K{?Aw_> zz6`NhPvT$Ae}A6;&du#UJ-ZE8O#f{^*0m;|JBd=kbq#>0Pyk|G{G(S@^f~Wj=wi9W zDz)KAEE=GI=lUZN$f}``!)@Z8$W`?!pxGV1n<sZo>E{oCd%{3t$HzIUxrKx>Dr^*V zI_<2P>{j!oa<c%5Bz@43FRe#Hi{i%VPuIIq4XQ#0uxANbyl64c(DNE790I>u26sax zP;oh<mnKK#bBD(22H$Q35q003F7XtN>3>0o!B_WZsRqBX-0MPmJ6G}_EF~iSLyI!{ zkEJ(`c!<H@=_p3`ZB*J9D-=uq8`@B$)2PaWTc;q}5efWR8uf1b&!LC}p;-8F`RZ+& z#~k@InS2`K5KZPRbnK5Ma_kCC0m}jkwOpQlt6=*k@7-(dCI~GzC2GY=2aUDrCN_-H zyi~&=++vPn2?3LU0FP_^j5*1axf>Yk$REj*QJXy#vZ#W+JGtk6M!amGGQW2|=1=9} zxjrw2HsjEe{qfVFkK*&6e(TVkY~DEhPrESWlLX;Yd>sW|M@y1vzvj{-3-g2q;>K9Q zf0YWH#MzISPv|tEw?(NHDm1^FZ{DF5Gl#r7Jnc$NJR37_6^8DAeh#G7I58-KdNK~e zi#D!OvdGpYCIXkVs)l@J#jzlRn^812$>r7z#QVVyl0!7FV1gz8rVA<mc`Y`gXvpy9 z?ozSQ0m0JKRU$*U4Jlt_0X*t(s`m#P#`R?Zjrs2<Bxk?9FUHdoX)#QP3Ts85bPxok zPtR@+WTIQTB7~sb$O2CzbG-O-E$ay;2po8!;6DkEqKhRkn@Fe5wbvhMr>w;KlO!U^ z!!xe6nIMHC;)QbQF-S}W!V|E7O>=l4Qp2vnw*RH1>hv2Y!r|7(c{_OvCeHxP8ucnV zyH`*%Qz*#Vi#0^|18#SW4l9b@kGKJq6N60g`KDQ=E~~M@V=cVIiOr;R{Pa2e!6?5y z@Gs>vLdGK+3S}NXo3B^GHJB=He@VM&f+ThS9Xj80mJk%?5KM33YP}vjT`D(__hBv3 z-Cr_WDaW%=t@>%T{QO1mP}Z9SBwj2K8**!Ev{4-Q<6%W(p<Iiou4f6(mvvIF-usJB z(<iYcGdwb=W{Sx!vkRJOZl|R@7hkiXf$yViX5ed`KL_XymZ!QneV=*di3I$an)qML zKA6bmaxjdBW5uq8S4WI|p>L(jcmf&F1MA%{obOIP*ySPhgjfF{m7lK=DPd3RUqmw~ zmP^~P+G)cGOuQl5=z1avIS0j4QR|i4BOQHJ{50R49vT)2g9oPUP%}*^5Y11h_v<dC zCxhy@FPed*aQ=OX`~Z`qx)*=aUG+X4DU#&$-u~1`pUvRE6>G15k9ud?Tz8O93=R_r zn2Nh;V#c$3-CG~M>XOr2uLsiE#dVfeEkMB+smFD@k@v<l6&JtZ5D=W*k>#b~UDhPZ zE*`wh^0*HHC@1f^Y7L4Spqio9>-I)P#V5LZd-y$X@T?1?kJ(xtXY)*it&mA(aWX_6 zpl)@XG)nPSp5WJqpYWVCq$3*Kyfc!;QMYp{{&#oJ695wx1ys)wU|s@?)()KtdHhqT z(DS_V6xVYX-+GJjXW!pmNZer9E4sZs+y8Bf{evD{ll;v(Ws%k=;>avWlQ-Oow!q<a z=DpWL6iiCZf!*i~2wXh|qB`Nv-ZX~1LACiZ!(Tss;zE+3fB(ZDK@!wa<a&@8p5JC@ zP8CFS1*NOJSGR;9I7gBCAsXo1ISO(y@1FQgnDzby^Xx^tB1fEsM4YLjGG9Bn$(Xb& zt)%&vqeFX@Su%?|Wxh#gZXWhF!>B-K<6D^F;M`^TC>Q#;nw?Mtu#fmV-`8Bbta`A- zp98w^$!GNeXO#H{Eu$H>=<NP7q-B~fwAlJ9IXPy5u}FYjqIuesAVt*CN8Am56kAqo zp>&S;vB0Ao?~NigNXJly7^a!{LtTn)WHx=ed^BS2P%sPGF8>stflMv6=~qAG9lEix z)YH%8U)Al>8f1l_^tM{Nlo_n)FC|nQDHyV4<aN(FeTO~1gNmS{D7Ew9ah>*}ms18( zFKC2g1b!zlB6)B8z26@oTnHla)>(W7zH7!r=J1e`;j+)N45d0%ESJ0r>|Th-$o-)) zr*M^Lq+k|7Wv)7@Q6a2fn5*d2%NYScV8Ft{u39V<>?+m@^su3C%nxCIWk~NdhRmow zks-rDy)eb6onairQl3Bj-=^Aa)s0aTi4GZ$w{U3nI<UCP-&W1a3$>O-ENh?ip|R(l z;lknjqfsag&VEsI5~f0R!Nl~^)Z_`m*Cyq3xaz-^#=O$)4{x&_n5$;x1qAi~aGv$f ztc)G*d6_D7xJ{d>5V69fiH{0Ms}<1o61})yB1i4>5b!x;JoID3kMh+H{B`G+qp8of zJbmKS*ZM2`ugC3?MC0M4VivzzNt*<jkv6Yi=qG0UAFs>59gatoie*zkPmTw~D>`^s z#~kczaz7SBO(%bE@W|rCD<UMFDy~%@x>Fvq1)hf6FgLX5+6SY<`k3v)08o7_<x<J$ zXzE0=;OQ=rvMCZKySpX}=6s)J4#hG{u036$wJ|hj!um|3r-Pp<D{UW)HHpl`ez_Y| zqF~+fZ+M6V7@;=!@1h@{A$~keaEZ<kmE>Zy!6)}JibpZ15L0>`CM6AYxF14pd0BCG z8}GZl=qjX;(CD5pqfYbb#O#&&QVd`6n%UZnZOr}a?LUV9gG@<K?5eIP5~ud|_L>V3 znNDR#0KB5#(kwr9RFy=h-(IHK&W)=TaiP}Tx+y+-jA64gSuGM(zU%J;(z@g9-_nKv z{LOr+IzvSaueihQGIT=7C#Lv(rB;V0j7}^f^~u3|rd+A$M+6?ELjtIF1W_}O_0G$L z2n(uB7B|z%J;9gNrBIK+LMCz_M=R6bwaK`yaG4w!xkpJ5`7Dg8`G2+}o^RWRfa@Zd zkpX4#KW;;e6!ViLv8w$;*O|crNd)tL)*}9l8~sp%VzCp?V|<fQ7uoEv(%_`)7kf2w zds6^noJ)tFXg2Mkw&sT4g#>qX8SMJoEOzW;Pm5LR9g(^bTRiN-XQs`^$yjnCDwp|4 zo~TbEN!@hAI6Fo%=s6~j^2Z{EN!0#O3*CCX!vF;)wQexpQ?w}1{jg7vh=b0UEU8^J zhKRpe#+C)#hVI5qM^uLCt$rS~nIjv@eC39pNy*$cA`Q&jD((po#-=^)#biGq>z_8d z_$Wn7$BW~W2%L$3CwlpN8teGv=sxtd{1p9@4_6ePYf-)LumfhzH<&k=`#~0@&;5h* zX7xAA%~xhuIhoB>BqpTL;jP}#EI?y=<yeZ-ogXdNVip<V*-bpbdo}v;SJ>T+FnxC4 znL?@I#IJ`Rdsk53%2kPcpzr#P?l7p8v_eckl?f|9Y&fTK`D4#{?v;4Hvar1(sQXe) zx=f<<@vEdMGdp5@+^k9lC!6L9Ol0--3hz0PbCP)?;e@AYvXf6+3ZVPF-Lr@z6Gb#< z#T9*#>*tvX<}z!M4OR1Nmf=)j?nZ+vZaJDkhBsSm^VMMyqfO85u_=C|LckoAzO|{r zuj)3P#wlhYar!6^k4k^L4#N@pa9xiT-+oHtE>M_u72jfxOC7Bw+C-ShdnXBv$@E9! zQON&x;K^Ed5hnh(lKAe<;I(xhrFc3Md+{rF=}W)?j@WMx0owJ*P{d#JRT414y1W5| zUJt}N&#bV-y}o~rHTD^lVX+wq1~4_@ZC1S!9|T#NEN2l1;SUXrok23j56@)p0{68L zjFp9_pV2*0x-7v?2&n`8m4Aii6_)20Qbnr&pb12RQW8AV5fD1d!-}UM))5trB<^xM zK}82qe{iwzWTkz9gM*ZO{2c-~LnQ+e>xuO<9<Qjy$d6nmq>*#(1c7exTb5nMym3cn z<Q`@@42dD7z__qBeo?=KG}W0W_1cw?NG+=i@W6>{2iX~6np3ig=-TNh5Y*!UJoXrl zmI@|BFI)->N3N<OarfqjrivM)K5hHFgFrDWkI7L>hloJ!NC|H&Nu?o`7w=x$QT`WG zdQfN^>Nt_(?h{1V1hNxTy(;(x&8-t8B~6tsF^8SUAJRj{t|CKN-J31yVj@h=-@ya2 z>PfvTaqvC8q&|@L6g$yzTEu=rfk)ZVr4?RT52I+B--j46ON5cqU!vN_s$AP#h`xSD z){vy6<TP`A7+v<S3t*`RC-UbVK(Hqr@B^TktxtzpK{_eHBJ{ZhdgVb#@_kZwrAX=% z406;;U1oZs?~zBP-%<*gHCEw_=VoXBQ9=RGe%m-AA&<)+<GX$CuGgFK<N30<jtS*q zpsheiCLRqtMlQo*Cw`_sXu*kgRUAExtnN%))G-C?-vJCFj4zhhEEoJ~Pv=BHQNTh0 zo^>VS6(ukoHFk`Y-|{@A<Gt#I5V`<u8DnMSNY!(!x5zyw6p4f($7{9h+Lxx??L{!_ zj~7bjHwv1(*r(|t`|{{PbVE<MBAu0CO$ccQ)@ZO3+4Wq1^(Ej5Vp^P%s0$++U?W^- z+A`ojU7LWJSt;*&yuSS~oRJy0nm!bnSXhI5dl3j2n<(WqonTn;+J^OW@5D<;fXw`R zW%WDusk`_q->%kNiiI^j9Whop67L;F^LGpoMBkw&V@uZ}g$GY6KG<ZS26tRUY+pdR z`Pq6i8kxWo*rneqn;{0mwr9KDmXjSywpt~5Br4>1#fo2(Zx)XYGc?}^snP3OgtSZ6 zUPRgRPUb!K_Jc(u<Hu!6>km1aY`vb)`mK#-A2NQQ4;{phGkk(k9dwT0z8s#Ln^*_q zsiFp&e-9`)69ut{&D&+BGPu!1^nCD>%-%vkV&jD}KQCI3rm~ctvK<%L0=|JVLEE(H zk{Y`x24laJ+%JO?sI*&ZpA709x+Gg18b2wLmZ<YkAn>EdlYDba-t)OxQbhFpD<XQt z3*&azPV}%bC`ygyQE&M~>izmY{CGZn(0bfpWv}&<zFg^CdzUkiN7k8pfQ9cpP3VW( zDVjPFgTJJBMdBJvdphpw&zZlN1j+u#<sy)3$c79o4RP*AI?<13T4xH;f^lA-#T6+0 zD|+2CLtupu5^4By<jfRsqp)?|aaBwidOcjU@`;T2bbTF+CURK8{oWeUY8bi*=rWf` zwi{7cDBq${_#ZK4md?Z*Q)?7!WgQl*z7f%Bv5LLEcTJ#vKpiq@1qEG8z|QT9g(0gI z4tzOxkbjyZP_Pou5aBSWY`mvo1}HaMXmVs!Wt)Z%Q4q&;lqn}By;e?_Roa4@{u65} zxzFEVFSsFoRER#HJ>jD!p3A;WXepZ9u>VSrY%pa#rmP`J8Y!MmfD}UCC>Ld=c#1(2 z<7K6!>`9ppEXjs2;h1M4_-4j0HPO+<G^%5|fJl@;g*!4{3a=98Z#yFB@U;Y`FL5bx ztw@6H?|&|-brEn$C)j0D$jht2QqI>BXcszDrD|WleJ)z69eS=4hu#xtua8`+2*X3+ z-=SCd^LW2*C*tH(EXvgL{#?~DF>_5c<dBF^{U!`QVrd7|{)*P^)sm6et(J?G`Q{Dz zG@1*hN{F9K2a-mUDEBaiMjV{y<v4H!$8^eEUICT9{l}YBYBPZ7-^ad1nfv27^k;vq zu2?bF_-_SH_-Y0wbRYik&Fk&-@DGE5z=v<1N2NdD=fV=vOco&(PjaGuPyGuu6U)8W zL_Hx9&L>eOuiaf8ZU&T_xO*AV1@0Bh<r-Dcwe2_XO?LB{`8a(w!9^?WzEBjg_;Grr zlY;>R*X6=iog<M4unl7Q1_QSiZ|WFrxMWJkL@^$QO5iH4XIVbSE+{=MTl}0v>+BW3 ze0r`(`TMRxlhrA4P)Et}CWjLlkJn|hD_u@J$Y<+OIUPmzSBkVky@lcXapP&)3!igp z+X)6`FiFEWMbFn`H0DbU&sL<=n@vz6(|E95s?>ycHrf<ROzEb6BEP@dP>9FjhMn)X z`5s7HZ#7}TdB7JbFXB1V)J891{~T;qa}!-f7c=J?u5L8)?RWclfgV@06|@%Syutb! zx#4kBWSzl$JW^lxK8;1CB>P)n!@4~0(R?D02Sd-754ywfmihCQOY7Y(#n3Lj6xp19 zK1v@pg#FdCUhT5g#KLPIwm^|%Q4|hBE1@*@Xh?8TnEm#)u4dAgLh&vN^VJ*SZ?tNW zsp_9zS(oA(U|H<L&G=$FQmymZNrQ&kJXQ)9wg}BDsEe1#a+k7IfRgTRdavH;lAd6r z8T$pGFY|DNi^(MSwH+n*m87}#epj<cI?<#dB-rR7RH2mXYmMkJq+9+WJ17mQL8ipX zOIhP`%A(?7gjw>pTHCd#$kkx*rX-!+ia)hRJC3j8U97JkN-<W7DC%fDrfuGDFp}=Y zVGv2@q|_I#QjHsX2Tnp(Ym?zSZ08G@u_cXn!vScVfYoe=U1vR~0*O*l*}qu&jIS=o z7y>K(&-RdVO_!E=i22&_?HG7G_af(7xP`52%P0;P7;_jnDi;xivt>4z<cO6)P@))m z>x)KecDv)Pnym8rfTp{qzv5LVRX&EMf29JcPP@tKv2P}$6ANq!nB?&MfPz@`Q@Z(X z-dLpO{ZJ)Gpaoc-H_{{Ch$-F`_=t6jz9W~-R;P!erAEOU;4TNPi0~<QDCsR4qRr(M z=j>y+{dmbUdv&^Uk=Ft)`C3!3ilc21ThBXyrmpiQ*d3wu8Mq%oK8?)oe*wi{A>eK) zq>&PR2!O&-bj^-1G@z$4SSUF|fJHlDsgOC5v36P+VTrdFvrU{pfQ+rxkRI32jg_Cf zSs|apJ!GkLd%V%c0&tGHF*5%VOlLdX>@XHyMLn`-dVMMXJ%A0J(5Vc$K`~kn#AdbL zBYAPFK^eV!_7iB`h6!N;pT$)xMG@*6V3!9fqs@-L`q+PfzjioL-ZOVfAa24SVA4i2 ze~~UQzBZKIO67UXC-OF46se(7*JnuD(t%J*v=mt;cE7vlEyX6<$iXrutqE_j-3(lO z<&BP#5q$4_f~%a{WMao-3Nw0~$iY7t%L}SZAx#K_lQyO^7OXfHSs84*SnHTpk31~( zG8^4RqtYqlyg^G|>onk7swGR8#GV%YqFeA{1lpt$@~4STjW)q?734)Ym=t@MHn&#q z$*h}X^&N}wZi=1|^BJ5u=S{UOHla}!Oc^^;WdAcmC3C&ZDFW(=tZP00-Sz18*HaXe zF3=R|&)nj-a{>*?elRRZ9A~I@tEns|IEJ~%+vOhi?IkZF!8om2G0r595jk$R?oKM< zt7i9z#HLQ;QroXHoeLa~iK?44ir&$MIfwy8TFHCO2q&(c<D%_pw#?64!RpUxpGMM% zJSvXTSI9U;qx`@bv2ao99QWItmC|e>a}?d0GB>)cI9$(H?ZC_?J23rF8B{7EZ{}lk z;k*#TMUWkulsEmhiCr&Oqad0*d4ECrYfkrTCjmUPN7pk}ZBHMyyVe>6(wk7Dp}M3W zhI{ndTh{{S(t?`Lw<q7s1!I4K>ofLlbxfXJxW(tJ_q2O8wFDq*<L78{G6c-v87*b< zggjJnsl@17j?^>zFhRjv2AO~6cDqG$|GGN4IpsJ?TzDo<(DI$bq=-TzURmsu;P*C0 zvGLi7bQ>-eO$SPU0rvPfadc|CRQHOmAtvkZ#-ZPc#`1Ui?+(FaORBH`^H!Zz{(GxT zX(*%W>$;!6Qn>&tW>*s|(~x!33!?=wuO_bVyx-28eM-Xtz-74cCnLv2EPEGH+e6SD z&_*6-_zVBFzen#Cf<8*}dLok5^X}OA8l=@?Z9zN4tg=)TEk_nFJ8I%w8@(90>|WVu zJ$^IUc4kS4`JqI=c~Sr%yC}y)YiTDm7Hd2J7g)}R4X2=a^z_;*@YNjpj<W`RUd4b> z5V=CK@n9El2c0{%^Nu-v1@s`OEd)Qkidim;h;~6!e}6GCQ-rvdK*<bSAn;a1+Eb}y zdfyo+XI9Dz`}XN@U!~Hp^2^v;f}hNU2v6SkJ=iP2+Kh8NdYzspo&RtrRgR6J1wlEV z*WG7Kfs>QySBw#v0tR{A=ZU|9^5euNnyRLkkbxSWie}O9Q(|#{K8+}Xprdr-VO-D^ z?3r?%kjNyh&I4iXnLlZP(7;b9EIgs#S#ZE$cKuqGG5B4mx+oN-q;1iLxSO3#;4JZH zej5KsR3?Bx-WU8Pi}{I8ukRB1NvTKNWuLUS!Zr1m)R87Hjf|l%X7|S-3nC6D;tRU; z_NZB&&;z|1j-)Wtc|Xo2oi=gUGftZ9^`1+7iTvH%1gOy|jh5@2{Edkz*I1!A*U=tn zp!uk^^cpjBygZwE`$kc7)C!z%a+sXftb_BK(F(`*zS*V2<<>}~Q2=x*;ZGT$@4`C_ zD-%8lJ1F3DEAs1*E|QzgN--{CrNxPX+qoUtZOa#7>Px=V68{t472CE|@4qa8_CL7} zvy6kc5D-!#M@A$ea4MP&%O-RA@UduAd3}$p7ld(LpxQ^p)@A{;U>qRKX$9&J7$iJn z+8S+24W)M=&|WZ)69NT$8i16%CQkW5##fBv1vmr_8=78xE5tV0wVo@E7%e~V)oK$$ zKy-@GC(wiHOAXnnSW^I+odZR2{C`4?4u>k^zgu}qT|;*fZ#`b`kqFY#Bns-B%tOH~ z`&4<cbtHl5opgCW-Hg&kDmd##>YO%P@+tBEJ50EX{&`S5MR+_u=NPd0)O*gT&gkzH z=$|kIRS+dbwucI%8d^xk`ai7uIRadk5{DM>XXs(opztb4B7B(TO_Q5=s-)mMYrGo* zi=&fQ1)WO?1E?WD(ymi7{;9-bqqf`@{IA3OaLUnZe+E4$nCV;+zhedP7;zW-3U|@k zn>b7TVum>_rqLjV>uZu?0zI>kM*YN{xi`^@8C>dI;)M1<1dD`QX*D5SvR#Xf#QK^c z+if|89FR7o>Nl=ZG$eZ7+hNxgP*CR+{1s_!Z}liw=q2?pq8-FHOZn@DSi{Z{`))_n zU@TO8)X{7lF7+>4r1uVGE!)nWFp$hD^IUr3%bM7_e<o!&$8gl4icrXEm-J*zmK2B^ z?mM6?n#EhXn&?d<+bK=8Devc>rRof>VXk@<wtn^YU8YYgw>ce<S7zYTt?7jDEAR(L zWiFP<bZ%?^=P~}TV<NaT>yIL6n$yf#OWxp2z-h1lBZrxcM(bu({I|~oVY2gJLc{kD z;Ay2yuF<UB09Ij!E;c&|d0_o{W<}YBD9W})nTVji(!4ZtER{4+k7vr)7h=LFjj9`0 zth729QK3a`T!~d;=O4+f?fn9T^}oa#atT>XqiOgLsbppWf%RvVTwEwnmT~j3B<^UJ ze=&{1`QwUFoB<#e>$41~PUNUkZUdT-GvCP>9Ra(d!yTrov8>N+`}ehMXIou7wjJj! zcg{>U#zK3&D>L#Y84<0XfBzH=zBktesQincyd{75s1KJ&<H4eOKRM3HEX9gyI}fFu zb*f9p54TpJ&nn>?@tK1$I}HZ<H{<r<Awbk8NG|G1tDe+Io@*n5jL46ydEB31+`XcL zhbwwgGO<hjk*MqPDOng6=OdMD%*o0|ugjx{KwyhurY=p|<eJ!z9sO1(efgSrf)G`4 z0W715_N5IQ=o_-h@6oo!0?mc;F1zhe3g3v4QxS2#)_yg$SSWx{Z?lHlY`@L7oV0YF zH-*-p*F>UK%%DR37LGrx+jB@Hi}wQIC;1BJN2?h$m-44zAZ2-H=(J9B&ojk>uR<4c z*PPB`mk%#Z#-Yh+zC4uAWKLjm3KJ)Pal!OL%iqVb^y`AmuOesLYB>)J%o42qh$)jo z%Oz1S)fbIzhA-IVv`?!#b)2;sf`j&rTf$!kg}l^GE9x;HVkL%-7JSpbSJFEXLq~mN z2a`;czug84#HUxm;<dEGx@~%4)0;uxhQDf}Xqe#jjST-MW%`%xU9s68vTZ}eoB1Nm zeF@kIgZed^vy$M?ZO1FAmYWmz?DErPo<hB25yX)hwF?QK%!8Il^RwZCyHc-*A6S?= zrk{RPy8SM$9}otr+E=a<C4$LNQcBKZ3expDXB*jc0o+rDM}QckwHNw|5R~utd{TC} zd~JkRFQ_MIBJ^kDL95BUZ$(9`9x%W$o@C2S`~}N6X06<hqhZFa99R$y)+gPxzZf8R zP@O3%>6Cm>vD?V42|xizNl7<MT6it(cwf#Mhn|(dfWVcf<0zvLg9#$0sWY*3d^uQE zgWw0ta9N%bRs)$qcH<m}96`F`2q=OTHzPLXM{XgB8<iH_gY2Er!0g>k*UG8pCHFWR z99yfJVz+cH&Acj;8C0a~M<G6G_)FiCTv>vNfE=I;lS3iLBH*T>t{l2UL1T<()&VAR zI-wci)`1tl!hE8^yji?yiA(82bGAmtYr*l;P4R-Z(=AYvo}PN&gQ(Phpu%HOo3G<@ zEeJ9YvW9aHWB6-F2pmrI+YZ$tj_ZKU)&~pUN^A!n%FX7h7I#h}fmQIEvIn$<2kjWd zUQEWIZC^$zJTWmcupm!E+_J!^m;!jUNbco}l*5><CJq-HFi9S=W#NO&T3S+@7zkpQ z5{F+(?ML7B$3RI&g%5_K{bK5^`dt0DV)>tX_EgQ33rV4Falw9H-JDS~|0ksZ|CdgC zBV{WgJ%a7ye)oHZNi$ie`?-OBrdXv)hateAZl9Vhi^K7W@8S<`wj3nH)b#s~R<g}n z_U|4Dy&pl%7J0B6|2#lcnGuS~0-Vcuj9T&6y^`6|0mR^BW(Xkj&iJaq3?Gjn`A5=r z3`7PvZ(T$t5}Ghk&nRm&Ai1x%H-kF@<gha1^G<BQ4CtrSYvE%YwTbDc5%Q?6iBgHr z9^|XM08cLr{fl(57fzcNO;CfR#zaaA7tK7|vUZSCkvNptw@#VOpMX=e1VHP<GVOvQ zHN(ziHi>)^+MeY2%`3jI-G+micg@?iG*mn5ag<|*j%dBwFo^Yq$C8L<+y|V3@M?6q z_hbeLyt&A9X7@PIOC%}?QY907d^XA#87?w(kHA*Mv5T_Yni*wfR`Sar%Y8w&TQJLr z0kXycVVL1b0{Y}HwuUPNvj)PDbpu$L+qSxWu2c~)dw%4)GZn&i)q>>$7AcM8f||ry z42R?bH$y{YC!};yDnI`HZ@p6gXZ-)P_%Hs?hQMK+_9HN`N{MJc0ebsrnVJrMtyr~| zHXH=CT6p;~uN=H%<vreg8ZBfKhSPBLNzIwfFkkMId^ijW@+f@jD7paKh8vzFayQ2| z^bTWM`BdOF$KAdJmLrihnc<VaRf~fMg7Qto%4CnJXOTEIzyfqhHGDj4Omtq@ZPp-b zq}aL>`-2k`yNq3#@!CQVs9cJ10tMb5i#m8Ol<MgK$_Ca#RJAD7wuy=7b^uKDL1mJX z=lM)QP}>6cWERJ?af0f^^qH_DnOb5oU?ugLtf8U#bPF&axn*+Ev|Aj9Xa3@^OxQFG zC7gTma*MO`7TBl^++hz@`YHkH|2mfcLe_t$PXBtj6a7(pqFO)n13VbrmK&He1^l|} zK~5%S0}h|}@O9@aRP4V#!Li16HW0$kHH;};gd0+=?>Ht~ZbI*P%(cv^M9Z2?xfUC< zmVNCmz$fFA7}Q^QE)j1)Pl76<B}?Jc5KO6t!DqKNuhxY!4oPf4v$CaMibMAb1~~&1 zde%{Qg4S|}&wj7h#?_FZQ4n*Zlv6xSTM<odD=3mOT^HSc5s;GV-`=0En|UB?1D1J0 z4m5;FIE-L!8xCP@&ZF9xFt>|pdM<JeuS!hcQ-r$ph1%Cc;v2@sNyY1BMWikkBaOaV z;Vzb$c4-y}Lyc(80inB06GCe!PN?APccoU%7!|(c>EA#q`TySA|M@`Rmc1~<jeYEj zuOfC0xB=K^Mu#g}=2+}0f+<C(mEVVS{#K7y(l`xgJ1^4uICv#nEQ7bfuanc(%1eOj zZcWUFz+?3Ttn&s@ME*9ke|A+B6bJFIV}-m9yP{MOErMd$Jc=6mT^ad{s<m~XhfbzD z<p%%GKb2K8%~onIOyn{XfIID=PG*rH>7eO^wK8k~AZmkNg{M8=2hR$^s>r5#ngWLO zMAhej6F`F(sd_?)JZ90~=hHeAY4T;aK?O{{r~RbIv&L!S2P?ux1Zo0*nd-e1jinA` z|8M32iizW$GOT3r$`Sd-Xt>g#Ua0n${r@D@|NBemL71gMdxJ4Y)g5hhd687*A0L~O zRrFGQxhV%+j6S9D8tqay-U9s#0>}eL=B>S}@%4Q2fS4w#=xwctPe5OF0Bc06UG|5? zPutBz6R%XQ+iTiMV-rfB@pBCZjm)p?n-%$hIZxj&f8NiRg<?^7`9m7)-49z{6b3Or z^QwuuY&${j?QWO0)w7-Fke<}5VPu2)uR!9yS;F;|D+c>mM%4oy8??3GeJVL>&)g7( zC8M<3OW1YQkD#dfSS<_c1FU%QFqJY!{yE(_(QT{c*YEmR5;h==TC#sR6+1Gl@t~6R z2Xkhiu1L7gT_4u$S&CMxe3_5|F_*9`PiY<Hz5IU{=l}P41n>V7U9OukBuO5$Bs|UC zG63`2ReSH<2uflaE(tYuOaHB-oPp%<XvN&mhG2K$&__iZC2G5RrUc)h4ZnDzjS4Gn zr!ilbidik!4g!KnLTge~(bObIo|x$9VC{4$SZ@D0!tbT7xT6F$kI^8EgG5i>#Ez<6 zHR;?VV3QgLTdnO{7jWhhV*lsJ2ByXUC;4{i_mM^0t!u7o*_<}0D^82iWmN1+&nW#V z3Z9c8vDO$o4J}@(LE2YB<4Z<-5@kuzQY%p3_Ekb7;X&32N<`xrpo77+Cb^io5`(X| zODL~3g8E$YBJPX=4ShqE0h(*jXv`gM=`X2B6PhXs3Cq3344Q|ye-GdPae@9P<ivOV z%aSzQ-|q73U>xme1qP2g?&f3~e=Oi)+W-P33N06F>*^C)eari^)pG4Z&K7xssGLSK zQYQK~vG1Bioj*Mx#OYpnRzyd&=1vbQIeo@c=@9PaE+cv+z^y=ER3NCoQ~p%J4!Q<N zoI^JU<MV964G;*`?Z5|$1$Wzzt+QT@-3Pq@G@}j~Ct8)#38qi^4aAu0`(N5@y=v|| zT_`<k)BQm5glu+O1c2Nmv_p1T>6)}FH4tcjvt)G6FFql%&AriFt!OaN>^%TyG@3Q? z+5@N`aA)Lqu$)n-4$IJ+j<qEQpOeM(RY?LOsZET4Fdb#lb!HB1x1+*-24phdnIA&O znlBG5>C*hZC?v8~3q!)11Cur2q3pe{NK(Aokfu^!jpOp<zB`ZG`M+F7ARt|RMja`v z9*n)SuSFaw8>3r^acYkXf<YO|vg^hrP_4)R7izZuCcM4;@VS9JOJ|3=W@75QNtVC= z96M;USGFzL+3Y*fC+^3LCRgM<lp;e-Zz#Q&ZJyyT3Qm`%<C+1Uy`M;<uMAdzZ7v_t z^E{@^n*3`Z3)6V6SPHuHrlm^j=LHj-dorrnQjRVjw{tl-cb5sJ7r*c8qcPYI!^}S^ zXv(jmUyK}!tq&WdC;yP^%c%y%8i&x>GkxJOT^=G#5j=5M?WjFJ;Vgv~l$N(+cL`xq z2M`=gq!w{$03JJeoLj>wDl(FJd2JoUJl!(gVwAj%ZH$ZbsPUt5LisW9f1R*bf&UbE zJ0Yt5s2ZbOo_DhnNo__QH)r0_B>7Zs76G4PlfSfouTs5Wc8@k9m>>k&%J<Y5_Rhb% z_1hkd9}^EAO+A#W`$C^?^#z-q6dx*%9ORFRA!)bxx12O;s9Bn-TjjrOdY;xm2Pd19 zCJs~a=Qp?l_P<Xfqi4S>5_);-#%pQ!J8MV(l(oj{S_!34uSO(dbD@KMf(MP=e5;+r z)4ON^MPzH$oVt+?|J?GV(O`Gf5Ez4JCL^C&(pZ$@KhJ8qOGeu&Yp5}_^kk_oV@=h5 zftnf>Zg9We9a_{o0(>~&G!aV|E}hdx6P*BKpV811vHg(*vZRoZnYCi$Rhs-R$AhuH z_qE#wXIJuZ9q<F7O~Og|uNggGVB&}PKX>uJo_`>UN&WjHxsGuKOPhgewL01qokpq< zKpaBSL^Yu{P!Preo-xR;kx7)}(@j(XOi*rb{P^p>xMArwQi3}LMGmbl8<+$)<h||% z-b@SQY4~)Zeldx34AN0HKWu@`p<#c|zA;(uitkma5gZj08x6wWHh91j8c;E=&YI2d zkg4^rfX)egpaZo@jcOo<hNCAnt9<b;#@ObX44%qTGROc59X=QfhsOWR__z;-h}Cv* zmn2^0Q>OG)k}kL7ez=tSuAwLVFL)P11%|r$P5F8TEcU(xTB!A(c6Npiu4gN=nB#<6 z#NMvN8r0mx>PHPD->nrcedpg3s@h_8$8vZ$ESGBuX_aBY0_J0jDNTI->n8qJ%KBpT zzmC}>p5z?xM~V|tnVeCqrBmCg);L{aG8s6pz<yZ8_T$2+#I|yHZ57gFXEgBGuBcD? zrwm38_6P7rPgDq!5{oy7{qgXFO2?g+<~+8UGYo1ehf4lxZl($RDdfGQUm_DeC$DM) znn8`eQSRBnNW>H)pz>4P5d51oSWIiwMLwgr8rfCs9t6xb4Sq<1{q*lsR7TGQ6z}P2 zf5^i)5CzR&_H-_bN-CH6)ch-!yWZX3zB9xxbx`gXegKNv;<8g*JB&<G>3T-M!`5Oy zksfl(g3jbEQ%CY4%wPB%<6KCi&{6?NS53gFWkwX0DXfo7-+&AwYhScBrlHOYTuSYN z$OkDK{$FKNF;h7`|G(2F!9V{F)q;!Dkfkx#w;D~hq_$N!5;Ywd#kPhsU(E3RW_RUi z84Y=lfatp^hoc+6nQ9-HGq_*LDm~pMQH2@-o#g`hu%sQ%G7L2H^4sCMCtto4DBa*{ zgp5iv(J8M3Ba&J2ZToW|u?ijj>@}gY+p=!Ua#0C#S0-(%82=;N`~9b_l+*kcntSEM zyzZahJw2-`wX)1(+zR^2md=A%YJzay@}d8le#WDA`>v;Ql1ZPp9Oqs1Yu0E!?*kpe zyxdx|&Pjkel4L@)>`TOHpPwMJU9X*<!Z^|qYNmbc3`-ofrqO5$r8Sks!Jt7(9xw!a zPPnBG44+!+ts=?Mh|bhJ&`1}r4$((?12lT<XC{HpeHyjTZDf%p8zT&I-~W}>m6osY z|CcLSCi*X5mtOF6l=XZ2tJY+-Og~Z#tW{IQX8Tt)MsT~iRETK*Hw)k*o0dPffve0o zB`ue0JaPhIJ12>QW2;;d(IZkke_-MXb~>xxx?j5Wx)%ba7;eVn0NwnnqWGu@rk;{u zvDYa4OwRbCrfQz!&-+CGZienhQuTlO4q=TTl_)Xlr{vb7!z?>?qxM*7`#E4><c7=J z4LmKw(G?AV;T_$|P|k>)rWH^kP^vli4+G9n&_&`g@b{PVWhk{B7wy|Fp7QSxJs(20 z2eF}uxQ5yTn}1LE#~KuHD=Fo(VcQxwtd=H@Wv)MqT+RZu0C|*EIT4z+xT^+RmF~+D z!jIgGr|c1Tzzl({o=E5Szu`azR@p|A%323JO~GR-X~5~0C@Va8{tNlHFx%)PE_ie7 z-)E>CtR)^_&wd4@jQ_a26kGXe%yiG7@$2+J(W9u(E`PU~qj+JGK}H0^D%3AL{2589 zTIn9vFMjCT>(~Fwudyop@27%FqsEL*q`8j(IceB?iWm2Myz}7NQ&g3g$fV^e&LOqc z{{x%?@EJsTH%=qmmMNs60*FfIY4stKVbT23-tFl4M03D0i4Qk7%y94Rc3PmXz<8&O zGs4jZYb70>+BJV8fz3@~cZc>&J3|nAa1Hav@fQ=~PbeDH@RBs&%2EF;R6q<;U_NHx z0x1)Nkkz@Q<3hE@yiVyU6^ALfc5L^{MF(O~daa$NghmKFLGnS>ZVfzY2S9uzVN~y} zmxS}(zoGXDNgV4EtoW1CD(0=tD{3;BdfFiQ@U&2&64QK|FBBxJ;p#EpwbN|uvlD`i zsDHV?oGV8yU$z_Z2L?+5bOxZ#-P|I81)Ku$7`(pIBt9kY?>@BzyzVn+AK~HQ`u%w- z;Lf?#oqzHq_1P^q@y@h5!Mv~;$d6l5U()ErgugD0rPy^~xa56~#}#?u{g)<k;<Lr` z64>d7(oPgaioVast>3={(9M45{eNgW2ky8Ub`4K#J85j&ZW<?z&BkhMqp@w<wv)!T zZQDB2_gm*5WM$3XGtZ6d*0b}hC1cKb*pV3Tbv`XBqM3~C5dmG<uj!m{;+pD@(LeQL z@`f3Um5@V>D*SY&<4p@PRjV~1bn^(wc3tslN~AY6&S8*LO)Si23v&%+Ba9vWf$D#h zuoYFxTnEVwBT`sfjxmLEtoO4%!86B@wMrtTGVy04refW@y}kU-FB5vUEhZ(34+rCw zpSrB4+3{Di(XY2@UyU@O+V@PKbDHH$%r!3K!f$=Z;>;||og}}*3~yDM>E}GvC?Cdu z9Z|wK$m{mYsNl}a0EH%9i)>&Syw#bZnv8x-qvvZ@Q9n7XABSW@{MK9`BT)m+g40%S z`5~?%E#sbXBKS@>?{I}9__27Vu~TbZGvzQXGbJ2Uyk7Y*3thY(%#}=VPS{W#Hoh3c zDO2AySWBlY%#uOXj^|)(o!uz^O^{iJeZHa9xM4FXJJwGHm)DQ+0?6h8t$x}4G)R+H zwHHM#fx1+=nKk`$=$3$QPd?Z`j6T_EM)_-yjP}!Zf`44#wd=C)rDXkow($SXzRKh} zVc^J;0Jh+Tm8<|MZ71+pBQEi3T|gw@<8sZ6MblU*?Is;qjQ2PSZL#Mi;AtbHL*%<% zEOcTZlC%5VH%KRl8z^7_=Uw`(AwJ5ZKxXR%oLU{!q)S)=f@I`7-JRkqh8O6yTad51 z-l}#evp|^>mk04gW*Q#|4(hz>UT<&bTJMXTP^PIBQBgsxaqz`4{Sh0`2wSr_t(N7B zQ^i2hjUTvyOS*=x7W9I^SZTi60JV&zpxKnfmad{12*?P@iT*!nJv`o9899Zf*^&Hf z<R=?&eZ|o0%m_2(^s!>JA=_vJcnAO6fX1au60LANI|hDhvPq__Ka3DGswskALyWec z@3qNIlHq^4KpC!liq_bHJTezu=xTBgisH*OOAMs5iHtG&NV#})=l&BEzNXla0c3Gg zX@MYr`~3V7TdzThAXSlbh^UAGY}`2_L<u0y(5ToYeR(KWbi<)g{-~e>@Jtk9o}taB zQ4j%i+J){<Qygp=e<$u6KO&Urqy<+taYY<CKw|t}<Yh5^*-lM!?=h!Ymxi`~C~Mi$ ztJ7za*+#-k7-^P72f#I2OIjK%D$*JPh#%ptK-*ER`Ik50r3v;e$*04l5MwP(85Dh3 z@n4cC0HtD>KN6{Q0W7`a!p69<hPU0C#SZuL2RtXZAYpN$xW#;JoFy)Bo2BEYQoqkz zRVB`dJE8O!zOA-9^Rt_NI2>o_;LWXcrMiWu>xiF73sw0Fb7Dd@A3>HVw}Pd*;mW5J zG{wmyuC4e7#ciy=Y1;6z)~7chEOVm!&Ld&MbUcAGq;2GiWypcPt$N`EabX_JYp+l+ zNA$P@mJ^IJtbNZzn<p2Z#s9se>w+O&rzkgOS48&fwWR#SrLcEPey@=w%c>=9MB7g# ztd)f;QArm7VIuiJaRMhRZJi4^OdSPu1Hs>DVgr5i#&Z%_q>7WP>+s=HP>vHYCsJ9V z?6;iA!o{k2TTurK(B<SV4*Jp<^#<3+Hn@skOPn6tFlq0eLQqIq_$sv5Ao_UX(yM$` z5@D<aG^9EFqUp7o*m4^2`aRI~X<9Lg72afTxY?^JKEG3wpN#`i2b5qOjhmXBK*}9y zA=cGv@a=fm67Wyrc&dq)t^Jm`u`V5s#fa#CTBR*mLWL4Z8i;@Gy=lG$#59=10*s-~ ziwBjS<bY(eh(t?Zq(sRwiTdECA!I}R$((%3KF4spsgiPl*VNCy#h@3~TcH_=opNCO z>Ku4J_N)~9Z3lShTX+s*0e<Q6U=0)R26VfT)nLj(uIrbYTMNNw-i@+R{6Pk!T6La+ z3I%&qFl~bfCWBs#WE4AVuZed&vup>(i|L2&9YeZ&unmTKO|IBgUMw*K3UH$Bxd9L0 zLotx7=@F-(GW?pqLgxw`ca=+6Igv6Y)n+M?3dkB^uVY2O(ceD1^lS2^B^u+ng#_{p zE6NhZgLGDG(laJ<e_G%H5|(+mirT_sSI~BoW}F<noQ(89O_Rtn9#ap@r`WQ4Hd*gr z8dQ{6aZaQjV@#9S&`v~HARY=l2B3>rXn!GR%r&-}vT;5rdHrOrEn|0|4s<VxJgij3 z9kCcZp19VJEmcxmIMY>21qiKCo_ro)7sc(BA`HRY9`UGC(`WAkoP{9kRlg0eHB?q& zu)U=4B)0PB*OCR3vt~fDQ)a;~`HI)iSKR8yXK8-T|8t$sbN)%E2IXYs+!_~LimGPh zVBF~vIa%u#_#>d>cwf_r#YZL2{-A%p0dIcTv!&`OHu;|nxnPj+w&(Hqq|p8svIG39 z><R4UfFz)0t>!p>17xF1LZ$$1pT<GlDRy*uV767$CH0(YNuRuXB#bO)B7H#}GiY=C z@+4NnHygm0OecP)vWxj)O~UCkFo*8z!m@wKt#L$+GYwoE$!UqFj*Wu?Ze33)kHpCV z@{;!r{;i9+hua=yy6kp;ec05<czo=JGa~Am4xyds!5HrwFvMZxqE5L=st!-SE@)NR zf*~d(Cl>VRiHCXdy4@PNxXp?Wa5;HU@{c<*!bBuE8JV;_oddINNnP`VP^y(eyLNHP zh2oRb92XQ5V!gwoK!ef=7kBw<YHL_25B)Z&ZU<x5>{RUqcX$(by1(N%<;YDXh4Mp) z90dH%(I(SA9z+$CPDacBTamxo{*e&cn66q>usSUAjP!M2VCi2{I^pf$9{R<Z(Gkrh zjheAG4@>xm=4vwP_~^k^$JkdbN$PZBjaYI!b~NTT1uuR1wd;s(t(A@0R$77=PWA0* zM~QR}R(wmzp(ag{MUCGm+AJI39Jm(_K@~f=DX>W+G_s`F7{}uXq(@o~xgW@YEbtU_ zzBxI|@+@a3^6&~IQOsFYts$8MYw$*ibUKM5f>T0uw8-B=oQa{?V3X`hlfeTNGQOwt z${P_3j;Y`owf7M*1spwi#`gA_ktJe8*_p*3C_=xvk@9`gl@+TVX;{6+RaFEz6*REQ z#2$F&K7L3k6Y_?&?w5Y2Rkuw&n{+1yo^h|M0u~cWOPdwE53)?F7f1`{=<ObVl`<L_ zE<a~88pI@XN)AmP@vgr3d7BLnt6A-s9;s0KRv30lV%Z|HVd7YrH!oR9!K>jgXw16q zuo!g{E?4)zL9_P^{uiT&nPB@T%$fD>3!FL8)9ZG$)WVOKj9Fl&%`)df!^bqv0|~?a zPNT=`K%OJ;C%qiFKXk_JAa(+ti<ofLUgXn{tG8OWr&=7Zv!S6p`y&R5kucx7d5O!c zx?QxGjJPo&DxrsA(&!w!y}^-X>aN1L>_2f1wTSdnuuGt;gHiZ+=m)8$S-mQ1Iv5?! zl(n_B^2Z<=9HaO;ORJQ#r4>uyR;_;p(y9T!2JYkGe1Ky)aUj!CreaZ2-UThGVZqc) zeDkm?Hx|ILG?1ZnT%h^nU6ib7PrR6={7q6EcP#y5Bhj=uf0xt!ieH1cT|G4|yn@WQ z6Hh8EpwtN+Mq5orqOw&Y+ii0SQppw7MryPGJH~t?o4OY3xx|PYloUd$ja{zvxBKWL zT}pH+r=yJAoMZEdS`l5?d{uB><Js;yp0(KKtnuu|k_|Lap!(3c{*nfRG=Y{`$wBaQ zkaN3clb0*##lX?`R}&WUt6i3%1!K|7`3{eu|M$wIC|lUqN&^)j8A1|UOa8(lB#H<p z1lv&q{GgL^cKtGQ4b7IKCpsuVUAFU_ZDy4;GPn#4uk9n@LNx(F)lf-8!C&jS9y;>m z(c;>1E%2U*00mU*;PGOC38lKr`d|1v)ZRdK-jGD51xzewpBek|IL#s3`(bXI8u%)T z7gaWlU=68i!CeDMW{j4i&g$(*6`nL0OirG4opf?w;j2o{=<9_yq9c9`tZGpfkCc=q z&OxbvUQ051Qcqkcw%Aaf;=aXE)dVA46UI!hyYL<HjeB!e9hadYTY03G-mG84IVxoy zFyfb1AN(2}9s_(p_VD+SRO&ITP5L&>^Q1~S3`#LG$@6LaQM!Ue$3Swg(AeaQ$>4MT z?TE3ArA_&OqHlgsS2^K{IzI>+Q(yE`WIh)BZ{Q4jx^bwT_%)JGhrl<y=pqDMV%;g# zS+E0nS6Y7BS3rT|Nj&f!UHR`F{r#-CVoW!jd0@)pamBPg<_{&~X!DkLcrbxG)v&~( zJh0RZd<E_sy+7ZK><++m#AsE0N*Gf_c6^w~gvh?4ow^=PB%%TFler+n;F^WtO)X74 zG`-=d^HeB7$!Q$F!`$u;A;J?jR*hku13`_!i~cBP@wp-6;NWOxkXIe#bpS2G96Bj7 z(rZaFCKW(p1&&hK4Ayx<6k6+A@F^|+MjX3Bk-e!TjZmG>*XPLTK^m>EY!y(BdXg^} z)R1fXy|&2C3`C*6qtsbAIS%2w6j-R7tr`XA-&eJA!+sD8zb&L=k2WgF$S}%N(=LjJ zW42n<Ga7McXcT-DIw@iYpoMbfdC1(tMvP|*e!+w$3i&z#0h|<;51~xJ*D@K&DZ9{2 zo99C5lp4S0RU#jXs&}?8(CV4pg8k}d%ei85zmeSR0IlZ~t>TkU+7<r&1M)j`$6egE zZ@!Q#7h1GjCBn9_E$K2TKy}p;E)E-+wucD13>y#`D5ku&DrqLJq^AJrsKo*fH#Q1Y z?gPlA`{=j||9%UKD@viMW>xFe;OcB~VtaLbb-|UA{m#n`hIcmaE22qiq2OE71_OVX zx<^&1VQ;A~Y@oB^wAV<d5gG1`%7uB1{s(qp(_UiBUBgAs&W<Q;k{ZsB3r@(QlMcBk zjf~qVi>&i^xd3QK9Vp=Bv2wq`z7Q#4foIt*wUAY9)+;9h%Hv8x95k=+ce!P`N0f1p zNop-_f@mQGq1$&<HF3#3F7w|c)Qi$zkUb4aDOJJzJOoWXs8eL#7Q|T;9F$Lbp6@8% z_MhrqCq-D`j3Pn>{^*%b2`S&BIQ~K%-cB+V{9vj$YR}+qU1C$=Ou*>zc>>z5M0n=^ zEX84i5mX7J4P9hu7~cIuR}O`eg@m3a`Q(NB$>!f{O(W|I5UwMm46KqcBow;y*oGFI z!j6}Qd;OBm6OvUWKr|1`{%tDeN%WD9%LYb+Z9-u7XogdMo!{7nK*IiL8}LY<HuwaY zj3s{x@y#OOcNfwK5e=&^j@Yd;O0cZj70H6ec8ma3&vDI5*7J6gQlV5XVprj?Vx-P0 z<{ZqWV`DFtAL9Yh(T!2$+c&8=KaSe>_R1rM`W9Vb>$w-n$z(JflS5^%x0J>^t62@C z_~<}JgKm?Ok_IdR9XsG>?^HsyzL@0v&!WuR&*}uA?(=Mp-*{NJj7~&7b{H{zZ^_7s zQyINPNhtyXZ4^<mge(ffbDC0Z)w<_&cg9-s@3GD4dp}&!26KO3l9s!Wl)DTz%wtZk zwWpN*gb2<<tPOSAR2I`7NMv^nBzQcjE5Ac+XsA-Crzm3q(KRZhp;Bz|t#ypE2j_yt zsmVc~I;a|9MuTBHzI!4P4m`$w$|S0O5f&G`-e*%)QEmI7VHhipje_we*Yl@`9xg&- zgdHiiv+l^edyT;P6V&pr)>UvmlKxS*M=YrgaRQABeCr8pns=3XbZToOcv3_$0=qCs z@~y|fvK`v<-YNxH^$0mTF&)+t5hVygRU+^=^C0ElT=^Z6675#lZrVkm1zdK8HY2-z z_$3~#%D?Apq14?ned8-W(|CTHl(X<lo9gWfPcOIV+eqbD`Lb)O!`Y0@I!a)+1HbN8 z6S1G}$gGwh8Kn}aM;gZiKH8u19bf9qwsP@lRQQIXNY2AO=km2cV&Y^b4?s}dL`$K) z%?T$mnDLb;<V5HF0*W+yK~UjCjGrtw`Cg9k7a%WIbwm0@Z)+pPCP4vYOA;x$jx|;z zp6`6lpo=!^VYZrRTE*s;2;aoUv@O|3AMHHFsMOI_XtIMX*vs-I!w-j(Ig@8%0zBg{ z5kUW#*wD^3{#40dv1FVcBV*=VdZKEw+VD-Z<TP9>LRfAwL2y1_wYe|<FxZzE4-APb zoaua{FHtzq4&V+W?At~5A;S&FqU!@LMGiIQjIlkfDzpXBwl_W&S{qkpesoCum<cf` zk!&qjt@ayT_X!L~-$w$m5)YyXRYCOM0-ZIFE#>6{Ry5H}WQ6B))g7-q1H}H<iK&<W zC*_G^I^7@7w4`-Ea{WtS0W&a13{zoy{~&h2oIJ!)p4HUX`yJ9xvYP<9iGLy{5#vCP z*3@$JWEj1=T^uD)${N`HlrxxI#8+3p=`d`eR?XPeX!}7`Z!*z$z0)7yyUUCZ3K8a1 z49;G+Trt9U7v-3R8bU+FIKMjipg{MXvx}B@PTbhb8)#7l7*I{-`BE5PPSS19FfV=1 zsHb9-3BmkA@1B(ofJFGd)#Vi+y4qZ~`4DFyF}lhyucKy3slVcvD5dYfm$N#?S)O%v zC#l~?Y7F-T8kbhRR5#N&=kE5@Q4y@8E!*gJQkWdqTG8&E>V^)WKGPy6ngx>;lYC02 zt1`wYovNK?mkZt6J$n1Kanv8LazGTKk)k(Bddj(5o(qBpr&=m?#lg??;z;w)xGh#} z7r3e@2I&QL4}E?yK!!k$2{ECHZGBH?13Ocz-nJtECPV#5$VYP}>){m2#f-uD4)upq z!8}~%zI(wn{oWX~YIK`E&qHkae6^e@(PiJCB=-&eieS%NFYm9hnF0Yd4zF<?F*sjs zCluf7hqf2Plm6@fa)*))FM<M!-gvqQBvv~q<Z%f~M|xuV)`p7yS>_7ogxgG^z;WBt zX4i4|#{Hx)A*qJA9Dg;Y6L>b`3d>MJds<&Zb1G9q9FB<v`6;61r&dRS;Vz{q869Ch zS7bO*c98P)cBS56#J%f)A-oYJJN^F7LzNJ%kC{$Dl2h+B<ZQJf!RYG+C0}acwLV=) z3v5n|EKh((m!>X%w8MO#qR8fcHk_1s@6x9>*hN*SkP*$;>cGIAuL@M1NY9g0`ovD6 z#ClUVlh)j5^TsHWO$~#IFETh8Wv5cgMLk_C4G%&%%>(XhQ0X;Q)IP*3HikKSO`t1! zp}9=V3iVo#+0!KgU*F(&ho4cc4kl<qTEVI7)n65>J>98p^2NO`@4{`wVOWtubAwn+ z!p5Zgj44_YSVIS&=--_wBrS(;9FQe+It`eMWU~jJFY%atCT-MPQh3C@=Xa5!Cejy0 zfBbUSy4DTLwd;?%Xs<~Xw7%M`M^bZagJ@oNMx#-o5&57>%X3A2-)q;-Lg*WzHBM?W z5*`*&_}Yzby<_^-SDhl@MX|RePMnk_G1I^m!Edm~iF+}P(dJq@+VVKa;Ck%Gt55~b z-}HBJ7+(%>OZ53mJsr3g@hcjh4cfn&+&7!k2VAqkB0R{cJS9=F=u8CaDcv+fhquW< z&ylWoZt-~bLbbtSao9IzH79f@>}@!)D7~AGC*L5C$(sjc__)8N^Dgom`?WAeitKH` z7e95Yz&ouT*oydn5Bs7N3{ThB=UWb2m;<HSM13eQH4D*d&ZAh-kLJXjys&fiK6`Ln zTAamV_rC6ALg-Sd9yA1n_}vN?hHRh5rxyYXJQ%$s_b*G`y>$3~7!90S>nd*>P=i;B zFsF+7n+~(uxOCHTH#s){2S<04(*06aNU7D{7?`6Vp9AzI7@Y!PThnE1g|86_)UmNk zs2W}n*feWxq~xUv+H#E4*2PPSn_5^nsryy*oT%j0cA@GW7j<*3heS{2;$aheo!u%7 zIg0}>ju-dHIfUx#{XG#ltk>CJ??Wo-HL$wj!}<f%TqqK4PG_nWxfng6pnE|5|A$3( zJ9i=3X_3O#ub1)w1!bXpkZ*W1v$YI;cP0~bkJJ-8Ry21Y!}aFuAFbc?!2FRx0nmgm z5X#Wi$ipc34k1Dd0^>y3ocjk$*GIEXX0E~>e7Dc}W@~v_n(1A3;6A`QT%aE1dqlLr z3v9YGfmnG{^7d!&rPvu}WK1}GzZnvSgBj!DY}#eIjkw`upD2|=6KK_`D>?2`bpQzj zobRB^eGr!r(VmUwROCPyJ5c-;X4Q59^Q#R{&zJw?GwC2(+9m_ch8S$Zlf^lvE~Ww` zIHD=>CI(i6Ya@EbT5P&|qyvJ9^Q64^9vt-=h+JJvB=1l)D%Tvk;3}AzVjvO_=M)w6 zFGmaSZYImCcRe(T52-aEo&=tuFVCG3VE56<2Doo|E#ZB@bsnF-c|P|Br+ls{Dwob6 z^Iu&>PA=(0g?NIa??v15=b^~PoW3y%_SJ9-46f3@$v5h<@;xu_wY<)T%Qpyl`^&u0 zVbf2t9OTQ0M}Hga)>_()kJZy3c-`1{!^h>U2=|A$%NP3eA08lFK^K>wlN1D)oBn3g zpYKgYlb42%pyu2-J`Pa7A7X>YdF7#)P?tCx8*O>Y-8^1=us|P;PhV_=c+Tr!Yn~I} zBwE6OA}VEJZFKz>8kv`<2j5ho7u>9i6IR_#82Jo(VEY6Xy;G&do9im9Sr55*b-klr zQ82I{OxO{<^{E*i&d>=72FV{VdO!l7VnYYLvUnWanP4P##0@P&aDW6A{*@IR{q@GZ zSh*5%SEejxuK9ZSiwoz&2wBe8VfQc0^Y0z0hV4$z0rE;a-2;n~r4oTroN!ftPi1|? zG(o&E6N)hIZywlhPolpz1by<JHjwl`SASEfbU_AnK47jkLt`t;KR>tRbJh4TVorWw z1O#<N$?_uRZN5}q_l<$s?YuNnw?B_sC>dT4unYWc#255paS{RCzA`wIK41Npr*-;g zEYsB#gvnAcjq;a_#Yv~u7;88*#Z*M@)8Jth>#gdqV;SQ+k<@M$$z^AaYbqz1f*$?k zK-|7@#7|QmXv6|gJ=rkAEX&8ClXKW5*=)XUbAJIC3kc9@6#yZ0qpJ<(Xcf+st9W(S zGC=+iM8PgUY=p&pNv!0#eHlGlV>P;=647$#Id!obd7tD+nCcCD=Tp9~!-vE+FhoQP z=PWf3tm7FmtlNuM|HNuKmziyS%&I4v|G-Ma(0(f1wG2}HN7_w2E!4uoQ@%)8&<-_Z zNhd2_?|X=YDBzX5`;-YrwjW3u-~5O*;N0B$L8Vl23n$kNnbh^pCpAlwkFN9JdCP9A zYAGZENqG5^VDpIsCjoW{ouZ)KoZkRk&}962WA+)w4?^&W+O4y+5&k-Q-F{Dt9fSm4 z5=QjNG1%eVM-zX0K&rRfYwP9XFm0ZIi{O`6PIzHx<6$dbjNSwfV4Ge(T$q*1e>5Yt z@?EZU&6fO$$zd^wh{$vN@@HR}Xe^LE(|F;ox*kA^#&vzm8u9YQr*vDI<_ZTvWiWN? z{LvE(c4#L87{MlvQzoaBer}8lOlv0@EQT?H@N!fQ_z#T5)Z5}v_*I1OHt<PPs=?U8 zO2mc5N$*I>&SJ6RSp;5|&-vg42u~sP&2z&k<T}IMdtBl;wqK&|GoR6)G2g)Sf9hCX zzm`{TKe%-D<u0$c)LC-6<MR1ZEKC-TIp^r?3cs_w!rc>I;~vtfM=Bo859G@U2Iy{7 zi{@(E?~~hYr9Ap|8{dGpP(%|3WDm*-$1mdB{vM*0ZxPZBkds<uBIzDv*8?QIP*R+b zahhwwOMUmVs0(9Ds)bQ_J}H;G?#o%K(SP}=Ts{XXH>Y*dX1PYnd1So{Z*du>Rnpz* zzczWlr8i2f0A6&OHOJq0{Ir67y&jIuY7Qx-%uo37OlPNcB(2Z`@D|&!N)Jit#JhQ= z?Z3X4zRGtD#66aqeu<h)p7vS`5|gjPnoM9#QXw<s8ywmho&g^}yqnGWRgLV)81;75 z87v5@Ov*&3pHyk~!RIpSdhhjVyicP7CZgv95m}y8tfon@Kl<D7N06lHDxqT|rb~d( zojBY>robcRy4_mmve?z7rYx`i-y_0Y;X*|V(S0p1wkgu(HanPC{!e%@Z%&xNaFw3l zNPPZSSzds^fyrx3wuwV<QY4gwOd-In{QR$V=Kv%j+<|8sAVJ|fFco5isXh<90jFAu zc@&Hwie3Fp(WnL1%ijY|BrXq2{n)EyEyM@j?%IY0KA-nSv;~#UTv!gmW~gH1laj)o zN-X{S?W-50bCM0fgD6Vn;rTQ~f;8s?M@f8Dd&*FATzj#X7}^JX6UOQcJ{p0_h%E6$ zeit?kW|8(up@>EzOiUtg6~HYKt_BXm4cs4QJMOF=tl2n}f=IDyem4~b7;gS#PD&VE zrqiF52KtZvK$hMmz0{o3GcaBBXE&4Q^|~Jkf$6NO{_G}Bnt@q0>ZiBH2MwJcY3r_~ zO>o@$bf+bCvQ;An%(PO{9U9C;&SzNpX^$x5atT*^s%)IX4gZ0`Rs28W&omnnTqgzU z^qh}f_WKVaapVF3^{d%x9stm4h(})=gxIfj74gIKQ?ccx>g{?T?I}+&l*CWK-}fHO zo-T<#WrR=%xO}F-8q;hmx$b@i=2|utK&3|n-z|$D-7BKozmMaS<2rEK@>VNw?6&qm zl`7~0up+83^Ci-d9^ARk-FSYyi^XPpMyObGk74M(xG~EXw>>DNj}51a1HkUEFCu7( zcfo%vBt42njN2!1V($PCJJDNK*d?>m-_>a|J>uA6H{)^*@}Y!fNQ%|4srs7*URBcn zOzKhEE_c0~!&z%J!NGQAOP_W6g}%yOZJBo~+1(`f^T&l&G^gId(>14He-@aXnX@q^ zpNQ|vEQJ%i1l3<A@u>diyJo%V?l1j_bQY{uSk=E9NRI>Y(VJ0qD6c;$J|x32doWs> ztxiZhA5WgBw9EL~*6qP652bLPGy}BkY(_BD!kT}HHt3#a|D08pbpUQ^;k0~;BYuQO zZ+RjF=zSsMxg7O~;#c*vP6>p-X-${=K5)0%H1s!Yn@nIB%6~W3e|D5g{WLMzy5SA` zySus{!s`no=qYVE$jR(71IuRZ!T$Q_1DV`x;mfDUaivho3k60&u+oiUbAxkwgS9D~ z8&cPDb>io`6T2204=4bc!+E<aNzM9Jx7S+yv{SuR#M&{Tf6kWx#|V!T;f%#D>gNmR z1^QO0b&K`NM16dIkbXTZ1e(^Y8{7v@QF&45osyF?$fIy{gD(DL&9%gd7>sz{1MOXW z@wQGYF{}rkytNEh-F3q^I&;9Ep<n1%KA{`hJ6S0`b5;BK{G6^AQ!HfO(0#+<`Mg7v z0D~noL454}TS#LtCBo!<2xbm=(r@%keDcRzCVehEXuSec%rPMUo>a&Lr?NC%*PXz@ zfw>zs)HtQsKfO1C8{+)WW3LJ$gx>;9#+?p^c!M+rPkVhXRvY07bWdG%=751R1!nvM zF?zQRW`0RpGI5|HAB7|CTe$nZDDgrICkcx|+syYULEFKYyhvs_x1fnS5@+?&Q4h`v zEykNK?!m&yh-{SQr~GjT#3s$pB2r^HEM#ib8ZvpNN+*<<g&bipFfk6RWhNa-k$?Eg zJ%-D{d4<b9O+3bt1FaFo4zhB&*0gY=-lIqqoLABSAgY+dl`;F=ksu95tJX@Z*&08? zzh@`mJJhhThU!*S6_99Qgqa77YEq(eveAcabi(nfRrPdLY9Tva18zCZB942IK+PY< zDtInLH8xCC&u7Nt#*X&>nWv%VzER=e9Y#9?pPuBmWSao&x{lq(82C>l)=PgsOH6fB zHI)&QskrBoN+u)@2}%@n(rcn9NIDeg+;V-NF_}V01eOQf%!5}O#G)jG`Na_Z%?XV1 zzZ)bhWyYl-FuOILpUNHgec{jc<9wRzi=tOU1btpl+R=Rto@g3XpkPS9Cie-U6%hss zxXa}eth-(2KyPQD+DV^2e?K2bs$Gw^_Y2!dvspTDzcN2w6w>1nH-qp%kWpJ?o-h9m zk3*wM<8?xZy!RnMGx-Prt&2Hbz>5}GM>~*4=g6aht9DO;GfzQN2^~Jwoi(?&*h^eu z`xRNq$qs~@khPC8fo(#kpaQ;!f}UBP?ZI3^?;2$?7w1>NlZ+(JKr(%sz)c|rJu?o5 zb8AkkuPYtZO=p*GLtpB7S0+@S>q(`XHu@;$rbPXbL_j7!KdJJ39hvKTk!e%=q0gZ0 z^QLqBb{|mUW{u-7KTGdcoBcTZ_yEUrUMT#mzt8n!;Hcl2bMsGewmUQy)nGAOA9Fz> z`xxfV!V%Q&*wxUs{$*ZE?pvp8(G=LeM%ZHY{?HA1IiR7l{cE6@v}@oM9|~GvGbG5V zOaxFh!@AT<7rd|UAuVZIMK+MH5IY!`b)hZG3#ygYy~};M+=6HWk30P085saGU^{p5 zgvN9gYLR#kRx*RWCHhUNA_JW|ME{ceLUaST>3x(Gywis(Mao~wR0Fj@UYdNCIT~vy zF?MrKmPxqL4MMu<23Fnifw5?XBywcUKmAmyTcXz((JGBi6kAy;>+jRv#4s2m9Kd|P zk&Ud7$Cu^tp|b99w?L8H_?YWDnzmA5><PM*t{N=I7pgFaxwE?Vwv&i;DU1@B2>(}; zPeSM}erc=cuG%L|lb&Z*^o?DaUMpivS^zgLzTqi}>@c-wsHdS1&7jtDZOb+6a+mPy z8m|(!e6QErYvyPtJtjFR6O*e^(mci%8ZUXGualo}poN=OzD9z~x~rHnsOuRV);5Ca zE<Z%sLeMaOA5~z1qN3wru*whRBjCU9wRE62a0_2uvTk8qTPWyD(&_`;{@%uBI)o2* zQ|yPcQhpZ~x9?7X$bSR78l7{1kNikkS&R;QpcLX_M_ne;mrjz~O!jT~*QlyLg*_k! zC?-`h>@}8SN!$U$HYr^8K>S4*?N8_R7P~#>k9i?XZ(Slvjbc_u;&9GD4Ec)wd5NCd zb=5i0sKWT-Z12^Ym_YMr0{-#NycEA&9+}_Y)T$m7;Klt6sWnpCoPn7}16vt23QL{V zSr6)aaj*sRY`7F)12`x2H;?PJzL`%LFn^RZ-l#j0vg!TyTPZnnYtvvn8>owOb3sh3 z;LRzk_Jx7rNY&9iREd0je%t`tHBjk5-X;k)9J}*T_j0`n`6CP5yRc^4;A|LC)=j28 zlQgN#pnmq88wo%Kv$dF~q30wcUNEWJ@9PRzB1T2gUp7d;2hxw<F;Mvt)k_p^`4@9g zE<_%<%*dpaei{=E|9Ze>v^b6uqhG3#!(rY6q4Zx8FEZc$?+iwkF$iGbDW86zU~n}= z*O@c7jq-kzi3NXkOXF$P^pfCEW>XK1A!9ngzo8-;zNXk*uh)Yyd)*+;Tg)TM3EVMR zceEAO7NA|5tedS|QPF32y&UVne|zOny@(QzPfE_+Qi|Rkb(XC?$?m=$^~GX(U$f)N zP)APwJc8uo+?HgkR2u=MF;O02;Qp2o>zfGYJs=GR?H>7xVD~G~R^urB`rIKp-!9TY z7HOc2wGNI*S+JH!JT^0TRI~$je5N5cicJx5FG$)_dT^Fk#;|JL?T!@b%b5z#hD3N+ z{nHkszgva-CBVAN^W`K<s)iiE7Kk^-9XXN=_6HtNIw`q#`c@$}=Q=`N8cE;0q{@;6 zUN*rBI5K?-J1C@aFfrOm1@UXyqmt%wSv<tJV@i1ayjoI<si)c#6u4y~==d^8pvg$) zC$D}z!-y6v{@DWn9XB)`7eA45vL)<Jzi&C<Nyuw&7_4Dv>Z!s{zxkX_zPS`9t>ven zT-9|V&GI-zX|RwFsAS{7u}~w7>|18eXR^K}G;=sPXt}L(9v1&t0b%Fm6xjfAP8&KM zRK|b9oDKyH@AGq0f~*t_IGFB{gBA+@%n0H`NxYWNHofWL=gd_X_M)uWgK9ASF^hf? z>P}fa50Ib?($rc30~DN0dVDW@w=qr0Fbz}F7M~DG`s07+T>XY8a{O>Vqqc{fex$vA zH%;o=;-aQZr4XYuecW~h-GVy*W;y5zpHqI{qG4$#oL+uCDIOqSPJ%Ww-KTtmgCJDN zFI5_a`ZxW(Ut;}j`7XrD7A1?)cBM^$Jgn@GM*|YS)YyU`W$sbtli^7d*ZSHM1mBaH z%RYOy(>vSV=g%~>gY7&#-_83X#NGVbo2%58gCJfe%LnTOfnx4GLBzkZYK=x(no_4w zX}*KIhEIlra@o6+?b$s=$3F%MJCUoqSi$ibEM$DMapyZF@hyIA>;=OExC4`7f~O~d zB8NDzx|xyr@7ibWsB+i$xgDVlP;|Ul#VGZY?-g4)|FKfm31i6C&3o0s+Fy?x;xNI! z1pa2+^pKAY#}|*+;LGd>znMRIpi1XUjjoKc4D@}oA&jLjepD^nk0d!|OI+rmQT}9G z^sGZoEVrgAO!OTbL0>(R(K!pxsE|+sGr1?{XJMK3<unILh|{wk1-b*ZsbMULz%BtZ zOER4XD7ha@BxlMdH(X6(xHGVaBuimv)BTTL2io01CM~Kl;4X=on5!Bqg-hOS5QrB; z@UOW>r?(*YCZ(DcwckYB!_yuwWN<Pbdw33ks#2w1ooj~)u|MWMJ+q|e?Wg;+X$p7% zwuN$~)5B+WJ4WG0b&<J86GRaO&`mIAKNrS|f!?;p^x=LNtm!Zm@V_Mi7AjM-4UuZ( zhAt}oM($I+<KUsoX0ZDwBjQ&|!0!hj9L11$Wa!A2zhExYW#V?={q3H=316azeQ7HM zE}dOS7gTeI63RM;7X(%W#COa@pvm`7)*=EEi9B#Q2;IVDbleH`Ij@OCIE^IWC<P5J z9aep~mqI+xW$$f=a1P_1oo>r6AxDXm?`d76rAD{_hdvkteK`1r@M!82Lj)4hBrinJ z);iNf#^jdB`g|UwFl@iKEbxvgr8ZXZYX|E)exO||2vK&=%L55Q&Q8VmNG|lj!9HGp z6}TcaUr!jlceZfrf<Rl~^!)D2r`)#xY9d$3A+<hZ4jL;tuM3!_nSk}9CYZwnr)*MK z>}3=|)S#gB=V0|ait9vC<$Jpx2>xo5c;GC`^V`*cdZP(DtMgZQOG-bL)}=O^jT4H+ zVx>7e2zb~ZJ3@8j`0XUeUq5Et&DlB&#3SjsMMfm|EzTQP!^T%@hb4Y$M5>f5&R^Fb zP#h9NsSuvX_~z;Q$Y%eLKNXG0Y6B#mHTA~JJ@rmxGJMw!OC^$Ki^~DNOw{&BKh>W< zhxAa7X+rR9E<$zruY@9p?ZHzd_syT6m7qnhdW)~R{E~w^BOBM@8q>8SOy2~9&KPVa zOjbF+3DUujVZ8@V34EarOjd?zwK)r?hUBgObYwil`x--7o|GT0J2R+e*LNQ|`KhUD zqvLR~hh#8%Ovto7pvG+ZNuyll0P;HX&_Vn3YqMu{8HI1J%n}xKnH|1iaY9HjRYy*% z>PZOU%*c<rYmr3$AkDrl#FISeo(yib(4oknryh*S;`SSQ^*p#&wioV3yRI0gIV((4 z1L?(PEh1sp1McSAF<g_SUvbt|bouIBS<2fFLGR_xN$i;Y@?qE;85(xeTWmV@R*Xu9 zcF4x^tbmSjMY(L7`tCfW^P%CV<H?OLC;yqFy$?A-v9%)hii2jhi4T3J%1{MNU0CP^ z+~eS+{935%wW+OHs%_zlXh@4JANHVVqxWHp1G*jyvLo9F5g?tMo}ADPeoH3Bk0qAf zZmU0fZ<5zq$j{U5m_m*oQedcI>p{c$SRS3?ry=HfiAYPNYTJJqC|l=$P2Z{Owoy@K zB%s?3N~6DTMeL^lyn5h%ieq|!Ua{b&%fWxIB+Pc*g@Nwj-)OK}VWAq#?GX{LJ9Jod zucB+r?@9TJ#EzPYr!W+VN8n~s6spwCCA+3!gUq!gJzJ^R2Te;WZ`ohK;sLP%CQ%)C zi`~wbstGCNvc6fd0&~koPeBHdWmbz78q{sYP`pL<ByL6nMKY71KE^XN`ik!z_k(yg zLaCFT1%Fu0K_<hLc!0{JktM0E{nch?P~@(*#Rj>Ea}fd_M~Zs7HR5bOz=@H%!?zFl zkD{MbdFnG!8YbgT$Y>@Mb6^-*I3dpJr?U3ZNc_-Wn|XJu+`z)8Uu2Gaey4Stn8#O2 zk4yh}G;h_vil%(4!r$dNtRU{mrdezs=TDvkRdpxU8iool7=>Dd@t(J*Oc0x9?%Lch zR$3vlJHI$|ea=MAb0M}LHZFUWWbPG89o-H8p7wtI{h}yo9`0j!l-c$h_Vohcj$AhZ z^?%r{aliv9Q`76myYdd(fPt7PwUoPetH2@|LuYe{C>}fT+u*I;j^0Yuwn0y-*!)Yk zQfViWTxGV{KunUNO+lF(tb>Q$XEGe_dYAu2%u@xR->d3nW#kKmgRzD_j`K_E<sd^Y zPSuBv(!Z&=!5;oWBPgpIk^v#L6U2L2u<4%fo@($ebNEE({Rn9&lvZVAL?I?Gik`;- zcZW>HvMmOh#Gvhe!s;y&ds|pzcOm6@bHX{SRs()IUm39aaF%BmFGi)qMwm2_KGA*V zc!EItUH^etdvk|me~KJGHrWWn{x2<9lG!rAb+-;#Iw2wsga|AXKE<e~8X2I7w!aMd zCmuSYH~1M0`|iN>UHDz)z0m>>x2X#^TJVNx6<Q*%;wDsF#`zA26#Vs`GLyn)j2V{1 z1GTj2O3H9Hjd+wq8?G%QZv6=BHi-5<lLwSD{wQR34ec}Z*VtZoE0<^^$??5`TX!Ge z?jtp9bsCZi;D2&AT}1ZFHgEiKUzlWlESZ(=Fel~Z1qRPbSUtfUWUh#fBqvbQIjwV+ z!P2i^f^AsLM~l@P51?1I-SD&Aqg2x(OjGC1?H(u~E{#26HLfJ%AjD==e-hRPTueNO zz<YnbI&}Ok0P5K*zM~IoIdXcMsLg^~W^`E|XTv+#6<V$EXg&miF!822LN{UKMEuyY zrwc#4^TtErDM}kTIFpF<$~5K3>%t=V9g)X{13Dn!&`J_$z=>8p49?n&kG<67+J1Zm zgjaW9^ow^y#X+Fwt6VgU4G*lBbaaEaNLw41Q<%2|KsoQm{|dNym$o6H;S)^L_GA@! zy@p7j`6~zFR}m_1XS?;2PJ@fk(EAyN)r6T$p<eZP_QRyXW(8domX(9oSkVl^xG(AF zaFXHCw#$HsV{g`<02%b<PH9dAV7%;~#+UowEyPgfO9!GBb+2E(Y&ujA?{HDyuRs*X zxe`G~DEGI|0a)INSt}#e5Tt3!;M@r;hvOgBQDer2h@dLU7mAzA<i*=2W0&rfC&*p0 z2TQ`p(vB=wDL1K5htN0vb6KeM>Ots<d`@yEK5|G--hwh5j|!a9L^{fF_$j4gS|B5- zj}FDkj$EwU>3#x9$nKYJ-A0|7m~Wszipr9}mL>GtFBS+_2$qCJUp;hP(rl-YO~YO~ znO08^vvgfhQ6o3Z{h-q4FKiu!(5M>8?Wu{|b&aQ-$mGSspi!0><ZRc0mca@+1BiXp z<k*7f>Z>e)7EO^+TlovHb}+Uclxs6vVAQh~T5bF^8K6uYDAFGC;^F-lC^a48F*&6B zL#c87Q*Kwh_Sc7$=bNBr*-=!_MDs?-EK0-h;TE1D@!w!$Lq9A}cSywZEx#)<??1UB zTYtlTi`$AGwcqT9f5?AzkPHET%6AvjY1Cl@L-L2Fao{Kwxyb|*>>(0MBvG>5jt$w3 zzu@H*VPw-dOfrn#a1J!ns;n$35mx$r%^V@vZ^!aZm{jRMBUK|su%B#D`{2ZK#5%=F zR61ezTJ5a-bvzzF!kx}I^_MQq=FOM=Zywur{3#yfi`2pG=hAd;VUi>B$q%CSeEj_w zyG3K{p)5G91BS9ZAUPeaAPh|_N<-kW4fGKwi6HC6=04t9g;ToB&}g#MqAwewcPF)Y z^Mx2d=^W?S#v=tlH!^=lNH@^OTVx~^;Mrm2xY&N_zF)0{E~8-t<Jp)6XzckIfo7`J z2-ZSdU$_xkcUQ7b((AythQ?f~H=|ci>o`5Tu-dIWH0Rr7d&nni_zkRBVwf!I6xO-w z)CX;?9T_r;oIr=%e_p^z0JC~yz!^0=w6hk}rOB$~{Y5%g<3({Dl|zZMDou(r{r8@y z<J6ncv;JD%L#oMARVairjvsauASm!oRIdPz-|Eq_T21*sQfZD|z0|b5Uk13UzvH0q zB3bVQbwi{j2y66|;U7VpM1G_tB{J?TxzQ@L7?Iz*pTpdD72`=^jfekf!H)R2!Fy*h zBw!%EcF|~GG(m#Sii?t&CCY>ogPRmy!XY&$&ViX*$~cR(Z1b4g!sf6AY~pc4zU@ip zj^VrH>TR`~&1fvPENJ1E)fyoa&czn%Qd_OGIa%iJ2eiA~@Ji`_e5<LLiIbibC`yM2 zfx`;jej2<}D6}VQE=g{_z<IrVhJ}xaTn$Ci^}wj^d|>9d;P<yrw9NnYu?pUIm*Vj@ zyhCO6D`PCOVL6gY6-CYI(w~;6N&NR_@-J?j1m9dR``hdlBuMT8vxMG?fLP5so^sJj z`l%I$O9^;Zy=a4w^tW2xE&ze2GxRIJZTw6+1*MQuQ&TR03@E&ET~=LKP9JST-K<dI zLhmz-pFhaXG)U6>cZ-h$Cl>?SYup#4-rGF{N7X7qJ<Q2B@{GaIX?5XWZdYs2#cW4Q znV@HD7pY<iNrGPtAI7&#NrHAzt6Fyj%kKYUC;pdda)ZQrXg$i>!^*|-M+JtPNLQR{ zNYb;Q6U>0l<%ro?5s{je28waQDzFsYqp>6hM7(}az*q&MxRLz0LDA8x<rpsPvoWca zZh&QM3t#c2C43cc68)01>U=sh9RqY5H}}c426M31MBX^MP1h(;7j#m##`8`K50az; z>yB{&*cNF7v$%zP!0>(CVU=s7y&x8h8K$czpW?VMIgR3X>`c=?;5puJ7tKSCFTj3n zd@Ec#WZmRDP)Q+XQtU|rj05Y7Q|E3=gC6rA7ZcXiou&LS3)HbmU3N0Js6SnfneJ** zwGI60eP-g8V(Hov4_0I2xPNc7E$C#;<`aAxO_WT5GA^gAMuWXZ%)S<3C@FgywWi}n zEAbF#zfjNpt8=p~m}m`RwxAmHst1cdZYPJLF`ZQ-9J@|9wd4ppf$0r1Q9<e87)B40 zJW62S?vDoW?Z_ziQJ#Qnex9#)z;1a7fL?jtvRX8r{}Bc!Do-|*Y2J%5$fC~>M1o7X zmid_l8AhT`rA-PW50em|OkckQ+C`&Q+Q&6CAs<myL*gt=au>rGE|LV7u_vt`C^Y;H z=p=gGQgvMO#gD!>fwP}+3Rgp2nhvfX4%1&p1NNgX@NVY5x(3y@B7~#*4(uGF-)xsI zICB(n{4*gzW&jpr<88E<+Y`AW%<tg}(2NQgodiC((M%kAq3hq2CfJDk$RMG}=k3_s z88^BG`+Spi2P_5?&X-?Q`8Jw4PnRMJGW=_)7!xm7Efs~mz=07>BQV99z(WZ@T-98; z8r{&BcS;a!V%gm9Mo6))J09V7Ir%1M+IzPkoM6V>Con%8DSv!CRc7u%<f;v`d5c9q zjXXl(A;boE_IGetyvcnzA#olu?0SO%miNi4>^G!u1-V7Od{U+qqjL$vH#s#ZC<8C~ z4ob@9?z%aJndPZ;4+SqRC>N~^5cvbY=F$YOZ^IdPy0hhe5SWm3zeEunZ&t#Eu@>bo z64O{PdVe{Qh#`J~(sEo41*$m@dUbm2<WV&C780S9?RKy`3?z{$i+6nwi8grAn_~_E z>~k6xkuuxZId+zFzOs<IKirDe9zSheFD&IN<ci^I_UMMkiNdCRlyw#~Dnc5;-AiI6 zov-3NwC3%7BTvo|8<VU{1-(teySaU-XR7%U^5nIKyv3*vcq8=6fQhd%#s&;t8Hw{E zIZ46!&TBj9lk>A3PJUz#f_qH7YVbSY&u13A{V+c4;xwh(>x!QYL#GacW7vLGDbHX4 zD02F~5c{&O^^!3I@8mv8z0U~JhL#I=4<!E`&KxTR4Sckmh?QtJR*Jpuh=EqC4_&tI zecXHR60B9d;j0<ckdE=nf)`wzM#07>t48Me!%oY?Sc#n33^JluA~dK@_JqqNn|!8t z*-n0Y@T%V`OO7meWB_ye;E^%F+-zKmg{-TX<*}3WQO;21(=}9p3YBgdY?kK<j-%Ba z?vCAQddP=Iv*GOW)y-r&;g0PlOUq+X7Wkb<p211Ml<>ydWBt5&n#eU<R?cVF$6Ev+ zd065!>hnL2P>)6lh_~wT-e@svE{O5S!yu|MDjbNjDI5&A`+4n<|C|D9%+1~qRP~%k zp1K=Dd(A7fBic5VG^<8updxTG<OYNu4v1ILp^~=I)Y9$=;pEVxs#bEN4_6!bgFd49 zb338l8w1b`%-<{fp=cP1iixE$5)>;AMqDS6`wDf)quP=(G0&4QHDo?%syfsuIu(3^ zVs?^YxwihYS#20m-#95r_ML86Tp#QAVCVtL(Dq{(>NL}mmSpnGtUZ(iLHC<TQ`b8~ z=@}!mW2t;wcT0Td`tVu#5oiT!-*kT6k9kdqXZ?sxleELjjPQEBXBO&i{{%LwY!4FE z+NAd^swxgrrC#er<=NEEe?fLl1@<*W&=Y9jh>odAJn<8|xM~O#HJD~r)U_lgwzV_r zwEB#H{u8~<yMt2s!FZ}}bC)&Yey_CzEk<vVQpkZ{w%j=<j59uc_ru&-?zV*MdMWvB z8vp++fLGe_R|kZ)bw}2!<LOnt0!o_P?|mp0y7!db0iL0M6c<uL&IJ-^6OLN)C~j@K z_z3P@s0{T+FTgw*yb%w_(x=GeXY`wtO+l<Z+tebsKwuUxV)a31(*C4uJpbAccD3F< zQ|}_jyx?^f^BH`%+^i`&=zX-4DZ6`P%)enl8<0us##FJ;`7`v!=WngE%5+xyti;HJ zoDdov-d7Q7^|ni!(q)VHDZ+Vg`t~4p;SgS$h>N3>%6e+~Hkjz@v0N@wc7s5((2X4Z za1mh1P&{D7Krx0)BHYED@qpo!&BkaCEi-}9Cap#MOcPa=<5BB0M2!9p-1PvJ4=aNs zY;$X1<7-ojNkBy}AVdEU*8DCk6vJRHEEFp*BpHhyqxc=Xppdr^qTubor;FDkc*U#z z>Oy*x;plj+^=WeAYLbq3D?=hR?ENw`w^rtLT(=`})9jvDi_ft*4#L4!yyPun5`RUc zzZ+ZH0n?_)pIoolJHTBrKBz-%u;=<23Uq`BN4UZF`0nn>@Hago&)+vJ-QI56(B~%w zP()Ru3OFy{LlC<nGs2&E<t$4<R0A@omz#C|ABoX9jp=fVi|gbiPrg||T8bSX*cK6m zz4fO<1VuEy$lM`=DM<*}i_`A$u8x+%;{7+BjHL*H+$$60&Ws>)mkd*xJVGVh+O4VA zKmrJ|yj9t?*&ILq5l&g;iPul@wmUMAMzggz*!>ZIb6~#7&Q#yU4-R#i*HEPiEZadT z;gCQt9oABRYJ(cEo&P}n@i=CH%WOq=!Q~oOcj%Mpj)eOcM4?O(^|2AQUe}nRS`04S z*XXO*`}4F5?$2AGEzA{abaKj7>mSdn)<%wsa4gV>$KN^=v0L0!(}yAn6w)A%U(3m> zY&Jhe(0VmM^h`Z}Z?wBdQAFVgE15DDizkHU_q*gt>Ny+IajiNb>&41o(p>2O1S8Up zO9@6<9sn-##<)QG+3eN??M_Hjmg+@MnN3!&m6!#--uHLdl)7S4ytWVwt491rjv>-u zR$6OBnoaaTa(#?(es7A=Y<Nvz*q|I$Dfu>`!v!3=A1|*tLQMH#G*-#_R<agcX@0Sl ze3DpESONuAcKWFxa_Ofhpr7UH<_jmnTsYXlj7c(MSk3I=(iqBI6hcG<?TQKdU8pPP z!{6qwKLlJ_KItf<1iQ^^9|X)Vgn7Rll7H>>RudOgqBtP|VQER}r^^lVg)$Y#*L!mv zBNy-)_HeM!2D6#(A5=hCV&Uv?okjX7Byf1h?$kvgJGzRr;iVyoV$hemF^U4-0O9la z``oDi2?JZbLAZVu5ke*m^fx^{J=0?CBw<!`%_>bH4wuvUkti#0vD{ekw%@K%M9p?y zqCccLE9|yG0p2o=+q$;!*7;MdPWv9DF?LA$#T%dJSClcKeFfahlvLHkEcRY^kUWAu zsv!)w4JSWNM%CaIqC6^rO(YXHVEi1WfD9a*H{@Od=1n+ks*42eu3s}uxs*zF@jM~u zD%sUa0AB&b4uLQu7iFPk2)T4Ey(^wHESa+j4RjXIh27p#QK9B$dkpE>=jt_GwPO9p zz-UrY(1Ya-si&{I?qL6W??rlQ$*X^q9&qsI?Xmd(X!^>iDBHGcfuXykVd#?X?v#-3 z?vhT)p&JFHyO9t9rMtURy1To+%lm!4U$fS%>(5z7?ql!wXLGw}i2hENvAm!7OVCIP zEk4eFT6*r?f4L)4MWPA)i=6;_I_JJh=@Te;221_ikNyk>UnGzzOXc)l1+WU;-;q6j ze&!{78Ab6)VnuFUE2cz!ZXtQFR2t?I8(?4v^l<$Y&9Y!?H5#X8Kc$z{RNLNJWw2^7 z1+S~z@;Oz4V-O0ruHXLG3**xtB7uu9`E`w{14N=XYZdlba&Vo2-a<v~p7z`OBSuqs zuAXIAB|>Gm8HOc_Y3g4w)<Zf}dZO(xTqmqK=5Bo5wbQZcx%G6J2-3Y2JkE_U#!=0; zPnql%hOAK>guGI81D*-|R$E~$<g!NQdMTG`O$h8D{!(^-j0&T;4%x&OV{O%$5huLN z-G;6{6{75Rdeb~4l<;D{{gG8n7Ky<nIO2RAWs_FliK^-3{3%;C;!mi>oGK+D6I1k3 z;y7)mad@dOQt+p|t=tKw4I$SJ5cA`7o<Vp__j6gj`6xB2`?~-tc;Qd6qt7XPA!GlP zrX<GU7W&Z_Y2{OcB6=gm+zX>O+4(bg*7u4FJ&i;wuXnsJja%>Z2)Xik%4@<ta0bj8 z?;{68)Hg-mCvAxYPiRT?;r})-g>TEAAd=-c9rRc^2Q4y*uTQ^O?{3p``uyd5+*|vi zUM>$qC|F1~Tc#^N+fAD0suC@ZJ{C4NkMsWXNE-IW`#rzrLpYZGMp$^Ohnu~{V=LDW zFMiMb$))FTiLW_oD}+1VG=0Y^X9odq6IzsT)AJnPrvl=AOXZ?9uctFHV{G2p5wSx> zp5eBwImJU$+lNjPrsoe3*`Z9OH$J<p_pCD6`>zDW8TyO6XVegtmPzOcq@5Xj{!uS9 zn_L3SS5Ls7I!_Gu5GL{149-N()U4qn$)|p|ZCQa>Dw9bcsCExR2gsEBL+|(XO3WO* ze7`=rtxcMt<*9#e;PB(y#Fo!LJV!{S7{@g0>SZL{Y!}`3#+@*)cOavc1VM>)EMs6m zU&5a315^UXknf^)=roI~6cOsr0MSnRu-H4a`<4(79WQf$_IIXSgRvGd|5I>9a2oB% zhdhnn&Rfzu@skzia__9}^Fp>qGv>!iz(eafSWr@?x&XhZIbLQ7K-MZhjYgA)z`r$g zOn4PC=m~I4oB0go#qA9}6M~d0b?enR2R{k?%nBLg8fmCGI}c5cLZp2b+u~?~r8#N! zx%ovIR^Xz5;XL<Fus0g7gv)NOl*}+n)_iXns)8OtoGow~jPpX~njUY-H)Tm+N5gMz zu>H2pA#adLmP$eX=WSK7q}UHTKfK}?L(utRDypvgrJ^2s!*lvDryd|F=Cm3kmdd4k zr)W);<DLMX%N82dtvf%7YR^~D4;VAIR6iBkg%&BANOGt4y6^T3oh5<%Xi`0GL^wWK zjbxv#P}J!ePulxziZf2EE0aqZQNQ7@SNm1dMSa&N_UO_vP5xQP!I}j#1N>S0cLE$L z>Bqq<_2RtlN0o=o#o0Sz(##yemXGZpbi}@(Wfgg5xF)=h%XAQI3Kw3aeg3x7GuiEy z6d)jU6(0FZECzpk<GzOsR2Z0_pX$2~@0CHL!fa&Zb2F>@`~(gyqB$g@0!5HZjk10; zxj)!?O?BdT^&)$kCK}WYXjh#Y={?vYeJR!JmrnY|CCo<C5Cndsy<XmY;0%H3Jr=%U zd9wNNu@%mVa~b`}B`_Ln;Snu1p3|<NRkdR7dQO}K-iLZ&b!TVNZ%ZTm72h_NwX8yT z`v&(7<Sw=VC)E5gdUv!Car*tIMIJ(xJLVI5Z-^-Wms5r!xs;&GM@uu}n5NSBdLj_= zPd1MzZ0?P#sEA4L8P);pgb=au)5$3Bwdn-RwF&nj`ISes+<3it>bQ)~>5Z%7c9+F? zHS7KTLAOT_Q<@{;{8xMKbe1pt?xfgSy7Bv~(lMRz+upBt+wa~;TV40E2^W5Ilonpv z*8Ijn(~iHu3|B3Ym!STbypC7L*N9<?u>iIdb^Ag3(;hapCQ*BOt9jn$cH40=DO0XN zpmS#ZC63d4y@VJgEC3H$4^{&sOXOFIH0ldv_k*5{SR{wq5t>1%@|i~xQvtdWOw=z` zSGL^|ZF=Z$cfDuiOldDLv7}sI<1*W&8>7|p(;a7w+iuWs=`_Bjb2*H((WE(bY1@8d zz3I*MEy@5D=9!f3Q)NP|Wn(grl=b|IQ2Sp@=VSYz+`{E%FA8L8`;IA^&T>)@118cR z?_QGRcg8#KptXV**|g%#ILNr+HlQ<WiE`$LQC~OK2tOq?^wKQ!{p4oH%34e(2z1fZ z5Z&`-VT;Ux+*ObKD5BRIvp-EUUaso5ia(vKkTaTIs4kgWJW?(bhW8_!cvJJKH}>F? z0>d+n4VT<bMg#@hoPJZh<}`$}?Pb|)&zXrIe^h%0C$xjlwTZAo95N+$FLBNWhC7fk zr4HGkA~haFO#Wa+@2Oth=BQ<E^Of4Qi*er9zHhN>VKuB46E*FxfRJ)R4c@N_Di=Im z7gYP}%gd=*6nU)3Or*Y!^5uT5M2`!>R`7STeY5muoBnqD;+mma%qVUEcU$~wux54@ zATgW?Zw5&V-w}x^Y0+{?*Xn+|h=Z{ki$;Kk1bR|{LEFenTB*8cYwc^qB$%#7em5E% zX9tKfwF;><5EPVnQEZGL0Z~(H0%6~VDW7gkD%`pcCbqG!Bt^g^4nx$hIb%q?FzBIX zNLl2ihY;yZFWQvq<>b$rY6`Q#NKI}fqWEEFFuY}2EeJs$<0mF+_EyDsDP1u4rUXqt zF)UTG#*uPPcq10XKd_<hb)`KZCjh?8$h*llh8R;8c6V~JQUeLv0A4_DgwR)n$1575 z-K{J@8-Hx-`sXoXO3PPBbw!ZZ9TFEu@_AlH&>#QWW@Yk2_YHid14z7!3)$gwt7F7S z+!M+jlLAr}qQX0D+Vu|BipsPY#9b=6Zwywi4Qus*4IVM2mE%&^2&1kT&s88Xn{`5% zCn^dA1ZWllXaxp3ESglx8D<?Nj$-Cq!dOC;3^XQsg8ZcOt&7&>6l*k@rtCg{XuJA- zc|RYIe64R~{a>0~kNBC49vPWl+_5!$wiFL%+F&23EOLB51DeAZZpLSym-?aDp1nxH zco+`^<Lh$)WHaq?;BNICusExS{w-x{3WG*@M-b^T%xWq87Yq~yj*dbd8(Rj7kl_WZ zotz`h$@9+cgK?p7I=u_|V?1ZNdY=-0>UB2J&w<)LJ(v!AiW%}|eTw<Wf1pe0o@9<i z8t}LP3QN8FyYxujn4f;j%u5X$%H`TcSQ^!aaf<18Q|5D!mK-`p_p@n<G?OdS8RDOi z=6Pm7?@uY;Z2nZO|5T{Ve&e{#s{j3C)~Kq{5B1np-xVi0^Mso8_;+OkYI|G~D8w=B zy_Tf}S4m#tsm)^2HT`jK%oCnQvBfoOBSi|-<tpu+Fr}DJ0p@33`fL%eFMA+Gk|$in z2WNt!LA5BwPLUFH!g<voC!8h01ToS4HnBe@D<w+AB`3?CgksjB2xjVmCK&{l<vZR{ zdt+&JHq$leoi0f%0fuJT3wYVckAWWfx*4`TWSMMZpo!$#{{16NvjtxdL?OBKuS*_B z60ObkMIXv|!5D`ei1^|4uzxBH$3WY%OLcb`)ME)b!UvPlO`fJAU+M4D&6xyq;Z7R7 z4*At!7K;f*1Imqsi1DrG$>mcynTp1fGFHD-W4c?viCm6;RT;&Y&+5{y?;=Lkj}h8X zc8iQTUE(z%qD%^|sy-L(1CLKmHu`1QfD+4*H62Rs2Wux}j)z;nq<l|G_ERaZ!HFDJ zbb530lQLwO!?Sp{LaNT@K@tXI5}&v0{do{%cqj0AxLt+q*JP5~?=NUCu&yRxyoW+L z8K4QBEB?UC8e?ncamtxjkLYM1tZe3uI?cEFSm0GwdQ;+8s`ckKiO~S*x+;P%YD-37 zt~wu6LV7an1fE{yFmonZu_PRQzh{d>vHuCLBmGZ{yM5eC%nS2s{#D9ZqGOeB5`zx3 zAEPlW5-iy3ZOkHF&;<b%UnGZpuTnIz{q6f<yWxUI?fO#peg|sT!lDxgoALBvbpPF_ zBXr%#ISIT$S~amp(@XWkYbEMz>?IBl-}5g%IYv_>CheI*2kc+g<Z@a+#HR8>bh#=< z{Mge5%NK$=c!YoUC8L=rTJ-XF#jJ9}H@~PRZ%bfcfLcIM<Y1!?X>l0%Vn5w=D>Rh_ zQ=+oMJ-k)Q=hh(O*$|x9prG$Kbx~cE2<Ij@U&BSII?&SN!Opn^@C5vBbQvrtDmE`r zIeuW#3YC1IV^2Vl&sj(NL#w(fL+TLWM9SJOs0ZPrXlmD<8NdL6a}i;t4e_tZKEGE* z`7vI~AMfW}T#u+YI#u*>85PDTZo(M0lb8q;WDKO`X13QRN+s<XlAe4NHVJDSNai{E zK?;Si>?+z82fDAFR?qrT1AiGc$|V6($dpAlmsyu2HXAGsvPH?bVzN)gy6zOSqltD} z2kW_eyJ!0!ykBUNSOdtL{hi-7nvo&lbd?$rXKWY=2ou{1>pmT69^}3`dHP0p4RZ!k zfu3`Y+7@8>3!x)<(c-Q%TF62KVBR~1!$n!OVRsx^13m2jic*Hh6f(v~9=d`yR70=I z2kHf0AA`B(0}6(D?md-y(}{H&5qE~RCFZNMibS}pN=^jgKc&sv)!ce0Gkh0Gxo|q^ z3+5zUzaZJa8;K`-sf6_1QqR>s&s6`qH%Op!&c|q{M1}sQ1C<?_$2922_VJyFGt~I0 zYeyy@=XG@T{>aW-ss4$lb;pF*wKV<hm*FeK-9R!hxugDLcpC}F_hNsZlv6mGk|;;6 z-8KEzQr*Spii?K`ZpS5Y^hG?=v5^Ct2S_LmkA|-8^{T*j;yQtYer@D!rmwhSdO!yh z=OrstP{3W<-*p?Zty}?D%dz}I0>6VS%QIC7?b~E}^6<gm6Jy&k-NYRLtZlGh>k{IO zcImR!CnW!!9o9lNN3%JuwsJKro<;#Dw!47tS7HW7jq~Gx5-y*&uuMbMWCIuKV?Iyv zKuVel6!*CGbW^gurbrlCW{cdYu4g{!ih!!pZ7e*4B>4zg6j`UClWy#Q9pd?3pyc=h zXDTA@OzmihnhBy^`bB&4LhWAr!NgK7ftVY?Ho;J;WET{+vFSxel>=u~WEt+!YvBjj z;ZJu^FJ%v3>glNm=w`YVpvk7D($;DhkG%L@4vgfpo-_^tO|g1M!|-~At*JEu&&e`Z zyfP4^bbDxwX(B<u7$s;vFN<hDn%rn2>Smdq)ljuu_Xm_6p}+L(5UyD^;?+Aa82pgi z#~H>Y%gqeSR#krS>iiOpPC6Bv@rPdSGN~otAoZG)Fo+@qKSwq%a~>IvK!#Mt=FvH} z;ket07M_RT5jN3<I8Wf?Df{)qMBB_S9S8ZU-EPH>z_Rb6<8#ew;?YNJrLVSc&oi%O zVTUlaY`b?YAIy=&!mnS2a@tjtjlPWQ*_cD~4U97r^6w+-{<efE8cWadK_TpVCDZxA ziMch{O*rkR&_0qbW+tsv2vfqMl1?mDir)NX|5nA!|F@3<<M(HA`l+G<9=o=&&M?iX z5c=swWpm5)+ZCLlELawDFToE%&QMHoDX2Uw#AcOi+;yh&-sMZVsETi&IW4xL`@nO~ z?GkuXsW4R%Qlbpc&WbJp{^-_cyY3ZrliAE`R|Wb~jMGVt9HqKnGf^xOD3qL~1RFgQ zcNHGLJ)#pTqi<0a9K$kPAZJ9XU)B3wUk`FDH9F9e@Oi`tKNeEjDJ@lDla5b#_1<%H zl8E`C6&L<XA-ggErI7aE=eC>u$!=nTCC8<=9G(46#Qt>-u)%sQn;^8BzV!!PL<Gr5 z>1|t?AVjWw6Fpd!+WBfD$M<<67$|XZU6bv}g`7l^;2^L#cn)I*jtUup@E)fp{^K)# zC$Z>QR}X%tYpz2{Jx4bonqLR4fqHsD7?-8jST|V-<!@`FU*>}t=F@;GLvs7{`Ssan zgVgU9quIf~TyZQD6!RV?LAMkBmB1`U#Hr_R$13O=-fXX@4x6a)$y`c?a|=YHQeB`h zCvRbB0>7?8mA074`6O^AUCxslc(!95?VNV5lrSapLT!IfN<qDNgY2MBazY5In$rv! z*KEOYqG{N@py--)NB>3G83QhbiPdg#ia-L$A7efSBstlADwM?>4mMVgq4WC}rqYt< z*6rS}VI;WXjb-Ovm}w8&pHf66(h*Q^ieg9j5EJu|KM8!4>a;KRIat$6N;T46CnpTj zg=|sfGR&@-Iy@?u*&krx<QQo#nto_u#b1Y+Jl`2We-x`Y>u>p(*<fExh<B>=nm1@4 z%VyH`!RL|=k?ZBB&<)XC;-w{b1Wy7QE399Kn5U&;cA<hl%NlB-d_Cc00?VUXy_W0r z=}Ghc{Ooe6SK7C0pM&FT5}A(d8e?ke;e@Y%yuA1wsZene0n!xhO4C#`>JKMTyy8YL zEawA6heroKzro4sapxq<h8r)hH|7-|3{m&hrv%}%mE=oH`R+oscS218vG2#;B8x}w zlcThJ6PxbtBanWPNk~mxlyE@Z<x``nab#%L2K18~xvb|Rt5@DOE9Bl5B3WEH+lg@d zy=AmLe)AJ~t%<jt^$Qn1xW>d~98nohGY(!)eB=9t-Fvc-EUDP%zxtP!8-<D<U)Hk3 z__oz|QI(L}9*2b2H*83&Qqd3YuH;Z-xO{&uH$ffayQs)ggDD^Cp3gEGak17f+>-Gp z^xXKR773mz!~90q_iCnSKd;52`>y3_?qku675P7p&Le#Hd$?Y^-uY>Az16iwCm~G3 z_vJ1hJ)=!dI8tnp9Un|4rfIr(2y?Y<Ljkj_`(DbvhGva}yWXf_-75X@MOnSnjqCAx zI=;+W7|pmF^ck#v-+(II$VQuXyvb$S3MPZuFiJcMltlJ*i~c^ACRfm&t`I)Hn)_?^ zfuHzqxNX~5Vd)}iD*-{U`c551UBe7--k9`C_$r$aL*KN8Xz(=mlmTW-%xXGr^a1i} ziosL7>c(cW&HB$g_3F=DbNpcfFbddyLKaLjJDfiI_)9HMtVPE8zs5VDW{NB%9_^Mr z()s-e{N`$5ij*${h3#ge=15*rer;DPMeAJs3~^-Wdyn5`obzQ14>9O9-sUXl=pf+C zvv|D@_F$NPZ9;E0T1}Ov?xLB%HF#VRBjLj9Z3e3&?9!7QLb@UKE@GUIc>St&HTdBN z6`Mx6X1pa!s?>oR?Zy*f@j6`OLyQ4JrS3J1-&7;s%5}5^-{toLg4z<*S*@$uv)9_| z+51TK8gXyi#d6rYBi($9W_@&8E5Hna;Q%wl4%ay+F<YUdmIikuI8b{y`{SshpNxpp z+Suw)(C^XB7Km*c=0fS__!D3W#W|2b(6W*;L5nmBbQSC_+p^-UC`=LDXw&jP0vFzO zZbYHf%(>H|nl2{Kr3joD%m#7Oju@;=R=CZ|xTWZgZdaO_I1-QQU_P4xM6PqTnDVq+ z2m`{(q^jk#@dM#66p!a@z0>`mZ%%y`i**jm+$k>*!Ql7hjDO&pMLvI=_cy}Mf6)^_ zQ^|Kb?ht~o+e}d%F4g~7e1w@xuo-#%l`qe(UM1ZqY){m9dY?k;tJ<fQo_0?@v_z={ zExchkBg}N+@@`&)lfr5wH7~-mU#^3gtoXEJH8~K&u-T*1n=m~oj<9Zb(22(Q5PhvK z4w`8N;Qk7oAa<#s^%fJwIR6Yf$FEWVrNvwX+@}6^d`Rq5z7OMeSdkllhE6RVl&`<1 zR!$77Kj?~txjsoEaJxL_lTV-n!YZ|d!<ip4faXR~*TdB(X#XIXsY59d$zaJIPhKw! z3?lT?TCxUrMr#;5yVd3|IZ8Q#%2q5LXKol4gK6PN$sd%8qHs64=1QRL2~kFAG~Y_5 zWzZ+$IV>kx?Ea{VcB!kM#4@Oti&{3hyi!<PF^QvQv`Eln3+AUKw&i1P6;F)H_#ghk zMgOSdiffU$3pG<^VRlP^C>|e~mfK%vy9kX2W=}`U=B+-2yAV{nH_t~~@lm}S=iS$t zlC-B7EiUk^o@ybpn)KvInP6<|Ej=p9Djg%*vETl@fbb;JDkd_Xt<){!|B)w$rm(Ab z$TjIKU!C=g@%ny|>9zHdXQgdNMq{mfTyjD$Nobgncq5go`)2?WPj)ro?t`}W{FVO9 zDxUNjTwb`!`jPkDSo?m8(f7&OA6f@fq0w&N-W1!$%^jlZbjrYIS{nedap!V<nM<gP z@5zM{2f5o@JJB(gG5rf~0901nePC1yvjkUpa`Dq2$4}1<a;1i?a51nl0#>)^>A#%C zX4nuTLs#0}gW6tQa7JIfg=Xz8F#Wn-`CKg(MmcdgRcnGLGSxI3$n>i)He3bWVTjZb z*6}+3*pR-_WN`Zl7p)JR=Xks&9nLaTQ<TC(2DaZ)uhi%15M)~rI;e?K2CHe~$tE7x zcz%j^lDS<ya@{!IAGqQTh=3ys821W*;;zbRW?Jd{r_6u?9}WK+bY!?=JfC`mJ1Zk& zKD;t2{xG`oN!d-c71srcY-FSEFCHg_xX0XwLpzLa8&eki&W9gX%qmy6=~Y$oOpE9o z^GwyN{T<2;AGqX)p2ESx@t@ZUXFtB59PvihiN4{-Wzq>tZ_@}zI~5SOVALw^J5x7P zb>?$7C;Mhadao8016%qwfH_mI0kb(z?Ys7Cj$#X$*l~qdBKXT)0kxgSr#*mFasJeS zo((=n4r6<~kXF`EI+_P+4NnxUj#6{GzrE&<<8#*g54y6-I@5RiHEO<01{*?gAIns& za^*G3SsSy$o9gVOy<IGJkHY)6<38)Zgctj9WWQ(DlR)P)R>Jj=Qz=sA<NtD*q&l`g zktg)@L$U0f{gf%W?&;^UNHfPbOb`f4Sw<9L0Do016{^^*-rKrc%=k1sd~<?y$jmG1 zD<PVs6wsj?70!i4Xtx7T{>4rGEa8fV=~l0h!5y0`w5uTMqkWW*R(Cv<!s4iDRA-F| z;G&tBqXT`HYOUgns5a#!>%&-vO5a<<uKPqXeB&(ND|vF25^cL(va@|{B8>y&*)%%? zDlGDff?r<fyVYn2(u@^)MZ$dVPZ*{U7vSRx1fz2T<9O`s_IPG$&{#v;`!o4m`Lo%t z5I#9u%(`$?V{^SNNXhXbxk~QDi@g5)viOPqigBh@GSA5!k444w)-Orl#`Mq(dTvOP z-@8gMsoXl!=>|{JB6W_EE~X%`W4?H1!rvZ{x`-tcF>J(fs)!am_n;~uIU>iHpEn9{ zc)zuy04R!#`kG@+OoVEFs7oMkDDn04D^P&pXLn8f%@*I0J_Spsyd0NQ?fNH`OkX-C z86of;%opeYn+e@ZGd$uHX2VS|W%xm7fmITt5!BEyi^^1?g7`S;S_yW)^3+A*9-YZI zbM-(Yr`?h4Si}UXXZB#O-wiCUQQjMG9>Jt4ySWO?oprYti2`ncilTR9ywZr9GzBxl z2Xt(S-0`Hf%9gKx7UN%PEr!1)4_&mc=&&E;(kLL+NRt>Y7&bk#WHmb_2YWor2-9P! z1PMOS*^TKRkEc*-xw`Fg^rKD2833&KP;Y%ZH{BKN8ci|Rx{a5|jN@9EiePX0)S8#Q z5AA}hAMvVJ;0(GfBnQ8h<f~RE7g10nsZo3;BXeKuC+TbUIbpW@xSCf7Kt@kzyA<++ zsGO;7cYN8=R@z)Li{r>7u-o-y`G(c4E_YlRMs{c4GWq0QkLQ`yc0W9yi82qJ%lpU= zv}<g+v^U^@!6q{~ga~AP5xgfp_H{88=S|7y`_GQ^Wr_XCI|$k2swHxO0>he-p!Bon z6S<J_w=vp!^kjOy??^l2{S8hMp=>g$mh)_HuU}%v^jnlts$Ylai^z5?6OVj>uDDul zG2@dd+_}6~9G(T3u!qnU{b0XS!fj(nXh^LNf9HHu39-?r+nj`nm<ya|gA5hjJ5bto z4)vDne@vEq7hj;6)8Z7)6vF-~ZPS|$6Wc+$(2fYIY>Bc53Hc5)#|U&U)TsP)_oDcO zPFhmpA7MRK!iv!sXi0^h5@PiIyXjG6z7$feCM`VwCJ{@|YOZ30I0}xASU*OAYgVn| zw~x-1SFab*o(=g;!-ehW&2+L~*>RgOZuX8IX#)NT7WL4psoAWyo5EhHVtK#>?R36> zT1<p@d+Fn%d8xW+^$eb(QB(|F*z<UQ+nvTL#!9l%`gN&wKK=G5a;O)g>ZdqC*iy5S z-!ln=BgZ-%Y={K1{pe)*Wfcc4TW7&DzpqNJ+tJfiZReEw?h?iLw;(1^1u->zWrzbE zCFA?}@CS>1>0=kzRE2f+E4VpE!Xjo`nDY-lNSpOVvWaP{RT`n}MONZp1yD^ZXN?V) z3&Q`TIkk#fu^5#ERIlyqbx1ywbiAGJ4l2@rqn!rS4t^*<V1PhDDX>5R%FL?-kT{Z# zCF0?hk;)APM$0BgzWA8pXV?dRn1NP>UQ*fk%F_P)Ew{52c1cbqp47b@3L#eF1X*>y zAJcLSoL+}Q$Qhxi8Fo;?-{nT6^0PpEeSX~bl4Ma>Y@sVgK(NQbygx?aix$lSYr(uf zwEG(v0?e3HKoAeuiSx+eA%_6syv}h=cxMm0O<0dsS(NJ`h~-0L4lljKs8$T=FYYMD zi<=t_%jY?}Zk-jsR*|BQ!|y|RHT*^`<-hU-M7Ve&=Z3-?73=;gk(Zl(=r?XD9HbL| zU65S7hv`g>*<`CJ9gxC^i842@eev=#j^GO-XudtOCYe2i!4iwW&@OX7nww*=B=oX# zb*P<?Gktx2@PI0MygO4y;KkK|*rBs9o<k$JMxEwLsBk$R&>muHkD_;YFL@R}=LmX+ zW8D<U#%G7TBW=mM2;Z-X;x+bw36Xhc2M@^%!G&DBAb<Ndh%v{Cgs_hEJVBBZnb}a` z08$|g_w9iJC`Yi#SR_T~*3pk5VO)YZpny4m3j|0~B$*+lLToZR&#QlrxAj}^R*E;T z)jiI3*%g*34IDfq#vBqAiCV!VtnbRYfz(=ZufVyH8SpN?uLW5Xl>)ZmU5;0AJ5M&o z`Ih`^j1l<HBz_s6^9t{UiN|m|@&x)B;$y(jWT$dw(?EA`5k=^wQ+pGxRvq?ryfC>l zuhXCh;Z^Ua^xDq?v&L7aVla=Y^lKktg7ceZ9OJ$2J(KZ5zV~H2LuZUrgB!DvH7$PJ zwXmkE3JP<_?_qS{cdk)Yb$cyvEEfjy$byee1Vd|rh(-!-bbtPVig5>@2~1rO=sgo0 z`L*#%JmG1Z>2oiK!jaT%IjvlI{e@_KUN5H;&M2#2qGQ%NnW?&35EQmFo`Emx{c=JU zjz-#?TUDL^u$aT=Nis5zW(%!x9p@L!OwCLz>Dd?kuHK_f=_jc~%#!p{L!7f?-<HUA zp2vVLEG{m-bad&<Of5Uy3|~TDLIe25YkZw@Cg(!t+TPvh;AP9@FZ=`p*IdV4ruaJ{ zvEd|4$uFxs$7HARAYVrpwm*oLcL>DVmiJ&njuTp+4v@oNFT_O$)Th1O6!^%+67x^% z93Cr4Nd{{;MY|_UpLU|ERfnh$wU545`{8y(of%z0_SkTtB5T+jg^jsmTFKfY`Vzt{ zSvifpWgY}XTmJ^KD0rykDZEYMVV4|I!`K;?pDC|OZ;@Il3k!Pce|Z$ZqAV5SSm*e4 zNe{Gf4C4ba64+XL!P}N&nKp62+!Y-(<}NC<BE2;(#C#GGNEvZ@TouUsK_x%LfO9_- z8E>ljjQ`FKK9)v?V+kN*4`U4t%NYf5ii?Uc3wH<8{Z$|G(*OaXNs+f_?8#kAfz)~k zek4P?r)B?SCa>oy@mm9@|A=0=xSP48ln0KaUq3pAwdbKo1(C?eI@zqPuuz$s$xyfB z5RA4f)A=Iyay-QoY4z3e)`@pif)U*|aTRu|L34qFuahy$<DS*i5jC@jb!(d!*8>i- zt%w(|tIlHPD^iAvm}nEE#obD2gP3NhT!NCo(kKq%*PSgUs=E2u??Vi0$M`8Xa7nM< zHO||bs#_}byEJi-2Yp6DBm%TbEU+gkv88)=C8W&{Yt+HKY;y(KowEfzuLqOLgVIA@ zpWzoFy4+Zy(+sv8k5CVR+`BOTBW8ug#g?BFM2UUozz7}KtYYsdFqZ72j@NP2NED#h zf;zUtr#82#jq8K-VGH3o*Eb<8pS}eSV$;ygV3{NhYa+_RU$w(1h>PN=<f{(6LqCnx zQN-p*$oY#<f}>xWHx>+%_5^b@uyBvI`fu?Y7%R4+5EyRY=~k>1jr|C|$XoA&A0Q(p zceXxCH?rAJAg{YS4wz{=vYIK-gC9EXPLESK#D`*8e~bIt@wXB7`MgZn{w44Dfs`Vg zv8OazO@(oMukvw+&y)##9fK*Rxv})i0Raa711{f4drly30{nMvY~3GOpVnOjW?Ny& z<|sIC$sC-p=0Tt>0<-<RSdHaFAr{VZ(>Pns0;WfGvyI><DMy~quO%Zd7g*e$w<vH? z3WhdfOlBw;8~V1*VO|9d#IBYqg#_c#0-V)MC?=U)e-O785g9`0>V9BS69}O%LpLZZ zpk3_=AkXt}Rm!@vx+>h7@F4}Pekh7XAWOa9dUHB4Lsy7Zn#DDwI`<Ci?%+*$ZT8RB zeEXI3zFNC`sULoS?1lC@gPq{1o>|Ods8w3SR<l5UXZY7(9lBi$yUqX$(k5FYu>v9i zHmO8sBpTb7Z2H?6Ih77vVjkhd95|=Pr+08m*1>0dGhHn;0>?U<X|w%Xc)Y13nivCX zNEkQ20_TatjYvyP)aivAj$!>p(x($b04QA#9RQ{4qx)M}7szbbVjYLH7OH{^>OH=O zr3Mr;WB?vyE}3x0?|`&Ms<$WB%i~Qgheg;MPXbmIz<<EESfRtwTqWj3YMco513VE? zuqFl?o^;4FIoPM1S`x0~<b<M8%CweA57S(`AYR&nCy1C{P>|#sTTTy$%Z&5+%p@a9 zDk+H`KVv4M3lv7R6h*B&k3Y)L^y%$@Z(k6|LW6u!OgR!pebHZ9d}1YVB%Uy9-p*O} z5BYypD{g!4{XP^i6pv#Vq8Y!?rsQIutgd{SFH`Fu8z=WA-877>gl1B2z<0vASL)%4 z{&R=0yB!k<w>n`w_q4YVZbnKts;MaVH*xHloBwxW3mC%?6cUKSV#=cBCm7X?v&FX} zSV=m5p<bE2;J_4X<xv$JlE${&<J%>@ZoMh1_|BDk7x~va^T3Oe1z6#tNYGrN>NcVm zJVwIO3u1;YyIdinEF}VL1TD?CiR4DNF{d=bNM(HbE2<QtJ=7%L5-d6ivdj%=k@kN3 zOaB<f0hlt`NecU}v?S$aS);0A$yphJ3S2^~*W=}j_oG(rJ=pDOlCOx<Q!)lVpMG$U z(n*w?CvgVR#CnrhclMymqfj7Fk8MA+WM##svvU!hBAJ=6*t<gE?7s6k)rY)2WQygQ zzV`iw1WNK<_Jvs=YXo(T;|DXQna*^UIFHTY_#I$TRph6e;W^BwX7kKX3c=qC6&1+D zO_|M^G690$4^&pz#@G9zqWOA>_A?-=Gvr%rE0ihJRu?^~8S+v5MalS*E0$M;pD`jB zPaPU3@#*+$Mz#)ucJ-PSF!OI$_4(BDs4m*n>LkWN9HK(0XEN<2{%&Vz8I4AbN_V7! z#f5{sy1rr8&kzx&W?b0;-SFpMff?`gZt~x4T?`}WlYxor=Ve+<MRV?r3`}?(PZ@_M z;=(m?6FPEgn9b$}$U_Zd_{#nIgd!_q6C~v&fo7xOzXOfwYz-&l`oWD)TDS3ILa$IU zWACd|4Na<Q06_lxnFXCnTIV+C@_3P>cJ!?M?Q;pHMfOi>=@@)5KqllTqcle5&hhag z1JI{M3F6Av3{Hha(kj&TJM|0$!+ts$jahv})(M;wI56ID9Htmn6DY_Cto{|0-?$?1 zK|N4q5Fc;>Tk%bk)0YWtbxh03^OJo#u)5t$=?3=&{0K&;J~HQC9GOT}EqUC6)%~3t zHJH`eK=X&@s75kAi;NSM-OQJJMYn5Z!mUIk3sGxMfn`0AGz9Ug-fmw1+u1oLq89W9 zrsUw9u)zl8oiI@z0V4&1BsK7+rK!_b=Tm(8JhZ=yWfGvzc{ON`PwUH&a6y%k4orT^ zaaW)uON3^B*L4N8+yMy|Ljs4RXb!X7C0Ib-)vIG7$QDr#f?%GToVl#s8Bpo;46Jwa z>ZfkEL3Q~fx3UW$_d4yUSPH412ZS*!46I@hzCdEJ*XJ}>x3m}M-J!&kUq2lMia2|h z%;Wqzd+<S2hW;mO?eT3H+{tLiOQR2<Ybst$*k6&h_32!tYEPQ#tjZpS9DTi+-Uha$ ze+v%v$7RL|WrWg&b;qR)bd5};<2AebxvRQ*xk*b<GXs+=LmdtWC?l^9aj<MtzSh2! zAxR6|*w`5-$dracze-rqFlYXrt-Y~7ddJbPVScdoz1itB#%1T*C=VWd^)MP?^wYZ1 z1Z_E`-A8=0{2mYS8=GrnA-ydWn!vTW(r(?>8eLW`Ge7B})Cx?$CC&VwT!*PogFq~< zNcZE53ikJopgT|mybH{J>*k{d%fUm$5kOrs^U>2<FF&hEG>~U23=ioq{HM^l9~a2O z9q+x5Ve4#W(Mr$W{iV-kQL#+=;ra<_J;X)CL@z3@GqN_SYWpMF*45vJ0nL2rWOSfR z>E-=jVfT*IvPqN7hRpXIDwafm8_o*DPa-HcusCB5BA?2dhXlgXoIpH^$rZBU`U7&V zH|d76OUAHSN7S#Js?_7b{W`B3mdhQd`xRVlEdB^6bYGn18ruSemYDmk52}R`mo{a4 z;ia9Ywh;&1H75w0xMP!9ksKlkV~2StG&foN?(E9l*QB~tW1!tf*7>>lOf!-MvxfH+ z<%@?4M(R6x-qBx-kpHryknpQpnXO<-HrDQ+dIdpJU;(<{>S?}$7LSu9rSVYB`#C+w zNg(AJW$<!N<gilWU_lfEGhi&-ib)L3{iNUVx(iU5%(~vNKv>8wI?*f|#21YC0q?e~ zBWUXyr06Ct<Z#r5=LPBw<O>>5<=BC_)P@pHQxN@*h*U5m&0HE28wld-vYajbLAbb7 zjxsNyp=ZVYEvS}`GfWMawT}50&T>;XL3YVW$YDGYe(^jjB6@y*{6jCNGA$zfgUM;n zdRMCGq@M{AhLk8F$7V{$-ONW5P>*bSQt<C{4D^Pa!slhM-gkwh4|1k%Wsec?>?og1 zD&;LcjY1nNNyZn(Hwhlb<1c>35yEX2Cps;)6L7R{SiIDqr`z?Dh9(LOX=Jku-6Jtp zpQ+DQ&2=KUHO!j9wSQS0RYx@^N*P}sBfq(y1i)0#^yE)Xal=(E*>+Hua-U7~$<kZ; z1Y?^~tzvPw;ki&91h&vPhhiE{lC+syKKPN9Cck42#hi<NLWgZ26T2@6t7&VH*TdAf zL5Av%g-+k}krC*YD4B#yZz(66#pCI&kNs_bR@wGv)5RDpC2IQtb<}8wN8NxdOb<?q z(^Nk2{gzXEgV8yvNkW1zWU$wmn_5etq>60>>JOHD!+ZAoZm|GAe4PiJe`z#66p%(c zU6Bm_l1rq)^v(1R1}DU6VAuQ)T>2*^ESC~YjM^^xj85F%DAB{4Y8+0J%&7JI3NNB5 zB7YeWS8ujFuZ@gossc$OK4Xc0WaEe3EeH2y3;UIaU0ht`m8q3T?<KHJ@eCMP6G6N@ za8eJ$>f@VG2c$8&baS(!M5)H8I8S7(SHx=7Wo$g=UZs*d|B_MFeMiD&nAq%%cITcW zF)^&Bl+mLFl6~$jz8%pOAILQL!^MlGU*7tsUW?mAW#O8u`6z^CggNSeSTRUPv{c6> zXC)1U)-^(yknbgOX>5F-kj;6<wND}SHyf?Ry|y}t3LiQFKDE-JOPb3UGBUv@Au*)c ztNGbxn0oFO4%Gw)a{o>x-x_hHXRdlvFku%YElztsK9D;yF~DAm9-O3-ZctvOvPQh1 zSsX!7udN3aAvIg#02(tzQAD7xb=K2RM>dENChkXRjcvB7F<b|Ap_^9V*=c!|HWF+V zyzl8iM@;4t8PQq73c?%v^q2F14o$|Gd%SGPC!UMEH?$l&h0zqn73$==C7Ugx#whj2 zTb^H1ZmP$h;J*9r5c|Z<wKnh!WE};=kL^75&(eG00#1X*s>ku)j$+(cQ`Vhkj1;Kz zUxQ*NYt#3yoOvx+ly*&x$irL-@rZf^`8CaRI5aIcQFqbmy;uS>nyeKq(Y-&Tj~eyO zHPGNIGe>n3cI^Z6kz9w)Mhf^YVQ&&;K}GcfMNDP4gnr$<5HYHJ&x8!?qGdwLd=Y)3 z)IXDCwDvYLtda&Le^(7FZcfH!mHy#`@cz4BjwVVzm)ml#l8%>e2<;y5=%k$Uw}3V~ z=Fs0{KtCn}Lr(W2P&1XFMsXLq$9J3Q&~0>~?u^gX0EkV|1t8NtRTAN7Q6C~dUt*e3 zd<w6wuIBRvY8^J`>z$UXYS`!1h-3)};B7juPl1Sn19Lw?A(Xeu(cFpi-ba{{qzdOG zuy;DZ^a#CF6i!@;sT3*ALuv+1ULG}Z#tU&57i5+R0*ASKGdAQ*TF7R|px@@JBjq7U zAS-8GDQ<>)1kZLdQs>hZg6Kh*7f}_vE=B<f{1<bhKzo_b#gF<(3hGNZ^+<4zQ93;H z&Fx|r?|-)xi=mBaw2fs5hMQ4`wd}VU?Q!N$HF_7U+CeY@0~h*k3JQ92AXi#coi4yJ z3S2{rg(5DO;lc0-Bjjoq?Aw)!uX<zs5g%SiAg0fTmwUSaZ7xW*8BV8bhat~r9bL~V zbBd*RlTJMB$wbZNzFd8GX9R-(HPYcE=CqLy3oa5upxrBMH8PAp{u)!SXg-C%;XR%z z;`7DO^tKY8#C=LLgkM@H>5xO(2IIluA(#}P+!0Q+!Y;a2;figYEld!j4FYizUTJiA zb=!ffK*vogMrT~IQWS6PcN4*@2J|OkE1AK(F>$f8g%oFLOD4=5yB0J3H~DqD4f+m@ zIU&-tlB4qV{anGBY;BJ-(VXRkIln!m;c%}XC%R4xRj9w^;FH%G-r%4fSMU`iUqreT z(E7cUH7itRoRL+5wiO&?aVsAmd}6XXm^yL!I%1kKXKm`(cku@9-sw~KgdXr8(nF^3 zR~nKUiftpNy~IrFdJJOxRp9T)Z{e*bV1LF&i%WfQDVwV3S<T0)BI|CZsv<2AsdL70 zGau=`h}nh(pdSMNTyxkhZri(yiP%6&3=oMkCt_S)ndAd&#HL=otw!w{fNPwJ#HRf_ zN26bB8Ji`?@Z6Ty%7q`g*hmf4HB2z*c7JXnfXcA~+WiZZA2@<yLf%s-1dG{+@W@7; zvQWs}*ZE$J@{AU1l&h0t<YqHZmnfG28c9oy_&=)<i%$Xai9hf86eZMfzf{9+r~Cjb zdJXKaH2<0En!Yg#cyWiwxjx_5EYo68xOD&3N3QeRP-Ejpy4479Y~&EJE*3{7_yy3_ zcYTDumvN_J#O$E)JpD`F1cHh^5=E{{a}Q`zi2LuR{zGnn*M*_|^|+^6NlEDZJ1LT) z<OX;Z#HBT#-&UpWn(D27(ML=<2w*Lq7PbO+`=1T{82GPLQ#bhK?o=Zrg|rGl8Gp99 zKX|Np;03BSkni8#W7s0>Z^nrdq0p3;C}pw#0C++7KG(}Qp@1@jEJ+kTbC?h0zKSwH zdSYVP0nIx|WZ8Skjj+b1lHmk$i5b$aY8nOCEV;>iDT8m3rSW!9lD~6ua%|Bkh`tb~ zi$*&E7NMMUBt6T<I1KO#S$1n}LY;Rd-_tm(uzbn-xPv}|T8y2va(58gv%q*n-1epU zBi)>9$zapgg7;Jq&J6)E<iC{b)S>@o&Hmd0FoGlsl%i<9yLv)Gx-W|VW$Na+<7aX( z<!_cLdB9o${t)$_y|V7#pv2scd7oeoWXjVz@j{T?K+9!7pm>B!v>QXr=<in`#mE-r zwS_ux1E7llxmYsuW%(AspeVoQdllPA1CkTlc2vfb6bP5L1>lSO0dKCPGf<M)5!716 z3*bBxpK932pFpBqU2Eu`$!-yqrNgH1PxqSOXbwU3{%@n}=TYS1+lUBMRC7rZPZ{KT z?Hbb|&r<hy*3l9~>KT(_AF<XDDIlWi6hF(9G=>%{V0RvWI;eXv`XT;1Y79oqpI8a0 z#^$oJj1LiQA%P&I|1((#(5GN9s8E1TN{r;bycW(zEEm<f-MdM&7F#z$S5!1_grw1R zFOEH+Pi43#5*v{!>kpEzfo^@HbUZ0Zxn?fyy3^aMAE3lgz^7q-*NF7`jY<wnN}PZC z6VPWf=?+VK0Y{7gbdNT>t@KcD)tXH0>0EYU5xb;BbI7RE0ON@Cu=@HFyVY2x(v$SI z3#b8rm>zBQ$FERuW_i$rLISZtnt0<9|5u>Cc5=~-0>BYKv!5A6j3`^d?B6DyWV`g& zDa|a{w`IBWRjL*vVb#5I!1lkdB9uTtnyBQ)<QD*t)N%Shd)1nELSR7w?%B*R@MwjA z%5JAVobTn$$@2V2_;=A2V7_py0uuOPB0DP5m~}UoEt5|BXKq%!gmoW9YB=pMFi(9F zA(5KY-Ji$U9t6ZkMJ_u-m;<suVu*O+-ZSZ%zb8+a1UMKR|E*RW)pCfC5@cTU7!t!| z7pi##^vnx<`OguN*0OKED&(MV;U^*a)4A>p-LyaoK|!(r;NP4IDrxuM(^Ns=r3BXm zo?DCa+X~yh+oUqZK5p-UFYJ@}{|~qdFjiAs+$uiBKrP2Zk|ZDQOH@0*mS~_Ly+IS_ zN{jb&#V@OI(xD8V>NL+}QBEgG>9EL>?;1ZeF(cp|aZ{5ZzSEt&#+GPm`pPMa8QhBx z93gz%&?m(FZUZ}0qQYI*g5H<gmL%3nx|C&<_^7frj=0tjoojjTD})T1-1vzY<IWGf zfagG$hOBVDVG0G+&_%JbLF*1ksO~nf_J+%~MSw9h5D=gUG-TyP{w)d-p@9O-=IJRb ztF>KV_~o&6lR?UiTn0E#;H5#$1D_rcX3z=2xT;!v**xr|7zwW4kx~5B9Ua&hcL0b0 zeIoNnGdOL;BjhV#LuLVC4!1eR`13@Y*!@gEJX!qwy)vFP14M9+-S^%JkW>5~by+oP zeZzNzDGZI73b(riw!%zBOb^1qNCdYN!z5`hfAMJo6x}?imY*N4G%&Ik>Z$-x9p)<q zB?1FT%`V|b9&BMvT+o@kzKm`zJ*ugmBt`_ozbnN+RYdmh7J@+Hlwh{E3E6?412Sx# zw;_z8yLA67i|DcFzoz(7I6%buDV}uPPq8x-BgmSN%T^NjCnirv@`M$E6lO|tcp^_? z<#G)ne^Oo_5&^l@$`cQD(=zma24u`n5Q+gqqOv!ZCFEauZe`0wmM!#!yK{!Pa1#)X z+y~%+c~xv`#R?3pv9o^(7XsIBErUM7HCRqel_--PP8CIu^+i$Ek%@t1By)FKye>>3 zjW^c^)7`VZ->5&98Z>)Y68X*pnkRiDAH^{uK0p(dr%<l#R?>TBpnW}&Uqb%Ra2#PG zL<jajZ{mHBFQXa%b%jXq{vpCcTof7>^MB{&3C!G0ktF5kjvY*wl!*pGTbgUFQ2Vxv z)xv)buG}qs^tBi2dM5l@Rqui0+t|6yt@qnLPl-T`34`ki*mp~zR6V71&cTr{cF=9? zCQ;QzfRts32ym2lx?CifutGY&%x!gEUtjB7_msqQ(|?+8^~L_fA8DXUW^(CzX*&pA zv`~@*%W)7;yIuH61Iq0bA|eg)=7M0^VEbCX9M(0z1Wr_`6ol!J5Ke<Rr2exF|8ATZ z_!)th7QE#o)9I0=BPZ)QAjA0{dJ0W^@PE!B1Ohm`yg=;PlJcgJvH#BnAj;V^1-b+h z8K8Q~0Acw35ab%x4V*?9pn9}Re-8l#;d}>|UkrSu9JSSE<Sfdi-Z_EL?MH-F6{(dd zsRI%=S%73`9WfA5SUg^a#J2-ApQTDzDk|S#-GZ!Tjh_}61djlLj254@ivRsa_*i-4 zhi-S!H$3w_Ku+FZE}Ds!RM1QG90m!6d;;Xo1MyX;>@<MJD!xQ04<499pa^}Zhd^Ag z1ALrBE&-Q?dKH031XywIBS0;8NNIRZkR0)UX9xTsU_)7f%!i!S4#e6&;~d|OR0+ur z6gmh@2M6V-oMU%$#Z_UjXc@}uSF;H{`qVLFK~G7FV*$_kp9?i12W*x$g4D*t`nqw^ zEUa3W-Fy|_37_+3&-Ln;GkR2tAMK(g$wtQH1DujhbC<n%MxW-Z4BY1qFwOhys#~R% zvjy441KwWlLe?o+f<=dMU$FoxbiswK;0l1EI2d^2#VLh#rj=huZxF3V#F57|BrP&? zc%3Q857|MTI>vn@q(RD)fKMr>Y3Ore>Gg0%k*o#gtDP|2CtKTGfk~9@U$r&s!cc{j zhPm1=?wjd9Z9jBrNO-|0Sd6C6wve7f#O?G1GQyMo^OOG<7TAF@F%u3vi7DGxmJj@^ z<0TRj#(bb3Qf-$6FPCdVNl{KMG%-<Sv61Bd|2+u`oX1L-m<TRoQ3y86=qPj^%j9FA zLsh8FLWFS5{LoT<Kmf^MW`HCQe^j^0|0|;KF=5cQwY6EU>Og~t^8@U}aLlb+bs~}d z#)#t2?d}2GNZQAz+hs=~!z=8<&Hc&oH3*OOL?F<~b*!3XgAzwhkJ9}&o;6sBW}ZkP zh1B%r?sG#m@<@@_#b)_1G9L2+?DOPS&u_}Q><fcj3xN2LCbE3ka2s<?xnYe2cAGgu zrXkkpmL!_%pZBw$YyIL0y+KM^_9+iykmO|jdvginAGqiL?n%%&`Fd1fAqa8sta{Ys z8xShRWY91P8N5VeBy0p5+5TrLzz7Q%=km~4=^m`TAOdKS&>D^0n|grB5m&#Hu&0~f zNbs*#nW_|QMJJ56eS+W9Exn8SI4r0vS$leCZp*R#rI=H|oj_LR9`1u$aSZe2BjvN1 zA&_`gVyBydGX%4ILkBtM@?c*DyV<kC4%i@Q2kXF@V<t#FMONt6GjztAd%;4ft*hbw z0=6Q);kT%`9?W=P>Cs}Xl~)QW)6K<;Iafg+82rwJI~$lU`_wP!vW-CgtMz@tS-SC@ zg$YR>V%!-jQ#d+VF@;preg!dXkSzJng3+g>qEmsS*2(6thcbl!trT!%A=09zuX$e+ z;2wBWHjCv-zB7OdX^$I5RQ?MZ7a{|-uo5^dM?Og^PZi3|cKd0g57(I384Dv#+Y=ig z4ya3x^##8~Q&p|^UmR7pbC*Pdsq$=Eh5VmWhmsj(z+v?r$Ar7{EYbH55A;*gcCVde zqzZ9D2D@Wfc6(QtO9?<Mf$pj^QQqu!fYr$Z=7a!hVX&aTfFhRr+zBNDhh!3bAGo>8 z?(*nXR7D$;N|3X@{+)m^A<;Il9Uw(j-}#On!XC<JfhI~QD5#+j(mP?$T4%%CibFhi z1KPPkRj=Bu`nXnH4N=f+@71U5+bsGwS|QUrNehqvp1vd$v<YSceis4afvj+THb#P| z*uTR3KbuN{;6(z3IGREI@q4N^m={SQO-L#i5s?Bb{VP~KQx1rJ5ug+RPgsb6XXTz> zTcKI0>vp}b;u--2A(#-!2CP&=UBqF)QB4Ek79!L~!}mc4HC&}|b<z@)4nnXg)oqVM z%)AH#wSe<z7V^{I!lqHk1>AU=ga7M;m4JiJRR|HHz8+vxa;5@5uQb&YF&Wz9CR8J= zLPUiy{$g*$;*%IKzJo%9o}6qiXx<VFR*~V7Ap(_k-PJTh&QN|V-fj;jCVxcoT>dB| z2Id4DJ_;%cA1z?+R>J}XKvZ+~2?<$?w1s4Rlw>M02(r1rlK(RVz>8^#3JjS;RUq6D zQ9>ROSpMzs5y5(0&IQN`ieTZ4Y{B%Ih$D)5atkfqt~=4AI$5R6!D}-20W<y^hTc24 z{LY&pY9dbfM3#v_Ew>ig9P=weze;Od>M1%+ujZ&|>a6Gf1bJ}@=FXNMkXaS$@bUNa zCsKcWU*&B4E7ndHdBh(GCyQ!7ljS`inBw_uWCs9(q6lIx=kQnd#CbwM9%1$8DJC)s zyt6(hiu^pkJMdM)O6ZpN^Iu*m<|9}zv><203T{gX;K^cjNahI*$0C4kbkM(UbWr{^ zIk3!ZNMJLt1u$5blQW3hSECBk$4gC0<lstcS>69#06_#VT&M>?{DuF91YR7p>pKRa z4uP-0Q^5-%Q*bX)%&>eMan1aHWc_tqRofRejKlE&hmu2w#G$)UY3XhWK~h3W1*N;Y z8>L%PI;0J{8|m&8MDksDzt8jj;?L{7_v6`n?KS6^V~jZ`8eamuACjlo<PhXd)Fr5% zD9iT}j;sfNf%;K?5IXw?;S0}_!Ia}qNp)W_+<Gjv274B&9oY<aO5)!N>xxPEBm4@; zp$tt&=%kd$jZrobP8`IrF;tx-sr@yboRBhG&cMK@rv}#8ySHLaen`>E5D5n`EOH~^ z2yY!MgXccY_}KpE7>&xqSfvecn@-5i{rDVs_oeM3)g>PvOE$&5;(`JJiVI5EXfQ~3 zE*OwyYQ)6Hi+qkNWBVpyYD9V`4Jc9mWx}_JrN>Y@C6wh)!-*jA2E!d^o}(ZOiAi*_ z9fQ4wD#^axH7;_&76uMhY9QYa4sI?2v*A`88?wEiSvUMcc_<#e#zsDvOu*Y`m<078 z*Bg+plpXf_ZRT50sr3my8{9zINsIQ7JS$rCvfEap{;k2~*_6>ha|v_~snn=#VZv(t zBa-^evJJlX@c0j0@#rH1_$R2|po?!7O5VX2lWz`_rqMW5qInX57^!(&N5Mm?&M1o? zP%w%3O28n)k-@xQ_qYH7xkv2C!+D|iPs|2cW<W^le!fRRw1xjm2NKflHn8sd$pzi@ z<=U9<AL6>jGpZgGhsh>L{=y1C@pDKM^_<;KTm2C(i+FE*0MlS9hLXJlS2SP9`Jjjc zHw{v-Vl|qF&J7I-0*P*Z(1V<AuHE;6<hUm(hFFzyrs%xBHJFb=m}KFL#-NfREDy-O z$FCo1*j*egTP&o1Z+1Q1`t+`qyCkPYsFl0z>Ojcx#^#lJe8d(eS=4Ydc4QVGS_BIE z9IJL)D!oEN7KoNzeyP%47*V&cvTJwBT}AkcD%<pgo`Aa30nmosstRs!D2cDJrNL>N ziM_t%1x)VWxw_zk^LHD2+pG8Q*^l(0%|K@z4rP8`P_$K_{YJX-)ep_3q~RTxUIF2> zyOTc7UPdw{!gTchv}|)Unkw+F2a5wruzXF$_AHqVoB2EXN7cEW!f{|lxhQ$P2lHRQ z5u)hSp9Rs<@c7eBK_CKPT8-dtY!~S6nN58t`JuwJD{5I!F;mnNCLU4a!&hTy+B7#$ zdyVywgv-aSf=bwBc;14uhBCynL8Za-s_r8ijkNz<;Lk6GnB8U#RKpNwY`b4e<zoIP zpnITLkS6V!>xq=~x>J42IR5`l@5tx74d%4-yC#S3!Z%T-Qs{U=k0?icu%4QY{#Tlb zw+H#?z+;}>{Eq)s;0cCY&{&ST#3P#6{CEQjj<u@H<fWx(U}${Av@~25D2=%&8}+oZ zQRBL&u=m(fF+^~duTJ|k{mbTr@GsgDwj2Ga34kSt4tfB+0CfJqV;@`V;Vj=&XGY{# zM6Hjg8#tEl;JB07+u=5Z8>67gb}VGodJP6`uyEn?Z7w~Vcn;mw2Q2{t^FX{UGFG+l z4Q9|T*O$MSwO-?7#<=LNmHR~0wHkM1yn6Tlf%e-yK`3{iV*Pw?I|9cG_k_6!BcsPR zA3+nvVlXYOI+SL9LCJ!T{2Lv%HO3A<u95)&Sq4LfiuuZ@yFk4#b;|V2pZNY|Q)(%L z;48vqK~-YG9rF3;<HpCx7CL0?dQd)op73#jB5!X);@?ZPOhQhEQ!}+<LXUP~cw{8) z6;w32v^*k^c*{_#XRTImOZqhO<itZT3_w$r0l^M#0I{6f+@hD47cRpuNeVhLmCl6u z9ZteqiLzGiT$64RknDX+IVnM5Uw+-*B*gEBYNA@ZBvh{XSwoQZ{}j>yv)MgBrbf&o z$rt|*ph^irD3!%J9dKKhI!m@St1Xlz#2&mOyf7z!`ZkTm0@r*x)vP~7-74(yyM?(o zZ7HBos5<RHU35HZDMS%xT>5hiQb$vWaRK&9&!c|%0qH<qUlAW7s&XAUaGDdh0o9*g z=upg7$VQQKZwA_A%S4i~WQCn$VpM;Cs*HL`4)mtApWPR2HnC%T2RhEVHmiE9I^}6Q zXlulV{4RdRo`{25G1}1`Ud?3p72HMi*FzbP3%vlD+MC4wDHVqu8Q&ASI0_k1W3?*l zTW5j=5c}SEetrJa`Z4qKvT4Eumge1<%YRq4!5?I+gDg77|3#~uN666(2wZVz5L%ai z!ajN*g>S8{;vdvyj3a$#>&^sf6kd*{5WcYwtQjyVT3%ae6XK*f5wvPDYHBgXkh?&x z#99m*Gfv&A?`(bri=YP2;e$ubG@{XqwF02fmBwB3_wsD_^@a$y{XG{3nqEeE9MbN< z{sc)_)q_)8`0_^=$I{Id@BP{-P4BBehxI~%yIWxL!dokLNm@NL0b~KPMDdh82Eret zOX#CSx6i2&D#te)*rQ*a-}%+m5W&MhbIRC^TJ*(jl}vP(v#!fcM3A6Qnuir`4AV5{ z{$yV#if=L=IC7)jH_6ifE8O8nFCcgft?>-XG{OzCQpTv4pdypb``lHFEaS3uUqgYK zd0_h*m;QR*c~J}Jj{v~K>S%c}6LU>K-mNk2fK*e~)B=*%d?U8~7IAXX$8p~uJ$gRI zuUW1?Gsv02@h5?{oG}IS>!@%L^I4X-za|BI^5_({FLwdQR#r*l7YDmzazIOVa8VGq zNfbqr*e?g5npg|Nv-R+KOPwm0g_RP^@@UH+y*tvuG|HYl^aU(h(IKic*Bt;5`!HF3 zXKjhmbkV#h#1a;GzVvJwb8yN_W%pcBnGowP-hB{jum1O}BgtjAn=}xi{^+ugR=C^W z;%D257lGG5L7S|<Fdf}v)7MhUhqPp|1#ECvzaN3Y0G8A}hvH+1CGgo!4-X#FUiut9 zky`PZK@k-IJkzUABwKjIx92FLBH313Q3xdY-N`a7Ex4afxxW1@7Mb_Gu_=#1X`BM( zyP1pM2!Gw50AV>nsnAJ3VpITTC+>OTqPn<VQ0J``t?yXd!@i(+*Xr4c1Tuz1zGajZ zZ^s4CM1dRIe4lH1At2S99`w%smukqN!f`$U0t_{~a5EYn$UYPN&G58aDpb!3L4Ygp zi_Bya*B_8vEFMdo_~OsACJIpWED%Xc@2c+c^ws$r&oKBFY5_1!6+Y=R+<?OHQ?70P zF5cZ1)<7H=#-b3K*%Ji=#|8s!N~t_7#kCCCxSBtTmtVgLZs)cuwA-7mgj<aD#4`e? z^W^11N{~!tV#-fPzbuUfMAWS*4uzl;Ob*y3jOh4+YWb|k<xpluT?H^8xYB_43ZY@# zzdsiIdx{d@S$Tu)U%>rCy%Y<j<J*P5nNiPb0rL-ZhkTLj*MlF@J-Rj2_6@=f=|0<? z`WlcW6^i$Jtp{Jw^(0RhO>`b^jJi=v%xTEimz`f{+Vzk{yEH}jyo%A7=MwM<DO^6k zQK?sZAp5JsetGRfEOH7q@RVUbgm_Iy0M$qpg@44-<p&+p!FcW;o@S2TF`P!NayG7A zM8a?-i-Wnw4TmELdcm{_dd;h4cWuQ$48nw;wS#@?@Q`~4oeY71)jjgh2mw(gqrryf z^}mX^83#F<7I7?w;T<#xla^XS$=+Z(%0<1iA1<&buzcnRKcO?SkFp5~6NVYUV~5{< zkXaFo;x=wa0!#&wL954%Fbc$Fxiip-A%3GLncp{yG-R?I1z9hQh`qR)()Ah)Y0*q@ z)QJy1&z(pknIe$W(V3dOr<g#?+dYqcxmP{3*W?LmoNb^nRI#2;V%0!64Vv<jf{7U~ z22W6xR{-Y0=QFNtFD28PFhMUTj+xf`MKn7x+(d*6r3r6eWld%h4@*cu<U6C~hO?=R z8Upm*e4jR2OsUKX|3g255K37wiEvc)Knm$k&jEOxJ5Jy^^XIGu)q2tr+KBoR8s05J zT25q+_WkkROf@>PNGB~~rj$<7W!CM3!9|yT<*UF(DR|3Fl{xQeMv6}(R}G;7y4(%; zMpFyLHNSaGrXrB=a%v=Ps=$Sz_L~rMcUWro9sKBKK-ynkX0{9HNf>gbumL!z+?t%n zu`mr>FUwk2FU#G&Pfs}k%l%xdBRnqzl@jv}*1r<%zaRepf0x31K*uECK<2YW=BAJ( z{USALGC>DR*nW4ZZnXx0CzgO_t$8~ySh$ai`zW?j8Vd^NUje1L_H2Rk;Q}^c5?Giu zs$=9S4O61U!$Y>brB;hh0+%Z;I{LNEyx7-~CWe+Lo&ipuwEFP>7y^##%<3zxK4Qy9 z14J9GTgfuQBsSfXQOgN0aA;tWE!u~_7Ym)vAD_ZPG%viy{dNoOmOBM^PcCL{DrOqJ z+ZE|zCjO5^b06_2!N=GX96$aq;EBOQ457k7J^>q8A&<(?O#@LZ!iUrRupT{O3rKxk zpp-f;DRSBVK(za@EHZU~81;#<O*B?br18l^o_id4&M1JE89l7vm_JXH)1mkR>D3j` zb~bu(L+8dGP%VoJd0jU&GIV_p!hXbL-kV^-EhnXethGe@p*x1Un1gSQQq;q;P7;t( zxjXBA2HD9LORsAI@4K-hHhgn?b!f2=k54NT@g>|C`;DX2?L$Q|{mzO~A`hHpA%p*s z1oyCVPErge_s1?y@86NZAS2;EU10D1WHazF!7bYZaP%Yq^{c)q6Gcu+BY4hQ(JTQF zp2p^~(S9(M7c84TG#-58g`j{in25)5hh{lKZ5_D?;n5-b!a$Dv+D>|2Mu!HqyP0pW zm-LMVh_l{f@rTnI*cPO6)U~4oNN@{lzMWIBtf+>UeR7@u?QBgbh^R7LV~)RnVC?Hb z#X7^0y}iB9-Xk;oT3|y={Z_;)y#ur^Wd(Qm&1{u9W=Ccr(VhT=Fpxe3tJPwFteWh| zPWHp7EdpJ<9Ua2R;3aR>msI$hkVQy<Rr<d#llVT$PkHtJr%)Yf-XEjG`W3E42Fx<c z91Iwz_8=}$OdeDj`>93nM(Sm)C}LN1{em1Bde``V9mBjoWn{JXBBO%kQllMnO;=3J zhYZ?!n5De4JqqTw7v5@Ca$M|va7grN=K)|8yK)Z%Q|1-i?|Xm%hKb9RLL^Rr|92-4 z`MN<Oo`91E{-XC~K5)ykq{JKESEO>a))S*3ajnqH#L`G_0Sd+%d;02hbBL9FXP5|u zy$2ZWQ?+idPgPyj&2p$iLue4{UueV9YVOMkRVi?!s&kK1tN+!+3&Hm%3PYSOdf(0L zBlW*Hw)+Uy-dB@bWLzTa5c_@qa+&$<F97(=11tt;UHz%Nif}?!L|haf1Xlj4Mby*N z6TP4)gAJyVXF$pSQWl_6OOTkH3YSa?&Ej(b2+_6rnN7Y4IFI!g(pGYvwiN19)Id_# z(Hmk}4Wt6vi24EI_b7ZC-C}0}0ldz1DVsLB4R+Kme>Xk}?*0xzlDcS}gp|oco$x?Z zyho0);;OS4_kJOnrJ0|OYxR!tzs6kZ%xO^;+g|HD`&S)x9zOrOy<@c1v1I7vNngGz zJe*}fpKh`nWw!rSZB8lZ>?21~?!On{=kteli5p5sDTqTUY*|l>-~?M`Omu>bnZQ4P zVSRwSMuJ#BTK;yw?`DkPQNdh@Sa`_vy^Kq}Bv&kM3VIt`)hBK+x6y#Nt;30an5Hfx zn26~>>)Eq5xH2jhN!E4U3baOQIeg+6#jjQ!pe@aITAS4R{Adaxi`TFAl)Vt*G=B~k z7w32yhDZR`PjyZrdFIu;eTlreEb)M>0sLKNK)>PP*^++=GMmdX40<tkBWkccvvG!- zp`eKu^H$Zbr;Ff$ton-EP}$VnTUJ6~mAJpZ!j#C-)QIIfY@7@b?r38Ie}oY}7lkd; z4zK`54q=(Di{i^}4B26F8D0dfoHW9QV15}3pmt3OdoUrf5+Ke$&;+Gpbu<uBXRKB~ zG72-<?~F6^T1He`ts46O%q4;+fmZY}-LJGY%cY#SONZ}(dh6sE(;<R$my2L)F%X;X zEM#xpMZ6F)Yz6+`$<<`9<xZ4hz+pE=rP(S(yVLQda+{)_?ahppLWohdBb`nI=%BuK zK=L-@Z;vYmR}wCS8$yRpx(dyUiLN{qjMM#3FZYMJU?HO`!GDl-kY>>biV+V&aSCA; zCWPbr6MYMs?QVvneqs*PNNvHB?J}_Dkyg*EEiw+7%lQ`fr_@CetiD7%e3Z4<H-8o_ z;7kTVwAZ2wt)8Ds#m$!vaXX@tIE~6ZBs#r!AH8eNK3LSqSJ3_B?)XoO^uhtg2?c<I z{)9bVo%Lx`WpBthS??<ZKH_j9_Not&zFRZe?7eX8y#MbiPi#*Xfk$T+ffpko`t#OC z-r_$U5(`MlK;C!ZKP5!Z0Sm_$4)~G<{lpSze70IZ60e(i4Pt5$xYHI3`1re16^u|B zd-`GH8r1liR?n{|CLvd9vd%Iu;o)0-iS1K)iD?d6Ly!7QifteB2D!s7>d#O~dCWpi zRzFWc1}2C3$n0^%d9^WH`*3ZQfLMwJ0Rt-~<@r}U;`()I$0BP8@8SB=4_Y`Xdg>RA z$Auq$lRi!4&&eD6kWF}bI3pgtc?Zu?;6nR!x>zkDC4ixUMM-Nhr4kzp=1qf7&X5Dz z9OWa06#VGv+v$Cp9QdEzsiATu9zQW9gb(6Th;?bcdalfPo;*HK*j7Q^f$psbKO@6k z!`)+c+!+tBoM_l2U;ld8nhPu=AAjV^MCOQkUZ%Lp3(GEn|2jd$-KiRBn?lGb#Z^_s zC+6qloO}SdYMl1<(y{HO#&=P%$x_zA3#0KE`ZuHRf0rB^S%;49tG)c~Ut@()J~tyT zU`AN1rv1A=ZQVwn^Vc#uc<mpicj>`B5`^H<1)rxE{2>~tGD2OncWZecAp%3Z;>{tk z@nz5f6^Y{{Z8We16)bvP4WtQOmumxZuK%k7sGgJH*YcQ3?|vK>%h0aj=5buVu|~E} zrj>n|el|_(hfT<7n0BzxQZfnWG!zC@GBjT`b7A}AQenNtz{d>%OZZT_(A2%w`;Vu; zf1f1C=gHn}74hwSBT5n&f0=YL|Mx^+|8e-8n?Q_k+Lg`vDDICslPE6(4?%~D4N||a zP67Z<9q>R7;I{(quK;WT?n@K$lO$x;_}(w1h~N>Kq#z+FQjvUqvN7-pdLsW_0CK<Q zFTH@u!?ey8)C%S}tox(+m>?$ir=8`=$HTlh)6wN@N>oPx!#f6YbDCBn&%Z;z|6<l< z5JB>C)Ko?XeahOL_tk`$%fENYkili-KyX2Uj|+W8=F4sRb2^oj76}_N;!<U-9MW5g zvM~*?=a_C`7w8Gq0G#5$2QEpYW|zv;WGOi)V2!L^yJ4}5T?G9`{R`;S&wy^*(D?F1 zXX-(X7;qfeOiD{R8q)$I7}eLCsGmBs^9Pe-C0^{d%zcso(c=nkjCW#~S-$qC&_8pZ zX)=J|g!}wWOTXOxOZJ_P@|nVoaS^)%WVpnVsNIs-NF9c67=hGN$hRQu>ao`Sxkg@K z1!Hasj-0%;=S&xIpCmU0|0;pUT!HtH&A0o9_NXObzM%28xKl7;kBb;M$~EbgmLHvB zQbZKFz{+@A!LH$}P14dbU<lfnUE=)>gp)PEZ@lWf5am=~5s?24EZTuPygX898VDFa znA~S9ge-mUqG@-BtI?SeGf+RBu3!$618;ZVBr)xOAAtM)2Ot23$qG6j=!Z;z6q1QY zCkM~b$AJ27Ng<h0bU$V15|JLpR!ssV<`{@q6L?DtNUiAh4)h%z9leM2O6An{7hRk+ z3DssjE5)G+zu;ndc9zlBfA0(X{#eIGMoMw9ikJ0+X@W{uxck4r?AKP?*DFRXZjM4q z<hzQ7a62?mjm(S7@7$AEvb1m(bb){eV*%Gsr_#^J)=U{6@>l<86}%%-;<ihW`dTL| z{r-PQlIT84q&<B{nJ)0*XO$E!`solrL4i!k5OIVcF7VSm^#tyc4LG=L)x3<4RbA9_ z0Kp8+jDlN=N<84<>$nM761uO&6oMa8jOq#m`LzS|U!+rEXn~!=?mvExdT&nI0w!bb zWQ|-I?5|rpm)`*v1>&iMU<qGH{o8r#4SH&r6cjuFt>4F*dnGkm5&;}`#?PXhZc;H% z?AzrO^xHza#Od&f?qecA^aA(4`Wn=8do*3vOu#+(LE$6c=fPf3iQ+=xKB&HyH7*a3 zL&cbGul<SQn4dG~f#S+AV~n;YuI=Xh<th1r^hGQI`Xl5Neg7{LaZleF&NjPN54!z6 z9?6yM#kvCS3~LI2=L*3$t{#L%x;MElCq}b!S@-7G-j19M9L5QtX%I2@=llCb87@W; z3sQ;O9w7ps`2H6nCJ{@H(6!D$%<YTgRcfSznQBIQAm2+h5&-ND7O~b<ns$AZbP+@* zg~P>wwJN)j68;JR$ET-*cvPOhaVhxi+J$Sa#u%b;zMFC|pyGj%Qh7kAPNAiS2=q3K z1C`|U=8*k(kvh;%7{BHVd^84pYvR4(_p2b7G|?Fj;MuaY(#}1<1wIFPJdJMI=mpQz zd-endsYFGtphe)ygQ;D))JQ=LdM|u=B>3XMk;lQnDyDlkhN1908l6&wiC-CtuM}ME zXX4yf=V&+|9T%6H7GRHSPpFu0Ul>pmRW$<_10NV*bNU_F5@93bE#i~q28sykS^{Pb zx&Wuuzo(m@&3fXRFsNUh-}e^%ci6tHHs1LJji(yD9w;=U`m_JI*Ckh=6-%63WX33` zU4iH@a$2Wn@sAG?vz2b&g>?fH;pp<WV9BK$aP)ZHIJn{n23#avK8G!}4|0~yT7YTm zch`gXn%Qw$G3%6*djkKc;G>lWP;Nj_^_DPs*dpZ(bfQopN0sQK%9ws6?7CG_uSG6l z&u>9W8v{Z@zauD575F7`=gAsAtE3CoxSd&7x6=Ll>i(sIc4cU%Jc$2W4CNZi|7C}E z_WQ39_?{cn8w+KSKfVTv;Djz9c)0!A!EkNMb|2)87jI^3sHL8qYc{$Z)0~0E+ceRB zlQMCqe*8M9(r}q5CRjq#@@L^gDZ^hi_|fU<b1&R%WsFc_&Wy__ML<h3l?iVWz;?iQ z`3XNLv@LOb;j44SyvSICy=eut@qqOIo2f#Wp>uT9fgTZ`v19H3{caamI7p=cI3|K_ z`&PKn#c>za^UL4ck_n2w2zWY7DMNUMW0aE*2~c*A(j{eV7D0VqO{-}$Q7ru}7{^(V z!7qHN`5{jnmx)A^{VM9;iwpiT&cJe97f_y~uayx=b;+bYh4GP><q7)*c0>kEzF2Iq zr}cFh_mf)!E}nny;(y`hJ{Q6K1ElzDLY*iK)$&{ai=kpK?qg`9^#qIG&xqWm?8l}* zBcgu95kqqbeSsD>V|6`IVU&4K2$h-2yxs(`uZs6GYO0{+FrrYhGocQEwGDye`PUM- z2lv|$U~9EWpfVl-+Ly!RYIG!+6c6~@)ZO;SC~Yn9IZ2pV9?E9vTWp6$U|cvt934{a zGP^!BQpjLcb@?c7@Gq4%qXDFnS3>wRQjr-of-WZh|1u0>Qupr@PaL}xjC~^zZU?>C zx~~Dx{v8J4dWNc-mk*q1PU89wjfLd*rA6WK^cNG!ovDh<vF&fa=g8R1dJ~wbX~>1% zFa=V>#f~z8g)I;${W*iwAviSQh2Z~|GEil^0K69L0KLYnJI41RrLdfQ99=eWQ_sdO zz`9R+7&Etu-xEM-0(_)8qTsfp_c^o~8`=3j@wdF$G#B~zzMH`xM)`dA-;1IUlJE(Y zD*?qTwmJt2fa5esksZJk@JW(@MYDS_U`BYEIur!<5fBjuW}aA$1}trks2e-o+)slK zAiX9sY<w>rYZ>K8e@F@8k~FNdP1SY1uP^mtH_&mEpeQJ~-L5GYHoi%;5XuhkLm+`T zaxV)}7To;*R82=LP%(+~+kopjTZdLQY0)U-fv$qVA;r)COQwh=28f}o7|p9a5Njpa z+Q5v41fY+>*Fi>>Vubkm`rhYzH{k3hL%qcjnem>#y}3gFo}2`hr)yLgwm3`*uZY%I z%V<{^rZ4rW(yhSS(efq^O+mqx==%P<dxQZy?hIgrDgF$AWSofkz*5q>(d(uOqc`{T z{)OJV*l@*_{{^Henx(M&Fl1A&PsDH!q}s#9?!yqE-$sC+O~M$!CB>7oGi>$S9L%i0 z_{n$n#K(qEFr7ygh_`&iuy~D>6t|rAy(zM@SwdvsCQ<!*Wd{b4QND4be0078LYacU zX8g>>g3nj<clPYQhn@HR99iZi`GDYJK|~HphTnj|bT3ySI`6e+ldZgL@S<E;AyIU6 z-Ceh(f2YOxs9GHR%nkk>_;<ehm)E&Tc}t!T?oEP_^V_Z!;v`U0;@kkp<^VJoU~=W0 zC{q7sD*u@nH76Jg3tL=@ebO(a?On@R5=PjX)!HfeT~;8qxG@JTQQvP9I+dFPLw<oF zKoa<0iiN$dFC5Nxv_d7`1#5igff?7>ElX5$e*tsqpUT<Uec|Cg1hP)wx|k#$^xoF0 z3k5DvHoyN!Q#@p4iMLmh-Le&P#<~gr&YY9zJ{e`-z}V$v#i28xh!7xZi@64&&gy<5 zhpB%E7$Kd2@gj~*m*?w;xMN!=0CN)H>98wdP`sWvdQ9`7jPxq=K8xFY5V57^r!|&H z0#MakaBY9GgiH&YbV94a@GQ5Q_v;G0oS`AKNO!@AidwM}cM$Ig7*)s()^KHG#u-)8 z)V#Z*sdTykNXPTr4`8rER?CqJ9WL$`5C<WC@D{WJa~Q^rCa|n(dwwPe$AxV)q8w9s zW207z_uS2V#Xu?v<G60wH{VvF$C6OM#fQdf?1^DvB@p1Ei{rv8aZ#jjr4+=}q&nLn z1cXvt$gu}@p(u5`cdfjCT0sk)x95Yyd3VOav=0mm8HX9EBV~S*Nde4}oKN}X^_mpd zt5>SNrEaZMS5@J{a1fvFI%D2$&*&l-$e^B@1q<{dZ*Wy9sSod!;9#y_axr`&-+E<r z(6@eC#T@2g7GH16Nv-5TJ(fu8t-B^(8>UI(id85!gRG;9v`j~p$7J1w-fHpQp02Z4 zxV=V<VHe}|zDa>lW)(k7jFUi1<<gimIw36nWsv47y|7TP`E!#@pZwjvV|MHDy4pyo z<4<TN+Yve#yIg?{*HJ1yXZ(Jm+Xz>4AttU)hdjCDUqg6oAJlH2T`nDy(n;o%Q_Go` zd-XD9&t$|+dbLiVxnwe99~p|U>2J?i6DMJC1?j~93@~Xn(AD7r95#EzAE87S6Uuxh z*_2scA^)D4=I1YEk95yULRxik#Jhk0z{GWYD<b+bp``15BaySGbmGfsu?DkVZL+Jd z<3~MnltW3oQeN`2d?j3%>TCY*<3x7fDZGM76{&_B^-x;fD2@i4%HQQZTCX>G_jELp zm2Kwnv!Zl}ZLTdgbhKwFA+D!6R$I?i`lZ!qQ_V784#|STa?|rCS4_R(%jpVRRDXw` zmE)Nt=Do|O(At@^fc+FY_>MoOTl->=;2Grr%%EB$lA|-{y?qf6N5iGmSPuu8#}U4( zdB6anf|}a?XbPRfiEa(y31(9Yt#?VDwU*(O&cohKomE*%iP1!-s+TvqaY<A>85ALi zcep=4h5g;<q)^zOET=Q3`|P9igV!iP=e0H>(rS(E<!NjowRs)HYrx~7wdx-<wCM4U z*v5<q&GJpjcW18*scs@Gq7T@=WNoOU7;)Ix*>IiN)P}D)3u@KaD9$%f0@^6tt#Qr4 zlPyk=yOXSyp>Q`NX9b(Au9p5th(Lnuf|l%J3OVM4<@)Fw4$fGpa4?HbxyOs^MO=Hn z7|muWS=rT2OwNF${oW631h*7q!@g{dssW-&nm|v+^oxZspr~1ITPZ2^SB9m>@KF?x zwRzte8wg^V0e-9F^}J<fCveI@R~_tnL7Ogx$HVz+FKkQI5y0t~f_4^hnv;<6v}08) zD=VuPEpCrJVn*8D{;J!5T7BP037oJOPm?hTVOEGdU++d#v-oY=U!hd<EJu?O)yB|B zmei&W@~ZN^Z~W$URRI)cStG-Jy?M-39IIoByqGElRXnV-29B8@l0S*E@_p=Gmf*^) z;-01_VK$ZvqBONaE-1`<HNWFHUAKv(BDk-az+sr87B-5a#D#gfCWaQl|MrNb)+0mQ z6^_K*1W}Nh>M=Xxk{M1})kdOw{(;b$OTOtCFJqwXrB-+KlnD9<_2&`&ZW_zUpA-Jj z$d88`DI6ooJ;OIm7#UNF`I<GGP~P0=Kc!8%Y<wba{(kdL@=vkw(+A?q{+c)B4}Egz zBJ8pf`5nxaIW^c_>yxx7{ZvrJ++IEwxJ_Iff$Ljz;E_{wh0|Od=PG%Z*R-qp3!>9) ztB6VY+#vYLNm$X-Fm!(sp3<h!<d~pNHwu}nFKWsBbjh-EYCql}e!YT@wW4$rx(65I z5ulGjB5%o8gH73HEtEHley7PA?V;wH{3)23D2Y+Y`mPMRUPFM5UHic5HGWGk-iz<v z+Qf&6FDJ-C@(9Mf-<C0{^S$rdo{408n(`vbQyk&I@T}NKV=FLFq_Sv5-)<>8gWf-U zQ>o(-BR%QHTsA>+F)?XgK?GXm(#Uy{9$KY4EkXa@`^Lkxm8L$|6M6E#EFAg^-xT;a zK7>)kiT8LB(WiQ7)U7b*>d8?TKC|&)R&Fx&Qf9&E&$2J{UQT*BJC#;&uJNnNhxSK_ zQ7*=1Y}4JTKMwz;3hHh32DFkxWjeAaFhf6L&FNBe=*WvYK{mDLZ4zURA~llLdg;^k zEvZ+`z1G8t9juujPN#YgSg<|sUOqmmcz|$()HMe@#C|$w_rL*i{EQlgAXIZJ&HAQL zqxmO-ckl~Undv%q{>|y*FTjkyH4OLVZe!f)Dg@j^uq$vb>Ea2RTuKFkE$LYRy>{$C zJ=ReJYh=xU57K{oMYqtX?-wt@Ejf1g>hH=fN=!VPg=PWZdrVw9U9``A76uLLEg3;0 zb)5J-d8={#tTQ?3#(8&=eLVU$1W(djlI-HCjo43I|2?V0Nu_UDzT1VmO?}G|iu5iU zoMTm6EriC@q_1^#e`Bq_t3Wx-As?LPji1C4&PR)9uin}<CDM<fqHpvNAiq4X;3Y)y z;Q6_O)m4YR%XN^bp7PZN<!#efk@By_0<SdNE@-KdV??D#L@yS8kl*}T9r?3|o1Dk0 z%zx3B*uOlbMkKRyi2ZYeOC?>1R$CC0S1exFV^z!82iHE~H#}jX&BW>TV&4bZ0F+m8 zKAGh?8|m9LYk!#qMWsd8)@sqbQfteuwJ#7FUP;dmi`_gdq$g_K-(Gq>ME2fLW;xXE z=~<f17!D2&BN^{?w=v2rox(})AB~+tg2>XXn)LEB`MJLL6_$w~+Ca~zgJ?t7^T4#N zoc*jvqD(w;EZtbA{BnAY>%6-cxSZBcH%_}Ed9L4xd&Ii-6oj9lU+$7-nT<?Zt7vaO z|I7TKtL3+O#;XKLN-wXY$63uLA6e<%C7lLo>Lb{&<wHZKi8B2(^p^<;e>6!e2(G&j zVqUs4v(<a?dqt?0&=uL*a8Fr7I!K1zt2|7WU4)E~SM+W_$3<HA`&5$ft>jbS9L(WF z@P*Opz+pHr`*1hK^++GTbZD{f!s3Wl9jX`^D%B96znRW8xET#jJi@>B3pV5D)16_% z#Q&a|IjH?g=s46K5<>WHsf-hvS*@HJr$dk@a5%_lHp22by6@YkHogm=+%wWc`T!Qq z%=e}fGUQjmm*t{ie?+3^Z8=ofdDml@bQucW0<1d5V%Mu~w+~+Ye47y5F%|zbNI%DF zB0snld{&YFGJs&hGN@LCl(44^-S=^mJ1CQmp;CEyc}sxn`3YP<Q7=CwZS}gV7}{kY z-Ie(|a9E{2dGpbCXjV}@bN;LI9d-7#`CMyZUR%Odh2GCH(O*CvMht=A|Gh{(*KY{I z_#xBjUa?=Dd7X(}5d8MG0d*3L48Qt$*`9&41$>xkUj$a<`U+8mcVg0>;nkc47&cgb z^_$Dgkq*Dbt;(*V#tz^+G8*=o2^fUczwF)PD#{XAkKhz_V@RCQ8RR;%Whb+kff81k z_ox0L!WNj_?))qDLp^SpBTI>%;v)VNC9TNS_-5y;hsE&>S=EREcoO#>lTf^lOrFv= zJFtiMA--%|#87gnSjm%gyKQr2xUw@bJ24I>?QfGGn$abF{;2wa=lfe5Vf<@J>mJ`U zm{m*+DH8__48#2iSKCRx;&_>V+Ag_F|C3^rP?Z9a*5JW~;wmSe`v2Lo-2G(HcD&Ya zYAWygO|xyYa&uecsk6)hys6bNVS}-e=Qcj^r1fELlF%{#pPb}R8=xsP^BYq4p613z zoY4aeXnir7+7o2ookx(Dt`(xjh94-cR)-%Tk=x~wyd!NjYGDj|gl^4Ayv(Q=W6ZlN z(=+<?-G1lGDV%&8VsaGE=N#b<+<H~T3y*%T&kZIjDT>m6Etyz93Av^qHbR;#Q!mLM z342dFrI<JT)=KD?nCC>YYF5^|^UY*(&nWW?BKPJqw;VAO{hdc#d?A#{Gww$nzj(PX zBT*VE9fkPbIdRl0FBQd>uXS`^^1a3Js-!*;9vp{ZG&9MNvoaJ8kcZ^e7z-a#R5Ym{ zSx%>K;H%psnQ~32sSi3ndB2X#TCwUMrokEYfWF&i%$1-xx+zQ3=FRrNWtsh2{zmJc zoG5!-c9hII_m%q0C0X*g4%PFDV7jY(;Tr*w*Okb8!~#fhx_-u7pGipAhIHkB=3j-K ze4bWTQEtL4`0IMRR)QmDZPN&3)>tYXZy)2l`D0z-7gsKC5HsYj{nQMaQ0wdJ)Kt4y z^jQLnBI>9sTTME*oCnt14w`lmo2Z!O3eHq}_}V4mn4ZCWM?!q}c>?hLHvJhQS6o__ z=tb>u-U=bn(OtjZwRsL}^qL+s91Z{yf3*UV6s6_Nv|lmi)BM1bYqSj@sK;7YHP^RC zI_#^HcuPQtM)QWExL{~%4U6+aE)#(xD&<_L4Cr?v!L7H#*gzM>17r&}Uh{t4ucM3A zXtd0`h)3+1+E)}!I;)4eqUoQg&M+yO6Cat4w_Ntz{mNEqT*sKd^R_~m{KX03&?D#m zp?K}hO}TQ;L>7}scgn&@f<@!M5MJ|A^m3zBi8EDwP$*yqb{$}E%B7BbL2D<=YP|09 zDku$>;>#kbOrO}r3w13t{;iog|02P2U21!9Q%wHhk{w$Z)s0uLPoB3HhREk9Wj_{f zn3)X9@i2&(ZH<eLr7j=(5U>+J{2UjX^C4o1#jzRnP+FC$>j9yOxM5UN{><B<-t5c% zkaaCXX^cTy#U@Qb^PU3kA$Oz99OEaY>kQIKr}S`7b?(SGACX-}@iTW}@{tD`uGh^; zMn(c1s_!)k54$d0qjFiF{lcxtN&K`BYt=~p`wLIH6y8s598FG*ucw28MeWF*Fhx9a zu39&YD)%v88%(R--#v#}Dh9kUA1`BNe0DR7yDsg%P}(4-R1_RY6MEe3R@={@$A!>y z=hfJH4}uK~K6)Jg^SOAVEV)o#cI;YXzLqO|$76F1Ps)nXkUWjHgh7<~-fv@z&$;zU zzqicuZzTSbm&9I+6M2r{KE>dB_(%BBgVdgGg*m^6WryDb1X%6$$}U~rtk`LmYwCZb zg%rE`KR!i~aDhI~+tH$8ZuIKmA3gQ|U7~3<?kip1FCMu+-9Nz=1|Pbv<Eupo)ZV~7 z^&;Zf_7rt@Y)Yy7g{`#Ytgg3Kx?LROF&N3cOWour2Ol<=D{$b5$aW8{Z&B?2Dj8iB z)=_!Z5iJ;ym$_$jV|KR_#yv5sGWUFyA=rXPwL+U!F$Cu5Cx-EEoM`S`LHfhTHN@@1 zvat!rgm=$QvwP5Z-7JemFdfFvb!H!kkd&r{D4@!I&)}0knt8<(UYmj(Ng$EYg2$?K z)n-kpVUIjCDWvRlCM!KfW2jO4KGE3GX|-6L+RG0IZ4+H2knf1~AJPK;L$~h_ILn() z6voR9u5^mmznhOC(*vSBHl5s~S<k#7^TVJ(kx|?2vscgBSC1bl+<B74y#C~6>mdei z(&>Qr)tNifRbK<nS<-b`Ujrx?h=tjt+>@+TpN~xP%mAtZO?T{3&C>-J+6(fgzo&c% z)x!@%B2VSGSXg?S5$oJHFa0kQl2or03vbNFy?>r;0~wkEl~4P#21;dRWn1Ea+HDN# zttNJWO2_T<iN81qhSky3W1g5a*YEEZ!wLq>C`GQzG*nR7v!xhBBrMY~x9yRz|J=}I zAzWyJ!_eRtL5A@CSo58!ZKbN!Pv$%e-+hOq-@>0i78FREP+SsQNU8BbX-bVx)bTZ- z%dl^+&|kg~c1dmN6enxqUQ!U|Z*5L1kfFb-Yk2U!h!_7G=^2j!1(N*3?*Z(X<9(Vt zaz11&U;6nr-bGmrkR*Pm?4qPqd0>ky@<=r*qb)Pt(uF={c?y+w&3w@FF!@=+O7@Uf z>$CTXlW7j9SXIwHE2j3Srd$4PN}75}>8n@p=7hzm?C>}Usqwb)_Oq~In`zvE0kIYZ zOCCS_nNy2$i(vm{{QHwoPs6_x>1B$nvsxD4Ye=*-OVebBT$OaIcz9u&pqpRsp^v8L z4&#ovfWu$A9RKIO6U8rm->BT}c#mSCY>b+ou9=|<B}l1npzpUodLEjGEB8&fzz8Gp z^EZ{EXYRCOf^`u>tfVhn4SXJzH&TSx2Q23mZ!Uckz*j3UBd4k2nZtZgSLrI=i>d0E zYM5`et#Ed<%2IpG(dvIC{85`USG*AF?vzTwPFM>yjO0IUe67XNt+{CZ$gJ^A>|9z= zQ%~rnzk;<#aoXDHb`gw<VypC{^wjo<^_RWg!+Ozos%my=4ZTW`a0KUMrHEJQvIFPv z#F^!~*4IX{vT11FCf9(j?I9aw(RvSC+~}vX*E;QID5_|N<0G6jc6o?I3R<({H}Rsk zeSfnyOD7Z!rKfVU&-+>od~(t~JjAoS@}DFlo%sB2xxn`M4Lf@E#&$hLxyG|~{|9-d zGG+%0Aua|r_B99g^)8a!zBuDhr=%n>J*WX{Tr&3#cL<V3#G!9lICD!jR1ccdmvX{6 zIsurXNK3fI^$SS3P<)()?}zf@$|tYfZ2>gdP!&J@!*ejVv^LWG1`UhE*wEf9A2j9p zBqi@=F?#EM8LgqRc^lI|MAdXFKxR2!gj>V*4M)eokuV5{>fjmW@eXI^Aoi16(!N4a zsfPpdodWeqP?9QDC8<R09TIi`Qn$Al?X@mjO6+$|-V}4*9xkUvo<xU3Ec<nPp;l%c z1aHsYm&~UJ(xE)`vCpCr=#Utvn6L-|vLcHzOlU%-tb+c>eXME!NUl`7+s)}$p}He0 zU7a0bnUcTd<Q=&UVnT)W6BMtD@b>@YH&uNjmn*)STOQt=vyyGn5y2R2ATqj^OXkrl zV|bmyl6j%V)#`#x>t<TlqFVyxf1k*`ZgEQYYFl_og@))|T>m*+_4#{85}fNeWHvd) z%Gi_AYA71Kgi=J1tog69IDO=F1=HD;HUATni8t(W99WmHo|i;7(cfJ?%zO0?B4VJJ zD5eQL4Mnl?6-(YlcVocb(M9<C$6{IV7?4ipkWYp{NC*-RkmM#f;vm&Z*xF)eHl-l9 zJhf1hskj-N5p~o2w5f*cLK_nni^_E+mUa@xdFuW+qh@PLoy+9n_fwSkP)D?y-v*|- zE#YsBKluKH$Ad;Iww4kc1x`VWE}tj9(X+A|q^Uh&r{aaieXKDOczUm&ZF-zs4sVXU zYya@#(+k)iQ9k$$WfLhkuKsmztF3X&eyyBa@wXD$%Z;)}LgmZs1|Cdu!77UpUmmr2 zPVjKV=jP8@Q&cEFPEh7Iq^pW#bN+%+l|%7Bn>!xsLfZ*v{E3MOs%An*C4(Q?W;0pL zrXhl9(mq$AjK@$_U+w0S-=Ol%#Vclnlx``BOaFN;KN*$EFO?4uvp)RUIgcBl9@%Tr z{AjsR<NvtLD0V~x{V9f{a{_`!789-H;*0)!_^>RJ*;_P%M>^*`zMkSddM`tao}x<2 z<s}jnv|4q#BjtHdC%cMn{H9Kf#ejB~=nrBdL`jgC#Y=f|2ZGgLR!hz{OGap77zxM8 z0UMLO`N@W1pksO?>auH|@%`!wu=SV#F8TcDstZ<c!&KEC7_fBXqAR(5_X_)3tFHlt z#p+Pq+erSdIKK_Zm|kkRdY3{UHk2NW+{hu{R$C05P)Sa;i9OJZ%1&l+6WT$ekjeFY z`TpOn0QcbPBZk4<F4+Yya`&Dm`n64_g<R|PonvhV*I!T5eqjkS;vO~L(|8=dEJ#N7 zwh}|?L>i+x-^-jN@lm@zVILH#fgg(TqB4iK5A5B3_=Ut#XNc3LIcaOGcqzG>;u%ti zL|LT!M?z`M;7Zk4P^MzdGQTIz3xQ3JgKKrPrG8m)E<CpE$xq%lzc3>|J;E4ORaNQK zcFQcpweO2>W1`7fOHA<fyuynWXXWzFhA?TA#_Z!V-HCTRjN=w&MQOAB73L|QDmQ?L zkyzzR`_wNjE1hd5|CSXlEfZxqt>DFZG&wFVT4lCW<-?noYK#bm9p%zoZ!H;Tj1sc^ zpIHF&C$I7-kb2%L7<bo+kfpx;+4?^0rB}l<<5$)Ulcm3c2w8Pr-F(!#IKIlCZt!}5 zLC794rcx16T&UT(U6>XXre#fQG;%HMI`{WhT0^DQ)CpCD(Uq*xM}AxR@s5M#CgJz< zli3N1-fvPtY!LV>O?Pt^1BV)sh~5SdfnyGl`cB~)iqGF#Z(27Q*IejhIZIfBCp(4? z>IGdcAD>#hW;B`N{KRd(b2aUSAT#({Be^WRmWWjAHrG1eX8b#3`NDWG_;-`(VGQ|B z<cw<yr8MrCTC*8$1c@jX*iM}7HO@2IqL<+LO^hHi5{s1z7G86X`SeY}N_(qF$YP@L z4b!^?zmUif2@5weymLkx0eEERkFZ>q4kjs$ZC!F+6KIQaScJpgT*E_o<{mj5+84R! z)P`vl#?%Dtx>&etV?QIX1IRru1g~~0Y`uN2OBa1>A>DBev|<=erSrZC;|_VUr+Kcu z@u?I8^dsCwb{bZXzI751<~{az2ocL46a7WphJQ5{ha1aDl|yS9>*9kp$W<ownT9DL z_)>YgXMJk_=pfjLx>$)lBJ*5uu+%W_L)f6BYVN`e$8U-17Eu%?ZbQedms(Bq3x?~> z-D4A@)7u}CW>_j_b;N1KsWz&vqcYk*b7fmxZau3`NoF)E4>%4KV_;0f-mT{mKYc-m zVVBXvAjX2`cXJg7|LK~?RqxIe^DL<$Z-<5|&mKXIjQ({cHsfRGCA3lIm;Q?!O{=vb z;!wHC^#<;whgT<Eej5_=LTUpq_(U26o_}CO=f3!xsx{z}fVknVX!kH*VT@QP_<Z%p z80XLQ)LcCMx*G2GngD~hI03s}_lBHrk;z^m8S~y8+ehEud1kh=&FM3=aGfkfCk^cv zPJ5~=C)D0Vj_{Ojrp=yW8a7sguQR>V{5#1Txky4p;UR>Bs%dSVpV=$V-TgL#OZn&y z{-S)vKc``itd@Ae=PpAR*Erq;t50Iq=1*FUS!!tcz7#3w*K5v5Yjr1TyI6<0JmRV} z=nxg0utp$t)F>C4lkmJ6E%otPap_x;jUG-aN$Nb`XMnk;Kx(v|siNh$vYjlQxeI)n z#4xx2tNu}YE`G4L@^I)3aFVT1Wzc&opQ~lu`JmqRn$PXzc43?pT?0G0I`BQ4nq%hQ zpp!M64hnHw^rs;5Q&LDCMBWvzkIjZ_I|fL|J-9pk7l``LY`z>WA2404G{9khiJh_T z{>aJ{A5>#$#>u9>qwCQpa-lsEXGrLmlz<B|`HKfNKfH)pR9Tr!+!}3UUAS|?>F{&5 z_u9t`iH&3^1RK80>{RQi+Kl`rO0-R<&dXASy&$cZZ?SVQlcnSPIAzBeu+{U7MaPA6 zSyWh_&qkQ>%JqC|=U9w!5=(uq#Gp>*8%VnS`9+f@b(6zRh*|kXAH$LV5eWn(Ac%)2 zHaY0z@svTR)Bb@}M*|5j>WwE+{ks=|j8qgpjhWt(a@3P%2_~+~ft#j?RYd}4cj;cr zXZ*0?Bgk1+=KHbu*Cc)XPJI{p;>g?<T-71AE;lDvNdA1KBtmDi4rL^D5LKu)Cemj) z2A{8MyYIN1R$jhnFcYvIFAZbW<CDpc@1+j&X3WD2Q3m@%=W~XR5Bi-OSGb>*x2!*` zX;@)NU?B>&JkTn*!K)ra|A-5-Lxio$`#h+mo&2olN+?upB%%1wOUX+FBSa(bM5C?O z*={M8MjYJH+s!3?w<^(1-%PJ7$_!S<pWfnNHtyLjQnrt<4vL&vKK|aXaA~R`nN74z z>20#)<sa0lIr`KJ(yCvvB!+b7&>a581y0v^J)V50A04}D)D`yl<+M&%u4&;xk$MXx zjA+nb=4?pz7Gj^k89A%-GN8H)Hdnk%Cv?WN6xV_?>&2Dk_&RT|qqM$oC0~8D(s5H1 z!n&+Pk0cKlNZ%(RN++JD+VTY<C#0DhDkQIvF!s5m<^lTF`zeZx^Wa1|vqq$j=&h|6 zY2V6B+<x!)Vld+Oo4$=io3i=d6^d1?vy}P(5hyEb!T4%wBXY|_R<?A$8T<3zTtI`s zc}{G-n7qS*jBdqSC77&uoFIFUx!H2zyCmc9n3CLgB|o~CKA~>2@bY5)=+%-sMEjb% z{I}5b^yJWP6??yuSrqfB^HvZg&b)HPj@%)NMA##ty0t`XF|KZ^=f#S%_KIK1-tYR& zI5prrpP?j6CUb{KrR(<=lCWCUTpMzv2UlkH_zwj=sFo*sBS1ZDjY8o#TYnfb?;fX{ zQKjbPYemKY`B|)4;`{K=g1;N__<FX^$1eTG`hw=D5!x=3(@Bavx|W{^mU1pij|NVT zuQik_IkfWo)8ebLRFM?krKpNAXpuO9#%^54mQORra}?8e;CV;=4ui~@%QLT0m#@}s zNMsvRlElB%D&_ZXc^EzAYcAq=g>Ckn#_?OzV<)c{Cyxc|4sEXvEbK)m`_kDIUdEkX zjXBiumuSCnZ=~)w5RocO-CZ2<GplV^JoqayqCow3kr+x>K)+neP0RhZb9cJYhVz&I z8ws3WrC&(Ki`+#s$bS<k5Yo37k>yd@_Y&JO%ex=nmXf;cjWEXM;Lp)E(Bq|!n8-(d zG6*|Q7s~Ny#QW$;!a37T$GI|vBbz)ugxeIvXJ`Ab=y1IP-Eiw%pMg!t+$ZFgWSEMq ziSqI<?}|5OB<(u3igvKP-5yNYHtu*OoHOVl0zEJWH7XC;oAgh%V&mNwC^j5{*&JV0 z<V^FRX!yn`51IY*q&61VVtYIPI3P*&?(IY%#x0f2(hw@b*=ULYSF0p<>BycMe!{s$ z+&c2{Q_ae6^muMn+R<CDxZqEd8l(Dn*9dPeWa{PLVfHfdN@jk#%xFjFDbyr<E+nlt z`A9!oM9`8AG?85$^veWDVo{TAEzI%|;aSTCXEw*(4{(fU_c&wfl?WXg+Aswj8&VOv zK8B{yw=kB_)(83y>+vNqm2^FA0^iopq`r+bUp9Df2pl8T;c3o(@jy9f+%znmNezMI zmn<haIWI>g4XBkGd%5iraD7ulEkQ}@QxfvINN+Pf|9Z;pHR_;mzpiDeb_a25C#<7y zj$M;&m*kpm8I$K4#8T`kQ~8Yz-y5#Pn#JM$7GW)p&nI#dM#_jGs{6USgR1FN3@I^2 zoVB7WfIUUv=8f=ezv6Ty;{#%Y_oSe&CE7Z%j~Yj$w9~4i&nMXn|Bo$T8&!U+s^WAR zmWRE2uf_U%{})<e(m<EFPu{?}^6SUA4x6#0W$|@Ch;qx`{t#G_m=g#$Z1)*zYDW>8 zmYz{&VGJBKa6i&T3dp}Qx{dcfTg^vF9An%xM9RH==&b(G*#7T0r-)Bz-ZXYMM4akO z2Qnu#dE>L0=|*5$z$rH2R>p0+#apERB<#|}5D)XqqJ=r#$XoeN)n^|5Dh5<PiH+EE zd3udI*Q_kxqZ?t2if})PYtNZWhjA-Zj7lP4V%B_INxz|^az?0W@QB&^cZ^PVRp_VB z{)RY4|A>CJFQ&Atuyxu^YdN09pu%B*6?n4w_~*Cj3WD!C+Ilo~wuZhar^L&t%kNeO zzy4bFJGIV{TZS+h=8&}5)Ak@giY&dLEY!XT@RUa@&U}yWLPKo(%CCI;L~ub4r;!e8 zYl4b*qdD5_EVY5A$gmz)CeoF3LZ!FjG+I|8GG7K0@t7O^>vm+5?T;anzdJ89nT#l( z>U*<`poEW(u{~RP^_*)XKlx}a=4mYHOQKcAXz_ua{A~diRUYx4kKRSDQPDnK(Q;oY z*LLhFV_N<4_?r@{jCxCy4bwhOuIcV59PdP$99z~KV)W=4bjV3tlDpRC7f`k*vG2OJ zPdxd(y?|!KW)K9)?_C{qa$eoo<&a$v=KkHx;m7~>Pkv?mK&vda@z6O1$+NdS79K~W zgP#{+%4Cl>(w-+!X3=l4lfJGhF8=24VzJ-cz)iD2@zm|SZ`!NgO(QLm{!9}^<d-s6 zh5P8!^*CGW*UY{d4Na=qQ?IV023}m9zK?LR=UYg-;pX{93n%?VJheDVH19qq8U1H; za*&L9Fjp|%(C4bs{2STcOsdbPU!nn%Zw_R_iHNCH**g00e&9Zm{1SB|uC=YkhMwPe z_d<M+^o}jQBb03}Gm}1zajLSHN+2?Dd#2&_l*(S{qTf3r&rmc}tj<|>p^I{AEN<8E zmF2>qY=d8{YBBNhh#MrM=`A&iD1(E*ChtQI+h0}anS(}QJ=LPpyPw{5HaZrM?ut^0 zjD_2&gm$N1{V<DBouX-^iRw3GdXne6YI$EB_MYyP)h`G}P2Vk;xn>&Jb)cM&crpPg z$%Zcrzx2Z)`)7CGzs$_cZ3Qk|(GTS=0nPq5_>0pWdLVwbFPMn<5SxsT|3F+j8#Go) z*#zudc#pJKF;a<Fp6=$l+yr^2n7fK$_-Mj>W4vFachO}L*MIDT7HrX1HDfv^;xdiN z$&^cwl$|+<!YIS@vMm)=uzzQ76Ho?bw%(z#61N6(uQIOwKV-cFcU=wGwHw=LY}<BY zr%7WrXzVmrW81dTc*nMF+sTgo?dSc*d&W8A{D!sGy>85T%|NqLT+UbI4NrCCgJLh- zOO82=d{g|GMq<kYyCSmn?x(;s!F|L77F{BuwoU2l!Avyq9@TEwK3|&`uIown-yYjx zOX~7g&`D!4n0a&=IsvJQ_Sr<%ngzO{u4#NvUP0I*kS&|@#IX-uh;>O~pFA-+2b4%+ zM~zWVZzW78PbUp!s&{&Ne*NmSQ^jlShv9B;N^Do^sllWcyV580g_(LP(oP6ilZ{1` zHlI}J@f&h^7V!{A@V^agO4NQd8B6JUYUra>C#O6Z*@@j(t;YsCZ<mzLLTYu{iA?cU zl7UwXTdY0XGzaHl?Lk5Px==w9hGoZ$mvAUOhD0^)TX2g@QO9j@1K>cuZbcSAJ9%ti zdMCp)Ww9xoZw5NSI~B$(c0s`|hzu0*ChW4@D9W!xvqSZrSjy2SWa~>$DPN5>G6wj- zeq9=4rEMcloLk(|zf#u3p4E@J|L7oRG-&yzm5###_EWyR>C41w%+CAmv|a1wG!*w^ z$Qw(z7#>FC3+wDB-Na*@0u&Dv7<$oR2$<GOziMOmF`0Lp17F|1(r~2-&3s`ayU_Fs zY_#xt?`vfR2a^DHIBdAFXB-p|g8I6OLNMy8OWW&&?UC;F-WSICs8&?N#zRo}z-+@~ z9-5X=p8t%3(cZrnGmBIj<MF+o7&6zL7+QW&^ex8rN11<0DZkG@x4I}ugJSzwa5l$) z04#D9Il;2d7e*qqAS5V2hxfEEXN?<jP3I9zhoCE*h9jSqUcQ=x^Kgv&eZE&*?xqA< z>ky;l?l501qy8)8kaAYUE6(C@aw?B_5%<{s%BWJf^g1`u%}0qsmijfj;KniYL2RTX zR;0C|_JeCM=<^aKEqbk$jPH0Ym8zZ3j#Sr+=q%D|u@y-jOp(a<hI&aF5hnZ4VLgaH zj7o8Ld^!^t`}OmW_$M}F3~_Y2W&7$;q~mzB?LW_9@Shcb&~v=6=s2r2`;Ryt1dv%W z=i!2C4DUFGqKN~s_!D?qfu29h4Wi!<ioG{}#T9WKJa5<i;yV0v0+yez=v_uD-|ivf zo{2-0O}Eqf8JGv8mP|+&D6b_<9u#Uk8;jrh_q00L+5bCeh`k-kY^Y0Q;r_;=9{{o& z7mAL~&mPZ~I?n%z{t+cV{4gckP2)<nLIOwFvu0*Jd;bc{>am9OvsNQaD9kyKF6iBY zM7geVx)v@=2aqjI&TYFI0K`_3LPEWsSirD3o0`n;4j75Ak2}6lxU$Yj@h{&u=-sf_ zG<K8wCY&Z5xejTX*E4EvGNyY`*%V0;F<xWKqR{D&CJvRPhVishZJBE{w2^zlw~d26 zJ}^g+!oj~->Y?$fqLO(KX2mps8-4oUF6#-j%Yp{Y)-)yuBk?OB2h{cQNOzGb$R$5p zqDU|>n11)rEm0ANOQQ;@Gt>#%#`gP<f|RtYu@CtjaNY~$%b<;g2q)eBJC3yxh?g<r zbOE}luaLM)^ZW2OdcU&R1);rsRlztx#;JaX3wpn64?yK64zHgxZNrD7dkcdp6LfPC z4GJWI({mgx*H-1M#e6I^f_XBp9R66P?s(*fQGQ0)%)yWGx(49BoXV!efA8se{E_sl z@?iyU1z?5u`fw4vZ0;NEZDv(qGVL|{KnxMrI01z)LYRoo5NMbq2;(}tFBQ_1Zu8Dg zunwdRc@e6e2-4SOtMaoK6f(w7*avjHomt-ko%Q7OgJALxT@2YFpz+NpuLf5%4SF+} zZUHYbt{bo&<ltb7l`g(%$~zeigzBln8X1~j;g0M^+TzrIFn8d)ya2<S11-W*<?|H< z+J&A_qC{}w;(t9P<2c>ftX@?~{ZB}lsBZe3!?xRC`g1+7rjh-KU?HGq-_LY!kPhjT zW2KJAB@N&QW?Euxsq_5DL)4y3UX#L4X5Z*+Hb%t-fT;sn%D;CeGH56=@(?uT=UAtV ze77uQE5Kk880=MPGM}9UGl)C1hN->4Uw)2!b0@t~ytlBFx9?+6Fia62Y9&b<y+0B; zm&-1P7}8x|>pWo}>cL1|ehuIPFcdmHvQ=q}yK&V0nv`RFcIUU6VQ73Rq^P5)X3W8T z$6^*fHVxn#V*yjZVHTfO=&2w{$-5NtffM}<`X{J<bM_n#*sGsM_K)HOLXf8CKJe=U zr1w*A<>uz>A(L08p)CRhUV=j}hnLhv3hbx<rm>$pQ%WZFclzWG_}H?D^F4~y|9TxA zk&%QVAkSP@fat945d3zB;~j1ug3|Osqxg0p-i8IMF~de#^2}G)d+@v86!QiZ?Ort% z9+4*C+lu_nrLNv`8%gTt^ibcE;b7;}lawkc>R6Tzq;l7@AhV@bs=Vf^h?a1`zF|-C zn6j5O$~T`*q~(^jkjkkFJQ=(Z87Yl9VVBM?a7Jw+WzuV^EcH7|2;Pg9h2Tfc`(DDp zQyWH)Hr6JseYWqYO3pU4#zz~a_UFGl*bgBWtmg=ioe&|7Crh*s>$Akb<_gKyQlw3E z8*=X^n!k_rW!iZ57h}5keodYN4j=9GzLSJ<oEwIx8u)-OjtN{Vdqi3Lj>*Uk(KzGm zL~A>%>{qn`fMZ9r+5ukC^)U_s+GlqNc!FW7>-2<#Ro|srD+w^6dY;R?z#ZB&S?Re` zu*F8*>spiGxrOz)m~)e7Qh~t!kUAkB^#HG|-#TB%8wpwd+O^7gp~tZnPM4EucT+A= zcw7kWs1gNB!IL)&^B)er+4L|NmDf(0(hy@=*Bq`YJPo%4BhYEjM^GTUI-IU^k%9jV zM;wcC)-acuO221bEiW*Tcbo|1&<RB!py3DAUyyr{EI|n$e?3R5wc)eEi>6i7c&eb? zEzhtPR;55gKVbV|w)<{V>wd6hC08FIwb^RY><;n=X^Oy5y?xpAiKM(cDPFgYe&{Xc z*5D9i-N};!4px{(?wmc{gG~BD7lz`W)=%msUzXu+xhj>CFVLBk3#<r5ALOhS<aQRf z7lGQ&dq)3?KesH+{tf$s@DgkPD-8d;@uwvI47=TB6aBwRkUS0m@}QI5)PYJ^s5|Pr zBvQ}_u{xyZ3%N;$Ogy>tB&OW|s6ItBAwwbJ3WyEzF%UXmr7ZX!b1SV1Q<O}WpMK6q z*2Cd<1w>D%6gN>S6T+&Xn--u`*|WD0CJpiMV7xnQ9dl-JI4E7R<398`2tM|`0gBHl zPPPlF5G2v_*p1?XY%H_$CQWS&+6iOtPZa&H<PR8hF|$2g$-q{}K&PD2!}zIh=0sV6 z*}s%(C5P_(&~_4DsBcD7dJwWm_vyS^jQOL#l!Rc($m&U_tXGi4Lk0g@m8Lq^&)h7Q z&!Sg}9*SfOpzaST^+dO9{zW_q$ChQ4y=5=>vpBq1k%5hyI4+}61%&gjhqSPe2sNVu z`iB$Y3cXMy@irmoa9aCo{l+k&otf`2{~746;St-ILUu-igUyi=4>i8T_=PXDwiVur z$V19xFS+5QDIf^6z_|)dRrH*w95N1P^o$+dS<FX=@Jwa-MB~}?CP}GQ+|ec)yxmCK z1+=Q09MGurR-eEn)#Y(Hp@3PAbB`)m(W64`{?4eY+Yn%n2sMvOCM_F*z4R$1MR}y6 zbnfoMy)tK1=4^(wL<n=)YMP58amhVT=ae0NU>bVciL6nLuWu9H86yBIu`tx0i~Vfy zyV!0=Z8)Cj#Zw<6S2o4)e87)7T)!*0?&$)wSu#P?Ovr3%U8Wxhd5J8c`P(eFq8|CQ zVywoO8c$d!It(5r$ETJhfypdiub?m%9ci$N{++<XD(=Krd{Tlr$G8B16N=8&Ou9EN zQ{aBAAzdi3M0{&;>)ZcW-)*dytTt;}u6T@Dz_4ekGkiY%e(!!`Dad1kJ0*C>X^O@+ z_YJbdZEO5V%NDbSs*XB%I8G)j&j{ai9YbmtaExI=)YI?tS<kV5yH;8I>;27|)eHz1 zbZrm_d(zA2I8-VVNf&g-+>Rn1f+97T;1L)43Qr@0=ov@ljQ2RRoA{504a0VQGs4LX z0W-#!38+%c-ePwI)V#_}uXP}6hJUM~slU$?-UG9r{Dx#ag}SuF{JnY?UuFLaEOpra zI5M2aQ8seiu{WIya8B+8-2jJ{pjVTRoe%VEmNF*hYAkDgjl!my-^T~H^ZMsT5hBC~ z7b`4~Lj#-Kd)U(4pJz@i0S}>mR6Y8*HG#9fKOBAh4Pg{;R3h->uIenyy0s%UV6;*& z+rYa*owSkwF~=s#xtBll%b#;<9rlrA2Y0gn7H5(jf^{@;MoLwcq#;meMfvG+eVR`g zgRO2Ybav8<+|&t*?x>(vSekvUpIy{J*-NM7YAc+r->@e|=*?j}5cSu3#v$&F3Q5P? zsA`ckcCY@^Mj!|dk9a753&xsEb<4`cqr4R^7AqXcl#YFSl4r*~Yz^P}K;aAPGV?7E z%m7l=*`wjLO15C**GEXSdz6>V<Mnpzx@l59<>3!&B1W|<Rq1X`?P&H7=7C!6U}F7i z=}2zd)=(1;#;gx~{>ICg2d@>kyOaUMT9o1F`^N=uJ6#cnt=Jv=wb$IPeg>1$!k?3o zGp{KOXwuoxUXk=hzRQsVrLPG&pvoqlN|glMUg+tD@LwRw12Iy91RFlb^Nqwn)VeJ} z7y3uPR?Hw%)c=I(aWLQUdGqmkF~I0xzURdG*>RlM3+Xoh&f#F^wWOL2NXDy*P2oa- zYgCWt{EZE<)}l02j%1&qvfeUm@)&wIbF+u|qg;=3D2DKF4kUF!Z<E{3VCl8=tRTO( zmPa^)sS}Anf!Qh)1b6KVF{Gz(knH>^xOOuPzw33t8-Me6LZLp>#!<#`wt~TLirj0~ zt`Ce8_xFqv@Po4rNP^IwM`qO5eS3WN`)wMRbwXSai)VUK!?}JiIN64qV6Yzj(2Wy` z<Com;9U0>Wq4`4|$g^iD=kBjnkCqf+QkxQ1mK0oM)0K?)CC%Oo^d=$V;4-H%F2z)k z5%rHI_V2Dy*^hh(n&e=s2j35<Dg_gQu+k#Emhs@qBUiqmm3c~Jd=Wy?=TXCp__e@2 zZ8#Bh>2#5tIwm{LZ@T4u^(YC_@rrstWw8=O>bC!oJ(87NP4T(qz5;Z@`f9bnS_+yL zPa_7-++J12=gKdJ>$mL~RvUnqLA93oSFbnkR-baf*$m_#A~VIauzV~leC;WN#R>PQ zUb*pD9k^e$uEK-d<&-2=sKDz&$pd<tfBvT|G()iR3pGyOXg9|4UFpg>!N4#lqbO6C zi8djTa;o@o6@fF-IPA2qO9bY1+wjZtREO3VR`2HrgZq<tOt)?C@D?at;<&SUsOfr) ze|zUFGx_p{-mi;RP<s_d7eVlVj+axxS)M>ps4k9>uSYyqMd~n-_S?T>S@fgX;}oh$ zl3pOh-voFB8l#1s<J*m$A6lIpS#LkM`@_&<^E3_-Cd61oeUk(-?TqO*L~0J1Y-iqI z*B#Dn?T}<t`$kHtWfC*<N?+l`afSXWyQob1%2#xkBgzY`xp6S?5oZgyNZmHDNH4!# zNpw|pJ|8v20w|x9Y}T^F0dwYgKB-esf9!TYYk&|+W;pq&CqvQho-04GDpd$BuPjCn zPXoZYuH(23ZE$^-<eDmO7s1+g)%WMF$}quCw*u3Cerrxt_3_1~o8~62jJ74<*$I{< zDcmw+au9o{7?D=JVx^AeOKDJ|g6Wt8HD68bf{#hktBu)#OgPgkvCqg1GpAQmX?(G7 zA}Qq|%&|xk!vZYQ;GWhcge#FAcOt_{ryM_8J()IKOyt*fHT39Z@cnGcV^2k^Wv=jO z6^RI)C{?|^-<cJ1Kfj?6%1D5GBJrVK3iLA2C6E~EL?WL6!rB<(Kmwg+iR^}Rm1ytq zBFDpHbzj7ST8xW)ER`J-K$3h;J+EQSt{&f2vLmfQGvk^oATnp+?e=IzllA5l{n=5R z9GF}o!*aO`Xg*zq!M(Gfl8XyLVjk{30ungrcAL)@4F<bLcr;qgWzkp5U%n&Eqeg3X zTf+)xurjA8r&Od0f-oY(h*gy!b|$UcoNSV;t%5##x2D9ZpEw#O#7o2NYKQVIaJ+El z^s}Z+x0Jdsp?No47<K<8wUk_#3q?|?GW_Y-*MDB_meWh)TR;2isO<C6JnGGywf$ZR zv5!i-6!ytI9Heov#v{$gqpWdf*Zi}l{gdCRFJxhU6&W(&56G`4u%Zqh15jYjJ19s& z8tdjdY5}THB;{c^{7bsQPsku^>&AZ97rmQ%1hN`rqkBi^U4Z^vR)sr6{NI8G8c4hI z|1Rj?hUL*n0nDL3(92_CL?eEKCP(CqWFO};t`c4tSn|;ksK*P%9#|4T(BSPS+O=X) zVzv))b?C8_{s(U8#-0>k#nl~RoS!ueowJQyb&k~oNWgn~Z^db2J#%M+dgS*^rnC7% zt0Yj$Rubh0Bk2w%UbJx;RWZSgHyC~dzFI2Jqu^x@kD6Z|Jca7g`;l$Oy8kn@U<7jz zMc|hmyjUp19?Jay8E*;X&jQOPM8d<rZ4<}B?7#tmxz-NX*-#4~FE2*@%&@&=tNd|s z)PhS}%~f_4k8KMPKw}W3yX6Y)h0MedlkK%=aRdz>Zk&<|LqN`N7(pwKY{6ND_?Xl@ zM+N#WUmu5wzm!nNaP>p>>rtAe6XNCci?aomKAr>a#Br(?DLv2`d5zbSiz$tmTC=D1 zp4_?{DHSC~=NTloKWhzezm_z4(bVJR_3a1e1HJO#&=v8z!SB!xLAwQoEk&Sc)Q+%o z<aX{zpbzoT6TuT1Lk*!pws5?B@3aK?5qu#A^uKxl;?LjTk{M~#nYyt~8ayZY75uDW zQXx}^)HMxlVcF%Dzsp0lF=>xswhniM5ZE95MLf>2^kXS)5F-~-;Y}oMx?8zB<Gn8! z8*Lb~S?$6^6gKonKG(oZl9&4Ic$v++RWEZ`qYE=L(Itq~MAdWBQ4^Wyxv~{t4d{_M ze|*X}t;40XF$~!iAKo97jdZY|ew!`c{F9W-p6KSmWmV^iD^}07?K4QVf@-o=uqYA2 z@auhH6ws(`X5an&cBt71yRWk`Ru{k(fl`d_GD4MWI^5%tZv^C5zs^^J{KX$4gzmhZ z6C(X89LVDP4(&0X6BBO|dh2r8z^eoYW>)eq8ct?r{QmauwDJ5@C$69|Zt5lsnxqo~ zUZ3wz0?TuWV}I_X#7|U2)hJ<KG;=>Yv_Eyll|%af@aELw>U}7t?A_ssy=<wc1iGn# z^AxOqu75|72t%Mgl7s|JK$NMzK`<BlA|aotQ&=d)T0=BOc0VIwZhsQ~$!zSwjwa~Y z;TSUqunYtK%3hFEu<GWx!*pb*o_vg0JgDD(&q2|MoX*=%r5a@c#olABba_CADD7Ze z$g_xdt}WUK&xEfe41<wjU~nGzt!o_@dK+-Hz_F?s++8I~)vK*Qw+`>_L0fDUP%T|X ziw>SWtfch+_?k%km-#l^#cfAe(#eCf+}MTaHp{^oL!d3yFa_r-bGl%)AAPXsKC{Ac zt?QXaOqitGdrRZ*d!8~0MOLc24LDp{k4p_LS;NH!O!~g`*JHce&S7!d%=j}@p55N0 z;-0ri^`R%0<v>Upq9!TBF>t^KMa{?;R{fm#x@S;0%&BLpX(Lq3Gzep5wp3o}_!f)m zj!>)Qlln$AwD(@3xwk6j<2ZDhCErRyKMgrNo$D8=QGM0Z$byq^kq)s#4P}GqtDv+v zWaP{<Tns-Q@?h#hG<i!tMd+55xl}U<QsRaZ3l@PU`vUwTO7r5Rw-#7-iCVi!pK0MI z1aAB7XlDJjy`s5|+Jp~}^$0V-Zd>N<<n($xhCaULmIqA;vIiXW%XcMb2mH?O+q>mQ z9B>B0{CiYbOi3gzzD;%Hpg%$yi!G;H8O}>LZFlyxN;v3JS@rkJ8cfws6lC^}wwL!6 zEO3E%tN2+SU_2NB4c<cm?$?b&dEYxwnEbRIKpfv{B5?*5hbsIGrgP@mp;BiospolG zEJ#;(a$6rVCyxI=^XY%hADpE>{xgG8uW*L3IO)MGXClK^!;(!aIg_eDwI+9*wnP1u zCDN?F{?i>ll9wYEv&CExtOKVQ<==Sw6z@PXajEp-3A0qLeC%T2R1e2^u2g;0?RD47 zUz(@S0RH2}U17c8@VSejg6Xavt`^}a??L53uj^>(^t}z9Oeq_zYU|^~qIz$#i9;`+ z_J@Ik^hkhl9rx9#2Ws24b0K)#Z{IQbXwe_kPnq&Z#0lC^7Y9NKa^MB-PFB92aHH}n zdvRP_=o9EF;y=kn``ypaYG;pqiJk5~-NI;{=<RIQ(PN*k!}>T&n)H|h-<l_L*l<Xu zKfY;hxeHCT|3mR8(ve_E#dqHRZB?F~PaILquHMd;XO5RLmw06<Gw<xU{CJ7`1oPxi zDe9%2_^MYw-1g$u%t;5i4NF25Omt?#*_fKw1ILx}B1dla^t*%2iq%s{5aJducs6WH zLK*ooRL!H!0STSG&-ozmVLU7~eq0&%DbM?3kj(vl_Lo)@2NKP)Fv<Mym_a%-ggNJM z(XynWo)R(^s7E>gj<^oge3|)&?#CVdMA|L0T&@d3hW^?H3dE26>n_8PWoqC|%DC>% zJK`CJchS!an)GxVoO%jFlH+6vZK?>YaZ*ubu<#4yCVPBkWy6U;8R1uNHmk*&aCv6_ z&~cZ<+gUGXR<lPpz~`fYqwglYUWuHFx|yCyBE}o~6M_N_JFnN2;6XS;PzlbmxeL9J zvZl$wc;f9qWP^kBTl?%+zLH?@lGq4@hl^+&N`&^^Bsp{MRcLGE5@}p1hLmzfP$j(R zQKYItuSODi^q;v$Sp_-P8Ll3+$%eA?n-#5qjCef*`Bh4mQ!5)wS?XDRDayT4D#JXt zr%(6mhGdz2jAt>59P!E&MHOD=4AMfB_LWdn0FKeN`LHn(s&V<x@_!HAGH3euNuT9( zK(gR+ALu$-DaY59K=mp}6jVaqp4+}UTU+b$iJh8)gJCT;sWSZocpPkONe4cW)D!+! zIZYL!ib+%mCH9p^EA!}1Mu=gn*g@xGAm{BH+n>);+9FJl;E5dm#!kNuck|lEKUAz* z6bAg}H_uiC4b0>B;yt#oonASP(wN~?k*eP0md#*})95l^I_eMn!P?u4!8dQh+p(@+ zEIeg?0#Olt@RZBDa(lW&$}G^$wp&5@Cg%COhpGD=Yv!aZYKNy4or3DxDLqPK2h(nI zVeWYqjJ&ndLuoO1<BmDKuI~rY<sie7+eIX8$Q^SV)HEtlm?8Ij*e#1-tlM^G=t3B; zp2zv-$>KG5mQD?=7;iHs9f7^D?Wk;*;x#^{ffq+2BFtPk!E!2>Qd8|gO0}-L)&--4 z)ba42W&OZDsBWl|>Ss$T>P|LH^TkfIRL(XqM>auZgJS3N`BEnA^rWF6&3y6~1(vD% z1qp?8AoCH6-e0fwM(HN{jj8YcL_$WXQ+_x;Z-U{mIJJ^G62I;VpLwsk-gJ@}<3gPc zV5p<h6^2V%SS{Bw!^R1&3~I_?A`<!|UfWB}6blsMBA^TCb31OUhbwKhT(Aveknq@{ zguL!0TI-AXsNiX_tIX*+9n{om0geY(Nml_^PC1<Bu=S5*;p@zQ&L1%7e+uEWY%XQd z)MNfr-<DGzh+3A)6FQE}mc1us@np{-5h7e}vIz4&uv~sLWIaj_Um12>Ip56@+|0bo z_wBct0t#viZBY&9H@)cv*MMZ~2FULeU?aAA{A4qVA~&ET>c37h-)K<|^Qi-;h+^r9 z3X*i|npPMPH%i3#RfLUQSeW>_<8G=}M=mGUK01TjHiBb{cR!a_F0Azb7TNz9wLk0d zdE>!~lF%T?V&}0<$J3K3?#9zSep{St41H6k-u!1r!M`<+I?3Ffk;7M=E)+>BO3z)p z9U-RN<uBpME6i;{3KF4OaJu*hU4F?Ry1KoyJU{PGJL(+bm+4%(1mFn%1bcJGe`Ie2 zyb7BJ;q<OwD-Y5^sk_Vs-aTQeq4;lfc=EmexwZo{-KuYzEtfWjh_gc-0TVig&}&N_ zEDjT4HjG}q_ECW34HPxSf25`=__ZHmF;_;0a4>l;N-~$KU6EL4))?w+xl_Z$z-qdq z=6-ajEfdKU_?xG(*ID^VD!2ejxjy0MgGZh<<L%EPZ#!8{XFfFW5Is*;bZ9=g(X?Vt z@hVSdkwR3Q^e?A)Ct97+uYe*5b9e_yjG(n96WF1yPqML}<zrMUYmllTRUHtg@N&Y% z$n16<;|$6@MR_uj-(=^o70`29Nkn{vLWf*Myq^!HewMEz`Q)5Lmf*~uC-FhR<cx^N z1Y6vg&$e@LIg$`xEI_Jld!u?mNY3up4bQf2ay4_ZOZ^G!>UwVJWc~)Xg^RooO0H&y z29R4Jr<zO;j2<%V?MX%dbNu+$!Dq{#!Lu($eD56<v$QJ;1fvWR1yco6r|%WJWWZMn zQ#z}&0-3s~S|8CSOy8Kb8_`UtmBkmG&v%b9b=G>3ck#M!;tJFO?c)wv>R<dW7Y=-K zz?&2})T~i*Hl|!ulWYQw>OtL$P`5@)WfdJMKYENO+kR`4()?wULdSllYE~mrH>`== zP~y-EU1P^`9`F(MZ47_YuiU3adMIP1-b$#SwRRx&z6ZlCC5f}RUZ*kD5T=pp`VrYp zr{%d4XV*PFr~O(O?9vUC!CdnF**-oAzVyykSa;PIxR8K|f6JEch(1|l-nc*b$xI!U z67#@(YI*L1p5@YRjve5wE7ZX<G7=e}evWAM>u_th=`WhzUv;@(e~=<th)qAtAFI;u z;k<}Jk)1%*z}AaZ7BgVOb@{kOx-IV$wBVPwCynq!kifGP9`4UIF(E##SI&!{ra&C( z+L|aEB)oeJjeoI7_<TXOHJAgf*JR2=O7a^4)4#hzQL<lu?dO0+XjJ^25^BrSKW9Mi z5&<tX#EsG~*9KHtyCpFiNJOp$iZ#)@U!-j?5BUh3It{Aez*toldbA!+{x*vBP^#C5 zL$F^3fcG1E!6NH6?vQbsr@<EKT3uV1HB7Jn(lr(Rlc{MOSFooia$J)CGxS~=b!K1_ zccX=cm_!i#l+8?~#XyL&4e*V-<{6<FIBYz$er>Y2^g*jr2Xl2k4-zK0P$AUUhUglS zbq{ff(Is$LMEq#3%Dr?^nR)MpqiMg=5`~O#;kMlh!Q<GLw8`Psb6qW7sq=x|^7MkS zS`x-Y#^;vU;*If4Fu`fAEZkM2LEaaeCf3g^eE^CYIpbsOwfwrTod3r!42deV0Xc{e z)P7qAnVoQQ`Z0Hh%W1>DWTPnk7iezu%s}Bz@5$ArFd{J=gPQj)n>=&e>!s)Ai5XC$ z0PThjR^Eo^a(m$9T;;?&ZP#gp!P{Z?AqApT;G)hz*8eP@dxVgbRM%)#L^w@kuOu=5 zA?>=8Vg~Fc)E9zwp;bL1_ROr6Ox-GUuswgYnC(CT&Jbzq>R2$3Y_x!9uQd$^@xalB z;(T93#GixohMMASMO&)Tk)H7&JX`FJ)79WC%)0Q%%H6<K6|gdGr&%oBIdFZ-zXqLO z%3wZS!BpS4V+z|_NL(BuP?~siq_+v}w%$SJ?bkt+c7v%FN%QPKOTTWv2H==lazy;P zMhg}H#bO`WdQ9;hzf<QuYTbXg{Lf;IHYX|r398@AoDKz`T^|qBcjC^}(X_j-Q9@_= zE(<Vtrd?v2^ikc}7EMF%`$^x9&m~=2&8!|GAxtw~Tb=fFuM?s02VKA3yFvqrK{bn= zx}>>2i{9TL31cFv@b~vEm!Gxz1i?UbI3x$dmVZzIcDMJyvzTWe@Q#mBuQHA5BDWL& z$A5($iWE9t-|Y<Um|$GGNfLiEOXfIn&Hn9?cv7m43q9TCw1T{6)ag7k?_jq?nL7IP zm}IUHug&M|;4(u9>AJ@tcE5nv(~5ng$Iy%Opc&?9z#KJ!O6{h0gg?owjgdaiQ8w|* zL!0U@qJk0HCNa-VA!%>6>!<asym5!xSUYn4Nvjz_li_(pcK-AWb(09+#*p)K(?Wjb zB|9Y}A{z=H^N}VVmgA4*$sA<7=!(JBEcfLH%a4vdOAGhj)q8|}a1kh5D0b8H1Iqw8 znpBohfMDI!e*9q*l&;uHj40gi;;DrAw10RUhJKJA#2zTJvo!g(wZbPWNBCIeJ0||g z9fdN6V5a_mYF`|oueuswyIviMm^&`ykbHM#lUTIldgA<X#j@Z3VKD7;?rXt_%zlF{ ziI9dtrA3Qs@LhD8$ob@cED56U_2Wlfv<yHzdC3U%@}`HPZFtpgz6Q4(YN7mNR0^aG zT{A>XJIrq~n}k6k5JXx}m~-^&4*d}?zf)XT)<aBu@-J&=11+h-0fqR=4W~0}M4-If zWA0SD=y0Fz?P>RLmu2r~4z*sfmHIwUgbyW!2aB+~xiIks4;JXEiVTBt7P}{Tr%gf~ zSwx1qD5UlB@g3CSMoxeGh!R~W$9-Be)sqBcSCX#76s3%c_^@utx1J7lv~JnrecQ+o zR0({$x^3M5#iAqyiU5NDZZI%Zu(e>bkb3_+4_<8Qe$%>j+7dM?`<>X8a(K5O^NM<A z8MA2&>pMH@{mI&~HWrHyJMj_xP2JBzCa*t}%KT6%qm|I8c^H4V!UH_G)o`t8^pmA6 zh2stkZC%`DHR3KwS)>Yn3>@1`j38>nboP>yn~<P$7Ie7ZO9l##MW#!Ckuvc?+Uh** zrKl^yA2que*?3Ze{>(05Uaoe%H^aGuap<)s_P>$NxI3UAiO(bJgYSO5N3s;Ur_TYZ zH#cG8WL=cKyO;F%;he}(KrJ?dFj)FTDi(+>R<vxD@L(Sy?Lo`Y+b87h$o@L1>~J+0 zt<pY57nYAvr8F;wYuJqSJ)c|<DYT~wOvhQm)I(bQ-7#tvfR-n*iMFuOWJYlXIQ{Jn zd|~%&OX;&*tk`|zUfwIQCJ021#>v5pNR{fIQcJokoaJiS>lJ?5tFofWlx`H2p=r7w z_u>xd%p$d1H0rh2`C662xMPoX=QPUL|2-e_Cynh~$mY$Aq&2E<b>sSWZs_6SFk(`1 zsV5`Q`CPkDw~Z{XqNKUUu?mNd8;4D#MMA54PdCcThufGzLp+n4$5})-V8T>v>+j!x zJ{zk0u=m9+*B4LSJNfdCfcGJS+XGA?bWEaP>)P`$Vbq6XZY-{ew;wsvR_K#{6{^>Y zjBtO|qehdWDLwBih!PVLM`K?BM+%djJx5Hs9((sto^)GM*KY|~ZTHsF27{Q#Y_=Z` zz)>0s{*cQNKBY@qd{4dvd6lhm?Qkg4`KO(R*yFuL9-Q4~C0j?O=&`Wfj*{CdKJ53w zXUki1J--KAttKXL^k5~ET>D7aE9+pA=RMn-JItFA|4)$qp71V`;BTrD@n!qz+1?;! z99D(qL%XgU<|_(F!(+K)4@(+)3)KW-6A}&hfC$SrBK?8n&O#HJJgBdPOd}jOpdMF1 z2Pi`C3&Pj^M_Y`Ki*wNHQra78O4WD8lS`s?+~~+h`hQj8AWjEU<o87|Q@vwi8BY(m zR3@hv(;BoNO)v;3Bn13K0;x(a40nbh#Wn0MCxudlGQ>>4F`53h!8^wnE}la5r{0r| z2iJq*e9CFj?2-1p_FP96W!Nb-091~TCEQpN(*by#U|!HELF>CMaA3L4=L!6Pp$Aj> zl!>~BRgfILT$aw=xi3_!`x4CH>x4pYC2pM1^0v*an7!FF&Jq6ctk}Kr%_oibO?Lov z#N94rXmjhBeUyzN<%K4`xEZB!W^=h$;Osu)-f#yU_=k&kkBj92Ehf4P-H+5R`=7qh zCcqgPN?CmGE}`MzHK=^wUi0gY&~^9Mo5v!pER9k+7{Oc8jD>1{Z9UcZMK@~)+wn?= zBW-hl**2%D&|8)uKdwZ^I8he0HuCwHjB;T-LCB=u9G}wwT*uRAC=Bt~ycDr--McB! z?0E^2)6+!$X26QLM|^t1;cC)CF@Y!;;0+B(-B$xe0>eBtCZXBzn0zl7@yA{fBlRcF z=bv?bnySVf48+MH;UIXZ?LdSiIsGeFJdqo3Q;(b`l4ll=7oK)^#OUJTKnuhYfL0dy zf}5(*P2Zsr!dRX9A(5%@og*Po6;C%kYJMv-fR?FG6r7kQJ|WD_d}^qyPR-#F8rfm^ zlBdun9b@7U$%3hMN%r8^_dOZ*%#e0)g4KW;Y)bSmHZR<#$#Dg<x2`uj19wXd=B_=2 zM!WTlw`dHQUq0xox6e*j!+@4InFao9E5T<K>m)k;o`+u$QV?v#sVv8Se^aHRBwof! zZxu)`E2Xv?04?O5$x9!N=+_fE{te7_0W|K<O2r6NfG5)VL4<Lbdd!pRcC<_WhhB3; zO>#6J`l0Se{+fHR5k`nOh=cCzJ9x1(CHI3vcne=`Aqb7P+sozc0;bN_vqkH$VUo+h z6D?4Z60LPy8KJcxE=?TqG!-E5=H7Y#pOY7YQjIgbR197~gED;t4|P=U1vC^>2uiPP zFo1LEzDh_`QdCF<ED;P3oNI4Qeka?S?Ns!#C=%$w*YUZ}-(ak0TpJ~mAnlQ0Wyvl} z+kS$FvL{rTbW$;>SHb>*hi8`43}K4#&vIX*5m0~_f<h4adaT(<^|4klCkW4nLa~CQ z$@GHJ+4j^Mn)?+tLQdtVpUFM34rVy5>mSJ?3>qEV2cA{3l~e;OvIjyg*n2AtJYsOm zATuG;0Kn2*)~r%47Cpeo*r<tG{eZ)joc#Vqg9uXHi#$axx0&MlWE&R`NG&w9Gu3|8 zgIujc&dgj3-Uk7`xGgBN)fCA_ssyLw*d9u9+A-g_svf2sBU-LDHOL{J+g}`Qb=yPK zC9?~>c)9M1lztV82_EO6@N2c&uqzO_>NuoNnizL|T3Z1h`5vU53Of<3Tj*{}A-q6X z0%mVu1o<1b5#E1@W7y&hT;SqpFh0=%NGJGQx_QZac(BJUQW-nau0tGDVw2(|<|FO= zjqCb6gY9e-FUz@cQiqfYFY?$Yh>k<}`$tO4-1xOkK<Nf|vLvz~l02C%><zpSGwi(= zz9Gx@$o%--uN{t$A9YUZ_a|IX_6q4yW7q%^)>D2K)x~_r{tW#mF7Qhp`7mBH{d!Y2 zg9F46k`CM5DrC-Y&$B6z?au+FTDQhw(UJS??m1ag&tQM3bH<bC0&xtz(Tn8;-nJHw zWNil2#jbkz$QY7YI1Sw42~Z{Whqzk`<oF;mH&9nleC80br<hjp%F|wfGA@@Nys5^= zVy8fw{d99Llc%kZw7XqnB(rrKh6-0IfrL10-S*p2k__0z>+^Rb7-#2iZK#$znxIk* zO$sfD;4jFzP^FEj=?r;F5zNx{-1jIgsG6~d&uL+lTUh+1w#S8M`8B4l*X-DVHauDZ zO6M+9uUz{7t$=rU@t-R}PiDi9-g^Dp#rY~7sBtc3(yLE*3Mw-7c5Wp^<}mNU*eE0u zwmX5lQh&fLal8h}I2kY~i&~_ph0Nz3_Zwo}&zxG!9Y)Pk3%5-=0aepX$}vW*Ns#bq zBG-rq3|djJ(^;1C%>5P%R;PCU#N?;2kA?b`C}|(PIPRW%oQ;4IV&HrrWrQ~_lF=5e z<%$BBlhIQRjHp!ZPsmHpjo2$9J4%PrK%EgpAtm4UD=!7#bI2?Y14vHGkwo>vxqnWh zsv9oWx}2S@LRXhd;K8Rtw3vD@07x?Ea7+6}3C1@k@U@mM#BJM^SP1NMRzK-1-Bzrv ztQX>`GTq!9#*O(njYd&a9B+!*K|<pKoo|1+j}%QrnHAmeA4dg)xsweHU255`>%oM0 z3r~rft(UnK(mJ6e>9fL1kf#sB+x55=927+J1b>*hNe>_9r^bNM2EGSDt0)Iywg%~f zrCnMADE^Kgx;dA7QB~<TU@0Tv2P1nG%v9PdFNoCAiwS^(FVsXGC^YwOUAh-s@29c5 zVPE;&pl=LtujKwiCfHXyiPyoa!xH6hh;ZRjdM;}-qvFtist<39)uw;)drKh}&h-Z3 z0gs{wyL{kzi-CB6FnIw)Y(^t_0(FHKWNA!Uh&WKV5Y&?b=Zzd^dVd~a^Q7<DQF7|` zz<sQ*ggx_VN6|0a5`-Q~htxJ?H9*4oZ2tA`(iEh_TQ%~JIM^!*8EI3-DAJxS!@b+H z=W@VDO}h%f0=x(lEhcJVDhR?TvF;|3#l6Cl1*^;fhS<{=%}Rr5Sa?cEuw3sB%j~V{ z{gVM!l=(Fr%#<oBlQ$U56q{L1a~+PD%)i5!PnpmUL9?-oKrw@hl(Y^tvilt-yG<xu zK7&)LyGtLv(o>cvvJX)d3l5{?u)F*=?Q6>A{_2ad>(dgE98r^U<OLr=l6wB`PPSRm zFU#4^_R-^Si;b1%;F$QhM^HHqngw|oxe`{9ArV#u7OYnJWO72ZP`jJ6Zjd|i7^S~P zye~;J(ozlgC$w-y?i%mUaoCeV{LqAAxMqvd4j$Z}a@AC88XRW8z$UUz_@>ySfL26@ zubyz+X&j8w<S`S5<pw&@<~W>`;#~R!4DMYaVvWV_ZPKdMCX!-$&0)I5DaqA@L&xRI z<=rZsWCh<@9<=n=f20mlB;8hDXR4^LOHS6IWpdK1GWpAT2%U-8eT}{4uf{N`D|V|< zIHkVf&Md9?I15MM(if2shYPg_82H$jilPiG>%DY+r=t9thdEAB^s8e^B{VN6W8Ba! z&3<TaCzkq^y~%0MYqVF+<!sa$<zd^6FtrZdeaD9BL53${dbOv2P8N^BiB<dSWOS$t z23(L$otuN2wNuY<(khP$Z;MHQ18gj{KvvJU;!^7UQf!f({@9~gL@v}h_I~)TWT|=i zvqFj4_uj){D}i%02w+qNOR@$1RAQQX1PPHtvY7Hd>Q+V!UoMMSra|W^x?##4-!J8F zKf)Qw!+zb*O)0GW-BlKfPL)y`D$$2k$@fHFC?94baQ*#*W;%})HPML$`~bXs8xlNj zK}fs4=e5dDjrnhwrDeHH0gv@>7@?FGMiwRR>W9Oob8e&i6HQ0uV<p<}vFaWYmD|$w zsHH`e^LOkpFLyW&@9{Z9$@j&nlojhAxD^`cF1Zph%G>2-|H}f%_5Fa!Q;2Q@v@QOj z)n;W8)0irM^-&X!wwzKf@3xUTetZJD9jKW~4CcM^nHQ)g<I@^cKoEQ07_8fCP-wJ) zURZjqx7Ac~%0}We@z`(E*8jP51h{TmAmX;Y?~r*Sa~yHcfd)x9`}zNI9nwH-x%}DQ z<HBUb-_Nj{9k)XSTA*wVHom!opQTDfBNUv})JJI^;^F_FUi#*o^XAVo3hg3*Z%of~ zu$I9gN>7>}S{KYzqIf>8*~ktqNHF9oK$f$@blG&KEb*3*Sv=VhocJbQYXAL8fTRbg zPQbdKs7<RynlZ$V8nZKZ=+oX}G%-R4GLzt(e2OYJw&mA>lLKE9**f1t?d#Iz8!8w1 z=LL66i=1W~@IrLz@kx0XTAbaY2zj9OVLKzZiE1Q;@%?5iGNm-WMFUtp!R-t_h`>kQ zZr3h~@BOQGJw%;QWq^!vw0iypqR{w$zw_n=oUe1-6^^!iNqjrv-du#D8m0@M$a|sr zYj42tJiz8qV_iWV%%ZR#f##<__|u(36rUkkrGvKK0)S45K^H<&4y(V~tx-yr88RB! zi-I5UJ2L|!n~U~?2#YolX(y|5KnrhwLkxbZVZ;c6O#-!j^H%p}EJ^tX@cs-?AnS9r zOzW&W#9xl#zfdn|O`^fL6I@Zmrlgk2b1EpN;Z<w-vfmP^VRUd)?tU;Essb>@5>9VH zW9fS3K67T75V+o}|5G3p&uIO|>O}W`l)SzBmlz7+OfRBcph<icf-Q~z7vnd38Pbyt zqTq54$UVxeHRXr198Eg0Y3+B_^^)1Nug~>s*3?i$_39sx$mhA!#W~ikEXUHchPN(y zKffTbnDs=V6`3!k%c&xRNM0tq&>wmjbamuj`r%(~_Q)gxVHA5pK3+gfHPqevM7Y;5 zSWgGymFAFfp4`6oLwG>#wJ2wW8_bgdrO@JcQaS-D%xk6GV2I-J-M&a>%Dl>ev(UMG zut(GP=S9`~t2qKMau3>}`RTpBy9zuoyyC~X_%jGnzi0eQ0ihseoX-g%(s7fEqH+Lm zj$W`>>wZNT$`JA_5DF%I3f)ge`aR}P8n+M1Z{Hi_Hpg}UkOx53PxcCi8~Ha_gkU7h znPG9JCGRgT{_QtX;TNEnsRYijkiM76`p_ZZxuDHr^~^Izr%Eln_>M6LCMVkBitQ8( zk1GULbdF-mv55cq2P7MATAvfXnjwopRP8sWzP|&IDb$k;BmEQI^isA3drRyc=w)j8 z1t{A#F%Zze@|Vtpwl+`3p|KlzJS`>9se;touzZ%CbE01-Pwsw6NBlsU5;LGfhC@I- zKEqlm=IYx&+e<klKTkM=EY|2!W3{1^1VHPg(8+u|#aQyrH>kZyVTj*9r8ZvcIu`e5 z14es6Axm*jkFm)FXyZ<M{T+dP)cYP%eLI>WQi0={g$7K-b`lu@IK?>8Vt-TdqajXZ zqMr7KM=zatrS7YRsOBH-`}Q|Icgr=+XA!#vYue6<1@8uYXvKmIy^b;%Exm3BX|DHX zX<$sY`f}0Yy9N1OJm8)hJBiIA*H^c(Qu*&pT^vdsdx3lOGyrZ#HuBnI&VX13fb!{v zM=pq=mpHMt-CI1~a0+hFs3ps3<IW}~<B8UQ60P`m>apOjX|;Jc;o(!DtYV#{?p8#* z$M=t-S<HWQ!r+@Em!Tamg?#%Q-LI`qvg(8_yWZeUyTkS~Z(YLAX)MjI#cY}q!uQ0S zNcsYX(;uWS0zFO{>(~RKyl@b4-oO%sP3?-)Ehu%Wy^%xh{*TC}V@qYv#FSlj-&3Xi z?{~FrWk)P#8s!R8vb!0S&sCgmCQ0t+O)MmupZ^kcDFq{snCu4zCs}qsV}CvFDZt8~ z@<?v=pGj+{!~Qe9(sMD={b~%B|A2o^5h$i7_Sl2h^HQWZqb@y$@%mSxc5~k1TMX-n z`yYhL5&69u>|hop-g33RINKmwSCB~c?%UJHt>1`K>FMVL$MgWU-nZK?G;aH?C{WtL zVOrG~k?wf)gVc%NMK-Lz`ryORG`FXHz)!IO<{=C=?kJ(UL5yg8#i&^=V@@lKyI7_a zTx|IZ>XZSy3#M<PWGg?!&?GY;=FaPFe6Bycx6{2^W}s|v&0V*>o|HgQDVgc*UR`d# zsYAj<B}mE9(8ECSGE0h38j_*~j+A7Yh1*7ZrnZYlj<=QT-#uI$F)m7TCuZuG)ojl% zyUklRz4HaRC5%VV7!sZ~La(D6Bfq?>n=S=<rd}^kmkPzz_!`RpMFBuK|CLPp&fof8 zkN=oju2=#|gjf;!eJw8#L*3RCQw=H(-ImwlyE`{N9X{!<z*kq)Q>00TO5xhdF^8;B zM;b1+Xtw|T-fV76oaWo~^&0zeg$~7c1XFZi0>+Xcz1_i=yP``WZ8`si<1%-C>w2>5 zHG*ch=QTx^p;m-wSu`Qiaw{>$n8r3}*ZnHjZZTu4QK4qB?si#e)(Cq-`nT{>AoB?x zrh6^g7FWSCYT2Q*Y%OjzCXN7#hWlOafsUT>FZ98}h&lmgyz<>~n7{W8)p=E*=i|1u zrgb@c<1if<N?jg+@i^<urC%FJMoI>0B_V2j@h$xR!(oB4{nrdp^Z8Z#n#T5~f;=kD z3M8tqnQ`rf%O%N5adg<vj44(3WUs3inhTW6Sl5|YKf6r(#&qnIl#2JJ=2hR&wO`U# z_O=pQ-x3XTthPMa;LuoExlYhC$_s58i=6KTOl+V1wi~1W$lcaJx-D(_UJRry!?%;1 z#0`IGT?><w!CsLA<)A{>Akx7;7j=Fc7J1R!YN;YL<SEnS{VAJjukEnG(f@R_?!IN# zY4&LTV+X%Vwx(K|)6IWR)&AI)X_G1R*g`_$74&CzbnN2t1ggcw$NoUV>!Zo-;>3{H zWDul7z%5dOc%XWr;&#07a=mTES@Gf+zl@Uqs!$tgGAvuug4pe0|1%kgDjmB3PIr7} zx(%-})7ZZG=Nhv4%a@-w5Lv7knPOd*@<H~r51L=>#l*{P;ruZ#r2u8)8ux8f8HF{Q ztw1o!@<R?jWu^hC)1S}83_mdOa>DRqDaYF`jj6)Y?9$8D*z2-0Q~$nnTdVd#w>&26 z$O1DYzzS&~7}W&IlMxX9E<*s<DrNnF2(Irj7*SbOmNcBUMzxnn_=k+bwkQ$fq&?%l z$mWsn;C?4TD%!=W_NW!EVBuDI5Dzh^(OCb`l4cr{F4A0YaYOl%(j(8V*az9qdm<iq z!RQ)LF1kNr9bo#@RJQg#&ndt2b`H_?sugFovXEN$jycm}D%ZN3f7ijbkQCK2Jh)1% zTL%JTkH^+4`<tABSXq<VVs}|sk-~$2sEneA=+xrqz2@gW^!g?2+gi=K&5>c$a}wqW znl!i|)IWXb`k+8a*qD2jo<u^lIC)__+tBMT69V=}HS4ae->z4Am6t0Nt~|6a#?j!9 z5loCa6)dj8b$%Q7sO_&A?HBVelFbh>Z&vp69JVd`&Gke0{m>O8A_AKFm~kvLR@SPJ z-@nX#Fg#)FIW^UPlf-ze!*suA{5h+uyKI@x;V(B>7YcjME~{oI_B%4Wv|gQj-0+bm zx}RT?<|6c{7KD{XACNWAnYM_B!|DQ~r>&}s9a3)gvp@_WCa+NDeZe_XTPr?h!mo^- z;j8t~E$eVM`Z^Z7jIAhMDJ*52?Km@f5`Kt-b0bPCj`?L3e9SpbT%qp440j@``+)hX z@&itjlF6;pMfp*doD>%R+}YQy`40}bZ00-Vg$vl5<t6=v$cT!Jh>N7W2bnC(Ck$Mi zd5-s1j`x{|z)|Y3?$_n(+cvD9L8QvC^=7hKIE2q%4Q>AEE5Ku|Yp<bQ^Q!u!&E55d zMaz~)q-~ug4++((-XmMKdMHGVga!}KK@=JJ%?tXo4*Uox#&?VN#bedsan;;fB=V?f z_P=;4p}go04?qpA1I9gBC}DxD29LgGlD&So?mwfy`V3Ex*ukLqm9}9D*b{HHwT1%M z0l@!LdA$kHo*5x9kjUX*@F>7BM8EoeDPfShAv6-Qk1{nbhj#w*BD(c^+~4;#^Aozp zS!(mBQy<sLDLf31-STQtOy}E<;l1TtcS_u1pOHKn0q9i;)#P~p4pTqb9{NCCQ#P<? zqQq`c$&tqW5#c7TZ(#hi>0OxZaTUyc6Q*`?mdV`IOx|(hE!!BXk*;KZw3Bk0NV8IW zoNXT~`~;Gz`C$s|HYQ#a<&sn!R#7c||7zi~gNiTX4jXxOACu-b1BP;2F9~}2-Tz!% z??VwjQ(^L27nQ$W;ZgYkj55LF_~arkatjU{r@89dR1!WnW{S13)wO9!{CIpaU;F!Z zVKZqafyoO;7PJ$an4c{53VTFOR`e^>nAEFSR3&p~h=UjKL)Xe#QgrL(I<@h@MgDD< zxIGLk&@{g8e7wbMrq7!f{B$o{W;|v4i1)pxt~!2r!=)X#$8gzQ+wqIQwk>`S@z2^V z(s|eEH`k%usX9fT6J`huPYI~nl$vdqeXhru{#e~e6#Xj6L~inkgSxv%+V+>((93p# zM^p)aENS8E1qo}?rj2bm+lsOo+1=}yW=#VUOCRpF0oQd~bL)~sm(E4@6+Gn?3}vCa zjz8D4>yInWZXR>ZF3Rgkp~*Ias}gd&=so1#I~c2-E`K|pM<88ix!hJB-#!L>ea={_ zG)q&)Dmn>h6#j*Nek94PV!X|whn^bYGd*Edj&|j|WC_xUq?>6P{;B=Az@b^E{%99) zm~x!;rAxKwz|v~<5!{7re-9Y9xoKCsSU_ZM&OIr*)99%d+N75|){TD5d%yW$d(7O{ zx2TO-AdXYyU!U~rp6}{j*U(AOqx{|!{C}u=%c!`vZEG~RyE}yhr*L<7cMa|m+}$NO z1b25U0>KF$+#Q0udw^H_-20uo-`{Gh)*N%TG1eT~JMh`#Qi=&8w{R|HIC|co!8$nJ z&$E-$W?>_MD)Wu&q|h%o3o#XO>E>^;5HYESCfC&a&G2oD!QU;e+LlI#?zudVeH^^i zpv$|o!zwTZ#W)VEutDe85!QpPdqflj%%5YXqi}pDYd+NAATXkxDET1NZd(7IMcxr1 zQR0BLfYzf>$$;U=p#^(;BF7E0W)DzT&16Bo6|Y9XOj+<8ng6Y-XGM$OzC0yKUq{|M z;RYr|yWqy_HUw!ZZ_u@+<$dz!`AxMWNK3G-!S&rQ>AZRA+eLVV<|W|=wz<&>jQGJ` z@nr-8w645cs~<eHxpj8A<#Or7!8SuJ28ckte6`gRr7`&Rqt_z|j_Upf=F{%xsR+#A zGZCM4O=u>~O_{vRCJaT%bxZEeV&Hi}XaYz#ZE&&h@PO+Gr0>xCkgday(J^uNh5qVh z6}Qk7)O9n<^7E|e)LmzShrxbUbsUT#J^X$q<IUu;01%*F)yCjM9ZTjNxCNeTI>lDG zcCl^TxhDva4JQ!U0a1udN%$Wdx*i03_1f&~)VASFoVZNJ${&8s0d;;pkXRt0rP7$| zGpMqM&=OW}laLMJF0+5WT~#wZo*e|0xKwr(F~PmRZ3mu-kR08;33@IdieXGBHXYWu zd3fDLv{iT0>d;SJ#sZ&W4Fi{M7mZ4eQl^Bh1%HAb{VBb>p9M7epRc(VIT?Gu>8Uj+ zN$*olQZDcrD$mj_Ya4QoykA9b>9*bfod33=A~m5+nuT*<5>reSX2spq&r@Af({NKN zU(?yy{~oYr$YrNgN%Gd5uYcL?UsL*U#HhNPgAc2APfc1<7yA-$@XOP!|8eEvj6vQ0 z5(=$Z-;spsul!%23cfO-x-HRO+38@mu}a(CbG&qzbwa!oMsTb6wjCw;_}JK43`3oc z(kYn4ehoYpt3@OX=GXiAxaoV3f{zxnFWwXIhMX{J{}H?ITI0(qpi<X<kOd1jbp@9$ zNV;;`sN1~#r~AT&lrskG_EJD%1Un%?E?jn6JU@>I%04;Re4K#TxxI_hHvHT}&sH$c zUcgnw*hwMD3oZO1cL1pZ7IN)xYov$LsLT+yYxU;y2ci#?z>arsZ*oIxe#gZPJx<G& zl82w!LIY(AFUtYW+h`7<0XOKWGeUuj8orn3ZD$*8!>cKwTTS;|%l+T@-(^mF_9GVM zhM0ZJZQ$6LaOzqTgovHy$^%Rj1fQH<4?`35+9tp}BzXB&r)`dw{El<RdxvVTm*e6N zM-3l($06Ylvq+)mZwTx)s?~LTCSF8qTE0c@=bMHfZRaN0cgH&sEC<FR+Oct_50rm( z<a?EQ@7q9|T)u0U%sk^AZ8mkK6FQN7u`odXC>7MTQEjFM6J=r3;e5Y3P0n)%nzw_c zhuB@TW>h^f9SZLpiSu$L24M*Tc|E|R8mQ1wr1p*;Kbgvm?B`4@YwZA$LL^%Q+#U&9 zm-VSrOSk~J=Pi^+fqD-4NTknp78~8KAG}qddA<1}O5ET1Hf=_p@rHMY)iru0rM{#% z9H2`w=cruY(R};y39eKtjDU(PxSOaBxnGm<+*=lNxXy%ixS8Nawk1-*^J74QE*XYT zVnMuhwTzXpu9j3QuwCm7JvJxk=a)^eUznC;ni6AQzTweypg33Bua@{3H|l6$B;X@7 znrm<W!*+1~eX%tbwNy6V;f6MaO+3bh2~y3dC7kU@{_uB;uTz)oW<78fEzqaQp~J@b zv_O#5PQoXE(X^1w*c8fRWyR<5?6ZsR{yxmhrmxf5uWK`htHh<V6}+Kk-oPKd9&4`p zrwh%oC)kZqZCR_DAg{creoy-xE$_F}y4UmE(PsNC%5MuoPp>NnT|PQ^@q;E)!WL#* z1Qz+WnI~pI<VI!7$>ad0^DiW0^WrpzpoKhdn)e%8yRD9P0m+37n?Ml((bafw-y9`M zGV?C(bDE+zx6|qF*30O_@zz`cMACd1zL5ylz&0g^p1<|n%gIuwE4&$h2T=u`3tAn= zKyVNgUe+Rr#+V}G+qJX=$jGe|2!@==WE-WzsQ~n0yOmyRJzaPg0nRRaS_oUJ@!c^x zhFvkzTqMgiN;F}c{3Ew3<srqzrmZFW?Y_v-pFgrmJe~lHfk?RmHBF4#z}aOCQ$l@4 zpq3dnx5@8UkJfZk;QaT$6VHb$WkioI^*l4zS%F^+jjbkd<JF6752fDr7CJqW&|UbT zZ4X+GJ<ds{RxX6sr#w!8Xfg+6ySl9+?+bJV(6Frbcw`;!iY<PDeP_HL<6BNCOUG)$ zwQpMqLX<w8zw}x!De89z><7Au+RxhuKX-8i+}SVee0J&*k|6a^UPD^VzRR82<&-1j z9c{g>`?=!r^TOiwtU31HzFH88a}#p{qoZ4eis~E{N;JPe1c)@9JYbj3oMq+Id0jSP z)H(k!!(~^yZ;gF5%P!`c0K_JT5yq_ixCz{v$w2$5w<Tn_U>OexL!SpV3{zp;{j_wi zQ_K5FwpN_*z9#gYOWoBkCjMhv{am}F`96bvs_y6c7k!7BB{Eg|i;ivYGqK|VgZ8eE z3myLF-{UpXTTJI;)l*Bd>+v<wAl3qt6+G;9mCdxPsRB`-%rclRG13X=9oaU8EVczf z@+mNlUTJe4e?u1HPA=R1rF%8)Has-d@r!R^x8LJNo5N8efa`58^X4vK5K&%lnQLuy z?l1q^7?F>*etq%76!rz6!s%%ygVJ79MV)gh&)2dc*Ymp8V`PU9`}{0rJ@ot6U(GZ5 zw<{S4N1^y|LVnlc%puaRntrkHHG+`FL=exx>Ei2wA8+F}-S><7Yr$}&N7w526H`4c zj8NQfIN>N<%e~+DPG}wIC-Xy`v~+$r7v={D`oFlHE;kl;*KSPk?DPF!TA~I_RavIc z6i!3p@Z8?K1moVV%2yK=R05F{X7H8U)LN9D7eEC?f0<`(k!~z77~uY=@?mF|`Qb5e zqg<RzN`Il~Sx-#cjLDt;b|~A)(xH``A_DXET=B!a2qo~CI-AG4YQi|V&C;Pm=fmN3 z4VC|{&4Vup8naZ!+_<O<af|dhLUCF&Xm?1l1u;o~pRI{|)7I{E9Ta{}gC>&R9Pj1* zUGVm=%1U4|P+sG(X3W|$m}|&7KC0<rb-<o%?T0iCQR)6>^B9u-oCBzN@@Cy8H3jbQ zkIgFoxw-FMEsRILQpQHNv9$LcOfzxFc&)w+Qj#^}N-l?E>W1^2;9`p**=w|t;{nGW z=DueSeeU#G8HGby;kWAvhVNkvL#-x^5%%zo-w~Z2jj&_~Z`Rsxg<AQ^yf!;TMJ@zY zd?<9iX(1c?NcQrL!}SDF<azgI;l}OoR!6uaR#KEZD^hH9AyG#4?1>z^)6yX?ZB9KM zX-aha>2{4t1M0i(nox)yvL+0h=DSW?FtTfxN~_=gh86FZR?PV?)KgQ~`X`lhi#p8? z#Jesa@2Khm&}Lmo)@Od`M7nTzXsq94grI*CwL^Xp%cc`6b3fGzh+#R}&$Yf&kc)i6 zUFE|T=kAzXyOYH_chW{~B8Y7jcnOK!Q*G<Toyy(Wt?d$MeQ_)b{i4_URhe%HjA#KS z33d4WUG-sf-g_0Lpw!){C-R(5fjcdO`Ng@zGZ;Qx^7e4~lrkb#Cf}Y+IoC$>hWQs( zi}WRmef9)52*u6iar;96JVJM!P8G?7*xw!B<lDkX>QY!Lz^g2D?{zv|R@udC|6}4i z=i0-|&ikSP9BFiA+e-dq8v}FKVuWqy$Ni8fXaJ;t8fGCn@;#Kr;%{)B+w8BVq}jvn zSJFl$B1elzQvZ_LtwyGA^}1-UR^(&^2x_5C=!u)$QK5HV!kFZRBG!$p+qpFxW`njP zj%_rJAkSwg_C{|C^}{<8%h$xwgiP}lGE2SD7S!xD(K-0w_lJd_qa9i`h2xoC6xQId z?KG+|yuLkmSH9HDyf=dfo6;wAbS$A@1GWSobU>GHH1)=p3R2k;vzrRQmJyDbeZoiy zvu+Vrm&G^&kMphkdD1`%^0pb$rm7qupu&b1GMTXS)7z(ny(wDn<H;=6Imh<%OD#}I zT%L;>I+@{1y!U*EgYTODuEi-6*9?Aox#^%O5vzT}$nDPRp*p99gPC8&1q#=u98L74 z)dnAEi3^`l{G}h}&m!7m^1MAUOC9`|{=ehLiRsj{g%w}f;}yMW?EW@R(KCs<yS)CL z!Ov+c_?^XJS6KSsvncn4Ck{q5jv*2C*~S_Sw|S_PZT%>8SAd$Ri@ryFBH!3R!tXhQ z3%Rv~r;_aj;ne!VnV2gh`V-MxWpSAu*y$Lb-3l`FSk-cvAsvu(NkBnEo6_W-6sw%B z(^E7kf1%SDVY74oP62r{HV@U*3@;<FLqa=Tp_H6ji4=1{aF`c28wA|ov3VWr3ze(^ zY9ad%%!pDiwr!PpT%kRJCQn=CM-|Oa<e9n-(`aV4<|y96^;-(&jr^`rPMde6Ko%d0 z3!ZV1@99bTh%>Q$#U9>sBK+uycc_JRg8@Wa6p(h|y-QLeLLYx`hoTq9VMnB8Mlx3) z|4i~<-W8u_Obqyg*}l)ph2JVUXN|~N|HnD~Pom&z5X@0M(mLQ~0Zlbq6)}#bR&EA7 zL}*`0Up#o>-(R1%J*R&w%jjR86|!Fz?JKBlfFbK~5EeL6S@Zc&KZ7K(os}DMG&>7m zWH<wyQR5&$lNc%EE3hS-FN<<L3kAqMp2=-fX|xp-xPHN8sdvVk&C^B4I(uG{k@7Bt z|MZJrmR5XzlzCyo1imW76hN{PQ;}IeK*9Xl9G_`yL6hVD&7n<K*zPlh?eQ7fS;p{t z|Inn3S=**>kHbQJmw?aml9G_j>KrpAz)+ZANpruH%W6`L!EttMb+lJIEtpm<yn9<U z-rZ$bR^e#aUKZr07mA)mo>|3%zk5TW$20!Uu3=Ox$kjq3x!Sa@-UHy-{t}O%JR<XH zA07ihMg=o2Z85K(SK4)B9Y&>soMY75<oW|T5+1NNSf!}+GQ+jXK)`b&>hUFi&ZtyI z`4U4?B!^D4$J?C!)1CZq;#9_vi!v!%@}W;GI=YFPgm4w4Qe8MjF*CLAgNR>s4pyQU ziDr~ez!G!21Zh~dgGo=%wt)ji>1{yij|AS)av!PC%hDsAiX1l$NkU~Wr)U99(jk=5 zKYbjeD=FVrC411(2+q$Fh3KWbrzOU!Qw(G&(juCe6}&Y+56~L7{(AQs%H;A`_agax z=cHe+4tE}@XOgdwV;R_eC6~=&7h&jjZvm>6dHuY3+22Te51qp0waliPo_-=y^o&%a zyY_7r)GSFZA0)9*tX<IOeuz?jy`y<b5Z$eYXd9Y3MMfO283hm=Pg$t&ed*oplYa?n zd@(}uShz@K(e&sX_&bdXA7Js-OY#T%sx_xE$I}nIq~c)g17v*)7H@079s}9VH?jPl zjXK}(i9F76(j^eu8tPM>!)9BCC4ULYZaRka+q|5}T0xjFlsnSb%U`VVav3WrFhJ86 z8ix1_KIIXFJLhdgjW#O&${HbafvQ^ch(hCiyF9Mkl+CXc=6=3_eKSjRfw2X3%MBLo z(o|@MNbFtNT=`*is?WA38(s8(DReoY2w|iTMv4$p#ehXM#i)FXa@C;;n=`sj)<IVV z-?Su(3hoHk+f#Fx%qpFe`d#`G`&KhN$&@<77SW;Zz0_+{5VK63@MPt8yld-Nzd2EB z_PxUA?^^bxjwF07>OHi%&_aUcfs7wz0(Ugt1IAoYn?b;=S;EE0<nYig0qXDw(u0-J zl!!w@vtU@<=p2+2Rbk9K+3HT<{0lOX6J+b`pJ}{0rooWam;?Ytg9p5y12k1+gERhk zQ}F(h0*L?Ohq&)$DpU5^V=liZX!jdGa~^V+n478je=9KEJkS&f?FTw_F+mb~RDg^= z>|HHb^hkssNeQ7D4{(0xgEVK~ca>XQVK;0di9gpfm!2ZS?+-90UsFB6vdMX*e_TeP zg!6_6Yix7lPXWY0>1(=sz1w%Cq4*w&I&8BIr?%!5I1Iw$=3N4xN#dX-)mOTeGiF(j zbi`yv(wJKC_A9yU?;;mLcFL!#N=9ayI9&I|st@n4WUJqNNp0ZB0vcLpTx{XFI(6mt z!ox*n<g2LROn-w}=4lq9S>xJ>@|2FS2r-3n&{Z_9f+Rv0(3s^`SoLh$$@&4n2HPY} z_5)^+l%oDvc3mr$S)upQcNpZED=2!HZjS8O4&p*~@=%NK{L!L@^ptCh?M7*y$>>Ef zro`V1()acj#*z;uplh+J`TW1%{o+1W$8|5s2<7pJBPWDR`r|{7%7&x)cM~rBWhFMo zK#dC8ywSNV6?mwX1s7eC?RpcG3U8vc1)mZl`H)`@yJlS9HSq0uaO$jln6yq)yYf95 z0(0yLTC0$oB@S*#ZaFYMsdQDM^J%kK$Z`)QVkuWHS&QmVb^3-l5T!<7Hw6Tr-9VGw zCe|M6hpGapA_d2<5v@FzL)%tP7NDXJ8`psH>SPB-rEm6=%v8*}YE*nNuXA|pg76r@ zSoKsMuOwov!uRdRtVtYSM|$ODQ&suaje8(xg&Mv%n^(}r{i&6<+O3<PJY#ZevD{^W zhD}EARD_z@j~Ww_3!vQP*AKiLe+X|PJdR9-FSn(UIYtq1rJn6F>VwL4pMqQVb=Vd+ zo*v#aL1%zj)Jb96Gr<kteq0X=<M3b-npX8U(ABk=v&zuResHKw>x8}TM5dI}^b$<0 z*-LX&Ti<odm~)L2_ad+Mk`nn=T!OVbivqdW16i@4=`h2oui+&Hu{%XZ7P>9%-;xnA zs;s(n$DJ4LS2+L>j?-r`DWTNjEPFZ9EpX}f4-0F$BZI^&<O5RgDdsn>7eK8+u+XjZ zHzn3H{FTMgi*~--PC+v|n&>)3qG(Za7X{5)nQI997<Vu_%Z8?Ooq*vff^aG^N2JqL zaYT<;(cncXol3VNt+mA-=}R6gJaP8ZxD**keeaIS-a@WxpfQ>(`a`3pqt5j5$1-4s z%w@EJ6*;c$FTYE78@^vN;9EynrPUdnMweN?8Kw*g0FQWV?+*~MoFBGtTaA2E>3qAx zk>OD-LT><E-O|vDu)+1=K{a)Cpq{_`!1n|Z|59GBgD@<m1~5C_1}@OZK)CXu15674 z(47BP(+A*ejlQP%-)ibVX(b?Wu#8w8K}o)(2nADeB0(8jjV*!<0WZD<h15-sivL9G zLmSbDW1H|poI|^XF$o)%Qb8%zW=xrS>IUtfRLeNF^{=!*r0D(i5)%+c_%ZZxkqm(` z+q${m*VA7iL}B<9a;~Q+;*9tPd0Q6MN-@=)*)3xkSxGVDHVDp{{v0+<iutVa`kA8& zIM1xckwI>k3*(^W&Yo7=1%qcuT^x7}y#24dQQU7&NuNd*kX*2eNp3K@#YZ{%<G(Pz z&c|u&WrZtXmlBiYvMFqYuR;MCS3|K=8W96*{B`-=tAj+5CJM~G5j*r~WhuBtZEc~k zXpYg*AUKpgS5AbvOOhnuqOax-a{km-D9X3B`spuNmp1;kDowNYZu*XMPol-;pR{-` zS82LH3Ff|-P=WpfPa*br6Qg!XKk2)0n;cHPPukF@$zu!;p-XON_$xo%gV~5@z_I5% z!1ro}`z(2!xhdCko^GQGE`c`+K2e0x>@$&*5vM&UAa_KJu9ZwIy=zNiqarm?O8~A{ zWFAN4eMaj|MzfUt+X5+*p=ZeY8a0UxC1Pv=g8ZQ5V`WXwJTV^p9IM$@TY}Z^Ihz^9 zzXdsi@?*8~37a5r!on_pq^wGM+_z6@@AHJzmm@;MPej0FloM&^7@|7IBk2o~$#U;! z71aZ*Eb&;r0}0I81n1_m%Xw*?%tVD9M&$v&;2`XSS;=Nu{OFE--QvEHq5yafnv?nb z=yW3A{26l?(TSf$Kj6c(l8e>Daj6=aPYZX!z$;DM8c?FuIGxsdKwnihAe$+2I61kY zS43?B)(Z?K*~Z<tPU!Z-`yXfg*0jHJX7%G@{saBD2?TL)OzNL5r34(B#p@~}u19ab zRUXe#k(6(uYr;s55O0?pK~5->F>Gg294yl^kt~y5PHEBL&m?tzlKg<TT9p$nOz`En z@q?GJ*(4(s(#KD?ao(9t*(_8Lfnb}Bc0WFF!0ek6xCtRFzO#N{REeKwwx0#rZr;$| z(jHXRy<yuY%*hlmkBZnGDBwc`>{#>@W#U*Tw8h({&25EJOwf!~rSz8zS4WLNx>guD zt9HT|Her)Z#7wfL4}Q8OW~vA_P4%OT*qq;$?_F@qqw#AW>_j8D6NQCiuT2@M6zBs! zgQ?TYrG_$YpxvWlz<2H<ydM+vUMiispZ9%}UUQAl@ocHfTYisy@>ZM8+)%*#ZT@Ng z52xds5}YDTN=mSW{*Q0HPl+xwQrtqbmjj!I13LZU;Ml$v<8yC={!!a~{c#~o1U6$! z{85%)&cAwhv|-(JZ7OrU{?@lrwa;J7+boeR+A&>n64bGkTxrp}XemX2)|Bxxb)*<& zQcPkS<NCt(&muAu=;F-p<pD+(;J6LV5(kzKl<Ir!9E_jlilw>~Y@19Ijl3@A$w{fZ zgdb?*;o>dI&1k_mHV!S$O=Cs|Md0%(bU|<@WIs}GQ>#@fKM}r4HFE<$0}uyDI7IWy z=FlQFN){DeZOpl*_pXMgUmz!k6YI@ZpwKZf@Fim5V%54A&9#wT72%&r$Hj|EEVQ;x zHck@#+9GusMWu(wBZzUyS@p@wceCX?H;r4_qmziyek?i6emiZC;0Rx*us8-sB68Zb zF9Q7c*>b=%Qt~#CjJv}PvG=slsaOB2Io7n-=a=s)!q`X7F~{n{E#ttR1)(f;^U%8P z^_K^0Rl5;5Ct3~_<r%Ul75>~iw;QoHnjMoIIq7&^^FzreTwHl=%@eA`KQWr$#61LL zR3KiF5cdUs@li^@1UI&catDj43RfiPbdN1t`QcTf2t~GlIgB6p`gO|cdH;TPgLlXX zxP!Xs4YKoxO*YE!*Nrv;!WV@~SD*<LBrtpJ=;BHt@RFGLTlUFYaoasb8;sS1fl+-w zHyH^jV?x@pQ@JYLCe8Kq$sT$kH6yFvhyF|se_%KACzENI=9FOgE)%kOXZn{F=p~eR zk;R(8Mv|_XMx0MVh^_4O-E4jvuEn}!I)9x%Iu%ExJk=W7bLtONmKFs>mgX<)0a=v; z_Z^AC&hf&P>!UD+;o`-8JAx*{itBA<%26$UY=yN+_P(z91;#^D%_@n_^lky71jhy3 zJlYP0&?(X5@mmswW2_O^ti;eAjVmrh2@TIF^BxsQl0WD-u(*4ZVzl!9qH%iFw0ph; z8N=#1&lq_Ia+-P~Y^hRa6JIznYMx$uaW3Cs61%Tx`vy~fGtOv>p-jna;9A{^ERpU& z3R1EHCa>Y!3LQEY!#`>%s)g^we7vkWBe(T@Hm~A}1jL@N8CpY27tjZfG%JAiPuZVF zFN$zR-$Cz@a3Q+SM{>Ca#ddgw+%7(j{$=-x8re$v;=ZC|x{r)qTxb~J7<Li)pIele z%l<pc44sl4re2Hn&Ysy%kMqS6o!><NX+8SqvW)7*3+o*d03f;Ji)Uv`iaAanB2^u) zQGQNNyyKL@k^<r;$59jfTEO9bJ<LS|L$Mp$3zHblR#aLG=zdp1A9)&ZM%{n<#gehZ z2#Mf}m>l#rNKWW)LEhwFSz7bidtm!HG*YFZkVVzvN9hm?H0ptnJR<804@QQvJ?~bv zLMseAQIlMfj}@6LHwrZiI-weBh%^~5K|mjx>;n;1N?e~9!D$t&-hc&8jKCPO**v_F zU!NV?&m;zINFsC#s@Gf0MC&}~C}=zit>@mg;ZbOteOMZ%)Vw=H0Q;^Tf(+(Jfiaq& z+?ONS`?5!b+9kBOcx}v>>AY=OI7B&TwWxsk+`Xn0s!q|u&Ns1FsCXnn5tKw+^F6+! zPrMR<(Te5<!<HpUrP;gUZ_Ybs{%~;HN@=T0z(lSajSzE8i1sg=ZbSlZC7N8iTMrvn z+IF?~AH?&)0MvGwx!{<S5QDpLXl=r<@H&@OGt?;>Nco&Wf(k<ph1cfN7qKT1)S`T( zQ1p=HnPBNSi>e(Qa^x_;uAwb0Dq%`v)mKTg5{+OW{{r>z6!VU9B211S6(K%4V)BoG zHWhb%h)RB$n;OF}M1Iq>RDWfibHzm+2k@mL6Uon0@qJ|R5a)aC9K_0YV#d_T>KW&& zhf}`a+QyP%Tko1_JGe$^KyPF|f5F^K{LCkZz?|l$dAV6>z!NJ?@;i+MSdqDY7mim| z4rxP=EhMzNaVmdH4vC4f8tEl`B}I!RzR?O@vLs3D8suXgd#5U(kHFHMqoM8x$YnC= zt`0W08`hW2@XOssWep!LNx5duSF4I=r80pLph;88eyhfY&4nz^v2rd{@;{8Wxlws| znH>_Dj%33u=JN-tA28m}BBZJX7U*Cg^Q0IpZRdL?NXFYr`c7(CTBkHsGOl_RdzHtT zH^zrcT%F>x#g9hDbu=Q$%;Qk80Q`I83;*<e6&Fj?Onq0ZR2HE?175Fg7j-VGc+>OE z12*u<z968wC33jcJKs5=PggTTvuQqKF!|?prWrB!=d)ihoCjvdY}gsB_ywxr%nVSx z67>P(;jbM4y+**L{(acozsUw2@UG(Asj6EMNfj<OTfRH1T*<(QsNO6<L3^*ttL?ys z=avK3X9b;exol25%V84F9QTv?N)Yn+4;tk>d$MEbfp*tJz01w6w=2S^G5r77;s105 zKDnSrQSIR+*ezTE_`V-#G%_>VS0fE>HHF%+G+nFqZwC|Wumnaw{I<1KY;`iUZKf|Z z8MzQAsG*s?wnND9nt;})V+VJBOETAqDUKx}h(V{<*9a7yM5T2w7S{23I~voM!*Q2X zYRnoka`G(fz*6CoO29!N9O23cGyfPr8MXaPqUaU=D5COme&|!p2{8*=G&$0PS=o$O zmG2S3TH>fkrN_AmgLdAJ3~D3_EBPBr^rPgd>rhR}Epb14G<?}be`Od-CR(xg=n*+p zi=Y9Po$&y@cx@G#G=m;Pt(jw3{Y|_zN<y^@29h`)hwcwcd1%<!n61P*$I_y5yv3jD z%aQ7rCuhSG?MQ(U6f*Q#Z3rN>vC+xO4CkGoMege?4FwqSnrK8qN?IqxFjCe*wSFCj z9`6<g!6XL;*<G15^<I8|WGs<g@qsZ<(L&w6i4}uf@-q-ISQrmcVm?I_l8SyL{I_{k ze&%aEkJtUlT#Mni4$mKVGVaPrC^5n9hbXt-{uI_nFB&r0;Jg6sz$3kl?gb$~rtX<{ zbje^U2tMkPgfs&^j`3DdZlycClrYlk<fmH`;gSLdZlf}PJyB4arHbwF;`{KSuLsX- zBy%%QOc5*eiBoRhSY?=r>s2V@kxs{LSN(7?l4HGRMK)tp&$A~GmDT+*y1E@=dr4@( z;^>c@vSmR|Gf#4&+-#MbmFCeke+a?igk`Og?D9AMYR%1l4pOYvsCt@iPvdJeR5dwg z`~*d_0>fJgHlVgb3qC8%iV?d|xY^Gy6v|yLkZfw~0F4mmu2B4^RvpJ5yXxsy;mE&O zg*NSJc#k>POcYnT@P7NyRA^CP7s9W!Tpw8NygLMDZZ=D3y<alk0&}(=h3!6F@8<f| zm>ll=6#711bPJnrAgJDB?ppjelR^P$3=f$U_E+qSJvkLP@*@5&towAJ&xaD<USoLe zI)VPgr&2Ph;zVv~OBckc?qBN~NaA2*XJOX&VFQgH8<r-Ru&aae^y?AqAbxR2e;Pv= z(QUR|QRLoe;p?y&6-zpA8fVth)ZG8Id$!Un+`K*`P3A!4_+!WFAeP`?R;1$#ttBfq zBnVhSTuw_#)Yr{Ey=)0dXIheTWW@fztM7kJt^?zrg}Ar;=JEnwj)AosIYk>_=2@U( z05<Wz9v1nMMrFQ^<x(3lS|vNeFCjJ*`m~6+tV8>+&=V~8ww>fQ0}VO2JI%!Rvg@%s zRmzp`p+4ZA;T&iFPCkh&T<Sl)5C3t2r_qB&#Ok))>`}|2^Ab_|^d^3SBiGL=tor{t z(tqw~Zg5DP6GY5moycU=`Gf>lp<Qp}aa0(oClGdk6v>4c_rDz#QN8pS;O__hj&AiY z&E!OGYhI7oAH=@3LGj`LI-Y;pj=OQ8yVW3FW{M;|?iaKJ0Vqt&%%D6$-&H9h2Xp_| zhgOgCReyj>apHdj{oht);^6hvXwX$jF_W;TQYe_z0jmju)XoJ<c7#)u;UND13GqMY zs*{27B!?iAZqy9z>i{KR10eFgzt~tK<g{%86`8jG>%HAyzzMi#7%2L$VBPt{8jtzk z7~y}`?e_Uc*5m;zo-j*yaZ%A=Fy8tEg0uj*Dsj=-A!*kA?{~pMlLHRPIv!m(@jRyU z61lg`B)fco8Mu^M@gfTi0MOBIW9E!XFZSGTZ%n%1a>w^;8XBgbwh|Mmq5~}-1F*p5 zg8vOr{&&;5|15q}mhIRC*2P*(WYk13FLwg4cGGzPr55~C^=~q)e+jJPiC#g#J%mf_ zI_-jp<9=QzZgbJtKY9AUA`G%8=pTFc7&5DmKJe?Eini&ArhFbReFIAF-FnlIvCk$c zkBpoNB`1E!caf}N{-6H!e$Yc26F}&ys+wdN2Y8<g$KFGngKM|<r%O|UBtJbbFFrID zl@pf!C49{*yoeC9z`l+=F3`4sanH=IlkBI&O(O(L_1E3KU6{k~`>rT1f%+rEu<?s1 zC1&pKt!b&L^FHFt*)*Hd|EH$^97K&Tyq^X1o-~=i`Qy540%fmoJdu5a=y||5ht(F{ z$HZtt$^ZL9!zz4DjGy_jy9pJUHqkhv*<kaHpFkkY-mb@uU*}8U)-CG*;5NvdfUB^g zVni4~S^QWmj`9CL`I_5*7NqhOp3D<m%g}l}Ss3qWH#(e&M*NonU1h@8r1}{M8+wq8 z4p04ZUO`Uss}YBW#4JkEmg2K4G50Xe;5Yi0WdGSp?0>e>vHVn_{x3VrM+??WN$?!M zZ9F}!-qzRYP|Hh*Ej~00&70~ZTX|(gnt5dvrwI7h>gX6cj~G$VdmUTSsssPk!I~6! ziJR-#%k-n?9|C24<Em?4Y{`C)#n5N7x~7A_E0cO4TN}xH_|bj&q3=#;kUJV~&CYT! zZRHz{rT^)P`uZ(U--i!$8wd`7Mc$nro$L+&D`qz~cv?UR)V=RW!h<D9wuJpuzj6CD z{DCA%SL^{{G^I<7;dbaf4o0gYe;;bU#ZT{Yr;1c@kK%3O7W$p`lEUr5J-4M~=tefJ zi|-HT&wY@uL%E@6b3U<q7^j1py@|98P)#4sQ&iksHXy{veNUrE-qtV)6k{}jez&NU z+WLH27bSOEmr>`y(3;v=r$u!|Prg|%wiaqBs#nI~2~Zx;!|s9wR5vO`a?*D8*VGBq z85}Vwo0ZrA&L4Pss2eYY)^(X3<gE33`%<VV>&Y@y*W@u_@tIqUM2C6fdL)VgrwJU9 z4U!050+7)6W2aQ^Ovf}oVmf|<M}}SwYygq7+Ns3>7r;kC!xGTlVz>~Ib#ZpY8b%`j zgz5*I2|tvi7x6I!nxU7>Pi7eESOwvwKcTi>7>M)AFdRYe(7tYqhJ?k{EockFUffpf zed93UFhOHgA{3G-{fVIg*WK5R0M@XU<DIgL+zxmKSuHuO)5Gs%{mUG~{>!BfZmH4I z!H`200e*jNh<!q*5e=R+D#~fugQ1<wXfrLLkl+TI%Li6sUy0m({Y4GXM|0$=A>>cS zPih$2AGBLo9i%I=d_&r1>wEhHPwC<iMSD7w4{8&n<-V%+VnK9Ti-OP^ih5+;D(yH! zPqXQBD@A%Bt;?|d@n&b^W)1mcj(RsZ(z%j(vDH^rk(T<)W0Oa_&RiLP`GC@To^_}Q zelK#Fcc=>;okPjLC0%)PF7${zX1*U+p!&R`CnDc?M_M|}cNvGMRSdjx8APZmV^l3{ zeSETg>v^F1b)_glj+wai%P5xbzqY?^C-Fsd&x|N3;p@tMmgi)KoKV@vv{`R0&lmWT zp-%))30qEdBS@6=Kb5dH3MwgqnAK{ih{tZWG3EQ>j$<)WDkRoH=aK>xNb4fWD?^-Y z8#1GGvQn~YB|L-ltg`ePpx+nmrvdyQQ*FzWP>(I5ONN%UdK@6r5_webTY6=Zk>Nci zXEkxw<bA2{)f6k}(14-a6Bj12-V{Br_IO4*0yIpHU=3BnGc!7;2?J(e{RCz`L+H9J zH8&`&T;!QVAg%8QmJWby)pYTCr<E>$tG%X!`v!w}$2qe*)aFQ9@<*~w-hT69dch>4 zvu5@J!UlTMPW(xtm^ZSzjb4d1Il6`#9<%H{uGfYr4EzXTYq`wv=2}d_v-ha%yyvfQ zy=det+Mi~}kR)y_by{rR;k7TTr+>6E{fViz<#J0Z$!u@5&ZtD>Tp?Sn;N8tHAzsNd zuQk`&btBH^h)!B9S?`5Z!<JTIP0B@+&Ftj?K3yu0%$%ACzg-B;OkyD$v>0-sDMJyj zcJ>l)u82SV>K9oIfg?yAynUfr(jCG48_+(_p}qJJaUADx$@P*UL>}T@+un;_gxxiK z#wbH?80+`#t|-;6B$wAFYH}=XNgf8X6=2-&3Mm#(Hft>%!(n@*S*_`lq`bhOaG8X) zs$@ywe(4SQIYwuIoPb4v(2Dn$EHWpyZv2aa86gZ}%mVbi3I?ST7%ey4>mJVCRaOY7 zj1>AUm?Z=GMb+kA5>}Qz^+;0%TFbkdu^tQzWvMrZTU)F6`oQPeHzU8#GNn<DEpHn} z;64Km%I8;MHSTY2)T|(BTBo#qGRjfYuEyD!k1oHCN%NMWv6J#D{jLJW5Q|_EWb?ZF zx0bU*C70;z>Uhb{AASuf@74_8XN7QvbTAb<k#l;dRi(U<pxqp96UOrLpjC?T*|MEJ z{8gHUeOjL$7TE)rm`pf)g6c$$;1djYOVZRu>;H|eZ$Io@8o#(uXfp$)j{g^lH^)I| zzXf~kp3o~>=#+}I7StPcF8*#f=Ly`9R->JPhKS)^VB;Triw+IeJWXgatCF9S9O<lu z92R3X0n=q-`MWzSB9Ecf7k^jK`LcR)H`)A$t`sHzv8(yKSf78{mB>GKb?0aB6IGY@ znTK5PyyJKk!KhAy1v)+Ua}gKaU)Rf_WGgB_=PY&tij)XTzkp!`Dy)T41i(Cs$efM& z3e*q(6+^C9eHI0aAYr*s=BmTI<co^BG=;d7XGd~Uk;LyBKgG<mEc$GLuUT)0&)oL6 z?`z8*{11;lat7UU6|*8uw2*evY!yj-2F5}Lb+L+Oqqp9WQm%SX3zkKlGl?*wc=ioq z4JwX@{qq5A#cE3C;)VDaaeM-10%+tA3P~3l-~6D_<s?k`v{2a^OCpHpRn{nqY;mf_ zvFMesZ0C}i?cv$P?WY0eOTJtpZqbDXBVBG0K{eMNxICjfECoc828k_{WZZILERzW6 zGSJ){;V^<q0_KvcqMQV2#=9|moy0bPAjPZBB$LzQ?HH;znFzTG1Eu`BQb%+AYL@9j zX(4R~7;0Tx@`%t$8<^zX91IsQ2cH64zn%D77-Lfa@$OfL5c8<cpb8nDx7@F_Wnk7y zQ6X`JD}v+1Z;9j=`!X#I2muw7$or52cXWO-sOG9t(BWK`8}c0i83^<8jQL?IWhPQ5 zGxgBC8J`;psmK>GA3N0v;=Ma9npv~=s^7*V`a`59cdjQwmI|zp6n|G^z@TGmNTekb z$fcmY-K#-d3YVU8rIv>wB_sdA(UKEkqZODowmIOiY!#}2(^5!N$J2f;(KB!3Fz>89 z4-X#{(kL{={~1nUJd#u45X~T!vnrbdOMhD|^LA2o9Pc<TZmo)BCP;mbgh)?ayc!`W z{EO7@NY<{=$cg`5n@0cg!l8>g*xnr`mrc&ahDZ~qvBiT)uSPAk+)0CvB!!^;EILoL zc^D2Lq5edaINjIZ|B8%atz9LW2ehS{a>s;K;=$86&ck4|A5_A@J07pIXIs*0vBYcn zS$994VMv-_?<YeeR|GOXlJeK)&N}``%s@M!3|zt=2w(hFeHUO}*8ywWjx|y!l_iM? zbSfHq#{2w>z5A{gnTje6&d_a!JdCyH0NR|KWa1xW|7-zom(|b5%9?c!)5}jovX2Yx zrpLH49`13Ebd=xQ<588$)Hw!+^H=VefKJRIoOz=)K>Y7;^cVN<N84mJY2uV*?0bLe z<)%f+SpCfYamBbnr$vAM>jFR7V(9QbFHfwlyC{QgE%u_q?*V~?#})K`eUSg$q0+R0 zrzo^IYIKeBu^Ab7{R}7kM3s2=|F8glj^DsG)5-(5_IgEb*4gmC?u>{A(Q1NH4}(|x z>YORtRRV->vVxRk5anv3D8?km8x5~LT$^NI)}NAtiPNh93KH0)xbzu&tlLNuZiNYJ zoOMdU`cD+8(~8dp0wW@%O9Spo@fR8&jGDTOJOw!Q<icHF>1@Aq>p{n|?Wrp_ixGU2 zY?8WNKzH;iDJVy_ZG{;is;9NaR<6WhrlLYJ!!_8bXE9UNVEv(r3H7b|H&OTrLWw#W z9l-ot*-879Qa$3gP3cN$MuuM#k4aJ9EJ`c3)u4>R+R<QxISeux{)`f_IA5%Fh>^^d z3l@UpH6+8KqD_37b|t+8fu1-YCCn5{Jw?1ZF?5rpUPau#gn^8dky!{*jwc7CCcg8J z%2|H=X#8pZ#?8DhUy<BQXGKcGd{hCZD~|<+hKx})iiyOJ^y>1Z{CcpLKgg%n!aZ{x z_vh&})y1S=MAcvfH7CD@7C?E<Kw+2oN2!__GH0qEz<*1`^<uMi6~FRu9SGmEYVQ}R z&Zy&PqT9UJ^1sX4Ju%N7I|b}e!K|dB%@W+yQ7r_cp&4-tYLx2Vj07sz*ewcboU4oN z?_A~#6n|NTW$rTaw^XMY#~MQD0A$4drZ!yac5DAE%66q?5w|E(bBYv}We}c*Jp=R- zk(b68JyLqa#+hUGexPIO^Ia0`Bd78v97{pIiRYS0J1RFowz+#aEOSX}R{2$|TdAp? zz9KuEXPzL$`#WaU$@Wq3!D-Fn^kNa-o|+uJTZEE#Q!=@}FZ5`&yDW<nRi=P)Hbmgm zeJajlNA4gxXKx`=BQCPqm*JEEZQYit12Ay^MIg$Y@e26G8t4-0oX5QPH9-xhZ!NKE ziCKjPNL8maLin94w);Rj_m6QMYunR~?*4hQ!iRV%-(8NVa-PNf!LGKG(NBuIg?Qm| zHYe}Z(JeGLhN6%D_@zkVz@(b(mHyJ66k-YjYDDC$7Z?GT1t-r9_l$UaR<SAh34Ofp z2jwO&D6WyVkQl$WxH`}cM~X-naKJ8d(l6G$d-Vz{LJiYT(E_vT;m<umX=tej?&k}k zHM(<US*W5B5d(xEF;i2WLv*km@-0!T7XDvI<oiz``m|#5Vnrxk&Wz3B1h`T474o>y z!+U1xp|@U<8;bbw?UJL?3fTUwtteFV`Qr*M6e1-i@HToBl2sResZRucK3r}f;ES8d zmk~Xal@{Mlb2f|T*BjF$)CD#{a)7)BG!V~^gIvJxYg%VP!(@)V3#CEy%^3o03`-gf zvH55By#^`l9Jeb5f**-GjxA=LbUjU91Z3Iw;a6S4d2v_c;>f{8qHUBGHeE-4*GSqn zP(MwJ2`Q8=X9!$g2qVvJ>ERb>-so$3>go+ICYL{Ti;3#8oh4U!q8^35kdTR(*da_& zxVl^6>FuU@k(*S4NH#tmKlSqO$IEfJY0K}veB}!q#0t@iG0}<AhR?yo){tQc(ztb7 zEz-s?^2Q&hps1#<7cuHdU1*Y5LzIy5>D|`;V6!x6X=0npxsu}HjM^LeZc&5Hql$wZ z2#@wiSQI$I0O5spus)9IYMjR<aT>`Q?o-!wf`m6>yg?38P12d3wkL%;78IYTx!5W2 z4Ut?uQ$2*aoUC5aEZP$8#&~5RN?@Os8MClLXRix-+K+}RZ4hBwMb9&4iAMtWawp|9 z?f5Xr_kx^aAUatND=0W_7YRx#3?A_q;~~Cyt5TV8<};mU<$LcqQiA2GDBos|7u+t) zk*ogKxPt!FPE+JWoNtlJd4TynK>Y6N{xKG$TF-IU>PWolU)}wsbu7a5u!;qL?KvA| zqum%*FxCmq(5-4QCu4P5w;F!^kr=$pzFUIGzE!lqX0%GI5;Ozl%PV^vYc)}nY$2U) zVV9&<;ZrzQz}=e1x^keIQ+%%3>*?+6_!J0bmHW|(iH9=Es%1(-kO5*VS|oWkLuiqQ zMb9s18ex+q53<F`>>CdqqUe5#9Le7K0+W%mK>do)C)|x;N(T)LDFHmW!l1F&$VY%b za`fO9!jwdCD`H)PoF!z_R2l-MFyJ@ZeQKHR5t)-ZS74_xwLBE+_dZ@4v;ZNbl`<*^ zY$}rT!yrx?wX`(eQ=_K-zSdjNX_ik2ZP!u{{Ex7a8fyB~$_|B1#;q!$N(St4H~FtS z&(&Ni@=7J1!9#AXpN(a|%9P{pa(I=_$&7g1CnYCE8Fb@=+0*f)fSx!)c*!9{a#qBN zx`S$%9eR&(_fjuZbP-NmkV!#*Egy~Nh5nn8H0FckB#Ubdry;W&{Ud4YWB7rD)8fBP zz;Mw#L!bR8F9C1lmi5q5%VD#={}x01%L@8?B^q7dZv@_^&hd}A{L-*>1Xyg<Jk_Dh zy73Ig#>%;}l@i$$`?1u7T6>#JqBPEnw;~IDTfQ)Z?uy3qALElChY!UXT{DD4Jj^gl za8+&FJm`0p@Ptq<>&C&9uDPq_WV6j&nf}+WW~YlkGg_Ut78ft)M?2gu>}%Ir+{K_c zE69uqS3E>ZHGs%cA;1qrZ5!Ag-D2+F3?-skrDYT$ICOJz=M)fspzW{>5nI|wI@f-C zH`_nN*>HI-Dr5`#f)w*Phvl-k8tXPX^j^8nYqLlGPUbGP;nwQ?z>food1H(I#EH_t zYNdgiU_iOApuZ#cB0Kta5`CX=mn+cMLgR2QKG1P8j&Lt0&&|Bj_Im|NHw9hssN}-U zVfhi&Nt;_qH{y6tqBSjz38b4p*$}<^dF?6T^C~7&66$#4Ahz76GWs8(OJ(|wCO<Da zn>le2g4;^5S}9y@@2E#ZB$L_AzD?xtu31iIIW`|oq(kW23wGQ$D4nnA9^Nlv4Q<p) zW~WoYiqJVdQF}igPY7pb$srO;i!=q;X}jl|r0xeF=z5DhRP9kJj#2GvG5d|B+YWQY zms-YW$Ii_Lg!I=dln?y0Dvo<qa#*wJgm-G6fMKg1qR&WQ>z^(C10^T%qbg2<i{8e( zHjA^hjCz|)1HJ7Mem5T$)@IjT^y=5DybEmC^Y7IROtBKy2k+=GT88Sxi_#99KE_47 zOY_d$tTt<#iL6*2%|`kpPRXo>IA>OHfzP`{S&;UM+3f5lr;@(DMKX45A-{+SP+wwA zfebD_JJx26G_S6Z9MczOMg#<>OPsR%@lsrGI$z8fccpI5#k8XQ{yOAKswR03%xxR7 zrEmR<3uIoMBzBx%&T4hEh<9IEZcHu{n*QG0fqNUJP3u3Bfp)h$JIkiuQ8Js<Tir1v zD2i0;P<^mi6HPxc(G<Apmy+vw++#25&j0g*tZgme)!xj3=vY3!7jE{~^pZe}-<Hua z{hwUuVGAb0cq$`k0nUNmnG7k+?-lOM`csg3W(1pg+RGww+L{Z?ozF-PFL%e_{%PXu zmr)G{Lp9seWA7h%d8Zpc-P`g6xf-Mf`%&NSX+KeZgg}X!gt)Zg7Ir_-Pc~<N!mmd5 zi<fx4vtP`xgdtp#&(P98R(pY)(!QtEvCac6uy>Ut3B2x|pKRMDS0bqCpKEW<4wiyi z>??7&ZB65exEI!ONy?wsOKi;SYP<JY5s%>l1RiaCr64V1ET5Jt75Bq@T*)PB7Wv&V z#JaLV@2KBsa2woq#E!L@-#8zsgv-C`6aWpf+Z^oTITo+n7WCjP>k(&W3qsAt1a8~Q z(yK2s7>y`&vxvM%Z-=vb9A0d;>T0{=5)Jn0raLQ>Sl&HiJKR~LzU^ekicpdFwEN?6 zCj7r-e{aUO-m!GUz+;@iPzLZs{Y~{}GWOlQX7XBgqo$lfbHnEdUY0QUP8zSeXhzI% zvo!hi)e6t8)(m4(OG@c@P{L=WmQipDT!bOznrQ&)k_lOzU_~*TqwReSt$}@tci@5e zM^~#o1(bLmPWzY(xS*QX^)%~DbbVk=;1qA4g5sk~NkE5$H@Wa`%+|Tqn#9VnWvTG? zE35UydTYbo^R#DzYf-d>$`UP4nl8UUxy3CI#~-s|SoklqFA~$(1z`Y}y}xzap-N%m zkR*LD8o`j4??{_!gmtT8CeK0yYT$yAzg-Kb-OO*UlSSD~7m$b-P8785MpY?Op74^T za(3YWWyh+=*4hMU6V%gsIXxDWlx-zi%*cw|y~>%nZY7v>vXc(XG6^e^VS$W(?u4+B zDeY3?GKY*-=^~E{M6xu^)h=oYLRTkpISEt_EiIH;6-_IRJ?m1vT%7|VgTR0e4G6nJ z4cEKF`Zj3~ttnr#$D^rs$YGLj!K%^Z(EV!2f1PT)0)V@8Qrsg9=hhI?t{dPMYRrh} zs(TyX#F90%-{|mcH9f!9(E>@px&^n|&FN81ie*>u>4DD7p<pje-aI!)`C1%oCl+|J z3hhs%HhvV=z(0PWwpf6$*TNM-gNQy<F7m)zWNg9vxD7+`K4#Ka(KDIIjxNBxP6ygs z;%K%ATXk_CS@a0)XHb-IJV>zM#B|bQfd*iE?3INDb<8cW2yR!+RQG-C8-humLc8q8 z<6kR=t^JNDX*8{)pj3M{l;~)?jTi(oF?NJ1U&4ft&DatXIQ4K19DpdKw&Ib<je`{F zF3H)u<KZC(pts4Nt9@|DEnG}1hv`X$vn@*qG8;cLTy^piI-j%1l!dQLx^7l|lZ&Zu zDd;dUcqi`n2R2_XtbPWx^>C(Sr}_>>SBhzBvv!SWJiaHAqMHH?-DR9WiR3J10-KkM zXNoz|Q&U-fnVK;=9oOJ7_&Xc+T-tq`-UoChzWWBj0JnzohWjBx&-t9ms<YrhCNq_o zhPzJkp81Q8eGj7N3$JR-;L+Q}b6h=;Bh%jp5D92yBxc-dHM2a=@x$-H|MkL1dbyx_ zvX#_uH7g=yN;8l{wnQ6Z#BZiJzrjJgw=f`^y+&*P<>gsM+7OL?5B@|15QzKIoOg{b zh10y5uXQp`D7Y(}$1xbu&C&l^;YGs1#^ijp6(ost5M5(r8ZX&9k;%Pv0Ay@_-y-<3 zwdEVQR^fzaSHjv?sQEY7S<s6)OfMAG?oNr}w2i|~_o1E5L?x0?l3p*hzNHGReeG7p zEg43nCi^~?&jZR5X2G0o8;^V<^(3{L)n!=;^yIjjl!|Y?8Pu8&%ajRg+kgSi#n{@f zDYyYLD3qp=5d6!ca2Mr0Nx{~KPBgn95#}^6k6XE!8qL|(hlA~nu?oaJGJi2b+581I z@O+lY%|7guEh<mP>jVE;*Gw@--hK*GQ%lrgbGO9$ZX%^a!Umj<dTXP^6jZ+dy9Kc^ z7j5&09MnCL?`6PKU*yBQney5&nR45Sn77c$IL3+1R%34N)$Oi*sN<<`JsY)mhlq-p z^3c_U^gpS%zd~_L|I|SLQ|ar?2oVA22KaTfB}KGiM6LwMdXT52xxu_%Y#+r|Gx-Zy z5redvc3M8FaYYJ04kw^vy~ak@Xp9XV^8N0j<6>wmRJyF?Exvdh%?^SGst$(a!{f$S zi-(tgAk5WTUDn!XgC`IJi0+dfcTpDu*CuLnI|T`kTkNWhY|S=(<{Z1;9DNT;wQEZp zlwTK)%h!zf+{*OJQ5QRTv!Ar}j*FfjMt`B5uMCqm`;t8;;D8LK9(cFWUq_Q7^?Eip zau7wY<5Uo-5?9I1Dzx04bT{;Ijq&ELY`x=Bm0+O#RfOgTT2Df(t95Oiy7<-|-(N|% zyq^9)s?IT>?l^AyCoC@4s^vN-EPI*Dwy|t2bF~(hZQHhevTYkD`{~AW-_P^z_xjH- zuIqCV%$FFE@Vthx+T25>Y7e5Gl_}1c4yO(g7)N`*Olf$&bbFpfQw3?oa<p5&i=fq$ zkU03=o~|#w#vMXYQC{LXh(RealqUfv0As%?HQ#Bb`4p+kCaW;WY}q$hi-Rv`WQkU@ zgh|=5NKFV!&(4iOID|8CetGG5jXt5Qh%Da=gR^|Lv*CY;wplw3Tb0c`>6Vux6qDnZ zNXq87Kc3@x+N~DO7hA~_G@V3{FL^BAyDU#NtoRV%-;Tw}?-!%ecwD3}oMk){*A-@Z zuBBMg5nj(w*le`JFF$<^7~4Av+Um%&j+RYlnIiUlP;7l1SSeSI^l5nI7pPH|e+;x) zt&hKk%jO~b4lVi3R8Xr>bWX}1!chSXKb$0?9r=_(dyXw7=s219Y3`rRE<x|<S>s0S zRPILON2u@63ute?%m$5Tt54ac-32sXDvlQYMPN2Y;#N32_#$r@oMsphw6sz2*y_z| z)Zu;L*{T(}-d?7Dao%tpv7((xyf&+i{@KD)7dIGrIW3&*!U0>7hfU`%vji6;n;Hgv zK8#uXKtxb&xz(=I=%VepA>8Z4+4Ce_k;8o-TDz^O3(m`zr1f@xq|CMPR#YqRd&n$l z(>;zB)A$^&$v@mht4h?`m3N0!zS4lA1Qqt$GdQn>yG0{$tC{L{o7PuXn^akj8q-U~ zsxMKoI^=Zi2r(fd`W}HC<O1kXb8^RdD?$pk^w2;g{UJZIW`qTC5|7ma+1FV;VwPD- znFonK%fhtQD{~P7&yg<k#e-S|bHC-OHJ)5PlNVhM(fzs*2U!x!q%sZrxIS^+^+;c6 z6$dX6!JS+1oHQ>LdrPlabTu?+Zk%&?-w?P!BnwxDmOw63&YVkI&o*}DUuQ^oLv8|| z4d_Wj@1AN3|2(H6{cDLbRK-<xRTUtq-W}7M{P|?G$sF?J$K35oo^p5IJ(S3Rd@xbn z&DdrhDezR+7At+*KXunoxPM%bdebof<oMUA=ipy3A<q+E>(>6tS-2v}lB+Av2aF(S zW6_o4Y=2iR+ta?prh^aWOeZzUqFrWb?()wKBb-W@$e)s7+$Dm_cFWuiqI_>G{rYak zS9KdYoT-hThD9I7=MmM!<%pI0YD!4M2fPX@1m02(b~hNKa*4LG!-Qf3Ki8da9F_af z;AFY}pH0h>=^bCV9m0_HUmQr;Oey+>AVy`_2D&-C?l9j%kG@lum;}poZFBtIgcOZM zb5wMsGa_$ouUBzN*<>Q=#PTj8mi1wkA&2QHo;L6T(y!X@(ls$rck<>EU9YAt82P*< zg<6>b8l{zx7&8jq(PVW_T2+=`;%nTXP<r*&UM@;Md*8{muJu{7ZjZ3B?rguWu_fYZ zfzN}Tdke{5WA?iK&jD&Dni2B<NFXi)DbT@#^+6y0$K8+JUrS3j!j$h5O5DWHT8VQ$ z_%CF}Y5c4n`3%GqUrEp)2CLEJDZ-5%-9B2B)=3jb8OUe7_X8_?iED;-VT2~0F9um> z?FSX)|5~(m#8?_df$dkrsV-yejmv2@KY5-+-7ATz5^oPzr?l$&VkM=Ijq|_k)1K~B z=bqMFGuA(65*fyW%1<X2KG)<%K1F|2dTR)KCVkiznF72FSVT-LuR9?wXITWN11sl^ z94GhnMsg4F=?^2hW#UvAQo|AFP#BD-vJQ?>z?8y1tz2nNw-lA38KZ9hPxC)^Rlg$y zjY0+5=eu4y8Oc-sHcAoHU2T>jYPp;$S~zQaZ=KA*dkNi3t!uEdYa2rqF!rU#Rn>*u zD9O=t22{nG1qauK><lhu(Y~3wu3g8~UsQ(>`3_rrSX79Au5s7(eQ{c{oqEQZ$9L!! z{Nn-i2c;??yBW=WwXsbrkoaS*$C)1xWd1icv;sIO7G`*Z0Gr2P-n#oZ-Ak%>ButEh z&=YdQ3(VVa1pFRQa}E#pHmh6vHc^qN?>^Ge_)OfefOc2)q2AFd-H*wtW-{D8aoHzf zsFu7YSfMd{U60_hc0HNRZckWgyzw!jY1|vOo`$zuL0QnXyXS+X;c#61?0mXi>N&MP zna-}KfW}uF%J8DWVljLA+`9WBuvGr;wOD4t$fE|k?%v5W#od7NEI1uDnLC~2Gfy}) z2_8U#)%>0X^&;GBu@NdPF$N$LPuV~=e|sd<R+PM0zbv>iB!7|>-R-n(?jLVIw7Wa< zcU-YtfH}?feV=J*u-OK(lap12BK@#Gl>S|eRk(P~__-ec`ioX&2f>Qp#aUi{d3u>- z?9W@}Bt$vE0$@O_0l9%W=0CcCf}<g2tm%S+s!2+{JkPNwU{Rbcmiw9G@36d<o;UZE zaE|?62adZPO^)r(opOiN3YYiZ#uXQB8}qR%<9O85Xo=0NG*SIoY;)hq<C1R#ocrDc z{0|nXTsAdpUV}TP<sK_wv$thAo=0;cmF)b5Z^~s*7j+bFrlI6z9hN?o4m(G}e#}6| z29TC8PbaTgI(PkbU~iqd4fIG~a^~+z)&6OV@zLfx-vhlv*ja)~w8kmrFN+=GnLihF z+&i2t24ZyDf*z+dFz*cOewQZPGNjqa^Sx!Yb9m*gdB4}HEoKM3?#sWMb@HC0TjlNq z{aYewDCjwFeiLim+ixu!`@*yAuC8O9dapB)LXAQq?vYir?x^v8?*FDpu?2z(zGE4v zy&7XJFDMwu4EX4(<}mNSpyDeqM50v3<a8jn59+9o#cVzE#?Yl<d3UpUKB;(W=mS>Y zCg95pngU->A2L^jo-Yb**tiQk5s?J;_L374Ik$ql1J3edC+e<hOMfU487=5uo1ILS zM8^kj-oE0dv!T|vV2-qzoRPJ-WLU}tSy>dn8HVDv6gp9dwP>!R*ZRAfAl2lT${or% z#wRc`HqutMDCRB0-%Y_^tOP+W%NT6!#E<Q!-F<ocTU@Nm^LHTVzm(FOvlA<%aTAdv zgRFN~a&0EFI<*M+HZ-DTIJ785|G+hgoSL*;{~2B$!$F#29WFLA3ruK`&(t<N8JWpw z$4bW4d@GA%VZ>!=tGR=}7@Sml0#4~jvVF7)2Rh}V)HTeND76?AgW8p6Xbn^uEekD; z(;F6iC+;qnt9wiM1$6`d8Ss1g$ToeK*&K@cynN5I=-xE<4fPx5R;|YcR;SNA*2M>Y zzJb}Dj27wCr34!UGklin`LB*+As8p5ACoy9cpgy6|Edow34W)b4QP>HgyVfE)5eU? zlwBVmQCP}@{azqoag{DnGB!3elLWV}p&q>}-wo&3SO@(w?|P>1OdM&x_E>>oL(^2r zRw&M4GqVcFwwm7pu2e0Y3d8F+(yz@tPXiGf2GP*!kQw=PrHi=1QHj+twDE~6@GfJj zjZ1uJ?Z&Myn+QD5ZMD|d;oRD+ni_a2w!53J)OOve?;e4=?zc7^CO#pzkK++{lRJ&t z7ZqnF<~y3dWpjT75VCFm?HEE#e|dT_l3(I7OS8f<Q!g16<hl2+J<all9|8;}O%Z&F z@_}&>A5jW3CkLa-nOn)_Z8kaVST9~~k+b*~gG`;>$o)5yngy$by|Mt!ca~j>>t>Ik zO0E0b*Jr~g=T*tl($+IXF7;*^O%vSpR_ABn-KyP235{f?q7t2-k*iLfuSf3;)sY9u zHv9(qJnual%N?z@xh{pyr7;G_Gk&v+B4~I0BJgzTgL4<yk%*<3#X*S#e=4{aV}pE9 zFniaAH@uC_s}AXYmMHjbPey(o<IcrbsAW5z4FBxqavebU5qw)1=DAVvG_r9TP4#zq zJ&4GrFx@%ycBLwn-896crccUDzTQdxIehJTQMv(qE>Nv)+d2N^f|$p`J=ymY{}SgP ze|^wJ#~4HN3tTEw?X1hgo6y}L@<eTV!$!|@=G!NI)aOfwu{RIMq{q&q_}L_dukDPK zw#MLjYH(Ov|J|aE6Nyoj<_*Q~8qG`hn02#-sHiAhpG*^-J7tp^hcCmD3>ZlKaMLFy z|4feFB;Uc;oSmCS&pY^?4J#zXme(a;SFTcAarNv&>*r&f5(MBD>tPHZF`p|NnB1HX z5l-d{BW*f*@8(@|JLad`g=X+KcVLx7x)16y;E%;Gj0R=B^W`^6V|j_yCchks@t}9# z0r&|>iKl<V{l#%ITfxCirz+#oD4w^|^WEv?Ff+_vbKFRWsH}}ITf8?3pXDdw7DGMJ zZ3X$sh@N|uv>Ru7`V^H@ZCk`4v~}vZW;(A}x<0>t@~t9yz4Vl;VuD;TAR{o%2Q+N0 zDLOQ7>3uAx2=|q98O39~n!|~&qucpiLSJu^djA-a3LQ&plv|Zt!55>8;)}IqSnO<M znwzD0R};O@P@FbXoj3UMv5YosoM^Oe6_i@<*hZ}nUwCK#?D<H~N~AKc@Cf0%AI&`; zQF0${x8i(x^*L$m&A4m*H(vh=Z)>LYr_!>duDt8#^J}r$iZ;dIGUE@q^L&#fqEvQ_ zr9dhja~?LT_VJk>hwbPt>^ln?sib#)b&E1US}ABUK;LVM<9K1>$*w*>QZw(-ZORO< z)%fl&ykU$;BUbE~@>6EDHupW2=gn{Uvl1)28UA>X%PP3DdM8p~c|LJLyCI4jz2N9! z7FP!6x^Shq^ShArh<^P5k;iiS2c-nYb$L{)1oe)fY~}-dkM@#IVSG*hT=ohPe8Oxx z(464^5Y5+kWi;h*nq0S$3v0@y?<Oq2$eS$(CaxN{ix#m<epy1{)G;EFOD|;{cv{S? zZ0bQ3IDDR$dKP+8)=I*Ib#P8jNMWpzu4tL_xI6xM<Q=`-B1+`ga-T^<Y7?HSkiPK@ z2(j-IB3Ya>y~VJcb@I;GzAdocJqu)<@8J7NQZ*?zXRjW&N!zMn5hs06YJK-*R^AU| z&&pUQYVP3#Ox1N<3)#=uCy9Mt3<;`eGIn{dRa1$H4e5gEzQ}Q5Bwn=LrSMX3G!~4d zu7o$P+A+4hRG{!aAhcfAIF<QsWXy{?S9AVSGXX%=eBoPdcXy79aGy7Uz1a*V`=7PP zhXSCh5$<=R?|bU*%t6MR@Uk|myD*DqDnE+e92UPdsdk|*Rc+%&kr44P-S;c=rFLn8 z-B&NpWkdPG24kTNubRkXJ<XEOEKBPUs-d~VTJGZFidm|KzJ(&e`aYFF+=Wne{|1wp zh`;qc&U+SnHLd#~PMu$J)79=XdAfz=vG5rlJTxPFv0q<zucc#a9<gFQD>_M!YV{KH z)H5$Y3okn%#%ezpXkyvs&YkzCvQ33*-1ZlDsh&SeXmNg%LXzgDd?s|2W2r48FII7G z%S)e?JW)IHQp$e*0X|gEkVaj0SjkIfm)5FVA%9#0H3DlB)S{1rC2j#Ind?XlU8IRa zBS8{qb1jwgua_8=pu#j452a!(s4n_lIaY_ru4M^(#K$Ng_N`v=zkcxc5eX3f^CG#0 zrb-ev$59&LukFkjB_XX`x;c+#Ywy1ts)zwUBs(l!Aj`=2pl9n=hv}xQAJa864dDI- zzPM4{7-?8-rSdx-*tpzI%=j7U;uc1EDQR4w^qdR(4@i_O|50J^a)<g7By`wVa!Ki8 zA*IgFf@en<bfe`CU>%I3bDyik&39{dREpwoPahsy#HglSJF11`dA;TBrd&_Rc(^Q) z9!=izfY;<d%kQhIP)V!WMBK&6OA~iIPUk6K?@L~r>c(`wUMCy#bDw;&RfVpCLwAY? zhe=Yz3S_uxOg9u!Td2%(bG<xlP}#|(B-6!wI}XG)g0Lj0`iASxnSgVy-esRE7gXYG zB$cM~JRKoFI6<{>;rPXA{4FI!ZCYdzxf58Dd$nR3Qv(x71~_^xq<QyS`?c$VpzBy} ztKrx{l8$7;x-(PBe>s?A(Wqd0G!(gg^Rxs>)A}c}Lf%-aF!_p>J3H_X-wrzWr|80% z<QY@S_?}LG-V%nJpqmBVaD^QCx}bvH1)wx;Jm{Y^ZH(g+a(?{RUxn#96u+-j)9G|H zN}ho7j6qT+lk9~KNy_|dO2QU%;J9j|n3>2o2goen0!SpYgJP*he<QD{$jI?L{#~ko zjwVrbPxc^n;g8H3V}<~Q`%QLhEIe@&r~5%Y8Cd>)gWf`EmUrn4o{F+}<5^`QdQv@% zp9y04dl>~9Lk8CS5EN-`CysJEcgR)!%NDZgGy&}7dWRTiPkR$`Qg^~}>cJ2B$1baK z@VVb@+ygyN?{|zxlh9&l-!5kJG=*x7N6sQ8GVu8&oxY~su15Q`m9(L;CzgJTjjn9Z zcsXg%jtRL4mq7j6<fNoB&G5K2WkyNCpAt=%@C(9v|LeOVWEUoq^8RIK-T1h$Ha0)z zC|Akx`Z$frN0{)K3)NVH%#fF<u(tYiN5o;qY*dEfbwocF7Y+@l;wBGw$`j#@5XkYX zqc4!3bnf~Xg$^J2!-*b4hPIk?+OYRma%O-&1_t%no#p53L!OHJw>T;TIT~XGp5qyf z@pw6@H;;V`$(@0INy8ZzaOL|`rEx*c?}~R6NJ^6?zly3V$i&3Nad8J9<nCee+bTm+ zMt`7t`$zsTl_<U-((SdW$yYCbBB=*hjhvGua4W@IY})0&nOI)|R=USu$Gf|ySUxdj z3nhVSIh^thk8jc7V22wNJktrrIdyg_d;u5Znv37!RPXLbHn+ZAi&J7akdv8GVJP*; z#z~Sbsbs+@g0Fd<A6L(VV(EP-Hiqk|S5ni1gv<B?wJEGB>Uew4tIy8o?zy-l`A!5+ zX>^<B4Ix>eJVQc?ohNFLw)J((n-F+!&4p+0^*571nYek`HtzW|1#WlU$Y|p~1@Bh- z>ZMxO9_@df(T&~EvsZ>prTs{upB45l&Z#G<i{}`)?DPX{==A-URpP(L2AkReUCP>b zlKc-Vs`?V10{{G8j)%lkdIb)h-}4IJ2h85bgXF`Y@Kd^zqOz%Sru1v_n6Q}CoaREY zB(Xl@_gfY|3Q~gUq7=fC6grd!W_pa59~8lAd>%j|tzS~(4{KSwvF>{;ZdHWFq6>6# z{CHeIE|1LgnEmi&O3&BBQRBr!3vv|496luo3{lAsAC(DN{`5=Bn)|y{Aoq7N8tZu) zuG7(fv5(}#Oy;B+s~n<i1G!do_>a@Zt1FBk@iTr>3)M*=jrA%k*H)NxY%%iiYF2jr z;n}3Zm)lpdvwp!rDJd8+7u9-%A$2`zx#uyvSfu)NmEk{*n&VH=yItm}l$hVS!{fE1 zMjtlAjSD;0VksRZ>8zLOxsF}cxe)&-NHw39@vK^6rN^Wuwz0l!?M|jQVrMV&(pYwA zIu1O(OB9S%Ue?63Fs1)dY0mPDmr%wCv9yu<d+>q5PJ7vdl!}sv0Hw;+QV<LeME@Ko zciJmL9<U~WXnZe85)wl>ll;L!q*!BW=!6J+-9!0dMui<C>Xdt`cui8V%#ngjgAZlX z$lhS7X0O|r-S#bcD)@8ATApmsI#}}E)tklk$qU0gr-zymVmb9^A?CHCR#8b~lIE!K zRtUUk@h=9X1dqvm7|aWm<swha!^?FR>^*zmFDa>5xSJHqD7T*6u=&39jQX8EH1BmC zL3%vq6C$NQ6jl=Yj(dT~l?+g*#yE<UOEQ7l9}_5vso*%S2(0bXHE<etZ+x3j=BxE9 zbj`ePy?(!XU0+XkHT7sIEiJKn@;*sUu?-Q|JekZPPj=vhM8yL&7f``i@yJ4h!35BY zuftTYAnbm+tWUuxd$n~aDynr!ZBu&IL7KY4rqdK>z6ojjh`*}LIjl!b4l-417bH@N zLY_%^H07-IK#^*dq4^S_l1n8h#`hs3F$k|cNRx@xH9lu()6F7g$^4$#ggnkro7fj3 z5Zeoqb&*ruJ1!DT<Nbo{OaR@c&)C>d)HT)kP+4V1{B>dl^x>zxzJh2L7TqF7X%<%H z-Ob+tEbiMflCppKFpoa*MPO-Yzy!heG9xjeJq?e6qlgF^B`#3YcMm%<caNLtr+25G z`!-tr+U8n1VFxI`A>{A(4a9u`%1Otz^E3=M))q((-TtdFnvp72&uxQ+jY~k|{v5lh z;TL3S8x@&F4HDKJE<_y6GZ8TNyPNbcqL$YF<cnXdSYvZSdBks>(?>pnk&N?hpF>}j z%y#(OPgaYr`_5;&<A5ndDl9SHX+X;29Z;;58zPh1x#WLLEniBWW!{}4(@abVbTXZY z?R`d*T&`zTs&sU}VstF5JK>b902-I1oBnnsLNp9021F=h%>c1TQ~dddD7pstr>+QY z><$A7YkpWiatm>};Kf+ck{M#Kc$~s6)p%2#f8y!bo0*KE3qx6GYOJEI55g)*NL^<I zJMP^u9NpYqD@|AWsT4hBg(Y`L{JhNib59K=q5bcJ4B;8(@n>zfKsScQJ5_Sazhhf9 zE2(YLwCPV4-XIdcpP-O+XL?ml1D$4#sLSah+0hYUp)LK$3|-ij*@SLa5|<o#?oSn$ z<1>9qY(>vGW@te#tv_XHJR<yOTpBKEZKU{ksdDF<6ce09pg`~T{!Rtwqwn?!e+rEu z=T#dfcv-d6y~ZOgIMch8B;aN%8t#E==RH4?5|QICM&cc1cmCSrcb{+n5<&tlGFYil zC1=$5fJniV&Z(shkcqlmPfQ*eY6?6mmWmPoBZ_>B5eCfgH{{iNxpTTr3aCIU=?e^G zAdZnqLPTN$5%InOU2q6$3=S>sFq)N`l-D7CGJjsJ3WIkLHjSdV>9{^)byj~6dR$DV z46oxvQm>JG%PadP6sg@i|Bb}vl%F^ZF^U`8e;#}VVSK*;9uNE@RRF#@D<tQ<PQGmi z7h7o>W>F@Gd5hG8yx$$d5QhDGy>6e_HETWUM>BcUJJR{YIm%b4nWG(!XPP4Th!jsQ z0q9Tw_q|m{maJ#98uN8DM|QU55TyWu=vX@ZE1??4JGWxBmOt2xx*s;s6ndenCHpQs z5>Y(ND^mbJ5O-5dFAgZ47U%j^;9I}fD-=*ITAiPmdWyzgm<%=@%ipfT;Fn4qW_o!* z>h482F*E`WX`s|P6(7dfm*^e@iBb$_oy)D`p8aW|AmXS)iIzM>!Si)j32qoanV|bV z%-O|CuLXj>S>$$nKVYOibL|cYv|HBpf=;MF=lgNfRo4%hw1{lWp>2mEYqGpW5D^6j zz}fWw_Ef)DKot~We_Ip$E2~GzTnvy>kju?S2ot7RI>aV0K_J>I031puBrVz}bDPA3 zedW@MiCJt^1FV=<0D+W4p{iCUeMMJ}+q;_JKW$uD`CY`JTHPu?4>VZQ(d=cqk~We0 zVFkd&h&46`9FNB*cDt>Q$i|PZ*SkH<wE#MVWKDzLH}&3kP{(k@e59-c;n9!MYQsw> zhpxLOBCJR{CX_=7KlCL7{Xg}sJQE)+UJ!(c2y_Wg0fp$r7hszJ89#LRDPfk|X#3k= z*mBO-<l#o5OQ*hq3lwV={Fd8kQJmA0sVx#+C1F0YQ(jH3ZW$SE;N;`&FAsXGk<PN{ zP`aR_RDc$m#6<vqn`Y5N4LMINo&x>!mWCfZ`ylm&vi<#LRiE~Wz-_#}f#Bt~QHe*} zo&!hMW+i~x$VhDE$A>Z#wt@wCI?RmETouG-ebY9o`x5&{bdctI;VUeUgAlcpkf8rO zoaAiAA{>_y+pnKGWpw&&8e(W9H0l6h)86?ZWz<2$y4d)1N_aG)m<+yW@cEiJ;M5Ne zL8-v{P?&-wzNWm8FEO54UoMR@;3+(Y7FS-{;}rks(#42Ic~bw}{YI7x9XlT*Z8^eU zJ}WkvvOBSIXowkW_jHLh=Bux2M=G<H6zqfa((wJrCKwq6b+#|qT!;8<CQdm$wfk+x z@>Q%e3(ctpF(wD_#Kg+3)L^>=)P;*o)G$^Qc(?r-OGt|&1CJ1o?j^?mxI(~Ub;K<> zEEU_^)Ob;;qZXRbq2Ka3?OQdI(mK^Vs=0o!jGROi=sMAWPLJxUS`pL9wla=EL1K8p zO=e(B7ldf;#~b5YPgdybKFS+@>QqtvPSe5qIg2cTY%+v7fW8*>+AXqWaItpT84#5V z5VT$IIDrF%STzDO4jQ{1(gAEN5?C@2A9;DiguM+PGS_$pa-R;+?vXmr$X#Z@ncH7~ z*aZpUR!J)!NcX-Yrre0x*jEW=fwrU*eVq&|b`272rmtG~X6+l2VLq$PPK9AaJZc{v zU=TiFaV@WA8+h4+b2L}jS*F)2hp7yxB8&9Sb_q1fc=sV+X!<uf!Q~LmQsAn8^!}*9 z6@JnEd9^mVn2g2sr(LmX!yi~uk9wKMAmhgZikLreZtsYI`Po0D$@~s+b>}P!KMjz> z{6_6!;d#yUYlzOAc~BL*$4xMM;6kxO<<lL1?yes7LLjZ_Ak2pDhE?XMn%C++q&O^s zLBBrqqv>s3d_I#3;Fh5&WX@>1%9QJhUPCgaZAO)X0UsPeMz8~=(aldm^jdXG<t5-n zVQ9Dj;&^EK^?r#$6NYf^N$jJ|amo$VH6M?5rhp3c;if-X-#-RT4BC`Ip#j_pTr+~4 zBjI?zUYd91LjA|#Vdv`uD_}@~#4C?@HS<`F>ZRJ}dVsZqqj(&tTl^C{!kdYNmPhF6 zV!L?3coK-m^(@*-y%L;%jcW`P3{IZuOb8w_cXl{bG43v|iU3&TZQl07hV)ta76+eZ z)pidt`*XUvqGE(U=Wh&-0lQkGX3MVIMzxxiw-p4ie8U!N(QzW6GWPbM4rP#|ue^Dr z;<x(&{HjsUnNJE8{S+nepd-;}e#z2W8Fv8go^jyF_}s?uj{Wh!t@ypK_nmaLiFWbE zgWz1XRnbKH4I2ug!70TQYSBlQP4+V`dsu)m<0sN$X7yTYy;#q#_UWv?FJ-$KEhc&T zwjOn#j~+6h>Gk;I^TwUZL6{fA)8M-3qKKJF=S5t^A}q=iTyGjQ6&lc+UjJSO+?er| zhp3Q{U09ToYkCIX@nrYRJ`VPXpAQ1SMACRyHJSNL8lTe#NiX(Ol{nO->Cc}rblTNY zaA-uJPSR<5b{IL9ZW&K}XE0x&BWQnJa&+G7GDMvMEd0x@?lTd)SjW3zIP53=_!A*q z<CT>D=~hqIC2!ap#h@vTCwQe$`fUB_*ccE4i&V@dk{evo$mkC8qgOGTkfTyh-ec(m zOdUOt9|~<GCp;0LtlSv<8}_?VH>H))S9g3*)eihA?GkJn0H7wA_uf={$??S>m~FF+ zOk^kaKH08nVV{whPTdW!Hl!Q)!fd4lg-GoX>D72u)UjVaC0SxYjq6<YO(Hnjt4_6E zbncUd_FfE2q)q$_pImZXX4QcSG+@>36!zafuGxAe=L!|9w-I1KCrXcAzxNkBz|6Z; zVgUmggh_h+w|->z%<Kek$Vk&KwFYwP*vJ<Aw)N!`Bir<ZlBxcr*4mH?^z6645V*B0 zBdnj~#{E5?Sd1qPnlXRLQjlpzHn`p_Djv-?!voSq+`>sJ*F~)1R8O3b5pJD|j3#S` zrJ;je@SQz|ix~H%RAiuSBdL?0+&!C1u>p5Vx5i5qCxC1l6tSNyF6_*dGL&*jKmu37 zxUjNcA<b|9KA$Wry`ZzZ>j!jpF`y!wf&_ih>x|ggccBs6N$PC8qVi()24!CZrbKf| zHHiV5VwO!E{;x+>j3DR$z(s{GCl~#1lIiiN%>YmIPYZ%~X>G7Rtb5ZT<&b^W$Y3<V zi_VS()p2pkBZ(qKS6DZe*s07DlPmvt$5#((YX-@?mxpj{2t7HP!2R#CC8ueBm1Xq0 zi1vCaVv%>GAtkLLA>&2E;1@xdaroQ#h;XB(*g{-~<H;QjJWOJm+(B7rKr;cF@8kq^ ziDNYC^w<v71bvjmSvK~CCpvgUDtdC{IZuA2F^{Q0@{-o0&}-7WMki!&5yl5cX93dS zJA_J8bhgdPbCcEfY!9Ld4f?LfpPzr*Rq0#;%TG;uI0|{E1A#!``EqTO(In;?-*+Ex zB5i$6c;DZ+4AK+pFvfE!C^3G_l7%h+=H+P5$TxoPIi_Dy+C530Ac>ZGb1LNmFA5Cs z5z+;uey6DvKL2bZBYGMNYI{dnEW@ojKdmFe;>V;M@j6FvWD^~cwl@&#fNmy;l2CUM z{#z1<&ov@@FXpO9qa3s6c!wxz=Z+JUU`7w^;+Ur-wUBIFZi7Y!n#h~Rv{o776Bnj4 zNFl@f2BVF^M^q`h=(G=c8Uqchjp_BrZHw%#y+R%^2dU6A%lk5W;3_k6h_ludoUBac zkU?pNW)stx%7!gaS<?j1pJ;T@+ePH5lV51wvSeq)lfX0*`(|g}1ta*jaVQ>%{Xf;` ze;h6aX1ja|{A7|j&gE0CuNI(ZYMZunzjtn}Z9tAcYf$-P5QKSk|8?J}VTm!h-XDWl zL{1n#qMd+36iJI@2H&3ZrT4-)*JEx|8>GJKowaT~ZE_R3axcQJd~eKjhC{sT0*NfO zg?(g3?RZ&ev?38!DnUl|wZIk1>c7SrKjlvbi<xxK7!mmsc(LD|p2tIOyyN>9TC1?j z74%&)KF@O>Ka>R9OVsh+Cvkq;3ZqNrR~deO{wI+3#F>H?gVpVpk9C8{y=I?eL+~rc z&c*aFjO94moh~)xdhHoax>Zis4vJKlyF~q4a0n0NkCRfpNfeZLc!U9Q*Pj{fM9J4s z5Jt6{3X-}t>0m{{(aRs$1Z%z+QnEwL2qVi?{A8|@#<*_)`!ah~_xBmek7R~%=Hc2v z9WnKiXQ_;}w}M=8Z@<rub7T>149W#^aTpXqWSA_Hm{>~2w`c?=lbg(rPp2Ts37~>; zx=n|NoX-&adznIsb-s8?N;ziFt@tl1DbcuJRvRLJ!;&epuR@CKglcFHE=x?F@1~32 zfg!@wVPcm;xUd>SnH{L7Zuh(sQ$<|E#F4R9ZmLeTvvk@>m0P$8Jm;PwJ|SJawg$6e zP{M_mS@Cv`h<pbHz2gm)ah+t2^CSTAa1Z&BHWF8|;ov&O$h%MbM>Wbu?p%OYr=KQs zqhw0sXqC<$Yh>YX(~1?M`K4+WtgtwXB)`_;%|@CaU5}s9PFE-{I`3VJ^(!lEZ;$8W zH&%}4%c-1C_<*-30_3+<zGt_clGFfCXsFqn3%gAm-({+j6>3C*PGvny75SGdsY2JS zVaQ`&|FlyV-qCz^Zk<nYc3gMqTSqXHXCCuD!Dm@TiA2GmlGOV!F)Lx@$y6~>MFvQB z1to=b<TV8}g0x(4w8_X9u;1_3T@MLry|b}cksx`g=Q}==i;heT*@5TvX-aRgFb6rA zy=3l#u`ctaQv^ibW=($E`(m%x*Ds^DU`LCZt7i+PLQD56lp+w;0a0Au=h-<2#OSu8 zD@gC~9%L;C6q6L;BbcenU#*+MZd;^SG10cHhN^=w*wn?-)1&vTXKc7``@7@SH$2Bm ztIqA;A<)K2%K*Uc{un{t^&}WGfaOaS*>8ai9o>B)F0Ld``>~!M5UJQiAP@u1%KkzO zjwHUrW*wL0B4_$C@ZMyQCd|%UOh3Ax_RcKgOeAknn9GqDedeoy$DcBZWcG&0hv)dH z&X@L1!d5_(UU>5Gfe6V!tO)XC^D=kWqV;Yy)vvJZz1q$xIL_1})|)X|ZZeHNE`z1W zhz4vwLVnXU>(!PW5`aX$`16$UeM(`uxt#`qNZd<ud+BbyxRs%tHc7Dp491$1nl#>N z$hH2rU`g(XZH?INXr4axkz0z=e8YaFB5jE_FRS4)lV@j-PvdjL$!6}pFSVji7H;vr z&v$1mzYZ0+>^J@VqYj{9^6ff5+Ra<BkiC~kYWM^d7f946J`H!<oVU`?&}U1NoX*Xz z2MkAd;KCaBUXJt@5&g)6S-7QW$jJDfqwgFKsff@OqlWeqsx}Z2VQaMaetfSNem77| zemH@mko_q^amC}J$kzQHGs($Xoy*ZP=*i)E)-sHf`@kW7)tt){64mzN;~FCDphSjJ zkHPmwL1G<f<2Vw##^WND`&WJ>a8rT}UK@-M!<E~z^E{?Mym4Dqw(P3&90UNOu)iFG zG#lKqt(X5UY_dKw(W(0AuqYF^9>~cgE9!ZC9w4lmN`sl_*K3`^JT5(TQ*akiF!h+W zsrZi~HPtmM$ou~<QjNYo*ug|~>ctH(e82AYb?Z*vh*^3(I)Bk{^{t(e-6A2<;dXCM zt3n|SMK?EK>$&QkZaAZw&Yv(qj0je?7pG_i5WhUY?5BD@U?fK@SmnlS3Fd0Ha7(44 z#&}41u_v%{v*ch@wEBaBZ6y(+Njix^I2eyxL64RE$GkEXMh?i+3L8kLjuYXE@nKD5 zOfi8Aw;jYYs^72~Ll+XHhvGm4TcXjvDtW;Xtg!dQK@OPsb>eWYkLXkWP>$~bl|yZF zo*>i=;BVlo5ueQ@G|n%lqzT^i*eK789K77-n$4~=fnTEBKFcTop#D=meGa?L66oMz zq=B48a?W2}PI9{6Dnk>oo8|F(Tqy^TGmn%ITd77=LkfS4{sQC+%{RbJo3k?GlwSB^ z2W3w44UP9Pf^OYWRKFQWXJE+IAY8GC%E1Cn9{0PWP?j1Qot*q7XY|dZ#tRkQV#{?y zdZUA4clO92y)ybov6H|1gDYm_5X#E-fWSQ_@^pMZgdx~A{rf4h`%Cx1ZXz;9OitkB zeRDLXmqVe~>I;koM9r1U9cMEb0?(!RH;X{_?_i3Gcp1DqIz6yi-FU3cP^sEps4PHB z^z8|Z(2NRq6t^<0rnU^Nf2DQ?B`P1;Ope?^2&})LqxdnRk|-3LApKpKbj~zwz*<1q zb;%(qg;8ah-CGjL-BVg{>8ZweMw6}u+S`xw_=gShoeWWpg+CrFF@0tdFDVFP%A(ux z=x5d%gKifzGOpb+!`9*wgQKtJxPB8IZZ#TG2OJYx147R#!nOs0^+7?n*~^Tc!7i0v zCx4w!$84o8$_y5EmzNtTe_Xk8B+O1-YH`k<tNjB^LAM!RM6OSx*U<1esZD}hC^h<L zQMiDDF+6&^k|t>}OScy>cez7amg$tKlvEv^9<RE`?J>R8f^9q+|LHf+dw6p4XjhEm zr~*fcq4D8eIBm?&M!%f(#EMSgHqu+~;_E#lX}$|}(On+GxxaKA1Gc|OC%z#A`NJE2 zbg{@n%M-?uiTssv`$b1b<eh*)J2=l6=Mn!cR9_IqV&0`nN486tYdD~k!UV1+OBZP* zPx#ueeWF_OlWIpDz24yW#ArgwRL*i-F+s8If-JU9IR=`<o65?A%v`|1)L!YDCK$|O zIfQq#T+W#D8&M6aDH18JS^u+`sJ>A1eKxLf_s35V22rf{(@2h;890G{1^DS7%O3eL zC;MAlo%{U{8il5ux^pf~VXW_eMX=XTtK>Vr$fM8upS3Z%O)&SYo;gJ{#Syi7?c0#l zPOvGT5$rjn|0oiUKsIz6>Qb-bw4neL+vm?$z1ogcM@Z|Sttl%^Gt=@(-C<ZWY%xLs zijR5kLg^MA7yWHW`xu0T2&*_wF5^5QL{tP{!s5U7S4aJ8770~%Q<KyAD`y|*Ezk4w zQ9Cx@$i2pR3GTpewZWM+#{+)Ib>jo3+5Q9$og)B#L8iI-jYt27fIVl2{Eh)cxV&rH z<QX&}BU<6xXrFy^#x5gAEKtZ{UXNy(l*q}$r$dQ$L1yv~d!R{8>%3@MqTx)S@_uSQ zUSJqmo-=x6O44N+q0ZP@3QP?$>wI;7-(&5XUL4{Y&Wb#J8Dn<b-xU%Syo<9(=&cUd zavt<(<hbW(=HfK&a0ri=BzgT^ZTNK4JYD0=86q#nI62Nz3GSGy&ClzsjHA}p9bnYR zjo$StijP5OO!d{F_$VP07meErA~xWXB@H2aRm4ioDuy&_PsGW*cD4LPIsHoa)??LD zgw=)kj}dDqf9(e<9ZLQ$3t(Hau@;UOuzR-ZNxaVYztezA^G!4>Qg+x%?4QJK@1nzq zPlKvez9@nNjnA9%0FuYvwHBKv5u(oRN6&PD{qhxw$<X9q3YXV<L=K}Lb5MHZ&J=RS zwwo9_jaDJt+9AK*99knYAh@k~CeQZv*?9V92{XYMO2YZ4V455g*3pdS=)61O6lxAR z*SpbaJr+xYr&F5?F6rL6htl71os4&_G8Qp2M6X42I(zt(V<W(-R0uEan%0|YC@Ioq z{J!@t()v3EZ+9?x{6FHazsJL<x!TPF+g=`em9nK^@VPCR{R-)H!5S3iT|j-O5f}qu z05ZeZLqTOtaE-ydO7r{qvQn`ys8}OARHaA(UmJ%e(i^{QQMXA#aZ=PLUuv;LDll~M zn@X(Z+(kUUcaVXS_hOVPlUt2e6$Y2uga?WN+JV0ef&i7xh8wD1Vr1Ktsl?k)s@Z&K z$D){U7=IaYj<I-3w1wzlb^`FBW@(i<R2s+SxX%nVD6ZZ+E5%RLSh#=0cWz-nn`9GD zztd64!})?-Hs$39Dlr$;kznxQGVLl%zSEwaclex1Uk*W*<!`(>o?)kI^7K-yDfR`1 zj400wTUb6BIKGoM+N9J#^>-gVdSCB18uzDLIY%Hhij#j&wXr}}noBAzYrBjy`;-86 z!2N~LoBxf~n?Lsb4q=w6Nl(lg(mW=*!F%_+>Q~qijr7-IMLs}zP9<Ud1P@zmOurP^ z^X%`CWE+wMRy&4apivt)1J@L$&sNr|c5@9jgb~zBIoi+bb@xdS`FA!A3z9p&vt*RA zI$(aFo621^eZ@PYlyg6NVq;k&pv_1=D%P_+90pQ3xJX;sRDgJPnGN-hca@TgO|$X& zf{J}Oejta-2eSFEa%4I8fSHq8ut;V!DjAP1m%D@Z6UsipEiL6ehllzd+(7eX;Bwfv z$oo$JsKs1alT;qhU}cC%M3FAt?w>##N(04Q%ej-0zeHwLp{<|xrgBU4`9wB~J9IP^ zVt<*lHiM^FJa3rrC++^cc!Byt?nV;wtb+D#sV;=r4u~M;u?@lg(C8lwh^^}BS}PJn zUSE7cbS|i_v|qXj@&sg{?+Gg2I)7y}$!VC7sy>@+V-eUSz2@D=rA{y?22v<7u}T(1 z5Yc?(PN`QY5Z|*lhAP$n{M20fLZnpjOOr;aBqgrWQ2<hE*z2Z%aWBwt%zi$g6PHB7 zLMF-H>#`OuyJYM{r|#!fyIr;HS=Y9_YomGhN*N{@CL<Gb8h29T(EYg>E~@?K9yg2q zvJ!v;5W<vr9GWj(WsU?$(-1rAc{3<gpRkP`h@6X-Vka0{e6)gn$X%A<sBoHdLXHT4 zalwx{<Fnj=B)uOQQw#2`^0@<OD|Nn8oUPOi;AvnG40aK$5aAL0!(pV!ABnHsF)%5O zM8dfcZ9aCK@J1V%$}KclQK{po<gpSN5_~tI{5veq8YHDUx}||W^Nr1;xY?Q?!&slw zln4?YZqzDv_ziy@c!h^q@w1{!JzoY&K=hk>?0&ncArjglQu*ZD!{G5Un}9j8W#b2< zxEwdC-&*X%q@W)>4B8l)k>{h0Ef|X(`Yt-z8}Yp(>qjCEpX<>y^sT2<We$1_M=x|+ zB6@Rrj2C|NUT^+;)>4u<zEeH-JxlXcE39%n&|tmSm4GuUhhJliVDs9^t|3NR5ue3z z7yIZ#lDy2SKC~Zz6Voud;yEb>O}>CR%h!pPKtDhL7s(6jSwX5=rP{AXq#cgrIz(hL zVqh8a4Zw3T=&GgaHK8h)xz$>>ovySu?wRLa8i7fSj~w$dqZkphFYd2IWgW3mn`Zfg z>4%hyV_4n8b0N#w$XraCEeWrbUXxCL9keSBBta=q8VsK<F3IMc68$ac{xsn#)^r4i zj->!28(?JQ?~_1WzMdeA*L%!=^|x%<Q`kmm(6S-OcyADjT;fOJL6!S(WWuG_>iE}7 z^6P=v|7W=S-&5YVDmcdg#?+=p{iih#9~5HFeyRx$y-(G%{k~j#$-FxzZBPPPWY!4v zlVdB!R)6t)#}1s|Uald-tl8=Tqq~d)DgUCYO*fkm3tYx5DFF-KpkCuX(bTElPPS6c zbB;`TJd>}TkTROn0~3Hf`nG}vI=#7<SNkODojDKV;K+m9fxk})A}X)Rlk1s<&mz9L zCGS%SKGRP>_mgIiB!>w+J8QTzf=V6YL%7ObV`Jm5-wg^Rgcz}$_lhi@^k|(Z&rxd~ z7HqE-*adbNxhOd&RvtW*o9JTGG0hsvb!_>GzOVDXnG#&PzpocK(%8jDr`mWSePIi1 z>yjs4x$<}E+kJd6cj|CYrUY?M1M`eiZ>+m<=vq-2yk5OfKGaQHxj|zI<=Qfh=en|j zf`%|b(+|(MY+W`o#Ms(x5*W%`5lRCKK{eWZ2l&G=@O%$N=7OU3WD}xh#z~kzkdl&E zpGQ;ee9Zl2Y-%0uU6f06B5A@}_|21S0&2i=VN9hR>4y9y_vP+y0TuhT6D_GMf!+FY z4OfhtXm2m1NVlJeYEYl1UTH4QY@T6>35K(5hSJkxE$*y0Z1%_XjZ5ZQCa}M04b)jI z3}DmlC(8E{?9uRf;JhaOlP7$BO5$ZCi4Sgzu94S6eflu{fKvC6)l&A?3Q|l;eOW5` z)koY!`T^TvuD1SMH8$Z#A3${FlcoEyL*@XPKytkSG_NN?Mfc70g5I|vEa)$_VYt7{ zVP6oQ_z#QR&loR~h!T}#^`eJOXEMt7tDkUW4IzS>nk2sKF;)hYn-hb8CZ^_MFlClt zLbKc5pGU97Urt<VRV2oG)-Odg2+yLG%9;;DJp$JIgU<Wu3EqbKHe*fT-f(>={n)59 z3n^?`bEK>)JK|yCgF}PZgR_7yWCFK2Z1!UO_A=>L0s>t3Ki-<10K7d9lWO*;T^NH+ z^66GUNv(CunJ83~rNM{77y}$Gbheq@{{B?GGw#$2PHT4NfrVd$EYn`gM@GuU5@gDN zJBFod%I#IeYsZ=U(W6ac<)&S}{oK2=(IUfiS%7g4>f(Z)`>7G+?5+h@TY-xXxeC7S zq<>v}$tWly>EmTg;YQ;#9M?nQ$Q=k{bB#mna%PG+;ctp8CIC~&>bDED2_o19SZNnW zE1IqrRTmfpwvIlZX(c=6hkkuu{bj@=BJ-ZnJ~kQ{6s8YOF?}5fEExAz9h-HS84Ez; zHOTPn!1yJ+GRowDu`n9OIFO2=oRD<<k$Vdl`LxRB{U)>nPjJv)`kMW;9TX}&Cse&^ z&RoTcr>i9TM^Z+D#l0yJ0~l^ODdm!KH7v*R9Ffk-Bd^DK#&2OJ_0W@*?Q|EOxUSxG zAdStLKN2TMG)MfaFTq;d15LP5h1UHFb0{&<vLdbJ=ek#AXY%{2l5(LQ{vi#Hh+YF% z{e|DrOmXW{q>o3vEF-Ijxhs~BX=k(jRf_uy*i1J38;$}846kS^U+R4Fc>5sU1`=9| z4+UH*Zl>2HcA)(oTEiF=f^Oh>U;B^WL<2*svWP|aHzEA+nZf(21iKG$fzMPN-1B)R z#=RVxP%pjwnjCC&vt^pC1FN1JeEU~a8G<l+c<{)Z9sTWP_ic&AdMNj1LJ`thICoO1 zCY75j2;Ae6;mj*)qwFM&L<T>vLzAfVJr}~B9P^qRweXb@P9Yr)@%5#Gum@FWjG5R@ z+mk-mKDDU(UJ@}hnkR_0FNN&;(aV9dP#R^7<#PS?5KG_M3ZFthu69)SZd!L3OdJ17 z*c7e}FQc038x>2B42z|bz+(Li+nw->Ppb(JdQbv%|CXN+pBuP$G~$D{x*}4w1d+GK zqhYZ;&iwJYe42}W-eU`FN;{K(ej?;HPkP;r|K|XIcR4aXw!da-BV$fJ(3pcGQ@Ac7 zbJ>r)-*1-5WTVACmys)jw|?0^oM8}j`J4*IjWeh`gz-^_Jo9id5BClBClPv4ZEFTz z?PwrzwHsU<RQ^qNa8gTF%pEYKsr|fj5q=?e<H|6g^+!Gx`qPU{erSHUfM|^l(l3Cm zp@g2L%qG-s+of(uDvnJ-%HpNy_5KQsOlNoQ7&7A=OGgL3hi}1vXv%ygJG-_oDvK+- zrD=!$UHFx3+fNSLCCg*JslM4#edG-&%>hoTsWcwP$<JT8$II4zM%$kBJZG#7IF&nH za9%0^@0+5}Nc78BK{Ww9c8i1&lYHN=^H%g=@R<0(|FwPmpEcx1<FPT>^&i^0T5=NI zhP6!u6m9z)T<bo75f5Iup9H+|?y;zPFiH2S&LG-poM~k{&06biY*F54QE6uG2n<z+ zB)juGHt$yvccj>Tl7~HiF)=1ex!fMXA#dlnGpo2@8z@CGx4CbxDTEIe6|34E-}OKY z3=?f{#e|4*hBgnKVP6f|;B(Zg_Lzh*DyKdo4c{wJraPqdo9*d8dkugiWNGt613g%b zx;etFw_)#=Kk{nOVX*MO(807i#~fsO>Y=71#mS5^Ho8A@<A>v9M8fOiRt$iLc*M*c z`fUir!REZ8)KIdcV?CuiNyv)1!3treQclEm?MYN+A_wEa=e^sY&1l+X7V<wOGv@fG z_y#ck!?-&tH>!#QU-qLpekFYYd2&=Fpz+)%{zFWoU>0krOr`=2uTpI=ECoV}V7S;I zin-2?z}?{=M{C9HY~HoSX-IA4nnzqUn3Zz!X>76#fBr}#sff3?BBJJsRV+EBnd?w| z$juSr*fif~C@q$@v6>wpTSP@ghw~(rjd#sO9YHL_BVw=i#H<X2IT&GIn~f|i+3=tK zjYZdp9b{)Z##TyPaE#?W!Ay*p$kZi)0r=lO)f9qs;sdeZCD)egjaSn^F5P4teQ#nU zOgZ6GiFBy(%YW^|y`vM;znO6|#&Mf4=~I45ZMvRn1R`DMUENv@%V@GrLcQ#)y5_-m zsi2;%FdB)YBw`6%1jr7K{GBV!11mF*B!M@isI5~NnJwd}&KS^M3jatH-s>fbh3mz4 z(S{)WluD>QkO$BB+RzIz&wkSCD!qPCIC8&NfalVfq#(HKp)MDJM;q#bdd(XfEYEW; z{W4whsWG9mwcdP6YS|zqAX1@V!t50Yq~jG(lAi-?)!-KwN;*yQYkflNanl=h{_5zJ z*!DIAvyHYmFw&Vb+QXZeU8S4Ed*g>tFscIXEA5*RzmFs5*I-_3{WDv3pHsFHQ1nCk z$A!RpsgA_pI6T-$lquKSC3>8q<eu{9C=<yRxK})H&y#+4v3e(ofL-|u*>;IZDhFnQ zIfd91%dsKk)8StX)35~Sru>Gym)uObS4UBPi`VK=?Iz4hO`~;zaqpmJl<OKpT78rR zB$JX*-`}3bd-9&fb5G?gNTnvMEf}*=ixa`nyp7`P{e+2cK1rNcbEuA+O1!7gE+Vg0 zoeD9j6+N=8g8C;naBN@E9dS2)!qVlwIZj5_9a!TrsxysCbcAw|`u2TW+yQ=dKIQeo zOEu81Q;x|-nYIPvauTVzDPrB<g^FD}o_CHKX!5<&T0H2`Hm3|7TIq=c@pED-Gq|YJ z_096^6y1w8aWy~ofL;Nrm9FPpesg{{`n!91KR-7EYX`i(#a|Q!KavQ<>sN?biqhi# z0gHAzya^ErutQJnZNZ6;I&khg{{DLRPmDEyB0@C{K4~g}Ych~0vTPYT^zUDBQph!O zn}56PfoR<hY3^<rLlN5XmKcSl?pJwn3k#LzV&<BQpk$>=ay9?EZ)A)w_3?x)*d-jv zvaiC`Y(yW9(NZa9pZz{~sr!UVspy{m{#J98<Og~+ShI~RnJ*7NP!a}A1(q^0q5&7q z3b{BI#7{5B{mLv^@94>$zuNn#3Wo1&l8$q<Id#KmQ7|UUq9Y3R^Nhv@mgDpN<e9)f zydBffO{eo;_e}bSqiss_Rtnph;(LkPe)v7L{guTEUb=$afJ)wCX;CMjiFl3;Zj$eY zC^h^aw%#$kvTsQoKC!Lt*tTt(9ox3iv2EK{$F^;!V_O})={qxbes})w$Mc-ES5>XT zs=Z5NO7%}}iJ}JaI`G!Y9At2cieam%a}y;M4s#!6FdIK3Qx7_a|D^6c?$f>QCq1o8 zd?Ph9`Z>Gx@QOZs&L*lMh)p~<_zaYFgKNTPlq*+1%ElEuFK=YHTbfC}+GLZ&y;#_a z&4)KxEg~r}X(UXpn`E!e7aPCzp;++cgkDVHt4Ch#8dv-v0N#2`JB7BTw$k9##;tIq zD<&$#-vpQItvLE>tEMwU`^rCh8fTcZ1CzoW;`uja&zB4$d;dSu_5Kwwy)xT*`bs>( z@_M7$dNJJm&^wy;;H;R6@#I8TOJn9@5nl4)lf$*Wj-1GBm1hUj1ot^NMF}3T?5{wd zNGZv27aE%WP{^;FqxBQ>PgbSNi9>S3v7eiGanZ*_ES}HB$|CFt&q8;VP4;0?gx+;- zAS|-@%BU@tBu^GT%+y9#&h0nK!Wk#R*(HbSvJ+45T-JER?S$2Xsc7_{&h{1^-{w2L zV8^dU0WSf)$mDWY=KT3qN3DI!)5Fms2xZQQ(KGMsS8%}iW1R%G#0L|HnP2yGqu0J9 zAUy*tRw71WL_$551g$3dg3C?3?eRFweWj%bWRpv<WeF;uX_$jbJxOq0zkwDXhosMv zJ)mD|_@41_*W;urx&D(|2VyD=BKI3<Ry%BR(?y5`r9AwZ)o#K;oyDU9wfIbzHH7*v zhhIj(h~i;VeOeJHM$g9-$dQJ?<xbI1)#UQQOLpZHY*^7`0QN50l!PQoO;(%aA61;A zMO13nfe$+jqJcW|i*;m?Irw#I?7^(NYhWictxGCS_R?FaVo~!@WN@^y@n{Z$xE1ap z9ZR=LPy)C>^bevpr*DgQd{VDZ+ezKs?|zxxxK%wg4_+_l6ltvH^<J-=iX9eMCA2K& zmLO}0I4^GM%s#%#v_I6m!c~%@3%Ul+x~TV$vp7xFe-PRU9^uJ8wI&Q3zm?|I+e|`V z$AI||_8ZGz`OI~GVmQ2M6iyL>m&r%GXVb=+B8*kU@Zg`ZVuN}E5ROY!_^6ZFG#`?_ zIoULIfk5RV)tmUbf{D)11BqJ%)o7U(mPk4&7X}7trHowDhebjTdu4QY1`+X5Qw#P1 z4u$n)`%6>RM(xl6ii>50<XD+LvJAdFM~KAi@I`u3L$s2Q)oEV?XUhn>iUXBfYQoOj z+%~6vi6+T2D8u+>jKI9^w}xEyRjlwTwyb2${hmic4tM2Z=r0B{EQ8{F08mvLYuXJ0 zPZS1O0uG|_w#ck`EvQ1C-htPPKIp-B2zqZ1V2TdNv`L7O@v+h;gMns0Uc!xOb?wR6 zBMmR1C_e)^b~s(nXx1OG7lNeK#Cl5hgGZ|$9E(JYxCoTM%olBZ8!vd}`xus~PXw@L zfcUW{B0SuNC0i@3kSNp&D?46B5nKI@UGgZv#Gl)!7zq3wj!7D$9-SNI2|dKoG+C5b zbzB+AG0<B^#bJ^sHG7U?!vOdc5sun0f})Az4ntIHAR@K*&t<^+2rtgkKr)e<tz`mp z&GW-^`aMoiN;q|d2eNU`J4(04SMaG2^}ZYL@+dDYN00zkEMhpegspAzoN)%u$4V!U zW`^Q?a+<2PNYLEuvd42tad(b#%3Sd*D!LVdxP}b2$%$@&4phBT#4(v?<Xok%u;bW( zw;d0&){ty!DZmIEZ)gYeHQ2K$*g4>ulO28|*lt9r&y7>Dp&@U3=MJJsyJ5L7R~5+p zx(;JM#QN2F@s3JB^@j5b)&2KP@a@w2q|s~jW_<X^bZ>t`5YzBj*1=e)Zg2e@LPd#~ zp_a+IRYZ@PDEJT;{H5%et<sA=FT(Q-zDPAFZVFNWJ;G)DFXRMR_ffo|b(suSaR_Qw zmp>aKfO88TN@!!kAZp%1e?}{=Mz(d_J2x5#LqwpZ113_57}`$b<*>Uy;T^y$`!Iud z^gO^o;?zMPSwrGuznE_CJ5^W?GpNM2-v>gFLq|0fpwU*yT55WlFJuk{*3UKP`ij#J zQV_0`Zg>4ZDN!ymSkY;Y<na2iW3@@3oz13?d0kWG>9Y``#hFsxq1zAC#;`Ee+fH0z zharJuTM+IT2^pr~;|_5kq~y7En8XBVF^9PrxR`z{O?)FIVfeHfWqc?^`@w<7Y9CE( zWM^ZxRklNgvRyPQz-V|~qF8Na4@K@6Bc1*VQrzteYlgB}@kDPeRV6j-rc=jl-h9e3 zJ$&)6AZ`0oZphF74AKf=va_AQgsnBdA}qdi_H~1Og$=x3<<jnM@Z9o`e2svJUJEu& zR&p+#GC8)BJmBr16AWd?@1gn+dco;No~WAo;|OMidq{9+2~7(fD<0>XKh2<E!xk1L z9d~PS*1H6=t5vn%5L@rQy2~RYKm^dDuyMji;_d^JC=hgu=g3ahS(q!h*Uo0#&R?Qv z4Eggrd7Mnl{_=GUjL`z4HmKX_Lvz2HWZQS1uw}FB0eollYH75&OIz@~Hf}|a%Vj?H zYVe}vPkRrI_1cXSD^yLXW;9xWG~X`B;ofQ~gT>;LLKa9>@Vakfc7TJ=@HZQ&-yp<{ zp2B1fCVa%K>3Q97MXb<sJ+GuPND$L51T>;X5=vM(eJtn;@s9I5I489%V++$4i3W}6 zW_$lg@49J&?SJzI34u>Uk3HHAo+JjI4RES~EVKtou8f3yu^$9BzrCNID>1eG&R~$( z*dN{xm*XK-Jf%Y_L2k0=v{TL*P3Uf{96bhP7qw#xe|WjkXp`l2uRsOW@hyLfY^g!M z6>>^AP%FNs3!5r|OfEUpO}K_1y;^NdT>Jox$J}}(ZnQNR=h$>)aPzE4bQEyH<dLow za5u6z<OuK~HJr^OxjPz*pz9{%a>?nFY_PkVH{3sN8oU+V8?I%SBmk&(k|5^hUI?8k z(EvN>SNHB)&h2I`7iskpDi*$V)<aw=%ojtt&*YWpl-cHzu-D1b5Cn|G;(uQ#XyD$y zX81nSjDY_BthLr?MS<sZPNpfRGZV_dc`pg%h?c$fODDUlJNf>UM;IJFhdcoMJ_!QX ziyvGry<`UnF2Of?s@K$0@im20AHmVE5s?j-scj030#g3%F*v{UvbsrDlDyny*wgQU zg+b{RsL^~6aPM$U?~4Fq0((aCr1v4FD;&b=QxcI08#N%g4WPZ(sb@`11E;5<P)n8_ z_6k$e8y@E3FW=r)JFM#MlMc0z6j5I;YEFlkfy$6q$Cf7|qEL{<?`zO}jaIwB+9AsC zuk39wA<d6W*ncItWB5EWb)aDsVYkiN!rKuskH_^L&YW<QkO_~qHzboxsSY?;XvL2t zs#QIOeA3o&X%q&<jWs>v#Ruz<l049u9{cDahoC2I5ne^9ixsJ*{_yBXynafqPqG;A zq1cu{J=Zx9U043@nc~Vw<POEiG^S9{Y~^ZRqb?uX32DiXvsN-Cl^$kK@?LMX)~3M; zpIsVJKpr!LCh%=bm%N&iKN<IKgY-CSb^#O}joO5mU}y&R7z~D==T#Ww#bePW47A(a zD)B8>muatN99kGU<?bn^&)7n8*awA#89Hu{5}^{4H7VeR=y)G~!uAy(uoll~{D|N- z0?hd>kQ~Oi`27e#z4Vxc9a8smMM2Jp7sk+~E9yjBMDy@lUnfxsO?kvjBsLFv+iLN9 zF!EHkx6L5IbhYA2V1a|t4Wx%aps|T!rqw|Bsk7xaNzs^c{8Xpd=ts`<*hEctd=g(} zA~E%nBRUL%_f~s_)r&bCZoFRf#Hs6e*00m?dya8p_`6Jv_Mi^)GQI6bf-C+ebG{38 zpI1aujM+(5x)16CG591~4C-Maj3s0H<X?LmhcxR&-XT*Chg!L!l1$Lq!VNEpVPPd5 zd}Y|mOJ>$SDSAY9DabxDLyxDl@2_68NBsup++(H1MrQP&k9v5mjR?m?2&|n4ueL?f zzBymtj=}hOH1ic;NoEqYor3nzG)<!!D=+pCf1;ZWs$2^yh@*9y)|jz+P>?AC%i+b6 zPOeFjyUpAr2W1TisS>ZBjQDY5LpVTI8WhOP6g%F~Q<0%K8jFHS-I@GM2-~Jk(4!{r zH&f#h&8PIi%G~M@ri6GlRCzt+{Ivb*B7^G|OS;9qqlr}8ehpJns5<UiSgY&1;QodN zn1w*RhzvT)r7jPzw=2keY$w-+nYbzZB*MG~#D0o#&JhLwqoxKI?roa+dRq(Z_0w{n zs1y3bW;n-L@w}CjJ{>|V$OoJoL6k9AXN_o+t1-F#tQ#N2v@&*Q2U0>ZGATEg$!;Zh zbiiI$^7_FJtOS6CA4{Uh$?E-s5`BR9PjM}?*NYGb26QaY<TZ=xvi-<tD8zB2B<4b^ z*qCYs8Aw+uQC+A{qaHpsbkkL>Xo(P;a}nZA0xkhaTVn#WNCbd;*V5u66)7SDe}n4C zzwZ}~zp=TU38PZYXw0@u0;5}26+UUz-QBR289=mR`!mw(ms?dAdbuntHU%)0)_K5G zJtrqX+~K>riFSkLGeN2A&Wyqdq&!m=43V!Y=hnuZ%9b=lZ0(q6HD|F0I87@&LBlM{ ziTT{G7cNE2h!Z<bdb&^l*s{#T?uNWfI7#K}XaKlwos0x*{OY`@RGt4vK9e^=`oIp$ zTKgFfUBnNYc}OJA;?n^O1R?Z;OdT@wo=qvacoeZ1@jC=fy<Z225ITAs#J3W9a4^?_ z;5iB3l}g62*$<%P&3FN$$1MJAFZcG6L1oLb^0Y$9lj#H`we{{9mpP*h_Y%^I$msiF zu{lfBgH)qABiSHFJM#I^_lbxOqN2{0v?SMU`aqSZ@6hNvD<C@rILrbnF9n<Xhoqyk z?^uO4lj&{;^_h{WP2vKiZ8@Nw%AX5lL}8G;edY&eUsEdBD0n4F;V$WlYDa?jtcDPp zcA_3Hz0XBn^slDd1lcZ9Y&ahpO?s)z6zkdl^dtPC0p&-ixC2K`xbj)ae=K?*isdAa zsy9Wl$`w7%ERex)n*hRlT-32hnR~n2PYp|+_)QfZzL86Mkk6}E5b4zjfOtxCpgHb1 z-)j2dqrsq>-uc#;m~Z`@oVZ+z`LJ=2anLhuN}P4fi0nLwc3JaQulZvVm&|or0h_A- zRqtV6a_%`Q#`xt=fWz0s=}VZ#sy}3*{$})GqH0)Jmq}7b)1#)Fo}*njuf%Zr5*>Y) zWItB{%aD?Vh60%)5r?CuLR~$C>@5-Up&Iz1lgI0!6-UOOODy$9TdKEf6}E(JRZ$a~ z_XXJOE|^GWna4n#(W-F`wH_}JH64^me-ql#trOI)!JiR1CE`nKVd@?4EMDwaxnF8e zEMo^XDOD<Hc!K5P7P+EFzYF{J4d8=Za+Ko5p!86k#EZeus&~Z&omrSJAhG(Jo<nAF z0`OHtPmNbQ-pNily~?Zoty#td$@@Qghsuy0GV3B9a}j{_P@orlIaT4NB?EA-wrIF~ zw5XKC;F2W|#>af^m5d*%b@vSr(SHMWspopWwK@)3eU(?%cf83;t-9VK9~Uq*#-$^Z z@!@e1W3g2x)d{_hbgEDpaFdgQgm{x=G~vaKe=8}oeT2~!nGy-ayh8eAn*<-yor14e zz1EZzHrs*u9?Wy)zW-ZJr6947sKA(6wRfvc=Ea1fN$Lj^qTn#Om5eOOrQ77;E#x-r z49wMXV<5YFw?`SX&!KwRkAf~{_ZR1r`5HDIu5E(6JXI1zCGy6fS2ShLsx)P4Rn?6b ztm4txt<g8=hO|SksKUr5c5ic@U>p7&0ceykR!J9aZ?k4Z)w^hq5=6D94_;xi15Yrg z`==1bBI=0xMrS4?Pv*-u$k8g@Q2g<%O0?0=&h}dsl{?>*(ev-<v|)u4U%=DYyvyGn z%E%51p3=wrlCbvGcAO=I&B(3AIS6ARUPlP!;V!?~XQbeg@vQ$!L{_7>e0*wmGIkRW zc6cK_zyWCX$2pW)Yxr0r>?S->Tg4nTT0X+OB5a0Q&GfE=n#!HW6<hxqQ3;%!=M>Mv zvzYd%Bx6OmwdaJP!V5YIKAx2Z^baG9Z^`hDu_X+NXQjJJECcl$^|s+SP(m6);W5U+ z4jq*C1l$T|r8`UqOpms8n%-XoP>*E$g~+P{%Z)ucV;NnhBovMoq>2I?UKUKhi4=P^ zs5O06ea9(y6=gitT<{&Ja5OorIx=2Jd}1*BwkA6NSz7m@m5KrUM+W=OY|p1K$l2*K zGt0UQv#aan4Ijma-1tTZ<YZ3k&V((avFQ}V*kIThLt4A+>QsDY7mnldp4QRpk-JVf z$K5zDlhX>S(#Hqs;rr7TD~8XiZ9H;5!-aQtnNoAM`Sl1<vD&ObX=u962`LM0pVOaf zp$6-9eU!8yiB}NG)a>`yH1w+UG)A?=K@1p9yZZOi*b0-i0VtEnWS+ySA2>2kHd!)B zia>4z3l4)UC@to|)^5UW{DExG!LDXY)S5P=vgtPYdkJ-F0F&Rt3-@T{KUgACrq~X~ zlLqp^v~&P4l}3Z<AY3kK0y#hR^MCKjpsONW(^y@4=Ej|@{mOEGoPC`oO<C>%ecz!$ zKsgKOpk?0K>mR*vhkLQRYR&aWz$g{)Co+P^<uysB)ixN4#xaC8xWPE}<x6wU!;s#O z5i+%hKDV!~00-zVu+HEP-sP<|I8M}GnWT;?nWU}U!`eleKXyu`w_9vlA5Ns1P$ts( z|Iz9p8#gK<%c#m|PTTDtN^L1*p6T<)O-=s{E5XdT)aFVJIb90ga)_0q&9i(1l3x(v z#|J&u&<+X|mj9+yXP_>9ELY&`(@Sq`^j-EcW|_9`n^?KT_#><FSn`ko@B*?~E;WWs zZdK{Kyli!7E^879Zi7t96v)IX48~-<3e3bK&U!7scqY&{eM-IENYZH*2DI^{c@ei3 zehIH*5hlYqH75N(+zIh#hR}(ndK$mZ%rtziqsug)F8&1IQKut%UUYna8f0&98Kx^X zk9a)11JahM69kKNg-7?f9?FMSLkuubT5S6R>jaWGyU*X%F~Qtm{eWOHw@*Pz%?jT+ z=5x(}z<c9=GFMPxF5jF?0r)5bIW@dGbT--X%_Aiw7~D6o2RW@a8&x!!>admBe6<v4 zaOuS!cB-{Qdc}=UkSEe2*i9Z7WEW3~Abb0>Mg#T$ss?N%(5+BI4!^v)^lPpx3ur}A zVAmr<WP6gWq5EY?SY-Ib0Ovdbo0>Fe#$X0Tso6)H$#Bd_smtp-b#j0wA<dxIT5%GG z*K;7PZk$NQ6TI(M?T*4O;o)TS7Bf$qbB{M%>+JH@6fjq#H2|gjXy92mAv@iAESV-K zD6>`%Owu8afQ94$i)^Il?1Yq^cws}OfVHKBegZuqE6!?(TGy!9ivtek)kqHt?s{i% zkn3%-!nQ-7)5XTxLZuzVxb7JSeJPde%o8Oi)spveZVr`P8PUN&AB%dW?!LX%WMPCN z79*W3M-4O##%RAcI3kJKl=r!`=wzh{Y#B;W@N*})e~tomoHFI%x}=#5!we|moWLeA z>=uB=xaCuOR{5>L@>8P0<j9=KzzmQ2R#2TDcQ=O9)V=em&NRPTTm%DtuA*g;iHY8a zG;Imb+lm%Kn=$nYwM~p6$G_ODZmwADDf{s1sx$AwtBzfHW>x8sY~yMX*JFa&d_xW6 z^R_Qv+H~s8YDgy43Lg7e{WTN&NYK??2S^RH<SUP%>DLS5Q%nutFf%PcxHU;=27K>Q zP#pEXSUAJ5-X&yEzjh@V5B*pD=+;A{@tmD896}5u3_2|{0&l2@A0{7+b^#p$2EeBi zgZ;;8%gIcWA&QeozQz7G)3RsoH7fM((Q*3SI0loe-kckr`a$eLf8wxj?eDo$j6t0; zgy^PW3<uJmv%2Zs?+;K)8+eKJjFVfPuaT-@jK%r|;G_UxH^X1p<3yNCuhDX@nbje* z?4%7pm6ViZ1Pzeybth11G!nHqpli>~2^I`jrBZ0q%2g^(epAb)oOW8jrXGy)VQAm6 zLft@_-1Lc<EUD^Z`4*_TMZs|Fav`~VTteWb#jH0nt57Bf;JW=>7s)X@lf;Oq+i^BR zK}R;>bh$7TmB});SSamj*LX#)JVtt2AR4B5513jlibVxm7@5WW15%;|8NS?6_YIB? ztA^e2^4xviav%6^^LLuX^cqO+;Gd1>qbT$`M`X0#wh4fDBN7%$P|&ex`h}+J&MT|t zaH19MSfEIzM$?&5o3m9w(1M;{EEx^U+C(<fG-`!cj{8+Wu^K)6t($R1=(XixMOwq; z90}DdE>@2LTP;!KIr}|B(#<BX!88B-bzR6z$pY~BMrNf|w92MeucKFn#aD^cRx!?z z{`!AJc|UmI-q--*V0dKuzs`I=KP;9%H7sEGx9o(g8l-2!c?k^MBaMjDwa=DPkrIy5 zyS?W&8*R20P#rQY+-~ix0OCDp_!GwZt<;qRndXObuXB-je3M!*F-&E4E(62c8+S7x zhl?25OladNK}>0Sj|PLM$F+8q^lx$IvvmO!s+bj9@#ycEZedQStqilSPB@hQ+|hJU zdQs6>zI-jz_ht3?@p#|#S*Yu+vxsdgkt=-SyZt#^LG_eHuOt0^T1t2DLy>v&v4pM_ zvp6B-8>Zm3nY18i{`_z%N5JE-S*p=B1xNV6mSxi<x!Z`N%Wk*9R?iE762p1{E(x~- z_#s#WFLv~h5$e^JQ~BcCiEPKc1GZ-sgYF>N=5D`IbN@*A5nM+Vj}SSFZJq2Kl?8|& z#knuFg0akqWFYzyYpn%VKyK7xKxx>6*;YXL)|e3?<l=`{Y`jF5Oy+@(<@y@|#F6fd zejCP5&eQ#(mt*!Al74l_6_}yGEGUKo@`FG9BghVRWtW_UX}aXaw+`DcS&30SOzCFg z1)cT>VS#O$cXK4MMtP}_bU5REy}3^ziqY14Vae%yX*7{qd1Ve<1}udfFGddov<)dY zU<mM$XRG`P5U~QDPJ}Urq-%h`NKq`mt2lt<4G{As{9S2L!5XGT%Fh%FRAj!b41^Y= zg?&22SZ)gjBrki>d-$<cf^{X3<$z`d%n^F(w?%*v<tOpPK9o(Ya@A4o0;aAo4dH#< z6r!|lTUx%1NH3*LU<C6nXQNMWjAi-i5$tb<lH#`b*esQUyf*OaOFG^8i>L|4r=c#y zn}8lFLc0Oid1@GqowODnSZg-bmovY_ZgQ5}8ae7vFl~+Y^cgr+ew{eR9h*sFx~U9i z(NM(c)z|mO)PsFi8+8EFIw@_O7-KY=Pg(`lOhZW?)7CKPSYqwv2o~#@Kjk@Z=damq zb@kd_A+pKK0*vdP!T=z2a7ujXHQCR$_x)2m)mSqzY?Mr<HIf69SHQX#gP9*(=3W<s zj5S7yPlxTSpO!uk#GgD^(A|z)jB56YS(w>v=tqj@=&|ac^<Buhe3><H>i*NLH4?mT z5dPniKKW&>+)N32sGs68D@fuUvH*v{F+2eO5*r*AFT8iTpghpqwzO{m^B4-^0Z=l3 zUv?DY0Ex<RU{pSCkh3)=%rT%v(x12fCYFCfEfPg{O4Ia|*<*{@yQ;3Wz)b+fg{QA_ zwRZL%i+6$hO<WtGvqg@eIK?CPuI90yUX{n^6l=`;x;BgCrnHl~ho3m?IUTNtM?U*w z;|fq;%}FQ`+Sk>sfR5^pB7oX{%N4B-{-7}V2=n;JOT>3fh4|Q;8YsB(%n#Ozy)pY4 zx;PlkX}F5zWH-_-bT;4QuJVb!*~Vk?y+43rB|93S@OP3KtxkuPsEkf{h_0aw0dth* zj~607o6owMGRiU8EefJxoX5D=YiJoFl;y81FpS6-FY+E++}p2In9<v}=pOATh9u(W zEQCP3W)LWO7oQv<YtGso%we$G@O_Z>9T0Kg_~(3OO)@@qAt+pXLxYHHr*_M~X6usY zcz63h%~mY<$2`F3Hnq3-`4jj$j&JrN#`$BXgiHV;vV3>iOY0!U^MSNpMpCO$o%4yS z!R`Tl-gN@>PPzc1uBrMxPL3~N3Jhfv`D6cykN|*C7nd>_$k0ET9OWrvrv{q;=U5LP z6C7Xlgwa^$q+Uh(9RiQBitnw5`$bu3PZJRz;q*1Htsi<Sc8@)8f`nYJljnNUWXDBK zECL>iy(Az^Lz+8(uXqX{Aa=MHq>1XN2Q?zDGfK-=fzV_YGZJ7!Np&262*gE5bLzI2 z8m%fU90>&j!-T-6g@>UY64b(A4(6rNwXmzw5|OB)sS$phmmKJ5Zpp5q%?QtQPD7fU zztKd$DW#*2YpyXfKqGZM)Fe9$zbue&d#JiBlvvz9EuHL=DV=E+?NF4I8UWf_=G`=o zX{Vk<UZ4n<j~G>$Y6uaNfw6sJ3?7rI$Jyv6@S4OAnSg;-27opLtlW<oJE=rN!SLB0 zPNf+q)9PAQhlpgL3M(8QynqDWu?>b}h=Q6(++FX*5S5>S+?^-HWC&u~OZo%o%*gip zcSEtugHHw&%{XscidhF7ll(XZc%K~}j9Gdp$qP8^0wL=XSWg@b>))Zu7pQ9T7;DtM z*OA}eVo0suOlWPeE$?ZKg#&)LV4Jz0QxshIIR92LSOk*NSZ%DFZ`M$F-53iNe7QYg z;EP>JwjOAzII_v;2!!>NeEl6)WcupoGHi9&Yg0$G)K|#SayTfi6Uq39dn>|Qxp6^_ zK9@~|Lt|wbpDh%!&%y!GDBvI%roQ=T#+xvLZ$GE>TQWqApjZ5MB6KIVRvaZE)#P-k zbvat~C5l|Y>y2{L0f)@PM=1j!Vx6%cp4*ZXu51U{1En%U*Rcn=qCNxvl(r@0YYUlJ zM<3t+E4u-=UFpORv1avb3=n3K_4D~zrAdjiJ2m=is%5lgB)&9LZ||~nt3y#8LB57m zLu@+(Nb9-Lr411ND0GowpKIU`KVi`HM(p)E1pba^d1{_fX&jy*>1T^Bs3;i)JDwCL zZ>co4t)JV{8H_85!uvKrkr0)#^vc7Oz@AoErY}1M1!#x#?&hA2h{YLegR4>P+ZGBD zYQ+!N$p}Sz_t4g(aT${>dx4sZmlOoUC0NV9(3%m$Kw6Z%Z~Y*R2ymMCr!I#2SjDbH zn}511pw!qqKI><@wuMDSu#m}y5LnzRa8Cfy#P&ukVOEXaHgUH0#*I(&%?yBzg+*=0 zczpLIjJWFspLXB2=yIWFyhZa<^wKEBXZ{*ctO<Z<;(pvuZ?tpu<$FX}^M~IE5#zjV z09cDA^w&5Zu5M;y_M}#H_t?l?@@RSfS3jYDzZn0N2l<o$C@RL^oPCF%{q!FZd%er* zf%>^rVY%}RjP85yKOFu&`TCW2IZzjYB|%h%(bS)40)xpkHQjYfANm-<o87ro61q?z zB-$o;$+*}xU1HF34Z;<dna_H|U<wqhY!7ee$THi#EzJCRgR1y((=|hJ5Ge`Lqixo7 zL~cI@&OSh?fZ*$Eb)Ojk4SNJ7#7QW20f~%mDQiKT@34QD0If;ij}kY)-3B!$#HGa8 zuJj;voKph;5h;9^j}lR6#r{D5iJ>FYG@*pRYA%Ak2Cntzhhegi&TQ~6ycJR$ov&%v za3#p@O`~l+8W|l#Wk#n?byt=B=WUVHVt_f;uS<4;peSQN6z5t>AKL>FF+`Rl@z;jo zRlP5_ryvzDec?-C)Rt*phm%#9$?iE=@p|di<lG`(+7N=OupLY_!$Jtut;g(cAkpZE zBpAN;Zl#Cm_lbEkcsy>srH{s0trl$mQhMDEWUW5#z~j{;9W#T=3f*DU-m_*e1~nXo z3&=Ur0e<}X#RwjQ#@Iz9tYGV}gcUiRhi?ZrF-&B25N^TJglybPr5v~@X3pgtMM&L; zi6xiXSUVyi!Ah5W-9$t-Tun5O8Jz*WjIH{tSH|aVuZSSK3^g~QIf)5BA478*b%(>q za{1G=0(#S`0zj1OhN*3>uSmxy=_ITfSLK%U+)ZolfeP90%WQP?)o-g=Ll9uP)Hz1t zE`-i$6!z)sig8wNdxa(qc~M{rnrj^;fhP2#=M8)qbOuGYT7X#coH*ohb#qj*^5F{_ zysr60oKti$RDM#mF8@5kyt@^kOTu2DQLS_l`gv(KES<dP4aduHh}7or%R-Fo2=?Gy z2*V6VC9!QhLWR~0zt#P50^KR*=N{v0tjfkm)9?;>TzaI-LZ|@EF0#whOi8~u?hy6T z(NhrVaawvw=W167EcUW8+qtuUCHeSOQKnIY%_t$0*@~MZ?QxrE!;w1%<Km^~f)|Hl zxcg&WyNp1-_BYLMaB@I(h_GEg7nb|bqNhC~U3P5j2wJ7ci`?srXP__Vn}W2~HL=<K zObBUOH*T3fM=y|c$hH%K!a`Qu7HP&#JFpm->JD3<{4S()9LE^fQoQuFt$<^xr9BUw z70GzGfOmYOcBEaof4fHd$kj3rF~EaMyXgh4erG^^C89*WI19jZ2>A0yPS*W6(bSnV zet7`aRO!1tK{qV?{la0{XkE0>SXHsnJ=f-1(jydQd`Lz_J@!HEc3snU<z%U_*>Y3K z{Yov_=HuVcMzc4D2k1XiO?wLb`11W)a$-__q0yxI2giOEu6_Qg_kxP!JMTP6oDs@P zDB=bFc}s*qz^670<f~cC;r&+m(s5<yxcvSg{iz@X^zp254e@}}4B~9X^FAs^2C9dG z?gsD;qjJNUe+DuNY?x{t@VeP5#Q#GN5e=`6wUpOiW*hW7^*g$qlI#2}gw0~y*b|-G z4tto9paRetIcGH_1;x+890cXKmNCib)x>%5XtycsluDpyN!|sCVrllnGkZ>q>?*5w zoZART4A?qFbqz^HK5~lqz1&uK(pUa0MhxE>11GLkTsn>KHcJU@)s?~;^3d)b?zD1} z!jIx#87WS)<jq6T?6O^*Q;#fTF=%T2<}sd4m8<N#WhM-oC^Z0p0sv`4-$$5pV8Kt- zg>tJnf?<>Efu3v1Gy{#VntoC0<u1q}UU?Q0z)oBJFrbfczKu=3jb-Owa~jYCtvl$b zF%<ocRD!<Di(9Fm9~=lGL@9Z9D1F0ikmqP4AbRdXByop@6vnNfku?lmEe@)ul(Yl0 z)cB!ovi{c#C-p^)J-e(k&mT74+q4%9=S_#PI8WfA>#KU1T-l3=LhS4^S`AQ3dMRr} zPg1G~DVXo&nkD(kEiWJki7oT#YfZm2rFsQHSgXe=%A*v!JBB>axec2(*=cvP$B)*{ z*H_D`3bOA?g{<*)5sjmm71UlxMaBaTIpS}(9NCw!xh!g<t1SF@R+^?nMuHjOcOI6h zA$$u*K!2%6E5vowd>9+t{7k~u-Xgc~9NMDzVPLz+09i*pY{OUuNK5i}wx(Gls<w3B z(3~hDm#q(>zA(DIK6Fx2H~A7R>x^Hsmo?%oDz?8!nh_sm8zS9^zXGm=^FSV>6=S)# zd67Rv;4y!jRn80J_i?gc2Y%;p@>g#*P8q$Uv!UE_Za!J*Y<EAKJdz>!DJ)YE<8_1c zRoZ4^-A`PCv|<$a@~x5G#G=cj4x5d%@d)<3BYV07_p<_F?1<EQghwIkraTFSXK<X` z^mWCCn_M1!QAfo?^keq%IoSU$YqG7;;Z{s)p+@kR-2P6^viqbcTwk>cF0Z)$S;y4X zFY1l37L1q9m@q|^>5fw8(eEf_8|hZjo>|MWj&~<jgFinboyB20uG@jM%)y7@bw;|S zr)>UA{yvRTd1!_`qrkTvC0I|eafEXNjI4Kn@SOkOJ9YuEf%vXo<4ALR#FL54i6hND z$8i8a-q)iYo+ksIWYeW%lw&bB_*lDVsaF5p0`@4@^#`tSmlNL3$7zd)lie=f37#7D zx8V2FS41rU7;PIrTY$tS?2+(z567?Q&^B~(TX#b$tFboXM1PJJQG9;KlkhwlU=8-M zU6ONe?cqs^lCQyVP0`Vua~jC1*m%?9Ayb$*g#MDbeJ-s9UWvVbY}erL&hv??&xU@) zX<ccp0|P~I)+wktWhd6x_aKbJQ0$Layc-lLLs6h^%6ODH37#Y>sX`yCwN@z&nPF;9 zEQxYJTsv!yx?YGUcyU^DSm=>r^_LtBooY2?A`Hu_1@DkT7C^B-rIE5x^xfmpPdux- zFF0LpEhY8<BZ1k$NzH1=W4<x@OJl$a7{${iN`wZ%+_~)~Y0}Q;I`(q3mGH@+x1M-~ zwv<o(nLIc98GEG3QB+=vGA5Hc<S#}YES=a%(wYmA2jo&)4#4|UPBqRrH(!>n8yEDE z03bfetJ1AY-rksm&`87+Zwp8)E%8l|0=!5{j%(oD0tNE?()h7x9t~qmF9x+bCaI}u zk7>ZQKu%Xn?QC4O;yE<ux-K7a7&g}n!3CBvULq9+cKa$m?q9s+R60JuxiZ2hJA-9~ z@flr>`sRA}HDon0iEk|}-1sbE&&v`BX)f>Lgl9;kN}03^7`_@H$Y`#Vsf^;d<W7{o z2^<R#qVe06H?c-nd)@-I=di(hJgxKWc@$f+5<$?Z(8-+rA+uP0i2%d~2cY;M)YZ#J z$Eht0-PEX*_FbCRZ+o;U2pgxCJ(RLU);$Ul!q_FPNY1|_bh7BeXcL-0AJWF`qpmW3 z{&s|bhGz(9aq32H4j^ojZm7m@ei4(wpkf7ecYjBh0fD(ND5&Q%)iUOZqanny27^}` z$9hN2GoJhlLMQJcueK@3l6ywU3x8FP=Pe4Md2X_3gS&(sOu)fq4faKk_D)Ts9Rfmw zDJL<z4wW^;HJxReqgZJ5@%7CFpcrvDPeLJTp;;PVwQ>cIef*w_TC0YDfvc1OGMVw3 zbl^jE(D1B@F<L#|CL&@#1=}d+cXM@0*v%&{Hk^coe9}2=g}Aqp%j~ZETX&H^d@cID zYl%T)e6K&j#`9k~*9F4^?Dl{BS~fz`a|Dk!4^@O7d)VAu?yfmlF<(d1q7vhb(oj&P zdM65{Qa6IP57lMi#Zb(tn4c-&Ji_eVk&ONRh?zax;FfwZL4XA$|K;960P1NjUcPLY zAcTjud%mS#6ApXd5{QW6!J)`?xbXtiY+6Gj?9$>Ot}urf`k4N%$>h;3W)mSt@lk(; z6-Y)K3v14sImhM65(UB%MM3yIXGH_%BR84yDQ-i3@~oU^qFfB<3iZA!KWxfsIrt?9 z^RaY&XqE;Z1p9A}1jTuj+ewh|1~3Z>ynDcKBod9&<%zVTJu2I*sUeN#7H5Tri~u@z z9#AvQp{DFPS<MPjGCrA0gKq$hHI9~9z#V^|Pc?W@x_?ncnt|FPwpjs1XcAn<O;@h} zI=>hN)gF#BiD8t5UnL+ERj&uFYwV=Y@SHZNaFoc%Fvb(5SG4PQ;E0%g$j`N?1Bs$x zC>-r|;~AKBMV>p#wc4Ox!8C(HRb>xat*NF&4)PJO3ey_VZFwvW(N$v5pFR$eRNGw5 zi8lK41n_k>lGJ`}7VGFbF1=`+$CPBwfgrRHh9~ycn*NN$Am4AVAYhsp)~$t}(gi*s z5!qFpAKX=K_9@^T46IXBwW#JOD~GU=iTSt(OFWO{$5|axUYb~An9UP*@T{+AAePNZ z_CrTCOAPS!udim7Zk!x)0RSL931I={3XlGH^is=i`?p%>yI1TdAouzO@!8YZ4*PI0 z+bCG2DFyJVJG?g1&<|TOG2C&GG7X-s8I11+1Zx<Mw$>5xlte9uwfiIdJ@H{Vxe~o2 zbaL84cGU*1M0I5u2_*432|v>u_UJyfq*h*|p9tooDt;7eLQ`=)X1Crzv#L7{IUlS( zLU^vN(UIR$Ky>Rm*`rv%D5cwN%nuspiqH%9#BH-|d6E0)_bljDd9Cc4fk^5FR^7@j zvUjXu|8N1z<^Cb7sWkW}3PDlcLh{6QJU>(_UHJCF(XzN`5KC3PuF+b(Jr$<4Vf*_G znDuvP*Dm!7Au?oBma1u#j7n`T4CQXtoF|Y1A}}iaRzTq?Q+Kw~6h}8f1*@MHYvRwF zWF;Kv+ZX(lb3V$=tsK;Zu-n#oN^%D8T+w`NxM#a?SE{j-m1Nz~@KFPeL__3+_e)pF zRqE*@>k7Y52ms*oQx-uj|9|=}oNI&m{uo^I>4M`d!XgF*kw>IPZEx@CaLM=Q3&+9G zoUqh}N${jW6o%@Bmq$cIJh{}i2#d0v{^Y*OY#0O{C)v<8b?J7Tn&`Nj;+mdFbDI{X z&h=x%1&Z+%>mk}fx`uQE<pw6f^gEaT^X-aZ1iiTgKii0R6>1goI2n~l1W^c)I6T(I z0Rb_gJt&kQxyDs|8-M)GAOCw@;J5nvhPc>oLcrhmizbQjZej)pQAT9N^{|0X>fIgV zPfTtos6UCzUO>GJnwj;!DQbGbPTD!7um~6sMex0ls{h#^bV}97%(tO|GIP|T)>%Uv zVW)E0qn_0g4{o@p!rlxFi@P&$Eto_3sh^5Xwu&aI!!fX*a`AiGM43>6pH%3KBCVU- z3spbTypUdakzC|x?qZ*q>Na`70fVm<3uCX;Da;s^r%X_ns6lGq6w0X7_l4N}_Am%( zj$z%1abQ&9Ak+z6gs>jf)!*ocnIv|t*A0W8%lqJ9%5H+Rd~z)0&$;rq(E)?82GD^~ zX3@59^R~#Q5g7eU&_%07iZ|?gb3GNKB`dcj>RPBn!U;7ndfY<j!3A4zDIQ~aBNHv$ zfboRA%!8H_p13eKj&&EEQB6^`Z+OGhY{pYuZHJ<0isYT>u~#rW#tqc9fJP)f{R*{v zUgBf9!2HH~<I>b_u-(BTzP5-0A4W>!LRI;8;Y$YxwF61KKkB$#su9UrnNbM84Zr^$ z6H^P1O5hNiAr5{(6r#kyF-<aB;u+!_-8hevll2)C{KJ0`-krLy<P#(v6=OCabHnxG z{G~;$gnle3`@-L;+Mz1<GVK)ulYyH<i+vrVRTz)S+yynrz^lS17UQZDk8Y8}tO$%u z?9G3iu;Qg)&ylN_W9(nO?H~8Glj&5Q2R3b(Idm4p{w^9B{hHQsb13pte_pSy-4|YL zcK;j9Z*1kKGz9_{!p$^8ROXBcSTs%&dcl(L5fjbbw@R&q9wYoJdqQjO?4SYA&Kje^ z<2?fYCGemQ99i0TSzx5Ik~!qD#G_G#IZq}cD53&8g_RMSPi=-4H!U6$;KPnmN!ZRs z#L)1ITC)cYaO#>geawWYusbDA;+jG1Af|}A+K9?AEK}?%s(yzsl;zrw@RLq^+Xz9( z8ti_t;r^S^8wPwKO}B9gqWAqm2aHZrQcL9+%ucO)S;k3@OImBBWLns;mz)e}hQn#e z&^IF_q4y378pzt5<mMlgG^4jC|D{C#tyA*sz>W|dQRT0VA`eX$Fl6L;)e2-=VKsiS ziNV-zMhd%wAD&tucrM39*|GVuAb^KQnXkIr@Y;qNAP@)<4iL}+=n#rsNV?F$GQ0S6 z-$qQ;*d)PW_huj?^gZ+#VhWU^AA3Dw;n+dTJsG>3JsWUi4*T?Jneif42bP6x^Z5dD z%mY%5K=3@NgtL-}a8ZTVjOG#*sFboiLHTE4(Kd)hVh@3fILULpFR5&F(NuV5kqPY) zp`<A})Vndw>_D*=y$k%mvxF*u@{AG%S18o15XV{!r3=A}g_C?Fg7d(SOah4tQYM2` zPf>Nui!$PZ5D2n3Mz{MyrO3P8Aw4C;!SK=i9O7#XSiOO+6zQoxpKZfMUZjQ%PkE3z zj4_Oxu4RGBfEvAsD_W%TEWL=nD%mKswKm4&2`<6Q`_dPR&l9xZy-V8a5-A%&{PeZ* zY9U`Lnc2CM(5ZfkRx+o;+%1n9P*2Fb?7R^U0+0h?q9_iNkURN2REfc&kni|1{EbH$ z5<u4(!3tEqz3<zY$C5^cib2!l6}b`;a3yB2id8ZPA*L&#dIs9Uiv>aM#peGYMWAaC z!x+3E&-WZyOd1cBHM;Dy8{tAT%<l^i0w$5<eS$wCr$OaDJY`U2#cuT%xlzN(>nn>P zrdFa%ptVI?=_K<&?#z!@_@;u_mXS|N0kf+7Z4h}(!#mgEO0Y#OA9ajndBoW<N1V2^ z0=;0Ydk}RlyvM)o&F-eui&7XB&pNJFl!_9Ap064fsUA*A<Zx=AU9&~Je1z@k(jg}_ zj5q@WJd#&5Ei)qs0Sp-?XqL_?9CuRYBN?(4bI$39WvtN%efvu_V_XN9NG9^cT3iRR z+Gi?!!izaH(-_H%G)37=Arf8Mw{@zb-V^SsV27H{mvH{ZcmYAqy|IuDa#bHXqEI)n z1^0eVHf=QdVE4h{o;l31!l$65)KTfdHl#0ULLR1vMO0OfB49$zi)2>^3=3t_gqQL( zIk6K@(%qx~QbaGBx?J_Z2qowrLJoBune#rjH=cB3HxS*M`|WmZ5j3_+IFxViluVRY zX#o{j?8doT>4k}2E|+vQ@b&T(H#QBOK@A^3KKR2mf;G7eW>8+UjO_beE!j_sRY*55 zqtPioy3T*xTI*pwGcGhUzst|+mZLhGn2c^nr`Ly7O*biAR-9uT0X-QRVJS3=!l{Vx zWZy>MhS)*vI=#RT0>E#b=u2w1Yck%Qc6a0wj5h41>rm+6fMvo4kz&B>Fu8(GNyV^& z7x9H9iP-oR+y;v?v@ePU!mL>Jg?)%!h49Hzuy(i*62{$Trhg+=$fxbH&#Ug@$YDqw z<D)Y=L_$sw7#U5s?FWwKjT0;jnT-|$;<YVe#nHhQXV&2s6Kz7;Ue@&@-BJyvUnqiD zgNcgzL?yv7B+2(3>fJ<2LgWWBfwEf9kUhjj6Qa3O`D9tny=YACTqW%7+q~kqU-o8q zl0l^55eJ2QY)Z*LqMHj*O>ZXgSXF&epe4@CwB7AEGR}~B!r~&&^`WZ(Qa~rMaW#q- zEu40fa@A8ZsK0mmG~1NTXykPkhz*r}wEjd6fqmjt$8*#u1iI^uo~i7tDjd2-wy2j^ zz0C|Fe<K)`FTOTqm&)jCmse05o?V3vq4$gHz8r(X=sw7YiNC^B5L0ZE7e#g#xhJ00 z#OpfQufX(;&Yz#Aj3)OwwrS>OoY6c`RF2C_l2F|$;~pb5Hpk^{933GU(^p6XRz#p2 zRzz07%s`{%BbpH+uF8f<$Ikb{jkBs2o-=_jOtOkA5!_cp3)v&FeK&$>NRX@F2WJ@z zjZr~XSas#r0u1-_hz-Qa>AT+Ir`gYtK*!V7lWS$W-Oh@9xL+atrsO010cD35IWWju zKa#d$6cp!Rz;nji<=r;F*;zo0oP~+Q6L`f+)7aKDHaVh18!y@zr+}C~GOB*JjxBPz zxTxLgBAU7!f5gFdg(_sz*>}$wMGgkdAa6*HGFlCuX2nvVJ6HNKkwlX?ZR244!9ML3 zKcd+^6Ct<T@Ty@HKK#uz>hxj80Q9@JRm4~Z40$U|;+^;puo3-B`7ptZ`oyjDug>&{ zqIqijDB#hA@KqgY{B37hdY~Ld!o3sXew1AvDMU#5Y7?WnlJvkjK<fTX(-D{d?YVtj zIz5j>@)~Hd8AM2rhb#_XiK14r2U-pu9|XOuAh9-7ApTWu2Scif?1J{tog$1^<T-+A zSFwh>quc%+qS!AKYt}_2c9-j9wR?3ub%#eeSd5slhfmw-Rk?4i9Zgw}p|%SBsF4+V z&mC%F+(ga(kK|VN?P3n-iByte0#E*rH2TDCp{@$<X#1U=k9|fI<**_}RMN#bP@3Pm zN32zEqMk9HJZI;1og|Am@|W%|DKo+?HA&;CYNRzC9GQb&4vXpNa;yilmb>k$-6?MQ z#O@v5b@wKw?bpraGd07h;!UMK!1it*;{$zF`I8GbZtFe1Jl6ldY-{@=-@H*{xnPq_ z|Hqg8w`;pX@ntmjW&LKEZvN%u{_Bt2Li`=HSQ3(wj?8~A{IBb~2n?vkmzsv-WPbO5 z&z3(9@fv!Buy;S~-yr`74j0_l`VDh=57B>Yln4rn?#%$2l+i4l^rK43zePv%KOF6^ zrTk%HJyiHoUg&>7|GM7)c=-SM8BX_?-ClP?QiuPG(m(z7e?LtAMIx9{*tB2{;Qzw= zKkNB#M83dB*lxLv{sZ_57$o((1u-Ryd9b8s(+b!IkJSIWPcHsnbP$njpZ;;4%0xSI zy|jy~XDCPiiK9F$($~=$q*CY*|6?l`oUc7v&uSksdHyfyK?Gl%3CjDu`47CvfBmJa zY*HhK{vVrsE$}l4{}KoE`N$gs_y0Y`TFbxe(hjINI{i;%c92$({{kj4>S+JR4N`>s zm*+{Vrzi*ixn4f<U&v>2=rI2St_v@4!`2&HdGk7+C$`<rl<6hMKV<QL1S8`w9T@_@ zasENae|U)hvk=!WE9i@eOKM^synjIX|9?!63A6*)fl0h0;2-$^FaNV3LC@w9E7Z(W zh;3AFw@83Ji~sx2+V#I@vI+hxX5`=Rd$@kTeS6Z&x(lo(*T_}dW$h7%$Nvi}7b;-O ztCsI*HJ5$^CNwS<9VZ3B1iYT$lv<01CASX~|BYO((_b|zBEs{g{0F+^guoxD=Y+rq ze?`krF|6mbf=<|L%SzevB`d2qF!9#@Lc2M)uV^{<w=<6vi4Cv9|KMo&S5>2TkAyt` zmznZ?e-TGc*4NScIvu?dLVPfz!)J!CZs?XJ<OD<qMD_LZyWv=0r&4m5Z2DgsB8l)< zL_KcjN(TNxEa6{dMF67-e>JQK-A^2-4D_-TnX%?p;jIH$k^D_th7|?(I>oFRpA;K- z;JLXK$r`snuP%@qp5#EmKjS)iPW;rL0v#+iDwT&mtB(9#Q`V6`I)k-vcbc!*pm#1w zoOoU>*4NF!x4zCH)U;T0!Twf8oHislDnq|}$y1c@xm_$*jqnSLK}O9E`G2$R8uFa- zFI!a!&R+gX5($vsSIfN740&$^<=3az^-gRqZ{`&3r`9l!B=NN0Uxtg|(={t{p*qc< zCgu;#wBeRpk=D2+_9}Yl9Wr|J5x%4t?&=-4=x<I+3d1Z();7hWZ*gD6#|s@*a+(3U z!;!t`U=fHBgR%TomwzIeE7e+%;nG<J91MW#1FVQiQ$)s>UUzn)FK(}IV!mV~<gbc# zbKfBUQ^jEZYKAsswduu|%Ak6JLQ~?C)Mh}v&?d!BMi6&X;9YfqX}Dx9KYx#PpMA#S zm2y2Seo+`kr(A}fuZx?YAaLYy%#kFr0goi1wrzuvbF2ntBr-%npU8<>ShSP|qA*LL z(T=nY{u!0f<|<ZH4+U8YDkCl}JgMP4Td43p2bnFWL?QUsgesW)Dg1}cthEL$=Kce) zz;R%=!1LK}3gZd-m#UB(LsoXxV=<DwwW*hfmj_DY@nBnCb+|Jf6nygl+c&BGFosu@ zHecG%HFQ9;(Tvt*M%vURIZ7^CH|7=KUYI0B=lq=2CuAwo%*GjK(`4?+Z*`<UeivZ> zJj_sNFi;H5wM%@#+C4@-uOWf`YftpQ9}YhJuZjHM&n%x*z(JF~k#5#fP^~Nn1#Vxa zEpT7g^OGtu=EjYbR4%h;)#I!si|EO(&_epOR!uOn;+_aBjU!j00o`n^1@~R5379cE zDXd5e-Ee3^UHQ?0HDA%{Q<5VobQanAk4o7O9M7wH@Pn4L0!5qwWFa&nnml{6R66rp za(trH<2JiXX|LPM686vH4EYiV#+Q~Brvt6S*o1C(&~UQ9io<<3DD{6V;g{u<fouV? zwK2jRYumM|&d5k1@{Er0AKhnXKdWv<Ph_yA4jRu$>C1KmznLQIUc5nQv0B*RC`DKV zr7guyl81YInGi^v4XS1>pwQ4Tw+kH_V9dB7r%kD%z$e*DPK=d(DK%bB)07^&ROZ)6 zmPZb;^U?GHI!NKebI{ger-;5)+CP%lvIauHx1T>@UT5&5`px$Hh+%K0@}R3!x1DiN zb|itZIO#x>%cb0^{r)!W%;SMf(lo!l;lKdR<7fjle3xZD{-^qllNXNzaWb{sZv2kX zSVB}(h3d`|A4Xok-$h*RLqE505W-50H$>yQX$`h)`$g}TW>HN29cf&jDyOvfu_=WE z#j?u%kKpq|E#b7Zv@mt1j{&;w$Ohw?KCXoEV$;tTvht<v1b2C`8+L@8y!twmi#GQ2 zYaxX^X=GL#wUF-(CIuD`9%gH$v<wq24F4Zn?--To|9*i^HPvL>wr$(CZJU#A+qRqR z$*!rM_+;BSeSc@2wf-;8>-**BzPPWwHzUFb2Sx8SmqfhOZxV3R_H6G0_XB3xaG1m= z>w)(XlK=nm`M+e_e<{)rSK$J55n0pi@`<W&_T_M)#5A_pDE<X=JDpfjAmQH?bVNjF zSW1zK?3&^e1b6yC3dEH&LxF!3qdW+0!C;@1@_m_9LY<pU>pP58$cYMGO9NGAMpqR^ z7kjC2>{0=-GK2{b!_|+j6K|QCgi5bB#OzCQ8iz=~W2R!?X5<0O4`Bbvl2#-3bT=au zdzzX!EPSFo!82JjVe76*ZdaGXb&G5EheA>6&=Jr*7ZonMPqJK0oVLzf02`@FYkudj zwqPcyaC9=Y`_^o|MezI-=rDKpRVRkkhynSju{a>1R{htg9lNJmI(n($H`SYLsPzfs zvTcIo6DQT+!F*iCr!+$@38F}4^EiXurglkLo%0pX=4!3<KtsHMaPtgBp-R^%`<u!^ zlWk`cpu7=13G*r})`rRbT;UlwOUC*744iAy;v19_D|My?<%$vE5QBS#=@N6X*iH6; zDB76j_?}DR$kQxEcVZ<9FiHN)+?+1mmj5?%`~F-|Q75kS1t(RnXt>MtiNpVm94W{- zu@!dC{)=302GOJ0Fk8ts7-;{<?nQz%B-B$%K_MnT-;Zh?R*alAjgnWYI6g7uEd68t zXc;l&+*M{jvSr+C^0uxtbw6>^orA*lY#vQjFzv*ZvdMf_@Nwec1yo%6Zw(hq=MnIb zg&=vut%31I490oz!XLaOdVP9e5~=tX0zJ@qC=@GG=TCG$u%2QbR`LV6;s@^6CWhyM z0EyE}s|K*Y%}1#atr$BNT3SV+iLptrO42@0`8J{W1w-Ak)ZgVYvHqrk(fHWhXcT!r zq3b8--#8Mt8Pj_oJIu@8EA<oxnbIwTcV$rm7+m;45#}S(ka*?8PFGFsA@6?b-~{D+ zrg<vdNZhJ>*y$>?$?KCYhvF9_i^9p@(<ByKLmeeGWbBjabo~}!kR}IZq`Gd)X8($% zu@)k9=);r@L+_#g{(=i&82_*HlbYdU_`eO?Mr@z}xK9_+9mprduYW%{WGzZeDKpNe zml3_F1_xTj_a7(E+FkPRCa7n0l02F<(dJTMz7I%~lh<yHs4HC?EU0A`7FLY*LZC8u zJnSn<3h@JfH*uQL{(b|Hk#U;+9#q{nL1?kr#(y}oa^Mj^z_ceHHMmez1kw8JjxO9j zwP9G7h3X{JD)p^-1>k7<sd1RfeUXIQwo?<*tprZ&y4L75qf=E@YPQ?+?WtlPVW&e~ zPQ;k_tJUeEJ)EwJ97MhUGQ%$<mJTiKFxR#Zg68ck?Xpox+o{v<X<VJ(bQ~fpZ;Ua| zUT4alEHKGgrf4>@gD!h#3Z|BtX)bO8pjr$UYfY|HD0K!=Z9%K}OF4XdP96BaB#CJ@ zST>f)5cA+4-R^Nxt5yE)dEA2GO~@o~pOXRUG+q(qy?gxyaB@&kr7d6cQx=Z8tY=zp zc3K+*&*-v*LQcB>M8<(u?KL)Qv0Vc-OS+~0N*SdsDWM%ZU%N|CEaRotpbW2(v-+2S zRNxOZx72KhKuHo1s+>$Wn&WXO^h#%O5-m@=$M7y%P%~3$7OxDMn&_XZM7dr+yDHFI zU3A*bl)$kw@+wHs2cbgjraJlG>&^->^!=Z9cH_Tx*d9YS@7W<R5Y8T^gyk!N`!)uZ z=ax>Ai2fDr5F>PZ%ZF6UUN=!jU%s=~OAp4Yt-m`1nR#`)5(h6GfTc7O@bQOLHj5L< zr6jOK1r&|F(ncLPd%~hrt!~F^vz~IE^G%IOxL7ar|9FKDC5B0(nY{F*mIcu|X?sJ= z=joD^{ww){S*?jwP0#tjpdx4wXuxOr%o+W78a2L6q0;<g3%;=8(4bWvx>r$CzE>jz z<a1i_+H_P+pOGx<l?wk|aV}0)FxN1$^zGA?`h7L){ejiZ<%z6+_Jw?^&frjAG(BJJ zEEiqOhU2_-AL-fi1*zHWj`l6vX=$(gSKsvlkMpY}*p}X`1<Yt`f8A!t6MZ&66eB+X zAEkWSG)JmJr4Phfy*?;R?rF4CLpOqYT*@n0$zW8=UsaG_Ck8bkThqLk;DswJ;E6?9 zqi%QsjV3|?v})Nlu)3}fDcoagwIR7k@qn1c4~0DD4GRnsZshdAO0$n1%*|R&qH{vc zajB64_*aByU#6K>9%L;a`foF|lA!p0U73`LKJ44RpYP)Z>%CtI1NKTKdfHIL%qAT| z5!t_-#CN82Lyx`#^S+-v0<v4`p#N*$6QuM-|IcXSj{n~fcGqy9BMk{Ue@<@ouV_sw zn<3Rznmv6_vU!wCb-uXrh*dUCBn}7<YC3d@>)&LBo;Iy$ifaFhAu}4i+zACNS#6j2 zM%VKNRaJ0e<bzmy22`gLR6yxuxkHHLe7nuA4l<uMZd!Ps<YkghM_Ew1!H$aPj+#KM zuM0H+sV<7;*PdplE0Z|<7buCiUpSeJhT(UX(v)r&i%u`3wP<FuT>80OZJ7-hW}0VV zZk}My#%@0BbiFG99L47-lsS6L0g*ty9M@2ebyddEm>u)7a33Su^x2!SnKg<UA{$g~ z=^~cLSSY162x01z?RVIQ8=AcGoA4uOZuEVD)^*$z@jQFkdbEd%JXS;rk6ecT*J6*R z?{|U*i+>N*i+6`(0e1OY=c*en{CqnMvT|wQH{`|aVs7c*X|GCI5GxkK?H$;^KHi1O zT+{6DHWq@Xff<>LpZ!-VU;PD7Zzgl;0z%Ei$rGx>TAN?LCGh`Xz}ct~L9E9sg}<5_ z?!J3r3fS}dznWu;zjNZOK6HS@o~em^2gjW8>}WPxt|f#i%uFC}4hvyuf#Z0v>`yw2 zvr#6K2~OTeNda8Ht=JrJFHd+q)x*1Rm<H1UP*?(H&~kleCTmq{9l}rDQ&9Y^QzT0C z|DwC`F9gG|JJHUmV|IU?Bb2UWpe=j)dr_tkPdogf_+PDvG0#`*re`I_acsTi52ddZ z9S26=GB)sA4Y_)_6g{BeY{Tf$m@vPy0oteCMunGCESe6T#LVbq*}4ow=NuRMs7Ydo z46*1XJHI(E;8~NYDigYsQ@`}tS_|7a4tMIgC#~O<$-u0IChA%&XA=E5MXF+gc`}GF z*DsUQzGC_#Ek+5Q>dqq&bqnWz|0v>rgF6!P=OxlFqy{YC)8>Y+0rr)wMcoTs(P4HC zR^|B{3F1W2DCt%0Bi2Ks47{F$BZ}-3gxsIxkt2rCq!a@y#wqvGIo`Hu(BoH_*Vv)$ znmK%@vytQ$C+@H^X>=n9CZh#fz%tH2nY!t0jL?)wPA;9BE_*o;Dyv-NTVeV!{X~W5 zpa}`DOMdVY5e+lPlflmCD<21w9Sahrb}5`3?**p_vr?mHi+scWv7rWwv$l@gKR68z zlMr?Nj08Zf6Up6}_EwyQ`8p8_SKDoPw8?4@t=nl2k*z_qp1gs#V94S{eK<SW7Okp? z>?oK1S}^@%9~}M{d-_xLtw02Ryx)F2`H}VF-Qm`$obC%yY`%?b`i<=&vuii9umqex z3_f{L&M@Q#&j@_OPTd|yk4OZ>%KaWqRp)t<1G-DF5@;;s2NxaS$M8H<K(z8cTprJ0 zbd0+*ySx4l^t=^-`tV<#uc6$nrV6b$Q9U~W2r3pEuwDUAzwDpKv;bqN&dgft2+Fs0 zhs@_1dH%nE8034)>G^_aR4VO;>U0L!^aK2ps0rK^qi`0`^;jjC{&yq(&wf^7yifN% z725o3gt1lm07dvCIIFWp!%t$?-K3kQ9Jf>cEXu#z7Uvz{$2~4kg8$8qg5+LEFocF5 z2>SmBIhPBxA=wb?Ue(BIDKwyDu*A|8=Pf1#*@;Jq&m~7oVoRWmGrMoAbJp+zJesnN z6UVnJvQ&DbJO0dcwO+4i|D7@Tey&GrB`_inidyV%^7j4hhYlNY(9E@RFV%tT9F^-I zBzLOt)&MzJoJPYH-I&)yjhuxG-zCE_rr*{_ghXq?Uf`y^peJ<S{bfJ;f0>i+2Qc@m z_m^bjU-8v-y|#*17@R}ir|I2Drx$a7@clzpo<m|T)0$*M<;>LEKfRzn3aHv`b`Og& zC}^qj`VVY>Q!&oqC&(eOR}tn_j(2cHs*}f16HEfc7e`eE+iVmjgdskOr-y`XqoV(7 z{hdd>7V0)o7O03|RQRLpJ*Wx6kNzxEVZP6Id6sNXR;(B@0K8W9I2+G?X9(C(<6rq8 z=zBR}#&KS{^1kT`oHv)tqr>|w!RCx)+J6s6lp4LfXu^ByvMiGQ=*x}^-`iciD5b?k zroHB;O3Y$prgzW${80JH!<N{4R^7D^TGh2DT-Ta!XnFhdSJkq8umV3$7(L{Y#fybj z+f5|7xh1n;pjF>TV7fj*$l?qaI0N55$lyML__l9lU<Q7?z(32>+6J3jW1uEvRD>!O zfxf45GlAV_=+wTIv@GDHP8{!dG95g&)Cfs7k4pwlcXS@RQ#SSzx3^3k2XWyEY4}4R zka(d-2A=r2k2Yl!{cy{YeU3A(0ROYELaFlRo9kQ+L=p~X6>jJ>Vk*M$?o9$Yc!7;H z!)#DxAivIOK1XU@ncQ{*JPH2?L!R%83Gah;fUB+6>hjnqXL?_?pYG<jc5J<{e+k{F zn*5gN+fg6acO`t`VE92s_fn<#AfqU;W<Jp==bH+@isYtNpOUyz7;`c#{31Fb!XYx> zd#Ocu3-wVFxSuu^BiPFK6494p*xeOIwpSP!iZz0F<3g09clj=TC<<&oTjvHZ!L|BF zSecowL~Fe?m9j%dL=Upzf<}+zFB<t$z}w<$wq^P4^fjui>uAp5%W8}JdhdtjvF(I3 zf!x_463b$MMQ{h04Fuo=_-Z9~uEP84`RYY_OcX?eljYyu$hOKmM2QWh*)IpkL-SQ~ zDsoMeG2A%ZS=DqGsKc;SXTJS1Evq%^p)#B8W+Fopwc1Dg{?d&t=Gm;)g;J|gAGtfZ ztHw<a>VzC-v7DFX$gc^7LNjUgP@~Z(s}r%%q^mdVuM3v}n(gDW*pyu2PbEp?+C1<p zTgpvl5Vw;m61eD%3_V=<I6JTsz|j)EF)NZ)7baFQB|+(PNvO<!1&w%|#e4)XS(~MS zEx2Y|40_!^zWko#VlsINDDu3~<+*M!RjU(XBK!Q~H+(i@2+HXPyf6%+$M8>qY317P ze|VRb&vL$v7SD{cgusQiqWDPcz~u!VHJ1eTk-N9*F$_$43DRnUtW*ei!j?i=94E#t zcEiTDhI+?UoUWyEPO?<-6uO^@ymi-8`JBR2`A=y?CvHPMcQY*%J?iT?i|oX59M9J@ zr~DAR419R>eNOR7S(*az9Er|kT`l62oZ5X4MR^~tkUHKzvy~b_Epn>hn>pLq>Y&#y z_Oq|YWw#^h`<{Ox@W0UOV_)-ES<nm3;?xgO4EYO(QZGA=xAx3GUE){hcXmr*A2nS> z3Iqh}w+n>eT>4-i<<9-)<O!|w3!x%3sWKOQ48Zeo=Y!PaxiFIk{KRQT&ta=Xpd8MO zy4m)Bg>K*8#K3s;hE30Rs_0j7uMC?IQs)B7%G*hTA|D9jBmKA3{P(}5Cc90yp^iv@ zmbhD*7M;ZyAZ!fk9n_MIG1cqvDhsx{L(NOV{!}?EnLz3i+oW~r^3CfX=HbfqhE`>C zK5%!><$YPUgW+6Wbi5WqWbxJPT!sWEK4;E47TT^Nru$xxwnzJvh&Ls_EKe-x+w!+R zHPW_itvLWMPNXX*7%h9ENIG`q*&1N+uU*P+T4#EIe&S>SGD#uvf1|~}%wHXk78|j+ zCxed@>&z>Qb)#xs<BxF<9(7gX6V&T$ZkrJDuYu*Bs$DiarAkTfsqp0!<8U$<cV&H{ zWUb(8I^#lF&tU-@X<F|tv0@a}t!#T|du>iQ3{mQdV#sz30pQ!6;z^3obfNny>;lbF zL>*z}Z>I^#)~Pg^T{7@4L&$`cXwq;LaCiNsG43WL2Av7*lRqp}wz3fJqF_}zCAKOU zBzBLOOk(9?TCi|djjc|pNz;zT2iP7BQQ_ykc`Xl~fpH=mZEsi?k9tMAP@(0pNt?PZ zrXIK#z>>rp<4{qng^6F<RNwrjkC4P-ag&EEH*`XxzdJ^xGL1|LK`rnTE>xwCveYW@ zdhy)QdI(oR&<7L7YS2$`y4j;2XVyj5sZq2Z)Y&C!`HCFC!#a6ny<C7j#6IRspluQl z*n*cB2%gozPG`*LLV3~my4TcqK$rAf38gWL+9Nyrzc6!_E|tYb0L^6aVUPCII$x`y zO4a60_2d(Wefhy>e;MpK^5@uV?4#qRsTuGYmzD|6VsYo1qMDB85-_GDfgc{g`wU{= z(-G|>U`LtMcU{>#*TrhTA25FrX2Ixs@3<5(J0O(%tvFvL*YW2m`FVASPxJBtADhWS z#=f7&p(oC(vcFa118m#>nV0_J=0_6s@^CRjZ#WJE=XzCeMo;|t?=w8;F`+?~$paPi z=}`)ifYFikyl7{$fAH5!CxhFyo5^77PtG4%s@;#S2EP1MaQU#FP~$Z$y|3qB0Kl31 zly(!eoX%x9B!PcWGJc#gaf6izc9`EgJ-(0CudUY|y%uZDp@yZ&I;`cFM2M9-`4Nwy z@M5Jdk-0WE6B}<))r5uJnx@QYKf(a9dY#t-w{)26VLy#z^~+Z#L;KJaNYa;a)R@iA z*J_D^j{n6Jn?<*-j!+<;0uCSqje*7tPQK*X<&CE5Pa5*VOLdb5#q#oOQL>U*Edie{ zLY~5k_M)1-ks1E2T0{{RMR>FplcW?jwdmST<?r99Wo5K-!s?iENv4Y3<P{KBO`U~7 zTGAgQM28DCEoa^QhZQ+cMpJ2H^}_L&M|-jHy(3{E)D?=IO#T_qY>#%jLt(A(OrfqX znx{l}Q1|~^ZGVA*UYcZshQTG={CzvmSZ8KaYP?wZAtOy+i6WNy_ahZ;D<!I`e7WTY z{kl3)MX(CbBzA^<iRw+YtN8+WUi`Do!~P`ez18EJ5uO~J(SWB4PzKFpjzF@Y0lj5U z&8me(G*XK3>@vy`AAeQB)fOvkp_EfjBd?g&2qy8Wg@bzO+7XMiEMLeNlyhqSSftHH zqmp5?A0#DBsSOI|A&8(}Z;yNC6eIM(_GTZa5<mk9%eT`hdQ_~f%wSTu|I11pZ(ADi ziu*p>#-Dmt+kp$ep%naEdfcq}=HnTvLa`Yuj{7<=cWFY~UXd`$G}s18VvV%wpoO1; z`=zL<<hGcvuhzlr1C-w;8mCi59YtdRSbcqgux(_fZic)5g1A(f;UgLB$^8d&rG$3G z<6BbfyeW15r2tH++1jhF1d-u`G=fs^Wqg+|^SI4)4f&l>9a@rZz+M6)Rl|E+bQlTd zNV}$Pqc{+dw$r5sf(30dcWZ1G;#p3c7r*+o9M7_@FSPte&hhrdqR20sT)meBTq$&7 zdCvb!-m=}{E+Kl7QUlq`Y<KbPD(%>TW_jarwKwwHh+CXGpi0a1{A1m?v*Bl<Zm4vH zz6*jX<&fVG7wBYghI{4*3py?Vf-me_ni+v2vc)M6DYK5id0SCAWdD=iGe$$*93Sr9 zAZD$~WB>Pg%=bG2&b@mYM$i7}3e7a5NHO-ayqoRV{%iujP#o{AptOhT-Mlk~!Q_wd z0(amCqvbHhF`z0>jb_EB-9zHaX{!UQ!~xL%L<Sy<&9*;f;vN2=26E$`&Bnt6Lz6x= zcEO<=eu}3sl<c9ekiwPheSpmS^bF>C8`|E{se<LobtudG1VFJ|Y++w1sT=Og_x`ax z8@0RnsZi{U)oM}r*SZ>7GJgatUj5oJKT55-P?`)cM706m2}BjOq(si}fXU;K_5RWc z2Kf{>@UvcE0?bcWC{kMfH)Z!SiK6j;P#1ExTY$!Z8kWn>&?8*|F#|TWC8CjC7F+Or zG2O;@o)Q;A>jF;_PK>oy&lxH!VfIEPJ84~7ZzY?F#TP$I`JLTLs}p1}pAc`)%*4Ls z#QwK!TZ;WD1GZy|rx6tBHX(+WMY4w6xj#Ng7RH<?!Je8DsY`$F!Pw~u#TwfY(Zy(p zuMKZ*H&~^X+@Mh$+(^%YgJouYEpyT1S#~9-_%yX{nF<3}^Uum~&e*7_si}q}+p-+A z>X?ad<!0S$PmH&@6IO0kNtcHKVs`u+6s6SrCF%8-oBc>6+uHDh_1KkaIS>GGfIVD= zzjBU#r>t`Vp{$I1s^Fs|6<JQslDE^wCzWEHXlKKo>izrF<yMVymH2MLU16SuQm-{K z3`hjc5iCAmbz#amB4YevrPExbUYHcCiwOcGVOVR~S8p}|y$~8TD4JeZns8n`P#$wk zO52_4816dSbae~w8LlMNiJa#>@Nn~Hm*@LHU8>TK^Q@>{9FrZVLM&xP(rjTSSvpYq zlEmDQ;2N5Ps=KE`c<^E!9eOU2jcX)h^Cw19EOg?I2@GeO8h8Twi<D~1IhmHnQS<SP zbX24~86OF{+e;HHiX+hIq<v8<OrexYLM8Vd)SK(g&*TI9oij3}!S~xG$7=$I;JITU z?HaaADW|Tf6nvvGW=5|Qw+p;CM>+qT5mo5+(!NCGM+`IVoeFpLzn~@HReTpd^h8ux z<W7uYA1PHqd-(i`AB7fpY+mmQ9anMu&#p_DGp=;O6R9-BQe!$SILlYk^3>6OPXfRA zd>%%b^biWVcvHr_$AFq`o<wES8R6v98wFZJ>&9JRqp7)aIE#!{@AWxyy!7vqhI@?K zsr9;#MQM$H!u{d0+xiQ`3Bq34sxzy-?7!`EEgW_#799qzx5<GOZLv~Rx`Tgc6gd5+ z{!aXhfRX2hc=)3mResf#CZ#YI%wZ4}(0h-Rb-oF{9fKVt?$%KXdNu*hLJmC8cmwtq z&-Q0hxC))#c6L19Co{dTVjcG{OAhsU;w*P=n@X`b<yrIHJ>@&TEc?v?d&lN4Qs`;n zZ6hlf^FH4+?+*u94Sad<)gCLNs~viAo*sIUZPcfR?08@Pc%@%<lpm3)Lt3A>Wfb%L z_`S}NI&Vvx!vp#B*bN2Ke72MOq%U*<O-;eAnEFt-?BE4G4L^Jw?EUl8`Wq&{t)BrQ z_;M%i*UnnpSKD>aZbkpd3qZrzS^|@+Qrne<sKQ(8sB)>Q-({k{Zem%B-B%509b(^U zOu+U{oS}AOe^OR;Zb%t<T)!7>X^OXDWnWb82`O56fu+%A`+!CUu8wl@psd-JBzXl& zpC*B4u$o{!0#AI<*2dMgDM7LkYYf60Q9ea`)a{h|)Y0Vc=T;kJ?UR$<mh;Y~YmxMs z+xD}-H1XDpdDZi*5wj#mE<E!4LVyZg;3pL^e5Y&!6^+G>3VxTslJogj+t!^(?F#aT z<}?pfwnf@gJ!hqGa_0Hw$E@{Cao>k#hWGOV(ODiA_}R(-f>!R=aX%YXy{bghw@=s{ z>>0VsVyv4LZ!{$Pbuom(KUrfvTIS`t^*)(XB00>Iq=;pBoSqE2Xx$D^CIpX)5b{_Y z%{K}-W8F{O>(X+I>*Az!Qw@bmcUi;YY~8vXAVGX`7^LX&Q0%(hvIT5*4ys7!ep5{J z19ve-mmSv4iUL@B2EV+OfJGabws^bYII-ysnCabUtYVm57!_DVxJpeF&!Tl9n*Kv8 za5#L^0<#pg;-==|+5Fz}ozop%p8G=8)p9lHBq2$I;FR;)qL+{dEE6m9pD1`~D`a5` zIUAE|cCv08E^=jx6saHaMzpPQkJTdiA;X)nbu#P{=0p-X*IF*LEoOwkM-HenDD|>! zR57=Q=~i?X3(uoctnX5o7LoB<0h>;9OU?Png%-i;QeJfpDLI8o<#7HnT1x1gXnY8i zU0L8ezp5a<EI6qJVdij*;Jvr{ssfpo^goBbPjrE}%pj3CPS9{y`>V7IY%~8$dTih@ zmfoZ%^yBO<)xR7NtX>{*6-`Erj(@r`;h@S6Pz_ce*08&UtbU#mlJ23}oO=;N4HBu& zv;wNy&9t?8U1^!qSay2xLsS%a(SKU2wD8KO6mv(lp<OJd2RkAIl%>|NeAs{>gggVL z%4-}BkG8V;OdHZ!jR51d2<zM*Y&Of{XFX4cpTX-6F3}*)q`2%mSUH}%!I*brrg?#S z`Io|_4UX>_i~-PbT$j3l_v=2VH7&h!ytkd!F~<`(50Xx2FxZb%9o)tM6<f{Zp!B>i zjHZtDiZM2fLf&-wFQ!kM9M^?R%@%IF^v&B}`u^SN%L!aTDGA}O)M0(t{|Gz;cz)I2 z2cST<SRw9}mad%Lj7T^X9(`?whF0RtJLk`MKCW5Jb$DajcXTq?`xOw#^B2*bs6DE( z*g>5Y1qtz+7M_~Cymxw*%+fv6mBMa$*9&A_7Je{S1};HTta!cNjgly0|F`j4NQe%o zX01p&tQ@<EwSCSTy@>CP5HcAnJkyVr`&I`5Cxyhy+C)?^2(6ch7h1Mvs|l_(gFJO4 zw*rieKX5ye?-)v|+?2LR%hHC!L!K)HXpD4;i-DzIpXn=|`rT^0C9vd>I7}~1?emA( zq|fvxhPw|ef!jDqKiOPwd*mIAPOB!_%MP$%=m)h!#)=2`APlu{!-^MUqg4bhz5nDu zq`c6|iN;W&rYpHsq-zrIum&_QT+e-NMg;J`(K92T0+*uc2XyKMLaL-rxsl6lXSNj2 z==ezQ)K9ktc?`M;q}&3{+-(!u+&V{iW<bnJ0Dx2{J3Zv9GbBo^U%p#~Y}&d`blQ3W zGUJGz<<e9Ksi-#AOC|40Iz#RXENIh`iK)LkT@H8CZvu9%i{T~oF5WDpDdue+aV-#> z6-y}mu4RDy-Y6ZSo-bLfxGuwm721_a*7i+oXk_S9nUMp*{KK~+la2g*Fg6QV7B!$x z@V4>xNBL3QY}LloRb-g#_bR@xCmI#HJ@`-DH8yXzZY9FU$0S`1`WAW<@uAAH=%rj~ zKkR+bA7DsjK?PXNjo8uP`V?MJ=(O7g_<h=;1vC<i&26%l_AZShR6!H<bls!p1Cvj3 zd2Apc;9hZ4ZP<rHG4i5s->s=UK2pL%g1`=!G5LHk`Jb-@X|)=W&lVOchRqDheZ^Gw zdc)wbSqIjRT!$jZ+@aD1K<~;G2Hrll`)7gv5^B^uNnQ<-nN4U;drV`%{p7gfCIw6w z2e26`!Z8J5F}i_E*TAJ!bNBP$bY{s55+!rtC3SQA^@z~uL*u<+sSGv;CS{csV?AqV zjhbPlVtKokwJtDj_u~k0xKlzZF6w&Ifky*PQSvO1%q%UWaC~3NQ}q(ig?F^_kF(K? z<{I5vgC6LQZOp(}DYf~J!RGk_bF{nI=Yu|)5}uI5F{WMQ^T#X@DSxlfzXTQk)}&)W zlO7hjGm~#bx8JU}3k7zU?ihx0dmM)GQ`uB99H8IC&sJ&=7J!)Bp<xvzB8tbC6Tvhd zSXd|TflZ0fU$${rkAg2vN>JO0wklkOpsFZHEwa&Ma?PDXRc0_TXruF_|M(-l$L>(i z=|W!jddeLa$Pi2b`6`Zr(cEzoL`YEa`4YZ=`EUtFf8=>?{%*-~;=jyRaGJ2%Ol+b8 zQE>8lcsTMHIm+*juOFKpjpef!ZHDkc%%+9)`{K&+@p2fRP#b}9@C~7v;qit+Msql7 ztyaDsB=G=tVV!us)naI=CvhGwNKmK2tVn6+eO&Xk14r8Vg`GpKId|`2905XbOrHB! z&#N@`1zMXEVU5l*qX%<scjHPJ-PH1j+;?6hL0q2aaXO6dTEwq?PwZK%v}49YDnrZo zbA1tX1_QskH%S!F|4S0a>16r^wIl`F-YCpzGvZzFdW<Bku>4pbeDb^{p{@!wIYXH+ zHPak5S}`kh8$_WjWXmIJBD?6`^JP?VAbqq|MziuP;0Ku&25}zSK8gC;X=rSeS$3Ux z(t@k$E2fAnP&qU8^%_lIpNkmB-p5j!(ax4_+eqhz2*JJM_4?c}kgVGn(d^DECaEjW z{^!4N=c?M=qBeii#%Wmf9<uNKR0K2GD<x{o&TYV7!%?1Zbdz}RH6#Nyz8_*RnJZL7 zE5cA*u3#iR+{x4tVX8<=?p(OmFj04OECW$5Aq8kPMOtjZTW=lZqJ<v;ktpqc!5+vq zp=;>H_t>ASttY96+*jbKk&N(^vx!g8E*DyhfX(#IPH2Yb_kLiBgvXD`wd>7-XoK5O zBy)nv$@sPEPNAyW+ORAvGC93pVSc^2<~ToAT51+^Yelyg&F@69aiIlhWviPkbP&ux z4U925%~%7T1D=2r(X;#hVdJ(QTJd8YwD#+!-OqqC%`6CAw*$0)0eveKnx&v<itoLq z(p)2S2Pf<?S>XN&QxOiJ54n_+U=m4oZMaA9$~;dzsil2#S-*$k_#k}PtD;G9b`r}= zWu*CAiKL4a*FV4nTJ6@btT4IvU3@2d*8Ujyf^fIkl>&ARRiSxg2oDY@IA@x)+gy<j zXY=I1FAcljM|~u<(nISga-wMJyD@#(Z6jV^mBy=mleOBdv3hY|!M8l0RE8(j2c^n! z!yn(i?IC^GC34r<=&n@JLw+MlYH?!-WPmnNr5h3$9!Jc=V>Pxr7nR1JWbpWK^M5)b z_F_JeSg+JZCo6D5;H_W9Poz?t+$3>fGC!O6GP$yzvTfq5Ivz|m>LKjmdrc5YPpF}s z&Ww|zP!ZZewV4Y_gGhOx`CteiY*FUMr5?E6HzZ=R-)i7G?KN^<9tU5T8YrRKj?rN< z*sRtL0l;AzBw9}^3^b$(-01Ya#JWkeriwB3rNcpyCI15x!r_PQ{4RxzAIv+R^8K71 zBf}fNIyxKw#BtSgOC9KZl&ji1F`69G;)}Q7yWz0zeJ0pt#Ak<Z@?&U#GJ6J2wp1qH zY=n%ju((|<tt?5_sjk?~q2j^wBDPlF%n_iS+hrsY^acWF`cMSq-cTT07tZB++OtUr z&5mt8E=RKSX9pt~wnWS>9weJ>w?uIRrl>M_9kA+-ml4|aJsI<SE(DI<PYyV1L~x47 zr~dYn^w1A|F!%>z$F3XxwGeTd^Ou{dH`N36|CJrR#jzQp{gxLqcGVSzxdHIkkYHqT zqAnTxcxJOdaY7lD&yB9~SrX1plbfsBRPuaz>7^Wsq{hzg04V#PTDf#bM@65yWtQF@ z7C2ntXS9@oZuwu)%>?e7LJNR3RWN%0LH-{-pkRu+uIP_7i-Ls={EGe|Z%C1YxYgxK zA$;`}z<ecinn1XXmcCVTMC~XqSRvdm-mMYabN6Gn<MbVV*HK9B2M#iOlXh8);U%&= z;{sQg6Id@k7pR6o03`EYavt?OH*XT(hX+R1s%axsoad$k>O%QV?3EiumOX4#wms|! z)cJ&VxDHHht4O9xTWUtTh;}EaJiq6B%-12?9H;Szj>lUT&f{H13KzVv?k|V;v)V#S zw`;79udOqsSf47(@JT$YxhTpT_+%=LBH!q|VxQse0zPL7Z6nJ~HiXn}TM@5SzbL6r zbc4u71Gs@33f<sVA+8+17dX#{<*|ZhOcVA3Rf#|n*)#Zm_8PwQS&_!G3K!BPfFjp} zr)~a?z^Cmojcs2$GU0dDtqHT7S!Cuo<5UBoX0DHqr|tMZxHVEY9i_jOh3K~~zt{UD z*X`<p;%d=U#enlMK?8@1+<A2}r#2lbnzWtf-y%2L@qI$!BJ00jc~t9{5hVybK($>& z{EvSi(%BqtcV{l%yjT>^R}BqtUS5Og@s&u&b(`9{bDxwn=;k(IUiCa8=XoEP<OH~V zV~ZPV75($Q=ANb{^<yd9<%X|QFUQVHiI$4(ZLLss;%R%aQ?`uw%Za1C*DzKbWu-gW z^%A?Q0vZKxVw;T?xz@JHEHAM%{Z(j{m~5vuC8ntoPj?DJYC6XS_mt2h#}LV<kdn@; zMHu+Yb&jdHG=~ZjUmV-Q((Y{cmwqtT>U&ji$>Ke@;pKH%Vw9pQNE@sAz7T%-zEG3~ z7^{!xu^Zlc!Bx84Ru^%vsOK2}JEk6e4?;5d41ti#2F9?+iv@e@QX!LzI!%iD5sr|7 z?>_-4){)Oicsf7Riq{iqxKtiJSHxp*?(p(1pI}Gd*>R5aoYCs~9+_Dy4QL4N+^W-e zA29Mn1gI-;+PHo_0bC&CuGR<4ZPxt@Q#h4z(aHi*n{(oaVpgZ)rl&W=n$7nPFbqUS zMyGG$CmF=?s5bAU3`<GI#M*FcrUn6uFZ%)h6FGz<r-h=_gjxwKUL9lJGwQTDb)XaJ z3WM*ND%VTJ@y7jgS5AjwtBwSJvlSiU2NllLXBQ5z&=U4r&6lO$UyfX96|{n}R8h@I zRY&Of>V?)WjvpQ9R5<K(<0Jb%gRTPJGhsfgY6L5LH+WN)S#Aya0G_iwj>Cz17sUgI zDcN1`obP<NJ`<^!toGb-b{i2tJAsfi(X!Q-T3BaJlL9j!+BuOJpI&g=0@G#+J48&C z$D<!+kn#A@9|+v|6nOqWvf3_UWM%|1uTrGKVyn~k0Lcpd4F+Y#U-ad`W}&M>do??h z)GxX<-9LTnBZ!8tp>$td{5f0)7yw5R2VJKp7|yTf4_U#|!Q~QMxdwmDK6^HZ?oS55 zIN2)AN@=0?1NX7lRddHv*`2U!XrpY(=kcX(`_ZX$w2$CSW@uLj<i7FJZb*iPQaP`U zk)4Dv@D%u^H{Qv2>!}^zPcIP&rtZKC`b7fj6b4kH>NdZbi9KFR>omw|^Gu*}xHPfl z@HV|p$Jdr5c#V`d(!;z-lrtL7j^E4A6w9iCBh|+974S85Tr4gB*-D*e)T7JMQN4}m zR4QfhSB_r4`OY|o>e4CW|I-2(C*omyz6AzAqG<)Y#6e~kgb)_K`w!fUA^*cl6z}^x z-MPQs_JLa7EenNZCUbo*w?EDq)40&Pg`dgY$^FD>r-dcno+vL3(>IYM2peTQtP4P` z><Wz$@vtZ^l_WP#e7bxNcZ!JSHS^Ty)yi9Ic9|)JJqd|KqS1?6*KJDaa(cZn;H{au zrly8LDz`D0p1Uh54u*y@^E9;nFg%V&0ZR)(BvIDJg)UaMJa^kHi`;XBMa>RT)EZYk zY0f_g9`BZOho#Vhjl_K!xg9;T---K?(>$n;+ht7~a0<GH{;I7sU{ObM1i(MjlPr$f zpNsXs$B6w?t&HG^oIvh4XW+WfI~qi#QkLPE#P*6Nq^+=r^sGa2t+jDD&~o(l!N>Hs zl5%;pV#{Q+(4CTp?_Wcn-MI!yaP-U-KC8nDH)qA-z<`>DKFWPZrH13Hmj>h&+-sJR z=4z8&baSt)P8adB@s7lR2*M+bdX0ro`o%Msp&G@l)caaSb=B;|I_f*~>*7v?yALEJ zftxv_`#PvJA_DWmDufC}EFAyqG0^aGuN0kJUO)4&+FQ#ml&i~oORQm}T08lBxAxPo zu8)}WX(2nPv(nawN}|74G-0||(%0nr4xu=>>(Y<;`7*t7e_TE4#;keTDb^zb&Mzfo z)1fKYX*&+uzW20h=Y?bYTXdIEC<CI^{Z-3*NgVqyb0CMxB>3!4{wO;+mF3oJ!OnpP zf2+G}2h@8_&As6OAaj6*ffoY+s8+Z>N#6!PV-A7rM8dEK?k-@HX?l*w!>ZF}V!`6R z8ZkOgF<7^HBoUor*#tRA_+#cc?h6Uka?1tr5cqOyHW|m3s*Ojn_>rd{$cQsuhR+5s z#__OHs?@1F+RgS30LUtd(4|dDJN~Fr4II})KoG=X;?ruiZ+Xpc6eQdenImOUFJ@X% z4Y>GSLDhA>JQ|)8xZF85|LFeK!Eelr#xKg3w1U>mHDT(i`*Rv(=oNm*)#nz!`6VEe zvHp>Q%fFZTxTo^PQeO+M+ihsixO1@@)OFQO;dv4J^|MbQ3$^>>RApeRRvSVh&(ojr zwOneLe<HKiDapXS!FX-Y5K!Ouv+t9c-E(i?EvPrX58t$+1`9!=xM|l}`|*MWAi<&8 zW$xDCI1pqgl;{s5)y}B-eGHpW=g}N-IO}8p0avXCwT1I7Veb`OnHO>QF|+3|U$Y$? zXQvH*<@?#(qmk)-^g^##i38XG5}&E8)GTs#ycMPgFR|6IM2eA*QQYQpxqHsFs6P-= zb^1E)!Xf-Txd(n`c@<Na&0h8_cjb+=*y{GtKfeca1j*;d!IMvGN#TCGb0~V2+6_!? z2T#s&5lPBQ{yODYqrkkq*bg%08L4BQR0AD2$LfQ$$a9o+{4{F^$MMvzn#g<6@=Dpn zi5EN(?Ek*wIH2BIzyV<+TnJHw8+71!<eK#>o!21e&<VWM_BJC3<;)L+jI{hB=V&H; z2bF}#ibV`<Ak%xald{IPvgm-~Qm9!Oja|2)cA0k8^|NEJ|K&>%$9=9To6!Sep|^~4 z)w>ja2kT`C14Ie1vUBc5u>wjs#+L{Y?B2W7jf&s49`qbMjS#R<6sUdRPT<YZN>6%b zvXg0BvGgQ48hYEdMJ`N~4jRcOsW-p3V3fACE$C~{NSgaayJUpL>2yS@lV7cJbc$Uf zDUeVPitXOsDkn%9cS`u@xMj$tV%Bn-3VI!}msz|{$#ckc?R*-iQ5eNhww!EcAQZVA zNI1<I-`_5?<OaFoOE-XyxpIQ`-CXCb=nnE5@BdKU-%>c>OdfJXt4%FzK$Q|3`?A9_ zQ6N6}EkodBjP>Dmu7LS8#;ogq;>9k)mNnl%=RX>ju2^kJOgX7xtxyLC2#9zl9pw^P zG*!D*RW=3STMtUxXT_eytVI+yq{lFi!`o=LzKdMxeZ0mhw$=0sCr9zVBijZK8t{VZ zi0wG=fi0Z6EK}9k+*=Kuro-Cq`wtgO_(pbJ`Tn9=0b2$9!=WH(B_RJ~{~aEbGLUEY zI06FM2COW%C&%Y7IrNW8zS;hQl~`PXEZXQCOCUKTTprl7=4dmq1|FldXW{}3Y_?e6 z&mtvmW*TlfUg98~hDs^!3c|1eBF@<B?Pn2bK5S~Wk`PYz;YIF>ZY*!`H8{oV^Thuq zLh}=@H!>Wq0gLqoQg0-4<+HJKOzbOaO3UMIUh~~rnD@Jerp{2eXdIU0W%3&2D#&Zf zX5{^NmK5!^qHT*k|L%5g&xFAEhx=#!MLj0mbysH|t)#t1@D4)Y1#~I{1Z6uMnik&9 zo{Fz`dUVZh9!PP$?=wBG^F0dA2HrHg5>h*VPtF7kl!FO~bXGk$uDl!-n>B|SA1&0d zGRCgFV?wl?%|xral{ju>UyXH%Sh}xM{hQjR0``rO_z{ds<Ojr~%=G?x+FXRZc(Oj+ zQ*WzAg4<ww0HDi%!F{I{M134aSjc>5{L9X74Xv$4I3H<ya)%aUGZ_}bp`!5;YA0)# z)W&xzc-wx+tH-gO`Z8cQ4E;dmm@8sr?;RE$18dw?LE-eDzC-Lk8SOxPr89k8IjJ0w zmm402-QVH)gMiRUrFtWl^L7uL8fm>CxyFf(%P@S-w|$b$&sg<@R4g5i6W$0bur~`8 z@|Xb%g7{&kqfamjx6S;QiH{8}a^#M$JhRS5B|R-(xzoW)0L7DNj>p(!2k;g}El19t zNbrEF7w3blY&s`cjOD9;vA#PR$NN$E487K?Vfm&)DRo1sG43<xZ6V)}>?~%HVYKg+ zF9==E+KDFEH81Le>&ZlJ05C4FV^H4{F9&e>cwX$<{r<3-xPjB+u-NSxge-05zy&fN zGm1nKW-^|H_WY8K^z1+34DcK>vs`v|!1b6a<V}e2((AW``iL)vbRn49NKh>Y<NrK% zW33<iNbqQyU-_{lXgs=a;AB(J|L>|IU}u+y!E9b-qtbcIdy6`IPY1$-nKV!DyBdDq zWO_kdP3%k25huG~6Z1sXWv5v#muh+bjiOfI2;4EBQf-Kwn4xU@#AY~0vVKTc`Pm6y z2xnN*u~#<6<o<&b*609d%*2mC^n%>ZQR|7G^PnR6dPKox{$wA9@f$CtoRv2wX45XK zH|pb+h;I&t{@Z}p-eP}N6xz>DipXjEvb?6|&1TzVF46<qxyUo7hmLcckxn}-HJunY zPISW_%a}Z_faBH>dj6QH_$)bxyF!mXCL;n8-i{ihOiGQ9^Q{Ski@2t!<dw}5ND5!b ztlUH$F9$N7!Y%5G!bwYls^#~IsqibG#|IgKjT0?<Pwo0M!HBcL#AO49HuGQrwS`s% znjHUfw3_d)-Q=iYdHZ<HKr~grBGb-=#?57U^3BOu{XeUH>2P_w%`zkr=nF+<$}*W? zAMT&N2&(MHya|%jp5>sczT#ZaQoBfpC{|`onQ!)twEX)vS8>TAtAM9C&qagqInvt{ zMXdS|R?KgfS%cWm-o71JR&Jm!E7#Q^-9m~!0v&`Z-QersscxJ20K_|!8|-Dr2fy#j zgK3WAI=JU~D8+mbWRaLSTdN;}sas{d&EJ24jRLSk8w3Hd0lKR=ke3^OA-by4)gUX; zRLCp{H2yJ;EmPjf=;VNX8i9QUZ+Y<kZqt(&y2|_N?*_k{ukoUBwcQx4OsXMTh2*14 zb%hH;HLB9eJx^49xzajkv0d*#I>}x!TACyBJj+#>znHN3zPQu#8gxNcaCW<!b5qoV zXm`OHK}a_EU<cE<@5S@6f<dpgQ6u2#ExT{=<__TPT0u9on-K1PUBG#^T3`maU)3IW zIJgWcRY+5n`=`F`NK2U>3E2fhb_aJ|okk0!*$$p;)(wy#Y{sd>xpmAc$KbOe7x(4{ zf^icBHP3QlsdaX1R>{6eO8UZSv2zNqPK4Y}Fz$pJ))au=hTrsshR?aGj;{#~`TbGp zEP3rLzkY6JAgS0&IoOrgb;^WaSL#%a7Y5BhbdPsh``SBExgkYM_`+vIoJQb7_t*{~ znBhGnoFL(Td$(~OVbR#lzUmXVHV4NQCzINgR&AQA=ztMvZLrR#8<B3wF~+$b(lFQw zU6t5ld}OHa-Z#B`7;Uo6yY~<!P8sQ>&hckmIdaucRFOP+kKSk{r6vsbe};JFd;9J? z@}lL=sh6u)f4$u)7OBi~=DxY(|E@y2&lK`PG9P9a)JXTWI~DeQ-v)WMd&R!*IMBA& zN(h`-u4?KvjFhI8(O0r!z@D`e?Ud<m?ofEmq`-@}e#?z(&+psVIy(-AE2r8Ee%c<b zNAX{Uht<q&OM6RG2M(yXRcdyDx^;5Y=!b_klkX*teZ?j-bYfEwtZZ$i*2Ks?BfJeK zm(i1BW@`3Wvu&DGXy(1$rd3C%%y#~eaCeu<@Q@mG2UU5PP@Aol){AT3@<owJuOAJ2 zIP1XEAg0!+4dK(djHhAXLm4j%oXQ`|fr@6UDTnBOfKVU9E*yK<RI0S~WIT~ipffIP zW6sMQ_oL_=*7FefJ$dPijFI;*am!j{s8LAt{OX&<9{9~kN(+*Gr%6V9=y7#qGCo-W zTWlm`mu&D(uGOnRnldM$r@)HUo2sZgf|}3SzU2ONHU*mJ25gu_vCxTT=l*U<Q3c#R z!+0Lw1QZFc@anogmU;#pld3wb;|F}+kX5D0xU&2t)=Tm{Yo`M@?UB3@Sr?8en%yQv z6Gr96f-OQop%%*;5acL7PNLviV3JI5RyP3PdieEm;PAj$@08ZW{^7e{k7_(@RSZxG zvhx6<K{Isbn9ts@Glhojxrl(36D|tz$yT8M$|j1P06i*M-vuM`jC4v16`e*>tIBbn zhJ#?uA`>V!0XV^vv3?qMN|rFwlkmX-DdZ&7)wNu?OZbLHJGi>T;D#fAjB(nCA=@Mv zf`OZ0i%UP%;!IG#TFzm~3`qby4yF|jjpoJ_Hni52K5cUm{J`N3nsCUJ$X&!jsTkNM zHD0Q5)vR2gC5^<n6T^%<-lI~$&i5q?@zaQImS<BjF``3(V!3wo&4mnWCm*}B|1U2? z5fe1a3TZJMUL6JGTMje^jtZ0O*iLs9=s!%;+CS}gDSUM{W2jT+9`%5@;ZUuk`B34f zvE1t91|1e~OC<iu4d;h{89j<SWkpCPX2fc_(669=GuP)61)Lr4+v(-^yQV|4J<|7t zqu<dt$$i|G`B{Qi`R#Z^kD>UG4Lsvl47<p4L%c@{uSM>$P{<EcfPmlQPhz<_O0m*R z$@)D5=~hxygwKuVO)1ZRW2w3$xEN&ALzM#o`w3F+-Umv7-_1}=Sl;mIdI6Pd>H$I- z#a}nxkp;kS_e|_&rWb{Wv2fGZ>7dWx!(!;ZMn<=*2=Tf46lk$jq_I6hZLU6}Gsr+1 zwEoBv^ZXb&x}FXH3Z1%TbMlJUKXy4={@3Ejz2*607K6)!w^`SlDBaqum}guWpCm_C zvrbN>S1V`Cy-dM$BYThN@+hY4h5WEzsiIVB?bfp4Adp_}wP2*F^|@cRdVmpm+u|ZV z7;i6#JsN`_2T9<GJmjA<rKNG?@(8p$Ug(v}xKrk@KCj44=|_$@IDBIAy!OxA;c+B= z<a+j`CcGM08*_tyOR;_<WkERH1qtl?V8=fJ+;`b+xL4>l@@`U@$?u6$oRbm|xLNd> z-98iC{1f?Tw0IMlD?Ta(cqBv9y<k|X#Ks1t8mb_pC9G$=--bkHu$z#xHw7#g7@?f^ zJZ=4J)*|uOHO&9E-oCO_+EOs{3)E5xC^kN|BVApCv>@1yjH+U7IrIEMooexwL=fw8 zr_UQ*xyxD2fDnQ8Jc$iU@c2!iE2&A!6(^`jr_G9QwZc)X)Ab?`f3q~dF7|XM&bnOt zWtNmF|H#(-JVUF~jmvhnDx^iVC6zAsB=*jkl9m?Ngf_Vbk~_#5UB2u<{P}>*DjI9e z&D6_@(|hK7!@|sAv>OzP?M$2*UO8TJXPDb`KvV2A#4YQfNw6;!H4!eaWYEQpmd%{3 znEm#PLR+uF#pXwAc6J3S9{aT)@6%zr=VxqsBZEbO_csDm`yZ3aYI<!mk>2J6%(M|- zUb%jTJMvt!3XBpC8HYnBXsT35S=4M@R{R?FI6?G7nxEod*>xS$oS|40&ME~eLMu+U zt!^j{L&vZ5%{x+Vf;nt6V;M)F*ebB~$zQNrSY%4`n#KA`NgqZvk+w7zRb|1YGM2Im zG^s?q-Ut6%{UbmHnBqV@?p7YdYF$&4Ut{_U*`~sohfdr9TI)q=9yNssD;(i|$8k>8 zB@!2x8{Bjr-H=8d3yz4LBZ-gWbNU0u#mUNvKP^I+IGXt0BJbNposYvX@@BCL&bAV9 z$*OGPL=uDwDj9X^mKXP2l1E0{X!PgCf-zq;ZKu#rJ8F6CFv|i`rN6?Hh^+s1KWTZf z*fJI91xT|XjAu~Eri;)d&{0Q=o#bJwuXlC6M$hs~jjzMwohe5<Sg+wb?cd1#Ur$cC zS*ZQ9=Bd|^nYn<XlZb5DiDn`)tEDmRS{zwyRX=G8%U(--QKPEcF7QwkN~Ku@#FFW9 ztN=VB6umr&drW_De)s)PYT|eIFHN+O*HF9aQ-x*P?3LR7xv%aZ9D6UsR2;Wqzj)qA z82PgtmHJ~51R6|@ZOtwS+N1vaV2)Rl@iI*BryiVTWG#<IeC6zmbvz4=RLkWod`%*2 zaj*5N5zOmTnU1GO563;S)xFHID?zn9+AJH=68}V<`y3mMT59Cw+A5P+jyD|X*(ocP z>vNV_qGDebUceK(YQ1t^Gl!Z)6&<vf;x4Nb0KwDeN2*qC{4m-PzQwIhN}BjcC8cWm zq>LRzYOd>HhHF>M>Hbe+O5CA;?b!b7!}-@!EVCqC)-u$G-i1Q3)a2oyl^@BfNt33< zg3;!3J3_dAH+$LnMf#JE9d+Lxm76WpTYjHbF}M$W3zN%(Vj9~aJPv*Ma8(+n{8hPR z1Tq;5<-RU}i!#ckr=qTPqRVdyfLci-?xeL#Y~GnwP0U=&=|fUi8Hj^2c5U6|(HrsP zyf#>eo@Z8k|64TL*{UcT`^!jvzIt&yI!LsBqWb@brf*=cL+iSY)0j<~#<p$SXl&bT zY@0i_ZQHhu9iy>xbDsCRe_>&)x#k?$BzH9R`FMW7bl>$CXV^dAao2oUYklkPm~Fc2 zUUp+@!wTiT54$wQc*~X%Qet|eKwnKBqsZF7xMh{$sKQEn7_oDI|HM=*vcTS4eA8sv zzhEG*FZg-Jx%aG+Ap6bTE6*Vw@P-4-RCcwV1$tU93>`(jZ)Om(s}UWlwkrO@%V+(j zF(AF8XCzR4dkd(p7RaGBu2pa*sIb=80No=8nxDggHH=bY^u#;jPgeLtTHw$JwI9Dj z>O1(F6FYO?5h;u4S9T2cXBYo~msMdcq4bw>WK@lvD7BlM-o1+3^_0RHwwWMq+#8@< z_r<kaqv(1!;{yv<`j}%M#UQ6wpT2oAn*Z@p=hGWHD0R};Yd%8j_s6t9$EX0zKbH=a z#UH-a|BPoNdK|OrCJof6<EcZOnA)*Mh}VN;(X6(sfvk|QIZHV$^#3kYB=!m+n=OAO z?qlD)?9$)hnrUp__3BWhN{Gr?lj3!@A!YmcfGm?O4?k&hEq9ynP9KdDAi1KqiHA3Z z8`fpPj%tg>WccUR=xzF~K7_kqHk0|-f*-bT{7$cpoTv$7F1F9f7sv05n-R;mT`1-V zlMbtCdzHG_DW)uz{eZ;xx*_!W#SF#&#qske_3|zs74&W#aqPg$aaM#W&kLg<Q)HKm z5BlD66v=+<>2mGNA-RuSajnr_qm`CX!a+%~W*`JYvvyBRXMZOX;FmNye(SYqrj!aU zZ<*I-BO4@r9jJHJSBLtHgMO%ROdnutdT5OtC-OEkFTMFMX9yBj1j>Lo!w3J~%nS85 zUpmHorx{$1_l*X}<-(v;A__31qAM*p5rgn^En=Hg(BYWf7UXg>p9Ql@7`>P{2h0(Y z&*P1@^LEV<{^Q0$O%8CfnK_N`w#NoD!z43AYG=9+!4gjed_Md6j8x~b_t5f>yobe& zYo8<Y@3=+lZs!7rZ~;y|Tjid`WdWn{3Fh;^<7)<&ah$8rWt>ZHm;UgQ%)kXXUX0{0 zV)h?KsItlQCtd$@FcTFMxPz1>E&NM`!vm#p&R}qn`rM=IW;h<;oVjpG<!reF;dDGL z*u-nOmn)1o40>61Qpcvyu&|%TY{RAN0sNy<xdG92eO)Fmw|rH)?$l(eLQIVpVnABW zO)XKW(+z?D<comBe+PBed>K%Z;|ULawe;<760D$JCo07-cFJPBED&B`$jIKLCRUB1 zP-TxX?86Kz|LBSJhT~0l)p~@QaeR7a<lSo^(OmWJHU8+%vr&<^THs){>3RTZ8{)CJ z4X8v_YmA`Z<pWqeUv*qF7~hy}a@(RE82;7~mh=rL>o6BCa5uM6=;4#&{&05YihF~_ z=#zPNK+isX!YOa!`1Q2;J+D()hUS&7Bg&(w|Dm@H0EY8>O?}|w_x9HK3I>u@)ycno z%(ZLisEo-C*k5@*PAtBxUi%H$k9fQ7S1!afH`8h+=4*rq(Y>!sF^nq;P(_2S?lUuq zCnh3}<>m-Uk(o7-Pw?}O(GO<V(P#4_e0;uu==!`FEn2t`T(v&gz8AbnHn;cv3gTFI zbmHsiL3lpgTDj@v&l$XKP%YRfQrpv|GJCRI?#*ZaJ$!r%V3Q6rRs$qvA?Bqi`cTP` zG>lL6V=3PZetaM=ng?Oqb->VaGLM4+;Jt_*hf`K4hDa#li@*PAZhW&BEw<{h->fgg zwQ=-}xs_H)w4{Rhb`q>?=D=vH)ctzft-06LiGRISskK38-bVb3XT-@`YK~i;<%^e5 zsGZF2@5vHh54Tp67&B5MDpzxF9BMCF4o9>c$IsIcq~kR`sQCCT;`*3`y#d$J;`-3Y zyD&Nc9-Zi%kp|~qzvbs9CG>E#9Us>O-vZ@+s8;J@8n1;rV)c#AY$KJcmE*#{m@2tj zvdZHbao~!Tq5+++aBPN!%_KX}Y8wKhmf!-ZYg&oa1?h2HQ?e+>n*_f`-XNM@VE75! zlo;$MlQI))8|vAB`~sTsgUW%5JdhozZ&4~{bwdUm*#RGB*~+!Fe>+;kHp_C8NQ94- zlqH&PxMbz(#Lf04o!6!q2>Xe=kD_vIDu9AJ<U8=HbU9c!tNE^RIMkSnR*Ph<HP=Rh zFSmaJnP<9~(ilB4kPfvmCttsX2$EA$f=pD9F6Wo{GJqzcRT31Ml(3iOt4Z)|n({<$ zm+?{qDaWxQ<(<q6Ex4SWnce)v3HG8K@(?c5D_fpq6du+D=Q$Y9HGoAQ?us@J&gxN; z{#dz*U`_@dQaSRqdZpLRXyi52-LVXU=EWM3`Nn7M?)miyM8^C=z)$H^2y(o3{sp=A z`ldkk&{-XYL<cf?s;T+494;8SF^1gW&V69?aF#xnW+qw<5nTjI)-xjy{+49^L}2V2 zKNgPLc9pAX2M6Y%F8Z{pYJaT;mw((pW3v*-YyJ;&g&M&M{pBc+K40CxT%|N#3FDBM zPhJcXTHOR3FQe6hA5b;{NPJi*g_WAvg(Wtywyz^EH2nD$$eaIqEBc^dMN*PDp_7Qh z|G(iO@+=^S>tXGTa>={$zJZw?N*Yrh;dOh9x>TpZXSUGde7E&L9+9r=Fk<%^Z3fo% z%G)=t-8FEjS~Uj}JAmKa@&N&J3;Evj{*RMeiA%ZecvXhVpHm$9=94Hna#=IT3guMD zotWRhJD<+r1Z%A5VA7jc+1<~g<wxhJ*wp%tYG;Mj<tH|%_($gUnb|Rov@e;lW22%g z0%kt%#O#+TOQ64A_O0M-aHCt->z(IM(5;L3dDHl8wC&Gro}j$(KHX{+_X?mEjTJld z4|>|nAhEEp1BW7kkUi0Fq`&xmaIOzLR_wGvJDl*@KU;QJ9MA&Bl#3z1m8e*1Ok2fR zUzaz#`^xe}SFupkE2T(6XvM7PVW-GolT(vReYHqCKM<`K=GQl%WY?ivwjO@G{kjVn zYAAu~s%fL3NKHakDOI6vtzY2}Y@@W8BuoZv+8s>w%6HXMOsj*|kuYoJidv$d82gPz zF^<2LrAPtga2vux1$r?xm*r4j!*Y6T7YHZELq##dij>uniRHy;=_RKh{HI6ZXlPzM z@|Ml!AwPGgiyhjfLgh#Kip@`+o5c)4DtTR`aGhrbuBPLw5+;;S89K(5p3mD75lSrv zZ>8A^&z9Zcb326MNiCfDqvD}$Y$sMWgG|ypRaE)D?NbSHlfWa=Nbf0{bG6HRbyrSd zZpv&6tk1oPJ_m9)I8)j^$y=I|zjYo>3E59mAHI*(V7=w}a5+!g7;qiVG+R(gM5qz! zJ<-2b1xpF?b92M|!vi4m4T)gW2=c-rf(U5q{G8pc>a*y9U){{tmtaJBL>=zX+n!I; zSsYHLuE0sRnM|jC7)L4&L_`Rg@y{*O=eU(gULAa9ZZxGimzTR!2lPV{7Y+q;4nOul zIeU&9HBP@N2)`Ph*@+CR$7@Y9I=iLb#?}+41_QhLpW7<#BI}#p#Z!>S0I3o^bGA$A zzJMQoly)YK0R*Ck9okAlL9?f_tTQ}ID^c%%JI6o(RM;oFBqQ(dOUTMly-^!z1|d;j zLx=S=KU&ZoDOHallPkY){1&Y}!W{(tMcB!6hs}abih><}&`d|tZy!b0v<hy0W<uPl z#J){&($X=$=@SfHOS5OySlQ$Yl(b5x?VFsX)$xBA&N~vE)Ee@$32$$izEsx8N+Lxu zwi(KFVXS1}Qie8yN`A5ED<45Wr=}<AC!nIq67fsEP5FF~q!*HSJ(BM|o#cE-j*(Ha zif@R$R{Ghp>$e&NL0yt+7ns(<Wf1Gtuhkkim#MdxW3dzCVUKAuyPjAT^MDwFbr(&1 zC$^ulvC(%vW=l#;F_`m32!VcDHvm`aihm`EXd4uL8$PFIY+2C6dOa54w`qvrQxs@$ zvd29)eNV@{M#bOF_4kbs*s7)??7q4QK-LmjakVcLBNmySe-_4$xip9gg6$fOU$GYJ zRxwYF6p&|Vi_m6sZL5&@?qYP9|AQ@-%PIzb+Qw#V!HmHc9~0>Hp0jhOzFXQiq8yZj zQR1#_T1!o{af0l*I34ku7vcvC9oG$jhJq6!%5>E?tuc6+pFHwEOe{@QH<`1Q2z;-` z1=|20jy0F_nW0biYXyMYt@y?I&<vQEmy>o)F2|(hcG+Zww<110rXH_G_c6s|FD}pg zyoAzf#`tIwIi2aMw8WWYWeSq<2C`g!-)PM21Y}|UyJ?=7R6q0nJT(HmKXaLEa^p2* zBQecKPnm)5Y;-{h>Q9bd=)d5qsbE+jnw~*Q1Zk9#S~Y}1Ix$<<^=#2-_Nf@&2pxsK zQCwlA<zA`OXd2~N?27d`DeEJXg{yt2XG+P@gFbC}dAX%UTAX*JnG%l>F0+my4P+OG zi8Ot;zOr^|@@RbmNepAf3Q~Zd)4OEY40_J$_Kn24oi8Z%s*^y&)mq!!xpS!`UX$WB z3A`3ZV2_?Dg~aWaSh(3_1D=OF^(q2^>(!Yi|N80!gBbVyVw(|Anx_?%P(`r9k8akX zXd_dtYd=@pt-YgeGTM~8S#74dv5(37r;2R2(lsL4RvVv9C7W52D!hC1J562Q>48`0 zbd2%UKb+`{C$CLu8i~Q{u}s)-*$a`6Hmqn-S02@RzLQgTLvU)fZ?Me;(skW7E%DBl z(LfHXchiInr^L%8lxuY~#r8fNK_oWZ@(AO1Djv%j9;|=Z&q!=pWqXxYc-V|mBr`wQ zDSuh6rT4E?_b)>GCac=nHfua?$lRR-ZcVk0G27VTvRHg9C1iOaLc`KQ<ABufKFSj2 z!V_VWNrL%OrGe{TyeWvIol+Wh=X`ZY3d4a3=(qkONJ9rnTfMu&mQ^=KV0L{q418Lq zGS*y64#={FyFeX_24TTsuhFt-=UK(}!=+Zlg*~hj(tn?HC>I2}if42S4^!xi7^Df= z(%prE)qIJ7J3h$44p(yWmlD7kEMHFqvzaxo)tW{FxJ>F_KHsjVZjY#CEHy(Satr&F za3|qFIhh@j%hX!(PCw?~$e^D%CAnn+sfttv<TsCGN<#I9$e>jM>;{=B8=%1?$-Fnb zl#3)d<gz_;Vbs@T(%M7>+r7$ToRf|CK5lTA5&~gpt(oq%A!oE!k(%Iy9mGE#(lkq0 z1BXT1o8!4+%4vlVaeFDc1~ECRX23N%WcAE>vR$rR$Ux6B+WbZCgq}KNC1-aHGWy2> z;;&tH35@EMDX@Pfv36Otj$@UlR2+UnkE)JTuBP}gt<k$~jM3)mM2^`|zu#rEtm5rL zQP6{Zb5i;EQs_xmlr)0a6+uTQ?5<F7<VTeJWR0v$2rpCy_tXTnZB?C~(vbA7ji^>^ zO<c|LF8!^UO;-gb@YVhAgHoART)oCGrgnE=*P}ZZzeqsZxP96w(V#%)(Tp}xN-|C- zmJc{5%+ANq$T@KAIqW-ep1TEU8(uHjW7s#!;<KGlfryYnH(ANqhTXUifVTZ{ttq#} z<J{;z7@*%W)9|!e)L~~LB#0vl$Y|(PFX#YEX!TvDY~USZi4Y_d=gI;2Oo8b%4oF6U zScdo5?5)7M%LHcH<BE>SwDs&{)TcvAO655*RpD|Tl3$+XK!MEC;-Hp9nrI(SIO}h# z%5EBwwRaO82m<zM9c#Svxq;1{gP)0+ptOILO1^9=BzZTCSP3xG#Xb4WvT+#D>8FvC zTT&PxU(hX);QZjhWaoH0nlnfvG1EoiFm?lXg5jq6gW>KIeP>!lXMMDz<U2L$ED=Cf zRJ7>N`J~j@+}cl_rMVZnW~fc|sCq?I?3zy3#Ck(PggxY6o2&G!|899U<oRBgH({r< zhen5Z4Vgh`IZZ9QNXx`}ZUBCCjz+|knO}Lg=B!1f_PUqyG+8lic#QrP!nkn~*sVIk zuSp9%r+<ZLR9Ga+dJJ&b#m}+mxiMg1ezlvM#Fy!iP7eeU0n@eG0l^h5dv!J$w^=p| zOsvc9%ung`+aBAQ8cms$S}!tpo4fJq^n{`Tzo?DY8EvQyMBf>Ld@i^4dfF1!ySKYt z+fE(cE`k2v79W4K+^lRT@G*u`3Z_O>fO}R{5_O0m9{P4T6C9ij-hv&#P1CRCWjcV_ zU)O7s;wjyL_}}l?wC0Cg_Y~0Y>MgFeTju)h<M1yh%!vUH5qHs961ZfXI2<mVyC88T zwmYBHv;`a~fiQ~@N|XCJ;_2%0jcvQ>(_}C|U|2D#7{>MFO4opU9UEZi)JCtqH&uI} zpzb<>AY)3E3eun{U`7AT00PT=3*8^!z$aF0mjhwIjJQF{s{yk0N=<t30XM{oRNC9C zSEU~rJGFKQAVsi7qm&;;yq2Fq6ejElx6f9e21F8cMb!#Yk6PiaetwF!Wy?hOuZ5pR z_r2TQTfGTz4-YAw`FxoTE~PR=9e;cv9a&(Zc*lojPIMfQ1FRabiO_i2a90))<e0_M zUGw5KiRPt}s}f8YivV4|)a9L0=>-aaj+R;$@4V?*y=Y#|b<YAbFVGXg5JnddjT0ke z<t!~v5(BKf5F_At-wy0xZ%M)Rr^LP#Cm+j0bQE?~HH8P`N(2!^Z`i3FO3D;?P<ziq zL44~t$2HAtJ4>;ug!d)X3)>DuMr2_7%uP#>XJkpQ?QOsARy+abHxk;UG9nimrdmpf z>P8RD9O!AGJ>?d884%bdCZ~zuAQD>s#Xw9u8!n#)-DXl1Dmtti39Yc{AMVPNC-Ttg z--u!QlB4G*i~Wu$8tQ{(BP|L)Qp&d*0`+fK+4hyq$>6{ec(#Ez(46&f!Qzd78dN87 zZa4>Q3|UFzU6nCVF~@V%>)YCdXFjNSl6ANpQQj26urgG=mTbu7hi&mPxcsgWckOrG zIc|2K2re_r&WVBRwCA<WE}dJO_MY?&NEDgVT4_4ZuwhQDf+TbWQ7dE7P8``b>P_?a zr?;gZ{{a46dS^^CBF!MOR)Q2bks)KzMI6OE`;m;M=h+al1BOZtIB$XM+04n*g8*p! zAx67Q9DyoLd{9w*5ITCGP3OqqeKa6ly!2nDQ!|)-n%+Yp*b3G3Uas3*CBAIQ#ub}g zC%>Yevxhg9>C?8i=^dMSBjlZ>7Q;ccCf^LttGeFZ?M9AOS14GVCK{?1@|4{?=<?_N z!M7}sE=xA_@ltl=5mzP@@x5_H{?nVHoA@v-rg#QT9>D2ztc4d4QV`54eGIV8TF;nf zn5m;>lwFepQ8yuI{39q~Q?o*o{*h(jX<?L>;%~a^VKeEb3_R5ovIuLh-p>3mojkS! zyf#(ncfqimwX}{$WwEGv$PC{?)(3oB1x^447Dmi)FduV{q9H$9EmU)3KKv4Ky@vmp z2pSe5(ROjgfq}@TriWg2gEDC+wcW2zo4US}(Q@+|#cH(bhX9_pL>ep~zEhRO3RtCq z@5bvouKtv&jhSud{$`W)vK@i<4R##Ao7f6XUI)C9voN3EdwV+z*+;Ck>sB{C?{I;8 z;(81jPZ#1uF_egWT4c)Ww@8zE95uKgx4k~x&N4X9mG<90DQ6r*_#2aD{AnwCo+H*< zSwRxs{h@tGKAHBYoXDAij3tF7BmhdZ9#(vKT>tL%(5nG>v`i~GB7eChL})n<XdH4D z^3i6XZ=QPk)ldKw2U78-liTQ}+BVV7%np%}8BNkedXlnTEDQ9EudVx)%S%Jy2dmoX zXpWjxPoMBne5ft*bJ5@e2o9jvmo+MM0h|euXrNE5`2Bfk<aT}(YyK_%o4uD1$l<OL zQepo7r<Yr&kc6}{$&;Ihg0hX#QMkm+_*uM*1l9GdiWoZyH1Gh_omC~2#a{*R?^4Zi zY3fNDv5TG=y^NlEg+670YF>f)yrhSn-fOwn*~vA;x$S_>!e>L+@mN+(3f(%b;|5+l z`e^&yF7Dd*Y5eeXN2=@hQIhH3-NHL;J=1z?DT&mGWNPWg!f`X<?07k(p5Xc|rF<n~ z4G3tKrAUp1{*bGI_?e@Sr#X85g!5}JP2S)R?LUXXEqd|d9or<c<^o;fNO8UK3W_{8 z&^#Qy%;8h=#20<8_(dGRmgIe~uR8>_(0vVo+3#O(kPq=YqKC;uvyD={Oy(du99m*0 zYK#e8%FmAZIDRE4FCMA(7HE7xa#oltbgzx?t8LrGrjzk!xlY0*B`KzkZ;RL05&_5W z`QN?DQS?ptNUN*SY*YrJ&BU?#DYoF)eV<6%^9BJBjwC*Pc1*VoiU|{RYV4<~l1Xxk zoH4w)HXrG%^@g79+K{0f*&yDD1>P*WvGbLTcAMZ_m1;e8&KK^fB7MrZUExeaf}LP@ zN$@}s&JMTBq*@}<LgzAd2NUa*ucmepAB}oQK*Xp{mtNA-8-G9#^zYdf!AY6jbG}oD zm95*g6=f0)Dd~abm2XWBz7)K>pxr55>cdqyRpzdJ?_RHiy}seVy3$)W^kE~kC!Tn< zGO30A^x!+Jz4-pIT&g(!32Aj}2$TD$0B40NPKnRA#pZ4LIgw7Cef5E6|23~x%h<|5 z$V9g`acs{`BYH5V^>m=bI3?anroV-L&fOW8MyqvIBS%lsVr9VXzp(RS>3UM1Z55A; z_!1K8`ufg)(;f4bf~>{|>Erbr*8@&0D_9(b(voY`Wt=EV%|bYbAgM0D2V4SN4ETa* zrC*NT9B%i*!W{>|W5;MySrfY69>>R<&WpTWI5-PjWfKbf!X5&6Z!0L3t~Vo#4yIDi zxO$t2llnjR@$S{3xvbH0oN!@_8p>imZ5EDy`Ub&wG*_oQ?ch>nBoG~)b|Xn|Ntr0} z!;sIcE)yWw>)tG+%^a1LWG9nq%^#(oUnlv{Kc@UG`6HUMmhI>ty0JnVXtwlu`&n`@ z_)|;r>TF&%`|5*$$MBAoZrO>ebAVi8FGs=joE#Ef3OXO`%skXv-eZ=04T~}%Et3*u zNJ^><m9af!LAg#E^BbV))*KT}E{+EZ^}Yo6qszhUmS@Jk=t{{KO5{_rIvyphMI<HV zCz8dcrc+uS4Q|E0QcW(9?hYedFBw(ar9Rq!HsNbvbO@cRwy)A(5JO3qbRl|gu&tW? z8c9d@g|;u2AZMY*ppEmXflt<qPM4gydXlghW&Zu#jy$x+*K1-Phu<8dpac1~;vnRt z|7EX@W7~<7R;;hLf$=R;XBXebWsykN^@(J$Q`do+u`}4SHS4<yE>OlyAK`o=x!fS- z_u&^TXXDVLGyjW`g7t_hmhT$BATNGgoR~lBxEmy#DF<1?0R3$GtEMRrw9RcnNV&=y zM!CU<+67}Eb?X&=9oEO3ZyqX}-6q3AiF3Mj>*rKQj%+{($<FkF$ITJW4vnWrAo~em zEJLQFqK0KkGdp%BxLEY=ZpvdS9e{Dn%3gJ2G1m#O*s2UKL&nV$TcNjGSus`~K(vdw z-8R}6Li!i*%d%M!92JCg7Z-`oSx9-NvJb_&xE^4wJ4|x5ZZ21&zRc3TYZ|Cr_xh>8 zisV%WEJ(!*sMOu;yx(*GRVA+4Ij2?;Ub!Pp%hnj^Y+M4!X4iu<Pn<PoG!JoQ2$zuG zR$vxn1-tn<x^0AK>B)!dYc%pRoOrbafU+|s!lmR$BN$FVSZ))_JvFxTZeMA#*6G28 zXdT)eEi4KBGYq{{J{hf1$dZeIHsR$1V0yV2UyOc<(GMEkI+0#B!Cq#B%j*{NFCnsE z=py5?q9g;=yycc6zw+g|W9QzT(T0R6c-^b88T$IgrIJvB*=bc9rvzZS7#2IZ_AtYQ za8tIEn^&gS16qB4@EiX<Te&B@Os6eBoK|NmbLj@hdl|&yY{jl{=A2!huh3?7P}_UU zhGRRm>>f{&I^cI4JQtf_Dt@z43;o+#5~#2C?5BNjG9xkhmnmyl8pf3B?cCM<U=i?w z*^<I{@Xz}F89R>n8?9YTB)*jY-O)GN2!w%unIK3^OSs1L(ZJa>?O@8Vt7UqU;S>&~ z1CMoVpt^Y%X>_`#3y&2r=b)yqwCl>OhT8xph1a1|n|Z=AEw)=zY-yLXZE#4>o7LE$ ziGXZlpKOM{d!KtOW^cL9<?|8^40=`BCDTbZZnhehSpL~QmGb%CP8Rn@OCrlE0;MK; zM*8{8iPt~UlOMRYOvg>#^D>!_*vp!g$eHv_hLuGU*MY@HNp^h9Sy!zi@16F6V-nKr z|KKn)08YmM8jf(~eo8cg9HjJk<`N$xyo<SocMh}Q`59>ULVQ}RCqkcij3z=!Gqyf- zDYKiH7evJ7!r9Flx60>ILXfH1DpQ3oAK<VSKHHtD_26r$jIpnR(HxuxF+26f#ZJQj zJl0KRnKsq(U{a}dJMTJvI!ibiHKt}slH@(O6N824WZGWfE<p{fYpVgU(ut0hctn<2 zW9<amJZ1f1WB%><@L$^_ozG>{ZJ6<%YSYIai1}j4bvn?jg=GuR1EpCQEqTSYD<4Sa zg0P03Be~ht*SYrfeE~I178;L+in(!cy}y+jrVEc*!x_o`j(lvF>&=YEY*rD+$AA?E zx|Zwhnj?+8UQ63@>te8<o)P{%&lELHPxknh*rz4kB&>L2_&j^=hYmi8wmw-r)0=<A z)$W#WV9117ZRb{!7UFmp4Yj0CVtRs^Iey0lH|*e)<0Ag|u~t~++%*@#&^&1+K#pk{ z)}_~l=`a}%l0S;j!jFTqyP(kXfkB`RYn`=QU_YlLvYN%&the-M;d&Drizp>SD~U~A zKF&sD`~_3CmP=oihcKq++kAii5%fJZ3*NNfN|p$05mb>M)Uwh0#nKbEJ;i>t=6Tru zr9*=Tv`!H_-l1|T@y`Dp2ike*c9+aC4{COJ?x9^WmSiVB#(H^`tld2Z%y=a#nJ9ml zD6$n*jd1p|s-6+4XHGoKqk9S~krDPdo-%uh(b*~UlqrVysSmyPv5D$@AG1I8GQ$># zbRTUwo)rob$JvY{H|PG;+h{D4(XCf?<oS8%&lfxD=fnG_VosvE_qkm)qs=a{v2sH| zwZx2&4gS~RDQb^b$YKrX6lfKeC?4akclr$6cAjmER;O-GP-wwL&#zL}JXxX%6oQii z_2%>0UX>q*%nx8U<1rRGpXeUoHr}?oKgM9GX+<Zp$fQ?fQpaaWez4CHAqW)of@i-m zne>m;OjJGbQ)|qE(P$kx1F-mo&r&ENTKsU(RE+|<&<Knx*O>(K)vx2hMt+{aoC>yj zK+?*(Q)1G001D7%2A<PVB%}W{h~S$}q}7B>l<d$Z*Xeab(++@dOfxY8<5xnZWBP8w z>_s5$qhoJRV($&&XIs*3?-5uDw`MtB-@8EPt33H78Rt-SuADX69b*<LaKjA-1J-mG z4INEB_Hzm?DqIuNu?gwq9kBSV>b1S)c%$IX_T%{9al%oinM1)5p%F*?DKXhof4jLR zX=b(KT>YcO9r1|&y+c>3Z~rPMxk{{u=qaC#d(%u(SSY2g-kL<GC79k~O`59bTBki* zp1fG9qeaB%Qh`ALG&&o{vJ08aVw4Pt%_4f@*%Y6yvTC|&eZE|)lP#735Lv0##J}7D zC$0+N&5ySzwyt`_%T*}gV7<V&W9lsixUjx?a!f|+IBVIvsZ=i0am$!2aShmuiOW@V zaibEyZuNV4IvhTzu<l=}nW%lToG<2uuTJe7L=4IrlnH=BY*04q5iZ{QvC4zkxa1`( zVTt>qhKG|-W>R%&L|h||9=U%_TvgL$UTp&=)oX?D+#6FDW2h^<_Kf5zGtB@gR@mpY zPhL{E0y2wzV`>ZEG#&p_n_6^BgAo=3=vvjH@m576<NKhU!^dgd!}3T?eO|-l=K!ep zfR~=J5q$W>BkGj#=F1J^x9P6^7z#3n<Z|iD^*=}B)HO+nm)8mPMG+Gz(bz|K^85*Q zV!o7~k0nwf&XP$e#CxLoNBwZ=QpcX$5{V7i)MY6^g09fUk?jET)>@pp%L7djJ_p=; zladLyou~vsJA~xcb%et?anI2<vmAe(M;8BInQ;PttBbC3n-4cRos1{b!f)RqqERt^ z(k_*&CBc$LjsugWP5wn7IG#qgOayLqNL^C>BxPn5ZN8F7+8>gZN|rK*mYTT6SCR-P z9CagA>3Ih6za;v2hui%r#%Llv`+dX7w8VVbl*nZC$S<#2m8;uI8C5+^xYkELn@Jmz z`0uMy)LXl85Jvl#^bng6p>e*!iQ^B)f4v+j`RpK9^)<wPZQBr@odZ6P(}L^5nckMe zaJ(l82xGR_sacS*#b;#``yKJaI<=kzC05Px{9v>~!!h$8zQ~6J?~nuv9fWC81k%gZ zx}<hJAHh8Q&wnWK1ieLJBay*h;BesW3J6aOSN1lj<()5SYP@e7RI1$aX!Py_(fu(o zQp7>$VDq01Tya9PnS7EOE!^-Cbu{MYbPnM)ny%a+2`CdBg%621LXLgjoj?&;Y86C8 z`S2L~r$w|mDIMQfS4JC`08B1dBxQfvDn-5{4ke7RDQ4T7GOZ=I+GKw(TTyW<eeA>4 z5amQ+k+n3n3B*P@1P&uaN!J^XWl}mG1+z;9U^a#POlE6wOOD6yp<*;YXT1C~+xu@P zDkV0=C+eOpai%89WFVHgwNN{_{PvMMuuxs`KK2&UJFvhe6e{35>+<G;%fzW3;B`}M zodV?OZgiB+KWv>Cy+nFQe%iU96OHc=?mnn9Fvs!R8k;{IcD)^n?TMIC7Sn98AU6_6 zibv(J%xU&awVpyQQ!M!%Lt0>WqsKl8@-K$cz7n|*k!;x&8GYH0`zCy*kwv!_*SrdX z$>jbRe}Wusd8|dR$0qiPF&2@c*uZcrVfDZ!N{#O@IV5ZV8Z4eC8~8*f6^d<}^pAfs z9$ua%Cd)1HTC9tvHZZ&{ngz%5m+){ZnY>Gf-uAma3&^@UrB*>a4FrJ(Cz*CV+S6!C z5KWouUz;hn=igcC|3MNC;(I(e*O3JakVQu?y0Ex#v@wT#Y&JG@Z2x)3#7zhcXqhS^ zBBC!_N|&nZlyQId;I~+%D^?<i1Y`y?z+R?HoauSjwai|F2TIX}a{jD@OFL##N-#NZ z&e}(eO(2?6Ovp-%Ni`z+Q?8P{`m0lW;IHL-TS8K!UbD>>r6>q0#!z}<Mg}RR#VH7! zQIXig+5X-H)pV9Rzk3olE2|`1|E9R5X<FvOk6c5P&egrm(}-FS+;!1fYF=Iq)JGCY zW0c9PqX{YXR$B36gKAY|KG&;N;)7wC{RrA8w{sHvd9d|BD}TD~(w`>GCz=NIUq#p2 z8a!_4UR;Jzi?)C3oUfd*?~g!}_DJze;ujB{*APEVjm;vt;mM?0?Q^AbZD3xtm5ODs z%G4?4^u$cf3MZ<wHb^NsMe_?HrRogp(&=bvWqI}tB-AtvSIMo-YP-a3NyL!@labYH zZj+f%m)9yQ;n(04JSV0<l*&~gzXux;kCGr(J#dbAh3GcmMNqwQ?N^YUfCNAa(Hm+4 z2`4R@QE?j0i%Uf3-6y$H!ztu^hZ#Gi9+ME+=S`sXb~dfehAz46?<Hf&AF%%Wsa?+Z zP(dIP#mDnCBkzoOUI2^R?OiuxodEf(%Xy980awbL93Y2fn;mi+|KY@U5o7;f*B7$I z4i?hnW|y=(>T<qQPFN#eRi-<G?+;z5DY0BnDG8ii@;)d<T4JMCHD^nk%tj_Dub!8V z?#UM3dIY**-a%-~^j}EyiHs~t?^hmjTu&kJ`oA9Gho*k(_HmRjG-q1ogNhq7&!{H$ zJ(z_nclc7yYh3k~4@BYAkkKsGs_)1Wd)^wNik77?G$*pyU(wnd)se<|^&o7RSEaAB zeo?9I4zA$B*s*lx0>9V8NM<GDkg@TIgwW5J2{XSP?bT}kun25_S~qGtX~2P~ptlO* z_!WS#(L+d=4FUs(j~4C3MweP#Lv_TFk`Sijc5=7WdNe63=3pXJ^q(%`{povX<R87U z?ah(~Q!40sCO<`|%QZmP10+N|UP}oHI+|^gcYO8a$o$oiPm=S*F$cfYS+w(eZIv5< zvbm52Tyz9UAS5tj<RL?e6{-`-0{Gane9y*j>urv&SXE`vRNY~YO#34M#|crFK59Qp z2#NSbn|kAg1c0Ml12rkuSrA!$IXo__)ViK$Olz0L{Q35q$yo>sfak!I60SP|Y6*%L zNEYAj1%k>BCj7QK83KcY9kv0Ej3U|ELdv@tY#({fbb5P4em!=B?=~JZXIGvjYDu@= z%Y<d!mX6>ig*swkKTs|ipm$*eWqWwpq{sABlMJV&O**k+<G(eb?y>(+bNCWk6U0Yj zQESoxj#Y1V=V)QC2?y#!%ZXxAbiKQG`^|+V*~}pn&h}K?#^L>AN~=e41k(<E?&R~o zgJjQw7zCu_elfV3_kg9w!>E~zQt5=yrtX<eBTg)qOMbaClh%}KRw<uT`1|Og)V|}E zH9ex8^kPUyO{-Y^#Uq<ixk<By=cyhcj$*tYNmg0px`&uB@F&18IjiO#HW#S^*gnn4 zgzj7ozkR2f3R3+h5m3-sZ?uB9*1@lQmZKp~#PEeOyl*LDM6Ue>L%~RE^MI|mHS+(x z0GQ0jxV)XbjUmPZLSF3Pfa5LvQ{S1Y=ETRWRzdd!Aq45bx}8a+{J`Lot)Bazaa|kB z<KzQ;sSv)BrytM4N^I#o2-OAZ)T6=)mHvkz)mZT(@_gUu^L8M>$BYHu@NWS1uKr&i zBg7Q;`#fgCxG<)`p~@Om)ubWgP?2WQZ7GNn)-ar2r{)~JN<}l+KlKv^L}vsMtU{w( z_0BM#PY;cHO2KlK3ZlJ}Y3tRm&Jt-gkKBnYRBT-T`}MjLw(5n^K_DLMYWv+^O~6T_ zO~%Ru^mTNc(jP17H^i2KPowyP6qPhI4iIC5E8bAo|G_!BA)>&pW59ra&oC&ff1-gZ zeYSptU}035efC;{jC@jKgNP?rZR0^fRiSZ%F;HEZj;eprZh84)eDsf};I|u2#qfu| z9yFVK6#tOd-C8Q}=o7zm#MsIN2I{Z*y95G3*^x*R(m8K!0p<-EU~T{^L&9C-QDm9n zpVnikECqfP%3KHm?fXrJF3$&N#}vz|UzC3(_EpI9Icy-psF*3OwLk)*Rbtp<Pyn01 z0)9+rA6d~%=W9Q6@k5)e%*Vo6`g+qe3%{&R>8X?CZ%c*Sn~Ict^PL|@kd6s5PZ@M9 zs~mm9IU9=>K8b5^2i}@|8X_GsYgnc`!;r<cMf*2#2wHyGOu%se0hx4+ULp0@I*3AH zY>SdnAm_4|FHHu{0vn|7S}0pc&kG^C)yo8T@nFv;&FVUi;Vut!Nq)cVnAF2$eGvK) z$|-S8qet!7OaI48{&g!pJUc74u1$0Aswv3!%nE&m?f6g<dmulS*}NqDt@<`_#rM9# z3s3#*)+y-frNRbI?1Z<oEf()Hy={Ludzq}DnJS5W6e}a%_*6Wnz9!&b-eTy7DF3B4 z@0LnTG}9j4DiH#`Rd;rqiieQyJXf;Pl{|aF&fk9Y!1TD0p9bS9{2P_fzUIs}U(-K} z{{kF~wQ^D?eHJ}vmhe(A$mjR`{v&^kgHG#dx75Y-k{R2owoA%Nu~6R3a@veP0mmok z7+vJ-Y`cH)gO|l)Sb%loG`YwiEuE{<G1|eO*cH#{1|4U{n={j!W2V8;R1527xO9o2 zUqWhnMo>iFg01M14PmZGX3+gAVb|XAB7<?JRc{@w)a_ARn1ynp;H|j~8m;HdNkFWQ zw#FWxC%R}z8tgLNES;H*iw#XrqESyIku6QdpnIWLkNfCr@a4|^Gn|oOJ?wi|boz2~ z2ZiXB#Lw3_AnjA$rQaxB6c2tPD#J%F$@gNkG0CUM7l&!g7I1{CeAJ|V5c@!#G_xFj z+jj^uJooByK4}-ZKlPc!q8k2b8i`m1jwF%j8g;~D^S3<8Z}F};hFPtNOUu9n^N>y6 zy|V3U+17OK8oNn{;%Co=S@StkFn$qCAr5!|))?F>RnGlDOEKn!!Y7YS_U!=$B>L+} z48o|;POu#K|2>`*oW1Pb|52(izqvOv8RlY0msUg|#po6G{u({p*gj$e91SAYR432G zybfI!o?~sr?rr6!7g0lJevtDNk6g&F6zs2Q(^hPBZ%d6lUycogV>K~sok>W4CL8<f zV8dI@UZ}X=(5Bw;dsyo5IBa2RjKx0M2aOeCR0PotDcSHK8qqWF$N^(J@CaaWAYHo` zL%7~48Z8Jy^zaME0*F(Bd2I|_cm%C5uO|{A8Pu=~pj>ieQ!G97={9uyHGsCe?2*ah zElCirI){Gd<<kP>Xeh<pnbnq|Ohuk?fpBE{`>kTzgNn(NE(_J^A*WR$7A*V5g_oG~ z+yYP?ae2<W(S<-+CK9{F5NGrVjqSQ1ea)Zy$rd9Cr}7JN-tV;}9VYrO9w@D~EiwgQ zJnIABUPD(?EOtC=OJI@NznqraQZu^NK>Xr|YcjNwq7OeaSr*!4CkQ|^7M(rcX%i!q zI@ijIN4#4A4O)$?9f^Cz66`S;X$=SdE_lK}<}$?Heb5l6rx4)5GD<xjGwgl{G@ln4 zrB%%z_t|~aq4Y^_<MieP!hId!4o?)$gr@z9g2S<8i6=cvE82L1Ja5)s{Ot_@Zt>|D z5GDxNMzxjNm?cJ)d$n1Z-bj1PB&Q=xB|L2G5l~7@;#)Zy{%_N7$Z>WrY>p9q?glv1 ztpG^Vvdfj~mQdZV5m-!zxZoL)z-+{<N$DB{#_-cMiO59=q&n5txKMpXRnu|+uXnx2 zb=K3=6$A%NU#3J{l)lCf0uqAJUdoAKr|rX6$(y<A3@&Km=%SHglT1hq@KW-D%4cr? zfY*~RvvRf%_qOhr4@(|dGbzL!V{~w7YmD-8FYj_0DV%AB0lt^vvducICJMr>kVR88 zNebx9eF6K|cB(2|wvBenW~YC*`&S~p4A~FTo>MRKoKV#(kOz+-O$OwuA51I|h*T#N z-9|mRnY#z?&c1aXDa-oayX-NZ8EXxu87}AS0o(dJmiY0>g^4)|KTrdlf5E)&%Y#ac z+J(EXJ+3ov$ws%r7Hhv)0+$hy02X(t=``aO5;IVT$-{7{-wou2e~}4P{62{ZwHuu; z>*v4+w-7*9IOT|vRG$0+NL+9?To%-S73r>hu7YDPC;^;F%TM%tLi^W+$;7AaAM{-) zWYw0$caP$F*w3A8ejmHZzYY1fcY9XP1(m7Tre)GQbPxW_kE9TQ?9L(4Mp&B<e1H+u z2{|W~DLlwD7>YNK0m%qgWeNwgL0tsn1=&%Nd7K<`z2h53;PIc~8wYn`HqfkIyIK1S zJz&t4I3V5A;w`(eS?8lZ&!o+{ylk`GpFz<eqnU6n`=Hm&6#q<ZT>F@G<1(*Dy<1kk zSO6W(dGhB4$PN|hPlzZiK&fogDQ=(~7pC%04-^qQC7Qd3E>tnsav>WvPBGVUavd)d z+KL_Be>JZ3E2zPsVW^I4+t0C@zLY<ZadU4?zCD;N6#CEx68GI`Yivb*+BV<Prs{HO zpq}unYOF6y8)!GIzta$ZeXEPoW`IX-3Y{~ti}e(bcj0_1gYWx@bQ_xvE>_?zpdh-^ zX<FBpHuZ6F?Fj9Ec7f26-fJ4B>(2(o?m^HX)+h^A#}lT<+grs}BO9RAStiTY(n~g= zPEd}F`Lm#hQL00hv6K)NNJ`_K(8nz^tcZo@rnDe6)zF}EDc~M2x3C6Z5F3NHcc?f3 z23tS;Yp;yHKDuY>2v(PLZQF#pvc-$%{na@H6xV@?V|g~x0Uol+pEh*e<pq-ClT7rF zmljgVHHH{;dS95&4#w-5C5X_U(l}`g|5O`HCRe_S$c|f*cV+G8_kWt<azpQFfpVE^ zl3%b&r_eAZlFKtqq|h;AdBq2*aK$n+t{5LS3dF4xl3cPf7t1j2#JtUs6q)ThgJ(PG zLZ%n)7OU!?@BPjdq_@6|f)$0%Sto(sJk;NkSZ$dpEZ#TC?k)!}{WV#7*E0P;gH*NO zIEh3@A$x<bhSEd7WxZKDAN66H8Lro<Z30()-9AhWIqA$m+K2TDA|>};#0H0Ob6lKm zkw~8I0}ds0XNQnc<kS=3EX86Zgn!7DcF&JoUOz;52}fGb1HbjLr00GU0<;zq3K%<@ z(7q&(K}#ypyTIQ#uIv*_w0%s{0kzQtTPP#*_+o1?{wLI6KZn{t4odG$$xa1b3E!V$ zm5B6ff#yjb9L?#1h<8NTeCh+zsKxiI&vd!d9dh}L<%{zE`wq$HO*^OWe~&Qy2K<Ev zK}VpB3HkVZZzV&;jeOf1E!H&2=%wRf_+wLodp>E7c6l3?hG<Qmsv$f+jy_R!8e8vu zUNzkFcyP!4Zg^zg_!u@0Zq3FAkem}NB2^_lR$=np_L6XFDz|F2Y`Y&2J)SPRQ4tG{ z8W#%K0`;3ivtik*Vp2D_H|e`8ohh-Df18y@_Wecf#3t5Zi&{yoQJ3w0d9*^|I5XdF ztV^oa#GKjF`JFtUl7wk%Zl4Ct7GkK6iOfc&14u|p2EWdrJ)A(XlWOGFVXM@p%<*OZ zV|%%&QLaXT@aEN4iQ}PvN9E9!snbzcIYCK{W+t03F;iWEk+NAUTcqnkqCDJJVfOZj zBx%}9d{mx8eIV9D&hNu6Mkbq066vEwfbg3=J|uc3<&LgXg0Ag^s7$F2#~KZGUD`_4 zoRL>xL1vC|jhV}xgki&fj~?Cs0y+syr>iqJwXsdaQ@623R7<nAYY?%BmW*Y8gFbXT zF!nwfZrwTV_?4HGl`1KJPMjr}GcMM9hTAt~62PbY-Q<$${<26wr`46Q7432BJmz}{ zkkri$oVAmI<JPket!68a0Z<lFqF368Zd;%&0uxceA_Vw(4dxTuNXFAphz|>{-TI&o z&wsJ5Q%x155CmE?u5)%8bi}E7^v=hk>O))2Md25EkKid4C{lY^DEM*~Xo_CCr4+l? zDir^P4Q7A-(=(Hthwn|gBb!dlF;3R9<5A$;dJSsfZc2MZ+O=B#bXTBq&g1$Y7f2sb z##&v=^1$x&ziIpXF2BP_TRb!2CHcDkwSAQn&avC1H$xJf2gW(u#bX(*HnyD^FL%kE z7P-r$&8dY(y~{aWcvLVrpxhztQG;s*I*YVPiWaY~l3oQfXCnctM*jJp0kkaOzD+xh zU!6_WEGtGMVBO9bY(B{Buf?&)FryttCyU)i9h}>qQpI1^BtK`F2&7B#+kzLtL=3dT zD65$sED1=Deoj7CPD#_r=Rc1n$K!u&s#EIgh8p!2vxz;d0QvV&Ju&`^`rNUENB_w7 z(&hxTGUB>bRC6bXB$9vLgCU6IFrbccg3Th6&3fuqc#Dh7xsr}xnSkmLTX3USFc-2< zm5@R=)E^Q<6${&bHuQ%{H`{F!C>Kwsz}9}Ow!1h{g1KFPNArkR=FRdrTMJ;MS3CZ2 z`Ch(nz5?a93y~jBQTyE>8yU%tVsoK29htCel@3WX_J@3@iPq@*&am`Df-L}a;DNa3 zQ<G}&Phd&E*3pI2?>_LNpU3Fh1q5ULAhoTVy1&RmpT4b~YC&&=PYOrJNATP|3!jd> z1mo(SdtpM|i3pR*vvF_HcJk*u&;zh@umdRfiFTbK!W9|j=bMP@H3=~-9B}<ctX@SF z3DNmWqhUyR;wWOByXCh(pUFM;quq|$vM)*D8zZoxW)$Vc_PID4{u-^JgeB_vWDr)J zsi}=H-@`_%oKo23@a()fcwos1zhBvxt-O-~SUrLU#i&3jz!`8(<_b$=@nT_|6?4hj zBF^(@Y}m8$<pmIYe~f5A+~RA(O8pSEFxXUCM*yX6IAR9fe*uSP9>zzU+1cf`B_2)H zM}Y;Oe}jWY#w))At<6F>Htmmnw#P8)2tb-u3lr#h-E&x~iV3!ke!VHxEA;D&q4W&4 z!yTl+6rtGJv-$y!XiPeBf--QJXxB0k#0cJG)BdmTK-g*tK}PpIPyXL-t-sBfP?P9j zC}>Wg_5E!X0rhvy2<pmiy<j=DOFHivkH=9-3T2~E@WrK%s0Bbf{cjg@?00(*1U?;f zNiv)<;CNxDnU~>M%mjJV8h<RLk{x!55d{d4O4|>>HR~Lm?oNp2{*c=`*^EBthN~Nb zUSan{i)vwiIp>{tGaAisTf%}ncH!zWKyl47K+uE|q+Tpxv1FVaTf&%j-3^P9tAp8X zyFWskhtf;1z-A?8qU;(GTfwLN@MLUORhV?ux7liOOQng@gRR*gI_w0>7OAtWs5Osv zr!1@od^p~xYjE*T+D`&vbT9Cg6ms(-31Br}rp;)!!uq+yRhes(Q^?+_zOc|VQD9gP zVglpA5$eBNsSGKUo9()IdfY0i!qH=6Z^nI{9;kR&)Y0i|!R$Brxfm`M4kK!08;WTG z-~t%M+m7b{cfiZO^8o#LTwZU38iN9eASI{^9ijdGD1J`AQ!@Fi60{Xb`<8iZ+b~&; zlPke)i=W793gT*)^^WrNRd&)y`0q0YX6P4DYx~o;NG7%DVG-=e>(JNq@T*LhLe4B5 zf(9G9OMV`W)HzygR68ne$T0yU-3r|yG~u(=b!6?SjY{6HJ5z4Y$E!dViH=gPK8#n- zW5LV=)Xd!xo`O(RT>8h3K}J|vDf?+}A{i}n5xB3;<?}w;HM?J4rwEYCxtPdvv_rxE zYnpsABEGkPjv`~Xb>9v2{-JDT3eHCst`d6FjFWdsFgDyI&~0!+gj9zRkO1ZNHohw@ z=IAA47m!E>Z4H7tZy?A^DO|!s$B*LMj3q^2&3CNIe%KGN|9M$a3q_mpL<4f(91ypT zxXF~zTTo1VnM><Fb0`I$4TLnE-2mUe#mjDmOOTZ9SE%xO0i-99jFp`#bvkQMqDaH_ zX%CFLHSVParr^j-%?q>QIDw8N#Wg9ok_ecCN_4w7*QqN1jGbdguduG|3K{M6+)(Q@ z;YNwAGk!xQaAU|>`Xq_7@Q72>u1ym5<)E?$!9LR0&fiIVyiUBoho@AmZxk63Xh26- zc1pdjq_y-hhbfuv0vE{U@;+@G{9i{QI2;@iL?i9*dEu;-K^#$rlo1v9Z3H%IVg^N4 zb&rskoF;uNqPuvu$330DL{!q|4+Z@ofw5?D25KT$?b@oqA4oQ^c%DnLs4UzIN(sg% zwRIei*xzOCyi)maGG@*U^*^}dF*IKM#8=Gb<kZ(5f}c_%rL||NKVSyp8O{{1)Y~M| zS!`+FI`>fRN5;+gKMB~imsN=JUc~)ViP~UWAY-t<SOacH*qZc9L5b<i+l5$Jnc0={ ziF4z_>tq^0M;f}`Y8>V)Y6krKN59Xjag77wpk@^TwizefL~!<MkrrWwz9yJ}M5r}{ z-!sJ7)w8QnRRg`H^Y0=Ik|unZ3&pqia6mRB6H-9G?4!~FdgbEtto20bJ42%BU`=rT zFIfVqi2-8W(5t{dgwQ6)DFU*bDSnAa&nF0S{PuMv?)k8BVfPeMY~DX$m20J$YyG@_ z+dtJnfW=`9l75&YeKj!dHbHt40w^^Ivo-3|4rletjuXLim{PoL2l&^7XqEl>BqINM z<v3y(DdPXCXtFeOK>vq$KrSIsibQL0As$0+zCwgxp`uJ@427zRpqP~RyYiwf(8J(6 z$tOC2rWVdds+fdUlh%Zp35~_G*BH`8-a&8*l;Cb;h|;ad*YbU%uN$Id$h|$RZ@@Dx zWFN=TP#6(j%|LI^V<qy{-8qy#k^|CHAQ00MH|(y%aW{lnirg@j+|QHUoMekUy}O_h z?+&D?@`EQ2!%r!i8}&_NT7@G#$b&HI9535RtRA}bW(rMnQ+odp@0jdhyuU%>-}6iT z0Gs4OzQ;Olvoxag54S|Tw6gjwk(l1aA3&;Ue|@y-2F5?4yX*vQwy{S})mmN#s|Np% zs;>--D&V>ux<Nv^yFt2yp&7cn8>D*(iJ_aJBt*Jfx;v#&LZrK;n~U%JefPQd@BEtQ zoU>!Cz1H5FIo3?^s!wJ|9@J!*Pg$fcfRVuD-(j8Axh}Rp2mPUG4I27<4onp|1(w=R zhIStM2s0W(a<T?-%%<kVtkYDB^iF9W_1ZmnuuR_M@6wtbmf4ewU#Q2^f21m9d5_Yi zHzj?lX^~=Hs7Cpn+&~=$=@(#j0vNZUA4|2l?^KvkjDEbm38xz&jAGMM`fR`}%bXgQ zM4eKdXLk@%OefC9fQN@!TQftE5?lKN$pc-r68Q$3;ys=^nb1ED;ZFA7boLdQ<Pvp5 zUB7k@q)v#QeMW@J*PAxf|Czwwi6ZT|8;|IapGB=cQsTE`VA(SRd-7W-3asW_LF)oH z#@}a#hXln02A$N^)YVwX{Xs#ztK}Gjc}D<~J1O0Ri+Be@P#Gj@#@gg#>=hkB8jPz2 zC{xXJzy^bWcJRx}0s)r2Nw5I9OwjBCIpBRjHL|{4--<;r=;gvHJ0KWF7iX%}r@%mV zdyYVcIHFkXH}O|-zFNnJd^%+0S0WVunQhq6tQPmIO5JV@t5A@@aVC6U2M!9~P8+xw zv!h=>EzZMCuvPs!wphJOqEZUcMD<y3Nx7pxIHcz->R6FGRpo4Z{9{LP2M_@b;HP>s za7TmC85fiG7OY<FK2p@srwmS3YSfke<st70uOyaQSQ?WCsymo3hX(w%GA?A>!*O11 zxsCf5Qh8(#tEl>k0J6GB7pg(JUz)7NFNUrbW^${oAbd6>Y6uc06r{1+hi|1;X0+!3 z_B@YKulA?2Q}1q)3UU4smwkt)TOHK&s=e+f-L=#(bo#;G=$(MS6Ursf76Onh0sdDD zKfe+5*G#!2_j4bwxH4IeAe-yIuK4ZO|Kvw-OPXpm-FYb{SKYAMobKY>UG477yLpsU zdn*1t(?C2-zjhgz4-(P3?sjk#l-aNzz->xv$pWkf%1$gm;jpe!cQPh0#QO>j=qSm* zPe*9y?bw6?6A}kdgKJR2+HG%vgyO)FWveG=o|v%)f^mYp+ioRA+gX}gc^)`TK65aK zhwqPgBaLq=xs>`UYm}+B#mZ@>#Xh@yIsU7Y^!uz!Q9e`_q`xbg@o~eT%;T?-+qf2i zT&wL>HIn|9(gl<^KN#~rKUnUKB1|C~M}4hcKaYHzSchwdh*^kXVE<P)t4HIDrCOal z+jwbd1|#9lO~kWEfs+e1br=jUt)7rxX&7A5RW9sgS^&||pt^}<FCXnzh>~h94w`~7 zDFKPkC-R2}wAq5G7#y9ldOQv-*j##i{f;GrX0NLGD(`B=SF8LKR(WzLiQ!nbDy2YB zJo>r-1T6$BtN<|760uy_fD+B0-WDo+<P*Hl9D)4b;l_W-qV+TPH=z3}iiKv6;xZ>? zqO@o~z00)zA;@A##l}>0G{k{K+T~aZCjlcly`IMwc^yGCb+W(Kd;72Dugc}b(r+Bk zKY0+%eV#IjGwpY`XdyQ6&aEtkyVU%(@JcX(=6m594vP#AE@z0ohb5aBH~s9S?zeeg zf2APZV2sFqqN{yM_ynk$1~gi?5sn57Cbc^IPd5zkx$YZ43O9)`ie@rw<YyRdKl;vY zA3UBW#k~w&^u-tzTHh0*08y+@oW;f}x9!~?Q`w5#P|gKnhrg!+a5ms0;1J^f)!Oy8 zLI5s&?vN@?qO4Y3WYuFp(beZC1n^T_@a%T1zOF5&(H0wtwg7DdE=2+##ki&4tiBQ+ z_6AT$5=f(U=J|75B3K&A;2sbOv63BFKfzIzXD@fiL-NN?j%p(4=XkN0(GmUvbo^5b zd6U!o{?SxfGW3n_xM5V9T<9Kvxl#f&=`#ZNf9qW(lfWYQDx9UFmUO=qO}do-i-3Q; z!rP$XP4mz5_WfK)x!-N4*6dBWI82ysN#MqA0A8Wqj>%PagN05LP<2|;i_<9d6(n(| za3`cDNbN~vo5<%LU-*N_{S6{<(Vuo^)MLMMQy=NI^aMw__?fhS59Wp!CbAzUyTu$0 zk*D+Vg2^b~9Z&;^*o_A?Tn9`4SXiPql9U|q)hw}ZSSiTgL+j+QxD7Q81=UG<#cKEs zy1sI%y-B8+-jC}5umRkE^kyF?vn;D>!miF<gXYWeAR1t7XvRB^g3n5+;~cis@5iJz zG|72Ey*6*oImX<7Wd(Nm140t3meW9p^@%(D&*=d2(cn!&jMZ?MQ1{DJ5^Jr-s1X@c zx26p_Zb#11(YsNaDRQk^T23e>4ZU-9Zp#pJyaMa?-T6MC*sEG3)9@p+8#oNcTx?TB zq&ntRH~g4{Lu<6e)x2v-QjbT|;rsGo_F3{cjE6TMyjBYiCt#Aj89<8xLLzV}=~i~4 z5Ns6w4@LSvPyUtg-*cz1unK08Q$jK`fugA<1g&*BqHUk#iOC;TIK4>>HB&~Am*0sb zg|OW!Y3F#&n8j?Hnh?@ubdkEw&C|f2L{hJCL>2B)vhg7H18SvZWZ@#v$-G6u4q-1; zZxGYkTue4GC7Y{S(KcBonjfj0QQ%sJoFHnTOwgNf(`^9l9TzM<5e*G>ZYMHQ5v>Wf zE{%e<64X^}P@x^udz9#Bg?vj+;;u2#W1ra4JH!s-r53*$O;!!VXsP$_#dyd*3KXwC z#vfTVHivcat&5l8>%d-znZ>jjyd7unN3;Y-F`{NdGK(1!Aj%V%Nbx`Z!3?gz>=Io* z&Xdh=My1CjRP_jGh%Xwy-&kK+eN}V~7cOMr=EuZAatQY=iqXE@lnJ^6d5EV3gb&AM z6HC94`2rQlg|N2v;p;<U!3)j&p(E)@<jihFK=SbQ&_#^&%n?lj!89gX8u7ENF~SFV zwz+$uQPLj5TG{g@$)|Tg@ICRL^AkfE|Ld-dcBOoYk}d3$eobx}uNE5A-{l$pZ&=9g zy_E;@ud-ph2;L;nEViz5xutd{<G0gJipt&V@~syVwj-&G?Bvv@3_R~#VuO$;I+IMi zs=qKmWS^O@Co9?O0CRmS8}(Mt)SwZJ^fu2!5KjXFSj7KrnXudG>uFkyeh%G?8bjug zm`xCZOPwF&NrfbHo_?jnqs^boweD@lm9qS>RE)T=SG7K+pS!|{9q%|u$|JU=-p#WA z5Ul>Ua(uh~Z74s=xbGew22$T-&k!<8Q8Y?p`q<`~IA^cb_v^1*7TOhM`#Y13MT-h2 ztDXoEc*@^n#Ao1(hoHwIdqbkANcaTTUq)=Q!8I_3?PdF$4#qDXkgp63U*FOfc(y&) z6gM~Ki!`x#Y1b5$PzkYr_zgDE`LD4UP(l-jh|h0HCGmVduxSx>l5D1JV@mSndxsE& zT$ci;u}ER;=uHw4fO`3Lq>Um8Y+-|-Eq^?oPw8R2>}S?`_BS=*xnweIabdJ*LdE4Y z47w*^F2sbpBME)DPXj3E=Jv2*`ExAZeBD6)N{)QGI_YlAk38Dt^FQ&fz<YsppI*`T zzB6`^e;F(=_3hu@>j>(cUm^euGlF#dL0Q`edx)UF%X^^V8-6)KM$zyv*)7UnQLDk0 z64$V@!BjdLC^Rn>SUV6pCbwG*mu%Q`cGAaUs+y}r1YvnlcL_zBJY60Lx%MieW;N{? z>R32#L?C~FqsEXhvxw6(9D6#qf@sP-**QV{5+1v@pZ2Lnz+}@r4~0leQPlUqOs}px z<O;m4%w$rQ?c*j=f45Mx-Tdc$(c?3}{7)R!$tYIlRz_A9s~GfvTcahiQhFodKa9NP zDM-15D>@X*>e-Ax5PZf1czJ12Hht~-xmgX!BM@m}M)(m|7_^vEQzDU%yEoi}MA3XC zW=?HfYvw8RYu(RWa!p<S&0b{0@LZT#QTxyO`>b{MC5*d|{~n8FsG`}kIQ9d-B9Oi} z($Z&R^qi)hY<S9znul)FIWL-{{lf9F5?#S<*|w77h5psOgp1^`B%Qs<UN!+kf<8t} zMd42>J30wfxeKUH|3`Mz8A1B+uOk*n`j=~QNB`g&Hbs|tE%XxXrRdu2M%A-i)1t?p zwXI9vZ@~muF7Iw$NPU}h^G)SC)ZwO%EosVSg$bGsD`@j7fJH#@9EkkEQxul}BnRhy zQ;x77Y#x?y>yx|pHk6DOcl;w+Cb7a}VaZF5B2W+TyHJRMMt#E|(5Ox`oG)hrd`H&m z+y7lvrMRRj*+uves#&9oGh!QBX(XyuJT;n_<=iGEpBkd{+)XGKoK-U86PkII$doHb z_6PnwsDX?MfrPhN>V*mm+Lo(K*b{7jx?rn14tMVSG)w_X(!VYO#|){X?>qpWK0fy- z)q6NggKy)E)eC&B&d2E<y{pr(M87e3ul$l>PLILnUp}(A2XNgw=+QqL`x}&h3#jsF zyX0a*P2|Oyln3MgiNm1zx^S1*+PAf~N_pZNNgnWK`c92JCp`!_!l)P8!y!8Nl`X^8 z(TtV?7VyMAPr3q0QWpL4Yu?OLxs?C<B{a7)fd;|<uavym_TEZ~O_@e+f3QXjT)DKh zIC_|u2Sg<jDHt17dma4l&J6wAd;C2tOu#5POQARt?NH83K@OETcU*%miK0}M$yKMv z@k{lU?~Yb$z17FXgQ@p{QYn>&9h%zJdQ`^C7U)s{9&V@tDNe4rz{Neltu?o9FGAah zFo=@^*y0joBghUgs&yTibA%^AIY!7e#Rd}jEB8QkEeSo?o>W^RBO_Dh=QZtCJHlw` z=|>MrzG0Gt?YPWmnr4~g1mu2IT+%cWeJxGUtkKneb>iZ_9qR*U6@tDasy7gxXp$Q& z)?39WeiJ2Qm^F=|aHK>YOUUbXo{q7m?5U@DFA10p%bWNt0I4H|jM4=KUfE1EY)p$@ zZIymUyCDx4v2ihKSH}=xqjqg92N@1>;e^jQt8S$*P;^Ld-fE?Jo1D-!+G`@JOw+tL zWC(fY@z~9(%BL`f-_(D0K?6{KG@Hs6&^G>jD+|t@vY2ffv{U~9r=$X#xEwfA1E5`o zSyi7Igd~GQ@!i)+xk)j(znyxdJ6stts&u=w&sVAAc=WE)CYVBA9kSr3GfL<FHSJvg zns&<Dc*(5)c47ZBpHBEsL+qL+gdjvJ&?xW@9^MvP<c>nDH|{wY@D7M(nk=q5TfaU< zs(?p}C<w3=KaATd36q?DJLW6qXVG|zT#<neCS8R#r?p5SUbmZ!r86=wt$Nr_OOIl$ zDJ2ngzfkKL0}^@2!nWZtgY{t|3bqKP_W!a`07irE<_GW<m0P1>TE?Y>7K!G0rlSYc zoYKW4sDu3O`#MlFrMG2ZAI8(DXQVBsays3Ps+vIsLvck8dI0YY9zAK(IKcJ<mzBHp z{Zqe9p-fS|ehJK7dWV>XIm`;UFWxAILsZl_9FwekIn~%U5XZFeo}~?4D|ZG#Lw6os z>e29ApA66<@Ao`^zP-jDtjQ&z6rqNThX*?cN4QTAs9Vir=h9^OS&xKCzrGNU1-7lj zhnzgIr2P*y8jk&#aE&Ovr@f|>Xl@Pi<82AZK@nRZYhwi_P6N;+f`10n?LM2leJ>hd znOw%i@zFIwv%*l{k*`hs8->S3x^I>|uA4dubkJ$JRm)#+^g=2f$+EpU{)z<1vG{(2 zs=Y(1FAq!JMj;XZN)S+Z1G&`tU+E?3*ni*Le;evx+<zch1V+&_+C#vF*%c5J3}Xsh z??DV95C`C3hpOFCAVXgE2)=Pmz>I#$1%^w&0n7DhgxYBZWF~}RrFot$duf{Unut%P zWP@JeolEb-tJUH-dlUeT$ko`$>Qm&XIWV;_E|tMO$(`n-O$x3x0YtGJK4PQ+Y4#T( z^SivV9reC1-m|Ci3p+a-k~<glHl+nn!=MQ47sjPF_w?hXP7Sw2HuNo$ACgYX)e*a- z4V0rW9MR!gGPY|wK~qWkxZf(m$=*!0Q%Ek8XgM->xlACNLem-wI5G5FL|`V;q|V#f z?LzB`OdJ9owMN{NwJ=_jYlr3|7~s(89z_QwFQAW#{}AbJ_~t3YaX{=Ka$rD8uidL^ zSra|C+YbEg>bt1Db=#AmEyHq2X4bUJfX_6|6e+*MhuOuM(8HwgUP(6D^KjYx@f3Ed z)Cz5+eL{o)Ng7c=q8YX^xcEqki=(c(<67TYu+tZTwuGJ<MixS>D)u|XFD;4%KVliS z-h5a0VEWS+kqZZt)|*+Gb2l=~b!<wyyZt^_XMSV`F|B0W{)KN_sYGw0MmO~k*6f#x zLijPcxwH~c5tr8XiaUvdgR441H{3{GAmPZ-KRB2156&g}4d+e#FKGG?6*MfE*lLj# zIy@ln<M21I!=VKD4^N?rA)%8Z(bJzM$C2>ME3=>MFkR7o9=Kfe{1Op_9t0bNs-~u< z-l|RqVB48-K?;iPD#^k-c^DDnMg}mdS;X_5c8CTk2)3f`KGB51)kH<d&UaaMf7pft zzsg}Sl)fV;(ry8XbHILrw|p;(Q8@Z3!6R+vXl&%m#&e;1lx=Pl;AUTG35`-wW&fdP zh7%A=*gdkBW_jLJ+Tu^RWu~Wk9s^s7Z2IAc1X${#Cx8<vql^rN9{U#^fC%$MwwZy* zRhn*GwiM&J=l}q_`Grdyi1@OofR-bAyUxo6)_8x94zQdUD{}Z&e)A3CglEp=>0+a$ z9*O79-<T9zHUNJj`CKl<Pf8vJ6LxzW`x64H9#*g@N3ezqwrnek{hklZ;f5%w<1Qg> zB*+TH!QL+-2%vOM13$t5yB<ojjWGbUK9+d<mIg`hUM1PE;#g!J=9)(X_`PuixAeg` zGr~pkhOGO5^C)mwW+wWR8oR|467cNCNSIC-X?QE3VHib~kT^#Td(dMt_?5h{@iOTb z(RM5Tw!a`LW6*z4;UW_z=)YEre}a|&i-S>7k&xTSN?~+W_k|MU1EE7fYYYZ_&M6t( zHuAoR@j0+9=Y3r(IUoIKxw$p$7s{(l5qS^H&CR!uzmtsX*?a|43L-qT)xN2mZSz|J zIrkr4v}^Pjx;c!PVE_v79<~Nk<R39Ycw1=B3tF(M2`ll5EnE{6=Ot(&hYE(s7gs<1 zs%+J)(S`#gQj0#sQex*ZrRh_`@tkOWPtcTrO95E2zpHSur91uIpj+)cr^bGG6MN+p zScMlSWngOaF4})N6TsmjEt~+4<etP3@YY9&SdxnHmMD~qp&h#_IF#AX7ReHn>30=Q z+chcF1A3+N=+AQiG_%tv7{RJ%FO3(cNG2o2osTdN;_f)ZO$9OdseWheI`*11sI`+J z_Nc2noBRBvlOm7Pyj-5{T10<e+|`TxQBbfV*!oQgo*cW7{Oi2~IyzpLbeGbhQ8zv? zwb3b+>LzWTZSRMBWBNiZ2$#j*rPK6t{N}HOzAYu))CH%6$`VLEpo7L;6e2Lc?lcg) z+QP+qz@=CzaB+3uAmFA3Y=l~WHdi8ocV6_Y7y?-e+#MDd@0bn6VT#1F&Lcf^5v?d7 z`ZuZ=2fWhR{j6;ZJ*cyrF4&rj2cnsCQESqE!dm?VN~;M{#-3`bT{VSi`6s9i8T-d% zmVVrt{^t<=9~$I;)A+i{dXQ(aIg1eKw9mSGv5;YAVDJwyO;=Wru%OZDGYV8eLwG<< z5QWzXKxz{Q!%IQNt7(A4h#Cb2Wp=mx6Dwd;_KpBC%QMFxe#eClzqF+f9;og&1*CDD z+jXqRr!0iYm8z6Zuwpsy+p5-9n1yv0fQ`9AUEk*q&R9qKI$9rj<+G06_O`oF{R1YZ zR4LJLP#bGxe?iL+4FFt+`XeOMD~Mb?*I?GoP@SibV@u3OudVwb+5cw3#crlHUTQi6 zC9}7nlU;}frD+t%ov82qIVh6JZ((Er6l1yiW#eKegcm2LUe=9fZ1izWF@=vHn@+kE z7zLRyUepXVrWy-sBAW+*-IlOy_`Y?$2Kx)TmHsg4l#bSMp!8nz=jFK^1O0AVIOKR` z$J>WHdj=#J<+y<JgdKoRY%Kk2bO1elM^XK`FnpOu14G$Yr?nPE>xsB@rUIFf(2N)u zdTWr>sL;i>!gJvq+iUXXV08YqKtsY!zk961QiJmD)Z1$QcoGgYKATZbe#6*;1*@Wy z#*;#O(tS7=g&q>$WN5NguF?V2hP+J)pI$pT_}N!(qWry?Me-D6i&elwz`F%ctD&bR zo~iV!lYyvyb^8hL!QB&!+k(~}$dxlgcF}XCe7TgYlQbre<>q@B!Mze=a(9!=?@_)S z*EhmgHSs^-rq!Et`G3EN|K}6QHpL7L>L`GT8O}U~Pxe#&JB-Ro{;BP$uP$#dC&vVU zz-2n;G*j;bQj|++(rJY8F;hdNN7=-<*F(G0GJ~Ovdcol=9LitzL5B$gKmEi+y#dU^ z>K2go`2YS2M!{-Z7x2a<++xrSz2SDgql(l3`n@Oi`24e>;M9U||4Poc+90|Q`^T2I zAv>;@cKWw2LdKo()D+~LOlyV6(3vt+pj4+U2`{Gi()5jcYs{FztudWgp(Yf^4}X07 zj(7IDsAhZgkv$nYm`L*u(-CB=H@ge)*|Q-JI_2&rr4p-DO8<B{JaR{bw$ovdlir+j zLg~5_tw5`Y>l4I$sAeA0b*K1zZ?n`Xrq=arTgxiXL}Mgu%#k{-o%U+<IVXix4Ju9Z zk?Bdem%}cjRUJN#0y)>+!9V)TkAQmf6YDbFGyemz+;4`ypW&Dgk+=^9NyzKC>)q&x zpTIA@H(Y);T11?=S@YHU66Vq3!nn-2@a-seeu`~Ba<~kdPM7E`#K0P9C0gm2{3f(o z<yz@z99^o+Da@F0YUE4S50q!THZF=V7{y>DlS#hTjcAg>CotL0(y4bDK4aTEFTssS znZ5TRarnO5&Bo#u8VNtXGotI?amb1^ss+P;DycVq^fsq?!NmI7@y3dh{)1Ele}6G8 z{l6LFt%T@4?^dWktl+CRSyjNweU*gv2M4CZ4P*UyZohigXe4tMhCKRfPO*@7{+NV@ z0Vr{ifyQ8rAVf+;RCxH?*JxPVS=d)CAAsCC3qS|Cl93itor{Z&VD7Sm(nC+1NM5r> zm!X#dg_R}qb5#^&qLXxs0#KDU+iYV2dh+-v{VHthHr0#ld2PkgAY^g^FlsH4*No81 zX1`fj@h0}q5h3wq(-UfeCoSVD#RDvfHVI;Le~~|m6g&g+SL}}7ESS~!fzQG_m%#~g z=puY`Lv*}kaU_`$jEq5BbMSW~NTfORNZ2U2a4sQkdtq#aZoh|%^fwj3FV9J{9Y!Yi z`|o{b*xy$Xr+l{6m{s7uKXJDiPrI|bI7q)Nd{dxpKfkDqZLevMNkTrSh@KdLqVlik z$xtadk!d-MYk|<&Sz5E-)*w_Vg`H@t+*Tr*y=(&tQ<GTO#6SuW$X6+W{v;rDCGhzg zXQ}inPt_MHjxG_orqhW;1?OYtvmRH)p8~ex5+up`-w(mV-xzP#d<q8mS~Yw<y0w@G z+URhG2T{~<gJ_MMlG(=b*^&c5pnB(Fe9*<P{Gi)lp{*i{-F#_M3bQdfAphj~sjI1g zd7hm@QP2nACHi@Rmy18I2_1X{60A_RinSAZ5oaa~sZ7|K3HN8@(nQ^It<LtyQ{l1g zqyo&!2(G>Lder}caW~PD$^T#+LnPe&W)Dhv?mL2`^Wt~jIg$^qZasfP0<zH`4Mrsm z81ZpdfE4P+tJcq0bBRh6%)L&1m_PjQE-)4UMjUkrT_{))#|@>w)a!PR`1QrWNv!t6 zZ7Ofm35LF1mNM{Pw2rWyP09Qf!nW<psSHB5vL+qhLB#K#CRPBga{O*SduO6L4&p65 zk0tRSPtbJkXJkV~oZe*CPQe+pXc(XgTxx4&YvPTt-7qqqG9bQALXg!h_Vn!4{6VrD za*2WyQXPBcvD6gMZfVso2v<OK9+@c*kKxk*r9!8aSgPMC^uOow4a`krsIVMGnoFPh z5F*T%+a(Dj_mSHkH&lOk7FCjw6+kP#1$akv^NuV#u^XO}NabAVX{p}*Nc;YN&rU!_ zMEX~a9!<N~F<>M$UW_2tV39(kR`yH6H|iO>?bCRp!i9dLBAGaO#&nA?CPAm^EF^1* z<G+ZiakD`F@CdAU$tS>9LW%wZxj}BMqmsC>^K-c14mkH-NnU@hqZWuvVX%zlW;Dv| zMRc{>J;Zqg?a%V&K99ru@ZMJRAUCn>v>v&jrZ^8>B_SamSIMJE7Q6NZP=$80!W32i z&egG?o8%rrkz5g)<<nyGx@i$<YyQ9`A=k$ko1)W1@#nR)!#8!quC(_^;|WC)2Fk|8 zU+=ZixT?cEr+LpWz*UO7+hN*>7-7X<7V-HpWc;Luv`$%63ns6z9{$!r4R+ev54T|5 z@Pu#dts7R`qXerdlinu9vUPvTL4@p4S=RFHBsnRVQyl<Yv^@n@T?%CkW&TcGq+#rY zhs%dVm_9yEQsO{?eD{E9$uRAm5{^|4IMLs<XR-bo`ura?#6kQGL`Fh2r0gZQdv7Do z^?xHy;^+N_zPA(>Oo_w@t9oAW)e%lSN&;V+Z&@q&Q6Q2|<a1y17jcxc?w;0MQ>jO; zZ3KQ#_CFc=yNNb<2axOs4wnJDt-$PmjIcRUkkg<C*N`E^E_^*$S@dr6gFM=;%ho8- z=;V@@@vI{|y~DEqR%7QB9Hj^Q){y8I0(TL#U+NBOEn*VWPjaQDPy}u{$ZW6x0Y3W2 zLn3*JIH>7{kj)|Qa{iHQ;x8J_Ta}NSnZ+cAwoKS~S6g3<mDv-p!WAr~;LFVnMl5DS zy%^70U$8r15`#tX`^@?quv_-BRTywKmR|tbk`B6;?N3|*ZI-h&2;*ZDY1`YhAOc(F zUgfNqWoy6(`80Nhy=Hql&re#?eKZIm9}WFL@A*!I&@aveG3AKh8s}XgDqoD6wSGru z1w0jm<2<5(TD@?QttgHco3x6RvgjXg`q4NJ24{w@QY=9~Fy+EfQ)zK}U?0EBdAQmw zwv@eHU45r{H;7jAtF_ilhn9F9y<RVOZdR81*k?;lYnCVs4Ui}h(&=N@aSTD+Zq#WG zMx-4krw9*mRM@Yke8r~+K*?(bwb^Re-oWZw&_WgycVGq+#pm;=<CS(5X3bdKKp8I5 zpRCDBe(Hr@okO$xm2<T8(O(_hONxuf;>p^J)Km4{ras<|-0$(H?o&UJ2mulMfM_on zPdn_}Ypi9vs@HI}XfTQTxuOF4GXke*04~;8Wu+HFpC|nDFTXY*RqB%n3SE9W)rWWW zBD@~i9v$T<J>MMwM$^Vp7Eg(R8w<<$p;Y7DbQjZOBjkEFm$Ghi5R=h!6q+LC0o41o zqTBK1k1}0fM3kxpN^pWyZIw6ASdf4=wAP_&XP>EAzRQF5lpQUfo6km!5-{)rm$WZV z?!;$XlzA)2o@DD^Q@<DrvG;X@w-6O>7wE@@&#+R8ZM2fEV@l-Gt2=j^*ZAd%+N!Lk zA8W?x_Oj__%mlx9<y+n?KnnNP1-Z^Ub&BjD`Zy>#u9&%X3ODraaZNHOBIE7d`15KB z!y^q-#%b&-0W>NYU>&En%2uf`Np75`k0^w~y&FAc|Cvsu`YqUH^#{LFB6+-qcwO2? z{Tb1v66fb{8Gu3B84E-Wn#aI_H*FyE6GG-s5gkS3q_wS}55&D*2xGRYd|Nn^`|ckF zuj0S}L!urhgb<zku@5XG_61_-iw-4`8W8^tA@THl0tSKhY#grVvEe&X5cvZ#5os@T z*0P6@fq&_6`4`%FMGohs^S>~pB;Ll>lPI)PVO>Zk2eBjm%DcV@e;*-Hnmzp-^{7SS z<M7c(wl+BD%PlRvJTEB~n^6aCj;Tg$vy(j*x}{5Wvt!YT$aD=OT%L&NcHr#fO%lvL z+yy{ivsJJRnwAqhyYJbDQPc8B`*}$MbUrxtlb{*ODe$U_glD#)j;>6a@9J^AAH2>a zCN2sU&~$#p|J$<RQwQL&qm>KMosIG-HvNX}Gw8^f(*Y1YoJhKA&^(711lEZ0YiL(R zrtkdL*okJTPJwRp^7XSgYbNFA3abCkXtAkrSZb1F)+}RpeLp7Aj@zO7pqu`7iYH0o zX)zij{tgjlBp_;bH}f4}6h4dt4<Eoa;3sVSL4H~Vc3siG?BWt@Z5)lGn}Lq`EB%z{ zV@vk$eRMtU!1}9`$4Y-;o8&8>2WjwCaC@P@gQYRjOgq@kjd(~BJ1RbYcJqE3_JY(5 zKJY~pP}n0p6rio$RB6&|%;&UH+UNqTOQS(}`KbP>+4tK1ywX^uQ<5Tu9048>|M%=` zkS=>ruS@LTC}&B(nlsyb+u13%pMt#WdPE#dhVVKtA?C^xaFmi^YFR2)J)HMf_m~$O zm4x@^1DEQpK5ZVI_k8#E_8lV6s}2WVml*<+aouD=Iif+XEY>P13By$>!a|Md;f*vq zRmNDOuS@MXK#~}a&p8pd$HGhX$*fjPNt)CK_0DvubWCjOX;8Y9cS$M8soi)In(8+J zAfKCnwVacaqt46M=SlxHzXaAPXuj~-AHQy^-5+oK#bmaiyS4TCz><2?Dapmpk;yNW zBk?WEZY$YNhtB?nl|EDjqTnq-J;H2h8UJaGi@ix$-+}Q$HOazPq;F%!gr%Q8US^_y zuBk{F2~O^Ud$w9Uni|QkrRHjQtx#t*@tTg|g5p|hOEz5uh1*{YH>SVcGD98EKdM3- zR)~q0EYiE(m~91PkV?Vrp{$=wp%9pytF7}D2TcLMBs$eKwxXy{I!wTwc!ry$0JU7k z(i~HjQyQhKUosB~iIHJDoS2Zn3Kc;(=GE!`fyw+=*~kr+;sn@DZs1F&BJev_`qixM z_H}V0Ar@jE)3b*do4(Kdcw)79!%Yvg5K)E@e;#006~o+pQj1kmB@`}6T*5d(s8OZO z8m?c?xKP7G*>FFtIQ(7y{kyJ?o_+`&G!)1|afC4nBTC@AnSh9esNcbZec7sRtmv{8 za{U=z`5Y+Xb`@FqXpv<(nWM$LW<st&1{cJ#Eqq=OHHG-%ws?F6xniEDp7R;s<J_Ju zjnI`hU~ScgaHg@%Ee;FM3W#i{RQ|4&R~{@*M&zv!o@cQAWp?p{2j9E7Iyg_kcOq;` z4asLj<d0Az10k;9ro;owP>c09tH18<HrL$e4D9rZAtAryr+eR(nVh|C6^CQ$q2a`O zR@=H3Bn_!^`lF8$6%S#s;Uy(aBKn}q8dq8CQx>k0MM`vso=7`5*tb-2sPHuDh*C4# z<fk|5c?fk0G$Lpt1024sP-;Tnils<HKU--~Up*35#dj8^bG|yHInn<ZO!r*||K;xM z71%lV7zIT4XYGh#im%_DG))3yWQTrSr$v%1nT-{z?sU}TX-8w+yQQT#SH_zVQF1bD zBxEfxeK00nKt#sargn`0PMHYrU7|6$e{D361H2@E+7V7cD1fJvv$$6bCt)1}BTLs_ z@k(+3r*T`nA&XdLCX3eDSR7qvd=k!1K0nV^d#k;l4b2el76A<he<_ohbPhCO)$#4J zNO98Cqeqa<Di65h4<pe`MaH&VI<ZVAo}2Y6JCUGuc1p#Py1mHT!RDynENn+jY2Owc zQ*0jN(_uJxQ;sv{7;+y}41H$SrfVN0PGo7fEWQ>FqbboDSo?-Vhf=Ju!TEWma+Gi+ z?&B?Oe@&2)AC^h5I2+QnGbt&yth_Jw_>`d0@f}{M)L?1bEo^qeZGx8|?#6wKf+OPB zD<y`(ZQ^4N5o3U{E#(q-&(ZsUM6nJ<j?%xMCdbpKWrG805d0BG0xhcUTrSjlWP^|L zf%zd}#>OfUko>46bB+`aEhep_!u<QSFIJYIGHW3V7DGL)Xw=NF*Ta+(Q4orMVbxUf z7FPG(Iv)@l&#Uvy&aMtr1wXTEUhH*B))(*fq`(==kv<Je$ts+WCZAizq^6W{_6!Dn z8Mn~bxSC&SJ?nX~I&Y0aNnc<8j)RX4=|tM7E4&a6dz<(e&6X&k`6Rl$bJ5XnlDVWQ zF(4G^fWv9IG!JYd6hug9s;#vh^|KKLK_p3ReJ%j9H}7<r_Ta6dE)biPa(;#unGWs} zm9czjg>45ZRJ-MEl+hHbcV0x8Q6LR;<Dc&H%FHuuo59Vr>7QpW#lpI~3x|e@4OWZ+ zcWYyTZvVRrfF>s_q29HON*E-vRew@jt5I+LZ0`dsP7db;7WZ*0f%*{uttCK{cvQtV zO+<Wbbdtqzf}E68p?ZRVfqQ+htiHaHL>84J@dU)U*4W1?JS=o1YO5qjKj<`q04WC* z897C`hXRydf&*pXlj1|Dg66_)Z~{e{^fXFfReH~*+FVR{jrx@5JKe5EU^2R0qTnq@ z=&s2Fr8+kjb@bub*a^u@LMt2~Z3}dZB*#=dDt&O!orT+2_n0t)K{%+VIUECz0FgKr zPtwkK+UV3}nq1jMYT@Kog1og)v#)u-<;CKMi{3;PTKBw**~iXRfs>Yy%mdwsu})^c z(#J$PQ$y;&3q%n!7BY+=Y@(^Io{67G%@gWFWQ*M@nB*exwe!-v+yF~@0<3{i3i8DJ zi=8)?Ev5`<8|)u`izsq}^m+G}#D~Q*PG0z*wF~-kuQdrH9oO8265_|dORa!e5lQM` zqQ7>Lv<nimu*eu+J}*wWmWaHVqS;;CaN4c4aEWBWS^eCmnti(Ng*IujWpE!@FlDkN z`)o~)v?MUdc}(_QIK;F;MU8v~>%7Y6oo1xHNTU*|=Jw><Gk4b6>^j*wjN7u#@sj1S zdkqSW<My@>Uiu5AtC-(_QNML!qZnq=QkPR#$IFF5y=6Z+lZUer5!dlYaN(CE2756E zm1{CKwoiHJ=aGdD^%N0wc%Hw0gB$ZyYIb7~<v7q2OPXGoRT_MhP=A3H!o33I-K^y4 znBdk+P~o<(cU^h!?lvD7UA{A|a|2f$q8~3V|3z9B5QZ6fe)?{F?npp2zvkP??8(I^ zTY#bU4F$57YFJ1Jxi3z>FR^&9nskas2u}5o91a9Eo#T$t#ZP1X&0kEXbh-kiSLyoQ zp8INguwUhUxUII-VwX^;{7w3_Mpb{d=Z*KRkLX|L?q#rC+8h*+v#iM$@zkCS1JhZg zWviDvfC%50D-?SK<GAe>{uqY#A;jp&|1xZKwRaR9{UZ2X6MPQC^hFG-M?74-YtH7( zEx0q7S4Qufkdaqx1J5j(urFSC#RQaF1%}C>81F{ud(4?_sX11@+lO9U=xwMME<-J6 zZZVbDNjdMuV_)2b<t3tewI+6?2TONj4FsmI$CLm&9@pCJ3S*dxw5|>tCkmpmY33t` z)Nj0;0wYkx3$YCT%Lf<R>ry#eKTQJVY?&&$hHc=<hjBak_K9}!ZxH&ls1_5-Z^g~^ zY*qI6ku;sGpn6FptdSpjbF{W|)`H-tP^kh9<*)R~+dnci<X5x|b8Hvo<j;Zch?Rl2 zcZ-ZmPkZ_qf{w-6m<j1TMBg{AHa*k}U9jy`yQ|+;b4|_ydZJYPj|G<+z(w#UF)0i= zKI-*M-7xsEygYo5MD0ioeenrtV%k-yt=(+N#44gpsVr$T0`@_)WImA?A(GUCQ3|#E zPOG#fDqoX?bT=nHQab;1sUW00Va7P(9btkSFIj0%IUyn+EA{5(d>jOg%)oJNcfxS( z26m4nJDQ~BICs$wUhF+7yk{bTOAC(3AH!sf1l<lQE4rLqf1)F;ZODM3HMPr{QP=H~ z|FPe};wC1B&W?D>VKSYibIUty;A`)<sV*;1*zn-#D-o`e01Z3pPWQXmk@Dh8CI2OP zAGw48dG=&#hZ0lXJ_{O=e-gq&YEXpA7oi?n4j#mH%TF-mq#JD<?6ia33$<JO>d${C z)!RGEgUkEBLmAMvQI2E3%U-9%!wtzR9zwa?S3SVFmgFcd%klW@6!#ZnH(=Z%@RS~x z?=i5<<IKo@{yUV^I4?0-L-dH_?1qBoadKb`cdCQ=q`ZgZ;``e6TpfkNj$bsTsNLQT zQ&eMbMQB^gP<<=nh`TU8sA{(cG>P;rS*>%q?}+PbVfaFm*u#Gckk^0uI^l)t8i%*O zj)4hS#D$4!mrW|_BM&=glZL*;1p+i6Vl^N#W36~9e&l+gd91Acv64+8oTnh7OkYTV z7T~u(kbn4|S{IJ?XZev<)t8L7NLw%H3Cw^^;WV=`>(K91SC&SO<xNnKA;e{hu{GHA zGaeWoRM=nQt`9gOCi?JXq1W^h)Zll(b}-)*wLO5dg-1Bz>+)`_Ep>b+rf!SYPn0kx z$AK{{1}~*jmyaZ9$Da8oRa3QPP$3niD80;NZvi`Iy_jFTgO@lpd>#_R!Rd0B-mjNB z$<vyL#1uyLo?hIpFkKv{kKv4Lda#HuZ4ixsbN)ag!Pue%jqb1Xs~-2;MaosKrZA`& zD?hb|t-k1f?r@$G)ob;wa#*P+Sq%w>@_S>VTUYHd+=`0^Y=4p3I!~4GPESQDUw@Y& zaqmeXTL5vqiAi~_Bq3H-?}6hYL>&3~R^oK9<c<~wm_B0e5b+DbSt)Q6Q@37$FL$r& z?MHDkIByh|y!K=9n6;I2294bkM15*jw8|SS$D!hJxzQlQY|@V%Cc8iG#H}ZD7+O)& z)AY~1+R=>7tWMd3;e2#ok>%k7eWr36$rB%GOoJRKmpH%ZKvF*iZ5Psv*`~Ys?c8lZ zF8b$*+<qk+8-ow@MuV)1MQkA*mMz{);+HYfK=QhtJ<hZq*-%;evi7s^zY1$yLu>?2 zL~yie26HwUm7r=1RS2K`&@YT-#={}3oS-Znwxq63q>&nyCi&|&l`#t}F#w0%JdGZ) z=i#8+X$L~IT$tOfoY#I>sAPiF=lOGVfi!;Ptdqy(qjcj@k+6^WxPZr-S-1<z^F7O& zRFWoi{p@c4q(Ad;T!Esk6;iG{-{BR{xybon{@O;E29l%g5X8*YKYyG(O7*=Mo!8ZC zaH>z4`1X5Q7-pQ9QXEN_-3X2rqy11k>Q*e_gvwb-O8D^wcLe=70vWuHB8INgv&`ju zVs`LwpfX#TuOpN2jY*|BP<m_&NYG6vrbzBnw05avH4wX2Xj-&qxf>b`WpKs^Nf(@( z$a`Lr*J5@LipCc#AdK8?ILp=bwW@h}O3R&}V+uCvte(wk(NAV@%-EeKqJp_&7^Wn- zoGh`Jj5!I;RrF!q$UhCb+O|yQ_q>!T)J{2>P$x7WGlMG{Qj*R@Ia;}G)Zu7VoNf^) z5S(mK-x~d9_mhXQ-M6TL!k&9XVx@!LtVRpuaJ1etTwIswdg_dyWWMrhzlW7CVI}}w z$NbLFrq`ATNl-}eMv~jw6S7##saO3~C1eEx7CriV9(mD6{0rzi#&d7=o}PDjbmAm@ zWBG%D@?T{<i!5hgnOy{?bqug+F(=H0dWKDTpH`UeHv+eIp3Sz3Ubw#&swAY-!NtlN zqpwR&eNCPa7w04m2mOqw0PQMfcrcdI1+g-$v#@nH6<v?iLE3lrGA?PQ<DX_5tl)xQ zNuh8I$bGf$C06&;J{CEs$@pvrJ&#-%;dMQ@5Z6!9s>!fGGnWYmXY*I=gnn&pR(;Af z<qRe^lYQEsE}7qPf?FVnGio+F3A|`;%dSnv^LY)56vM_YB!>5j?2AyLDC7_+K9S=} z2g7#5p#%~ZG;Js71(ql~nXp%)EOUA?koEC<CqTj8&K@I?!8B-_JdwyW$Y0SmNK-|k z2>lWLQ(^y>0^-NmesD#X38&NPVuSJO(To!Plo5@0x}VfT=bBFDd>cjG`cm<@l(>~o z!0cHZ;^Erf3o}X6Y3lBjC`(bydsSPZsK~pU@YLXfy%u;s+;me}xsN_T>k=3o&f`#; ztv>StM7dvnB57+8qxoz2<5=I*Kw0r8h3aAL=PRerWg4k~il3F&N~kbm6F4H`#`Ie& z`5S2;fa=QAkA#Kv2X->%k2D-hZ5tSeL%46o@jF<gSoCDa$N0kw{~YQ7<MS!T6X7mu z=dKr6Oqa1YM<h}K4&Xj{ZC-U^IIa0UpeopJ+>K&IHJiG|57@V_yz;a8i>a2E5vfpf zCwfmFNUL0gF^*Ui<xGYEw*%N?$fdR*spZqu*hBaQ_R$3MXjux;|2^yF!n4XLn+t=t z=Cnv1T%}SEei+wbuSTvOs=g<k%<9>+Zdyqx{T5Oeqh5XP#9hgNRHNK${PoV(XiT9) zmD9z!QJtIYAn}DqRRpc1egn;7SZ5CRY^8NTM!Qod5BQ#&=-2mD%dt#iq)o#;@^Dtt zzwlkr0;dJ}eLaYFl@X>;uXJ5WMN3E$Be+630A+Gb0@33W6WGmqfXGOIm(&>fuYgwe z^>M^WMpIQbTaA~mr1r5WtfXtU$lNvV!CF=0_IT1pNalhJ*7_S}z4UPJXfq+EY=wV3 zP7AxZ(=ghu79!i}uU_%PB~Nt0S@$C9dMjKfiZI_`F1)IZOqTrd?o`w%wUtR1X{}Dn zS#8YgB2ogai3H3;u6*i5J&-DXsD|a@_;kt-R7n_bp(OqN=FdvD=5J!p2UfFIA`iwG z&r_v~%?CxjqVhVW>R)ag6!cWd!_Y7!kfjKI|C~bjx-y$*WB~#t2&H}?)K!~zIghg; zEU*BgN5x_<{c2PwvRP=}(JUwBdYV(a==tL<FSRe2ZQo&}+<T{6r%pGDStE-n=jlJ@ z%u8?fCDRh<%Tx|F%hhc^<|lgE(78~BSYPy^v4x6e99|=3w^;h`rBP-GUGkS{zpXH< zP$xfUTV<xQ+g4rYf4g_8TmD(I>(wjTVUavmBXDhy3TyEZXQVJ_C)CF|Z06+o_F)98 zyRt9GCqeF2{0#I}_7pA(WV){Oko!u5@uK^|Wc6UiK-*!3C1Kv4`uX7&imK~n_b8n< zuZ_JC5!MT6g)y%DKvbwUL2RF*nuUNtOne3lmmvD_HAeG018je!1P|w(SetiA?2~CO zIvKx~+j~Z~uWP;<t3G9^>jGp0JEEQgaO4#;*!8~mIQMp^IN;KoWc79#D=V_yF+v_y zW~v6~Ju05O^B_YEILj}@l;06_B_nx(T-DsQ!*sWdsd%pS7F&oJZ%)`z&xPmNgCai8 zoE|`w#H{d-IzK!7v6@T@_o0aO^DOjV76XAsEn4V_Jd#WL7DamX$yZUvEw%~gpG90< zBGAdtgB2glf;FpeB1Ix^ND{}0b1iygOC$>lr;Tn$EE2SnVO!n%eD-=Q+JT-I_%FX~ zS@4C<8a~(5?H=DCbB0MvkK`EnS*~?;Hj%-)@4B=C;Y!7nCD~PTb5qz6R19(@s@)Zw z*I|hwo?SISJa>40CPOgh<#=3W3zruUBiCH+J3M9T`N+zeLof!l62;VFmq6xg+M>T0 z20}e^{Pg%ahq92ufJ;90LajjX<NYw5LGk=%a1wh@vih$7O|i%RWtdbkE31)EH|5EU z%%$}xwX1;FDhUDmaMKI@wf=SDpGRf6Z&O|AHxuOwH?cSH&bvMn;uXL@@QtFI)bV3? zA50V?x06e90@N=o$158p?@&B~D{t0AFH1)l1>NnrUBG(ew!c+`_{w0MZ#_6SC60y< z=Ew<epJr}-*2S4~*9P(eEPHA}Zg(Cn=tN=)IgSstmY~~P@*n%YK=ONw_<85cVoj&Z z>Z@IG!2{S@0<Jrw&YBv?=LJO{6N$H?iTRIw$&$1&VgFa<T)s1|$0bQ~4~->H7^fna zGBR<mFmdnIr0BnQ2dd@mp&|<GFW3cjTudKWQ$64AZlQ?LHoDC2^<nhRx~>m%<=glf zg=09P6G2c3ZG$;mZkR*@ot5r#Ukw;*Uw_xoX_VDNi;g>A@l#&td|D*8r1WzA?w$w7 zBnog;hc0P9G@=`$J3xNDQmrZFP+#XbF=&mYOOTEb4>S(9>ALp6U2dUDie9jZKTYS5 z#Y~?nVM`=fJ*MFh(~`Y8Sz(We&rU(*6y0rukSmO&5cT;;O^FfzL`Pi2Gl^nkHjhT5 zrjD9m5Za7=5;+nk60<7nxStfha4Ayv$LNPM?I9U7{T;6{JT($avAda=ZVN6Nk6GkS zDlv7>9aD5n=zW3o-q-O59yRNDIXz1b`QH>-GU<ZaJi+7&q<S(jl0N&c8KU40k25}? zgpy3zS_8zNrz3rPA{Nemoq3RMd&L|wg!HTDucYwycPfgpX_fAzANLBQ<IY_)&K)a; zv$ZUg;`6$BVmRdTSR?P<gy;)+{8xx6Gip8+whCZCXDM9YYi-vgB*C^sWD8KQ#gen1 zb-YI1*-WyibWiI&+yqG0msq|G5QrKO7M(5C=@py34)X|}rg%9TD1^`R2)4D>i&nx+ ziw5tprR6y<OTk%2&R3~m$)#mHi`F%XAE|(0vHot(Z+yI%XmPFI(xmLz^99Ana*Epe zZ<fDeo)%*6kBZ#)MJ11TJ7G2tomH6!6{eXtPxK=ErUt1%zFV=b6nyU7sNXNK<1EHX z)_@v4T%FRX%$GuSu_MQyO`Z>)5z(-`ftp*58gcp+J~dOMTUZt8b`BNI{%OePV>*g8 zG695-jJROJlpUi_K~lfc(Z}@VCOQEcoAA!z19v`XDqR91%25c5D+}{z7Ma174+xJR zL>E4_`M(^gTu8O%bG8j`ZrhWthSKusq#)t~t|mnq+#40Ye%CfvIZYcCn@n$KUVuK1 zrKJC=B9U)8wxjFGQopImpu#W#W{sGrg=3vEAjIq?dAyWav2;}JRq1nJM>LJ-h;gJY z)~1|$)X+$umD8$x)I#$k>I3?G#po}hpzR#UUS)L5^hnFyVzRnwF4)Pdr*qklm&BIY zwuE(Rc3h(Fo_Kukhjo_xZMQNhKlLmrn$BKf+{RwvG&?w#fPsJAEb?vLwC~^Hy&qAX zvu7tx7yZy=uKV8{J1^1RM;kU#SK1eA(;SPSjU7UctldDiDq~VwHoy49^el@h3kRko zSc6Y4N7(;(P_N=1B_5!<1ShTIY}C{WiyZdA-6v9=4Y`M*K6efMnanS6sceWR%2$Uq zcGrKE?x^Em4Nv*=g3?Df`|25fEm+|^Lu%N=*Y2m-y>GFoUnoX1=bIgw{xXAR8r}K| zoriDEEANb{H7rxOv<^pWF1ymQgKyv+n3*-14$RDcw$UEcT+D8|s3}(C%*I7cZX^|9 zcAt=`w63-t>VOOF1ELg7RCgT>nQq^YFqJV<dvd$2V@b~u(`205m*&HJCpHTT^G{B7 zNAT@!?X*AEX!Lla-V_P+<fPe~ro;>$RF#CN$V*v<!WWMNIH1`$Z^J3V4xE08emX8{ zRAc@ZD3gZuXc}8ZVISZNu1FGg9w9t?N|*xwm~cQ_UjaQ$jwJqcxnw^~A>P?fK$*98 z{D5r4_-w1#n8C-jbkd^ozOCY_0qIbMj9I#!N!a^&LSXCA6)A8QZj6{3FvpwO`#lSq zFsBd;qS5wYR8|x9QddTzNd8u=lBy-FLX*&3sG8#dWwBu&{esWnZo$dO2^^9cv;du+ zaeaDm16RqaFr|?^sv6q{!5gMYV>$E+chl}{vcyo;u%q8#bUW7S>>YJzdpAN?x;~t{ z7<O*!5b?Qn%-b%ZtjhELgn-ua_Zi}kp;I#GX}1w?$NhfX*DBt75^=RuScd-$E_I#a zH{z?pRr>69x(#!`d#O_B{F;Q5{C1zi?vGkHMu0+nQSeb*TB^?mB-mHVw)QEQZqcR| z$ub~2<SX<#()&rfA1m;LjAA{x)Q_P{+(BuWu`-b6!$yha&8-PYhfoP(@l@n=xo3Hv z_@Ykx31FOzq|tYDS?D|CB<5n66S#rE<h4gO(rc6kN(|cZ5Oz9~gxlVo2pma++bdM= zY=gd67>|0J*p0f!g4zVEdW>jeE9Xl58Qk$tQkx&W()|>+5ggLq;d#MqDZ~6VK&!zz z_cSBDz3+a#)&2l1FDZxOruMeMYkUt-g>~5;hUE9DkS1b75JznU{EJ`Q$%;Ou$Eyo? zd&$8J$P!m66>stO*xDPfTL{9`QVLVk&`@=o&*!9yy34TMHfCW0>tS#%H=Qp+cB4wK zUar@-Z+r+Ti6VvjcPKxw!C@qptq<O(x7b>f<4u0U6&4s>MvF-cmfbG?Hl)yL^Emc@ z0Ion$zZ>J`$cvBPEdkgU5*sz5H6Z~fY7{E)!SA8X%VhGjC6YcpJRZ}gm56g^us>oB zdA@y1xg%Q!cvq&Bn6vw2;<VqS#61tl1NW4G#nZs>7a&_!{3^2+t(F{_vPl@ch||WV zmWa61z$ULe)vl@J&zebTui0J87sUuB$hjE;rF~pfu*{n=AA9sJlLuS91_NXf9Dw6c zMJtu%6A9Y5QRdG5Mf_6-qVCelxw8kvKUHaYx(&Q0?+AqFBjo`nC14Z=Kj?n1sMF1B z7t7o~&Pwa1)g=e_9>%l3(EM7;afvi)fCSy<P5MAy?ln!`{q##|TC=>Q0e$^Y=U2mL zm&n5R*hhhXH3e?40g@8K4Q#qen=cg#b_JZNa^j%zL8HWTe+W`LgN?0qbv7EU4|<R@ z!wsPtOT`KBunjR{Lo}-r13-?FKqZu5xo<`)X5fv6@*FEiPlib5Tz5#iG;nKXGD>xz zq1~75g&bsV><_bHP_wAc%;@}`LlM4BN*j&(4}B$6#x>^erdKuKJQ!L+mR;-JmX~{v z=%4{LX*WAZT_{7??)^Lfm$*5PdM=^0bG<MD`R#H+xj=cyDx<`K_^PT7v{7f^FYVy* z)T?VW$bpv6FxGP7lLq9^E9HkMw^d-dFIVRCYRW0O%P+jWTv{jkc|WW#o?gc~KuszA zL3uWMT}p!iXMC(gg>J?yZgtsnJWS#O3(A=9zLRI`SJW9`1*iN*e!P}8=;Ch&w=AI! zP8HPEmgl^}UE~INIRh-_lQd{{D*NyTH{8R>s?j)nhqBUxk6$c)a5AC^k&%7gl^z4f zNvD2aO21xDOM1{O9x^rsXaO?=@(DzI=Hk|=N-oXPUbz@BXZM{O-^GkLC}z$B!eSiK z#ZBY9(i%(}*L{BJUl#+$xVn^=hIw^w$baNKlt+=l7ZBkS`^~qO2a@8)sEIU89*?+O zmXMBpmFDAq6RO1q7dJF`;SoUP_jaFw_Zc8B&NfC5e87HN(J}BQ*&(ZzF2xDeJLDV& zn6>IPmf{6+z$<Mlj6>%n`1nydh)>2l3QD8KP34}u3+X`j<gxwo{gfYJSjs7Vx<3Uu zLwO1505-O*1;5n&Xb=Dz%I7NUymD~YMj6z*x6E9&Q(AR+S=v9-Oztk6M^!x!2aHJJ zkCR-L|DjJ%_hXw>vCcN321vjpJlw~{$H=~2J7vkjMY4bI9$CI{g{011T&mZoDmk-e zkcS_BM2Zy1uW?lddSYe$nng19f4|6+PrV>@s+3YaK#?b|l)ET|wtHTy!H#VP`EhV- zAu-BDLPBZvof^3unh>apU@ZvgLj3JBE-PLzXPS(jI8)km>nn{ODu=lvTXt+*C&5Q| z%NHYu$$-IQB~`{e(yYzvG86{LERI+wovC*LDCmWg$6>7b>a$Oz-+)iVWXLBi+H{h^ zgWizLf!6bnI+^Nf=u2X-@7msdyCgI|P%7S2%Ie=*ZXgaX9gDNAN5WTQtY$=dSP5pS z#r$!v^+khBxGeeYN9pqFJF;niuvD(mP==2fF83GDfz&uqCn_5IaW0kF^Oi|HoQz$w z+Wky^3A!ed+7lNk2M_I)L&4E<Z~1!#&WujEQ8!w5wq~>*2@M5^i#Z3+*f}!x>jm=C z>n}^48uw`$LM6}MuHjZOKne`-UV0^>-K*w>I?-(#*gnA5et5s=mmlH%_<=+Q<de61 zzbmyKt%z-AC>fOLnZPm+d0X`ywk`0e@&pd&gMlz;^Hw={7<)&8%RTTM&VcP6?kQVZ zGG&A@P5A)r=qeb3t)0P1>RcqSmVIucT;!W=%0gf%ZE$~a=M+oZHA{(!7K+8w+gHfL zHJVAaSHF-!FV>KBn1o0Xh~>xhdgQnZNv$lvQe=#23=X7%nh0Hyw1`0*cnA8W)+Nen zw8yh}?)-{!`+G2ESFb}R03A&v<SiN)=^U3zVp7KGuOB@4Fl<l2+Cl!RekdDxN_RYD zsz2orQl|zc>wcOksY*U1B{7K}$V^Bg6+#3LiqYE?vM~iF$~=%YDdM09!<!m@q$nf$ z4%B}N?LR;TOw1@fAj1uelCdZwLE13|-~4^S1G@XAjF)kJUXmf-?U&EL9xc_%mq1;B z#=w`onlJb$a63}~eK4i(jSPuHr}M;*)jhNifS9A0K=TTR@WY*dTAWBo<04X^&9T`f zAccJ<{2&ovmJ|;jGOZts4F0KbQk_Pk!N@8#%$Y_@3R(k&?deu+WZK*n(x^oznK<DC z2_$SrqMU_b^Yc=0qOohBmU3eQ(Npz{3M!RTE!mCD<NBeIAPmIs>Vqxg`7pFv07}K@ z1qMhjDuB<a7PyscpIxK4bu)8O*Gw&Fw_|o+UHlgSIN-vJy9hR%M@Pyg!9JE<lY(Ps zrpyL|B;Jz`85qarK^Q0xnfE^xoW^v?GLujj(uB|4=NG=aBp~Mnr3RHvJDAn+CEm~g z$N`J^p$*4H$?vm1mj=zcVrQ2OQvT6KGUxY+k^|MFN(I`XT{?#7u0ndHZ1LX3IMG07 zpE0SnagA|pZRnEOGgAhKOc&fHB7i7r8;4AzG)w_SiVw(+aTtuJ^c<BZt2dAp+aqQE zn#EE&KlVNXz8>&0amU;;zB$9rj1qG>zsz{0?`>%lYwrBE&sa7vHQ(`<l06YJuM^s4 zVkUfi*}$l7NX*}Tax;G2vLbi#4g=%@doq?T@jIc)G)iI-uhd>N`UPK1&CkVn>ssJl z0R9rUs{G&P^2}#|ym;k%(Ep`Cf4Coe^v#;{yW}rWSRzksl~=ldAVo`8kp>NF%Uy-@ zOXUadlayHYIC1PK89HVbyk6dr_xijhnF77Cf5)FP@r(aS_L6m^bNgDz2t4e_TS^dZ z6S#M-(2RJ6KeVUtGsk4gm!HYIL%)(bPj!;vAHF47^dw_Q4Ky;gGpqYCK4rhv9TbN0 ztkV)XxTboG$TW(1VVGLAY=I0JIzgUj-Bwz+s;|a08b{Sgp%_34LLb<^WvzTMezugn zuex+-^*C@R9KvNF_6&rN{GoG(g@sD+sZ%goFt3ZXRhz>7rnE?tCXM9Gl@kXJK=wMY z-EvV;Wx1FKJxU`&;Vp<Q1HPZLR9+kOkyI;H1gj`fe(Edm5{iNc-<<CzV+nSDIT4#q z>Nf5m!-n^iJF}-rpgZ$cqZ_<DkL=qaqXrL_;bXp)Tt&*t>pijD{ki%&_~vqSmXQWX zm1@Y}1H(fc`Uv7`r_!|s6+gmdaG%&K_l|XJgXYb6D65_5jg<|nmr0K<J!Ia>ASnY{ zzdvM{)O)xj@{7ij^UX5-hhHT7oyDci)6FF<j2f1O+<I^TU-$#wjgOC(7?T=%so^k; z1fA3J1xkh#C?o3>fuuK{a9KEa9t@yUrRnp}fj8<X^%*sx+BNp=^>wQlAdNQ;ZJ*wI z_`?Lj5u64;cisXy5gI2ouq{BotbsCY@KBlY>ndsU^6S#EZ7aDWQyS$nJITR`0km_i zavJXG0SH4I7>ced@$r!|YuXIiw*R=)t5;8o7bzr%4(^v7dk;vta^-L;bS~uw<>q9x zZ<kBRYsC4&Ks0R2`0KmGxQwL;JC7Lm{P^d?kJlx|Cj1!my~o5`rk#BK(aV^GfCpt@ zTFe!&J(CW=2)vI{!(j)8F1AOsaX)U;fb4XFfchiv-MGk>`Z8RBa6uSY#*9BcqfA!! zAL`|3R(@C-?uFMS%!Ur$*Y-n~C4W`9I1<A&IbcVH9F?VWHc9En?w5SIvSAEn>2W?) zY<`*)vH(>LywFE*(jD?LB@C1Rh;~f_B_Qh<l@E~4Edz|Xe$F!dYs3D^sl2db7%Y$P z*1VCdi7qCe4u4xp7s>}*v7}xNkSMS(_$Y82Qvh<v>4mSOkXD$w0Fnw!K0~YKBT56b zC%QcI83&+V&sk|utC7sb{%mP7q?0@E$S&~^h^kcL1T79+*#u7>KPVxgMn;bvBkkL^ z)WI{CPipfd`U=ykkbV><n6Wv&f2R~LSwX_$(nyw^_saI&OC@`H<g0j4tkUQNgM}aG zRVXNLya5tGHJsl`xKIBrza$95wFx_0n@mqQl;Hd%4UEAL;NyqN08Nk({k%bRc3t$s zy0-k2=Hy;8HwN<9#c{G2X(Tl>#!HjBb!7J3h2ozsy%fj;ZwnY5y_goHH<_P5wyDR) z?ZGFH;S|nD`FP}L>D;*;C;gn#YQfwa3-&+pt&Qn2B~7e}%S5`$S8PorHEHhh3^)iI zkn2DcisUOz8_Jin7E4TuyfS9;1bL=~J-O2#14Z>})f{zbrI3<?fX$OJ6R+HK3HUhN z;6A_Mzkkg-fsw5e2rmIhM@mMOb3h;-ie>oTWf({|koy|FD3iwylyux%hV9Uip;Sh- zDP9u)#CAj!7#uNfZ!Y@HG&UWT-UMY^%fK(1N+IJfR;G)><3l%hUSB9@_$;}>g_BGe z4vtoiGmi_?*$5Wu<@m}0lw3459@FsS@_N$5iN=?tPtU)$d0shZCtebDz%`1T5AXK5 z^BEv7UYFRTU%WAqvSH0qS+L>{Y5DZi^83_@@_Mf!lD}A4EUE4-%^TFhGCUkma`uRP zJ7JW(*>|E;ult;QHoBkW&YD8DZ&)s)hfk2Qb#Q1w%Ll>10ICC6{6csrw?Tf}U%sNO zz@!M)rJXpuUw)Z6RX!UxNdj`+Egy{>Di4$@tTM;SDUE88SABvllIiK;Ls>(^LSh`v z4V`sNM6k@6@f|!HS4r;y@5qA{N@^+sqI|MOF<yCbU__9N89PHV<|!_3zt$S?@ScNR zeiUo|*toH=(XttbnEZlMnxnAlhB^%)GG5|0ZryZv&%tkjI}6H_4eCpd99cD<!YAGu zERA?cyw06ECf|)4C%-KVl3t@m$vp+>5$eF#5jGCb*|0_i^y)3s7Hp7m57v{R!~4qv zSf)r?5K~=xtZ5=;+n-CNPtO4|Ye|qi{CFc7ICy}RFOe5<X;dKopeNu`GqX707lk2u zG}<V3xM%q+biHuy8H*oVdi&lcw(*Gz<-dWUdYcUC+gHZHTQ*<u^3wg?zVgD;b>!5E z!!mo;53=`UjJ(vbqvXlKQ_ootmf7NDbG+C$a7Q`V@8~2lGG)G&+bo~)9U-wF<MLfG zQL<wGd>KA;qCDKRrF3ZDTvAgOqP{K87t80?e|D=FAoVn9wi}TA$gV9ide~6;`uiVo z&T%R!RJ5q%z=2F>&PGd>nhm6V`=_Nufn2Cz@G_0)XlvwS)?^A8-TYvbqPJT-jXYog zatS@U2Mri3nerBtM{Cr;9-!$Ui=rfJ&b*Q@Z$3#A5CB-<2euD2z$Lftk>;Wt#ODlG z;x0GdU*nRKd0>tmzw*6DqGIDD5PR!%f2O|tvNxyvFym7xm^CAI$-uZ;z5OUnQmA3i z;}?zc;P4tX%E9PGPexAKu&D#A6=N(jaO4B7tbv|we-j-vIDt)F&S*UQUdPvT2)JVT zi1)<<Bq>%cp_KIafafAHUylikb1^xj;(aA>3OBZDxJ*EAVsR&4n24vI%fooM(}wuN z0SP#(holw}d_h=TImCe-`9$kkpYqL(4=}37Mje$#)tgBE+U=y*D=lD1&w?sInL&KZ z?KeJKA4DGo{w)-^ZUdw%9?x&4?o$>MZ`@l5a9(Q1&ns`JYzx|hlgZ%r?Fp07g9c&- zYpD*5Jt<O4zM^F@EAWA2PD7<Ky_6_>mt@V7R)^Rea5GP;LT;eGKsWRhm=TT(KP&Az zbdujzY?E4bTg&Lty(IwoYope*G(b|)GCdWVD=9T@E?4u*87CUp)RFya65hnPF8xT& zs}D?_n38w+C|wg_Q59t8Pq|7mv&&RP0F<Fqy{fsY^x`%V7;dgUoL?FTpNrJ38&4H& z6RR8DA3kyd?(arM4jU;y&YmaHs;mb{jzVQ*%%>kpR?H-F7PeIBQj!(>n{X^*xrSxN z&2{2_^`-r%Q;>?6E3`{x{$8$qkq-#xa<K54K}k&x0#DJ?j{%IuK_mSABpRL~wJKJV z)w_>Mx`GeL`nA7EfvjnvXi!CBIu1N+u(Bf=c_KQ~{3WIiP^jiu^Z8%iJNaDe&v|*e zNE4Wok^6|Zii*;KcldxDES~{y|8H1-dF8`zW!9=c<iWxjbuf*Mg%FRD3H72GApzPT z*_grk!4>JskihABr(%;=ZbTQEgl9}g`Nuk9>v!O2J4a-A;RrlbG`KMA-DSR+iJQ^o z_~|krH2qb=V07T<{9FV$%gGW#v3KELAOkOw=(3L%FIr;XtI%{2aLTO2=QH-Fms3*_ zhtYtW^*YiU3-`Qlwk6ww=)J`y*j#>{E?qjQSh3=HF>j|Ep8@jXwaGCbjcR*#?~oJ0 zXQf1;+%mj>Px*ZM3TXh3#E*ycknHJFtIRoZc$bX$u&;bNX|XhZs<Vv1K7yIjcx3aM zWioR3M0x1xSEY4*E@x#6L2zWIHHKM!wi6)mNWuhB@bQzfHE0`_O^3_+RSV?HDZk5$ zZ}pZ}JG7JlMt232i@MV;DQh@DWqZ*5y~z4DLz^W!>$AuA%H;85WyLN(>^0a^^5)2Z zcfiYOPi!4DQt@x!9vC^sOc%e5`C!!RD5>E+V-1jii$4bSpa-$MFla=Chs(Kh=kNyk ztC5nKyX{R8Npg=|fL!X-0g^Ra7VPhaNh8Gpa?(wrv2lZcKj^ckjvbOoIDlr^+TGHB z%m^ugy%1G?)0>A_W6&HOdRl&+HAVXL8!F)`v&x&j`%Al4b#baRf$~EFVl`3hIa&P6 z6nXQl_a!ngpS=2JcWK+Y0rrYxnVdW+ckuD59D|G@9-uGF#uKWQ26(Sk0;#8cDbwQ0 zBF!KBmWla>_qLe0R|6!Lf*(CB<3|jYK0`i}bh(O3ht99VBk~zpy=bxgGJhEkl4~rF zRH~pL6&&EZ)FjA@1?EN1RCPvxz80^8dAH{$y(sJ0|5<ul17wV>TJXCJ`*4g@YS3Id zz1&99u*_G=>|zMqLeFj;1Ef|P>cfNW0}kPEtI6`^gh{ev&ptS>WRZI-JRpsmG?luw zYha(h>@c`Fyr*@c-0AQQD%IgrJLy3kNMs54ZS<#K$&-y5$)k@|lK{-F1mLhE?jh(; zM+7%D(xy-YRdOqt+;}l2;&X<Jy|Ztw^i65!Plp>AQf=@`RE$Rgf%mUt`^bwQ%#+V% zd?SyQE+(nL$X?pk5I+uWA|(`Jt}CSRkz4Vkgu{g&mUL04Cbg_w1Pv1mjxYy8U(-Dk z*^YI>AGp&&Lk*A|8&MCALfgW@SD;gJJi#wlMzuR~8zHPz<RM!Am?YS|ZmZ-fdY5E_ z!Py`AT{fVsq%y~B+CP8*?04*HHu8bx5j%~Gd%&Y{nj;04^F}(wTpUlY>|QfdT0TEm zIt+YYTGn|G2hcz#M&F>@UugNRoj)#~r|+qc0{<QgKu)MMzGjSEF-iazZz}BY?NAiW z8x0(dJ|PiYkTL6`0>E=dTGXf~GZ(GZ*PfJ_q|1Pz@<F$DSV95V07KEhHmNhZ37NUT z>;rCAtb<+b2@)IUg>f@h(q_yk0jW|z!Ga)iqH7$@nF5!9`E?@$5avu9ItT2Eq5hT3 zQx#NXle9~`k-6S%Sm#rpxwG7O>IhHPKGjc>H-%$0rZI@KX4=tlZxN*7vRaLF9rfVi z0)QGUjoqgNY=OH^Y%JnNg%lkVmR_0o6BsbHlBvHgN5@RuGf2nYgXN<>I1Q5t@C;)S zRZQ7^AwpuX;1lnCR}KZp1tiYJ2t)$%bE)@ul{ApObdN6#erSM%qQDk!J!->c``Q)q zP}L{oj9)hSc=AkX+o-angYeK(QdNRjuL#zi9SkJ}ex+*{PbZ!#E7;5dGrd%Clpn4H z;ws)J=7y`JVp>N<mb)$O*nWV4LtYNNH7z{BW5SP1)$+BaNVP`rD0*MAP+3F-DvSOg z0Ob)|0KfU1X&LO#`E8lc375gXckbLo_LcLJu&unKs%zyfBB;^_xT@H~h;d$iE`Uq@ zGCvms#n{0kNqoL`U?zErOY-1_AsIF1W(QiSjBr4>m@q3pRk~Aw4^u+UlV;3|p8Sl= zRJh=c-t*a&gPnbMb8+Ll_$GNyUeJvGT0S>BTLd@lrQ@kkbF!jZP`Y$!2?`2wGr#SA zkNh%QG88E$8H?X_+m-FQ3ZyK8_NxNYE88}#mhP{-BI^!ENN0G>z16WPyu%pDD?2u> zlXtqjCd+r9l~=m;leaoQg*|6uaYE`c`E<lYsrt;T(yDGns}dlE>Oe?q4dT|2#VJ}3 z3~8sagn4t&PK>7mrE;aaap=lid9zDj$$ifwGIG?1QZQROJ1{0ggYVVj#w{ptwT2|% ztrJsduf(6v(LUG~4s72bV?O>=VsciH0exT66Q79~apFLnSKKGuKsN2$vsp%cHdQ2j zUiqN!%MzgS7f{&T92w*qAlU=O#l=Zf6eiMbV{@^(%rEl7X}oE1@PnUY(4c`+NuDH? zH3Yx_dHk?^J$jrhhXHcn7avRUJ97gO^n9!bl#j;S*tmEJIeSW`O!y3YMb40F^;*fG z_urNr>FAvVnv)I~jGqeztj|Ws$Kz&5({`Pu%PY@gnI`rM#-R=VdfKk-6^M+bj!skI z)=vD<%bp^K^`?PF2pSZ%@Q}+)$AZw9LAvpsmW?uqHNp2bZPdBbGJWD_(xvA>iB6pj zM(pRL{j*JE36?|C(9pV7L#LilOAeh}NoF(u>o==_9&@_168UofH|7c_Dg@%fDQ|aT zj2IEuXc!=WlVO9tkoy}nlb1U`s|HAxlWA|)aBCSL$&K)GhUZvl$T``+{{Z&-JSG9@ zGD?Ah1z~v1B^fYjc0~grs~Z(+4eIpX^Ovn#w#ye|zLMIt>%jn7RZ`(3;+WVd*}Ho` z4%f;q*|TTUNjdVt72z{dLa;d{+@5!Fxpz*)%S2J_itQixTRz1SW8BjA8h+ppINm%f zRXg^RciPpJjF73G)Myi6X39r@rsEh5I;?G1){y8<>f3Fx_zdj@?OP{|(PpS?+g6O{ zZ2zi*vxN{3zTqB{9Mjo&xVZM9AYp)nR>hj<E|7llxMl$%Q>;|KOzTvlaC;#hzhh&o zXFO@(Vg;Gy!Fa--dMRa;?uQO7POn*t>j_TfsSH#~YQB_1wy*NaS0B7Cqh}wN!DBv@ z%4LdxayTg+W8oC^*mTCw*MosCt&al#W(r)l0rJAaS%rzpAw&imF$0HgRy?7ByFI!J zPAUp)_;5uI-7A&ut}NS*oul3(@oDnN?3L@KR@t1C3y!iwRnZC(b%iHzykz^PFm`8L ztSX6z_@@L(7&;;^K4M%N40xmapyAiiZTR%MgPnafa_Zz^Ss%1r9(c5dq{oRR%$;+_ zq>3s%dUb8txn3$s>6{!$jL*QjNqU`}v=@y7aD?d9`er@x4j-+1tD@SD5|8NK&l*Gr zLS<GJRd$}>1#U9z5ay!UT<M|a$}a}uf(qr{O!VZ@`f$oi1>B9ss9F!;Np`24)$;}i z$^GRYl`V%uuzw!#Or1x5T)IRat5^v0dR8H4dgW{d#IDgo<dw_wgnhY?wBFq7q`yp? zTv(UO=bwJZGO?c7?s?7qwv=495$H2Ecsn?<ZCmN!(iEii<C0+nr8@+PhXWzZ*1D~k z3W`5qOYCXs@lppFKJgbRT&9{VUGa-##1>eo$cs3!hTP~y?;j7I<M0E0JQ?;XLed0A zq9e}9q6G`2?1PU<t}K~}(hUvDRV)|UhqhNz0RPGts+{l^WrEkYzs^qc9a<aHfd5l? zBW362m2&?hFUaH{f0XJ~%Sa#<PNXIEI5?ysfTgm7Gqhu;3`!Oqa54`(bn>$UO62Ou zZ+h;q*1VWiNTGY?0GI=VxDgfRrF9Htk8!!T5T&ph>F~{PA?cI{656cg9mXL{#-^<I z5FX<2IX_k=0vBZJ9-yMM;Cu1_iKid@Xh=roGYQgIS>?=$13ndWdeP|8OmB#+T)RcG z<tZw~^5fJ^(gsFpc6BVL{%AkP`{acI?+wsGA!jAMaR&Fw2gqMNrYPg+CV*he2Tbvf zAC}((uLho=>C%$%Tzc@DaohuEn4Z^3LyjCd<i!_XO!~-o{U4x!vacG5Fu4*NDa&wB zNavTjiOE(-J{&np>OOR@@;DFsShZlTy!KL8iA;Bgy#Mhh@+9`=;zZu|b<3~>d!kfm z`jR}`xRSOywl?;~+V<HVwa>>r`suT0LvVWOHY_3ZNY#g{NP3*cd~i3H=k}BNn+{9= zp&v=Znw22dXmn$b%YL10AN)^+5m&Z_qiv|3XWJ;-Er-!2K2H8zzC=ci8ZVU_w}EG1 z9eoyu{8FVx{{h1rG1GnodF<J}S;ma}LDJ?dCcWNh1H+`vLo?CRurPp&=N=q#bLh}P z*@)9uV_*cdor;4SqdA!I3Jn!Ml!qy>^g4%BC|^#}WBVc9hfQS^6S!qU8CAx4ap2Dp znf%2#S-5hG^uysXCG+R8vPa7v5994&*|Ot++)=Qk1VjhR$d5+iV3#oI|G@yMbZ-%q z&0<0My(4IY3?1~bgr!W6Q?PqWwp1S3v2BMGEn5z!oO3xiXa-^^Z6RY^om+J_+^O*n z#URBTsGvFYIh7yK<1`J60eK1hbeX7@jXk!lC8Y(5>WL1M`E#boYh8ND{!`IXw!(w* zK(&V@Q~LDs@(a(%9oaJ~1@*LRrnUcgcIluThI0C&uT#0^c!+7Y1Dt7qBv)8ma0{OF zg8_2o!ujxk1b;MaBAq(5#*W~&e<a4YYq(Vmkkt9uMzn3PFT^$bt2i7SL!I8A`>0aq zK}99MzSyQ|fW-C;(H>d0Y&qId2)vRr3s)njf;U=*bQz>@p+Yz%I)kzR`AJz>@BWQn zEE8lOX!G$KPs?{Zvdi~h^^^P=v%rB7##`uUDLG+4-Okn5{*A@B4RE5AQJJG1D%Si# z7Sg!LGb&W~4m&Q-Kix*smTe^6UwuXj=Ew-%!p@wi7xFQ+bYJjM;C7|}+5xql>j@Bc zbl-;XXOkf~ckqYy$1Yqu3vEhHPIh*M9&l)89-0E8Wc|`v@<{cka4Zd#z|@kpNO}2l z#|pUv(w^?u)?<$F>}-e*@(`EUQ$gaalmi}5ZD5{$REjuwc7y;2g<g0^(tX?DG+o{D z0rA-2Z(JZ!9-Ou~S317>w*0<!wd712s7kwa2UkiVJEh7sXPb1um_YL@LZiWgbp-Vh zv{8f5U(lcmmkf%K_)1qObAX}rXZ@>EOhl{!5*$LJL*?VlIr5LiOcrL_)g2zO=t01Z zi`CHd7hDJ@d4asA$^j7}-#E#15bx0XFW`y4#)p~=L-?+xKT4H{n@T7O#BBg_7PwC~ zZ(kx=Q*#E6T?(Vy!Hx%mnv__c;Z~!9Ne<myycA!H5$nP#H^7^8Md1Cd6D(zjFPof| z1J?MVrW&+29Sq=5sT44Zc%V4)lsXM4ry8(9NEIW5flcq#prtf$Xo71U7lSM`l#y@9 zVcZ-aV<?F^a{wo0R+XcYRhmB2S^D>AFDdCQ35AQsMm5esme2snoK-ovDiZ6W7mG4- zKY4V&+*kfSnf%Klx&PkM>Zz?SZ_t<WGnotjt}%(A`J4k&ws}{+lIXh8wi*rb6iRst zctHOA?Km0u)iRkg=Ud5=3WH<NA`W#ysjEs5X^(5&>>KSiVdhtPkVK;#uyO1_ji!1k zvhZHiH>?BV#5R%G7VyY<5APyO%lpIIhak!4{t1@aD-&O7pgh1loS`u86&Ai+Zv+bo z87SVs2oF@gImT<^b4`JTL`mpPh1`^9RI-2(<1oPH!A5@O6qbLrmwH%k`h2rT!E0>G z@Q742NFO4Dy0T~`4-F?@0Jr5veWIJye%6wM5!@lPH6&ix2dGS8`AHMf&KYndrKy$< z@6{uX(HKwZYxygA$ogX4P81-!kjMGQJsziw|6Jbc{i#%VxB-?W50Mgg=0tIgM1&ld zX_LlD*KWh4<O6lFNB0mZQy89kkjQ(ste0`4CP{(HP2|Nkk0Q1WR1NGT34S3nD8s`- zLuK=pU2^tZxKyiF83s9fa7t9z8JRuhE9w2=XsO=#IT`R?H_6KFcz_@$a*3s#I>ZEa zj8|YwlmHy;l8Um3vP=(Mpq6PQCK9I{&zvJ)eluHoygxvy-dkMGoe7qMM^5S?J6SWO z*WR7*h}F*Rf65nM&XoKmE6J;E8)zF!?2i*lgZ6^{1p3Ury}M=2x<6nLVIM)<EDdqP z0^^GpZaNAAf619Mhdl5=CCQS7+qp0f%fo1tyE=TuHKm7<&~qo{hi@jxkH4*w?!$)5 zeMJjVG~f+&o;Y}HZjh-{f0jE6-7gJmRgz8X*T|SJr%BbCwWaOz&1`=M(B8OkS-#*G z`C`H^SWe$sYQUJhcI8T0xM-zxc&#(`yTj6Mz@;ZBCs&w|QU+J}2429;Jq(2JL24B* z))Ny;I<bdmbS!+1px>p$(sI(CY4j9y$`zImfqgHH!{UvWb<2O1x4OI|%hvCdw3+hA zBXt@}&z_y7a_Pc|gviW;ae0{xA<CFaJ<2joL@Zp|;;qtF-`M9Uho3h>mdu9%@}ntI zyH#^|VK!Ep5rB<JK(}AGRSb|`cvZ6{b4;PiA9#uNqWnj`L|_xLar8EsUl1Auf|QX_ zk#hD-2s|I@#pl5mBpD<l43B|<7`r9WBeba|6Z$_BjV-{)f%S8xZi{!N@3`?&zfwso z&Bhth*v^56OsP)t?=Q$dL%ti7EA8Zz&m1>0u-Br&f&CKsZTrG+<+)zpO1FUnq;BPV zaL5+=4uAJRGWJ8{_uE<ekSf0LU#7ry8zAkVkexb|3l7FG$f4ds*~SLQz-vc;P+3pq zfcsCVLPHB+e5my4+EG3nJsl3vXmoz*rFP?1GUfZvg!7*?Hc&CtnN)4gP(pQ(hbR2i z&H-v4anKy8fM{1`^VNqIDcfP8al?%tyYN6DTLljgos`%Aqcp+n>+%IZ%Zpul%iL9~ zC3m_22!6O%>v9mQ6th&<8r;FP4l+^hMCJHO5NUu!&Q2P)uFg;8Qt$kyf4PH#C-A=F zGIMU`%X%g}8aHU9K*eZHQwWpFUKk?$a5@^5&iE8*v0T7km)GzB5h|9h2kT$*x#9z- z)|t81Jn4%3)Ocd4%s2L_1I$Un_y$TdHElota2fE{8}h+N<0Tr0AbBwd{z(1jWbVun z*hk6Igk@n@LTKt~q5Q{!;~!e})hIw}NCM7OZfIcQFYATR-H`lxbyNIPzb;+K1GWqa z^$GHj_G(0<g^^M5OWxI1>R26V8286D2bi|uBB~=(Tv?)qHyE%8f-pINrD<CYXt7}u z9vLPvDKqNnml-fvB|~zlHdA;}KjcH!5>u-DLE7YpL<1xTRl!H$wOziFOoRcla=9|t zXD9iPt{fAbrYG@P!yWm+19GvAF&mo|=?4y`LJ13NJbn|D9aS>pBpzN$C!<nH_RMLp zY?8D6sdUdDmf9L1EhW?#%eIivW&m63fhJzo6$X_M%_cTNJ(%PCU?cz%tU9YEId$n^ zM!Xo<w(RMOG)`KICzgSV7=Z$aEs&<U@aw$xpcM}|z)iiJ5n1_#^{FFrMgSE6lidP~ zz`#7ODQJ3fVnOZz06+jqL_t(=nOeSS)FrB{2oHL&RC=PKi9amOTD>lhwRlZBG<(SL zmcrg+$e(-N>Z!7*5By)QnCGEKKDV+A)CclZW6$FOmt>T|3{C;v@-n$j$`N0dopK6L z^v0=UCSxuP8lUkT0Hitd<Hr~NYZPEFN6s*Ebl+AP3NN|wGgeFUHm|~St}DFC(U!p< zCywltkwg2-CleM*<Cd?;@L^pgE0+7h6<trMo&41-@nk6}Z@tnuK{sRjabbI4tUG%; zSb{cek`o~@QnThGk_`tYForf3OrUJ}W0`b+^IbU}ms5t18ZHl&E2!@&$r+Evw}`OQ z^2fR$IdmdSs#bqg3ebxW_;IomF%ZWqp=XcFx07ecPYbrlC!+^Su8e`Qf8TC7b1qWK zSEz`=IVKDckMh$GlgB}Su9R`#{3KQDHj`$L-;b<-Q$kxHZ8Ud&;lnn{_gB-GC<vQe z)3cocSAD`ZO)9aB?6EMp77+qH<U9H5`=8{cJ_F=2^fwkI#zkLrVxN5b_5Wni@|{wn zRy7!8BV_&hEt0cnDe2Yg4ap4DNR!AAoR&T9E1CGiN~vB4r-0-1=Z%|oNzS}Q5U;bO zhmnFsqKsqiydn*)h{hYGEAhl1Zz&5I0~0JfNqG0(t+ICAb{qg%PRf_R8x#FD9!W<S zR$5^)mziizF|u{jYU$IxxBU3~N-0*hvb_0DA8FaRy6#=cvNNaw5_vOU>XnxZ1kDf2 zYh@nqn1*-GGw0eu#M8J?nfLQt@W#*bY^S!;tl=XL5T?3)!>wb0)D5^$7q%YHuMvj_ zwS8WmH*7lc1JjTpS-a#ZK7)>mwohG$ffL}jmf;aB3!b+DJdHCJdUt3mTT<RHBL;Sq zeA%;rdT6mID<^+^eY-=dzv~Be!2{jcH_&sRGt&0Z8+hD?9+LiVzavM|mX%&z+Q^-` zvg1&<7(@wxY^2NwziWSTJ4>Ixi|{_Uw+sa!u&yt7<6&=$b3PsuACGfaF*@W2OXN&E zKga<;2)v3-cps1TV_r{;i9WO6R4SMi`)E@=4S@5`9p=q}qfHEA6An{(@X>sbp4WsI zACL6-g%Q$y!l!(q_wG~vDj>vm-x^OWqD7lnL{->~bHf62j5W*WO*f@Vl`#jxBatt1 z@y6oU>*S|cU2~2w-k?bKb2UJ)Tocg~^H$RR1wb+>;)ypQr;nSS-MX9I`wyCEfF*Pd znvbm?V2Kq_@u)9cd7{jL?JLczUEeV$!$FT&eT%XrGfx-(dB4afDIdmz$H0e#7zdpA z%THpdog00?w7>!Jqr$hFhf3XP0;%u9k3#&in2zs!ZekeE!H?M58pK2XqrhHff`1s; z5b^2)^LEo+cztz{{^{5t0H|#F3*>Nkll(<Fzz-hcLxQ1x*#5NamYOOj5XsAknuziE z0ZsWxp<DinV>|~GNgj`Q@J7Wm);ahL?<f;Io;ZB;1`lFQoVGp(5CNc#UR3~mrs9Wq z;Q$6xI9FD)aQ$X0tF8*zl_Db-(8&`QqcWA81#0MrW%Hu#Q69Q<WN{dWA1xX#NDu6n zgfv*d#579F1nxxy!oYK;!H22suf4X=jEO-s=FRxtxG?kWm!FuCqsE)4IFE@zKJhMW zn>!;iwgxZokB&ZPh79`H%$PMdp$vrQRjLsOC-NnJ$V&{AA&jfVVEOQj)yrVZN}eKb zF%sT6d~zlD7Q!XI2_N}`s}y%d1+@2iqqMYOJY>1gG-=qtd@^MjdpD4Y^#a+0q#k~g z&JMl~x|hf-$zuX=sKq+A?MaKJWk%O$<%ZTF>4LfgE|euIN0>KhKq!o?@%U@sC(x8- zbK<dVn%0GJ4e~5W3I6q$#}>>pVS9G{>+!tV2-@}xzJ`9Zb;A<##G@5V!D401urH>A zn<+=g-*IN!#wDgv^?OaOyv0o4kER%O<#<c}iZ*9Y?KfYK8)x3?`H=~Yj?pG)`O#~z ztlOMCe#8WA*kHc+WQ2LDX-hL<(o_=}g*F8~<%j)oMA$jAX4yQ`zEuNLtYk&gXVB+n z|A9j$Bs9$7S!9S7w`bQz)3!|uQ>NT~=9?epD&H%AC$xun6BZV1rcM3cbb6(i*|B?{ z*|}@CS+Z=IIT3sc__8elFD)J9WlXqP{_78>(@U?I)jJO>`Q0|9($Y2*EfX&lfYZMC zULWzXrcC<fzOnBJ(>}4OY<zyBJ>#Ra#JA!X8(|jz{GDmipn>^r?sA)s=}{N#2f{*6 znXktTGda?wGl79=3=WVo*>dJH&%E-EIT8W-GcM?H?!*Bzs$UnADQ!BFCVgfTm^Q5` zRJ61iHhPNYs&WdnptQ5H3#eQKPvS%*6m#+e9-KQDY{rcG&=f9E#Ju!cFLN>^1Td_; zQMsc~2^;Akir_7Y-zalv-xkxYb30R@U~$u}?=W*BEGn^2(Y!Sm<Uv?WedS<jiFibm znJLARe%k_Ae)X8>h+y;mq%Tav#xI)1tF~$enlu5>mGit6W1Q{qlsQ?UNWv%V!@k#C zj5DpCNPt6_;iHFLGpxTPWMwF~**bJM!alj`iXtrA#w>p@Hw)kGwcR_uxm5z&VA2qe z_H}6ePv+qV>X^yDtuhhOkZow&)CJkPec|t>0Js#oU@U3QKm10=K%WQw7ft=b)UWr9 z`FZ&!69M}`EXOJ)8a)tY9Ppy<bwPdp-Proz`zUa;DZm+%%LJ#hPwc-Dmp4{;skrmT zU~C^@wr<^S-s#)V<jk4VJW=~`Gi&A?6A>Ga24zLN1;GJ-luZuMgzoi(o5R~zn*wPA z)c~17(i*?ih0L`1Yc!>{MPBIzl`<Ofm<~!$e3V(Xe688KYriU_HWCM+h(Toqe~g<b zZ0!}61e%behfK$ItxTPIEzGvPM-)#*%xUz@j_EZxKlbLz-`1EGYgWvgVak*$YYsxd zQ0Nmcixpv<N7O3=Wemjw=>W?MBU@}_xS9L=au@+{ukZL}b4a+=M5KocfOLy6i+=mb zlqq|!88T#)iNpX^Yt$(_V<szbpo+mnlLoa-p@PNC{-Y-#LY=G}%B$#Q-dg@xvv=o4 zlRsNJ)4WY56XGz3hYGC4AX(Ykvba%64*<d--2>yuo?UxQ-#+h|+&QzE#~ypk%>MCb z6CM+*rVcG5lPNy-mzU%b4tkF5oo5PVPLB-$I2{@Y$Ie{lt2xUO4B?381PjR}sRtvk z$dI$Bi^VW_>QjxEBpa6~4(g~cC<o*RZ+y5}y=<W=UFKfXf53+(6xJRZ1Q;$<DD2Zq zd?#jmi3rJmoCu2LbUzoQ*TPvk@LSWc9^=EzvL!1_g$fl+>5_MuK_7f*4jw;iqQIks z<%x^NfMd5AIbxW3pmHS>kUF(#(xi!*@b$OmNN@<^5g7O?F4BZ!0Q3EK7<4shWCGI! zn)2n#n-2yLG28YWG_fEO#}yhKbR>U~Zk)8R*ia7G%QzUys94fC>44YxlqEJ2ev%c) zDQ*g{IeBQ8DVRO0S+rrRLP{10H<IFJY2w1<okG`w#hS3wCr$tN`kTxdGnz&X>zf&K zelektschjf(NX62dB2!;&$lsYL7TE=Dwq%Y4>G&<9yC#C&!hzvofz^M3<;D;EIZ*7 zyv>VrBQ#4#eVy>dr#2St>oH1i#P>v)1wTzUnbT%5!$y2#B2ce7QKac?eA}WdZ1xQ! zh7H1?IGdUK+X_c2IQ6D?96%>ziVFuhJWF^C9OEKF&6NNB&lD|E)Kslh$xN6q$(#v` zRtS`Z@i27m*uKs5?fb4NTDXYGkS?uh``oi;_D?^Xv!PK5{g47p3Oi}mm$_!oqx2(E zlsBkx%hKTanBAr+43M8rTLU8uBcKf<3b{p7IRw|Fc$Tc7z)^3Y_s*?Bre6K}=FU8M zO!v2Xm@PZ@n`l-ra$q|-b^Mt5YQjWQt5z+n!uK<eJp7>fWYlPL<Yc&sKs@5^jf*hR z;o;_|pMEiI+qN|sGo&}giWWBS^y+2S{<#G_gL-5g1FC+IKY#5PFA(&By}TX1=aemC zwtw=`?NF2(S_YMh900|IoBg}~G~K(t0fQ3w4szEuPR7DWw|LHEb5H)<rda99X3DRt zwS8!x1><3COsHA1V6J)Nr7k9D&mnCqoEV@KI(_nxnepw{X6T^7rZ4!fW9QdRzxRil z9eehJ#qbB26$ifF8uX_b^j;s+t;?&XM~@!n-F^eiM<0J`mabT%ZOffhIeqGcnf%Ro z^IDfT&7|o+V`9X%Jndhdejy&^Iezr8nKN^mnL2H{S+RPZIez-I;sviK<cW5S$qV)q zp=W~4jEUn+&z`-^(eNld2TqDRaihHCAHq#-4{>JWn)#;P(=E-&v9nda6M5>vG!)|0 za`VTEMdroU&}nPeHg#*)F%6qOWrlqIjX8rg(OL%3HT>*JGkfwErg8l`rgojW_&i}c zywJ%kUb;$)Lm9_nS!t&dk0rfqa3{JVqaw`OW%JG3U0*dH4*%3_J8;y(Qu>m%wq6LI zkk!}>y)7&x*vy{(oq6xQ56$*H$M767i^fUHS;|w3kmBS>;mhKa+?SRnzyx`m4L)c- z|G2+-rd?OF`{-E*Z$Ki-w{f_243LSHKpx<9fgRmB9P98%Vyw$uC2*kSt%Rt2&c5A| z9|_NI%?nQ)+fS7F`lEMD>kd84pPLUtAMijn!w^ZG#25Z%3Xo4R`GdZPGA$+^#>eO| zb8yEx)9LxPX7H#f=z~H`Tr~7p^qCx=sC)w(YCrlnW9I|!qrg8+fy){oVOFu@LCP`6 zWHyR;7#t1EOja+5HNi)AnHO3=Wtu<T4g>KZbNcidvw!=arWK3|RjM~P`(RX14=>7g zZD2^R4UG3tO1!~l$@DKx?v!vm_Dc!p<J2Z)_HriZScEE9%$H4*h6^tY37kcsFOxSm z#H{^&s>zt?PBU!WRP|C*nW~DU&47v-RAJ3k$7|YYMVYA36Q)t+3MMsuqx}L*=?9x( zmYB*V@KMFbVoGIM(bg}kG&z^RT~#O+LgOSn=LJ5@d&RFa&AoS*h5-^~(PvI<-e@Y@ zdGanH=#7PKV_9Vv#a2P)^+o`AjEOmO)O2Xo(A;@<O>+`6+;nn51msH(QPvY~wI8KV z4(kyQIH*ASr9X@{cV<clPgCsl<Co36`QapZFFFY{8orVf7!C9~ePXM5rg42!u6#`s zwELJEkz7SxMJn@#@IAa^jk)jc5~juTUCfct2#97PO&;KXGV??VEaleNObtc=Uxb@e zCyv1w)51L2tgTtPCdizFqJ3b`CeyZgGgIl&CT36YId%n_qooV;1f`s8z1}dh{^u`E z_SF8^4h_3V`DZbyGM6wx2ZB+Pj7wr7M`p_Wk&b*A2Vikgk><6wEls|nmCUh_XeBi} z9S#kscC+~WvPK}>kjK#B7%z;EzfLrFW=U@ip76MQxzCp{2qQi+aJUaQR|ts9wqfho z$uA)Z5$4A!Xu|W0UoaNS%e=MBItZ{7&=ic|e7x~AtWz2&Nl+D`=JTQ5O!<4Onn^Gg zHGlGP!;J^B<tlEzp1stBgq${=pMTa=gt4`6{{iOPX;aOl@ng-s#q*)v2bkQ2E1KCW z{xtCz$c+DVm?=@Xq-o#bB{K<w)oIiJXWF%FU{YcgRr*W?O^*R%O&IEd9?V3?Euy6w z%bT3Ql$Va{6f*&k(!+_)d`=$PZ3@Exxc~+n)-waCW?{OBC6G(s>N^)O1s3>+Y3Mzq zbSJ$rDH9iR+|;f5uxZ!vbu;CwF(z+jdWNSqH5#-xV<&uLO5J_8d9+3?^V#R)%#7(j zn4tsum>dCqCPVt{rbXLs<}7%KIH}2%4DT{Jo?TDSc8!Ujg)_f0Su@{Z`V1Xw!U2$c zz;?+Q_IR2k;RS_?G=q9~GkNnCH1ig(HIXPTSsO3if2Oqee5|yyxRNy1u^8<u?38)? zr4FWUo!aJ`ug02tisVLL5on5+eavjyxyS6;0R!E`)lHR3kD0+AePm|Nm~OuO^dnO+ zPgblbPiab*uVaGt+sP3RfRY@<gVm6nKn(ezeC3sG8@N>fsK3~~rWrhwMo(R>b!Z1i z4s=^o2f~Fp^4^8c-^BOoRULoE{QSdLrT`3&BR?B$dcD#ClOtj>WG!q44xfO5M7SB$ zucs+l;%@V1m$%L2$={mqzn^GoKU~42LSLFLQ&IED*RvsyW6hiylT7(i_n0Ov+kk&2 zn3>bRH+_0`HEAI40@7qPPqu#BoQY)JDVHlMq>-Ye1qFVI=<&@hAAAPLi&r5zT>C2+ z_9^3I(7#1QTF;F*)iFFU(j75h4(nsGrO#rj)O^}(Li<woAg`!g<78uy8PMll^Yst& z0gipG9c0CO022eTSPZ<d3|nPJOf33R^obl8>*O-zU_5j_PPC|ZJ5Y^7pBfnj-3J3} zh#J)e8J9YM2RwfG_;ItG#&o<_IYrqDd>EGoNb4aSXJTT}b0c5AQ_n{&6Xh<RVdh}( zuI*;<2gA*z?|y^~g}k6}Q}$;YrQrkdNIL!E#mxvF^%U&?ZV%I?*D!dM+Om<RN;B%^ zpldwztXPzTIydRX2@%pB3WCyKjfK!3=~c}*l-FEQp!7sBSi<xAuqzaeB+$AAOr1zZ zJ|X8$nm>br%&w!sN-5^4LYKUOz;9maARD?6Cy%|ro9WpHvOFH@b=1chTNB_??|5^A zg3D{j;NY&UW<d8Yrh6Yu0;7*mIxs8N{cRj>83W{PTnB$!(ZIy<n0)rcoicqpzifK; z9c8v3I%&eg@r>=x7yf1ns6Qj*809aVU}7T7>7%>MuwI=__xC<E`{1ynhDl(->agMw z@`mzHCD7lDo)5f_0{<`tu3&()s)*_UXcrV&F;r-%Fu<eY?2+xJdX=i?k(y1-(X*j; z5Y9*#cy3t!tI3c$rRg$gth0obB~=KjP`HYYH~yIU_??#ww;fO62jdSsAn$#=jX9+e z5Ffu(_i)mnRRmQZh&HDW2bn7O-ec-DeZ`!@z{x5>R2-<}asW&`8QCg~1gAC{69JFQ zrKV(tK!fdG4GzRGDbf`)Yj%gL@`*%j|HzTB97U6f5j1Oii5o_;FZev+opZxs-11*% zn0rc<Hb>|InE)VZY?~_S6APZPZQf1|SUt!okMV?=dDFi!nbKu6W2Y^&UWWjpiaTmS zl}Q367$|iKMn2FaE<V(}(xQ&Z%58o4@y}!)s{1OGc1y!VJdx}Qfmy_&u8j#bkyu9G ztX@4+;eonl^O2KyP96aYK!(d~_H0^e?kSevG;jNgIgK^VFo`Oj$`Yt%D}1kzq4V0S zg9nEf;mvvW$WBwY+M}jI^(V~XGnl=0%MOKn+v?v;It;L1?K{GpC5_y7ymtPSP~H$T zw*MO@J!pa*1(h!49(xwbC^?8RSRY7atHxeaNruPY(%<Ho95BXwGJb}ZORI@WH~0{o z=;Von$eh`8K%+)f?^)BmZ6lLK>jAs6_-8hy?{95F;0CB@I{bwsmk-(=qfBHNJP0E> zSd27LSkA^zGzO2+QPH^O$3DCKZ?uU-L(#1X6j|V!L|Ne@QqIzh@%SG1@YFhfaI-0v zCy)8^f3v`a9`pSd!%Q}o4aUXdWvap3qJgQ|u({cN<e0Wfa*j7H)~ug1(PUN{WHd#} zKWg6Y-rbZa{jgcMavh*>Ac~G01DyTa7MnnSY}4SE#^lUb(QG{y0v@t7Rb~Ud6lJ2A z?4TTfLF@~l@D@Q$Gfs3$holBb@(6>)#$gis=mMM^U>ce6$R`{Cvi;#56~@>zrcbxm zO~on=O&FHVcw>*4#?>owXBgv`D!m$@hJ6Y{H9T9`)|r79?fUDH155zqnP18r=K0qL zm@s%tTEi$KFyajgtn-*CGk?w`lP_;^)BFAZnJ~<%(>M{2Mjwm8a7@Gr^TnWdO`-gS z%};X|tMQS8VLPZqyU{=3<KS<9mBM&vWi~_-=n-m`%^qh0(&jd+|J;RY4l(^-e+p$x z4L(TwfA+2ez=|Si_j_;ivV<k)j0gy#h@3g6(=$g@^vvj)v!04MoH=0T%o!tyVnE3P z1_a4*mmD^+Y<Rn`{_m@rdHX=ZDk}&4)4Ok`r$cpBb#+g7O?9^%c<_<Zt;gPS!DY8f zUNJ2lt=+|<SoVF}b!t`bLRoUgrFWZkEoBt|)<7x0{~N0H4RePwMVN5$x+nJ5ALzY2 zM@~BSczO1{(SB_rv6bWB{LCbYzbeNk0$wi^{YQEJJlT7XJ>;glUVuednfx^JJ>mAJ zp-7rEY}!u#aoRs+_XCcSiPL7IUk3#Ci;#oqV~0px%0Y65H0#h+{`2Gu(zfl+^6LAa z=!YhL7UBD}q;R?P>DI~X?>foQ5kITEs6+xC#R?aS4k`BOufl!%_5}*a4c8yrs9J5H zt*G*fwU4&VEiGu7#*c1`=TDaFE;>bO;k|eEW%tOc5?@*5$uZIwLB2lw^nJPOfoEk! zK9)^GfK;(W`C}Oh7qX>-h9@0+q3r{{DiHm6ik|izyi*K`7v++8p<LiqTwEkmVFCTi z^w}r}@q|S<Na&A;s^Bv}(*Pr+VS4sme9x7yEtD}MhRN;sJ}I+uSE3N$qj<4Eg$$;7 z?G-^=&&9AJV1>Mc4=`t)+h2ZLxYV!!9ro_P8wekLXf<e7svf?ca!(bGNXtHzt2978 zQ0LvKF}^Y+F_cf6cM1)>QTf1laB=QD89ROw#^wCP3>a3y>jLtEZR|kav%c8Vnv8G^ z4{Y&cLS*HyhMg)v!LLfZb0>}-C0AekFL?(mW~~21$-oDf8ZLF)0v9MCx2^i9No**( zQOu9nw(_9(y7}tM<%wtClZ7i`b;l(df&0rj!2VCi_2|zERxXuy2R$a&-gKYLSco|g zS0>@z#r_zFa-t(<f5U(OJ@c2N7Zeb1;D5@2O)4NcM&ZktSH6bn=dgte$g-k&a?~DO zq;<O<GJ6%412deBhhLxZ)qK^WpQTByG+5{zB+E+Jr0Ce`@k=fJ9A3b?c7YtXPZv{$ zg{k;yEcZP39@K=4WTWJONt-cppa2e3qJ?tj75%XH(5^BgcNLZ(BOL}3jIQ8vJmQN+ zjWLmi5e6+vh$E)QQc|=~j_%n}GIXy$C_dBM$%rYdke=|7mUIx9{_K|UgkUCOnY`=2 zpAw0ES1u#J{7AY(0l5SgkVIvjv;=5D$__wEfWaryY++F-Y1AP&iVkbd(rMD6X?;2W zst05Z=qmNiz%Ur+3&%2YfK51f1R#HaNyX6UPv4LhDIq9eu_JLfUHTkyi7FsX(Zm6n zW~<hPIFjcAJE&;MGCA?+Bc)NRZZdN*_{q^Olz>aHjH^wf26F7#m&!`al#Rd0f@oG7 z1M~)Ob({^bIU&NH8EcoyNqg@qO<MGnd8@h9nm|DS|G|&dizY~mdiA8)&ihLa%*+_2 z{Lvd8SdWnB%JOA$>Os9F6Fk9j50Jy!a_eIs$Cs3Iz)o6;y8>5fDwE>HQ>AN*hH~14 zcc?`ktpUkvPKuzVfgg8@3NkX7iUP)0fHxduPaN@)G))dk8g_@K^1Vy1bEE(!kjzIp zu9ibNufF`0)XB<_Ozi2Df#s(eyyM5`OziiRk&zV-^W!#r&yp@(_mP!(YcSaa-sB^B z2JCHmKn`PB8aQLtFpNW;mMxKi_uU|^+V_%GG<8D@e&ps$RJqEtgF_CA?th#EYu!@i zDY^uut`d8qEE+#p>XCkafQV#B$DW7F%;hE82Pg-K2R?W#pAQ9O7_j(DZYm#-S)w0A zfFa5Q=gDh$`9xk<&oQ;<m`O7-%!A?q(wlZDeq!zcIa_exfqeJV6qN?c&a0o_!1+%e zD2-JpDohq@lO0ft_Pb)?RB7F$k=*>)8;}qv_3~#(uXgp(UU{5JvRrt}!vceCD+O5; z3@n>-CVVcnXu%6bb|k5ROu~{$$|Ie^H*bwxO(qKD+aYgD-K0A5*i(bqvx5&D@aD-A z_uMH-;Y=C+-4BBALuR2)M41tHpC`s|at4H;VOUS6(@;#LAy?%~<cgCImt77yOID$O zt}IwAr|i=Pia35eLOV@rDz`lFvJ@aMKWebml!F&BSP#DZ-~d<xn!>Kjp8aHXF{Oz= zDmiegmSa1HsvPM(EP*>8fGOKJ;o&3N3CA5T&%Zm;$WiJLWfg-k<|N$)gS0bb<Bn+y z<@47cmL^R*$h-o`0OWu8JNM%_CG^=)=(})3^l696f|bRp+*Oza3MIsfc@rc9OR-g1 z8BUW1O}au!xl9$XP#>Y)@*NC2)wL^Rzg}G>8Sh=^+Q|KnzsU_!)FR4o2UPo4t{Kvs z#(d*6ZF@0+0&>H3!hN~fUvM~N$~(R{Deq7kqD@vn_J8|%gdDSfPifw|v;61zkJzFh zdu&(Mwkh*`tLM(2B`*zpPKJFuT1wZkOk_*-(y~v$&n)G5=a1zh9$+ck_JJAUnhtkG z9c2(7DCZY1%9T-Lu%{!IRWnXuK*k9N|6Uk995(<i;&cfxpsO;H<)J<2&Yvl7zVecM zJba|RTl76{{f52&2um^AF!TPxP)=4SPZ%ZFT;5;a{NxLeLjLd*o$-piAWclC{Nl?S zb)rgE<t1t4M<TKTeBlQRJZoCeM7oSN<sb>ImeaZdJX$Um<}Z_9CjB5&rp^Rj0HOT% z>ni~qVIvPK2me*+REDUW2Hq+mj3glMS6!qMirSc0L4sdvu-f3ASN|(lTzQAgTeJct zuuPvH8_T_8ga-=99itvML<M^(m1B7L(Xn9pbh-Q1$7J}Vso0B9KmTtiTM$-L9MBF% zwGrr1D&&{(-^zUtJu5R7EY-P{)(_t=?29>i);@=I#r~(JkO<%e9N2a_uxSOPwgWa3 z48S<B(E$y6vqE|IrTZl#IZJN2=UFL2IvCri)szk@VDYwc@nmU&eI1ih+RKF5tKt(& zHbk^A{MaSNWc9r9(kjE03J%N0QZqWs@E>P+OM<N-vMpkmWWy0CyNZ|2m#(c^%k7W6 zE=5EKjo9`%^M+3-pZh}=6v7gWjhnMt3~X$`OInJhXvKWF>+*hBBI+cyem9xEf&($Y zLbN#|$&&5n`49vjc%jM;z>KHSgjE;PIU0LFCR#um3|@7JqtICji{vj}hA~K=H8soR za1JBK7_1+keBj^GqGbp9H8<b0Km%`xJoE7@IKFOGltPh#WzJM0ktQvJ(F(9Yej7hj zdbDbYJ;T!Eh`zUBZxCcBkNG7g0TYI9%n_6gW^va+?;0$}o+GFH{YdHA`$(BNcZn>V zJ6U@5=qYDl+4ZslED_=a0?IcIOgVH`KEkJHZLFY#aHgXbE|sORiah!J&1a-eN`_p1 z`!jk7jxGZNG}27V%lySZNV9siRmnVh1~)}F9uSUk1+oKKS+-!JG_Rd1X*dXpmS)Kr zjb!j>45E>c19Z)&d6<j2A-&NR@+LN2Z<5_y#?Dxz<;Nw02tfHNP>WPx56XfyW{qa> z5DXApN=9qeSwDX*d$wx|<wAz^IkG=2*T_%GBcWBpq0XmG{Xqsk^Mni>__REO<(m8r ze8&F`lxLoK7C+t*x5?kL^6J}zrC9fg@pwgk0}UIJ^J*=LU+!4{V6>Fx&6i!;G?0s~ zyI=Q{i$#~o*?-?pGN1qoN0O!6p2x}D6-CA)<N<k@&tjsBI{N(8hcsOX+aZJ^jpU7C zW2FdS*=#9}+T5_$=x-C=m2@hdpomM(Y9(J!Tka_!DYFDf!2BnUM65cFHS0O0g?@&q z04W3F!P<(vv`9k*WSeRzAc>uap~pvnRWQ7=Ea0nsEBFdU)7ar3N!_$0`SOP;Xdy9~ zg|?avg;EG@HH;55Z+$sI6^lCA^pGPTXMYD}U@{N#N{3>uw!Dfx7dgyKpioQQ(hG~E zWOCDNXh-FnPu`Z64e{aVzGtzYO`bgP@0+E4>uxgS+lkmC5~^X!2`MIxM223y`B#%H z#`zOqn-s6bm;0&Gp<#V_@RgxbfILM@XG!O*RBWFCI>Q-q=*d^&15Y_H(cN~yNA~mJ zTG>(=(Elt+Rr$jnnfqNJ`LMh;KAR%NumI3aI_9B5)auaa2Hxy{^lJk9fqAfi{D-{o z4i1N4LXSp!AZDxuD(#KBL|GsQe(%sTmamc%4*r`Qe#A+-oW7FV8{Br0zOO=|y3)91 zFPS)NiN14bAxve0z5?(eXzZ6SL#YS_EtIsOq$cvfGau=DkndY<y-WxtWHH)oul6mW zC{9AUcJkQEpD3nO{Ai<tl_Y5(IocB`vV7VxT%ds5SUs8m$Hf?OWBnofMEIeIoczPL za`XXx<d7qdm+vM{M?9sQ?Sywe;tJV`VsFCfQzpr4ufHyH7Gf_*9gwh1*?5j^fq4^u z92@Z2gOmWz@+oXT50b7e#y+VtrpfHtvk1)6Z@@>WbP6BkTWbK7Y|D5d738my??w!l z4?g%v@?lM_mMh-4iV87HZ<tjza)Y@wuH?t+6*=<yOHaw|cReDj^YM`oyyAOUSNDJv zQ{u9v8}~>vdCc~!A?P2CemrYGV7xYZSmO$WiS38m<{Ybwc$8t>xiohH4i}n)rSkUa zOZ!_-DhSem`sG+z3}*<_D*pBqry-6D3qqQja^wd;Qd2(f8E~fzdgBut&nmv;6J=z_ zc7XzN$FAS?shdB4zKj|*3I_xFpQhJO5j_7@92hrloRI%f{SddK_bh)E7X!FE5(h#g zX5&Y8#}LKnuyZjSBag%3oy1)6>RIk@dmrMaE~(?jO&sC6cdYMH!Vw%CA9KmE2$Drz z?%ZG8p569#%PX3?VdK7a`|aM=B>@)y!ZDaTq1aHQ!hJn>kUROLi(DbpJ`zcFja%;P zMo)a-HP5cabBJ+-y&Xee=_)mEBv$HPfBXq|>yv}s$VuZ|<Lo4tf|wBSiXmwXI7XuR z?zI;NxeKqk&-LqnqkHVWt6f?$Xi<2$5oRpr@)l2V9ozPHEqWjAzWV+{hh@nw3{o*F z!QB!ATT;!eC<7PZ!KXDvg>LF^)08a=k5O?KLY|nLGGUZ^=!qBHe_kBq>ZftRx6e;P zBoy57pPHWGx^?N|Qd5w|i(xFwrb8v+0{SZu8(Ze~-S2qUvim{qxq<h(%rNK;fp$#` zh?S*o&B|PN{sou2_lN)Dh7JGR9k@>qfD<k(CW9Op1egVG?9d_Zz+*3QS3dZ%8*t5O z;I|S8^$zZ2#AaMfaRio?fD1e-fk#Bvy2>?cUEkBrbwAHu;EKVgy$(OlJ@ee-E*pk6 zget6SHRY+mGr52V;>CKw|K?l;>L7wTDp@(t?f18R-7ia$-S<C^b-g>a1e~Y~Cj%Y; zVUq2ZFZjXr*!3v4qO^e<HgcppxOa<q5n)KIri+%ikwad0ha7(iAw!NLu6~ma?z>6f zyUtCr<1(mxK|NFe--wGk7hU3xIjo-x*YDw8f9nyKkrYN<03`W`Ur5SbalvAD=|$JN z*FGHOKK$Yncf>(`NG)J89?9_MVr$&Ak>9w#9ejp6?bdtU!*^WiGMQhipc)Jj(7_)d zgDq%Ru;BzRH7CHUs|FaRV{+pPs#Ge;MZiLvRv%Nq$3%dqxI?Ctj*3Dze&R&eq*E`~ zA{%z31vA_}eGYdMW-UT{%W$_m`MSHk|8Zzr6)qA^av`+8kSj&|DRrkGbBz1w%Q3Dz zT;J`w_mOVIH?O(Wq?p70kraC?OUm3Q|GnRxa={(oe1>b-vb`Jm%V^iOZWgEp(dbi% zJW&-;fL37{aox0|;CZs{@rwD&%Sznj$x|FGRkgohR2b#N+a!GXE0(wm{&}9e<<S>h z*AA^HIb;i*#~?h>mz<jFcIw>O;b0UmUK43LOW~IfT)^|9RV&c9On1BV+1DjU%H11J zKIAUFdVnhl*KxHQ?(BY@KGHR>lce~NIoe0Y*1C_MyWgF4>D_J(ZJU$R+`tb$c4r)Y z0My!O`)Hpv=_)~3810?!11BZ!n<4Lm7k9XW58Kau_RR$M)Jre9Bahk}eKTCl$|tRC z8eW%<2%lTz66B0^NSK-cchq#OEb2y&o#MLg)yLINiMih<eC-a}>nK-H0lV5-ZQNHs zeCKxS+|;E*P}omW7Ar|>QI0zd{2Mi6v5Uqs-04>gaL+${wM$1i+PABegHP+#2m;n| zuqJXdew*y_ipq!~`Uc87`Z?0V7Y^SOl`Gt>w?69n9CoHV`hc#Q-&!AKr-CVwGvdOL zbl0|hJ6FE}`V^!}{H;@{!Y+4HCjI7;v+B9_om;!4^3|^I5r?^tzWvFSxJK^8f1cxB zdf`4-3oHwRzm64x&L`xG+#@$#>TZ1KO;DKPT6aItjhiskHNyKZrk_?QFRZo#H}9wM zZomDHbxTUn$WmIlA>V!E4&1YwBUd7jL#<o9*X`Zn<I8&S<aJ%7x4Wk~gPwQwdh~SJ zyX~>v;r>@53`v3<@e0Q=1LZ}ZO{zHtDlW`-vu4h6l2Xfc>Dm?JKPI)DOr>KMv`2<S zqs4CC+<9)nqSdbV9=%-M+O;&C=>ZzfN;AL789EIOXUXb_2mSi8;TRKbi=ByvvtLHL z4ncB#AeQTQS8I!QWnwKEvK}ojb2wq!&COZrcHOO~Yh1S$V6!~5bigDQN|*W)!EUC& z#H3s37xDz}`MEP@xgno@<#y`X(;a-kJ{Tup6a_RQh}J$9Ji^y1`0bgTq>t|}zF+Jm znb3xn1XAcbk0vA958U9LNpvg^Ua>o5UypAe=wpBr`Wx0)h;`+0&p7FqW#yO@n4i`A zJEu`v60+l=>IL$<q<<uUQczNq=e`>;!cCr@>(1)e*EMTYAEErScRB3H$+{iZ<zLv> zMSmP0r!W1Kvs|s~Z;wC!5l`M3$GD1_)8bh&&b!oQUUF6ZIq(D=2sjXMAmBj2fj9>+ zc-W}Z1#$T5sNWoEhJ-JsTw?wC8xO<6B3X7l@)B9iNGye=y%M$zw@;ba4{p+TA4x+T zEW;D6C(K%=)=bp-o8BK+g_SQiU2>|_!Kf(>Gr17<>gondmF1<nOO+*N29&`sl?*M< zTOj-5(2BGAKO|hnX}BQ`9KXMF31Hc>pQU^A`WUg)my`y*BnQhr^<yv1oh=6vmrC)f zInpR2TQ0f!KDFZ1kMjzNP}Tm*OHKP7eBb9%W6%0=$j2XeRwft{(b6RGhf!Br5`Gvi znRQ7$SazjC=SC|g`_amdv)6DEta;Mw$c)+Z)GADiS1#GtSCY>!*8DOYi^8IB=C?Tf zp_zO-4krOK&SL;A(Rh#r53qRp-{)g5IKpoy10H{iiz4l7E)5veWRad#GJVo;sgvAD zhK`+S%O?R$ZGC8-Rt-lB#tJ~^{uPAFrTJ>rh$URp#|@LlX<?~VyQBO(bFnVNBv^i_ zhm>f2khw-51H6aLmdhNp%qf)N?>!I8xn${c*oD}Gjx~f}TzFRp%fMepy(M*1ai~mc zI~hGKU#$U9l9z@&1~0I0+J7!T2?v~Tv`j5&9qGKs(b&UiT}uK*8Zx9t^{^yZGk>f! z%x)=zzsuFHTE3k@1*|^I%Ai92`_T1z5KAbzwOlpeNwr*K;j~_(X|7s>mY2xFX``iH zBufT=|Dzu2K{|L~MztJy2jS&GG+r|`b}~B!gkSPihA0P{`xzC$4rl^^;#tKp#YfRn z;6M@~ECPSzCPTTu%<@SeOQRHMXK+}E3pd8$GCV2TY-DIzViv6VIE{X?rn6=5P36vk zUqOxmiB>7J0HsV~nYQ4NpzF>#K`p?Xt1G?sKSfsJ#BjC#Ag*L5tJ0%a@vPQ`1b9wK z0&XaG>Xe@(4fv;UFFlouu<6X%e(_8_Cl3TkL*Erjs;}0Gx-?w-0a$&qtwWZQu@7Hz zY8Fm_9$~Cv#VVJKafwg#tMdaPzZK=Va_ZrIV95t~kp^<`2{&N*HTX!LlTXTg+@pDN z*-86KCh@@%-4K>Vzds6=C;%9T>w&M48_Orpfs5|f1xwxm=bwu<lnQI)r**$ol_B(* zW@*E^;j%jRTG|76azp(12Y_S=Vd@_}7N+dLB?ha&SD(5=msN+cRKG?0LnS8<hgl#! z%ktYNm*dYFH&hzgOjyDx&E@0oe$%$6-3;ZA%aD<8bFR2(x$NDgy)J3itpvi{dlLON z_#CDtGmQQl+gXIrkB3t0APjxJr?a3=#`<~6P=-Vz4dtPS2V%<*v=J0da`|4`kkkGH zL`BuaxI|XW9V0C>Bapci$U!@K>W$&BR%Bm<Z8yjpq}6R3N|wuMd+us|4z@iw<5KL6 zNqTA9=%wQlO{rKWFXO<dRLE%rdrF40y2`ATrD%J`OIn0sZ7Xopno&+Ej}_|;VH||* zC>)@)XhXEds83aLU~$?vdjvydyw^8VS#C5i6>eMRTc(zfdDths2&YP$Ao5CBX0Oh+ zz$gC9S)6qUh$TG!n1VN4Y?(2jK={pi&cb<J*LnF6sAV#}`80%My^8WRQdp2Dg%~Sx z6jO=5mxujX|K_&=!eJ{=1QPD>ZWTxVR$x!(Vi`Yrq&)N73$h@W%lYt*R4Yz)0>BP@ zGJbma>U)BIMw%_8lE5IJlnvp(sW?A9(%5otlu0~LHtT`{K|Bl-<F^&&7rO3U>xD4a z4Nkz%i%=Qx3*WLkm+nuU{Ik6H;!D_Hc!~i-F(&K88T@3iJFp8ZAa~%(4M+<(5O5&i zz&6YQe!bkN^IyQ6GV0J0FJmf9ZaV8&iD2)*hhP0%C%Bxba3;lxAO}8Dv0UDH;#Nt= z1iWGUgJnrcR40ErcF;kI4HzqmbL5D>?WW5wQ($x9!VTn-+n$pGl*0ut`tE0$I!hx4 zWwL7FFVd=3hTQSw`?|D`gHPKW9m7bDuYl3)@86JyRKSHA$#Li3C50FeQ8}l&H{!>^ zT6vL7{PrCv4jRjwpN`d~p)8R2bGeO=fzqRcPV?y!5lrAJu_SacmYZ<zp+$=pCH(N5 zyGR!1ERav$d{Me}?ktn$E|we|ys<cU3DPk=e~V?&Vhhh%ycA2=!8;|G2%3ji{wffs zgF2j={QcWcNOr@HG9w=gAW1J3Pe{aJF_&RimgUP?2k!yJ2u`>T?<^mE_bWKUG@Nu= z!b&XHjFsicwHKZt9l9Tfefd~-IOP&_E0xt8<Z<f2{lxS@70887S}}0XnemhSt$SxV z{<OYw%uy%Eo_if8Gv+N)JV~QYYjOASRw_AYMOd{QC(xCP<fi_8QGa#h-e-pEz?TX= zDo{x#VZ~x=<<sZy#KAHlY0!2bnah*TmBPe=z&R`<J@bG)^;Gmw5|owLSMI#4ACXel z2_RZ(1!!<p0a_*_KYU(lXSbDEs0+^5O)-jAKwj%0yi_hZ@o-bFCwGunKO2K~fVv=D z#K)in*ZM14jSZsDmUcTIj%D+h{&+<pMYY&LM%r>v6zh$dtE!NQ`M=GBV~Ki-Cho>7 z03^Q&gOQ0pJZjnG5esB7qzfM;UcTotJ<!L6YD-#nH<`B*hY%o%LL$CsgM#{*Jo;VR zixqX0T&s<I`|C<9s|GwqBV9RpiKXlXOMa3rjp~{bFw#W+{ow0Z!ftZUVma~ArSd4B z2Om}6F}LTGHeMh_sGG%$7D_JKG21iSE1wsuAJ2<(Wy+*6(ki>IeDKX!nZIbM<R<h3 z)-Rxa=dz72l@jbx!P7<!GnQ%P^4Wjl-GAntd$Fxq{iF2i&_b1+E{rWN{=>Z%O-ZEb zRnE#Jf7x`|seX#3gUw@7R%`hYd(Eh-j{;TGP7ws|Sf*Q6vO*pmaJ}r*x~n|)*n`rz z)y{JJgD>j`BDMuz0cpx&uMHA!z~GZ{MISWG=ZB(9xuP(z&t1D%t~m2(v`;8mq4?Y5 z;Pa&b+B^>;MG=m&vl@E@pC?(W98Q+jT@II3ML7Kye9*RqRI23G0yc9&pOUv?p)AS4 zFE>|m@msWb5$ZZua&mA-AHH<KBt4<~zJc!{JO{FpBa0F4%SsO9Vln#ooSbE{1|K!b z&}aK~Z8-lP2km$8Ue$KR{UG1CU;B{=l*^IYJ!H}XY_Gxn3CJ2{CAqL#*5qN!i`LxE z0sX&gBagoLvAv@~INyQ#E=M0-vTCaIX`797VeA!|CI7haPE#6F=?MI^2_bz|U05ys z9@8LXhvR?>B?ODY1;?7_yFi;4F7#7A?et|x2xLpM=p{j7C_ij)_%Ml1z>_6HLC4KL zUV;0t^@$<tIfQSdk*I<Taki%;aUcwXv#!s_iDmgo;L}82`M}Sz6CV11?;Xx=$~fUe zM1Y5n!deg8zx0tPqip`L0!PM-9W9>>9WMD;ip_qu0(>?eByd6LAO-94peAuAk5~un z=j{Y*MHKAiXw3TO_4%@H`FtY(*GtP_<u!5la;%$ieX!MkMp?_yhkyRr5E(rlhux8{ zUU4?&vssT{Z1n+eUnv6x<n~ox0k#1L0uBTm*iksJNd=@&B$Wm_gyBmX6V8A1-c{0| zEEqp6N0p8oByf(%mo<l#vC_G6#VH5C5+_5B|L23Wk;9M^F?_>gw!{}aEx<}vPLa;d zvhC0hEC3EAwUD9XW~wrfLlN#P$ib~Y2%utc<}cq!le84M?(SD~e=(}fXjv1*3BODi zi<Zhq&kvB=utZ75B>an?F$pJrh@(<d2O8LWu5jfnIcopjQme@xGG_($>0<&6N_3cp zNhkdX0dzVejuSqHk=RODx%pp{8K&WkV;P*lVd_7IhtTZYRdR3$O`MFXgkS{+U4YI3 z9PU+7#KL>_0u?h@mOgkzU&+jBF2CfIC{~IYfK*Zm3_g^vSt5t_+*wj#sgvCShZNud z1K7xb9Hit-m1S10maji~1q!zmx%H8cVH-nyX_;VkRE3A4vGEIW21w$s$V2foZ|Zny zQ@@U!aMq<zBm-+$<edKZqoh-(J~D05N-c?as?rkqjZ&?djhC~24C|(Bo*c7ZPf5vW zA;W&2uX|xqp+##ffASoQu9B<!9*G61X>#<L*U4()>(w*y#Xl}M=A$@Q_GsA%)~Zli zhp``8Y8&}v^a5}V4l>AehNoqsWW=zK=%d%4D_M1#$+&qamwcdH;LkSfhw2AbVaM&; z3szytQWpx)`T3Aj=EYxyRyz1yo+qQfejnC$$#VICSM-n?oikuEL8WlD9O`!5_utB` zH{B>V-f**AcRlVm-7GiVcq4u{=<i1OtM|KE9(?#2DJX)HnuL>NDmv&<F3``xIq!5z zjb1gHGPrh$?9;WGS}TT<v*nP}uR|O3Qmd@sLhBOrC2u@>vswy=VA<7br@duf5%&o- zMWq!F_}J_7ttYOBqSCAi(;Dm|Q*)3X7N5~FoPv(YSScqz#0D3C5@scC?n;E#b!bh1 zftsRl!|5bieFUx^hRU*>Inug8wtO>jvMP5r)P@t=c9iD7aXuOxqcH(&LJFSzz3A7W z(xO(fp5`1*sw;!P{Zac|wbCI70Ek7`%7ky;QtL<VY!HgnlRb_+Um$LVm-Y>D#I4{h zyt0oggCZ+hx<p=i^bToU7kj1-84cVj<cp7AktX$<%KcA$q9<{)JyI!5{?J-axvK4u z{V9Kmb$|r?*Bisxjz}luYWY;zwRsklkDw8jme)V<s#y!O=22H#|G1VF&Xaw6><ncr ztwz(O|E<r%LK#5NKdr&uZiU#Nj1r6@s^QS0aR?ak(L0b~J6D{D7yH$U1#<EU$H~CA zN9ucon5c44>0tXHJ;V{o8OCh9!0AUDBhUg8t|rS!gAWwf^gS5;81{9<d$Rihu>K_+ z#RKqxM+NIxmdkV;=#-rtfxM)F_O9~%&vUgGVR=NC1y|xE@iAY%W(P#!J&~H#QASN( zZ12Z%?2nvZD23SHQd!0<iZN+6S_md^J1_^d<41jaHE->c@<pN3e~r<xlr~hz1;Z(1 ze0h0qIktPYcZRc1)@K0V=T3esWG4HwvJhZp;7aE|t$()|CIDts7E-2Jj`r7tSe4g& zRq*{d=GB)4C}F#ZQwzNK{?>On@n+isMD1NPj{*0+c-m@?xEs%{MXp&}j6KB`;{!<% zFeHDyag@i0DlRZ*m9r;a{a;la>%8i>Zob4+aX*sy^~*Zuj}WvL5}y-5`K88#l$m_z z`tJij26xh;@d{Kij+ea!9*&3eS1gnH^XB0lNxV_d_!(y@!=8L1Y)5v10&+*L-GH`$ z0|5sD4s5#|*t7x?FJFEC^6jj{inX$4#Y|~izm~M#=|EYuimFAMLVBYP+$v@D!g123 z4wj0+lI*2VI4R|Dgun>LpKzARZ=>FnTHH)atsm2*ahts)r_ikMRH4S492MZ7H-256 zGj*giO;44U?e>(P=Pj2)lt;_I7?<GU1li)%IdbvoN9$y*Tkj)eaVgbr0Kst#2gXne zO`kAA_S$_HNltGlPrdcEo+zscIGANx#T68zOdEDvD4)69#Rf#6oRd#Y&pe)khdA@3 z$kD@a2u+t=pn!yeis71sSI<Y~7QE%O9%NiRisgB!ys!$M#ESABx%Dzhf%WMr=UglK zu&OFoz(@pTPOPFpW=$I_-C8ukVHL1Yee)aeht9{jOv+1_$s-TmA`R;`k|vFJl_?9j zJf7uq;AnRpziPhCTu`j>73rXm%bh+^cI(tpPCKi=EGnSV75ss<W&W~xa^^`VNXK3F zlV9iK<YJ;j(B6d-Wd6;R=S6d%8eK9;IyT6ZCardtX)FAt)s#Lch6xXRS+Vd(X;%ja za=1qF()(XQ5w0=Hj(CB<Z^pRKq+Sv&fgp>p+Rbj&M`jl)R^Tb?f^cnUN|d#BaMJs8 z_go4q-xN9Kw992_F?fqOJ0J&X%L*lD<~Z3E)@z|~ZMox_4{%a1N(BHtJsOOwSi4-F zf8;i4+MtmnXLgVu<}8u5RQ4gAE^D`v0CjT?hXPC*E%)6sK<>V401gAWNA9@?zq{{| zd+)v*Kl<;rFotj9clSN_%9GCy!XY%Agju=1LXVH0gv9TPA|lvw_=`a%m&_R{wb8D* zOf{6;Se_aDv$kDYPm=*q&mcd3_*ihoX-BI9(z$He>#%;Z68S08tVOjFg%YkDr}duL zr#tG0OJ1|&gn!;FFgiuul*?BizbZZV+*jtn!kGE2Ij|=1P%WpmnUIqCK!;9-&|{$f zbz+TBl?X36C%aTYw#Okf-(dNcS|cNCRjEYKz-s^G`}IV7d*HRIbf#xJV2BrwKIHS~ z?@+~}!xG*UY-jLO&PsoJZ+I~|K1|$u)wz-m#T@q6l-dn<k}-4h^pk=qsjNL1HZ^l) z-&a|&QXanJCdhAV8T#!6Sp&4$P6Xj!fBJ@`C)dIj5O3-SCADrreQ6yj3PhX}X8su; zjB3=pet0r2P|*tPl{eGIexyn>J!B`jjSQbSSFQVW+XpB^Z30{-b4GoHW&QY&0OeXJ zrHKq4^DC5Tkhk)sa(=&a<eyg#P-{plkH9zWAOZS;fygTz#2J}cRh3*~9-WUvXpWa> z-W`j!O)0S+m4q>kb|G5RR-#@R$4ISj@`9ljuh_5vlt)EK8TyGsd+em|G;Tj|>1~gB zA5*+sfI%E%;QQ0JT?oZ1w=+qS<R<v&u?n~#D^f+!002M$Nkl<Zp7lkLR1n3=SICX9 zeotZh45dqtz0QyVH1<kxbM7w_q<6O-u$&*M$|Itr?HX!KwqMpo0+x#E_Ik;mI$27V zE!|$x5AY5+5O5&iz!q^JP(W@G`-02?2LcWR90)k@CpoZb1tcd}I@2O_KCF~6pFNM| zy~(osA?HdV);u$wlOINNs=~e6o_pv9wXWOsz%!wkf$gJd@%-5m(m_E`Ss?db+s`}w z7S@lE+H%B6SKCr;LgGwS;Q}xwO;lO1oE14!rFB*YEJ0GF<xV~1t_L5GFNO}2p`Uyv zciwTc?Ad)M-JdOtJt|W(8_T)<Z<fKId@5fJ|5BcQ;t@If)Z?(97nDsnLG_qZu!kjz zQ9CoGlVup1ESebDGkx|<pDARRK#A74^)Ixb8uR4`(xY2<S*Qv~&8aXot!B6U29tn& zC~*(xpvGEohRbZf{NN>9vX06931^%mue|bx(l+S%XXKLe&yvjakS-<W>DG-q>?-#^ z`m}ug)z|XLM<2<6+i#IRy>@|O2ug~&ZRO2(zEQ=APc!ePK-f54K8AMZbQB5$&^mwG zMCq~fPSUp@PH{$kQ?+1L4orztps|ec1e}iDd*4H48kC;CNU%<=OeE78GSib4jH%*- zH+yD;!ksweCCP+kWB0vIlx5fp(4QEq0+P$Zu|)pW$8G{I(qy-NPnIP(S{gg*X*x30 z%0~$}$@<A#&oiFE!pMa)<-p@EmQ_R__^6VZ6L=3B!w64MK#u%ukkrN`J_*X+qfYEA z&kuTCzWL@Gd3Der`PaqgOP!1etRJb=%#;Rgc9FXtcuc-RU3~cIXL9=;1LUB+_rQL3 z5y`0CT%LV>xGHdTvJYi}(wo2!Wy(e`q#jaCtCBe15_z}Lj2ny~H2!?KU?OGv@9qfI zL{v;r4Fo>Hx_I2M7tQ)H9Fa_H7cgca6vX7E0%a}Oa{toR3$a|Zk*0Ow=5o#5FL}#$ zx!D5C1iXqhvS`XU=~yQdZ5Dg!!Akm#A!95aCj(z{+TW$io`=hF&tg;e%u_xj&`$z3 z>VBV26+<i?IBWms<t0AK2s~3}m*>us4zz&$iThiw?+mUkO@p_p6#6JlUKl;(p@y;5 zP%^<NFe?_#mn%;{(s&uEEA96<UY6rSi}lGUkqm|6t#J7?*<+`cs&sPUdUEBzAJY?~ zsqfV^`q6}C{5eN3>a@ROnOt_AFOT1Qt8{A9MLxjR0?^lk2OxwU7Wf~Fu9k0yy(>*y zwU>JydQr-`R2unx3Y7zd$K?1U3$z^8o&MP7tex72i~@P`?yJz|`N685G--F3EMH4| zXR?oi#Sb))z_OLn|LA>n`8Ac*ZF(M!Q?l{F0@l&FlZQ(qe0Ul3@i?t7Ee|<2=Tr&J z#Q5nczVOgGpQX}*F;+H5PCo89dFq`p2qWH9K=K`C^zlLa5_n8W3VIobXIgM6V9mi? zz5^U6H~BtYo%^%w)EFxT@ZJqYTFZYw`p)*$MN-NkbMYF@UnqxnYli+EmXhel4(WHJ zDe7s;80R&XUoZMqc58usOOY-V&W0uFAX%g6<jJG>h*2-QvrNfdhW9pPQ5BQqFmO@7 zVe4bLJ>P><u(#*h3vdrO5O82iIS?oyx0HiH{(u7k2LcWR9QZRF*t7!Dn-9@~gHyy< z`4YM2jDw)y%akL}zD4qAb%^i^o#3E&SizMR&5_-A?jX(E_LLc`N>rhUBygCTak7O; zj6kVSS};#~wP_|iYmk;rp-8seaR1v_O2)~Z9aX@jG(Cv{3YYek!(u8{x=PMCf{Gh% z@bC1n6&@afgX%Dug4Ig|%M~L@5`je<Ei02!Y9kyQ?ehq3RR-Y@0a%fA+x1{sv=SDb zD1uY|nssDYg^U^YzU<Pqhs?vq>ztU9i~e*|6-?DAl<8F&Lq1@cd3oMU>D08YT8(kJ zWdw@Ga1th*pbaP8f;QZ_k0E$KYd-QKM8yr4BhoS^f`bxpXvVE~J*sr8o;Qw%O=UTq zt)7EA0SCC`%=uMX)T=M2o^!e6AuBEX42D19#-l1!V9ECPgK&7n9x`vyDqWU~X{~WZ z6&J=Mmdz<Ie=35!P}xH6!5=GMEjL|oJS=^(<bY!@lT{EDRkkQ|kq3JQM)McT{=0ON zMoqiR^o0d#DW!HvD1w$e#YjsjtH_@vd$&o4Op`}EV4}VrqCvS(*`^YZ<$H{xS80Pn zqoN>3x?<^eI(VNN;ejiVJMf=!Nm<0Pw-QN)6&4SzV7>6})eF;xl4|3CjQVo%b$3Dm zV5%ntUnM2>xGi6mAy(h?a^KCD2VCwc71N|+&jV$_S}fHi4NL|_5!H(^9F{a?)Q6_P zC0}Z_lh4M_Rmxe{tV)%JXrYY#>@~^emI|;ojnwHWbC*-uR4UVd{!Z%GtuOBnpCl!U z0&~IQS(Q61s|KA%r>`s{<mC%zLIGJ%6_B*ptgcf&F)=+vnLqfc(qccSy#y?C*Q}T# zZL(|O02;^>4k$YCq<=x7gjl3C<rMlA?2CBag~wqpKlA}94dkSL*TI_2Kx!YOZ4vPQ zj3a(<y4M?PgNi{|nO8=O<mrd+m-MtcGUTf<dVm+{*QVmpqn4MFC*KTtRWef>$<xma zmJ+l(_GKyyKJ9=@$!A+5546(Z;U7U+81_3Xo+l?Ag2Q;whq+L;oN&%<cq?#ULv5u< zXgx{E%9+v;eSa<TEUAG!{@O@wx}_!a<k-Xak;9HSS&ER_6x=LeGmbbZABd;XXnldI z<UljR%b|cg_E>r5z41UF)X}mXX<3s>g$F~yY^J!xXjP`;qu<X^=-YmlSrW<GRVL3_ z3b?-N5xp8%$8r}<A1%$Oe8m2bp-2lE^u;)}`ewbb`-<{|Awm{S94<|eP7l*bZ6%ZD ztw6DrvUu)9Y1FW>JoM5xnva&X{OHBJUQg`tA`#2&*B>Y#x8J%8Fb_BoaA3<h5GWwG zoQDB~fCB*s0uBTm_~RVdqyo|`PcY};3<R^B;+1n{XDoXSCuK^f-TxsAmKECmDVPp% zsclK&V!7zd6QpVLF7nw|KVf+=l}P?l&N5jrZ;njBhR@^2jgUA0`<PCuXwkx@uRKBY z+5t}^eu9i0H%S&O&$Fd_oQ87Q7-mtNbj6^MSTy4Y*{NkyJ#aylJy1-9BDK_dtwG}! z^3L0DNx#!iR3!-a&5Cf(FrG|G#T@peJN}F-WNz+i+aC@1C8~b@I14wFgOh0}AiwxP zc7X-t0$M=g4}sp5Uhu3M&ZgqHGCB94EYFwwZo5X6UOa_24CRf3MW@4ZL;m*J?*RGo z^I_7WF_!g$b}A-lIp)-QCS5Y?wvgvud0z@k&4Ndjym35ONcHftEK%$~G+*}Z)=5t3 z_b*w26KQD~WL8NYB%K`tf65S)Pb-(smD5i+R=V$bq%2saY74|+qN@ZNj|iI+cTWZ3 z141bIS}rAdQ)HJG4M102Y1`u%nYI)MmoN`Sg>qW7R4zOBRB7B4dpUkJL6@mhK}p3Z zm+3E?{fkT(GX`=tR^EDbpwxl#(3H7U+(H3)(|t1The<Nwhw(CJ$x2oD_-rxm;0h}+ zo}T^W{kN$_DlHwutOM?4ic@8|mt@agy=3UnPo-^(X0WitsmZD!=ER?;;wIyC<T~=$ zbFaxN)CD;~>H&Bip9XEq7h{Oxt?e^bAeWwWke&|hLJj2~r(Q1k5HhN7>^lWz8SNSE z___P8(gSE{b=soyezK^TDrY)V*E0{5AS-fyla5UqLb;nH>CN}T)(>Se8f~j{+h%g@ zeNWkver8n7oLNi9(NcIdaPa`LJz70M0hu#P+QS0!+n=VY{8hJ<D%_}wGi8;A;X?T8 zVA(ij%sY|>nMt977E5I#sZHhjJ0F(Z6{}TDrvCDSoZI&}$x6+X^o+W4$Ni7XGVGyg z$~D5FQjYLFm<GA}S1%juLHDc0-e|PAeDr~PrB$<?<m<0sNvI!-xXp#C_f3fXX3X}6 zk4D3Xz9U(++sGpW-_}%Wtq9oG1u`-7;?DAvxx^SDei~RCmlVyHUY*-P8Oy`UvgJM~ zG^_d<t$fW&3&;T%pDyX#0w670-X1z#mMvQ@cU*C?wC%E|jQth+#lo`h4{=5Lpwei( z)4mK=m3$(N<yeA!+_5t7y|KUn1n5UIO0iO5bdeUzU9Bs5W4k{rmj`YDJ^aW9OY27M zj*yi_D2031;!pcYR7)j3{*4&=l4K(t50%Mo*h3Z+mBCWdYM*7>Az?*QwralY*R3=9 zt2D`|(@AD5DU_MBCd+|)?IvfReV(i=K_5#x)Do2$i83zsZ;uSx&Rw8@+|Da7KtJF> zz=18|K%ju!BK8HD0}ccn2sjXM;7@X3(+WrcRmC5)H!&!d=KT7dG{oLo*{yoZ7bC{W z71!P((`L_;Re7sq+T@AyuX9e9J@z?VMo*f-Ihal+O)tPDvCHMeqYjeHv@~hix|K9< z-9lQnY%Q%?w3IgRx5BSQiw@GXVIxe8YRS!aKdO5(s&bHu1<vbq#!AJ{8X5oX5IJDa z-qNH|BS}fCEgg2=9m<Y>%8yfL09R}<y?lXO2xVx;R?Q_XIZ0Z#=_Gp{aJ0Pm77j)L ztWts`JSamriL6;icoj10iw|J|*<EtCKmn=KSn!_4qq;N{li#x9<?`@-w@441u$`Ha zE_LfSk{-PdlH2ZkTGryI(^y4`j2b>z4(QcG8r9B_TA8(^GbZ1so_nQCos+AytLg)= zz<~s}?o&d<M!Zlim*vTz7qEm6<#I1eY86;#oP4Vygjzug1EMN$vM_Criu0Gr(=WYc z7PMUEhdSVXe@sLS?8mF+(*TX*bD7Nl?Q3b03A&qimmy<k$PHIrCsSt4m6dq~G98ED zTy{}k*?rIb<r~Oh5x`WIL*0O^<+`6=o}6>+K~gUj`-rw`BQ09Cly<Elhq$+F(L$QH z>MSi<b&_U~t0X89uejv_RpS5|bv}Nq7oN@>UAtPIeCQtO-nENlX4aOhx=p0VZhOm3 zcifGWk3k!hHb0E|Mh@Dmk2I)LTQbr!WM?R)Pw#uS{5Es0TJBL6sVX9DMO1m{J!`4k z>P0b*Bgdyo?6LaLP5q^I8tFVlMva@MY7)dKjqDGUMp!_O9QvxXYT5)m?;?-C{DE1i zsz#iO6+*)mA2zrQd-$jC%ieqT!oH==BrUVPbnU*EJpR=4QiQ!Kl~YLWpOs_Eeil@N z4)BQ)uas1}<=6wVE%t!??#C%A>lV8CtHRL>)nKL!Q<%JHJ4Y#K^KU(JD=eL%P=Zps zRi_>@=)+HB|Gj%l!v+nY=+2O4O<PINU3<%!{jQLorp{Iz%Gj0&M1KTGUh;0(!?Q`Z zPAcyqo|~NzEKk23{)K!oY%~sbAynES@)TAo5fdCAkTHftJQaP|mtV-p@joe67Qr5Z z`Taj8)_{1ZDy%gO`+$}#k-o<tE%mbMNbkQLBGYlAG`bviH~z)@PylQBVtjzO_$=w% zsRKSzU@MBIJIOJBKSyTGU4rtdyz{nVK-NFv;x+FnAbnYml`q5|kjKh%?~PV&TOVkg zSE9(kKk7gimAg_|D1%>lL>kr2lJ=c;llO;=ML2+=LsMGFKQw_DTF<m!zLIXOTT0`G z?d9qlAJX?H_oUSQA8E<R>SI>CAEr$DMh@7&58k;=BpL6|jvaf+%{Sd8MQgZ40;E#m zn-poikXQ|4eeD=7P(bb&^%zhQa3J8opW{HFfc$fO3vvY<2sjXMAmG53aUjI(Shl-C zSBX&A);Sj|cA-$zef-LQ-D&4t?e;(QTKCBt54fd^7rVzFeZal;>YMJEV^47xpM9F^ z^0&QQI628BA#+ki42E}MR}o$d+odwMc1?wgRwUyYc49~qiiKT7R}DuUCN)?Qmg-<8 z<#3{{ORbgZQd2nfuEZ2PjQB7N$DFIEtZ)Dc+rOAAFDr9pNM8Xs$!V!BIR)pQ;xC2q zm8A{}JH%JG(y~gIlA7)!h)+ra5I8K^23+2aeC&s%;WcxKDVR~ihq(S%-QvC+Ki)OU zOhs8l%$$;4og$?I8Mwea;wnSnMJxh?$1;!~b!BA{S603jE6qWBYAR?;cCf@lDdI5O z1h2r$(lYP?b&-|^9^iNauGLn$k&a-&UszG14Dx{p@mEcUyaW~vC%KAfsY?SMMpwD3 z45zpXz)CSzxJnmuTm?_;SVRo`#!Oc6Vco+D77loOJhFO0depnFuSaYMFhZ`(4S)AF zck&tiUGHQ1xpxP@=*kx@bWc3_kQ?~Io9^gij&|ptf05h0&z>fS$d?qWKv@wNgPCL4 zt#zeq3S4<K6KqRnp^z=Tfp?HYV9CYm&{BY=3Kz+u940%aBu<c0OU!4bAFz?W9CEm} zv>eq0nNCi1>EJcC2|#_Z{wiIxJPJ8PT{y^eYMM(*MqMB+9qWfO9fC|-J<wcNqY_H9 z=WXjsd`Sa)3UUX2&=4yta>XSe0CZ-gq0NPu4!jNVTw<$Jt^kE{#jPzv{{Wt+r>7|l z<pa3HZi#J@ZP>U3IYWJvfro7Gk@R$zOnHy6?*Oln+aWFUR6?-PThuJ?h&Jn!xG8k! zmgmlMd+yfDz4pcTu20XdprU$?;^w!1`pF$ucNiYBN4ug>iMy`f>F(**K5?b4jyv$E z<K2ftUUuo_=<~`-T@><}3>jjZcaTrg9g%XCp$OU@>xHoCtSy;O12%C{+~V=}<cC2i ziuQ^~Frt#wDnFu%dkFT{<{>qddBmfhDAJYKjevEX9L@wz=mn53%(ep;W2X*>9v*P5 zrU{2opnr4NRs#JK+F0dU7cFzHG#YZr8R-C@<dTsnNwbLdFCoCv_Z9jGd^mIE<&YQj zf8i9gx6}-WZ4#_qfuJyo*P_Yz%{ZTa0an_Fvy$MCq2DBzrDCZ&`K12th`v|3f1bR* z;t*5b7)z8GB4z@#nbIs8%094<^pJt2Zp~Ws^GVpSB$DDX@q#1TEQ12W%_AK8E~pD# z>00#rUi(NzV^V$~oQCqTN<0H51tV68cL>^LX(?qXj6RM$qD?*fBESkIfs0tojUtj* z8N>s|r<Lfx$Z{6Fy}KbjI=BuO^mjX5cJ=m7N`QaBfq(-62mUYz@-OV`qCbw0=Sx53 zELZFL+vCrF#FKZ%F|K0fw0M?`^DcFnms}Np4m<$|0uBTm2sjXMz~{gw6_A{FP<J39 zOl)JT+#UbA*4;JmQ+NF%FS<LgJlUl{A;t+1=VP%jCZL+ZCPon|wm1RB1TqxD%#lh8 zE}F&!2J25T&q2KIn1{@qU}83?6MH;zK82f3a&!WQC&m-JPJWmMe>ze3CWDw^VbVz@ zCKPp;d~)JSN97WIoU$<wb21;ZVWU0`srd;N6(}J$cEp$NlFP4iUqb;|KO>DLD=vx| zQ85(Z*_0!qj7MVd2}hpb?kQ-%ONTm8#Sh|rr47?3f~JDc6pxJXV+hydp%%|@KTZQS ze^C&qNoY<uEw!CE2?mp0;)oiH#FDk%SaD%vI`tAr5=Fuol&Yq*tWrQ44tnLJ7a5_4 zVD-|cij4cOy~h3f@ekaUciiU&+}7Wvt1OiwZ4$~&Rept)FCL95P>>(UL=54SDXhgO zO3DNB1V%(I6_a=s440}(L5dJDsKg!HY<k>DQ0I^yI^v1MtaD35KfFc+XeAy<g8+kK ziV)^z5=#c<8DZ(w;{7KL-li{9II%4$N1=bhGut6}LYknr09obWffo-MhCvm#$V5Ey zL79eqT9L+A8k+1V%cw9xDk}c8QqX5GmKtlSgUDO<CoDr1xKOkZszEZ20zi#8t1n7~ z(Xo7SuIt^ir+fR$5w2H{>M9_KAC+$r!x2CwK^tk_5-7C_+#$UWbR&P6;i91??(!RN za1Y*d1zS86Lf`<~PlRoYsykKdsf=O2QI$jTgpOB*=|Awk31>9=35-_uA9SoDn9r$P z6F%D|4z$un!ZNf()$E}^SJf40WVNAxKnueUe1oD=>xUTtmr6W^jZoiN8$mPz41a11 z@#Fgh?*V?;;6L=52t(?KN(9mqJ{6YWF|+6+<c`UpqE>aG7Hj<#lUK+2c(6ZX!NyNM z5g0=7Zan$aOWZN1U*^s}=|H8KeTIrOGt()(hPMT5>Pooi>-f$CJ$y6L@uLkLKYXyS zjj1-67=Z`i1No*YnU3WX40voG*YKd(p*Tfe4I}RqCh{SUQpr9#9D@QE9|J28M|lH# z;XrMe^@<NCeB1%t)cXgxhI{Sj8tr%B4nR#nLcoE50|5vA7zY9c<R9Z#kUHQ%z=41R z0S9V^1DjMpa&|?fN{o}I!a45Hy$^IFrbpddUk!7|@82Cqc5qUN2`FbIm}y3JQq8F~ zl_^w~*#w!&AWmRRdFD-$m_=txoEWJGrBzLBG{}#~#D`Nx#;Y;|c{yagV|%7SyRG}g zb~?6gI~{gx+qP}nHo9Zmwr$&XcIJGKd91nD`c^;SuB!VQW7IkH3z*9p`@{fbQZ*2> zb~<U<{35dWc7$|UzbtWX=gn&;Cs~}v>A6@B58%;+z$};A8roLr;6VTNf$scr-rJw8 z`G=ey6~iVrBt&KR?}D+EZ*gITWl;djTL*b#1U*t-L`GRSpgQ6i%0KfF3$McVXgE;? zmb^g;#V#TTc{sVpNdZ<#3J9t!uP1CdEj63r7xr8*M5Diu04TCbt4sR3XRh~#-N^2_ z5T6}6{u%^|i8#2)dyV_=bd%n{k5YqB<SRxHzcy|XBabE=Mv_!iL_uGZL8rH72awbE zD+m!#4w|7+q54pKlRQlrB<VwD)Mefff$;_pQw1aPf-NQXV23-7=7+8C3&iVk{QfoZ zi?^13<~u~8V!$OK#S&2<ofam9bhR9oQWd6!{u)A6s#3S91nyHd7vx!Ed<WGKt2gTw z`HMBw4;F5@fcZ4w&yhb6@t1mH+VS6N^g=)?T6L!DK%B41V9A)dI4Nz%c)p&bKQKKG zol~UA$AQO%N6<LE(01y^nm5A*vFn5XrjmP*VN={XACKHZ1%kjR-)2vLs$(TkU1Eze z2!C}54^!IgaRr$9cm5|_vb+*m!6OmMpl&AMU6sXQiFciLovji#9IJND2lyIx&-ycv z(Bv;>fsd{+sRoyhI=n3zic~Pa^?r$;5y@*=9WaX;S+WUurt!RtilMih4^n1_WvvHe z&Uq-BK;9mP=X$|ar1tKQr=qiNeCxzgL`wQ5AN+bUf@2skr{|B|&XhO`={>MLU1dFT zzU;-vD4ix@-oQ^q**Jw{qIP4#Qm+I0nP{KBlx!4dANnYmKKmqYOqP`SWMzDxJ<9Ht z#!an>hKAVkKcdx&%zx`x^ARvJ@EkS$4uE|tc=6T&v1lcZt0SpCd^ZCc*?m@ys=e7) zz}#62`jCy(_@XSS+GkQga=un@sgMb700{U{2jPTb0YlPmgj!WrojrrtoSjCLZVK4q z!y@&c-mgZ|MV2Ex9#R1M&Foo7J@izqSzG`oakxfo%?t6p2g1)rGw9}3ijn3>k-|M~ zd*Yb+Rn+9tJ(Y97#Zp-~Zuu`ysnfp{aV8uc&DP#Q{4nwCt>YB|cn_@KR0hg_S!g6- zM<P5QaZdkF8YMG_xdDJKCqeWRy2YZvDlaW=Wk$YdqLi64TZ0iWK~&mN*NLj>)o-G{ z=Eo7-uLYl?r{)rgS;YRSGNsh4l?zO##ELbdsy5`tVaZ(dyC+jE5l!YB1^2v<1UNtE zj+Jri!-w>f&%}{%twp^An%FJkPDvh!<k8J02$5?M6qcP7G@mKQ^(_wnTd6964g5WV zl5XC}TEw83&h*W#+44D1OVGoT-TW=KN^*X!2GS6m0-X>i1KD{joa1*VzFTQb%dEYH zG#nTzGN@DzLoL_ca@=0gw$VstM0uVjl@9BgXTybGp@h`Yal(RdaH$x|yk+{s%x!Pz zfnf#G`iICU!6@H#k63Sje*G#Df|qfPef%g30^OJ<nf&gp{|hDJ)uI-WDGl>}nhs%a zqzX7k1?$%d%q#Ff5$g#omod;|M5cy%;pJ^VOe*lZ)rwX;pL9_#--3Wntq5Qpnty4g z;3`{ix}~1J4P~9eFNbS$lU{MSJv*a60H;V1c9e@qe^c-GcL*faPz3^k7X{ZpKO%=k zftmd>vERy_FC5g6mCScQXu~>V&dGTKC>(NFf8iJSH0_zT?6INt3YJESNVXuDbK(RX zagfFfQ7tj@u_((19uJ25KAK=4{YDugfZst^G&1|54=L$}GS3)9^v{DOY>ybmWdyZv z`$Z{KfKM<E@^WQ?`GTxcmU5Ii>~;i3QB&P|zD;n)1Boq9Rucbimh9>4hb`7&6iKeh zhja&nzLLwCP@})ZBg*VSi!1cd%3*}ztM$F@;V<r4{U}Ks#1WW_vC@cgGI@R^lECQy zd82Zf4e}F&SuYp#M!El-%nyhm=UCWpM<=GUx-N>jw&v<8y)21!sTGeAI=Qf5ytVxO z<+kz-gU}Kg+t}tEgEbnYZEsH6)cEI4W$j;UWK3fV*TBm(<G$$2%XfgOW~Ml-6yftP zCD^`G8lh;slR_m&t#L-$;FTy~M4-@BCF54jF0a~5ZquqvX5092o0*YD%jF?f%e9Hc z%EV&#@o{Qx9UXs7ko}sbOO1cG$oi{M{={2wO&Dl$hBltIJ{N@}<g5Vw%Dl?BK##?k za*v;8V_;+ycp0=>+%C`OV6lzX&ubTL1itlX3@*g?*xnoxeH(GGgjhfc^Nr(L=qde8 z15_>HKsiw*iWqSKGl2~1s}WIYdPAKx@DPS94NGJy2i^#Bd6skra=ampy+PCvFht34 z@OTF6goMdS3YUvr8R^cZE?MX(PCHw+j^%2e|HR*>`%}WpC8e--O3yODptnW{M3#D4 z$0D8mJrwU>Dmy7_UHlgQEV^*8*WU<x;f$3;n5hE~J}Quq$_Yqgfn<jVn`(yd1NySe z7r5e<*@#a>xI8CN%g+Jp+QULqPTTOFqpV@JS)tnC=F(6Y2mT2CW;LnM&$9~-%Ju@m zbj_f8`oc+&_63t0u!r@p)~_s<QwaXkh3WcT^*nwer5Vb7Y@>#Vt$B#cqXQ6MY3pP4 z<+&p{X}+0G5hc5_TrJvxw60(x8q+=a-w$*05v$}U4qk_>XSuiHMcUm<AZ}*5tUOa@ zDxEK+m?U=@D%ML)n5Ndbuj+ZK6ke>m6;|i;1_Bz^81kUCJ37gK;w_#CL4`}R5giM^ z14*?p9Msaf=V-^X&#SucpxKQENW6N)T`E2Cj&wZl)t5V5sC0_pYU$}tiDgmVneJwY zGavJ^Oqj-!%aYahOtNQ3j0PfQHK@-F|2i~KAqDQJl}k;#{>+azLUbvzjcJQ8>*)Ew z#BP6k3c<?3kr{H}8kS{{j6Rvo^BSphJNxVvVKg?NV#8i<y-d1C^nBg9GdU(eS*6Sk z@ONgxr;oCa*uhBNkphPu1PRXq@iSJILt79iQR6v?Gdl^!Kqg7zd1gcfgxPg*?3eNF zR6GE}mDtH-<JI_P1Rzop@aDWVu%88y7kXj3Nd?p7_;ejsu3h!klo$YyhtI)}iNRP% ztf&gF?H7FekE~waogSAlpl@xVhelj=>b>O76jrU5hEEOb`lS#G>l?`VrV#J|AHV&s zxaMkR!MfEM_sL;PF{|l|=L*{!{d>d4ZB<Ray`5&=OJ1N64>s#Ptk5J-fa!MHOFW2M zz4iTGaV;O(;VZnn)%w$)tkGL|W5v?@$bjWNUKj_fVq%J*YMk@w7Zt(Rr@U8K?v(aM zoN@Bb3R<D8V(i0#+<cs4e-)pHy(j#Z+fG3|#{)f2ClJRALm3-KtKX&CjU{(Rz`KM` zp-GtD*I$@i-ej7XE{_;jV6U2Yim&-TJ9v9dWWrkf8~I*Wvyl&sR>u8|0DDmfj&5*) z@G&-E+P=WAcg-IGiC6Y(nJ`Jyg}y?e<8d>i;CHjpDphKZ`f{V$(#%XDV1_V$v5og` z)JLc2xBTu6irX_N;C%36CYB(x<8XKt@{KOW+~>nM!g8&n(^7+9@!hN{<DYPM&cNjq zOXcDq{A8+iIENDA`!@8)3b%tywI`LmPyW7s7v<|PBM-LUWAdz7YbLK{2sWcbk!G9I zKWeqswZlX7Hdc<Gutk52owvvJksV~+`1H6dv+0E6C3l0P=jGx!v>-RJaNqu8b(MXB z(V?0C`f4yQDjZiwD?p{io||Io`L&5<Gje)ZI<W~8j3h0Ho}LKos-Ua1UGVyQ=j(os z!PULHJKulL4?bHjUp)K7PL^M$rwpr-zjwFFT6u~}{e5(M5im~}2ONw|UKR9*aN!SP zF6%}gYRM7_grYLN16Vn|p2<O?L=D+<(d0ez1~oHbH~MR-El$|)+&nae2pD?+5RO6J zII{+Z$|R8=8Tok;63&yH=>C2$NZWwA5FA~>ALW91gO8rGq|t^&39&68T=;;b*b<Ap zwpa-CAOd0>0?bYh8pv!ePCd^ELSj*whO+#<01$^5Qlv@{VYKPu4-Yq}C!->PpaQU~ zkb4=&*iOc!&Bu?-tG)XeheiNTA3RJAPdG_f8I@S5@#c@q<tMTB0h*J=*t#o@kArtH zZ4|NWyiytljCQt&u<X@>Ar{u28~$h%wCdD%Rz_9G1RbkfBi=6K#}faWsKI&$$W=x_ zZrbA*1~*oeHo$q5WuLbzP`#_sV8w&7IGi5qE<UNuK!H#IZ^WSF2GsEL%&-LGEL%If zD+&_SVSwqz);+yD1gAIDjUq`#fWi3SPSdFaOD5fa_-SEX%70>q8&TYc6K8G^B%zAq z8~J%#@Vd>;qNKcsEL1Hin!cV<RbfvnPz87MKv%3iq%ki}jI5Cf)D{i|So#D4l@gTF zE2YP2O!|fW>cc7|xz|YN?ZgW*Lk0v$GqKipehW@@iI`5OrT6!xg~y(>_@Vf4cr`>k z`x81vuPUAe_|-V{sG1niDHJdQb7V8~L9>Y{7^7|+M;e4Gp2neBBSh~3Np_YVUUr^5 zUHN&MJh@K~SWN}Z46N2)M}ne=2nV&kIygHfm^Th{qwbQ!vk)LRvVu(dB-FG+sx(m^ zc^^{np$09j&_*uG5E>#V_o}geNcesQ5&eR?xYi0iMTXxxv-s~dPNvF4V@hqN%-jF8 z3~c`^ttHGH>YzPuGo4zeOs%cp5fW)+WHoIB+VV{aFAzgH*74U)lYR{G2|Jl%Al6zH z!Me^w-#mUxBcAt+n;>CkYA+tojUL_RtU|Ug&CeR{W|bTX?wqqSSGl19r<(@huP6W* z53}H3Cxi?21<6NF2H)=`r;J!IbE3%$YJ%51G3i?0!uy+Ah!{2N2Vt#W>V9$yK$@IK zkC-%JhGb7$n$!LaF>o{d9xD}!T<>y<0z}yw{+hZIx8S&*wG4b1lt(XS!WWO7gNV{X zLzrT(BW;En#&cYxgnu=rOdSji7;vhP%Q1<zASQ%Ki(EcvQXy;MIph}Y`ELt0+y^L7 zJ(;55o*(x+jc$JqtEhT|%v(7dX9lRKh{(H5dKB_j_sDzgSl%b6O&1H?*!m_>cY(Mu zQeK?U-&dR_Gq-SuJw{g9l=fL`&WGf99Uz_@IZZy%hM5ZNAN>d$A0I5PE87V6)>tO_ z|May&?X{4(OfSiQ8k}~%`E@>J2LOB1wY=||tWv*aC$D152ccmiv}V`-S}wEz4XynZ zyF`!2z<ox(82!Fn{y`jUwzX-yoR)+p(P<`}^ND`OVDZ93sBx)Q3o<WvNo%^^^uD)l zx@?142VaKLhC5r@N~aige?vX43+7)~zibt4h1g>A=wBt~riOy>&ueeCIhS#aTn%4m zb{zE+Oh<lvt;d|Q9pp)&NX1-tzS}%MJ|}KqUwfTo80`!Ek`i^>5nS}^$N#IQXbkmr zz7*mT0VQ#>$F7v((m~}OamU5!^&8-7iQvc<c6J1e(t1%$%Fia^-6%NZu8+t*fRO7N z^e_1m;)S)lwXf_KLf*$R_yjOTgvvTsT)lc*2y;xoAlfuz64zrKct`*<^!ULLj37tD zIfl`B9&}2}Pwp!go5!ob^KjEuYo5&cf|?Cg&?0Q7pZvxRQ~4&zDWp6!ob3`>;Dc{h zbmwJZV4R3Z85Cq{2u8P=hwrwT6#3q>;X4CSZW7&J4EtC(<k5p=M?R5}w2)``!O0$S zOS1R3y|D)UB$vKdSSShv_>95?eeN{trCPtTa~)sVBHd&uehZfS1^>AA)km<+)y5zl zcYA(hk$wQsAr~$EPeqgKBR0G9Po3p_;#IQm$oaUYL2GyisV{Pbgp>;N7wFCd7OhU> z3qnNkFmuppn&4t`nj9k>?o9&(xKc5zH2!{>+Z6fHyEZR#`4eZ9iN{lv63L42<XB^Y z*B6pfqZSSul8Ehq$1WxFIS0v{6YR4^Nbp`Rui;|5L$(yQF98i#0I^w@qo68}+W6i6 zMb#$>Kjg{-*0XcA@ojO4A8*p~A5nE9ESWLh#ztKg1MR9r(|1ouncl6hvkDW25Qg`9 z`zCTra5GI*2TN?L%BUF%DYaKj=Ab~d^Z@dO`Tkg0woy|8#(gkO9yhE3J&w0V5&OGx z{8~9I6)Q8&FhjI)(Lw(CdaI99m=Mm>l_%O{RfR=QC2kfNW30g4LxJ?8vNuhinnQBy zl-}t+H#xpEhgpUD!aC`NbcBW>n994M*D%IB{L5cW&NgHC=h~x!b^dM`hGG0>rH6T3 z<(9r3z3f4?aOO!oN9<n-q(NuP(Dk;hzzK3}R|XAvhiX{-+x8wM)55`zkU@`yd`J&C zma67M+LVuO1}&<^_w(diAYevB>`id|hcS;jDq06*(YS}A(rIU0k0+P#oO!W7h1O-X z$xt1s@{Pg4!Bs6S7-6AWl^W`F)a7U@^E-+RZ)8+!PFcX|yLhi%JV~kh`xJYLiZvo@ zO@enS0|6b4$!r^I)KT6W_YS7*$2q>Ut!SOv-}Nz$&djZY=}!?mjPr@hR{9r=z|X0U zfIDrdUA9BwcQ$d#7u_0<U~IMr%T)a679a0e*MFlpnRlT%n1=g%tRiv}qFNfFv?B4B zBh|HgeabdV7r}I-yyK0Q+e^j8c2<_W<oD<A(XQG2HOe>5&e>&qVF6u%1hzXs?GE_K z9HLPAn&|xlb1NYe4RN+#jltBLH~K=_@+^b6?k~Gl`hiwKeYbs#2;9_P9R#^4KTt{( z=fp2`F8(OoG~oHE8HiHBUeX^kaL*6=;*E0^n9>lHU4yize=ypsWZ~ZdVGj9r#(g`^ zHDk;FxP(9A<RiyV-f-D)<U3OgTQN?H%8|pNrWVv2L+xA+xC{q24U_H{hQR);Onx&1 zsG*j2F+*8Y9~b9neb9m+)LuG8uYH>kj4yW)+&pnGLQmIRB&U-l<WUh7lphQHnxF^L z5XRtW`+7}i+$lyN{?{^`K3xbwU%eWM8vQ`U*Iy-L3^Kc$(*fyUabvK1dz?l2_qPlt zg0n#2ulhR3k}s;d>J-^bz@+=DE2EIvZF?b%g!rvie!_drGHgK@+o$>(Me;-(!HZG$ zH{jyL=`Zw7G_IcxYRs_Z3F>=>zHC>lFfs>~M{XQ)0$;((FXV#5Ge-r+gEnUa_E-1x zwR^>euC5>a@b++ZOnOm-Rc@CW%?^hWsu4nL4vvnyx>p6We<fw7ogVAY+sULgTT*B< z_x<25EW`LB9Eqt2{<%%`-_3V?01q@fJ)SSWX9s=$NouaPIyrZ0gwKfT-m`c*kiWVu z-FA7$cMN%d-|f@_hbP~aNMU$`&vERPsVh6)?i$(rsyP(ncrx`;-9y1x={9*(c%E&q zZnsxdZ5^+^xaMlK%-1H|UnQ<XP%78mXr&70<?;N})%B9o$dQZE)RYo0_0JaMl3t!H zl?0LChmI{@eWdu?A`DP1TI9i#MB`LWY(}A^?N9$Y#*Vxg$5@f1!{FNH`STTOsr18N zH7Lf4d@Jbw$-mQC4S#SF&GwM*?h>8N@pUcUiysrUVDRqFrMQ*M#z)%#fnNZHK+eQW zMP1nvCF}Xs#sXdJmM~E@7Bb(lj^geApXcHKt#@PpcWMPu^{YEb|E4Fr_;_L*2yFPL zPG*3)BxNAWb50>%1#<&FU>?*9FzBZC>^~sD)5nXE_RHsUOc!h^@M<$HB#)JGY<H77 z@)Z_>&hu#@v|(dOupL;;Vn_+-Se)D@xzxlvZ2lo6CMAMEvHf*CJ{{&k$sec_vOpPe z{&)OI`6&_Cl>y-himYwzm(%Fe5fNs}wB1}n^HgxlJSEbZ{8a)7TYmXouym>b<gbJd zbJ2D+93f=Xz9EdD__FS$*|+$68jWQIz6k_u+$*^3ph^iIFG^<7GJ1NlUm@9){?RV7 zAxiO`Kh4-+2Se`n-C^?S!u(9GL(^A*uKZ4ir;{7zrMU-d?B$_XV4gw!d-g{Y={Bo( z%1NNM<zW~}@xg7^n*pzq`cUfImp@S3<vL}>)S!N4r+qpKg2F?2oDO+d5#x~a*}~9r zZFWm)@u!kjagTlN@sh+PIT{W0=8NC_|Gdes+(7XSY$j@4H+z=FT41W$doPy*q3P7Z zh-7FFXS%Jmc`U;=E)ikh`Mn{i@4-Ct&{|w|ytksi-1FN{x0_qw<1ELzmLTTLGIyDI z<m%h!5*$=PIq4~BgXeG|Fba9)fzq?G_U7j1XZb98C73oPV|i|4eNK)$UHg|zGARk< zslo`RjEy;DK^|^Uua!Pdl5}tl<Mz70vWtRkE`U*;V1c|oI^%Dl9bt|q9j4*EW?3y3 zd$Z@SVR1ebArQR|Yk-KKd^Fd7l8(#LXL^xAwgX@hBhd_GkXr`uCp{C1D(4n2A`yCw zfPNTth;J^Vr^q*ab}9Vm9lZajW_}>+H2>wcuxYYtA~4#rOk_sealY0<WTx2#SVUyk zG>cWrsK$pRVo?Q|B^P-Do$KKQ{_=Io77qqmW@^!jiXl!$B=5%<b>xPCKXJYbE)Uo- z3L|y9;m~JmESB!#FprV#PD_F6Y|ub-U><?j-i@hJ6D;WAIhPnHpXUidSxoB6)&`aM zqY0ezx8}jlP;iXA2%NVzj#idE%DYGN^lCA6?n+ubSqN|XUnXhpLP4UqBfUs$wXy}* z+si#_92KaSiOGlDG9CvlI1=kM0YA=snPI#J@*x6(5e<%)200ga$;aR=iA$1Vi5?e% z>$N%vyB!p29Jbz=3N(}Zon=(8hB#D;jxW;-2>aV``c=#PTid6H^SreyRjqUXo(Lx$ zxofTEVp;Nd)%HlR-eK6i-foMnb#W%QZw@xIN0MfP9a0kdDIF{Ac=57?<Ky{~^JFHg zbEQVJeKZzZ&z+^3*j|5tX}vUn^}tHMTz#)jx8@!TG+GWpF@kzv)m8p7cAAr9eV{4C zZiNM-3HR#WY$=u|6LJScVwB2tznjiAc(rq*vsrtuj(Og%`+0YW?R|}9hoDK6BX2Jc z7e~gAf<EMMKl7^l+UF2_!?%0AQ&RIGzCri#-R|9PC~#?P39XmNEkE;PU)JXB;?>4l zJzNvSQvaN~pAN;-+qA^EZRwJ`b<^WA0wg=5T?12&Y1lXxPlELNwg)TUTu4CNRM|bb z3Kn`^Br>H93<kYTxm=}PO{BOywrQ<E*>V}S#Y7PA5A1i#=kE91?PY;=)-`pFM7QrA zFKJCs7Nc{5=gutphR!?g!4%J@QEGfn1c^p@ghO(y^z<^5jUN_2)z5PwKTg3J-5#Kb z68aovT)%GinD1mYZpbI93r>!-=lYkzhHgMT!010-ATay|2M#1^9Jh@27o~*LMo%RC zsr~a14vwZ?LcjgbIVlg%te1@zXxw+U=uXGU3Wi;|ekXDQ$9Vh9A4K(+O3BGU^2M&~ zh1e?zED}b>()pVzW803BUF<%r#28-LILi3dNr_<2-kzmYEb2J9{5Qu<sX~H_jE~17 z1HG>w`eT7v;omZ);#d@n56E@uv54KRI5zDtaiwJK22du_oZKu@kMt38H^Y_bgv5kL zrA)|GXgZnl+Z4!CK@(xf7R+z2HKY<~k*&Wa%w_vt;j$NyNr00yQBFKxg=zc_#DePz zrEe%#;WG*RrC;X|4)QU^jgqM}j?tN{j!0_PB(-D6SrO>WWxq3LI=O;lWxJ_~39GN+ zP~-T>o364S`=_BQD07CShIw=J@6Jr5KUX{1-NMGr=0>xf*KVr>FP$o<G1fG|WZtCz zj0)7#IVR5<sR9$us6m4mrJi+@Y>bZ=(3$GTlnZPp1Q*9ipR>!|<{>N2{7k_1gE!^& z?R+EFVDRIGiyY6}CB`iBg~+^7LLY8V9rVo`$FXlP$^mu6pZMHO?W5biCskdq=F8tz zp&Q{4mnHay7yV%In$<vGvA3H#k);>!Q(G)vWo5n^bHRi{s4-B5q3xD7UTfO+<I-0z z{m&sA^|oTbWAI){q)VEA>~r2dPV}A^>Z{vzP3fGypH_bWadW#>io<MGE-KopVV{J@ z)9EoFq2TTG-MIT1E+<!0t$(|@Z%;t9J83AM8V(Whb_;XLXKv*ySGjMhggu)L^qO1Q zrlVi4B%e3N1MPJ*O3tG?zY-0NZFU1%ZA5g!xt}Ir{LTgGsQW7jo&U5Bi&M>q*YxhG zg=DQds6X~#Zv;VXm&3|~87V{7<`FqBgwb!zPj?+neJ(d%jexxGfK)D}EMh{S2&b?s z=_p@i7~2DA|Hsn)FSr3DN6n<Y-kx%5OGzl+X$JmdtTlWyAip~eWb5xT_;uP$&uO0a zui&Tw20Resm_%wJQj0?l=P|Elqf@44?h0}&y+mh{S$#f5L%yQvma=($Rx)s`7(_m5 z7W!Is!8vFMDsEKz<ioUZA^#rZ7V+uM;lC8bToJfe7TX~}{9+da&WC5obZ|@3qvoe+ zOZUR6Mn>s!N-Kh#SwSSN5hN6ZP$+SU`F>$`>Gb1+c%~5qdiOmMY9hhZR1|j3XC{Wz zk~lMdhgJ>p35YcQNhp8-ramrv1AV(JS|ZZt7$ZnY66&Th!`=w+UvX(Iz=4RT#NUYM zkqkg5WF|&`OK%A4Ht3^z2e`ldGe?utA6}-&I=p`0@gFV)H{n4FmqnSiqN!>q?D@RC zqBmoCKH)l?=+j|3|Ni_No3q<XPUU}FNF`RuZO>e{M1Ala>koYQ%(F^G_?JytprGru z)qijN?O4Y(x9d6Q-TBGE^&|ar1FzjhnC3jq!Sv25S#vkyez_&<*SPj(1x+gGYM!y0 zelM14wLJ=r_XLr^L3EqLi2T$ZPpW!58edA1UiV0x<x&w8{B2&`O`;$imrrweQXn1$ zmi?j+><)FZ4C*jjxar()FsYzV2>ToEF)ZQ3*nmBSO}UDJP2b64o8N*U&kw#fuF_{h zoiIWDZ~A-FO&|Obqu;fzq<(D5o4%d?&lC4Nr1e1(5`hZlXc7gmgvEcL@{3q7P=15_ zNg%vO6d6f!&l!H^;puSCx%NK)ey?=ACO))0xPR<^?{vK4e814YYz(bmx~}Ma?&j{8 z&sYUNS-Csq0Op=*w^y(-`pdKYDDqG3nGf?r#`VG?x+&O|sn$Yci7PjDCa13cpgmo8 zbiDd0F>#i1?kqjk_+rMjSU8_&i=>jCVK{0519Rd17bcT_+X1bL2)H+kR*ri?`T-Gv zE$FJ|n$UXd$@f9BqEF6caj-2s-D<0Su+!yFuKR$FG_fn41nyjE_<e*{U+ih5oSv6H z6P|o*#6I`Wd8keO9ri!)gWK%kTKtb4Pq@#C*C0rfPwD4K53cKwRGCe8<{Q2P-kcpa zLOzAAH>-+@HG72+9}eL%Rhr#jzh;Je44+)T3}?9co7hFRt7Ad<;9od)_Wl0X;+qcM ztw=}g)J_nMY(NxlSkTRiiYCYiC5iRVZ=v7DLs`jl9U_uy%1S}VJCHLaY>c#Hn~25# zcsQ|H6p%O&{EQF-Le&noT$CTD{ge>_eBWNk_?a}CzB<H~OO+}8!$Q*N(<Q4p(w6XX z1%r~~J+9l}C+Ya8zgPYGkbSs*_sQg>U^$of^%W8<#BPXZ8nql={F7U)@hG-ZYZoLk zOe7(031jKH_Ay_7L!!h<qt%Ca8d<=+H`?B1P+K}o0B7GK_=!TcpwcU-#o%#4!hkm~ z{L{p@G->5wF}R0Ow5v$VLpa=Xva!HwGUK<R?nS8c{{S4OPP(hvV*J3qDGbp8ad{-n z-1AAQGOa8-zm_tNqV)f|mkEIS+)6$sk}?L;ym><RlW%2qYw*pTIir{4*Ax^d(<Uo4 zVSh18S!rd_yxB0iu+xzs@T|a|`vaNvfhhI5qvlJmycL0J*XodDA^5SdX|<9sY;yvT zJJAHPu;<aAt+a?y$YoOJ8f{Wkb<SwO?hVXAme_~M16(;c9%_;=)@yZ4CSL`i(Iz4R z{%Y%V)xtx?;)$X7iR)*|wUk*_B=Py{heB303UyYbqbQ)|!#t!1;Y*W6ZiE+qqwV+c zoheeW{lfUepB~C97En3ST%dQ%h-jGVNo?(ElG@9lhp?|yE^41l^1sHX0OB(^UB1~o zYfryU7knFdz6T~TY#4W!+k01h(}#S8p3I2YTviE&{jWOWCq8cCC!(XbyD(VAyVPpr zOQzGPl*fJv@#l%~`CCuFnBao68;ap396j?=mAm5ffKxOcwEu!Bx@}ax^ft=|+wbV~ ze1(D*GFquJb~x^|K5$bCP^$E;rqN~+s-n|gp=gcEknFWhgqaDP-2F_?z##_Fy{0Q9 zr%#HZ@1o81URgh3{Rf&UKbdut?{vy3Y}5KpX?4dWBk?Qm7s)%iZyG#8%;(L1q(2j| zak}JA8dtXQzE%!*?sD+vDjlc2Tj|63bB>aYU2Ml<dFDay)P52Q#`0D*MIeG7&oJM1 z^8eZy|Jf@&-RU5R0n%w~`RPyo9fiMuKwU@fK?^s&5D)B)1nqs!D_x6~+vyxO;U2Bt zhzirEq)6A19egemC|8GAT7(Ed$kHijus%M4C=i9?U`NFxQ^6#cM#AKC#hqR#!=w4& zZs>nWa9uvO+=|ovTi!7_eYLPPU%kVFf`m>IfPA84M5@!Dr=wJDEK{o1fjZYq!~(=k zz`q(5lZsm%{84AI&Va?dZDsMOD1Y!She&EsNI;O#qN+d{ib|&u>nkW$&O}qFlpwvx z(nRYKpbL+UNtncL7H@@C9c6X4{H^bYb#P3<Q*zFLpoV$`h%+&V9PEozJG#bsX{Cwz zXrd~D4}r-X8k3|lycrpBFl5*JYwDA}GKr&jf-+}(8Ua`5dTld0C7zNn2rWMEd7X;2 z%vxhnR7<jIZbyZ3tQ^xc=+Q1bMHTz6{+9DH)>TQx&|qq8r8ak5I{GT{{i+>~FDn8; z93wAL8k2>rCt!&x%+j8V;RZi{(G<u%{OtZYK_nYV*eDzG0v5o;ODSO@`zea{(V&}i zau>kka~&;11ql$@oX5)2Aa!#$dqzuV^lqBSX4Re=Xg`c^$}V<!WST4b!`#|6r946a zW*9YAl6+ruoY`MA#tK)o#M)S7kZf6OTu-LZ01$}u#qcxoG**S}3B`y(9=+YIyL<0@ zKAHF*7688SWsaf(Dw_EhP?~5C2IW^U^+-Rh<|u3O__~wk`%9qPx3nqFQ3)v!9p=iv z=#MO=KPIx6bRq%0<gi4(Mf{)ar{CM7nOP<K^sOF*ru7FLOGsW7i_CXQ*Fbj?!zw1P zlan$Nb(=aJZtSLoIy3A~Hfc~Ww=T%>2|u+o%fFW@(g+VDdhYN?9V^B8J6zMj(06w% zIcaV9-^5{78_vT(kN#2J`=-$%uvQHVF6WPq=vQ|r#k|%$bL(k2t?;=YY(W@_xrKD_ znMJ{R6~o~fCPBpIW+zioA4w&WuXU638vigpgYS#}e2#@p`+!@@(N8`AZ60sQsf2ZF z0c<DT%EO+IxyLYvlsu<%o(Jkkt*K7ap1w9GM(<_^u8n?JqT{&i3xG&#ryD?=I8fhg zuz7B3#`WAV5I%$#&W(M~|5^C^LO^u<t|l&-H|Qxu6!;^L?uFDt&!EVpeaiIG8T-S| zWi66!C(jGzih$bxf$jr9HLBcE2EaaB|G}0%%yFW{cl7b%Ie0jEIR(M?7rarkU&S@y za*g9QvnD_nM~<x47%~~H3_CnX)pdMstvh&st|^e%@=c@+LC1{@@ly*meLN(Rn1GK= zx^5G`-pd^l5DYq3>=5j{TY|?paXQ+eyUbh??E)zuyyyDFNd$kAuzw(2t<!V629LnO z*``FOrh@oE^#D?GK{rtW$6vgj2P^T2=5At!lnQl0mpPg2>;RdahBWi&`Bwl5?G@x4 zCk=tFn--l|lco>e*Lnp@QvWT8)Y%Z0XU*FKh%8ZmjO4d#sAPn%{^|Q$xdIScF}4a_ z%Cg6EBHndOyvrp%7`_>I07uCISFxQ%yufTRb+#&8Jr}{}NG`WtW+SD*e$D>w-Bi0_ z@$)%vu}3ttnJ#>fkR-EKpTC5Lpn(O^-{DT7O2vT4TyMa^pu6Lr+`K7RaW=bkAR-x@ z6}nu#3}Y!h_n%@0<$vlWaUfKAv^9sdL$h)A{!P8+sp_kBhMx-V54BAWY{g+x+IN8) zo{GOl@#A3dK{p)s7VuWvS(TbDHem9KYgjCAYm}<Bkgd7p0%`@}*5kJMdB8FY|MCwJ z1nl5QqWLhZY+-PS;(1>=pS~%<P--!#xda{^>s$~&;(MtK!Jblz+yigChn~KaJ0B0V zmD~75x1;-zTK`1YLwq^KG}x+!w!mfvM3cKS8t8T4A+nGbF<X5n6`QHmLmp2F>z8v= zUbm%F?*^fX$Ov7dth{DdoZLF@H)2HgzohGLkp2Z`$xOsWJZ6lx9nLd0L4f!jcmnc> zd+io*w{sg{q++&crLR1cnyxs>1Ya$I{jw;Zw>@azenBYU*`<U!x|>feWy*s$<7_ob z;Mu(W%^HPFa21VB-O|=5XrZ75s5Vn8F8T6Ht~H#IP`Xo(u2h>!yo<f)1J|R}b&gl< z@cMsE&CT^~^GR?TjOmhPYt>{hZrz5MGecDGzk`2o9ZFq58R&a4y&ydf#FCK<!HehW zd=~92vX6!azDs;<sM++DOz(FN7C{QUW&J<b)z7cpw+p;p8?K3@XZG_H9709Nh$)A$ zX~{{}sqQH={lh}qg4K&YHl%8bNS!5nKljw7gFc8jdens$TFi7hywD20jQXn0q;N*~ zY(7_wt!-!7?_b&Ndf_GnxXmW!3Kx{PTgSg>Rom*|znrQ>iDW6{Qy}Lhor^6_ZV^8{ z_E0zLkNr$mh(ku4PDm$Hu+5yv%eYyUwog|@0`Igc4NEIjQrC-zf5V>_jWRne=Ln@e zmZ$JZg62&LnWdBrik+(FM$aEwE?e^8G2riqM)KHk9LS}dy6*@N7LH#z+zkW^VVm#5 zxj`dbz($=rITsI~C&dRgo+&FoMyA8CLT%A46my>@HMM=K(5k<BY&x(^jYSw}bh^U` zEpb%#jgwp_`d&SMJQ-Ps1~Z1v8JQGV8=p1Ub}jIIzL{G&w3+PKqeYtQtBGo@z^#L< zCqAcxwVY5^ohM?s3nga}o1bu_!@YYV7_9SUCBn~3eH|2TM>>S(9y1&wAK#-VK$x$t zVldBKGty#y(krG;=T=o_@|O^kPb{)H$*`~2C{vv;W2(BvHtw>Zh`Fd_(0zEc9Dz${ zcg$V3eV$-SPdb@vD0EzHHvQp$*`dAM>df`wbB-q~&Z{JjmQu|yF)1qa)T`+G<iF%7 zF=~%TN0tePTSk+vn&&C5TJ$ED4RlCCdu`LET)W*`XCcsa*Y4m1C5*;YQPAq;EN+s# zZ$zBBbT=ihaO6Yp^YqmbkbOJu%leL5-r{%>(PnsFI7#%_j&^S7r{3=&cgtm8(#2SJ z{Wj$k@bPrNiXQiD!dk59&wR)jQ$2sjmmR{mj53me?fRF+@MQVNXy4mIAd{^^(oEqV zt-R9G1-H>@rF%uSgPyZV`UtztuvUdm9$=Qyz0}p(8X`*O*5~=J&hN-|RAwZgRZo#} z^JU(OHkH2lXi`-;RQ6+O6nUS28$><byv?Lnm^OD@_8y(4)R633Z@Rvoc{a5NtYN%i z0aaQ?W@+KUX|e(S<@q05RU-IJu9K0835PoYy(-!;vN!-IcSILkObu(u;5wh*Ew(Es z0i$%=i%IER*Eh6k%YFvZQ0wa_GAwQwczy8yAB=Q4YF^&3Jj^ymzUc=alkd@S@&Ff* zy~iEywstr{HmM<a8`YJWjWf>J&lb>5&M0HNrqG9wM)KMKd_w!oJQ;p^KjFhsq|xk_ zbU8FFOsF=!HMh<x8ExxtCs$rPJSZwAf_|~nC)UWvp^V0docHyUw$A*Fs0CVCMJlHJ zD3P-W<?#n%3X}NSe}FuSA;nQ(KOmNfHa{VVWI#aRY@6vmf<}{?a_4)FOWW~`d^Vr0 zf7N;iwg6~A03L`4(pp5I*M>TPoC(G0G{Dw*F6tF4Bd)+)oQ)Xwv{jJ&zK=H<R*`1} zxUTQD_w|meu-{Cui=gkt7&M;U=|#kSZcoM{lN;+a+SztS#Io6(D5pgW@TAb^q!(Mt z>e>~-W!CpwT970q_S6mc+I@vnY?Ue2_rd5AlCtg-!)|Or9g>Kk3O1U@Q_b`F^xynX zUkn4*7$qJjEvzc+u*5@??$+K5@AEYXK{OHtn{TC%o6k2SyHBj<_l_fR;wP#f4wsFE zL6Q&O9<TM|0CStwy#7nQvFAF&_%0BE{4glIeJSQBBUhcR=iplYTG1ml7E)?O==1fA zx+0m`GrI1qD}?XgpH_<_L}{Ag-GD?Uj|cuMy~cAtguMHMu11Yg1tePU{(X-JDbza$ z4<!Dj2h01KqdSBdzQWWV{L5u#G){cj8G1nq{<Julr%+EeTZe%$zr_9PAbk#MTsL!l zj1iO&L$vv0`gwA|UIX0M9Ovc0pY7dx7<^CB=gYiC?1s7hSxT8B8NKaS{A0gnzB)NE zn@_J1Y>h4h-c9$1q{ZY#+VT;NPLw4Z$1_IBQg1e`NVEwEIY#kqT<*;fspHR}IM9Ar z5ffIElaA@Fc|DAWLwYr6{I?P=T8PoQLk4Zz@|WSr^h5#&z~#@Bc<^S-++dZX1t5?- zsR^&AN$Lc#OHNL&Do2-c0gM2XIvo^=OgTCoMMWv`I=&TMtu~4+S8wNKHd!zB6Xs_O zxjt??U1(k~(|LVFL`TmGg(94kOkz8qmq>f)J>x}(N7rvzbxtGk#1V5IKggaNUf8N* zw%NX0bQbChUGmyBn79L^>D~DNbK_9|m(uXjz0>3BTz=BaNc{E7n3tR-xBX2O^&$Z^ zfG0q~0;0;@(rQ1vN4u`1bl@bkU-UH77Jl&nR0G!CK)~J(Rf}R?$%S{P5atN7RPV6f zb6RIJbpIs3KO-T-B0{cYP#+DmMkZpxmdvZHQ|G*N9l%r~4>L<5Ez9#)=)JSz6-H_1 z%A0?V87e&k+~KbTgY~4$+`<6}m-UemE~|MAnL;TU1~}n14R2Zukg^<ZUT3}2YDU37 zd;K@7`y&k^Sw`>IXniizL2w8uku^|pbMHZZ3|dYJESlQ7`aP%bC)T&8yjbVu@Op3o z1^u}TrH>-dB$h2rvZuiE?*K#Tybq;dad>zLAA;^I&m`m=Ml4sWb{*Ziv@Nx36YU0{ z=Ar#om^>Y}3gOVMtv?_ER40nOqGree`?<4|x2YXPx!Jwdj<S>YvRP_>(D7uPsIou_ zpyF=0hIhF#RT^ttB&Wk>)9bqy@pvK5W@{j&#R#bUL}N+EE#DG`_>aCe0Y#zgI(VOq zDOx#l1krkt>d^TyLeI8Kc-rgd_0?S<J=Bi{EDSM<$2QSW{AIY;WtCt4?hV6v(+|gR z=M7@bY#PPC%>ky;`m4WePis=M96L-5UyH9>kA1JlFeBsG#v1OA-8HK8@>DDqG-QQQ z?p#moK-9ddC1K!z?bf=6OK(KdXResd<6(P<h-rUW<6h!^CKi*%a+I{LpaTdvy@-Va z;v;vE5%!^dkYbkf8`Ma4(!xP9-_1NU$YM|@L3jE)P)}F#raTyY@<P{HebY=zY`%O7 zQYba0$-is%uNe<*hh1KtniE?CP;Qn49s1P0Z;s9z4il>_6u{3ASnA<c+TpD1H0Z?K zv2QA-+|pCrM0MTY7$<Yd#ckWl6GeL@vS>l2!Qq{!*n-NV4iw)G0-N<!1c1CN3}vIG z^mGjgLPYt@_+4OfC6C3Sw%2j)nVrweUNyP|YK}%#MMJ$9hwF?X=VSm5zW^h3HGVXJ zo`-o#>PvStK2*Go#y?^R_`yEi+RfK1RrRJa3v}7-CwI>6KFUEf4eu{69Oq&wJ?@0! zVj328WTeGu^kU%bZ*a8fhJ{mSswl(fS+9;x%T>5-7O$~yD$~nO2g4{VgslB#gD@wF zkxn1R8Q>p**Rx3E4cn604@cbi^KoHnvXCJU>H=I^H`(6*d+OTxhJ*NW1&lZ%hKc>= zQ5B1OqPSrM9du|9m^p?M!$%pQ)It#{^oz!SQzR*^F?aO}k(|zkikr#~?}HRdy=OV5 zBZtNBl{Y)m7fg@G)!~;r9Uab0MTvth5-J{SHj{#6@!Z?rW6vU=-*&sp?Zk-133P~n zP0tphrx%E%7DTvEE4Su$njI`}Hbbj~0lGSrGnb%ER=PouU}}KW?sjR9!F*5ld3=P; zW_`rQeOtnAb6RzXmJa=G{g267t2L38m{dhkF<+0^P%*M@pXKPr!djubMCI?28u`Qr z6q=3Kk-JRrYVu!3Bu(dyWBk(w<8u}u5xWw8dk;EPXV6{$*Jw8BtZ9aL#D~GN5YEI# zJ3Tt<xjQgkwCijI=`SW&TCDs9;;PzAa@PRSoR#WL-K*;JreF)Md!j%&8*nbw?wdgV z>2KWOEMDsY!om3nHH?o$d;l^F_iv$Q`eljU*M~L_*E3h_C(LiHD;6n5{sQ7HH*f+O z($4+c<wq+jeK=X8q~uB_lx7ul_`viNT^hQ5Z8wfT^7{8}_tmsKr#%a+7Z)tN4tBXu z=d%z355UoZnAGbj@sb2t&ievO$91=49`W10AOLqlvFJo}4~^H(9CZDm!v}Cm&?#7q z-s?4d6U)eV{5f{M7p=tbHm!wxa*w@`3yorD$z#Ru4bleh<*T*w>GL<O<0g$VJv>^q ziVm5q$HEem8hSNQauJ=QBJV4z;d5J^n&A}&e;)R47NJOpSIbvTym`f0P$AqkD1ol^ zQzSTWz-rk#<hdp&bS+Ry4lM6KF$A1N@Au}@uYN)dPau-~?NyFwmdzJH0-U53y`AMg z&KjQ>;a%cx9Z(-Pz$l}{xaedwk^F&SZq0Wm?rObV6(!+?5KQXHPZ}+?;TFNihOhr| z6y*Fd!-4c+uzC1fy6U6$q#{~(3G&(j++;=yI-9{I*psh>eA~baUpo$fr{g~bZgPh` z1s%k=G%~TYS$<@8``g(0qCv#1vS3S|q+?f(9%nmi2Paouwt`<YHZp7ug?#!1v!nh8 zj6p}Mv_qBMY|-9G9V!AKNC*FVs!A_3jznD=LTH=^c?okoQfd(u6~(^BnVGofWAvcg zg|bc#Hq_<lxHqj-C<{9p)l}GicgyI9;xUY)p;@i7nkv=c>5+v&|5w1Aa#43|{_pnf zumz#fc^#eApWZBqmW@kzeap9*Z|fEJCaQQ4e;xJ(7uQ+CR4Nk~W|U!i0&2hDmXVK6 zBb8qJZ@CIL5An?P(eR&<Ul1-;^GDCy)%-RqX9t;CdG*7-Mb6colFc~qt{J(de6Lj` zq%oz<`oJ4fe`Z>BW9Q10EzTDPEopGc^AP-;(ssGu|F;Fu^NkJvQ4NT*p;7{!pxAUj z<kHHh2}Mb!gTC>b-+_RkppY|x3aEj-ViFJDK}TivGk+-B3sDZT3&)0zdqI}fUnE`@ zVi4s((c#S_ypldOgsr*_=3r?d{za!|%18rcpfClbAr;@>W>~XB6b%mU53aE;*kwG0 zmb*j|^!!&;VV6O>Uq+5M&&nf^6FnswWjZln`Fr{^L9VnziSr~%7;#4;W~q7zb~aV_ zx)dUB1JREN5IzGbG!BqKI$)i%BNY<gE{Wy;qA3}wnls9au&L;My4CD_C{Fb}5u{*m zs2wqKc^ZEEGxW=k-^h&hIA&hDo_|rn{mvqg4EF~;A};Hu5Rw7bUssR(I59fOWpo12 zZm`c(zp;mAYy7m*cqAZ!BZUhhqOkCiTqIEwn0h<l?L5s`(<r_YdfQJyF_{&A!&H?= z%aRK%0#hx)AhmQjfb#yQD63uT)NSI{qiS*tx>xNelvA_lj=wu<>@tBlB_sgP+F=Uf zoVZ>3*i%BPvB96aRJp8#4&--$6=x$=KOw_iA@t4@ZC;Vw*y~MyMp==Z3Xhk?;UkqQ zNcrxwYLLxn*%gu-KCF>_uyE*dK<iJ{#GP6)BzhX8AJ{0n?fP)Dss<9Oo-D(wpzNw- zP0#NWyXH#_NS_z4j1C0JAxoGS_lc!U-RCr8>WO*`?&9^F6Sww|g~4SvPJcYyChMI? zlgqQJ=x?%F8qQeXmX%CuRmpX?_p1sZUHG>Tp?~YuegqFY11`OO-b7rQU6dsnVELrR zbxz>&D4W9pkGamsXQj(5D|rmF;LzMKck`EHJh2~KFx3?xa0CKaeOsK4My`V4{9aGz z^8AWzvmBQB{CeknLtA?>slYz&h`4bPz#r-1az#o*J~P>Vx|tagE5gLi&7*wT>91WJ z5{)_(d$wM#?s^4BGgx=pPm$*OxNLSF+F*U+a{zFMmhvzQR=KB+x*}*99N1fXdct+K z8@ryrAGt%x7VZ3Y<)aYoGS>T?YGBb2nlD3OR7*bq`5tjAb)c6z8f$BIh1kY|zw|<o zN8W9>>|5t;P#bM)J01Cx6#Cf9P9PZyLroqz;#z$S{)gu4i1~7%xS6c9q(8wekgY8A zP+G@*c}sIDRA`Lt#Pmw(GtZR0(%#ze)BT!JI&@KY+EjP(R(E>Xkp$r@J<C}=ZRE}2 zjOOTpud`I277m)OWb@s(&maI}CV(v`KBs8D8>7O#Myq#m5&JYns5HtPl&slGqZ+0A z1C0rSgeM9@e;D2@6XI$f{Vlo{S*~F3Sfp!y-;mh(;s)Vik`LrT{DjhyJLz`smM@*% zv(3e`Hq>UV4Z@w9W%g}0nE33${_}1=yzN{MQry8(>%sifVL_m?@{i`GCsCi7eUJVS z$+tkKm`j7f&Or!Io$I)RwOVsk*NQF2+gxkgy>u^Gs@K&2QFVWG-mmSSUULY)B1jn^ zTxB7!e&TL-Izlx?5(ofT{-Pf=bbyj54UVBgegLpoakK-E55<ilN3mYcWVCV|cwr0T zQPzjJJ}S}$<|m~d6Hc&(BGgS-0B@;x4lxyspCMZ5JSL)q;8H#+H`i}fBOiD+VUcOH zXYx;}P$eczyao%xn-C7Cn=$(-*6FC*<t$2UB>>`PK0G=NKA<&hU+i(wl<TxqS9-DD z9CHT+e;2b~6JsVa3|yEjduchxx>VN1UAaGz$r{OxeaZ3tWfJ|-KNN3KI)9hb58u)s zhb3okEV@I>M#|G+@MI@-%_2Szc&$Lu7cLyaZ2X~es|VyuP>|o*C>tK<ri^a2LA}+A z&s{_$%PC&6BNU<!*>51J|3NsL)w<xT!LCjQi(4TQy}HuYhe5EA@j7$2GP=eFF?Wd! zZS#!#&%A+*Me|ej*`7N$5CL}*B8v%jtsksaY6Uxa)$q8x-RjiHBBZO2oJT0uegEj1 zNz&E&LuU#UFhKoTMyhwK{Eyo~fwKOZJnm9+{TqbRoacH+K9btSz0v`ulygoMzgM@M z>(xrxH5^XC=hllrV(oooWAL~NTMCqW0X}Bz>`7fMRL@v&eWT%URhv`4OlFDgSc|-< zT%S4p5X#+->qa+(A4#d29?p`uy5fbsuOC!*f1%`Envuf=SoCQvx${RH-<#d|6W4d? zCVFu?DI*O3!*ay~YBocU`uA;osm?rcDM}pL8{yD+ZmM_r^5S2}@ezZ!x1De{<++yr zTZ~su?KIQ7lU!$+>-xUa+3fK~k91&-Ivr}b=&%Maby6*myT?*I7P-U0d>BE1fxf%H zPW98$D>eJBkObEfH{7Dj^Jac^C;uQMOB~48to-iVWrYYpo`{AwlM31=i=$5Wc<NK9 zzd+A?^cL3K!AmnD+B?LX=}+Qic2ZSt=VKk4^;bqo{>jweqg{}7Sj;Fcdp=m8|BtJ) zV2T4!mi6N99^4&*1b25?2=4BL#oZyeFYX@PgS##P0t9z=CpfvhTlK2$Ie%hmrn~3s z$B@$Jmvyq)72cNlCWG6ZMm}mPdiqPjNJjxEu$^FQ?c6X5{z(U#phJx)@u05Oh**1W zOwN(^K{(ba<)7$NIci<o-_P^Harb3{f_4_jq9la|75E}8*giWAJB;0YQ#Hitv5QP! zPmU+UMUVcTuhyrI$LQU5Abeqg&wppo=c|Dt-;K8`KCPQOd_n#FOR()UA;!w)ej?6o z#Z#1;v01!}OPQ>F$iVga``m_3?Oih>>1}|gjuZZTq@L%ZoZit+f_=frXwGk_?hd<e z8v`qatJyrP>lRo&590KejbUMYXu=@5-bb%gkF$9+du!+}OTW}L3!a`;EH=iA>iCy$ zi9H(+Fv6dFB+N}*gq#m}pGg*C414|S(pG@d<P<i?e%vE3u=k1amRM6cB88%?xuw${ z7uCjn9Rj)cAL!JiMu{ysEJ6GWVaKH7>l$x?v&7cGJ*e*69uFUZ;3@^dDFiVe{_U6h z|FDbx5s>JtwziY~`<u<&Qyq_qz^Sa`8KC@l=cWF<%hpbJyWRf;C@K!~g_W4-;`?@p zb;8I;1s$&YYGtZGKll0Y&9V$NG&Hc40|0GFiH`RLI#MagxLx@(ypE+kCbk;4c<Ka< zCIH$?Db#j*lLz=YXqNgr7i)=BOGvMZ=_6{ex4reD+r{(RAMb>Jv!yB6!JV*%oqm}f z$1}>>?_FqM5boZ#BR*6CIaJhgyAHmNQ{GCGxP3Z%#BqEEc8ql<=E$51`CI_0{xNkz z>!R?sP8EiU15c_o{yM7K^{EoOd9LYsX$Gbvuq_$Pqz8Nnd@LQIl%!YHC_ew>8h$_j z`~F!3Ft)$iYR`Gx*Z*9yUksJFhwY87*FJY10(a}av6h*Y<)$@FvR)T=$~$1iop4$< zNZ%k(64_$Gfj-(0kZ7$X<WVnNxLz-_5aR8N8gy3?6uVEtFItimc{?P32+DIs<oL7{ zu*8-dy~EzuIY}t&YLRWEUzWO|_D}2W;&6S6j(bg${*7-T=&T5;oylf3J;DZC>Fc7? zvu<b4Rdual=fv}$<nT@V{fU<QrAorlohuMNMroreT!l6a_3Rw?*^J8hN_%$vvmbb* zbbu)qZFbH#2WgMxft>ng6H2UTz36rAqa=V%0fStiWHcc^tdy{3dkpb%yZzO?x_z$@ z5m_x*)YqX6-Rs!aalJO%Nk9(eBLdG7Zr&bCT81-a6X|<mXL8Z?+;7e0$RxrFyNo`Y zyn7#G>fiFMM@X-Ag;n4-@}8$wU>fN#ky<IPcvAEnl}Q%9zE;3jEqmQa_BO3+oMnYC z;xoieiQLimAug-#8&Pg!Y9E3O=EYH*`vK3{Qla%!-a;<1_G#03-n?pgZGCf2i#pVp z6#3%#?#R)SD*b8Cpy}gQN@?W7`D~Q==&`JM&q7l})WSVlDuO8b#b!}VdR?DvID@d8 z2{~B*s8o29q>AxzK=Nu9NhzN14FY8-MkDuY1R=Vz*d$5&U0~gx<vHIJcX?{pYzp3d zb{AHVJV=NLzv!d6qhN8NqV!zw;rCI77tJsR`qZOuEenC->%{f6Y48`B)>W1`#P!NA ziuj{^LI!hCgsY?6uof|mt>#ISFqZIQw!22HGWknIUzpPV?9f7N(|))&>kT(%^~xE( z*)DRF_oWJdb4LyGdMbizF$kZir>p+4uK=C}?mPcpH%;<VxWeK@k#8TGV#Gj3FIvKA zFX^i+*1x|-xS0JYMxL3jxA(WPsUQ>d&`h6vlOdk(mT~SN&E7uegPza{xHFZquCeaJ z2AzW41s+yy1+L=WpT{4Oe2#_~$6)2skDH>X>u*)u?9GJwrjn?eJ*Rt~hr`(K+6jD4 zpB-P1g1;fE7KWH(zd-Ht5o>ecy+|El88&+L#1mcj^ax&&8nz%2x0@0X9S#P~8OQQ? ze2eE%Lgh}rg$>#*rgoFNOmDV}%XSPEK9D_xp&%7`ocgb1RA1UK6mo=-HIQ~#05J;p zoPq`P1C<u2Qa3d+a1L8Wg2F3RBryp0upP=A_An7q4}`54X0-mB(a++DT%ZyGkI%`$ z#}qU+zo!tLp%k-ipjq_sUX%qFOdYG&x+I<yMA(K62&aHM0m2_yS%8DKu|DI>MRJNE zl>fR;`sh|l(-m0ef^PaZN-`%P>d5rh3E)h`Nbfc&OMQ1->wHw0IL8wQfpVX^o}N${ z##o5C?ae9p0!jVzMoC|9|D`Q+d?r+o*S@Mu*}czq@ZOEeumA9SvFv@Pw5UC<n!-(p zLn)jkPhSJfs+QgFE^o>l<8l;jNA4K;VvKFIT>LzH**vsC+<|`QerQnS`GUj3C%NyY zx|>8+<H$2`$b&cg%<dPj!=G>vXz`-mWPqswoLkB@z{;%nOrFg?AUmm2(0#VFy@nkN zz!WWLsJZnrkk3KTYOd(d3=B9saB}`6$qrM0C=e2iY47j|g|rvSsK4MPN3m+2RVEc~ zdn>bO|F&}P_BZ<eW9Bea5ogcbT`nlN9#&Ql(z6YB<ShH(qg)2IxkW`t98XM5&Pd<l z+oLf=lv6cC!2vBq(x*9i?<l7Q@~c<pe}3~X-vs!#kNWz&I>a`~V<J(J>xe!I_d4GG z9$rg>5i^RdG74-Ji2u^{@Z6wzM_m!oqCBVJ{?HmHaCGkJ_CeD90^1jYvoeS7<r$!< zsxVT8@|t;5>NYtAg|pt_46!?3+M)FSF<0gDs5BWkxe)#ZYfv?JhE<e(Rw3Ng{-SHx zeXV);Q!wKcY>}f<Uxu&Q<+P9gAJEC+VIA6KfPv?QXo)&(_0?qb#2mRJ&A+4~6f!Dh zVvNUAg~d8qjQMEGAJ8<pg_QJzUj%NdYmG%z>#B^zFGKeaGWohfuilI9MNT>4JD;5l zUQ*&oIdxvppXCOr01QP2e)Ly{vW*%hrXu@u3H2nyI))FocBGtFFiK7D=$%1=onQ4G zn=k-sMXu#iryqsIZnI%7D@}*l9i|WJ&mkhs#ON425d%PSmo9SfB*xR*XX_GpgtXbx z(+6F>z<*)bUXM;+uVP@gcQIi%U0K(?*;j39YE!>CdQ5jee~8(iqTIhcIZ^eQ%dcb{ zralpj8=3O5@Scw4aP%MN>j!34Nr#{ut?nLf8^VgFV2mOCb>fR?VK(BkJou{R6D#s( zhpa}c<p=3Uq<+rskMnPGUf+{gzhJ?iPqN*$dS7ZzkhIaZF9J%MMogA*=`l)13cv}{ z?Nam>TjLXqL{k+HGt|C!HM}o2r}QhwkagpQbR%!|)i&GEmJHvMgL4F3Gm<@&f#P#I zx*>bJPw9u0?DbRTL$?0izSjO-gD5^sbmJ?q*4_1&OEjJ@TiJ!ys^Ldmsv@N=CtqfX zbW(mNwJ|7$u#`DECW1bJsrzMokfNdxC7(u@tF3-lkFVUt``&fp5$mGHOvf0<PWzbz z#5>!W<*1PJN-=9z{750Fo!G7-uNyl2uUyQ>1y##}ZV^f%iZ#4V@3dwSGdqZWn3J{* z?h670bJ8#MNj19eC%?8s(+2J2_Cf|aXvAI<zl&bL9#>dwi^#zyyg?g6|JG_;dr$r# z{X!EmWD~u_tZqiZAbq8xGN+-Pqs5y@OI!;sL9*Rp=VB#`qA*T81Rdi43lc*@pP+?; z@;ZoY<`Q@9P{g%;qP!M^45~`RlO}OmLgc^oK!a5P6=ugeB4mgcg^Sn4?4V(n+Si{? zbMcH~Y_cl_2$sJ_@&i4Jq-4X!`W||58Pyb@A1<h9V_-uMl)_{v(C+4;7$7QGzm(G6 zg*VgJeI+dx8l`v0OLiudQk{D<S(&w7S?ap4I}G$YqtEmjr1I?Mz9Jj_kt>_ZV@qS& zPZ3Kb-<lE|k>@;4xxR6@!~z*ZMlENx%}eF-#E|ar=WHZ(l)*o_5cXHS?P&w|PfPb< zJmtuEPh`bCDVU&ztfVC>!8NN7koUoD(5PWtsbA(!GRk{a8WX}oZIV{5G5ADTZz7TM zQZ5Y$r)wF)ge^)kBXWfz(wRalLZ`R!zGZK_+K|FsZA?@uYZRc%Ac}Z{((Ezxb7$HE zmc6+q$FBcv-(`$w-;;zvigHQtRhO>S7ZcIT2>K0X=6%-UWGRW$X41mjcFV+eu{Le* zK~hmsh%tf3o>6}w)UtnvcDBIEl$jX<n__|_=wsmXQ8=n9@)pbOyGJ%2ZWaQw@SNkv zexI2dq;mRdQ?p#5sGY2o&1rlP*sJy2^)F(+TK(%y1N!g0<;A8ncU%*<cQW_uX%Sl8 zRo;DA$XrMFUf|n#&Work)`JC?3#mvV4y|)K0qy3kFzDjnZg?Z9H(!j8q)RpbJ~z`m zmn<M+JL6j|yqZzGWfrldUaM3-x_IC-5Ituq^}^pc4Zek0M_@rqI4Zf=t;;go6eonr zVK<0eaKIR}p-Hry9kDp=8^~rVQh0KXal%t=Ky}&83shKaHx%*eO;2Uax$NSe8s7e@ z0IZ(O;!sq{5u$R%uTJbMFljG8egoasDDTyFelneu?S8SGh|kxCtX_7r(^IGX#=RMP z!w{uv+w|yMTfD=+)7+c-I~2<D4}lc2AN%`fpR&OoBayIA4hc#^V)lg%mF3M|^1A+l zqMT;5+sPl*Pm5J_P|L>^g9gcInT$)BM#(rD`${_BS#%oJqP2UKJDR<9ZVC)LXA<6) zYt>Do8n!u)n^Y~AR}4Y+b1F9jx2z>5WOo?U09=Y#V&2D&aI0<b&>n77Ty*NaBEk6e ze9`RvGCHuqhApgLC&DEz_DbVhgd@go2>GbbtD~WyDw)HIQN+}vkwBY6Y)^P%Z|#)m zlz6<N1!}vSk-lqkm}tI!_uiw<3cBjoHCyYFU*^*aV&kX#yI9>NQXH!KQ0D;-V_NzD zzLmaT&%PBV8ll&p>l>S9s;@bVlG3R53IKav-(_w6KgL-4qY5P4Iu)r4gfcO9jW%^& z83~9brIbZiP%@x8L9Z-|gWW?;{_*FBVsMxE7@RZQl>jrXE;_jgl`UIaH#Oe`ECCx` z%MWA6OZ`)9#PgC1`8CjUq$(NwXHoDkr>1N8;TRO-P+BG?nE};&Je>!Hr&+vGx6H=G z@+CVVOIhJ^I_dEo-P_XHFT4=axRdQdeNHZ*#YJ<}>|30w#l%23C~#2EMum`A-DAT4 z42Mx3sqtbIuW@hm3$R|v6lqFBLZH>2bsqwjc&0!!{or8K;vQR0{8c8lG}ftZc3d^M zfh}U=)`%xxVRQTqPb{>gE)%$f6Ry_f{Pr1~S49hoHD`LkAueU6{u=P^67S}JOlrIO zrtJODGKD(ud4c+D#PjC=UYY+JQ~W8x2YAZl<b~6cV8Of>BOJB}V!Kdcm`YTkbn8ss z-9Idi*{?CphunW)rF-+H<tnM3SenN>aEBNzsPYILZn#WE6gg+jERPdTEzjd|Zf0){ zOZ+PRFlQ@c#l55m4~YB^P=jjJD!ttCDh(=Wh7}krFcn<B*pJXWxm-i*wt9t^JnyHE zV2IE;-(67N+i6E|CbCgS#3iZ^illUfqbTOW-<P-^mhab&w84bAj+e+APrUsiPeTS! z!B7BTTEal$0^Oy1cyR6#xtKOY5z!Irx6ApSba%TJe*H)X&_7iYC4G6vg2XlUIy&_r zx2ocmXcF-NiUv7~0kLtI)i*V#K;^`x@84{f&)~k5Rm75E01Dlpkc2(N@Y&zwo$UO| zx!aoxVLNt9Wmo@ly7t>KYE~wpK0Qj>`e++6;-bP46qxM&_Md%PzQDd<qs&*$VsN)l z!xLlVBcbh6kf9_CvbMX?)qPx-iINCV6}e8t1tfrUi8yJ5`GHi_s*t}mf|eTz`ulkY zHGA6#mpqsP1gV(XK1C#JEnhc?x%E6E%M~`?{Y&JF;ekJNC>coP5QOLx#Bl?-_Q%A7 za#484iXF+)?e-NF*?4%NGv5Iv>YK1nUIrWh8m5RZHUOG2WPoG+as6{6dSVhC2M7KB z8-_^oQMKRAfNO54#Q1BY%P%G({sUL<o(JEXBl8D&BT=SuHhERmbY)^5NmH~m(w77X zsqzIllI*A94Lpp2XBHh1h=?Q&2!=UNc*AV&chKOeS*IgMC8H(v?WR+{Xg7=o%s&hw zKo{^AAUWdi2DhAV7G6z2QRKd(;o{*o(Jjx_{La;eZdE0*sVh_4MKX6Wu+X<a)%M9z zdI4osuj5e~8Xwc4)iGii3pMqpT$9cu9e;x@1UYT7?doreuy=~Oj~jU9OuKK)y>;|2 z;l$V3G$;}TFkfPju`g~9_I1AHrwlw@sUK-uwuJ#Gh9F)1w=@_7uy6#>zoG-knTH{o zse+eX(l;L(Wn`&iHZP=*x)4~RBYzjl62!#_>~QdIf4Eq^&gq6lFZkn}cp&sbKSfxs zJ2e!>$M1F(6c(17ddHof%J5b1WU(sdx{>b)VXi+i?7K#z-L6PbYMcBq72J%shULH( z?_P@KsO9xQCXkJMG*3uHx^o>Qv{&!P8`$8m+9_Mx`y_6=&{dhr{8b55{C1l=oM3xw zi`3|NZ^x+BU1;FyuDj5BX27Mf;!eWkPxmVs-4hJMmx;2a0?!AQ1r^6JJd3X8U6b3A ztURS~_m-D7zicTUFP?MoC?D>w8Si1R{6SqB2W<}`0&)wsC}vLg#)i&wM_Lu8OxGe! zvn>D_;o%*76S?}(21&DJf4H#KeiX(+J!&-SKt+V@F7@$sy}SDsU#9IXK^R4IUMdd3 zrrmkzZKC>Y5Z<~}nHHuGbFUl_5=RUl?fnS-Zb4ix?Nqq-sunGt>FG8_)CH&*6=>ra z#z_Mu<3t#^3ZZQbMQX=0JKfPgQ+-A8WK@yCse}ue_+hm$IXx``C}Ig{m;2)9W%W=n z)ZfOoX%DOOl}d#)iH$TbO`pt1p+j^LpIifqjgEd|FKX9fd&2)_dG8w7W=2%9?bj8; zLA4hNtJ`Z;%A(&PpLaH^Zl}pgt3j`t#&w-J+ivd5s9j6Lx&Kqn=qD{drFsvEpdNm; zAX5r`T(ShfwSl?&Y@<PD!^b>T=-$uSyH>+h4QVDBZXAk&bb^#W&2lT!WoY$pakKrV zVy*p(3SFExL}cI@Ah%FI{q%o5#*a{{HX%X~xw^!c!fa$_JZlZIWBK2>6eWQsiBe%? zi4Q(KbjH7o*?EQ6R75^Kf#++1Q&P6k>&+xCIkI9Ujh8Bei^nv&Jr)gJ9FMM*8&{@8 z{C+{HlNjQ-2V?=5OL*HrYz>S16L&S6n2*N-r!Y}*=p{6(7fH(E`aHJZ+p?D5{y{a` zd8T&p`<1Nu9>ygTfSKR3*nB<75{bC*6`N%B<<{Zdhsj-_DbC=<zQv2UY8|lXvHa3+ zPMj@$q$RW9kT)P)@3JytU}t=|{T#O7_4j+izY=pYqfze0CcuqcmxIB5ZkMP>E%)W! zk7nN^wu;iks^A;-!Y^UaA1pMgvv_6V62n8v*~@dRkjm9$6fk!sAlNygRP~R2ZLstY zMbKc@)h?9t7=ol|3hciD&@VJz`Kr+@`I;Yiv|mINcm{xsG-u6S{5Giuo|2Biti{3B z)w=lc_^8!Zf#X4V#>v%&ZHgXbabWsYAv)<B1YNK3snnFwzhk_cN=Y?>7*X(e$@*DB zG^))`be4*^5$*^qK~yReL)ZD^9W}l*(zgo33fhpGIH%-DvM$AFJVvkhZM9(}iCVpO zJqhZ$y?3hz`ATRwF&xM=&saf);F=K@fJQHTcZ>reXs`QvI<KL7E546ZY;9@DLbt)G zoFsfWR*+g383wbr=6W62dC_7Oyn|t1Jv2lkFFy`88%DBugd}yp>?eV1EboTo>p43! zdH5}c_g#<Ln!C(iny?2H=p6o;9{(<`Tl?Kw-0ZZepfIq*51@d%xBrV$-cd0Bj$WvZ z43LLgru?IkPq7A<NXG?pP6m#H0@#Oyh6tI*4WfXP-l(aWQ5IaA!6A0}X$(!hPg*<| zF-g{)o+-ra&|<R}@YLBFNosklo|spHXU`b!Q^+?0&P-aiM$^XcJ4yYnS(GtW{;ZNR zs_BAc0SX&uzg2Dq6)=U*(zk^@wKif|nphql%J0co(i&~rSpdx@*HaCImehU2o?)UQ zEHeWbgTxa@?Cq{N1$TclH>Y-ax!z;)nmYzGmE7cX3i>}`;c#AyGhv$3$_PNq7G(D6 zj^*9Y1|CUyzqg10A5P4Y!FeomBXNoM)*<^T>X(YwU9T*Ijh1qc<2anof1$^}{%maa z+k@BTv@fGMsAW;kUZeZ+Bel;Lj(qnj9p7I|goID6wx=qWySGZ@#&!HTt!aN(6+CfD z9tZ9`O&b{fa)o-?=rCh`9_$!W90|q5ROq{?m>ro7i8G8Go9UUB!?Zywd3u)4ZJX-u zJ%lz}w2X?42RC71eLVS5z#;FYC)YbM8+LGuIADHv1IU3>gyfav06$4+)f*a;le4I3 z6)7DGS&kRl%lDW(xd3BE016HdUmF=*^WWr!7bIWPUy!A4$fZ8<SsBPeq`G?+3Tu>f z-DLtceyaUQr6n9m5Qnu^Cx@l3QRTZL<;Uww$I@u{mKye1WB>v+IJ0%#|9O=h2xEZ@ zZ`oOnYWgoV9I@}^Hk5c1%kOrD9*Hh0u*~1q039G-BqrFe+3SEY6U~y_fT%=8D90&m zImBAKl>hsX5~W(d+X#DB8kqnU92RCVE|tIB>738q-WJZ?Qv*c>iY>NmCl{%pg{-8B zjz5Sx1$_xbXm1E`^vy$!IjJ;OP5Z9XA34(s1e3$*@P9uY`3ZV`G+l0VtxJ{kFQF?l z{i~Rj1N)fYDMsYoXsEA~aUkP0;kA{I1?d3UOhHi~Wm#E|Hw@aB`md4!t4Clsce5!U z`RvZuvd&Alo7unq*YC_0@^0S*!ewgJN^^RZpj-O@LuU}lNet#m4kH`vL<NPo7Y}1z zkr(`{0m$t^%e(aSwh?6i6Suu1I5wLPc+t_F2P^pm3Fn@a2npeZ)fwBHL85#u8@zGZ zU?IA?kXsHEP|gc*4C;D0xCO$x1~G<d5Z+5Z3$~u8{#wOQeEF*?p&Mf2EJ61b+71Wv zZxWc9RS#d~Mei9si;1=KE=k+SM?wLA42&Zi4|&e#g`l<ZfbIS;Q42?Jy$&|JfZ;So zv{?+9To@T=&#p&<n{<$VWkAB5bXw|DH4Aj%VJLJxbi&`t8B;dKg;59XoptI&TkzCW zk=0<YsJOIx@?TnFv!7DjKEC+YJa^r(VY?CFk#<5ra*E<H{Wn&_<MZsj$qD7oDM)j4 ziZz_xCUM{UED(;`DsvIZzxyDG{`|V(Z%=VznGlu}EAw=taGYFP;`8eVXjC}vW9?Z0 zb^~ddvo&rRh~JS08c%dV-$-u!!5_g3;6n9BoBG-eriODB%r|Id2lO%<Oxy!B*!P^q zB;x`Cw;9Xg&-LA=H)ZUPnX_Wj)0rSST0UAzql0Nfiqfh-$?yP16wDz&;3RT_8zsuk zB*0M<)7vH}$~CwXvY$bTApmBO-M@ZRTZctJ3zFhfQr^FFfeVxC(bI1{47$f0A@BOu zxwAj|VKe0UZ_gf#kCvD%7bSbS^>RCbdWA&2s)hc%tB=S0OegDTpjwJrn9v%p)-ae0 zVZ9h~@jg#mELpnuoPcy2Cv*1q*JoK)>KHh8(y6{Tb(#U>Qjx-?auYq$N*;Cii30Sn zlasH4VYN0slEmqZk)`AlfbVX73~anuIPNk7Dzfq*J#g^wlSxC@PA9p=W|Uiy?ldH> zCD0LSyf9QtI>!z%La(Q_Impnkk3E){jpd^j5}lbJkh{UL7owJ@-zt3v%OaXYuUfwc z&G3<(<oM2Suhlr2|2N!^4@!gXBR=gTx~Xtuh7=J4o%nqh`g0JIjMf&xGc(w+sSy^| zi=})^HHP06QC86dwE;1vvXX>d$RC~>=AA8py3gSkp%~66vuL26cXGfyPhKhgj`?I6 zDYi~Q#$&mZ9Fvdk*l%jk`Z<Q&;0j(pvvrPqLPDyv>w%)(J81UDGE6dtJ%$C{D3n_s zlM7I9MffQZmkkqjgvwjT{``X;Ld6MEbYgMu-{!x2#9{>2whDnR9mfdFvvgayKHI_g zxl(~phrieey4zH_IXu<l`WCeLaaNS$4*9b2E|RrZ407TTlAamb7t^Hd5LP$(T$4PR z3bXJycYckAR!Tq<rL*U`OkTYVl)C7=<zdVqa0^Ahq2alSoy_f28<;ASe>**uYZw6d zm~4}{?j-v0*)?ibZ)(Z}-gTrhD4=+NBB?nc+wRr+sZnv0pHQC8J`{lKu{CEc5wZ|1 z_$ZhwB7%Gq#kBfDoo_LxLJuW3Rry`sC<^1VfRO9!h$nqfNR(2D*C2Nvea!jDXbY@2 zve@Oq5%kS%bf(TTtX4hZwvgw5FT>T4^pntjy=@Q8>Pf<%2%*QBjnJQe!*&meoudzq zE6wRY-S+j@tCaoxNisEvQM{l2M8wE{S5HF0QXaR1Kb`zpBu~IyAsIWRR42-;-i(FW zJLGzK{v<IeQ-p<XIxmeer8mj<!XNg$l7|e3d+0IjZ%&x)^5#?)HEpypZ9-pi#usx6 zwsCQ=0Y2rc=1(cvVFfn8{)bGERP>0ce3%&76q$~Gn*n`_&`XoaSah3@yh_jR=BENg zo=<YN_M@Xk-jYNS5S_c?|L@WI4-Nr;v5M(yXAi{}qYvy08#^txtei*B0`ZwFV3tHm zxYv!L(WTM*m!0ju`6iGMv~hQ+A|z-#bU%}gwbUkWjpyqklsP66bjP!`oRwV&O9q#0 z1nMWc7mRSl9?q{Nqc4Md!z!$WHk5`Cf*C8H<XEyVGER=rmi622@I9D8B{qtHS%5f$ zxWV+*RUYZhGcmcMpO(whw;^I+b7KB$y+zuZ$0{qZN=um;p@zJYBokVW7FJy~k}RdJ zY$|cIQy7DJYzG^)Dig57_6p+@P5awLI-G1ljbgIej&L!R*?g!@1=q2Ai<;c0ALjWs zAwHVe4FpJBR<kI!cuwE7nCj@BeF@#3t@ptjM_WUWkU`%-NemMz{C24joA_S$ke0HH zXEB!HS%SOJiAseycDRQI=gc6+l5G<$mCH|g+Uk%(O<8_Tk&w!+tzKK{8fWmexDoa+ z!ku8?x87JG7L}l_gq0?%p&Se5K5EcxVrCxIsdn9fUT*uomX6-RFND%G)AIxXO%PsP zk%U>SNeC8AENdUXO}Csc28)UFb$jb4?+KEJ%ME&jzvQVA$``5FmI~Q_5=6z&N49!{ z7ZH#9{FRnL?u`J}^u;7L5?G>RHKSHsj1~$4OKVcE$8l)Pk`}vQUUALF@27N389O1; zSKv5(i~SpSV3QUaBlPKv<Z9bQlDX-P#J{#uptMqwtX|$)#;)Zz7V@9xw&cwrlhGf@ zL_?LQbZ}cFM(PCIZE=DiTuUp=51rXfS8Y^)yc^=)%5xf^vb9<dUGa}Fu<+muuuKgz z=s_(?RUt+HqD$YYA`p$`sPPxJ^?8STat<jA9<yfRYX(_93V!wGuYQ5R>-LgSVjY-9 zEq;5H!!i?Vb33OFi=tkHLkM&G?>Yw-3MP2yE)w$>Q|q!F5*$(_NYNYUz=1~0uKb|e zu8B9IblcWlbLw=y5~iwfmcUYUw@J~md=zrVm_Ly*&Rn9qO0f6GI%^vS1D>S#u&tPj zy<8|S;+LQ9aS7Q!na=fVe)J#*5-(Q7H=;hA_y)EXNa5%W?S0ASYG@9}6r(ddOKm*l z*qjpEpet*>HmZSR4C;2N>O+^<Ybv)`&vKmI>Om->S%G7%f_?=ln%&9kcA7@c_da<r zYBW-SC8PsKWVzY&F=MP{(MjRxLrO<lT1vh8C1hYkv0c_R1Hu}xLb-{IyPA=}V@tG# ztK2Df&xRH^74JY6?Xo@eBEwf_!E$c&`Tf`!lDN;&)}`{B=|-u)WVtNv2#WWzswQ^M z_ra>N=-|48+LY~L8TsPpKPF!iknWB-IPH!;>$Wf}Z4f=?8EAJhEm&G9KaKaZiprnz zOe_9c)f>x5c$Ob8(itVdn|R33_<(00KU%>Lsvqa{i+$p|;QzXnI*0TCY0}UxF|fcF zp_|I<Mbzkfx{ekq>@9tU$Pujlsq{_1yI5C7-aCwh4%r7Y*Rne}s$`+2WP-HFy55YU z#yx9Z@7@-HgbQzh%cdk2@hZBB^#5E2*K|c$AWxTihq<R=BI$?W&3V3{eS@R}lw*r* zPrHc^<R=Pw<TVt>7hw(L9bxhIm|zlb<X*4Kb|}u-6VX8NT1I4a!;I>u_i>z~0+OLN z)>|Q0PAMPp9zn34l-2aJ0#j;V$0i{n``&B*<S@b7f5i6uNFF!0`~H30Q)wYTVCWjW zGZdNGWHbBV!iKrW6$Dvt%chfqB}WF$DA@rib2oh{h89DkZ>3ZVPbfv0h~o2ZP)hy~ zg}7nv){p<~L6^n{vF}L5v~@pdVMNKOYsl<k@8KASXHTY$RR&k=`hq+y7|Lq!7=eU8 z;;40i-?#}=`yweFkCU@7sm*1SQ?HFDQ{$(FslyfU(`4E<sNC%r!|;&J#3)Mh4l#x| zEDW-_ek5bVTsa>YFdB5$uDKr8BxB6Of7(E%<v`q`fL#LUT&hDg4vr0eIl5(9AUk+H ziKJo+hN-Ji3=cJH*S`7k1yM*oE(VNLEIW1*N?)>BkFmc}HKACqogbQrUQ0=uN{G0o zTYbOuHk@9%(e1eZq%9y1&l@!K|5*Uy)!q2tD<Sd82u8)<0;EnH92svAkoxb!PB7pC zMdc2b5r;<isQ=cvkUZ^n!>TI#e;&@@QCFklc;h)Zv(@c&N!P4$?bfW+L-K=4s5Tqd zh?FdWAxcD?8Sp#atti|x0pK}5W_@M#`o7K{C)-f(v)pAGlgg@X^g~=XQpTZqc|{}s zVq^qy6jz?yKB?UY*(~jZvCs19`WtgOR=tu6zdT({?^3)x9TciSNL@3yVJ8uzYm{1r zmA<#>^ZNB!WlC~Zv~oz0$fy~Ug|tqER)tO;GS2hRJ}ZsKUP}ihz!pGQmTWbsaMu0q zJTam{McqTl`ZWf3;FAYKP9*o4rQQ9n_v`$%G-xppnwAzSt9pZeTJ@W0l*5KQ@WSc3 zV*ZDYW^1((9ZvaVaux9!t+3G%g?K$l4i}oe@BmY%a=8jfU(!jBGMU6%qK8mW-6O1Y zoVgd8Vi}jS0sn-IKeY03absRA8Yav_pJ$}d=t)*q3ly~VoV{&>V!!x?dfJXtf6|C` zxu%nhlgGhV_GqqAa|3!gZ&Ucgl$JT+ED$ff<VSS+R|XQxK00>DwV()zuiM%E2$r)W z3T^S-GFxl*rvsq#T$LIy)W-<!&nlm9&G@->cSj_xar?}PRhMR$egC<>@Ub`adL0)M ziSp3-I6HQkCCd;7wA-SxCUGe3tYh|h#3WE(1W|CKsMK2ilg@|3A8BCX4U(_=(n_r7 z2E#Efv2F%qtiv#%hxs0FN%9zG+p1fCbueP21gS1y4YbawcfsQ)R72R{Ti7Mpe5Ik= zE9hE!$KqEn3!luo3QnC&p==Me&3#y9vzBVUp@It$F5wnb2D9qM|MCLv7g~8L7QQ-o zQbo2_r}9jrCmKCoEf($@W(4Hx|8;m2*YiAMJ2yUOXLt7_3Gn9Vapg(^j4Pm~L}s^w zi@sdK0-hpjpvDsvSmN=JvO_YPK=o70Ogi{R{EK^w!z7W4bW$Cv5#i&NS6mf1BZBGi zDF?$qOh%obsq+;sEihSBSuLNPKPioP?UvYd1<UHaBDHt+lkOPr8&yX=Gd}kX*F*;9 zaz!18M<(wiFHB@++^90|88l}^kViV+1oJxZ81Qlc`f3LW>`nhp7G{LK*YV-P51WlM zAQZd+xToqD1J#^Z^!q;*>~rONTT6&tZONkcs496Byhb#HDgL_318r`4P>i97HRe$d zsLK6Y^cgF|S?09<s|~C%;F#G;n|Swd>Vf?)hdr1%ALbu3pu{{7P?$K8V(Su2x0K0% z7R>Qk5YL`FFF7GHA!!gRGa1Fzvs^Wk%A09Eh0)bYF@<;n>S|CRNzLvJ%EZzvcfgzL zaC}UCm!?83pndy5-(r638d&+<a<l!Yy1y~9Xbw$s8@dC{?>8Ks*64Q3NhD-}2&=)= z(_5{72!>`!r8zt6^8S-B+jhCCla8X5F&F_^Z<|jOk{e^51xbAQDjHyUIKnnh*a$Q; zVSGwCi&hzpFC#6%?CSuq1LRTUAg~M3V=JkMc0}<*%9Stau!i488KZN2Z1_^?D~=`e zzVTS1n21p=9Dag<q)0Z%&svX}w0F31G!41o;#x%>Ut&)2r?FBBsPq_jp;C;T18c0{ zbcQKSt6L7{@s7fv<+i>{i16waG&%=CRXZZK22s75!N78ctGnp9fNY9HA##>T3eW?V zh3~dcaIWx3qBx9#o|ozRpVnEzkqH_qm(UBu?lBQ)164zoO}P1;z=)Hvi+kj=*P+nh zsJI}I=?Vj{(Q>yh2JWZ<u*!oJX~>P4PI4)IObq?XO8zr1cyJ7%vYKc*&ec70iVXSD z9NjHgWR#$bH}DEIKy&_hsg?--YrMUzxAowFlvsWC`Nnoa<9i<gZ^rbMQW`~ioAAsb zh;LL6p*fUC_DPl*5(}P|jZY-18noEc&R2}Xmd?3XAevN|PNZ2u>}AOO*xbe&LNx_q z!C@J4{P8X7b7~0vI?QKx+qs;Mf6W-(9nHO~w0Xy)1=!3-{V1_&p=aBs6@is*rrB0! z(W1;6qS-XW2{aS8{zhP8dk}JKDJrDVElP+up0Uf-a`X4+_Wj_<y=Q^NiLXo5l;1N@ zPnL;FNisrm_C_!>b(_%@np*JLC*)Mg_5{Qe{GM(UF@q9fTsF&SilMA%q{f<&iuYo4 zvl}G+*}V(rx|0b2C5|kAt0r?mIWQDYB8ULP%;YdMYV7(j>0m#&Qj<dHqrov^M@r)F zhFb6g!HESX2=fg+6E2f7aH_p;Uyc5SMW!1$>vegqa0r(12L9z|ql8{kHvq%|XMqhH z23<7ty95iK0rlU};E%McrED2tQP@IcpmY?1i?doj0oY&<HD;4(@J`La3_y}iWkhCZ z6HW^B?U`B~0t1gQbM}6v(9chBi1A%iCh`!a_mxqBnNPlF^<DFY;Up|>bu2kTnhN-n z65XKn;TZlNs6?FT=%gWNeuF;l_dV{Y@3H+OT9NgwwjHphS?@?^46lFd$7ii))Q)FQ zpvLog)#wtuRG%^O=>~gpKHw_tNay6_B>ZgKmPur;ntB_XGSTx+Ow^($%%#yFoKMZ# z7PjUchgn*)DxC=VLc65is$`#q0s|qshF6qW0+*2EHt6?wa)*mVc2J{;djN59&Q@%B zwdknncz6Z%?9TukMxDA+mP}E-8&j=5a@Re!%=41{0beFIHlT#Wz~}IPGz-62Sik-- zusnS_n8r92neRl|vM@6%B28n`f?f!u<YnvnXP#>CuBHMpyH+>#`*>$2;%N;{`@E_H z%F<`js<ne?;W7eY%}Hnhem2U==}V6mN`I!9hhqkjf2&Ch9U^ETQz72^lGnbg>53;1 z1X&m-2>C;sd#d_vDUaMh8xJBAX73gBdn;T=Cf~vRx2gSJ&VSVlEoQba(4<@NhawHJ zX+uC&1|3jA7~WF&d`Co~Odcr1$sz1|CHS_l6E?O=9!R;~DZ&8vvy6JDoMw2;^VSM7 zvz;#&95TFLtPW$jI(0sK{uB)Cc9MK@n}BUERIwaKpq<439BCrzGs!oePT%Y1Uxsrd z^G+rWFRpZLO1;%mjA$W0bZt0$nzm@!59YcVp1dr5I!}X2#=Z-NhV4-12rh-kqtSmQ zRj~5#$f-8!kv^ziV}}tvqJ_J$Fc+Z3rG?qV#MhX!;gGXU+voFtrdcSD9uy|pX7DN5 z@{<i`B~}oD3O@P6(T%p?XM`X;Oj7QeJr1ym5+-IPM<bz10!SN^3#m<r^I?Qg?W<n+ zLJ)@I!8o`J?fem<vt`h`s-imIu((Ra$N?Rw_0-<6*&4<yp7_=IV<^=@@_AeQZk#A1 z1uSuJhiLiN1Y}M@347%BVo;x~%nUok0BG+}0Ai(fF+QPUDg`n@u*wz@c8QNnX{z-L zOdK-ZBiyW6qRZ#|1TAU+*H1xajDl7foOY{w#nRL;U1G7D`0`zMIH*MUyAY*O0o46T z(=x*#qxrNq?-hcl7<U;Yf%+hYn(-3^PZPe?L{Tveg6EJw>EQ#%jr<kPB~X6!P3-~c zWw}Z6yCY-eC=X*x&Si3M3OcQTeG|hKfuw>}b*fxW<Jfs-xS-}zz~`O%2I~@<@r(0p zi@A9JWWhl7_EvNrYlWEPy0XdC*R;Bnp7s2sp)1Lo@p5B%GclxN1VE!%rG%C*k&E?y zwrWpu+$i?mQxCfdQ8+T#%1$rmY@<<Lt7aqCT}M^kVP2O-LtTl??mA59@0jq?HlE+W zC?5Ot5)J0>kqC?GB>aHqY8sQ=F9J;kttz%{71+&05iNtpH~Z`+_6>M!v4%f#DS8Do z&RcV{aHuR-4vY6=mWlUWU?{So3Hy9X2#MJ)W-yXS)1Ebh;$_jv!8669G<$A*Bfp@5 ztsuNgpD$nx29nr&gJK#HN{tB<#_(B71xoA{K2a*~wc(>%k>2LsJt9T`yFsRoIU8_i z7l&hC7=Es-{Ye3Lp<FS|4Ny@DNKiDv0Z*hcD~8|fm(VP9?&@XNR@2BUx<L6Ui7yc< zb+S?2pDcvH89G(P#iUJVH^G@vx<cO|joSFY$~lY$c(?m20unLCLdGTQDG3%ny<y-d z^5_Uk-{@!x%6HCUTW-V>HCp`fsPvRHY=4Q@F9DTS(Ku|%csK8!-b@5}mhKimD2U9z zg;6?>zmQL-V5Rhe4?KB41F+XOp96gyz6<$m;$$$+;AT(WLjjH*BnA_3iI(aaMab+8 z&2rdu5Sz&AGu7>YjU}a~)bvXIXd$$g;?3g*c@JCc(P!<Zf;@fLp;kg0bp|lA!QX|# zsp<ko_r-}>)PFFXjC!~6Yvgn%EqPoUiGwyCuueBo#PEN%w)^#(Oy<`IN%^=jxZ<;z zCq$B@ltRFeC>(kkIy!huz?)Z~=vsCAnvbGn(5U!9ul<8jCFuT7y{3~z9~*S;B0S6R zza$)_Q9+V*0ZI<>R;LXH;sxi#r3@X1pAj(k#&8fFp|vy9N?;F52#71A7(~aWd(qK^ zG*Y=!VI0r9M}3-sP{$bls*EuE$V7WK&P`3xbbooDRV|!K<$CDH+ET})%)j52bmx3< z7<2I-G#3$cgJTk%cv45^wo{s~0-~PMDL&{yu$h=AsA`<SzcZ~W)r1yU4Vffm0;tUC zl(FRbS-U%XsbUt+(gfnN$7jju<T--mGhNg<Jy+bk?UxuTje3K-gbV7{yc{`*_-zvJ zd;>c)>lSrJREgQ|>zzKaQnaTt;0^M=^fG@C{L>c_+F+N4(S%6gz(q{CZ$NbT&&g1V zBl%#~RB1)<c!(uJfk8Lw=jJL{aiYRm@dmIUleHvfS>x`dDl;YW%<snIa(_<u5iM`~ zZ|saA%Aea&c*`-=yXlXlO~D!ID1EE_gD+4tB(g#k|4hE8<InE8w>Gf_5ni~hA%a7i z<%*gWfkeSBN=QXO^v$uErkj9XPg*2otKRKPh45rpiUuh7#XK5{VK12vWF`y3I5M<k z7F=Iy0jVSf#cji#3rLc`#4>H$z3TvOm+)u!m&q~QRakfmf&nfv{z)dD4|QZ)J~knB zHad7gur(8K#Cc1qqs3WP%y)|%Z*e1r`Tp%0uc`5Vk%jCP3bs?-Ie6l}gAo0$-z@p~ zYRjr4!_eueI59RzEgpItluWgdPfpPMuqV9<Im}?p+#Ua&p+rddIws@qyNY%p-#$nL z{)N-uC-VqzLB-;)8>wR0$!VGrKEbh%s{1n$e^-C~b0y?Jj9`p*M%wzbr%bBf+cF;! z_c1*YuY2B_UU{l=+F=<Ds;T>=%&p*s!iNJ_;3fF0L0EtPgHVjiYJfz1?v~a_8w1&P zw70nX8I@da=I>oQSey(8>8IUfhdTl@vAccfEtE6gLFF=$kn~-;vDO(}?{;GhTeWVX z*QWiM+LoK&S6Cn#0kOP*1KUd7LOuX-(!`%1azr7t_2}06*LqKSrvT-g3tuW0%>aWQ z33PJ)h`)U+^pz?v{Mz(g*1}KbKi<F2HXpA8tE}8nUi9fl4j)sKa9QU@5|WUb7UZkS zjYHw~{6GBElUxMscP0_<a32p-Qb=)R!q|qeZ!q&S425daOd>VtOf%KsYkR!r54BJD zYr4RCHzM0_<}i#v#8Wsb4!yh-t;26VaQ^SU=nIGSUhD1V<rW1>0Z{!wcttVXe)Q?5 z+k<4UAjZ{J$5c{5j6M)Eo|v6?<>Wp`$nEYM6eQqoJIJ8D^jpIK@NnfBSRs~|({pnO z*}Eg}%EZLesF!@0fT*^lCIS=2a-u>@ER3KNpV+fl%zgPMeuo8;D0@`vvXFNC1#7MQ z$Um^D%3<k%W=Yq6YLa>XD0d6APHg^pOLr!eLs$5+2x+QAO(ocT7VBsZASC}+zd*a8 z-W;u*fRyw>8>N-5dlLOy3sWCmgrthCU{k1lOhF2Z!c>8X_#F|E>g%us78E0u4yJ8L zIGwV1GzBRN6N3Uy;zrEfhD6X^UV7JCuk+t-8la{aRG?Ezr)OK6rAO=9g=Z6&yTu)% zUjNjO+5D*b=q|ITx<<QoEq+f<HL_}5#UGlC?7mQY`9cADQ~i@JdJb_;fBo#+t1L_f zYm)%jlYa{w2R0hX8{^av_FkQZ1t|Fc7Or3K5){8?R_R~~Q22U=q&dGhEk5MRTv>#O z40s~QnmP-{A_>zaY}{6q^xnGYzP>$H0VtLaXRO4Qi2zrM0Z+OUX}$VP+Lhli5^VP- zkEuETRXsI=_I)P#UumqT{D38Lrj`GsNZT(rm{@+Wc0@LdGB4IVOhQB_rLnOs-a1+U z*X(j%D!RtgdjTVDI?MG=Eq?cZgb05ifw^tD%p91aM1bm_gmh74tU)>(rqvDZ{mXEo zexKI^gDB-jKJM*5If9ODCUv4G$#qa--~qxjKw_Iw6^H@ExAm=WJ7^Fp5(XWC1fAh% z=(xa)nJj?NftLDXw2aETM9p?iQ^==tRCTTXbG(j0Nlk#iOG?TQq~4Cow47Mey;*|s z9DmR#8_!UsSGexHNaB6DPkXs!gBu^(y?G~gmU!3&GP*jGW(vG$FzQ3kYK|drx*+5B z+*<`I9Wg7OYE2)3qOS<<kCNz6B(Q=)Xf+)EE&udL3j-Xnd~IdHr<C05+iq&SN)HE? z*f`~$aT)31hM^D%IK|!GhQnISdOtaivt>TfwwCx`MeMO4USR={X(^Cq)S2RfNaNr? zQ<5uGn_|^&Z5b<p4cQzxR6=W-6O*q@&B$bnnH3Pc<fPB68}^(25yQ}OD587648DV8 zFD3y8X5t9AJH9lpKTR5dQjg(bv~B0J;xIH}C}#u8-aE?+(qxqvA}m{)OiBAe`6`#< z(H{^m8SE>?1&y)KSp;kjNl|N5yevQa5Dq4jk319%e<h)V;iI<m)muus3PQ<wSvWo6 z%Igus0OdDHC{o$z&|DfN&c)k{8+w%jT4c93a`iU+Nk5e5pt&XweMkv@PUau4Jew9( zV$&gwXMXI+Zr(z_d8=`0+SsV@QX}JqZg0MCB|IP7eX@OAu1Q&gS4jMGgHJhz5yV$* zzni3R3oPRHL8P2Xq&k*VRnSbfQy$l+u*%HxVg=Jj?O_}FIa8MoalwY*OhcMgN5@`L zv?sg(iC>rwq>W_=7m{w`G<_I{_wm+hpv98)wFXvYJ)DeKQ_7~29Hg1Y6&*jx%Q%b* zd4DTc%71F1v1FpSx6?`?S>}Z55~Q!vc1)gq_?m9_m029fk{bp`nr@3zHddR$aifq> zdn5M;8Srg(Y-AtB@~ST>IkARNq+~v25`Z0(%7A9hQEJ*X@|Sp}`X3BrMh4MI4f|{? zsTi9CJKCzC`-F4NLdWN&Z$^@b(Wr<J|B;^^XKFXRubNF;DPuDGnepUXCU-z<%twwG z2?Ox7h@BW!4?R^=<_+3Ua`+4$;yHp>YjJ;5SZ*=z{pr^z=j~_HQO86hC(m<4-DjsC z&g180R4GIz;M|9CjNXaKU_B+H*swEfDo$eZSu<j(Au&kQMyj3AX*18T(fLv&DxO#3 z%|qAKLK{YEI0iq7d;WtE*n37FW>1-C9!Ba-_%e`0dZSP^f~|MpoylL8zo&qKM}J)N zJ_0FKVG<WU+TTVB=DB6P^XuVvYefAdsPbw4rz&TGa%Vxg^RHRw67z?`SvdIGi-_M% z6odjk%|5!`<*Lq6ztqGw{EG!OVb_8^DR6_fggro)@U|OWDY!kCNKbpkB0!2jHlf?3 zP(hxFf`00feZ^@=iK(RJc@NIbw_N)D@vJ}l+Xz(?QG=Zyot1U+P3XecN#}UusHCZS zw??1jnLf#YssO#JWTME5ch(#TSMi1TLCxy5Lanf{dr7mFid(r5PqJi7HJP1o8FS^E z*%yFJi%D47yQDh}jVrBg521_==bJw@_wzNht+ceX-M`6HMx5v1Un%gHM+~H$f&bLk zCyW~{kY0EEe|;_pqXdpPJ-?;r;7f?6hMDX0x9O!c*_B{eS}#9hJ>6B}bi9fFBb6@P z<Y$*Gh%yuD!yvV(vYS`9k8J$<DrpWacMF~Ps^)z_6F1Yv6j@{%X0@To7>m(`4tO%Q zvq!J_e}j&X<lFyFzP|H8sA^=sq+2$p3W_{Ms1~+NT-L}yQHq)lRB*rKM!JAb*CS2% zxN{7FT-_qV#8hbcUf$?QUy(Dd?&lXl@2kR-o9Ardk`>`Z%tRf;7SeRy70+ajCJ*`W z7kfy~$5mJOni+QUjoT;X`}z9Y3tHOEK17ijkk|nW1(0Txar#qKA%zXV@+?wpby%UJ zSAmm91HiU7S*Nng1Qx{<slbfNzf4UdFFY|BkHBRipFxonA<G%hh$D@)ECmSrFK7{c z-a{LQfobeupdbwU8tc?D61Gr#ie0#A+sicW$yjg*)yw9D<#A5=bhAHK_ukQ+93UsV zD3L`d#2^j@V7l5P@_xDZ97fQe+Z@I}3u%X;L37gsRdJ^?j=+d`l^=SXI8Sd_3ePR* z1~TbY6Qq0aAzJ9|sSGw49sjJ!xn>A2eV9~FIRFMD=*Dr`SSp0EI}rUGQ~VmB96HTP zl(&~j^O}*oSZYuj_E)5HwhlXN>-%X`UNW7~9f!*E<gA~I0?#K!u~EJS`X_vXFaV-l zL++6o8Cfbzv4%Ja%ZQ^q;UdZpDw-10FY*y{tbgR-_6k}CLhlL?Yy*((nKDHH1gxc~ za_zub*eFabybHf}hPe((3Mo4wh!w2H%%o%#N|mm{=(2#M$P9vlhZ^VnqJ}80!2Vyk z1^i>Pmj%{2*m9x;*Lt@-O#fr+_HdCwSaH#QB6;NGC$91d-~4x`V!G)hJ-pkBBs2)! zs+ogB**8niDnQ~&UO(=QC=aL7Lakm*!|8WiMk6Uu{}o=%P9DFz-d_>{)^Nqtq#s|I z<a=`78|`1%mVM7kU;#lWW2i`?6_`uy-l1n9?`^(Si^<RTb_(JZz@;AVn#l}dRrI_b zip&CySp@9f2Vn!%Jll8N>IOYq?tKEmKjb8tDxM9!_uYTFCZbE$k!B)!Ze5A^y$k09 z%ewDQmT&<ycYoh9VQKWij$-4>os>V6C`Q!$L*gknL?T+_uQU7q1cCn=wtDHat;!^) zv@`w>SKs(wXVk8_V<&BF+qTv0*tTukY0}t6vy(J78>jJ(ZM(7A$;_GaoA=Cr@O*gg zweEEhCp|f}KDsuIvQudpAt0douAN|Ug7596bf=8%k4z1Xl0D{^C&K<h5^}=fzm;Ax zKe8AAVK35F!fwWuo%2;iprEE4`HwmtcZ^}+s(X+n%$gpmb7laRyX!uGgI)1mpkE?p z%~fHO&5Zg@KcutFG##Jc3-sy%`KUo#W@@E6P<Bg4|6&mPrq}GX@Wnh7lSNO%cBz6{ zr||{&)PCFGagT_{X8F^cQCYL&@q(GFQiPNb^37trw$l7DBt^AHOygwwXN0|Q5+zA2 z9>c_$Rut8BQ-j|gy3b8{2FS5;X@Bn{k1Q_}VemHIl31~5#M7MW-20)-;cBXV9L-KX zZm$TYUGV)|(1_Wg<fs5Y*b2QLBo#K)K*1{-sK;$|W8Tw{S}r|<akk0f8)jI0$1c(| zQ~rYOaM@-;1#<oCw~F*P_}s^SZV$r`6yq#sv|1m2iIE0|eSWD|vuUvaUNB$n!Ktv4 zT&m6|O@6y7H34+rJ+<^XA}bB*8<i(TRd|_LLN_Ixr)jOVWQ@pLm~XC66)9nnAd9lL zU-16dTK3<kRq#NFUNqDfjXlBaIostvXlq=GVMSQ6T?!2Mz>*|3is7-zIhW7i%;97n z4ghKaF0ML4>f`1y1IJ+?OCPh*^;EJJKDRabhHn>r8hu*03NCmQqNcq#LH2A&;oxkc z3`EEXRxIEXyI{;h`=K2ik;&=0cAm+$Hz;C8ZL`(g#auChujpKVf`*f7=sq4<?RW46 z<YK$zuYPklfe_55sCc2zFeSXEBF>SX=7V%3HzQa#GU82(>_O=|DTg2~Vqfew4EHI@ z{B3bD)g#yQAq2roDMpL{@%@*vN;CtOpg9QIUQMs_7)~cbN{jI>tQ-{Uh5zFSN6GrK z?_mIEwYw0I6fiUxlV^685#;;wXH*A}81Q<R@dtSYv=tQwkT;J|$Ae(zADQw2(Y2-5 z2fl1O<!2($Jbs@T0}W7>y`2^okHe{^*uq16DqTcB>R1^I4BZyOU00cA!+U69qOJ5L zSpkj4n1;K??!-J`n-9jX9If};WOP_ecRM>plLWz%rVx_wF{GG!I1<O)ZmBxelmo+2 zddAnidK;W?1J03p%gx*Q^H`v}(3EhUX<e0!uPQT%AEQ5|=^0^0QanCseC*<EW=g|y zCrp*Agu8NPz;RJRZBMB5AFpMc(VOGxFN{}na@oj<9erI2DWX<_yO3{vi`p;}SENbj za2}bk4x&HKZ4gt3<cqPuo|6%LNa0cPjA?4UB<|&?BjKXYka}KQ1r3J6dDqQ?y21&8 zoYRL9n3?e~8O*Yj8or&K766%euI-F-wBtRtq-irxF>;gWTwhJMqe-%lU$0+|;qQP@ zdk6r+IY=4zzGE3}@62%Nh~oS=V*^}Y95(6*HGFypSbz}UAeIlY?@nME$5-i!O+C$7 zH?V72lD^NaTsP!1S)8;?<~=a}ov(*;+d`>|i#YaDLBfuGL5MkpXqAt|4Ee+41LtO^ z%}2Fy=Jv*OX)$rR$rg|tX6OpRT(3k*5I<05v+UUC9sfW?#GEt@gM)>`gjdwc^R0z2 znN1CL!}SdA$Hiv~bVGzSMi1pZ!DV0Iuvat;Xn84tL;zK;J31L=ZHP~H7XFLJ1vUe0 zK)*L%z0)<r;!4UeCBAp3$cvG_dAK<^N$uufEdF|9@kAp-3J&n+=5Bb;j~kdHjZz|? z6T)6$^ldcwG22Ktv@qzrvsvk7^!!sKJGL69M+PK7rI5laENlF}?x7_mBLq8|-F#MJ zJhST>wBSdnCLI(WRn)kB+Yq?ti6H2u_^bv}Hlfp@EO@)QWpQO@6uZHqqxLux{IuBc z_&?jAnGuH!Q7d&ZE@XS8ehur8n*;=x;8OGuipY1|6VY5I6i~2mlF^nsEiqvB%RQHz zXDW4eYkiMRX2;Yk`Mg_w0_-a-3Lcw)u^Air4s?xLVK`?!8OhIX#fbK@V3lFv)a1)= zt|_<hitx$PhfsYYry~kcE}8NC+2v>)00$8(ZaYxaThmrqAp^Pq7bL`CDe%WL{LsE+ z@P-Y5{%ABu?lnzos+QWbGN18BAO00Q+=Fwl057YHjLi2G?bw{_<@AY$Bp%N24A|eI zvtqWqP_ZN>WlgM`rZ3S6d&H;#3@(B@{(Jo66E3;M?TZ{eojXFlPrdv;H5yu@Di!(Q z=NpRA-1z%bK;qJ<EltONKS%%T+}k$V24D+Cs_JN~<9Vg#_Ip;SnDr#89hp%Pv>?@P z)k(bs3Cf=?28yy9s~iq6{nDOxFu1LBKU@6fNs^Gr&Ek>%z|x$oT7o1lO9@2jd=hsm z0t(U?82KAg`!}m1rvGBh^Set#&YF`=8^hY~ZYZH*nti=~y)>U|A-Ylg7ea5*8%^ID zh>`0)7%^U<ab|w7xOc;NCx^xI{ah%M@bv|t9*dX?afzHrhLJuRp5+F*pF;zPdYFxd zG&tYK=`d4Ky@}Q`@T;f4cN#7dBBft!tN{U(%d=l*`smkCdV}@K{Q-x^$&!OKDvAan z7>T>kj|uU&Zu|yH<amm|nA%KgpJRV`z2DUS$l`4WjL%;7@Tm8b5-mK2g(L=psZVet zzp{xbnf4`qDLazCJSEyqu}l>wnw<x^6l+L};(RA?g?3<tfTmzeeKEO)m!S?J(Pwo* zD76V@6=C|l`28ji$bn>mGPe-xxE&qNu9Z5WHntD0MhgIHAX=Oj)5y4p9hIiV_J!hG z<LlJ$cTZc=DS&!GQY(UVl)t1_YI}^R7f5O#Y?l5a9@aai;6Vnu$gPIFf1`xxDH&TY zkHobnkj&n`UHru6E^8cIZ;pY{99fiFMFJ&`8~CaXtc<5W|5fWWOJmnA2dBPKdgTkM zq9p(MG`**{CEhkzEnT`g#jWn<ph`z5YkB(l|Afv%Onr7c960WSS*&WaW`q|lCpm3- zkyzMIT1As!p&JKIr0m1JFcA<ySfnT2qZ(}}4kxGJA;S^>-kTbmSNb-7wW7D*sN=RD zlH5L{dHp@%x@_%~YXVc4;)d!%^AlafpRQkK3`YxwSu7x<E!oD*_-v^iNI)<73$=>e zblK2D%2-=OgBCKv&m`pc-nWrse)zYRiY!3b271FO0&zbiDIPEi*nIUtc1>(F=iM{N zF+&s_ablTrsGxf+SA*>$gqmT;4&u>+Ma!YrIO9wS=~@G($3m-i+JNHs+AaCmsBHzr zo=weu9*oqRxxV1Kze6;|z$1kvMYG~AA_Uj;At%>r)0MkxQME&La5@l>*9w^pStR%D z7*+{fh0voe4`3Aiz8D`(Ip{4a-aSLR!t4e5`rF?^7|&lX!~?S4HC8ivS7Wb>%?~E` zRIC2v?Gg}Cr`ZZKd)NsAxJZ_?WA^C>U_Q_;v?(S|xl(Dip7min7m?AgMSY9lo=<Zf za$ah#CHIHXk*zibrfP}ERxHo4pq9hTSGHR&?4big`+t8mi)l9h8~PGrGJ8wppNT7? zkRNoaGAe_#dI5j3@*$P=`z;at^g-a$Chl_lxz46vkUgvhjp$-V3NZf7ho?SBNAvSc zgea&@EXhe9hbloTRx$&B3xX}XigJY-alIWtUqvbdsOO-gZWIM<`V$m7)|vm&|L!5p z%8dLNx7L*6S^XI>9zn4zeZ&yeT9wN48bo@10!isK`N?S$Q+TDe>urWiY6sl`(?Ct& zMcmf?Q8j8ztOH0dRvsDXD_l%>>A<aK1J6r7@*QQOuLw}O%z#H>*5y<xIZfQsG1M^s zk`i?F)BSN24S{KvF&|8yQSM<5yF=d}N;le8FF!(7<ItFXw=g9g<p&thFWOQV#a@;L z%tMemjV>O1IrvY|?M;tR8&32ho+d|Tr*z_9HRDH?`$oM?)HVe+%7ydu!RyNGSvA`J z;{Xn+=oeChj{DTWcVAgiYQ|q=6H*aIxlipTK5nB4B0ytM?R@z^UQkE_B<T)@436qg zhOZctAY(ip(_eSqj~Kudw%_VistTvv)}#tK!pvB5*ddtaKM7w0GGYmD%aIAWU}rh? z-|(Ul5t2)$&)dwery5*diLa*&bcJ7@pxSFy>4MF*aoay@lM|54!N2Nn_9~!MpZiW{ zAD)M9jwK%DA{q|rjL8cTb=5<efTkwZu6>~eRBS<CeQvJ5Q6X9OR-~iN<6pusHXV~I zifKM^@KYJIC7abVXLGGNovo9jF2j#}@er-(!-YO154&!^+L2rtrj%KJHpaXDaONW> zMk7kRl-u#=t1>~Wc}{H6^FTsh--dqw3C^51;*}$xl22sDa)xK&V&27Iv6_m4Qs1;` z%`|gKMH98Yk0K5Umj^OYi$NQN7x5)x8wA(M(|*yZkV6P&<%WB2524W;lj8vOJZ6=| zc^Q7|01Ae{^NUs+rx;M$3GFVPu2Bj`t3q*t_J0N&RcckGdkTr9x)dlR;-jVaxh>MP z6&^GBK%V`IQW_az@++~-i=tv^d90tbdCtL}%=$<&>lqIrA~1&pML!lOB;)wrrKeBi z_daaM1CaMDhKHDDOCCwfb*m!<@0_{HmAg|h>9hg8MRMFVYoukNW+0P2Sb&JimnI(k z8U(m2nE^oGFsj7SsWIQ>7;SUDH7yhVQikk-oCK3No&C`tY=^o5=HxEIomzJ29&3uz zi5q9JVK%^lXI>Q6-<g}|pYQCxtCa1P#;8c5$v&}2{PqOzx1PS^fW#`6<VlPXt0W)m z9BBi(C;3rAY!s6xF#lC3&zpAN!=B9}etf66P%dAfGPVCpyZ`N+?eR}0RD`PrSF00& z5_h_{O&xSqRlH^)(Wcn}4yRSE+Z^#ECg{CcB{>hExcvzsEH7-$%YhyquXikFPgxBz z-m-!#jPmgI!7dy26Ubs=1Rd)uxm?hT3if*^a(W>K$aUdV^<xqdu#9m4d1vx*b4$MR z@k-~@AVrX7%#uq0t2-@>1t6aeXt!rBdf2+3J{^eG__j*h-0U(T`)qUJ{%pNVIBIz8 z=+o-tMW=a(>Vw-Gba=;_kp2Z_v`-X|$3F9|$?<b?9y8bD&@2zG^XZH_gO3KlT+`Kg zOeLG1)q0F5wmcb|YCTDlOlO6%bWAAS?+R91Vw=4(I0q8nTHqQ@0(QGhUwMbf7o#3v z9zOj*90O|tL`#{mnxqi?(@<P!Z;oWbUuPfVmMkWxet+tMIQBzss93SC(nj2(Kw=w_ zyJH$a%gGn@nEqpQ)lMJOyG8`Pyw1#}?fd}W#mtYJ*|TEv)nu$2@IcxOF}y6sUn-U_ z01HlBS`A1-hm3P7ViM6-`xPnyZpO5HCp3-n6><yPvF|3AGCHxfB{5jy!eD?6t(ytc z%R0id=OWIm+q7i)+?9>Z3Md|vPDg)CgO=q4VKE7Jir4iv^A3kE%tjN9cNIo-F7uf7 zSG6{?*^p9VwZH?g{da}z8MYFz-L-_00GU`yTx37w{k6_*-%sa#jhasXkol8GhqF=d zX@NHX^E3<_9`>rZ%-tIj)EjcSEwmZ=<t{#{c^q35YwGvS9YcV*OaUr4n){bwzW<BI z{a+@+kpPvkO1=Lt0moZ9OYIsKT)+;3Z<_&`<x$6_{OwRemObBX))D_5Ta+SPj`!a^ zdHGOJ62fTOui|DjIpcqZrL!}ipfRG3?&N~oGLSwlB*Q(ZcHz0AysFuqx>n|pKeo+o zZ)5Hc|2!*WL>yhqqxsNCMr3|C-LbDd5^~qeNX#Yt;G{|TaOAH2H&JEKwP?TGGM9@I z&H6o(Vx|qfcp?h}ZsO3xZX&yx09=8RGjR!rma|=_oD$y9h5>;@og|aaFczNA?-+SU zV(*#DYuCSnlIJ_JCafr#DXCn;NkL3OO%>uv9qb&$>wM;sSRu|EKIlXqSPz3!5=FAh zYL^}+Jcj3072WAPgd9}aYP0#~)A+uOhcS2r8h|yIC+svS)w*OX7c4f`C6F2SUG0#G zWs7>SXRqy?ow+*|n6FxE8u+`?Jm-JCBBS<Onyb<KSr;RWHhnlfP`Z^$2HN8D&!yBm z9^N|?P=ZLqH`Mcru3e(YB4dOW6oT1Fkdqs6BOJqx^F`n>q4CTqJ6quV$oi3$g~U^r zMvA`%dp3H*$9~s|CuE<>=e&*Vzs~!F69u}C3Lj;`nf-wvVoQzu*D(f%-X>B>$5@<< zIcq<jBl`NQ<qps7L~NGZMAoedHMaRqQcKUDaCi(H0^6au9BXc;6^qdY&#2rl8Jt4} zs}5uP$gFq`Y3v5Du^eAVSRgFSf-Ks-y?;0a0eM~o1pq(#0Q+c;sg_SPQu*v8_ZP;e z+`gOkNQhi){$Npj)OT*GWa0K%x~2d-w~KuA(Qo@v@3okBEbkJ!LRq<}bFug$yDWQe zuMq3hWWq!CD@{Yl#8>e)n|E|>MrpF8@>!~-Dvd3NYlA&m%aXA%gi*>)JYzOp93pR* z+O6|V76007Zf|l9uYBSIwOoH`wK%j8#1^q7ksY3~h_GqUr*feboEWFqZqzu;&cQpM zb4NWmax&S8ShHJB*a>IeaSXZdgIy9G<Onv?ZaP9f%%R3XZ>>EwPtF|mMt<9q!iPoD z8{m~~T&krA7ZJhzPMt>oXuOXPz+Cg$ndL>O#c|4*$`_Om>#}z4mlY>oaaN8Sr-R27 z1<~wv%f1+<?CphySevWD#w8h&rdc?t2f@a`&elNuO!>Y(h~W3EDH)<bp-p)>C%18) zZX65>@S{<XjqpF$e1!PeND+zO6D?cVS>isoIS(6A*>&*U3yuwD?P<{CaO1?SD|P1a zqZb7;$hkK}hiHX)x6mkd11mCj!)-Be(Y)&y-U@Vr)@9}DZ>Un8F{zbyiU!{`gYv9M zQBcOAds9ZPL~n;G&nL{3y3G}%jC1dK8yM)Ko#1cIvAt*o+Qnt}*l=E-*UC%XXF{pF zf-L7i3zdhG$|F=T#(oHVLH(Tz)p@`S?z~a0D@6{I)mG~KThW6!g{j2}s+ro!u;^`L zBnzbYXk-pI;rD4wdUde;Cn@8qE1E)d^q*@NFJW5%@0Ae*={aMrnj~{_aV!J#ayTqp z)?A3ygbyR_PqrBf<6#7nfqs5^>h;Wr9T~{r<6R-*>+SFbW~;W57^y^=6zE_odiF6% z$-!)GoD5EY%#${hS#}Pt?P9gA?T~z?qv`gr`#Lnhpb*Yl8*+MLzey~N;A=`9tMWGI zS0x#e-K%Z!V7lX<u_gw=iU84%mcKY0o`1`z1<6MLm|~S0)05M}M_&QM({Z)Xro&mY zF;g00dX6(bGWZRk`*WlkJGb#{ew!-jTNh@rgKBN=%+(rgAH^_6S>?B2=aKYOComti zj_g(Uh1(+{QbKF5EM5x9=>In1t@I?cA6>wK-v$|a?NTw`q7m0^DmFFx1!G|5c0{kR zb};Hhf51VFsOdolHxc*B;;829T8{C|*2mJV?_iB*uk)v3I^oVvNDP#9x6=aF$kdD( zT38v@#8ZJW!e*8UM5eIaGXtReDW{jXT-adjbt-YW&7uH|5xtu^7EADPG~%xmE9jpX z(}B-t9`^T+T6HT8rY+@~2aa=9=WCY#qLHrRIC>cMOoVfI7yb+aVkKv<ze{(Yp-(Fu zvkVb#b`2wYKL%h#qJ|n4t$Vo@$pdb#q}{Y?7>7g(V^5woy)i;L+x}WySYK!ZY@xjq z9Uoj~;|4TAD8Eo<((~_gaXn}6&Y!Am?oH7eMUYAGI1!u?fYt;{4LgS{>*oMb-!)@- z_wbbtlWIHx`(HL24bkO~k{BEwi;zut0*0sFH#l!EWyFn^f8kOo-TW^t=Wa_5OP_D^ zCKf4<YI7qNt6|Xgc8kHuwZc4)=}e}!!q=fI9gmrd0wRl)2`aS8=tI#Y!UXW7Q&WQ4 zt<8M+yAF9R)%tvm1W%G#Vug?a=@ybC@B&`zo%%iK$BK3x$S+{YqLj~jEep!8C8ym; zk>|4ez6OuoI(4Px-RqzjQib>n-%ba8^12%Nv=;_=31f>R%Qc<t%nOcQqK3vMZXDzi zLLy}UGks~ZsjG(@AmIwCbK#|4{y4|O#--)^{^(%*&X|j7R~nCJ-e56qMLqek@@J_2 z!>K{-M%CMRJjZ&Hc*RuqXwqi&4ma8devQT!QfkR%QBUyzW-R(TQD0>m-z*@RVWg>C z&j6<6eHMpJgmJ4PLSDB2HTiAGdumitT)!!c?E^}!)Ze4g@|7&yBtS2JSA32_z{%lT zDZm>x2|8;kZ^bElz5|Xtznj`CMD_3tYc17Zpxb*D(kHkM7=3Ly)xuS(zXLfm#Zq1F z?4|I&Tw(FhY4(wH)2J#&%3DeJNz$5sRtnn2WOOW5t@`k0b)f>Xz=%iv|4-uZIrc>V zXYBb{Kz}gJ(b<xyjiX>VsE?J$YLgT6JpnxX`uI~mp=dZiwM9>mHw94kDKx7lPZ5Gu zWP^Jae`puc;GISJ5s<Bhf6M3DqfzAWL(NyNOW8TjjF9e+R^`*b(v6k~jg|irMPo!= zri!Pp?Hnp=S||EF0hJ937MZndDt`|jU}B#g>p0f}prmPpj^j;wVD4x9j2^h}gZ?<S zf5HrMvX+BphlEeU^yquzwaN6UFi~st-mAd`pwGzEOoU06fNqENKi=Z&?US@Kj0yXw zt654(9OKV7jPXA^)5?v?>UEmW3SrWew}5O>U^^BOvl|?rX?deM)LAm_?8V<S6W*XB z7}8P1shhu32roGK4YBD0o3jmng7&j`Vjs0euQt6IB72BM(0)vJ@2-r&WBt?_%ns1g z%yBA<=gtW<u${FWvGTnqarl{p<+iuG&_<ykZeQn9zF}wi7()6${KvvRhjXnQ#tzdJ zphlrEQeIuEl%b^%J-aZmBvQ@E!0pIR5}yaHye_TkOq79O9k$<^)0~QFvO6FF-tLB) z=rD*v@k?tlX}Nv+lH%-IS)MA;I0^vVq(NYSVG^;6n+malaphPj$S{J_Ba>5pDYbZg zGzzCYNdd?_+L47N;fUD`bUC^5exq>?lbuVBsE&u$fmCqT@$t|;{=EN#N@Nr~&GLYd zjx^wPYH`vx3)FAxWz>17<SRErEl8Z<Sw7*-wI&aX&s2KpvBVd-O@6jHH&ONT5#P>( zh89Es+}C&YWMz9{ab-awX0M3o)J4o1GDfBGnfmo%y|wt?C&{93>YRLSv{wpO(0g`y zws(wV89p*6g?~R?&i5!44-DGNU@pt*wr-9_?lxXz%yw99wYSvmUS4}^u^|xdPgFae z^B=a(vD&jDdAvKaql5Q}l~9Y0X5HJew}{cKF^kXN`+<6as9{F(5!Xl~9F&|Qd*Jnq znJht$K5jie>;mP*O$NQg<@3v|K)9EV4ty7IZlTt&4h0BA4b^%Hu6N9bsvZ@Jmzs0I zC2=$j1#={<TU9Ka8c#~8jeVWcZhjdi;Ju%R&itOPGprDsVfNAui-N4)z3sF~@LqD0 zQ5{p<6!7micu`|3=l7Tfw^>=>;GZvBbGn)7rBNwE=9aA$W<;vC1b_RW?T;c$N+oLm zzsBXwWHl>HxbyA;{}}7wrZYw8*YzAt5wa-|*HpaDe#-RiyG8%04!1<`jA9Lw5S%*Y zC#8Sbp>c)KpyhZf@o=JvERN+OH_w*Kk3f+AqZY_B{vTZaKRCD#1^^|gxI7WxXO%lG zjHn5dciH%+(Y*@ri#U3&^Q?=hO<5YU70tDNA-lzsH-#VbIV9|}@%5NhJ>Y1!eq^mD zsP*}!(n(&%Iu(+JnVIm4(3`e@XFo~wn%d^J8AIj8WsRhjmkQ!Uy$U92@8`g087-Kt z$D#K@C$bMJG?O34@_}-L!{rc5&Lm?6J~l|G$sgJKx(_$Q3)#l!6c}z1jlyOZlxvx9 zGYba4S;R&6QZxjs+9H?u_w7!(eJiMRl@F`Ws+FbjeyS7(idhO^f5UP;V7ou#j)Fe? zx&e6+>HbS#r|slkmLY{pOJ^=<ANf;l>WhG@c9T|34(m~_ch>%eMy3dUStIE&0ooET zP0JTHWIscbd>jl_a!|{|6Chn)4KK41nPUu)6tfDIS2j*WKuDNxSZxW$P2{G8S0auy zgy%6*%r#ZK*s_d2Uvq4*ptoObI(HB+{2|J-K-cCsNhr|P#~IMl$cIE{a42pp7H#Y* zv)n@cX1f;07R`1v(Q2f~?S;*3ns5IQdLm%jz=w}t3?P9lrp;$B6j|myw)#b(rJk7e zcz}F6dIv*|d@i+;fappCfEMbQQ6D2QX18Rq;77~14xO0>Qv60)6aN`{*9JB5W-Usu zBmDqZYu=cX7Wa@h!W0FdRXX3Y(4F^N_rEzIOhtL06SnvwIBcTS`K0FM2S`kZF-Owi z`7=D2d3;O@#ZYgYVI^onVYb(qr1%OY%@Hf$Cj2@rXjq$;B^bnXnxE$FQwE>}{iHz& zSm<@_p!4t&YP@7@b<lfR@wB)1o4Wbnt;v8)w795o&?LID@9Rnf$kgS%4~}gXON-t* zZ3S4)N~|~>u2W5bpMQWm>C_bNUuCn9@!Ya-{NmVW{t|xgL(}z*z|e?au1^)#y2O=3 z^W*{%;kgdE+c_8b)CKBc?DUav^)Arlp$|ylpG60qCI>lRXE-E==nS+R`2M7(F>5b! z!p*@}mt%bKjnCr0WpEQ7b2MA(<#{*PD`!F^b4!ON-4!rUs1fwaiGx#G@xndrPaldT zUC|ZNb&fxvW7OmOr<Ov;RMjSSZT!yNrH-F}NgR0;HGW(6m^H*j!scLfZbi;FyseMu zM&RJT8lM=|U90Mr#<v+0|F*49*Y{Vq2Q#^NMG#=l)p(tmw%Dw0ck(rP$0bhK^<rM^ zR=t@XQS@+34=n!*1sI)j{};aZRQzw-C3mIKBf_W9Rch`!j_hS-Jtxd8{E$Ss`Gj)k zKezHXFW$Q2nq<|6_e#|cxhcJD>(v+#xrc~uM0lvX?rur4vj(LS%0*jopogDSz!@u8 zH13?W!gwKCO+tvs%m>mJvr(;2$O1N*D9l>+d+`ve{~(OWp;O`0zmcRp^qlQVSWa5| z#G!;p<isHKDxJB8Qu^T~$>fyzeP>s-nRZ3LYxtNa2$|7q3b=((ivz#PzF;Pe3AG); zh6nB9rbte0V*X4VvHV3$xY$1L)G<AjH~&DD?u>PgSdV@9!{IR?lZYZUo9ct39vzfO zF11F1zoMb-oDAe_Uk7D>{aZKd$Icm2zAEsYi?<=G$qsK+Z?+bHYp<{8w&662YPLlK zjZSM1;e^NZyE?s|I{VX~{z=)wyT5ml{tx$xHVZYy{(@~~=1>MZb$33@oZ84$e};zJ zLFU)Hw)gWmk#O4F$yuv6r(B8t3o4xo(H81qNZF9j5uptuZKf#-fft^A;$=x~Z8ADt zjwydvydWbDk|~K71>%C3eNMBiK-M3G@Jf4Vtg^w}VO$wihRra*m(j2VSvi0ASV8S) zAf0|ksQ<?T=4hT!7s#puNY-FGsH#(UQT18beU^;XKKCmb4P~k@U?v^<FOb4u4SV4N zP_<6H)g!lg`rcBtiNm;O1y22T!NP!d&03A$E%wx8fAl>8s!~gT&eaRVsMny=ZRDZ7 z>DQWLKGpj$DvZexZDkyOvKe(?ZAxadR-EJir1-5_bIK5TT4fRj1}G^>`;s6M%lI@- z1cM~I+T<N0Sg)*BxjDUrxc8fLId}$OvDSi`ehKGKSuN1Re4k%MmSy5ikKzNu{^`(M z|G^^Y+q#+g3;ueP(3k|oKPS>WKK;fwy8hZVZy5B--=rY{6l{A$+o?@G8vJMv+<1xd z{`Y}$s;EcdY8n=9CNM2s;q~tV=r-@af`@ML99p}d!q#}u4a>A2cTqi90GrCZ$7?B$ zR@YQzAlGfsqjdU-d?Q&RXWZfHJzLfZA(>&ONWB26EUYuQZ#Iv%#w8L&;OsuT2$TVS zB&&$hJ$n5inyRSdvUTqvY{Gq17_dF$wW!(D&xmR1)c2>r$lUh*{cfZE-%@rZ%2~EI z2X8)gskt~7qAEgrh!g5FRjGZ;W8H4eif7?T(^COg%!q>Za@iuQqKG2b4Pe~Y{KFE3 z!_yQ+vWP6&u9iQxwL&Xs&(v1V&+_(+@ui%L5#McPzB@!jZ}+xI7n3-q7Ib$L76?ka z8M~pn!LJ*3+mPMGx%-#70jM|X4&ol^tr+yu!O8pzo2h+j)Uv~t9@mpnI<wZ%%KTg+ zrBqrHW}Trh&NzsYYFsprAM{*y+(`psCayG_a10p}DQ_#hr7?e`qDH<2Y^9R$<fp6{ zDP-(EH<B}N(pU>NH7Ve0vvu<yL0qy-1%|gj#}k?vGzK*u<%$Hz82Vi3JbNB+k7^XQ z`3pZ1*ywltjI6(9bNVOl-6;_NcZIR~Eqn(0zq0@cL@4y);pDQ$xGWAkM^*76bF^_H z4+lLo!wb$_<)h^9lDzRH-Y(=$o-cTPtd?<Y*4kRQHH1G~S<g%xFjoHaG4WLE0w6cf zEP@LD-EVrSNr#q!pG*Ea{laAF;E2}M5ntChvoDpIcSDvrOrjN=x!bqWrigr=z>_)I znljh$!z}`eO-zdvDaGJ#Ys+(QSbAo=vC@9%SDR83$PwwKfNb20lstt@I}{np#DhWr zk`(AXCLw}q+ua-B4D+L#QVI$Sd%>m-A4P!~83#$9-nl69fFot0Q(KsSQ$M*~xcy0z zG%-lO&h;GP9$3hvIhprj0E?DK`SE<2wDh|<O<!luE~{NTq|0=C$<CgIGQ-C;sXX0Y z<%9C3p9YpQH>2bhXWVV-A&I`3V8o9CcGTeDhZ%<sa&Qyr$wGZbY<`zSw(!5u*w=lc z%p2tNX2248vME)-qJ4ws0k+RwQnu>9>s3HR7WHk>tKZvn;lJL|MNYScu@*Yl!SM(~ zTUF(H;cdDsG&;=ZgNy_A$JfEx8ab_U-J(orqD_j8Eqn$PJ@?c@g^LXLz$V6tj+l&; zD73MM4H}T@!YjzQ&we*1CUuy^n!Kjz<7QCF4J5jmyPGg{c+^4a){{&BE#+opoXAKS zz@B&bqh*L6kWhDx#%qbsX`n577&?hX@y*jIX@=t4=v&F}lGos!*^7vmWIiJ75o?-1 z%grM7BEQlcZ}_m!+2y%wgh&elKPvqN--Jf<^GM-epiXJ7!DOEytKas6D-%1fd~u%J zF6EL{OdyT;2)t#nnRRI)ARy{y^9=*Hyi`vGKQh;Yf-JP_nn@v7hQf>~`xJq(DJ0#m zQr)?~m3=$k)75KKVF8%K@DETA3~#;lTlqb$pswefqcccSJ*Z&8t8aiCCrgHQ9+H>e zVzmOf=V3C^cv6=24#@+Z4L!cMEcy0W^}<YCQ7tv;Dg)nsIQ5O)T>S2$a>5p;cc;6v zCJgtAxX7@5oKGSONt)f6NU+fV_YiCfKlLTt+&A#g^z_dZfZ`kTM1eKE9on}MyUX}w zv`zakm$^XX8;z^6LszvabEuCeNRuB*-%&FZnTS)$f3(VF#XOEz=KYql3troK)sp>j zWRx`FHw8TErU3mTV3C<*^!6gnKZtv0jY5TN`8wIbZ#8Ee)KbtEX!I{kaI@{l9U+^J zuP_qQ^1okm>xrha@2mSKLG?zmLv;1t2PkJK34ZUbW=sJ-%gXt6`30Y-(_&f%@tY}O z3s=GvFIicMOZ7|g>jf<P{ajx%>K=2o$t&efN#tWqK-9KDFA~_UsfCs9YS6<JjAx^H z3w$=&Qyfif&V6foBk%#q(uJI&>TsfI*24Kye|pH0UeL7a<;CoC3=uQjU;5VcRzn=M z&susLlETB`weRykxmUDA-cizx*SPeL+E&&4V>mi(okw7UL+IjO2DpHdY3)9}3Bm_7 zM*uaQuxe5Tpt*KbuRL{(6<Pvp{|m9;Z`qANfQ^DKNMj>GPL3d$+J+iYr_*4yl2xvy z1>K(g=OXmKwJ*+R&cS-|9vnza#>bnAjwJnDL_yA1!x%B$59Ks6uB1+)_ez1*1D~fR zjb|8|>rOhWuk*J!$GAg7PDiK+ViNo4gGK7!g9t92&>+fcm2*puob+bHxN4>R>gA4u z*frhyrBt1j`Sy1BC`W||nz?&I<bgMDJA}QJ51-5X8KYd>Fn_9Ya3q3j<rgNhgg573 zC)3XcZpYq*jySuel-d83yL^|5B!2j?895@E3Ed1^qWmbSNwGZXq@xacAuM&=(ER+O zW!;_9=A$-=(j~bG`40IKg|++vd29clI^FKkK8=1nZpR~r+Pn!o7}WAyDEKX$R^q1a zXEg_j2eU?XyCebj<0F(p2j*laHUW2^F}ZGA!uMI!ky&$5581lS1>6+%dA!LT3OhL7 z-i@Cg8jd-uV|k2drlIxhDW>$VMPinxe_ReXy5GTfD{kO*C(Eqb!$1>aI<MAp^&8^G zgI)yt!@~!Qd98IFj_W<1iSIxTg)i3IEmjUw=18a&klWn0_+83-oFjYlJ7I^vPcXpX zYmywe%W}t4uE0@3_>MwfqLueH2_**9gIT*$sl2$0Im_GCw9<vS0B||RG$%rkBYX*2 z_UEo3f1tlo2-VPe!nw_1Kcm>YXnVXG$~@feW|^s&w>psQ8IFK}%Ju#lVC~yEGo|0_ z34DNY(ksLAYDjY6BqN{pXSWYOnQpG-^FFO|?9s$dSz0ZfX_+5*>!bIuwOi8a=w@bE zX8LCh^D673|CfaAiD)_iDmRLTj<0WEfL6F;-$k}J=uP%kBESWSE$R;bID~Mer_APE zoTt%b3Qv<$W*|u(tCrQ0%)h@q;PAuLC(dYS{jeIXd>oa6y(JkICZC&TGB?6e5_e71 z5BME{jYImLo$vj9VuP!IJLfU)TedyH;&Hs?TSCTPe025fE8;%UT<BGact^H0qyui7 z#(nm#&4Ql@$v8F3)*J!qMkySmDWgVJ6<HnIJgHb8({OSI{hC6Mnb9`}Kh#j|NcyeO z*v|OOHo2w7MXVQz8n7dpCu^uoXePI|0Yl8yt&|+F?}gUa6_!)iq+ph17B)mz>w)NE z(yevgKASij98D2ga=fQgw+cs5$|$`110`g0RC^=Gi)!VSI|449VKo9Rl6Na5;9s<3 z9>HHwG<W^Lx%UHXYErjgpF&H!&nzacuX}i}0%-9Z$9hMKS&r5C*~nQ9S+G-`rtz>5 zx`y;Y<!=z3nwy3scAXs~8?3&KK}))7M@6=!<7*^m>wgxr6$*?N2>(CY;d8FXU4oUv zt!5_>Xs8Q(mH7E|Kp98LhIErJH&x7hU#xQY_x`X5p7)?Y1t~g~mrX%2o!&~)ih~@* z>;SNLze)^`_XZ#nPft|KGP7|lvto2}Sf~doM9`GxzraI&HFh<*2IhGoPXX!grEGPw zzCT{+uM(a^ZoGc)3EHwjmF3YHLplwUb&bf9Lh9z8YPPXjbXv7By^dW^fV(R8B}hx` zDUdr&lr1=nz_=ZdNEgNGp~>es!wGVbwVbjduHEXd+VY!+Ox$);ofn(?ZQ!PDR&DHy z{7e|Bi9QkUkTdb;+DyTC8)%^I&*#wM)1*n^_Se4&QneyeZ4GFP`0;L+9vPM2o~d=H zE8;{j!wnsn{RiIIYdViNpkh?*uS#%KpS2eN8e=kRBPTucG-00YeK-IKfUYk-Amb{P zv+-N`Vl)LjHJ+Zm0C-!hGBR1L`55e6tSF&V12sMSoGW4=LRzN|=Q$6>2KCS&qk=h( z=9LiCk{RJ+TJnQ^VU|Tn-|dwXvjhSnSKiiYsWD?-{Jbtq5w}!k!MdI6;bg*Vr3Ms@ zB*Da+jmn@EBJ-AN1BZNv#kE|1M-=Gk?J&s5VXsX3_D0BHMk_<2E4taAEdnjg-i@Zu z>>R##w0pAO*}j_WSdIiID3odWWx4H4t9%F9%;1nE@p$*Xp_@)ToB4t5@_uJMO8c8k zO8=o>HeX}OIMSCSFB~>Net2JakAo$}^1o~P$}-V9$a02$9&E;R-`qeH$aBkat6ppc z2DOjR*TsZ>n%uo7lf(xg1!I433h6Gf;k`Fz<M;&v0@7y=kBfvXKdSI7cfl)`YZn{T zyqxn@&n_K4PZx-#_9ao^DhmRk>nxhJ%GT>m#C1!fP){x0j(8*<J)AfWJY!{wpy*fd z+X0*?skQX;%1UTaPmM&QFSP-_ky`o7oaN&V2Q@!-hlv5U`oS;9;S)PLoMDCs;$!PL zUMEBET`{#*4W46ka{~i8U&Y*>VF>mND7vk;A;Q)6q13kG?|6JC3}6KJ;Ds_e4k+lG zdAPHf$wj5)XUEwn>Nt`X4$;Y0kEJ4NM&9KnhqpGH)ru58lJQoie!pGYKmWF)_Zumn zz`>89<B}0lnT3sFhx>g7rS}-k3Y-2^U@!@fH5*?o`R#I$zIV`t{$pc%r3{<e`HZC{ z26AacBy`SpqRasapF?}VyS&Oq6>hC5`2hGYa6lm<1}&4y&WqIK!DDSW^G73$fE4b0 z`~PQ>T<0e&+~l$MQ2g`2d4al%&F`)KQr9(fK{Kncx~NoeJL~AQn=Z)zyKBTz>u`~3 z!|}TVk0(RQMnmb^RHk6Qu8>Jvzb7}CKxhpU4@0lCt~pY#;=PdLyNh##(S?%2L1K|( z(v5c#qP*z+WYk)JJ<-~E3hG*o3ife@sr?2vypR<rdhKU>LK;5{5M8b+YBtK%?gd|N zuJdVsXL@k+Azx73-&TCDphEa(fl)G{fU|NW>Wio?r!~D2rwwV=teYRR`&9_`0p8@& zZWA&u9g-;by-u>Pbym1lC*fwj9>36**t$=Q%+}X|gKpUpN(ph0jDMoL&5}m9Ar57j zG-}3Cj$nme#GY9(rJHmRpNF9GCLX7*?LvTfcB{AeTTwA<+#*A{IV#U&eXP4Z1uf=B zlF0I)Knsqc8qZI(R`g;pFsX0$q}gjfv$9UU;2~uHUP3P_{&(%+L`nj6AWau+LMjbO z4K3bR9?IizMx#be*-eky&wc^b*(9fR5w!Q>xo@$_eZ?XfVkuTK8y#qJmLwS<1^6T# z3~E{Bj{eye3BA#n&N)(|iszpcR>2>I0l$kRIHV5)nnh(XS(v=E${A0J%x+r;x8#m$ zx<Kw-Wd|u!(lU<WQT*&1tKf|#UBX=dbr6MkOYIiLz;Iv`)AFTUx4$|=FBqMY&AC9m z{fLZjm!6#E&R^lvBh_V2t(T}t*z#v^c-R=plX|5suuMMZp^MXYR@qkQAsBRj%q1g^ zSH7dtN<{wmA&$Y~F4d`Ivyo*4qqzcTDICSj>1d8=ud#F<yKFda8reOqjvllXT`AJx zo-m(&$II*)I4CE(Dy!+VKRESqDjYaCW!gW$f`Ba)7~UqqtiOA?1u8N3@k_Kgrc(Mh zB{a>+%YUO3r8IxFIWcbWwj7<@ef&Oqb|0Tia!N8^PcCHELDb@JzV<SBW4QH5wM>)I z`Elyj5HRkEFk+z04oXPx5<r!Cu0R`GJorI5zdzJ+V0Cbf|0qix6g!0Lv=SV^8mLxV zp(V0CamcM(lPln+DlRcKI=fN;Oh79IwvR0w?78e6gt&Ui9D;S!MT|^MQyH_lr1(Ak zB*b@T<q`r14%(^FfJOa-RC4K@-aNYw;WsNh2Mg(lLf`fD>K7i5<Edtk%N=iS;0olX z(iiRnyt;m?)~09w+q$y8Jr#tiH!OQHv5M%twT08E7g6jsxQf^x&(`@3zeVS5L7jlZ z4f|f_k-0}SH2<E{lZKzroK$$F-TvE`!slhi&-|j_=wRH*QU>Oj4}?#!@B`fY&jhX) z>wF$1j?$&!<%sI${%0Dy`TncxL$9Y#wI0c+T4}sI?qfVCOc+}v4~Y_pd`GWDbX)Jw zZIu@LWdCy=j;JDKD1h7sX`N|fRVeNnU}O8Q{&MKd1dSG|HZE7#MP~Etwv^JGg<<a- z8n(O2ozk6Ryx2%D1Zi#5xT5}lx_q`phC>{j?i2mF&SU}sJgrSoy<$=)td&KD2x6FL z&Pm9k=%Rm86>%z%w-Lgl^CQ}yQpW{f&eVymB9F*Zb+Hi8d;#3heKamld!d!gin4fc z8M!TUIdn76HXndEWRG;VIQ7XI>^88*5z?w?{BU2!Gi{x$QYfvA$XA;$xhAMr$^i)g z(Ue;W+#JS}QkK5aaTe<2#v9A57o3wsK&g`l(r)_K#IjF4yD%QNe(2s?iCt|?GLIGa zesAXpn}EyEgoc1+IptnIDGC08N_-d#tZz;K6zu3oh{S#r*V_Jh5(R)+BLf-evK!A! zks$N{%2m?SE}h6^_DUP6e%aVHrLY+NNwN<O7+J_cm6_t%`iymvqvd()rPTWnIq28O z*r_F_)zeYbtRV((ZTjrF_Wg>~Q*QZHIH%fW31zcl2kKlciZ+LuCP4R=ghj)prPgCR zS$*}O1ALT0DYt!Q0rPnXYo7|;W4epK=yYjp7Xf3_206;)hBw1NOII$lr3z}J;sACw z{q&$7<@9rubYZ6+W(eZlLR7hXvuDUQ^RRHtT7NdPmi=)f<x^ozq+Sv&AZxhW&Ubh3 z`fA2yf9Y<+ZbM?a0woBU(-3nz(!}yl0e2Qid8Hw+^^=3ughln1Yp}S(B(ac3=4VVJ z`9(Ht>NYMXWSD~X+D-ovTX{z*>#m*&ezwhr&PPbuCe7%aEeXS9Ni+JLUjX<8Lt-!j zM$?tq0Oa*#3F~N{^HH7qb}^U4>}Md)mz==L#5+3z+TM6Y8<F=rCBMmPXW&q}Jfd!v zv^AYjo<*5aZBR6;zI{Yg9xHv51@F6Lfc*8s682$V1c!+qP^??#Oa!Q(Qsr~*+8MX- zD9??~m_0~nhiSYgXO`xQmCJ>nNTnngqCB0#h^I;RkFUefiE<2OGrHAWtz5=iaVZqr z-DGQpFJ&YED>liKqvefRpwoA$M4C-1;gjZ#*<UN49`c)j+c__z@yLla=-FJ?ZSU{q zQy8Qc<C+nM>zb<VyLn@cSBYxu9)Go;KaRF2Q7;FpV8&$!1(3!YSv*sI%N~%LU0b!s z6jXXL<Msl>YLN?&|56&g;W8M#^D4v~iEj1#U9EomsHEQeCkXjXi9cSMU-racY?KME zr7BsPi63}bRJ{LO>Jg04xZ@Td{2XG1ZW84NnRpC*0!YZSQM<R!`?S?py}y5ddbLU? z<hxAWDTqt5%C9O7&Wvy8SJ)YOC-Gq9J@TQI|H&ZMQmsqB(b2<X5Q&@;Bjq|iR?w5e za#)*Tvn8L=0CP*qD)K}%_Gu>t`9;Miw}UC33ZG+hMOx%GgMz|2PuI0NT5W@k<x`5$ zx2Tqmp70pSsAbbXSe0PopHyLyNvQ5gDynW}_ddNb!}>HW|LKjn+B)bB8bsu#Net)r z?sgxmX;caL7|w1>{x?|eJz$W^-o=s~G5aHalWwWA;f_w+M};s_31M8IwwMKtxyQ!> zXC)O3^dtt%5p10~b*b(8z1P0*c=UHl_d`Pl7(ZDEQJxP4e1y55Jd~<e>*G$XBLZGc zu8RxjG^`Gzx2bX>rbE3k#5VyAp7yJZ0WT=2h#D7ZJihmd_F3#B{V=!tX-mGNBhif| zIw`{dUI=qlsyo&n5)Au*J58n!;3fgPzO;P)XS)dw`j}$LE{G>3=$$8`1X^^3S(Q)f zV?-#FC44TfO0Pja`?GLQ!7xxEGEh)-wih1U@6?@kt{0Snv*wkUToMze@F~{smY@#g zmhyc#p^A{joNZ7cPZK4JgR6dX>=s-r%4qU)OYB^{#gf6rmywYk%Xbhk{}WDP@rQ;) zMpK3hJ-@I-iA084+$mQwDsueSRCnUQj*a=#HzzqyT~iuTWYIruljCpEW(R4H!f8jp zyP3ka&d5&cz9=Sei*AzJS+M(+3S3t)eq3v<xC?6fc0M$iM~2hj3<0AZqY(tD9yKb- z%1r%B0*)NnkMouWMTk&%Adr93Qi*!&y0{Mh8Ot4=J6M_!08J%^sNTiv*BvSdt3qb8 zQw6#{-0{g&`!hesq@`-Iw1hM<RJo-fm%yw)!tj;^j4_h~%R-X!b0Ea|w<$7%V1}<z z1-@LTzK0m#-XF$fY^A?bs#!55(sL2W4Yy2C3RUIY?!~qM#V_y)9grf){Z&qY%o(}- z7@(op_`LW;Q!n$R%N|_j0w#Xau&p2?+5IV6yA0;kCMw-AJtC4|v3P9&7hcHD^c!}c zLqaN5bem1QSwWJ+T8oUcbK4V~dE_U$e@Z}AgkyT8au7(TOq=nrv3#Yx(q@_VWDcgm zn;Ra0bd_#*-pO5m-8NHY{if^i`hr?--&KKLFT8wNJb9T?R$#+$aMnXsylKlk&4EyP z_g9I>OtPzj{EY@OY@ArJ;XS1c=N5}Z{pvWZyLP-Eg~t4_s$7-U3lO@q5$ox6{jJmB zOB_Xqtmw@i&1RV}wRlI1HIv!VKiUtxM&J=o)JS4?-c=E%0PecK7P&wR3flMR%729v za0v7byuz*z%YilvS9B`@%(AZHy7OtcEH2S_=8VD>T-7Qo-4WL{0-b(gO|~~x(7QU+ zL3ba&;FDt8&2K_$OFSczy^F{U0ExmKc02g|%Jhoj&EdI%4O*}d1f+O~8c8OXJydwc zT+@NB_YFo{&HRX^F{k?c|5N$=5yW@3^(k%$I@>->i)HxA3z^?J@9{;2Fjz?Y>YJ4G zcwyfjrBnCMSv);L2ppO0J6pIMxjZ|!d`7N@&;&Z-_1#GapguH-NT7b8{$0x7tsWzN z0PfBHI73`Eca+q!Ycgswa`&~$&22)DjC^SAyn{B$4+Q&x&EE#u%|5`6ZXWe~#~bKg z9%J35*2uONcJg#4tPE+xZ{7V6>eH@}gz`7h!@e{sLufhVZikGC-4bvkr9=c&Of9`u zH&f&j_#zZu`%?@>WOapnFBs3n*bOP92al9vud+uOCA~y|h$IO~>+i7yT=Lwt?;5E2 z@JYE+W56(Jl&?MUm`te(KL^M`-)c=}A2-NU_fdo3!KO(OgVykrEIoM~dX`i9EM=h- zl!ePeHx~j<vSCs5;?=<klx^!b17HO9fLY9yAZAtnw??@QSd<dS^Ur<`U9|EDTkO#e zO5k^1vN_8D3ZHQiaxRi~G|d_V*Q-aO*~)Jud_H$=x>WIxFrvFD5EfukmY#Lh)vkGQ zOT|2@5?PJZY^B8^%~xohhkGq{(^KRVZsTA<SCKg}I*9by1}AjU5vuXUe%l9npAt0z zI)l<*x&=$NnpHTtJ)ha~_*mh8k%2PPcW{p^KygDnfBO)JrLZoBX^})%fsHSrTG15o z)W1ZJiU0I(F&#lAjK<o`?W;@T+dSIR(5dl~EQeaHR<=zL|L|^t5|RC7ryt6dxGZJ# zGl6AwBb2Uqe?{?~(yAyqnL`g7SWuK0n=K5yV8}<orv@x@h{&YPxw1+l5b~@Pt+?vT zKpUi5S=j`*ls09@Q&DOUBa{46-u8~0(T2l`W!nxT00>uS4m|K6iW?UCsF+^R=LNcp z8tJi`6#8>M*7?5-T9>O*;`kB|>5DLM`KAH+`&b4bs@0y>xF-Y_H7Z`nDI?Yr8>9BK zupLS)Q&4Yw%NCP`yGT}H#3Y;anh>~=G`ZJ;#R52}E@(4FOj7R%1;vSft*8&h;?esw zLOOqYHT_8_5iq0qac0au4DnI_N2TcKATHj)Vn<h?1tS=3B>mfGf++0-Ne`SGVsJBn zG-#_ub+!3~)XJ3AGLfL$hSbJLp>!gTRLae=&s(zPrfb4wC)<keJCfa@N#D&v>?r%u zumZdNU+Z#h!JbJ6+V_z>R^7f|W>!et+B^TlYQO!k6AUG~DeUn+oa_n-4vVjJ`M8n1 zO3I09n^uAnvg;ZBl|*q+-8VoMt(Cf*rZ`@!<K3V0zxaB~sJNP?4HO72!QEkS3+}Fi zyAy11C&Ar<ySqCCcPF@n;1CE9+}-s~-gC}(a_(L0{+zvfy7#WGdb+Es>uIWn4tRgi z?FZyOnzXVYdfPTFpY#c2INYV)0g-n&%LpoLC<!q%N``Tz8QjVKj5?s<pYxZK1%sEK zZ+)s?ZGpDfy9>^Y4XV{g92bPnCcLczn~3ppf;d^Kf!ZP_0j2<w&mnT3KPPqGdkfq8 zFtd>QUN+y0wLlaj&}HttyTFn4c__0a-6~Yvuz=6-cheu)2##}?vJ$r^4hoK3;TGJ0 zGQ&6NC7qE|qnS!x^+1w)`O<_AGX_fw8Sc#pF(6R3*2~;Fql|%K)q(IsWG1PR&~Ts5 zEITgsJ|wPa0o_4{vab(G)B>F1-YVWAJd=$%hVVI`P`c4Kagukf1zFA5@G&Nkj-eA` zQj5civ9asfgX1>ofFX(Tid>x0zFs778B2|L22*a4v^J?7!^qaE6aLe|=TXhPs?Mcm zs?Ui~alhFkhiDCL38}RhYm?d^9kAdJ{9~)mdYmCJmR*;;8*}S(^I`#QprfCLJ1ZgM z#rIvDMUsW>;GEr2!pYjoDIVNOL@y-<nd1;FFpn|Ykbt+=s`&HCoPsOd7unw?Zosqd zGudyCs3vYyB7!j1acHj^rIv@VfphjTg&-{dVTnLe0d4yJI2^~DLUp#EZG>TouEhYT z%i|g=Cq*NcMTU2DCWooTrn#@5N~5IFVx&_Lj>iL}xyQ%t4CDD&d>DUytSUA_DE|f# zq}&4C@Y<>U7Erp~xu{bc=@vm<(NZlY!*7!Hu?rM%P4Ynj7L|}bR&#Keyc!BQVktu5 zNBqsOTgVD7sik8oENOYcx2e(YZ^Olo;i?HVUj8vX&^xrOqp?crZ6<fDmacDIi55#g zc%jE(!iTrw0tE<(LZB|Y5@AW@X65Sm&ytQI4|+*&DdU$~9eEqyAbiWcGJOWL*kHDk zREy<A>PfvpWVfv6*=HLzE+5LM^%lM+pyt2dIlwhcw#XEUAsIkr^sXtu%`Z4k@%-V> z^0j>BThs2rz^DIZ411>G*?@?93%7nu4QrhJc($!2$~LvB5xr(qa2$h_!kUYmO6&Ii zV4*M+B#YD)groKZXL-3hQB(`RV8v6`%YqBrZqiE;kOyedVdtpj0KTK7)OM0_cTBTg zYLzs>gx?L%3Ygob<g}43mreehF3*;%F3^!5vvcnM1!tsb+*QoP-nLKEzmFToSZw<| z;AN&@p6p=G!(ZUe1O?{469PIljFIEmhhE9M9B%F#8vzZ4WgcCkq4p|(T*;8sR%(bM z6iJ1-7G4UiR?v@6nOgo??5Eoi-SQ_;LL;Jx=e{V<Wa6^Np$H0N{`=PMd4YRm+tQB; znJlOAZ~+L0{z9vK!WIkOqe)C1b2jh>x?z<@oD|c&Xtt643@DZZVsUwN6tm|jx!JrP znhOp~jJ^l6;S9{WoBiL4bgPE}4i^~hO?=fUv5nLtV>@zY(=2f&eO#vnl1LTTh4VKE zP~jbpFyS!GFuv938Ieb?N}?mNd6<{Kb#bNJD!kylpP!CRY%cliEONj#SQcd10$T60 zqLZ6h1X#eeof3MWU-gsAah<?$JGDMj9!i7{>W!WUY|FJ<ZsjURPHjEbX32+Cz2<e+ zgflsItC>EE2Ra{RwfR^=auPN}uMOq9gv{2dTH`0M9rPVM>3W`P3w?-Rl1ynlN-S&x z-k!I*>n-)dyxDFs=`vDPjb-9}G_H2S4qN?F-lg2F>CQK@rl=@<Nq$yH3NI9jm#jn` z35ypepU=Vd39wc@ml8Eq4q}5JtxF?Kh37bYVo#STi5>eEYsa5D%EEi>x8JYExboS_ zl<?9FF>j*rRqGVP{q#3d8tCD3dXcKfavjpMIp=St5uVQLKCi>`K7-4PvQbrd*k6y= zo+ub^6KSMaOZ@n8E(5*y($d!p@ZSILJk0&uE*Rur{T9#G8Hh_K1!`Nj88a{)rM9=V z3%2DqSn;_wk;)A^^5;CNV3Cu0NvB?UhgWO8q1w$`jM#mCY^0|gHO&NKKEunf`6X|N zsM~YS4f5~1ni^MQz>+{Q`QJ{dJhrH+lJ(kOP(T3F6ati`%vHiE9z{@zA;3(Rddm${ z>iBOD0v;RPfe=6eUU#qqWCR$(%}F|^fIlk1qZt4C{F}-?j+S?W0s_H<_NyLB)lvc! zl1TqIVw#?6U7EcDpJK&d1PS<$HF#>cig~FQeS+IT*N|8<b$GV#LCq$@1mAbRY|#5l zcKJY~qn`2udS06)bsN257d)-Z(i|B8wRxqpsFsC<D||0T(dv*o0BfqLrCr*laK?BV zD*a#Kao@IC-s1v{n8HRw^b(+Rgcu6*-!*7f|5PoM;@pXxF$Y2#%THZ~?ohaW-F{_4 zn}H;)8MvstvhZ5(G!OB<I#E(BGvV|ou@W4`?w!2<N#wC`G)Kb)JQ{cP#|dKk#meer z8Jo_6$>%b$azao@<u2}1k%UHLxg!TOTg_c<5N+?~{P=PIF@wXiirzCGW!N{28O4om z-GTe`SK4Jg=T-HP6Twy~gYK8kyRTWX<BVPFhjcK`X0vyN#BVALWy47ozyk#CFAFQ2 zxcuMGlfShWaB#1uTPPB#iR<EG%*gh*tp`GzOWm{_k|={AqT~=vvhC5)Oj^47-;>1~ zTstBY2Z;$>a{fgqBc7Sg8@J5O1{IDJC+YI0ed6VaiWMl)oj(d{9RiP6nzVK&9~5)! zR#aq@Xc-%yE~oeu*G@zaP*@-iUUq^F_KxY>f*2rdPbFlZjS*n|75n50qRG<7xtLSh z@Ql2p@1`)kcIHNuUC5x3yvE=@B8#XZMm`=6(8xC1Ei?9j3AR}py>y%{#v!Z_RZ&Af z^sZysnvEvnrsZ6ZQo<nV@XX;Z=7!U&gt;eaixEM2dLO^DQX$QS4v&pV<<vu!{UVRQ zvo>Z13268lpC^fP+%!p`K6`=ho7UQluv4{0A3rh`&GgekDL28O;|{poahe$T@QKnd zC3<HU$J73f`aJ>!#?CZTaR$x|paLk1kJDQLH3}gGE|*e5Bk_yNiHZ!52PT%79Jv@< zAtQ`4;v1n5P9rF&wgx+v+IKB93c~YRy<y%dfiG>jzo(h#9+S3BL6|15cfJtA1N>w` zU9h2Ts{Hlto8;We$N+P-elx_;I78r?eIHtWFSn@Oum=ysZQh=BY(AjAiwnb*T)89) zkGbxFG>(KgGfcR-R#hR;m(fUA(ytqNg}C{ZkZ8jzW{dl9m_MdtQ*67iFNjLW6#d}m zZ;#P*_RQUhyKpWCuSf1Or<qP7IGzb3?K*ZE-_B2?ZS19>wQGE5iV3DJPq)<0w)&N` z=rYQRkH1fYBcI~liF}M{i^=^v7W0Qkv-gb{j>oTrQs1m}`gupwg3%iS9$i4TKSRw0 zmRfSW#3d7S^XN0P+qRIv;&2<eH!XkIPJFeU?@y?@)x^>(rEeVQKt=l7l;-A~sw!^? zN2DEzqm-Or@T6NiYB^*@0fHo{j>iK+W=+?BLOfEaz#(B^Xh=3{TxQpw(V7De#ysFW z3WB=moeTO{h_FpKMvVR`+L9@rd&4P2d*2U^WWV1@@ab|8j;lGPQ%+FA18|<i7d+H` z(*2Ys0E-w1VD7@MX`h~~weGNFO`t##jK>TsbF^#RZ$=o@mP=k>zt}glMI|<isqicn z{-u~nw50xRO?yp4jQvadWKE<l_pgs{c&aWw^_uAw$$;OkdiIzaju^BvRp||lQ3|>o zsZsclbDlq8=s<L|T?iv%Yg8&wm~_T{(hyfuS>aLsF2}em4r#me&8CLv-rk6?7Hjy( zp08Ok!i5*E-X&WQKgB+e;Oo>|#vcn}Qo7{W(z=PF+VPbIoX4Q1?nHBW=j=CzK1(vx zk~`$GKjJ(_W@<L`mTZ{HfYciqpRK<<w^J!UcHO05O=PNI<SC`JLsb_$Li8M4DYADv zO-ih=&I65}_fiaMg~^%KrD8KEbie_u=BXC-a(CI#qxXiy2s))P9jrtfa_DC~-8SdA zxE`V@%+I3la}bkL`93ER)eb47<({d1`Jwg4c}S~pa(4RP%@Vlw=!Pe*UV_H`8%l@1 z0Y>L0OKyMJJ70BU!RGxoePF%QmgchGhQGj#I;D)!wz_|uk^i9;^h^?gfCSWA-aB%{ z?@rCJLBct6Kqg|jJ{u%n_uRE$m~?I%swj0Q4-+~yktj(O!>92O1l;&`<p5(ymrins z@(VE6tyuDdxP($0TB_}IeI;}e%$s*wObbbTjE1@-L7DW7Gp(5ypQ)Z@qKDpoLSwwH zfLb@DFzPz~5TDYrHVIy*5z?lnf}uSom>`RMsE?n-dOmfhE*2m7jfw`zPe>N(T&5Ny z8c~W@|8jQI5Wpn_JQThN2EpEsd<YM#C>Cu^dZdQ2?fFQudF#-61Vc`Ie&O)pp&|$^ zOzKH&4_?Sc-dCqttpAtJc6fVJkxW3A-+K`@7A_1fv{v=hg{@}cAj<vO<1Qec^fOso zli7{Q!{P9Hk?)b#_B6fZd75#r$a{?YA0lY-(nOLf_Fk}S5U>#Ks<jbkFbj}UX6g{b zrfy<^S;*~V4@g+OaNG-s!t!;=R|KK68xA5baibqV?|k(%KHLky8_bcD;{xQqdM5;U zS}UWkara;pvG7ghB}IryL$P7AXUYAYtNFv68}MfM-VxD`Sd_sYYj=AIN~>ZbhXEf? z;di}s{s%n2{Fv?yB=Q92t{!Nk6`^9xH+6zhb4MQwDlD4p4lnBS)_Iq7)zm1?qOs6; zcSjZ1pzKhtU2CeV*15YG$VXA0V(JkW)v(C{ZICB~QPW{$C<G=G1n|QoA#SR5F_C~) z97<g}k)nKP3}>;B_jh^t?LI#1`Yn1KmkH_5&lgbcNurIuMXBAk=wW9tWH$$rQydmZ zAFb(t7(jn8P3Co}DUdO*95*L%@|So_Nr^Qrf)JQ#-en$q6hrrNRRw;<!FV!B>StZ^ zr+j@~3}`i^Wk#BNOOL^<jr|=3ZNabJ?V4z8j}7q{>{hE(2v7V8v8m_V)&i}Li;vr= zKW#rW!;uO(>(=ivlewkP<}qE(Tz@U-XNmUKd!Xfja;=Mf%5c|d0)>F+G!-k7=%JMe zc=8pO8;`A9rA2O8K3hJ;v{q}oBqG{)K?rj@WvO{_Jd%gs1iT~l?%bjuo=Z}hi}}qR zzQ01Nw-9?5gzE_-lu|C~3~^nB)c<rlAJhO93!2<9{IjMLauSx7{dY|V&)i723Mue= z1*+_+H7fscD++IKQ`Dl)dBiw@Vm_T(01QnZz;n8lt(VDA_M4Gd^;9d_jm!X`U!aLJ z>ABc8{kG&0_2rNvjl;d<2BNH0Fn!jWxvi=u)pgCoxGl4VY}SQhf1`&A?Xw4-B1D`v zLAI{P?yWNwHjP0o8ChD*%9%iMLw?&nIa+V8d{iWH%>;$GGW9#-TAvw+;G(AEBw5gF zRHy|gez>^(+VkZibr}G+89kXE{v*@K#oFE`)0j-42)d{m8wrJ8v25x!j@GA<1DbTX z$XjQfXLSw%NGWhG4?SCDV6)%@)vrPyi59LJa6W>Nnqtw~$$>PvCrg7Q*6n|?#Q%l| zu;Ux`Og~wg&W(n;=ednFcG~lgO|9L=K;@2NXw!#iuYD0RXn(77BZg32(7l_uE#^Lm z(5}OsqbVc1JjTXGD#%+xI}Ti`Ba0}2x?Llrr;oT~EDH;vm=P7pxNfiYv7mnA<!0}& z(IM?7HJb)K=#EWJ0=tzy?NX<brW!)KWRvm|!1-oLw$W67k!;t&eJSu4eC>O0f$vj; z*oG3w=w1o3cuo1yV@R}8<<KTDvl0vST(XBNRsB-W$Mk&)e50oXU)Ri0Da^?M!6GW9 zH|os|{O=ku|0kBKr;@j!Vyg|k4L`4&E%gGL>zxK8@weF6H_(OSiy_+in-7kTgJ%Ep zm;F24oQHLiwWT-0mjyz#h13d8w755<+kANuGBPwYcz9@NC@4Kfs6M1yoE4W$5vMod z{^Ft>6%iAnrsw!=lF<rvbj=BB3ObB@X>(JTYvFl72wpCLEK#l|aZw>}l|`bK?V#wb z#v($8D9nG`m?+bk@G6;1x|#{6eAXO6OshSE-ZimxF=T3uIsQrWvTuqG#*$*%k@~j@ z<|N3tBt4`M9{(o5`kWjHLC-8XM~xt(7g2TEP`q3b?L6VEnw`$5!<EjIm?Ez!&!!3E zO-@?Kep4F>kFs+u5&t*@g|BgwIz^{CExkge;<ssnpn^^*FTYi<lvoKjo$9?Hlzcf> zIR6Vh0boTG$py=Mz%JMc-GO^Sufd7oO=~DeQ4u&kln@u-T?Nq_Q84Zj(v3a{Ls;v4 zqg!O5As$qH=onXKI&bQWoE)yw7k$=K?@Z_<Jw1)VY?1v&S#ZEvYkD<QB7K>8X`#`9 zp78>s^BfB+EY39z7r8efQ8lJ%xhmt;PH#ynb{pAc;}>9^AK~9C3?CpO@*2d)&%ybB zGXM!m2A-B}l{m5pWGDs6#90-E#}{;(Ab>QPCkK*@-*{FhaGOPmFQtdOF7puJQkKJk z!%KxBtLeliP-hk|q-Mp>rLp6utSGj)&RE<i5k`1aR^BCo{e2Y6Aeoh}%sY_0w-KbT zBcwCtju;B4$5Yf1&9K}d_n2VcM2Hl{R+@8=$Vpa*C6!l9fKWFm(O(vdAN?6ko0KDe zmr*WAQAZVUvyz>Icb$hsiqSF`?iOK0Yo2Qj^s6{*3fi$PlpRyWx{?60jU&#a0NDCx zsD6PwRoTRvS7}w=BeN{)+Pm0J9Q4G;Q8mUr+l>#;?mL!{x?D8b%Nvj@{aX>AKcT}z zZwt4aiI2a7f(-B%0Y5*FmG~o<5qpb5$-OYP84c)Y8BC=t+MyI|R)zPXpdA@q+W2|B za@NSfBi)?OjD9tZhHyZwCGCWv#yX7lt9GF9TILua9cvV8$}~I}^FafLtGT2e<87(~ zv{R+s!Y4mpv;^X-(+FhzI(F%9_ri;x$yip&l2rr_ey|-XK}92Sq$uGOfO*N7<F%IE zP1-7*oD+7&t&ss|>XE7ApASZ8*nAibN=h$jwWG=h_|<gVItP>BWsXqf?jBq;yNia* zph3Z2-#t9a^<C|Xs^-gO8?p4XWD_|p67q_^C)Btbw2GIrv1X&rEWmy_b$PB+CP&Z- zNUKVOdeDaCAm{tHhR}<E<$w)=S@3_NK|{OuqCkTm>9Oc}z0(ZGmbE{ZspMH9j8oaR zPNFy+N&zEBC^8u(^S7!WNzC1QEn+j6w+_Y0gH-U<(bOUGgtI`lXH1toysh-IGMb{Y znyMXIEu45+hDklmhg`o>S!|5tC#sQV(~_p80+-Fc>P2Wq6l~!2Wd$)xbgi1l7eu3G zj&SAkq`VIr=Mwev`BdY`6x?0!>xqg&j2T5mtas|^bUr53OpmKqG}0wzPn0JJ(ZbC( z2^nUbQ;dtBh?X<>=v?IhiV$^;bIM{LOD3e)mgDt#?D4mnX-aPKHM}HzZ4lZnE8jC| zfse!#Gp<EOav&MVwb0Hk%@%jdQyicga-{?#Z*P%);llbCjzL2Hk;n&RsQ>5>SV+?3 z;75MyZlOc4V5IYd2zZkcgT1^!^~bOO^8l=9y;Epl#hcoINBy_f{ei{jU+CKG#zggm zoMNt9C4P4$Uv6RkX)YWkA_)MIk-mLM%KxLHe;Ox=gJ)-_7ry1M4*uZkKR-8eV|rPD zBO*etv(gfle*gUC{*4m+R&T;zM8*Ey#s4+`)8oA!xe)*q`&DM84yIxquhZbInva`< z`k%3E!EX)OhA)Du@$c9F&rAHPhp`y{@hNdYM})w-x~oQz@4w$jc@%71AgZ&xypMkk zn28hcP$LkV(Qy*~)9bX$3I@*V|N8~K4u6EY9!w?i*MR44l4S0EuN}9xmRf&x_~+kd zl3-yZH(3OJ{Hw2LI(TTP%R6I(uCEXd(P<$tk)P0FJJzR&RR2<Fu+&4~i%Lq2N>2_q zwhLXQ=IIaoj3@Ie-dLal{GZ<_@W$Z&BULi8TFE~%8_`i&1c=Fm^9@L@ykhu{rTW+0 z!^7K}L%S|Db3I;LHl;Vg&%dFAW%nTc1JUEJQI|IVh-T1$$7%=>*~8O&5MNC8e?Cbz zu(w)^G>{slQVYW_kl+pF4}5b6i+TRl%8vouvyPLSFXt<b0JzvAf;~9t9|Zf)5}OPi zu=WeJac3!6B0F!$PxKG0!Q{me{d)xli>h}WDPWKkS^DP0O(Hs5_qmIp89^5lenbJn z1P%SKW`=>_ao;e~xOJ!k{8vHBu%ds-85+77OjH=_U!}=uI&QE3L+Ic5@kc657y+xD zo9lD@XmLFVa>dce(4gXzj6ChXJ_9nK2PYr`exyNZnb;0>b+<-?dJgBmV~dFR!*@RP zF?ydLtQs1l!;ct>s+LoNKfJtyh8Fklb{jQ+OoA}dB@15-VmNZkCqkU4T$5*zb!O0C z26`}FeMc<g@?L#_!suhNE2Bz(D14Tj)@`s%ikbBQ72D;es%#qn(2{!2tUIZwu4>Vk zWPt$hYw^{X^g*$+Yq-v97>9~PTOPf4+`vpI2(;6h@x7aBMoUIIOl$xFPKcd3ga&s{ zE!e%Ji2Un_OxA@hJ7jE`9}%nU&HZ_N8fFa^(4;ZqP-Yr4NbW`%7`0<0V8(k(W7EuW z;~Mek@39nu^ZB9$YnSRic&1_MLa&@o6BR}le4Km`6Ut!V$jm3LEMFZ|+=`AyLOJ{E zS~E*`46X?%+VUK^M7W{yW2r@7;DGqYQ+_vEGb{Gir-&~tk{B;x6quLpT5W-k;fTZK zxdg=lX58Iw#WoQ`HC<OkspU>37_l?9jN?QEnTRSe2aW0}VHZdJm8h~?JlsGl-&N`{ z{^(DH43EtKimm>|)Fy{0<EhPXp=rtU$20UJrO&4FXQ(R$TT`eA2AJ3gm^BSGE8kNj zO{D`)0MvBl&#?PuyPty7khq#u>}K}WJ|+-%vWdpa&iYVDr16rJW?{uDu?guj(0~oC zD(mG^x(N|_n^cl<8}*+J;y)T@6e(r2To$Wbt@BBJ#Xgj&o!IZoC0GTu)j7L%ispB_ zI~NDuET92fJj+bv#>GI#40OaXd5V7OK3N=KZ+TAv5Myb3Ng`r%vrwjNfKeB^h)qgc z?4}I94GGEjV>Mhnz7>u|@R!pn=A9IQY(P3W9rwk)S*p;zK=Og@J$jvlmxPhzk|XCg zco_^nDYm$#2z+$l@sg1f<``}?4kc%_B_V&`N28o1^-UQMSeP9`EfDAnJ*yRCl^;bi zt&9_(N5YRjte#BTlno#)itEQv>p}~_aH))X))LZ~M(pOSkPFHqf*eg_3i8Loo5>E% zuzjbvPtP0>&}0BlT{oTl5+|c|HxN=A!OEO-_^D(FBdpG^1rI7g;T*Z?*AkB!gDrG; zoo40(#_+>du&-@c9CEDm1EqKd&8UX#Lm}(ywn(5nNGIx!ZelO5xQt?B_8CvhT!<G6 z*HkDzoNr(RAKR*^`UZMyPHF7y3AkQ3ka!06&2N%M)z*ZDbA2>@O7Nz-?F-+BL|2&W zsd9)Um2jP}SWkyLnXk(+e4in3?oNv4B$Twq63=oDHhUn`pPhMbY4G-Lt<eXgZ@u%) z@LPof7(2AK#oGP?r)C-GK-}Yq4kqvp1I!<n1gI;}{_e?p!9q!fU5ro<FXJE#f(FoZ zgYYMGzweG}Qi#G1@IILN3Og}Ni_jNtPF93tIw=+q(@aGu>aJUTWD-;K471%RwD&k4 zfQz@UADjD)ks>5@{y{+?Y{%kuTVs&HKv}Pd{Oy51=Y}P}(FrZ0*5bFg#AXhUJZIoI zZt7rR)i?&N&Xc4}T#ZbeNW%9xwBtIBtoJO7>){fnX3)wW-a^>&WkwH}^+{9j<(iY~ z`PG(4d`K%useW)=F1x!fh&0JwB(usm5K}0Y`&l(41Rt_&CE$m}qj)xdR1uia{PCDM zz?zGdJ!UcNCR?DUDsVBdFN+rp8FWKhb6Y^yzb`^nD>#v8*>I*P$bkB8#R62d=44D( zFfl|kDjj2?b4WKPql=A07OaiaEkkGCxqpd#6WDduO)o5Ua}_M*n66Sn>QtdiOY<e| zfK0=8Av)q-F0c_uGLv$mmU$l}YK?)(sezId=o<f0GK60}qLGw#q{@ebZT6BU&_Ca! z*8?Eepa>p|217H0+na5b>mM^K0z0<<UF=_R{><s7Js8CYm!1VAC4%4~1}_KFYj7Cp z)6fk}5E(C(W<kOSTHOHryz*LEz$ko*nUruTPIRvkrWpo{Z_Xso8lXa>zCt;}Qo2&7 zJuF-KM;AIC5K7fkMH<5qk%C1-vnY0qT2@DQhhN7OLswQ!u+pO)mrUi*AqmO(%K3xo zE~<8edA5T(V+67;pVXE<-{iA7$KcLIIUrC{;<#hIyG*0wi*cpdYWVl7jWUdPQt(f3 zDiqzX65vER)s;?(GmRmAxcwy%U$&f7hfkMy)Pw?vg-5q6EO$khe5L<Ir9PX4p-I}O z@b+E~L)=g-zNn|sTk{wlRgPwPpJ{#u2xxG7P<;?qtsQ0ko{-E^CfKdO_jFOt&Asd! zO-Kyp-qK!cFawkPf<{dyvRG$R44&@N4s0ub_v(APNXkY8uR6TFQ)$xGV4gAujJAdO z=7oj%%QH}tX`m$k_>f>$L_>DNR9_SFyPENkkaGJa$R%0wsc2?J_({sWjuRPS@Fb^D z^sM+%-)_23SSR36=OMe<V1v6i-u(vJ#{{{&vrF7}dtasRGEM%C=)2x~Fu1NdKOWw3 zpg?b*<zvqLwO6@c`PXiS<6lOIrI5hcpjBnw&&AX%tt9feYCd0_l`=JKwNSO1VQB+p zH*V)L-4%O|o0F_GAQ~Y<P@I}tC`~CO31TxyJiHY3C@(-q?Zo}1Qh_?Jb;}g$kF{o< zJA%nMF{}O4hFuJb0(?oOTI-#u=x^BP4>s?e7x$iS2P0Kf<3i6$C;AjSjwNTPv$rWP zDDu(s2j@OM9Y@pSNF!2<Y9@`|aw5{q@BhYXBUg=9qChR4VllGVc7RP*f@KkRZe8VC zcAzd5cqnMLFFG&UnEb4;S$J4nN4nlUNZ~!eM1Nm`D88<ktMr6dpQKYx1zWO4Q?F1k zB!MNZAvEn!A6z-t_Zb@&(RY<#-V)v0oF5caxu7E#r4ecRP;ZvTYeU_FI8s~hgb~Th zd&KJd%+qMI_#KQ;km(V>T-TB2E40Mh@fF9Rly3&ysll4J>|O5=b0Efe!rv#eP{tB| z6FTU@R2)92BTP#gG_`&97T8d(s~h`s%LNm%-0aSY`P(9!O8~X4gqSC`q)5d{zk;Ed z*@e41)Qny(q618P*T=?fwwlpdl1$HB@v@0OCdhX8edq`Wek6LBejE9}tL27+{~zl; z9S{-GjGCNMlOS=b(Bm`4O)fzAguh(yTrV*5c?mvc8+m27Zxo@K1TY+Vsgt0#15hyK zr4={B(gs%{@?@|%FLKM0g;R1(7f?xtR*hlpxFoBS%JELv$hBcgR;58}j*)?UR^+Nv z%SuD3wg#>K!v!D$_zI6_yfcdZi%?yPO-e<(mV{CWFDU3INucMAH752L23mjU9?#wE z6*Mz&1iCHRUn}8$&q>Z???U|n8nRq3v4}{l9$BGMYP1L53>tu66fBuxW~{<Xcp0$u zB|}FBksdR9M2(kORY?#aG0*kJWvL{ngn_RD@`An3;n)+ApIv~Wh)$Y%l(gff&_<zB z!Hq6x1q5Q8PNk;jjHxg`Bx6Ba+xC44kS60LkvBaOkJjk&&GElxvVaDT%&>mv&=E{9 z{Z^q-dA^(JP~deJ8EuP6S6RIOvq!zJ0)v`@HH4BuRk%zjHetwfGaPrP-gh%P+L}@v zJD12x{+twLSKU5YAxd=ZC0(?MN_;t0i4}c&4?E6#8{W9YG6~D3-BP`zjJ4jk@hp$V zo^zowN|-|0$k}ngO;<tI-gJXbHu+tBef@EEY84v2@Sk1Lvri){0W6fWsWPI+{}?XW zKW+%yzYSOEFgdp>QtSt4`POPK8_WR>U0Fm!WV>KH>odqsE+$(Xb)qT-I}M4rQ^w3{ zjlecLRU$}-R+^p&FLUzg-Udn)(?Mx54Ut++^`Qt}VNA|O7N9v3Nn;_=So^COI{X^< zgqFzXy$1q!N}ydNy946gAj5=S<Zn{%par{?ylKs*bi<;k45f^~UvUY$!2Gb=-|A@0 z-S6a^KVaw|8n!`TbXXPX^do$6X~@RNlNF($E%8?78oltEp-X<GW>AxwujX^VjZG-# zS}821Ii;VMJk;rMzrBx81ONdyyx;8rnWe5fiSwmQk4+^{CFm+$s8U522IR^yIXQds zIZ^EVxv@FiYa#4P{1IICfE9&(L-B|g<2bn|ps57v%xq%qE$!L-zyM}kkxlyG-jB3% zDh}pE6V0#sA&a5!2M2KtK`XHEUC?C%sb)MwFm<8@`Q?yOs*BBlTBqbVP%C|*TVSy* z-L1lJBr>1tmk$cXLBk6@dXK)(oZ2>Xa&RHJ=yA5vPq%NoPZM(zu<IWWN`xuMDOO|* zz~pEn(lt$_p^xvywv_PX6roane_NMKuF$|fIZ_z8Q~IsH3=RZ<%#PyU6mr2Xo<nPh z>R+yvZ9e>j&#u$lnhojPvfCR|BaC0p&p+$3Ew9reR%)Woqy=Z;O`^Giy<pu&I0VM~ ztW|42wohe!6!jnuX+lP9a>#PQ(-EX3SS7cEcnpmcY5MAGqERV}0hCcF!*Ztlm`|5X zUbK{Z+EQ<g96F7GDK$eptczok4IdKiWx0J6ScRU(m~?^3AHtB)IZY%22=XZV2-05H zu*Mu!_(4=StV-Abva7|7F4UpTUartQR)i5%PnrPZ^dQn38YDH5nY6h($w2=on;IZ` zPU8rsvG{5uOzz<o3}y&^AwP^Bz3k<;#OVpDp+s^D)YW!+7KcvcNTbeIiQ)Utl>P}& za_qX!RD9)r91EN&GTUSQDSV}t#I?8k4L*-$oy8Vx(RZG6eZs%3pAwu|WKb4bqt__} zKCc^HclnT!cs<w=`K^kMIC@9gc0RJ|g+rWIB;6)5^3QXj2R}E!HFJFI@5VJQaggAX zg%=^n+>{otuXV`Gkq~)L1?e$L^$R8yW)R6vaHYFg6O$D0clPWEm>|a%O^zY4fK~cZ z0fzGVy%V^4FUns%ceGyF5UrR!N!3mL=i#}k_oh_Nmi{iI&8BMPCIE8mvbn~r?enK* z$~FoFOwlcJd?Mk%_+Sl7w#aDwXsSb7P<MPJ!KVl{y|kdv9TsAnN9uF0GPc{j$~pdu z;$IbA@<B5{Jt&R5a{;E`T(15Y|76fp$yab#J(FOXjO8zf+rJkl0=x!rH*X0*9+d8P z%RAH6%7|rheA*;+3dunFWS*%IyVRJwg}f+fIzk~$Nik!kQVuV}8a8I0Xuz<M`?-=b zW&8wc7Wf{7cR&W!mjH;}&XnP#<fWClkW#^_>VqTo{X!q@DpvX8YMM<!&ervQB3Ud! z+KlK<Q9XT3U=W8~OV(Oh=l6D5j~qJnsL%Qw?7FA8v;_7A3kBrEY3SAk3v-{nwOnmT zEJ02l;h0_ueK`3LVE*?G0{*Q=)yND5zzH$DLALa2`$~r7ib{gINqO&yR;f(JLWS7L z<g|PO`ji0hOyfM1=sZ?a|ER`ab*TCfUMl-}`iab&BZs}S+uAFFhIBH6IYAPcS7^Bx zK3#8J(HvWc(PWxpUn0b+!2N20xzDQ9FnH75rSowJsmy?XJdE!~iVC*BMNl-1rW)bo z7f0884b^~*W=lG);?4p>=a!gpM}@)YSIyf9c$s9J_vHvmXC^<Pb9r?sPNlr)`(a5x zr8WpLk+Y^tQ7E4Ej19W)P~K3Zj}|Uz^OFUcVcSu-zfk618zg@uSP9Q_KQTQR743%e zem&{JeR<lnNkv9Dca~86>5ic(1yYrxv(_GoNGDZ;BH2r0bDkN(X5aVfZC7v>qvGT& zm#fbnt+c*&p>LpvH~#b|s5klRU1rIvh=@G_QPBT}fb<0Z?EjXS87av)1?P)6#TX<z z3e6H>qzn3XOimlq_qjL7B`P>2d%Wz$iTMP9iGl#6F(_3t4(SC@s+;EA=Ka8%%HDu3 z$;ZfA??JxK+tX4@w~>IQu0h4k_ZT}o<uu`@E|J@F#N+a>kHS2MONvW3d6?(>;%>&F zcKav1s?j*g;B-egr)a5rygPm3hDfqDT@Vc-(OuB^H^Q2(C>=FwlY@4QMteVs?>skn z7*$pPP3VgEoB>4v4Cm0>BWI2xD?xQG#5y8uwAssyw#bk`fvv%#i^0-DN4Tf@ogSq@ zmqmlXLoD;88aOr;2j1z5fyXbwbb`)$i2U}K*AMPq12nC>6_N4jB{0_ol<D-+gx)D3 zsjpZqW@vFlqMz?g$3bS0ql=Uw5}RY#SFF!3ZWsM>HAV{)l8qlHcI(|RWb_GGkc@RI zi|e~CEYXJxM`}6d%4UgP9u0!BGe8BVsYi~(f=V0UD<!YA(a?0R5L0D|F-*sM7U#6S z`44AsR$i>}*KCEBC)PUKG2ilEs(%)`0)X@kpERi=bg$?s$Zl??TPQRnN)Uhi)N)zw znA*eYUh&lJaeeot=Z^VHmmt>Gkdk=|kLR+cR16b+k=gjO<UltS#>SGcOl9mEw?QPy zo=YB_$3h|M<QtyE2l}wjjHC%ghL^fRlk1f#W;clZZ+3IhLm6mBgl0_R)tDtpZ;+(* z*_7*V5Dn&2yRm}u3#G|0$$}wv3xwtl>9<p$XV(?GP>UR&_bc`*$oOpH3c>Zd*yMtr zlZqL*f+vIi01WDBX8QtI<*X%wI{$JJ!HGTEe^f4J7FxU6!B@8mScx8&Q8|WL?O_{j zGTDF7xXFi9IQ+d|bLA{Fw&xjsg{w+&g(m*X_3GGYLuXrrz>n)CCD$&F@CY8}u96*t z@9i$FFEODXtXGKy9v%ITJBDu=_vpl}jNaqAyPz*j2I_(@3|LeD%(q8j+w)e}`chK) zBae$_8h|IEP{tgO)oe(GFd{2FSQ6-~!^uQ$Rjkoyj4~8M5|Gn%Is~-18*0*Wk<!4> zvBg8(38zTb{NgAHAk*5)j>oJMMi?<ifSTE|6VnlCJuk>(-gseQA~WDXHS|5l@zi%^ zDw#BlCPo!NC-r-#CjiZ+Hp?g()&cNRTuo6c#3eF^kixk!q}ZvI2IslgBBL@C&Y!RD z3h9Zhi{h%9*Eqy}9wjOdR+i9XC3rrTj=7}75Y=30LoR&%DDAu_DR8-DI`S(n5-)qS zYKln$C_sFWKCjY*m`YNbsJ&=pCN9~Av%6DR3xH8@`w92%v=f#Wsbu5VwD4wlYL3(| zWK6{)gZQRoLfE4u2|uf>@&F35havKz*D1XYjNI-gYR`{O#9!Oa5cC~i@yq&ey)u91 z#^zo^7mX@p0oL|8;#YK?s{)K&;!UEkDJ@>;J1=$#@h&&EwCg~;yhA+Bm(D6O6wI8Q z@8&Bts18zO+0wxGLJ?)ZU|~`8kOdMnx%JyU=WlN^5C6P8f5Sex+%60o+E&Sl!fM0c zS(4d`h3nq2PCxZkyw{l>5W5s~CNgC+k4nKZxjp7}-wxOMaDCHa<)10OHDj{9i<{@~ zF<WU?D4T3+3Dcf(XH&+T5Zl)Fut{3C?)&t+IQ8QI*9ynOvW=NbI?hMTn#HLbI)(S# zeso|>e3twDI!liPy`2kdhxS+KTf|I)%;FIXv``sa^@u`W=$WZe3RY*vXK?Z?fmT+O ze6J#-+Zmxk!77sVAQGKtb0o2@IW6&Jg4+FY^3HLLwSzKpK(r!WRX1>yjjJaafR5<B zF|d03DRR%Guga=*?>pT2b!BeBWZm9oANitbN3~5_L4C}XWO?jZT;8;VAvj03t%smB zh*P3jN40)XM3T4=<BV7!Aoa0KUd$9zcUdvVZKK`*y^7>Sh7ol<WkO_X{L!@ZouYW| zxRP|VJQKMYNfVR8+=p;{y}&LUhqq9iIJ@^lTmUl3#SxuQwA&Y|PR!`rO`r%Ox>67= zoo-yv9xRGTZszGw23{)E;u7{*tS4#csX^{|Ex5R_&rx26ExuVI>Cy6lv-NF#pl-e3 zjHzWSXsUGMQ1A2`%A$)XPGm`(dORi$(;1geRH8bJ+KC0KP`7h-IN$JRKt?P+CQaTM z@tyH=((=BiFK**%AwJGTdLW^FHz_ZS4$nqh;q=QUyA{I3GhlsognBSi_I%L7(DdQw z&Hj%aTcXyz7(B<Vo28CPgnh?dgb|z}bKuy;cc+}=uVWzrkMdg)?at{9F6k%98>zoi z@l?tba3ktKhZ4THG14u*s9T+%_zU<}TI!&SNKpyOs$#Xvq;%MS#$r#4nY_F^CAcRO zBDz6QJauRLNz_WSz>*uvf9eb0fLqnq%zqXsv}h15)zqMq;C%ma&?=kXV-uu{%G`TV znjK^sV;w|4CzyOWxqXcaRqYTLXh#><suZD|vFQ?4bbTkU(Je9j8sVSBBbPd8fnY)f zb8j-IwZGzk2Gj^uv~cbHK51>Tx?gkggObJA%$ILiMJvno(0IgzkX@$nat{aV;&E`F zRX04Ec`qyIm)pwVP#(x@PpX(6FxM2}akhRY0cy3S{*!@A_g^2F2fKrq?+6C|l^Og8 zd6nDH;Xl?goPr&Qf82fnwd6cP#_*2PaP*C?6eIR*=nc3Ufslsp-B@i!xCP}XPPaQg zANF%{%EbEnaD;|i_4E!hR7cf$$2Nks)pmIssPon*Ta1@7Ny&xlu@wdHJXgJxP&ukj zXojRjB5LQhvoMd-m|T+N5aJ^NG-)_AeTDP`VQHR17A9Y7!d*-jraFX$Wt2h;7Y=Uj zta^Cl9D*{_ek1`?;>zQp81+67r+#!ob>-RktnW8iUN&Twq^m+-vq6EkQzhZ$h_h3D z1r1sW8bgnp>0Jr*#NbjXJv5GUb5f!X_jIIPs>KMh?}mH_D;SNUKXf{ixs@X7mcIxi z9n?u9uH%KF%&r)b=w0BF&PdwxV$EUSdJF3<c<Y5#yf`cv+Zl+|P7)!HBSQsAS3gV? zI^sN=%2j8Uz|_td?Pg}x6J!XcK)7I*f~to=vY70(TU?LfmiCSmYPlW8Ud)mUbYbeo zyP#J*bf>yB5d7Tr?0Ma@gE2R{Tkl%I^r(m9+1A#mJ6STQo3eHJXoYus`QbC)nK#FJ zU3rt5X1BFN1m6P-0s$m23R8wbtdC?|)u+faD>#G17bwDJ6ZJwL`HkZgvd#7<bffSy z&*!5zy!LD_dTTt$^2=~f3@ELy+R^zAoiV2fG#thAkGO$s(PG<p#V~dPs5Y96ef}$O z8`HQ_d3v!z`zv>d>Qf`%25P=+RWUD`48<Nf4V3>nKTf<es<dvT=7bZ~eaw-SGk*2& zXHCmUwlbY|rQ2z6ur2ug=&!5=bD&#+>L5G45iPAqB^gIg@nvT`b!#|8&aoHrNe%i$ z6cZX$p##3x7!|XO->V$Ubov#@Qo2@5F_FWEzvprk0wY(@YH?1?(<aVP)K=_%bFlcM za8J-%x}{G|e7&EJ<`@JG%2*TibuwGdO4SlMTHyehn`^5T<;LeFeLcjaKUXBr*CHbm zB+7gs0&i|tAv4P!!O%=W7L@kaPNNz5pY*3N3{<^|?O3U$?jh5@glo81{0f{RDBVbr zYyY}WlH2H<iTn3L2MGlvu$@5_7sYjn&@ko+4W-p1@78B)B6q>FUiVtffL8%6eZ%s1 zgX1k~V@e0M!}~Y*K}i)|Wv)ROt-C>D?wrV<%Z*TM1!^R<2Rf;8ZIa#zQvetWJIgLW zI>^0IUqv&S0=b~G1=x(9Vhx=u^IBA*TQalU;_<~SgL=0IR{~boh$|k2RadomrcSCn zFBiK+Y)(-#0`Zz$p-VlEO(xj#O<0FXs#Th7Q3;6{X(np$enJ={&S_UcTquPlLjh^z zsZNlI%%SxepiYTd)?D!-B~qVO)gOVluyukul&`U}V5#4cvQCrGv_cY0t<h{T_wC$- zTtj}oz}${5sZhJcg!NJ1nfIfY4fIn2PbpVlJTd>~GR<S5>%98m);NO0iplrjuqYEl z99-jL+}y1QhMI44`0UEPW+QY>dK-0nhP?;F$C4JL;6soL@jN$Z=~c}(xk8714F?#7 z@118%@Q|F3SU&3HUM!X{jI+f$s`eF?ehv?FniAlBLc69`i!bK(G*a%s6qU#TmA}dD zxA7~OrJGAM@6e?#=g29mw<5-(cm_Uk3q^4aX9vE%JKJ@ArxCB(2s`!550|;e3{BOB zYxqPQws8DF8Xtkhu8WG9i8dT5o#p+oeiQ*OVkOSr<~F;MloU3GNlEMBHJ?s0cGg(c zq3?1pA|jx`hc|{CCo%csY8Y3SVSlnuK^;9d$Tq9w?jsCm49{t}Lq_lPQ?G?bv)ePP z$nwj_N`PK8k3wm(B~heBjQGlJBQ)_j;QN^~8-h$U_DxndCAD^co#&u#=i?zm>vp{y zBUj&xO81%#dgz=#h}Z6k#|Y`-wbsp1G}flpX1p2CeVy#M>67WuEYkCl((f6Y)4qO< z^48byko!K9yd&Uh2{u)?hNzT!fjQs!tB<5Hz$gEa%Qyt0Lfxt3*1-VydG$?`bpcL; zow8IqSrzYVi|9#rp`lpf$VK67nM&|JU%}%hhXHOS--+7B*au1At9M~=1Fngd4wv-( zR|%vmr%?}F)1@cFf^o?%$D8E6LgRNc?Nmq~&YJ`FSKcH+oc7_dJ+JT`b_O9U2DPa2 z&Gdyi>MDjh^WyOLjBV{(Q@s6T=v9IXK{K<ZG_(Ex|4|6pf3irYIe!);g$JxjHBQmg zJ;N)|WVyG=*9m;4S$&}bLe1YJ;;~Y!cObp=29gF``#j9UFYY(OXPaT-u5S<Zaw*fn zi?__+MES47<kqj!ES=X2PtCdMmf?*V{2Pe6;<s(bpVgI$2k{Z2@u~yZ4y=|2TVo5y z$?V8tdX@I=Rs=j(rRYadsU=#4K|lfos_%ylX;UfIS8L7wlnCToqj*=PGkh|b_Qk_8 zLgB3yX<=Bf0Gq1L+#;__RS88piiyI!&WwpjiaE+r<P1PKW7KQ_(AtxFOArAqGG1MQ zlH4pswKGhoSV(ca7AR2^=dXV|YpeU^SG0j{t|-#T`!Yo+)#vO|P5}hM-}QUmr?|YE ziQ$$^Q1$jq2&Ow#D>D2_k7eA^GU$r(s^=hPrg8oEIFqmFds$B8SB|LCYc(U|y^3B< z{c0>i5ihO|QnCroODXDzP6J|_TaDfFJI>RihOyt~Qw^e>5=-*K>}Y|b5+~->7yELt zn@fHt5=bN7hufplI*micxLuN!?3BkWr%+>pm+n*T(M|<{%~`4ECFM1A?1MkWis_`? zFTY$I#!47{yeSUDp#+Ze{*o~_j;}ZJ>6g9%r%hi?8r;u<lr?SHD6GBge4lpiMi{;i zL7wPQGB5<m8Op^aG$3nbdy$a%IdBl1-LeQ={bXPAN<EPgA&?&cE;uI09tz4j^G4@1 znBfy`DVA6LfHxSD-nI-0;?OCSO+qE8;VR*bdlON{57~B~FU**1`QoBtjxY>y6oclb zQ)W$+Fl|DO;pT0%<$c!_TUqsZ52b=J{7Kh@5H<#8CK!h%A3dRp2;<)BR-4GBpOvR_ z%ILcDobd^#EQ<qZTVZsf-wlf9z2NQ8v$$#{ndUFVD$nOXpnqs=c3qXbcnY8WVDnqH z(aMkZaK1bM8N;CtC6e|2dv~kZ`O(NXP4~OP-#phFzj(|a5@FWe(ESPM>r*s;C`S}o zo?qmNSJQTB78k2ojZ3`T*w;HE%n|_yJ{ybRvw<4(_ml`6F(eGiK>~1F-4BSdemp2{ zt3L^wbYjs|YhRVFbta@bwn1g#NyaEecwILHG*qh$9Ju1Sen>0FwG6t>hKsh{l;x`l z<Sct|`ag>KzxbXD{&eYtnCf&CJ{+UZu$z#fxv=q)wqBjN&BB%b#c_H~8DXGP7=K%p z@K)7!==YRA+GxCs#>Mc*Ew4Ivs2_U=**2Po9Qap4VF}|;6nd}=3w*e#?m;KQybK2v zzgJqm_QruJ!^fl8iaU`N9u(V+ws_M{gegQCv-l-i1hSe;X$xcS2~K}>v~CNK#cr(d zg|{u$%!qz;VCSm4bZ0Bu{o;h>$JfaK?H*@za79PJ#3PgA)w{dGqXTJAB#MQau6I|? zDVq&S-2)xpq)o()$!{HI-w)@yv$Y5__Dzf?Ui@mEP7`t>8m(eHUOIHlnr~unwowlq zfTUTZ7?-$Smf&Z-((I5>r!$bBI12`NY!MH{8U4;}fiTMlNEK56gry4Tan(vEdyA}Q z<8v~?lgAhH?6YBc^5!9z?4=Vt4(iDYVQ>&gPbzidGK0>jpZ!U98AXynq67$`?fOFP zc3rls-e+=4Hyg8#FUh6(e5t4OVO%Efs+iF~Ibo1jYGTi{Nud<Y{^Zagp)1QOgJI>R z(3f~URKaZ^;8c~I0_fEul6F0z+js3r>U%4~Arm-qQ-3!IwnlLsL~*+rmfRzfc31+~ zSccGFYQW|VUO?$`4Sl#6XK{K#aog-D2VZ{?Zg;V~KlQ=v6_#WD$x+~P6^*D-?~`u7 zEa`%ziN*XFw)<AL8>{^Uw+vl)p-*UxrQbxncC#fUb@UtTR?iDTLy3}jwWosPe!Rs- zFlMaCOS=XTIpRKnC;@~aRXq+bGg#YIpFx?qmmPH9T@Onmd#}pJzLaK8=c0pwyB3Lc zDK6%Mzyu>6J?|x^I1rNp8yP1@iO}Kx2(9maJBau2qGb8$Gn~NN&%!c2&cu87dYz%1 z65g5wQtl)E7|3=u#r)#Z!`XVh(db!OE{&qfdA*DB=Ore;H$5r=5^LO@%O7l3pOBMB z7@=fCr6yqc7Sq}Hq`klSFtY>QYYZE3nvU!uT~AgDt!5vkKtS%M;pql9`|q+*FTRK+ zZ>{jl_&PE)z%GUCYGpwtQj45*6x>@sEL_)}*Ww9>6A-cYm3A(H!e!ft@%*8N<x&yz z77!}o_;aIJqmcQYwtl~^wnWkWluU-c{=rJG7hkPz2MFhDM*(*Zn7#>NL-YRf==Z8$ zqFh|Mw6IVug=X@-ivK{%2#+gCj}65muv7P_tt<FosIMBb?@S}SRe5Ms4DT3s5Q(z< zE1AhEybOBLGl}ohe5(87md^fS3$8V*Qbv-xQRz`v-DUYRtE38m+oh08CWld;5`alO zoOqxm_L#7hA1v`f8h%&@9Y+a2nlknzSchTOQT(mLX=lfxA)4-aNLgs7=x5}2S0MAa ztlp^R8{t7FnJ6W~413=&eWX_Z*WZo2e-1Y9O8Cvr6N8WQg_^}-{r9L`FV4Tx#6|z| z7gae}&1I^Rnt&DYkX*cb90Ki#ECLSzdm=WBGh`n~(=`vgmUT`%1}ol{Z@$ADH{3bB z%q!|NkU-IT`K{c@ovq<?HOD>TcjvIFxFn0^>|cf6J_|V7km}xehwDz>4H2WF4$(=I zAfJj^&WU7wG+*<wpw+C>4{De?h!WB=h}m1eM~&er$8`N=X7OyZZt$aGhosS+Q9_t` zuX}6yckBM)$9=yevsHGLg;)RyNXH!X#Ub%~PS)15e$~hsG|pYXa)M5@+r1e+rntW4 z0gvlkY1-qK7?Img{4%{lYLn~kr?JSX&GEWf$AfvFA0~U$`rqkQ$-a1F@F)qt0!pUz zqQ`66F;*N}m{t@jzxER$`~5~=ecA8eIc}_6K2=jzi;5`2r8j!4RHQ51sZH7)(H~e6 zzSL!Mo@key3$jm|XO5yF7X@`9>ncmhrfl41o(&8XTebE$D6M+#z_{PM)F@|7<CSLn z;h%QDICE4>B5CW8Cj62i$3Iy0jC!+1{@U|uFQ45(gzMS^FUUvo#Wcn;Harrk_Rg5b zbY$yYo!iw=S^uND1wyJdDghgObcRFZi`y^!#p_lq%w5Jlt6%Mfqnb@WzTWsQ+3lTJ zPB%f8x*P{Ol<sZBK)P)*V$5i?0@B`vSKkH4qifeMn8ux?eK*mg0O&x6$2)i4F=>6x zh1&|kP@x!V>RcL<sZYebOd6Ei)tFb#a|B=m^_y%3;7E~uu(kdly52G>uC3`BMMHo9 z!3pjJcXx+i!5xAGx5nLrySuvucXxMh+@Z0?osaXp-+Rw<#~t_A9;1Kly?U)#vsTTT zrMrM#my8w9#*Z6Jw2-zNb$m)g*2MKzTfWo}kZh2wqeNQK)sr;8sGKXHps2OEjTp`g zyD^bKoK@ZKiqzj{rX$xD!(c{*Of9>+ViX~jr~RWWRhx)``Ri!xBIfg$L~xzF1m#NG z%Poj$Zv&3mYtnPgbt%(qqk<WpJ1HE~@O9P6^(hs*Wltb#@-Qnr=oXZ|y>~((!(@2m z&|Gyv&}=e{$aQ}juQ-=b$k1MUo7G;&VRxaS3m@cGS**9{O!k7o_^grm)kG{<Z(cKP zf5ka5ylSYxwo52FoMEUrb*%as(i-seO%mNFHXOl<BDFE%G|kLwSa{hXIa3Po6kBjF zE>qUPX&&*|AQwPaZ%qpkb&D3;hYN@Zmm-oj9ysxti@TM9Rq~eAjIPm-?ujQeora2o zA$J&qQrbj$oBRb+FlrVK3$*e5{^Xt_{diMcBblcwR-WH<^EuU<3VX?dc5}`kdM(%{ zc|GFgREw)pnd-C?baz+DM1QtV37Mg~fWJ6jr8&Sf&Ej!AD#tI2x|qwaT`AANTx|9! z_jywy<M)?h!EgV_g-0OXRd*g|kVyVt<w3zuex<L^t^3(NPtoQVMCL~+fN-5A%Z>L1 z@X8Y6TS!Wmk6tay%i#~#7~)G5W`ThRu}@?^`#MY8o6l_w{I&oPLik!TQOAihu!{Py z?zl?+HR-%`NzmyL<0rn6;z2a_Ve5!~q+KzQL&=zYIcV}|7ATkT9It&lXXSD#(AG>h zdD^sI+2FC8E^UJ}HekkrVd_+#RAKk}bmxTLg*RqRrruITMR>xZT-NH-aIrTimkk1i zBsIHkBis*LFWDn+E;m>KSLk(;55rdc&7^BEh~LG5A}3V=vyZZmd~cR940L%FJb8*q zk;f!{(#NWt%!|nvHZ85iyf4G~Ybm93y0K;9Sj{c0f-XaZF8&~ociJkU6shbT{QJA` zspj=2;E31T8AkF@g%vz-GDwoMnR^r2rSjf<zv}EhNn2aUE7b;bXt_v(<htgM1s*t3 zBLBt#?fzB#QMR5Z&!U{Muy?$iklq0MYBbOlFuy;Qy|;SW5#RP)gRSEY*18|uZQ@}d zqMTA5I`f)7wi?pui=$CyG}MaO6~K841llH_>7Ka*n?X+~&WP%jfb!yK7oh2EBQ5(_ z1Me*qr#BcuJ%?un?gr}YU@~RD)scIsQlqO^F7x3JZ^Ua>mg0J*yEh}J?aB{zu}mW? z^>(}1w!I2u1_~p*rQOyZ8>cKs)qQdN@Lu6CL@|k)@fV`Q){P~dvq`>Pwxycg()0Q# z0=Kgx`PYG5E}x9Sde*hbrnLhsdc7a0guoO7%G}>QWn1|JR|U-7R&SZVKvzq$4xIWk z1F8xN`^#hG@ydTBaW9m0Eq;75Ct=u<D?dZ#Z>&qd>x&NR8cilQ?q68~o5kMdx`%ZP zv!c^}9%0t@excl@`L2XJL2*LJ5vne_T;4lBioUroIN?A=v_8`ycw@}zvqGa@Q8NH; zcRb;0`e>3`vqs_DUqp3|oN@)z+&|4lxAaBvt$TrQ#RdUiXd+w7Q6zns=Gn_M*VnJ- z@oWgne;5|&)gP=h^-BcPGN<+@7|GNcMHzJuQlqn7sSv$~mFBZ8dRTuJ57!-e5<edx zdDZEta7@OM-gPaLIGt;b%e=`#wzrBMFSAKbl5CD1lC>A7E2&j9RHW;8Ff|ItKDK=r zDpl7pl5?+Ph~(EjTUW1Gm=tSN1N?}t1nB#KquREL+SU;$E$Q&85~$Zy1OJ-s5YXpZ zEz*5Bv0xS;Mx!+XH!Qv9Fi7xs=8IkX>|F+PEAj7>9Ah1${>r9_I%Iq+rq+wM{?z3~ zz;kOqws-*WRAd~PZ4#kJ4LWgnQ_ik~KGR!Bwv0s+U5@zN&TM$__ia<`y^F>2{A8j; zwd5(9^eY|lJ53SiJo>*}Ku9Pjj_l)i&c*=acrqE1y4&1_C_={_zGOANP5V;oWQVCC z=qY5;^Z;i`a9PWZt0zNH^a~cV)@0_&8PwXsU(OTNDG8or&}8}xW>xzgmM51xf;<n% z^9znE-pSJFU=XbG^znl-_-y`<SvBYl=V~XO%k=`Q-Zx<Z<vvck{cFCYkN@2n3QI9s z@TtpJtbH}%&7SCd&^O8DH?sqN*FMslbHKNA4|7s20xzf_B!WP#74r?P@X8p!XiZiN zbJ7d*`o!u_a~m-mYGJBxq~sO;^Hv*iIV`l)zvI3@57)Zt7-vc~#%)CE_ju$FZOsZS z8T>r}ri*W$uwUDmU$oVb>S15-^WtdMmuc0VO6oX*8&W#xP{<@Yf_WBLrPN0Tqm%S> z;&^>dG#vT67?DryzCG!z`(ee*>#B};M&DY%Q&36prScP|!l!DPQy0aRB0ftuYSyl? zl(SN-_Jr^J))}}WYJY)pzwba-=(s1jTP-9}n|wn)L*_ygtSpYem7Dgt>^NFH7Mm{^ z(1<{`6>ziVa$k3ZD;j@<_j<Y&oyx+_^}cniNMrj{d1o1%y|cn~Qh_*qv5{Wm@VdH2 z70Xk50!AM+8bnc^Zn*~I+`c_G=K%LLvKx>#UL7&C&VNQ*7jNj;6KS)fOA@(}N=!)i zU@qxKr@Lnc<JOxb{!Y1rRSoZtuI*{hhr4(|(qQr-w7<S;S<Sk0i=cAqlNBh|dcGEt z;mp(d@Ni?>Y^1JjNhVwQ=4T+2hdx{R+452K(u>%#9e@1YfQ_M}gi*qi8AUS78>-UY zMaTq@up5<Rv$h0&MG@%9f+O@lPrmQgqfa9XhnB2}r3-h<#j2-VXx&MmONyDC_pABw zR+;lg8r$DGW^eYg%JonQ70Q*UD8Q~P)1H{!=Co?Bk6l<vIP?<$AUr3$gt&*$^%ai( zBAkh<vxPSy>UpNX^>V2kv$12wcReq}R-pvZWKR;szl|@Jh94+NbRKMiR98u<2_1LZ zTfitd0HAX2#k}W>3~$ZUX)W|;2j-~Z?R=-~wm&h}%P)*~EFkY%4+ui4sRocB3L|Sm zZ{Gi;Nv5#X;3rzr@np~P^7w+xbMyJM?p<$qa*xH-x<g2N2$d*GET0mXqkbXqfIU~+ zEG}FTqQspfT&^{n=BYn>IUHlkWV!*h=J*_0GPw`5*MmNvOIhQL+Y=Z&`k1;>5Y2I3 zfB(}c;zHkwpvnJX@y@qBQ>Gg9v)wv>gmy%Jhc4V`zW|@ojBRXDbuuMoK+HT^I`S}u z4nxx`jYDFg*0Bkab;v8y87@1*P)m@|a~{0xEg8jnj;;A;Y*@WY%MZM%FhKGyfV%FX z7a^goN@h`es=|Mw6~%?e==r1SvC)N!897z*(J`>v4fQitOgi?voT|r1%^x#PSpK8- z|G)i3AMHK(A4J2(3eFu$$vD)%Xl3uaYhLnVo>TL66&&*kklNMj$g)H`{&{i09=sOg zcjRR4QxQ>QaPNiE8zV_5RL<|x8y!EG`}_xc>$#=e&VEV8PWxS;M3DkoRhp76;|`N2 zYd&?%)kh@!HM(2*uRwrqqqVP<+?8tSo&N5X#Wd$NCy`fJe)LJ$pa*`KumXy3xtH?+ zOolNuCVH&fow+V}<AF~H@J!HLsbFdh5c$j95kfn8<5s+143H&8y}RW!I`$MHth8R7 z`e@=rMKa`964#0$Uj+;i0QO=fQ-_Rulq5uG@^AK3jfw9$=(eu55+DD3*QvoR_s$6W zU2d}bW*SV^uubTCUkay4)_}uG<@M*<{YE^J;BEkqaZ>>*>UjeEl^Pb~*IPm;SCh7W z{mFE^p4YK-3QWO6K%myRs7QdjB0m}qshU?S#dmBlCS>W0gizc~!p07?`0mJx#LUwz z*L8)=&jvkFzJ~{5l_^S1rCLZ%mkU1<1(boHc^a;ldU@BEZ4brlz`^0BjqZk~H9rbV zqvpFtUOPZ^onoYiR*{2_?9-7GgP;H$h)jpnT~XntqmHw&N)_pw;;~4cxG1%f)LQb+ zwg+K<11EoAfC3M8G(YEOx$;m?)c}MVi<9rCn<uUq9IJ4zpOE@fhZ=-2H@`pL<Q`ZA zv0Q&NMr)vIS;c3?8;5^h+59}3H$&{iMmPGhKyK7=b0uDhi=gh^^*KXD3H;$Fd4SIK z9Or>r*+`X{-R|$@yuSEZoy?~s_%ofGNpUuMTpZn4ZV5mRckDAeeV@8@lm}GU6dHW$ z546c3Z#P)9dzt2TxA_u9jYg|)EG#U`?^e9GGzwC063p{ex_FZK02o|$t348<RE$bg zQ@erwk@FT5QV_%UD5HrdoeGUkG&kCV++RKSM+1d-x5zDDr}+3G<jOFAttZ%4U-S^z zZ5?+oJ-p%l?4n6*a#7TeP>Fc=B<IQS#A3j^l=b($(MKcO(4e<|bqzC^;E5a5T!_4> zLy3^ZqNe%NpT<OmtMkK(6J9{G%0a9GyoG}2@S$&!%y5NND`Fc!SKtprrXm#CiG*EN zB+ZM=P{nimek6&6Cpb<9rDmV^Lb>KNB*aFn=yt$uN<yYgzttp6SaX|2E~S__woO=+ z?E~gMVAPUzT5&m%9W6s!@zr$j?xu1G1FXU8*z45>3AV@Rn0$+zI9agBmjgO48w{D8 z0vN6vF&6voP8O4TWNbYo9SzxlF(Sq6;NHUK=Yw>>ShsqOLV5n>^e)P;srAOg&KQg6 zrwv<?udKT5pHX8h(!C2~G|B^0(mbCvB>-5U@|)=G_SApw7EI24<y5>rKmj#I_`m!5 zKR|)tA5btxu{a-ftIps&lGspolgu)NK9I)?KktCs31M~L3Ui3w7t^Mu&|rDxb>uoA zm(^%TJ6>oa<#s}HwpKz4IPXA|u_xsMwTIgcuw&<%2WZtZk<JW^fFmv>w#TCm4G-Ee zm)*Mh#se;GCh$m=9ez(%x0Iw92l8!I4Q_cu+f7t5Zfz2@ZlCuw{VJwxI1VJqRzCaC z9lwz<@LkYEXzRdEb+UgcCaS}ehEd=s2w_+H<zWopX!wXgr_mgO?wOwYOiosL+IZS; ztdRblCaMy5euzWcc9%XLtsok|J7piOva{bNgiV9%<F<<HgmzprDZu%i=kxQ~Yyx5R z(pIhIMc+=Zmg{>WoOH?l_A^+2=Y_B-f6}Is`LqR6qP0lM<_9WhY`~Lenfu}eIQ<kz zc(ee*;K?Of5$+Wx&!9V+?+h`Ra*iWsMrrC-t(+AIST&mDk^9yVof#sBM##LwpcD*J zXMWm^253dMT^>0wZY?*q#mp0{kvexieICki<T&^{A!!m|ZFi9)Je++?@Ja9nBdiuL zHs(YQaZvd<HzSbRDXA`pnJkOy(VqE=v;m-YKQ{ew)w5h?qU!J|j+B<J%ukB2!+B~T zk>9o(ozdryrA-UmlHO*byv&iTsMB2O@DSsdT-dYQWs5E{@a0@|-mMLAIyW4l{9{}Y zU>P06aIo=*o7>X7N767ju-3wmjrA=}%9w7BElHCo71-)zmiy81?tPo7!BC~dZa5MY zc#hs+KSFnL%MfxJk@xEr?dE)iAi9eKE7M~m?D>K+Rt5z`N+ixSIubKXbc-Eacbgn* zeu6<MRr^#B;}IyI#)cS~&QaK)N0xMNolw>FrKJTQ`})v`KXjMe?ac$GK$E8yX`xJ2 z^!i}pjK(T37YW&rgikDI=#i|~%3a9kxkI5kYSLhpa2A)|Wg`h$b#W)<j;i-;!w+V! z!%V60tIVKRAoOZxXyf5p$n*J`C{!G>TSzF~(_X3P3pUZ#UX*FB={pr*1eQQCae3sK zdr8tEqGsQ*F|Nr3Q=WVOhmO4}5x(nDRf%qVlE?gjBbh)D$&dxhaIT6NIqpyf_Zjs_ zU&oSOIFJxOsIgctFqp6z63CIzhKG0Aj%FHv@I3FX)LR<Pbb$6dngl%U8bTE!;l#=9 z)Tw>KZqeg<R+%<hqnME#{09*`CP&wHFMAJ!mpa0)NTrY&!8u4jB#y1?n>M54ja~S6 zFfCs+n`XK3(Ya*gUiewI=p-3t(Hth%k(`p_O(R+9WjV*O6Gf)TD>AA$BNSdnY5MvJ z&rbOw{3m}OdflQ^5-?dY9P=fb!TqoWP$Bih3%kCHTu@CuYjnYTq2JxQJ+%FcLEV4k zsT;8AV*g+Q8csmWe^>A^V8V`6+33^Lr`4rbk*ulH-XGmR<Sk^(2W#5>S!9pcvAnSI zTE{S{YxB76FMGSLfIY4?_jge)yWk*l3huMQx<J=$9=^4|j88W{IDg3XPuQ&n;XP2T zUAX|APg)s18{ZDB$m7oq*y)$h`fUa9q7Ykey2r&Wt3h3FkyLta2p(3zubLIvz$1V+ z9a;_y`1TsGQ$xUH-}@;8cx|yJLB-loR-{ztS<Bnvx*IA9=tH_U)YL-s1g~S03)D@l z1Qsn6VhLHr#<J^po6}g<PQf>e3}6`xtcT#sEk~B_{PF3`SW@f{an$Xyfp)*|{MN$e z)^<0DH)EJyM9z9tnk+NV*yc>^Jvz}_Y|9sM6hx8IWGBGT{(_uyz=3nON>(CIDHP6N z?k{zW$K*5X!u1z;#&wi11{m0<%0<>Um2A<{stj-rHu>{=OkA26r>D13+Nf|8@o#;7 zJNf5Q;yJTm$wTxUr^O(48GvXu9usF52Vt%%W{aWLQR!}epd+`t?kc)M=M5o(63dKn z8<s|wC-VvCI&$)TCm~g~JGq70NZvKkLJzL=_m0<>ua5kGQLe~TXIh>yk35DN$cf8S zf9G>AlB8z*uy<N-59QiPsY+?2Lqrk0<&r<MV@js1vl$I>2)(yfzw3rp=!oo4;EN7i z5?yYUXr=eLtyBs}JJMe2udzBd^n9LJ(vUFZChPN%N-8X`c#M1P7bz4D&-iVsRc9iH zzw!2SzC<svpf=>2ChY8;984lNv0~fzp%7_3m8kK^&(@Ou=2yx20Q=%=MHMg0wdW(F zqiGv`2R>3(NzDQ!NHUkeR;mO?6R9KmUakJkJU78y^=u%ZX8=3j8jq)%#K+_@;U0TC zd6)gM!U{8T`^v2uDW^g1aU$+#>u{<99ZFqsbl+_ge_$DsbN^Y>tw?@r!wN>Hho$N6 z(cKV9<8_VeTT4$#4-qset!dtbVrKO^$@*nCG-ocPTh|xVh~CUys~z?C9%d@%LDhS{ z(DQXZ$WmJ|c=}&+rJ|E*><?2OL^HKbg3jh{#JHE4T_-15%hp3@<FyL%1|JMV3`R7W zZBSGDK}1rA!8=U=ehA-zCkabc^5P8|0A3l2PsvAi#3A#a$j`!|KViKK9@&Y8l}N(E zHX59#PT}=o4x6>eeMJq<*Ww73xMc<@GXX_n2e5`TJc7Rm8I46FjTGq3G~fu{;qifq zcyg(A{pI){J7NgSxWJ_b_}S8*Xyi8<D*sw%9D9^cCbuzmtm_PBcM(qUaed{S6=7`v zL%KdjCQn=358|78(}}05@86R7)?@ZqI#E>ck}<@4iLfM#9b~u(8t&|smME9=TwR6N zTtHUN6d33xQ7F<Z-RYt0i7x-sHEi!d(iIBY52gwHFR*}uddGp;06KgOIUMfxk@a|& z5)D94i~R8JLu`)JilwF2JCW#o4)WOPp;~MIgSeJJ9ls8c#J{L&d-ZN&>x#)pzZxlo z(iQEuUrTdC*9G#sIO+^Y_2qt1&+lQd=|;b37Uy=e_v$`7Z|2R;7!=c7+;6MN?l^Yd zEJ7{b{$_L70c=rpbd96chflzxjdg(IQT|TtC{yfpj{Cc~MeEkZAs`FyoP$aC9COEU zJ+8~Uv8~2~N}ZQ}fWUEWzy=-^<CwIU>gHHOMxsF-!B&i)WVS-XHKGZltNhbcS2Ijf zscP?751HUf)1V5E+dj~8&C11PbC<EX;if8Ag?mf0!?6hDsD`~%CCVv)-73B5dD5AF z83}T8V_Y))E4r4EXa&bQrvC@upxHGlU2xxM$)+n{?bfB^cyStDj!mt*))7~vnB!(% zM6Nj|(b~yzaC=!DDsue*;ag$3r;${`z@US!^ajHH<(BYyi>bcdSP~t;w&O7k=#}lY zHg@52wkU%IG>mfpuE68Ne&y73(Ri!-DRoQAf}m+#&w34y$n$*h05h$sSK~+j@+6KE z?%lYMdid!Ni62G0m6i&eF8jE1;*;!wx}i+=pfwjFKG2D&8i4oA&Hwqdjhj*i*-^(T zK)cDfjMsA$i-DGZOxJS`+J^l$`5M`v%K2zI6BY~g?GLP*&ExEV&35nOd9gU+dfp#I zw<)8UyjdgEi?OKewHI;0mI0aMw!9s~ixMf81@F*31D^DIk{#VzKUB8}Q@nXS8Vq3d zxb948{+O)o9*<Mkz-zU82Q9`C-4Q|Qw6pqy$HzTynPl|oew@xuM-S%SUkBx)DSOL@ zsFHV1N~^Wy*9P)P4_Mus#k4UzZl4j|<1E5yAiK?KFA~vp{H|U88-ACkLO!i&tFwpI zAu?!s{k56$AgJROEA!%Ii{aQl$kN4_lhde2t0gj*4J*#5Anw-Yv{+QPZ<T$m!%-x@ z&y2e?bYMlGX^}pSb0c%}maa)V+-rTMIQy)Y#iE&}A*}_Ve3(Lp)A4M7qoT7%P?%!O z^M`r-h)vqOx9eT?u;nJfYUv=wVXfZ{K3Gx@G3%B0m+mhlHEs(j-BYi~gXR{;z?(<y zsb+;upRu#*Lxc198o`eVPbS8?cT+caRhga{8Jwl`loGq5(Bci^OU<?tT_A?meZr<V zMR8o2AG?B^>f@xSqmy5;<#EUEDrBwnWjDWWnt1q7`w$X95O|qcCTFPvZ%^JUw51t& z-1lFFLRUCd-Q;2fR^277z8)7E{Kc5_lN0vCdpqDgFVcQ$nd<s>crcZ{9fX8;K<IHI zm#m-T`NTqn5nu6@0}rYPe!?WcJ6>&EA5Y}}n(q8xtEQ=cJWVj~oj#gg2a7zzvOj7M z1J|97#RPMUzl)7$+5kl|V-=vgwF?+d_g>lb&v+z*(sfd-v3}sV#PdqYa{zma4=5AG zQB)9DPK4PeP=fhz=)iNqWIXSa{rUs5?Keox%-VD|U?2a>Xt2#Rt8JSRucH&l{uo<p zLt7fc>t<B6>eEQ2wTtzIL{w%XF;Oc1goBLt%VMVYO)dj_+`bJy-+cRYSP_~*ZfNVO zVZ3wtSv)M0dv6nm^zcKmewMUjh%u8=z<lyBTwC#xv09rVf5EO)H4@%kQu&gr%l(68 zU*x>9IVxgZk@rEAz`<vidFsRI^!rcu3)uN<fz)&B8KtaiU3bgDdVQM?+~Zo~PkU!e zH8;x!C@m(pCv%8*<u<>wOc})l2E#eO#(U~X+m{%SGwyi-J^ByG^7qcv`!g}<3;0lV zH@(1(K!bG3#b{0Q6^2B@l4x!aUsD(tBJTAltyUNeIe}Ai24=YK-)rgG8b<9?ujX_n zqpUGTR8*B6gpr~UUlsM*?}*rK@9jMO3zXoBfm}EO_X>~qI(YIjBK!5f?JJeV#W!fE zbTf(P+-SNhH^$z3r5)?z1EhZozB|!ro)vlBMgeQgMUz!4YdkELO&Owl2jEJvl$6Bu z`y<64!c<!lu&Ir`3fonJi8WlFhidEgO|AXoYbeNxQ-PzjLC=tBj)k$Bza`>K9%<L> zP}V`tKyz%)hwWk=0o`<;*X{HwJ(Dt^_mb#(2($7R#Kh2<j)o_(e0kfzWJ<3UiMctL zYduEjnuxe33WnZUJ~r)v(QDubAGq})A@$OK?o@t1mh?Mn-9PWa^JuP2Z?H2ujFU|~ zAgwk8tz|Hi>5QGFwHPV1^-k!j?qs=vVUv^VdMDB@GkLEA>((!0^Vcm-=*f4<zljS8 z+zRQdQ}NCrd0w$MC7E|dFV&P@uP+=rIjXXPngyB!j_t3)brhxj#%NIigFNtw(}uSR zyUgJSf1PbRZ>oWvZptpNaxTqIAeps@8Y7+Xr(2y!o{9CjJ^}VPWgN<}r^&<kOSW9n zyJcF>MYFMqDW{9}H<r*@m$j1npjKS%v;9F??SZTDe3#H&&DtCH5u?Tp`b2f46IDbE zwUckW!a{m>*APt^BfSet6X7)U^nJY4zqCRUey4dAU#-`|&gpD|swkP;+McgK(hOQD z7g^utrxr>VhR@umOKo~q(eTJP##Jj+%FYYY-F+|MZrRY{the4`ZDy0Ro5_wVJ^M@k zp7G*G+uG#|ye;!HJ%}euLe&Q9Ez8{Q>V8f~`6pQrIOY63VE}(e+4vo4=fAW{C2ODC zyOxlbxBX?R9j3}@n)1?x+p1wac7>MWh7y)Pd2+hrFmzUPQcmgpA!TT;)N7(<=-M{X zaRR57j6^<?u0~JXVP7M@AK62LlIZ%T4Tucj+$-Le-r7hrWf+y4n>B!0D`m=~QI_z` z$&~LmeJ~j_+xVWGUW8#v7Q}7t^ry|Btmgd#OTddFoMNzHm0iS+pLf&FAP~;*-KcGA zgbFU-Ex>B9&f7ga>t({n&fs3)!A6g8<HZbPwPAzsqZS`qW%Lp^&E{6OP%B5Mr7g{0 z@5|g`tZI%4mwk||q-1*_$4n9m8?GZi3g5K}7iT@SjduD59n}5XB=?#-b2`U_9%H|< z&!0OU{94cb;5xt5e47Mn(Q#$JTQe0bQtxTkoC6HS3<2bq7?y1;&mo5?W<lzV1K1ax zfrlFpFcWtI2#5O1nDj2TqZCC05ANd{d`w3G&-=6F<#+wyoH2@IgM&39rk%{(VeL*B z@f&x0gTLu^5|Zv!Re2O6{r-CH*&dfRI-4$^lMaVhq@38yXQ1u{UIeZ6&;Qp807BlP zPVh|OckM@WlZG9&sWgdq3I`#XV0vKu<dMGwQrXI^s#(`q!WV55I{f_`GBi`Yb3|9W zbYu<XUjFOmFKud>t;-JY&>zAQ&TakY^U=3oEqO>sE4Os*Y@Ya&9Z&K)k|;|~N8N$> z0h2!$w{A^|M56`n$<h{5p3S@iJGAWte<DkC)vA!mwcS$Owar^7-v!@Ro_|yL5wcX< zscNN}?wPHLND;$n#Xe@4+6D6yj(*Ct{VaTlVt3{R|4Z{3<r?cHV2?#xD{<A#=~7su z$rExB8)JL0EqE&deKo%<l9v9e@XHU<L=&Dd>Cltv;ePKRhCk2rwQ)o~DFGj`m0-76 zet^(gp{FHNL6Tj~O0EVS_EqBYjDGC$d3Oo18f>|%vn(ZeCR6J2Q|7jmB=emvgE#VG z`PV7n7jFh&G<LY)5S-VJe?G@U$c<;{dN85bycZ^OR8K_|+`toa;e;^g&5TRr#ZMSa z;Pa)?W|#t~v)X0+rto03$LpAMMTgAa!rH34hTg_z>)WdO=slhtn&i<SvB*IWc%Qp* z-LzLQzSPd)m)S1}?yq(dZ*5n(?g$e{1dl2Q*o{TH7|g69=^X0DUra#Gw|u5eW)zJE z+4RC<J2zG$&YNmUS$T9SMZg<obpE{YG#>ky(hXp!D|RBaSF04^XtHYt2c<K$l`v%a z+(FKpY+yY9tjV~$Ou#^<j_-lPV+=DE1bOTjh2)R*H0gVV77L_>dh7V>hPx?g24gu` zs<OjNn*1(EYP;4ApGN2SCN{{NIaYJM__tqfNw3cqSpGf49?w_BJx(x>K#ft?cV274 zZmKUjf1lyjI<)KT%wlYsdTMnf-YdAUa1gIy&*N)uvR!f)MzXFeQc-2)AK*nRBzyVb z<?cLuiX_V2Q06k~gv+v;+%M|3OZ?sgF=D!&jf^AP*47WL<Z<<vxc|bRWvKsXB{Tn{ zm88x#bg<+h(`4F3Typ{nwS#*&*MNVqCi&i>Zd!_X)7Yy_fhp#^!XHwtQS%G-SUgfz zHWDoO0coxg8tY^%ijHo{bL<f|xis;cn3%AAh5@qs^?-YUN5U1SwAnFB+Kl;JXsy%k z4)oNaJC0p3@15lu*Sp7LfM@ZfnZqUIZ~`j=8V`8K)AMrH=*W3NS8CH;FyiUdnyoT< zWK}9G7Un82W@+rsN_l@?(L?BmI>9^rwExJVGH_WfQIU1;q!&G|of%E$M&e70V+hOk z^SAE>oR?493w^5%<u%s~ym;Rp9!>KvcXu$ku1fN&cN-^Cvim;+YYmTCWM8}yen@>P zlwg^O*-v9D3sn$!#TN&EQCTSyK(=bZn+;FeW{5MWMCL}`6>$Bg(DlO5D0nHB;k9vm zgC%EZ+9!hV-A^6Dv5Ji%$o7@~I8oELIF|VF<u&)n=icaH4^&#RX+@;tKJoj=eloN~ zJ@R>gau_4mATS9BK2Cba5T9VF|4$;o!`?ri|0YB~B6YYb#Q|}4&aE7KJIK;@aF1vy zUq1hArpQa%k!u^Lv9Ohji%njt-;-y@+7mp%mNDHz>%4BR9Tn?YP;8RRWeR`Ze2%;J zJT7&*{A3n^|3)fJtF+Xcjn=;@4O?1dePbn5Dkz?HVxib6=+z}99eziZJ#hY7IVcq; zwAks_sh?QHqa-CX7=C@Z4g9;?2}d|^1dd;6(=@AfayXs2g3xi5=EQfmqg5HXG;ZQ9 zl}3$}u;vyD!Ldc>kt*39LcD*_X)z=az-2~zx0!=d;Jf}JkgXYlo#p)nsVpu`b-xQe zE-=5ta$bMRUPMLlJ3$@pO+U>a+009{Ov_8VjMcVS+<~&h^2_zW5i8G67E7gn;^Ih8 zTc4|jcQ(>4x;W8bDJaZ<Z%kIYUC1@@bE%|sTJ;gTUI?}2zrkKoJ&Td)B;g)jQI97M z%@sT)x_?pcfTk#HRmp$Y5ly#K`V@N0q}Uyg0pCvIN)+~SR<C`NxMIi~@LzDKsU{xe z2l5|r1TA1bA$fkjn5|Lvri0dIw+QOcY7{wSFx}cimrhvCN`=zM4=fvV`vRoqE;N!@ z#@qh!cgc!-ljY792C+!K_nWD+$OT+>Pfw+G-Vf<7s?w`-S<@k+Bdl;bO2MjTjLHiI zt$}%w7#%p^TXN!|t>f4a;i0wH&rI{H6PrzJS`h!Vq#2P_t76n($z5E;C9g*RtAoDx z9W~#}R$U5*hXBIzWTy6MP~(Sd2@v+s@SfkLmWaE;t0?%!@Ok-D*wU|kk7M?@e6m$` zr6s6-^$Ag6fPz@S;){Tz0DJ>$*mRCF(rNV>^6+?35<a5;;D+f4yg}VRR+SS7@08_y zA9f61Mv1@wcYzf0gUYC_$$WUZ;H2vp#`uPbJ5;;&C_LDV;$y_(SbAOdkSAEUp_SD8 zp4wno(O50&qQ(Vt@MAL%nYG?l<CE6YeUCDRejO!sS;wWz9XcvwmsX2$l~K4)lH_<y z#*nLZqb7NbO_TPQ3=Ee`4_C}+`-F1eg}1bRjfTt%Qqq!H_b<y(d3G1W56dxdi$fhG zF0ogh1DzzUJUGOSqkbc?p?=i)VG}nGz9+434}fP+rNL<-^{0?uR09;8YixkN4>4-B zM}({<PX~)7nvurx6ucabQ%3Dy7aNSHFq^gLTk5Pf;B}_Hp)<603NnCJ;BSwGj9%B^ zxo)bXLfCjeM+<O6JU5#49-x_`^#I(pvu^uzWV4vD8}Qh~$6oJ0>VxD&nwjonC0`aR zd64V|!h00I>g;IFo1BpF3X(xq9xe>=ap^5qXoahS5ERR8pyw;(!lk32F;%Bk;g+Za z%C(LyxcameYMpe#!&DJXwnxvCcN!E-w)3<<ZDrxLPIE^NOG1)b$--`2tI?z}6@r7_ ze?0fvTkS~`l>X|ScV6s?uQ+~j4JFk|h}Nt#F&M312_!~B!ebvqZaWS7gamR8=QS|c zReX9>q&1xLph&g~V{vPx2qCviX3!7bmr=_#uf&1Bj|a@REN#zbt^bT1sI<X)zJ`95 zB{{Egf?4=1q@2W0m+2OgQ>%uGy`8W0wBD0-8Vs=>msTea-lZ7W@MvktrNzX$GO{D! z|BIaiSDBdYy-#mE$I}d0r<9T__lE{H43MGR?0bNowfi%ECMMer5q&$DNDTnQo8$%V z);O;}ExW0srO7qs-4>LHDYNDlC(H{Eh!2BFGwEZCF-~X^6yuC$aP&N{G}{Gk==s<k zalBKmp-+rWjqcaAaR8-;H1uK9#+TG?REUchc&uSF;ff(G4u^&>;{#l8&G}q5;y-BV z6_u9L_^1nb2dM@#I-cig1v%lAi^u!hA7vgyVcw!U>U`tNd4LaftROrW7b*nd0Nw=B zp2Fs~HVgz$jc`nA3|b`-_<9VauOA~>l3?P#qM(MD>YAE%9&($W|A;G$oj9L7;2&9Q zxj*vAa^QTqoAQ_pC+v92(SP?g6aRJeMi72a;URL~f%IhPlAsGJKy3(m(r0A2aypmA zuii8}bsJZ0ewbyAO|5wUrs!Wg`(156k(ibiUGv!d>0LMp*B9y&F<v+6yg&RWVoPB$ zP%j1(tSqE*_s0WG($AKG7lq)S_j4wS02?5picAJc$fjaCvCF-@Fw5fJW#Q!2Hpa<f zhY#5S$H|?7L13Tn<+|@%^HtW6-7ah}sVK3SHUYuc(rzled8ad#RgJ_zu|TH~I+&OF zH7``$E8(9q+RJW2<PD5FHnZ#+t-m12D2c+&;^kdW7LsemoV{YC6?#iA-r$}i1+aOE zyhz@z4lSqiJ9bo*5kx3&>6vuK5RabjC5CJRAj^hxfMwD$`Kco^3p0k^3Xg_R419-% zo-M>-hZ`>t`7UP&Pk95@chhQKFkWuM<HZnrDg-%d7Xhf8R}<>2UdysuYA82|2b?|L z+<pY9*M}Efawtu8%y)f^pBLP@Qz)C8V#!LcgEEg|gUvVwJ0BEY&I-ZJH>0$l2M~`R z+i)ke8i%&5gLB~g^19Qe^V_j$#WmF5ogCP__D}j6L2@*^3K)OX?+XimHy=M~&ybg6 zPIg^Fy?_>c3~pj2b5zsS7TSN(x;q41ZKC_hZNP2JUBw`S56cPye=(vt{Zzm#b1yj& zDCyFh(<%D2yq36BgAVf&R+TAhyE<&h2R>3xX(0|ww`oJ35N{?EcLklHRPzb?=OaH8 zq#+0`65Lj~J*h!K$3*T@FhQ(vEzX!2Af!MQ`BMM-=h1CK`wPOpj-uin8S1OArw!^m zWbmmE&H*Mz&!*lZXViuZS1u-rFuu^J_LS}T+M51p(_Z~Pl{hXYgcOpvgVD_w3||#* zH%&C9J~7s{t1u0Q4foeguB!q(Cdc_s*WahgNAolh^HL01Eg%LR??Yv-vosIDF1u+C z`(r-uE>q{N^49OVZ^5U)7?nT8T#U?|Os};^{FGBt7p0UC($Vxbw_dN0rht9bC9)=I zAK3>Jw5O(-$3Q4&oj#^1@Ls0cjE6gTqXP~s>&?E5(WFf1e+BPI=#imbP!01TG9~yi zI(Gc(!kJW|5s*Z{(_Hzq(O2CwX}0?%Uowl2D0wO)j6m|t&+?7u6IGTc%oIW7hnM^X zTL;af9wpe6olc67?ndH$xGYxybGW)!-fgH%HY@PlNAK%r78;Jut;fW_Z=lWL@!|es z)2yg-{<a#z4w`ZZZquMNxRH)lLZ(les$H)dY0*NzCvM9cOFKNmq-{^W`)rV5uv5sQ zT(9ZyJ-=8!{9YktGmi^e=&I;>gCp|Sy<5ZlR$6NF?3DSM{?h~9I)VS2uND571w<{N zB7fq)j;gHRgjzSmo{5ac1p!x*kZ(K&&ESn~*C6~*R)oB$^FSubdT`G=4<J037~1EN z%4*t1(pti5SsFqqNA9u^fe!!_{{wW?BM^>kq#yd>#;}dM=6+q7agok-b~Oe*Y-5m6 zQxeE~T;T#&8-Z6M_M0DjBmuog&@=sz*fZ#;gm0CzuUJcBeLTnPU0Z%z!4Pp)LE<lJ z0zJx_01`d-C+an~A^zpt5Y~^B#3koj`t^;pX;I@e9RK&eb@d6m2HcIpUNK>=Nlh*t zRuoB@8rKc{2m!E;jzb?&joj2?%F`VFsncbTS!yEc=FZyXK^-+#OSZcEeh2tQA8^p3 zzU9x0^Ki5*>K0`sdFVB??{X2qE0aL_2WE`(m_Kp#siLbU*e}g*gL+{O8%4yf>E@>~ ztIHI{Y}1Bf;X|^|&vn<q)f{HuNWWquJ7=rQQ{LrS^-j|p4!K$C=BK9qmGY4zpWjFA zny*t|d?rg&zQ#Do&-55K)w?ae+tU1kxZ>QGP7#5Qfv;0BDfyoR^*`rITMZIAMq6#O z^@RTbsxN`r-HKt*=aPBV`6Aq}FDQq4D%#P{=7F}kv11f8p4qPfi$9+ji6;<snb8MX z&x4FKp8_$P%j+MA08x6@21{!<QmDRF=u*6$%FMXi&5!ewv=vvzO@2Eh6ImSS4cv`2 z&F&tyc4x-rdft}QKMj0U@1q`Fw;wUDavK<OF?t3QROG6jhXViZ7q-~F@p-<#s(e|t z;dBHoq!QY%MuFmqr8A299Zu{B!Kj?aW9B)k^LK6&gV}mz5S+9=x`Bv{9jI{lo?K~H zFOz<v!Fl(-Z+sx-;TACY{in;rTf|SoJjV~{vFJ8Y2E6AX!oV;6^1NsM!qCBaK7yTn z$6wsV5_=V&d@S5J-9srF1$wmW1dvp#_Ix%zJg9KD^WR783h|dR74V907sfxQu_|9w z3xE(I3Ooy2@BLNm@H#E?){*xRz=$kKgJ=8S>LQ>R{?3uVMf;|_$!$pn^I7?C*+e;) z^22@+TFgqiU5SSrep1;S<oMr!_7T@|AgO;r)I!n^Ql{nUm#pi*<()wZf1Rd=s^DNQ z4#ncy*=}+=Q3Hgk`t14z;Vz2D0cusIa}fA)m*Rv%e8b+v#$XU1#_O&R##6)f9Y}Fl z3}MoW#J@&W^tZix!UktJ<2m!baPi&FzaA}<5_~&Jl*=%|gis<~5VlVn^Umh8na4L* z{sUiMp_8Qv{^FfH@G&=aimL&6ES^<EV<{7k(&qF1S~a7*PudZmz;7Bz)dWA6gQ@pa z?b-O4tkkGG0^S&;Ke}JjXl#Z1vX(z-P;KhLYKMKz=z5!VaD9k1#hJIDd_NRI(`q>D zE?M-dK9l;C>vpAPGh%Xy<<I<KC(@3N#}xE8uSq!DX(9YtNZmTqrU46=#g)n}Uyp`R zxBTG`tk&3;7m`r^4=18MxXn@8L$wRztRW3fX$OGdrHbESgc8CE9_3|JixG9gA*J8f zCbKp&8XS(cZ6akw&Xa}v@1KZ49<Uasp3pH3`T4ho|3(@3ylx=y!*7LkQoQS$QSNIv zXi^qB#;N!=30K-qh*}BDpx^4vkdcx~t2^4e>EHs$aIC|<{Wl>;SO~)t0Npw&r1=AS z2`XlEu2HvE4Xy|VgoCms$3{(!j>>^VtK|%~U$Z|}Z3eYW*&W<+Zr$NciYR9p4MnC* z;*CNwiSRM@wECKahvb@vlD6(uBVD`%J#di$rX@|^Rb{iSF(5Uiw`iooaL#FAxznU? ztyhGl`<|Rh`}L)d8Tq+bKfwcpq_Sc&esDJpj+)C|{Jp=k(x_X;w{$%J9e81d@V7>a z8Nnf(X*ZqP^)Yej@+E~?BbG>Fjsu$6Wd_?U6>HP^!fb1>vv^i3I}JDjWPWq!{#EjH zRfG)oRK340&SqZ<ewUtUr@eUCN@m?i`i(iS#O_swKpN2A`jQknDL+YD=3w+Vw5{+; zHqsSafc61U4-rK?liF_bHo98oMwJR5U;|R70AGC(qTEPJ9r)ki?n_<$4WXUA0_7>g zN#IG}_0i;JmMb0C*Xj%C1XbAg6Cd%{<?X*4S6Shr{`Oc$94oI9lX&_ykO;)k=3QI) z-&KB5`Q`oytSmET4*nVktRrw*@Prp8{kT<FCX4PFVhsmhB2MiLdr5LV9HC~yv7A)a z7PrO;gYpVe&9E$ca>E)F`4g|nR!15CSe9DtCtki*YqkH)(cwm7Rn<DW2vl`D6soJA z=2s6=p(~-r#8sZXbI7_nRuc#{Z9<rSZQa5ie=rETe)05L6N^aag4Xu}(_mOg{j{xY zGKSud@qe<C1?5aU1uds|FD`X@U%hw~lu!TNpd{GtX4LQY;c%27modCTI>g5VA`WR% zSg=5(me8uN+d#)G+*VWlhwJ`_@|x`-;P_U!`5_4{R>+Yi9=RNsjd&!%@2J{1CG<s~ zv|Qipba|><&;2@IH!g$V`i9lCPB#2QWa}ajQzM&D{yafUWLU$TA^)+{->t<U!+vzc zY%|c0^0Pb57F4eMt5lAgsvNs8fo*2j=$JBV^1DeQb#rk}mr#7#Q#p^x>!!y8s7RHY zB()Hp#hkZR$#8rywY3MkqmXBpRjg@=+}kiPhF1M>C$nj@Zz-OV8Oj;qPT<lGA24jA z7yWfp_l~gQ@)OEle?kskdERP2cHZhQJfK3u;O*U(=}w3BE#n`%D&8Jq8^wtC>)v;d zk;h}7U*E0Umpe0cEmc3ZP6Lf;hm#3J?M6Y9pWOeX0RJGS00t9;X5Gn0day`YBLfwZ zqhH32{w6{|{3q~XUCSem05(Khd*JPtuK(kME##-ht$@yk5!D#lwEh@gm}mo+2fXb7 z1ktPS7``{a?0~nE1MS66NtXR-Ir6Z1yPoaIIh$N%Ze`<5*IQ!oN=jYwu=n%CjBGRF zMu!O8x4YV>`$sg-4QjLGoxF<ydB5C|>_zZw6STc_NeSsJqg(g{FzqEmsbKq^zHgx` z_(c?bmk-m{R5yTTbeG8}0()~-r&{iA7B*<l-&9rU{x#s|?Z}jV+YE6^tf<)Lt5R)> z?QlS{6z5pOg^t0iQWdQ-ho~j_8?|EcFKjhb`9cn-QLulk!bdNT(mu9%aOumJvR8&m zngtfzBf5anerqJc-<9{eHzDLg2sAEEuF{liN?!>F#^q-oWAe23OKtKJA(U?WZpp>} zG}N2F{tP~vpP08rUGl1?NWBlNgDU?a5LAz$IMI+(Sw2(EKo|x<YN7OY@yZcrf?Fx) zt4i%mK->1ZO|n@|yhhWHPIOpkehK3u*l)@HebbK!K8qBOiy42>C`my*<#vM_CeIvc zj^%;5VwZsDls(E(%L&A;rdd@-dLL&|Ew_tYld1{GJ#ACN{P<(b?H9F8KM-5a9dG&H z)bB*pFO&*Dsw$W$@_Z;mgQ$=5h#5(U<7j_HYIl#im^=j?f|kE+v!eXf=FCB5v0B*| z8HyG<keEm^8|ISF{rbiC=MW^1Fac~PwSlSyDw(gb5gf7GLHbh2Ml4wG<gL8y6%=(2 zSx|BFi$UXWLCSqvIOXHnG7sjgB?erKO?u0c@wy&Ju()@X%Xhx*SY6?w{NO}=a6R-V zi-HfHau{`g{oCvUbFVsc;zp!m?~uL7aP=iOie=)EQ9=7x>b0m$3<@hX@~p`Do-XXf zQETJt(I9xQ;%ruGlDx4d8U}x#!<!sVx&4<%MO7EBf;NC#yGEJhKfEFTp@FL&a##yv zu9fA#cmr|l$6}=pm#Ysr-}BZ(ko&kDG%n)ge+DfbZK+$`BQ~CV{W(y-AK%ogg2X){ zLBYxHgBM&fI&+#(*3IF@2!GDh!U`jeN6QBzP3X_cBpMiZj?aaS*o0goyAZ0fe4#%4 zZ6dr$Pa%;@o@$=DC3O%+VIMN}z&(bjVD%`U6?Q#y?PSN=buK3^Ti??Le73ZqB8d11 zVbN%_uJe1c5INawEOg)WoJtgB-M)&1`lD0AtjwFTC9RcmAOQTCwe9<g`+<8a#k$n4 zKWaJ0wcsO&R<ZKr!f?Sk)bqmWmNjN0%}Z(sm&^JO>FY?0G}!B%hg67bQ|a|1Ev$W8 z%Hg2<*eiH6T15ZGlwSyJP#-JC;s0TPErKruPCjhlCthcqkK(;t0vvu?u5Oup`Wh+< z1^#faD+(RT4eeZe^m~d*9<_{c3nQ&CfvhdqOojd;Er5?A!@*kWV5+l^(|VmW66Bg2 z1Zc9zQMjb|b?QI^87q`=!Bs+EaddZ%kg8(UQ*{)28OFYjrKGOh03wIKgi&*K>}#4x zWf*{7*f0Nfl*6l<llfw=stbKft{|0obaLT3XBRJ<keQLD4_F^OREN}1mEO{DQp!Xq z+wEaNfwJ>zHgw)kRGf>+%T|UD9$NOv(Q7~W<fVG1h2(j`&c2?2YH?BydC-;}{VU3y z(TP!f$F|7(^P_qiYy<8VT_a8W$0|habNv5j)%D1YJg_?<hPti0y#ub?d_S(UQ~+fp z^V>H3IalM6-yChrVPbmaPBgl!`~tq3=G?E(W$@RR24)Mm%2%)R|6%uM5oA@@Z~D<$ z({;!`tf!zTo+;N+y6UnZu*i~Yp*V4m>|Q6yk#t}5gvH|MGUF<?AM;C{daS<Iyo&K} zpam#D_Ho9V@7U||axuAOC}+A;&aYDJ1M(w{azBoBlvBOtzgGbtY+>ai4z5|jR|Zu6 zfK(#I77mm$Be45EO<v!x01=PReU)W3*%mp~^B9FJ(&FCk@c5)eG^$c+IezgeC1brk zCJ!O?ge-hu6<_vu=hT8{LbIk0EW7-O(@}Y=Wh7?#y!q#*dZ4frN^HYyZv-+C?Nuup z3ige*4=v|i>xycoeV**n)NoaiQ0DiK%_ncXu@ms|Iy-1Uh<`WVbPNWL&t=vTV2x-R zw8x4Yr-{^y1s#KA_-#ByOsPAQRoYOjv!L!Np?ygkUr5cD3X7|noKeWF&kcopD)Xgr z>IeCNVKNj=p)I>jj`3(Jb+ml6?C;j}OftK1haNt@1eKpTVJ#IdJdg!n4$eIsx|Nzh z*7^QV3ag#8(3ss~F6SD;$@y^J37@}b%4Y-*jbe;gPgSunA0pF&=cO8UHsagsj1jCV zKNivopVs#OldyCA^lJ*b70#}klzc~I-0a5ER$%|g6sNR+vX;_*zR9uZiRd`T(ehRp z9QLs`H}s7vJ;^Xhfrm6KDgjdh+;)feYfoR)>AzQQP;L~wbr};1h5>tWCc@TbO{I1; zIHQf>))E*&eNlo}d2s4g=`<sMh@xDMYE|Xgq2(6K^a}S6)<2=aby)RsrKPpPn};^^ zw#J%P_~5;0rr5mAhbhOo6o@v0Af!~w`d2oL5;P|%Bdg&DYZ57x{~shYZ-X5EL4P{= zZ`5e~2M-q8hyS4pgFj^bZfS%F$vG&=_xQI|WI7{gLgpypa-qD%s`sGYKP%R%W>9gP z4B%s%h!I?&zbge-`9#kAiZ7DcHFg;8kwnoV;EOjkUUTKX=eAY>9)D&0Y2;F#P7HgG ze5huInXtI(!X&$ZylbL5@uYu`2{F6=m4OmaiTUy!IU~Nlh;A1olnFyr{^gX|*c0Xu z@|euP<3h4ip-d}xiW29(E27C>ImhoGbn|1J{*-14VGsSM*5bc57}r0v=b8uCw?Y$- zmKk=j*teZ9agA~XVRZ1zP{<EmO<7YyG!gC)a<0Rz^c*cuOL~x6H|-(+@Rwd1Cv3;k zRlt{_wxGlUq3)r$wIs(02_j1DTwv&SPI`5^qaF7oP|;=KXNG0t-N1ddvkg7p^S*Xd zz8ntI(P(8I#*CJ_tlE6+g`e>Z{j<wPH0CJvTzYQpZ6Sgk@YiPGt){hGk<i&c$HUpN z;^JeD_u@Um^25Jx|FifXCad|uaM>-5D2lpQ5kj!V@!7*j#Cs&y+@hoC2BzMP>UUEn zJ;^;~e~8v+2y2awp++W=;)cdd{PvCh42}@v?uMTnfmYHzsZyz?$p}nHFfIrbfvnO2 zM!5SVAw$&|wA_o2#$c!=Sh`&%0y+)En%}hueP+zQ^`=?k54+<Ya#l)`N`H<Y8kE|M zi;s6B%41M1E}G`hOD=0k_aJf*Hd<!wiqDWNvf)PAfSbbOlTbO!(VPRv;{Dx+!KE!G z%;0^dql%7@XrajT2dfI%FRSJddYiZ_ke++l9oW4Y6ci!oU8f=ho5!n<O$IvVE&nc8 z>V`1h)%f`ANFxGktbf;|+7H3A`d<FXZPxtA>xmn0*$`A}0$~r*v`jZY`%WB4&WAzi zETRIAdL&Um8~YKKSWPE#gfS4Ouf9{x*x3_&(HR`Q>4OrE#V7%()IyM4&7d{z?ypW7 zU0{=^T$Sx;TyGZX)Ah!3w_@~v_<HN0xZ5OJ7?<Gg?!nzXxVu9L5D4z>8r<ET;O_43 z?(Xi+9ro^S-o0Pd_ZL+RH8cFWpO(|7&r=8iL->nkI2UP~Ih%!;$+tg$B;m)kQ!Jz9 zD&*ru>c!@Ph!m6-G}50?P)o3|;)B>jYKN?#?<Mtkmy^O?U5o>`n!to@2YNt+;3vh= zL(T-L?`XLT1wrAx?xfxNAd@nZ+6S0E24Qw6MzA)31u&N+Mmux>s07{L@xj*)kX}PY zt%Bzj&UNLl-B<k9e24~Bc%_2aDbtf|oE{E|-|B~`$Pj0RO-)J`!1=PA{y{!Ahn)=K zPztDVxzOEV-~cB92HI>b<-gFdH&v7gz?-CN(U{#%w1Brr@=2lChP|c&zF$>Vwt|5- znO$BD5Nr(@>vg6z!A$;<F+(lY4Nk5(_#vZ#ozh?#nhokU%{=MWLlzLDpo!hZlYkM| zZ{0~0v^CGK8`RF*!txzR!j{}slrbbU^zzA=U^93ivwQSOYO+`ZowyJD@i_GlWvFet z1$U0#hvlH8l<g!FXIdDO?ckD~Xa8|LC&y*y##UfzdEez0C|)R<<t@Se#iY?0h`5VD zGr|iz^!xA#!#UiaXg2b`9Bp9`k@P#v@VFmSzR3W!p2W+{hkg>;CeG@ZTy+*VE>GQN z<oqgS*bRL*mLbW5=4l*N!Wgd_yDtnkg-?fbW<cf5&ziUnw_W1-s^iQFXuG^v<o>mQ zNN@3fBfaJSC({2Hnl-@#{1GD56KO>~X%1;$=REliK<J^OA8>JX=*P=V4`$U&IY3gm zW~$x=6J^~4vSH1JAH5s`p7)A$)$uG~P@KFqhe9__HyWwCgtNxDD#-A(atHo!F}utz zPRg<~!fII;k9NFE>%#?({bR#m(0mT7Vcng~)qb?Q^n!oj&w+OM9NDkMmni<tc^vw0 zE&Iw6ow6q38M*xL9H2(-tDY|wQ~6SA)(cG}k?~6R_))+SVWI6qdT1l)7evQdxjdXr z9x2qA+nScA=;oZ|$Jzt(wNN9T89_K!?QofL89sJ&E!Zs=)g(VSJ2s<R&O2c~lA&16 z!o1q9h+XY1{a6G?IJC86(?hYC_j9Z^JpC($qY^}k#D(hewH$VJTdEu_s>SCgQB4Fs zAEiKO6;=Tt?ZaM`{`n`O8ZPl!w)|qXpmWIa#=VJy3U&@7x<ZNaRRrl#lul*<F3fPD zO2F{HJRSMy&S<gn+Z|-$dE3;p*(pQ#p&=o)`tU$u-6a8u#C=^V;EL2AQ~So&pNops z8My8v!G#%}ZmM?C@47ow+AINLK$i5{H_&*xP0eVtjLq}@iut-Vm>!L+5fG{C1)VF` z1R*j+YqRd))lI9G9=s1y&IK8(6|rZ7>2RrXpyR5?KgRml$l18bHu{G&28XZCo2|IV z`AhXMv|#LZkc?~w57tNmeUInMxma7>oXbwkye<%vY9lPWo*mx%^)4o^-StxAPWj4Y zfr`@Z>nmtE{|9mF<-NT<Ruv>)`r{W(V_V!~#00pI1X<eQMmQc$4P#?u!%(gfbsq)M zSyh*!=dC0h<GeXGaAak`LxXO%HcPeuvZWO~o%)-zrG3gidw;Ey;gwc)4PXTdU}9S# zf{m2R-z!zI!%{W}tP48<3j;g5Fy;Np2kHK$_T2@ofUlLJb-5W^kz1+3-^!`a<A}Ek zpL`9W43rpWPeju_Xp0X{wHPOK(eQ|=0<=uN(n5yKG%0J-^_Ay+GuQd>3d4F73u9{; zhh9X<l3MPoW?+zI2Q>To1K{>$E5DYHdya^wHCdDHrm4gUvjO^a1T1p%Sc;r+1yu8! z8I^Pnf2F{Q)kY1lT7|OhGd~&+yKicj=Z#K`9?!7ajzeUY-1q$;;tNUuwWv21tQP`% zux8kGxP~<s?s~j+jG=6y(YJl6G&w@ft3u>7`?E9W$MKoya@GPh19wR7L0;%=qsVpg zJ4(D51>OF!Hy@bO0+UVGnoxkm@n;-dtt&BY0v;?jU2Oa7m@KZ~?Hq5;_I$fg_BbBW zxtS;ZvXel&{a=6HHMoL<5e8I3jkZGKZY9Hrqx9`ow2Nx0YT2JGAV?eyiHC|*+IC?y z9_Qd(PBgR&PUyh*HX`)rC_(UkKoQI##594Y>Rp4{r#3kd08wE4`DPs=VT^VyMR37f zGzyeFguGUxY$zpRK|QP^8;-&5OJ|+~#HEkDiLWELn$$_In%hB6O!ky?H>2$|Zm{74 z+UUR`O)kaIWJ@>x((}t%e^u^~(@?JUb$Mp7z=_&)OCzh<e!iH$o1;tZjQs#Q8atyQ z414TwyF5wB7P*mePB$w-%{cUY38f9HPGhA`MelTGVRr5=2PeK!j%Q%4<6#T(QU4gB zal3jXO;J~7?zh^!(`%J0f*|<@sHKQrjXhF<Y-+e?kE76vBkga5qcP2l(5s5J2qn1| z#F3ch&7p<${;QXJv0`ttRwd)&ekdt$ey@hT6kZejF9{?JT2Denwo$d|I*wo$-q-Pk z2c3L-8cg8GN&qhoZn8Af0=T$^$m!Bw7ssvxv4T7C<1<c=e8<pTFFI(Vie(0BqAJ!% zEz<-(XeI~x1GR{MH|VA?MD%Tn(T1U`=2}QPg9F_--Hx_BH9ayFzmY&q+n%c$ECH7? zjJO+W6vU)kRNvw7k%*UM4P7Tfp<jvo2)giwoL5tt_;AM=zV}bOb%NxsWT8)+UV%WI zBV!QeuIL&U{*mbovK(-MVv||1mFv&I?i9agG^pE~DK%?qZE|}`%tKRa=Z7@q-<j>{ z-gdHWV435ToeG7SkreptNHWvEm{&%oD$+KLUgx7Dhhz6FQyFvlZZK3lyMHHCUML@T zQ~e5*#AZfqp!%w{YUj^X>Dii~g*2Aw!nnLYE<4+6h__;rR*516Z1cm}s(T=b%i(Kz z<0EqMz`IUE$k|y+BUMS$k2%62jba?fURaMN)9K(&g&iA%ww}<{3|-x7WUux;w%4oo z!YR)|OXs(-1;$1Xm@?#&Y5cnq*~f*kAQ$~HxszkjsrWuR`3Qm$-WGFKIs@Kfx$h^j z*R}Uds=4X_Luq{)s?F2q4uTMr>~!U?o$9~*t9=;#Py672M!0LU88s+(@KEIoDv6&< zB-y+_ey_wT+8ZHido{d4&=sJz7I9jQdV9KoQ>In7i{*XGL`pgR6uAc$zV>`?1hzZE z_yefnoU5{rnGBCImYooCO5mATD+F1YbGH|=`fDQCIqs062;}B$uzb>YRHAquY(GAA zQbhG7D!_)<n(Ftxn$@wehjurwIX_o>fS&B6(qps%W$a3IZZuEp?d(n?fc;u&;sDKM zf8+xI;kn5RiY5%hl)vK9t~_+fu<M1K1>Nnd8fEw#L1p$Eh_R3tH2u+962dd|3H+_q z%}uu7D1lVVwZalcSWrC|^~9q!1(}HS7&kVG@w(>>OXT0c|BA@}`UqOyersEg2BE6; zYky$6M(SJ?28mQ}z{RQ<Z$Wcv)Br5%m^4`MS4iSS=f#oB$J9e8W)|RXs7Y$J_-`uB zeMRx(Y06-CZwQ>YYPt?oOq6~=wfq>fYu0CN?Uv5)653<7f?|CBP<p>2>djhklF5D6 zXj(mns|~-976bSpC=PqYD;7Z2&G`3*e__#ZZGa(J=_>))Xk8Vu(q;o{kpM4<?)Xg@ z;aABDUSQ&`a&`P`JGIRiX8O*Xig00#-`2w}6w`W<Kr~eS3@oLoX&J$><D587>yDty ztV5UWW;{{~_yOIi5_|qOJO~U4bTpLWqTb{S0t!@9Y>AJXCd#P%vdLjea=hsZ1zz8+ zQSP$Q;r072JY>o06gN}tPb+)wA75tVetiGXr4tCN*M}^7#Wdaea26N>mU#a$uB22D zM`(4YxN3VA?tFWcC@;iOG&pbQjg}Sng%H^^ghaL#@nOw@wYh#`TYHg$7rhRSS3@_@ zzfnSBHrh|@>6C{8bWlS-YJacPdPctf__!;*LVSdpSj<kUsfMS$Oxt9fv&t53{mGE0 zfB|t#CD8<?ez}*3?4*)94hfZ7T(+-rxb&J7=%_xz4%TPHR!H1uRK66E-~ATbapeMa zSApPa67$4F*HVksBA)%{NyOUKG<AhRgN~?kq`X>?UACBoA`3y4HTpsPu@Cb=$Te?l zP!VJlw$6^7C>rVVgvzpVozhGdz-lR<R<r1vx2gahygT{P^tTh56#qnhZ@T}{*CNL8 z!TVf^uJ|HtqigRckc<H{Fc8WpnxGYUJ#l(^Eo!JM%!3u`*h2>*9Ev0<cc&nsqM`5j zA@FzWz7Tj%<%;DR-O%K5eIG1`>Lvy=^i^i=c!a>vbw;xE*sfUA-*vntP-Y}TJ?Rxv z*rF4n{6T4~9@klc3Jwkq%b_z~G)xm;i1z|L(C{Nv#U)aLHEIsTWk_6BLNJ#6mn|YG z$1T47`*E>KQ!f!7IHI&&ukvL@DG+n}JBV?*8(Diw9qfU&J$XIeG(s}zZ@x)sWIkMW zeBt^PU@=@LSgty=Q01lWjJ-LkJNv-h>3|XIB{Z*Y=)w$dP=xhZ`Iws6flTBR&by~l z7ZbSI^~7Td2~M!wG`p~yNQP~DOG`G%5fYvXMPNT6c%YN_x8Tel<Exw;54FtcUqaZ< zoXJ*3gsW7jGY*o{y4@D8xG<7)ZCG;3eG9U$iNA#|Y%YgR^pQ-ohZ6BT-0Y$th?OJ& z=H(?KsXyg116axOIi7o!D&Kw+jo&C_)Q)q<+^G0p{z7^83(9bVE7Y?Ab;RTW8p0ld z%Zuh<F9cuEMNE2nHX$<#)+17>2UxlM)5=a~#hQSwqZr%K>K|uQ_g`nT>fdMcyT=zO zJLnsz3y#fP$ZqBs!fi5(Dl*CK1nqC0eVJBmaO|tR5Zo91*a$q1><|x!s1J{^?6`l> z|3qVEtXRlo?Gok?8YUI;FzH>1c_#DXTzEYK!*iT-)S6GlbZNIHW`5Tmwdg^^+X=K> zB0413(nj`I+Boe+Kr|eXdduA>5h!vsE!%ZTt^9eno214=Etx37#6>=y>Ng;H!?^F$ zu^FTF9-`_ex>dK3`K_b;40?e>EqRxRj5iOZXvWc?YlU(k-u9X_F2kkd`tlj)LO;^u zLFm8|uQPqfQr9!J{xr7_UVt3w(8km}SBXXBW0f;Gh5BVqBN8N!I)Sba1FUOAwd^)Z zHpQCsDe0ZT7#*EfGYs@$ZKBDv;F@Q=nrT^3eZ^PvqUiwNKZ+JGVb;wRz!8)c(`Th| zfQmoZIT(tqeDMq-#wfGdlX2SKwu?C6Oj1_C4=a`Fl9#+1ekAnhc1O6~x1QiAlz<v; z6`7&fYSDnH+F6IpF$mqKA=BRHCK=l``qR{mHqE`u6`z6pEhGAhDcooXRa_pB^~evq z%Z%!Q2kXG9#QrglT>a8}2%M|usUsiM&pQ{Mkq$f<o-m4SzW2rX_1k!^N2@eEn99!> z52_BZl6_A<KLieRW>wZc)`mAEj5Ir%6y{3F812(<A-h|HTHts#rxG4lk@b9H&~;!# zz40-JdzkutnAw=20qhz%dHvlc_yQ2t4E*#sH~SM}5>-63Dg{;kM{yuUhnaD?+%AMa zjeh2+Rp0|yPWE+!O^c(Ed9H#VR}nm`c@|tR3X{}cbGB)ow^PnHq2P^|36R!1Dg#8Z zXLSL~3aVp){boEyN1~++-I2bJ{{ARU0Xo)n!+s1)HPmtm;?KRj9Ba~fkPQ~p5slw* ztB6*pfM6NPWfFo4f%5EW4mv)}R4cwgcYt30sRHNYe|%LM&0vN!PIt#v1QTD9Rp{Jf zO-V^P-ZDrsBgZkSsnOl2F29yo>A%~+g!Bqk-Hhh88bEX6^YdIe^XuS$PzyU;2%oB0 z606?NVKl)B2(C2HS5Ak-PDrEx&O2e{)9nRc)bF)#zy$V=YbfC|P_aVQFV@p@ktl9! zCAoY5EMhc1i<nl|_<9`g(%J6we={ck^<%LZ5Mi5C=sRRQl~AKba)3}Lc)}RHC0P=- zdC>4;iPfbgw;fMSfHN9j;I(abgb!<GqMc8J`3-j2(xHZvpm6(e@u;_R)$<I@x8+8i ze3To*pBFMQwmYm^{U$t<A^;>D5R#x<r%5>-j-mqyWqJ@98)OlNI>7C^?ypl~>h12F zii$IhWU21~@S9IuXoL!QeX*y}g&RJQxZd|?%S|@5b?St&LsxXH2>at#+KBj$=+g<; zIq{FTZ8jXYk2g~;sXAAav61?bTd+mBfoZ?M2g6d2o@WCjSi!cgRo{G#Gu$Cy(2Wfi zHt@pz5LUsD&H<uLoY+Z;YW@xDZ-{zc4|vVBBgFF3-NA*Kp|TdKNSn|i!w8Cqlez5d zaa;>fwZiUlk>gTP8@`SqzHhuQEzi{>OPUOmtlxj32|tk{C<NWG5I7?4I9h_=PdSG) z(!#k*c6Sp{Y|ZY-4ftn<STB`%b&si~`$}8>N{sQHF+I=)@^lHq3L3LKM7B(g+>DLn z9|*FN>x`zr4;5U27sWma%z@?Vak4!3&38U0sK|1uft_9<zCE6Y8{@w3h0k>qKu1`+ zwPs2Rs^PLs^+*N@&IbTuy_yv%rGU9_EK|Zif@?viY60NIGV?Br=F|#r9?YYv!n0aN zBw^8NI!elKeEi9@nuH{EX)6UC14u!*K`tZ1HdA9xTOm^K0v7{7;Vvk<C*-6BWrHA! zz6!pEAgLl|s@pX-7ddVnK8;uF#?jMxtQjt+jt9KSLiCacIDZ^*+g)>v35l{{oVR(d z-N9YFm={!Z=)Dcau3v9f5`yO%!L^-7;kH@{ckK3C4fc#EzfuWX3UW@T8fO3c`Gt51 z#=843_j11>)Oz2DeKW9xPGDu!-ZE1aAs>HMk=n({bo{wD8vnv4#}_vY?*{jN*~mET z?SjJjF4o2QhyWqiZUh;mPO(%wI>_z)npCsy!uw`|6HSKs2j<JN)*!W9kHi3OzfA}p zR2;owoTg-dNVe}4M{Q~(VNQXt%sT!DQNct~1T|gjB5-#nn{gaULrAA7g$xu(n}G?e zQU0EKtWu{MA^2EIK9P1pBn5#dRKw~!;&jWo|H8)`J?z=qD)0`}oe>WXIlq%jdvl$& z+4+r+kaQ*+8cIi6h=vkIc3MUj`-UfIioyt@{!ZLQM?YvJPiX8!6O`L24~SAz-D_*j zc+a{RZYXtm2MF!71H_+awOgw~U#`zIn)jJTZI|X5mw|S<V$=iwcJ)ahT7`fY8^#?P zG^_$a;J;Pzx+rT%z!$i`QDr#4y6}7)bELWL-C=qhjz2zzCte+NMD)?Q;rYCLxI(%* zTI{tF1XRZ11`(6yz@%=(j46sJL~vd-LaDy-U~ITQF+#wvpa-QpGt2USd`<J{Z!cBp zuZNxACN_Q19jwx}g_?ougta`2hs>pq(#zZ|tWXF4<FeiltAYj_o0}H{Y2Iy78{K0f zy@b8Dl)zjl+m##1=eMx_4hBi!$Rf*ePD%6pZlLWtH-_ml$oM#;<JDc+&Z|8cXDGHf zJg8=r&I2AGYlP9DHL#2DRm(uV(FFLX><jP;{AmF5cq3-IBL`~3hAXtDKa2!L;?6xk zufN2N<kbQHMhIP*kowgLaz^MATC+Jbu3H#(a2TnpKmrmJ1@mwC@CDqq3v#P8cx8c` z-P~4=wh9B}b?gtHQ1o)j#V?LKW{sM~SaP-LkhX!iQ@4a{qKGX&=e~q_JgM-!F3vzT zoJOQt5(B}~_gFNnM>chcS|6-EY%S*A|LnM}w+A^%8(?DhG6p^%Fz;CSz08JBJ<=CM z&>Ehg<GT5LLeLovD|;KnkK2<aV5DAis;2F=2Y0w?g`@2}XJnF&)xCPeY;z>Cuv0W6 zHxNC57icdu$MCY1=o+?S1?bd&0LYw7j0+YPC2#`eWxsh-|BHeP<f?AIoX`mewcQI3 zydhZ5-mJzAVR^5j&XtbMmwIESJI4sfb)|?jrhl~ayq})j_DhLzltH`R9`{lXf@3!A z@HO7uuT0h$b3^v<IN!*NR}M98aYk}kcI~n00uNFWsd4h23PmHw?Ur@E?5q!1AiP7; zx4m<@I!Kd^Dk7o;=t_`PUIR_r6>xCcBY1`t163cps`MyExO0+Iz#mE@2gPC-#oW8t z{T8nc>r@&HQ^*Uwx$<gQ_kB6{0O{KU3;888m1}H;y0`becQCqfd;g^B?6-vp9{V@D z2yE(tO`g^(AVnS1kt!fkq-?&^mZH2UpPo?0lamUYQJcc;DzC_%BAr0u^aH8#v^!eI zl?QoP{zKH)t;eZB$_WucM|`G~y57MxQ6g&I^yW$D2HF(FM9r_i%soJWsBq$5d0gO0 zE(ScV84IM-LrS0t+fq&kROH8iR;vA%_?GL2kHE1*H&f}!w^wWEJ0oWfvS?<%&@R`C zCf5HFmof9Xp=-k)z`x<nQ-X4dR|OG&xNmGn8(LLRfJ1AbMW+@WFV<6#=7r~b=i+(l zCBbCOf@#n@*zt4f-wH`RA2@S*Be>tNLft7l`2OmKay8JB*^~b8io|Wszc?m%q59i^ zE2FrbHW>uE7!cUObQ<eM*?^i72=7h)QBrFGhx+Q=JpZF{at991j*=Ev)2+r<qVN!+ zA27b`UUZ61Spr+R;P^t3b_ofQwFINna>*m|9{rICsy(iwP%FXfe2l8pXf{Rso*zln zhTx$49X6mOaXaCpTv+i1xbc49Eb2yzuG!u^a5qj-H5^o&Eu0E5%+K|fvh;Kww1y+# zOOAHU4|nA?#=et8?h1jfu0|R6dHkOjtl}@wNNA+w{WVm^9~@{1uX{*557Q;15<P%b zd+SFViml%y_kxk*c+tcKMeQRl!^CY!c(w)&U!I9sC=s=w2{mR^=*YZjdfOT{A}czc zkRtg%Xe2SC@>OP}N8h&baBXjo8lSg1^f%TV1(}ayqceO8Xj7)?mD-f(U3evhEW#6~ zN>RkOx+)+em`0ZJ1vL)F5Y`7ulbLO<TrdceCv2M3hphM?Opyph8=JUkgy%}?*At0T zS9S*?utMF=+X!yZD@14Z&um_yDRxXOp*JjdzvmSenh0}<Z6DVdv_a}O7-i~!MJcTf z>Auem2=0gjlY8;uN47I2>&7n-=9VIsrN(bhL1uRHuV?rU5VR2Vywv}^n{z(RPQ2U* z4!zubYarHchtO$xu-2-WOW!yj$B`-!@clgWf*6*xHGo4;_M7+b=u2P+z^XSKJ23;Q z{%KL#i>jUp0$+rLI|Rzqe*=AVe#l0dC^Ca9{pIHMTY7d8ZQBp2UKM{4o5zBFX<OZ} zjSz0CATJLZ16~-du?#l61szXtz?!z?Ej|-6ed{GxdFvxA1j`niuFF#&FJbPgCrvAQ zME(=)?5Q`;IN4QMT`U28M#&fdP!N}4C!lEsu_Zcd^oH2GU8AILl$f-%HuYjjVst?a zxgvhiIkC_*IzVxcVcK5JhojQK>}%Y$#Y@%n5j)k&=+wQ{A~!aJhc!0uB5DSiYoePs z6&+o`kY|xOPqCF7`V?FB2OGVfEfzuKV5!;iR9`}fAB|KPxtvV=!cZ4b24b9uU&v?- zE6P9WfDM0JvlcO%ZA}c04RtvR2R1jGqL4<?q!ZJX_+m|yC`S(gZY|EIg)J{zs*LbO zA|vUpLfg{R&H93ivaczjbG8|wzySPng9xWuDFb#$v5a@?SKPrb^u(>qNPhnU;RZ3$ z*nLW^Htd%RP9OtaXK=YTHgGvU7yf5^8L?7l#&P}!^lw_`K~nU5cm^3>K<sPRV#X4L zPGs_T!pn20;-sI=)U@fGdC9+9-_J#+|4Z)l2Y~mbE()LI&hYpokQ1fOE@rerI|UjE zE!!utF1c=4ag?-NN@Ub;ndn)z>s~h9D!})%+B%Gi4oUJ-KobT{h@cVDT|Edq-bxdE z;LQ89y^|JV`j1(By(+6eO3tQ00;Cn#`6dFwkX-uyr1r}oduSr~T$gFjJO*gx;Sr<1 zNooH_3&6mxeugtV<djCd@SG)VxiQkusg_Z;(SAM0&#aWHLUc@#t8uv;?`G&YXSMot zT;6^q7ti!&n$yiC7+rs>b%|pyt;7bPcR`rYkp^s;^26A&3O<ppPZ)tGFs&4y<M|Sl zsAFLJ747k~<YKDofNjyBAw8PhCLeEL_TI(`C9@?H{6<4WLMyIKw${(#_Rt=Ks5D`= z``}N+xwg)@&gPO>jjGT1@7<-eb8T6WZ>lsq6aja5uCTY(9yRT5staHdrzL5gF^awE zH5wVd)7y$XZ-;tQZiRT2=HOe0n_ZZbg{=D@ERYX;*Iy&J?yYan*Flupoe?5mEnp!o z9^FoBd*o{^;v?1`R%ga!>dTq&*xPlaeR>rD$8EcG&Pu}+=(=IHis>J{u>HTxC-EQi z;S_ias6_dD78hpOpT!XJ7oCmxt&*bdVr=e2^5qoj0XI8b_?$T{P6;v`@T-+EZ^;2y zn<fi3;5_1m;V4&}Qd9mJw83g^3<J72s&bX#RjGZ_GrE1J$v576A#m@0LeCXmnP0RS zNO#Wof&D`1pc``GaU0+lN=2GN#zSvgnC_HKx3-2EzZ2!yysI3tvGA(0)}L}xriDDp zN(t?H{Z*L{eDCDt-UDh)wU#(73`uk%lOJJ2HraRG<HcZ*&F@f0l76n5$(`K=dw(>w z=UD;vR1PyeC0JrZTI7VSta2fvg(OyCh^%h$B#^3-uZ3m;)dcf%GKzUp*`x}XjB10I z{bK+{8V4v;&2;Jh&G-=T_=*S?9c&9zQ}00CBtU61(f(Xp<~RVKmAzk>!7Cd!9jl-V z;3Skdt_Kbyv_eZPq^S|txSw_AWK{%)Z-5A3sgEsPCJ?+ipv<_$;Y+zH92#R!sNuAs z5Lvn*oa>nB3N5>qLy}WX9_pg8Gq;%2ettDvY5+?7|Ewkfm`>efp;6PdSc)mE|3h>F z&~<H{)`@yLF0;DgP%Vxv!l=9heXVZKW|E_&v*kJ9G3xd-R^q|;8uzsN^2~spVcT^` zTp^z0vVau(VT5cQrv(w2@|a0>UY<cM+*vK1D}ZLolR+ck1r*}~%e?i-T2eqdKHInr zMGBi?KwKEtOwRv{gns{Gt^kM@mI^Lqc1l_EsMfkx{tCX)LqqE?W%FDW3lTglx1HgW z3K?E`CS4j4L`_#mqY^?*ouJBcK0$^KK!1=uu-QCsYO<5jhE~oFMzIiko0)l7jo)n! zI3-b3?JWKT4}%g?>41H`qoKqyu0?BG38#ws4R}t{y((G@KLK2Q(;uAw^L^q0FRp$~ zTq92h`qEg|Xu}QKiMs2;5f2o*NQe?J>#oRv?^9cR6Pm!>2nU@;>}B>2-&z&in5Vb{ z6qORZ&{a_d8K$zJh17tiqeFEWR#vPeuhxCI?xUr)Lihhy+yW?n@qi>~OReLaTK}K+ zXVM#hV=Q@N7?Vf?re#P!G*tecMsas=PuETS+I4;7+BKtw-b`uQ3Bb{%g)v=A{%^_r zpPfQ;L_C0RAdY+&{Yx?w(4qRSP-&*R3`nob>cRi{%<o@jBLRMVBKEM1KL=!JL2df> z_x%L?{*{eK4E~*s|GTJqECxVh?sDBMA_1Fm^=NhPf8m%c!B2|U{vP8ed0X`#yC`?L z0LOTqYO5Cm^!F<vnqGemF`4x*i2VAKLG?-f`p>)hJb#9#w?o~PTtE?MAyUTw_koy9 z0!&xx;sRh|{VTit=iLO}K1o`h_7!KJiKjkiKJ)Lt%3=bp>h;3P#O3%+w2%&NdHk7S z9LUh4$kO0%1=48+*jECCLWwjc0N_-k`tyIt5L%yeeJy3(lhyxZIR<bxLBQ`)2{l2@ ze*hMp=t7eJF|sKT@c8^Xe98@sC=x#EXa=#xs~__gu#BWc*cHh8D6e*5P7*|FU!3mR zO6uQB>6_ZWhW#e)H<f56%#%H#1t+%%gErl9m`Y#p=}0pbI&WGhui*q8xvf*uMn!wl zT5oc>9xBth?2C7TX?BFXHwRSDfbHS|Zop^$KT+YItQfQ}%K6e=ZIg;=EN=-A@u(qn z?pnZNYZOh!I%eIGR}tV9alIA3%XjeQAb736x>j4sKZFxaQ^3wp&RPN`z^awwJ5|Cl ztk-<M;<vs>*2%GGjOr?7C4BPtq=e?}*a80J0&MR5*H}eb;OMV61Saic^0l~Jt(K6o z-cx|^&`F#ed{-&}PNx}(r$VI^{{s?s#|Ta3>&sQA!o;&P(4ToUl{@+1KkgE^LaMd{ z$8|cfTy4tB9p{y-OZx{nnfJ|O$X~_m6t3;coQoT;^5@F09)!$(WAYlVIjz3bkq;F+ zd`Bqgod5K^{;K)UC&RT&^B?a5R{9Q#R!O<Y3S;zd|1MJQe8Gd50JaSg0dVvBJ3G*Z z;(tlmC^89cA+lqeQP=Zb(GIkh07Zc*#(PG!hvt!j3~`w6mPu8av?3%T{oL@GFnm)g z`Kshp|D|wvy@<~Yjmu0}0xF<e+}3V0!S=Wtmw(E?*;J-B!RO4gTGMq*OG>56(><a_ z?7WlQ+Au&}F>a*jNhvgH9YqS@(DI)|5tTXdRX2buwmAN5`s>Q(zMt6#eeB<-8Ih8( zHZKw=CCebM6xJx32^9k)*FRI7Q$LO{_85u*sWRV~RdA+2CMu!S5!f5mJamC1`YSc9 zh`tS0jFMthbjGnH?j&ie)V4;nKCpE6pXqIPR5Ua~vO2(hUQG63q%R6`&$Cv=lYuwE z31ae^s**aAk5oCbNQJ?GDPVNlpCc@j<yI^vN@=J)8Vpww|B{Vg=G})WP4m-Q<9gLD z1bbX)xs7?a$yi6?Qc^^}(elVm;vlr8JOH9o?fg%ioKS^@B+Se(`o2rOGv84RYsd>a zAwJ_HXn^VF9DwY73C?u$*KS#kpYft5<KJ^@;0kX@8DC>Y*HX0Iz3=Cz$&a4bsIMGv z6f_#uy};~Z;5wj!^*<L~8hCAP6@s$uTK4mlubppzWYz8{e>XXA5tj}P2|wWTP8N%x z?C$Lu%oWc8@H|0V+pn4pzXH(x9gN7pli023zI+*;YS7bTv6_mTe|&EZzq6U6xsApn zl&0;8>4RZ-dbwaQI*tVBoC05S5)`JEWV`CaV%OtEa6MDPVlCnf*<;wRL_-sK(3k)C zp}nnCA@6Obt*q{S#Qc+(l>~;@?Os4t6x-IWy2^I%Yn)={Zk%$h`Ai^C!ig9Mx7)rn zDvIp=@f-?m3R}r#k~A#vsHD>Ok<W)Ta;&A+27tw>^DS`yo;ef5e+5Xa{{%?<N+d>T z!kD<dgVJt)XcUI`*a|4T8%DcjrzFk~HCWts7>K)Lac@)+{I=z4yO64r^_Lz09noA1 zGhZ@D!hDJ<qKgrOy+?;3V(CmiNDD5<o=YN+=r&ud_BT(65E6k3%d^XoZ4pXpx$es7 zm0Tr&j&F@AxM$KeiDHfBkHvc7Xo-p;I11HnL&0L`JC&^3EaDD7$CLW#hD>`TC|YXT z{@IK6e(oK<uIYHQO8Y6fq}wsn+T&G%m6`bhtm|!>{%WI<DXU3_H0$kP%*hV+?&XS8 zQ3ZOHfnwK-V)M)VYB4X2{BTL^t}$PX#Gbo2z2g4xMCE8^%W$g@$`yZYe#?37p06HF zv~#PLvJ(@(_@zZ0ZBRiW;RI3>XyxM?ATm9lXeEgmZx5$|OA<apVoaC<Vexz;&Q`Jr z*>Uu|?(j5gPksY~y3W9`g?re+u+t0LpE|@l%>?UhLp&#!#Se%rA92lw-Kim_-B|0U zro@_MBh5zg0i33Nc76lUEEOSq@-2dn>-Y<R2bULSU0MF7I*3m`XbQ%_zYjDaIFCtg z5J7{0ob!i8>(l$e;*&Q?<p&+;)wL4B_E|8q^?IGt_IEz&c<U1zq6WgkpFfG2Sp&{o zx`})Yqz$PG%KBFew37TP+MgjxZelAJblq}(X>#)6eBkrFIl?<~e`mSJTtb2Q`S$yx z{fST03CG(Yf+MQk4{0>zon)UzJLFwBDBEd4_9GSnn#?6IuVwQOQz4h$mtodWLMpjG zt}=U221n*nz;jp|a@{j>9lw9BLF~*bMf4zKhV}J$xgoVg@PT5aIUs8`uI(x8VxTtO z5HSB4YnI@M`U8@3B)C(~T`y@WxxQ_yHyR{PIxGiEHKYw``Af~oGL^d_bmW4mzia}V zbCj98N1s2T9Dcfq85=w^c)!s?Q|pfuF<H6JS6=1VZHs_2ReG)82>h?e9uNpUlU;91 zdZ-%!y)VA>X3UneCiXzM<A75#yUW)RtDKQeq(!F*yeS@PtPRg=Mo)m)%9+y=Ja4np zw~+c@Bd#)}jSDxfv0_E>*j3T*w&q>mCY+ui27C%m=}9Qz$O58Aoo0H}EFqotG!@d7 zhFRw_F^%(s0bHo#PmbgrsXHwK0Jum1ulvV%DodZbayR`W=hsEM$-I?74_hsMDKn4; zLe5GQbiOyw;Vp&J6LRaveTzEEP^ZE`r05lZgZQ!T#$e#`<-GC45%yxH51cK6>}r&M zoFO=h;_?!P7+>s2vJi;5gC;3Zj>0oC0e~-b@&-*RS)%E_9Kbx<*dWRBT_D3A$3>_} zdG(LbM+iES!WgHykS{k3c3zX+T<zsuOx6mkoi@*i=aE~%5+P41UPsBuy^kBsJO44y zZy7G66wDSXBJB&g9MZBfI9`okJjnuO%o9`MdD_gp>h>bvsg<JZBZyeXpi=1O7NSFF zM)m*cL85lA<B*08S5noP*+A)yNn}VfJVAj<CxSgOE<GVBW=n~cFG4mrF(LT-Ie$8~ zHji|BykK;Am{j=|h{4-wlQUky6<&12fRc(*$kLN;2ZoF!^ni^#NXeP55HfMYlMO!h zVE4x?;BHL42U$wmp}wSp_rUn*pMcwTdZt>m+<LFoHrw3@K$mZOuLf{^=~grJ;@+6E zcPS2ezas)Jqkx)-kR~#}KRF%`Ew#z`T2!3ug-$c~Qrs86P+(74_{L>d?X9`Hhe6Cr zizeeD`ez(NMk0S9Up@DG2_ZEgg4h|o?{BJ_{I`ucDYXM^Q<K-h{ZGZ$^I0_a=n~YF zd!iw(Pc=o_`oun{a}vQrrGveDrm^5ZtiP!FFT?i%WaKtmm%e#SYs*KEau}k#BOxKX z@8Go{Z$4RWza+ixxS!fyUM&`gG4GaZ{`TT|!`(mlxwTDAClZOSU#iiLIPtNgK{GDf z-E^Sit(&fy%iu=UAD-!r%hII}dFF?%@#_RCFN=c9N`B)+I1D5!L?~Sdq0zdL=`nO4 zJ4-?}dPp!Z({DdJ4+LCcik6?~IOjXFLN`siP13^&&Ffx<+tr!SX4=hoe-RR|P8$O+ z1o)$(5@x({TX35StYmhrjx!2WlAjfBRUQKZ4Enn-8ufhT3X?xTJ$SC1x!K+_ay7r> zM|aRpG>!~Fr^VIaJx#-8DVtgJteQCmX>`b8vMg2U+YNP}uZ!Jf4+1|?q~OnLCgwr1 zKL(~SVXK~)Tu$b}>>p3Wwo2UJD?A*9g9?r)N3{ZjK5Y3XtEpvqwm9rBW+Tp%TpADL zoQNrA(F-%&L7s0-CVnM+ALZ{Sq^jX<(-*TjaZJeMF1)x4XRMUNYU3a&Jy9!C<eQUs z@crgHYv`*`R<XfbmMF6xe(Rd|aK4(%uYX<JL}>taPOhO5){7@78vAoGxU*J7X*}p` z(Kr1H?La21GEFu+LE6Vv31I3r3B3|fK>AhTEMxwgegSGeYJi~dS+=?8PzofGOfVqh z5qv9HCHf;SfwYeI!gKz9vm<V{f&dui^i%fxt8UT2Vljfao!7$%CItC~!0IS!3RT8- z7Y(k~<52exSanR)kf`lkDn(F~O7^E1-CXX@Ong^RkkWQ|%0HZD0xwac>xGf~zzbCs z1;CCNHX{yN-$HG#<{Klg>>Odm2<rLUh@ng7B{^YTtG~bVWC$k<Goa~~%v$kVPUlg% z-v8K4RV`a}SC*iZa+cau1hyT9E?)GZzGN8hp;L<lVopY!cRBo3LPwNX4^W%!9?FdD zS#w$oaw+M-WHlxA(S+bd5<Z+R;lE!sU?0zI3)G^nQhT49KV*VjLB-<^oSjvMlw9by zG-EBl$21_=i~b?~Y>)esX0U%S{h`y_Go8_6xFPBGjs<qz5|bCTWixj{uM2X6rdMAK z-`AHFMgd)_kMHHw&+%-T3vYE6{AO5+!C*MidA})9A#N3)BEz00Wk7X%o_{?Yya}uE z=KiE=A>!?Fdxt(-W5Q?APESbM@_}wpBg75rN9>CI02M|0Z+sgdmj^tr-s)>dj-A<9 z#w<0+Aa#D%9fG8KCUD5p8iHp>%bofF?y)CXG!*CYRPG7z>Zyc_V~GojA|<Y7r;CV) zbS`<ZpOY|ZC0IMlahIjj7yKVk6FkfiSUL?hTH9(9nISD77rJqEhv7jV&p^#}L%YcZ zeX@2g4w6oAcOAS8C0Yh@1p*d;I<A^+uC${aP#|R9vsM4C^pil~Bms^DXUaL61W^QJ zgPtA1h7*+jkW;^J3UjxC-%4=d$%oSeRa?!}4JKlAdubNz(Fo_VvF0S|`gMzdNER40 zdNjQOD7zLNbGCz`ZPWH@eG#GRy9*danipmY%H!_kYbW5E1#JFA7CWG7yHM0pjVerf z-Wyc(3Yq~<u&B1?`ho===ymrK&{6F;znzGA^mX(T%7nI`to!51GC;{P-lUNnDS|2F z6C8r9K79o;DY;IWx+XIPb$%A{>Ag{jseU3b7{mi2mFS(Q>dJ6W12$UBL<Z=<KOZd9 zr(%F+({U&hx#y{<$NOO9c*4A1&2X2UP6A}{Qc=7ai)C5BS1#Hi;km2{>`ljtHq9uO zMQ?wnu`a2%nxI{{%>U3pVq!|Y*6ux@W%W2iXXT%Xm<#pl?m^%S9~XA)sv3C1mzj1x z|LMq<;j(=}Ib<G65{VtY7t7ySLLl4c83fSji{|NwwVRwbw2+FhQ)3ss-^OZu8E;|u z<q4*yYsU${XrM)t{LWe4v;`kmiyeYf-VP+(?0@+X^d1f%Yelx*ui+2fexV)J5tN$* z+<sF`A^Y9~eYo_87CZ-X_sr=#*7A0(l3Zt22432G>^h#`gYo{hle<&k-8n8~3y3!( zDmuD8dae<5Oue~XKj%mhrvowty7%c)4Mns4(eAoRIdVhz&8xyPqtmnDs^^MDQVkQ< z1Me%MBmN?~QpYoD!`drFEnYqUdE=e!?t3*R_57~<g)%BeT#goj=-$uEJeDLF!!i1l zc=KPM@Y}C|lL9Y5-pZ{B{|7t+_su7tpe>So%`Hcwf)B1YC(s}ecrdUA{ij5alECVi z4>yRoAXT~>W-#h@F8jcCRY!Q&C1^yyi!pw1!L4)X^oX1{B`Zn%dX(v*j}GGmtah_I zS~nK$WSs%EsMPqti^0IoL3|&_d27!U&FERPnP=b41WynawGRwk3)tJT5kt`sG032C z6%BtFGd&N2&N6cfTf<oUjh?F<opwNOBsZ$gN}Z-yZA^|(sYXo*zQt{GUSUpFwp>d1 zK9JM7-be!No9d7KC+v3jy^y^mMhk4!a!sA7^?2?WEFph97PF}@eh_d1h4*FYg}6v$ z2QZ@_M_R8>8A0;PwUBg;kGQvhpf=LE$^GYuhn`X7zOne6TXXydZ6v=8q!sl$V4<wi zRfY)y0WZY2TjcRQHTjU=nlcc9Kz(RUdt{@X=JlOq^<lCEv;N}3din~IF#JRzB{9?( z-wjquYT9}<c!0=i{#)zQ+{EI+rf}8E;Cs0+q^S$V=GTJa+quT7$DOi<+@8xGn>{oP zMC|(hM@G4=^Pu+#qz--*j0^`5uDr6|*vM9&^_8<h+Qk(c7(331&{6U@cOaJ|JnPk~ zfh@Vi``_pl-8xRILEE>M9DBRDM{vb=Qr&q@x&tpWYMWUbXOY=&&5BC!=dEhN9Zhd; zcgHI5-y{pa*X8A?N{=9u_gYTnfTysU39ZD-F%0nyH^F&ydkt)+aO3xFwncW4Jm?0^ zR-1>tJd8AMoqKIQ*3kFZK*A05%27-y*<(Nmf6<>l&?7DrW<RYzaWqM(K1cV0|22eK zg!0+;1dnRDBLcuP?H@S*9T72rW5<BpWOyLc28IiiAd%qwbE_Dl1V|rVUy;!-3DqXF zc${NYmytm3?aW46OFd+yycxMA?C>NjGRPwZYK8KcRZ!kW0!y_*y^r~o*kq=PHYMNq z`mpnd`{lly`lTIP1kVje?RIjs5!sTn@oCAUZU0wXo8zO!Dl07-9Tu1m*DJJdGu+#| zHH~NN%;A^Ss26Q7NNp6M*1G`Bt!$MVhd8aOQ#I+gcP*ibJ+R+YU=i0TJ9@whLVutp z=**Xj;Q}Ku1IurdP>e%s>O<OhIVl?NQiE5@b64qf<kf{1`<S7G^PTNZLmwYnHa5LU zA_f?P&O%3P4dJoEHoKC3=e3fDhFn+uRAC#2CKMj}1!c2xYfR9AP<t5B_OOOg)!O%X zablIFQz5vD-G-rfG^h5B7kp(Jig~W$y)^ZQI-}KBeCJJ0`xQsEH0xI)lNfBF_v3i& zhK_8GI=BeVbCc2}HsA|SPDnR`SGQ9xTf`Q9tCOSiHjIqU%yW0BmQ3f*OUY1cEs*<a z5LUyD2Rwae=v&YSBG)tVBRL-jNa%BVyt5b0Iuyi7d?G|bF4sGBNtGkEvV`IL*>25g z)SIBZTn;sA532y5_6k&M)tALS`(t~hV)H~#vU0=o<-5Q_1lW=`7gmoGW#r~<i&aNg zcR=VM>Cu!Xqj5Q+#GiT%<2;*_k4d7#jgAI0lG`#M7P6+2%X2BOfe+p{a(M0oE^W7c zLG>O1(FuN6dfl{2%)~Wo6jydFKc^0L?;E)f&}xpz;IP~Go)mPBqeedyy%~qSI$Wi! zh)-ZrOvq|W9}xZYeahVar%Ds~tkS9#e;U70b^;NKa3(#Ek%oPQO%<*<iWadT=y~vB z<=%6{4iI=CPGeQ|*ieg}BG%efWxM3oz}Bdh5yGa0<ePn|1Z^;SI9XM2N7kFBb{j4Y zSaiF!Ib5L&UH3v7O?rjndwYenCupQ~TrWr1A4}OEr#WT!UvYg{91mBBnIL2#a1WX5 zld*mza$|HJY}Se$ab7nBZleR|Z3=1tQGc?-?JJDIj3NV<Nilq4rearFRHsT9O%1jo zknK#VMzuGeLDlno#?o{+j|7nQk=D3OO6sx-Tk$;%e?3Se4CnZ2yML^q(oE0^U|7n~ z0aj`Ph-Kg3l?)xu{e(T8pmLTvzMppVXK5_>Jg)gbX3@AY^1VHaLBt&So&_O@{&YQd zr8O=hJXf9=z^Q2U-4nrDba(*h7IS%Oa6l4-eSmmChIh)s;@<R7SZ%*qdG_PK5bTa$ zN*l=IL%z))-?c=pcY1iaV81;);zjTt6ZYEfZ@s&{`yP!j+l-8<8Eh!{HPZ41dVTD; zWVslhHcgzHtc0BiongGQpj~*dp|w3f3`7C9RhnMWxW7J0!>&3)ns-=u86t;$f&DNZ z#e_gN4QYG850JHJRVyLPivc0nJJ`FzRe%t%#gF3K=rH$f`j+JWfVxSc)Mayv{Dtra zckp_e*q!qoZuR3){nWbih~w$^R?^MR!s7|=14)Yn|LVKf0<rP_!J~;NA06j|GE4aW z_RPb2Z{m$N^EgLFmjh<hKn#_<+$YFJv1R6>4v_PqDRMCW%U>xF$N^M!ObTk_r{&b( z*Qy^ORrGuTkOUt1dw<3l&0ln^2laz?I@{0~lkq(x9-(ese&iXu@DI<(<C|o9-J>;V zVQh77ocY09XmU-|W)^w{$&tVPE*BQnzli4LjAv*g3}y5>HwS>6qu{z!RJ0;e-Ss}8 zFH=1-JEZz^6*rel7<wf6M(n3`ClP~$otk<v6-2*OUXRTl3kf@lFS4%Va7FJLaIC`< z61P*KFSfUW2>P6A5_7aJfc>oiS0ru_c(;d~pNe82#D;tFfHx|<N9xISo>+MW;;-tq zt!?7_=j%KD-0y|niCV8mfaf~|`gVi9Ri~yWc5?1#z3KBp;<kn0yxmk~veZN%%klhh zJFYdM5rZ4-nLKW$a>C|8?$=OCx0~R+Co)xUfN*=U5JYH=&zIR*!;*;leRI<Si^YW7 ze$&xb1iT_8&%j0yp6}z4L^`trc1)|T*Va|7{q<V?c4<#s+iMOSbG3xkjBKj}VWa!j zsPo+IG{jRUwS|YP`^WNavU;sO^fYEZm!_&O+v@sigOgR>Os-0Z*cY|UzQpx!2fCmP zrUzStIbx+elDu36nzy!bu5+qX&el!t*6T5+V`q3yNr{*Vg$dP^#&ZDCart|CkqJv$ zMz?+^=Pf-HhU3lHt3)lit~fdV-WPtu9p4%`0dm``r<RM&mcAp7yW1XI<?`a7wNwy? zKLC`kS=ntQ+z5c%{xbUq-wm+!Ee~)e>7qR*gA+j?6H;F^DGY<*hYfufS!jrBjv&Fe z7ee6!tS?~D@0S%VaNbeEQWAq2?O>U*ugES{G^ce7bS6_YFd;HZNo{FQvGSN^A)pTg zB65wW3z0lTq0q!qb#qCbUwKLVv{HM@)hu)}_)jQCliGmRUf^tjEsA%lC2b60u!^MO z55Hz0P26ea-XZS71X+CB1`2RlN@Ck{8+~_yUUs?&%@(c~OhxAkVmKTy+sSm!AewNG z)6EQbL(}`H1>wG^;;-LI4p|n(rKRsrMBx+qRmAGJ>cIZ(8e<1gm5V*R`&FKllSH9X z_0e~f3h?>8*&okFYnE?tPjso7<{L$0m<kFa4NH=U%Sz=Yeuub2$Ytn23<!fSQ=g(* zeNT^1J|gB<Gu@_*h(j~zN^_wM`8HMS!fY}$(8dTM$Ma_O`rcb(Gyh90TgA?|*91yx z|MmBko^(%?h1icpwzkIb6k=;#kj#KS@LIAE!*U~tHq^Rs9?7>|T5hl9hNQ<aZP+zW z(p(285$rZ4hxuGRIN-s?gf8EHg0*TDD7=a>iz`X^n`S%8P==3#CQ5z(i-<7ij7%AX z<tqBkCieE;Dr3E%5!np{ewpmV{lXcB=R?0K7G-~WzIV)#ST1DJi@=205kTzF`-~m* zduC4BfY?z|c=rzltO9}V&)A`#I1XDu4G!hmJG0wXcthBuFG!TlpT3UqAYlJ0R=2$? zqc{5Ea78Sg&IFfzTX4vpMc;P1jOYzrAFqEeH^X3eUUA6m%mHzGtd7S~<pBhru7vaQ zb$FsHQpxKZejB*h<!is{n1g2)q#SOUW{6f*#&o0poT=5e-%P-k?5&LTaXme^`d1x8 zja4?tArLt5K_PXP7jEhORc^<lNc`1e9cA^=!PTQdts2-+uOYz`_;iJo%rOBDkwflE z`ep_YXBNc>6`qCaxY<gF)cV2EA}WC|1J?C`dp^_*ATx51x`oiWO-gx=1-mIiLG4P4 zqvhy_A<x?(M{;SgIA0iQC8&FoFg}7au_zB}Yh-(h&LAgSVrpm+a`Py0V#z%N<!kO2 z0}1OjVwHW>e-V<@%4B-6&{-&DaFfI-^zgqp6ANLLG1{+Wn=JA8;a8W(Iq>Mh1Le6E zC(MSQI)MxRi7LMF*j;2C-D7)yA#er~k$Kq;VUFy&2It?($IuhiaODQDc~vl%Tkvwr zDt6}|2%^{9nV0hi7|g~e4yU~cA@0wBGU_!f#N8Ocj}-xxgu|cv1e_6|-GrHW*MG`j z5@rL6kYxE0qyBk6kZv`F^ZfW5e5<I_MT2S%?2lq)6A2b^0v|$8Tti|O8oF-4r~`|W z8yb(RuCNeq0>XY1igHlPkCWLr7xoB~#Tkgnxga|S14iJel>cI+e|;%&9Qf7YN{Hsw zh?5H-U7)+h)fioz4n6pDPRX4x5eumJn3e57qOIiyy=jhzT*t&2d4kx!JP4N#Q$g2L z5*~z0XECPpT1^yUqR{DwrY)1-a2|8DBaEvX2(?;y*1&h@A7NkDeYG;Qs3zgNbg*tz z%hkhCT?6VZm(n)n{J?S>iMDqtz0N!$AUCGI^zAAPR^=D-SIwA_wC!17+E!YvwSTcw z-RW`K=%1keGL>zHk!8rLYK-yYvYuQ2G0F$FdWT)IrHTVUD)s6w1s|EL7lyPyS<TQo zsw)6VH^R+i<G7>(8FqwiuSwGCN~9SRU9jYxY8S?dvS@LV9R6bK7CK*7a%}$QAuo1w zeUaC$Hksjsd1)d7%#dZJwtG<8mGYW&!?5Nk&pw|;tKHJNs!gMt5maheuCK|pTxTUU zA>Zu?8Wpd&qLcnfUl=FbAO^+uUL~&9Ec_3#;8S0gGy^boMX?$i-ELMP6yUl(F3I5O zEzZE0y(;4ggt;zWh=bJT>zYV8#bx=mp0;kqH6xEGXA!_M7x7T4rmX%Ojarp3UZHlS z&PtA<_w}x`p-!~uy3rG-Sa~r|OXJuazBalEZN>NPl$smf{Icv7_szrGT4iCb`2TeG zl|gX^%c8*o32s3G3GS}JZP_J2aCdhJ?yifwThQPd+=9CY4=w=~cYm8B$*EWG)Vsg$ z*3?&D&CK@B>~v4-^n6vY+vI<_=ewU`DRFY@L&;gdco&z%CRN_*rK7#wShEU|5^*?- z88=%UEZ#F4(qkTs5-pX-y}zNDhuRSAao*tOX{XN)j11ZPDhf|Vj&VAOgt<ntNK8~p zy&)GUB_Oqw^0)Srq!Q5}+&@%!ezvSQsN8e_<9{3rM?RO6!&z^NPrcw6weP+Ox1jCq zSMyPA57YkS$NSsVO^n<g6bubm2@3pX^EZoOCyoRMRPCc$3`=c;rjQVk$PA|$Z~O+A zqm*fyu#2>hy>T0K5I&>zt>WigC9DQ@xp}B&?WOv?)?jCIPS&jUB?B}LMc4@nLS>Fz zJ{t;Ye<=0mKNjP`$HVj;wXxIAy{^+`J2S`V>`#tx4wCTK1MPWVb6}ZRd4Z8>mKEG- zMpR%2p~1%<g3VtMEq#DqFFYc=ToO8e27gArPu!Zej@)g>Qp&2TKX-X-aXE5dDG001 zJ*><#D<69#?Rv^S#vkwU?8dx!1uYpSusAVA1T^X7e(xoODYvdamQ;Mov}&qwy19j5 zPq<AT80}sd4W|L!$o-y0;Auz#3~Okik9Rz;u}EP4RZh}hAmpziE&K!GZ@8W2RKhTB zX@1U%4mdGC;j@0m{b>@;!OZbRsUy(mrx1qyXTgd2e)<+#8RfP`BjF4GuhMA?9ho<| z5gf(mmq;fZG3+lc8Mp>-`NFFflw+`dcZZ&=`ETD5`6MhJmyr*tmU)%L9yDs^<RkRB zIyoIMs#scf32BjK;xc8EVl6K%Vm$y42#4~V&S!Wq9G3~!F}Cc9q|ZXN%uookS>^@< z<FA0@BVcJpSAo|M<zbra)K#@>c?AQ?Vli-L`%IaITJHeQ%R>vy6y&i8B96Z1)(d7@ z9evQ;WD!fQUgV#(?Iu5tI)%nmPVxvOu1d+0_qu*ubA%3`Ka-=SlJWJxk>PmO$3K%M z$w876emUdFlHyCA^IB#*9-fN3p=f%5+M%mDwA(OlbV`mct8Cb%r24ppa`VC$E4n`j zExB&9o|J)XrtZu5&rGIM4SNgwP}GVsH1naTD!JGgvN|oMQW-Nde9>;e)5lsa32pM0 zR_(j<=)Ud5QlRq?_p9!RzRlSuK(@Iq8-rJ69&3gC@Gp#Q6VcOI9{KuPY_02APAvda zb5KBSH|-{hxSCo@h8AN$B6eja8#h-AKQ<Rrs%k@3O~_F8i`eJQNav!Ff&|p$rdpX6 z6?b=VmC_OKZt&O31Q#f}gug&A`uu?P8;|~<C?q_AEqD40XlaRDGBhkNuN=9Pq~h4j z8^J#nA<~Hz4+eX&xJtZHP{i6^I6a%x!vg=9Q3%;z<m~|z=BQeb@srv()^UAlZN>S) z`3dP&q%Z&gZ?L%;Gs}${>&!=V)?QNb(#8X2YAOx`v(PJ8Lt%mgvN~E`T>?m`ZnP%r zvtk<TK#}hVUQDw{NKE|F-i~RFMo`-_9Tz!OpoB?E7&+pXIxzAp{G{r$Es5aZj;@xU zoaTZnfS-GAF1Mr*#tsbif`o~El@NbKO+ZdhTO|CzcZh_F-mp{dV%q}*O7xY$8K0$_ zJ1tDMxX^9nl1Er6ftN0MpET#VAEaTQ9bQ3~zkgW~`rx<6`9mQTYuqreB|0!`{79&C zQo+i&A=TDPGLV%vJU-_wJ=qlzOj}He!%VU?CU|0EYqDJ}d`@>>o3_hr7UvngFS)P^ zKc-mQwyZ3Bzlb5q&298deCdu&z+fbZj-#AYivG#xaIzjYKH;Y}lEz02$BvleW5SzD ziCm+|b}ShlF0Y{z?M)B>xT2I&(4Iq)ex~{|jU>^4#2%@!@y)4gawRwyE~JXml-}OO zhkSD-D6WJnKc9kxluPt=^W^ek*w=ZOo5|?P{zPQcFum}Lm-Y{hkKq*_mQqLLi|Oex z$;pU#WUNL57!-XV!rO!WU&40!Fe(f_#2)AkP>&TYKDz}z8{1Tnd_)Wc@X3w!3L+FS z0~5gVp%$GCGBl^*Z2Ktc$$K_`obLe|S@}r9@|%MC_;21KAmn$zt7rdvKk<e44}>CL zj5I}v9T3SCP@|kc)H8%GBy1ysS_488e;SKadzyS1k;#G_&Xj5epWi*{f7fSnA^Scm zmAz2nrBPYWCUy*An$hIP9X)kBn6s;75>79YVDwR60f2bI(IFDf*6!MZsV>lLgJs$2 zS~eD+T&he=RGdQt*-<lnzslqOU7b^~J_I2z1|P40^P61<^l~j!b;63_lAm$vd!OqK zmQ-~Ow)+qCqGg0T@?~1DS3>4B^}FLJlQ$pM2^6ZZogz`O3}C5bvLa#^Qjuz15_1J~ zzwS-BQr6hcITO*8Lyu>W$MWPfjDQ8_+SsgrnHBdMKA#?cn9m?NyQPXCm_>J9*Nbmb z{D|Cu%~!vb(~61jvC{M_nb3ALSyfcy-giH5nmt)%vo&6LoLU%W;e1yPBn(49bUq;e zPj2!1>AMQ$0*}Cfm;Ncf!wbQTma3a=(X$)=smRr4D{2fLmplyG?Px;HhjTZ38|EvM z;bB<vzlMz!&0Qf1O^9_390r;)XeDX9EOsRlLxD8vZROhle(=cftv#-e`=LNYhUY79 z=V>xGi@KbL4sJ_kk;E@Sw;r)Al}LNL5j{-{aHE0&{dcG5@eJ&<k7$(WSl^5h)UNu{ zX-bg0IfdHMPAfzomb}ovU_GAt95=m<2cfgsS>E)cX;<TaO{sl)h@i$O3HP<KE$IZ& z&yi9wV#oJIidZ?OaPm9Fu+4@&uCB?V3;MO^nQj)ot-w-$TReTJomDy9AYfKT*IS~j zOXf8%0locP0x%RD%ay4g-&=w>^Gh7YoaF=vs{>_O-%l0)J1-Lf317w*1oBeUo(ew+ zDsedK&A1u*_K~~poPw%oE3rDBHnUkSmmMpqa55>L26%-u_6e)=_3{~~GY~;&$$E!r zl^F5MZ}G;nX+4lM+RVK3q>?`SoXlFf+HRXLG@o)YG`qG^j2HXP)NcvJs?mKoh$8B1 zM&%I}eLs@U3NyLx9y;ox-QTB&kYns9t(|?p?{<%Q`87^)SUH&(_~b{nM+LVa#&)tD zHg_^XKCVBIKYTi@yBra*!ioizRbG~3DfH)@5|8e%Z_YjCgN|=L%@sPexviSRG?m$^ ztj@+CH(SzLOB>l}A`=p(Q7S5;xyI6SalJb|g(mhu9Fh!^Tbc-)sarW2n7VXMMs2&# zCl%xxGIC9W3NDPLjM2m3{Srx~p{FP&S)`5J+%1e$ISL9&Qc}T}y)Cnw@uP?=7RyEv z?>XT~)3#{|V!|Z*Tiv#oTpxmPQ+zHj)mlHlF))(3U?CmQNt4VMOF9`w`*P!XTl#fh zx-(*dJvJ+iq*;Dg&02l4;fSg(zE$0-fM7j0cbZmf#5;3TCNKy@qH%?V8sA2v=uSDj z%R)=;Wp-6a&<v!0FWn&2dK`}u+bgk_0Ntds*qVJyBwz^SroZd`m05D`p_`BMdygxk zukZ}4#&uC@g)#!w8i3djv_y-wxad!NFk8fS8>TK#D36K;(tUcOqRd9d#-UYl0vM6& zQxD>}7IeW|OvCBukOjZ-*~6Y3%+1fIkm^2|paCgmq4G#&*X`TgYMu@lmt`-!KI3av z(T}f+siurO=~{>)In{0#c$N6bs&8s|B*M-Qo4!((5AT_Q48`CUiDlw5&9;s2DDt+m zx{RKO0s~zEVHs1i(NSuBrI<~;-&zsB*uRKcS_qtbx}(T)H{qeus>4Vg)`?yxtA>1u zl{m=ugL$07z^stBkja)MvvAJ-Q59A#gBfrnGgy%j^2Oeu?x{H7BBfx24Tvg?)?N*t zD)A|3CozGS?p#YqLYmP@d0==o`b`lctKH;hp2dk}NT;t~z(l1inRCT6O6jak_t(?- zSfU?b|FAa^*&h&g(cb#X#rmhMn>WYLE;AuIZ+k{YrZ<rC3#y}q?FBX0h;F?v>zWB? z?kh9L)9WufHZ+xoqZ-c&aR|A(?khmVHXk#fUQxe;U(s|xnp-`?9?9@#A`|TzIkWsi zbG%)FVC>7sUC~ptM91nfW)(3w76ZCdVN&<0bU1MQu$7bjlE-{0uH;UVZYUc_Z!8K4 zjRK43j-*q%Q@%{>e3|w3(<SG8tG7V?F(Vs8u93_T+94>C9cxa@1-FKMD!-M;b;~)m z$(M*7hv`0iAN+Hq9S6P@HVVptIzJ84A^>3AB<Iz@|G}K1p-m^Fw4g0!7+gVj0s)HW zlCXG(3d*<kkNelB+0U0aXv5y#-D9x==;BZFU3qpZjm2s;uB2>t1!~*9-QT#lx@fzo zRf1xTKG>|*y|d&#?r&T`W;GN|GXK%gVQBpQ9fQ{q<qXJZO|_#LwarjW+<GB05CzlE zINn>-u|vWXS*1*iTw&DD5^o%&A(?UE@=#EuvU@n1h@Ea(kYyraL6xN{JQTA$rQ<(P z4_WV?D3Y~3=37nq#`tKp2Y7VenqcC;(?vI2*k>HT=g07Jrwnb3=TdmNHbwtNf9%4} zKDQyXDlhr9pj1ZjTL%~CoRa3(i0E&+$fxY(RNlB#Q-cE&*ffNh<5Q_~p#c_@KW7aq zwc^Qu8)+d-Ryu93(_QckA1=)C`3z!=9ytvzS5<O`Fr(baPz~Rrub-MGky=8OMp7~& z&%$_72Jjg|?k<wb6xB_Rsx=>9C2zp-oep&Sh=`f;+q67V<9o^2wm$5FsxHba?ZQLX z(tSKx+tuocj8QXF92Ug!6DF6!RFBer%rEGKgN~okac25AXP0byXfXS~aHVqJI=Ju} zjX~HD&!~;j4;La-RjvA4n`&A1{PjUgv3mI^a*EoFAw-8FVutaacxXBtJ8hn?FwHYq zKa&8_#*+kSlrO?0E(YvByX}7FFxX5>biG?}VR0TZZoKRpp489`?BKs+;ld4EkL`a# z-2`;j50gqziX+Oa=`d246_J<v2=xr<<SwpOuX-d;+{D5+$3l^ZyGtliTTwU*m|_+7 z7q8seU|tVo@q0u(N@G?nN2f7g^2Kpd7m2Fk5qHv$3x;2|gt3_KFi`XZLZSJJnPAT{ zAhGtH17<u3yvs;m#>QlbXlcd6^WgRZ*z}Lh#K(5C4ZE*IrPW;-3nPv!2e}8!lrC#6 zH;Y`?w~g^XJdrKi4JYQl6K4VQE9uXy%tj4-H3Ntb4Gw2<IVfDUZ@kp<xHQI(Npghs zFAR21z`;usv%4U{u~h#?5QeGU?D&C~3N6*X%UMAocTbnHAWB`?I25Of4MUt_XeGf? zr8S_Vy$YrJ@ulH%3h9|ljVPrU8*2eGQwqyFv6okzsX@5|`3O=*=9+W@m$K@Rr6%0t zr$hFOA$~+;rYyz{4tX|7ariVHRJQX4SC;8u@5FilZ(4v}L`p(E#oP1L{wxtUOB$QT zJzkVgvYdvCH>Yf^-*^%6blc$-rw?z=k&nsGTR%3Qoi&9{8SfJ&EsqE-78$+gT}rEh z6i}aRoJBUC1uvb-&S}A>=e<V%c?~LC`WdYIH2kyCah9g_dWvnPA!H*rs5VwGCz;y_ zEJaw#G}`}oEdbssJGYybtq^@)vA>CF{T%+eB9UQcAjP$3AkKzZ)oz80!OMeu2kOzC zX5ydgF{-QT!a9p&vkeLgvafMXPr$oc^wZj@fMw&5PD;GSj7_sa`_4*GuL0ao#@$}8 zMm*|OMI?587%XCOm!Pw6u<gu4=MTHmi9hLle+=l*kvFR-?OT);>`XhPRP(%4CeuRH zggsM}-NCk{fZoVTLjtG&<{{b-cFHH%%I`03`TIlBPEMK}(T*2MZFXcSPLl2?w){-Y zGOzZiTF1T^|K(f*t3jXWLoFl#ACFebx}Z*y3s+*6I?>stZcxYb@-h+$HCog_A%np% zNwJ_qEdW&$nf0`WGKH(K!<DYMD7SbToH)GNS<_+N<$qwC7+}-qcJG)2y-hbT0oi;n zH8dP78rp*J-ut3BV_-SdGKoR>dFJ>{Os{x|9J2?-KJDVH!skmR!g3nsSDZljtxmsG z37M<c62wJr^vVF<{imRs1=6&V;gbt&pCrnGPmP;n*@pX#R_roOgWHJ#E90+AySGI( zElVRtqrQH{kBvy{MS|Qs7<#tq<MoX;!JijK2sR@v;>E+1A4;f4PPxp<5++~jTq#<W zcf~*7)<FvJL(*+K-id7iEVetgr>{>Q_$<YRnfgY)$h#gzD#yX_yh_$)6G!vJgegu9 z<^80vh?Q59ZK6zi)Un$zuT31x=i`CC6N*#DUq}3W*Wx1%dXRhA;qK^i>qf+fQC}kT zcdNPJHxw>G(*)V%Z>*FboNPJJv)J76Gc<V?Lf#h>6miX{;^gHw<9gj+gDT+{(iKpQ z23N{m*MC;BxU5J^XR>r9uy?>b5)9BN3%|j^$tiA9_I}fEQ~@lHH>nLFEtl0bLLFi8 zDos(Ahr~(`Wa^fGKR&u+#OfdE&WjfC#qr>qt#HTlX@1t%x`_8U3D-;_p_ASyVdw&# zX%5>;_b?x|zM{3moN9ETZQKjx#zG>33dw%#cuxRPm_2lXS;~J~kx2YV$e`K=Ab#-6 z4M-Rvv09gIk9TrLF1#xjt5K{A6L+JN&$cz{5aAG-%k()ibyK_ttW=XEXDNPsraxF_ zX`UD$yhW0*e@B%sIlGo~q4O&tqH(#hqYE$njMaX~Y9!q;>I3H<2%zmD#-pRtjI&B) z)t%YV{MPVg(ZD*LOhV$D+%-K`_X1<Rn*j%-+bT%audn@}Y)`*#r_9Fvu<+P48Uh#S z4P2I%RX)0cC6))H?S8-{0^>piai>8nNMj>B%3Cg_EB*u&Q7=ehc_tH2PeI)a+#jeC z3ElQ#*E?(F+u3^afvJtR!St~V!%mFS3Q~e<_KJyFZ!bBOX#^C&EDNjh&d~rRPqMqh zf&mwFLGMk}t;7cXC*^QfHg<K71hzC7+T<la`{LbSNU^R87{s_ttme$_;GD!36T39( ziZ={Cr??QFWq+wk4gYf>3XbZcU*d5)7?p3hYHg@@K*p?xy|TPZZ_u~(VX8P3DZX2E zgv~4&tnN~xgsQIThH?EgEI{K>uvX#mw7?+0Qg4Is^!a%jpYxFI;cS=NP}qV@h1mm7 z{D*al-5}B66@+|B7HrO8<5|7&$+PO{1yhs3D-#()eKu9iwEZfl1DQa|e0{(b2Ih}A zTzbLNwW~|DD|5k}kxcL_LqsVrv6Z?4f;cBm&iV9YYN@L9?V@du-9ssF`m2f07gDnQ zpHmw!+^md)>E2V<Ti?KU+zUOU6R^KopA0z?G5y4o)OJ<&`3C-)|AwX_L*P3LBX3Md zgN_&OV7KW;U+FH{as~3BF#$I-7LqU&=U_h27GYo^Y|#oE;{LT=A_0HvY#&OAri-yz znvt1I`M7K!u*QX+u{8MC@#ia<7d010pCXZWWJN^tnGP-)_i*3l?>XINXSgm;%!GP1 zwfsXhC1>h^oOVY{F!08N%g%WR2nGNR{7iU;zA#wVwBD^9jk?|zaIb|Dgf7{(z<^_I zW|ZE2->Gz1L;BcRkjxlU(5F&pXlae0Qn?UF)nmB+uqP3U*>qVx%*fifMS|^c1CG^d zu3DUmxl>NQ+FuFOC)<J8=hjl*Z?#EOEDo`?KHd$hHJKp4G(r>oz#B6|jT~OtL`WWt zA{T8Esr<yc5Uv0c*9ggbbue2dX8wtusZo!Ecaaz=JPLZWAl2T;iBreTj({lEyzy=k zK_U`0S<J?W8EDR^bm#Kzhkh@pR8DI)?Dl-uU|z16+<x5tGugcK`^D%Vs`@K7R`adI zuiDsIC3~zwAl;3|if9HN1)E*q-Mj)bJ{|X6MWe`e3}ogks(bCep(k)NdY=7+6p$1p z!}`+oIx+dg$s5;1ivtf%F>j0FtiaW$n{@f}0W&n|mqRQ*HkjB_D3%SxqTeSSG23lO zVflkpJ<Ev`*Y&<&_j3*vyedO8>_WhOPC<ck4d&d2a1eH_v5@4?JcU{uYx@c5vE5_x zqE5dB2NN<rDL`S5{zh#2(P?o9qG<@^fW}`f)!jjeQ?F?&^};gQcz!)@ve<Bv;Kw6_ zHCcxg^7+Yz;&|>zs&Dplr6pxNJKng!HOK38tdn2y(S{G7)z6p}1YGW&Tkr1fQ|z|C zHJa_yxKU9%LNi&D+Rw*mKe@&Vll(Sz=P!J?RHGr0%_O$`4?DQr@1~NyExiY_oN%v5 zEH+p+(_vui(_Q-4GF!3P9Q_n7CqgRO)KGwc+oA-ku3c%A^C4#S?79_jOjR?+qY5j2 zXQa0s!@=#v3$&$=01+jgNB2PmE53bWp7Y?#^tIQYI+w!>$rae(=;`UJJT%dq4~IZT z281;s#Z~s;<r1K|I%N$o;yZ+38k3l+8k}DOb<pi(2!tM_g9kT3<XsthWdbg302Of0 z*<QUNnbhXRAoRXlI=Qwlr6W`J-*5|V);d<Zsk19V0IOVxr5lXNXey<;O8{ntxl5sc z(l?A0oh^0kJ(1QXE8H%ud&9AabMeMz%<PnigdX?=;(_n!$KHN03!Bwu-*E<;kwwIf zzttIoBr7R+)IdoM$jM%aL#)R8Mj3qeDVX+!*rn7>@58l&jLbi>(nTpr^<af8flmfL z<eM4|ct?|dNNIuNJ4YiW{U!u7LFYs~1f-Qo(wkT-Y!?^R5{o0E>&trk1!DOlrDHQc zZPN~hO7~P66I?;S<i@x4+E-7@;T>M}xB;N7Xyozt!E$aYx=!#RXb{lYoaTC+xWUQ9 z_Zom8Y&j$2e0B?B+f*&9;Veh~WmrJ}cJT0zu;}ED@QHj!=`>!<!P7~g&^zKp7qW{4 z3(GQ<1b3k$tXIX;IplI^Kv?9Us~z{Pqs8#YUeE*|C(O3^t?SvkkYQ(_)X9z5b5uK+ z%xk;u#FopZ6EXX+)2U&=kB3Z}b7gT~qi0wr=k%2NotdN7>Vqh(Y3d7vE%le)!OeNT z{9<|w48Pqu|11|A&^=ASx)1+2m3%GUVJd*();igXh`xl*Shn4{hnj+vk?{w^uJWw| zgpKRhyz1?YhHe;Vwog#l4$DZo0NSbDpn{Mnyd3?R^D$7~jTor?8D?r4Yl4FM9ru7f zrA>Td5n}yU-#Dp2C076imiSsPP;)rzXN5ClwH7hR*a@G@oulSuJ{ZVX?NjRa-njut zq3%=@V(8_?SW;rKosq<%{*)O^!PBdWUM9HC1}okBmBCcd^98+%t*BKP5|?_`k=+so zHZgg~&p^ZOee{!sK7Q%g$M;1t13>XTeVliKWCTfYtVVJ#dmg_O7vmNbY)izn-(AJp zxdko1@^W^|Iak!xjh+alDNZJlYCHT~-yo&=DQ(S+$S#FJGb(brjmF6qnCPqmM<;V$ zZ`;M)@|wl-Lha%>J+PHn^JEKKYSO2NV%cr?u%;tF%Zy1wC273!am%4Dgi`<ErutVR zKI2A({GCmVv`ndhfLXuGf^lVEPY+;^doe<6G7)#npnLB2gUbk1HWQHQD`Pi(Tu~zP z#?#UDSiP>?5w>tHV7eV!sCyHn%ruhj^J;Pbb=B2$^yvmNz1^+saSyYtrcqMxoO1GJ zZDMIv%SceVO%ocJREFoG@CE89Q$#FWLYz^hqz(m!#Bb5uoJ&UF&FcY0)Bd!-4g(CO z-@ZBvULJfOBsIZbUv=u>V}In#X}XEa&)HI!<kbgDLRM<gQOA%L;8?ViUQiFW2RAe4 zg4lNHs<?fG$Tk#MEqdevhe;XfdPnO0LE;HN+E={Z$#~Kb8V%ao*a$)<KSG@h@CMr$ z8HNk?PbkZpbB>mm)~HJ4v&YR!H$8TQUrg;WoOm4A&nONi)?bTcdw(Q5TqYyg#CUVm zwfKYHPEO|VoyR)hLMl>xB}>Z{fTH8N9wfo;AvY9vzE8-(^({wLGR$bB_dW6T>f1z< z7yB?GLjy(*lKQn;nto}YFLyL|tRjc`cxmVTzP)b?-+u1}{+`!wST>@#5=BJBVBNiZ zi_GFQg%1FgR3*d?v+dU8dd+95`ai+d8mYUz>~dVmcM2bFm^XXw>ZOX4Pfq0nsMw4S z`qA?f<c$$CEkwtOSXvAVP5BGKvH|W&%IUg&I!?*Bc2xAgE6<S(sYjLT`oMwIc)cBe zVxbI6CZb3qO1?%j*t|nE`$nz5m~d)V%GmuS*Wh9pKk9T7m_DKu8H)D`{xwt|7fyZk zypiL35&hmW{@+9!BRqit<p^oTTfz@idb9<3aYIX4CaJ`2?b~Usg$KVZAJ<~V<TZ?$ zJGqJwC*u(CC>LDlQZIT8(;4msv=scwza0+Xq$Va2F=BmMEgq_IO!|@1AX}V=HS%MH zYB)+tZhF}-V#G0@>cCz-*3x2CX35Fwp`^E2vgVku$ob$@Vkf&Nry#TD*if?+&W1;X zkBot6eI2u=NFTW*ib$lTDij<J3Qe#zvq*w;ez=H*49U?J-4k$eb4k1<4ULRszgMtW zdj7?RIkZdz`yRo|L|d@jW#jF+PK1rPIp!6FUbtnL3bA+Ic!l5IOpc0;?T$<VEvot> z0XunDhvH71T9PIAzzv53I}htv3(g`WZ0}&kLSx^Y$V4zmJat6#qp`r$H2VZdhH(zk zpO;+c#c`8|E_)O}8M3`~dZmIhV1M$^MSkWH4$2>e@lfNKLPW=2r<dw1;Aw!I&qK2w zr!89W;0uV>SmaI4u27s$f!n<hC9cSmb+d__l6cdh^fFF$$UcXMu$5{!ob=Zxn*)M! zYKZ)FuiiL~pW)s9jZHIB-lneSIJY&Z_8c$*CSea7Qe$&tS|ujKK1g4}ppptvyihVH z$Mia@w$xSOb5|XlnV*N%bmhRpc6=6YlPU6@(eYHB!}lDQd6+XI88TGVur(<=`yK(h zOu_B2HBvz?%z5*JNJMe&msGKXXA}1Q{S~%uPvNs|#{=K$CxN!qFsvX?F8_J{8Z?*5 z<o3`ROp8~^-QdMwAOHX)7gX61mZ7}n%0-CM0SXPhD35KH(_CWch2}RG8X_WbC>ukM zd@#e?31H(;Sc(wOOXN@&(?*Y<d>SRQel#<f^s^v#h;O49-F`gWGkwmjPTS0cm!XED z?exdm`^8*eh~O0@^{*8GHVkS75dMT1um^<g+e~@7RGd3lvM4;bx9zCiFU~lBR1axW zQ}^E~HyTj4kQft5+V6vLOU$(((LE?MHjKz`H9{*Hsw=*jf~9g8D_P}Kcow>MpM&17 z-R=>%U%hPqRAV8B`z5Kd_M_IF5Uyd;4Hg<NFuKP&o)tg6=y1p*G3rcPh#s!I=$hS4 zeM-i?S~|nXa^Lh&-f+^V3{zc}!#T2_F#L?WOBOARm0ImBOfhA2hvSNJrA4|)#@WJ7 zy{6Y-Aac2_GK+Y$k2BV4bCmc!tJ$`GXlyte8atB|FpYFzo?(Seg`jK<yo9odwa_na zyq~3^MUBZD9@F^|iXHs4(lENAuxx8Zp)h|%yv_wuXcUC=huUO4vb9=v-onkgQM-UT zK*F*7oIPDpU7;k;L9IpWaU0;Gn3x^$hr}0*JssSXr)w7rFI$J_n;=_HZNsMu4LYE* zNii?SYw6c}rj_?`CKpX^dSuE?Mac{<T>dgb2S{aBB9A+aR$lyKF6_LRPK4=8NI-g% z#5mwaCPvT<ORiF?=4IK3j*#fFWUY7Pu-mns4My2v?b9Db=^4zI433kYILItrBoF7V z4`QwfJ9;W8M{c%VidfA*wOO@CNSsGPwRV)>T01NH6Ho+Zk6C1v`aiUG=qw2+um|=3 zC4UHG{FZE^2J`=GbjBYxRrFhiF@L%EX;fa=8Qaxa>R%Bd&<=h;Us$#YlfctIQq6DA zxGl8u!%l48pU@K$n2uMT*}fUv0?6!CCO1C?-~Mg#doQVX3v!#UZ`la6=x8z|8zV^Y z>~au9lKwpx9_EPuFq4k)`W<7(m<nJxOZ*+fvoCabLN9RiDrrgJtVHqA{)$+Rcu;yc zA{+Pqvrl-_Kx^JhmU#>-3Oh6VT*>@}10$xl$z9<3G)fGEjSffp_pdu9KS|FX#)2>~ zeSZ=Z^t;OVzor}`%nd!+{q+sH;G;74<(SQ%ACp+4cs1{fc$6BHkpDHltkdA<Ctui_ z7E|BH|KKOS7$>g2pk$lxSr7X!z@h(MA1K4=1j84~O7}-f0W)v>Wnq(`1l%cu3P=8T zWVN!L+xCW!bCfjv%Sa7`A9en$83hIjyr`Jf&ej3)_yKylk;vIT4|MPJ7}H`^_^Vd` zU4?(Z{AKsM%W?v%-hc1%zY&TRDk^GL7B&<4Un|$2|M=f8zdpiSU0z;7C3f>ZeEPpA z_6PC*CDfC^)~`N4T|@hsb>Y+f_kI+x^+FHp=>HRV9>;ChUwtoJqr4#^VtQZyuJOM^ zv;NfhNp?D~dR<TQzTAhfF#Y#MT!**1UiA?|Fhb7;1k3&<fj@x$`2q!ZwHAP`ApHLY a_awCM5WjjibMW{A`uQj>1E>(y^Z!2`O!GVd literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231109003734.png b/docs/images/Pasted image 20231109003734.png new file mode 100644 index 0000000000000000000000000000000000000000..3a08d4b119c36645081ed465a67a6f5acbea5846 GIT binary patch literal 157645 zcmdSAWmFtZw+0FX0tpEoB*5VAA-KDH2oT)e0}LK~aCditTX1)GcXyW=oICG#z9Z|N zocsUI>Rw$_UD8#xtM=Z{Qx&WzFY)pH=l3u$FdwBPMU`P-5U62b;MkGgLSs~pOip27 zJ_wnMh$u>lh!86}*qWGI8N<Lx2FI%*s;dlQXK2PmMNPmVNxo}+N6Pjq4($ibp;#q) z3`}+pE)uP?ky7WMECX2lCfb|@*eWt-?A|pT(Qk21ReEY`dB4gZhah{8dt=_OT-TYb z`(v$+h%mRYT2-8gvoOSJaZJG<-|2<P$?HdDz`bXFYqSAdq@|OQ^ofuVRu9kWRcCD# z9#q=8M?C#t`s&S);vob;g(3gE_0<c&gtO%bv!TjcMNR~h6ULF5!jzz|?o$W<7U@zL zZ%lE67EfMfqtzkxPMy7n0j5Z?QA_GAjD;HUIQ53H;Kx7wpmb4>Y$O<`w>@o*jj{J= zg~C>Etb5RgZ<5Ug4ve1USgj>vhevU{LK+7`rL&k7(z?@MybHFy6ITchvry^Oe<#OG zs4u4Jui2O?pd{+k_O#~I4p4*s5Wf)b44;yS(<Dz#zz6VI3=A7~r@?B2((hI}>_8t$ zP_TDJ#i{RWf9f+M8Z-z`n0I-|^Y*x*F=6c>^wL<fOHuaIdS>4qVzA2$X6{Sxcp0|= zq-!wMrJv`M;UbiYROm*+6nvB5s>FPlSuhOPK!n%T+g<VOxyY=G(SGb0=B4yr$RI<6 zoG6$8{_jzY?;=!}68H8#j^QlF(d>xQUcNky+$oBARbm6w00L>q&SJy{6d#U|uKL73 zj0G?ueNY}Dbf-k4=%I1q2VK80_+)4w!b$bRJTmp2gRoHxUQf9zg8fhx(12en>b)ng zb{Y|31qhRAWGhgNZmToV2dU$&&o9`#$^xH3Vq~OcH+;9v^c*T&J0Ex>7+5>SFMeb( zJA9<T@HYV)3Lto5TQjX+Eow0DiC>*Ss#=7CO)d3;{G|B2KAbrIegr_K_(+V8t}^hE zBxFxPE{vtTxV9*z)i2)TsMYIu*hZvrVLvCxL_8;Aa790m2V(dI*EPVNg}QH}UmT&9 zu#WZcA?{zUW?cAB$OA<igbs*TlF8{~p0IXtCtz>=;u|F&S#TOY&HU_sV@Fhk5^t}) z0>imcK7oo1@yl2x9{%3PF#LX->a=}yBd9RDmW(G_>592pU~z9h+QQkwMufIn>oti; ztkhiO-URjb=_K=61bkol@pTbH6GYfCre9czyr5JH%Up@6PBs@p7`vH0d#m2o^tQEk zXnQb_yUY6y-=n%(c8_b8`<ByF>1G$XV6biS7oP^NHtEQ~h-u|U1hJl-C~rUd2U99j z92ld=(5>rRO7S*Z;-<3o#(Qs=4Mzh#y^R4E#uIp$N8XKN?>ipTZhy@nT9|#*>%15^ zgrH$Y_`7(;AlnrFmG%*zk7<#tc8F^oMDRY$Xb4+EUy_h=$Ni7B;0k<`^#Ihc#(H?_ z2y;H+ddLf~&VJ8XumlK&9U6A;v|u?p_!``rI*}(3*L=p2e524l3rpOfWA<QFNu;4u zZiT{=pi9!ngyoUqfsmp}S)=bI@suM<McB#M2KaZF9o{$oswH!YlFvhQ4fhaci3_pF z6)*b4jbWTa|CJzIf+`E|0IL>_K|C?ba>C*#&X33pVWw=336vXzrAS!WPt(1!EQn#j zRaMmV2r~WT3s$9AB^||8+@<gM_bt^C=R!Suf;kCIH&E;lg0|jqqGtMz_u*_GUl0QM z)_irlc`o^%@O{LY$rmtNkO;ceh2QGaX8S7&Er@f9a=uy5x9Q>`jV_X@rF83XVM$IB zOB2$P)lygy;gzzYaz=lYB9Gx8%-9hLA+?vf&%>DdF~vCbZc0^|<IpdpI3zfvM!Hfu zBt$Y_GGExZaL7KsgjPY7KbCDE!HCHLD_J2!UPpRO+J;n@(j`_v<txn`7LhbBMd+8v z>Of@)E|EqB*WBV_i-M!ypL1!yrI$2`J5?OH&dSe5eq$&mjF%%+h*wTjtXEM`K380y zF#AfEBES%kpr9#SlAT__m*=UNTf$XrKXYf{I72&oG+SQW`i-hYv$$r4su-tOt%yjm zy>zWaXs&Wf&(e;~#PXX3!CXWBWQEi`K|Wr7a!I4QW8ogcsOb-K2D&n0hPLljbJ%6m zKeT^_*~pttyWZU2l-;o2*jVS({b85jk!hB7uXj#$&WuQiD3Q+@`<gDDZpcm8lvEzi zD8V7&^83tdHMJ=-5bvYmN6ZhJUrTKkX7$f+1CQ^I-`z;xf)7?F9`nX0P^ZS{bj#PX zUOQkoDp^4+Nfwoz8(~7{cBh+b-LBm-LFYtX^Jr|ftYK_v`VGC6vz6-u3)DT5R<&~n zwMrFL<yGzW3768_+kJeLKQVPNvj?SPF)7FKxIbW%1yu!3b{(*?ef`K5pJKyq&H8L* zVx6G(-Kehr#D}Xl%{;@VZK`FlWxT7$Agot5^haoOf{{#talx*|uw%k`S!r2JDYiPB zI$zCP&7L~WkNF?#_1TMei?UU}>l$rjYK@mnmdoo~4T6>$7mb%xm$d67PFGI@z{jV{ z5@_PU2(<7bfc>z~QHKMyU6Iql&l#sMJ9-BzI}ffY1EZmVU9$1;r@fuMxb526!!_zM zCH>qGakg-`Q>*<E$MT<TXTpx}oRhbw4z7k~*Hkx}I&bUnSFOXA;p$E5E6xCC7!Ym< z02Mj%TO@6yrmVHeS4WoX7OGCx4#$XnrSV9eGo5>#$JUoC=Zi7$+TpWR?X6koL0N9I z$B0J*f2t?92VUFnwp0(EC)wu)uUW6ir_ty8m*uC-YAX$mQti@2Sb5l(Um~#Qi#jJ7 zC$T>2dXjqPdYVz+6@@37vVuBII`KOHbb6B5kgy8N2Vw|!izEiEZQ<Gj(>}}VCP^%m zRwme40JZL#E+o*M(PKabEC)%IEOdP<k+or1V(g+m)bcYSMTnDglPWopJ!pnGhO~wm zJrN=4c<zi501g@()0O7CUw8SJ5DY7fymzC)N5R{emKf_)2$b<uPGN*x&T|VggKr1B zcKWcCr45Ga;$G~9w!eoT1J2pojGji{&0!YEH84-=8I1K9#?DaLQxQs1<Wc6I$v$_5 zZ+&-soaQuFHTUFYw`Ds=SkG*aStq+dk3-HVc+5*I6d1l3RF9sFJxtVyUZgWZo`0un z9AIKS;+9Dm-^%AsOhsd=P%dp_ai$-gK&?6RWf6E)J9ui~ZXeuW7&0HHs`5a-8Ds4# zx#r)}=V5(Ewodye`i1nA{(_;1{*IZ={>aBXWm<IlN8z%Z?$>8?eY;It)(gBAyiry; z)3MY=u2441Ybzt?rIS6bJ;#v!pW`2sn+*ZRI^dS|(6o@D(6upzl=W{`-+1dAjuWGF zEo5e-$tmiwflLbxXu8x|3v~m=lS^Xj()al|!)ZgbLv8eX3~hJEMY{7(+?C{>Qp?Ja zeEbCT#NdQgt+RR$iAEDweb@OA7P=#~FW(c&J(?}1ijhB+f5KN&`7Wd8QW~s2-7sfx zTKz|N&bYi;2~V-HaH!HkY4-8<=~j*7&bDaTthUN(yHKu6uAU>vs=T7ExO_o)MY(c! zaIU9p-^=jjd(Ehx=3-sNve+_@bI+OC@5`d!i{=fE<_tgR%1#&AyyoLqeVXx)369v$ zCs$SKa8BaSJlmL@)<>T=A5&48QD+EidDWdjUPZNl-<dk=^HGZvlSwNJUYsX(j<GJ& z*<=wCbwq4@KU`(^7pAu3wtM>#<*_mj1Zemd-D$VKsa@yoxfk|lw5?%GPdQUQjojCC znkr-(rt{dZ?LSQ->)@d18tGUy?0Efdn=QMYIJaphvT(F5X+N=VybRfoF91)T_E$V; z^EokGEG-_V9Vgm|u9>wb+g*dpF6+5%u5AUHV;%QrSACl^&qrGo8gw57w}pB|x`SrD z7hb9gyIZ%_P4!HVa~mWeO+alXz&_v0l=hQ9IB)Cs;B<=V*mwjO9-`&Sf9487z6>32 zrSP_R(YT%3+wE+BdbK#kU!H%KzOvZ3-Qsw#t!sDkTwWnseZ9~=YaTzB5jgN(xQxEP zTq(>`P!Ldf7JjJSD><Dnu-#lgL)}670BXc2e^P_-`y{7;xN++YV>Spgv3Vc%Mc)1; z7Dv?HB%bUdvvMnpn&}K?rt=k&q;u!ui2SQnbMq4Us3a1RIOVNi3zeX@R^ZWwhMZS< z+$U0AM5~a8l!Vl`FLFw0T;8C^ee8j6+MVO4?J%HU9-j2feJxO*BE(o-%0x~Mh87w| zf`Nzq41)j-!9s6-Sp5GAi^EdGy!lr=91Kj5ISl;2)5t@g|NNq$_dj|5<M}2g5C#$Y z4+DAwv*7+SH3D_koBs^Mu|wa%2&srjNkN|~h7QKYHjZYtKQWS}e4!EV>?AcDVPLQ+ z{<&eLl*uok<<FacQ~#+hC(CVUYt5){WNTo|2(-5QryLkwAU8B<ZTwT87-(%}<H!x< zBmGwjZfN+QXeLtPe<k^8$w#U#r${Vf>tIaG&dAKjOv?YBn3$N?!N`PLSycSr*`fdV zNX>r!wBu%Ca&d8CbYW$*bueXO;o{<AV*bMP<qHEe1%soj%};$GgN-BEe-!ec<%k+P z8akNU{WQ0=A^xXaeFIykpM0dG|5Wr}zyJ77W1#te*JR`P?`A<8$n?(}CKg6!rvEA% znw9sTSZ+mgps|&PsJS(?&!Bbiv$3=D{ww|edh_2k{*RpM|DBVC^$YX=%=$lG{lBxS zIvP8O*jhvD{K@~{<Mr>%|MTU)Gx9S1)Aaw*75~xC|B8inH2-^ErvDl={`Z!U(0@jf zz+6<}8}td4vVVS1350=x`oI4?|GCdAZkUOzVPFJdq(p_j0bx(l5gQ0qX9MRODd3U( zQL-tq=%g|8FpH^)6JX%7aejvg_<};R)X{m=1*`NreM15$eLv<)s&x4Je-05uqKH~? zAAdU5-Y*~Av9okQl^Uqm9~(KT2Ctou3|^<5m$#~wT^LD|62twU7c&vk47uVM;?a>Z zyr|&+aS<a)X3d2Df0eQhO_64MFk6KL`t^TZ@Y1bs{?G3qhPw{`1wV8js6!a~f0ppi zXYl<0>oWvPkg&wi3oQTqC~1n)Mn{AFUzZO$DY1`(zu-_95~$;e>K8MOlEaGtV))+% zBTz&TZr9H2cR4gEoJ<z2Jox5DT~jl)X9xjoZm##2-epdO_Ua=2PYO8F$|%et#?$io zV-jV?9hIpIvHxAe289B&0!2WTt*KhY>?ls;4^5@(aq+9+HA`@_<%z3lw8mVLb-G7! z?daH4JkkfzEZVw{-)z0&R9ipoOT2pCCbwK<Jl&6b+pwC9RPuorx)ZdW7u$;I6#gbz zdaxwWmRBNf<``^dsPml;#2$o}Gdnj+9u~S)EG%%|0(-^7l{>$R%6*fnIFAorR<a~2 z6^RcO^b?$YQ|Z=9eDOQNR0xxfsc{Em*>Rlj&9v9!sp<OjnM-#p#%6V^wr&T)=JO=( zU*tMVS`f}SUR+>ajL^7hlOb3g&&Njzf7x=6XZ7BjQSgD`!D!X`W+<+8uBAgIa$k9F z6LD9Xlo<;S$p`O-VqC<0eu$e!zMy~0_e(jJbfmxwkY_*55w0`EvfTXj`P^G3@I>Y} z`QN5pr5<{eAlJZkQFAG7SB|@&b2eL3(*mA_QQ~^krmuviX+>t<dVw$=EqO78#OSLF z%k(uGb-bt^GaSg80Lg-;<>TC5FYWjxy_t_0n!FTJO!H}7D&OnVHMlC$a|DHR<JZ8r zeSbLrUm7h4kBtk5L5=8&B^fmUuwM02J+I2x&!_@Zh-;QP{shH*g`Cpx-DB9!)8b=D zJxDfn_`@<G`Ak)iD|U&PQ^TXpNNQ_q&n+%$xWS_2TbCRYzbz1KBxXpJk5pO6uQ!Td zO{S*?WO4!0{~}s?N>tFnrnZF<jt-60o+hdicv=sxTeIZ&qY4q|SW?p(3t>+r5Rov5 zluo1y4aC)OVH$R3vRjur_fZfXUW9cHoH|uJ&NIc`$G2(de7PwUSQL1<M0E!*np&6r znX4vrUg&gQv6nbLI5?Q5V+yF;d)X5kkV;(`xKvGiJ05zvXU`}J0R@lqL9{@@p-gQ+ z=J8h4%_yxY)|f}EDP=7gcJIgK^%F9pdr5fL#tmO&9W0+OnX1=#eY2Nx>D;r<>z<H{ zZ@h<ju~xtH6KMMrtu^npaFG$uzrNe6l%Usk7^Em`Zf^EifBY;F!J?sdtmr(<P`@CK zZ;iF6QU9ax)BIrK%T>DB*&~zpeW-QQVS(dGzQ%I|+q`Wrr?JXkCWv?nbnXfTlX8O_ zDtD^vUm(Apt*6K}uNDi-ECW=ncI(d#>CUbwkF~5-OI&In6XF<QlvlUyHl!9O>9p9j z=${MDNR5{V5Do>yh)EQmpki4+EzdLRbz7nvpJ5$G=0?0Eo5b8X#(hlhKCHQ>9AdPX zz@3aHu1tL>(=zDxCf!kMMyk`_Q8lg`ys|`8bbhb#mIF7_?dW&s#X)Xl-C!)$@(^7G zf$w6h0>3$A&Ar09su#QN;ix20B;bv8?0BvDbXT8C+jTlx0;<5%#g_w_#Uccp+5NzK z5B^!xq}4Bp6&|~Efp*-Ed$K&&Bdn(#Z&2yi%dApwB_6a0G3P7XSC3EjQf=#44Eq-L z`5}#HmklOXk^B!ud@py~;JNy?KSm?KVs^dP2@%xA`SzDvq+&<tF!d^5vdyV)i=|_3 z4?%n!ox)K0@3O*)1lGQ57=Pk9$nrZGAdCD8UKly2KSx`?{a#}l_BSQT90O0Th$4-7 zS-y;rCx4vbmig>{rBgS>I!#JE_EQ)9+}@j5sYZA!k6$yLG1qqT{yRS35G3WMgKMqy zLx1Pzixei<NdJB{M%eSwlwlROJrc7`)%Z@q3)*gX)NIn$do+uSoR+I0Ix>OfmlsHT zJxBZfD9O&#UB3WI1!o{D6RAW9?M>$`{@TUc+|1iK&GGW)vnH;V(>;eHWUHFOOfPQS zHMirk&CU?BI9^W2j{8$vZ+B*Sg?21z^gi}QBh2nGoc6n3v~22a*O6gXy!Vv^R8A$H zCSH5?nFdFt8a2W<ZCfF9CrO48RpZ_-*DUfwn(4sy14KrU%d&O7HYggpj3Y(!KNg~_ z2R|`><0|-=F%NJ*(FX=H){K1FY;>DZk_g!7_mG-(Hh0e(yMfh(7w;3*b)7&oo*^OS zg1aM&<Ta3?uM+jhoX(ALSW<-aZU`tlCKCQHEeQLsRgve{*U4>xr{$H$s{N|p;K)|z z`dJfR>(z{Xi(gEuj3*kASA3p_@m4E&o>nV6tz~sPQ-E1_mi5Bwn$53=>_z(y>E}XR z4qYF8;rpSw04E1$zND-!#d8~fy;809NR@?^x4#Y2dcN4WpJAzK+xq8ukE5NYm!c=^ z-23$rT@+qun>F)3to2y?{C(;*sohRPWu&^l%W^w(O~0^tgi6>aK){EHt3+jkwUOZb zzWP;XO<=8#^P+JlW(9|+l&C>Q_th{Hk&}6Ba2BJcO=JEl^fSP*nNQ^Y@);s?t}MV^ zf~zz*TE}7=^e6)gL(>)D_47rLK&^tu7N+x7Fjd{tVgXX(_RdH%cv$ykN?zdk2Dpy9 z{1)E|4UTrCe%<R42uWSODy8nGi#x{vBn>k*TY&-=2KXCnjHRpME=j(9SBdcX(qozM z!aAmuD;_{a2Z+BfZ^1p6a<Xc|{)_qHO2I7a^QAW~8%ahZkpw0GrA0nJ;B*zX`hceN z@e=Vg!V_F;KQ8ZrDvg7tg=ODPg=4sM!i7U)dZ#~JZeWN;3jyXjl~$)PK>)^Vx^sl^ zc761>gZy_<Y#+XXutA@JiX_#<7Q`UAG)|V5A_s4N(U1N@{vUgU{ll=#8Cx#8)EPs{ z#=XEb;4_!@W_T_pVMMSbk|s#>6>3Kq*b4d&#ee@nBbw=oE;KB}sE70Vxc+*Ata~R+ zf4jF>sX!*v>PiWcO5RXO7jQzqZ@VA0{hZ;h`!JQb<$9GSIg_5aAN`E-(?oWWD8nD* z+@hlUa+PSkpYFmKplrpQfHl+5?-%V7djATo9obg=N;j;h!L?#xYok!$`FA*gZ%G~7 z`ye}L$x`P!1y{H&GAz{+rQE!K1^2ZRk%(Z+Yc8AQRxk5blZ)t~qZ?0Q=98KhOP!^< zP2+BkOkZ5E8*ibCJQqb<%}L|^vF__q-J(fqX->^wY-IXx@DDiD&xm%b0rlek7MZcS zSk^U9UA^qOXD96o&xrhR+9Dv@CrHh@TZWoYQEn-O!)bIG7)bPne57HN3!|^tbp_Rc zatU=XVZQX~ATxLUD114@lfqJa?)u<cvtvc8_3nP=&FAn&GNRj|$W4;P)BEXW_fmcn z4bA6`T<gPC=W9J~I`u@vX*^X(3Zvqj=d%m`AHIu-`?h!jyMoLgh}g+Hij+$iI+~{G zP6p<*!U!^|jS@Y?_TqX%6M{RE*>9?1h`9wGCL@L8$X~mOUMgF!)6c`WYYl%N8-zAe z6(#1|v3Wk+TzqYQeR({s>Ic-k!=&uV0MeCK3X7%`5Z<C!Q1>^ZRCG3<xAB}jZ=!l5 zoeTAe8(AzFrxGyfxC6U4pMxu<493O%<=|6I&Z~<yh{Dh{<J9&w|71F8+7}SP56UpL zejOn@A(4;K6Xudoz1Yg|udD|zS@u7jK_`6?CPI9qg?n`kLtP0(%hbEl|5{One;;ZN zEUaBdxb!$0c~9TY>w0&*;0`l+T_P{LpSOxEv^-r6=XymjjEfNVD<18tZ{CKewUGAM ztwjq!h4hlptS;JcV|B#Es4(5R+OoWna%~X0P!A{QEVX93yRz4hza&}C4Vp@=j#%2v z&wJi#6eQBRLQ`0R;^6B^Cq5ZiE?K_-1fUx5Qfp!UCceVM7#^%Kk<$ucbJ-34-|mng ztB)7FG>)7WFP)a$@nNztp*5pjL%&|@oV7M%2g7&B)1kr-7R=6SbTN((g$39tq3c-< zVpn1G$D{AGS+75TmP`2HF~&aoqjvl$x>k&6K}7TjxRwYMus|iSk7KxenjQ<>T?*ey z84mxcFw2NqG`$HYk+{x#`u>#FFrl7}vbFpBf{U)DBWxABTUc{<W7M9L#%uW9uc+lc zyq<~Q_g;w^#{rIvmw9fw!F({f&qr!OFdznh65e%5Bmm8xeRxNV?+`2^0h*2)C=Q98 zyl3F%s(Y@G|MoW;J&obw<sen2702pN6{JWI?aZbg6K@Y&!W}7Aba~r@Md}W0Kv58` zG#|!f1}jM$??uO({7NZ)!>1#)c8koX9V#+2slCYz<H;aG=OoXkZK6oGk#N_1s`WS; zl@mXrC%qfjr_283x@8;95F;+gN%JSuo_V8490D1;Snn|bF~*EH!IvuFK8`jPf0~w; zB<}>ZeyQan*0Q=n`p1p5@zmosE7j9Ir&<1M!3INfZiAnU=LL-HHSH&%9zB+8V!l&o z)}JGXWM_zuIIBkmP4^N{fJ~P!yBQ3~P+K(<mkcr+*G29cR~42)v8q)#Z(66XGb`%l zRKCKR=>aKPUMW~=t2m~`JVDRf|5M>vR#ix!;}z0!(+vT+{BA_e3GYq@!>cZNzdmm_ zHR|X-|JAp`#)5lBihKGcVO63@rTp0!(K7a#!@d4>evx&WanV`<|8e3u<6L0H-PDg@ zA_~4Ja-`3jF@|J-?R^fVK*n)CaM3I*ymorPb(4zHjHi$R=T9--C!RNp$K%)nH*_N5 zLOmZ=d+nu|G=7(v<gPM1ea6^2i6-NzYb@d!?$xfq7KUYvjdW#B&-kSF$KG~*`TK&C z%dz@mB4?z|3gTLlLS#wo$1X1vwV6eBLzrg|V!J5Hhb#S-K3pDv(Fs>@hmbT$@bTN` zz{=~o`qoj##+?{5l}{1Hw;Cp4h{UI801Xrw?FS((QD&iyyfpvB?Qo7YT%Bk&Z6{Uw z^n9;blW#YuR>W4-=ellpo9IxtpuhLdT!gTNlZ(tNpP>co-B*!j0#qk687!0X`XviG z5#}B4{zT9EqbH~tCg88y=ig6_o^_b&XHRUhTm4Az<{sEl2A!~-!TC+_pSr{yb8INp zH-8VZW;0oBKTBld+qT%lFZpPL`LNz9@ZH9t=OJbvpVW*;ToUtMqZq9tC4iP)Go4*^ z@}TZ8g}>Zhhga17$U}<4n6b`y%Q4bc7y{#=(?C-7`ko7#er6f^h4K!MA55f+P2HfY zYX949sBxBweh~cY8_h}tArCt*?&8qKZH2ezAF1~F!N~WZ8(xv5SLg%?VaI&tX-#$4 zjXiL=9_7e1e8;if{niwmYOKX;yGD_d2w{6+E<pW@`K1o??uJg$xlu)1!CgQ14xP7T zxnOl$=i4~n{*ZDa4zDewWna5)%2A=oic9nB;C=KoXVmINmDP;7he;XN_{U(&u@?UG zqJu#35$wIUU-ouSSd!z>NZf;d8OfN3^*Z^YNo%ai>mVVWC>**Nk!V#*?25?HTUYR2 zacWvTYL|N6e=1`iT5g__N(b9zpWI63ZxX*_L5POSMz3J;50eEsQKkQk3CHJPJj$ce zO&}{L9zxT8EUg)PumAR36s}PbCz1g!bmMYB>p~|_pao-`b35$fM)*m8Tp%H!h9K1q zUa}Lg-9`721j#3q@8x2G7wR*A6bfpBztKNr4t5_}2#T(we-^h|fg%aHVbqhr=1pz! zcKF9ZPxQvZk2%Nx7|50Nz1W)mX80Vf;Oiz;)4sa`j#iq!uBrR_mR*K?M2hWgy$k}^ z(d2yy)Hh*+pQp+I=3sfJ_DgAF4BrK}jIr)CUW9?B#$w#SPvq#-hfyLZ!IlsB(r)MO z>-ZTUF8-wp#vS)wwk|T#9}yJ$LiibM;};8tk>QZD2%a<Q%v;3=BKh=_Om?a?JK>YX z!P`-ebprQ{f(c2TIpeS$M{$s`w=}#n*hciE*S+E1UDzFC9TDu(D-wN*h{lFKfG&!@ zSQRQbaE&i5ZFAE;DUOflOXb=!ykJ0(Rs$Hn-ta?>cpMqNuQWY$-A~7{eucUsfl0xH z6n_&KbtI_3V7Gls4oAOCvPuQVJv%(6TXlmqNcz!do2FY|#7R8-O{UP~ql7-IAvu7U z!yg;KF@2u7Z$oox7%PjdQ#ZvpTH__Uun7%qit5ndnpU@2_q&0(0)~5_9ULUYJT7V8 zcKlA*MCtQc!_$RpFIim&E=}{yH&!dKv7U$Z?kW#}c<OjQoyZiCXdE<V<q1xx3MF%6 zc`lsrK?Awqp|@P37y@XtjF!*6Ak8Emb_#Yl{&Gjr$}rg<Wt=agb_S{&E>IJO&i>5n zC=qRjJtLcUbE1u?*GWeK`uzHdwhSZ4k|za*{T3Z#EPF<^7{dj{J$tBH*3A6siDe8f z6Ud_bV{TLw_}Kb<6c_08j58;*5QxGsqp`+?dKlqnK60!~09<#XLGMTJaH+H$*V2Lq zMmkqs9_HKo2CneFqQ*V|Yr29TD#daAuGQME;*$id%Ui)eMDj*oQciE26!Zv0<rC(0 ze@==i?JlpsI3u~<^By8I$z`A$jy%=6K&{w5#~vQ+^B$-j<=>I)RI?_ThW948mF!Z> zhz@qm(O=(pqyvem=M5_F1;Xm(80k^$MW0ww&?oj}6;|&xz6Ze~@+m%2K3|@UR$j*p zd;^}XOGV6Q{m4s4lh?r@BCmz-+D@|z<CwO~1c;AAjBR&YyL_HI>gdOpw0&!){MX5M zWSxrrS#Ezp9xI8_4m7hwO)br=%av!#`dfXyYPJ&?6~X@0i&0CTNwFQ$UQ1CsBYGzn zv3wXTzg47Ar8}9;S1uPRwc6NBuY1y21;B3wiX2>`J2xUtY_3I(G)=CbaIrE<fBqdE zIkzvzI}a&wjE>#1f#jv_BB;0@vAdN7*G=MOR)USyB24(s<bn|dKBg!u3iWKH@DacJ z*{u_{VoC}eL*&2kx%et06#3<-k|2$uc|kAu(0%PX!wP%Xym{oLl~_QGmX`&cL<*=~ zU7O<X*>Z$-sO}q51Tyo7;2AFr`0wMaCGS)b8HR*vP>n;~JY$+I{gTgU2V9Vg=jqHB zEI7>JH1v`m$uTU3GF2bWxp^NL8#a8C48iSC^FLr9^?KmmQJkRr8j~d4S%YeMFPR^$ z!(qI0{RLc~4+<qzCnMfA4w(QYEo7F}E_xJ1uApLOqg;mlVn}{l6EqPhL1idZYgp>{ zM{2p7Z~sw(CqarVM%VlKHXrYSZwo{w+%PJ8r5BJ$<?iVaPTc@S7!t?nj=%MfdgTDg zRWg5xgHC~54&zfm-gu3*3_#1`x}fQj3DL>&;Faqc`aF7LP)gDx6w1UiOy+g1zLY@x z>-<kbx?zBBu?lpIkvIbnn=35jFWc&;{%oL1#UY_1@vh2R@HTAb$lrfJkfXl7;EwZG zmv|OWVGuW#&v@o=CAS*2{A{i{5Y`ru_s4Jn5d@(og%cTTyv+%@SI#sS<&t}9N=rme z1uF6%<DoKD#g+Y87pi;M@hh#nn?hN%u4|syC1w6?jf7$BhW!Ol?x;bX;ReNE<&l_n zph7MTGWu;6LW)HG=3QK^h}{qj%_0hV#K8(ZT|wIJGE&e&_b`1cOe2wORvyaXb>^!F z(2FD_-C>BPDlWlNlzK1TvDZC3e}){qnzt@H2$RY+M~{E#7?J7)wckLM^d)VZf%qSk zfKPXq=<o11ty*vAEL%8qGUE*MPAOBZ3`B>#)*shQiJlK6MD$KATWWn69xbnAFPxvD zz@@euOBZq#ZZ>;B=Sd-x`>5*-1v>g?1vP(hfBC!pnvE5;AurBtSkQsXW&lo~qfx~3 zpX1><#j9$81W7UzGSLF4q7hg~6sh6ss2*m-U%77Xyx!7t<tSAz7;R2Fmsv9YpcPBK z&C}~HWuW<{g)&)<l9wKR!*xtVZnmu)3OK3rD`>*;Z7T81_(SNufgL(-_In<I79zKQ z0gd&%Fb;IHjJ};+_Sb=WYY&|dMRBNk+_iwAc3dPaz2lBd64e{^ZaiB7uLZV}Q2Nrp zsc+ol45zJU;S#ks7v1`|9p%#<s(t4*wFI0$EaE%H9S%`BQ1a-FGizGkwoJsIM53Qb z;j6oHb5$|ts9eR<ZYvoANS5b^5p#c>a|#OC#*e5}5#ov$I@x3tH2NOAUm@NkD|&F~ zeiY46@61I#Zw-p&zn1}p(QAlLkod9>x1v*_JEI{~`QhMcsXKeDI?cy}5izM%c7zs0 zCbj@PND>->4FMhgXd(baS9)vXcRa>nJ}p+S21sAITpkQw#la(@Eym^?!)2EyBSi-= z**X#Fk67MRvPpW76~{==EzC@$=oq(=LRXZXNh+D0#m6Xrz0iHjx$*mM-xk@?x-aeb zBdopGG5f=;_fUXIW2wLfJiSuBghNUwqzfty=P-8~8$I0vXS|?MU4nN!{gAr=kLg`O zJ?=t7RlAR!$=oNYL;OWR;_oVR3MMO<{y}X(6QDv@K>kj064|?D5vhe9FMcNVOO)vT zm;6{txz8cVMSct|OqX4v1be7&{|07OGNa?FXMNC>d_{lmiFHnPSG1WqT(jcmA?L{Z z`h=u$#k-nFuK>ArJhNE@yt4H)0dxUpZN`i%N;Ne1sP<|oq_N{TaU80do-(70T{1iM z6W>SXnvXARB<6X6p~tA9{d(GZ7h~vDTx2qKl=UR4UxymKR_I2x?9<8`_Lr^FBreai zKI%_FVz0l?yk}BvKQj99&X4P33>qb;Boe-BI_bNueunxLjK>QS9YuLTG`Q`k1|rEU zS@#7KF8bki^h!w@FmcDELWooMWmcYch$P63UZa4iW$j{ZIBt7GmMfU=?IKk)^>nfX z7ouUwoE#6CYaf4bo5uHXK-LcWApSYW6%^1Oez>>#63LB}d{P+9LGBB1opqa`$o~kJ zL*O{V(wWXHs-Hkyh(mWeNW_S^v_Y5z$Nu<B9tvGq?P?Xp&W9_tUR)b9xognxnhJ=* zJ51?W>zEmD5Wr0n<8GCOWJ&MXpGmc-4Kl4)5pbAZEeOO|_6@Zq=aqIl&Az>FfzWpb zp+Xj@%rF5J+x?M+QXYs`o)KXr9!3K2>-SLKgJ>PGj<I9UE@_i%kO*zz5%bcG(>jP* zRu%m($Xx;kuCL&sj=6&D@h58c(we|KefDA0yc|<4ZG1>$#nRSsx$z$qxP%7(WJZ60 zWdG7r!CH_Sy7<a>@^UhJ-PW_w@(j1sZ#4#j3^l!++IJ4)zaMV;Pcq0*>#JBZFO}H+ z)!?Ne>&Vz)gU_$LDfP(p8IZW~<NN%CI<~dy$g;|H*txcq_ibVBaqhD0E%2Qxcl>c| zyfEe`j>nd6Shw*|%}W4v(c*}iRMu*!R)r7=v7C_Xx|DacFu1XNV$4S9Mf&`r{r7RZ zrb~2gi_tJIUqq<$&Y?yvFE9P?{%1Wv+>A&b7ZmFsZiTzNGU9R@V-icNO*Y-rVj#<m z`|yKdYUgR;IL3JPxV+h>(W-%)F+<_KT5_hNVGERG85Ws1wl%k%E6YG1y2vo1VY}{O zB>jRuTXNeVU&Xlip(nt2^2B=p!zn@5RN8jD#g^YRbHu63|J`OUq?gHy1?*;3&VvCt zsc$-Odkp*yB{{g@9(Nvf_#m@5=PYm(@AS{1C_<{A#?>I#E?!>?#40ulPzuzm-lsi( zwZn9ly6La}=`RJYChr37_4g7JE$B-L43FIV3B91}N14$64UI(z>>!4tkj_0%JrHtW zT=kM!Zm7Y(XX*LcLMnyYK)2h3qh%yh_IiZ2KH%tyBFChx#leU(q)>pa;=0xfU#Reh z2kaUe?(Xb%La}%jU4QIkx)oiIPQMyGWAe~nGj@_ZDYLwE&O4T{W=?gi?(FK)uC<al zJl}=sm?xNL=i7SZberJ;FAiSWPWeRz{6Qi}(ok9Y0QCzBq=1_wZqY@dmA!bdNVc43 z0yo*Hy*?WW2FtCGHGKDTk|#8-6hSufqnd9?Fx()flSzrMw!S+?()jd|{6|H(!lgp+ z+{dLg)zUN_ssXtK`0>St4EXm5x6@v1-sBY;5uu9W0`%UdL{b>r_|z<WX{Z^I^r;eg z6ftglrtVg;{X)&MC#Zwh1|N3F<f|ko#+x+Idf(Dm?{it(iyQUgNAF9DI)Qu1^E<es zBsF%!KK97L^`VKm6JsxoRVgy<e<p-@8M(5dl7OGC$0O^2ZWw9iSzg7~`T;?V!<QNu zqmME~wd0M-0ve75VXPl68pw%JCKm@y+dTS_YNykt-hvy;#{%3@T2k-3VdqDVq42!J zOv#sC8}BFcpvquE-cY>6n7`q=vhaZnip~wp!MOVlQj&3yM#09ldatjVS*1-dO$k@Z zXw)JFr^T8OOw=Vp_x4$YAu8=dp$@Z=ieWJ+4`kD-@9xR=>~2$QbxVL|jmP(N&1&X_ z(5ZNS7W1*Q6O#DBf$TbkSa}mYm^mqjB%#C?36AU$OF5z*Fx*D74?qw8MYMvsi0kvA zGnY0m&jsfm=t6R&I3@%Tp8JQJga92#>Y}MdzLDgx!=Vf-Tz;3at-;bO>Q6EoX1hh2 z5*EnADx;RkrmmpbPw~4X9#a$`BQ<TMFMN@tu&SOX?;`cw)_B+^dgUyKdLEbHcn97Y zo|_2~va2tXsZeG<#!Ml#G<JT}`2Z7D)wkZ`P)0YzwZ@jbOS>*xo=rb?CQSkGC|<pj z%u=P5vcZ~MY-nzi%KrP&|CQxUbeQY<&uKZ51m*T6ertz<3ZovUr7`xILEds!lK0zU zQj7C#U^bqU%I+LgtLUJKr1?e4@h}8iwY^X(7GVmS$C3L9{{A?_0e4>N#n+oYeA_TD zbg6$xloNx9dxJ>l*>h8HkTy7E)il#HXRH@Tm!Q+rOyoIDqK=8DNb7=7CQ>nH>3UTO z<1edkK*+CGGyt*dh=syxq=3%T)gLA%z=~1&R<zt41K^BL;Ao!1rqYJxc`r4@ZC*B# zXxeD#Jhdjpf*!t}`QYmQ7OMu3{$r)#)TDC*-Si@A{IxB7j^?HHlDpRllY^na<1AJT zQX3SSk<8lS)tY6jusW_?^OUoEE}jsGjM+;ia6i~37SYvPwq@)6sJZDQ@E-Cj)NrZR zJb+0;EINdn5s1aO2k(f(|2_iBbg>N;Z4av=uP-xQRc&|4ZFWg+c4^LJXHF{!wAv}r zTU~4dq60!>jfqmN>ojV!!|K9%A^Blo#yc!1fym_X$HQf(xnE7oR2v64<i;rYsm+7S zido*u{!S;nS5-}06{v@mBIbT2H8Ps3*{`l;75=cZuhj?`6m4g0zy?fE^?lUU{i1s{ zXwL>21b$KKCrj#Y*wkeh=1%imwAm#6zPV+{#l#tN*8cj^)p}>}fiWe1cVVyL@vPY| zQG$<&H%Y18vti-;MHmprqrJCCf{534eY+~@i?Q_0{8RL^;(V@BKPPXL?52TpyJvp5 z2Ropsz%H9-&zDbmX|!qfx}P6hbr9q-)!Ub3xHJTweVDZz^2{8qZVfG_sIlN%(;o7u z7~F#TJi*+v``cSTFQ7zj-9q4-+m%!{lr}^1D+hV=pldwSH1rWym)FZk?>HxIc!m|8 zI=k_?YHKWZPoQGj)nk1>!2N6d(f7ZQ`Pd$Cz=sb}I@F4!()?H40#7XiNO89sVy*7q zS&lamLsIKjdHtnCmtGq<@AnxvXaKJd_r0Z$h1h(o8BVZWy&O2C(HBkVIY(YUn{f{y z07WxVOkogHE29{f{})|;?b61*lmK^{KBxE2X^<t$3beN+eu5stE5dQo(GE~Dmth6D zT<{l3qnaAcFXBGpKsV;3${@4=Nq<fW_Z~?MVcGXzka%lzGnmR4JOqZj5^J%Cnc6*O zq^kCygeKEtHsfwvq4DN$60+{Y539<~w*iO~!EKcCY3g-ylR;j%Z>-G`Gi5<?Gx&!+ z3+qrSMYR3qG{Y(Yk(3rq7g2@_(8ILUh1AJ$eH}&!VGei5uw=`$^zZOM=_hnqAz1C| zNE}NvSb>sfm%c8<_)pLdrawMyIxde6_l#sF9C3X++g3wpdd0;HR2T`cfB14<{UUgZ zOE&)5xuu!BVb2{MPmT!W&?YAohGS#c7e>PiQrV1d%_SUfZtqd|kny=n)^<D0pDf@O zf7pA`Tz~j}vzhT*Kca;IM+-O)bgmo*dlaHU?&X=;Ar|zfrkY{Ko*4>W0xNGg9`pe% z+dE`#DjdfW0YiwseA`*=&}|fD>u&LsO;~?f7!X1_Cg6wq0d!t}I_acQrF#Z>b&ddW zl0QJ9w;7B$)aTBqL-U`!*X>rf9ti8G0Z&Vfy(6z{yItgPlun=Hn_HD??X#zx0vg0= zQyCKPN0BJ}Kl?XhNu$XqpO8krvByCF$i#*rEb*RsB@?(6%w*=r>;UDq5^gWdWS19Y zg#vhai7sEZml9Kgo{N(l>fJBOD!bk*Wf<nPo+qn^7;{mg9;n=TxhZjoDJ<#nEXQ~s z{Vp8a<Qw!r;lJCcjyRW6k7(t_-s8cb=?`V#RXyb4qe;d$Se}$1A_SB@-zxAU>bSL) z^1)L^_GzP3ER7|yCVoJx^-vf$3sNK3iLDe$>r0J^t7`;P9PD0S4eT4;CVSv{E$Bai zyn$9WP|lo%aee+vi`t__lIOiwZos)Vp65M(juP8`)PCF2_H6R_0)&RpfoGlP3%q?_ z>N#Rpy{)MtbAr!9kIH1Ci$psRsnAX`_2>_iQ{?@{iyK;w?|G_ii6SvMX~7qpbvP1U z6+9p~_+SVU;jk2wX*_HBu;rexy}!EO94L3S2HhXl@2>M{ITf#q8}AMqcC@z%=WoN9 z(V_J&uCWI{+Cd48+Vf9cNod>5?WB7s9mLb}a>I0-wh7=IIk<0nhjC`Z)Mbic-zDIt zNPf9?Wt?%jh(?{uj3qlxknL~gv*6Q@?fWhx91umxTc-{_a_7bd<mENIJRIlhs1oZV z)$R+D3*j2N)}1S9v}}E<psri8C{edbF?jDZ2HEWeOi&D6MlIWQe>5EAFo;47qG4bC zIgPfPQW*3Rm0lUD{ZL2>%InwM>`jtwB7)f$=Wh<DMUsS!jQGO_$pUfO5{)+}Tank# zD@unOIL&1E9s5M4Ax2^PMjF>i;#>Uvsg4&Lf(UDcpjaBtO}XT?RE>&?Hi73u1&P#j z=cV69%4ObbuKNMRfklDVqCZglX?o-q?lL0t&G+QG#N8C9&Y&m+-DzUHI}<LIjK7MR zm{vDy^zMY;sL#s_l&lx`6crb3v6@~{xXrlSv`)F+T<x9{^d&eom*9(V9OEk7NS6jM z-_I2CtDY9L6c8fjn7t26bKS2F8{&GKQHa=1gCJ<7*89!hd&wATOb(8_=s|6C<MdKZ z<8DYIg!kA{+{)zfZC^A^`}x8^qe>qnft{D5PEhf$T06XB!gq)Fr9r!Gd#+AjB2m?E z=PuHq`IQ1d9>mo&buh`xizYMg_#N^K>l6UnY-U;iqh5m8=30;XG?&!3{+J8!QqZp{ zs!k|S&(Zacga~ab)dOxXOfQOn1A9;`6zOWSO9H-tB(`YmtXK6d>1878k<qI7u(%x> z4)0b1c*Zfh?1PSQa;N}$rJuCuUI7YNyOL(OQpTHcBkz!Ftk#}|vQLE1YAWMNwzgNk zfIwlXfY4fUF@oJS{kp@ME%VAMu}<PB&7-pa33MepL7HRGY-V&ei;JG&80L9-NzsbV zwG3GeBc>8{8gpZm?PUXlB0T4{T^9KuD~4^lMfWjo_yS%YqLTZ`(YUB-2dMZ^^I@56 z<D(&23imC|Io)IecU!;d!p}>(oO07=A5M&-Jzr!-X5BqPA@>;XvE23-B!_L8>D&b| z%j?rOTPdde6RgAcEGBo2E=7&=79+|0?~J;6e#oh&ist=8Y5N77W12JiO3d!at+#kH zvVZO@0tpH@9nBPNXXNh<PmS`)<wh23_lZ?fl3K<>HHw*<uBVfhO2RfJ86J93P?j*% zU~_Ll6g8ll;yh=$P0cjNy+-X5W2QM`c3B^<P4k|c)cBji{Rt<6L+#?=Q|+mQMXk*% z^6kK$q-+%-psSbkwc>1ZFxb>4o1+OguwW0)7@gEu#7?Aq=c1v@CKsZ5pxK;S0wE7T z>50bjxsugz%%MMKN2Ud_fQV-X{kRvTqCrn5n9ExGo^!*Gdu^%5-ygFWJ-<f&Uc}x- zVoz?Mnq)sU)mR$#O0hO>ZR9KDOJcjuJ~>+hE!=oRX*r3n$7w{avvGARBC{*YETrbT z?x%nD9;N$gveL*Ne~+ae7q_;IdE{7N1`v`UvqXT_^J-NIC6;>MK1WaKM6g^JLw26Q z_3eM4Y+~;U{-lS1xTfdr>@bT;Vs7Jj?Ixh2(+oOA_SV|=9>WsO_2#l8_u?E&m%zVR zogWShgANYX{P%`SQd8s4@!%*Y_gAl{R}2?CyvIOC>DS||U@jo!AlB7RAxD1Cew@u% zbPvp@l)D0H_zDTj=Ny`ruP)njlzXgAH7uGN<wp8_cKLam(t;1J*u5p;q^R(3+g_31 z_%xzXccWI4G~IvDeE`HEp=dL*I4^yG2;%SRSOgp!q?3G^E#rxkdXm;|5R4G*9l_#` z3&pozN6X)fE2!RD$yCXcBFVM*O>2>trOdFO@>IMrMPHYPh~t!cs`_ZvR^Y`psQ^|z z_2XS4t^3w1v1H=yIm%+KiqLfu`Jk#f^Lx#-)s?SsHSG=fY6%kfRd<b$luXCvFgnFL z<x!pza6r+58p*kZ!~=Cvg_&h+C6~xC%WEolW7Ymd)>GtUOT^ZtyR0oj_bFutw7#h4 zrTYM<CD<m30ExE1Zv2r%sZ@zec3l(Qh#Kw;i{=(EALc0J*9ZNN6{Cr*C&o-@a3zjo z&SCL>E*y*Y-cwRk$+l`}Iv}7Jdwsq<n=8!cYZy-bVZXH`32&x=Z%cc3=KY@4o#F|s zfu$0Fty)C$>i*U1r(B|EGoXKr!qG4ayDR0W@u+pRXNIRH;<efFWI`30jj2Xm_y^Cw zY{Bn<lh-qY%Xin;uIv83DYQ6vZslbKc^UIQM2_R_w2L&_;<9eH$P0WL&>o7?n9>v~ z6pMh7sq|DBP&YV<t{BbD9w*@^F=L|=rG=**1N|U^GJ_&JO-IEg!Yi_u#f__i5G12E z@50lz$Fn_H9fL-$+eb`l#A;QBVTy?beGe!``F^<#vG86eiU|#&#JXgjUPB^Ew1W@o zDUOm^N?h9Yur)-P`61E{r%BCgIm!XW`bJ@hY9YU5_8$2H=PAZRs`AV-w>DuYbrj(d zQMHWdwIu{kj$PZclmzf*@0BRl-}IQE7GN$j5F5E?r8$grZ_X>!5B&{d!HMsvgdYl5 z-&!q^tL{jyHA9MHI$~8aMP`9bP^v-Ak^tACdR_Q!@+G>9ppX-g_~%mrNU?^)1+Jna zd%O}3<+v0dX{)jRR1WHZhUsf$L1~Bi606xu#Y?-~2w%XnE6}YO-8|R-Y%%2(;ImWK z@T3N#b8CDa<K)BeI5ht88E=QQ6`POS6X_?=kg<Nnf#ic*N6`jXoPFgh832UTJtJY) ziy7-le4YG3ZAR>;@#3vya4fTd6=)qP2I$o_PFCCBzz0<3#g7`5$@C*u``e+5TK|p< z_@M$~E-2u@04L<|Ls&;#HwJ#~X^&&s50&2x5YHpZ0nZ0d)|0Q*x0YxYxG+agKbf#W zdy)^rT~KR&Aufm-;8NMM7a-7F<R1qaFBn7s@!fh39g>~q@QOW8Mn)UVx;ga%%_J&` zBbkY|E}+;BW;gB`uHGmh{hxi2^ox{eN@w}Oo!LvdHX((xjnM)tJv_0nA!n@+om6Ih z;T5tB=za&A=2LdHr$8Q**}oZK-!YQte5Q7T7yOjrjOmENt(dIf(Q?t^zMyyV1QcUY z(O6<PJz!J~3^&o}u-Ava_w>lKgB}IF$^dg^@TYvFLvH5kE3Qm={y4i`>B?J6G{oyD zuaPOaj91mnov|tVJ~b?;Ls;Oh6ZOO&Qy#Rp*so}vUzD_;U1wRYX57to-6aCK=thl1 z+G^1q9sk<+b$P1wZxGJ_{GMFa&w#5o#+uu<TQW_HXEn_-&$tq%_`{~Yt<LiOf#Nvm z0UI4<c(iKCG%jW8lJ{EA!M3y9TCqi`T_)bAIR?`bOTwi?&O0oCG1t`@E6MuWQ7G6! z6?sfwv1j_+Ha4TclNPI?>y&z3&2&}MK9Y)~xiAbKWIk14S1bl+@&>XN7N6F}d#as7 z3C1JN--*`6;GYbCIe~yo>qCMZmuS<TZ#^?fI9Z~teDI0Ta>>s@$g}!$;$K?#AIk|n zJbWO9qRrHz;VC~2{17`NfppOC3-f`<UsUhEX(T;Hqz^J#D+>ri5m8hcb*rH5GGZ=A zA#J(8&`ke%7R9%N89_Rd`gn99KprlCjrcDc5B`0I#s|7_)yk(jRuK2*h=~3w0dcp5 zAMOv1&v*2q=FPgm%P{L{tez02O9C-35j{HPKNe&XnSY_Fp~s1sul_;k*uhz%;0cWL zXm5gQYB(}cnAxhi?JdLR*#_|vQF|-8rx;?jmyhM{KKo9PGpc1Fibxpk$j7=k_SWdX z!G6$QtBvTWM382<v{~(rGDgRJ2bV3^l+B1k%5x{;YdWJ1A{S73+q~8Gy-C*XBMx=w zkM83y{&I~<lwbaKenJrbho~MSymSI^+lK;m2%8Tx`IC<;`LD=4ckw1vBMGHQTZ_qN zHW7RZpnTmQjmUYSkkU=<<U!V^rzJv$vUHC)*}t*4(9Sd?@zF<)OJ{WP?~X^t<y13= zmd;O@jP0|DadA!&VpyN4p0^rBa+zU;I*GB#(n4<d+a>i+Kc6zi`X2kSvrh~?Z@%F> zV5$~1VZdK|LJ;}g2e~Ydr+3X({S4N*5jMy^)nBq6wclx+YYJ57&w2luU6Nq?8A0!o z|As{cLjn$J&;3xyIvcKSewLX(JZ`d-jAs<bei;>WHCl9j^2r9bp!VSWnqL*GE~Ba| zvZCWI9bVp4U9?N<35enOzgkJ?L-IZ@vRSb44|1G#RiQTHrHMKQwI;;QNCQ4l2IjmU z>Y6WtvR7yO%KM2}QrWtl`cUYO{OhhhH^^a+YdkKfmU#}ce6Mx72gIMY5v;UANh!*& zR+3o+XPAnff0I*a2SShfXc-hU!67sItU%4CB=g(-rISe8g~_?JOOO)|U)w%8a;x_L zL)cr#MY(nT|B5JsD6N1D-AJbcLrF<UDuT3>2uOD~NW(}73`mF4AutSGL!-2GcMsCP zi|2ms_&$gG{Qfwvm*;gn*LBU_Ywx|*+Mo4aX$}Ns%tGI{#_%TpNTMBW%Q_}JqEKIO z65IP=1oRzG+m>Pb={i1C)j^CmEND(_49UmLoHOPYlO?*80OcmPNDh&O{mb3-L~UEE zh`(yGvQDuAyI+*@K>CC6pdjS{FH}WoON6S7pNVR-$;LzO2g!&|mSwTK@No{?IrV3N zO_F<)L=3PMQrG`^m%XoDCO)$Ws3gk2ErXtY5BI?-zVF>2apx#^`4NxtsvS<(DW%CV zp?>Jw$nP{NWe*S^MLN=qEx?CLGZ|&eGi$U6=H4gn>W}&L3Aev5ifLv147_RQ5f1}B zU{g6Q8)!~&AE8P!ZP=rRBv&|h><_GKQtrM7Z|K^@upfOn`o2pIp?QB;t4m|kd8bfb zVU%`v9zP^|dP>A;DpGq~sGbrw4ByL0aqQ`;I;D}7L2vHlds{4+Iw@7A7Tr*+1nfoz zS=V|v8EP;IGd5gRG5KS|w3q$luS^#@@xI5D7HDy20*ob65@rjEFlpE<Y1RgL`9{QH zi3w2YmadH9u?CecN#6cQ!dzWZnU*@z`ORbh0`7WvX4xwl^&S+vXX2<;Zt&eXJA>oq z*Qd8#tHC|7nd^p+@VOR3&CwRetrNs}^8GEsI1l}oGVoj!BODuCV<KF8pX#RT=wO(H zQ6=_-HTqx%(WvwZEfZ@mM7J=g;DTNS-ni?1XB;RNUo-Tow<ckRh#gg2yqoN`3{#c5 zjfQfDX8+~@EF^ziXy%VE`_aUkWXJG$@$q#g#xq(j{Ofge9%#5c2!aL6rGrCqQ8(`A zZ<W&Zeaom(*1aTtWmwtnDth%D9O(5VWerUEbEaO(f>FzJ$V^$b;MCZ0I#@(FFNh@L zvx=-7rqrx7Etiz<&>g4A143r~tl*4~H@@H=E$|D*RY>TniiguuJ_^2s8yAZ3WfRip z(x`~868JNvT=0|EZD~BhlYb-kJl*ma+520pM1T!TU`P@(lS|lDw7O$<b;E8lyha^D z(l6o=&)TUUS9(?LE$TYXY|RQ~-$w=aZ)3ykL-l&4((eM*K~=X36hHk{pbhN(vEnlr z479;JB3c!;a|#IEbc7*LJCx(D@)$ldHys0l!8AmeEs$6y#%`pk&7;w$w6?{v?Cgh5 zAbHvWHw=#{=tG82)qab7nrk=JhDjM*5|X}3mwNY2jDM<V(mVD$<cKnXd}Cy7-iTwG zQYW2$*_ke@?>x1@jl@^l2Ph<yo~5z)bb~4E4$%%&i+6!r_DX3uXjLwO3#dw+bjyQA z$d=UD>Z9k+)6aX}SZz8@YJN8=op#!^8Qm>`@tq908S*8c$WkL?9rX1MBinXbjLME5 zdoTTQb8?(?6#i&p(eIM+t@F4{Rc{Oo+~bDG)RXKz>KBtd6c`2O_@C$ffBxaEIAAe6 ze9_H-2QWXipnxboriQoxS7+j(jWOL-xj@*s&@VdL{!wJ`Luw|p?yDW&hvAD629%8d z;|KbT(guSxDyOvezCNon{75S+%Z}L@^)k70Ri9$R!C@osDRYZtu7%Rh73F&(Uc*W? zRJ>7L)Q~+ZJnhPoDGEQcD91nEHz_9o4`JXfM$2PB^>VlK6$OJz75a8pEr|Yh)f?)- z)u>zJg%`nyRc~ek@3FUaqxp`qhJ#Z^-V?4C+8b+3QwQUgu<qFMD}+k<N)%*RL*&q) zf6G?2yyI%40#}Foqy>|Z5k7R;aO25&ZAZY=X$*a~A|U0)=!~Aar21s&4hjvdlWhNp zvrQPfV#IcU7Ne%-w5zBQKS@Zfs&Isxv+XgKJnFijYw0fA_@iz)?2qfrDTnuANj70} zYZGlUW#zRa`@OM*80B-L6d2z(o*)r8qu&rqaPHCLq3&UMeiGln2GXkxv`^gr6yP)H zT5b;Glj9&S+I640pTFAJuG(;R@ZHzKM9GjNt8}+%wCrihSH_MfpKz!Ib!u(cc5^5> z)oGgwE3~_>(nOB*D~Q|>r22r^P}iPV<cC!-GNr=zCB{<5`RV&@P9a}C<*r(saQ+0= zjZ0~%bjyXaPUoNf(o=!bGjU~k{fE>L?a7ILr40(kI`uL<lZEa{&tF)UNB($*$>TvC z^e0E?AtH6dBDd1Do01c>18Nv|a9|uh0fO<edwtZ93IDR}e#v&}bbXAk5&{)%L8NQ^ zTFYBs-qDpV*7b?Pe%HPo=WQvPGR*jX{JTO=j__{zoVVObPo{DeKQ83={h6||?&G3O z%j115y`j+Pwa|v=S?;EP^*_JRm=FGw1@ONslWQK>RU)6MkrDeoCa|d=s1A7`E2kf5 zH7C6mQyZp*ETqrKvX&z2uEZYRdSdi_L#xiVTEz09{(OWW{RCs0>Tt0cg{$9pr&(VP zJ2$1|jtyYC&n5iathTo0)?_AR0w>lW|INssVE6;0pmwO3fMsH_+g$*95GDRTiaF$& zV6}4%2-1?{F;^(CF_LV_?aqOT!qxumR$KeMJhQ}X=e&-cB9?ACE^EwuNDL>ra#P;) zY4Lha?e|Opl<CC5h!(k3R2ApP1@!c&#*`xo3A=ke3wgv5%MIQPFb;G|1~$I2KICub zMdoKsR4{{NZ^^}wPHzvcx+}V+Bx|B{omKbOfU;0;<N>pG_GQZGp12TYU)_{0OU<^8 zZW)~i2f47kfas)d=V9K|#|2k?!s(!UYZ**t$4M3LZ%ECOy;sggO6NaJckRmLPu#F4 zUIzs_7zb=BqGRe~0p<ObrIVIB?xT)wS3jKj&nw<F2$MWxu)`$u3~7Yo&$=%qOFyQ# ze7Nz5T-TUwj0q^v-Fh6=UcU*`whAx4Fiq(C*zZinQx%<sE0nnrV{5wR)Pmv4;qG?w zZkwg+=%=1}k1f+UD;C(eGIH>AyRU^vUHwLX@+$!;#Mf?eYwC4jIgLkp_Mw~2Fi@eo zC6^ZudhnvL;Z;b?Cc)YVqp3EzV=J^3lkoT4x=B;LGqbvbRyr%k8QIuk{c3NA+SM_9 zTJkgHcgW={{s8$8{89?EzRstBswI3<mqY%e>tO$PtIEprBD$)a@K2{VFbja|62Ls8 z#m8w&c%EXg(+mteBF`b9+bGi5@9;6poz!IlTPXatt9J~FGI8TpuN(w%qL4bY<ohPQ zaEB$kY$D}K6ULWi6L}2vMToRJNjF!kzr8NfSJ*@S0EL5Z8@KO<0PcN&tO+?zxu-rV zqdQ06HveM7^U7>NgxZ-{y$!D_annjwZy2B7oGQO$<$S+%seL?1?6k6yotIIn|4Eyk z@_##c<P3^1Q3LEc`{K1O)W_++2zN9@nZ_Uc;*($CkSid@UzbH#*kONJa95sCS01C- z@k(H~pFE<ZH$x-iKrlA6k}@j#sjiE$xu74@%u2_(J7ST5Y3wZ)^5;Z6=_AhoQdVCz zYxqr$hIkk@5F_gttrL^K7J9|cfue>0LCJZZv6m_nzBj3O)M2sS)D@jh<kL8f!)Ig~ zMkM8%`N`I0XOTj`;*U1)8S6QwW4}H}e~O6^WB>K7L(;d}buip*3jU-n<NH-y_iuN* zZ=<<D_0!7Ger-&q@=bOHxJ0(sZoPFPv}?p;6&}Pq-y*&!&J`mLneUgnCk^<s5A|i= z5Q{v*?A){e-f>sH@Ar?Qv4cgvy15WZ%imMZ6Z1$}lltoDxHByoA25Pt(oKYUFT>;a zT~ujDie({{P2TwXkzhf3#fFfLcCG&sh7UZ!IG|VI0m6xoz5X$;3EndfXbz-aM%CMy zL_Ljr1{H8nnE6yT3BQ`u-xBMfH0ho^7+K?pl{$2y7!vXr7bHN~*9gXk{J!v!-Jbr_ z(NNMiJhD4HPj*sgSTSmOpyI&!U$z?=gHDX4BNr7VM?6$W3io7(JSB_{&1U=p^B#i_ z6Ma5GW6)D6S^a`7g?ip$GpLa>*tsGCdGuDhwtlL1Dk3)fw~LCvgrF1L(wP&5Rd-)| zLzlAVtnospY15%jk6;I-*G812_TO!93}Y!zuMH!LP3?91x0*(R<SADz0t+SGWoCr$ z?-IYyqEZHM&~B=ce&>tJ`u($7&IMCh)Y~Y|Ui6O6YM8DrdU40wL|sX=OJny#DtsoI zlN^KLt8Fwh0S%R&lcRgDv{*U1RN;?P{1zo~3TL6<{?+IIbi4lj=h-%Dt`hMz2|iHl zAg^cbYY}F0H=_mn0@*7HZ*+}-Q*x-r26)LxMtUyJ4jXn`l8Tn=9p;l6&Z~DpZ9_~v zu&(y%;$<KLG!wPDg3g0B5DSdt<nN4(`Zd?-l&flRmg%PWk5fFVzq@S?YS`PB<<@rx z_MqFT9?iS=9D7%pEr-062>SQu{HKqY{@h>;!^CWdaEJJXyszDco^M$-5c33<aY)a$ z(fU}FQyo!8^>{AmZz30PD<2Us&^-~HK?RA+*`#14XpIXXRtXE)>kyTdu61v#6KYBL z683yaS>K>YHU{&lZdeqWudrXF>%2-sEME*U%+4FnDO7IoQdSG&CR-{fofNarbtA^L zczzzbB}YKeA_Ch!{=G8n+vD3?ingGnUv@D+Cttt={!2RKDRxhw_}Y`8Vvb%B<|T=7 zR0rK8Ef*By4>T5^JnU4_eS1P|JoU;M@ttz7mK>*9gd=i_|3kRdQ45v!+1m{lpHu-7 zI_wJIx1tiXF--ikMQ@BD-zr=WnSC@E8}{8(yo>{*g~msmEHWC2XObKid9-3W(GUqi z#b2K3e``6CeZCIedZgjClP};jghX0z&TH(T1AkLY4^^9`TWJ^1&{sVX);+!X7XfZ+ zNMj=ggI%Een<FT{@QX-vy5(S8v=#v=4F)JIP$6cUWQ}A?;G*p5=C*oN_3KHT<Rz1+ zNZoOPKZE_>jB1v2do9hXyKGXvRhMEhbk~ZgD1}QCnivcO-?(Qg0CQu>qDMyJdm`TG z*p?AgO#eKaN?F9{%44+7a&zX&QrW$IJ{W9dLE)M*{w{T!Z%vK<V;pm=l}LR8S<U2e z_U2K}q1u1T6k!7)9(xmOCM_2gcDlUj^E?LvyHowk55T$)VJ|(Guey{Lt3;b<G(#rh z&J=0YVrk`-v_rl`JYe5b!WFs^UsMqZxbY*UpG^o7tufzm%B3*tx^LRjl%anuIE@d= zPPk3(7;I45Bt8m@s1nfdIrDZrPBEV8dMjD#AQBfi4Tlo`05h*l(!J`q!CNWm#7{Ky z-EV?7Gp2YJMNFAyVEratntigZ{V=p8A%xcLQ0P57&ntdag2aBz=jq=L0I|@mH6f!5 zSNHu$VXMRa?(ug|zt3r_*V4-|Tp`hi_hET45yc;hadH46(>d|*jXCcpm_aNmN~L{j zmX<m&jHRl{WXC^nClKswm<@xk-JnYZpTZ66>L1QTqA*4aG4qbCZ`o*F!RV+w#?o)! zH&6fTU&p_#f2HNJjwAI<LPl{$U?WL%swfROt5R5f%Q!VqKumwLk8+y;coE>!B7=?l z)$Q-Y9`2Pr7KPz0Qo;b&(pg#j`^|gJb@qpV5uhTdxvOwA?|jPPxcT7thpP&l9S_;| zyjCeULO{=2??u`?%MoFgJx}UPzsYw0Cs)A6bDgBwUcy*{K``Z+%|nlA4~pJr+%UEO zfL#GW!95aYD<CqVs8>ah3#)vA0&j@<yEh13{~yVIi{S+jFbPYTUl`;r>aA?<iVKM1 zvRGB`xWMWg)|(py68{=XUlM$vUVv?#g9AC>U-nf{02?-`Sn+m+dB=xz#zQ{+0X~rO zlK>G1dTT!)pvs!ZQ27lVajXAmWpybFQWg;r;f_M2P0pE8y`EgOeb6Rw^a2OxXU!5{ z!^F}-lKw@Z{$J+IH-Ykh64CVvh@b3sACwLM5$sPrRYAuqq<gH@vwcyu0P*2`cx_n3 zFVdI%I-nDcMsp28oly7$D;i)$_iH-Q;GpV6lV1FhnQ%9mrnlp=)$)gjzNURRr)LGZ zf6bnj%o0V5*UXC1Mc5Ef`>e)gyghQ0NOp^4m(DNH{A>b=s-bY7XvG}`hrrFfnVkv+ zg4FaKgJjcB*$PHm$}?_?9R{em-e8zWK6_6Zjg_s(K#=H+!IGDq?fU3sNU5+NvQ3;% z>ij9;VCWdAGc^OCIo2+!k>rAX@tW^KX|R8U({((*!olfqHRKnYShnv+wn5}p+5TdG zT!Q}ylr05UXvH&yfs~ZLu9cL55(Znuwd96UA@{oI9?!hE4Z@E2;S7}j`CRNLG*l#8 zBgX+W#ba__({L+5#pkr!gw^4yC*%Le5vVnqpa}*Onj$Z@tS2wecJ%M3y}n&Gp}aif zJmZPJChS~Gp0!PrObT8*h&;zM?MpESF8Y$$D}Sk>%M$7>eZBQ%-%s$+{pD*1Xs_dI z%D_p>e+1Xk%I`RO=JVq-9#AT-)jM6QQvmI)rT6L2G+^_-tQI+0j2oGnvI4jee&5Sb ztk=+tae#gEL3sOz(Rd*=U7pxeuThB1Hb^*>w>xTO*uti`9$j`_{6E-%&6Hx0cCl%8 z2JQ$;)k+n#_XOl^n?_V;iNO86t8MBIcm<l+eV0VXAdJ0A^MRnNEhXF1naAbH$|Qj- zm|z%S@L0#cTQb-xu3cxH1j=9+Y7oo(#n=Q90w;(do}i{v7nX!K5Zm6tHwLtq7e4?t z#6prcz!|6pKp#ul;nMbh-H+aL`!?N0HQz<$=1d;NF^zvw-{A(%7%$out|*u2dAwe@ z_oeGukC~_u)k&x9^XPA1<P917LCU~%)m$TLusO?nimL{XEHPNbo6iA?K*Umqi-=Mp z7Yza{A5#6Gv<84KO}5~PfuFB%)NK;Z_is+G?7V)R1-+&!h4c1-=01r-o)#m@*a1a0 zjfUucCtY@WB_M<*gGVI=p%`b@Y6zIk&!%>~MsbB!(_J1H7S$Hat;xN^%|f<TF%QV% zCki<hi0rizHJJnTRFwc(rrzfPo0iknpM@ydMRW_UaF2`LO^F4rY9OJ}$6j+cUH215 zh*-#7;jIdFHX_C}P$x*>8voQ{M996Re|4HL1t{ETShG|P0O~<6F2IYrYaoDgi9aiM z3V=Y~V^O*o=y(I_@v>{6l&#1s0uI(Uq9yLvEC&GWLEb#UB)W$!3|P)n{^c2l9m0co zm*pfg%k0k@Jm_Gl6yua03S~JIayO8Z6ob(`f`23=dj_EAY?j=^!#Vw;?MqlZ2Qb8F zPCceJ^vtg7?PXhA95v%KL!K(bq2ow^0MyYy1)xFdt$xe}aV9?8X$1fl2G@7T^ID!4 z8~TD$@;5mYiP`{iZ6*FU#;>Bn!fyP>nzShx{o8drlnS=v{ak^(0e2Bs9QB84l8K1r zFBZ++5f>L_eHeV-?|x+7rK9P|5_cWZG9yzcQ{PRUlsNc(4KXPxA9-uh`#mYX!pJg9 z?0gQd>H<C4AzTHppvD0;Ex~gWCn2ke3jEfq<Ay7;W_tGz^M;{`kYBK!o!=nXp@cgW zqV)+0Xbc0L&0ZT*tUr4^>;?!lK5fy={;6)b=oOfDSrAn%F~Qu~SRKstFTcE4C5q$u ztB)D<!T^33h2?%f+2)_ofic8Dvd2b@xxs1YsXi@bf+RS);9=CQ=gkQX=O*sQbu+r3 z;(%KBvvAM30_@u~ZB%{q=nY99am6Pu48+3|`7Ja+FWFAOc^@nL5jpI%AI!|mz%5o$ z6zx5PP63TNP7{_)8v}ThSuJuQnqwV|l)i^?h#@6ABeK0F$_GKBqJU@-%YB_MifNKR zZ4FEN8uO+Fs|x<$zekuy-|_ZIfzB%{JKfY7m9wuDSVx?-tF%UI0;9>6WudyxQ;vh$ z6SV-DCc=}70E>W;fO-6wct_X8v>t_jR==s7-cveI;+A@BjxP$zJnT)XO-gVqFw=~+ zo9X#5E<Sn!F5CKjf7nBo^r;_J3Mpqk>YHo0=WwXZXT0_fd!{|)>#f%XpA&}bRracu zXM&Lv^k>k7d#5!9AA4-mk1Ho&-kf>;iD#!A8XN0x|B@h|We{)lHb5t>$4nBXO(~0N z>C~MmwOx=Gt3%7=C^t@zYTI6t7pW`Ot?y?{^B2Ca*z0%Gb3JP}N%Lg3p9cN-qw*)} z&%2AGQBEBx=JQ~WJz!UX?Cap~cI-a?vuJ;qP!?Wwt+Sg`fQ0QWbdVs8t9LyK!>p>t zb9OzSX1b2N)UL=!pOmLvd>eC`w8A+Cv3ZC!zHeB|Nq)TTt2vU1#7SRD^f<AZa|b=X zW{1tq>;I|){_A~xq}~r%op66{m&4UnfwMYbrwY49wW+Q=Dt3{c>mI?G`B@5R$rcs8 z$8o&?sF~Xwr7ySWsZGpx8{cXJHmxWp%0Jm-z!?<AKdQs)0#LYYZs(2x6&s&`!Xx2G z;8De|BD_StILzJF{`9?SqJVnF|IwrEwI@c3@yHqdUuKb%6?uS0Yg*-eMeHinYcAPn z=}YO4V+$xzd$*=%TH|~xkuqD3a++v|Cbzt2<h8ha7c{x|z$FrS{C=-~$CI-?@u1uO zLC$`Rz_S_PL|8)TVsczw7Xf(aVm|dScho`xTnLy^ht5Hr+FC}xg1&&xgk34m@?6Gi ztz!VeCS9_mYt!_j$9boB{-w2>dg)TU_G91|puvhRa3nFLz3YI1I~P!B^1@mA1F9%t zOsH5n9%|k+tWip~yjk4^h>Z*1#{3<sKjP38kK95l!(9LplsyK(-*E755i9ESL^%5) zPa<6w_gn;qodDdO!5rn_p4a|%J#d(F7X6sNAB3Ne66o*%NGXpw7)dOO>z%?MP9jDx zgTtHa^UBS4=ca6<X6Gq(Tx91|Yy5?;;Jc{{o=jH&8ZOlP&HEQrZ}ePEJY=u2aP!md zI}y<Kn1jB9DB#@tqX$4Zgc#_iJHYmlg8fL(=jX{y?kF8|*^5P`dMHY6_4!|{+2AXa zPp(p0K8+PWW;-!6)flNNpzld*TvlHOC_VR&7jaaZL~wBQ<H^Kk$&`+QJ?`IvC}R5c zbh{-5j~(VKdlp;+w&Y7`@2W^aPOr<2R`7S<CvOqF!UyViJo^B}5=es53fk`TCwk$i zo=>tfefqlC$xrzcW5_%6{`&d*GgsUJH2|Kj%tpDeEL;d&Avs{=6&~?Q<O&d0K2!~@ z4XJZArV6p#mVUfdvUg1b+En9QiLpAkv`;(J>6-gM^0F%z_Z=C!Ob>kout9h?&n_dD z{&?awb}rC$Y)^;MDAr=VH7C+`{Xw#c6Tm)ww{`BDWEw<pUlagj_3h!pQZ+dCr>Jp! z@k{xws8MQtU}%YQ6Yp2NR-x8$52{$#w$1bePi)ws^mFEAS6-~sgL<xR*B_&%5dHR7 zFOircE?i!%LU@d?*#Hz@HpQlDP_HB|B+H{APNJ{nxQ0#dY+|%;kfWoSY;Yo>rJtrC zyD=y+!V_7DWRRS5cMD22mUqXUar&CbZ6t$OfKK-G^B%06>?x8`87&xGg3=*)>jygf zaEn%}ndz_K8LR3kjd=C6JrmC&-l#o#|7+^Sx(d2b|DvEZ#c1#1V^}rv==-3cqn($z z^~q8KUJQR4OaDD?vF<{vA2RQyd$PSR^P;y<k&ZNf@efN>uDx)4F;TB9cc~>c#H=h- zY_>}ok1;1fY#Cyo)fw%0kYWPJ)7>~qTL}ZP$gyo76t`z5=+zRF<I|{9cX{FG;CrgQ zPe<<fYgq!`BF(*boNZY8m)g`XmVZ36kE$lwf~e^<Wuopl5rfFbDP!(g^K6rG9>_kE zA7nYe*Rb<AY)S-N$cZw%iH7yp#jGB#766{iy@zIfZZN2WY)eUKEi18wweTCE6@e~( zVxIpoxC3xmb@pX2<qg{twq?jqo3%NtW}7<73+}^S@5r1=bG0Y4Te<$)B;}mWb4jFe zYP#<md<s?;yKrzp4&B2=($~3+)=fWZCeia=boEKL`*xy)ndb#~G+hh{u!Y8Uz>U9r z*OSO?LfMb4Dmas0kxc6#mZKl7`-r(=FTz?1a&cC+Khz!N><`JZ>T_{yPNcglKM}J_ zZ0u3deH`Wn#cAEG)ahYJgZAm4&yyHYLP$1eYq}A0pD5rW8FcT!JNlw@h^sFmHs(=+ z@2Xa6RMU2D?+CzA<6`fi@Ycg7mp@7>SbGWXxJYf#Xi~}5S3J)=@Exn&__o3)hLAud z%XwE6;u+M=*+bUV+ch3?Z&@6UHSy_~>Fn#va&aw_Rs?}L8QlT7u#=^W>j4t*R=*m2 zJoI%o6(zsy6sJ6L#qGJcX4~xjgqMn)u4ZyigM<728Uu4uVAwOLh=TQC8;_$tgdTf% z6KSHp_+jb2aUn55QC)>#4Z}`YHea>fMLgLXl4NeYv-jZ`Ba6~1FF4V6*Y}UlfUkiR zN>mi^lM*nnpQm6AfqWzE0-AyHCWLratEj;4J37O(1z@_Lwnvb^iC2$W%63tvVVm|m zo>GO|D{;4F%92pZ2}ymu27Tau{T~p^VT@5LuAXUl8ro%+rhpzV{vBOAk0`Db6`^I) z9R;5*GfPT(CQQYB$SPgbwJV(>8<~*Z#<r1zr%5XsD|$BG->ylDhrz(o0Te*2NO{9- zXG>*-mwjD6;eXN$G)P%<ZaC9r`LnC{=Q2<=;AMLkp+WrTmAdGyFa28Zek|b-OO})+ z`^EG4YDBg{sH0uGMpf}L|MB3c=j(JtqX=WEzbx|(qo;kz#Vv3_l{J8;*ssYpNJaw# z<Y4p-JSI-RkZPnCQj4s94{J*LPUOPL!wod2vJ89CA)GJ+fwOe~Ht#-bviqRM<0JCU z6s=5wAR{<hOWU&=J)7P`W>K_C;hhs*?DkR1|BPSA%Zy~bdLb^Bc6GiY+1epYBq1=~ z7`k)U^C#});$V;vLKY0V)asy1@2G1Alj$R)de&g-N-P}-l(2D<t9!;&hX);Em)sKv z$ai5TGcY>&A+ZG?{$>Vmhs1fkIS9v?T|bX^yEyW%cjS!<QP)*E5hl}sfYGY~_gqt! zO|fYKanOfT>U$3TV;Ch!<c@DQYnV9dA~SER@iK%p1PjbUsTNsJOg&Z}BT7J3&}~8R zcGpSX_s(3nQ}5PzFz3eX*T5+-=RAepJM$Sj<Ai4Yi4%b5^!h$E2oe&&LTHFXvvduT z3y<P{N7oVga5?<=iG6D_z9DNzl2OfM;J_iHcDG3FP*^N_T+B#Hv!_%&-s#yDP~Okk zA*a9Tok*)ZlKBwZ5ZfJG1E5?C_0}SS9!4Sc&=PeO2LJ+>`1-GQeS)I*TOM0YpG_aP zpRXmKcF`6?a#OifPV(XhBeUyV7~cuvodVC`&lW+LxxzzwTI62)5(4FB{O~*dab5(~ z`&!w$r;Fo^9f#>Xc9>F7=F%qLA074#3`CfYt$L@kb%9)wx~M%3MOz92kz>4U&pr}W zu6hrG$sfh>bldNexoM#qRw_|uiSW<A_VOmOK?+phkban9@QyNLd#CTMm#EW|KGk>( z`UA6kHzbi373X|KM95T%9ehnfZVHI#Mj7aq!(^F_GV#!by#nJ{D=ZvBWzGzt+`BsO z@90|^Cqrf1rlZyq3r}tUlWMwPKTuA0h?3iqsF{UYdLhak5~<MO&HNX7M_5n=8v+7+ zoM$UdB33{&xC5JiU}ew3eS{xa5?CT3e|r(A{#P)^i{hP74KjN*(MA-0{z15CFXLSl z>X6y^9K@<cf``z#41eDgYpoV<->$%sz)v?#GjHM=`KY)k<!RINGO+e0QIbhWc7-9F zz9>J8D=_!Tfgzcoo)bN4*QN&zf?Y6Rz9lvCHxTGm@G9IYz%X&dlW(6RC~d)Q*7_tg zT;-`--tz=c;?%TDm{!d#ogvdWb_KZ^op6MG7&ouphl8s_=R{X!_!O^Q3DW<Gn)7=4 z_5o6?F`IcV6)sw=*DSu-VZs!z-9x}dMT4mM&3zcx*2dJlt|FdcD>{Y9iIfNm!EZa0 z4-d=k`879%oDBS^##7{`LTeDGoXocJC40K(Hn|I5Tp8|>OC$??!Lif%)A?m2*T7lR z*?q~)gQ<S6a$G-VlV58J={;_}7$(c*ROXk-tx&aFAGet{?3e2jXrcC|)-U7j%}}nk zX`^?>yPa-GZ?i!$gV<CqO^#E;u%2QpWfp5ID<D=5?3ZPQ+-qqVcU$1uJs>hLeIMIT z`gdI29@ytizN6IhKz5>&>U^^;L<AS}9&{GO+}y;Y2(8);$rPCfxld+Oe<~3d-XxqO zO@=&fk30GyQ=&i<KuwW^A28%k$Q^1@OmCST67t?Z_t6F2y(P8blsld|&pKVksJN_b z+QS~|9Y(oyAQG9TvvtZ>C=Ys<T3H_CT;OmbxF&|YxO@qf!f)?%`Ksw-FdP_|bHZK5 z#F<}OD@)~H5-wzcV-mUTs6li;%7Tq^Qk3m_&)1WLz#$Q!4)dsbq3bkNkZybXZ9(`O zQTu?!Z{CN4vTu5E-GGz1kTOszP!{&BPi)0^@GA%w&T@^jK3ME={v-sl0{zrlp`Ib( zUMUBt%k9D~XG0#ldTLR}Sog9jR39;qV||7p@>=-MDow>)+D#|F$&y2#xduZDFuae1 z+s8QTHp_PV+WbE|M?2G|k-!^=rNj<sRd_@%U7G4-s6s|q;JAm8d(gd+oQDUdO1r&Q z<R!@uo~@`-)ZL(QeEjh`GcMZjf!G?I)+549HAo3NI9fZ9^qg-E-OGei9kcZ-5@epz zi5~1LmcWSbj47AC6-=n6C01eDSn|B@{+kXtXPcA(qJ3XgvziemuX_8%p~Slfzhs%4 z9v@xjPZCUADru0>{a(Hxql(^A`&0}DM|}ICup%M6_~K>FX>?U}FSjhZy{8Pig4l<j z*hWV&Q7CxZgI(YzCk7Y{=#s(F*u_ML9a&(KE@)J85_^8cIXV`-7S;h0BHQCc+-a{P z@A`fLt%k_j^q%%Q6;$E7CSe&Fn%i--v?UYY{>-yU1n4m90pPP|jPlj%;sNBTd0*ju zSVjMe-^v29K4pqgpFNVwA1L!w1ao#3I2+p;fH5<_DlfmDQs<>}=8Xpvt*pm@^ZZLt zE-%94UOi$iZn!+Pql9>^<B#1-E-}@Dm<;b3hV9(*ROL)?IQXct0|3$4#*!cV@^yT1 zjH5gDIF^G5^a0Z}1Ycb`LGD`<xen6_ee+O}nHTOs#;<9mF31owY2v~YdmpfxI{Z}; zbKSLp+v_Uk%umX+cm499y4MZ<<>RO_+}J{?zC+03l@-kH$UxbUsP9@CS68nkn_Iod z1LXKiKXUXNyvUcv>;s7R!T>{s;7hOn#MqScj1|D8PdUN!IH0<+&9T_#1#(8V=;30o z;d88plS{AV?uy>KVI^~Lg=IaPK{QbRAb3n0R>c8M#Cf}%5nPjqe^k1Xk>wh&`Xdd% zgVo?a8XY^%{$bnuj8s3;x7@usDJ&#r1#Y~Yq4=QxF3mv*YPq|yw~gN3x5EQs@v8;5 ztL^!LCtvTKkBK<2Wr=4!^&=Td$i8jJ2aYUhIF>bcR1t+0i!-O{K|QgN;`U2(q$Q+% z?YcLnk*jGRmz}k|egDtAJ4__Zz4dF&a2yyKevDu$N*43LF1Bj8Ko3UYz?z_Be4|Iq z)64EAG6D}oToiQb#>_Z!?z;Cu^+}K!-^8@Lgj{PhEjfJdDI5z#>~Z1EDE#s$?z?TJ zy6UUdQ~x%TvVZ38JNr_;F|K?1epcICrpN%1b;R0BYaSBP1v2F%p0?kU!yeWzu8S#Q zcuOtE>ikgy6h=!F$08gLwR^gbRr!wJMK}{^htsSmia|MJIrplb7X6?tI<YAgM(O-` zm;<C+>T3Rgw^;g}I|4gNi*aBwx-;rL>${O|DtSN9K2m#LLq%VP?ztiwJVssgAfnTP za4e(tcz3e)6ql73zYcCGwLAL>A+y9Z->kf#u&i@7`8DU>s3`|vP(Pp8xh+6`2Cc~G zA|=D`1R)>Poo^rL#o7G^kXhBPKB@0FCNW!`g<1JLJ!bDvapC<Tu0eYG?DfcPOOVY7 zBLzLK0M_n$Nt@=gQ~AS}o=EHMmsVyewn2LrOH)i~i}1;1zmL#jq$TrTJ9`+=FwKhL zo+-|as#&u=0uCf}9oEvfq<W|KYkItUYg^>FJf7&UJ+4eXB&6`SmrsIZKjY|TcMy)~ z4zLJ!S&+Px?=QfCJ}(QqWkL}zR2Pk3wfm~|=~JSkp?fRq5)|>~Jh&5eo%l=R$ce~W zj*NK6y+{;8T@O|<i)9uT!%^W{!_|c~+g=W?0;1fi5|<JNd5pL!^IrcE{kAWLp&ufH z%6qdEGn#TxTZ_eTrlmpTSQ4CCSd0{EZ+xa{DyFjD?;p$X6H~WoA>x9n#+niU_CnjE zUB{Wica_@C2tI~mTUP>T#AgL64Gpb&Srv1Q{@g?dJvF9Twwv=333{J@ms^Q*v?v4c z2%rETi=ink1T%FZs4bKUPTG>!mmJ;%W!9SLP25cnFtKl@>^{qn1HMt?N>V)B_Y&I} zW-mwHYebWVSog&;>GSt|ekQMNSt_lCg@;0JYGlT|p^G3&g_qiwT(M1m9zLe2_a<w( zdpXtN#6M@%bN*iW*P&wXObim8o<&t<(P<XN#0rn;UFhGVZ(vPBv`Z#<D{FG}YmyOZ z-#7k1>Abx0*UP068^T8WoPJ_4?O<w^X~djRTSXxUP$H+BZpmloPRM)~Ak>_6{zBH} z9mMR@eYQcT{*u*v)?3jrV(SFV1k``#(z>DQd}EHIx-E~<zc;uhsFjQ%0zZI)fL<QI z#jHPN0FJw#02b&p{@9T5Og8-6go1DEe#~QL`=0F>651z53<b84Vq~^y^V*JH;Z)Ng zScUYgq*Q+2_YWKEuK3KQU8KK-iymw?!$Uyg<N8NB6ii05ohPk<-YQh?Z1pDRP$M+6 zWl_S>fd@dyj6WJbi=$@G`aop^nW1Y}?<;Q+z?ug#6lV>1_5Eq~jvnK(2Q{oJWp8M= z@NLygXkR>VGL+KF(Ew5}P1Bh@p(izFmgB%7X$Iij5$l7jzOkY%_sCR2SHh?tZWv2Z zWHhdTIaVdpzj5rzEatux<t*am$AM{CqhKt1xC2<;0kda{?x;d6Cjbj4bY}P)fP}w2 zvA*xQtYZhh!JR_z0d0<SLeh*b8)c2(0$oMAsrIj7R&*Gges{%I3o-7vA|2|8Sv*3I z!I;;131-RJF_Q#cRQ)}5olewPYd7{8%M<(o|BELCOz)KgHi^lfExZgAU+&ISXbKDI z$*P!<_vJa0u#tRW6rN&@JXtQg0$Y!?-FYYxd16Y5P&YWrM%sheRlCGW?2n-LVPok# zTOJKc?eb|zuo&q+n8i%TWq^k7%x=q$63Hfv?p+*@&Qs2K*rYZ@dG;u_WAF`ankSb! zX%>a*;GSEr(@EronET3Y>o=;7d)TinUwqCWq&{SQ?I!L<fRB%v%|d}e>!Bw7<poi` zAD^@YrumS>CruCqp-`-kn&f9%KgQ$aE2R;`>8|>nspEaU^(PSPzNGPTv;HrT(HX6A zUUKa{jYkrpY?ury$~?ymL1o!mX|T_j49ACUI`~QC^*S!=A{U20KT}j}JoO`-`er@N z3zb@<!ieI=Hmb)O`_z#aqBAEoO@f)-moC-dg;f%DOmy~3%*=m3itKG2i2x1riB&qB z`*|m;T<~%UnMCLVv-Un=#!h^J*)`ND+bES207)>9h*J_`vAk35vH1KO!D%Mmc<;pE z4z?!>cYNtLi1ap{0cN-l0T+f$<3Ij|5f9T%N+nYBqqzSqhz>eE<=NwAV1Ljg!1EZ8 z<SLnpvx<rKa#6p&5|a>`KVc&D+bX9g!07xG{v1miX|6zc`%Y6re?b^E*dGh82=v5w zzs5m=dEl{dNGlGFgx{=|ZQG+v9RX3``j6s8Fp{2Gx=7p(|2G!KT`)CEF+j2|Q8gwS zEZd8uM+vrqLY?s0qrGWg4oI}xIAkvDbx`3!7I#Ro{9@5%$LL9GJmFz8(H%~|YHEK$ z)&M>y{JFQG@3+D?Lg*s%GN4A@qMTeK_ZCbk#7Qm4izebBRwV!zK;SU5QW~F<p~`@0 zj)I&)w#YrC%}$}RJqLY+pl9AoCvK8fil#b}oPA>XYF)vPFuCb7vc^Su_X(rn9SbZr znrTfzOqmP>;?yrafQ@lbFy>dFyX$%5?&f&NoAMDTPcKM*1cxUak0*}1T!#8-4atb3 zU+m@4wvK%-|1cucBKRDS5HU(W{rU3ZOtwB!k6IJo!WKw`ggLT{R2aTAhwh`Lqc&%! zyKb5uPt4kvD$kX^q^Gzr>Sf)g)V7>y^}lZ?Ar%Xvg-b(MDKl8GGFNv?`-8;@en<m` zUjtmq)|WP7;Iy7ZuO>``L5vgKxSe%Cju3jvdgfa)$ZIuTq$7h*GB=QbnQi(|dk@jw zB+2@%<l&BT`-=)o5Yc$Df2EYVWdQW6h?&0M9g;GLxN0X6MRLF<#e%rXedR-&Yv<<k z_jMAy=a!htMPM+4aZK=wOkAz13p`RTYUpI*n@a0Zx`&?8ucEt$SS%CY9A?HjK8NVV z;eUx9gQ*93jwSmuy_O<z)6R}f50K(Cv8Rr|r;RXa0b07K4j=PNbe-fzn?50e?0^@k zR<zgazj^@OQ$EcZ))gVCuV+j&MVLjWk&*}By;6hvJ3kXJ1=D5|3PCl$?%pnV#l+lw z^yvY8twVIVfU*C`Q#gXYuNF|yDU9{Fhd|4INgxD-z4?j%ME%D)_~)Wf+y^-*sR-;> zjr7nsJf`oUgb|HC=~NB(C-w92XB)&4r8@a7c}u)ef_he$1!(W$?{3!_1U7sI%8%WZ z!Xh!ga|&sQvC2FONSM@f-+C0FFLyW?Z`N6lMdeX4&2}0T&>0h)NfmM*O15D>R$@4; zF$vbH+5gSDL|tlZoyz<?lKXiM&%HhrQD}w$lqe;r{N6Z*9wS#X`J*A_eN?wqspV~r z6S(^}8LJfi=hGj-KjOY2_L&o)m=2LC;3`_C{a{F2A2=Uc<?u7eb<v|8yoP9bGVpfx zxANv~Z5wgq>kMxW<J|xgJ(~H|GzFnjY(jVchXNtr`^$u7AyG#;rRLhj>)J<W*Xi`3 zm*P*l!a%~DY0fO*L@@@aCQAp$$TK-B;JSWGv-;NoE*Ir`R-F6D$H)g%LYilg0*_(1 z8^;LLHy-r%)qFZ6$vh{CmUQsqct(G1q)uAcuw7UM&91#0@F)flD{w}c(AimLnu4Q) z@5f3)CQ&rGrMl0eGp&IxS|1R9=EH`c%(D#>QcW0{Mat_}=Cbby8?l?%WBwWFPt>xI zU!^wunJ(eaI<Ggz<<!>|kVnD&PO8)I1fbp$>g65=KG<IjzcZie{JJ(X=IXB-UwET& zptzV!oET<@JTY1!^Uo_qx|x$Vwa41pIh^%}I$s2k7X&*bR(emyUtB1QKJERn-uTOU zV$E*vy<<ck)n}^Q*!P`h$}_YoN@kI_QufC`vbcL@Z(hKb0d+@34^MX%xarwa)CH_7 z7#8Zo^<s-TGt$lumFBVE1*>+<-JD9~DUB;*(nZ1TDJBv!Q2~;ufEOrZS(LVr`gD70 zS%)?X?!*$u$>PqcaS^{|EQuabNQ!=ulo#%l9lp(L3*$*5Gm>x?`T8_1HE|z33d61} z;g8GYrfip~Z|@R0-3FLdu>OHC(Q=aaDD6<~$e2r>8safiTAucD0Jom47@w_J764i8 zxYr(sJtcM3T=$W)tcQdJ3+q!#O{0Jv!(v&2w%cNiY(^TG1#&HZq48&v+xpSpYKmG> z%u!qqvg*;DCZyyUixP<iuw3k+kk;*eN^-z9Yhc(vU~)My>|7X~e(q*IN$r4t_=pN) z;m~z=gt2Sz(r3{*Vw8pVY68Cx9I}$a`x0m`^jS%YMV2$sWS?z>*dlUY5gMdBn<(Na z$vbAC%*c|7n>wD%#YK$E<BMzxbNtfvdmvQrJJoh+s?%!s<fIY1X&IM^+Ows+rLXcX z_w^_CDBtmJ1QhDvxmj!aC%p)-Ock+zs;F9U)JV$fIzC51u-*CfDbWTC)ouJ8U0kn6 z&kO~B_)+}vNpgtA$yId7@$isDUCk2Mxt=*<X>p-s1*FJ!SmYLd{a`Wb`6hN~9MxIz z+pfDUyOM^i<SzM$z?hMKq$#C~-_!ju8P+3N-y2PiKFS9hCFgZt7+0KXkM+@9BkwV= zhMx`8+f^>rz_Qu*X|WxYYbNZ9r9?t&)kuUC>U$@gO#KfPqB>KDD7#=ar?8Lfznsf! z%f4?j6r0(t(Iv3MjG_*QA{9(JD~F_O9O8Lc)zgk#nL9WsKG12w9iu2278MB9mQdNU z{V0>PQ;sE+&{V?Km#zXm$HfZvBO@_69ux9m8cs6Q0FCRo-vg3<TDjySri%~34@lgk zKd3S34t;f6>|JNE7^a+Z6j@Jj0-C+7k&zpd7*m}x^ouMkCegcpE>u3W<II4$5t<B9 z-91q@zhg4g>#4<*x;WHSzo{|PoSDQCk@-s(En5?J)22HCN=#3wSg~f?P_PrH_puA8 zA>saNW;YS~Y?h47HFU2><mkiGcfPfz#=f1PrJ?WW-idUa8Xo?*xbSvA_Fh8Im@jKU z=_akd3r9zmklhrWdQL26h7Nia?sSCQ=+72i9FEr+lQz7}JavN{m6g)Fz0yOoK!#(~ zm0ek6A))(a5vb1LBClezUjF_e2|dvc$-Q8=Ih4mhaC>1@nR@>RC1C>Fg1B#|Ft!>8 zg&=`i&Lw*7(fqyPBkHJcBkJbfx(%nWaEFXcq(HuUEG6pj<8!`lIzq^JASL0S=zyo5 zh2E%`(ee=jlhy2p2@@}JH*-8)`*}loCSG_sn0L&Otglzm%GU9GM)PkJ!j9^18l<-% zhnFfjo9wV^qUpG5mww<M<+y5_D0B<ig<zFS8m!u-Sk&h5@ea7y=s|Dn(mqyYwM*3K zqo!bCs{Pa1QBU&#=(0S9_<r==(?4(eoRq7^V%M$Y>yO+kb0ZGz@xBhR4o~vMNd|*p zLVKzxUL|Ac2?Kvinq1Bp;o97K<Mre0?R_NdjjJcP(<bK2_&3N`Bx0o|$qSX7t)_9j z{>EOMgKdBYf?AhzWGxme)LBe#|86IeAfWQbJKiHH!SnO}Z+l-Ot)i;3z?Cwj7w2R& zk-(4^ssNsn<rF(tqw^D*KuY(f57N&tGL-9dNaOyaxcasC2PWb7>Z32+KgSe4Tyk{n z!fsHD7h;%@3o6@(o2|{kUx_9h7i5YE9dW4jm7l&*g5+O9Ykzr1{HK@ukJH^iO(vZ| zf{e{b4C=&V__;qF;a<nCe#MQs^eU-?bhwkMr3Ss^ac>F1Wa?)Z!OtrJu`-Z2S<Pg& zKlAFXpL{;x{ZB99hU3JCATfhr^|1tGr@KEJF(?RSKAFUo81KYf8uQXp=Ub*k+%TvA zevT17shQvYqYM}4c?omBA&cG{oWXy+-B$zTAg?0OZn^idq)j+Y0%AQqAAz;B$~VCo z%RYUf+^LPga{4_Vq1YgU8*PAx;&y@X{>$V4*Hiu-3#3PiCu1&6u5DX;)AgP;@A4fb zQbRHY-Bx&+uM)6P3(Cs8MMuN5FZ$l^$5KNe(12=}QPtz}zx_eJ;tGCc+^p{MN}n^4 z%LdObro9CpPI>0?Z4gPa`th8}-rM^#e<hQBDVv&Ts$<>4H+-1ZDK9LuCm^x*+4TPn zQvTmh7JrKQmJn7NCv3e(i7j!mExeZR>8!wu>q&hk8Hr8}fE$+|7t*PpHh-1PO+r?= zt_w~b*0f@pJT1}v__xoM#e7Qy8~3*(Hd8?-3uQZBeTIW!*eDt!5DMY%UU6kiS1(YY z|79aRb4W4SI_C5xF9nwJJzL1zW^IIU^A^+pjjjHl&z8S__zzjYvR<K+6nE<5;A3W^ zhc${S>ks5rVN!dS%`_cZNdmo;u%DmO7azzoD-yvN#*l)4J8yIt-?33_SoNgZHM|lh ze?;qYlY*y(85esyCIL<i=F)Eo6;nLaS`OJyT0u%ln`M6>N?!f@?+kAw#jK@g&PAE2 zM4}|@D9I~iznFB+@;NS%Kqh4OD-~7xuqA57<6Xm!U%6`kS<Rbr&2@G$_>zA3_U~=% z5yliFb1s>r$_JuqY?Q`8?M>n6zlO}W2%k%0{L%BGzaM~p{8a*paf2(T%cujEEs1e6 zd!x30hPMBD*1rwipiDO1)6XsqSmXmu`M>8M3Kd5wiu&7?=`&KM|BX4Xl4B~WpdS{E zeE3@fA_r9{t3-y*>$<79g*lUhv|Imn6~}`dlG9V%6p458%jAh*?6!`9fAbAo7*^B+ z3YbfS<~hAp@)tQttP$&iuNgUbU6cG*v%E6*sqz&6|E6{fR3WQ^JpSlrIk0WMOmm!N zetOh>8$q5a*Lm*T+9~s8V>YuLAEutGs-Bb%CO1v^_Xc&ts17{v{YU^Se^Ad<+BS)4 z!pp4t_v_Y~U{ydu3oq6P54HXLqwC);mjLl75GrOoSWUuCQRTk;$_=mocP7Ju#1{=h z9UqXv&Nks=z*cCY?q_H3x46j5OhKPpXK(O#@8W8s9T1g(ypQ7Rj&71riDdO#M8x|q z_PByn5!HMWkTwoFyuUNm!w0@q*r*Qwbov)c^1#?Fy`P3CFfzN}Luixz+w%T5-SQtc z8Lc*nxnyJnWe%OEz%-F5*1t@{mgl7V+fi}*Bo3?{H)3ldm`LFC)_*+h--Ge5DU(>^ zH^5{x#C#GVv)*BgqeO)13#g@~8@}9Gf+t|}P!Q?nev8V_`SKy7y!+l?Kb2A7I`tqh zGw<00oCfNUPsgnSEmdY^GPh{M73f2-W01)oO9Fj}vE`I$X}etqz<EVGY-P)#1h<z{ z`MHjMslVAUdROsN;D#qN{_m5m{OsO+c{RziL`}^To<g5thmtU84zExWy?+%$C!1rQ zn_5Mi!zV`6E`KaUgKuEPEMYo2`e{9d{IBEM*a5hZ=cG6@WWI8^zOfGo2-MvEytKRX zrSswA_Qb9W;I=7MV9db(a4wiC2T<{|>$)y|Hm_NVFO-?9$xBas_feAsfB2^&Z$wuY zi|L4n%Kx2*_D8;y1h5FNaY_2CV_RZtca_KusUP(OtJoOPG}o;_{qRp(nM4PP9)0}z z5K~GeRt%7~n**V&{0@K_!&i+~>uCaHqREf-J@%L-E9FohZ$XnnK4p0T7{;GKhc?lq za8%2`^K$>3+CvJAEh50IV@%0}o_*FvaBm#Nu=KiyV55-98GD&Ycpo^bKyelpwDlX~ zQr&-&!ZhmNQ;rGr=-Aj^0U~<AUcR4-K&NP>g5{FWxCv3@7!zd=S+1K(=OpNRK^_9> z8eOlGCG+xL0fp-xTSF=K3#;rI|6~F5ku5F(qRO}R!bf^Z-8?VZcH%c<vC=KsM&VHe z_^jXUck6)mGebZ+fF$6khqoVWaT^RtR@=y{yf^wUJN(xPmcs_@qDoo^Q+5>|TyfM? z4nPDW`i*5}VZywbx)E#>!>0`N+jOrz98$RMeVKOM@+mJ_v$KfHl;@Og^SYgRE<?N~ zEg(;|U-P+x`$Cq&@zocv)3u))#SL(Plt-0yU2I|wjHq&gu9H?clI&}4&8t+01e=#3 zuC2I7g)_dj5e1x9N1n2njeCG>PoCVWLiH37O%m;xU0q%*924yiHDprk?f*4Oxjr{k z(COfzLH{9b1XIJ^S4{GUY--O>76tc1y`>lo4*{8+AcfbTxivGfGc6$?;R)z>w}|f; zctK@71ryw;E`jl7tlIGcdH{nEua)|*Tc<sFW@GRcNRetkY1R>-yBugaXR*#tk7AYI ze?ZR1@jV~gT$}1)jq)#^27{ydFwS-%O#|P%LqM0XWYa{$AZn&Svowc~*?-v_edX|d zKN7*zSK^ptm+k<Exj(-I1iR0Li7||irHf$d=}uNnVf!5n+VJZ%K?QIPk}HB9qq}Z9 z^l02<KGT{}Vk0f(cyX(GCX$-@=SxA|6ybb5X+@gRqy+GhPBg3^dZ3s>SG(JcqtJ^< zmvlsaOEpv%(=7?e;x}_xvSat4G-vpveNOIj_R;GCM9`ntP(C;ek?EzJ{CxTO|6N=; z2AFQ4=}@8GigAtn89rBcn}&QI+oUc9rwp{wB-g8)pRJL%sD9Ei{kU#{+f4MJjzr5i z#-Wu!wiW-}P-M<*A5hIH6n-m{mx`c-y4cKn2s89YMX%PKUnA-9l@LsrEpsUneVGA` z?tt)kXyB{lLh3j`^lu3<wSPVdOcXmHi@v)CB%GD6OM8UQHp`h<Gm;kW0C(2EE5_c1 z1qN>eL`iJ|i{AEM&LPTgzeuYY@jv4p{T2i0=9re<0XcGN#XVz-zlI$PxBusGntmDe za6+UPx(Mfcc{%$DfBJ+IDDIXK7}CL_;txvi3BFp1av*|v3fp_^exh!a40hKQ*&<7& z_f)}q!pEFy+fF8tXbCLSHJ~^5%hyzbZB(M2!<7AHKw^>W0_eaP!QSZ-^BMiP*X<}? z^jDPS;N!Oh_bkIimlKVK8W9&xz*eV_cG6=eG$t-Qktgz*H4b-9a(XlrIh=NyVF^?q zy%3ysF{%X$IDP`kfp4rU3)r`T8a4p6J#Eu3dS>Yc++Y>JwZy(X!XUYrCuvwMiKjmV z@b1}LRg)Z3fD+%loy<%TP=+Y@ohJi1AO;>iyYHMr3wm-Ek+;N|(md>H0da<(i>`V0 z=OF;E9s_(>WOM@9>ZnLA_#hG#PRdPtT@y6tDs0>tO<fTPc~)i`ZYbMxZv20Iu0~j( zcr^&66*L_;HlLcGK1iR1joPbyi;5bH)oBF5^LH$@&Fk8qyY=z*LkSjr+2P8fC&oY@ zW+d^XNb*{=ZnUYkRpsmJULwtpp%;&J9R@%3ydSBmMwR&Dc^27`e{l5%er(RQ$RFd2 z2Ox!d;D<eQck_q5-z~xq6Xv-Qw&`)N64ux!g@4jnGTc!`0E3phl%Ov<*ELFhz&_O{ zEbCL*`h?(XKs9}UAUrzj`n;+7Z4FGpoK`4w=l^5tt)rsc+PGl}1ymS90jZ%wIs}I9 z7Nk2AkOoPImXMHckd%~?4rvf!00BX|k?!vL_MCUU-@Dd1&)=-2F!$VhU)L`oTQW8w z_XLrVouI<Lz&{sR>oN>ZjmZJQ-JB^<E6+GqZ_C`R?bahI0E|h-SgBMenc$qGWQr*) z8>~#<6QmZ?*n7!4NsF+OGgkY~+j|wsdh_qk32da-$cYQ~lAaD0z|}<i@|AM*(`<-t zj8m_oe`#aT7xj$<ZKF`uBJkha<FclG>C*M2=Atb~W2~9K9IG1!yeU!O<d<NI&qzlP z&tB7!7Ib0hP3q+a%N;oEh|F+lAGr-@A_x|xaV8bw&C{prj|Kz_GH;Iyo?a*j_7sao zG<M3F$8Llf+zb(!x`T_*f2N~q2k=Xn!}aW!H3MUq91tMSYo*rXQ*CgUMRsP>3q>aB zSr<~a);y?@NtT@wrw6If^U6sEPV$@ct-jR1arQ9fD@#3hZ%F3!F+H2au<EPVGCaFH z1DaPn+m6a#|ByKSNMs~OYG3~v-D~LT1(ofdH_xROjgGi7z;%Z=fHu^k0r){sReC>W z9=6nUPW|_tC15}mre>5S6nAR+>3OZhLW=?|H@^jiocB3Hw8;a5g=#(C#2gQw#>i60 zBRiuz!uCN8hWusg-Bs(S?c%K<VzWl(ad2~f9uU2|t_FCkD<$TZ-R0kBSMs<rXY;<k zmmp>QsZkKMOhugM>vK@4$h!khb@9s`FbQk`8%W6}WvmpTf$ONIcoRM=X*%sC2{a?@ zGeHElEz<hXndm8})pV5B1x5XZMnq8(9XA8@+^*OFbBIp~QRy>XTGS{DGpe5u{)G?w zdQZfE3MxJyH+T{rEPCzpu7xEd9=KTEH?eOLPFKjAzO_Yvs|QN^2s-Ia{o?bC_7bK9 zprj~xG1t50K9tX44+4D8@q$e2oI?Mzo|u4%Ee%saIn`?v?2C1y9l<PEmG`J4cm6<q z&R=@~J({U!;ikmbRNwOtW5I{u%KePFy#IaBo2?n7&ZoyZB5gLfPotl~14}EqNXR|9 zw2sGmQgI}j&&4=0b0P(v<Kd+&(9pdl$=voc>-a-3jrqWz&)kY(8E-BJ=$Wmhe!UIL z#~f7qM%2HTRYY4qp)3T>?ru16Wh5R0DN#*8DLKjI7dv#FM|zOY>KXDLiCl8_1KQ?| z+{+yL-`PQtWVC5%Ij_`qAvWxi@&xlM8WZRl@!`Ay(?%KQ+Y{qjroBRT^G&ye%AL6! zq<~owB;4D42Gqu1Vc9a5q#JpLr8P2X_dWlgzyOhLy=F(<CeRj_>Wlf8kL*|K;%vS^ z*#DS;AE8gtFwPH(JDpC_^mCcLL+@d#gSRGP^}--jpUx6tpWfrdE-}t|S8|+xSn)^q zdrZauu$}i7IEQ54MN}F=8<%Ol?>V!R&*T))(rE+*LugmdTF#m=W2uBklF%P4Gg_!i zyxC38!6kT-o4`Qqty&;bPlOWe!{!pUpqjbKP7--RqnjX4IP3<9_b{<1xbU=4U57G@ zsRbC)<(dZ^pRj?MKpsZn&(Vwi@L4dYnuep}sKv4gpGo7`n;ZfUE>{!7q|C4HA3L19 zCVmqwkw67f1ox@N^_EgR=g0@50z2su*cQw_7k$Q&+_b*uKcM-1^IqIz5Vwb>$K}GQ zXK3W`3a4s6m)Nj2w(ek-T&|3txk%}@6)@tmN_WUS&BE9-k5tMcH=_sakTkLhAb6an zVa)Ko;R`F~Zl5{bCOTi><&)O1y6oVF10oBPeBvP?{7KR>jZ?M7%@VBVGN2rpX`W-S zRlzEmFGlt5zT_}?YoFbPR08Q^e(UuLJNa0+S-x0^klBBx5*PGCS&KfNO3tEoUz&OE z0#28L9TIj{!K?%879%6K+pglih!$U$jSEr-12=io5m~7DWK2YiuD(6jDnv!O*-z}Y z&F<Zb^DmMMvPK!4g<+&eH-{xoC+1JoGUJlkvoqL)v?-tgBa|3<EBQ1KZ`If{3JX{W zXd=kAb7DdhWp3d(<Rf2_q=e59yP#en;#zzbkt<K*8KTKWrE^8o$hb<O4=lSEG9po> zF<99+wY|J2y6T!IG>y4}o>IJAs`$Jsb{h%l)v}4Sx+}+bp(<X~Q_EG{-LZIVDJ9q` z;JhyDU<<rjkLps6#D*~{A7|EuXqj&0d}Cm)DWOvfwV<CQNeO%;L}c);y$kdf%^=!i z-|Up{9^EnUIK`hm#3&^{RC>e5rAo||l4iT?EY5thnPbhr8ss*)#dX;?_vzr<h&eo8 zcpOy!j3QK<m&n&<^(@j|NmAq-SjyW_zXZI<2tC&c?my;Xj<Z8r=p@;fmS<P~iVz%e z`gEOM4EnajU=86U_we>Qzsj@>Hhk_dR?sIRBW8oyREc42(l5{mj(=3iQQw)4_x~M) znI54u8SCZ8W|75W^%8M&UMSEr8h;Xsi@%sdH&;COsFCP25h372#31Ki5nHD5?ov6- z4C!Cd$i{#O<hCJqU*r=Ne`TGH>Hb1{1mN)b4z+fB$EYNO&|g>lmUyJ;QK$i(`7;PC zp2QxM{FLwI5b;i`{HqYV%I-Hb7`ax<b`e7uogtWCnszE;a;UTgqQ~J1!Y7_x5c&(D z9&4|OPU0#H9n+v^Z!u91fs1+1B-LdtWa;SvH~1AW9E)0>g)NtRPnsuTmr!bT%c{-e z{tQPBTaVSWPa`0t^eZBpHh43KDMh0Vvp|01|1OCvkd)uq9MVnfamrsZcJKZ=Kgg1Q zt|pk-IECn@;&EC?mJz9|VKM;sp;}YbdjE7$@%t(^7D38aF)Op@;NUYpQJKHM{P_F+ z>mKJu`Bo_64^Hzn;cpcYV^@~pW;XU|%gn(qC3DkwG%~N2NA9C`s9abVmlAGqWXhAU zwom_8$-qHJW8&|G|M{kAr<xP2Z^0Pj<=a?H{{CqYV<)zlxOi{y8kZuTAn@eGnothf z0@FSq^vx4ApBsV}a}9X>O6gL9h`7dSQeB3Or(7g(d9#?A2Q2qpk7^rZqXyqnx*ncR zbph$aEJD9P5>opMT)RV3ON`Tejj}k|PrSor%@}wW@q#R9DPDu7DQ`IImmFpEEK^YW z^O)4~2xJOqO40Kt)*1j*fQs+kLfgZ#w{9nIpYhs)Q9+!3rHzC<gf@n}d2)XFYZwf@ z_={xlgV+6f0pWpZ^c&ti?Xg8QaHN0c`xuXaoRFjzlI9iH$_Wdr;WKIb5M6lJqhC~f zW(O2kMcUm}W6#{@Bq#*jwfB?Rwm{Wx>&I_Pk%Da7mPIA<U%IF|PLTE2FFwv*OWqIl zq19ehV-R$z-upDuNzt3$AS1?KF?TNebnK-Fb&j5I(Vku$-Ty@k{@>0W2SviIH9xPO z*1AszRH|r8U9|V!AQyFLO)#00ob<zZt~}0Y#^^ZeEd_QaL@*ha076hM+AH6HC*hli za$c{cBJke_bP$SE9yC1Zq4|#c{C3&-tb=gdZzi7Xd)G(p<Pf}3qUU;Z)P3-S4`xDe zm&Bbu&-nF}v@K9ZSls3RK5dhZ8P=6Nc>7pa==Y_-5WD_<D{#G|qa>nTpo<(cH(gBy z$s4w=;&VBrm?wsQH%(v8lH{y*vag%AZ~RpK!zMw)IO<~NC*`qjH=II}qN;YXcKUh3 z+$Y%I_rWKcwe5tLOU*0I*-<v%zSA$8V=R5JT!Avnkr)>ij0y|HpUYw)<eQwfy1C<> zVu_T6oS&ecI<8b%H<||=zqE4q&Ip1)jmWv%M7>6~3V6JPjQ)N8ha<tZRsAO4)WNJ@ z`XgQs%*#p`MYN>l)+q)>h3><k-*)fo?8Vm}R{Kj$P-Q-462{e^k&H(y?So>!vf}mQ zlv5byOX=11CV^gky4qaHdJ~AzYlZ4XGP$l((4fHhDHV@4)*)dnq~l8}r{k?zV`$5M zM<?&p-{!IBRH<kqffjG&{oQzXwHl^aea{zz16<4-1*GtKe?wtO>f@Ln)Nx!iN?XZF zn>!#Zt^jJ%8x{D__GF;Rp@|RoqQqG4U9EGKYbrWSS)xU^x7|g8-3FO1Z~0ui7AZu_ zfi551uGnh2ds^Sd?BU28Zm!+@XiPpCxJaFS36B~kWC28wz&4wI&bU(KD#aExh9Fna zZ18W^e}CJOf8l~PV{#^77~R~V>=E9>UaDtQER??))!nOns2;C@MUN79zs2+J=4=VA z-Zr3)7#&Rt&FpQXy!RkjvW60~pu^M8R8cNMZjO5r-^DId={aev^eO{w$(0*EMfQ4r z)UF4ggjhv$YHix+B#YII30B2Ddl<fxc|q53iJeN{x-(KA)Iuq>Az6>e$k@z?o$?z6 zNFT*kzze5?pF~j~X>4!@6;@q=rLklzpJNbjGbi%&YOmEd`1?J@enoDBgI;sHFQmf# zW-l_AaYNwzG%CJi>TQX~;BH})lkYh->mOPj(|5q0op1qR4!ku5ll&TP?e~c^_P8v1 z1x_A=CdyTKhWl!$*lXcGf3^O55%r*<5X1u)z^6`1Xht2{rxHsyUNdjZaU)MVxVyML zu2BBSeLOUI@p9}<SYr(1)DFGN&@Ix1Gf|D84s-cE|B1)%Njqt{2o+kzBM8s(5EE%d zj;^luDc&Sm$Nifqp+h<Czow&->%$pMy0H<<vQTfA@N_ZBlbwqGsngtWpNX!%>xGJ7 zj3Twrgx)khSuveb;4`h@g-2z0pH5o$7gAKF)cp8)9Shg4r_9sc`}L#a5xdaX_vn7l z+j@;|(yUZx?a{Sv{2VOhQqRl4Tr=jHNLCX&{NI}(qNU8%;pAI_N1x|OSTN@$98#0e z9KW@hA$MB6#sz2`z0$3V^fxa#AbN47d4{I{TIj)|+JpyqoQqy3sUx<*tZEE%2llvF zuMZ<1blMvsv3`&6b9A%QF)=X%kzUCFmJ=kTivFmb+h$Z#+b%!fDg_fq2uJ#rWpUMJ zJfFH4tsS1dSF&@^JTMffh7N1(^j#@r#ifE3y@lGaL9sp?`Q*Y+qrdj6SrO&Z20ooO z3tlmiHYvJ%Yv-wljDgY2eKsA~Cz5=3_`SeeX?N$Cg0*(y%>m8<MS^~1dvqHo{AFdn zZjx=Ww&4DEu>R-Z_~TQjq2I=;&RL5j3m#|R0Ux1bwZqvUxNXSW-&+p;6vZr`)%SkB zrvR<p_zPtqezZkY_DjpHZn($uab$Qf>)fo}yux0*jtJOaw6{9=l|z}^OnLu*@bv$@ zbYe(`X}8{R=_hCIavu!(^3}jR{QnG~Z~fIioN9fG(sV*RMck|9l$3LkQFv8wL`B8J zZ>%aWFgb?RF6ONwl(mlLS&u0s5xXnkNKc*MF|}Ax1LT5I`j>0A(wI7Q%e}mL_PZ}m z8y=f6n5qTZ9k0jkYQY2mA~I)rmon&;pP=(m*xRA9ho18RHOZfh77xL60Ap~<hHoL! zB1LcGW0)3092~{@=k+h3?cp>AsFi;31?mr^w7pifDnnP6z4h8D{Ii=unsJZb3UzG5 zs{Z+S=2rAU6uO5oCg!N_aDxm(s8?qQ9^Ouh>;8s{uRw+-JE>(sZRzo!AYX%pv%m^3 z(0_xy_sV5GyYyJD?pRfM64{kvIhgDN;DVwlcRsv(iauq@k0O6jT2X9HyjQRJ`QJT1 zjtq54>Xn4r=dA5%*qWDIQ#vKX)MR8&FsqRkVyTpoIv`CTTLPqWWFM$13AdYj9C9ih z8)JR~*(ZWil15+Iam5SRG8Bgcj_4;V!!a13Ytb^)AEQ|b1b#CEHGOmM<mo5Y^}pew zlV5J>v^QDz3WFJ?F{UjW6%bJ1b)kX;0UM8pxw^Jpqk1a<(qy1%M_3ihBf{uBd&|^W zDP_X}vFp=^Z%l7E?%)fFcDkv!<9en@kj<3^)roqydUsRn5GN<q2Fx)fF5@ep(PZv{ z{t#BDltkUwO*;mZ>}KiY9N>9U>2pj%Vi(<E$V>@<H*1fKy8Zrm#=ghW$`oC@KHjMK zjsl^l2D`mH0zD{%ri*;5Wxh8yK;U+Uckc|4C(U}K=#Tz*Y_{;${g<Rrn)>H!Ir1yO z3Fw<dKKq8CeFLWDI%-B(Ty*6C{s}HyGzP9OZLgGD8h{2>F?3OTzRGo`Z?J6r{z1ns zhbIyrv#uD3ab_@q9g5mR4-3Js{VZ{rg_bSXFhuiR>#T?&m?iL?__!#@x+r3G`(0)> zG|B>2as45}UoD3TWjq9hm=Z3I;=e-pZ+}2<f15*JCb+5c&wCyH{GN_Pf|8ErJ{B=G ze11_6vTeG^s$}e&4!S6rs3?d49n%HUI4<_-&2C}O@44e|1$T1$x#|=&@gXXHLb+7% zHfq?i#dijQV-I&nhkatmT9^X9;79fT7iV|igN@v~(z-c;OS&oHy*L*W8u5zq&<a-Y zgftDUg64$hFkCor<lGU;0~11b*GEgx$CPqIOgHOUzOOr~gsL|P_6F1vJqk|o+5*zu zO-1%cMnC_VsVnP={qF@LPl|-}%UHnnsaAvJTaA@`FWLv6#dtM+1GS2Fcqr9B17f3$ zgr2xk(5$58VN^(vFLxxh9Oo6a%sL`?vmb{&@j4mR7Q`i9m%vd&ZZnI8t}6-JGDOq@ z=eVLEu*lRFD3@!~s=6-{4d5jS^1QFQZUEfeZ`~x28FdIST&}653Z}_=rd!H0u&8LG z4}x5uo9xpi{gXnnY}vq3P^>*NHse)Nx+NGwvzopIs)x24{OCSYQ&#RENvK*!0(ejk z*1nRt&CW}{*(dFmZ5|+eq)^VT{{`%*-|g+x;cfZp_ld)Pfi0GbRjjX4g0-5?4{WP= zz!aVAP@BTNmIi^bWIB4Zp<qZ+KAoG~^I8+cOAbAq_<8?Aj{MYj@sTm{mZ666gx}e^ z#3NRXh}R%b%i-NnV(ENz?XcpvTrPxa6Mu}cUCpS6_iS-16CFEE5y6gOVW*M#!2dWP zxKW#>UKtG&pQz6H3q1FnGOPYu#e3_ryTb=V6J#?bcqSG}M7xZ(hL>14iovpiEUm@G zjK+koi>XQAO2|nVWyc9L-CwCt-`w5I5SdVZxagmu$lhE{E&WxpAVh9pM)GYixf>=| zfRh=e0<un#nDlhPT;@AIZDj2S$**72&3e5WcWR3<N&KVV?XF4_89rG%5f{UL#+4gj ze<B`9ftR=71#ZEFQS#jw%~lO$BdT9J$s|EF%iiy=!4SB)KdH8{yXEQcYWZ)^oY6vW zL8w)!o_a~C>zFP>_M57j&vLyc-oS{bv1HnxuodYV5zJ=6u}S`>zx<|=J2v(fDblx& z$N<!kCbYrt-VI0~!9#JRY?0=FLm<UCSKZ`%7?_(r2BP&5L;0G&nR~b>BE>&g=3x`% zGU*Re9rkf1nQHsOnTyFYzOE<ONBng6#QZ?I6*{lVhHzZ8QkwqpTkYT9b|n#{P~ok= z4I*-y*GMO5fgg=pEHWDop_3cfW3vyx+^0E31&4NC4GL@@L^o(keH2P%WRDX8m5;A{ z!K!>eGz(&kd4D%l;~H?QL2Jb3X*RM&TP!Ezdnb$G7P)fq$ZmI$k~~>hWtuaC1lr%@ z)l>(Zs2bL~8Lp{8jvtTlTn#*4P`G448;8E+dN`RO4s7E}Y_n$p#y5;?0~U-fKRJz7 z#;vLT(RjS)d)L^o$t4P6$pZE}avooM(pVY%!sZpvb?nLqle*<>s0)KddSxle@Mnv; z9I)P$PJLD)4WSxi)XzAf81*zYimwlTWdPvCH(*v~Z`$ur4h46mGY<XDy8*hLz8c2a zWjGVpTJ#FIHe}%hNtF%SqysV1>^2#8fBW(60wHJDIX}S_{mf|ea6LCI_e^1MIJp1X z6lDuvrQfOeyII<M2nxsQ``{P3_lzySn$8QCCjNW4Xv0+Uz;p@AqW#2&zS6DQguw$u zFSog2a&4rz!+urNOn>qyE<#p{2p-xx(_04BQpPQv{B(Dus|Z;m&VBh_BxsbO-7SPM z+}jo}0h<~gy_CVtKCWj|+AE1oecvA~ss@A&eLDb$t$WGsP@Xf@(4dx@i+J=`C`UAF z{0@jpIEaZ7@-DwmuBO0+uqla`hb%=WJqO|D)v1_zv~MsCy6Ji-Y-yMj_;V+bsV{6r z1<AE51_2BdJ|*0UOn_yvzl(kh+gb#)CC-~zcUs1n)i2L1i*i`cqP^DN3TFbU&a~8Y zBl=oZmi+17BVKWw>;Nh66gXR7uaBa8&o;O{M+IMao$sq@27C6rPxvEOE01Ca*RDu^ zzm3HA5eVKMm;)50AFUhvLm{<$6`OpKgK-Ys|2Q|;kn6Yc3-QUds#3@wO)Xuz5De7e z_+>q-516R6N>w*bU<7^4F6~l&61Tv;Oif0)drq8T8VU2bMq#<yHwesH1n%xzjn7Zd z5U+_~xl9(D!az{qxJok^-^Vt~%z%lVi#HCq8NEpbZ}*`X4$6f=WbB?)NpG&oV4jd` zE6C8xh6p`{K_V;N2qyjtV`aeABNd-_cN+8+$L;)>#Wv$%b5q*1>$_NLl0iuNFW~;l z@6_2^MD~wem|`QNAEFkM1QdiAwFP@?WKw*oUDd}~<e^8s757T4ni#1v^2%(PFVu+4 zSMuC!@4C^V+W68q^*5QOoy$&Fymhq_lg_S}?%8;Qtq7|`fja4wdc<;RL<H4DmiivP zO~?y`XtJff=6s8cBFTUB9Q1%pmU@*a?zAmF$rlHyU^uh^LraOkkSsHdXc<LbigX#n zLZYaJmgN>8gk8ZLT;Pz@_rgp%(PUt?AK@Fl457E?xWwc?1em1@r5r80zGVSd4SQxG zgQ~0v*|9`!HW3VuYKGh1DPhZ}Iw<NcaY-^Lw`Fqo5hqq?4d5nZ)6M>V2?Oar7v2*W zr4HW3k2c0ePdFET7K+KDEBTqYZIbvoeTx~>ErBEOU$iKdKrto8SdW5}zBO5Fd2H@{ zg(e1!zhk4_3a+9#p-8Me@mx)zA#~YpS5ssiHNmcFT&-6A9fsWmx&CqQ?t>qOgN28N zc4TQ&LCc5=REQ=ZV&Y+_%qz<KbHi65CF+BC3;Y;kl;<M*ZD?QQjz*nJ?XCX1MOEVx zGx$46o#yk1PhJrWbTds?0Dk3?au6WqvpDJT&@yT~%qKrE*o>5^_oOJrxZdH}eTKYd z8}Mg2aaqs$8L-^r>ZnEGHq1w1V_rl+IifnI1aW=NP!5?MMuvo0dsb~m(-it9Z0UM$ z>RzmC<y>id+T|c6|E7ZV@8WE=VVz871n3MDQJam$Zl#+q2%BzN0G-k$B>r1MOVBk! z%=_C@1lAx=(@4<T&fqV+K+;@XS%!VKg?_mY#EbKqDxx5hs%Qy&fA`}=$(iA1v{5Mp z_4FMD%hm%_5^}?s-@|@JV@wSiT^ETSTDp_1yL|$)%t?=7t)%f)H#gCeI9Q|=2{g~j z({n2*$CYF;FI18+KP+9WWkOpsuY>S^DfQGp#QKkzObP2BU7TWc8i4m#LAWhYSI@)a zDPc)?KLz6$Bmd6Y*nq7+1M4pY^**HZtvs}RIjuc}WlciDUM)W?%0#**sN@-s<tyno z3i&CwZhaG*FXz2X2(XDO?>8U!(PdYYdn1<2gM!z<HaM#sXWwHo4l*!@Da#?bkMzGz zx+%lt-31k}*gC#DhI>~0Bz(j!9Ff{2*bw;iCOhe#sEGg=e}4ZVH{6*Jp+krrJ8h$& z7`DY;jD1|ASw2M4859i*L!)V&vWPU7VR`IG;{~~U{iN>i@oOEGOZ*4+l@(fTHzHf+ zVp+#0L0BX%d{NjPFwa^P`OTx_@!w>(A~5%^gWgrpYl!46Egk$@U&Ucg^*d^D6_S&0 zrE&ZAbI}lcgvZ_N@p+c;FpK1_yt+jX<K8&CNTCtwq?|K_lgnqTDpvJYt9<30%a;jG zFCR7(&42ac(^Q{j+a~k#N_^8xp~&Q0l23+CWA0F1LBipha;-Qy&0z=@6D9}l$TcwK z@T}YuWb%BF-xL8uDl?d5(UoCs(t58yJ{?9%gPe}H<K<I-7kZW8G^j=oE+|fhaW?}s z3R7Gzlc#u>Grg2L{l}t~Db=3(db6ZMw<$OJxWQ&6n2y2}D8*E#55VU)cY3k1GlC_! zL7+b^kI1HRD0_Kf+aHg%oeQ879u65IUYb8FFG!=h!UneSk}B8CdZ%OmY!;Vg?A9+u zJ`8(%X)s2H^7^wdj(X$(g?6M+dgXiTUO#!YQ={;+Fc`-B)red-*V4}_{m?;!YKPJM zZ<2#e<9aj~EPZh3kt3F7%4PKRdG8CHLx3gI@9P2J+0;-ypXbZA`dyrQMu1(O9~wrN z-f|ri!2+kym|SD4Y#advMcBV7Sao_-JA(MAQLNr@?bd5ipdhJwM|pkt9WL%g=GciB zTC59fi#k-k+ZElzk%GI)L64se`*HXw>A)91{?WBae`<ynm>+`al6cmCxn88SjAPbS z=5tc)vfzgy6X&I6*oz`GHO4M@{QBG4w@ZgQ5eF6QVP07f6~nK9`*p^&HRN8ob+A{A z9Wvo^Aw!r+9fuZwxx~ei%=OB0nq??b;9aWwYRZxim@t))qAYI5q#8f5(3(|E^A7!$ z&+IF%C)IH*uCeMyWo30`qJMC_m#JlA#34yzX3d7iBI8$MjinW%TUW!0OyYd-Ilx;p zc`kQ3z)u6Ce5DG@`k7E3MGgH+X6wfUb|w7yfGQ00+pMlCuBEsBm3xFLk%-hWV9KL> z4&rg+tAU9vVpLZ?{A(;kKcpVysS2-@b}(U}U`17UDVt&JvEb1NAKa=Lo3rU74s?E8 zS-;uGWVTzT;JUX5>%x9OYrC4ED5a#~a)6;Ll=+X_Du=Ov%!MvQ8u8aON|+a!9c*Yx zY?xl>T);iRPji{S49+1H*gZv!RTJ@zH0ObhM8lk#OZKCj+$*QZKF?C)W&Ki=Ud;kB z_l+T8ckR&ATo3(8)y+KxZHKX9<4FcjGaHA~7kOLwV-VrvSG|6}|Gswy!krM`XcNPC zu>W$*`A?8KOJ(k$tZ=)T)2!_(S0^Cl%ERWJpggW(g<)h_O(lsqNz?BCqT6F0{gdn& zD~IQOFNurlcfV-=aiT!q)quwM%5w9lZtCt>0{>8Lr&xnV{@TDHSlxIG0jtU+d!+m$ z2>X#lvdBbsdce9y^80+6%z$S`an(5vLMG1D%k_h6_k!vy$WsT7zwer&2Qt<BQx#4& z_aX!p*Q1r^ICm5NDDN3s2=q2M8RaQ@#~US>r?#||c|Li>cWFmd&{FH@^t)`H@0Qa7 z_~cb!6KdBvBVa^-lg1E?bxQniAbOn;Id!FazM|k>ecXH9zRS(n_yVOrkP4ljflD?e z5~5lA5~(J!r{Ao^3U5QMwk{iaNnK<1n7v4iPDnXWUkEzZng}vs*ldVNAa7f79kB;D z`@y10Fl(3f?N35mCG2BQh|ozc>en|*pyS|E|1FHp{~67}8M7B4@XSal)U3LR)qlu@ zHnR`^@Cg+0KpgDJiaWBpWqjv>E00vROubFD^JsjuwRIoeZQ^zCG5Cpqe;O`}EP9?s zoh14vq4;g2s)q78qebyKfOTe=1G9zhfXd4SI2zglB|lWzz})<^bZkm0Wd6b-YVVsJ z8D=nN{_D^%nZe@_hwT!dHarL^1XmCj9_4+me=^=c3U8@LGnAQ(4?P*sR8vf-Xn2n; z&-WLtPA4tO;??F^MzJJ%V${!&0cim8@ECgHf0z}3Lt^2t=8ec`z<&N7`MaD;XVEf( z-t-d}07(U+&@*=L3Dxuc`@^7TLF#KrZ@3O(@2>deB83?}ok^(TZo%gqh(UJ-KpDq3 z%oTq+gYW6@`5vXtcM>{aDr7rI-hz1JyH6(4aMm&PbolvkfoOUNs`6h0fq~o~IS++x z_ui(ycc4r69M``r>Bc1X%b;o76Kt<;0W5z3QdT9zIQiG`E@Iss^1sF>9$d@JtQiX+ z1PA7TCBnUUBhr-NwBY2d?f#9`oRc6@dpTo}W%;+M?ZEv3op;ilt59(XOIeh*lb4RO ziiD4ZJ#!*?<wpZkRb^cj0)Yt+U+|@UPszxX2^e|;{g!EYDLrKCI&(=cHzP!FyW9oX zE8UXg+<<G3WD6{$X~?LP>fYzYxgg}S77dF!1!%p%a<Q(D4&S5jy*|LPcm<SLr9(`u zndvvHr={j&|8=www_=79h=&%IrDko%J)?<bR&Am>$E>deOXrEas9J9@R}!X-(2krJ zWzw8bzesXlEj6u`;zi&!BHuR;sj;;J5;yEr9_7&!9*dG_M08K))y!H4!6(+a^<eaC zpfH-#aJ3>r#f^`C0`$@^5zehZA9>#m?8FY2NT_x|>L*f<``|G#?obDaYUz6Z7p{(G zXbHX@a7hzHG!@>HEo3qZ*-qP@yu*!5M4fp3e`W7&{Qt=E89iU&6nefo?W2gt29oO~ zS{@r807c7WJ=s*|Ukr2sI1mrPRt=X($al&oNMCX_kaf_@u_9PRvL=IOKBaYHZstnT zT5w+&ao1x@lR&a<K}BQ3Mu$v>=MUcFvZlk{4G<&y5+ujk;Kt)7&|Y2v^7Z*J=R^H# z6!wAg_-3$^Yt?9aUG3DV5E;Q2`KS9%kLZ#NxWKaL`T7q)1z)8nO_J(V6MqgvJ}Oic zp?qyUt33WWKj&bWbMicD?0i34n{&;-FYY+(e+)4L3@VYm7_XEQsP>=5d)MJ0bG0d3 z&tC~IM@tTKc9Z>ipKjhy-M#;CS&3&rEYK{~BEx+c+%JTxMVwia7*zu=ya2EE2Pp{# z>D|M}zISK72ScnmsWs|`#;f6BTL2W0mzpsG`mR3%f_r4N<edxk6CdY366!Gu1FFF> zh&CfC6UfmzmYyj6HuT7Jd!bw|n{mVpFwsE<p(11kH)b*q(DT0^Z88^jdjr|RJVYCu z0h6q-kb*w16VkKd{psEwT`L}lfKUcRoL)ztC&(~W0MA|~^VDYL-{=mpUnriRGFGqB zPOeXcl3dFj@S}udn5Sov#RxO59X^Y17O9K&2Pm0~SGCWY;JiF|;6`O<s@ez)ZrW!S zPbI<+4t_lg19k>$ne~I$5kyp-(CN<>fJ5HD?7UK0Hm`CUp45h!s#0_Do`TOraWNe; z11P<R_+wmf>upoJNFBlQt%M9GUcr)Y4S%Kt@OUhSWh##~a4REp(bmbwH8zRxo?rEP z8C*Gfg41hCQVg9=wGoMCoHz4te$5#Mt2fEnj#Wkczn`m&$)Omq8DhawxL}j)vfC6V zbB$K(BA)rWM}&J;S1W!*oqZu*8jCX+<mqoOFSVFnrV0=5mj=f5IK@PK&lFl9@y#(& zWSet`57_}})}r)y`kZul!g5>))A7ibX3#Y-y?2BKdt!Ej0BAmuWGl3xpSq#uo`@Cz z(+eYB)-vLctPy0Mcj`bV%}IBM$^z|#lFW;2_>u;k(#)qJqSqX#17zSZQEdX>-~s@o z)Zh>C?iXc+k=81*14#~EY3j}&B<9bLmr)7z$NzhT6j@~BqgFT8bEvHUaE`C#{>35r zEA*X~@o=$)6Pvq_lgjY33}0|K|KQd-F%%oI8LgCjXwEl?91a}jfgF?Hwm^9)-k|se zm3N%J(ck+IgaX=u)}K_CeBUQ>4~A~quNcZ#`#NX!)4WJi2-RBmcvH`VInsA{Z!6<0 z{KrcGQ<;!HQb_LRv_Ym@v&B-teryD`g#(Cq_1y})@3V}#;b~n@<Zb*fBMdzQx&R&H zRYWiPum+SMzRK~z3h`e&+$^?`zu4jzz<zhiEk0>u6W~nw4^3_K0EaBu9>iPJx^69L zL8o~}x<#Swxv^<k;T~*L5^^E{#9w@kNVH4%^UY^4@wE^E^2F?}T|~-<UQ9=_r2ZB! z5{+WpxiCH!7rWiI5PdX@3{8T+7<=L0gWOzzHli^)SceW1yVHOFP54eO(9q-}7aqsA z%V4{pa2~OretY>5Ye~oJ;Aa3C08dhWNIG9`6zp+W^iQb=;jE|#9Z2Z`edC+7=vfSM zmse6m79}NR$fd;_v=S)HpLg*Ux#9j5C{}mA0n|?}^m+k<Q)KsGy;DT(dt`PN<knKD zU&EB9HXZDWoJ2^yJ8~%!EK#o^P5K@aDbIvaCrjZ@TMMbmPu3rX0O8&-Qmw#2GQTuL z61>lL_a$JSazIZQye&v2J<a)(R#t^2)7|pIQ3oP^&}2|)1tf%uNG}FKM&z|}<!y~f zkF<U7?toK`>CT~j?7mSjy5{UT@p}v2hJk<0?kF@IbGQho#LGWlyS~bp(rV_A(9GXx zFD;VS*)-K}Uq@&sk^hF%tr@Vd*&v3G_~z=5W4jPhw_(echToa2lz1=OeH%ZD(f5(K z7xUPvFCnW!rtOY`eFB($ZDmQ1qvM@bnw@%>eZfJSJ$U_k24NvDBe*$2(d;oWmk>c# z)8J<t$vcZcms__xk@bGX?md&VB6LRkg*^^4LdhfWW*p?Y=va?HOc8#;Bq>Um7pe9Q zg|fVlp(0H&0T@5efx2n1;&MwKh4-z>fXpeyqh^?#Dh&p6(P{~K`Z^`&0Lc30a#@jE z{1U}!fltrz#?G9&j-+wQFK-n_Kp*ja^)vG_QUTosE&~1j^nKgze8-p=!%F$V_0F*- zyVjThxffjSPn<u?Pd?ZphHZ8yr7v-H&Dj@M<nVc3@@nb4{@51u{siD&C9CCiS9Y>c zXNh62w`Bue`Kk6KTSp){-<Brx#{_Z4JgXWkl5sspv=ZxNLV9>=kwWlX_*eT65<n8# z1)PP>6PwYo!w%gDJf5-dQU61}SvRY#{STeF8m{GZfRo%mF68P-(@;v-dGdkui>ZLa zubdR|X|Hsr|E8O#H3W+pc@5oTZv(>J=O=sfqO}#ZTQB28OMVc1&B)Of7?HjBbpuHH z45ZxL@(%n3xk|(uUB%e<FP30UdlNxTKnal>OyR*Ol+D;3_BCUK55@(5o?u>?Gxu%Q zqRRsmROBhe%iK*UqaS+onn|qC)qsELXYEVW;di`rZgrKd--0a$u=<xBZGGRS3TEUk z#VQDmf#(SZ$r~o`Rqo7C#?2DHUD^n=GFTH`D0<X;CjKwZKo1aMmzUzQz0e~AooN4P z!D#fx7S_FV3}il#J%vfX@KrT)?}R@@p{^2{%X-|um`=h8_IUlD;=LqSX;RAS_Iec6 zQt9w!_z|H=Y-qK$umgBK@PNcjdQP+U2cM_Pl?T~GzWY*!=~H+x=C6-@>=~b~S2>Jn z&ANlrD-~NI9{IkrrjXOO!=g99Llo)y(~%IIB6ctGcfWDFIDi%qraKyW^oci*M7+nw z`Mm}I$1!Mweu$y=XQVygu-W$oMK5S)XW^a-z#o(sVm!zvBcX^V;*&8iE2|J@?1pRb z?zDeQr-~MRMS8Ks*YxS|!f#RYPl}gr5>}oJj@}<c;L9gDVN$n%G2z{9y}L#99pWN< zafJ5U_NxT|I+D#upl9liKg8w$D-$|&>fHUEF1o8fB~NMyubTzDa75G3`k2tpqKNGn z*4ds+ARgG~?>Cd7k)<qiNfa0nH4op4Rb&h0G?U1Rp;^;9O|a9O&0%)%jXJ%+pcXpS z>v7XGg7VdxS8}_omCi;0C8kT>n-UL~zbUm~0@SQGi!F*7jD8%|AV9dneYU`~H-X$| zj!l!)n93?!ej$ArG9rhRwjI2e-4sr-+pq0b5J!s<i9NkVIFrM-Uz3&YFbN`(EQIcK z)=C(Bh-kT6sD7ty)KNn#aGg(pIJ_bzbj6yYyUzPK_@%q2E6rViG+Za(W#|`M38YFl zY`#auds97v>_c&7BLkevO{g^qlq%u$j~WL{i2gr~-v6D8=+)8pajZW3XN5c5DWRMB zAKsGJ+Fd(87KeRK`-Q&ZghnEn__^$$%e>Vt{CY50caRv>^w&W3r*hk=fJgdNZNW_1 zr^+R@ERy`2IW4z~&)sWL*FxqaRD2HO#AV8{@u;IcYDKFe@KK{44HMwwr_*jA=7b`) zy$L&CGhZ>@?Y?g%)&Dq@AdFRfYE47!Z{Z>-V-MsV;)&w%@5Hx<L^78q5Nm%6t@OWd z_ZtO80JRVUqFBvAM7AOZ&9Bo<36T<OnT3`S41rR({k8|KJP|%a)6WZ)-9@fAwg>U* zm~Tp_-0H4@Kk)JNM5H&E=G^MsC*lUtN?pjD5LB$=QSmkg)YffzzIV3~+w#w-N5<Ko zYiJoOj#!b)@tGUaZK#tvjlDQ6H>zGCpIvDxD)W+gdxBHml~+*g({0h*C6`Hpb{20# zCKRV(9GT-&=9b5DL}fUY-+I`~e1-|x_yRroXg5;~?fGi(eTp%Oto!~xX<O5(7%+3x z%Gc_$!8T$Z5AM(|=LHye=xAT=1R^X9ViW9z*C<6I$PmxBje$i{GLeQ&14<6yo}1{O zC06ec8Cyd}0wWeg)&_R}MdDd-E#+UWs{A~U5(UEXMozONa#D7)DEV}87<F7+*<1GB z{jBQ~cG4V?Yeuv;{*`rF_n~F9nA9RhD|w7Jmm!)1ljgXw2q$sdgT=wgXn<R$CCH_S z1jV#p1-o71<|EYz<uP@4ZkJyog5S>3lij?lHB2!BJ8oeB?aB=AcF%M>DH7@+0rTEF z8i$HVuBL{418crQ$g*>J)c(UCX!523UMv2#l=A?4AOW+!@AH!h`YSD6^MrE0gLkK< zg^kwH4uN>)u{|-3IVuB=+dJqz`QMv>byVPZUfFoz5ydZ9Cl7Cusb#+8l0S>uynCN7 zhH8(ccVfcGXy2%V_F9}m)N!BIN_1OECfN(&u56#L+O6i(30itgU4w!sLs4l{U(2vk zYz*|0I%G|wOM5F41ZtL21R^pm@CWHsWk{RyUu5FWZ<@M<eY+c0nasBjwv8n_Y51z% zJjX7~4)j=@vLFX6RZ}+7D@CKgaVw>TaZ5QH+q=j(1NaP%+Ct}1GvqfF2je#~e2-th z^xpwv)(8zLd~m4U6^J*oMDV>qkQ3~`2?I(4nAJi7T<~u)B34|!z7dyajT;v~ATR&i zY;^JLB(u+Yp&HCIr_gv0)?VFOt&+E<UcTgWWxG0m+^c#~-CGEE+ayH2_)#tJ-VV48 zBftKUI=%(8=d-o@*(~h63Jhl{fpTfOJ<r0^u;k;-d-;GbIlkHNuUDOt%g+>lr1y$i zkL4j!Wzq=?yg>UNAd=C?rJ3yvBpXZwo?q^eWd)ekh}EbIoV7WsJ{@ATAuDd(_zYkX zlQOf$w?kq`@pXCyaVjD(Y!V*1S(nd>4)hDpzXNcJ)e(o*70f6qy+$uhLFTXTNE{Du z`gi#Ypp}am(=m-G`le<yLn*6I4Yw$(=KmAJxZuw0TCnr*sokv87&*T;C~9N!gvhv< zPR>O7BO#<QG&^OXgU%3J*6EZuB?Df~A7os{?uxD@;sXzmv5tQ;+-N8LL=2G&rTXdN z%ar{{%ONS$Odvo|Kb=raJ4xyJnt$_xIewtYP;fwT`T7@t64<4V+$MB9g-jqv(#vrC zop_x`X;nS^y2et^Gn4Ua-?WaE+qMGKbr={tr#mOVNzJ{*e&<8G#zWz;{^h`);3UN@ zC98OfyVe(Yvp0ZPCF=d>`G9S4GK-f^yJjLClym(6W#U}D@7_;yW=Ll%O_2(Y%gj!P zdpCaGw-_HRZ-M$Tce{eb;sbTxjI$BVjZH~-Tm#ZCVztobH+pr1tm9dY66itDpY%J( z;p`K%QcVVMuJU3OeyaI7nFAmYAAM5^Q6gfl46kMBzuqvgLjTCPhLAFOdTKZD_r*E( z18?c;*r_A?w|jf%h6CLXJL```LlE1wPGj_~-Rrd07h3vunl)&T{u}Gi_9Q^;mc#n9 zOhoTo^rBR3v)duzUh7_+_7c=Rtd1JKBp-^gVrrbxdT=>-bm0wu6-l!6ldJ23>uP{! zbf@DR9s;^T72gxG|GNiTytwl<ab&9_PHs*LevNBLdU1_HVFy#+0gP8@el=Ak_lbK9 zpHo}70>pJ)^;^p(Z0*HxVwf{mjJBG7!s31DV+-4!K+QB?ohgO*btSGBTzK?P4OgwB zD9;R#Xu!medM<aJ2&`w5{%N}j&Mh={^*CVl?$oER5nlk?g=9F^;7hw4hspBbr$|dz zI1>iXM&g5QF919;v+D^7g)S?>wsJJHGcKq}c;PJ7za<iapV@s~8y1FbePTR9EUh5$ zP||MXjvdD^jxw;4t-WQIlyBpm<FQJ5j|gwpO}9jnmtqt%u)g=QO>v3XBEwia9tg=H zVM>MkxNqGy3FR8fw1-OBU1^RyC@~1WDa)MRfX@fc=F}|#>ES8N1hx@MZy(5{$UTZO z8-u|8NbQ_)KR?9iH^ne#r5M4m@U0{?e{{a|<r5M0UPY6Erb@=$BGsi7hI~UZ!PtYj zIC#t(h-+nW{2Gg9B%=un+`EdcE$Ac^=W>xuw#JS#yh!JU5@H`7;OY<9vsjx5PN?l2 zeIdl9e2gmvy0bsB`Za8q)`f%Z(me8<75rdjcF0Qi->YtTTkfZO8KkVk#ECJG?z4F- zA<wofN=Ddwu5U`OD*La7$Y|GUs+6NBVHZbL0pDgSe^f!IBtJmZz0=;7<(`|YqVdXl zL^zFZ(L5{lVmVUkHIi}trCE9J9=o=@l(@!0yCSJb+LpN1lVtzW(I3H(vZ*1h8#fs< zbBBUWTcr?zykWN4I7yj(JRH1zuys{Z$CPXHCV49w7aQ<Cm&L(P6q(@FOH}mrZe-*# zu=Rb~^TnA_|D@QdoGKajyplX#q*sKFj}3M?F~<HEU2ytk<^2*W-E!wd-M3a=;3mU) zV*#*wd$YZ=ijkp6ZsGQru$|fAkL6?N<_6({o|{3o=~Df3Eq>S@J^(QeAJs1QuN0ki zmSOTpHjTY3o8L+y8-CmoRpBhIr(zrGxZb>CE4OXdf;=Cz^Cf0%9-CyHy|jruom}GD z7mv)ruhcfFmTjGLos!rtG#nLA<*V+CnfW17%Pko{4BZ<*_S<!{h~duxyx(yfb!Eh+ zk;lzi1Zg(g<cpvo<jFi%r57gnr9fPsFJJv7gHtuBnV~P=aITMVqr;x#?_cOUjc;TZ zmzM>*VD10b<plmXwGlUof-y$8dDO^5noR}LX)SB<|2}2fPhth=E5ycyl#H2^zL{jS z7H!Gvvr_vM-ohDJz2k!dIh<-1uZAsMet5-+@)uvpKly@XQY)gIfCOlwqV}8a3yAcd zEY9`vxEmf0H3ASw`%U#yhhP}QF`Gw{(B(`r`5r79b)E9_dtv#^Lr_gvav2i*VNpr$ zzCetUp{&KAb&eM>t$l%d5(};rZ2^e@df^ADFRU3KN~aQ5W{~v&L#s%BOUu`AGRNZ* zp)bOm7W%|M1rbkl63r-}9YuD9>CvgT@FvY&&^o|bDm4!chd=9cF^Hu2o+3B8b~Gqz z+_MWH&7r#O*XfHZGQP7^+8eI~5TLPL7fU9)AwMX>s`zXP&<~$(EBss)rr#EhFg;6P zau|!`8f6|A?5f&a%Kr&nKH|i9&0vvl1d>>(3OTc6w+K{3Vstj6OjxPcj<l{Z?ehd& zLT1p={OJ?qot9}=Hd76_W~$zXRKNUdpy7j7juoXp_T(;EBD>%J5gYLdVm<BU28n=+ zWeuULNYUm<i`OdO<15`(xVjnx4AbD<70}E;&1WwHD8L&W@M_W%Y>qXhZvlxigfrcy zU0aiLPZ#eR$stTxy?OTECu<glWQc}3m)Cb@X8?SkTGQTL{LPEa&<kCX@srNxwj?oX zG{gge;-5!Z3~|JaVE0;lq#8V)+EhA4ejlA!-|d1@R&>aIOWrNXU8IgJ1bxa;ylBBY z(6F+!iu1)*fEz99N*2K(!ElKnmcLs2$5p^guwgy0H7jP$eWq`HHOw95)0SL;CzcZ# zm65sv53CsdTx*-tZxO?L_{<X<LA9vWjU^mieca=ww^7=+0n4-?zKkg#w+Z8Ipez|N z)^5m+Yl=6YW;V@&jDg&Z!-ldb=1gq8MGV#H=kg4&EtJ^k8eJoh3$K|oso5KU7TvfW zH*VPMP<r7-Z-a|yDl@+5)&A?vva@&-h;DX0qF&%AA+~nJv}7n7ltZ4IbX$KnIp{-p zvfc{vL4Q21NqU?MZ3uNknqx4q<o8*QSE{H3j^j(Fb}ReXIN5(;?;Y+djWE5=p*A>* z{EEFoi*R#)uvh&@*?NqsAmZHwz`Z~gvx6$fN;ZWTrWRVvtbMG}vTM{D6Y&~1YpMrP z-7xk=ua0G(=yg_EdLWq@x6yVr03&Utt=|6c2MEDbK*$3Y{yX*YkP>u8l2VLV{6TrM z+KQw4Re;c(lGkzUQAwvTIt6smO9N>qe(Fw{;^yS;HPj7|`pIf6?*wle^u>0dy>0)9 zP5pAS@?}CK6N~wGi$@%_%VH8w+yCfZRpO|<q_Bo_Cp0L+cBMZrixIvS%!M9On`|B~ z9X`GYG(tcTubM3TG^Vh0b6B^l1I+MI0t*<-;+A{#W8SV?F!P%cexHiJaVk5V=q4c$ z|1ncplX{u)Mk2G}ce|U#Dq*V6L71_It7~enMU90Zhg}84zll7R!uxm#KE7V&V>SD{ zY#g*-4}w^aPg2Zw%zG6Cdtwn$>!-hrQz$uJ1c4o~peUQw6>yQQ9S@lU3*NwF%=T?Z zuf-VS7#XPggfGb5Q+b^SI3KU1gbO5!+gWyBJI&>82l3ES<veO^!x|Jz`1tA;?O8!B zY+t1&Lqo+VGQinBX3hWi(mG11IQa4;c?dLW>&waDeFUt{sOy-KlR#CC;F`&B;=B{b zUnnl%Eh4@(IQ=(D(WFu)3q&u4a9XH<l&<-2VTVA$RBJ84vyW05b@Y}HiR4k=O?-Me z+%33c-<RP^%`zb|6BkdTrHvji&{@0{bF&gG;?@M@=hz{HBEP7}s_nFS$4*>M!q=Vz z7Q48P(>!@|5C4G^GX2L|UdfUS*5G6t(QS(DFSoSaJCHG!3B<IoN$1k(WGZDn%rUm4 z%ubQijFBGVtI_wV1lSfDOB+7>w3fU8f+}5FYltv*3p865y<@Sn&nq)B+8k8f_(3uD z$UEli9!p_H&VAxX<4BZt;Iqa#u0hC74{q5>7$x_LX4%?zuu?m2K=JilKSjVL364M3 zbf4PNar_bV0kY`sM*m*`n`Z>~wBP5ifRFr9Bv4ZTIaZ63r5PM%21cd_?CPl7ABZR_ zkivUX*k{kDE}wW2+>l=wL>6*tLG~`uqJSbFVz@aZm3$_Df*U^KSW(lU6q~1Xwvg-l z<co?=D-vESm*mRxDlDt=tYIBA6b21z#Xf>I`eO(7Z-|_k(#^e#J$?GxKXAXknB7#K z))M$1F@4Dzc<aLchdE?F^(~aOuKfnH$dW#`V+e;rwAqBN_mw(ml)(#j4Fir@W{CjS z!prppoB`s%4{gj4C*_lmpOhUcupD^sM3Dw#K}0e15VT0rQ5!6M(TKd?fzpAV?YA>Z zCr@pjXK1ZxSeR)cCxMD`@MSP1*jkpf*7&`&j#GXH0w1qo-7fKWgf@kn<n5@P)mVN3 zh&k1I?Vcl^Vda%))Jx2+FLTiK#vT~~{9J&mazxRBn;gLb!DU@Q!5i0o?ppCQos#aD znFXdFjaZ~TPIR6~G1{b6getOBNKI&X6!iG43^SyT7+GY#A;|E^^&qWz+LOOFhcK7r zHk@z-t|u)x9*gv0WlUO|%mkzs86+{mt`9qU1$Q1n-T7|W{qqz)#aRFp+cug;rvYTN zcL1ZKSU%?JV<GT^FZaj`7yhCmelZRj1#N=`%&@YhGjUgNFLNtZR;5k-KP2@dIBU7I zTj7`lO%G7XW{(F+$U&M;bqtwZ-__xFmL%cjmAy%9z8MZJPZyWOb5>KKrUG-Qd8!8t zcrA}A8P+Tk8@wI<3x|*)4T3Na&$Dj*rp$9EoLJ}8b;h|InFuNnN^;sWWfH~=T}va< z_8Cb!OOt1C`mjFhMI2_kumpv$i{wudzRYg9J(x*2kRl*ze|Ol!5S1r+iK*5xCO<&+ z<luw-_TpnfmtWv48cLTVqF5fq#6l65RP%HRGgzR&e^B{!7}q~m3O22aB%`}Ps@T|T zuMtOi9DJgt^1S2IhkjF;ppcuPHsH^E07PU$T;*l8Hbn)26VaQ`2Y4|lxffdB1}JTa zF*<)I>f1m2Nm6Vk&=*6Og(E;2`O$gu!L$C4PMb02#q6{ZO&o*#OW~H!W9zH)M$|Xg zG6asr-*NL92>8Z|C^km3vQJ7)0@h9&&!rpc>(!i!bs6s6BwOOR-=QAgIZ^+$dzx4% z1!CrMTe7U6My$Jt`{^(f44Rx{*xtDE=^k|NhWAkCl1v_76qI&VqPcHq`haabcy@io zYetQb+VRUr!Xiv5Ip>X61B4Exc+{hPY{$`?&LvKVuVIvlLWJ%N!2R-Vb6b6iIzYq) zVdS(SCL?e2@%{bqp>9zfL<U!qQH^Hg<Gsf^E;5^a4<_3kxbMnQcR|=w_{jf)Nh*-B zy@B}|QND6mBKcTGsy;kNC`vZ~ynP03##J(Z@^%wTuLFY<`Ugao7)rl#!9cz2<c^7Q zciH&G>+%~z9=eEzf%8}&Mi3)_2bn<O?BOSlni@*<3=!L`*8(Iu;~$;EHGc!D;Ojti z=|t9A^j~d1Z2ayMhB$6|3Ar#2MM|~w(5Fi2%gM$F#WFjaVQEN;!XudElQKNHlkD*% zY#Set#_lgr!1mk1l#luZvYKeEqv_=L)(fKU)LMXS;U_Uwv_M>r^2r3Xr#)a>Ddluc z;i3x4-#sK-!22q(z)8WuFcB6zrBL9sSx9i;(t*XG0Z&63CPjvp;ZU0v%;VfnI6R4O z=G~7XibF%^Le9ge$0k268B_<PJqJ)V_ZcofG-+jLNJU-)LW9hM-$Q&yQ@ht`kk0+m z2gyMxU7p)5Kp!Og4*YzArMF2Xhhz8s7=nAOpRYBz-hLJBssJUcx!11UTg<-rvx=>U zsenxILRb>Ic2h*oHB5IgEVC<mz7Rl+VRs;s;AI%ORvB3%pL(bhTG^uOne;!X01I>v zxmN?3Xe;3@+v2d>L=0#-?z?DN-1lBeag1yJP1M7D(AzX&jGiw7%gYtgH;&!pvZ}#R ztBmV^qmDy`+VxfR2m12iw^ogu(7(7bxL&q3KhYkNQkGNd4Kb<RBZtp~){6(_`Xs2! zkP5Y6M$%9#?(AC&0LL-&Uw=1%PWDMcoU)6nIH=xW>Yy>@T8^%-_tEMfJfMq)m^~IZ zP<UKV6w~3RcmEn?9w_-m<g_Qhx(yc}a;<r(PB|g@d~;1#$Sx2aTLiFn4NEJ-{y)CH zI<Bg%TU&7}ASk6E-Q6G{ozjhTx3qMFG)TjyySuv$a#PX`(hY)ylzfwO@44qa=k<Jl z5x>3mT5HZR#~gEvXFLz$=b*EJP*`PjXcZG91msBT)JI*SqUl{4B;iGl(Zul3M4s<c ztJ3U$;*LE1=(t<fAZe7{3qls{@W>o2s<CNK$$O)CbLtt#qU-omD&CWHhnQToX$1I| zGbVFY-Lh?P<W(|w72S3^E|lAb%K=ysnX0vviI^fp5>AM(g6$kwI~@0pkd4wtDa9xX z3GgNFlCHI4fka#+%tc~4R<F3;i=W&nkxjg`v)n8dpB=-}i8S}ScZ%ou>8=CIsZ!S| zYFB5|VFy_vP8YykpVa5%$Qk1!_n}1POn>6p14ZN0o&4dbWIT0&lskqLdPfecz5k+7 z1Dy6B1W*uQk$n>4fKYVR#`rth&>yTjIAr9Iu;53fE<kvjv=MQR;3$x0_pOw`<6arQ zLQV@A!qYOocFpiGr^f=m3|1MhBOOLLAjr|5iCIiQ1$z2%AG;!gWIgRv2wz<Q-tsE` zD1-#Lty<yS_-V9{*mDBI)Lqeg;gsnv+2*P%nLyC_*w^dh8c>idwPfrG=kbRV6rQ$5 zQc#!cJ$Vg>vfaJ<T=V%}9$wI8epulYs^$O^7P~Ge=QBTAORl4xOSmsQO`<JV3y)HN zBm~DAl+0m7oN%P`a12CT6^pI5;2l&u)v>4Zo<YO$2tU4f!BM@H-vQXFI3~M`3es^b zQh!OsAZc&Czs{yN(x9!b+jI6<!l=W&da+tuQjXKeBD!cZ$p>MA;IV)dkfY_%B1nOM z7JklXRR7Mx1Au(=ul+g!{|)x-i;w(xsGqcV?+uF%S^?2CYXNI?@^rpvN-;)A)rJt~ zeY?U{8bot_v2O%3{*?Ajf#eVF!%~UhlgdO0$<|%sNSu3#gWmk0^}P1_N+9F~4uZ<u zvqCE@UbC>+7x%k0%9R&{8?!@^wA7bcS@ni(aU^4=SUGhnYjY|9p0?5Nm*UeFBW|Cd zw_h-AE=kP>jB%I#iOtr7<dfa;A$u@|Uuao|dEBOTFLm%29t|6d#>R>q$HT9$N&z0{ zyQ~0<`>yeA!gXF;&Bzmeuk;wy{hX?uRm{_Q;rSyUB-^a<y$8u$p4T7NR#smeeoCh} z5%dq{A&z0Bo<!cwZ>&VLkqjmW!4|A|j`}KBSkr!{`9sfJb;cw&?8R&sr4?<;8<?4J zjCM{2j%_)yn!rlP$Cxm2nPVXTz%P!A5bV}5I)T+>nJMSmQSFJjhi&8OF)e`GYiN~) zwG2`4J14hFuFIic-wKcpeD|pz$@8-ar@i=^gTtz$GsvQMyOC@mX{vmJ*7-CL6ph;s z^PY?FvXu6ygs`V72jidkIpdB*aBfC!3i>@#mSLlu)}1Z<fvc)z+g03Z{?f<h1>xaC z)6c#S4K<9SUmJv#Ufsc9Cs|iFeMS7HgLwQK^Y-tQrK3NfI=Z|;SHK@$2ly23U$*z! zv<CQDqJE-YYCQPX6~D_isYWW!JBdX`MUZ+e>=W~jJToj<dLt;8>lh%yxG!_$7Q0MB zs(z$=YW(?xc6gHR)b@<Vtum$eyNk~;3MA^}gO}_(!pTzfW^CL<yQ4_bY2_XI3~E!0 z`i*;G7d=lcNt0XZD=or$$KZ!g04i<w&8iE)ZqsN*mr$-X-D!+=HvZI(rgv25|BWfU zgm4j4{pj(^jOOp8@m1{1J-)zwE_jgz2=c02zCT;diI22{8~jGy$r<MHvtIHNA@JVv z7u-V**VLkN<+&l)kwC6DLTD&MbK&LNsUR0qcDAul9<mLd3p$D55Ku)es;)`$;5H7c zz$5i!a^h*L#FgXcIg-?ry7*CzMQoJP+P75$wdx5>hv@}v;0irvlzqnuiVecXW~MXn zXUj<eLHht6fp7JK)*s&@PnjD=tovOckFb(hl52haVN*CVSz$2I<nwb>*(mMV_)vQD z&~TT?tdvlz=2J5DS?05{`dOMux=XV!vw94<szzvTuzJf76<oCb+N4DEGoc-H+q5cu zMk73hw4>bIbXFZ@c!|Dx<LGy&?v}KZ+z7v1$X4)WJ|m%$MA~g+*wb+)sJyDocj?)} zV!>I6S|ZcOM!7(-YW)78i(msAPRR~-VI@c?1{5E2-PaqIyxd<q*v&(li<E{A=P)%b z(a4B*QPZ?e2Gu^oRX?K>ubl`GD_kSCGH$sP)iGX!pc>Fi@vm_!Osp>iw|X)5|9WNc zfV(o}TzYOV+9rMr2|Hr>8{z$vND*lNnaRG^f0HLCqN8rz2S_qAUppbXr+h|nKQq@a zKu>KL>w4pqSgld-slw2iP5mz+6^}#rCEC}`j*Op?+vYK}vC}-}mw-c5_TEu-s-Nov z`v-0_QGPf1h>ZkACQ?}AD|obFn&79tYfwX){q=Nupbff_E}{by(I>oC;4h3{NL}c` ztKNTe_HtLlaSfFhU|h^zKce1oGu<b$B+^b)?d6TB?8HRpygXv^3p3(o+(daSH9`92 zwL9z%T>pW|u-~>Om%aFlJ*f4BWr*+=)fVkV+VPxJ60S%rR`p6tORN$R@_D#CI8@w_ zTBY2?PW_lz)`R0`^a4dQ|C1;|WEkObbf?B<;X~hzsPS~y&vR&DMB@Ek<bJJ}#Hxx( zYbVmWTZa34plc94Qfog>33QVYA*oZkQz!5ZGA>R*E<S0d5=o!dIM;2AKa~?LTLLXm zbsChT;jNaG1^8T_Uf3u;%#JA=tzaLuU-CRx&ZRJwfa&a{ke_^?>$f3?6z(bW!&2%T zll~juXD5~!1R5ka<$=`mH65B~Ydm4!jymC2xAM(e@?<u`eJv0FNU2dVUaskbeid!B zCm-UqW=pP|F7enc)lzo@oz<LY*~aKgdx`aWi7kjIi4~_sHPKl|70!^hKfcy1FBeDH z-U@H66*eS#g-&MNRM)W=%D(;@e=T$<50v$0@>@;mZOZ_1mASyO2vgrL)sp5)9-DoK zU<RG>VC2h1A?iy@`@9S{MfbHPabsP#h!5H2bU~$GzC?Njzh_8;O*jc{On=shk-?#5 z-%jV!hHmSyxKXI`Is&u=O)Sr_%i(fTue<vlyQ-FW&@6Nx=DsbME)~K??OUz>9cx<| zmnUI6!<*{;Hx(h-=`ByCImJNtzBu+f^4qM0vg15>rsGjkSG!4l&a+F;8QBi3sC<_+ zgImz~rd(#cT_D4|-1b;M0-ij#`chDKwY1^rH$Zhs!Avp8I;|mzOQhP6W^2!s&`1v* z;m1qy$sVSr9nBe1^l18w4{%|n4z=b}rCOdv^n|;pf~hv}+suHz>AQ<i1X+_w^Nw+C z(QZY*!)8)@Q*gc1*JpdHv!I29wD9X~jq?GsBBlj_m#Ln~N7`WcSmnun^Ox#O%-P-U z4$tF$!WSy6oKhj|p|7H;3yv6u`5xi;;V>(ZQNSNk;Mg3+u)3f|dcR;3^+^@Mun8$Q zc!T%Qr1|_td6@f|Rpi(LD^vK7XWQkMJC~C`JeSCBR?BGO)(ry(<GSS+v`~xQm=gUs zKFZdmADJZZJ9gW(itMoSy5r$Qk067Xb%>v8Qj4_DmdLow?=WEwa+~HfA1Qc2U#DL( z%2{w$LGVLLkGGUu^P)DzI+#VZHgCi{yWHx#M1_)C4VC#BD_$<@tp&*FXOwrn!YVc> zM-#*Cx?Hm&W!&jZJ-*)3++W)-bkB-Bt5FVaZp-`8KA}1usRoZ-#9w7&V<YDo@BLbP zefMx0O0A@bi@1D2P*j{S%x#0^Nh3$hIOg5HWs|xHgjL<k3wU;3<5|J5MP1Febc?Z^ z)?AS=>BN7GFY&lW&_bs|FF#B~{@k(|Ug-)Qt2_R2<S6t09)#%LeFTAfaHw~`GQB}O zp^?9oD=s_Byq=n;ZAR(S4>^xGs}z_1x@e1TT`QK>N&wH&iDFM5G>LBIN@Xrl?gd3r z>FtU4)YxbN>^bBkk_N`pJZfhXtmPZI?nPta<PhE!N)FmJgXnTY>tp0GKDSvE`IX!= zqSCdxLUuGe8<sSRvKtPzc-esA^Xah{`f|1Vw3Bw4``XxxRTsQFC04Gk1I&?*k&Z+W z5SIObS6_!+o1SoAo_2;{xW`lNK6B@#{iJlBKY5i?201C+!sy?*G9b&+@MatrJ(vD$ z#-lk>kIAi4rV;m)Am%OA{n`%V?g%xhk-D<LR{K+Haa8&Sju+k2&0Zj%Gs+E${P4dv z<TDG!0Ef_@!*Vx5dQ=#1N7ruPJp<%V4CPa<bw?iK<L<@cV$Sx)F=|RV59U*le>k%$ zn3+yeo!Q!EEo*X2G-XRL&pj5}=E`fqMYnQ>Ywlt&NV@HnHM|<_x!)jY*w{<-X>Pt| zcs{i6`g_F7h+}x#waA9UFJ^|_VcX1IuLILhB4WPs?rm*Vf@b1*t%0hE64g0>L=5z+ zM8AzvH>r3!W-O%vUadj7Hum#*$#e1p<?&&|I*f#G8wEjtLM7F({Wh!VYtrRAx$*JN zfP^;<vsWd2Z&ZhM>#XeNj%)WqU4wf7wAcz%ohmLQ4mJuHQwX0KGW2fBh$o<Zy~=do zzT(cmVm2SAvPYXE@c1rhe?-6jaJ4%BIb+vCmpAvf_YV}c_OJ5Xoj^lo^5J%3`Y@1S zOmR0Vs72cCi_l2NS{nU$otbj-w9vDSc+n?V`?{9Xeq%bB&0?SdwbHmheg-tXP5fwI zI}G0&T#A&4rO3M|LcuZ^<fYza3w8R#D*rOjUr~@9R4OUA{Fjtd2zxCI5SXYJ%Sun3 z7gNyBmr-XMaH6gnt8eFdyoq`aN-7d<IzJgy?(g&;EW!*4J}mqgn13+T9Z6_|j^@ef zWR58mVSp&ppTNkWt6?5XDJSbIfxxc7NJx92)QKauEysT|j!Ca!)NVBCLD=W8?=Eo` z9IL>8Sfa>Pfn{IxrXsm@OX}#Z`>8!L`yz|h36NPO5{kq?G9~Rx^AEEW#rDW>?kEU0 zD8EqNm&s1{7ezGla*>%>$rO3Fq{)0E);r&1zYk;-<*Z788;+j?b8P7q(^#h2Ff@<B z&D%nJsqD^pszohw6I@c4)2ef_3C~8ptbBX4lAg`({p<SV;I(HsY5HSkliCSy^euk) z>-U9Z??hc|$pinstnb~wrC;YSE(Uz*BfqNa^69(lGletfKW8f_U1s6&e;^k?u04;q zoHBeypu`;SLdD-ffGn!-w}*^NYQwa*J)CIE*flQqlAV8lK3_J?{I1<CQk>dGePK1x z(8jh2zZfeFI!OtUSufG$H|o8Htdu3IxO-3N5)@k{G=$V%D!O-hncE+y@&L8zhUSjq zxeR85QhqnQ;qed8X)U|MutSP6sL~;?+88I8-Vl0ymo=wlG<MZf!B|NO-jucSaCLHv zzsbxW*JWGnQFG;Y<$_s+tYRzS-Yh&Lbj9d*XJJ%w)e^&VMR)Ube-f)&*y@qf+EHKR z4fi+acF%_&-6#1Wto}f`>M|?uy}-<Lr0{$Js=bjFJ^#;=G;Od3)%ZWM$%eJicklJr zqwZwuSZgB0Db$m8HWi|og;00}%N)N;<*?DoX!R4!yC{|>?oefpfSsT<6k>U<osw24 z;(3C}qMazCkh@tQRzFGDR300aFC&$G++5(MN+wDO@O6FMQ|Hps>CjKLIHIR^DBK2g zUC~&>nownn9)Y%{mF%i6QTFwl?z(j0iI8)W(OIwMlQFplv$6cVeR#6jVwnN*74r=d z{J%M;dvM+ka6nv^{y;G4kSbW<Ld;tvQ8x!8N;L=aY=4z<<iT>z$f4TmG}aZFc~L`r zcR$AYFoO%DcJoVKr6!`OS1KIs<me<*<=QFr>WzT;sQ8S^>N-iE_#XpkC7fyEQ(fDs ziB3)co!f~2N((8bjB>XvdcI<Gx)<m+`2Bh;i-qg0M9{=QGFv}cVb`b^Vq!GGPOEv6 zw~OS5Dn6#t00Kwizg9HSJ)bP`%%?sqOvLh!5DgHJDSS|cpON|_Z=_9Ebw9P$Bv}JI zRpy}GM^|IA%v9X?vCG<|mz-gd^LM17x^oeve~g20kbpK^UIoeij7=!{qVT4^etx)w z0G#*%XHo&~m_e!eGq|HYe-7j6Jn&sEw-2LtR`rTrjkd;4{K%pB+uJg|L>#A+uQzja zCik)HmbS3Q-hdgOQ*#xY9t7m<LJ5-JC$WJGd_>7n;f$v#1!b;eMfpB!L>18o>RPoH zKKc9haW`&tVwQCDM>>Z%YZ)fjU1yCR@iX7`%U_eoAFB!e?*{yz1M|lhOrQy5mPTOI z{pT+IpC9tE61eAMhbxdL^^bx0KhK%T1?PwW&C6RD;gxFjgE0T?CI92A<Y|3yAh2C4 zkt?amSu!6*T!nalSh`XxCs~2Y*?7=DJ<9*w?qd|?*AfABy31`2nL&ovm}Ot9KJne` zo=%>fV`*nTt9cB!?!e#G5~tJ}bdB-w-oHHKxIm_;k0Jqd#61a~9M1SX@qhWRKQAmM zlP?fxGA4wjlLPr@Ws(A%e|sHN$PPMHX#1XK1XSkN>HqG_Zy_)}$$xC@e~tVbiA+@= z#h`EEfnmH<{7w2<br-~(R*K|GdLhnnVMUMrKBIqKcOsNY;bXT3ODM~0A>D>{8H}i{ zEFh^@|IN(*<6<8^#1r96I#>DX&K9}uH~)yi{+bduV)<AB&g=zVsuao3Msz3Le$`mj zM#6vH_&?*5dvKoUh3c7>77V9F>kE$&pyUJ||N7B74DeAXys?X%`6~!)Hfs#-f8xKt z?)|5|QK8*^sf<)Bxx$KIpD^S<UgK}So<s`Z!x<w73t*E4|Lc2SB8-#Evo}2;cbA`p zPgVIp6aB{<eZ;);WdLO!F3=P}ME&R7|M^INj#sAj-N(w%sg$U|s?ue;8Vl=~CP)}& z!Q~sM>pw7TSK?))yL6OGc`Nm=Q!el^Pgu8DTM@@wIA^Qp+sliN?B`tU)07-^wP^c{ zxNz$>0@3&X_M-nW=Hn9ge5z&Nz4ZJ2+PDX~lmnj4&LT)E-sSw3;_HKdvDHADKUSV+ z$hlN|rzTt;d)&ZTX6rQ#F0WxeTLUufJ|}hZo*?yO2!f?I+%I#?v9pTwt)HJhq@`SY zo;cSiG3K55pI&c-Px2UWSeVaHx52vf18UR!p110>n_8wX{$jmYKr?jykWaA`{Mor! zex52zo=VN${@kl|L3I6${X<&Z-rJY)ah7j%rm=0)r!;Yo|2c)3%y$O^%)ECm*(gVZ z+~vJ4r*_Ns4;h^f1*wTM$>hDJjM<&?k)UHh3;uPc<-lB+GVsKox+J`vxr16J)havE zTx0gHPZLzWe<_}QEW<u<Yh_NOraDH!y*8V&&tISu_4S!XvsSZ1bOlo@nS3|xB2ls~ z!%u2_gWQ$!at2&*!P!fJ-hHSxI<-BnJ#*Rpf&DT6N{$SvwbL0FTvgQFO7hNcLqoE- zAd3N0b<N?yntSnZ;U6ntdKqz?N*?CNvJv)&p?;-;G?(h7{W9CdG3gpiJDc35oaW=d z$q0=^r#u~M&fGjQiA*uoHNDbyD?&<oJ-4M3$FQpwI;BX}w$Qi4qK$Hv&`I$SQ9-f; zupQNdKAk`08Om{A2hTRz=G*~OoB%WQNw6Uhk<a5pA3s49w5n{1k7S&CCUg=vsPC<# zdJ&GwZnJ1fPf!2c3hEhdU`kr~`O!a2K3qCe)`w*ciIs;6_u|Z8PM-AJ(?JHl=FLQR zsi#Zx#<x7DYFCjFr{u^CLh)ph+UzqGHRW}l3@rofY*?{$)IQZkndIM00uIXX>UDCp zc1+y8gA(TRWm5Kl4s|UkPxnujsvCk%s_?-Ke*Pp<v@$f24xm5sg`xeY0WO<4^iG}0 zY2-E5OfVX$n@At(uX>Iz<~>OF+5Fp{;Ib!fj4v))-!Wkw%Z62(U(KtWlF8on13HZ> zh|N$Jq#CSthfAdzwu)l<ei1eJ$IGDt7bBGk9U#8N<{a^u>qEC8pg?$u?jw}ozSXB` zqg2qwy6wW9xytQr*bp4+=Im)(YSnDub2CRirk#3{D!ad2sQxp-K=+Z3bf0Jx)!<sv zE1N|gkS)I28&{I6drqq|o$h`>?WgpXY+0^;Af0!Pz;z9c8_+@AA!@5Y9%|zA9HXW6 zxZ3A*$Wk1wDutZ<4E>d^+cr7(*|Z^U_g<aF)GXlAw8F>7mw457`|D~SbQ(2GPEHb_ zd_`@*?S6~w^A8W;^8w=aoT{!@i6yrmFaM9tME{(aQ=;qpkfaXOMP6l1k^=H5<bAG~ zuA<h-!-X{MvomjeLwF~T49gK*+{0Rt-f;V0Q{6Wgb{0Fw4O*H*muImOQ0a=ZdMv8` zuAD}ONaJfzxi$rK+|WBM04KmCNLkVOl6tW3VVzw?JCB@Mz%dtfO?Sl>$BN`2`GG{P z2Pl;70o)wuh~XYs1lQEAU7gP=@029BwqKUMA#nZh+>U*=#}=4^1Z0w@yybwaWxN4y z8suk`7678HtL`x=zOA`@Pr@v%$nE-eBVc8!*asXM4Ndl&vw%X>04ON=-t{oo1Hd?? zCeEi4m3s7lI_+=gh~s4P5n313hYG5XWi%LeI*8Gzya}1|P^Z%&lIbz+^D`)2)K1p* z-svk+t=>ZqVKHpSq4Piar=}aF7^mE<Ree2{1a)`H{B0z*g^WKL%i15pe12pOye<)^ z9U3DR5748ilFMGpejU08xaR6XWuM3O{FH*HOVOrlhxC$qu-SWQM`_Vb!-OG)QZC&R zFjdW|q;+e(QQgM1X&u32)Ui~`mj(hx?sWSJg^${1I+RV7b>89yq-wwGZRy>8?KO=% zg-(`0rydhOWMM6pz))ADRB*OeP~<j3amd)+|08=?V|7b+za3agZ9&0V63>3^nB`h; zbWw{(dGRec@Xdi<LJNR)RzALjiWjjzxIrH0!rJ+VuX-=w2)QJdH-Aqe)mpMDO^;xS z1xH>43yNu;UJqJJT_J$-S0wyO<fBnlkjT{1yY<>e?ua2$Klx(saVSauQx-0-d=O<w zq2K2Tu|Pm!-eR0e)Vl&ZPv|euP`?*U8X?~A#DBHNItQB9y;L*b5RQ1Cu%eR0T`EQi z&{T+P-(mRJy{>;k33Zdj!mw8R{f=`Y`Kkdi%felI!TsklhVzwjhMQW-<<&g=6`FV5 z4h2@TwPr<gcc*#)WNM7tH1(3Krzu+6;%CEoUy-`}00pp+Yz$OsJI#<Y&$}PCjUimv zqqk0#X(pt{0qi4Z9T*t*M{f`a-WQEL{O4}@KVg<gi@SXO7gkAwpv%txiHG!}5TLny zg!2hIzrOHNq0E2Ro;6j>&NZs9wes_}NwzO@m)D6ebx<#HH*1`9b&pqNn2_mu@as8= zMpI*4s1nWC=*nHUE<I~IkfCvdP=+Y36JNgZa_v~3TDK}`iho7<>7b7?L)z*3`xlgY z;OK28UUrAL7QVYUUT62bbVy;+_r3E95(0R=N<D1(z6OZSpNK6L)Tc>N`j)@k5V*^0 zI2ESDK+C@>H-HAjVr91~*9{l!JhGTjy=|gW=Tn(Rw;C02^a!cDd<E3uEGLSU%{mki z$8EpK53n^)*3HssHGVw+xpfC!K5&F~cqcplUm>zjH@SR`z|3SB(p%~xI5^|gMJ+m9 zUr3Cavf>NFkn{Ts1W*|Lz94mUbszh$b2!}10+)oRU!rew7k8HXT3BxQMT%1H`xSms zsfDOk@hp?EQ;WOca64IQw9{rue1>*b0&SMhPXPx#S^6E*s}tbLpkS7<B7-VF9?_Ai z>Htz2Z;Vg2M)KvnUkf7Y^x)Zt0f>Q|)4Xj@UThgHqAl^P*}It^z+cP(g6fP>K=trJ zCi!Ji%(mlZSL#%St_}aMpE-AWJG>;hTyeahV@L*_$Z^y$IE+SV4gvk#8r*iRj7H(z zN@qxsxc$IxS1PI8=S;O-B2rhb2y9jW%o1Iy>)vrc-I*{`Z#c+{@7=A;LRe=nY(K6= z$xEjX>Cs4Li2PcJYZdZe;mr}kHUGVP_ik@<hhk^{l-t`&gU@_3G19ZCEKo&M_?AwO zvFbb~7{~B+CxO(n7E!v3(kfi{XW<W-XdZuP>-q2`Jh@XXJA@t+noUA7x*XTGbZxRk zmtag-aqn>7kJAn0*kGylznl}e54}w`pk&FpdXi+(=r@ef1GUu0>kl_2u9k--Un4fv zjQ-S!UXS3`=EC<(g{s7dkmbz?l|cIz3vdU_aa4T-h?qLiDs^kTpj(U$&7!}KO010Q ziug4cXLMN;W->e`BsP0to)OU^-Wk_JeR5=1S9KY5>Vwz&`M2s9VDQ%gbxIT{sH=ly z4(wiTZS5PdqD9of9={GYwuHqt_x`(;YFtY{a-<8e+IB!nL0nxuDU6U`Cmzt_&~AR& z%^jYYm^cQ?NWDNjj2Ng3WxbP|lcpfOV+7v=O{jJt8`cYOZn3ef4M?-hL!gW=sN-?; zy6LDJ*BE4c*x4_wrpnXerY0w0`a$><K!iSJ0V}2n=oiAkY9za}ALJKIAB~<BPbKnP zZs=L&G8=X$&g*{(oYA^dOS%BmGv<zq-nX6?`!?Pdo=V=Jk2Dql2$TWDQKkfG2#?it z2nrPL?-;yUx96K`Jg$#=oXTx@23!G?wH;tp>9eS4qX3D&`lI*QiHE@B158l?3_w3q zcj47f;xgU}A6EmyJ`JGg;<^pQuFC0+_vae0F4r#sd2Y;Zc?*LsbkG$L@kIkJ-ceZl z^|6#XP>8a!{H2|gqhJJq12ct+@b@3JTyW%<Vw&+~iH1}Gh%iZVs+!W*fTR{`e-8`W zM_`v&{@fza0g6LT<s6uqs<&!u9<0mWhbT!(yl<M;hX##`LrwmXd?!-T2iSedK&dPZ zO(#kP*Rs+lIudkunM6Q+!?=Kxu<yhbdFH>e8p+Q9prn2PMLXY1-M!k0ClVJc%f>YY zW>`MmZHKy_8;Fq@0Srz&uur-2<{cW+Z(I&rM1&sSeM;+R&7a8juPfeR9oau4e;&IM z!89Zj?9~Ro%nk&160WXI>+9ZHKvGb&{!ZiR7>GBrb~KKhU)*Z3c7Om_syhPT;zxdK zcJ^n4g*lrJZHC5gaHPt__o*MW+!gp;7`9IU4?{nYuCvNzc(rIh%*$TkfZriHB#gpK z1}vdgI)!~uym#s5!1)+(@=V*`fc}iq{k!1DpK16}nD{qUT_J`)NFv~>9%B!<aK44F zmo?!7&YJzuL%lZW-oac$MO_Q<S>dgD_;%N+OAH4Oels%=4J;oMR4Cs!A}ailSMYGJ z{RGg!c$-GK=ZHndgIj9>I&YntdB5PxwOF||&_L)Kq1S1LvJ%D8OBGDk+X_I7J>m?( z^)H*&Pd}zvlwRBkBau!&dV*u5;-_;9cmbJX8~_<^omYa6+x8<uEEb90cO*dBd=fRd zHREQ_^cXltDP!Zj)BV#?({f(o-8&vzG@G#d)ssCNjyUe3m_ZHRpbKmLxSufr^nnbB z!-Su5b|Szut(ySsYW>*^z=q}Nc6c2FHW-QFbYA26MqBm+kW-(*=Im_&J6CwGA)Za^ zQJ`hrgh~@%D<k15s3{H5*naj$^sOWL>4sm*2{w4oq*u1tpq@!9$}l$6vv;b6X_{WQ zX`j!KOYw?TCs>J&O9CqRvYDq}+LH)rcP5;Dws%L*EM&dBzoJ50Qbg;~Zw(&~ZjglP z)JFVjHS#F%p)oB_-4+XKA&L(PF;$h9AGEU!J7F0V_2&Rt5MSx`J4B}htNB*32)v|} z=vZ;uvf3E+_2uIh&}gsTgrT<0`cOFN>0oq>b=kHNrl&P<9~&gdW*bJz<zL{itj&Uu z%ZXu=8W!~S3PG<t0Yb@M#pmTYGZw0`@!dAll*EcTKaT~dK!lWW2c*vZ=r-W=d)TbE z8da2n3;}C2a|{TD{9D*o1F!uu_ok~1Bk*`Ytz!)w1K3<qBYALph`i;a0@OZ@!XI2< zX*(!9RXTnOP-d=RA%#&npeJ~ACr9#LTo})L1HFqt4o_iU7IwnOj2}Jg=l&1gBRs+? zeQj%Y?uBc<%d&#^4<GS|$M{-}@G>dWGAKv~6-s{v&2A9LtU`DO1lC8T7!j*bZA1A$ zYd<8kz4nT=Gfz`qD8ltxf-)wNfec%Of?*`eH$8RS_dSUqR~rb%tGh5YUr^V9@CJt& z{=V4l36j2K%LclinxBC(LQ@be$H7=S5j?T>E@{UWR_JHo(G~LLG8pc-R0d&R=Q!5G z=$L56v8*QnJhavo912$^QI4?M4k%JA4a&zlS3B`>IeSU<@g-YDnI723oEw9_W&~+* zQy4LvE8jx1WB&wEI(Z_~qnPt(ulgpK+w$rUHz=B4%pr;u1K?K1LrgB$6en0G)B0Xg zTx=Altb(RBBoVNqDd_Qc=lQ>X0Us(uK}AbUMQ?mtd82SkpmmlwW|U+YiABw*big8o zWAtUJi-I#kCG~+1reG!_WL<iJ%=GyJS&vsqEv=ajGVEnlCtD|Rd6#AS=WdEd8{wh6 zT{K$s{#W9p>~(jbb$bZ<X>S2N83v}i8e<In{jMa^G$JC~qrkB2u*SGXUPI0h9zxY- z8N+hV0l-_7iRbbC6U7zSTCv0@u9*j92pA^S{DtIK4$>&JHYdxgj8Ur^dxd#~dilVY zpCRMXe)oB^7B<(WDaDnJ8rvCb6xLY9eW9s)Yxx++T%0yLY#XT6V51x{^0GZ7v{^M} z7r&E04gYEUg|HXaO_7eBa!)@Xgqz==#`OnFdiNRr>F<^tBsoX`6*~BZUgIHLSBL-x z0_>tmA_7AoHAFag9S5;Q7=e@WGZm#E9~y472SOoee`OUTal@zkPIU4MOueSGphY3! zV#3lD;7!wwU%KAl*ocrJFiNt~c`zfP`vlE~A(ZuW8);X(lp+Wj+n_7z{a)b0v_G;| zv8tN>LsEpQSDmx=UgT@uAbVeZxl=M{BG9O7sF0ja>$!3ut?fi=ih+%OuExz(g-~_J zTwn1i3n(rE1zb$hXQ|@gqKq#0PNCRwEuko8VkGpG&PM`iT#nVdfqZZKU5N6NSQ$1v zf<F3IZ$uPjdFAl@bF00x7QIDO1Yf(w@1c`E0=C3o#eLDUO*TSI`(Zym`J&%Tz4n8U zV3MpoM{F=eU`BWJ;4q~_2$AZ0#dmX}L^{<d8!HY}LBp&Ld|O^&CZ&%$@<g&;MCE{^ zVQCXWY!KTrV4b1?d5<1Te|+O7c_*nn1QgcWcg_1@<9;XRbjuI3;EO^+UtxZb{l@+> zusi-11TEExv3l<Sm;(X#VRR$qU1sHT`D_?AkNe41^cNhUTM~KU1QaOP@kl0uYM$@F zcP;^he^hKJ9-a2gG=g1I)pTR)33e#}cfij81zP_mHuj4|S6Rz=KPi4@{ysVHTO3-( zork|Oh+1U0K_aT%7g5be0in+QJcV22sBfRa$&gSDEBGF7xjG%mMk0|QV7(O=EWZ;Y zn-lNa6+qX=cK#{|pHxQ()(er}L&7zD|Lj<ay+vg8$qsMtP{WY0rf8j7(&YmW&|lYw zZJMgT_RJF~Cm|h|=-$9!xIdPww<7Udh!=ag0h{%J<kyhNZrEoUG%SZ;0Rx`qE(60^ zjyFNJ`U@d(1-gEWhDO(TjbnyIkJ~$MJ7;5>p|&PHmZeO#AsenP**yFTOLK}5c_a)= zot0$E<tW4&g;wpQLg$@Z0P+2#3_(iMh>iTHH3|Ne^ZqOwmQ4*cOSbiYMPYZQ(NFS~ z%(wc>chfwQ^K<if<eyn8Mi;BH39>zSl;qDZ;cc_a9UL8B8l)yKzm<k*rNjeh872bV z3Bq^QQc`l$o1q;8iAk0ICGS%ybt_n7b8n@jC^nHty!ganWhM`-Jg#{3w)#S)r<b<; z<a|!Rx0Hl)<}{(>x+|Ec^b{})nqPo5mO)xV)Iqc}{XFHe&HX$ckm>Z6r+u|MM&eii zoC!)1Kt`wr!Qo;t!LgW7jm*Fbab}x^ss-c~!|7Hp<-9Lr(c-mYTO;=tQZsahu!ZVW zD|AdegS)<g^J=Qad&hK}N3s0_E$^9rXm__bA6i$TjjaxpEUsyGi(mHu#CDIkgaM;L zmIUF63@3Ln2-~j$M?e>gjYv@o?-+6XhsIH1bM#Pjl2|CeY^1FOk5mKEYrYGx$E8R6 zS~mJATY70?sGSR@T*8vze`Gz)-2r^AaTc&?oY}2lF6&Qy&QGKyja-W>bQvS<e>(}Z zM48@=&!v;3tzxQTq!qax6_2|P<s?LHnnhWhYW9xO(mUoXPuISLt4euodD|;;*GO7S zP1cF;%$gh`IiV(jIPNPl<fpR9j+d?*z{|`Qu}PS8hcz2&#3XUD6{YEvoyW$gHq6mr z*KF_fO%JM0E$!m;HKdf8b<9<zR3v$vCj64fH@AyPD(@Lcaw}sok)5ikPvaC0_>p3* zrFgz5(#OONeJ2ftRIdX4SQujF(B0{k3h|MqQBbqa=4=x(&bx&IIl_`0<|i0+A8Orn zHiRacnbpmU@?t<NJ2e|sQQo6+4k+8|&Lnfmo3}r(>4%ZkO-hej@r-Df$ASaOD+TA3 zR1a7i!RiYpz4v|k^L#oxRA`BB2f9I=$=7!(<K-nZNgRY{;Iaq0C@;Ed7RCreelU7p z^oxXai#RXUAGyw0KH1svMN3p%iseTcGFNzeLp!tC)x>HyaWgkdYB*k~&~)+YX=;IV zQcR(-VfMlDWIWHT8$LN_8A{zytsNnw+MV7Ad%g8SGkJ59Y<YOY;1f|s5UTt7n|3>I z0iD?D=5Zz3agn}Z5e^|q)r?g)aE6+UZ+c7D&j}+X{hjO0{E7OpI#-WIL_VUAl&XhD z@M5I9WLQ>yXX#e{9^R#Cy=S)=u!#Y92sF1U1Ij?~!nN1RQRaAEN{*8Bpo0zD^VX`b z5dKiQd!B;|o6X@Zi%BnjUyG(qlt)g75++7_T~`2`W3(Wm6giDp`Zy&v@0&Sf{M4}a z^C6?PHoq8Vl&7+M-rs%Jf>8L!%gu4v-clB)mIAuYhA<*uBgN29BHAA?f<?repW<_o zfn#1Xn*7d2st4HXIAf4FWz~pxfnwPZnoN`rRM08<m3_rzvS{fY%&+g~(W?D^QBI4W zrh72Mf<O;!G&f0OO8o*|iZ1%?o+R!0uQrsSlVyK(5Q2v%-W@x`Q~mLjY2}J1QpU3x z6+-!TcR>hW(Lmtoev4Wil@XT42h_}4@XQh!?|Br#`?!JJn`Tx2aw#*b)itV9R8PeH z=hT}z94xTGqe$=TRXoSS{ud5C*6x7=N%e~aF_RMV2%<)cqAS+`<3IiL#U{wUC0gt{ zmKrPsH9O3C6!v?FhP{X`d}y9+z10VdDCLf8kaK3+N$W@3_roXqY@Gt-l3DF`0k&wr zjYW$Q#&=iByj6<5GpymV0%eoTl#Dt9Hl>18)1!|8t%}-xSa(V2xm}|R;U5``?TnAE z42$9K(3BOTfve3Vh78EmiI_{VT+Wrmjm|z+un@cWbwqr8lu;fdyECMj-O<2u6CNM` zX3K_|G&F8p{HmD>X=cf?s9qWZzt|^HCO!Bacj_y$q9H@W1dX9cS4?$(nRD+-ign=y zO@U8tXJpgWPKObNA1k-$?JD7IWxV9Gq)__urp{-bgDK(mP)in7y_JXgbECmmNvx)i z4?Z`dU`!o@(MtV7pQx4qRmf-zpiFa!`Q}xM>ArECx=04!6c%t~XF~d1D|)WZf>N?F zBqo(2$WALQx-ZK=aWH5)p25#!9yY<EG(O78VY9YT08UQY<2a)$vgo?eY1K&N<WqLG zq}UG_#z2N3sqz8ms$ovL(D6j^n1RFS251C~$B^S;KIhpAQcK-Sl)aW>Pgf9{Y*s}d z*?<?_W06gjneUh=9>08mCD%(4LBZ{BACAP9a`4^b9d!qA1aym(<tyf=Z_C&8)>b`1 z?)7z_c1zDXVS>AyPR}7Af3i-Y^WiYGpAVsw;89#L+h{ndKXC=N*bka`tgXN^so(X! zS*4E`Ririii+kQB`bq~vCShs_IU^Z@<QEb?I3G*_fhlB`yb#5ZnI#?SHSaP8qOdDT zzE?j5wz)1Si|CZ$BDx;RKuglHCIb_z=yFKRv^BEVQcTEknBrNjXlnP7+lqdjwpRn* z5-D{t@@kx?f@Z$NQ$(@X$cTMIb9*jNs38|1!*d?eOsk0uizXGrx!)tZX!#-s^TW*j z*+i55MxJ-y1W4zdX3Z$)@bT26<nd~KuJ4Ywujx<1h<@1l3+4+>3&yjs2eZLAiP|Q? ziFVE(Ug!ttCS>{yWeMg+kVHRiB;awWjD9~5>2-%BC;dc(TO`+Vf>&z0&;wc$P5kL_ z_XH}LBZM5s{B@L-<CaA{Wa>1ak^H}=*}bwduKyr*6%}9^0tsu`k01CvhB|YMob7u> z#6@8qUcD>nwV=%MBE9q215kH{iyKRmU9Kk;x3qLUFxDc2nGKiESw=kIeC(Q(jx=St zVh{L_rq3VHg)k>|&-hPx5=E+I4D@eG;Yn6%0*-wXT=!=DsoH?I$|X{yP7}qGLpqGS z48x(n-&1!<<rxJL?;}Rv_w;$Vj<tC!$klq8`eyRR(=yMEw_TK;O718Bw!=8HVsXlv z|3l+l{_z)|gg(4K7O%@QuP!Yj%jsbA3QbmxdDGYE(*QenzE+R_;xX#gGQI*UR#Psx zccJ{n-Z;!%QK&q^-xr3L<G(q4YnMUSK7(m)R#YFSo<3wWxc^`UepJCwI@y>w-Xcm$ zZB6i4kWLULXsN&5yTP)@<vC~7Fi3&Pi8sEE{K-F$G-XGRx`_FqeeUz)B4OXeWRO$0 z8ifn#Egx62bZeSAWi`Tutb=oSxVR^1l@9+Z96xnrF_asEL5U*~q!oUVI9Pg>>rIK@ zB>D&*LJy&yvQ+eQ%$|}$`flq+@FPI)A%D0gwHlGoE0ThCe`MH=G_TXfU5T;`u_X}& zmz{2khdz|K#G<{D8ExODd7Gj}^pp!4OXW8Yu_$GzvJ3dumHcv{A@WnzN7%ENnC5Tq z*~miJ7lVv*`99*}RaQD)=wMxt4gJzyPTy<<=YvFP1lv+;(%(km&-mf&$*C+@UxgLp zej6}5UJt+$4@x+VG`hK(z7^T9Stm3{w?ERk+%n87Rm2zj($(@a!!4{*h9oMFV&YOJ zsVi4SyJlhq?Xe;wxdO@VYR=Ob*`@H9$4>@7Mm}3XgSQTc6k^8CEYZKj5Fw|J>x$MG zWZIEnbx6TWYQKo621Fhb*(wfs<c(e&41z){F<~u-fY^u}XRK0Bxb)lfL)_{oC0&3G z$~3}F)>`2s+oYcwoseQ1NZguiBTzp?+m3%Pt2IbW$N0ci?Evsu^_Jcc4OFf;oSUuX zUJY9;ek;SUdowO$Jdhl%oeS9gFgbxzPMN2tVV*9!DV^A-K15yw9Ys&8GNwa6SC$5= z`k8JcgFaV~q|u~@ePrU*J$}l)$5bQQ)rRZru<*URSC{hs*y)evl-0@2F9+Yk?z6<= zFGlj7sg-auz9RiN=gtpuxa`N892d-X=YXXo7SKW4McBR;{cXf~M9ie>t2lmxaY@2z zSnOf@$+dd=yD7aBep6KJwf-wXi2;V5REmB)_f+V(y8P_R@R@g9xj!igNFPIH(c$D( z%}YxeW+j=D*-|#3=#*8WERy2!D#OqbKkMkehNn?^Cq3%<Vs*dxigcgqo2kU9pTDd7 zqGTtDC~eF`%vl2c?%$cJFe9kqzUE53+g#hn5GP6VcCLx?7yf$$zeN9!z7Rhxzi|@5 zS=;bBlJdo<Bv73%X#_Mbd8Sg1s~9zbUv6G}wgBlnR?a8t&o}x_N>A=e-8lN9t(^qC zZqq-Bwo<<j*i1p)H$np_CWAYp#$`<DbaF7v0>nibbLdqfIxW_ckCtf;*8^rTaZ(J+ zxlM4l#qsCAp}hL`e*TAe!w*2(ytmla65SE?`L0N#KQ{g=S_U@)r1`{&%p8B<aRSoa z&B`}cd#R(Vrxt7O?xo}x>8Nur_t6j67b%8*ms*AE3KF=1kb7$x@aN&0=?QXf9QTW) zd%h{Fsg79c<~I)~jPu*Gn?@YHSW~Kj<jt6Fi}+>IwHM%%nvWsq37Qd1!DLKMoP&|- zXVD~+)ahw2eoi2`77S;NS{+9=xfb(gPQrd^s55-kt)XXmQxazPQ`o2oDq$|EUUO4n z+*Wc+SN%eBi^@!0lVp8^B^^Wc@L@`$o**Jx9|d`*m;Z^~XF2C;_R%MwLtg|`v|kqA z$xNTZ?1kvGmjR(!N*D9>c0tA(D4L=!Jek)DNPB;5-z<}5F&|6(#4+gY44}5yEF4wi zw0}8{+#PsI8t<znk6u&de7Gn&&WRZ?8@*{S8hF5GW#5UP4z1U#4HNZv@4eLSN$*5z zKdRkGuR<o%##lb~gZvgS6-4W_xh1*3B3lQ@1ago(%PA(OOuuPwuZd09yC1!WnY(>? zl6JtaJ^7W*Fpu8)TS2Pb2ee8(<f8sYT<)R3%aG&$t~!A8?!!odHb~z7N?GSah?q(D zvx}@HN0uKWS(tt-QqJFltemh8hpq^zwTE7{+!HL?gI7sh)cZ6{>4pHo)PX>wd}QA= zOM0v9G!H&khiRFxG`ohHT>t#m#<JZlmG@vqBO~1A?IW3@W%5%FO)<Njwpr0RISe%Z zI2G~pIe4k7Q;rF$C&rSplhL8!*ZV@4Rhld*lL9z`MAcP@7iz;*p)XYe)Z|w-WKsoS zI3&@j{&v+;LFTxH$oO32Mp_OduP1d4B^cJCU%B7bp1LQjnwHG_qiD?$zXfruO-=IN z*DSxjGd`_1#20GsSf2Ls49R}C+b@#mW~6n{ab9q=60_FY=D*w`{Q|2JDUa-5Z+=eg z&zdsZda;pG--pa?lK~FH_LlFJ3gw1>cr~7Lenq)hv=JU&GJeh_m%+DSkSN5CQ36fO zM*U167R%?M6EG{L^LzI~B#$E4N7(7+!qbO6W;E|OC0>UPU6+(p+=<A*fIi!9U0NQ! z7~l_nqcUzAJ^s#w)Ki-WBQhESXZ7^{74^0l-?p5WcJbsw@~zkR#p<1tkWs-hY~q(C zw#$<xisY6ss}UdWRW`PYH~Hp?fiY>$amtKMijs4T<&#NJAsr!$<UtB-dzmQND9ycg z575k<Or901s8%P~e5VR)(xj%YZbmlI8l`md@Zu#S%LZ4LE7eKbz@}g)5644y1bwHe zM^~WEKf9uLoQh-EC*jWI1rpc+PppaVRqgq|qsJVW$qjnq@L~+KvzhwS*oQy+?SbJ8 z^(~%Y5yRqY`AsZ3^gJ=tIoa-|uicVx-VgOnsccBztP}O)C@RT_7bDT-3upH}puxjg zA^I3?I9wc*&l$tYI3&adXsg=Cmh{h5w;T+eqVFU1SC86Zm;G9_Snw)vn0JsOzoD^g z4q*@}9L&?<kp3xPB8VyE6-~4??TOQ14V#|N2ha?aAb0dl1L9^&0i<R47d4t(MW7HB zEJ;a8O>3mRH5|lJ&goKa=~df}WARelx}Gd7?8&ZHcUL}Nu8_TXAM<P7-+Hq_VIl<B z#xiCZoX?7g0LNfa+Rq#huWy3YKO=J-1&J;8OSK}Rp|Z**W<m>Q8fCP!4cB?4<A)UC zyhW3?D&NjV+;T*e4bhFFV>O;k$W0*$6%p4a>mEQzH(xSuqwju6za;aP^+L%ScqA5; z))iIx-ALN{IgC^M(7=U-Iq)~jJ2^t220@awuQ-SMvv2iwrdX(eo*+q765s3gcK1qY z{Asy()pK+77Khl%G$RZA)=uK|ZWV{9Qvw%hnCc!wU9-j0vlvkc#k4O?l5MG)cIZfo z{UIdBuX<@k0$pe3*F@ESpuRhfnA98QMa&+}kRoOo&OjXgnt^RPEEW-)Mo}5Z{{kz- zHo)DPmOpHZ?>FfHSAonvh;be|<{72_0%4$_{Lq8Tk(a26O9)$$tRqkC&3im44+%%5 z;>TWjiUg9U8=WQev!PMEHk8{LTADkFVyn2Q=}zAxN~#{^;)`i(FY2ODe?mzaLR7s& zTK{;$7Or%eAX`)kt+!{cPkjC`E%&6gcF%#kd~7XusbIHZqYh&^RU%+xEO|Aw{kPRW zoJfIKMA(OB89O3|OdhY%jwjrQ&WYAB_Bz_gusy<1G{5R26k_v7a6d47W^o)n$)B!0 z@H5(bGL`&14-I-bR~KFZP4|C~S9C<dvE^OhFl|XYSUyQyxLb}h8wZ`77UgWta3F2y zP0GkYQU9$~fqzyO5~D)av(GvW+e0C65{}{H9=GAG_TTxcS865dbDU-JC(kxige8hp z2oGn|-1}&-v`9u3oDWn?&`rO`gf-tw*dlq5vPPCX_5uU;8g3-f=(kP^{F9CfvJsML zB)_qOj|oNEx$vJC$lONIqmn>)wD8qv9{<5w%bZP2d1uTUtUVgXpouMC78)fI+*3l5 zP@AT_H`FNVS)E2^W|P&`D*ZEb1^%!6E0gYy`u}o2wf6`wLo+)==FCEgsIb0`A&&S6 zV4%tCjP&*?k`p0*mcJT9IbPO>hgB~{j&iH@peL2{f5V<TB-zz*jWfbLEWA%GHQ^Q$ zZdofDqM=i4;asGl2IL6i0}+ie2nFAu{BLFGzkX1Ve0}MAT-6eySb(W!Pf8U|Ql;js zelCCDxAu0$K4iy7pa%8hqZnN+vpDn!bL^yEWNg-Nm`N;e-_!Z1=l<d^@?ciKSuV&k z=vs$Hjng}f$8nE5hu3tVDpD~$+|yY!J{q%{WDOSmw-^8V60$=~wd?=U^dtRHBJpZ@ zi$*b_vajMH#@qrH30a?YOwD1|=tb#|UG_eoiOj4~{BEg7{Ufzv=yeZ#Tm|2+KUhf9 zv?3vXAthOy>vr<O_3HZ<qqx4Ml2aqmeCvi#%XbrXiXTpma{q1M5g;1aKKW=+M@*=o zeEqRfD5!m3qJE^;R1(#0QYWNRaNo=|Z@y+axqq>pUt(<H+EnV=gKF0BE6|)JgxBH! z_q|v?t|U}d<JB*q`hqjfa?EZh5Ii3`{-icT4r>{s2@hV$KzxTxhb1p=_04LjyxbcD zNgX#b^%6|Ne;X}Sgxbe<Rbtki^RxwSQUsWatNDl-(N|PB(Kp9gElvqgNeSg}kK?bx z)$?u^{VcfFxkuC?tk~4QaX9}wAd_O5>Ja1XdR0sv7CI`;Tf}YzI3FHJCON016-S9i zIoXI(h{hWV>^3U;gqYFF^Z`G5>)-l^yEIlD>RSrIB20BrA8>4@<!#tvM=d10Z%k?7 z_|Qkjj)h!4t~oP`ce_cYU(zb2WRFDn#vq&Q-=8gBAX5Tj9Bv)sXGoQ@2Blez-U`G6 zeukVt=>!eo<<t8v;!o?6#zQ;jTg;LcnBXlWZx(hcUiC`Ihx~Tey}MJ_dx2O4m^mdC z=_6xio|YHFL`?8-oW3ldI=H2z>`0cJP9}$A!c4}W4-ylx{QG)+s}D(*mRF&wi4GS` z$`b;cN<fC10~W%-^ZVhfW*ze3%tc6u@xi=iSTl{W8wZ1)+EvfH?$WvcwF3WV9?JX$ zcp=7V_$t{E*-<Z83;G%@ZpqZ-Rko}qacH?$h^RET`;PF&0~&ITWaG`OFT(2OQzlbh z&+W`q4H~g1YBY?5Z9eaj-tlVLS>vTO-tN;QGbKj9gF^jr%a8M@-v&b%h13_&b<c9! z5q7eoMn1Dl+<)^#Nn6iaQKL$_r~9WoyhA6BU-CT}V@`5{oAmYmYPB-UuApby@PCa1 z&fQvxTqJ$onf?Y*HuRxjQee$#c^cWOw6DLku5h7iI)+6V$87zSy_HoNT8!S-)I|-# z3I}0y<Nvv!SqiwfN{-h$XOcDp!h#&h!YEX<N;}mmjwRJAMpPIle4^Hnyqy3pulinl z^7OZiI7J$WuoXP-x$DW!!oN&UPv@?3sq>X~v|d&vKS-5|QJY{YT$m`FbP6D^6cv25 zZR4L=r$P&#|25{XBkv)T_x18H^b&oI_A18CqnD=9SBFyT8}ih}ywT3ft(`CBlXCnP z=Be^ov{t-_-y+KPKQ0eNxLbTRJ2EO3NJy~Bt9*f|=y^NF3?5qOl3R||6>rOP8de~P zVX+4C%TZN^JuuKhPJVUR(Q&drH$_J?`%BvJ(f>^eNyI%G6@2dm$DkqejvX=mgV9&g z!piZO2z5%xz54qhi;DS>;-b(nrCU=C%Vg7|!X|1B!czkQ=I;NnBKnZKT^Yu87*$$N ziViWB;w!(r@=Yx*E{?gQPd&ba4gq!_qC0w)JG9ar(qWpdd|`V!<Wwp&<`VVZ6ew#0 zwC`>i9<%fUP&}6Xqqa-CYk_<5=c9rek|^r?R#v!3CH7Xd^RF@A<FUzqE#3|nRQEly zz{-2FGPM*IyWYZJQMKA%ncwN4C__c8B4HwdXs@0NDS5&IvZ8<bU%hCdyFiEQ5xLu( zTydV`;vv(v$A)Xn8<oOYzuEkdOb+#ZF`K>5)vJcTh`(V%JB2<c9|Bxy!qIBaCf7&b z7%m_on0Qyqv;zpsWbW#QA0Osh>d0NUEh<(w9TsZwY*t+t8#W8(?9(z1*X_9ruF^Hz z9x998-dvu>vJUf%y$iT^m)J7i7)Vmo(P03|fdf2<vD?7*ZeaJ8BN7@+XM?#CCnio; z);&RC$sT5dasKDif6NZNcPQyFEv=XnAKaW5wypd;fBUTC1`V4--&f0Fl37v5|D%@E zO<MIvGp^*}0(<P^`H?)0f^1vXkzrz*Ws10R%LqOd|1oW&K<JGuyIkZWGMiz?EYrhF z;`P6xgLqL8KF5oC@SO*dfG1V$1qmC2BUEjkPjkeT;#5R<w?I~7AbE6GI*m&?f@_EB zV(Io5B~Xlto(Jr{qI&46XrJkIZ6#>wQBBhe#jr7xx4EF3OYSL`$8Gb&I>RB&`7w5j z1YpP#mY}Tr+>SeB7?iTLO+d}9q#EGBQr34sb1#{8i&NdTM^Y{6`f8Fcqvzqz%Rtc! z!{H9OhSOiYKlt$ZE8rub6O>E4U7UYfq}nqy@$tA6?Q$s=N&aG(k|O(qO>5rSKKcjg z2?c>|3@J7X+6?@gR5glp>|qSe)`hJ{L#lT3Hs?``E!HH@_xN;_Nb{b@N!ETCA1_{1 zQTg1y7(I&$cX6qu6m)QzlQFiBw4T?$%JqNu`-(7tA=vkApo^Q1>i==}mSItTZQHjf z(j_3>jg)|NNtd*ANem%9bhmU5-QA6JsC2hTD?Ow%4E3H|*I%#ee%|N)@_b^GZJgm; zv(9y{bsYQt+wspFUontNJ~g%mBxAA2t>KuAvdlezOm1eN4p9C{eZnMX75{`5NA7#8 z0`y_I=55;!B2)5M4u>95?*~gAp04hIjxTK=B|5_iAedBc;Fcw@DmAe=9USlp<Z6@{ z_+(xFI`Fo>J}2@Nv7DmO_J9_mcX7?>sR62E6RYs0KCI%%{8~qu7{1ELcqL!x$?Y*u zQ6zVC$nZ$=f6t=uw^F4tze+0K>!|V#O%au9p!NuabW&Z4oK<y(SefqGw7wE8U15|& zn(CbsVIJ>*wKTA0vvvuX*+E-|&BRjZNZL8&G?HpcD(04?U)jRzRhvMnp0#4k&BV1a zC$Aq&pNO$Jz5k<|nwa|6-qL04Wg74tfyIrktO9*gMxdYG_#^(YR}BcK1*WR>+pIr0 z(K1sunT@1S0_K+d46l>Ht;47_xKw1(mahoJ13>4S4IrME0b(A+DPVb%(j~%E{V=dD zqpRj2G?q0L9=pvFT7M~2T^Dx>7-t56^f6GL&-Jh&5bM+)kAph)AuYSzH``Nf``|#Y ziV1=~c<ci8INvPXa}#mE`154Mvw?@?&HRX>{rpl6rL;G<bIq<}Tf61q*tL+m9s;3N z11+*7Coqj2s6kj)@C`0=&^)~(A<0J1`L$tWT`^~{b18le?lFHab=RYJrPzrP7izXv z_0q}d<R0mJLD1`jIb3l+r^V*KAGn41RDqg-yiHm&tp4j){cK8vO%5~B>yTCgNLlY! z@l8c%o>P;CN*Zc`XLlREv#Q#%<74ca@uOD1j&o(OTu*>JKCa-WJVzq8zcA~gz9kYM zy@_WcYv?Tl10`FY0Blq_B)PR$+z^Why)}K~!WJMfaRkqEa+oinFN)aQo4J03qYhAq z<I|jMeJ>t1I?WCbN4W;D!Q4%|EgVgPL4LiN-i3)8br&rt3hh@r`7tAFxM+`VqKKO? zB=T&NOuUHTy`9N?bj>w&4UIBd1YhWzSg-x}>4NTcHeM2*dL!H4vs|d9B46Ws%a}6@ z5VG0awqS9d0@&)NtJDE%_tfQ{zgv?UEb7?Vm6Q(}O6=L&87n$G4lH$-ZCRW|^|h;C zLN*7JMIdFSgwWP+avUx*zMy^^%{Y-PX9*Q-2tK3e_3hs3P&iZNE0Zo_+Jhmw;lciW zO3%agxc5mjGOC#>_(v{$5rNt%BLSc!R>Kh444vn2PJCwvfO&g<E15a8O?Y()uH`Ts z@jIY)vIAV*OJMowgzX}8?xrpa{6Ej}Hz;u4qO;i?vUv~msnF?!+GPEV$Q7q^(|t1% ztKHg9`o67$yMxUl1}UayiqoyL8X~2$+zT~*hr71#u)ZyP|7u@;F2ljapG(Nkb-$j4 zDfh;ybv1rAKz6WX13)dSjWy7yfN1A|a7LUc^3osWr;5vQA|xk<fTmXhc~AnG%}U;r z_8yy-2#5Cbemfu<q$|Tp%}7g2dnCxcO9Ha6OaTCxq7)#_EMdB~wmE9uV=b5WZJ1u} zNyrlN)FD>S13Sm%wtb)n$ao@-CZ_KiC>e9jy%`*m9(8gq)#+0|wDhCnGX?>VQ5u60 zZwOlUCGY@GVF*icf=>0qidY==09jN5phlSg>eU29!J4-EbXiKDIQ&ppzB7D)X?6#* z`@fXFxj1mtf+|A8bgFc4HX=y{xcLCw0=o3>F6LxbOnky1z>!N@0uqkCXRq&hgN4^4 zInnBY27!ReQ{Km(L;}$H*UA=L2l!e83$H9wtpVaBvdJTm21osMf|?>9t+vZNs8R&> ze2+SsmrAAZ`@&;4Pc~cFJDxU4iwX`iiZiW5(gF;`7t)lS!64?{e&*HiZeXD7MmH{e zV~tU)x7qyXYlUARc&gn|sn{*vH7$QQA@Px;>}F<%)I+w2KeaTuY3UAJcW|Ffr%Uc7 zUbl!GLwl16)2ka5)}%8xaFA97ITnM&5ry7tS;$~)q7S!}tOgF^byO)`h#aJvj^mIk zH42pY)-C(s(_^A}(x(=UDj1dx?ncT;m^Za>+C8CC!%1UpvSG|s%EfH+QMcG1$p(+@ z@IyVTWLL6oZUZ?)PzJNJ-2ni064YkL1(4Byjw)<9@g^I1FE+K2hm%)cMk$)t_vDnO zt7Sdh<<ExU2~rKep0Aky<P?dh<;KSDpetVhIBFw7;k!(qzKf-*E|<P@YO0Pd7ZHR= z{ffgy$>2h=8sCPM9h@FLN-5uxwqmR%W;0E#o7=nn$@mNqMQjf+Ayoho+(f^&0&}C8 zsC^z?R0@=$go7f=KD-pCWo2bx8!i`6^h^L!VRVyZ?c;v5g4HI=Z7qxh`4h=*%gHlF zDcylqfunXu?#<|9(IKcAr-t;pAYH6)!==l>F}o_}NfaMH`(9Am+%L4RO&js@3j|Zw zdg8xDFD7}A`Lbf=r${HFKD-<6-VQ`N0rIdI6LJOIxBK?JkM*X`TRyp+ZHof3$Ue-^ zEoJFGU?ALO^Yw*~&t==Hwt#(rb)ns7GzAR+WY|p`6|;^&Inw;)%eG(pS&9!3ZLml{ zf+(_g_?z2x>uov^HTZf-=FeEZO_zLITDt$k{d{pRn*@np|Kr@U2?y-HTHX5z_@qd5 zoNn>Fm1Z9NV3n|}=<#~~@{*12ChNqjPNBLyp}wkh7)h?+<)Xt^XG|L1^ZWYfbExUV zY8PbRc`9MB5%HF9-Zoo=22=1<iJHvHxifX4tl+zoOJ?BM-1}@2)_HeA37Z{DJHQNA zRA17skY_;sTsk_dd+o$Hg2k-$1!`;6%?1wzdFIOw<c_3ZpX$BsTkg|S1D=)<Xy>Dx zT`<h7eJA6?20wMgB9JYfvFr<Qflp~fi2fd~P6OTwv98FO!~(`wMPH&G<vxJM|6atU z>G{(+B--6`qoY%x_~yejoZ;Nq8eX#Q8g}SXQb=eMqQ<UrP2^%RD<_%xBw*g2RkLxl z3OAT&^i+F{(AQp6Nj4EJg6+{bqT?k2>kf7U;*#SL$-Q3VE2+N3a#WjQ3vUT3>CHhS z6a3+l512HDK|>J6fE%vEUmpoA9GGSUlz@PB!&Ix+cUX?cfX=_+Vkuz;Ho?8@el{t+ z3GneglYUjVOaQuTDQL6})~>%D$M~c}V+O0{K8DeM95g>5#21Jt|7^x;MrXTiy|nI3 zz$p+;ZvO=i3@Aeffh{>Tz(uNz5`W3867iPsjfL`e^x=Z=-f0rRSi1~Z;Xqpm<LKU) zB)k(_Jzgzl+cxS`W{&A*OIayQwfy9s`|OUh2yA`%K{=17ECBiUN{&uvU&+4PTL)Q4 zWlzEAP!1~`J1B3cQV?j&acd0Ob=|qB<V_ty6IwXPv(PVnC>()pAKvE;2+&zVHu*sB zVE@fK!(+gt;$w>?yX@m4t?Ru7H`ar<$)^@$9!!i0{*vtzraNSN*u3X>B+Fv52?X}w z)B04BbE~f1;Qg((SfnHUj-DonB#inxaAWX5?-n<e;GsgbS=hQ6)rnaCd4B;;X~>bS zy?Rbwwz!H(26RKq<zrGfGm^q6;&oGMUB6ie9-I%^SgXUwAxmEV-7Ls+%LHv);BPhI zad<Oa(CAV2j-Z@)8=?qVk6DoSIBYFFIIJYwFWcHh#Q!9%;W{V(Wst6|w2gHQhd<Ke z4nXk<8pANnor=YvKqgZn5T)6DM&?9&?iV+fDUjZ|-ip=wvK1#?nJVH8Q1PX+N~G?6 z4Bi;87Ch(Y$V_Kv6lL7K=1|Ie0Ngd&B~)7#WU@uloS05_-2M{dpt1ixz&sX}q+aqm z5j5aMh_)QPs2iEzUWoRil~}Bz{+&}RcTP?0x5$-|l(p7=kxbgOkhbeYX_hE6)neWq zQEr?kS1DyW^PqDt8J!m(=Kn1yUb0>MP$gw1N)xbmkW)|2RQ@=bmQluBiz0yZgzm2h zwM77+xy>@l>}StEEdx5u%dYfqPubmoSEFu_1JqOaR6u19=nc&|C=TvVlDh~jcfp~E z*XgUbbWLAJ0H=^C`y2125xBJjz=Ok;id6+X$Fg5I%}|P_kpkkA?`#s3wVaec7#;xs zj)@%g+@tvVvjUSgLrQEEq$@9dsf4R!&@{TrBL0^*yRFjx!srhfV1=zm1C03*`#>}* zJ~3T`5oac#qgx1lR}C+U#CQdSI1a+7R<_Nvz0Dl>EXA{11MJ*h<6#TbVFJc3ZXT-f zZ81GLdImy)9u8iAk@HYa<ol6X9625u`VAUy%0Ty;TI{fGWZ46gUn65jJ&PMeR7p_* zGvH~-zP|@D3r}DQs&C?YM>kb|<bY+BYn;C%t=9Y4@H0Ahd{8K+qcYr@Ub}8Oe98bH z=0t12LDW{Ow-^oE?UK{DFF2+zmrR7_b>|d0G3rYh>iIOvxqim8sD?L99jlTUoDJi+ z?ypvlyE9M}Y)n2|0pT#Jfw767IW0?&ieqPz6D6C0;MS~p^l*LU>?p#>oB;^x2)hM$ ztf>kfDM99dbC%)l8h-sOEqP`*@6VkQpqX1AY%zyZn$ek6dF<7y;%ZIJFnM$joOXu* zDc0P+a4IJ1*3RS(5ZnM*Q-Vjy?^e!7o(mOU!z+X$|NH!)HGpM7CR+M20?Js{bNfDh zhmOyCCg6l*_8d}BuInA#ET2mB%DT6>o$ErI11uwht)kQ16l^AxKVw#0v^oFky;W^c zT|j`p^LpIJs7pZCPbAv=L|IJhd2d-Xy3-rF+{8F(!tdc)++sv7N5VIBd{q@K0Z-#D z0a$j582s@yP^#F*<%iK5MIpw8Sv#lJj_TA<(NH4xhH&=$1hQt0&nZT=YNaSo*o|`g zU$Jh`;3Z(0(r9KV(`o<e4aY*2k>PY+Z{*jKt*b+0eY6c$00IZPWOgcYD|raV6oAvB zdeq@<I*$J!QQGy$(%(UZrww8SMUn@^TVX)H1H4ypByNnj{*O(4dkq}@6XP?)xy19a zZ>sWdVRKz$vp0YnkclXNDhmpTT0roW<HHFt5%=8lrZ|g&h+u5c5_=)5_i^SE0q3@4 zK-anenE<3N^mF*<Z)p4`=ufw90%_s29AeNg`UaM2Q#M2YR$3b@;Xlx-=c={IcK9_; zD|si+eK&JzIz(w%&)VKtk$zzP{Bl@so3&iVz0j7Tgum*$GMDCR99LN6&Ak=vx!JCO zx~?Ox_Rw3ISM#m6;rfa8v)75cpLhvBM^5K{AGwwFxw=Q?qDrCYnp^JhJglodl&eCW zlAEeqsTv-0$yqMlZi7Cp%w6Zkp8^yLLwM!d1bwK_k1!1fTvB(Una{+8<0rhUy6!#r z041+YXO&$pB0AvtYfmT%F-MCSt(u;S=0B(1aC3+8>v!dPHRTkb!vx`J@3x9z8*V~u z<`_h2gRhOA4FH>N?U#K}=XM2e^W8Y2w8f<bo<<v!{`ZE4apeEr%TBmpS>TC6SyzHq zZ&aMy#t_S%Z$i!GWrM4j%TbZ5EeiwBIB!nYY@;_Mp#iYfBdCs}0oz;cDn~PF^pA6T zJG@+1?=-Y$bseK*87Ukw?7wdO{<dW=7M597yD&YfI>L`_EN}9PXfk9L&|p(*$-s6Q z+Ux~HOKZtSLC-aRI)MwnAj=KaXi1bha>NKi&<0qT`7EC?E&y(Xa4<5DQQr`u@sxfv zrHn%h9eWV~7XE@H=dyecxaq7+#*imbw<HMhaw1(vQrH{ixlNjP%gVt5sp1nhfWerX zY(cH+m}c`4x#jQ{o($l1Sx%lCaMDK&o4BbUU%Ez(r<7y<LZXBUFt6PwRHJ!<kVHd8 ze-m?<hHA^U<_%WucTU9!Tqz11n3|k}li7hX3blNy01XQ--=}*$`}t2jJ%!}&-0x$H ztFWk0>rz@K5ccFl$NugDzkG}I>zt}@&Cn6qMO9vn*s1!+R|?Y?ao+PW{^2>a=^S4u zP|ZM!r>nEv^;s`bXts6t!>^IJ^I}o9EL{##u<c7#P?c*@omrc8MMXtx88vIA`aP~4 z`Rqty&J5DbE2UCx=gWJCB?iXoYf(iZBSYwQ`FWvW>6Ck!Px^Zc?^&pG`0o!yCDWnv z^9ZUvJX+Fqv7=*iZn!Tz5J{2mLY`%gos*w24M<@hj=90*n&*kD;ol)Wio@*Qc#m}0 zP1RXM2qUmB0L7;I#)2iBySOR$0gzYcz}QpXh?|*Q;gC63R5{b1YX^9cft={<RQcBG zTdU+t--k=zscJ)!>FW8fZMsdiQZso?Q+=EE=y)R$&)uAS`(*f91qmFsj!?)EP0lVN zQM-}1!oK?TwTyfgcWGsd#GKI8?wK2X?FbrpOXkb@^SFDJg+Sy=FZP$W+ISQpVCFJ$ zB#dNH{ij9YK>cX`kTOv=9uAIID@((yUOeU^gw`G9*1cPumV9+qSjN;q`_VwlSSRWg zpM^|gYX)LZ#ifgZ=(DDI*W3L>yaMLL%4*?E1pEbe?awO-`Qh?~eO5i_Qih?9nhNIR zhqvvg_=0TazLO^Um%#QZ9Xr46c++6y(b2jDRHIvxJsgqcmf{^MT?)U9GYDe&(HK({ zY36!cXYf&AP>vAr*!CQLJYZ*VIQ~xBI|?G+<Pez@LBRpUc)DWmsql?sQ<4UPGsL-_ zm6er!YJN+o(DF^Dv9(PI)$LI;FpA?<O*4R7+ZwgmTE8W+9RcZyZ(Kj(mNt|No=?Hk z+VW_rco-{YW#rHx(Ar8@_=yYOT>8}~6wL$+N`7??UfisCrG%yk;V}lSJyn#u+;m?5 zYf@xJL&}j$!z(`$uAn+bEmODZUOe&<{Ui)an$d8H2PLUD9bQDp7in;{tIqnIzpPk{ z*tv;oq*)m(dsc=K+d)@-KSN+#O9`GT<dM>7tctEIh|ZajBHa8X=fv8&oHLgHzRc`h zLfE>rob0F;)N}uE%5#pTK#zS=)h1eTJcH8Dx@g6FGJDcei=hiZcf8~2AvS+>k1I6s z0Z!%(z&?hvOwsr4<R@)Vrwp3oz&q1s)}ZKcMFjs4j1eln%^hDY{k1r8fs=_liiwHJ zi7@AUvV=h9AxhrT7(v0%0ci{a@tw-;Y~M~&m0Zq0EC8s<ipZuVDzII-qx?A<=-}5s z-s6cB!$^;;FMRHtFF6^-5w#yUkZ<TDy$i<T_!vU!QsdRvueFmNY>Vw^B0STw7S8nU zfrgxqMhqKT6tOkiLnUzV2$^B(pGFoUYVugx0n(Cf68z_Ie+5&J>tmSGRqX>cOzyiR z^I#Rfgxp(iKWi~U_QNxhR1pLm<^dc>QcS9$KN8ahboew0<vQ8u7m%_aAGktwLNGYB zm)nc!5?e9!Sw8C^cq1BVnlUv>9YGh%Z8}Mq@nXh8HQ7+~FJ9`=i9nnoh8P{1c)E`0 z>OY6jVv@3Qy9Tby91hq%RJj|iH-7v0`fH7flX6Op#+k<`C4=Q2d|`E#$7)Z4*G_JT zHFL9HzSfnNMY2ZY52p}xXPF+^vnN|v5Urcqg>dXZ&<A1Buy=YcUbBQ832xCeFp4d@ zS_awJPgwO@$$1Q7JGqcw8l$gTOpFq@PeikWk>p^{tZ?}Tl(56`Q5dd+vE?$WeZ+UM z6Q&YyAd#r3%1Cm3sI@7Iipq7yk8xHbQpz4e1JFkwvfeMgw&#T+Y-6!W43m0~y^p-M zxb4@+9;|GCg^6Fj`8}yxVyI~^npCw?_isZ7pZxNbQ*EhWo-HhIsGnfhA{Fzqko0CF zPK6F-9i)VArqubsFfu()q#UagSu&OCz|3Zuhh>*;!n5DYdUY*>cLtG)%Tg0S-!Kj3 z+z;INu2Zt=#;ej9WlQ<1zbo|TTMwZTaSlJ%M-+<f)s7FL6RQ^G5qA}zGj+HGU@VQ2 z;Pw~>UjRI7ElxsCZUk<1-ZO)z(1_L|p?XG|f=+TQn5$o`n7QvaB0hH^=){J^bvU_A zA#&VEDH@&Eg^fdUmmGADs2#G>$7_k0x=rblkyC(nf|Z%TjRgk0$#HMD3Y~SU;zapX z#joEg*QF>5b5KahE<LhI@mO~r%e%n2jV4qV1C1i(*=fILh(l2&sROb3FVa-zEEAcx z`bXKG1Nxy_co)bDL6mU5)qc;+Hxior7em>n*}y5(&awSMz9KbY1x-d6KmG4VxM1At z$1pnHKW(vaB7Zs@NNZCrqa(ws#>0vuL7+HZU;=Va(n(YY<y_cjSQ@0!+GyM)CHIol zy<sXVrK5e-#b(K71vO(K{jR2IUiuzX-Ljs>RbOOq{B85Oo?+gSEEf_h?h6R}fRL&q zlH3BHD3r~M91$;}0wtj)M`GR)dz#}skljA#O&ws^;lm-0v%-CY`?i8=TS{3q+o6VP z4-aBlh-@XRGysaEsj6)Zx-xy4GW)Zy;7!tuQk$EaloxfAOAtk{m!$jJfKtVd0l+xm zrqfta5;$nkdr8kQNKsTg3}4?+@kTTZdxvR@HIzMygl`Jh9@h|8e?SHz5O1;uPkU0E zBQaSNN&V-!Ls9dZDt6~vtNYc?25?;I^!bv1@}mZmCZC<Ytzts|)zG39at|3y{G!G+ z-_oB;gDQ-bWY_<uVK|LRBTBnuJTBZZ(bU7@8P~|?#ody&##FHd^q%*XyL&shi62$M z$h4WbW~Vp%kEG>N;~~YQbGjaPux-^cG&4pxro@cdU5}5%9{zit@0vU>4~tN9Z*opy z#@u9d&Dd(mqa?L!-E!DM@e?9JPsDr+N!gnji_zF<FhM;5f*W+Lgr@W`oL><X=b<6d zS<;VHQpYx590Ae*>^m1A3ArdeH)IOmfszmv**i_r*_2bt>9bcryrhNTC;N`AHrec0 z2b#GKQq-Xqvs$uCSL4r*1rM|*z_6-QqcfV{Hk;;$PzUxPgpUwTy<k${*6exxq$BR0 z@`LP|XbLUfPe$rr7|}18vLp#uYZzik9*Do3yM)RCNA#V%orW_^?t$m4K+$KSf)a>) zLh}@c7`@!f4Qp4@`*MBb=lS~yzNrMtzfVvW#7Hyp%3?i<xuH;z-?Gk?k%z@WL*3#9 z9i7ZpGv00QA8NO|m=6L`irI==1*!y9g!jfA>)j`O^i;AEIm_D_HRmt1k+m&HlQpxM z>+xpe%=Go;OdA&Bt3=L(p*67a!U6zosFI<}dVJzMHDowaHF7mfAc+j}^8`rQy0x!1 zh&U!pl>dFY8u_+pe?b7zJ6)qUqn)EMjRWxWw6gnBqo3Yb5^kvBgQL_<`uf6|;nQ$} zE8;omAQWq6-_1p3Ne46`<VbQ5#jR-U;P`Gi?xZjV)=2ySJY&2j2(>fU_x0PW6axD2 z_?W<3C*vi>i};x5bm{%P2wIL}PwT)KNs)^@hYoxLIl^rbH-`(Bdn&tpqOw9uQF@fl zgg!0-Q~K>HTlOZ$!X+Um;i}S0WRSfUZRL|Y**3T7mF+DKzT(pZx<B{#Q-AJHPpa#6 zW<i{CUzQy%BTl}oKg5?!(V9XxHR9{SU0Qc4YOjzqgR;7FVWc*46x7bz3upSDb0oIk zVAqQp*D}J4F7yRlWr(TS<gs%{%fH*M#l!E(cFYW#Zs&8pzNpnR(@;pv?u&`9OLLgI zOc63YGPI*AY;99~F39Zooi`IGY)}7s8YxKwLq+Wm!WSDCS2FFE$YQ(R31Pl4W<hqp zIBYx8AwHAiRtp+AeeTfiF`*LHFT?D#6jw_lk?rh_oN)n!w@shNie6F5h+x-QM%W&n z^W`Vx>*lX+vIU4MuN8J@*n9V>6W_(AL=E(-ci63Vwsaxy(BJWhwUTc|5_6+&?0h3& zeVY=m)PbYOOSw%HL#Ch)vnPy<=|Y}xl<jtYM%kW6K)h}rkJ~|vjlZWJ-?WX^cL;TQ ztP%ocM{Dni7|(|ZOk^?0kNuu%8qvC{&);>5Zt^e11Q(Cq52tX_aKJM=2F{#mof-58 z{cUMYQYpvgNN|Z&G7i6o5=*`$R#)!y+Eq!-VO>d_1=ao7-gPNwtLrO~cFb;JGCE~N zK4(ndYN}w43b%$#RGdjjm3oe}ij&3mYOE^rAO?&TnkriHEwGdXaXhh<5|mn7E5Kp1 zguKSZlzDZif@crZ*lCVci_tW3mx5HdLv_VZ@LQO06_r(`(4=8!8_uDe&m5!;84R?3 z=PJALaWIN&3!Y7gSMo_v+mg}X;%Ed6S`7qX2mb~TC8IAO43Pt7AfiG9!q{2{hO-!J z?71wj=%wkT8z=qh{?uDwZ9S1$B4>Lh-q*9s%e!6|aGpP0AT+1=A#Wz$9zEps#Rhy~ za<0}(xsey3Ib^x4dJ%!@n0Q2XWVj`Q05D(@sZmI>I9lICi`y^1|C!P^dK3QFG&P}t zHNc>fJeiUpPEN)ec<8NO7Ef!MTD4rzzP#3I;_CT%W$O8drPjoD@yqFmr)tAn=3Lzs zE?PONOlB?jADupGD9lcltl62=y>J}t=v=g#MJ;PIE4%%@Y_6)!X@CLks3dW{$|{>T zTelT+YE0bVN9&mb0+BxQqvM5jhWb3h5$S?Q5WORLBbh(czm7~sch^!f?%hu3H)cUn z2_=&dIy1&LU~k6Wrk7D35H_vR>I5pu+Ap0L&RoZ;lpM@Pw21iqkxOL_H|oFa!zh9n zf4POahgC)OQkj(4`3w2#E!9IY-3pN9`q8{!WMYfq$*Vo2`@8H6&6v<TxNvO40M-#M zw=d1FH3dQ0T~X{cuz`gh^NzT(%ii}<7#NIC*le$caV@ucYa<r=Dt;YKRK8vQa8k+L ztg2t2C^9M#(zn2|_K*8F$KnNpj53FgE>QQti<-@|W$ej|GyOC(R+7}zxG15aRxVn> za7X@-m-$N&W5kIkF-~2)-n^>6ME+(W@F*F>$~xn7PJ{Y+5-o!YMd<psaHaxsx#!_n z@PuJj73a#4ZeeO;ud2I#QdU{S2q5BxHrIamEF<PFR{Hb$#MmwrsAo6}RiW9aTp)c^ z@MXZrfJR)st`MH?2O54>tmF;!qo|^?o*IQ;gL{Tvp%`5rE|2D6KaEk>3>EL&mWv$c zGHhX|bS58R$<BFqw5G6lCMPt6=MerwGTz4`2D?}8wH*DqwkTbdvW~+m?tpmqd<HQy z6QeI~e>UKNfFB?3P1`HljaRc^a5Gx_o_l@P{*tqT<!Wujd-Y@sG-p~9NDUK9WyFIu zzrjkR4UhGiSkwCvCcAUp2K8ts<BC$Rr8!0oo+DMD0MrLLK3Q)vlmQ(`@ZGs~m>w-R zX#`+Ls0<8xX}@9a-0&#hvtix>N0oEoInz{NQr^|vc0a`uioA*-6Ug-FNtQS|z0lHY zMdeQN@6o4sK3WmN=O5(Q6%K8Z@x(SIN(wkzhrQ<Kry+IzefEn?UUcD?4~FQrv(Wbf zob)VA_Ap7>)AhIGw(kJ@HU~F$D@VjnA&;{fx80TGY(jc=vPtunPZYiA8IWjE<SN^a z6cN@l!_^t=sX5tqTW`gVf>L_i0<h$;5`~3_D5WVy2yxtu;N-yGSytqBKEjuOD(T_) z{xD=Y^^v86Kn9xFxWbPNS^_3Tw^nWEh3UK2yiHdyYscb&q0{!E-<{jV6%|x{5mPTY zNc2)T`F7VT<@Wf+4-;IhY)l>8iHfnWWVXi%n+#;64R$Kd#KuHJbM=0{ihAlFOv>hC zFk_7p7@W`aWTRFTMUKc_ixhi2_y>oUPM)4yz<bl)6o{RuELk0|)~qD5MBH1tAX>yK zPAx%WP#7^PDDveuTri|Da$3JV{iA3Y8qAaxe&piGW@MBXgc=tg`wojf{_Pq=K7^f& zoOAnD!aXf#WYshTJRtZw$ZIp}?a!a`?eBg|AUj&A45)47Iu*WbGNxuYYC96HcX0;N zd#=YM|Jj-#!7ngBC7eZ^0lBATWf9){pLMM>rm9S<BpueJy>Hyh@em6O<}|*vWyYv~ zL#9LFVWff6pf`&@kyyXk`w5}-U8Zp0tUvwmP!c=h>`FoVn>fn^-&oo8z8y2Zgv}Wo zmxK<NMb%dgX$v>AvX%mPkR3=>)6eCnaG@dSt+b#{l_<N=z%hjRPl{4nBxf3Dg8)2p z2@e+c+;T8a<Y1X2!Rx617mHKp-Nj-dV2jZR3Z}80=ppPcM{ut~1S=Se66C`rE9j#= zXK>BT^00nA*nCCo$EV!IUMdXi5?`ufY3~QD09Cp+#o+=>Cv6$2U3NAx{#=vwH3epc z-DY|3T=rb)6CN}&iCddr&b+52jX#W0sb60&!gb)F%Jqi{v)le2^#e{f85fY^a}T@Z zEOEVm`ir=1PtUO+WqypJVK=C@tS|9uq*zX7!t34{7FFBS=T?*r5wpR`M|qNu`9GD& zF3w=)Favoy1a4a=>~FUZ4PoRe;+<J8zoGm%|2yQNlVy)0eaXApNy}5nlakwH0DY`9 z7llEknMnNPSnLvC@ZigrBL^j;;B%m|GagoufzK=8RX@$c`tlyTnADcK$NhMtZEcb@ zJBMa`lQM)9L1l%2d~n!XkU_J;pk9ESc(&kWn0sxG>1}i3<%GJSo?$F1pNw!gP8*#u za;TULAuDCGmRf&8%;eGC2nkTHf$IS1nC?s$+-HDW>xtcxv6lgB_qbO3nof7s{LJwM z1fN)R@T2gt#9f=e@#v7tU)gp}B~=dD%8*i-eEloCX)F0n#$^igiC9fjIrYNBpB;G( zhVA(}T4KVMXm<4!5^Pe08-Ns&(qoIk7IkPJ$GAY)37qo$v_`*`v(*uN{wDSJD9==` zb=vJkPUYs$J0D6s1AQiJSI+Y5#!p37&upd;VQKVL^A!k8B2FxVhW4v{uow7dcpKU? z(*2Y#w&QwD4=MM4d<a$`cL=_hIyPb_A;puI)2l2+w1g59d30qk=ChJ<x&4^HjF{CT ztNRdhA7TW@Pbop-tc`2trKn65;$R{=7{G%puPB&Lq030ENR!So)mdALB`T|nh9vj~ z2gY!?NHeFVpB?fhNY6BSr(H`i{tFSlonXsr@P`r0a;fqHa@$Aa-_jNFC+;(GasV}B zgshDc7l!JiQ%vVWcNaf#Q!34eOt?~<9S3!+kvskeiJ;toG^3=vkoGYZVwSUc)?3+j zc?@Hn%=yJ75}jOtA}Q%O!(zIE4K`!Mk))S5blP92v@^;qk5*jut)Qa^ZK~Ef(W~1F zSdb0G*0BLpwSb3>;0W-O!O)Z7-h!?rDCuUzG7<o1lZsH0)rLJka#s1_aj|b%r$^`D z=(P#)zybpV&OC*ob+ULv!+@Ob_;_`VKAEnJT9O`?KvI<Dm&>3D9@}jOYlf&t5nD^w z>zLby^=JVU0nEIH*JJ}yNRvQqKQ%zo_fa_;_2s;AK>D~FHo5!-*?4T16BI4&eJX~$ z3phV#O=gMk$?cMDBdpMlqwMj;_^4FIP<U9yd6u2jY{iLv$yUe;Uw{a#m7i!|7h~?W zkc`FlV+C7}b!Rx>JPmB%K=`EP6u=lxvx<YOl}!$I7iRd5HQaSQYPSIt8$RE+vq996 z^g>PaEbRF{hGR!&{H=b!ouu^JE!`kK(~a77S3<w3UYdA7cD^)FP0}_3m0GN-oOhk< z-)Qd9m39BVmq->RXD;<*GvDTFyYIi@61i@hJ0(^NX^kq?EKv*q74IGj+nUZ3%>3|k z%u9z)EV<`bSZ<|{CT61L?3Z6P@nu0gTaaq<pW&b@-6=s3Q){b_;QkFq7TuI!8T+AG zJ3l+`68i*^l%Yc#eN#(diYyZfh|{<`5be?*d9gf>X9C>5qC9~;J!#|FaI2WGi*Dx+ zL-Y0sq%j<LWwojjpZ44cNZSFy!Ilwx7!-L5*VS_2#lwrhK-;pLT52Bm5yXxZNLE|Z zxX3mRWM`4aNv1+(@_K^Zp<0SeTIcc^>X~`pC_-v%5u`1G=UPk3gZbk2zBZ>PI6WnO zghj;Y>yTq$b0HbAVbON*^GyI|Z8-|8jlMM$d|OpGHytnk#aDSe^r}!l9uX>s%4lE# z>hf~ym|R-T-~{bpNv4^}L<<2)p|98Mycuov#Ba)&YV>oO{o`NR_yrubmD<)bm7L}u zwG93QDXayL4CCXQ=oQprZGfWX;UzThBT``v=lDDvKaid`SuE5I?J<?ih)?E_NFupc zASCF$s7aqeylbKQ8qR4-v_XOxjyXhOgZlZ>fgK}s&<i`kHdaY@BQN&KO)J<LpMcxz z>+;g}m|iO4L5ew$L}JsUWnY(y20BwHv(tn4KQl3Txx5*tl$SZ2V~C`Nq{98$*j$EL zoASNv%&D;D_WC;7*vN30_O5FGwu0wjoUHzaKoLYGCdjKoN@d7<cJ(-iq~&b;d%YGC zMKX0JgE^}gn;Y5nCbZRo^p8XfSKz6(j;ixhgBudqLV6LgnDE`y4R}v~d;qc=J!Lts zUZ8(NTksyg!0O{iXP!M2Z}U7~W%8*{QBD(|%ze%AMwcc@-?J!ana-gKa5~X~aJYm& zY;YDUB_W$g%ic^`f=?XUWX28cin7FZPZYZKUQJzZ_VH{7?<qhciFwADu_t5Zf4&%& zaUyEhn!uUnN52e0rV`cg7#RdS-izOsoAqS41pS*=fkyvm-U~j1F+P!8Un9OyNs89j ztV_*lZ3caWdvbWI$o>#IhGjrY?j~VWi1ZaoLn=YmLw9OI0<GPM3B2(Nm~uTXiX7!6 zq()|vGPW;br&@Jo*oMuUXO9NQd`rW@w>uk8qG3QTl>pzin2r3DG#31`Wm`aadX5db zu$3%U8AX4N(My;A(3$Kox+JG;+YoSg(xFU0J?!?C5WA|M!%<#4gMwM8xGE=D(UNw+ zuusv89o|>_W<I1>=sbgfdi5nymrEgI7iRM2ChPP##FJF><CHt=>K;Bnb$a89us))8 z!L6{CXrF$j7xT+77Kq}27;92u#V5ycLV1}geS_90Lr+3CQ8MsRSR>S{Iz0(`e)n$i z%rVdQKBIIGTzYiUta$m=JGXHop*{2R;4<TmU)S-XbtS}CsbtvsKhMYms+=PY+Fzmh z26@EGSXs3aFZIz8s5#Z=yl-1vLBBhy2MVC11;gRXkemw0RJe<rYTjP$MA&^nRH#X5 z#MN(Km{c};v{#gUQr~Oc&wOwC#m-Mal({PBkrK0U&?_rvc72<lb(!X61$Bb?5$!mp z-!69>^|-}-Jb$}@e|C1oqLhBu;m7BGGUa;zEp{Si$vOSHxpM~ShCu;zDU@r6hX$|H z0sqsNv!F3)H{wtM?A8|%U5CAZ0%V2WjjDx<?tCXCR>m#w!`*-oUf|*JQ)nnt)1H|Y z6$e?LYG{rrT-I}QB)Rq?nV_GPxR|BVF=Q=KjQVEY{JN9@*o2YC0QHwg)8>%Us+Ixd zpXpF5^8mE@hXEk26+z8Fj5IcxU;*$*85&T7*;oclZKDm2(D4gKJmv<-=x(W#<8lAK z`sWs6Ac9B1h7?_wTqLMGA5pKW;DFaIHAQ2pg^`08+#)1Y^>Mw?%i>KXDiui)-Rv#U z(~^?e+4Sj0l*w+N9}MAb>Uk2H<DxPDDj7yi=e%YRw$$F>6WuaTKC=00Y&)3v^r(Ar z8sYjnjQus;5K3b4p4uD>GZayi6e3bJNUz1i^izu<euuaTD<I+KO1o6bfp#)GW|{-V z>&oj(AS`mWHaAjm?B|ZNcZN?kTas|xukoJ#q$+7$)y{xKvg(*Xk1QoJ8-ize6+TCf zg{-THLoyB2Dr2H~=yTWJx<>!OQQDxuz0ukyJ0}e>?zf7`uh1!*0a7|DA@o^3O13Qr zvZ-m>sv3u#pZfA=YJ?B)<}N9Zqzieh%!ZosrAt(`DlaYkdy_e|+>$f~P?##qh5|i0 zcZ%K?5!0xva_J8aI^@rO{}7+yb;erfTYZq2G4sA0mSdY@GSU1AliRV(s+Z?i>x;s3 z0&*G}GWM5~CcG0?q3Rf4w_x#2)PgULdrCtNgMB1+$eacn3?w{5CF~IW!xnjZXp=$$ z5iyghokF01e)U^>`pzj32rv-m>-O+gE<VN<B^3(O0H#EQ0=B~nB?B}WOIS;34JxJ^ z+U@@gae<exe0<d5x1%>atxf3cqmoWneSuRE@1eG?=W`~X3TEcZODh)=SG`ct!LhXu zbMf$-fHHnxZMe5-qlH~bMlC*uU6Y;lAG1t2w*NQyLiCsPc6!N7kr0!E&kfP-6TX{V ztDj%KN&XZ+XH#NuJb3b=R66pN8}IYlfU1Yot~ROytr`bKD;iC~+Yy4>G|n*mIvkS? zhvuo?`91B;8N>sIQ+$4osk)P4HHCwz%_5NU&r4RGuFSb#OEdfx7WHYjfJ!VyYayQi z`!c@gm5YaZhSuBW{MfDU$?6lBeOV$tUE3LoP%qP)j?48+AF0|6cjd!zRCfrz+{)Nq zo1WeJIB#Y)>*>Y$V6km$Wz68B3fX@Iaex}hK(bVA89g9AXt5sKBg_^<)>8fRfMd4^ zg!s@+s_f&df@v^OLS5!3i%D<=-SDuJS|^+Elz!D`<2;8am5H*i(l85?-ZYvCXuE&@ zoaj0OI*Ui~t}fTToFNCw3I$U1X*9)IGin}3tzp3lY--H!pAS~Gns}EcYh%x`hMO5E zkRo}Y!g6(`z)D_r16*@~`m4E*2JgU~b)w~vtMH~3k8-HQ40U$TH@5VJ8f{eDjRGgW zITEZStq<`8{eWe}Y$J2{m~*}RAS22W<pso=S6ts%*?3dN*sEtIs69x_RJhrrzLwT| zF8KsmE=Ck;^0oC87}JKU^kCE1-{GDiq|7qhy~Y^p$+1Sqw*y*rV+23kwgKo=qmdyX z6axb>6gq@I{#4@`eBigllsT>{JmS4y=9fqe89&9)ep83^oV7B_k4c(=zCyWv=mvN) z&6m{)v5ZRd`B(H5BJ`F6$4@ipj|G#M`~O(xa%f)+%&nL$w~Yy?RU&7*{jzCUKg2g3 z8i}s6o|`SG0JGEH%xLT2S9B2`ckb70qJW`%A&ueq3gQ;}9)Q+%KgtdiY`Z+W^p*v2 zHUPZU5O%Wu<Hc01@uxFBH$=YXOE&9$zB?a0H1se#war+~W+@y2Y)t$L8tn;I$PcIB z=hkapCPD*6+*-JKhG5>X?K!NVSZA%b*sIvpxO!P(5d%d$K_pZ~&2s<{ZWJ33+&f2v zDUxFq0RULXv`3&bH+>J$<jpso)5qizPZvz{bvb&?(q}5WMo|<Szv;@@a@q2!#e?cX z$EDJm?YHUIDmh)bhm0;Ae&+}i|M(d`cDu9}-Z*0Sqs9n)I?9ti%czlyl`X8e`&why z2rj%_z?90=sug21wk9?bD>o7@atawc$*V#K5nxn1e7BS)s%i_F=D~w#l^7ezoq*fI zV*c^9<w@qi1=LyelRiU*-+KGyCAmm_>j4V&5LFw(T6{qKn(Z3~$v<0!f8F0Q)P7O4 zMqXszTdN#DF_xDF^2rE?t63x1<|UC6Q#p30edS_UT8B1$cT949rfed9!SZ}!1~{vu z;?*^E<<Uh11_}myGDxT+lHVnnVBQq&ca2||$>`*MRF2MJ{^ZY=!`^H=keVNRkLce2 zi_$e?CQo><d-KXU*P}sHN~iNuL4Zvh58kj<7_?IyYXzB(7M7VgbtqU=P8!=L<D2<4 zptK@#eb!5WQh0XNe9_{ezrib-df4B;cDE6ecrkO#ZRwq1wGj8kZ{y_loq*k*yRdMz zlJHgW-t}kXsQ-)#U}Vele#2f<MB&G=hJuWusKYLb0b-!{k%C(j#!V{9A#wgYKPBPe zHVfX+6uz6YkRES8$vW#gU@VOvtD6BY7l_}0uWfs}Op953=#n!$O&zcyb0Q4mUBXft z+RiMgyq4j8Dj5{CoPC3-^ard$uJd|4<NkgMZ(<X6#Za%QB`>LSPYc7EZY|rQcM4LI z+wMbcWl1rrGJ{TCGGq-_7jIHwu^yH}TwPJaPInOSiOd-^?BtA>(Zp7`4;CtIr=+{< z=9`r*yd5(-JWx!2wA!CorKC^Z7BjfLVd5Gvz3D-`%UR{*O-|3j*B;5OhrcVJpjWh4 zd=s(v&kR`;1IA*_gN!}Rj4D>+9SS2`)rh?!lWK0w8=T)3cz?Fo%p*u&xER?WlL{t9 zdl)N99l!mTTrMLx3R?r641D;20z+}#Iv&#?`Gax>{ARD5vhdA<47AQ#Gd1TJc`@<* z;ADt3J>pS)B}6+?me%=fNylME_oRH?BNqpBrZ4l5pOt*gbs1}-cvToCl>BQWwP`cs zaQbL^lQqO+K=x8vNVRiG%(;%MKAV-^TQRw~T0d!=QooODQ&@`av^6rq>IlGkCMBhh z6_fBdFjEh1Yg2T^DjwFg8}@(QbZ{Yr?m2Zh>2GWfJI(*GbTP2P2jnnUZNJF3q<hLh zMT3i_DW~@ywo-k!@BGK3_Af)9AN2>1r?o#4d!|`BL7#L~h1vH-z^6I%vnMrTLm$hz z5H??d2l+zeza!7-;`LwW`Ctw@R{IuKwSZI&IK`v+Ht@j%K3x-EN9*1VFRZidUnJDG zTM(U^>WOUZha^}uxC%{!9I}-*3PA;7wQu~BlEm-4zOgQA>PU6&dqpS@LHm)_$&0fY zm5Kp0hVa}<^7f6l4#L6o=_Nn(!eDiK-zKI0^5}=XR2EJuB%yzPadRB~nq(lKHOvZW za%f1dE#}X}Z}bPi(l+aSy$pY6_rIor4jLS-2P9|a0QBMG8ABX&_w;T<{vi%dPE~{H zx^@|_eE6j=Zyp2k5GqWFf~}KJ&a{t)Z{1a>aL!gYWz#gNQ{^dY|6$~qP12lw1SK)) zfAiCnk^CtbP;;@}{~9L#rR9ov{j}96eAIwZj&(+os1>YZ(;|4icEho8*l(JEt}(0M zeuGOZ>OPoF4#EHAOG8g~&%|euec*&|x31+(wGXZQZXvt8#emucw@GzN8eRI=uV8}; zeBR>s)9}gv$+Ks+hhO^s+R9ifZALDB(gq~QR4BEq@Nj%V&vBdh3w)nSk6ZX+4K%mP z!c;k>fU$UquUe#5s@{J##X(D#OFv6AqZ*rldaH{|`o|FnEST#rkOJzCwIoOX_=x|l zQ<H>)yOI@bo1IYZ21<Buelg4*v}y3bGqNS_rs<>#x`#U*HoRBKJ0AUUT(^IcNjrI* z#K@=p3As?E)LD30N-@onfs<*7uP5i9Js0rf!{p<QD!J$0Z~Z^NJ0dZ^4haedXMDTm zylw`;jt0nJNxD-iq8+maIA&DU=`<GGS%pm{JTXej$&ox=#&$qdnfr_@^uKUZ7JR^+ zV9i&NU;IBW<Nx=sfk%Lj;M+CsKStL-%fo*S$>Rv<U;y8NF2>%@-!0bv^1>6qEYE=% z+l>Byyup92``-ha^!UL^-TWSZEAId2EB^Ug1%WFWc}DZUvLOEbc5ibwfe)_RtclM0 zU*6~MrDFnDa{44}@$WDG@0b4nFoZyc0*!1zL4gEEYGme}aF?+2)ZpIscJW@1GX>y{ zy}Fzm4~7*-ZmfD%$;-<ZHa31AJI+LilVJ&d@{n|LcY0Kjje36M%y@cKJE!};tLf(x zRuBk;ASuimt>ick-G=Lf-fRs;0;Vr{s@VIe-@25AUBi%5JLSJ8XbLQ?*GTZ9Eg$UB zOHm1*VsYH6gn;G593(BzMUtj3_1d29olm12iXkYxD~_W2;>vl~@y@q@P>KG5%rnck zUth|{yBdG{?FS#q*n5l<@6)3XonGUYoSQxefXgUi$lJpRj`_>Xs`}}(XAiDl94=08 zV@UycMUupalZ`<zpt>Ib<a)MUanR}FVZcMi*5Pp;4?xpvXhX2Q|1KdBxKBluSyf{M z=oU%fZ!t~of53q1{qtU~2TarZf&2^!?`U9+(*|6Sg+R0fpV;(+pVb&|o&v>dkr%&@ zxHwv}fK-fIKtw$39dlh3e*}-Pfw1Zj>T!}};9;q4Rr%ShoKvJ9zwW93o2U2Q=cg&` zCZ<3hl1A@?{`rxWf<lzHbS6c<7m#ic_fkX4s1as)9WnHIef!jT|JKJ~Y~aF|CzewL zG(Oy%XG1Ze1%G?_^&0Ro#}V5$ivk%UG>_J90J^2AVc-seP8G_V^h$R8XEIq(0awTU zqNb#Chw6!_BapsBARBgqBHQf_q*ri&H)Q64#5Z&jB$E5Lhd*lb8JiwS`X0D_<kk^~ zm&HHK#x7Gg;5PvK#w&b7uiCg+sK^xH>Y|+o53_)PH)}XzTQyp+?Yg@F4>1=1a9z}w zim-`h&k9C_>vZ(G%%JgI3!^vPnaFMNRbxzNH~Az81RYG(n=3K0vGH&$cWrya&f<We z@#W6yh?B1FpWCOGmp^V{NfhIop5#7RhTcILkHo4kt|>>%=FxyDO7byH$Nk~%5)?+8 zG;rsFw?QE0^3P32QNuv}h)KFVGdWZcdjd+_@TCwJ6B~JqECB=mW%!H#Ge=X*^LF7O zRvQ^bgn0$v;9eQ}WL35^<~r!<sxJM@tLR6o8;9HP4?z65vvtFLKXDHx4KSl~Xt91D z(V9n#JtRc~aYwDLN31|lTVl=Yja3!9VczLE7WPBq-N2Tcqbvt+z#qo(ai-*&TjJj4 zi(?K@S2-8Xzy7X`gaVKE<mvs*&(&x~wW0wzrpkW-rZa$qm`5M_ypITK&J7mfpS6tn z1h{$T`?{W9``Yu?PRv+R_N$3=OgXm{`H0)-x#;q8(q|`UqmIUKO#S}V?FbLb^@vKX zA3kXvaFCoIPNO2;T-d{hiLcyP4x9g`WLNT41d<+Aml2!&5YPDxe6B%!fb(?&$SQ~j zy!@P+v$ew@W_bMQ7v@UQq?a4pzM4RX>Ci?&b_LVhPr$S@=IhNc@bKSA-k!4>;?-%b z8h5ZY?|Z+RF-4#p<C%p@bL<EAY=4z#DY2s?yR_|fq1e^+?bQK(-9m5<Jh5IECBs8@ zho^rdOX+T4m+)#hp_sDihZ=Gecq}aVuowGVxg}1oL*d!Qs2M&I*LYJRh*J-!spN{j zNOvknN1`Szuz4z)E-!(tf@Q<St9<jSTOto$`I(e#UDq|!)sc$p`O5a;sqpqn8T<FD z&%5kaW4^Ox`do7rWe3fj?MuU5D2B%lYeL0c2FdhL%*7-3$8N_ebGOTon&}Zp>S0jH z=R^UvnVH0Xf)0Oy0%yZ{V7PeDk9B<{FZd8;=e2$|{%|dly>gP&#H=|`AhOes{SCWQ zvmJx~nZN&+w;w28WAW;~AV3*1F*v>Z@akDbW@u0}9DW2tV59T1s!l;mnBWk;?-Jri zQ+p70yJFUdTHWWM9r*E?{O!tJV|}5JEVs*@iUcFlsC+WvWC#7lz3Dj1Xef{GDGyKY z_~PpQ#b)27Ig!T3;o@W&kXYBU-=?DM16cz?x{CCi<GERxFJ)J6)><m3&Y&?vLQ7N0 z7e^Fcr|r?2$6pyNS@iF3#~*H?-bbFRXX#zn>C>5qPQ^tzs70q9y3#ki!O|BkN@hl$ zl{x#h603<mw3mCoamI5g$5pCg1_-q^j?>;)R!`CCuVLd=U}wj?n5rzxhX~yIe-WjQ zZG=U;wwri-ug{ugrXv6Chxl&wDr)t|1qyyOX>pYA_@&qQ*{)`nNBq4;Q>(fO&oPvk z13}nATgv@EBd7MSk<+WcllXE+@3TgKC`S}n*Y$AIl`XufCJZWluO<09u<4x)M+vG( z`3XsJO^a8SCZo*2=z)ePp|w~HhZw2-H%Lcx$VTSPNv?@(yoa3r=rrlv_J`-m?*cp{ zu|<;EECc#&Y#q}ZHB0UaKd|bp^o*a9Z<~YfmRIlebpvEO4K$i*Dv}*|P=;pUL~MAQ zi>yJk6>OS@@vf}bH&^TS+4uI*EbbbEg2{}~4H5T~4W|%+B_ofY&&YWJB&W0dCOv=p zMB214>-g)RR3<fgb963NqNNp(IPhE|ZPv|zwD1%xXGU`OAiq|6kEhNu9e3xe>sX=F ziU^0~JgdS<TlR1&|4>`{RnRc!(%YXkSTdfs(;|1%Q2EXc`68yO=Ddz)n7&ut#pE}& z<mqIW&Hb5EMR%G$o0>i#lS_0vH}RX*Grwq8>N6m2)x}4POJIl;2@M|M=`(*$bpPBO z!7Z+jYp}{ySS289zhC#gjj?&!h7-5{`80F&I@3mbDdu({<_&f^f*u0Mq3eXHi{oyR z{BF_-F!422kALHIlTTaU={_#@g%uZz+;)pt8;%;a4Ly(OP*zTx;Y<9UOO1=g=Jpk} zNS?K&Kmm&r%b>TrwZ`|Z`oUSZ)7o;%_T}8(5bwzE4-e&Cu<`_#orY0Nub<Bp7$ewh zcq~1HMGmHgZTPn{9E-AV2eUJL?&f?uZ2TS?_zAXdI*)GB;wj|{g~wCDn3(Bzx>NW4 zzPJ6;A;M?5P#Zf>UC(Vscg?|0;^!bbTS(W!+0n!O5fAFy&5NP_pXv8~WG)wX#=pMB z)X_krTQSWwR}onFKEdrthkU#{H+(o(=!vDrF+4X4J24?UO@Uf<Zdnx>!U_%3$Y2v8 ziq&qtOhvxOZ1=q!c0))m!=WZVIB2A9jzA<plQ(wemrA=&3coXlJBXhbx@?iw90dCG z=BmJO$qyiNZJl1;D0>=SpR%vKv-0h;U9s8Rt2K^aMehTOt%Eb-u47_!UlaJDAL`J_ zX%{=6({v?F_W|*ue&LJS;l_5>4#948cnlQ(_HHG&Z#Zd^1&w!{BBz`-c7s4!$Qs7; zu(is3gC_`;KXk74{2ch%;4BZHWs#GA0hax6o!vCue(L|`!4i>noWUGepa}jo9n6`Z zo|_9Su}cC;-x1Y!3)T8F@E=qH^Ls_E=^sp0a3bgwZk_YakAaoPx8Ch`o!kzg@hU9) z|KsUf{F(ma@B4I<$SO)I*3D(PrgFC>A?6ZtzlYrK*RfF{A>=l>F1MCkCilxw?ku;t zWti(+!^~|q=C{7z-|zP)?6LRjc{%4i&!I+D9gw<riTh0fx}z}Be!wvqP@_OySt%8! ze~TQu=clWY+^)Fc6|W*%V2*Py`^M_l>LFb&T)~xC!Z)Ifn6*0RQ;=Ep(f88hG|Ob~ z@~S9;d?86^M~*QXAvmo|UQ$3l_11+}TrK!*n*7dMcQn34G>H4Me?`WWYXTHbOkxwq zdTz}ELIbz*1r?pVaArjBEu+v~Bduq~KHKG{GdyJF(k^4eyB9K=sWHutiB8f*ndJ0* z(N&4qtBtHu>iQaW?RmhXWff2tH;Pt>BCM+O);jBrwdg?#TieFoD#ZK?8|o|<v(9WP z<4TCpdoR9vdZz$u2ROU%UTJd;*PdGLu!U<r#9i1=e<^*PwmKufZ!|Kk%fWU$`y<qU z^IgH3SU??aE~aTY=6b19D}pxgjh}o0>K191BH%QSE@qBwIVm}q7eK}|o^Oh64YLCx z1b`B5pfZwEz4!6c+I0y57R<I>{ms54M(>mOw3!?J_;RyH(MIEh#G4d)xu#3Lj!|Dd zMUDEzy7?j*;y*D#^iO!;!uxfEwnXzBi~b$lh5@*^nd{Q^#mCj*CE6xfa)h`!HFOxr z4^Q)){NHl$KmDrA_O$U?_5jUG)QRS!2^EuTqRxee84AOEvN5#PhMOWKHy+tP;U^xo z^6iz87Urjq>7k(-A)IcdX#Qdm(ADF=sG|z0y3!*$(uw9PN`4c1M?X5Yc#TT}&##4w z{AjgnU{zJ{PA`a*CFAvKOLUqdiniu5&7cKRqcPOzf_I7DbIr&5$3(|I`}85Mcq=0l zYpLr3G5sNX6{+fj+~T6r=yBVb>?DRz9ohZl;R=eeQsUlI@26{sjVZTu)(}r}-1n1Q z&qaERYCh???7#KzXK0xiB7d-H@FkH=B^$meevM1~aAPa6o{dkkpfsExZjlvz{0n&a z>#HO6-~T9z%M=zG<JV4`OEE*bYyHa6xsUsGCPGprBpK`(+8<0DTK$0GC^)G0pjWs1 zpy-pM@i`;7d04ZBD9LQnILY8>!abAr<xAss*5;($*L)E+yo!l>4cJWniV?E71mTPk z<8%Z@HPIWI8)o0KTzhfaf*G56VPcBx_Zc>%iZ{G#)}n~sRKJN5F2e5p652v!$A6_R zZ<;HOclK@$b{Q0%C4{B{l<gJAS4o9B2xt9z-5v|(!9mQwbV_J5Wh0<DSeK5k0;^;K zOm8w;=CRnu5N%oelnGkR)Bu13csRo{(fOcf%t2wEM@v1=LhoX04#zFiL*nL<<(koM z2|-50a<4qK3gAi`w=OG<^KV`1lE3)p!pVMEpU+j)K^m&=TMEBf;sbCXV;eP1vp}3r z-TN)QI0D(RF}r*-;s1B=Yv)`){(SMmoqc2w`kY5yR-MPb#f9R5_pMh-3QRf|oo*^s z`||IXU(xpt3c3}iQ=%Gzx6XRkZ4Ln+nF=)aEVUGsO$xgA839qjPC~DR*g==7dxS;# z$K9_a2io7x=g>TDfr0h9AP?u=Qr2KiJ9wyBld)r(qYwVs*$~RkK5GWr<21(s3#u+; zttO<%Byoy1TH~(qw##sWvvU7uTl!o`imTII%4hQm=OJQzQmZ`o!J?bOuFQUt;EIdv zgz9;XO*(hz7PmCXRJb;zMLAnpewJ$uoLR=6|NCOx^jOng6*K~%ViCxm)s;*pU$0lM z0fzJhF5CsyQ6sFV5h;@Hredacbu;hS(y?5McC(eeJLAN$uAWVjR;>b8QkCeh@<uj! zF){C-VYr7T5e0pmW0w&k7IO<*4?d~{>j*jpqa>9Y<g<3&`a9Pw_v`n>GD8^$CDS^Y z$EwFA$*l)JQ)KKDZ|@Se@Arl@B>!@_u%`^!QI;2z#BMh;)|#7+B8M-p3uH))zWVVA zyPO+?Bng?p&6m&hr_{~@PIKJ&&ke7}G$Y6<Nnf6D@6Yfoy1xPI4;C{j|G>S0koK=- zMrqbi#g9qNA`=h-v+evF9R9abNS|XrLn6)u3cY0iB$TJwB~-2X)slu!6%!m=6JTut zNmnQ+oY#KziuH~b<P9!7@e3>9D8F|*=Z$W}eH0sTYb&D``GvkRpP23Olt!{*kYdEC z@5GHWr0tB~kAT0RwNiJA;7}#d)an4zFm<)1TpPQi(6=2e{kFJq)%2(cdj8^h?H*h0 zbj^Il25w|<lcb*ZAy@|re-4>VQIN<ze5C@qiCI8T^2?)Q*losr7QA#0Tv*{Pi5uVO zb{u@OStxRN!d;s>!GMjLyf1%K1Eo*8ge0R6#gFjf7Kg2&Q~-BX&C+EnuVac812<X? znh^Q1d4P)qY+5V}2`FGd-u>_N7p38?(jv~N&W={?sQI+ra)2t55mXZanqLapSRyp6 z92Ga}>m(S!eubkH{P6Hrcl6=S*I@6qf~-YZug2d;jlRFE<<D!JZx`9pHt_+9JB~F) z$Mn;R`%N8_kdJ)=$y;%Elp%1Y9ZYl8Jo&0=_K^EFF=9G@T-<8B$6Ikbt>1OjTwat- z^st$df^nU&4V*SnRTWr&WE<}KU!J)boJ<$ShO1^rLN3aPoc`!`B(Auu1aP)}?*}h? z-o!j-HifL;jo1rCAi_iDZ%o$)61TI*ia#8$K#tHQjV{x)6K<ik|96-9H!AF%WloKg zH*NwVqLqdn;2jPks{`Q$@9=i_!wRTAi<)AqzAea3us&C&z%8Whbx(dPcv98z4vI1K zZr9W!>wR3A+)taWhGu$$R$W>Y4*NSSQ0j$mLXH&G1KKZ=(+1&&En?55M&d`?G=uuj zmWv1()eR(;a&(VZy({PFbEF3xO@z`t%o<-<Pp-QMxTpvVlX_vd#S6}}apSVJ`n0}7 z=oOF#k~-oZ1a;;_QO>`r_~_TiUEQ;D$X(tmkq!!!(Dkv9k`Wzo9XG@21;PEAP<oAc z%2}#lXfa$7xAe}0mvL*^SQcxBbQ=%io%>;azJ%9XQ7pR~Ag>__Ed=>QxTz_@m=->b zqSA({1WrODTj|`$CAQ>jLBCHS0*K^F#YP6WGD78R_<AIeVXIUZow}avB3lz62V`9+ zfLH01HH}KPieNUqTGS}#_J6OcK|0ov7}bS0p+aZL9;~5z3Kslot329eHc@NG?``X9 zqR#NQ-xGFjl6<#rzOcheyl|cs5fa!EX^#W%P*403Cp}Z+Q}D*W_c&0_Q`y+oA+WG% z08ja^?Erq=T({omo!;Ut=_O2X8zwyP7M9+RifJ~>R%N{XX?fd|=|5HdU~~w@*cq)J zdcCw0EBG<=W0E<Mt-sn|#>7^@_L(ie+hjzaoT(3C9`^qS##3*H?n-EHiIsGC`5IIW zg)zH||D7NDSQkn)SDwJTA*Qneeb4+9+JDaa4%ACx<UgME;Z5<w7V%8RR5Lw5pZD~` zk?@kN6PCecqB_FKo!$6?-<i&H;G;kBN5=9d)yOB+L!r3q-?Bu^Zp`aEUd~|rf>2rX zO?))%K`C>Fw7@0j+$PD8q9-sT(p^EpKGxCwru{~=+zI>dQ5!E$4HfPUq-TzrM`Mu! z3SIh8A@sl5*P~npG`dot9awr)NhoZs(ljW~s2%vGZXw@`Mfwu&_13?EH4fwJ3%O*5 z{#}{tR7t-oI#oWLcvQ%h0=`$t)~IJ$9lWJ|a5RoO8b>a*i-&BzM5?aeTQfyY*qyU{ z{K?(Bd4XR%Eo6&3)ayG5s&CR-$!X+rT&Ajapj{$jzx}dj)8EQaMc+iUv<)t1Mm9Ep zY*)fKLbK`gHV={@LX<bV=X!b8&qBA5sWHS9C7du23naF<lyOaWk}RqI=7G`8Vjexy zl{Z(QHUrw%4Fc?UM+k*Oiyi?D6IxYPhAtC`25+mLmOXblR@ydrbDIFdYLAFTXv%kE z1uWL@;j?u}$=+Yj)Qz3pd0cfbB+XU0DR`WGt0d{oCUcsp)K7GgU40pBT}^u*x=Aai zlNk)(KYLDNQ<18HDIBPRTKCOQ4EK#hwLpqngfhyCMmr(7;<L+L_6=|YT`9XVd+E0V z&ZwuXu=s&TqLlqUyt{%o73&kKeRr$H2MBR8QXC^@l$4CJBo!vdCh6C8Ghe~eU<!Fx zm!XgCXXI6S36fUhZ49E{`kxOXj(4G&dLI^N{x*wjs@nh0L!BF3L)m65>+hBnd~vl; zH6TlxEtj|yHEQC6785<x9dAg_7J1yrS%Pqjr;ez%HL?K_f4<YRn-|otO&_O+<b$oX z3yRY;bjR&3E%nIX<kNp&Oa5H;uN9tr3!4~{S_|9u{g)XpavRNDEy{i*RLd_p5s{qn zVgXzees&z2ikP~kCCJxJwIpe8J|l>C8>G}b^8$Q--FJkZOtpRxs!b)coQ#b6iM814 zUx~bYHMGwI-`m>1x5QkwUyD9bUR-6{cnKXyFYmTXeOF%WZ)(n4CULYJ&sg?;m7JPe zY?Pk+qxg0PrI4fib5FfJEwle16Ny1y*5=~lsRXT^5f4<#kQwC*Em1fh%hdMOfK)7x zX=62&_!JW1CC(jPeleZM9CM_CjsScVL9P%QwPd3}T6e)`7Sqp3qZVU`Lov*aP#{$j zbRG29`GCHoHNB%Hn&AoSN%Z`FbQdjG_ycs|S+p=))z^h^t#$p{g+}p*S?A?8wrZo+ zwiDV<XG)Ib*K&wB_p}Byu32cQzoc7h+vgCvRNXl#<>4;nFC_F;$DEqA4xX{LkKpqQ zITW1td*&AgwY$tC$&cE(OhC6lvHze7QNhd>i`AV6k9C(WkMh+6*P|$3FnMA@I5Q2m z9`VX~8a=%CsOxl$n&PUiR+PX6(_|NWl@YrKUTPR*h%{+4Q#)H(+^>Qa&^<xVxvSam zJZsl!vVUd&pbf3q0Ei{bG<U<+tH#8pP23`%Htc=Oa5nMEyTPN`1{e9VbFhkGtiETd z_q&LDX$UKs>b;Uo)`TtBipTtT?-a;^z`Bv{H1B{pk_(LHe=U4!(O|me5VS=rvbw%y zCSRd}d^Q9_gqu6{>Sf(*mc7ZjzY7*PI7H`cAqm|&M!&=UpBKRVeK`byVF?D_=+f3* z3RBN|*_3=m)JZ7Rna8G8aHrJ_Pqz7*#nRAJygr$yh)$s_`Ys-R0Em})qp)@$w(0i; z$9Fah<VKM~boe=ZTtSkK41dEh@F=SKXVm_WXU(N3VYVhi@tzf&d(@iRX9ea`UORN4 z9xoNLTNt?aR=Y7jRN3sh_i&CjRK-yTD2nx*ecX?z*V+g+#piLR&tdn$605CCVk<O- z?MFq~q<Lr7Lti3nNy|Qgu-bMUJU77p+Hcul%{Jiv{Cz&vKToV{&N&u|0T&TB@%=CK zX#EPD=EP=3mM;V#=t3*$614#O3t$@-w43vr`8JkseUggKgH1q<YYiex8F#-Zw9E;v zlL3IYP1+;9<BLHDL;H4rS=qL->vp==XKf)){jBmg9(?>Oe00*Y*7nVl#~UR4{lCbQ zrRx!Qv2t4x%1^()o6r*pem;`FEr8P&F+z6aa3ifX^po1E$KpKEOWuxO6`+@R9c>C@ z_}h?;Q(JKX=3>g4gumiONnNV8j3nQ{-Xj69+~aSqumy{yt~-pk0JwGQPs_|qNf8gx zGc$Al0Rn%5d_{CHO21nYQMF_{)-R;b5}eh2ZdYo=;yn+&De|&^F1z8Lc7NgfuJ7V! z&l<|XrOxLh67Z7y@v=KEb^zuh`q(I5Y&|D{Vm#`m!yibf(c~GqU9FEH0T8%15qY+- zJaQLLGkV=xfCYwKHNco+4@u%4sm$<XasuPB74kb&4;0GdnSKLn9A}S#VCQ6O3&$q6 zvn1KV48+Q}eVXr2eYIKmAo5GBa$XQj+Nz_1igY{<<anS7jrlrX^}yA81GvZ#&=_}t zqf0)GG9Y5V)1&O&f|0^Ekgv!gChO@7Kias(3-c;VsH+;2`-tg%QBwNQut3(~da{jJ z<<g22jCg-jI%HnDnlnTHedW;^Zkb5cL#-ZupsYm#&)Hu}^1GI6!FnN9mel8p!9;CD z@!W$)`j)GZ*)2M@sAqjUqM7z)#BMh<!A&Z^ff+(*8k#Egp4e?Fx1#8u?!T$mG*o57 z35)PK%+|*5hv;nj?k~&hf_L-cwX$}17n?)|Q`fDv$0#8z=<#{)8nHlC0fl->CO;7t z2P{sWp7v<bA=DlZ?i3Il2re75GmvO(53l<zPp*s4&3-pnyV}QGnpehERBf&|ajGem z8Ynz7^hziM;1D!*r|{jQp8NHkqOK`_JGI_dL`)yh$7<RqTVD;YjN|Xbp)+ZNJ4G9A zM|r(pFQAY55cupU1le+IuIx+kr9CfCgDt33kxh;LhXMuHQT{tjBPH7FmD{{)KjfY` z)UR1=5}IVDm@!YicfwWJaD_#frh1bBb(e8}txPjH==>`cBhG|s_Ls)%N+ZRl3s>BE zM4=G)@UsGw(?8CZ-#lz7zu1DCRL6B6GhwwFld)PzR?=BiDYMoG&?ftjCP~~;U=RGT zrP9zp0-)MF%P;#7X^71IVe;m1>G%+3cCE=Id)N+Ezfr&TRqi4>A&F>TXno;zM#24< z3Ipvl{Kjy1zv5PuPNs21`S8mCsy(k+^oT$a|G3CZ@)=v)i)kjE@d%33qi8K%6}#!u zqoy!-X`S(p3)v}lP%N4qJ-OOh?q@%GcJl(jFdb<!8sg%{TIjplEg1@JFA$BGw>y9> zd<3R%g{jzSP*)D~jevDlMyfi(PNG-r8(UjeBE;b~X75Fs1Ch?ihZP@&#3Dcr8(o=_ zNz(n>mFVEtUN56J4Uv@5!L&{jaQAmxi-VRbx6$r@AgI8^{d4-3pb^5=Q$1A?|FOhu z(n>d-uR4i@r=&_AFtgm$Cq}K^mC^#_HeEoc(Q?LLNLt1q5p5Rb7(l7Wpm9D-j70Zk zB4pJF9yJzmKLUKM!5Q^SVCcJCxtq#*)dV518uRBvR6Kw5-@pM#nZRO8Uf^Nb(}qpN z<^%!PS)M%y8zTeg*TY4&!2E;JEM{6=MU$P$D&Eu6LKBxwuY$){|6`r?f<f-ESQ%40 z`?WJ^W2MfYswh)W9@-bU+W+_-LqfFBDFwHMg@bqPZ(LeQZq?Ik4rY?mg&b#G##et< zzt$~uH-`Dx#e78ajQ!G(X4*nLByF2qUR6#(kyTy8fGa5nry%50ZfBl?hy*>~offtj z5<$nOMcm~nso1+%+3j(z_<CwNMkBah0&c?lD>@;@9G-e?YwY0nL`O$~4dz$2+PFHj zx4%$T-*POvRza&B>o|-5WP)unIQk)1+E`qp(k$*W2{^rX>OZ&SAxk&W+0Y^X=c!g9 zu(h>qzIC;67L|vH6DCKPWmK`Y1enY))p|)!tl6&>=yua|f;&aTK6tV@x@(U}&w~Tl z;xcLV>pKBzCZ!J}YAOwEWra6fXJ5s=b^#U9KPD9arGz?}yD)4EzPP>mJxyuqfarV5 zmU=HB<Ts8w+_xgb7-NS@8IM_{fmQeMqnb23vnx)Ui?EJwc%FU}QTs_$)2eHyw<Wi- zlC0Xo2k?>(cd&r-(x}}S-YQtsdH8x`+|*1fn@=-+3bS6dU0u^yvfeM4nftz_dnO`j z0}mB<!{sQd@sRkm#4RkZ(alGGU0+XYDMgWui7t0IgCLA~NL(98JCjW@7;M_J1mhHp z=l-m@=g6*uu*7O4DP1c#2iN>?;g1Ms<zd>LpKr9rnY6f9#-#4#%Dtd^N?LMS=07md zHA}}To1V;5x431dsOEqER<NciQ42h4_vKc8<&Nf{D*zIv<@Y?t5%?4uxX$+6eP#7c zR<|UgFVS>2rIviZ&-!Om#Mv@#<XowCq3c1rx`%9m5;hom-zKaHDv0fi+I(Q1>dq$y ztjWSsUfc;CPeqvM%cR{an$LbuCqD~`)AVtGs3y5hoOnU*uDCy?F#UarvkLxkPF}Lz zD#g&4TD6Z3&}@iFd~oOj@Kl3l>6V){Ss6ly>P7%UN$*;SIgD!sc>|*%*i*V3iL8i9 z#z-^GsHB%UI0YtJjU(^TWo9kzudQ4~%B)CvdDfuvM7b($vHH{*l}vBE)SzXgyuEei zBTAi=-)zQVd|}khzY98nJ@0b>5ZcGOr0iFNELpW$umOQ=N;0~#e%EG(d1~OX38QoZ zfU{89jiHc{RJu<Qk;H1*4Q!Iy1yS7&E~1MKIF86|H6`!Z#0mOVAv(&92Y{en7t5hN z@%%1ILd0C3)b)i=mMD>upqz_3Fekw^uH?WAQZ%pNzm_J!9O&5a)a+&h3Tx7+TC5z` z_pQa|4td#B-TLf}`vl4|3L9^}TB!JUCbC@L>f=TxQYt5Y;A<^;(bBZXW>*A$1%of~ z1_vGpeSuJjL7{HKZ?pqF<Iw|J)cZkqU2l1QI=5gkxD*@;zcvVftf=dlmM8c(u*<xb zhK+SQVl||IG?}AfMv7z?3+`hq;$|)tMiRDyX;^tp{<sCKBkp{au2THCYtYIodb-kR z`+^Vqdv5jzmGbk-^W~;WgM=c9?VG@p5f9?Fz&BhL8o{QCSy_|cbmpaYy{j4fXuv2_ zV#vcY@b;RT_u>j|!3aBd1y_>yo3vtC>EUBUy-;)V?a6@JyYHVI4NAp14-6ize$sis z<L_KU>Ukh|b@Mx9k>vd={iTS=(VS70xJFU40*vcup|DlO6yA8tEv=L+vp;fBsRj*O z)3Mdn7^qfISfLi2b9y8aS#;`gA_8jFv~Fp3iQQ0J8oY_!CKO@{DxDU`Jnuu}BZfXy zz%Pr+%#B|rS@L;NM)_=G2*Q1~KHHBJj}htlY<+XI;C?1O6VoxK&{X^)6`DM2*)!bX za>Od)+&^ePh2u6FEi2(0uHm0-gu)KX^_&H#a)m8)l(Y3(D(gr6XFg#S8xIhK?#xkz zsY8>-Zu$Pyr6yM!kQ%ky^y+zl86f#&h;|UkXL&E-aiGT^xjJqOCmPhag@p6b$!pd* z^gjfLZUmb|%wmc~xb0`hv@c)qC$7`12MEu4u;dmtGhWlzIMyY+!!QwsV@@RjiK!S@ z+%C@4Q`hQ%&{%zuJ7_Bc(=vM52pUlJ7#-)a+5*MzE9|WoV9@!befaKd9pI?WDlA4t zYZB?F5U;}^rV1$3b#jLIh`WIfZk&be>O)4#qbJ(<E#SM(;~_c?osG?EkOMr@Fa^}> zk11I`&30{=CB@&{9b}*S`A>FRa1q9^6l`LZ7dt$*sE_;|eq2tobho`|(sjLQOP|g! zz8W@_yN7i(Q$HO8j`eLx8he=f$UbM1Dpb@;D&L9!YJ7YnNd1y&_861eZ$urg9fC{f zT{EFz!Px$x!0d+M_(OA)VE>#e?`(6v$e~#}GB6B99u>R*ESjVF&WGG8Gdh=VF>$p` zijz=Y;y8yF*v49g&`#`Z_kI0~4a-QLT8eU|G#pBgsgdkM?-KW<X~TM^)sK2ET3&UH zF^#BT=i~$LjL%Ak0L4Y%=TOr(tbS)bQcv}!l`%rH1EzeIKlCe3S6|=F3F4_1YnBW) zS@4VK_dB3@I_dk12P}7NZr8?R5sdKtCi?uwVqi;ta)O(}IL;8*N-(@#^$K%_C692b z+3m^|xiyIt5R6)w+VnAN5<Qu<pcoB%2VI!kw_Vc;+;B=BS<7X=mA-L%He*1h)T!%F z4Th1exqCZ6mt{kYerW~wGtVt4Z)$&|w~F74=d$QfF3FTM8iCQsC|lU-yE#_Bb;j-A zv$8ztN&+|iI%EIJY5vBTQy{$OO*zsr?6MQPwt3ZXg;q6<`&R5&+qj*s9Ow1`bR1S4 znfZw4Px#eo=xef??n~VCbt{&muy{FMf16iMo6n8gQVf3QHr<m}`9h}!4epf-v$aY+ z7}f0p7Q72y5qek7QXr9<nuYV}Ij0RbnmbTO#pT9}LpxNm9I={7GT2F`8L-D^bO<#* zWG8RpUX!@sj+UPO(#AabV*SS2Kr&MMMj<InRBS6y1e$r(3h8m%OM_uQ)9Jp7bI?EE z`q`VB>C@*F7))GEEETzRBW30am~xZIf4Ot^hvq^?c_!BHi6+~0AE3T4Ub4z6*?{c* zGrhch30%3<&pIs*A@Q6@9r>GEt>@VDC%iR0H)}32SMAt3UexV|6hkB|L&2+RxMaQC zV6;+H$oRQFk~>B&(@7V4nLsSrE3V>pGXY|5{$}d_rJrpncfSSfB>#wtaV5Sj=P*m= zH`DKdd2n(!SF1So&`psILPZ0H@pJyGl`wj~`)W&Pef2vI6-<B@us*4gX1%6&Rs|&o zt!pesD5Am1)95Yiv=|l{VV~jqt(6?c4Lm)gq@*qo9e}9zf7)ct!(6d+JNS~Ll*J$6 zR{fOTI*GT*!O;lg@@aFEteQva+&6=ooA-&yBv-olHmZ)7TaJ*|sJA=B2n*lmJi+<E z>mO53I4%h>MW|+HC95mJOxD-xqFQz0)iy{MFo*vlXO2~)ZG#`PO$-;XS02S*2M&AV z_aH{NT`B&D_zS1~Bc2e70k%AVHDNqBKm~pyEoE%qY!+&a`6I{My^vJ8DIPx76aD(; ztxV2QVWEfBSB!+S)A9Ig8ubi~(2F!GR3W6UiQUT!5s2r{Mjhq|UT89>2!MC0DauCI z_Z^34zm&vp-LxDXd>+C$G);Bj%l6hYTz;M!%$V$LUF`3M^ao^S-wn0ve%Nd%Tj}NO zne;mAU3v9=vw!gmB_Uz@hq8Q%jj&1W?BMLNlseA($P_{9Z~LgsD64iW{O_ak=N@Oz zG3H789NSCw#ksJXt#=^ACCMPEQMAqnPQ$CM>&FhIU*JrFwL(Ibqc__Uhz#)(HctYR zD4a;SmH9Z_(Tf*+gXtO$HuxQ;3vv_hYg<o}XAGgnR+lc5-2%H_gZU;9q<d`?9FBv8 zI1OkiFYTZ2H9a}x802*`H_rx_^dH|D6Hy)usl#M-*<4MlLQenlJ}l%XNY2NFEqB?{ z$+t64en(yqTfMiWA{uW+)o{3Dj&84x%hM4@;o72KEwVMuuwA!&b}^2xGho+dgL5e) z<kzsxQx4g}r1p%t0;Hq3XjCF3?5S}D`JTS$Th}CoBx3SJD!<5i4L_^J`4V`T?x~Rh z<|EUyO2+&Ux_~Krwe|YRCQiqkvIN`6n->O8PI?68+<>u5)+Jxbri%Pm<+h_JZym{= z4Bif~=`%aNNl3dUB%exY4_<6ZEjvg#R9tUt0`O74JSidN#+Y6nIO{SS-=8kWBrY5L zd!5^Uz2F$_4!$|AKp*%5jPgFsyOo?&99vaKko;m}hV#it@rqZ&@7Gd;z5!T!3D<MB zienp6{q-Z&u2t*|Gea}wmW33^RV;4C$KlnOI*z&oX-N-LOT3$rQW_kt@S?tv+AeNs zYG1@+xJ3BgiV4EfuxlIL-Deu83F3jz=bJ*W`hO~2QlHYjT25ux*#cz-pD75zJ$ptk zErDpO$A?PNKdCB3l{!?)L|Qp^lKuYtiIpb)Db5#K4NLLG&x<RNU99T;|Ckf)dmj42 z?QFX1c+nz;lU&CPTd~@iclsibHY-DoXPX{@1J$!n3PDXv0ZHXaA@b*Yn&R}{1A-Zx z7xHC&OZeWXxbfgUp@gA>gbNq^W=`ESSBz<>H9Q$8`2NPZztSfOnYcixnN;cE-sL{X zxm53+haFi}2Fk(GhgSUVoZ$S&0$uW%Sk`_eJ4e=-clcRXO53dRILwHXIFv`;fgs}* z@E>%>VH>TJd1*MG(&Tm>%cd>W_0*=r7sNZ#RMsi7?e6DRrR_@(NxkY3YO{5zR}E?F z;l0}>K^%Za4>;jiEh?iSd~5cmC8ro76w)7hGka?jZ#kQjeFq&NVY}XS`HVe>bP6&F z6Y8LR_aF#jpC0+Ge_(mYH3)d953!T!6Z_NFAIvE`k4gFw54hkq<t#ssVU`t<3D>!? zLAk!!1ksRbpo>RGEI~8Vx2mlnc6*WeSz7;1@n@PjPtcwA@vfw&dHX4?1(_ujU{x&> zu6BN`cbI>PlI5&1YxhRQ>1VEzgM^1G4B1)kwjx4WcPdEO9&&W?2v@b@5g`bPX>w(i zieO@pkn{a;zcV-Fq({RqT2XDQu7EkN8^Y5U^p<(ZfdY9Pr#ZCW+9SShfB9s$0_rm| zI-g9OOJwJ|ko->f@I`G7sPByq`X&tYf{#Ittog4jiua5MIRzZ*u8oM`6w%T=D2^J4 z#UZHu-MvUTPsOIdJIa~Wxx_*Ht=9*E>-%F1DPk~_>$CH7=_1~9dSYjiY6-<bFu6eJ zO9(~KqJ@eG>{*_#saL}^(<&Y7j1#}c77B;G_KVWd7+%=iE^Po{oNjo=;uT5!m`B7g zLi2afLp}7Nfy}*WOIqQLb%P9g59Y9kbi!En?5nejA_f=Awlr)a)z+0Pe5hAcRXOj; zluJHTnz@r<Urx|j2L*HTBsJSp|LBxC{Q3s2bn){;xat0syDIu9rGYoHw7Vl}b&Wk7 zJGLt4E0njR&zRW`(KXZ^@Gc6R%0J8!5^CjC(O(d(35cR-T`Q7Z!B$NA6XM~?P1E$o z=?NOrTDxOl>-L;1Q=5^?(eG@(bMzE1xGo^`S1ML6C$qdn^``7FDU5IDOZDFjJVEV- z)%2FjjZ47r+DbJAtACZ7cijE1A1`X8*gtjuDX}f$ec5n=gpnbKV-cYqpvpL=ObhmZ z<#6MMDg!T>bgxEk&xW%Tgx55$u4PJWM)=2C^*fTK{nQ(H&+roz#RPS-T_s&Gfm@;H zJlv25-zz~5`b~Q8gVM}2N0s<-^?x`T6Z~(L>7T}{{b9VNyb@f8q3!pNJl9W6bbJL9 zu34@0i>MKkfh+J6TQ>YKyhDEf_V1|pclgVj*#NKZ{!Mz=z&0e>Dlo#b;ozE^;g(4I z(Pl+%5N!xWEao=Jreic<0!!5&0y`dN4_0$Zg0}|4Bp=(4+=jWaeIJ+})(JT-{0Mkg zP`(Xmh%@xO(;%vL&6)bVB8wp=c^2AnuLA%Uh-B1LBIuvY>3ubfYV?&LGm_$}7uVyD z58$8f=9TDoJ+Fpk+=X%_uUf}hWRuup4Ja|GhV=5e7MTDvhv>YlFz@dR^Z+~bqj<fh zuDogMt)(NobADdEtV^j^oI5Z(Cy4g*SLbDHdCi_Y;Oh!LRr7E>L1!8bl(H<TxMMoO z?<3woSHM(!;lea7P66Co5~Y1-ErQ!?4lH=z*OobZjTCGQr^Zin<rbz6sPlBT1JC!| zwbbXb5?~X!c=oWkfOa;Mj=h+z^+|Jd$_I8SQJ^W%P|tBG_b>TrfemymUUeLqxJSxC zsDJ`<6(p}EFeEa)FMJiU_f0=rAkr*!X>FJyWo*l1+sv+UifQKLBN0{qMZ|JpSMSC% z)*|Kq2>HDf<*)}Uq9xL|9)j-GbXO~$0F`Tx+Vz){<qC^H+Cd@<_DTg}HY>R=Df}5p zhS%dZ$5mE#f}8h)q2`=@OH_OVyZMkdS=I8|@?@f=T$t^OG5_Aqq`vE%X!N_}LHdSK zUH0gAs)5aH(f(E!t8EGwTjfkg4LhRm_&#mBjC{`MJW%8EuB$|n42<1h>)u~XkS%C- zy<{~$ZEdLP4HMy&C3}Y2gE*Y^x1>ImCI9^LF6ESpC2!^Mo<+gm*?ej0fF&qu)pu3k z6saC@alPuCnwNk?_dM^#4aD<<DBMGcHpE792I@?ETdCxxelV9LeNaugi}7Dm<QHah z?0M-$9A^QO-^R%8d~ZYxTtk+-tl@=)-5iU&4cnQ$aU4f#Rg;)$5W?<AgJ0cS_lG@v z^XR|){85LU%E^lBBmF=61_S8NUtQ$9Y1CZ@wE3k-n#&l;BOTGKIW0M@G~|Ny)42!_ z|Jv<lP|A}pVgLqc%4c%WzHvpxo6DVdqV?n6R_xukAZukZjY&w5-Zn+U)Iz~WLhPE? z2mRbSb4u2oG6-+MDs&Qjc$-M`yk;35%z}8c+8XY$%1m|TN-oS;s1mdy6z@yzpPk_< z#*+x)m;r-;Rb1y&;H)uZ;;E|DnWEXVC+Shlq4PLf&N{Ek1z`t1``2My(GBjnNqgGE zjmX^Zk&>^5)G=XZ+JYGox0ILb<xfNJ7$it<0wL!$jt|r^Z@_LSVx#YJ#`5b)q2m6q z_c9v%n>Fzd7)$Vbk|BMeWxkAxo#46MDKLSjMkVL|1^CC<!E~L`c8t%gdKzua6?Hky zkOa-1u{pGJxqs9Q_#S1I5@29l_CV@EjSL#>{ouv9ECcMlVvbv`>v)Z@y4|(!<#GC- z_jFlgt7Y?!x%PkE`@_QGt->^d^3K+VdunHv)eXh{?yOYX770dg4(q08KzIP|XswM( zY*-if<N=`wK<Kcp_NIh<7qoqIK$=<>pQk}+c@XFMhex{X3SDpfS66S@$t_EEE#}qN zRafh>aMZ{?7xy7l?Jb97y}P{W)W5~qkvjdEsAhYV0c(iw+NO0^$n`YtVIcbbvw~nk zXZwXSq)WwxO+T&=e@;$+aiFmbu)=b`LYJa3+mF>H2OIVXE~%BuDDhbCc0}m_c|@gi zQF4nb#8?c=b69py^2e^hLxqDOJEu0*r0n?{U6xjcR&r)ZA(CcNbGYg5^d~oby_$X} zBwbGWE#mbG5%u+#1P*GYtAEyXV-Rg@JEHpEXXQI>>&!*tpxX#N|2V?CSr_vN6z1_I zgQW873AH=%;rW+V;3Nk$cHIC><@wDsqv!u()b2@*1z&++1tv845`l%3x+mIaUsw(a z6MA1I7~Nys@bxz}n14yYm)!C$S+XxxK_UOBJkwWP1Pk*|Q0KF%ZkN3leMsZ%AsnXZ z4LdiBcz{d}A6)<TLxQcBs@P1a_|y1>D`T}Q|6H{frMM@RT8G+!TY*e06L>L1gH4_4 z2hRyzeen~Onuj><GX+ap7Cke;n?gFE8id!^6Vn_e2KIVQvs%Z0CGMTNrw!x63#brT z`e`5>5rhd-qnfD%H@A|%SfsxRT$&^MmeX$d-Pg+WG~5vQk=E6sW43$g`E-T?-g!vi z9{Bu^@2{)Wy<(;6DW!>4Jjr=9A4GMxCXJdO4<wEr;OpK=LraV!oQsJ1oBA}s%8t`n z8Y6yZBEiXmXWNrR3XOP|co~k4vzH{jV~li41@~?Y&$2CYaR`8u@0m+PH|x{xPCv2M zKV4asGy?b>exoQ&C}^LO?XKY<y@Dsk3L`F(Xq0x0H{P>*lkrc=u1{Oax?J58@zr<1 z(4BUErG^H1b=39zSD=GI{eUV<eDXWmi+NRqB~?rAcnti8_S3_B3O6!+Bfi|Oh7bj1 z?3K-_VGjfC+I~gHe9Wo45=#~;xne7@ORcGjbpr)mM+~;mv7lD9RH0v0kB>#wrT3MU zEo~*X#kRSQLQ&P?`(HMKi9wc=K5L$rQXe&nD=Hj8%oMA8)aNNVzrSY-2_;GGP$ucy zGV4=+9!FoFSGDC|@!mb~LCLsvHy$g`TW-cZD3MSQ$b#1`^`q#uZA{Rpq}AK*QCu$e z6_vS_evnArod!rt-Z=GXV*DI@Q@rTq_6bCoB4O}{!RPq;i75^T!SdEYV+}|`5P_8! zrYBg49_aSj6hyQrphcJOR@E4=SbdE<U<3%gK|EIyd^FMfSFm!|o@evM7=G~2^=_8X z-TdZP{DmRID5!$1<V3cK-*cAB;OhH69W4n#H<>-ufEO*9=jHUx^0(&iN1o!#?iP;u z|8=SbFfNm1?e}<}$w_IvgwygA*&{o<E&_o(pQHLC`n$xnP$3Kv2sebj_CsJ~#n_Oq zUZD2iPCEsI&UoaQmMkFFM9!*R030cFs_C0&k`)AX=6v(zAXZLr3we#wR6)P7ZD5)d zDb0Yh{RGtH`~{8IkJ!JNTygH#R*^2Neim`&m6dyc|5y7BdpYb^t=tTHHii%Aq##IC z6tvnnU_1k98)v-m)%~Dr=-{1DDZ2evP=Tzk9X~E|-~=Su$6C)^UsDflYZ<wu;@87& zC5^0dIZKa{cT-Ba1*e5=>I5lTSbE>j0H%>xA!uA^eIO#by0Bl5yHOAMI4)r1O}hTq zAj*RnZ}B+S;C3BH_s;%Mre!ku>eWf_P1&ue7~pmI?i%kd!_?XF*3zj@zkCG*sG8Z? zOMIOBIpSKO(@W#4V7K1RQ@}5k$_kE9g2b7ED94*I_fM%u+at$+)T<u~gi!4Un==?e zas7udPRm49%ha%oU8&vBmaV_7{hp`Z9;rUbuw}Ks+>PhoG$zc2q{cVxm3j;;YKd)M z(v<;II52Z6a7VI<1&yroUv-LpHkM0Dpj?D=8zp45+~+jYuEwPiNtV_bf<$uMJx}_i zV{C`Vl&8m^aR6oq?<96+;~Al`y>oi1*-K3iGPnM7%~!MtI!NNs1`D*`SHCgnQIdCC z;Rx>d=T*mdsc7D4?H<Cxag^i|<vn1QDbP!51HNyC+Ob(39LN1#qpo`Sh&S(XSOG5^ z)h$GwDNy`Y7mn#kD$8d@F@i^Of+XS}aCo1v!nf-%44MErTqC-pPD!f~Yujke*^Q*H zfYhe`hv?aZFH=#Rg6Yhxj0cg^JZ5^yt-YC2Kvwcq*d6G?Y{p%aw`pZZ$cTh9?HRIE zOPO+&(t$P76=cx5z2^0ay|O0Df-lL^o3UH6{Ec-6lxS2#6T8z$MAIJ`J+QY!LHhQY z-)xIJ1J94e#hAJ*i1@w`1n{pZ@y0rZIGM9ftOHH1J6{(?u^k;WE-k2!&qk7>Ar9wb z^Ai|fEPCRmafuQNBuluRdLXLvhza|*AJCp9B-wk;!Kc*GiAwpEJqv=zneM`lk&xxD zcmLY2Z5F7ffdp)_ry7hcNd1cEbMhgY%#c`{6!S(A^t?V{I5PND$Y>f5{0D95KtFKO zSmP}4?BQEMAZ^1Zs}y?_Z3N~9Q!>k_2rS)luZ_Q?z@l1BhIw$MwcNMe{V*U$Tw!Hu zpA<-JgBi(O{awtjNRR%UgsOO^eSHUnM0nY$BWahL3fbb9^Z%|ds)S8?)lG{vE-Xcg z({J-ESGcoP7c+L0a>Unn?F&kdI(h^ShMIy2EM6G67`zs6ydm4)$PT=4<XB5@JJUZ< z?)vdeLr4IhU@UyQ{AmVIZX-$C*gO<fW)MQ1*OxMl)Bf@Mo#Ang7AtN6I^A>U&x}6b zkvrk<eOggV5OJY5^yl|VG~3-^G8+dPS0M&I=yqJmEqP7W(7swJa%eKbE`9Nj$LUIy zt0u`87-K;(jLQA686`UUd4)q7!U8ly$rfr3O$`nS7t{_J)dqk2+N{n*=J%KBfLrpo z^rleb)c(_-PyR&SUn8p%srZ9yo3;X^ixFiqscv#&MPa`*%a)EI>PepcH1?j`MI3YC z81I%81mb8q?Ql(>R(XU#S@ChBt(taAJf;@K7bVKd@3>kJ`2zMu=0Sq7X&}cWtI*#$ zoThNnqAYwN4OOHwc8+&OC-8+`zgo+|n)w{H8>-}}UD@|e5(e+uwuvv7cQY`bTe2@b zFU|LYg`m88k5sAwOrIkci5`4=|9<ZxPG_qwQIOIOK&;={M`VY0Pfte@m8itW6UTpo zA`JWjueiqudDG7kL%Ud;6C%V>`;*by9a2#f9z4I#?4ZVbY@|sMOLg&I<<>2-!;J7R z6lgM%MlbrD(v4Ptm0n)Ut|Xz|T`1+xeL>jo|H54+io;stsYFs5ioR2UsGs+Qa3!l% zBJpK3ju*z3$f>ee?d#HV*+!48XSbmTv$G4`NhSJ2vnC;T+~)jSr?n~XbzoaFX))p= zlKW0mkxSv*Ls9oi(Il7JzRbCMoKTqY_BrW;zfL)q<P_cZ6{q&f!hpUMG+$6o$z*bO zf66PG?_R`qr>kTZIbYrt2>B&}{cW#K6=>RXZ*hIm=Fr{tz1uniKlQ}P(&OxaCsC^| zgIsNpo;<aU^v|kC3asB=IY7XH8+?4o*Jjy&nTrn^i{&l~WbY+&%54q)X;Y7Xk289D zBc<XZPIb-k!$XO(!|>d=h&5(aK^_?gj^`^lwb)YJdR!!;fpXo<JZQ=Tozz1SGxqFV zX(XGsh`w>j&v!}4%SP86Rxs+ufi7=Z4mlZH1KSTe1y{<((CgdxVkMH`NhUb+aG$89 z)_i~mYds3=hL2F)3@{lb?p0PAMTa|px6^P4w=HOtv)&h87mNs-iG#kjsdt3cij*HB zZDZ)HRPQu8V`z20IynBSta){B8TTU*EXv3dM)Hmt^<RnGIrVn^&WuGR1oI#bz>^Gj zT63&pLUfX%tdCZPJ?PE5amDkuXYsm^%AH^Rup8%#m^SPSZDzd5{iP;)%(@)@`cU?Q zu%l~0o`Tb80ThxF*pzaiBQE(WBTq<{_uC)_`$-IzvTkB(BW5eHYiIw=u^;vq)%`3d zuv4D+!-RVmMx%q{gT2J4lXF*V9D~)I@A3@w4+-kDY^^F6hDpytA7mVYUqtEfY(?-u z%4@l<rmsdPc1n6t1hG>$$vV^)7wXTX2hZl__KR6@$2xNd%P*>#H!=1~AdG!$F^%T- zV&Gh36P7$03BnzJkFV%}FhxqAT5*PzmUO~cwOf`De`8+qlRcwH7%doO{_)PRS+YGV zw}Y!UQ!+vd9-bfHh7aslJC(!fJv3m4gP83lV0{%SQt_`1`nOZk`|0_g_a`oUmh<<9 z^yIN$P1b!8v>z}(FjQ^(JXtOpXfm(H=n~F6Ly|jF;F}gEJ9)PHsM>{s@uobeEOWkq z5OaeD5+37r$k8<n;&#1@L7JMZtB_E<^?JTn#N&RaeAbCrRL94&ge`q0QW1xea8hhw zKXLSHqFDoumwxx}o1vEaTEjZD@!^j@@0G^Kf1C@h^OZwhq@BVo$oTdZHqQ9o;yA_3 zA#m&fh;J=b1~VnrK)yT5R;rFFap2fm1v9WSC^znfv7^AT&B1IuP^1+)cgL({?4Y|} z`m^te%h&e~Y}fNbKr1(|auQnHMO-w(HnngjMhwe{dC|kIRwE$tQ51AMyS;Ea-(ia+ z{QW;d{4q7Y=B<&{v0^MEM0?0bXUvD{+02<rX<?GT@zB7YyF*_~(VUu6y%{@2hXYf| zqu+g(uYcxQ{%ogD^Ayy$9n9n@d`u#_o}L{O2o!XAlNlllFUdu`unClzib&<d7{CRI z3qLQ59i_ZQkv6vdYb?fT6dHYKaAjx_4DZR<7Yb=flnOyD`PxUPdZ1x7xxjR@g7N!e z@U3pHpaUJI_U;1{nZ9yTM4%$ooYpe1F=5}b*V^AO)7&*{@?#^nxUKbjfF<8btdg;b zK4001l(8OO;CGSTJkQTdsi`Mh_<X9dUv_?=svGBxb#~8}*J1Z!Qv|QBz&z-_2v~yF zwKcw@AIB*4aFb(4hdI7h=U7lPTUK;yFWindxqKcsEe``pBl7E+H$w#TXNUDW-NHov z=6C^5?->;VMsn;P$&%Dkaq6k@$DX^#{Hf;n<ce(270ErdyD-b$??#W$JY=3^-+vWV zatQvwHfD(U-OYzA3jEVAfjtWhUY6(o?8-4|>pQE=xDO9QAK`cp7s-Or5~DF(7{YqJ zn-APt>a0;b19yO&s-P8Io9c-$a{3r^Q!hLl@OIHbO!eMkp;r;r=$LpZnz<)vc*Ck3 zH2xlXsA#VbYw(V`5~0FnLj1j)#rF>X_A~zO#U-A(+Ht>3@w^y(=CQG{wk8kM5?WoC z4^1a$J0M)RR@E~e(PxFn{GB^~8H#RnOd0#g9(^3SNvJ)t-7Q#sOlddbIQUpHRPDC; z8hR4wJ5$~B4liE}*}c?CtaqBA*#Heb8ZBw3foeQ_)B{XR^62NDfiz5nMTv>xM@2iV zY>m_$Kl4K-rY`o_uZ_C%s+RpV$ArexmoMGW4V}(ZxzHww891+f>{7ps)y*Wv7wUwY zEMoz2X?RejbPBH!ebD{YUFe?Hi9?%f`E9>`qCWAb7ia$MZ^^W3>^nZ4xFkc9SjHGD zQ8|a3Kz1hLuWy7MI`OHQ#0&R36*Yanek+Z-5+LKZH0)y42&Dh%lq#~~{O=T;<>$52 z1%3I78)C+vBFqJp1R|QW<v+Ds547F3YJWJRz-b5B@ROzj&)vLtlBsfl`cOdazm#MU zFQ;`tNxRq1fP^0epVEJ)D^VWahTbu!J?69=P2}Q7`c4SEdyFNubqFAhOxK@C9feXT zgZN{f)TLZaPY=HjArFscCmpKtbP8^+A2^?Z{}qHOELx^f$_(@V3<BnpVqDj4!hrOZ z>jBRa(j^y71|v{j=k3EN(q7AT)~9U^t+}3anJ}P2#=%AMq<a9Gp^ol1p1ZPHnGs)( z?P1+S535T=ldhzw@)*e!$wcqr#Lym%`6A{)`?OOqC<8+E%*Ohpy>nnp{F7oi{H>3x z#xCn;I%5KJ18r^gqm8h+TkFFx-xe0rImDx?lQD^jBgNIKO6vce9`d`IygD#?(g_9c z@42v7WT)pYww2tmcPhM@shxTunCw1Im-S|m?-vmSeE_8kMUHIpZg@r-raHcG7eINF zPoMHbYr1`a?`anp*W7uUF~Hy{cN7F4y4dEl#=9b}(K2cmVw=^o{hX|S-8zK=hnt%K zrG-R9Q^%}+^;I;=21h(-^4YCy)n8bhADt2`!J20;t$>8qx6V%_XH{-v5xkLckED^_ zdQ-YTU2HqL*u8~PO42jpQxT_sOr-)?3Dy232%PO?2|`6F&70bj`_p2i+SY)Go?hh> zr7Q<jJ`Q@%JZ(X_?JDbjkE3=leo#}u?r{bZYeV<eb+;qmQNE3IU0M>1B|wwjqk@ak zTR^V|)xCUmT^rsgjQ2*j$3bCKd0$hf<HQ->SMQrP?u^|oukcVw(&8<YK6URD)si@4 z{VDTpM436IAZ|al`_!GAY40Kt6wPpvU5bO_CkOJYC!%hQpMVdIx|+971i1B`Mxzu2 zCZFKiSs%VxLyeSpj(PddqEJy%E>=h-0YQNeP8bvIQ#DMu^3>Z3z<-=lJx_XAG$M}t zS8Rut$e`Ck58yL9u8Es(q(@D`pS-)#sIM~@m+o>FF=a=x1?l#$Xx>TohO&kd<MSfE zbGXj#8`nW-6<>(Diwp3o9WzSG0-rG{aN#&wxYY4ToUK0uV3(G-A#nQje?}I52KvLK z6Y(V!9#q2gW&h}Kt(!p$VZcn#ImHU>_VjFSS+4P?(JSm*&jz1IJx?owa~DJ%^UWWB z<ZopoaE~E@9XjU8O5l(Bb_MKL-HM9_Y*>ZhDNq`<2w%*WBzT-rw49XGDr^Gh(voXB zBACElvz>5?fMP_yHlFtZ#k@iYpRw;@?>L-{1e-FaZlP*kB${`D_n~`);HmIz!@#_S zoN&7Y0Z0f2gAg(SJF^tuZH-Y7J1=@Z@VuE!S=?QqN(yP^ml4df`<mRJ9r#XVgvTm5 z$HHqPV0B^lQe;aEc6Cw>U<*Qy*?D6CBky}*!P)v!p(9lwD@radV(~k+x@P%GG9rDz zxE)yBw!JHE*Ta{I*T1J{>OAq$S7s%)%5CDS;){Xz(oHcD@~(^Ld)o3UqEX@7%(v{6 z3T`P9Jc^gfpluzi3Ye|`AY|6WTDw@zgrx$`&$=X001tbaq`v^Iv&>Z-hxHQtdo8-+ z0dB>YYMvbyL6Vm{XXwZ}@tJx_{d3&SV~6k1C9Mtv@AEk8G3z{_=MJo&3*M!+*rh7A zFTySagBv{Vs{g0s#j9ro%xM0a5yB;e2z)NOv2T()Z^`SuDli(x$_Yl_{wq`8HQ1cQ z`tY+I?CB5pSFgseD474x@v8&yWU;{R8Cv+17~AA&MTGA0ao6>aC&N<m7;;{FIgbbJ zR#KWYEu&R6PM!}FdK9i7UG^0|ltCQ+^Q1FUzem!y*!$vD+N^=4cA$C799zKVE0wO? zGJwnfq3gWk;oR1~zavEuL<kWri72Cnh|UB-)X|w}5k~L54MIeasAKfrqQ~f+=p%aX zb%@UB{k`pHpY!bJ?DPKRgAn&x>%P`ie_!H~WYHq#D;cC~iBZOj7F9*C;`pBM%ZM&% zaw{?kBqXUvxiIGYByka4gJl#a>hy;s9;pT6*yHs#H&Qs<<rD8K^s~*ZJr26JON184 zE_Y7j37f^W;lL=}QQ}9HlNtw#GTgsy_FK-|5bE4&za1XxnUNA-Nh`7W`B%JNTdA4f z-J{Y|-<>zby=xHN=LPo6PG4{DvNV+Dd(3yZzmTFzWump7;0dl(CrZ>=z|4y`h~yv3 zz?nE(AF@hu2kmX;v5uasBsXNR5;;#WWfCz!${kdA<#-HE3F+|qwi82JkVlh#LnwV7 zgh83Qsaz-$vpfH>bw-DGwYlL;f%AMN!i2A9<R+qWVq16Hee`g*g*FL+nfT*`ZCi6? zUVmKY2T2HVJ?nft_TfEo+zSEnwc#7##m}}E&-Ot=UdQ`i>mBZNEQcxdcAf!*`i2AD z6VvC4G#;AJngBgdOi9|%;R-&wY6>JYpCrL#pnc+6Y%d$HMn|@k54vD7O+RJ0C{$NF zdGRU96NK9^BQ`R*B<p%!fCm4%E`!VOhuV!lE|+T#mD5V<<(Vbe9)L<|)W7f}_m--U zX@0)jj(5|(<=`Oh$IB*7PWZ)=s8hWAqC-<l$=R_9j%avn!sT~*I?7E$)11go1YQz` zcq;aZ3+d9MiwwfUgGIf>99D|aS(7;iwv&+Xj%?Vgn75`_7`7#%t)=BTn$|{yBb$N$ z!L>?*$vvFQY-abboy=YX6dTz-t0sfQB~xj&+^Y(YlDXMr<3Fh)=1ChE=T|5DOE-p| zBUI$wLq2?6kaQ;<>?4Uj%Sb#M_?5_2aKQwvwK|{!XJf_>rCgt6i)`$?F&NT5>+RA$ zlE)JZjD|lR%~a*kksq^KFV2bVl@^Zl40tG++Pc=`)q{9-JnEb;9ya5RcYaZ%qk}X; zy5Vc`DSzn5E{v2G&ZY%L8py87pZs!H(Z!b&>`Db`ml2=`KlNfBDB=OaJb|l>6c!Nj zN}{i6uN8z62Nn5~zp`~PKN-e@F-SgSkg+*gO@A^@qZH|;>{*L)rys0ln3;bH^FVT9 z+acBJqB`)q9Wy7`v2;k4>!Rv2kVL#uX8v?zyd<SpYt>f=sGs@GVj~6WYV7PW7c3FW ze3<bKN8@pHb>`TEl{##_Jv`AvifW{MX<SiP)<Q<ae^N2A+^y+0MXBJhR4FT+I*Q>_ zs2~(Sk^31{GCeV0MWN+Ks>@sYon@r8zl!g-osQ{z;@0s%0=FN&xvU|_d8$GWf3N7{ z-#4|uswsKWldf)jR_#x|og*q{+$Jepdl-_M*98GHty#`6)&%l=F50{9xmrrIsjZFW z3UYE;`(o3@q)o-lDtx$4niaB96nxe3qi`zy!R3`fhTZ~jtx?gZbPjc)xGyy9SYJ{{ zHr6sOZEZJuU64Rty^c4RSj}MrY46yzE>vO@tH(mX(PiGwv*5h5wGHh_{n5(`)kEdC za`ly^R$hb??>q|OU$RaY_=ja;*`b6=kf!Hu0S(@FGiZJ$txp=sCXO1?c`=p^m-f#! z2FQUx*)H{aiK@_C`Bx_i=Ggi}Fw59I?`u^nhx@<JTH{(2$}DYi;aypAQ;KDw6ZJ>9 zZFhjf&giGg9-CzCeKrYsC6;I|V7Fee>w0l83UPYTtQI++gY>A_KhB3UWUC+)IN_^u zll<IQWo2YeEVngkmMHXak@7IHL3EzFkSbis@(6x4c627fdjaoK1Hbxcy>Cv8&dFzv zE}eP~KmW8V_wiNK?L{?QMIN_rRMyu+u$gz`WjpzY(FC23fw@eM{e@sw|1LGOZw{H{ z;B_MeY#c6nghkl@_@;n<=aqYL(?+Esl?u#bE|isnfT)7_v)_fxV23}!S@Nn^uLsqs ztjy%Xg`)<HS#Gzg;eX3PM5?l%B*<2k$*bar=a7YLo+!Fh531pZ<{;r&-x(mT-|IHA zP(yLDl&^-dt0RohKfyttvsDsa31;3;SbGu1@NMc%hzhl08LUwajbgaSfUZ~&EHji< zEP>7sR{KXk>;4{<*(fN8Lb*ND23cmQ>?;^)v=2l_xUc{vC(Z*6bR$F3ns!Y+AkM%y z?DcsQuBNy2yGwK$j%|siP5z-Os<)nThVjU{h*AeuhJbgVtbI<+qoQ2Ut3OzeCn_y( zUYG6_6&TcjG=r3Ni$&Iuz5ixo=N66V1yvAX&0xtMTUDx7Py5?Cj1<92$i{*T#DTU2 z-wrViPsX0*h6;I2!8bf$DoJ`qC8?}f5maOyaXY#2L@4?bmUYm>M-Q}`C8(V$*~>+~ zz1A!dpg+=65bDt>r#IkxwvQuhv(U$hIa0%4QC)k^BU{BAg)y{nD9b+~^IBqW#j4?t z=H%nWPl+_l*tqVN`Mq14KK*^I^25^Ae^}^oRYtKWee61VU^O$jUsOl^B9HjCYC%#$ zX?i6hk8>z_RIjW6((Ygd>YHg+c!5XbX%=}fZ_Gk4n<JW$@qJmYeOGnXO#5e4)Cyuf zR?ht>m0kfI!g;Br!}Vh7PrbJPkwf~ogbDx1-P%Q(ZBwM{s~g%n&f_p#MmZogwxWf# zn0;&T>Z#7V!XIIVB=m&qHg-rPsx4P$E={zQ?F48>atf*I<2Tbi#5I~;w8afrzRQ{^ zvlks(;bthq<ki16ooiyiW`Et|#OD=xhgcELh@1Bum`vk%#1P7V#DV<8#thv&*o9wa zm<Y721*$9CFbroCPS+Dr|IsYS;p$I^l+9GKu3b#_r}+w<!>FzHseblclYO_DFS@`H z?HWuBcbh87h}?p4dc*?3%}p0su0FO`Pys83GZ5v`@r@89*dln`kGocQ(+pxEj2d|+ z6stuaG5Y|D{4#I{l5ZAo3ajEj#mdlI6@GadLU1vZ=a^4XwKQ*WbL~6AkiC}SJKafH zCfn#|_I06JEVTQ;Gp#jTnx;x?2`}0@3E5g8!dXU$%$yLQ5Im)`U+mV4rhXh=bbDhj z6txp6XIHfXbV+8{nHWNAKypT6e!b!^v?bou({l0*r|;L;5p@>NR@RZZEbQ!~HS1BE zBJ1$Ojh~vJ0&V?;FiL~tgQTC?qVL$;qItQ^B@TgFhgL_|>L`>CRgY-%{#d}e;Y3Nj z5D+jUEg{Uh?9k<|t&Or$#(tS?nOC1iagUbodDGjts(%)Vpt<9?ni<W@s<v%E<=iD- zU$<i>8$k7!M%v$mFYe&96Mgi02E)D;c>Q#qXTr}mwleM*%Hg)IJzEX(*kK5<Suojt zn@uHs@~jT;0}`1e?1oaH#iX`4hP59!y~SZ7mW;b-XVzs?m8yt_XQP0*#d<dfn7HX4 zeE@exnT`mlg~5Q*^B6!)S*8z<B3j1o_uX|)Im@nhHdSo(FugrPs4$Gw|9jxkls^ZI z1cOBFO5|vhyA<dcaBwens=z8$<aah%uNEj8juFi-Go<57-l$PIC=14KWb5pPt0oF~ z;wp57l5!AA<9)ny`wnK*fZsj}X03XE_PQ-xPR0WYGT(uS$#7{Q>j}p2OX_3~F)bc1 zQcSa2)}vn^q2!{u?URp1g<ZdATgE;~Ech~4ZLTkJjyN!0BrZR8ydQKEqETjtQ7)Cq zyX^9H0ktPk$R+njYS7k7TYI{39)O9yu7UZVD=dw3f{)YbW~P~@P_AfgIGOMn&p={N zW?@DoMN(?hiVD&sW@7{p@iVLObug#8b5Z2NcD^Q*@O0iVz$G$$DkNfD1<QZI2VE*7 z^!Ey}PY6y}I=o5;K+WI$q-jK@PNEA~Gv?iAMJCRtCdEJ6M{rMJ4>D|GA$xwvO}<)s zpv6P?P`fodc+czfy~Dw<W(DTrvH~4ZJ{{mWuzd350`U3XmP$kaZ3O<;CL}!xlhI|g z&2MDB&&(-rdGx`zmPTq*vg27eCa6;=fG>zl_J&8hThCJOj13}$jGi&`XX~i_67tdr z#4e($H9^<kS#U^(fK2p-8)x^3MjX18fVF?`IM7jU<e1X&N4na@s%7ic4m~)`N_pyi zOi<7lOjn(hnAI(dPmD)AJtG~7^5Kqr78upXva)0q=@DstX4X9Rlu}tMja2m5sHB3a zmDE4o4=4RxUJz61BCx@T=FIk;q)_!pC)<Xl9H*EnHH>F-J2KM_F-hvNtLtM+WRouL z(GyFiT~I>34i4}wJknLF$Ne4@B5cV-4skQSq~F7n@*Mjqj4x|YwUq7{Ah(n9+MYjL z1f2fqYi;U!h9!E+=3>OgDo8BA3lQS<?8ROv3f3PHvCCR|3Tb^3kCltRcX3?&KpldB z@{M>!A`}h>HlpGXBLkK1N22qrnk00r=6{r)%TwacXY20Kv`OM&5;NFfA0M@{w?a>) z%=nxJawYJs;16(b&R2a}O|B&+GZOJyC|`HZO=*elx{N@CQH+YBayV<vy%AwVErGrf zt<|A~hwcTN_sEH)gFKIsp~F9p$}3XHvT0O(&5sV3q99i-=#e_sZH=VXGt&<?Ivx}y zX@@u3nqY@jMklet=&_d6f@u{|cfJd{)e_ZNrggBtdd1+fz$(1afaGiPPL&MwEXtUf z`G{a#%;j&ID1X_DF}_>!S(V3RkAPOI5%8^lX#tSkV(i47S8-<aVN9SHdP>F^mtQ6S z2@u|Fs7hQ*EIsBPKlqi~`6=AqZ}?jvIG7@!BIf-&7IOi{JnBeUS^7dvpK>3X%M|bU z$*C-w36cl%kr7*MDkDQPRto(RAOLsaLPQ+yhZ8&yq|$*hk$r{~u*KuWescEYVQyl+ zeR>QufdrhdjStA+O6S`v9*5wB_vY?_&jYUd&_vt280kT7NSD6CRx=fN^#P+uD*-D@ zsV-5YL9CS72&YWBj+%$#gf(_g7a5Nl%8&<74>-fNveO@>k{OtNrv;^!>f&qS_9<8Y zz$sz)=#EKH+VWw-9agq9Wkql;fI=}Jaa$kVGx&=1Gti0^NPVOrmkW)BZYc_Eggsa- zqvTh9q^yT);p(oB=)B!KwTH>vzc?+rI)zcmR1al4CfK4GgCt9J$>xwNDk_Y1j;`$i zR(~*OoH}pP--4B%UvS&OQl4Ik@nc-2L8j^QnT~Zp=K5V?;|ZWl^WG39BrGF0Gcj5L zrAU{+qm-69fK*)}Cb-3uo45sJ%QGewW3d}*VzHOXXM=hG=(cu*ye@g7ygYkz%>~qG z0qNG5MGqD6?{u|4*@R3UDk>R`Tt*dys<xBGpg(r8>g@)N;3~Pcq4-d3(vx)rde`ME zlx`mD#g|YPQFm9DK1FvoAmOp*Qb$*=)mL!@j|i1M<)C|9>Ot3*bdYaS#yeQCa_JRm zf5hF*|2*40_RnnA|G9l`eq0QAt?(6zi!=0KI0tF3NK|e6RzcyENGB!kNx7fZ%+6;% zd05@6Y1?K(RgnF}Q&4837S_)uL_eq_hw*STEJ9_eRD$08!8nlvNG>ji%tSTuolw-n zaqQ~|hE&~|p@_B|1cj<XeRf<6pI3)cP}^#pMPV%Zv8h|%ryUi9V&>~abWi~>-z_gh zmWB}P4*mLbcgyDyZoqc}RJ97{mfXilqB;;}ed!17iB6u5!iYAtrJUFR(LQVDL<I4! zX>^&H(C=F`_6YHk-TB4{0b&r~KT65NtfEq)>d!OJt#KdEH{W=aITeq_FQplo?+f9_ zeFmERs1U8|3?*n&1qo-N%Hw4F$0wwql~$f#q)fLnA&dcY{Epudl$$>BDj!}|m5Sh= zAQsBYB30H(dB2~ld@8+ZIF#y_yk@kPg9zQ6dt~2Cl{8V_tVqqG5;RB7S>)$PExYhS z3im;j$`6`}rPt}yFVusOhqMB3Z#!pFClppL1ZiAl-qIzwDNw2zfJo?>&mmJ(1tnym z9IX$&iy%L2BM!CjSDfdF#?cD}^GZPpBW<O(w@FqKt15{!1=(;*1UGAFG(Le3<jA-E zCA{8u6nONG>=H5s$fs_GQ97;E9c?w%kacfP+xmpN=n1*RjQ*)9NWN1%Z65_iSC3Gb zX;0dro3-Klv9frhYZdv8OaVDj{!Wq2Pr*d0XDH4y)M1F=J-M2GBn{C4ApTcFbBd`# zgaTu`xI)zOHMyY#1)OZGts~y%5~p`I6E{wAwk1I`RFkVm&;0y6%)7qkltWBm=DkE| zESPz<v-5Jlst9LQ@S{jE566y>n`1*|FRth(aA`$Y2X9DR+VG#Ocv`<Z)XSv8N7sql z_fh`SRU#t$C@-$?MnO>FKIol2_ntG;yhoF;9`hYEIv<2(zQv5z5IC>dS!G$z&S7)O zLh)MQQ{(@r%$V-NGlJexP;ALcaEx#<Wesjt-RhJiBAv{LWIV44C1q5=G7`G~{={+H zdNXoF5zqo+yh=Du@*>Dj?o$%=8h)AiS_kd$%ocj*6-*XtQa<RKz9ah>vpqDw2$b&? zKw>0|`&L2Y9TS6@wXExC*oCZwf&GfmY!wKfnG-a)TOzxhG~zXdJ2)f*z2vQD)@P2{ z#RNU$sLb&zHFIOOWj<oI&bU@fo+J~TsOLsMF7_AboWc8zh*l)bo>F#Z-%bLgPCa;9 zDPRJ^^Qj5%6sHkh=+s;3wW(UrQAOTXnM;0j+7Q8IWyhK*tb1LRnijO#W&Z=DVFB_~ ztqu};OX0RtK=;W8dY_k}STz^q>k(VtMb(;q^bMs&hxv4b+Op;W!9d_H?&9I63Fc;Y z!4AIg3AA(95P3rGCJi9WMszii7(9q9O%`m)DpL*W*uOoIch=`jEY~aguCXtG(hBM= z)5O$pBv@K@13iHnvPPZSVgUt|6nIL?`(eGk!ZP`T^m}yKL#ohZUdhx@OV~l>61&?^ zZEWElJ!fV%=|ophS>i-tPp!oajZ^BDdmLFV)}8Zg#|g7xa;&7Z#Z>Kg_|HJ<2j|^4 zW<LC^rGUz3QH(iMCw^x*$?r^MnemOnzE13K?24i%qwfWLvwf88Gh0+zMmQho@>1;J z<Z21Z0%~1?|3RTMA}cvRSksy8p2+fi{B~RyWfCbxCekFNcVajrfuTQ_+r277Ix>C# zJFHw4Q2k-NGGztBWEN@l0_A29^xe)tHy>?Z2=-}diwuSE&k9?EvJ8)0Sf48UD=Tt0 zHiFD?LVb`&jn@nO22X=2>fS!ZcfEPo$d^1By9w1raO!wT>Q+m3J1cw<{AU`@`Q%XA z5e-~9HgQ}|H0CEowUCo(XVC_8bTc2An`O4HI`AHvY%2oE9kQUPU3*lwJx!L2C<~b1 zdF18s>skDdM8VSj)GzcNn+{`S?@o1sIMHu3Jn|c%TBGw21-E4E(tID#!lB=l8DB<6 z0F!M}*!%2-ZmBuqQLH2o8Lh3Ke-4aV?;VjUC<>Ct6?sgr$1M=|^3Av!s(w0sod!va z=A?_OTR*uAhMzMYb*@aiAC@FfuVo-R`79u4qiucmi=;w;$;U_>>#1|x31}<l08^QC ztvmCAY<y&h0RMC5|K`>_#9=gIR7E^yQ)kmOjA{qx%V;px-|G5gmly`Gm0{~@STAa* zhtkD9KZ;yP+7fi1B-E_O#6mn5NaOAO7dVAMoJS(aSS==wdY~YGDs19Q8@DhViAf_% zM;_Um+G&GSn4`2zp!l8GZtk`j|InSxjk%Z~JEJR;OQNM6B#%=mp{k<pGK-?S$Pm=K z%ok1I_41^oQruO9!ktIqp$>rTrjF4(Q=#M#<aqmHN#>ns9tXMM%&0W@v|m9?CbiXl zAi`xNV&V-pC7XRNn3LM(Cn*JO`C<UXO`KqpIi5bRva+Mwg`rT<!bT%Ce|_zbxGYNr z54jn?9eUMc6=U097uLt(qXDFotXhXQovujkQ86_ukYnQ4X#_Hy53}c|{WHRt6}+vT z?47p{*V&0#AruXSBncN`%j(qUu_(oSctG}qjYBmsKu#rqvPW-mNz-$fxmPa?lrJ!` z0aFGNvo$T;i4ifcn1VG!xMMK_w^{t3&p@+I-@j*#*x_06$m2c|v<5uS$Nge9|Hbok zxy4PnIBGW3ofhyg6Jr7Os@Rs#XMRGe7+LESRK7D~!Y9CUQgqWki|+U%ofgZ72*${E z;cfrqPLD*RX|h^mu5oW^Qay?ua^5lC^-Py;W@UX4)+;!o#dxH{sqalEx<qV6x`_)u zZt6B4LFvo-EH&vPaONL=n+lNnZQZ`@_Er@0+4#IZ|C0=aQZpL{Ieb|Q)Ld$Gs#ypr zC?}e4oX?eTzC8LV&|A1O+Qn^B6uQ1wDcw7uWi^Ri<f~g%*wmx#(g9VzmneSV@6aou zKa$`~SFs9r#jF4$;ChM!fY#BWOzAIu_cKZr`~r{d71##GVJ)J_^L(G<{K#OkDx0nJ zYGp9#u=LO_Rngm8qtWS|tE%m|<}fdb+YzEScOb&;!fq#Suk0alXC%-j%nDyhs>p6h zO+3rk?7}1dnZ`^EUhsUB*W5O7MHJjATI49wJr!X5dnb|;NY5N4K~_$A=R^!M6GeOm z8S6~)8QJwK9H;eSIoyVICwf=W6Gg{>A?7r~o&FF1?fTQ%`yEEVGWrc@uVuX_xs`EW z?nf@c4d2t<9hK>{67P+}JYfuK3S%a6GH6;=^52M$33O!a^?1sS$+*~{7F5m_;AC2k z@9X)bn>c9^;X7FG(!_dDk5}L)Pf8snBcRFjyZnNTrsu|Fhf|m^jU)8XsO;A1VMPPH z1YuMqX=V>-+jY($*kstj-Str(<I9Jt8UcmE7po8(jY;G)y5;up3k0bZ{@ZOD*1710 zbIhhK^MO&-QSbS$ULIC)x#GG-A~uKPh&m9cvD8kJ40hJN?$y6NtA3Gv5yGBW?(&?# z0NHe!zMl$xH?uOyIn#5iT0+c?acCjT;6D$mE%NDm`;PIOTcSr*5Fx^-gCzs#i%oJb ztkHw@nKxbyOnYcKs3*B4!joud?odL;X!|X0ppxwPl}!!o7QI|u;)6>jZ!D7)aoOg; zxE0)r5A3;!;z6>l@pCg=%I^-AcQl&^qk^JJL<j_&q^b;qZ*-+^#%C)~Gi7fLnaqqb zXM{xFiw9aR11NQ!hSj^#2f#fz=a?-toiqG2*ckVzz`;c4CK-aPht1GI+;OJ&Wop6M zYjN6W(rxza@>c=%k=)4PG`KPRwE>hRVd`u;*+wN)TI9N5dGPr0`QNm1|0S}{O7ddW z;dE<y+v~{K&8hp<C>!LCsCA?m$`)5391<&18T(e11NLC1eS4YKibo>8fhtd0?h%dB zyb@7B_pO@gok}`45KpBZB~YoZ)m+}hB@U2`)S;$i=iGc4hJ=GJcSCK+qsa7$;>WGx z`R@q~7Dg2mx(sF!`&}t?J<le-xz-Wb3y*h#IPW4N2JH7-Q0?Y}_MsoDJDMsKnt-9k zBKb@2jloqi57~DbQEXY@?LE<=vOocHY30J^Wiw`G;+i{BC;ufaQcluwtDjpODVWc! zzZW-JI;a<#_p|+Z^7=#Q<Q-!w%J&_uy|*S_(jGP+$bK7|XT-dn+<PcU2k7We$TWny z{W6R@7+@?V5>!}Pa&Y@x;SrShavU4-%S?MqfP3<6s2-8uH*<MdQ4vZ&rqfOsJY;fp z>7|B#xuOZrgmlzMS6}MUcqr;-*D>ka3T}NjO*i@qGg>0s>U)kWHqPQFxvC8iI-Kt! zc$(%byBd<uflg<yG$B*s|5Y>o*AAV1_K``h>*J_DURaHg<A~*GILB&efX!wqejdfx zy7m}RoXGDVReoovLQv{|l5u8hM1&^SEzp-fTU7kLs4hy8DdVb(?{v%N8Q;k1+1yM3 zjo6_}tBU?;I2ikm+q0r(+Um6Z>X@#gjxarDD(|qIwaq0=;GoJcUs|+Fhu4XpnEuV0 zwcfV0ULzr;{A6O+%J^kMsK?ae#Qe+hB-a*tS}qX`2x68!d^BdMH3W?XTJd_(=5*r! zc$N?_4w;%j)7gsm<w~~A@n;)T@q<X|?5KCnCZOYMMgG;=y&enMw71E4PS@hVkM3^J z;VAF8x`3K(D(62RDqcfPge9w9&2(Ml`H8u0lXQ58SlwegS?&>7NicpTFo9im1r~By z>l@;~oCp#zpM#LjIY6PerhH`-P*<mu2e3<*ps9<K<SREJ*ugbUVWNqX)2&nPojb0* zEn^5H(r|Se^y6E=$Hw}nbMW<9fuk7=8zAwi^m~Kq+;2yeK1F23JJV+6OlN~q!V7rt zm|SY#zlqoX&nEV8+`2pty{ZJ!ZUguOg(CQ-MfSD%viu|Fk=JoEUDEa7xU*{z!yF>) zu-0QJo%WT;QB`l^7U0-dlq!cL=ynjA0ScbMK1V$svRtc4dm*UYUn<+p7+Zws{W0o~ z%#4`6q`iLD`CYzjSLZBXa-^hWCSd3vi(nY~N9K|QaL88yMeUjEBs0fDDn`HSbk8^$ zqG3;{;U)ZX#oH_X#XF7DYt?S{YhHtHB$%|*khtys`zN;d?x)lS`Wty}vyQSlKXAGC z<}q6m=B{Z&9S%1+;=NrmFL+{ql?tt-lth~z{^39ED^R5qziT9Z3~07lT)TfFbwD?_ zRe+Td4)f(&UQtrQ#yOyvYg66IZr#rq_QrKLSYKEK&?qv`E<jZxoS8wPN*E%I9@krG zzg8bckO<nj(O$lu`%eGDro=78d*}o#dk)O8Dd&D`>iVa{Z%ca1T~aDvSri){Dj({( zM9)MXQ5ZkHVa%Q^lL|}g1?F=Z@qZC}?f9{Cpt}H$$%oUB?c<PDp!%;lSz<5$%m(M^ z?*HapKhnP-L*NpfFx&p~DaVL#5D|6H!cqM>Q!aqW7t@)X=!!ru^qp9cgKN*9GQOOi z^8`%UuHI|eUTfGn-{`sx*x+@~BGPRZ!{Gv5o+JX(Z~pBeJc0q)`YrY(zlpzn@vja3 z(S8@8=A3}D_0L=NE%7^RW)2F!ovLf<4kN<&rfi${1(Np!vYB6in7wy!y=_mgaVe{R z0#8V9GZ3Hw(#mYymgkC4a)eFjIPKEE1=U~NAG?1ot$qJ{xaB_|lArn(Gd&%knW_M& zQ{K!<KC4QO7d?ptyV=_xNzh`$R!@4pFR^`uQ^n<uk9y?vuo0_)fZx4;EpAzT(rq*I z$i)9d6_6BSKfk_yt`$BLBaUn{s4|KEW(CO*>4g7yq3+;FKfb|aKMVX=eA3A;6U9*X zq4YQa!*g{u7^SHvFukTxVO|S>SG+y<O32O+io7oz`z0w9fKl)SYmdoE4v1<QCk7L( zKlAfXnv0ea?P?s|uYcW-<G#RJC$Ya0S)%^WOais)Ev+|~Sk5bZp|Q`BOHA+qrdPpe z?b*{2g=c4qhq$XsDwo$n%#PR1xc1CF*WeEbSqy+(JDcpB0TxRnD_is+M?rwHb(zcG z_=m_}uoHlNg99wJFnzAwU9NwB?JsYQ-+?5>c4>qC#E$OBPGS75*$H0q4xR#+j2I{( z_%?$-26D9zfdK3$s_Ye!ZMQ*o8@H}MGi7=gYnl*%;9@ly&FzSxv;NyAHcPw*E>Ge! zW$b@BPd9Ls1!dPnDO%H5ck9xW9~~|8HMpT>pZhZ~V4}TNqdAC&NoH4eh5ufk#0>=& zjaGO$z2(37m{fP)jK{Dkvq&j-x<}w}&ks~V>Q6-0<=k4@vD~G9+WLQOa?_vhRp<$` z-QWJ&|MDw=?;bzG0R;Bqe*W_b{&ji&^@7-%UXuY*#lZNq|GA<6`fvaJJ3jl`m;Q^C z^}lcXzrX$0%Q4q?A7E%n_<4~D|L1P~^M`I@OmF_f7XS4~WAwL{v)hldyS9}{+I{a) zcU)dw&R$uFW{D6`9A59YoWLiHz%j#x@Fw>l)Si?&aB_Cr|M&-Hs7qs0ttyA&U}&#@ zcKbHOuWkI=L?qQYfuGa;_ooz*dV*heb>@9#qgrj1c|5+D7D`>kT>c&l&}u3{jOl&8 z1hDAJ>qhkC%WHcw$mIExN#6Dh0XadeMuGvHpYkUffq5dIr&_H|tYZw8oacRCQQScb z>ZO?qaE4^Zi;G-OKx6I)9<VP}c(U}}|G8|}__6Et;eG9cV%)OSP?QoQ2nHxi4RQ4V z3&*t@sB81X0V(`V$7`I<X(O)ai$7&SfqqpXc?f(>HGW|oXrAuP>f&thbpI_uCwS2j zdj9tP)IhaO?C*Q^sbuonK@AiO=6Md71(s8p=u+hm%Wj;mlstE?kIKaV0MP!qL$?m^ z-auzu^LS!rfXX8T@QOCGAm=TRDSC8!sC+*5^4dijY^Bf_zUG<?n!ra)Ucn{-)=RSD zQT1qD))`Q+9Awo$L6b9HT+<p9Y+ReEvM6fjZWGq1<CiQ3wDbsk#`AyTzb!Pg8?xGP zQE^pHQmkN`{(h+k3;@rrfjsuH7r8h)yV2e!(Sv_l=jvYg)?mJF6v^XwL`BfnU8=jc z02^`dLG%A-e?K;IkfgkIzjn!hsMW?CKXb1~$R?UB)WsQ}4c!4`LcHAf)9I#>4yu)P zfTb|gh$2I9dY^Q~r^y|6Mlxjsd=UMZ`t_RnJobYS-!0elA1}8$X<O;20sB^AoslA+ zG#C|>#SI|YgcPp-Z6&W8BJBD=ZLeNSDa89?*Xy^|d(1Is?|w+Ngj~bYXe9W!|8CF! z_O`_Oye4~5$A%Y-3ZU~3_t*_2?QtuYKLJ9+3&*|qS<mYE&s1@(?;$Ql+s)Fh9oWe_ zjupp!L^7&b^@Y(v`{~woZw)u$^%aIIJa<DuEKu}Z^tg#wvEk67ffs%PEabjS^1ck9 z0DIimUB|tt531$V_uP(9jH%<mC?jp%MCd5^+I^^hp4uAJb=iBE4Utp<(~gl$PGc)B zoS||eqVsr=7>=r?2;+-5)F>u?5PI+x?BsK~`a46|@fm^sF$+c9LML^VX6E$vkDY;N zQa5+Xofr}5S*gh>APtqY`bv1|zt-(<eq<;49YwWuwY7a|4a6LxL&#wjvNvw`F`s$r z>_0u*d?~v4GA;s>n^zb|3pB?o{@Ig+TK3agpt)?GMgH89$iPNff%rDGCIo&j(_N%{ z56Kef(f(WnW@dO&qtEo}nM)$1pd1*LKNv#obwEPsr$Ilofq5aTKzm39O!y8sTnHuA z*0KKLnd|w*>=oRi;b++}Gl>4f?|m!H33bJHnlpZ*4VMRlk;&&vt1W?~gmUvjPBWa^ z&vvd3ZLXZFyREEW!cPIp8Y=NqA+~b|aNLUOOx&(og7?IH*nWpy0F|;LD#GnqX~5w^ z9$ho_A`SS?KPPXVy2|TfM0tc4h44>Ay>t_wZ^teHZhNd+yae*U8~QO`9E1qj4aDPZ zz)Q*2Y&abrq?$c$TZLRMLE^CV=mKV<j7+w9p&blRY&d(vby5X*BZKL*2j7ivm^Qq| z55I7BwU;#TV;U6`l1&Zfs5U*l#;IjZT_9~vkgA8_8^z6&o`DrFJmn}X)89Uz^-p-Q zi$3!MAN&1zk6z~`%lXoFhSb-1+)n<~J$4`O(&N>2o%atCb|w<7lbcqRuLpFN<E|%7 z6#j&!1$Z9^$gxG}y`!M!*Fqiow?}(+MkhRo7CvA4$a#Bv_Pl#me)iC6mKWYn0q?(d z#><Zr-=(^@(*iW43YTxb12soK0z@o34Ud(Q$>z%Oel)PU2?Uu1?OZeVI-kjV9QOdE z%9l4P@|m|>nYio%<%~#gex@YB@%`eH@||trP7qrV+XJX1-ZLQ_oSVLuzWFHT7d}3p zbnoKegxn4CwS0D8dBu!u=n?6wwhe(Cec0tnp3CyoQBU1=eeBVUn)hrST+zkJ>7e0^ zO*gyRz2QP<H6V=|!+>p~y8XTFVQH|Ssi%4V0EF38nWbSrlaoEKp!{8(pGc|SLiP8_ zS6@$6#02h<MM^&lyZam`@b&-s&{!(@$L)LQ;KdN3Lg9lU)k12qkByux4oc)HJWrH9 z8-76OGJjU`{J|5Om{U}XmE{By-*_PiT9xMt#=2IuIni|ZGr-AY!T?kck8$(70v)jv zAgt)J3q;x7qY?7x!e#JmlC`?w0gCtlHKlc(`)J=MhU@kf6N?qlpfeE221M4~5W4QG znO!t4Q}bQj>YCc|S>|yQL7voupMh?(Y-;<Cr&}sMjs`!utg<dz(pF;Z-}|dvAhoUS zTD6uGptsrXH${5hM$Rt=Jn-LVQ$79Z5avV8whlmMCv~f?01!v9WpOKc!TBT7jmyiD z<cnV}?k4v(tJe!*JqZFZfXY|YP9WPA%vnEHARNlSaCcU~D<>1la(*YuA*}pWS0ASi z@!Xe)Xs)ki%(9yKOh62L=SVvk^^jHn+ZAJSta}nZI(DLDyztEvlDD@WeEh#3>_}dp z*aLvqXy6LyjWP#lvGHf$j24lRih`X{c+6CMWAFXm83d-?u;4(%u@;o7C{yM$?&fq1 zXy&s}NWLC#+8WcgsVid@`d*UvAS+s2)?V)E!;@BSLGr{kW6j^)e6zI)&J$+!L)wnv zMP!J%1Hjv_SEn3g3mB%3N&l)1+>!+7?CY=wvsJUrakfzsy4PqQ`AtU+83Svw9N5d# zzd-ZNih;792qr=f9=T;|wJzM3oZ@PyUR)&90SLplH5;$DO_Zn+$3hz6ajT7k{0rOQ z=g}FD?M+z5{SY`!@fUu(ufwzM>jj!bBKv(nT<2-@(=f!sq?wS9ZB*YIp69D_KsxAE zI8F)??teI?^;LA+tvB!NJk}%$Bu(pPG!BFuU0Lzgg0j2@6qDuOLl}e}c>^Rt7t9ub znq4GM%Gh1h^L2W`@oWNF&B+3#kQ2G1^!fiT^uIoPANabFjB7?wRZT4`KSv%98mq2) z@R_eRm0PY5O@@qu@~Iose6G?uh={Juhy#0j-4;n@|D4U<pZ_Z&4~5C?;Tv#ok~vM+ z(_VNtZf_F(jn@h9r&wvJoY{^kHt^)<>-_{)La!3z?p#aKC^Xx6%gi4Ax6KXR@rV)g z>_q3slB&r(M9dZ=PEpV}_2umn_l@HA1YbwhLs$LlWI_Q4Ab4MIYpV7V12N+S|KMva zT{OU-H#aiMXuG+gFs>f!n}=f9QS7bE(z&;0IN(IR=Rp(f)lTD*Up{V3MR!(b8owHG z<K$%Z93b)L{z@yUK3R@mFD*vLJ+yk|ak#N|jR84mA%zSXj(WChcx;ww!n$fbux8kA zD;>=cL!o86{Bz@}461eN@$Q8Z!IPy(3(9%v%I*3ymJ*GEdcb~sYyBX#oNCbXU(Cg| z@n9pl`=<5hVklTIHniFtsHYWL##&B$l@K{#i11}gcJhGy^(<S)TOWQFF3VN3GBit` z+I8^5YSr!8fy;cOJLpFmyNdn3s-)%3cIMnK^hIye9Y6Gg^jDaFwW%nn1VEKEu5pzI zmq!h=>%OyEvZ&;%^OdL*nfzbkeNkb#k>wMpQvkoNVN40VuDR|lH$zYn_d^rk$6fXl zO<32odU)vX25An-zAf8RFLIA!wX_=DM|;9U9%q|7lhS3nd|PED%U}-n-T@}B*_R!Q zIeCnK9p$kuE3viJZ??vqc8d>0#ThrPURZG4VJS&Dun6-s7!H<}r=V3Xk11Mw%ST&) zW+uPL$xeC~tN&{aa5#fZa_U;X&ccw;tO;1OuJNxJ^|SV1hrpu`#oFDnr2k<R{yePY zxHwtQcQO&YP#~9x;q0maX6jKR?<}e~MNd3yt}f5uGJIJ0h9O;Ew0p@d)sI-gl^9Gj zTk)&B?;r5*=v%YQdb7Nw<hne(MtST1{JP!6tQmcp!gRmHj!^VcOYqk+n9bkVj|6KP zZ0i4XcMt;BmH)V|bxnBOCzK1j2}S^%?&`A<QtuBh0E`_aB_${;fz2YnSW4jPd=C!d zrz#gd8}I#Wsg^=}u05b>Y5x;zeG+F>g_WYRQj;%U>{{Q2eaVj?kt$Ah6wdWEa}=lR zyE8#ZYh17<3K=#&Z6@2=8trGJ4u&E|;L-x<JaByXotMXscsnV?s}`P2sD1?sO9i}@ z8uP220PsF+WuHD?=IN1z{@FYIg*psUo8vjo!Be_@YSOU|d`+BVi}Q)m`eiTuaU)~E zj^?%Nf;UM-b8F>1!Waf#^|l6U*_VWqFOpT<oboWGxFK38I@aPjfiegIz0fYgWlH+! zos*LAF)>a-_8(Rn*bh_bCoK1skZ*2(CcDc#vNPTOncVXGhpq-`u9xd<y@reT#g{s( z5QfTjVy8y8oUbH{T_&w6s!(@tD}u#PY4>7H>R;}91pMqk##BFB1)Q}ER+4$jNk5eb zv*E|yMij7;3<r5$pb9&?am!yl-Z#SClCo&K-m=SKdY0De{mn@D(e&uUmvu|hBV+n~ z#RB~Rs`lxu;}W2%3-Z_~4(Q6MC*!nDwY2oZW~t^o=g<g_O7R}cO#|$Qy6xqjMD6lf zFAp2q{XXBPS})2C?>EHo&Tu)Q1irE791>>52~VQaZ?!i(t8q#HW96}U@we??x>n6p zp4=!Z&v@Yuh~Ox@)$8%P&GN}=PH99uGvlsg5cOjwmO(~2c~Tm#b36sgxD_jmy3Mb_ z;w584W^JUNrGQJUh)21Jh2<i64@h+cS8N0AQEbZ}#9K`~6Y$ZLv#sNelKy}2QCVy4 zW<3mLkgnZ*wdbVj`}uYKZ*|c{Nk1Q3O==7Es}>%bJjiggtW6RtJWQ*WOirqEn3|6( z@swYavWLEI;9;=nKo~ELL<_;mux4o)dy6McML%KOXW<<T6Q$!X0Zu;mz|;^%LbJYL zsgsPnf+bQ!wgV)=*t=8=n<rvUrPX>qR%$Hhy4p(O)qSqT8~WGVm_?3b)!W0InncQ_ z&|W>us^R{19wIv8C$#aykM%cyyEp*@e((KOL^HP2Q?Z&m<3wIr#9gu7y_&Y!@5zkd zVarayZ3cW<Hq;Mei-jjp=Cs8}ks$+j^ImBqH_@U4jW;AosGL*wKfHX5-ldl0@?Qu} z{GzOq_9j(t?@CjVfBx1iHLj$As#uPD)4L$GfxG4=s$N(%4%$3wbSK~&cbF-Kq%jZI zgsnBDMJdP_$CepH2COmE6<Bljt<W7j*zb7?rH?PKo|vHQ+85LiSZfvB2I3U^dt*=T zFxciN8}f4f<bGr^Bqp98+MUu!;qM%Okaz6B{$8M~XV%7jFkUCMvyFGIv2cnxd%Wqa zjmn1FC6d}zCFC$p&fhnad6XV)KQVdFN{i3TvBy|snRt*ZxDwRRDQEaKl$`mUa!eej zTKH(Ot8&uxdN*#~ws^0TWE^(flVIHtaX9x;@^{1o6|t&}eaCW#0g}14jQEFK#QWt` zq`tqGCGxqs5_zoWc6gZj6zNtO>$v1xZ@=&Dx)qbBPk-6%6>J+=AKOOo$jx0Q@I*KC zmG$#zG%!Eqn(=C#M8qi=*O6K-$yo5D_C2aJ0Gnoo{cN3kr%VPb*W=n_SM*xj&`Wqr zJ<Fonl|KF0{=8=PqNjj-NYmV}hrVF#0jKE@xaHRG`P6+aJvgVRs(=QSfAmDEV<O+= zlk-nEPpAoq3!TJky@a1${pHJLQR7r+uhY(~&&-k~*t>f%TeGqP1K7YN=Ln+_0`GlQ z5^&wy@VO(2DQ>4-m#aRYCeig21r>laM;$sDPI<>+Vx9J*l`Y!9Uk*EIbueN`858T2 zaLX?@rE}Ao+pL)Ns=pOa6RwV=LG+5ASyp`FX$ULK@K5q|c4>>Vx_0K@icw+$%0Zz6 zLo>S{5aMhkKysvEyLOK0Tpf8SW_Gj+@t&A1;nxI<_i|y1aa!FG_c3J2ULVRNj-BD# zDgqzGH3i=EYP~-Z>iTqGeV1-2WjbO7fE$}OaU)$W#QfG;svlMSu`DqVy;`yBhh#YY zTAZEaj(+I#o}Dt#rV4}nK($r*lLY2gvYE??&Aw6&D+%Tga?E!KXTn-x12KzSV@gD~ zLC6;BiYP1ejl?!m*AGpd*o|TwL-OeR0E?yqJ{3qlqXV`9vc5Vep;)IxrxE4Duc4}9 z0*f{LRF%vmb6IT)UyEpC3ijr#@ASWJC;Spa#Y%iHq^ip9m*#WYG|$yV)+cV1<m@>6 zw~47w17lJ|Rl!n$Z?Z8D6G(?ff!FcI<%j9qt_1&R0*=ZQYOmw@%V#pW=lecU_tLT_ zV%m%KG}J<P^kj*JHeOu$_6!h|C1d*(0-n@<pvExix>;>L4Rv;aJ3|Wx+6-%XelRM9 zZq}|IeH&C1>K+`TYl-mJg5L>m`yR3?=li?!>SEh_+pFYo*8A#1$Zrw-BT8`W9q-bB z*S|uYA6T%pEgCzRvO1<Q+-Y{5VT)Y(E9g=sy)nJ*1{t}43(Hi^s)o>McnJ?4+%rXD zPX3??qGF?u)^j)WZvV*=<d`(d25ME==%5c}E9a8C`1&;Y4;vAaKs<NRGnr)X1^=k$ zLBYq0j2g8bX^5)RwY+JxvQ<{WPdqxfR$lAT-H=w|6PvmNjfzh|^l(s1z5V)V#-m6( z^25VUZao}1rPShXD4L>v=eB+vtNeW62Nyp=UR&16tlO}R!Qv0Ds!4k>QtsNXjn9cb zSba9=0DOI2<4Jqyj+8UD=@vNpymTYlaY8{}gsn`n)4h`+8c|R&Gm(c=AvSw8*TpYp zkX1dgWFwazsx-CBp$HY%WNX|4{Cj%>(eux=wv9KepUMcv>?nTuNgyXl=JV*M<NP!u zlUWC@4HCNu!3xcu^oZXP?E6mhm7$Pw^1OA0b0@_M8>oz*7So)}fUN0GDVCo#yYvJG z$IdD-)RGM3>E)dv+V(&B4jm%(C##m!t9av#<J#C@cN5ktWmwrpbX|0hssf4oqcq-` zsexZK++;#@m-g}so1<cjR{*!5ST~+fd+6?OV?Rzp+6cDdxf|p6rhbsMc|5UgUV!-& z@z+_~FGTI`keG_<9Iv$#aKQ_3mGjk!wNCNrSWa<RAEUpGuB2H7gNl;Lc=&HM08Kn_ zXefFoLbl#?-?uGTF+Vv#*p02#hf~aIE+$~{3;;OU@3vCZEIOIa2_ym%eHX3mH}lEd zIw{D53~Syl!ahdpq91&ABlN91{>Z8y;kMcUsA+nBxDQiFj%*9IE}@HpBrW+@=uL&u zTzW#=0?3^p6<!&HrK)x<0nUR(TIaksVU50`OOI}|gV7F!yCf&C+?L$_C-!d~di}ch zMv_fUT(Tg-Nq1|umLm1byqhgh`l-Sx+7w{E)bcgBXkVtg4p+T}Z`~Nao#>@Jo`c<` zq+e&AA;2Y6LGQ4c$Z+J9#@&bmsygc&eA_r3uOD;wYfOZI70zc!_AQ??zI9Ft7FO*Q zTxZiv`r$~y%Gm=Ez>r<pD#TvbNP2+lRrcwOn?K0OFLjf4Q}#!e?*MBl__rzPwvkHX z6WmqZoA}g5Mh?`=`phe8v~G`B6CCc@c$t^X-1riHV;zhr{Q6KlW0M7vA++#?-t#8a z@!r-5gAx<@=dVI#>2d<5-*In0*Frfyl6!;1<Xsth$SfwfrhPnmu}o0z=jpZ-E=`W= z_`02_HFX`|TKhEP{xKmZbn=uKZQMrI6=#>%_xU6G312<S_^&n6<l|4FniD<8(j;h< z>FHy4aVpMU)APXkaN)JmPPs90G7Oda_wb`OzWU;^o)s_l;wf6%1=iaPW2u&~oB0fk zk9;VB>*W30yJOKPv~^Y#TqJkn^8oq)$n7~fwLa8TlcsS}gOQs@vB!Vkc)GREV#xPB zh;F6aF@w8-rJ$DE&i?-W!^5zmU#reAPW-6YRn5b&ybZ}A!;sCV+-vO)0gjk)zhV@{ zr+05pNoV}-MEQpbFck3uRYx@0yPn9}Wnw`OyF5z)MVObK4u=Ox&IUscDw8e>Zjk@W zMF~bMO=rOp>M2+bdk}RJn6uH^-O32BzGYMvy@q!7&);CRgy~1HP85j_*p<);XoBOt zW6;iT6A+9R!akeVsdTjSZr=9IC6GRRcPSF00aOHQSUpm6HrA`V-s%@tEyqPE@Yg2G zf7Cmo!OW$;um8g0P^laHtk(=7O7mgjL*%{aNxe_39v=%V%_2e#Pb2Fs*QIrX*BlmB zgjWPYoJf;beI(E^*ZHf)h!CG7i>!ov%LlWgy<|2~AXaG+D*7b%nF-m?XoOl6=ppM~ z*Y93hk;v4QN21*;cUNxhib*B)A3hx)#62N}pt0xagjSp7)1eo-!^kWl!tI;qVIO1c zv&Qma!JYzH3bk|zt_y)tC%bu;4>e(ONvzAf<x@4>>s@OvlTW_#-Ef~FcB9~GRfEy( ztUK<0ur_41W!W=<Hb{sM<sbD)5FZGpX2TU8Lmn*>kGtZgG|1;*HpA|<bSJlk4h$Eu zq&u`4s)-nrpSyZz6g4J^nyyzEKfbt~l$%_c{2mz);tyKQ1rlHF!MO!Nt*TaA0p5}1 zdgrd8y09p9&wFM4VN!6WM8}ARfOzr#UJ$FmmzD1LmF<f1j}h4wyS^dGRWHB)I(XeW z#$>Ayw=L~W$3tLB2U(b2dO0Ehn`@29Ag;MgF_{s&YBH>SzeUWlHwlgXFtrLwr`v0X zmKdv-mrkyDF7C$3oS3@4lvlmQvs2|$Y3u3}BT&~qHN`I#NJ5vwGH8h!F#MG<4n)o2 z;o<0d>#8(=!MSWI?MMiCW#Q=wGu65Yx1hS;(vU)wgI76q4fhqJXt>7NGeWJnhQPHj z38LMs{x%?oP>(7KiGm;G+gV{}jUp9TN;>vEcN25RzA{AHJ`OfkUcs|ii}I{}vfEcu zq#gyO&{&qsK*0{n9^8_A&Iw!g8Ta0&1OHaCOl6*z>`cfTB{m;UckOdta~IhA^^#TF zcOaI~kdT2DmHK0YX^g{X_&TpO3iKfg+?jt^6z;WTJ|HDp`)M*F9qs&Zzdp_TH|GQ= zEb25g##6f<180U&T$pvGty3fz!%0P?^-f#Qht!Oxf4A?b2~8Zo^y-kdlhr;waTOCF zOSrzfb)~68RacX!U}91iN&{P^gNj~>c7y{a%w|o#>k)>9>Zb_d19r}}K3jMkEFV1h z3D%NAxF;|7KLKe>)!pBejV~kKdjYAKpIDdM_we4X#6GX)ecqv3{{g)#Y9@N1)1T_t znj0F!lUT949nn_Xea@s&u2x0hrjYI)2tLSxoSfa4l{FgJ2J(95Fu7@q+YGX0?X(`h zqLAg(qfsd@)F!_u52d^>&TP3X);ak8LAzTewzum#jdMu1oy8oVhEjz+5BP9^OE+&d zUVij2NM*TB*Uu<3RH<Cg>jWd3%&2=l-+Gn-T|8;GCX?ythM->4>rq3blyv7(7a!4c zf+s?KLyl5)U8aZawxwyy{9<?q^lXb6=6h;1y_In3dSe%THH%)mi6ZwnoPk{Mx1S15 zgA_~YmKyI$rhobWCT+V{jo+_a1pRti^Tg2R^8ADYf6S3^!QZagINnNwtG+wUA(d{m zJNdUI#V%Syty}{HHI0Ohoz~>uBm1tsCtPy(aGl^L!Tb!`_6}o~ul*gz+}J72@-vOH zDf=$<WzANmCFW-_F?%Ts#vi%;2z);l5peSAuIl_T_5DO#N}%*qen5HPMZX^tsUd<7 z^*zY*j(`-$8is=NSE~~je(<A;vS3f&rRBUpfvCfxZ?dF>j#IB!>ET=hn)0T~8GSCm z?6u2N8Yg;RTu#0cliovIlb5pu^34rjx);dw7v+g>EiI%5iu+Nh?P;ruoc>O?hIK^0 zM^H2Wu*8#TZKl7pgi1JVRjp{0XZ$QMDsEJJq~Q_n&_Xu-6<5Sny<Lk-pF%kfJK*b^ zoBUpm_xuK0&chOS46niKI1m}FsZG8lJf9v=j>Qd}Z|Y(vcAV(yx;;t^@6dD}_$_f7 z5p5w_-xm;M1wwlBi~)%%mOW1OF0x6HFFIDRu!ok#za{RRB46to4&z#vPbN3`7;N@2 zd|^5m<9<+aS6TNxSOczmOdOd73huF@44q|)erFEymfBTrKX<NX;97j#`ZCCoP4w-G zbc4NqYtS6f1rd70evC()<Z^xeT_?zq^0!<mR;It1G$i@2BsheCA(n2a1{;uWZyIj~ zV)QGhtB4Z8=-zWc)R(d8F8bZ~!DUC2Fea+VGxO@lVWj-hZeg2nAF{n>fFMsA;a5&Q z0X|J7^Vi$9TL_5g@Dvv;n2?1(>K}Vx>|Id`8?R3bFyTSBnTmYpZYd27MU<D;qI8>e zjgvNiDZ5>QcN%XxT?}#Qz1A?2GWa~4dSbr+P<8+2>bcf|aaTC&-rg2I(^uIa?#(~R z-NNLoXp8Ctmk9`V#YAUp8YQ?5oxa$IhHlj^iVwbODc>pV@OZJU_Un~vD6e;vQ#`$X zNK@lENaNAa3ywH36lr?p;!SR}umQ!1L0EIU@iLSv5w+0F|N2JP)SbrzP8WS9TB3f< zQ&kQkoLDpTh%*uRYu%&Kb63q!aAtdqi{k0cao3}b11}Kt3#E&WX7bt8iq5@>6lZQ5 z11}#U6Bz=)k6jk&c_KymESRoUekA5od-BQ3@0@PjI~-&jh1d8Ln|%c4a}hswsjcZ7 zE6e*+e-(-+Tzt$6uKkByHp+wac@vFXNEy20MqG0)g!JU`?$4V@wkyWa6kZ2X2{WI} zcccWrmAne8*K!HiR~R^(Tkb1?oBVNa%B@k(E@u~>0&(ctuT}lixA>yi$@+m@up9qi z=%<cZQpO!zP8?2I&$9J{9g95QA_tvjHV5N-|Bt=5e2e;h*MFrYBm|@x5P?B*071ID zK}vdP3F&4~kS^&CDJ7&uLAnNp?(PObnxXfbwZEU=T6@J_f56_4I5_6Peat;~UDtJ< zugl{}Z5D{rqVct2Ncjdlj|Ws5Q*3<Powpw!nt3>D9xHOQ*cIt<gAf@?j&_P&Z|+Vp zZW=CL0uMoiw>zwS$S4{{TQfi=`c(~+^{d8yJzIsrkRB|e!Qbd35Q_Z$&AB>`QsFKm zBs)$zm>_|WBw=1kP2}tiDB+ZBh)(oi_-kX-J53q=BwgyH`hp$GV6}gW3XHfYI>BZO z@KH-VZgoMRs3Fy?Oo~CEW9|dn7WncjoCJvNVlQw-^S*d3uW@W3C8VMPV+fWv*M3(= z%NSDRUBoc`E#GSVjR%#$4zQ4v2!F+J@`MG}vo;f6NQQXI#-{P8cN(>juA5aj1^bZx z5a!cOVeLgh5+_``c7rMPD0>dfyn`i5o%c9MRXB4bPz<So6~U~dR@o5jNxvBE%`caY zR3+<+agVC*=My~kN$W84mpAJ90Pr#QpKktM4xInF;9;<kav19mY}ueqTR#?AzD-us zp%S7^3_YRML2SSNEo&2QY*%Cr^#Y&h@g9nIuX#NLVM8$m&PwHuYD%(qM*tP0MOVi> z!PbksNRDGWeB8H)1iAiKhiwF~;iZYH`8R@RTrl#;lRrk;h3kHA=)ywCDWO-17Z&rB zT~%8c-Ir4M7%^-0qrP3kiXl}tFL)4M-CUC`;05fG1ko;S@~N))XFzQ-+SiZ_<!&Xl z_Q<?C(u9NdS6xPO0LEJ1(+F&s-X~{QTTCwnY)p_%+MkuL_)GL`3f<4csZej;fN%!F z(K*y<-Pkmyf++MK8!nI04`UjOdbPE+Gb6rd;1Q@eaw`|;Ka-#cgdQJZg|$oYf9t_& zNKg}<c@G_K*R}kLCOak}%VjBi!ic-4&|ENzwJX)UtxzAFLrPnTh}_Q)c$_dIx7w@g zKUeQNt{2J88*7WjxoG&)aO^gUX5w-=h~SDGZo&xkRT%Jr3$*}6lp9!{U4Zaa)iEOh zG0uTWW95u$l)Kmmlqo`gc~Jt`6%HF%DGUN%9~puSsf8Sd3j29?l~Bt3>ZUBqR~{(& z><ttp7x9e?eq*jkiRfLXp9EBdy0+`Ndwe%fb&Ds<7G^kX>p=dX;gi!2de3Ft-P@rV zlwvX49!uz~EwRC(<J0}GWP=huYFYen3C@6>m)J7e8F1Eb{(USQd1}m0%PsugtDJC+ znZiyASPe-K_^2<&GabGBnZd?#zvcXwtSfr6f^l5m0yT#Wplpo#!EnR)Emj=i%1Raa zdAbmS%sOXlhXq*!TdYY}<cx*rCrJ#-#E{0dTxlt@ZlSvD-to5Ib%ui<3=*aO8Y{|4 zgiO%f5?@E~vXd4GOE{CURk=y+$QyY7w9>Cw7jNrFntJ~pt<<q-#uE8>&Q?OWCmA=0 zBX_tQI+{o>93y&VlfpXc8K<F_pI8`hz}<nF_yJ7hEcNOA82Kk`+o<=IngOzcF+gsw zP430tJX3@(SE-4-`JWM5l8v0(Kh{PcqmQWznf^9`X}wd#4t}k@vorXSWS10+3fB8# zt{S?U28nv!s3bngA>p7Ig;!-S9CITN7|L7E0$~{S8m%rgb0Nv1Cgxow+s|XuU_fTu zcD|#5E-x@XlnO0PTofUnrsyhV{hS#?%3hERjaY2qv>tM}Avr0xiY?~&f{k;1lZyz0 z@%ZR)(~g{gGf}j`CQij&R)DOl$|>5}plN;2>XRnAu&k`?vjzc)pfr(b=m@Ea=CVZY z_gWCGpMpajji8g<PN1gLSzYg|q%j-08iz;&<1-XU(YYUe<JqJEjd>GY99$E<iTsFL zHXXq?m+LlLa{e?{yQnvRKl8Ye%~YZL^$z7XDqQ*Xtu+}j374926bvDgYl?u5$Blmu zWoR)NCG?&kfR-X08+{EHWbfI~++xj-#UG97Rm7N^ungeh?GW76C432R-V{}$Q&Ai< zb`KOuV4nRL`>h-WcF1fh5&1*Dc9W?^H_K>`{8`reoBnD_<3;-m^#Je43o#~qAIKJi zntkXjTGMD!NSUCHNJqTb<-f!T%Kqr7*OiTADV)M`mFcxc<+rzrLr;DLZhe9&Mmqb& z<UVdQ{Uks<#LmZSG4W)Gda)3>%;$M9f0Y)+$ar?L`1Dfx&M3xqi0)Zpk4)1$9>nv+ zpFK9ev2+=5H~GjD<}DRj0Ww>h@sN2GXKK)~8Tr!3#(XGEH<m`CPNQzVg{C+??qZ{7 zpU+c)RaXJ1gdi)+DJ}dr!-+}qmeNPOCPZoW5p<gc{*s@MCvRw+sce>uL*gULqWxhY zF7M)8uE84#J;IZG$E!eZMpwB*(_WqvmENTazr(Is!otN+u^Y1~vRqzi1$O^OyzR;k zTba&*D8#2tsJGJIfymr#nY3tBB9c#qzW=ZQEUBm9ep=IJ#eGbLQ7pTg>8n?!*gulr zp5U{hVI36?6a=AxP;<9ZQ;((@!&27YC^x{Gke$`$BVqX7ZLuEt#BFfFjFe*-0se5@ z(0c_O;8}pu6g`B`R0;-d4rJ*5l;>ySFm|lWTY*jmOY{@Sd}L#<%3PNnc_tkj|D=$b z0L(#I$U5n0sd?C{bS$3VI#|<Fh|R=LcogQAmlKuh<F-P4Qn_x&RDCp&U{rq@*nvi| zlqrliVYU86__uJrjYCm_8l@u5Z2gEV)g`*Y2GrmZih<vBgH}zAjzN^{`tmQ<+D$Qj z(n@2_hntskKMc!=#hCQU%|7;xqBS=k{FpK(opfy^AN)Z^w~(u?>RjVEm^7)KT<$jB z+o83V=<@<=ji!+9RtmIjDRT+Y5kP{CTwGNNpTHH@yc!>|n@6WG9MP6WdGUB4pN8Kc z-88QBER&dLypOutQ<}B5Lt_!0sgTxN%thi2#^y#tKJO9C=H?Srxc^fnmn+_LBFj_a z3i3$nKfhDOdLW$7A0&j0x8_N@3!MxM3}+%Wm#=);Xc1DdZUO(^P2s~A(YZd-ROTBy zS7F|_w56&OLdM?P-nLBg_=w{U$)FV1g9@PZe3{1_4LU`5TKV4<mmy{D2G&INng7Yh zLB&5<Q{oVkpo59d+DJ6qhW<WJ&c+qCUJk{jf-W|x*B;Jq+<uDv=I1o#OR%9Q8qG+d z*bLjXN665Sf6jeD*?odfv7)g3oXnm3@0c&D<!dG*i7nyZ-ppNxs8L>=YfaK8iX-sU zYQ5Ai!_xXM@fcKE;5}ih5%t)hLtD<fX9`QEK~LtdV*Ca#zj$?Dk?QMds?hm6qwgji z;|r6U5I;FwGor9e>;8PDMoySe<ObDw3zg~f%U^o5={(;W%X{=UWy!7Z>p)rFIu>oD zouLZG4REiM`j`cB^O7bS4m+#6meH7`b$%hyY_@@<$!fH&XEElc<MGMlXTsKth2g@4 z8h@(#sLr@-JN<GhxET0~nVgQgj_3Qm#BBq62Shi0zbM>k`8Sg1Mvaep06w$o4zicc z@=!ibMh1STq_vNg@s|tYZRA16;m##^b%1{`_Lv1N=1({7v$rLL-p<NdehVG^a5{-; zE#0XPQJ<!Vj1VOb;06i;Q$z<Y<A~q&b7?BCN2A6tQ)QZX6@IHDdYx>G-RE+;=}c-_ zK@=!5luBfuNpY3BaX4!Rfao)Y)eGpG8)lxqyZfBg{E3};`Q;Jf=vewg%m#&FB%5a| zs;-_#F)?LtzkguLYbT=EqjmC9d=h(2^%$9{R~0O{TQ{GRD%Ki?oWAp2$5hl59J$DV z>M)RxaaZPKrx>Hj><;=2FWRg1Rjc7{&6=(tXu=CoboVFivZ>1#3JEA);HF-+4f(0F z;ewql!?UpW26IVM>!sBNuKi7k8|L!{`ZTS&XI3q{Z#UAO_3?XqicFDz$cD74`GxcR zbM6wL|FYhrAo;sg&~?J`J=_x97yCrX%ev!voFCicBeX%d#NZiT8(kn{ZGp-Q_3XkH zVJd-xpHHd|$}N3Iy4+$W_!cWF%R5b1#&YgzD_)rCb0&wg*#)asv&OiD6C6n|bu8n8 zt}tX+s92zH+D6S#??{f^!!;8xKv6bMj6vFLib{N(UmUKyzsMk&{X#Taya;({A#CBu zJd&a&wiR8$TJ*(=VVX+k_|b;eVFCv-7*Cp&LdPz_wz6;i5LYx27x4vDNmYX{#rtG4 z35aigO`}g5SnyXs`6r-EM_o7eUJW9Rh_`m%H!g?Mikef!o(u(r3cTVtKP>Z>wpq4T zq#UY=?26r&)dp_g2>)Bw^Ruedr@3LO9d?oIbzrM{?UMpy8~dOfD8V5#f>?~7(Yk5? z+Ng*qq0tC2qh&xlp6!#W3bm}FdS4YDfWpAz?5P~rkqjm|QP}2AkFT0O4u(dMl3}C` z;FL`3jz9^x)e`341ufJ@UOr;0Q=WFtZGwmsY>t~hbJ+kGvU=b4&(%5W@ETJK?Wzi& zRv}a2r@fN~?~VSTtnSCzn?HN|Spg&!+gL~aW4bz#ql=okhL1gz#zPNM__oRjfxAXh zwqlK-*s?@$i}CZ^KoL(<VntC5D#v0W@TyhVELV1G75=OeVF2`a$KWcq3jeOC%tP=v zS3}_GK>LqW)DZ}s+GP(u4S8#*-iDisz!>CC`EvF3gH*07Gg#<7f-h+OIi}iGV3qCN zyND(WFRFA)pRA4`aiKqj-&2F%L;5~IBdp;erxIv>$}9THmy0RNO}hzYohpXEFn>8J z@NfLOUk<v-`zrQ_@kgpb6!aNBt~OfoaEH`IOmLXs3-z2!ZMO4|MbiZZe}JN>C~f!4 z2>Wq6p_e{lsnydJtP7#tFH41YwS83}Z~J?Fs|vXmtwyy&w@FJE>e!l{IEg_U7sPX; zE-hPHpf59O1#LNWlwwsaR!wzmJr%D;>$B}w`FGPt&t$w^oz?rFHaEYIv~Gdu9in-f zDcn}ksMKG7XW03dIDiR+A_Di;aayA7ZZa5R@tW0C3Ba<tGcT=(sJCXRLoG_p`+7(# z=ie`8pAZGrN$fhu2cLf#Sc=576>(>6HK+!E&v|{US<iv|W|*L}QzU%mUE*N8`j<yo z$(wnTqQpeZMXN67g6>DK9`_8^F4S=_f+7qlJQ?K>;eW%{|JVLx6v`Tk<I1%ew&_@! zs`My_EUlswI+-Iy!LLzX4j=HWgE{SKV+r@Cc5XE`@@H@&pcw>L1V*SQdZ>R5(aY&w zFE-7SJ*8_tot?t&zG+qS!&SumiiEy%r5@~)hujqBQe#F$rpdigpPkC7p0Ucf3?7V* zT++AB(zfR>ZI^0mUcc-ZN-k{}U(X;m4bVF@U7k-CZE)dG{Y5t!EJclmz;Kl{=s)fO zJw5L#PUYm%jY@B6gzC6;^{*R2zEY(-if@wTJ#+wut!;Jx1mus`(Z=pwK1_S5d>Jw( zfS6mU@fMutwN1zB@&OGY<(m2Dc`mu+7jY_ZWPC8z_sc(S!FGvSykNBc`id4mL(c{G zJ5%B;8+E$0BwdLk)4r`FBRDwSbJ{EvYH|_b-&HyW7pmk8=*l$ytyyVeI04(OG(tq` zM|k)UGJqnO6Z647<XD?_-7<wuQ4}PGje65ABmv}sj3|~x>=ob#P=ev6@86~=llgv^ zk!$pZ&FRxXw7U^mR2LR-^mKE4!*M#FME;#7MK?BgoFgox@vnNjylgKnr?H0@k;v}1 z{D}Q`+Y{kmcWGJq?yJhDHy9C_rm^t?$@v_x)d3|;5UM(iM>UBI5Nm`ai`&EE4Zn1! zKJ?kVULET;!BI@y(nQvdoFz=!Q*D7gG%(X&Wwj`e@D~uDxX7@T0enF+U5ny-=)$Vy z0Zzo_t+S;=|KF`?zbj<ua|2l|d(YF!ymaAW6`*8_cG98s2Nxy)B)5EHJ~Byp5!x_+ z>?OnzVv^dd%cbo=c;;aQyzFa&`=JYXKw5IlYu4F+&vr)LId%X`_P04DyrC$S*ANg@ zyJz&|<N1BjSk6zWKR67hw_Tekbs0##el~>VdZF>_S$(MUK!z_t3&$!?zCPd3zYA-8 z>gY*_M6>pO?R!s`Vhn60eRl#|g>Qn+kmB9GuW^*31iWAw0aDgoJQ!$?TwAn}HbcKf zPd-RU`sLUncpkUFyrq3&uuXeT^z^v@uH9w}5V@x7$#U;fRB#tWa&#BSQ4U@|IYe_6 zoy_~T?*Gvn*RPi$t9iYHPnNRZ&i+RZE0;GYNR=CWpc@iC%J8*a+5$*a5#%$GB%sd@ z8b*84VAy<%^rk)mTq&D~)};zefB4hCjF4y9wMOvHPvNJ<JgG4OlSsTV>W{xV=SZxZ zwJ5Dl*hssHYND0yt5{I+ZAkw}Y=#yQ9v7AlS6v1!<VthD1O!9^-4x%AgpIMN!U^Tc zXq1?o)l1zbO8o}cs{A6t260tKLGG1G8Oc<{u~AW84)4&K=?;nIsAeG1DvFQe(^SHG zcx2vYIr7_!O@jL7+olq=nolJgCuFy0*l9$I=rpP{AeMj34*CY<EZtszp@o(Fl!{CL z#2sIwYEKP3)Q_Jeql`U+x!S|cR_Fz9=w{LSArMO$b}E?9VG6<p2le!|OtwRx{>*%@ z@$+}{+Bw^+-YxL)e30dY@u(9C0Qe^pOGjForHI|c9h>(CvAkdS!gH#UxhBx(w{4RA zx%28Z6ZkwKSuDA7l{I-!DEWQ7tmr9Lv;Sw%eeo_XLR#=hea@YBudP>L>T#dpV?Zz# zlghYr;-Dbb=e;eqiZrjGPtK}|e13T&%_%sKdP@A+BvmWseD!D2`B-exxa-&bQ-<46 zG*3TzXNSR80pFG<>{Gbt>Qc0}zU(!n*uNZO&4GNFdz5S+OE%8Trdx!!pUVF}o6HXJ z(s<x1!;P)DT|%VKy(cm?TrNu6xVp0u7RyNG&(Q23EG?J4O~O-mxF*xGYQMyG-^972 zW|Z-3oU6~XWpNo|Ol2-Y%^$Q|M*utE_~6V)K?>h1)ffFgE1CecVaqd4uh!?;GO-i! ziFvHaWh|gjJ}?gT)H4KCxsj9c*S#$fJfAlAk7?`XZj205OA&<U>ytE&FLG3iEB*F% ztf|MnyY#*{59gXD^itguVL*Ul;iaW^&0c)whzrHYop@Jgk&8H)mU4#!nXewN=0?{+ zLjqRDfxqbt^TOpS1RIJ7BGsm@ig2<jwWAD=yh?iN!Rz8m8D{AW9|AQMd&o0hg{oN$ zXm*)r-o~UJtB^HgiV(XaAUl?xwJ@{{_%~q~E6H*N7QU_W4R*<r+Orc-b?QWs7@KX7 z{{$5y=n`3EZccJMFurix99Irfq^gu!$rY#N_g>i6h!F4Ks8KHKjr|x(4WlUTDBFYT z_$#LYR0K4RNZJVZO>(R%j+nJe@-A7+kr?BRMAaxmq@8rQjDh;LVjP2D_b2vS58+%h zX7fOjjMs#*Yazl;W1DR2;bc`YU#MQF8w0`cEM0b|)xsv?v4v$Bu{5VZ;hT&8Zj<%G z2Izfw=%`y(E9R9RZ5JJmBA<h%Pkw{O*TYU`kkIi8F7NTPfC;4xb<9;MSrngRZL&LW zb?~tUv{9UbWH1Va#H{B-PU~juHL>k5%O<%GVx^)uCznsrvBszLPvo!IhpK1&65S6u zKY_2HR&lS-OtjRcc)V8{w3KIN1w`+=5DZ08?BPdt9|&HQXw?D%r%gX%&fg=j*H7yv zK7<W@dzAo#bM4hJlgTNP4Aq+DLvLiQ24)N#VK*A%t}23#j0VcMAD^WKLo9pDN8x(w z%@LB^m`NLJPdDCt9W`%i&u9PMo8ao_dz6`P9Q{K+1^$mo<I&^gufsYK<3e61c&qvy zz7#v;PEM-*C+P#%R?y*^l)4d}#Dqqz6TB^v*w}49q?`se?bU!Zo0Vk7cuu1Ugx?(Q zP`H!zj;WSst`bQokFl}Z0ke4}hry^5|7W>7W>gufp?OTW4F43t>j8vZJS(z+8{xpz z#V@M0qJ~zO9kw=D|82VP2<<prq0iTI?>>R;rs2I!46cBkmC{hHPaSOZuzPFJam8VY z@%<2|C=`a4X=+sGhS_!C8!P9s#G)oDxZ)+Qz+;++bGaPXq)cYw3ICcLGn%hYc(C0? zXsd4Bb~Ygs@Ik0TJAsU1#*%rG$qkog--{q<js;(w%)Z*Q`7kE%)QVMpOriBd#8%m0 zg%_JN0u=yTKNM?X{40z<3R)jRa(TNDx_C4$Cy|QJlC+x=$-Zx=d;1kjhkIV_e4RQg zq3wE^PtLr5ilOrzeUub#zHZJyaiXO6a|xU5Mk2C{A!EOCL^VOKU?cS$I3nhg!;u8I zt;i0+B(gUL^uwLPSr^ys<sPLDv&&(kothFm8pgef=?GV4K@|JfMJ7P{zswJs6r>Yj zgy_DKmJ$T<+WbC@aa$*bQo1|6FQob7#ZvgoD;^Xu-2Ei3Q|Z*Tzd9|trE)jg``*O$ zI-r0U(CRspg4Xv*rKPCnx&$uNMT;Qi8iKB|L{Dzs$ihn)jtg>D1>l0ADKXkQjpReZ zCiN*D3{wACd4@wiWHS!D77YM@-AdV>^-|g56)~Am<wLG96kqzEUK0O()vueDKdb2p z&)=sI&Vr;WRFB0rZl&Ya@0x?IQ(JIHOnBUH1`C=qI2;r}iF_St2PmLK<f|9`H7YKA zvo;JDC}u&!w+hvePwZPK(f0B@7;<J>PYs@Jx!L>B2Y4Y<TCus>Xvt|~&#=T$@A?lV z%=p3gRdHeL`W#kATd)@U=f>A>Dyj7L4L#WwBcBg3)pdDvdw{}<xLgC`E4&Bn8lPm2 ziQY)Ay2h_PNTL0GT>1$pshQR;i0`@WV<aC59lNuc`0}Nl3$CLj`fdNQESxTH=<>k# zTw*HXJ*z$%B6;3C^Q3w2kZS7HvhOJXD0Bv~o}wW=cMOnHayhF8PsB2iCHVtQs19aj zE9P;PfWG{y`$c<Tb!||UwTZ^UR58oDd2F7+B>owT1gMbe?|a2wdHq9pD0Q>xG(g+` z;5Qu6oMOLLs3g1ndQ&bSqkVdhx+*&N&ClIW$v)b3DwxN=iVkmkFkjULxqS&x_{w?M zB^Q<N=GQaYa@dB2pCNBs!?X)HPMT9J^Pl>u$B=ysx<-Ln9R(>G$OnnJKmAn5(&)#) z;HTY9I2Q`ixjMhQ{tNQtVdc{NfYo9(?EW$5jZ+wJVv0Sash1(U)Fk(7R@5sl3oVwL zt!1rHUo9T-(%gpUoX6R)E8B|{rTb+e97F9`=uP5m{Jx~GQ{G^a&Uo*yB7gLwV1f(E zYcCCD6tR+hRhxiaR<kx)<N5c$XzkNlwjx8w8^aum8<)mr{$S<AzDs~2*IJ(5w;F00 z#-bk`CmhNNu3_N)2?|`Qkn}JKU48^>XF$A=Z4VQsN%-n&(W)VI+gGziKKDAzH_<6V z?^~u9aY6-oKRC2Pzg&Wkvt2+G_U%PJF((p@lTU`{C(VIenaZ7f&Oc|K5)-P=<n~OV zHLuO#{7OBk?d$CDA(9`F7mr0s71oS;b$pS&#CKaqW99yjTIDxh4|2UCRL_}?KY*6{ z-1sNf$1P55uhn^eEvENZgcv;>d2Tz!kahc);Iz);N6SoKutgI%Noc{rUdSxBQH2el zgyT^T=Kne8C?vL7g!-L*WdG)~biJ&IRo43NK9`fx0s_lNza#PuB_Z!j3?uaQV@A?t zGJ=m|Xa>B+pM&sAG%U6;qed|c8HoK4YZ=L#XF>`-;me?9JgOSw5%Oo<wtBK?S`ZCZ z=cr~)cY3~wrP}jRvV)C}tR193BSC#L?f-L6DN3KJUNan4DE2w>ssa5<<1E+7aW3nL zao)<b@@=HQ#tAQrCe#T0T!VuSD<k?)v)xMy(rv{7Hg(Enr&x*RelV!Mw0g1?k<&vU z7=4nuc=md-19C=Bg`?1o`K#uLm?{GNxgv#adjhrrCog;v@wS|Y<df^xpgYD>1T@K< zAL@Z)LFUQFkSEeu@C9tfFM(R!7P&C!Sru)lu3qd{7Hhs9gf-Zx5u)|%Mjfv>`epv! z1>i9{9kA#Ztm%F<i_9~FB{tH4!=~vzU1i*Krs#3z3+jj!Q{yNe=r$I_%NZT6$q_c? zxFPcw4mag~|59yDXkL{<%P9Hg2n}4<W&862%Ws=ibhR}IWPX<IdvJ6d9~b>yojL(t zWH!%AzVrt<_-g1C`&*pRl-GUMQXDYI5CtbP!O&ECDI=+PiCO(aH=lTU-Iq#+9A_oU z2;o_A^=oon&w1xiR`9^PwiBP*VvsE{j&`{&67Q+;%_`Y-jbsG$$Cq9u_jr8FT>~d* zKNqIPA$N!k6)(;^hAoGi9j)&4*;YB>?C>bk%*BjCC$llW#LolAo1UX$%~kbOLj%UQ zO#0la|F?EWkDF+iCq!?EI-BKYl?T@i`u3!rhj@4`ZSaJ<F8YFQvCnJDl2|Z`mrFC% zvYYyoU$Y>d)~?#$f=(Z?7}RdhpQ+iv4lsE<{iu&?fGA9<aUgIsrD&$Z=}qaM5RJ6z zo)oOvM@NN$&s)hTZTZ44$mIqg>dAE35lKa^zcuPjegImk#gv7%F<R+CvK*t~A4kuP zgd6iP+{1Nj6Nt1z^*I_c**q<Zi`VI`!e88J*x<sz*oY~JsMd7ZN5)n}WEEL;3$g0! zwmq{Bx=QZCkJa;U7HNBu_UCmusXoc!AxC-a)RvS(Ppx1D4z!WU=Pt_g8)UW_!fW-& zgb+1VU!s$`)gi9UDmK!bm?&J|qi_AYb;eJf!Y`-Ltoi7l^2HwkqOW4*DvkFXQX+>< zd*#1hYSq56Y7#8T)?=<6AUsh)+3DM*zyexxF0ip~rB^PL>^XlFc0hr}Sr?e~3N;7o z;kS{Sbuh-ryjOf~GCR0Qd&r!Xs#30Zph_5U*g;UT|5!gI)_q5>(ODM1=-hpbzvL-s zBEO+EZsTnBk)nG<&UXD&s!PuX^LGX2t8z$Rg-U(xu#07qu8<q8d9P}^ev|gRXMf3v zKe3{5WzlWXW49JLhnv~aH?hY~>y8nYAgZFol4(3;@9{H0<R{R5`s$-_xo)|wU*G5w zdT$qG4KIZf`F902{7jx~@O<^4?|OzXB-bq|UlsOx!5aIu(zgd)3nSW^fAp)#Zz-G7 zZ;zrNmpF&y>-@$vt7>@c4s`@hN%}OuIXM9?htvHsyhc%&REo#=L$Wy4v{S_OPnC#F zGFznHMgy7Ji0dsqu6ab^(J)_-O@?y<$3LM;vM~CoeHi<DrN~R3jn{Pv=8MtxGC7=k zo8E&V0yyh(K84neNFtl_Cx0aeYP&cs6}hsAmT^@>Y-2u<Bq~o&cLwHW2=YH+YFBof zp}{XCbW7)zl3P6P<NTYzaoitRa9;BbI~5uJlWDx56n`N%*X((yBz{ifc<(2UgBvA* zBvQ33*4Wct{PE!9$4gmY#nkz=q5iU@mo=YD_@^F`IVIb7qOa5d-rV1TScW}Xf^fx* zmR9)lTk)JQ{I@rOdD5dV^lyr#;7Cy^1s?zw6KDAKx)*vQB?_wzuNz)uubXa9N(7s# zCvwr+h(*YDqpzWK{S6`z)%)4Oh9^Rklk@3y_jGuQit#iuNZh}1dbuyYS)yK<_6(P^ z%h<FnXOu(>D?+>*EJhMv_u?0~oun=%eZD@w>@$Cm-IjggQtd~hj8{zRjzL6IAh#%) za<iHbr4KTH4IwH`$i7rtpX%1~0$yz-Xj&bs`DL5Wg8P&^^L_!)mno6$HIua#gUxf8 zAQO|5N-naxa23$X+*q`Vk$eN!P=IcaiA5|mrbkt;V)w`kK|<^ub8OglU3``em`BXb zeI&o;$)?+U>-NF1Qcg}Qav+zX^(z^T5*O1*VJq7$+x7&%Xotk*Q?c98XVOXw_O%!- zD)zd=)3JxEet>;ca3fJ`UJmR9ZVeJIYyL!ANNuisnV0kOXhPRy-(LYV`m?m6xnU`1 zhJCb*)1QY~lw<qt?pK<2)GqGSyn^*~Q?`}X9A92oP?wg!94!u1l%#m*Q!%ucfqI2r zRI%^%znh!yfZS-pS`9ZXvnmj%R9et~2Hal5OPcE3;TinzjYY5vZPR(38$0lY#u1X4 zv)!$#2<1P3r0&uexe_X3K=4>ZI5p9^pCA|`p+R1XUZpua?GX=(bU5!6+vmr5TjZ1{ z)>}HB_Mg8HZs^Qfbk(9zOtXbP5uYZ+>Ka#M{r<)Qppd<?0)Nl@BPgqrXlH7Dr<EBZ z{6hlXsTT!lld+W$-Ip`#dXZTh_7ySa7{e0zT=jP_?pAMmp-FSCT7n1DRo#nu(h_jX z^fbl>b#iSKXZK4*0Twr#93V)=(-<z^@4Q(K-Y~6o!eBii+A+t4&n8M?-p;Nwb7HPr z0vvi~u`7uwlw-wu@;*G5s4_!Wu<rD-luM<QaB}2wd(4zQr8&%K{)(fHAqLlAba%2q z&pSNUV)bT34&)B2>;L75Yd-52rc<{*%^ottWj$k=a@M?jRUkG^r|4Dc7!4WJ;0+2V zSs!N+oLG9_pNe@RL7F%Y_Ybp+xYIHi&jJ4+=RyC`r6zbY!WS*|!!>)sq%EHFu7F6r zI^XRl<5e~jo`$_^Q*{-QMB`^E%bDD$Yh~9pHcrz3d&N&rX_b^&&Z}N@2cBg8^|Q9* z0QuECyONnA_3xE682{=M#z+S5>3`KB$1uX8vk)n?X&xd<O*qDJmEwC!J+~ZcN0x?7 zG*<2s6m+TOo-HgjU{bw?Q|I@B$RiFkB(p9~q`W|>HGItQ#Llss=S#HQ`oBlBt?^+W zvNLK$XgS06EHZ#(p(!uwPSB_o)tHDhD6#HZAA*}P`!if+d_k@gu!iqsU{8NSWJKoh z-cUTvZL6TTJ3qvNN_Fz<nAQ;cJ&vzvg~0k^gbsc|6AYL9IugBuqgAKZyO=(!;t<#z z^~x_$FS(7WbTLijBUgMolVyC;^&wZABFAag37XnMwh$LZ9lm~uWytkDkL8E!xQ@Tn zcRjgP8zIdQSvGS5?TfhMex4x`EjQAegtS+MKSPDhz6ypNL9p+TA+^}w%~eb)og-N6 zWLMzWmXGT`P27H886p-OCBu+4zI+|<E@!sPm2bjSIgR_vaLa3Lt2M%m)@#|<QH)w; zUItDv(Q2aIxEZWOHlW7CtT2!m-?!ZT_Jy)3zy8$Yet0&E>pO*D|13iM7a)jv&XeqI z6TY6-06M=z&Y!ChtUe$~e(+?^JDl$7LBTzexvI*CWNmYAls?<DImX7+r{Dk742hl< z@s9`n8COtW5VY?9KrD)WgiE;**zM88VLypVP%dXC1NzM56LZP3>`EXOo~PTeYne~u zcbYblcFq5Zz&kD!;TAm*SbZ*G8?o}yiyp1n{HQlvOcK>U>|Tzqr)}$tMS(+uTr_k3 z?03FEA-^3dzGpQ?-3tWF&EO*l!ap#z0o=hPi`2E0qAz#%V_W&HaoH0%q|ayA#>u*t zOR+guByT_eyey7pF)_(7QRDh`NJw<c>ZW2zf*&gE#lYM7+oqSC-S=ugkaxCJqOM07 z5t*h>V93yUfEIB3c63_Su~$_f`tMOe=p<WHWc@tY<nB17iStOR|3q104dX2g8P+uf zZdN%8Qpj~gt({l0$8NY@);94jx(!#|qG0|9g`vcaDy*A9pOd5_eJo6*he}kLAq8BA z;<dTFU+<C}%2$*o^%iY2IDg&0qMCKQG~>TRcx0CAQGWd}frWxA%7*0t-I$c;8#yVA zWSg*}06$}|27e-O(@Qne?-39k&@1V$7GP7c=fSQZ7Cp2~%Trl>7fBNXa1m~2C5d2c z&W!R*VriXXWlojzc5g+WQzh%`v3{hfVwp93sy`qv3*FwqO15`VR#$F@0UQKFzf7+- zkat0(s^2%?I(GIS3%{~7-MgzJ_w=d>i7PqKw7OGg=_%*J+Tl2B7<+Q4yy)Gb4l!Dg z5KG9nW4)WI+BDZAz!BI@GwBtN0z+)+0l%-pR%#B*xu5sfb=eRzbg!BlYFvITWg(8Y zfl4j2MaoJ3c;pit2)fYZo6>>!DGv^hKEdwyc<&;iNn`ch)LZXNlmQbtqWjoz37{L` z>c6sraeovmlc>Tgpy?S`3#-;hcAclI#3RG4vx2qUe8Hm9?|?K{mRpv6TmWogyY6Yw zx$oljo*E%Q5^}fmD$Y6jy%w_5j!MwN!f<X={kuwN$fK;;{JYWm<6N!VmtT3Is5?C! z)h^KjN0$K+#YdpIHvd$ZC5y-x7S39tAP#myk#YgOatDMuXVD#f4n#pLLJVE67wR3A z#Ipktj}@CYaIEi2NKz|X`}fEbaF#@T$d11BGt`t5uM;BLj(((rLQy1us;QoLI--Wt zOP&wrW$pFhp0wvnr~=4WjmA1yoJq0p0_Q<Y66FT{q8@IQkzAVs4rtO;yo<=^H~hk2 z=C^ZgGt3zXkcaYZ`m&3?j=AyAeN3TuJM6snUi6pxCA6ey4lZBR+bgItmI;?3HlH&~ zh`U}Wd1&N?bMk7jFKc~fOg&}E&?o$y08)H(h^f^Lf5<!w=Ag|6FY(_{bI<4sX(;E? zO;*1>%EyC88IW{Xb-hiY_kW3zER#Q-d#`R&MQwy21duIyqgJpe#u}Yd#w7=bFW;>e zcJRA`6SheRMqx>elhZ*2w-K>2>?yRLJPjyj1-Q9aZ^`%U@{Q(g4TISJZkl5%9nB<$ zisuYgGfrCtZ|&!bsS6%!bbE}P^WMnC(;g*hCR<J#^33y-_u&wCNo^FTm`@DA^B-8j z<rZ2-N>Du7`S;sGiL*z7tMzq9-BeQ-V6)yL$zPvxhe$t_ekVMPl^@X#xA`Ze`VTOb zBcdM0#Ul2!gEl{SQq#ra@5=ckQv|(9jFlptNp&x`c5;5z&F76DZ)K_H91_ZWY%}+F zjryV0h5-JexmMMUFVpXmN{QKF)rhaEaDCitlD&&<4aa4=b6_t8?}54^u$gM^H&c^* z94|*_Me#x@WyRrl(Upr(vc$_Jf)J#f$heZPK8JmT!h5tn2mO-pC_W8#D~equY1<5k zY7ONtZ~6nPy5;@yYz_<9i=2)u8%^`;WE(i(hs<=iA2&{l)(;uO5kVKZH(5J`_n*Vh zGtSH*mYIE)&+40bGv4*%l=P?Zz*AOS22+=XF}+d)yHk2=K8^YnJ)6UxNl~T+2mqoU zGHOP<aG*l@^HAvKu)|Jx`IYvegibPYHWb|x&6J9UbS@R1a{Zjyp))IR9-UCiT*qBi zO^6&TiWvh@^(NEV7DRfJ&SbLx%%}yjf!!GgD#!01%Kz;V=5pHC5>4y(CS}(l-(cRh zsPp(bm8Cd>B_q<IeeF5Dn9}Y*&X?b|T)17;4}btWv^nLksqKKcxaL##qbC2)N9MCi zOS4$ip1!8dANHJ|v~g7y;Ty4z2k)VF=dqmG2^gj_ZWAa!7OwEhUTJt_sBCtibUYAi zH{(8K)FkG7-CBc^!escBjYkZ*9CVu=l)ZO$KKGvUWOIP^oW3;E@3{BO-v&F7HzWN& z@r#tnKfX~{C2#M7ixaE8_>3A94yNCP(Ccg$)_ycj;Ik<tX|tvy<~sg2ip^y2{THvN z32Gw9lRP|Fqx$Q?^jCKD&BJXu+?^)_L+Sd&0_+HdUPx50ccO+%i6aSqopR0cHDQYj zxKsUeT46S8*P&4;l#H?DrlXk6*`Rglx#%d^yf2BFSEEp^7%RuxYD7!j`0?+fb(;hS z?y>QEWMs#CmfP@l!hk$ve2ryn7u(MW{nTf37_+y`qb-`_(la&;{y`N|B;8aFwQ;QP z<jF+Nj-)<DNw&^Yj_U<IsZD^u@-lB}$8x|7M<?GrzJY9U%?V7>!OTY=6=~bbe%_>V z4;SMps`+iNgvM8~`XD;Z2Y+KCiQf>wkxH-Z^zKdRn<IL2<kdw=$c#HyMTqKsk}M6s zRIV<He=Y-*Lcc8gdCqN!r%>q6zcPOkLr5r@q|XJ-@^igd1@#Eg$QpL#1R}4ybc-Bz zwGV&32H&enDw{pOiWI-r0Pn3)!qhduV`L4o_3#g50J{Tdd37*!m`i=}QWQ14@aSn| zDOy6nKb4GsQKwozJT3@y5nnEngs_<L&Wsk2&+r~u<duMk*^+h`#V(Z_Q=N#UE65pf zyahvbi0i$S^(R>CKZo;T40g$##%H+MbQxGOJuP+YZ4*F%%5v;&>kT5G@7V(k^A0*_ z;*<Dd6%CS&kxxm{Pp7%CvO9y&dl5|B_C0Orlx*^Hw7Zfzy?pXC9c*ZP)%`yT=P+<z zkVNU7%{neL*Y^PMDjln|_H>WVI^GR+DupS?jdqCJ>;OS<C3~#9U1zGQ0L+w^G_bpV zHc0uDey29F4jj8CPe3#MQbn&7?d{3h+x`JbNJ}6wEpd-{E{E3~$C_h30#kRBwI;bO zJmmDNpqX6O82z`3&q?NIPmcHAs=w{m75I_RTzHS|H{BLNP^y<WO-%E<WGQV9MD^6H z*p>q`k=Nm{9D{Zh#lMYnwd`&f`Bg9m`;?+KQG-s!zoeGwKym0lL}vf;*mTR%ktUk2 z@f5ngY8!pQqFTFJpa74UqbzKE4GF3k1SB&gktsH70`LOj+^J5LTIXu!yF5lFl??%q z?B{uheNBMaW(@6BDHGoCZ4VSf5QojUpRY!8o?GVNR$s?VH(daPXjfdtGM5)7iOlET zOQd+kAJ(65l3i=3zS=++V?iTiI1by&%NK@&dkP;XAxjb(pe>!|BOEb$4q6MlVxy$v zm?L~AHn=UR6|Q9*`Un1ij6>jDrA%8cMeinf0|kqExlhM=BDc|OjdD)Ve$i-lK1p`} zJ%VazrO<UY@BDLjtSi)rA#;y%h1~9-W>B#2d*MpqG4%yi9<|=VY>};FQ~$ABaQGov z><&5Hjt~!ezn$rUEp?@2DL>^L6<i42=Ke1%G;vRKO^F$r(gNlG4iNJnt|NK|AmXJ* zOaJq)`Tn2&<O-n{=l+S&)@1tUt@)p}!#}&?GZB!d{*0pH@!x;`e~@j%G{Ax90e{Kz zFQvu*G_YyU!#3;r!1VhcEY^R=CIdd(juC$e{%xL=_`eLyWdTf$fQ5L1(LW`p{{ar= zCI>9Ng(^kF|1vN+H!wBS+_}9R|DIR)Z@*2$!(1QeF<SmF1LIKuQ-e=2Y?1PxE{XsA zGcN#hZRuGS&;7p)91;agO(>pC^}pPi|Ka!le}1<EV6Ll$bQIG5mw}}ocBK?1?+oMr z`)c_Am*M|7KmT7@h5#qvjkfmPGQnMIeb*YtpX<WE?L4+2v8{Q#U+a7tihlfP_-;?N z5FcOn>rl_|O!WemRsO3m(4`@^F;VQlS=TIK;+ZeRZcoQ7gGqJ172Yh}-!2_LfH7hC z3-<uCJkeTYPe0f#G5O|AcH=|O&yATOSl!q+!vQt|CQ_6$>|2!c-IVF~fJEl%voI_% zNwPsfs7F9}?KL#>2EdqWTmo!wBV%Mc*%jmxeHWk>-wYi;wBUeoc*n`{b|$9GQznog zCn{jt#;18?mq;z&@n>CwUJ*C+`LiG8smDZDH=VUC%*K?-a_UaQi*5ln`%iPVg@$IJ zQ}mLLSbR})xLa*dE<ifiBqx31cKTQB{zNQgOYHt~<AIZW+bksz^HnRCoic|S7Z)%? z`LgT`&^1^ITDC@$ryIKsxO9lBVQf?qslfi*gHCh?BSeX#z93g`+74(Pob;N)N|UWi zGm|<}HsS9Bznsl=v;W^vh5CR8+OAN#z0rp7b9Im&&Wm?CKAbFxpd{HQn`@O=^H0^_ zT6|IDvdg%JT+#z}@kcxcMJ}WKrDXrF$gRAOst#{xOzy9y`hd5uuBz}+=i4+H+KAj@ z$`?XaB&xe&P#Oj?cvE1dWIc2LC$$Rh+oH&dtF>_EY%tIy0Vc3lR+E`@K%^q@MOUad zvU*pz4rKM<^z*(sg7*RSVzH8Y79k@v2W?-t9oqh<WWpn2)y~ti)yKuThScAzv;LcJ z-|vK;ivFNOe2^f60ZzS?L)DAI7$!vL{oUXD0~=FDg)r}I(*QNmON$w2I8EO}Kv&(* z-8ZiIV#8Wk;ITBuaLe6ZOY-H(Rtm7B0>FA*cXKVb85i1sw>;H!AWYL6p#3<rcJj?i zjCST!1CaFlH;Xr${3$?^>USeRNOr-%yVQ)5?6`dBDSjMja??&483n;ORuBAMJE{m^ z4|FuDQ&Nuq08bDOz=E-nY93Qenh+;vWP?Nfm<lS{m|e+r3&69t{gDq+^zM?B>3>6t zE}*81N_)Sez+vmX;=DiRwA}mt(_>?u(ymM+Ql|MTfq?d6DIma1_<7`&L_|NZj_$!g zj@&2hm0fZQvytUW4dCZX20-@p)NaEPukLr;2rCrUH*bKRQ5u)MYOvL{3{jn&pFeQ% zvM(C9k^n(L`3K14zNTOTGr(I@wR-y!%uKwnp7mevh1RDLj}W;JJq{kIoaco<ls}}& z!+SY#K#3T`@pk~`t}fHLo5B(RgSfqAkxb<!c5K*T`q|TXceN*Xq%TQt{9-_sLb~Nk zu9Uz<#?npE%~Zhc)VJn0_q-UR+;6YW193UPzyCJ-CRj*rjYrz+Z8dKKrUQWfsV2hF zvnIE2lY0&HPS$KbihiF+^}ex67>Fp1F94;y_9B3oZg_eI0Ns@If#^9aSsB6O$P&wa z4)kA0iQS>`nEq0ClckRKOv22_)erqOV5l<;k3@}y6&ekQXUw&`W}jrboDA@%sPHe; z>RA04c@p34wc3FJ!Lcf%0#x1ClmTaGjkW|^Q--c8-T)jE0W>9+`59J_^MLG4dZ_P^ zzV9q8Zzze(=OY?(w0WRMU3<-V%sK2ibBFzj%*We*#A^7=@2u2>9iaLLY&br4GN%jn z$uMk}@IJk#0=iwgOc{AjC|=h==&yQX0L0YHW9Iw+=ba7wr&sWp3)?)t@Yi>j4Hn0I zjdUAmS)-Zi=CYa%qTEM&Yc(w2z6#b`lqwvffocyhur?mt?5u8yoR-)})}kjAx;|O1 zg94%oA)7!F8Vmy3b^E6sIR4(>)GlWG)p`LmQ}FZ#=#&Pmzb$B9^*4t(P<L0&4zFY2 zgO#A$GE}xqCwgbB%{Rw=eG1H3Z<_CK|E4^U&z<^M+5T3(ML!X{t`R$Nv(Tit!VX>p zaz5riGrOMS@5!>6gp$4?Q{2;16)2ns@&WF*hy>-%qlO2RXCILq^@@&%$@T0MLQ{!d zJCd|-G8`BG4%o?yaL}3?P-<|nx^Q1CW6pL}PVGqz!4kVdDZCFRGuCrTYCZNOfuBC< zTg86BT=zY+ig;_=n<|YG@^|2Yz`0RB<X;{jFWwfe$%fd)V?uttZhts}kBim(OXfY7 z{12F))>U!Pz*C#QaxNXkcqX>o&b91E&4^sgui+??Oa=g)>e>2v^bA3#qiL&d3>*(b z<3p6N=8or2O`7yx6K~f{=okzf5jP)x2qBOv0GLufmIw3oFdE*!QfRn>9|Hj^+aoW1 z-v4sL6=9+(H$GOL9|T4^2AEmn#0D%MQ(GYdaLIQ7+3FCR#&VX)O4CQ<+;{0Zn^mlm zR#M_41_iMXTV3V1w}7<VKk#uyIQniURNaAoQ!bq;l~_X$?`6heexn5{PfVO#wTvLs z02Z~=2ZOREWEW@o+zSeI9D9Js>UjI<EdA;cp8B1A%>duV0|D`Yhtz~WA>+?>)V=$Z zQT7d6_{Ezj#+J%F8bvANv)k2VBY*j*cp{laZ01aLV<2grG6XxXDL-5mob@{yxJ?&# z9IaZ`%ymeVsRz1G>DFt{%`Kku{gpebv0;811Ulo9t<03h)So|JRibDI_JwX`dsp5G z&>S?gZ?aTb`K$2RaJLd?6Tk+-dO}H%C^zD<{1FS^;qvvgDa++ZENt9z!>1#ZNpbUm zi{HFXYZBWN3w^&9&0ju;7NfUTMM8}$!>06*puQ5!lF!J{+YvNvbTYZiXt|_n`O3F5 zJE&1NQvTk5&p=d_0Px1Y?dJ0-)L`D91Maj1C^4>KeKz61n~31Ja<zjvzejmFs=(9Z zc+j(XOpN3qBNt2{H0(OC@}4-#hH6b>-|A0(K{q1N7kn$wFG@o$M9lSnbZ!43$QYwV z$!OHRQU0hoV}Yw8ZAr`%E5H<;!=mugK+-U+OWQ7EMS`xb*WVIG)P!g0Ah~_xrfg5# zh#+xPT|!jGN>8W|WvIuzv{lT}*oxdm7wAua_vKthUtqFc<%V_c=ofciPs5Wc_VtYT zuiSPGh_aepmzVD&A`onWB_ik39U0%MJBL$a8xSNE6YM|dHBU_5=;3LqC7NtZ=nPJj zdnv;TH0pa}7+Kv-0Oa!7EAu|vrgx(hp;5lDqV;e6@uQYW{Thxj021_d8DHy|DD9iN zsGnEBD{Io5O+99Bi4BEStNARLXCJbmZmD>IxB;pDV(F3mP~m_04PYrPU0zC8xFe5* z);~+_Hgogi#1Kt!iyZ_taLx`+x;O2zBKGu-w?)MlxzNt2fox%t{^?oQ<W24sxdmIg zjKvm2oN?SXLa?PJW2n1%*J!-6r{vHx;KDQM68)_Cx<^h_^Mc49nmm}Tx|AL;;A5|q zE&8U#nSe>Ud9~%WIq$cB=pFwtL`$7~+}T^p?oi5Xt9&)kURC{s*wDEcTY&iO+^>!# zR);6nsMbp1{w_lnu^<HbiLP!MV;n1Ee)ZE}%7`BlK}<2}@=p_<jbUww#JRMS(#A8= zvZ@dpK~KUr^&YS&#<C7^)K(MPGu<qUoL~#6K5{00{N4GVnIs3OhJrI4M)+<GO%v-} zWj=R{&ns1gmWURkEXNO`G`D#sPFsha$P)JDD8JK>4&-Y%FauEoXAyY;OC8U%GfOIa zwt{a7H=TzOM_h9#OZ>nsm~<)deb07{(>u{x$VIoV;HS^sNsh^k%XIT$2-)jYMi0x$ zFsOh!UIm!y;$>nJdUV`Ja!zokd&u*NGDg-Km$Qa9Ir_?1@Mi~hb-c6J2Hu?wi>9Pw zjIpC`qH*NLH^xAB3T-PCfs%tGBy2~?<k*+TVcmEn*06SjZIuQ@GNJYAn@Ysxua26~ zSYEJA(qQTcPvq7da00&FDs~u_^(j<KdQF<BRmiLv^IvYVR6^8rzuv(3UjC2aU_}h* zoW^XDx$-h{1``{10(${=y}xw{=3POfnS5IkB)J5<yhO6DD)Txc?4F|p2VR=GmNK85 z>C7A}RuFje7H2-bmq2Lp>%=^eGA#QxSx*dfS%W_FBQV$#)*ng_NtcXe7D+Nq?a_V) zFaM^_GLa^+i<O;7V=V!&?y)2ITX}bI2pr)5Y$y)HK>>bmE+uAveFI2pYr{AEI^fGz zR||{Iq=5C_=W2TFFYBQq<Iz!dN}iT|#!VHURi=sis^jfCJhVYc%*ItuqHqJf!mRQj zQ&^xU_7vXM!L$wncgQt=`<d#qw<wFTY_({8(q*?6N7HJT@{z(fkHPaA)!2W-SA&lS zlB0AtalVuXH3y3&dp2NY1DtgCrOpOzF=yr2V}d<${VJT!5~DMZm0O@8Qu|-V&9&Oq z=8^Zy>2pA%Z2z(g0}qW++yGIM)V|=|o0Fjm()#wuSR9{o=lcmb=q$%;+eaEUTBHf2 zZr<!hCo=w*TZt*^!#>|$!uv91=&&?E?<+r1U?+A<_U^`};#H2<@cSJ5)M`lN;*WrB z5gX2<6U)s>zi})A6&&+hL?nb*T7?>bt7eVciFWS#kWENyRx>cTL$g8(S-eacaq4O( z_=Jo5|E954LMdV#m>qw{e3Ij7JpqJJo;ME67P^D4Y}NB}8>Jz_fK}eAE@v);-4Vlc zBT0AC>*v$A&_n{tv!A2BW~F{zDt84xgXKZq`ST05U$YDyyR#gsSAVU_E(6eylKvE9 z_xsz6DSr-u;(TxF%er2!e%{&qD**rr*>u~md?oosmClG;f(jA_9}d$IW@NopB?J{- zL|9@xwn9gq<CKs^8kF__YVNOqvMW`%K#W`xLb_-U7=X7g=(U2qIU8~81V?YN-VRu} za6HyM9N+lp_3^<LIc=S5&61r>2O#a)zAY7ulk?|^x@zdLf-$qQEoqb#AJn;M&~8`W z6+8j|ff^g=7lx~zIRyYw;k~P+5XeSa*Lqq)d92C?9?6j7McvnRS{0-HbM_H?-vq_f zJii0k>6Ksv@38Zr+FDF4EO0jl(%7lye1fKvBIuGpz1N2KUm_(gS3=VZ%?#>GOw`Vz z(~}&P&%%6+!GC8F^(vcwDQ{~Qi&0F`o_VAeQUA_OPs-kMUVLVsw^_R$&V1xIr*c-^ z$H8iau}!r{m%>hTp@L^MkgolnBi|*(&_$uD*TpE9g$PFo4?e6E!h$n}_UI9KP(fPa zjXcjbgqyX}7W21l2BQ(gZnS-qxM%2K;7|X+CWY02mU5h)W8+abG(w3JM<jz#<9s_m z_StWZDi#rcIWs=0dgN*(*=%MziFUIR|8E|UYd>W0>x|<riqeUez9<mG2p*_VzKnLz zg#F>PNgO=V`=XCOTLtWXOLB9odINj_h5T>f7{8SF{q@pcuk?xUYrXh0QQH4kd*2n+ zRG@9E(nQcGhy-aOU1~sjRhra@2!eD%=%M!z5K(IARgj`I>Ag2W2)&3DrT1P#O=x%f z?z!*Y^UnExUpHU*$jHdZSbLSZ)|^vV*_0aAlYC>SR|~Ydr>U0g=_2{bU)(yElOYs$ zb$AJ<OL7=<2J|Fx7_EFpnlC~`!44R+-oyCiGXB^48LZ)txT%l}V86MimII%$fMVcS zLvT&Jg6|EloNF$)I^h;Tq&yDrMn<_c_2-+_B`M(vK$3GQ1yevWgU6~1@7vAaw_Ys6 zlhp?k)DDl^-G!+ppnk=4sdj#~wS^Vtj+bq~*&TLl?T$N$IjJXhX6($V&aQiX+odY; zRDdi`Kc^iGroMO~wnlP$<cFek4hPQ)!`J4-r#Q{r8=Y~nQ^4-&K;7qsQqKN+{0#;d z1huWOo|#~!p1Uyv-%Apd>{L~=kz_P8c5R|2PLp=7{|JNn6h5^^wvz&^ax|p|tk|z# znjCMuX{jIBe4j{NEwk~F#7$Ml?9`V0DV#FZ6HTK(|F0nyb+ZplX#Ok&e!G=TtJy9- zX%^~>jh%RP?_mOl)5P?npL|MXT{@rEyO9K@ubSk1DM{hw`SWzD{F5}l6H$V>0g39v z=a#Xev$89HXH-PT<2pN%v5EW;0bs`4=dgY333dNoPTXRzE660MIvE}LNK8+M)P8BQ zeFhR`$BiVBLF7{`Q!(n5ZUf;Op`A4kKG!WL_0xJFQgLw(_yHC15hVI7OtT~y^!TlO zvV5Xd|GJtCS=Dxn>lC!fNgqii*9n?M>&k^%R%i_4{8?M$bgLA0NTm1tAM%+81TMFs zDJQ~MS)VN{*^$<6zcn)D3C>O_jNvHoZv4)2mB*{KF^Y<8#6yb3bR@tn61$BR`d#^j zW)ppo-jjWjJeOq;#I5Gjy|U9@<I7>((GwECZ~}uHF9Y{^PHr^yFhNU9R5WXvG4OU> z*C!?Tlu8vPMW5w`fLEx3B)~DF>GYWPM;L1x;)3c7(3l)@f3W*U+FV#+_k+mIOvXLd zdSLp%dHOq)JUajW?2^4qKB5_nj7Q{<sS1yqTDu;~<#{K=McE^LZDy1(^&XYWPK>P- zbiVmeK*a^ZGwjqS6^o?2P@En1FbJdDq{))*jK7wU9~b8H_^KK<pY3eWQYdT^Ai8r_ z9b2Cs5RNZpyc`K3e){jaT|wgOoE)FB?k$*yC_hk*>V^pf#h_)yUDc|)ezgy9&q%gx zM|M+7w{jF<vmop8*T0JY%_oRv+{&nPFV7n;r<ZRzttf(=<NAF#f^G~IlBM#w+645d z>7dKM7ux!~B8%|&RHC$$>DyreS=l!EB+w%`Q7p{gZ7C)inrmeGOI^h6l4EmXqQjiF zgPC&kFTP_B5BM6PE)*4?fu9WS){=(6HEkf#7Ro#+v~IXh%b(6}KJ67;Rch!Yt0a=N zB1<XHc%(oaPSaDN7GKsC83OpGhQ14b5032$d47jAB93fvRI1RYo4}sCcf5*8<YrgD z=V)zq(cx|9;Y;ucD68r6sH8+k4^Fj9G8~^PnqVuT=pR`k<?fb<R<G|Odsyco+Z;kD z?d*v9?7fkf`MVvj2<H}k7RbSMSWgV@eY>Fk&~+)yS8@h%B=ig1Fa>)$GvXnh>#(lm zYY;F6@+QJ3O1EF_$eS<12vihzI&5r9#6MCU&GTLti#FvJOKD^&FvC+2W$P_PJl4Ma zCNB|9ZUCC1te=vYuv#O#akNKUvaLaP85Q8%j<((DG(h4#<&8IzY^e%g4!A(sANiFC z2ik1N8TRHUBCj-+=$B6jgj3D*aCNI`o6P|2uHLaTz+eF(mBjQfeS^iF8{7)j-HCih z$h9v)KAg$w`8|LZnoi%io~a(2DF6x`!as8FR^wuG4INvFI()XgK2bNVDSTXx5-ux9 ztPs;&j4T&!E%8eF_=T@5U<){7<IXWZSa#_8?)+M7!HYhh`Z9l(Ew34!uv`J4s*)RX zB6|Mbx)$~+nWq%eDV1kf53?IMZq4fHK-Bt)KrgpeAH~RWoB?+V99OQ657WEN!}3J3 zuf_uR7exB&JYamoA$CpEb*{2sc=FWwP0F=#UB$<a-hf8>)=?5wVlP<)f@wiXdUb=Z zqu<#EszwcTcO~Hwt|=KvhQ&@FkC@ke&Xq~=g}JtBKkrNyW+yESFPGmAxwZJ-2|HHP zT-8^RUGNtZO6(N!$6au*6qJ4j$Qx;61-^rH3ycU0W&Ylib^Qa?jb3GS&R2`dDU5*r zw^>h)nF_P9O6bivDvS1qyE*N=XdX-~c9hX@qC-F%!`$27@heV%tm<K1m!$y;u(89k zHW|bMs)Peci-FFB=76~Gn+-Tly!V(UlW;=zZc#e-X+^*8Enc#|x09Q%8L%qSJG2(+ zo8z$?iuUwcn7A`(qu0%|zwgg=6jC+)2K+yHJpk>z=ohqoxw+$}Dh9?F#!1G_%+GrL zUKAHnR{TWpvPh8*;T@+FlBSJc;4em62{<sUasI(PP!f-kcC^QFT6*Rmh#4LVRzsp2 zZkl`&L&=IiEmNyNEOAzj<~4#l1+oevbO#?bf&u%i%p{>qzCR+yn9MZ#y-M}qP*fae z&Iq4HonF{zl{8f_B4Z0k;@f5^<TydOamq@Q7r}^w5Bryevj3%f_djO~3-TM~8I`2> zD_+#l%_pU+e?AXVAZ@s!uq%J7U)op3I{l>cl_(ZZI`mf{-iXAlLZXNp)~<Tg`o;^8 zRMe}~4Ja<dJQUK%>C2mp{G2nFr#7#zKU9`S!c@IEtjc#(4TFq4m<wQibTL$|e5bK= zt2O`bc^|bEmtt3Wh@Nxv7M!nO)1d&WOQ}_3j>z0jW=m_rYq&-E0hUb?X}W@C1_@6u zGGIZjr5Q!K?|-^;$CuIx5!oS%vc>gYg;eQHeI}}#Ck<aHMpzFkyN~9Ao9%)#H&?4C z?KfYi_h>~%q(D%4PdD!II7w264+EZoZ}0<yHi9_Bvvu9KX3vPn4#Q6GhAFz;O_|ls z4e|P#JzE+hZ0uLHwWMss2L?2BwK#>F&Fm^jM;_?g&3Ed)i4C$P6y9MnmRWNpM;Qdt z{ca$?M-stGhIJtyAYt?=Jz+|4TTv1$2Oo$oJZ{dHJ9T7OA1P6xMpZm^=T%CJ1iW6{ zaBSfN9bso=<JV8T3xBc_lx;+F>%K5c<@Ac<P1AKWn^wCZ?4fM`1$}VNsV?ctU|r8p z!0i-QS0wqgt0Y69-HsyLauUEJ*BW1}j<W*84lkySz-U2Ptsa+gwC{Q}`o<&A#^B-8 z<bONSLvFr!7V`KpuiUca<;&{dY{Js}zpz3Tm^>=SQxz7D5-wS8WPnJlVw{zQls0s0 z?u&BTDTdT!T%0XnKsaq*Sq9AHcNmFT0(<qh4ex(JoPt@b1bQJV#{5@+BV6zL^Xt+U z7poWV+CIX!``>*X;XZ0)NZ_p|>M3fu#5WsgQ+mu#WF`9auroNkV(4v$^@Ko6d?_84 z_{kc)`#Rvedl{)pbWZX`-`lTP*14rD|8O_J3wX^=7tSc)>=MT+4?0HJy(36S<4B;R zL1;R`z`EjZv<fyd{@4X2v89iUkn{KlXZO4@w7n(@1oZ2n`+ux-8l?m0M!8-RckE_H zN^hWAe^;reHTv$q(mUO&xUJRb@FLM5KOo81M6Uobw4}hAXa&p(Y7Pu!FzMh7ZszaM zqm85kU7bdS5*I6uOx;e78~p;4ohb-j?SnUU`(_*CQem(JZOR|UGNYt?SY6^fso2Sl zjDGGii^c-fPz_Ob=C@p)+Wz21?Uv!F*20AgX^>1jwZlN&;Lk)rx3@4x%6>S8qnWON zx1(p1J%?L>Vq!x}+^Y>x;zparL#AJg|7b|Rdlpk}Ah`Di6`HALvA#2Yzu6GxD|4hc z0aO_1?7udez$`OF;qbP-xK#K$7E=}%MPH@IVB0(+naY}wv&G5nQK@Vs1^}tOz~X7G z)3&(I;;&r#c`cXt2)w7R4f`Tt$$3Ddb{BA83d5~omrF)qv0}!=xwTwZ-C3}_LcN!G z3YUtf2dVY_o#{2#KOu%UB)ltJ1pQM7{wPe|kMY&eZ=K|R(R*8DYECsyiuwH60l+4^ zUn)cds{@!pp?Z9y%Xyt_nC9M6gwMRhmx|Y)55a2t^QvTe7Iz{63R1QPHl!b$pR}A) z!#eCL6&T6s5T-YW8{V$=&I^)dX!x`!JO>zI`R|_FNmJYEtsxWi%VR}g$IWLu2dUlG zB0D6y;&v*rnh2Qn{??xgRIY<NgN~s(ZW0iLu1x*aSqb$KQ`9hEE_F?J)p~xmGhXJS zk6L)fomNX|GVX?<QpNOJrbaSa%{}Wo6<tIN`gnL$#2mUzT`%P-vziN{edkq8$dFbG zvx>b=6P+&Uj-CaKdQc>=NpQ#62cJ>($vVcQwxPsVDIEookWm_3#iF2U-(T~ORnqjN zK`-){XVxR#k?!B<RHy5F!Cd*2-pek90(3P*``P4fp)%{-ro;|d-3`R88O_GYQ_gVg z9sy&qRK?R1NH2vkCP2^6+i*y(bJ+G^aD5zd2soMgtv8rgd`MlMf|Q=8()W$OwdL`^ zz3V%lxZ!+Pt!%fq^)Ktyc{SC;JDH!-=<77V!A(s-DztxmK2(Yn?VYJB0Z#wyk38=& zS~kytyoar05lcdQC_?wjXo$7WoG&2E-(PLJ^|GWG+HD?+HIt5?rXqz+3R`OFtm-a) zNWwd*I-N{=Q18gqI+lWzeFyK!nO>u>b-F5#)Ze)y`!oOpoP*r2<Nnv{4J`_w72Zb# z`|+}ks^#BoS8KOh&*CBwRfK$Ji6?z@i-ZkJ$TrPU$uTRe=k^uDcz*L#9`-)MPw>W3 zGEp-09Y}ob(aApBCk{FKFbV$o_E{!@Ou`?Q?7ENHV=dU0|2pA>>V3tD-BM?}m?OUp z{sd3vVu+Nv^gOBfV@HYjc;_Qg=!^T`Ipj#&2owZDIoW_+Pk((Luo#N}G7eKUGc3CX z?Y<ilp96+>0d{;_mp8v;el`zXo`_&&jCI#{-&_p9_Ft3Pd#u=P)xd`I%e>zv!+hO{ zgW8Hc)GqEf`dM6+N$_LJ<t2a}V))DD-Q#PsK^#`6%4}FW(uxxz)EFD}(?z1w`GSb% zXUZz?_-=Wen=Q!PXUspW!`PM7v!w6`Ci0}XD@du_z8`Ul`LUYgIR&g~i8=~+6x=%) z*AK2rngrdWi+&&PU6PQK3+>T_=2#F*^S>gvr+JqUnqid@939$9+WxX5!2iADOZ12= z;WP64<N#3-O}=x^i5jn&ITI3^wBJrkMp~|%QXP)$Ocdy7qqLErs(KymZHV{wM3u07 znTV}9#NG6~L$@m}Njdj3;fAa@%6|qVbM82gD<IGmzb%HpRoA{Xe*!oS9bS5aXMaVk z$ukaK3uGeS2Rq(u=z%i0qP<^@>GBdICkBy0@5ryyY=CybnrE0j%Mqy5T#x8G9^C1( zoI9QC`vj`B(P;w2+7f(PCvV~7GAfOL2a4g~+oQS>(gVb|o?6SuS@CPOdD{#L&c?fV z8DKSb!430i25c@h;x)Ml62<p&W+mJNJjOX;w)fTOZ4@jv;e#EAtj<%p+tJKL)vRkL z=Ky%wH;%aJw?s1t{toFe<)A;>+SJ;JI_c7#seVVmYsI{K4}J6j1y_){>h%=a+gYNQ zH)%1)$2420VP_PfuB`U+EvIs``=*i=4$kyZBgk{?fZyL|Y<CJBzh-`=dC9oPOof?t zJPR|sywu@@ypX*?5%rFc<<WK0zi(^dH`_ZJ*xpSFk1pA6z7H%gputoZR|)NJ{Bm)s z;$D=`9cL+o9rH2oe)&RvQ(yBqy*>OB{w1-vZQ$71+`NXmsN#vvzTesnUNO_Nzhb^= z9BTBY2Y`LD-5<vVegysW9bAN+dW;AZI7FCv`&cVT)6QmeG6xOSuNg2m@$0BH*jXgd zpUU_{z{4BUErXfLG{VUno0)fRLU!@u&TF9(OK$^ryA-O?BK_zlfnJUp1lN?~x&>N* zcSH8GjzY5l;jt(u^R5nbqRS|7EAb6+Wf3nnuFO*_Xxnb%d#HQCw0230YNjE)Yu(qh z1oIX#wVcRQ+UY=}fUi@YjAEa=RnPY*1!SKgVn4M8(NdgLr-6&WUDpfOzRo%w!PDE( zT$pK*S)U5d0Nol7?gkw<_okkx8Tf~v^}K6r#zi`a8k1_K7t_os;?AMsi!mqHtfN)y zx?Btkj_d8FFtNftt_vHW6Xsa)a4#pl&L$aaYbZ7<4PQC5N20gW8h-ipc5TaI=z!F* z;4*zX_)CjoYCv*RVji+6f70BbJd)jhY*B(@+zVq#bEg3vCwJxKEn0lh&<5<@8|nbf ztE)<S3`ZF6M4M>0L>kYdS2das9#n-^Y{qQgtxd<XC>j?f?;<#BBh+?0+JN5?#d^tA zr(NA-{IjgYxVyb6-4~yiPMrp-{*wW6N?n!MjS_g}Zg{CO*nBH0=y*@E3}i#YpdaVD zfnoS&N=c6v)Y!66+fRG+nS`wHGx7h4q5lr28ghR%qd#O$pGzVBJuIQ5M&yC*YUN3; zWsDDF?a4#31j{timS(9e1rm`ygR92y53m~=D6?<o!-<mZAAF!*S(>?;?AELFL+Rz4 zPuJCpW;T`if<BZw(4Xy(-pWlQ|M5Y1q^G%9aU(e?gquWYq<geU#AG8)6w%@MitD;a zRsMEd>xZ){@7!=2@bp*eJEU1ox}b|gfVgbGnRZ4^uO+hq-0o;`WhLt&=u77_9(az0 zmTN7N2QcHJ_!5_aBY3!qEa>EPNT%woO~Z-l4oue^B#yU`tYyW${kZ{xXRFz3wxFSS z8s_n<F@}6F7vzJZY%c^;6qlM*)}9tq^~6@I;5+_L=zKu^ONSn~pFG;cE!iiM2t5QA z_!;}or;fVDr>J}ytE@M*Du?=0QmM02#f=d}hh~{_Gv`Qe$#u2L(>1m=2UaDEDx`*H zGA{OA#kC5`JpD`|zDHI+Tw`tuQX!996!go;x98ekepd``T31c`LBimf(Mh~`SB~1h zJX+>y*7PAkV=xVE)vNMNAU57R#hvi&Hm<Sr1zn8@1OBJkvz+OhZ>6SWR7~brvKsdv z2GF5&?0-%tHfDM$y-f6}jbv)9W?qA+o<TB-<<g)%IYuM9<-|!ND!&0Q=pGPJ)ke!~ zx{u|q20701wrM|z_}sWhFck7oP7q0~#0G)4f}6W2Yn9TK0yokA4@Bo8d1w4ux?Yq1 zQ^3sKy7zs$h@7$skZ7p*kW7o1o;fw5TyxLtmpYyd-JI8gN{#X&rns2pclBw;UmX_8 z(P(?miccBUv5l}48B*Z}gq-MOhR+0Ei5Pe~Iph>iu|N9J^p>?I?wM7C@v^SPp+{i1 z%-XV6?36pbx*=3UV**jC5rlYSW1#WJwh&D_O&nUJjo7wOPAl`BDxi|?{kzjfI<<i= zqG^_$Xm~SU?jF1$p>U(OiC=kz>2#-QXN{Ll8{xtIX}B$7f`{<N#JSKspGdCN@u`|* z;XSCGSSXLM6)$ez8ht~YJ+l}swQWUkrnWG1hqjv3#NZy7y;gDY&Lyze;DLYNbWNJG zH_pvG5jFQ41WBKoY!XjAm$=OGZTB&`>ftJ>4D%3OT<9|jtIc1G=sA&-I~>lDBv{M# zqk#f@^CK+45U&y+wmsT;KWR^snsRTFWKZoY`_Z#nw2C2U3QA)<@(Ir*Co2taBedXG zM-6o!C~y#{oRCi5a!mIgdonW9%QvOJcXcHnc-a7S#0dbg)?F{N@5?wdWwF!#C2;CB z>6Yvb;k|R)n)Yn9+=I;?m(}X;L0$aY&R8=DD#U*1!q<0)Ge|s!r0LL<Mmn*i8K2)t zWWAP85a)e<4)7~3?B)1yYwQNt3KT|{0r!p1tw65Fdn)pzZiVKt%vl1~m*pk3!I@VY zm~zA)@nq<u#!dwzFY?artr0TZ*=|dVTMKZz($LN;8NRP7;rS*DWMy0=ilBBl7Us>| z(?r$T-#_!j`czO0>QjG@eaYo;rf1lj=wFjgiQyRBIxWnKu*=;8)HjZWA8ei@Ti&og z{I9b2kCZhfKv@1hCSHE=R)j%?O<=r?kn#qo_@hwX2I%fWb2rL0j_K>0V%95g#gi@k z(dM>q=Z3J(N~ubOz>soR=r@5FJ7~8>)h*{}rs4};q{1!u*pj!FV$MKVM3)mP?Rt|Q zO0J<cXUD)L5;R^Yzi7VAFCiwjZiD6q!235V$))y=4g(i!^Ov6LdQ~U-B{$897`Yl1 z-3{2GW<93yYz3lPgAeLi{H$hm9f}X6By~sKJnDY_pnT(oQJm<!RW(88aPS)z>2}r? z>%MS#TOVV!#K||l<~9G3x}GsM4ao!0TF;ouYX_ZUP&9W$24${%8c^lpJmQZ<zWqVc z{DG|C|5&C^$K9){x%*u^-SVb1yl+iArHci$ZjgHcQ)`uEt^yg!u%pAKpxFX!KVy;Y zFj*OAPFrrjxL%<GKfMq=#afnBF%84u-j~&R7cw>5+0sFQmErY^IYuNu4&84TUb8IB zQg0_*iu@V5)kPxWQ_Yjne8>d<N-454QF1tf<l_A!bG|1x9xyt%PQ4)~E!`N)h&ueK zwT!-a-=}-Er21A@6N+V(a@t{MOD&St4e8Hc>7~=v(+^x#zlf^HlWP`++wF{2SI#H- zPK_$Mma0&k?1)R|*R=|JkDu4Rk*TbdTtuJYGSYoU5)nk@@YZ5yk8D%8@W1JUWJ97s z0UGpur8uBq2m_&~+CWkcWwdt&2idUp<Y;8>kUF#Jffthqof+xd-ArEWrUaioA`W$E zxu~9={q1m%X37*IKL7A-u11YN3H68?Hi=)5w7vF&Ptntfncnsksqf#Q8y{N(&lk-v zB_&9wtp(jOF2{=vCr6&qPaaNnuH6)r2ETF2W&tq?EV>oh*q#`eD~g$)YNQ#gB9~qa zUaT>+EMkM5mW-DbA2!1niunYx=tpi7JS5gF?sQ*pMl&T}TFgS9V}I%x1Uqe_o%pv~ z`P(nk!ADWdfU2_Kieo>hW@(a2$)b?jdaX58IM5cW$mZp~uAi$wy>3A17-CTnATFQ( z%Lq83@wFI&PV%2KrC__{3>{k-3@?@0=Zt!Eu7j%&K1U_;kHuGNvX9R{5Nlpd_B1xR z8WDH$)}N8ClluizD~Pw9PIEH^{ggv>2Nk!Y>1W`C6N=(Y2-T?&zXNvsJvr*Y7ig`u zcA=}Kr7R&6?qY&2d@>TvgpR0sUw-z<X)rBnO|{|Pio_u4nZ=5Pwa+l0GL+UOJ*jjo z@vymW5p=Ye+UHw0Un#fM7W>U|qNhUE@F2CvDZEdQ0B0-Y;-C<Xvdj!a+6C~}&-`L^ zOVYSX#{&!Y8n<V{Uv!|y!nZreR0-fWAFBRSJNzc?S}coBJ36o#OcVQn;1Tgx=hYd8 zCo!ZCAhBo89-GR#<jOE#S1eQb;9mtPMP_oZpMw|TRLFoYkb>nGFi<OB%Xv9_JSXMe z^22Fyh}qYQDH9|%QG*5^D@>Wm$4IUOCiy18mBBAdQ5zZkMWb$8+|=M9h~|$r`>-xi z@Vx*6>ZB}-uPTjP(4AEVC+SULvk|i@D$3;#OT8yy5!RqsS3E6j%xddL)L-hjUFV&^ zb;uC!DXiUsPZ1jvM1?GL&ew{mu^Zkg{r(6K<j{08x=&?jgUA!-RL?}U;em%06Fb0| zJsHP!umZG@wy-CKr=R1Z3k=*RPyICsVdPu~x}3e&)z2_D1N#e?RGO>^(ha>H%hA<k zWpAIE;r&O`>82=Gx{-E`ytFXe9x0u1j+QanR2be<YGvAk9@h^3xaqn&Lw4+4^oad? z^2PIcIepLE(i2`}=*(X$;fZn$`>S7<X=^NZe?@LdB|DE@P}dEV;$tO$QvcaU4hR2% zMSI*YU>_HlYO(VdXZW$0gg>~7xY9m1zD3q!rXXD4_-8ZGRT_=NM_*CXz5Li3_jE>U zZT<=@v$kKzNc;39AV1*s&wa)#is06Fqi*0~{_1c>v_h8497$jlQ15mSN^CH2uw!e7 zRWPrsi6jfgvAdPBwvFv2$sNP*H$x-^Lb`vbsIu*UBD82zk~V<oU4%%&N76pzvVG)S zlw2GkfN4$y{d_=hj}mHt)7@5-FzM`h#rAb+Qb><s^RK$r$rBZGtpU%gBwH+ut}Xiz zDE-^og`G=R4!r`JtLFAeW@{@Fj5@!Y0lAXY0h`x%2ygZBtMom%1{O%?Nwh+{t`(r3 z)xaJ*ThkI#qumn4_$_pwkx*(tb8h2aI^Ywj5PxxmhG1YVmx8?QZ!P1ci|XpJcs^V= zAmP6WlRJEAS^Tr(>{<Zrc%5J2OaVvw@vw!bNyf4))eH)4o2D+^wNHTg0g{=Lxh(yf zC|LzvScz6*SSPSMu3{9MYK63Qq8L!C_g*=e-GGpMmpqwrF<foz9mp&!_(s4WnOHcm z!q4q1`weA}Od)L~Zd(OBz_)o=)|e%Ubc^~M*1c)+jD7Yygx{9mN^TxV5(^9pS{m^q z5BR?W=-*20SVcO*@(o1#sF>30>?K;@W}3KY2HF>8BClSIf9Ef7H+5plPd$STk@}iA zDqBOx$mVNx9Ifjn_xMh>4iQh)EAu=pzcX3lLrR;kGeI>YD%H|z?*lYNe`k@~qVCG4 z`qUS3VTEv$W3d5NqU6^<z4iJNBs;`*1A-7AylYP<`U**XY|2wvr1OG@j{kLmNiu7Y z@rb!Er$>J_TZSRggnsOhbRRQ<aZ`tD4u387Eutds3!?sVd2C8;#(T3!`l;EQPcR&{ zTYv2rdpZWq-1L(#?EK4*9^9$$w+0H)ZgN+R9nHHM5)*!g;lVxlc@)M}mM&jDy{Pks zUC+zXzbDsH7BN>}!CPF3?n6452ZP2F(Mdj)b?7;i%-~*eGaG2VeVL&#Zr%}xTTQ3F zGtQI>LP37Kx2z*SC<+QN?s-%bcij@1F;?uoZF{DzF_=W|kdzx~MU7Twe)L0Xcy04T z*Dfq!H89}4G;sI!F`(3QJR@;XO-9jUqsudIG_}_<9aTLNI>R|_J*yplfWGT;?WZz* z45mU)U+wTp1kb-ErWRqDDErW>EzXxUeD^$(RmS=ZkEG_i9oO(JiS0kZgnx8Z2Ant4 zLQl;F;x>JtuouuSH#XzV!+i+>NU{0zL;;Fe4KJV7iZO|eFgmAV7r%1`DNaFw)q6^o zW^8F-7-Y}PAd3Nvw8`#sKHIK2>F(^ptVOxA8;yq?Iv;HP%IQ@v4G&wBRLzjCQn8%> zV54E7IH>2AntcvCXwT3hVdMdD{>}H-!HZ@^7{sC|MDd;4TBe_!R&Cp7*JjGcv1eIM z>NH?tjO&hJj_kC+%r|NTDc8<^w@a*h1Qw<rqrvdJ=$gJw<d0=cIPHZT;o?(qj8Bk} zk_;9cFUIqk@=Gt(F%%*CdR04~47R|pZhY^@tr=S}^H{}6=9)+Xn7`y9)9xK#beCX^ zQyJfGvuh7DHG1Bw5b=28W{>jLViQXIl62j1q4PR97M5N#slnLBJr&HHE_%`>VN~K) z)MA@qK)K)W&kxA*O>;B(jyfZ#g^S;3H3$vw_;xBH{HHm}<+Gi_s;DV#@4$to65HBT zuUpT<%?GKUK1X^3=S<_A1oS@#38~mZ>Jn|2qBGN&jfXpTmzd-e&I@&(cznNVa0+ZG zRD>Tfae=hP1;61+%#|BB(YE-+Yne{xEGW8wE_QRtyFZc!tq5-&KtSWlk!ij6Bi-mH zNysJ=%I=GqJ3CBAXa*veilm^(BZh)V(yoj}ZYHmv`bZOAw<OJygcXVFO_rmm1iXQH z+CF`h`;Q>dVmO$WCcP^vp*f6BU~|7)O1eAt44kt06elda+v7nF+KBe{!*;Xx0=Z;5 zP}DVRD-MaC(SIg<ZcRpRa+~Wpo&_awOn?K5Qbb*#7(QY?-=D(!|HUF!UzmI@Obwbi z7)ul{V*jLU+<BFU9bZ1zYDp)VJs8@DF8d|8_nz_F1UZYp-YI<rO056p3@VxLc)`%a z>KtNeQ{e9$nC8X$51{P7L5}}~&-^)WJmkpT`=s|zaN7U)R1#Ch|9-*${s$EQ8wWT3 dzx)SR#J}!lKl0^}O1lQUlod4Oi=Ugk{|{HoN;Cif literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231109003934.png b/docs/images/Pasted image 20231109003934.png new file mode 100644 index 0000000000000000000000000000000000000000..e5aa9d700b68beb6b7af000da1f51b7ce6331640 GIT binary patch literal 100395 zcmeFYWmFx@7A?H-jazV+;O_431a}V-WaE(F?yd=z5L|+LaCZ*`_aH%n`)kg*=iEEK z@7MePdW@!ecUP^FRkdo>nv+O16<JgyLL?9fgeos5^#%ljMgf7K{J`+Qo8u4(T@VOG z+*VRjO<q!xT+PMlt*yNk2qYJos)L}bF@&3Akd%-x2@RG*{EkS;9gu>d589Wm!b}2v z?!^Z)cvz};)#sT*5w$RUS%9jh^1$s|#go!Zaj!PjS^XMNc|Ux;d%rvG|IB}$%egoH z-4y|JnQU0ihcE{s*GXZGL`5`>QC2Za$bm*;gST9VDmFCE$-p5Yfifkqe>PrSfsH8t zzDquHXZ`HY{Lx386dgoOxXI;5%8Iuc3|iL`s-`9beTm`C{m7bTrW@D*3lBb%AQ)F$ zXCP3~SpV+w=|-2Qml;&7)@&#b53<uCpP*Z}5<{&QiO81n`3wfR!}qo~Hz(g>6iL{_ zIP_wSTx8mc{<3^f=5&xt9vQ>$j%pr^R>)&h&Faa1@-N)-PhTe9&qHU_Ey+xp)LqOn zTXnQnMN2nh=>7hsZjdgbp8Sb?d*nBT41MPGBy6a#-Qb8tPZpF>ME1>cCnN%u0u6UZ zN`~&X&drPs!MsUg(ze@2MX2{Z2J5SBxITIZ9(kGp2H($@`&c}RL%Dkj+kRH<qzbjz zx(bg!GNI$%kZCZE#;68mKvzo#vaw^Cb4QSz*KBpC^5i3PE+z)^VA+;4`5{MGz<o&o zg^Fk=upq{1{Y>B8MIFamN}=DDVmNzx7`;)G_N&4r)gcwlLiUg*H-C+C0RGc2gEAh< z3PyP|O7ejQ<8?2+yGX=2j5&^la}*z~zHR&`L>CFmHiF(tZ#d`SYA<sU!vrK>A)_oZ zl5Y{%tfQM@(u|v3>4D%*_`m?DuT_PCL*&TdrT0YdH?qIb;zI&qEkRHaHI87aq-|kJ zuUMGSb=3%1awi+ZfHoZv68W=xgq9(RSW8=@m<T12P#_;(NHDP%Yic|es<$F+JO$N5 zxF<`w5WW*ydCimm1bWRH0j?!wN{rhim89=v6224)br@D~WJ43warB2R%+mw(GS2Z{ zVT8T2m7LR%Nfj@tCh=e7%bC<nNe{1f@F$@zgHxO3?%DC0aAw_lU?610XsOOd%OJk> z%1LzO>)@Of@)7NR<`JYV+TR^x>)}P8>!<`1)&H>7h%WB#CE9t|IZ86r7(Qo^NtfG7 z-o8b@d^pN|l)SpFLVaGuGKe7Q95*YfLS9fWhhnS3)}@+{B1zu(Ja?(v-U9!<Z+L4c zOrYEUhRCO;MroISPT-QySN&oKxp1g`DnM9I$cS=uaMZeLJ&xQIA|*6{iDFG_jR&&4 zkKR1Lq>*WNB5$c!Yrgddt-G3=nywFevK+yJ?uFJ5{ci-VdqNDt89;mJ=U<bc;lf8) zU~f{@!ks>fEO(3sqGrW&LJ(Fv$zTK7FyJ=DIWoZc6CsC&(1k&nrlfRGR;C2HaPxt& zrpOCW9>I@!P{eRWoq7;NLnz)(;imU3UC5INtAP{Xpacv;3E2xw>|U&D*(^+&&1hH( zOgW~cn6H!s5#U5h&cs_ef;VyHk~~!0gCg5(E=bJ*byS`SDqj)2V|^spQ=;thWr}eG zu&ll?aS_ML(&iETdR2$PER&x1Zqm*TPd`3Kg7q`+B-#bs&v+;$oS8l)c7&M7>S{VB zIK=_#1^e<>Wu2wf0_BJzd+&4+=A(UkBl$?I*U=zw;hTtj=(#}?{dil4rzBp&t3f6` zf@dNRM1eAF)C<^cVB&6F33xMx&mn5!3o?9Cd@ySTj@^QkiN%U_H19h-*)ubwv&0RR z3{{sUh2-sNJuvU(sgp#8a<(O-D4peRzhX`6PqR!TPHVm4-4Bi`jf#w_Rj5*kijpgk zE0C}%8g@=CV^Gx+N#-6*vt)I7m8qJeVyv*L;7Dmg<C!d~!9_p+icCT1bu>qOP1qY* ze#vH4@BGqIyTXGK!h8nJ?6MXa_iqQ@b1HN3n#`pnsmdg(sc+KN8Z}hkoT#l$+Hf&` z6lD%gQ#Ft%`<z`U{MA=2zl^`sdG^N6b(Uf7V6L+CyC!X!L22zQZ7E)<PBEEUNBL@* z_<Ys0={pGb+jp9F#PdxBQ{Uu&5El>>WR^ASx)$xijalncGc#6@Gq-D3&*N6i=o`7k zII39BcwgLJR9tXgI68c3sOOOtRBToH(CG2WBR4KBu1w|2I9IkpwuJymOGafXi!86K zXUVbO%BPmxFalHyRBRLju5!nPIkS_?u*2I!#0!PXt6wXV_g^O_(WfWoO)A&&o;yLj zRh$v*8Fp1&>oMXdkl!1tJ>ETv;U{E%KQOrKIAgf8%$oYD=Bm~P7wCHB?Ca)#)v150 zuB`5GPCHZB+Uggkal<yj{ye0Rj7>8^Ab^5P6<!@S)%}Z;n+ugY^`j$?1LvdtTZc4L zZOev%qd@+?EZZE%_UX38wu$au^O!!RX#MEcG)u)otHK?-5!bYnit>u2a$H?*UE$jK z+Fe~d{U7>kjh`297L}??8k!vy>#TmhU8-#SZXW)#dC}^p)=#4b+21R_L$3~hFUexa zc*SAF7Lz)U1Riv{&_Rmbf4R-N$3U1|>>)n<)8>}LgF93cu@Af3yD3|BbNj1w73yaB zQ8L`I?|<9xjk;F4wI55kB6?(QP5=5cJh!T~-qLm1K(yizvjpAvw(;9B=`q%|z%?m4 za=d0dL%e~K!&@#__VYH{F3wKZxIOiWc;jQ^TjTrhPk%g4$FElRAMNWdZMuF{<hS~a z`ZS4r@)htQXfJ91<Rkc?^w{J#=NJDl_IUfW^pIO)ucudTRGto{0+kdX33ak)e57}j z9H?t5XKHI|kf5z5G1-zA-u1SNpsT*im%@>PQ$i&SOQJ_IJ$!W&-`OjRP{kxecA>l~ z4PxhIc++w!i|K)x6j8|jE2D~?v41(fF6Naqk5nL?%4}3I!qohf#+UeB42v%o3>G=P zaZ%X>A6Vi@dFdUkms@WFZVJw>vFx$FB928KL~dcf!&;+-qe-Q8k0Igrm|svFf*<PM z?tk@0!F;$O<;humOFQ<E^n|C~@?i{d9=lMviEYZ%e7x5pd6w3hmPGFLSDJ!jrN{2r zO>Niv89rMrTVEj_C+-utwcL)RHL6q06y%)3`>*Lmq9dn6x`|WC`{{a#i;R}YKM+l< zLf<-!zRx8|{Vx20oR;2NwNk;+?$|6bjm}_}W6|qR-Oz9I56+QI7EwP^v^4IhH<BE@ z<yJ%5`h6U3sMZ+j6Q3x5Go3OQGu^OpJ0Aqvew>k-(Jxw3HsN}-HG^z8ah?*i5sYyv zTaSNQ<d5clcW!U#@$+bxf7dl?&us!Vv(<vs%J`~nEjlY|IC^zl_2ZhRy{1rO(_wmo ziJjuC0`==gTrbvzCJYlg!-a-HtEr#TYYMjocq3WE48!eAyUgu3hs7p89t5hWedU+l zTo(|fVWvl>tr#9R`p7oF^)~bV5yj4Upu?e^R_W7fH(iR1Q;9>QqoJ*+<5?c5JJU38 z{=25$WZtT>Rh>YsxoEh`PJQnF^5Ig4_r|Gs$)>K_eyd2iTe*=p+`jT#LuuuL#PXY} zouT>OiakGzC+*rXQ-j5ZZ%fikf*!rcHYI1pC5yIAuC~njj1|8Zx&3~mt^~Fc9TFe# zoJ_4~G~gYj9{aYly048rZrp!DXG5PQsT0z5kMJw5BQ41_Ui*=-I60NEyx_-o1aVFF zocT-@C)+^AEv)aYw6`$5m9o`0fS~d!=a(qG$l?cvElr*Cue%?L26Eb0v1X<{XdXsy zYrCvfb1kw3omclBrjU*C&`d0i?VGm!O4{ctE+<bMJIL%@oyt0noSV<0_EHP4rhX56 zyE77YXFmP8c$jsV?kKft(~$`|zp6NE6mUFu5^YU(-J4qpYRx?v`>xt#awoPW-Y3}; zKIgyiR9)2beM{Hc)cP>LN%p$M%ZQb9Pxxut=pp3l>t@N&%t!0-iMT7+YeR35WAAI^ zv*?NMul?<w^e(4&ce*+rp6z}UE&X^@_+z(zxygIy)X?GXyR=NU@_cG^+&XchDEiBP z;Vkj?Y`N&Gs;a2!qr_d!ZrSf2g-#o5$LQN=C=tzAl@B_gU>s#tg!M}gkj)Tia^p6J zL&f<i8BfajZ7S7iZq;TC9qTb@w(I#i!}!M26*=I$!NwW#L0LQk`A2xMHd-+w!?1&O zJ!QYj6dXz+1pBDFk7=LapOn?J`28d9_izU_jk+d&cYq=Se0-VM`rCjrMU<7U{99#Z z5CiZG2EjrRg5ZEBDBu=>BKr4P28s>@^VfT55GdRh1pA*nDnR;jB>?wJnZHw*q%aTy z@CysLz4D;{$qkK?2lLM}lppX7B(5PTFAt;|7A{s+j;=ONZm<jz8^8-hh@74)2!#9k z<%W`fLwyR!pSRW2b<<T=60mS`U@^0FGPh#!a)7+Z0SS2t0FMq<Zf4|O4)%_&0$#$D zf8`JWo?l+GQj-6b#qFIirLM9Xxulbe6*&(J8w(qy2ogCtxsZ$HTY)!HGXE(K{1T?L zadU$Ru(Eo3da`(OvN*X|v$FH^^Ru#XuySxP138#oy&c`myqFzbss0x7j~pp0R|^+g zh?}jGBl(M5Gjk_*H(^T3mx}(q{%)t0m+gORa&-Mqw}1|^zI<V2XJKRgS2j>o=;f_| znyr_Wy`Ge<12ASl9U`23972EP|NnjYZ;k&`Qun_lxjDH0x8(nP`Tv&Ga<y`ibaDWy zbQAfny8cu6e?R`Gpb+az&;Ms6{vPJP-U8z+f+WQHug*k}3VqC9)J|+GrK$;}z$E+Y z>Hz-I0ryJ^+@WiXR6iU*ATf}<l(?oB)R7TffY#i3&NYu-OCkma5j%$T<6>y+%1SKr z6Z4Twm-eeyt<spOHPzMCp#6kpxQ4Yy|FyR4ft3N4*3M(3R@e38@7EWPtC9S!Z+E4j z`JDH_e9&<LRO>HErvgR<Usn~Do6sO81eO>|wi8HRLDAy3QT#WPSSXmUON~N`wClfl zvP@5T{*v&wARNkdSjkWfZ`i*C{4FP_Yw16=yd;_t0oW)w65E*nspKU=gm;4ZrzHVY zY822aY?|Oi*?${C{L&EA|JRWJyAiR=G6e^TQ6@%EPFNdH+0-fcMQ*ocmZaja1e_)H zL`6rxe*Ie7ygDPSLM6L<CwzqQWO3MV&TVIB@97_9h`Cdo=3<~+v1euRv!`>H7-VTR zFZGW2WLkUQ>U%Z$6z;TQqNY;dm$#+PB|85aE>o1=U>sTM`A4^bA0_ho5#jxG-BpsL zrKOWTer%cM=-yf4JlT*Je#m;TpdL_0L+|*;REf#L$jF$LE-LuXlzhg4=2l@_pdLcs zm9i~+D1{EduB*PQh^hJ0;6ji-alPyspXL8_JN;E2`!!Dz?OCewLz+LI%FSZ;ZxM%| zTzWN@k@gLXZ{O9yncv>7{4-&T9buoagUlXo&ZfVAxbAIytvVhVFz1EO`8LMBc8q7b z&UVHn5|av-uLKVlcbI=Ki)zWK<9n9x)uNSSB3q8p2J@?3NxaqeDz9BKzdg@C`VID( zN3|0oE<LEca^H-<4^yjgSv+t3v$D!xgEbkuI){>y?Q~hzuh;z3jXV~mX;iZ4Pzkxz z@Vl{(OE<eYM#nyKE4Fz2W?*f<`J&RhJJE{yI%dLpb;#(~QsXxWQNI84Q{*pgGAgD) zRKCZHnVmKN=Q+1>Ph;a8CZiV3pN&qes-ll>n+6$spTkK@i9<$5mFVf{CS3$Pj_Be= z?usp~tZYd~U9VR>(?3gw+hzA$nm?8wNfkW&yO3{KF*~KSsL-(U(p-<5_guozSG~4k zLD-jssj)-+RX*qE=fPzD5A2;G#HJi*o%~?@@mBt5Rnfxx`;(4f7NZte-LrRw{T5kO zTdlX%?dgUt@}M9}o8=~FHpgYY*pCk+z-A)8)Zh?&cX^0_F8WY4AHJh!#3YJ=+~u+4 zP~>h#nuflmp9L{`So}v<H{URdJ<wnxDGXMgAI>MH^JURj;1_K2W49aE{4|bx4zQF! z%+*-5o*O`~lUh&O4FueN<>_%`EyvL2cu6$<+!Jg@XscBz%6VT(?78fW=m<-5@Ma^% z+7@4i*Z0nC(K1<i)_*vKe!9i|oo|B>f%VnVA_Ka39CXh<6PbvCaT}S-AVrI?>-iWj z?eJUTo|uW_e<$`cVW1r?KHr&h&Gxp}W+d(K2x~`H1`556*P>N=1t$FRPp_xjy;NOL zx_HCt`**3Bd=IBR?we2hMY*ucC{VKG>MVyn^1eTeJaL9K7Usc+!|%fysmq^aYyuR? z_p&{6PzX4rDqD{Qn)eGo)jf?S{|G_Ew(JamV!%seD(Zr`%3!ozuYPcumZu%kG4Xw! zE$C@X1wH)ds`YP!4w%t7u%=*_DURR6*?{|(dc=(D_m>AlU*(gr${^7Oi-HSRH9cs8 zgPv=?MZKMe-#S=;1u?%Dij1cqBO@d6mfVo#yr`362jjTqkR^6vXqm?O)5GuVGv+L- zHx9|kA3Qu7)M)ahqj3qJ7OiuK`tVGc@?~O^cE>)Ik<AcRCmJH`_W8&+CA?#|nIxyh z2WJTWy(I+JqeCg_&h1v||7gQwH6|A0W9tkl!BbP?hX+f-%Mv?>9B**4uqLw>D;3DZ z5fiYXE3J10B9Q7T$OL$&(jtfv1ds8q33&mNxgNjF+G@CtZ(&?bFANxe!|!6$um+CJ zR-mpysb-p5Q`@8yZI%WWXbe@T20koxr5uWl4fMZkn<hIn4?O!)RDT%*OH22W{li<5 zp3Ch8e7|pORPkz7U`VKe!?@qCc+n?aT6ZiYYQh-Pb<SBb7zj)qTG>x<oamF+STt-; zm06DhHzi|hdHns=l2hvB4KR+wNR=sM+mv<o^Upo#q9}PZ1g0OPBH?&0AQr5QlK0xH zFOwOxoM3u$x)JGSRp2c8*T9s*KoP~4Qk~2V)t28)e*5C=?mqm7D^)g6zma-SwJW~- z{#I4^GNop1D6L2m=W^U3lFaW$oDNoA)L65pJcf!fcM0^$=3yt@#O+hSz8*a52bFQ; zkH`%EVo)+R9MlNu_l}nqt0`K)<|{s>Np{I#pq7%_MpoFje(G3>jCRms(ybDU<uh`d zlGgv0I=3=?|Ch}S<dzQDN{Hnhjh<+m$F<%nnoGX?k~@@H!F*ZHcv-9+6e!BHAUj>E z#n{yl@-zuMPowaz7*I{F;rso9vY1=?qAbb@;p?nniHEzxZ#7SMhwn(!oV-z=yOCK_ zc-MS1-i~IdD-2eDLDJ2)YR_}CT5@Q_DRwE{MbKozrYT`$SR1AgX>)OPO*LJxEy~_5 zNH?A~y-U~eS3L3jYuM&tq2erv;~hpfn`(KK`pXeW4*Q(bFO?J(6@3^U=fmF9Flfq> zmZq3i$+P(Q@1*K%hhVErMkb27=vA8agq51hQ^~odwU;+-K<vbh+Rn#Ial|)d3Eyn? zx!8~+{(+PDLb<5Umed{9R-Uiv;nEO>#1F=4qAm)w9Wq;Roe-|48)01jm3)YSmhXYk zjPv_veR8$MfcDMfkoRpXl^PWog7Tx!+K252-UlU3Q@D63xeBjI60HD?l=5zDuaq`P zA!M2jkcM4z?z=66Kb8(#VXy0|`&WNlIPP$exp0$tZ)0+^c>)HZQhR>mF7({EVl)Yh z-Kl45PRB%R%d7kZp2$9LOR$GYh`yvln+jS>g{`Xcfuh7u4k=*?-q81xD3OF-oCmnL z(B>>@i`tWgNA2$M#Q%9lOJro}!^!uZsva~A=%6cna<!6dN`6+Aqw~Fq9~B8&wr)%_ z0{t-PLU{(XfPtykccnIyh>qU~8*gLwb0N8LG^>M`pP8L)zuEod^hy+&kum$8ANm;% zx<DSP-E2~&RBoS7KCpfrr%l=iuAPI90-O@inSmS9piUKo{eEC6i{Et?`Zus8ev3wy z5FdZ{iO0chG=tx@FwTTn*5+r9#XxC{^5{2?xGkjL(`~2S$Sv8eKa4-TKG4X#zzx4m z;gwm`{oX<x0BIk6_xyOBK9w(9#vrJ5UIv4A&(iUYIFR8rzV0i3djXZKA140a3E$Mn z*9n;iqDH%b>!hpta1BxxF__WEi2VVJRRjyAvkM5Xa6z^)Fgspu9&Y*KKanG>RX;tw z;M=(3f$ak3<JZwP4zj&<$XY(>c=nT5Rn;NFqE@PG-X%;8HO&v(kzo#V_O2+O!Pj1H z_#8;TI|kL4O;y!E(P?ai%dYkV3?E~Ul}eeHX#5BJER#+OGo%&D{5nbZ=#VEYF?o<# zKTao>kb625-KsiH_)7ORQ)Sa8Qu9`vpth|&1ASpP(P3xHDM+YtzIl++(@l%ye7)D< z_AJwG!#c<Nt@&szU)e|AElv|6!RDs>&1lxT$}C#^e#SQGY5^;+k6N;M!-(+OfvBOP zE=4NYv-42?hWSXhhG`aCc~b?f9S=35VVy$z8R!#k<YrxwSAgA969l8wwq@$vWSW`D zqQM}dIog&-ZOua|8I)Pc5IULj*X?v_&@MvB=lR_27yX?2{b6K8^g+1aj2yH3#Jc_6 z^x`n%%p*x4w`5*SJ5eEJj8Sd|_mA?rdQNV7C`Z9wdT2S@jYy|$x&Rxsny9?f=DIDf zJ~)NF@oaZ9$)G@)Ek13?YvnFT9OEn4@WuB#BAQ%rDJ-8id5JvnYxQd1wsh)|1W^bT za<a~+FJs#D(if%pl^J;Mj<F|<51SeH#vAJT!JKW@wi3#K)^##_;>+w<XZJ!uxut5G z;npWp$fEBz7azQ=iNn<EC&#Vn%HG&emkJ<?%f_OM58=$(>xQ3dX^Yf7c5+f{&vh|a zfgFQ!ZaX=C>Cy_C1Tmy(R&Wt(r-{x?v9pAb2BY#Wvw=RSt?8tV_Yem@qXl|>Lie&b zS8o4hg2&>++xq-xVju(iNnPQ4FHH9qTuANQG14~J?ZFhEbx`tkzqq}+jRX;G_u{wX z+SHzl(MI`Xno_j(mRojoW43m@PGWyhWu+g&W4Bd>%2OKe3<s<0mA&Wr^@lNXF}sRk z65U5DEO;4eYHYNtalzsfP}$WRcO+gkk>J=u667VQNHiS=DC2J1q#nL5i<7F^-iezX zqda>U`){zmcNbHCGRU^{2SA?U==q!1QwhmC7H3H#=pCFasPff4**<@UB87UK0k^E! z7IuL}Q4n8?aU40yoNpF&hN=ZtK>U~a_BQoJnFHDyJ|lEVfc#W@ZoC^YZIs2?5XZ5` z-8VA@Di0xQr>QT}1^x7-ngi?!;qx2z#LD&-hy#Ri*e7l0DgiSPn2c<6@>7x+5<wob zqd4d0oAsb54>Q1H!8vNbKZcr}SJZ)ZiWz~q!2iZ%?QYea&;f4J{pr;47!-^qK-ctm zwG{k(-|>u0Zc4f?ln2tbb8ib*3hUpxQGoGS=RinMM&?=dvLKmpYTii$Es;a1V9)=# zjV;Rd_&ASkPy@By6vS@P4=W^>u!F6NrS%}=H?WuMU-^U*tl$GGYw04e&id>pG@6hB zc?wv3dSmfHZ*9-7EL<!V3xy|;)c0ZvQBqlkI^^W&l?*jLLiZ|xQ*Q*OfU~~emF>1+ zRbma)v@SNiW#zB^g^2P*+BN3yD+uVM<=I$;+1R%DVHJUIPDaD6jJ<bKp_m10C}yfD zW^yk%J!jQr>5E|R?Vx74xzT#MotYdLa;;21PzTWOgQkbA{5<)xfddnFpjZ?7>zwGR z0VHucR%9c^Q{r})Q{$y?r`IfSG|f$HT(9uDq0KNlHfN>wO``Z*V!G6?p{_RPOi3R3 zav=6y^MxvHTyl7%_bC1<AGy?Iy94`=`4(N<0+*BH3`X|`sp3({xd<Tk7C8xxNTw|! zY;mD;5#DLCY`Wg%Fsv%uSqXZcaUH56x0Yfoh|D)NqzSB(?~@_qp93mzvwwMGu@1Pp zxPBh4yfpW1=KEst=!_eW#V^Eu6NJp77W`hQFMTH|ZvpT_=i<*{Mn30%7Sul|Aj8w+ z<E7(U4}ftK4|jmXqI2K(;+IE0sHT#u?Qo#HQuz!bvn#?QRH7gFP9K(8YyEI@&<C*- z37DRJY~O}(Q3n$I3duvehAANkjQdg=saeD|P&dlDcs8qK_uA+2@&^NQ7le^4`*mWN zwdV5s!wP6<nF2RGR^&#(nJ@XJ5ZX}IeXn9%ErI<BU!D;InB=FbIL)!ImRw3&$O7un zxv2$;!~G^Cfd|r{O=LxDoRKm~nZeni=iwm#T6UbgH7SZ*SaGonuD1M&tz1VjZ6}AP z+GPsIaHriHoF6fA^76@HV+TWB1IG+YM?VRMvB0VnNQ`lU<y`lIzx&iG5<g<<df7bh z5pW4TrXfsS9{y0R`d+d&ctiY-PWQXz5SFmzM86toTX>{K=tzl~%pyx%c-@{vGi+hL z5{^{^5b0TcgYd|1lGf$SrWY1y!DPjZA8!2zV!t`mol>!$(JN4!GmDhJAsA<3)ao%8 zZNWIhNxIWp3@6d0VrP{h13$82S5~2U6|;8?F|_i@;X~P!INx2AWXfH8KgvD;)?%c` zSGe@P>r(iZ)6wGtk4Bu4;Yv5CGA0CJcQaPQcvMZLP%D6i@i*0X*p46Ct66qvT%qBr zk&;vv8cR&7v|osELJdJhv*(?Im`c`+(Cnj&+=!uPn)h%I)Y&g6Av9#_$JJ@jF~_ag z(%BA>cxwJeg231Lq?zsXxYY&h6lRA=#FnF<o6Cv-2V!p0t(j`fTF#kiYQapz9kqbu zG$K8`=yyBeCrruNnIVXD)>`%EH^b8*GxxPrYS>`d+d!cY_u+qr!bKGom=r0iHRU4{ z<mlcc!-@xlf?%KJgicEuTJZ0Mzkv`2aL)OqqcmI#%$A^=-%Y+wTFnr66`F)3LAhA{ zZN~Xc(G*{)uf{=cgPqq6@p%7~{49+jQ9R$VdTkK&j}J%HvgU1@3vPoH;lH*=`p~ua z1z22AdhLt`FjUt0wq(#3TMtUhu(ZrqcQ8><YR|&E519=bX5lafM6tl-=y)2lQd>~| zW<h~L+cJ};Bhu&_`8Xzb8pVQHyuUY2mogDZv{bu<wH+|Cz9s86O;wQ{#xWzl#?L^A zq{5=I&UQ}|x>~RxOm9k*qnHw(Q-|1LtsSCk1-}?BdpS3IHlAi$9qfD4Zp2(%RC)eC z1ABd3ZnOC0nBvy4X%lH=Cl^ILP=drnU_^v>Uq_?kG=)ku)6$Rd!wo?SS2bo+dQU!Y zd$#(#%A<FN*s$Pm)1S5}*;o((q~1MWbRkdxKcpjYe~cZq$BXt%qEhMk=@ENvRA^Z7 zo%hWOW-$wFw?oc^c;z5J!YXs(GJFyZsu*ovg=;;@XMKuHB;CYrT};cxGu-Q$0R0<; zV44WZ2V{=ZF?ITgT{-bx;^vDuY^!Jz9#DRP+!suR(*Zo3kj^{KfjE_Hf&C^ceXKfh zNp1xfnD-aI67fyCEhuR{OI>GLm<HgCN0YZO2k7kV7WsP563jF;X!io63FDZz%@;Dd zPyc}7=YRC`t@3X?pHGM?%vPaM>+`KnRmaJ&B?PPoC3?@~!oqN~-+VWe`gt?x79%+z zP>aIy(Wc(>V7A0%*?C}pVeBSmpe5OK-4jy&mC9K>C=i)X(4+G~-Yp@bbKdJq&d0&$ za&~Af1vbq>9zbeeuR{p8bKL=-_aDmw<4iJoHy88;(0-nG9%_9#haCS>11wR!yIAx) zl9AQ2yK#XU6b~#%lNd5l<DU%<WqrCvrLAaMkIFeFzr{P@-5NAh6yO%w_g%Neh73~R zYw}2GM(E^VYj%)Nr<Rif^vx0qrC=A(52-Oyx1#gbHV?nB`!Kfib~g5Rn$ZnrvFfb2 zx7gP)-$4YJg<YWPfG{FVknlrq8tmd_-B9OH+R`gvvF3?ks12|gWI?cYbUlDD1|lqy zBC|e|$&)cLYZwZ_7rf@2<;rzF*>Oh1q;}tXntqx7*Ii<*?8`~uc<wYj{|_Rrn?+~B zV8H{4*sa(6#TcEM#~|k2nkQ=gLEHL<o)dEdYCbtl{H{)E++4EvzbIDThY<&#3X!^y z3j{Xh2_tP0R-tXPoqiCx-A)GD7Rel!-WzpAHkx>DN({e?{lpTzbv-9*noWa$vuK|+ z-`QLQ#7j>0{RpmWY%)Sp9BOL0xDq6yvdbBHnBM*3o*D!|nAcTAF>={Jv=7>LjgVQC z0NdXawi~RQ%h9df>F57k;<R%~kzd7B&Popz0gr(=Y^4?ySfXgai?Y|~D5Rsr@k;V- zuplON26+qW$2>8l{KaX<nSPfUNoz&wWVTn(crNlf)c6sMw9<qbTMUawfZ{vuk6RfV z1McsL)A_2CY}UIYk}q;T9GCpj>`k&rdE}|{?Q{-F=H9`}n<8HpF(r0%b!nwy>M`9S zhOJ1=SI6zbU<o!Ld&{<8(YT7G-}rhUkcSE$1wYSfk_C;G#b;Ff^i3l*U*L>!Ts?hQ zGI;a)4-+YtG76QMg#Dm5jpstY<$Si4i()q)N^d+dJQcqEXkiB?%C=@xnLg~iZBQ4X zNFy&@g5(APl5kS#+pQgbY-;i(654kjQb;7#!OqX|Z}odn1^AWS+ca{5vje*0`u%EE zx?3hEvZ+o@$T5zQe@-Z5AY!+Fq;u+c`pjgU5RHhv1j$Glo$^t4@cfF|go;TEFJ{__ za&ecvG`KNv!d$^?!;t9aqBCelr_6?*leI1Ad0hVCRERm95wfI^XJwdkDCQ0KNiMRe z;PW!fga+HYC>|N1`=eS0I=N=XLfYt@^7p$V4mvJ`j!hfzIB|86sh&3S#nsK0pJmhJ z2OgS}tVxL#nVGHH_#9o#3)#Lp$g61wrP=W}Oskt>5fZjQsJcuoh<oVrI~~kiXq&!w zacx&Y5@iWcToiuY{9aCCLxYLkVket__x*BSgDI~*5x-SFq}q5}0HWAEpcYzv@RX-M zTb%F6W=Cd<Y!*8rZSm%ksB|(wA5|>0Y#2@J6-7Of*m}`2M@AajQ6=b=1HI8(WJX?R z99UDv*PRR!?pc{e$|-tqb5~3UU}*dJHn#l~ANCxWViG*b0={o_bi={JMj~2B&J&XO zn#hO!p(jTD$ZG~JeWpA#+Ms%c1#3Dccp1BC+rBXKjA=9&2WC_0?9L1`O@r;5h)BIT zSY{E|?vRo#8k!#<LL|FnP*6x|B^WKZ6k~c9YUWKvw(UOKqMg95pzZY6_4*&iGi>F( zTFfgkeR@8voXmX0rIcvQT<vxSRRV$7c??<hWW@gbg&K27rCFMc)+@y>^8WVnHkoO> z=Oid|9uOVqpGTiXwWKLvOBfP~M@n+!wG?+%ThSj_2H9+c@pC=!GkAaVg^+*|`_gV% zomw~WpW0}^2^?kWI&-ivj1ys9<M2G02M5#o)Ph^XS=`3<$gsStUipN?W~93vHFfU@ zWh|%{bWl3m8RrtaZ|9|iyLWDDsW4>7n;!$Y0zw1LzuPoLCY$@1Gf8n6k03_haIXEx zj$V6{>0dP(bOP<3=lRpBi?cXXH|7d2L2*bbHsDR1#VcBSLThMVO<F<wP<UOlGGQ2* zx5VwP8$Ck_*mSYP;@NLd$;_7CIDBV|!KTyRfwDy8682{;uY?(dw!zoFSMU*|p~Sq_ zTuA!t3;)xyGfkS36m=rh-|53!U%uN~CgQtS0W%m0lL1W9AhgP#2BySVhzVwsEe<XF zg-{L9v&JxdMIUj?9zYBkc7sFh$vn7K1$hnRHhWNpfVz&LxHw*sVM!CmH~$Jg_`2&m z&cA1~vLDZkJoc&oqm5A16$Rg}q_2j9hH0zRq5gsFX*#!zY4&Q8*npk|0&Hq_pF?ag zx`^)et9_m9a;BOwU3fU(NdoMnI_@X@iB8O78CbsP66fohVL4d3iS}~*cO7dC$Hkoz z5<|T791CG|ixM#%X?Mns$#MM~ZW*Sjk1DsYcD$!51Ta6b*L6Fik3QHDnQqQIN0?<q zaCZRFdV@y2Omw{yHiq;`SW{z7y&@1F$%_jq_gQ>cQ9U)AAtpt#^J|&a(oN5!U!1&8 zQ7wCd3s`e(d!GKVPe45)5jusK>UNxKG`Dmkr9RJ;<`BU#Y?UB<32oLm4^-F;gxn51 zm>T27M{P2fRXz*DGi}!SX|~q6c<s%@;bt?8boqEssk;VWZt-w#RXwFl1#HkVj-O}+ zh-K5_qe$|2d6>3-@^@cZ%&Q32r>&^05i*fA9m8B_l53^SQY*$xq&CU_h{-pv7w>D_ zm+3jisN>4NJ`*9eP;pvsg@H2v<G17ft%|h;Xw7?(dL%M^9G7jw>&ia4u+QuP!tcW) z5o*iV?+jfeN-}eniI>aF(o;;TLfP|B&a`W>!<oZBl6-=)_u<b<w^!p?S})pR?*nuD zT&U+AJKBj1M#y>f9cPv|TU=}D3sh=q7yDBn^t+Dm@`!64{P?(Owv~6WC_nT&D(JJJ zXl?_Ro5r>rLuXp;#gXst=CBLJe9(33sj-Lm=u$4Hj?Q^9&lU|A)@X#{kawLXQ1WZ* zt{iVePH_9#$7l>c#W17aEpcucv|nts_BC3Uh0}DC^*6e;&1B}r7T{I}eiltD3N?7& z8h&W*t-q|s6Diwo_E<iS!qy>0?XPPAn`KHDI7w)u%+2v`fhnG(OJJDr`Abe9m6{QF zL5M)W4YvZXU=hc^Tg}LbTNnAyPGhQ%(+%g=`RjI}aY_?{jo$VNzX`3XSePrbjkAG% z_^`8PChINup3HPiD4u40(v8*~i!C%frUpv%qS`k6wdr$y!?@dX73+QPBE>6SQO2e2 zeO1a}!!QVOPx#qyJ*xHi0#s~{p|f(*wEmNKVF330E-bgm1NMLpnkO)IG{yZD+_SxG z9t#D4TN~ZgKN^tyjeQdb&PjD5hRwl_C-eUUNxCBfIP}5vx8G|A{{nn809IX21IZcv z2em3z1kVCUI<T!HqbquE#qz?^$STUO&A(p%AKC7RfrPa9Hv7@qqhaV|EC7bqQHEWq zSkZU*AIWOgn8nUPfqTX0)I3-y_rDuWB%GSYpP-*M{()vY1p>rku~D|!)~PwYf%x!t z01O(P6|5ym=SbPFf0{Qd{{nY*HBig3HMzdP`gxU<V(&s3Yh`qez4V^m-m>v`Kny=L ze89i1dFbAFI(lilsR7o>_v;)-`BPds$MvV$zi@XoBFy!#O4tK$qZU`k+Nxti+m^gh z%#sJq{5LI}Q5Zj6*dAwkhn?55MUS-JE(*Vh_4fd#!++QTVyNVuk)l2#Fl+mKCE-2x zN!Gev(0gCUM<S3vG}Of?%9{6rL6@Cm{nb9dNyk|Y;|k7NsS;uUbqz(_{0(Vo#eit7 zUC(#NlAYRbWzh9&<a5lj1`Qe=nN!YdhO+#!j$*-JY-lpyi$oxbq>Ts;b87wFPy>W@ z<=?+=K_L;)j1xR=>Sdo-y8hj`X7{kXY{*<@J&`kAro&3WWs{KQKCh?!9o8)I^b|oh z5B7y}K>v5wgTV<P@~P7m&$S^;Sz?L`{rVS=_CV?x(Ax+A0ew}^ml24}^}E|gG!N9u z68_MDg3l&K>!)%>jlr{I&#Bi0`K*+|Cf<ItiToOc$sY^L|M4<C>%(#L^k+!~{{64X zUw!YdBLA59Kf1rhupt`YL+1vE;?-ADfQD;jR<sQqq~8bzphyP9<?F<1cOw6#NmFKV zP_G1NT&(2h1Ask=1E5_1qEHhMFy@M}*a4#JK_0(<mOQ7M_?0}Zt5J8~f)+#9k6TaB zTHN-r0+KP<9`b_GkZNjbf&dKf^)wslxuwX<X|+V?qVJgx+KPOgILtk^`}|G-I!>%Y zJiq|M@Yc080L`NA)vH&7DuTbMw+7<zkRo00gItiUvz)_(&PO?2fWV4khu<TX3zCvW zoMF(>k-e548NbU{7iIy^V<vBJZw}jOYTL;?aS7v~B?@xN?F31*L?CiR-8BSJ3I4o) zZ3)a7Iho$Izm{P!1?(^-KA#yd9alNtj^Z!6%_zeWBXD~(j<B>AV{8M6G{s>>V~)z{ z@+w&M)TeL_fy{?o@T9Gl%YH#^-o)QGllxto(A}^6Ze}#s7)1vp2su|fCh5ilQzcLX zz*Pxug!v0bdZL0&LWEbja?3gzh$W&Get)5c)&l@eG?HN`>bEdhC<`@{UMcEw9$7cB z5OV8HAi|yo)TNeh<h2p%0szE{$u!DbXj}R|ROD|oG?HsCJY~f&AwgY4K>!|GE&`ne z(H6ZF$mEFVEhDK$9{>Wuiq%zn!#;)_06pNt-Nin`V3YkKNAp=f(M}kVBZdne-Q=KP zJ=JJxAF3&-n+%s4$OSM1=_MLP49*~aa5E4!NJ(Hb@0!*X80!QSCJ%6P5?~`b0Cjan zfgwmy&XnCa(eTiT{PJBLbZ=Ev^4Ja4L(Ud=r*K>m?=|1*R~V{n7{1#iIP_$ufx|y- zJ=2+nl}Um&d<eIb{gPUS$W0B98%hkImDrs(rRL)D-okJblKMY5%PT4-0|>046~@)F ztLp7(54xh2W3nH;YFmcr34rpuOiAPI(|0MRF{x)pka#SJTTwJUcJaMk`^-d1&F|#@ z?b8d3h}Ylq*-qAU4x^J=7scaNf<7fO+FHS{9K@)r#Bqbiiw6rG1PimuxW_<=Kd)jA zwT=1I*NA#kAWe=zC|&ziF*$9TEr~)LrCl8Z6~~u!M#3+EAug*NfF4c0vjR}2ew__P zIGJD5#qo;4XUjInl@`QC%3>LQyV+vcUYS?aLJFj#qD)(25&^g#^lbcA!>`QrVu^Uu z06@y5VcA9TwNjR@oXqrE571Z)nVwu=K8j(khhTeTQK!qbFW+x){&|c!!x{@vb^a`+ z!N%!ABpi0rRyEvzCy-SaW4&u6@XSHkRaVn0yI4{-@Z%uPN%L4C>g#Tye6DfP5DQ6T z(q^~Vn`w?$Nm0YJ{mV(eW=oQX8P!Mwv4wQ*+<5lS+m{?$hl+CjN}c8T5)Q?5R$-lN zx!(+tVUcRXbF;&vlQN~)ntCtq=DiI|B~jU%hzkI=uwaUf7g&@o6huqn3e|+j-^J1V z`*C2W(Yr%|i{#xqdu2J;GKXmdFO*KZ2vheloU7q%<rc>1J|Tu-YpeY-P81*bV`(~P zSkBQ!dY7)8qG4mAi%Ex%lo(k1x??)qa>Qy&U9$|4jmj6)u*Fw{h*=XUR!x`l26K7X z^)wmdn?Hq{g|PE{)&mi?lN4E|e16G(3AFtM1h#SbH$t#At<I|lNHseCL|~v^h`JNL zY^N6!CuApJP24~+Byr4#7W*(E(PLD-CO45nR}AC~PxEb#03r<f{*Zw_=g^qI8%wR` zB*q*s#&p%WUL-m4K=O4_u&W&PYvrGo4JoxAA__mPxw?vqz)JM;b_B4Jdf0;eC?tX& znrJYzb_N?nMS-4o6S<-$0NbY2^P|g4>|jn*s5$(+Xim0NWB!|oNrn9Mm;6wJRi7e< zFaXw3Q{mrvwZn%muFh@a%~FpFG}&&6^<Zratcd`fu{9)47uIj2qDD7DtvXF{Fd*!k z6%FPO0~ac&<fqsaqll{!NaS(cY7Pvf<<dre73)aU#5_!oI*C(AmLs&}6BEOrHB7{* zCvk5L#BNhw_Ms^X&_{mTMBi)~t?1YT;LEfx>=hTV-{Ymu3txpxfYw`piU&B+*k!P` zodyv)ezBuzB%>?pbU@VjWSNs<Mc&m3p_1U@1V~6Jfx!N06|iXx_zY@<P%5!mX<u48 z`%_979m<PRxzV9S#&h$a=xzq{qE=eu*-nY(&c;uuofC$ck%S<O@XwLzdWN{49x_+8 zZ<Rmsq>g6`9yViLpu3{nIL4jPdy3&GI<l*^ZUU4R6|kay3jm86PkdbW#;&UuligC? zR*S)BmuT@ksq~AP0Ic-t8~!lBV5@%wOfq-|0caofi_?Wg{`BJWSW$J>b8FG^Yix?a zv;~HuH3-!qYsIn!D8Wdk8ku<Dj`$K(Q(7mxN}t(r5MTC>N0(|8p0(=nM7*8`7n)~| zhjVQ6$+1mtD1ixt-`DB8_y8`EX22P+GwR%i06Z6^t&nG3fxAS>&flQ`?5)!bvpk+B z1Lwe#V9@CRE>&%?ouQ$Csh$wIFP@}UZTO0`2as<{7tiy`zI8n5YcUV)vwi6~-VnH{ zr4oB_Ydl^^k2qAF&1hvdNTP45)Ke)pX9~U+8(UTPzF~KOU&v4s4~wcb)UlZChZg0R zMuZ1RZi0G2)f7r8a9T*ES?FBH(80~jrV<fW%Cr5cri5YV934Z+v}GPJ=j0S(+)7j| z_!A8P$72IwB`%LlwH4qTn2mkn)!|moiLqTG(9U%!JzjNxp++8f!JJNb!ZO4LsDzAI zoTo<b^8J9C$fBpf(5*Q(CUp*_Ei5me;r6kj`XSclwQ`%8qLa5JWjH(~I#j0F)WHXR zNcZB!=8I<OEdA@o$^*SDmaqHH^w<6fxQ?bI(ttzkei43d_b*A0I}(^-+>s6GJO6l` z<@tcYtcrVr7(4t^Fpmb<2tU(IUDf={o^pSomd;O+jhFrYr{F9#(1uy+pT=qb5SXgs zfDO7w;I7BJ{$Hp3<BL=NQEF+#<sXvjygJZOU0Hv=Zw>zxR7-x@VUle==>6AOjshBb z_zQh+&f}kgc33Yy_zNm{3$S*!fdg@Z@AXO}O^160Q}n>pPv?5=u2am0-Mtr!T5JTS zzP>-5nthnwh6v&=J^a40`(Q%i)@|D}kvhc4F9IC=)E5~?sEE@i%<xE`yUm84HarWh z4F%!bINZVM`xB{>dHslC4Gv2OnMW1_aj7c+?JZPAz1i+Zj_wAUnMvw0=IGkV%S!!# zVY;^0_hf8n$TU-^oD49sXdVRI52%4Ph=T=>GBG$f8E^dncx^*3{!ho#U0IgPFnv-| z(i;l4ETw(EOk9Av2rNdH+P7m#fafIWEX8|nOft}xxd#vjnXze<5&*bVm5|G(N<y1w zb!U6q27k@LWseu23GQDTbhot$jisN2X#sRDEN3JnBuju}ne^!sV@XL#&FcF@`Dk3` zSGhFGAF10%{+!=`q)^)eaGpti*WJMkc8e5K-4*zjx4DmNMGbL1CyjBP`ir$I&-WkS zqrMzJS};sSU-(ZuF`VNGs5}c|fPG*ga;QsG%HmURDmLe%y?DG{Gx1n3L-6%~*+l?e zS;|TKy^79k7855YC!?0M%8^EqN^04+cKt9^A{wI>w?q@aTWLfrl?7@g21%a~WD64h z>Rcd(`v)MVFa%1nxP+sTbWdST+}_^0%qa5?0jw;h#l^*>oE#R~T%Vd34*^Z+v{On* z1fc&2x&Ve_81S0usX>5~%he17jk(7M6RCE9{VY+LXHiPO(Xm3Rr^$KiD>j&UbI|R$ z6d&qgf&1WRoh`O$5{k&(FDhm{)H<0FlTS#Jd#K%OP7}K7<;rsxEx>6)jGN*V;ETeq zQ^M-LMmV}A#{T6s5G8!G5l#kOo)!G9{Z3&3segkTzybc8xii6asqOz{H!;qr3kJ?C zA}`#n_8BLwev**^qy|q2E;I(H>tcU~xp+4FjBosG^_xitXgL(LG#lxh@Z{!Uy}agk zue{|85Htw;-?Qjek%MR{nt-Dzb`u+9f4ZQH`-dTRK&Qg?=f8kev8Z|(5<2n6GkG@M z{NgDjO?5N-d5;Q}v<DAkQ)c)huv6Qa3`jwAYAVJ{H@i(Z_Qkb*1f!6N2-z%DnL&=K z2kfjIgz5x^Z$}YNx8g<Tt>ci}_%<4y){GIutVYtb?kqBMjbur^Enf&YHb1#ZoHA(7 z`S!A0q3yF_H42sJYgJ;bj{(XpYUdcZ3KerSgI)4a+Prg9S6DWll*AqY@1YQ>(!~8C zx<P5o2Jq|l#ksdjkISwT_2v)8p)aRbF*F!@i!C<IjYds@vK{3#`5PG)*&B%>21NOg z+Ry3KC`EL1aRbaUUh3t=U&Rsf=BKI>3yi^3(lL+yrnANBU3ucc&>q@V<8?jBTjphO zZ<dcBpPbsgA)QbNumi-dN)Uk0_6rH--n|&dE=r{*&MJFE0Kcbu!pCzDtce3{Z(#qy z&AmB$u`#@wtz+19tjTq69JPuBW4263^`7UkJKapFBa_n_9x&}@Upfp30Ls{mb1=58 zo~^^5?UkIKvu;?J$9*Q2+#cti6RW=JQxV@g%|WyECh11Yp`<*(b_l?)0>-0YxVA=b z9+5T+!}MOf=XU(!`P%;(Pb`h1^U7m$314QQ?uGihI@j~8NdWDhWLix8-rmQ4p-Bv! zGWyWeGXh3fMvfN8O!w-?M?dRQnk}nh6V+|95r=Gq;xXuiN<q=vQDMjte=R701K?*J zhEJX~=Yv6(_*+C2U2b2CO}sYXjEr;<WCM?h0|})&!CFK&@9IwL^VqJ0{aTfcHy9Sb z;#?t%8vF$2o9Y0xBl09`vnVH-F>Ze(`(h{}JY)J<b81&AFRdk*{9riCcHb%PEMDM% zZikHxb?XIq8=h`VZ7Zm5NmxPu+;0j{wh7~r@fp*dGgYNwC7aNCPXWh6o0vQtV<9NQ zTQ754$nAJJ)3{(6n0S?2zq$~}h!c9cYxbF*0crv7h7QB$j&e+B_Y_ldb_^%ehfh9z zm{wUkXKD9+Gy8&sw&ir_1igr%-9bXzp{b$~5$Ljh`1Xyy@p*p1cR#D-K?!O$bER6K zuAKGey_}iUzFhyOlI8H*^F4$%z!rYZ0w3$e0pyhcQ#D90rYs#)*G1c)Z-7|5hs%6$ zcBoF%dH>;|KS^MzWam%4xt%7*UCU&GcTQ3oR(HnuqF|l_^YwWHC*=#1uurv3qr4CH z8*Q}MDCNjoA{UdAT_X2K*liDgM!EniKq|(`+;qG9i92Q=KOPSeewYp7vJ*1ahlI!c z$)Q0Hw9zHitmHbcXALL(;Yt&Y9*-GgQq$bxY_ktVd!UAq62E(`+gboD%P_?T1YLZ2 zne+w#&a5<^VOkuf+^Yw`I1Avqh)V};0xp{Z20;uFjR=><v&L)i1Fb$*t@Q-1y?k*R ztl#N#Cr-XnDY~>fVy+=nSQT%0_IJr5DEeD%EXIgF-@Ix~HC^hHSbPfB?-w;~m-9<l z!M)D<`lW#NGj_R{k{tn1F8YNeb#6*Gr0>C?N%PZp2iYe+4S?|w0jytYOyO*mysQQs z;xckG(DMTC^WBfR1#_bh@l<M|;3|jel_2TL=07AM5S+BCE9=l9y0fvP`~)gBWw=eX z%=Uo`O~GY=!oWpBBhbartf{{{;<eB~x1;J-jM@niNQ=d3vO`c)4BF8MHU+{FrQTia zfzJ0=zZo&mUfJmw0yNl2A%2=zQel0MMJqh0vphoN38C{CAK<88Dh##AK=SQ{7u|&$ zVAsITa{e`~U!FFbIzci47&QIE9?^8;_a&x+Vp=5PlhhB%WV$*%N#3<F4h@Skx`nnr z7#bM#(9qI{7PiHGUDj#bkae-SgLT0MCwC@GkuY_a=BM^BFz6Sd`@3M2;ImiVS)n^^ zAy_8JOdFyp@3lH^c=|T`_%U>SkpI9VAP{6;vL6<~R_K4j%W|8h&sz>>G{7K{WLIeq z*FldFi~5<>hkDN*Gs`Vdr+_c%F4xG~q$RG<CNyL@GIJ8w`H{R6hw*xuefw9aIRBZw zpZmu6$*y!I1swX&u(f}^$h+&Bs<-%>!|u{!4l>0QY5D{Pg#7^8HlewmnBg*~$`5bR z%xRp_)9Goa*?A=n>JIpJz}GM4uHKAN&I!lNjP8P;@r^%ir~<L(_SQkoY_{ozj)_F# z65Z2Z4*bJ|!~kh=h`!6?QxqQx?qWZ8n*2BeKW-Sp)?{vt0T8@%_@Z=oW==Ayu13sI zGF(8evOK;51ZFe?mN##{A7GFdXy-dtkmGNjdm_@CZo?2!Echpgg3Xr?sl-7PJ@^d- zQF#qtr=y$bvpbulO($Ye<_*4CU?`7)Dd}y+(_?v&WMT>6nnQ1G7L-24M|-EfiYO|D z9N8c79o+;YplfSW3i8d>8h`lBjcU=<3_;)&?GS`6i|VvWH%c>wafN(C?iK&TOPJXE z)X&!5aWSn}KvSQ3$$K>dKoT?%VgWZBbLcvGu7}pnrld62J{+B5&n6S1F4GS;ugop8 zJ73Ff4@oIWQiz8+yKoOwsLUj>iLQ1$KYhsd`T(#N$XS$(q52Cn!Oro*SCfc2urM9z z7MLR?OaSZ~Ke7Dfb>S;mE5DTVJQ<P>(IXUtp1>2I!UlqR`J?N7*gzL7zT;Bdz?SCM zU6nAEq)rdWySfi>r0NgR_qYnwQNIJtWkO5>tc7GWAhIDJ?$%g;7|rNJAtQgCfzRG4 z{B%DA9M&stWfHu(KGIZw(Om{BAR?=C8uy6)B1gm}{uopv>;G^j+kCSbo%(-hI;()T zy0+Wm1lK}vcb8(N5Zt{`thg6<ch}%j+*@3VyIXOG;_mKp()at%WiGR`_gdM{9CNHJ zDJJs+Z*`+~8?>^c;qL@6;6^NY-JVY?qzFfFUL7eu5Wv~kC)Q2CmJ1y+8;!x3!obl8 z+|9{Ex-{aWb^mA;{OZSl*0c@R0G!P+9FEltLdh+^hin4+K`hxeGVH?kzHqe)R<Brr z!Bzl<muG+J`1ZSHImOSnU;fsT>*TCp*53g<{CAAzdZ_<A%wS@VKL2Z4xZ;>V*r6o7 zcF)86gj*$8Z*F>1mtQ9-;*J5U#R!*_le9CJ-ywhaQpze@kXKsSXfC*4+!3J*TsGV$ zwSbLkpn8Bwmvd{14&K=>Ola;a$P<Yl2F=X6%LumdFM(-G>;?@$Rj$JKci$i>hY|BK z0N<yoy6<yhF@${mob3;w!~BCw@wv;^S@~W|xq?ob`Dq;EhDyYhvC%ZsvB7@js)OD# z>O@60ZbzoZeyZv*Ln#F!IF*9TZL&<8>2op=J|=F$d3k(k{&=Y0u0hDu&9~J75fyPj z&K0#TnJ)yuG0gZC%<Qq(e_?`nJwbR5+4XcO1jh^wT232Q6u%y>CRD$iybaUkSO}2| z)B{rbSt4rrP-hd!8yz9c#vEt!haQ`We{Grdbh;P@mENcoS`CD2T@rNInQKmTyk>lI zWf;xY*{kS+kry;7N0$RT%Rf18wq;$6CQyO2m#x&>N9Pa>l4LExV1LJ2aRtGmI>aK{ zon<@*{+f0lF7EGzr2SK6BfR+uH#whI7<9MRCtaeGDck*A1!@+HfHJK@5Bmp2bHsg8 zcOCY-5F`-?p6SF%gOs6+=6!t8Qvh1iFOpA4BoV>(bX#0BX))hq<*aU;A~t`$!5`WB z4&xM{ExPQEzlodkT`WD}_x8M@qI?SFKxa!+RJ5j14eAC&*n119MIj&eLNS>t;G-+i z0!tmbn;?@xcfO2bBFNZ3)S)#Hhw&J*p%+sT<i)Y-n12FuEb$0~O?7AUQW0a2%N)eN z*DL@R<nyWVgT+wfI;dA}wyU~kd}Jfb7cw1|8Danyqi%DNG^%A9DAWJCQDRw1@V|ro z@uN^0b@emxA*Her*rIU90Pl>I9G7!w(qLl%nwvO~GNNy~h`dBovXfu0<K>1fozpbd z1dkiMmCqefh%4Ql&}nj5uTqOOt~wmGGj!8`UF33YLtS^9U8|`r!%Uc1jzBPNyG>hr zETkhl@wY{`UI=9*3>SUTba6CXn$ar6Gu|emA~v`QnBSj2nFd0&4KJVVXX>1$KVTnm z6c3xJKtYvcq*3szJ)iXCZm+@onvst9Z+46fsK!v2c&BJ3;e`L!*C^Wy-W~0*dQCRx zw1%Y9Fz7+L_TBIiE$pl_B9r`iG$Iv|mET&C@vvd|;pUhPJ`>zSa)oKmg9$Ez18ccJ zoeWJA3&DYX542gMAk3nRT)NW0V?20_R?fi+K(^f_1j#`PMs<-3wzQE8bok_YVljo| zK_@7Rv3YKm&2C%bvd;sUNY6E1yJKln`w_I>b4o5S8Z<#p{{`h=bpZzuG&A~5odPQN z`>gtLO0X=oQAC_p`gi-us|UFTkxZ{H43@rZu~kZ{9z#(IJ3VIi`{9Wor~3{rzOsGT zZjTjVyv*OPRNee5!obYC&ep(J0W#8)_$BJ5MzyewM^=)+5?%`u)U|4b3;U8kfvv6I zFf-R*^EOsVl@QGB?y09S;OMr-H&VDl5oUY?HmK6^OVzMQBPqCLwo-`^cLl1gE@cxs zyThA)4LH!)L()LTQA|eJ5m{>WSP^NIYOlGZy=KU3Vb>9Pmyk@aM7<c)2Z>$UYCG-s z9TG(GL#rHO7?kZSgd}!{gr~1802C^^Kp)cD4~%?6oJ}O%HnOEA-#-$h8pA0zf9Vz_ zbjv3rQJ95LXbj~0T~~!#W+@@PMPJH-R<ih*Wv_!}8?CH4SVr?-5w(BqrogQK(I*>u z>~&;j9WA0APdCp_r(Zwn=F?Eh?(P;4G3D+u)XvB@+|f|>Pgo(WuRN}_!YVa|FhT_o z-HC`qo74kp_W)q+k$Hn2jv%44Tyr4iK~B%tIv974-8Q38%6?0S0xog-ibkh+n9VO5 zJRhQFx~>sZnB@o!!ysOqwn{^lLE#k0%2{{WQOmcidnIyfW(ZHl6f5H^n<w21bJ#q% z=eVJ=B6p0AMw5UpOO^>hMNH^v>FQs2+F<D;Qx?9hOb|ZM^&})w0&mARFLJ4q*c|cw z$W>0p-AVs<QLU)_H+BEjJ4!fXLlxkVuN_RsKM2QV7ypG{wp@e&sn~%&xCh%uUYyo- z)j2`0tc#)2_Me+t!Y*k)vl6Y~F&cO<29rFFJ)FF!>AI++!-(Ym%)2$$TJ!`%-ZAvz z(#=Q?+)wTx1B<FvR7@PlHIMzDfAKA7=%s?r$M6ZYVVJ<xpA%`>p^5?*>Uq1}eCeuc z2S}e1zjp~-Dz;+b>h^7^t{)D*c<f6^jU)8tP5*+4g~UjzeimO34wJ`%GO?Z!AanBX z(Vz-SpftMuSwBUEdlwI!UOh+gWE1vVjfhbkxtp!LZS$T=`n7pY;U4cSF7)q0n6{F= z(S*RmtIObpLY-y7r78&@OGGrz11f1(W`)RFZE3?hRLgYQTIQjI=3CeJ^z;=uTmJ|? zRq}pv*+@*@jD*;6Xq$*JV*Zn)Z>AFkEi%-JS+ry^KoWq%)?NW+0`|J_PtL$@0dgJ0 zJHk0~WO_SO5~JTLk*`C1{~D4Tog!UNjC7+H4N$Kh={fy%NQpQWS0+R30|j-Twim^% z^({O!iJ$07ez#TVwdu6k>)!T}MVa5$KTu;vOV_Z=8M{4Q8xaodb7lE_%1IoRe?#yx zCxtW~irv0`1k5r9Qml<lHr+s+QL3oU2f8;*vhnGiY$;N9zUq5Q6Jfk?sF?i7kAZ+4 z;w!b3k-o?EAtf9snVAiJ{u&#U!;A=J%-`2hY9`y;6RE{3w@LlRl0!M?9pqZl{B-jo zW;~yj9g9AOhlnyr)6@iVhm+-Hid)6wn(U3bdbz|WvYycp#E1;}mjaS3!sS@RjY^3b z_W3T$KUPKx&tEo4$s{xWVxC$iQfF`HQit!!4x_4m0xXKBuj2Qf^TgNU{^%pH_4(oE zg;8SceQln3v7@7>>E2UGufK;ytIaI*`X}UAO{1wFWnByLS+O{8JIhxRmD(>A0a~T? z|GNPCk)CyyTo<BWCJ3pN%K!)xK{nB7EUIvv&`IB^NoE8D)B}dj*X5I;7up$X3nL2q zRg376^Te&m3I~9^O1|0GzrA@~qG!Vlw!8lvjlL7kr55MnrI3%tC<#b;>bcT1FmV>T zuX%fzz5gv7uC>O*c3(H}OUF8-zQ*?#h~){WkisPIZ>F>iSqzkpr*yuM_N;V1oYx)i zytMeaPN`<Jp$)E<u~q~dl%n=mXNbe|qd=;q8Wgm(TtvLK<s_IPwBd;7y5hZA{~OqX zv;ecLf!*QoL&ydKq3Ce;9Wa=1DvwvMIXg?w!eCAG2bg$N8HPyYBy5_50Gr@hkE<o6 z^O2;?^&%PWudz!OR7<oC;u%z7{hF^Ow~KnQzMkw`W+J^5>P8+CSCAI&(Da0G(#sa5 z<?nvQ+L^x-Bfa+>6rJyFnnxeFp(jMCd23NW`n!rVF518wG#bho^`2^v(72JZPI>Cm zbn$%&=J*=Zs;p)8`6WnfNakOb)vZ!v#T+`2mB8RZ2kZ%l;Aa0R5J13yWhr)Lbxu(i zS!7Nl9jH$@!rt5}*)8Ya7&HO4u#LzT74f3nX=VHPf535mM6}nA?+F8os!g}y1=QR7 zc7>KItPKP(KO5DR_;=z5X_jl@Y28eQv(QT=6p5cQquZOS>if`pJ0${6o;SFrZTCO# zHj)*OqQD9#oe+emYC=iKR!>t-Q4TSf$f_8UOWZmZ4*HVpu6Bg^A1jxOqcH|YH&0`{ zbDIk5;2JMfj8H2DFd~1Ps$GE$+$w%)qzH{6Gq;-DyZmoLUOM{kXMyf4<Row=92nC} zV|02SOKGhnWt7{KtWgIC*g#px7?`mJ#{`>#)gCtX7feMqO_mCcoji6!f9$jllExpr z93}+FwB^2rIzIHqNk2*c0KHK#vX4SlLYd-ru{@a9uKHd0PV<L)E8A{o-Ngry`pP3u z&lFy)gKRr*WVCKDJP>!N`>0v8F%m=oQOwB}iKdRvYWUKx^M{KW^ub_SdVK4G#hrGe zAbBuSc&j&?lR6(7t^3VRqSCJ<uIL&-dHql7%OgxOruiwK|4SdNxL}SkyFsd5w2E)k zx<@lpY-bn|@ULNYJ70uy4Mb`({cdcq|5!2{Vyg6Qws{8Vf>+0At_~;8hh{VNi&h3I zb_xuuhDhj0sQ5?mq*V}3+QlA<Ckle7zmHaQSz-<+d4e6uMO4H0)3~8FFQ2k_N6&lL z;<u7YnPW_b`>Q&bZ<ou%mc>oa`UIQLTSQ6`*8-gxdgdjpl3?N-jEZCioe#YRL(*PR zFv*T2MgJiABJrv|kbuMJFKa&WvJn=U$o{AwAm`XB&fZYBl<I*pvnYZ<Fr4P&#Glbq zbZ}_Xb%nZB4=Dxn|L>+`kuV^k0P-aVg1Yd695F#;;=wp95eTf${8&z$B{A^wRT4j8 zP9;2cQWkbgCd@?i@&fvDHPSNhLefJ7wbGs&y#*}`nMZOc#BvDfkMWrkRg^x{qqOj( zTE6S(BiGTx2E261hZh=U3{Y3;02fD;U7{!*(T1=<ZAP<HG_dFNbwExe<;`e+e-L|* z3a`cw9jc@<5Z`u@vVAS^C>hsVe2rc1PawB&x0{5B<|H=F2l3%4&>bNg0;^Q}mZal5 z7O%{Y=;8;BBmcgBS}f>^@DjhTFUC6PZ8Mas|9l52(*_n2kYIwPG_m&OO0_C2=lMTw zX9F<H0yj?)7?4P%b^j3O!2+`dBB3>KxnNR-fpJAcrn-8<$r){(@L@TWxTR6Y0pU<q zXqxRSCQs0{Q7pmN?W}SsCNRYcic9MGq>pLUg3O3(vgD5uo+l26aB#eltr;dU)!;%? zoWBRaA?@HBl}9T6p~q!Y!31E*U#WzONGBw6(m58>s09S#3hpKZ2O#q^(uj&tQ!|5| zUJ7-+f#K+0UyXtvuM_jO0y?3&KN&4qUOf!I7MU`_F=2%r<vJ&)pY-Zr2!_P|N=f>j z%TE2LRD%|SWeh@l{1<G^^8fesxahvlq>2BDM^nBcEWLyWD)e+f+pw%U3}36(bK|T) zrM=gzPJ|8gM7J?;-lg(Z|7KTfSn<_)JV-a+ZQe#trRBdirR0O}Bx{IaUhQCs6d7nH znC7laE-V3^k&~?=;o?e|aioZOLVQW^Om!gYm*;1;git|Mhglaa>m1%i6Ez0gMN~Lg zBqX4Ps4skTKc^qUEZ_BXy&^~HH_4gmW-O+po2QWJ;%|5-d>h89MDz=k{v&h|Nt6Kd zJ@cL6gco@7B;|`~RF9otuOb_SE4DF2bN_~UtQi9&!yfIFeQ7~Rr-H=s^!EZXy7!c^ zEkq-sqvw3@_J8ZtHlUmel0ea970HE%PInR#08sb6Gq}n?mHdYk47$shiJy`PYcen* zQ-?EO{7hzp4XcOvbXx2>L!y1%%3mB-POnB+CZxqMKlo8xvW2;&O6YL+r$EC|mzWL* zr3yn0!`l;q?QnI2zSv_&<_2IfQ0NYAm&Vxyv61;n`;xlHaf|e6T18qrtVvAYmS0n+ z>LOapiHq<t|Hz?R(7gfg{831(&v%~vATDhcx`VeT^SUSDc-m_&H=~GVnXc{jIp0c> zFavKxG&=LGqKyy1Dl5JE7#viQg7ZA;dH9E#qz|Bp-2?^2K@L^^0}CU#sIR|K*_w%l z)NnX~#wrxAr03tDrfh#w#~U)6`oGB25N@6z5L%65PvqpW?ye<rkBCg}g?y6UgW+nr zOXceDN2e@S17$up5{VXNo#R_l)tk3I-iPsc+Z8*8UOgWqjm+ZFi)+PXvv|SJh(?!Y zKSu7Kt;wCVRrjG2ux5xx$uUuHYtS(JsiQ4{*BlK*d}IX%*i`ig#55wDPAP5ni*E_Z zuT=v&lWldGZ)fxjRtOMh8gda4A=oSJYDTd6J_Dbo0l2TRae}O!5#5bzmAx~h(Y`$T z$a@pYiBO*5PzK`>BouGT4*F<4&F67>ZEg=ki~Bj%WT?yd3??iuBvPW*HWG=czl=Cg zM40hruz}9ryK*^yp9fjVZ^Z=1BDhPd$xba8bS)*7i;TrinXOg(UQ>0+Sau$=&Dqhu zlI6?fR7}&)mojjMH{d34evKUT&Hx+W5^Vr7*5HJWAywkr#Y$unAXwqoxa{-|5L2!6 zk};B-q2WTF7rG%b+j(Urd%dI8IJ+(!ME|?{3W<+bg=vQ_xW*GCn^DxyC>qs2@jv~+ z-wDKu8wo6LmPUjzl>F>bJMlUl{sRkBd#9dQB5X^%@~e!3{Rz<+2!E9B^*lv5$5%Q7 zRBV7=E}SiRK=ZS45S<)&l|0mCn6$xcGIXruOMBkQtvG!pGTBG&=g)#cY{ekbF5$T5 zf;igHYKKao7;ZQ13p>jZ)ny6fIdmd;T2f0`rq_?eHxDpq`lQHCo*8CVrXvy9jX;l% z9Y*XJ4oUBH>7gFqp3evCm<Zao(x3JJ<=yCTi|_6<L@EV2SeTnge*wsAOJV8bTiSX& zn>wrZZ=2jNq)|9;JaS}r*XC0Gfbt+Xv6nEa7);o&0cFR4Xpa6AILBj}iIG`-Cu$b> zL<isa9dWaf@9V;$RMdDw@2*QK1F^(3{ZV_v8&sZhiRm-!*MmD`n6UVrua!Hlr<C}g z-4dB)vrw90$F}QgcMgSKi#Yh9sR<`ViU8i|@?%M<<SKbbKQ@T%G4ky9zIa$qWY?;A z7Bh!Xlqe{+O1Ip$t9~bd4GF+$xJ?=%{{)s(1k%T!NMetc+)!Ty-VPbr3-GKK=jnP* zAStKOgUNAfk$~LNYSC#tirK{1rG?zgNn0nLj_*@$BTrg3247(U(>Lf3TA*Aab6n;0 zq<1sXNOw4`J0ABupNL`vK0=H`hIDI)aU+I@HN*kx68<>N{Krw7Zv*zEgsJGw^iiYs z14Y|)?JIS==5EEtz^u<YTGZkPQfLfo9t4|4hp%UVU@T2@K&W_;+!OHYBQ+2%v5r|T ze!uzyhizXK_HbA`eDDYH{o#E-jKrT&ekoC`9iYmNCo7pO4vEljE;YEXTrz|dii+*b z{1=xcg^zcihD9}v+g_HAO%3NMhXg^p4z4MvXI#n|{ssV0e_d4ZR-7aL;=Ak-v;dSd zqJVZe6mjU_?vLlQ9#`1dCfjuxMfY768OwRbju`08A){rZF1$gu?JlIlXFNW1zD?|1 zJkcMb_PVYrPuTo><=+YyRQ|$;Qfz_|g1ge1*GH+&g(>5o;K7FBBd=0_8A$5p)z)Bk zxqdT-OBo>$Fkto1mTlQrwhKON1YJR#B}a!TLhj|ro}>#{nl5mBhHAdyvBfL=S}T1@ zloU)TIvE$nK${}_d~@$@K5$yDFiC{B+=RW54%uFoC4n2HTkgrt6BkhVwJQ7HkZL+# z0wtZpIJ6uBM<8v9a@`8Yg0NwZ@w)vZ7Vi#Rwgytf;h0|R*51Xko4)fczM#2?PC(aO zOii%KxSr)Wj{3OC=0rUWMc3qve)1Vl+6!4akX9LnCCXbcj*}@Pxle|&N|G~hxEwLJ z1uv!7<)Q^NyGa(KHoF^S_WF-Y=|Q<7^Mw&rKnVl*w^-1KW1&Q&yKB8YkmkwM%oI|J z4sx@+NGMy^5p6{YXSqb!rMWT2!bOMmHI<%-orIfEV?1_#AWP;e9czfoZqqoPU*iMB zaluY4*r;T$&lQ3X=*-GI14oo4nondNVa~RbDO+iU85%zfssn<Tm~|TDCmQz2Zy;>) zF@<^qr(x44DFcsDy8aVe1*{EfA=eYlf4I2GMpwXet_Up6yiS8P!#`5Qa;A6~GCpSh zSFV|iOMHdIG!>Trs$`5)kX$kSUq||%Fi84%zQU!)yb~P<<<1upg%53X2dQ_Z!y!CB zg=108>Ut|G#tK4QM-ZUsFiv}P<}1X1_4sk=_xH~1u?!BK0bg!O*L53S?h`&87Jj{- zZf1q)n;3j&m>AP;gsj?vzol6}`}&*U^7eV4O$x|=qdfP0Z)0XjqyNUc1nPKvMAQ=4 zW%D>(q$--)dK5ThgXx~MeHSZQXm<<W05SX$HVZOnLM0A;Os|XQU3A`H7epfnrOnq! ztQRN`L{Fx{*s-5<HG$KGoqSJwseu7L*R(ml9d5|uj_8&uWMAFcTTYr95ApW6<4jAz z9{BV?&8$rLF`Wy&#T4Sr1uY$Xu_r*r%0TF$R2px;Gg#W&(3k|1%YZ3!*q&sbI_LB$ z(Ui4qznt;kXdF(L2KiPw5~<`gl~WyIS5Zt?v=H%Frx7|6a+-u^LbM732Ygf2M||_+ zxYjqbC_N(|UL{DLDG7gPsLcq)W6H&bE%bEGzq@p+Uis`?Ie2lMVFqQXQl+?8>`3MZ z3{JS6uYLPRsy;&45$EY*zx58EUC1<5J#S}1_+58;nq8<XXEg`{fe)W7)y=g%|D)d% zu=z6KuOP|D2*jvF4@qVd*3$jo>R)8Xd#0qwD*A%&?~_Hf_F>DCArN-z>o0{B9!|GA zVgj@g&-=fw3%;gV?EJnD-#%i`2JNMTM7H@O>nPVqZz@p9p4vxX3(ZWo$$xHM?FZ)2 z;3S^T;p;Ol=z7Gqxo%OY3cA#Cck6xQ(YR4?`zv?XeoYz?ID&34NFKS?2{f0}<-9@A z0*eGfuVA#$a6swcTVBcleJ=&<W#ZyhnG`x;HC|T{==by}_|PAluLh<DWiNxts1ZpV z2c6gw{)~qq9X#Roh+At1QG3Lb#g{4hV)vm6N5Zn~a&$#><*pj9$2yvIwmZ1O#|TU8 zguQg`G<>yH3#4dZrgRH3SghWBT14p903gtz>q(b4mm_tvyBvMl<(wpiZAKMxzi4!j zf?IU$UX&yf(=o^I`t&jMfF4!eBfH61`qZT``5}b*-31Yx6RAYkj5#Q+kEO>yDDw>A z231cBD;kz%kr1%qop+$XPF>pvov(K~OOQti$EOy;{MXuVitdVoxkM-_mpJSM)*2U$ zP=?3HQy?7R@jTqN4uAd4Nbf<Da&C@|6ZQW7c`PUf8#TD~)bluiGrPe0_qXI;|8BGX zhU}YBdsQ>Kez+K+t^hfyiZ<uw?Y6Hb(`=Yu`Z(r<<vsO%vu=MA#+?2B3w?F4-8dTO zrbqMc`-~J@5i3nPJurXH9EL`~tY!1baBiZvw8;!x3$QyNm(!_-myC&u>q+c=8N@^f zbdCzX?GEq$RRmsFCZEysQ5(?pisA0t>CDv=<A3~Pn6UH{B^<{dRa(>DKIEjoEJ!$c zD#)*I3(l2*9a(D5nmaUOAZjPzD{Ha^6&Nf0`P<vN<4RPcTs=iNjXm(}$fwSFwz|Mk zj!*trGbZfeDORX#zlo)0GnD9PB;;fi0{t^{fGYH2vw!hWD099a&>epHBB>VTW{Os! zkdys@7yDVavb0cnxF^6EM~0!N`%?Ve)F5$)`lf3*Q*<zi2GZONk|}q(>VSk}&T@e( z@cY?bwmqE?q^8!O8-|9E{#-f5*mF;e6{eBtXrYP?@?-q~FIKY`Z#zLs4Lij@Y^SY9 zD1}Bw)?bfEVLnQ+Cq+}7%CL{6GZ{<9C4X~USH~(b?T-vidoT%iKPV(_vcNGMP+D>v zeN_7Su^-8)6MUH{Bx<e@|A*&*Vd2|fsg~dP9`8MgMH2NuHQprVAHP!y^gYCC1?mUu z(G4Z#uMX?i!rSnAYPWWa0HIIhK!nOngYX4XKNSk*Mm}HMZTnwCJ=O#*c5Ie8Twl#V z20yQd&4<Uo-i7RmwLka=Vi-t`>k~__8<WMaN=)`aU5flbCU(D4-5<Th$fhK6wyW^) zO%ztK^&t(j_!u|~hZHJin-W9h1{X#l#7EHWPngS^O#HL{tms|2=_p0VcIxxgziR!+ zAY$A!aBi3P)D6nt`y)@C`*SaDWP>#e+uN5Y6{Gdt1x8ccckKjBYV!Jh3hA0s_YZ|k zezCASdn$4fx=^-Clks4KbuUO)M19Yn69pn#@fGE(6$?X`Wmc}t6ATP^1Ov%S0(D6L zp^9tmUS(}?&EaF~fJ6w3r_{*!a5j!bkMR%Q%;2_UY;JDm^c=HzTz`Knx&74?QHx?U zGI$5&_OwJba|PRcUyHvxac(}^wmN+EHo+#1igQ-{$5S?rr7;CMh&5qB>5S#Du2=>S z@AR77-F+3MYV&6J>{kUC<{6O(>gwdzBbcS>YKh3iSD=A<@>XqMS<Yxz2fJK7b5^9n zo|2|Br~xPN1;(ROi7dkVs)IRT_^==C$0)<O4}H7_-!L{w0?wzI9_zxkMZa?It35b? z9YiTO1uZ0Nm3<@NiOB!*Vq>wO?Hl<gi750Af~}(V%Nb4+!1YST2>hCtbe9uFLQuu{ z06Q}M)t<P}J${rOQdDSue|z4A6j1aivb|<M!!7E`(1Yj36+{|7vd>QHP1-U{mc^bD zCYH9RJj@ppH5wn3p2=s3G}4@SxqwvuvTPLQ5xSZB^$;VhB(Sp}7PoFiGJWx~+!>0m zJ+5rEdfx$xvO<5Ph2$o5>FK{z)y+5tWOB1Ukn#<-F<eM*N-gW>q2M4zpGO6A<~b`h zeBjp1YW+oo#uSXmeJNhdmfNw=KG<-e$-S<tav1KfMr%AJZ;z0h>@Q;V6o;~tGMb&R z^sX4M<VO^G8d@~{b9cU0Z6Ry7<-1}MSx%dFZ6_I>7T7c`BH*<24c4^%^)8j13g`K4 zsLJFEO11pfFCik)$ghGkN_#~UqObHfnpL8K0mf3^;lZJBI~dMT@Qr~hG{T)%3DK=* z$d)kyG(@XmEEDZtTE4jlNVlV+(nuo-XQX9cyb4dhZ!M75%Mc)17?YO*T}CWanPK&W z$W|~p(!p0%y0^~y_CQb?ZsBkRqAuGHp2PemhjPY#LrsXBsuON0mv_}Zh}&{noaXmW z-+nVAChP%+udP@c=Oo$EixRiw4Wig*8~K-TJjl1;;9MD1mlG^^vmNd21fkGZl%ohw zPSz(+YUDHWL2g^#+Ve#1!3V5?N<n(-gI7qjl++4}K^$S4<T!zRNP+OGy3KG&pEtzq z#`#cJQ-+584O|Jvugt#<nHuDDKz=lA@j>6`Q@Vd(&4^5}-}%UFd-T?789KRg1%#9< zbFkP1CCKssNe6vyi*6QeKiRZ>K;f|8jlv-^#0j7i9M7r;J>7aJ?~Us)=e*uzGxuK3 z{#`z!*KuByzU#-Dix&og#$K|1px2fvAo4$)K~EF*$@mAbKtbmbqCJfEW^PHQQPu(; z^@R#^n9F&ILKCa!zy2PH<VSsB)|BhgN6iGX!P*0z;TzoJ+nkpf67E*qgT=cyOW6hm z@7uW7T9~Zh$?U0{@Q|v%c;uh6KR(X<l$H~&=HY<)Af~fbdhIo`Rz1v4v8~^1HuRek z?TT78jg|M@Ez5eoJ_>@rl~!5>1~B2v>N$}U2{@M$L#PzU83GmFw|UC5Pr{o>;(lJ` z^7yZxReb&4Otl2;5VW1+3xf_~wiv~8im^DbCoE`=S$RfSH9c-!Dgx+neWO7J0^fUM zOjfuQ<AK2$R6vI>w;4d{Cf413b6{PLgIu5^5{BS~za#qISUMGVzNE_tgdA4lSu_ZO z!|HK{2yvrz40bORp+_O+Jas+aN7F~hJI*W~?8p2enL^?a9F*O6J<>p)ILR+IpI1XM zumP7Hz@QHUO`e-g4*JsfHm%0lyYnFLtd3eTaV01JF7n^lIW4<3k9VVFrZ@Lhqn*u8 zrYqymvJ132qk9C`MQ?5K(_hStWkW}3Xb-8RyvZ3>kvC-hxdgZ|K(z&O#({$(syEvj zlIV=?1dDGd$A3h94CqZY`Z-Zwgs6hc&*1r<12TiYR3l%Nyiu_cFUr+|Cc)}VE7o*_ zsJ@bvTGgGoLC7Nr-PI2{#LaKB6sq;8Oz?z8A|H*1%nMF4Ab(xsQv5g_3n$c4rR$Nx zX)#e>@0ulf>^kyDR}=z8NNT^z#eMHGtS)yid76Wea)pdviA^$<0R?Jq*}v@^!@Fe4 z$^N>Qy*#ceTf)8W8r{TmV<P9`(Eo=0L4MM^6HnvWF95(k&OVWSzN`RjBepupa(^=u zow?z&{`-5S6CbYXSnL^z`PDg=B_caLa})U-*K>z}bu|Gf?AxZe+>i`<d6fSi-3HP1 zRH1fb@?3}~%L`CZ0wpO1|Iw+Z{FClD$K8qF|MJ7^Qa~P>pjZ+b8Yfb!Yhe<}1j=*< z&aHwecGc+u6ZfA@PL}{WpmefuM;7J%+D)+c)uXgl(sN_|c~gva`y1;tDoO5A&!wvH zGyZU(jHH#g^YXbef9?C{gfekiLTNxLswGRQOMqC>1`a-#d~!eVuF~t$Y*^+;L^JWF z8BbS=IJ`FY3lEXf&GUgsCG=IufEcs+&o=wz8tfNtJ#7Qbbb!-bJDHE3z)3qDD(8o; zFWi7sBkMY5hNSOGp0Zc(f53s1sGU$uBR27SA)FgA*QVO--pv<>D7hLDR5cF1d$(RU z$(1a;ee<YAq_VmnFj0BB?3MF&c`Mxyn%@6yE~&UXjV+=6m5|8IWaqEjNMT8sw3;?u zi0KTjyzXjXF0GQM%sXwE^<UTdywNvgR&RRVFToMSkZeFfb@!xOtZ;bzQ-M-YuRr@! z$(MxQE>&spj}$m0ge?V_EH|A?qD_NfFH-=*-XG_a1#UQrX2j76X1Qrh+~$a}RGs+x z*Ny-7cZgos$ohsRNLsNT)UfO(XW5{_wDjojQ=~PsN1ocuvq_Fql5K-v*1PwJGJl@5 z;qSb)lT$K!BU~bLm!Kt`L5Fr+#dfPkC`auUU${4s;yGoi2@PU`nSG!4I%S$l`9r}9 z5@EItxgZ-xNa=AyN2ezt4xnU4_Jue~0R*BN`K6lEdpt=c7KDViYKDE-aLH<cN1QZS z?bqp#N61m5th33q1?E1SvTFjz+?KEkXhW8=WuLu9Nna7A4PU>=Y-iJ<m*o#gy))^h z2zO|PZz5j7q*c3or*cWZX?|6<td;uSY;fU$Z3$P4w1T&A;+t$e=SYRAjN};5Z_FO< zWHs+Rv`5|>6{_bB{GgRGJ5`*6rm3C#{_{8BqOoCELKwTGa_>(D!*(_t9jdnC&-#Q= z*O3mK+^WD1_^;8KpBjcg+626RD4#Fu-A%nKFat=TTYc-VKC-L79GKp|QS16xjuEiC z`|9wh##c2xK|L11@%1iA|6uud*$6xE>;>&W<AG&E%2=+x7es*Y={sd+>;yG(u~JTD z@cTHq1wBsp+jpO|$18z<Mrw!xSbbXo(nu4f)J3_6j9UN!Ry4rH)mtOFUf@-Kbk5HB zCM@-IJrwaLZjGS}hn{FR6m+3*O-|SuHd&%SCuw{^(5GaEY4Sf6x+;Q`n&$Yyw*uV> z=9mV`QDDwNCtO{48jYka1Eb@f%;-zx5|1NT{RfcnURdf+0?wVthr>kXO2A`b!U5<* z`UgAbl<zM#kNU?u9E&_ahrRTK*ITJ+b{fi=YIuj9Q9HR;n+6enU=jz61c&_#yH$&z zC(d{(y)~o6!y0a>SHjYY!wM?@TVBCVkGbK?Pv}QxOUK)@ucHlrco5{$s4;{?llP$} zc+t(v_BG7~%04N~*hWLwIBX9vzBF;(R?IO?sZ~?}G<B+<EahM+NDY1?-@&v^jnp@9 zj3eONI@7$4PS5{pWktA<SQRL=d~&XS;@Goa-SjugAq_P)U02HQ4koosJA@dm<!(AJ z>~gnNW!`t{2y7{*z^iO5f5+0fb|G8+oSFp#6^GR<eVzc#3{g!_%M|?=h_iHeR!u3n zBs(xepa-&=nf_bNV3)3S#nqI4e2-Hqj!q4rB1@Fs7L6$G#wZa!>O*%mZ;Pkm)I>VL z{|SDH2@GTljWj}qRhK0MKq-$gZiaOrNuWf0n7qJ#sfO?V;DH=W7)61W3G-pZNc)RC zba(gIBJ@zcvJ^~kEs8@)$3sCd!j_{8SxB4MKs4=DU;lm219lM|m@OP$adSWgRC&a_ zkgy;wWl}=L#2(nb&Y&DYxVCR?i9tz@2&Z@y>or=V^f}_Ql6THL$}Vf<kg1d~ee*RJ z4Q!}pBsg}oL3-xV@pdJ3bhqjor9`?MsJc*k{c}~kjgB>?zp^l!-dzR`>ZaWWV{pP8 zq(EDNE-(vQvI#sZYAN#qRJS{+D-8Pjj|1*Lh5IPx+Ru~S6!E+p=Jek8C-KqY0mC<N z$Y^9?9$$xHVP8k=iSMP^!M&3eI*q|aQi)my!aF;P=9$nPiM^ni$@&$Lk^iHn?wVzJ z#M^8Oq#Tg!d=%V!p~xp<Q_i00v+~5bn@qnb&kDPnvije)(he7dPOEz!1OOps=(l~j z6ZBxSZ1(W7TygM`343GzMAnS9-06JPheNw>bV_{?>Tbp}n(|?&Eggp@G=lqMJ3&1Q zp^VuZjHPlD5LOFXKrWKGUwoy0G*lo;lCOqC4IAY$3=ToyFtv^50MJ%9vl~bSR<G*F ztQnP=Zl4QHDAGXzcYu7yBFY!sO}AkYUlT~KWt0zd(~RV5cVlK06JByUl9{Q;zc0ze zl3r%_)lP$OH^l`^FhK`K8*_F;!Bu!5JRIgV`q<jyfN+E*$Ej;`+0OU{BO)p(jFlEb zxL#Kl-nl$0k0o_6c6)YY48hl@+eAorMhnvYFAs)QZ^B-0XtVeG1q%SGbiIZ1(~VQi zj2lq=CWE8Gt-nu=X1T;FHrbxbrT=a~4@-K-n~hULRKDhVI4#lfbi`yiU!FdIii1q7 zHWu$xjmDQ$-);ZTwWa|>=a(p#>k1#?&ttPZ1Zm~x4i7;P;q%VjOsDawL@x%|Ztm6E z4UM4)x@`K_=lid=A@_D-%jd&@FI?T2Y_T?3K2c0b(FlumVVqqTQ^qE(6<$4ItBB=& zE*lZ|oP?UR{fZPaPi$$eAoNdL(vJ}3eW9TS;*wS3-$Gc8{Xcl#bcbM5=`icQT09oh zxY5d_tXMt-90nKaAqny*``yo}f5Fk-a>g~s64QA+#q%F-sEmjyHgDK)w8U?}z0t`t zUuZR>4w=8<=L{e3XVX@6Jq{_A(S>zhMHbpN@LN#Xt4jYi@Y?$$k~4B)?(1Js%xnVC zLMHb9FgldHO)8{G`fTXGWBL|#rMC0yb7lN#S%kqxs(o&)NKncSefK|G<i~x5`J&dA z2q+|Yo@b-_@4rj11M_gPNU!uuNJkH6iaG+KeDod+%1!O1D2X;06Fa_`<uk?#0wedE z?90ie;%M_dWQ#0$4uFA<LmwX?mH*p5*=5s>hn^_7j=$;cxBAQ9azmu<OtJC)8C4;( zO}bx-!#0uv*d!38MA%J09zQnb*k~4&GAYcQBD+1S$$P#pXHGMGcl%w{fKNq9wTf=n z6Tx|A)OIjT5xDy<_%tNTbycS0@$7ph)RKzly`bX!=r`Iw_`VFM29weT(;l=9OylnR zu$Hryu$l%`qk?Uz7R|jnVq5n+okhm|$0EYXT3sZy-?Vveb&$HjnQVwSXBhxyAzz1H z7tYHVe2Q{F*4@CLos&4>RLabc@#tsLP$Hv{|8y+(-yS1Pa6k5M)ZkiApzdbZf3E%c zGPB8>S^9{<$NJOpar~?71kVpKP(mSkXUgwigy>?9ul$&wLyfyEQ&OIbA?-$t244`^ z(0)5BC=r8mxO8sXjfaQtZaYEBCSaM4o1C;b-s+Idianl>62W=-{X+MO@cyPV7Q`Zv zn}LMjOm{;~Gb9JKGY|dR@pi@ZaaDW?A@VTf6R|Y>1D+vSr)Fq7hpr;uorxuQSrmQw zN>hu>PyyeM#m1CSv5+~%8WZLD^J95EoGEMit+H&ICcOen*l6j+eLdC`rBPD2pOkl( z^7)8~bRhIttP!%u)?~###t}`7<KD2hvaA<|yRN{^GCoW!xg#cnpRf4%rx)~L&3S}G z4pdOUa!KZ3kHWs}{2RMy@>7ZJly1YddhNF7H;P_=JB8Wn_oY_si_%|puV%D~G1S2y zgMH{uT8Gdnkpc9%njch@L1h+Enpl^O8bz-^HEe1a&wT1NbdrC~jTFom#XYp**+auY zYl(@HQ&6W<b6t0yr)RRmm6fJjXD5#R-CuKB^V;`4e;jWVk7FNtsDX@6i}CARjy0SQ zCcAI6#c9iFdwO>EZh_FRP+x9VuW^dYHr4C?$}8?jIouqyG!*9i2<e`0Cq}Q+?$oi< zIoT7|fXi0`o=nKqXW9`|U3x<e9<B9*Bt6UBpOe<1UpK_@zLd5PreST@oV_XlmwYLo zN{R~}v0^Xbc`4FuBjI0mUE7_Z5!m!ZiGuj<nzWd2OW0qlc8Ofoy`}8nM|tJvKHBFm zkA#%Jz|q;0BB{%`7;_)84ZQ#LL}?Iw3@41J&xU0`yd2z+QOv`qEznHq+t`CI1K&ni z^QPS=1P{siO^~oO6ihjj#THu6&DB`+8DWR&&4~ho!|DNCW@GFO_Pb{MzAx@Ju7%yX z7gQM+>7TWmR4-qo&Z>no3Z&*6i-zVU8!BL8hhl7(D3s$c!&wb6m5WizbJB#O{iV@@ zd^I;GCxfV6n)Vm<yx50UQE?Y}*PDntU;lhQm}(Io_)QQwkGN2vGVCXf7g<_q-n9D= z+GO(Q_`;-+$PSjR$|X~6bKy0T$>zBQ-#?TRcsoBkXHSAnh9jU~G5G*Dk$0{x@S%}d z2i0&AX^3YhgJ88DtE^aF6d?xh%3_86F80%u;gvIOrqPfU>Gcjt)y8Q_<8_<fKq&p@ zg@m9hw<$~o1IJiH^Bi30<D)%xXbLr|;7He~+?C`nqw*OC0I^Qqd6U_10EDXLw!qY= z)Qy0&#MGmI2%z=4!PTRa+4|8X=XjJ^0^Ug(&ntA$-sYEeFd2D|bviX4QEdNGDBoj- zGa4$>eWST*EaY&HhqDAi#2T6%ah;;iV%$9+!~NPWC~>MXl^O@|_{{rE>L>ojM)xQY zjCM`X$3mN2?r@#^5fc<hB_qmHV8s*j+M;eAFaP}PBJnMD#UL&^O)ZK%Fjs7sj|Krp z2B`RD*Z>ez&rFFb7@w*KB>US!tS|HmNK_vn_n2gt_dVdiiP8%;JY5&=HXdE4<p|$r zm!z<v_g<Wd&Z`_uB?s52;X(@&H3O-%?;`BWaC<f>A_}aq)Strezk`ZiusMCdu+u$S zjk3r|YQ?g@*he3a5S&a5ykwt7GU~s5V$d&V`orIm9d9GxYv(Q}vHhoK>Rw}ad(`dg z+Q~c#j0-_PDRyWTtmJS3waJbUw>$esRAx@co6<1(58hzO*kfVsFr<>K(4giJ;F2Y( zBpr`<6xBJ$wJ}G(5nzeinz*06IIBe7+%{a?rTixv;NGd{DXOZ~5zUs%X69B#)FKfq zA-CJe)(SSsMTK8;AA49)lRi@<LRC#<TR0s!{VF^P#F62CFahWxxQ^In22Eo<hM%_O zJi%gA62EapTg^pny6-y5o<`Smdy60q+H3#)_5FL=#l<Rd3Xs<}GeVXw%J%y~>Gx05 z$}aA$T>NmvFz5lxksvh8&}x4q9E2ryWgy3cz%IJig#`TtBD?1UgZy(FK}7;5d)=sv zMe03P#sFzPJ1S*ZaQ<ldBhcs6$Q>JKs$d155=rW3V{%80%6XRbDnjs)KA@^$^G$6a zmt+`3k&Mxw{@H$N+b@8Q;lp#o&h~&u+@veT9Ch{drPmLW0&6%ieYZRvnia49>N1WN zbuw%OSVE3)Aw$dorI`<3&a~!ZMNE3I5l`LvDK;?e0eo;rY%srr*rl66$$om>hS8r* zafNgmNmy`N3?x(Y4$?aDSUzi=Y^E40k>j;b==;Zyrci=zJCrsPizIQ)Cv{Eoc(4&P z<S5uasOLuyWOUS0wsqWm9nyQnH;Xj@F(rh~SdLCQPU8~uL#^6(w_o7*C9>0x{YGph zIt}rgrFdxB1G7&i8XbscP8SQ;sfWsh6Oyo?1+CIaAV=c`EqtFYjJW*Z2N`HFHGDz~ zvaM!9hqRo;a($_knE*l4BFV`Q9L7f;n%5)3Q?x}W#m)pGRD*vk2<p;5TMn=QigMGI zL*f0j`<Y{rlH$jtx;JEzAH{V<vC%y=EV?y`XFFOYpM$IMf>Fk9@W<H9j*gL}N7hUm z>^3JyK2~)=+x2QZJkEZgXE4cF;zUr5M-yAN#f_siJV-GPp9{?UYUJJ8eZdJiQMH~| z9w;tTE@Gw*Z4gE+jx0_JIZeh=bct~}(`fN~sput8*8y^||J@`{F`(Z#2xUF<V8|$p zCOnYasO|V{eS0})-9ITUl#kAdxdqV?tk-~ac@j^COl_oZr9alZ?>FTrjo3n-Knu61 zf1kh}PIW=5vSe4hOB?z7xYANO(7Kymw3LB^5evb}b9?;5;^SnyMOVv=D6~&i2m0%t zZp3@~v)9Rbr7O*}6D6q^(W&Sqz^ry`j79`t&<$o{?|991L=)50jEWWyVh_hW$d2GU zC`h~Zdp*{_9OIfWfVhVD-uThPPCZw3Z6IF*It;{(S<2CKan>5$n`<D)tZ%a(u;%kr zkoJg6>jn(T%QmV<voT!@F~SYSu3lKckhr03I$QgWxdIZ&N&n4(DRm7WX|N0(3@bgu z)04>}_%Z6Y38jeQH>i&=#9ot=5v!auYu8Sf8$SysAM9DTeliT%tP<8~bjE&Y6pGC{ zpZcAon2gFEP%i1E%pFY_ItGh+h1=KGE&MS!z-x4(Un>a^Bpo=%DxFvj5na7JEp+lk zIR3LGnD^#-ZA6N7L2myCEOKS4U=h)S_WPc^yw^9?Xc8ynwUPmfI!p7+6>iupIX7~S zVoYD;`JisI#knnR-P;3B?&Bm`I{>n(6^#*)x|^w+=^TJ8Cx%~6BF56{!0C>9EHVZa zsl}Se*tr;oLDq)&<ISFzFhO-^D!1;QW?}R6h1&Z~mZDep8I@pp#ez&WR2gyV6bi=< zp51)XTmHbk_5d!7UL2gyOWmFL71xqzzVcfX7L{b04WzBazL{S!U%CZq{NJNX40DSf zKuCcqsuC<huz+qt1~O}u=Qac8=hPp^jECr}x<4&B#q^RESB)zkhRGM3em0*n(dM7F zm;?u5et0;k;F_ybVUjkR-=ahlYf`SR>(R!sjATLE8mg>tPuk4W34WnP-rEd4owV56 z)x56F!40ISl?lJ&9t(Ug?5#K40E>J7q(H^_gkHhZL!O^YX_Oo74$&X=o&9aC@w~N? z&)^<jVh1{}_Wifk%-X?O`Lioq)b_rzenj?3Pd=UIce<QbQ`*ia?VT*JAX8PbkOmpD z6CnDu*Kie}yzNgN$IlC-V~^eydcY*WG2AI&{3xSX7O*g0RLyPp%Z>I!xfMh;0A2=R zW2z0rwF%0~UR+jm_Jq=riBhgO0Ff-X?ySn+z?=DVw9DU3ip&z(i33W!Slb*7dz7_$ z$pw2Zncc@3sg+%&dnkXon0B{9+)@gCgX(1(OW$nI{#za)*BBT;CJ&?reW65KF9&n@ zqOATAlpVl}U&1;-9tMQ!`lS+vnrA-|k+y9&rv0tsZNb|sP-pg<rC_^DDWvQa@jHpM zi&3eg-8c#9wb-B!#Y_p_WRe_`urX+Z;VP50{28jQ5}!g5Dn|dS!0H#&c=3R9BlA)t zew?B(ECb>lK~<QbK5a+%k5Cx>KnnclL?;zNcElPVaUe`n?mMykp<seYfee^W&{(eN zb@S(6yqHIbsU+G}I-WGSo%8eOzq$j2(vsU5XPN(7IfW<;OiT7$H5Wz{f6uV4Y*Vh^ zehlfor$uex(2!od9U2JvgGDpCbev3louqQXmC61MzC<xQI`zGVFw46pZM}tN`j9pq zw3OOAJC2wbYTzg8MXY$anG)s~xpz9dBBa4Lk87ar@+~M;ItYL-%>VBBVd9$*qJn$C zYthdk8@>?B))kJm;M87D4?a$I{F={B8w&Kj9<OXY=~+^0RNWK=KefJ$cmzs^*X#rA zDz1JWl^I4rWKd#S%n%c!*(&6qxJ}n2{R$qzMfEj%H&MuL&_$sv0Z6+S{^XT0`t9{s zS!K`5<MmXPzVNkgjHzwjknu^iy+UjCJ9!WJNx6M>OjI9NAGPWcR9KR5-~fb?yzYOX z-)>U|574d(SGg%UGZ;*y>yH(Tyn%uYhhz_i*IWdP$4O!$oIVI;=qC{h=kt<yWVJLg zx811h41fq67#Vx6@h3w4UZ3UVlKqL5zMd$ML{Vi^n|vIT@_qMy@SOV1ITd&P^k-m} zkQ%iIk^!6#<V!@^LqsXtkRzrz?+1inUG?zKqsr?3TbCd>Br_6N_xoB~^AzVQ#3#WQ zV~GVZ?u>m>AJl9%-w6?f{a*b--eW+N|5V0dBx?j(CY=|wKM7cdH%&p+0s60DIENKV z%Wrd(@F?{D9KN(5B?{^dfIEpe4f%_PK()RCclyjdFfE)J1u`NC<2E`JWk3@{qg3xt zMc-B<UGEaarLgwhl6g5UK8_jeGc1f}mmhe0Xc&?aif;4uxQOR=-;T7m?L=`fTi}rF zH6WiVB>afl(&^ht#=yWZ1W63rXed{39(BKPSf4rn@3tGKB4?=xr8sG=g{XuUJN-H> zQ}YjnF8gqRpIn&>Evp9?JrsD}yl@cIwW;&KOZfVb;tN;G-$pzAXu^*p+|%46((YWU zRaoAAs_X+eP-I0bmNA4zqT64%jY$uwqC1lI4@18VZ#xVv;082#zc}s^o7{Z2z&(+b zH{CJxF+xo~^9+w?3_?WTyv!LBzxqm~GRBAFWsGR#b;OPxN{)W}C)933r0*e;qwbw~ z?7;O`j{p`vn#h5f{mA=8%aZCLvU=+;ud0*eTEj(%dIxd}q8)2)nD(<(Z|}F?EUxBG z|LyMTVg9EkmaIMC#6-2rvoC`>=L<A)DQN~Co;mZOZbwL12uM&qec{|+`5kuvq}~@I z^iG>e3~G~=-#&>E|Ev9%Yu3P!2sr1OiC{;|%f{@2`s$Q~BIFJ!m*`mWX1Jy;A$d7g z9m`%Wi=&$46jMG<r2CoW^|QgW1YJN!;!B4hd{PkSlc@6PuLvXd-3wG3(VFAikM1^8 z-i7R11Kr9_)(ZS+pQbY?8~s?lVQV)cn7a92S-a|4w<o*A_Eq;bz|cj8C<ytE>S9TR z`7PS2<f*bW`4GtQ$Jn4=E##SNVEw;^(TWI$66x;qPq$wHF;~|+j=B2h4;#un=n%N? z7r1wj7+7PpK7sY)m-A&XAgDbb%UTz5NMu(aJj!Ib7S}2yKsE!4KHq3{c=MY`uq8+G z&JPMzduDR)jIP9Sz#<e}cKD=C<s%6^32sQk-6i+eA^ITP(Kv&!jM)l*qiv-iRtBg3 z#N`H4<YUg-i#Kc5yZn^9w!_)nqg4~@G6!@AEopijVb-%S(`rTbrmnp`P`6{;p#msl zgS%68L+d!rjm+X^zy|fmf}h^e@~}k;Soce5Oq`WDZ+Cy=US2|^nCuP&Ja%ikBGmPr z#W7C#GmdT=|66N50>ZgVOQ~437}3N`uneo$a0Fa?f|1-I0;w_fY8o7YHP)4T#~uD( zo{zyuK^4)Az7S(}8ppADj?es;`C1xv@4qcBwD4Du&t^%mlD-a(oAtwswPt9=_12-T z(ZXQ)*3dwIjHNaC6FJhT7rqQp9+ZuS=PHnuB&-$PVq%eNcduSO3~*R^+Bvrjaxx@e z4j^cRcP=LqhU*uUq@VZU(|52EM#7h^<}gy69MjC;KS9$QB$~l#4=`ik(7a;?>C3)E zrlD_jPk<mF^x164`CE&@_lgP%{R1&XF<wP?D`C2WO<VuB{|!>*x)nw4n2)BgFj)gn z;uA`qEIL_gi4tGhAwZM-mGEife$C*DaRG<0VGntbB!Sgf)~5vk;u6acpIARK(w|O< zh!!Hm#nsZ%iq@505A!FR;JCTear+yih&nVG{KI?f2Usm7x~K1rFKH45vCUH2nka|? zA5H29>##hldZ54O1Zwgaysroz<~p@)0kpzgmYRafPm2Ik%*{V$zc6u%P?agN<d<5M zF88J-r0LMZ2*!+zgXSNs-SLyq6asmN<FNi8PiGw!RrkJqa;Twe=$3{dq-*Gu?vO4) zy1TnUK$LDoLQ+7w45YgoM7r}m_<VmaYt7%Bwa?jm-*Mfai^Rg&J}wPMm$WxmBxMcx zyexU{T%X;B5|=Tlr!W`U4tGTC&LNsy43LsS_#7aLN=ixdwbE-}57YlUzCP2LT9pn3 zzl*}AN?crA+<0Fyl9@PWG&q-<l@$#D9}2L;s5p#TMt?T`rhJoBwSNPofZCqG=*aHe z7shuS#`gY4)w<!1(cwb?N-TEniw#+mbW*_g8d{^DM;~5w|4vp>*8XK1nQr$dZd`pl zv^&Op+@-IXs>Vq#!6-5UEBth*vJYRN05|M|Ji>Wp`BA^XkF0`By$0*iod^n^6x_lo zwnnxE1zJ9=qev+WgPt7Hu-{Lo@O+)e%wZB5capS>QiHLyv$Q&_O}cBLlqLc0o&EOO z4WGaM|JS^dC{gUWnv*!)rY$W&!P{Z+S6J6o_s40mnw-ftJYXPOKKrDya}U7LqM>?{ z#{js;0$`9On-v*}9b689hTskXcv?6&$!&%4F*0J7ipP)m26|EfPzvdv{=;$ZPlCyz z+e_O;Y#fA7i^tUU7)@@F!r=PP>5=~FKC-(JC3(Ip-Kd@y0c3_boy1Cx$`TuRlU&8A z2F5cx?!3PY2ie|5rKnbSe_h@idOwRPpU_)sBi=V1<Pg~$K3ox9@hC~!v(}89*1<Vu zUqdURn3iAYS0hxe*M{8omhWrKzkAggl{_psynSliKI$DSafcz@O3l1evz`8tew!FD z(6$JW8V6g<_OmKE7^NZZ>S#0xIYS1Tp6D7;<@GuOb6Yf0ky+qK0L%k^iFn{c6alSq z6aJ8`$Os2wQan{(<x039YgI{Jc6&kEWE<<#DS}B!#Xun?#WRec5GI``DX6f-vE7AT zqn#ILz)S~v@QD@mHeIH$&G-_c(E6>fK#fc6AS3Yuk1wKK9c0!OQrb+OaIG=Wz=Rz` zVgCNeSw3kW?V#YU8pV?;L2pZumFONIkrnt|9d2ije*G^m?xJxPLGbn3r?A`F0Wci? zi^<^`6`r5J%pU1E_Fl}qPEz9RnDl0z-zdB}e0UWO%f;3R7@AcH?bb2DRPVJysyKf4 zK8aFve#oaTGUJR>ZtPEx9NrS`B|)Z{VR9J0%3aYymrKjxy9jyPSB>asQlqxS#lA7b zydq_#TP1;K$mR^}@Y<^D%8xiiDmU!oSB{c#>-<@5JXBO^&;#KjP7#$2E<QIrj>C~f z{P;eJ(Q9NZMJQfrx1w1~QGCW>V}QWLD!^}Bwya4<uF1vz>-K+Dif@$g9a4Y&w2qWy zd_NuNR5&RP$lBwbQ_NxIdM*20_j3lC3GHMI%ki#s0`JaYV^gSXRr$^CUusDlyWU!x z-;`;|yYp{qBE)X7%*&ff;eISN;m;`NhL4BRdD~oZ3=qo~Q}j7G|MGCpv&8#Oo$w$+ zj}IGgFqN0<apygh)H^SKGVY8}lW#&@hHjjv_pP2Pu%>t(Q*)m_Da1uO&W?8AdaCXz zVM>t?Tx7>8asQSUafDoFxY}AmzH4BH)11Oj^|k_u=pukp(`)yxb7`EEqEvZTW&QQP zV|E_{0RS%chajRP+9fVmztggf0#n$Ge28f~{Q5(BF5#f|&quausm+tY51(RnUS&ad zeQ8kvDdRU>kSaH78fkIt_SP0j<2e8dvYw<nIT^<p(o2zbAuy!`*|3;@iw;9M9sR6n zgOsIe{t)ySmfKPO&03O0)^asJi~-s6?JM<H_>&2I4?D*Lw*n<=kqt<<aVLJx7y8&x zd|fVs>zQudV<(5bZJB9(QJe`j<RWgy)zrg@WP*6akMz8$uyHjpdUee30`B|M_~D;F zd9ly(p6+eR%*w&ZhF<?7qYNDANBg&F<c*{t;mLeQmUnP~`8BAXCS5mt$p))@d)SK> zT-h!Ot1)WD1IWmHl=$;aRzHaF+vPsf*vCIW$UwusuEF`kE`PZ=G7jV{dT&*e=e|VY zdTz~<&z!ps^)Qz2gm*Jpnny!AXe9%wK4-gd-s^M8qfrDO4du+v?NOhWc}nNIAjn!K z4&IyaB$F$n+uZXN!@@&~_w~Mcke80lI$s}~x&NIf{3ztnW9Zaj#j(Z<9+Q~=I02-u z<=Cit?A6<;nSA3G^dxHMmUB@FRN|BX9P*_>#QV2*Kxk)2^y#*DM26s#+Gu?&X_Zym z?;#F6(61lg36V~I8Yu+9eR|zVx#V|_F6RQ~L3G0sMsvbjP#c?{A-BAoN{WFcdx9tD zsI}JnJ$9C(dOjjl$LHeZZB*$Ps`1rvg(h@Bri{ba9O#kdA>Umv$wXcIgH1ZJb_?<Z zTng(P=i0oSBATTyrhANk{g-W1AkivF0W5lw)MRDt*f*FbEN@COD(toCv&$=Va&gSm zwph{-w8h35CsR=<-Z+xQAFtC(dkCKCky60e!uaeSCNTeu75QO@mcJx|gF{YJkcMgD zfiB`$)8G|Em54UkPd1o;-k>?lo6jL*(>VDhf3BGPPH$ylQ^kqHlSq@90~$Scrd#wH zbHW(}=TY8%K(9vcQIk?*X8!}o)84K-G5xIgzf<e@7pk5<GiDfS-+benF~Bt(z0h>4 za?|M}4Oqvquyi3-jyq3Yo|eqY_m}Jk{V);gkb>NYV$?rk3&FWdJeb<3Ua9PM(Dj=8 z^!ZZw_}kB~sXvn@sF^Brc<<@79)w1@I5R5X{}qjO!I{g}?;4T<FQzAjdZ4)cnUoP| zePRZjLmWdOO%|vYwkh%LoMT4QJT$)~fzgwbLGj12O_CUYtU@10ueblje=|71g5uJQ zo*o5W2`lG`b@Yg89Q~Fjsj{N5L6cT#yb6B_7XK7#wx90?-sOiQ<9F(jEtP&dQTmdB zVvC|%plNo4)k*xa{I-dRa?Whwp=(^fD!Dn#tZ>f`?;I$!?mQgFkAyM0h=(2>^^P7y z>eZjxd25u{aed1IuM<?A)H=KW+?NJU?>sEa0Ynfu*xY&YJj{3{7juU4xi<PpXDYn& zj%~Kp@n$9k1PGe{1Q@D>ck^Z5;6Z3cWsw@ByGN2JFX)W%EJnpAjH1vGi$eOZ1syaa zmp*=3qv)-jQ_x5K)`p*5bI|uowLQ3adC8V)-HJR;0Eq<h<IhQisAd(e<Q)#{(gl#0 zp8x|P@B5gh^pL%n|689j+~n0vw#hp!1`Q5bjyIi&jc?O0_3kM7UMG$h&!dGoroSwX zN1|19{3KjPXl9DWh1ENbaaa}!%NA0?HN~qG{pgA#)q}GDCF42@i0I~YkV@k-=6Y(i z!If7idPmbILP7p*O+@zFyD6h{I8K8GRKTg4fS`s>FdLrl|5sU^WF(GM4e9aeW*V11 z%Y9dJj5A6yYTBvX_W_Ep3-Z4%Dmb(iwGoLk&N9S#Gti{;dTUp3K(7t3M2?&WlXv)v zviWgsM6MZmsf1E5vB91tHm|T#Qk^CxS^@249nj=Hn62w=L7S2wTx6j5R}TFsE%DKA zF0@*&uBXqawq7Gaa3h|l*8j$}xU`fMvk&kIut1>S_a-c{On%7vMeWEZYo=il4s&!V zE*PgEGy`6R4rfO)X(VTbnOcJ~mcqe-JTRvYwwpt3e`0tQ;DRw9wXU{Uz&K)Xf!a>; zYxRP8JTt2MLuDRR-lEtDFIKvgo(Y49t$b3TdH;W*`x7R-63#h?HlAFoPGz~~!vL96 z7Qrknp`y{&)m=i0rH;<Km<B%p-bmt8xlvSMSMJ%9530~}KERRjuF7H2wkc-=b+%vQ zS~}?jqP^HS1s!WIuz3#<cBOqq!Sp0HAFT{3!U&VyN%tLfJj{Uj{vwpnpuLHVr?fLO zOi(kJp>9ROB;x}kqG0ts+ZU{P{%Me(^5$7Ad9H&C#ROXxvIBzp-KDnXVa|f9KRpo` z35*fTCA3HY_>pfO)he<nCF8GGkzkEyk7-OODPb%5FWKovx2STh>#4=T<O{)J1PdJ| z|I1f+ky$P`$HjkT?poX%3?FHQ$S>*MJ*NAp7_8lA>d?JlPw2%vnR<I}dsIXl==o>* zm&mB^YKfR;-QA!00Ot#je^=C0Oz?6>)1q@P<_rF$X~HsCFZO&50a$VH7?2>)F*6TS zny{bQGlK0iej&c?b`c#dx|%nY#O(bw2|ZZpTLpiY9yW`iaNN`Ju@`GsxhyhvHT=+7 zge%th@RoP|aZv)bh?rAm@P-^z4$p};rT?ipKR-W|o~ft;Qm>sfcQf|xE5pAHw2Fg+ zphL7TYL__$uQ@rmzHV;Od<@Wq*MYffsW1>GwI3IS;ZptC6FeN;)6)oSHtGLREeFPE z!8#Lnf!{nXv)^Bim#Qd`DMX|aDXI_YG~|C0e{(6FS}mEvE{z(46G32rWA$e2+i&Gx z-+ucqJo$|9dyx*GHvi;pE!%FpYWvZ;^KHj}Ct##aNRo|d5DyIcH9?Lgx2O5zFq85= z=`ic?SlIdZ@lKsr033C;WFlM>zkKA`B)I^7+E~85#o~-LQ?Brd7Ow=HNg3i^-4t}Q zsKi-UDOkP@kQU3yU;I^<qlf@Pp0$r&%iY27h>BF7uj=nw)5$LrRp4_F_>co-LL{i+ z$|m%MbUpVc(W-Q+LlX!4`_}+t_dx)M9O&`dhr&6X-*ogx;Qh&9WPw(VNk=+#>!K&> z+)Xjxup9#M+QX1H-jNFautMT$;rC$de6A4HW=)FM;c@JI)K=$ps;PIfNLL<;Q%}Kh z-eN(!|Jt2~oP$x4+#U2jC8iCPN)m~%(j@5fxaf|!Bo+qPR@nF4_Stu&1yHTJ0E~Ib z!E?mg&o^?Ewz}q;U8TV)A-(Yk@9DG~YRA`=769TdJiv>F!C>&fbdM8}1!dCU&$8*p z?NZlUCa<pi%;m;6#Lp%zK*%u#0+&!wtW!Hfh9%0G!rM4=Vj4VTP?O8rLQ`f<oEXW= zj>5hSh|zl|brnw>NlCgAS?A7CXuD3Vl|c)k-(GO|KS@bXR>Fc;Bl8+twZ+HmhEz%& z?TJlMm3&ZT6!RWc{{lKb6aX<P3z%YJGEL?;clU_P7`IVAFEy4Nx}GWQ$T|d>y`cdZ z?DM-npHOvfHM%|-q#FCA|3w3D_x&l`78YcGx;n17nEu&<TVN|)^ZS`G_K6JzD#S#3 z-WLJHZG;HfKZHYt7`@a;!I^_gyGxWYH-S4l`i4Jz^b6*wh;w-pyfLWKHAbAPs)d6~ z#CTjCql-o@fP;o(1nP@S0YFCLlK2=nwr!q&4FH`5d`wKtY^xjN;#)-h$CRDfj9G$O zW>d{o=aS&<-}P>GZ{Kp51YBr~0FqD;baxSmeIo(G5}nz0gTvspXu3oRMMZQXb^}X# zu+_!Os6P_dZbu$)rY-j}mGrSV1g5Cc=5k9PyX^edDl<al<y4f(1h8U8AmQT^Cu6&; zYfpzt1bBGfiEop5Y&t{oh4Eg&BVchy!O&<7gj-O>W=T=R!Fty=aA6mLq@#cniS1}U zJYaAGW;y`4+107FsFqHS=+94lOh%B*+noyW2RO6?CeMcNvV<-G_IMqz_=%YL6H(j( zDA#xz)0>U;S`j0G0LTJ(2a(y&Lz_*Ch3?1X<WTtp>aN<3LyquU9O$I7jC46^X|5Oc zdcc^o=0)=PBZ9x{hOL&zP0Hc9`L18ws^c^ge1!lK<U?h|g=WtxDjvN6lNnTREe{?{ zy31lEV~h83382q!t4c_gw4*fpls}mL_x(zJK(J!K09=oH0nYcys1$aA<3f|{K6P6s zfQ8Ny)LJ#0{-jTMDhqrI@A({K0j=V@&tj~b)!6+}sb#U%u@OHa%@%jFXRkCv)akrK z)d8UgqvXT*>ZeBHWeM`qk9RnDQe*A&$Trq|CglDv@Vq|B@%eale2HA0L^+K3O#us2 z2t_jBQM2f-{vi?~AgQ``6$FB2%_Au*YLR;_x}dyx^+C^mF#l{?@b5xDu;YNE;>ikK zFODe=^q#8mICb;+jtiHN0%-C-?Tm9iegs_Z?bCgg9A<0b8||l9w9WJ`?iUtZQNV+g zexF?M_3JIs=s!382t<c;QLnC|9JZ|!(g);)QMdX@Q<ECLIg&UA`zlN>U^I(^CQw9U zD+^FthR&p9;EO+BlVfnSp_*W|-?xyqc#k2pRE}S(2Zs*g6lxcPNutT)b=Iknz*aJL zq>C#7R}_=K9p@Xk?udMspGq%t|2yLz+X!m6mGge1_=uMK1AaS^jEX|6wWjR#yg~b_ zuMhyze2Ji#!z|Qd!F0*cB%RHx>$y_w|MYN$V_K_?ch@!tMh|>h6-dgt9Q3Pd_6y5` zJf!`R$)Q@IYgGIf9Ed=6eeaA??m~@VPHgGLp2nW4O7EG?1+3>AJpq!GZP3)ysP&|6 zc;QAD6ibU3hZjd6yadDdP@K_BZ9$v2tFeYkN>UPmmX0prc9`^foA$2ve@pIyuIE-d zlz-y_Or$&)@GlRS;s7&?XYUhUf^orqQzkaHK7gWvqCn*CBrT1U>%EQ!_;VB*G3y@& z!#HRWz;VQ!P4K<&#uS?p$p|nP$YJL;;ep9VsiwnlxZbAs!pvs!5k;QplC8MjhpB@p z(GS7h>I8k;H*U3-KQGE9>v~_wA;|_^a}|>Em-<Ny;6%e?^k8nc%I3OAU_9RHVwz(> zY&!u6{A`O0o#)Xq=3Mpc|GpPK<Q@Vh3<yx_lfrj`jUy<K^Cn@D3yij??hDODGB>FJ z-d20$ti(#}KR3U9Huc%kW<i3=Te5eJcKCUnjlZ+9_31b-xF#=<M?r}++m1iKUTv%~ zAN+1qBo<9zTHc5e^3Be9QV|_7GDWi@H6JsqSM@ha6!{BW`IR`I-pHQLH53A9u++jE zr{Z)o0;7~Vvjij+hyYQ-uc87NMDX6xRWEEsvUgvVWcOLx=)G5x3AG$bcAaT__?ubJ z`g{U*m3DPX!~e>D&)L{`dBOB%%u00ny<zpy^iBPh-p+RmLtv4`ZmV=_2A=EfZC*#O zamz(aZq@uENqA3<R)ZLy6ndb0r8BiwGGf@_tIU_Ce!oPIKfXiP?cfbZm&)=yu_z~u zj*_!R!y_8HquK1;=U?utY;%(K;QniwNo=F+hv(rp`n4&m2_prG{?j7vDNfe0@A92f z24HKy3M2%4b$kSFy&QbV4*yO-wN_@e!{F|Evn=r-u~*^`?qpEsdvY*TndD4}kNpS3 zrlkY&Ya~w`D8bbW)ABsUE}Xs%V)59o1=1~OypjYetrYR-+nkb*?;O1gRw`@{JgFzB zBo~K8$DU#;oTUc}q9NTs#5c47qHL$$^Zb*M>o7xfQWC$fV9WxW`#q=F^ym5izFa=! zM+WqCVbkQ-73&s3$K5C(s8+h|*6YHZ*OiyL!6C9q6Ng!07jZny0;tqIR0)5lJd4Wt zMd?XP5z>i7ge>s@PX%-|CP7rLLxCs3kBdY^YrQFS>c<zvU<`^L$^pBU>tBM=0+piV zCe10b;ocoevdO93_ewHonw!ity>hK%^Pb=*yn?^>|J@C0uLyuxz_fy%-fVZF*-5Zt zyWjx=589(UXMTf(0~O)&#G2;#zFJ338xY^C7J!ZJSJt&e{p&-X$R;kYdEX$8BbDvF z#0A2IS^M-~PTA8_POhiaIJGqO>@TQTlI#W+y9do{(TQt~;Y5>WNPE_M?)QFXIcH~Q z31#8M=&@nT?LKExZTJV%bN{YZ;KMr7$X|pHGw1XNP<F{yy8!(95+f{W#c|KfpBoGr znq^>A`-FrL$vD^<l1KEN<sAoa|Jba$D9Mdz+S=O&Y^*#){1J*IofOQ9I#eZM0!g8+ zH=^)Vk~f0hc3pzevo}1nOwzM*`n~zYHbu8CgS~4s^3<lu>D@4|pFv+5-Y$^>X?O4G z)(@Ba6aUN3PoNwAmHy8Q|2ua)p5L9C$N^CKT1NU<uK%U<m$U!^J6ae?{AoaOX5Tql z&Bh=$8pIn~$V4jqrkJ{UkkUIxjRDpL4IJ$d5c*2fD;u?iM_=5|xCZ9tVMw5I)Af(z zk9-|1q-B@2n-p-n)`!BV{vF4v82A2~m=JHxE7hy-O-+Zje>~vpar^qIdhW>Szq?XV zB?P!e%o7dl3=CP<wM$CZR~-Dah%D>DEd;cV<Vav1$`5f)%PM?$QA6vHgTio{oM4(l zeW4DfP)N|FcSC$7HYa@Ksg%4Bu6ZgmBLh~dc5wE{@>f&T&_B97E8+MHX!MaCV#L}D z%^Mym4lV-Qy(<p4N6TV>1`|Ji^ZlF8-9<@a_V+PCSD?G%|1J~<bn^P=4~jZijR+d8 z|2VS&O-BIDamzcXc0sSQ`>(J2JwQ-tb%wes1N8b=a|zMg*+^iTcnW9Yd3th%t}a7V zQptM^JZOvM7l}PsZ42ri>$h&hA~|ZV<R}r!8jtk~frJWm+?=k#`#U_4LK+B@G+d|J zAY0@x>Y%3UZPx!i#yt)4cM7OpDl#&QMgvQm9t+wWEff^yj)MeN+V+o{(|kv=2aD$< z62{X^UP{1=+~y5GN9NjY;M&#t^0FG=JMZoK>)<9dj-H5Qv`uL^_2i_f3CjMY->+oY zIEV8`%tt@Xq|DY~xap_|(I`k~pQ_G7%JZx`oq-UGEVvw80+=VTp7Hw4{NJu;!GC@p z`JQ~*iqNds@8ZMd$`KjIQj}P+N!0JdLpl6Ay;*Zf?<jGiB^p-Zj8E>812lx%*)Q?* zu3aYV`16%6nqGV_f+s;jGV4bQLC_|f-$ALL{?r>EVp9<D1x_%XTdU0(;=3e93D23P zp+MAqh)P1N<R-Z5R<O|1oj)nsLl{)BD~g1duCDUHDm8<zDl#@{d3E=ix;!B6zeQuo zLIA?5Pgji&#C;+TU0o6h2w=-|h6B<Zol?_v56+1{G+10PY|p_Gy1&;Q(e}N^qw&+; z#x;LNJErR**I0*&T0{tO7hPz(65`&boqmAZ;P&S^fp_r!E9lJ}!c;zkB(<EIq-Nxx zM@XM;ez@Mqkko8o7Qjz@AAx;QovOAqo+~-5ZFy~b(bo8YF*V=(U$os-DuJx_d?aK= zKR*8P#6Y=xSs_V{V?9+bC%>c@Z78SAU|Jq353*NO9FmYN<MmD|H7qGY)%EN|??~EJ zMw1d?ao6uMr4ClG`BjD!zUed<njLmq<g1Pq`@!VH&FP!yKcl!<#Dt^>WbHI;@=z~4 zf5=UEH%5?pml`_QviEpI_-GaQ^#R^OhQ9Y*SIwOZ|94gu{M&*C`UV=vO6+DzkRCh` zI-Fh)DE=`Xhl9#l{7ha;ihuz;oc_EEY`8dtPh8I(-BaPgvQZKPs#Zux*j2t@=!RGC zaW?$lha4x^G)nyS&>z>F#vTBj2yf%By-e39@iYI9BvQzz=R4-hof-ttR1u$YNy?VT zjBykOXFCqi??%^k3Y!1lGf9*bNwgw@N{)=$JlTN;nMJf!SOm9)EFOsa&@`AzhQ>(z znro9$j+T!gWU1~h*~N&IcAhIQoHcmuqg<iWM%pTF68}$=i*WcbX~f51s#p9O1dBUc z$4AQ%JH8*ouO(=T#J@TZOmOB0UTJz`BMLHW(En9UU`MKk^gQB=yy)xt`ecu5s>b40 z!h5vX$^-Ns4eZ+r-I~((YBZ+5{r+!5Y^gq<UCoQGal_`<fNNQf(J}&<&(?I1Z2J?? zb&2>LpK<m2jN8*cbI=Hn@*qJ~%Dyci`XCvttO`QxMH>02(v~9tUdtI;NC?lDe$iDa z$#98wT8O&6Wwz$XPaDuJB8kLU=_!sWTBdAGT?V)kSbbc5N#HVsC8>e(H=}yQci_n@ zXK;r_LKoPnb#G=qk1rrY4gxtDqB<=8mx|;*Z-?~mV?ZI(lLm+&#){;~5a!~;ESccJ z)^w47G0e8Zs4V7$$#6-IX<yRd+fj_K7K|1BFphUy$V=*$%X`&@10tz+(qb?_X92N7 znlUJ*hH=pOYX%n(K{&yi7O#gAKJ%}{PG@4RwKDly%YQc|7fvXKT|fwjSCXOS6#f1E z1C6d2f0;BiG}JnLJt&&~w^JR^wYbr>P))tJGIWpo@Ksmqe{k?@*2_%LBQ~PZM7rn{ z%hlU+9|MBfTe|I6cjzX0WXyHx&;}KmO&5J>#2bOm4IHpYC1W8nPES_IU@t63dJ>vv zQxc0XEL5`P%stq*pL5uyieVxbJ`qu9aKUA{Y}8UYRY=>T@*90=SjgKk+CCOfKLYEq zGmZf^s<R)R!K!QCA4~Y6Ec`&vVR-y0r}z@{zu>D}?fFTQPZof7OMH0uJC5}8PB_Fc zS_mr=Lq7V=$<lgtR^Sgw>Bzzq(!9h?9p-33G2IVTHqB)5Zb^a^TqtlLi&FUkDqdQU zk4gBPm<6o+FNW!vAJys?t|GOJoi8LuYqLK-%lygtEK?wikkUT1S;PWQ*@OLrWZSYD ziUIYzbdbmN*v__@uZ%{27+%0`{x5)iT_h0!2U22i0bDB5eU<MUx2a^kxXM$F$fYcg z&79DvJga~7UH>qVwS<XW4p^DKHXJY$;7c=VhddZyb=4-?(1p@NXUGn}z3wrUCXyv7 zI9C3Y#juG@9dyO_b9Vye0>WWXA5Wl)AnV_b`uS_)Di#i9i+;)^Id3|6%=YvM4kUAy zel9P_0B9bf_9n{6DpJ{vp-W~#{~dez8tVBy@KPm()1C8rR6Y$xghR#5*3JU=Ln;`n z?_t=q1^FD~=B_D|*4Wy3+`iy^uZaohK{zaWQ&fWi5`vHt))i74CPsloGZ3$Ck0oAZ zz3d=IP0R{N_}^HIMzBaD?zzv2>>WmpxkGgyb5XB-l&QNJI>Mc0A#d)h`7_;NZ!-|E zfRr~16Yq)W<=>qD#fw}7weV8?qYu=o7n&3W$~cLsv*?zW{jcti7EwZ$V&vm~N{w>~ z<1R60ULyDJE*-cVEnkp(`($pyVWlk?<Wn2P+ZS!-?7P3u`YmJ_En!V*vNwfTH)n^6 zlW#eo(|@eWY!#g(mt2X4?~$6PVbikddP5v{Kzv^I0T0ObBk2{nJsS_m9?css9shrH z5C8m3$T$!AN$I@7sc^lEC3vIX#KW6&ugT+Vs^vVTxh@+P6L&w?o1w0@>@%*Ge#=zr z>GH-vB27#lgs_r^z&Y{DCR)KG;)cg#hG_}5_{&_M=Ei`D9}v<skRh2g;Z4nnGEum_ za}DzN?`TX9Ae+uNS8!pI*s&eBWMpp+h)n=5V~bwXu*k4PguDFz?o%v%^x5DwwLQ}6 zfng)<bR!mNo$7KWKmP5t<rJP2l?WNvxR1x4BOw!H()hYcBF<wM=}-d2K#8tZOhga@ zHZvhx7d5ImEvtNgmu5c_!rMv?gq)_e{<sk-$y*K!#I?#5q=(mmgt@+Q5MreXf<3{< z!f;q{S33slcpy+gQ7@9k1n_8|&Rgc{#Q#f!Of~a0p0Cng75=4gg|rtWV-3=ip3DUj zS)HkSN(0ngt6an7{>ZRJo_i|?RYke+lr~%+R~k%wX6;$h2;C!Zq%q4!tOo@_nDQ!t zDRr8zN4;5cs-#386UR^sGNt>-)|thRd#}39cW=}ad>BtF0*^h8qT<R_EgnoFBPX@n z=g(#|k~5LPsSY0i$GU5P%=I&GaHFnBB=swyJ{wxntt<mOJLc<viwu__ZR@eVK56`E zLu%EB67wau)o+4!|MrIStmbn#Kr8y}6;%>ka6s=qt9h4X0{yw=lMzoiT>dh9!fh?4 z&WS6s+n0VumC=+bn3W}Z{iTV!ssK^*qB9yYE)veNGcB`j@^r$vGL+#b2EB9gL>K|_ zhYK`_Vj>F9#Ifbma(N?X%xX`_0gH#ra452~meOWMsyvQ$%j0{+^{&8<?e}k>UWY~& zzj26(ZQ67q{mLc9s=wjt9p61%19YA!;@AFTNOScgc2$A)V};1)IfScUMk>a>&Lrk( z&@9=APnJqVs6W39z(Xk(=uV6xz5ROnot5>VAG-sEtO2LVfcFwnLj}5uXF+#hoEbsp z<PGurLlD6LUZzEw>8JBlK`IsZ6~;@7h9!T-qmi|DC$r6O#t1|FQZh*!kINL3Y#(}y zUO_GyVs7c*fp8{g6lxoq=wC)=^UE-Jwp4}5DqjWZ&CMHU8s(*W@OFwEWp_9lel1`O zs#T@K?jQ1?PeY*AIke?5@<H&~M6b@Q7epuXEGGgiO|2z;SXp*}@B=R5k_eh5;=}#9 z<I(_;l&#iuP^}{Q@C%i_W_}M7kaU{?rgkqf!)Zn5gUy0El}f3%IWiSpJsw@66bj?n zC2^g9SN}G%oBw_6`Kv5EB<98RRQOenJeXt_#U^1lI#`6;Zd6_n@ksl&yw*TcRn3D1 zecMtZxKR8(Md0SvdgJ56+Hz~RM1qAZPx6HJ4DD_LR3o_aOKbyNSW`{MB`HV8xrW1H z3+~1K6bAp$<0l;Sa`DZ5A@^N1I_C1%onn;UtME)+?}EdB5b8)VFfx+ug=Sc3<-^8N zF`!!V8-Jso<0>^Xf^z3BQ?3m3qAr@#RgEsSo<$O92&%+DTslbYNA2oT&GFDe4fUyX zY-mv|4y|dl0dACcXfPLkRN;-wMSOZULmOfYc6o3zspM2EvSdr|J{WFHUjYmJH=uv^ zdf<<q(4h{!0L5$<IT1g*na;59MMa|XkuF6!tpY=fdYwdcBE_fjw^ik$fXy@v(8oNx z4ZdH*n-=uDyJ9j`pW6pbs7%8y-tF=Hak$pMx$&``TW6v_T8LB6OzP>oJCajYjwiwX zD)~?%4v+X?4EV9X;I5ka(=U3ph^T<(vH11ys3Rnx`T5++i1-)w$VsA=Z<_D}R$YeJ z2G+&tBWLEfB9w*n)cG;lK2-Itr_jyIKdZLA89`cbAqgk)*X^Wu=oVx79^`KW+)+P_ zRVw2P79f;>VFNzz1dFqT|I+qG5TY=5m=31F)W)g(qCT<x6!wC~Hh+exLxV48Oi&a^ zLvxv0+>1VAI{)$HI@g3av_!~G4vANMxxU%S8>_cc61iG*gNXUJnDMQFC}i`95-t=w zH^-jtmEMW4nkMJed2^X2&dEbQrHwO)(=ch~+8>0Y-t!iQe)kv=qjI-??cd;xJCN9k z(F}#pj;dtBVSC3;lsu!Off52zK&AtVjAd~e@BUSFL!OA9)3u=?MWKnJM4`%bJKGZT z%!ewk-g6lomHYP_!|7WM$B#)rpc_@$&a&f4<`!&~Y}JX^i~Fc!r3KnM?^|3CsJ&?g zZq7Q@Bxk84_fbMYy|evW+Lmg=m^HX`Fc+FY{|iDkDsiGIG@MiW$${k7qi+4O&t{Tf zw&6Fudo>;%mE2PiH%a!_y{TzwVd3FOMJPc)cKLLCtLOv2X9f_;hgJe$qDn#2Uu=h2 zoU+VA5lAXoR0Jhu7P&nH-6G{_SFZ@ohh&J&mfMq@2S@_AY?d9CKR<2;*X=XgWd?^H zrYL?#z^0Q+<n_eVV0K(?CrK5U?Of_yNV$CALuSGLmq4c_HQn9`3!Q$K+7_SDh+8>8 z0k^BBBD_6s<_@5vykDic9wrDS!^dfBKwtmz#&zuoR>wmz^<H*u`c9U*E>H_X9c?q3 zrT#W^lXjCc@>d$a{Hrc)Mr@_|Ra#QCEgOr+a&;!XR&ts4LhDYRvAb>*oap#1pL#+w zFn0#@bqa!vC*GaUH2i&}O`vi5yus}$FdIRU8(+$X_;m5-X^-x1u-j?He773og7|Ry zSgi9FAuth*|NaL4V0m>gm)#F?DvW}y+=frZ{s_nZ-lKcGModPTFp{urT`^DRw`*BL z`a^=fI6psehwlaVVJ6TsqXB$S8^+)KrTEvG3VJU1;3&MjDW9#vmx_EHkpAhemAg1y zf>os6THNk3V8mM4`w1Qzj)0I;MSXeZt@Wd-zbh$~1xbCALqd|B^DyvSqi<%73n3yu zY&AH)moRlUB;qFnQx|oZqGwoFc-%$EVHPuMXU|}76m70D{qWkrvDbF@MEgsp6uq38 zU0+93ZY0x&MC}_MQ`pS&fcZ55FQ&1R($Y%Dn%g>3lL#K&<2nA_-$L=qqg*Ib^z<T1 z+<bY`YxVn23734FKW@!t-2?pxlGr1{j=XPM??@YjzKOA}?rNZDFu0hC8w3}8s_w}Z z^;6C|0-PO9Z%(&LxJVyI-ppS8JNg8l4{=yp@(b!W-1Q9LPD&=DBe&D-&EHS&`!9YC z{(h;y;QZSUAE&sXtC<=11PL6IJ+)?*E?4I)zQiJxj@>tdxq3g=G5Xn%M?h&@pVUiH zlj_g9PANuZwsl5B4L$X0T~CMKF|C{OB=d+FyM%ib{^(I_=4x~dUlW$=BJ^j3aB0GL zMtKN|E2(xsav|X!(50^f=Ae1)CwHlJXQLi@ktZ_`cnu)VBIOtYiuW7@#kbI_Ib^-N zZan%@?kjm`M$d@=&%je12d2xla?sM)HxrvlJ3Yi^QGez_yo%ISND8~s+*=Vyd2`^G zXDP?$ulp<;e~Tp?bn3Jq(_VgWp6lIfGS3++ZQcQ7@$fiy1_39ESpR8x0rKq?$dvG} z-P*P0v}b&PpNKIfBGa-7p-Ws<p|3B+fOq^VOa1Ju&?r5g7-I+1u7b-?1r?XE3{jld zJnvbMvwLx=1t5({gx}e^nT1hE1;3YeZ`LvW9CSncEqU<nrKu%KvCGT(qlg)`A~zJ1 zpXB&!-V=-1WGe4b&|&FYyr2Fy$1YxP7M4Ya0<Dh*2IWo}CXW`J#qL;`g9z+BF+QC4 zhxp8HG52w5kDYl-5iV;|^DArG7aNR|(s&`(9AZDdcNfMRZ3<RxoHxx-cWcL8qD7QX zaD$p(bpTD1o`l+zIG@4;ChQjvUjnPRLxDC{K};D<%vg6<fA{;hR9}ExD&JKzUlJ}% zhTBiZTs_qABnpwlX_$-4mxS!`LmP%y2M?u~D&@X(LqRwV?j9>7vs=yybUPy4a_Ti6 z%(Z#mqgoV}ALkmAC34=Dj}Q8=qAk){9PWtsQ;LDFc3t!uaY+Ax-K5PHx}Q9?sm7pD zv;%kUe*iB)yB=+T#MblIo%_T26ESp%LRDQ1@c(s8i~er^E6A#C<#gkyvo10+pE8A3 zGgG+E_e7{&)aQkH8efs(8mX4Y7TzJeq0eE)lEQ57H^*#mwnRs7_)`jPu->`fxXbV? zkF)<#ks|%8N~jSQd908D5p?JsjHVbFV$f)B1sD0?$3c_ZQOE3@^{-z2a?jSaPKRsy z5?XSS=U2Ug0B#p1cOHg`x<jDXqBrFf6Xe+Et@uvj_cZSUk40fpY}pd@M!en_V~^DG zRX&Wm3Ex%J<3%PNNt1HJ<_ip0u)uUGo?TBg^PKXB)MgEnl&@l1&Um=4)^V90AK$e2 z9GT3EeK_kmE1%ku4kc0~p?~CS#;~=uBDH2;`@IsVeQ`Hgq3N>ZF|!81iXzw!pOj>l zs>~f5Ip6EA{5brxn8$+T$gQr=x5MLqKg-rv<|v_ENxjaj!cr(IC8n*5q4}kjRv4vG z^zFG|A!eb)D+xtux9iXbpJ-R=Z!lE+ToRQ={5)GBE{7k^wT}&fZS#tRTmY?+-0dgV zHJ}v%n>J3x1y#-*!~w+$gMWu;2{#W9E)|s%To@*i;=sreJjkRl<KcF3spX-%4prt> zji;36@Q5EY6=!j>_dz?0-%Sv`et5KE)RW1GK0C&xnsMV;4HI{>4#5WW70WiEJM&}g zE(-xa4h{s`Qyq7S`YKd_WX#d$4?7#V8_)jOC|BlZ+>^4r5S|yJ@#bFOcGpZ(L(6NX z9Sr1m8i}!CT#%0J3j=fR*h_ERrQ3l-iZ=*w8SOV_onviLPkY+PBY|zviPMb;E;?vO z5fv3@2iyX&VR|>WDA&8)G35qXKf4V3qqotTd*jYck*3v<PHry~km701t4#<8`v+)d z7Vz5eU%^rsDSf_C8`FJp>Fo$}alaa{@=bXdMmY@nI)&bpa8$T*(7X~D$6@?6>mDC{ zVCt*Kp9kVOzvtAJ{M~aU9gzNr=L0Iw7l{EtR~}Q{aa4jkeTx?5=VbkBoU~buT4Iak z7W|NC$;s%dxH~}cP$-W6cAkjdak&3FCszW>idV2MF#4FH9PvXH0YqFqA9~u)C<T)i zTU1Ae1aA4*E>z=&8tH>*hwhoPlTR!qF46S&yf@YhqGwx()OjNpq?mivzK;3q^P5tt z?El>Ips9(0Q(?a$$4-%oc05+P?|Py{!0u3uK7pG>Sn6&Huic&KSNj$k$N6oRURbF8 z))*b-^YzU)5Wx_u%raxKO7bNGg40hPMH`&~878ZKv*Y~7mmF2a*@dp(akSmRwOBrb zyVhwb4SK7pt;*Sji<wEPl<#AIeX%J_tjdyjmC7J{i{+iXUlscy3zYT6jWBRzJ_M`I z<b!4z$iUm@a|=t8uOA&lCD%fM{OcQAFWCTa$Ai1~wH}>I>}YR*bL$-51zlc+shZ9g ztKR%?fF~l3h0xDlW3QzM0BJSHF<xA146OagzqP;KNXjX9`A&B-YmqdU7XR|A0GA=Y z>zvg53^ROWHF8DE)-S)+xFJagBih?Ws%R!El|{i!6uawfrueQA75(e=4W|^9QdMCA zZq@-aXK80Ers3ch0e0Vp2R`1EYp{Z1F!9F<lnk}1Br`ycM3R=TID)tUvTVO_S{XI1 zeDYdsaG5s7`PTz(1T0$c^p?5j&+`E0=$Pa6%@-8v>^K(duxnJJYu;WpOCQc$yLE8t zNwr}oJRq5PiA&XacPQ+JsY*rJ?~W&qlslV({!UwY;9D6JqT9DXViK*3Yk6#$spS1A zViH+$g4ES-DUf75^V>Bs;2+;1)&SO32f`@u;r43tr|sti#h)H2xmuBezw0RKa2{pS zDuzfN8qA()qU*5TkmITpajh19J1+YR({h1_mjIvAk>x|VLwZ9*dmYMCrastCH(_<K zp$eg%($1|AfAD@m>h}gezZQE=K=4XPWn)$(6gdRs)5erj0?s1lG;yHEijuRLcX}3u zbanp=Kzx6bIkn>ge91<5FrLf&*WY0t32SuQNH@W_$WAn-5S|@Mq{4ciu0b@hR16r0 zg5Bb-d+JL~PKx3_7)^;s^RB%E2?1%Ak_`Tfto-0lLz8lZ{52Y;jHGgkR3kwmn8X)L zFpyueXm}wqXt?FWq5Ql^<PlFDO>wH}1D^Th32$Hc*;^Q`?x#%#OAdn<ak#F({cTDP zb{rSHAY+XXWnbT0v#FyVIP?2yNu!lB)Di2?xpAt~oYF&5LP`fxre$0;Z<NG(u1>O2 zT2LoaK5w&S*H7Pn?V@QTNS%UxjcnP_+NooDRTSzbsGvD9*v^r>(Njs1XL=O5wCni* z*T+jEkWU~fK~Ik(IY33b>+HM;Rc3lqrlIigTa%O%EB2$%)Zf@QZCEhggco55uyhf@ zlEZbGX(ye9z=vBic+EoAfYww^{g^7{jRWj|kuB?UUA6^)O~+F;(}UmBJ9arAb6I&S z4l}Ea<ea9toc;0YO_5mR!(1RoKuu+9>4!4izEDNIHFEYH(jRK=J2EDaB8%)r6W?X5 zHPsrz(aoT7;UkLrv<=oQ{N7`v8YzYQwKv>TD?r9sj)hA-OPyIY!syfp3{zR|`P%Nh zJz&-|*IXpy?zoOLr8H1H<vtv%^?MA@_h>o5T84$}-NAuFU;o(II+S^zH8l)u6wG|j z@IyU(I8QWATY(kwhZ;QjQ@?=4Sbo6C)qU5O0%wR@=4G-A#?QLWo_q;vDdmq34qeE1 zF|-lXC9uz^At>FV7n%5X-{umWa-YDMZM?EoZbJBSMBVt+k9gPlf6?z`Qjw#of`i)Q z@aPbU1cMh-D6daH*seN8qS-7*dxMbiN42&P(pX625J2;a8pXjzspQp0t@V?}LjENW zcK?Dz=@4{yaDDAJz`~m=;MRR4do5#sO?oou)R=8Fe^^j7J*jQQ7ghMo%XRCO3SSXx ztB4T|w^q@%I~PW)n9v7g2L%1#lXv;W-6bW=Pc4$*8<Gkd92qr<$G#036!pmSzXi}* zXKn+_AsR<v_)xg;tQ=K5FeU9EYO<N2IjWX-jZPy1rb&>ti2Jf0ud5az$Eu2@W&4UY zAWxI$tG>wLcY3v2JJYh!Xg3i_OeHJR2Yp*<-t)?G!rJnCEb)o)cqWole1dx4D-Eic z(&Ch?S{O+?`@PK7NoPz3j11v5haIcw&<6b{De{~LvizV=d6g*Q8RDr}%)g@tl|Yn3 zVVr<&CGSI0;Q@~Cia(_!+NY@1k?xi3qO8@Vw^>+Umk{chQfXq>1>}uoy7r>Khwwyh zbRWUuSR9=VYgkjdn5e>uN{#EsofUh!>ud=h0s#xX_@y>4i=B~=<%Z3lJ-#nLXC=;A z&y}+<qkSYIVAed6gvWYzJVKl+{}Y-4z9+}a4c6v|=;&Q}Qeq93E{j0MFS@BIN|p!X zn@-zqF5W~Wy)OMV3gQgR_-8w8a;MV>8*Q8l!LQ+huZAE=&Y=>;ID_tQV*__SN-Lpo zXMGCr-rCN=&G?$s{yk=+hBU%nRJH#sZhO3oBjP?1<aLAQeZGFD9;Ymi%Ye)=i9~0H zqd7^;-CkH|PVTdrqUOB@3{VpTAhw;D-jZF0IqYqZS!~PG8!dd%`gNaAijS$|dDQcK z2hn36Ib_py{uV0*$Irk)72Jxs*I^fB5}BDNyq-V(P%tRTlZJZQYt`wsQDnO1EerX$ z*A3}7>uJzMk<fW{DyDd`W)=ha22>$oGr1ol&Z3M$_jo87#R}Hw|0IHMk1xZnOn)Ef z3cfOuznYZtT}NYbpWeBFTYoP&dhre)dbMCPrwika7bCU!-GZx)W@1^&Y!?kH0d0lf zDQ{>vzB{RRRg(Y3L{?JYU#|b1vi9n^AyD4%uiHN(By%qexTGiKd}Okzq7MwZ*9(SW zT+&t(l*qlq49RX6v^(?sQoqATPTWmC#{U=-5pl7dt47bA>Uz?(#A$Xk?H~{<a_qal z$_X|+xg(*SkM5*%8~xLRC2%!PIqAP?dJ^te=XS|z37AiPT*U0i^C6%46#!xmaonVl zi5{trm5Wl5C=3e@siwW#c=y{nY|8q}ZwtkmPi!T?7ZlE|^LP~Wv@zCO9=%B0Ve-+E zvoN8nm(_Z8A)WBth{n{`S>&zA8oKm2N7pPZ>dWJxXz)UxXvz031wvT&2!$TchW<U& zkEjy$s-jb21{}o3Z6rs-*z~eqN}IVP8dlH-;acq27%R{_{Y48V354G}>N7lBkx8Ot z)FhP{#?4zR7Gl|nIyzos2*Z_0=@Zi$Jj}vR0muoVbfJj`f&wRNX~*-}6E|#B@1+|D zT6mmZAQe|}9A!%MwUhB%#nFQSj|&mmB+7(maV8+vj7~^+nW?ui4Z^fywmw=QC~qey z$LXSeeeX6Rhypk<eAO?|GC9p~`e7BMih;mQ923F3^g=iFBqyy(Kc>3>L&f_SD$JgI zPm0B05N~wcNv?n7R_RP%tjrte!y11}YIP5xlgR777<29y#Ja^a;xZGstq^~i*X~ra z==z31eLN3$&`D=F<jIQH=i@vr9)mWsgo<V#1N(?{d()K$ir&*DY9LP+4Aij$;>j2C zu<q%z5AmA~q!|=HiWSnnX9hp5Ph1bkwwXez<bQSgBSa4W$m?w$MgqITL`%&Wjb>cv zb^nf`;z+chVj;NNltfZ%W%Y`Sql>*x)c0D6DPLsk)6~*bhNf&^(e}E~BWNedG_?tF z&jrEj(l??SUFiPkPtTs|A=?>9Q6Zyc_Tm5Bx~{04d&(3$v}cTDcj}L;ceZV5Ven*9 zp4yHQ@l!a3!Vk|=wy}tykVW#ORlv%X|L1KW%U{xaTY@?At6U$%b&`p0g~o6aNy$(Y z0;(zP+bZp<cW5`?0HH8Yh!}b_rjlU1s{#brAqa#B5DtJ0iwIfvKl{}i68SVF9K9Aj z_-M^VjLPjSCy8k6a6UZG-a6qBFDYWA5@S~M>W|n4R{;+m!`<SL0%u<mE5F&a1;*;n z7x;7*s3{wQyJ4Ijp-Jy97_n_*Flu%~JdQe|ofwy;oN=XPiy~*ed{q4@7G(z{WVNz_ z6{HSjj3ddHk7|B<qIcs!!`%$+6ArlHa|Xt2UU#hl?!DN}XSLVhs|1BpnNYGWiMvqd zAJ(g62q2R5CdW}U{*Ta9A0bOAYBKC)O+BQQ#J|_x^Sqmn$Lyz94sx_1(ztg5_}V14 z6*Q+Ea@4;yseHOw!09sl2HbC{wB;!Ln!38i7`rl7<z_}0&3eCLww&&#cyFdet$N6i z4TosTrXJAQ5iIhiDnD8aE>ro4C6JJ`6}3=aYX1r29mHjd<&<tl5jG#W-2>AcN*H^& z#Z!6nl*p#));7v&6~kMD=4yN$fR+LXF4ym{wIo$afrzcKzvgW%_H)}*ZSOf)T$|E; z{c`LPV4FG6gD=DJD0zZVA@126c#PxHpN=e%i1eT<9!&lN2NVu7iv##H;*5chnQQmI zS)12xV$PD=k_zqSVFLP{IvMqKXKi0x4tF(2t93=&126ZYRg}7Y5n@06@U;k_TmHE! zb{MKB;yM;kt_otj#7pEI{yuC;5NP0tKXEb<tQr#7r$xZvyf<EA|Eh$A=;PGx>-tw8 z>mDuB;1n$ovKkKb{nHv2;UYaTzpihO^x_O_w}BxPf;W1?SB`8SPpQpMzu>@PQig>T z6@Yqw9bRQ#_=SE9(<ObaSY;ffgNtpMGvC-8G$0lvSjnF_AQ<+$2jwUz_7#O{7x54A zm%#|I`C=yhEO&|loHWB$`EBCWj|Dqj&9Vwbg|!n4B*SAL>-brsDX$v47uu}5a7iTD zZSWWQcllU2Ad>I#SP2ti5myXiHaEGR=Zz{Qe6#*+avL_XT+p*!9xWtyKLQuAo*Gd5 z=}o4Q0#76>_HYnN!LMP(R4@=>bHD3-U(;lE>ZqZfyq7jNG$Sr=+{D_0sOyiKW<nm) z5K*%ccEWGrl#jY_*9=q46nX*Gw4{blGIAE*$A#L;uns89nqAwB&KjtpaDo(KqG<z~ z-pq{jS&Rl+u@I5h&a-u?5%KP}8_^&qA+@_Qn|a^=$kuCpgVrfL`t_~N;+PddVYwn8 z2wB@9e%)=8Bo<7{o0y&<$rWONl>jFDIEyX!L4-U>{F19g#3R1Cz;GyWAeF|K=Q@jb z|DM&iaPY>F>*{0kPbY;s_GfI<2iNb+FUnJ6Qo3L1D5D_z;<bP^);CQXhLEwv;zfDN z3Yvt2|H6|N3}AP8I*EK;8pAsqe_h-x&1El4Hl}^~3L%mylpx!De+db4Nes+#<mBYU zv1nI1D<hu(ZP53gyDhPfy|sDPfHXVgyD~f(RBL<rF2`}k{je;yTdEX~1>Nj|G3TW3 zI*G*oJvA&|l{k4=c-L<1zW9C1>20pJorJEXRhhZl718WcQNg-ouO<P&Fc6CtqS;2F zF;$y)XeF#fg+`C*#lI96UxD<$v>k;5@BlnBTDRC^!@jVa!qWi6biB=!;3W0{(8__n zy#pjsv=HO%A71dyN??@F)e_p%??37)kG1K2o5>Z#+Eo$DUaFGzp0p-@sip-2q+*Ih z^hN6QgVYS521A*_Koyr^7127Mg%|FJ<0Qb}GoM0Pk||Cwvl20$1@@3{pobmuV_F6f zoS*yHZlalasUv7u+?gslAo8|-MHaj2z_f9vtVAJO?LIq{#EeMVZbK6z#qpM~(SJKO zZvgv1>9dK8|DoD}^bYaum(G9HYBXk3#7M<iyC?ay#@jDiWR@VBN{rJ>WS2oJ&V1XN zIF1|*uTcigaZnvAY5&q`m!O{LiT#1m9mDj;zKlKQguSPo;LL1p#*gADc#$lXsgY?8 z1rWk!bKdzi307mf7xeU5aN>4$c27f9>4pplAQYl+rOZM$CNKR{ijk2E%th+fk^MVt zvf;swOTV1gRmB`WT%Z@36ZI&)hwj5W60DEzhZYFDz0R1er^8lF3`z=s$?58By~sbF z=+K6L7pmpbAY3OVn;;seOaYNrr7J<t?Ar!PDFQ8C2zj`chVgALU{Q;2zXUCZ5#L@( zAPVgfA$7>RkcUxBB}r|L7M)0)GdlNkJ9xXOD1SSCt7XGv7a|*isq{b?xOQB|U^UvT zYvO~PN(rD|8ehb|nfr4P@SF^?h$B06somTi*L1*>py{LCd=;R4>KnD2Iet`nZLu7m zp`{|tW2=c9hM-P7A})?7r2Qs6DNrR?<_lF%;@gXq`6>pP&2;E>A=k;G-`J3L+J)LK zbw_I!W0j~{Pd?yd{6Zx;Jw3cf5;<DvJdQdz0^>ZelZloBTQBHqBJAa_D+Cfzjv)Az zVveG}5;PxP(--^+O|VsYnIwWS&K$w)FbgIY5hAHmF*INKY%b#5&%^XR)|`RYz*5xw zB9-V`<hf*x=OreBkSl<Kj)6W}u0VIa%h4Ke=ZQ$v*RG_Ei-7h?f{UvM9s9-SR5N4? zC;`LH+W!M#L7u+xp1sk?x066Fz|5Alup{v#<ec3Rn`$j5VDKTqpMWVB+>2@kFofT@ zlm@>b0N+((iGPZ((X?q(^zPl;*s7FDIm{S4;3oU4O#zz%m5u`C4jA5e;|<75LWXZz zk=QX9Drn3Y#wWla-Y$`VY~}p$XSs0y^{-&}Pq_pPE?F_qx}G75y%b2h({RHzJ@NR2 z^O4&=9{c(<rA2)VoCR)77<>;JyJ~R-%eu%hjqxL&p|sjYCBc0`6qVzTKi;HA-mzl` z>eZ`PDtRy`55bRctIL1}woweyFk~A1S?B#^zIs;$bEY?>u{U_=bGlV#t$;r}3(;Tf z#POeO#gQ&A_VIl5@!fI$Q#3MU0<YAhLfm%sG&s`;)adf4^*o^$89Et1fk#yB0*rt9 zO2pJs?uQWi_Zxr@7tF_V&pnHgBS-!w)dUK|{i}=->~E<!sD8TVgtO7S;CtFr<WqhT zi_P9v*l~JS>}j=ykvs_)f(e*Rz)&+3s{o;<HGJt`^_A!#U?5t^jzMuY>eQ)Y`d7zv zPJec>DPU8e@>8JP0YhqPDyGqe?6lKP!wDyxQ28lXncskuy*Pnbx|p8HElGy5;p-$! zyLS%q)4T)?Ua~Deig|4$b4>KR_*i)3H(}<or;&B)5p=_3Cd*<k9vD0x4V*QpjvzxK zgP~^L80Q<nzynfANVKh@zL$ZXJSG(F(PBF0<RSQB0fMqkvjBrjOZYM+Kzk1tBU<`X zv+?7K&+*KbkC1$%!a_45<_fOBzu1A3+jT{wzWvd>*XaZcRj_Gw65e{|3vBy&9|Jxz zm==MWR7C0=A7dgMeL`*8Ec8Lux-skrN-Z9pg0Xkrg)6VPf-aPg81;^_M;<islMEi& zvjT>KYyu!k7&f-oO{ll?6V!60@|jL-XOxY#T{_T^l~Rf-1SmyS7`^je)Ipr?VpB*3 z{y&iUiw-I}t~LxDIMAp^6#iR=m^yDS3Ji(t51Rs&o&x0#7|O0X%I;TsN><7j5EBT4 z1p^$&Tnu9`a$?Q$9hfq99#bMmas|q4mJH|=MWef-h%}6QZUk<5;VMcQn1_JJk?F^S zXN^UR#AYT;u~}7;9${9ZI?1reIOHXvGJN=O%$zwB^4*uQo;gQ`V{OevhuBB>UBZnr z`+6U(oTWD)@$_aP=8Fhqr(+%COU%E2BJC4=`1!<o$m`pbOxlH-nX!0s@ECfY(AI;J z8D$q;wP+JwnD`z-IS~X~Uea2)DjY4dD3pgDgWKc0Yr2A>07K7-_f23di*ax>z4+EG zWb-v^mZ~Atx&s+{xP4*3Kzm2iPKBYq=j<t{y8d(2^!<ov=DbLzt;&~8>LR0mbA)R8 z;LWR!$A{m?Ak_4dpc=zL`w1l=Q<TxN#R4koJN>O%wF;d&buyv9WdwOB_i5Spu=i~W z*cA9<3Y0rwu$rWa#?rUiD-eq+<+rsMpn(hF<)=wv<W}4S<{b#-dvMnkGmy2u$RsIp z5*WCcILVKE9Mg~PlqVEmN#;jn2n_O+>ci>L$K%rTuOTC3i~%wgF)kk&6w_3ZlZF|V zn5xPxx7>n<AAZ=l-hJ}PC%<NL;mZ!KPZ5kSAmc$(xG}yT+y;xeWT$t8Z~I2f7&!{j z$vYS!F^IjS*2)u)K*oU9D9Qyov^WVj9zO!nB#AOKB(Kk)k?AzjwT6+*$X+4DfLd<1 z2gSi$R6jBb_stjvM;vp0@S*G1{*2?=A4j8vAm+aPI{FPblXxHuTz&-<!mZ>dA4Z*m zx>$dv4+t2>U-TRzHf=y$+Q+EpPN(@}0G~1rb;gjB5vW6ZhnyOCbj1Ax43P{EPQbv7 zsEX8iAYjmA4g>`?YSb`+*_2$)0u-gqv3G0=*c7O=6exGVAgO|i1r~mLqN}tttrQI} zVS8jC>JKU0DJ|e$kn3XOK1ZMb^lf>#;}Rw#@^O_Z_Q;i{a#;9l<ly+*+Tp$3Gr964 zVA#WCR&zID`lBzSdYjg~jw?|bLl%)cMHrDdpTd1HSTPsnkx<4`g%ehmLu(8i$au<y zka}shExdjYKQSyXu%0eNVAyOJFi147q7^kWKRUVfrKMvb!(69-@D|*ZGDK67q6nB9 zX^^<CZ!2V+QlFuqooLhOINa1}6k<bO1hPVS{I=Jz`P)=huY3<=(#q+;?(i|07!vYu z-_%P{^GN1p;Oah)Mw1<m?Sze+Hsg#lPRHAG=kPZ~MowU+zu%%=No&Jx=BFe`G_}AZ zqh=%Rhi#~yv6un3*0U}jK8Y+w#)wl;RENHs8L^l)YBE(4w5iY#QShb`AXr)%cdX}H z(n6g({q)nZZ{I$X?%G}ql%<xvZ&RRhQ=r@dgC-c2-<#wrH%TjF>(wVEOi`@UbP>NZ zl<@ukdl}nT=fWd?K^MFr_3IhYjN~^k61(fJVlbcrcy{Nb;VY}qf6!&<dc%!OXvNUS z##JIri!dk=a|u5~A;D$%DkdXO36F=yeG>0iL?JWe!kIvcFUWTnF#1Kj0dm(6RWVYh z$R2|Wda4Y>*l9}0D2J)vti(sR+yrORP9sgxYxr18Hl+kjhYiK|?Gy1?_BV|5=s>$h zU2zj73=!F0JU;d<Z2D?1BA9C2@9;5@V>s@Gi)spgY!=SGq8obkKaR$xK(Vg?ms~Oo zZ@l>yy%3t=>#tX!N<thv#8`^_KGoP>BVFKCk|sIm>M1G4<m=~Q^U4&|%l{5_^A{u5 zor5pDKI|QFJPMDfNgIqPJbA?w)FGJhXh0|hdWkl|0tvtM;G3D<bk?j{CeB7g1VdTd zrP5Kr>SGHCmYuJ4PRFf9pI%P;*0uVsYpnCuaT`2}GL^ej2w<=VqeZ$3V-{8e?Cmco zp#Cw1jB?%bJ(zUcY{pukXqusk{hTOr;&PDIYA-w|?qhmuGW?VR9Qpj0Xm{lCIDgiw zWO9^NFiDk)YBI^FxO5JctWa01SYbj#YXXsRTw-Ek=>%hLDyI*%O<n{FPN_(YW*m~? zmk}r!CTnrr5TyViuCxUfkWaVB6<^}r8?Q!mL6%{vP6zXIkURUDwZPD4rovtC2t4w| zYxpvKDKmol(4k>BTzAY!OdS0bGPiS*Es}jecyiS%hX@*q9XUAf%HHU6L0dyR2ct30 zc;Q)$8hsCsSfc;{KmbWZK~yDyiU;%Oe?YgzQ`KN1fM41Z9F%N&NxqXdDh{en6c&8y zZ42?;XS-29umg3nKcWg{7rtcX(d3aQptx~01X3e0T@nW7uAm%){Ud2cxQ+vVzu}|% zKV^t{`|Y<IDT88e*roDOKz%HAk_=a^09<1H`cvp{h4|mHWlO1HtB%V%X4tS{#;&F; zz_8}`KN>fck4pc&7MD9<(7>{gragcT%>k!=Q86xk`5{cWW)}9W&t+I)N&>jb&hTa< zyKNpEUH8D@VV1?D9JH9Z5{>DKH)`Rha8;|q1!;_7QmRRSL6Uqw!yC(zU+$Dg9(kkz z37a=>Mx#cJDn!CS_D{G#uLdPtAUIN64O5gIhxWy3#n8=$*D{BO%SThj?b|SS%+1JM z`xDg*l1lg~eQ+bq6N|p%#-efGGYFcZP(Z`P$;)Tro0LTe6ok;CN*4s?0eNc}8G*4Y z6cjQ<#_yq<WsupaLecrS=$gLh!eAFpF3crB_<H4XoXVI91qH?QE}D*!BSyf@AWkCa z!R!gx>|YkWh+e|HLs)jA=RR}yC;0N?9Y_pjpkD5BW*q$n>%0ZnHR2@rn4cn;?!olS zr=VU)l8j&4p#1Uyzx<}LqZIbaNIQG>Y$#`p#V~$(rTy(trGWa-vOUqh{xokZNZ7=Q z6QSR19z&a3bGf!E`fW!?N27iF_IT>4r;LlOj;sGwpSITAuj6*9d=w~mz@Wir6>GrR z6N*KVLt|UEk0@Wqx1aos=@UMn`(!+se*n3W`PkPo8?Nq2WNbNb>?=UiXP2Qxo*SJ; zU5VCLTutN01Z!c=d&C&|L8hfrTwIK(s3<eRtX{p^<dx8IT~nT8K_gKK!;O7LiMmAX z2rv899x_T@L+0%C7bC#Pl;6EL6F<EA5~T_`h~oQXGqiS=I|6O{55%#fuRv7&x(Im* z1{lJzkWnxvfB8ICC4Wl55Q*Y-(Wv%CT_hA#=LE_+g`%Vip^<>klZSIg^g^$}?MPG7 zfx-iSun=w9w#WMQ8)zVUD&0`uLp14TR13QI&q^2wXe8a?6T@9Vz%X;dB78o78zO1o zTF3V@qO+G^mp7S!p(_Cc0ZgU`(=K}y^+O4K48_fCsU$I0A9C+E`)kpnMd;bHr!jm~ z+?Dd|Q?<)3f1d*SEn0tf-+eb;dg&$X+_}?Ktl#dbr=E%vPdxD#5BmJ`&mkjb{l3-b z7hG_G@rDveu*QJ3{l$&;mr6r{at914DJjNEUeVyB$F|F%Nr5nfCx_twV2%S1-1Hi@ ztj?qnqnoLgbCJ|^A0qmsk+~Hhlv;r1lrXfVdu5h462oS{gP7*6C}Izbu}g5mFBps> z0&1nANv3Ppu4Y21kjX@^$OeiRsu(`3ZwA<sHFIUO@5djo`R%z_GoK7QCyjmsAr$d^ z4rLQfdiKGIS6vNni=${a8bOv!)eF56B&o>f-y_SP#dm4TP?Sm0?z%)&|GYNh3gZb9 zD8EoZ1V+%T**Fg8Uv(N<9D4*M6IzK8MsU@31>-C{``q(5@BH&=6YvUK$IPJ8La1#9 zZ2U=;L<wM^Y>)p~2pC>}co7!8y@78KiG;vj0)`dX=Uj#4VeR2>5<{a*Hy*q6F*I-_ zn0p*0?^G5rsH%gNjT<+b)un7x6n7;ymWG>lIb<nN7O0!wJzJ{9+&ABRW5Rr|T)7e* zJ9b2m9zD>#dv|p1+}ZT$fzkrqs|c=&vGVS_?_%-d#c0;7nTfk|+;PX*(uG5I1pN7i zl{;WqzI?esrV?9eARajA{(RHzEB|c@7=b;-@NRlgB(2TFJ=eYpSAHZ4$mI4mPl5B) zWH_VfC6O0I_b)OKw`3Jp%?`Mlw8lkTSq9_dcrRHLCz6n2FmNkSpovA6^qN?-0zK!P zbN=mD`OW&}F(A>uR?xD~aC0RtrmDb6AxaU7cJIQhbI(EbLaJoQq-h6=Ot!zcS|Wx% z@hoCnwqayMdKKs%>iMZ_AWvn$qQU@t5pLYK=n4Fkw*tQ02>8}lL*f@TQMI5N{0t54 zVM=LNLJl5y?gm8Gq9LU`PS_INzjWD`oS;u-RLo9TvV>|Lf-jY@;>3bChW(r4zxyHj z^8)3RFtt#+@$R%Q@bT;)sh_583V};pa0^n4<|E_6h6psH1ccI}NyDa~p@S-k5c6IH znY<$0gx`IXLSCzny<SG7<a59O{(H1()8=>Yu}@YU1uWHr`b}fZnvZ3;DsLv)FUSS@ znrp6sWx%R_{Vi~>b1FJNW5x_zdg-O6PN}E#JGXxS*4Db#++=?o@)Rg{z_4`bQsaN$ zqD2e*^wUpfQu(dHcgR!kFmIsPj6j2fVs~Gz19x2h46?R4joaVeW_#f5CBQ(}LR#HF z(CR#Vdfq5h3lt)QL4f)_^DOFeHR7Z)zH|~1XkgLmMXTp$o_WS3Dbi%5QW4`IB*eh> z$R0q-35od~6sZPijJf2Ihp_pBcMwPYLWF=0kwq#2P{%9(hjteZg@fswT^<HpCIeOu zY6n#d0oo$CLVRbYk$!i<QatzLY`9wHAV43}qD@s%^^4j_WQ+rmBC@(4_dS0ZB5N4A z1ZgEI1Somgif$*Lg5;#V_<6$ydPX$T3AK(z6LNS`=0nYq-}}&&5=O|7Q~NI3Oh}~i z;j>@igXh0y+oMcoO|K&z>4AmFA4GuAqAH3rgP1gY3K}`%38L7?e%i0N!!7u|=jojK zyF-T#CY8BXnhM}#mqU{R)^F2loeUZW4H^W^(=vFRM0eq<uDZ&c*0ll@+8*q;YJm@{ zPI*9Gef8CN;e{8B3Ub1P2?lsrphWY41%$2V+uK8%0_6@EWFapRbjy}44PZFfz&o@_ z_TOop7)*dVZa1y}#b*}Kb@Hw0wD{)=IHl=sxO?wqjwCAUX$(23&lvoC(?sNa@ewm# zdr+-UKb(C3{cuFbbApkvlh($nF$@guyz@?I0+BVnwiQ)^G{lr<Uq**g(ubH2VZ-|$ zVb$a*aAhWOQBD0nS6&(9xV4Y%j8ks91+hmTMH>x*0-n{o$;QE<I0ckSI2o<6I5U9x zFR#L@AHIv6WAhQ!J`;gLN+;GQpz89vh|Q0ME4mODT}3_cfHnxw6GBo2*$DU<yP@A1 zeW?rn6#u*SI!vB2iKMY6Xwgr9V%&d{c?<9n<b(kOTP!aLs+B&OwH9wr`;=)v==mbx z;VwkF=UWu@;ybitfUZos)D9kpqvPtc2EC~aUisKRC>AqOoQ)|{reOT|@urXe;5Peo z1yMl#W%Zeik^A)N1F4j1*RGAb?z#(?Uw-*7z=3t`Z_V4*d2Lk+m?Uk)h!J?}t+xy~ zP&jzmKUhHFx9X`Na@ddk0}50aU})XCwON7uLHq2}6-)uc<jHNs5QBM6Tyy4B<QBM) z(r6Dnr=>EpVJ`f6Ufg`@ji~<dH~4b=?T{l~3U%JY-lER`nAVg?Fd>t2OmIbEtxyyN zP%9TrCK6p*6V1Q*y4EDN{~6&VQ2~MmFC`5H+qU9^+r}XKr`3pN-VBdXqd1Th5r>|) zk43Y7XE0+F_3<95El3&WjW7xf1zaND5JN4>^<(nwZ(;X0NwoDS#-8J8^UyVw$jgm_ z)p4l$c}-L!*tm)*s#~4Vkhvs^$&ghdXloh5=*us|bI;E}e0&0S?c9YJ>i^|Q5oXq! zgvGVPiitl585D)mZPXD08&0Yp=$C=TZ*IlxM;7qCmBW&zp9C!#@w-siB^&ORnFwV9 zmv=ZH{W|pG<7fm)1|ZP)XNu_jKEq=V7%;%7o<8{CgFkbdeN6>WK&yQHCJXWl(5-tn zqb8P{^S9rAi$;wamHsYuor?AQJs6|6e#264$bQADTlWneI@HAGs8+2SHc)D&XQ){B zm@oFnAy0vF2Mn@dIO(L5j8W8@HERxe0{xd8DE1WK<gaYihS@SS^u42A#Li8{NNJD+ zoW6}J2|6a`deNr19q#DR9Z#Qs8k&%iD$8ZWNvELyQ_s+AfM$Yb!9k`&o};?vz4I>4 zq03#bp1rVO{(LeeMT6w|Ke2LFkR`L&m3;*7<J#U7qhjZCxacPfG@1s6T-GTvTupeA zl;{MH1!>Ia;*vh-=a-^<EPL!RY<&GSMC4^6l5QQo0E1vVJai$A!Khc~BIc+T<mohA zG;Ivmr??BM(7YM}QpVOIOup+i?AxBlfJ`1_MHe8s;~qqvkis|&jL)z>8Z|e>;oe*S zheoaH5P0xT25r(?bBT}l-g^({o^!TIef{dIvuI^bqhMYVX4d9K^fLdyA|%7Uko|%J zXgLTzBw_gKgUxvE-i0(`RWL5b_vBwjl~fd-oJ9l96e7Mtw9l!9yRMu-8;y7dmXZ{N zY8N&67r4Q^J<o-SE^3IGeD~dVkfB?Ae7y17SEI#1bnalx=KuFnhu_s<Du&<7kXHw+ zgTL4H)-}IJl9CGbJCPL2j08#4%nyd&_=D+wQV)Ewd?^yDRK=Ieml<Qla6hZR4pMoz zyUmFMo1o?%2n3YLRLKU{u3c-qCluJr9tQ`Z>mh!qLI8u@aio&40mGp^Iy4bzl5uNt zDN##2d+)ngLI3^K25E2%*k+hsfChcRFPwPk#&P)Q_RHX16E<c|rMuzqcj%7U_(*yX zc*Rm!$hgU5KmBwGdeT$o_~VYpie<~F|CiWYqVI#vPUgnaj}V!lCOO0Ti9o~>_05DZ z)>ZssKm%XEPe$k#z~F%pZ7U>R7tWANqocTx0g5v4F=Hp}`g8$m@IDX!(y3a=@<ih3 zGtb3I*Wbvv5?l=_awTU@t+VtjF-{65Oub6x^yMc%V)nF;QJ5ADFXJi{GbMOdY(6qO zCBb_v!BxPEsLVv%(Q`D8Y1|}iXh}Lqav(tP-FM%kTeoiXZ_mXI*I#dR#}<P%uXNB^ zTW9{D2p|xUNF^al38NSyNcv&%7EHTy0X&M{$$x%wl8pE?<e!p-h~~*~q~sy=<{G^G z*qexI*-G8d*DvWEzPp-ZXl&{<6ftyBYt-)K<YY8%+}MC0{mzy4S`6YqM)C)(|IeJ( zZ!KInCbVM>VDqKq)NgIVH}IYVE-=T#(x~t$GJg$VVQ2PtfKtOEW>FnTm*7u7`2@A= z*28-r&PN+c1$iYeEV=7<#-6Sy`&iwzzd2#>$U|mK$mLR*YBdJt%$Z|sC3MaP4x&Qk zC^lfI9Q{-wt<*%I`NbH@aT-uG#4i`D!BY>vht%5naG$x`SoR0<qfoRk64&$^faB@} z@$q$|=-*$60&?c6olZu7rZW#w#ID>2PQ_Lxw_Pq<mXl6I-P-k-PhwZ8RN(g(Qx*|4 z;b@jJ6Afo4vvT4AiS*6vWh!BNX{<?2fLcy4p@ZC$kt3xC#mRe-v0)<?+<ONil6NDP zZ<<d=SIjJuMb+!!tb6Z6Vu!X=K}6|6`p+Wyhm;X4`XF)g(~Ge1wXg8uoMmt_PK9g& z0(^Jb4dg@@A+uvLB0BFS<Mg9_<5O_+3BwUXvkw=MiEJNK_RtlrfBymao}l5_4(;*T z=bssi^xqTznj8PjhX4aniJlauEgMZ*tXaAhlWuyKNiZ2Rg8u}p(&I9a*CU;PAqkGO zLR5YEdz{zxEcCwbUcM?*ox3eJiEz6~43U&~8{(MOXixnkUwlRW%g)Zmi!Z*2Aw!0k z^Y+Jn3W$pPDaSA7fPQh|-<^@xaNnrC%+cTa(3QHmq+fn<nVz8j7X;vWRv+^78{K;S z{4FSQ=-FqTg@*O(<K<UhMrSVO%$2-Uzb`+3D{dEmL<bbp?t?w9>~*}z{8o9)0*g1^ zcq67xor?N=o?@`rkwD85?9ku00mGr+M-|#aWBJU9BdjiPA;8Fwk58D354U`ci2kW? zGGS4uC>{mxB%pisrnvRKA^7&;d+_rcFT%_F^2n@uOnev(&m2gxHkl6jwcHqgTK6N4 zIi?M#G6xN#3YqemNfS7s{TT^^B~b`N0Fg(NEN3q>fr$}^k8yDG808CWhoVh}g7ki% z75I`z9>bRT?<3ZiOCV85X@d)yOsv&u<mG63@eo8(EbEAhMS!|pm&pvl2CLClAutIs z6=(k5AjaQ3ok_Z=vkk`4EtALnE<{CAd`||P%3w@s#}Y7f*~Jx>pUJ0AWwy%UsKR^^ z3Nft)XJlrg<x#DW#spTEj=YpU>kKJv^uOV#n3{0^)(Y$wfI$Qj9UR#DT@voU>J51P z(F8Y?Fpy@caaoiwFuz3$N<{V*;>cOwqfxdKS1eozSM5ede{GSVbSqjLdWU;KG`Dou zqehLwv(G+jT<e~G`sst;Us}<BZ%4ghNN2`v$@_EMXf$hd$hL$Kn-a1T0+(D;c4OUY zZFSD-k^}1wO8v$Daq0I=yPG@4j>8msLG<c*Dqel%WyHkAnfM=ag;wsA@YoB(%(Blk z`=;_RxcSw&(gRjYIO_OZ%_SNe%2q3v&5<KVn(^_s#&_wn?49zUfDIVRgUXfo8D`R8 z`(-!akXnM){%gPAh3g)hjOc!h@)%KwU||e`?;U~q=~0+E`v!(MOv0PA^pD6*<wOxg zX6=R;_Rf2BLrkOyU(6TSvTHM%F?f^s=GJXHP_JQqGtvFV^z;h~YML@rk(safVZMab z1!Y&enncCs<rW&u&&QfK-^SV*Pop?x3(fw*lN}>A!_lBQ&YbiZ;#*N{&iDaB9DafY zF+Zs&l-^M;l?I9Mwop+B3+F7ydo!28pB>9<qRfOCGQfm_e*zPSyBOJtxu|+!9CpMm zrL6?et^t!zb-EmJ@;D%4$j!|rXljS;+jpQ>uRi#Yt34-Ieq`weBv_1>E%@uD1Td(A zFon3o_uI8L4dX5+s4I>mOQPzA&)gfAhl1{V5ZRI;zxVpkc;;7VL-)#NXJ3HM_fBLO z@Nh;`k%X83vhbjF$dHV*Qz+qc&pp>z#V=T}z`T>q9DYeQ(d?k~G$%^VnhSn;pT1f2 z)?V0>M;B_uv+O?^{;oqDbCR%em@)>+BAh+wd?Z$@j?G&(Fg!WOZOJ{x&WK+OXwc6~ z)gI6WU8=tWPg%!H&v6`BeXhAgMbanPu_>eJ`t|Ee<2#s>_QxSjfpP~73f3g!mwNT; znVbTLG<EF8mCg!WACMZ9Fi^Cfn;pU>cioC$mkdf6iYRrU*#5l+sIe;=eJ?p4gD&cX z#rNEWeecXd9OtiOE?+y}HV&<ZUBW6D(1(*ya(Xh3pvao3DX{vxA8|C(VoS$v3C@3) z^x=7j6QCwa-6LimZmPCsZZngUR?{IA?n}Yq+it_2WuG$15+_WalV-n&(vP@yU2w*u zlYyEvLNwkSJVTK!jTZQwhKl5-l1><*K1KOSo71S*UxH1m=~n8OE2J1a;Rjb`PEE*K zArdSk*7M+^JI=)0*^96$eIe6ZJJ7y<N8Hf)GUlI<iz4kf7Jb4*Qm3I#?YdaDbU7L} zsBd0d_8k9Q(VK?rQ%eOFG;ybG&&915Pltz5Cne?avEAvhMab#41JSLMfutfde)%h$ zlm+bK`(6Io3V3VOq&7p8Al+G&R;sGf{ApK&XWe2DdPY`O7OGdTZVc$wty^ba=^p_> z{~U1+ftoaa)iY+)ihO3zXsbk96&dGP``U&t-M`g=l3XZ;{sf)sAOQfW7s5~AzIOO6 zIc2vArj?PFjms$odSd!x;YulGGk5%%;ioo~Z4<w$nD+CWo=pwpuZmfKaC|7#^sr&W zOx_XY8&T1?(fH8T0vW%mz&=o+6exGVAiY(mPMuJ-YE@$xrMI^SM}>}o-+y??1SJ+L z{k?wB#SC}&+OkhDH|aHohUU__n9(2S)I`ISdWfqP!o+7sBg9qwvuAWeb<R>AuFeBT zw#2#g#r8+VvA<n(&CEhI20n5Uhb&mQ2&eY$Q8Kmt@oc3g3BE{pEB58$KTU?3tjM>y zl?MdR7v#g2v>OYryB?YAe?%0Q`5uCVVy7G1D3-tAu_sZlTTe;@=+a1h5a2r7r3SHt z0;-7K1w=GX0)-G6{`a5l!nFHm!CjodIXsd8LG+-TBCQ`i4B+IWE2f`rk~N!0;ofPN zBM|LmXy}*m)$YZtJVXh@ak#0=D8y1yQ(T<SNxLn!GDy=`Uw(~t%o*WiV5BgeH5=>i zA1I=UsVdCmRj<@bIeQ8*X2?`Hveh4qyFdbF%jTl{PDHn*(POF)^=EvEQ!@NWE)Jm2 zW6z)=qjQF6$6%x_Y^i_-aStEBzXO_V1@Wm-qlQUTq+~^67P8B*L4(z=7V$(v14#{| z4f<&@!WiH*A7I~b=#a>YpsHVnfJ9K-m?hk=Ve$(LXv`~cm{Vg`*HLW-f?Cxf+6xFv zz}Klu7pz_L1KPJa4$Hs#0!}ZJr^$4fKvssq?4sW-;iv!l5;FwUUXFE_K+EqGMUa&J zf?O~KER~<a0u#S;n|-Q+DNyc!LH@mpMJ~Xgyb^Xf^eLbTBD_vvlt+3H&_@AD&Rkso z`qiK<9L4=)0t*|W*5+E&x8~!9`-Y-<=jvE?&&}BQ)@*_X2U2)u=$rH4Vf+nR&v9~M z>Re`Xbdwps_UaoLIQZ-mW^Ja$KO~A-EODAs5ksfeL7s`6RLSuDc?e`?Va3#^@$*}A zm?$b6k(@z;1S<P@ZL6~e<Af`(f|pj|AvYx+s)G}$CRU?CmKdLZ(jP0_bJi{&o}TnN zHm;^U0u39L9$H3Y;iszwoQNI8D0XFH(1`BneO_01Vgkr_7Gm<!SMY7hDo);1Ni;kL z*Pk$wVVJ!bK71HvGppnD=}%$A@Db+W0v;|Ui(rGq#Q&)hp5O@>)L_1(+$jCoz|{jE zfGeje4-zo&ZSp8BN;_pY0Yeh}H0Esb$`3esPc90`z^ZpX1wEgn9YSn0d|Cy%2-Da` z0~oA^mhcF}oJzpKF~=P9f9zcafE88Ser{~DNwXj&Edrt<qBI5u*oD$aDJmEsB8W*# z*r3=-m?#*4NQnwcNXOE!Z1>*!pXbaSzJ(vZ5*9w$1AAj;?#wywoO$2pylJAL6i!#W zc5QQH$qLdUnDt!gvp(@p+8=ZC8P?0WAQP9L+vH=T&7!q{0}+FD0)8~V6y3R9pB)6k zPJx3wVB>Flu;|NWIJhevc^N*WdiG+&-c?w)^;gy;3B$-?&tTx7UI=Ar6EF{lCbWxS zRywJF+K5`rKl^^`y840XE8hiZ_+Q}AJXG2jY?>Qt0*zg}b~P1ERo(Qan{MKv90T{4 z%#R?k&cL@~2Mp3MC_Y=NN`+pPXcx}FS#eyK^oUywfkKxIDUZzTpgRQ*ee@7lEZjp! zzk)9-A#rCFMn?n?$5h87-|mCV9jh_(*3PKL6;CdiQKMc1(U2Jc12jv>EKsge8Kfp> zVCv*)xOc$4oC|^?WRBL=j_bt<zRI>C=0w3oc}ylnft#0&y+16$Pt&F%W8+%Hb44sB zo5tf}>z<E`nbtY6bsPAp5up3G`Hf_=q8jv1{LEUVaUa#Zhqq;8>?1Rfoy>!L(q+iU zf&Y1JrAqcP6}DDwQKenzHu!2ZYEji#Gnh*mIqcP>74P7e11o8gV7laLP4U3ROw2U# zB@BJ+5!9?%lQ!JV>^9FO!!iH-9D_6$QYD|P#_qEH127oKm+!*B8^^$Zggy*ZuXqR< zvI!W{S}|`#qy6+l382CJy=bs<E27x1BrZU^eD)pUYMsmR5tgaDL|F#b=mPvMF=l!l zWcs>lhYlU^{rBHv+_-Ugkl~_gCC|JegPCjAUA6?UfLtC!h7T8};ZQb(Jm-*9X2ubi z^DUgA$&nF}2B_(GBKy&M%Xz~)f~<58)~(r$WvuJ6Z^vQcfG}e^lZNY1)<&$|wiHan zifYvwpi;TIh)sw?w|+OGW}Pa$t!_lPB6t?7S5_}i{AwSedv5i?y7z)DbZs_$j^w-w zk;;$FzUMYz(6(8#X5qHmZbRe7jZMNRWq-7f)Bcin=24*70fRIQ7hilal=15@^Yz<^ z^2{SmNsnv_1m%I@3?7;zJY4D=avi~-4<DqHpzQde$eUXR6$u!^2p&SXyy^MewK%_d z6?`*z08$oy&20>|t5yeheEJECD9~<BpwX^<Yb;r`j45bG;)zj@lTndDN=*=CSVb9; z)fap1LzbqU<W^#}hIvwdo4;=#mQI*}ZSy`sMWbz?V<E4bLB`d*7xN$7+m9>cX!yyP zv`F)F9LjU(AOO<pNRbc@N`HZd!W<7)F4&H@r_Mtt?ffpqXELFa=@Xft5<dl81@MRF zp<07PJTm%LxXQ3!Wcuon3RPv(Ut+?_H?jJ_QfejqXjG*cnxi2)x9-T|Q-yf?>CprZ zL(TOBKqv|Lnd;<I1sF6iQdxq@!CVZ(yT5`X8>LC%s*<2Ci<L)HFF%0rCI{iC8RD*j zTF7{2Ix5kIp33f3>UJO6JT!=Du?d<4Za7kx(2^R-$3ytSa}%Jc>0QN#X3UszwA8gN zFzjQ@foJQB2&P-Y`yu-0kb>WCTZy;7eg|Gf+JwnWL3;AOX^M)f0>8>bVtwPAHT(I> zyCD?EFj+q}SPn(v5F`kPn!F{Pk4_iOLMSkr3k2wQ<YN|5E&v>1xx^(51?I7u7huvc z(=;a;Wu*Q|y&<!S(IN<(uupmh_1IXLzyb!E1qxxVTe|`JwCRGXp^P}<aYgU9hODfw zNl8g)(4YZxK@^xGbgE&YR`gi2q2%R^p+K<%2ALtcb?avQ7)Fd3VX3Xo7;=<!<QNL* z$z~H%P}7^2t6>lM#{qXHO%j7B-+7QH1O=ZFFeIG=XMqz@JTmqiHy(MZD?)O1<HOrJ zAv`k$nH0#KCrm@>4($mV!qLBfe@uUQI{L5>)r-?65mbmVNdQ^Qhu@3>K}rlU9fedV zcH9V5G9`5^K#%JH^VKh%JQ-U)VUnSoG(?bT$xeTmHrr~=TBAv~9;nc&HO(hN5n2OT z=hdp-sBfu#Fsfei;p`)Y`1bSVShZ*)QuZ)Cv@e#tk-s6wR<=mDzy=w%92)~sxwx_W zRcLiheT2nI=mvYPj<e5Mj(oiM)7w~;w8SuD|3N2~Jo_2)(hBjybI-9b&j6D`w<u^f z!{pCTTH^_=`$xf}k<+ow_<nHXj4=za>eC%&73!nF$fN(op-UMhaZw62B3=x?s5|yP z{2~h1tu(9J{J8SC<Ewda(fN@9a^^lbDNz1#eraeZSR_m+ee@@=Akd)N1S)5)iih^T zlQzcx!4nzaBpPw92o(6}JHzrFc;c()u`hE6!D9hOMZwKUCG(e$KwWfmQtQC18PrJe zIgv0I0Hm4FXsAecV+P>6k2Og`LPH2ld8~Y6ILGySfe4d;i{RH!KLTl&G#_MQlBQ1O z++_~)c?)PVWVv?MM)CRbgr#|(c|8M42s(Jv1yU?DAYj9N0=uC+8^NYP$IXpz$DQ@A z;@siGpgEz3g8ze%+JFXy+p0j7fP=Kpc8!Vu!CQJ(bh+38gUw9L149yP5|^|ylme1o zYI@$SHxs8_K&F$-64!%f-Otqp8JH&&-uY!wc56kZM2?g;9)+R#XwWPc4?f!kTi<>S z%g2pE9Pjnv(9-Do^_K`^WWco7U&Ww-_v4n^Z^gSGuynQnLvTKrSs_WpKOeORPBAog zf_%qPLdYqASrIpU@g;sy?t;TizQn@|c|azYJc*aJMvDg@K=irwnbMi1naMQ8s+5XZ zD>h?C(CV0G5O_n8#4y9JK3a~|KW>4GC7&I1dNj<Gpu_NH{zlzl$|n}o%EhG}>f-JJ z*TNM=CLGi}h_S1a&Y&7LmwpWsm%fQr`&Jm{d|>%5Y<TZif}}Tb`)#)x<}T+zF?str zu<6VbowTNNYU~CuNQ1(E0${()--FjjeNG>c2zXqD$O|pNkrwn}XqpUfp$8AP>W><~ z9KyE`4n!H!FN>?u#5;SU?XaQngtA-~b=w-NWQbr0M`EsFUP&*FY0sWLs9LouA|oSB z4FM%{QnSZvzMO?GHXk%|nzWM;&E)Ho3nw5cbrW%bDx}7tQcM-r`%qR!-ZcVJufG5p zshOl-Dde-ZOUB_WYQOk<?sOCMg?Ll=J%{_LOW=epU?^;%q&?@c+ZBf}nj9R3SqOLJ za_UQ`!OZAkRfzec_=#Ex0+a9<2V%-8Ww?V5iTn7>Nu$AY@a{UKT_A7|IIJqP%Hd(5 z3Ep)#M-frLYYTLQ;F@}!(Y;|O{*wDNAI$9F#M3jb=P5Wx<OHwixyc0m0uN{V+#sRP z*jDU-LC!8}_N1`i&sYkb%^kBO4R4mjpm`%;plN}C;Rvf6-al&~7eHhtzHoTHPC$jN zi3l&Gjg{)qd}<!t?qm!ae-Fzum%`keuRz$o9ia0)nmqgj8u#jndGi<GhR&UE<uzB~ zQ<gyvA!`Y6)o%%OT`<@I102`~?o(|G7gzhK8#ZF)xbZl&d?DhfGMB*0V!u3P6LIOF zL8x{8bp#1i&AM5~f~WG+g<Jwt8U@4T$mo;-(VOkWiUpf6eKH*~3*%W^f%*{%aW4IQ zWRAMDIRRII-jD*6sTzfwd$dQBmet5#$@B<ZoN`YOf&{(EA3`mg;AGPBnfPh<5}wb2 z{Y$r_zOx>tPo(o;kZIcU-+s60Y)){JUMwp9f54Ek&5y_Ko=l(?!^ja2@<Y5xy)+3C z7ak;F@S%U}htM8nF!`!0P%S^3y<s?JOd@k?e2S1t6)4m!4}3k*T<7wi=peyhHH}Hn zyZn`MnFm8FNIOMz@Q}0i%@&rrHv(`n<;aBf`1j+Gl(tc%Ma_f;7~HZiVyH>*Q0VJe zS}rKaUHIjveRyfY$8hkrIDP2^7ioyk+6`Cs7K9e0a=q_Ba!3TeIFt$&SI1TDuR)!9 zO{uA%=4<nMcz$1wvY_UGM;?i;iLBBMQRpvAjan!Q!gDa_iLN-WSyd)pBlzGky1G1t zbaz>*jeipVy7T(eCnte=4#v-)fQ)Pwri%ze`x@7xSA!djW=;;W`i1_RF>}0{ANqU# z`RDQY<BywpB7mu~+D22tGnce8ivq<C80_Kefe|w)Q9;=hIRoGIWUB=qatQ*TOcLCF z*p-Vxvj>rRk%@4L=~-ABW!INOEbaXcsv|wr2slG?QBW!s6J|V&U0=<_&*MjP1w=ti zq2BfTZ;^B`6}4*D!iASyjAhHI_U7WnT#ItY5<<GT*r_@~2E!1nK!F$QroM!gGhRh` z{=n<8Y_dnFx~+cY^=LP8B%CqSa!~bcRIF0z8bQY2b0sg;tkN3l{qVM2yf$Vo_A$4D zgP@0qz=VKunZ@5)gBKL>II_5M%Ec8oUV<BXwdT2b9+_e!^bO<Vxg{vMs?us(a6v!M zA?O&tbOzQWucU^-gP5EcOu2gu(@=+T-m5QUv+9%it*C1;Q|puYdJ<l=c2$qqM?+jO zca6<-5dE)a41NK#TC&51)G{2oWG6yf93Tmt=yk~h=$P05zfGZE$jj3REPOPxgyY(G zK1RZM4Ow`M#vd*`<-Kp|)^#20jvWO+99#SL?XhIZ5-ecG$Tn@-m}Bhy=F3_5V%>A= zu83j|g54}?yM}!?7JIX|nh8{=RDC?w{ys!GIG;r$9^>NFob~!jrXv3xzU%@dAPr@F ztXGn?7Ucp*5J4@2a;BtE8}vg)9zIV`!#xA~;#C$`lmAgj2+Nsg=HtDAz2R87h&e%+ z;gjji_eC^EW>gat(67PEc@UNmz?hi>5mt^cffG`xAgD+)^IN$|LiAmI;y&JDJ_ZDn z<Oz>{J{sws{RZ%KsC_+p*1wS;hl>XT7<jzq3W2}fBm?Bjro23%Oq%xl@4p|7rm>GH zc|UU~Q0#y~4@%K?wlj{Rv^XO_>voALSZ|hwfkOWv(;h!G>p?P*LO%a4bS&QkOP^eZ zQW?<*b4JqFL9PuF(mANtA`yN2w!zDtTA+MECh{q08}u85#=ZL@GCl!y8`Q^YRyTCh z3_!kO7V8E(@S;+!G8Tb;3OU%nWCa$#Fah4(8xhB)mJ%w_lYluDT)5%c@u=3Z^HGO9 zaWiQ{B+~^MB-kb0WW)XS$DR0Q)-TL<c$hW}iczCR&>(}WI5IS^;@N3J_A+Z@{pN|d zq1)xCQnMU5H1<#03EeHjG7VVJHF!DW$6&AqKj-tfQD47^P1(P3uMZ8YT!@F8^<$<- z+VKrVH9mggIPB-ZrnAm|a+(boL`ODuT-Q*I02d=A9=`n*<Q$S8zKeo_ITtS3hLBeK z;LCHOHvz*{RU5;*cL!#(w0ETL9RXP2;?}t1^%+c`P3?^UgN^R=uCo^r2-+ew^Gh$i zglC_97LPslm^PjD&G11^6a(f+GWo}3Qd>7-;dty!`NL?f>cuv~BklUr)J9(dnfX$^ zczfLE`0b|y3}yD9oFg6a*&7g3u#M)vG(LASO|VQk@9{4=1(<(06;bEb!SXe$5gtiE ztPG@_Z_<GI(=zZykM8hoTutE0Flk?Tq(ohe^r(8sXYK}R&#E_##gK7#GC7-`AKo(d zQ|32SY<2M*W<Kdoa-W{76n8EjUoZxTb9V4K_M<H|4EHv^jWa74`(!;dhM(9Iz@Gam zg|3q56X>-3zyl8)eJ1Sv_VFd}r<Vf74j7I%NoYcpsGm;nB=}cXmw-_dgOJms)~biO zlDUs237>5GWCZuNd;;6w+=gGj{DXdw5o9PXM&`*$(20Ck7X1{Opm4=I$Xodh#lH`} ziq+7Q>4Hl!!(xRB<*|hhaT36C0HZ>Z9Ed`j7nIG^m79e>7=ktLxo43;jY1@sv>whI z4^@}Z=hj90p~Dd0{8IKLj7*b)n+%L{&2(6+A_=s-Tpxa4{Rh6BwH!Ov9Y(m16(|eI z%4lkk%{9mkd3`3C(n#IxWk?<xT~rHwAGw;qMj8w2oO+kznVRx6SUdPiMyh-UQU`0> z<^wy>_r?2>(6kJ{`*Hp`7h%Z7_ns!epdRT?a{Wo#ntv>U^+eY<aCkctT2amH;qrCg zC3H+|!#oU(gYDDoAzV@I0=NsZ@zEV!5VD?CNGWhO(&RK`;bOSxn;@|v`dX$Ko?cDE zFVdz>n}+-DyU&EsDdxUJ2x#8$UIYPy93ORS(&@J_a^X1aIJ5!oh)|pxeLjY@Bfu;S zMf#y!%y{lg?D=&!qCA<1@f~D-k)8a!2l1SzVLXXKhx2HL@K>phao;b*eqLkZ#HqOV zz5&7eV_itkuagf~-lmQCxaVyMOF4p2XE^rz%Og4VQlz<R%jE%{@LUX^d^f6|UzUC4 zugtXOv&+uPzlVdMhEaVdh~y7a-8mS(fM&v+ZQSNV`<mCGPm|k&fPsMZ1b{))M6^)3 zYvpCAR;?P86;v`IM5)NRPk$vcLX<lFt=IvBhO7y2{L1R|lcJ;te?|eZ8N)01E*~cq zS=#T)#*j}RMga>rDdy|Omc0;}lz^F&XT!r7{!nI&<1&RoT!aA>;!ek2+}^GRR=+uw zNsMxl>yE&HS?}Yj8*Va=l*@nq-PmUR0vWs-gEOU9pei&UU%vJVetrK#Bos1?(aT~{ z^g{G7mqYvR-O#2_FC<efK}{`z3R5ogovg-)bMYrPwF(FK9mcbx#<O3cTsW1YX~PPi z6cbYB2cyN{b(Q9szu+p0R$Kaj^%!s?>Nl=J;F50!uJxeX!H`1Z1QrAt{5{zj|0IGf zhO8|GJf?r&uE>tfMYVSIQJ9_2YL%B_NOJ)O^;5!|bR`$Ip9g){R`ufKHCw}ApI5#a z8Z-ZRb0!S_5Sv$}7?77wAC3JqNkq0h%*AK`cQ?Hk*Hym+A)b8foHrlKAAJCk9M>U& zq#I|xgEFjaXqQH^=7<qR|F7$F=gu`?p-!DTSigS#G2{Jz2cIPybk7AC1dNqzN%#E- z0mIV^$6&|dO{`|>M%{#qFtklygdXwX$v&?jZ+8wV1X58da}DDC`v?-~gFvubNa37M zb(pVaE!;A80y=iS0c&>dL`^11TfOQRgtM@lfWE-HE-OGSJS{cg&V}FL`+?nQ-eU$- zg2p}mb68X4N}jJQa>JPI^MWWmKA{`Kr#V?TXBZyDKJz5fBAGD=3R@sO&6$f4-%rB+ z^vyguH4N1|qHohX`7B$yxPJy1cJ10_@{(v?DsM;Y)~(r3%_?4s&uK|JGbnIc0E33E z)Sz;1DQRau1uS7;@i!kIVhNnXE=EbrzMtV>T&C)ekp_-JdTui|%;}^DHCG%`eLBLZ zHQ-{LUJhhZnOv==(f-L;13GdQL`GRF9}4IwmcRBgUeifNWXe91Ndy=Y7RaO5HUCh^ zik9-erpiF}b_Z8d&T!h^>DZ`5LUKNoT36v_65vvavQzvVhQeH)vw$#!fWm~58KnUC z6ZrTA0C<!w>~%NP2Ze{Z!+1Su8pv$<!T8%KszK1e;+15aV)|x@NCrx#Er&`ocKUGS z<*+zc1k*-G(;$)OLepxO;h{^q(}&@70tN;|^1cX0xM%`;WyBn;`ThX!Nd$5Q7%tw0 z$jezYjN`n$(LLyV?&Um=6wNNgTi0|z<l!XJAruWB9gg~4?%@56<ciZ`=yE*Oowoi& zNvkbiz8o!Dv@ju+N&~FW%Co&$AW^I5e*lJLK1ZV$jlr%%o8V@yi+ZJ+;_()JF|Gdu z<g7b@*vwss_HAO=a2BFCzdQsA1$<6Yc@J(HGX-TYYJ{urxCKkTUxFIvoP(9Ce?fFY zJnyY_tc#{Y$$VbYn!lX?-jo!KYjGi}@*$Oba6X@x1Fl9);?)!>VF}2f1LO;D^g)H1 z1llHC$ojoB3#I}rf1_%!GXG@}z&y2RDw0w*m?_ZeoGZ}(;=4FIl<$P&)P>c8Z`K#} z#qwvn>Z+@-aN$A>VRAP)LfT;3{6rluX{Vh6#SRz*6yALEP2=QpHFMLeX=0SLGnWDs ziPkgD4{~mjSddBL!8t>aOLetbB`LKm8H2P6<YPx4b`xSnrskKYlmJAC!Wya66r-do zxNNRUcBHh(^2R3TF;QAtp-7;cslnBcNtDmu_z5aZ%()R#)CTaJ>Ya)?>H2<eAy;P< zUHZz^km^cU6(D(>xEzl+$&rlHqDB(zx496{!*`QJiF<SseKsIOClpXI`vowH&ROoW zJpcF`o|FAl1csVJ-eSClKQ|1Q)@X_QFTV$oMu(yf7NwJQK5Z>}W^>SAc(JZh^qd4h z%ALSIxk-;Dvo_(~N#B`p*gWQz*mq$P!doVr#8h_^FkD}!1&^h^r_hN_AI`+`(Zdlh zT2-xs&a>yh6(4H=gZk{WZoEDn)8oB+_o7ObDrVbn^i^rpsL?U|&$ch-o=`}dBww1p zn%5-45&8o?O~A1G$R=XX5X2uUjoK><;9CAWV!VeCO@Zv@v!W*@hi0L?u=1#L^X<5- z_Z>Ktn}J@vdt&kO6}a~LPRySAA`+`4>WLtp<uhP30x~A>PH7Hv4r=DRsj>4gfzsy> zJ_OGn>j)PZZA1-Hs;fQ@MYKX{L@X*bEQLoI9vz;*-wAB<9O|zrRnPA0tO5+#&OD4> z{1SE~uQyZRvMTLyU$ZU-SQw{Ap=@(~o#WUh(6DvuRy1we)YO%bSwiIl^t_eGhhu4V zI=>Y=V9=zfU%$SY6k2VROor2W`~Qt=+Y(2I>N6i~@;5REFXpXVjKyn~!ovbo0dfyH z0~(b91yXiq0di9FC`1SfXfIU;MInIzBM@BvROUKJ1;fbsyD*bvrhM5rAT^zdpO|${ zOogjj3F<=Dod_+@{0`;HQ{FQ-0tK=>_;WLvH-KK^K4qq}xEMP}=15QTfP4}pu&EW0 zLl<Q}YcvqZP_v<91Wp7Z+~F?7m1mwqMm_imR1_X5HRw?=V2@o|1T%QP1)G_-+$=MN znsP-P+?@npKCeLnC7xT8Q3PVY>;|<haa_T7Ykxb=i?2yY#l96&GuKxi#H@`bggzSj zC|Yr>dw<Wx$opSIL_q>;U*zDx1qTt{b}#Q!0Cx~D+*qfT>8+EIFTNvbc(uJ8SJRQg zlXMz885Lww;t{&_4z7>|E|eIkXcJAtnW#&JhE(#pbLY-QcmF*<Yg!0JnRgOL4-Gfy zP4`5Ajb1*av)1(lxZIw`XXEMbs9{L^gGrad5c0!*)cWcV)TQZwX)jFjtSp8-9$~0! zLAi5rY4<zP@}7=#Qq0HAx7>gQ-+Y5=)oWno%9SX~P*z>v>V{s`w1J=bX6ecJQQ9+K z0lWwI;@#WsLP82Fl~Nm+%9PRvofjfC<^rUKhv53|m*M&@m%taMXH1?e)WT^XoKw>1 z@sUCXwT@#}ynzi#s|a`kxVUm#YSg+Sf`irqLD$vq3@P-}AZ^S(e%E4BS%3v9pLymP z3>!9#Th(QOEB?5oopuToJ77=|8m%xiIW!SUCc|l;1OK!GdZul5W5k^K!srC5Fbl{r z@+H8<1auZ7ki-;NjWOGYk&li?>K^(Xu>7?#HSnk~DpZ}>>k*pq9p>!ZgZyxon5NG| z=b9C84t*5lBM_iqaWYF?vbz+T-r5`2^zMfZJ2J5L_f6QldmnahJ4_1&s~<4Akli_D zuQ$sYX%N^0v1MsceRPrxq3KIZ$w|9#jwb_ts#%-2X^1<!cSb}E#Ww|<U*--nKFvpq zlW9O!)Ar+=88y!-HE&^{00S7h_BB`BqC?L<_u{Fio?~tU{fbt89>-dIhz`)(U4^%b zv5BW!_f6xHiAJTkxsmtJ$)J2+PB{AAFb<*FrFlQ|vF`%f#@p;RJ-q4sJ8@gx_6FcM z6k)=wn%iHVjHOe@Qh*U?HEM>N-+7N_7lw}Tq|&D7)Rs@YImOYJi!QndN(=uY!~4#T z<UFE;{cK1~@*i)8nO>ZpN=vSpY6(kAbCwlSh$p{&7P~UGF@;DtBER2(`d|NnL}E~v zlZJ>u00Tk%z9pnZ)J95N6uJ)Yi}Ttxq;CPxtKYqt@!A_^5hh`)8YL&P`y2Ug?vK$s zut#hJvwY}?5wdV(=}NrQvpcHsxh^Cq$o7`P-cqfQ9C{w&swZId+jr6gB@?7Tq2<e9 z%!hpDggerivtc|_p|9VylFzRL7gcGE!Ogm}N~~zX(eg5)gTRrleLP?gC{UDyOcG6+ zG{H|l{bbD6B{D)c>da`x4j80rI{*Chxgw*tt?a=i$nngW34hWHi|vW^Sr56yvh3Re z0AhzyN1BweI?yyL+|kLEf7*d;y!zZ1*z$WaA{ZLxEhr?j2%~B>6@ld0_-xNQl%=mg ztJ3jk5FTj~FnP&Uav2w%jtWSNs>Rh!d1^4?DEKA)>6z^c=e!}i;q|0twGtqS`G^Hs zj7dE;D`=BXL751dufdg%m<l0ibKQlwuw`A8sls{|Je|1MQO$zpB2OWveoQ;T92FDO zwey(=ze|@c`24fa_&XmalHm=!kG>s74J>L|eKU}X$4l{1oJ~U!Wh_Z04NDL((7%K0 zLin@Xcy91V*t;f&H1c6@(<Fqo-m6aIhK9G}j=EP6{;6IFDN0pM#@f}Gefupa%~IZ( zk+Hbzs|9dZOyqr4W=xBC$5+}EtyFkQU}5m!!KM(Ey7YH#qPaw}1zaU6dEbL`%DNvG zolN2|uFTz}tDoh+e_in{#%_Keo=Pm8&Z?!Q7VkohuePD0KMq+T=OQDr7V^uLLGP!! zphlC*%mu=G$eUZES`8dLl#DsEXXBb{t}$di5nr{QVfBjFGkxM@WNrq32z?N!RdCZ! zXyeCo@zdy$tf<OxX&$r3UlT`SuBJajDcsP%Ij-n(KF`nJnarzt_W8%}(&A;%WHNEp zO#HTe836;(v{Fkva%oRSBylH!vX0bqY93Xd#n6N(iffLeeO69}%9SgldiCm9yLRnS zf0q-D$NE*tYjIMb*a3sBVXy&%23s;2iu0ELhu0#r*8?sFBW5RgXSoZIA!?sa#}$X( z&1W7-5p6Msd@>>i7|fi)ng!o)pt*su;9QNk$tgUU%kj;YIk>T6G@3?+GO9u=bqBM> zl|puC9j>GrFwBfK3uv;?YS^VtFqA8xm9BK5;!wPxtsYf3#DRi6;ye4t6}6l)<13d! zr@LFDS-W$&A``=+W<oqq>GU`*({Zcw<}})LY}18~-J)+YV@P#6augYCR5Yf)F#|W; z!~#0v;_RN@^sZ~kUQ8cDqgp<}skrylG!4rzW<x9i2HLJkODAdIX8|mSHxeIBU4|b% zUdR50VDAOn5ZdMdfelR#4R6MswXb1hiB^;Zhdh}xFC8<l?S!a3+qnvLpv41^pjw~4 z#`)CE`CytExb@L~RoL9!ci(NICEkDk{S&T$?PLEA?=~qk7IVM(5~L2d@Do?v611!r zkKCl~SoF*&EL^o1+is}`)T@XPItzy_Jb?1wrlTBJ`00^V;Hp{ygP!Sua@F`u5Q`S_ z{@uqM7t^Ot$D@xvg6CMD#5|LFF8OzSQaoMXn5H->tyR9RPcWl%sgrun(z7w=z6VhF z)A!8(z!L3z9`}b_iv3Xy;Hemn7vAlQh$un{MO^3~=YU2iB|<i1q9*^!>a1Ir@KFt* zarqW_^zz<_VBQvoOoIGp0|rAA(;@2tQGX=|^sZ{g2M!!yCD%=ej*c#o52Wy!(uy50 zNW&nLgzTBdUTh}ZnL>_|ejGyqJ<t-&h9`(YSj{}_{3y_;8V|}+r*(^cD+9(f!QY7& z$ia@QnBSJ|#<bCM5S|y#Fhv&H$=-zDH-CUzDu$pweF+L#Iy%*nh}`HFi~}#ncyiil zsimN+0U00HKhzc|{47k72r`)RiV|SFDggwq&wl!uQ$hX<Mor2UPN{NX=+d(@8n>vx zgiAb;1h-+P6q^)krXUY5z)hy<U1PAvVQtlwI1qD8@IYQuW1li*G9G^T5ky5rVb#y8 zP^)Ggc2-HB7-7K`x1ke1ixHY4fINx(7ub#BZFb+yeGzk4&*XVPniYiL$9Ze;{<x(C zK#|zfWGex~A!CESs&*&zIPXRV+ey9&G7<{X-ktm9*O>e8K$=;6*h(kV$9`Q4M?(3a z9|JFT9AJ<T*s^5{>eZ`fiq5TAv7&g#e>$#4GU(CKypdK(CJ5^(G1E}whd-|n8H{9@ z^-w>Q&Q3uRSM`f-IS<ap)d;94@K-ueW_bd`S`!gb!Hr>4`XeHd8C2=8>!M%K$M1ZA zE<L)T;|(|9(>Y8NZB0@$+CN={nYkb^ZS}?}6wB!#0O98Y<)Y;GXXWFS_N`DlYp--m z%mkT0Uxqf=8CDGg$KJ{k?iJ0Te40<@VIgned2<LDru_OYRvEy+yd!0s<Iz@q5JjBo zFlIr+C3tOfN$Z*7Ib@cx!Ghig3>biS-g(DVvy|hb4JJ;<Z7jLwu@oqFz@UnCa(WbC zNJ~pI2=YYswqv_l^6m6dASf*PkXub3EY>7`sAh^r8O|skAYkzi)@A*STWChuy(tB+ zKQ|Bi_axy^`VRcKZZ0n4YNbQDbI4RH;XwRl$o5w-zt&1fs~71j<Vfz&ikMD|a;TFE z(<NU3p4_8wO4`m<Z4nF$Y<NK}v}}I?D%WK(ESep}7Ukf`4p@Jt$2=i{jGB?1=F>l3 z<X_`*69}m%?1z|`!by$!gNNni<)eG|?wCD9odlr(06+jqL_t)07UJUK@xziIa2~7e zX{_SMqKh?de&9EKw)aWs7HcyCLRaJm0~oCPBZ*}~Kp9E0WzAlU8T1~L`NU(-`P&iF zh6Rl1+*ZR^4=>#E2=i7@kdRyg_yI<|AT<p$+g*mz)HcZZvHjE;sNA6g>CA&9IXKwk z1y*u$vME9p8yjm@kHt!ZV!oIFCXHYug}@;JGlj4;G)`)~{B({*4$V1RcH*lipFqL3 z4G0e~vWIhQCnw_yX&9Oi;Bx*It}czJWpSv$64B4R)&r#ySrCf%QFDLZSMyjh{3aC8 zm*>}Ce=#=ye>F@qFLiq~CkRM%F3oW>SBpFd0cy?`PkkF}CcnUX6PXC5HsPSREV9eA zgSUDOJn?2<W>nQp<{9*3A|gNUy8y$hYd*q{8^34zbO#!iZHA$(?nRUi5^7T8wawSy zXM0YXeZiLxKl~7P-E|i>Z{BSDF|_&k`Be1ylF!9Qfno;?J9qAc61a#di;0vjUAp*2 zTXLoUhyvm(TFdKE*J{)>i$m}UHqXAEf3x4L!VL@3c1su=USj>o2q&W$;L!(mq~fcu zK1crtdr|w^0JpTb2S;|~v0xSb6PUxnNg?KtW`cTGfd(g6UT)^M_cQFQkkJ{@^m!=F zsEVr9%OJjD7|N87MPjw`D4$pcp{3Ycc1k{3gcIU4{Iga-`m8>g&YO3>XaL7IZPS6l zeG-)NbI8fb#n>@p@z%^Yv2Wi#+;a2HR0ThV^BbLiLWX8YrBmrVB%hI`a%-?U!4JjI z?6H`^=!?a;Eg+=pv!Y>!4@2&nh}>j)#y2_$2g54e5q@~ry71nR$%tXJhp|IR$SC3^ zKL=m-?16$`f3$#G^@h0q{kP#t(6emQSm(ByuBGBrdhVraPEAdPfWzOmQMI5tAws%d z&OO0rIhbZ{T#pTOj7?j)3Ws)Vp@yaqk<`!?_@fy4kciFkrLp}wW=TDlV2(8(^4CYB zL3S++8`K-6D>1hTHE1fWK9)t-UU+_t0kD%9K6&RIcUWNUUra1L%bI$;jn>@e2R*j} z4%U4OJ{|0T;gJHoKWHL+KYhSNV;N=~Y5rKGQv=v?$UV6HmgWXDNV6vmfzF-J=kvAS zW?}KhZ^2X@sF!ddhP72Hbc=(SIVWoHGUiI=vf?Y&oa6`7G(Y6HdHLm+<5LzoQ!80i z8Zw;rmtqGDJ9g|as>wonT+6|wY+0rqEoo;Y1@t^0WitG1=?yIA5`5&33RQamM}?#| z=urLXP12HlK}lYeu6gm|MQC^B6}b3<OR#M55>}1$<Ch<{V9Os&`l3~tz=Bwr(F_39 zYE;E}jq0LoB^Kg|;Q7dBl%3Wz!+p4ct6wisiB@1nTdJK>y=o=Ik2<H>#23S&w9(>` zW_!^WBiy;q#}%|R6bJV2H}>~s%a+j*D-;i~boSGuM{}Pv5%w^HW{BX4tZQ1AFrYyj zj^&L-FL_Eo>(XjRha2S65*fTHc<Z^ZuyX!Z?5fEmPHodoW<T%RaE!QaATDZB7p@51 z4?5XNGehEh^Y}0vn*9!w0(p=T2u0g*lX32~9jWD!0plM{D?<S;nQ$66Zfw&2D%+#9 zjDNRg<~Ro>8VejNW2l4Lg+Nv|*1h!>qf5qf#m<Cvq@>pN`FvRN{4vOI*F|bvBkYWD zAgx^r!t1eoHGdnnKNhbJ98X}uX=5HNKMQ!x!;PJ8GD3gc_~+4!5jmmZtg!lT5c8Nh zV7~B$&xW3HeHGM`222UloJ8C^mT$$Zeh;ET-gZQ?0GslrB>U)q+@LK6ygwFBY6k@v z_z)PAMjoSurmvZU?>5diPLK8CnRu%GKt>1Y<eWd8H@d>V0t_08G<a{3W|9%Ac3Prg z5LHfpD|WzOYZzpbICA8ONzPG%9#8*7IAIU?pj(V2xR+ATUX6&o{6px<nU3FNJ5V#+ zOA<+c{6eQWV*{7e<S~8<kyW%~U)HiE>aaM@`VH%8<5hG850_0<ttbaHoglNJZCq#6 zKB;)sOs*jP#2jNbks(?8l+jS;baSd;S9oc2u+~*#UfOHDTfa4XgJ{97Cb?n526VWh z13`nF0Uh}4)6a}Iy5_A|zm>zmI+uQLE^+j9);H7d;J#z`A3gAteXyuuk;qV28~A6o zlkQp}?pT?I=N@_;2kSBsS4-9wAeYZu<;L}uFGIfpx06~j2Ql2$A+$#I^V;9>#!Vej zK_Pf_L``UWJ+7WSiK=LZ#RdmxGkM!rNh?MHE~Wl$+qUf~8}I2ju?-e<ZEO6TUyKU! zCLh6P4?l#=)juJQla)}Gp~x<p-a?TPQUkf6^^obVj4XE~Q!-~F`^rNIsdgCdkZ{zA zZp><xy%ED>l{;kR&%dC3yEgFfyu%(FjweSv$)F)VTNL>+ejGoK{~sMRuTB4gN1CsE z2|h38`PDW~5+C`qCyP$KH!)Gy?q3<RM9@G7;#_L~_Bku!$_Zm|-c^@b&X0QT`9Gf; zlNoE~V!_6*2^a#X9n%<3TzNkuE_exojsFBNe8Zd)9Xob36;9i=YiIgh@^bnqQ0#y~ z8V0E*wc@bR<LM_uNe}*%0v3<4c9XH_tJVo><PpIZ1Pn#CSYSa%>sU*$N-dyt(b6)k zUiCAYv8;6k7N6RCV4qR98nXw}H(LzXy0Fd5jHZA)6cu52NoUrdk?(vDc8ecuje^xf za}NH<fCbZadmP*r+#bXTI*Vz_Xeoi0mzPV8Sbgl>yARc?SHmn8!BUL)@y#$pbM7L0 z)Y0HJebnEvI*2027WYSXM*Y#N09NjyLOgQ!YuHgS86oYGY0{w;eoY+e=O<$9_y?#t zPzW?(7OQ&6m&2dMYKQmsLe|eK5JljW!qC^QU(ZKKVnyCxdz8Fi<|3peg+}jtd*h8a zXW-+HXW^EcZYu5(|Lg0CCc*oqY@~)jnr|GhhM`?%Jm%#ebIebVL46aLbdj$)nES(X zcsG{Ln2wDfeT*1JGsx#w{y14aH}XTzWdu+yhNV_PUO-U*QH&4@;7Du+(yrW#sM^%< z@O(8R8{&y81`#kgvH!q+T;8e`_Uze%tC>Riz4zWn6jQ6qcR)^%bPxWw#%B%+j?oNC z8#Eq!;QT6$gOjEYuxjPxhd)Hhq7|r^yAtJ{dwFO8=?r`J*K3My@4f|BG!swJwBaSt z_fab%4a59DzJ!aZIjTjShmlu2fLPMUL9L&jF%j`7HG`M6yTiSv=~<F<yfjizJ@pjL zevg`G(cWM3e)=d-?0`WUhT64jmjH&-ch67DmF*Rn-nBAUf*GZORp?iKe*VA35bPD} z@dL1g_3>=y_@hqz-8k|E`(&R-U{?K7R?=&)y%yWHZG%=hUwrX}$yjI~cj7bt?`+jL z)Raxb$F!Tn`n-;HVf)~`d_O{Hg7B<PK-~6l%$zX-A+gr6%DdsD5M?DV?D*_cEExPC zDup^JL|C%C??5zR4hnx*1fxM%JtSxzlB96bwDaPWNqFethcRi=6x=_s{~1Xrn<57A z8X+nbx;3|C`?vOsXw<k6ASflW@+nA5<MuL{Sb7?E%$tWFrcPvXvLi^K5S1{_pwM@h zu8GKVF2PURsG$j|$&f`AGh@^PLuh1rONmV(U|<!>b2E4W59-D?#iJ~59mUYcHf`FN z436iXdoC1Zl8}(VYg(Z8WD`<j^wHGhqWS5^IXf|H{A^Un-hr~Yi%}sYo4K9>%u4A* z>v1om2J4IXnfOU{S_(*~nZJFCFV`|<cqsygXaa@~4>8Lr&31g|)fA0kAip7`XlpQp z*;n*M#i$z4k@(U}FU5RTwLLyWwCJ%VpNo$IC4iy$XnodS$!2hRmj|@M>;xXNva%2v z8EI_Ye+CNvY`chRpZC8ZuyJT)A9N1=+2%2U1Enxlp(KTQz3{>dNB7x);=j4xne-ct zSIy{Km@{L>)Oq-D!(v3V&Zd7zKKvWX!~L@xBZl-vlXi)M6$~z6U?`WMN(1dn+KowV z+M#xcpJA_l9E>fCe&2luXLOudruqrGWXE@kuKb(#)mON#Qzwjiaul8zG5ky-MUW2C zfQcpq0t5lln`zyyKg$><!;<C-H7GpHihkfWM(HR-^2m~<c<<rCh{{YsVrUq`X=BS~ z#KAuLh}7%U3yBRnVCox-sc9(9910$Us2D>ahFSue9NZaj*U3i6ts&T+v5HQEE;NX1 ziig|w#r%&x#hrKF$%vddNJASD5rNQ9ntnuA&Ru&BvvYsFY4{qO(+Xqu9&w`g4Pz0P z>qKSGABf9YgfedKqx}E1(2e07v%7K?0)8+PB`{~h*ZAbOkAZM6&WUb-r>+?MUjc>` z7R8d|qj*DRW~K>U{_BG)Im2J2KnY;@s}wBx{l85CTR`atc3i%Iz@bBj{%N$#KLZOo zm(KgIj?r;{){1Hw<jvo=Z(oK?&PD;VIG)E6!9V`^BVuA0q8Yr7&8YwEeE%!ki{20A z%Gj`WFCKbn9KtT6uR>%tJinJgsnumrr(8LVe!Um7P6-ECiJv`O5xeuU@zYb|uyyvE zh^25mO!?RO-H%bG>4lWAtX|3$I2XqZ8MLI(ZUT&&)oWrvzy6p!ZOR!&CZlH|IADjl zB37ePz%(mD$oAi{-~;zs`9}&FD#@BSD<)6G#@X+q9BnUNYN+xFDp)B3K8D@4dGINu z25R87R~92YpS4P5?qb-amq#$vfDs5@#Mba((6sJ&{+CJEmAZjptPa$rBV?~8ci`gM z4NVBTA_lIz?mDYeeAS#ksbE28=B+a3H~|KI^@L)0?-@wj=0#La3d-gzLnZ%unxXQM zLk&dJAy1)B_q&-g+KoJp=)(=)VeT&<!d)tWDy8aS6ahm#{T_&H%=!Ku4TI*ToZ`=6 z#Z3VRg<0Orh@_Hs`YBKX7*78^I4gQkRM=|30tpo>Ry0gcH3sAtU?20J66C-Aovvg5 zRyjeIELnn4qedBXiOgo#Uw{2EWp?e=oEY_A0Vx0J_)gXF8oSl_&i{oBne6%WNTgRg z2v<}d3fGoL)XLIGU}^BDXZA+fY6MMOP?PsF5fufdq90h>W9D^NBbH^$l@Kbn<(0T% z{CJ~faL{{RKCDtfQ$!l!7F((muD|v=eDLu{r)pS#;k+Ci1-)otnj|KLxxj%OcbT1o zqo5#VGywhkkiK;%_WklRHoh|**}Hc!nnCk|M>8a{6q9(xw7d+Lbsd0xNgllM+~-J6 zV&zG9go)&F1Wg(NM?Okd55b66`ywr-5YH@}h~251NMJuIdMo4b;$8Uay}6h;aiRgT zns@e`6<Dz6q5W=k{J($I(Di3>bZDMaJM!&&EAY|FKO)o<jWU4)h^Gc5!M_DD40X<n zh)2uk$0D)Kr6>#!!zY_o;Jshoq7Q=)=S0=V$SWV>u?%OTO2W{F^f_vh&{%Y><GO3l z%PX$90^d<%B@N%ysZ)<Ts^shGpg^$$2Cd)}QYDp|!mHfO0A{O!PX_@?u6g<>pcTY^ zhATe*{PU*9fO>MW7~hFTB}Sw_TkzZOvX@?P!39S3DRr+>?5aSL-TsdA(-t}wb0*s+ z*UqPOe|zyfe3A4CZO~qL*H=R1(geh3h2qM4F2ap{FCl}cj)BH}#mLAx&cT9VUk(|J zj0K-Dm2d$2DIBhz@)D|byqamjsf}Q9F%!x{Fri;Hy`V9o!XvPZ6&2O&ewZ)C_;RA_ z5*8RUgJ6Mxk!%qvzi!sX%xFnNIs&;_$Y4H&IgdSt+}+!mbjb&${tyAP7}-#%!<D#t z_;5H&MRC}XSpEGTyfStULcOYoLIKZw9y*_s{vAH1PcC1JU|~ux_@jMDWsZ@j7fnLa z;VtkS%*B!^Um|Z$9-e*b89c`8opf!2x_yEsA#R$c1;^*7f6FuXzm0vH@)73AMw~AP zu{o<y&bNtCA9+Y2FuZN-1jJo?HNM#S8)mG0o%6?!3hr|;`r1cOmPOa(2O?l_jE3P) z07LNV482}#d^hC$xMs~7t4n--PbH7Aul>L9exf;is{38+fI$P2T}n-P!i(!6Fc&O& zIin~b59pC2M;iOAY7G>}15nieK-ZHmMT-_pM@<cbv<jcGh*YgwwG5qXK=Jnn4A!(z zZHR?Ce#c8cyvPcaT;y&{Bw&a|`5Y!$O322zj~+k>!!2EYuCS?Q4logh%8BPPcgEYD zu0<lv5_yyemAZ68^I?xtz(%oNhr|RO1Swi1h&o==5&P)rznTI-iv|0h+wWFSPW|ig z*Hho*%%_ZtCJm9i@hIBWs7ydeKArvc?8kRcjmDv$m$L#RlZjDF5JuBN7L^dLb80ix za3W&s*EG2(0!+ERV%|2qJ?S$hx?-M$0P}}%m0jq`WI1(eTL`XVs=G0ALN`Q~4dt~9 z8CnU9{(b`fV94rEuPi|3u5>Q0C@h(FJS2qCL&YR4MGFcBq9-Hb34EOR;gjDvmhTW! z7=}nXIL7*SqiohPdSmP&%?gp`3`gggZ{yc8eoR|Vzz_vg46BXN*F1`{G*1bCiJI2C z&aI1_Si`_Qrs-Lgj1Y)d2!07ruqk7`Yd)wICtZpiFxZp+_;-s0C9h`_1r&Xt5L?w2 zS-pDoDF=`C111`a8I7mvT-pr*SotjoyeRXi9zgq8`*U$Vl*KUziavk3p6u3M+8S18 z?7%ahjHF80je_;%QEFuwlu3(%H#7&`AHND0T~nWel9ddVz)4GR3O-+6CKhzP7ujo; zB24}YjW5P^@4U-`RFQP-lR1J~2?`lr0zG?o$B#7qtY5$3v{oXt$6u7z>Ys`KG+CGU zg}DQ?%~_C#Ba0T}%O{4K$cHG&QEty8w8#vJM8g~IM3Wx95nj0h!Gf}s0*hv?$H&ta zz?Bol(}WRpSYenU3@<DQq@!|!SUfhq3&Nranm8Ags40uilcVN5k6BZvWA9H%NQh6s zx8E*7qk47Ce6)e<sh^7+fCkRzfI1OFlH{Z;JknzlLUJpzP#kNb__I+Vkc8Nb#VG4M z!aM9oPNnKNXWRpLapR|Ob6jOz)$#Q8L+RJSFif6K*zw;13`Osac!R1|u3NXxXr@Jj zqR(d0`**f|w&|d8pZYmrQTMa}23@-7q$sYzT0<^*JyR&4IZ%!cbvZ2Uo1UI-%v7hk zZvqPPnUL4HJkG^{?!W(jOki1RwW9O#RQKg{p5Gp)-pOuES3FG2v^IMmM$H`wCu;?G zH&%dqNen7xmLZ+;(V%%E`i{Gi$^|+_5-=zUr;~ud=gq?g+Syk>Jq!s9p-77^jl1SA zhO2C8s`eFr$Sd%8U253l!|>KyGZ?bE4W;PMpzBM^SlnTA_V|z91NP1Ig|-MIl$adJ z!2xD$-Gnu-zJ^U-e8%$YbpEGc_i*K%$xMi4nl#5%Lx&-(ejU0v5J1scGT;qh#e$7^ zYvO!_=0q~olERXC5<D&sg{q<=JV>k)gQ4TPBD9PsZ<)#D1er%V+|ctzeE0DeT%m`c z@8AdU%p;=_$@7Xn|F6$SJAbl25ZrK#N{(g#gKiwlS&n`9J#1N(M-7u7VZ5X}kd1Qb zOOfdRjd>>WnDNtzO)YC<)8*yiC>6pgn>8`I(_<({lZ3#B$=|`>{VN{^do-FCx88ay z=FXjKOft_t`>fejd~~pTa%R4Z4t6Up8G2d(g9c|0wzvjr6Sn02%%OnhfSet*f|xmT zrYSgMucA&>FICh=5fB0nVn}bi@dmne>t+dw-~(vS&%g8Bw3)7X4k;X@2k?;TZ}FsJ z=zEVdN`gKLo68|=Spv$YBp9uNJ1h_5J|7HMX@wn922lRFsFwFL$&+u_0ZeXl8LIPh zDh1qKufGp>i)Jj-EKP(OJp;JBoHBJXhL3n0JGSqnHmA(V;{)QI7VgpF|7Z(tI{N+S z2Xn7Ah@)EwZrDLNFED3>pXr>JzBmaRKAeei)DOtPQ*i^?Jh_j_#%_J_WyCO{mn$-i z35)m}hLAW4ocQ&dUG!OC`R>9pa5G7hlRf|eF0Dx=zUL#Zya%IRx*rkcNf$T46iqnF zeCi=_UYqs?9(aJhGhqQ-a_^OB+vX|^x#nKPGLk~~Nq?HNGUc4I79^gDZsA2NPZf^A z<3{TCYz*u92D~0cdJsx5#5N&kE6QgtqB&|0OHcW*Dlr^McU{crkWiEht4R&RV<>NY z807RQjfLh+u=k|BzFUT$;I<-f8t;=&K50tGSFT(c@-<TXpL;Gf-XinN45G-(pY1L} zrlUtoPi1^+xJ93(%~CTwOYdg(|C5WEqyPJtVh0R%S2Y>TAcODr_LBFrhXP`LG6OvQ z^wX$OqXv|M*^V!_nS$oYe+nXwpIf?)d?a+Oq@*M>@06>4=+L3&x@Ql?|1naVM%rS3 zE@YVBw*13*^n;Ob&?Mp8S{k8CN}=qLvMl~ZCgdnUldCGA=dhdLp~If)8@MT8J=8da zcwAUb=DvCMTVz_SgK$wRbb9R-I=@Mapuj{r4^lYJnKK8s-*pG}F>|K0ODBy7NYJZM zok1L9*ro)LwVD+iQm^!`H8c0H@8*vmRe!`y$32CX`g2mT_T9Je#|Iz7cjy4qA<OB} z#}GoEt85iqIIy3onc<8mYjQQH47HPhfQl5%dwT^wdt(X0{d92Tm;)TIay8I>gUW{j zBvf%@=-6(ErBL-VY*9LT2a`6bXDeB8@`@`u(9DsAnpf0Aookz+UL~c5?u&T(02FJJ z5E8mG6tjf9q9(jd6+NQYD@fhR0&$d7E{;zbCgXG0p+?~XnxoROsyvX?wFP`Jkw^$h z#B-e=M>#J6PY5GsNPTG;4BX-Abqjb38Mgkkef#aVxQdxA<-?(ZZz^}K=UEyTn@9ZV zkI#f1qNSlH-!<ieeX^*k?`DSbS+aLn^H|$8b<_-?A|Dh&FC^W==vb^$<O*_@L$UD> zqJ~PKG=$rfhTB|BKR(H=*a3rXwo&<!0Af^X|EWMY$uuZA-D#qL=0aXxp7CRlSwiVx z%a<p|Vf#-7iRP02?73w#6P^F{*I&nj4?bx2D|?)P!;LrIc=S5v!&&xXg9Hsb_!x2p z?ZFODGKRcE4Fg^O{o6~!y|@(0r&OTxq9ttIW$3m4RzF0Qi!i@aLMEjK_IoJmHf+Zy zw|7F6j}Cm%WpMYGUm~<ZMP7l-jDSN-a^<q+XnA=nEMLA1&6+hc_eA%~zF+_8Z3x1I zAX5!WA)fDOD*`0E6oT3#0c9Aq<_qVbgu0)ZD^q^{6$?j?Lcz{WD8++Ri^NN*R!9&M zQLiDcnKTiRiB-t3D6D9L@JY?W<CMs1<I;l|KYS*_kpNE~ZTyUe@Oqgsl*PC_&OB78 z;l>jadLbl%0)i62PpyPfa!X5-mXeCfOn&6$w#t`P!TGme23L$5wG+<Aqiyd+X=)gX zzlpMfSV7T7MC7EFVb&`P@$H8M_8#?#$IvuGmqb+ZtwluE&)8a~06V*143vvv(W&xy zw$pGV7M5Z}2oI-ffnFgbzV1Nq9u>J&+-RCD7xXSuWrYeA3`kIRSmi}gv*n2Sa;Coo z1-}52nt3zx(m(-gL+}`*xueh*j0h+Z2u-E}4sygbfLCU(3@<h;{~1SiZRT-#h^kZ` zO|QC+xiI7yOAu!enRTs`{d(E}g9h?Hb<<Ba<x9?I?!N?u>NCivVA7;X=-02G5h6ux zw*QVWvFDPQj6j0Iux8Adflog9#Dq&;a>*rl;)y44<&{?+6;fyOEjS)9h>3YAy^?(C zc;Kxe%%k9?nV~G43u967NFqJqxrC;q%X8(T`So?s^Wm!{E6hSvJ_=q(E*wntH<w9# z^4I<h4>KG#y5$ZuW+aR&l(`4U?&K42=-?qFR;-L?pMB<NjR5uKzg;wl&+1S8x1t;P z!F*$<D3GO5kkBLNwff3~ee8!AGeti9nOVqM`3qLFHp8~%-yvSinsYLP$ECQ!(X?Y{ zH0#<0k#)}Hc<K6Y2F=syq7;Ds!T{F&a2Rim{S2NAra3QQHA*t>5DEl2JLdYb5JfY@ z(6K#GzGgIk!<D*zD~$$)uuNkQ-TxqFyfGa;9~%T$i#Q}@ZZS;1R^0g*+O|IuP8VP> z5>9|Y9hUhd1m4sDhW33OIZ4+2<U`EWaR8Aasc7FK8lV3DE)L#R7gVw!JUbdw?s^WT z^O?<(;k8bNjXLQk!$cK^jyk=Bpk9w}niG1a#Rocc=wR|O$ZUDfJ@*)zY5V_DJ7$#n zqCd5wL+5-|Q9SK*5Ez(aIF0>G(=9DlpumT$U$<cPh-Yy)X&pAX@~|}h0HWz%GOFi& zxc-Ibs9oR>)QX<h+Hz7}Pa9y+WKjEW8O2E%eaT5qD+O$(p!b_@x(Q!$McT7xPrUl- zt4D?UzXKLD2r*t|W)vv+=%bHJeg~;BqoSe=5b4sT%h6S=&Z%qa?`)la8oNzfel+~W zM~1a0kcIoEKLBTJ0Rnr<!}o0rDyLM1n_+}feR?S*b3>2d`RV<P0CW*8_$l~6vxLtd z4$tO4Fynewv7~Q93RmH`e*Pt5YuBgjCIh7AftibVPhwg9vn`al(7qRTU;g6>S%mQ_ z8be==$$_u>Z2w8+YcP+PFS986GBa@CyG8hx85#@r??fE=EVBieniy%3vABBBV4TZp ziEh?xVC*CT5d|bshMVuo&EOz#5LkG7(mX8xd^1flEF#6KlGfsxF%inMKmi$3$$=*( z^+0SzrgfqjM?KV7)kl@SzV)`-FlX*3c<z~}(S6AM81=(MBpunvYL(P5#5TZVZ3oaK z!5G(KZ_)%<!bh-+9xm!Jg;of@{9pw>e|0sn51lc2m{Y~5nC7}pvq;qH7>bwoeMUbQ zM%`@9LOayOeLWwCFFu+WiT)R)fJvcA`W>_4{*&=ZPQ3QoYv|v<KRPk3xJ+8dYZ3qC zr)SJ&%|SII!|gA6=u9I`xkIy6@1zdt$?x24iozA<LdDDdx%pVe{3h$(e-|O%TqM(x z_SehKL4KV?6s}K4^MW!M^}(B*TMBhPbzrL40fX1;H5v3|OIE2{<wq}RXD<aLxYQ0F zJZOr|C?A4qI4B*g>Nwb%gA-B6{_Unsn~aZw92k?6S!t0BxnaYGW;N2QS1%LGeY`*_ zDlkuU?!WuCqT{#eC<wm~IT-NzAUNal;XGUsdGjN2PD*v+0j@A94OJw`6Iy^CkF~`m z*VZ>o%^|=*iCjp>KX-N}zUp=l@_t*%63%{HJai=L_vlHMM^AYQT5@}n@>k4o@7}#f zf#H8mZ%rTlsZ6)|K(0$cXX-r2x4@twzEe2M-@>1rj%0@Lu3+TDAy(RqqnSdvr4;s< z>5M>)>u<ruefrb%P?-XrJLI9qF$*l2^BRFikBodb-kdZatG?QZ2qtLq5Ii{P1ZZ8) zOCOH{RBsT6N1wlk<^}eNV8KKj@J#Fsyc7gaJn}eRoW=r9b!uS)b6KP_gXGAC<FVuL zAJkG1FvJirv>RCLfI;LW#msoE`yv|9LQW9m@P#9JUltzk`a0aXkvxubf)OzC*~kx1 zLDz|`F=_2IxZ(@o+>(m8Pd8&k|Is+-j?Sb>xLiX;0due9?5QjLnRv6GeI;;e+qSJq z&#vd&_Fp*unYQ|R=DliOYNQ4cSj08s*GDodYvB^y@8feMUmph-K(v#=Uyy^XUw@5t z?|p#e^}i9=a_;aq^CDSR{@%;sji*0JY7A;6m%;NRM{v6Gw|^(VkeVucU1hTx{NaZm zaM@*-iBu)+ETn+60($5ru*3x3dFLII1~xl8+h_(9?s)gzcN-g~z=Oc1hedm&NzgIU zNJtx@x)f?Umz*abfBbQD?b_9R*LIun=yOT4C~!PrPzarm%;q3%qJ3Yx502P;gk)4g z)qRbS`fV0UaTO_f9Pk#>fh~Y)7sTVivA42j0EMamgM_h@g{cTER*rcdNpHWx?X=-n zuZtV!aK*{YheqI1BhmPRCfG;;siH#R;Z_8|Ut|7ay@vhronRsOQI28GpzlP0{saXF z_hH4vaajA=TqYdyBbt5&8gm|hlUFJlokx#FLhIIa_>7>ogo2EKLscUMh74HJikrZr zfX;s}Jn|lPugfD?pfex+H=HgqZfXSzysRMM_M=jRC_FK?J6z0pWxy0cf{Vswb4r?P z-g@H|^dE3P_l02mqzSmU-@SxtK8*No40ck(;0$%5jxk9LB&aD~9|n<6D_$eu_}MIX zNiPfXNVDR=)S;hX+p<*T^LccHa$Iy$D4>eG{vBnoIN}=u&K!hnC$E3!XPlQGiJLzB z0C7#3DU_xdX?q011W*MRNY!JS4Pfm#q3~x_>C|>*2UezFHGBUtKRyG$*ig}Uc(Q+- zawc(?V1%?)s#waEyB;CVBfb~1>S;zM0qxKD`k9dk9NLRGQa^<J&CBO!Cqq~!h2)~? zV;$g#;e4m*XHeS*arrrQ3CIL)MNtD$PC7M;UBh5Iv54ufWO~?(F1qNfRSTc=yZJwM zLR)A_pzGn+pXxcZZQIr`2W?l>gtSoFr{ndf!Zh+z5O}c9Av@=oF=I@&Mu7|aeA=(3 z?<MUY6tL;0E!JnMLn$Pa>5I_&m4R@UrhrH(h5Igf7&8ZcfLLD{=37wwJ=OVCKj%3z zaYOHxxTf1BT!r%_K7t0rq#W4CY?<>PxsSGYKT>$kYhHaD6<f97ik%6J$Spfu*$zv- zU1-cksweVS0G(EE9D&6ic`d_)gAzy~jVi+}PMp7HJ?0J@27l6K<_sWb=5+9oQSZ(3 zqSZZpa9+Q@2rHYwv5{$0Qy{i0WkLuwBF3^zpdjz_++;tVyl)zE_JqTg$AcL;B2nsQ zk}5BOlQ$#_RnLpZBQM;A&=_hQSk=?SWl&YDQ*u3yk3M)G-MjW+DsB&+eSR#4JoJD` z8J!u($CJ$TxGQBN{XU$i6>~lwZ#&S0RdSHU){Hzq=4uv=HBZbw0;e6T58(OxK4Ivn z9PJ1iXg0}r<-=Vw4+mRqgEKx0E@rB%@zzRo@J3;Od|BM}!ECszR@3bwDZCV%6qNdR z+@o1^ZmJvk`T1r6p?UKD`|sn9JMK98+#l1;GxiJTo4{s}umTJ+P3bGMnb0)F86<O^ z<{GP>9$4}NK7IBngc9JE;jtn7Q<l&yIzjFYl*ZDWbSx{Ajtd91LuhIG2c?H#Qnv|6 zWaZOP`H66riLR%j6+2*%%2`Z8OkWy?%P+tDRE(?Soc{w9ur&;}Ft-_n3R6i9`OP=q z7(2J-jO>;=PQQ^hLe(Q%w{C6B7fqWsJz6ST=dhbCh>HHs-gmaY+q4!Ptj}EaP~aYR zWTVfkgMfH4bTXosdrrgK4}OSUE7Qq_!l_vgp`hieo3b)ACLiP8p*Et7>LW-jT5BoK zmaUj}O*>R2^I}d&#JB5&D_<N>&PQzmSM@jFb_>3k^NGpcSGR86zXay&yDbc$#vu^+ zaMdQ3oR@=4W)uB^TByT|zDJDL!!SuO(;^)j`B$w~2VBGqpK&x_`9cW*xcqm>SHtjj zWo)E)r<Oul7==A{{c#wtKL07wlj!KjFwy`uUJe)i76cinq46?w^1Mqcqwnx*5E@OI z&|gDhA)uwB0lW_Uu=sl>Bf16YY1!!2w+|+<s8k363dw{_X3!k5XgrdVHyI5>?U;rb zP9KJtV%9K-juu^mM5TnY1(3$7o%tDb*6i{UaM(@%78eR#1V<rWq{kgWZpVFamCJ&A zZ#F8wwG5pYQE{-)hnP#+pyNv~F~<k3@|*_(TADd0l5O_<w4dioFTE5${qz$?j2K~Z zGuS*seLd5gXlcZ^Atx!wxuCJ@d65r@zktsZpOn;%oAAwuk;vJ+7NvNE$(qUsEuY%G zG=C}NN7TU1&{%x5aUPrvU1&DwN@~MM$Fwj^>i!(6Ibx~3;hhqIKSk}d0S0Lp<ijBE z^|RIS>=fP8|Ebg306?9#nS(xyA?Um2$$|w7j7Gs$MQXb~%c)VIz-AuWej<mcqSw&5 zOPUQ5tW}7iyWwgqHI8fym@$NL^i+$cc`>#3B$VABh2h;^qmZyv&ptAHnH$^`kY($H z<KdU?K`1j5s*JVRAaiZw-P><O<hDO}90hc#vbg>GMf9AHrXY8rU++G6b;cVEtz3@g z&71%A+o8UT8S~P93TFpb?ge}HVExA*W5t`(QJO1YCxtOx^pLC98uieMSrijnwjy)o z3R$e1c>;6-iy}N3QG;J$k<y=&2^Xd_i4da$GImpw;vskqW2h)sd@gzX^O`<)78<pw zf_}qqWW{PRZQ7r?-%0N6m+6hF=Iz_Jqxq$+kjgO1E3Ryd&p%^ENB(oTmFdCH3=9Me zizguI5KR*7Po3EFF|6GHY8Yq^D&{7V3LHqNNyV+45{5Q<;hzB1C)1W;!F#_FWHH3n zfO!wH%BCZy^8vWZWFRUXs4-_PTI@_gI!##x%o1>3kG{BoA<hmKAd`7VZlF%ygQCrv zMZ7Zi3ux(j&pz`EhO?-boR?*~)SR`S`=Y-+(>_~tG<eX=QS+VSk)yDSV+ar|WFJh% z=DD-+^IOxAK;M=K&I64(i!{!m)*#zi16h$Zkrok+#XEk)rqs1axG)w?`?i8RhCU7H zPK@s{4mBNg(4{|#RS)IVP@>oYgM1h&RjOn(3`>_Tg^*)OE1^IM1x_CY#Kb7;$!r2N zN#x-^W_rwVrNBXz`<U*}qmHLMX0qbqsxNj^!xJeMPu4GwcLF-9+;1Fs6*}BrizWvN z8FD!f!!tjbgP%t{V(JcL@x0B4KZ|qk>SB@|4QJ)WG2_PL>#x3|;Ji{lGOPOIDG;Eo zU&2(z4nh>m_AN<8b%L(0)fE4$+vKlgz7)*<tTY_@=4;G-as;BO=8cxq0Ktui=7hau zradN1LtMM|6j-#ybI>j$ln4%JTleYQEVN`a4ZNOYl{V$4_%OWx%gEVJb+0eNh*5tC z&&hpCq7zClh;ntq@z^W9ShS1cHAv8+0`0(o1E^ZHD!d%i#TPf@V(CXSAldLu<OI)} zPGIxYqH)-Dn1F#=w7T)<8>h$O_F*{wJ{<quXiP-$9AMzJQ{l~|@Mn~aobA%1a*=mC zH6*23X(J;7<C@-y`8V7}$4w7n7-o8q<G<#mS5dxYO9L8&^IX!v@ZR{P;o)}y6%&!c za_d?x^9?_(SdPnETxR6Ok3ars0K+L=XzCuGsA)SVqxz^>=g<VSTTsoVLwsDwn8gc^ z(O5K*tU1a7@c=*b&iM1wu=Vv<G5^gsQI7XJjCAnwcLg+GWK&y^?X1r7;pZVcv;y)u zKXcqi@ZnEWm}a~Hjc#j!#14tfm%`B8bQb}`Sk!PZZwjw%`7qd>I=Sz~4j5#QQnoIw z9ChOb7>YhvCwF)yXDgvV2?hQY1;pUQ{<Km)!fcNZyg!`GDH+Ih;hC<_q5&!yJ^rkh zzQZ@O8S+Q<sFPU{L&(Gm89wQY%0bii)zN40bySh+G*r(gr{m?0?U0yt$S}y{@Oa$w z`B#Xjl87l&CgY)phhX~j>FCz2D=%Dx>8c;WCRuKzw%+tdWT1KsbRRSTN0|nduvyA& z&;G;s@x_VQz2tjlLOQ}wH2M`#OK^y0gShh>qj}E(DA({jgfUFg5kUt`Iw*>9i;0W> z$fTfL0}@<jHBEvPrZc2(>_^!AYYM!%;lwG_7SLoNyR(assemRIUsx9U47?r<TUSAN z86{~lP)3->2sQOztKmkC&c~)rn>qF=xU<WhrjCXYBpR6kEkG(G5k@T}U`XCbK}n~_ z_(mAou0Mrs@oN}Jj6ZD}kI_Cb74{1QXVdvJlR$_7!5L}*L+)*xSw|$7fFcT$?-+@= zU$)}2ArBz@&_R;Jk2E@nUeJx2hJgd%jR>QrikcYNlK9_BTqG=I;xw$=&s$SakZ%^6 za(vdJ(~gw*(@y@y9U7rE>&!Gc=4|q6F<bS}2rv-n=#BsN2w8pRF#=ZBydv;bw$4I7 za<^^4_Y=pXaLXp7AKJ$d$wHP$ClKX1vT5>b+TmWzTa`rZLL5zh^r>;g(_hGEioY%0 z@Hw_*uEem>Bhj{ZXH1ws2F@skGgI?7zQ+UthB(ej^-b{l)U;v;402XW;6p3mAi$u~ z!X<#=)ZE;XvzAcc-=Y9{jM$9U?P*jT5B~TmzVAUG*MaA{jzKLyQ$sUuK0mz>&p-4I z4sD`xnc;O}h{Oyi^s(G^cpk31;}Uf2#^+gS1GtjhK@GxBL;50$LNkZ#^rBHb7xQhr z{q8&H-n$n@KRw!{=axg4t}ljbH>*E}1ygvC;mT=@=i#E>l%WoxfOpUj%6lXkf6&Qt z#cMAiIy(d5+%7XfDrJ8}jXG$|q)T-=3CK`gtKaCv6nGA49(YB==y_gIz?cpQ1thiB zu1Lc4adS|ZOlaVvMOnTZW(8b8tprUKQm4duanF#pxUgMK`eqP3@H_$m5_amVr8als z_S<ha^-Bf}7+@--T4lX0$zs;j1~51X7(6DdGU>=B3oyhrqJ}|<n~qi4v$LnQX<WKl z%1iP7`0ufB&N_suUIg<{q(-MB_tqr1%BLZa8H!0=C!lIxD3X6)gU{~mjkvrta}N#& zLeXXB$B1fvq48^xmO;9tfN>zvI+^oP*WjE~UV;J^18dUs0+S6^m2Fjn=2SKdFdTaY z;RCxFkxVk^IGJNKt<+nAT7g9~&)9zhtP~!ZQ-Ey?=3~W+W8g~OhZr6!4~|^^rO>yg zVuPlr(f)4CoxK6s`Q-`3Df;zr$>bWsYN@`R_~MuM(70J`%wN0+tFyLa{Fg5TO%l>D z{EY!anKEUJO<ErDC4j-6f+g=I6gW*3AcG^nCWEG0oF;~$pT2+t`CEttTo``qa5M|A z&Bc+2LQ(~YGBBdgYcyBHh#S&G!8#JIND5RYmS$L8w;@-f*>!bHGCy~IE<R{+5!{(+ z2%`gFa+MnBG3!%&wRkBy-FyT3^y!0_=mclv^$CV9rYnttR^amdwuNwj3^tHSyZGjf zm^=7kge4z9EFBX)RQs}*$O<oord@iVNuOSD#l=t?OwP^gD@TIDEPedFR<&jTx~>3= z00}`xL6!&eXRpMk@BIR2PAQsHsBLFQ+)VLYNT48TzyM8z#0Bsu%TrgX#R#5I`b-cY zg}CWBDdEpQ6`b-gJZ{L4A!dx7IxFeWY+cOk7hn;+1sE&=9H1knmnMmz(<A#=n;M44 zOs2;(Ps6}bumx~%Qx1mrnSzk~1Pb<W9Enar&aHdlE>F!80mH<*C!tz^wKaHWHqxhL z`ICcDiT5Ipq%3u5TU_<(>&ybFs3w9i+3soL2?UcmSz=f;q7I2Pm4m$eUdE0ci@}2j z^EXy6Ojl0Di-3{-)HE4&>vX^Lfq!ybw2Wis0JG2R;apJmOR8PqW5T86)xY7xNAG7T z@MQX<=vSO){L7)nDm3w2bRNPv+^7vce*H(R`gRLkz9^b!m@13&L1sB;WG+_jT!23g zEywbeKj6Fzn_$I}&3N$}R@e<IpbtY(!@%H6MO2uM>g^P?)2?AC$-{68?rO;?ODOOk zQb59#>mcKJH~iCaI8eA9KH8|Cy5mVScAkSksLSw9E~K&Yi|u%0>=&$97-Km)QcbUP z#|{cipX&(jdawgpc4|xkQh?6}^h5sQ1!m>HkE^8{rcOsvcr049YlZ8tyB>3yy4&!5 zaZ$tU?2hY%<kvDgXdmS{6ExE9n~T&nYw<M;T?KY*Fo|p=I5HT`kj;Z?UC|MjJn}Fi zD_7<32{O3aS4{|-h|P+X%3ZS}RP;Y(lyym-TPwxv-T4^v_)Hww!K77W+KP|Y3NJt) z;$*=H0ToB67Zqy9W6(2qGK(VxIn4+G+1eTD;3W;+(p)h7RDfXg=x2-;#YZ*zs#QO8 zRZN-?2nd`R?Tj#s2G8FGxQtFY>cc=E0Qzp!iEqeS5(BAWpq=LoYDRNHdU;42H|tBh zJaRVHE<DH(%P1t5%0l+7I}uX;Fw<@`$3(Zus8JA&Ksdo#em4G?G#0<lm<f5pq;l*x zyf6jv*HHr`07ZH@^}_8z3xyHO(mjYqJ$v+EY4o>DWRyx?pHje}Ij29~9-}f4{q1e) zkG7i)oJ7(nX&X2CXkrlf0Zl0T7A?kC6Q>|-&lZ}MxR=M}a~zq{rc|heD~FCkxr^HH zUWa4sqwiz)`V8ip31!wy8odZkLo_cK!n`kc8y0Ptjq0_cvF4A}G*vjUB6Slr49~+I zP4ge4nT&?v?+h3eR{8nopQ9twub$EyulrikN+?i5fj^~ygr)uoFywGmBfzjHe;d91 zoEUlMlW63wN+w2uEiHtP_ExV8Pxb#02i6yG8#hw3K=(lk=KpK&IsmLHuJ*V4wz2fy zS&Guc05(v9D54TY1wm0`Ls4UiEq1J^iHg`o?Cp;V7!egkk$^!&5CjA%0wTREZ3}FD z`~L4ccV~GJj1abx8Q6F4yLaxCbLY+Z=FBPF+b46a(IgJHKQRbZ8^t1Z)--&0$+=ur zh8P+;jJo~KN3F9jK-c5DF_6&Vm^Et_+r^pK80YRyl=+$2t5bO~fs<qbtuN-i^fKnW z_980LSyG~&;olBUtl7!c(BaZ6(PhxZjDx|L4RMqxuuYodm9!R&C2-KRZu34Lm13He zOFPRoi??9p(D6uJy^}f$vRz<4Ar*RmBo^VsO@~ae>F9Pw2b_ED$%vPLg<A-56djxS zCG!^$JjAe_Vj#mFc?3hK)i2-vPe1*%#YkZmOJXl-g!-p*EnY?cEit)xfJ%=m>FH4n zv@IPs4LRj{imyx8ag#OjH$SMLr}s_H{`0(b`0I6VAt}Ehwp7}VwEjOc=-5`eGfu+w zr`&{I_1m+rGO*<s+nSDXgRa2NA7`QxEl0M|EcL9{{*R2a3&9kbB?+Q^fBn<j(sqQ1 zr0;UlCKu6i;-tv7vXUyXq<6x4$@*Dy00(5%paz;3QJLE6JMR_<1oAvaCb-!<@bkop znE%?V*t&2IDp8`4VC|2gG9v?ZH9Hh-=zX>=`Ce>d6>R)D15e%e0k*E8{f>TQ%oD>g zrM^c<v&@7o_-f%NShsyXUKsHx248)pfeuL+p7`_;gsRF)A|8(qdIGHuR=`lZc5T~| z5K8RVuV0D1b6>EhfTzGdP(TwOS3MGur<1YXKjB&YoHm~lh6sk7I|Rp6IfP(9N`#yo z#T025K4t7&y!+G?MZI%)-O=(roSfLUZKr9RoY=Ol#<uOGv2C`oZCh=OCXMai>G!_( zzL~$1C(mcko|!$fX00Lf$wdJ?KFx4AJ#$?|C>@<8smjnZ5?%tN)3B@E;rGN=#~>b{ zj%GEug1<c^??(?z)pAADJ;4gWBIf>amrjZ;y+-F4tI3I?@qU+fhCEALrHjS<HM*bh z+^I3laPx-06i@qCh3;2k@A48|ae5BuhCuPk!~qB-3On-nIoZ5D0V^1h;mft0FzL(L z{!rz`AjT2Cf<1$b0@`@=FzyHSPE_N%2!!OHPW{cjk_kO`>wP}X1k)jGs9(B-H!m2K z6g&-zGTy_p?GM6m-@+zx7nU7$Zo90&fPPpmDdJG$_Ote-Pe(oV;ik>}0zU%ms$Bc@ z%k@P2lzLhymtf{K_ylYMxO2fP>%0M*=`@RP4m1n129r!tOs<2uk)l75hZ}C~#ejAI zdG<lncg@h&vc1|Mzodq=zThb?xyCo`Cd`VZ*bY)i8F*xB@s-4fYjJ{}YS!)hy<vpu z!_K!SM(rO%dOf<jGCLu^7Uq7Em3UAU(6MFtI!m3e_|l;&XS6_3$)JsRjG1!ZdCeva zp^(G^zaS$+k$zW;?U$_-$_YFu_AdA|j3BF1Cc?%J5eF?say-Tr2^z99*+~&-&_?M1 zJ`XY4EU8N89|v@Nx&OF*XzVq5|B|6pD+*zZ|EV7cL=SHZ!C~cQfFr{4l>is_y}`V~ zr2PhO)lyU@DE@$=h!<3vZLui9AN*~$3vE=x!7}fN)5)gTa3NGIOH<*+5&Jj(GhUE5 z)rciI1u2IFIuL?JMm$Y8)pg5#F>}oD3&D5dj%<^4)D?8xJAwyTg|-`;zgtORcSL&a zx7!zvWCdZk*63Jxh98qmTF>=#75z-{W=^OYKf|=~RfYoQ_g#ILn(*W=0iuev0CVO_ zIKy*H&%~y{8X?-0{IaaE@sEhiN!GXBbh&IHW|83${<>h(_S%7n{idcvjo{k5Hl+E( z11?-&2Ar>$Kc#dE7Y-B^u_|Fyf|tBK*!{wDyhi?{?JKV8hm1xD8LLDT2mmnvywPM) zX+g;)6I(M53I4a78g=@@sWD<rRa?Z5InEG|-4IlLJAZDjD_0BbFpH^^29L1#oJP%O zDPoRND+9C=N>b$Pr76h*=vgo7j!`$0-%A~$P&4bSI^*CkFZCo^FH;uGFuIrdfAD$t zUc*E2E@WW&P!Bf^9k-vWT*(F2(3eX7NKE8=0_pLb*+i8TSpL;tidn48q8=l~#hWQ! zie5p1TAJ6sIc3PWnLyw?Jj6Z3O;2u^qWJ2<s?K*ri-`Mx+0DLkxPnznB~?F8!aSlo z8&@o1$1d-}BeK4%XMm#W#hH0AKyg>HQK5>(&vQy#Vp%tO7y`ZjjAO{!mn^?`2|!F{ zeM13*&QzzrYk)zdV*l+|m<M>31DB7_LM&}am(U!2^!>opu$Vfwp#kv@k^~>{XOTJQ z{ajzj!TSSO`$BKL9_)rWtl~S-t;;leIIcXU+DHIzmQ9i$0lmy%JX$4QU{C7Y9$d3k zMVD5$=aNH-QvB`d2~vFR=a-z+GeP*16C)<^Sv2n#IdaiB$3v3j8}j2bndWarWFcJU zvUo}6BPyG+MJ5<$&JU^by(O@0IeMjm8l>X93O8(e=s0s-Os2BbEp>{bGYSvc#x*?O zIqCt7fA}_Mj}P=DKTwmaMv9ePbfO(e1Pv$hZ>FU3QB3ef;DRZyvniguCIG%~4=|Bx z^un8hk_D2zi>S#iY|5HliUGWlYwim8Nw5GUGH3Dgz?xZ|5#F|8(X5tAH%NQFYn=`l z<_KN%za0;&OlxVRcmj^SoOcj%xs9;8-VP!vF>(+lnfYOkCjIkmyLh}eHhqz~r(bie zhUaXIjs_D<<}+4L#@Pq#O0_rzYlS)%B_(}-L0eFfqs7lF=w<By6DANp`9`#!K;yh< z6PYXLMjCMLZah&2ehe$Nim68u+4|Jy>=x6-*2M<14WUN=BSbR?y$Fy_tu`SJ9~`_* zGY?{I$D{E6wufYHJkc{>B9=5P!%?}(fRCZ+e60MPP9589<0OzKD)}Xgq!VKqe{>h+ z*nK#CJ9ZdjRv?-pfd@dcxK{x}Q@`1<jipQDVoTad6AlFeI}kvSpFvO~g4KF~G6#e+ z8UFa;7nBD8`HTX1V*pz<s(5v#(|Vi7*5VV-H#nlRMC*m^;0HAbB%r+GjYuDuTFXRo zd|=Nv=R;Q+A}BV0wqIJAp-$lm8CsdK{FK7|KgJpcs~9y*+?|N>I5LSbX3cAj<irmf z3H8hI!AMG5sPG~}`_MOkkaA@#@&-jQk~FQ?!u16Du`<sbQwp|-c#4}}FS<hfm0SMd z4G#DM1OvhjJ`~md${D)nAKst9FOuRhM29_<s2~c`wGxmllL)}-^=$-;89^G;ZUY13 zz>*dNs?Cb)IRoNfRY}yWrNzZtW?u$O;Q5BXpQx=7KZvIho|?!Nl@OL#xx>coXBk_4 zZo=YLd{_RB9)(U_kX$D&HkD(<+J)41y)xQRGpIvZ#+sr*J(#Ol7cZL530!qS?tlK8 zD?=9&OxswTA`#YVu|u+oBr>ywcbDCNPS&%Dudgs*Js3ezXD@F8`9rDOlB$QHJCg6R z17eVvBpe0zsKcT6C(liA2@_(s5COh>RMWCD%Pdv*>VQk<ab0JzG-pNxgvbXuW20OT z)^{DO1C9eeh_Y#XHuRs8y%7gBt}WS{nqBn;O1kSK;gW<gsu5cup=oqY_67Ga0Wg0X zS<#Q=U!hn89?0MqJad1Gn8K-)LRL3y^Tfu4v=O>~_{r)yOFG073&E$WkVy6@V86AY zGU>FM_#@Mi<7jKiZT^5%l=n>W$Hnapjn6I_oC_8tz}-&w2;tIwjd?C!s---b@Bm4~ zV@vK;RoCsIBw@rT{_`Mn3GizN`GPD8my?C3>^PylN)!pw0n`q?r$~+rFC3l*XRH>N zRb_7kGIo{Pt3lTzQB{D#U5;5L9WhSP0_pG%GH4BWthxB07bMqGDa{FZv0(v&y1so# z%nZ$m!<(jxsHD6?PnmHD3bGsY5H@LepvM%CiHa?Za;Sz`&@wm`_zQD`kz785yFJr^ z1wx<Wk2LlyIs{CvT$og<GpJf!Bu**b0bcW5R0cXo&1CP9E;wxWWvxVR<X!}jFt$;o zOp<lX*Zngbyrl1%iX9y+CfPJUbHG@!mQT3V=b>^Nx=q>uU$c(IVdk@isZzcNy2M|E z^hDf?QAJl4t9mJ+w_<T;rhC@R(B;$Q?z7nsn8oU`V@Ju;8jl_EW$0l<Fj<Ezg<>@^ zK2z}CTTMU8_mN6WJ*qTtKse-h!6&cQupjoF>xGdx_nV*iAD`dl0&hhYB#acYWvl*( zzihU>oSt1BU<^9FBYh<hMz!9jbT`RsKq6L_mHGb0P|}IaMeSu4<sBB*N9x&52<1KW zyEgtboe~H|_)6B3!&<ywrd)MRhNV4Non9p9rbT{Wt_=x~H<hDaOAWo{hJvq@4{hs# zoJ~=X-RFGk0?&HXT>0dC=iytQnj{7nI-*GYN;2A*Gl{yAB%^KhyO22?u{YKaw%G6Z zLF?m|eaqt$0@wK%^+uXYN-F2@$k|qYvkP-@RA|hq(N>ptnjQv8(uLPshI6SBh<O)7 zGn^$u#0r^J3MApYg5cC-&t=e%c^=@0LRNv7TB=ef*Jfx0-v@Ub(CKi4zzH&G+cV4p z@@Td%=bey_Oa*lM4|dJMIqnW%d49$vSO+MK$ksn`38+r82Kk3#RQ}0rGNtMlN7iso zeseMv?D+h^%~@&u()0O-aG+WaROP7_;Q|*?_=(;2r|=c8ya+p&I;kILW^VzT)>ftO z={XehU~g@WUtz|@;v<qp=oP+QZ3FQbf757FoxT)RN8kq`9A@xvv_^uN(RI6(lh~KH z>tF;cqyEg_b1^y;5?GXt1>D%hUnqWYS~K9QmiY(yu#^N-;6#!rz7fW4wiqpq2#@v) zJbsg8ZW*>&rmv==O_z%lrp_#=mOl@#m@qB0`BjglO1+9iDW#x@A3CfgjW*__>W&QE z>rIeKy!hvd0c~B?ruhD?Wh_cjv^y=z^D4F9*YYND++*;AMk%=2?IXeSv&co6gJp4K zQNla;uQ-ii?aPCxU^8^-2t6uQ)X2fO;a-iP<xW<0-N@Bw{!zB03Y4;PU(DtAbqLuQ z{Sr3h;_E>(CDo>5O=9kcb);Y|yLv1Bn6JkcE^=%O)_~0pzXw;}w<puF!Xk5lBCvK+ z6uCq=Oq-PfYY(Bo5&Z;F!qn$m=@`_rd9K`?IJ@6%7!)Lgaq2<~IMNx(<m_*e{+fiQ zUicAj^22DpOFWd&Uj^n!nol(cnLM_GY4B=lwQn)sSRDlEhcN<w=yO%Uy8iSO%$@1Z zdreU&s7k&`Vda<ZOB7K|*zjCrsV`Bfgn*XDEh>ghgK5%J8M;68hF61xmpZ8%ryauE z!ez6Z;?J{US6>jTp<L-?fLaY+Z$W)xK+%lces>`=@ILSh4$m^HQwc7a0orn%{>_Nl zz~fK~gV*2WMqyN(6}c~=<TRo^KF!%jZ{wY!Y8$KDfVE?31L(8-jTquxj$>0@>4(d+ zGkezHK)~9c-O7uLWB6)1cpCTQHSRw3;m*e1I^oBmd3XT3U_8eam4PAj%=l?W4IB?~ zA45QQrse$|l;;;ekePlbX2L#csSBw~30%`}711S^>#Bpgfg$;TNZ03veZCXnG#l&2 zz3Ka9md*GbkxW6(6sOU%<+XJOJ1BxJ7>reFp-7NEFYuv>%3s6t{3ZjDH4-E=j?bXC zdz|!J+w2O({~bN8<`w4=m!8bh28mPGmG%#nQc}>qck3usz#q{*(xH)0e3v2o-dKMa zjELVsyi?^K-L(p$h(+sua?{XDJa8onY>*}~{(6CR`tkid5HtM@^*z?6eUva^ms3WJ zn`TCVO^E3Et8<6>!~ROyUNK)_R)cjRkpNRE8h<1c+lhqavtqxPju`#g`cpB`LhWKi z>G;>S1X<Liy2VPsh?F;{(8zSlziR3n$6ZVp@0v3c&Qb~dp;-IL^^VaSA@2C8oSms# zJseU_%P`~eOM=CBsj<Gs(N@vkYDKZq7ip<qEoiyC9(@nzx@>#vNo{|VC)Xw16nfc; zkXl06d8amH!hR)u$Y7W(FmU_^6Lnc?dhBQPA+qc8?W<e@7i|*jmnPu1;@){YLAb(v zs;48hDtKNB=5e|=BM;EbvbO>pDf5B*P}j~(G3)10JURGW3(e{#Sd#d|;1N_gy30{R z%!+nj(Q|HnK;cJdOx6lEk5Sx#NlTGIPX+J|z^QfE2D|byMqB&f;<xZEQGcXZOoQ4F zx5oC8wmPjr-~YJRnCk@}G6WRTlA{&sUBG=GA8VOkDc+h$ywkAbxKOm9Mu7ev4a=_- zoJ_J26?*E039;Ir`V~nyj(2<rH5l#`1sE>2X-3$;HRSTk2%RE1>fp(VWOv|pRus9L zhuBH)t1sKGi(2iFCq_w<w`uj>fMqbv<A=4jR$1~>%JTH(5p2wqc<b6v=X6M1cWFaN z+#zVwKPj}a$4A{UnX)uj_|F%!QL$vo`D9r?0gb#=JnzhcxiZy|VwkH#DoN__dE=1C zpP;1!+dX>0_!SsF3=F61K~Xwq#og#%55r>&a8k|-PRo5CR^Fa`{8w|1E3~Xetchx? zryE9r^OH%2bMmf;V>M|A8A&UQn();VG_wTjY<Sc}V^pmqvH>In<<k=Hxv}?&+0$3Y zjQX3BzDKdZ^xZ3eOJjynZRVizb^s3Q7h2)cAzOQ3*H_}0qdKya;&ry^M1-54wCyI4 zTAR=m8FA)K7=X#Va^kSX*}oHplGy#u%;5spsAc|laG)M<#IfW;zd9g5NXE8)Btnhl zr&kZFADu+N2m5<aXksf<s3r4Zni%+gNkbg;UP?3MzwmPp6#FjZMq^DI<o`@A0L2gW zkP7Iu(8%V$*J9<t!Y&whoBbBn`oNDHICn5Itfb)0{F_jan4`ypm1?B8LL}^XB$H!~ z^^riWl!Efwj7=hQxpaPyoTHIxA(_uaHxz@!4F`bai$Ut*d`PIfrT`!3m4Fz7sLnWG zf0Ng!NeuBo8cy2ymFRdbN73FpZrx>J2Dx-U17maljX?nz=e@<1WJweRF%6n!WfudI zLVnFZOpoTrj(WY%9%0MjS}NHJ+AR6p(U6vDWGpFQ-Cqv36L!Xj`O$Y2SOQA+J4%Vu zdMP=DJ7B3{N!K+{_;M5+QWgDQp?f~f;cI1{kl~I7w9O`^WBY*)g?fDisy`n`k14!( zd=runDoB9<bg?~BohsO5*vQc53lp<pa*HwB4Vh&0ni6dHusGCllajtF!k40OEb3)* zZ~7(42KJ|_k|uhwV$JGTGWG!Q34VH#p#^yAAue&Nah!RNG)r_WB(0*OHOSKw)?Pg= zn0v<tmp3f}TIs}@U^(V}3`op2P4j&kr5U8-`Gp8xL}TPPExKX$K<&sRMfpEz=cy)4 zBs&fvfzi<|ja8%YN9xOk{!y?_8|bE?*mlb$R6Ci#!8x&Bf)>TLo{|wc&;h&s28Sy2 z@R$*NIiTC2Q^LmFd8_i$Nmf+w<03g1++E`&TxOrv@=<h7sOiM^OAHftrg$>H_V(pG z;+x9nf^l<RRQ_UzR&`uglED>g$2qDuqpsIIB48cA5^n5w_PueGLYhHi8jEofw;MIK zIt>RaO6BqPONcZ1svh$ZdQrvKu@SctT);8zX_6{m{@%_+`-$JfrITyIgVkD5IQ(vC z^>NA0n6uVpolNjY`||`Pk{A<;;2UbVAotQ~&(jZ}=R@W(Z5;9x@vw$kYesoS=-7+y z_=Zk~a)FdU3;SIq!ix&=_m{B|?QAb%QM8mhBlb$p*8@!l<CUyGoS|etmkRc(_^IO& z^O%PyZXC@MqOa&h)G#op_KO8Wv<oZv=YtT{%euW;OhWsy(cHAh5{LOsX$u=3C65@r zv(+NSC!$AitD_TI)Zpls8XAM@JgSaMn-~sPSVybC5$w#RW`%1Li{Ni{*SqXZWp)N$ z`n_Qjmte4m`F)Qi5_eW9^kJ}PuBGWBPszrjs2ULY#j6TSqDE+Q!?X>s26*Etc<B*< z@ol}!v+i1Yn9J&GEJ-wM^}NL0JA$00$RQ7xd$2jd<+YI}@3d}xJ7B@_GG$?UHTpMU zUhtkE&2K2qAZP5<OTarlPiy<13HineCD&A%uyJ|Wi!m(p&nR;kZ$OUJ7rJl=)v+lg zzDCa(bjCb3oNpGh5+K5T-)>u8|B0<=h1!=Q>vPjT?j7`+7wubBO1j+O2)L|Jb7WRw zD@l!@^e+g9H9}e1fbFt}t!hjLDafbXY=N$VY#k}VbXuU@IbyZV2DN<Z?Cj1ji&2lI z&_|jCi-o8^>!v+Et+|P-@;t>cYjRa=&HdvRt?fR3bGk;6I`IWzVjcq=V|m?yMsjiI z*+^oE=CvGs*w?jbAfU79$Cz=+>RN*ZLQYsCbpV0j(}zom%j?c@DMMrYMS>~rwJNGi z7k65$!4yYSVQnYjc9H=nkIl&`U(hAH;!d!+tu{MJrAsdb>JoRPWNr&cLDS78X0OeB z--7YY9XsBFKY8eY@;jImy^&0euTFFVGZw6?qh3Xn%I`Qb3`J6m8J)&7K|$=Bca??I zF*L=f5Lc8Rf9N<{EwGvj(TfRL!r-U@VUvueFC*QRTjP=1M&BF#hw){otjLP|la#ZO zLn#g4W|(h8je;n+njn@5C<~dp`8yI<$#od1=-MIqbysQ!JFq5|TctTTt$z;$))kc> z9UV2ur8(%MCqb#K;Vp>Uw>O(R*=94JxJY@ZmCeM6G)yj(|6kSUHuT`MX3P<`P!$My zKd#!RS`bTXgn>HzSd-T))6NNtew=F*y>~yr-`RS#O+#IaJv=&?)7FI1r*A2f(LP(f z+^G?)6IQ8YQ^=Ch4KGSU5*-jr5~t%7H+P(Io0Mai?<NgH1|q!afXkt4#zKSb^;jlO zmI}fOgF|*cR9BJ9wt!)~em+?%MN;^)NW_FvFVhP>WeFDaxJ07C3|(IfU&|WD_EU>3 zJ25TWNBWE>)8ljvF1yuMqL*WKC?kOO3hlMuQY&=1R-w}HC?fd&jnDi+g|%Jlip47I zI#h)B=i~$P!-JYvTiF8?9XAD)ErHA(YTG0Q`&e=2x6^3Ot$_EK$jy;Q8403%Db-1U z#Fs^zT$zA-UG)(nMPv(9std&VVv80qi0yAPZ|$C+dqJ_J3KrvR4WR|M53_>63TxA; zoK{qU&if%8LwOO&@Ggat;EEHgz9g@>c-x#^Xo3*5U`V_HM_u}FG#YZx0MpAZh}sHU z0)la4M%b1NU9ikMq{c=SBt-uU?WI#!PG>rvqMp*YI4#~R)WoFxL{tbdyEiJLgx><_ znP*nfven3rQ&kppE7ARvDx#b8KgwW7FZ-OjH+G}XUNLfDxu6yhQp;Nj%gD_yzbA}N zIh32~LceRCD7Qq+1^OkgLSa!~(%6WyYKUFRY_!aIAa_C1L8!)(VeEy#vz|y&v*>>o z?8ot)EHm)5`-+?FXJ3!2?gYdFa=Ok9S=UD#TQIg4_)DcVF&fHh^yT)15+%vi*j42- zaw4>mC%GWWudAuQX2JdF^PRa!5iz|#UA9`R3&|8USa_6iebskh%xlH3tkkVlfQnrJ zC^vsgO;v;orWUI`s8X*DmY}<z|KWzw#MdQAzp5ZIn9?CtB@!x(Gt<JZw*TC<etoMQ z<$lPvK<AE5-JmBw?PGc4(EZGH(c=TVQl}pQ(wYIS9J?c+k4u>>OA4CtqC)~@=!+`| zbKfjXs9R<;YHyNNPuN`WDUH;hx;m78CpW8-Ks$PpBE`L5>oAT6j>MHbv$eB59d_P( zUc@)LN|as?rSfE2N$Db*)x^fg&ne-oBArL@BDEc}46Dkdo3vUQ-R;CA3I$O6;i39E zZc(}k;=daZMWt3+bH6pjd!C<vov#lF;BZstKqO^#C=~ABpv1%(eUzV-8Z$~+WV_o& z?X=?h#dhp0D`y0DSKQaKQkk&t(2X%2e;&TJ;nucKdNt<WV2FN|O~-tDcri74i{c-6 z$gx7o6_JMGoH`^@!f(ya=9AyvH6s+fF2QtWG-p>{Bz?vUSs#o6$Yjh;Mo<adXASP{ z<$z8{=}1{Y%Vl-j_!{J)ltvf$jpF<LsU!u5yq~7fAyCYs{j@stUdN@{wjWV8EMiCY z+Apmm6d1T`)e-Uz!fIDCa>7GEBa$-7RCo+a(ikR}_W>2af#G1RVjgNPsS81GBJ!aV z<7~84Rg^POStr}RXH0r-hw4^a6>t`8h_3fG%hoWnW0}@V3N*LtIUU1oL3mqE*tM#? z*fvWQ(QS}22(%+D@A~p}Ig(2VvfvYQ!+{7en$PV%3Bi`Z*$Y95OR7Fo-&X2MD-ZNN zFS{S*$h`;PXpBIj!4-O8MfU^GHjl~C^xO>?Soq>a5DYc0`N${zvmyhq!ef~lzW$8V zaakdchVL}RJnVhxq+obn8P%3vE+w|$%h?jFR~r{6Tg^lek%?d%@MCMyt*?)whi(i} zpSaWCXPdgO*a^M=V4XM)T{_PCJ?_k|Zi^_;2>|G|ZrCy>WS%hh_>${HBjLY)EAtD3 z`h0}ekpILH;J}`n=B7fJ`aW`lp4BRr9dx`q7KFnd>cb9Bw<#K?t4d@hbXSEH=KLDY z==(mbC--hf+)`h@ZeN04ijnLCC6m-IOF_ExG*xb5S0RI}aK4S#4dW`R;sy)>tC5)n z(lyY7b1iI?%V)R5R{sbwy5r)1yBY+RPVJ9m3N(yH^tphU+*O+|zz}>p_BmjhsW%7U zZZuhkl**>>m8KgEU}@?p=e%E=|0@90K#Pgwe$hJC0)^s3Z_l@ER&%6XHxmqD2$}#e zX5>=VGB5rN%n(sW;=T|FeaC}&rh0_bn%mZG|IH(+=6ZPWf&9-mOGF~xrM{t{6?LG& zH27E5CXR8WgvMvzgstEglPTL+uX~1}Lk?=d@D*DMdQ|^7nPvvrf~f1olFts@iPuMx zR7n%9U{2V1?CRC;RLvsrV&D(qk_Gs}WBtdX<J#8UE(Df=Vnx9q#$Y(R&B;foTrJ$d zDa*MZ=P}quM~0u#(+J1PzAUJPb`;Uil}#DS#n=j6&lXL8C!rWjqsAgaU1=eW1_@o0 z{f96xZFTd5>V-bwND@A9usp4mO?6R{O~xi^UM1!VaM9RX59p>@@HkKBDD`|+p(?UP zzDvP(Mv@_tTK~lrR;Q9Hny+pB9Zi$(yHMmfQ)ZypbYF0Bnfbu=k>cR6`smxj-IESy z1X^f^5Ex(@B5>#m0&S{{`9}`V;~9p72HnELMS-R(`F;<03Vi3BoHk35#<4iX&gSAc zq*`;)a<|l<oB=jB%~5JO;VPj<@}(@mjn#1u-h4hqSy|C~gKoq&T5f}8o8^jwC!`IP zU4?VU?|#<uGj)nskGN8aLnrs)O?&xIAHK2v&$2`8DW0WL=+AWfSuzR2ol<5?yIS;J zT#=(#t;oWi6lYGav=}jXC0E%n7h+7CD$y_@{QJ#Fl~#Vfim}gDjQP7t1w}Q!jzg?Q z+S~$281|iL)wsA-)IbpcPdg>FGe>t=NW~vK2*-u<R*E|8K{?sapasNC8f>c?Cladg z9gE$X<|nHq9Ie+yi-U4yp`acyD@AK_D-=?N{h&ZH!+VtoGC87%w>j(_z6u)eTp!9k zdYDJ3tl;0Duext3;H5L%`-s?@fpn^61(FHG7FA~>8@)ox51ODBYQ<!&ZtKVo^GUe@ zR?n-QALYRgLI1vPrHZiJ2AhpKBQ?L{jxd6kknsRyj^hBF_&FS|E2(^grKjWyMmS!y z^Z94g&n1;-A$Iz*Q_UO#@G#JJ>bORL!l=wWy;nm6i7Ryo&T`3$NS%!DsE5?zINkoy z{x39)q(uE(GErKhg5@FPXDTCKv@n{4sJ~(r-niW}Jn%Gm{+RSMqee#<gAI;LF?W!e z39j^WJ#97+>?%6O%%v*PzF5kT(mIM$Bz*Wn?;!>fUu#6ngTW-MMiuHl7OlV+FG_xM zpAOtARdW<eQqPU2`4X=6z-@|upCGbE^L<?=d^@}KS`#*(&fup%yCHeRsBjp3gCuqi zAReMJ_PhI=A?Y$7yvAr>N*F8%ksum_9NUDa2p779$z8{3UzBS7D+7mA{b1Vb_GtHJ zl4bOER>+}1?a@xR=BkZki8-|f6epUf3O$clx~>3qC2ivxXr&AKhEe~%tXDzbZ_t|M z{h1xZP7F&=LGZ5MNCU<Jr6hxFwl9y1><}sxmisui`~8IcL}%S!-k6^Bq$Kbl3~62( zg`7xg`K+CA0{cD?7Ae8|zOCc1q!x3j`^;C<`hzhGFyDk!hd?)GAyVYuO~)?kWSB)< zW6*?DFUUiDmTqsEDB-NhOINf3?`M@69wJTTjE66f$6TVS^F_EEd%5vkcZ61(GpYKO z@Xb%49~?N6Q(sP=x^P<h{UgflXC-Mn2hlh>W<yzy%opYAU&<$*3*%O6`<_Ezts}cA zy(Q!(hqDgPl3D~|zOCB!cc^DKSgX^k{4wF@nqpm2GmAaAO{nKjoA_x=FEui*N!u?@ z_{GfyFPK*)N?{DSGGg1!I;L*aL%17LhV)>y*wGVP>BT&#x+HEaxF`rjg2FeSKarIm z@WBH@SDKQp&(8;ioxEKbcyXt}86`$42JX&Fk~B*f@}my4_W!HG|I+Tf5tWpc6%qZ~ zvoGBaxrH$hM!NarNTYZTUO)I=X{CbXQm^Cx{H1b}vRiVoI5U019ixFyA&-9@vrauB z`80>kR3d3P?R3uN_kj<}z{RR&4<Q7+?^t3k7$in3*g-Z0Lot|#{w)AEA@&7;I6!$B zzlDriGgfRK*FtAPOD<(5HutthBo%Ede%qv7p~_0K&3ZI|-19lJTvf!CUqLQQsF5z} z7o2PM1RB<gulf*+Rp_A0lX6_&Dl#;<KEqELHWBKsVnmwJ%&CxPmgSorE$A2QnUTXJ zW5Qu!M&lzf#_OV}#nTqJut6lG5FU_XoOibLl?DhRe92zei`e*{Of7|2cn*Wi=?B;G z&2j+2R?9fqV{R95+Ygldi|l`OXf@lYhv~3_0_|La3!GoLPv1^>l8`qjo3%yVUj}@3 zMp=LHGIWN++9W0jw^^>nV)M&v3?r18i?&ZVm~h(Z1Ba&5?0MRY@jP!{l~e2wgrT_t zv1)C&hqjQX+~xQVpY(kAzOc~kJe6pR!17D+D3SZok*L@VsrzJ<rKt+(2YVP2CbZo_ z@+!)d0LU|iay@Z5EMbFCGdqI5+LJ9!>V{=y8nPQLD^?6(`MI5vj&VtRz_C}fwUq|O z_tJZadDjj$)H=(Tn3oj81I6?N&rH^h?Jc#0*;n)n9_Ajt<~uR(Svz5reTYWtqCmM$ zQHDue<VS9*z5oRfMu;ny$?=X6PlFUjiGxw!eWdWx!y4TI$RFQf$>%iZ9%R7?5v8uG zl3!RYX9zc==bpTeb3JUg)G3X0$^v(jB#Ha&IH^F@eIKa4&j!Sg$H1Gc1(dqKc0X>J z>YUfoCHbBdMmUaWTV|>OUA&U2_1Izt)PLn+x(Wj&Go54!{1A&#Y<?(6O9Qui{H%F- zAl*)tp5w+dwAHkGH7@e*pDumM1GQ)?W!&k+!K04GxyJ)<t%(Y)a-4rtYJkZ2hF9)0 zapk+ipBFW+_>f2{$7!Qfu<s!;HOU0!!W9w1C{J0JCJiFP`Dluq|6;QrY3WE)I{q?@ zX_P`1*HMu*8)7XJL8SP4V<6~;cvB%qmrttVi@5oa7Rv(10V_OoY;IC%7l8{%WbLom z(}4Vn>lr;yn%!ERVBd{0I#1IC5yzP!nay}JFI-^csgjJ*?nbG!L*$c||Cdw|$`T-B z#jo#k-i*s;0tpIs5%a~8IMNOD6Iu*zeFY@uAh}(6&_?;LyG`}~b;EY(3fh4IDzMc< zCn*@zzR?KQysdVd?uD?f=4xZDe|{D!7l%v9C0Ys`uGao41p~llW@c(hqQp6)K5n_p zg4WuRrf^JmgyG`?o+k}Yw3X^Wc+qN9>R+orlj%=%#50F#uMe+6<_a3r#V<l*>r^;X zTIGuy3x#9|t-R?jI=$2d-3We<-n3_<=8wV_sj;Wjhil1D9ejsiOHITbm$-?qtjGfK z7{+2}>2(vdP_>v6#y~T2<muwN(oe|zpcQ~;15?wo&wo~+v)o}fL@sWlBL4*$jHWG4 zx$pu6Bi*jybYH+FkDZ7!b+YLtKJntkqWm+~Nb3}vVal|dFG5N>9u=sl%pMip1GT>p zN2Lu3DorLv%4#49IF)=DR=623`W&a&MsfF6=|$Wt4E}0zF1<yS3x^d8-<2HW)}4vn z3FvR$c1}Ki8wIgL@2*?sf1#3My8>-n6*=uoa6hb>%EJIBqB@u>`$0RLCLj7E2_y-r z44MnNW>uM$l?tV@%<Yh%6(DY#)w=WkzIwDSt@>|=wM~2lF1{KbL#~Hp%9hEZw9s%K zuniaKwVwCa2@Mv~^sO*$@_oO8Aidy9FCg9p7bc7mdUUU-7k;i3+sUwS)@{e>!mFdr zGDT<sf&uJyFEQ{V+4Sfb<s2xLY9mUGje(7#<S80~%5*MR-q{nWUTZ;h0=)Y*E*-_c z$-cl5LL%2F(*q+_rVo-}(ljB_0c;`WjXsdMK+-CGVKq}F(tD8X)Q@Z5=`X8lV{BTd zfj~8Z!xYu4!*s(vhk)1YbXLg0sQ}O@PYPZtYO;208QkL{Fesya<`EM8^@q2|?1|U; z`vgK>4IZU{lC$|{x`5zatcD9sj$?2T!g^b)?fQaqr5?}Nb!Co{uqUts>}@fxw*{R% z_Kei&Bbr2&?Xxq#;UFSTt7iu%i&w^`-wyV7UhfeBqs|v3Hw@Levq+buM9nxOU^EoC zFx-S`=0YYaAzNZ!BQ1xV435p$is&@EEb>x)CQiN*Hl1d>*id@kJoD^1dfM>A^8n}l zZKB@S3%<L*>x&~rHG%Xt^ca1lFig%%H*2N|yJ@=im5EZ-MLmw&_KHEtMS-}D5P*x5 zI&lsUkIU8#GS;Fl1wiGvW?7>1>f1O?enxn^>BmI5kR6BXp9QFZm&N=O=T`Y73c}^m zS9`!`ZO8k&N{R4pmHw9r_WqVESn?7SBVs`>A(2Ya3~bDp0IjG@j$@PI2_~)F4#Z+X z-z2bN_L(y`rc*V0sV<;$C<G#ZjAFqNzzsvBDKt^q3=u-F`A<$ThQftJU!NV*F2c(< zRw|fyLsctMB_oC3bK4(OaV(`LPSi1dgD65<Bl&mO2Q}kyf8H6o|GI!u5;utQii|}Q zfVh!-^?!Xe6BS`yaCU*ED#L18Hd{J0n_i6$*v(dlQ8Y=y{xy^@w#lx~!(9OkaI6)! zU!Ns}s(oYth*`esc{8awcYV@A{7S4pQWjCzw4{+ZiJMAjq;`6D_~aQXV+w@C`Qi$D zf}q}umP3D>dFKn#nBJrt?*D2P?E7Q+7L?Fw8A8r@$9+#_0te5DJXMIE*&)vOMQNZ2 zesYg>&r8XYkw^gQeAie=l~XFsl$ysX`4Y-bQtHoq-0VAJi=G(^==PpgmW!C+WvY8K zL^-n|`%>^jeK5ecVJ)XI>0b52#O}5Fw#&!T<hmxeduuR4GohNfT;TTdU3?3xix;@< zJR5=KKI^<>&WC`%=;S-?P&^C+1j7K=EMRa$ahjCA7Q=I?N&=&Vx5)z0qv6nGj|BIg zE%5?RE$&F>()$s&%bSc>JKf5;kZIc!?*@{u!Wjvz!mX1b!J|ZS(4@FCCP&8Vegwlj zzApwX*Xehvkh5d_>Tu)8qcJxqjpl`xB?7g!-jA{!HvCI$i+mpbwqH8*AK(20k+x#a zO~@c8&G6sKjeRp+2DPDTvD};)TSEoM@Tm=I&Hk?Y!7;CkcbXyUBZ34jI(9tlG^a8- z2qfKj@Zrpc7}9EmMQ`WuY~$7`=tt*-LDcFI_H8$=bsG?H5n!@&xcb|ll*BY}*)79E zXIWf!(NGB3n8T8lW4#e7Fo^MQ^Ckoy(<J}KW%R^QoWKrgrMllV@>yod;U{NU^_o4y zrQ+a?c8zC70xb6WV`I}VeQeI=iT=SClL3JGTTVV2f_sAHa(h|oaKR_mi>?setu7iN zqCK|x4gj^h65HEms+wj496A`ZwGyOd=gr^OOoCgGf|KOq#V`3&s$7EhU=7_ZuFalw ztsdtzJR?UlM@aYW_xXPn=$=yFyT9Ai%#1|2Lhf9Hv8bH!oj@;b1@|Qg(n61Yp3ySJ zc&{JD;J>Nq$e6c!j@`RRxsYdKL>ETUd$%Afx9-MU9Am>rhMP`L;mK76slWBjxw#5G z2;p(cfa7yQJnk994y@JoaChgr>74!wR_?NYXXk%-?Htg)1Ri2g@*&oCa_g)}w=Jv) zt{Bv<LYk3dI&~SeHzbAd2BHjW?NYdDScQ2PR|GE()OZfl3bfUU<(tzcUF2d`$TQ}J zGCK%MhUy3|sVdQ9Q{_p5Z(z#e8nrl`_Z4zz(H{LPcu}M!G|7QDVCuL`4|}>AHjv#Z z<k0%~M^qP$CeM=`gc1w~mF?NDfjZ4L>pvCtcH>{wjCdy1Kw<jb10$9%jU(&n$n)Rq zga(QeZYED)lXKv(K*B(;`1@zAr0QV)r2;tHxxl(d;-EBvnJpcRVt<FBW@%o<Ebg<z z5RYYkOrz=O?$V+{(fIjOk$5FT7+#EuQnujzF_)ODu3e&9@fD|4vi)Bdm5kG~x=!T# zv(?e9c9-*th+i6^{xI{Kl&^Y@JmXr_fk40dG1}^!F1~F<#UN)OxP0)7fT7?0vL{HN zgvTkNnH#CjsiVGxUq%p6lGGnSND4)WqO8Pb2jTj6ZGI$84o|nq$~gA9Hx=`*;vyk# z;>8STzgK=-8C!HZ`zy=B`Fj4%gv)P`zh?0hPDBf`%!=LE-GVO98XpuP?pl}EPx*z3 zX4~~2MX9Mi6Y^UhUoUC*5@2M4P8uo8nDPakDFluBz`8)~S@Gn*5Vgmxc{q-EUu-a$ zd!9@>m>g`4QMR~3H%>-A98y)$E<mBvF%+%v-DXgE5Ogu<siE%pKEfv~7U0uAp`Nvz zOf+F=U6<&UigcbWK!J5fm~JPdk-&6;U=DX_O}E3f5_~P$Vx>yg)NtP*897Wra|(U6 zCAscX*t)HE7WBta(ZXQwO$4mgwl$A#ec)3-+Q^U9+l}NR1_AH)?n^77)Kj3=SA7DA z8LTDj?mn>at*bYB3q6i4PKYS?aY)ebMYw<T;B%)ahME3)xtpKc<_w6=1tpfv>sGal zH@%NcJ*Nb65r{jGNZOBgh0JWJSQl2bCh|`(zfA$C4-BZSs&S%JO^g=*-sAiLLBY2x z(W$I22t>TD4bpm#Zi>&VHQJ^|K=>qNvy&bWvTzs(9>-Q1NAOi=D|`@{Z%WRmc=C6? z)A302h{K)Bys05s)nT*e`9?GM$J0KOpo)shLjUxvRG^Atx}iT$t(gfq?|%liY_xq* z93taJVv>*LX{wk6g~{5X7x@&fXm(z%xs4>Qk*qUfq2!xmMdC4kc{)#o_@QJ10r>e# z=Byv=&Ie;fjTL7y_^q#5{&rnw&*R@|B=I?|Pzy0Z`CM6295(W?`mdjzsMn+>H9B<r zR0`KUsKXeoY3TO_AM(ZJ-wk$_0aqw!neLOG(y3TZ|2tzYNS*%-&tCej7Zs7J`6BIX zaJv(NVghRC{sRstW@LCe*7r^P>3lV`P6MP^za?dgR{KeVWA*|~SL~9`8JIZ3zl_|M zAGFN(zML||d@r)&(l(vSV1sD>w#v+&yR~}5VA2C}T5qQxszjhN9vX$%wy%&JeWrCC z^x}yFAk&^yNUI40_tqkay~hB5?@pHyHk{{%YK+tXC?Fo8Mo<d$(YG&lQ^cs(bpJ3U z5GY+Wj8ptGY4!Jg7bSqTp~|V12JA_Z$=Os-(xdJzx@V)q?VIhdj%7@u?SN0en9Mz} zn*jP-qc%<Iz};wuI#xRs8e>P;3nS8s%aHQEeh^GOPlneyCP?s&0};|nWaW!|&b;(0 z6te$g=k_@?`kRAbmdr;NH!Z3Fm-&XzBvUJ{)yYCBLZ1JNwF^-#|10}L%Iu-K|DPRN z{(BIqO=3<?>?pC%R0$&fW}U&kvEc-Bd{3G>9;llWj!YE&df7{ouJ4X#;B}Zver?XV zO9U(ld-+qIzfrOTqR8hvEwwUPFgy4T>hk=5W_lH$P*Pf|&1oh*0P?GX+E9z>EWE;^ z+vxl@%c9DPZyV0ptj598qbjPZOnW6QD{2N#HzdoYf$DH@a7Td?+J4+%dnL|wxpmX= zI32z=0e4=m0nvv!NVNAuOmM0)g`xeYY0jA7f$u!xbiWeWu^z=K#GKHeo1$z%lvA_` z7tjBY2LCZsdGPWbS_6@A2mVkwP8ATj^%#gZUO#2|no!^IO>DN~3~}Dzjxp0NR3Vf6 zj@){pt1iB10QpMH&HZd;I)xTR;7+Mpa<zg+dFZz2Os$tzywPWV6{P{M_qi=my^<O& z$R`&XcShh*@2mlT#~@{<_w(Zw_OXCmOgAmTM<VIp1JGJu@>tzJpC6R1|6_zdJ>=9z zK>{n1@q#Z_=cRZ;#ue84R1;@6?Z;xkx;u)yT_X)4oto1GZ{8#jnG9Z#Z188r2Z#-K zYD027>{?J8TRw+-UO0i?{hpqslo*=%<Ds<|>%JdfbAY528Fz_fqi$o8@3QOG9Rj>* zmrGR^9I9K-MorR68Ev;EG^xMah{*5XF3f+-5!2C^EUWP}>tpCI)q2^N5H@pZgcAr_ zcC)d>v8&xd3fDWcf<QFtIJB5gSX$N_vrt`pafWBBz}-`(y5b4!Hat!%r4rB?uP8K! zL}#OoRMJ*SJh!DfoOeARWuJGPl@|k*k4yyVKyP5=dr(;)Nd^~^Y(Oo#hcD$Q92Cz= zPQYc`fOFWwxFtNtK_!p7y!&5o5*{uL+(+P*;PALc^_!iUiI2RDoIO#j_VT#sS;VkD zsQEb)Emu|#mAd~S7Iwm}uRjbV(oEZTY8r{u198qLfn-8)z+pOa;{UES4sP6z5IAUc zI&}Og`{h~4P|m&4)XFZS|0juMSWf@I!GN0O{pB7)IeGn?tab<s#y>4Lkm`!%Lz8V2 zol{B$c?AC9fB&yOpkh!>4Wr9$jVDI6MlArR=BU09B#wm*6RZNgRIOQWmJ0J2Gy%y| zFw_sQ5xAY=C_C9Mk;a(Y1&v9Tk^;dM`L9D$sSPUClDmG$fk6!Omo?JMD_IxPtJmr* zgAF;25@|xBim_T3MT1dELw*bV{O@6LSJ3WcSh<#OeW@FXk@NdCuyn{^=fA&kaJo9L zuc~V{AXf>XC1W$7wFEIa{v+l?QlfQm(y<e3rFiN3S0E+(PO}(vd444=IFp%YiT9B@ zIv7S{?%4g<0#$GSF{1!FQs}>)F*C(p@%vvc+Ir1#EI$M`k0w^!sG33juOLql8*EHh zbsDD?Ek@s5r-y^m>mqM0GCbp0ow|Jy=yBq(N~BC^T-2)z?Vl2ne!8)j@DJ<$&#)o@ zOE|0&)z~pGQ8=kz^NJoS^x><-e+kVs2QoD+8(jaJdZ2+i8=FXAsgzbA%n2#r?K&Y~ z2*d--xRCx}eDJKy{IyxUux)R_Ix$<D3Qc^LyKe{fut%5rbN7GuUI|EtI=#OH_2~EU z_Uw6(B*{4N)0G7?OqG}sZw_fy&qY27IRt{A>bD<PjT#0Yw%1M&jNIVjvvI*qRA$>) zN@ziUlZYbUc@wN@3{Iw6Rnk0u)kT*Y!6n1L3g$mX3l7hX0Efk-svz!?W=(@Lil%MP zsu08DtkMIDF~1o3&8P|~d+`05Sg5YZC{<6bCsOEE*3asDd&W>gco`Mro!1V8L*kta z$m%ub$3w!bY@YsQynhxHtpM(oox)T4h6zXM_^lr-gpix3T)8e`tEW}G^^G;sgSSs< zp{sGJm2!;@qg85Yq07r<sX}?MgqBil{$UWbLJFCg)CH=i%kC<C;iIOxk2??VH_@q> z18=bY6`%hsg%xV(6SSB9?K%|`Lev}9mC=0j)|rizO8%PfP&JFg68S`CBiP1T)=>KK zuDpvX6*M_%i*KK)4vD`;kc(8h=#-N-GnI*gY|{t#?)<SsGJ)}~Cyh3me)j(#13qQ} z=dT(VKDSe|{<?Vnn=x{OiWee7%uChe&qz>*>@$0yY|=6_`ngyROqA`hALsagzY7A3 z4Pagc7KXz8jd}dvN9V?+-2or$zryw-`ENJ{RU8=rV%8MaAiwMXx>+6o1_FxTh#U8J z5h!W?H#G^vsrEsHgHQl0zyIg#J4OY8Fo-aNx_5s6Jy_8D&KUkp=s;sq9zH<a3k>ul NEv_I|Ct?)*{{U;}IywLV literal 0 HcmV?d00001 diff --git a/docs/images/Pasted image 20231109004616.png b/docs/images/Pasted image 20231109004616.png new file mode 100644 index 0000000000000000000000000000000000000000..d130d706ba980cdded65dfc8b6485eb80837ade2 GIT binary patch literal 171604 zcmeFYWm_G~(f|qsf@{#=7Mz8<ySuvv3GVJra3{D1*Wm8%?(Xi+UD@xEeNXlexF7C% zo>|k=-PJuMUDZ`x6DlVo3J>!c1_T5IUR+E_0R-ejH3$e81Jp-g&7J67G6)D9znP$* zoVcJMft;Q7S2GJ^5D>A@1XV~i#X<B8&DiMZ2{0%z=vHVVW}kQ@4Uj|OO5|9O>>f-g zN+%=v&R<yupx8~6ISZgw#7^kFYZyXG@s3q`s%v>Z<<CR+d(V4g-tX+!nT-2mt@e;0 zw{cokY>=}c1gi0XP<Uv)@6s~*(HUScbRUg2K!0lKWF({E;)3d7S-k74t%8S?w(b#3 zKbgFH)1-Rv;~|2OeBNU6!UJGz`GagIb5)VxgXDZ?%}fO(>Z|$Ifq#U$6u=sj+n~gf zQQT;?`|+U0(nACCQ?5}<{3D3DD#1AUhA|)fFP@NeA&+b*5XX-_ZH<j_k4S|A79T8o zkcMwk%y<usUZfc<#o~rXF}uPV2f`(?=w#En)8D)cw!M>9a1OH&snm*6VkguV)AZM@ zOk@#~^eKB<b7}|3Lw*sw5$p_~5{giyOih3Xa+?nf8+NCGYKNphtaR9fz!M^%?+S^K zKh`?v(?J?E2uzrDdB||}xFG>hcOZHxELp_A^iz6f-yWi{NDgN1OYC?Vx8X_Dd{UEm zolgOaRKQoH8u>2kmkd@V>`O<FV!#}NdtJTVmB5k<%eWZh&w^rBO6>(3VhE8F4HC$s z5={#osl1f5w+BClu^dmaBSd-m_A>GyC+t;;j;D&pn+EG7Okh9?cLa6SCjvJX2!Mi9 z7{PV_f<)Rw;m8wm{lNgu&^C;XOv5bd2eh4lQ43a2xhsV2P?d`Tk5)8{Czo~_K5j+G zC&0*7kTBI&XOb^e$46fu(7eh5-$4RcsAV^7x6Sk%GE5s^a3c^<8#xAl;@BN-BA18{ zfg7?R-~`sDT0SkRATR{)jv>lgxO`15^?W=;*j&DB7y<q`E`Wq66nIxj@F+s!mtbew zQZ7tugwpCa?{UQHbu4rvqWJF)6U2g^6S0^=a3nz}{-JdZpl9Lk+sGG3h$W0;J=~D{ zm#Y~U0TVJVLJj-}1S=^d)Uhw9yO<N8xBdx@V$bv#4QMkC-5+f5e<CE<YOjE>ZIn+S z!ruF5tP%{X^wA8%Y?Ga~k8T7PX4evP#>ijMRr4<H?Z=oqnOg}`R%^W{;|rIX2|j*B zynQ*zd=<QVtb~7GM9~bv?HJQ9tb|>VF9oHm{G>)a7ls?RnLT@}*4Ff~wRdQHFo>he z`vKddx>{<FeU{^v%~Sqn7q(!qZPJHZolBc&WMIUkawC#J&qj!=9~sVs%mf3(=sA4r z`u2-Rn>9gG*?QxnH^_#)fu7#RfHUn0ILI^C#<BMUr%88!W-uklKH_y=EEq)aFfI5) zf?Tk5D$h#$h%bCv6r&B~S_eM3FC7xZ7C%EWRPK1du@+c?Uy2?cIjFH7mKwyIZ-gG~ z0;rS!YZfRDL}7=z4YU?0YX^6OTT>_O1mv3UIFw&B(q{qD8{|(tC{?0q$X~X?!3mMY zsAIq95n+Wu#Sk&ZJc?l{M3xG&5Hk<(?9kc4H2TyMJ4egpLApkG2++rendgf9MB_j) z&Y@<)i4Y~r!a6{$MWPW&%KA28?tq~Yl_3DgW}QH|fmn(Hl|q~Dm7<6I9$HmJP7NX1 zPqJW9idxc9T*Xle&9nba4RS8rvnP}d*JK011|oP1nhi12Z@dp<`}hLag?r6Ux0~~l z=LOqWgpOq4QwtPMmzuyweah?rIsOF^HX*hT>-kn)oJ27{C2PO9bvV<fBnzkUYe{Lz zt_X68TaY;+KZ}#Z@(gC|2!;{aia+L|OleHfPC-v8E3h8=hZTo~hSf+^N`!@p<%{JD z7#9xNCX`UhD)YoK4<s4^>`+r=Gh}om)+DTmbiX*q@hUP=%%S2-aFK>HL{$eVh_VYd z%DUzj7n>Ix6@AX7R7x*t5^=0Ja-Ef#jZ&g1#!ZmMl}%7clB-vgRXCShpD<;jO68>q zOqA6WD9KJQ;Lh`u%PnCqww-w}x1XV$J(?{qZdD>H(JZc+AuGlxR{e=D*Iv3-!ar9z zrT5K-`Rg|&bDX(`{K*ROd7ON#{FIVLHT%Lnh*1*_5*n&90-83JsyXzsX$@_M?^ZG< z)2=s<H)S`BH&&K8b-!3dIVGE=-0PiwIAumAMwZCrj4`E4q#JVJHYJxQ(2BB(Iv1UJ zt^R1r48nppg#QGm$y92!Fspxl8+81541FVUdv~xp@tik4fjBijr(3?B_1*!(TFDqf zpKM;)x$&L<+~#z1t=qL*GWZ<dYaWTYmhn4tntnrX<!t5pzyf)Xm__Z}L9Kj6Re4pr zZQ`ZG_I4ll7l%)}pRxxf;y!&D$KrrPCl0O(n(R7YWM+bAPDr(4v1EL;_-dJ`r(#ss zf8xvDn`V|_)i%|#*fQSLWAMFKDqJJHInhY6z_?)7eAqtmysWe=wiI2BS&h49u4YdS zLt|cJy*_*KVNt58sIJjUvetO%>vDO0t3mKm<D&7B@{)F)=;`Wd;N9`*vM7>>OC(an zPdwXU-=hvYa+{xy2M#li-)*SvENnd3rwojS26l<ZBVP7)_Tsl|XAjrN%jETQ!$g=P z+)gd_N9@ZT+Rg;*p`B8;rw*=$X4jNAnmTXmuvaa=FN4*8t*<!4J43nWxW_|;jZ%uD zjM9{{{K{lcf89dX$=G2Zxi3E+rE{k9sPo+VcI9+2cDHu;YEgS@+Idix+w3vo(ZKV= zlfwh6t*GsX2j`2_YlGLUSJcbs>*L$<OJ=o&x_YU0X%eUmXsnMQ==q|~iTX*LubQ5i zo|&Fzw2GX-L{nC9=hsfG&R?CLgjR%%0y04;0^Nd1!E0NXwk~O(WptB87fLG=ZOmP? z9-1yhk)4oZLkj2*k}K({`c|T9zoQDX2>FuB%!K`foSd6f%!%qjGR!fgG|cFU3`@sy zr;Ws8rLZztX@2l|$iKWtu|Ua#9t}MT-Tw3qWt|M-O9GkWcU*R-xdq9=kAq!1eW(f& z219l6Z?^o~DiOzc=PYeTFQd?Np9-WK=qB|H#(E6nX2@*GaK%XTzT}@ty>>-xsn|bH zvzaNId2+E>GoM4OXST<#6JH?5!)6pb=Oq>L4qpta#Z1N>CaK3PQW?R{L+cs`ezhEN z%fwA+<#s0^qcD*zm#{KF(~n6c*PLNkbh)Y>JT-8)4Q((Cn~zskd?MM5wR9C*3ux){ zuzVn1r~DQ3Ms!MjLGzRPfsWbs$k!}&T4-9Ma9LWH>D5f%X49JS0;>gUlu_Db?8hQ| zIP<q_3nQnclRfr5`>=h7arl&GLp)=hyO#Cvw6LM@wK3V$btMZWuKI@Kq-b4p$r%X} z(t30kz(NC(F1gl1-GK4rlJL63V?M@k+7RVX8}%Md+r#ls-T4=eN)k`;Wrh2E>_p_G z(8N`(vw9EF#;>mWuJd8^R7a`|Dv9MD&E`|ZuxRCI*s6*ulB&+7p=#3&a|Wl?zjWt} z%bVq~<QfZyD$V6*pKo7oRaqabe=eKWR#|KpN_R=uvj$s~SJV}kF9@tCRPGMW^_1;< z8NR91jOuAF)>SMEFLOHeoS7C~{w!KFYp^$?(V!|jU1au}PgwPB#y-Y5VmY5&Rjk7} zNjURt130dazHUDMK%_&Q!L8*|a}4qNS&LVcsk1&Gy*M$Myt3fMc4A{6=RBQF94T6d z&&;jiDz(2bwH?3R+Yc#&nsLBO!L#U2xvivnoww&+*q_n1hB7_n^yOvbv8K~RHq$Vj z({^qDWfE2g13}kF$D(1!tEg?Z>~`YZsvY0l-nyjy#J2G=Y(JskZt}Fh;z^s^k>+A) z@i^@`$x3L=v^~Y<`mXG<p2O<enzuR5et&k=uQ~I4v{kl2_la+tzgMt3c-DL2t*WrQ zbz99u&*V6_LG-@KMH_&(&;2%~{St7Ow^cMaooX^R9(f0TujR^f=6Vl%89v@h>TUj} zemk|d+u8o|ZhnfrJpU?jWxjE{#rkAj*Y4=Kyn?^_exZHVJbo_8d*Hor8S{9#QkW+z z%PadT@Kn85aynmNy}5pdxPt%}(uh+2q6*@VCM^rOaq9$PItVhc`S_hd#`Y}^L&)}P z0`Wy=<<@s{z!}I)=lgxK&V#c(tWT@v<|XV=NfabO>PNm7GCpmsprZ|SX|M8lG$JlY zi?FBE#2+8uq~+7ty+fY&(Fc^YJI7DkK|*{yJgMpWT7W)9n6aApS7~VwN?;iZ1RV4; z2n4VM3cPqgvHw#R0VN0d@K-$;2uQFQ2>8GH$N=xZf6>6}H_ZRtKg0%sKmwmofR{@a z*uQ&!sLuNE?=lzzunmM?QBYhQcvm#EGd8xeH??+vs(U^JRzTZ`soR5qpp*W-K*beE zE`a0DnJK9`s7Xt47+PD>>Kj=b7}L5~+WZ~|gv*5kShO^D&?j)Qw6L=0aN#EUs|N?L z{JR=JMDSM^hi}|OYSMB9g4TA%1T3_4v~)x~Fa!hyTy{oZITVCM{sj(v;wCb6aIoP3 z0GyqjX`LBqt?f(z^z7{H06GQ$0|O1P2aUa}m4m(ujg>v|{|)l*afFQR4eiWq9L%h( z2!4;NZ(!}{z)eK-d!qmR{_j1FUCjPFla>9y&;lX|_}v1ar=<h@XKWxS*Y8>mIWrey z3w0qgOCZgFbMP>;FmV0V|Bsgc&iFS-wf{o0GqL;~@^3Bw3#n{xY$s@K37pb_=fCXw z7x3R3{{_ee_>KABDDi(}{;L*9XC4?Xz<+qg19K13%mrj4j+v0G67UWbvfn>YEZ`sc z|J{LQ(6H5MSL9F-5IzubA$}zn(34i^ES2fEcc8zz!Zkjbr;r*ClOO-(GYP{qE0OJJ zEPIL>ozPa01PO`Y=g^Q4)7U-Nvytg*uH$zv@4Fh=!o20y`PcWfX_H-cca3SUQ_Hg3 zwQptPVKz1fV^El&#CqW0eURzEL^}TUz=uqTq%Tkx!bLG$@b~(Ebs`7-RDDPEPjE3r zdIEJ~+_b}`{{WU8{mc2^GyHwJFjU}p!bi61UnBlr{jXOFC~f`lpBMXYyIdYrax{%X z)G))h|9Sb}eZCl-;{FYve}nlF33mio#JFiCs{esAun*z4^MCjJJ55k2fa8VFY*&wb z{(JSm@P}4+hx~t2@2@ek#DL>z=HVq7&;0|1r3RKb|Ci{$!Gyznpcjd58>nmk0cAab zxwU_I0c3IoaH#?GqJHBP=Kr$r--!4ckQoVPM+=FFgxSjw5fM2I_n+Wjr?LM7{^U*I zVd>Gg_z)0f03%pf&G#nDe_%+KDGIrh01GCZdDO{B3ZwDKLKTDa*-CfD_uB!ypl*ae zX(1fRSA|mjcA<aQS7$yekw~NY<p-;EVzF`w`psBsG>zT)PveC@h-8E5Yd~t`YJys| z?s=bHYq_jqeG?;!7vp}`C>mHAy3n1`iu<PshLQY6c#+C|TAFq6;c`2$`@3W!HAS=Y zdE(EX<gaLhg+?hX|3D=$uwI#gvxO=_8ID7e!Qo-5N;QxBRp;S>7-GjWi_Y}r$bS%M zRPo<Xb!O8dZSQaHXjN}%iwzBIDctULX^wO1!dHaq1^+<64J2O!LL<*k4$mhCEIK{D z&eSTdaeVD&r_-I1iZ;pyd+*jozfYUEPy5UW!UfmcciWdqH_+~YhKz&+($LUQ4vhJz zWkgLjJYJmF2{fJ01NZ0FuWYY$Z?5kPb$^JB@242P81(A4%I(CiO85IS29q%y&qyxO zeQcK;I%8SOxG&N$V`y#V8JGPS*^r2M@nxFz65D+dw>aB|I4xtIFmg?v&v%0#5V^8G z=9}WC%)c--X2!+kZsz3X&hiFx_4oH<<i%xXR_GfT7~E(PAVn`Ms6`ld1weOg^ZS2< zu9$wbJ@$R2|AXdfKHy<3(fO5m9eMnPN3$icf!XKeB!@3L<3K8C=y=}Fg3+s~IXvlO z;`eR|V`!5kP%2OTGIc$vkR7IL3mF|9O<){j6I^rM$1PGUj1<}IA9Qg#TcMcOaW5-X zuMwG=o@Pb}Tg{hDDpt$Sgr#lZLkH-T3M7El2?irvJsnqk`z&>xpsFLE&FOG3(JfS+ zsk{8=`j%k=6V@2G(tk8?9Ec`_$T=U-k;I$UZM54pdcHfQL~%V6^A6n3&B}|;-~5R} zDgh;I69|I_BSilylfodpVDH`y&uXeA<<G0j#^`nTQ^9DyR9$gfv)(E_Oy&Lat4fiA zaE9ld`r%}5aKY~Wa8!l$dfU}m^Er&W<Lfu6^|U{vZbOJfZYPi$f2kkeoBH+Xma0-o zs!9}jpsan|@NUKFa7y^=XsWW!sP{pO46ECXsq5ozlB4%@f%H_hvE->dF1<kj95zcS zADhY7ujUn}koX>1ttDO$#DN9gZ`H%Jiu6Mb6k)Cz+|`~>H}ZrlzrM|b#T*4+Zl`iM z7Qb8#1FjBoqtG8F;g<0K&>$VqVp(cXi_<ck(ki8D*{zvv58E|)1UpsUkzFzN(q=bB z!r|x;+=Vy&8Izmc!NYN~JQTHdQpm%P6(uTVu?)sTV#jl3w=MYdJA-k?XDf{ya1Uzd z@Y{RmxlueQccpXX+M2+t#MSMjs(&VyA((6$ZL9>J?7GGIT&GC0zC6gVqViA0))6X| zB?hYw(}VBzz%Tp-0zVzV^csAGKMlA)jOvQHR`Be%XX=WNkI&1wZaOZH!_aZz@1?1D zv^T(l#I4718`0VLVcoVEwf9q#S37J{QHEW3|3ZPl`(ZP<+V%P?{J4iL4|TnlMj){v z-e+cW5-r60A*u>$kHNb?7e5(}FA>1V`{hy;*GW?iM1hOvc1E$<ZdU^L%Ltyz`sL>+ zK-+@>_b%*gZ7mapa&df^QrPz1=#OI_?ni_8XVf2>br$mSO?sVRX0yd;vhPKPY8*j7 zSS(ZFaM<L=IM2BbXG@ac@VL~*ubVPIzT%E*+mAA*mRl!0ntGl5lQ0p;<prL^ApWd0 zJy~h28Tr8~+kpN}KtRA(jvA*ABMP-<ad9y=Ev+=k`~B6K`Krgit7|GM)85X^(xp2H zULjW`qDvmnG4qlUFU(j&r69UM*l=u-8?WCX)9c9$i}CCCQr&i){T)16wrj&b>@;~K zcvwO-&5KVYYIR@*u4Sg6`w!-C1@@L^MGe3u(zHg^dr_F_MQJ>os7ybUp{s$p_o6c9 zXbd>3N&_S|=Ij3iE_P|2$DL2wA49qWVDCxZ)wxi+7{880gMRpU(6Z{Cu$S3uxc?^~ zdVM>f0Y<O4`i*bY@D#UatD0WVr>yKY8$NeiQv=gL!=XI$)LL`D?%m#U*@t~~T+xnx zv-P$(%!e!iGz;s4pJchRZI#Ql)RPwVKYOKlqpx9fWqRJF(2jR!tX%C5zo$5JTK|dg z9k`4O;V{|AW`B~7TagAs+x?pRZMGtx!p_tXef=AqUWWHUcJPb_Jq_t|cg*{VboRUD za$QjfE~iuJ&d!clZy1^*`87~m?(W3NzSU$w>|^!sXL^^n_GrZ=9&e^H{;6hv{+?1Y zhRxwXE``Y~Hm|Vo8-P0axtc6NQ-`;DJ{~=yv7CB;%5LDYYGs`FotkycC6`*OL2lbn zt5$8~*02$0-2J@OxpV_!e$DNeM%&xz{p~e2HdeuA&FN2DPxjgOlg>ajYn{<xtT`VA zBcozwJ3z;iez*+qwUO8T&H{H&(opu7`7Fmty1p7OS1`gf2mSuyR7V^><n-pn#=(K9 zxU@74+j%f2b=O7b!DOyu#Bu~SYid<tE@-v=|C+Zny5HFSh>0OI9*UR09DJ-gA+=m@ zYt_IgFwMV)Ait+z!3q-eE0jth+Rt#OmBnCt=SaG6y&5Fj1#(dtc{qEpr4N6VIEsr1 zk@uw%LB3$JkdGj%I|;UMS9FN(q%;3^7ie9c3N8QKWwH@Mr(Fmn62*KQTXUS(rX+Ed zniPlaWL<TL(_q-6hxp>%GDZVo(I1Ix{BW@u+{#w_Rcc!fr$CBur9c|{m%>T#KF(sf zb~8*c&a+_B4<<7rpxKS<i@?U84Wr-Aw(&Y^+@Ham)rVg4{nHA76YB|}cg3TJlSw5L z5Q|2}`$Hm1SXq^~eMHR!E}5p5*Slqfny;hXIuVD{g~wX+tm_`vmDg<(`42aNl-rl- z-szfe2mQ{05fYF44XbUQ&0$*Qgx@63QNI{I|3T%D-&EFAvw7-@?e<y}l<1Z~&AvUF zjoTeg!nhew@VN2-%7pP&PiRv-!uDokSI#Z3XEscKFPANp-Ebn!thufJ=5uDB_2!=f zBb@SkB|cuj+y~h40syl6xwPulLStOlQdnFrl{SYsx<3`P?7Ww1&AJ@5gW<6Y&O3Ao z4PKK5W&IyFTUHTy9yS27-Lk{~u=B|g+6cg?4s_>j9RH==?08&YuWL4%d~M`9ru(%Y zBl%|d6{uNZgR!2EJKyTL3%p)d7$W3zMZ|Z95{xIZ_=BO(a&BVPb^g>I-lRZ>1t}ag zv(3lI+CoZdL|-uA6;JbNGwRJXQuD5B4X8})21%2|!qI8oVokc44jLQ~Y4BMs7UZUP z8{4brlP**KT&bwcU}P=Puh#f#`k*6@`tQql>U;ZYl9w;_kH0SdmnE3KIWipqC%PBl zu=g`>^^>-2Re+$^jE#2|8Q6c&J2F5I;SEAIZYxgE>s7!1T{`})(twu-TjFJXqPFsX z2S*hJIy~=wg-@z?1F6xkuy`TD`v0TL_^Q4DJv}vEo#sCcF5e|kIO`s`6`P6w*dzS^ zaR1+>%LXsm1`^X2FQOM%AQuNk#;vw~<eTgH%BE=B`}X2fksCc5S4me9jx1aTK5xc0 z;^jWiYjbuK@7~@;JOc02HQQ+zP*I5jnSW=h^tauH%@z{WacH+uAS{3Ig;bs#!KAR> zxV<+j`6evc$(In$s2<rtRJ|?rb>Yx0MMTiF9hvxyt5!x2LfK8v41Zm>uIr6<D9Fqv z{4TV<;fJ&UA_FEBX}?aGw2yaN8;#vu7oRhjWjI#&Hzhaa8urc~HPa~B`aRb#IlR3* z2C&mG3inzF;_qo6FVSR_{TF`kTO<8}ZuYj1k<Negk*|T2j~f_DcTomkMFyU`K;l*( zMs*CO+`)XD)(YdkWW4}`+@pMlE0`h?$ees_kh>JIOU9WE;j#9uCq2sBgWQFpC1w|6 zPPA|X)XBC{fY3IZ>}wE_!K^hK_}wPX*2afhyz=^d$n_$EJMelzFQp*{bv6Lh^af}q z`!<a3L{d-qK-|xx!Rrs+2)^0@_Zc`6V{sL0wn*~&vY$HdqRB*zfRP&CZ34NM0BTr# z)Q{<$&WWzqd*Ui8i6kT>IFK;c2LD;2Y0=<aUBZsSm_CJ6<njkDLcW2-mL|#3%G40v z1A%&6w1k18oka^=xZ(Dc^0W9PX*zivw=W0iT~Yj81E|q#b8D*SO5n59;H6|fho7El zHO5`XKfY0<Znm_qz?%3qJD^6s2}{FOiO3BwI7e4WMeQGwQ75|cU7my*=uG%*);>fA z^p=0@cGSJuf~hbwLe`0@P2$ejX1=;&*naKJ{;e`1fBbe!sXrdPygxc(^DH(FyCPNF zlMr)CqilU5nWD0nQ*#Y8QhI10sKiKk{cm7Hh7PRFN`4g7l3%@>C2)wLbzrT%l5Tsk zQjMdN?)C9hA<cZ8%$?9PRp*>o7O2N$<Fd&R7S9L04^r}-^Km2BtY<d$*>38dWQ6I) zgbt=V8RhulC}4dD$QPQzZ9MF7#)iQW18-0!17<3`d#`(<zb9>Ck>kig*n2&&eUx{( z?{45iKFc3!Xt`L~e0ASU-(w88BRl&*lq{Hq%WulD$qMI}^!CB0TMM735{qmE3zXPK z>bDPBO?LsqfDXR)^OM)3LCnmr>qZ9eHL$^vk@$xmm)o$ZF)BK_w@KOfIW=mI-%$Sw z50O#&+GM7L(Htdr;SWv9`PE&zov?AK1V%zHcI%><bIdx%JD>(;Oi!C;3Hu}+Y3c;> z8A*=DRTGr?p%M<nU&kIYf$6fj1@i}FT`yU|^%KM0iLez6IIU*Fsy`Vc!K1G2_YD_? z9SJ6N6+VuzgQt#jX$U^)kQcN@qt2{cuVYqlAIWD~-!vM$mBSce<XXyAm_Tga&LOk* zSn?on6&?46`RoCg5gP)Su;zf9F*poP`^I$`Ir;}}0;BygO(?=25!t=TjG(-49uTML zw-QKctc313=b^6u4hhIvKv$x5*7>ie9KfQlRl=wbVOoC68s*zGaPv1surIy`ozNG( zMEW923CKS-<EexLzcPMr`+$-ZO+>0dXO2L)z&NOq7R*BJar*%bP1ixKQsDk_^8iOP zA(KrnH9GM@n2>Hfh?t$r+pVVqZj+N27hIk{qPD9`&A7H;7ur}_)Sn(A>?__zR8V)K zK$=M<{6|7PV#3B-CApjhMVu{dx7KRZYh<KT4lS%V!I1Ad%;%rOe+M)+T%b@b3Bx&O z7=m=WYNNBrXU|kdVooWq_W;qQ-{Hi?fI)$MzJ{zFRc?>gYcRvVdGj_oD0=ojZUGuX z5Mg+g5u2>2FR&y=cH0B@0r3KaH#OB|XjgpI7>S?fK7`xr4Y8L)-kl{XQ+XwhV^GJ~ zDIX28@7E@Lo~4vD@MsBBCNkl&$d$i1<U2=tqH;7(z86x$E@}4x|Ik>iKP?j~OF@$` zoDk$g{o;`fI$pFk^K#KRMbG=t@4!^$fddiq#Z6|`2eoBG2c}@eT!&n*8=sLW7w7XR zms>g!Y6C()_PlkcX@`(_ksSY4P7V^byRj{e-?i)FM`Hv`3>J&}DcqrAXA5uOKItI| zJgheQHVpKweY^`w*e}sy0Xo1)Z{OZ%G6!I6f5Zb#n!pDNCF!6+?<&Y8KnVAVf3dT| z`M3Q1U$oZu(+?lAm@Wq95Im-vkHtv-4_Tdrb?ggkSxfMeQJ=8YvYYp7Y4-`h={;18 zNrb7Fv~;3KTp>spx3etPE}BPP4-``_FUhJc??It`jt@`A<1@J3#hd5K^6X}ZP_RSw z`-^F3Yd>vmXBpT8`|RlHcA1m_P(-s|sMUXYG>$yHXdc>FVVF5<d<c#F+CAniu$DN= z3nLZw?L7O)aK_|_TQy96Jk~Dy+Kz(7Rw5XJ7=U_+JlVi1lsEiJK(Y>x5WDBzZSMvj z6DZ(%b@~0?XnxIqszB1YNVTS^C#UN0#xsZaW+XN$NKj2=r(QS3@wZ2V!|F>!W27GM z%8Q<yMjh3y$48`iKkP3pn*c)}Gj$vzn)kImTxg5nt8Gf4x!4tHssOsah0&#LJJsIg zzXSI4Up7Kf!m>i-kVZo-7VE9+Emo^^V<i%kD4B~T4d9YYva^_-F+snF*=vE35y|Xg zLCY80vN;j3Dmq!L6Na}XlT8<TlOMBKB=yl~NY;;;4AzZ)+v$$ti5qDVW3N%fIGlb4 zGh3=`i>EmKwWws2qsoMG%7TIQq395LnmlAUM6ZDQ-L^<7nMv?-{VDnDvqKVtEo!I- z-wEMuCQ2P@^1ycA?eR{BFVm=|#dlUMb|1oy*i16lMx+t?ONEj#afKYA*sw$L5c|Q= z=-cDD;WxNiT*EDrpiT0r$*d80HgPeT*f{g~_?`x}Q@TwQ>F0ZkMDdDtT6X!}Jl*x{ ze3eo20TlNHvlnO!7&l{zEZgt;{hOMca3#Nk#5NXS!de4YdvZ`0lIUJfyNCiT4TdEx zE7|F3IM}4F<Sht7q>}3x{gMjLEDu+Ken|MsE$418L3{9!>?~iJ&HrOrQB}co&M}1{ zm=TvCkc{1(E#g_pT8OOMctvH*yy{lm?$f7Ab(o=$#SnFg&7htI%^gs~lkvhfTPHVA zW4W8_297e@V`RUM##kqnC05TK4+UZ%M%yoC5~2;o$G^PbsMlPnK03?=Gnl;1ZyChy zw!l7#6-J)s%iI>ne&7AXJ$Dc;oMvti%3Tsm#yM9JAB^WE5PMt~xBO18M){>rpO!L! zEYOU9dCa{4HT=<akwO2(<<V&nWpI2fcBGbxJvp7q6{#XNF6tmI->pn>r;gJ){tNs! zNhKvH&zhLn8t>rm?t9{oE^9>Mqqec}Y1Fpjp|SA_cvWA-x`QH&4kk+S3<9Ub&|J4C zjs~($78+DCaBgekE8L6WT3+mm6slT!Hd-g2<>`m(Bj0TzTWi5h&(SE78NvFcvrJ*t zU)E*eCFzI7ulW&P`Js^m{VvC7wex1qOY(*7T6(ewmLk7t<9RDk-ZX(g2$zC)U(@DX z29EzXZe_EDLXK2@V7ARAf-w+-CfOc;T+yV0Ua?4sRy>#VoZ+Qn)zDA^qy7oU+e4Ln zpyja?M<k8#2a8p-tNq?k{kjJgH0hA!y$<&-^#Xt*28Rsibr?_cZuy8{S+2bF#kJ9c z!99ao<0W0GNC(#5gj0MtaWqdNVF(4|RQ*GNUL@46q}3jR>r*KG)o57y)kV#?n15;l zDc*c-oL_6z()QpBo$5<=J$EwT2dicLhv&PYvsKRBz{y<Wv!r!N6&*SA8EabB6^Gnf z&fGF43pq&z6e9XtIPT5^Lj8tyRY20<c4i_*!AMNclyd&+qDhxEc9CXbn^N#bxpGZd zPwsUO|3Hm;@y7~+ukBAaxUP5khjwrI{`n?RG71c#mI`6oHyt^xLye6%kR6RyOVic@ z=r<!+zT0GSwSg9$o=*^HCQ=)Mm@t7E=^VpH0F0qeuTK(ph?03kL%)<zEy&X6MN?O7 zlX{dW;oC8Z0tow%V~{${aX{>8U!t7J<<%Mj+GEi2j5z<}F!IThbvS)UFT~-JY{tZs zl;=0(?bKRquuI``J8!)joMKievtn$#?u5*<?oULjzS)MRgCGAHRtiEfvN?c#SuSry zSyZX&L?Gue<w|H1fQwLn+oP62{kFxJa(4z7Dp5?m>UI+|oyweOhgmM!WnPAn4xNTQ zlp)5_B5=_Aov$D4<MB|zy2^0cIL6RcrdQl&_|L=4s=5@)l4Rxp6V&fcVZ#Z%__A^O zh_cay#2Ja8tIHA=OmLKe*S%!+4<Go4k<xK3W&@j@Qyf!n$AlVP7oZj!I0Zjv&WgUV zAF`Xt<)Q?9S@IjfzYg$jSwAU-bKTF6Vc4DCojM;n&QpyVQ>c<+=%JmyB6q=V<2U8r zY9k`LB8jh;%<wWQ^|-#aYP{Wi&g(5AlLTwN@o$g`S3w$v!!;s<tJ^X8YeP>aClzpl zZ{1+OKUS^x#wEV~OSz8bL11sqK53>eIg$XTrnQQ~?yv<wQmmz}Cb++0FtW)f-^G3U zlZN~QMYwt`aB=;c9l(QBa`5pZn*1O#<d&oKoS<9IsEflNIUlz5aor|bjOAKlG<?&f z)UT)SuMTra6`Ci_rgqa1FprM34LxuUhDeo_4(TX4ELxdb<8M$C!p;$_jpz(BrY}b3 zf#IlVLo4MhLOA#Pu59l2@59b7E$5`dx~30B-mPJHLXk$qkZPYhl}B2qer)LC2_{ZX z(MIO{B;1@8mfxWFD(s495oJqdf$~L{_6>5^qB}PXm7yk;*8G(i&n6~#XTcyuvQ6Tt zaTTbSN2k0Qe2mE<<(<JYl7P!uKb%9_K7?gCo>;uA5KU_`@KtPXP1|mIwq9K2ap`Je zI%-HfU*f37X6aKW`-sPv5S8@%($;)W8+_E|7H_D%TI~|!2{eDBJ&Y34;u-O)f#kxS zB_3Q-QWlwOzHPa@*f@JWbed$q`G^+D{yn=chqEcb_R==><DhN-r*XHehn5<=LU>;9 zFM>flM1{IGt#FM6neo9O1>X4xHVF4PLW+ts%)z;p5x_l6zi5^k>>|)F(?<|$>Jjag z=sQYaaMaT+iUhbO{{TRu3=jB(R!C}H7m)kQ`5etNqEc^;>r=PfN@lA{;NnYP8~?}D zyl_LwRs6KsLFmOfaye57IONDHz2GJs4oxQvp+1_zT$s980=XE$V}w&SR`lU_U0cqD zGL*&Vb=odoSD653LQVsi%IWc*yy3&B@BKjcX?-!oEZswNH6ABFhvg1Q&I=PvrOMgx zSJhbR<-NlY0q5d}`*kGjTSK@ao5zp^u-Ro`heOvv0TZ&tlR{1;n$ll00||?uSHKeu zA~&+dGy6!G914g<_rnT%U;->urU#jzA5Iyaxhw9zTj5h7a&xNCp3I6H5cuRqtHYQ| z!|5x1F@JjuzVDF4c^cmT*q&{HQ#gbT;08Ez)5$m$avZL_+qrt(bSpFqEZSg*@PR!x zR_}xZjD~6vchg{>B<k%s#lRAw4J@SmbC$ht*j!N|n`s&~jc5F2hfYYJcP9(+<5i@O zv$cn~x-ON4_Q;J~al8y8QKHfrfO~aQ@UZ%5?Mgldh3P6_OgJx#U|8_{<mkR&u)4~S zZiY<(A!|U)bV`EO<&-(J2Zj4Z1~U{;tx*j%ml0SaAWZ*P+~BW$s&Kdu3>G;=F+|xY zMS%;f5@P8w1upqPWiLe-!&}ayzNY&rc?NkU*P!UP8l9-JAU@g8b!kzdY|IqOUQ&`# zmBwzAs+F?A*OU&8_*U8zROxPpYG<ej-QoQ<Co!|MQVCvx0t~e4fe_?Yv8|;JC$7fc z#JDx5x0SJ>^Up)iN>XmJYIV^(1PbDQ(^Uh0Rp1@ro>|C9nMR*|GR3GfyETo+e=ZU8 zYstfvsAQ$>d{Ad{=X`Y+mBPX8S0Z=Hz04h%P9S}-1vO(sco06fBsWQV**^MaG!`V5 z!eJT9RHP1?jU4$NxL@eTjWSS$-yRe^(r3RLx2-*qtSV&GW})?#uI2w&qFc5^Kw8Wa zgR!1Q&OK&I6xz{oYv%p5>F#Q|g=)556@GKDDj19Mi76^ZZ%j2{CLxFCgHe9;v}%YX zityKAFltt&ojuXrq2;s0Z-8T(UBv}j_<iKdEaD&a8@<Zp2+Kg9e`Db{*V1`)85n9D zVk{Gp($0~FMia~IzYf1>TE#bA(%TV)RQM|&i$~4BQA{#ZWp^0y`|(B!$|3bp?MF#Z zmjCxe*Bb!#vzxn9LSEFicTF+FX!k5V7j6^lZt4>57VDX~@dY7J2`U04a%-z8b8=~V zKQNfJRR(#`6Ck5wNX_->4Gq0I^~)=2Q)I4Sxy^#0NmOh9!vPoJ@#!UC`$}7FU<*&V zQee~UJa5l`Yi>A(;mW_V9;=PKuLa+YY|`*ERxfBLQcg%lT(tumeRI`f_)t|pO0YI2 zm!E_qo9whGGE&_nsuyZC6k5;3jwu4g99xdE1|!CcsSnRb*&PPQ5MAGeJj_U?nsm^` zHaqCV#YTalU-$%o2zNe8(!O8_D!X2;Z`OcwQBAuRh`xY^*8O3smqNkR$!_eCHL|E| z?uV0|MLPmkbt|_G`o{Y`UxhE7gGahviK=9+R1vAa;@>dt5>dp(zr$s3VgeEv-W0t= zk*i@4hCg0vFSj`*z%{vrh?SvV-E7}W`WNrUDDS1jTyn$qcMJZ@g)smaF)9yKJEK8B zP@$r7AwQ;6dyV0!Kfl1nwt6M>Y=s~3pvJalekP_!Z`Q-ARg34PPM51K#=76$GsF8& zjNP{#9u$T{)&^A!f)bJYIF$D-zhfJfc<%MlRXsM<O-|u{J1K=?(Kkz|zt7Oh5UWV3 zF0H4hPr}Kmt`0Fa7Nr(a!TkU;xK9`vO(tOQ7}Ay!{msQMvg>nuCF?m(#bu8^S*zsx zRt0`D{?zi5Nw+{E{WWS@VFd*veHvzK<w^D~X@ctk&FG*^g8yNPo!&dBxa?>mNFvMk zE(JE=aYxe7?$Bn2@IqTySZG3gWrrf+;A8E<=}L{ezr|{u=2hjIzC!4fLZbi#g?2$L zj0VHNz(D+~TCVeZr+@6n#2tB}#=LkcU74W-itt|=lbI#>C@tB8lc|?*j}}KtjdxAY zMh7(&0~=Is;^JyBb3Be&+gj5|G(3b}FzOZan87XdP~UFqk3lo<vdO@^<?&mISmE5Y zR4inYI0_wO#p5y)l2?>mPZL!0zwC+Vx<2wzq=R+KZ1(4#EQlCcEL<&K3--szEXSOf z^!<{X<7wP(>b$xfvcTfpgkWzz97O3qr*v@39EtlKqI=T@>(v+-%VgE9mYe7^w4{$` z(MYVq*~SnmYeT?^pXbOVCd=;lO4x`UhsyEYMQccV3K6%Oe2+~EVh(onzacE)U_P~q z?DE3y7yuUm<pS76dL4udyrmCPQ0&>_FU7?77k`gN)1p$XUpjXMXMv{nv9W0cvs9{a zES6)jl*%PT747Bm3-Q%<GW(4AI-}+%$-*r<#Sld3p{8V|l&E{4@X=tTgW*aH!B;tt zGvCp83d!Df@e5A!&w3AfH!^PnEgr@Q(`Eo}B*c2G0g@<o2eh(5dS$NrV`W#{TNTEg z&QwOXslQ@l>U47qb4b~FG|cDN#5tT!LH)&$uez@?^TFY0Z<{NV;w5ByJ{NuGCD)v* zNPq@JB^gsC4bQ<hlQcSzvNsRA+R=mSx0)vykJsH^?Iua?Hs`Mko>)bHFoPtqJm(3G z0uYXln*vs!5u&FxS$t#2acfKO@u0V*Xd4tWye`<WnD0KhemkRPuMyT3pK2^HEwMFa z6qzzB<h1JfwDTm#<<uledNi6eTZenbN<^eujaZ(rT;8Z&;90FUMI<p)>28%c<N2JY zbIM`2IGZG~h%%V<p>qfk*98N?`zu?|vpo}`WESBKm;Hllz;HA@;tIvM)SJwi=aw1P zLT+oGo>JDm--T;{dvxo{lJ4&qZ5&?}dNnM85qm9LVz^Oma#qML4m1MB9xKmhR59(K zU!5Os5;Z0t4^krHxiN>P4jcFLJ?d%6RVLyj8SVZS)gcn}vGcDEWNvtSpvUGsDVfgK zv01A@8J^>l^Luoy_8OJF>gx$*c=czm29OCXIUiAAXwOI<&Hp4ggmfC(ui=Ts!uO(W z#AImJ-$tiUY%5rK>u9wbk5Dz!C{7^UBNtERStVTkApfCT1hvH%Bxv41V;UbkCg=h2 zonVU`?m41|foW#6#YDLv^^@#?o4^lCd>krN7(TduWwc1b8P~>Y^IjCJ`z=_8>(@q< z5DMZ|zyVDX+yR9$Wujlgx-`RS+2GaXOFm{5ZY=zAouriAhZOpK+{38?!XBLrqw{6z z`_=nok9Mm}F1L3Y2KS>M3{Uy<q|?3P>m?O&*cFXR1+7mlr3($BZg(eNPBoYl81fa3 zW~0J)&X&*PZl9-icBb71k}q@f4Tt0C<ggY$jD-Be8RV!GDQ`A!pjJbRjoND^g)d3y zcI1*B85K4}=e_y(j1Mp7gV^bf)RT?qFIeFE86O$S*FcA1_j+D8X8GJpO69cEp*D=! zXablDM>DVOtK%|GWQWQlVB=KgB>WBT{Rz?aI`a-rG;dJUx{Zi6(nXuL{ZOXScp^}t zzzAiHzi&7=8|!^OCKVAV3kbw=rGeCC=q5(lqAY|wT9vtW{Mmi@!M#}?o%5p9rLFp{ z)Yz;VETeB~lsR9QBlU%(ts0bN8ZR_LX(5T_%w+1y*U8+S^29~lg7QoX33=d52K!k@ zdW4{MF)2PwU*r!bMPDgPNLYvqMP4cK)-iC$%WK^QClq**_UL*g8)qM(=}{l4HMr@T zydu_V)ZyMWoMbh8+K|iZ(sg>>?$Y$mq&{Fpf*J^d$Ii1_ZSw9=Tmam^(ygGk6<|cN z)dMqiisW;Hya)d}DE0+PWPUmTjpEaTq4Y7dx>7q^w!J=mFn!3O$g!9DmvQdvv=(~L zx}L<J1h0U05vz93pEE@o^jc_;M)z~;JHE^3vEtJ_F*xG!Q)uSH6U|mJ!Pc!oqtFqV z6!HMuG2-zmmHRLqfM~5>v-z&XVuLMXOHNtGG*q{fUzjA`A$tZdLNJHVbU_Y*-tk-s z;PyD9^l|sqErzkWO8{MzUrU&X5VPJ$G2~iPu#-!@^@ghP+XGa}uM1IeT6OXA=3BhR z{W^XH^zK4t+LeJf%aYwGP>f-daBu!sMS+~Sqk-j2saPEo7QbKnQjd45^+p?IQG+3@ zYjGu<b<q^L=W)$vE>d-Z4}D+03{ynNB$?lS9$c+Qh*25+%=eOm)-&?eBAzF`d02G4 zB2n*Wla^z@Hp5=bd)$s%h<$4y&SH&M(aq7LcdX{El&kd;qe6`oH1653aoo+cuQh+_ zz0w9|vQ29Qt4S)PKB1&HGJ7??En?diN6PK$Io+GOwockjvDU(`bRomTEX>+*Q*HIY z()I8&(66SBUN>*_pLUk}7F*??!14wWVR;ilRk_Jc?ixiz;M#S}l{)0US;7%9ajHXY zg}5O0nz;XtphoajVN|CeRYNDw+s;&j8jFVXLCR%`g4^vR)fWuj=bj~{+RCsQ8Y;?s z&tqy9OSB3}OcT2~GQh(B>`AWN$TZU0FOJh@WVQYaI{`|DD1$s*_IM{x(OjZ+x>!8C zMkeMcVz^|LJl;=7Jq$*O?BN?)xMJx*?VN&fxF2F5M~<TNj8t&NV!;A3)W@o79n?OA z4bP=ueQ987RxB{d0RNUpeRGoc^>?Z$Fk#_CkxJQ;{Oc1~B1WTZcr08=B5C(NX6E_$ z`uofExbbFJ;O{KEV%;*Ms8qjnrr-YkODojFEV+HYBju4I4D4K$Ied~a;T|BU5^lH- zzGSDjKhwwMk*_)@cDL4vd*=}&GhPM0xSMwg`X)TzZ0gP;AxShMzOb)_5RynzAo^FV zyqe7J)R_r^%om}QksE@T?pxNt938=>8H%DJNTZd5$*Z;Rh%Jaq79S=MuQ3o5Cq7P4 z^}pp3p%0JuYy!W*?DW@{I|%awp**`m;36D`{an9?#$*G6^*x}*xc|I;ptXLDM$v@E zPkEE=aN?OG<>89FNS*~+{~!u~**`YZlP^fyHc-mN8lk`}hF|p2^bXuiAs6+#*;#Zp z20|jfbMVgX;<;pQERpQ0lRp=NP7xGtm{=nEY4gxS=(u=IT=5p>DJ}_qAXmT?>rjWz z{_wMIMQn?l@!`ZdO3GWG7)1&amDV5`m|!^TJDn&;hI9VRiAPz><&~hqFQFV(236G` z8`8d{3+@R0Z=*--U<DX;zaFS|Fz(yE`^{Z#9y}QiTOVT+KT-KxW7Bq@H_1@uin0XV zN9pLcL7v>sHqpJ5w$!%#L`*jjK&^g}TppDINVB}WMBE&*N}1Q45#ICiXnj^LA+UXd zn<2h(C;ym6Zvy_k!xo8+Fu;N+;6xr*0_$@lZ0D2?IBcB9NY{g7tJLQSX>)x{SlAxV z&M6|tXUSc!eTi+Sh&(A$)FYhZEzX{pR$lVux$~IWVU~fWS$Ct}>h+6WM)E2;j)|QS zx2da>AUlm<x8xu{0c`GH{A#iV#yn-c59$j5msf!#h*A!8FY1L-n`;-;_x85rmg_N2 zV_*&|gX`4}nD1e@Tqal)Fhf%RaJ{{q$zoxGSG#ie_IjLG*XewXW^!^e7MSDPS`SQ5 z%&E0n)p)%<o|j#?{`|?`dd$V7M5%}fm~}@UvYn`D6*Dc%tNjrHM~%P(mUii{yy*>V zNuOIXD%ZQvDSiB63To!b;oxng9<w6^SB!3nb8pky6Y23J@R7%slf-7@oz-~>m|`7? z4uU;)5fP)IyW3&<B)epfr(HlSuBu9Ex}$H)!%*B*sft;}KAM1RuOX5>^JIjWWTVDx zZlnoz_vW@Uc|5@V?j$fvTA9DhkCIw1I@i0oZr`%fgcZy(bc!xksZ9%O&7xtqBm5;W zklLxyO^~joujCG$c-%EbbGJ7Jap+a{P0^0-gzZay6BqrVbYs<ciVhdwA)N&q7<UpU zYiT?l?pP9<=A9U=o6&gN28XN3(Y6914<h#*Ro?ZYs(7=Nr}0e#Bq@hU8C>5$9V^f4 z=fq%Q(ndQ;SIZ;psb+2M3!!b;)*mCdfhTVf!+G9OZ`G!=Uk0Pd0ot@}5(P3YY7#yD zUBJ(v#?R^@rt=inkMl;+x_2M@trD(~8e?7z_z1&~Gf2NeiCS{R@RpHJU&?fbgkB<I zds(R1k~4JWpRJKtOM7XyJ${X$*1pOuU9M9tW<DYqZ@+7C*h;N<csN!!70IMtBWn-b z<E0kSTsZ6pP0M;Q5m<u^WLj+2Z@f8mOc$Ex&_46NLpD<{OeIkmnZ|Jc`iPgDO!Ix} zE~2CTi%*|bl|wp*qru|V1hM<bGwhZ*NO-6ISr}|y;L1&ZyHiwc>$0@v>hkDM=hz?X zS#|EYGPtbP0}-^|<5n00qEJ$mwioAFVwd<wUtX?|Me)2E$97K;nnrnX9M+|DH#3?p z;aPvK3Z9kIjyKnzy{^!_dO*AojS_ss?nZC5cYUBo`5M>X0M##u3EiQa!Kk_d9dIGT zFSa!c(+Et7Yq~pK<_wW`zMWNVCKL=}3mFCjzYz>xQ*i#BmyH?3JvE6RgxgG`S;q#4 z?1WTg1<ckv8jT|6=3eCoZw~!L)&$J6;0Vzkh2)+@q_%HbYjtl1X0{#<9Gw33#li*a zmyV~nTdE<E#1svy91p?Pp`|287rOH-&D-w%@_DR?Nu7|6BS2{RSO1z7Y*=q63-$oD z{#+S^P4ejGMVcSa#ottFz>LiDB*ltOXj=~H>v6?*Iw4=pn|&PF;zYU$@^0BRFvWhn z`|-PcCH8ggy3{?y#P&7~%ku2>#G}W3YxzbvNAJs(6#k7w5P+$0;-$$o{i{fQPQNy} z+eY7cs)&0<^~aql&Jf6(-vb8BsYAF)q$8RhE+YaQQSML!A)<_s$9Kx*)3vrK?uQLS zt2IAs+b`><52uFnIXa{^yBiy(&Q9k)R{BbP`V;A|umbEhSeIYfyi>nvWygnSZ$%aD zSbcsB8y+yGb;XC7p-F!X>!vet?p+;k)LvwF69#Ms31)MhFz}30`^E6#DGc^Tjjy_Y z4Bj$a0ZsC<ssHhC<A3&~d1fb><avCCH8Y(c5$23c|7!(Twr%^az=T+4k9pnwM>6hv zur|m0gk-157}q8o?NyUKr1sJrY5BJrMeX4lx8^8so$aY;>!$+z^VLg_srtWiOrk*C z-NW*)11;w0fmt(%=x%D)BM=OJXW4Cl#viGX_T%eJ!@E|)j@avN^U`ISqobVp#m|*G z#`lMht6EE8%0GkEuw1+Rg~>`dgaQ~QscO~eirDthNnhI5?N=mOz4ywkS(f0rU)fo= zLjl@zcOXI^UcW)3dwpaR5tALMUSM`6Lf&Zh*=#Ad-R?u^-qcQEFkZ1A=iXncvpm-L zWuAW?22i751Ad`Wv^8Bq9rafCFkjyO=EfvPwDNr3ULoe1VGEDTG1Cgnycg}2;&nKv za$Ie8p7-SC;jZNU9rpKarvRNRC|y_fDFWwjl_m^s((p!#S3ksFeSY^?nw5~@d&Jz$ z*`@+2KX|8-JENa$xf3vraPh6`w2Y25?#?IN<q`_iLh5N$nnhLEw@Xq3pXL^R-YRDW zeR~6Q>~dQv8GdD874k;Xell#ZkshDAo0x2eOb}*H#b0vUNW4G8z3gW5dbx;Ppcnu{ zH6B6x1p84-XN;EB?SVj*mZ3|32(`ydd){#a${7it|Is(|vEW8E@sV>i*`3yr&L5gS z^B{JZ$*#hyDS%>wW0(5gBk3^F>nevT2{R&cQ0Qf-u{kq!=T5L?mk99*E;`6QWnkUv zey;(!+`$6wN$e6wV%FYzME9)n1o>qX^1UUqg4YF_h;dTe{{Gs^*{OU;X-$+oiFN!r z$LO|)TF@nv=0WPAh)|Q=R59W{ssziWU|Ppx1-@}prQTteBMH%;TzAZ6E?wnUOLzqN zX=(<0hi9|?k6{wVN*EuALA=>ZzqgBEL?Q150^*%Bpaj>Qy3d#G7M<1Bt*(yXt2Q~T zWx5&j<-5%MJk0~12YAbD1fWze(IF-QG(u|R{F0@X6VKOh8z)w$&Y<sy%J7?B98hVg z!7g{Nj;pp;noa72&n=Yi)nALPD24jg*kQHFIdL67z&bw&>PIm|-Ug_e>jy(ryxmaI zz(~hmVkhC*0N%HWSxa9T&z|mxR}mTK8}vBB7O0<YDf!S%bc8}CI42nI3SB;JG(XO1 zS{E%)13xOzY;q`a-%oe0Wxc!X$9I0dKkw)CyHEIqhvRNom5~`H|GrWMHJZvSx&2iZ zAWYZoaWg4uwbEeQbPl_d+spq>N3v^Y_prP2*TL+@xvUQ<X^BzTk7&b1VZ!i;x!H!# zBX;i2uLmNl{|{N;z+eZPE}68GcG|XW+qTWLZQHgxZQHhO+qShQ-|Wopo%;`7KCUXq z1_@u<@URHmk%F@}b1R%9nEhJoDaf<>FWRw-t(L(^OuN`VS=k5_X<H_A2dBEuk4Snb zuaoqT3`xi+?_Lg01nR~bBd}>>UjJ_b5j9njU>00g!BO|~wjaI^236QT)<3B}>s93M z0vJ<ZR#7Cw>Br6Aj`5@qn#VtQn#U&1FPfjF6Z!?lvkx!5UbS3s30{k64PEL1G#RaB z>`Z|n2gNJ$l}_<imv2;W4-CFrK{u!b7NiSOUa!o_5WbXgySWG$Ei61Ag9o(IhtMn- zxu=7{e(&W-msxlyttrQ({a8ojOq@ehtJPx%@EM=m(Cf(F&-4Kner=CYM;n{vniu9u zJ5eHIq-YFpQVqY6-!|(=l)PAZ37|~#RtEF6q?OasZ>CVzACk3pkw2<e4-V^~lP>9< zKF=#p*H;rmBJF<=nY9dUW}G}49{Bj{e9=!0*#uIXFQ%%h4i{SK>`t1m^fQ^S&3P({ z4$~i<%Mt%mk9~Isk!Hm!>ob(a%~_wm^&ATGzbs9XX~9_IJ_2%=P5CqZ2tr;)RQ3L& z@Thr!<*Tnlp{X=ot1Bp7xhm-G`1F(7c}Uutm2Ou*v7aVWT~Bs_9-7PWKy1e+H!%@K zkZ;r1$Ni&I?Q+yOx|I(r+h**re1@L6-!I{%H~QsH+<0Thw*@d!Dd0k()C)(+825UA z;_vJO4Z+A+&9&+UKuE2p&>7sL*Sx2~8L76mw{xnLDN{ve_XVIi%@@monidxkd_JGt z-bb=*9&3AlJoq_$Qg#sJRtx+ci|hVk03zkOi3SSfvMVl7BPpxqZ9yHkSz{izU(#Ct z-e<_BLBFU}yg1HvH>inZtR7hREa)RkI$`;80qJa%%nWA~OU+&xXYQZ1w!kr0pV^Jb zITP>=ow!}dhFGM?h;0?@JJj52mv{D>Uo7?Onjcl6_j^&-1jN|ZVugm5nR?oo$l%Kz zeee7S&e^YwfqT+M|CA|N(m6{Vp0Ngw3gk;j1#tp>E&bHFjeD9!vW7oP9TL&6Yb|!M z9Bs-*NVV{>NSevv*7hYPm)8v6K^Z?{K{Nz?%QLM^zF??Rdv$(kCJJwC#5JsK2g(FY z^^U>vAfETyA8)o&a}(P@*u`-;Z&O)0nt=sS)=lv^yjZ<tG-(bb2s)2c4{cORhDdNl zpWO>UhcuHJ`G4LmX51(MCssORB;2j2p;>K?Kdm#VKs#kq`7{rba=cy#g%q_oXLn64 zkZJ%mHpOWkg<CtCH(lKXnV*gI1*Ftw)0|_E^`zfAy={C>glh&9M{2!MC%3*(urxy% z@xqR$Z+6${*P8!L!UK70SRMm%2Fw~#>H_6dT@X&x4EOx?ak&Vip}nLUE!HW3gPanj zfzu7zp`g&GX}^V=siJmQBR8a=jE*O^IB$}-9eLs-<@v=;guX<sibW^u3=XaQ+SSd? z1dGvQ|Hfe1?l5nL7x7bf@dp%Vw>ljZrC|3hUR;u_afHXsj#(<_t3ZA{NgsBrBzm@% z2L7Hd^0%a)4zJ#<*!{y$=@f$?0Q49IG&<vUFj0?<J{q$H>LyY<q}fPco9*S?tPKD@ zL8!k%62x|rA0H()06WzTKwx0=T~+duN&qkcpdB@!U>V2JUQrHS&p!}|Ap$5P^gQxh zZ}05#y*d5?l>&OU-G5-mWKhv^(QwnW!uYk$)u;#MNF|u7KIAVuF1S-~N9gC<=;ZU{ z%v~Q7RSx`^ANut0b!(E$$FUQ#yV3|)blzZJkk7J-6H2L2U|STjJg&{ikR;}KOl1CS zba#*vmIPs{W$lWz3AB1Zy-!!mx~Z48Kc0fT+|RK!0~H-m--2F2i65nY-8_CR=ultr zQ;cgGU&l#+j}CminP!ZKtK{Box^8g}Vnbt@Vg!q%)|x*2o^9HSthIQcHY8FfXF4a& zruI-lPYjpS9)*)Y+@Ut?i3p{CKGiTZ5YB2&Ii-I;Ioki!^XzcBNiIysRhV%YP4rLq z_TMR@R;6*mNg@yHiDT&7-ymcBi3Ck-qLRZEWIGO#NWkOGE%d78kXIgTYJegq92D)P z{7JXZPlkk0F*fHCO-G2)^`^@1)TJqXX_xtK@3CxF1Aqsnn#_ksR+7SzIM@`_P>q@p z@pXof@?8C)%wSN_PG=UWM0KceFk9o-&jWByiKlyr(ug!xWs#_8deu?Bx~3B<nUK+Z z-Km|}Ix&PEp?832Y`>EXB4A(mNq};2zX8`Gncrt^T`89=-)p))hwjWa8-w2a)?E%T z^tbsc>+_MW{hjlChCnpMJ43+>M#53w6&h~I<QQppg(Rc^J{u+;F#kSi7ZjKVDLCAN z^*6jDQDw38*L3-4u~W`ArYwT=(p*wPsWHBp8ih@ICyb%d;Laio$Hv4fxTBY=&y(dS z$jPw1(~<{M)&>4S>+J)QTSJT?RQ<b)Ho#zt9_NgrVxIG+sqWug0M8cHedUE8Ni<d5 zPmSf8ol=wCY33*!^V;HyInX@n%LaH;lIF<wp=LSb28WQBTP4?wJ|8a{@VW!y-&?#s z+)7lcvJNjAmbBxsx!j78^nNbp=M#E*lj)yi<NT)eR;Ha->Dz^DvWiB`^;%z_-3jkv zv|LpbItL)b%9A3{f|g$HlK14Mp8H%*Tt35TI%5D;1Q~h;hOccIu9bfvq1{_S-^Mt9 zGAq}^Ns}I_rpXxwnNXpu4a-)ZufAtSpx+d?(;8)oO8PNcY{+SQd=RnaNkc#DL8zBN zi%Ty$y%?Tq&>J3m*7DHsk1CpyK5;W>TeUw!d9+W8IA{)opJfKkO@q`&Jtpns6zFCd z92qJ*1$lg~{I0!!!@+$`5maseqy2>G{1fIqUSz|qW)|NrAJ8ilAF^i`4`x^^+3Kxv z`Glk3DJLl6gOCU-grH<>cAnEmv)O@Dd+t*Qd;xUlR`JdBm)!Y?BHAL}{f&bh?$HD~ zSWa95;mBmpd=#Zu#MH+bk=Z;;%Y)MqrhE{I9(Zbj&aZcYlg&4`m26;ccrv?(kfHq- z@Tz2&fQNFnzAF031aEHJu63`k@LC!kWqpOyvHp|20`H<E)hL*!K+b9epdQ1cw3pe6 zH>F>;x32Vi7c=r5l0Vh;>IE~S8Es|GeZCn)CSk$*bVoz1TJ?G!fz$7|RdpqVT6fYM zJ$6aDW!V=J4&Z^h><0&!w3BFt(IKu=N3Xk9MYwwwp3BH2m|tR26I@~wE{GSH{08j~ z%#>N=;np7$-ATP@2nq48wY$MQv0w3@ZD0H5y6sgir<qeuGXH?IeMkGZZq+6A4SE^> z3<mmg8xGc573_&sa&O(9eMYo(tp6Gzlfm!o`*<wGA?QX{gQ=D5S*(?4deQo;wX;D0 zJdjNY_&aU;*WNY!<rxmvVd%y;umOv$lS6HnSob1nr6=2uQL9<8g>~5I$iakk%7AX3 zNj^c37xr<m8~nUi0Yh}0;DTc~R2csr8v|5wRZhpuwwwq1%U36YjYgd(*G61aZR>Cb zan^Ix9NTfJ9$MnVDa}}dKU2S29-A;rCH%$VlBn6()S$T=OlJ5ipanRQ*Kt1VJ1smo zJNJ-(UJWU1)3x{Az0-YKcYQ1_RBEm9rJQ<b@<1JRV^6#+xmp5DKa9jPV!x3<c(m~N zB%rT({e;_{mUMuABwTCt1m^GdmT@<dQ_({0cxCpqoA+fSMn`uXBV}9E*w*dYU|gpn zQ&%}Ky{hXKwD$gn?|jD8q1YfOIG}H30zPiL9-^v-*5_8KJ`P>vTZhiqJo|f<^DzP$ zPb(9n?6>Oyjk5*4P5wn}RMB$Wwuc@}UV)>*r0J-b&e5l>nsahM)%A?rOyz*<Qu9{b z?F_vy9_f1?e39<9&sygV#nM#<a+Y0qhyzK}>510{7IWCZ8ovjlS-!ouK-+rC8%^*H zX_QE~^9`Bf`W-`;1KT|aPjOUx&hW4Vu6aDh{D*@IahMkPkIKW6kBuht8h(&>vpW&j z8@>IudabQy?xT9UhO~Q!v8HnYk9HDn9cd7Qwx1X@a8CD7Q@uNtbug_}hwWzos~?)q zZtgqQZ=>Id2UR5y%O;X|!3!E6iA22V@LL~UP17);Z1J7*>4xTP{uyyjm;N2=(j}+_ z>r+8M=JdrUoxwArOs=A)&2=B7$<aHFelJGfn)DvWfRodU<6px)%LodbfEoufFlFB} zN0EYxSFb%<3S^G*tE}p@tnO*6g|qt<ot4cS$$C{C-4Iedhw7Hirx`D#00>Mn2_?4L z^b05gr1xtedXUM+5i)ce+MTg^FN7k~6ZhfNWXH{y=4T}qDFm4zn{9R=1qE=G_`_Y{ zP2k<wNxdXZ3KsvS-3HI3(55=qfimTK{)>@a1RvF9jgKMN{ZZgt_cD`8J;XCm{Meo> zqP(QGO%EuHKp<AoM=J~#dvo0+`xuk;re^Xq86_r}p@O{p=K=JasZE>t5_M!WatN6p z8q41OfZ5J-bVQ1m7XXGG++e)Wg>xthC?@@#7JGh!yEc=VfIV~gs8J5iFmV5tXzgWH z`ldHS=`0;COwCNZsZ?R#n$BvE$L;gG)VA%u-v9C`F?>V8S?9<sG3Y?c12a0D=7jyR zee|Q21c8oDzN_;o$|Z=*{eh9<xp%T_^zM`*gJvq)xTgBa+h7Y8KqVTScMWRAIU~Fi z;AtshGijBj!Dt_6uGLT;-ZwNV{xE4{pKLu{uw=4LLq)al(YOoA^8PBJnW~CzuuCr_ zX4MT%umLmPw7@LSn(9HWSUa(LTzR^x$ul07@O?@8a>()xPoqa?fO3^7t;(Uvx=*Fj zu_A1zr9QOMGn->$5vp+r*Cloc7nC?^`PWb53MYaf?aMfc1?M_%)uUNl&W<)cits5# zmS#5e-+oZRmLccol+L<W$}IMyW0&)<ByBm)T<1<#G7B$FS#r{=Y%oQ960*;rxA0a| z)|X$C9Kgcaxmtq!O3qKqBUVeD{vimTYSzJ5sZF+uMNc9#la077nEmuTO)cn58m%+d zUZ*g|x_;=uLD_xTgZA^o|D^uhzWCIJH(g%MvWB7Ee%%z8{FfP%M}Oduk`q&Z>V@)y zFZ!Z%)s1Sc87H(AoH1N(3nNogj;p~P?%{Mo$q&>2`YK8|9w~EZuX1jV(AG*YBvn+{ zSY#n?Ym(uakgC%7(NU+gk*_?lo<-Bu%Y-OT3dIE9zn5I4J+B>jls%?m?n)`D2jgWv z9eK_(0B!b}@OG2ekOfa#;U%kf+JPVB=gv);m!|Qi-~jRL7h~S?c)l{XVLOEN8sW-K zKmZIK!dOA;dj58>AvbL2irwl>#H$v2wb8buH(7C)oXdVU&d}g%Ti;;HG@JLX*5%dl zI9v<F0`L`oA0z^)BF}3ZrG#Ae-CiR}E5EAp@8q}R3A)O@6Dh60utd$bNv;iwFOLn+ z>mACc_vYjcAMOs#4sj#RpYA9Gx+|zj7FB4E#cR=E-`7A82eqeY&fFnTFipwOkV(Dw z1##X3wOFk|)$XTot`=b-zSgO1R;78_$3>pQsB;jwr)G>eCl*D$9=V?$A){NBq0gFU z3r1V0JE|NMwo-Sv-;WU}zduEsEz~rW>9DI+aM&-}C`vj$Etla0QZX~QHOfrK>95<Q zYIxgfrDv2sNE$i_E$zj%ZTNCF)=yjc-AIJ-Rv{%Ec4oc!m8p@V0sGVWvz3-(IBbnk zBk9i=fY^%bmEYWQKejdLU>=B*Bsm!rd7eJXDbf=^uJY6B2Y=~#N3V67w!E3m@Uwhm zj$AHcRN6LF3tLih4`ywBsXv|g5m})`xPYa=YkBrc5FidawWM;a)9`ri6?Q)Qoh`TL zNJvZC)YObr%9TZ3K9J3Apy*K9Qm9lY0n54Jgy4Iui8jaVxqhfdU|U-Fx43U`eJxEb zm@fBtJ}>-Cj&#EDaPdvO;^(tm`im(fk<C9EK7B`lDO_}g-z+vmx7$9Sugq*4et*#! z?EyZ)UzwqQD0#WvOYRaMh?f`%Nv=#B{<Ucl@C}Mei0{S@8`#*>1}G8*{*clp2x@3X z@bn$(+!h=3h@%^_Xaz)Xg^V0AK~}wR{CG)4zo{Y?<arq_BrXUzShP;hpQzM=jK(_x z(w3fk@_73kVK9f9+~<y#G{@c|CfI_6W`jW?iAI~u|FV@=-GK*G_$!7QXpj6?k@v=o zCd1WX820yf>r#6SobGl4Rk$Q*3}#UPPmBXhsrSSda%UT$1#rr#;@x>V^Zxva7k6-8 zH<bhc`pcH8R8`(-n_ipthrpZNn*z!cX~6~qJ>~!&lG&GrW41-ss0^92qTd?-)El+} zeN<$E%tf(nZV8XZ?68T(bQDKpsbzqA7*}53z*1S9bH>%43(B`zF~A<g#Rf*1_U9Ea z#0I03Zcizy#y)u?5-Mf|F9R|o)+#ST+0#AiQv^m^ii(4B`s+b^(Npgv8gdUaru%$c z?5(4ftiLpv++3)u2Ax%T3#Srn>DLF@65we>WaWk#DD7yYO~wGD0^lzWkNl}^+Zro1 z?%4^FVhLtS6yigT6@~-5G)C_UPlOV2gaz^nu5bQ7W;+}O1Vfv<V@5!TkSkIkMkF?< zowc14B{iBg#TQJ-qj^}=-5M;v5ogdq(x)_G`hv;kOC;9xS@(GCk;SFrkkk;7kKDy? zB}lY2#Dbu97;e(Krh0aZ0>7~~9lp8R$!(SG*N0mt6ybDgjrI;B{SctSH>!`%%_U5! zQzPzV<SU#~C%mD9kIRl$>#-e)i%s=^W5;bc%_e^0am%hZlZ9lKoJKadH!Gk3(7U`! zV`DKXCw<f_|56YaH?7~vja7k4i(BWVtc|6h(x{K)xNMdhO{TdBJmB~f(FeQQ7Y=-w zZJ|$Sx#rgLS;|+-l#>*J^^}tFQ$U818+rB#_(G;LdN|l`fADX)a!BYe7fce;>sQAn zc^M*dF>N`Bfpo{z8I6wjONXTAi$N;8R}$d>q4-?m!+zRZE5u;+pKe_uVFI?8pooCj zmq1uZrgv448CM~)Jz+hx$^_Jau5Vtkv?}NF3`UC$$r78VI7DoSF^tq_8-GgfgLblx zXNh*mz(A>H0}k}fjDA`rjD!FK61-VBFlgKFU!Wy64EP5*6oX@(72rnG{+{_KE!8HF zJLTF0z)+Fioh2lP{hD(4J~ZRxsy7A7r}HHQh#9Dl6t=di5J1#niFB26w02_#_d%yg zK#dkFwPqd5UB9=c5iow=N57O8yWAD1RB7MthSP{&tTx<K*6~jzU#vAr0Ek;aB%UFH zpv)254~GEUNzKm&*h!RX_^6lVL4{HGM{i9Pfa4P0z7q6NV&~y89|)@*--71DmFt%q z)+ePrRq)V^lAdPf!(|b%tGn?<f3VQxug||&Baw-0Rv>O?)|$;z$UiK}G+Ga^ovjcu z3gB-Eb-^dAl?^Ht?PL2%L8CP*E5W_)YoPs{XV4L;v(wiHJHOQR*@qm4vZN=6=Nyb_ zk6=aO1AJFbg+Weo4(_*{Yl#3_)}D~}!sc46GY#{dWLz*-)~Z!=^GyHcI=o76gN5%j zn~s;;<IA-~1rMgvwQKzQ8RWbQT+oc%i=EAzy4vj>Sc&=-V~L}@QV3tHOMS|;XDG8Q zB|F?LQA&f9RqOSyRN6O=AFLj%#cP7b6W%gu%4GgtI?o3F;Dhv#5V<o6*_~>Yo!9be zsS0w1(%w?i)GFdt1V+p=(_VgGvQhhn`2^DYMD)^UQocLIxK<eEyW-MbqH*%OL|_ku z4R(l^*;5!Cv=E6@uE&ypZb%pNVp)$IV+19%sb@u8vSdU>6?2QRcYZ>u(I2p}pLhE) zq*A}>$3mgmHPv^$tGB$oQskSJ7_Nd0AYEkn6c^|O&G4-M-@yXXTmGb{;}2^Yyl@>- zbxp5)sJ2@=v8`AdTVIe92W^cLX90~+a)BvYf@q*HA%r1pk>CM>Ju*@cxSTXgk@0#( z96`1{BqqvC)owij9#U@8NVvTOn}~Q?j_f*%RLRbF{F0Dax*xlaYQ|Zbx3iG)En_Vq z48r(%d$KWks)}WU^;pMB-_c1R=?g~`L{Y}dM(Vy?G#1O%NS=7SI~1)oVbJ*8+=e!F zCLr3=DcnFvjaw367Ne1%h>%g8;{dHzaR8eY5i&9<8U6_==E)LD3}POtI%U`UZFq*= zDB0=M72W}paxJPfWrcb}Z*jnjJiu7{ReNRRi9{!@S$Aof;Jy6iT@n>>?)CPlnV{A5 z`aPOJR%^4<+pBG{^%p34-9)s#Pz+b`9Q+gYfr$rGp^?A-Pv>O!ani$CqbL}+&yuj3 zIx<(x4V)~w4Z%v5Xndq9{lRP5C*GacyA=MOg!tVZb+TA|R^lrWsWonZEO%+h+@|W{ z@cVc~_48RT6}YxaVgXV|ba-S4P-sy6wSrB@wd>Ybwk4T(s$XGl792yymhkol15Fmq zW>X(M$GD6jsm|=vRa|1(q8M&x!aPqyPJ%RV75St+U5~6Gb!`Gs*Vlc61IN?Pm1Y{~ zqhAGU4bEe0dm^Ggxm&^Ud{zv^VcyxV6kYUj{A6-h7H_$q354>83S6H#_2o!F4Ubl> z4{GngM^VfhcS95UPT`YB*WzmgVNZD)Xd??8NTc$mr48<>*>RlXh~sroshqj#6bAov za&{Rogz|y=GN;9$L^<zGoDP8$7I0PS;ctTF$8gP;z+BJ{O3-0^?+L4WmV+RG;RJ%h z5b?Un@h=ouIq89SX@>j$5T>g)#PvL<ipBsGL~|NsIoZB(JF7r565!kwE28Zp%wEr} z6j!f6fcX=f$$aPig>DVNlL+89@DVnfan3OIX}hMp)$0T)6xVdQY^c<0d8BqmiK1)3 zhrOeBpbkeT*lvd(mw}MM(p&a>`O(@3sW+tcCCf#hWWy_M+fDdmGVp*Cnk$?ww56-U zt}0^{PC2ryWl9g?bfa})V|8iJKv10h-7VJDUhv%kt%k)w5E{1|^2(R)@B+5Q{k3B^ zD2r*-$a;@6$_6#ldv5?~vcxhB_4|EBX>1XIT1uBOA<BG~O-NOJNGgkSg>U~9>jf<5 z7$>pn(**8xgd}_3({0yP8^D?MwDEG3U6mAyM$%t88F|38#RUkQD-}!R(~zkM4LsEv zOwM&^+KpI0ah<S&@Xm;MU;{r^I{#&P#e5toj*RrjOmk8Q!V3)7D=*4644yW3%@iwl z%@(Xrt-STyIYPox55s}({k>OCI5vu`xereh#DWyVoeD;m>{z%yTi3?as`U(_)Sb(` zttZQueqEOzo5lOezQ3lSO{X@jx@?1fOqu&sM?6j$JT+q}+~n#(eO^tk^e#;Y`REZ$ zfAhCUZuP8ayEv85Jg_^^N>ndu9wM2XUJulLkGu2o$3qnwT{#`(vGtee)n%ECj+7|5 z#Lm8DtE8v9y*(^2>+pF$t9Vt=q;pQJQ$0zZQ-xKtGNzu}*p1e4BuNfg2(%~6jca=- zIiZHOH)Ts!p%U(M3cV$?lJ;LnacbMZ=(L@Xwmh)H<{rF|&l4-hSb@3grRQpV9!8+s zL3c{czv_jiof7`J38T66m`CgfoL{7UZ)}nq)_(ls#TUn#2r9ql75>Y^K+)}vb=Ujd zb!5M_quOobt$fjH7)z!Nx((K(GNlAavR!8)Kb!9_0iaDg$Td?bX`4+B4mFFap=nO= zXs-FtWJcf)Jp(Rw!(;CPkheBlo*A7c)Jq^wIKxNaM{Ni>X+k@NTk*V2DBGVL4rJB! zrP`38lM<_sGKBT{*2Ik>=u&}sW#_Ah^8>pj>uV_1oO~g;E7%VM6$+3@&?5L8<k;)_ zy&_C!&u}>_!7W?rl#&5@uI(Z^T4Z~n2p=8O7k+rItV#f>7CG<DhnNs?lcwKq0A18h zTOS5IZ{N3g$LYDBXQ@A^Y2Nh$^pkneLvwFP(Zg~Nq|k$M_n3I3wD(-CPH^n47WjX& z#`ZCf<IMG4AN5VH{X;FaZ7t=qKtQ29AD;k~HQa+oe%^k5VKwucra5R~j5i}RT!#9} zP5UEeZQwz(I)M*@pM`^A;^Y3p!`XD{k(wEQbbv(J>7rHptW&FQ0KwM#ES<;gFoY1t z5<F~$_mP;z`ZkXmZ#3N(9RcI2vi*+jYV#OepP9qF?ag#Xa;e;l%3(`5XOirU{Rv~2 z8LJ=My?@}9547s`;InJTk7DCY2FmefMvnTYtq9Sgb3C`s&h0f5U|Q|ha*Mwx$Sz_e z#i7=k9b6L(ko#%M+j<Grq+OktW;iWkwI*eV*Y%P2sY~|i>fLPsfz&VW5PvBKuAH}L zL%8L=!XDm*m7*s5E1Gv?{>&?U8hn`gyA&PEvy%_{e~1J>vHs%5KVK@GPUpo2e5^|n zxj%y5vx8sFt8CD+>aV<PXy!`~xqbd*YITLBZ~loITWfCkGn6=h2ifJ3G`}M+JJ7t? zU2b#TH_M3=p%Y@{nq{*!p;_@cKlRn#{b}y1YB5C23)yGBSZ>?l{<P?v%vFjieV)c_ ziEc$}GEtmp_${)gKVjDDqBZh0%I1Z%%8siYf1hIaD=PC9r>Zu#_v<%lK268{ERS0? z!@uT17`{`zKL^j^z0+YB{gz&|VgX;YJJTCUB`wcXZ!rdb>OaHLx10jD+RDPR+H2KW z*Fea2zNo?Hla$P$0L;gqtv->nc%M{dt?O!Ofn<gezyAQUtG=I>etMLEZOd;~#e!EX zP{(3<sjFJg0tN>#hrO*ILYr^oABnWgohp9!S5>K%G+Mfv?YV4{T2mU7yL0CXvnbfl z&Dxo{X=}f~+JOF8Ya=Z;k6Nj#)X$8%9BWwnbJ4yj#!Yk7EC{_PQYSK%m!)vl|7;S@ z<m0Yo)7fS?Y}0hcYqkuV#b|x&eagrp>dSU_s&cVn6fMkpWoC+&_w7Y)|49d>wQ|F) z#a%eck>d%gyO!rOj_>{|@Ch(Z^HrqQG#trGNBB3>#Wvq}IGW6K^umSSv*E_W%F^l4 z>@f)Zpr~{;)e{%ORRMAb_*j(tSi*53ve1`sjhN_g;poHw1`aVp{$Gcttf)kPjM_w@ z)<YNe^{T{=ByGCMF6g%v@;Kec)@rSX_|Vu++(OBrtuwaXt|SXyD6GbJpR?h8Oy--} zP?GF5*=Q0M17E18vOZdzD`Zd2y>%%562H|Li0py(1p2)&1$QB~3#!<xaBx<3jVk~s zF+l|~3$#1jhL8q1|3TG!B7@Xl_u-6lEuiI{dk4~S#!9Z#xp%bR_VOHbs6i3}3wxAi zDXQ$!TGO$okN}txV!7NOB|PlNN}z!SH{3I6I;fASl}3AcVfFPhG5I98gr-k2WSLqM z2*91JlHaghC6PT|sGzuo#3#Utbd4#E=fUg^$C9Aq>~W=ji6<qkLZ=M}CPO7yX>mxb z<g<>`fC|*BTo)*vVNd=zT-Q}U;?hp8Il^dpejnSfyJF78ipM|FW)#)N=8-Qg>ff>L z3Hx!hiC-&l=U#);jkzMKPT7MrzV&gLUUl%eLvS#9W}PHKeN6m=HtCop{L@+HNY?0V zsbZ6BPqf8GoBD9Pw^>nHxRlfD%D<MHgzpm7E19uU4%^<6E?ad=cq$-alExUsgI3+~ z>&ou(VD1y$cNakWe6I7(Nv3;3D%^a9bVcg%R5aQsb2#!2Zk<Tas0)Wig@G_ON}KW; zEgB_~$*Ta775fc6CAZ@HB0T(e^q^j3M?qXF!Y3FPA@X@@vZm-Z5au$Im!!bfmR)`y z<Unv3Oj5u_#iyj8mZ&$B0(g<ZCBV0_^foG3!jkzk2;gsL!}ki5#ujI5l_1**J)WYp ze|)|q@{owYuQgfgv;ewj2N4XD&tDe=)7eMEmH!YMM`in{T;{YJwur(*25ZwM7|{v_ z7|B&96j`j*3NTx&;=4ax1k7|`M*NA4pH(&e<MCoApQCS7qF7K$I8fsy%&I<H;3J@E zrV|2>OazX5yeb$4Xb?>2_Mw;GzO6#nx}Grum_nirfB)_yB}zgg*H9l#q7HwnB33e2 z4DJrpc_;0~Ur<E`;bIl+wn^|J<oyr`b!w-MspHf3Is|n!yib>}as_Vzmq2%X{aS8= z`BoBU;m$6JjcON#ANB({Wr>oU+*od$O&5sn44oG=LN}@`MNLjt77mo4QeTjd7r>Z< zMtpSnd9;4Y!cgr~iGvtan)B8H$X5duq&A#SH(MLtoJ1Rb07)^MjCRMW>Cw0nl4z#! zZqIimViBie@i;+Ux;ubWw(Yo`uNZ;bJ3Tw!M{Yg}8a5CF#gr1Bc<C)mq}-oCX)ZUh zU@<st3;sBh;iJZ?5ApV!tQ|k9(|!iAip%?wgYsmL_7U;<N)~Or@2Xr3jN~IQ|6>*; zZK&Xn$n|*O^~EHdxsGsg9G*o?tSWltNfL<~T2IB18qC9nkRT&u)!AFK7HQ@-A7EmH zDzib0tkcDVfC78ziv?pbg$)JfCb8eetOsH;YQ6?Cd`G)fom*dz2tWojP`U29-E3O~ zF>95kUB}oQh4*W_UxcG%dt+-j?O*9}fw__?XG(KiFd}rG(V1r_igXif!!Q4VXhy+^ zr4W~O1xJoWn%W&Y{LW-xacL$r<6tns$AM`>7VX5)z^PA&k53RcnQl1k<Xhf+G0rP* zvKjP(UDF8HjyoHZL>sCp4+I}=!_UD>N)38IXT>u7q5ef8NgggICm*46@`J5IS^&UM zk?i;rFA-F6Av&e)MJ?7CdEkwa(YRccKq4>MaAbf*xIIi|$TMv0^+6!HqM4=qv0rbs zi}Cm=->pW~w49`q113*6TBNFunr{h<W2UZ__DH2xdjSFH)sj3b`fEVxQ{v_(&=rIk z4yYk*SUQEa=dlAyGMoi2=xkEiKOJ74c+W)%0J&Hn+0t9>a5i{(if=w~Mg?7`KlVwt z7TGh15+LR3a8s5xz%RPY2!$45joJ_QrtJMwm(3TPsj(ZEGt}a{ZfV$f>Gs@~&I**# zaX`rkz4gptLxc6`H^A!V+~2E%lIz*#B&OHpl}3I++d;54*7rIxbF>S84dDXvi4Gzd z#HwmHF8NEXj?Ix!+K~ULK`lHMb~C<^Y0~8*kZnYAkZ?07#q?Whk|3)j8m7#s2FuT~ z2q{ul+49~r+T=&t{wIWZD*cF6bJ;3%Gt4#f{LGok3X8TZL}9{eJX51kc%?SUKO^7V z=cBy$!`r^`Av}!-;5-DI^^~Y54zU+sA&w&{EhI9YBm~Zm$1!7kHAalyd=BY+H+8Hz zqFy7&lxY5Z?RG+4D}2Bt$s>_Qjizc`MW<S|(0iEC?wh48({d|PIJ<wdzcBExnDF+j z@C?QFmBRWiW5{9yYZfJqmzyd9qu!|I3<`b`1~l&ZXzJlGh07=|<=dD$VLkhkr1Kh| zUcHIn$q~2}%z1*<Y&c#t=^XWK`M1m7LA32xh}W>isPBvz8q%JCr3fz%C|HNdaYJuM z{*92|O<KjGHD9fw^M!hmH~p|G!EoN;OZNCA&*8sLS098C^_IZ0+|<xjx|etjdE-aD z{^}c}uphZxDQm?Hqh+4{aHGD5rhz3dkEXV_t-_*$tyvRf8fqf%POCBrqYE{N8Q2DF z2nwIB&DKH->0o`~0t?l~l_wD!4$hK>Jg9^m7k-R)OtE8pK-##qP`y@3A*gc2L<XBn z)h_~N&wU-j0D3R;g3D7Xy?M8vy@U`<;w3*qt=h=zjHFrMnR_Q7rHZSi*qcS>*+=YR z@Ad`UHo*b5VjC83JM<jK?_`R^PM;Sz6@*|SlnsGoE;VIQI3Ym~0P53s*t)AR68^cg z9#E6(rI7KwYm;AZF)@?E5XF2TI+K=wnASm|fh>@%?Qip31HL_c_sCCrF|{<s(-Mk@ zJCcm(^ULc8`*8>gp{ypHh?B&pw#(Y)3ajm}$Fx_ea(holE+A~*hiIStYA`8JR-ai+ zr8GJ@a1mTlLP-q@%j`NAIeFqk&%&khoDm&(>H)jm>8yq^sZ)tv0h|esQO>1RlF{D` zdHE-N3W>u3KTLD#gBfvPay4Q2Co@Aw#nwzzW+y*;bYEIVW9ENon6?)n6`jks*BX}8 zgmiGBu|bO|P+PVVTT(SUH4Bq*m$rDF;Vqc=ft0DzpD`uGS;U{_XD4#QR}LkCX>?`E zW(2HxS<gO}rQYZCT6dz+OHEfoE7)h3iTq*42b?3=rBbA+eDSDWJlJn&-`i^u=QGau zcn~ww6GOfA)FQk`3as}Sj|4$_xn(_$jGNxB<MAr$Av+j*#7;MMNd`l%*Gc<$+QS!E z+c*0U*(ygVVvLAfFJ40321-$$tJfuM-eRGUWFnh|5@&;fQBF>_MxIQ5+edX`+rta~ zF0?=<2n}b0%q^zmDe$xvNA7KFHxN$1=|+P3=9A77R+E+x;_J9%@E#_T#u%1fqQ)YD z&i2=Yq;Hg2g`|rdx|oq9#oLuhSO3WTf&6=-Px;h{KYu!jClrD>z4)=%brzqTkYqj{ zg*Z@?Te_81y{zrazdUDABVZnro#<_pPrb)&WK`612PU`W5SC4?7^2C~zNmy9{Gb$? z&$^BA>`TK=X`8g!K=$JlwQb~yb5qVUf9J@0!bXxX(?IRl#uC?uaNhXDhxEqW=NiC4 zJQF~;;J=B;s$ZEho`VA8g0r#fgd`&Gy>Wo+O`1>PWdbQx64kaobbB>ziPLLDkFZrM zjIu_%bf3$h>{NEj>=oa^bi@C?u(TU)G>AW33IP87sTeWA3+{iJhLPLTSa@Q>t3EEF zyD(l<n>&m*Q;CL?uca`_9C8;ldqzOh&i9<>3Ucxh3$Z*!Jcu2&9Kq0ZvDYZcdu8RE zs~wKH&i4N66-mQc#~l;!guh338~gf<@W7<+v(EOI88S-gAlb%@l!j1Bu?wXkk}_sK z#1jCzcPrKD<6{Bj*(|pYT`|nbZ^Abfh0VB<aVmv=#QaSCL*ys-*m(HFBL-I})ZodQ zH$PiTV|@oI_QDC(%;Sirn!o!)E<#r}SzM5YL$j71Xx6np2H@Y@e*C_OMIbke`6_Bv z)%L!ZNYuA9V`NgRP@=bK^5<y(738+G3#9vWwp%4S$(smI@^k(5T&Y%zh{t;eV8F`J z07i5vVoV2l%yPBGE2)=nkM^l5{bqLT*`u4PScaZLT7IUS>#=pmm~kcAkV&hML~=}Q z_BL_8KhuH6?$kK<3$nwP5+(|<*NUg9I24nqcY>-7&+$PR6oi?ECc1LBMOzq%Tud1d zS+@PWNqAa)fA_f4FZ1yGjlpbTlI3K6h_$ZZWn^UZ3?SyG`kKt-ARr+DpDU6XdR(*C z5eiun3Nk-zTgjFnu8k&oH54o#xkbx<4|1<^MP6EWByL=-DoFNA|A_7f-Ue(36$qW? z1zv<{NVq+rkND0doiNWzG_i#QA=G?X#7;3ybdyPn$f(k97&*0izx<c=>>FsYDU&v2 z#J5skv#P}cb$g@hQ*EjG?2hlcQcM0L!A4eticaaaU+G)BDF;=UxmJxmN?}T*GR9R# zsxU5@#a2<zCBcY(#H5S2a#F{#42U@|mtVSv7O5XIG)v2;y=sMT_Gsm$3I|AY7*|T5 zXok||KM*Uyi03`xl%1IMat~|x_|hqBzHR}I+6x767v3nj(CN5*G%``ca_x41;x*nz z2f}YwF24GAVF&Tj{crF`=O<CLLNlpZF^c1R;5GbM{FZ{f0&M$8_FjW0`PMd06}kr} zRM`Yop3#pQpacXCTR|!r^RBwSxL;>1Kh9U`Y=`lJ{{RFeQUEDBGPPz1fI0jZKq-L^ z=yd=^M;E{v?Q+%eRK4M}rq}KBec5@-v!+$$n0Jlc@l-LxWjB=dth{czT#dm4ARZvB zzt&(LoUG%u;sZTgM^e}I#S#Cmn9OcZ-sz?oa5MbyHRzl@(dVD{hS$JNlyhlM-@9ij z`%DAyKf3n9xNIh2CZw!!Irh#1H^?Z}>@d|mncL&ST2IfXMM+16?+2@;$nz$;x9ca> zT4(1<{5MJ?nv#x!KKyVvnpJPA8#I!?UGH2!CG5CGR0>AwEgqDVe3j^x%elq%jN8jn z_^aX^fVDuVY*#cKFX~^%0kGpI1qrjh3bv>OjFk=EhPxFv5Hkj#tl`gzj<fn?!_th# z@Hx!E_r+LE;;_5x*A<k!_qDG-*hK<&rd}C!XI{rnU!D*wqdS!L<Vhac(QA{QP#x49 zKyMGL$Tx^)wrqK6e;_|fZ8_Q8-`yuLS#5Bw+HZsj8r&}$l1;UTA~AyPC)vQ;E*dd} zBT#+I%PFC7xG{?|?84x;+AdqoD*{TYtKm4#tAV4qUrp8ll=a4On%de?02mDp0JMl- zD4DvO3ICy8RBp#(YGst0R;ZBCBdsWG^OEzVKW4eMdy6+jQqd`D!xgIq%J$FycKPcD zz5|ZCn?M#YV<Y%zeW{Qhv!|(_SO=1>>~JP4ry2!{^98Q6<qBP^OvxWOEHT%3Jbxr^ zVY?4sFDKTsw-n9iszyiMRz>p5G-D{i^5;o)E!{`PgmEP^MYDQ(0iP#8$-)M}6uu46 z!tf0#AC4IhEr|Wt_J^hQdUpXdtGQ9R+!&+S4pHClvcCiYB<m_;C9igy?XJsqV^p>W zi7NWn+dWPKu1N_A+tUKDfsfBpQUxXT3r(+V-i^#4yX(23hobkR#TO~R6q`_}^Pf)h zE{~Wclk=oG1~?+mSM9EE{_hU|T7Z8x?7QmcLsIMQEE8v&R`MfSn5Dr<1m@fEinPX6 z|A|ty-6X8bXFh^lS208?p%*A2Bi2+0Y9>t^x=sfRBrL4!4*{K4(3QwM&8kr_wXCT2 z)&`m`8ABY;dpS*~6(eE8r*(T7f?B^rfPTRsKwRhMFx?vcI~G7F!c=WZ$WTZ%nOe*2 zuwUJr!|7ZVa5&hF#LAPo#8PR7>YJo2R4B0zhL6$j5G6Iq!D43X4P{a9YV96VE*_l5 z=-B96;5(F3L97S`JaOqV0J+_NZRlS&2*{ig;I9Rp2#&cdw=>i3sd|Je>*<rw$awT> z<+IGA8&$QriPxRLZ?{~59e)+5ig}t3#ZL|}Z%p+|Ephn@OmbrfKc4b`f$8_F>-GMQ zT)JMB+iz%8?7stu64Bwm0f02=!pi&fEG$ct$uv4vFzEn%7byHnUKIPOGgIyC;il)) z1|U*DvxL52TGBLFT>;nxRj!1t(Fa1OijCS;=m!FCn6!sK{vj@|K*`Q+keTex{RObo z<*Hrj3t896|NEZ8{@#=Ol=#@7cub&)hDGLRaAxBVxYUNoUW!~XEe$f`&R4KP7;K;W zSr2z(SE8pFOB+Nl^L6y4&o<cI)OEWx&bO8dE9IGC;xRRacwqdu`#G6B^QFqeW3e-1 zBYaMPWCW&dKfExzk$SmfRaa505*mK#6xUM*{Bk0NN?OT{f((}tOs<1Wc1TIgk|F_4 z6FE??g!EhH%e5a)lEJj;RL+x6*76~Q8-?-KYU{BQ&aKM-+J<^4U>g{6O<}*m@TM!p zn#e)RAWZqs8*_mM=8ShMIz3}sY>?^Ex{C1;Am^OA*<@gaIyTf%dzkEv*xhCuf$W~J zk#vyZbG6JUQ(NTl<HYC{K?(;t+#dMv4ku>v#SknS7L=C(vz@qi+r0MV2zv{m7Jt;B zhfV)jCZg3eKB(0i{-AC>#{a9B5W{w}7tIp|&=u-SEB&1?8N4Ne%O_<)TF&K4(0mkE zRHG{of9ZPlOAw<BvH>p|_J3_=0{CxU<?H3dQ8d!O3=m8mLlFP{6>{@Y$+tUXI*jW- zQee#7I`p0OappTj!BI?$u$V1Hiu_v%5w7>}Zn-|kq3S4VE%S~s=F+-2fjdCEr)u|H zEI^UCm#Lx9oS^o5M9(6JZ=;e3D7?BWMd!93WK3386pr`%%;GfI)XUx#LANW!>G2p_ zYOG&4>}mA43-e{V4N=VGLQU4dC$|rG;6Fu#|NIQz3chZHl}G>s6u7uK`61by0X?$W zA#bp3Xc&Ka$}QF==NC|YIVo7O6n>QzmxK2)9piB=Me;~kv9L)*DO1y=g&JYwssMdt zN+J(ZE`IH;`uj;ycA5ck?6OY+7`ignlAs|lgpm5!=%@wH>PS4v-Z;Y)qh;AGJQ^}t z(p~YAjyD!Sm?F}0D(`n<6>L|uPdZ{qo}nwzD<(Hc$K+KM@Z`z)V>L<R<lNHL(VoKp zXOjPAu$Ub|IAb@4-DNrF7F*&7iAA3U4F&9=gzQqb=~Yi9>8$TvBwH`Z8ADO-ynrBG zt+&#_b2mae;G|=TliKD+trKEZxyQ`8ixJ+2ePblU0i|^Lzi78*fdBXk*9;R3wTVJ! z`Z<K{e(qfnizKF$=Kb}yWgM1~oE(fqp{$xkPKG<+yy;3})$yP_p3Q>;KoZyg=8Q$+ z@51>Nikf()N0}`baVG7K8r|W}^b2}jke6^U6h>O}`9JpdKjsM&;9{Hzu8icQ0)57b zwcy)Cz1BWdiGF%zM5D-be4Btg!sAf)O;ntAJoN%ved>f#)2JtkRf3rxWEVCUWR{LM zke4J7QPH#wj9u~mIMZRhsGp0dXNUenkTY8x7GdUTezn<Q`}uOT7sYW|?SQ1&q#-No z18BUX_h{9dz;{0HLY{YheKzu3{2<BjIX}0cRIUD|)#}jW3yvKE5Jl2Mia#g?dx>wr zkHP&^zkcV<R;h8|qqh2ZTH#H@^sRxVVC#W@NV{n8JF@<-dzvTzdrQl03djTdBzBvI zhRVhRP(Rp3ca?LIi!NMy6ZPJYVrQP;dxmBRZxPS~Ax(TS2d9R+OY(;B$~+|$1zWU} z&<f~jj404COC`5kF{*}walArqZ|(963UUCdW`L?Z14G>?yn?MQ9X5c(fPspdlCu68 z5G4@Q&JLcc!EZ!iaqJ!d07dI9_H>5BaExa2!w{92!lu@0vFfH?LJ<X_4^dg=1YTbf z8<R3OwRZPxr`Y#x4;~Jj<=g}<DAsoL{9On*{|N~GeSPV`fC$LyyhHL9{}+Y1{taT2 z_+sozj1{foAcYuIUdr785U0lu0_$E37M*=>ho~AG4jEzl7=G&U%{ndPc{>(Anc6t5 zsd{-s$*4|%^3e#cltp!=k{lCL9aCu0uD^R2Y}SumKTaf?TMB(lIMsm@uNY#|HJqg= z-VCoSuTKj)ut)cw(e3WQy${dn+t$4H7<z6D+FBZ2j~VY+|HLl;UMj#?bp!P10LIq! z3vC23&~aU9Jdg?b4e=&FDk<0{;;kl#0-howcS=t{t_a^RJt#Z)>FO$c*ETP9gs~tL z;!v1j<|$qbf@!-~oVyGuk)B1F7(a<gtdt;yT;iY^4o(rvk%#rv%BG?jH+$huk$nSp zw)~`X_PN>^WcU8i(YERPFhBF9=aqPW3zkB_W!Migs;IHz^n<Kk?*Do(E+EXn|NLu? zmN4;C!JIUeR`Y@Q@WDO@5X5lZTXP=$WiEs232rKzlguFiWD94z0+NO|JfZmlr;V|K zS{nU<cvjuo*RC>sftXA0*A6OE=_rS!yAf4hAfpF<W`uo$^Mjw(&8NF3e)r@&kMu9m zF7#MzZTCx?J3`C&gswlROPFu8r%W;fTGscro(d0b)5KDZ4A-yaF;ioJ9Q!}^^KWce zE%&#GA-qE6-7Y_9@Qf5!nDn(v)IDAH75OrUvX=#)j2EZm<A-CsvvN1dm*;0>@+(ST zjx<7`vI{NJJ#+l`EPPQst{R3)3~NCQl<h+)fqW9%*)H2T&Q%OgrhKcjSu2~ptdt>> zK#z>*9CUZWjs4B@g!Q%`M)bg>NQ0bN(VwS}yCS(K*njF4|F$RB5Ef~GN<f?GqlQvN z%L(+9KuF9LA^$26Nkp6wou=)+?z!vsC98Wk-#(vF$kEYGTQE+KH4TqHqt#w*F}|;I z@IyC`6;_0aKc<=PNYH)z!Jz%2!lb}Y0yE0&3i74wa%&JE{4>VAMcCI}k$9-v^M`Xw zgX@WWHq_fgBVJ~yo&w*7kH7_MGOtcOPv_97ssDL!x_Lr>T~DL=r^$f+x|p*2K-~E1 zt6Ex$vhdBvvMcKB7pSJ)9oljMc!RS8V!$naMC<*p1aJ25Y?A3ij&&4s^fsRXurVg< z-)3aZ?0!&7shg^2#E7i3swIRZz+#|&pBo}(DyJtYG;Snjq7vI4#TJNJAVdHT(jqlC zNKWdYp+Eaudcw}`_@6GZTR8CVA5n6CPaPf3rpx?@aS-=JDQr}t(Ak@B-gG{o9skgW zm*%X(c;u*q{I%{$qNprhBn#?tkiR!`o!r7mEUin#<nEs3@SR=L89Ih<LOVi`ToZ;m zQ;1O#oL`&B9M$@`ik!+~_@%gVKdVNM-C>q}#mGL)=B`9W_xMZ&zanrvy6^lqymk|F z5|>W=qt$Wg>-#^&lE2UG->=V`;&1L%aa|SNi#3z;rLHg&C~DZyMA{S#8n%n-u-SFJ z){dXyeHXf1qXFq-$UJ`GrVl!Ha||z%voRYenkQz<rsPo(#f`?XZpRg)mb@QIon@#e z`3ni(^j5Er;1Bhjq2MsH#;lX@YF0=-b5ht-c6L||U{tp!k47J-R;E}Ac7!2${($p| za<ThP=f6Us^dErLErvxQr%Evg7#G^ILGAX6vtdUe4P4J(7~DLFZ0W6CtnS?6b-+~$ z1c}!o(ohbDIg{*Oq`&3xxuS`qr8h3Xu<CZ}8d`QyIeHS-8P@HD0K(moDZvfV_$#<r znf?;JBUe8KsG4;}O~+Z_<x&NWdu+Riid3ee+1+YM^9}?O0NvDmvO_#g|9=kcpH*&O zi2z<+R~PK(7E=t2asmlCy#$rEpT^DbT}9)>Oznz`DUeQddT<d~7r&MzVsMr#ZWO0G zipK9y7q*{A9}y_gTt6+zAyedlBn<E{U9R#>7CvOjom;FH5%RyBaXzfTR-ux(h=aA> zjf;d#S1UaA4N{&i?4UZIl`__@M9*C`DFpE~+cZbi!c0;anW;b8Of3r%o_hZ0DglOt z4R<@#g6h~v4%aioSej&kPF<)37jnUf;m&q%<!R<b0ZiRu1A>Lyi#b=#BkZuRrd<=j z>_S)EWCAmrx<;Q?cIlz5W8t|&1Yu-iONDhLY;dnHS*ILVE+`lv(K2@i$JE`bqm(qN zkW(6zdE6W9h|gP|ABkj=<^$(6Xlcsze!3lfeTk91m$g*IyP;e%-)ujm8mHVtJx=hN zWNr}sz>fFG@?Q_r4EFEEXLV{yNbJuf<;V9kYNH7gElp6XRbxhPe3B;t=<DKzC#Em< zJ!_n!VfOhbYWC}Bt|ysP{_v^cCAQ)1FPTReWP4$+V671(<zgAP%$3Iy*OL7rnOO;W zMwxPyrR7G_R1{jK`f7jy$yaLP4J!5YMKCOX=}Opr&4MLp^FjveaHZpi-!LHGYo+dR zxOy!9-W3J(PW9j3keBLj@T)!>Yi=GSTE5s9bWAJS%58e1|3e!^$i#{hd<qsVbadCj zkR@t+I^KD}m*m24H;_kf|A$DPoGJD(D~fB0V~xa?`Ao^uh+=nP`ry)i(7s$f|EG1h z@(qP2kUkRTlCl_%Onb3XqOfvQI%0hhO<tjQ^*7i@cVKs%I%w&(lJvd=&)&porfnu= zjmW049&h*mS9SQ;S2v^jd!nnA(CEYyS*%e8@$!XfLCW{>hl4k{Al#mN9Fkt%013j5 zZ_wz!^Uk8MW*p0mRj()So=s=XO^{3a#Sd#9$d2@a$Ebx^Ne~V+vs00a)N01nPvFG+ zmGMlm%#V-{#LD}2ox4KwhPxCi`YEMJWOiK0H!*LSh&ykItT4R5>{dsP(?eZ&^aPoY zmHrmmw6p)8CHm)6{ZR(AL@X*!Cz%)ldHq~Q9C<A8fXPovOY9L?9=o4Lf=wA``Y6ad z6-UH7;WavVidkV%RCU$vYjB5AZ5YsE#^EpXwf7d7565{X?d~evlMQvF0xy6jiA-}f z!ygq+_=$xcZqDawWe_N#CTc+ZIGd{?Y^zaKbka|Oz{0r%nIlQ3iciiP-;?QvkFmWI z{oe)&9B_(O$RFnp)w$yE@`Q6~?5`t^)%aP2BDHwRe=ck<-+#5=FAI9y?WmYYUNvjz zf}S4A2>T!NE7Ha%ny#?!94y7QDru<q8ZY0ink$#tA_<xaRXY?!Pnz4%Xuni5gJ9k) zvB)-Z`i@1nVsTAzfPrUra2d>th(#oJ^Z(lTc8t4<^IxBZ6Q}_dkT9Ct9;we^UhVuJ zvfhC`(sgUwok_>G)3I$Q9ox2Tr(>HHyJOq7ZQHiB)AL>H{r0!_QGcN7splT|z;&IY zgh(_up)g2#li45hh^KNSGR`;nBrZjBhET?F$G_kp<!fNd?e2yRF{=(EN}^L>>^Mej zhNpF6VpAXf8<+GE%4%-)&9#KfYp(^Sm`R}AJ$+fg`|^XN@~SV9Aw=uRUoz3#pEI;y zy5{}GV=?>X!NREcM)A!{u9iLdzjGQn&F^BQvGIPNb2Z0WOX`d=*rKpo+)+>G2HcnZ zDT^dvLHSlTKk2QLSOKB(Pt#s42x-g<kS)(UXBzDb*2Lc2G;sq;Pz^gJ*JWs5wkKMg z2rR;Gt9r}4c2IkzLrt`V&1Dlr7mmGoHnI6Qvavi&>ouxTzL5Pu{LtEdz(py__Py@= z!VlbEd;j16u>tSz1N)5^v3a})6XIMLYs5cj7eD#O4C~zHM#Iu9u|FkoaptzA7US@% z8ij7-g|b(XS0G|pDh=z1K)|8BUEcEk*az?Qd<Hbf=@8jPL)+XBStPc>8lFk%1_(%T z1<D0isI^$*#oBslb!i{UK!-}=aG9Vo1XghkYl-*=83G}3!|yx8=G*5tyLol+oS_2k z)L@KCNYV$`0OPCfddsha|NB{PBNk75Ct{lE9<DqMG;!N#yo3$&>!hQ;sd!U^>8|TB z89`fl!bXU*eI#l^pqFSvnUOrU?T|a?tp;Yl65O}lV0Oe(G(;+Mq>&ip4?)7pPi&+E z(urNqN;<KPS*@z@mCB^+ESCC3g%S!kR-HuO9>XIfFnR5lU7w%!u6EMEr+U!Z<kx6Q zDc@n}Tu+b7$gLWJz4ENusuKQR>BPUsMURK*JC$_@t7kPKD<#&k7**CGE)JT|mGfPy z^Z{#$AIudz^)wQKijx&kS*b*h_PJ)ruix_j%xf-<KQlL8%)nnMg(9|{WI%zWB?^#T z_*iuV5LZUK)cUm^hEQ6jfYTTt?b?Whv5Qmii0N+J5hNU{Zud030;>~u4SF|_Rg0C; zE6c#RXZ>?3!T$Q+Oy_@3^76kWvg7f=mnpWPNH5@LOhb|)vjh$`p4;Uidd>00j9FYt zkcv5#JPw`c&!*#(o9FoAwlN#A{6Z2)w2|cHYB6*^LIZnOh4|f1KFd}HJ{fQsaU=_@ z6E_kDVp6A5r>llOxopeGsg}}^Um`tK#>Y!{v{ns@;94y8=(`jk>5qemL=}v(F8of5 z-??kcl-I`pry^uU`5R`)jVz@*31#N99XztC$Mp&@6Bg-pfPPcR^b<Y5Hk`OwZg)*L zZfi0}ehO6$9x$^+=Uw=T8fNpm5-3zf$5nwe)J>KrZG)T&*3@E+u4?>P^I_>XR}8@Q zv_6BmS^h5zfKLtS&FweD$CL+D*LypLY;*@=P9%c&`xG6<>=WvJ$CH%PdK+RBJ0+2g zxtNkd0Pcd2Z(eQmFef!C@~>B2;Wvo?|BWd4_eNaIIqTxc6?<RyJJS;96t*U6Rrv-u z$j1ejAo~n<z47>i4Jgi#GviJuQX(3r&GW$b^8UEWSKY%wVzeF;6qR#NN)w%vzg>q= zuQ1gotaUgh-qfi`TTI*Y`EaEE?Bnsk!}-lKn=X32b4}rPcJifnT?~yly8i>D*31|N z(>WKS2!X~RS;?f$o8Zsu9y1W~+yA}_eyah#I+*t}mi`yr_+7aCksPH?k~Rq<Jq3<O z|BgS4H~yZrwl~*~`bkJc(H?&o>AF(rOFk+l!&KO>>m6IS*Fp3dZd=;Ma4FIHchfX@ zRXuYFR+pA%Bq!c07~<Kw=h!vVMTdkCBgASAStCfKl_H`)xz~tf!Bj|YN4nX24@Fyj z6EV7xg_^A0u%>W5mD(=7VXAn(YUVhG*>6aFx?Z?PI<7d6Ja%lA1tbo$Hqgw@(YOZO z!^R2!r(syk1JUe?@RYV4YBhoJ^!cY`Jxzb1EY0=3<@-#^rT>k-tPh7^7Lw9&J$NvZ zhy;$JsOsXdh6x@MvqXq!AF&~Aw7-!u6-H;ucRd1=yuvvXn4qcrHf&F09?5V-Y4V1t zo8k%Z=4xewCPa@zJI5B3=gsr?AjhBWfG)cpIka5XPKK>gg1IW)V7~nsKO9!`cRSEK z2QA^Hg#zHzoA-huP9W2EIgtcOa4m)VN|c2f2g7zwy8icdm-9fF<_ZzGz9f*vE(1gF zQ%h&q^xULW5$@6b*7MN)t=`*T-@axvAi;TQf%u)v7bnuh=^y;pX@cKNBbQ2;nc(zy z>a}2+kJam^X!|Z74h?Uf^5T#ob9_l_FP^TVtt&fzVp^}o#fBk7%u|pZN=6sqnxQB~ z3cz-r6S5B2?j%{oz?2sBlEOArxDpcA{^m>GNsGT4P*2YA9gs}g*}GA+n+n}jqc;Qv zi=DTb=_IM_{DKiWC0iPXvQJY?1#?MkXA`#b%>3UwxtbP)_?Q`zn*WsdkrUuaj8G+` zS>`l5OKLh2Z~p!_JulAu`*Lx;J<wSvf`mh8{3@^aG@hv!fN4FqpBDwH?08a$Y(IyX zpV0JWW}H7c(9d8$M`gZfW$HCAVdgvB`_3C~$uN;t=@O|IVeFiJ;!z~vFf9SBGb}IZ z%v6Uo8sKwbXngY~Tk~h~=k<c7Qf^O*R!t9$$IA_vB0O)1kL*Ss84F(sm2{Q+-tG7I z`vLzO!C9$5h$VmgrtGl%rHu=5St^266}M6DjoVq1&h|GXZGLolYv2u|Lt+7@Mn@eu z1H$!2>J9F%K2R9zh?@6CzW2=9x8<nMI2g(0y%~x_K6adnIC0()`Wh|bVA$uaO3di5 zVuw(KuA`M8sZ;71W^2Q$HJ6#<D+J_a7>X|shQ-VoJ2L&OQF9MSLVK&h9{koQ+{q=R z$GFg>=}+21$1aeg{s_sA5R&1z5x=9-Tbim`_>ahn8#o;Y7*Ggx8TIFtI@FaxX7+Ub zugXTx@z-}Wn#f6JbHcV(RG+P<55xT7%1v^S&t_;t!}P%?>~_3rS|U9@pgpA%AxwnV zXDSQN{{ygS;LvpljvF-T^@d+(t;xwC!B4_c<3Mbj8?GK~W#TNzrsuU!M@Z$DM!e3+ z(q?ufueQ}{3YWIbDgOx4u)G7(P@X6s`Fj^R(#su+5$VCL1*xKqRUrG52hqBFU|`*m zZ19|DCMt8hF6{p_uC`_IW9jj5E_>vvC&^P|I!u;ZAXVdYR|hN879CXo(XbIml2jPo z9r^pi{yctPvsM>Zd$8*Qkf@a_QqwoF{>;(hx0ni^)S#%)hRvt<Z*rJr{eO~Q@r`$^ zVE9_NG|Z?lKWRdR?Yq0%W)80}#q#qVBQWI!PD~PU>6{wlph-lPl%-XaVnMQvI`)i? zI9UuX_p7Z*%1G*Jc0mfg>G5K=7_rpDT8q0#?E0uoky<eb`xT>e60*_9L8kwHtG@|- z@dHHYJSU?h=I|Z+5`Iv9e<;XOm@<^G1`7uv6$d7NWTAGNObnyn(~j<$4`HX@PoVD$ zL;Xwe*@tL5(wIVz8P&q7BG^TNv^Rk|3;;rV><!<0kl6f@8Zq;SAB4_%3!H;w>|}vG zP`4%cJ~RiO(6s6U@eqwC2c<H)z*L7LAY9Q-*w~{T5!`+bpPgWgmFz~3=@)3deta>p z#sOpkYJ%ZPhC<};haaAI3-A!h`9yWOyb8^5kG(+OZH-Q6U!04m<iG?B5mp-r|HHSu z|2-a`D8OYF#uTE$W-ktL^nR47Vii=NhM{f5fgCf~v(Uky=7#ZD>QMT&UH3)XPw?L% zjN@+z+i$hnE2}25M<P%7$&!k`G!nj?B;S^%fGJ=l48fND!mdI)HPAzL6<|2E0<C!2 z205qe4YopDHqW;kQp;ZXxy_W{Xb#KCQOIGPF(iSsl0WFWXW3aM|4RwhAFB5cUn-Jh z24gLb8e<d4k1Fqfge6C<VC~t{!pB=zj=hc83d8r3Il2r+@70I3<6<~d6OX^{m5bMc zF-D2%Lp_a%hV%?Cuyy|`0{)eT_9NJ(sVQ^zyZWjbQ{3K4UZ3?Agch3qVc9~QRZx`b zO-o2TU+8a{z03IW{M*9(pC&5|=S!8jL6o%<u{a=*6|wZsuP_3g41qfRG?2JyIPNp` zch)9|L=H)Y`+;<Xw@=CMJ{%6SG|C#x*?D9u`&$%4D66%wZHE?98$~gpun~o{ux>$G zwBj9Bp}3v@>XP|aYQzv2Z^-RIsu=76eulcg<rNq1L{mkK7@BDciIXv>@Mw%0rHQOY zB=}q8FZMFvr|9ztGeIcR!>NMW|8v0pED|D^83}5r2-=s*s@v0gXFS4Y`Fx^AdY<tx zTX&Gia2;{uxD5N5Z8r0M^R?1p;Kn1RF>C=`xbv$v53qL-R`ehi9C4YUxw`^JCPu_S zPJJ1)>>{mtWDAb2;c%4}S*i?79;K%{Mx-oNs$Qj(98Aux7T$L@-%Md(P~$TW%z2Qd zg%(mgyYr#is!ID?hX=ujzJ&vdsD+Z(LaK<RB-hxmQ)TTK{KiwW1^eH}45qr}4;326 z679;t8%fDJ7OE`D8d$wYL?(L$MVkd9)|had-stCDUQAN$I|BHwth44a?f#pdO}r1> z=d)LwfsC`3vFuc_2hFRkV4z1M8ZD<v{OOU-vgMy{c6ac20WkjH{<WA@kF#v?!)LZk zP&b2;S9-5(j&kxSqGKwsc5*R3e<Yux#q!jhxrGZA5KsTSw2NChs9lsv&f---7*6^m z8EiL9>9<u{+YNN^5CqjH?uXa(mihEq3K10l;rmZJx!YY7KNgh5=$BkDaxhLkOJ7L? z3uD-U119MLc~uPdO#Bq-&;x!Ee)_6+z3UIl{0vr(x<a8}zswo6<aNSzy|Y4^M4|?% zs@j8t#_nbcwW&~!j`U{$iO01|yzFP^j@3_D+VXT<u=1mFebrE#|5%4uePd@;!@^xZ z^krM&YS&n5sxFg_vdQL@i^K=1_*f+*bG5!WpQ0}>q7Rm@dLO(WYzZj3%4&;gD>!|8 z{z^;BVf|L6jmW&k6ce<Jj1|hzCxtM@!CvA(HOc`(^3bG3HQ!y3f`<@74J}v1BE?)Y zb_*Tn00QB6$vn-_$4Yq%w7yy9!4hL7PjV4a5fr8N=_CdytUvKF_?h+$Etv&ND`x(1 zu>us^0C`O|3em38_=SjZ;@&gnMUqJ;$U?`JAh|+g{Px&G86B_0uB<Qzuab3w5{I;& zc`QWKf*5L#0!%4=P7XalU7(XYzuoWFcL>PQRFSMer7eiHA*!T_#%ctOOEvo50Vb0O zDDM;U7pvw_c?KVzY{H71Qw)IWCJI%Z06s(5<=9EwVtcUIqk^O#7o7(Zv?=x81=KyK zg|3rTR*>qeZuo1z8wJnnVACe1R|t=<nHLm@e?fUU=*X*Zs2AbjaQ<Q=X-gS1vzGgU z>P6$5#UDy!kStA)^HmMorj1n`k5Q5)(*%HVZB!UW2h-fXsu#g+nx4ncwvVlp&lS)9 zv1bpls(#ux*WMGa7$FTfKk>_+x>hz3)H8`hwB(l|?X0^_^+=!&Ji)2EnC_e-mj+JC z2sNQq+s~x(+4o&r6&~F@(+ZN${|;3a`GB!(Q8VWA^kNa{ZwdABzndxhLHl~4Nvr^4 zKnSrp&IX6OWH3Gd?318EASu~$VlpH)Ro<d^O{##rEsn-fsVkTtS`mq2c`fi5+E;K4 zX>^|?9qdp{*S^8jj~M=`_~?Pk%(XnH6Hh5O4;Yd58(Ndkq?ix5i)cj;+z{=?EwEH` z^KnTGB##mE-7JL3K&9J-#tucc8oGTPiCZn&+~ym+xigI?B|4A(R(X2@&Ac*nhKH!x z8{Dv>+=5p{h?1+7BsVo{#IS|HP8)I`-m<NrQT?yhiUZt4723zUosETyT<yu$9HkKi zAr)Z|w)YvL>K6jJvas_vWL|!Ke%jeOLGlu@0ev2wq1xO=VqfML7*&k8s99l~jttOe zJ0tkOk!earj%T~rKPf$zZ$6Q?LamU00>Mb#r=^7nY+5TZqc1v1ik0g4Oa1$IS5ymk zdql&{aMDI@BA^L5^n{DEA_Bv2dX_)rVo39`9D7j{i}6#}u8waql&ydr@R+idH|5dd za5KZ;w=Tl&QGUN4=#AJ{1x7l5^@-%sFOITW&urt!<l9e2?cDDnH{Z-o?lTfHC9ZdZ zJ)f7MHs9Z7%l$;<k>ZD<!lIh`W$~;U>GMX<OjskED5{TSkGSdR5!1h~u6YaCZ%+_p zJo_n2a1!+uF1y8pq&^E)OAXsCEM)j)lZ{^m(6E65LOf%))=@NIIB)%+b34t+QzxYA zkxyOAb0Ew?di%+Qm>4EvRUF6_;#lb{9%H<nI<%T2In=7gTLlrbeovV+rS7L*Lv!+6 z(#hcprE2%3#H%3D<8(Mu(tJ9Ks}71J0K3~Sx2g>pB1B>zZK4DTOcg9n%$C56(ym8O zN5%?BkW~=tflHdzK2z$^kr6tk2n5jKge!EmlI>z0MfN|l@%1$?@d?QP^x>N?EJUo1 zpFEH5aCiFU4%efYs16pPD{5D`BC%a6$S-O;_@sM-<o!v3{uFf_W%mQJw^$#kD7Fxq zI(bo}B)p<6&>7{@_V@pEf4lKSe(g03T12;y(me~;?)vYR4jHJg9OvC|>i3RFbGB6+ z2nA?Wi!bi~cF=>bwAhiaKnq?Co!lv4!<cN(qxT^x^!@<V!T!YRe6|7Oy!wRCSU*EK zZ|`Fr9+hCD4%EnaTcCS=K##=bN(yv=2_HpbzrX&;{`s6Y(`d{j^W8E7cw$uowhkY& zm&<U5ex)W?3gtgcV97m~nh>_<&XX#Zy#id%wFN%PS5;)M&M*f!qNwg1f>aXo-Y+Tu zQ<mt!h&mB-4bmFNAF&7OBK>_jz|@N92Qro-ZS^d(B=OGyqIz|L-=3RuAGHe0=N@pp z$fuGx8cL0@gn0;w(Yc#`rY=2Ud2J->aJ&*0mY?$JOV#oe?%A6Vm<ln4`3gjmw_^T` z_i<WE*WM)H-57J05aak1`?WCVwc2R2?CcWs$_|4Mdm}H;$BGsj1*FCr4w`TIfPZwo z^#zRp+#+Jsee;iK@*Ype5uj?Ffm4ci<O>=Z8?mG94znuTy^d={RC%F&->E<v14@F( z&2yJ`U-&HboXMzhHhE;D$%<hS2HaZJPgFqKL0t|Kld1A{L)<_yJ|<07J|@-Ith$Uv zJ&0-cCW!P|P3ozAlImp7*TK?}{^2f|75E)$90~6YGd>d_r1PkOKhp_GWI_a>e5l-i zy&V5rO}^ZPa`VG!R_%*MgGO}9u&KJ1nN?E0m60zPJX<@mmeHM1#b8hzHM6%ih6Cz& z-S1{qGBJMfB_jNKby<u1ao3eNRNv@`P81I6_`C!Jw=X+yjo*3tqtb8OH$TzhP>%9U zJVd;atL!u<<{`c;L5Fc2GeSBG#DA1TC7&{X$lp;1-2CBf+FEC9&8{aGDbh`!+B@x$ zY7{z5n;(=1K~j!%`XW%U`iy`^zKFsHow#;}*?>rK$4I9<oc)~>7!-@D=(Xe*r1D3w z_v<d(y6cEt{bu3MO0P$17yerBdWcYY!>aQa_kK}~uF3Z$`TDN^HcY>M022~pIdD|3 zVN6w}39({CN^gTaG5=DOxm(j|V>Y_m+oZmC$!P}!xZPg!DVZTlN}#awQ&aEH%g0ZI zsc{@mWd^WqxnY03oJ-bQuE7mu*a5qo&!U>I58(H@A{4k@;Sy$Zllc-xL8H?W=itUX zk$U>xk8`r$rtDQ;@p|OQvyuT=An_L8;)t@8r_+L!F~i3>S1i>jMdFu4jGT47NP#LH z3-a|E@hi%+<T{+@8^$_XVUh(%j-{@I7U$aQUE#|3Y*!px^NijrN4t5d%!06HXnX&i z>9~Vexi3^I+l7AnoSu21pjt#&d0-FL9}k*@CFRw$q@wg%E|>~|#11<j9I$f5^T5O+ z6a>X-O6z?=L50=ESuhGngo7iP8VVK@vJ4X&^#iPgib0i&{~X#0+YlsGQ49PAU2qZy z7sYa^Wvrbpmxp6KGm7JO{6pkNRTjC^G%%*t1k6j_C=}!Q9w9Urmzf%ND2+vs>70~W zEoLdsVEQw;Qg1_Y<Dan)E#?%FTtsFIB|O-(_~Al!rlV0c&|B!cYPTDQge0_?@{}~i z!en!M3wJ0DW=sFp72=qA2}>nv6525|I({2|%pniBrE<*_5NeT}jMT)QR^~#z*vG_$ z{i5n(gs~**JrI6^hL&;<KxRSpB?kwGnUoc?{huASK?g@i=xQelG7tz!c3M~}Q-zgs zI|-~b=870F=acu)B?hQGH*pxMyW8sRqXISFHW<Y%H*h{#cgTu9s%j57Qv(joHUNAw zQv3nt!^}xDa?O-+GVn=>mY^g-K_oGVQC(g)sYV9{GYXNs0;&_iZxkUF25t1OvB-jy zn+=@t%!YsXCZ1tYBXY^9_SYHS==iOWN{pX}5Zes0^BRTc9;4y_GSttSv;A})!ERI) z>HpA&-sjCuID;sYxRnqHsIXaUI>}z?r*Jj+MrYIVi%=bmB%r*{29`lu6#lpMcdbeg zi-H4SgTjeni7K~W6N48uX(Q4X{Y}zg7-{|hhkr%^TGSA4g=9W!M+aSm&nKyH)^&a{ zN1gS&321}K_PnPkoYM5?dE!CHY+4In)B_asC)q_jLuz&ivhRqwi~Y8eOeF7W7&jZJ z6@GpWkfncX0zP-#?pbzTYwS-zo)kz~bWO;DQ!HeoV%nuaHY`Gw-ZY>f=xk#L9uGi4 z0}OdChO3;659(klp+0nkHY4gB&<T|CHl#n6&z?#Y9<-80Rn4t}8@JV~aAkrKsB3Fi zl5mQh#QgM|K>IiAW;d0^#56C?=dctPrw}hP`DDgFdC2}jBpo?-JjxTFO+SJVf{slu zF*YWzpb-s~R$;*tv8Zf@4;#;&Z)y~eqF^k3kphMuRflR!a$m06&7XWmWY&zmv_0gf z{N`_BTsS*UqIM+#Yh%2As-U7H09yeOL6oxt(Nwb2of)SSLY#Pm^P!Y|dy8>LTew2G zkQ6zyY+}+d!`zy!`icTLRay+P-h<GrY)wW1Jk7-8o#n}^{;&@e;t9Brl6DM~^l$PH zESo=_d>|(FotyzytkeIN*f5EiC=!)M-2S<75C%O{h?Ypov4q`XfZIiyG%s0)W?{<o zoJ3StiGLs$guIIxl4$-^ao1z(4_WEFzsE7M<G0Iz4iIE?u9PZhOnXU=tB#Kq71tU| zM%Di|R2qBl!c8*}bZV&k7M80j8P{5MuqPB8>KUs*_hYdNX0qbO4cmm?ze=arQl2gr z6{g}U@iXOtpo=FTBBJv)GP{zD*g}9(-62wuFwl&O*y~3kqoa}!yKcren96j#Vwx@H zBCfhv#i(d93->ja6fd>I-A(+Gz-^58B387zQ9_nF#X;t^f&Mw?h5SXlbu`fcvN+PQ zT<nvI`PO@LgMlVJ)>m=V=^GHU@q<jKjw*ee`Bgu~MFsTiY5OqXqSxoYNeh_Jui6m) z+C;;ux!ILJQYHIF1-n90R1#yw<{44yd~`y0kGM6`Aujg;1i(a)SlnffqDIo5%gKpy z9$n<24Q%BjJdk1|+%nN)r{v>Lq&XD1*eNgJffA>dt-ts`38l_YaYJfXlMq(+ZJ@lu z>1_{FWil=xkra2ZWjoV{Z}QWb^;&v7a2)07)PB2*%jx}mEbPe}oh7c_*l8Fp(LU~f zopoO)d`TKwmDnq9LV2LtLIiZ7nqN9kE$CcjRMyd84^|?nyx|gCDkmB>tSR4o_J4~o z2;|1X&cO>g#)lIiNkhn@BC&o>l>8$Of&OTTKkaMUM=FYBKF1tuuAL9#_7K_+K%|M& z<sl*@sL%rVg8fJ$S^Q^^nNl_&-2^)7XB|Flr~_p;uy`SJwS8gik1{YvY+x34i|M&K zteR&j0XS$kgJ=S)>p5R)GKuz)cb4O}q6CREx0jgTYu8i!s!TnQwX^gi4Hf7)FZH7c z7xHTbu+f%_YN|$}Hy}$-wc4wkgVlsBi{Tn<*HFlfz8CQvv2F>sP96of>mmjVg3d}6 z?4f16v+I<x>uZ>6CE?+b8l4Vl156zVYI=looQz4Pp+^<n{XZTB&OTamR$h+uF7NuT zvl(m&BaB)*r6N;lBiKhvlz7o0(FxP*n-RlXXq$)|IKt;niF8+8pc<eWyZk?rw@o8x z)*Kaba4Iw#1OnV2rc14fn9Y)d&NHO)m&BQBDM>5@{AKLum%+{{<NRfo%O))pXJg_i zC#gOy%Hh|&mY^DpHuwnvvc%cOTQ|&ujD-8oRqHH3x?b1Fm)?7xfz2?Q&n3maLXvs7 z_s6Z0H?IF_;%|S2_=-4V2VI!$HST8_c{t?5W9w7&$j)^Q;eNIMpo>b6v=PmY_5j=R zt<Yqd-<E#qk=GOe?6sr|!8v^JnClPNtm-~`@7ghghq}W9<m#T75xqn;3UC*&B~W+j zod8AeOy~E$I#{7RVdb0F0H?WGvAWWyCX8h8nSY|7BFM=G^2C3qQfJGW{Z8I*Io-Z> zxe|6?0PN(xHn+OFx5;-(8LEr<#SvGa?RbOQv>+&!aHS%aO){nc1hg$Z$4(T9dJp8~ zJF}Y^mAsv|me`HK7J3#mF#eSb&sz|3*#ooG29YpF6+9~W1%#SUGGm!TO!MPmll(?G zAu^n?j*7t|w#wKKV=@)z&BJz=%gYj&ct<JFWW~5sVGJ7$Wy%cZtgC2nlIX`);a!1} zRC=LYt~HWUuJ#0^o&uQ|1}$$_=&J@$BUA7~pyVh0UZ`tTL4tiG^mWOxW%FH2J<WkC zDNG`Ku?8i*3M(efMlTjAjkm5zQ$wa^^CBS+6#&**xyefyQFP_^!_PSg#3YFtZdml0 z^{6TdR;3*XdAo>60>=xf0Nd&@9X*DifTuE@=<#nF+%222B?2^ItZ0E}2;?MYF*DE> z)|H1RfQebpqqX7K6Jnirfh(*|!!*+_O%z8_#;57uIv5Nsmademjf0RdkTfFElCHZ+ z_JAbgz6gr}3s6Czl&%_obSG(umJXzG%K=$Jk3`2;D>D9WGT}=-%yb^kRP;Ub;PLhT zLD#MF#>!7UYVFRf-#Zj(g}m^`#*(UM=s!xF?pJ|dPT~MIj!Q|E>#2NN;}FuMJyc1C zlMc4&r`peyR`Tc{F}%>O@U38Ljis_PzX*jm&_ND}F7iiiokzpB!=&HLE~Hs|8d7U@ zSHU2S;^aqkbH>8#MvU&BrF8KV!jal#t}$h#l0EeS`O5Tl`g5fc&2!~kDv@}Fll=)N zchw)!T!!FjG-OAGsp#KbMKP5%DwM8#2l@jb(AF_cb2aqMxi$%{c$9=01;1q>UYfOY z++SBQktHvae_U?)3spU+p&z-DlP9vHs=8j$VAJYFlC@ohElO_{?C6jwCoA2=$yFd* z8#LxApFV=V$1VbYl8{#*$!SN5AT3$J5ju{^z{L%raO42cKc(_U*@=L02%OUUkV43@ zU7kIr<$*=}^1<Y@EbVeQA}ZwOe_(-Jbf&{5bm^J%3WGl+%<!VhPUH-#(h9Qp74?v- zx%McIsdAi9Ogx7<Nf2w``n#|F!9_q1lQx!`Gayw|e_doEh%R@Z6^IR@wW^=DA`GZu z2aq<1C%^8(Lh82_NufSRN-(;giCC#F{aRk;Nu0b_e%L1oD2vZZT8t%G_JX9!!m^1* zlMIX?oRdpWksDXz$T-Qzyzc+;<%hNr-QVcC)i<e+>6BsI8)+GdoJdlvRs&4st?t{N z%BTO5o_8}=Ulk{=SHQqpo|=KSF<iQZ67+zbQ?87S<8nhXyi$mK3_2FKyuV7KoFid3 z9IQ%5Uca$`r6nzLT=>RwgD&V<A3T&1q8_2ucAg+kLrfs0Q}OZV{@pBsFb6j`WVg9~ zu@;|PqK8Noe&`$zeW!Cq6+eq$4QS$!spLS{x%Tn><G;#nH981(oxMSA*d7rl0D#|s zNh(({g$uk2&I5#P^BqMY%{oT1vI`YG!v(|PICO>sBfnj2R1KGvjIc}w!Tptd*{BwR z(ht=<Q4Vg1Dz@z$UFyr8HFhp7D}rlgq)?35xR%r*Riw6+5`HX9m9TI$!qp&gAcfNy zYB2Hx;bF}xXfNi(Z_xRKes)%&P*K|=$@n&=_df9+Sz(++1XW7}mCzo}Gp9I`J<KIT zlPBL!w-@FWZibPv<HvDSO@?Gwxa8;wcA(doE9g;Oz{5O~Cp!yG=G633$mLCIyB!Iy z+mrPrBLl97>$eZ^vH?0%gX4_94C@T3y+^qtrWyNxCi;HADoAUQNn?l6&<ThH8&j}? zQP!^yCIf6YG&MbANt<<<tS1}`%6?ZkqSyPBF?%3ZM2JJt6g14ULOFIzL@N~n8EI&% z44q`iUISq-yV+QZGl$lN8p&|a(VyQc@a`C8jaZbsK%5>qOxKlxm2H&DcX>2an)=@+ zjGP)*WZjg$^sB@U&(=2|^bprR!I=b5?1Kc~?(hX9Bu6_!0YTAQSRJ*qA$CRML~V7x z!<gR??u#8?>p+5L6xWTnMa-Frw2w_LKlP5q)hU`nVG>F);X%rq#|7n~_6eAQ_IH<n zMi5Pw0^h~HRK>a?BbCO^G8CsKh5ARLv&sV^8<|^e`GJ>^$f}m?^Z->u<9$R;(Y+-f zaD$&@*0M1Zlwxxv+~N0{AB)%JF@LSF-y?dzhme0lw4yrw*j)uX2JFZSnYYb}mBMvR zWqV?|F8hDb`S^Fhar_Lp><H4FY}hZpfRS%75hfIPInHxCXi$eagri+@VOd$Fqd%t! z7DMQBBk1(>fw}DZ;$U9eGh6rU3n~`O#?lxy6iR|OFG+?*@&$~2D|~LbMEJ1hx?U1I zW}<(olv&#YC6lsz>zx+Ni`DcvL9LT9as@}TO(wcS5%cJcS7V&qQl-1_Rz!rTN-$~3 zsdMR~49@E%(eJqrjI1^a3r4(XlwU8)#NBR!j_99~4~9oeLguYFK@MzlYC}KODf^y> zfWWu=_o9FO;QUN5lx}FMXUDUR!U>}5%nT-yVMlDc+DzmXm&$EZ1z(ix3Mp0P&@bHf zCca$%F34FOzsFyMno@+4Rc$_s2#8QpO3FbCQ!IVx`7_j6l>vsaDogxW2m1SzzhQ=L zzCE*N#qCZoy9p-WieuxJ=M=0JQgFPTP%8(7r4-t@gTO8mbCx#goc=eB5WpV<X!&Pi z_BzhY^dfYrlt5ixx8%`D11OBk_%Tx!)b0YNQ;Y-$y4CYa5B)b}kKC8dH#?7PW`G82 z?~3-ym4xG%q_|E+dSbNtt18jt_(*?FD!F*JMnN4*W@|j3ySRSoFN~J*Qrb**<NY+? zAjeBvl4IBRfa3Ic|F^+=$H9NBif|;^BY@~O7C|y&?*4rz&QO7(cd!P_!pb2~AXAJ2 z)W92p!@@nKUfh6fIt%%Dbx{Ual69i7t2nV!6DSISP|Qif08(})<w<$*3^HluOO&=w zsbLpn0mEI;{c*#sn%q=V1A$Ar-GVVOLQ95|y$46QqP-)`o@5d^j|zBAg$=JKzWJv- z<}<d?*S*!ICj)LAw3i+%ja#+a4!s;<EMv;*xsz%8NntnP#*)_;O<Q)@eRww$=(;<& zHfMEuBT%DX)b(2?qE3AGdN?lIK*zO5mFt^ibEkdaHEuoB?K~FjSwC5E;=9tLI3KVL z)~vbopR`^0!FiiLCbg@_;4}%j5&>DrQyO>`lRCBAWH26&x+zVJ!O(Q4Q5Rf|HCwTy zgF)fEr4{`7$U*<mx*l}#0H?EjOC>%*H?oIljCH(UjK|YhA_7RkrBajZlq^>3DL9>u zeZTjnEb~^EAy0lUO9ko+fghSLQ8fRV8U1bN{Ns2uxoi+YQ?1tnoZ)fVk|fK|5A@fL zB$e|bMcQ<=Vo_F6eUPM?_O$!$_g$HN2c1~g6Yf`0NV#ZY)4*{+;oM-FHZfFANr)w^ zG081ZSCa-=hW=-St6{rWk(39C5sJXwU2K|PsmK4f8poF@^@|PGXy-E$Q|Akg^l?Yp z`aB32UcNn(>y7m$SWZ%fT+z25dA$RhaYc0}vXwdnOLLVff+<8Bh+7^qcL7SJxIg!8 zj>NX*w~3Az#LAGoswx+HLD3S9Sma5)`)p{5+e=T=&31|<f_b-;nk^4q-bMGxVp{f7 z&3_bm*IfjEW|RXSEc|9feAf{sQ3(0Ni7AY4L7KLy3bulqbUlB5wV!y;Z`{az6MN8b zT0KPLktD9(7c6=eQ_b!d=Zi;YAFxJ^&I@q^3xJKuzSfnhCj$e2D3~%rH?}eF(2Q&Q z+gEjjg5!BX!ZvQAdR%R$O6o|)WhDl=Xxap1x^6<!q%rHkjcPvMY)DK}am2}~w8PkT zypZbrK6Auzv69Vj(PGP&Yt&?8Xd&vR6z7*LS#}*C`E8=$32Nf?h4~YQ9fB?rBWBdS z!tS)-!)}fRJ<r@d!F5B(B^(8eGW`lu(mOM1=%*({Ro5L2OF7wIf{v%@$#l}w!kz@- z7>!J8nHZvaQo2~ePG1af&)igGzl&Cv$LC8?jt(wuh@nPB*@8z{ug?eJCsl93-PU)H z1op2%)Go%7ewK`n4=)7Q1*7xj5L+sPeWt#D%jb*7rt8CnNQ+1$viqCiU`xz~7NNi0 z?brOY>0#dkioTuUILRM@MsxiQyxsYBS`JR<2-*X)LHT^!`mAw>FikV`jk)iq1x4Jx z7nw$k(RJYr;kx4d^tzvcUGIg>_Og0`@^sqXG;@)IxANN3Cauj_-rJTTFc9PhO<1#9 z?*JQK6>FA+3bmXqO~=xJ1Y1zmu!H)UHPkYou(CUl!f^>({%*nO{l0G)TS}<O)QMz? z!a6{0NU_ietI;3~{kWs@b`jv7*(k_P6`~<;VQzdx3?$Y=D4*6Yku*SsO1U_Oe_Mfd zrs*J7MaLM{7~u>-dQcKMrmC`AOLW=Kcl<4U`P@K|n6a>NPgU`E=B^s@`j6Mj?@Q!Y zUr|&I_bNRlQcfHvMuzl5DMN;k7^DSnH}u-;0HN?~LLmzDk#`I@7<^A15n0ZWu<CXp z_A6nC=GF*y5P7^KeSW!+nV2(iRRWzcCLNoc9Oip5%)(r!a>C@jJjCUR28g!3MocNu z)hTDO?saI^0v`#ZqOML#qk0^r=n^1$G;UMWt%SzT%2ur~LVi;Ni7IAo8?~bU9ItSD zf=y(vfo;fOusmqkVi}9eWd+OnOqAYskeiyiG{TX#4WxsP8>obOkvcEMK3oSx&i|_G z6$KvF3pmFF*X|;UE!Qi+s;rG8uGaeiOKsG+X<t-8EgoT!i90#C(ch#eg8s2UzuCC^ zM@lPkpjQkBdef!@$>ZgG3WXZs9Rua$V*>iou9poe`)7b{^%~!&-_H&BUn*&<mF)*p z{>BWM=4Zcik;eJSwy>a7sJrhxo3OuDxHD$j;G=o%OgmeT(Tlf0Eeju4m{tQ+?EA-F zV_#mrE%W2wmib4zSD?_0a4p`4dBx$036|cHTw$5DM(c<q8cl=4@l-KM$v$n@jUa4} z>+otFry1eG3fNK#a1eOz>wkD(kBK6`4YXTcPq;1xLtKdZ<}Lw$*#?qN-`glb<<rj@ z8VxW>ajMxge)hA}y22iQR--`S^h@ik{$tBHy-J37C>7yEm~#SQgfAm?yi6mG0y;pS znZc3hfadiHEcLc6m@u9a{5)Plu5-`ygiKrS^gX@xHwNtx5pL$QeiMWjRe6ImtJ!EY zo43~ttgBOFTa0)^<RY+%5sz+j1$Q-n*rjlEFk;1TDZOeHhz#VE0(v|cPQ`F}!p30E z#jDk<Gmc~ms^1LxS1|K8wfe#Ynt=sngCPr}4vSlxj5cI3j?T2?ZVJpLgfTFNG9m0w zZ_OqjY|8Eku&itc9h-*vafuli@HsO;iX&{au{?DY87aouB859s12Ss=10<>BRVC4K z!I;A$fETJ9nooxD+X)5-nH97x?|P7CBdwB)4{lEOdr}*`oJYdarFOQS683I(^Gtjq zzi}MViB!8q#Q9}cm)?6E+wC??KZV<vbM}noSHPh3bg3~mj$604Sz3HhRac6?t!Y(% z$x)Wy-P9>RVcDvMzXlijKS95{b_<TO2Cn6^ckd(U2E}<|1Sr>Nkd9Y}>KkE+iU7h; zFZFkT^VJgtaY@ZUyv}zJSNP`iw2cw7+69|qM`v9vx7RqarD$-%BP&s3bxhu`ePl=S z1@j{w``sH+d@gNw16o@J6Ait52atb8svxR0toB(+P18Z2t!BBJuX^IlYA%49A4lhA z>a*%=r3Pber#ZD67<yT;UR*Gl{NTT1CiZvC{L1}AkL%bCr@H<oM+g)SGNP(Xb1r6N z;3Om@=#2nKT-Hs}t*4vq4d*r&E2uuUOZlg^+|McsYrMW8%rh05Y=7|+7>q_@%DvyU zjF#($Gg?#Yh=X#j^ggl3?$>6gN6rGj1`$_iK&wf}!LJexYVq^5SbBnq;FaO3nd~nq z1a|XoTV!L-(|#iuI;nDUKo%+TeS(<Jhl}Ev;hj%P5S^|UXhF7DFd*peghd`CK_;6$ zLQ5P>z2~TYkzzd`bT!kRvytOjF2B)gXq>#c7%Ezn+}Evi)dGx_d`{+E09fM2rRQi7 zW!Fh7M`JdhqUoCgffuQimd5w|c%U^zl|${&Re0o?@gGgw`%hp}WGiA9l*w7g_Cvn9 zcY6(0o%lfWEt`q_v^j#PHms!+W1U-(n}Q%o`o~1mn<=jB?n=?@C@$MBFzIHt7Lcg= zSQFY(Zgw-v^CiR4!tiJ7>KZK)<wO<d!(EgrJ(e1eR)?DMI^SvKTfK+F7FumPqgipq z!CBKF50Tmg*rmWSyIL2j#CQ*Yd95*29*m?<X2g!x9OwOxDTAv#?<t#k1oDZ}$#Ne2 zpSeQ1>zAXgSty!*o~@>Sn>RdPug@9Oi8K4m(iMRkh!OtLeZ0<Bgr{{L6sp<AZW=b- zh)hmq!wL1heGk9-E&EG~s?{;=T!D$jHp`J02b8(?-_LVXdfnY`)y2&IeePL)*f#BG zTuf6CVHU>fyq#(99D~sx7@9V9$k9BXW=11iHH`Bxb*qz40ck>uo^B8v283m`a>W>9 zXcIltZy`H#B@uQH(q8u6o9h5kyE~%e21Eb1hU&>h^zkk%PvsTxZ&KA?QiYFvQ^fG& z$sD*W_e~(8y15SOD0}=jvXW=*kH<`|aP!+`+f0{_&$`Q+b@R(%I>$8`_?8jRgjUi~ zggM;WH~NQKs~MqfI<<Q=kt%BZ?{3p#-LB4pq(@d3WsgFeRf5J^5F+!*wmtEpKYb5g z!tfM<V)z{4MXL}~H|v|^^D@!rSobd^9J%(J`;aj<TqKZm11Hg%>UnSO{+{vtz?Fj$ zFmtImyY87nzhQ*=WQLk-JN*RG@Q<dx5HV3`SLP9tXRTJU3`_=4WKyj;|J>||>YaH# ziDp_ik*y>Ml2%5AnWYm?P6lgRD@E|3sdX|qKy4`K*>#y-?;TOuzcC#-fF<josvptc zJ^a_P_(=>b!o7|qJp#@E(L@4A0tFe;AN2^wl1gaMgKWM;%vo=oA*MvGG|3}ix-;W( z*|&x#+gH%E9>x^I)x5g97>I;79~ZfJyIVrLfhv10G4z1DsJ!a4r5HK)vn;5TARvzX zMD};`KVm=Y2-*RC!WTsnuvAq+QAAqqNemhP*fB;@n70^t<TJ^d%QgILApSy+#Qa3E zY1>1T`ZA_an8h~iy5xDGbs~9O?u0!`qLLRWqd@aD!%CjZ5BCKGheH75!l_S@si^ve zD$6?F{PdR#hf<qQN+V{}f{K&fwleH*wA9KTFSUPh+~gU-l-8VC7DgoQl*McfbZgoU zrNnfKw9&rpT6Cso+V^)t4256QBojwrallQ8ReEGPKw-_78IGlve~fPc#Sv$ZW_O_z z)r#X-t0O=<3a?1Cf8Lh4-LJ?mcO6kQpZC^H`)cSCZ4hoh$~GK?@szbITYh5){uOb5 z3V-0483`L5WKfJYBx22nz+!)wGwlf9=;*?Tm$#Dx8%;+j7L#!dO+~69IZG(_#Z*p` z>rIcV)V(5I?-$TD>!!?9QrD}^ja%KdJIhf=!zjt=geJX36r(2d05=oCqw}ys?s~1= zGO(K({taAWUliu{wV~l`5XD&(b^jn@wG(ne!0afZDl%fNJ)l~?ag->mZkCE~!0&B5 z#~-+j7=Fxjyc>8Di7t%=6_v^R*Np#5u_Pqg0ki~1kQC6I$<hS>#v*QPT_5f6roCwW z#&7g|R%@{QBEYf+O+pz}cV@-S+Gb6Esrp;EKY|VC2SXa2@opjd)FCaLad|DNXn8Pq zX(NAi5(xU|@qb)amIA*zkpcN)9?g=T#A1__$HdhM9uY~ZX4!I;w~<08Y7BkqD)J(# zc3i0D>Un8$LIj;(CX8hHA%uWAupgILp)_gxp=eZ0PlzY8#tM^Wfhv(=dC-@gTuU1Z zf)h7h4<2W&m8q&M){DrO5>JUuWnpa!=^5)aN~>MU=HwCk`@^BAUC1bMi3h~_#>5#J ze`4exgDAFU&AdpV>rnuz=0;Hht2lmjCE=qS$kJ}6UR;n*>%0(sB3_Z<a-14gGnnYQ zUa0QbKHN={iX7C+Z)0@|g#HXnXC!gPUQ%OYC~4G_+Klj1GcO0BH@ds`mbL;_hVa6L zucFIka0ye4Gc2$anuSZ?JSCnaS0uU(RDMKz7UnQxXi`Ipf>%QyG3|l3=Sl1ry;OD+ zsHTLrJywyPUMRC?Y(3^h_X2l?QIY+W=nG4Bdmg^2z*Ms~2$FH?iJ9*}p`jtol~3t0 zq`Q+n@C36tRIghOKR8*(YeUBC(-ToHTpAj%?*7&3e~a|Hj@jhY)x*AF;Je>Aq?(3W zN|$d))$_xWE`h1E!zr=DTBSDEofvhI92eleoMO40)D}cY#r$w8JI4FtReygt?hx?# zem6D5^R%vL+}mF0$(qRyxB2K#0Azv`3mnqGrcM`^ugF$SrLhwOe`o0?Aa6OMx1iZR z%V%zB9-XlbG60zB>UZ7S6z);Y&NI95G*ZwrmP;usUFD?BHdmdtS6Z?W&D+V@m~j}I z95$PQApmHk%bReHu=1LGSeAv8LzID}NORB45zOsR0NI?gKqSL+;A)<)23wX;V5wgP zF0T6$r%q91cBI@CSkXu;0RImQq}wFQ_c&^XEuMuCli8bsrf^{n*z@hd_4#z{iov$W zmOOv3N<2?wxlU5`yz}TMt9*;y3{<|UgGUlgTAqyv%-!L5|FM1iOl@By`)&0{iL(?E zh2U~xKafU1yF9Y++4zj8Hs-}aTw<|A&NIFl^H&{_d#&f;pLJ9%8-8`mW+V*a=+c}F zMe);7_4qPde=gz#gBQR-%1a-P=jX&y%IBWczN5IDiwlp;q-}`T)7lT3HRe7An*#KR zf?VsjMKd+NOpn?+YNVObSz`>YU6S{^K`#1>B~KZJrJ+r5+-RTxo8Bxg=Rfzen>86m zdK%&$sVjrcgUSH;G&>JSxeK#gF55w)b(U*=DP2H!MS$&)4VQI*lS=m8(xP02<$@^b zfXx_hLloZP0FFQ~g%JgtHDLhq8Y5k_>f!DNo9J$1`c<zgQ?lOEkC^Tf(<~wXH|TG% zy4`FES+24or>_BP8nmj*tpG043hRm`CZ*zLf}JT|@df3u|LM=ZcRb$j+5=|rY3yt} z`@?pSzs=fusu(T0oQm&YAm-=4p89Q{B45-6MtV5jXFaJDdZ2*;pDW&4pmLzN1uS*z zOrlvz>yqfS3Y3%Sqw7BSp=SHN>(jETv?cw41sE2VnjW43^NI@IZ-7)IqOrNDEZ>I{ z_xBDD6`2Wc)&WQCFNzB0NJ~;CggYb*QkKs{d2L1&!c8;hNdKy8gaXB)ojp}u!2#Ji zM4d*A#2_j&uz@JA<pKt%8bZc3)QqUjo$kJAy{`|sE-%gfX)b4tyh4Z~`zu2vy;S~G z6}5{+e{BokQ3?n}lHp-haNT<l@2mz0HXe71G*=5f76|i2^^;VYLmd(Q25+j^)b^wQ z8iGI|?9LCLE#Q2F+?r9$R%)|vb^=|m&mD>AU)C_qR$MI4JKt=UYqbrjb=mQ@ym>JT zc9@NpN<!#(zrZTEE&|VNJK=_Ywz3Ub$*^MC@1jtdqHj!>$*c44)$O-p7imX!qK<{6 zNHI<hNEU|f&wIi{Oa|nUd<5twwXmlXDU47%*%d7~*N4;VFp!%5P7u^9k}M}?Fq$Cm zgMv=pDVyRu&?){J1aUu?9xDl`^f-^a;B@|#aiy!+JfKbMYCUYGg}3F!2U~I?Z7;uN zIsKNg7faHn(b<J^K-WDc%M-o!`5Qhd2`Q*NiT!k+iQcRmbvd_XA4?c-4ik-AwL-`w zQ*Lj~x7tLDJS(J%?>F?1ON?N-yG(ks>jkr=b_U40ELE(+To+YqdQr)Qu0?2rmV^?* zTmnt5F%(ww$+s|vLfWBq%&om1F7Uk-)j`6nIhc#aHO!3|c9^4VcbwHG3k!@AEW+Ao z8%vHj19Fdr?2%jClvcZ9@EM8f_azFql%(Hzd^&-fs@g${vgamUAPXDj0}o*RM`~;z z8VLb^%bLFo=C54cU%!luHK?lwFflPjxP?uOUCQ$yN-lLBMo2_N8a^gZ3wwIn1EODt z&+NZBpk=pmj)k(>GJb7s4N{h-!bz6GV$sj6aU)>jLLj{-ws<on;Oczpk?Jhg8_^&g z^?BU0{KC2AD0iD4(DAyz5pz=K%rBMr5y||dWJZ&LiB7b1l|-yhqlfN=HUi*(mC-u& z=_Xt1jU*7wI7#;DLM@#sbc;}2-}y?$v?xM<qm$O1#jJ-HL{Nt3hd2Y7-^O9_)~Vvr zJwOKj$3j#M1&mc^h|_ItRYBcT#W&S|m+`$Vy(C#)40g9C1TTVDRXdu;Wp%RAoq}#+ z$P}+r`fiHrrswG1F2;%3wh8xD%N6xiXL+tUTuMFDkSKadB~3)%l~e->0WoUSMj(j{ zi4cmo(l63<LQYF5GO^`_^hn$P>&rFt3MX}*@MykDv~KIm@QU)E`qJ4)rY$E%L03p5 z%1}QDay{P-+%9d)@)pX*+~tlzjj>f+JvLy8lmxM%Y5EP__o=(At4SE@%hoo^NXN<X zkIRmuEYGQqBc7?>TX#R%SkBpn<ObQh=!GT$mLDbdNF$Vxv+NXYHp;w%-@CD*n0TVq zBcP{?z7XDD{Ojz7y*=<X!D7sU+&;_Ao9`OeZu;-`hL4b9<CZ{&vYdfLbUk=A@+qt6 zM<tT>7Ra)@i_2{LW*H9wYltD)Zk!_8cVzWPjU4iI`~<DB4o0sk8jAL$crf83j^!4( zyxte)k*!B8_p5Ih>vjVaW?7k&W-?JLJ^V{hwP8Dp*R?QdYzPxk<-je#wc!Qg5Dq4{ zTXriNksgQkTCRH?DV?1DpM8%5EKAycI{|McYG6q$<TKAg#-(e35u~PsGw+0W0}k|k zO?h^7AD?>y?$>c89Q##u_NRB`xSp^Rl)|(51a-6sQhX|e%giF*B46;@t~o9_ykQI3 zmF{K5f20C1Re@yHX_6LpQkhIw8@aL3<;_pTi0?2t9P+Ifhyvs#Bu|Ei=e{>3Sy>Ez z69-A^Mwi*cz?`ReGcp^~^JEZC=Wu1^7o8QU4IGswN5Way;|zD)b|TqBDF6hgB9ZZm zs|=-RW1P36kl6-=sVZiVPM6wcQ8UVl!tgo%vwje!+GWUd(_T}E!+W0%xNld%axSEV z%>Tp<$Hkb_FkDdJO%5S1b^6_j;s$McGzc<>Ars9QK{=(;MG%IIr;mgd+;`leT>twi zF7Ry?m3|3=XkVm#gPeN5AXtCsR#elD3-oTg4A8Xc_=dx^(vYD*?nX{6>J99sx;-yy z+HY;?2#b?rZ@is{pV>6y4E<!EUliB)nyTdWL)S>ADAJu<)vv;_qdUtE2!T5K+<VV( zOfW8Ze(r;BCVMARYwGNFYxj@%N_7-(JM+22j%3PTOdDnC?0a0tKFab!(`d4?F?OT? zg9JN)=8oe-<eeqXrQ-0@w&&*^?0AO}*}6e6p;n8Msb7988msD8|9=4VKnuUe9gJ*F zvTExY?ZsMNxD+q^{V`m9!y{N(7)GnkeQ?&Lm*J9gjzl&?MajsbVQxS3?%TNK>YMP{ z%z22UH^cCQj>IMBpN!lzt~#cMQ<P;+PR~Gd+Lvh4vL(`!Qyd?R(^iZwT)GOcJoPu+ z`pA3O`{eU*<#|UUH(e9?f~2ZX0LBSC367=hWb1MGOuRB+lNwj3t&M+@FWa8K(K3Af z`CAxu!yOnqX&$<7w+k-0;xZh6#C}Mj_LQW);<Gjmvl({fr=#xVZvOe#QJiax%a`EA zzdw#U?|&CVk2nFBjyw-7GLp?8maXws23B8<H9V00XG(gX#z+AVWPgWNSH~u)tJc9j z^UO15aafjx1K_!F5ng)fC7f`=38rTJ#1l`TY15_~1erd4I$nMCRa|%7bp~YDty^b% z&PvKFMy0KMMvNF?mW;K}Y{0xWNTdPX$TU*|XUVxiD;Y~FS*aTsXpVJD0<yvUtuZgD z{?d{68gtY$^ATs{g)uI!m(|2}tctU}Yu8}@NAF|dqzNcoFdNltmLrSLvqFiS#g2jk zSWBl_^Ok7RdndFUu{Sb0w?S^Vo=8Z^#d~9>;oV0+$MJtT82u0JPK%C?C7Y_ZnmQ@~ z06+jqL_t&>vlKhk;hm>|r+}w`r@)33P=6dHV5uxzf%jj18dqO;2j(p=KxWG>IPR>= zaKlw+AvZM+g|v=@`^3(j{v~d_>^i*u;bhdL=V9RRLvZV@*P(w;8YN_cW(A*Tv+ES^ zfHfg2AnW>KafG;fs4)arCKrYvOJO;72-j3$-rTvEFkvFf$=e-2*Ha$k_W_REutq<B zr>qn=F)10{x_9RmHiM9z=_b2fxq`yPIflTV?YSz2T**SY*-dphzWihyZoK9?d@^l5 zk}_Li#1Tj1##^pHFRJotO|V;ss)>PFc<kQ0aOVTBqNpYny(zW5Y}B<lY_I;vlqM2^ zej>r_I_?7SkH0>Md;aze@=K}+Slgm|w=PH`cq=E6jYzvGF%vy^9Ej7-JO#V$v@Law z1V+W{T$yXQf9&&*JcN6n`3i@ecNs1`bzkJ9h(@Y|$=j{&qK?-1TC8{j1*xcpqN(mR z_ArTTG>kPX^YQi@FXHK^pToB^7ji;52S=Q8Hb!1?A+~Cn>)L_&h}XLtwXY6WHa1*v zML!0yUp>>IJH8p!EAi&@Ph<4$uVB032jlW<E=1?1nMhWW3d4fANfF(}+sD%JKb``O zmjWKh{>E(|fY>>6=3vN>AqFl-jT&VV(>86|Y%+JndGpOTO~qJJSE(8g8Z^jMlHYja z4cm4{AT~KU+4iN?mOBFm46yBeI?}T5Bab|Sv17;DdfDz|R1MulD=IPlZx3VZefCFM z_pQkrG!PIIiW@Kr_`v3_Xq;cw7K41ImN^<D)vUjBVwP^eqIr2;(J3%3J;uV-2(Mg@ zMQ^{2iLbnb(CRhFqF)Br?#LQ)6$et4j8MWsKv`NQ4m{=0NZ)BFUb%5B<`-1roO@5f zR=ak#r8zMIXBmJp7o6j_{^Tj(Dc~vKDIf|EL_{j_)3;w>)D>6Z<&VEcIFyDieFkFW ztvBQN;k%erOg(jopes_d4ii6m0~elmBW5gIiL|EeaOlbB;EtOwM@vc&tw&d<E?^^6 z#EDG<poTgFu0W6zpYROYKog(NDUK3wVYN@W14VjT8%Q_*lT+$Cl%jHwb8t&}2f#~^ zN%!%C>wi}+{RxlXb06+~@b4%LC!%H79dS0LtQVenF!_`WFfq137bV;aewc(ixTWAz zZ%jZmxjBX&csOppV<h@^X@gYOQP5A)+X_l<-+%pOO2Yqvg{zCGamH<S2>!O}+KtAc zI-!c1X7ecdP0VbH^DjOdN79Ivq@XI7wm?!%%4xB9%zgLc$+u?Xgv+nO8OIGpCetxV zsmgB>%>V-06gho0A@0hd)J*besj^%QpTIh-TTKxA_WPJQFQ2N;srZ0~pWdA`7yWiS zn3Cp^IAHf}<9yZuU$aKcHnWzpc4UGEWE~~t@2*_?^47V?dc61AOSs{tG3c<%p19_Q z%h0QBo@oKt8eXQMb;>HQ4yEFbczl2I6ljDL@IdxAZghcC9a8a?F{Z#twKyjy$JB!Z zzu+8%lVnu@_{%T9L|Ivx?H9Y_jyu}EvkD`SE5lJ*N2~N?xmfDR+itrpdi3aF>u?*o zG*&c;tS`cIyX}g>Xa5<UPCp%?G<DvZ6;Ec59<X8gZANDdHJ*QPy)lo8`^!j$%s@y< zOMq6h_hS0C7oL(J_>9%Kdc~^B5Gg7~A!p;?c=S=El@}qeXf@Yq382#O6X{S*gBxWG zUL4IvIMxQ~UAp0zC$2$S%Ty#$QXor@QK~YBlC-DrW~P(s=bfj3r+}xx7Da(D%DGPS zy_cTD$jfiWymggGNNs_E`yGP2AG{UYwaKA@Jpms&BEHgf^YQYS2XXaHPhnMIHClJw z7Uyz8`Qp<LN4kMCt+5nPB@hyLqOrYNUaWg_?2C;j)b+^%vgXA!Yyy&J0W{~!hwS(3 z`fx#^0F+sRzvxFP+QFXyI16993C}=U?2=OY%FjTTBC#y7a4{x-G8Wg49EI`U%q6hO zK<_~Z;@Z(S;*i1J4J#_)1oCF>={osit|h+a27L7Gd}O!mfn(1&hcrGJZL(#xm}THt zrm$c+J{b2po_O+kWH#@FqmDTWS(z!A{lj!DU9t?t<z-08$U;XN+!`==ckHm!Hk6Qa z`Ha!pO>2wJ#VfhY=I(p(%sX>%>d0$x+Ob2pa{z&^=?JrKHVG~wi<UC_L^#OF1OtTz zH0iB2<8#}lhkUbe?FxKA1DxN_S%TpQABi5Vl9<P6-2Jz)NNUy-r=NcTE<W#Q<YlH> zTxXPtDKb5y9@A61IlwL-QB=<P=<FQN(E<aq*WU0X+U_`%>v69@pN`scQ15`OH3x0( zfoz;;{^TjZPv{To_S|z%^$sywE#9m(q)Ks&>sf2dKmb~My{QX@)uC{~v2nQi{z_ji zNH=&^|GaVhhISubzb5v|cHLqN@4lNx61l6Nexudg@g~MA(w8>#H@{QKA}onYq$?J& zexZ1y`&$3th90_%>dd1`?+fq4k!Y+s!kVdlc|`S2R93_yWvgT1g7vZRx{}!BJMN3! z*ms-Q3tP93ebBQ*?5*zYc<vl~y?dwFbKN?|#&l~Jdwtgdv1Lz;iIpu{K$2B66Zc-# zFPgvh6z~-A6lmNOD37gNG9h-|1;@rRIjfjVIGWR9huE1{JrrBdnL_pK;yj!X<aH#r zbndj+r6&%Jr6(p6Q8bTjv-2UbHzrJvRf&k|$kmIB*DKn8=qxAxkOjCgfcQXETtVsT zsgC+rcKgeItp8U!F8#3Bi{&F9rK^0%SnV9oOL5|LSKTVs<;PyU`|4QNtYpcPW69~w zV|yKYVQliEm9EN6B4WI`Dpp!JKlYFNu8DQc&E#}yN~}xoJ!AJi`$?=!nW{eI<3($i z#GZa+bZm$1wvFw+&(X1uzWUZm;7X}*fva~NFPfEE*G8U5tYF1Yu{-|qr&!<KyT|T( z`lDEBm=F2Sy?<lX)^?S=XJBg^7E;#?6X8a{Ve(nk+~`5VM8g%a^{W@go_X?-*!h=S z85{e>)L1p+)l{sFjeGX)*pA)W#*&h<VnYu)HTLm$b7K{ZYvVAD_cT6Xq1<SoCVs8a zfz?_?+JsYMtckt*$^)_f+x3eba?+)-Z<nmCmxj`DZ{j8*doNFcMoR%Nk@d3~TRa6K zG;lF?*Z}Nw%2{ZC;YBR3<})>w%QI(N|C?Fq-?Gxd{HpSBGp}{I>6!U$Dp0&ib)oCx zTReO2_P?`9T+U?2xB-2XhQSuRITmAYx(*#eRcJv&8!}u%w#d8^P|2CxVyPHs=3>zC zr=i8+ha$B@J6pSzkid0E9FD}a7avC@k{T#4H~-6f3BFn2YF;Gs8H3P+H0SKM)TEOn zQ;vi{?J|oeE6kRH5^*)PligZr<iEL`2&kILsV4E(kvPIiuXFsl=u!W<i12f+_K~Y) zZM>fg@BKXmJO#Ea3Pek>VAiL&iQB)7dE*Oy!s%$&Z3kR(-L*LPxV>$SqPl<>b!N4- z&YZ6&;JS<cj8`ViriM@p4B7WETJF6GJz7%@RDFp_T`j_Y+#L`MF$GCv)h|0c!C@{r zsbXKxk!qZ7wVlrYL`SWYO-`Za4#lyi0&V@EOItm8opbq$pR8Fr7f;=L8*abvDHM<i zWH;-8qfVog^{VsGky6$KZfPT9QVF3-tj_-dkKFYDjTb#bK9q(&gZIPrx88{T2W~?Z zUT5TK%7piE{WZ5?#;OR;`O8RLa4My-EDzx`b7LvUcSJ;I1(=tnj!i#FT6N23+6qW= z*^)I2@%Q_sT09*mFs-wX+lyQLC>2S_6<Rf*%CA+2_i+iQ_=44!X=^>L_+nY<N__O; zC-`{cT<pHra2zmvFw&@|EDOdzP5%ma-FzdSd38LRcIk)n{&FeKKJ`#DauwqHp;Afb zO55bPYgY&P>dN^!n%XUWZ6p(2k9S{t9yi_iBsvcmj;pV~0zKR2T6mX&`*m^rucv^g zfGFUBtbY%-cnS!}jvKlwc0A?GIw0$~0n5JS0omV-pm8o3u)hc`S0`~_SxzClENKiQ zT3UqaIWzIq*mv;5*iX@{vKmbitNFZw>c|n4kztpRX@&{ZI`-HGeGb?M*@O2$N~=yt z%;I(l1i=ZkimdUHSbmh&lWhwq=|5AI-S~67g3{KKV`%zwkVU2~tCsa3qCF4FtDD+p zvnQMRM+IYnHYi{Ho1l1GRH1`H`Lm~hr@*g8ff%jk&Yn8X)QaDnFq8Nr4ZU|5hTHDF z7yAvMT?Q`SFjdh+u8*xQ!K4qz;qnXqf+<|HnbTq`9CPLcxbdnp(L9}7omuB8V5IJa zy<sp3_KW)w<`oC5f;ZJwGWPTnrc9kmV^5XwD#v@-Uz}zgr35nNLdi+!(se8BI$#&% zWM<ZO&OwqYf6yHUeu}qr-Vb<?My(!w@-6a`RJ7x^L+4(05zasR7^?9Sd<w|2<_Rdr z?C(Cp=<7z~`EgT`kk%A?9eNaQzU3-x---4?$cu{BF2K`&yAPx8cosbeAAsv`yAcDo z?c&xWlLnlQHU45|9i{tRkCp<bg872GvLvlst7u921?~iJ?{kxI(7Bi5;#2oS6V}s! zD$8c--V7O70Cw<~v=C@kB~8Z6r8?Xj_lxnL;)}^Mu*2ZJFnrG;$f6};XIP2`HH%l` zr7?fS4L3i8{IYE9cf|kU+H1~3-)`JbmON8H+49l^fdOx(T}wng<l)e?NJ?j1l>6|l z!CNnk!L7GHhdz5Bg1=mS2|986A(dAYtxcl#!o~K#o&t@T0v^aV=GJc@b@xCv-cTA< zkb&tWXS^)9;eCWaHBpS7j5Nl<L}Xn8?mOjbRQ<FN&68>MIWmhg-Q~!oR3Vw+WPy?j zP$*+c%PG}uvmG~hKmR;r4H(RU94%m{rD=JsjUC)>0!};|m85|AnN?0*8P|^UW);c~ z7iNPp+6|v?MyGP?2#OM%tw?+jjFak$7@s7l^QgV5i>s@;yV?N$!c)Lgpg~X|7Ad8n zr}uH)m80?EM_(f`H50q+aS-mk|1Rv*t&QOh{b)OxlG0^(?b$IHdFg1ZE{~$^);r-M z?k9WpF~g8*(!T&63HZc2(Eq555Rer-Q(qNB1^1Bs^plTh*zs{1i!3DIa)||fm2&&# z{SU*&`|p(0bPO3b6la}rI$Ad0aAyQHT3uhsdJA~TkI`2woP|g3xDgLL`WlLmg{}Jz z#Ff`vf)fuNW`NL@hy8y|Att=@EH1z7MogYpj2y0gJ?4y4arMXx&@NMw+e%t~o`^ed zx*5;B{WXRiay)Lh^(OT0+}wbyY9+9$t#4#DDZ!+h@}(oMb3m3Blv%W3V<0ZQ!Ry@W z=N4|iGvtJ`arFg9b8;b-2{91)lv}qfYPox(vOuB%SxIPt$_iR!o-hILe>@4>?mP$w z9k>@VQZzxqX$gi?n{ZPk{P5MsxaGz>@!E&qpvyM9;Np>&;H0BykW!@;+u(X!GZw|t z)q|jXp!f=)GPwFUn$gx{*>b$B?RWnA1_mE_0xrAa0<=y`v9-kUnp+uzwy*VLYTkJY zG*$|DAlq15z5&(S1KD_EiT}kpmoCLng&}QV!*e7|(-qv$u9mscuWC&Vu0L)x($^>9 zh>H(Kr@k5Z^!AZhIC(1as3z5vs>n&4*OqOm8ip_9v6ks1w{DA*ZXAuY9s1Mg2|+Cl zYe-V7#GO(x^Rk&{4kR={U>b27(shMoU?vwYsjf7yURyeQvUz?~mf(nAa&Wf+id8XP z;WsFv8$i^H%crhJ`rQ)hwn1_Iji-R8z%QWyx6{dA@D=X8<$m1z)LZQDvM_j`!*S33 zcVOEN%?)-4%!R^LSia<2JaYG4xa*-;&9ZS%T9>`~-aBw$|6Wvw6<CrSRuD;GB@Sd& zhX0^@5RkPFNC1o-QFV1SD$2`UmlOxGF2VmGQI&ztb!+OIxi4!<3XMV%da2Cuq=FRd zx<B!mxVkLEm8{9fi;v!qYi@ZEtEwrv-gysPbNyd%<nRHkw*V&V%y8vvm*Dj$AH?+x zx3DM?ZMyA572NZ2J`G}JNM)Mp+*3Y(2RB^7EquONj85E#_q>ZQ!qEo~LoT-iN>1W- zd$r}YBpts~4Gbw7%w-sH6@hK?rmFS$@bzag>h71Z^{^vx^Hry#b(2hsXO#~KV2o3I zOSM$}SZ-ccRhD4Nl&N_4lWFMIyDyG9cmy)jOj(?H5Rh8?D*rGFS1jOmK@Z@Ld!Im2 zYI7WU`k!zm>({kuHYb!Bge5b6L0Sj|JLmF?-&m!bkDx9mE!NM&7;Yc*@C%c1=ox3> zg7f|lIgFnaC&Z@MRBc-R!c(A;QosY*M%wTVsoIhC>+$xmf!N_>uUbrQXHLwozB6xn z$~3>OIT_3!4L;~smWT<j&csU(j7KQ72$zliKeX%9j5Fq?s4lBO&5C@Cz2+K3=FLDW z&OE1c@7hW-_A)Z<FfC$NGsO_CVmI&77lSW2A89-HK`0~Bq`nCR&f?KpFROfYXl;|$ zcbT(mT?HlPAZIf=+Ujt?U+P~Pxv9YMlDiUW0IDk<<{`DT+8|W5CRtfE8r^W|#2*D| z@YXv|0Z)MjM**&hELwtbFT8-Oue}Qkxs6%B!TaF0yY9fizFqjO6O`0cqmbL8O?dBB z+<)Igm^f=0E$KGH?gt!!TkpC7+qZ8)Fhp=g;Gw<F1$t`x1?y-2Gol!njVBREVe9(Q z|02QK?1OT-)U;}(wkvd<o|Rjn+^v{Nm^7ddJNsy5IVOGl7U^^|CQM&~PCdAm`0~qe z$}#&RHHorOuIDW+UXO1keS$~170!E~O+hJgu-&c)a66exaPY9cq>Xq)6~6i6J=}D~ zHF*Ea*@&cMq33ox;pn3e$B@B0qf^HY$mY%t=^3<cEIz}Y*|zmjx$KVMleCtcT+}d- z87aZk@$cZKo1Z{pn|>I5+ZE{6t|>#PJ)~0X;_`+O9DkHLahTiN6&0?*SD%l^ORs;3 zHobSix#yjM_BrXyN?~0-OvdOSkQ%8j#V2pRfEy@{pY+pO?7Zi}xa#^VF?_%_T*edR zBR=TlvBp>IozOGgF%bW)NO7O_`QPKO_uPv&zgWxdj4r~7NA6+LSf>%CK*rcDv}M67 z?>q$>I|V$DZR~GA1E{|TvOnKQ0TXnLU7PVxa!R%>;}_cGCqhsPsu_o>W0>;6Ts%Gc zZ6r|_>xfJC#NZ?P5~wn5-Y0VHRfOwnOBOD`JEO11+V8(cSE^)XYEM80p}k|{xWydE zBxUC!(yR?ejJz5d+Y{9CUIRF(QAr{kBbs&tFGgfE8iPbqG8wny+dp5K-{A>YxM}QQ z<<h`L<s_!%NY43*TqGEuYrw!VhglcWK$4bFl2of1KowzlGe#00O$0*~#rDoqz*C^1 zQGoqdtcp_EnfM#Q*WX`y4@hl>!;U=##~w2rnZz?|RxHE#_uj|5ufK(vbC+<UFBwgm zcgC@&pNZ>lxCqTs*q^Z9u<k*9i~2;8Ax4y_ZX(`Q{360A-Y*INOT*P=${6a~Y@*Si zl|8b&)W-|p)%wtvL0Kc$x2x}D|EIpbaQ!m8{QNWANA?M<Evm+#J@>^qXP<(Oty^%r znl+d<@e_=D?G;S^W)@1T*>9$`#GZ$piqWGlN8b)PMi)(gu3Yc~9=_{#Jov<GD4{Vc z)jB0T8|^xD#&$dOqw4b>=)Xf>bZXlQ*-f&M&I#2-*@a*+L*zGBT-L>Si#%xyV!`Zb z+|Ty`%vv4A)wkV(K|6HkN?!HpwBHb~qIhEs*F~3<l%cq|8mpEs#V1_%{M-w#prAYj zC!ccxPCxTFw9Rcob#b?$j<usELL*g_j+bEF`gNGVt%V-sq{if#OOe}#Yo$**38$TS zD4OMDAu~H0**s()%E4BHu2x4~skkb!oanDGi+`Me+ehDyS!-KT%6%2~=--7;M0Y`P zwuR~}{?2>za1r^$J5PbeO92mL8*ke;n3{Va`wN;%T#lSk%vK!E_M|0um%^`@JQaYc zJDiBpl@)kw^qZLb{X%r@(jLd2dl1_8%c0sZnIt)`vFz$fgbNE$xMVTbe?1lRCr!qp zsox+qQh{tT(rl(q{6~wGgv|u8;hbjZHE4Hq?%y97JMD<XY^ri;T@v@LjdER+O2nmQ z1i3s5Fm5)dfu#mN95T?-GA&*?ysC+L7P5o`pQ1t?MVz6pL=IKba&vPyK;fX2TNdk3 z#Z`B!6wlgg(9t{a<gIs}0-gd5iURH{b|7W-^2K=bwKwqId!HkJ)p}&+WuOTS?o?LQ zAcLJ)b-_wZ{PG7Bgj3PJ>-M<tii>gH>4!?8mH>nOi@E{<4L28Nm;Y(+pz{1ur?h{$ zQ=xRIBX;1(#dj1?UuFy=-oXWQ5qQ<4pFwh}r6hzRC|I`=pMLN@-hA^t%vrn~Nona^ zYnw+&Wfjt5oEWVr!lZ9!W99mCWVPswW6rr4*I#)y*L*5(*B6HwX2OSW<M!Jhz~t{{ zp^O?rPEM-)LP+MamJXe^!l2!D$G|~5qt7<I(Ya$MG|A0HT1pb>?I`7pI4KVIeO<Mf zD!&iorT3@Oa`9C-{;<7~$u+gIv9HERkO-Q&EMGPU@4Wp!CQq5c>m^u{zYLXB;f_QS z(V|^f9CgC+IPS=U(K;`Od`#pD*}k>mssemFWjvmL;SEfg_5)V0Eh2A7A=#3U*EElO zbt|-O(+Puy48>l<cSBaHcp%Fr-os=Z-FYWc*WT%-2H%c<7o%@|5Q$v|;f5P7$JQ-q zfKl(1Qeb4Kaiwy&l;R0ms{Y4Qps`ZG1KGyf@(rlo9>{K@vBUxEJMy*oxXH~@i^0=R zz|9R>cuR(;JIze5`hGngzVS6~k5Gu#ow9N1J!c@RotPsTrVS2wP0(r)XdO8grt00Y zg;@W?3~uu?3OO}p$RguSV}K+L?l`!q=D?_k7L+5IP0($~o*2ljl9F1|iX#UcNEQ-| z4}?^P&ETwB93^qHKol&g#ux8R#W&nOqhMtTYAUEY$MT00s7Ot4D%D|dK$DbAYn~jT zX67Yfj}iSb;^du?m?1iGU_uMeemt=m8q#O!Dex;(K;5Y%kD8aVubYO5Bw3s{e<@aT zX-fhvwzp~97AetcJpI63cx=q8C=4}0pI!FG&9_~HeFtq*50o&mpkuI0ffzaWYnPkt z$JNx8#R1vck{Qp?bC%Oif?jmiajHu47mWng?Foq%MQLF%7A{$e{FSRvLm=3)WizyB zl8BGSzKZK^eGID#!|2?LThv^21x`D5f3EqIGO)5xCJ|JY6=T|$6Y<R7pT;NSCt=0< zB2-mXGHLQF1u?oMAcN~>J9q7l!9#}QsN;{rz@4^1I{RQ(KGlWS1gz1jB7E}3%eeEt zf1vk1M`7e&{)A>}d}g^aXRAXP>(?&Fj9EX@fEEoPHfh53!jkkxX&Jf-rRCLV(YiIZ zC2-Ek%5-#K4vCB#t*OA`Me{KG$N4r<o1M+L;%^L96Ae?sTL!XAbfQJ*p1rywU4Yw4 z7pEET1WiR&l}hW66UaTQxjy&J=U%~M&yK}zM<0i?Pd^@ctY4z&O(ZR_9<_<;017j* zIi=#Ar$FPSfCsXTx9uBD%_9W`cxmWB^grWI*y`MKS#GIsIdvb+f@{#Aaf8hk8{?y& zNy;{49AcivJ9U;*|F7^mw5U|-JH`_NPd7IVaJJQgi&fTV8uV2JJ(R1>(@N$1g5TO_ z7SQsljVCYh*C6aB&TdGd`Y>%*$l$~hxtL;(_3J2AUp+DSXyvq_n$=rU$%=K=c;c3E znEu5~q~~T}kArr?0jKOvLnlm85?aQUghAWyXhvECk5DDI*`ca%<&ybW_0?2-`otqN zD3y;~hR$V}R1S7(IQppKxrkUWmem5yciIViU2!=QTM*PHrxMswJ&n>|kwh}%fGykF zGWv1XcX}}~4rC%+9F)jE-Z6(T%R>Voy5XH0hPmGe2M|e0Q1z5}*<!H78ZA)z8l!6U zs-KGR=085eqPh84y=pD%CCbG(KuX8<{raGNr*`PFEe9nTT<4`h6n8CJL%{p#2a_=W zrzM=vPvT%F5d-$@hvP5XgI1lD7vBli)ik|WZj#D56_Wq)rgE<a+e0nD`Sf@ofASRY z6xb3d5M%#QNp;bp;tKXJR2go{wV5<<=N4AD5=!-W#+1)+^`9@rN0VovCZi>W9C!@w zx#vb~(<YmN*w@fmSI-aMzJ2u%=FiT+`Xmdo8Glqp9V(S8nF_N(>0C9;Q~hILL0LVn z`s<piG87h;KpMkMa+@M6gT?>_axEQ2j$-+O>3Hz=TX6TIZ;%({V5i;oz;&aq#@++_ z#4QpB<xnZq)rYZ`wi-VF>{E=R`u40Dv#^rDxUi(0ptg!qQuUqcTw}=0X^lgVJ&oJl zT!8Le|LRnwZB;U_)gRYj);HsE$8GncAk-1pbKPp+9__5wP6bDKivO?-@ebShFnNVi z(bT8AI|H27mg0p1mHKmQP~stUVlDVDdeu?FsK<w*8y_>Sb4)v)zVWe`w#U<+yNmI_ zU4O?^uD8AD>Wi`4uKke0G6s1n1E+DNE0sef6ir-?E^YtoDbV;R;DK!8Yx4$I;~4is zT{8JAwCmZ6V5kMT1v~Nhx)?WV5R(Y1<vMrq6<x_+-Mr&7@^P#tU^fPX=q(jdF(?ad z!SoY%aVBkdwHY~R8L$vzihL$^E3g@)ujdB2jT0&#7sDmPJS>i}#&{hRpNGO}J*EW@ z*rQT)<#Oq}5}TJXWjzxx4C1=bmKVLkV)6uoN}4NO8I%_Uc*ScfF>U-Ty!6n!v=o^_ z;~kxF#A(B5MY07FGANA|Beu0sl(`BdiuTHiBN-V$iB^=LZ23x*tSvy%cLcYOKZM-s z3N)paW93y%lqbVcNKHXb9>FYCk=qO$gg&R7h!EExC8T7KNTit+w3_)*EtxdX_CAVc z@SN$yWV|ZE{NoFq1jZu-j|m2fNedU40U5gr$e&$^_g<KUWk0S(SxG5Msm7MuIUOSo z7>aJ&wMSZJDzchnAgu}0RF2F;;}ca)zcy?lXctP2R>ZhQt_W+F7vYI}UPS^8Xtn5= zhd+%v5>481n<D;6ikoNyBgSOeYTr4RplcSU9B(zt#s7E;cnbU;6bL>-<rVK2En9ux z5frUkK^52c@WE%35zTIieGfYf!*<<?DzXfueuWdARb?yi;TuomFIU`!pYn^)q)j&* zcmAJo&0o$!3-%iUFR^c*dDw&-C$G#<5AUrrv^@Xak7fGr0>z&*U30-Xe*3d0rOhhY zZygU)?2S`UpQe6Tp)|KB?onM{fbYJVfH%f{h;>y-7&3f+958$ca=4U4RF(DLD3_po zOG8h$TzeD7j-QTDW?LL^<ng%qri;*{eRD@o<8O88J6^|rlLnZ|OV?q}j2ZZH;#ZjZ z?e~~DdoGqQUqMM{G0NBvYjMkfq5EJI*W2#7OE2bH$8%jh!YEq55KsU8A9&^MSvckN zGjQzDBd9r~I%;-R`SOOgBcyc{BR|n}soGC_z`DMhlbM=KWmu^%$Jw{>Xm_n%+?C%R zia#nHrsvp`r6$(FaPDyVTJq+j*k(kF6C{Y1;mglH#{CbzhBn*mj!Q2-8Lg?#E*|Id z5%qZ`y3x6obM=m=ZvOtqQ=l<YzysOF*y;_f&g!oTUc+LlTyrVo2{L*RVkaLXr_gdo z{wokWc<02L!~lYB-@y_+Q)2qn6UQW6IHe$C6GAd^?n6#v%!U9fNH^|7e<u-U1apjK zPWfsp8W&D`&oLJRX!5B`#a*c^E_b_koXy2`8OM1P!;yi>Op!_%q!I)V;yMP)T!Od^ zYc3uzN)GFCv|6%2Wa6Z!j4_2c>MC1Xh0k957UP~8kK||~I`wLcBmOiDop)@-<weXz z9GWgzhZ|7Q)r<7t<5&%)rln;lTf7+aK6)Qtzw#myDY5O4DtV@huW($7in5ec<Z>-i z*Wn}3<M5*iYV#1v$)tKO+l900vi%vV=5>;2%9`_E5>2fS(&V<)+x&=cxn5V2+sZXj zeEj+pOnLW5tj{lFpeQn1hOqbH1JHL!H#DcA5vc^5vk`|#%NFARMv~_k2P7IRh)$Xm z5XBVQ%EEjj9Mn{-t;VyXKE!ulEJD+cnK<|6LuutQn;`{cQ!KPvTZ0rUv?e41CvP>P zcb)>C0>3c@Tz})fMO~}+5Cq@{$UfddjVh{v7GTn+@8jZ2Zo=0y7jVDRb~x(vKjXGh zmmyD@I?)=03C`xv`W_G8eJ37$?ma}4nqcR_BXG@4S77L_+tI`xdniq?T8-TIZa~&@ zRNmq>@qXtQ)jBBqFA4mgq`P5y^>f)&D(ZP_0T|c4&YSrq?&P*?|9It7gj1Sf#39Gw z?t4a}d)t;q&uF9)E0@l}bB{m9t&5(*nu;WJ>bWb<x#&Wi`F~uiN@IZ54x9{i6jA!j zS%*%>J86=SJV||eWknel%v*@>r%k|TAB@EZ<A1=);uP$*_kp;1)TJ2QuRDw9CU3>d z<cw3s$}oM(MEv#se;}b%Ph5EUMcArU7A*kl9Z(6BpC)JnuFTS?<G1<-Wl?HMFQAg1 z%ZVyMYsR0&%Wv^5NIYy^l-i`@3_6~wO2WzH)%kegZ;#^BZ-2s3=Ut3_xl4nlSIPP; zKLf5TpDQi%X1SenWsTqXlczwVq<{yqjk4JrSf$lxYwe45<6>5Vv>J}Et0&+JaHlwf z@giO5&`FL!MKi9(Q_PQmRcA6XhbrO$H9N~xZJ?ugyc6pX%N3|`pv0k&AZf>x1b3t` zN?&7Wf<e4y*(`5EmWroXI_j<spwZ8z8iY`O%9~71AV^V|h6C^MdrO8tEHmf)<8@;k z<*(Q@#-UQtUNE0IrmJG;u|-uFGIc?B#YmtkZHP2ZpaGKw(^p{po177U|2qQQD4Mou ziv5lqid{!^quMdUN~Kl<Jf>vXDP7)aVnL~yg<nY~DY1=KRG?(R94wviIlg~q917;l zK}&AYkjnTOobgVhgm*Qiy6afZwq1Lo*B<+z{qVhz+_?op=}m~ZskWA+_Hru433?Am z69I2)5}sn5rJpr<IX->!E6o08J_n{WaYX|gI}F+ugAdpi-L~(5B(7@}O>D5D!fH?; zM6DvT+%X;@YbV~THt|7&4O#S3DUKWmSO%h5{W)Le<Nj-&XV4^^a@ir+ai1<MCfkfv z57fvsxYAHX?Q2Fx*j^MNTT=eVQ@~T;x1@kR+Tg?0IRG*2smV0-JtlGsm~u*5-+K8O zTzKiNSY1$sHl2Im%!@C@=_edQiEIQ_<waOHZzf)S{zbg>$~crpQ_*X?0XUt@T#h(o zPh`lL4}pc-^;8{-`@XF^wEWeV%U?&saYns3`Pf5pTb&Y04d22ISKWxurY=NQ^KLlu zq|<QeMaQE#C9*X%61ZmhBD_EDH9R@yc`R97N@G~t;E<zE!s(|RgD!12i5Rp2J4yA4 zI*cwsGbtZVDy~?WkNNZFAu}r*ty;CAVW$XYem4QP-S!B+oUww|fzQGfmz{}@&0U)6 zuf+%D+!Qla#fw(qtyf>e%O6e00Y{&JBljDGH118Sx@a_^cB(4_Z`IHL>dx^=4N~+L z)V%`q7b8(wxHs{apMQ>jJozj-Zrc|poqIM~a?P$ltZJn4ikG{%#z{0BsB^zXvFlRz zSDpe}JOw<E-Qt_b7trLJ98d@-(zFoy4W)Gg9|QzW^~TXi-Mw}88bPSv=SdTnhF59C zM{8Y)%jhq_#|L6A#z}cEW}q~clyM13)8t7%`n%a$-O~j;#f7$DHdJ9eJ1dMO#Iw?( zF$b;x6kIj1%LFu#GB#y1s~YAoE+vGDF9zqNxJrai2-+lx7HG9{(^nZ7#8$doKO|La zfqhpYron&FjSm7rs;id#7*v$hVGv7YVOCZKMU-RYvNd5W{c!~re76?k-h7AglhC3? zQ?%~Z3f=m3#_q$oUtSZ&<<>gpthoFkNUdQ4Nvy4axZy=H?J7#uR~Mo@e+5=Anvdll ze}ILPJ~j)NIn=*PV&haW*3#-kq~x|jlMcO5%xw&II`9DWCAj4VhD@6jN=nDnkLTgr z&u61>^?KxUZIujk^zE}ff$Mf?-aZ$tIyXg1j%eau1kozWwxAE|s>-U&Jc3KB0DUyO zZ|yIdD89lgD1YMbj67_jfD;vK<`v<iXTHV6kG{pA{rckAi}s+!X0-<=5~4H!La;6k zZaEw1@?D@Vwe#@5o&uf%zYhiMn~wuoe%I>H)t4sFU|l3!jPIsR!Y!lj#gy;oqFIZ! z7`Fd#v}wtGVF}JwES-;Uzy1b`m#jn{pAFo7Zya*O;n<~r9~$x@7-Blq3$p&x^}p(? zS*`eY?>Z1wv)1GHsq?Rpi@1!DPHB-=i{^fZ#~=DDo_+Nbq~^52E<^W1@1CuYsC`&h zuEvkwPs5xAODL_)#CALGf<q2J3VRG0Kww5o_UcEKnDvQ{=ea4^dUWCADD(OLyKnH+ zlTTvN!o}#^xeMC1YKArWOEK~5ndq?1PB`zvKVz4Ey~xq2Nn;(feyw+RR5p-UgZ%tO zc>3v=v1COd&OG-VY_oM&w!Pj1Y4-3vFy0;~6yJ$o--!!rQdyke0d3`Cd`AAP>#~JE zvWzccS!oJRJ>zur>CxF}B_L~ThY>U$(9#<>z7Xx`M9<%%$V%HgPk{zR0S{ywP-8XL zq7sU*LuVJx3kl*v0(`tKs!YI~xnu@fI!S*md67SbV(8vAgr-f&s0gVNsQAU{WGq;k zfJH00)=3P2PMW0xrK!nL?66%5&E!jgR4$A#6Z`J_Fjf_CRjG7*7*1&?5D>S>i(qGN zS(8Ldg9ac8@JdQz_~ffnl!a2cPb(P>w|1$K1d!Zjhi)m@dMg!<@#DZ|&b$b|onFpl zX(?BQmz0rrX^ExSeNc0>X~FQS6W0t?(R%L0Nt6oYQw^B+k!S`(R#DqGiY95*IQ*cN zh9#{!1o_2fNf<jWABCma@!=I2H$hiILOJ^NPQ}mxxg1NdGR9z&Fn3Wk-h6)z*Rtj? zPp;PqGb{<6mRy1TMl?f@4ymYK%koZ{g-P!(!Y5OTX+)zP(@Wtx(Ol$p&Olz1G_-3G z!)ZshMou<s%|=ijrCdw;w-@uVd_^jfL&+4<at$n{wMmr14(<vZux~C_eEA6$y#F@x zCr-q&;-;9MuqRDlG(#fmU6>L@8Q1N$iY>?PvA5BI(&1Sv!l+K_#@&RPA*E#=h8{lz zy$5cMX6>^;@>{*^Wl^))ECyRu0~Qg8G?j~=<h_AYkor!KT@a%#n^13vCIHm3d`2<~ zU%&ph&+*=KU!r&4Zn)siBWMMMMzPqYs)H8EMVPtbNIvW4*?IELQ@~T;x2HhxQQHTr zKEYksq#!$W_32fWrI`2QPna-)K<uaaSX;OTC8bsDuahYi%%sKQ*67ir7kY2g2R*j# z!v4<nt?C5?Vr?^O_BD=!u<zd3ZPd?f{CLZ}7oAu)o~++v9irh1EMGhqUyPrM?`JQ> zigjyIQoM%!U<jGqDyK!$Ty*W;3)^hJJ$m%sn%nWPAD0%5^?Nj)#k53sGs4I8v`2T) z!x{|?HAhg*EqoSpdCHWpreNlbncN;{8H*CbHaqmk-UlCy?ptp~uCB>#%3;;VYtm7D zveHySOh=kQvZX)kyRY%W^RJ^x+ip1F|BgjV8uB6=jw=<Z{TY7aawv^o#R+_>&v$Q% zvNF!W3DX#jJQWwL#@Mm%V(N^=*zd3-vHPw&nuQ3xqV}2wWnlF*_6eLzC%E%xPl3iw z0S{ywcl$Sp+Dj2g97=nC8ov>1;Qi$9%5ctQpA)3zaa|>ug}7umnT((m*N+^8eMS&e zqMUW4`Ft|9`yW||C!SkOoR-ZLDu^!xNTO(-7sccE4a8O*sm7{g2tW%;L%8sgNtil4 z8#T#XYe~i<14&7tQtZ$-0T11?C)fLwlaVroXgU@z3*&&}-a%zzYb0<Bf)K@!+_sg` zYB2KLo;dyZwhT$;#I!5Obf1594MyMf9l<VFSBYsQq*0(6M)Rx!+;`_N?A(VNsncKj zMP&p^myeu^_r9ng-X#!>wImiQW%x?;>Jq}UV}>9*nY2;$6C=o9oq$tMe+#SDx3=}e zvYNzg<~iUh!EuMT!DZ+4<el==w(tpffBZUJciT6pi8N#RD#$=nSg%B+rx)Ssk=tXp zopX`S@S2gYDNn{Vqi5igX$0XlS*WU}RY`(V;oqEC5%$<734ONWetJ~-YSB6ul?my% z??p;r3$i%iNMiGlffMAW5#$ZrJ^@#pyA{*qK&O&}mldn<>A0Wp$i!rnl%*h3d-}!J zp(*LSZFD;NC%ncqBq>iuIRRpNUOQxQV7V2IvNYSOGt#?tMq;a63Ordmz8|tIDfMZM zS_C6mW70rQ1h)%!UHdCP_dvfUiI-PB7f4sN4MX5GP>EKA@X~!B;)}6AV7G&I#9`;| z4(;5d0iGr=Y?6f$oJ77h^B@U-_7w0G_^l|QPc`^l`RO^Ma&>;<0qWn?IY?7ROAexu zDqd?j1MM8pD1(f+1p+(kP1vt!64Gh+Fs^051Z>%WGTEpy4f2y$B^;2|at>07U8#V( zt_ZBy2S%txW1v*hP4>4T)n8;_eO)-wM%Dua_XT7bpBh9V0Xfl>+ZqLZuF_;;yj2`I zM>N+Sdc;1R%TkoSqdxf>gNJOglAiUP$|SC*wvBPCxUZ*tg?B!hh^@BU5hL~<hGyF9 zoMDuM+Vi&qvU(LnM;*#bIr5skw1UP5CvlJVPbYkbzB>=ZzQczhgZ3M&CakMPaU?K+ zUf;_}p<Rml_0ChEF;l<;*~Z-Z4W#a|nktkmTEcx!+aSiZINaTn;4uLU2_8TCvJl}) zF+}>wsx3KaW~c@O`ZYxl0;&+#S86u7n(HRNn;yaJ`2<HY>|?A|o0t>k=0q@Tr))}a z$wbJArFc|IU^R7GDORrGyl)bLn(z?w5YuZz!;Ag<Wpizm)?5-ia=^2`pazq_twsse zXOo$z3{uJ7Z!#HE&#p0a?Uarb#U~I8lld=L62<%_G-gqwl|7EtF>_?6C!*KZDQM2J zNa8ByT}B+eU=i01tykIUN6Wn-qTEDs@x1I1w(FHb>8VB!WN(a9SVBql{7Mv;D?ZD} zL6_FACev(VtJX>A+#${FzegHqjqFMqNLoy(Y)v(X2bw*XbeQE&qk*PQ9TU*Hd8+Yw z)m@U^`OB)1zp9M0^Q4#70dw3@xVi*YMWv`(wG7MWFUI19tGRZSD#kS_D6GjuImO^I z_9TgN0@o>Nk5)|tWT#hiy)4D35lYQzOr(@xesx%r22snmbDJczSuqQ(SABz)?V4lC zf|+Q?s<xy`Uk&S3$uU8g??NS8bTv2cYfouFvp)UMZP;FDv3);;@?;g6X>-676&>QE zQC9DtoyHm(8P#{@S2t|X5X$1}#Zf7P@EUuO9*e(QiQ6w5gVybu;gZ|_51Ab}QNf^^ zWKei>@sqppzn%h~0>2Ff)UOJxu*1;zXWz0;0%E+;cNmxCxrgqFz=pnf7ln5WXHrB4 z*VnIa+4@5H(~q5^edCr711raPR`KTyV*wSop*hxsfKT{RWVDK^hOXj9Ha&9^RzX(> zUjx8PeIrIvZ=S@yU$oP~2;^f9e=5;>#8F;GWzv*S^vrfBU^_`7>9XY$@;Rfj+K&m< zOM!9fwVfqGARR8n_dk4(uV*dAjyv|p4!yT>bz**I8^H>*VJepWukmALAcHVoq58@> zwdcuS|A_3oHW<*qAF{aLtll%LjKxuTc<^65#Jrpjy>zD|9)?%mc?vXE3V0yfSX;gU z)jP6oJs#bE1dhJ(I^+%Chn+ncBWKM^N-MB-eKEq6+{GyJiW0!eAW~XVGMeQyrTSN3 zp_Z(X0BK!81qzD`3BW2XjTpgGj6gFjBZTI(n46hJsi?s%prW#zd*u}oL{^XqGCch? z+a4ky%F4)~6gLk^Vmw5A5rV~1qD}3sS5Z+(U`jqshNNdnM6|hinaIk{Ban1fj3cz{ zTU=VgvJ@jiAnS|(IcAkg^{ghj*~n5^%%D<;`}Pr>GVRieVwRohYWCYkR}tGJUiC~( zO|w~Lj;UDoDijnIp`wb?Rf2XgN3r@u0_hB{InBw*Ml!GYfNITQt7B<V8EUxBNkafZ zPO)2U#gmhr#<FCyEUFdRFIB!u%DI(IX{oh=c&W-FmYPYr<YZ)0YOSppDF0nug%yid zV+FUWSh9F2O11Z3WhDm?R4t};-(=3Nr=$^7GhSv^D$+C4kdd8=j27w0X_|?Y%ox(B zx4ZJmM^X6pOW1MDTS(4H!Rl{lx$=uIFypJwQM!H=S`Zj#lh&GopmsPV-rWB+%=NaZ zndrL1uIRAaFm&KPv1wg8as4XmlFW8vyToKcQ|0HO@q<-@5^x(#@K)=Z&43kYs_~Kr zQl>^|0V#`D9OkJl5j21^xLcEew;r2-cc1(cTlHy=OCCA~u~eqX0bPg_1d_=zAYG85 zABcz=-gyfA`V?@znfjs)KQ{r{04V8Wv=7q0XFcJ^s((6#(WDyx>|56ZrNy)ET_6i- z9`SzAg2o^JF#v~Z<me?%qTWmtvwqU(AVP?8y5V!{4@Dk@B!3gVbVuIoh(>M{05<wK zKf8$k1Zf4&$lIB;v|-ePT5Bn*xKr|VbPjx7?(R-~x+Z9AY~on_Ej^Vy%F6D_=u%ZV ze*<S_byDV7959P6)m&b~`E~9}N6j(P%)LVjYz5=Ft`3$&ylBoh@KL<qsNC`V{K->b zOQ!()6C1*9>E-;7%eU8Fd*S1cKSp_ZIaMT0G4el7!$;TxD8T-@X6Z7FJzyAyTyzDR zo^l#_COyd%!vus?++)`5j~aCBWJy$6N=~MVv6z)H2u9%ya5VvMO^wzr)`e9KlL&+q zUPs_$`d{J0Va+I$wJ=VQRti;D6-W8VPigB=+KLy1)iWIm8-!O{3afBRTi5knP<Dk6 z(y1S|e%Y0F5MF0FJy)8WN?YL*3B;9leHWx(-%r;;*%c>nLD?0jzEfB^rM;=}RxTN( zvZ09D$k8UzwqtO4i61Lm4ck?FvTDSVTouORd+))Tm!3l3H$O&7m(Dh$A7dS({I;W< zY$%#Fi$<5`V)e{fDCBymg0(AX5jke+&@!;BlCC4Ljb>({EiIC!P_m!evj=+aIuKbs zdov#bTfQq%Z8XUIwY?8BK@HzCD#J<O!g~%M_}C48+@Q`tu3jbjt7dv;V>a3qoAuce zJbm{YXy2^^PPytpWVT{Dd~TBv3{U+!{wN)_g`=GYD9*Y2_>Dh#3U~_qR}=_<tRnN9 zvX4`j`p(!-+xMoA(e-cATya6_e}C?qbYRRSV}bNB$G=-UDS7$?2QSrg@KNBSeCnsG z5Dmn!u2RQVAEz40iDEVZD>|@mbTkcknQE^3s>XaS5|~puE)4-WIrf_NYd5t&dZtM6 zXKWN{zNoj<gsk<u3L6iiHgj|ic#_Lo+DtA##dBId<WP*K^6{kPElr*6Mi;-nv--16 ztb?n8E3FluKW^fb7p~aMU*TNc19}IAa=yA#Y)gUX->~e;$~#YiEt~=#$Zp{c)aZ-H zzPe_~QUcjMFyxXe(e&g~9nZAcU3TT<U6PzR*1&r*)&SHAT<JalS-O@B&H-)pJO~r` z)ejR~Z=7EJH~}CH!YEEq4y9Q??56Sv{QlFh|0-Tk?jX#j%AjW(hx>QoHx=jS(hkxJ z;<$lJov$R<fx55Ovzi(iAG1lwrpf%N?!5Sp+p+3}$I*A(CrE4G-X6xZ{#D`lqgTP| zK;RiIuSB$HExvvEIjs0%JSrB>MIt5B=}eEpcY}?Z_@EgVlu*Q4otA}egNLH^pn>Q- za2F)C>_}-XCFd0F2J2zn2!rLcu?Q34fWy?>lsC(u0g)SIS&1n9r+k*G({m;*#(kGP zi&mYQ<Elr`KvEOFj~oHoc*Wjdh3B0cQSn+C@KiUV(T#VW0-gf@H3jsI@w>9#LSLSJ zeQ`elA90R2kd3Rsx-k3@Yro44E-fwlOoQj{v#$*<7^3_X#=^yagFAXR9LK7tnyQgp zEySXy17P$tk}8CooRbX$^9&;K&ZR(FTUw%xd+7Lqqml)y4Xfw!ch8isla5Q8t3ERx zIv&-ndluA|<FE000br>*OJ7FIiCkM7zu=Elot2hreHYE5|H?lqs-s&RmfCw0FSuS! z703>SbdvzCdX7p8863Qf*PS6OiFi8p!2fs(G)@Y5Alo?Gz2VfF{dE9jhZ4x<Z3JX( zc9nhk|Jt1k2-OE;8{hxl1lu_Ojqf*Ao?jAXQ}KRHzm3Zf+z03SdDZ!m%?I>1CeKi8 zPz^v5sCvElw%f4k#U}`4KSgTC4z*y{;#h)W`#LmG(x{5@s4^X+iglEhvetY#0n^7% zK>31&h!n1+1?JUApqh45sx~VPZOl~4e5)y$ZM{`bwCKMxT5z3hUc1gnZPy-2&1lV8 zTMS7m8#m^n0hmBEqtjo*6gP;H3Y+a6OT<b8(s=#B_wn&7(=cen037+}J&>47K+Gr_ zuqZywTiYFV+}+uEx@-UIDc~vazfnLRs6c{234M8jGjjU)>H}Q)5{R)M2-H6nO5yC2 zRCod(edP|6)TLxeDJYZBGncl`)=TIKoy*l-H>}^FMlxXN0GDd$;GdoujYJu#u8>$x z%f$6^wbDirQL}jUXyhoO-;HS#<XHci{M24bm;RQq{qR<861X@>HV*+=rJ+_+T*cFp z5S3HXcRh<Q5z*yu;zSR}9h8N=K~^@_qn6jvBmR!M`Z<ZQild+|o<(wZ^)400J5Pbe zP5}>O8~YourPrUG_WufG1CSJ)e~&8vmU;aaX>Te``N`D>_yO%U6+U?O@6H>>4Y+dr zZ2G${1sfD{5z!(7*);^ReGJHUG|q10QyY9Jp40^8twE<$$M`^l8=jm$9||whh*XSg zd?O`gsF*nuGe3L}1v9?Es`+z}&h43UsY0F10hg^5CLk`QI&wbMoSSy-fqr`qNBiA& zLzCV;5#n|nW*OO}!f`+vWW)i9hD?I1k~Sx?5KE@5#i)y)K>N;3F!DZ1W@*Sv6EGS_ z#klo{hPx)kP#SW&_0ChkQ{aE2fW9XkRHcwKPv4}LHaK9ar1hohZ~)is)2Yu-lT`7@ z2F!Htz>?N^*2ZTa;XYM;$aUderg|cO2k3ay0KaS1Nwi~R{bP7$;nFUO#&~19W81cE z+qUhbW81cEyMvBxbgYhb()&Ae&-JZ+)sOLWjAztSuDWY$N&j{ksGwT+cSNq28LG+0 zwDw;jUDUx>W8Db0v$&WU;5iq|)lB2CcXRWez7nI^<dDLj#ppV_D#!+$mM37Ioj%jr zwxbe)9D(*DN}RfHOe(fswHU1)eP;;FC=T!zrU6TuDhv}$dF5Jih1E`{x<%n<77xv3 z-31FJJgR0-44>5g|N2kq|Mj1C+wL$}&CGBEHD)Q%ezuS_!Ubdc4=XJjFIH}o1zaR< z*pEpm(|*EM;FV}q`%hb}6ooUods+&N;BZwySVIw7Pke)3zoh?7ng`}v<l4B&T%vfj zLhkiEmqn%3G0;N)f%6|M0Bf79c`6n-p$!4Tl=C>^MN+*n*6FEorfyzA+Y{eM!Sf$m z3F`&CLZ?``WePbnt+@`M>TtO%e~y;JQ9H@@V#LXIix~9_oM(@pr%=l36=+amk|aet z-C}Y9m;a__`|E@Q^Q|MSWh`#+|Kik!LxFG@>@F*h5{7fZ69Rrf^e>iS4kE^@@&uBU zAVUfqml;vV&Rk)Eo{n~Sr3J2}`l|7Qo2XLD0mYN8+l~Jg?0pEd(QSDkky9iNmp}rN z?Lw~E-(5Dl#~q+i+nVhIX`B>{U&M}Bp%V8c&`yh_4j4S0yp$lQ|5ML#U;kQu@j!-q zCjOOIci?K8>!shE*G?_TBhSnB+8%8+QRP0eje)V9d#04jMrpuD_p|Hozj2t<f8#Lg zrS=49<|mhdHlUVOU!Ccr1-dqluEx7YPgd_xY!HodLOM9*Z0aS2gi)7$Q%wvFVTJ<^ z(x;M_vcmEsYR^#SQ>IlS*5yV_U}6VK2@jzZACKPExxAqKa=AZm?o7*RH0<v`GhnM8 zS`)ddlNsx)$t-?b<20YP;5m8ON15q%=1aEK*iPYVikD_s9}fw_w&7!c-935SMj$Z$ z?f>Ms`@0n{5o3B8ZWHCMiC%L&U-$o*o_|^T|Ik<NKd1n2>=(qWB#=R-uff%%v~jzc z(HFQo^iGo2qz%+~*#m4%_9*<2_-56FKNljq<<C4c8M{dKo88^_ZRY6FQsIrIG^def zogMHr2?VNYOr{}Jr8PP2vO>`iMZLbygfjk5cp@vcjH-t=a_8m@GE8w)qtyANCjcq? zB2CUey>EJd>Q|teH#{*aiOdx>s)CA*j=zy2cT|n%YSn+#zMN-3nKJB%q{uj=5w!k@ zFDv{1oPuBYTcP=fF??eb6#$KWu}WhYUwnESVaD(t<@#VlzJq}C>|2$0!URm9D_MOf zH;V$W&rfvbelF+3Z;rIrx=viW8;#t{8@xH<6V@1;Lvmz<1!>NCctzH_7ug-DAO^^@ zp=soT4TJ?l>upI7+hYGJk6`X4sal2ZPF6hwJA>vn&<>8ANMbx)N{i?J&^B@2vNbXd zy=<7Gjp#_Dts!DQMefZLm1&kNgU9svJ28IIfH&W?v0G84H~fB7vicSRT0g7Fjr3;} zjxVESHviYHRK;c>%%7pR*KIGI>jd7WHv&X^5!sg|gffrs0Oen&%72JO<(~~!(5^*F z*$B7*_BI^P+v01~^0uHh+E+tl4`Gh^$>6_O32^-_5TzzaItR6Im!?0u*!5%B??6vP zO1d^-E8BqvD7>&opkC72QlPROmDTyg2x4W8u8_;A*@9QeiYi{R$28E|_NAzXKngl> zMP2%+oti39n`oI3@`TS1Wq#cR1-LBmvE-LP<KQHP8j)(Au})rA|A$-7T1vZ?3#}3> z6_%__sOC{2^IT=)oe;S@<!Q_NzJuC#EWl&)Zuvp}x&E!S|4Rl@Mc?IaZJnfN5L=nR zOw$(+zrLP^rxEqShp(KU6oPVvhjxtEs||si{y_sTqX{3rpoIZRgOkq*wIpRSh6`d8 zw=($!B??|t!1+nZcFR(nNOUW0PC}yEcdMz~jgeB8wKCF<Q+XDGjLUwHSbUy`gvF_- zPSp8K>+X??S~x;n2aCgl)uak?l-K)bm|U<}u>&W0QPpO$37g%lE7PS8Ika%qBu)tU zg|kp4U4$F2;cZ~8SH5w?iYemP{0Lc~KnIvUYVcsaw+6)|*J#Tx_oKf2ZUgvn2B1>U z|0W;*Ljs`r-zSC3Prx=tI=BCgOi43jERGwQBo-rf7RybLDMDavcF}U%shqVqx7igY z2Rwlb4k_Gf8>5i1Ts?`YgjSVG)=xGill8m8$Lql6985d9id#}!Qw>BCD`x(CSGPVU z@m!0wme{h1%+cQr4JKFYUY{>p5_L4<hEjlLa<kbDRD)eaw60Kf2Mr~huD5-74diuL zcg~w)PABhtR!e?l6X+duvj+_WRS%eR=aFcTFG^73Z5^Q=A9W*$RzBB7rzd3vi08@w zAClvLfH`h<{-qSZa^3ijuSJ2C>#7f-ctRK;UlO@Ve<N&)i5k1wHZ_8epZd{Ty*Jz= z$rUSSkttb8Zs~&5yMRU#1~-8@XDyue9K4ysm<KzR|GFKjH?H4Q+XHiY7`@}%tF(PX zEOO!0QWTr8<t+U=u$1vQ)ign^5o{_p>0Kc#RyrUcMP&q4GF{}NC;<41Dj~mK@q+Zk za-e5u+s7!lK_DlRHk3G02knAMRi?OS`?Q#QakfuEdeMd2rVu-L{SPSBf0-owuloY7 zVF_D1!`5X6ze2+akq%me$-jWL(FHsI4fqBButcG$kr8gZ@q3af0&Pk_Ru)roBH3;J z?)uo(3yU;u$@@>XK|zoI9Rbu5v+_yH(=xA0PVu^RY6N9(j3a_3Xo{hp`mjP%A&~nI zH>$)a>i8^;QB*a8aIdA)=Adl5hC&KsK$TTtb98p}Vkxb|_()pe#0+SBde)e(AC#4{ zBu-=i3UW><$jBN^y0RzPnP~^6*hv0@=17uPb2W?i|7OqJ+`m3VVe1Alt!*F{u%#6N z9?WEGfgd`MvmYJ6N(Aul#iiOXHLEwQ%>g7(=u&I%HMj=KiYqB%e1Ua9wb6_Xe*-Z< zI}oqnYNLqjas10spE<P9N1EHrc5B{72?=d^YkfROkfkt;M^-UzPpM~#auQciD{0t~ z95D$al-2>Y4Ya!n`gnp^Z6BPslhnUmzl13m$VS>rIS3OHwNg}0t4JcC<!)C2BYD%+ zmD8CX|NHxI^cDYIuSgrd`D;1gAz*Be`~26E0w|p5DiS||&#tyH`_ux^U@5)Q2xQY+ zO0|Jt+iZyzr&{u@Y`MDZY|!G)#50GS5H&6kLc1knV2V`NItsz6&kH=Vd=s>C&I?@9 z@>H_lUGvdSJGosm_`w|uFbRq1L({X_q1kMwb8I3@FE13YXUsl+PdVk3)T~SAETc#& zvPL!ld!zz*XSlvNpVAe>=ib%xO_=z3OKNI)AtKVj#@v*Cjne6S>tikT43C2E49$Nv zUca)z)IS(BZ9g2=SLEf`7f>lEM28#Ni5xm`TQ>S`Xu$Do9|U-{tR*yuRInJdN(pTa zCmjCv7Z7~s8!*Yy@h7(CJC`LUNDMhzUurySJcaT%G=eJ><y}3)`|lc%3F?ATAn%~Z zcv1@txs}FURcEQ2KY!91ynb`pES15{bUs>`G`pM|ltANB(urU_sn_PRf}WSkjj-eU z22Achu>45**{ncB+SdI1t0*zQGriwU*9m+5={yea2|Mt3!#?it@sgsUWS)t%6?$SF zzWfTt$!e}PoyJlZjjcU)W$J7g^4C;HyT3!%ZHL}-jPSCo;UZb9qmBRd|56+Z|K?q+ zCHLrC!2mWq?Mu7-=%mRp4mBo10B}i3DCOpqLeZZ98Bs~N?vFWlX^S5H0$3|$ykS)~ zeZiLfAVztEy^pq{6BvA=CUbJONBs7d%bepg%}SUes*tDL+%WdMSJVlg>o?fbpd@;3 zun12jy;2emA!usg@*3xuxd4^#HdFOFvESbKyG<Cmf+Llr7CD)N_MvCPJcIACVCYkn zEwo1@f=*4X7JUb`fBf$xB`!Cip|My9L|u<U4#BjGXo?i%B5k_Zns|%%Ypng^=A#KP z*+orRA>#x-FHEMgEQqVLx44myUUerbWkqDKp;q9i?I@@WbTMZ1|F>zkiTsyZiKN=L zZ&D<{JYQ$v@I#@c9T6_e4Ph4F2|c9Cfi^RRR6{_M!pZfh8X+0LAF9xFT?B0m1#67L zZwKAVdjrbo;reI@tkz0^;<H&Ulz@;jk4jD3KfeDl)`^BTZkZZ0b<Klb!_D3#>n2=E zb<rD&Y3}0kXX9szdZCXg-(>2E@oQ1sZWcYCU{<qA@vXIF*)Us7KU*k4d%8jU&)-Q+ zS%oZhoR2-bxXr7c>LHDp4%<JKjI@N=>VG}XfhB%tku0E5VWyCqYWj}MDK@d_ndnuZ z)yZ_h<xo)WQk>1!{~j?hkd7iNWQn8(!ftvISi9Wu|HnK1_vDxV=iBA7eNLF=2f(?s z<Um2LYoS*NdOpbW8~)mZ+*{qa7GCD_b}pvY=Y(J9bXXx+jq_#~HvS;fY&1Q9!<I0K z`urq8=l8(r<dr7a=wi;=il4Vnd_zy5kR+&@uIzhEgS#y?@<l_J(GG9Z$BYBNPtDit z!iD9xVZUJN#+c7!$Y1W8Ol5B<Pz)c<N48j%#8<2?h1e@JLZ#J?y}RxkT3=gG<T)Xy z$-CzTHXUxpF~QPYPK~OFtfs9+&T0{=mc?<|?%?;jWJ6usY84YABW)GRZ;qq^qDC_> zgG0*Gm|u5&V|Wp^tny8Hjja)>o&HPRe^%Tj6-{+`caW)z?c-*Opn5Nqnx>1Z_kU|b z`F{vYc@q1)Y~<jZ93H|1+N{Q0+gw);7u;uZCb-@F;TzZtFr7@zIFfIS*T*)^`mFY? zmbl~VUHz<$qRHcQo;UC|4;S8Gjk>GL{w4v$>Ezh)<zkS&Ff-YxL^{OM(QVJ+svaK= zvyA>)e8|cRzg-2qvpr7vEY?%!l_N!oSqMrH2C<Tfc3HeARV%KPdeXfY&OAw!0+HpA zYjQZ??)5z2t?y5Wv!Yy*po8El6Ms!|4mO5BdrmFf$M<d+TzDNSS}dE3hs;BXD3dgl zWUK8E=0sK(az|8ouEp`HHkjmQK&`f_GbPk^VF2m(b;D|QsD#=j?vt0ENu1Pu_lEty z<QMiYnt?U!emX7)zzJHJ%0e!o!fy8bNFQ?OFYkgfK{ynyDN@FSpP|fgz0+imuf<r< zXOjRx4L8t&?)_*>p?rQj(D=O3{d0HGr9yi(dHiME*0P+RnOVyR(TTZIB(+`1-{dbd zM;@%e%&#ASf&Uo*Q9xxm#|iD3gVOMI+hy4Q(-teLfOUmfX=IjBN?Z6{kHXpX6>MB_ zQ1y4_xnq&!d#V(m{!de#0@tnbug^camE>tkDH`X$16_Vdl~TcrP@^a-%(v2d{cwVM z&GP_&muI}<RvgR*yq3K-&e_Pk48s(5gEiOqp4!Kj)$!*B$K~clnmVf&o$R`Cxc_C8 zyE_+p*8iR;{x1c}{%fR`O&syIqXSrYOgTE_FcWa2)ctVgfG-wdd&>v4#l@{2t1{ee zFErN0^<N60M1<rLk%e%z8l><!bENTpmUCex*odJYhp?9btvxS|vU@ltUQ${a*t@X^ z**K@jMGb_evrbfykUYKvuVQ$MI(q&aOdpRrEu<GkHeQ@^K<BGv^hNwAKm{j4YB8%J z9kQE9pp2;&G3BES2VBLQ`kd0wHd^F0ZIxW7EiQS=By#)_l40Ky@c?s781Bg2E?={l zivq0#9fc%ay6&jQtio;^wphE>aDrt{++fKj#F_CcE%8tRpvW-v+ic?<Uu{1JgFN3u z7CaIlt)QeBdF9K!pN|4rpxc%@ZZr8|5B~H2Md$n<jLv6_e`2JMIL80_L7C6^3L(78 z5$}7HF6=lb3)YxCJ_<YDt^lZO=y3N(1=Nd%)~}XZX*>9uGm<t+{~(I@J;tj<xBm!- zY^-cWg%7e9wC~JnPe909?R02k(+Qd;sd&gtW(yl+ElFp0WhCo<<30YRAv6tMd8)L& zUZ{)0a=i$~jj;9O<JDEz2>n2Lh(mH;trK%8fi@3_?_Laf5p&7^fkvuoFJehWG`A0v z`uNw_o%{BHJPN<KTRX_KC8`wD0b-xDq(PO&uq%zaT-5UTp9Wg3hpRYN(}{HECd8;z z6~-EukPa4t3Q4Fp+y-v9^(yYALS`f>bHSgbvVWxOFa87m_&=dZe_!FZJMtCD^|^K} z7ie&!m*t2%-b+QmedcC@=TQ&m#yXc)Kn}Mn>-@WDO)HW00;U((N+$yH)QA-cHO>=O z`pb*FlZQD~p!I|wShI)ODN^z4qvGDZ_aRR+<dwe#!J7Vzzr~stI-6S8LH!Fi<n;v+ zC!EZsNS(*0=MPf^iRdnu_(Z7?gkH2z`uD2qI01PJ21#ZhuOA1w&DN>O2Dfq23H-)* zYIK@WDN``@P9xZ43K7l6SQZNfc$vztYt^pGhb_N^rL3S%u};S)r-aPZAdr)U{z{8! zc|{i0Fr6d_6l*FgMQ0wJEByVisZM7CuQHPt7QI!nLRTk@h;l~hKyW}-EySybE1<~~ z477n!8Ffn7s)T{aae?BxY$8siV3o^vq>T89Vo}IhY3o~VY?vD5dGvq%#@T<KYF<(F z)0Z!0{;l;#L*Lc3;vlmz+cw7);syU1yb1ESRgUhW*!|3W1^B%Hn_L})Um}OxYnhTL zDMOU%n8Hom7_^Ca(Z+&3p>dWilm}FNVF=f4OVQ)m4Y`N_`FR@z><gXccfW~xq8T?- z3{f)X87t$d*=A+!1R<xUQ4$eI475mq!8TKUF%M0)o($FQ9SLj&_a$#pA7Wd5!}}5a zZFw~#Qu2t6YlYH^UIj=xjcPuEJy(xR9y3Fud$P&V@~dL19M&qx%_}_%XoHTF9>MIA zysHr(O>zpkgm$QjKuuN4aJd&QF)xZx1<x2FU5w%ByQzk#K$nRcbm~VlM3fml@dOGI zoH~<E<0U6Gs3NNhy`0Jil$5ZUj%=d(v1C715ukB-gX~6=$T9_y(pcko;_-a08nAJQ zMy$jTXEoatFLh1wNr~H5Zt7(PQ%UDMZD(}9{1a{+%{S~S>M__IavsXa5^YVQ^vvu3 ziWQjuiMBb^L65&Vz+%&u_%7z|Xt&F1nWo$6mmtR<vr6=9e~KY!2Pi0xpM^cNJ=V{t zbJPaq@nsA<-~*)^s+i#NaRp2J+P^>69LN7`#RSCl&uwFTLZLz!BoWN?6AdH>3WX9{ zAg>Z5AC!Rl!jE%FNd1}O7t}NNRKHP_FN6jwh7bf_{%f^-+9|cA#+Rv(08C26^~1|E z$Dg;^`nqDk95e_Zm`}6h(dBNcUXe`hNSs92-m;j&9ZWUR9%ZZoBILCm^Mis#n5m+C za)`Txe2%)GdZM&8C5Hx)IyV}7!x?Rj2?C(5T2TDc+V&g0T-FnF<Xj4|LQYT<xPY3` z85!7GCLrZpml#Ql|5$HEa~e581nnrhR5m_0B`mcjvq<zDw?K{W#02F)WVyC~b9SuA zU>}U;^&Pa5T%9Pz6_r(aHP#S4<R)XZ7+EnjF)}&FZDinyx8K*sl1J+3{$I}hzqD)q z9bI0`B94076Qb_scUg_XN|_*x`n7G!MO+x-W-lZ`9&xITb7iceE1Bs>f9D{<)IfAq z!O|>248asfz8Ch@)ph}b_47iS?P{P_!H6Q9pRpw#E%Rp(@e4BTUcyAcXfjd*WxbD! z8wmAq_##24>Lt}O;^q$w)!ZJuZplP$s@$dbWbY*VpqT6V#p3h!DP>K?K7e2@Cr3Se z#HKAk=hUbI#ZqQTYC~qg`Xj0O%@cL?!dvKLNV0tLn?+%vD?(FHpjTy`X!y6oBO*vy zS#_rKGj|MSh88POeVxehN(-8k<v=E>IVg+o{^YACBdLl}JrQLEuy9H$s4LknGiQes zCQ?*d;H?#oEui~0SqyTpXZ6bH&$_6sSE*Y%O~?w3LuHYrtCXtI3XRK{u31+q3QIZ& zep1n7@Z?d=PSra-%4@Vx;cLop@OEIM6&PK(e#NZ%4f93YR8T{H7X|)L`i%JJ_n=62 zkD-eK!)I5S%?w+w`-Kaz1*=7&aB8&%azJ*H>FyioDp6cxbAhi`KGF+|C4*%G?7;S1 zsc)Bx@{D{u2ms|?QZ^&3`Gn2CDh4>qTm|&F0&}*ZXRJ|E#co&A(KK4a8fSk7lobE; z;ja{4HQYdy<8Ez1$-VPUSaiSIx8iwT8KJ0~AbF0-R7o}({4&4h0{UKa<<|4WcAc0c z#Sj4anIC|OD8gs}gmQ)jj5b@Hjz&x##?6c=H{ufnt%A6?LnEPp3MMKz!AWbgop$!s zdzJwQrhA2|k-eS6&dj^Dw4{nx*~ulr1<%HNogFrRL{N=Z;*>T_KiK!O?d9qHOG;om zm4ddTpE>&G!FhQqX61@_8rv9!xW80L=O@<um)C{)i<wyLFfmOY>D*mCF+Iz~vUl3# zN82@Ng$m+r#PaG0b&}JX>OwIAglP`?p#)*{^l83u;9t(N-fT}PVVQ-{WeEudt1;hB zy&pfAFkZ?dd<r3knF~P0OT^4_VLN+bTr6^ex|KSj1qo%--tgZ=KkbE(ZsZ_8e-@0? zH%DG{Dktzf3==9b<1K^+$|GCrq}53#P}gM;!Kj<<>u6OQs+N~1_zdm&a2};+I(?K( zlMYToavY9@*aMD^H%g@?+mYs}fpO=4@J#+ZoXlZ&k2mf#Sg24yGB6>mBb@Vz?S8%T z`ZYW=dMtlVqDG-q#i9PV5OFt`oJCsVmRd&2+!hE!fv7-`FCY*Y00ImS0<e(@6iC=g zCkvcqD+UrZj(j(TA9QxP0`a^m)^nOEijzFv(>2T}3=%@Z9wmU<ZiZ5g4SDKU6$Zp- z>{2BYXpzJ;v|BRKO`(StU)LxXH@EYll2VjCuea+3Zu-k>ua(fLh{IYrxSp>+P_@Cm zN*>cgrh_ea8u5~^bd*|l;`#_gZn}6fOCAZy3gm-44rLQ{yj@u;T%8^8+5z-1Bh}Dz zXRa4SVo&upw1==0EO-d(;xvhgcXT0i*_9L1opHi~GC|<l1gC{M>;!PuiYS-Um6%1} zyNwdYa&svc{G?JiSVj?1yP<A&d4hT#p{8ino0Dba+`}N%`X>j`M46s@GnA008Xmd< z&)D+8cbW0Z-b-l*oht*_%Ilmc3V)@K?j=j^UdKz6B3)|;=SV<InUQ0q#ngmevzJ63 zw~ElKdz-PzOE9G#tcy}7SDGS8v-=}ecV)rTHmF!DG16e(E-71@Dn^j~BC023lhVTJ zlaI~?{Vg`KVP%e3;BKDm)5v%`uSrg!DxnDwp82OECb<t%1rtWRN%RL5Z3Ls6%oY~* z=MU<0N-lHlwj3#t6ZSonda?V2N<Va>T^n~<WA7>yiyLvXye@xak^A=gX)1X**zSS= zz)+$7%j-VDZ$5v(?StjD@`0E4&ZR^&sF>74%bw1MCN39Oh#2A(mfMQQ?%Ht)kKA~` z>pT<#dD{D&=xAzyAMCn>tW*9<@f`7FayL|o1RUJN31i8I9x<xA*=EwRHX1U9d=5W{ zzK}LrSOy**FT9>4^U>W!3#?VClPhPk%_RI)v4H}=w*>(#b#^0bM&FDmT6ifSc9gO} zTib|vwO({fmoAECFG@tp4#@)5nNr`GOlKNJ7+=wl|Jc~nv>8@mCYSx*f<@VKRy=g~ zr<4Rk*juNyQNw9vp%7-Zw2WAfgv|BaY(fsMi3IdqNccHE<bjjEPerXdTFOuoc+sG? zBy>yVyP-recCjXh>fzi}f@-;Z-mz?7wJOT=Arm=bR7ytks2Xg(PRvaNdvPK$lhukl zXpmV8IW5IH%Ai3n&b6}sF-U{)kUcSzZf(s{sSo&SwLzl**4U^O^=QmQ)h_T54Fsba zl#QFYdVpuA#V-e23G(Ha#EF@5Ke(rM8ctG6$FBUT7d?Lnh)(^RV-B{aQryXeQ!O*i zbV-DfW)~HeHQ<hsAmG5G5XmySWlou%SDh(Jx_BytQo|c&gx%qvu>Kz$-N_foAOD1K z43gJQ15pw2QCCbjN)|g364cnT@N{10+9VVu@9;pJ`FL#z_I51>df?H^zLFx1wIYpk z+-u$r@~EiR?$Sd}50+wO1YtJgnxU^rPzDtr6~Ou{B|yoBLe>A9K~$6>T&dx}ONk=F zkfQFCm8sy}Oj-*-o4y#w_|aCZ0001EEEsgSB~K}L5WA6pCWSXyNwEzs04DdxVsauQ zk@)!W6ObT6>EQbicSV&JNXo<@9QG&ms66`d0eXUhxyh&lk1!>fR;5CxtU8E%%-nbY z&Uq0%j;&U(fk+sbhDWq^@_6sM^84HrRq1&qCI=FD17St7+7gA=Na;ve$a%Ql=dc)m z<?`fX2|%)3R!;!Wh~W}l1cng-5P;i4NSMMJ?lc})r;)i4I7>Ae3r^aSh48lpDu5ex z+GMfRybCX?z~`Vn+Xi<DMe1nSRwLXnLC(O-mC_QPYrZz8-%DG|en^0Yxd>vWYDC4b zE|Cg?Oe!irfIPpNT*~10=&p)oppW-<1oHHB3LT31u8bzE92nhymFqu#-Qb`?p|0%^ z$lX|eFGEo`p^RT(5*up?16XE-aZ=S<Dj+`dMo>nV9`;*_4{RgM8U$ALqB7v6hUd>? zM;JR)(+F@!2`7{s(ZiRdo+O2}n<cqh1yN9CNBlZ)-&fEQP6zqL+RCV*J48WWadU#b zPJ$+95z3Q4HV|$E{Ut&~HGydpTOUnDGay+l4L5*_JAfphV+^33ftn=ka->LCkw}sl zx*v6aRp=1oH1Xh}PFAL_kRnAF{DrVyW;xdn49ZX+PUOFulW_`yFt~u3iv%IMh01T& z3#LDO;K)8+g+~u|w00*#ikBuR$T28jag1mpgh`e7GdN;l0<n}`*ipvN17<j4so4vJ zc~|xwGuB%)DLuQ}mL<6GDt3wR$1qYtVD{zRF9xV69EScw3*?_H;(ivla!&5X6wQ)1 zlWv)0d@|u$EV;%SL%0K|Cy1zfCe0GP+<O!hjpv8?b)~`yuBqlE*zNyg&;BDK{bZDg z6pdLV(z_kJ3IUBgc&eb~M5tMYH3wTHj&EX=nRm=1H~p&i01m&TK9xoW0Yj;{S$lX> z0q!Cq(Xsx;tc#H!Q@p(V^y6Zm+b5H4js2zwDSh4wKJo}KUoC?@Ok!w!yN(C;S@Jbb zzZzlFJk?1{@kjg8L?0d27%;K`>WuJtSYdX`j=o=!4s5qJdJ26N9vcDRR&It7J{#vA zl$u>qT=MU7LRf)B)+X?N|4X>1l?W6}*rhXfhaQE1n<j;x;TAGQl~qMe!-N=h^C!5t zR8I8o=4BG<KL_^ZHp*&}M_3k9n#`nz*lbC%bCq+PF?Z$A516`GSAXG^a3Yd|*N^9V zWDhUbCdi@mCOM$fPW*q|fLxG3qAt&MF#T2xfI>&Xp)@t(rzdPAGgL-d7S$O~D@HUZ z&!;pXJ;*p1#Up4$j`5QHX_}Gg<Fo59fL%;VF6wxf7e-*Wk{Ud^M_}8`FgPXqtUC1N z?lOYcVNt0Tm&39%WFAzsweya>pZmWOVnYi6i@aDabcvtw7YCN;iF`<y@_$#vZn22a zwXbiYB2Y{lNM-eLN@TDLtolUVm6Ex`cmq2?VAG7&I_&!lqj^5LY#h5uNbGUX5=f}| zv|%IL(9%5&ow7+1^}O?~GbW9M>sgo24Vx|qsu<x0$qMHA&kgx@f%ucYPyJ@D#2(Ny zf|`$fP@1NsUyvB7Oj|Y^@Beg4eZqfRy!dAmN$<)6!OnSzng2UA=5>Ld<n<P1faB>n z&D=^o*kn77IutuXyb~Y#v_;ePVV-Q#ww?xV{5HhfUp|RyfOj(TYMp{HJ5eZ9oxlqm zdBJtca*884@SE@d=D|BUIEd(DTRDo)MkQ*#gY=lLhAp!S70sM^B)M#28y$zdoaY_Z z#DyDT^0Es`h@uDM1FE4xH?#_lc$d|O^(6Jv=~3+BxFkiGu8*?m*7%C)RS&!5)SfX( zmuc1a&smmnld7g{9JMzI6DJudWIEf2DK?bjJ$;`OUcKbd_^UU)hMSN7U+3`C<sWbI z<n{>yE0qk0MVCwAgcEXj1h>z2zQ1H&bK;Lzd`J>U>d2u^ZBdBp@@b>0EE!ZAo^n7i zCeLdqUC>q(>yLy7V)2P?Z~NpPJzsVOlQ!dRRV>!J!VS;%T{leehdEMd=K;?fzM|AF zbu0r!hX39SFw|%2e`4?zsk0+@ucMeSVpi&aXysT&^mZKjakxl0L~{OfCf>tvfKe3P zn&JgfhILDh^Ho28#B|ny$BIQp6g|oeW*eIpreOSv%O>RTVux?Hjac#FQ?%z;v(J#5 z5L=n5-n9YC!ZEgv+pNONoW7s$f4%<xp9b;giwQ<;jR$F-RE&dDPB>cJpGeo*#8-~O z_m*me=ZBp-D<2WM8Npu}_X=!dNFjK3lLTh^0f7J7tZg-<^ssNHX}1kv@qH$(0FLsZ zuqndaAbkZ^QY``+qu!Kq4+|Gf{ZT#HE+p9v#zSTZg7M$K4+40H_;(-Jf1>!TbD=V9 zl?W-x#Z=^v`|)au={VG8Gyb)lI9s0nt5#c3vTI$t-*keuS&0umF2;3G!#tZI+WK7s zU^<Bfp5H`W69y4oPN;bO^ol-C1j0$Y+xE<*!SBHF9Pd@xp@B$;{69TKf4+aOoh@^W zAG}rw7_6#GV)`Q%c~LyUROye;2_0$k9TDUd8Z%gq1~N~RuO2NT6}^5YW_524P}|km zP|zuHxF!GUJ>asu9d}kLl1}@+dA&4`4B|0k0-<3<qxNqjI!<@F=xYqMk(Yukvv%>{ zk%+$}z-F__-g9~zaa2Ds-oHTxlIJUm(T91h#*6dYd``zR+-!THuGY8P6_3kh(-hHj z$;)BB+D~wF<CLPjweJCQW03D59seEve^k0#CUVg(<)sr(See77MF#VY)|&D7g3>{} zT_BNmPY3M9ghhExF41{K{Y@OFEL(Eei9kxtqYXUMu3`WlIz6|;<fv}PZ>*dYCpE~6 z`~IapN;URf!zptbiHFyQZiY6So(%E7Q@`MuGlz2_F)IKC+g;EYHztUAP>)KEYfunf zJe3TH!HgcF=8C@hZ&3IrnuO{2)<p<eP{MVx;TxC$QnVe;_eq{f0S1w^DEw!7Uvg0i zP9@SqdN^ie&t?GW&C>B1W)8^N$M?EH`tl!))RU`zlx%to6-;{1r=RGMpJ{iO`>*9M zlJ_}j+FsuSgRRi8Ee$ZJYcZC{&o-uj_I;h)a{YQm4#h%YrS}IC&&!~uqrYXj34evV z1UqhFTCL#^G-NWgLI?G7g>IU4m4R&J1?Hjxp0J~&_udW;$2RQZQ#FWno2=DYn){aO z?N&Hp;;RIJ)xDDtJ&BR2C{t!@aS6CrYUsUpe7R$H9Nk_31HoefAWP{WwQ0_MM?u{Y zHn`Cb5UxrJI2X9CRNhO!JLqtNDDDJZ!MGEdXS>@y^BlsRC{86Q$_Y1RJ!(lf)NM8@ z<`~E<6*Ut|=!HAyJc_D!-&DYW_0zmUuY1)?9Nw?Gr0{*@heGHdmq5pSyr?pg1gHY{ zVCePr3@`dQD>+n`N_XdmY<~_wz8m)sd0hQzwX_3s*(3sB#`Iu%91CDumtP7Wq+Co! z()7(Iy#9cM3a&*KrUG%xt9rLq#6w3De4~Vnq@nOUOc0+O!}q5V6%|d)$j~%hhX8Kl z181uSn1*H|NT%#lD%Y<qta123TAOs?niZ|!Ubjg75v^5eYxP49Lj95e<dZ7<KdoyB z8NpzT$8VEQmK5zI{Th}19S^bjNj%X*YtS)61uU4R9IY%0128qJJ1Dl8#^!XIRDmuj zvxjL8VgUubQ=-<}O}+&J%qwM~d~xvHEy`RZU`owbio{u6s+Y!5Qq-*rZ?g?P!nh(I zKq5PT1Wj{BjNEKa*)B*!NuX4d-=bj!1t+2~HEd8e!|rkOW6l1$?51`_fV~{s4VS{_ zWf=CJN|A+J3YVV&c6*^tEX0<}wd1rwXux|C<4QntJ3;W=^%!F3Q&+40#r*uDPuUNQ zPn}lVLdc=cr5ktAXR8qZwW7ivdF>&iqLVdXD)!g8y?*(*#8COcmDnKww5`GY;Rzab z?QCf1PUzg>5vCYz4-9o}LfLe9<l``U>_^%!VJ>N=X;<qCo9A|6Slu~w4lb1g{kt4> zOj~Ux+%f0K5M&-B=%R4a4&<5Yz_oI$C5~|5Gd^&g9LOTsgprWRL7|tc;U5YnD^e$Q zy`XiRJsjU*k{co*zrV{liL%&`5SBVXHcM0=Vv5A~1MOgmee4%1y+44J8E?cp;gD9J z4Ac&r24*D^)^8VSt<4nF5YFArJWQD1PM7n*JF=Sp9uU-ae?S9Q*EgoTl#P<Ct1-Hz zpg>@whx6Knne`!xT2|eKC`SbB6LjbJSFa8AV7jz}*q4EeQ;BnfKvG<)qX4%kBXkd8 z8-(ane$)MsEOhOpu%!WuU^^faO=}s2s;&0QPSTblTo%<oPw|I%Pv^eq9%t0gOo1qa zEM6}TH8`R|h)5bqw02v`z{a3U!U6Z#x)4iG;SZ^5ZTf?}A5`Jl8{$gtc0q&i@{254 zUXcvTvmbsRYpI&B^R-mq{XPI!$%{Kw$x^KYu?8|QGUWj{M@)W)r92SRlw3TD&f0g7 zjP-Mk-w!YIj_;_@=HQVw59UtsphZAaT-vPXGuin+#J<cTY1Ui7&`0MuMct%DB%)fk zKHI7Eh_pJj?0Wuyc>XzxD;B|?03Q3B{M(+N(sf}-Z-)I>5E5)I+J@IooFVnAJ?6^9 z*b(7s@3Z4+7oqP<%u3kj%`0s<MK96$ybzZkQ?&U)86J=y{n*&c$B}=G+OyzGnb(oT zNx8}2!f;u3w~rz8`xAQkT_=$EWHGtKMVcL-qQSFuqBkqx@u+Fa#>3!isueV`lKiW7 z^_MLCp{pOr+cksa&k70PAz-LB`Uyu)Fw`(;LUvb--+r}tM!$cSQofPl3I}%tN3~-* zE52L<UHD|xP6ES)y-J>KW*osSZ4r>?>2pNbboHghW`4I8G4#1ECdlC9g^qI^T~JUZ zTqBV4${;cSOx&8$3#<J*L!XNu!@2d%ATSQw`NdoZGIh4gW7IU-BUtrH0@R=b%K{MB zPnpzLe#d))n{zg|;jm{$^K><pbo!mAGg3tv+N+-xBYQ05oA$;e!H3`C4~%MHTbw_7 z>Rc<gPXEfXe92*xWP@PilmmVJ-s$^2FiH$?mNLvRqAgP>BXHO17P32YPUU$#_Mn7g zP5kJ3i2w5b!m3EY9&q1bB%?pv03Kl8fZ9P|aV)-nf0-ykddI3Pq=wOg2-g4Ri7wWH zbg*D+Kcku_mq(Lj;$N53_TK(bN`y9W=!+Y{oI9bT2%h?iVYCP<*TA7w8d97)+i>z3 z{8YijML3Ll8mBp+mZU*u`m5|S==md@Ia>`aypTyK)#Gq`)jHfJA<UqB<Hjqqx<_Lv z8eXgoK?h2%jyk4acNS=QAfl~AtU)K2sUWpK>O0#Z=%XjcUd;itR7L!)&0A&!0vAt| zKxAEPDeuk4%hmPJY!1%|MFUNE^#1tsY%l{(Rv@s+lOlS#(Y`+AH1BSeBuewe3(#Ye zgyz|FiMghD5oEs$3>-#NY*#|=Gqkfs5Wn6Si;j}g^inlwsNUSpskUbL_2;dZwj?rk zEL@=wDRg?2N~8V6Bk%4@Jj3DV@8apIIpb3s8aET1vwn}ur+d0un=n9VM^}vS#-$Cf z>zp#Y;6#8$R?C;}>RnO>B-XC}fvU8E4Q{Mh9jA#6qqF%y53eF9C;mCj5uwmtw&53+ zjmxL{EczocB0WTTP(hz^SSaBrU#n4~u!FjImQ;N*u^Sfa^{}b&`l@9!x{9e@uA*Sj zXw<47;Ft%7;-pNH0L1fa48GvDa73)(ku4;&RdO!D?}8mO&el+><a;)r=~svlGUSJ{ zz!ym>O(^ltu@bmvn4wqUu>pa>d-}lxXJlK~bQtebn!KM$gU<nx&0E5vODP&$W3$~L z>T<yBi;=W_43pUK0~~>Hxi-WMbeK<2W;~*jL}Obdt9Q=>3#s1`HENnggG^%Y^9bP; z8M84o#zrQ`j<Sse)<cTvkB0)Gf(NuE5`fPzfXARg4)Mq5k_q!NqzaVKu@iLN)vytx zq^v9GLU}6$JCWidD-9-8nb2}Xf!ymQUNQbf#y}tg8N!^Z)3>)q$^;(RN(%m7JHF0d zh1(xigUh?>=^3|yJVtQI9|ls31vWOYh>86@_QQ0@JOToMQy6Y_7blEBUo%Ym)D_B$ zPU%F{F#bc6I+mE&XD;1gx*4wKmJ-AJNrYDY%SWCJ<?c1deX21nFQHTeVTST=6_7I- z_J<%!Zz30*d#wn_il>L3#M9VBl8HzjU!!uN2BPkA{?kvFGn$ni9wCw#p+KZ&<mj3g zp&w0hNl9#fW}Xs-GM4YbC>pIx4vOvT*OUzsz%@bIgcX2D`6SP&Ls%%9QTozJn2&1{ zXSO;et9aeq1~XZGsxwsn{P7u>=~0c+rwX<3U+osiX_3vD&!7kVrgZF%5^-!scg~pc z@d9a>$^suQD${Aq8_Q#Tg#{u_oaA?rpG!2NTPS2tR^nMT!Jw$O(?Hz$UCP9JmV0zr zWc~EZA+ovRy0M288+H5TBv}<BHi#=lgQ`u%?^K3EoFg2&9!PH4XCbQSY`KxKcPPXW zmxT{}h60F*(=WmPkom0`SqFEn0OZIkoW$b#31!2-u8;SAIYoLILn#Y9^$wan>wwG# z8um&=p+Vvr(JZ1}Fb9Atjw)0?y<Xi&@Z(^Ed5U)^NZIE}2f6-|d;6o_t!;py6i?I( zb9IQO3AK1y7GLom3Ht&2a}{D<tKaD--=XXdsHoe53$#xgGob#bHoqalRcH)u6n~Xs zs8x7dzp6DLKS4y9+_BlnkgbtHl|=fEG&wWS+IuGuH-|ZSremQuiEs>`c5G=f-iBfa z)uWK2i$8SXu<_cA5I>tNjwvQ_Y7Klj?0z(r8$0Q<i!F7#WgdKLT;Yn6fz%X9O!i#Q zwdrs7MWR%W*hnmqnhM1V?xJ99EV?AzaEuV<0aglgR8r%Kt-Itb%xiv8Vd8j5YmD<& z3YNy?UCywX{LWL5C>y)_y8QR%51V>1w+#n!i3fx-AV9Z~gA|KAz$r~?Mc8{h+EbGA z_;1tE!^w5pg$k8vc^o1X8o-`IhSY828#;^YD^<RE6EW5pQ8ejK{lflgJp!obs`oaS z$-2*<!Bx<KhjpCCO)z9p=bsObXUXD%8i|l@I7NWj^&=U0z;QF~?aUE&h{%$72W$j) z!NK&z7HZ>59B4p2Os}Rt;ux-j3kYWkG>NPM)EG~@dFg<;2dEfGa1iA<!tC(KD`at) z8*X)pj~!E|BuPj}zuPURLkb1Zon>|~jt*LEBX9{h$T>F}7Wp(G%S$9X{CRvGPHLjm zO;FlSNdTHYY+-{8IYYY0NCGG)t^=TmCR`CAIb5UBhWQ2p)%>H#ohYzJx*V#>V*&DO zl-X-HFPPs27xB)V@%iEBt*r;7$8Z4Xxe67;Q(^fEZax*aS9HKCIuTE9<>9x@kTL;) z*fIk&5cV-F>zobYL{Kb7vRR|$RcUY0xt`bPC<WLS0@FT;OG5rs;~({$*CiA|Y>~5a zweHMhT#99k^*$HMbUcWiDiLq7vFt&ypiSZvO6c-A)1k7;qz!R@$t0LMirL#v1w}<2 zWgd4)&#vompM-4EjQdOPQ+1GM6Mx{hyAxwS=ZrMh^(G>f<&lUp>CXLTlj(2H+w>60 zg*TsU&+~6)i5VBWu>EWN*I@mS<;>MEP$rxRXJm2zQMq?irFi!_$96b_V2wWzL{cs^ zh4t=bJnb-~PnTSD&&+9kr!L+QL6>?nKP!vh@k~D`$*EwxQMcSJ);04IbDfH&TEH27 zBq4uX988EBOuGrFppUIcJ7W;?O9~4dC@V}>AGV#)hewelsZ1^<uJ>JxuIunxiJcrq zIf_sr>-Y~%-JCZ8X7DH`L;ilX446ytv%p$_5!Y8mG8u<4gr83<x02Lw5!q@NWr|$M z-S0x7&~j5cSW)lk$dbD`V&S9fG+kQROjgP_vFa(~ds+t^#ejto*@{5}P>+yXO=lHd zh6%LU-5gE@<ahEokf$Bx08{p`Je7GiEsD(VwYBK9sc-lm8gkdpfi7!(q-MS;g}u8X zP%`&yCm0@c+y2FUyiH0OMA6)y##w&JE38r1A0+v!VT|$kWBuTe@yHAk-M5p@$W={g ze|c)N1cnntNEV7cop=W!h9BX9c+{-gE9?0cOkz|9X5GXC8`p#Bpsc~r?*9l=o))HC zUmu?q1u(;+X{P?IOn$tiO9B>3p)hz4K|tklGuLPY?oE@r#n7KXSka;J-uB8{<U1nq z*@?}F5zCc28q71B@D+DSK`}^}7VsOyw5Jg(`joax)nRlkz0@y2TCr4V9&c1WfjWJW zbx%=tCQ6)nprP6PGwlzqh`r^JmF;2ZuTYi^(TglSU^DXm!t^I!t{$vRTJ|p}<L=<^ zi_qVwo_&hOFSF0`gnw+cqpHv08mu6ng<wVH7?|`!rgIru+J~3N{b(sIPtlxy!v3o` zu$BU?#9Q7HbsRRM9Huz(OBM=xdp;%oc3S0&nPbXlGcJyL$UZSwc5G}hU!v`^d9z3u z2y?bc5>j}+Q=3jhD(XuvlIIoAER>B*FO=@8;1B)XVl1cXlGA&M*DnTBfPC8?jm0ab z=V2PM>2YFUxl)Q|KtdWrhCBBQ74I)3n6(<|UktlQd+c=#SSW(@fg#Whajtx|i3V=P z=8kte59NSS<}&e2Q|LY0OPUl%uu>wJ2pzFlFL}P_KQLGx8+h~W6LJtqlnR7R$rM?0 zp6pM^?_$!+6LCAfq%i2UNt=b~)sxi8K|~3_pmYh@uyzjPfw=2NzxOKG^Reb``sg@l zu8Pe<07l&kYP7mkZQJ}JkKc%`+1{g)iL%xng>$I$A|yDb*<-<ssl;4)?}ak<Gjw|{ z20|?Z#J{o`C_#6sWA{)F<}z#sUn2mMXJZvpRcW;G{;<9JnQZoy7`jdkCg!G^U_r%# ztA<nk%TRL%?z-OvIJ$@+pp6g^KUsnO2GXd*kt#@uJV^Xhha}zV0B1Y?PH7b&735@3 zcDE*31~}x8V2a(QY@ry|ZUdT?WHkTJj9)#E$d*1+JxXQn_A5l6f|j3q1{PkXQ85W4 zZC6+%eLVNYEFya}qMW*+jK51)Gup0&g%L-sYbh~3@xq3{(KVW1^ZH&heH_PVmB=St zYmqcVA6i(s@Mu2raL6=QZzh0jKs>dm!gSqp4r9G^-NJjNsz%l|bdJqd63$0sQZf<S zi3XcI0{huqHdhuk3kB(S(`o1uPsi}d8+57@Mmm1)8N^($9nR>pTK0h(eNrzYyr%UD z`%?J}_dJI3v}%9$S0Yr<pf88ie7F|6aOZdZnvqV(#n_>X<M)eN6au1ZMBTNJEhfB` zS2tl7ihZf6{02tU>5#Y~f-~SA0S(m#<XiX{jW8Mhb#^*iLYU&#_a}b4){(ZErV$Kb zoK7%AoDwXeI^!g!n9ZY2k<_5~e+bAjU7f0%xT1AKxu`P{VzU&LMnEC!u?fbe5iF2; z>-P;l%0u9xI>pME?_A2oM4f7G@dzC$VRC+Tfi`CF`7>AGw2W1j-YCT&3hwE2x-*;h zwEZS=wo*qf>t-9vMxiXl_><517}ipyFQNN${d~UC6{dNm9}dK`TH~l;>_>w8s2{=5 z&JSX^^JNy!;j&n`<~Pqf-j63+uN@uWn~w+`(U2)j*sr^jyE#8!2gg75^4p;2FgdfQ zXwoN>9X;|X_NAW`q;t`Qt1VrYQ&&uTQ*9-Nw0CL2@D$SN&u6Hb4CO>z5H*<}9>Y{S zSRSD7HNU+5#;vj7_EaBj7;c7uF`ko1j*og$erFp{%|)?B?GfpuX?2Uu@O<c4x-U-5 ze?>|clMO1y!W%CS5eGv~3=N5m=hA9RrLsTp1H;gk5sfue`W{W9HOim&93G{G7fkO* zM}-`o)Fd3l@h0rYE>>u6K*S*{2qbBA^&*>#(`&cNkomCcWnOPr!&279(N1fV_|mt_ zaOF7^Wbf3q<xtAHrjt$-zy}mVn^sV@f2Vvw5`qY{GeBzHh!oXzqsnAbPiC*lPx^Rt zm>xIMmS&bQ*2|Fq-nf^zUH_A^ZRIu`URG)#97^uqr{_!JTzO101HDe;D$CV68nx9{ zB#!tVykUwswW{jPBg~7zBBngWny<3gk6@`psDg2`G}-3ph8A6>zp9-OGq&SJD5Vgt zz<K%Aq!h3f=l#H|e#W)~>YzAJ>1jL4DJ>y`z6X_san-J?Myo@iD}PB_w#|olTVEOl zD!?|c*#d9GJn=5S{fnM{BYANu5<P8vHOX5d#zLaA_Y0|14^mk93nd|V{0kgh<CY^N zOlYF0Rzp+<C$P``Z;I18)u4jmz5><9mRJ?)03t>vMH-?4tT}Y+ehi={;(_U^g#2(5 z#y)A74)1WOO)r5MezU83r!fOM+sV?J8wsh_2<~A6>S^Q)Lcf(z+n}TV#xLrC)L<DE zq5j^;DkO#-kmyr#?`GCi_sp1pVu<+*qO^WHrbctT*>RLU;pD1M`pW--8S7(-e7@NX zPI(>e(wGX|w3?BXVtW@KvKX3s@S#kJz*?O?&G~hUfLD%7`1Of@EJU~ONO+Fvq`LfP z6tF-cxBs?I2JboKgnpY)uJ@he%ik(2CFIG}3oh=d34d-)IgTp|&cFG=rfKV({dn&r z+Y#kH{I=cESTChKcQ;Xur6fe&&7106_>SecUIyZp9dEhw1-jZ3lY8shTE2vC<n@}e zpCG5se)^V+rQz?!yDf>qTgx>eKnV=Ao&ED|N-2chaQG7X=9er|8(G5Prg<~eU!~g& z)#~KP*$~kj6rhC5;A%)AW_noRrduf<qYh_3>&D4DCa`=ssV8E68#qLfXZ7jYc3ir6 z-mh0m_Ik&rhHr~ZPHak{$+R?$0U<gG8!{(PxCbw!BPo>pVx|%)LobG(<=m9Uu_gyF zcgg*tXRA6iWbz>%4M?~5&|F<TnK=lYL2zBb!ASLb*$<<^8U4F(dyWj*wou6R?hv~d zz@r2o6P+3ZPA@CE?&GVc9e0yev(g6;tkoZkxdsLnGqXEWo1yn4?n_KB28UgDk6rju zNI=7k5AJE`ImPl{&PU}#2nlkR+JZHvytE_9d#+5MQMY$9S=Zw@L*f(POJ^!p+B;k> zyxMVpKOkBzS68_3Uno>$2-X(PtP)@Zh&dhM*ywl;xjs$ikLf4EUusKmozp|KXy#ew zw3NoM5c>Mf63)Y)cDi5B6c&Bwwz*9{-JWF(KN+~lx+2M<R}5>kt!@`(cxs9Ng9UJX zo9nPm0yIRj8B_PK{@PzE_DrnoNdASwNc;XwoU?9+p!@ck<zb$&ntLyK_>=g4Pa)>u z$CLg|^d_e`e>)&=l4t+6eTqynkf&(To+uyY>I=IEYW57yX04n$m7$PnngnsLr3UZb z`lZ1KNnfWSo$mEaSodk#WOp3#yFgk`OVOWrn$ib$MnDB?UHDRuyeHL9Ud#Br7m9ze z?~JM*)Eh}2a@$KP#hS^l51H*9WG1HcFuqW?6nY+Y*@chSg68PC#&7HuOPGB>l=`AE za_evds(N$<Dx~rCyYEZSg&(&f<g`^RkHl%vtONC$@tt(PWZVb1u}SH=@6~6k!%&#F z#h#z{wf*2>)i`cNnyyb!JUXlVg;AV3jchm2ZTT$lIAT!L>r%ALDlOOiEF0}y0&mFG z`Ps0{9VQ_<nEnrQ;;txDgBZV;@lUpjjFO5yu63Kdt4@N{Mb}|8jER`(tmr%mL=O5T z(mt6*-K>jJ|2~_1KX&Wb<B@)D0kP#(G{%*H{~rL6KyJScJ0kCBr;>?vI_vw-^uPlS z(6L`m(*p1W)1j>lxMqwL+uj^;BE1~V%CVzADeZR>e8=VWC#(fY@|W>EZwG-~1HI{K zj)Y=o<5D0s5=KSBhGQ_&Fu7Dm|K|~{o1Ugk+nu6|)&m05GG~Fj=PkVvt8(W<@*$Uh zsT{7{{||m*GL{sn7Xx*zlp9&;%`$~T<H%z9XWK#^0Av1F$N<Ay9D1_;89xkyp9IRO zM@IxCJri08cC6BmM~~1Jd$!au6Q*l{gYM{!Fj&KivdlD#ajn;Nt7mJ!BRgnK=#}A= z4DEWxHM+Pcsl|X9MY?fTc&48KA5nMKES#aex^~nCP508*-XE`POQOIGVG%5fIC0cZ z<1LX#+*q<yON*E4?bn{K?G89ze_4`;@JTIY{(ujwvnvbC{O>zzzdNK06xr&_Ru)}W zQLDwMEJa_9*Jr56e*1%~nD)svo2(ZW&hEiab*BLNY26(gN(wX(0t-L+NWW><Lf4KM zZjGl&O`FOn%SGU}dkT<EP8jk#Z=%flOhv#R=@Gbq0$Y~?Ui;ySAbyj@=x<^sf?G+Y z@aW0-?4MjX4@JJ9RJ(HQ7h}HTiWlm#U&d><j%_q0vyndf>U$6^@r6m??&7i4E9><< zKQF!)iXmNiKGFH#-P@M_64vG}!YcpfKUMVOGyO}Dk375p7t#j`3f4gCS0BHl$8~9| zm^!WLSiHLHo_p$5S6!nw4;Y{=nzz#i&5za@^Ou=GOel`9%nxA{=ojz3s*SR<b?9qj z6wo*8DC|0cmr)s)0yFvz(^A)I$+GEs^uBv&hNNmZqnSSa;S^niV5B{H8HezmfcTt@ z=V?*iQoZW(OZ56%|Eakprjlzs1|<MNp>tcDXpBlMm1HW*j33o#(Q>`{lC!jJm!7() z7>XWnfG%tC5>)86TjvqMF!hnFSf=>BVmaqC>BY?9oBM3V(D}Qt3YwVakMAtijsk@1 zy;)fy9hd2QFF&k1WoGKG?Rx9tJjY9dEeCEdTlmAY%AJp<gIn%zh*y05GoG2KSJC<C z4}jS-er%A0ghV-^pXJ*I#4s4-4Q%;zX0Av}mpjms-}%OfxajYzv=+`h_<g;`*8iZV zop7x7zU&`1kYnFDSPtCE>JNfOON#*~3ijn`!LMIvr(J7lN+hf`8@AHt-~CLBnHJ)3 z0I1XyW`IZgHt)x;wd<js^qnuigBt8OjbnZAjdg*Ft3^XvNCb7xm5F>^@bj12Ag8h3 z|Il-~o-i4XI6?bmJ*uh;6xpg$DhRjLD1c&&%ETIDrP@<u_cleANbn0AQr=xrHy`>2 zt~yfyY-FQqJS9tUaip+l;$;11zdd#JlTWdg!?hWHZ^pYilVpd*9lRpD9LxAZzOys; zRfHWj=RwA{R|<Fq()B+aRDps60n-=8DZ5+aRCX^ft!%R>oLR4A!Wv^yOr^k?uTwvK zK^xa^pu2VGslTi(GAjiOzq7nBjEhY;1aI&3GhwdGmtQ<rhJ^1?<vU|myedZY{h6Yl zs>`M8k^Qiw1(r~tDRvf|Bo)4BfiC!QqF&ekY^`4-Q&Ykz+OSb$-F2@v+Wq)b_3lCU z=%8D!*REZ<XuCuE>D*=OV5uR+Xr+SiOrWr+7Ulh<7oKyvw%P9}T@1@L3_->N;<hR0 zE3?i*Y>0tx#2);Mt=2al8>kJi15_kbQ(GP0SLYXi>iACllT^Brg}QFlT)pAiTeSb> zcj&woYZ24s51J~%IOQz{#ldLd^M&XdA@cO|_l9YmdQJ4<7shA-k~V8Bzin5J_y9TH z3^o3^a#!wG8DSTcVMtFzD~rpSj_@Nm4+N=XN-h-<FA8toXD?0G2`Xu%@N#{B_~Y6% zBU78SJV}@2vn;q8!Mhg$_bqh}S3i~yiTBE`a=6Oh{-8HY+@;LaIA@`ZZtx&Aco`-Z z0Aa1{y0XSv$BQBOOIq3kp7_qI?1Pm>)<-I%-glPs_<H?z^fS8K9xZjm<T<p@qON&d zu{aI}m0H4b7F48<8452wbdxsC&d^9WO*<Zaj{dwJmR8QBK)tZw@e+*pE!FF;x<W6z z<52|*k+MsjxFusq2bF=wUMjO@jphpy;>?Cb=_(z3*#&ywA>DQA@>OQRW#9yqd6I)L zs^S7gwklK#!faIvSOu^Y@kER4_%C$WKCQI)n;BNHt#G3P@@@@4m5cjU%|?*ee?b8@ z+s0G2b$DQVTQu=&Of7~Y`@|Dg9yZHvD;WPpqCu2xLIKAv{-V>xjl!RC-|u9%306U( ze@P0k7_z<b%AgZCoruZy$P>LROnEp8TKM83;YJ`7&?%@RE-kwDy;z?fG(a=68|fn> zzjo950Mw=c8f1no7gVih^ECm336PZ>)A{cm^Fs&@ivNVW^C<gPF&wdTJ+2E!S=)^# z@&Uqge2uPN@U5PGbQi4wD{NXyj;7SyO<y1TrB0tSM+e?<tM)y&uU>KKCHm-)q59+e zm0CiD2Y+$U%S2y-juq+rZ{N{9cWthNp7_A1Sppe=obb@wWX5d(6yfM-Wp&*L0TycU zvahxC?loaqf<T_Rul{H3*RUf~IcDlqcJuXt!GrX&s|M=oLRggXjr|b+jn{aKK{<em zjSp<A93{y2q?umxHE;Dy?bvE>?b5xs&R&Z&i7XV~c$DQ~dvVMV%PVdkF_};1#$J7Y z@5QNH49{u9xbepbOZs|KiOXn2QhAU(KPJNV+~U#C9thQkxk|_VXNc~ZSxcL>It7Ck z4iA^Ej|_rWbLZ#8(VA@oXhISoqx{Aa!t%&xr^GrkyYfke(hF=9cHw-Oe6v5#!%Yw7 zzz{ADyuezTSie|%bl67^JL*K8u_~9P7<HEnfkQl7%46~2$9LXPhgdI)R{W%Ab=z0d zai&!`eHT6Bs(Z8$d~{QbfmdR^zCHW}J-90r(FIGjgj4%@0W_x-+h7s#2h14am9kv~ zZd8O_LixIE(p%cNK|_7yt%)8TsDww&h(Q#q;sQmsDpU%>Y*h+aow5}1gaTjie;?>D zbP~l=e?Z~4e|&X~9;$;q+b#I1_7ouRji+qq>?Ns1Q>N%dtdU*))DW*x-%K_cK5*58 z0^}7gim?<E$#iz^PLT~5Sv{Dz17XRsNb4I)AjNb(v1Gb7$hAqX$MMQ7!&@;$p=D?) zWhle0G&3YVVp)VHiZIhMS5NBNUfXo)uJd7*u=SZ<`^NN~U{8;V>CoR2z<oo9^pH5e zGSrqj#&eK;2!z7)d6j>0PYyci;ZejQGniRWaZh5pZ7hGT-g-%Itq03zI<}Tc$=pS+ z|L2P~h1%BYQ$(d=2Rc!}CDjO@a5-pTZ2(33M6M3M=UUxqr&c<CKBh!^sZzON_)WPo zORV>icriz%6vkooNk$jy(AzK8Y)o+uhj!AwSKgz`Fm<>T(2EP!=)WHus(<@iUtO?l z1r$*5pLAecjI1%AOq(nI5?nt>Asv2%Z&qK^NT3>E4dTD9yGR@F(p=y83TtIaO7frI zw;M;SnHxBdnB=OX7Ch+ZUE~MVA-CKEN-IAzPmB&8Lj5-$y6}L202YSvk!8}xtn7TD z<(rC&1;&j}P-x=1LO&Ssgf>sh(%oA3wl%U0MOBC8qGEWw{GrYbI{l#_Hw%m<fcbKz z9t0#kPzjtO>z95%$Br8yu~{%lbnYKv)3wPv(zz0CILJeO;1k=RvQ(hT(&`;wt24fM zTeC2*bj_{*(zR%R9DNN9hZtdU0XVS)0JF?;P>8QkW`CXfzP4_JDaN4;4QDmc=f-|v z<y)~ncJ|CKwQbw>`s&;7W99@?NB!WGWz-#m$V}2|3*49|=90YUi<KuVBPd!qS&upN z0PTG8mAVeZqAfOVYp9tiTvc#^B3lI_1wpnh1z2{i{IX)8LgjxjPM>SV&7P>py2{EB z4C5LI3%zxb3{v}ZC;(Rad}V{nseQ%YOw!5wL6LoO2pUD#*lsfMpcrhDEZd(a7{$&U zh*4N#2X9KOtvlnIyX_C-0HYn80wyrB?3JK2QgC+)SB%OGgie-8DxfhGR9heESsvnM zePDP9{`k&KR5-nkLR>P6vW;ndzs~$zo7AnT{~Y?9uEjT6DJaF^(Yw4pjo<8#y;^zy z=HB2%Unp4Y^{BkjpKCV>XUm+QG9eHEF2d!-XU|m>_K7W36T`}j;-=NY55n%GaW87) z%rKPL6zoe{LtAt_RzLrBDQJQin7-@8TBw77&lITW5N6zH!937+J@ozs+H=3wdf1Vt z>zu-3Q<(V8lx82XD%}}}YB1sE=?@dfXosc^H4|%Pci;CY9Y1fWt}9)uPY!udPsWB) zv+!=XLgD7LMj&XU0RR*HDO_6~SP<Ml;NpSp7Zrv?zW)5_aIKqDM{j$^t%0^i&C;(D z!doE_@ipo@)V+K--ncf{^lno!xIP@}Drv|v!LY0g$S!A#(yC|c8OcXaQL$hM8pGUF zS_GpAh3$cmB=}F|hGl_p?4qK)Tt688gzk}^4Mp~}O)Ihp`$svyJa0Jg@xQ`%`9fLt z@<@10!!n9zkjqMnqdojdUp5wajDi@6BnLwBte&t87DL9tCu>g_j6AT-u|Q|`oA`ov z^2@a$<V8L%)+IppW;XGTFeS@$$ZZ#CB(1T&IP!B7pWy3CC233ecq7N0qbJe;9^`d0 z4&KF9>FbXS)P@<@-#E2~wmtl8owi`P<`=BhYcB7n0|!5#>wzd`HETb}V1OW|u557- z%ZJYVy1^ip7j6_4EB;BZyYxJ**=Qe~I&Za=Ek`vMrz*dJB3l(I1!1--1z6^-+*^f! zMfUx1`h1|sZdD#^v&1~+vyEeen=D0lIANkr-ES{l{Rl0xY$3f?aYH0G<Go?9;C)+D zz+*CQ=x%`w_zVll?3Z8B<!`)YQ!ckPhC%v&H430zF)I;DWVBGf{$!MP#pX=)Yt+%6 z$DN^XeKZBu0w-W5W9v1Vw^-kP`DyKS;z^oaBS&l0tf@yF)l-K&H&Rz%!=C~O{U*pJ z3UuY7AN8giZ_!!5&bO&^CLu!1i$ZZUS<Y&J|Kt0xRybj>k`D)apcoVvbK0`^-IAgp zS(S_VGzk@VJhLt3MPP&nVc5US&-^LoIx981WFpO|rpQuRi7nO3PCG*DU`lZ$l%k<X zb3OTzdvs~3Z5v||5Zp~QwD`aiQ;2Qqqu0k<GRalCbj}CbC{kDZUwN-CfyPuyVVyW3 zzJ<ZPDvow1wk;0dn3k-Yt5=+KxbonVP)1{Y@cD82$!DK{e?4_&UNO}zYl#?v3S10_ z#F|5*OxNM(9xA@O_KS)dcA;MVjqbfmJw2iCKb&I0SQgQN+CF~Eu&;m{6(d}1icuz$ zm?|DG&DZ&}f6=?|9ITx>9i$mq*?P!<2k1ZVyi@a`uyN{iAujgO2+V>55KvM8g9Ff} zM8$Gpz+SF1X3o^B2Hc_hwr#7~*|qe9<4@92Z@ms0FVXj39jeVTvUK-$r|Tk&09iR9 z8b&z4#{ZVOjiV4M%MnU3aQEHD;ruUKerMf_!E)-?L4&};XWCjhJWG?_xHu5NQkIP8 zYHZyvI`p1fbl1j>bdMG-b->Mc>-2>y6#HMHdZO+{*XXjj)AY_;ZqT;-?yo5+Y1(qn z7TT}x1^U&rnYz~M2+KRlB7q~z_|?*N^R)j7T{XQ<8=dlNfvf7|G5@?u#T&S9e#SkP z1)mdCI#CwZul!NZI{q+h+=e=yT3c_t?G7FJ-dOE+!nv3do?ljf$_%^2!F)Ms8ji2t zjh{Hs!QH)+Xe+sU^@~s3r8Uwr^ubrhDQ1|%&q|iXsmf2F$X10)L71&d0V~H$(JJKT z6<G#hB`m8Y_8k0FR|=5t#!o8%_(4lcnX6>REFHaHD_!%(NCbd?pvYEN78~BiUOcgS zo9IH8<`wCLBf9IS`|XbznG}Tr7f@j9Qoxjw#9BM1;-HQP={@({t~Xq9q1H>!(zJ|* z+W*=?x(rGWh43S~cGez8AE$TRahJaGpO^Knf!At_Ms+d$E=}8Y?x~+npO3bT1sfZ$ zP%*$`2`yUmgQ7$wjv_VQ?6REtlBI>QkQT-dXG#VXCQj+&Suhk>O<&$3GBHI$^i&0+ zLmxD}J}eW236ok0{4E{CVcX0)Ykn4<3MO{@T{la6w%-HOiUsRX(=?R6r{4U;2w10) z2MWSy#LWPOxRAF!0h;N%JURsUak-9u^<K?@_2|w=hifj{dHciN(k4z-bhIK`Tx(?T z6kUlOatCY82&NZ@v$fftoweI>=jd18PRHN^Z16sgmJs3sZ|2UZM82@kA&N-9oF9BA zU8n?Nop0exJ@trA+I;_0bQy?Ad!*5;ia2k*V8{ra-H;pP)evO?z;Qyw`3v<q%znE1 z>Vf*vCtvE?-1S(`oX{VC{9dnx1@4&RPt^A(&Co&+gX@uv$5Cf3B!78CO9E3y=l(Q7 zuehkM?tkzRdjI3k>4Jp|P1#$zc$xnDiO2N%tIyPjZ@*M`O3&1$ZBEez-Wpj)Um}Og za5QYI{IhWsAVeOrOn@Q&1)u*0{3h`*3oO3yPWb-a6?W#RLRvtO^?@p06xP_><#Y7v zb57PSojdE02L@@!7L70<l&-t((^W^jKUo*fo1?efdW-JUuAN@c=WKoa@h5cHGf(J= z#~h}a7&ywT*+?(H?LJ*u#Od-Z^)9;<o>u(wwI17{rS8<Ght4Z;?S<8A(!)Yp3Ab|X zY8eJ4P^MXDF<b^dqW*H$No=i7{&=`Hual1TvJtIStDf%FzN@}8Zi?mu6nkvu$=VT; z+K{ju`WPXEbFMu>{bJeS<Of}+pN|=)yVcIoGY9-b*BENR#&Gmw{q{XjWPh7J!Pjj- z0jmQ{m$d;`!3Q7ev#qe%)3-CNg0Y;N!)Gh={(Eq*))ZiqYU6NZDmw(+tWzr~hE;y7 zCJHcd&k6^BHsLnoy@`;4*S4krctze?UB*u$KToF~(M6~1*9M9#JHWsN6xhlXz?#PV zg<omc_AT_P+lT17SX8Hc`kJ<FSQ`RkL^EnN(UbdMuPs`(*GHduRTr;;#ficg6xHH& zv-R3j57(Md=0fSaYR`)vfEWlX4J0)Rms}TWx)7}pP(*3rH1U>gmR<OP@aP<$t!7yL za8K}~^2*(Tv4IPfS=*4sB*rbF6B8?k%@k>W;e|;Nu1+#}z_lsR49cYO!;AhtQf``X zA<oF1t0#ACVLJn-gt3k;r@7wu@;k^gB16HWP;Bdh5tX_UcSXgm?BYW*3QJOSiQYco zOwF#_TAzLUGZXY}+A49W5T4J!>j={$unFimBB*fHbUkplnwk@i;B3tLddrZvHJ9ON zy@i#V7G}$?Y4pAon#kfJ^Wc1X`7fOEOqG}Gp_8Sv^_IV%p_z5}(dnxT&6-AXZI_OC z8EzODp(4v{aw<HI#QF4tVY=(iJLyH&-J^@JXpvc`dc(3@ls6woDus04&VSRN7Oe!$ zpzKo{Vg6AUNDm&FH*Xe>n`+-mo9)(KM}0iWj$|=9f`Ybw78d!LQ%387do|Q7C}Yjq zovMqln{*jk{*&RjWfa^vipN9XN~@`_WV#szTLyb`p(`q{R(E{HTZT-kLB0_ig_601 zPKk0u>*+Fm_1PiXeD}6G@y7)kD_yArPTU{IMMX4}va{~I$HChD$nH2#`5gV^+c{cP zY?FuqX0`q_@olZ2!ri!2H6>?feR9-iR-Rdx$%kY-Uw``geQmc(UF~}MRk|2y+7L0@ z5u5IBHQJQ}d?Q|N=!QIWYi|v6d`m?0FebN1U%G#Q*1%fx5T@ui+`W@doVONdCnK(R zx%vS}^dQ-BcQE;dfruN@wFq83P~zur#%P;e>TAay=jsxe`uW)c^Hv2HD6&-`QV?X@ zP{0a1k}jS;Q-^jxQls;JMFqpg5=4gu9d&~Ro>e4pI|2oqxMb}e7+c0?HvVL?Crs=J zIsMD$0ri$0r}bB4ZGNGr$hO5aV~S0I3n;KPDS);omZvX0aGN&8kujsOVNXeNoqjQH zn6|8)X;V@qTvIb@w$cZmc}?@s9+?#aDAH<?C|ab0`k!Pw_J&fLX|s-J>pHYoRB~vk zFu9HW6_g}~hbReus{{Z5AQ0{-+Oj@4A<y+{_6dIQMYvKeDO{`nxMhIW$<ET+IoX<n zvsSaW;9~e3#Ldpm(d?XBnw3*evuZTJ^yo%<)eX06L5WkaeLP&dOB5-PGRIU}D4{yE zOQDdEZbNUnKzD|Kn+l;il)i^vIru4^yJ)fgJZq-TnEsv4m@!j-{$(Df@fH{q4q5t5 zx@~5|Y1{ep^_*UvwB}A7bi_yBAPETiyhtY!0?zRA?&h(%9|Sa#T0CM8#UH}|Gk5ec zg*zOsp$DHfKo=vwglP;y*f=x{#}-;z9S>Zp3`alr<`8iqTt7uc7SluTyi!xr8|hn< zezNt@9@?A3a@+Y^rkOkkhdDrk8+TYv&efZ)IZ0C`9aFIP(80srHf7a@UZAihqwBQm zUbSI)-%THW`4h_{r-_=?-3FggM%PW(YtK9e(@-<@n!(TNYLt1a0~i>Ja{z|v#Zhib z7wSW|U8WfrBx<_f$vWS&$U35U2=Z2jtNY?ST;H+Lr%eS1*N9&{R;u66n4$mo(Z@E$ z*p$680Gmw6Ptb!}7Px}Hd*m^JET^kiuhtPGM%bO99sgN(fHeyiW>oltAIW4c+Kp*? z(lJMB&%SqKZ9VEh!9qRf(B_&3ng}*m3Z>N14oCk@XD!E(P>4?@&|qS>;M}<rbhjE2 ztV_q>SxPOv@UEv!k#+e3LlY}?(%4sYr>qP;<GKfR8Ivcv9C$#zA{++`VYwC--&vL! zhR>xX6^_8+dTA`F;Bi*HyX<FaMl$Q^rFTE0>o5RfeL32@C}$>k^%h_Zj^*8$NXSf^ z<ppWugBv`G>#8~9^}yYC(LFo#Kwh1}0zs<mLJTQ8pgZ!&Bjw|dKbE4RBFW6m+yQg= z*U1t(a7h;BNhGV5BqT*75|$9MA0`R>(o2uPReuVU@l(O;5XL2urBFg*5|LD6cEITB z&t&8PeASRK*XnYzph%{j*h3O)*GtDqUrQ(*tJwk<P+)6OKue@JZ;70Ka(`KtpDH8A zjg+Rfa^=-0hsb5u{!5AzBC+(H<nn>{%Uw5}BQ+u+>wgj`!x6Mp(e;bumJ2VEr{DTW ziXywnF8dxL-;RG>>SUq~W0M6ji@laLZ-|qG7vHT4SRV1kUf8QK6fZ1Dvv2ssdonKA zXi9#ZIa7X`JzGMNREYynIJ6~gVmU-e%7E{#a40Oh?Y_Ho=+Mrkh2#h|lvLDHB#kse zz&dQG;mMLjo^Xe`M)DR-m#Z$kT;BZjTPc*9(y(bWX};S|l9CD-rTLPQOv;)(m3G~Z zk%u20BsGxN6hMRkiaf<FFNxe=<m^*UmQNOB%8PHjB0V}ZX9)aRPY*y$+!Dqet}H8# zp3Dos8jk!7*b2PEp}1(gNWPo&soZ(XH8TCDHL_?;T<Y!GR$hGVSvj&}Yl{;Bj!Yu~ zTHxQ{leQr##S0-r_8=}s13ZEriLm2QibV0cM20{9f?PacsN6Yxl$_hUtJFrA6a&Wa z6<ita^z#9Fp8hwa1z{ezcxhJ1I_YL^1KyWKbzdE1cv>)iG#HLjd{hDL88*RuFs)p9 z@tG&($}0y;VR}<}{`HsT%%j=^6L8B4Lb2R&@kw&ei(kuW0|v^2|GZA>gJzKgfLom? zkQw8K%gKMcR+dM0l@GuEOxiZDFWIO+;ZV}G`M8Hr-!!>SUVG|Ux$x?Hq~1Qq%lPr5 zq)CqBAyG2tWeAFr(E(8<TAVAdz4jm3xy_-{rPF?r4!&tP30g&vPvnL)1Fn`YL`VWZ zjTOmzqu!ObKA9>v+;Ek&+O>(4l&qH*UU*IN^YW!uW?V`msLA0BS+}ZKN}{PUaNq!` zkxh=PloqU&ArCz$@o<)8*Qz7Qa70RDfQ@`#dBx?Dk;?Qy%~(|4edkU2<b#jo(ra#% z=B-<@#MqTWo-yA@BZ07yWWMD7G(q+|{35yG-=pM$6WdF4$@kLzz-}^aSrNiyO6{GS z$gsCwmmUYUkxWJh9WXZ@a?x6u`|an_>EKhPFfLM>k}c;Byhk3s;|i&TcEXk0Rr1Lj zqvW)6Z<K!b{abDraHiA+Em9N_uq7K7vs>K`DI_f`Pt3njO+ZeP(bWUsiq;SL%aesa z&yaq7u9BHQ%$0S;rBbuWe)9bA7v%7RTT42^g-LrWY@|E*!9T(Q1SS8GD|^OJiA#xG zR>@!dy`0#im&^+{mp4WYmyUZh0*bE9WQgB&RaSYcS-|eyyOa6~MYft@9-v#10vyHS zpG`-=fDT6vIb_7q8jg?hkKY5ggHXU@rQ<sC#9=#3St8rr5c>|2&%b&$z~?d^gBF2B z_OD(bwsroCb@{??^{~T_(aW#@r<O!vH7NN-uR5zcj%=aW7ttoIyXlvUR@oLNW~rog z)q0^~U9<FiJ@vqSG>h_DY6Cs6*X6n%{S<8w&LXiT`C}u<SgxPro7XJDl7apXQv)l0 zvzIOS@nKbh4!CSz+23;Fi%T6qkx`dR&(A}~tzW~pC?-&2s&g{7SYI7-r`E4kgX#_> z(1_M)*i6srf2m$_>4p0Db9-x}20LlHBYNu+z~Gz<XYB<AkuGyouym&OXuGF2YTijd z|8bGgjv4ol6=BkN!$kprAG}xGh%aevVfccF7%k$Q`i&i77yt6Do_1VU{rr=+_4)x9 zV>%|*%4Rpvs|P=!x!@zGe$z5cYoSd8Cp`EOCbl)gW!v(Ur)m9C#dMjYc{=9#e`&o) zExq!A5#<)Jiii>%;8wgGKbaD(-LQOdIyNk1Mj(cTs~E-k@VAUhWnO+bTd#;0PUAMn zcqWY<ogAO}V&O5(l<T%#5h&GY@ml@vtIu`X>?PRXj8Yc9(dq^Ow4~m1MNbV!()HMj z2O2MJAqW7`>YXTEpaV`hT(d(pwPlyHbU6^=_c)2kf@Pa65fkjv8(*L!hG3JQlyq&n z?@784I~$edh=|egZc$+m_hf-tUw@?g?cP|g81#_a45^ee99%wasxxzpe=|H%c8IRl zuP1z<J&!(Ge_d7NrhFqn0@meUe*Rg%nK((WIOjO6nH9mYQR#Zn;l1_Uj~Ch6Pn$Ll z=!ue*I_={(^pO4AXi93TwrIPbKKsgBIu+A_i(GP;7HpJ8zVh_{-g;TjIrBVST~utP zr-Z~MQnX0pk7bibLwz&)C2XQ~uzvaTudukrb;`&8(Wcp$p3j*LDUG#P-y3ulXo%*> z$-blo{*v*fI_jBQH5+PTDpb=@N(~+O%y73WI@6+sxOkqvHuMfm-OkYmU;bEEBQEWw z4iCJz|8knMuHY*}n4Hb;^k90(MJ(?pJ?)sbdiC`;=>50esC8L~LfCQoz>}2gZ{7BD z2<>g9?(@Wel16|<8?T$kz*Ibk$I_K^^yv1@b*B~w>xbX{3Z5}xOWY6jn|F>{?T{`| zWUDV*Z3+g^_wOvv)^Ax2!w0+LhdtqzmG|mPl)nPz<R$w8ySYxy8dCU^<)+l~9=PgH z0oG~zb6E)#+3L^IYMlcJe_XptVVeRN_PNz~?)R8R*#Jr`gvwA2J?iw!bWVPeDPh(i zS);@TYqie)ZmjOpAjeJf!_?BN?;magEQL3g^DT1>Z@?|4AKP~Mq_9cl5)GqWTLyUZ zp@}D8a%~(_HVmkEco_J8K0-FIjJ3fUFVM9s=j)AEU#K}XYw7t{-=e?#@`H|g{YAa& zwmbBU)6Ukv^*&uMy5ItR^y%ky_VU#@gA%kh&`gxiZtCf}MbowWzRk7KZk=`ftmVK1 zc_a?*-;#Ff7?eh@?<Zd50KpkhQy7p3e7E?xFP$?*|9;k~`os%wB1l3fV7lc#^?5F4 zMECA|vd+W?UZ(gVEvgyhzpX#^@uULf!>gE%hZk`$)jYXSKlsn1S|3N0^u6uhx*Xq$ zh2y1RXd%mf=tUUDQ*8c)Y1;3OdP5KDu%GU;_nz9i<zBi^>(<(`WozBL6|R=8>}uJv zCH(frwHGcvmtSRJTJM9f`)H5jdg>3eezrWZEYjJHSz<<sAC)U8&fKVnid!6KA5*DM zAVLg*a`RW}+<Cw1H{VRv&psWa=lATSX(<_cbiZ45DS(;YVz6?xaP3rWRVPDJBX#u1 zzBiltPZpAdmN4k(D9kih>hQ<z)0#Nrv}v1@O_6ooKc}B^V8AI>WT`v8hyK_YXzU9( z*R-|{xakgk1sgz)c<XJQFk`kB*cx9>kp(i$mW>6JV5;-adRFgV`pVm%8a{S}maXe$ zeJ37yx^DSTdfqXIVl8~C9^Ug}U04veqqN+yODIV=Vk%j@T5q`eO1<>D>!C1m(mV3b zvWq)+aVGAzITCg%FI=}kuetbQ9dys*n0m{wtXsqlcZ9XN3p{xOY#g|7y=)?}RG<IX zb=o8~f~m!+Fx)oNA)_Xi(a^<VsYW_j%5cr!x?nAB7z0N+cE0QA@8)=GkpZ7;&f~x8 z^AFt!She)w*S<7Gmi)DWla1;XfP&D3&2-#`P+p#ZTdZ`sJ~iZiJ^0XWx@g5(EnYKE z|JJRIZTu8UZ=(GNKCG)T71`Q4W4Md!I0$BdI0Vag3xj8-W&FlNY~`<dJoYB2k3p<= zr~CjKc>x%x3NBD&t3ae6$hM~d3p^VRJFuLslwUKv^1kgc3^4d#DZn<%HFRwC@B%iM za(i~ZVttM4-2T^8g81771+3m$muBb$itKj5mA^C+6x`YFP@Icn*VQH8j?|`UAx#lj zNK$vxD{ddEYaz9pFlf>>$OXY%6N_}rOM|r*HeTU+we&i>>$4wytwn&vHDGQ?Zc9ju zh}OrsW{_{r0T!%vE=^hwfhh&PEpiO+;`mQ?$B+L`Ih4-U{n-;ed<B;QnJyaVWIn8S z%k-{mF4gR;ntIX&SL!dh?mWySjxaK-5Q8BK6<=DVDD-oKEKiy@SPVc#Cl`urw>GfK z?A}c$%vwP%Agm``8wU7sz>KEO8jc==xOl=dGeOmY3Ie7R>ylq)YtIu-(g%h<qic(3 z>7?a%mY#XY-dLL%wvDO&{oZ%B85NB{w7W9JB#+-QJc+PNmVJ}MhM96t`06<*Mad;P z?xjbyE)=tVw?FMEvWRTF1n><VzyKuhXCBDUs4iYOSO4$*F*@$O(K>D{?qkR5*s<eu z?6}I;xN&23+_?8}jjME(g+rY8aDDpucwLv5$1E6$m|j_iNH#;k^{r7@OSzl2qU<MQ z>okAaB7Nvz4{G=0PSA5MxKtl|{AnHY)+>5(&yHCCnx#kf8)O>@+4;Lx4_4~@>0`7$ zc7_h6G}2S9deB+AktWl36yOsn$$ovMzB+WUv&gnRQ5WL)9ScLcJ9Da)7t$qBnyX9Z zeycYQ=%?-X-CHv=QgoL++UR+GFVekQx7Ah$oTy)X`xE%fxPW7d8Wbz!<FUJM(bF-Y zvM{#*{G}oZf6Qt~a9t?MiP?;Cp6TM5pX(9(?5Sz#yXaXrKB!C39*{EeQY!ZA^|LXr z>lx==s&kg%tWzLrv}5_S%h8wRJkE1<F(@(pi;r~grn~C96MnF>rI~MAze-vFKRc%v zIka=Dp@K$>X6g<7PBcp=71_+jopkaFDB{G~=*Kv2kY@ejX?lFy7O==dk&QIc`mMU_ z0_<AMxdR9eI<WlC(dQn#-UbyOe&Z`sWC;g}qrQ2xcERau{-i&zIFxRda62Lkw3+wa z=i0q{5B+5NY^x*5M4rx``o6YrR$o)YX_!TEpuRc5?PTrJCmbJd2b+B1H*@yL8qNo_ z3oB;pai+)~r0-6~rmpznW!j7I+qXcG{cZXLU$+Yiu=28jWuw8G!0O0q=0?NVGzPBv zQ-EBxhK-FF*vxkdK2&l(yZ0WAu32mixu4T57vlVw!F`)k!0X6Zo9O~Y*3lvO-F6g+ zqi-<*kNpfbVtMJoD<D+j+(fKS%c$8wpLzWg2(}cls6shG&=io8pY{4a-82Q$X{q!! z+4~UvXx3btQptwQiE~?$FTanoW)Sf`XZ;@p%owdmPNCiMHn1{m*ORi{rF98|#h%$N zW&?*VeZM7USQ9Ww1t=Sd_zL~*|6bIcGSakO^8<9+%BW4-<TO$W_i<YJyckX>MjQ(L zH2opI!`;U~p*YRbquTGSjrKTP$Io19c_g+`9RJ~Pz#IQ@5uQzXC6x(_86YV5oBEN+ z*Zeh0^wNI)b<iU(>T2>9f6P|0WR1T0_|002yRU}pYRf}T*EO)_aS@vFms7X7vnx%F z9(u%sY4Xqa<R`wlA5O7etYcq%RO_VH(E$&Q(3SY;ZE58PV(2nwvJB-J6Y!Zw_Iso) zo|z#}@b~3^re*1sL9h&$z45^hL$Ds|pdWaFcMeP#OyjnTYl@n^Q^kYwgWa8Dg^Tr_ zS02}$aKuW>eLCrzAAII$1E8Ene%}=*XhtMQkLf?yQ)G>@NN}Yt`tE&fcn0Mvt%;s^ z`M*pNWJ+WYad15Md9*}_KYoYiq(rc5aZg=9MV4V4vX&b{<_1I4xO;eurkEWO)@FOO z(Bpfbto1N;y>{(-TDQ?o+POzR{c*uc#Bt8}lw7ZiW>3<Z*vRbJm)|x8jA|=+LfYHT zyeOkg!;XR}U9A(|ct)GzOz3ddPC8`dhnQYWLKf<RpTE<C4>(XK{;)vvkRhWUzQs#W zYFPgK>9oA_E6RDIXsMpnv#a(z|2AETGl{rUu$6!2(KyAr42+m*oIJdC$*0=u(AF3X z<A7L>wmq`1F2FZV2aa*-H{%eWWTAdP;T`RWU4FB$<RO&0tDbP_KLG(l{RBk^tGXtB z(cw?ruIVU`_r3a=uEICBQ?qN4ET|XW-7Hs@H<m`$UUbY_nzvLh`r8?L$GuP3#$B8O zP31pPx<a42{UU9U3Vw%cY3CC!(G{3pjpL(14<bRR?sELVt4qRp<D0_-_UP3=>Cqi9 z8>2-R{b<@R2*|X(=(zo!3pRWD-BrXvfNf3zEJnww8*C~8Ol%_ttis_6a&z92@$!}9 zo_}zwmK3m+?bvAm+aqBA2?@usk;+f=Wy)En%HF+Ckp=??Vq=hqWets+x3NIA%;{en zY1U_}!){ZKV6&&cc5&F&xo5Kju?m}<aBG&BBuke`@1wfQrxSmXd~EPiYnMahy$^>= zr@d;TQA)FoP;3*YBsL<<ogv*0I9w*qk76s6T5`xS$IA<^43Vbwa<KO++9+mjgH3tp zwRvZaAU?Z|gc#0XU{f1dO5}@AKb6T}e`7efkX7&e7?PXPa2pk3#?6p;Cwd(^9w0{^ zak!*nGet<6<`?2dMN9;Bm0PvA(4-Zpl=}l{)Kfm1wpuQ_`$@Uwrt_pOf?|Isfr5`^ zvT=!lo*~i;yF+1X8N>%TuA=4UF=)s6gpYt9miXHFa^}e=$tQEO<&`&HkRF{{06)g! zCR4!2`UGr%gedF*!hpfwB;SA!AmH8ktzWrJ?!Eh;B0KFV*I#p~)XqpV+_}|Es+36n zin-FO%TY4<*ELd_(NLa$`%O9dr~@Sj`Q+v|ngC|ptOnWVW<hk^oQvsT2P}KXmO4-) zj5PR(BF=Id@zg7F!8MP{J+Hhj=bm<$)J9m>TQR4WTZ_vd>%Yv8K*<wg2MXJ!Q{1=+ ziIYFJ>rQ#x@+a3%mI18r0385P9W25j$sNaC9CCtBmL1a9Hhqc-MvLWzp-;-q_dY9i zcRyH$z3`aq*SaabCy)>1H&G&k2b?W;KK_4l^!eAxu%`z}Lqb7X;Y6MkEd5#bZPQ&A zmDG|W&%IDaJ$r{_5HF9%+=$C9qAo@FW%A~e&&mY@?vq;k^pY>fza>qv*;AN>%V08a zRAzlOTFyP|5}CHNR5YuJyz<&GIr-=gvT*jV*g&jM(reU`-FIstSmRnoP20dIo-4y1 z`<Gnv&<8Sc$`{gVmmK7hB_HU5#yGad(n%oyA#C0h!lt6p!X@&^U3bb|kGv|obvR0% zer1@nYm}7R?|Mi&9&xgqazYnNgGC|@n<lY7IBY>+@(Vun3juG{74m=MK9I|A8Yv@Q z`?sSb^M(Qeg%UwixVqKxSBho9^!Mc0WBbU@tH|LjxqQ&Q*l_AXY|w-a!w^2ix}a{; zrMF*rMy|Tz4q0A|HX*CI40&_3^y{$~He3RqNw#DO&{-)TzWI)vcFsUKZ_p6A^M*cB zhu?v`+j0r05P3MOlB5HM3b>IQYf^-Dsc4xDd*o61&*zKe*%zLYW)15~8g_yreI*o= z6$@s`MQ2?gA5NMnQPiWW{&BzDc=b6_2aRKz!Nx{uw#ic_;#g9amU||mxbS`5itnYz z(Wl7rSSxw+-It_&i@Knr<0l?|-~FDZTV1~gYh<e{=Qh9_13JlKoJ;oUm)MU0qg;6R z2X)+&8z<c$R`6O4DL}q*<d(y-Fh1ZJyv6je;^{MVa@)Oh)jw{=yM?gaZMikVq6I(O z4FznR*04$B7vT7vt~f`w9qKvPM+GjRz}BMx?FKdt7*?xfbiFR0^SQQY=+?Z3BiPX7 zkh67u0W2f1zOV)I`=BJ&!_EHWMctL>IYxL~Msw|R?L(UDZE|Db*lBH%V|bSWpUPs> zI#W`pk3aH&9?*V2J@~)_^q@`$=m7^*{W=g~5A4`cJ6W8Av_q#uw0);TwZlPO^npj7 zQ0&ACs}bs@wZUdqaR>kjXS>1!8)r;Eo%+GQwK1lVrlr)>f4=mYSs?95A;X?_F2)Be z5R6gmhZb3b<=XlRwjmh4mT14@4$>M8_R|p`PO)&zJI|}NxjD2}BC;8D;X`LuWZc<e zFf2EpD$ZN31FpPWFS+tsT~k<ylSRD#gs2<tus%lD>hOE6*E-m+CX`xBdtH2|F2ja3 zcE&9cHp>?P!m%Hslwk=F6=olQmOCbD1p*ec*j#;bFxDhy?56KbneEQ>EaN=`ZqD(W z2e{Jxx8iILR=Gc8SH8SACS{<>XP4JF&T6Oi?bnH8v~gCZrqtd`M}769trKPbIsKJ? z$>bUxeD%?oeUPI^_q|nDApY9*OZ18>Z`Itjg;;XB7{{}8z|`Y9+V;2$bq&%nni|cR zOJ~!!IStrMZPcSTYn@0K$M5vkUty7@h1j8ok`c|-==xvvg5x`D4%Rb=Q|jqq=Ut~O zVfADgHLE$SoaAXT<_Z~Co0`QH<)k=wv0il2QF_>^7wIYhW!erle`!@@V)%sx*udGW zzxA58<a_Pap`~V~W@`7|ef7a1&*=^Scvx3)Qz@k7w*hf(%4McU!Xiuu-2ui-0i4NO zu<i$K-L$2?_@DReyj4pG*33BU!-fHpxB7u|T0eX7ZZ|C(vjoy=w9;qa`P|mLvUpiC zhA=Fl#j|zLm1ki?EzB0d8N4-jJxC|5D!|lz1n^O?sRyfc@&_;LE?Mc?>+iSQ)MA@0 z!8!z(ybM>y<D((MJHTKTL^8f!Cx8BdwrjVqel_D4TL<j22}&Z6<r&8S&7bhLHm?~* z`-fw_8noBppG?J8ULJf)1uch#haYKei6I>n3|g|u^`-N^)cyC~MfYlVvi`gjc|;gm zudC`f8n8pUK#{G!Y-JU(s%14Qp@koRq))VKqtST_%%9)95MCx-MXbI#4lu7w0iT~} z$S}>SWX8`rk&5h{1HBFlq5UA0BL;8PfC8@m5>a+);4wTB`T6=q_ip-0yZtd`DNtmq z0ULKH6j>%IQgJPQvUs_EI`R>%oxx3>Fm+Gr>RC5DYC`${vv(!nRaMt|XCNWWkpz<v z2va10Od_LFv;{#NQBkz=L@j7=sD+AJP_SaHJ`{1n@v|03s^Aj^oEWsA0#0ZYC6ho& z2!w<X$awR=|6lvw1iyZ*(DxoC@4F}8x%b?hz1LoA?Y+<0Yp=Ect)Z0$pbA5_tJ-2b zJ?B~^(IAQ<l51pKAIyJYwXMA4P>^F}-@cDbS)Lo^(Und+EG(D&F|=5tUt8lB4AHfL zr3Q<Kamt|d>HJ_*2AKx60$ugtpZpP`qk@ec4}_%q9AWZ*rFd@MjYy{4(OfS%VB|!6 zv16C59ke9Wrf8b@N-o+85e@<iDFjmYMO?3W<)IfGb8or?aji4(<X={qk?KuIPf>Xf zUE8NjGHOHNv2}F>;ySnw5B%{yOr16pr6gP}Lx*)`z(wNQ!iJec;i8`}!@y2$iM&eG z+#aK_>gzmPV`%lpJkpUkvv#4v^jl0z9{$xEvi!}576<0v;nr&}Lrkj^vAL++LOn&{ z@D5*=C^wvkm-8Q`I+RlA+R}<&lTGzO=~SuuuGxzRxCS*ovI)}qorC;Ru7PG!=~z7Z z{Ygu4!-YMq&c{x^lVDFZC@TII-Fghi&LSq{+Q~Pcy%%j_o1#tH0DQHVz(*>adQ&~f zSgK)JS|?psorl*R;ADbAi~G}%C2Fz4Qf;C_`~^x-ynQ`}rl%o}fNPOlcY8nEMG0@! zaR#GS$l^?=(?Ww8eyecv(0<2-IawG(l;K$qE()#>6(c-McGY10rTvRFNO>8y&&jD> zo7bXm$3#R$#~`)G>G&+S$mFp0sI|4h33cB_f`mlZPO?r~b+$+EE?hcdD1P(1dujAj zHcLXSa#BV*@Tw&}A}il<<vD&I>Zs$8k}(=<xgNEWtxRdGAF1teV!xJq&z^f~x;7hP zNN;nTJbEH>4l<?6mX4_#KVh>UTQ;pkzxE0E*@c-XP(NT29U`T6F2br4t%<dsq&}j; z7@AzUI~$WHPQqP}JZ}>kYVV$3CgHV_QvYJVeQNGB#K*FZ$oq&3rXXuinT2wz3@eko zX}!CNz`P=4#<|)7Q-1fw3iN27$mhr;>?mhi(bq%cFpsbydzgv}Cp&r?&?CS)iFM2X z%HLjzC;Id<LpH=kFh%gEr4HQ+e>Y|g_=*oopr>6eDmQPzdNX8a@!`jZo6>}<yz$m@ zef??3VXsEM46Ctf_Dp;?|6zOKHD2MuoHtetn8BkpYZW{3*vu=?oIp>Go~MYYu2{To z3k@SacGz6yxiwTxqV`tp&&H%tC)--uNFupL#}B~=-<1*MMk~xT2xSJ}#E(EN>L9^> z!7KgJp>?Tx9%`+fjRI{DdZfhvp0@sD+kx;~gHAhT*icR@Tkm0(#UZO7l<FQmF)wkQ zsSNlg5iy8}ZHED;orC$$EJ8t1u^F7=Oapg;C~25%pg;tnsS_BENQPvzYl*ZIZ!VgP zsF)PYng0^ejWwXvV3w4aMn-5gGn)5Ryvd+2USyE%MM>diTsQeL3_s&?e3?hXgIQ!4 zF$qs`qX~eZ@m50**1oTC(?qWK<eJWCdQs;*`igB|Lf>StRF$if|F948A~M0>;;jA_ z4cP#}dd80)iu3^&VJC$alC9)CRu0vs)u{NQAm%aGwOLm(ND49I;!#N8<W2kTry^(9 zKDJ=*^_HLk&OX!;_-J(R<It4G?wG4?rEyk`J-f4ze$puXt(fhisuKH(KE?Sz>qAd{ z9PU}P#7_WOIaHnu7uK5$vbw5l%*nin$hXnx*zY{#(<7_4SF5N1eiN1p<wc)k%)ks= zcN<MF?}9~dA$M0PzTW&5zTBLJ?CpDOn;Z{_ByQD8*+K|J_Wj0n=$q65udd!~Jeb)i zx<=c71zQ&<S*&%K8Eo4hRqepD^JgMHE(UE<`rySCAK?JmR|#6<El;BH8X_l}Y8%$r ze0w)!@2X<VzWM^3e%>T(V`Gq?R{GYd8Zgt2>+!2O88EbSf;VId7B*<?waDJX7Oeix zRK_-WtgB{(+V*$REg_oQ$+F)?C*sPR|A+#Pi){U?`h(GCS{n8R*&8sXUw5?27>-=( zSCa&OLP33te26~lFu+M7KKOXD5MI}o7vSMrr(p2F5!jGlV0}q_I28Hd8Imx{vLAc$ zHsbOT{pg90L~NVRn6>a#1Gr+4L-3iwS|Jj)^d~i$v2E>6&&X1&S@tZt#<#*{H{Qwh z?CQ7tkb)1h1BDG)Dm8o@TN=>ARvp(GF&p%LBJ@4pyC>w4^*8M1kFSp{5yIU3s~YeX zAIz<XnfJ(s4cUKHp~q-Gt7i?R^g3l%)=Qee83Bd@`a#Sw%6FKp|F;^jF%uhNMalQL zY5dRW1=3=-BqVe>6S-wo^3`yVEiVw;s?M4+6l`6EA?Y0rtvG_7$&|qpY)cYtwc)2} z^b9*vm8nPgOx8E*v-7<uLqG=YA@}QV|1VsaTtVul4_-I$prNcER7<{stoM=1uuyFQ z;)t^9BBS}uReub{9)H;stXcmxiYseqXb`cOR5TzLG1-Q?6eXjr-?|`J&=21%N9)+u zxIA+X3JJhuUL(t-e5Av)esHV-JGU+&nr%&GA+~({21X9-!4-Zn3<sTx?fY0?q$!TA z4AyI{j7>go0^Gl|_TU~=Fl=@1^vQ_h;M;NE(=Po^Lta@m4$!LE&oEMH*=N>;m=rZ0 zBFGP;t4kfEU9)==dZf0&c~{RdZ)|nF5$u!v`#+^|FN35pBbDEh)4X4`C3tDxG^B75 zWfRuHeb1~QxR3X5YW_G-S%q)@x)xuqdl%`6Er}F776k{Y@aekM7<=hd>}Q%fy7dDG z3$fw7=h2adNyebD_$;r`8}-sX`;Yd;sS6b2vkzWC68CP6ifD@VJ<dd4G26Dh_EfCi z0Re^XRu|*F7al>9Lif3%vssHYwy(D4DUFPdMpWyL_}!z+2y#RZxh6JPPsVXzH@<l1 zErz^y#fMqjY=T1aS~XI5t3v$_UU_|}PTArr%UGTHxZ}q0=*e)`2(EPRHS~OJp@-VS zca=)|2$GZjbgE=OX5|m*nLNqxe00{Y&}Yaf8nQ6ZESpPV22GeK$QX6IvGtQz(2g?d znG+EihYP3Og%Xmh<pi%q5m;$VO0cap&;Q;}oH1Q&n;v*@(K7QE>rHC)DB+Y>^h<Mb z%~`_{)218#x@EUTIY{J?Cpn-#L4#ME1UR`<Q$eG2XFjG~c_CVHQFW`NE?BZ*3(D9I zq(5oMbQcnya>Yc1eE<LoVM#<mR4QLpX&!FBW*lO~e^g7Nfp@}^)$35szEn%2zf$>C zE*Uc#n%%M&y$t9={As~Gh>vNF$6i_P!>NtFWnig4eS{6!pVm=0#ZlHkeP_{|lrJxN zWFPO{168?UL-r_F#nCU0Ro-y$X(mH9>wELa?xM#o?2&EIPGi2ZYPJt=$m;E=?rvkh zuqE4=tF}?{uHlu|zscKjVDENZKYk=VbsW$)>w+n_Eu?RVCICZM6&`DoE^50Bqg?;y zL+I3&URyKZ5^=@tkNYr24PrIOv&2WL5+iPzbfq(Nc&{w^Bz<{>HQxK59l;XBuUVKJ z0JH!3ainCRnEccLU&fj`s0PS3Ag$g-Wak;^7T<ziSsDF;a3Oq5WULvpj$x18`<#r- zX*c85|9T7A+jh~|F>GAp-%9ockhV(PM*}ktV@~dcVIwcX)&mt9UYh}{`|?D~tE;eN z89DDSUyO<4&&HX*7>Z6wDLj*ra(pUcTc+T&vww+=U*)mBlrOl|3X71bvuF2q+;z*Z zF=9YZB(`jZ_Q~y$l++O^shu&9`(%zAKLL}jnTEn*BEPCElUGtJcj(Z6?Kc0%KkDZD zRewf8i&mKZ)Kc?c`E{HPIYK%Aec$4xfp1;OIFU|ksUz*9TvM8jTdq78?OL`#bhBh! zedF)&r<WJw<yT+B-FMxKTc-0J%ybLypMwr*?EPg_RB!tR3=5)^bSWJo9ZGjecQ;6P zcZ-yOfJjM$z#sxccZ0Ol4Bg$`Ffcru`~Lspe!sk*pS7MZ%wpD>z4vwIaUSQj&uhVD zz-Ep8;C5&FYtmX>`a1~?yRTQvnNvh7<LXMi&xn*eZ{v7oxkU*$|G2uI9shyGneMJf zJ5M>NN9vId@$Y?N0^JeDvG}9y@dVg-*xwiaLZK-0#(7l~xjk_2o}kX3>)<c&f|wtP z4oeV~VL_=g6Fnu3%8p!Rz|0{@pQ<##0f)cGqjySRfF*792t(KQ;{l(FtlPJx@h5Wx zbZS_HCSwWcE@xksmeZYhOvZCw{QgZEagyq$s$ztJh@Fn{2J7ef8=+qwI&JI(dlC*| z4<?@v@!ZNJ^vZ(!3TO*!?Z|a6-%1jps1kGT@&wht>>p})U~MTWO=vVZnN<WS<D?)@ zU{VoH;je(Al_g0o>tvKNY81(WHz)%3e5`(`9BF8SA^F;h2;^xTuT&KUmir4Re9hF( z-Q_$_iy|{2-w^-Qo1pb%3K0kR<>$!{oQ!+Ci#-~}un7oX69K2jQq&Tahf=b=Vd0X? z$}(Wb+KMCna%h7pqu!byD<gLp3*KpAUpbYnU#~2#zn^g9Rgn#xj<}CDN<1&*+UKk1 zb9*=Y=Db_`Mw0XRp3H1a9-feGGQOJK(}h;ZJ3x%`Dc$ASM`<pmpewSg&LQZ6rc;Tt zB7`4zL*c~^Ih*)Y#4`ua#Am2PUhBjv8^uZob5lVci%at$7aGIcXDRiesa1Qb(OsH> z>$^git|$WP$V{2{Gui@UxHNh95Bo;fG$p|g`WPs$QsC4?nsny?pO#QF)>7}D6s^3s zF)a9?K#kptdys6M>7iKtE+$XrR6=9C8*6dpot5ye93snhqJp!$R@*_KFy}(evIAAe zr@nOYotWyY@s)ubqa1bKDvXGriFjz^6P)0@jZpUU<)1V(hp_MQ7)f0ejphi5>RcZ* zC0H*X@LC;0ofUTQ^1^KS$b3G3{^?PJd|7|BcpVM9D0N$yB<lu|<Yq+?cF17ZXu5Jb zy*m2FpS9d$^sZwlO%~q-0-X0LjcB>@{=O71nNd~OI5jA)=@34(@C_rozN4sg2P<K* z#scBQBF{7?onE8SP@rldHj|e14LBw`%2piT;N+FF1;P95jWe1SeI76WLCgH1EmR&U z+=q#86_w)_L02(rYW_qE)v1}6>!{<r#My@*p5a*KnHd}{(lu@>{>VUhnE<v8;nR_l zacT|Jc+>T6!OYFF-Y?7Wkg)l(QNT_`goq@^fel4hqUyp{AY<f%CaDsHMww>S^IEM0 zOphhB&l<H2!Fj&|7AzkLsD#th+0VHC@C@2Vlare-H=&s?Xlow8pb-9DV>k0#Q!}wX z<BnQe7b7JjV;>h6kDd;-3j9O&WS6`e({Lr$zi#tBZeD<*#EWmv?FCL<P#c2dIh$1D zO5wSeys`f<i}#1%XxoL30(Tj=$OGJk1|mggt1qPD)oUS+2LlDHXSZ_(w!R`>SIrOZ zEO~Ydi!GAi`t^^|cC!OD@=7k5jh>!EW_dHv>E&s<(Dnm^T-fr(gyU*Kkh7CT(59Mt zTBFvgJQ>f=r!Q~8I+iU`<(QGwq`F?Cr9oE?JZ6igSLfLjUWN&#2A73SO{i;yjVxi# zb&EVB_m{Vk@9UE58Rd`I;3z-tZ5gEt*`ypm^Fr{5nZrY(sRk}%duOug0MltB_t6Wv zfGUiNgYn74Ca)#`-hgj43m8Ic%slqTk>FSHL3yunb(4h+4O5G!)Aycd^8UG3(OAKJ z&*^0oFyi7=>OGt}s)W+kgD=wZ#kMqldXL*lXYDpSYv*0zi0jp#*2S97mU6{`!Xor_ z>pz8c4qa<E%Tw?ic*6rVFVFOBG)DMA8^2Qpa?vkHrxN{(vr)+mczzfLI)a(l*i1xB zDT?ua2%K?*Wsx9&7K~MQW`Eat81i{KiDxE=s)#@|lZqJ^c6%~|LW=nvKl-gr_^`67 zjUe<7S+Ovr?%%-+dzI4~V>rcL?ia;tk<LtJ#0|lmd*nDOVA|kzya)Q~X*&Dn&Tzhm zisvQ50Z)%pLY?|%!aV{S^Q?ytOyc(AY9@GticI;;NYA^|UZjz1w%sZ4SVe{?KWPFE z#k5<twiXS1BCtNp{u<W~v|01RIIix~)j`x^dYb8<3{JvQPF(YPGr1lad!{vF?l&Aq zUmz!qR4J-X8Wb4KFs6W6n@_58XShiw#wSXG?hi*Uat|-^-@I`Scr8}RD>e0oRI$Dv zWk_MReF%H3n#M6`d*j1rOQE+A4f<L^?xa4LKVPHgaQhc&Exo?{FtIc%edW)iR2WRJ z)yUr-iE(3wplQn$l%pM!lB^j;eYj^V{f0CmQI@#0gb_gTE$TpmDuZiNaqWKgT_TZx zEL_OXbb1^0y7l~{vAp$F+?bVa2(KDKoXXx72DD~Zi}?H@MR?c4HqEA<h`PY3tWE-M zR(-CYco$G$b6rp;IvV%$Hitw>p6=;9Q;q#q-3y|lq4KqkYuhO?Kc>DAoxF=J1-qSX zoSIf(NK$q3{p8osSKvmQ4U+BoA9UP~a|Z}NUT*%XHTVCDT0>$-(+Ej3%n~?tW50=# z?Hgd={77ShjxKbQ>gUvP^436L-UnODzj>zY6)nq}L2ko&UvygOQ*DHAVg8@|W`qTq z@Ls)O8D4qNk^3rAgPzQ4(RZ=Uwy!Q2=FJgsTH8LbYkNg$cTjcNJZ4mtLEib@cp*6R zPZ{JXL|*32pp5u?A}kI2u9?E~?qldkCyyj;vKFoNLj5<N`y#fTlrk(lu{umXAD_P5 z>JD)Qt?VgR`h?i!x>olo%mU5xXM3_w)T7M%jN9-TA`i-)`=tqe4F|c+WX7rZbDJO5 zVQmOco;*D4tNASdHF#=26ZxZ|<V3HPItuFRkJxF6D&lNv;shuyGV0h2jFg`#K5-Hx z#&RM^ViSClLymug5~Y?OzUYS@N+^ezAK%z?mbv5u3u^G0S=e{<OsGre=$~uw8c5}M zNcB77a|7kiOD;_6J7ucN`E-V&8dirJ*6CenaRoLk!Y3y-P97RKuyoyO1aA(!NT>xX z-3{erMC-vHKh{|lQ5Ot03IZc|Z&qrwhO;w#)xg<$`qo!qm6e7DO!Ywr-SooQJfrlz zy-Gs@{*L(<%Hu6^I5|PFgX%q4gL7q728a3yu8LP-XM}!toN;NKT>5OolQAt$XQ+Eo zEe(r|TH1CaWfRq{j#2k-HVj}EaMN|an=$00p{;B;-$l0+htqEXep@%{idntp6=_*# zn`z{On-e@RN4URh%L<az6Z4V4tkwF7Iq1X2meXd))eKWv^X25tLWO#zD)()ort`X6 zVyVCP@!s?D$knM}$6XCS`BzxYWxIv3{a5#E%09X9!F6<S6H{DGdA}C-$;{i`50?Dp zS!B|)><A*T39jnwg&Cgq*~&>@sRP(ek9=S}(e@(8k^eHPPbh7+{f8-%%KU7!YV{{e zoh44=Q*%W5weKU@WWe{#ZI|Pt&9^@Wx9pC51>@ed6clsK3Z{G7`7pQC<t7Pwh=a3v z87YGH-`;#<0{7$DmA;neETCGdk1yNox}1JD0xeZuJSP$9>+0!<9IJMXG1-f{E5RZe z>L2fDvyg&b^TKn4&OlB6bXawj+k*v462de}1oT~>iZTuLo&+sdoqrjh(tYwk7nD(U zGnCuFGorTZaFo$~ma09UB~rzkg_%XxnmPK3_S9Rs1jZ~9cqZvHQ;<BuBXlbThluY9 zBG7(!gU29RaNg0>(~xf5xT)Lu>K;rR2;4;b&vzhiDz>&d1g_-8`+TDPSjRt`Sj}Qi zUBhlzC{Gw=UuakPu4@BxAIsN}+$w6HmcH`n#TEm7VY=s-&UE#3{qAcNPR{1pw((z= zCgliUBBu0c@n@7EUpUMXJTH{3TOtuLmd<W{@pK~E5()#aQv>=erKnb)2J=Ne$-K<F z+bMqNH$H%}TuH@e76u8Q|JggW##12q-SrLMGN8d<gihCStJ3f#S8nEP1EqbZRSW8I z&E>ID7Vn}kbZzK?GmaE42Os34Ti+n$>1dKxR<}$UA~`xuxNGPiqDNE_jps`0khE?q zCCQ{{U7Kxo&R)FfY+HzL6Q$?rwadM;rC<8!xT77*LU(F^07te!mof-`w_!1m0(x@) z;i!37t7+p3m|sCwm;b%~PQ268D%TD>|D*+LtQ{1pyCmjPQe4x@epBPW?O42NRAgoJ zVMpv{N%@5vt@Eil$$2@ay68ts?B>gR6}Drzh6qEP_g;7NhF<X|$Ah;#d>-;vC+d`c zB5_7GL80J%FvkXwnJkzrh3#RF;#3%!^s7h~d&793y5g9}{V@Gh+P8}_sL%24;6|1Z z;b0S~t1rB>a?C9=bS#2GyE5}_o*~bhDdii=qqc*ov$!}Rh9GmBH~MLnc71DT%^u&L zbJgay<@AXSk?!nk3s`y!ulUWS;Omm`?kzf9+>PpIub*HbshaeQovJ;nXGgnaR(b`q zg%5)TwpxPj?0P@t<~0`Kkqj`d0D}*H^i5M?-c}pm<1;lmY6PAoMVzgomt_P6bZqz} z0<-roUchzc*mYDxi}}LE;~g+FKc^p{cuTVhMHP@c3Hj_BKJ>ToM9(LBEdmF12eA8K zf2msSyRx_9M6(Y<veve95>{*0vsp9Xd8_PmRO)|4Y}ZJwACZU+j;0hvPZ3`7!0Xw9 z)y};WX}wA2mW%#O!ixP<3u&KB1LoPf5huNMqjoi)2hu*gPYS-d(?1%t{CPrd2s!bN zK1n*|(XG(}Df%Z7=oZsY7Jic)*tL=CWEv4krU*Pfyc_FNeN(M>P#8NfGViB&IM?KN zIN=m_*JO9(R{T}Jnts9fDa!oaKFHA@Omd|qyt}+``dr{JW$D)ai*6%vVtDv^fgn`J z3m57ra5>;zvLW!kWv{J|P1wblyn6Ea%_NMX->h_<f688itXRFi2WR<2wAiKBYvH+g z`|xw_-NM%N2k%*g2B*42Klh`gt(}$+i{{5lH~VMsM5i`b@ZIU$(FQ6;<p;9KfZK@s zuVns8q1^#D00Ywp*55q1<YNpnH(&T6A9U_nr2$fiAv@Cz+^exVqb15nBhoWZy$hnt z$`&E!8DlBd(K#?PKZt~I2`iJ{JGS1P=bhdylu}$7a%a2jVBBQJ=baH5D-Gkx+HOpp z2(q(Fyt+vcG&w)>=|U)82V!&grZZ>$Ntzzl(3W%y3+O!W!4E0QJ|uMSZgMmJs4eko z+I#35^_*K|^Qt9mE3Oox-lCKkjjP`|CM%Anm)sV(+vh)08Z^kn+$7h!F_w~%avL6~ zC+?sYNd)mKcSEnL8P7jC+At=Ew>0nO7@peE^bl_yJB7Rqr<in8v0)I%?elcbdv=pd zBU;Gva4tF*?Rb~zwLw)}W}Dn#!mXm7MvSN_RdOd=&>OLbi*mfXscCSCtiE4x+1=;g zwFujI8z-n?d&H^=ZD_{bV8f?igG~nV35(PW5&CS;+D%*g(^tCr9Q{1qozu64=->1? zVO26z3E88nw>3|nlB^3Ddk+$D9?dQmDK<*dUy&PaXxe@gV*IgG{a&GTV=kJY_8g;@ zlb-f6p!Fzr@9fqNYz}?KGa|x&SMI;aSGXzE_Llc5%c;Y^Z)9XRPvNBf*Nz<P>;9-- zo~5wM$merJH)nCiBTWbFyvEmC#iuW$t@J>x7#7LQ(aRIGff4*ABRUwR4s?N+j&RV4 z_j#n%)>uMez1oU8I5^BW;vGab(obTB!pYsobL0hC`VXT@{Mg|<DZ!Mh1sCV6B}>8c zpF7D-sp9(37UjdbQCy#z8ty*=2dz$Us727oQGj4iAwnM7X|-ZOKndHVGHL3A`=p7F zSk-o`@Gn;7%I7A#Y{sOwOM7f0DOmGI0zOAhN69?o)lx=oLmsD<#g5;DIM(^AFrnV( zE~no;oL8s)&&6PyVoy^B?MfS^j65zb&ZI)T{w&RGMfhYNktZAb9pP!`@9n+OUwUa3 z@HF}ecGD4r)z4Jg>=U@(P$vf+qLSAvwBujI{s_EEBkilmOq$WBk+S5yvLa~R(0$sh zz>;Ov-~51@k|u7;&@8f=K%B)=hSnb8z7Q(tvX6WdnoXXJ>`)^e2wNM|Vw2nGRhOLE zWXLx3{LFDH?9mK|-u2zrt;cZBGcUoe^?iPXP0h9k=Q=QRj)zsVtkdDoVA_;Y&JrSR zSKXe(pOKJk61$BA++c+~-(a9<b|OnBipC|RxT{Tk>GKN>VKym+n}VuU&K;rY0t>nx zNf<_t2ezYXm!3`YZ)T{}pF@7IvrGMkeK21$TVFiU^SiB|<}@Cb<~mtrbvWVI-+a~4 z_J?AwS;m*u)oe$i=L$8rnnS=gZ|VGEbXF*ZyXdt@b~GPr+?};I{Oqg9*8SxiTUq6R zoKJCS-9U=5mmS<xtrWe~w}Yno^jl%*H|l6g$EQ!E3IliR@AgOa&u&Q^6DfQwLQAu| zjMP_qo*9gct2l<xaqrizWe_>4N6`f)j|iUBH(yN7ZFot?xk-Y?r?r?EZpnHj=|J`v zy%8-PNpmG)@dXEkKTu}NN9&cB`r8B!LIpqccb_5NZ;l8xPOKl&yK*hK{nBm6p9?z` zmoNQB;pb6*#biA(`#~lX<L7!K+i5!6LK5s!pWis}e&I$wnv)C4Qk8$=QK6%+y1E@q z7;e8~C&Pk7J}4!hWmY#Vz7(jm^mB&8Y37~4i3&HGS#5u7E#&~~(x9}z*OuUQdc=lT z54S>6&CbB$jO<{T1+{UPGkAd$$y<hD9QiZzbqo>t2no1aA*&Z3MvDy2KJvb0*-ycU z%Ebx(y2d{=4Hcb7E8iLb@lU0?K4c1A_7`TmxsW?Fe~f^Zmkbke@<YUy@F!ieo4<K2 z_!Rq}Xx1e!rW!f+e_r`j;%rSN!gXw)PVK>0H^e=c?|0O~Gh?Y-<mIGKP6k$|T+Xb> zm7g3R&)3LSU)W}Y;CaD09O_{_>RDyRyO#0`cFgmvYApo}_j~vg=x?k(eXOzmf#sb( zIi&-0bpQ{W`i{SbeSUkL-0Xx+4o;v^al)8onF!(&7HZm4DuPG9wYl%jlHqFc^*Hr? z1~Vi=@ROKOmdS4BVP0^a%PiWuGgfR0bc?I*6K_$!3cn&aV#WjCZCE%JLj+3H5lu&| z^1yRna^VZ$8ZXb%maZ+?h218S=gB4dhEFjU?iZA#&|MT7=U|I%8$anV^~kdCG@voA zd+LS`0k^#|b@_YXwzv0pzY`!i7gJnmT#*n5a}JLqu)n91i7R|)R8atym|#Z-3R>{C zXuLTrgt)Zv3t$-7;=s5SnQGpo*nYQbBoLoVjaQP7t>tPM#?B+#p=k&|3JhW18o{{M zZS+-hS2pVn%*qPzwe~$7>xG_;w0tKII^E&izmHEInQgPmcAqXAmMwg^TOJ?z>C0q3 z@crBFZXw7m=%o1kws#G(LuCA&@L-Pag0pdfg>_2LXMwq<2FHR@9#Xq#g}OQG;~Yi) zfw(%X)2>V1P~K>5>5b)gUfasZ3#)ZCCU{I?mO|71?ScCp0T0N@vCU=I%A@2h-y4sr ztktlu9j7F+Y+j9R1?<)W!r`(9i4{A+en$#eB5>1L_c=poPRyh-`g!@SfDtXV($qU0 z+1S#AbHq1(4VILEiXPPXPrgJ$XVVYAV=g|VU%pU<W%!PhY{E&2OVw)VTLTQU(xd|K z9Qil$-Jq+37z!f7yXBlg*}|8#<<uCV{7giL46P&%So3$5tK#vQsG>MR5je}Jb;C|h zPd3%3V**}!OQ)`pjXK+4nF7_|lOaP}btB8>jDt1PBkfi$&(!O~&^<X69XlTS%8`T1 z7>%nNYjyK%;FS}rmH<PSKitp7XNl$-V$)DdEH~JLtA!^#>-qyP!Ml#cFOL`&jak3V z4Sw+=1lu*&p4Zf%aiJ_5@i}^!)Qo^$fA?I8vX|}Ie5Qnmmoh}hVjCr9!Suxke$e?* zowQ(jH2GeEirZvT!D^>~$XM>7{%q0x+9aYNjBs0Djr&WzNH4~6R0L)(zp@-fE6lOc zyiao{B7!1|@L?CX2>Fiq&GA>o_>W%NXg@6?ILyO5sUv=TqLyJYOQbiPBsP_Cxg^z1 z#6t4c=vtOuK(gEG-+``B<S*V6D&g4{=37N9X2xFM=<XcEFF>DZ-_r&hrH7~+cV%_p zNVQj?qMvv7XUEC-9l(Nir0KHKYiGO<IO7PG4<w}5f+hJhgFs!x%G)Z=+XWnH!(>@! z8fxA`St7|19Yik+jjzhn#+9y_GhOd|Y!vh;GcVE;)F?<orGr7{8V)k5`jxpq8{h3( z;HtZlTc!L?!M92X+0o`|Dasuy|6DY=^#%LxozePfeEd%ipBZE=;?LiArhm;sv+34% z;-vk*4)Yy-sy;J<fnr))<JrD$YuX)gFkCKt`G8zMTZ9MUO2Lpd)^**e-l)|tTs*sU zePQh;S5kLngG#IZTOwYOfw_`w6n*QZY?c)4q;ln3lT8ZzNuv0gla*9Xu1yPCL0o3b z{(X#L0%#T;T&Ta|=f27K{D_0{1BN{o2ca(hjGnqVvPTXz3EKV(3~U4k(VYAoT`3X^ ziD5|!iFlJ9np)!D3PhrYtSocVvnpy_7GorhEBgB$OecjeB{~tY>;0xbx`nXsfAeK{ zD`zAd$$$#ZN@pg-aCB6z^3&)f#_LIqRIhwT)p=EI*EP}lRHwBu-C{6vi^VvZm4CnN ztyNTsVwXaV(5*L#7Z2FsQxO9WMu^j8DPs{o3PX=U(Jon!suhib+gSi|9x>7SiyTMG z{yMEK>9U=kr{P_415e@^Dkw06XviubsEURaK0nnqWSLMVPCxWp9jfl&_RBvT77)JJ zvl;lY!DOOr1j}vL9ch3qJ;+Od8yW65ueJ(liFo!JbSau<%EE=swHDMkbc5XF8yWnw z8gh3&bkB~H%ynhDt<~gzNv_t}YvT0E`cO?*nET+zYv|hD2Av^-bF);)uobJ9Zg9?Y zTQYpboEr6uVGbAwTvRUE;yF)&r01^)iMObn?%E9v%(Iw$E;V6ixnN{iNRF7e9Zno8 ztEzs9D5t|I=q4CPf1Ty^ZK|er?hanv2@w>u^VEhe9G1JMynNS2mbqdV-TlRCE!_(g zUt9FMsE}d!g{^tXOnA~+7KwSwbHTJVYUawJTs)VFkS9(U86LLe?m>0VgU`UvGFuYa z;aV(+lgV(hirV#pA)Z*v(i#TyTFxFLcTZ@`J&T8Cbgx0jccE$eO1#$dqHY~?0k!yN zYIEB(7uz^bsof;6c5~!ReOBhyj`E*VrKI}ME({nMU_j`j(v_9n<4Y5Q^1UB!kyFq~ zO|5tI_lYhGH6(;5J)b@I#<2O!ggTicZ6xmOX}r{xzyTaT5*6PUJZAl&>yunS3`1|{ zMCg*^o4Z+DewbF`&*W`Ch)q7#(jsfR<{$5D+fHF;cP~lvUkoThLK(uUwq67!zPrNy zoUFH!vhg+Oe<I0E?{iiLn$_m={Cz0Cr}f0W%3KUQ8#?d*`POEAJ94LZ5KF<Xv`TAt zs#sb=V3eZ7m>tDbF15J3!75GA(V+1Fv<EdDX-N+BSv|4Y2_up{QvqG6LU<B43es_< zdA}@gM+}#_+1Jr7<>S_o<H?Ii`s~N|7FbdE(BEHv6M(EpQ>0JoTlvti&sd~7atGH+ z8_McRytT~Li2O$DBAM(&g_iHLXdz>Uxk=w8sInKk8iT8}Rkii}J`o<SS@piW`gL>( zp+&4g@(f5#UCBY2w=S4c{Z~~I@{-5pi;HTCffk~uf<}!-b?Y{f@O+`B3oW`VV_WVT zN4Z^_5zG<pcgBDqZf92H4`n#<rY`Vj!n58EQNs#K;}1CSUQ#y_<K!^7?DiIHRiD?L ze?0v#tBfkwzve_Il{4Ph-2N)EnkXG(Zi9^uWFnC*HwbRA-EHuGfSji&8T5W=`78>Y zdQA=UnO&|ZoDHz8aCp6j$R>V7m+k+JP~X0S8qb9cr5X*vp0q~YZs?sU;`fbeGama) zQZ2$o{Y#Hk$xZU3ccHe=mH2NWqWHOT`+O6B6qRWv$!3Mpq$MY+w$9R{Zl)gp;golj zyQb7TtHLj#d9QM{!+Tbr6TADl8#O81=_z;;MCx@EyQ<z8ktR@BmVS99xmdgEvbunC zt0*R#`cVSzqWOzN+hSPI9sIDi{QaF-y)I9VpN>8cy-IaK_mnPazwdWk>s=}YVTZ{i zZuuiv{&drP!kX^O$pJ_1FrsJ+p6Fte_6`EQ*~0PXBO+JszQ>U%P&jgc$k3Ad0fb#= z)rL~4|D5*?Lqhmg3g>9W!*KNlKSL(r=0rKpcjYBN4nx@1AoL3B-e<RMy>pT!=L6@$ zD`kzUrfXAiUs;z6gtu%FrzH>G6U!a9nwc${a;T&n+i&?|-UaZxU}e#IhkA7VD#7;s znxY~yalNgoHZ40dbiJ!2bRe=ZCf$&4fLM6)CjiDb@X>2PD)-r%<8nWT(^SpnpEJQT z@-XRZ*USB1eA*XL%!r>!i3OF!QO|rxy(m)iT&zDs`noaa9I_8vwz4>ZNtyZzf^8my zkWN?7#}p}TIX2RfGQ`g8DwNTbp%ZqO9S1Xt&k(EJb5x0nolR(+_p!AEBuPC%$iPZ6 zC-?r<$M^LsP%*2YWEVb-7EMEtU-~bU?Cv&yXmkPl4Kk+YtA}x0ayYmIe?1u~YgtnK z_>)3JSja40NRcagKRiw-v+<&*aV!vAFE%~ERF>g6@6zjjchXx3zlWuln`BVpr!pDs z!QIrsY|Y1=oTk4~l)J91x-fVYL~h68?%;6Pk+QaNK#lR${tSnqYd@`pFZs)$MoPrV zp!)z#--prkRKi|ZUupR7hWgI1MTG+4$(xSjD19#CtW@zZ1LWn@OLXJX?Gaw60FH)y zo7(f-Pcp#k!ztSh<ws~J?h4a&R(LB-g7{C4;mx1;!BpACbJ;eb1dzkPqR(nO$Fc5* zQp{`y+yYUV7=Nn$4lJLFg><)_Z8jNghY%*(>7*GL$4!hKHl}M%AipnP)=gKg3GC(w zzrZPeegDUky_RIqYJ|ea8mn#>icF;xBqn=-fSjIYCoFQCkbzarNe?P$wY&MFN~{qt z*_<La0OOYQ`)v4ixHh>mILYUWbherkf27lg?nJkA+#^)tZz+j(u9Urr+sW3@r3ST5 zTwwndiVl0mb&GL|(c9LJ#E{R;>uh9ss+~kj5??f0P7ZDk%J#&D^(D|otkUAyDjoVH zGz0`}OViFu3mht#1@gnKGPy{<pMj1UrZB@EY?2dxX_-fhcmIyW3wTYI`y=JRx}lFc z`ns%VbMUD&kJLQIM}E7{jg7a}XR!i>utT^Lv6Wq!@8!-xPGaMWOi7h*H1io!A19B& z17UoNSib8jYI|)NUwi!d8CmMjAw|Q9FF_*S+FQA7R_D>U!Pj#(I63IsJLdFRVhyu6 z6a~3WP6?a3o(<I}F?BPa-w3=omD@Cyc-};Rm8YZ+Ylv`hVtO!3W`@~soEXm%&yYc0 ztDEx#uD_Za`C*2yn>eberAym#F{xi<+!nYKPU0w23~sd51FR+hStG!W^W!d*h-GBD z!VJ3H5duYLYyL`T;M~D!J5KM!jK9pF4$3FcHW=$lMRi~F*}AD_z-S&8DkbK^KuQy* zTpU)U!dnRzrDV55(P*KTzcBJUsHxt{@&h4L__GIWFd4f<?|aTUqy*j!;z5)3op!`a zl@X6|aMdjjG8-<q=L(Pyn?~?wDr{PfKz-CFw}So&Ujoh%OzPL9$Sq5CH^K8s+4T^a zItIq-RMdEy!+MSdPx#HwvR#?7P;2AQ8Vb2DG4s<h88sk=8rlNOL-A6($>bAWJ*Zce zIeGj=a1o8LQe2?fAm_tCae)W;z6k@uA!lss*7(`t*gfg~ryce9jh&>xiP-=lG{QB; z0c_HnFH|vjX#=s!E@a8_=AQTih1=z-Dygy}W0G!1F-v>Nm<Vm>gg|TxGdIyn6LtMb zZDfFH>&p2t+_Qa)@?1Ng&{<_7=3)!#jqg^8gf(xzo5jki7b+?0SZw%xy2e96LImW6 z4SbM&64hj?#C=C-?0>>(KV8nb<bT#ciHPg96yS9`MkS(D)&`f`U4*_t{r+K3AT#xw zp4HZOho%k7oyZ7sWg1~P{e_{kD%4PMz2*kx<(aOEAwSlyj+`l~(dT2y)G9?E%Y&Z| zmu`68&#>?mJY)np&hCW=fetPCsDM|UrAOW6H|Ji)TQf{+W?^zAHxRVC1aq-PIkYJ5 z_}gwBsK*f?gD$`=6(xPiw<rPaV33cdQP&47BspbXC@|&G!FMcFb_Z_gRpoZFDZ6)f z1{!zBish3g+;A^Q(sGp~6jlLxyFb>m+##~U8`C3&)!w?ANtlBNh1r2=le$)!=i}<i z1-TLtprHFb<DEYoBcT~iuM3*jQHlN~p@>HbX#k|S<Js&H@b{3${n*TQI<2_OMBsZ% za<YN%N7>ihE-#0AHv>ex?w6oJaU!fkc6r-EJae4)+ap0WEKOTAsk=~SuUgOfq}lHV z`{l!9BD5s)oVg=m26kpx6*Y9(OP&(9BTgeqOK{kMWxOHCq@w=7Ve=C;dY55bYM#gE z&N&1GJMY<6UiD80%Y~RhJVKQ)9<?I^ZTS$mX97dzi}y(bZgC2pW6L#9X~ceX;pCK} z$Mp7)UL^GRtxW-=G0-giPATn}moPzuZ6`e>(0De+O!{JNLyx4g5R2nP!QT>VbRsvh zjn}Ku3y3fPlnXC-uf+%p>7EzT5cB+>xd0!dxhNVn)X`7In!JuUUDx|6xwO=4S%Ik> z?#EQfg;&Df0xYfDYL*=pHm05>;sGPK?!POaLJnJ+<~sKhv(ngUSzOkYq2waM1Dx8- zl?A22*naoz2Rq6BUi6b<&9X=!ZL#{UecMbZ(p*N*e4zgAlH^w50{F&nK%P1BRrjpl zYz|TsyU7YaAL8OMh+RkhG|^Rw7)@y*f}*ggtwn#A$2q3@#6tT+Y@JoZIVq7oS$AJb zo0sd$Mq!v>)Aa1YwznO}u*tq<OcnsP{3xbRTSo(Bj#<W>4r->9oMv$_B_lR8IX*_I z$71m=KgpK*<EwXS7Pjyq1VeD|E0qKUE9hFHEtV!A%DTtnKR)yrdi=0|+DcxgT4l-Z zm9+($=Fv@(QQ1?nFCVpBE!s>s9f5i&{6>H0kiS7m@}w%R>G~XGtsdVt)mDZ|?y<Ac zf3X9(k}jB1p!!wE(mEp;UX{XY-xPuRhIE0<ahRGt^Bp1+IFWiY8Gn*&D_z8)YTk8+ zt*kA}s3fyfX`gm5Mp+mnW|%~4Rj(BLgyXe}+w@G_PPfh+5l_K|pIyl}@_@YqPWR4n z&S$hgbK`VO)z%1D>ru5!QAUm6C{^=aQWP)CDMJ;r1wWA~&FRKJLvJOa&vWgz>t2&z z=|+oI8?4(}^gHrEXK{J@{Dllf;B{_Ujm5)r$cZ5&(R2(;<S~-`*FyLSgMmav5pX_s zeo+=Aq?pFpABKd4(?Fo5LuKf7KV;K&F~wQX6N-h$`*K72Nu&8u3#4;IIC+x`VJ)k| z7<B94rG)2uSy|Kzs-2DP;kr1R^^wFNoPpeN$72LxQZ7&OFijD>9PkQ;PL9khOL)Op zEcBz<77LY$xozZb|A6WANiNHaR_$lQG|39+V9$-*KHkt*-ea@3gtxX+EmSjXy>&eo zuVe5i(jMaF_<gB}rx@R78ShbC+I>@j+=H+yt7AS_#=xJ98$!U%0|Ie=>GSbt_OWte z<38E7QTOJ{2}m2@+ndiZpPZa*g!l}y)aAc5>-i&^c!aK{3$bm-r}bEi;Zd40a8uN? zOtrY{Ba2<^z?J8>KBydI<rt0n_}{?$D6Va9q+fdR1-D<q<H&{hhXjtAg@43;aA`gG z(9}b0m+#=PWlH2_uv)={=Ng%P+r4Eo3Xv}$=hi&HoujuFn(L_VNm_>ViQtx<YvYA= zX>uTfbDg6y46nz#Y(ic^r{AbnuX74E4o_4kZ_L!xW)qHjF!B*inul95KgTZ<ctXPM zXKMR)35_p6APNp7%?&hrtU22B>U8_c$ZVpfyVJo!mb!U}*O(PeCzkMaj(s;R3+v<` zw3*|l|5Y|(aI8emF2PLO-3FV@@p1<$I<t6BKV7!H06|+8xD9?=X(~V_h$6PRdr+dv z`id*X85i0{n)cuP({2zA6f=@yER2~3Y}KRUt#}o&v#B4XpPD3Xq<2ZFuKTRVOG7~E zj=NKAZFiN~l1%)Pc83P&t{Q@WncH`a$ApjmT;Zu%LZQ#Ty_i&U#W1zPak2XhD3g1; z61+X267eqDj#-&DrXK6RCc2%5A`{O7PThdDyRTG@2n$qH;Bf?_nE9X!Y+_Le&-0KX z;dJWKH0@UoHsapJIQi2oxb%`)gz1prdMcj((E4lTq8F5-4EVZIjV`AZmD~kiE#>vi z)Kze}Wz?NWBJrmtwXn`RWd9o;+V`bIxB70cI$DXMSsSf=_bYlK9}%A3rFZD*wZ848 z2x_J%?W!~HCeT*kS@L(=HM6^z@psM+xRfnxz5P{IVBzes+#U@6^W*pB?nLq3ed>Zo z^yyy-Jh%ZhSSh!!wn)r8IdjZ<?u~0a10WxMas&*~{wa4wfBZPm^K$;ID*D_O>>P)Q z)~Y5URn8gXU^jEGX_E-|%~UH8*OUR2rTjp*ZN{+da#d*iFK0%~L=6TP_j!V}P>cYT zx8r<WWt6m1ViX#CeGvV`q2E`XIr-1GF;^V9RI;e-+wr5I2iR{ZrD&Gg?<w-v`>P%3 zQ6hiKi*l3|C6s!OmHl}<VEWcrNcr|M4cLldBbZ^*7U4^QD5HU-c|Dr}B@)0X7nzW$ z*2|jn%p-rgi=(Bsd$crETHVW}FYx^GZGCatyT5!W$Bhy@%6`kbaQPkf_9;qv(OhZW zVj7{&2ZXxm7-Fsgo>^V*m9PLt#-@&4?*vvXDWc+>M9E*>mI1)%Xcs-_j%O`~R=woU z=^@AMv)UQYr5MYE-ogJ~f3RqwC?&AzVobp>S~gTBgPAghELtNKWJiTvWAh@oKY^|g zncTa5iZu{62aLKV^D@v2xR?m2bG=CFIhEA8pvkei%Z(tH14{ESeXE%;@{P)RKlXzX zt8BfZg#zyZCx@6M<<?W}MJB<&mqdyEGZ0BUz7)>A>q;u;{hN&+wKP<=J;_*sXv&Z% z7%252BU}Ct_g4WJW>cj*^V%F)8^CaJ4xxv;vz;NHC3jlQsA7MWl@=8Z$BR}<rJblF zw9c+)f7?s@e1s^_e>F}YIU%MQrT#q7b`Ft;5*hoisAKlVQDi^IAWj5OPSZ~4B(}kp zchwN#^UDRVC3oPCFuqJRYfJeKRhbBy_Osy=uC45#K>qVli9&UqiAnqCT<+T{BE#Ws zdZ<AgN!oY!<v@j!pQLTnQ1Zl!w@dXer2$@{!G)OHr{!_xZn&BM`$tYI?68S-9uC-# zyta{#g`V$D0iJlV0eyw|4?9@KQorvspw`)u{ruXoOT)sU-dM79LOpA$pv4qDTLx`4 zA1vzw4u_#|m8}dnrAGMe9+YE5Fv0igFf$yBA}jE!X{jLl;chF^e|=1E3LK&|{`#*7 zf`X(M4M?L@k{MEmj;Ny-<yg1iDZg}o=!IuT<APF?A8-6>GjdfqMN~9k<qY5=c7Bft z!|e4OY9>JHS}I1>4A?u<*o=v(yN-cEZL8m6ngfqRDDstsZ}R;enGSqsZ3+t#l=zF9 z<EIYlma^agtnwws*WpHJT8kCHoxFWHjh(iF{I_m^M;Sxje2J*0be#Imdn?lm1msPV z=O&s_u}Ev!mRmXr9x@%aQ+12JOb*Q_JvQro@f%_<&@$dxL^)l*7in1jgbwjP8%j9@ z1nPdXky6+i0P{pq7IUA(R!J9^9J#@fCXH_e0{i)v$U}pm=mmg(Z$AF^-7DRC_6@7R zBQJ(q&aSjZ%NO|VV->c1(ANJZ-Mfv_r1>c+_@BDr&jjGg0@^$e8AXDfj3N%(r<Ze1 zg+OoaPa)~${)`(x?Q_heR{CbbvMmLcALEyzA8WhEvi7ZE(Z+Y30T&pn-yPvCM*(aY zuim`|P?wSL!QHG~nIe|Ro%199l*I){;k@K=%qVj!z_3~JnAGhp#BRG<^xNq~XH&SE zcZ*Y|0-=Sr0Bmw=)!Sq}NZ|EKgs^@duQkp{5CM;OIpJS;<j)(xl`<7YrQbra+r>km z8mg16CO$V)ZSaki7}O$q!IJE?7jgz>HiFb}cYY*m{n@kjr&tP0x07`c)~0<m@Y8^e z^#o-ls|*(@Vj<sZC&J$!kf9n*O$W8^K)g<b_DFhA<#<{=<w;Z>e$vwjW>}f8x`CQT zvuqwH`{K_5=nsIy*Q=3S(DN{dx&>}Bw?A(=UN~!NJA|bF;}72#Q2ty*m4I4?9GCN& zZIUN3xTo8_7^HOLX)(K>ixHZn3>m4osv3L`WESIP-zP?~{%ZP|E`X7ydTBxM8$%lt zmVM>G(}Z(qHk`Ax>9EmA7bDR5%OJ(WbuaIaLb;}oi8?o?34VdL(qU`L8N6@F0Fmu{ zlV?5I%JOPIY&yyU6xen;>jTk*yk<7|3)W(z{0Vq`vi<p~^$At8P}S!+)BWzL7Rj;- z1l_mPR7pFZfs9q9zaw)t?>15Z*fgsUF#A^#t#d-PYWW8jO1aqqp0eOd8{jm|EI^I0 z*m{oPS=E#2I>2Djy#-Ykx!_9n+pmbw-%8PUY?#C+ve}|UB<39FFftDdY}atff&nKO zPD~9X#GZu`0gS+SnQ@!xX+7q@A~a<fwO!_uU{oTgCRsS<Lx?C-2^)~T-H$tv3r)Jh zX&GpL=Qig|n?`o|o&m>o7Uae958U@4tzcU5qitg&ZKLzf8XOF8Ma7hOhPuTl8=FMv zmz)CZfn($Lk7)kTGRoOjl%Ea-f3(!51ahab`toYa6ezC#No#<N9#vN+rTsksMaJi5 zHJZ(TmU2=nke=zW;?AHO90px21qJD@blZ9XkOm}85l~Ia4dadd#*c=;z%-h&I#7eJ zdy6K=v@`u;cRMfc%`EK6l!5?;_C1gjUFnOHl+eJpA-Cci0T!))!I(z_Zy*Y0E$;h) z{g&2aC5*_i(t~evZKp6>NnpQRVupC!eD$+650Z-7bo~xs?==(!ogWZ;U9EdfW3^4Z z^mMHmu1|U?t}u+lG0BLd?3-%dd*IkA*u*1hXapw4mYaHeOuVUQpl)}Oy@y>X8^dO& zqB@|4#iax?b8;P;I@kY}07@`xVV~T~+nJHTO)a64z_jGgaUVjz4OYJgmAU43eSd2f zDt)aP^+Y|oqTM7O<FUHVL`GPwYqpxHxE__jQUpMd|9{vZ>`!7Wy7R_C_a4URO}}yF ze?O7jvRPc_{3~F8H$!pflO&W(iobKHo#`q3S&3&^X4EpjI&eY;pe0-W<&RGxz}5B% zKLI&_;{ZT-trDz=nmXQ_I>z>u%c^-&H<l{EX}p<OqV^Ttgo>b;&wwBP6h@Nz@^a<K zd^pnL^4Z|?=K#-Qg~);TG@_=~>u9kxHyuQ%ZLIhy?;oH2Nr=>#L0w$qA#hl4*0=|5 z^7lPi?@ze*?*z<xA<p9^r?raDl|C^ws9aOt%RUXOgdf+tqOtd*1Qa+Kno=bOWxGM> zsQC=S7IY&|VK8r=pa@aqSy=C-FRh)mg$D)#I{g)Yzx;^i{x3oNdhsY{TiX-BS+jLg zfVgONqrqKLN_yb(ScY&->f|-QNj|@ge`DZ5O-aQ&`A5?VhNK-V>V~r2@+Gb&iIyVW zskLF`>q@F6k8Mdc5I>!K;Wt}mIluVWX;}Zc5$WT7)R>U+fCn1qL0KhViR989WNj)z zm$7I4?QT}$|27OGv~vgpMJ83nu<IAg>&|R4l+lOpnjKP3#GH3`XCqJ&r{<MzyoU*3 zT*cda-o?SHJjowl{t{n~8_nnjzHTTLlKZ5p@bz*?;E<4r6bvUv#r-d+@<$g*=dz=n z`p6+so7>kHfFJh(LRNgykiUx$(VSVFZCAkevK(tBw044#$z@8KOhf1<hvCb}A~GpP zzBWG9#x}(*@t@lMb7OuEL^TZ`tU<%Tn~m1!w?`(=iHQIhk<E7oP(O(*wQ?kZ|3p3{ z#H2@4(<0RMWN8I*5A^zE4Jvr{XKi2~;4inKkwgH>Y%_KrlVm#i3=_>6q;9WLb*IN# zK@6S=dxEwXii!sT%px6tActDh>dHb~WWW(G;QC501g#kWZn=0?;BWk;SwO)+14y2s zQc~=Gx429x=oXqiuoa8j%gG%I61iK!S~M@|eay=D`<<)c`pkNvkPFcd{7BnZmEJhP zKXSHS<In8mM5SZC|0wLW9E=RI12^=**0TH#Q{lH$ZJ?X2>?QdEHgL_P9{CkSp3Q@j zPK^H_eK(>Z8Y;z0QkveTapUFYV*j|7{cP2%FdWwcWMlPg;Q$E0nCZo$ue27sAN)i{ zV;13tt}rhG=;GG*y(L3Q^XY(a42KFD5<fA*WP9ah($%3DGFc*~$lY=E?QStlAf?iW z=WH?Ha>fd;%6$4e+hP~l0;Aa9yutPziaUd()==;<>&j<#hH^F6hN+9bc$)hc5)6$$ zZ~`euXK-?q&qz2d6?}nI4}DBnyz)MPO(>(Y)_+KIYQ5q2BM5m=`t;-}gMDppnRFca zhAyIHn5NZ7qAq^fi%&y;Sso?!_ox2}A+&^&HQO{VPb7Z!a)GLQ##i}9VL$pXB}Jo{ z!wkF@JRC9199Druu2mcELH|@t5Zf9NfuS@i`Sh3Ypn%}NQX~@M5EWp|Gn<SgF2U{d zpPvkL#7mQ>3g2$$xdZKzM5?c+Dwv<6|9OD__;XIeW933;^Ya4-wlxbPeR*1Bd&9ue z1N;gKoVT*if&0Be#Xx#dZ#G`|A3gmi4t!5|1YdMxag|SlF{PeZBoAdifAR7w5XRHA z^lS=FrT9(a4?Y}+`2X9MgGD2#fcr&=k%R&}#N(bs?E{H5DOLo2eGV`?06nwUyCvw= zA@;w&p&aD~@RI|HV>}b~PhTVzQx{<GRb5$J0AOMRlRBM|+3Y5tD8#xw?8~1r0*3$Z zHS#|NAiig~78?1}U~cO6!*Y4HmTHOyHy~&w6|t9IN77}<ptDq~=(%(g6skK9My^u- z|19*U+G8CA2}i9(489ay281e`?og`>90F7f6^89|ko5zbW#5rGw<Bzr6`2n0yC45n z{NLv%paIrQz@r2J!arz;3Pg`Ofl3k?CK>?|pn8C@xE{i9JO0xhAZ$QDVfD_?bH-wW zT0EXb0*B~-7K5l63t)52MbQo;%28q@6(dy{fH3cNf5i7*i#~LUsqeZAvE1e{r@A7r zyuvOYIl@^0i4U$z{QtR_8j=oHbmai}H;1}hWC|oYE?qY(`4ng8e}xG!Ex=)@GqF;< z+sKGjI0%Wl_-Y5DU%oMhX$}-m+w2>;{JV<yj}Rul08czI&)=a>If{m4u1g!8sNv7Y zP%W9wdsuMI=<q)Y{4ox3JqnAfPU-k>^!%^rM9KcB&fzDrNdNxwZ-r@aJl1n=dq__I zE4Kgpj{~sv{TE-~|Jy$PS>XS7<G<zjAL0JLL)7jrNV|J`>WYdnQ)+?3GhN3w9($9e z(RtVt=>M3=BsE}Db~w@J|7QpXpF|xT9CpX@BAANlE9gsk!K%(Kxxe{eoY4Iv14e8V z$y&s(^%(!X4#1K|X=%%)bK0o+!Vc=7Kz=mRGPQ_FDyUs+h{FBHj&iCVL#mZc(K5$> zF2)-AMDAChj-@j1O6X&6%Y8MH4g~Zd*(N3?3V<UCQc7zKf9|R#{bQBZ$dBO;89U_t z|HY9#9MO0(kwE{(<4$xaaH2^Tp`rWO`HWR|0aQtVrL<u)O-W@^=cbg6*7cu7i)z0I zd=)(XOBG;`fG7DyijX+%ver}JHq1vC0MsQrpJ`%cn85X>jR4CC$@E%GjTO3_uAb1+ zA1cSuNYZAS{+9@6LIFRnLfxi+^LQx|1P8&_tTXmMIqW$@#p&$|K)X>#rUn)*v-}=J zX}tdIjE<A}@AOs^9)O;{0zeelH9nF80QI~#^K;N+$}ol8cRSa;=ap4{7?DxEuIu<y zz15K4oq01~su<MnQH=dN%4V&(D{#91UXLMWu!?z;L4s5mAnKeNlpLKL^W{O=ozZ|A zn3}?h`o+%@i2}6(Uu{sju3?h$4&xEQVuo^7k$NGh!mPKkl9Bkj9$?7xpAi|1mZh&M z4^a82ypZhT(Cnv}klz2S4K!~4M!1L$5`gGxR|p#(?-fl&NsAJ8e1Em1Jjh)2g{e-F zL3KhSfZ^vcW?Rx^tDFVeqHN)D?YPV8@5ol@F(NuMyMzx*x0HW^ksQO+s`MQ}SAB9` z>#w~O<G>xx+l#%z?O(^zv81V+01O@n`d9Bnei`#ovi{429*K=P+dgUuKymJpNGfT( zh~ZpmY^~R(w?j^W37gqL@L%9x_(J{+(%0QE(`P8sCgwcLwfsppj|H$iYs2fu3f~53 zKQg8)sWtux(In&<5j;!0VP*XJOIzJN6&DUL9XF1>B~=!N4qSYbuuo9HoHDg^EeLvT zEIod`frq60Wso^~IDjYU>A$%~1GF&{+YYp!aMASSCoP9PH`5rfH_oHkT4hE=9-5g# zg#0d<m1`s!US}Bt_0S`4&L0AqA?`-w=iOd(?!wsVA#pl444(pceoJ0^{#}4;^V4%| z*ns4Sg$zW}Kb0@O16|X=0iI2+?RKIJ0-Rl!b~$Z^H8Q1f>xxjdgJ@yMy8zhF4nP?x z0$rf*iUrbd{|@$3kJ$;l(5l)5Ji9d&V%<`p-|c}@Q2H?cUP(2;AtjcEu>2A3{nlUU zGa_`Audc+`O+fcuEHyz~nmADyUkYCuOkmv5uPM)jh!H4F=ArS(w&<4wIQb;m(#t<J ztGNqPfOiQX2`qGP!i^PQN#WQJd{Vdph(jkmpN%9#S&bI`KfmqeczsUIx8fKcRqkV& zL-jA5_J<fTQ!75{IGmCuSXvy|W3Oh|P*k`pY3PD0+Mu0rx4YW9=S;IdF%@+H@vxn7 z;Tk*ph3j6{`lp3GlPo}Y1k*y56|ILVg7n)YP@lSYqSEF2Y-MVfBxk=x{GE4as<Xjm zF=`xTBMV(rI#2x(t$7J}_KD%g3Jq4Ey|IHVavhxAKhPsvLU8~sjAIHPplhq~N9|G; zxgQ^#c5FJhLm?Z(sh!``6E;Z{08mLapsNA^k#tYJu8K{x8MynMGBDP1x@sn7HMItm zZX<g#X&`p(K!3jL_~I{YJq#GFvzq=zN&wR-60pXIZ`a9q;|<XJ5TJjNQo9rga|hUm zTh>8F3BjFK9V3H((T-~<?s}5RyZFx{dy1zTBxvVV&{5@o#UIl8hdp_1KD$KJqoS3L zv{>5piZ*&pmC*&Swo~(^U3-p4K{ay?K2B0tH&)p8uVV1&+K2MP{+dwZ0*60zZM)Mt z{(fPq;q34E?#AK*6NT@NyQ(Mk><S+F)gq^*R%i=bQf*}*%SNFN-SOR7_Cp5zvaXFU zHshH*OicgCdW?X49T-&tj|Zf~olPugF@Uc;$gj&>r9jYw#zfo=r_3@AxX{$jNM#&a zetM5ycugJ0Xgs-KdcUHow85FIZF4Ls9bohOGmZ_=hrK)oxcU!`c^?z82CslFRYsQY zE<@cNl$%ky6%zih7{no+17)nlrPSyKGoq*{2cp>g;_%pr7%lLXFUKWcsS`o$q@Xa- zMRbFujC(NrI{KyTro6<Gg&=nzfIGL!A;AX(i3WYMM>hfi4WGVjhJw^r6mr@#rix)e zkeu)v=peZ92QViD*h7{5eK@M-k(j#Rl%y?v7e{BkLXo7a00)>(Z@$M(GW-CqKX?Q( z<)bfFDC)NLe@tQk!7)D)D+H9S0dA#$uL+cvccSg=89(^ynMTqM90^#fya{-|L6{Bj z&G4(hMP_vmZG8tWwyHk7ohT1hQw;^}W-Y#TJ6Ycii;!{=_(_~20UY@Gu8$_SP3Wt= zvY@*)ibCMkmyrMnwzTf4B*(wn6V~LxN=1EgqGJ)p;^KBlahoPZu{ucpyBZAp_<Jk} zKj}F&k*^FR&@b3*UpIR!0IpQQh0rw+h@LDsc-@%<15HZQ(nWN;R=lWez)K!{WQ}ju zeQX__Wdaaeqror1w}fi~yLuPFaG;x!5eV$e@Dmyqx-wYm*1rDbf3iSG&UEHHLaaME zVERm|!T{(MXePo|;|z0WFw!pi<XLJGkJbk{P5G{=OBa1Yqpzq(GKBnqtm{Wov6&*A zCn!gkcHFCc(#YCVOd3`*9zp2%*lOzv$M_HLUzl!WnE%xHyvQl=EWMTF66lSsjjcwf z%PmIVto^HG21)0rGghKJ&3M)4nEKe?iCa}K1;0W1f7pAgs5qB(3p5GtE`i3~-Q6W< zNYLOO+!}}A!IR)_!5e}F5AF_)ySoPua(~WQd#|<kI4}44-WM7eJ-Vy@s`_Nk`F$n- zLL-jC(Nsk6v<*g|Ug||h0K$xZ*<*?O&zooF;1006X?{1IWOwsYYlbZM?}f;)?@}y= z8fAI!+Brj@HDhyANk7}M6mdqO&#KPymb?8LfJTYOv%gtS33L$A^P<i7!8F*^K~6iD zfGNDsZ;E;N6PI;QEdt~=2HXCRzq7jLwFiD2{^)M3NzBWwLb5wn6*{VM1x`Q#5W$EZ z)j(CaR%Hd5>$It@y&*keWPTpGEXi-9aHezFS`g`!@aF*Jq#tiCcfCmXdv`e7R2mo? zy_=g6hK%U@+Dtl5)(r$pRv@3$7Qdh!)2aw`hOW$uW2(rr!ZyO#6Yky`{!h-25>_yp zlBqpF7f=MqwZKs4oj*e#x<&zT%~f1DqPoF-AjNkOL(>^VLBwzXWbm4|NVD^)#+?3z z2e&WK<(0&ic;x}ut;GRF8P2MI^#b_$3@V_P+A4B!Y1#Is<iGdPJEwQ}`KN>!87_hu ze{2c7!1A#2^pNEs-u0U)Kac9*6`8X(Hh{m#Wu*?hdq0mSdZ8hBs}yODLsQUxes8S& z0Z0fR?sek1rxpDG#hAiH93X@A=ABAQTmNZQTNv9NcNaw_w(Qw-HE%O$4z$yH=!(2o z6pdILcq96OL*=$2stS;Bv_3t!0;Fof!Z+c!laJ>~tv4wp!A`#bGQZxL(MwT_S=H&B zA=X8wAGmLnpdgxWxqi_=QR70L-MSh;m`0t9=Q+0~{D2fv^+)r01cq!ytvkT{Zb{%x zy}x9-gGlw<p|%2otVX?*TlC6soB@Vj&^Vu3b7Zr4TswP#X5JVXkPMGB?dvmBmHz`K z^L&;WB)n*oGw2utG;yoYaZG9fqs(fQ%58GcXbeO6aOYgD_EhZRq{iiTrVWz7hZW~R zmX;WY(z04-WBEXAr)nvrPle_CZEF1csaGBVfsK7|gXvr;NbzFhv(3;~Efwp@o{w+3 zH%f<c&3_QCq?8kv3K{RuG|D!J_nQzg4jhilksVFp;*;oDo_%@(7?noJ%A?wayBBcC zpXZf?=^p^F2P&|Wz5%sTe`n}-Yrf(}Fi0r`m)GZaWMlZ|39w`L{DjPLRiP1~KI8V$ zKbmC*O*q8P4x<K-2b)pQMK07<l(lb9_x!yqzi2rn9BD*p5OpwCQYgh#&6!2$aH7@+ zm^)=hSE&pCXgU@gb%rYQ-QsQza4Y}ny*O;cP$WN4uKdW_u=#DvJ<Fpz$+UzAUkz6Y zoM*vB8*k`md-`)b)uu5pG9gJn1Su@6U>}*x)>cMD`+9KoC0B6K36SdV+~m?%8{=Ke zWM(S})S#W<Oiyd}M4tSul@QPVpLM`Hz&64p0<?&R1!1IKeKV#`Lod;D2-hGC?NY8K zb8^XRa{8`4<d-?e_3J#)nPiJ+5ke;%+r%5fl5IgS{4(RhYBzzQlG2p4r}+{^+8p_2 zi7KxaU9cT44eSS4t9hiXW~Cqb5F{Mhn;J!Cs~QnG4@Z1U%j3bx=*C<}bvXtVnZ>qG zg3qEj`<xEONVgIJxLg5<9u9)4^NgYYF9(&b0{LE$OVn>z4E~9BD$%1(4&ERH3@}YF zxAwZ4eDZ6_R&fSN1(UHL;R}M8-&iD<uaEJjQ^A^|KI|;$K90(>WRIr^b?+v2iWUH! z!+@`X`T7RE-cj4H_3k*UZ?erySrd+Iy;TVCux)|L)%<sI+zC%3LMIo+y{MulUstU1 zqJ@R_F3=sKc*CVpT9Okws=EZC&*_SilxMe4kXn2v{5$&QuIkP+fS5k=Me9z`|K@*H zoz)Q7&`aul^Ao2=EVt16b}WqS?yk5nb3cdxV8lu>Sii|#Zlz4uc%Ea&m=i|wXf6TL zzr=&GyW*(-S|x+83Ev`Kv|(W=(Mg@Q5$WN6X$r(7Ukjt%APQ6KQoWS=<aNE|?i)4+ znDik$oe_ul)1#Di)ig}Z9y54<2s3IrIci=-wpFo+e5ad63|La$;%EzCL9nNV;Z3aQ z2HJCMjVe2VFyVH|E2u5{(=zC&U;q;8c)4cs6vB3Ctj|OubeJohO`kiNOCP8zcV)R- z8U-MoZ7iMi#q?0;b%HE+Ok^B@=JLe03)v8$CJVwUOm|kC2bkO?<m(^)4})d?wjaA( z-&+;6bXVoH`@YHWpcI*@H}Sh82x8TioeOv!$%ikI&r+ZzdMP(vP|mz$gvO-dSj=SI z)k-kmMHVjz1{na@HjdEs`e3neCY%M2Fc7|pJ`gc6Kz}j>G0dYrT9K=IMv9J3)jMr` zFeWup6kLJL%;^DDyU$|oKl97}T=FnvHG^n;i>uQvH_cCve||j_ac!9z)9GvYRurXk zCV=h$1~ZkZuj!=4`?Ul62Jw5>(@~)ShQ5m|fK|y8hWj<E(k%?sH2gamjiyoqg!N>8 z!7qckbb1Jl*~-l&cXtmZ+Z^>u-2h6op2rl(FI*`i1o7bH%V`{|!ch`mfFI2whzC^b zb>zgSrSEVL_)`=kJ`KN61c2=UjoHYfw>l+vR0nJ+;64s|NMsYBhtL-<K(pqX#;NK@ z6T9OVm25cInm9teK79l-$Hw)#c6j0&$jeKen;l(rRE1G)<>^9aKPJMTW)GECHQfX) zH}vndk$BWzigX_kMKakCsk;hn%ZySS6jUBp@?yggJgS4|z9tnvDOGk86<+Lfjj=I) zVJQpRMI5C}95WlHO{2?cQx_fJ@x|9lsnwQCP!;8+G`V`IsS?kHTMc9tb8+&OOcQSn zZc#b0W3i(tqw<(RYpCcP9xr4s+;|mpPjGtU4VI4>d%1Y-v087MnFOj6c#5>M|6CsM zNj+rua-v%Bj}>~<_6?qRul&i>gQma__t>3^lTpVE=hdtwd9a?h^Xz4h)`kD9qaPIB zm`pkOHqrM3f)T+y?SCqhLu!O9K=`>F=kq^YJ-Y^MiNV)=cx{{Ha(7@2s0$n()(Ki2 zUsm3%$yMw^(BB|;;2rqAKC)bz0lbSAzI_paBy&ehd9hI7EFi7O0#X!jf<C+xKyFcr zrRM+22C}pQ<O9C@<Og>^XC4s(ZY;(8FWm1xtz)?+WOC8Y;StFBY*o?^NcjN9O?$BA zvdrOD@NGOlE`B`aK5WaR#=|=g=u<n9OvGgdJwZZ;Sba@ho)7c!b(#$N8&Dc9&$gAE z-`mjm?PsV&DiqaeD?~I`0&#unxRF-OZp8I%`A^UbQr-QEV-pr>0X*<cZu?L`oT}(t z<;*)f<1*2FAJo||;3R$U+1@Yhgv!sR0p@meduoI_O+%kv+xR;L^Ud%ovB(yiZqVWC zoP`20gmUVvdP=~{>4Mx@>=6ho?%Rp*9mNk9QSA9?OXWIY11}J7H~W6H^fc92Ep0sl z(Ha<a&&5Zhf}BZ&d(wV*3QIIT(XB;^A`C%U>q`EQln_B79uufLMF$a5xt&n~0NU|c zo<HOMBb!mCV%NjfLE^fTCpe+;;O?fBgqa4?4Uy?WE0foHmKkmzRvD1VHwhjJta$L3 z3E8?Udd_R)lJ}zll7L3017}(jEc)KJ?bCsYZ-1|@u_Fap6CXi{az0-4)oMekHKOWS zk+;tWEQD?byKy@7fFy<%RC-h*?!H1wP8poS=JQBTH|2ED79}^=!<S1(eq1bOnJQ{L zPmPw5O@c}z4H6*kHP$gdMS}Yxh!0g@pdfkmr0>486@fcj@p2NG2_pV3?L%d{;;WCu zXPu!+^i`<H&xpS{>E+N@gHf6qY2r6RgT%>15mVTLZ`<ONE<WmYsJW`0zvDeCb3#QN zBWu?%|19cb{JtwU{O#xS{&zdM8V%ol@Ae8GGCF1DAtdH3{5x$`BS~CF3NSzD)3v`> zeq4X|M7gxiW22@1O($zm*8$XgzCqGmV*^>$K3EGQJHi0p7?la)?Y(6cTd%zF-w|3- z08}%H4y5_|2k#Si-_q`F;XJJdVKm}pTsA3j^pune;`vTU77`Ym=M;Ltzn@!-Y$q;H z=*7W(#AFpsZXB+H0l%>r5R8DVBkQbl{*8oMgnsf(7n+<yXjEE(O*sF_N`#`3eopGt zg*69TZwqa4cG*k#!9k{*E9ax(8ZYZ-S~E{Xn;KtcW0e9&y->hzAh+P!<H=<__CT36 zK(zv!+YC4?GmXP)Wu){Rm4Yun6Q)#BFg_GjpE79Xe)cpy>#nJ_=UR}}or6@&G1GPz z;p-FJW`C&W-y#9e<}CJr?TdfUQJTC@m-mgkn=o{$y<!8xsmA3bJ1OFmI2qxHSthaD zA)>S+W|iJWc&vhh!R}fryL{jxU;MLRhGuPAC&fqy#kwTxre5s#-~rVaGhT_(gS@=w zmJR?@HpDA3`5W(d5h`WGOlC#2|GV1VV&Pj0eej}PsB8g-mf%)l8SvqD#j>|Ll?;t@ z1yq*RMM<5uFKE-MGWnKVp|()tjP!w$@53Ta7HdNm3B%24s~UTD?3@d_kG9iqFf>S{ z3(pPK5=1YS{hxgOcjheo=L$}|vA485&!^ZFq>1!!4m>dgce8D|d<Qm*nLOpCNc9Q! zzG***uYoNfruG^GA~7D_Ur7be-SmANS^*Gd%cJ$5MsUmomeA=KvoMy|Z!7lIWhI@; zOf&~4fIZvhUC%+H=VX5m21=M(ry-Ya=5y+s`+PO@(C{&Dsa=jFt+7+gLg_+$x*s}M z??Jg!)Z2@jfk@63z%-JFs98d{3kDZ79|cWC*EBZuC25?x4LOw0Qn^<@CbINSPX94a zYt&boD6u&UejD(1$Ox_lxT>&rw65ffKyp2{MjCJ0@Z0Un?`*%D11<A4l26;~7z*Yf z?=lH!It#$6GuH{V-x80*!^*9gKw0(cKM1c1#UA<>y1;XG+&?BdVs%)mb?8Jgl$+e( zV!b9>7}K0>_icCw4R!VcWWD*PB+Ml=j4#~uz-tfF;N?sAp!Kadd`k^o-!XAtVlULs z93C3)juGn^ppOQ*q62Iz;dqZ@q0Obkk{Na`T(MaG%`>}yYFTU2rJQo<Xe!gQzoJaM zMTbF*@B9?FiyPM|bRt*1Y%z~Kk4m31HTj27)Y@^AZrK8kUnHcTF2nEp)K8MSO}A&d zEu(f~VRDVRTeJCVm`(bT?%@p=Kg!cTh{<d_MAu|WCh!Htjscmo?_|SHqk!eXz=toA z#p0M)(c9<mdcwm7ni*RO4L6n7xHc-Qnp2jfRJX`sPwF>fSTQMP$ziq5;Y2zd6Pjn? zsWNAH6Z^GA;$`<lj971}l#0vQHyb(AD+)l<gnEX%uNpEObTtuE6<4(D2YPng0sh{b zIOoE)s-JeQ0FN)R3>vB~$E=HZrJY$!mnZ;%@Spy$g*ji{#BmTBYy1`<GdeP#UjBnA z!}8-c#vaj|(o@Bi0(kF*bf=!z24N-!`ds2>HZn^l)(0jTEp`>#id2{1k4wmAwDawb zEb@G~JG~-v=@If#mN#9Z13%{?UR8NT_}}7wqO^w=RhRXT^196qQj^*+M^HpSCN%I9 zb>WR{k<XQGtMxrZ%Iy5OGXjya#2)rkGsNPB(@)nMwK0y<Tuys1@`*EZ5LnW0dUgc1 zm*fR4;EmKR*gFbd2$2od&=>dvEPu6K)z0*?$?Yl}3A{ODt61&vQdv{?Yy7bqv~^Ax z>Jn2LfBG3-xCQ@7eU<xN(f>r3&^631)q8eK^=~=CSVDNZDFb0T-~!|AUT{G#l*buD zJ7YaG>W`Ux*YOH!j@I6I<U9h&vx9{+83k?*iUgrtLpPbRO!MarQYI|Vc6rI#^Nmp! zbmmFTj_5`L4jg<%AT<c4TFkQzq=PaN5B|7dIm_vf_rOK<Q~Kd^+^{2j0GY5?xFty_ zz?Q-d10>BWbKp$3wM;>-g-@;t)@usJ5eO&{KP6K*Z#^3!{nYIWN|g)7gEt?{4VHd` z=F6++cuAaP@cfALE`gFPj|F2m>ACIKTfe$o!e}%u0}%8O4ieQNP{zV<g}}Mz8(=Vi zTH4t`HsHav;N>&5+Zr@vMtp4xd&sY=`PVd%KE9*SZ*qdavQ8D`T7UjbH;+o|n2(t} ztEr81@q8iQY+~1|Yja?#pTe3r{L>>rRofKZ>)uwmY9{HmP(7vU2h+W-s?pW#GT)Kf zJeOLY{SmUuuOTUd^Iyd?d%zm3P>OUi=%NBfx%LrKTwW#^y_^j#z`?I}d4AyukgT$* z)@gb9c;u0+M$&L0Gu;6to`16?Mg@qjyB4aNUY@^Ez#lh<M0gulJrH6ljecWKoHE%L z<+}Z{-EVI{qm92QFR--@Hr<Gt<{vrb4(Q!;tfe6Cujnk|-DYp+p1Y{N0P?>Zb)v58 zla-Z7wbbdvIYNKhE`E%g$+=)kvGpzIg+=%~+Qpk~<#|vT310}-4elAPA+1M226(>T z{gGQjs8Wb^B)Ei@PsKW_t{fY_)~MS;806Cal{#IcAHBr(Fqca_t>nZPxKh&Y#q{Cw zNBkbyKNcFdNOWvsH`ynZT+DXE56?82&{9=Ol80T4=Fc8=GBEx2Tn?%2bmy5mh)!|^ zWV_Su{2h&0)aeJ8OG52zlG|`ofa&|${zTE?0`;zbi9!ZCqSG#yp+BKEnHw*`%}Ara zz$DYvFf6>>CV8ZHa6<c4NSNh)bWNL8DD1uLm3dVRwSGhBZUz1+JTohF7BVUqWE%K! zWf`u5>#YLIBE~3>Z5m(E)8tY*Hb+I%RGb!ZVm6v~4ZSQK!Aw3KWTUT~K-H!LIt^L# zQRo<!)pR0Mr}l|5D?X9K16IW86<28;WW2%aA2dg%S&oI3y?AriXGy?kKVQBOn@K>+ z;y=+W*X9es^EFl=l%uUY;1pu1juR=LE$2ntCpK_0U=ey-eTMrGcjdcZTzH>iR%qLz zz?;15QyEtQ4h9Ea^)mOj6qC*_y!hnss!;#i9DO8OYg<g-+E7W_Y*8%9?$l#R9DAoF z6*F&~X|JswL3wV04bY$c!@twH0P#4)nlwr#3aMA*qJg-*%8tST(UO1c6D>$i9bw_Y zcha64MeyJdnQUqPc=13rkBE$r&lUYKsTL2X5%T;+kc0thkRLtD+9b0KD+ou$02T|( zz=Kj0M#V06yBU{Bx`h>xbgpKSEhRGFNg?jE2{TYQk|b?a=*Pbw6Uagn{~Of~he+#H z5pgq08YTRng|8sc){BBe?9x0Dpdmj^=;?dr$Un7$<M0}nNwuf)x0_*X<FH((ot4D& zmNm}lD6`lI%ZJVbF~uOBj@OloX*|tJk<IiphxAdop|ROZiFc)bhs?t%U)Pg16n0@I z^^D^e-f9hX@`za>A?(se-zQGkD+^XzHL#C-dbzc_J40W~e@FiCm6swj02XZ)cOjbJ zgN{U05lQZQwnuh4)~M=(^r);kVFb!iNCzxg4Vl=@s%0YA3PYj<cltmuy4^^5|7L<o zcT<oL|9+Rt=Wi-vCYb1O5mc#ai0ZTogL7^4q97EQR=Yhu10yc~$&pnfe90BN<VPhD z$8$GjuLs;(09qBor-ytb)6+UQ5n~@iUt$b$Dd8!~6T};&K#fuZ+tmgzB_Ae3xVyLr z!`FL+Fnb$jn!|=)ogi}tg?+?P9qY@Y6uCo;_&J<;x)Z(`FGX~F*cDYZSU!mQJ=-?d zX#Sn?)ApCJyF8Do->y#Art6NVq58(i6?W`fZsIS^9l!dClSz!r<>dchvy>~S{3CqR zf#56t@LqTgDmUAnUY)-e8=*nQmH_hq8{#ywc-}^ln1N8a6dTcL5JCXvrwJpQ)cenb z3x^#cFc6riFQzP8R3j-~g6IL>u;?R}n?%NOc_h?D;;jsFM6h(SgX(IpId+=GVd-N0 z#VciuYkt~_2FAekP7CC}v}m{mXsESUJwT>-*vwWtYhs@Bz4%<0XoLf866+=6O9UDe zbCkm(s;xI3p|r^qAbdFC({4Pc>`X+BE(%xY<?pZzs*3|+n;~Ms!aoZK%BW@L69ui* zk|@h+Pm4LvWN-}jROyRA<H6bC-3S4x8`2fIIiJT?2!-3QVWw;NrUgM4m@(=~71R?3 z-B(uDB2$@T8|iOiW-)(&#sem@|0GT@7f`VsNs%}$ZnQ}TRwHl+?=_0}GOJFa$oZ<1 zs<YCQ4Z&+07AQNOhI9mm;2TV3g-DF=r1${Px-gr0pQIv@pD-PNxf8t;h$iT5F9dl$ zH3bPI6JpZ;g6PQVz<ufMXLG#5`%_szkBy;sIwVX`$I;)4D*<#jm}tv9{J5YsRZz`V z#0;`c*^l#VxX_MD`KGE5TMUUZqM)O^3slDQ^34zL7_^!TJ^Y`+<t=xvTWJl?oG>1e zNLodz6T4v#buSNCv1NY@;nPp8zt#P6B*eB!hUY4@MbexZ33Rm=)T1gnf2+uSr8W?j z2y(qAbj()iwoG|R=#kIT9&klnc3#T7FPp9`as5&UR|nSsUSYDe(nBiNAp}&jnVsVe z|AA0^3st`Y4{f5vb_?a-+CxOxRJm+@+_`mx<XGNodQBys4XRk|aLLg3vgmLz)}8dY zn-WgqND_oy5->FQHY}3Jn)(GD3agkIxfmoMNtnG9P1y!*(~7EZNqg=}zohmg>LpIQ z=0BOEn<GfTb>qK;v0=5G{#HQmh&yOI%o9lbitwU{3>ioB)lK)Sko*`fk`TJf9_N=U z$ayh~8@Qoc`|pJKzIl)MPP+1R*M-WRe?r>{a8}ldXOMt=!?)Hwkj5Fr8?dnXps|G& zBRNVAcL8K9<XP+CUxq{^1zrh6&>V>qvv)sNWVqX)T}mm;0W9^e=tQmq<ek3t)DmwO zpP<*0rDb`){p59TJ|O_t!0c)4!*slQbX6AU{!@F39-Sf(kA269?q{2%nI-aad5C&- zPG+@mgdgG~9F#DM<r67a9)|jQ9R_R6EVa38$@Okbog@KaYi=5HX9RnnP0n71=d+a^ z9XJeuo6pc8<sZ)m?Vf@r9-AHdq&#cBmM64)Lr4fx)!kkDt&wSxdR3o@oqrze^u{XE z|2zWS_<BL7v02C?DLZ)G!y>ueh*&{@l|FDFR<)soEhv$`bI8^BBhN)-jO)Olt9OBo z>C{fIP|8JfY~?&#^$=$_#825^Vl@&ShT#GWQm!PEq@lY+;5$yPB+U5h-o)!{*wx75 z*J+tm2?k%H;ntc|<TXxEl~F#!IOC7X`-p#T3=3(aM7+86UadefC_|+%#RqiuLDUXo zb;Lk4(ZkxNJiUHQM;-rAwFt>Uge)=*zt?uXCOz-eakEkc&MUXW8Tz#mlgpXqKwF%@ zaMti1ZTZZ0U|xbEUq})|$BG8=c=J&QZSz+ty{gwcQ4*#0quM@qM6I)xN~n)ZtOkn- z7^9;FD=;e}ewmEkn^7{)!0Wx^svt0k@BJ~MzC4sZu_`6i!F8LQ+aEtX%|AtAc)6pC zjOmemUqKpclV6AmudL>3CSht6TpZwxYQ#Q_35N?uO!1n?&gryA2^Ris1@1&9%%P6a zCxlGLjsl*G_hh>pu56+Va+jLgHoJAaEL)v}#k^lSE<OxcHqu2vKxf~fE?qn^j(0zg zk)+0U=0e;d)xvS#HT306TY_a!;DUCNX^>G3a)S4CC|JZiOnTtBBs};|qrz!LV^UCS z_<|?^7U9ZcV6Bk*l-#E~$ddJ*qB-wF<#Bx8b>IzCVwuhPJHhqf=!u*UoE27<V|QGV zr0_L_FIH35M0A<6JeFLdO=QI^KUUqmWGh$Dvi)N+r_E^>CrHL^LjIB__S(f%<&p-y zQFt^A<osE0t+G#pbnD%;sv88jWMp2$S8Xri9!s?W42f?w&1WZowqaby$Fd0`?~oET z@4PnJSOy1Owdg7t4#_P${#)2WJ|_IC8qyabOlAg3gOE3KZJ{us9t3Cu4VLnIEiXvc zuzJ1TO=sjtudC5w#t`nweeHf5@iv@2ux%_k4;3N}z7I-zNL#t@DU4ANC(j)Bzmc#4 z<n%M(Z*GmXk!H`epdScLq_BfaVrJvR1lw>F>4<gJ$riSzX0#Mm^ZWp&`kqPYk`6uW zMSl-X@EeZn&%E~me9T%9E}73b%Z#P+Ref5fYY|Bp{v|k<-}Nh{nOfxY8f<Q`RZhd4 zB@Ne7uS^_`J~2cuN~Mu`Vy0rrSB|wKB!ZYL_;)!T;*~#sHZ7qFqWe&nC^j`7BXz!4 zvKmf4So0oU%W=$>$?lws1=~-(rI@&y#6z^gLOsc3Nnr&G{m}_=*Vd{VSEa*ayV$1k zSL95GhG;W(>=RJE()bF6BonFN&w7M)UvIqQbm6*(<(MY@82?!}k9Ep`;*(J$#|iN` zrNInjt1iQhL@0i4eF$@$f<>iyUw3P*G_y+`tbR*rs|mVzA9}NGz>jauho>T%uSMho zg88EK@KfK*H<ekVxzhf(sJRHs?XJxvR<DSsrzPi&cvJPg)M&x(H_e$%^VNWMzB@)P zwTtqdw1BsIHAQh+<$X;97OOD%U!q@lUaPB^UNVJBsoqA4uB~gV)sSiAx3AZ=K9uQ2 zGeN(omRH&S#HlwvvXDhgJZb0E&gG0~*$w_rm54sBjxXf4%`|+iGuE_>7MWfWto~&+ zl`N1-lJ<5^=ll~4I=%m*x?u8gFA*OsF|#eAsLurr^E*w9)I(5s)hA45FKk@-Q9<@# z(_jWjt8IPG<$ExCuHGlCTFjxfw1a|yQs&nD>(g*fnb%_lk4mPj$CSF?-*+WBPRV(u zw6K_i261Z~<Dt6C334qsAA7~dWccH^8h&nlF+dm8j;?rws#-DOdcnVy)*@UpwJXfx zn3d4wMUed3^Ock)qM1HZNuzs!UXZbxrp2R6Fl0*Ya!bdkj9$g3UCsvN8-Qk&TorZR z-NShpJTz&*JWT&ZiAAo##%`f56l0>qkW={`RH0Z1TF6uw#;a+#rPZ)$9z+V!<Y#uF zFQtDevxWGEFG%IE3k5A7=8Z8>oyL&|v-PsK4c~@6M8LY6K=eR3C-PFAc+j&aRBT<V zp0O3swrmu#-^vJ9JEMsRoaK1mZ?8u-JEFC&me}kXr<fZ>T~iSo=2(@mF|-cQh}pF@ znp&`*E^q1ULRvlE8XW7)C^d1ucmIUOU+Ml*k$cug2X>FhCAX6+|H^_EC4v@4o4K1D zt-LSnoJTf}y_>+d!*g0q*mF6tdJ8_`>^l}|*BOo>V-|O_3lNCk-Dn3)Wqro@M=OxB z=RiS6beVtpm&utVR$FB;nj*YpSizsYyiqxj`AcKaS`e16=s9rv4Lu2BE$|c8b~E>0 zQR`wYsH!iLhmb;fubXNBj_RPRk^xn+92Wg{?A=|i+FRz*vYFgSJS?VH7wSa<iZGxG zdxieE>>##f`B)9Y8SS0fNyIRdp!YCxIwh?LHLDn|PK;p(wPO^9`Aie)0;e;&q>-+3 z`LAt=6;b#pCppa<v=hs9Fa`z924v+eQynUOu?nnl=3kVGblB*5<OzdnX01NA^mwVq z&`Px9h?OARBRX^g;dRAZj&9AE9k`GH>nd$@ohKF<43M@<A1%L9fGx@iqosx4S5;m_ zL7)QjmjUYIr|SK8N(jR}9*hOXv@f7KPTJj`noJ}%d+Nd2GE2p5$c*Oa_jzA9E85#& zXSB6)`ctKUg)v(1XX?8Zqu7mF*hHU|*0?l{o}<EB62|9ccs%NE%!-Ex$S_wO=C!ra zsf<d#u^M;xc;cuI-AOz_Jb9cRvnmI{zuPmV-*qlK!T}V-okRG>*{JEdZ=}rsDI<kq zCY#IPOGpONL$9=de_oAI3x^BdGXQGQ)~LFSy4x!SP@$dFeVDP18t=@ok}HIHcDfL( z>&u(v#*Fn@HHpeAZ>qp5<!^5^J-)_t%<oH~gst|@8y}|tfuTOL;T~omV$!M<zwu4* z8Wp{rxsaqwEOr=W>HPqpg-(dQV9fi;oyu7H4O~g8yj6@!pn5KF99SGZM#S%!jWRti zQlm{u7+5)dT8WRDujxu3HurJ}Tm1C|xsu*Kx-z^=a&1(1a#c!6Okfvlao6vlom{5# zK$)mZe_>*!G#VDy-KGm;=BCrpYTDi!zdJ79G@h(YJCvu~8Ei6$T2ZBarx-p@ym<K< z!DGGV(rTE^2h-+XKw8(LlEROxvrNIig`gFWA8!saH{yUL+aKmZhVlJGhRj-xOIS~D zvX#R0C>}`$HP}NzB^PH~yg)2^(8h14RYx^2dEd=5T>u5{fG^~Qa{<{ERah6Nwo;0S zSx~X#d=~9|A-z>SC7iHr+KuB=8^W4~UN!XTgv1wT248U4<#px1oGMU(-p0&S6&Ur^ zCZ?h-kg>N$pX9wnGVCiKT&-zS3dHJh97%a~tFDrWZ-M6KpLERf`yxUIiY~(CR=>Pp zX@5;-9Om}nv=3f`KF$`Ey0=egkJ_wnBLC*<TwPc_xk9#$El~)U4ryK{Kw;*4=X>Oc zV6LCZdkG(?x~ySnj+vmN5cCqRqgP^O!(v=_>)~GNiI7pQ!5MAg0n!~w$v84iYv6o; zZ7*i+8qZ25$<EV{AVw;V=`uc&){&&>oG9eAhTLy=@T<ltJ3DH>Op#SdgPyD+$TfV> zy6fUVOO1}1jZ$oKi%WcrG#WZCekQW7-R_vUE51~Yq<g(1rGXiaafC#|(Z!41i1*8; zV5)X=TD$D4`S9YgDXE!NW;&~SOJWpy+|kr$OOLy&z4JUd&0Gun8Cetm!>}@I&+~1A zjG@!_om8;K3VlK3!CUVl<+hZAtG1G#u2ysjdYgqJ^YRzcWT|CavBIaHgV2LmngIay z->_X9go=GI0wQ{-#Mar-FQ@@40V&l6F_DnDogV_V*e&X4WbV^El$!)_@W4TA8T`tx z#2~x(!8inuv7g5i0|UE&=1T<!dfIKp8qR@z4pJ6&D81nfrsh(F508!!3T1Y0ERWx$ zU45C1sUSxa!H>rMk}ZIaYgR)LIM-b6B-UuunF;$6i`~v`J8s2t5+4BL|G_+kbhbyV zMnOGX0xM<i-Dpq5TVjQ|IP&2FZh9UWgeRl6c`-1x?3qa_IWjiX`Mse}ysE{^PgH5K zl`bweXBu;;%|>`3d^a*LyPavg&bxso32z_O<w&+Pc-773a3e41H<Vr%*d;%FO3-ox z+8otD`H)2)vS$su^t^A@wdCYEwo+cg-sqbrydS79Vb1T}(Gn2P_L#mqC(U66#f5xR zS_<#Q8p(dKwbq6U*?qH5AY&_{zJ}pS)G57H3NpuHSpw9M*`Jdf9Z+YsPqEP^KFjKz zY8w0`;hvW)WH5;I;Y}zgc050aAwE->zuNp!Tt)ToHYU6K&)~&istBxNJh$isM9x$n zv-~Y4d0C8$c(%;0WeN4Ie5C0n(E*W-+}xM2y##u1E}R$C{NgZc66PDG6rprhMh(&_ z#&<O66hRmCdi5p-$CjF`*1GHTVQwDUj};~u>^58)2KkVpbj2J%6+fu9q}EomzzPGa z?Xj?*-ESoAG|ysuv{po16U?Pil7c+ws|OO&wb9bEg4WUtILi#VN@JN<sw9Z^8o}Ro z%~Tk7K5N~4>-tQJcjRMh`RDOUDHTbDjRG2gdO_cr54*)nM0v_y)8O2pGt`{E{=gub zL`zh^6w0#Vn_Q_Cb4FGh|D@_@Yc<BH)`S8PUyts)!EDq~rfKy8)&D_&ix2ru_4jaT zmH6+%cSz@rUc@L$84MU-y_~k3|ArP=F~*4IdV{6qSyq*xd7U77OK<q#Y_Z4mdz9tc z2$pv>1jm4-OzhSIZ-EkHY{UDlZByd;#5=*WB4_y--Aoy&pwh)U{L+G($kTsG?TzeZ zfm}}~Aj~;JJd*PhdjMQXWro=8=QlajZ1@TpM}58el8A`}!Opzjj0eaS=>nbeY2>yB zEp_Rev+GgWX}&ITZ_T2H4F@<vmdx$4b`|=JHZThks^%~PYhZsWuE9O_>AfzmBKl1; z#vTnQ5}I`n`p)p3A!M=v0T|Qo+lkG;lKHrnU0g2+^5B{R=t(XJSuWqYSoL*$Y@oQe zBM@}YAJ!-dlsT;<WVu;RCfV%fcuXvJAT}!g;OYOqL5M%`G4;nhW+{uNcsw<{a(Tlx z(ddtx#B(G+h(kV`I;n5^&obXXS8mv+)R{=13<p+wFWhmRW2TK0Ume&Y(TPCMfP>0d z*gnz*`4il-k4OS9BcJygfvK$KTcN`~hUZkPuAZt@2NVyy%;{NI<u-3yo2TrLXj;O4 zDgKg7*yGgolD2ifhesu?QvC-|95Y;~nq;DA&2yBtWLCM&m5{2uQ6y)2k5kTn8=aqr zy6&Xh?QM3?Kt(Pb`A`R%3q;vUQcYZULy;f)Vy5|93;VnMg-k>31RWWAtGudf=U?4> zo`pcu&*qDn%)(E}Tlx%2qyxt5cBU-E;D=JqK|+2%A)4+O1sfy920KOPeio0RL6P~y z6VM%<CtbH2cMViEoc}gt2-^$gTlUC9xnF#4=+<(J?y1IIVY1#ACe<b`A#N?Z*G)+) zN3@Q0r`{zX_{xSrLyakx;B97sPrMH}DTKB+pZ&!r9C&(o+u1JGItUqU#=3NzcQ7+( zFBE`9tdmuAYwWeQH6FKp2J$k;c8CD~mtg)maX064jb;(kgb@`Du1Gxbt|MzDn7IJ8 zLq2vwN-vg>qeI8!Xx})DWP7GtY%+zHP9&{rY^1(mpVeS9E|F7Rckk&`26WV3`HufM z@}ho6PV|oc;Q^>cJ{@*Z`(A1PEt8w*bB_M*&S??9Pv+|a5SLoVwh;XZ>Ld4dww$N7 z_-h{%Djwc86L<4;kB`g_98sp_YMM@~1CzD_R%&FtfhHotZdm$00#gCrnJyy>)TH@| zTd*JH){!hvgV0*EHDV`5b&Unqf$ydht43`@J+N~^(ESf2?YU?tj>0H#nOO)2k`b!Y zP-UmIA%^ooWGL9?I-w_Kq>pyiazTN6fvD9MSx=J)`<sfjGDRQn!{pxAQCzgbsYx=8 zf@&SVbk>@+?rC)|Q4Pgrr34#EyOhj<>O8?J9j@v!si9g5C~CJ_3&ZLN&V^mHId2Gm z8jXWsi)Bxtj(4>VTt*B7%hp{-Seg59ZND<_U}{)oqQ|7j5LVA9Z}$LDs9!#_F#RcU zZ&)n=AHE2JPwU{qdA36IY8@@hFYl`M<yTvc=s`CEy9LBS=oo<&*L)TLjHM+WJ%rX2 z(DNk>b#|lp?9Ru}*dm)X_@{;NFT7iE7Ji+e*=5%VNivsn@t8ZcLe>{pda8COGpb^F zKliDw6$uMgT>{A&Q<}QylSv{9eJ(XuM1T!tvO2EPB9jD%9JRMNuG&|l7dWItU(Mhz zfjg6pByp=p3?2GsCg)s7l}24v`Q4{}yUr}*X_nnFmLuB~4xNRvwSwg?UXeDh=J`4_ zK&_hcgpLrszty+lkEjxdq%}fg-nyr!zA7WRm**lh!1TPDI9@;QqasqKZ)ww70Q#q8 ziYzQiLEo@{9v=OXA-;QSlV!T+6ZN>h_5*1@!@)cPyh{sl%;{Bbb!`2!^y7D~Zvq1> za)4wuCjI}u@IN4eyyOxWmuaJYXFAmtg-F3QBQ>VKVjQ+xKr}*N<D~_gxIsVEX_bBt zcXpc>Xw#3o#HnDWqh@_TwGVv&wD6>(F@v0@TC?_rLPZ^F9vdE<Wi5+GpgEe(A3}94 zdIvh%#-|6%`QCnW{SjiBpe47(@j|hVyp7ygk1nb^cg%*{{uxFn?C0>elq-X{(^#fH z9l;Z{w?9qIX6BcSYHm3C-EGg#cC2W8exr?k9~Lv-s4b7~p&d59ZI2X2Adu@L(f0)^ z3|3-;pt6TnOzB5$Z@+J4@}O>oNK#(1r$+C1R(s1Ef8!?oGuwNmS_fHwEh07_7vk=( zq3;HW1Y%fS+=Z9xl%~kw*%qg?>_R8lgig876bBVvMNBw{X=&eH>JT?Ybj&KaQHtNK zVd%Tf9v3d@%I&0$35}Zghs8F^y6`@Zk77OQ0X=63x{w~mIXvrvj`Ygb#nzBilkMF~ z_1ye6yPej#%E%lSJ(^)iGfndjQg|H-X+cNeuq6c;Pf2g?)3@6bZKb^N8JlA!HqdiR zzQyC#`*{*ofhg{ShJUTr|18?7D@6sC#I#u)$J%%EWODJyO7BqG)L_(Wcx7><&%rV{ zTD=w|{zJhe(MqXYm2R$QK>r4}nI4;t#xxEAIv-5rMKo?F8YN6>zsDW_7BV)PuGNji zx@L2K_wN(>Z+c%Fo<(R~Y>d-FQ_L(WhkMdYd*k;`E$bT!_q1vF)-;vlal#zUzr`4) zx-Rv)Q4?p?R0<|Wh{=NL6?<Jyk;Gz@1T&Syd--GphJ=0G7kdpoP@{dNb%gqodm8t? z3rhyE?;^5NM7&r4a}{zadz>r3kA!n1FDjNApqcm4;z099&RgBP@m%QF!>eh^D@8|9 z?Z@#0O?A^z`MNE0%*K-}BNYZ~yPL2`di0W|<uddhrEJbr=XJyCTn4n+<(P8sYqTUB zSXIiTH>jna-ng|+W}KbMe6nxq(8to-*Sg1cs0ry80ee=7ZwLlleP`VWQ#<+7;(_18 zHkw0&R>S;32hx!SHddGPkR=?ob!A9#hG@@X{Hee=a5GG!Lxo!S%4pPV-Lwjhf$hEj zY+{)1CH>ctT0#Wrei?=p#<7o68c2NZtI68z?A|+NHr*9xQV6h6XTF?@MHOi&OB}|^ z?;cDRQ@E^KN8HM}er|O8)-n3IEJ!CA$(^a!(BYUIPLFLKKxt?jz!8Vj$*^gYimHUK z%!DW#Fr_<HX;+q)n7)5zXlgmPA(;R5%ZOvg#z$_joW#fA{9BUiT38whm37*U;qTO$ z<`*z$`KH*Uwq0jRFT${b3cO=FI6BzFp@yu1V*G`RW^$s|7eB|0U&=hL?LBf*WI6r- zTILGMuNsCT`MX-P)_OZo^yKzcRRpN}*1m}?j1RBEMj%@h3FB?4@6O2bn81?-y#gIU zJ3Lecu<g$}>j#zpaK^bFA$GP&Mv~|VeLXoNJsIyDdK#<!t)N!t5^Wh+-%S=N=h2?F z!ikfKxCV}3>B{b3of|34n5E}<b2HY-)GiR(+SGnz<?3E#G#LZ5QRJrv)~Rq7Y?g1w z@sh<(f4;(u`Aa)C+XPzXQuX6M%^E$d3eT%Be6y`(YN#|v+$FiB5f%G9iL<Rbp(2?6 z<C#*EeSD_}nKEtpZ8^1noX1L0ltTLV(WPpARykx6PuKfziSz26OvaO4LUIBQlcMj} z<-aTNrT+E_W)*sjQT4XJ*7$>E{;HkRuPglZEj4#D&_3}*NS1cHuD+Y)4*lm2#{<WR zd~da5FrK0lXsL$SGARv-?ZG@+Y%h8{+f|mRNrY{1#eQvrZzoP@O*TWL<+MTy#T11Y z_5%tn?&rA>Lvy2#Io&Z0UQG9HKfIUVGEL{Q12CHE!6x}+6p3Vq!5E<(UY4<9kIS#O z{I`cvT7m{yoNfi)ugbG*5dQ=d;=~e541c}Y5xs8E?{kY<c{R2e<s^(_c0?%j8k0iM zx;GQr*K}Vr2<xw{SL4i_{Dp;0fyonO$Gz^L9*${Gr}cQ`T)i<G^C{KCYR~YnMbJD4 z6kjPUWRXQO%Td0A1>MX${M(B>+a+j7n=I^{(s8v7e-?kL(Ly-qoI^y^UGT#9tWf>l zSG`F4h-8iHchnIin%8HC=Vp|tB=~#L)-l|?x6Ej=cOG#Fsqss#m--)$*R13AMy%I> zOS^rKYzo7KHz^)O3zqDf8eqdu>6RI7ceqtIy!Z7_5wA=IupSTR=gM3@q*XZddh?m) zz?BCx^*S6mcVhYS-pPgAoGZxJ4Mt(O50a#qfAhb@YHdA5X&oc509DsXH4Fr^rjhTO z1=zeijtR3ke9z6hWpAk^RMjSpQt5+Po-cNuZU0|~n;sUOrOzVQ+A_Gph+t49xu189 zCr&NSyjP4w|AIM+s`ECu&t7ItrI;*LG~C3UAR5%9M6{5;IgmzDFy36@+d5Tgpy-wg zzmci+xUdQ1%P-&Qq?0A=Jo7EEWC74hN7mF0!-&QVYO||v2b0~tBLlH0XKK(PrNwOU z4%h0RUg#TiV866ZQ4l#7(E+x@>!Y`Vi80`Py>;4O%?=ajY&j|J*WlmLbD*#2Wcx)| zGMK&98~tY}B)qyD)^hA#JzSaN2VY61lFiRH>X7vACLEKd=)N^GaY=gJpL)lmAf)wa zjsF!J{Pi-+`idCK%v#OOe<}uxrI;2PJgXF_ER944Za}Q2Ejlin`>LEgJ6LtFOP(5o zY<Z32>slp6yKK*$IIcg#f@5=bIE{r5(s65^QJ+?-rE-P5@y|G&aKw!}9T)YVIKhW^ z@#9$Nq22=}l%Y=M)73c~&3neTjy@iaW<FQ*j083ps?bwii!c~gIp(6z38*Fuj4qCw ziv5`zJ#LEQt8YhZq-5A4ehL;)w2kA9?&8L268m^YdGvw}*0HGsU(iY<rswqiEiSs| z@qi$us+v}k^{|RQzI)oOQkwHgI@mg*_OQo-PT*EWFKZ`%8RZ|*5j|{q`m-_5CrNY^ zw_@MBNWmg9Lwd3N8pjym+#Lo!ACd~r@3E#YY2#Sn>??iP>0Yh>-rs2Y?U?25=S@;_ zqV?3(o~XE!db<fyx~X^(EHjrMYNQ*j{oG08-z?o-Nq&OklRN0Hz2#8dJ6&H7LpQfs zX+xA8$tRZ&46gShsm~#xNf>hpPl9f_<)yir(yXTWrY)@uoUl)}*U*O@E4IV}?)zH1 zw^`p)8q0pEGg|=md)_@!i1=LP>-*zzStG+9y2cz916<9yr7)V-N>)3rtaEr%q2U49 z)@;_WR`Yv@xU5`#MBG;);uLEC`{F2w$zMbM=6Ct1eX?V!?Vm}+;k@|r<S4=8U5(dZ zFDrtdZ=`dgyggvw1%6ieZI7cFXO}gVO&FnR@`{>51!T?M)V(6DPEArnpOAy3<wts5 z-|M!;X?nNun|2}-S`j2`<rEw*F4q^4jiW?~__@i>Z~NZvw|)yfmowRHwP^<|d#{yo z+c1Yaa>e01CvI?q9*K-L6|YEJgxEk^`U|yXd`l}16(ZOQI}~rM)JnedLoW4s92#YH z$oJ?qsM7{e4zWy<G#T!BC9BIFwSX3qNA(L_t`XL?0A6y6=v0VCtiEm-^~EO)J3%~O z*rwS__^<h&V?ED*?MnvJtAg+cpn>U5dB6<yy!67gsV~`t3Nyt_p@Th8TH4xQ$d{=6 zmTPS!m{deJ)>?sQk2aaw;LuJgGlT6_vnm2$2PV))Jy(LGX{ll}msr4%3nl3OzECE2 zO^gMxaMVTYpA_;!(z%R_IqFCvZj@32ST47b2V<d9_ojuVyQMcPAKufsm(sN>zb+lL zm5Z_-bMskP55YlD>afR&T$&(<v|i-1WsGErt;E6)iXAPgNNSUtXm0ViTDxDNnb|=* zUIh5RPgmaL+KZ{NGW5I1BU}0d>pmQG!h1^y{ju|320Xki2To_M_CRrA4`}kZUY;^b z9Y1DNH#M%6)l%uQYruScXl8Cg?EN|zixInrM6b!F1#2&+Y@`1^*-q6DX>v&QaZ?p+ z8~{I;Cy!$h<%7M<4Dz`0Oz=^py}9^AaGTX!Vl%LUrMK0g>|0%3H1ccZ&o9HLP{>Kq z$ibMs_L*sXsRyb=qWHmPfU4}-0=VHiIO%?E)B%FikC9pB-9Wt$r_x`TVeyK&Y-V9d zV?sj~*6!qo*Ho!sW;xQ$rh4!!3Sn8&e@;r$2<bTv;F6G8;E?DgKDwyqvN73rzbrNU zrP>^#?_LF3Qx_J)F&@aLZ*JHiIhp-Ah#fUPvgxNFig6SidzvX6Rw#vIC_%p0wP2q| z)s2sSh<<lv+hNOfqVPmLhh?yYS1WW2^yg}^Nub3oc8TfhpuVZl@T*MPvP2y<)OMRg zdNJ^sUZ(Lt|71SzSl06Ok#c?XtvK6#C~xMr@jBmp@P%i_oQ2;+j0SCtT@z)tL-yic z4_}MZ4gyBUh$pe<e=idd$pjwq--76JQp~EAl{V_K!mqTsJN|^LTA6FqO3y_v%{?a~ zA~(Er>)35DR2go+$EZk8**pt32lVCLzc{$&5wpa6fuDi-CgwIy8Qk7ot$Gp#PpTA5 zJ8HUwNmuylW?1>&^miS<)ZA=!<|Sm0LDf@HtV1Z){oTp=Q7^S&<;)gEO_vyb^uzZQ zL1YcN7Lq}C=|wEhi284$t)8C8VSXY184=ezQ#e{l@ZwA=L141NixrrJByDL+JG?Bq zV!hXUNa^M>rNV}(hi_<>YY!3S71%syHNE-`cfHA=s8{!L*TJoXM*_6xgddDBpU!j$ zPnxEHK$UB^$a0@u=xpQofnVudaNFg53pV(5R<Y1|FLmr-hy4JHwcz`&yr{iKub-A~ zmT}o+3jZsMq5{UGdBs&snzNeN|FOfYBh@jS&pp=vFnG}0_SkgsOu(4ed^9A)b3RSc z@;jHROZsl?+U6hno7Yg`ksZV&DvaM%7^H{7boauxi*p^E6(e8WPMj=HYSWkwd6mzx z{k{>LoJB4$iee`{85nDgYtM*SD>~@>LMLnY)xX1Q`Oo1D{7?AAL|~S%@LxOle{=N> z>1^1!4e8bi*8j-g|MJn=!~xi5GocX5e;V???712ui0&0lA1U1((6|2I|NHxmZS#on z<W0P0csc(uqQ4-5Remgbi7Wo`A2t8!82^g4r)7a*{iG;G{M&#0<12c@#gVFd!~OFA z)58AsjtX92SmkIsGXEKG{Ph>V3asK65tR$3qyO`H`~-#tw(Db*{6DAUM5z{d=#*<{ zP4ExL_V0l~qJd%ANNHmIXUg!`Uokkqvy8=gP;C0Yo`;bgFf4uIs)&Do+TTx7oWe03 zc$VJjyIS-A=ku_k0){pJ<$dt~Ii>$kEpd+(yy(Ar0X#=s|NnCT=PCGqf1*Li0T~$? zq))@khr^8ztxtbip-+GOpByAyj!#64ajaa^dY?|79#2#pR9sN`3JDs`|2iDD7{G?F z3$s)IhiRdb{xo)r?{J0>rT39tHH&>^89Y-T{p#fDe)LI+&9nbaLAB*5_z&Qy&Mx+{ z9`~TnVbUJY56|I?&vL>hcSkFaM|-U94TG+G`AI4#cjYHu!3~h_e;qM$wLsgcpuZ0R z{}f`B<Ssp+b`g7kUhMck?m&U~w{eeXroP7&!1nyT{?z&ZVK6qqv3MAxfEC*j7)=?; z5aL?`nmlKYqziC8tg}6uJS`pByQlf>CHYzZkGtIy0r0n7W769`ITeT7L<i4ymD6JQ znq;<T3%ZI64C0W1{<}%#-^V<W>PyD^7Az%^)?FF4RMOwcy{;08j(3_4mzq#C2anD@ z3Jg#AIubm5KDp5D%lov}+cfC4-^sNK2GBFSFm373LSFefASsBwO^)5`*aw>AwC-hI zH}71at(>AkQ4DW7SV2#1824?iQ>6x%fg~%WmH)ymYC{2|q!(0+__xVwtHtWGw}n;T zdssesFd)!=y8H3u)%bAaAm)4D>wkao2Uuii?Bi~%idMtG`vS82cCz&4E4!82>O>E) z+0%yDV;*qN@}H#>QQv*wcH_Xyq?U_(oR?Q+D|cmoRF1?RH^fvhyvBkGo`1_cobbC% z^7kZ&C&1eO%M}<MJi7+B&rJWwiDqeEVOh-iKVAEa`JNH@pIt;~HJdcHquH|yJbD9h zm9N*aOO}wx@08K>^7{3NJr}WSm%=~G*DbzsyzXXaa^k-G8d-u%z<)BA&q!9BoEC5T zRsEb-@_zx#$0q_@Om-~P>VFgFKkM%8;JvV*a&n<^@~)|JfqC_R6O}gXXAAsFQ2_7X zw!Ljn{L?9s@g&xI7|>}I8vAq;tLpH$?I7wqSm*O*<*V=V?@T_CiyVxjwfdD!TE3KL zELcUWX?|*%I_~Mx@M#K9_N?!hjwIWbDy)&1+?VROv<uT#q;}`O4&^K|;HvE5rYUv* zPL<?B#DfQbC%KZ^0thocdI4Q7gvPn=Z+gZ2yqfB~oAwr39~KIMD!e`Y8*0bpivqqQ zp;BD2ZpYDIbBH~QkLPSpRVT~2o<K>ND%lwp*?69OTzExVQ|;2<dm`p}PlVND|HC%e zQGQt(d!AgTAMlXs=`O9auB@TYXXbio%J6Z^@VGacD*Nr?MS|fiklAeE8*@JfPYOTn z|9ITLm@<5rf-W=<FI<o;>n*P1Kgc@=?|jcVT^O<)|LgR7PythI!HV=^{5#Olh-d@m z(&}c{aopF4^T*Bb+U-G`15PELTYcyv%2GJb-!E*Pb|o$PMcUHrvx!JIxT;E0{^567 zS}3%*hMs{Q-Bm+qc;Yp4p!?++)nS93dp1Q`<!)s*%0PlBBKVPJD05;!!xq^6ZN<;A zj)snHx9i`|UHlW~fbfCNXll#jL2C<2Vel}W$eseuLWVZ2P~pQCn*Y;pv8U>rd-Ot} zZ^7+DOj$*&*JNG+#$7hXep97rwM*K<VgZ?)Y;2q2>_Z3JeMdP-3U<-qSj@%0;B_PK z=glr+`~NWY-SJe%-~SaESxFgLN$ySd$R0@<8Mjg-JA}AKxYxzK%1p*hh;Uu|R`%Xx zU6~hG;o9@sd%Kt4_4$6kkI(Nf4}ZORz0T{L=Xsv-jClXwuku{H6s$7|*{kNo^^1!x zc_hf<sE6sQnt>^(A&LVu9IEd1K9-t+`h-Cf*C|AuHy8`8o8`s0k^i}^*_<7r&#Fa` z8TrE)=)|_z<aVH!Z`!fQ|D5aay>pYgF>%}Sza};M==b_km(}U^l8oA{4B*l|o4t=L z{!^DHKaPWrXKM8HR-{4<)y8K%RiQO_6o6vbltnj+@P7_)V~!623l4}JeqqF%ApgiD zeapztanS1<IsfC_rZ&%Ui4SAM{|A?N*e+3<-VApF?CYob6Y#13%Goy(gtq8@Q!eIA zjZE=1$GaIE^*<UXmyIiv)OI!1y?n=4Eal0oxKo!i*SwQT`Pz}59G1fmEQ?ptT9ciX zC){do6#VZ8r_Mj<zIyNN|96-&m#)jIuG+99BaSfvzT3PbP*?)=yT3fdLNjr%RA%MJ zrel>1#F9Q=F{4}TVG&XKe?gRX808sghk0ke`0r71YfVuMx-duLq(mawl2Wqp64;@{ z8$C)7(3RwsJG!rK$hU{k|AJ`&Pw88Fb~Ny8jr#xdr~E!Xzh||#H!}b0_zmeUHJ;Qq zDyvRiWLazvq>ufNLkArOgA^p8Bk;$!YV$KUJ9`R5ZD|#twjtqu2YHSE8@}?-p{DV) z*vx+sUy%WI>hU1PaPkN>ITE{BKisaeAQfAiPdg$IC3(|^ox(sA3&jzKN4u^5@729J zf9YKw!b2kTm%axV+3qKi=vETq54Kcu_Z`<B1D8+$WrgB)l6^@+T_nO|^c#vdrjH+{ z{6y_5VubSLA`9vP7NK~GuSZxY#-jQu>839p>fa94m#>><nuYg|3i2&QjLiC6ziQ}= zPDH@X9Y2jGVyc81M~i}>1I@8D2?vKre{c{oR!io{kSpqlznF_+KzyIk`18}p6n1}} zWfJ_-n^4hNc=)+6QH_jOuMY@vH<fNaW_=^0+b8U|;3}yHY!E$dn}Sf*c<j0ftIY|p zd@rB~vq3+8dw)IA?nB_?)XEr#r6#3^qTNCDUS}(fr@0L)RZLS6Zw1^RUe)2>0iErF z{(~hZHkLUi&d8Gilvm7mzh5+^4a?TNZ9GE9=c1*qL;r7<qKj~j548A)Dms6&vL>h> z`Q}#o<}Qs@d*WqMw<4EVDfPuUzlKpBPweV+lf+(EX_+mqh3|%yZH+eBMHCTH=@W68 zrs+-m$+I1kC5yUqgWdWDo_9ghT@AF{`(@%if9ssi&yhF`lvoU!D_Nv0Wm!3K;5=ka zNu(<WJnJ5<A0IV1554TC<6F0nWE7fKv;%gvF_iA44!k@ZFK_Ulsz-<xB6DP6N=&SI zd6GOnx##C`w#9!Yb!0(V$e%hvv61T1m|elS=(@k26bns3Q14b#Vy3!0e9t7n8y8uD zK>Cf@9w!wZB~6^=uqcofEl@#pjN9Ukh%wRb({nVj>(_YT7wb0Our}JT7DMlwTdi6J z+LnL*1!UWI9^3c*`iJTk?w|Oig!D?S0?^rA!9ZIa1)@ztE}oqKsF{p%^~zj&XHxq* zpkeqdFwEcAuvW$@Fye8xv&G752F{WTMeaYs9!_07KP9@&d&_MfKWHpEH|{&vTHDzl z{4%Lu&Jau`Zk}@mXRTCFR53`FvzsLCgO~v#X1pl+EpVYI#UA`_>cxnwPT7+O>=f+O z2oq3wd$sF9MSfjVa$v&7>H0?MDaH9TFccdvov$@9MDOaN%Mz`10!HgxM39dwDKA$1 z(SzEdjU4orq2nIh#Fey88Se$5_e{~{be;ks5j$e!lCh<Y0reA}7^$`TiIsXoRlbf) zQZ{Mif657JyXo+)SC%^?S>P*r(?aDP1)HU4^6HWm1qYlAYkm;2R-QoEa|JvHNN$l5 z0*(^MpU%*v4z&KpCi8~mIHjWUU2RTNZSF~s_OjN<s5T{3t=XCjr&v>aRjE^)q%0*Y zfs+0MFpQsle;G6-Vs+HH#B#RDf;op@co3--q;G7MFFUbh2u-4ZS3FXFe7~X+H9@%t zgw$~A)GGg{`-$HlyaxX#PA%08)w`laJv__qz8$5idU<GdQf{?!X-x)w)ZL5E<R>p8 z%G}jPM&u+qJpbbfRH=7WGmp*zfq2>J2%2mP{YU%k*sfW0H9mX1>p<ac{b8F#>VGgx z4N-MNv09xm!n~fdCF)gbDA8Pq3-%J*xU1JV$dRdj6sulMJh<DbI%Hz4_ew@WlDQbQ zdi;$7rp13x?@^c#DaBp~pC3q&PcvH%P;D!`enPks>Q_lY;d9!EtP|9Nl26L8F`<i9 zp*V2W|7udB1g^JjR%u~KrsdzoNCXEc8mR_!m%VtLf;&n%7c=?ZK<aAr&)9k|?>|ed z`j?$xN$6^MCZ|0r{ffS2j=bo(pCcUVrZ$b+`C~gaD~Dx;xH1~kth=4<yP+GlMH)*s z9wKcXI(T&jNAR8v+g2Uzq$IR*45<o3lj-}_cVyJ@NGYLH70a<MHJ(d5HSZPPne-07 zlxHzs7j!+Ird8YgNOp7@3s`MOxcDYe!qelk_eC!ZP4ebYYj%AteEUU9ET>Z}=gE)w zaZB)bqKg+lnmAo?ByOP<z{mH-6B*FlDmFbo!nu3y2`mCy4BUK;G`=M%j`vy1kjPp# zB1^zL_Z<iA>giJ>^*tks8abpA@%;C?`{HNM;^e72==GnY*>c7w)$jKxfM$mm8T2Ob z^jB5w5lU-JroHJTk!V2ll=r3len%gabxXOxOZfMP4#V_l9FV@xVEd~|wCv0E2pfCv zZu~P9<f{d)Z_#aP=lRm=-1vfA<w$9)fjJvB+Glf}uAg_qr#<rzHXZ+Gix~5CyA|x> zW=b|h>7@i~ubd;yobw{gdTohu+M3}GKSd~JBaRIqYugUzQ<KGp@GSX-HCpVAQvL(D ziE3G=8t0{-f}Pf_%Jyk4<W3%*k7Z(e@Dxe@l$m%zK;3}$4@`6~f;<!eZ%qEtP$TFh zC6Z`4vMkI<R}^g$&`%lfnoH8_c7?x}WU^e8Y?6|d0|PDOWO8sl=0LJPDOitx-c&&y zldU#yq-KBIjU#m<+U({~0oxMM4lp~U*DQcB*4;6kHC7=rxi*cxW$n*`k6*JD*Qzy# z{&`|kEg@c2bGZ>o`h!g2JKYSUv?fqm`{aZh2fMPe5s`?U?J<_MSWdu^o@#O<5SP3F z&q^lRuesru_`XeqU$?Wr^65hNv&S1p+1pnV0{8ukIgcW@^7=8iJ^4L!t4fA6FBDLo zT!0#UBmr(}@>v7MD)#B5?Vt6La^sG&Dzm-db*B_BK^%d>&%gH;Z)5*ApbgjhvJFjo zpQO*(g4^j^j=N5bye$z4?x}2O?!5B(n03x?0X}+3)E^wR^pyb4odZ%t++if{i~e`b z+ZW8#t1v0p5<SJcwbCb=x4e}h?&DUgS1y0FZr?vi-8f2JI?oQ36_#hh5Q|}kla#dZ z-y~Z_qdEO)neJMA$-|_1ehTom*rdPh6A3tMT_7sL^NCyV$l9O8Vy3JB8xcMAC7B%u zS5hm^=T@WybKe^<Q1WOhb(1{J6yU)>{&iw;K~W)Cdm}Z<YWiTFB7w3CLm$A%ol!V- z_!KQ-Dy91|S*^X7dG8$QgK&NmJ2~gMa;n;lpjyTXzv5jw&tu!8Ha9P2N2PWyklLJ0 z*_KSr&z<G{ob4LM+AQ@qF*WKns5l}U@DI)4bz>#L4@+sMyP&hOjTF@N3zbc@jHIzf zuNPS8mgAe3F^R>`-F`{C3GxG@-rjt(%F(bH5)1ls6~VXpfmT#0)ILf9Hhn<xr3KK= z#j9hh3#nc~8~s1z4?*N`bw8ezdLW}8BL?hSDe`{AK4I_WqTZ;-ij?^PV^k~7k8q@7 z?xS~1zoF{taz#jO!B#B?^p--6JM5vR`|h1s(^1dH6_%tu?RxW(UYDKY8K{~^G+V?< zw3$XA2zCGsIIv7;ms;-(`*W;l%+J+1zB>s)a4Nj+J}v{Dl!;i>55DCh9PEW*g_Qq7 zezc!Tuic;4ZZu3I)3>N1Mt`BF1(u4VXjgYt>4W6g5j({K2$#+?$9E9<9plQH8<=c> zY@hAdNvZLdxaP2gR(oao2Tob1F{hEw^d!zAMt-y82)<ol)h}Xy+Y07Y!TNqFDcM<z z)jQ8!e2+pbJ7qU89dc@R9#&?jVU)ys=`97<Km2G~q;fafQ#8<7va8nJW2YPLPlROX z+ipHeHg;ED`>|z+*RR~6M{m+Aqfe^QqetMNVZ)VOL)i^l8^eaV??)7Dw}Q&4v&IO! z3@Zkl`a_8vXAx3ov`sGK3Qa}%N$X`71BjJ~l}cZWcPO29h=h3ng-$4Luchn&tKZqh zs8fcXSGGOkrsu)3Fcx-#$#Uxcf@xwgDtki6(EZ($1PGyc6(w;xBeAY~CnZ4zXgEgj z$b9UpI>3F}r=QY~GV8=Rg^p3QV^q!Y?A1FBlrA4-13fQ{JoYECMc|9{$$4-`LHzwO z<0piV^(D5(@qeeE*ZbJE=<&KjJN;1LB#6XBx2v$j&)7fm_MXc8d(Zg)p76mxoK~$} z*o#Zp6EJ(T^yrI0z(hfZmrBDlcY{qok|u&x*}GUQ?m%*E?`SNNig3UQN#=?J$m|Pu z#)qS&J~bXhUL>_UY;-eNZU&+tZFU&?tux|g=$Z8gtyDH^p4mV_m0$*zCc#sfn~C$o zx5Sl(^%V$(0Ge>ah%JbZ73i}x-5+k{lcGz_996>2oRo(IqR!J?g400^$NYC`v#<%> zE6Ft>z+o<aLcyt_Sz`4EgCmxI96mf#_E|FDm=0q2v)YSjb>8JZGhB^!$vUH1*rgCT z9QgSJE4BWoj`96ak?+BZ&qS!W-{idf)gZ0;{qkCnacbT^O3`y+t}xn#F32F(Nz6&( z`FQ$V2he=A`}uZj52)&;cf{oR6W^b8F}8#UhK4rBx_*Toz2kk3n{>9^N%~1YV?iZz zCU;dITGhgP4CTzft1LbioY?Sd!;^jeYJ_u}Bqyx$%1JT*Nii8u1#y_=&<~zoP|LR+ zj<&-qi~)e~unh{UHCy{nS7dQOhqSpgt{cfuLDOiS$!j3ed6!o5=^^sWCnJ5Q7uw)? z#_VqVF%~kiB6xu^q|h)Ve-~bOz}>jTjY%Gx1E8#%@197XXg@&hS6@Zb_cQZ!L7{ow zr&phDaFT~bC`o0*$-BJWQ#rRCIkJq(vtg)xZu0Us!TjT09EIdSCp{>4Y$svIrG1W? zdU-S(^N}}tRaPjqKm=y1fI@lJH%?kD<?%o9jr6Nmv+;baoc{r6??dV4$wlTzM;mqO z=rxQB+p?Z+7OMR*+2)wHy3Wv_`~@$#gv**AQFuf9l2;lV9-wP<=(CeNS%(Y*f6U_V z;#*0U#QsUBn-d~e<+0uKaep6OVTWEQjmR;mUB5PgEz1s&x(Vai5kW3+M01=_$4DFa z1&`FwfMuu7w~9B4B$BF-Csl~J(RfLK0)Oyn4ar5O&R^1we~79q;-n13an2RK+n7BB zOCxnz3~*o@OhR(W4*p-<H~=3PW{|`t{D<ag#cZn*4Jyp=m`ZJmiuvy?Ir<5NW41>d zyF;Erdip>P-hlIH2-c~bpBK%6zpD3xSL#Ys2~^v<)dHh)xK%ITnfhkG`ET01!e}9> zv(U?XTW#-wCV=fYz0Hs-ItWZNK5TnvkK3sUT0j`gL_2jTH$76DAi^gc{=@9vH+vp+ zR)$f{=Z8^JT>th0(N^di;d1Hp{-2if_e@L)>F|yOf8Dd|hS3M1?bdI;4npXUAGI|{ zZrn_gOgG>Znp3*Ah)7Uq(o?gda2$J=MP17t9s_tazFFHpeB+)u+)Dl-HLik$@p~}H zjcwQ6Tjg{^5$6ITgCy1w+g=0uK60$pdAwXuT)0+W?by6H10saJVcM#`^L7|Wf<$52 zUN&m>M(rDt&9+^O28m6h&C~&VQd`8bSgdZjk=p>0sQL;pDeSq1EVA*>bYG|RU(R3R zhN*le;kw*U5!Z^DQ+@olW6@)U-j15f6O{F_vuaB_h@0CbPW}c;VvtHUP53lglD(9X z#e49t5ZPn2KXo0x;dkKi0F_mR{6I`x9}~^I&mt25sxHP8Vf&t{)RV!DWmHxdeJC95 zIFeX_+AnAgPg`ur_WRKvB02CCFukou!Tl#O`hlzElvHV=-4WyzMEz>$V>c$!Of4Rx zs<x=XvJC%9vYL=HR6EX8uh~gxdq%#_Cwjf=><I{azrZ7^fzH`Q7NARo#Ny@@Uv-aq zkw&_fMWG%8g`vHOwN@*8+|m_{;hn}41K{)kao(c7X8C0yp<Et`m<CR3CG*FYTzTsO zY+aUscWU##gaAkGOm=v>sO;#SE*#BE<SBkFKCqYYGac%6ZFw-<%I3<34UDcau=#!z zSJR87s*aFU-fjq&m4A{c1)Yh^<jenZ;_>w#=do1Yc?IG%kGi4<<3_9iY&*h<w<DP+ zA>3+pYKk*YP$vKRhQcz?_4^*H4p$k?=#~rB8{oBrV*hW?+(cT)Rh5}#2G0gFM4x{P zml=rQuaxUwv&S&<uDz)$Hxzu9K$sTUA9&Csb(*=RsJ`_YSe~g?{_!MmRuKFWff3dl zsisi&jd+M{trgq*lbHGnr3Spx-<KWhWfrxFtb91GFie+hr+n|9@pUNS_Mo9rbMaJ+ z)d{l;a;Txc7XM-g>Y_C<dc{w@U~iiLbXpl)j_~m3d~2|{4sQ`kFfW;{k{1-OA?-}? z)2MF<2F(0miB5DI2oCG(uAQx3yYu^Udj;D<*6^m&6Hi}mr`Y<(-^FGnUTp_u&xV65 z{W0*a()J;@^2@QOt8_mqX6aIoryLvI!2`p(xyg=)C>oiHQG0)pooeN}Dl*oMgpIBl zHPqOx;pIWz-uM|&jJ(}r@C}GKPuKTrvecH;3FP6&wUc(Qfhgln!&=Y1PLEa!>ufb1 zzt#$)D65W*F8g#3dl>jA)%@H@9qMWwzyDDvbunw*naFqye&66pQ6GJ*)Lizsb3(hy zxJ}`0I6qvM?I8zQ)5j)ah#dzZ^uFY8kL2|rVhXs22=bFBg<@YI0qZ1QlXy4y^W<TP z!zIQtb=!np3lHaq&QL8Y%cQ5HvvM}1z+(S73HW0I&m|bUc;n96O;ff%9J{K)hEVfa zPy^>uS`5^wOgU#9Wi}Sl<LTmha$gXATmkSBUrd)eF3b?_{-ie}JUUug9e#T44AXIE zvbaS#vO3$fRaLIBq7PsA^mnP)F;s=<b?x+)Tpq4spVkZ>CPe_5eYk(N3A=i%%^DU5 zpNV|9?MJDQj5ZBQ{cQCB38{NTO4!`JAzlak1dSh<tIxk+**DAvs3-z^mp~7dc5-YE zT21mc5!b*z6`A_=uI0SH;ob!u+R9i0Eh2Wag1h!^WwF0%dt}f>XrMd3Y-FPYzCyuO zy|JmgS!!GSvv*uq`}mY&$D1P(6bPS*#XVJiYrUDw*Lp~ZP1=AWs5RKWfdN9f76^aU zXz_%F$Gi6YldO{bK#75G1sZD5FanUCeNT?`_zM^<L2%-aw`z?Ks}QWhM+ZPt3CqqL zB&`1;zrGRy>R)^7mZ9X6)L^&VHDxgI8x(_clU*xiQf7fKYSy}k7aH7j3L(yYzvV2Q zv&v+hY`9ZInr(kHoc8v%?w`q??jw^0K)8hC!QZhF=UTD)d@fG%Sh@EGW^H1lY&>Ry zmO`IMSj55I31U65GYK`VSf~+oB|aLr@xw^!CzYV#GWB%RrK{<w4+Peq&08o<t2*VR zhHk{Vuo2V_gVd{rfKc1NBIG5f&X%05``Yg?uYJ+O(fNgU&^1>?VohRSK4gM6S{;U1 z4Le~jLkRNCC$;WB1wTdOMA*K=vI;!-&;i@PfRY2LWkhGR`p2<LA#Jit<-9*pkeM8$ z8SB&bJIzK$(fF1`V7ZY|#4XaE-r_HjHExWms*_LwEM9h0H=lu;!Dg&JG<FMn>3VF{ zvAfUDFl^0KxlWzx9j3bEu6YYi9HVcMTWvqwC3^Ip07m=u7Dv+RW)Q-$X4Khb2uFMH z<%(N6>p}f$Fvvg9<V1GDur_s|-C>7`;gG&E(sE{dhbQtcOT^{l&QgQLn=N9Qo?pkl z%@5^#Xye*@T|d_I$?Y`TkQ-V0r`RmTn;dC^6-%aC`vXCHIx)yO8&drPt~+{EB=b6Z z4rUs-)&d?vufCoZjn1Yc!trLSx&g6rYFu>{Px`@ThwDXUGz6sH2|J*1%V#Tv_TUvy zwMR;u_9UnUXte-S5Z(YE<nup!M+H;QP~yXk<Xb8tR&;XTZyU(ooB!VWEL0IN_v2YI z<F2ymqWs02A$#<vG}99A0rIPa%#P@22@#Nu<Gf33Tq@u=+P;S4tMC0c_txY##iBi~ z1muk8x>C8bNJJmz&n_SEZe?43&SaLGF5<6-1apXK{~UcVgrtk&jB?5t2`)kGChj}z zy*9`8+iBPL9iH>3h%>oY#k?$D#NqKf+Mzs`Z4VVM(b(eFv6azv{2F`WR<bW@)aPBn z6nzdoWzF`|%#L+y#prL_x;IIqbGGkdlM$_i6M+7qwM^$TRCw*I7g+n}SyINYULs&% zoSF&#)s_(Lmz%JDJE|(m>5lqXFg?NrX6!&{rPN~&#Ou@;4X`J5y%41QVTk3JVFt>- zl3uqF8t}N5h(SVHzdSqOMMcLrXib!9+H&IoL$RlK6Zu|FY$YJlWZqvn9gD!sK1dE! zw{4iRwC{d4ov<5?H+I++F0iS_rd!o58MxIrB0VR9!;*`2_%~`oPcQ|eWo*~T;;DYW zmfG7e8s(^}rFQ0e44>abSDNiuKW@O|Ye|PHo_lPHCgSv=5_qU|GTd9e5rths9NI<3 z9$%9s4_F>9)echCNSNElsM};Ytjb|Ot$6wsblqvF!eRjC=8~r#9G2=n>todjhaqpy zgW_^7C;Vc8_|44Gz`@J#WUuKIugLq+VK++;FVik5Ou%5u1CeeAPw<7C+%2$4q;5@f zPF`P!r<uws`qz7=R{z^7q5CyXPb8fBmESO@yLs>m&u8=RMp^8j#}|Pc&1p84Gk3SX z%OyB57+V;5blxYWdMQ`6G>^3bGY0L4@MV9C>#%j7h*h<@^2e&S7@StLZ6_yUoG4{+ z%pHka&|e5%CIjIEK<}@$@k2FEu1X{d%VXqWkZ0g>U-p12@kMAX<8s}X%}6Uqs=@0Q zcJYLItI3v8F;KXJwCi)%?cC-yz+vyvj|2JJ4`Nu;bMs5~o4~DVuNtLxxzSz#Fy<$; z7epy`PufX70`k^0eI2+1W$E(@*ga3O{Y;6>O!HU8x4G*EgQ}$zArh|@WEoQl?XIXQ zrEJThwtii?sOE^{Hr1e_-Qe&q`L2(BrukwuTw8?^tCUQ3W98CMjbCf~`(>NqP}nys zsMzMUnnQP5{H3T9bHFtKC{l7+-o|(oxLL!UdeIQLVwo3BHllE6#}+`3&2ZPl`_D4& zbW-cLZ#3MvI56&LL-_24-erv&ucVLaZ524{lRkPkbo-b(;;DF#^)N)R<_obl0q_#o z^m`~6m(_&QtO#M>vv1UD_+A!r&YJQ%%s-@Oxa<_Cl^q!fn+fNZ#{oyCjMPTJ^4XQV zoShh54|lzZYsRSq%mxKEh#Z4~-5Y=o$2;p4+x)5etp+M$ovgn>HBC@u)dAr2@>ScC zJopms=%j5Ui|AlPVzn#359ibPM?`)5KB&yedVNpx*vPxLYPwWv@dt}jOOdQxV#Lx= zb)oHZ^pag#Uifq<v+t}5cGxB5eh08DtMIDB9B{r{jC9q`V0(N8^V9%7rTxhj2tBrV zMNaZ72oGZBqwB_M*nV_4C5h^Dse=n%d2Opy7+gwkdyTCt;8nM5HMl8>88es+(}rq` zy?!<&$TS@pj}@8)*2SuE8`J*8IkE+gT@F=lQo{}hTh+0q#cK>)$L=U;HPAgE<S3&| zUBdEZH(BKEAO5ibe40+6=br%6y-F)quxUzL`vpDoJ~9JJjM62)mrF1TD>Ir03s{-) zj{Z(;@Ifpf7s3}b7Z{)UDu-GeD60Il>eS)CHZk}tLXO?ynybaJHhY7VPli5K8NYy+ zTQlp`c1i6Pbhzp<YL~dV>Ju{irFs+}{6V#HgRRoQ=eQzZh5E!JEjE=H+lkJMT)$X# zRvGQFs#EWh1UZTM^6${kYhLE`HD*Fxd)84154b{RlNy+nzlr|h?gfc=3UUW^vBu@} z*>0`E|GF^(*ERuB_A1J*s|6W#il=p==1}vkA*DLLO8SF{ilsv<qwf9{826(S*2zKJ zip-Yv-g{wyAL2gxoUe8~N!+*&D(=vPvP?Y^FY-xBaM1T!%XOJ*hYim6$&Xgc=uc)! z*$C+ftkh5|vi>%u#$4I-4wJ98Q5N2Oo9R(jra8|Rgy$rSv%M%jyrF}fGl(K@bC8CG z8QQV&v6;|<@Vn4c`XI=%-D=;6TTS~7asQc7DIM)eYs>`j%tsH=PLyj}S(kKU>*m9G ztYk_z5w;LuCza2z7b<zlhRgb9bIatY(@v1pbfRUatwjw+wXUSQ|ILBI4p+v@qbt$N zsUpk?6(Foa&5x*exdyTO(X$w-pN+Gx%HFMx^jP=<=4A;#k=UziI_i}4OAwM;j#5FY z-1MY)LKHsvY6CAy%gCZ5K1~X&jX1h5;7lYP?V#*tl-~b@*BEBOv8oWWA8SLBJRM$< za_gUbTrb&f=tVsSr~f)Qz^3H1mJ&4-psu_OZnaC65@`Zx+WP}g(fHoL#lk6U(Wp~l zud*d)l{7uxYJUr}Ud@-zymaQzT!_+HvUO&Qgb;F?49y&uVQ!eG#?Rwi2Ml4A_%O0g zr7y2Pt4>vXt6>_gKd(Uo$6DSRWIwanwt?sZL}Lx+?@pMDC$*1k_&K&i!c-3IdZMO! zS_2xrkV-tdCl3HoB3yPv*d0zNL@9N6Y`|U1w}I&=-h*Fby3H+1Sq(TYWj;3CmCB}$ z$eoyN;8%9)Ir`&A@|<i=6F{zaVk1e^+=#LM{^_@YpbODf0aag5n}j%#KJE;ug5R2} zFmI-$7u&M@xA~OUSrOiYG%bC6c+hZ#Z@uQTugc2ZM{)}H+#be%1kXj?&aN0po~z*{ za47I?U#3ZSF0pyeilFyZ((#U<PbJa&`_ao%d-z=A<J!`HIOgoTK_RbFH(*@9b$pc! zW1T{`k@~@2`;s!n^p=O#bcM%sY>Yk`YZKvKA@}JsAN-lS4bwH>3Q>lxn`6}ZdDtuy zgHh^X=)-ot7JA$F;7fy$Esi?xj5QWq@T(yInbKIq>bfE+$|-WX8tFf;Shd3+FcWH= zI^O@h(MIp+CCQedGFs~63yEz#vNlUV?sk>oP3;@(xF%_TT3ZGYc5}*O7Ua2uJedaZ zeqhzGB2QN6!b-}sJu+(7%2+h{8^N^I5*L=Zt!dn1#o<bs`p*r+bXV@q<`hKEOXr|{ zzxm1^&vS`mWynA2m+l3HBEA`3f;&XkZes6Oy*pd4b{oA5oPB!ymZ6BEhhU0ctZm^k zr>yO~-JIi3Jl%e9Aygw+=BQjpkYem`DYm@+BnI4AU{r1CjOmw?^LD?-{32?Wgo3vR z82|2CE6PC6u)pLt`mh3@X=OQHHumbwr&9ANMT?R!;sz|9i+tC6P_0|0eK(}Z8Lu@N zukOn?o1f96N`kQ$u1!f`nI5`~de3>^Vk5YaUeg&v*lD*a`T5uk{Q({il}}+DSeb+V zs1t<20A~x3*LBNnD9yJq8`WfB7HKuJpbD8W+P}ikDPi<&S{~w<SE8Ln&n7P&Qd3|B z22Qa1axawCBVEIh6Jz6kB<;qmdis;!fqAXOZWxkV`2j;RW8@9z?lj5B=*R{6ApCh3 zpP_`unM7;InXU|_Ie#7IkeS&(uW0j7eM9y4#nXqtXZ4gD{oZH&KDYU)e{-Z0kVjc| z_HEJUP!*11Jl(={b4!~G?W8qFUEoU+UW15Im(Q)BMkTiHq!ziTV{a8&-jk<#-CWvk zrJUM-xeD?EA|<Rk6b#t9dqet}fsa>y>$N`*k)t^Vgp9gZs$lIGkWGi*F$FJ;P$tR) z<x^39%iKaHxr|9luZANdq}kIQL$oS+lb02)B-i1;x_qeoEW%rr_{miAX(2xS^?gGX zl}~PAv5mdo(#IYV`RuO&03`Z<;mKYjV{sT%Se!O+@boa3pIv|sa{U@B#Gq>PZT5)a ziVkRu)%H?KM^;CKN(PnY(VJHLswFC{#c|)-MaYp}1N9b<8EFgUH^6{Y-Q+&KX3Uvn zHLX?Z0C*p+j2+o1{n-CI8REIm^jYbe`mDwT=$GmnCZu)q0tUfZsc)#C5$`;6r~6mk z7VxmSo|m}#dC@pzJnrO=x`y#tEN`+wb}^IEVTJSjBepuyt^|8`H?LN#O0+9*OVRTh zDOv@GHbQ?5J1jj~GNaREH(I@oRiCzHqv^>n)B8N!x@S9FGzjDdRybv4yU8yoh-rS3 zVJ^$PUEk<4!-gI{d7<(rLhh}~cQof`^<*>(1Y}$#g%gLo?(h1(>BdM|61MPXl`FEU z2D7EUj})zydq3Nmyuze%i4-^{?X=krOCqmjI2z^r{(Mb-HbjNXY%f4g;EmSJ&dCgs zHXT7LT|xg0dyl3nuKa^^`O1*;9gKmQD1h-7n`z1;8K>#d+hYneJxfs=;qBO3iO-Hf z+dnok$*>UxnStRIMbc7oUudJ0tQH|xzsMl5uATV|Mw$HdVuQZC>3I-iJc9)r;&`-E zN!Ic#^4rqKFu9HHS4tEKtEyqo(>jbkmPAxMHGLXSGY=!ROL`v9o^Z;ohj+bwbCAGv z%B%B*DfVzv<?M1%a75$gz0<_+QhDwWr;Mng@%F3pfr0DHEog<sBOzW~dKVvA6EwUv zQd^|oe2_pz3aR)pE$lk*XFdM&>Zcbz2G5(9sk!PRwT2xpmTy0Hys{=W7C#LWC0eH; zV4?U=<A*$TOvBOmW~D9dvDWGJu!5HcL5;eIWsjM*h72Yz8aaj=?4q2AqpXV;yMKp= z9gbu2Z>{`jF*z6>;I~Z5_&CA!D*$i}V#xFWFfGf`K2-{@%m?u;G+Q>eR^&#~n7?r( z_E0x{_S_Dm2zBb=TQC1J?lXA0mg6fgFb(p#o@&E(&6APvPJV*!Qt<075@WBDEmfn! zSmH2^Z{2shP5vbYZ93?SPF6nh7r_SrW2J-D45esZ0_$<>{pu~4;FiG;{X1ozYY3Hl zz=95TLVvKZ8XMwt1H2c|T->fS4;PJiI>k%{L2P-}8F2mLSW6ua472{`eo`D8orz!k zISClvR@@H%Rs<ZU7D-&-!u`avKexv8n(}nnnGMfDD^*e{p(JoNqBdkai~m%gy&MQ{ za*|xWs-aiEjn`f@v7K8gON<#RMzyKB7RMGI`W>tSBWIHdH`g+ABh}g!04cb!JK|<m zPpmU-CU)cu3R3TC+FsCjsVoh7r)~NwM#8pCZE*b!yXaRp6&ik9s#7t#sOd=IZT}O9 zP!~_E?%856kH$b?=D4&M>Pp#gL;=J`-k4J*I`rvxH5ujMU@*ha#YH2ro4=K2A1`n( zact(ed5tB;yhU^f3dH_)V}xmpJ_GEoL+W0n24nX4Q>jg7V@N$r)BiZ_o|)AQ*uBBE z_<{IR6r{0D#)_}w<WGg%x@Okf#kNK*2!^9EZk(%FqeTGYs08dLdX`-oF~MRBiNJyQ z24(ilP*1-NMAP$oMD$FSD&>kdk7nqR+Wmw7-Bb3^3UFO;He3jnXSg=TrdHw8sh!jz z(HI%E1@eKUw#&*N`QOrDr&3h1x!ki(t^A!~cJ+GdUsa~IN8-G5(wm-<nk~Iox?OKY zKA_>8z7KFxa<v;s3XPGy|ET>bUEsZhgT%h>6U6Eqj4`<^Fi18p^lgY?i0czt-^;)G z&ssIY%w~K+?JI_%O=hILqOHb~B<r{GhGgksPT4qReH(?Oy5zhS|I+s&`i?MTQ2wbI zs+_@L=%L_{spn3<BIM+U|0KM0WigRCiN<IxFeddPXsnA+EbNudrhW-UAyL+gryHkk zMXg>-%KLE!0jym~;_0LsTh)5K*OsgVIK7uCag{?nlC*%4c>&5lyvMe-{TZ<8O!Zww z!7|h0>Z9>4eXc5y-BmfC9r-OOQ;J5<!Dq^Vf27JQUD+Rif{xG3R+ei&YDQbd?A-zd zqIVZ)m;$$|0p^m6En!6k>H;o)Ch`wK3d7PKu_l)SL#SlQ3tI4yt&vg(j;#foZ}oZ% ze9MUl(b$SPv{+<A&m&z0C*j<<9vu^(pkD|fD$xL&*g`21B6TZU^)7I4^wv)v+d!iU zP*9Y^t0?uuR~Np5_WrUetZ64t6Dv(D_XG-V|F%RKSOr{9d^J+(<A0OdRN=KwU^#!C z{xTh3)2orWqr02R`Zo`ETV!I1Rk@nS_sG#6VtelxftEAcVW9|vM0>2c!P)%vC^gf` z^uhrgtBY8j{d&3RY0lWDM&EP9u@3yY&EJlj^UJmQ-`iQcd25l9oc^0%x8It@NwG&U z#5o193q(B*)+b*zkD7-3p|d5?#j;C{a{+WRf1>X%Tn&tJIDQKM74mNO>AD!f;|8tR zypYA(@NIDd$b}(&=CFfSFw%$A!@2;NcZuw!SE(C?4Oy+eZSARa!<83{?g>C<ei?O+ z-TsY;JUrq8_WX_FKK5DK(u0q&)Jt`9;#6AWMZ7h*9=me36#6m;kW|~{v|lvXvF=$+ z;D<upRPGoetB{RSs!f`L6|!;VIPg7ZZ_BgCS{({f+X8u$DdL2Y`{mZZTmjvmQ0|_B zDUt*D{lRCRmo_3#)o0cDaA@^2Kw1AME_6K8Yxg~weP>{#`*!ncn=Omihej$VG1sN5 zA8K<nZ|ZX6E%3Z+@AI3znX+X+mq%AR+uBv?L%f$|XDld<6l;XZAAZ`vn}pW@j@O1x zSF^vbs7~&v9t=MH_hDJK)osfA?=qMJll#~$Wbmc;<P3XdBH=))7Eos#gZcN}z<_S) z=3Id%YQ?L38GL)<zLpmE>s4=Aw-An_H?L`>%TEF<ocZKcDsIgGeEGYeDN3v8yrq?a zhcM^&F81@|R85xrO-(<u6-PyHCRcD<p*m4wdK*zpXsWv3S)g0ROI%61Y(_hLe?izJ zX*?;dugk(`_|61F(*CrZyWtwQyDFo)PbqnDRPJXA!DGa-@U`vQ`m)Gc4I=;JzQVG_ z$|rUYr)jXrTMIVSF5$vZxo|}|`7!|(ALT2YpOcc&KB)!k;1IMjNLxXt^fQm%$stnF zsNEQ(jDw%|9Qq=h-0ML2A7j*q1vZk0Jx9)g>sibLi;H;LO?s@Pb8PPEPB?8+SiA}M zD&}9z0f?)dxisM0$A1kKpU2cM3q;BN@dCGjxBEsh6+vfm^eahTqZtp{Psb<L#&akt zzsI~*uUWIlmGA{zF~+~;eD)wi#=W)wG-Y>9%VfHe)ttMNy$D&h1N?oVS0s*_DFThm zWFu};t-3Gc&5p_gImum|NI!OrT~0wvf97|fmKK`-E0)u0D%k9i3rpv73#ZtFXdz2S z)vSJVly)Z57jo?7<0?6um3du3v9pTfhC>onO|xFuHy`_Xt_4{GKSTbq$b^`}BhTa) zhTxL16F9=)&kCCN0njOQUu9j_AH@BR?ZZ!cBVHr#HXKHV(5w|;%uz0|XR78ltd`wx z=(Gzd7PXqm%`~`>n)G0FGz2F@F)o|9Sf$}$^l5l*rp}I})1nESaMxQ0K458+T65!g z<=;rF@;x(D^X#8W|D}ZZ2#9M#hJ@X2Izh-_Z2@F!j$2Mgbnyggy-Ct0YQZyqR?&x{ z{+*8~Stj)KJC5$tXUfG`IHDdyxoP+pkg`VuZ$;5%gv!gk1tV6CLP&$f6>_~?9O!_$ zax=cBkGj7=XrgMOp?YLR2b&4FesD^gv+xV+jG%YO!=#TVHZ_Vhh%Yc5_qVI<7uQE6 zmvX7^W`i-M&Uo-83;rO-Wv~h3G3RCZogm1~TxUNmBgG_nPLt#d!}x>n8c22~4nErK zKs0S=1vSKlpFXNHo7nyqdz4>XM*ryJ)Fm?&CwwByETrV!^WLt`=aYDL2ftS^hKjD{ zC)8jXgrxHou@m!ewH_@ATCKcC8?66Gc=SMOek1sy9~vYq0oYB5VGP(}U@!ZVjLap1 zKUN+Tno!iO{Q@X6Nm<CrD8ynfc<ECZjoLIwuvnT{&|uXsYrQgC&ww{P*n7X{s`j?v z7vc^&y@S$sD=xk7oD2S#iHkY}uBH^$B}a4wm{qNUqZl8`RQU>@HDo-TE%VJ`j2Gz{ zSj0y9yB|0++)`Z?8O6+X*Uz(k!>W?wjz<1iIR-BPR;lPqu5=z){A|MB@m`=|=aRI+ zhbNN0|6WS*QUgdS0UmUUrV$MFI9{|Fxd&eiij#EcO<B536Ip-dQ=?Xhs}VrDT=27M zgYGYSF@Zp-twEc^N1w1Z4}lVE>ko(q?UxS|U*yzn*kdk*S@B{vLRp!yfjlkg!gXcC z00cNYI}B6>s{ubQ$PFV-TwmHXl#aK3nW7jKF>RrpzO|G`Z*ddZ5&1Zxg7A;y^&tJ; z?>kXn*!->YnOE*I(XEMFh1rQRFi+Uh+PcElQ`bOb{KX$#q>NPc`6sW8CjAFKT*xW? z?4<4J7nbh%+4P$hiTPcZau5*wjMlDC&Q$Wk&XA>8+#ydSv-r`ln8D=VJqug!aR-J# zE}m_dH~)-N{nYkok6P)*tTRj9L~3{wiX;1;PI{jL+=GLy9WJ<P|4>>7JQTLFUuRRM zfiql5=RgcE(>BFCbrBE%*x-Tm&ex{!d}>{N#*-ZO5^hEMDRHI~KRW|#PV&M*I*F7$ zVU(?P4SzKlAZv>zPzE$T+r*pX)~i40ivWmY32+mzdbb+v;QMZf<(T^FKY)Ibbow>J z?`ZHOq~}u7Zq*9M9tz+{{W{3p$B=MR-e!bmD(ieTGF9z#(r}@1E*}21=Tp$Jb;@V% z<QUpLEz4?{9BWmU*oPkswdF$7qfh+K{6i4k7<T=V=;joFhViJh)=KSOrIRz(XQT6$ zxA45@bxzmYQIWjC&phw4X_B)P*_+}TPag%q7MON2{cq}}+BE%R`Gi^f&Vw^p{_z;W z<{V*3sZ|(6bCF*+_sqI2TO1vhkN2bk>ykEvBsyQIgLwu_JUCKq99;H#kxm%jW8g@4 z^#U5IYf<c@BN>8{72`~Ih#Y|CSUqMLpSmD1n;8PO&4C3e0mY%RJt5WHpuL~LQVhWh z{EMLhWi9HKJ!bIKUX|~<3O1acG@dS`G%%mup-!rA+6el{VYGU!%-?}G-<s2GA~GQu zwsUvZk&!PrIeAdVW6$}>pY3>I9h)$In1rV^oLX={Fr~YnYW7Em|K=%lmc>Hlt4Oy2 zK{&{gW+7-f?(#LVmNI=GMGv0(p+q9?h_IpxdwVjHB3Y>kvUtkBBZ^#RhQh8jtcC8& z<*os&nr`pttz+LZ(77AC{V}KK;9IEsg<f!4xPtZeyyR)mS?O0v=4xENbd%k-TYED> zi7(0LYN!-@b5Ct`OtpM~Y>&{UJztsyLkrFg{}!ZSJoCH#Y7jk>TJ9MDdIx@^ms-zO z=+nq}|J|1l_-o(xJ*8_%$PRQ;QCj7URhpc=O-=QP_QBM6Pq2iF(+i)c)A`Fzo22{! z(`n-vFY}vKSFGKierbred+v4{T;6hT0dOHfJ19E(CjY$<w}>PK$$RVBV2Aro^yv6L z`;aIaXa#)@vuXAV#rXcZ6i5qrR}**d<>4a-JOEbLALTlDImZ5I)GcW_>*BEdn&mJJ zWZp&o%Y!%9{-jB$Hwa_Y%9Uedc@;SwGMwJKHM?o|Ll5*hIelC%QF)OzzaG1$l|Fa< znpE-luyjTzO_7OaGSYwPaL}e%=wr{^tp!PYo|`L#<J-J)b@BP{Tf^R4tDI!J{<gHL z_*GYKN)8%l2uur~&|&F;!9OB(ksB93yIr%9e^D2_!Lo)6y!4Uq`;CdR_w7A^KarOy zmaS@3;0uW14!|E^cWkrt-Eql}X*fN7<9_<r&?a+rp443-YEyFjxD8mZ_K78%xc`QI zS7WgNLyDv6s$_@R+pp?~rd!j^0TbHFh)xOI%C^#g*<K{3uly^x?n^3tXh)$GwpMZ* z%-BKw7%g8B0lPVER)62MGr}TH#-X=6X#JQ^$u@0Mr3Pk*XqDnqq!)nO&fJS7ZQ*ua z8S4hTOv+sp_vBy7<Vaesw_rRaut$nrQWWxdZLs~WsW%H`@l~EpGlCoNk&$uN&2-hR z-9h4z*{QRP*J6#$g8Q;C$m2*R_qb*q)_fLtBRQr}WkoNUFQVfoFm^Mu*Wr*Zn0*LU zvYG#iVOXj|(+6n1R9UWWuZGD)N;P_4X?-K9@!AsZNzmo-N^E6-dn!4x`FJktR0V^M z56enjrZvr;kb>D9WNnoo8BsT|0zT^1@Qv{?RqtnYSuzB{`Yl+N!GnJZ8DQ49r<`nj zJ8G4)g}hBKlfTG6On7{pWy?wnPV8({oB=Q%AMP92QKEj{=0ND48GAc@{&c*{L*tv5 z+wJYG8{BNDdbVWKy}lL>&v2u=dt7MJ3c+Qwga}yCW3VTU$98FP>_+>&p+0WBWJPRs zxBcHq$ZjfB!f)^88D5P%IIl9Rw_Pp@Qk}6my%|)SL}Ps5cEi(#7+C9OSE2O}rzt;O zjJAiaj~*=>+Z-S5C~nC)?kiLG*2`<`2g(eCrT^i`%IfPpKHOzBXDQgjiF<nLP=o3S zhEuS&vqy!>v?EIo7ox6OP{69!qn7(aLdCVe@r0^?-*+0*i}}q`q$UodK^uxY8)_QK zpCFaNdWl*0F*l%)&Cr+5k(omT9C%>l#$?sT^u%rbv8~;PNp!9ItXpI|uSMfOI*H$o z>fJP9Q-ew<OXKC&W}-_6(yxhqy4h+)@g664eG8H6u9E3(xYC-j;7@Ht>8f0OvMj~O zjEJ5%TBO0B2`AnMjbSw%vX#0bM;~7*r;cxY>`W$6D|;_1=yQwKJQshW`JAIU3>rEP zxMV@EZ8lQZ`!41B|Lp=uW7-Ba5TYNLe3<IBHM?UP%!Vb8R}8Ea*H%W?wriUCLkq|D zGLEiUjwOE?*eKi8aXZA*K4TsT?q0v<Qa{I~igS6QLa@UOnYkY8Kp}fTf+qK;+GdU; zJ^!+-4e@X8h+`&?YMJ$uj7$kHwBlO0RkP1TVL!44|7~~I??h^wGbq661on0T_9U@i zf&_3y`uu6kqEKUOm2wxCeVPlz?wL>VH#Fm2U49rj{?6kK8Wmf7-e@iVrbO1-^SZGD z7XAmYDH^xp)eb+6a=M%V*BZb7s_2GeYwsa5dTP#;TP+`Oc;6-i*@Ttxyg_Iww}G(~ z2ut{03Qosai|*{!6D-**A%r{7eoO4OTF<MH1M3(l=QD)e`a`FwG4<)_=5G~fxmCX0 z+D{YlxK{}+5yekbT>~|sH(RRYS6xLzg2t9qd^ET{d$=;p@4@ab<fs*m!?lNaG!rWh zAx-l5t(N+=f8J_QQ2oWd1fc-Zj&p4vDxplb6T9hiN;)bKt^r?PGw;XR%?b)mBsMA@ zW%al|^e80m>X)G!A1f!ee{T$vuQ+Wc_12+#k!4f}tlP10Wb!fF&HeAKX#Dt!MP2`# zs?)$<0f~Wkz*zA=NJ&BQaBg2gklo$R!cEovi}VqO&GG^jIL*id@Kz0ue@3Ftec@u9 zbOzC3B11ext2vw)W@4|e*Z3Z|V&9NZH(+b6A7fHtJ}P^~&#YLN;CGYjjiiWRS^9Xf z@N)qlX@Eu?t)06r?L8O$2TliUN@*9;bj8+PlKAdFO{*OLc{wq?xSJhB<<)ey-6dhw z%7y=zuESyxU$aKq_qxAXHEZ!P@plNuekp$?)R^(3(Xo?)TL14m^-`;cDTnl3`%BmB zxcgrGJB&J7k3KnM3j^qMUcGA}DV53Yk3xq8lkUoIIxCx!F>L!|5Y-c*otLoDsFy0A zG5&Wie|4Lur$yaSk8+e1Z%&S5&?Y1F2ek3HER8U&-}*}Qey@~wv%*1Os@~=1qaET& zaL}()$djoeU0#@fY+*(6FmOXSXzt+8cbH}%jYxzfb;~C838@*ak%#IWcB=ix&^X8t z!A<xU9`pXTLPe%-gp!tq8I7uUuQgx#-?>-;9`pAdLKc2MWQDs23ZzH$End<(wit4= z%lrE<H;$>ye*YRKLYTY26rsevxod@>NvNp3w|rU4e3-LuPyJYc&2n8|xufLi3(ERe zQ5pb(eiqh<9k#wz`rrro=d5jmmQrmst;BRZFo<8lx$wH4k1<ET>Em2&l{qU%J@v#z zr0Dw}5{ToPU|USeL9Fa!X)f;Pjr(kFjDq!2aGW1m-^bwna94ANdJS@^O~R*}%)Aqw z<JB%p2oJPG2eNe=ya$y&Yj;u{LX_W#eQ`;@`%`_<nwoo|^YvR>42H8ZLOy_=>s67Q zp$kssu?d@K-=S!m1I0AN+v|(h)_=H=LbM}lshvHM#r#w14avyYA5{GIR|5@f=Av%p z@bqxKi4<a2Zx4C#@T=61wMF17G;&1c){iR;+zfg8?k!=ELKg0ovEdDII%bw|oNKKs zJaV_*XKx5}vb)obO0(-X_O+d${Tk6ehx!s4x|J~YMV3ucfe0_#lHh$((|4<|8!t4x zqQ2><61;*q<i?MzD5{k9eB8=F#lFnCU&yd1*2Pg-Wp-Gk7!2K+q>I_orUK924oTex z^gsq|KWfa-IWq>8E0()23^|5CZ4&Etj4<<U{(;*iS-i>b#j9?fiOJ4rlMc`L+j__w zdS7^D`lILe;vttFO6Od1{PaLFylk64Xp0n_;Pepl@PQzrne9`)PDU&$vd`2$)2Wa4 zrj00|F5Qi2B%m96Z}<A`T5uH9CIcKL(eP2Yz$aOD(P`61XSO@~(?h<V#0uh3ZINts z#{5w9ka%;XjdoJ4D$?l=Vs(6GtzDuF@3_-|uCh(sw2c=(k~`YA$WQDuMi_sfn+M<_ zh1wcY)2(dAw0`K5F$|QHX|>4rkJ-S<6s0;!BRa2Ll%AdZ8~$2<yV)4MCh4G|b-Fzp zz@v3$*C%_(riMc)4_&T^*%*90DP9LRQ^3c}Dr>2~dH#D6Q?UDZIgDPW5;Eqb!Ilrf z<zTek|8itJ{_S<I>4SaqPqdSEz4+qB=3LpQmnX%DP$a7+t~rs@bWX5JxBXH3gF;XY zLRl?tG2){%44IZie&wT|Izj^oQdKhki`Tv_w_SXzp*^T3oj-wnbO}Z7YtlQkc+1vc zFegT58k~k2RJdeC<=<&+j!TxFzFe<TTIk4d1*-zvRi0!A%%IDN8y@^%o03sFnM<Qe z0Q>N0VqIYdt4pxp>LPH&k89U<0q2+f-DhQ3R}faxRT$m;DIbOOM(`4VLN4qv(%J&S zfJwkyYJ7s+PnH3PqutcYvQ?Wb`>=n8qP|O&k&2A!jd+)@xIx+@fh<MXyzHY|;!tVA zF?<l#hAi9Ce)?Qp>;>U^QP8_QuCAuiB5K{)Cx;7I5SN)9^!4mzFz{R2yMia~QLMc@ zuaYHc?nHTlSMfMy`oZXE2-DdN9ZsjKkhgxVSr5_^2xcjplh_(T5GhL%sXv_JNEWrS z{Gdsk#i^+46N#;aFO~}Q4kUJy)NkNNqL*-d%?Vr5wSm;)wokDJHlmT&rU?Br4V%0Z z`z@2A9jaFG^al8*);EWVhMj(Q;`}KylY3D1yL}I380u^lY{V9{Q%erPnUb>DA_7v8 zIWHbnBb^k3R56?5m|$UHkLNmdFZ;q`vNPu5vmJ{AC#r7zsR-tP!c{7x%O^Fxk4{6~ zs(!DmHpmP|H6aX-OCX5RYA1(ua+QpjAepD8l)OGz-Z{SE=fM&EmCE7xyPV=8l>Vek zJizB&t_L~#6<f}UB6%$80Y~Hd^uVp<5tQzd^x?ZSiQYWrLOv)W9nU*N(o6N^`+s%) zbx_>P^9BkB3GVI^f(D1+ut>1rfuO;H2X__?9&CZ&4p}4#Zj0OEuEA|_ch|c)=X`(l zR=xL9`v<i$(%sL~{h8_Mq2jXtu)x&=-Up@M*DIgpR48J^#N)!C2~oF4?vd-Sd@}gC zDzYchTRuYgyU2ITF`5R%Z#Uc69zWiGl67^HU&+F~E;r~rtgnBb(H4gjV)|ZC6LBeF zj(+E%C$a%}KQbtvR*X;r=n$;jCU}_ryOH!cK0H{W7_5A>wU(#y-dk^r=9+0zlqKgr z29?hfnRVJJe6S^dN{N3%mL`@#ZQ|q6QEwyVVc9E{U7{{^ldq#EvV*lg`Bn?m_yeg> zK?)+HJg{1xR-Our_w(yaZ&KM;Yb=A)@oF`%KIBT8hTYQ<4ZrPxTqhi56$U6~1t&GJ z>eMvx9i1wqpa(o!+)M^EsJX*ariYev{Ju6--Bm&)XYUg?@Wlbg4@-K^*Aq>m8W+e4 zgQMc`6!(l5*P<Vf4tpGl0Z6uvXR|0hAk@qq6{neB*xrr=AS9Xuxr)FDpQbfrQlY`% zd)2+H)^;Ij=bZZ>?i7%y{sOlbX7<i{g9_(;OR)g?&UJvzVKgkKxf`^?Ye25P_9|QS z{O-~{#x0S)n>zcnd1xo<LTOLh;Kk1T+okbBF(-$U1lsgyuOowod+N^7*cB%1^a)2y zkRfT%129EUtiH2#fqFybtO{FyUSf%SKt>{6ePaK+*g%u$T;fE%S(%z`!kWKY@(&SR z)brIufhnd#!)>%s$GxNq)?WLKbr$Q9bF^y6i>dwc+eG2r!u^%T+aN$@8q-%5mA<3* zj~8l3H4rr%4t^3$hLWb!BZ)>=vI6zR&GN&N%hTxxc|UoE$kp#UkFf&f*mZ=mhHZfo zD?(dOR)p;LOX~cDsL6Y1G2L5B@UzX1z6CTu8f;JJM;3#86Ff(Igoe?VENZ;ClL3R( zO*wbYw-mdv{O4lHT#Y?ieps7w<NyLD=PiK%6ej!as{MqqmD{DCyKf|mvb^g}hI*L; zEI+n3Z6iFL$k1XMlH757e_D)vTc=>Cm@VhKCfKN$o%s%AQ`GG(&dX%!&_T=LYJN_A zPO#4O(&=cLlIu1W*kxdFvbX;8l)^FPlZzrQvpv9B+TbxSX3ozz^)#gjf;V&QRTm0h zbh$&-fhB}*R1+?&u4D(<5zz2uV|9;i<mC3LKRSGfAHqxs1Ak7VOIzeYUWQbS<vg;| zNf*{H8V)VTc2M%64mLrP3nS{F9z09=1jZ2wz7_6N?XeNY%bwM}73<YP_SdzzOgC|1 zis1g&gst0To})0wiy|24w_Q)Zp==C#3w$XsTt}c&HSLhtlPjR+Bun+x#SDz+)}vu@ zV??x($Z-5~G2b*9_K80-DIsE(AjdBa?rOH-jf@i|%&NQ3l8cEQTu7QWp|Kmbn!8jl zsl_rBK2W@KCT1k)SDT<cC#wTjB?#ojz7h<2d6;sCKqwLf9{EH`6xQeyDP(PuB6yj& z()<()RBq^2O&7U_6weWJFt(wui^FCY|9spfC|uxFx>gh0Wfb$D@LyxfM2K9S_5k?k zCXm&no@AUz2%4OL72_J3Iew?1_1?S=4O9hKw8zj527qMOx>PBEg5RM0n5uh<2DeA{ zyuOSF*33BrjJp|`g-g12-%+K-V2n|c*6P1a7j51QJWf(C=GPi{Ll0&`1Yrrr7PG3~ zE~E@a>`B|WT0vfnb_XAK^ERvP?28&wYSB~CyG596)a|SS9R-7pZBS_4BdWL^29>R= z$<6YsxY0+<E%ll^>tCMdE5?I)r&q#h{hAezSk!5mhQT2CVKfA$%xDo6a%@j~4a)Dv zm@Y)d`U;a0mlhq27Q)j_8!~N0*l8)7=kHEMOCi3U^8V<KTgV|lA@@`JpZ9v4H@P-n z`Hd!~5`0*|UzX^t<;G`JpO0^@S?XN&%s8KT$CV8cy1LIxdE&Mg)WxG4e#zm0g2bQv zC#vQVQoXQ%`_fFH=)0V?XE<>Hk(wgB1`rB2YEp8&{|)q+jYd1}5Z28@1B;C_Z<SJi z-@4_T(%=d<?~_LL4&i^K8oF&c7j1JjuK6=__X@EyOYtdX{1Cx1peZx~(v57dF6646 z@dnv<*GY*SX!*T$dkmza$}90@;SLZ~@?;vVwBPcQ$So<bHNC22Or_B->Vn9K!t>Nz z^TRU%VI$B=lkShI^rbf?Fk%(M?D%j)cl0=B9vXNtexf8Hub<(ytQlvRq`+&%D|cTp z5Um(ot~i87Mgg^|&0(|7auKawdHa&t&cmFznOd%9t&Wlwn$Lr|E&ia#!+WzUru=o@ zdE^Ng5n`&ub-XqhezPckj_EfF#&<XpxW3N*NQ6WZnC<~RJty4>*{-aR0r)Epu1<lN zFN8z@UOcDAT=x%3Pu<ix*W`XPCJZYbe8Bm)YpdiGA)fU%P88vaL>yHfLnZ2WK&HOE z{MiX2k0kWNn>sVREK6;%b)&0i`dn%<tf}>ciaT+xlu8Fyp9hN71?Q>O4D#X5U)xN* zA+NHYj4)}=YkEBO<80)LS{&;}r(YX7A2#C|9rWpz8ujLynZ~XDcBIeD7}K+%xsM&Y zAV&+%iJ%Sa{zZn!gv8ersNH@!&NSemHHpg!CT+B9ejRNE<;Cv9dO+VjvyL;E1{7cy z9$=L)72X|UwXW$sR4<s!1a0ZtFxd+nW_ola)f&!?875m=ImEQZCtCp?@rM4e1`E<p zK^1PKjpidLqqq9cNJl<bpyzo;VWre{hdrj}BcQsEciEKtbJfpoy0UeEqGgv`qWL#; z9(h2_vEUZcn8zDbQqw;S%=T!dPO-F^HNuFiHvD_uO!X&V*2Ic04?MzuxU9>W&MU5L zN|dQW)gFzLuW!;EJCuConkT<}7=_<FlSNXA{;Yh~6Y$YT6x3YYc4zxo;jwhY;Q>R8 zg-r^X!=Ndm-$xTo&uXLL4+p-aUgd-q=(vK-x~ugU6H1~nk53(jw2orVRlVrnm+mqi zCsc%_<6}7Cds?|m@B?k9M*`8S>29Wp-uRyD2x71iG(z@JV$$O~!*vfR{7jT}z_O;Q z^Fk~K4cP9`gx4bky=o%+yfa{9RJ4<$=Hjr&#r0#9AUww-V6DFih+xXs(=1$6PXNkk z%w5*C?ujj@UL9^uH-<7j!#b$c({>U<gJXDQ7)+ya<LmO1#6p<rV$za#<_me2*DID{ zUDHIZ+E`b}9>uq}IluAE`qy}%i>3?E?~^8se_{LK)2z*67FRH;2+u!au5dk7tX7F8 zNf+syQ~->YN|Nk$ao{Wy3Obx$*T)Ljw;Zxa_4fNA=(puFI2d5<ctBmvW?>d?>)SX< zzO{0du4PN1-vDjy@Z7<3fzj(m{%u%7kJJrO5jNuEh}zk~k)kydhghs{UC(sO7K}i` z<6!}L7jbCa_$m|)c{@09Gc-})Ijm?3!E?9<=qWo}8hqq#xnWG5m&)#`Jw2RoV&9v; z(&-`ZT7I*a&V46xZJ6<*Vb#-+f6>nswP#7hbBm>%GR6&x8%lG8xoZH%WAoo@5mitT zI;crkZ>wj>;AU7l1u8R`vic=}a<1l4PI(3<wrj-s7ZF^K6J6NkfV*6sfP&Y96ZVA3 z*-THJN_)_WcNt(OpHRicu_2!fv@6lIJCjHJ(APs`oSRufg9jm=@{rOB&!PFE?c|qB zllEE7XqcX!%}dqGqttp>tAb+Neri29c<?I6)2gPWt-TJ2HwY{_nJhKCZ(MI9))JkV zSBeJ`nv5$HGsi)+27nZ22Q1h0?BLJ`?#f=Vq0VUk-rED5&juHJ^IHpRN;9@WIhE1# zI0kLF#VZ-x_D|W(`8Yd-tgc^zPBOYwW@kJ4#0>`GE)e#~E`QqdUbaHezxq8jsy;l1 zbgx^a7)~#U_z|yD&++)5@vf0Q*K2tE@c{YI7UdK^^wpdDPHZ*bQ%FLKvb=B~$1X<v z_|LD$)w}?a_O-6N<4Xi0l`_HN5@6!G*`vORVtU*jG1v7jsnIMg*Qn^W>;zRWOb&r= z(=?sB&=^eX2vRXQqxxdoi-24;NZ!2yO#!CnV~zK#R=4R=E0{arD$vthae^bz->!Rv zj&%VCT>YetbvqnG{dNK{DRRVFy6u&E<Dr`Q2l8Qx?b9=e9X+5fDK4MThW1e5;h|(r zbb9>jr^SBRSmQM>P{z&BqJ4ha_A_Qf+jHUTLRwprnWJAH&EJ$_Elay93pzlfA6y(` zd@Cs?P|p496v-^3XQ;1Et*izH#HjQc53i(lO5S5Q?sYRB9{72*YKIzbm8tesiw50P zec@OcjIMd;;T^sg6Z5>7Rn8Vny9TBgJsSFj+V34ILcf$Wm98JGs8+Mt3PK+N?&_%} zRBKBu#7$sr!9$ud+tu9TsyA_WNI4(n45w*lAFI4aN}}@a_KdQ!RBtPhY#81D;15y- z+6TV}AlfqXTz?sJNf}@(zt;un3-cx$mes_6yo~@Xpi}pz9`O5w*D=i4=YFc`w{ZKw zRAy8^YIQmLzM7CEy6FQbqN87fM^w8*U*tqJ=O<N(WUSes*zn1a_-N&}DIwDl>zm?- zGU&H$wqORm_1~WJy$XWPGH)Q<ppG}Brc~lJGL0bgun7x~;$WDHkZ6a;M=H&tCR6HQ zM|c!Fo%a@3bONHeiL9gPQN!Z7xzGQ7>DE3Uux&+oT!#8f@Q&edT=9*4Xj%%b*h78M z!_|N%H1xU!%Dkvpn~)=n1Jik$z*+MkuzUO=oLni_1^^6)I0CC=96`P|3-rX6R7KjG zGX9tQ9=?Z*;A#Wm&Xc4=oHt7tWhlaOjRrTs#ye}jX7I7<Y5j-5Q5CXgKChY#`DYNY zicquouCNO|3@A84!F+a96ThUa6Z6T@jas&WyGMfAn+zr|*0bGU99z+wlciat-HE!G zQ86?5&0yjWM5h4%I{J@CcRvAn@ua}e`lh_0*?|xx<@O^wfd8ggX03DXW;CSkLU5__ zv0*Q_IVnnrTPtTZQqa}SEwr*)=_wN5pPcp-@YBykibRGYHZ1qE8AzIV;RY*!*rWtG z5t@2}u4Llgldg!MF%PQ`GK)es++L$DpHu4zeDjpXXGIdJO9X0yNXiDE>`=A!69>!7 zZA-E60`ZJnd&1JhLPlwJu>%GdlW#>m3Srz6@y}$<yBjP#<5EIvbi?r;*=9`!%pfs! zL{t2ZbN`C>jg=}l=ke|ro3wJ-xV9TI!mF5t_C=-^;Wca=r*BEb;I&)04m$V+VmO(a ztAYc46;^x(xM4c*v*d@rD|7@rXHn!wfw2pU?PeQ;)m2t}H_92bOSj|~%E`D@eL<}v z=@MpwVg%DItk*8h%rp|yJV#xPf&*k@%6mEmhdYU)`ZsQNIsi(nuD^vz02E3#sDVZ+ z`}G9Dy&v7SpYE;;yDP5G*HSY@X~L2(w8?F(*Ar*;uo#Cx@|-GP7S~<G<|N7KKQ?b5 zjV9_T4pQe)`4}c`WnMpqP*ytO61VM5`Lu5PT;0#0cy6+0MkJVxlt~I%)*1+7as{0A z<IPv~RZ<$CVj3T$Mxzc6aKb_h6#8Bv1iqg;wv=|IVcO+XvZe6=9K*OEqRV>~Jh-5} z%7(!EuU7M^Ex+8ZI~SNbXOX{(K5h2K2i%&<l>~DcEY}8`Od@gJD&-JSitlD>mu$>% zJ%00L<Z@P`iFxD}VP$e1ILW9|qB+TW>iGQQmXuzyKDBH3-a1^>iR`gwdu&n=)?c}l zFB-OR*pTJ4hsjBzLY=1Kw-nR1w8L@Uxt);lgmC=`-~F!r_z3$}@IY8G%!lqq@>V=H zs;WX@IRlVw>#fn{91{vHo}v{CE%SX@#}hlaxCN9NUCU@FuJ4hFs=A4Hm@o8S2?~-8 z9BN6>o{-AOko}AqTc-5A;UbFF^Qr7AuJa;onM2?mt=bup#BNXAb$-OmBB=mGL*b8y z9;vRbu65BT(dP|T`S`RkMy0Vi*j;SRpLmTpmHPZPo+f;WIGdMKfD|)>IY<qMMa~jT zLa?-=anGvP%1*S}uke-W9JGcwB#UYFk{i<0;<_?CTUKbah%f5K<!G>88t5@^Keq31 zQ~l>qW{ziqXy&-eBP4HW|M1I$d^Ul0D&%e%aJ+g>vrNco>QQa~C<<Xd1_`KxM_xOE z9&57J{XdzAF;zqs)=;;|lpoS@fSAhR@ri-hN~X(VCHm!KQ?tGEk98PXr>Xx=?*5E+ zCyp<cY#L;#$Y>_fN;GGsntRlBIn>I8UG1!H;2XoIwH_nlr-6fP5z6~~)A%a0ZSq*4 z4%Y|4wUK1n!#i%K-EJefH@;MmR^cxh#TcNInkF{!hB3AIWom?pwp}i&XXkvoY=46T z1K-tV^ti|R2?d5xSD$Ph`BX0WwJOW11=|^JLq?afX_>Y<uYErZ;(zW1f9|r!^vw!* zI^!EHf<H<XUth27dwM7(<nU9WIzq31;Hsn#+S!B^ZYy!M)D&4Q+7KquSZoxdpF9d> zv^u&O%NpdM@Lfa;?o*Jx4@b`_w(c^{^2{f*1d$zENCRMJ@EzFzb;_29F(<LH)S~0- z;Dl?)O=TavJg3NrR~nebbtTq5>c;Vd2LldJK+vW3D-1G_pLy%E%yGa*!947D(00nC zb|&BnVD*hn9R*??_xJX>4%pIIVXXr%)G~R7d3+zXPkXq1#03#5>N+4^jW-7aM$Xfh zy+vyEX?3EY1rnB(kPvQv<ultSyCFru7d!rAQim?Z8;H~FIem-<O@C6&n0-`JR@iN^ z+8z8(f@&S|UH&`==M4zQtLt0_E(v<p*qgLT5&%$%qKuWI_mW&?_84Ab)PrB#uYkL_ zRU<asW6y>s%nyE4{OkuuKVRCwCj=GWT9tfI@e`?G&MxeTS=oP!>4cP1=iPdWnB6>+ zB5j|^P!<hRt~A|Pp;IzXR@3hn+~YQHUWqS-SRl36g}+$Ev2XS1a!leOKg}xpy6>YH zEi_`)YnYc>(#`c!Qo+@#gBpccx0xuqB75PtV;g3{*-c>zBC*5MewS4Mw1(r_DE=+m z_G5u?dZA%0W+QhbzGE6pLiO`$XY?#rR9(tK>hevqPIJq{I7UlDi_YS>@h3tVcNGQ= zqag==)3YFmb*@A9(kAC0xCxofUp~ko2dNzh-er~)Sv)u!Z2FTOZS!v*hv&7h!EZ|G z?Wuhk^(}1*15kK8Ct0@ghcul%2N2MDZJP&A5iUPGx$@y)VmW#Q)ktdw^mWnPXI&&s zKvQy#U-Lz*7+VH};1d!@`FXkJM8NX^7I0ifk)%8%#?cxezn9hx*oW$3WSDC{-}{$4 zeoyZr11zqqWJ^2NbW;W}@skjoU<O3}%HzmBJBitZxU}Lm%X^<&Is4&~T9Pndo`&-< za1HK6KOyU;9?HiV%GtV6?t+d`fpUXt4P<<mkG~9@>gp>E(x_j<*DS!CO@N}sB~8dq z$Lr(D&J<6mgXo_>q-}%(Pd;;NIof>NeoxuHr7p40idCJqcFmi@S38jC>kzYTpkBR& z!+w~&%yUWWUiq$9YK8^BeBCMV<EO*<=2@?T(z^9}(i(UEhlwYdb6?7Zq3ubvot51+ z_<@a{Qjeq`v7RIj)nEB1h{A>>+rnDIofHIBCVK8~#73h$*Fzk$2a&QD&vDDWY?!OP z4Fpi$cIyo)urGd3<{{=-k9F+iGiyCrR7K$EVT$^p=qgnLzc}aQH~ZrbL{eT?+FkUr z-c|NqRitz2`m_9}7+~~?;!4x~5H!AFNF3@3trE1ydEFPrgGdwhsIXidtvt^fgSQrR zW(`jQCzjo0@STNi_5>u2pDN`*SqU*nm&r-D(PLnvk})H`GqNyic8q{*kW>%O!7R6y zLh!eU9$l~En{|gjw2o|17}FpLb_^W`hFJsIdD|Io8(n8bf7X|CnBXqaQV%C>8WBQ^ z-(uAw$<$}7aW44^on1PHRY8V@c=cp>>TRWATSORv(TXi<K0J7?468PLcbu5U_{g`n z1xq_Vmzw@}KhS<vPI_*M?*iq6OC4uM6&)oaR=GxIjZS}zCX@Q5^L(CjV57%1X1YgS zvFHJni0M1kOcGN)1^8@}f6>7&gWa0SbSMARVCadA>_PMx!>bJZEYFavt5Nwih-0rs z&WydI%$i-t42dz4V;T>QL|y&CRL1V->|5<AK*PE34JY$L%QfrVWu~Xev7W_V^>lig z<A5L|CFpeYC*rOqQn1U9IhLP7tnA)Tr%FbOf>}wCu`Utbp?BeKENwUT=4V=M-7E;N zl`R?Y<%+Nn4@~6EMU$A;#(nyEz<l1}mA9KV4vW8+?}c`&0n5eBs*t-QYpOj_))nEZ zZlA9EcRm(p8~x)Zb{8BM<S5K_v1sOof*PtC+MDhL<8s<(Kr0I&&d~-{ps|n2kp=w5 zYh<DVxx~pnT%_C0raUAKB!e5XikN*1Jtz+%1$9iK4^Si^Kf;aGVQ$FnRSuT4#+Ewj z+jQXXixh!PujO;Gy|+-QzBdhYG8)%B1M@?PLuVgC6bPx&fi~j=Vo9jt40}vueSq5_ zRCYyDn;$Y%8EL|cMT8k6S|S+2+NqiAAQ9ZQF9G`!un%(dv@n!3b@v=EHtOLskxZXX zBZdsA5Ery5E<S)L=4YPX=H*PQEtl#WA*F4YKwDyEd%ar*ADQcK4X=(nIxO4lvnZ0@ zbR-()Zd%M=ddJ<#NP6{(<VJS5LBDOMKja~YhA!P$sfs!9{!~ZoOwa$s)8%{qunNWA zU6nXWTOUs6ny&i+HM&+0j9p_BDD2??ES?oxxmXa|&ZahvCUdhSo6?A2f;B?EQ^xQV zHP8L<>5e!4HoH$GKn11>5`#<Va$>xErYrSgJNx#FXu$)0FUl&5Y&-To4v<zIebn2G z<Z3;vc9unoEW+;YGEHQuleyh<l!APEzM}QlCs*U-ghZWs*$CO}B?9~^NOo;4nIEpN zC>dlmkE%D<I)Ycjp<<JhY6CF9H@&}s!Qs#HXRQhB(9U7otlP<FIh3j!EHkfwdxyoM z2I${+VGYnLe|PhszSc8Ob%DHU<Xm+`Qt+;XArlbbU%M4ivx?G|7|JqgN=;z8(Ifw9 zyLE9DR6Axz{nY{CG>Bn8GXF#dn8@+`yGRJYxi8!&?Ky?nrD7<18(c*)P17MF`1=+1 znf${gRwVB?+AtOr)5rK}_dl*H1GY{UG3?4emApH?)!9MT)|b{k9m|s3vAwj7slSpo zN-qd}$R!MU>jor|DiI#U?omhUI^SMc%lhHhN#Qx2F@DrHIj?ziflktF;2oRMz3Ia= zhJk1&C`T#oxh3mVQY~wxcw~ZZh)`m~fxW_XEG*YM+^W-1kU4^=Ie;XU_aX-3(h!=l znB=U{R>73)o(c4@9N-f*dn30;I1dB1v&~=hp&kT_vc93U!2Xpe&8nQl!-Ab}w@nEK zwOh8ZzBgBzWC7^aV+w~=MRMOl=9WQsvEI?{?fLPCE+}_l{ggIwt<)QM51MVspZbw_ zUtWs2v-@;@fM`0XTUC3Ikt37r#OE&3f6`45nC_^$f?v#NSHQ+J^{1qF$r>E<3cIE$ z-b#Vgwv4s+r)E5?9(Be=w2n81u}PZ>S1FFstl6BO6Hj%Vy?-#lhkdUQ9fl-DBKwM+ zt*}x`&K4WCmHmBex=$V&EXkt?PC<Td&TL-AAUuqJG0aeiki{P_!1m&bgwcpXzhRq+ z=0(LXJnIKM0GH<6PCEw%<G0}O7)lCFYqWy#g7C=$#@8{;eb#S+DKYb%abwZ-Dv^8y zs#vlrBEZ=&8fSP@?jm^BEN9XKj(n<@(1RjdU-k`L2Y!O_X?P9G-jbMt^Pjf-k-#fA zlL{}ub#8Yxb-&%+uCPd{lG@kz@2P{e#u5>%2REs8gac#pUYS+94$zh5<$gPpcW?%q zA-_+AnNFff>J~O@%oRpzZ89L@VLP=74wNq5>o;tEI;!9aks+InOyE!2X7TzV%|Xe2 zQxN<;GDmJAs3aGx<pCDcJl)bGqkl1>PM@<l>9^JuM-zfb^o>r-HOGzKi@=is{J=tW z#UlUW-I#8`<0Y8=#}PdMtpK>E<D_A<S#EUW*7$+6BMu}uP-c0wAIh_6+rr+*rsl@I zfq(9$eNw=XilPa=`|#wwG%XrBt+vOXSeNGn@{aL9SrJ)b5LmgJVsGElQyk|}TK4jU znVKPHy=reKvMA!8B;-1#JJblFLczuRisu9b@FZF^@7HSrsRX|~Z5a8_t|Wq_%&|gV z+l3aKX+R!6&}wkSOCY~R;rS`ZV$dLer--T#)98|4Fy8zIrBep&>JAN3o2iGmmQ5ZN zjdWvO9Kyoy0&zZzB;bpfcI8H)^#8O~M3MtWB&@0Jt`T75^`W|8`piWA%8cSed_#?c zwS#wjbGi<09jyKcc9?pBdn*Iuh)h$U++@$1owBzOSEh)oRyXN$pPfLETvGIADY`j5 zm{ZFVsiet~18UucoBg%SSKbuXMB_^D9kCFZ(~7Om(kFI0B!y&~7*2rwJQjr)6+6VM zd6VGmqA~27H3qwhC`qyA{F^}^#xN4@wOssOaqsV53TQPzA;9J>OhYdY<s%E#8|vBj zv|!&0tUP=|DFUhF;X$7I;_LRcEkMA@z$C^*Gw}R}d<bb6Mg(bCtTLDJZqZdLX&4Q$ zxBHG{pXScz*E+O<M}zz`cgHiXXDU*fTiEm@$=n5+LHAlu7cV*z<=C^BoO-8S4|Gse z>(IZwIKFtc;Mi||wzjY`S0`3ItP3KMhPZX$T5wwAve`o?1sO9`-y+K{uIbEUT|Tn- z+6@?b+uV}u<}%=5S<v^g5ehR=4Vac`OppIurRWWjeYiOKz^Msi6A$U-$@;35o1ayc zDd%sWcH0Il#8q|*E)|h8?H3ogrC-X=F_V+DndK)mA9PY6ecEBky{7F*b@77xY7N>C z{e-wS8or;ut>_0s^!JEDh-+rIe(BY!&U-9J1+k}Xwgl21hA9F!ke?p7qy53Vnxp)j zSEsbMuiBayd;@^}TE3*s+cjy{HCv3l@iMKVt)4B$ewp^nEx70>%Nog=mX@-zfBM+< zG{_b8Qd2fUa}|J~+`==pD@i?O_7I+sS9{nSD0`?6`%OAaKfEe$HHxfJkgAXmEk)YS zre^t_*Sf5kU#<R@fZ|%HkmH!1XTef5l*}<}VC(Wh>^AW^-naBw^`@3DDK5#?8SHD8 z@J&9>z*3wj$=6oHv3_*4Jog*yRk-6kC89XfQ?2EJNys_M1wnTpy&N}wytXqC?V0R+ z-<u%brtvt3P?Z~(Sgh{p0H=cWWL^wdwsCeLmFUktTGKw37!k(;aXYExccv^_X^7zH zX(cLfnwZz(iOV?xT{A*@ioBdDVnm+P;#lVhrY>T<kKF@{0}WbR)oHh||E=?<)|+;1 zvRQ9+s+3dbk{SyRBc9UK>{lu;w~Tgao_WuD8zz3qWlm__al{gb**)+z!uM3IIVbV0 zeOYO5?2}1CCu0R}2>=HZ>OaqhV00){QL?u<iBG<Eh>!2TdS<wUoK^eIB+<4a4TwOv zOweDhydWk5OWgTuO*^Sspkdo^jOGp%YT^ac`l-!YWHy#L36)!YQ*$6<g0$-0#s?Vo z7IsG3BmU&W>-j~vq4R_Xoij^zNmJE+I86`@eRGYGW7BegI#|Pc;4SCBi7NO>ld2*t zLTEtTqyM+Y?2y9`n5>y3V(Em@sM?$I%inaxo}r9FLu@Py82mL;yJM`XrRHT77dWQ- zhA^6ALV*2b$J>TbrL^rcGEV`fF;zrwT>KHdxLKo^Qbyt46NxpH&TrJxgnWLf)H?p1 zu-q**)4@UzSh=v%>BG^`XODsb-R1#9@eEs+;;MK4L>vy>E;^JrPuv?3yY10NuY7q^ z3yxJigi3BF>mn&ZxA>@tRck#_YxYFRi?5m|I+W#E8U92E4aP#_O6$>S1;5u3B|kVD zhw;jfe!F)mzMnmlzp35+z2B8^k0Ar=5AbsMV+_i-V3PS(Vea~!uSp2=Q>8*`_ssPZ zn6ptYzX4T%h+-o<p&Pi7=ki|n;SA|lS?#&xDJ!5WqbML0GAL$f65+NAA(nGyYo6E= zx-RPqI&V(4Ic3iAorq+i4nt3EM|+jai~LgB`qR5p=~5S}q&Ky5BjP1dxS|IY>MsJJ zXblO5`>k2qk%Xdx)+F0$B=IR?1$B|hyn07fPJ|Zg2Xocytz|l(sNgf2`88KF+tZ+z zm>8s`0Ikg5Z9jGDlPSOExrJ;e%6~6@sF8U29H#4%P*o(>a%+q#?)2ISj^4*m+yS|> zosG3-iRSlt@H|Ri6GWyl9z>vkDvO#lI{rYyjkYVQb;0VlW0LOoKxD3o{NqL=#D=2# zS>FXclPH(0V}EV~muXB-p&2c?-@a1lrr8L@6jy`%ILrs${zSOfME<*+TwFhIw&oN! zOEm(-4)EvXg53OHe8hDtqy(cVN95Io?Y@kzc^{}*&ApRU*c+IQx@Ez)iJ{nv)s}ci z8T#k<{w-q^a8(&KH#|c4Mww6BTc0=<8kiOB&ApQ)az4ZdzK)`?*{WYi{feIY0-1$x zYQJCDwnqcGn}}|}sIX+>4Jdv=i1mrZjI7(@S5FV6BUL1)ZgmmwPpA2-&MK@8vX`F9 zqd%}R(`PUSoMLy2ShS)37vu6~UCDQOdX21;)!b=?YB@Cfztj)tyU8({l05o9^-j^A zSRxDCreZNt4sp`k?~yxNP!N%v?)UmYFZiZ6c^NBGuxzGWnGMC%3Um2*JBd0hN9$6~ zU^S`j3QX;uk$DdmU2$)pOPb6%ST?yg$-!ytly;UZxVMG3yQvm_iMJ((U4@x@S_?UD z2_$P~=;(Yrzl`IQ`uMKR1qWx;kN$-93b&Osh$o}l*Tcf%aopBtA7to|zNGczibDsu zOf0rv&U{p3Tgcsj-8QyhzYlq+D#d9Lie9VI`R-lrtV1(sEPB8TpaLJ|EHl{?C}-yD z*f_|-^RmbbLDf|WJ87SfnZ2#-l-rS&C6TpMO*D-vRbKplWUVH%7#?6`bH6#$938>9 z{=82n$2!-PRzc(;etp=i-2-0}@L901AgC0iyZowb)JkwWgsA!nY78_!GLO=5u<Itl zZ3wPC1Zw$7Q+&%=VFqer8$4H(;@vZSe(&j=haE5g5Rluok<n5je$8-tKtJ>o<ln$U zwXh$Na8{v(KUWQhO$GW6Wmn<i@cV$z#VnAdjiv&e&*tuQU>610Y0UO!ROP53Y~wPI zhpqS?DYTCNdax#rd436a`yN@bao}EwF!o_OOlK?pO5%PT8sCV+B=AfiIpO$AV^ca; z3{8L<MZ$-8^DPIy&h6JP3^Sb@BAQ)z=D+$<nR*BFPn0}sO>53RaoJ6?)u&=4rU;k! zM>n(56ew;h*+$_))<z>0Kd-x8Ren|zrzGS?AheeI3KA^z;-OCPQ%OS%BUhgL<p<9f z%MZJU2t+jzUu)qcZ?;~A$#IX`ih|AD;CHIiS6FdeJF6}xX546!T}}kYCBEhB<s~^x z(HS)?F8|ePg05mzO*I<s7Kf5%xtp9(P??0X2GeaTK(D6uw`t$x$ozqwhr)A+wr2t# zLEti-q}~8Q#5}LyKHoP1vB{tn|NBD)yXq>H>k9Yiq7rLX5gzpLO;WbD`81z3W}34^ zt5Eh4TQ^cGaTMn=uR;Dj{Wo^qD!NowOT-;KZ@%bfzD4HhC?r0;^dYm)(9eYRx*_r- z@zuuAdnJCWup;OkRt}?>#7N!h`SFFwi(3{{O3r=5?0XOh{X#M-c};|x-aPg#0>XKf zD7{{RWn;g|j|$by{+3grVVO8X5)Lg{^r5B59j_0IHz??Zpu<6}4$77M)?&(IEn?nw zSmkT;4qfmewKYOOrbcd!^d<2UcVaNvfCy+jv7e^#w@xZfhNzNEFrNWhpM7=nkNmin zvs6wL=EV4#DyrCbQxEaky!IQxjBHb`)~g)XiwRBXbow6p86=f^wRgy}pX}at3y|?P z$J$v*=@0tuwA#Z(I6`1Tik)1hjsv!HY`L7ql(n!nlP4z{#I$(^D;im-fQf!Dz44rV zP<I=+Fi$qBxQG*)*E9OHY+9_8`1*r<MJ6s|4f}ncw8QLsEARu>b|bWF`bzxZPo!AL zmZh@jxkM(v=cJm_OFeNfge?TRK3>Oc)X`+L5~(%VN%4%+7!oo@?@*-`Kt>?jO6@hW z@GUb<_aDx0?~$;jD8w3c3M1d&mZroGjC13nWi*?fBUB5#z;@zqofZ7kgA4~S1%B># z*<p$MMh%d<!v;RQ`Z=nm!&=Uv&Fn(r8EPPAX>XPQ8!B=6fDhze>KM_2E8TGLkea2s z0TdHY8yXlBP_tY`jWoZ44$f|xP<s<Q=NWr5rxYhges83-&^oa)a6=LLa>ZlHIA)D< z&;9D7Ealr6A#qKLBs*7RW^ukb8SIrKm3HLh>=&ElwnB4l8LHAD;sbp4;r*@E`z6(? zzU7;q29(tUKCM;_ojp$2<Uu&v5S`4ow%QBR7lh1!iOy-qKHffhxAZOi`8cb@E01LH zDd)*T6-;UzHzsgPOV%l?+M{KiRvhE`Z!#ddR~|4>ucQTT=iM?a#sl6J_2ntLz5MxP z_yyY(-MB3Dtj0Iqu$r@ZNgD^9PaE;#A8bx?4<d0>RKk)x*DjTo-rwO2BHv}aut*wE z8F=qK;0eE);XO}g2!hMp&jXghrsn)t0&>0Lk#|hWsqLo3@|hQ~oHK<9N@r_%2uqVq zW<?#B4`J0NuK1(CC3?jlf|8&2JYs^7cCgIirHP+q>lef<rrfi{x!|Es=7a24+!mrd z5GR?RADjH^H#xG3eb4PM!x3j0Ktivw+$I#q(G~r}DINH<2XvaC<uMsIH}Ry%Tkw+j zUD>Co)NbliFqYJh>D~=URRYF`5{?aYnC3<Tawe5PvS<wMO{LCLvHU<9>08Ob6IeKH zPmPhc_Zb8a|4P!d1|!=j)5Djg)+QwFEL1>I1d#=AC&_Y;+-6n2dxRw@<}dgpzq&+L z1@a;{vHLX0H+)Fus{duBwcKwx6{o@d@QR9$54kO}+=#68${6uvU49+;a8M5@uiOB3 z{#^YUp~Zk-e=a=Rb$LZaVD2@)82sEC4+7y1HR7G+$6gaNEuE9cHMyBJlemDhaFqp5 zco9#HFv}J+);BLopjs3t<OjK#wG2aY_$fnGKNeF%BL)0x#Q9RY{k-;OSTe^wS~i31 z&?!>A(akZP4uQZd6kU5++4|;o<+syQ`Xf!X4obWB;n<XCO1MO9y}cmn4DC<O-Su)- zk_;Y)3Q?W>@S$)aCQ|cLumH?cHd(LXPvn-V8sHIL5e8PDG<@k>upBz^@8K~t^Wn!z zcgl=8v!Ro=2d&=m_(2NMJ?~}H3-gVZ_>>d6I;Bq+5$LIs^5}^xd3(84WvsE`>D+r& zRfkHtE57F{SaIX{ec~G^2mTytgJMwTH;qw@-0M9t20zNe_zI2B$s-(3jp6uzn|UE^ zR@@=e2)rFgsWdX$AgvQ)v4gJa;^GB}(AwZ8h$RC_P|r&CsiHV~1(@KmnmU2HUWqN6 zD67(-%e!kO0}C7r+qqvqxy{$ZPwY_SUpR0R8{bmcxTl`g)(AA?eLC0nB^I16uADZY zdVJ#Gu(%ftoW@gcX|L0xA@n}HRX6Jb0FshwdlQjdCPyt0-Gk2x#eS6#>hQ#gYb7&` z`@skK;+M|5iVJn2ZF+3ExNclr4RIn1U6JX|!|fDpAglc*Im(xlotGq}i~H%uTi>%| z;m~JcHrKK=+1Isj16Lt=CW<GP)^1{5b8q@}TlhF3Yn83*kD5D4$fvxqM9!_i>i!hn zSJrYh&w4B?oD1z6m+fzO8@Nm_ITxnU^yxBmkK)J`TiApp%%c(-2N-czImLTY@6`5M zf+V5ZZI+h2sn_;Ue{;N~>dDo$@<B=)R}!jQjWuA;An0u(#x8CmE;MqxYi2_v2Qb?1 z-qcZj$$oB3b8YsNX$hzLE4<uAYb~bV(pu#6KcmYy41{&aOUyo$+hUZ93sV5|l1KB# z`N)6`G)ACh;C2?j``*;=GWkw^1K$d5<>OZZ%J;RWB4WH(7Kkm1xeuHl1^J6p!oFjM zYW8T{ZF__7%H3x6d(&SQ+)3Sje6qOqmJms6O~$CoQm$X;Mfe*pz+YrQWb5Wi&%4sP zWr`S03U|#yWps|w%aG~$p6qXlGk+?!XnOh4DmM$8xt<|#>B1@AJLBuixn+L|)vUjm zg}<Uj5UpQZ(CUTgUZG1IH=h$Ms88{sfm1(7Zo=!lAqmzeov;Bmg=hW=@Y<2@g5ke^ z@={eT_}}j_5KE$#taAK5?@P#;;F~)(?iSVz3oJ|x1Hi>-U}X+-uEAKqlMtlTECN(W zxfW*QLlJ5rDhloP;)if*8^f{19hl8*A_du|jVH85{A;Twh~V%S`(|nqw;SqbAuk4! zeQ+giOeT_LV-)Cys*X>i$@wPaY5j;sPDTYjutZPPm?M8G<Seh9);BU+Kr1ZIfX_^l z7O#SC0Ts7j@ox`*I~kW=-7U&dB{lYSF1Uyr*9)1H3uEnyZhlqsUf06>YTmY7<$P-x zbGWxC+xv^iNjuVHx^0<W%)qOgwPnpH%J@t7zwPYUBa)c=+}{eh|2tA9?lp8e<$*=7 z^_bm2RGKjxv`U}j7SB%B_OoJ}PA_xsvy0uy$@5V_PERatj^%KAlE9MNB-@aSNaf2p zj40f{adU1tnr_@-aqnhV`ae2JZSSL3$B2*q`Sf&uO#hWrw}MXYy^axZ^J0i^^!0&U zA(1&c621HQ57}M#8_LIR&;IE`&Y$g;s_*uS1u>vA|LXcK4z4Q+Uu)H>|LKYdv4H!2 zSa2oZbwrri?*<mm^U-TN%TrZw#n;ummP)pCxCt6JtUm{il@O7$yj}@-PW{c^tyb&r z=kSkW#&VF^`>wWKU4Q@EgL3XMy28n8hUmf{&Nqpgs)~T;2iFo~@#ly0N&0Xqf?K=S zeQa2zN!_QeqvE8{H?}5!xAxuI5m3E2?9?xE{xLu*xIpDcs@+uoisD~sD4=z3)j7eS zvwT<Z$*G$4L@So0EPW|1P2W;9r9<P}8@PqvyhZ_KH#iczKd81@tam0c&-iem@{fi9 z@CNUX(}cVKr=eHqi%y-`c{}K)ZVUExDmun~?i8XP2VbRshUnQr=1q~WdT9fc37M1? zV#UrBD%P@#NMrkEdeY!PBP)Q<7&L);Z1>lw{@PU$8r{2rDOLPw1-9#0k-eYlV<8#A zxDrB!ZsW3lSZqrHp*r&+m&-oK1?wPD&O`}npM%QXXugr3kVV$cxRa>oGu>TSdf9rc znKHTDr;~qVkSeM3*8(s+<iGqM0KOtihrElHldCODf}d&@*~tz5{b*9&d^S+iOXCyb zbBIgH{5GH#am&ziDaoPj@d{7qxb^<1=5pE~9PhVHZ}co@-J*-L%C5#uNO!HV|1BdA z2QZXa``b#@Ag2LgvD&{HY*c9vva8Gax-R%1O7K-BgV>>agIsM?4NK0w)Ml|dOHJ^W zCphXB2@qNK&9+CfGPLz=3Z&vS$k2XmXZtvKU;fdV)VD27qVe9zs~KP`4jGHAVDm&C z;E@BD&bB?>*?PlGZ8F8!pIkFtL!`C?g)(0TSDYVN|3P5~d-RF#pRRW(5HPC@Wsbl7 zXIdt1cqWMn_^Obu+lxsxLWar($2PyuQ^a{m=Y(ovJbot~sFgjJk#EWr?hosX+oimw z&>Y0|Lx%mJH&+XelXF%%)bp{PaDD5VH9edS>cCjoRdD5WpZ1E&Cv1wcNDvRRJeSjG z;M(Dbmu#t-|5DuD$DW?xId4-mRu~<yc8X@-!VI(hYeQptaElThT&PU@51v06zP`8_ z5k1cT1y6*tHPSJ3|Km3Nb|(K2vcTDLyOpsUgvqG@c)ZZGX3ZA&@p${FBW=ZJ9TM9l zxa`FMHT}X3CpYoSshT0)L3Y?jD7ym=;NisWZnvli30I8!@uU-%9{IRoJNplX!6NU6 z=&$#1n1?utre3h)=c)Y*lX+>l;tVQ8)c+y3zY@fkq%*I%Of>`jD!eYMTlTh@F441* zo@VzQ6~BHx4dM0nhJ})9gDcNgl)YZt$yubG4O+9MgM_mM?Da!5?>5P<XVn0YZqaCf z+l>U9n77jkaJ4&#?B*v-45jf+=EKimda8+?z6*(1`}KIe0{E^K_KSaB;9upj!<Cn{ zc{uwYhE1mM<0^o&rr`ynfM>DkawFf<ZW}n$fOebUPAUR_oZ4fS9&Wkr^kdV(ujz?8 zh)q8P{aQ5gzuiRdNZ|099k7bxfQ*$^Z03yXA{$PRf5$1S&L#n{eEUmuo5!J~MheRA z%W$^?wRi7C{TJwljBqbfd_&#vKf3cpM9WTv^CqLA$DBpPWwFm;tq$4`w7BxNCvRm| zIXr5Bzpo4(S|%BK1%Yy<9<xs$eRxQ&G8wMeiKM=BH*s-AO)?3kX_8l(K(v9Jlhsga zJPih_0P2eu$oz`$q_hGaPTig#uZ!S}Dz?^s4lj*7`Iqbk7VHun;BHWt!8TNlSey1A z+L-wZa0+jEyZ;0D3n)|M_pRZKl)oX2Zd0T>yhcb{sCv}*Lg)3KkBH{ty!A6RMsp#9 zvGGR8ddTyB*Gq!PmLLt@(3pGKD3b1P$M7U4qM&nX&qe%kCpB=xUnhxH71HmHtQX=K zvM}M-a&epfFKKQ6?VZZD*ZhCIfBz~cgKv({21n<<`pE^H>cb_4>B|$6J}{yGtj&F0 zv1W{T2zQnE7}-w`=c5->nrfkt&&V@No-5*qjr(Pl7C6qY+FPHW?swtQ$9uS^@QZHG zcAwUZU>%MwBUt{ZWBAdAec5G@qxfwVSL@AZw5kJnpZ(H0xjWm*E!TgHHgJRx?xKNP zpz(irza3eQ7$L^tyG@8379y+MHJ&8Cr8|va6ac-WK=K~$o<mO}=%PBXQA~A@%w1#Z zg{^F<i9~q@*z#^53l2)x%RY|QEXy7X_6$@{**-@Nsrq89Z@zxM<0*`<pcZ_z`qzWu z|AlhUT>QV$Pip%P<JXgKQr70kM1h1E`vlzhcJ3|stmr=|WRr{=QocrrLMI#6W*Qb< z4H4f?#>^q2g{qanx>spRd#rgaa}4|&X;A+^2n-%<g|@><FAW5Ex^aV|Gv_nJit&CA zm5lztk|>sk{H1zWAZouB(Ybu1WB1<(<z0KwfwlMiNb!FboZ23M#?5;_V;s;u1sj#P zXTPd3bZFRIqgXhvNWQ+?FE5viCCC5!sPs27;e=ywY4dpYKLUmKAJSfw<DU*Es%C!r zH#zBIKo|XbC)2y5reo>3Nw^jl7=F3&{tH<;6RGLr!2j#_Cv&cQ4cxxv(JKD(7)$6p z+!suy@|dwnY&OpC{rD$tX-5`Og|kp^yr}g5SSZklfi9-^vJkskTYLYr#kKxj7R}$! z$n5|6Q3&(V!+#;pSM-PQuaIXL3b>3ww*cW5K;zr-ulp~Cf764wjp09!^v~S>iU-~Z z8+?W`jF#8`Ire`-#s7Eg|EFF!U$?8H>&8*D@ihJax3}}RJ;UzfzW<ZhfArOk9QGcr z3iXJ&mj6lQU*`WC0O-KmJ7n{h|2HK1{}}@lw-(&E!ru@5UBvjmmj3;x@%`#ELJ;>W V*`;1dwioa}MOoE%Wzr@={|{~ggmeG^ literal 0 HcmV?d00001 diff --git a/docs/testScene/tuto_1.py b/docs/testScene/tuto_1.py index c0990b52..63fb60cb 100644 --- a/docs/testScene/tuto_1.py +++ b/docs/testScene/tuto_1.py @@ -58,11 +58,9 @@ def createScene(root_node): bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) section_curv_abs = [0, 10, 20, 30] - frames_curv_abs = [0., 5, 10, 15, 20, 25, 30] - cosserat_G_frames = [[0., 0, 0, 0, 0, 0, 1], [5., 0, 0, 0, 0, 0, 1], [10., 0, 0, 0, 0, 0, 1], - [15, 0, 0, 0, 0, 0, 1], [20., 0, 0, 0, 0, 0, 1], [25., 0, 0, 0, 0, 0, 1], - [30., 0, 0, 0, 0, 0, 1]] - + frames_curv_abs = [0, 10, 20, 30] + cosserat_G_frames = [[0., 0, 0, 0, 0, 0, 1], [10., 0, 0, 0, 0, 0, 1], [20., 0, 0, 0, 0, 0, 1], + [30., 0, 0, 0, 0, 0, 1]] _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, beam_radius) diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py index 18ffcb64..a3ebd7e5 100644 --- a/docs/testScene/tuto_2.py +++ b/docs/testScene/tuto_2.py @@ -1,8 +1,5 @@ # -*- coding: utf-8 -*- -import Sofa -from useful.params import Parameters - stiffness_param = 1.e10 beam_radius = 1. @@ -58,7 +55,7 @@ def createScene(root_node): # build beam geometry nb_sections = 6 - beam_length = 30. + beam_length = 30 length_s = beam_length/float(nb_sections) bending_states = [] list_sections_length = [] @@ -66,18 +63,18 @@ def createScene(root_node): section_curv_abs = [0.] # section/segment curve abscissa for i in range(nb_sections): - bending_states.append([0, 0.2, 0.]) # torsion, y_bending, z_bending + bending_states.append([0, 0.0, 0.]) # torsion, y_bending, z_bending list_sections_length.append((((i + 1) * length_s) - i * length_s)) temp += list_sections_length[i] section_curv_abs.append(temp) - bending_states[nb_sections-1] = [0, 0.2, 0] + bending_states[nb_sections-1] = [0, 0.0, 0.3] section_curv_abs[nb_sections] = beam_length # call add cosserat state and force field bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) # comment : ??? - nb_frames = 6 + nb_frames = 32 length_f = beam_length/float(nb_frames) cosserat_G_frames = [] frames_curv_abs = [] diff --git a/docs/testScene/tuto_3.py b/docs/testScene/tuto_3.py index dac6ad97..fb3bac86 100644 --- a/docs/testScene/tuto_3.py +++ b/docs/testScene/tuto_3.py @@ -14,10 +14,8 @@ from useful.params import Parameters from cosserat.CosseratBase import CosseratBase -geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, - nbSection=6, nbFrames=12, buildCollisionModel=0) -physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., - beamLength=30) +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, nbSection=6, nbFrames=12, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., beamLength=30) simuParams = SimulationParameters() Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) @@ -31,4 +29,4 @@ def createScene(root_node): # create cosserat Beam solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) - return root_node \ No newline at end of file + return root_node diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py index fde01043..d8477bd0 100644 --- a/docs/testScene/tuto_4.py +++ b/docs/testScene/tuto_4.py @@ -49,6 +49,7 @@ def onAnimateEndEvent(self, event): # choose the type of force if self.force_type == 1: + print('inside force type 1') self.compute_force() elif self.force_type == 2: self.compute_orthogonal_force() @@ -57,7 +58,8 @@ def onAnimateEndEvent(self, event): def compute_force(self): with self.forceNode.forces.writeable() as force: - vec = [0., 0., 0., 0., self.forceCoeff / sqrt(2), self.forceCoeff / sqrt(2)] + vec = [0., 0., 0., + 0., self.forceCoeff/sqrt(2), self.forceCoeff/sqrt(2)] for i, v in enumerate(vec): force[0][i] = v @@ -67,7 +69,7 @@ def compute_orthogonal_force(self): # Calculate the direction of the force in order to remain orthogonal to the x axis of the last frame of the beam. with self.forceNode.forces.writeable() as force: vec = orientation.rotate([0., self.forceCoeff * 5.e-2, 0.]) - vec.normalize() + # vec.normalize() # print(f' The new vec is : {vec}') for count in range(3): force[0][count] = vec[count] @@ -102,8 +104,7 @@ def createScene(root_node): cosserat_frames = cosserat_beam.cosseratFrame # this constance force is used only in the case we are doing force_type 1 or 2 - const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, - indices=geoParams.nbFrames, forces=force_null) + const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-8, indices=geoParams.nbFrames, forces=force_null) # The effector is used only when force_type is 3 # create a rigid body to control the end effector of the beam @@ -112,11 +113,10 @@ def createScene(root_node): showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], showObject=True) - cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=1e8, angularStiffness=1e8, + cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=1.e8, angularStiffness=1.e8, external_points=0, external_rest_shape=controller_state.getLinkPath(), points=geoParams.nbFrames, template="Rigid3d") - solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, - tip_controller=controller_state)) + solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, tip_controller=controller_state)) return root_node diff --git a/docs/text/Introduction.md b/docs/text/Introduction.md index f7a45b8a..62b03fa6 100644 --- a/docs/text/Introduction.md +++ b/docs/text/Introduction.md @@ -84,13 +84,13 @@ Yinoussa Adagolodjo --- ##### Why combine different models ? - Existing design and modeling tools demand enhancement, particularly in the mechanical aspect. -![](Pasted%20image%2020231108201224.png) +![](../images/Pasted%20image%2020231108201224.png) - Offer a wide range of design possibilities: - Selection of actuators, force transmission within the structure, utilization of materials with varying stiffness profiles, and more. --- ##### Cosserat Theory Choose strain as generalized coordinates, defined in global (or local) frame! -![400](Pasted%20image%2020231108233708.png) +![400](../images/Pasted%20image%2020231108233708.png) [Lazarus et al. 2013] - The configuration of the Cosserat rod is defined by its centerline r(s). - The orientation of each mass point of the rod is represented by an orthonormal basis ($d_1(s), d_2(s), d_3(s)$) @@ -117,27 +117,27 @@ Choose strain as generalized coordinates, defined in global (or local) frame! - Strain $\begin{align}\xi(s,t) &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ - Kinematics : $g'=g\hat{\xi}(X)$ ; $\dot{g} = g\hat{\eta}$ - Differntial Kinematics : $\eta'=\dot{\xi}(X)-ad_{\xi(X)}\eta(X)$ -![](Pasted%20image%2020231109002926.png) +![](../images/Pasted%20image%2020231109002926.png) --- -![0](Pasted%20image%2020231108234643.png) +![0](../images/Pasted%20image%2020231108234643.png) --- ##### DCM (Dynamics) -![800](Pasted%20image%2020231109003349.png) +![800](../images/Pasted%20image%2020231109003349.png) --- ##### DCM Dynamic -![](Pasted%20image%2020231109003734.png) +![](../images/Pasted%20image%2020231109003734.png) --- ##### Approximation via PCS, VS and PLS -![300](Pasted%20image%2020231109003934.png) +![300](../images/Pasted%20image%2020231109003934.png) - **PCS**: A local approximation scheme employing a local constant strain assumption. - **VS**: A global approximation method based on the chosen basis functions. - **PLS**: A local approximation scheme with a linear strain function assumption. --- ##### PCS Cosserat -![](Pasted%20image%2020231109004616.png) +![](../images/Pasted%20image%2020231109004616.png) --- ##### Discrete Cosserat Modeling: DCM diff --git a/docs/text/Setting up the Environment.md b/docs/text/Setting up the Environment.md index ff858574..42b3973a 100644 --- a/docs/text/Setting up the Environment.md +++ b/docs/text/Setting up the Environment.md @@ -66,7 +66,7 @@ Now, we'll dive into the essential part – configuring the Cosserat plugin with 5. **First Cosserat Scene: *tuto_1.py*** - As said previously, this component is based on the PCS (Piece-wise Constant Strain) formulation. - ![](Pasted%20image%2020231102173536.png) + ![](../images/Pasted%20image%2020231102173536.png) --- ##### **Goals** : - how to create a basic scene with the cosserat plugin @@ -143,19 +143,19 @@ def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _fram ###### The complete scene ![tuto_1.py](../testScene/tuto_1.py) ---- -- [ ] Example 2: **![tuto_2.py](../testScene/tuto_2.py)** - - [ ] script for automating sections and frames - - [ ] **Goal**: show the role of the number of sections on the overall deformation - - [ ] Example: - - [ ] 6 sections; 32 frames: $b_y=0.2$ on the last bending_state - - [ ] 12 sections 32 frames: $b_y=0.2$ on the last bending_state - - [ ] 6 sections 6 frames: all variables $b_y=0.2$ - - [ ] Change to frames = 12/24/32 - - [ ] Shows that we have a smoother curvature than previously while emphasizing the fact that there is rather a geometry impact, but not a physical one. +- [x] Example 2: **![tuto_2.py](../testScene/tuto_2.py)** + - script for automating sections and frames + - **Goal**: show the role of the number of sections on the overall deformation + - Example: + - 6 sections; 32 frames: $b_y=0.2$ on the last bending_state + - 12 sections 32 frames: $b_y=0.2$ on the last bending_state + - 6 sections 6 frames: all variables $b_y=0.2$ + - Change to frames = 12/24/32 + - Shows that we have a smoother curvature than previously while emphasizing the fact that there is rather a geometry impact, but not a physical one. ---- -- [ ] Scene **![tuto_3](../testScene/tuto_3.py)** - - [ ] Use the $CosseratBase$ Python class and $prefabs$ +- Scene **![tuto_3](../testScene/tuto_3.py)** + - Use the $CosseratBase$ Python class and $prefabs$ ```python def createScene(root_node): addHeader(root_node) @@ -167,7 +167,7 @@ def createScene(root_node): return root_node ``` --- -- [ ] Uses also python $dataclass$ +- Uses also python $dataclass$ ```python - geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1,nbSection=6, nbFrames=12, buildCollisionModel=0) - physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., beamLength=30) @@ -177,17 +177,17 @@ def createScene(root_node): ``` --- ##### Some known examples ![tuto_4](../testScene/tuto_4.py) - - [ ] Force type 1 - - [ ] Force type 2 - - [ ] Force type 3 + - Force type 1 + - Force type 2 + - Force type 3 --- ##### FEM & DCM coupling for finger actuation ![tuto_5.py](../testScene/tuto_5.py) -- [ ] The cable is modeled using the DCM -- [ ] The finger is modeled using FEM -- [ ] Constraints are based on the Lagrange multiplier - - [ ] **QPSlidingConstraint** - - [ ] **DifferenceMultiMapping** +- The cable is modeled using the DCM +- The finger is modeled using FEM +- Constraints are based on the Lagrange multiplier + - **QPSlidingConstraint** + - **DifferenceMultiMapping** --- ##### An example of the use of pre-curved cables, use cases (see scenes from Flavie) [tuto9.py](http://tuto9.py) diff --git a/docs/text/Theory.md b/docs/text/Theory.md index d40f71dd..64beb6e0 100644 --- a/docs/text/Theory.md +++ b/docs/text/Theory.md @@ -9,11 +9,11 @@ cssclasses: --- Solide Works -![](Pasted%20image%2020231025171449.png) +![](../images/Pasted%20image%2020231025171449.png) --- -![[Learning/Learning&Development/Formation/cosserat/docs/text/Untitled Diagram.svg]] +![[../images/Untitled Diagram.svg]] --- diff --git a/docs/text/cosserat_python_scene.md b/docs/text/cosserat_python_scene.md index c27d84ae..1893f237 100644 --- a/docs/text/cosserat_python_scene.md +++ b/docs/text/cosserat_python_scene.md @@ -111,7 +111,6 @@ Les frames ne sont pas obligatoirement à équidistances les unes par rapport au $$ R :[x , y, z, 0, 0, 0, 1] $$ - Spring - - Rigidité - Rigidité angulaire From 7ed928a5d36e1aaade41cd7c6966792d7c9c1092 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Sun, 19 Nov 2023 18:05:03 +0100 Subject: [PATCH 22/71] last modif --- .cache/jb/UpdateWork.dat | Bin 0 -> 3912 bytes .cache/jb/version.txt | 1 + docs/images/Untitled Diagram.svg | 1 + docs/testScene/tuto_4.py | 2 +- .../tutorial/Writerside/cfg/buildprofiles.xml | 12 + examples/python3/tutorial/Writerside/hi.tree | 8 + examples/python3/tutorial/Writerside/in.tree | 21 + .../topics/Advanced Topics and Future Work.md | 49 + .../Writerside/topics/Background Concepts.md | 57 + .../tutorial/Writerside/topics/Brouillons.md | 40 + .../tutorial/Writerside/topics/Complement.md | 84 + .../Writerside/topics/Direct Simulation.md | 51 + .../Writerside/topics/Introduction.md | 156 + .../Writerside/topics/Inverse Simulation.md | 47 + ...el Convergence and Sensitivity Analysis.md | 53 + .../tutorial/Writerside/topics/Numerics.md | 10 + .../topics/Setting up the Environment.md | 58 + .../Writerside/topics/Soft_robot_intro.md | 70 + .../tutorial/Writerside/topics/Theory.md | 41 + .../Writerside/topics/cosserat_tutorial.md | 86 + .../tutorial/Writerside/topics/tutorial.md | 91 + .../tutorial/Writerside/writerside.cfg | 8 + .../tutorial/formation/chiba/Actuator.py | 115 + .../chiba/BendingAngleMeasurement.png | Bin 0 -> 895374 bytes .../BendingAngleSOFA-COMSOL-Experiment.png | Bin 0 -> 13247 bytes .../chiba/PicturesExperiment/0kPa.jpg | Bin 0 -> 157289 bytes .../chiba/PicturesExperiment/100kPa.jpg | Bin 0 -> 161836 bytes .../chiba/PicturesExperiment/10kPa.jpg | Bin 0 -> 156881 bytes .../chiba/PicturesExperiment/20kPa.jpg | Bin 0 -> 157846 bytes .../chiba/PicturesExperiment/30kPa.jpg | Bin 0 -> 158002 bytes .../chiba/PicturesExperiment/40kPa.jpg | Bin 0 -> 159519 bytes .../chiba/PicturesExperiment/50kPa.jpg | Bin 0 -> 159632 bytes .../chiba/PicturesExperiment/60kPa.jpg | Bin 0 -> 160243 bytes .../chiba/PicturesExperiment/70kPa.jpg | Bin 0 -> 160838 bytes .../chiba/PicturesExperiment/80kPa.jpg | Bin 0 -> 160849 bytes .../chiba/PicturesExperiment/90kPa.jpg | Bin 0 -> 161698 bytes .../formation/chiba/PicturesSOFA/0kPa.png | Bin 0 -> 115298 bytes .../formation/chiba/PicturesSOFA/100kPa.png | Bin 0 -> 145545 bytes .../formation/chiba/PicturesSOFA/10kPa.png | Bin 0 -> 112182 bytes .../formation/chiba/PicturesSOFA/20kPa.png | Bin 0 -> 114954 bytes .../formation/chiba/PicturesSOFA/30kPa.png | Bin 0 -> 117182 bytes .../formation/chiba/PicturesSOFA/40kPa.png | Bin 0 -> 120387 bytes .../formation/chiba/PicturesSOFA/50kPa.png | Bin 0 -> 124184 bytes .../formation/chiba/PicturesSOFA/60kPa.png | Bin 0 -> 127441 bytes .../formation/chiba/PicturesSOFA/70kPa.png | Bin 0 -> 131710 bytes .../formation/chiba/PicturesSOFA/80kPa.png | Bin 0 -> 135723 bytes .../formation/chiba/PicturesSOFA/90kPa.png | Bin 0 -> 138796 bytes .../tutorial/formation/chiba/actuator_v1.py | 132 + .../chiba/data/mesh/CHAMBER20mm-075mm.stl | 24222 +++++++ .../formation/chiba/data/mesh/CHAMBER20mm.stp | 287 + .../chiba/data/mesh/act23mmwithconnector.msh | 29361 ++++++++ .../chiba/data/mesh/act23mmwithconnector.stp | 1026 + .../data/mesh/act23mmwithconnector075.msh | 56586 ++++++++++++++++ .../formation/chiba/fingerController.py | 28 + .../chiba/loopstest_function_param3.py | 125 + .../chiba/problemmappingtransversalfiber.png | Bin 0 -> 461877 bytes .../tutorial/formation/chiba/timerreset.py | 100 + .../formation/chiba/tutorial_chiba.md | 71 + git | 0 log | 0 .../forcefield/BeamHookeLawForceField.h | 1 + .../forcefield/BeamHookeLawForceField.inl | 95 +- src/Cosserat/mapping/BaseCosserat.h | 24 +- src/Cosserat/mapping/BaseCosserat.inl | 29 +- .../mapping/DiscreteCosseratMapping.h | 6 +- .../mapping/DiscreteCosseratMapping.inl | 58 +- 66 files changed, 113117 insertions(+), 95 deletions(-) create mode 100644 .cache/jb/UpdateWork.dat create mode 100644 .cache/jb/version.txt create mode 100644 docs/images/Untitled Diagram.svg create mode 100644 examples/python3/tutorial/Writerside/cfg/buildprofiles.xml create mode 100644 examples/python3/tutorial/Writerside/hi.tree create mode 100644 examples/python3/tutorial/Writerside/in.tree create mode 100644 examples/python3/tutorial/Writerside/topics/Advanced Topics and Future Work.md create mode 100644 examples/python3/tutorial/Writerside/topics/Background Concepts.md create mode 100644 examples/python3/tutorial/Writerside/topics/Brouillons.md create mode 100644 examples/python3/tutorial/Writerside/topics/Complement.md create mode 100644 examples/python3/tutorial/Writerside/topics/Direct Simulation.md create mode 100644 examples/python3/tutorial/Writerside/topics/Introduction.md create mode 100644 examples/python3/tutorial/Writerside/topics/Inverse Simulation.md create mode 100644 examples/python3/tutorial/Writerside/topics/Model Convergence and Sensitivity Analysis.md create mode 100644 examples/python3/tutorial/Writerside/topics/Numerics.md create mode 100644 examples/python3/tutorial/Writerside/topics/Setting up the Environment.md create mode 100644 examples/python3/tutorial/Writerside/topics/Soft_robot_intro.md create mode 100644 examples/python3/tutorial/Writerside/topics/Theory.md create mode 100644 examples/python3/tutorial/Writerside/topics/cosserat_tutorial.md create mode 100644 examples/python3/tutorial/Writerside/topics/tutorial.md create mode 100644 examples/python3/tutorial/Writerside/writerside.cfg create mode 100644 examples/python3/tutorial/formation/chiba/Actuator.py create mode 100644 examples/python3/tutorial/formation/chiba/BendingAngleMeasurement.png create mode 100644 examples/python3/tutorial/formation/chiba/BendingAngleSOFA-COMSOL-Experiment.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/0kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/100kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/10kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/20kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/30kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/40kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/50kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/60kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/70kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/80kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesExperiment/90kPa.jpg create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/0kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/100kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/10kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/20kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/30kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/40kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/50kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/60kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/70kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/80kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/PicturesSOFA/90kPa.png create mode 100644 examples/python3/tutorial/formation/chiba/actuator_v1.py create mode 100644 examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm-075mm.stl create mode 100644 examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm.stp create mode 100644 examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.msh create mode 100644 examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.stp create mode 100644 examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector075.msh create mode 100644 examples/python3/tutorial/formation/chiba/fingerController.py create mode 100644 examples/python3/tutorial/formation/chiba/loopstest_function_param3.py create mode 100644 examples/python3/tutorial/formation/chiba/problemmappingtransversalfiber.png create mode 100644 examples/python3/tutorial/formation/chiba/timerreset.py create mode 100644 examples/python3/tutorial/formation/chiba/tutorial_chiba.md create mode 100644 git create mode 100644 log diff --git a/.cache/jb/UpdateWork.dat b/.cache/jb/UpdateWork.dat new file mode 100644 index 0000000000000000000000000000000000000000..96efdac2ca8478e462d735b8f00b89cc707ce3d1 GIT binary patch literal 3912 zcmXSoY@5C2()4r&B*2fv9%YV(z-S1JhQMeDjE2By2#kinXb6mkz-S1JhQMeDjE2By Q2rw`#|73PKQX)<P0DaB~3;+NC literal 0 HcmV?d00001 diff --git a/.cache/jb/version.txt b/.cache/jb/version.txt new file mode 100644 index 00000000..1b346901 --- /dev/null +++ b/.cache/jb/version.txt @@ -0,0 +1 @@ +(ssh://git@git.jetbrains.team/llvm/llvm-project.git 8f193d135b5e285f03a4863d7cf657c97c24b0b3 based on LLVM ed5dd8e5f0fb6ca4af26adcb6193a9d9106eb36a revision) \ No newline at end of file diff --git a/docs/images/Untitled Diagram.svg b/docs/images/Untitled Diagram.svg new file mode 100644 index 00000000..8adcb32d --- /dev/null +++ b/docs/images/Untitled Diagram.svg @@ -0,0 +1 @@ +<svg xmlns="http://www.w3.org/2000/svg" version="1.1" height="51.05808008195618px" width="426.69656662948114px" viewBox="-10 -10 446.69656662948114 71.05808008195618" content="&lt;mxGraphModel dx=&quot;1930&quot; dy=&quot;410&quot; grid=&quot;1&quot; gridSize=&quot;10&quot; guides=&quot;1&quot; tooltips=&quot;1&quot; connect=&quot;1&quot; arrows=&quot;1&quot; fold=&quot;1&quot; page=&quot;0&quot; pageScale=&quot;1&quot; pageWidth=&quot;827&quot; pageHeight=&quot;1169&quot; math=&quot;0&quot; shadow=&quot;0&quot;&gt;&lt;root&gt;&lt;mxCell id=&quot;0&quot;/&gt;&lt;mxCell id=&quot;1&quot; parent=&quot;0&quot;/&gt;&lt;mxCell id=&quot;4&quot; value=&quot;&quot; style=&quot;shape=cylinder3;whiteSpace=wrap;html=1;boundedLbl=1;backgroundOutline=1;size=13.467679773635808;rotation=91;&quot; vertex=&quot;1&quot; parent=&quot;1&quot;&gt;&lt;mxGeometry x=&quot;70&quot; y=&quot;-150&quot; width=&quot;42.63&quot; height=&quot;425&quot; as=&quot;geometry&quot;/&gt;&lt;/mxCell&gt;&lt;/root&gt;&lt;/mxGraphModel&gt;"><style type="text/css"></style><path d="M 192.03 -173.5 C 192.03 -180.94 201.58 -186.97 213.35 -186.97 C 225.12 -186.97 234.66 -180.94 234.66 -173.5 L 234.66 224.56 C 234.66 228.13 232.42 231.56 228.42 234.08 C 224.42 236.61 219 238.03 213.35 238.03 C 207.7 238.03 202.27 236.61 198.28 234.08 C 194.28 231.56 192.03 228.13 192.03 224.56 Z" fill="#ffffff" stroke="#000000" stroke-miterlimit="10" transform="rotate(91,213.35,25.53)" pointer-events="none"/><path d="M 234.66 -173.5 C 234.66 -166.07 225.12 -160.04 213.35 -160.04 C 201.58 -160.04 192.03 -166.07 192.03 -173.5" fill="none" stroke="#000000" stroke-miterlimit="10" transform="rotate(91,213.35,25.53)" pointer-events="none"/></svg> \ No newline at end of file diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py index d8477bd0..d1200b99 100644 --- a/docs/testScene/tuto_4.py +++ b/docs/testScene/tuto_4.py @@ -113,7 +113,7 @@ def createScene(root_node): showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], showObject=True) - cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=1.e8, angularStiffness=1.e8, + cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=0., angularStiffness=1.e8, external_points=0, external_rest_shape=controller_state.getLinkPath(), points=geoParams.nbFrames, template="Rigid3d") diff --git a/examples/python3/tutorial/Writerside/cfg/buildprofiles.xml b/examples/python3/tutorial/Writerside/cfg/buildprofiles.xml new file mode 100644 index 00000000..e0e1a8f2 --- /dev/null +++ b/examples/python3/tutorial/Writerside/cfg/buildprofiles.xml @@ -0,0 +1,12 @@ +<?xml version="1.0" encoding="UTF-8"?> +<buildprofiles xsi:noNamespaceSchemaLocation="https://resources.jetbrains.com/writerside/1.0/build-profiles.xsd" + xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"> + + <variables></variables> + <build-profile instance="in"> + <variables> + <noindex-content>true</noindex-content> + </variables> + </build-profile> + +</buildprofiles> diff --git a/examples/python3/tutorial/Writerside/hi.tree b/examples/python3/tutorial/Writerside/hi.tree new file mode 100644 index 00000000..ec3e6f22 --- /dev/null +++ b/examples/python3/tutorial/Writerside/hi.tree @@ -0,0 +1,8 @@ +<?xml version="1.0" encoding="UTF-8"?> +<!DOCTYPE instance-profile + SYSTEM "https://resources.jetbrains.com/writerside/1.0/product-profile.dtd"> + +<instance-profile id="hi" name="Help Instance" + start-page=""> + +</instance-profile> \ No newline at end of file diff --git a/examples/python3/tutorial/Writerside/in.tree b/examples/python3/tutorial/Writerside/in.tree new file mode 100644 index 00000000..55eac7af --- /dev/null +++ b/examples/python3/tutorial/Writerside/in.tree @@ -0,0 +1,21 @@ +<?xml version="1.0" encoding="UTF-8"?> +<!DOCTYPE instance-profile + SYSTEM "https://resources.jetbrains.com/writerside/1.0/product-profile.dtd"> + +<instance-profile id="in" + name="instanceName" start-page="tutorial.md"> + + <toc-element topic="cosserat_tutorial.md"/> + <toc-element topic="Theory.md"/> + <toc-element topic="Numerics.md"/> + <toc-element topic="tutorial.md"/> + <toc-element topic="Introduction.md"/> + <toc-element topic="Soft_robot_intro.md"/> + <toc-element topic="Direct Simulation.md"/> + <toc-element topic="Background Concepts.md"/> + <toc-element topic="Advanced Topics and Future Work.md"/> + <toc-element topic="Setting up the Environment.md"/> + <toc-element topic="Inverse Simulation.md"/> + <toc-element topic="Model Convergence and Sensitivity Analysis.md"/> + <toc-element topic="Complement.md"/> +</instance-profile> \ No newline at end of file diff --git a/examples/python3/tutorial/Writerside/topics/Advanced Topics and Future Work.md b/examples/python3/tutorial/Writerside/topics/Advanced Topics and Future Work.md new file mode 100644 index 00000000..fa7b716d --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Advanced Topics and Future Work.md @@ -0,0 +1,49 @@ +# Advanced Topics in Soft Robotics + +**Slide 1: Advanced Topics in Soft Robotics** + +- Title: Advanced Topics in Soft Robotics +- Content: + - Introduction to advanced topics and emerging areas in the field of soft robotics. + - Discussion of how soft robots are being used in various applications. + - Brief overview of the evolving challenges and opportunities in the domain. + +--- + +**Slide 2: Applications of Soft Robots** + +- Title: Applications of Soft Robots +- Content: + - Detailed exploration of practical applications where soft robots are making an impact. + - Examples of industries and domains benefiting from soft robotics (e.g., medical, automation, exploration). + - Emphasis on real-world scenarios where soft robots provide unique advantages. + +--- +**Slide 3: Future Work and Research Directions** + +- Title: Future Work and Research Directions +- Content: + - Presentation of potential research areas and directions for future work in soft robotics. + - Addressing unsolved challenges and open questions in the field. + - Discussion of how the combination of FEM and DCM can be extended and improved. +--- + +**Slide 4: Robotics in Education and Training** + +- Title: Robotics in Education and Training +- Content: + - Highlighting the role of educational and training programs in fostering expertise in soft robotics. + - Discussing how tutorials, like the one being prepared, can contribute to knowledge dissemination. + - Encouraging the audience to explore and contribute to the advancement of soft robotics. + +--- + +**Slide 5: Conclusion and Call to Action** + +- Title: Conclusion and Call to Action +- Content: + - Summarizing the key points discussed in the Advanced Topics and Future Work section. + - Inspiring the audience to take an active role in the field of soft robotics. + - Encouraging collaboration, innovation, and exploration of advanced topics. + - Thanking the audience for their attention and participation. +--- diff --git a/examples/python3/tutorial/Writerside/topics/Background Concepts.md b/examples/python3/tutorial/Writerside/topics/Background Concepts.md new file mode 100644 index 00000000..88be5df5 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Background Concepts.md @@ -0,0 +1,57 @@ +# Background Concepts + +**Slide 1: Background Concepts - Introduction** + +- **Slide Title:** Understanding the Fundamentals + +**Content:** +- Briefly introduce the "Background Concepts" section. +- Explain that to grasp the hybrid FEM and DCM approach, participants need to understand some fundamental concepts. +- Highlight the importance of a strong foundation in soft robotics and simulation techniques. + +--- +**Slide 2: Soft Robotics Principles** + +- **Slide Title:** Soft Robotics: Core Principles + +**Content:** +- Define the core principles of soft robotics, including compliance, flexibility, and adaptability. +- Use images and examples to illustrate these principles. +- Emphasize the fundamental differences between soft robots and traditional rigid robots. +--- + +**Slide 3: Finite Element Methods (FEM)** + +- **Slide Title:** FEM: A Cornerstone of Soft Robot Simulation + +**Content:** +- Provide an overview of Finite Element Methods (FEM) and their role in simulating soft robots. +- Explain how FEM breaks down complex structures into smaller elements. +- Describe how FEM handles material properties, deformations, and forces. +- Showcase real-world applications of FEM in soft robotics. + +--- + +**Slide 4: Deformable Continuous Models (DCM)** + +- **Slide Title:** DCM: Modeling Cable-Driven Mechanisms + +**Content:** +- Define Deformable Continuous Models (DCM) and their significance in soft robotics. +- Explain how DCM focuses on modeling cables and deformations in soft robots. +- Discuss the advantages of DCM, such as the representation of cable-driven actuation. +- Share practical examples of DCM applications in soft robotics. + +--- + +**Slide 5: Bridging the Gap with Hybrid Modeling** + +- **Slide Title:** Hybrid Modeling: Combining FEM and DCM + +**Content:** +- Introduce the core concept of the tutorial: the integration of FEM and DCM for more accurate simulations. +- Explain the motivations behind this hybrid approach. +- Highlight the complementary nature of FEM and DCM in simulating different aspects of soft robots. +- Preview the real-world implications and benefits of this hybrid modeling strategy. + +--- diff --git a/examples/python3/tutorial/Writerside/topics/Brouillons.md b/examples/python3/tutorial/Writerside/topics/Brouillons.md new file mode 100644 index 00000000..348d3c95 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Brouillons.md @@ -0,0 +1,40 @@ +# Brouillon +**Overview** +Remember to make the tutorial interactive, engage the participants, and provide opportunities for questions and discussions. You may also consider sharing the tutorial materials, code, and relevant resources with participants for further learning and experimentation. + +--- +**Partie 1:** +Each slide should be visually engaging with relevant images, diagrams, and minimal text. You can also use this opportunity to set the tone for the tutorial, making it clear that participants are embarking on an exciting journey into the world of soft robotics simulations. + +--- +**Partie 2:** +Each slide should be visually appealing, with clear and concise explanations. Make use of diagrams, images, and bullet points to enhance understanding. The aim is to provide participants with a solid foundation in the background concepts essential for grasping the hybrid FEM and DCM approach. + +--- + +Configuring the environment with SOFA and the Cosserat plugin is a critical step in your soft robotics simulation journey. This subsection serves as a foundation for the practical implementation of the hybrid FEM and DCM approach, allowing you to accurately model and simulate soft robots with complex deformations and interactions. + +--- +- Voir Deformable Continuous Models (DCM) + +--- + +These five slides will provide a detailed overview of the "Inverse Simulation" subsection, explaining the purpose, examples, computational aspects, and concluding remarks. This will help your audience understand the role of Inverse Simulation in soft robotics. + +--- +These five slides will provide a detailed overview of the "Model Convergence and Sensitivity Analysis" subsection, explaining the purpose, examples, implications, and concluding remarks. This will help your audience understand the significance of these analyses in soft robotics. + +--- + +These five slides will provide a detailed overview of advanced topics, potential applications, future research directions, and the role of education and training in soft robotics. It will also motivate the audience to engage in the field and contribute to its growth. + + +---- +These ten slides incorporate elements from the provided paper and database, delivering a detailed introduction to the hybrid framework, its motivations, objectives, and contributions. It also includes an overview of FEM, DCM, advanced topics, and future work in the realm of soft robotics. The presentation concludes by encouraging the audience to explore the full paper for further information. + +--- + + +These ten slides provide a detailed introduction to the hybrid framework, its motivation, objectives, and contributions, as well as an overview of FEM, DCM, and a glimpse of advanced topics and future work in the field of soft robotics. It concludes by motivating the audience to explore the paper's contents. + +--- diff --git a/examples/python3/tutorial/Writerside/topics/Complement.md b/examples/python3/tutorial/Writerside/topics/Complement.md new file mode 100644 index 00000000..909a4c89 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Complement.md @@ -0,0 +1,84 @@ +# Complement Introduction + +Certainly, here is an updated version of the extended introduction section with ten detailed slides, incorporating elements from the provided paper and relevant content from my database: + +**Slide 1: Title and Introduction** + +- Title: Introduction to the Hybrid Framework for Soft Robotics +- Content: + - Introduce the audience to the paper, "Hybrid Framework for Real-Time Simulation of Soft Robots." + - Highlight the focus on combining Finite Element Method (FEM) and Discrete Cosserat Models (DCM) in soft robotics. + - Briefly mention the key points covered in the following slides. + +**Slide 2: Soft Robots in Modern Applications** + +- Title: Soft Robots in Modern Applications +- Content: + - Showcase real-world examples of soft robots' applications in various domains. + - Cite specific instances where soft robots have revolutionized medical, industrial, and exploration fields. + - Highlight the need for adaptable and safe robotic systems. + +**Slide 3: Challenges in Soft Robotics Modeling** + +- Title: Modeling Challenges in Soft Robotics +- Content: + - Explain the unique modeling challenges in soft robotics arising from deformable materials. + - Discuss the importance of real-time simulations for control and decision-making in such robots. + - Reference previous research in the field that addresses these challenges. + +**Slide 4: The Hybrid Approach's Promise** + +- Title: Promise of a Hybrid Framework +- Content: + - Detail the motivations behind developing a hybrid framework combining FEM and DCM. + - Present the advantages of using FEM for deformable materials and DCM for cable-driven robots. + - Provide examples of applications where the hybrid framework can excel. + +**Slide 5: Research Objectives and Contributions** + +- Title: Research Objectives and Contributions +- Content: + - Define the primary objectives of the research presented in the paper. + - Highlight the key contributions this paper offers to the field of soft robotics. + - Give the audience a glimpse of what to expect in the upcoming sections. + +**Slide 6: Paper Structure and Roadmap** + +- Title: Paper Structure and Roadmap +- Content: + - Offer an overview of the paper's structure, detailing each section's focus. + - Provide a roadmap to guide the audience through different aspects of the hybrid framework. + - Help the audience navigate and follow the presentation. + +**Slide 7: The Role of FEM in Soft Robotics** + +- Title: Finite Element Method in Soft Robotics +- Content: + - Explain the role of FEM in modeling deformable materials for soft robots. + - Cite examples of soft robot components where FEM has been effectively applied. + - Emphasize FEM's capacity to handle geometric non-linearity. + +**Slide 8: Introduction to DCM for Cable-Driven Robots** + +- Title: Discrete Cosserat Models for Cable-Driven Robots +- Content: + - Delve into the details of DCM and its suitability for modeling cable-driven robots in soft robotics. + - Showcase real-world applications of cable-driven soft robots. + - Explain how DCM handles reduced coordinates for modeling efficiency. + +**Slide 9: Advanced Topics and Future Directions** + +- Title: Advanced Topics and Future Directions +- Content: + - Provide a preview of advanced topics that will be discussed later in the paper. + - Offer insights into potential future research directions in the field of soft robotics. + - Encourage the audience to explore these exciting areas for further study. + +**Slide 10: Conclusion and Call to Action** + +- Title: Conclusion and Call to Action +- Content: + - Summarize the importance of the hybrid framework for soft robotics. + - Invite the audience to read the full paper for comprehensive insights into the topic. + - Express gratitude for the audience's attention and participation. + diff --git a/examples/python3/tutorial/Writerside/topics/Direct Simulation.md b/examples/python3/tutorial/Writerside/topics/Direct Simulation.md new file mode 100644 index 00000000..82af0d81 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Direct Simulation.md @@ -0,0 +1,51 @@ +--- +title: Introduction to Direct Simulation +--- + +--- +**Slide 1: Introduction to Direct Simulation** + +- Title: Introduction to Direct Simulation +- Content: + - Definition of Direct Simulation. + - Purpose of Direct Simulation in soft robotics. + - Importance of accurately modeling deformable robots in real-time. + - Overview of the content covered in this subsection. +--- +**Slide 2: Simulation Setup** + +- Title: Simulation Setup +- Content: + - Detailed explanation of the simulation environment setup. + - Mention of the software used (SOFA) and the Cosserat plugin. + - Steps for setting up SOFA and enabling the Cosserat plugin. + - Loading example scenes for practical experimentation. + +--- +**Slide 3: Soft Gripper Example** + +- Title: Soft Gripper Example +- Content: + - Introduction to the soft gripper used in the simulation. + - Discussion on its mechanical properties and complexity. + - Highlighting the integration of DCM to simulate the cables. + - Mention of friction and contact constraints for realistic interaction with a rigid object. +--- +**Slide 4: Observations and Analysis** + +- Title: Observations and Analysis +- Content: + - Presentation of the results from the direct simulation of the soft gripper. + - Discussion on the influence of cable properties (e.g., radius) on the gripper's deformation. + - Emphasis on the effect of using pre-bent rods for manipulation. + - Visualization of stress levels in cables and materials. +--- +**Slide 5: Conclusions from Direct Simulation** + +- Title: Conclusions from Direct Simulation +- Content: + - Summarizing the key findings from the direct simulation experiments. + - Emphasis on the importance of accurately modeling cables and their interaction with deformable structures. + - Relating the results to the overall objective of combining FEM and DCM for soft robotics. + - Transition to the next subsection on "Inverse Simulation" and the broader tutorial structure. +--- diff --git a/examples/python3/tutorial/Writerside/topics/Introduction.md b/examples/python3/tutorial/Writerside/topics/Introduction.md new file mode 100644 index 00000000..86b33fb8 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Introduction.md @@ -0,0 +1,156 @@ +--- +tutorial: Introduction +tags: + - tuto/cosserat +--- + +# Introduction + +**Introduction to Soft Robotics** + +- Soft robotics is an emerging and innovative field of robotics that focuses on the design and development of robots made from *flexible*, *deformable*, and *compliant materials*. +- These robots are in stark contrast to traditional rigid robots and offer numerous advantages, including adaptability, safety, and versatility in various applications. +- They are characterized by their ability to deform and adapt to their environment + - Ideal for interactions with humans, delicate objects, or unstructured surroundings. + +--- + +**Key Applications** +- Soft robotics finds applications in the field where the gentle and non-invasive nature of soft robots is leveraged + - healthcare, industrial automation, + - search and rescue, + - space exploration, and extreme environments. + +--- + +**Challenges in Soft Robotics** +Despite their promise, soft robots present unique challenges in modeling, control, and actuation. + - Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. + +--- +**Slide 2: Soft Robotics Overview** + +- **Slide Title:** Soft Robotics: A Paradigm Shift + +**Content:** +- Explain the evolution and significance of soft robotics as a field. +- Highlight the key differences between traditional rigid robots and soft robots. +- Share examples of real-world soft robot applications (e.g., medical, rescue, exploration). + +--- + +**Slide 3: Challenges in Soft Robotics** + +- Despite their promise, soft robots present unique challenges in modeling, control, and actuation. +- Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. +- Soft robotics is inherently interdisciplinary, drawing from fields like materials science, biomechanical, and control theory. +- Collaboration between experts from different domains is essential to advance the field. + +--- + +**Slide 4: Motivation for Combining Deformable Models** + +- **Slide Title:** Bridging the Gap: FEM and DCM + +**Content:** +- Explain the motivation behind combining Finite Element Methods (FEM) and Deformable Continuous Models (DCM). +- Discuss how FEM is well-suited for simulating soft body mechanics. +- Introduce DCM as a powerful approach for modeling cable-driven mechanisms in soft robots. +- Emphasize the benefits of this hybrid approach for more accurate simulations. + +--- + +**Slide 5: Tutorial Roadmap** + +- **Slide Title:** What to Expect + +**Content:** +- Provide an overview of the tutorial's structure. +- Mention the sections and topics you'll cover during the tutorial. +- Encourage participants to ask questions and actively engage throughout the tutorial. + +--- + + +**Slide 6: Hybrid Framework for Soft Robotics** + +- Title: Introduction to the Hybrid Framework for Soft Robotics +- Content: + - Brief introduction to the topic. + - Overview of the paper's focus on combining Finite Element Method (FEM) and Discrete Cosserat Models (DCM) in soft robotics. + - Set the stage for the subsequent slides. + +**Slide 7: Soft Robots in the Modern World** + +- Title: Soft Robots in the Modern World +- Content: + - Discussion on the growing significance of soft robots in various applications. + - Examples of soft robots used in medical, industrial, and exploration scenarios. + - Emphasis on their adaptability and safety. + +**Slide 8: The Challenges in Modeling Soft Robots** + +- Title: Modeling Challenges in Soft Robotics +- Content: + - Explanation of the unique modeling challenges in soft robotics due to deformable materials. + - The need for accurate and real-time simulations for control and decision-making. + - Mention of previous works on modeling soft robots. + +**Slide 8: Motivation for a Hybrid Framework** + +- Title: Motivation for a Hybrid Framework +- Content: + - Explanation of why a hybrid framework combining FEM and DCM is a promising solution. + - The advantages of using FEM for deformable materials and DCM for cable-driven robots. + - Real-world applications where such a hybrid framework can excel. + +**Slide 9: Research Objectives and Contributions** + +- Title: Research Objectives and Contributions +- Content: + - Presentation of the primary objectives of the research. + - The key contributions the paper aims to make to the field of soft robotics. + - A sneak peek into what the audience can expect in the subsequent sections. + +**Slide 10: Organization of the Paper** + +- Title: Organization of the Paper +- Content: + - Overview of the paper's structure and what each section will cover. + - An outline of the different aspects of the hybrid framework to be discussed. + - A roadmap for the audience to follow throughout the presentation. + +**Slide 11: An Overview of FEM in Soft Robotics** + +- Title: Finite Element Method in Soft Robotics +- Content: + - Detailed explanation of FEM and its application in modeling deformable materials in soft robots. + - Examples of soft robot components where FEM has proven effective. + - Highlighting the role of FEM in capturing geometric non-linearity. + +**Slide 12: Introduction to DCM for Cable-Driven Robots** + +- Title: Discrete Cosserat Models for Cable-Driven Robots +- Content: + - In-depth exploration of DCM and its suitability for modeling cable-driven robots. + - Providing examples of cable-driven robots in soft robotics. + - How DCM handles reduced coordinates for modeling. + +**Slide 13: A Glimpse of Advanced Topics and Future Work** + +- Title: Advanced Topics and Future Work +- Content: + - Teaser about advanced topics to be discussed later in the paper. + - Hints at potential future research directions. + - A call to action for the audience to explore these areas. + +**Slide 14: Conclusion and Call to Action** + +- Title: Conclusion and Call to Action +- Content: + - Summarization of the importance of the hybrid framework for soft robotics. + - Encouragement for the audience to read the full paper and delve into the details. + - Thanking the audience for their attention and participation. + + +[[Complement]] \ No newline at end of file diff --git a/examples/python3/tutorial/Writerside/topics/Inverse Simulation.md b/examples/python3/tutorial/Writerside/topics/Inverse Simulation.md new file mode 100644 index 00000000..b3e5e78c --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Inverse Simulation.md @@ -0,0 +1,47 @@ +# Inverse Simulation + +**Slide 1: Introduction to Inverse Simulation** + +- Title: Introduction to Inverse Simulation +- Content: + - Definition and purpose of Inverse Simulation in the context of soft robotics. + - Highlighting the role of Inverse Simulation in controlling deformable robots. + - Setting the stage for understanding how to determine cable actuation based on desired end-effector motion. +--- + +**Slide 2: Soft Finger Inverse Simulation** + +- Title: Soft Finger Inverse Simulation +- Content: + - Introduction to the soft finger model used for Inverse Simulation. + - Discussion on the complexity of the problem. + - Overview of the inputs and unknowns in the Inverse Simulation. + - Mention of constraints, including sliding constraints between DCM cable model and FEM silicone finger model. +--- +**Slide 3: Soft Tentacle Inverse Simulation** + +- Title: Soft Tentacle Inverse Simulation +- Content: + - Presentation of the soft tentacle robot used as an example for Inverse Simulation. + - Description of the scenario where the effector follows a predefined trajectory. + - Explanation of cable actuation to achieve desired end-effector motion. + - Highlighting the importance of controlling multiple cables in the inverse problem. +--- +**Slide 4: Timing and Computational Considerations** + +- Title: Timing and Computational Considerations +- Content: + - Discussing the computational resources required for Inverse Simulation. + - Mentioning the hardware used for the simulations. + - Providing a table with details on the number of elements, constraints, and computational time for each simulation scenario. + - Comparing the computational time between direct and inverse simulations. +--- +**Slide 5: Conclusions from Inverse Simulation** + +- Title: Conclusions from Inverse Simulation +- Content: + - Summarizing the key takeaways from the Inverse Simulation experiments. + - Emphasizing the challenges and complexities of solving inverse problems for deformable robots. + - Relating the results to the overall objective of combining FEM and DCM for soft robotics. + - Transition to the conclusion of the tutorial and future work. +--- diff --git a/examples/python3/tutorial/Writerside/topics/Model Convergence and Sensitivity Analysis.md b/examples/python3/tutorial/Writerside/topics/Model Convergence and Sensitivity Analysis.md new file mode 100644 index 00000000..b8123dec --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Model Convergence and Sensitivity Analysis.md @@ -0,0 +1,53 @@ +# Model convergence and Sensitivity + +**Slide 1: Introduction to Model Convergence and Sensitivity Analysis** + +- Title: Introduction to Model Convergence and Sensitivity Analysis +- Content: + - Definition and purpose of Model Convergence and Sensitivity Analysis in the context of soft robotics. + - Explanation of why it's important to assess the convergence of the model and analyze its sensitivity. + - Setting the stage for understanding how variations in model parameters impact the behavior of deformable robots. + +--- + +**Slide 2: Assessing Model Convergence** + +- Title: Assessing Model Convergence +- Content: + - Discussing the concept of model convergence in the context of deformable robots. + - Explanation of how the model's behavior changes with varying numbers of sections. + - Presenting a specific example (soft finger) and its convergence with different numbers of cable sections. + - Highlighting the role of section numbers in ensuring a converged model. + +--- + +**Slide 3: Analyzing Model Sensitivity** + +- Title: Analyzing Model Sensitivity +- Content: + - Introduction to model sensitivity analysis for deformable robots. + - Explanation of how variations in parameters affect the model's response. + - Presenting results of sensitivity analysis in the context of cable radius. + - Discussing the observed impact on the deformation of the silicone finger with varying cable radii. + +--- + +**Slide 4: Implications for Design and Control** + +- Title: Implications for Design and Control +- Content: + - Discussing the practical implications of model convergence and sensitivity analysis. + - Explaining how these analyses can inform the design of soft robotic systems. + - Emphasizing the importance of parameter choices in controlling deformable robots. + - Providing insights into how these findings can be applied in real-world soft robotics applications. + +--- +**Slide 5: Conclusions from Model Convergence and Sensitivity Analysis** + +- Title: Conclusions from Model Convergence and Sensitivity Analysis +- Content: + - Summarizing the key takeaways from the Model Convergence and Sensitivity Analysis. + - Relating the results to the overall objective of combining FEM and DCM for soft robotics. + - Highlighting the significance of understanding convergence and sensitivity in modeling. + - Transitioning to the conclusion of the tutorial and future work. +--- diff --git a/examples/python3/tutorial/Writerside/topics/Numerics.md b/examples/python3/tutorial/Writerside/topics/Numerics.md new file mode 100644 index 00000000..ab97c937 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Numerics.md @@ -0,0 +1,10 @@ +# Numerics +### Spatial Discretization + +### Time Discretization + +### Reduce to Global State + +### Global to Reduce State + +### Boundary conditions and interaction forces \ No newline at end of file diff --git a/examples/python3/tutorial/Writerside/topics/Setting up the Environment.md b/examples/python3/tutorial/Writerside/topics/Setting up the Environment.md new file mode 100644 index 00000000..25e6ee99 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Setting up the Environment.md @@ -0,0 +1,58 @@ +# Environment Configuration + +**Introduction to SOFA** + +In this section, we will guide you through the environment configuration for setting up SOFA and its Cosserat plugin. SOFA, which stands for "Simulation Open Framework Architecture," is an open-source framework designed for interactive physical simulations. It provides a flexible platform for simulating complex behaviors of soft robots, among other applications. + +--- + +**Step 1: Installing SOFA** + +Before you begin with the specific Cosserat plugin, you need to install SOFA. Follow these steps: + +1. Go to the official SOFA website (https://www.sofa-framework.org/) to download the latest version. +2. Choose the appropriate version for your operating system (Windows, Linux, or macOS). +3. Follow the installation instructions for your OS. Typically, this involves extracting the downloaded archive and setting environment variables. +--- + +**Step 2: Setting Up the Cosserat Plugin** + +Now, we'll dive into the essential part – configuring the Cosserat plugin within SOFA. + +1. **Obtaining the Plugin:** To work with Cosserat models in SOFA, you'll need to obtain the Cosserat plugin. Check if the plugin is included in the version of SOFA you downloaded. If not, you may need to install it separately. +--- + +2. **Activating the Plugin:** To activate the Cosserat plugin, follow these steps: + + - Open SOFA. + - Navigate to the Plugin Manager or Preferences (depending on the SOFA version). + - Find the Cosserat plugin and enable it. This step may require a restart of SOFA. +--- + +3. **Loading Example Scenes:** SOFA often comes with example scenes. Loading these examples is a great way to start experimenting with Cosserat models. You can load them directly from the File menu or import them using XML scene files. +--- + +**Step 3: Configuring Scene Files** + +Now that you have SOFA and the Cosserat plugin ready, you need to configure your simulation scene files. These XML-based files define the simulation environment, including the soft robot model, forces, constraints, and interaction with the environment. + +--- + +1. **Creating a Scene File:** You can start by creating a new XML scene file. This file will serve as the blueprint for your simulation. You can use a text editor to create and modify it. +--- + +2. **Defining Soft Robot Models:** Within the scene file, you must define your soft robot model. You can specify its geometry, material properties, and the use of Cosserat models to represent deformable structures. +--- +3. **Integrating Cosserat Components:** To utilize Cosserat models in your simulation, you need to incorporate the appropriate components from the Cosserat plugin. These components include the Cosserat beam elements, which are crucial for modeling cables and rods. +--- +4. **Adding Constraints:** Depending on your simulation, you might need to introduce constraints that describe the interaction between the robot and its environment. This is also an essential part of configuring the scene. +--- +5. **Configuring Simulation Parameters:** The scene file allows you to set various simulation parameters, such as time steps, numerical solvers, and visualization options. + +--- + +**Step 4: Running Simulations** + +After configuring your scene file, you can run simulations to see how the soft robot behaves. SOFA provides real-time visualization, making it easier to analyze and refine your models. You can interact with the simulated robot and monitor its performance as the simulation progresses. + +--- diff --git a/examples/python3/tutorial/Writerside/topics/Soft_robot_intro.md b/examples/python3/tutorial/Writerside/topics/Soft_robot_intro.md new file mode 100644 index 00000000..fefd0972 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Soft_robot_intro.md @@ -0,0 +1,70 @@ +--- +title: Introduction to Soft Robotics +--- + + +**Slide 1: Soft Robotics - A New Frontier** + +- Content: + - Soft robotics is an emerging and innovative field of robotics that focuses on the design and development of robots made from flexible, deformable, and compliant materials. + - Soft robotics is a cutting-edge field that focuses on the design and development of robots using compliant and deformable materials. + - These robots are in stark contrast to traditional rigid robots and offer numerous advantages, including adaptability, safety, and versatility in various applications. + +--- +**Slide 2: Characteristics of Soft Robots** + +- Content: + - Soft robots are characterized by their ability to deform and adapt to their environment, making them ideal for interactions with humans, delicate objects, or unstructured surroundings. + - Their compliance and flexibility are key attributes that enable them to handle complex tasks. + +--- + +**Slide 3: Applications in Healthcare** + +- Content: + - Soft robotics has found significant applications in the healthcare industry, where the gentle and non-invasive nature of soft robots is leveraged for tasks such as minimally invasive surgery and rehabilitation. + - Examples include surgical robots that can navigate delicate tissues with precision. + +--- + +**Slide 4: Industrial Automation** + +- Content: + - In industrial automation, soft robots are increasingly used for tasks such as pick-and-place operations, packaging, and assembly. + - The compliance of soft robots reduces the risk of damage during interactions with products. +--- +**Slide 5: Search and Rescue Operations** + +- Content: + - Soft robots are being explored for search and rescue operations, where they can navigate through tight spaces and uneven terrains. + - These robots can be vital in disaster-stricken areas to locate survivors. + +**Slide 6: Space Exploration and Extreme Environments** + +- Content: + - Soft robots have potential applications in space exploration due to their ability to adapt to different environments. + - They can also be used in extreme environments on Earth, such as deep-sea exploration or nuclear decommissioning. + +**Slide 7: Challenges in Soft Robotics** + +- Content: + - Despite their promise, soft robots present unique challenges in modeling, control, and actuation. + - Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. + +**Slide 8: Interdisciplinary Nature** + +- Content: + - Soft robotics is inherently interdisciplinary, drawing from fields like materials science, biomechanical, and control theory. + - Collaboration between experts from different domains is essential to advance the field. + +**Slide 9 : Futures Directions** + +- Content: + - The field of soft robotics continues to evolve, with ongoing research to overcome challenges and expand applications. + - Future directions include advancements in materials, control strategies, and the integration of soft robots into everyday life. + +**Slide 10: Conclusion** + +- Content: + - In conclusion, soft robotics represents a paradigm shift in the field of robotics, offering exciting possibilities for various industries. + - As technology advances and interdisciplinary collaboration thrives, soft robots are poised to transform the way we interact with machines and the world around us. \ No newline at end of file diff --git a/examples/python3/tutorial/Writerside/topics/Theory.md b/examples/python3/tutorial/Writerside/topics/Theory.md new file mode 100644 index 00000000..acd4c6c5 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/Theory.md @@ -0,0 +1,41 @@ +--- +[marp: +tags: + - tuto/cosserat +cssclasses: + - multi-column + - two-column-list + - two-columns +--- + +# Cosserat Theory +Solide Works +![](Pasted%20image%2020231025171449.png) + +--- + +![[Learning/Learning&Development/Formation/cosserat/docs/text/Untitled Diagram.svg]] + +--- + +#### Mathematical Description of Cosserat Rods + +##### Cosserat differential Kinematics + +>[!blank-container] +>- Configuration $g= \begin{pmatrix} \mathcal{R} & u \\ 0 & 1 \end{pmatrix} ∈SE(3)$ +>- Velocity $\eta(s,t) =\begin{align}y &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ +>- Strain $\xi(s,t) =\begin{align}y &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ + +--- +#### Reference Frames + +--- + +### Conservation of Momentum + +--- +### Linear Elasticity + + +--- \ No newline at end of file diff --git a/examples/python3/tutorial/Writerside/topics/cosserat_tutorial.md b/examples/python3/tutorial/Writerside/topics/cosserat_tutorial.md new file mode 100644 index 00000000..395b9d4d --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/cosserat_tutorial.md @@ -0,0 +1,86 @@ +# DCM & FEM Tutorial +A step-by-step tutorial for understanding how to model a 1D object using the Cosserat plugin within the SOFA framework. + +## Modeling 1D Objects with Cosserat Theory in SOFA** + +[Theory](Theory.md) + +[Numerics](Numerics.md) + + + + +**Introduction:** +In this tutorial, we will learn how to create a 1D object model using Cosserat Theory within the SOFA framework. This model is useful for simulating various physical systems, such as beams or rods. We'll cover the essential components and parameters needed to set up the model. + + **Prerequisites:** +Before you begin, make sure you have SOFA installed. If not, follow the installation instructions on the SOFA website. + +### **Section 1: Setting up the Environment** +1.1. Import necessary libraries: + - Import the required libraries, including SOFA and custom utility modules. + +1.2. Define the class: + - Begin by defining the `CosseratBase` class, which represents our 1D object model. + +### **Section 2: Class Initialization** +2.1. Constructor: + - Create the `__init__` method to initialize the class. + - Define the parameters and attributes used in the class, such as mass, geometry, and nodes. + +### **Section 3: Beam Physics Parameters** +3.1. Mass and Radius: + - Set the mass and radius of the beam using parameters. + +3.2. Use Inertia Parameters: + - Choose whether to use inertia parameters and set them accordingly. + +### **Section 4: Adding Rigid Base Node** +4.1. Create a Rigid Base Node: + - Add a rigid base node to represent the base of the 1D object. + - Specify its position and rotation. + +4.2. Attach the Base: + - Choose whether to attach the base to a link or allow it to follow arm position. + - Add a rest shape force field if needed. + +### **Section 5: Cosserat Coordinate Node** +5.1. Create a Cosserat Coordinate Node: + - Add a node to represent the Cosserat coordinates. + - Specify the parameters needed for the beam physics. + +### **Section 6: Cosserat Frame** +6.1. Create a Cosserat Frame Node: + - Add a node to represent the Cosserat frame. + - Include mechanical objects, mappings, and other necessary components. + +### **Section 7: Collision Models** +7.1. Add Collision Model: + - Implement collision models for interactions with other objects, if required. + +7.2. Sliding Points (Optional): + - Include sliding points or containers for specific scenarios. + +### **Section 8: Setting up the Scene** +8.1. Configure the Scene: + - Initialize the SOFA scene with necessary parameters and components. + - Define gravity, time step, and solver settings. + +8.2. Create the Object: + - Instantiate the `CosseratBase` class within the scene. + +**Conclusion:** +In this tutorial, we've learned how to create a 1D object model using Cosserat Theory in SOFA. We covered class initialization, beam physics parameters, rigid base nodes, Cosserat coordinates, collision models, and setting up the scene. With this knowledge, you can create and simulate various 1D objects for your specific applications. + +**Note:** This tutorial provides a high-level overview of the class structure and its components. For more detailed code explanations and demonstrations, please refer to the actual Python class code and comments. + + +## Applications + +### Build a simple cosserat Scene + +### Cosserat as cable for finger actuation + +### Cosserat as + +### Cosserat as diff --git a/examples/python3/tutorial/Writerside/topics/tutorial.md b/examples/python3/tutorial/Writerside/topics/tutorial.md new file mode 100644 index 00000000..be4bdc58 --- /dev/null +++ b/examples/python3/tutorial/Writerside/topics/tutorial.md @@ -0,0 +1,91 @@ +--- +title: DCM-FEM for Soft-Robot modeling Tutorial +tags: + - tutorial +Audience: Researchers, engineers, and students interested in soft robotics and the simulation of deformable robots. +Duration: This tutorial can vary in duration based on the depth and complexity of the material, but a typical plan could span 2-4 hours. +Prerequisites: Participants should have a basic understanding of robotics, mechanics, and computer simulations. Knowledge of finite element methods (FEM) and rigid body dynamics can be helpful. +--- + +_Welcome to this tutorial on SOFA-Cosserat Plugin._ + +_Outline of what participants can expect to learn during this tutorial ?_ + +--- + +## **1. [[Introduction]]** + - Briefly introduce the field of soft robotics + - Explain the motivation for combining FEM and DCM models. + +--- + +**2. [[Background Concepts]]** + - An overview of Discrete Cosserat Model (DCM) and their relevance in soft robotics. + - Finite Element Methods (FEM) and their use in simulating deformable structures ? + - The concept of compliance matrices and their role in soft robot modeling ? + +--- + +**3. [[Setting up the Environment]]** + - The software tools and libraries used (SOFA, **Cosserat** plugin). + - Instructions for setting up the simulation environment. + +--- +**4. [[Direct Simulation]]** + - How to + - Build the DCM scene ? + - Integrate it with FEM for the soft body ? + - The direct simulation of a soft robot (e.g., the gripper example from the paper). + - The role of constraints, friction, and contact forces. + +--- + +**5. [[Inverse Simulation]]** + - Demonstrate an inverse simulation for soft robots (e.g., using the soft finger or tentacle as examples). + - Explain how to compute actuation values to achieve desired end-effector positions. + - Discuss the handling of sliding constraints in the inverse problem. + +--- + +**6. [[Model Convergence and Sensitivity Analysis]]** + - Here we will share insights on how to evaluate the convergence of your model with varying parameters + - e.g., number of sections defining a cable + - Discuss sensitivity to material properties and other simulation parameters. + +--- + +**7. [[Advanced Topics and Future Work]]** + - Explore potential applications of your method in soft robot design. + - Discuss the ongoing and future research in this field, including real-world experiments and stress validation on cables. + +--- + +**8. Performance Optimization** + - How to **optimize the computation speed**, potentially using **parallelization**, model **order reduction**, or **recursive algorithms** for DCM. + +--- + +**9. Conclusion and Q&A** + - Summarize key takeaways from the tutorial. + - Open the floor for questions and discussions. + +--- + +**10. Practical Hands-On Session (Optional)** + - If feasible, you can provide participants with exercises or hands-on practice to apply the concepts learned. + +--- + +**Materials:** +- Presentation slides (see GitHub Repo) +- Repo folder tutorials. +- Code examples and simulations on the Repo/example. +- Reference: + - Paper RAL-SoRo : + - Paper (Féderico) : + - Paper (Flavie) : +- Q&A session for participant engagement. +- Feedback : direct and mails + +--- + diff --git a/examples/python3/tutorial/Writerside/writerside.cfg b/examples/python3/tutorial/Writerside/writerside.cfg new file mode 100644 index 00000000..07181d87 --- /dev/null +++ b/examples/python3/tutorial/Writerside/writerside.cfg @@ -0,0 +1,8 @@ +<?xml version="1.0" encoding="UTF-8"?> +<!DOCTYPE ihp SYSTEM "https://resources.jetbrains.com/writerside/1.0/ihp.dtd"> + +<ihp version="2.0"> + <topics dir="topics" web-path="topics"/> + <images dir="images" web-path="images"/> + <instance src="in.tree"/> +</ihp> \ No newline at end of file diff --git a/examples/python3/tutorial/formation/chiba/Actuator.py b/examples/python3/tutorial/formation/chiba/Actuator.py new file mode 100644 index 00000000..31889447 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/Actuator.py @@ -0,0 +1,115 @@ +import Sofa +from fingerController import FingerController #for keyboard controlling +#from timerreset import FingerController #Uncomment to perform timed measurements(increases of 5kPa every 2 seconds) +from loopstest_function_param3 import looptest #algorithm for generating the fiber loops +import gmsh + + + +def createScene(rootNode): + rootNode.addObject('RequiredPlugin', pluginName=['SoftRobots','Sofa.Component.SolidMechanics.FEM.HyperElastic']) + + rootNode.addObject('VisualStyle',displayFlags='showBehavior') + rootNode.gravity.value = [-9810, 0, 0] + rootNode.addObject('FreeMotionAnimationLoop') + rootNode.addObject('GenericConstraintSolver', tolerance=1e-9, maxIterations=50000) + rootNode.addObject('EulerImplicitSolver', name='odesolver', rayleighStiffness=0.01, rayleighMass=0.01) + + finger = rootNode.addChild('finger') + finger.addObject('SparseLDLSolver') + finger.addObject('MeshGmshLoader', name='loader', filename='data/mesh/act23mmwithconnector.msh', rotation=[90,0,-90],translation=[22.5,0,0]) + #finger.addObject('MeshGmshLoader', name='loader', filename='data/mesh/act23mmwithconnector075.msh', rotation=[90,0,-90],translation=[22.5,0,0])# use a finer mesh setting + + finger.addObject('MeshTopology', src='@loader', name='container') + finger.addObject('MechanicalObject', name='tetras', template='Vec3', showObject=False, showObjectScale=1) + youngModulus=263.8 + poissonRatio=0.49 + mu_ = youngModulus/(2*(1+poissonRatio)) + k0_ = youngModulus/(3*(1-2*poissonRatio)) + finger.addObject('TetrahedronHyperelasticityFEMForceField', materialName="NeoHookean", ParameterSet=str(mu_) + " " + str(k0_)) + #finger.addObject('TetrahedronHyperelasticityFEMForceField',template='Vec3', name="HyperElasticMaterial", materialName="NeoHookean", ParameterSet="3448.2 31034.4") + #finger.addObject('TetrahedronFEMForceField', template='Vec3', name='FEM', method='large', poissonRatio=0.45, + #youngModulus=263.8) + finger.addObject('UniformMass', totalMass=0.0008) + finger.addObject('BoxROI', name='boxROISubTopo', box=[23, -10, -8, 26, 10, 8], strict=False, drawBoxes=True) + finger.addObject('BoxROI', name='boxROISubTopo2', box=[0, -10, -4, 28, 10, -2], strict=False, drawBoxes=True) + finger.addObject('BoxROI', name='boxROI', box=[-2, -10, -20, 2, 10, 20], drawBoxes=True) + finger.addObject('RestShapeSpringsForceField', points='@boxROI.indices', stiffness=1e12, angularStiffness=1e12) + finger.addObject('LinearSolverConstraintCorrection') + #Plastic Part + modelSubTopo = finger.addChild('modelSubTopo') + modelSubTopo.addObject('MeshTopology', position='@loader.position', tetrahedra='@boxROISubTopo.tetrahedraInROI', + name='container') + modelSubTopo.addObject('TetrahedronFEMForceField', template='Vec3', name='FEM', method='large', poissonRatio=0.3, + youngModulus=4400000) + + # Parameters for the fiber reinforcement + loopnum=8 #number of loops + int=3 #distance between fiber loops. + loops, spring_set, indices1, indices2,lengths = looptest(int, loopnum) + hitching = finger.addChild("hitching") #fiber string that crosses the actuator transversally + #nbDOFs = 10 + Ks=1e7 #spring stinffness + Kd=5 + + + #Hitching (transversal fiber) + + hitching.addObject("MechanicalObject", template="Vec3", name="DOF", + position=[[(i)*int+1, 0, -4] for i in range(loopnum)], + showObject=True, showObjectScale=1) + hitching.addObject('MeshTopology', name='lines', lines=[[i, i + 1] for i in range(loopnum-1)]) + hitching.addObject("StiffSpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1, + stiffness=Ks,damping=Kd, indices1=[0,1,2,3,4,5,6], indices2=[1,2,3,4,5,6,7], lengths=int) + hitching.addObject('BarycentricMapping', name='mapping') + hitching.addObject('UniformMass', totalMass=0.0008) + + #Mapping + + #hitching.addObject("FixedConstraint", name="FixedConstraint", indices=[0]) + + # finger.addObject('MechanicalMatrixMapper', template="Vec3,Vec3", + # nodeToParse=hitching.getLinkPath(), # where to find the forces to map + # object1=finger.tetras.getLinkPath()) # in case of multi-mapping, here you can give the second parent + + # Fiber Loops + + + for k in range(0,loopnum): + fiber = finger.addChild("fiber"+str(k)) + fiber.addObject("MechanicalObject", template="Vec3", name="DOF", + position=loops[k], + showObject=True, showObjectScale=1) + fiber.addObject('MeshTopology', name='lines', lines=[[i, i + 1] for i in range(loopnum)]) + + #fiber.addObject("FixedConstraint", name="FixedConstragetLinkPathint", indices=[0]) + fiber.addObject("StiffSpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1, + stiffness=Ks, damping=Kd, indices1=indices1, indices2=indices2, lengths=lengths) + + # Mapping + + fiber.addObject('BarycentricMapping', name='mapping') + # finger.addObject("MechanicalMatrixMapper", template="Vec3,Vec3",name="MechanicalMatrixMapper"+str(k), + # nodeToParse=fiber.getLinkPath(), + # object1=finger.tetras.getLinkPath(), + # object2=hitching.DOF.getLinkPath()) + + # Air Chamber(cavity) + + tracker=finger.addChild("tracker") #trackers for measuring bending angle + tracker.addObject("MechanicalObject", template="Vec3", name="DOF", + position=[[29,0,-4],[31,0,-4]], + showObject=True, showObjectScale=1, drawMode=1) + tracker.addObject("MeshTopology", name="points", points=[[29,0,0],[31,0,0]]) + tracker.addObject('BarycentricMapping', name='mapping') + + #air Pressure Cavity. Note: 0.1=10kPa + cavity = finger.addChild('cavity') + cavity.addObject('MeshSTLLoader', name='cavityLoader', filename='data/mesh/CHAMBER20mm-075mm.stl', rotation=[90,0,90]) + cavity.addObject('MeshTopology', src='@cavityLoader', name='cavityMesh') + cavity.addObject('MechanicalObject', name='cavity') + cavity.addObject('SurfacePressureConstraint', name='SurfacePressureConstraint', template='Vec3', value=0, + triangles='@cavityMesh.triangles', valueType='pressure') + cavity.addObject('BarycentricMapping', name='mapping') + + rootNode.addObject(FingerController(rootNode)) diff --git a/examples/python3/tutorial/formation/chiba/BendingAngleMeasurement.png b/examples/python3/tutorial/formation/chiba/BendingAngleMeasurement.png new file mode 100644 index 0000000000000000000000000000000000000000..7f655c1321a0510b065d6fa3d82d08005854171e GIT binary patch literal 895374 zcmV)+K#0GIP)<h;3K|Lk000e1NJLTq00jU500Y1X0ssI2<-S8M00001b5ch_0Itp) z=>Px#1ZP1_K>z@;j|==^1poj532;bRa{vGi!vFvd!vV){sAK>D|D{PpK~#8NwEfwW zW!ZHec!tkI%n=z8IRZ$6m?T1^IEVm9Nmi8VMS7N1zsan-pS!Ies$aUT{}w$;CYiNL zQkzsQGnvXrQKU>P3KU1oQv!*cB4ct7kMN;?Yk%i1KYraK2{6$gA~)7v>s!Mf&OYb( z^<m{xpL}C&ZEa;`<?!(E`Sa(;$H%(s1D6({Y^<)XGM${9;FC8tHja*to<4oLySqz3 z5Q@INwzjs&_;b+6wYj-Te)jAcK6ha$1qmnak*kPHml9bEy3t?1eqDrvg9F`Bb(PKW z=;%3`Xkt=|Z(M5L-``KD1Zfx+G7P!uN7gmK)M<>A+uPe5Q*%dP?P|3ncA>2xR3=ud zD|nE}Pa7HtBCiykWrQyzCRBofr7lD>(w-Rpq&=$_Kbmx>=*P#Iz~-L{m#S<6L`Z9W zpFDYDAOyYyd^2|NY`=XmdtADiLrX?h2CKQfa^;FH%!6yWn1uQKNTDT1-=<&;qCnZ! z4oI&JxNFrMK13OiQ!sa3aS~sbGN#02O^SF?CKMN%lp0V%lR<W^E*Im{@`{pUE{D); zxf;ws*8mBaAW}rhn(Gmg3x}0H+0P>p&Z8YuKU$!Sc?~IyKFgXc^VasjHzF`nOq!e? zi6efP(PU#JDKG^|M`(S7xCiM5u|_#>)ew0Onp84(RBBAoL-c`C2XPrM(r4`Rn3!OR z$uZ$rZW@c2V<(6e_&UdIlg-WTjg6XlWHY9H<BivU?&p3^DA(Y(zV)r!w{Jgqcz@;i z<Y514FYqY5K)!$fe%vd{Si!83>oKJYOHc+m^`NC@0xPl;;M%ooXsr~GY%*C>8@;aW zp>m_UdGn?sv(}JVg&Q|+JbLu#@#Dvo4ho~d!B2cOryg;b6si99l_I&6s!sYKgAMqG z98(KYT)lc#ZMSaS`tgr{tUNVbzI-|L8{q4&zfLddJMX+huQo0mZQ~40!Se3x>~KjI zdP+3a-nnx}5VfgcZ*Px)naO<Xt+xbu?X}mKvfR8LJa}NX0W&k8l}-Vp-r6=a0hzB* z3P_i%NbZsv6lE?qg(;7_`83a%I4OyX8BhQYJ~9_3sVQ&Xxc$KgAH4L^OS;H{3!6A` zky@9dI2@lI?9sH6Knd@@`)=l3WIzViw|?*=^Ze;ge;Ppw`&K%eLA8b~e(o|RO<~-R zPiix8OdA2zCLPEUB{Hn9Z5r(1NiD~RAAV@tSQOUhN2mKiYl>Ya$90LUMOi@y5={*w z-UOUjBL}+OrjpjQpq*<vTKLh-1#QTXO0@Ku`RH-7D+p$Fc%P<D7hl`K>Emvm(@oog zMM+p7#F0Mnqnx{>8%=~D)j|k!8aYTe$SA@A?x{2N&q1k;ez=|)0<U@Hy4i2d?>0iu zPxuvOVGW{hp}R|1T{(Szo+Hub!Gpu2I!uDON%7^jK&(N{$e0sKw9J@p>v3WNS53T@ zko66%TbQo0+0=oUIe*BlPkZU8QaBZzA&~1-8O||RE(j%;$ycXq@WJCptZ{KHkP(=Y zm!O-BHJHV*7ESgZO_XiQ$`V9~<~-)>8>Bmog(c10lqn5752q3>NC(JTqodDLuCtNG zpbn4gSq^aM5#s9<Wd$^~v8H?Y?8sD8=9mrP>A};r)#*7raiE60x^m(_<+;<d9@m4! z=EiuEJgFh?Y;Tf1E8M$xPhs!9_g=~qr>jay$ZmXYtPdYPeD&2=os(9_BDx_eU|xS# z(<w@zcYt6zu|=*)K3Ow%U{VaPr_bv?s9TQ~$4Ab2yTaYaZb7)bx$Vxhd-<|Nyi~Zg zyW^fK>G!|?{ZIYen}7H3{@t(s@qd5w%{Sek-5UNM|Ih!|Sci{`wd>cfMVb#!K~_;W znh@v#jZ6u~Z;_0j-uRJY)g2y1!_h`==t{vv;FT_46DKc%2&|L|MN?}zy3s_4m(*Hv zmLxPc`UG#&P)?^OWkAUV6g5ga-R|ioASPerlrb?DU=2B-!EB_f<p`~TXdtrS_K>r~ z<3(=I?c0%4K&l#rmjE4&5SJihY(yEkV|M-IL<r|hdouZkmKI!@WL4P-i5dCe+3ABj zWv9TABJ-(>43q{E=2F}BlcS72V}~v{2%ml&BlXxFC0Yo<2wBMX1B7tIr)1&<vFavu z3qa<gg;7g^oFH*b4ULSKGTW)i$(5MVsKLfYi;0(9A|S*Xgs)8{HHHBx(4b9K%}<YH z7l)k4YS1P)h}?)vWSn_Bu}2&lK~!i^ae?w#j2$x4m>^aV3Zl`5tio7>;V}VuNf{R) z$JB^*uqI4~voT@Pj<uLnXYnFE#Bu5j=&CcLh+t(2=7-RnAYEIacG7rnr9{rUc<XV4 zafT=$K@N|eyR~>@FcG@Q;@etoGr9Y6?D&ZT&S6JTF4ELPKycHFjL9nmK}17KQog#{ zSb-oTWH`w}FJRJTGeGV;G)}_oVWGf%kv>x-LQ2ZjAzA`z@uN>1-7#0w^+KOxiV_Hr zyf}$KkEu<rczGsZ@=Sn3@1E^WPlFH_91+NB)=l161veIsILRe~HqSTeBnZgGawNWo z1Gjm;J&=R~Q=yyqx(O)4_3PJVi45YP2}pyi^<1JAhl$KR{HzNlli++)zb-*Bwt*U) z|6Z86AnOvC6ktEdLK!awr@Y5c9uaVW08D7QBF_=WYuBzz?RiMF)MmCNGM}>W;)|wE zU4rd7V%L__3J&-ghzMwq;Igl-)PyJq%`jyll-2)c$j;E73^5f3x<bLAoFdlb1)6YD z+n^LDZG>Q{3nTn;{KgVL<W|NpZ4mvujSvj)31cFsCpR!}h7-gqw8#iroYp`bq2tVz zS%~uxfpzK(gb(xJKoem}-{?^1+c{{0Y4u06ZX?VQ^3=HqAzXk<7Z15CGlUD5R;Hy4 zYVQtYJ{yzyEa-a(lWJgiOylaMJP+1MS|ILA`lWzNnC`N}D>Zlh;NmsmT5yq)jSxA} zM${>6ZaRq&4Y{t|ff4M?B`-y~2?B#sE)kZ1fFEWs??#@tbEM$F`i|iiCe_T5GKHy7 zYx18xudir3*7_W#SC11fU5;EFcQ|lzTxXyz6L*4kb)}LLv~$QRq5tfnQAah!c7s^8 z?#GT+S^VclBdh~3>Ed4O#iBcPwT?#_Bk%3)DYZ%(XeM{E0g6mE7S`ysPxtFxmxdn4 zx?2x=O2vqx26|a)Xe+C3{}o{bPZnp87R{~j@|DZHZr-|Ox@gSdm%scK){l?1>({RO zzZ42&6@ZGXpoN|gAY`;gf@U!&$u+{ojhQ~P6InZ4C#0KMBX@A_W<*O_i#^c3#^0f| zNdZZkZg$3~*CpqGBMWQZJt%lCaq4*@tash$6UJK!W#V*jZ6K^JD-fi}ewBhXF66Y) z#4C<1s6T@uSKP%Agyoo)FJ)*Bf^b4^bcA^e8GBn(MyjHTi6&MpQ;@ts58^~<=F}Yr zdT8_3x)Van=|&Jl;1n}QYsPfeLfif36Eb@sS|UddEnZOub=fTD6WS%?WlCf+jUX9* zV>lJmtjn5E$p|9!%+SXx-C%f6>)S|4A;$|-oP=tn)>e-U;Z)G^E|DNX1_J4JOcll@ z${-w=mjPr}LbvB3)Zi{7S;9$VAS-~CkTycsbG|iR1ago#z$J(k6Ua>3M(eYtFu5(z zz7Ur{oVjLVF9v&_-=-i0xKKZJF2WMOp-%1GDo%<w)#+*x2nO5p+$f*Yn2MUfD94o6 zthzV2S9v|lTZ+2{<H6H|ORmR7BJRRk5%A*FN=Z8}K|PUeKW!yjTg&yXTeq?CyuvZJ zr6_R{jaNA0BppF6N`>j7=?0x0I%Dcg8B$0cFDcNNXwbN8lNT8$`UVpYYx@S`kK_d= zn#`CAJppJ%+u7L>0W&o#j8YKumU?*6C?>(li5xwFi$$><U2Tt@Qle|uu3fou#XB}! zzI>VK?YG~)ckdqe#83SMT@W+w(Q82*mFM`Ckw!Wiax}n8OfDIwp^?48imAfLOqug! zA*3sh6v~SRKcPYsoF)?m^hd`vSLRTgQHN|4gw(H%rj#r7iGfP8Z%s(z8weVLF7g;_ zX;#;!FGiCC*16E}RV(bu+Imh{U5Siknn_$uz3-m3n!}^I5CjRx!~24Znh8>sZaAtX zXj=~vF6?&X3sXRQ0Zt=x9ywEl+2jcGRy}1Hh*wZPv+>p}516hH;*ubM6CsE@;LkOQ zMu;+T=52(Q8*^*B!+GWsLSAx-7iB=s>PO!##M)^7i;&S>fY}Su99%kGy3vpKms4ck zpyzXri8K&RV!~Vrtrsf75)yyO9nys*lWyaTb*(;!wCSCR2VQZVhh}DN)mcyA>=0pk z?pi$d<bC=HvjVh`t}`%OE@5e`6i^231@yLPIS==st<f(bLz}1z&}3*M=NYth-VUMG zXd$1Pa?FmUn<iX^E>htgYv9NhQze|~uUx(?hk+<s2xNMir%w;+@*AVeSW*d1r92CX zB_EXujx}n&R2yu4tqN0BJszyAI>0x#)(;MzdclSiDKb=?@$H%U<}5cLuf8w6^b*-C zs2jZ+%4adyK;<KN9Te_3nPIR4R@c}3v)1l>{)r<Uf=N*8vx8?xhez%W8|(FO>n1HI ztI;}raHPp8{mD;$(qP_w_ubEa?sJ0JA-8Ye{*_<-wW)%ShqY_h>TA!H`0VLf3pkq{ z2*)jro}e;H1cEyX<=incLJM<*rWGe$ZDdn9cMr(&5^zj(G&li%?UZq{E5;oZ!qMV~ zK(<2KAdW!L6&WAWjSL7(v67Prgr$iiRK$f>VnPd$r;WG-lVO1<g*AlKnP`pBI#-bF zFn=1DY$F0wl#PT6fi*(wJ4mIRVO(0%ly(bws>^XkR)6NFuC@gdHb86Nq75rqB~ixO zZS+g^=<?OhX<DG1gEgj31TjIZEhhqy4Jrc13+vR4GA(k;ZROb8HJ}e6`zLax93acv zH0~xgFt_wUMie>gp1ey)%*Y|&x8o9Cq>uX?BkJk81mx(|6HPL9Va7}DnS>F3dc)yJ z6GE(zn4twx!jc|3EKI6_1SG^o8$>y8F9cISo;+u%>F3=!;&mRW6CsYe0cGZa94kTb zndcA^mdQEcwXWP2qb6i0<b^HYNbIHY!Gi}*&V#2<>%J1|VxDa(w;4CQgryYMHj`18 zl?Fs3CpacP8g~MXla^8(r&eNOf~26EXaPd3z%fehIDKw=^I;V^nq;JOi|H){9Ld_$ znK%s^B}G36jj-yEtVPyUfSA&my@wAUUcGuX-{mV~YA_aMXn7$6!R<L#aS~Gybw;Dj z-cHxVLMq2ekpAMjQBZowuw=3bi^<VcuxgQ6ak9Rk0E83|Q7RGvc+~=oH+dY<@D-3R zSY)uN5SSE@Xj;*FI80jD+1WL9-qqtJa%Peyi%!FZZyd+sPn#hT0$vEhf>4klJUgh` zQdLhizAk}Fgeb+_+O99P#2pZls~^;8fGJ~KTdzA5edQY8-9Qj6O3Zod`Rv#W@FHDk zK{#_1e;|ZOI}m-#5$2dH&%0lUa6$${)*1^C1RPb@E=}-x8w|e!nLfxc8&M*N6PNNF zXj3br39RpVB_s~St6Qd_o-`rDoHoZ~K06%kq@C#-P3V>;%GS)=IcUx+=jgdwLVw5H z5|Vc*`@pDaU{Vb9yd^9oW7?S7W!OvErl9rbk!=$>G!Q)c^N}0TK;+iA*6aaoDs-UP zS~&`I(dhe{>g?J$I-@G<0zG^}lYvlI_4t-)dcvR=qMthFAaC3o>5iy{R<@k7Yit9P zy!Zk~x=nEKW_0P2$Fa1&Q6It94D{inatF1uZj7vkIf!-Cn*`?%U!c#32q}IJ0V!A4 zOlG~2kDRWZiZ+V6<UU~t&fqePFI8`DZK%PmiIpjfm0^nHej)plCr{GSyXoK%D%@h2 z5ciC99w#v1Dr{tD$^he%vt4|8LXCNpo;wJoQJWbFo{XOrx_<Kp$G6{o=To2h6fbm> z{A<7Vw-WGUV(rHDYid%TR(b_xYy@qT(SzJs6&j{!(2P9QhlvnhVIyCN`MgI%upzYc zJ)zNqXpQK#kO*3OE<j+V35Qh~gxXlcS2ts6FUod_7deQ_C}G-RgruO472+7q;1;3; zxiACda8f{uvC;%g#bjs1F_A0lY@)~!8hpD3h^&<^j@{C0Q%0Z*ticFy2E}>7C%`Jt z^A<-MT|2>8o*&lNAjWVDWWW!k%XlfXUNkX<)-8<c&WtzRSmT})l-ZEFS<`@KX<Ug3 z^je&bpejh55P)XTr%!Gn`pB5lwG2!m03iV(n#i_dlR@fqwJ9E2K(1jd5E=+>8nq)v zAy!~rA`|A_CA>&4c#v*lDhWTJ)J6}Ot(>=D)QN+Z*#@B^(>EcUc(o9e&p^5%chVrH zK+FhnnLEyfC9g(>8(4A&%1QcZkWvE?bYWzuM+fm0OeScVC__lgi^=>IZ55{!msU>d z1F^Mw$ne^R=|1=P@nct_*I+xuV}%*#nH|L+haSPrI9rjgSdp19J6+aD%j#m+lJNy$ zO>GGqCJotL*4-3MHymvOCK`E3Nk|(Za_SUHn{$Rfc}+r37a+6Zr+!dskaXd2Q58;V zLu2KLM(L&0`?hH@hfMFi_nv`pVZ|2#C!uK4rKb@}5RSS^<w7~CsQ8p=aRf{y$Tx4^ z)av3#DWIER;*f>q$VD8!dBCDf4T%qwfZ%|tkCGoh&TDoGYg1B_1<#X>Tx97Yhu<y% z*&^WBUEDKK8NQJcgjFOVO8k}88hbP%lT)o$3Ne#NHySV4x%Jy%+Pt^(Ra*~X)K!A) zHheNlEk1G;IvhI-az!8TK-L;w#)2l4mU8vP?Tu|}PgX7+9ZxU7FponPXAT-j(h!37 z4MIkU(3%MGjpnC<A<TV8s)BmbU25r5YBVWQknBtd4H7np20B!fX>}pK7KJ8qqnYR1 z2rbXS@w{nXA;hYkE9VHIiWrCzrv9SrE_gC8aG`Pzj+1m2FZu+y#&fpj=#P%;8p+Zu zVZ=Kvcn<nGA;l0{34>Ue`ez~IBrOo~l0Hi4iE7Z;Kh`}0@~FB-mzKr_>!7I1cHy3p zCNd@2Rh;Xcru+xUVnXT(IYB~*DM;$b;arHWFi4la<!&2sYz)mb)x%!fAV?Qd4~+^5 zYxP6J%=PK6e`LpNwa%XLY4FzO=I-{+*2X4{BWP#0zUkMD^`w~@hri=)gfCDg{`k&l z5+<R(hs8A1|6RJYJ>E9Aw#L^JS1(<;TE7^=VjVuO`?U!NGmj~b6nF02AzvH6aU;K$ z;?}KOTC|FMb}HhPb6B+0NvK0$rM}h)IS}T^k!~Qo2$k0qotzlH0UsR~->8LpepKII zeemqy#*G{9{VGx7jhi>$|KNka^LPGk#roJ-yLt15rBbwf(`+ur5PgxxEysF*qR|3f zH!W5i-4Sq_AOc^=hK?!dt`uYh5ilc*NtQYVpd}Y!#48N%scVYK^NeHx`L-7!DUj(y z0D4M^AVGi-kP{&;T_?1O%&KjE!Uh#(aJ0z+?H;D*t&Wgr>Bc>Jh)b8z?u|rleuJJ@ zy9e}PrlnyO5SkFo0#3@gBdC@a!Ny1~vU&DoQrmxkem*XOHd{QVk@MpCDLZm21Kq?- z7cHZxOta%V?v-E>Co+&zyda6w^FW9mE#0_?Ozv*`0vQm<2v*7%b2Pvx>J&5`0U|@5 z|5}M=ip*h@x@`hVwMA1oW>)Pyk?x#uAx6lLLTCy55qVqFZG=o(+@Y;x0#gXl2jw|H z?g9ecpuN(Ci7~J=Z^060-aT&$Mio=R(Wg!KJW|z#Xu=Z5DvK6<b4(6XlmyB#b(F-Z z9(v2+gtq0pypf@%czm*2ffRXCFTiy*F0Mz8;QX;gMd<61aP{g{ZwQWJG7d6RfD8$u zi;!GWSE9v?v3kD}+&w#qn5v*rQZj-;rP^F9GJ4@mG++%s#kkkth|E0!wSs6Vqu~<Y z#HXC=B@%&<mNG%KOryF2Iehwjbx-O?j~>ya5+!+zV5QN;7ldPyX5JDc@s*cv9*$mD zOJ?%G@$lh8CIn=U1&KiBj$j%Afl^YbQ!qqGYpR81MfMUX4tFVd37Fv!Fv+sh8;h<1 z(&tP5l)ws!9FUKXPH>QA5!{@}MGxZejVzR;X!T=8<0cN#Ydc!d^$f2~UR-Qo%6v06 zGAkvGlF-OnV==pwiI&mHt2K5SKm(@8t83H#6hZxJCa|WwdN5toQ*B-Vm={+f%qyRx z(k#w_@}0Gf;+=~yHw7<BF-N>$R98DBUXykaFcTGhx6u56UXX5qG8_@YOc%lrYJL`& zR0C)cqL0_`o|3jEZJ4bYt`l0>(9O<_H3(;3e=8yL00_}AL6}P|v||wE)VT;RvgQMW z^T@n)mUcfrseL%l9@D(kIWnB^(?(AS=1Pe2Jm&kPX?z>eEKM(@+j`eg<jFjO2<}32 zP%ybXfj}AH#23g>y6T7bR6jn103qinXiXg33gmd5$8cI6pf;xN7HL6?<2h9Pxm8t? zItjJ$rOa_!a=syXyu>=_Oa+daaTaCj#+g<~s4G|Ndu@y>0}(-&Owb1OleD(Fa%p|s zN~>oiML#himv+Ysnit@*t<;;X16J7mz3G=kk`q$_@c8j#w_qi`^Ugc&dhfpbE?Jw~ zlZ<JTT1>u%U?9oO3WTQz^*WH?QAXg{UVxzM;AYw$-|K{TTyO71^-riLdwX|YzW0ew ze8O#58E%4azy0>#|NH-A1^w7qyLGF6yH|=+3J`Roj6Oq!8rb-5XUG(Q!RJ<Lz`%t` z7sy%Zny>}BD+PC3M4NQRPY6OA847WsjGW*=NNt1^5YF+@rL|SlS{tvv6@6_T_wf1A z_{yA}Q2)j=p+KUoxM7bxwS=;ZEK7F@Hm)`)m};pO%#edz<UmG<b&k1GD6`jc4SP0l zLdYZVG!=vpx&@p(6hbrsLaGfqCOJZ&YXWQgFTU@0i9pFaLbnlYVnX&na*;j0cp3?z z$tgf0G|CiXy!7Ul(98&Fv$EaoHty-B{y;aH3<nJd+7uuJEyo?dm0i-XmogfhfO5pH zi$$(<vyR9K=z57p3nnM6ZJ(GGdLS|FpJbuop0J4)fhlbSNbq#yC5|p-DrrYuCf%PL z9U&kG3ezU0mT8nfeT(UN#Ea0?hTr-YGCxK^jy^3U%P8cu5>_#z3?{<@^B@!B+=EVo zX_5v)hRj1F%Bgb^USyS*sYd}(8gKRnp~udec1+cLztsfhnF;7E$9U~pcZ1m8-m>!f z7?a)(v>}d<4!a<Hh%Bs7GG^oDEy!*1{{8#ze`F<5;#c(Xg5hc<P~u0<q6-yHVhS#- z2uXxY2}zydK$wJRyvXqqM61h`Z7dEAIp+)ltGrB!Tsa1G5psQjupApIq{QLt?8=<; z!pAf^qo((al2MyRx!iX>8BofOsmL2Q>I=t!BfB8l<PwbxOkIzO5;kKLSxg#MtruWI z-l*e+fXR`N^6)`$1&7u^(_X!LRbe2YYOi0vZV?F?AP!#<1Q!_;Lr%4<G-Pq+^(S)p zmdHjj8_}DknBvY$UUN&(Dg%p23Q2V-6Bapw7E*&a9>@qLHuI2g;LofYf|j*qF>?uU z6d5u!8orc0OhRyUY!bLw3%9EJD#7vLa}NO&^}tw<r>E`sSz!OB(<w-tq?jZ6Il|F` zZa9Nmh;<N8O;LUX5-P~hg6xOZYb)zO^yk|M=P|j>YCg}563}!*h7?1fB!n4Gc2P|2 z)op~98|V3fZ4gt?1o~*^pa=X$D}!{G+Bw?mMW`qj!82!kmyp?rqb?!(B+372Gnrca zD5GiUjy#1~kg3$UK91?0$8ai4{n?17{)_{uzpZl`nKguH$PP?fl%tE(Ip8`CO`B+d zNmge{?QUdD=YVd)#uPp1c98O4%u>iN!rU5}OS+Bdo0+g3pBOz<X8~O&A=r>wC$LeI zuUy_8ANJZ9Yu@zy+uYb(Ut1S$duw~AKK$IQU*fU4wza9h;|18f<wnqZTcVt$G)YG@ z48|^4z2=O<RDHt0=w{6Bd@R-RkwewdE$oxWdwj*QBH9F`agPI)yM17i5i*=9*J8YJ zoUgBz%*4^*xn)$_J2)ALHHxDMWR6Z@!sc4tAj-6u(vwTmvnw`J<y%{Q`Q?`h<}-J$ zzx}uWPRJh<(+hAV8~3Wrg1L$iQqA4i2WVLmrg#~fo0i*^ai(ZA){K)^=B1*{5CW?< zgBM3v5W^EBgdpw_(grE1H-v6aG#Qr?Az7MWjC|=s16>49lbwrF8-19B)Y%JZPoR+@ z{J1B6P|+7xd(T5O<|@^CQelcO5Oe{jD*^g&@=TDJ+J<OhLPABxPj?9&8FU5Dh89Y9 zG7N-?l5S(6uOSmSayLu#Hn#`yN;4uSctAGlRD}tYE;BA8>J&CDuwq6tH)U}lDRf8p z>F+QR%%PU7FzK2f&<Cu#ao0wZ6ognQwUoNUX+m=#+XF|gj7~I#5o-Jck<&`Yy+Ii~ zdGf@$U^c`YPSdnEKV@heBmY#Vq=9*u>*EL=a0&Dy|1vCA6SOpGrATURG*#>31(;^3 zZDtFpGXdu`5lo=vqlq%sfIcn|6Bm%0K8Q64C-P(-rE-aK39OSe5I!UhOooBzr_NbO zF-d2E&#Pu?6dVm$-<&PxWbWJiCgWt#@{cEW#<lgejm?d%jrGl)?Op%O;jLS@9zTAv zv$Or=$=>?fs<Vc_;1YpptO{0F^MPB17<<OXW2OB5_rIU1_D+~j7jbkI;K*{p+NG3k zbsSZm-x!(VtGLCP+3Uqon*!*`QDTadMc2B+W$Ed)f{c2nFN`V=1W8_e_lx-y;ZOo! z0U;?M@txaRL5#}~RE_{fB%rrkW7p=#fW`drkAIwZ{=D?^m72zrM6T0h0om0l6ppHB z$SH$HaQqCJRo5h_iY&6O6p5gvNx{fyc?zMCH|Gp6^`NxsF%~J3T45i4_~Co+y~mdZ zM+8~os0>yEp%habqZT>7Km(YWe=A~xiSMZ>L*N^0Xd-7vwR^s$6PXDJnHHQx(1I?j z_WAQ?9ta;jdc3o{b@=?~{SV&t3i06K{jJUI!=q=m`s!MJ6T|bvgZhg0di}Oii3}$J z$%btB=7DC+(3z|3==rgy&r8Rb)b;G?v#0w{Wf3;->BsdI@Y%oes2AYWsqJVP)Epz# z>1iJqG$5P3(3XIiHUjjVya*vfDoI9D+DdJh^H8z2%&WU-jdY`j;Z#@}FO5Wm_6lu| zL7Wg8@X}7&S+3?slL$d8gJ`msf>_hehaa4`hCnmNoCz6SqrF~)_@2l3^yLC%KI1hH zzFNytP(Z4UkWGFbOuR<Pr=cj*UD89k=Mih<<`CvC;RvpE6^9U01TCwf<t&OjgacO1 ziQz1AO0eeA2p{6^N`dTW-E40r0daC2%_DOMvX-6(A3{jj^I)oiMyMe2T;FYk5$`Mv zs9Gn*>dDGU$?BJSb#-fFV`sc&u5YgGZf{+_dU<Pm)0uwn&fVjaL-(9#&!4&n?q1%$ zyn97^{o0KiH?Lj0dfmCVvEki!<I3f$*RNftdVY9hkPhF=?oAG1GvZNsYs=KsYptBh zGwLexQhmnfKQ)xnF~?Fr%Q0?#b?-Kd&z>K8^WNU{uw6f$B;Mv`zG_*I<u#g`?PJdj z?rb-2-u&Q$`yS&xMYxSykTDrGC1ZW63MoBZSV@(OV;$ThRJyx+dFS$uL0r9h*~WG- z@9)*Su6dGFJC5t;$`H_-f4)Qe=-3(ULXcwRkbHcyvVO^In3MY|x#ERl_44kvdR~6{ z?l1rHua5QkxLA4R<-0YSv2XMZ5wfLHF2ovw4H}LvJ;7kW_(#CgOAd7Nykh$%4o%#9 z*QOgG?xL|GbD=S(lIAP!$%ToQswm@?2)aOUz0pJ&MDI55+Q@T{2q}y^bUHQT=t8o< zQZ%N#10&N5t91hwa8B-ew5EuaknCg{FFcq@G0%mj1_W1=u1BJ=x29)D?wJa-I3h<F z0ctA;<cuN#wPYH;;siL8G$PNt_&}NUB`mcOL`yg6w27Zk+7?7>Jr_uP555rwx2&oa zB=UJ=q-k~I3l3RckYO^JH_#=AL#P}B=?1!!^kTV7nzvvZNRjO{&t()L%+W~+A_N(W z2vTJ121S$k?0E}9rjd8vg#_oG?s;@}h@<xW{$bU+^axS5b+}#(E{1@qfSeWCw1i&Y zj3^rW3KKFwAVjZ?2~)siCkL$IryiPgfu{MfrUhPc7d8aSc?w%)IGsk&wxbqw+X}i& z-3CT&N&(GS44I=u*^_hrQacAtwo?#7YH&68W&_8acQ$85{&Zd(%`}?9tsEb@1zo>- z`Tl*kw9D_l`!3p}NA;H&)z6EIHzH$q`OrAW-2W_J3TDkV$RUvRtqR6@q6=Oc)xbB* zyv~tv#Kg~L5P`<s_s*R=G>$bJm|hk^w3)FWa~t4@sh+$XifL030CNns_69<#BGX3$ zWG*74j5tDq^F_!hkqTu&Ga{fDL3uJ_D%kv>rM$#PRztGzr8m9WyfISl?>}J`L2LLp z;#mv1%6)ucEfMe)<{eMVlp<r*%FA5=w{PG6!4H05nUYjH3Yl(>TnLf5D4wixV<8}$ zio^#3WwKxr0?L>`5CwScynFZVkAM7Q<8tS^b?cV;O=-d!U8aSs4pYZ!9%yV%p}6O! z3F6bMWEypyb=00*MRUfAw!O9G5Kx8+*&U=sbjorx3GJJJASMlyLCKD$HhI_AHdl`7 z(dBS_Zj5mM!H4Q+IyfBHyC}BwO3ggrnC~$M%P=Bsa+Tw7jX=p)YC;H*qmR(adCN;X z7g`VHut2)v$7+}vJ2_j3Z0)pU8VjKXE|jJnC|#%GWYH5UK`1NztdbzzSm!M;LEKxf zD{_!-5JK`o2g%M1bQ2SBwBbzV0i%v`3E8&@ORX75K+tWdL>pyWwMymK^ONG~X(F(u z{w9Z(Zdw{wgf>=f3*z7`f$2racoU&P!>i>Wq2}{B$BX_hajX%#1?NwMC8!4{GtlIu zj(i?UviIC&0vD!zXdavf4<0;lRc6LqmB30)Ko|iES+8X5)M<kyO)m`)S`N~kw>>{a z9cVdv12+&Q)yD9AvNo>k6X(%MU5E8L=(1crK74-t=8etu4X0EcyBiz-r~mW+@elss z4_<qv{-*B3hmTyHChys^16wSc?!yo7dl9{I<uZ*O#K%0iBkW$eeEa6DuYKd|J6qd7 ze)k<Qwb!m(-Fv$KbZ`IJ;q&_YhDV2ME2|q@+m9dZIm#4i0#&&GxPE_?mumBNbo89k z*&x|VcW&RldE1TP$cy;Xr$>h;^}+MXx|effQT67=_S1tsGGBUc%7@Rrgs(n%ykEa_ z<kFfKRQkx5R*vy;o*f*DbM?yg%U5<b*0)YB9qm7>S0Nc?apt&1s114i(fj&3h(q29 z?DBL%Zf|eCeD~Jl$B(=cdkQd{&+GAKV|#ncj9tHe?cTkY@4a&G_N|w$Uc0invE_yR z|MGwPzt^gKY$&?^?gHfMrOJ{k7ous@b{HTJr-H5-k9$B4$e1m}F@j~OK<6+56j@BO zlYMW#6jM8IAi+~%f^%fm#!8=qU@U(nqK`7SJ#u0)*$p<FWxz=s5L284sgz^95rS~E zio`+I$|WW%IUpxgy2wt(j0*^<KNx|hS<;3h1sBHzO~?ewSVL~m0|8C(5ItI$$+F}H zojq8h5t27u&<&>kfUXKtWS5aPLd(IDri&LLrjI~|78l@d<}>-aJy>!k%5sk+rv-;I zCkGh<{a`Jl$xCgrgDwvDtg=uv;WVO2B1o5>BOxgwM?dcdQGyid&XtfLe<?<=aug?; zfP0|4X<##S%`ow17huMo;nReZ=g|%xPM({|Oo<$FLV@m>q3QW4ngnUkKrZJ-D#ULg zXqP1I$Wa0zE|G)y0(r?~6kV-uOj<#rkK8WFsN0&ziO`4=IsC@VWR#wFZTRYqv&{^w zKYe;YxN+m=ty{Of7b(H{_N=}zx3;rgf5g?Zh}H{?^7wGJG-9R8B`;}iT6KdQ8#pk- zd>urTz!9HD%gT!^4!ssxKxBHLj8~K*<Cr>nUXtP)8ciYysO=%c2OoSuW(8zPMH5Fr z2q*lwhl!?5@d2-<&D%skR_$=DCkZd8Qsl&z1yf4~WeW>@fxtyNWU}dne0Ps`U6bkE zFo{@`iwCO|lt!R10*%O0KRu|QWu-|m1l>5^xN$?|d`9hc6j@c|uFwqU%1Tx7P1%$* zvd}aTAY;jl1-h&PLe??B(F&EBK|{{CbPa^CH+~iuK{2e^V@xS5=>l?vs!x7g9pW%m zys^DkY+m=tv2pz8WT;jg0r_&2B|)UFtv-JBTC(ubtrb762e*^M`V9Ee$;$J?ql2gQ zw_13UPdvw20wX;c|Henf8T)x8V}R434`NbM<|N%0f#Z@8jF8KkNg8s792jOR3A!mm z8$#=|G~^)GK(!I*YZwDuK4J*r!_;47jG&DbqKPssWC$HU%m$jaP1<N$xdd@K@*M32 z$rZUL4I&hK5htNy4Z??5Azh}ljdbVy2+-E^2;n?>ewJ|FC2?Tt56tTPsC8Uw!Qw<% z0>XSmu;jP|TMlw8m=iQ3(t?XLr)x~Y&L<yQfVtdAv<T43Ml>*&A>Fg>3+D%LB!Y=- zelBgSovf;fVpwaXR#)nGIyeR0aqr%_^XjXw82QVu+<pK3_xAVd_d#C2eq(&T`t-qr z4;|9Z+M73T8GFt;r>V=(ja0y$o!!g3yN@0{`rdcHTOa<_+w#iJc75ZOgjLf?-3@7A zYjgAF&6^wRo6hb{4?-)`m!}0(o|$t?abiocyL;LF#bLX>xsw@{TIBJCL03wB`Rw3n z-9E-)>(!%fd=6&0tWq7Phq-XZX<uKdtg?Bnu8h0wYF@hzZ{5DNyDO<1joU;$>1hv- zo(pAwZb5Zik6Y`Q-Ievt)xG__gJ%c!!O`*bRcwj!W&O*Scdz)*!^wtciA&61`P)CE zUxIb*>J{n7;x1Nqz&$cub=2I<Hf7}IN0TlPOcq4YLO2P<1<eSfgapyX1cb4Er(b%X z6B3y|!6`+?#9^&v7|^Ah>jBfy0-Q=V0&3A3x(SkH(Cs!*8(Q+}#-tmUm=Z_ugo=_z z8F`GL93z;fZUmm@)3%P>t%BY4<&8$Dq|gOHTB$3t_*`^VnAuJ)f-WJBOXz@IPe312 zN(B+Lv9=~kK-R|8oU}nRgH#@`m`1{>m|zem;IL+NOuDtY<FR<|NQfr$50r5aOhuR- zHV~OI{5S@KTR@(-@oG(&T1uKI(+1(!wpeV!41Y2YaxnGJx;N(APuqFZJ&z_gqEDPT z1o;T0>^U>_=UZwsdzK^nJcDJ;TEqn>5C=y<ocP8{A7%7W(nQu)-3v4mbP?o&934=Z zMpfZ3#gQh6KFWYHzJV@fIBn{4EXr~lAcsSa3z??pZK;j50u6yn=A^CBlYuqkrHK+5 zXwZ_vYrw;Y59@2mCnwgxJ@3*<eG4(Z+nAFfCl~^a*`PE(9JOTUkAQg@BaA#%6+)FV zHa2Ta+{agW>vs#8kkpo#=AR3WuyG_X37dd@4o9z>ER}Ce2z^Y_Eo~>j2{~ODey1}( z2Yo*1R-~9A$PVTq8bBk*G=dd$rKUj`9tFzqLk>aLJcyu%Y!4dm?9pI~l+ut9%+m8i zlYdm-gI1Xx*V7M)RE|X!zJP3sjN*qs{NdNW_BG3dfUN!m<S!<TVlbuVrQ1V}p3I~R zRmw=A%@80Oz9~ClxxD-CyEwX9&u3b&G)WD}9KBy^b$KyaIKJehPykJ`&==}kMK;#! z`E6>~RyWqx*E|$4)~`^7`pm&DUhxWS{}>cd3n&iR%8ID~-HNjq%lg`er$*yv63y~^ zj`WnLTdn0D+lM*zgUUu(AB8GuwoxO{$PP&@;M@xFiiXh22*IE%YtqgUQ<XdBJeow7 zH=2N^=cjxICfl&mM~M3fS;CyZg!n?banX%q(AJ*VC?T^1=|(@P#?{@-@?U@{%JT>z zj%k5D0ikJHgziQY0p`99^DsqOtSpe{<OqS;o}_`cj$l(sk%Nx21STzO5G6!E#|Tp( zPwX@NkJ``i3L>j6-6b@$gICIP#WY-otjO7rCM_4Hx0=iVlevnOK6j<?wNsQ?x(J<7 zK=OIS8sU7q1WGSvQ|BBQd%dC|t*)%A!)xGzP#o3Wy?fUI?liu6^M)htd*A!s_SV+! z&Xu=+{Ek!k_@sUrf!7*ummBq49k(ApsXujl`SR7v_2(PvVBFZ)Lj3*@e(+!a;16DY z<(1ET_Onk94!i>1dFjq?|MqWtA*|c(%Jef$mv?q|>IZJUuZ{0GdtP5gte-AkuTSu6 z5|2(CnO+^YHr;3I&qEO0p04a($qZ)#EdiOJ8zG0ML21d#s_=`S(yI7l?JDWw&eEZt zKYzCWbpODc^mrtw`&-=yGj)93mFjzQo*wLbCHBs&-s6+{Y6w~~LiUN5|1l@^ixo|g z7D2k-_*uOGU%h%o#6a~86&POT2#+S5bX%hhC-R`2fjG!G+2xpM@#;81<S1D~pb>;1 z&R|VRVGxUOzN85Ba}yA<a)O&{C6VnX+d`MMT?W1QIP-2JdWfk(BSP1o8Avh7NVe}S zWF8;U=8la#F*JA~Yv*-BOx(5Pgld%MC^cS*AftUujujFon9FlyIFQIm3Uf`AX~QQB zr&APlfppV$-eD=F2oO2?v_TDi;gT874oTkB5GzC<7jnpEKx<}bqSQ_fiy3Y?LL<z1 zJBmG>qE3-+^w2Uw&}9d)(gf)?=9*N+CCWCPuXc{5nB7er^=O0WmyqCEOl^0Ev7&ha z7AjXqPA*Kcd4}jaOXN(Ht~dy(gghwA)y_3!?uo{+%SfDLbgk)%35gjO-3Z}pEA-+) zhd|jt4k0FpSAxv-b09=OZX{!r-9pMM#?UAuh*BGYNra?pC7KB|)r6N{e%U>eoPZ7) zD{^^v=h35w^$UO&hcK@UDnEijb|z$j+?ha-<jNjq!lB74D9EMT{Oi}RGs&A9mAomE zDH+M}0yKm~kk>s@i%%&RC7HmBZ`{S_PIjB@J7qG86LRw*1=DmK8d(G%B^1ao=!I5h zmf|RBg3z-{3WQb?BFB{O!-o&alrp-xC{i#5FxA}E6F~U_no*dse5jilP(TxaoGvns zc5knKg~{W`k8j_u&-ra~^PH&|9yQg%f&wHp94$RxAY_2il*2;M)&Pb}ml35DhVbog ze_J~GYuBzR!|3Fi2N?rg=T_~Q!<hJ5XugS-_>`ILwfYvsn#|Fw=eEHq+SuK;PL0mo zSFB5`o}8F)L<5O{kV!y~5U8u7dF+Ih+RXd;=;_i)zWbcAq7GF2?wrGmEL}sq8=1pE zcap}mXj?NkL3v)J3FL|}+0G)78(~7^_%7*#3mto0=Mlox8SYCFAOw1g6%9}dYhAjS zpu#PHuWfxteo;Lkhc<7MVh+k!BhQsV99!Q4eMT|YK;$LN*FA{Wi|U!r&m1Ahl5Pv_ z*cibkWz!lmPtsY;<Fs6XUbyVjs3RA1cttpmJ_H7RN?~#wT+TXYmothc*D}GiIl>oo z(>CVa#P9iRO_1(S(oVvQUx1~^UQM?grekQeeqBHzuRkTPt=I375>o5H^d|g;FMR%g z_#b}jfBK*P4?q9&pLNJzxpMVRp}up+Xg>3q&%FHdE1&w*r|#apXDV1<8TitdzVw^F z`J4Cd-4o~MfBxq=dX;?j)mNQb<lXK1h56=o1iZ4fv3dR4m93h~&FL3xjlcSqqg9<= zIGl$Lx!v7*?=Z<5YtwIhP%~z>Uyn5BCuG#U7IRY_tmBtp(F?)^1fh<O58r+Ny{Av> zj}gd~BV7a_i=^wVm@kcz-ND=(=mj(cL(aRdDWXY{y6$}jo2tI_mETOjkBPNw*XoAa zkSQ>#s(N<g9OJEOq6vi1g}HCbm0&z8@B-0jVkLyrNDAcSr7={~P0nKk0>m-26cbIX zZE9vr<nZlCOVS7v&~W%BU}V;GV@*5nf(n%#nZSi9ZIp>`2uT+jjmYY$a5HpvTL&3> z-n4d1a)pDO_>{Vd+ysu2>JlJUEm<YzcEp%6cHZPVkK|fH^jbAcs<X944w|WrX-=3& z0OXW?o<HpMI2EtVe`tzlswp^oV3C92dZsFfDYCpEPRKNKK2vv>taJVnLRdohfv$`o zeyk9ET4+-=>88|HYFkf!5fILUzGh+UrO+T<$Rr1$rP`#!)J9LXb+da%;M0AWE{xb! zDmadFqTyRpWG3WrC?Q!!@;V>r=W&30_QTYl5d`OwICFw-gfL;0KV3@6sBMHC4Ekhs zUZ=3Qw-uTkCLx??E^L8IXh2ryg{J5;3ag_GBUOg3HtQ9Qx0LtaeRp?f$9*TWVb0BS zrd?RR^Fu7~V$88mA)rJ{8((vdkeT;7ByvE*H{V2^6xyU9h`=2odi-Rebi>OAV1h&o zn1pozBHK<m8Mve*<Zc6m5o6MeKm#{!+%WtMnMvO0X#!z^6$mnhFy>&I^KK(V9%<{x zr!xxAF78>TQA{@-YclTrW^dZ<aWR|`rerlff9^Twsec{|y6jj}l}X6gEI$3|PmAxd z;L)Q;k`iz-UenSuBX!)fE0S7FOsK@O-377cZWUS_O&VWez1!csdDEagiwG_+npw&= zz??P`_TpW71fK3Yl!D`{IqM#7eL_1vn1x<tNX<nU7?l<dp4HY;4<$!TiKLE@TtE=& z>Hfjy#%3+y7%aUknE5LZ6?S~y<-a7-4$EJTs%c;v^<uL@2y#Y<DI5raFpQ@{FeuBK zw5c#k=r}OaPTkO=Nq20DGoSoJg%~hVA(QFx!JuNj5QzX}jy+PC3=30~4Uw7BPO1fl zQ=uz?n1ZG5dBm~XWN9y&nC8kkmgWbdw`Xja>?mD9Fm-zrb8=@{!g(e{zL4KIZ=FX7 zM%2>+A_T)QJ>i_k@S7Z4{>TrEPZ2&${c|u~CJK~9His@fw}yOyHFtjk6X1X;<w!_` z7X`1Zvt2ZAA?{12pk+cZ<kRjP;y8kG3RQ87vvjpS1};J(b?e}9i`m}Z8b7FV^>6%* zFaEv1_xFD5xBlLpJ1-xdtUTG<KRi0#+}hr~d}V!Ob9HU~&fR<Ub-7C`kDu&){|9fq z_x=YPn_Jhe-`Kgl^V|RFceZzT?!El-fBsLuYXV<??X|Ce{p+`H-}cgbd8fXp>UHq0 zxG%qa=iW=7``l+g`H9zFzIX5HmEEn4?e*1lH<JCwPwQK=FRgkbUSC^vQPpqA+}W{r zpFgWJ&;}lr*X3q_hUv64sGe1e;xx{afUcxD6T;VJO@ww~(rj+kueRFU^afjB0TIX2 z!&?2aFzdVGPUm_;cBc|`b*=6l0`jpdK$l|za&fb>XS6Bc*T4K5v3^XfT^}#NJ%Efs zo9!5xDIiDLdTlm$%F=}pC?N#VLJI-HfpilJXu_n)wu`%`iYBvC1|vqHeS^>jy$}v~ zdJxuaJ5$Vr2IM&6#3g!&W_X_pJ>C?FMy5=JAY?5o8mk3{3@V2yIb=vK;KGCtWE=v0 zl;O<D&;qh{45g4<DGvzgX6%WOQ1cer8Vv7KOxnSpR0FNlb{9JA66j;fxDq5totd9# z=7dZgFKsx;Tv~%OVpn;(mYazjCWw&vj53G`GCy-uWTuwqtsRx5WM!oI)I%Bl9IXj0 z!kpHL#%O90qi-Mt@tOymcb5=-I6=EFp-qjEZ9)dvgyB)>u7S_z*2y*O1zqkY-+^e} z&@w<>N(7T1ujC?7;$ZeXj7X<o%_UZowSX?>JO~W$LO6uE71E8q<%DWPkL+@eSGs9i zNc_wdIr{j{+X&%j2xJ=Q@lpl}0tu_D2Dgpu*vsSZE--mHF`o$9{k<obcXyv1)KA{J z?ICz;BAabq^O*R$Ok(QNLxLn1L7Um&E)l*Uo@x4pIS-5USzP>ZxX`l-_29t+dRgYH zMk8j`F@P3y7e8-(aWoJCGeybLm}?S05#-IwPr}lR18(Hu%#US}6TE}8AOiiIBON$r zR49wu%*k7Cz2!x*hrm%TU0HYu6<JAUZ-2igFf-s`fC(qQJr;RC_}~L%Z=n`Z*>a&t zs?CawRMRDvXzfm*kuj-505TJ13V_6kqZT0(l_lUVwE_&2kSPs6c@>>F920?clu%bX zL~pv>*=wJyO!a6n#gB___=y$__vuHO5Y(&&`jB~%vyPFyQ15JeQLm(;+k$)J2i-=u z($#+hk_L%$9%`PXvrw?M0uDqumqFOH9Y3165Ddx%nmH&FpPZ`FCFoM7JGezqq1J4q z8$DF?F-!4{5+R84JmQ!ZMyf)(5Ywbx?1A%`%mZ-@bXg-uh~`Cc!c35Pi(iHXD1*eI znY%;w3{5AB-cF0sC1BIq_8|xr&b)>5>)Y}YQqR<RF_t*zqb0?QqP^$^xZ|_{Bhn<F z$2>*P(u;tjwfBI)(F{8)T(h7{X|5nK1q4Fnn9Xgh>0T&=&@FvT^EMck^QKe6975&X zLrZYw)umK_OLc+(6>+qiTW(DC6~jAs?%ck8>(_t%*I#?>H6FkJ2Y+z?{)fhHq>d&` zcj}j3dP!G=H{N*Ti(mZWtFON5<re>wpL*ku{^*ZB@rh5MdFy-gQ=f7Z`TqC5|N85% zJLvFF#*YNshpcz+-t}($(%l<(?!3gk{)*E0!QkVg`hAU#zN%_-Ykeb+2W4_PdI7cy zviF2%Tr{>ip$0Z4N6n&moFGTfF+<Re0O3P=(%Bk9>X<iSt#AcjuMZ4dNgVU7(IfxL z_I7;*Kl2<gNotlTjg;WNlgm(?FaO5hp7MP>)F;3qjv@*pbqz+2$c+pm0z$|HT^OU9 zW<j@xyWnfnWzr3zi83w`<~4*s&b&7VVj|!ZM6*s1J(md4gl6tQx3<9I*RC)jo8pj7 zddQF(L=Gn)2V9tFvSu7bQ0I9*O*19cQp!b{0+!H@4%rl@%TY;O=xJa?J)Kq7nC43L zNL1klm@*;cOlgBMUTG1!4Kg8fO<aIHH?<O?On2VS5ly=jvX_EZE}>Rvc2GiSgf?Z8 zqo>KtgbAU|H85fqOt==Il@XfUnzR;+z&f9Q$Z|K@JwlfR;kOkCDbj>wXGVD*ah$vJ z8u6A90?b3vryBzKJm#fBwte_>7qV)zby;b&igAR+3h_#JjIRb5GNhXeD!#$oE3&qc z^@0&&Lii99&_t=7Yam$&v8D~sltidl15x5n{j+2suo9Rub!0)7rm+z|0>mBDBxrT3 zvVoZJb9}K<nra|0{oK#}+^t);+$zXI<-3M<>syTKH5kpileM^i|31Du8IH>&S4vtb z&~DtgkxGCbQ#vw2@`|sUq%@<1buTk+RN{j-v{znv<--p@3|TaSTWLaJ(hy<-LKd9> zg0}!U0ENvPJ{qNr0yYQeWdSDo&^X2f-X0AndP$kmdWDON@<0T|P|Ay-t>KM#^}y3x z6*rJ*f&h*p-+udT^84?<|AQa=zypecj}A{fgSrE(t*v`C^IW1*VXs}g#wv-%oCG2~ zeOljICb-DZiOj0(WVbMjXrT#$WL5)}Lxuo_L3+L!vf+>uhmiR}m@}CWGOi4SFHNRm z|Db+7Nq!nli~Z>FV-5tHMw@>X3xB*tBzVFmuU1$sP>Mh1Y@F36M~D1Qj#k!I>X*4} z)Q|htBh#hhBOCMh=uokP;GehFilsJ#HHwk6_U_1GMN<iaJFfQdsQz$qk%r$G&h!Z| zCn(?Hog&p1;XG39+?vsi0287Ny4y+u%=L327{m)SvPYm9#TLdCPESFQE+Nc-HOrlD zIEl=ZmL^u1n=V8+Y0;LL^obS|SogV0JE}8;a+_rgVJ-wq-NsUcr8uo@WN$a2VV1OG zdQPVrT#^wCWL&UyyU|sD^w4CGB0`iEXrT3@ic>`SlS8OUT3{*u5<cPu7^coV>~i=C ziJu%rUi^Cjy{0RZxrBVlY+SgxYAZ$-g;lpEWub?PHPGD_Ak2B&oD16}l=9>PJ&0xq zfRj>{SKUm|_ycP7F0AY^4eqywc6ImiCqMDJ&HbrQe$w0O2lwy)jbHku&wb(ZpZol0 z@7}w!<z;Vk<MNf=tJki6^IPBi@WF@oUcURQzxFGyzw!FU=K9X=&W)Ql|KUIUhdY<+ z(^_xQfBMIN{OsAm=GNxPrQ`kmCwu!(p6>6}IO<5hbnC{AS6_SO((2LHZhh*yvAKEu z=8fAg-QC#SJ~}@6{#!pVGJ!U?H&@qI#oXB1Ja~36{TA!7K*}aVCdVp}a}&&p#A@JL zO9qs+isK7vnI+`R&oHeVJbzZF_H<_v)(o4Wdhg|h!u0%k-2~kb-CZTAuPTg5Mo<;O z&D{fx%gs$6-08?8?dq5Q|M3D$ph~+K$)r?GjeGV9WUK^Ch}?)0=xbtTyF4*XL}-IP z30m<XUReWk;qGNFIs!z{veGL|KrIbl5k}7Gk&e=VW$to{#btl|Eea{{nc@z@rUp!) z9|<Q!2?!ZNnBt^(?L=KnV=8(4__3B!JHGf;-#W-DdxaZ_%W$1OX;F`Xrv{F3Y0zln z+w%YfVQGw7qD%-5Q)<wi=WQe!LR#qfi4bKpOl@s_l+d&#C_p>6BF_bd1ta9?1H>FO zhNfi&<D%rE$d;prxSI!Zr{E6O-DyP=eT81^PgZR!36X_uxm(~RK5NFV67#QZ0x%^} z%i%{O0;Jn<5(?BGS|iM+1@mYTUW8@>$Be6EHq1i`OBs=YoQ&b8V6E*+iJ)r_XP?uH zllj3<gaBVCR&C`QTQ_=fD&+u~NrYsC2+5T;1duTTFhQ6RMv|JeI7ZWiSapLCv}zzQ zWu!E5&xIf8Hqa1&J}&8I26X2w#7h>OxTpS@;tS-sILfqWG<F&gXuNQe-7QkE@@U?9 z`)&8p=g$t@LQJez;)f3(dUxUy8YDPa3+Jut!tt2HCp8O8Pml#LlN2F~m|>D-^q%Q} zrRfi%L&#+)*C#*uNlI3HF<Etms!|ryK8NvUHUvp+!qQ{*v@m7MflGVL-*oxMQT*Gt zZ+l%d1IE%NsljZRwBDs$2uvJ7kVF_Ei=geiTF@2HORqR89AEgaci@*^dP!dQeh?p1 zkut8V)*+UOQbHngeDvtig9i@;6FD&<qeHN8rrqcijAkIBxw#07#*`6JMq}P+6u`Ht zTudwz4Sh^BRo~)kBI1LtQPY5><*PPNBx<mcco~|7FbZU;kts7>x@6!LJ*cE*G1Zx+ zRKGHw9$3@E`hy&vD^F~yXEfVeJJs{5dg-VhQdf>wSLzz!p2`Irh1Xh;>19v+3{#8S zp8y}PEPe^rVQou6YGP|`%ZmKbkVrdcW=dt8M@UIPuN#iG1?1Mxg`jvBX+TV^M2#dO zqySc<Hm;D#1Z9|Quu{4We8CfBQjNScLAvJ={oLC8Mk@(6$zUxbgvO-3D1LBWa~>Us z(EKPX$3Qm566j47mocN$)g9PQu35;!WrOLWg%Gq0T4Zet(U<vbkr3-oj`RFVbME=1 z@zI|EFSRAqm$oiOS03ilL@gl~X<En@rH?Nm-7(*_S2Go8K{I=b(v8sW=i6A9Fn64{ zg_8^TAey5L$m-EmWOXY^+5IPo0&5mlPx4EiUw!4?=RWs2r{$}!zIx-v^;@@Jy7$Vf zTRU4;VgKoq`r_s|&5n+rf9jKOI_qxVdg*hY|ID?k*J-X@yZ*)}UVHbwcbv3dQEtJF zn@;<;-g@ii&6^I*x}}ca_>e31=8c=Lz46NC?#AV-SG+K9ZtsY8<JRrt!;?o(p8VOL z{;Biw^6u`|_SX8^>ekNY#`?MncegKRqOyEh8eK;OK?-NG9nOTt>cGdWC7C^P&@l0$ z><H$^N_yoULV>b^92UoEuWP1|b4HEVvdx2oeRN$`LvwfL$ZOn)>Sot3z`?J5=_{BY zA8S{}pFxsLK?bixT@~mW02pURLJzsG5Nc!ttn<@N(SZn{*6wQC(O}3i@fxWr3ptJi zscV@RM+~7V=q<Y_LxcpU5o9b)IsWRe{_2w_Pb{PwbieV9Zy5@XF#;hpL0XeCl0r*H z(CQ`yW#XHMDt&-5G#mnQlxo9F*_Kcl<Svz*Tw!WQu<7{#IVKTO0JH#1x<Q9Z96(4Y zng}#FsfQ+IK)gnnLNsx2=*A1W{*k9@&=tS+&1poLHWfymgFea*m8uB%T1o^OLomtq zDkV*7=&)($<P6z0A7(G8M16(hLvpbKffwI&6En4uQ(J-uIpW*OJ@Mm}Qs<!WTwOex zdn!JeCQ8hl6zOX5Aq7OwF+hkF5|DdLK*K9BI}RaU(U2?R!m1d^=tQ9J@nX)A_)cwt z)ydo@UEEy)u6ow^hL(M<9!N&|k+TjWGy;CC@^aB;5i#j;$hjWLNvg%y4Iy1E=thIz zE?RQ3GzUV^CT7r)As2Ntb7Tk^cwDsebbNKmA~^2VA7#7<VfKwDp(s^i2Hc`(;>&7# z(|fhMfB(MQ<n`;<1;<AKcfP0l`zx1D+<rK|_uhMnZyM3&Ni&cHOu_Ut$`C&fd;-!7 zg`*O8COCNde1HGx!v~M{_nxk=ZS3w`URzz?d$Pan#p6)416H^Et<CMtjV<%>Wbd&` z<jrt0CqM}bsItd4Bde1DsZ(}dln9F(YHcB=kX8E^fAJS)#yntVZ_ta0X%ud`CIQVm zBu?g&-tH0s84cf#l~Gp<F$G(jd>`&?+tZf`27B|yExX?9S^dQ6=9ZT(BYpj~H_Qg5 zB1Kc7EXo*bTB{?Auy#jkQvjyIq*}S;hB7`FeXfQ}8|$7Fwhx{ntO#f&O`}=GsT8Z_ zD?WGQ%}QApFRQA}vLa-gWxND>Nu`!imojB=5h_p~Q;q}g+q#q=e)u5{y{?#`D{N+4 zoJ6M4X7<9*c1>6u!v{1^gwl@9P~TlxXXl|8)%yND(|=MQ)z<gyc}~(kdww7oFTMz) z%sflgx5UdLj^Hw8$aVcWE-rcEJbwD@Kx6@x#OgUTzXF;&uS#cOW?zU2QZo=ZYD0i> z9_})Vkks@zfo^~keP$!dxO5yNYG%hYQr$tH&KagywY<a(A(J_Xr|BT%%-A&WahL$X zxaiXrO&flKKuj=dEJ93ChC`FF5TXwgSTp2wgA`Ud7LEaOtRvNgxQslf#mo^Cv^-bN zk&GR-g~*vbwCICa)n<cf$;!itJfcn*#DX}wLXi`Mi%FQTPWTaCq<<0W3pptD!|T&O zT?eeWoaDv7s$ylW{@knBtK~CZZjH(e8$}gZf$9@Xm&jydo7d2zAS~&j_2&^<h6d@z zlz^s%%w%r!)w*zMD=hXBTIQ3SjX?;FtR1nZ;J_L}(+HJpR_9!X#c$o4g3ql|rx<ZM z%kib-I+z^@F68_YteU&yd-v|Tv%K;8Yj3{!rbF!h{SQ9*#wT9?#3zmL>a}bC`S<?w z;nDNAe)!hA@4xE^`jbEVlRy89KmXwV`+NI)_g=oM{o_CR?_c}c*Z%OUfA~jV{p#=h z&hPxYfBSEL_jiByU;K-I{_@NB{>}gA-?&oWeditf=+&2BHm0r3O?p*7KYVuO+U3ph z3$9F@+kwq$MA~nB;~O_`-$p)OIk|W5&JTb5!@GCxtZl44d9r`7Km81_F=pUK;e4LY zLr#et8ki=bPZ$L5UaxwJ2$aD6y${~A71iUgbh8*gr&Hhd#fmJ333J4c+mN^1b$3GX zg=Ga1lA0!0O}=KWs{nV>U;fp<#rp9veFCg3X)<hGAWxKmjEay}HyVfxgLt~_)S5UQ znWkruGGK~Jf{-JOV5i`fEl6ffSPNi^qlruB{n3wpL@@Q<flVCW!^8SbTJwVEs2q!{ zr4fym7YxdjtAQX<^dW?tt~T8i-_hC;ngguShuJ{_gqVikB#0atvt3}W0o@>)2++#3 zmPWwyh)X+`&w$hweK8!S?gkyXyDj$+;@EnKiN-367E_qfTY7DqV%0{|rU)<|g9_<3 z!ig#IA>Ej8veSTIDnf|WiXdd+5{;=j&?!QL-t*9=25U@ngw~j}16(HUz@!~6F*PAd zg;knGsZj<kM@VZw^myY4slTWLlXj8FM1_!f2wcDJaD<wI+3;z!aqoFv;sBv`;rK*L zn_PUA#}s$q)h&dBpp7tsoepqG185PJ&`BF{X@25EQbY6*ebC)D%_G1V<>|b|lz<@* z@9C3gLM~X->mA1V1~j@?uU>WTdD4Z=jrFHb_v_c-E>50gA!h=~gvioa2wq7|leG(< zNf%NHjaN{&H#xIpnDQdT3iRT1d>TQvcj~Vl3Ni|ro+;_c^q3-0+6-DW0!K1n>Y4#? zUqq%Pd+W>Q!4xMZ1EHq`@zJzoOhUrOOI~qwgD$T#;*;sY%{%Y^l<qRD$TZ@IOwg4* z8Ug~DiMzJ`0>t>F4op%KiN;!C52yX063UE1KpN3#=tD@&N1n&V5NN9U@wIac!HW_{ zmShj;Gp;BFB*=nHrVkPdGoDcnvBsOl3W1(uIJ&IKJ3I=Z(W8MbLO9-j$8yt!mN(&g z-!SNC(&D=~JV6{BoX&HG0P5F9ACN~V+jULK@ndLJCuY9n;oYG^kJ_eU26|#4WoJ+7 zj;fat_r^S0G@u&|5GL(H4<UyTOom~K5Pqzns-EgeH88jrz-%;O?j=YB7{oJZC6`7t zOQ63n0$k|Tng}C*A<FYOAK|0%lkn#?{H6R5=Iw>(A+%7T7pMLC0lrB8LY!Qj`g}>r zyYx$~=2fMQ&|p5VY(#&iE%i?U1wf7hmt=y_*q@mS%3Rk7x(IQBbm#4b0+5$nUWAkB z>3$iC>5>wMER?n**AE1jvbrCBc>jYB?%%!h(w#eZ_V??%V_tpb)!p6g@4oc|ue<NO z`|fwY`|aJ!m;aal<^QdqZ++_<?$=kY?7mfh)9%k5?|=HIfBeon?-=#|-k$r{C*JtP zr#|(m8`rOY;R|25fB*i^{oK#J@%kH1#m$Wk?=@}-GGeZ*uH3qJYh}%?!Go^5Nmcl? z{`~*bKmGGRSJI_b2gRzFWcA*D>9+UHgQo}1!YY28;U;++%eW0?)H(5T!lbPcE}pN@ zG7sVCQbxmf=W@M`XX+5#iMF@u$4+w}L=$9u!8v~=e#=2lFfwgI#W7!=7RvLC2_fim z|J7grGTO&S{SqwU<jY2+k{BWb(;P|PdO~+2Ln0Unbex!ILdeYtIL0*MO*bAOw->Y? z!i+qB0iLJ>X4dqXP*;&nCY{Q)OmSR7^ux6fC6Gl<om!faYPwN{5X7V%!<x2;Hr>n{ z(8NSGsC2`DD1jVP(80xF9gzwl15*$hutpdGPA4at2=g`&sz~QBnFl7-0!zwt6DRuf zEg)ov0NM77K3xK)I{Wyeoa<pJU@)JzW<ut6t|13;>`FpwfukDi93b0N!|6<9Xbs1N z8d2*>mvV`(MHpd9A5GeL1*|R15oN$-(hf}80o}PZO65^TA5B~5LU+|U4-(KcE!K)S zgqn-RK*lr_B(-mI3FN3H1o7pPN!BI;6E8r3?m9@rYz}uCa>pUGOR|G5BpS?XfJr;n zeUi>XoCqP$y$GE`*dV50a3|=791}EoV$6yG-Fd(!bZb`a$v{{)iARqf;pc~V-+S*p z-R;dyFHrS!l#BN(;I0cMEhz|2OK$~`A^}Yte1vRfT|tm_!*`=yUz=WlmEqLon6=P~ zpc}7b(YibH?d(F;&2W52fG!tcO-A6G2=pOnSqZ5@E0j9j5p0swjNm;dG(bRO!k5Ua zJC5S%6FHobaN6O>G$Md{q6dYOxl@Xkyzw>IL8w<sUSxCf_{qc7HK)Pz@!q@o{IFh( zF%x#Iq@7&ulF}bMoxanG1_v3;k1SQnVj(imx~3|QKma9Wq-12YlozX{W6RVVU5|_J z2sK@Ul&84lh_;}|Rx<xguzz0g*>L%Jpc#)}%5Z2*?&1iTn7SE-wzCk7Pip%pFQu%Q zid2$%w4giU_4HQRsWv8FSqL(vE{H$ktR5a6>qsfCIu4#cdn(ZgKB7+PI*To|WHMmT zC7(w)bI=5HInjb8S}+oxV$u$T4^w}@HjZX;7%*z3Mmbo8_?o>a(*<%g<+(sP49vUX zXa1x42*j&>A?{OWfhdDX^^y1qX^j{0N5V4A+qtj=1G$j@B3Oc&xP@0Ht-a_YG(N&~ zF-|TnpyM<~S}1u`R2Y^*45y67LZ4pH-3VveQeS|1t~s&~U8fL^IE3*llndFwK(NVO z>8xP}ojvGnnYQ<T5Pfg{^LWt<usFQpIFFMo`59mg-6+(5?b?;kf9`Xyzy9j#rIpLO zmv7&`$!%k2>+k*6Z#m!IeDf3E`1&_~>$m={cjWryb7S-Kpa1N&D_5OfzwwpdI6OSK ze(n0Ln>TM<yRkdIpzTb%yu16_Yp-prt$+42pOxBeYi*^@-)mQ|-nw<m9skwWU(GK~ zSRBy~=;>EHeDJ}0-~H})y<@v^?CjQe-*{d)dOm*UW1O5BOID$WSrNv-r%{a$Ahk@G zi$k>_EG8k21l{soTX!$m-+y}e{AhKhK9pv4AZz0*jst(Z_tvlWa9gy>iI!`}NiONm z_?|(^@s)xry7VIa%)SNs`t|zr6-k+4=f;^C0i;+X+nQ*@x6lK|k0!H5LkM)Wu?jL~ zetKYqShawljUM6>@CxX0xJaQ?2s8RX*L-PBSv{PM@Ay*rlkrC>Cem3{j*&e=L&hw5 zvV;s|nt9T66&7LAE|_XaH`atg&V}8P2|$y*GB*VszxBgoLi9nK!Veju$()A(Esr_A z08OY610pO1nRi?6HbO953)v@H<3&g}<dmJ%tpx6rnB5H%=tuYox|89e@zOxY@6=70 zJQr6-lp#bPL?5Mg9t!dR3hB-fcfk`ME~G^nYY=@f*TbZp)f2Q*VU=l?YuHOZ--7*_ z^2mG}i2x&5$=${=2$^6`SY1j`ZVM#%d<Noz4;-6A4xt`w$E!v36=is7ThkGs>R1dj z=uk_hrS2SwAA}a9%bKpRYB0tZ@e!E9Cj&ya5O**@t@=ldLLva!Io8SqBy(|x;N`4y z^y%Kef8P$=+Sm}Te)Z${!GZ7zBTt?4k|u9tZQqJA&$6&`kJ9`*SGAZ<Ht8%#+*4Je z#W7%th9LXHM-N0M#~LpJLcp5TIFR64!_l_a{B4S+?g!)kMGwe=NJpbZpfoi4t5>f+ zdi2O`!cBoG1xPWHpYAJ>y9`|sA{-soQ9~~~cQYVwx^e*;xwG%>J#jm)(Br#!m{dX# zztRjO`KaO2)BXDD{*Vi-$Wn9x5mKHO5dlV|2?$17QN}!{FhS6aT0Oda6%#AHXmOl_ z#`}I&Jj`SVakS}XqC)UwL&K3q3T?3mGMvsh(s?OWhNUzdj-nOI;MVHT|5~_uqc%!b zt$16T(~qNzkP(p;U?D`Vf(KGk{a05<Z6RdV%zq*T<T$45^2sn;DTaWpgt$aNASff< zpyjy|mbwl4xhdUXQY|oQteOocau6$IVuQJR%Oh&Z5hnkE5Q5f()>xt~A=Y^dag5wp z(jYhgr^5Nj!AI*~)P6LYLwHfOy~*dWDAAwyVvX>V4*%rhIy+8dWS)Me_eFWr&M}<M zjBc(WEVusqY2Z52R>TEFHaQMtTiOww>y*-@A?Iq1MvI?zj=4VZ1q^7!>G?m87rg*0 zBQb%HIOK#<GTG~>@(H@TyW56v_s(sn>;7K-ED!I;Pab{l^I!P>kKXbMdiU<#Pk;L7 ze((2w&xz-ddGz?9BkS(HJNTdZ%+G)Cd*8c!W%tpe$MtQ@<8}J__3OX%i@*5NOE10m z?z?Zl{k9jGAN}Y@2mAG>q#iza`0l&!e&;*i`QXD3ZoPEVopAhO<)cf^$)n?aS)V+9 z_~HHk_SLW6ynfxw<>j62ORFoZC*%97PA(liuXAzCN*$htX3{c0+Buwi^K)iQ!*tdu zn<liF1c8I``yD_oN~RpS_~IvpE+z8D_*0VOgXA+eI4wEZ&5~yu8$$%Ce`cQm-xx2z zAfGg%Yb8)OB}Q66fF5x4QGzNb=`1kg-k{VPaO9f)f#^ZxAl(2VLi81Su@`BQW$wai zuNaFvwAwre*lniUgX74yjJU)XTDC|%*oito6I2}o>1JF&6K1;fp^?$FA>@%FOdv}K z^m7{29$9>0qJxCcZ7U%fpak6@n&e7%j>JC?safL!?GAAyMA_X4ODKogcp;kXpVnYX zsx=kq7HOu>I;M-07NU&4L7&S;gn0{05rX&vy_T<*9zXM+>mp#H4_Xs)Leb>lj<O+6 z$B%#zuujrIOkrw+n1Z<;Chd#$z!Yn`AtY~<^A=OvRmC?bw*|UuXf?t`v>?8gxK7>y zqt3w70s=1=tO#j=QsgE>=AWJ%C7NTg3rHNw1PK!mnge8}#-v>g{5-^*q{VQ8#Hj(F z-Hm@KpPrm9D3y{By&$FwjAFz%gLn~=i;SklHx;*T-MVw<j(`rpL|9$9<mU7IS$$Ny zbg;WFI0g#P6~WCWk)1+LPBN>mXk4nS*=t+8@<NCcaM9%@yDq*9LF$C!VlVJ=6>Bqg zAmn=K2+`{r3yos-#;?D^1o{j-NFrm*TUj!44~Kgq=rXyR=GQ|Ah||U62tuF%)(lpJ zrqR?FwpUkG1%@Cd0a^TzanvbMk<Iy~WB2ZaH&7a;453ONeD8JAns`>(D1|ERm^4{H zOnKudLgH7o`8l-3^^ziyV}(>j$N=x(zn`vx1qner50W^+!L#W*x>+H?)tR-(4Df|o znEK>7-?}_q>5w?KR%rM^0va#!>dN|B{jbjUljD`6<D->JHBzz&M~5dgWP$C{#N;WR zb|jfj3GOtJ%l*=&t?eBTg+(44(n=XlnHIo|OS)o4)1eaINShhN7bxe563ESgwx$iD zgrsZe22xL|bE#7pnF&+n+IdxJgQjVl03xItL<vjXfM!0TIa(i~+sSiQd}A`qOfL%l z5tzHr@gjZC!1?w<WC&B|BbmW`$N{A`*JHYK{M17}xwwGykt=s8PnV;yFkR%exPQeZ zOz7@%>%WWeqH$%v@y*4H<}h&<<zQi=!J&kuNt?^TRKrXuEE;s8U}>K>KH?K#UIcB+ z!d_afpE_|gkLftBpTc$q*H_k_ZLY6-QF9SqIyu_hs6V;twd(!*AO8GjKKH3lzWLqn zeD8zz@2{<{JIVgj@BHrFJ9oeSwXc)kfA9ToeEpmM+kgDuu3owN?QehE+vzvI@s0oT z`@jGH{a^prKmYST|BJu)iy!^)hwf`8r+yD&J|=bh-rR6p-hSzp{rv2pzJ%y-KdxW8 z@$|umAAWfM{&&Cg?LYpLKi%DSPv5+L^@dyS&eo2%Yxhy11j%t>5L%}(0qD(nrd>Dl z29YtLry^?<E4_dOGn1~ENfGd>RT+pQ4T@QcDPCj&S;_9vtZp36UdO(!n7{J3zJ&Sl zv3BFeb^j-yOsQ3O47LtjvYH4X0DY#0kaBA%vt1sqhLs4DUhqJi$vj32tQ{u;gb-wc z2#I#Sg)js2rIm|bwNjYAj6!=JOYV(ajS$DGb+J4n=QKHxt~rcAgUOMs4F^WB0y&`+ z8JRL<t@u&SL1QdU(*;802r<E21A|+LMzmO?0ZMHWok#luVbadlG0Jcfs)czQuZlI8 z&4+f6M!UpGo37O?p9N@wT*El641u0<j<z-j$T3a*MUc2yDc58)K%?gDXX`R2Yjr7e z4MWIn4ZmHO!~t@c+8~5x!ekhj>tWK)hS2(s+4^*waABJ>A-?uxMwF*s)<!1^IabPS z<6wT^5+EF=xWp8UU{yoaI;)n9rYam=tpgEqorXi%p+=agk`d|5bTxq&Q{1Cj!kn3Q z2?-uFEeIh{hL$o+vdBHj!5|hQcaR8i?C}bS=5hc*bno81d*jB9ya&c>@5y6tXI_AL zfki|EakS}XLv~WHb5VkBE*~21T3xpy%mlP0HrA&vEGA<>R+0!_oNzcsFHwEx*g(b- zLO7J-q?qItLDvAuIIO$lcM4K^W}*p!UhtGHh*mcdQfK%n0HO)4mE3_4r8gzA2oO%< zd*Q!w<%<7TxniWoB#$vw{ozkosYUm)A79&ZjJ19$XLPG<T~;(H6t=ZBeG6{on%!*) z_&_<vRI531Ov6u{Fx5jzXyDrz7FRSAs8mX1m0(h)O~#-?J3lvSwppz^a+DzpLNmr) z1CPlIu=+EEjsr9*OyxBNL)IdUoMEjVdx|?ees<vXK0msCX?*{F{ng&Fr|Jvz@k;#e zibj(}pdPh(0QCS^kE>&M;XHcuC|?=R5ZXnXZlYBwXF(HA3oR#If}|TE2#qqBD`C<O zL<3WQAjLFB+VZ839GU{gI!wzN(5HnkQ)fG#=buOPA^fEfcBxGeDDw<Unkr~9CqEU= zM-Dz(ztl#!5M9-r^AY?J>@;{F$kIBtb&UIh6feZd#hmlLG*I7TanZzvA5Jtuwt99~ zYj9G3$Y)yrU4#phLSLsKW=^x5S2@snCzGXs6fisraql2)iYAWd@uGS@;%9)lq?jC% zs;$GJz9FT+Dl`3f1wQeX=7ikZ%-43OcLBZCjjgYJ{p<hwU;k_F+CTY|Klu;;;Xk-d zU%h(O%dLQJA7A_0*WP;TtvBC%^ZobV|8IZz-((cY&4u8+dida>Df-TLzVqWB|9F3I z@7;Ibb&Pv0lIYs?t6LjeN?JX+R6m%q;=cUs>E4sQ{rw;P;H|gc{?V2C9hMu{uUvb2 zaImwv<?Y(}oF%Br7hhi^7&2wrXk-T!Qqn}Jt=SoCm!lFNts^+L$+<5eCuRiX$Yzf( zjd-RkK@xuoa#SCZn}N&YZy!QU?f4$vU;9~o0(|S{jYzVBBJ4s>3DQuepjb1!R7{gX zwIKxLSb+felofhG2G(pH2pOaX!je8nJ?)h^VrKT^2ni0EEPR62O62Jz*7I1(*j+-3 z526GatByq_kS@-=9vZR&vJW6iZ35;i;xq<=7JbNC(2ZlfA_wKa08<beAVi>nxIi>X z5dzRei2gicojS7xr5xeUY+S8TN0_&8K5wuTjW7?`pbY58G*4M*kZZnPFs@c65q;bv zr>hMUC(1^w5O+wl$bg`W5GBECCVoZ{D-C@Xy21@0)Kl7k?ud6fgn)jMW=UbLhe>-* z-(>?+tm)1PQFaUS@$ynX5PF`qi5BQ~C`_#`vepjQbya4VnFK%%0d(hC(gmEJpW#$! z7onWyQ35iwqqYOWL|V{-Ni~#{bQVbzYqvnJP2`~1XX6awgb=jqA#gV+uXec`#flaa z5E{{kX2`i2#AUqy*7rDw=AOzVU}o40kDKSChYyd&ccsc}As`bHT2BrcC=pTsh%79< z`$9Nc#o*BJwR|4P8Z<Z~NxkEV29!dvGC7JBA_ygu3TYBnThYdgTr>zC4%FbNWTF&A zm+*M}Z8=Qt1o{*ViJ&DjrE*@Bx<W~+rPrn^WJpz7a`f8P1C93n{SQ69Fi9-}f>7Dp zO(rZhcEur%nRu={zLmFr)3q|H+LP7%s%KAGo~D>Y2*k-$0AB$q$@GNe0(B{d5=S?* zk?Zt+gg_}8y$1``vW9GC5HdL-M2;8a1sF2}L|~;S6LigkHiAK^D~=&(A>D95ih#z3 z8l%KDE-pq?V;@5_#tJeUv|U~A@C2$wgvzL^B@+Na&1>r$W^`|_euFft_R-_V*2}>Z zGGL~>?zRj}wT$QP3k@cmIT9g4IO&EtjFUdym{N1}gHj;VBLtIn=yk)4sbMOkY*RUm z>8c4CmslJn)t$!&${<}dZTMP<@;t(6p}QkYA>BD9!_4%P#9zXT_%G5MT7(c@L~CSz z2tOfzK6Rk%AnOY;%?WeOlJx?dTx>e;LIW~S{j&%^oM-}jA_apk>(~y{{tWp{>%WW8 z<6Q!;pi=}6B`zSB;}IM<$*T>gU9|MAoVVHGb5O>5Azt(X97wGUQ1EoxT$*kKV%9H! zHb0qy@$00IkLvE}#PXU72hX0}xOv<A>b*O6|HVK5=Q~^5htHn>&0qW_f$CRSom^VI zw6eascIo)!=8YS7U%K<*{ri`9c3yw&wY?`#jPT)u2i~Y}+_?V9Pk!QapZl!#^-sLM zzOlZ0W%u?=w-25lpw;)c9y~vMc3597te<syy8q;fH@WxUeOGlNtLySk{ZW8xSFS&M z?(CgT_{?g?LU{7z3B4iIhz1Ds<}(6h)R8G8W8!F8>zG~ae;QUCDMSu|zRsKz6X3>O zGlr5NpbG>X8^FCOk=<tvGq?UPedRYR{l~`I?OQiT`e{cB?d}EMxx)bZQCI;X-P8o> zX8IZ#1E7V8Mvo=}G-uFDjtR3hT3(Gf_Vn3~<|1Frj!S5f^DSPF9z8OHhNHE#uC7XX z5#klhyMojp7xjmn!G;z>TeYkZ8B%jDo~A|Sn0dBiJP=?~W?YoU7+PGQ<0NC1wO9yN zv@j#Y5r*rO5u)J|>m2lH&m)e(NL!#}nzXa|r&MZ`A#|($p*{s=>mw7yna8gQ9a9=T zWLBZcwa+ek`;AwJ4S{2Art!4Rq}v3cwCy{R6e8P5u>wLP8XzYHS^Qr2birCX2<V$E zqb?{0p~5Xng>*v>Cd0s750my>g)|u#xlMyO#b=E$R}xff)agR3LAud5Vgf1RXi$bG zzM;`O#d3tDi^dcnbBQUwsS{W;MX~0Lj*ALi;DjDj<N!x28blL<wxQct>Nb)q*5Nb> z(I;|hjy^&#=o7*TpTOO07?(R!M%^X|KaN1tCN7SS`Qri&&aGRwc6aMHUO@J$2mNOU zPd|A7efL2ZiJ)FIY{4Y6Hg)B2_WnGqlnC~U!bD(6WCxTZ)bg2dG1ID9qWXE-hxO+W zG8>f0tPnm8eJ;;9u5Xl#pAlsqgz`>Hue5qY8b_kVr93%C_LyF;G4+E^her<|K6>}v z_uhE@6T-NM9=Y|`Um84ibANW=MREFCt!RRPQJ5Km;McBQbK|&v{kq_aSAbV=V^_+w z22>_|l-P5U7qpoE;%i^Oe)9(X<Gm;5O+g3GpY81KYW>?6_uv5k_|gd%Z(q+3pRaAK zJ$ruSf5u8fzqz&bq<)9zsw&kk)7qwasVl`WQ-^;lf*QkkXEt_2W3_BKzI2U!b*29F zg%@e-ys^HiO3I30$DORK*GulE){vOi)<;q+<pQ^L>zkaPJ@&lif~s&e*m7RXfKBxD z*+D(}9UVU1-#6-mrw3#e81J58JgvV@iL<}APu||zu0>s`EcMBVF!HXhUb%eL&AXm< zENA_$7N_32c4K`*mYP~Sx!zbe>I0PV*1b}H*`+?fGX7cut;sk%5{IwI=GQZn;Txie zB8y*p&K?)Ae(r5`Z-4*MV^4(jMR1n>3_Pn1V^yb13~WVRLMERO0-4aXM)o%35(so7 zgcD8B`Uo^NTVt<w#zvUKuMn3Y>7tyssk1dLh_BRmB{G>N{2=@}Cc|vh^I^`xG)Xg= zFa?^0YD|W+rlsy*iWl);q|a<mou2?1OI+sdi(pE%bB+iJ0v(}+rT8sqFUHBmrt>Z% zm=o;uxgtW4?x38}t3L&2W0<bM{?To()7F0%A>%p^_XW{9f^<#-CzNh(931P$v-n#1 z>i7oZIt5%BP9{}3i3PW{hN%vzA=Dvme=c5tlcGj4#**%Nyyyj(SIScx=sE%+h4_b3 z=UAO?6?=PoXM1aNduR9dty|Zw-*6ig;^z3nyzZvX_FwtcU%hqX<}ZBl7u5f$H$SD? zzy1rq;2!L}^XmJFPkwT1W7Avl>#x85+0TB~EdBMr{?}V}UhNFHXE~%j0KD|lOKy&C z?i;I{j~_mM^zfmRZGV5S{`%|V$NvBAw|}g*M-LylD~|i!{%fzlZXh^j)o`qWVdmH& zy#N0Dt&fQwWH&teFbPbV83GU@Bbc8nyO&Lhe;#g($a2ItK}23zTXk%^={VAP84kKr zf86E8uP2<Xt!?@-&uUw_eEG_?Yu9l+L4V~p|ISGJaj|mu&TY{%t?t@;dwZtowbx$z z#y7rUy7MfhXm!|>29}X`8&sgh#_Fjw05hV^m_^{8DX8%;fE<2ikOmWttN<;UMjW&R z7cIWxSZy@!?rrpBN*w%TVTxmXX~bkgjuJr^KiwwKr|ist;nU<AFi~cP&;gnF>c*?v z6rdHK5X2N@Rz;A7UYDHUAfOgagaA20+(U!Za31OpAzhA{7S%=rBi@AQ<D!ckzLtrS zkg=%5oX<INR5Q?YoVlP*Ouk^TT*;W`Gu8x28$l>}vn6!Rzll;nj>ra6F!g6hC|=s` zreH`M8ii#JQ$HnZXyhmXVfamhZDd@)rGtZEHgieP0#00l%s*wUjVb*o0IfChYDJ^W zo*x;eb1ia%ruSiMBG4zG)ENt<ViM;(Fts>KZG3rYgXqJLKIG`<;~n%#$UsI#H9Ck% zH$h^8kZlZt>;{rKu{pEHvVU?RgbdkEASNUQ*e6WfDMKJfBL(n9qtW8%;zSeW2tTc3 zIEfR8-vM=%8n|8YB51kHlO|3=1sn~BfNZ=th6&sq9d3#@Z`PMJ>rS}0=dE>b?{WR% z$l2AznsnrR7#NLECXLtj=7u`BBqPVFVD<$~aw=p+dwz7fKum<hCuCb9yVknw?M?d- z_jD?x&L)gNKi(qqE3ejecdkC&KRw|oaon@sefM2mNL7LtR*s(^*LNO46+P-1g-;ht zqqw8&qwxe3dEVm3OGbr}A3b{HDdAUs<yXG?)vxA5U=w)%{{4IR?r9N>5t(nQN*uHE zWbe`H%KFu7m)9<>Srpkh8iFwzDVO?XDr>7Aj7-V3-D_4Z8(7{HAe4t50=+DhW9S7O zub=cdWSY>TQ3lOaiOcHJ$?C?MRu||YgcOg%#S9aa=Tds(jW_N;cyO@4Z&Zflre$hu zzD?)J(3Fp@<<4srY>&fB$19iC>YKkWd3g1Ds*QX}EnZL!s9wJ7(Ux^*bK}z5iZ~*u z`<Z=WrB+s6zI*qn3)vJsdqz`FLnF)eE7$ne@8()v*;qBB74zuQ$(5bmr@RlI$+fw* zPJeQE^sIj1yzUxi!}8^}Wtc7yRc8{GKtE=sKyH|Gnx4!swexN?kxgUd5ZYu`X&O<6 zudvRdTj9p}Ohd?;B9AM6dVx<1^oeHiqJby_Ox+8xC=6%b0+&Xjfd}H&XrlymMhLU{ zfoPe!v|#5?wzFWGq_g0t6}IEIQ04)?Xo2`0s`8x+yX1bJ&}a@}&c6_cM^o4^=R&z% zfQ#3q_s<g6R%)K-VIvrFx=XE+w830X{Bk}UXKnp-+v|=o6>@+RmRh$L?Rl_HQO?Gx zi}fPp%!%M$cJ10VkBGZl+XwsgT|#b5U`=!SVQRC`6?2h7x4uVt1iTPo&Rd7Xg?ga~ zTGv{hAzgj-l|Uy?I4j4_ZO43l*>2_1?c2AX?(Zr4@BHRhzWd$pe)X$=_={is8{4}( zw{E?3d};OejhipO_Uc>T`~ENd;@@y;{n^+4;=u>^zxkbSU%Pze_T4+5c<uGCee)a6 zE9u<C@7%fL{^B%nvoK_b6`?M<<Ku6C``gO+<~P479rDX}?`>~w+`M+(Rq6E0`EYnV zKFfS|@SX2`=dHKiy0p6PsldzK<*QeAcP@YU?tOPLtM49^1K+%fFK=!Ey4f3b+|*5^ z?jRsLYr8ndOpD23qGXL@{o&!+Hp}s3kKnAX*UJw1gAYD%`$jg*8&|KL)R!x#9YPpM zj$VHGWw%J<(yC3Dte*et|NK9Xz#kWDcka9-U&dzSxi{E+_8CD1k{KirbW>bIH!!>e zF&?c5fh8DYFN7b0M6J<Mx^06*QQ{CxX!bfnf<OpyRFW)Y99?odPVB)?8y9Ujtptwb zbXm2-wI1@MrceBq@#pRkJ`J=0u@XY)!Xm^fYzm;1olMB&XFD?CK$ZY1^bF@UffSQ8 z5MPL%kio_}Cr8;P^`xXIA;ou`!J5VxO@u}`J-4D6rWL15*dVkH2qR?W;+si$5r-fq zeSn!1pc`foGDxiw-MA1k%<j&CPdRU+gp4bQDG)6Lato1{1Q_;-8BHK~itHMIpv%<C z)DV4Ra0{#<2lEthjDD$$b|Jz!kIB3kMIvZ*=PrX%2qBtziyUhR5WOy;Wxx!`Svze{ z7j$=oDMTMRq0&M&B+$%vnh0a-m1gcPZ#Xo`q8m;K5KZ86&OwSCQzFn0dx5?Zj0n1f z9#p%K2e;%DMu^_sB?m~K9%dyU^of}59ykBII=ez>yld`z;q;JEUqF7cyR$vb$fB4) zSJLQ3g2-#*?*Pk1mK_Lf<-#|kNX?#@Oqlr_(}p6ldARh=Z+_c5yCa{xxw(Di%4LrZ zw{P8f_ni;ibG_;B?CiRxMKU=51oKZ_Beq!La9ueWHBy-Y$W&+*rjnu#RAN{e%ZEQy z-TG(x#7j3*U$Z$rycN-HnSk@*g9i^EJ$kaYcgqurO=3+K|Khv8xp7#}OedKrvn`sL zH`~0t0W0s)_{h21ODh{|_+A-3x2$WQ>l~ffkx%yzo;^P#tH$ec?Y5H@aUVZ=SR5Yp zOFrwfPeJ6WPbcbw;&pU0Gd?@1U*EE}x#_jgt}vDqOvolN9RD(W%5-fEuZ~sr7>=1V zd<$y-WbtaM^|QvuC-vJ%4}~&W`M^drlZ<I$>Z6*JS`%93t?upbp^iR9{m#$b%a=Wz zJ$n4OQjM>~nJ&x6YPYX%co;SG^5>v+DeBdwC24Jf3go}Kj7zA?M5&@>^-Z{k5Sj~t z6Tt*G1ficg10i%9wEQAMZMG3#z_}i1Sb;uP2tS&McQ!1-&=p!g!W5$a2{8|QVUSdn zN|sCzM~J@LdDsSh&+`(Nn2qF}N9%UpZDGES-F^gKM35I)gO-`PZRi^Jg)=h`GKZN6 zZ3+03bQX0;EHF<b)Fhq7TtAn^zpzdXfwiu<#eEPn<OS!n{Ruyj)(tpJs<U94XBo`; zE}Gq)9dC@&L2OOk_g5T}UODS)U#n(=3%B~7n>x50cNZr(J6(-@LY{Q<*4TyDdN7Dw zNk)Ml5Kv6gT7C0L9b*0uX>V`;#`Wtj-MQ;US(qC)uWxPbtgUVc=f(Aj6YcTiZ+z|R z|MuVh+aLevZHFq)4?q0ySAO}Iy^+5D>T5sz;Saq}{@I`X8I!j#Z;5Ze{Wixx{^LLX zqd)p1H}~&<|NCCBzxAzez4_*w@4WNQE3drb<=Am%V0BRMKizw}?_{g*`+EA+%|-CX z^@|=?ws#$>JKL9cOlEz{&|!T)5jYYJ){!eX!6jpOgsi(R7-lA<hClA|nU-$r++BPC zV9y+Rk#qxMwQAO9T<N(%xN*2Sm5WD|@lDa@*7Vm+%Ppb42Wa?JU~}VnUh4Wcemmz5 zJ=&Ll^EcG+@v-*OOSjcDMp!$KOo+^^YbwXhu0AxNVH%Dl1O}kZ7bob^YQn}OYU{qf zxa?`7OiKv~6&d#T_qAqF8+SF}n~dRoT7wpFnyiZktX*)otS#V^y9?Gnnsg!7Oh{w` z$8-ralEx(jAS{6uVr_7YVC{uca|c8w%WDXkdCG7=HvtnoL0~S=5n3a@z@!xxVv<GD zbi--T^g^^X0wp0B2`6;eW=4n}L7Pz%G8>^SwXMetKYFqjD%ot9HiNdk&}dAu6vKYX zj}Uz{iJW3M4to)zVGUv40+TlNESZ4sBn>bHQ-2`c=$DZ3!l<RtN-nyYKp@QZowuA9 z3k|)9!K7V0bwT({Q~w1p-q4oXrSVSeQ73C?b3N#`elASrfw?K6q69LiCzp&i>lN$L zc%j0b^_`>FQ5Lc`OfKD>N3gq)qwKsRQYq&`hngc+;5e7l1u+8}CP4z4?xrwpT-+sW zcvIo%){Z&Jvwnpg87eQn;t$3T@j7RKHF3OW)XUYSdb3LFpVydrgR2J%w>EdL@nSPf zH14CBf06U7AewIKti%h98dtp27}9aQyj45atlAqlZ(qH3ZEJg1iBAveXEpDC`0#`K z_v`)5U9%oCR=iR@^X^uEQ}=LVYeRlQ{;8;*g=&PBqoM{$O|7u*236j;PNPk=T{E?6 zb=ynVEO}UQ%P^~Ed(3Tp3(~!N_c944GaHXrEx_U7&i0Oa1@%rGB^UEg2KfZ7C(Qwi zU`mgUj|}&c@g6>Z`rNZreQaCbx>ld03RDC2D$IIt=w<e(zVCTsQv&kg$#K0YZf$xF z!ZyMqF30%el)rTBOng>lPCqbgMAU|$BpS8NVaPl6YgE<@_VVS+*<g@|Cxna?LKe+p z<UP0EQtKmO+FC=qX1s};#`2^0fF!9BHaF}2wr3lZln-esnX<1!kUY5{^+z_bWMr)f z@oj5j1_rBmN^#BuQ_I@E0sSN`5PoQJ={CZWCb%$;Rvb0Y%RbK!Gqmu-3BrjLqHN(s z=;HX!+ss3|OBaMNGE63#xpEH5UbrTRoZuIt$xBG;Sm#2Q)JPT}H!W?13-Kb;Qr@&6 ze!5GjOZptbpE_qD#)x+TCdLv@F4n(@-}S@12Hi=TVQ{8TVsa@_&etnm^Y&->0xXLP z(?)PmUAcVO>y#tSO6T|Dp}JSquU}pr@5SSXO{yI`i|yhB3y9op2^W0=ub2#fX&yKY zzZwNjrZ%k;+xzXy_wG3xkB{oRt2~d`{7;`Ay!`UZw{G3?I{MYGe$~6{XFl^8*&U}e zO#kh_{kNB1ddVv;jW=HIZp}ab@sEG-gCE?#e_v|8-gO;W2x@r!_1A^v=p0jr+o|bM zQr!jJIWiZ=mmWTPy!T|^&C=bzKEmGG-rC;Ta<fKzR^L}Eaz1o)!ZSN>9ifg#wHc0< zELJYBu^PIb`Q0^4KkrHJJ~Y=qKbSsA1yjRKSaCUMO&-1Ah9kZhrnSC{pk9nKlO<?{ zio8+3PkVcJcgJml@=L$*GkO8Oa^<q|t4(Dl6jY|I<O`5n-#dnKj;G_7dBhQ?LD>N_ z3&yN9-Sn(N(NF9#Be}COg|FqS%bL^yrIr#u!FA^`V@(U41p!hgD*<GTHJbLaJme_j zl`e!3d9Ggq6Yz~3Wxzc%!%EIpizx%AWbMgE3n6hT{Q|@3F9*kfi)cWm*G+a==FG^f z>LIiX4Kf!(XapGaLi<7mnxU0KMTYhbp<5}!45CLSjD&?S8!0TcEd>mJj^R=0_|cn( z2w8=BijFo1Uu_eDxKEu~1ej|gw5ElI;D*!s)Y;uGFEv!rV{uzUfMO3&hLdiaqFm}m zK92+;%v(sEFA5UboHUv_uMl*XeCNy_X?N%RbVEprAYKG*geW5f^a(=lEP`lr0Y(D^ zU5M8h&2+&=lQu%5&%Ji!V$%A$8?mP#IL<>#R$g&D&w<pYTVEp`zZp_Y2YU|N@vA1L zd5Etd;iE+_LcP<B581qG(AV4TV)z+aKnYPox(Nl5wd9Gh@Eybn<E0TzJwj!MOGwLg zc*m*A+uo|b0$?l#1%m6U83RxEO#GFqsuGX#dT8M<0l|MojXY~1i3senCy_Xh9zD8o z<A!G!vt=xKDEaiKKkbnvH+3|QnPl#S9HIEy#P5Zhu-FgAlm|-w+%2IL6oz0jxX`mI zSj^|1WsZ)lIz20AGgmR{x#Z-@_%lv471@6vi`Z+f-_uK@tfOGhK%<bUaxpV?5>=eV zcZ9j!YsVrc<OE)0``D<{js@;op{l~gRTD=@FC3CGk^%^M@gAIMCdWdZY>vMJoQy%N zVDpQnTaz<B@1^8I$Pl6ja(gYIBNM_AAwgn_G8mNVUf9mNjl=<=q6tA)mUNe_K!~+9 zFzPDIm175-A}+u*NoUd85So_R3n<kSbl9}*)%>{?vh=MCG6}=}lS1kU92?O`fGPSS zb@cQ0Bk&?ZhD?~Z5jyhRcj*N<R<QTDoQLu!>RE7^q$Qk<-*^%KLcP38dfmV=9Dx$e zN&%s1OYP6<1vt4n5s>Tns-K6b)2Uw#Ld&|OJHif^dS&{k7vRJ{(=NVcx7!HWS2==o zWpQZ8oEl}OEbnqD$uc^)UU}tZt+&Gbbd2NZop;`KzWuv@_wTs>gMaW3oSgshKmNzR z^|$`k_3PK)c;gMPoi}gZtWSVnf1RUrUWTt-yT%GvuU=Jy_iCY#G4Wq}?KNE-Z^%y` zKiM9CcnM8ehvO^1YEtv#Cy#A8{TjviJrIs#yypi;`%m`J)T|g*<>~J2?cqbF1?t2c z-)2ju#DVaEshQHL99Ze=P1dBXPPe4OrTQ~?rp*n^d_8~mEVm~vTlM=XDq!Xrc!`te zCF{OBeit;*=>F=j|9WU26ZHa|F(^W&RL|h{pe5IU22`e-vVsv|+A;Q}v4JVBaS!mq zkAPzadcKSyL3E=bW8#Pax?|32uIa-GEr>>|Y=X#IiQ2>~1V|_XD}7AC2v*A(nszdb zg3EbmIx-Mq1;PkWAcs6hOg({($-Jnuw;d!e4zJ9{`RqVWJ6C=*(1N%G^twrUzR2jc zYUmBBt6FW(B#t&N?Hi=qh(<I*CnZF`)Upy%m2NbEAA}GNWHW>V?GpF!TMzhgR}X{+ zDKF#@KzvF<w~%OUYJCtZ#MFrLBQWt6x%$E(%QY<1A`bego@|)*Om_h@aGfq`A}3n9 z@gj@U5tb0^@R-&jGO+RrnmljAHzIB3`9f5zfpim1Yg|B%DVk!8Rj{BLJFEE3Z_q$H zb~hNM)mDrtL6kaNCrvQ?PE(^%#<7**M2J!w_XeeQX&&MT&S562=D;*An$$xGZDc#W z@#GxF#K{#p3d=lbrb9J(!F?q&mf+I40lOpO4wARvsU0^}x7GRp*uSBSrtbfeu?vXa zsRbm{RE!14OkT{Z{7W8FPLAr>6RBRzo*lSdk54d9j`LSx*H)c=)5nq=1x#cZai(8K zoOvKric57aVS;W<$(sTix`na+=_Eqh2w^65j%Z4^VK2ZQN=!JtIehToLFBAOW>uSY z@d_)kzLztr)hSH1$cgV2v)(dC-?NH##q$*3QXZ|Eh|NtCVyKkntqNwh`jV`#KR<ka zVET>@#YYy$LJm{?i?TMsXiiofeYLO5jD$eY?SYR$*GMy#5NON*kTWzc1fW6I2IHrL zivYSz0Xa&tXf=Y$Sie@oD3f})uZwKYgYKwhB17WqQtBoe(5N%<BSTCn8)&q)4a6Pu zJTf9c7|CmaI@%oJhe`P8wvp6xP-?|Vy2!&)ri@7CW~r@|<O;Vy`0yhA)IWzdMOb3C z5>l0^ph*_pZkO^lQvZ3x>nFz&zf<?T1+fCXwrOc$&Y2^e^GMhwn1sZKCC70}UH~*M z=fS(mx(Ji!S)Bil>52UU{z!3ZQhWsZ2+OEXRi~F9$a0Gi$Ap@<KdTpDxgy|<iJ8hi z*sl-R@)k5dwOF;h6h>*AX*mmUae@UhkZx0ERW>U)vNpRHEf-*Y>r>tNs(^}+#h`E> zAD8Uy+qWF-8*3ZeTRRUQJ@A_P>Z`B)qkr^|{_#Kl$6k5`_~l>z<<EWYbNS7ew{G3? zmg|M~&Ye4-{p@EA&>j3UpZSdL-Me>Ref8B>UU}u-y?bQBm%sdFlkkNve8HRQFaF{$ zK6>=1J_;Uxgikp~;{)&<Zq`gCj~>?xaQ&!@o7DKD#9QN#KYVud_|YQ;yGg0t04eix zuVXf*W8Y-zG@Vm)U60qb8#Fnw?W9Q>+qTizXx!Mg)7Ul|+qSL7jcxngzyCMByEAew zGRC>sd#$<VoR9G2$rsJ?j9or~orr2YInI?CHn!fY8|KJd#{3k+uGig|E4(<iaX35b zWAF;LUfnOy4ibL)AC3CuenfcpX0a;7&?99|i|G~Xgp5iEBoIH)d}zQBTFjzH8b#_@ zLY6b7FnbGkgT5qs-L?qkJWV1U^#^UM2qFu(qcL_l=J~U9l$=su{3xao4hUk;lwPVU zi&_u5GEoTf!@t32GVyRu0hQ)ZrKs%{63gIDcpuhbLQ1{e_M{oj(L;&Nh$H@#!vS2p zb<FWa(9z;(!v>skw>U?|2qXD}aRv*kBY{3+3LN3!_`1Y}P~ePFe}i?V<4j;i457$0 z{5Nw+gQO5C9mLWm#gV;Nqniqe+LRkYkPFw$P3k1LBoeh67SOyslRjyM4-65dE9=RE zCX8kA>miX5f)X$UVjiMonro-bB7HWYCNDcT#{85xB%4V%6`QDzM<BnJ93YPb4Xt}$ zfXGx4xHgJSO2X&&>_&Qu{=&K9%Lewr;Pk<-8?EEkpBv3l{Fu=s#-DXypMxtW9KnX5 zM<|Z%-;2(jl~G|jyx-j;h-4`0Bi*HFXQxNW&7Zh4wm*6G3>Bm@JzcByg3>T4)%Q}_ zg0p0nxO$0Z*SP;~&_X6ZS^v2A4n|+bOb>x%epJ5ThWPF4^5nIIt7rCT$nnPJ2SZ;z zVf1r%g-6>)Kx$fo({8G0V(iM2Gf#61p?)7c@(m{`X|)PHD_0PqdPp(GjBa-qy`2?) zlgj(seC?y^!DLi=Mbb-BNy>@$l5YLxpXFwDCP3#tJYWUR+ZjA-_Ye-JmcS94FL-<5 zGUb7lEPYZDqJj*3!9Xlh=9l{<D$dZqU+2hsU~2ffdf8%CdY$RLP5jXY>^k(tv9UIH z;JBjsjTQqrCn(Swv*OP8G?dDtVVZ)u99d+0PX7ek4$xR~2e9attj0lVL7B`UkIcqE zdsIQtja)+mlUPfQ?#VAaVT<YEyl|-$eDEm$?>r*8I4nOX1<QV=h~GmOe}E@E;IE?R ztr=**#wE~OlgWnh+V%<_WD<|%U>daqkNk*8wuya;g|QOW>Itt2qM*%tMrrfR?j|mD zP3Neou5*$3lalhg$0UC0r`NW<Fz4+9Z=nWr(Ue+~Cu4N>yhyH`W3~G$%NwM|Z-eav zHX_1>9FWU`8`lDJFgrs$b4n$0pH8L$vF5?~Q(mNScs*v&*A<h|ubd9aM#SRRp?z>Q z_4Y=cKI*6E8O=u<eL$1?&HLr&zbKB)CqVHi0HW>V)<^p9<-YgRpU(o1?5~}d-j@;r zFDN&kAKjmqK;75};5XXU`LE=;`#%}^RD0_M(0iqxfF<P(z=4Hs0?3UP0OYmS@g3|I zP-orlu1HRu^dccdlOWOV0sSrd?){pFVqG2b5wW5y!EE><d#ES_OsOq6O)t95`H4Q8 zI~R&K)?#+YfLpSiNA82uAdNKexv#X^Hm179Q)R}?hrbJ%>Nk#Omv4_)5a%xpq??m; zB7EJKGH2`a<*vJ;vI8Td|3IU4)cNBGN<o+wN>PU21M2RLIM6``dm+X{Fd%a(^*>h@ z%uss+p-27{JhaxV_ysVOx$vo?XuaT;qdy!L5X|FQWtp9j1FD{co~%uz$xWrylOZXM z;$gybgIlIi_`sEQ=EMa@%1V43BF-xPa^cASS{Nep#nuM^^b@1GuG}ef93dIaS&2p< z_FgX<%Veu;2o5&m$Di(w=MN(!Xz2JZ8jV59%4J=E4S3gb+k>(-j#3k6hedO^VJhJx z5$CBH!AMv^B*Lyd29^f&B5fPue(rj?)9dVg_+K&erTF^w!on#e)mNA-3SzLli@`Mt zG}A+q?e!X}sju@pZ1BLL_EPJ71BBA<+JeMk{g82i6bGqd2)<m5`s9ya$NhP%wUbC1 z{uDt^bBy7|26SnJ>G<jFDDhQ7{cv^BNe5?=uQbKLqL$5k;fUabgCi^$lUyS>6i!x7 zwpzB$snqA1biCl`-#2Wj>fPJuBQdjj8~EakBN2L!AhQeCM0sj?+RoFikVBArxMj!v zPFe1I=Z;ByMD5q?rM37Zk@mQX(&)p=fn$dlgSf0-!V`^6EIzsVWc}A>f)K?Ve&Bp1 z3+ds35A09MZ$%~0{`<r8Mb&Gwe|bHW+I_S{+Wq7`uGhO>(aWxa9_C{1zsmD-50%pN zQ+@uQmC{3dNVPM}B+d2suCtaFgnS-_H5G9rZqDj1ri8{bb4FTW<GTqi(QF#y9Qo$o zgEwxv+B9?Em7_U2oIkSB7rN`zw%Up-A2*!ck;w225IPRF_l^c2B&;=KI4|}gJ5fq} z1hxJ!-LmOf!?3OWstrCXSJ6(hu);~AiZrEl9=yK<&}imEKO?ys5C$gT4{$)F&tdK_ z3_KoInaBF4!=~3Asz@Z#^!-++5!K}cne&%H@e+82A+7NCqd~t9dg+7A>xxU!Zh27| z^8$`qCCmq;iAd6y`rQ#|_oM3eH4<nj6z%TPpm8D6ur#O6lcwyJm7p5m>A`bA=ke^} za|rSFXX(O;AffT+?$WHUK`L|Q${&X_aVaw*Ho_RSGmv}otlvvk+VNK1S<PUCCj*`E zwt0hWr<7j7JM4(`!gj9#y0HcD@TrTIVT9@TT+uyUCtcvC%U$EVykYSIGflFwgH`LG zUzBmSbi6qV=|M-t!s0Yc)btoGe(vV%1z-8ni7<p^ltRKE>3DbNIhL<(${Fh!hB?gS za(|L^eVTaLadSiS9~;9!jf;{}&*}5l_hWj~zq9M3vHJl)RJ8u*h<;rPzPx<jyd1q* z>waGYoFK0+%iZ*F5|wLP``4DA|7HKGy9Azkk=C7L`#8F;5g7WlE+_tzX&;uF3Y5uJ zt1N%XN@CQj`hq9FxmACFXL{yf85osXc<K4#<(wS^5`R^vlUw9g%R|C>DcC(M{*ydd z(ElXyP<<i9=Ip#y>3bi?;NT6dzE}`87+y)8mzyn4zt~J#r?$sSm4)v<hvSR?W9a2R z2C|pSqPe-bN~g1<wUOlGDGS9?|0ODCb_=Y_W53S+Axfg$R8fD4!UKFJBUf$8e?l4w z)aH&j4=W#-FpFxJx|5&b9*(RvIlGg`;xUGv8~iOo3g3aW#8kKf#hjBm5W`xulG8fa zDgYfB0nILNVG_Nl#uz3o9v^`#o$F`~vSSBZle}26{7a@Robnt=VVQfTcmSkk%59h} zFw_hoqU5VU`2?A3STtyg4jShp-&mcrr4Q%D*e+)_1v5sW*zHt3k$+_37e<;-X_G+i z7xg(En(Ir(A)|>ZgjL@#CleRj#dFh%3IxcdbLF2k1-lP{n2OGdo#C>+lOKny2+!zR zKlxR&eV3;4P@dJ$#Fj^+UdfNgIxolaFJQ-*VpE!t#M;LvTRY|z6|7Ri91CyjS;v)Y zQcTX~#~+cL7ar+B7YYjcx#*IWmev%KLvMOR;d2MZ)kU4A0+EIIt8G{lGQmB_L>P_* z*Uon?X>b%GE8W)odM=6~3N8Ul-)kAGWzj_YTLnA)m>u2)XB{zF4Po}X=ubBV$)Qn3 z{Kk7vwxR9Zj0B<tsDv4o7@YK!tTz26hTixSW0S?Se^45}Rmr?QA*b=pymdvMKAhg} z8kt_WvdMkO@M;<!hI!*?w7B^7achdl(|n-lwv#0S5_3K*N762i@Bavk4r4kyJAoA8 zueix8V6bi^F;7ZykHvBs##&7(aZ{Dc8`e@c{M|njPZ9~XWCZ(*D`uGCt3~Hf3aRU2 z?fVH0HZ-);EKPB;S4BZ2;h-p*4wlAg_e;7FMt_zRM^daZ(y)004yfB}53ihR(vH`F z9DD#PNA<id9Qj}1&+j79N%1KbvT>`BRsool<59!`X?Y-bWBQ{2w!UTH2P#!8ycb?7 zs+Pj*ex(Dmm@*=CS3+=7ztSMV1?a;l@A3Cun@7ry<CT|5WAH4qcg9d;6OdU_o@xR_ z%lOP<J!#Fixai5NWm$vJndG7?6#OWtig?(4psNJZ`;y33Vp9x`w!H?FgLIoUdzkY& zNbO*$-c{loV?6^*moW@^IG2K89;Du}W6GiHGut7-J)3Efci>heo=3n$@dyHpV`HbQ z6V4Jw<`mukPf~GXMmmzO-yO8_-e5XRv^$?Ku_8y&pd!0f+S{Hr^zOZ95MjW~(>pQk zmx4?4*RfCYud4!hB6%fMC!-t!JlEBFoe#aQmy6Bx-ETKYzEAy>3J-+*UcmD0lQ6U~ zX5DA+@%iC>*`M?Ib|_{i(GDbeSWYH6w!Q&YvJHy3AE(Y(^J@&9^^d@21QgPBRkb%g z8rpXMcN}`({OE$)jOv-}x8htsp?BBe(7(^f1cF;rO&#LVYwx`uy`w(}BI}5a)#5Oe z>zm!e#@y0+Cez6rDBPK@Ub4uHy=31+ztHroHlr3FI_tDvE>|b~)8UxEK4nStsA=}y zcku2Rrw(x9gh|C~W@>wFsWcW1`mYyp=<P|P-Sbf%gM+vzKf#E<&`&DEf^^rsAPDy^ zpnBiNN^J+2wsJWbCya#{zX?wcgX^Hmy`c*h@BPk^T5t%mOOM2SY_$@wm{cKzPD}ho z<@)mDEDfzN?nQ+7DnC<Vi5eS0NvSL<BpgmOOkLI;vo?7to49LnU#3TAEMH}8p(lk( z@}1Q>qJT+!%PUSO|40M^2t3;47n$n*CQn~Y&r~!IPaqd;>Izz#CJ9UBlzm$HqVx?t zjjcF{dDCtHsDqXRLKei1V0qjYzlaTn;LQD?xIw1KG<>EN0O9LJ4<xzQ&{nA)zo6CY z+&{|(T-$Y+M_XY-wv2Z$gpeh%N-QALiyOsd(#~W&=#+I9(iT8C@*u%4>XtjPEX@yo zo!pW04>LO@!Xh&iwu>Cd%(1(u3^iF#s6QjVjL<>I|C*Ae2#yjGSN2uPP}OA)6GVc% zU|tnS1Ilqqh43Z(nT3gouf~EyD9{nTp^_9qt3R|zs5H>H*k)Mmt_F3e8E_r+)r^hD z8rs|2NlJeE6{DWUgQtpzC^zt+In2$PbCJd-s6Sr0S2CdS`GgFO=|;e#(OtT=>3MWK z%@7yVj#pc<nTzX5(Wp|p16KWG$G;R^OMSD6(|)y<&M?zRr{g{MCND|X|LU~#n;sW1 zCZ8(iJTGqp%^DM7uf7XP#|5OqNfj-{jToD3&7_R}s#>n59l{@6ZZg~#ZhF~a{822= zh8H6wguxO3k#LBF`!ylBZ&@|4zoTR5cdeq9^W0;D5vm(lQLFrwtS|=4k`^Bz4)k52 zlZIKxKJm?=7fd2w8CAmItZ{NAz7lz*7S3I#D@6_tZddU#>r>H2yvKs&he!6P+s%&L zrQ)-Qq3&B|rE!PD>!;iUbyzsLxGmUZX}g=7K7^Vl&j<gA3l8wKhT=ta_8J-TW#MG0 zBaK4(3EZMY=bfYai*|GOGeDqJX*uNdD;8K;j~@TnuTuELL9z5s>T7D|a*otvf&tL8 z%@~?8ITu&uiXoW%qC~<=qzMI<v>{*aQWJ56I}99HduCrKIgj+7kn|x}8db;q%vU+Z z$u#P|3#I@pcgF+#a+=fotk)`QtcN&}I>NXt>ZAQ;M)%6^^LHDc7~iais})&9A*fK( ziGUIjG$VV4KnjIz%*Tt{TwB>P98|+^nI{uaL^%l2zV}_~pGORD>Uz6di55&z`4ent zl}m$$q!#ZqL}-dzkH3CMhZWx(^tZ8{D)lQAev`^ty?_c-%Bcs#@|+MWoQz;NpB{4a zzx#Cdkm2iFAdS|<VT)9v)XJLaw?r}9<5e~^cv^YT`*jLeh<ESJr|^*7f@Ni6t=sOC z<?dxU9oOm-Xn!c8c%{WJgYPJ8w>QyFp_9=%CR$l-y&CkPdXtb&ul=LFwbevPPS884 z39432+lhA-FmJ0t=#)1m%_7GU80op&06F*0Mv+@H-;a`Al9N5aLD=r#{D_w0C34dF zP6^aUUmo(mA0TbM_)N})w|`FUkGBIX4Oak~^BhRz_1U<r|9;TiMe>x@&LHJ}I3*K3 zoY8D!fU5KIUrKiPI!dAA12Fh#(<|3Bs$S+J5eb;K`0R#MDZljYN+1!=E#_oxVf$iC z({d*_v!7&*jGh@xP{(crW;Ph3RqZQbjXD)BSL%3`l-JDiNK$3}$<0XW+it0^x9lV< znS6|t85@k3GGlvqd_c_Mdz|X7SN4?^Vp_#tz2Lmte6Z$nSmf<OS>@@-7y$~=#`}D{ zTKv<NsAq{Wu#B$^8`!KNbCDu>g+Ug1B5BIE0kJaQrEd)6W{EeJhO_viE8$sQ9;7+a zM<`^JDC%GnxYfe2M3*QWTtlx}bp@;N$>eWI##T`vSSyTJWSeQ0fKpu%1b4rl(XjQ- zRPjiYf8VH#i3M%9I3r(pVY!y#ygc^G0-$Du6{XBcAU6=w3~nuscWL5MjW0+F5hQqW zp#MNZT>nC7Z4Y!yXR4HoC*KWAILwA50+S!N8NLP4(dmz%nim*K<3+R25=%>Ru#{%7 z|67xN@uQ%-VzxkbO|KvTn$Co{qc1wL;ABP$Mi+46#I#{i73JrCIv@0=R3N-G_(8Sh ziAkAvE@6*bZ-bLOA~3(%)xo0KstMYWXf}_ccyyo~iIiLD(qeuKV6HntF1KOTByP79 zrBfWjYMDp=dGgOuzD=mj;ySb{*KYwip=S1*6{nDxPKS>Z+|936<5Zb2GG$Uc`P5Y% zp1N;gxZnBEgC=S%k$VYDWM%!Ke7UtT3krn}zMJ-m=bV)WIk=X5MC1}bwT2GXLKNf0 z1}mv<MCFNoclT@$Fdq2GF?Aew3?^Ar@Rf?2#qbogn-#=4DP=Tb|Arz&UwX{sJPS(I z%46IW_PKjv683`O>(L-5H!Ca^0Q08}zJ{8$%=oh3-co_uD*SAl+1#eU>k+vXdJH9$ zt3FbrAgO1NwLY9bBFqSLF!FX+yMhntQOUiVpX9_xqyax6BNq5H6zt%ZM96ZDLTYAW zA&5hYme{+<{--3f*02sX`|GWzK9HLo1Ph=yi5F+^Y3rfE3y*xbv+zDe#{HI<bdsfD zu{aV=mB_g_05dXc4n`;W79;p1)V3kKo{}ij1GYpw23pn7hQTpa5WBNLutxUH?;t{; z+DWCoRfHiFO)%N5TS)&qlgy}RPdPD8#&LklWp<;#GZ#it41eggkAmy?u8%`dcCG$< zWwEK9D(VZ_Xwcc=&;YiiYb(K;wN&>4pOIEaL7x}m;r+xcSc(A##W88-WBzEL*b+s1 zO3?*)^l6s3j7t%khTLzpxcMSxFHg!ZB%W-u#JCpoQ8HR~h357xf{6jkgPcv~awB21 zf0)@hhL#c3fyJx+0JE|C^X{aP2GNo5RRPe#-8|o3eLpX^0L#IDF4K;2Z=i+;*}tIv z`oE@W+qWUx^$vFy{ooFd`x7&P*Og|V;P>HtO|Q)NIK}5!Ip-zORoEi{E{cpIq5pH` zsa`~HKC2Cq?fd9;J5$$=LMe@mycmS0ekFri05KQ49C3qS4hh=7(S%{+xIvPZ5;un{ z>Ws&@^eC_ZE+I~(F~P(juYbo-d7d?HhD#=>)^A=)-p|#SKOuW&Pf**isk+`W1PT=V zs`cAXKH;qpah;L+n12Q{ZQ85rz-LQ^3ynh+AS7UMb%p4rL5X+3%$jA|7lPen$`X+P z3~t7xL@FdZMyg7oj)5E=7c7tvtT_<ax&?nvG-VQ>tqa}x3e*Rzxw1u07qK)D)6dL; zzc6Otdp9x17D&WeR{2MpcI-*Dr+R5fFXvubei2}EdTRhflg;|7mDb_a*ugBj(aViS z3F;NbGZ;c_Q<_g`?7$@v)SeF>!KscE8lK1{ZlGExC8pt%BoI!FibkUu7OGy=A~I=H zN^lqA3~=JhbLPQH2Aa7Bq*yD>b#~Yu2?n#%m6QURA(QTeUH_(nS}#CC_<>#Dj@^YS z*cB4xlEKjgdX0XaW`>90^YigDfJ%6wQOyRvi=t^F_uC&Bw>`mP(2y9Sq2>LYj4)h` zFMy6lZavW^rjIh$BI^1fnn0h&JKRBML0lTRB$38>ND_cKENCFB&E$A3uGXQJa&z^Z z=b4S?=pDD_byd|}*6!lu)}YkwXJ62@<>m#`(KXf8S|nXg66m0G_Ls_LkNkBw-8ay& zu3lUJx^d{4UawwlFbWz)`txb_N#YN7@=vch&liQ%myZ08iOVND^S2*cFHiY4%MqmC zf#jN~{d=v1GSA+NTRGv?7>BRN7IvZ`p+xPyQH8D)>_`{ovQ7*);QKRP+l!XLy02N7 z506Wr@^m(D(3HN#=Zm(X;AIYqRI!0zd&h@DeE{$*=c<=0dN+{=FO8N^Y-{{%W)^&Q zkx%IXakCi}lTlvV2CI_SvR)171-}a#VVav=nJ;m=edBbCi^Z2C_5+FPcy%~o7df1) zbnitC2xtU+9xC|Vd=Jt_#{htg=5o|Due-4aQ1Cm4&iSi?J)my@A4^BBxGELju{%N6 z_(*8wCrNDU%y4i;<V?f$PIR$6E<kXfHIJKTcVZZDSH2~KJZ`ExO>5rg&E>Hr!Phl` zZlk`eBN^vAD#^WkC=u?XAjScOqqPd*h+eRd+++>EeZ>~{3y4I?w@PS$%bNigC6X-z za7}vHP1=AJ6y6TrV-;S2&W(=i17oK!Qk;~Q?s`O-aXNujM$~7v=hVx}J-4zl6K+>| zeV>bjc5&W(3RSNVX-eBMenvzgte5-z^g<<AR}23mMQ5nW{nBlXhi3|WBk*uK^K0Th zbM#kxCC5SRTbL?>7ZlGi6Q3cCX<9JOiv}4z=dIEsWkG5_^@81zcPH1!o6Q8uO{5&& zvJ~;JggFc2Cs7&8oh=?F@4@;{!T7tmz%2_{)dueJPoWA=_n(16pSKc$cZ-s(t+x!{ zdCwd5t{V(UCMqD<c6~E`Z<d@1b>a?))#~a?9ZK9GN&3)FCv9u~w=ZcKA8llJ&%N_z zHfa|(Yxe}T?G+cnTu@??<U1mW)3Ulz_Sf(SUtF*lm*U5M>{h7?_y#H~JCw>>=ml_w zpQb4O&ebQ1UB2{^Z$RdaN^OX`_n<|w7{48=ef(OV71O(}PhGs4SYFAvyJG6u-h~}? zmDK(2YU$3;elkrQ&VLW3ROF@Xs{^$`E)vwReaMNJF3b2OU`6;h8+{LMwY%ULak^h* zDMCIND-D)hBAv1GD5uw~Y|c^^rwL@LuB=xeI-{*WKR8H?Ncpbc_60}SoPl^v<9V(N zrgq#So})|7#$O6K3BsS^8iwr67#yeZjt)Xtcy!IndN{msUMRp)Bs)dah+hQsU1UbB z#Xr?gNl%Db1~WgDg=y#unM!VN40FJsFlK_3E1`hbEa^lN<O{n{N5d}=-Nq6$(_k$d z%-3sJl|MYokmhM`S1c})e+(`piQG4Z*BKyBzgw5_rXQr-!n?CZ^6OE@U@`iWDl;mQ zrjiRMYQiyB58ziR=OZ?vbG_y2<~~lx^KY0dNtuP7;V%`VknXy=il)<l4*<<<Y;%~1 z%F9AJkPe`$w0xZ*ZSZ8=k&|prB7t7thb>E-EwY^gu}5*Iw^CWl&RXIfus}kjNf6K6 zsac)czf--%Q+_i2!nJQ$p`)scp9`yX`>pKq6kbg(0v_FP@XKSRr_d?Iff523?+|w~ zpew`^6_cWRn^M%4C$;ft5~l^h#j~x9wwV{hztqmnfBRtxp2U-efsd0nH|;ZSq7%g2 zTueh26&_NctQ$nBkR2qbKVSRAohwVCuJ?&>B%l70T}yz(JyzTb@RB9q7!YcU<B3~k zZIi8ns8;LEoVx?zDI5I{zcmbOkN?oV`TLo=rvYIcXRpEM1M|lX_SSz;%Lr#J2CEpv zdUtCc)PbFWhGZQsZo!O}DHE>*OD@wv%=QI=an^2nX2eVE@83T$%p<i>K$=#tA0<|- zKniPwASd@7#y|6>_+w_GJ+_KHNiZc5Gh`lzk%|+4V?tyGBHZXeCxe6o_1n1u9M~>r zSw_|41$Y|sNQYQ;$k0{Gms_lVR0D#PKt;!ORO!41DQi9q#iHVrw&WhYXQ}R3hX0rM z!WRqT1>RMCFeQaK`0%v8fFu9RLNK{z8SK0LXWKlJ)bV?h>EF^Gvu~N#S=(YS|2i5K zLUJQCDsmUHvgS-3oy^nl!?}#DWN^Vvf^?|jcBdf2bLD!x{0(5t-N7g#_kP3eDG~VT z`4uc<jpZH0UMn4ay$9H5tHVe{?%gKboNgyuFGH)B9~YM&qd9M*0`DcCcaOfGkDued z&kUQ+pQ8fLlv{5H9DrKf2@EWs@BbnF{`ckQe*?_tefP)mrO#vg=fTz+-pkf=*4FbL zrNFb9?}J%@?=Iff(|>{dw{4=2?d9%|`)VLKvGqLVO33TR=)-5Yc*Hwm2ft#4ok7}5 zGyU;2h;w(rEbTz+DHg+)@MYJD>YHSuVvvk8)<_`}4s);JMQjOC#e4^vqwH;JJ$La4 zXog12!se@eil*-P?XL}~<Hg*Ag^-+h<aHvz-&5>!lhSp=@<OiB-p*6nwI;X`$atKh z7&xw`;f4dB(yDj=@5AidkQBhSv!0w3hJdkzO=l^og$m?}Ym_~1B21mo$~Tcm6Y5F7 z_!|Fb76*)r4$-NZZHZWzwX)g3crS=lrZ5C>L@RP2(Faw~`-BFIhRNo@2F^6B$O@$j zA~~9{#=0Njgi#5PoTL7AFU>T<jQ*0~?mxylGaK+7Mu++NSa|Yjg{uVru1&syujpW= z$v(+Jy(e>B2$$@^Vl$hFzA+ObV%8-SH0zWiL#p0_QsT%K3fG#?z}Qk`!3V~odvOpe zn`$d;e)HcF6Q)io!WHvG2W`z3S_>}0!YFRnR;nc^`FEgX6n|(ObpSVr=o>!`g@3qs zGl~gkS}6HISr(k&K|FW_hb)<~f9B2_`acL^EU0bPZmyvgV+4|OyQ~UFWn^zMTx*>j z8lUlgi?VKf(>!ixd9PjTKgu-nu!O-mu(C3Ff>=VbDN50}4koJoqYXv#gWu*gwiqqs zs~>k?ROeE}EhdrD)Z>TvbS)Nh;=iBsU681UeHE6!-c`w_XEMhjA#Z&XGL-cqM*=gq zOBI|fMJ|i|YCIb<N*;t_CVUGs^6SCQ?_co+;cRBdh|owZxZQ!SW<V$s5#q8|BklJs z>Mx7N)K*Q<4Lj;4yHK`c|E;*${20-%8dF-3$}B!E<sa5IRwo{8ggJpc1u^h`L+PqB zC^`)wQjOVOhO~BCa0lak1k@rwKfUWTCW?T@n(QEymPB@#Kl-d9h&UsxASkh`j=mHt zLR#{4xt(kBYv6{wP$nvarhJE=fpZjX5z-bl^c!_9>HEQVo|I%yPE9Ok1VhN|<N`+& z`u{(1Ft;YJI%H>knNdqsft$&Qolr%v`VvL)_N9I;2e#CV%9NZRj~dt9g88ioyZ`=k z18VfUC!=z*PV^zNJYy-;oE%MGP0p|6RnTFahmTe!(o_BuLqM&<9H~|;hOKO*KeCdY zu`m)oRJpzQ%1x#(`$w7%^3?BxP>XmU<{;nA@vl5mW^pua)EX^+*q50R$_s|l`m;6* zQ5-Cm!#TRZqOzIaS_%MvM-;6v8Eaet79^-GS{=;&BqChmFt_y9&icG4MUR`G+vm85 zXLVy^Tw|(-=;H`TKA(DKbUzI;w9SI<frGaK6M(*%^bUOsSMUPg2DB|bOg+4(hvsf? zps>aFVfrI&ErP=^GxCS3d)#&AS!$>I?b3TF68fG_IguJ6QT$<|TFDt#kjeIi{P6qL z${mX|Fqz95?N|y$ya^<LM%FQ?Y!O@@>Ozjs_T~SqRN=|X!GQy?pJYLfLE`cmIYVdb z7Za^O?MoX!s+8mu(Rh#7PHvxS$o=Zi3O&DSol;wl6eA_th%XLzGHPV9Jf$Jbj$mz1 z21*UZRJ%YAET7g6y0f2bLQTT28Gws+A4KjwY}M%zVEjXnT@>`gg|!Y8)KCfOxPeP2 zCp*jFuP4rGPpoGo+ej(<RS4nvhix74D7JnWprGwQI%@V9myQz5<B`<#H&g^js^m$q zveKnd2@BfXbri|?#nmH|V@aPE5`@8skEG{6LH($cKNBOj4q(dV?$E(IPOqW}6_8-P zb?KtFhY!k!u~tGDsfw~l<cex*xA(s?`ZXXr0>RXW-P>^2zkBEYRgNRbX?KlI)R$04 z7-W86U64efxONO;a`pm82x8o#OH_S4y9#K9--z-Y@fy@56$HiMk%`F3&*xi^7$Ah= zr(ftK*vKNgx5(!)k~ox+OQ0#|!rdzNg7h<tcj!_bMK!6g#JFb)_D+9|H6qW4F(FXn z9zE@iaftkk{%a<P)74bXc3bVd@b`-rg{+8Pc{Q>^LNd-j@Q2EaFm(<}J?gF1sx3(p zp(m<vn7N{oUP`}{J@OgsiVjG_g1tE^Vvl?I_xb`yJ7?=_F(|Nxwu-0&k-C1)&Jzh; z4JyZzsZe~miqyE<oq_S~$TNDGtrAwd659cSqfu5b0yQoAyS&=sa&l-#{lGCbs(m*i zD8#zCAR>pIBWW=F#ztAA?T&6US`ra2izDX*l@#?NZ0+ERk<@s4wqf0I*NS40>aPk& zgGt%B0rh3X-fLOM(<M42DT+Pd8Xa*LYbL!*$owcC5uS@csj1`zK{B3)Id~XCh(N;- z7MmxAN$ETnTQ5sRkqL#+U`L|SKIKF<fl{RQU`{%ry>uI<hu07<lS|_nf;LGk58^sk z_-gN=2(u<MM?S+^Ayb^CzDiv0LAaS(u4_O~+2wpp+iys1pja#&U>+dVcy)q_UXV3> z#tuFJ`vYqBP34J(hh1e3<v>^+TP5B9D#b7M2lO_QK;Q8OC3x(0$rL=<@u0h*Qr4ip zobP5?_H!&sU+r+d|HH}T(D?Rl5KgG7{~Q~=iu}z;Mb&%sXs6>o+Rgk$e#d`JE7JIf zx##H$el%FBonI96^_-Tn@N?W4bhXoNF3$O$*AMw`|Mi9<_W$?V2aWw_rU#ls&vjjG zZ7<K8x75sh@^bwWtGixK05E;5t@8)qr!x`ySk-^Ed;(0<@nSBIrNF$mhxNhd^)w>6 zj#e0mZ!fP~X@2|*4IhN}o8h~eVlVbi!+t|rj{l2$f)h+d*;vUK*HyvvTf%Y9@-w%b z?a!siD0hg)*<01rjNn_c7|hf$<)o$a{!{w&RGYZA1B57;^YQLy*HnJ~C4j_4ufr{s zQ$SZVy*3lybx1F5jqvEy6|u$mZ>b?khP0ue>R%kq1$ci!g`;bjCo8gvPU-}%zjzNl zae9LcJzWV#9#bFIPgp1AUyL1a8whmLvLZ5n&IaB0>;hV`YHs96H^}F|(RB!8dQGK> z;b}3pu$`kAFvI^HFvwYf@~S5iTtPD;HZ;_O5{1zrHHaTHRK=4!i6jHcF$8-gMgnoM zWH*Q%z@y<!&YPZ1G>GHKL?O<TYW9kBWP}24Uz{dm)POobU1wBO#+hK`WUW+*RHJbA z!E{|J`)`H8vJ^9gsA0dWk|)v;b|><M3~>E_WBP<5<VyuP@qCSK#IHY^oOOwHYV?~Q z<BFZ9&}x$^T*K83I#aNY{+If5ks>UaN3=SlDG!d+vL7rOY&g8x04iL;oDX47Fb2!@ zT#3UR%S2`}k-feoYaW-C;2V7`NT~s81kE?IT9iy%_Dg!kN}(Y^x8&&Wv4^39rH>Cn z$Mqx$Mffm%4BB5HFq5JWLIb}2<mFZB-dlg|S{u}2#m^H@3-_!@qBVj~CBcuC$OO~t zSA*f{SD@@7KCTK9SDV9i0L2s6cC~-^1-4U1?_VLBl++%;l~2rfgT_t2rVNump==3i z{GG{VI(M$NTo6uRvhWkvHa_}oo+1(SQwg591TM%9bRf}&n@kc(^t<lQf)2fY7wu#3 z)8gYOxdolOsVK3OM24^4Ya~9BggW@){mY3*l=R$n<KtisLY2O=nE0-e2hYmwOfSoF zgh8=uB1<x4t<OKL_xTf1PHtYGhciL*qGDmFeQc~1r^TZoOx4y>BLIPv5?a_oY$lw^ z62#OppUe*tQ=BB|H(|I3YE;0)_u8G0=hL!qe&v^8paKJW6pg7^{-Br!T*RA3-xgn` zAa}AGwbl@921n8xz#cdtW9?lzV|0tkJa$~_!`8?BGmi7O<9FlS5XZ5M)#QsQ!uluf za1CpkN#(H072*ugBfgWFE9>nMJ6P_GVH+YVNZhFllFDXvqbkV;Oso-t3=!`oR_Oj6 zl16wH6KqY3fV3zk?iuA|vM8_&!q?s6KEyzu9qJ6QHBeB0EJxVA6wtv)?|vPC9DLf| z{D%+%Jjdz1G9e-Lj8luU7@4t9(~ucjhtAF4A|hngqw)~(g^FAvR40<S@v3#Y-acM0 zV}9aGQ^w@*0zrwP>Cd<6?&~4EO{<Nc!1(_!vjf=c{sCeq)@hcz^*K-p`X4b*>-*Gy z@b}A3y%>G>{Um{>K!GQq|G&_$1KOdQLDd#G>9|-s8jV-FtTUam?rMn99|WP6^~um| zdY+orx;22f8YTk6BPdWXN3f7fO4w{S^rmjxa~B0gwn95}_AiE1J#8QfUK3DR=2KM_ zJ9b}=6ZkkX8l#-$37`{VL;o<|x<NobrFDMUYIA0J_9ONm$Q8vsR(8$x2#N$_4g~WV z`SB}I7TTXVNTW4H`(eH%Rje3@Etd)Xo~90?cUULEKL@!N_Z{tO(+I$h4D5r4soz4R zOX2>@jswTFL`JZTX^!(NTO88Gi^65j>CwdzY<k=NW<`d}WcdrT`60J_2h?UNj^|CT zAuCLyy=AYFgibL4%LE37L%EX19F-@Oss*`0p0H$9QVvyzIsffS7*Ru_DPng=!czZM zB$-ttH&W&VtRUJ4Cf_2BxYrVMD5ZDg#}F>@Z_Jcb>am?(kQNciE2RS(>76j6kZW4v zMgk5EN%SpdDk&|Ao;lmo$`Eo6GpIiJAojVKFg?~#^yPE*!K^#oR5SZ<|Kh;r!jykl zB~EiiGf8(QKiCgWD@;vwd4`oWHy%0gi6$1AW&I159T+MW$o{J^c+eMr<e!8CY*>;y z#G+)X&gCj1rsAf?qEA+V?KnA|-P7%7T$fzKeFdaX!GkxA%P*CNmu3R<IGc`{WIbzT zm>MG!9EqALx8SlOV>VZAU@nj}l;8RWLR8%fyyFRh8>-8X_?hv9tfGljPR&f|he%Hm z7&%G?P0mhubOSCjGD&Ci3^H~}Y&6727&9a1{aPnRYgVfSB;Q1D$R$Ln0A%JaC{kz- z8ssB$!vmSR82Xiu8tUqV*T$PD=l+MWTTg*^8Kf=GBfjIP`+x_i*ZLA0DSbY-BTyAS zf#G4*i_<8k<$ZoE;Y9QXop1M==4Q%fotmK<5KZ=~Ap|XL)zr}OlHyYiWfGe)_PN6v z=#7G@XI9~L+;zsLSa)M^xk;5vkG(w~>Q|_0<XqiN#Lf0SRK;YYo?h%?w{Cb)VcZO2 z>Ce!p_{`Nfl-G~by72ri)`3QJ*P*ei9Il-<G+F!Xdh$wgySY0y%ki~&n#uau7WrIf zoOw_|taz{G$V1#mC-+t54X)^>yspIBz1L_$JP2%F67IfzxHVHKIxZ<9*oU?i(D3{> z_|l#pegEN@&#<}l6v&bF{Lu3nv$<wFkzJhp`0P5J<MqC%uJ3E1r^QHMmUbf7JJTNv zWk75B>)`cfA1lYV>Z~NkYe&e=oA54yvYzIpx%iNG162ac(*MC`*ZTbE%+loXMy|s9 z@n04+(qoExm-owET7kvjrk4dK0OU6J9TD~&cHl19YQR~#w#MNZyQ6hL(lAKmL8<S@ zwYja2rGUgSbQ&9T5PqoV=QR6Q>Eu`|xgt{A%<`u7o#fnj$}MTwZbnRc;p379e?hxu zIi(|*IaRVY)Y&j}L-f?{iKDJxGqfW%`x+j@)+{ixn<|12>Qg1PttcR5sv;T=?${0* zk5j8^L{m7qCUiXB+ZY>87VnnlubI_LBh$KBH`4WGWE(fVoE`h<A{g^T64rduSmX5y zhe9@=`^(Vp6#6eaIRf4x(w{co*n4d?6$}GiIvjj@FI~LrQPfl1)e+h0YP#yXNfvZV z`(K~>k@)|4HTYmZWdWsv&;U|MK;KpaY4hprcG~A|m&jxJz1{cm(&O^I`E%{_JUX{M zl4I?E;p^@fRRP?}+k2a<t2_>4+y7LW&;6~>_pM7T{m(0;&nx{WtdHRTJvW;_v_C8N z0AsPyeg|cHy7xo*^p@|NhU2N+oS2U<oyWW9Yh}rF_L(hA^~Oa6bvN||mZs_Pk!7WV zzzWKQ$F6^~tFrHtowsn(c;)zW`(@YTaY>GrGu-XNT2)JQT&Pqton>S9m)9OS-wmRB zP0VN26c@JoZe5aTb$y>>(_LXY0rh6ogjIE`U$)CO*X0PMgaSVL@mq^Ag5A$4zMmx# z72KZFas}Uv@S=JDrs%^WwQ6<c-$_SjK_)Yj6mso}86DE~e}p`N6CgNj6DK%r*8UYQ z3cdjZQWgeJW7v<~_eXgD!C(1{5bc3rAuHs0JgBL`^@`$E@puS<Dt*p>8mtOcXq5;e z(IAt3LlW#f`0=Dxz9S33RQ9i=8mGVxocLRrf8|EAJDN3RqaG%OflG|yOEJW(b1uHz zb-`~LG5*V@&VE}|6IK?R_Z>-T3i^F!MU|FXo)yytr$>zB6=Nosa4exH=*-Mm)B8*g zyPnsy!K}WREIGLEG&SBSx%>@9G8Vy~m5LQXqH9NR%pJ7ImME&?PyS7UWbF?`vX1a~ zBY!6s5`v?)pX$+dXbhr=Ja>qo7#Pp2rN+^P%x<MdqI4?Uy3-JcGupCUmY>`^iFdkQ z+nLGn!Sp1n8dFO0MM6GYZ2g2>tSM=6R_Q;~b2p9I7YzL&-V`aHBHOo$zIaL}nAoQO z7u7E~1}h7u=;qxoM3<Qr?>C2FaNC=5DvZe0QM%0<sqB8IimC5MP?9gf;P0C+dA-c# z|9n_+-Rh$1eQD3MbyxMipfdDczO1~TB6-ZPHO4aUY`<=paN=-woqu16snR;QnTcb? zL*VARH&P;?@Hm}m6S|e7H|dr>J_kCY#Fx5loR73v(IDUWjxQ&|XxH&)Czf{<@tsKM za!JzjiM*~z0#rW_GOF+PJC!V_a|GUBPALHc*$4~j#)In*Lsz`#Z6x2Bk6B06Rixw} zq1@M?{0Q}*&y^*JRQD@{e`x3`SF#Xo=G`C8Z&OZ#T@9zL3=x)A>EXG$N?0uXWk@C& z=L9~UcBchCb#hFhM{YVEr}~|BHY_`?x*spJ8MfSB&K)IIWUl6`yPxkQ1l|tDtGRc! zI<HZmbKZ_~+}h@*U-Cogziq}3Cj3^POWEqwh;gy4=q|s$%K-KnJ~mYa+h6W#^Fy${ z&kpZ{<CTyPd;&;`wp~vyy4tyj1eSJ@z)nOnj9X8{X2vR!m66hzG_XtT^SUJ0ItVSo z+Vf-Q{So-D$7s`yFJ5;Sp0)yB64TSm!=cqgBpL!fcJT~bUc1LH$Suw%T;d)zejW)D zT0?8*++-3fw>*sW=9~`b$_J|CxJE8$QmyfiU_>OwREE#}tr4&C+(zc+jWM)53gR^> zE=!gg?wic4L47Prb*yI}APj1*nP6p?CAO9PA&0M}i02fd1gmnHw<<IZHs}uMbAjBN z3z{xCY1@Um`Y;{gH<|WLe|1A$(3%SZZue$v!1a;x3;~)L`I_eH=3cC}G3R3f2d8X^ znkPof-|KoL=J;cTet4r0+E(GAZxh`5h9Gs$LtAX8D%IQs`tGW~0#8o~wq07w2v}+Q zA2%uV6#1lUIpo`4$J!)YP24!9YJb4QM^mt@*wxbg#jB#T?YN&~o9nc#ynR8*;n-4H zwLJ5D9WTBZmZxzNODb+@xo1DsqFw}K>(7DTRi}A)V>utkIb#5}`EB6q5=NJR(;ie1 zML4o@|3WxUtIF!%swm*TKK=0q45*{?)jV2F!NK>$3i|qqJ~i3HT~9mX3|)F#mEKoN zFLOP^M7}5a8zz3uwtH=e2_Z{m!!UZDrSlR~u3J9CS)Xf%44I%)TZ-=cIh=vIOX}0j zn}61en^LgPFUK#4F5`c>WxkpgVvgGA9o(##<xo8a5@|KxOC+^?w=C7~c%B_5^7>dw z@jWgPV8>EA@EsTUoaTETx*g{Dy#GA#g*$8>4piX(ko28lLQDrHOb;%OpAfeF=Q^8b z2+Ie5A9*oh=<s!$P=&c?C~rq-JMNL`f(fQ@>fl>$B8p-Y1b8eoh~IhTl$xEVIM)a? zMjW$ekWEub?QDB7_*Zh_?V)JTM(k4Af5xkiXq46C@8k3A-OP)KBrH<a9MxOY?Lu$o zZ6oTAxWTg@gvFF!o$Fxp5GU-Ti&2kRhG!x<4c+>OS%DI>Ec9*Yk(SiMzTBzqqQ*N= z2=<%r=KDF62?kx8mekak;hQ!XV`gr=Mpc5S)Nf$(X$LFBajN#Fydkbt^{M0qp_X$) z`guA0YO<>B%#8jSa6xtu|H9Z*_)~CL7L^#U44xHSj*J@Or3TJ-!_)=C!-Z8OaUPEG z^%%lfJX1>BZK7U2nrQ~&^_+TgaOcc~^8lk>%k0LF=74E4%uybkS;Q8xr*FS$`(WE= zniPX7c9vw*-Q!AC9Pc!PNec54R9=2xP-ok<PSBbVm{0RM)m@R2jpeGUuTQ#O&!nT? zaj(n%sFT%(ZtlFVCt$bsc&#>u(MGBkyUe3~cjHn5ypGZA=T+0a+3dm7kL_lSE{da1 z!#9qWro>!1?qjckkxrYPWOLDVp={Ass+Hj!qktQ0>8!)xq;!8rtA6!#oqjBU0%=B* zF_f1s4s=GA^j9?Se&yTg8e;kQeciF@<R_uIY{Oafh_qo&<NT5=mTLjERvrJ#LaGF* zvRdEFH{dOA4%GW(T%L71H+ErM{i}T3^nTh`*Jt#)zfYOVIGCs00$l!U439`bmuSxK zoIUgwdX{v&`LRExHl0&9J#Mo?Z3O_E(8l`?wfH^ZprBD?`!*Wyk8`*n-8%F&k;n4V z6s;m<e3*tabWNZMhDMKGL2AqEy>ZCxJO^C8S!-i!IQA+l^m4|1!u4D{CTEDj*!!Z} z3C4Yp+F*Oh)pN;~xf)_YXtrr5#M0ZBApKyZh7TGyS{97_PF@OX^F*9y{8f>23S&~V zWvE<-ae`C2wso%A(eSJp#ai7h>DvUlF#eE{7Z;fUd0Y6IU8JqhS>DEgrEnFp;|;40 zdHrQS|4`gxWq;tk5o)#hWMao8k#IlFUT4(hC<kv%s8|&I-5c3-KXTN9?+fv&_bu#U zkeU0C^*GLB<*j$im??I;u(YSGiO==T%6thDQOEn$x$6?a#oFc4F@xj=-H-QOtxrgg z-kUI=J$~ZF?@77kbv39R?p~n|414+3&ztS1@^=?)0{m{Cy3R|NF<!Tm%L-lYC#v%Z ztL^3L>zj0))*t=8Pe{HWzy-du`|(k!1Gz266AVa+Z2?EMq3&y2HyYD#$H3>u&)3iA z&o|$XYogEV?uY7kOJCrx@BfuuU!S}JZXw}#+Z=&gm$#|584IVz`gG0Z+muT_j}H3Z z8zm3*{rvzN^Xa0$QR9`&-;>L1x#Ra}jL#hzmX$O?mHT<PXX81OF&|F_spVQt3qt3+ zLFcuW=$o0sG9|u0&v4tZZZt?z*rC=gF2ZB~0asyb3yrIb^7@K^1GkA|%e$qk0<f68 znp6KehR*p=j1NWHde87Zyp()e+jRp|^W+=IBy>ITQMhq?`}r*nuTEshKm(mDJ;*@P zOcQPOPi86XD6>>7S>|&r#~wALz__3l39^4JNpMloGWJ0lBe$p24unbUZ{8s+MyRw& z8xU=X-Qp+?PKkMH8<p9zCQ+t^y3#@Xu!T9nugF>x(J-_K0yusdab}|gQh)C<L66k$ zcI)$$>&UH#>f*t<@P2+ns9Xh2V%s&Dy_}4qemL1M1!NT$uAd|no{e*(9Y!%y>_HuI zBu1}q6SR!uNxU@9Ung~mjY^9lD?B`-3raNd&jlihrEbRLvG|>bQ}s61zJGH4y7yQ? zGU>7C5(#XCOld_=n)s~=GLm)~8T5&?4QN(*Epy~O)@nN@!R_<oW9WoRPuxDB2hld| z?T#V#O()+G7XnVh8?#oqE?nW{QKZA6RrQWZtaa+X-QgHdHsPy$aLgX-;-~>PRT*{0 z{oFj2xgjRV+Rdi#pkrdn@qX`82464y(mB^?_21oHEYK;pU%?z#6iT*j_Wr`09h`nh zXm;vVY5n`4LxVGYpOO0<XISP)F0dE-1AUv{>_^d3j?aL4$GJa{$cXqgR4=dmHeI&Y zkQV}B9b<_}tIu(kzt~fxvO2Awzvi@2V+xDm(WCMZBUE^4b9ZSOhw$i7yWe&50e-h; zRsJ-F!gJOAZgbZsXW5caXzPUMW7p*Rxp}LSGLK{P?InXUhOqnd;)ATGkKsJySVRG1 zFGb&{k-CZ~Ku@0`R)6`F(s9#sx~Brmv$}hPel=vY#%yHI_cXL-*|LP+L|ef3Dl5-N zBl?4|>-2N>E;GDvUM*)yn#H!G)l*ZqzB=~(^z=pNciYlT`I!ttHTho_X@|IvW*>4d zeY7Ral~7yToZUMwzC@{z*=EN)l8GzYWy4MFBC&D3<GXq<1hu`dp%%Nm__`mZ?PQo0 zBkrJ#_SjSTM93;(if)YuoFOS_y;Q@$X_(R1bUN42)iAAShsjg0_fMBF9a?-)9EK@! z6`2q`w7VEBzz}tD`ssOt&`;mh!^s@%`h#Kb?zZD+$Z<}#5;`k><i5PgT`%y!searX z!th;On{iPta0&z*KiP)euScB{mjW&bb`)+zuMdN+rz}*PdLkZ=!r@Dc^DpbS;5r!O zxMg*)BgA^S*ILb;XWAb3&Z=IvzDi7J2lMaIkGn+g0~>p@091p6Sr$?~Pl5k=?-5}0 zeEa;bn2RAtFGe@4^X}tmSl~jtD?g~ExDF3M>V%H`Jg#e9F7ST4mQd(+ujBvNev0^O z<LNv32n@LUZ@?t<2zTDb(dt%}`I<ZoDxQISv|5T`zE{&3#Qk@G+QocXB={#&(}{}@ zZRsB-5#yRe;aiy}dGX~TR`vdp1D_lG{Mp3pOhyxZMbbXoHGnStJdJ;QaJ$+LB|5U5 zysCq2pAO~=W{Z@joX$M=b(Rag@mm@lY3*x~jRAf@Pq<ijDw^HNlH_lD0l3(<201}l zNI3NdO%)Gl=_H6)<C`2b?%RwO$~VIAhp;RCD#J)CB?)ncW5JQ={)xt6jBklJLxnn0 zL7aD-niI|YCcM?C1R+v=7-o^PN`J4VxE;7JVOvz7oz<^QK;;>oG||^4gJUy7#*y`{ z9Q6C4F4U}J@-D{X{F}&Ta&FV|2a$PNA~GcPwqwGWb-cZd6Hplk2&0aDaWhke6-x|^ zqLQtB^6m(GsPZH7j`$Tig5jC+LtGHsGd6wru44twc1?H}dYDI!>&GY|QaI|y@mb)l zrjnx$!7G%(ikZie^mQn?f4|j{{cODcU4$*qQiMB_95<m<&S;#B(b|iO6C$4MOB=`& zYJ7=(hYGt)cegYA^_+eZA{sA5TM|p7IigZvO8}}#+6Xg1b|(e$Y7}H}Jfi#1LR&6V z-FzmbuD3VmK8{?89CYku=sQu@zpDx<7n*M9!n4qE#f?HgCi=x}n1G?D)wl||CRb`i zK83h=;^%xE9y`Mv{-YfM)@d)zqK$o46EP*?U;s<;sUwfR(4ekUBOQ#2y@4JzpN`q% z^>c>I{9Lr<R%#QSh_nj&$VypqN9zpRy6mD>H%o{932waBK1PeDrsb(rz+io>8Sd}t zIeVexO087y;B0%7Ez02h(@)#ZdjK7$t%tzKzak(U$pC{MpiKCwxuw;b$xswA`rAvK z1bsVM-E%I2bdkB#ykk`HK!;d>qJiHYaZ7L7Y<h_ZG}~<?5%2*fm;GAvlR=vEG!{!- z0I#<uT%;d_YvV?)A9z~`FY|XB8+Z}~>t6jyrA^+nbIQFX4D@6qAyegAE9c~f328q) zy==J54L0(EOW203hQX1wdS6F#_$yJo-i#>!V}-&I+2J7OG2)?95xV*R0471%zHoRi zIIMf|t1>c$Yw<41=Dxz29GomEJLur2WEtGH-=~M$mNV{M=X-FtFF34w9Y~gD0W2<s z57$L;{Vn>g1~^W6SFM>Z3wv#>?*Oka$=yI{p>QZreoKGv3$PQ??QGwnYHIyZ%KBS$ z>(RnnTtDCID(8Z%Lzg4UFMs*VKm5Z#bdUJcKmF5w8N|zQmq8hnrVBy%>Z`BZiA0g6 zV~G6um!F%4epk8u0*voIWB6x(_UE5{_SxrOeyIl(y**w(O#OkIk$zk-$z~UHf@#Xi z^}3FuoI5nHev&eiz_r(7ufWE!;QMFFGLpKI7Fk+72*Fv;02>rgF0$q;+RAs&{lO1@ zfb-)Y{}_S&U;G=tyFY`JW)9lgH-&{PO)RO2kR3AWrbfGC0mZOv6tr+A3#ZKP9I#-H z7j~%|ZE&r07fVXv1Jwg>mS|eiUR8KmWP@4_E90e5C1O%)Y3!k>V913pVNngo8%9sr z&R1R#a%dOC0o6wtJwD}14yR67a?vAP*{5y#na~hohK9VPDprOienkh-LYC2YgKIsT z0=)wi$7w@m1Pa>KzJitUVi|oExY_xkZ8Ve$XI4*sN}vPdIS>0Nj1AG~lECJ^B9{c( zHV}WNaF*co89l^51{*Ac+r!()9-#(8EyaO44~B8BN}s`-a>Q)Ruvmz;ufJ<GNUPK~ zgCUTxBNk*xDd7+(uK|9X-NK5pp4)RINv0rM0g5&n0)1#zWF%dYCpJ6KdCQP}`wz?z zAw+{6eFqt5^i4U|zwl9Vb($FNo5=B_w(g6aCN+#e`Rc3nNkxvfVQ5l-LvL8ohIApM z@N_N*u`k53knT*DSGE;+=^PVyW!4X4;Ch9(-jwHwUiV+p?~Pq@!=4X9TzR1PH_B>m zCr1z~4-Q>X!$RQgx7S@0GyBeW%+64_Y;;rD+4_3(a-nfy(t(b{=zdJ<6Cb&>fXQAz zz=8l*%A<GRT}!-=A-VFe?_NH5xj)T#eV3Da+1K}hNw?AhYn2odW~P;kw!Q<f54Ubf zE8hn2kVI<U(}NZEv_uihD=peNxrB4<4C!5t)`w=T571t({e6X^=bmNUUl%A3$Pmnk z9HT%{_|*j^CXlyZMN=AZv`X@J-4F|ClaoGeQ&^BG%`W4R)ljxCxRjPR0w(zylx=V} zrbEM!rR2a;Er<|wmG?^ChgN1qZpb$F6c{6%^{c=`+c+3E^PEwhgS{~pO8Uea4gu&~ zKxw`MmT-)3VUk?ozL2r6o_1_<db@(wwp_>pSHm-2tiOG8Od*;L+0-&#)gAlq7Q6C- zX2`>ODtF&}p$;LP6m`X4sV_K87i7s5N)m3@ML4v(aG&?}QG-=}Ll1{`0q<Iz^)t>3 zEUpROyV#xkP>91f*Sh_CK(G4|=+VpR;^n%9zpv-()pscCQ!!krj<5Xg3)=R1Y32R! z!w*0C<P-O@pZ@fxf9<dRwZHmT|LX7m{_lIK`-{K$3pcVazx?ta{iA>61z3}=hcdWe zy58zv8rLotb1%jpee{teXh4_k@#9B2d-UkNciw(?^|F49=J@Puhe*F#(bYR%G9N$w z=%Ww)dw2iRFYNAC>$5Dq`nr#>xXvp|KH9$(EN4uhuprO<h;h~0w;s2>;gC={)1kX- z@S2?tC8x+>nuQorKo5O?SVGg3*#gp8{`%ki9eoOPFTmBSdy?K%gE<V?c@M|l_qqWt z^7dM+yqAR-%rIpox>zI>Xh@k2Di397bh6Bl9dhNBB+$b_x>PKX9$$%cc2Qh=TCYAF zXvo>K1olB>8B%x~3XJ@E6b1DlVfH(fvwr5E<tXKhHmDZm%*n_SvO5;^T=83n5*oHL zEg(=blEAWyzd9T+c_c@uP?nYpzvGe-DCLPzNDA;KQ@BdlaOA*He%VTL?v@_dVe*`n z2{eorM2)3&yCOjIqMRkP6oVDHmoZM6&r18V*g`;KT!jE~OPY*a1`4tylq2{uqrqa| zLT?Tf;blmfLn*Kl<wP*#C9?pUi`_8E6p$(%CvtYfJJB_?2^L5iQYIX2rP!`XNMSD| zJqaw6%4L_5F>f@(CJy5YhFLHJj#OvYeHgEGYi%0}Z<=&dww?_g4tG#D2{#Nz$Scnd zUz<$>WpmdV;K&J8Bpae}sf)uXKS`I?Qb2P7X{Fv@{yy5PE&`OlCc$vwo%Qu>FTf={ zzmg#<y>ebo`GCf&glIBmH)%<P7{W|JFXhQ7xgjOcflFqo+=UG-fY|ERCIy*A9?B}P zvyl-R@<M^KMb19*frlkN-hF*NVzzGGSJjH|K#x>vGf;)-4Q-j<e6!<g#njpX>-c(x zXu#ExV#LSssKH`LvdH5Zf`Z8lYZ@0cFX6=sA%%DWmba*$#&kvI-IW(u2DTbk$hC@{ zo{Cr~d)ZgppMU<jAtQ^Pfdak2<M1l#SUZ%Y;m*AlH732xV;Qplym(`6uq-hnr`*P5 zONKSC(|lob7r16P`GL{!$^x29zmoUC(yg$KEahzC>0H_fERkW;Z{W&)H9X^-2gazx zOd+f$F4N3XCs`s7BET`eg-LaV*Myug&1m4NP<Gvo{kFUfFTjVkIYIKW4R+b`-<{`* zKai`OS2)}k99H&Am2jm8wZ>xoD?JTlZwh0)y<CIgH#|f5ZTp=`2KRZVfh!#D3l8ha zPCqyQ^qckC26}U^adYhY#u6=w+2k3HCAc8(N_PRGWn9=XE9zkG>RYZ)VBV>**cI)G z#5=ec7f%+KAeYupKmFAG8t5!8%Lp!aIEG$vdke(}w?DJ+_Q)lhqAq1!C*2Xg`s&M1 zywra15e}D2tw0StdG_?94?kvcjo5vzPPk-y{OFNO2aXF1V>(WkcZwmS8Fhm;BX+}F zYySISrOy!dW&XkXysYiYk_*sGLC;(=I~;UIL$un^VPuO#s?KgTOxZg>uh;&6*T48L ziu&#G;Ny?h&y*{Fp2<3#rw!e3z;dST`5s?lXP2i`5wxC*9#)O*g&}9*m5|Ozao}a9 zOEM)^2bYarAkYgB2rVU7A&fivc){Q$*$s15kxqe_;ApJ^8@zk23s>_RMUu#4X~@3m z3wf^)Z4}5}l2PhB=yQ}IU&&F>T9b^^Cm;-Ga<a4_*=;*YUJAQKus(9G;LFNTcmur* zuu~p~H8A2(3Y`2<>`Ji-DKL4C@d>NO25$;u<c4sjrIT}f4eKg<!>aR=8MPOIv2Itu zo_-Pv1T;&8X_W&0Dz<@N&XECUn1)<Zk)h0^pf$`w7LtU`T8pd`QqJiChqMB&ESO`Q zC@{PeT=EQ9ic*3u&#JvKX<hH&OrW!fq9+G(k~L6xcFLVFyS()yq-N+5&PgB(FC7iJ z;pQHQSz|FFSJ{$Wj@RVR-tep^o6$K{xEey7b4yuLx)GKQoIdjc%xg8=3(X5n2Jgb( zt<Qp5pLpb-R!qs9*M^Y79LwvV=x`68J$=e+MV@<Nc=OFi@4ZLT*BY6u72f}jRMM>0 zjwx()LGEUq4i$W`U%sC0*BG7CI}PcrWZ{w1dm}QmVGPsp-9dF!W`Qlswo_NmHU_?0 z^qL_X%7)_wxU`J&u*Vd|PAb8|ML}~*mPSqg(5!@Efr_>OBUhz2-t;!65RQasTzetc z#dEngQZ{|<md;WflC3#9zGg>v&cdSYJo`gRjw=Rbw{c9cubQu1`=qc>JZ3$3=WP?1 zf2-mftK!pV&&+mpt;3fup1U^mwS)ajwlZ7rr%%_flgY-eB|Vq?vME&m&T|<rT^liL z*pM`2)Rj(ZwNHD-H$gfMg3N}<g)0q(KmYDqy*+#WZ2d`&XHV&Nw*Fc6zvWs~7q|U+ z)X$!;S|Ecefn8D6Z$ou*4ob*=3_4O5G&~z817-Aq>RGPjeQ2G7;p8N<gwgqyej3Jy zm15)Ub(*DLL7$jb=?K|*Dw@KQw;^oetCM%9c~w2cfn$6NSNy?iLdLbbSfF>VWrvK= znR|uR&^`IrucDujv25pIpx?Kz?!zQ`J$CVhqp+wex$D+MoTRN@V|%oqLl`4u4~OZ5 zjJLh_&G(A-J#jnFov4jqc%B-4o!k5OUCo+mD|VLwUL}_Q{F5LnN#D(Vg);972Mm!{ z@>OnqW@MXUeMrN?Cha@U-uqrI)*XR)7h0ctuc#Z@&wu{&zxa#4_|>m|^(TMwC;yNC z$N%H+|NXyD@1m!}u5W6&Sbh2Bm!EBXwLiGtwacwXPHpUq*}8bHYvR-AkM|$&x2w(A z)!SwN#mhIJJXwFN=<EHGjI~^s$1pea=TDxR%(|<+`PO%C5Z}F^xF))wt{eS#FCMPH zS-8KOy}#+Y=Xg9O!J7E~s}uBDD3+KOx8YdULhoz7*^y@9ecojIUbh>go7Hx%-$g2+ zXBhJ(U%v637yR#DeEZ3#UVz{E=;IIng@4z-8|Syj`VcJt(b>r9d-*rk%r3|tGuk@F zmvw1w9Y5p_XUxI@6DWHb4`jg<(ol%wL>fxiQQrwxTG9}omxNqUEg=ZJV~HjYqbBL{ z7*eVjhYobE9<a`YLTZwIz!lUojGW$Z^fTB;2KpFfpzN%NLR!x_wKO<$&T?FoLg=8M zEOdlvZ_=``Pppkd@)puMfR!wq1?W3^Rml!zC>DpMv}7E{NBb{}SnUo?E{YOlM-#FO zp|cMn!*J4P2rP%T(NH;E4ei|9=;g_XJjQdNKAT7rgh_%n=S3l0d9Nh!MkBLKDxja0 zWJL#zWZ`kL1AUU$2HlPV-YhHojsgnHosc2OfM)t#Sh?hxR1I<Dk05P?s<2RErU1RP z>B!@y+zGDcWt}^wV~hYh!LewDT(!}$GZaYS%6<kfxzik2bJ#R4n2@|WiO>+L8)1~& zxU$z<M%k(*c}J7(4&>h1&2``8jz79!Ve#Ev*u8V@O}VxTyK~K}viBkoxO+MBlMUTm zm6k_NQGIEdE=$Ln!a{OMxZggGGa`GK8)Wta`-#EUA!XyT1L^LF^cpZE%V|<3LRZ%{ zSppUWL%p%|b7Jug&F-tO){7GkI}SU&*p?K^#%0%dE!<^~^94;ynrCkc<zeJ9UuQFB z6`NqoQqhu3Leh(vE9QId=8qpebeg>N=K2ii7vHUQ=U*$bzV7hScz<uf4wkv(qzv-Q zX{d^0`o$MtICi29Tf_am&i!(@QHY~sajc$A(nR$0i(mXg2}cu+1g@T_&~U_(8P%fq z8f>U;k1QZi-7@UxCt7MZu5YSe-nxZHs0ZN)DW2^%d7+B(d+fv4gW0jjpcVqXW>~&? zvZ8k7g|XwX8;1IP@!iX>1?=9Cmt~*qm{w1f+mMRXLv5r$c5Apu+s;Cc<u%v|4rn0D zmAntLoj}FF?ht3Bvq&4-bvyJxA(6x3*jRh;E}TQg0`jMvUFxz>cr`q0!k#iH3XbtD zl;<{H6B5pWbnBCT4rJG0ma{x7SLhe_kHLl{FnoFn(67k97WdV?0$MohSBN?NWU=RG zIMC#p!-<)Z%yLG?vxJGgJ>NT%4DR!O&vg?XW(triegAOO@obM~H-cf8N*94HCiJqb z&*;Ai=H$Sz9sXi{n#THa!|fN~m;1LxT;Y}L1z1B0ee~hSET4Y*=?{MJgWbzIJ6wPM z+F$!??ksM^u6wRd_^y8P2$6^VlTSWz4^o;JM+2f<%IL1Bn5A-Ur8G4+5V1O47tgoW zZ<pZP0B^pve$05^_CI{^a($8oql%Kqxd?lXT^`vbVfU`?Mg50ATpzy-O6aXsHFPV) z%q~#QeII!8`2F{53^4IUA++GC2-F6n`SN;*P!0jav4FcXDgVniUVOCw4x**lga?29 zZ~iSwetW$62Y>nZ^hB#yijr#7WfEccvyQ#mV?TqJ5lRB3E!BWA`+8=&04F2#jB*=} zrP4CQr#P0#4lP|#GG?jR8?wV34BJQ)Fj{>FIKE;0hSQG_6%7#_p?WYJ0<e^v5*g|< z&>h8teM%0k=WVpfc=uL5{(PCX>E~7rfuedwAz+w`jvvtKhhp{O(^KG_=L*pznPGJs z-iB6rqh%?!Hj1UMRogJZXt!bMTD^{!{xg!h!qJ!{ByWcaS<Z$g%e9tc9~69uFMOIg zubV>UJcFf+4n!+Yfu+5|ltWH0kBTef24igi*QOtsVbdIpU1_d?42+cX`NdKpQEexS zqZtY&FMBjYI>ZOGmG@FT7diZl1DVMyBUm@j;uM!-$3+`mI-&erqNKI*E&i-(t(G%c z5AlOMk?EZ~^emw$IiXmnG_n#^>Ac8(R^;cUCs**!>56YIz^H9WR6%zA$&OQIN+`A@ zBhRg#ksaZTTqe@2<)o-ZHalmZiKwe3miOL!_;P&!?^@E`!cvgoXFvOyn@SfJnOR5+ z$jCwgd6X+K9cp8m`SjyY99gST39)i|5%q?nLwD<+{`9AR_Gf>#UroRI<OiQxABS9E zRmy`YswvkzDI1H%FavK!@OJmhU;eVII$d?CcAu-aBVdOFA*P0)0eYv&7hinl(Zu@^ zy%p$kw7&MdubDb57FgiXqxI8hYp3oz2)jVl=e~0Vy^xNU<}8q0<Z4uYbGHbZwE4|< zTRcQv0$;5&StkPtQXF6UtKkJL;Mn1C?1X!5)^XRl4Py&APtUZ`zwLv&Z-#@wjLA{H zeY(C@0uf*e)y#C2oORnd7ScO|=w$Zttl-Oa09fLiFQa2YvLLg-w=a(!#lk+WzOr*0 zHbBjn=c;a;vo2LbFvJWxi9jEjGUSFqo;DKKRICRWelD2lT!DLKzwlxB+2L$AIIJ60 zr07ITRWT$D!Rb~uGFM(J+)##$A@Z4z01a<LiCknE!hQVvFy+o*={#zPGtgm#yd$4K zTaVox&6q3lbUlogT+055+L&iWlF`FXvySz|4p<_GEP<9~&~S`bLwkKTvsxsbr3>AW z^QJ=Hh82*r;|N18CoqnL`|`97bCl6oBC~|-!3lh5H#xJOaOS`KZvA#oIVs+?e*EJf zdzo}6a;fQ7rDxlK0$vmin}raH-gvto$<xwh{PsJSTNnNHH*lACzX!jyFX!*Ry}n5L z&fDu<_oI(KaQV`K@OR#R*P9-)JD|Ijw@SC3zx<c~vQFw8(6kC@$Qfs9$!0_$vxGi& zdHwv(J~v&=-AdLpzgu4_{rrosIx*S3fqR?%`0@JWErtH{Pyf`)xJ_%=#oy%0zoxmr zAD~ZBmWa{PX~1G)O3sC#9Nk7T)PtpShy7~(y}fnmR+k(dK`NZ4DbMGhe=hBhe)N;J zfd8-mtRB{sJT_oHd%ha`@sEG>&;GOjtT$m9{;U7>|Hhj3Z;b~ZfBca$G$nV{8~bnU zdJPS8ozd1gW0DjS8j_AvA#r53MqO16Z^N7gTAJwrc7?l74EYPpRg_^Fl(wL845392 z!r9AX^&7HBOV2oR6n#qDa6%+$m^>>$zm4o<6*Vl?<Oz#+VYb6?&JqOf?p|H9fY<a{ zG8zW_a^44=6j3QcioK0p>eVWR(GSukp-xh+U@?cb^Q~?bZN7}jyyqdsa@kSjT8Nu{ zwhf@D_*ojJM@|pUVG?2YvSPEN?YO&fUgs<|kcDd>iUr09-ygLxC}+pFqG}DQ656Qe zaO7m5pS^H6F8e<mrj7G3okX^7s?%$%L&MT($ifwqP72)XdaOp4vL(+App9!XG_+5~ z3wdYakR5P9ODQnMV0aG60@EZgR!$YE&ZQ}5WEpuMWH>i@23PrkQaN`Nr72dJy_sUY zz5W!<nmA)jv@TX12t$yTbWj{G684N2FhO9|&)|LQ&Gj`b{DznmwHT!;vvPDU?UL&t zZS2a&y?`P~;c7X2CITgi9}{-m`ico1S(FlV)A{=A<6D==hTUA;$h%d$<6=&@>7qS- z`lM9kT*m8vb-Sz6t*~$gF0{2q8*~<4oZDbW_<Da6@{2FObl3mPzt29iA}n9+@0yZm zG*Yb+-j+wko8U;%Ny?!11{p1dqoYcevnw6U`p_I!&vz$W9fH6(u+`)rL=Kp@C5WOI z9t5`EC|QQEv)(v;a><hm&i3bPHVbsF(vm5+A!;%VcGkm~GQ;>GOSm)t%mS|XV7o$r z=Y*r5!_WE|ti!*;*)BYs%faaE2jj9J6w)b4-bTkU<{8<;PP{NVZ=)*7$YDEw1GJJ8 zC}C)LJ7<<~m^SQFd4N6{aL%blZsllxkgE)5uus&lMPzW=jAazKDtbl)$~3Q;IbX6| z$=hJRJ+Irw0oS43gwjGLswB{Ga9HJkap;HRf~)n6v#>tcdAXeOE?=aXy12!$D=1w~ z*ToIqI%W+5$z|O8XDl@=&-!f<+j*0=*ysNKk@NT7T{qMB-h21)<HugWkzEOQrbS`= z_~VbgAG-X$w?7YAb;*T5Rd&R>cs3+QA^ZNYKzs@~6J^ubdeqrp4p<$!u<wa0YnpDn zECuQTEXTLc)_qN9jQbvYJTO!dcKQXemM&?C-_q$pI3~NmUf(DPs^`@VIeOWO0=g#Q z;luS2&}z008%y_6{q{Sn6CsZtz1R1{+5e@#^*j1Iz#o6KJ`w}esEjV5E?JIVE(+JC zU!$cQ2oF2!f>?G+5`T<nq**xz>zLgID~^nSRua(6c_`2BePK$o3rq(GiPr&xTrxmC zKs5Hil|4PLA^xCpDZm>IL?tseJY%K43uY=ILPhCfZ7lh(k|2|9-x&g$Sks)wD7@@o z7&&l7I~&j7%|+6)z^us?&YV#~Nos?hH{)&C4~KTinQkdkG7iR~F~=GxhH7y|fU1Kj zudvIqKs5PB-w_9<pB?ln+gPr^zLtJhY4>W+@SLAz(0cCB8(_TCE>(f_I3RQ95oKT) zbGNflR6sa_Z{o~>!+O(xm~JB1s<)vZ(`TtM(+4!eX{M<7^xCEvvQtLKkI52^g+Ad> zNJsw)>{UF*7nG_z<dp&wG8VHSv#Zr<Xh>dVYX}X`5^gsW;_!xy6!x<1=%uSpdUrz5 zRXe|h!g7mqU-i$M>O1?E^6cp|Z)0{O7vp!|9={&E{#v4UA#akFR0CR2alJjSJ2NKE z>R>$v9MY{{A%}80Y<WRTF7<Bq?w9V<Uh~%7dfzYBBgqC@O15sU^kzqK5o4s3Gp2Ho z9g}^%L+%d~Hhu4d1r}>rz^i7Rl%LD<geWQFuw+MI8AYKg;wS;$6Zb2pm&WxE>&X-E z)lbX-_twAXFWy)mCAF6J_~q60k79i{W!cvP?;j=i&q&$H-|w^fw~yhge=L>Iw-f33 z$8Hw;-#V)66KvOal}W??J$U;a7Ww?!(_4WEwhQ~xZ%SKiA9hF9O1A~pKapqS+AsUx z{<Y}!?e6u<!}ibqaBKe*s)T<yOHot?;p^Ax_P@31*5CeJ;m()!lZGqRInQ|GH$+%< zcSyry;``Cf5nNqfu64=1TkpWxRa7CPpC#CJDZn@oLKbx;5B7<l?ivEM7dhk|KG)fM z1rE$152P*gxXP2!Fjr{EYj)`?V25<wOHYQ@A=e-~WhK2JzPfR)z;$Rhqwd2&y@js- z5vr&YGRqFV5sQB|76Q0?<z5}lXz2|{ZoKM$up@4igFB7)Au>3P&ZUF)TIbtPp#ISg z%Z0x~7c!1F<qASlt|opT?(?4Q^pKu0WC!n<4YP;CbwU<+@x}|&)1qZsS6A2G7vDX7 z{_On^K6v#0;}1Xn$P4Ily;xt3eYk&G>MBEEIWL-7uZgeoeRbrzlX+ynZ1m{(8$#>x zMvP76I_adIr-fGDt;fw}CA?IDUE#=kMn<W;0fPIx4Dz?1T|=e!6tM3LdoH`>7cbrD z*9Rh?h}FQmj~_jH_dV%cB{iT=*G5t&_;fvJ<_s2vI+e`A9o!IKHnsNb)~#PlWK8=r zej73!St<&YnWCap57(cy_YAWZNkM!M%LZ;)bS`nqec<ptde;m4U;mf>c6okFtlt6F z^ji20CLP0WZ_S*H3YcWHkOfRTg_kijyh6r3!}UI3XkApyMImoPw)!dUVA|US*VQeo zN_Rm~ty*+su^M13ghd|1>?E>b`Lj2SnNna1I7ny#ITutY6q}OeHk583*9nDO8{#sx z@<U0^<#6JQEeYe$7@@^C%qs*F7+LN^<)DNxmMg42F8k_i0lK=C&fcUNUV%4qG+;!| z0?~GzWpr>UW(S5`LW&(e!VX%<0)^*d6rM8RA}vvA^OA;Rxf3lcj=f=db)rdn-ktkK z4=Gt7Z<gEk=9PsPb~|fv)?vOJVhtz?4S9<iez7adB~OSpIIK7AhiRkyVHa7n6ibSr z6PAt+Bg^I<NhpzbQww9E7^Z`X7ZOd{hPlXw?1oT@)<pH%80?e_XC3l_5-De+gpQ-+ zWh*&_rLGX7h1>dA>hLxsIal0Gt)Y-95tKIMBI)i%jL3Vqf8chn2^XnhcOA&W<&tQ7 zRHA*t1ydC0P4-HTf-wAyGI)pd+WD(r{mNbT^Upu0dz<50@02?#{<7@4y7Hb$=hBt8 zO;L1~9kFQLH6cso);sRyLxcBh77f<>?*85^X;~;jD&&>eX88EykF+=Wi<<CJf+VDM z#VjO3y0m*XS6J_5{$p|UX2BJ;b9#tr(bigDjw!sjY|o;Sz!eh=uaqzxioo=+b1c-e zhFgEkT8dVNkr3@R;((mV!*M#bkMYfk!02}xch-f51B5dtnT4#|bh869ZIM^lrtPdN z1Sl-GF-aPtb$&@z$XP=6kR{BpR3lS{KQxL10n<Pj?-;Y(2kw>nW;4*~9}G(co(2pv zjyF9*I+?D+<vul&9PAvgs^?`fFLDPhG|k)KI<!lwaF~8W+?j3k?7_UovKw5WcOK-* zvW>^aOCJd@-?(u-XCEA<3l8fA8L!d~;(%+-VcN(@X{+A`@0!4AS5HVvSk#TPeg?bn zG9)vm+{SBM0U^#=4z_b4bt=L(FC62I!-V<9t6MOnBXsR`C-N4T1t|NHzF>%--LUX5 z7L4_IQnd9|KOse}5H}Cz{ozgTvN#;B8m{xodTZtSa-&O=_s_Wqci<4Tr^&8bSHM(m zPvtm{8JB%uo+$#k);8W3|L5PXDo>ui`nj-o-d!I9{ph_%?>u<>i~VQeKl|*n$B!TD zN+22;G}CecyID}o%j#8BtmJv|dloVyQC6fTS>zdA)JlEYJnq6zo;-W+z4Z%md!by2 zTK09Y`U{Rarpv#Ub$^fjZ~U!)x$xf-4?g*1eM~m&lCLgIs%m<5v7z<QOvVn#WE0C? zo?InKh6pSW2eOb#Fy4lK$a;uh2t5KNSBf=4$Q3!ASE~qOn<JfN<{Ps-z}S!+uaGkb z41u@0gX~bAvnAZN1bK8Nv&JAAsWdsmDP2n`Gr=he4W$iP3W-2rNx2ib$cnCMpOh=C zj3-1(9;S`4SNcxWEm~8f1Vf<kuDNY^JnhMn(W%%Yviz<KMO6_BpJ7SJX(@Y{A>~Y) z(uQ{erv`9(zEqUOG0nSK$02B@kcEsu=DKZ9Suq=`q*OG0m~gJU8$Y&0G)S2|F$Wpp zY(GpF9M+qVux+d{vWj#UQ?5A0TAz{|W-**{ql7q6T9(L=opQyj9D8$2-+N)<N*`!A z=E`;I&7?3}?GoO{Z#c@G@-~J)XvnTy71LED>t|?m3YKLhXW5+^oe?ApnlmN6D0wI` zBbS!WcpJhI029Wz-$~c6&Hv&TzaZUf_3+i#U(=B=<<y}-nelmd!Q-c<CF$KY9fU+c zCQUg7KSKECoAtA86#3=sn&9U7=YRg^^#cNNKK$^*pZw&<fAS}P(lSp}b6I^}zydk} zDHr>4H_51(jJNRO>8f=sU3qfo;cOh`!CSAc`6HntIKz}Ipn*X{33EXq!F0&%Xwo|3 z9rTQOha*o7hm~T(s#XgO^Xi{*hQTn}6;_tbObLhY)Bt7jq?6faNOp~->!G6-OfAAr zb`ToUZ{uvI&w8Hgjs)3KV8vW8>u@C@=I~P-2q8tuS(Dp;4fgw7z_D7n*$mugY+ucA z6rI!qJ><f#0mw4m6c{^+mJu2j*i3IDZ#cqUi!=X>PN-vWxkN+5vmRz0c7vxLR_Fq6 zuB*U?C*$4yTtxv(IK~%L{mLE_%<60z{XE$-^nE_W_1`e%3ej#O*Is~Qg0CUNuk{W} zXoYiy!v}91_GpLkR`SCt+Z(UW$Br6^^_u6BOBqYIlETlY8wH|4#uSog|EHB)E=3f2 z`C@$!$xE7h4ZH2v%D?;Yy^lWn$a|)1k%}y!92#ZP(p|v-%`mL&7r24Cf4L{Jd;j$K z)O+cR^+xVi=uW*p?CR}z9=`bQC8C?z*YM3ZYhyg%*m&^Z{m1XW@#5v@pMP#-P2}mx zdAEH$qnetEtsV<61)tKbvln2)m^wjYUsHSIcm$G%99^I!_}S@JLx1nT|G_(Nzx&R^ zb=Q+jee+iO$<uFCdHnbh`R=>#5EMQ9OMm;{BmB3=t51PeIFmVm8V!LL7|E97Y#)Uk z5Ln`52?fH~D<qI>AC$EZT9@0f%JBhB2#7V@#SdU6%SIU)93BL*5$NT#H5s$$0WhJ1 z3X+6|F@a^}y-aYJtH09=XZAwCkc?LN6}apS(!|?gS}Kt7HrPuw%w7Lg^0UrsYV}~q zr9+1R#2y)M0&OG+Oc~1+N*m(5CWPg-F|f-((QWg}PMI|<959_=mdiwV`(6!&%Y2dJ zlf~xR<|EH|Bb<|G-xE64Id7JRw^7e%T0&zfvjrz1+T@vG3dF%DZ`*+p#Gbw8zSF;I zvO}CVWDkewl5H?m!ePB>KTI1}_GC&^Fnz;1u{bVgtIG`*IO~}7bucc6BV$U~^y5%A zq*Dx`Wgk~wb+eEeZ)5lrn57%b%Dz##ke9LJ%LRsK?`;X^Bxh)TIH94O`?wt^wQ|tV zp10d6C-V9M+@cgh=)7R*hD4{dSD}*yhY=_&yl8M%Mt4^(a85dUFRr>G84=X7l49t6 zANbsrTF8vNYi=975g5r`b6uQCLxd{g&~YNj8XqE)m2iD<RcHBX|7{5kAb#=17c$V% zgrwti94Q$ua5fz;RL~T5v+E~NcFiliT)!bE<@#~omoKzq9?!qEtPj@D_wFC1lVbfC z@YdIJ)zSZzY>q4CO)!E^LOQ9R?Kv=HM*-S1g#<Gl=9T2tW3*8uNnbG+CdfR-u<6Hr zxsZ_{@N6OP#F1;maF`8A{ZM4<kR`!ECvQhxP5(BKama~EIZKdyF*dS<8BT}El)O9W zQ06R_u)UNWe~~tA!e0aK;a{QH@sd^C&NWO4hLxiP#xi8ztXE0yLmW6q!F}t0<`g(M ztT%DypJ4+W+RZ%i)ANS<xug2>9IM28CWKr`a4MvXJ!CxNaBLi=6RwQWz_un2>jif< z7G_`3<LorA4t>K#{dJfUqr4{YK9|^C@W2>b|H0v2SoS%EVLCq}>cUQg96Fmip==32 z>D6(^EwCKg)<va^CFQ95=K4GB#|!ZOedGQD@T2`g>j_kH#O+-~*C8*No_0DAT?S?Q z;SYa^*${G(DWea(psow|{!Z-s@4qjnD;sY6)4WWOBG8@Ao3Gk^2Y7Y9f2erj!2>Un z&(|;a9A69A-L5F_L6{awDlVWjEPqBhdtoNUc9}Aa&+^^N<7=R~WKLHxT~2lBZpvPO zA3b_(&E9@zxnyvhcRxh$`GgnXhg)BRzwtMJN52F7=_em+x`BrF?ACTM%$^+7eatLF z>-doa_CwofMbaHVRZNvdPN4UY#Bv*A@p<>Utc58Y?hL_ECB2FPUo50I(}wgQ;pFVb znbDAJh#z4ky=+`y+36RC142^DunKGxavOTHMJN`kjb#Xw2w~?~kW(sqTiq<Xo%QsF zR+C_exmNA8ZtNr3x9tw>1dCH(vT5GNUVsHXWSLG#FoaxaDYwzOMGoa0`^c1C^LP%9 zQ=aC<Mc>>bCj~7f7o7zR7221JS9_@pGfb~ymMipVE<;I5PH{{lOd#WxGQc_aFkok# zmSF6vj7}czTbn#%giSw?9SR>D)|>Xjv~kYNHNCNu>=Z`RH*`=eFKJ`5mn}4$5TLM3 z!W2f~ka36Jm@-<%GuTTQGsK_R<dn1iEW>9>k!KWbAVelv=7cq*q^DeA=ePqEI!GrP zyWXZfilQW!qAac((C#I)Vwv53Y)F09ZS9F7b5XL77pe#|+3YYnS4$)bU0pgwC+=9X zxhc9?e*E$JfupzgjdRu52Tq_2>u!Ac@-Uf_9-&%tZu1&)8P;~wH;nN1+w1(In+3?M zB6J5urZeK`;q%WwlWNvM6aouZMzr$Bw>)ew*W}nd`Iz|nn3na+vR3Hj{*ATszc*e! ze7Jt^+SPf*$YLii@#cH$$z%PE6=sq}VG}cN?n<AfaLN@loC{J&;A(|KMqsyH+CYZ0 zp#F85t$!&O`R2>jo5w7Djx_N#Yj5@ISH#!c*V^wD@F=rlFQ~2_s+i^M8f98dVNYQh z4lM07BgpIjHg{XAWtohIvryW|e9n1Bc7%2Uj4}JjlsnfM8Xmpfl)1>(q@fdsqE89G z-KU{puCoLgCdqB6vBGY7X9Wgp6IhL#e3?^N((__AT(viHl>~-)Cytm?LZIJ9oN(|q zlsL4TIP<R%A$=FW&U_3m7(!lH^V-|62~HB0O<YJH%Zr!mz>Vd~dj=ykuPo&UdKCwe zfiLB7+?v`I+QzaCt?;RPmaoAOrq=5N@3T)2HL#mn&}W3e71pKZg6smJ;UF@2C5#O0 zhqnJZhN07nF5Kzn#stm_!=2+*lF_g1YP(wR>-uhHzX11_1|L6KpDIt?x8L=G-3Ls) z^Uiw1EXm5X6?XR{dc9?*XohQ7dbN5DKm71R-QK(zt?R^kBY(>?l?7Q1@qXt9wG*$G z)o1HF#_z13eO~aQ`TpbgzkT*xD#87QA$Gbz_fv{MI@Av+ibg3Xn&vTEJw}R_=#=%f z-F+wx$#mhO6w*uyE9wp13O#T%9=L0}magiiXzaDOSRqy&-x0L3zq1$MPj0>dlQZG$ zjNwX$2@LGkD*|Lm4#sHFm9QdoQKTo2C;N|2((gp&S~W>5oYl-#&Vga8mYxiX)@0Qi zDysAxT^8Yc*B(z%*>}FZr*7VO=t9DIccKZD7H|r@!t{9sAtorw!PbU6Cd+uZFF3Mn zpg~hJlo<-CTgK^!D<d$DJ<Dw%$DgQObA81<*KJq?RY-c|2|o{^<+>9VAw`Em$_a(T z&h!eMjV3}ymY?0QLO?mkmN{eOAlB@5wIfM{5Qn9l>9^sil_$>BV&PpWE{Kno62=vO zF!p+b?4#HTrHVPIfh0sO16*0s&&UqLgu}FP-a?0IFS~W1FbXuBjmqK>1ATKBGNwS? zri*2tRpJWgb%@-s%s>~_u^_$woN4E@=iynI%mXg-ji7{D2$Gu}?>e1setE7o(%HvF z8T%Ek?1hlp(c10~XX%}4BE0pu$G!jlqxEA&@0hP!@PqZct6l=1JbC`zw=3eo`jhuh zpFdkcZ+ne-`RrSsZ`UpJ#Y@`m>5a8g?}&c~N7VYLOfP<l+>&oUSifAPqi<h)C+EZW z-eqA|k^c2pUy+~v>a&kN`S|IRrygg%*&jo-C$bKTNqxItQ(I@V;$i`dMt9WqQnY89 zHSYSMFQ>a4@4SQ1m#D3V>)yHul;7cS6?M0UFZbV~;8IIYFXZcP{oF-n-EqY}U!ND! zX@zDJu6`t3#olt+aUEXwopl^ut`0WyRkyNj=1q7Sa~-p?FV@r23S8@U$n}w;-!U$^ zKB)WK^`TYf(>k0bv{tuq6xu)|87Zy6VCPt{0ugrf!WH2Rc6|ccHXJZCWk;l?4m+9a z)w)D?>@vnD8;(5%hA>Lr^Ds-u7#fl)4k9!!9Rgz(%Sh6r-G)>X3t2MKZ%fH3!Ej(G z>KN=KXC*#lq;#Fvm4%fPO?BN4e-mHj8Os&8SKeFRt7U;`lkf@%SFIX?JZF2UU<bV- z2NtdZVK~FTjiEtF28Z<~&ipfWQ%99ud_nUW?@O35FD7Za>Fi|~T1X!YO2e_I+(s@q z#y96O&4+{PD4c2y1l~4=u3sx~gJos8%r4F-uR)wL3|69hV(+udz;&)(&a3O&%Db_z zy$h}Up3Op0gM;ll`Sx+7=x9!>`0fSHEKmEc;cWvId7W_Ru4JT+1eNDi{+C??U9;C` z?Cq~p;=69I3+c|Y@;`j1AEJEoy+`kP$#mO!`0jh}Jbd>jKmM`cu9oG~$>Yb5zyA8` z9_-oI^fnB&l+NCDfC69aKNq~dsk_maYn5|XG7T;4m)`X_v}X18+r3qJ0p7i>pM83F zzmk9Q@yBlWAAInE2cb_t{Zv{JZjL$>qT=H3?~u0$AUcJs)$1p^+3D=~5h&00ZzqYB zYOUIF60N!LW|y2!F(Fg%3cSAq+#&7{g{+Rhd*O!bVz}<bhL0XSwyM9YPl0~(ul(U3 z=y++nOS&n6<zPwj>M6t=x#zn;x6qXL-+y20Ef9rW+8_jhom7GafyA*2z~#`cgST-m zL4kAW6j5YAlc78^7Z?u4{`o+QT4Q>^q^N~+?vPRsO(ZW+cBkto*1*UVA?cW*p%D6{ zm8w>`7=ePYb1&c&i^)shhh_cPJw2?vm+*4N6kZ?*i8lNcd{d*hP&PejWrR=$B?op5 zgIKyKWJ#Qj5q9o{Bl7YFj?CDkAZA8-Ogbj7{9Fa*)jwmghKvYPuGlL$G}^<rAxSz* zokJmaN@)iy8S@_2z28h6*!5;u!;#4u*0%k8p3&qK+i+(+P`KlgSLdSSG3+pbAz2_9 z6IzxexUQuPkU@AEfU(|+Vi{ND9k-^;ZWxn-(E9@*?3Blq!OE=2ODukP_I&*^r>P0C zhe>G-N#rV?<->Q@#4DXe5(&Fvj**PkA<mAbRVB!;zWS;*RyUXRFWZ@HSSsKh+7*x| z6|h+UTw$VApCLJl@Ufp2J+vSipnG9^w12(l7r*!gJH%0R<$CG*u=;1T;Amu1a9+x4 z_H6DGy%w6;`rW7JPriHh{LQx?Jbw4Rx88aC<+tBG`|jI^58nRPi`lo|k#BlI^D2wK zzNh)X`PTEYYqVujJ4^bi{bGIE@Y<a(UVQle`;M+l53lP2NoRTg(IZjjoMcZnBWM`| z-8s8fc7tV4cELU+b>nQ<^Y(w44(Tx7lnY0e>pb|chJ#JywOo$KtDI_OIm<Gv8mCn0 zj#2h2NF;Wz+{)kx%1^53k%Qeui{0Z2yUkOdx6x5fpQ2>^^JG;d+ZcOxYt0?2E-#;a z@<~H-_qNW0q^L;}CiBX20*m~@B`FUug57%rpTJJykh)TfY)H}}4&;?~=X=#a5@Ck) zRroUB^bqYea2+Gh$x}*2w?rhJvD0%?UXfpq;a{PdhCS~EIl+|Ag(xg-iH;GY_F8au zdSEXD%({W$B=1HqkZw|aVTj^7Q-+=CP{^)hGfcv?S6XOz9|WE`!h!L;PqGAh8vwbP zQYzG3aIza_K`3^ZlyKWFB>SBbVnV|jxQ!vCjBNd7D<Mm+!4yg{StY7cZw=Xpb0x3V zrxL(&8*_hzGMq7iqYUR<^fjmxxZ*39a)tFvA@`#;1}rbv3+f%ndmHDvINA%-nAPhh z3!Y>jJzC$)boW^w@xMRhU(|yK@2p3ZZ+oI%54|9X@MqsX{pOpm7$3dYE8O}+^dEn` zzMJ@?AN}a(KmYk3{K4<P|K6j2@DKih*UNR5z5DPFe((3aG5*<~{TZ(e&b!(WuCD4I zee}`q{oe0=_~D0={QbZG_y1r2um9Iy|LcDp`G-IJ;otjvfA6P1{b^57rsjl2!`I~c zGrymI@$SP%?%i*#UwuB-B>A(S{p_>PJ~JaZSN9L!`QY*T5a}O%`U4iFB`l{-K$I#y zIhR3W@ad0!9GOJ62*{-5CSrofXuP>T{P2BAy1H5!#tL!iLTNfFsx^Q3a9xGCDr%Wa z>$!zo9e?o1d@aR~fBa+X{Ga$w{b$jBd#pc$q>lz_(@hWRV~oMjOjwc-2Tan?1Wd!w z%&o-{c7e1lAK*-QmRx2l1GK&o&M0bPrKLBlN*FKMAt8e%$p|XqDBTdU6ew*v<SmeW zGE_P_%9_vRu>kB0d`U_kb7wv73Y0>C&Z6P$<Z#A5;K~aKAcKmLxty7*mpKd6JQ_)7 z;U%pM%YY@Bi=63`)slRdUFEXC*%IhbhI4p`P}}Kn_%7LsHGR;`kOOZ7=M{xTV}O>c zoWM2m3NeFARfVb;%5RH8dS^Ht&PgaWFG>>onS_|2w;_jy1=b!~7DGBEebZm@8%9os z(S?+goSY%TF}NhWQUn719NS3>Ez3+ZZz!tp^~X*wclXx8(9yX%jsv9*Z6{H;>RBdL z{ZO*gA#(a`fUyMj)`Wc>+ROE!2SkL4N*Uw0QtD)o3#OS+9`YF9g8fj)YGT81Z{g$o zDs9*c@ZB44I-2Wey&k-6Ngu2i-u?FpO1N{ZCR^t977Y6W;yA7R`!gy{esT6uvK;jK zcJEine3rL6<!+|fH4}5$&5&}6T0OOOcT~DFaO~w_k!OW(Ec^DRz|Oi5A-Dobyjg3w ziy*A^ANxtZTCN@a3b!qg(eWASzsZ$x`B$xzJg~j5uzYvrhuu=!HNqkHDYF*vo&7U% z@{vvu3$><k3zMHd5=3!r$^y%3Wg|V~UaqC6n?eo^92%BfjMA<RbGZyMa;^QeABOgh zSTKygt_T|nMJ96rMUr%xfdwaW#>L)fDD&#((rPkn)-^<tyyYC+$A{I;W%>b`rTLbp zwrBO=D&#)gSNCeBNl;?1?y;WHNJ~n}7Bbf186|<yQ?_%VJiu5ghp(r#gK-m>hju~@ zgk9vi%6%BlWMG+9oji)NP=FG04Ggm%<D1oQTf*4Ma^8nClYBk-3b)CV?LP3f4lzT+ zgK-lM{XUHA=m-q>S#Bdc0%RFf;<o&aa9_yna$$cW!o84f(9j!jt}8^ijp~v+#{rgB zDQU>KhwHl<Z#{Tp{T!|neSL{@1@5zCedBkppVQ4fab2QCFo}xRx#Jz}2S4}$=`PHI z{-dA#<jK=#zyAk+@X1H(PwhPRO84ISD6BvDgFpDAKl-Cybe(<P!1rJGd9>d0KKQ_s zrwsqjf9JpRul$w2@^Ah(|C_xD8}fSbbDqke`ET~$llSUK0k5p@yth6~bp5#2<w7B| zOY|>(@r&NBZ5XcYU-;nt_gfz>kaLEj^lx55T=@^Yv)=Er2ygqb&?%zyCXnt;a6gBv zmud+?wsO)L3vBU8&6|Sa%(D8|A?3yIHF#HXt?STu)Bf&n|9gH%AA<GK<po&18k)@! z(#JA0PZk0Vtq!FLN6vd@o-sy6tJ{l5*|Ow{7XK^}CJ8;zhXb;Kw2+s~&O*sTrc^gO z&R7grx{b}f(a9KhzsGHC@2>THU|W<2h6(hsqfHenNuS{vJMO??+G~}iR06ZBo?;>? zfQFzP#R@cJS9J1(_`r2&mvBtU>u_LrC%BH_Q+OD{3|FEHCmjUNK?J8wWGF2!m=tL^ z;n_>Vc$R><JqtU{f!2RDv@trRbCRM5r+s9YB;@efYXHuKPLNe;W9+1;vrDS+o{=|2 z@{vK^6yY_~?y_`+!<nCjlCdGww!pK?unV6dorNN^qHQWhP;?aayJ75SX@Oor*Q-!Q zlq-p`B5xjCn4Dvb&{j+bJpeL!m`;;|-O_?6LsI9Rsu4iQl)%ga<0aY0a>i=$vN8jy zGTz2qFs&hp#$tD!L&`u(uT^J*o6-7Vto6m|^}8`Hp6(_1yV@d)YF-cCdi%w94#Z33 z^_AlN7hL^Q(0Uv02Mo^{``>=?3#{Z`s<l@26IM@`3FggcNH$d6P!v#DFd1hbM%(EZ zSXR1?2p1gtFk}KD4X@;cr?7<caQhE5%u6;rbH<gt3eSF4?n8trXB|u-g{AFhtsF9( z+lWTFlG$60EUo!@KWB%^HKap!m|;q2xDy|cmOPh3P)^!l>t+u-%|h47W3W*Mig1#* z!0kNF>oG3sX&8zcB~Hlx8tfuRI21xQ7kYb=j+TB7nG$2Ujre!sV4QMV*w&Wbf+YI} z1AA*;dvm=VtSlR|m{2wnnp7@B*{rZjO?DPC>@+J6J^NV>N|k&KMD2X9Xp?7@2z72= zGliy{D;kBRK*O+7TyWbGZre+eJmb#r+nB)B%_S9Fh3~SjOK6TWO~<0Sza}J3>oBp| zBV1vQZ?teOkut;I6t4+fHE!Y7dfx!Tp}o@Y4mdN<I8PH+$<1s9pcUI^oBN<Qw>RDN zoKXAiZe64Jx$HI3{_Vx42;$m5fwh158Jy)S3&;Qf|MW>jK~zC}AAkI@chr7Icaz`h zM~fwV{_N?;UVK0B*12AfJwQ4f?$lp?`K2}(MX}dpvAcowxmkbur+?~&nFar=ufAgG zge4Jn^XsAI@%tZWUTIPi#=eo;3oxcO@>0n6_lI3g2FjY)X?^NMpW(^VCy179Q;-F& zMjk$VM-B>$HIbVv&7RF#^E#wR*rkRNLEZW^WZa8?ypaVxvyfojS}XEz{H?!rFn&9% z55d}f9_tRQy2%}8h-U3@3W4n4hDT;GTOs;JZnjroH1jeHvQxM~lF*QM*Evd@<+Mjh zXTRz*a5(_w<h9%oEeq^SD?>vBL*A(p$~MZ#)$1k?Hf#OB!we^RQH<v(MresLW&t7b zVI{q!BGXAOQQ0MFj&mR)B&`FbH8<o%6U!Lb2gRmS@Bz8%86%7W(L(n0HL=Uo%D|O{ z(r^=xD99Mt_ZN+pQFzF1Ix|_`hR|f=jD&Mq`an2NeID*jC^_9(-JWN$!Zk1u+cu-5 z-^M}Rs3-+_EN7V#8lJJ{e>o6<Q<F6?Q^>_aDWru0oQy+@X?A2Gfj(YQ)&ZsjZ2EGY zrT=irFCod;A{<FC(;SIFHeCH(W_PxShR*9NV|6DmZ0>?<XonKmr=N2zs2mA~^yDA{ zjD3ZjkTDGTHn`NSpN5*zzabqMr#D5o`f_e1&|G2M9o<V<N)@?q{3b|&jvAmDmLGZG z{9>;Y63W^2vpnR^ec*`PD1;(p*13MjfN(^fu%i!@<bq=&;jnGQ9C=n?F>av@ugL>v z&e?U9bCR%!hF7@l%F?lrB;E2}E&CNL<GHb+WuJp0n-yl1{7i#g_WC?ZXS9ntI&n$} z6ez094l4|KGEB%-i2*|Pi3Q{ocKQrc7)ORlLO&}tNv4cz^eapQ4bcL-IkLz@(sAg+ z1hhjtwedY6Ke-C;z;k#FQ1UjcnT+S2Yj2Pp$`7R)%mzDnm%77;F~aEOIm<h7j=d9C zgywP#HY5-1K&fHO$P*GR`wo4D9ePJ6V^0ddlD{dgq71`TOH=ng6h%Q3JN%5d5dp3O zuj&rihZzbV9M%hNTV9Xflz*%Kfx~%m9|ObR;srR)S+*4RRq+1iqV@dS^))-!w1*GZ z2QN8Oyqk&eqRUPxoQk}1?7y_c=vrraKltDS?`EP%c5lDz^8D&ozf!>KvDaU3ab9Bo zY@@edP!V6Cd#>BJr%L+Ie)h9}_z(Z#*I$2)@K^upU;T@}_zQ2sUZPnv<G$}+4`Q3h z2OoZ{7D%P8B$}5;6%rvY2wCCpuJ0rRayOv8cV2D0BztfJNGS>$LeuvGUq7;$h36|q z8A`QtujH)>BL(Ea*X=ZhCMN<5oiUfCQ{wUC$9=c_U;G<?W9R;Dv0i}vXScVm_)Qx$ zF**ehNUb!4Xtiq^5zLAuJ!R)u%#;bF@PfKc5;|J5zVUHJzmg$x$YQ;Qa5(nCBQsVM zCwrC&q12l^yPbu+@zZZht|`GHLxmhX7B0ptd07U91cY646#~qZbAA|mN=5|wRLOWo z8Im})LAU-6-(s9P;e~VE>=gDPgj_JXs6k1fB!z$;cH)Jx7fT+F%gXN)XZ?r)S9_*u z<`sxJv2c~@EYAwi2fbQ|U5mKCj$kJMT`FfR2+7V!XNU46on=&1ZQF()Ksu#|9zwd2 zZUiI*0j0ZDV(2bmK)OrmR=T^phETe@LmCE#cl&*7@td_+%$|GS*L9x95%(QQ)S{(9 zQIUMto>(4y(D;d?aW9#0UyB!(HTYNBPFO4dKj#e_kPY7p_g+g|(XH|RG@&;oR8Ul; z0X{y|Ao2XMwnD5crDUd_96LyqP)JkihZfEkS2AE*vjnm%=Q}k;UoAZO9*`{c*KNHD z9^6S41L08|2E*eoku6qz9yt%+1}l1t(3}&75&^DY8u%wWFd=Zrp4pU@&L7=v6AN=Z zl?~~_tLIgMful$y7#1Ts>3rfka5k#4xMYBAh{an{RFK(~to6$TuZc&e*W#^#5>#6T z<T^p|K@|f1`cs)z+p61YstL7rBh;*Nb$EW56Z0Z5)(W6`S=PO6l#kN84cbhvF!}zV zY*Wz1J;?mma!xp{H$6%O(%j6j0@2BmL{gK7Vhpao`bEAOcXzzV|KXcm(E)KzNFFSO zpMGti*+G~}OkJXYeKF2hrxy9zWdKh!uJ8sev$Kt97$d(p4y89CV<$6B(vd+&ShZCd zdx-%3`&?Zr)Dj6W4DZsg(_Ti2MMIX16XF~5wbSQdN0SbD+UTvvD<IjAEVkwhv3~{2 zFhxWnowZj76@^=IHprKub3Tq+l86cy^wUq5#>;atAHr^q2x=2WC7S0v?W=4ivb|s4 zNYCMems}l+xO5B+^v~}`Hy4y$Tj%1A@eucW**@29DNp}QG50{L?VqgtA9~{K`Kp+v z|D5qE<!DOdn=Y7R-C^{tlWrmM2=Jnbeb)YbNBeAH?ARGfqaSifN?C5xhA;Kd7ngVC zFKpyE)n;DU&-&}#X8cTkZ&v?H*eG5e4tjY)iN~!+IeWa7guP)0B8y2@q&&A}vC9S> zON?S25??N5RbSWn^aFJe5*2#fo4RL$xJCFJbV|_pwmswV91p}`mr{V_eq+BA&cW4} zjDXa+mR9<ZQZoyA<mx5!q<?j>TyvX}Zm8yuc>z`&h>mI_J>@w`!Lz^BQwuuAOOR8m znG1vn)KuhsY|q;X7a3rrD<=LCLR!!jn8?I8{8ousg#=V%lfg1XLVrGO&{)}t(7&uw zX^%iwt+u^-WveSJvCGzWnHuDjP!;*Q0N;JNhj(>IbN9}CPr46@YSjpmTf$B^gmTB1 zw5<yB$#Mic{o>=ZiepMbAL%7j6d7)9n%pa(=96%i+dGHd{vt5qZ{w#T*Zy*ap}f3X z`C4=*=#HqL1c#RiDKi$YP;?M&z}Dt$m!?-q)=V`>DM53HWZo^g5yJBPA$=YrQ9IX_ zPv_<%ya&fZBwrdr(0VkcjY;Gj#a(i04*_dMV1>F{D{lnDFUH!C+YzyUt;%!i5MrXN z%P-Twa~ag33m#WrH+E@-)-jHSbF?jur{lki?PIN`#T9(GNoMKgQ|;}S9a)V%nq)Rh z7B62-_7CcHvT#bsxr$RnmL0Kv^6o2E9crFjNN%$akl;XFC>x}I|Li)Q90E<PyC7a& zVj&&jUkJpTQpRI*)(EX?_Mr2p8luOyb!23ilWFmC%#0Hrj!U(}fB(ws#Q<g$PUvke z4nb|ko;96L2FTd#U!EI^7oEYF3C;RKM5e3)d(**eU1R2YW9=jei))l76^QgwLk<m! z(OO@?+nsi$|Dd**)|DKU$ZKVp0ddc~%!qHyU|sSxyhVnMwd1jJ05FPjX<wc({{c3a zLkPsGa#k;<af78%C4{gi*}tC_UWxi$S99fHL$Jx5W^44}-@M&=7Sl_i;-_%RS@{2- zX{D^S1;??qO(=3r_&S(2)L4d0sWq$E9Z#qCk!L9vw$HiLjfyIV70`wNmA6?WH9G!A zgC)>Wy+zny>}~c#{`0Yo)Fs~|P_nrglzOZ-_*?rlT2XNs<@Z?Qp$}aK$#70Yg#PmJ zd1J69fLKSNT16Q0$omho0usob)a}#lXvJ75$o|60Hy^l_O)ih-_E{(wf7>m@PYzEN zeV$?HQyO-tV?x3ZXdm@6NwhpkLSZ;v8Xb>v-pTi$=%SK*MoqaawisHer6jwr>m=Da zfP{I#p2@wAIU>dLyc-@nGw-7J`_<edSHLS~78CS9Lrd`cCKwND(UImi2C(IwC1x%e z5aJ@N!AatP#?7)@aWLpS9!w7>u#bMEvE?GJr%J%k+q4PqoHcK>Y}yTI=ITv$ritO= zVbRxD5dFk*Y0ar(OCGml_901t1LcirnYOWRxydvivIO3!-iTgS66P?5*uL=9K~(90 z6|aj3*N=`kAxqF=h}H*Jiuv)Rs9#&hO$=VXJk&LeaoESa8^o)5^aa_R#NTi@Si#o9 zs+9VlnE);&cI}unF!z`1rNJE&V48!q2L{kMj8Npg^UN^Xn{f)Fc9K>BF~rFj)l|&$ zmP>oF97H)W{!|ymp?zgD00KCXnZuIb(#2JM#^;y?MUWkx4i3bg8Hpa8{o=T50t=}w zb|SZ2Qn-dwKLtYtI8F#OiE;Jl{22fIP;t3MbFl%V=!fu=7mA@#3YQ*?N=03ELWPC2 zP6UK5aFRMUg^2k^$^<J_n-ChyhPQtG{UG}V_B#A^r<kG6{1nNBz>buI1oz7BmUJaH z<G>Zi=(_q28u)4J3G=f;_g?^<sBVi85p6%zK0Ww-4PDh=dFH5pYLFbcZ;H%Hxbv8$ zqzU<r4PlWQgD{pQ$Ye!2nb{nfRJ>=dDVG8Ahks=xRXTR&!Sd10%w^{z4QAg&Mjb$J z2fwcL$QMx^|0sE3WvRRlo!+I$6jD*%+5hEu>6EDyfUBKO1RGAwZSm^ev84rFAp6uh zc*>VZ^wx&7#i4TIfOp1#d`T01Bc8VrJb<ew)g_1$KF~?cWm(t+bq3ICQVjA9>2K={ z{|>4k-H`aoT7K&##I<C>{L}=X2NXMNLX=+DeBh_@BJotH;1A-mG#|v+v9asWYcVdY ztfH<tfS2{HJ(GSAA!+ILXVpnye49+@9>1f>H%g*EMv@#--gQIUWZ(R?`GoIBL-E#~ z2zSJ<=GqT4pFjA053BW8sQX*NM`kI4Qhxo6XyV8Juqg-}m<YsK0E%SNk2os?r=hmn z)6(n5-wIFde`ob4M)gp~jJsC-fSlyZos_R%OyV+=*(=II+j=BMTAnqRg?uXSf%?+p zAn@}<UX@DMsClNh-*AqQIfy-%2om?Y=xfc`woUSw-J@$su9R9k2e`Ly?g0H7En*#A z>YVS|r}NgQ9oO4dL!W;d%f#cb<HOTB^#H$jLpSRi3)2a@MB0w$?(g@XbcRq`BC431 zj$PlM_dlq-T)U11Hl7om{}SVav9mT2WlVYj*sFejPtcDXWhA`3eZS<gy~iZ2*(OeB ztzV3bqUD6HTwOb|K4eq@CKi9i0QC769AC6hAN1QsQJhMGzi&-z`PS&J7yiJkWZ0u) zFnGwD4dIG4?Die`4>`9bALrs!;U=Y>X;hkPpdpIahjcRBFEK{Xxn-EtKZfn&U?`XS zN$sd%D1=E-CQviJC<BI_B+<O3h^$L6#0M;75bgS-{e01=1DL67$k6Ta9r<dV@r0_% zKdDk=FQYlcCFo3os&#W1_}$&1y&g!|F)h5f9^dO1e>JAr*21r~RHmA6ltdj_D6de- zLPU#Q>OV0EFq#!EvE1v;+UQ1Mx9CbQ(6vTHwfjfDe$qSF+@L%29hGH%i7YY6o8Jv< z4>fFEd^z);(_8i1n3{fjuQ$;Hv(7Mlj^`_)J8D|VovIYw96bS2m|y-%u;xXGaM+pV z99%`NLVu)U6RQ>a^eJkPN=4Vv%5+%F1*HG9_Z6H79?e&br570I+osnt-7~hu0N63e z=xN(EXCex8gUPpo%bu^2!R_~gP{Y>ve4>i3&DnL|5l=AHQYc3*rI}a6SEIurP?*M4 zgTUa3^XL3Z)msClC^KhCgHEpcBBe&=;Y@!c+P6%fi`dpl^*L06Y(NcrflEgTWR@Wo zz6&3e)<tU!cbe@igj-)YoCfg$6ivcc6Xt8KE0``O_L(=#7}cRErFMoX>^-X6Sb6Rp zI;M<~`sH?Z6VCmyi8v>vKWmos_FHt&jQ6GGdV5NdVVOx6eL<&Z$CeeuOxlkM8bb*> zNggg_^yft;!=DoHT6fJ;_<`oi;5toGG>$WHPvO)P5e1!O#5uUo2LJdLK)L5ePB)?X z+vyL}@0SBAHbJFcW}(8}1pKY%n8SE@=DsQ0EJJ&Qd-KFYX-W1=74aU-lE_-Hr@(XJ zosDVTkd&{4LA-F@g3P$T<Qb6Sc5&7{#30`7c<DP$SUmRVJ(kCU!+M64HBo0}1v6#E zul#Ygm9Wx7;O2A{l`9VPwefWT49vpWmzxf~c`^WseY?|1G^7K6reCZ3svSQ%Lq6XQ zZP~Hkq@>XR8Cd#g{c!AXD{F>2m;V^#B!e_A1|YJZ_nrYoV%T#`z+fjzH}+ES6Z6hW zK|5*rMn{^b%0&tsKt*o|BaN<KzabO}I1g5Tz7BXYNsZ9>74R7Q{8#Fp`8mWx==`wo zKNpFPwx^rNWL$-aPl7LRza&gy-`uC)B*sd<vI?Gkfv)`Rw`*YJYQ8HMm8!cjmz;WR zLhQ?qCx>x*gj!pNYM`~kahE3B$@L1x!+9a_a+M~nAaV_gdqx3V1OxY+e|JsbHqW2+ z%XI=PNC+=ZSvmGYc_|Q(q21b7ooD-Lfkj57TyhDKQ?-9y#K<<#GZmK(8G|3rN73x# z4U>&C{cba%lzcu4%9UI_NI@DHt@i`Wat{msDIeRShXaA^zJ(n&oBeCzdLw~}LRU?? zbYwS-w$RomD9!Secb@%HeOv3gXs=4oS0z2_WjmT*4j5WV@}b-IR<Avpc@t5Q&+Lb? z$#5c(HK6<{W)v~Mr^5g9nU3T!R%Q7py@i|HijT4Vvcbv0kuma1w7w~d<xeG2Wg`$N zG9Hqe>6n_$np=!j*u{GSwjew5=v7|^=^NN!IHwe=FC2e+B$7(%JA<tM^^6W9w{^%} z65-}=uPI{t?{ce`#wj&O`JC^tV%0H;P`NsRClc4j52E{KCYJtn7Yj4DS_QHaxumnr z8_K1Ffq4VJVX!~=FoDQecG}4%iBqR~wDr2%tc~hhJwfVLT4ajGrE>#EQLpB@o~&E& z#%GT$9;5F;7Ef!&0pB90GSke9xVX2s2G9PznoVR$)Z=lYV(t8JoYjexIfi){>M9$Q z&w{k&27AgtNU(Ltu{3b_o{>4yl_tC_X7Hq3J5kRJ)r|IsWjoFJ-k;Q7L+7IS)K^~d zRcN?M`v(|8WAm_n21SkRJltGCJC{mql(#wfGZ;B`I-|8~#8F6((#=mny~Wx7pRup4 zlH6Rmg*LH}A~TwCEWUnt`IV(rUT5t%mZ<UP`BFx_$7F8YNj2zIu3dht>k}_(97HU3 zG^dNA)SjGMhsRJ!$l9->Kzn$pWSIx$sSP14;~)8hiOiOxuxmKZRcwwwX25$g33P#H zomOhb|BKY>7<{&`<4k&pB`TsAjmQ5%zDZ4V|K0n&tCZCK{t(Gt3Nh}{+dcsvEfu9K zgAwz9U(?zf<{zjJxAB&7vP1eqtAkxb<0LSZsiL%GAznK*+FOe!R3`i37HK^fcT*1o znmokQ9W7^`Gtc(K{*(@k^&0(H8i!T-FE^JxhUO#baiO{!m@nMZ9>tER<2EpwFu63> z>#v^IsH|E!9eZm&mNcNpq{bO|-VZ#a6{CWMX=;H~X7<G}bM}0MF~i2N&>;8h$mMMC zwFFw}UZ6hjoRa(8*c!Zj?Xu{h5-1|GZ2@)Vd~Sd_uhaRETspjjzxud7Wl>oJT#q}S z{~h_I+YY-x7*I#4sf8(Z)(?36@3PmcF8L0-!`CzQFiCi!4BO6A@V_PxeiKrL)ZPj@ zi~iF3_(QaQbsZ;Btj$VK2$P4Ovj2ehLxB2uZ_&MoVTgm&QV^AZeYo|kT!*s-B4GTH zW%2*ea$N3~L9ed=4$?k9l6CSiWF-7yduzoMFT;QA41oGO`(Dl`Cu)?1|A*Zwd%Ozb zJWvmK(7JzCc}{-Df;q;bXZyAx-jGm*t_b{b;2Oes0A7<7$5sX0!YxX!Lth!v+!Xa0 z(D|(L*PKUi8o0O21M?c=#VJbq(k$K#gF^IA$=I@Zx2S~@%pzNoVyb`i*qF^+rhaUV z*f#E90nlXs&ArdY?ANOT-bDiMdhLyKuvx?7l21t?RF!vK&bFx*NzN(qg>wVMEkqZz zi)fODtV=Fe&Ewc0^j|MTDJ(mCUiwOHCNYZ)xVR13dM$7|8uPn31;t=96uR-W>4zm- z1)oN|7m<z}w(<)}6+d&82l=(J9w$+tfEc4pc1_c8t};JaRqc!b>D4J|8kcOa-RwxV z=G}imU!wM2hvWDZRVs&s+FJw}N$)oct9XKFYU#A-xX;-%mWWgIzh9fNTK*=RAFl3e z{zXV}%DRjM#vmpfsmkLbBY^&@Kd8jJC4snq)mhc7e`WJF5A-ZCaP)D;Uzo-qTgoK6 z&}`pfgNC7eX{;l^{D;t-YZKht4OMLex2S#FVN0!t<RSiA3HyozeG3cz(zZUJd*4SJ z8yEk$ybj@m<X4L)K=o7O0-j$2nJv~PPu+Rjj4TU=q;V<mQO!n^9tw^SP*`*OMg^UQ zZvGc!mJuTx7Py=otDBY?7ZNV}s*vy4E>E4q3k|N^cv9Mhx<#E%pZw^9LW`*wF1-*< zTWrsx8m=x|Cqv4&OY#d@%oUtDCLikRlgY>O0wAG4(!Zna_fX0j&o|#H)fC63Tg81D zve|jv%hrLW1D1AdVs@po2wQ^o<kzBa0&K&P%i@aA&P_*ac$TN%&@aEl9BsFWo6-&3 z<+`=Owh4bIJH-mh&T)m|ml-Z}iA<x3*-3e^9;}XYu>QmA(}P3Fj*Mpa5uK8-crYTS z6|I#;S@RG11epE$70+sTTVuDIZ6|ipNkd!or@dwJi_Axs3R(jiU&Wd3Ypg{itAK_M z^=6vv<<BM^)y7KXPP+Pyf+%O|{ue~t8Bwb^P~S!b&c+YN&U%D!2HbfYAK0bJQ)VA? zNfolT-?3^WCtI2<SwRkp@{^g{F3;OBqH5ypRVus9nKT;pAmw9@71<Moo+vttKe@td z{oD7>vUuge=<39T=Chyqar5FhiBrLqU1w@i)%BEyk=(J;!@S*ZHa$hnqTWwoEW!ai zWV?k=0?3E`vK0>Wqy67UD!u!os6xPpR?*wS3l`nVQ~hNsA1W9Uy3M2b(*bily|6y( zu}u!`W*Aep3z-*h9^YOr%Z2S*6%o}KhULK0x<uU%a`;G1yaQI!XEzKzyVn%}?4VE9 zWe`)Z>+?QVcF%l`Y0Yty&cc4>fe8wunllfPBROPbV$~_PcHeBL#nc7g6=Oisxg|5C z#*F~%!?I0&3<gHH#2C0oCxTc>gXUSaxOpd3=(EmewG}Lh&<k}8{Z*G^<vN))M+WRr zTaGKiE|K0huiI**=P(v>SPjjhh8RjcLs|cb`?dX|(~115B`7y`VcDH-74!+eMnFr| zl&XU&HJy5$>By!s&W{Pa#pb5BrK4y+GcU?|vVg6;ZaI;_^?W|O5xfy7kwiqG>6z-J z&IX)BnWkWd0%nh&`8F&8DeNF59Q2f(Nq4l3@;zgE#qN*hE7KWraBPfI$kE&Cd5Z#x z%c}(;;|PzJ><r;<x)DnyxI6D})q7&@t-qHE4qa2N)5@-~U(kDRax_2aj}|2c$143? z*f4xDxXC=6<i02u(#d)<kSF~Nf;YMk7#Ggi{uwogMHDjfvaHeW;2dn5MxoeKEpieg z4|?Wr*l#6UK_tiVe-G4oTQvf{gIwyrSPjZVQ7IbM+esWYWSJZvcYp=0LRNB>3a8;h zP`srh${=WwCAs23cVDTuU}JuwWW;{i;U^d#Qo#7S${sr{xPgj^?D&Nu*0a1Y2+xuc zy<Swf48CaP8M0!>J;t-MJZ#?w0yWr}jqlZ9+yoy|lacBW;_m~=tZFzOHkn90OsRv} zn6}49p67#r6-WMBkimwW!}m!7<J3JuO1wk{&wKsDdB;7w<O_NmN7BGC&)wxN3C>KF z<*vd9K+GllRrv$-O;i4?#JnFT)mCeq&|;wc!AYmW>Ke(2yTR%}<_XUIF97#slj0d0 z0QYZ{>}yi2?~sFU9|-+>*XaVh26NZl7g%;W$4n;gH)9d|v2FH<ZraBnh^g28N@Vex zxZh1*>ygKrAAEBq?Cc3Rrn~_jJ@Z<bRPFZK&SFug+ZXpvw;NC@6-!PDrKr-{G0I_! z3!iaKnU>qiL$>6#b)+MyKD}4GeZnoRgaRBu7@z-Zw6;Fj026A!Y51dtpxRIv9)H|K z*F^Fq^OQGOgS!<yx;$lj*@P8>e-YKv5evWz@ORR+*_CTbG_8Z&z9df;(J!7ajK<B4 zRylCOI<Fd^Zw?O|2Y{rd!-=$9&QwxM5JiLt3nTfggY7Rqs?$s_;sw|+ib^CQIt$6y z<KVlCNw1F_A(`=oU`M_}ve;c@4&2dB<OVCtpfy^e1itCEiU|GeR|W?zC<M_=7Fc+Y zDKY7HgODQHFlg41n!pZ{3gL?)>DBi=*4>3c-rv$?(W0$rhorG+sSDVO<Bne?G>U_2 z-xU2v0Yc~NA*kpw&bq)}7{)VXLSi;>_x3d%qkOf*+d;=S$&@~~5_)!;t<4#sYSxJH zz9%a2g>~t+D8trz)v9_{-OK4@hYpZg?JV1r8>;Q~C+dresN#F%9`Xa3S!&}=6k%3W z7(odku}?$(u-s{(cfCzlRh}M8>*;l@=w7nro<Fp0;}<=hZh(fMILLE2oWyM)8QAsH z`&tgY4gpn23R0Z9uibowu)gcq8Tfm%v>Hg;cDtJIw_@b?F!32)Xi&dXoo!+i;Mq)2 zV9(XM+XK7*b#HXP9=AoIFA_Fu6(o6cr<0baQ&U&<c8O5y_W=<(=MzrK(tt@MCaW(` zO42*M$&uU@SzqA+%Ds*Kq#_r}Jvo%W1}Pl5W*4vznZJ@YGUBZgq{WsAuyB&`Lc`p> zC()@OlS=Lv5JORQnSDDbW;P**eQwlncV1T94hNG-j8B!O-55ml=fl+}5?GxyEpmq2 zp7ABtRhPUu-exMUt~v6PU0AL2fNp32r4!7VM<aip**-a@L+lTJz}>&5B{NXG3|Mt- znhy&|KA+pX_FZL{C5i2RbxhK7>;2V<g;H#dnxwXuw*wn}OS>oCe>HSv0j%HZ;qC^^ z9vpaa2T5>G(`VY_RC?s3x@F2}(;oL^Z_OHA1X568E!*1#M#pEVH<SKkEP%o=tkm9_ z#5u-(<uMhO6<H{^psfE<?(CBu&K@$Vp7^epgvE2?(-Okom>~c_1^sK1?hl4`8qku} zOJ?d}M0!jCkw6=@>JIp!CcfcCodmIm&|2k0DLwXF18wS2RV3}@azObfuiz43)3LZz ziPPqNIlq9(mHZCAflf>Q)nB)7GtMj6IwpgAE>-(AD-~yJ-4LUcJevYONg&Wi^w`1> zF_GRz8rD0EHUiA2BR$5#3-nb6#wvUAnHOS!LgnhW`lDic9Em_~e~w^5*-X=Vj>8{U za%$$M5%wA0CUh+*&00;7<FnZxe3+;#vt-m)?V-0COAVoN*jp4-F>9z9gbjF;6S&2F zBEO9FQ8{NwV&0kNTgng&IV^!vY!s<d7y0_y@a6kync()snlQG*;=F|kz6=ztA@kq) z)o)-d%uHmKW3B9+Ex+S1Y%Ipa%u4A5#`D}Cpyrk9AAk;O+&Nyh9;G`6-Py;4Ot+v_ zq&y34eKv@;O?Ygg(eBJ?KOXxQrDK!f=TAn}YF)7+U>-0JC}C>W+o)lZ-oElflw3Z} zI3$fDt*t6?g+(;Qma$crY<qm9lP4IN%p$l(lY1)~&6H_g^sK3-%atkE?8OLU2>;q) zKPW>aFfqZ%5w~`bv9wh}$S74701&YWjMbJQjjU766qs|3Rv(mA8MQm>AJ<E)>Ww%3 zKGmy~T}0fp?%k!h1If6Zx1wj;AtOxap}l%c>X)eAnPOx(D%e|#Wnw&ql?8EADkQKJ zj3C6bPFjDi(T4Mz3LegPKKTVEthXDVzk_vbg>UX!ptVPzB^2@UaCHe-3L~^&VlP3P zI4;LJ(vyUfRx}ob<V%!s64ZjXfjEB;7<z9^f}b+X2wU(n@~340)`~KVWhm=X=VU>k z<nW-{g3K4ao`_~kx-IF7@qcnEe<ETxCatfstP3lP-Vc_yWji<9Q8$y*m%OG~d#GX$ z@J%2NfaxY{Jx2L?9k?0Bs{Y)IV_%+o7Zlu!RouJS{n<0Pwt6c@J)G9j(zY|x=-CyL zQo+}#IjkPTUgBfh7{~5U?%bQi&QM_Ei`#*}2j4Qhy-uItAION~xzRAZX|T!N`Z0R2 zuKC|ym_%v!^mn?Y(sj)7qlJH5{(#eL_}+spJ9n2FlLmLE&)=KiMk|g>KrHqM&<^8Z ze9Y7qO5S-(R&(-q7g5a)WqG>$5{-X)N7{k_2hpHgZ<U?$tyouR9$Sc9*fr#4)&NNT zPCy^~O&<HvfkFTv=~No(H>T9Yv=IoRSZ7l&{9=)kN1(9bSizjA6RCyqib0PgHC1@` z;{~u#8DY-$rDyg$xIR4M>xaS5?r)#q+U;u;|62G@Q*1lAr@60y1;g%`AgHM>xklTA zp`$M8>UHdB?Wf9Xo<gnda5Q<6eF&-W!gM6HzUg+JC4MN#Bh!sXQ@iT`i6RuAzYQ6H z6TQ)3wK*Uc^Gqq!<4@5;IUoRO>VCHv&`-|Q#<t6x6W}_Ea=}~6^<Y@k3*sxNd_$R# zt!0II$5DE&gyiyO=?dzqndO>sB2uIARx}Cx=D&#fPjddN9CD*>%ve#iM6_vnRpIE1 zVP8UhVnTCW+-Q4s9KR%F_wpmJAj#JHU|V)`_`2X<jD7X1cRqBfjX_5qLT$DdW;u*X z$VLgO88LKkdSqQt(ulgI8X<~)v&D%rNx6%vOoiPLrhvVm6-ugBT?yoA`Lcb6Uf-mY zK<!2INDo4W62Yi7y)01-GVU#GC`^Hb8&u@FpXnr_P~d`vc%$S-BdcMNo`KEnIk$Ay zphvJ|*Z$lRCh7GM-EJMf9NW6+`OWX9OufPL`b$@Ef}FR)ewpwR*+C6mD0O`G?T)=L zW$uQ3-2}sO3SB@KV>G_imTGHx7eR+qNJuEtF+o9CuuDzG-$QcyH=$QiklC{rJ(5k8 zf*TvcK~APllddYeM%_aA+G9ze&>@2KoyVL+LZV3p)(PDn#vpdGA+$kLB8mhijz_jh z9u?)iQC(QbT+ViG?k7@tsW8Pf$!7Wtkps{PEK1aaW1TG+JSY9k;WXl+kdk@#-aNF{ zpB7flpyj>*t+t)MB>(h!x2e_G7cjvaZT{zy7t$4j=<t+yc9$jLk4f-b>=+n7cNqdL zkm2=G3u830@Zai>c(!dEw|6@<=lt-0QGwy)Z90mYe_8aXKtKZ%-7dE!-y(6w9Y{mA zz}W-9m1@4Uuv^6i*v0bUJ1Vy+H2#ctBn?k!{5fu1Vk4FtG1e2#lP_(yFFenf#=mUS zK26brywP`0EQA4))e4~0=>&v~37nBysy!V>s#s&XS#EDuJ-<9J&r)m-b(NGP64&nP z)y(w*o+8JMMI$%lHubEgYblH6;_JVZ{ddA=9koN94>OhG%(gR2O^HT}H28hUMs5l+ zglgrshHg-$_(YG-2Vtm*0A0QS<4w-hi4&NkLXg7^BZ@6gLp5lW-J82hI||W=*a^@> ztkK|0KJ533{*K`DE=Tc>+EqYaTo9I~sl@sIs#f|_vv!1tX|Z~5>Ffs_TX{X|oD9lD z=1-nzqr~z<&i%z9QS8ST<$wM<L%r`1@AZjylt=Pk6jCeblzP3J>cWm<?XtB!eXV4c z{+bn^0u=_X{M0erfi|W2*7wto6_8xhSEI-_m$sgCDbl)KS!R!`pwQAW_X8vrx&m-t z)a<$1InAO1m>O?hFLq!^B<4q}`Nw0swZ421*F#8{Y~X1D$^O+VY7Q{pRo%;4#vOD8 zZ%mJv<QGYy!dpzmVUrM3jN>Z|^Fd*kjg{B<maz(J>Bc987`vMM9BqvGW|Yns(lVe% ze^r8g_G>k+D&6@Eo$*xk>@UJlIXPu635Z+Kw~_h?`@X%1l+tY_-2<TR`C$JCtX5M3 zRayE&A;;6U8QYipqBqn0IvwZgPSg*6;xWfPa=IiKd+sl3`b-$Z*^WnW(cuyx)@ffF zq<lP!M?I}HS|h=|+%^A5^wG|lxmt&JuJej1JD?H&;$dZ_zie|<sMBSDDnRUfpfgo$ zW}7PW*kq<Sf&&r!vS?{4krjIh@s#UUV`uYeVYs{L(Pr3yMI9JrHHK{fN%~$PMJnT7 zoJ{W(ZTiY!r-eQ6D^>lG9B13vxXq1xh`=W;ERoS}cf@xuc}jnQkAZ4gC(W8UCH&+T zSyne^!FNRq=YoeeEuuCwqwHI!or!AJJTH!JKC2rCYMF}OvrUxC;#$P;_440G9ovXR z%*V+m7DNu<P&<s8bG@^f*qYHJzy&Ukm3wPyY4S!A+usj8wkjaX8gYJcw}Mz9pdu<g z2eq}TOL~<_{(~IF{r%thZlQwWTZr%#T-F;iJ>8Go!pp4!B0l&)4p4L<S6n_GBsT`( zA`>B}S$ww)5Gv$=r_O(QgT!2{p7`p=w~IsRU@-blO;kmpgXj^Nmq@f1QyqGS<h1CQ zw%jKGfhTqOuZr?dNAbq{@zVU@-6^m*UMYRv1QI;mKqw9%M_xz-oI-D!zcfgkhG>mk zQZvZM0wC{Ltp<Z6huHE9IDO}m_``<}^4!&@#eTy+cqJ{XcCQEa>w$66MjpA;!?~P0 zcVg)A9p`9>R-pX1R4e0|Qu62mt+&!BSnxxaaa)<USZ`G>e!cyRtQwI}Kz7aZbI7sd zet;hbFa~d!r4=2xJ$c+POs<yJ&--2#TT)wYV1-H#3ln}%#!MrR$yM;ez0IG0*!@gu zJod^uEx{v+tB=?|&X$8yCVJT97Xj{P3qy`jlpA6=-36Y0+O*Yw+ekVC><~bj%Hn4$ zl*{#ri_S)@s}1Iso7bf#NOmL3$Xno|XY4M(XGAkURVw7YDyFd_%qnvs*NR#9omJ$+ zw@4bBuIXJ^GT%28SIpP=xR<l;q&2dxH-_)Onc>#HX{`+4B7FB&+1KlBZ&YLp30%b4 zSAg`a8dnKAZ9ppOugfa951TPRI5FE<M3EionijP*u{Y9Z8{UV$rJp$t!vHVZLz0P< zHA#k+M7y%aNA&1a!2D4;=$aqgGmiBmdgW6F<)J}b3%{HMG<DeTvnC(Vic~p}$3N1M z!A5)*JgL`Qoo6~Gt?hp=95m055~RBxf@F=;2m^_tJ0iK)a_xwbNpSlk^qUH-4s?H` zYUUXsF&D-e1-yQ5=WMg$a$oUdcC_BuvHkD*cq-6jI5P5R^q^^j--tPsO=OF^rTSL~ zkldX#uKL~reaVhigzsWSRSpq4#`KYWm4u2JdWPi)w5sZ@+4G7NxjuOIo^H7hfn*<M zF^m}Bex$V8F{&IbwZ!D?QEs0wJT<SVx?F3A-I~n`ibTj$X8J+_@aqnU+*q&TayeM= zoOiwntL;J`x11D;NsU+BB?57)MM(r(@YH!Dw`wS}8|o{M@dvnKspckuqj1<w^K;p* zC}3};Y=kYK_BeYSLF_w%p)Lw@rI0jPE3O3vOx(uj_Z*0p5F;A>8uAt^-3b>2wX5Z* za4&yoN(O{HGvQVcR&9fsC#x`diB4OFFE?Yap5Z!>j!h>NAFkirA!Iz!$q$Z1<FMeG z*$_PGdIt<vIbVw_-^4v(g`Iuv{q=z7_}Vpj^t}(HAp@>j=}Kk!U{7V_@0iq?aR5qI zL3cX}Yim6H*~novuZM3LR=NS|{P~oPX9ZX^oq8jwtozrCp4KZ-+(j(6J0`e}&0yMh zO_o7l%Cyi1?@z@ahVcWgd;se#;GUf5yh)^enupyjWFvk??&V)s-N1l=-X1`V{)ggq z7!~(>upIQ_GrW~-L08pezWArML>4CtcgweMWh?nrKW@TYMAJri5}V}p2b<@smaf$L z$?XK<c%qIOKh?wZ)9as%Fh$xjDI$0;ErQ_PMCV;UH)K9Pe6fC3umL$sV6OGPC3)#> zMk!IM5MB$-)o@Ge1snWvII%c(&15cd=D}FiOMBkG@&%J6<R|!mBgx3NJ+E<b606oz zW3T5K@TY@b-=94J*37NP6wk{_L~?-jlT9$aSb=4R$e#$sdkHA2@ygs4@W)hN7}2cg z25!FnCeLMWyl%Cu=&@p6XrAG$BqzZ1wzQM)^tUH^Ih?mdZREd?NGU18LoT*t);!x- z7aw%Mz=>w6`zN`sbTd-kn)gL-@&mG5#mDuKgcshu>_4A}I7jL2$y)QYlLfYGUI}wJ znGRA1-3X|NOx&0clH>eU#7~2grKwy~2v=Ux!Qzm9Z^l_*I;{gI3X8KF<U4Y|?+;Jo z1Q?$$p9R<r`(=*!I>B%1FEv)j>zbijbi*~jsqS%u$q<5Uerfe&(HuOEVqOGDFt-U! z6<EMW9HU=2OjFGb0OxEdXvL7=Emz8HF{T16&tBQ2ishzky*L<rta&8CKiZUFScA0F zh9|b29&D<#>JQKTSWxTfAn>X6u1FlVro>kg5mNYW*tSMGJ^y{;Zv}Tz6}i#^0_-C8 zC9j(IC`iryA2gD383mKUi#a9l33F)mZfatY(YMBhXr=r)nhCGb+FVcKbF{&12q5Pf zkC;Q8bGH&auBr#H#l!c2k6nIc$Kyr&AP{#M_+c_B`MkLVKnXoB%gG$u9yd#w9oq~Q zkt|h$rnR}!FCJSR=a_j-L{-6#mx<iBXLQsL3Lh7<K@5&<#00!sqH*x|4Fv~np($4H zp8K7?m^R+MS2G^D4I2a2@_e+waW*I<p~<gP16m2?k2WNdESF2!>4=739BYNw@Ka-b zk{Q9=g08uCTwoxDXlKD#X1bfgM^-{h<XXdFNBkql>&|YvVlQ=XaALIlCyw85YPlC< zb9Bo)AM=xu&NbE`QK-C6>N68qSa6J*s@VSWo-?PE9#d7mMwT(-)?TBFD`bZ%xhL5f zjlrwfsDZj=QMhc$;VY2q)%RlA8+x$A;AgnU1$4_3MM-y|y&i{Zgd_Wj%pxOB+k!ZI zO-)%qX=R9IL?G!NV=0Zh&t$8ov&YWOIVs*vvT0Lj;R@Zcy@gxOQd1?g7w4GcH4aB; z?)@p1;%?Ft-UVeBX5oxTzrOm#%{_UNS~`p}<_W9bkNFTlbo?}46+UGs&aQpgW>9D- zW5kc_a&Wo;L9RUivG~Ig9ZyqN91G*%zFRZT?_xty>R~E&c~I(p--0`ZX4+W%`R3?J z2ioCN?Z1A1R2kd(ma*-3Rquv$mHO_#Hn}lpxfJ)^#kdg7(D~zn2aq0m*lZP|>3|Eu zf7`6hThRJnA$-obtW6p(uGG8}H0E0AS@%pHR04jk38CS#zqub)pIt+$kjO~#H+*?T zS9~+p6V(>}91PT3+qOF{Z(98hzg2v&@w(p}zqX;xYL$U^CVS^DxqYLhf(PL_&;Cd~ z5zJDPPOcQZ%Awt#$JCI(%NNuH%BON)zKA~WJTC^6KXx+B7E903Q#G_xx+*yt9@Jt6 zW=(e=rSWEobQ8>OtV!FNck7eW4-t?v5I5-!)~bc1ScEq7j3!c%TeIR5CujK)k@5WK z$(f&%zMEA3v7)N8p>;q3<0DsN={-C{mUDNu1^7)`-<<$7cW*(+aZo8vaOgv9++VEb zS1Dr&WY+V<vK4evdUP@UpBOUX;`y?{N<%;vuZFG}xC-I!k*L7pBLB#VZoN<l9pXtb zC11W9B}hyfu>|GYKlC(5BU#v{-72d&l3;NFBFp=kwpof33vjc4*-g<h#&(2ir&f{l z*a6XiSVr}mFD2-|a&J5oGn-!!d#2oyP6zx(8nEq3<5LyowpwJVDw*l|WNWplE<A}o zv}ONP`>g+sjc11qlDxpfjqB=enTwNMGrx2VSV*iyADN%Ep3|Q<p4U6~iZ1T{<^x=S zN5s~kiSJ)%YvKp>>@s-tj1yD9#rA@Mqvu!8k1ZigCjEj9dtL6G^idgZVx!PeSV$D$ z4nzBaHFT7Y=Ja$KBk9b}9`@RpikEbwoa~6Qr*g3<jUnj<ZZXq=-dZgNX{v;{ASte* z6N%MDC*RgT!XYur>K&p4Lcfi1(QET7cn0zGjpYV78l6lK@Z&};Gi0%OPU?llNU9Ai z3`XSU-yA%rxSl}DCFu9BkYIp0=VkMaAnwv(HaBC(kL4MHQ^|&Wma~!k0+(1AlprUJ zKZsG;h<<Z<9+g5-!MChOU8KH_t1ZbSw#=34A)KF)&fbs7(IyivtfQ+F_Re6?Cm-ee zE!<)ji7nGk5z70u^eCzH!QuB&_jTk>pF&`DET3o}?-~$Mf-~Emb_qaGD~1Eo8vcr} zvG+-#=plOjh}y#3r9N;>(46QAq$ajiX2Yi=4=2Z>YPO$FctyZg1#Cz97ILRv07bR^ z`siouoDK26zBlkTWiRBJoU}16WGrgD=6|cYEQT*}T4D0{dcxo94)8S#3yD=upLM{i zXg~Vjof~n7uX1{n`-S^7cS0}C1A^9fynVcHT%WG?ThC~uZtQ5)N{K6*R@)v<Q-yTT z-r0XxiI6=PRZ30FEVR$RR0An#Px+Z8ZU1o0vOU`ngTM56^6HsMZUG=Cv>*KzoY+Sa zhR}?SwPuks30{-=<5v9%O=`Um{mTCAk5YUIa~1z&kiWJPX1a2XjPt696KkPpu3h`E zWB5NYZVa1j@nOCUPNjWRPt9t4kx4H((z>g(mxuNofzm)ir(#vMm*+)|p#D{@CSoa0 zYLc11y;o_0Bqq!3LiG<Q-U28@x@#mxXL5+Enqr9z{Rr8>vFF35sLB3hW0_Hs6s1FW z=xz)4A;*KbZ9eJa1SCu*r?Ihmf%BDyO*kwx%Dbq{!+t~!43R{0FsC~YFfvj<z$kvs zTG^Q(<9GqFkM)L~s5Tu!#*qG|F()B6Ix$n=Rx?K&;!d~nXZ?}HTbQ0Z5t;;wC`1?d zGSdRe`jp?5cM4v_sps_;A-leipFD8c&QRn5o0>7V`F~H1qllEMjx#1sfBBrTJr<Um z9MLz?LqZN#tKi=jufqlWv<p=qu1%OjrDfKcJob6(0U7v4XA?d5ofP8ix$zY8ugebv za@fL;elaBvey1yzGU{|etnd6d)kqCkh0H}3K2k_0d4o(ka_tKZU(6DX7#OrXIqVb$ z;GfF_+^50!-^Ahj<st0Pu-=5zwUOrM_P@K>ihf7f=B{c*`=FXP@6F01shE#v^iA%B z2iEY}7mP|^_Ee`!O;j=LUbLzglY-iZa~A=eShQXPKpvJN>*c-R1<W~iM{RjeVo7Hj z`&7&rPw4%hdbeRg6f0!Kp7~rH4iIGr4XP~D2iHxYuFJFtNL3olM?RaIXig88La;KJ zdxZHgr0PaBn)HQ&7$(T!O|MWg+I7g!2&S<+DSF0)YHq$y5x_(Xc(bfVKo&|1Ny#>v zM&-RZhX*zY@=oT^Y`&UDGk7eUOF<33{j<a+<&au9Ek#y4m?0xN_{TD3+Lkja+;FVI ztLwa@KLq%Po{mnq*;dLcH8?ANs(|aaa6d8HX<8^fpE$uVL1sojxJ+jn$V~Bdvi&bu z4^DT?Yb0g;Ivc!<{Qh3_C+<y{v=QGm{OERZ>_t3p?gTfkfo~P<%ebFf*ngXp(Ux4S zjXq7+bpE|CXmq{(4Hyy-Cygdj_qz+1dyZa6ez#!96vuW|?=AnoE5G+9IuHQkp#!0B zpW(6QqfXqK`O99VElFtY{98-s!g2g{f2~c{%Pi3$*Xi~-YF(>|mq$kMgG3;GkRxY- z5?II+vbtpo<a!ov8@(j@-868a78UYKKH)-<9~Zwg6LeqJ4hDMRB_-}W-LBo1$RRQV zc1-lbHW~+_(f9fBo(Hn#f);;`rX`8)782Kxe%hMKS2W%{2}cei%BGhaqxP_%6&gF5 zF*lt;chcTIu%u%r)_sLPS$mW#n8Qe%@=BK&V0al8kIIPjnzg8+TkHPOT}0C3qhWPu zkf^xiu@ph0WS_!gWS*JViV$T0HY6|27)LEbuZ--2Xk64#MCWn#QsvwMm+8r)g7C<4 zhCWlxaem8<bcJb}1T2mjzfZL}fi=JP(6kq?(dL3eTNc5=vz=6bDR_uJ;KN+d(=2+e zJK~Ev03_-TL8AeJ6bY^aV2(qp?^OmqZpJo!Qi(x-Cr`VZUpT{qto9758G1R?YP!19 zLEp*5qWr6bC>)-@W-#vB!Fch!hzViima*Ac$gP<s!NJ}?kts0HxB5VR;%H=5zCe@d z-(XM@0O3j@wxrx0tCU2`8Gjlyen<esZ)aALf@T%dS)6h4eC?T5%HDui?Baa{Rx@l{ zW+49B?)&>cj<H62cvPon(G16=c(-T7Rt|c2zt1qJV=m+d0z`?8Y4&yHjEB_B>YnXa zV1vTeWTB)mQDW?dry0<ScDOs`5CNztEEL!QrwP2cDU}4zd1>msAT=NyqKR2wBk0sv zPjCCu!R7uvi~|}Hx`56*LAWU=rwdY#6kKJ8leAFacrS+Z`e9qOM)$VI7p5=Dvo?PY zw_MiAN0kp|&aiE)wsFbX7)lbkvcSakP{hV{+=8shj*tFE%eNHoaR4KLZ-F(`5kbBk zA!vA=xv6e~Ud0(c*kcp2M$hs`X0Jxuogxy-WTf7)N-MonwCs1UlO1p~E~MUZzf0-v z+(}qTJ4qDDO|_4_hq?y@$+f=k?DhP#9aIx0j=2X`8GZn;G7D))<3l{I4BA*TTY_uE z-VA^o_9@RiV;P!=ROKZef}+tZMp7eJy>-h%M%BF-DE<#yc6|N)TW`7Is1km6D3n<} zYkmJs<0=!AS#<&WS>wQp6f*ATGbK(){P)$=B)4}{S}ysQ&KqY<Bx!^%D!lBrwpl-N z{nXFFI6whp3xD!zEyrYw&`DXOEZ+pWn63_)Qto^l`eQw4TaVMIK~r70NP>rLHv&K( zehEd*wq2~I1jXo)7+GN+YzzF?91_(t4=GU7tjTaHemUX`ld8Mo*QSM+oXGpVKDzPl zts?R@N%AEYt~tg;*1<-#;U>546H$e?)^p0Ew`fldr7@+)fp#gbZbz(BN4Ds93}3Hd zy#HXjCehLIxgg1x!$yQ$?IDoYl3Sz@b9!7O?1vA>+<(pU{F5+vXIB^3Atd9yU`~E? zAx+?P1<S;791_DqY=_~;4du}459YiM-d4g#!u;dJ6>J0PjB*wm`U~nqP?Vlp#!>zS zWIxk1AwScmSDimV*nfsaHUdtio=xVnP@a#TXP&2DBaN%MFV#8-8hgl)@nQ}$t7o?X z@Y+<d9ZNLtd;Tn=<4_&b)HreV#1}UkmPp=kW;j8L?x}@JhSMp!Rr$BqUVlTsRR2f% zLIge2X^qwjxQiX%nopeaW$Ii=8hYWHOmyOV>;|#>L0(h!wGp*Zw_5nBheEQ2;K?B_ zyR~1acl?^D-^0^;Btw>@by>Mqr;9A{L1u)Zy?*x}Ig}~0N@?uMZU6nQ9rQ;)@0+*B zQi#5wh)J~S#XICLc0aFmI+k*a^^(qy!wS$dPUx^Zx6aFX4{Qe|S}_tkL&0%!^H)~Q zL~p6T{t9L&>0KIRT29^n_2wtQ9sA0`AouV<*ZE@zd+_dSlzw|VadS*J$t?cya&(?U z@aSi0l|LJ;E>B<t3xC_0w^+y=3a9lNINJ<39Gy%a?x=TqHae7$&T?1!zR2d(O%iym z`NlZPlZ#Q$PKbB<-k)cN9g)mZ-wr=Wxk+psOO2dg-9G?dBma%I`Gy`RB|ls-Tv;=} zXPdtMWpXS37iZXNe@DLg<IS-5xEk3vf^9?ljEd@P->Ygx?TQMwk8|pSWcE37A?D56 zj+D?ip4zne#v2m~g<8I8wl}<g=KE3-V}?6sAyOn~s-qY~J<UAh6t1?^h~DSw=QNy7 ziP>x!(Ld2Ek3Ft{K_>Q%B|An^E@%@Y3g-(U++b;u+L>Jz>nDMZ#^2H3JWLcFCCC;P zzZxqjn*U1_FDv#+4oKLBHvAD`!&^AVk~7e2;A$2jO+Jc>qQ2nZrK})MEdfU*knQhj zvE=kq?U=63h+AM;KfLOYb^j*Fa>)i^1&fUFjOv*Qt))A29j*DB3fPS!;qJ}lG3FO% z7%U=mh$fPqt;&#EtEau`mS_$F<M_N_aXdNA`+-J%T!#7($?Uy)(N@OocOX?A%evYR zP<GV>5j`|RuWP!Hui1VcEr>f$(15HAITJBzRDO2!9jl%x7L+~GjXb}>fHcM9wis_! z;a<+mnh6*1<z!uky>8SZH16GapEnMvCEXA1b=|Pk7_EBbj~~}(vDucXU{6A#ujAO0 zbsBOOe4KdNLtGwoV^`Uuk&c(k=7`5!EF&ukna&w{dGwV!D1xf~s1x$-Lep35(~<W` zs_+MCX3xh{#nAqy&F#|IzU8{@DDnPos8Ty?%^8zX2wj@%os%2NeM<2>5nV<@KU?QP z?536Q;pnFmfDLg2IM3(UvSUnd;1F6cT<u&LNilvoNk`#<O0h7Op?wN5k%c21N<_0S z*cO+UCqiv{5rQmZl+d`r*w~$CGz_OZoD_6vtjf}@G4xWZFgpCtA_xBjXQ2i?CEg~= z&oGf-z>{){K4WJ=QVvoNUKmW^d&I=F5K&3nnuo+Y5SnuE>{P51c$6t+bZ>M(w>;N? z4|)<MkSh&c_$bbHVox;d-@2!m1NP&HvBMgT->-PBI)Tx&Pzh;r3_5!2H-Xe5Term1 z3JhK5Y$#QYE+r4<E(A|`xjRx0-LqW=EvBEmP8-&QxSRM3_%lke=e*6mEIKXyZ&$qW zd|QmQ>w|i)O`nAS{+Q^Hkj#(Nz<?g5c0Lx0)$b|zDldiK_In)hvO>V;vTNFA#9Yiz zN0pt{RIk+3b0zSP1?RrkDF;<d0QJO)fOhf7#Zb5SD8U6ya*5)<vo83Qp%l`u&<{_s zPUlM_HrN8pYAmC)FsjnNWh9d7vyiTSe+k@zw}9=3q7(w?Xz64lKLG|^$ub(M2J9r} zj~}zfY?1lJ6|4F2qW#8wY`)btqvII3KHBnB5St3%IEfzGs9<|D7lBy7wpko0M#4O> zT&vj0^NvS=nAxJQiRZ=Hjk<#=_f3nK>h$*&irR=LKh}h#sdzAIGYh#ImTI!?HYknN z2{wN~w(k@&QS~8l@-SY^A!r3FII)(bX=IC_udPP}v#;2dD)$4i5*>r=JqkS6$U5FQ z$zOB+h||x;JNa{-<^`HBS&bJQDj16$M+8?j{+p^aoKKaeg0<bknJn!xJGtXnk|%rd zqJl1jI*e~<=i#k$v`{Npr1w2+SlqYf-1Q;?#UjIuU5@u17YN5lx7MWlHMPAqTBqGL zXdo?5dG&5*0x0n#XPn?BzSJIEqS<%0?qiiQLL8%?AsbhWoaE@NBWGB&1-(*V=lmsp zbq6I!*f@6l_w4a3_H3_l`V|;3pvvwURROE}t#;Rkv*>_`wDEn!M-i{bR?pPsPMkKx z^^Y#*`}It8Khqh6(~;0Dx?cMU;e)APvH9WYn&@h;P#Fv%9(_&4=!~0c^)xE`P~7=+ zFL*SUk<v0}Q}5iYR9iOe=U5iL0@d4QUmi4xHfn3!p>F!5*qVB;ulmRG?Nk8P8w{OZ znK3cm$Yq+M<woJa09&DWzrEI=m^t32j4EOsLD5OQ4`sF?S5Y!qY3!o|$$043Nj3n| z)<wC`Qo!js+=J63()nvfxv_{D@wZxRE`gA{K~sFio|kQa+8V=xHZ_Db?nw=&d}AL# z`V<v*Va@w})#4i+S{m^Z-aBiO9Vo3>7tiF!yJg~`GtmQDNa$h<r761w<SHdEw)t>w z{V-CD;`vfUIuy5mVx@u$H}qETxA=KB8l7N<S#ze>)$x+fF>|j^)miKioQu|yO-B}G zCco$X4*u4^NNPu#ivVRsW<9T@b}p<8kUWd~UUnPw*m+hT@s6pC*Y2%JKF{VylFgpJ zD=isJyB>Tr7WeBw1j1Sxj^}9c9k&5REjyMocOzr|#_#KQ%g{DP;{K96wf(hY+LDy2 zJtk=`IeyJk-8czik}Qd*-ClgD$rT-w0M;V}yW&x5(A>%Y053t%zINZi=f=J6x-Y-` z;Dhy^Sdvg$h3J-@HyO<2T#;V$7D^PIOK+_Pi-`!&f=|bU$-v@S@#Bv_{>e{%;vM*J z{H?#m_1ojs3-DpM1<eJzX|%F61Q~}AO2|w05oBf+8StT_$T)M(wL_2O>FlKZGo<ev zYkjMm{fz8!3M`?epX9t~X4Fv(Sqg+vt{}sqU8)NVLSU8LMVtHBDafmX-9z4VC>so| zAw964hY}_OJ$^Z%Jh?*Q(MB1RA2#<I=PHtu!-p)PZ$_QT&6H*PSN@%B;k^D=h&h<p z<~3eQCDP@jkc+*M1qy`hLaHvD%sY8T!fN#9GG4*?*_YfT>{`~f>2Plp3krdR$m!vB z>12J{y@sv}BwYy=c?ax48v{cwwd5}Yql9F37}|hwB;+MS#w$#o2*ox8ZC6nnWIc3Q zzYX?QMw0SCNzyas1$w3Fb3kEHFO300Lz&ZIjL{6QTo9kPSeBh{4I_k|V_8gXr&%Fn zUMLpw4n%R~H53)?Tq5Sx3-JH!fAT;6<daX>&H4vF_<`5pQW>sR_74s{d;UyH@r5v^ zKovoTBvd`iS%J1qoRRSGop<KP3JuZL?d$U66=CYSvAQM5D*Os!5ACu!7yk{r-ELU( z%F+bw6a1C&d*eR-c}>o^H-C+7?`?SpZraiAWxf^@RR(CN|6_cs(4pPLYwS{$%^{fK z;l72}=O@o#X+Jb9KV-LO+FezI@zRr5N(30)ZkKAR$W~gzGa^IRlS1TVL7shUcqQ+{ z*{5iA$@0MMp2re0;-_5UAYG8<HTH2`l{mCp7+Rbw=Iv~&_0x2kGIUA~A`h~hrL%a3 zqmXChlAN6Nyuy3$z1M<AJL6#7#C`TbvCwep9@a}g6-}P)_k9Q0)*>5{2l=$;VaRYE zo|XGvfc06D+lVk3fN}II4F8Os<_<gDm*)z*_+nb0l(Rf5SGdQ#_*ydSjzZz<VBMSN zZu|G2*Q&VrE))J^!!xeK`o<f5kJp`PeTLQL4z>Qg@6%`By}3Tdh_Pe+<npu10)r&@ z2)ugX?9pf?x}-W1UVeX=A_?6a)|X#?xdYe3&${DZUZlAYR>sqH3EqA9jyFk<tjJt| z#w*GM5wtWfZt(u&4-jgpK9lhwS~{p#1`nttS5+h|10BJzBwu~?6+Ix6qChGc0GTcd z-|YSafA{b1e7`N;{G-46hq|#qs&*J;2TMa5s;w}+sn*9#6`{pNXhrIt>|j9rJ+)&s zq2#w=&aH?*8HxqQ!g06^DZGpnL*$Vx>|=@6au=Hs%BCC(9h5+8_2~`_SBOxQp**ER zlN`ThWHUQ^g=^{>P6NDLhSqlW-xXx8&~Eck$ofyRlwSi9Lj8pJx+1fjm6i0a<EVKO zGA7~cufMJqFe0l3apaj)P{=XZWDQTxtAop8LLB=IL3JEn*_0!dV}vmZp|gm}QiihC z(kgJ8W|pyshQcSgwL&&@P>LEkiesmxm^;m@Dh+{UjF7R$#%>6?7-zn&i4-O1d6Cl# zrxY7(p)A83wC0R0kx4;%1ldX=w%;8^V0SDuAl9(7Fx7*)Wk9oHlE@6M$diAfz>4AQ zj@Gp=P6RRqb~~#d4UjC!I3N#8sVI4eb{nc3+D&NHQj0QKLvyFMm=Ug^BB_Dep5`qP zDe4M&$w5Od%59vdgVti!{MinF{3kzK0T=v-{)7KMFTl2?E0wu?^wCG=^~+!W^0UuA zLv~no`1zM#y!Y;-XWy+;n-Rh3Ecpi?e9-rep=^8k_X)VZ@OvyWyTegS7HS>B{o_)O z1q<)D>r<nTKRK=kdK>A{qemKx&&2{&dHD8?>+|HNBeP?k&&Q|F$@O(5UdHkOZ;Cvj zp@b<{kYRUmTuGoFW_X23cm+Ki+D+VNA0P~ea$o-YfPc;aEMtT$O$ufmawX5$K?@Cw zg0l<knJY_Z-Qowvq#lA{YYv;TFtnt@+R?{%OhL}P1C|m}A~TYski3g}59;$Q&n?}+ z&Fgtppq)$^<DvM^&Uxlj<j(@*h5PE3|2E7^LQ#|XoHpeQ>$9u9auwM6Oa^E@+b6f} zhIeAF!<)Nk#WvrNF}MzJ>1qz#a7Lboan4Gp|JxXQ{Hv&v4_NNIJ_O-su-sR-<5kYH zG)?kO97!)7u7>tXHoQXFhCj;e!-gfH+=mz69UL$$5b};b%D3O${d|6P__Pfak3?fU zEB48moWiocV0xm-*%@)(KWDtL|8DT^?na+-lDF}4Iq$%I=kMju)*dav3{%cvTHWq* zk+Ob{3D)S%hx<2yAH2C9qTYY+k!|KC>SgBP<A>fIRYznb>8^6!<5u|Pi6VHUI`@F- z3hX4BH4F`LdYDPyjU15woSansod<6}e(&MG>EHBk>XxmOKl`&k<8q%R9b)|KEidEe zpMB}+$PK**zja66-{a}iq0zvUJ#Xm5v&Y9De=HCIguMU$`-UD44L|(wLp^w72T^tS zi_d<g9GzE{is}TDg1{v|*W>kfi68#=|408LoZlYn&md_+?Z)Y~MY7CVSll_Q^^^iF z`g!eG#IB>UpD7uE7jl*PPFTJgh|eN~r6I8JGH&|PXBa^P^~^YSmb~3rv&Shz!#K!I zWE8HUWu%v9LV%Jn=D5g}{ZfuH{9I>33Y=Xdt4r5|&0%?M3)0@ojsugNa?S~i$un|6 z?Lo$IRgT>B!#Ii(XPk`^hV18Xm|=YembE$?Tw-GyM#j0?5)lfIkTP)M2|2?~AWe!F zS@@KL(vD04%xMFyDu%1x37fmfR*WoX_MPl_kdg`kDjmObenPSoTPm_48gI&U70&ab zh}x4ro-#v(N!5bT%UMXw5UrdA#t~Ro2<n0i=YF`XKMuX=41pXNUZHR}#(TcI@+;)M zGaL%P4ScaRLoo{$7rj>CHYQsY%_WTGjHz4HAmg1V70z0SjqK;-dH*y2ng8rD-uOTM z@BTMlfL#H=UFY-9KgTf<^I|bUGji))-$Z?}jwU;Tv~=EXT3ti9rpd>T*3BEF+PRPG zjN>SrU2Npll~jAbG2-Vcw&6L?N(#sIbs<7%9T*GLr`@$S*voa7HJ4c^xLSFZkuq%C zHH7b)$8KRM$$k9$Fd43JxNo5ar<~<K1*UFF#w^hAjI;f$U-c8{x0f`uZWQv24o6H< zI54&cvLDnP&YL~g$h?5iQQnyrh7+RU&v1;C__s0ko${4Fd9HD)2<3-jDP!FJrSHTG zS>Q~#!a==-!+i@}Wea0Wxs5B%L`|OUTsRXTBfKU#IKJeWQ|x5e$qozLt_#_Z!A%VF zD&#)?*yCSCossL_<Gz7&2FvT~#yQLT^1GA?2{!qls5@~xIVn6P%df?>KOrgQfwQu3 z&v%%w=5=t{_q94>s7m`JoC)&GuufR6lHbJQ^q;f5D*6h`e+S~PT&FzX@<X0mO1Te< zuyQQgapl_j`;Q*4Tk5;-xqlfuvXWvx`}UbD8iI?Pcbu;_JhZ#zu|T&uuTkJ8i`$S6 zLXb%b&-~F>PnWi9#$t{PW=Af|TW>ym_u&sd{Z#%E_62dVIHLf?P?O@!sBF0?4sPDA z_6<wem#Q^Z33&|ZYgsNoy~yZ!pyAW?1K8_%%<AEAu~&{{51v)LA;Z7=AN&vE{PtL% z0<Ax2R*<7-5yP31R^|Z(4C6yglhGdzZ?ski^9nn`-EfRaQ=Mfsl$@Mc$;%I|(I6uf zat;J~v11?0<e`MTCPkWlG{$`(j-Q)_9dsNjLzzon638w@xF}vmLq-<La6%bY(u?uz ztp^IZ(=X8N;EW}NhOojeNyd^g*pyezXBi0&hnx|@5WrAlXCt{;ubyTy<{e}Kgfq=7 znn)|gxaYKh1~bj8aQaSsAa6?i2?TmxFr-hOh6P4QsTtT^92Jq%#~a2K@-l*94YaT< zTnK&CJG~G}Cjw=R<w3hbN#b-78L)I9nsQ)Y9bdYNKrhwGa``&cVC6ck2^0cFozHhh z$;%@-i|Qd4oM~C0Y~*0)TTJpG-CXLb-^Ss-1uh|7)9X-IPIlMmgK-n(Pp^6nXQbph zBNsWyekWQVRRVn%d6jl2ScL!d%@^SR+yC|d?5e978M;_K-k_V25Ynq>zh&#a7`d<G z_R);~zm@fNx;L6Vx&A$RZ~ZYt7H`u2p={RLj30dPzJHG%y_d`D^P|U)#PfMaHY_<s zEmM&ccy~!zSAJ`;e*u_ZU)h%a{MmCZ!^L~^t(Pxeu3PB0&v8xAow7ACuUVYEFvn7# zhj)Uj<s}=2yx$)sxsAhp4<el9Zwht8Dt1Bk(MM)nVYiCDMj5aS8t%%+>ZP=Avygkw zu2aLY&JK|SSE;U~?ZHcFCqt=#5murLVrINjhW{Fzqej1iEa&QHoWrl=z;JMwZsPm& zd4(h0#)Mzx;Tq-a%ARrb?Kxoh8vC8NT^dHet)x#>mWEfYo{{mY)@_{Ajy&URq0bh& z6Su>EBM84QgFeq*!*E|e!%R5`HXO^Z!wp)2(D@k3x!dXYKktB$k#LY%?&^P6Sj=b> zHA*lveV~->3he9iA};#K*WrHu%66+0#ji?_>rO21O0%HvW!d(39;`d;M<0H;{vKgJ z-|NNi#dlvndE$k^vOazO{OfO?_(%Ef#Y=a`=Lp|@_sl!t^KYMc*WLd-TReUC%xmGZ z^$WTP-}ZNa{o`7S>*OBx@688qz1$zyp{xBV9s75!HTPhBr`kWRMPS<t?LPeJCm*Yz zL)fq4p308Hgdvj)`AW79%UfRR-Nd(XUEV3uxM;gMlfc5>rJK&)eSaU=1v(l9q1R*2 z6V^&X!{__Xj&t<_Tn2g;w-q5czq1!$tB|&)emOZ;zo&au6Qd}f0_P}T>CsBZ_`qVq z`1JC~*(!iXnKE1fZ9Qo1FaLvKD4`5$(aHFj5gNj7=haru8w|&_r+BO^P{uNK+1E_= z^b2H+!?@$_&OfQfD5oS~X!?c}N%T(%XanJg^#pba$@CfnyN%>pOSX4RUO4C3?Ysg@ zO;Yefv@02=9K}#96f%LTcYG&pWJ6@$m|5baMB{B(a?0$J!dWoUY_>JkZQ*4Ml^#r< z$PGh7A;Ke5WDX6JXXJ`gY}xX{O0<!k5_1Y=OhQq>qNVAdMPNEKl*IaHU)eX(&m3SO z4Kq%*m?2|c!<3crk}YiRfwAZ_T5_-Mg7y$f3pGP=%_<~s_U4i@$klnlyXsxAI=C!; zI2_w`Xg6`@oWWkh6njivy&1md1(>XXz>+acA+EC=+-V$WfGj7VNeGPez;1Z;0{nmZ zKm8vVpY7kdsDIP>>Z`9l|NQeWzx?valP88R_nonorO4AZlfSvMC+orDzj(fGNG!XH z72Z%_cObROM)7hizWJ9ng`E5iOTwa?m3JdMaIJ1HD;aZDSxMid9m9<hlHshwrrd$G zxTjM97|AL6Jz>^`UxDk;ZX)|_`A>(*Fm3CH92Ydx8QzB>P@oXVI8Z1h*GLeeI#9-V zyPs`d7~@FjK2C9n+cQlq$pvdZ8!?mL6Vu*V!r{Ij=LR4noOLk3jC_VdhjtUTar`S> zr9ETUUubv)Tq=%z6u3=jc;=jOpZzv4OAZag)sUXWI&AL3nJ}j_7#`Zqbt~lc7*0vf zsbGfV9m{?AJ{(Xt+Q{?pHo6J68_y{4H8|pL;x(>oyu3jx5U$qNFsx5B{B=MZDb=<e zD0zr*9}d#xlx#noL-MY7xc>V+aX+ynSK01Nd}f}(q+2B}<4xZ3*^{RZ@rNILuzr;H zz4tg>&Gx4}KlhqSr<x<XE1ugZJ#^g*aVU&(+AVS>*P+?iyXIJv)y%0|^6W}sY*lyI zQa=6U6D26%Ie}SG97?-XRE?4EzWa#ljB<MLs4=>>4Y^n-j9wV&yZ(AaH081-4S})( zFTXK*^#V-a)sD^)D)b-vkNig{zdas&`sw-r6{!s<%e0}S&Q{}l6|7X<XgwqB3<vN# zNX-YIMF@GYH!zbO+S`~Vqe~?m=%j4f8?JPhvn!cpx4+tG2n7O8ItgeEbB!IcNc+t< z-_+{ixV&3VxfC+g37m}}u%pgi-STv>&nN>zLztXlGN%lG&->NVRgPs*H@F7pVcs(` zjs&SdEijbU;ReRxWHBSMuEsU(jXmUrbDjZ9i%*vU=rSOyl5rCk(v_ZJmZUrd4jPif z9J?x6D1+>b!4N1DK026bO0i)$q<zk!s~TewqItvNAXG(Hyyy1f3~ey{l(QGP<H8si zqvg%Gvo54dHFmW0_{Bor><zP=(edKllUT=^(WEGWE2Y?RjeSrOG8cZvJCXM`WKf0I zl?o^^t$&0oAd@&0&>mP%u@TNF)lT_Jf$h8-^%Jsao}4HO7kTvp{J;30|4-d)+`vE* z`qvv8o9T=E<u8Bv<^GHL;F^Z^bpJtxZd!$8w*vA!-+#Ui)&{-2laQjedHqUKQ9|6^ z#Xj9H;p}lL5m~I9Kw$^BU_%{d90?jG3#6F!+wZu}yx{=?W?7orpvC#MaL9%!Dh1B^ z_rdopcN+zs<!^*N*BjGsLAvf`p~&18Z4X=(J%i<pF^-gkEKjIJwbX@bO-M?#LHuKI z%HOd2peh}An<4Uq?5wXYLCyL$?z78Ztt<JOJmDB$uxf8K9D;NySq{=Jk^Ks{GY27u zb`xcThO4s+vOwOES6*Q3{7N4Q!@ROn?n8udn0Ed{+sG?<>u|0TZufJAyl^#_E8N%r z89U#rDjDy?72);#o$nRlYIsJjkVWS(!`}$!Jg<ir$V0o?!>s=m?t1~Absl7~(Hs6+ z9EC5qvUK7PGNx|%y>Sn{6aN^T(05NmMZ@j+1}-s6UP>ije7pPK8-6_pcWr#<ZTGfs zU##zZx<&H4905<~%L>_8Tj5fXi_SZjR&Z@h0h~j-=wliFU}fCkdh5+M+{=IP$tPAj zrrS4JGkWf7sX9Uz<OgrP`r%*TGUU~pM_Ir(1d8F8Uw*l&ZeYq#a?`J3c_?eb-m{*r z-(i;R>IGOc0=ej1GPA4lAN`O2$II|r;?2MMSN@s0X+9K{K*v?(?NLT6j~_oa0hU6F zTJ7)88r7WE)1g$Fj>$gqHLwI^v`J3iO|6@;p+317wV@E13sP7-nMEK6ViC>>5t=xZ zC*$xPND14=>{TbvnM*hd*OeEf6{r@MY=*h$5#T)ELBlapWT?qxXdNI<lOi3I0&^vy zJPqlCA*9R@c<Yc++nvCzb4LBNRuuiLbQ^`2N>`*j+qTeBWXBmaY_+4w%pw-fbB8HJ zC(pwxOG+@*r=DdqRBPH$D>8XjpwhKrD10(R;Eh9e9u4x6@9j?~0t7>g=}b}7`@^}P z!V$PA6{SoGu0aG61PYM~$B-8v*1N}!1;$B;S%#J9GzBMqN-{5+sQ({zf7WALwk76a z(f6mzyqQ_Isp|rZB3}p)AYc%Fpa2?hM-ie$frKa!CZren&6Ze{|Aqkr0%$=rilS^& zF34a(5Gk8)d?FuMpbSVw(ZF@p?J`d`r;j*sPBi|;_~sgW?zPt5XGflsrQ&z@ojK;1 zqnmTh)kVaKpgdZ-HH4mtAQxyP^8}cor#8!Tf)z?H1L~FD0UC25mtLjD2vaneg5D`} z2xuvW2*|7K$!m)Ntpb|b|6w!%o5HTsoWcrd26PQbOQIZap{V(1KmVl~`E&oXKTAw1 z=N^Xf<HwI#QUtaWZS1hOZ*R74Pft&|1?9VE{3Bkj<V+byWb9FfnQxn%+Ocn1UZ`Sd zsWXn;uv~zW!gls{DGnvk(6|jS)(Z$pa1GEO@5gnCt|-%DqwJQT%N2|Vh_`QUUcZgo zkQocTfOOSD=|@l)VHp+dbwR1YhzdBuI;X7CS9}Am3j0o|nKp{f2+jh5c_EMm7@~|g zhTQ|D_O>I8VC#`p#<=jXP9blTmaz<>YfP{U3e`0)SvbUiz!0;j>4?UFUIDLOsP2f_ z=MdUjpAm~Kl9tpU)}Yc>xE!SILZiL&Qqvo(%G=Mehfua)93f6WB<T@ogHZbZxIh`K z(%a5bHq9sD^rUs~X+wpyXwtkzOWS6k2GsPeE@D^xl-duy`xN7BPQ_VuTq<ByXuGC> z8bYRQK&bt>ii&Jk2xT<%qoFakaqSg)Izp|R`V!{;N>PA)^BnHEEy6G<^wmOz9l`lR zTca#*hFrQoF8Ss!!HWN;vW6<rh}(H}JC5bPh!cPNr}^|kUr!M}`9s25#`l6FLUa%J z@_U50TgS)8A3b>Z;K2i)^tShQzxeX;i}UybG#58&s1pRiI6yH4N?VM9QNnsEIRw<E z0N9iZ=pq@Q9eswlBJJ;N<NU|}=pW@WOBdynCr_w^_!@Y&GRo;}((SFKFC3Fv&d$!T z_hEx)S06%{@;BdngC%zdhH&QrgBD8!jadgGqrr?gkH7wkF81-A^W|THg^WEzgyk{D zf57!0|K@L^e}A@r_=8_@!W6-TX-({fjI7qm#86sUxaBG^CBVfNrTQ8|a01mWfoQZ- zh(kt3Y3*8-m7vF+l|sWP=@>OHqtyZntpHe>w?JbwMhVr9aZcR4nt|(JSoC0OhG?h3 z!(th2@G^*IW`{mn->SFU>%n@A1}d3?LZQ6|)3zUt1jBJ8?8vfO4FDN4ibr7m83pv3 z*<ws<SISobP-+9zub?q#K%zQ2>?O;yn^pl`(h28=j<%Z7Qmx9uF8d^pLmUXtc8tm5 zzAYC8T0>a|E-LAwF9SfMvi2wFBJ5{!xwp}i4h@m12S+qSW0clV2JhQ~t{_(;;t<eT zxPSy9e(h&q$YL1Pi#8**Lkylr$_RiN2E-J){eqCxIGXkGRni)&S_~?b8ZcT#pzA0t zN-3q-9Z_Z@{K60`4Ajg;8R6y2m)1YUlFVW{K<1(!!*gh$rO;hfkNTL^a2#zF1er2^ z{)^9BKlxYxC;wxPGH|5me)Q2ttRzPS4ab`Ib5?Kv@ZhVjzS=uDK;}wL%Y2!s>0*6{ zYoIYXvEv`;#xL(^HTUH436ODQ-QM0@A08j=W<YKhxDX#-3IMtoyGbxWgUiug`;MP2 zacJ$vob$xN5<QN*0CNN81(?-Fj~NC!QnvE6orPu5i^yuI3VTyeSrcj&;x}oTO83qR z-wD3GJCy^AL<$cgqfClQXwhJ!ecuYkwhG|-sKgRnpQ<0q7|bhlF&1nT@I_CzY(%}S zV8g*>|FDxO8()HZe4!7eJs{gHWuKy_&g+qV2_x7a4E3XyK}mLN)RxVy2Iy)GwVqI; zu&Pd6nzW430NFT1psn@k(S^}!RnltjVuA*+N{=v$^=qJuzV&=hs~M4L?P{r4hHocw zwF-c}20hwnFrwB|gH>jQ(Ke@!`xHa<?S^1X*?_<WvuT%MBGdS^HBALH4y`0#Aj_;A z3-t>FuKsiM`%R52kF}an>*y37P0UpW6|h*+<O_WKce!<6O}QNhYj_;XT>*Fjj&?GI z+4{q0XZvP*Yu8ubjKS`wJwAv(EOh-gz6O2o<n&>3bb9jDH(z`I0`F^Prydd&)<bJv zG{nIM4cA6cE{qe|^L)|QP-qmuQH+s^zzZ;A|H>cvBYxwTQQpjXxx<FzYY+sFHCHfr z`64U@gW}}m1Y@qQJWw&OSFc{7WHWoGCKm?8ClR9z;qJ2m7YYrKN%Yl|Z)k}#dI1KM z6u>Bni1x`RpFDc>=>Pa1{YR1hz1clEj-OMfL^|ZC1A~B)#8iNu>M^5>5<v_h%wLUO z7LCk8)Io9-h-r6<i^3WKLA1nOFIvsi0A?1c(o(_fq6;`LTA*veXaE_@m{p<;Fs}+8 zA#w^DAS0-RG>^@vU?L50abAGNA!H_qUUy)qzy=Lw4k_rR0WvnYJ74q~00J2!+3<pm zy=@7a*_B>1Z6(9EsnG%{$^a$nPf38R(ov0}KODfQ^fE-6g!r^L(xR_p#L^kcj65@O zMghmmMCsie!Bqmw17#w(R))g9*GwTbLtrIDrbS<gG%L^;4Mvtg7p0*zHYPTdM?ENU ztbM|$AVbCou!k}rAYIQ3M-9agU2UKuAf!7V41D(E+DBFRV$UaJ=AjLc0xz&UPdD_g zp$CO2a9rdl|IM}~VMYQC=xVPc0WHins|zAiqF&I`mHvG1A#Af=hKnp-)IbofA#};k z{vnP5M-YnEN@y{bzP28WZAZc?h)+wj3TQ_4VuZi`8-K&D{Ad5^Z+`aKXFvY&kAL)| zAJMX;xDbR3?>FCk^W@1Biab6#VsTH;&bWVg6gV7SIXPdL`|0T^H=g_V@6(>a=_$Dn zjt+Tq=5v7MLHxcf+MT`peN}t$i?uL7Ntc^{T(9#GlbV+J1V=`VVGb^S*K`>8tG9CJ zSduL>Qg0|1nN>!^4UnUWGS@P|nC`GA+b*R=@9Iq<?BErsTxATahAP4crqC>wVMxJ% zYcj5f`h^HR43UDW02z&D=GCBYlf{Y+>&8W6zcj>P_hs9nAt);V@jXQSp+WBf1qJnh z4WkHs3t4y^Zca(hS%v_m2BH}tV*@1s`X<exBPsfp6m57JMtdQX2h2tN2&U1bq*><# zn`%O{Sf-6lFivk^VO6K@g~}QQ^=K5NhFA(UQhJ3c)5yZHqm3h%M;5a}eHe9z8;ubv z&Pc!vL6Fr?DYJ64`=PMTS^A9c%**KzOEZAIAUBI;9BrM%nW~(Qu7V6rN^}HkDCI)% zt!{#cK&tByl)eP_RSqsd<8`w2GY%m1%4J7-OL3<5ORP}Ot}~%3Or%Ndnq`K;!f*c; zJok_yemNxfFW#!tpGCNQ^9Bv~KiUY&vT&!{-QyVuqgZSVDT5H%<syg}p@wgbAOmSj z=w*!iwhW*QYQ=c}<;MQ#;X_|jDbFXgdU)n3f@dMlWwQHtaDH)4jHq#o!nS!5<RM^h ze`o7<`|Z``&GqfpHka<}%Qw8}wx8)UIN9kEjdx&LpFq$sWSttX`VnX~l!5Q_=g%pO zVjetr@S%PQR(uE8)u9MLASJL06l6`Lr)3BwD}}v8fLvCwI|8$Qs18i8M9yW8j2s49 z475aMrCcmPsQ}p9q7=Je1iA>ck*`B#joOle2u#yfOZ2Qb2HJ>291r!N21i=fP#Hay zAiH|#H3kjL1q@Zqw00RqCS5oT&}DP9PIhq-yHJ7<N&%Z{fjH^cR;fUvi?z{ZW!xB^ z9_Q!h%-z$HQH~d**p!#^B^2FROa!>tqQr$Z3hF>Z<km@arzI~#9v$@Lb%^W)v}U^K zU1xo#_%$%V%W3MuiP~#uk<pAop#c)HI1~dIurlDNX61q<D5x2MB}2xfYcWyZ@NTIR zB2Z^34r$y}nF}*59YvWTn~+wF@<HJLp<_{Lxtx{UwXk?U=?h@}XZ0)yT{Y?6zzmH; z1sb=IK`^6i*MT@pjdiXq=P0r^6o95;a$MN1T(yuH)shHC!%RyP0S0IsqAkH(%6&^E zw04c4C2>&N)+jBh)tE>a;%=e7$03E%{POe1;WO~R```Y%ys=`&jDG&}pYsOGd|ey_ zzXQxU`Sp{hC|MjfHgVYYRKj9%dt-5k;{ig(CT@87PkGU^fRu_aqYR;Rg2;f33rfFZ zP(_x|Pg96PyOWngY9IosJxniNyzu&u-mv7wHeRp~j(B8H&zi@i@^G_mgd`ygPheVP z;`4SM2{M;h5+JMZTLL;G46I5$^&nT5QSt(1xY<x*4;UES!f5HD)E5|<!o<sluJLJ^ zyYVea8(^(4)3|Rj!v%rI1=^A+3}Fh78LwYou$E-Y-|)#HzP`MCeRg(_%PI?iJ|1v( zSdF-xvYvSL85P)I>?l`>O_i4Mi#i$gFi{wLjJeQt(Q1y2QXYC*hLr7A3e0SK&=7}Q zTB;-(ayibTZ{LDmpi<Nrv-Aj59zGMOWOUrEt?Z3s3q)2Ju`0gV`ydr6OAAzrLsKfg z_O^h&d3HDiy|FEaN!j_@LY}ZQuo?=Qm5hBwPzj{&w>>rpuB}x~Td1&T@DfjlDOE5s z_605)YzS4+;%Hj}@lAnjOf13mNyE0g0F9MoMN2~2K<QzWx7t-u3~fXij1^etS^d^_ ziw}LBex;bBsj^kGy?wAhUk_%qQ&!bOs2HB0{S@}01&oMTiIKtXs&$*sI;;=$#zC%6 z{5NhogR+~~UOoqMF$9AA%BP>OXk3=LNP3;bj5_=MAg<Wk>zlpdPXrN@Ahezc#8F^W zUtIcm#ry~8;s^*vM&8@mx_5SR@8pCVJsRrq@q;=ICCDV=%1lcEc~9YipA%}En=|d< zAysi!vKv{YNbdKQsBnMpko$s97vFsI4eh6&e){7d|M+)*_jkz%SOX~l;p?YQD1ft- zk}QLkuJ=2Np^E{+!-o$)`skzo)8G7?#(7V6AKbqe>(p&K7HFga3Sw4Fj#`^)Sb9Jh z*%viL>tRsoA++ld)I3XrfSITl9ijCHv!)&NB@|_&Fm(ZB^q%Cj$lx@!L_m+FHCtz{ zL>#s(yqyNxkH{q9OG~#Rt4E-_2JMSXJM(2W!9YQSGV?j3AVLYc7@5OFOP3)hg+R-` z1T=K9jJk(IrXvDoQ;dcUsIjDKd(aSv6)rMEK%A<UE<?H)87dlrw1H(TRZBqT2m-;G zd!;ZP8ip{dfC_-4T`IwbE;1UtDsm|SS^bm<Hw3p!OV=6@?5YWe!9{`Ap<byVeOH0Q zQVTd@s9*cmW_7KG4A!DCDU~qNSJ#Ov)4IG<dKai}8y*%1y}P31G9xmeQP3Xr)kaN0 zgo-?Bi;<GZ$knajDhu_rUiSoFmKQ8<>ZKA|KQ+Ix{2k!m`oI5YhT?vM!2N@Op54Z0 z4{pa_724U`-#t1y=56KR;E<!u-TC<VFn)v8Rs7XKYUEJh>I^R5yt&!BWkvY##>w08 z&Fu|QI9hzJuCK0d^7lA1Dazv(7>4ast%CwjpFZWrS@jUvi5%?h^UlocDoTtwWf($s zjs(VjaESv$8;OR!?I??Rz>`-JCvE#nOJ17Vbr=^~Z6I>bQI6Q?NHn^nYZeK5S}Non z&)c*1v_yc&F=WBaA#0mOo6H>OYkVO~)rP>VbJZIqGfHbN0+x(GcM41B;lK<?YA9R~ z02^kOdX6)R+NoNtLQXnnja;?S;_d;`m<_-)7EfA?#*xdRf-W}dGjQ7{gjE0qg9Acu zSwpmI(5!DqM4&{uZ-GgL(Hxpt60@L^HTG-jG|rS&dSFOee=XLAfIZ~_i%jcEuEOAb z>jaB1>JH5m^;-6=AeSSuT{SMLU57Lqp-UOlWnS+8HDuJtLaU?t&0*;jdS9}mw^YKq zt0PkurVWf-92&K~4TMobe24mWLq>U<Gzt<|=lRHJpvn-!l%+y-XTf)5fTr3htMtIo z6hl`EGzyfeFk)47?fV(o<{uXduhA?jKF53UxxPL*KHA^e<!Zjqp1iqzb9u?t@bdNR z_+1-e!QHie=;q%Jjz6tzG<GtVcc#EbqDw}$6GBe3ohhSvIRqsmU}l%n4-fW_^9SE> zB&=__g!Sv=m?49ay}Z+9#B)m7O9x#d0B^tP615#4pK`T-{`@(Sap4|;@;rZKCIXlR ztcq7~T4!oH3~&Tf+men7&(6;Nm;c(omfr8n?*04s2<kK-Rwtndx)ulI&Kbs6Bh&~6 zQu7&+E7f9ZgE2}%A@}K|%xD#`uQ)=tzy*yqw%QP<WXL2zZ#ne>x<EQ$%E~ICx3^%> zOBaqbSxQ42K@+^hu4Z}xdNqJdYFgZ-WCVzrbn6L};ZR{HU9_wg*oY2|FcjMk8y`(b zM3<*n^vD|USf&k6HndqzU<9T!tw$KDyirG@W3Q2^QVmd8E?evh3v<*%hLGk#nlDyz zgb_5OB@WSmAvMVH?3q8S2^nlbIV#|e4K8*G;&DU|Wv0gN2uGp1ww7vDDv@Cn7Sv<h z`ja9{(+TaDSEanLrzMnfVVCd@(W=iWwl9dx>iaGRaqxy2(e{|aw(Ow|XJqxDY^w_f z1_uu%IFw;p<#ZuqEbw?aS}pVu`j!+3%AgsPvL6EVBr2tKqR~<VP)@5Q<>&?Yzxb`c zOE@fewdHhW`^Im3e)*EORu-3&#J@N6>eVaWL9X6j(O#TiU~=*5{Nm!}$uT#)o4p-2 zdHg+I<ZW*2<cXK&_!2DpnKj`wN8o*Iv`<)G^eAtxnHo1%X3@1<J1<|pVo8+w@TMHX z&ep*$SC3e2Fb<2r1;^kN>`<;))WW4G{01;X&wr~+OAyJDqH=445|{#)Xx}RPRs&iC z4ndkD1_hcL!m?iqlxU)|oPt$pug#RYe&UW$6IV74D}%<CB|@W8L5RR8LIqJ)m~wFu zKN=9FZ^b=`<sAb0G!s4kkHCkdbW=ZuvT2zG7{M+ww-|)9in6(bc+)|N;HbBl5!kpO zQ0tbZwv!0T5@o;UX|)o~`gR1$5h_U`t5Rs0E7n$Cdq?%^+f^86$|^lDB(1*|%&4kb zm6Wu;HZA*BLF`tLSs2o?Z^1J31>{(@;eLSuO7~USD~vD*mOz)C!^sH5(O^U*8>S4V zfGTW5M)uXEPGurfgH;jV`bW7Cdb!#uY1nA04q`TGV`k$(T(g%0YUx5D$3e<Ds^7}j zo|x5u-8Q-zYm8S7Mf#x_QByS(C}}aUJEFNwz<v~GV7?wUo~c<V;plVIJ%9D`>gJjo z$>H%4HxJ?x)OPf7N;kLd1sL4PjCg+}rX?ZMny%`kRUc7u9T-xm(fDe0yaUIN>QHc0 zIDDgvcS~9|v|*g55?w=8G-Ys(VvzLOf1Ur@8Fz1gUiPtP6wrWGfj<JxD0f&~&|pK? z@)**R?&;|%MSifq1N`8@{k|pzp-a}1?J^m<qiH}d_pl-iQMWEcKm$fbSzv4sM*&#@ zjiVYUE4a9zB?3c4OWUyNyI^qbs|8a)=|wMxpt|e{!)jI)x;|+eAY<kcEl{ebt$IqM zO({hsg3-tV2>npCy#W1C>4{G$gY+=ua~_uLJiDAHJicIz3yzo}Yd{ylYH1Y!ON9}& z&Q*`-*g6AfJn;(L#Y%KBm-;G6(1Vt<;8JFQOf)8FUb@J6{b`TF=rQX9VviXb9bF|g zj2fi6+Plu`N0`@9EDMw)eZ=a5DAQ`my!z3i%!=&BG1XDfmr!0M(6Vi51&t*Em${~$ z=&OrB<UCySUntR_w?~=fERJmH9Z~?z09ngkPLsgMpdQq_=cSZADr<<~;oNl<RDxZI zn)2VWGG+48Hj4=u+ZO5pdGrGO5C7}`iZj&6{^8%JPoKVc@q)D_3wm}GlRAoDop``5 zMj1aZ4Ebw6j*jC;1luy?p5jgC>iTN`;E1fQ5AJ|K&5+J9O$FhGsW8&>dg(i-XOIEo zTg#CuEQy?AoatO-qP#)x4#~pej{v(Htbu4pNAW{e7!wxMYe19V<z8sC0W}eFxit~d zOp2hs1Rd#0E=j<~1_WwWZ-kiq0A23=OmGUm+T&;!90KHgRa~Gkn5f#`v6peNJL1)= zmpD>e?~6uzeW8Y!9F|iUjUVY7e#Z%5oRtR1#6;;Lm@eWb$SBp*X1vf~&r-YQ40&7( zQs{-!qXX)-T!o?fb_B|z*O&q<ZxthB<SI#_Z)d@!Nz1I#L!?Yve=VGktg6P$1z2;A z1=VU$we<m&N38<Xq@a|uI9e^3S6`L6a&a_iwL$L?ptL)Jp;3f1Z_hAOn7H<lc-T&` zD*on}w{^N@0au=G8|$coTYm-GNX5wvGcn(fMSODgLauILH#ZR%&oI!XZ_9T*n60PT zO|XmtjV&eR_!4C^<(+z_<BXIUQ64$c)vQ`zZ(R;Q_RKxV8zPn(GllR>-&|Lo%Xit2 z+_da*vjZ%-#_Hnikaa8=Qs{?}?K+Cg+wbko^<jQtmu_Bn+n+C@MW$3zXpe>#Wrhh< zmOPvE<~m*#d0Az$MB}jp7k_@fStR)Cev!W`3L9pMqobxqPh{`Ev;=|w)t~?K+Po*b z_s&j<Zl<aRP}()OSb>6Qsj-eDi~tyCyf}EkB#i*N3ody$;zmeUV?b{l$=E?H7RGHX zQ7KK85E+e$`WC%{U}<Z4MHS3m!2mCgE+C_)7)vcwj`S6ZmZat_4KkXrn9Dx36!o^f zFdFLh1c5r5>Zy}z=_0r$blH^1v^vsiz#|SyVruLh86u{6r<9%`)q;AuJ!pv8I!W3F zq-d%HcaKFMUzAtXV|)Y*w6W`Sz##<V(^aFf>qbjAPK@r^0u3^&M~hq<*T=|HSkf}n zl9n!LP(vz>qYTKn+cs4ao&%$962>)Uz}-0M9Vn-9K=>wgHc(3hO_iXhwQ`1x4{kPX z3N#EU&>9U5Z7qnJR_<_^3Vp#L1X^uq88t5;>tY-YR$<=0#U4S~u7VkBC=w*ppW{JO ztzBnv2#`lF!2hqm|6h`eW5<km0cM?f8==dI3CxJskT-8Gk9hHBvN+uE=6j30%L;K9 zC;jyeJNxG98i7^drRVkK<^JJue8X<|v%s`Md|I4PBJ;}X`_JBP`_b7EevLU-dT|JV z8aPBw)Tt4c8$7enCJx4M%0#7DMfvKv8ON2M2@;n0yy0fFeq+Q1LDHqcotR0HsBeLx zW}RiwS_4zl05E30fRMpr1sp1S;-f?sqhas5O~Iy*Q@%A3$W*Zuw9Rc9^!RE}L6n=t z1j=E#Sk+vp2#?GMJqO2+`pg^`v{@*Ubb#O?Mz)x6%Y#b`YH(2i^@3Lo(ars`I5&G3 zwFM0F=(qQZ(yzi|`gR0LY5hcv^*H4zq{e_fDaa~obkweb6ir%Yl^&wFr1jTAZM4%$ zdiT<oQlW2Gv1W8OhzsSRM?f#gaaIp^2Zu_Yg&{YCX2fKlx3LMM<4AVFy{R^1wjPzV zB~X$V<Y`HoLF=!jnRdpOU9!R^7-#CD-mh=>qw1N6AT!D`3aj4imcgt^-wjz*psW%o zsY#uUH0?6ZXciZtZ-d)K9BfL!K$~=J%Y|_7^pujkaj*^8*j(|rm1u@bEaGq$_|J-Q zM#dduTo~oLO1I3)7Zk#GxOe1WC@r8L-QC$f*x!qPU6X&K$lC;FWa0jWtTC3fq*G%Y zG*B@aLZIuZrxKU_{rFYS=s^uazyDG8TwKNrFfM+r9040zQ?ml-iEj|(KmQm0f^puH z-Lup9E!E~D6GbSL%uvluOIwHliT16tjFy0GOf9{%Rj3RQAY&sLpamZ#EdjkkjnZO| zV5{H|^ar3?AYBGnnq3LKtiXcc!X^fNnUP8jK;vAz_&$Dy2^=+%8Y^@z$OP#}#jYDd zn}V*s*c5gdD!E#qY=sQAh^CS(7+5ndKzwIs0dx^KpV^D$j-VybHPi^BLF+Hm#s<(3 z$^{gIgQL38k~$B?;zuZRFhGO7wN23gFc7;uxO+fNipDu2;DTAk4qt5;s;aa^K*Nwq zK^E6`ic`Q*G<K-Ub4Vrjv?|L|)QAP^j$kV}gn?BrU0X#n8M^$p?YB-DlzX*8WV&jw z(F|B*T89dUN&xH~Vp6&jkTs;OQT3pU_O+h0{ZK6+ppTgk8@OqQxhRxgp}G$BT?OO! z`YP2#o=2HBaG!`SJ#8R|MlZmB@4xte&=P?&k+(H$+*&LwO73T`UY+yG_WI%?U*Fzd zT%7YdX5pOWRLVle`|lMmEi4PlTg>(j4lm#MJE#Je8Xr#i@XSgWr7N5&*Z|5BfCBQJ zF~E#_Eu_s=-sj^IN<a?~F>PHLf|!f4D2@N3#N9X<zP&eQ3GMAv$e>b#!mzXoB|8Kv z3pCUK)fJ1h6=Wc_GA(9RA;(vP5$ZLj&AA44Bhvs~HM1>_ZXvpcEqNBMZ)8z6sV;;< zP<GTVb7yGEasDeZ-D%Na$*lcOBN!(aFIEp5GzCM(aTb}d?RJNHJ*d|p)3&^Hu>{Rl zf!U}Xfl|ynO}!=s22PoJ)btS)sx{h_yXt`<Y5lc$6aafyj|&B$Zx(YHyl;u%T<G?o zS%U`ED!?d|vgO$=M%}_C#RarM<1{rGQ5o%m8Zz3w6BP$R*?N@K$Icjj309#^k9v!N z(ug*qP2aAeH^8^rReBC@>KZ78DbT8P4;X=GCH2+z-6@r~%+^!(BRJem%9v%=ANr{< zg-z3>ISgCDL%3~at3gmEZ*^-o!rspIdBTb2D_nox;e`MQ5Yc(Q8fL8}dTwWgLWyh^ zS{YT?4@LUyI*Pory>;*2*~#%SS7|ifC?juoe;4E^D6iWbdRk=kB~x>CO_Aoe_wPS= z_3G90=g;Yo#n%LGj@kf1S_U!nHonx35=&ozwLu`VN(8zr1>L{!7ylxo@6Yb(N&Gnw ztFLOzt?Z};sV~&@E>r4+>CMon7d2s>_Sj&o($tPBNZJO<Dy6bOFN@v2RUj{rZZuhi z9$l!AYuRXt6ht#n@6i=C*w~g*ftWzoT$!^$H$2mFs!{0C%%Q#oH!fYk#-u1cB@pN$ zxGV_Ni5Yqx=G4<=1<-3rG-rei=AD9LZzDudN!z1Y>m+I*%3Zz+&?S_0(zRtYXR!2z zi5^Ei3grSkAkv~|lv7SKG@3~owv(Tgarz{3V>pBvF6rH}xQ2`(Ptl8v6%BA<NZGs^ z)Aev*EDqV)g)Fu~a7S&?(54WJ>FjaLdSlj2)iT-!j1I~c#I`e@*H=bBLoPHU7_#`* zAC?-Wi@*xACg`;UO9kyqz%1tyv!;u$anK{9(F>3nYMr6ZY8{%k4k_DJAV>bE>CHsb zgl;GTQU7r4X2}cz^5_Nlzx?h0C-(-+c=F`Q`FXtY^47`c<;z!3p2Uws$6bwMx4nIJ zearjk+p8Po>zgg)i`Q>x@p$>_)tk5R?}cAqzI}Oq&Wq#uMf@8cmO9^}U-2$UmS@kN z`vObM{MK)LLzTtk?KY#u`z~#LUQopOIiK^eeN7v}dHntlUa(1#dEZjc?%w{+?%vJq zHI-6E9-e#@*x{t!zPdplE0^EdZI27o;kz*Zx730)jny7Nwp;sT1n#u1u$H=bGghgA z`z=!h4mnDzQjI~-!>YX4C>Rz&M}28ywgYI~$(W5=hPY@TV2`GkXE{5)&l&&r4d)SO z1gFm)VIso~mF(`s?>ODQ$ulf|!P(C4_07_QyO<P#TtFA7(=ODE1dYb%l~Kll9M0wN zN$A#;h0)$1S1X8fJJ(iwhP0f;(Y_slQmQ0dmDQa>CA3lKfO>^#OT=g=m}SZ;J!EM? z>#v0+QqaXUL|{LcUZF>2-`4u50ppZ%3ZtVI%3gOsqcTfdoDu5PtN|NZ;<z!WQ~eav zNmC8S@mpXJqe02klN+-wdkG_E^Wtl$!kEzd%Q*L0YN*_8tDdobMI`DZ6qF+x*vsz# z8$|4;$qXD$hC}LF?AJ`73Cm1VP*^|NQM(H7zf;<9hrz3yW|z<<d+Q`<a<y(R<Ll1t z9gl6vWs|qK<NVXRbTy-eSj||>SPG(n#t7V`7(^&zQbhDtQftkd`C}9pg&O7hesp+n zbQs?QW|VWEo97TV-P+Gm#i!VdzmOMCq{Q*Ih>TN)rBtru#)uRL2l1zXDHxd)*26@| z6&6Xl2guyUy`}oLjEgpO^E{4+XS&33-9Fe0aQz)%S`t)2b`=0q^d3L;qCIFc#T#U^ z&Iy3V)rvAx)e@PiEDY30gcxY5$rO+orK?%7O5+z8pp?cz5ak;61^|^>eSM*V?#M*} z7zNE}Yltp#dC^XBb7X)3+5Lf61?f?bFlwO+uuE`S|D+0D3^5lVxGw19F*ElxN;GvB zG>)NkudpNB52CLXYEPUVH2nz!7|Uq=jRwdHU|7M$m?NmCpP))`rerTi474dw5*hc3 zj{$-;qX+6_lq_xxMhVNMkRgMNupS^9UF?Zq5M)4EmCz*`Lj`)vpp~?3#<WCM(~~im zj-xdIskIs5)excT0pri=txZ|MM07`JLmUM)F_Wx~wWTEHVqs{oWYG{X(B7FA3}L{i z`ivCE*HMB9%8}rxt;%W3D1x$G1!|3Uu(1V81<JNnV7TlH?A1hq1bOrV{Qv&1|ErVy zlU>Z{^Upv3=9?$ao;`b+JWY7tWWm09@|1VuCr_U~{_?A@zW(~@v*-Nh^DiE=$6vg7 z_4Mhpr%#{rYWn8Qm9Nduo<D#2D*i<=?gZi0I^$eFe*72#h|jAvE%If4cNanX5@>O8 z!vkh$Xc@RX=gm3(N|W#BEDKjQmVyJzq+Ba}X*sa053kEizb)5x>@o4nG#C&;ylT0T zwFzl}T!aNTk|2|mQA3e5mo}E&GBD7-wic7p#x8o{hOHMeEpnC|*XJ}G<31!QmPRv| zam2zvp=p<)HY>;1fXb`#o}JxeDL5S1U<^(Zd&(dn0vfPOX))Vn(7T>3XwDiX(a_V? z#+J%CIvNOix+Ya)CFl(W%Cw-3xEey2QL9y6g`<5t0;SZXdObpEMo<PV1=pHmk5XA1 zSja2tG|QA#dWg!B)?bV3*4xJ_Cw5^PN=@IgJ~1$4H>UGdKZ4O-sIChor4eHy5R-JY z$kead2rV_Eiy0RIE-CCo4Mt?b1^B8bsltZfh&zID6sp@74`$JzM`LLHWY$<Su&Yhq zuA-ueGA&ij>aX*~MtKCG1exXXyvDG1uU4}u>M<xwg_W$Gon%pi*$~ahV0RU(j(Y`E zSajoS$YV6<Wsf`XSa+}=zi^R6Tq3-EV8*>WSFgch#(M7W<=3La9W!?_GG5q}9+_4w z%r+w}hCGiDYLq+Z_SR1P6m<RrC8D`S8KRheDI!o-g|Bsb;^!T<ebtO1l*qJ|;_7Yu zn=JpPk&gt-^wUp2<>4gaCKwlQu9jYa5u76tkcIfP)J&*<{onXE4Dz0A|H@~dkRFLi zI&<m((jYrzde@QG^@2JKKv#LxG64e`3h)9)0fCqWW`xqdN&;MvG1h<<Ss0~@LA7W+ zX3E&m1q6L{Dd<usPi8;_jnN}>FenBuvb#Af&uH49F$D&6*&GNAv0v%p!cgsaTF?=} zNg>ddK+B^E2D*z~9JNFM^yC8LmwQp&kzmbg3}tXY!;qsTSb$4`O;!}3DYF6%X6pMO zw8o#(=PhbTRGODFih5Y;<NSy9JW11X^3dX9D;U$_h%rHY=HrN<r%0Agvk}<a0>;_{ zH&omK8DI3oB#s)*aLjrG<4nO<14<RU*hiWKSp!=^PnH^D;)G&qzz~tuQ&JV<A;Se6 zqScF0W&}q^?QfuK$tVzkGs2jFU=W1;{rD53LKjP69m?KlfQIvnEbdaPB@RQ_)0*1g z1fguN^?<!(q@eYe!Hc#GN>D$A^I98IgWZawS<zS0Gqsd?ZMU!NF7gf+x=}!npa&fo z{r#W*+#&hv|NDQBJHju2`O8l}`Q&$g=XZYp_kYGAdwtRVovJn*()hdkcVTC*U15N3 z9EpU(O{)!5{oLQ1YMHt&jW|0x=G7R1^Y_7n2WMwzyL)kk+23!!bCOr<*RRhF9-Ab- zM;>PcHpC1~n^HfqwuVr1A3+cTA{berTBp{xBx2b;3hs9FKzv$D0!EFnir!|Fu}~?T zeN9?6<KQZonjxt=v8PDN%l#4?rdceLUuRe>SC8>qr<HWQz0)orFen3UrZm%WocIE< z0#GC<Gv8*HmZf(_b{V2u(@gI;$|iEw4waHFAh140c1R@{0e$a<FxBIN;08cY*~?m% zi)}Gd5>8<Xp{l&{^7>H9!g;Mhm#I90c{OQ*UY10cq_o;wLxG0p#@0#7ojPefb_fiy z!nCfcmVJvQW(Xw07p3m2&I_&ySYqG<TRjh;!A!KY04|TEL8yR?DwM{ykJCdIgA^!f z-9MoFNDyRQq-iJma_RL||FkV*K_e)sstN=3t+NdG4@XDzk$Y-?+9gX?5l2nU2%aNp zjfRZ}1w6k*12KxqzFmVgV8*fYu%a=3r9+8jBv^5S#5YDKY;7;DJR>38mX9(V?(KUk zB(;ZtyB@dfhYugJU3n<=Es@JR72>tM*M1Kx8=h;X1=C{L01!d%zMm1qAsTFNEj|B4 zHC;W`%Ffo!M-Lx;|FcgXJ$gi_7cX9r+PkW!54(#vq;u);wQS5N02}VtbUDkoePi#c zVoYm!@mJ*Yl1^BZ_2zFJ?EwS3kH7v38=`s6niPY3_wG>%p-8HpC&~Nw@BhcY`I{KL zKkXr&Or)U{h$YOMDA*0V0o`VCJ|mbjjG_tl1awwl4Z^4zK*rI-gW!<cg2kd+_JmUJ zjse}Zsi~;}Mm2+857lMefq=D2;&d=D2rcO1=ybmCL}OcL0n7-<E`-H^jOs~hx(pD| zh1MA!+Nu)ktb)ZZEohUjjfz%+2I0B<U1AK##gPIn3w<lX=1}=)8O>r|R{&+!5(QK@ zZ5O2)0inq8m0(|3gS6oe3}{&aS5Gq?Ax&oRpa3$(;G2gxf>e1eL>7=vi+L4XiB3*V zc<f*)@WnWe_iz;YvrjO<tc-z}bo)vGnIY^m$qa-oUqB!N$~N3#&0JEAW>~t=?-R`+ zYP$PAfst1QoTZjUFN~cy8YYq@1R6u@zc(#h(svz&*6%<`Nzzmu-aFX_Po6yCdT4~@ zI6K@PZ+Hj3%jf#4ZKM$vL)!~$XeCUzc*C8(mC8<F3LFuR0@rvCjlt`<==J`rDQOnB z_mnm~A?7@XL)yF#Ui7$7urdT>p*V?Hz&1SK=FiOYU@%J?UQO)6&5nBsz1(XQq>o9r zRkM5wmqwdjfHE#&4ZUNeTn6RzQtY0r;3bG&9~NWUnq4-})fYJ`_*+0;Q}+cB7Fesi zeYG#Rl#&)rt2=KH;EhQQ#(lIAqeQg0pfq?N-?I`d1EJ0o&G6Ndm4pmA!!+Z1DmdUP z&g)JPWEG4Wld@|8bs4p5u&~zI0GH9(Rq!<tJTB79ZFqt)H;MeA=<8AF+iyV?FMXVn z%Z8&y%X+dWX;~s}+|Qps|K%@#iSehOe)`#GpK<%<5M#i5DK@S@URCFseY=Xj5~2<4 z@$UNa<x9VuiVXr4a>{57D8XGPbg7LZc_G3J4f_xS>O@0}Oc2bFF@RAhFqE=-z(zf& zM}s?sQW$W9BeJ6z@`KTi2g%4<xzR*{Lsu-Qlrg^q8I6MaYQc+LKQSm9Rtl^E4F;Mq zgr-;8t+1fRnCNve8X#zZ-UvV$`hxb5CA1eymCYh;@Iug1FeW~esv#pFU=PG0ng+;{ z@#b+<Gr`e-#vF~(MPC`w^z#xep;jKyXMv5rYp5PaBUYk2I11G*Wv>yvs$D~x&rr)~ z7l9c8hhX{wtj#PHLCZqrl&ERgHegafW>iNF>{1Lzq?CX_cNM)2?s24tjRbvs&CsY+ zC@}WeRZO5x>anC6vVLTg46$^^$DQjJ^T;GI$Oi#UzM^nC%zSXfy=umjE(eSF1xipL zHOAzvtEZQR-V*E*T;W?_5Tk+0DP#u{IT4lE)1|7?*U&1onbL+QIMf@Y`Ha2w19Da6 zP|qvgf8SglpPfE?@ruj&)y*xRc;k%^uf99inIR%@KqsHkdvE(}<ypo%@Z@ttxSMTS z1?6Z7HTM~9oBG6;KbX_j_S>6V>gSXHG<k~~-J7c$hK5v5gg6Y=XNqBy+nxBV#RYe5 zU1aH%v};K7g^dAckE4`938`LCLt=MI8=hb>Wz*L-OP0?GKmM@1Tw?jS)PuaJNB7oQ zUC->0E<J64Oi5|7yv4m(nbt1!?xmj!n!(gpnrZ^+`ivS=p<VUWDnK8w*WVS>wN4V} z<J@)0EK?jBwF)KosGrh?JIpTHcnc8A!>ksNE=nKC>@teLsP~|Z+Lo^Gjx>PRC_VyR zm5kCYnNeE>Edc{olI|wpD6K!i_+XddVs~>|nh6Y9HW=BR;LwO!rL+)}C0&J22p-cc zBo5pfM}{m9dbthHF{(Dhzq_zIQ30osd(E1>vqLUO>vU*5a?z4I8h5enz1^+d9X{OJ z&M#j-dH(G2*Izw-@to29qr=nt_s$;NKRh|!*<Y-@5!hg~oA28Z_!`8p9@#72Uaz-~ z$ai$Qy|v5d^yJ>7haW$D@X>?&kIqi-qu<{<+}YmaetNKfguJ(Vz()=CXlT(mijvzl z?e0$d1|*P|0$3AZKe&6{8(?|hsAz1>$|&*jOTE4lH@EjD{tmFwP1&j*>aJG7YCyRR z3cJ-RI3;8jy@I1b$iopz%pz`1l@<d>b%*{t<Jy2SZI46xDys+NsA;)K>v09rsu6a> zkJjjjB@menbdkSs6&cd7fg{FMVXri1gifZK9!A|L5oOo`JhEE=txDP~svR#u*`y>Y z$kDPXU%ODU#-e6K8ynWmw+P+QxFCR1d%&zo%kq?n+kvLO*eN8E*6-d}>}njbIxl1l zsEP_Pri(yJ9EB+imC(!8f{}$A2CYkBOSd-|;p&YH@M3ErphxbZcx`ah*RK1Mj8Fpl zd-v|~s!23Mp`=BRFG}?qqoH`NDQH|Gz|zr5By`naqmb1FHL7g41nkMeSxo9)sZCk- zpq%PePHDqQQzcC`hoe<(P9he{?#R8Dd&+)8j8oAnyZzFaz!F)QG6(42|M&j`hvc_@ z>;HCga*F=)^_!<ppMLe#*K7lKf>H5}SIPXP8XI%V&6>9LvL3OLB1=;<-m#KHGi(pR znUr74;{VJK7v^%i6~FP43myh&m`+RIHgg^(YK+m0(*GcI>igo?K)@y?cB=)hZ^+gl z$e<0ym%Vy~^{le#g8<zoE!(p!ZaECVEdh=e3^i#5+x7K=3B&~B3rd>SNwkEKW#MQE z;6%_ksUGyx^G>0kY>|eG1*eA6SdU$eMN2?XQ(dv!)9ZCHk-mKkeS}i3VU>+>80`&E zvhkEhj(y%9%|@-123EQEl$YRAUJd~(Bb+bQEn^Pi@$lQig&oWJ4t0KwTEkWZ1ia7? ziq;?q450x}Ow167S<8i41_;!Ekrhgo>5u}bAK|IjkD80Tt-lr{Lw^c4Rbtt;P1Wr~ zP^flFS}mP)y&mk2;5O|F+bzdc_7zsNhn4Fv#4%vhk>Jv#<wSN=_U$Unt{kzt6)26P zYS3jn&tMbii+B6aGE)tpBtl%Khqn^-Dqp{T{qp5YcI@ft>Dk#C#=KmxrOT4jga;>9 z(oGJInoG^-dd`reCF5T3kav7^xOEf1VyZF{<mBY!```cm(NX+zEKg6$!ybbN4<67` z01y+URpp%8i+Z06Wj$ol(q+_AMKf9*UteAl&_`DE!YIYG&hSlHl<=4T%3sm(Jz4xx z89KzZZf6cAqg-sT1T5)lOidXi&{CmqExj--g!M3a$z@sWvk@9&kc+UWK^&q;-UooE zgwjid9$ZReYc!85qZC;-2riCht^k?}rKN(TUkmP(5e&W_Tp;F_H0^-FiRKo;z+w<k za=e<|^1PtGkkPFrLI5>s*f5b~yaq!?cBo>iDM7h35)&I}s`rLN?6F`j2xN4rN2vv6 zrMB|E{xw)LxHy7dU%QNM5^4m;g|mP%fG%-75QGAgiW;%(9yOR*2^c>r8*0ObTx9Gw zLm6wJP-s8|gjo!QO>V>3hj@{t4G&91i<y>v*HJ)UmI~|hZi1ntsU}dr>#t2LRvrSn zeR*Kzw6jExIrN=^%e0l!=x&@Urffzq%ERTWSFb+$=p$MuLS5|i_(o`cTG+V{(Pute zaVTdo>HBlAf3&?7Uxa4O343tRej7)BTqqk2r#K%DQGV94+4p{3jUrZgz;3ncDN6&6 z!j8zaLF;#@tkJ$ZB^>6k7;TXI?mS!9v!9*at@%$LkrA^>i44PBN}$c{*{)RJC{(wE z9s-ifbZRsMyXqtHAf!6z%|s1QNmEVC>avECXrzv-XZHg~eG9rnI1fs&dsq5U%CphR zW=h%jtwPB~#h=nF2C#HZTK~Nvl+k8e1+bF7o_-XN9p!og94{^-XgG*!G)99S(&^n` zpZo3|SC#iCXEQ^sww1F3c>)9{t6r2<PBB`6W{ok-j_P<POgAMePDW;SKNJ;k6gg8Z zG^5d;k!4@=EZU34!m(o)q4cWaaiqnCyY`n~e)-i`U-1@-hPP1OgfT|O3tt3YHGSJO z%jTF}L5*-m@Yem!H{Z~bi==*u3cXiFWcM2_=#J8|Giv+ykLYVs7Ky9@-~tMLH;U+} zx9-ZtTG7(Q-gfHs{=}a_stGfJnw#k*4rX>ssSVgguRLuDORE4Q7rPNXK`xDg(4|O^ z4J{f%x%w=9Zxc}xhMF{lEy^BrF)Tw?=nytpa@&Y>u@UU)q6F<DVrJ17fgu-@F80LH zKubVR+q?Hd9SGw9g2kY;V8d!a7k#-4GD9i>d-V!Uo2W-1V5W^w6%ZIz-y1*`h6WoV zOBsNX6?%P-dfFZ|gsP098S^DCg6E#=P(?<>E*dgsmWnZ5>}hoj(+PT&P~AQSvRzXP zdJP~w=BayFb4y3sJ`@;-BCAfjw05~_FfTQ_sP_v5beSVCN@Of`R8L#c-sbNrsK^m0 zsl39d2A*FAM?gt@jOl6#8VkoO<1KcGvKa-JvMIfx-bq<1q-#Jl^&?!g*6Cngvn4q? zrP)njdd*@PhN|r&m%gw|otjY<EBv#c|1!-N{Jp>TTlenW=Qc+Bd%yR4PoF-`D?_;W zz0h3jo9&%AS*G-p?eNCaI@kzugzB({6z9*QRU951cm-ou9v>fZ_vP#)N}i)!Y~vpW z`yF6p%*;*}=EdyL4Br8E0ke|SG~V?MZ(@}I#!*?Vc-;WI%Ge{9vF<}L??4w>6^AaZ z-5!f^H5g?bSVpLQf(=7}VD~*SEVO>oR73Go7-~|Yu|jG3E?BmNb<U2KuJfhU(oxXM zQHRQA4LaH?lw8CHONeX=mmN!U^(~Y=)DTP~i#AiV*SFV@x^M_RXgMWa7nRsbjw}i= zesyQ*jYZ9@zLZc()(1T0RoX?+Y}6Wr)-E`Ax{)A9k;PFi-5evr(na=4UMWOh&`jAO zsjfpsA7qv?Xb#I^SJ6xdW2*w9p`;y!Wk&8pZtiNJMztK_5bJ<EiUxM4Fl6=~^rY5c z1c3}FO}iRq(xhRs<)sXE#g59pT}2fP5v!X{DHYVL`H7e*8Lx#^Q(>W$BY_q(4jeL< zYe2ZXyhPw>P?^Ut<OdHP_{&XE0?&B75+nE<un1DSmzFN9`VO$itGW=@+;(@iuk+_g zx%2Y!NmBL|eEs#;&!0c%ae`djg8lXqP#ay`wL}jTLs(^^5{<6sbtViMUx)CuY+5u? zN*04LY~^pwBC<iG0%GY9E!Fb6{%`)}zifo}WcT#+g#Q>C$d~IAphpITtS1WUyHGaP z>QJ=`j1rAjrNPU<A+T!-ly=KZ1BV=?T8vrW91pAk5CF4?yIe4Oy6O$Z>TAgmF&U++ ziyBc6#zDg<f}wyeXn?@s<PwaGh9ZqXmsW6TQeqGVT0<cl4HO(L90H7+YB>~MCFfvU z3WspCtDaU(b#1};bjwBPs_)}h3w?H4?WdGiPp>JN2nO*~^zeB&5F9FW0Zvixh}2*i zv{U;6y^hG$g1(@;mf(4=jYO2yP%!pjR~O>Y5*8eyTRV*|%FNcf8fXvY;^@fIE?~)O z&@x1qHk_|<+~G1BSJK<<+xREJ@!<?0WV~AN!9;_&f3+hX$r9w6PSM7eH=$+NwE$5g zrAOJLa!QT%Ef6Y4#&|wLZ%k4*iP_QXPHT4xanf}RE7~k3Fj_6dY>7YA(8Flm1?f`N zU;pdBVORd_pZ(MK?%mtp-(&FV?e&WnFTVKVaU4zmjAKOQ%;j^t$0qXNEq}NXjx_m+ zWaO+*?2Y`e9x)cL)6GDE3!Vm}Pp;o0PJM7-zw(+IUzLe}ZpKr<9x{Vmb9uvkd;RA6 z=Gs&!(<gGVR&3UoV9sthyde)Q^{o7fZ`^4KWUC;htQN5EHv=HoXbDiGt-lOI3L5lg z$bEN&j%7nJscvM>FsSPZW)_UhKG16l4<3xqepudKw#!x4_z?SRAVbZ7J}OQ!VW3_{ zGBsOvX~YN)fkS0O>nNo8c>U8UX#LJzWeurM+lJk0rOc{Th-bJ?uK<;9L>Y|er_kGQ zii~aqvMLTZ)VDx{zFQc13Mm*xpfzKfH+#Em1BbxtA<EVt+^_Qfs3R@Vb^nN?wt^R+ z0cCuZ8C9>DT`!eBiz9nRltC{*4fRT>u0w_PQ_u@GbZZ$MeJ2`&LHd<s)K;OFs|9@f zw)90rUw#2rBWW@NmZM^%4&MkuG34~^ilbAw$kSG2EvuCrY1mQOx2v#hz^rO6jlQ<( zu~HtvP?OTWqbYj~jxcRme>bEDg8hliTP1DW`|>+j7x8BZ+g}94hE{t7UQ-cXy?TWP zJaLSyhTA4`!H}bML_o_ptUUL|-$G(Ap6*g{%iHex`Nfm?bBXb13Vr$I!<#Rki;LHM zFk_)m=5K?(<ff1>$dnd02tLZheET+jk2IZn)T98q77#|+0tP@W*m$I(^yN1!yAJV$ z#yjv|{7Zi+ru5$I-aCuGvlJ_l`A}I_EK`C;17V1+Fr*FG)wq{w31u{u$OLgd`hr8) zlY(y98$ms-L%5d<T@8e=f`MqJyDeRZ@GbQ1v#3EpS$c%pplBeyqgu_7O~-M<5(72} z2N+owTET_3*MLf3jyM`k8-~F3H<x<a@)En%DwMH~C`*<aE#sb9dthprp^fI+2UK1* zj8<#>DH=!Ij?$z_lg&cQQK0qCiiRPQj^gVAm~jX&i(2zwG0I|&?2Fkr2&O<LNF8g! zvJRSAN%#y?p2Y|y195<uQD0I@P@{3L;i5@uFG6%{lq)9d18DHl7+3_i7BZy*0vcW? zBr6Kg(-O+Alnt||H5VXLIVeL}N}dY@WPP}V9qjLO1X-v^LQB=k)ZzlTjC}-|YI+<^ zza~&pj*MZ*2`W1a@SIg2bqp}1azxcRf@w61Wf-bf2u@p?aPFWU3qYoZ|6utA`0xMy z-`4Ex?B3U3e}nMTpZ=67J2P&IIOclBcL;fTjBD;r{=tNyWws-YEp=_hS3&aAzWxy( zWG_777bOq+s6UP`8=-Hrk|j;Hv0FF-x#Wb4W!yj5J32U|+}zsNTr`o}6*+FwWI$xQ z;+v-)X(LWfwWW^oqM;LmGZ30KLS|b+>Z3NqzUACPpGi5zxb<+kiy-AlD}CfC<pKy( zGc}l1oRSNaSKUnkSe`hCa}#2ms~SqXfS~UP&)+FtMu1RILW)6k6mU^L!WzWL!cdb2 z)Res%FbjHzXw$seSL=|D5Fv8zeOEzE4MB|-Y9P~&PkGZJOxw7GcA64gqA40oF-1{I zujFdz7G*P{^a_2q<bpWU$qGZXy-TKD*xLn<7mq!?61g(s!c~a98Y?@OPJ4y&vP;{0 zMd$<>GxWSU5Sbcyso+?6Mj$ZM#}Uj_($;7(8nVSJ#wK`tH7-cH%6>$17|zzB4d<*C zP`bhjxS*W2jMDa?2luC_k*1o^Zo?U^k6HDM;GnjM%Q0P_DO|P`D!7hD5cOh5W#6vC zyadOr_5j_{@#?bA&#MRfCP6&3EEQm=QbzQ|E)QugoyQKDD>)BuyvuQD{N694?qT!~ z9z5V=LB@=8>hSOogBLGe;M>oFmM*M$0ahb8VvG+jwfJ1!T)#R$kH6;s>eZ8HPrv;7 ztHa}?xaE@~AH}%m#dm)55mNz|i_6#N7Z=yJH@o|L2w3tcK$p=sS8s9W;J&_m&2kVS zG?cd+U+>0OWxgiUxj};g!L8G>fi6n{ECPDEK;_hrfbuW>TmM#0=zZD#!S_ESU+Z;S zM48q)ut87R2<RQMP+H(PrBgd9wqV_YGUkykw2Y#}5fDs73S@@tVrE_zpL+m$js^4Q z`JN!J^N;05=yU;;f(u>s({>7*j3J@hqI7Z8mtZj?B~Tk)2(&1xJSPGO&Z|asgkC02 z8I(RNiju5~ICK#(bCj^OItpiw5uhRfLv+O<aTI|R*dS90oS&aFWp8gBFGd-nfZn$U zn<g#CN5+vlp{WKXf-R65rO>5i2y_Gu9HMm;!g->ESFc{NXDHYU4HF>(`-eIiC7@>I z>(pupIksv3ee6<VMi7>QQPvr`Fb+1vL7t*JqpYnqd69{q6maDcSa4co^w(EyiGav} zp4N%z!VoqP3zW|U#6+kAhZ#z3#Ap#T|E^sIURpW}Fa<+Rn<>I8q1&WkD}r%sfk|MM zFTL2a`7vWv<0oKgu^J{6E%sdVbsRx1N-{eoL6+05KYj7o&|(m7Ly@+?n#8OU=cPSy z=;BqONJonq2FQ+TfS!f5p3>_@9NJ9PR@Fq<qn8>2j})PRp{C6TUmY<<|BGLKks%v@ z{?GqU@87?Fe0)mS{k_BA`@P@$Z~mMA52xyzH~HK0w%TrIkC7qba7OR!?C<T7iQH@& zHXk=OW`1~dL|gKUm(NLOYW6ng4l*}p=arWP?o7j<<c(h(y&D&WxWTbddmJB>WZ({f zX3_@E6w7;OXAd7fJUu<$-P(Th_VVChZ|gR`+WqF@HM79rdTaaj<y-Eet_+prO7mZ$ z#meOR#LysbQ8I$E;0v7cw7o{T_9wd_R&IEsK0Q4nA?IKI`pGwB_9*cnz>*W+6UxKH z`WVo>eao8At^%7fR&WcX5ac>EG#j;KFUx9y15{>$40-q#=}N#Qh9{^sCPLXWal5^e z)`P3DI7(r(bSYSka9ySKpdw(PJ95n^!vtC?0D{Ij*rre#+df^5g54<$HEEfV-hfbg zyCu60c7Zaiq@PaDNME5=*<&ypA0;k=j7B|eGhLnwX0)d3Th^Ja!YGdHCA!QA4adD= zf}v=E?kEWKc}M8gI_Uy^9Asw!UVrQ|+O7h_l+lzWM7SZKsC2Zc5|y;L19L=aaFtx# z%CQ%`z}m%30S#HR8Mke8g8O+DdS&b;P?&O0X~@;1#-R~h+evNqh@KH5_^=;ztRa=Q zCD88e%-`4OHYq8CRV~Mtb_z$NNt^NZYVnJLiCl1uRJMX@Syun@h~}B)H6PC373Hit zj;rdY9s?@JZ8aYV&(6-`o}Nz&tcmwoY@R%MqH%fITE9j1c#}e~tu4CS9hNj~)8w|R z;Aw6#c)8C<#^8Ld97{B89!llBF*uYx0`>}+Av0?Hy`7d(OEh-5y|NU>p^MAO$;q$& z>aYHt|NK8E$osQ<a&pXn%tuQaD?`=-0jP-~HDHxJHL<=`D2;K1EGpBg6#$NcdRH?S zH0%+)3S)rG>foZK=nH+dn}7>#EOY1B%Ni(1jkf-P8rm{IpnlqZn#_VJpeY*#QQs>o zGD<*za<_|6E@hME4TnY$L`$G+TQCavS~(gjcRDaKE*NUka=^%u=uR9lGJ4Hm8X^6H zUMcDUdE_Xh;QT>@K<kX$=cKMyu&=H{28(FA_hk4W=F_Fd3uWu9K>OYduL@$!womfu zzbqqDQniUTfF77KS3ugD4xt#;a@jt*1dJ#HcA2umU>R$Y;|tI$j3Nk=&>#bV_Qo8$ zI7*V%UnYmz<)|;LKQ43&^t39gRj3FCDW#M~)L_ry05q&BPl3MkxV)N)^@L{<OP{oU zk{KFw%Yd#CfXD{a>^FYnZz#y${@ecvPcTPE@s%B7eD&2=UwrYHt0FIKjNaa~U%5fy zS8sVwi`Sm`T1ae(xV!M*)6-KrNAbrHjt>q(AAi%}=<x7h@9Z>wGX~-@3674!ac}R_ zPd+(4IYy5C65sdb6*{)rRbCS6nC2{^>|vJHUo9VxV_ZNE4-R<$IpSu&6F<337G9s< zUcR}0dqoU3NJQoZa#+O-9&r&^r;OQlQKSq3m$*#z<Z=euFXLA?c9<c@G{0W7Z%cgc zIK2Dv=IpH}w*V(moR6ks@v$T_D{qP(46=>QvxdQ}wZpo#jX?`^kr_qkTZOVw0A!-& z_!vi}f<UkDQJYbh3})-Gm>3=cq7m%v=3oPxSc055-8>eJs=v>hk;V};D6{G+%-Tci zPgpgy#zp$t5S(v$)zDqzuh$#44^G}{9fDd+7zG@43xfc%?i`fTR7SuON~6#ltU|}u z8R#_{2sJdRyVwHtpt0>~Av)T?>Wm78Maa4CaN4UMwXO+5Pidz1w5te*3H^{lX%wbd zwxr)ukP%$6ysY6x*9D{<9k#TMIHTZAVwHyH6KJYr+Eufv?YC$TB{gYN+9il~M2roy zu$z=HMlWdnWYsr}`}OHrRX;0F+Y;oKM#B;5e-9P{%fgZ3HpC5GN5H;XE}0o%21}xC z{ltIe=7-_<<d1Ug?(gly9etNgp#GZ6MmTSUW!m_!r2Jq>1$-h$wpTatuVuI;+C}zl z!SDK(8JY;|1USEj7i>uL01dCZJmIhc++mRsfQN+-^&Q~dljHb~7OTu!$GYSJ0J;pv zQspQuU29S)c4;ZP@7fBobwlY%QTpBh7_BA1jNNc`b;VPOUdRZ>!Hn7vz}kvY_ni<h z6E>Q5z;x9@nb`#@r=9w$alTY5D4iFwW|EN_bVn%!Wv>sn?kh|+TJ`j313J>?k}nPc zHpozB{U`zk%%u*Hnkl*$m=$(uF(Zz!za5o6LQ_p>!^uda`^d)n$>k^l6CrONkf7!W z6#=0@gNuS_jG%$gtx$HSa8}c554i>bWvI~%fsC1yvblWR#LwRB5T7FwpO!rJ4&|je zG(OOC2`vLIl2_Mnb>V{$pBAmfO6SO)RV+Y*0cI|gnvH4hMo<NG`#5EgHuE<O&;}vv zS}KDfTLr+Nl+^-y7u*Q8qb@|CuE=ts0Co-+C4VZ(H7Nr?Mjta7u#0a*9Lgxl2CxzI zMAiTp8odDjt-tj*kB^T}PU2>HeRcEr@#7~?o^n;;1dTXb@w>Q);y?7o@<GDQm3ztA z*;#(~IDQ942020So4v^Q?%jX%=%f4hA24`u5bxN$Xd|E`T`J?}vQToj+}_!Jeffq= zWFxN=p**{mIzh9TlrO-CaRta*Dm(Tz?)O)3<Gb;MVHVrFydIC9v0?*rYNQ-soc0Qf zgEd8a801h=4`+*ql@?hDLNO%Lfb8M5z4(b9?9p>QzsNsd0T?I@ghvzS(7sw=Ls6EK zbv=tLcnR!j+i;>D9GcSG^sLm|CMhn+dY3>+&9uF-`l-8`8pYB1=HTM^mL@ZdC&j1+ zecKBo!a8aF39E)y=`Cs6I+xx{{i-;H2I<;RKZ5uK1b2=alhSHa2H?;%+EgPMY;id3 zis@`Y8_Oshf=D?>4QW=CvWC<UQvr?fZK(&Pg=rvt4bleYGFFS16QP^efIYthTn6Q? zji`|-!)`CHLYon#FB^qb^w&cjfnxe@4|+zq%XkY@0G{wNMx%^JsHBZM%z#5O?W$ST zvh1`|oWkZ1jDS5J5r#%vLS@Wg4h<yD8z1Tg*w-0G0bdRu_YvUE>Qb=xxEUdE4|<)y z1S{MYWw&;3cj=dR7HPYvsx&<OqAXMbhrS%kxW`ejX39fZK@@<yC^iVp0w~*-_!%ZF z(I6O#r*LOVOBXX`1iGveW@r#t95jFRul+USyeEW;Rihe;0|dHNCD3hBhegu@F3<*6 zpnbXY8gc<$g190EtW`rs$%b$_SOq|!%VU$FXr+8xe?p|6L&qu2ZE&>aUSLQ|l8W7; z+-aLdqJC;qlpYuYGPZuAz3r$N^(tr4poqyN<p>A{v|0o=N$=}irdWeC)5NYVDe~aQ zq3q2@E`VmlNFQ^~j3tyT<U&JX4p}4-oTj6Fz<B;nINvT41m+%DCnvVu%+pe9M%Y!b zpV`J(5+N>li5V-D@ev3`Js4D%MZ?{%3iat|)le|T2-qW(yEbJ8$XU^n-t16HG@@QJ zX#+`9t-w%yTSS^}#hP{nE!hAX-TP4mHB(p$W}&4sLIY|rsDNr<q{M}TWvR+wSTtU& z00UjbP%!N_X-HJ=pbY7>fMbe1dhE&0QO>JlgBpa}BSE-Y^2W;xFfDJt_wL<8M#=jy zU0!;DAxCK$efaPp0(!P9FUDAsg@7nO`Q)=-`ITS!<daV@COh$Ip;h*6ar$5=+FXG4 zl;7)D5zhH`J&Qp`EvJ-cpT~|MSQ^ST_pqX&YY<S0CRVun9wrO|!Py(pX7}BYOO&e; zC}kQh1kjRJnl@>w32iuOs>EDV+VBKtU9^Y^qfJWsZn_3Wrp<jCFkdvREt{E(SXu?m zbD(J_WU(_#(fZ#Rm1VY7kWq!J7`ZfQ1*QOG7SLU)m-;$7nY@v%@1Ww)5>`A$K)_LJ zBB0w7)^}lAo^jMG12P)1)Dh`=2MpWhFkB6oveBS71G_yc%UA)F!(t9?R#65TgI%y| zF+$n2>M@vImVz_RI|VY1Tn4=o>b?fud*Op%v?*<PW1MwAca*fXGChud5Hi&aZFmk3 znRgS*!~W&Vm(QL(d;0Y0t5>f$B4|AIbde0)=1AM)5a41LdxDdNgX^76Q1*EAHK1z* z$Y6naD}`Q$f*Q5!XkiVsg?cax;M=66mZd63#-{ndH}TbL(vTx}e*8NzqH{_(J;10* ziCt{KF5soGIV7zhOo<50(AgH4VUV}Q#osK!(Jol0dWeM_XsQnZDMpZ*8k_=MZ0hi| z(uZSj1i&6k^ei&BcI;8&?r3kB85WbWJBy>ER-rVpObOLmuxQXTs-ZW_sl<;{QhZfz zv@~DGs1idV;Le(G1bMaw3}(TyNkg2B+UUDRE}>9E9FI%dwjE0i2#i)+Fq%0derX8e zaqsnRTDr5~G7DZh>WjwJaBo!EHAGTCCbgv+K^v3~fsP77SIh;BVlT)Hsh?6d$VMP3 zJE7w18_^S$Q?S=%)UG0Y=9tZ*Mz8Xnn)SrG=Rrr-1-Vxi>Q!<GJQj307hb=9%?l() z&8}Z1K_(z(Fj_j+P1&{tT90NW!Vz~a&ba3hm_OaHM~Nk78E^4`%c!ly@29wWLkT$f zLB5V32e_q7udlR+hx`7pGo?}vwUC*O89!&8-zPRj6cm?Vv?u;+ZIzL@OZqKv9h?gR zW7FrFa|dJz-GB<(Yk(miN*F#_gMSuy`Ln&XJ8do7bmXF?O93R~`Q!ZjoCD3l<=g}W zutLl<X1P4L5olNn4?YXaC)Mk~MPferpwkA1XfdN<w<z?o0;n&Vc0wEOFjpJi7?ucd zZ~XydPN^ZyV0~WaUNr4$HnI6GsPaZ_Khwg|S?;trQ0uRk_O)Tu*8y@=?9zgxvtW}k z0%UhPdNm58_Jcqcu^Y*fQnr3(EVB=SF%4cgG^Oh4X+GVW^zEI9D?)er7ps!C&c@_* zzFlt-s@sO&1!Y)a>;Iu4j>_^9ImaGt*3+E7Gd!U<Ls@oOWNyCPYdH|yWw`tB8vOkE zbAS6r^XbSM+xcF!v4r?_fXqT1pHd1f^~DC-K%&MV7#OM;?HLV7N(x}eXzKONsEv#f zaAU>ZRzYy#DTo&Y?#r0bJv}}B_~VcDdViuOilY<{0E{L{w@HIcE9KkIWEKnzUdDZ1 zaj3w?6wI7GfdR`=n*ae&+J)ve(6kex?mIGaq@;o_LoMZSrzvU(L1Sds0o3RCqFMvm z7IcfInoPtX2&2Msa3$JMOdf&Q%A?2{fC4sF-iDX!9HAF9)5NYVb#kh3d?5$lO~wnV zYg-kL=!e`hy^_4;mB%D-DcEwrxkpQpfZ%!P3gakNf<{4Q#ngC;kJK(W!AZnb@8l$2 zFwkI7p%5_O<)gA=!!-hTf|L#PUVdQ<0b}$y(q)vAP?iQk8}zgg&KZy)FrckwQcCr< z3UjpO>Z9431?Z}Qm0<?VRiM$gB0vqzQeL7G%B%EhK&7Q3vk2@Hj|dtJ(9o8R7(rtV z)X<jDca@32(Sg!{(MEV2OU}*PaKlUd+nzkuw6(DbNEa_KcvKvlB<{YoMTs9@qdGjq ziQ5kX6XD(rY(rf}WI6AJL1<mfT8D_<LFJTZD=yv5b$d4$!KeZI7C8Hal_465SU}D) z76Ab>l(gt+iLY-aj4z^LhA|p2;9b#|XbLr1WDP)Nu0&8W!U&X9H9I8f*J!GwWtz~2 z*V0Ur7J3NYI*A&<tVzQS9VnYF>%f6vr@0zpWYKGuk-;eGcZ5kTvRW8rPpfssYrMHj z9c9yL87T+KfFTXEu?0uhfB~lft-jzfa%j{-GfJ!qT7QBrQ)Wl4K|zqUM0Tbl((exF zLO^RqCM?s>Btcp&3TWDi9&j9iQnM+#Oli>vnsqYj3d*V+h+y7TV9b?`6V0n1PayvI zkM3)TYC4+sy=mblwBe0u(;ILRRvm(G5q}j{JEaXzsDqVd#^KIeO27~Wb7y(+;svk4 z`MWLSFY!u7UC^|X9XM5rN=Ly6v^*7n+0kG_5U4wBW^0#s^mWBX+0TW$Aw!%vjM8-! zkTEDCN@7M+lmJYbP{a|UG0Lr>`M)=@#H6qKoEu66!Keh~(tt`_6sBlHz?y(cHF?Wx zUq3*}gsY4mG#H4ZxVSW#WI;1pUC%1aG6H3d+7{FgCTgmTP<l!4z`1J!YM6U(BiJ-) zBHJyY$8<z?4K?VC8OasIZXF9W4jBZrspmg~DBz{d6by>elmJo3kh<cO4QSRn%K<@+ zt@VuBUJw(Z)Qjo(4p5+6K%W(0%A66zL6M8A9HFttgyrVaFuWC49Ofl0_k<zC;+zMR zy#|9aCgkjgY0+XhRN9nOM0<I8@#f8IE>jta*}wIBfEaTr^N^xP*~-m=a}rS-;8Xgl z8M34WQDxHl6AWp9zGeCNFljXeaLt<A9Me%W5xzTu+N_DAJvbdukITrbG_<S+=Ljt_ zF6<v=Mmc1hBc3Ku>joN-E5Z$+R4;YJ?bfL2j7IBdvA?r>K-%q{?VG5F8$-^iaht!g z;wE=1rEcZlDnPS;cyM%bd~kFazY**3;PCi}HvUinX}9B-Uc9}I-*(Qv<^-jp+~6Fb z_79faOSxyR^6&DpCW~J!o^^eDa`Bd~JTBng&h9=tc4vzZ_vgiDXYXKlpLOuVQrPA> zG=uS{c<eABFB!SBTwGl6hR<Dw?5rNoh#Jr$V}|Ur0?Wc<3N3Lkw(P!rCuKY$m!Y9% z)@-DVh^u3YHqiR-0=wA{CH5aqCqFIvY7FbtfTg2F6DQ2_)rJ*@I7msFuiR#%(Mt4P z(~6tm=%|b}^~1F0HTGT^5L&*>NCcNr4CrVsPY})<(1$V(ZDF@>D~0I_M!yApou(*F zpBH5-F+o|R?F<a8`b4<g!wAIU`pbi6UrDhhK1XHt(<fT`tbn{l3!OAo(o7T1l&0<U zZjxCzG`M(WgX*?4YiVf`ZXDm~=dQGwCvB>UL)r+%+s>lRcM4ftb6RS<%74m4spvg% z==ufLHI*a8R6B@3+rNlv9EW-M38Qica@m45+}(hO3a~tF%oVHIz4|(Yo?Ik#6rz*? zjP)(lfVqG~O-cyG^ntJ@Lg3ci+}@k^phoDLA!VU#;~maiLG1R^m?dZ0)=L>BDGKyx zNS({xZgs}5M3zUZfU-i3SfyW&8AqUO!viR7ExQt7nYFiX#Y_ue7ox<m>c^d<>*&bd zEK(W!uJl8$p<U-fOh6A-+Y1$^%;HGoCNoI2jM7qbt%mlxU^9!BJt}LIAZBD`Y8@Ps zvh0;&Nvrg;RLy0By9;GI!rFuir6L#vGkiIqoTwE9y`yD0i<cF^9WRVogv-mz*x$pM zXb@qDtAI6Nj}5*&h+|V^{<bEhARyOGFP+v;5ZoEU%oN&ZhQ-Q2MvB?F0*tCe1GUdb z^buwuLX!rFmZ<`|L=Z=(IJCy#PPD`WXl5g$WR#YrU@>V?dI;<?%9^kZP%<M%QL^B) zcmW!094bvO;|^uu5rK-MkWLFc7FJH1w~WO<{Vkd6=4EaM?i{qlF)spJ2(a`(5Qn7b z{inZ7(88EK%FD}(moJ~cc^iM7=<sO&<n##Ft?l?7QTkej0+6Cf8xz$|E;Xz=8nBoW zKz$Dda8e%dc0UKBX`oqaVMr8<%yd|#^Ye3FfM2|L;fgWj8Jaia_H;r42)dv|6UQu1 zrJ;>A$j>~zaW6Q1AU?FtfChalBf0O6SU<WsRh~lO=;m-}+=R$10!u1!Y`RNCq1PIE zn-4P6^;DgG3)6K**`zt{WDIT?1T0O8oH=7J^`pJP=JcU@P00#{iAIpO4Sy^8j6J>5 zncDWW;k(d^PKZEE&VBV7h`~on(JRs?B_lM82^vgk!^^DF1NHPr8O!OK^l;$<Zw-E@ z@oA#_6kMA0hZ|?t!#dRZ(^Z%~e1DKo2{qKcjIMVXjtILBO&v{IZjO2t{egxOg!%gH zM<}`&6OBX_ry>_v0!l2oAp1iBr}-<X1sg^U4s_c<4xz`Lj1g<Fv<2*udmIJo9Kp7v z<>ACf0)(@(Gb*8Lg&&0YJHSm`#_Fprfkh!bGof^qv0(Wlqn=CXk*ShV%qSfj?fX#J zc*q%Io{Zvx5`k!FSVUx37BJHhr8ZRqV89TlhvVb;JCMo_0hSmTkgh{^Giun=8qo5v z*U`3wk3asHZOT=HDdVLccx)=05~`hco$?e6AWLhdTAK@tMzhkhP2DuewXm!q@yob} z{S@g3j0qmEW|Y_^cvjR(Qm7$vxlIx1vS`SHjTIv3VjR%jQMw#5>^bv^fPgW21fmHx zZW5F%KJHWSRWPG1;Dx*C0F4EsaY>1fFI^v$&o3^@xPkzdPTwvvk%{mo>oKx8*%1|r zbhN|)l!eCy!67gm59GBbmV}H3Su?zlbDaW@yLyKrdiNE2a7aC`Z{<!Gy_VXP0LqTi zs?^a4tey)?mmvjCS(L6hN-b%*!fGHHEI>prbjc-jX=@e?X`lcEsTMr$1sW|eFbFc0 z&?48A%dA>#XhDNw)CKK1jtF2S4q<E@grd4wS_v9fN!XJt8ik=}^p~GMjz9zd=3n@q zfB*a6-`<J88Gd!M^-urlKjp6R)1UtI`X)|<gM;|@$zOi`)$!rM&Gnmy_s_ofz3=g6 zi;{pvm4{IB;ePu&pA?1-Z@D+uTh}*lIbJ*_aa%k+J?3h|&F=N<%dftE@{7;EetQ*3 zbpfM=?;P4N$Q+N4jvhRC@bSY3r)MWGpTEF0{%jM^0T=$|p|`j3ee6A2ARsOXEET!@ z?trDz%QhB#XFq-|bAQxWMqr353>vOBgvu$z&b)VzJ1hT<Z|8Ci2Lz0nuP?p0c&2Br z_)hwR2anM3)CeZ3belso1uCo-;ydmG)CtNfQw)v-6uYj~41-PIf>}hpaO!G+Ty2l` zw!y?;Jp^QqaRA!E4LFpnu%n}vp~_f-Ee2AfKyWo~kAee=a*FXs)DR#Lv+vI0bVxL6 z@zoLR3i2$*nc~iz;zkv^Z31<4CYV~|@}gbkqQMmPdS${UP^S}A(`G(AA6B|*({*t{ zF1_vMuzzrA$-2Wt=+e`z+R7&L2X;O0?DlQh--(FZZB*da-p0NgtRGAbc7*~)?ap?b z7g5=uR9JPs#9xA+!$cKi)Pe?m%TSGaP=Nb^qdjO=t-nEpZpH}u{nk{8ag@s)fxAGj zFX67}Wz4=6NBefweq%vq_0!0Ge85cXa&z={=7OL{AUN~w&4f^l(h6$@%GN^{171+M zt8%7uL!?UzZ^3;)T<jv?g+K(14|n1r2LTOcw8+-udoN0E+;}11yLa!m|G_`Vc<)Qw zUSL1wlz96A^%zi%1pyPI)rL{@xFAq8kH7V00}3^AW>|ndzF@SH3H$2RE8Z$yIAArI zHjg7DqDyNcB9IFVhz1yn67!pKF^9<xXwqtoCTd~{CQ!-Ge)h93zWCzVvuD1EQ3?AA zc<{{^sHLA7sAyA0MNSz_q*e?iVM#%ve!hLKRe8~CJj-avZa<O8l-rk<1B8H*s*ov+ zVmSKRg#WOrMnH)T#}{MmQR3pf00T5NFM~rI*WqL<<rEj61JSq8h9{81s*n+Y8rX8A zhzWFh3jk!4&cZK(fJ)mEXsxy|CMaV=i&>$@wgg)8B6!@9DO*jsR6sNgA$&Wsioh<R zM$yPpn6#hQ!-o%jwXlo5r$z--31-2!&_%R)Pb%sAW3|xwtLe=USPHvL%H1v+2t!W4 zjSZtJb8Uj@vanHs9ZQzu!$Z!yU;gr!bh+@d^PfL|{`J>i6aAx)KH|E>p24NX8bH%h zW~m%3@t|At)peYww_AScFb=3YVkm9qThs4^bhOTn;9LqgmB5W1X%Z7a{8;mF2?A<h zf=sIQho6aH@6~-r4SNqqD&)@c<jE6+m{GRa5P|#a!-w~ej$(aKS_T>M!k5A*GMA+N ze45b3hEZhnS;EpW{jiWiT7Ly)ut_o6^ldNnY!dA~A%$7;XfL*94$jaIy>nTLk>!T* zzf)q88{~>(KSvw>aP%=h)FKemPzWAhv&4D60?#t36P7mP-3@X{>nEi#U1>&G>MS*j ze~G9Ax=H0Dn{T}tjMKM;G5gjlEl0#Ii_CF{+3ag(fxSWU@HT-K7eEk=RVw$Ow4UD5 zdhC9un6z&TtL@uf=;@Wng6y(5yIPqzGZQA*q{N|g9iI_KwmiGY22|O%WxqMx(DCJt z%<Y>;9U@S$Pck2b-G>kETO7oM5+{j<A<5+m%w3~s!n2#FYYGg}<(frXWQ@Q)M55eI z?adaLs=)<Wn?5g8H054zcDqHIhdt3Ue=8f*w@#ulAd^}_NMtTrZSbYVjLLZt;_=J5 zs|Sp2OQ;qwGhj~{*oCsGdw?m5C@aaR3rB}qC(!`Ca<#oMa)C^;m=R>Q!1;QZ80ARu z;K*tq>w>W|mOOE)wCgkL(b3V%moL>Dgb0ix@RCUi1kk{wU>PHDcQ1`veK82n^hE>M zlLD}D6q(}5u32V|)PmAD8q+#`P$_x=@i7~Lf$5sjG8zcop=B0Ktu4;}zNbUXOCe_( zlf{;~j(pRGHeR05IHWScY^Ht$W@k6mZOXK0N{-wKGWI^KAcKb^U0Fj8DA`FwG~Drx zyy?e+MC&IFA}Ok<BeOeGy9F8u&yK!Z^OdF@rl3aq>Wa!f)W|@3jRsO03m}f`)7Mir zw8JVb3O2QRWI+BK|Ka~3ts4K=zw>{IZ=qunF}6SF?f3ecTgBU}xEviGAK!oQfc=bT ztUD*v&hE|a7Nc+8Uio?c;^q0p>sRL&v=^^0`Mkb-!~d^_pPwhr)m5B>6vn}2<8gfb z;+|*C+pEjxFJ4@{zM@j+X#G~W3T?0=?Ec<fytr~5I6lHHTyOJ-VDrnM%$wQm9~`o& z`7pY>y}P%&cX)7g7_Y$b1;^d(J@$B>AJ;e6x7RmU@z0z0xl=}+)J*J?lVd))y6oy5 zUX5|(lll{`S`_a!oEAAJyHA&Dk#S>c)RV>U92_3;U*FqNM$qNmawl}J7ILPIQika& zh7D6_&+^)xrH`o`X*wJN_HmO|pmFcA37I5t+oNF?PDDMV;XF0kn^lCKX&g1H)`w9I z6hN7_;+MYUSu|Kfv+Gh!S*53vbR9FASJQ4#jBIW>qR*mGU2*kLdc--iQ1+IzzzL{O zg!8-h^Azk!hhQs2Grlzl`Yf%PDO8KSLTPMuyepNlppGWJ9~L&HFLf%+F*Ahy%Jq-m zKe8zn*_Tl=*I{G~1dVMOY=}n|Awnl=JdVg-(vd4sS_Q~O%@@69+PiNzXB2jXqkUV< z4o#KTRzh`U<jyGbVyVH2pkZa8p4^ZX9HrGjr2<M~x<s`3TpHhM;?|A6%#Z=SRJVqr znEcxf2(;QLS9xHHxZUsW{*}M_S0mPYv-{}b10{15rZ38XC1X}Blax$ZWk#20BOVT* zHi~h8$bh59wUpv0US$a$Cp67yAmc4+L&g|Opazv?CZuap9wAy>XfxiD<y2Fk=SA15 zaHmUHrVQxQZ-MqD^lb^&DQKkilbT4?Z`q)M%UIo698IU7l*)YzL@Ver)9DaN`$L25 z`z`ChIe;JxVW5l+vfVgN3ElJabB3^Vg2))Skx*)kUIT5Ar_^!pL0|5riE4(QL_mXq z-!H-}47&JeGzN_6s=)>Ocm_W_WUE_PhF@TCY2gwqX$>WIM`n;i@uC~wiW|N<!1`cG zml_Z%bp*=VI^U(R4yhN1n2p`=@2GVHEp1gIo7WZ%FAP-WbqX7&PY_-70*ygOKu{w! z1<_aNGOD02*d3APOSFM>EKNnQt7g>JXbDoXLJkJ(|LRt?;ChN0ar$i_hoYvWWQ6~4 z`33mz{O$jQSI790C@Z|Z{fl4xVrO^n#fulb+45p`bR4gCbT2Mm@9ynzrRHp6qxxnG z9IPi#p1gedl6Pj{9JHnX;u&wXeCWP<bIA+v)_%NGa`MJL%(FOtjEYjPuC8CaeEE9C z3vdY|oG%N*RyjU8x_9s1!}$Bdr}<9_Zf|m{(_lsb&NSY57eB5P3eMJe_2tw<X7{3I zosrpkd(;`P&GF?krpd8zL(+16KJpJb@#33bdh=34*_g3t+SARj@!Q%JteGqXApq;l zMUGL{lc6YT*eZ7-rjx#X3;hc)s9eKr;x)d#zT`Atpi)@eCapmGk=GhBLvsOFm<1H| zDreEFbvjB}K}2PtW_Cy%61%0hLIlby{VLWQI7(Y)C2WY(oHANEQ$Xu)z<T>tdCO(w zOBWZf4|b`LGmEYoP_T8BbJMd=v`^bR5DAjj&+MMdhPBjYG>PA|NmF&`dsn7j6w##b zo<94^`fr!?m=#SmV)YAfty{l_6-S|3&<t|CDHqrNWHdU3t>UPyN12vudmi%!qwEBT zSREDs)uoNNUBDdK6dhMlVXGx0La(u{l4fzVZ&$%6Q}Bdh`YcP_aPw)+1p#Excov2T zl4S;*tv>bPYikh9=tkBgOqb_KkX0|hltfEp?$p4|moC-*Z~mQsCxg8&@f~2LoKawx zOjV6~=fnM;rv%?{)B{yIbB%K)+fS_!C*uVeNJSR9YVhTO1{r}|4l#LxaHw=~h&EkU zUg$|(HfkbAzQ8D;sZqKZD}?DVgwn^O9u1tJi$HBYit$8cUMmFS8>-}L6?#TWg8;I6 zYpB(TLo$%AL3k!pImd%u?lG51Av}}1pp;U9RwY&W!-pvSwn<+nMD+Y&1{SSVoF|@7 z<Qij!5;J53wwYZ<X&EIEsLZHiI1t`7`xY4LBOnkHu-A;k=Lx2sM{n#4Gzz3H*&xPe z3Jihq3pAL4_T|WsvZP5{QU&E<G>lz0GP)<-fe2WdS9{B&n~p6nXy7P<t;#fByrcFu z$Ot_SsmHO%!T2HwtHCm|uym=AuIGgYg>h=dkZCKgr~#B!i5jpgeYfPaT0%Yakt6-k zMJR)6VYF^VucR$}FTzVymK>ggmnqyQX%$p<WxM!}z61Q9{;mJ>gZuXnkK#{cZSU;< z5<dT&rM`dv!R6aGyx7LI`puiuvy+>fYyQXK;L7dQ`|>ib<kZP^Ixp3XR(t*G#mh8^ z4;pHZ7t38=fUh}Y$c~<aOXbg>zkGeksoIXFQ?SA{V8dcCDYgoy-pSF?;o$)<<!tA8 z119=a>=_<_d7(w=Epl+hG0r<KHCXbt%f=(d+1b4Z4<0;x^niEiM;|?U`0&B$>B;^3 z_Z~icnBV4&?_m2~Uo!Ik>n>$REXA-I?MIqvnGTS}E|z3rGxPdPb(nkBGn!Qen%xy6 zR12(3jw~>;HdFe%Mktzg8MOUq$?ng>QRwAaG<c_35z&`v14&b@j<#lqrRY~fupcQi ze9-#K)H)#dHps?D=+9+9o}~@X(JYeED2!O8A5E&Dwk9Q+A!z;0z<yQyHF^6)BQv`i zXvwLE5;%{lg^E-35$=Qm6^uhmKcluX%EnPCO@VT@y(?2MifGdNF|Aq1SoAh@n>1!# zztVoi3vlH^=;bUVpxdOB8LB-%m!l)otQzPwg^PBRy7<85y+!PfJ2)!MEn$CBkFs7w zrd6{!qp%|!?c0K`C|5D7U@m>Dqr^N1Dh?B5O$0rfT7S@{f|RCU$onI3bM*Ncz3zt6 z5|Fioz5uL2Q@)GKsuy5d;u9H^<*)v=zm_52m-tR>RN76oN2LZ>0_%l_3V49vh39O5 z<zqBvlCTiI5b6a60RuW8WU@H1K3(%k%0~N)u^>IdKmmIy;R&yX1OtPVrKs=a!uaNe zrX6tK&;m&-U6#C<tW<D?YI`)3v<(B@MLp}rT2YUq<f=;OTBk$W(-skQfNlisl7jjk zZN#p6Fit%+QV9p0r%W~m`q-pdCo;x3=EB6vq~GFzs;~VZm@y+Fm-`6KrWg$a1yF9o z6I?f7&+st)D*vScvgLu*HtXRAkG;#z^zni=Je1lx%NR-w4#*7Q(pQ@?mO!Z&#^kLv z*SG>!G=)(srI8FDAfq=9Xj3WrQI9NC90W%><uPVi@M1pzqpXz%$eF6GkD5Xo!-AR` zvMuNuO42HDNE=Z3PDYjntQL$0Io{AfYLvEC1_Kwc3}V$14aE2g7`rFwYOmfdZ4c)f zuW;C~8P3nopFMlV`tR)RzP*m`Ki|7|@6%5|J-vT_Z;yA^FhfZwFbn(KZ4Ai3zKR#Y z%ge3p-R-Tt?X6uhU%lmk#+xvkj;X}YAaC*B%ieHO*ihKw<lO}4LK&nco!@+Z@!|za zE7T^U=lze`Fph=GpB|zV&eQm2_3-WM0?qU1&xwiGqeqW^@Pi-x_{Tr~)nENpmV$R< zylQ!AErS|x^u$L=3iM_nyOt;k$bLqk>xxw<*VAZsB4(IgeLI2_LYAhQz-W^?W}`_B zA@s7scTJyBoEkzL;Nk38Ghax*MZqpn>&$hVwAnNbE={$JdJRD3=2Shsdtc;;n9Lly zPibx&W3<*;uIf(oj(tE5rAM<rzF^)doL|5>1--1-=Cp8$T~k*LHAL6i0C~!+9>;IT z`}lqfX45(GSzH#dn{y59-ia1ySbv2I)rUo3la!4bQC8XG=oEuY;UMaWY%YvZ=HLvu zZQJt?Xk0<QQ*s_b$p}`Gr3ED;D34kRiwVptZuxoB=lnubmJD&O^%IxA7#6`UxF8xM z`!HWNW%e!L35RGD!ws6p1MbmuH~Bl&8xju_&J(PaqPgq$dQBZAy<f2BNz2DCjM2M- z2)YB$3XB@3Fd$$_Ol9LEV8B!n7&Qpd7}8g?*MMTm-GCTS2~R)h#i63Q<uVdHW_EQq zj#vOKshyyYM3l|3;UJ;6Y=VHsU_c{R3mG-Y@umd3(7Q`NT3|zv@-^VBr8bqZETJ?t zT3AMJEOec$E5ORL{#d#Q4q=0%5m+&nNIfmGUnnUvQ<TdnLXL-l!W6O>lvF~7oPmOU zkmV}C^EA*!ADeHO0$qbsKsqfgmxA_F98L4U>CiHy%&3v60ZcT7A&d=3g)B7%>%}NR zqR<SeeHGTX3MKcH%Lr0Hjglg#wb<e5-G+dASW-0K``-8d*dP02zy9mL&TCj`Zg=W) zd$Y|4!B?s2$6rAyeHQ3t$>~OUg*NFoGt>1{w7vzS^{6icsUfcn$QZCDY(kf@)(tR2 zBkHlixE4HDbg|CJv^|_Y4q=ZY8{^@_hje)fWQQD|o__Sb?{Ss(AK3Fwd&_GoZ?-#o zv^Tfg*Ed^!uC8z2Ufu9{^Y%JE`Jzigb{vNZ`TFXX4|Q>zxwLcQas+R#$r~+`i)!Y` z$<0t@1C@iPs=KR3%Z913EU^%*(rsMfx!Cfe%UOWzwU_t*ufF=~m%set=Rg1DfA_op z?LYtT|2sav`_KQ|fARnQ=fC&+Kl%ADe)_YY|Ni;KOFl1OJ%9S_8$K^yK0~H82rV^K zUNa&CRe7@`BYCL@OAI_H)ZZK56&<Tp=*cw*T7Qnw=rqWP-k{{joy>MWAT92IdmbTn z{BRvZ*{mm|)1s=HJA#b5g?in=?v!_q_U#(dd?n2&X{!H0sr7;NRk@f`9PJ&|bAr&K zA01!2(vOM}dikzo@<vl7CPJVFx0#v|rUqq|VmE{RA)-xn0z(w6ji_A3?C2=MCd|eu zWgk$P3#@Ca5=##dngV5^*_1Xs!Qcp9u@UI5IgXCf+QnWkyWbs^u}3A@EkL11WwkQW zgX^i_U5p`Cp2rCddLl%oHoJmrLW=={HX5V!2_MpSW+I#8eV@n(7x_mVIdGKPhTogT zS3c}pF_31oMS#R;9HJnq;nC{JlP6z){dEPQ)rOU&wVQ)8jD{*5&yKto0nZ%dB`iZ_ zOt<P$lO@MOV?$m*?kNM?4Fxc1CT}n)S{{`Uu%tpBF)5XrIq>3XYy{nv?+U(CLF`h1 z^cn@|_0o?{>Fpy&(#zl|mcSgDwO<EeHT)tC?~ptr=J8pa0Q$Om>>M9Afg^<;8x5r5 z7i}PMG>VvmN`R{R7TWLxr;tuz$#FbAJ$>-tL0`PI^g{t0V(k4&(8<XO-B}FMW8_$! z6#C$-kMV6w&kDJP*z&Y&K-Q3!0nZ8IWlY~3G>*vVBFZ2;TAFHyYyma}T}y%*s>)$x z51xAW@89R`_fP-nKmDiv)SvqP_rLEtpa(;N_9cwy4My^6Jj<eG%cO_77W$#R8`Qi( z_CPaQwiDL@77Aaty_C%em9fynHb4U|wFU}3FV0`RejDf7$=T^gAAR(_Pe1+Qi!X3L zJBi;!@c8r3fA1$h`R1#y`mn%|T@F_5d~nAC0psMn%wP5I->@}vZu_0RFhCPQa%Xzb z??gXG7K-dvQUz#co$w}pf;&|l)SK<M@#mLbpTEA~{g*0vCFWMfF5}&th3E6&(Id`H zt}~AxKmO@YfBN&E|NP4@zvNcMiQ|{Lcw46X^yyRHW}iQM>Cs`jb!NHb{5R{2dkr<B zxx9=QV2r6M%UK+_tnUMJr?6#gRqsTzY87PE{jSONi{dM9Y1Y#h+1qdEzMeifOaqP# zHYY>5f4sJY%wu^Dy3zagJEx!8x1JQN^5tYP1qOnQhBLkJ#8=42sDLX&lTyxLcc7nF zFO!89O`+1-N?3z78SGygs$l24o{`P_Ox93+8!MOr`xa^spusY){c-nnbaU{XC9-B@ z(HM;a^m?$K^7_{Gd^;?xZ>u(izSLr5Q_vOUT46!X8(cfT&?tzh6$&HtdSy^9O+R#3 z;uo6a+XS`IvhsAf^|#^oX8YIvN59GujR&3K;f#d<mcWAz=*ca1r{E~%VjRMv#F4g- z$s;l^^axzn&^skwKd?t>K->|~0IwO$9E?mrywLNMgC;|^S5x%hu_Oqspe&(e3j-dB zXshce5Ks*`N{ikI>U$VvF?sOfK?+~GUb`8xLclTCCT2mGAv7KWl*|Y||NL`CwV}<} zVMa?FD2-j_Yd15**Bx+#oNI$o(5zwt-DZ(LnvOdGQQ}Tp@fq!h0AJc(Z$OoWO5q3+ ziYys*F$-L1o5KJaB0Gwit+2dwfl*T<GpSY2;>MYxi(XVkZM8C12o{4z7rU5YZvk|9 z2X=otgp!Pe#S0r+^hS%K(@P>&qTCNnpc3M+)L3$esfT#1IY*6m2Z}#L!@+<1_L6;v zo^wc>>uVnCDd6h#^qv}IBGBgI#oRN+0!v~p2sqF(3(No|C$9@)TlLdr5qRnSlYjD0 z{_uxCMETGD*+2V7|L7n2%i+pJ0SLt^d9ombqfmJbt0R{Py6!iJ)Z^Dxv1r*8w3sZn zOrK`XVMSZVr7E$d3|dCjfc9)8=0%+hv0}8y`EnKKxEd_oB(%5}3;_ah+);prn4f>~ zWhQC-x&Ot#`smT4`}ZGi@9kb+-TsSz@h^V*)1UErc77h0)9tOe{34L??N$2=Ls7<? zP!i2|PVO-j#x-YeKdxQO2uo~2z=4xucl+S@=(F#A^6{r1@7!+faEfeiUvFLSZf)Oe z-<-dA`Sit0UNCdx#c_<vavi`~Ou>>vd3YFKLV9rj{(}b(cDHUX-@Lwmc8@pHgS}X^ zr{Bc;>e<=J?*75W+pGA=fScRPtG911-ms2TfzjK`OY(7SMy)p#myuQhjSDiZ>h0T@ zxaS3a>^^4BF@N*sie=;cV$RIw>go-bc2<cBn&<n$646pmVV6Ue<6|_KLcvX1#`uu2 z1G_zC1G5IesTe2caAnhlRYfS!m;!1WjNq{1?kLfSfPk-FX%ghIh!dP$+EmLh<T1s} zfXLRvsG<567y>Nq!pH!jmuZdGQyLA*z7N~e$LZTGPNWp6NGr-m!=!1ID@pv{AD>Ck zGE=9|38GS}yy15mE+@@HrhrE5dSsz#2fY<QX%uJ~D#9W4R+WYU%K{Fe&#GGifSyxH z`-n0KIXDk4T7q364qcTsO1tW~sP8QmO5fsk_dfIv^({keX~2wQ!B#}cVy0_bsA{3& zjBwowG`g&+-{Un+;q`3_@i7p(ElroGZ^6S9)}6hY7@k8LK-LjPc{NiIUBIsP2uzSw zMc~NBCLcEch;lRq*xlWWL(}Vpu%?54bXEM(I+URMlp58b1a6hlPT>Bo%@k78642|d znpOLOyML3G$w(~}UE;W(y*{8s7WJ$-ZH(pISuUu&YV1-u$K~F=d&p=!Sd7N+vwZmQ z@fTlVP(M*6TDDHNP;k5-&l-SC8|jC|<kb&>8^PJx8B0NmPd@qNw|@J#wRumX?h($= z++cmmrJTY%nI2$6>#k+~y3i^VWhrQK`t2&9J$hQY=#}-=1|_AU_x@Lw>RB)5f?URQ zQ5r-g7*H7HH3qQ6OiMyRMs1-qo&}ex1av{K5|9n0F|bh9AO5MN%hJUQ&G7S$j24=y zFX$Q#N(1H+HA0t3Az)cvbWx`FJY}Y%P!f7H#>`Z0)<tG$IOIg==A0q|Q-(U#3B}<6 zBWIXJ99^cM*K%_VWfm(pj(QBxNF*4Zx@-%~{E~<D)5XC3HVVbOfFZh|zA)4*na69l zi|q9xekIS*QGEZI%slkJejWdu13fKgWbQ8OiDC{8jwmK;L>a4!-jaxw!5c%ypkxHx ziOHo6c~rbz7Qv<XyMOoZK700zf`0wif1UYqT2X4e@eIEvAuDNjYc$pXB${0o+n$(4 zk}oZy<Dz9yljZi#`{b^8&;?o0*D`w6Yk<ay3thcvxel;mEFcD2_8gy`9-bWU9<<Yh zHAHC;V3q6R#iVipf;DJtMl`_Ti|Ev8n+wkyFE($k<6p_%?!+k*KLmY!{hAlj?%%*~ z2s?rH{QUgMlPByGGO|5B{`h0&%PTRvh1S!b{l+eevaW95UdK;jQwODTvN5#1w;jKk zYtrVXUf`4!h-nQmk>TiY4ag7c;~m-s@t5lPn=O45i=<$L4?@)=qwWWxpRz(R)qFch z@t&1eB_$BhqccT=O;|NStF4-6i|>`hk=B1Ns(z!ryIr+!)kt5Pqo8rq4oo$&N`EIt zK`6VRI~{G(X4$csg&{-r0oOCKG)TW<6|gKzQ?15&sgzmcH5jLLhGKfnl-_2&C15ZM zLwBn4eK1{5rR#@~y$A6i0lsLpu@#hi1sv^s^uS4E_fAw0sT8Xi8I0UVcwSFw!yDsm zZb}=TuzsKSsONUft*`=8ws&d-f^b9RkU2zTju+1xKD3}Q3(UqZvYhc!>w=!J@d%Lb zmG9gSo6|N#pUGsj4)x3`g|z@4Vua@#=I?rC$cDz`Vlrfbe4JQ(qYM{XEFDE~2phU( zMhh5g1BO)zbWvuEhBktw#tLe9-eL+=j(aJc1!#;ivyIn5B{(lE%L`={fF6yZ)N7AS z5cITYIOqGPUNmK<<){+6qfs2I08#EWV4QLRBNXVhsmP$Ea?LCDdtwTWt1TFcDhHez zLK~h?1sexTGS+0lZlTxa=t6uFfiq&WSruJ}XfZ<*r7VLDFoXeuW>R{G0DGfp;1Dp> zq!s86nKQ_G8+0i+UVrloifm(MkxLsOW5A(dZzEUg3P=P6P+7P>8q?C{>f;OWETn$) z=+WuvDQSQ7qaS_t*=KYgK743W!OWJJ2(;vN^H@Me3Xn%#3IM!pi)JxF`zhtsw;vEw zAkZRv6h<1AXma5LC#!+zlFP8zO9fX6(2JG@OvAQftSlcA@X?Hn1mXQ~{~-1Z@!9HF z#@B<}(ze@-5d@clE^*i}<f5gE{kOOwx#jR>FZq;1aFi54VF<Y%u^?y|wJ<=i5(MhJ zdV3R}2}CeRg%SeVRuC|(g=wG-)LoyLRVw!)jo%+qRJ#e5J*5rLF$%7+UZC<@6Kj-= zx~tG^71YClurTeFr!<EZXi#Roy*2dhs7tHR(?{ro_xkUY*pa(i+dH@Mtt8Hg+xW5n z>zlV|N?D)Vt@dS_I$sRJypZjdQda5j%E-M|G8eVUnJTagH3Xxf5plZCVT8T~;vkEf zVyXe`Te#tBkXM2Lxp(R1@<K+Bag9!0XlKzzoc@|cfZ0)$E!+f#X3-G?1?c7Plu;s! z@wQ^YdA(m;nO9M>5W~jY5;YL_gW>&cbBr*;6tm0@%?1&7S5Fpu=R?q(C$!-S?pUzf zte2nLCCB5qFv>*qLSTsX^mR#lo-w>#GRkwHvJtdbz7yp|Qul*6`u?;(+3K}Yfg3zf zaTP6Un%@K#$oT_;>s4ORFC0V8fi41im1rW<Fkwa`bSf#Vd_jRMVZD6O!3=yEFgPI4 zMQOBh0lf%C8(&+<hdGWMM5fM+u!e&0NlaG)bz(zTcOA2Yc6}_=E6`$34YYI#qOUPQ z8<e^T`U+cSb|Ffi!@_h#ASocwMQI$!NDbpFM2K!pbWu-agV(67WYqQ}F?yk7C6O^> z&j9Yo459Z}M4+S(GKC<b+2-JaJMpa?4c$D#?aEuz0lU4Xz}>@#jBlPpf%bsj;ATXY zk~7TWh>vhoh-S6mH^+204rOpv(y}>s$4<Ry4;b`AO`EV4iC+;^+MVUqt5?|n<R?G* z(T{%k#TQ@v^rt`lhyU;&^4jq1*|Ylh;TRCg71JxH(k4Zh_*uxJl9H)sRFaO4PQh%J z8tq$!%~@k#71GAO91c1Kmj;kyp38?uFU?pk=8LQ^Z4W1it6?ZKMi6bJUsz5wZ%$}% zWXJ=7OpAe`06|#+JVqHl(3gPPZw~XKWuu;)oZ!wB*f~$1K4q(T;$uLIjp-090KvS- z6r9^(1})1=us4*bsnvs;k&|*>=&`XXBH#TQvk|23Y1)mk{wcGe+E~(5@6D)eyHncm z928RrLQV6TLxU;h-nS!+Q2T1yDvUH4I8g3eh3}Gfm4N6ZtQDxStsw+=wW#cUi*yQF zf1qi<6{84Ibhq05s6${E9EH}O(1s@v#1wrrC`}1s7wonu-428@tK!utKn}LY6&%rE zIW42)UO7wUm0q4w#tNW*mS!>G+tvC0%%-3oR*zdu-DPOG2y>fg787u3QU{J6$LhvW zNz`mktWjc@P#dCsb6$ODtg88>m+f6?X(qJc3G4T{ZI90({Z)l7H$)#Ku%|`lNO8P~ zgUmhDAydFKY*Cd6mId8D0>KGu_x*_%Auxf-Ad6X~?DYy$SRi3hnv^hv*C-2fpo`#4 z)ToSDb2x-OSPw0@%J`~`G{ZY8>Coq6OdJxrC?i&v5p=|cBg!+nPw@E&)E)|}{-WYI zBie#dT1P8*X{J>12qrC;@~UdFQK?JW=%P?eHKLNkM5)9vDFR)TdKJ1rb)$}?*H0OZ zS|=@zwB*u2Jq4uI9nf8x>OE+IGL+@f7Hw=9Eel=LBUiVMuQu!)FC5{MMEc1(PnjC$ zL5MFTp+~6Wh=%y)1$`}v)MaKahiX3;k!%<O1iI*rNpQ`ka2|0H<aHPMAOGWj{7?SL zKlz>C`5iJ+5>No47%~X@bXtisg_5ftH3oTSoGDIFq1q3K0huO6B3HpVxFDvKwEhHq z8O>Fnxp~)dL11lpdo&uLv=s|rp*TAJkj~LD_bcA>b`Fo?kg<~3&#osadRTuBrEjWq zap7*)Og9E!N-`ZS8p1LKWV?0yP~%F{MX*8yv*+;s=#$%|eMwi`emR4A`rvG11<L^3 z379tV`B2268fdByN(-H|c}{4ibNln17#T+0RcJP)l`>qZ5VYrr%+lN@;5cm+#IQmf zT9th(r70@lsQm+gL{eP^m=@WOj&N<K2CMXUWi|p8)>4}VYDnQdG5$1~N@=QZO9fE? zWG)d1H6xWJOUb=*gb_e@L0(0T_Lc}O+{WP5q~$ulYfL0gLAXS7nN`-3Bg-NyPtj6Z zxPfNzhn`Wj&ZTuWCa;<^wBfs8F;-Q0P&gLe84>8lEq3_}ZRLmoC_@Hbhra#9dq)KV zlG@j7_3uyINQllO1fiLmAX5rt4GlHA&7y$|fxYGSO2Dk5k(6BV^fEkByULomd=Yn8 z7tNsb2q?8Ir4fkCN{v9-dqH_2lbxqJKu~X}Djqa0FHq?ys1&=EPEA1<CDU;Tw4^PA z@-<_xS5vEPoYHFv$f7*bj3}iBhBBr~1nU9y3XD=ooDIXv63U7oM!+5cGDi4PIfsVl zOCK>AQW+aD|IM}-gdr*SLW8?9^{rgy1!hE-bX3(;9gM>3{3D{)ue<Y7F3Wrr57ao? z7odKMSrD|LwQ^FBs6fxdx_|bjzzi2^Bd=Xs7-ckzcqp~(laht=8hI8BxIF#Zul*XU z@#M*qFTVJKcP&Dp1ggcCm>Ltm1TZ7rs4Q``b+Su~yHzP9>*|@K72u?*RoEN?HEE7W zlW0cE(vd>F%jhUDaSH&Afl*EYFI>njPLJ!!DA72${wBYo86~VOHvWclxSu?Hc>nC| z3;{hsa3Ko;vFzPjS&6$SPuB4_pT7mT`+7+Pw#U7D_h{KL%*z5S$@q~z1s4s0)YLEw zLj;$m%ChM)1QpFt#4IW}#{TIADnu@OY!E&;L@t_Yf@N>cY^XN2ysB%GZbDYQh+ub0 z8(smGcxdc4pE)#`Mfbj)r3FgtR;y4lK}31lDtxD~(@g|)Ew4v2!G=@V%?ujoNZW7z zVwL``j3SsC!7>mufE*9XMn<C}G=3+|y0fot31ZizP|F3SXJza{4JmsK*QSiu*elF} zZ?)3PQzBVXviey_?bK*XpoKE%WrgpK*%VBH>#Y}C*08^HH;W0gvnIIHgqT(4$`x9- zM6>7xc8#_P+BfI5d7H(sbClcI#^^Pr4Ns_*0lFHK-L7pxm+J}mGy(`dC-le5BZWY4 zC!((y-+)sx|Dsy#d!dHt5}dqt-=BEvt6Cu{P3*#`y9#Y`7H!%-nU!+7A{x|EGUNja zW{k$>&4Z*bqt2Yxm<FU(FtRqlgA`#=5)csRqC|j5zkCTWsl_1ZRgrbUzT&GCY>J9D zstOR)JEUGEx!gJq(K>1_1ma-B`czCEs~ZUtWD5YJNhyV}SQ0ZHKf9kwZNtN?3pLpE zpfMw(?tXCHG!D;1cUtUefl;SM%NeEF6r(v2x_HGTC!iO-Hb-BCQI=9#KouON52VKe zH06bi0JSC+M;t8yGUv+rGeg4&fZk1R3g%LWRWoE48G&x^o>3zy22gr!gg9R8h=8#M zxX{Ia_Ve`Fv(LZyf@)r0UcP+w>cz{KSby>Ov03mn4v}4%D$Fhd-7GC&RF|T^_&TI} z4$>WeSdzI<+l0DT`vIXg4~L6i8U^%B!C9z`<sRm)rO*WggN)d|x!v8`KHS^qgYRX2 z2e=Kfu-jYpxw+mt*gxXc_oI(Kdi03@-lP5aV|owy+`oUut28cwe~Ou;`Qh-yZ+^}X z>3G#X+}}UiKR7-(q}^wVVRGlyb9Oa-ATx4Zi|n#Q2rkZb{NAg@N#qvdHGK9{C23sX zWf0K7M3lk@iRkX$^NWjD=jZ+o7Bn6kKgjxi5OS_F2lqoU3ZC;=EQ`u-jm5*byW-;l zPCw8J8ZeGWYRbrc^zmR-8$vfzBTH$jopuX@Oxr&Im@@Z&_AeiLadO8mDyK*aU?;av z8T6Nznh4eQW!nM<tMm$Yr6LG%1eqZj=|%k-;#8fZ;`Gr#ebKZlrbhM_Zn!A9*}(2J zf;UIxoKu4<jMJm_Q!>Kr2QLQ2Akg}A%#Na@l3AS86ucPK9eVjY#igLFk7p~ND1s%; zXAG{?Z@I`{UG?{}(I@^UM%Ufii5nj~A7bXqhbEKXfms(~Hfh4_(3-qi)DqsI+VIBY zL}zHj6WZaQ+vj>!tKgLcf!Z*mPV^|R@@o_I-UP_U$H${rIoh1uJJ!E9$Y2e+B+Z3s zX!HKW14rKC+n4i;Dy1rbH51_3>-Fo`7Z(@j=R7%F&^2ZoPGSKvf&p2+x<<RWt}K|e z77l%{0nLC?d#{WX&s9J`YM?4WFe9xP2ka7uQGW>*O1czJ<lb@=d=|`Ttw&S}GBNwG zYGTC`NAWU?V5W_;D93`Xwe@<lk0?Fc6k}q#0TAe-)OQV-iCvQt&<eABFJ)s!N*%N6 zc+4d=I9V*6EErjr$eQRoi<X<C7g>r@LQ@S&^0xkflZC#1lx!Xs76Dut%=(OxenJMD zp%O`NOngr_G}I7ZpvynY?7ET5<w}qC^&q1;1e9$k^?ge~j*bz+V!&uqe(-}I&^~|u z{Qmv>6n1)gdUA5|@y8##8Xi-y4A6^Q$h0P{YDb{27hp<4gK-~c3NEv>;bqp$>svsU zT;0W9MK%ROoY>vtsS}s-rF9E2LG)VoFv<{mLeUb0R+>cz>&D@@ckf;vlw%r>(Y<?T zXJ@C}u~<@UEC6&VO3CGsizE?n^LI7JEO<B8ZexgsV|~AuE_?XZt5^9qoX*)HXj~;) zmM0H#!?i+SWhi^X;`isnXf<#YyN*JCAPCFCa@U}eIxgA+GP>4zZ%nEnz4Aj*0c#@t zjQ;Qt3!T`dY>)U94W^WD3A3zO;eM!>`+%$D?~c(vq%g=+V+PC^5-r<6Vvq_|tkT~J z+(!}2-q$dj;++N(lbNGN6*ggHY|?(kVkSvlS5fvYxX8+aF({8*6xKklCT)iHeY*<h zWm`g3j@-8je*jdXDxOO>_bKiRfZ%=2p*56y8P`nhVgPkq?nDKbin)rB!N`3?*41$5 zD7WE_VZO7p;Ry`o@<gd-gwgtpCc-GUMPKx|L2FDL4ik?7;IkP5&jvoU=vZ+^@kdZV zlRBzGd<jU{e107NQ_XM9_78vXEBq&?AL(OBGNn7uWvcYF$fbvfkzijBYOZ^EX{k%^ z$YQZ%Xq*+TzB<wZW*QTRA+i8nBO9D9j09VQ6gj>`DG5&7dsPkQ)u8kmgL;Q(vBUtV zjc(b1dMFLBpEMh_3~5|((9n{liqQZi=;9DIxi*28Wm5uq5f}wE;1p<$4C;aFkwOLt z?2-a|QRAq-%56BILRv;?HL&HvXQ^%mM%f;qrBpz$+k=wUhv_JNNFm{$IAt`h4`v2L zqX5X1(Q5>a5QkPJ(P&+VDxNZc$zEJsVBm4VEGkHlEfS1b2K_;FlrHO&^|rSiH0U!@ zo1-!)V}@YN8bzSX6^fR^h{g(|<hrIMlrfMU8?&1<>kXKaF38w~Cc)hZ6-NOh<BPs& zyD+X6YP3*8iw$k962$|TEAO4?QF0X6;T#TL)$l@7*sZN?SoMHc?z{MgDnV-cv_!LO z7GyP53>dAbbk&XwiYh>ZGUL2+f@sJ)`a8h?`k(u=pM3Jk$>}|g=EddPpZw$}Po6xD zUu2Mf2bkj@Q@Fj^-QL;X-Fx`(;rBlIh?^5v4i<oF_x9rppv><1vzI^n+0XG~)9!5V zaff4u98;>w;~RgY=tn>L!H<6Qqn+Jt-cfltVPP*X<Hw&c{^pyfkH32M>gC0Q2M>6O zB?YgJY_l)F`ts;7{!aUpo2~enXTMCuJNOTO_``?y&aQ8+9^AW+^6E{zd|qC}FL+~5 z?d<Koy1csHVi&d37FaOKV-~q|(Kc?jZ?~>FVk|0)=1PV-4>^JwhajrqW^@pLXP&u$ z=YAf~_RAXQXj^>*E=^j-#T2?N_mI7H22{?%fuJNe9x*X?@A2BMZxvuJG}WyZFw619 zt`oacYCxN^bbZpboz#HFxP3Z@SY$PQb_A|32--L#YCua+&#A85FD!75pfCFxC4K2L zUK2dl)h(gc$8DpMwx6#C!bzkO$`}~3T^8c(%h*v~8ZKOVp=5em(xR;OtO&FvgmwG{ z_>u!%oNo>Ff@aEq9(qmBXj#e(Ju<mWrxLgj(UztJvw&S-2v|>)&W<k8+~=I08UV)W z8t6M^)exbYv`p1+e7c@!+GpBDUIg^YV70Ql;$I0dL<Htiafnar{+xoPLS_!^`nTMB z94dnmH@9)zqp~bJBeeozIO%;|hhC$v^(gnks`Xr@-|F_~w4LH1a1YSM%+*GtV71`T zUjCt5qxJ2odUo^g1{(^9gVMG@-=qOGnYQ8eA!96t5V)(-f<s`}QE1vhzkd+*TMt6T z@%pB+Z<!Z@(A6G@KzE8}Q@B153P-!hWCZoXDDKwAd`ro(;HlvL{rGoP%=g)|XWxAD z4bKCZS&0`PjS<?;Pj+u_cwj)lhEbkF7~)~<<m4ou6XKVH5F91NeER99AMEb{Qx<gq zLN6--GFbs@CrOnEfCjy08LgqQXy3a423!!i7cxViIS}Zgj7)R%aViL{VL>J2JR16< zY(~SSxgcy01{mYg{PQZH#yCX=3mg*co0P^)N<D`Vfs9<)O{9|UEM@^Lo3t5ZY0|(b zLRPf+iDeIj$AZ>Tz_ONzdfW-(5eMX0f;rf=z-D!_1jL?ndYMA33Q9JD@_KNodYB0G zDKH?8Q=qM|ku|aYjI@*#Azxq@|6mo%T&?!>&|@fOiaqDB-yFk{_2gB-nC1dqGF8LT zk--#(uu;}tN~0i#wH-kmX2C+aXo9jT(M(V>sXB<5VXS*551Q#}v>6pszP3|h=M5*j z#+IrK6eGyGFzPm@LLAwCUNN;Ps;gHIN+*j<1P-Em09ktk(9$l(&{tcdvoJJ^ai%aA z3f8yc7bL}oBDqgIynp}EqerZO2bY+ZNBw&Tao3E+icmKk(xdzdW_C9QQF;8h86L61 zaTX0<-!-@=GG@l)MVc2~M(N(m?;zvlp7$4hfARQ>moHxu<m{A}?RoGeg%uJUUrRML zdNl}iSp@6sVF(zCq7z<^<Lx&Wziud?jTxB>GXmlpB+J?6K7BF#bEeft@7<7PmNq=c zP{T&Fa7nLGhF)GnE?!{QAYk`S7^Ff8OWhMkCuze;xghkZ=@v~jp@uXQ4yejmFsQa? zR_|(1umX%^yLh>80U4#64Z$JpE2hF4s*F)RtJoyw`;Zfzp$$){vMEeURs&RSPORE8 zMr*@=AegsxRzOK*!`$Va`><RP=&GDWv!Wd13b@Ry{pM`$J6e-(ozyse`%W<1&=R!l z+ciYo4iD>y-b}B%GIh*@wqSZ3r}Av}&6Vrv(-p+AFlC{O(o3IsAGgI418rz^j97`9 zo;<nR6%`k*oONAQHVy{g?s~F{r7vGuf!GD}A*iPg!C5m}3~1G4*abBQTxuaeWi12( zU6ke$EhWP&9$C=nn6-?L4YUx$6%&K9EY$R%9L3RH?CL8j3%XT*QzfOrB@X8BO>AzK z2*6O^3bI+Mur+9)mo21s=xreb2l0BE&$aGXt0Ix3I?_ey$~y&cg0y1rA{KGL?np^+ z+-b|P^r9XOt=%=~QuVN&f{YS_iXWMha;!3X%0{md3}wPrWO}qvJU#miO=?H6cUASm z#*7ZpLPZb^)J!RNSfzoAX$pig$b{_?jkf~oL?5e`q*GA#pbJd()h*>aF-}kU_MvED zv_wvJgq0&;zrTOT)tL2TW_%Fh8=U)x2(zD6@M=VA0+O0j!#5>|(DbXS#<PQ?JX&xm zOWQTLRi-#W3=BTPt$y47f$A1pO+BFTA4iFk!k%czMCRbXeS7J3h#~8z1K5Y<RYcyt z-Qt7%njQY~<*OGjw{C9HoWFd9hMDtuo!>PjCYO{S|M<uE&h8x@9q}eiZDyZBMj)e? zAhJtLC+C7pKuaPxLJaT5pDgCTbTMOy81dnCBWBN0pq%(E(1(Y|`NP`B$HympPEJnw zoSvQ$hP5OEt}Gt!$b5KP&R6%>Z{DyzBxltyW5t><_qj9FY+J%e3CN|Kr8azzhwOh4 zEVVC~dT1%Bs3IXI*}2$)HeeTh9PZUG5)mcQtZ2g%upG5Ox>b6sol>LyM&$}Xi+c@e zX+V@(ZqBHx6eyKmYso`fpT3L1;Ic$kfx+F-Yf2lQgVfr%6u|l0#x@3DFb>!y6hlqb zq00xsb!%~l$kW9vnq69A#x{tnc3!wv(K{-)fjKk~T_pB;((DG>@Prm(LUUU^!4b2e zHg_*(<E*b!Atsab$|)L*m{p1!Ofr1X`W?;s?zD(WQzfzVNjsbaHQL)ixhwS1BJ?tC z;EtH6bp|NO?6nSbtIjD{YM{+*F_ET28|*!OXn8QmlPN&24ZP2R7!k!~_9bFq`GQ_p z0i=8L?I&5SSh{E&ZbSUCM4*cjnT#q6Mr#SexkF9qo5OINlpVqb)Qr$k7to$`B-M*9 z`Z6{S8Wu!-+4rl2QUQ#Epcew8P~W5ITW}N?XAN}AYf9OS>KrYaL*RouP%~5(XF*#U z9ZTpTPLmSt<<0QVU$LP}OmeZI9R*Wl@&I=%DIUQg1iQ1u9ER-LL&Xu?3zKRO&0;t% z&;|x99!F#%Q#|iNJm2GjrtA%Z8L3e!=OK+hM0D@oy^OuI>*x|ty+Hsyj<l^m!O=2M zwmhjJBj<W79eP2D7dw!lsyQ4I3^H(ljK;b2OTj^8DVkB5*{;XnwxYY(trn<|jG!ip zOVj{DoN2?eX1qlW|2CLW3Z`r}q4u;RGRX|OYePDB6j@MO0B8vq*BMkpSb_!$)xMLF zivnSZPcAh*rjDVT_EX=r2zcRJ>%fa)b!q)qt``><yj@=BFW1@KYu|K**zJ4mJK=Z< z3!?k0SFh?H$I@kSu)MmApQ2}DeD>LAY<pfkd9`H7I%hE~UO+TMSvDX8dMs7y1t=Y* z9yJ(%p>hWCjcaf<YF>;oWuX3o>AZS%!3HNFS&Tz#4aVP`D18nBGHP4GND0V&cM5X{ z0wQZ^{2W{`)r??jeW+Zyz|lKV1!o}<jW*}eK+~kbQlW39G$o{ZC1sEvf!!$#F}tbF zDt#@E0w}wSFtAGt+9MdvfN0pCWdj+wm8v|8qkY>8MGKm!>1-D3ADs?|H>X9J(1s_} zkm;CyoTzs{k8pJ9kSh-Bsb)lET0ygz(1s_}sM$-i3T*({m2m?&I%Tvz$~w-X0cgL9 zT&<v4Z%j+G`hbpT`6iXyy%QBj0o1QSGp4z@aS71NYcRfTPapHH=vXxE+@Y`iQ)X=- zQR7gx3bQymr43K06wpi)N^;090$r4z-NNZvtp?t9D<(pZN-49PeVaa-+S2I}IHdCZ zS-kD^p!A`Ed?cfYoM7BCZNd7=-kPTEDtP`9e^yP9@e<8)$_={cE4wy*3(a)-fl1VO zcxo1ap0-z_VN$FB&rgKXSCEabOWC7$9jdDtAcLV8^#K%Ll-N6}OSOV*1R~Rh-D)&w zp34Q4yLt^Mg9WGU1z^^_Jq1%L1*0r7YC{{^iVwYBp=72kEmlUObrf)?i-AE5IK_Yn z8ne7U@<vUQ;vt<DXa=p{X{2daQ)W52_|Zxp`p*)|Kts|s^;;gTH0^4%F{!95(rRJg z0;((nG%S=#7mXG;=o)JY$Ps0rhQc$~+^(oxPsOQdsczV<7TAg`Acs$-M;XF8LC*qu z9x;kBU4k<g_b>(?f<njj5O5aV32S5^7jn#Mn3sBF1yHVb4Ww{7QZgx=5p$mgIXybQ z7vI=CW$$q`F-ECbeET<v(uem+ud;96#y4!~-frFO?6%@b;Wdgbx!BLNP7wX^@v%SK zfB*h{qEQ|)8m`!{U%&P{t>~XWfBr@C;>C;Yt?iSO6Qa#Rx~wZp9e%q82c4v3q_(^o zwO3-4*z^o@NiKPt_ah;nzj}Rs{`%$1^A|5(J$v@z>C@-meDjpg#l<C`*RS8?-!{UM zMC_CHU2$>NRo;ifwWTd#q?A(5!rZM&V^DurSU?~eGC`a^2gT9Nv4Fk|*Ue>=UXF@8 zmug3&;!J089eRV_amqBftkR3|`_?lNa6#iTayGG7DT!#DEZ8uLk{yOkPXt|ym5kb+ zFd7!QM}0F|F`aKg9F;lR@OMT(BL$Wh5S(w11|I~|5z}-Af9HCZK`*Q!t8S>#YZEL? z+<wLAe%I5SCsg*TVZHr_qEhtfN|<7K7&vh)tL7<v%#l2c22)0(u~>IGScPS`PKWWu z;L?VNIjRIL(Tv(vFnTA<(mIK8)QkF(drh^vc(p_@NLnpGU-;|+Tw7?_$-s)0FtRto z`_r!etH7d4S3@bKDJ3AQbQF|1E#t^1r3YM?Dy!oS10k=gabY!Jfs)oZd78I?jw%~g zjd1`uQ$-ot^sP8LGD9|w2hTWRoj5AJSJAsy848SI%oNHD8*l}x1xL$KS+7}o8!2Vc zkJ2TwjPe$kQLPvOYDn5}(o_kD6$pz9U8d|4tr?AjUPnghDkEs4hIW=rvX~?G<O200 zh~u_F?p;8+$k>6afdMj(oP<2h)E8(_YK+V%JWbB?53%wBY$bT5`O@WsF7~yJ=^D*? zkk?RV2x>BXM1WF4nUw)DFe#N(=&6SpvZI)354!ks@)*#i+Poaa(_S+gV005qA<Z+f zTP@V$lm=f)MQ~mS4yorgj01!VGLy1qEsKb<T*DNmMi2yoGgD%^IRVFM>N<{~vI>S? zL%Rmt31u_|K*o_Q&Ltu)L$$pbHWd7Z<8vJwPe)fH^!arz7K&YZaq$XA4B}{B#Sd$w zds`X2ECW4pYDsB%*Tn#(Tf%5WMvjWFub(`5a(#1sb$x|BW)W@<-O1wINrbOMpwdyG zHia5BS4`(3&PvLtZ|(XG>e7Hp;C&b`!xG0Sv-eqAR~S&5<=c^E&S2OI-gieCN8J&G zqQ%B)Vb*?qkfO{CYkMb%(C3P&ChDhXrcf=g{vHCAL~sLy^&F0h8KI5MVV0t4SL;Ph z-zpSzDZt%G0cboZ>OFlVUEjUJ6}E2`N-p|nC2QH^sA#h}EyRR2JfTu(#!`4>Ro)5R zt3|VF3hHNR7I#Enw^mcFAP#nx*H;LRPSFf{Gn96xXaKE0N1Ou#&3a?9@C8k~nwGMw zT<qS77AQlNupVrf<L1Uva<3fGrjd9+Z8K7kBMpX{c4Jzafu>!4&gp5xNz2;h)u3-z z5wYfI!z(ZyLRso%4WiPg0@_{xhOp@`>5x$us1&-muoUXKoO<!}!JuCvWHfrcKZ{@M zIt%$Qq9$g-tbDSkTeE6*gQaZ`6X@rF21lrXe(MZ@uEC2~<^;VfLMs&txi3I3>}fMb zJBok}#wsOaH)BCr_M%4UDxjobjyEoJiR?5X;&wF@){KB2$}8iw$ki%<(L~KEdIR0{ z0+nKLunch5G9BPpP*SXKcf5cgbPGo{1C<3{w9XpvZBojaJPZI|9$|q8X!TI`R%-#P zz@S2j^`j|Y13FrIQ!ssP3XE+t>KJ@=*G$kb^ytwe0{WaymsKS=W+cVH8UR82Q9Wf~ z%qbX@4cKjC%M0a@Hcd64-U5_M56X-htu&w#>@w8)UEcL%hH*WGajJ#hUJW&a^Xg}Z z5KEnZy>{z%Cw>i5evno6pPlVJ1%0P*Pz*>4(y^ULO_#RMOP7{z9Y=^NhXpCQZ`Uwu zfRX};j7(lr_i*C)g2($F=aDryguu?L2O_p1qu9KB`SPo;zIy!l@i*Um^Wwz|WO)Ak zIYY$fQgCu|a_`=Qdjo!_mx}{ID28;b2JqTRcCQ=g>C)m$-g{^F4iDn0&beUrDMX;P zTBnAF>yL|xlC=c{x<s~HV4v<Z5d<(}j(jj~OEK9AJKH<RZW4vq3E5T<K_&%>BEbhG z=ejtK$|^zSJHgU*kj)(n4z%|#e4RM!25tDgsby4vSl?V#4HT;D1+(U&3!A~wDH=>^ z!xIQ=WZPoB9xO?aSt7F__XQ&(Fu}SS7{pm4+ir+4ZD$3juzlp-vNx9AazmWUlr}sE zS<LPd0SC8@ZA?WF<Tfx&xu*@>h2}Y-619E?@3W6^f>mMj8CGBx9W_%%X?KbSMbi#H zlA3GN_9vsXZFqw2Q}l(_e;2c%Hg_*(<E*cfHfECa%2~>$XI3e$q{MP0y<BM1+%_hw z4qAVpolXPIC}|c0q^7N*zEzOf?&dhh)=7**ZO9BUcQ!miDT|Tg$hc`c&=*`bxodNE z&1?Y%{W_x|9R_|KziHo_buYmEvq-%r<@p{{LT{m3X0!lJFVy`YZQBs;PJ{ViAaqgY zYRu4#GFl&}g4?B3QKr=r1I-+r!lY=m*VuHWfs7PcXju)w1zBU};(@_HGH^SEym2Db zs}Wu7fuSj;OV<E-L#j?`{>u@t;epjh*s8%P2(rtCv9q8Hu_8I70O|$%!XOBwX1;D7 zo{7<D%&566z{138X)#tarDlYUp^SqNWo2QET08|{CMfX|Zua~D0RQw!L_t&qhwMh6 z0lTaW5Ut{H;2=#J<w)2+^Jo6dAOGWjoVNwDm%cJqI`vjqqf!R5G@}lbMwpW04tbGU zv|L6qwM8y!pdCd+Sxd?g-8z)Bc@44&xJ&C#@O*SZFr#3g3{s$^tz2sSPBj9?nAJAW zvd~^(7P2tPfi@JNq!>r1z7_^$yoNOfh8?xw4qWB9e{{&J9PhS#!fW^m%-!u=BG!#{ z7_O_g+dC}EtBZ@Tzj@00@8ic`ef8znUwr=ft1q8Cd-m+@>r1Xm#|QiOPLDr&c=oHm z`osLYM?d(%4}Rs7Pd>T-Abzl)AY3&3acHvd?(Bc>d*Az&&wg-naz+OY2E1VBO2l6R zTU9nhg$!~*&cnC29hDy*968_IXuCViV|RzCp=>rgyR>m^+8)?CI9z<y85d%?bKb`9 zLR)Ozsw9t9!yR(Xe{b4#tSPz^Q?Cy~7Tf~%a*xW{p(0(!w6TrJi&?u9F<EBKTCrkn zcw<&&cRi;tG;5!SG;oxX%6=9{Ar5Uv8(zU|YMAQL%u+iFxe5k%9eP(%1C*9DDXgyZ z=3Up4r(|1#Wx%mzwS&tCAkK$5+VF&$X%vyTGAcJG)-=JlNyEm_pl4S3J`ixjn4|Il zN4BN%ELc`>1RW#a92FMmHYxMEup`>=#`N(wq%Q-$MTEjoeY*)*ZfLC8sGWsb^stf& zxG0Q3|Lq`GlZKrD>#t*Gl%`6`thZ0^CHD`4F)6@pW+f=S9tv`iPVMYauBt|}5Z!6} z;&m7FtdeFt&oqnoX8YIw$glOe$&?dp4}W3>!jQ%|a|hLuuID@kv>r~|@&aWH(9=~I zK`4g2H*0_f>`r;~=n<pw>N9);#B>bNRa45$ANMez>oXHJM4)xlu%IJ)Wk>Nc4(SlQ z1~Ezmm&H0Y7P}1D6=PPbriN%QE-p&bL%QA)cOz7tjz*P3ooU;QF%#ox+_%<=oPnD? z0`o#IH40|2bx2s-CUtoc%1jLcmK<*C%y<Dx%|M$etag(IV+Hhmgjj{Ft>#5*79wk@ zO>Hps;hgq30vgSDtdF|8-NGnchSVTy?7Vnks3C(JO|!_CXhUn4p&m54Pg{2~#e0A- zCNhvJ!|;CuESV80whj&sdC*mk2mkA<!^8Ne%g>&@$cYBTA*Sb`(bSX9M2vb3!V(a& z%*Aw6_AOo*5Q>&iCI5*(@h86i`s**h{E~%Y#Q;5<fpv~R6U-7>m-AAsLf-<>j`Hsw z6CauQWas4i=%bGiNW=o7$I?TfJjH;SwoOW*=2bzAv+5eHy{Iu1#V80t98$oT__SX< z{wkds|MtKAzvk_9Z|~sAlP4GFm%sn}zyFh;{QsB{b7E7ni}4~d?CiF`kGiu<%WG#| z5_5gnG*oqZeDvVKqqDOU-a{E;{jaWLM)7NuPfm7r<BD{CevaM^fDHmSqc6Yw`tjq( z&tG0#UB|!Nb{!z67+LK0<ZqU~J=oj7-Hrl|j}O21(Z>%T-6#0T$uTiGSg&8dzI+pZ zm+0-=OX}a-J&HEJ4tsg|_Q|uS7w4}j;Pu<M4&3ISGhq2+O>efhwyk0QP~HiW(vp|j zkSUDr;o+fMl-aqjFhI|`hfl8av>kP6i|G&x69W@!c}KWUri>C5ZoX+==R2h~WMLQk zT=_WMbln*6w!1!*5{*>1ggRf0R)V8bV&5)D=-Vm%c?W2;WINF%S}E11RZv6HkJ?pZ z{C>z*cV*BXkn_tmY@0ZwH}PkjxqxHH5QjKUO*AFbGFlogqFB<ZDLrvg-~NR{W?q1% zjs^4vc6-!BaVy9e3oqlaA4oxVs0irkYCu;FEu)?|fTmg~J%rnEAl!$uXa>mE2AryB z^sOOUvrnN;T8(=zF=j8UI$w-m#?{t-(?BBDaPQ89Eh9>Ah-A@TOBTWBr7}}Vt1@G> z$pV6ZhqgwmWu3WddDO^7i;PCEDXtGhg2e9bUfA31TaQ<j5e}*Er{CjxYTUPaRo52K zBUiT;(7aO^YSJ>LuTUj`a^J3svua-P14o@#pHA!oL*ROXLsJ8&$pXihmQgI3yC7SS zLw(D!R+f^RXRaPyB5=gnB)41b@BIQpgcTkg{gO8VmK;6=o=IN5ILC`!`t<2j4A2vb z78l&79PUQ7MBuLKjg?IZ)X6Cf*x*jg_=^swr@#FV{(+9~Nj%8<6bK}+L}+te{yGz7 zF;(0U03p__)AU^zt{hPUqsF&80y8Eo_*Tn`G>ajTVS)91{`@&lW<Gm4q>VJUu2fK8 zn%-;#1y}>q!Hg6n;-SYZxaVwQBhp2gAw$V}V#)G?k4<a9r59*pZo@>>K;;^NGQERx zk=|WOImOXgGU_5!ubF~@d&zwTR;UZ3IgeH|tK{4MJITxq+-ZsCLTP{!nIi=XIT(U2 z2C<A9QgA5B8tyl?+DF8sEc;QE2oiNHhhl>61hxUK3!>SGa^D;_r`Zil#;mrTiBy3N zM=55w6LnINnw(3RQ5vr{2u{<JE-hoLXOe(XXq~Q`vs^m3v$$NE<tf#EtM=!gfBx** zGb%@)MFx}+Iqm`}nzW3|9&c0mJC=Z47?)sPk1RB|Ik0R}Vn$kpaxcxDz{Qmmm#YK= zPQ#wRzIgHKCA;eA`1l7u`r#k_WB&?8wmO+w{sp7<a{xRXZ}Zu@zGajb#l84R;M<+k zqm#pfqy6|}MqJ~zj}8vbP7WU2J7o(T9PS<+AMWhlUR|?$Uy~gR0&#6)F<-pkxIIJQ zhV<EIpP6HGsEQ(%D-5_<UR=bH;^+X=k7qZkq3Hau!!X;~ile4WVHoC@Lc6@YCrA0) z#oQjWZe3QGgOa<cz3`)PRIfFBi@ovP(eJAdUYPr^?ZyGJh`U<BHM|pjSb{WZHD;OO z<&I-VK;qQpy18x4sv3wad3gv(WbvG!Y2r4XX=8Odn>e8(%S!vMT|h4LT1K1pgl655 z+3&n1%tAV3+*|Yk1G)m((5BOe#Ne&d{S!Rfq7ARbI2ElA3-4T<-o1QdP3Ig(dhA`F zRmQc>+JGzEEbamk#5m9fR#P^3DY(uaVw4n?SIYKQHe!7WWA^QaY*P8Z?6|_pERL|+ zqy3P3As!yIoZ?x44RRj@UoisM<vNK$IU>+S$xwvrHZY;89Vr!NVXM$$OmH_6UFs<% zDDcR^LxR!XpZ24zgeH?qKnp6dpar_*E+xj05gK;2L?8lFsz(RFz)^{y0~w%^fm`Gn z(pLe9M%X;R+Lx~!G7FR?g#R!LX#+#Spv^3fVw{s$%%a?#jyC;ddjl(650*U@r$$ZW zD2%#*nR!JogCJ<H4a)Qgm%i=E7z=7I8V5mTvz~wrv*zgVFi{(tytv@&g2W8-D~`MX zqnyQPpsZ5pT7z*^(k;{jX4VWDtfej+G>(qIOXCWd-V0-7f`hU+<O(o^2HA~jK$W&q z?)r+F^>7MM6~?Z1Eo?=I;)az63IK-GBXEFtKh%q8J`pm6837~55Jc2qjEs99u=1+u zTj!3T8CmixeFsmUKIMu=VZ02Zj09`<)q05Ew?ItNK~0TB$H&LanvyUuoi=7)50P!9 zpOg{kq72hHqNYUmrtS0vL7?9=#Mi4}h>2jz#7>Tm@1M0lyX7cB6x7i2&dJC4V$F;q z)8>IV_O0*eaQ|?BZ+B<w>docbH?OyEZ_of)L8iX!?Q9<&>>VAjlvH!e=<(sf{rmSL z&0V<N&hOL?sSD<d(j(&Zc|GQ+VTK+9l(ZUTq$#mn9}v>9$m~*12MeIf7IKw<VyMl+ z5CE^f{X+<)HmPG)DGt#VrR-;_rn>#~%LP~~aeIR{cV!eGTBidWa1_YZq-C1*`_acS zFIyMbA?{d}(2O>~@}TuMLl<+A*8-?S{gmeR-qbYhw&=t4-^E8?RcW?4IiYoo%*YGg z8GAIF#R`Q8whAM9%Mr8oC}S-Wy0)SckTYAr5~*zcE+#`z8f;u%yLY9Jqp*gNO<&df zGaK#0rua^w)LGi_dlS1MK_)DFAkXYZZ3ztOT$_bcKm%<I1-Xf4@FIp~xzP1`qB}Oo zW=CeUD$#%z%(4m$D2%g}2)H;SB6$8Xik^qn=g*&Kun$0FB@K6RpGSqR3k0MG1T@_E z5pbh8%XL&ub-~aqP$Za~sD#oCR5}Wz@S8S*3@91W%+x~VenXs=#}O(=gPDs}NvGh; zD3(sJY3Crj&pp@^oEeG1`v?|>jWoN-cd$p`t9!`=1ft1E-wVBLgyxf!MnQWRDf_nX zN=6D?F*IeSGOgy(5|A}!HEIY=JUkBnZgUl7-?xHnSg6_%lt<_S8i0;Xn`nvBBZ!Sk z?U7k(wxYXBclBy|GzKQftThHV21*>8=>RT0Y8+aFHd$bROfl|QsZk4{OH~+nE^7c( zRZ}j#T@5lus~M%C5DK~|OCGhe=)&3I`HO67gWrh?*tcLw2(G*>@4zNvMi@9Xx@u-A zGcYn>PaK3ckkCchIume7*D=JGW;b9-=&78xSr4$0coSm*IiOFTJo&{he&Im`Mq@sU zbc<)BP~Non;QHP;+lI2;JP`lZmUMAn!!%z?^A834qfm!O`)6lor)S5cJHL4O)mM*O z=#8l&ZHxaudw=$-+qNzCVY4n*y^FI?A?51k+98ENC>XzlK>QGg#6dA6ey{_AOJrM* z64rJ8jzDlAfh44cJm$d&BSetwTwjDAj0prk2wS@6+`Z4*d#yF=I=|L_eYDx<7~}ia zH`ki`oMXwq^PRq1Z@pE$k3On7=bDqbuoKu193v7%_E>?q^<s(ax#n?9j~^G;gx2$g zk|0ZJ&(<h0L!-U)Q=?V*U4xpXWc7;}8Q7gpEh9Y`Dvd(H(t*pU<?7_3-luL6JJgqr z_Q2t5Qp!GKu;D$9>?_WxCHLz^%qH#8K+N?~n)Pr&wiOL#6OG7;-d{lME}^+SoYAAu zQ3&X%O7Yf@fr%&vboueHjFJ_|u6`CR6*RULl^THES<1d|n_FU+wih7%+WM4UrSjAm zFs5zVl_6C5B72OM#OYHP*mIO?gBi#38hMuHIR_Cyq1xpv5BN_Kt{x!gI^FLRmFiU@ zsF_kjIzpbH59sx}5VJqfC>c`F5*ZM*F@nB;9A(X+nX;Ayp+!dU2H_}5-v^(BxBz8s z<0W&RT)9BmQL16IH@0+Ig%J@t&B|D_UZ4dn={jNVNqGjvDP+=FxLtu2_9?&>)Xd<3 zhSuWC23fNyS{6+^H(w2`xx(UZZOv!_MiYFY4Xg}~v}UyCQqGd8Vzh62Vlqh|(6)r? zPSFdnfs!3n!`AX?1G1bMw1?JDYJCjYx6LAPC4nQNL0Jm2#|tpSg{nAMwW+kR#ehBO zs{$HEsUJZ-0^}_37oQ;na8y~;fZeS39yQf2!OBVMd8&p-x(w4I^k9j7d{rs`z>kis ze?J#Mpi4kp2!b3FTVY>epiSSFfFqH~OA1z!8Vu_YN`?^1>#<l^wLl8r@rVp`kx9hV zYC0NQ7@Ciw%W|6O1ct~}ZPPydP7zR>?T857vAMpnn<o$vnC828@5;>hV0_rfpNB`k zo-e=5mliM91UZJ*H*fCZ-`=2EzrDM?y1u@+yt}^HTwC8^v#)Qg-Q14!bT3ZN-hKZ= zrg{X_)1(245oMKG`2A^!o?}Goa;g8ZVLeGiOGaMKftT~Mvon{@dNkvrfu&XT?e8G9 z!U(;rFvX#?ZP?A}25EI~pr-VozI7gkf~H-WK61}AR1`NnppW2?c@_x9wx56zz^+Mw z_#=9=DYz(T2D+3ZXz*#YnNP6VW;CqBC*<OE$XQ0U1SB$N4d=xupy|Nw=hMP1hGXqa zrMXR@!YUGQtoBiqOXN<JjbEsw^&%tTHlSG>NYt>-b>%_nq*!Xb9tG}ZCz=PY4a^a_ z2cnt*>#5^jtKHmI2Hz5-SN`r}%~RU&6Hx(6sKr<5`Y+iJ9-XLcxT}hz#-T02XF|df z6A<XCGzda3V}no;kR$G5e5a)(t`+zq6U6ux!R+y9-u;51&m?{TH3}b~>jRK!c(meX z56Cg^{7N2fG0U8i#VPbMX2fAurMK-JB^)};OCpbuNhyP&a?DBts^xK(2NCc~xo9xJ zvgTzM+!Mw@rZrS#U5t-AI=VQ{%g87z8ZsJcU{o`}MIzQ>a1_J#FiLQ<n5cwaHjbJc zX&NJdO6Zje)hZOtA#n&H56k`68q#ncY$yg}TDoyChRtJ<P8OLJj@(JQwqn3UMboBN z)c^<;HVyA_)FDwR$d;kZs1pP&RVtSyI8<Ojissp^k9$BzHSUKDIa6w3SN#&orUH^H zPl5nh$moWoNNoVYnrV6)gc_v<gNqssnkrF=fESd|qZx(85)79bPF`Op=rW|uW69~> zFPbfwmpQV>xQrm9B!#3?JL%{$s(uN&XY9a$#u1eoPtm|u)Z<d9sZm<&DH2o`UTP4y zX8OySD+0>Oavv^1F9uAH*t9y{@sb<g@QkCwF~TgAxsyr9^$;_J`Z@v{e<}2%h>{Y! z#LqT<!09w0K4n-ELuG79QSRfPu08=~N=q5Exo0Cgg}r(6=HTGK+Y`7xkWTHWRjcs3 z1~o$opnee}1G}@cV`!w0=!yEG4Sy1&2*y`X(~oil-AkfOTMrv_apd@N#69SrMxPzr zGoEN_fV|p#l$g>(+Q7=_MFEyk6R%3D#W;0s(LN!Um=TbP#@e#NhV6rk-PMWu=4itc z7-DukdF8nOw~mWw{*#O<o6*wxo5L`11rEW~k)c-Ha3C<iQsc652r|I9LfxBcWr(9M zEwUMr+wg=wZ-G7cajt&sG2K1r+;Hj6(mdzDT}oEJgjH<*$-tvr%hFb}1Er&YWjf8k zs6ula_M1xG#jaNm%rwwmrDowgT;&*L11Nw>NY@#tQZow15rHnzY}FeLnSI5h4#JZV zs|jSKHAhaQouxe}-QSSY3G5O`7lQ&_?jk<K^h0`)EBzV{3DX1WDb(P_sP+V;5+69g zJ664UVt_FQR%=-22*_E&gWY3y7F<Tg$V98)$WS)e_g!!W=zbLKMK1)02v~_^)GaeW zZ`U}qD%F<~>{i<gVnD#fu5l3Ps+^@S9#}4p4*LN)k3-ynIAmxTB4A%YFDr;c;yNRc z$TBF&$dYB=Q%Wn>k=D@)ZZu_3uE<!j6=|uN;sFD?JVj|B5phTa$SB>$2<VCFP}zXW z$U2~YIi|yyl7M<pqRBxLaUdAte7WWJ#3v7+<?!UUjf{bZh8A~95@T9MQzdj!*2)kL z5LDWoMdRLu78ffgtV@KzSxoyVsFII+u3A1@92(}iv$MCqzq_}G%w+gjt=XLji^6ei z;U-`J3e|!Wsc42m>F5*;pmjRb&q9SP2%C)q)T{^ANyst1y^DX`OEE(|ZFrzG{HMkY zzOlWtwz-jEVu!>W*5fyZpPrvz->z+J?W}KZU)|iDo?r4gzr4P<x}nPu0-7`abGN>| z9lxZpexub#Kbb!NJ#yq4KDjI$1!hbsY~1aQ&HBzW$I}B#fto=E`f(v6t7k5c0%r=m zc=3W4V4m>UGpspg9wv-k?Y{jT#MK@#s}zT5i&8>A%~H<7TDe7S3w$2+(W?bTvmmK9 zw6U@C^psxi(d!c!xmRr}qt={qTy_(*i#}K@P-1;XWb9>_QDY_>SJ>R2PQ0dHU0w7A zl+`{8&J>R<awHgtqduokr>7w%{1EkhmV4zRKjql7tp2$zjnbp(rypWtjF!%$ma&4E zPr?wCF)*sV$MLZk1dI%AU;!fo9BJ9oRT2gkKfPgn6r+upRsL>5sk5}<&xS>=b*7t# zE11<U*$*5YMm3|07rsSQJWyS|xQ2i`6J@y@N;4w2pPxj-xlh^LLx=A41Lida5CL;y z)DQxB*-;2SB|Zu95AeJqLp**C=OOoaAGsi&^an_f8^wVkq}EzJU8X_B*o#Ajnpw1m zIzrIKx<f0JJuLMDdu3ZQ);bbIjnOjdLOj^E7?X<?+g<Q)2vPctCRdfktkD*34r`$8 z1wxquP#Od(U{B4fK&dcthf;nNjV0<B=4%aV+VF&`zht*BU4t-0mu-fgQS=$F1?=S! z>aD@9&;<@qPZrzIAY%l$khjd#s1(mb^c5B}jwxM+^2})eERe&Uv4hCe9iu#@+HX9D zJkMfdWC>3Ip-4yBE-&?vlv3O9Fii>;MzP1hO6a2Gy!Jp~?<jg488Qf<f!4`miUC5* zc33@EL(38b1BEod|B8TT3b;hHSX#-G;8lx&Is2Gt{J6;ZIi&&`S}Lb7ig7^}K{VT* z8ZuyM7LiV4(Cgk~!OGMR9N*?J;8zL}7&<;ae)sO3DQrDJ)1>Gf0*(c<CwRQo#Wnwm zoM<ktuJ6`2ws-e7w|A~?ZcooI&bb@h-2T~jzkc`O2$|1^<CE{+e*f*S-+uS&w?=yu z4+~@IqN>BgeYOF|qIL*llt){W0_2D8KNhUd-rnB+epH3rv}<cDHJqNFo}Haho+WuK zru=3~eJs>GYCjW#RGd6MGqYAdqK$nLy?b9kp@HYo6fOvyJN*&#a-{EP5_22yq6f9B zm(x#VIw>G#la_+7GwrV@Q<`;Ry4j>3#W`AArG{LCKr>L^I-gA+xj;z`vownp$f_f_ zZLvy_-f`qUg6#oiW09h!2c_#=E-og=SA)mW=T%rvnU&+g!GXVxf|96&(~1itmq$k- zX0r0K8@6x%OT;5CYFJek+|A&qOTBzQ<i+6r`4;dci1HMMu*9CLCFqEfM2sSv)MynG zVT5K=xFlkaKvi6giBA_L8U$)XATRrhA-XNxXS4nX|JA=>p(G$Qxq%|M>uZ6&Zy7=; zmjXRX@E8a-tPx>rtzBhWvd|T}g3Hm-k+Not8i$$FWku>p7}H|_#s}@`s#gh7P(JSa zfJFg32h$>>(HKT?j9<}I(ju2l--4EcQji@*uC~y)7iwORCgB3yo0~Q<4lNVOWed<S zM9t16{qEE0SfF8)bb!D*t1%Q2+z(vZDhNs(ZCO3c7>Z=WSphsuBcs==1mX}4bVq3- z^NN;IhsOBIfD5A;wH0q1_7AfAgdr?Pj!=%0c>=perb3k?2&JH-Es)McIvS^Jj0qZ0 z0~%!3mKHtT(Mp2VR*(WSEdc{8Jw_V46zI}B&{DXFG$|pnHhX&qwC07VHK8gEP*w|z zo)NL9HFED_9F%<v=y`L)=H<(mhlhtugc~PwVHV}9u`!t%t;!+-4a*Yp@C8oDk)VdO zCzb*QFc-^4LjknqYfRkH(_I~cm{-}DHDt@E!GTc)hYB<vP-JYr{qDi5=3oEAfAwbV z?#=5jzy0>x!{;yl_>cei<oJ|R;P@=w@b7M;?Dfs~355seS1y>`-o<reXS2RW6MuG( zjN5zhr*840B{en#K~M0kYsC7|hZCY98McH)uoy(kJ#x!C@0VY`dHLcwM}ap@G#hJi zny@iob3Oj_-w*G<rv~<T9EdzwF0XHx?Ac|Mcbk9l_%^@G;$K``^mlX@v8Z6yKLQVT zF1l_lN2hoMr)<U_U7o@CWG6n8qD2|;+n+KXqXG67T!Q*XkabqI#(_m~=4X}HXIg!G zVbMA))Gx}LmpG_3M+2M^Dgi+~ttYZJy|C!~<!EZd#H$5%zVQtXD62)OK5avTCG8Xf zYAhN@o5B<gH136+1=m|gr%+E+)@3nNo^&%z>(`g{>AQVE=#`_PS*&*2PWfoGk^7>3 zyC^>AFfCb3RKlWt!hUPg1X2jHabSCAr=Hj8dg;&r4U|2V2g7^~1$I4NcKf!DW0)p( z4Mu!YBXBw(^PtNmRD%(<|66|uSb3or`sYu&`UY$F_63?nusD=QmP(YXa_d*X)rej0 zQ?xBrCpbZ`$rz&~EbYzpe0I`drZJ!~PW*v{A!&pj&}Itjz*ZqI>AW){qj5T*W4UuL zRv57;zEHrZm8fjEFv|AM{JfT+rO-8|)TmpCNij!nPo&`3(K^I7`|7K&u;&Q``(OOx z7jNFY!Qh*(zG2t#wDA7@d)m|C@6;~(>E*5bBb}sn8PTv4fYc}%LPLv&H&fcb{dfOv z`h6~&`}=$3qjWk>iRj$br~{4qY3myG;DS4&OcD^Zp+yGeLQSC(!7U|f1idz3z{+A5 z8(UCGYZt<8=qjXBJ7K`JMzHm$(_*7>x;EePQm7WJO0*Q}S2JoEQZCTgq8Gb@Y>HA^ zFiN|?5R80P&cbL+CZ}NVnuSB8sQR@pFIu~xK}L$5&<~X$bTvc3vM+uFHo9O2%AhZT zW}v0}q#}cJVUwp-TP`e7YMfR<#7%m61il7G*30;WwX0dC3K&)6C|&Idq6Qf4!<I2Z zX&jZ_m{wyG<#<30yWu?Om30^O$$dSopQFsnu0d=a%3x!>m;kbt;Noa7g7c1}fPfh` z7x|Oe2zJqzV_(A*GL-=?1zjPaLT{t2k_Ds^>ZkP>K^(0_n<)mFQehW4f;Lhb+X{=2 z<BfmoZ~c*a`QQI<|DBz!ZQlRRFD|yXc1})Dc=_d?bm=8MUklea;vl-n(igPh;k}C! zhq?2@dv<nua(;Gvaz>~RN5{t}r+iM&&iVhz$?4VgO?<AdAAYW=p+#H`s>`hvPab<a zyU(5-9vtj*hs~k8jVzIRh|HalyYJQYW!mSBFt5xcyuP{S1)T}S4_4Qb<^0xt8UAcy zZ89)|TPPA$stFi0=^=PF=^=~aFEGEiFU)AWI__^}d|6wFRbB8Rw<vmlo|cd!^DL@! zk$w~tGs%-OCZUotL^CKC1hG59XayQAU5DPwQQIP&?!Bgr?4h|#^uo|6R2b(v+g%ZY zWS()BMR69@UwT800*;i^bf3&)Lp|2s^+6c5wQf_w?PE04G&Yn^)U>%h+dT-uGfpMw zK3Z+4p%Ln*_H~^{!)4R&%95xoN7Q^<e}MQS7i|b-SM&|?&sI0>3J^b>@<j7oqf2m= z(@=M7?G`+06|je1nZNLHhS9o#_Wf6d)ksrKsP#brEa@^4WRwo|Em5<592U^Gg4}n3 ztwcNI3PuJathsfDu9{wt9Mj7eB5g=v7WHl|pRSPs%Y%c1o9p=XOlN0j^+czEzP4z< zusnRwVqiC82bH(5`&a+)52L=%X5;0{m(QO+=k=AKOv9pq6025GPOlkor^SFxKx?6# zft--lwRF1u(^!EXm@w2rsLykxfv>Ihi_mujO2C~%LIkq-g$;(#04pFRm*c3lyip5b zJutGLB@KfzmNtzEP9KoVo;V6<G?R$C0PTyW9m*gJb0-V3tJLSkhK%T8nkeJ7lc5U3 zMt2XK2CTd*fL{9^h8)cdZL*P|6ABCnLhI&1Ad!UgFiOA*Udj<FTigja#(WaG7)!a- zPzGzW2D?y0Y2G%5aw)+$g?Tkbn6&|v1R))PS>yW9Wz}7HKU`aSnT4`WBb$hYGAyVm zG@GTLMK6QhYJt2&BN2j^OOzZ$+Ok|kt1M}%&IKir9i2sErc7#fyH^0ZC>hOJhPyV# zoDxemM`n0XfB|tquC||GueX)5VU-k$lcVFq!$Z<>%VE*J{_-o0aWBw7z9Y6z&-&UX zpX<BZ%bV-di}Rz?lMg4SM@J_oCugU;RrB7->+a1h!r8^;$=NxAKmUwSAFie?+{(1# za#`Yp%&P&!WhcMbANqA(h}-uE1{>~(?W>cyobE%8j-O<G;kQqpkXHSKHvCC=q@<}P z%np4*UbDDY>9Ues<o$N;qcDOPQ<`c*bDPlICg9?w2^lkH>T%CtEn}}&<0y<SYg6=c z0m~6DM}PBBLz6lv&%&lOi{BDfTQwsrLW3zxZI(9tqcNL;I^7Rbn#Ica_(T>jT!2h` zTB30U<8%WAx)w89rP&I5X6;FeUeL%V)Q@|UItbOI3EF4cK;;r@LF(+LNR;W_Xr{?* zYHZ>h=*|MoM!r26_<j`o*~lNI4}$CzKAQc<gQP`MEj?bW_AG69jtZV@79g{Sd2BmB zKS$Wv*+JkD4ml3%_08SQEgzpcHrKhK$7f@0oliW6ux1?m`0XR{07h^M@YL|U=yQQJ zu+&d@ecpKX?AiYQJ}F5++{@vYvgTwP*fnYKp~VGXimN#|4R;0xqd6$s?a6CJJlvEq zU@ufC>Wv_Mx0f?*%LT~B!NyWuXyXGzO-i}kM{T5E3^r2sYz|;e`W8mULP^GfHr9={ zez$a#s$N-;HJimy(E8n?p`-wClu+zW<!~5WB5}HuBh)AhTZfXa#)O)>qtQ}KU1(E8 z`URB$@o`a)T!)gOUJnR#RgQ?Pi!THwQlM=<!+z*B+O*Dq!GY1<7}QK@!;@+qH7WEO zCkQA_=cq%VKr1T2ZbTm(ODTq30$bWckBqM`mcG{N-nYP;7G|D?D9MY=*@4`r*0={t zTS0E7Nk1eb<JxS<KrVI*prHWIO|dr3rr<bBB~k$GODHT@eLosLd1{#5u0sWD`~2|P z&erzx!^6Al2fs|Nw=d<COx{LucUgcg?g;%NRQ!sZNdmi5+VBLj<@j)+%Z22>y!|5R zXvQ=PbQHQ_{M&v3cye+rg4UnVh6jUM4TUM1P2tFnMn|i?B5~M~R@UOmr5UYEAH0Q_ z>;%wYgub5FnoVKK6-Srl_D_WsE<rPEgQi^>-B+ij>9)l3I5pb0zeTc~8QSoKHrvVm zY1#>zJqn_+k@Cx`4WIHEBA}<6ku&p5sY~)Mvah=pJK2Z%)6>)A<6{k0$CAJ<k;U$m zW<A)Ku!u5n5daM}M~Dt>KpU{zhC7!UwX4~RRM^!qua3xekt=l+k@WHujX!~ruLY<a z4b76P)ixoN+=eG$Kx+!*x_z+2O8|plbFjDX&nmMa8KpcQ1?jp)@xlxj^#%cyw5H&} z1A|&yl$zN-2^;U;y*oNO;`Nm}C~J3j_wexW`Sa(boTd3qpio9BnmGfZsGEtk;bHAs zXF!cZq8?g**y5$>kF@K!oDA01ZWawJdy1o)^(|$9ho^5X%vK^tS4Q6|6l!FoshP6E zK$lUnkdy-lj;gFOmOzAx*;E5)*rRMd5)sGCXxU?63NcZiE<*+tUmSJ!<7nAv$ig~j z_(pR`h%CB88_0mPZFnfDbtY6^R?H(s7iBKz7>3L>MPEQBJC?eTLX9Asw+wp7TlN@0 zxzMV&mEK^4^=Pb_l>5ln;&Tli;3!}zy0_s(Uui}YjL^rK%GCmUfC{<num?OGBt_{c zq+f%fUZ_?9nooM6Byx2}qa<Qfi~yQF6(%wxsBD=Q6l^Ow-s-IGh>Npxudzhn8vgd} z+XvA$;!~Pg9KGX(eQk3se)M>AV||Oy#l_jx#rgH+1)rO%OFjr_)^2b7#Ggyb&qn;P z@#9}aIdkLR>BetEy}rA>;yQL4moi4;&kNT#t8e3b*A!UWuhpA-So?o6a9%~zPM959 zv^|!<x#sDHOib33#r!R<XHI$^N2^t!a)|R}xCP`T>i)%5Wzn>YX?6om`%ew7Wa~^8 zd`fRn?GnQ0pC;<NN_A$j2z1$^aTV*HLzG=5$wSd-;U+ZGq?smlUL!L^<V^mX{(?@^ zE{59{6X(`u!Bk6^LUTPHaW{FaeXB3Y1#7h7l`*M~graLeyHYa3j}2L@Va0Sg={9R+ zuse&R&N?5O0_2N}3!dC~e&aQPV~PMJ_)rHJn<97P{ZTd!+f^Hs8ZZmGC<&{*HKch! z_eqG~_6&UvaVbaWGYe-svxPeC343~aip*&9Pw1-bX=B5a4Q=ZWL`_+h#>j0Y7JwNx zwk6O4qqW>#dKf~sJ8IMW-o4tWX#h==2ANjMJ`ZbrsiSW}Gbqb~3T@dRwxBVXPOMWU zvLI_YOJ=yIX%o7n1NDSrDbgy?MlyMzOshd}mQFz*6UwplH3SazZI6~^kAd^0Wnn$0 zy#Z8ehHBK*fGo<i=`@3hi~xE;DO-QYrJyELHNv?w1~o;~4j5mkL6|8Zpw!IZ%FxTi zEZ+?CV5>Bvu8iJBS=#Udybf{{@S@9(<y_;MP`-T&UN^9*)cB5m0tFoE(LPIV(8bbf z9b)=fexpWhBg#W?VW`ecskzLOnP<SIAeTwO(dInBsLD|*$Ob_e!DH6d#U%^4u@*mL za(!`0EcDHDNHps!W#e9Az8pcY+hhH#M$rax$RLj*e)>AHw=Yr<<mT>nXY>B)EfWSY zocTjYkjYC8E!J<GSll_<@XGWqZEi_Z%`q}C?;@Jfgf=`}>sU_~ljH8_V`;G-UgBnH z4ilWz6vH;7tW(s3`exl-$HdVk5DG8a)_-_Jemtyp37R>JC202f7^;t1H7r7dzWoHu zIHe7*3<b>6h9|T%-DH=e+3M`=?ePM@-Hodm+ur*iFvMo_vMKJp*%VdYlqL4GX7t`l z8PuY|>g1#YyRlM<-6>^UF3Zv0m{e<Il|34RmSDFH=b5W88daF0aqD~r9yOB^&@z<K z_pQPrH24I_)ug1Ntr)ZHO9s2MI5k1;4;ecRH0w9HOVn>g;H{9m4EGx2Fr?mqDDkTE zg03<Gp)ioh^hC5Xla>ldNpZZj9vvMqMphG7t1t_5AP&XFymJoP6P8hgekLj<t?n5; zSE13&1#<EVXnLH2AeUu&H-VObjCx@rJ`a4fxR7_2k$bf!5;P@PaFq?(I~OQHdYfv& zfCbeG?vj4@#tLX!+yTv|Xb-KQU{5Fn;@A3<l;x@;!YE!@R8*CIZN5gcjojVrv<HHq zM}sdL1`P%^9nsh9P)b@HK_S%*Mz!~i1pxyy_M>!T5p%1k6l5vcuv7G{?7D+4quNk9 zWIIC3Li_Z)r;R;)p#qNuFxfgTG24V9<9Fc>-_Y}$dw$0*-a3YlL#-XQ5LliV5T!z4 zd9&cvq{)ozRttt=7F-!Qc40L9I0+#4?Fg$CHNCNVS7{0<TsokOi%<_<2$~_#T{7QH zGK20@%1Z%Ap`fyF!8!rovMhf7^Pi*S5r@%NuU;Y0)r<%gBsA;stCjtz6z!q)2jUBv zTN_)O>$H4!wl{Zow)S?n*Y0lWv%Ypad=_FEvpCAy<{8-@5WO-pL`lP;X%|)Pb%d;X zT=qW!ET7kC$knJdSsm8aQ2HXf({k_;#PLWtj;j!JdknZ3pImC<EE=F&H5gy)s+TNw zhKe%^<>+r7%NSuvvsn3*=J^=N(xjn`kH+cEXqS-YzeDtsEvVD|Fr`_nj8|*~uWYnr zBtC~s!LSG(Tr5YcG+SZMtbK(oWp0y4@8?l)SyB@A()u661))?fJ6?<EqBICJyMfu% znDvtd%+mWKWsF>AgD=MjI%dL!8J7$_A=UuODwm)!xPXG(h9}famDy2h_V)I8Y=iy% z_?hQ?RJlgxm=aC!!dS0z1T&VUW*X2XCeMW7Hqg5m;q!?<KSQS4f(2bI6so%fD`Wn& zMBub%MJifMv0IDg^AJYy1udZs4BJ%fx|*WCb-E><1p{iMC5ySR=fMkjjUTnmXV?MK z=jy3PH_dt&60e3u8y+wVtq`+G30;@h_0iHe2pJ%lEnr26gF7iqgoc7y3S_9fP8Mc! z8KfUV1J>_?6Bf{5W+Gicx!NhXHz_GI1mh!Q!UjX=Rhkz;V_NK|WW1S{DRVc;<AN*1 znpnS>u5dI%Hgs#l!^*VI+>{;F3o3%q`h#L9YJ+m@1<V|slCBTRFup_DfCn9#-Gn%c z@*M^*f>0ipmnGj>A_WF#35NqO+&Mtb$o5h6F4j<xt6FkVo2zFl)=vS>7eP&nIDr(i z5Gr#9MpkZa$y76iIxUq5P1W(mS8uLv*zngUXUALH8~L{!?$-TkNB)R$ee$n7G<+Je zWr1ipT1<8)&-D0<w|m=L>v`Ps$B)<ZH#~2~Z`$72&Mh!)eXs5#FK?ry_4pzUp6phC zQfh}eY{eIY*ETkp?#*3%Pnd;Ex7blpQlgxZ{tJ&2aVO-C2y$ee(dehGL+<_ici_H; zN1<;|e}JYmx0PvbLwTM`;28ndOvc!SdD)qgk>)XisQIYNk4;q~7GqUYw0T-AU{uD4 z8eMMoyUb|yYSy!8vpOdyC+Fwqb&An)8Rt${XGcbDPyC=48if^)?9?6&TbjIa+sKT( zMS!D^qJqncC9Q~eSW;LjH4~rnw+%ncZt7718qk*IDixOTXVS;X5~521CHL)bfJ(Pw zMlGkb;R&v-2FQZUyDqzn2Rwv>g98M3wtv7V4-Y&!gv-tShUAqH;(=;ootyjR_0{?1 z#p!wc<;&Uwo(>ojIZuu_U(kSi8|;2Q>;KFj{5~a`-p~kW*q|{yBu0b2*FZ1FJm+9O z`syw?+AS|9*$0GCmldHrEU9faY!5aX(1M|8l}(3i1n`%s*7O<G4AcX9g6PYWVz^~? zHFgm&6EjLvB^kB7grA<C(t78{o-9t&YXM3|GeCn;B2?rElm@t1K#kT==4_OK*%1iH zmPLt%eQA7cB+_JU82Cj2x}@XUiZOK()9mQuT_N9pxcci(s3<Ez<|I*|#hw~4rlm`K zK%gEXGs=*Wv8OBg(w2a-;!u@JWTI&goOM-CK^J@VU>r!V8zzmy)~!lHCe1k6(u%Sv zFGB6??9r0ChnQ9cj?&s?m5}?{sjqt#%4z{i4G5?vGein}N1()>7I)(p8dOypLw}ES z2pHv9sMLiBMCRyFhrWij7zE~}{Rqxj+DfMjtuf0Tv>{F@(O^aa2y}HHwGI_@g`rsp zNQ<Ry31q~}xrbeXUi%DrKWhZ+!=f8fW=sPpW6-9zRET^DGRCa1dn1N&x6pDd-hTfs z%^UyXfA63BZ~iy_TkP%4o$X)!>f1ksfBdVXqoWTWjxVm_?*?%S@J39itBd<TGk|0K z<J;>S+P$6KyZjpv)yD5;jGqwLAi~|v?bgmV8f4myt<C3$&psR<AwPflVrygb=;Roi zy@U8kZ03NMajtoF<+gWs8-Jx~h`GUQFXxVJobqw0p`?Su{Z}tu0yk0ScyV#Yym_yt zY%Y(nGuv-<ZcBZA8{0L0Ni|$WkeCVNA4zfz$r$Zt)1pmarcHWC?S~QZi`W+sM}2^9 zOe9uoo)}74z_NE}mVSRe5QbB!2Tg34K^D7io7Ley(fl()R6L-jhHQ=BYit)m9NMy> z>w<U(5k^aoTxc)4tL$60<*dG-TN;Fqu1{}Fi@gGED<vtj5nj)=aYj)3DL$Vt3dYnC zJ>5cMxE_AbWsjQPOnP5!swG9OyjL4!G--QJxnrYDTSAURG*KzuH_@1-(7taK7OfA? z3T1B>(lxq-bpgrcewe}pn>0riR)=g+*}Xh%K?7Uh{4$hlYkXRcqXrC#UBEz)+gM(H z9c}&2ehCJ7&<?+@zo$m0I67sKJvWxA3mT@6i#rVsT|jR=k6`%20sW*(h}@aIghj`_ z-_O;8f0vkOP@BOaiMWZ~Mf<Jy>SboF(4q`+7O}BldFpF4$OIt;S5)A+-LRD?CXf&O zY&rDUP&1d8*RNlH@#^*A&cXHN)w_4^e*OL1^V2i#&)0YHuVN8&tgD`n1YG#y!C;6? zG@fdR_Um8&ns#@07Y#!cMwg_2_uv0}8h<A3M}KqM#J*|j#c0-BwrMP2WDFYXCCsWx z599QXEN&c!d~GYUk$sPO#jb4}+aUt2VLggo>99fX5SFDWN4hB4D4-V_h^)i<7#tAj zqRhcSC8SeafCyU}TDm9^Dng;bqZqkV%*Z{|>AY0-Hoa`iM3`^QI!*4uCZh(f1E>eH z^m+v-C1Ihu2pKq_+oS<wvR1W*+GMtI{XAGh9Wp`I7s@g-*IhF@!-GUP`u%&%8Os3I z`3=r^6z4y5u_qdvijx-DTF6FbIz@(U(=5<r(lHD*X^?HJ=2;@*!$s4c^6YAm<t*Hv zW!#&U&FT=!c0`=g9WECzgniZ<WQ<jLtbH+Z{Ny-GaMrA(LeYkkzRPB##U6p1kji3r ze}89x_w?fI!-w}AsIR{IVsmSKXP3RVy}!%I&h9oZu<<!K+~f6<<&EvTxw*X=H<*LH zePrHagS^7gs@dJ!-rL>Y+uxy8rrqD$xwt%|-9Om9i9e8Z`TW_z^B0G_OyfmN*xioX z)nR-&_~6;Wp?dP7r{#S(j5gPAZ!Xu@?xL{$D1*Bi*_n8rG*Rc;=Em*%TKs;j+ncL+ zik&|-er#g%&C!M@wBZSD_({o)(@rZjt266Tb=K&USDsgq23_LEe#?iOelDLdBl%>< zPoNfO$ttm{Ym_N_BLOv!s@6D5a`j9j<A`z=M>XrI(GeJnv$K_E(Xl9qEE!tD$cwyH zgBlEKk9|HBc6Hd*lw?(OEvAn9V{yLK0?`z5{9ajIg{s_2w9%I?N=K*mpFjoqF_;Z* zwYC`iNCk|-E?**7bxIpv!0MG7jVyo{hjR9M!l=S$QgPfiVAnE$jF9C7Wx0O0w!5?Q z3=R(CZl1Mi5H{J~@dS{c_;P&iNn?h=@H?d9X`y>8WRxKuvopXGu>Omm|CImaECOX( z>!^xRk{E%t&Y1?-G%3F`spSZ4^ffGKuiPt*R>yJ#k462=vBX!@jL=||mzJgMH6%4J z%RQ^-l}RO3z#i}47-PVw>!Z6GUF;&z_VF1-Q$x1kI$%)PMPD{_D~@_`s8HjOq<6bU z(`8jHqwJ+Lh3U{Yi<~~bX2+mb!|wp=)!X;(j-t^<!DzG&p-0BJ43O0z3q#_NqZro& zRU%7S(z+jtAz)<3D%%HPJ()$NbLYt)4fe#ZRzXYOy%DHN3`-080-6Y&Nk^>)22`mY z9O?zCqSZ$1a&*c@%xLS7*roMwAdni2M%|7=bQ1*Ps~o{{(3XqFz<I484B3`I8`TU; zisNY1uFzGZ3ycg3h7`&`f%rN~>6LqB+0#M|DKn-4lrd<pW!VE4c-nAGFmqo$fBrna zZkj(I!RVj<^3SxFf9Zel-}#Gw@h_g9o?+nb`cM9o|1YQB+1VNU&98!^XJmi>;PxgC zC7@(6*@3jyGh%(?Zf`Gsmm@NHvAN721Yq+cb5lb;K0YSG%a<?F{P4pM@$Q`ek{lRy z3bYij64VE4H;0D@C{S8PEybHRZ*Xz$2xK8Oqy0Z!{xQA-Tm_6+q^~bmkBG_5(*F$l zLr783jfpT7$0o$ka4wWaVU`*#`<BJd1g}fVz2M<n9riO`6#>ZGQs>@KQyahy=4jvQ zGNnRQ*EO+z_D`h{Wb`u9J2YyEGppBSk$wtQVF1)qpx@hzpBMt<ETo}kieAkqvFqtP zh0~T$rmHNamo#j8<FAfhB~%wo>XAiHqCR+U33e@}N&;kt#IAUMX`RIG=y(aT?o(J4 z1r0`KmDIT)Fdc_REQ;@QMY*fQxb}mnr0wNV>kuf|Zsk4~x|m66pclN1BhaGpWT|4x zY$PlK-%%UCb0i%_IrNXDMVqqVPrH)^7s<?xr}_?XLCk7lY9KrLhhutU+pEj_=lNcc z3R{Bvc}oAh+8<D_d)iEeDT}@X%(DW!qBaHsk=Z=`bFT)#6v)mc2$_jv2`^r}c>Ut# z{>JX!?k<nKZ{NO+Zvvm6U+39ybrWxJ9<z8T%thd4%HxY)Kt~gH!(*7=@1<qPlCVer zAN+$qiBdkB^>2RiRTC3J_d<0^Oic(Z5K3_Vwt!yC5e!*3*aZbzl`tEpMu8g!1$bl2 zU;%m@H5frC49b|U%F#M{bP3`Mn|g-;fv3Q#jZp#$N?HsM2tu1t<CieyHV6%)*ibW| ziMYeW4G4Nk=@D>ID2=U2dt=MPUS*F42o6P#POx&jxDy!xO%C3NGKkYDy-Ec1IO?mJ zb7wv6reRDI<A~cu21lXwbAp<wH@;p*Lsmmq^itW6dOE2DG}Hzt%N`pA+bjX%_);%Y zcy{Z9FG@xclmTI5WBx~fy>Q^m#s(sgks8pT&)7lQ1{G6fwV5r3Mh4Ok*-~%}3@H?7 z`wN*v(|IA#qC}utD|b`_hFA{GXd}uH2YWO#3@LOkdzQj+P%p%xMOj`7DyMCYg2v)H zPhp5w-yY99rwJMu6G5dKhbn#zDKn-4lreZ*dP@Z^^R$||GQtZm?*?cn>6gFyHf`_u z7yi5d?Z5n&|1v>XF5VU4=;#D{&OR<gyzz425MXC#pCD*>`HX)cym1%5{A}ZHYjY>= z{qgfhxAD-BGWy-!t?T$E?dI0@#?AHJ<<&Xz&Mtd*hn5KE7pFwn-P>mL<m6;;?=T9= zIB0Heudc6{#`RCW{^{n{`sN0AH>SFYhEZBxV4XX2q%JC?R2Jv(@DLddqw$t|dWw=w zdwzQVr!4<zegTGNIuzFI7u3m+LK!Hq!}{)MRLU26ea|BOq6c)gaqPpyu5k3Vgz^Gx z6h^4;%?Lv4rBxU$y~d)wq<4$cw_cZ~`b93KpTcNiRVeEVf5=%#L(LQ%8AYg8p|0~I zs(w)ktOji<D_YqoRJSP0zFR_dbK%>{Qv>PLlmYa<qeOifjEY^U`-NQvTJINP0aErO z7VZC@7UE%rBV5lZ=$mtw$Sh5ps8?BX-xg)B%*raLfssA*qpT0h!fv6ZOL-ohe*g6L zy*y=FCwGKs(~EYw`x2(J5N=xveNrG%FWZLliC%z>xjOayqhq;qH>4$OAD?z)RxH}L z?zi$P!GNMtdbwxO3o!eE6cC|@vzSTo3Th}cpbdgM3L9U5Q9gV2?A7xZd%U`CZ(m$q ze*gXV?>@Yb`+J<1x7R#^aQ3+Z`E!&JF8<`<oj-|&#?+?Z)^Au^^V<IXKlx)UKcDrl zzxtv{1IndTpdim2Zd7R%SdA>Y5Q|enXx3d=g$hL+m3<2y0BXRXY}6}^Ae8pBKvyNL z8U&Zs^>ua*K{@JWdB_%kp1jCVqjnjsm}L*zfB|WtQk0+#R5$D%y4XS*Hb|ravIcz@ zN~2&~Raqx(e<Q)bQNR)n2D5r84J|vqy4V8-v}93_Y%7>qL&ZT!t6pCtBcrKNKt>}d zX|X}?QP3W}_6jHk8`^YjSu(OUgj}OyI!J^2fQw#$9W@BELqkRunMZf@bWKXDQ1MG| zi&u4f3{q5=bhKq(LS3K%WzH!kj-zv_0@Sn5IpqNjL)xIP7ht<ZxsR|cjPt)OIH(l$ z4l!RfH6)BG=xYnw^Z_l^%2xqn+S;ErkxBs$A)r)W_0*6uW93-J;2!8L6}VeyCTOaq z5{?1~?mzp_|8d$j{^kGizi@nf`j`IFU&4m_M7|EjKjdc02)qUt@h*C6g-nXDoFg1S zj{eR5{(%|_anv?`3)SuQ#s)7kT$ArEF3ynm_I8lZ&Q9112M2qbn<PC$6Xk8j?>i(8 zzC`xlNf7_+?3}ZZEl*42JPC+=^Ww!bUbC~Lz!`zR3oVx5?vB@ZUVssJTR8a;f0#g4 zdjY<Wxe9s2W>~nN=gk*#x8OS%;0g%cm<UsGY(ldeR!n19R3}3U<)YA^zon!tdr-NY zMK)Y{v#tlxpzfPq>eXu?y%)m5^-r&|q>H7k@j-o&frDP3-Yrhw_Sf6KwVtVd5q15k zT;hF4Un`MC(aO?p2~KlLzi#^4qVKzzGoah+t1H?lR4XHmD-R^{8crO#j+U_kjD`yI zngLzw0oP5N5}?)-@NLp?-<*Plg7Iw?bVRl-rSgb!98vQEY*-Dci<>w~+sl0m4)rat z*J;ZJYN+T(SqDn;;!BrG&{&TK(A)R*Pw6YP&G(vdk)J?cL(lD9)XAs@eG6n1yFq?O z`Vl<Q3-HMC-hHTN6yJ5OZn1FRcJ{O-JoY#)dI6?j+}Rii_##sY?B(y!sp(+A5NL)0 z7j~533-DL3zP!D@dH??X+qZ9zPL8p;y1n61#P9lA69O%_I&P*s-}p6U0)hc~s&U7n zA+qn`w2c10|3CkJ#`s*?GzwI<i*S+}TPyYXRJRDtT4y+HDhnqG8fa-(eJunaD3|3F z>zslYqgg^*ZX&aL)L>A0Qq;UEDY9`u7tjVUL$6TKRVmt|H=s5svEjHHRx<_BtaS!d z7HISm4azJW5=SkmR#hcvP-dfUfd=}>D(N~e;>*Z5z1w7KzG|?s7=-Zb7Hx`N7&C>M zML(p_cd_9>a}x4k?HdAb>AHgvh9K?f4Jv{qd0J9A8b+J*O+=3W42y{+Hk_;IQKGS1 zj+rGQ8y10X>8JEIHCZ)1=zE&Bv#e=~$^tV%)}UrosMlWFK+;qb7;>i2%Pa`6q&+ND z?-g-}lGH0y+jm75X#EN0B_m6_efv}pt*EJi^*|jUlo-^pMleEw2{#*F4%y5nCnqf0 zS6_YAA1}=avbDXjySt6${{G&<!9o7Pf;~1eo0(G(M>eLd%g+Yam%4B#dC507SDZea zLmahu?Tur%`Rv&Nnmn80HcU(+@9pi9>&q{{fH!YmC$HYTc|-5ZFW*G6;cFb!>{$d^ zK%8IbJzL|8$18so<CAg4R;Rg5Xu}iQ@Mkj(m78TD&1eOTJnOQg{+QbwZFq8`Av4NG z;t=Q7ihGd9S4${496p052{MZltX5$O+BoYx(H8ue%wmktI^9|=qOKd})mM#VynEC* zv>eSc$wJDYw^XK;O#5I)3M2i9QG_OS_cdfAfE(=77)4V##nCC$BV|J|pHPoA^lb@! zSmhcT!4P`TOw>R#>R_}<D^sCH0o6}w!=HggI(LK?_bDRxw4g)SSh&RQ6pcCVeGAQP za7?Qi99;reO9Pg%D=_O@=~f4qTGCbAu>rDIRaWxq)vLq9LmoM};(4h@Pw{<BEu}w> zw8&_1RAcb4OM3Y;Axk6Xk+hKoI2p~XEFN1HzX11>go>XtYG7k1aI|np=w^ZK2+>lE znkg}*0c*BZ@FoOU5}CYAffl*kOR$Wrt{D))$1>-R5-d+gx;3OSO&%<T8lzDOkBs2M zpGl`^-#Upw3N#pK(^L<W7N%fEeUasBTS9fQu{<@#2S<f2VKswNs>e~i1{ICAEXxK| zPQk{2)bD|ytG*2SE(^;dBg9cjw8vL>LV-#^7~)X{W%9gEfNi>d7^+b%qTGioLqJ0? zssUYc)wjn%FR+WjEH!Fbwj(lUqp3QKP}3|M^}P&s%NR`+Nw-$7NT+4!K4nw}*j29v zvtI8|-}dNIH0=U(*GzlK!9cm!d?wDCfYpklF}K7n2E3`VbJ(Ks)zgPu@XC3aKhK<h z)tQ6Bn{d9J^3r&L2OEuJxV6RGZ~PKPE|z&nulaBc$>~>P{LsDsY+}bd31vL^kcq0F zKj*#skS-gXcWFMP2E&rVfCT5`SDY>`&d$zG_?(}g(q%e%vD@RbwYd|;U*DadU7j4D zF`f8ny8J^<@sE}XncX($|B{D$vbM@&$z9eURN;^|qVlmA8Ae?%wrKK-*e;0<rQri+ zmCMm3<2_7`@R-jcYBdx-x;UJ7dFnm5JNyP1COw7%3QH0O>cbU(_Vd7IxHVL(V3w%> zy)4v#ve%<&(gL&xyE%`5tB((Gtq4@CHuo1?=03|ArC@zB$qd>|aaA=i8c?94p967d z%|4|J3YC@G!jx6c+CP?<UefwcjYrlGC5}F1?G2u=h}mFEmMD%vcXPLeHasEMENK0Y zVN5{Qk%Rbz$FaP|?l-r5xHRzDjK66R|A30mHc!9#=Z+Y?yXJ-+e{d0Bo<n#v+2o;n zC;otiwN>#vceo;<j|0{&BMiA#ba_Z7h+bSmd4};ZhT8|vIqCfb5d5B|TMA~*!LD_C z02UFG?9e?XJzx-NMh{Vsmvt&|Q(-wYn375E?Zs~1dBc~MF2=;qN4U6z&iZC)4K*Ad zsCOsynYQ^NXxwY0WDU$hG5MX3cuBJ`y+GqxjQ=QF(3~AD5h%W9jZ(8&(l5}rX$MM^ z(`xfd^U$j#ks3$AZefJhNz_bnh=6tAi0{xW`7N*b@d=aCx(CXANd)bMBkn=Rm@W|r z>&aR18Nz@Ee@@hNYFn;`*f|xsN98R2=<=BY21Qd1H0_`_FWBwThGntqM3l>2X5B~N zYa-}nPa>DJpxfM53qGo66+Y^+O5RT(Cp`m0l+>e=cC;V`yX*V!zvs<ze}Dh^^XIJO zpZ@8ex*OT;C=U-0U%Ytn>eZ_^Z(gzea3K_C>`Vl@c}N2{r-BUK*w6e|89fz|>+tXy z*-uZ;(4%?x?%nQQ`@`w_){MNYWypXNM9s;`2@x<rL$&ccqZ5>F3C~ADd5Xn^e?*qu zzkUaCd4D`ud4<nUM5u}e99;Gu8X~hFIKI%vhP-|I34F5Siacsf*uC!jnkMCaLWLxK zRNhLVBiM!3e@Gi!8E4^1YFjjmhm7>gGk!unRfAn3jJDQesc4^24455sCluS>tL~$y zGWu4C43!1iKxbA;*N1M|(?#j%)c(IH{00i{*Bq8-ba_YMGV9ex?&T#ZMgcj3{l0pV z<5<CaNF;VKpbRc+8k5&i3)om&fBW_=w|EMxQ3US$x{u&2y}fQX1!spNPXavKsNn&C zhXfvM$Ve!Ln&)S;{?(Unh)ZS0<;jB_bS=UMuUPWDlu#n2_<({2Gp_IIeW(JbY7j;- zjywYlDX6F0qsBNuSh9HYa1;%=(16BgBSzH#qhNMgeCZO67RxGl)G{NJ0$sekbvaYO ztVT&kWOLC%6^{$TESQa2&>qLaE{P&;(i@<srJkCUT|-r!PF6iFHtK2Vf{u(vf^Pfv z^=k>EjF>Ts5=u^wK#h)e@j@UnU|D6;#RdalKSa0$Ws}y|IR_ZU-EKyWQS=5h1vsju zX2>zCEV%5Etp@|T?jOx0gWYjX5Qia9;}EU!jh1<=Xa1bTMlWgF%*YmUe^L)%h8}^E z06lw;(+V)=eMU2Eh-q!;F++&@2JB)W8mOdYofU*p(2{Psmq4ywQ<kJga0N6#1IVJi zEtmy?HewAJKY|X}<yxdHMAkm*jZny}1}!og4Kzlhl2#k(M>)HjHYxY2XVf}6g)Fp= zMxcknG>%7biY|bRWl^KFzkd6JUHL2j!~Z_J^k+Z&*_U5_>Go!;9G`pub`CSTy1L-n zPR3vT>Q`TX^)n3I?Z?N*r>CdLyvp+KiWjrs21Dy<h}U`ik}6i47hu+eUCK<i(0upZ z+ZQjMy?pr^&FSg++1Uw4fXJI0@t5TAH3c!L*(<QK$a>=CCuS92_-I!W47{;13Y0<p z=jZ2)BK+{f4;Xy;<(t#v4`@7^H~E*1FY+rVCud=Ka~tt*;xBc_LV^FF$Xp2MG3YgY z3-Qm0*JDeo!ColLZd%>rFIiEah5@qnQ|jLU8{c-BFv%#yZ^;Hw(z@G`X-lB31xFUW z)J$83XscTShX$dPU>xcxr5e_mmZPR-)Ox;DD3t0e$OuQLV9$`b=n|GnXcyVz(1eFE z@nUMUTwu}rOV{Edp{uHIvFS^t0Bb0HwF(6WBcTk?R2)tpeZirEuF76eZwqb%;QEOS zOicqI1+oSVrAH8BO&p_355Ba-vOB`jDL!{)=KFb-0AZA9LwPD)mO_Ivt1eG(w06a= zF6CRoLH=D+jy1&657W`HB9!2K_3c~G22={yLq})9VBF>}c^bt*U_U5B8330)H9crN z+*6ofZim3GIJ$^R(XtNz)>OF{uCL<P$B>=%#D*3b4Wk4hQLc3SDjcp1;5YY-&<mD_ zi>XWS7bZ<{w1O0m{T&U{2(oBBnM;#aWWn!%aK2Oe)3z7b4_u>IVQ-oUL_p?-8*URS ze#Notp?B7OTU&yzC?D+Z06{^%zWFB-2}n1~3DB?<Xwchz`SRr#UwrZ6@CBNa^Rr+7 z`q$jVDGxKM-8<ON`+WRrVRr)YNqTj0Za}&OVVVpf_;BKm;+%c``Zb%1i`(D-lc)JD z(3>w`Jg0gpFgG$F*Oqlf)Tq=94KkIfcdtjtA&4twSA7KmHEDPc8s_W}5P>c&;0q{e zwbTXDHYi!amR#1UJIahSh9T2=RDdqVIMO0xpqbrXqtccLv{TA*gmIctSN6!>Q9#B; z0ULy@CDy0cgI??vRzMA)p+Zmw%z6mYq@fbcu+QTbWTbGn?Tyh?w=^oV%y`bG>%M}t z4IE_%C8L}nY<-G%J+)D=#U>IA<amI)L5u@-xkl6$EqnANP22lQ1QW{!gpxB`+uNd^ z2`P-A{w581^|gMwq^>&cBG9@5ni0gs(FP4DkCd1RN;MAA3X!Xu<AJiu!mxz0D`n4U z4Mhdrnj@pkDuQz9+oC_d6$FrbOJf2`DW%;q5Dj3Y2koKtA40*jj`r;mOfhX?6aisc zPfyu{OQ&A`=->WdHYxeP|6l%3T-eyv;MYpISREaI;1F>6BGK7d{06Di-)?Qj?~?#* z*jH{Xg1FQi1#hU9N9w!$rCIT#$egX$cUSS}u5T`{;`eE-Z>+~pEMJ_TpIxGf-z?4J zTb{GD*qg#j?$OZ^XR#Rp12gXI?2^T!k0sATOo0|oPEOD;iY4~k3l9$u&d+#Yin+uA zT92yyg5_0y<(LApX@nX7?@&ogOj>QL1@3`b3VN|xX#D|dr!8Yz3X9qnaM%8_S}VhL zx$sdcR0-2IrxwudDUCw4ENQ9(x=u<xEwr%#r@UN0+bR^JZlUEAM?EfdEwc18<j~x4 zY?n$-A_S(%5x00SV1=Cu6|giyS6Y991y|d5i)PwU%Gps!zkpdZDQUwA-AdF{i<z$2 zau&rj9khNjT|I>~3}KYL^vb=4vozKB8e5nKp=AYFB5)LC9D`vql-YgzFh~!h()!89 z`uvO2BJgfel0g~g9YxYA2(ktvdfySws~<%Jt+SYN6tdHzAGJhc^-_qNxJsZ@TGv($ zl#OP+;HVmD27}oMMw`Jy=B*bq8w4o3NfS&xqK!>i@J7DKrPq%ZgqtI+g}IE}Mr%Ds z7{>^GD~|SUjnWn6-T2pkty|Fb4h|k)y7_}#2fKNHzmDI6dDg#!+}^dn*ND4QV27aD z-MRlUF+(wg8JA^V84h^@NO-Wpo`-~g{jdM^sNl1S?{o4Wf`SvEMYddq=oaCS-;bu0 z{r!E6wLzJcH?(BPn8?6nAoBzn?;dRcnP>)7&;S?Qt0WCTW$8gZ8eCXeAG{EZ5V;4T zTJR~2uF(*D1F;LEyisdvrtK_YJ=usdlBJi6UfJRfH0=akBJ_asZEnMA1Cye~7-hQN zrz@`vaF3%ht7%fAfe^}-M<ywokk)#j41g}aw!NUeGJ>+v6r$W=!&C~5k^KS(-F{<~ zJvN-A>;*sE0{jq({Y5YYx}3!tV2sxivcR@^Z2gH2P9=(=OFhWGgkVoGZd!6<fH6vB z$awek8Y2TPBV%P+D*^S;o2`x!@Xcjz2TOrg1L~1J-7Lm22(#wYQ|TytGy+sfwj<J{ z9SG1yWuYD%s#al^n0$hbtvISs8rwyfy>DfS7iNsQ<}4Z)F@NreJ-`q<==}VWqruj~ zn1#iFQ8pV_Z#El;#*Ig7DB@^_W_xRQYinn7gEM6-{$|p8{7d75gJ;MW7gxOfvhx|m zhB##OKo=^xQ@GXZ1T>3Z#%`u*j1BiW1W!*|AOgnR@X8DgAOIQ{A=V-V81!7?*zN5@ z=K9#}TRtNU1<Ix~H6X{Yo#v^S@w_DX+1T1tIsH5ptcKXNFtAi`xAg5SvqK&lDFdgk zJf)9QH9#*Hvq~Y(EV#_V5MHhGaPG5Yu=yz~IBNu=l~SSamMoRpqky0dWL*pA3yk98 zj&jd?o;Lpu?PoE?sO<@(j*)U|up-7;9ldHU{iJGC>`rIhoAq)m&_iQ2MbmcR9(S6_ zt%?KDM=oZAEXUMS+VF&`0il=6OFcqq9!2jfrF;~#E<~&NYO3oZ(`7m?uS(6PRD_<{ zq`w)cXBJADrMZ1JEzM*#SVJEaX}xFw$~HX5G{`65Zp>?BKuo&1Nkgvyu>{#&-`eD( zQYaE`uW#1#YbAgsag1g_44f1KNl~&@9D?ioLOBn{mh>cSzIgtuiNm5JSgu*E2`pOB zmpv1pO3ds6LmEI$Pim;*t5FbKXf-aFyaJZ3h{SWr2!O_JwU$S;8b!9MzBLX)Y3Ks7 zj<gb4hX;Z(LvLF{BZ#A*OF3$vfdiEY7!)c2y>T?K&Tz{vp%54ipY)>Zv2(St*9FjM z01BgS3ADW+=CXCDGK#W#hcE`7t^H0BqZH<8j2>l0pf>Q__SgY>%p5{sB9)FVt+@!O zQgk5&ao9p0<yevYZZP1YBW;iIp=<zwfGSH<s2M@_CUw<X6)oNJEsX-Gq*U5khl*oY z7h8!;!*|FvR--SJ2Et*WsUBh(MOoTfgPW>W43~Zi+933fg`>4CL4Bl|vsVwu+S@J1 z5hK0EV7DJFB`EjpB5KytL`_PT2Z2#WVD)G#Eb<@y(Z8)M|Ih!&|BYAIXV0GTlIh+) zIy!p);hl$`Tg8VD@!eo#PC6EtcTNNxIXWl}g1{7TX9xql5P)^fU%-4tU`BDrjFzg< zV}L&0;|h!w3*dQ;GBx>^mvVgsr9~n$sSh9CqvOb5UlWbH8WrM8ktcLfVy+$=l5#&K z8jf(A-|r;~nv1+0-uV@OCNqFVlad(Capvyk>|3BdEk)zrh0{>W9ACe_iCJXS08QUc zp<ddN<#J&bR<B8EDOA-LBc;(sd6pVQz$?vz8bZl|D`ih<Mnf(XLbbEqk5UUh!r8S> z$8;UU-6EJZDbW$ZovBjP_iZuivO^TAu-Gee$EBwtmr&~rX%bYBQud?DwzXWiAeUYo zDw_6VjErl7c1JAI%P3A236Ud570gofL!h!}(JD{lNaZb1mQZprlX5_NX#Io?O?t@4 zte9?d_1^vCd1WB4M)5qLftI?6`Y8_OsxMltc?>Jnb*QNMR`9ZMPa>Ea8O_ve8WT{; zqKX}Doj&^`zX#k0=~<$mr3x7H$nO9zq83n@OO_G(`@$?3L&*yI_H92T%6mJz2pJ;` z&`<*)m>Pj0G`yVe2M5UP()tc?xyOEvzcdkVxkiAC{6|j+xx3p<nXZwE!+UQ&mc-vg zJUl%7tAF^141GT9KmF!wPO8d50$)6MSjlQ*N)&_v^+7%i#eD*e%6Lk;x_b5MmG%&E z2N<I5HJLZM)%F4bX<MM~VAPGFmPS|<+EQu{#IcKjFQG7CA{Dl8ffpw%1;;!JaTtz| zj}cs=bZz?&GrI^zFdfErM^FPT_M;Yi9cc@?Wv^N3S<jeiUO}v(x)zLpuT{}ii7y(D zouO138JD6@>Zq2)LFr0D>8(Mu7rF`<XhQ_x30pIk)N_C#4A^@p`;2xue@cn5HvnXg zdw*E5q00pQ5o?p8WE5~`-Oz)fKr@wCDu8mN@2DXPpw&h}uxZjmurFUQ8q|ELfwB>- z$_X-ro*6-!hoxNvSHQ5Wp}|KjG4aAo_tGm18qfes4QvJ3wXLqk2&I(LSUgmPF0z$i zL#tk#k@_;AWk?O!t=3Tb5}Yp3?a>kJRzQ8#qf|c<1e<DmVT8x7SY);$RYTR;ug`bC z{$5%BwSVP*!mj4R#r?q3>izroyaVIHO@g8KAAVpIQ10&Rb1E^!3F0|oWGoT9ySSJh zL0)DVMW|Nr#h6)RMr7<s1P2G9C#)xk+Yf`cZ{K2ByBd4X`isjmm1OrGiI>qVtX!y& zq_^=y*zF$$+{BM#+}+&8x%2jicOmEB0lv+L9;>~*zFOaCyG{)Tw1rArxVgH&Fsgxw zod0f(O4O^Ny&8V#qau_r3un0oeY;F}SZzV}iqL~z1F6Zj;UPFMB&F;PO29xtSnA#k zDo9aE1P-4<uPmnaBZGpKZ_-0t2WhIMaHXKtxV&h|TSpeuMDWhITF^%90s=u0yw=fe z7K^Vlt|wlafqIXl8jaP9%8{S}ZTJi^tCDg@S%M%l+Hh<EWl}BYLynAbF&8n)i_kCr ztbwwEjJm>Xn>3)A(WZFcWR+^6V39F6pk?1emK>-Qe@DQSn(wIH*u0;+M3nA+3Z(=u zn5FOAMc~z>0qmK6>&#)U$T6_Ueq(*+ht9y;0RkHvm_8b?ejw&Zn1u^`lO94qf+JL` zu({w15Q|upeUX0AKKJ~c;gSCa*je;g3G2qz#ft+$F3gY_T6CRc$WVP-7_)Ed_|g^S z7yF0!3SDoAz$h+gkP*=5FWr3e=F6|paA&W71ALobN#`bxUiTI*IXyjQSMb2#;{gGQ zhMv2>_9jAzpM*X*_;>%#--#+eo3{Gope2FFk2LX6lfUdLwrvMhQk+G*5P-YoLdI*@ zwZ#~mj6tCEVVw}iP_3WtXmA`^3VNv_?dhVlJkWq4&}@WW&e2(G*}H2A4AE6HYNPr& zB5}7Gwlb2dtK5UKg&P8j_Om!6?2(xTE6)yNSB-)&Y6~&3hm!@Bt^;jBw`_ziN(D6# zff5Q3R+TPG&9nRI=_xX1lti^Yj&t$=`ba!rm$p)?p^HESeEWUtDTfjRCr)1UB#m>j zdny`{hyDH}2g@sBRx41(wuTbRHc{1(r(OH*8TORwQaCCRx1%(fDi%=p-cp&CM3UoA z1JRraE6kBaMq@D~b+nmI$m;HwB`Qm%`f7Vdn(|T*yEz_2^z^DxQD4fwU5<|6#1-0D zk|7&SH36?_tFQ<boQ?7Ax8MHqm%se}`|ml4*wUn+MP|sefc<lPd~9uaaZu2loSdKp zZcZOQeBcckaA6cn$fFlunqfC$&-ucr-$O>}Ts*(DQ6P1pMoUA1(Rlk!#RWZDR-GFH zYj$^c&5QKG0jDV&X`Nf)-d@}ghr=?1OW|4-gxcJSFR`&id9exHoX!i!zJ>TY!SJJH zw8D$GzCb9J#dLV}N|PE#d5VsoPo)DjB&8l@u#BQ<=O_aOK%Pbh4z!vnI)dHay<`PY z|0r7Y362`pHBqyO<~CUnH2N|}r&*yi?puYDA=0P4N-AMX07^9daT$?e+VX;D2cT>g z9ka^90{RxH1e6O#QPP$ftQfppv{y4ln<<qAp_g^hSL~Jzs4UXzUX$_ejqOfxR9{ik zgIOCJM)d`|KOQa3gm@aruL%}vnp;QJyaWQe-w>MWk+?WuH){;klw92sOsZzOGYf6N zZbl01&Qhc0SnfX_=9<!mKbsaVX{v;q&VK%V2kuQi&;mjmo}hc*_QHy6<ky<@s>4CI zj;W~Z3FiSdY~a{`!|%B9Ie{*>U8d&7a8v_E5pcx7FWmFc!qbj1KcDqq{QRfPhq!t9 zjjvL(n!vLTN-VgVQyF^7qI&9Z8niA1AX_>D^ny0DQkq2&xi=sPc@gTI$uNOkQDag; z>8%Kvm`tsd>2Y77vNKXcDAHkxKsUp*I24nq0_`nNFWTzPg8itiEE%#vmpBnU=|_2b z#HBV0Eixdh$KE;}qMPGmd*ZZ+nJ)7L&Q#Es0eb+ARjDTkt(rcgGeQ%d!;4T2Aw=lm zDv7|M!I;xnz2HKNF?w3TK1v^M;hY%w5|iyp*VBnnEdjx32-MHk#S$+b<!O=8;1Z!H zY;DFr#{wfz4@Dx3;+L@KD|~{ZmRWvVH!62QTmdxbsfSY0Bdf<38<faUL87eg90V<; zENQ_Z+Wt5KN)52oz*dm0u(}!}loHTjmPNG}C&4CWm_y7<N808#kimkA47k$;e4A>> zhz30ZbEMTKM`q@wEL!T0Z__@+vH_cF0WXCSt~0`@<=Dk=x1@F##nG`hL(|7W^X+$U zmE~XkpZyiyTG`3Zo;_oc4-O9KQV-i3V;p(QWrq`l8^+gPf6Xb+?AQQkI2`1{3uCv0 z=MF(?r?oU)Rlr$eH>(SX2_zyuUc_Wnfs>aqG(&@oWpp+;YVoH7*V!Oj>+u^?*KcpG z?{03dIPc=`38ox>{#QL`NBq|4wgGPLVp%Tod%~yZ@ncbb2ly_(>Yv%}wzpWoSTvv? zr6<gnR!!Hg@9pd(OzlZc*GW-4d0D7XZnW=sKrTSLUM+$L*DhUamkA4^m6_=(X|L~x zsGOl11q~=zW#9G!7(tL38jWh8UewdNsj6#RLT{{wdSZBjW>fI;U;#FCmmdPIq_mkf zj<Nz8yxh|4URuwWI2VSzn%M$2;h8~7Lra{jrEMN|2%uyg(yE!2V5_lR>vyMRh8RKv zYO3u8GWIrrMm+(AQHQ`$1X>+6K!s*XZwVON-5%yO!uV5gG*kt&b$udqHw6SvG+H$Z zJ!Nkjg8vybIsPEvs0D2RO(_x7j9TttvqPXGsFX#2y4>R%2BSFn{4k1xz&fy`c)74F zqx(uT?HN+gk#-8Bc!36V@dBc0FiTc(zj;9AwB6Zme+{0l$J8#eUS>yNE+{$0kipRs zuu&Mb*YOWzW+0k1;D{h}xAK=1u8xUTXOX?xXL#gyfL%!-k+~}4^XJdGWO2O$4<d7~ z^_<13`nHeRw;m(Ag1i~`$6bF$fpjW`N_0U_WDdtG_~OmW*Kg3ApP%3V7U=dx^7dDC z@IuCg%>eWW>pn+7FI<p)R_C3c7TE~@;6MJ4E#NcR{Njr@tTk~dh`5wuaf~6jSxJl# zv(L8<h7hpvQ2;XxbOeSlXyxYw)JL`s&8DE&9+1ndx}Zj?FuP==Fk6&(siaOcK%E*- zTS74r3I?Zx9y}@-;7%w6(4|LX5@9oCYA;6Cw?IQKS{%bDDLpP=mll}{)vGk4qjg*` zpf+|7Eoi2_vMyMv>8Y@;fR@6L8n9dGkR3&4NIhK(C?&;%#&m5<@BTp<$+{Ytmq8fy zn9^l-&X-nqWV{&lEFv0RWFqY4FPEz?^k4(#iU{$iUqXgTs%7D*VA8Y?DKFY)nscF4 zW%Rio0a+{?9Ca>~-521bKwpRGVs8s56(DWHn6~$&b+k7dQT9@nxRab1%z!efH!l^u zccF};Xfa2h*N?bz>1bPc>|AQP88$#hBWZX~DSNXVX&NbIp(T)x^=aCq4Gin1rrKVZ z!jL!%+l<c#FO~wUkXaM<b?N&Szh2|2(sFDaMgCiV^x(HZ|6l*l|3_Bu#fulb+;Y?5 zzR2|1)jNB;&$wIc?oi6X;lcjFK2bOGfq(<CzrXMG4dL1IgPrZ&SFc|@d-i<)VE6El z{~qk@>~go>Sl`^*+1%aP-Pzkd*gxDq+<SKT?BLmc{NtV7t)1;1&X29lI7_hDJJ{t8 zu(rX`+}PT|g1x}o@AmHg?$y=hdh8A2Q4X(-8~F0S7cXCMHf~VXCeJEy7F=FkoW=K< zPuVJ*$~-}`3Tx{dw>R8qt}b~2UgHfH<2b>29`c_e$MQh@3#<HhzZ>yGO?Z->lZa`8 zLY`G|TCoUpAGDiWySuE(CNrbM+-x_t)(`g%_V#xVcK2BaMky67Gmi=7&3YsLwHXI1 z+W1o)cenXVuf`uXK};tPZMDmVS(rkThLc5sQdEk1a5qk4YM{Pv>tZ4(jewFC+Q2}? z5oKDvs%u-&9clWcD?$XafZgR0xJsH7=$3$&OL{##jiKlIr46k@$^CrQD0tn-Ef#wW zv$~#ZHp2C(;-QZ$>VYA<r5p*>7DmRg!kSUg6dGWWy)nJ9mbUEu)QuShFRF|(P*W>V zL$-PS4D3$n^@L)2tusWHia8QEI+$sRhB7!(v}iOav|;V+PRWo#>o?}@YrZ4y;<A5F zmKJ$wiHsK@s0Y(U){b<YhtcLaOj+zMr<o>p)r%3hh`Qk!tx{cNx~^?Gq6FnqDyT=c zTY@*yDWk9oz=gR<t5HFIEFSr9fZhKw`9ztP=T$E$XZc4HSYe1S*e%*u!<s0JmVMgx z27(-acY*b!!)=d5anD=li16Vi&h0IJ0pw=<0!Z3Do;VH;_ICI1;a2Vsqs30hUn4^C z-irxKF3RQ>440Sf-#~#jfSyNme7QK&-OZoRLi6(F%m4Xb{i{*sXA|E6&NXa16%Z)Y zFWw`dp$=NjAPbJ~x#yEg+$yM8!6h>S7*qYI1-!tFxD!nm3{Yx@h9O$xsIL|ck8zAr zDrQ;&dRD3u5fjkU;-!Jv(fFkl)|Vmc(M5Y==CNpB(^6SANTmR}P0F350Z?I?^?Kr< zsjy%TWJHs5YDob{=BpAJOY9AcjgAbtl9p}!5x7{tEylP2MY4ApHKu~NRzf!lP4LxV zgl1Dn(LCqYux6@;)*pKiHR1|P^+4E~m#aa`QgD>HQZNzLkPVC@#q{n5bVfv|_{O0H zmy{rk(xr9T`*{_N3PEU9TAQh-7@REF6CaIU7w0oS^&}d!PSt#O{}ptx3mUY}V9;ws zjrGvdbrDcv&$==X1_{iZhC|0FiEzY3!)W<GZ}C`&1H=T54qbEgEeES?3N)^>5lRTJ zTrP+rx;^QEZk=x1U*&hC1wA%}mLs^HxDM_pQpDM{wRL=a%qT$|MaBTwCay*tiu-BZ zJ%9d!cRUu7w6t9Jx3_nmJv-!fhQ{^8YuIr&>;<m>w0nEIfBMT`Ggka-|I>eo_g)s{ z@cBzl+td8@Ro{RAJv)XvxOOuH>;!V(TwX-rER{Neg7dJmq?cH+ew&-TG{#hrPfpL* zHrIAGcQ&@;e|H=4znit2lMg35`#WeZt}iy(`#YQKx9cb8CwOwrBIVJ^2}fdkcb7=# zmzTU5pPrwybvC()tgWHJYxiLP;_8x1_H~?_S9iSQ26?-=ixZ07Lc<&7Id8t_acSZu zn`*f(QZZd(a%V-T!^e?lQu~JoZ(hA-J-_|-+q<>)j0;4j#q!y+XLzwJbV&qwt*>qF z=l$;P=5Bj;o7a6_gm12HF0L+U@7C{lg|Gj`EB5;O(b17%bB)`ded3s*w4|Y`IFKQ* z>g#dicND#_g&5VIA&7d|=Qs0T(I*-$2BUU<*VgEeq6AXA2TW(FH9CbM%#0>zfb*hc zD0$I$2tBXG)WX`8d$quj!Yuk$95l?rp-~*Br=TU+W&KssV(cP-nrX`rZFOydqpvWc z3`S5ht+^^G8jgrUX>9#Ts5(Z3t;ie#M$xkgfgRG1mLPrnYJtdD_ABX7zu(Y+HL!Ki zh@;}Xrr^?~hxEDnmVH^HP)kJpYDVBgsep~M&_#Q?hRPTbpHs2#mQe9aZ<k935s2JR zutukly-5%0-FrB2Y(<ZbYo1Tp+x|EYsnyfAGKQ6LUbe8Pr0bh`eL0TUh=k!%D=)P^ z<*49afkd`j0xq^AVRL>N?$@X6?JoL``Vy)J$;`1gO74a2od@$O$3@3ceQ#`Qv>CE~ zY|2c_Mf3G~QuZadH`G)c0yoZq3IbJsZ%?bxC$;r{q%0c0e(@5y*9*_m-iWyhAp>_< z*xlaqRpR~o_ix|6<uQrZbuRuyh}}DULyj)N>0Vr%v9*9buYeMF!s3WPG_G=Z0WN?1 zAN@y>{<Gm_V9z@@ot$Y~P%4OJ80w?7i)EBQd2Q3i`hW;%2;wLh7BWoxL-|;e9T2d= zUO}`39np*g!KG{<T_aS<>I;o?60yX%1G2_aW>A(<N-8lhX<-mZkD%f}GkRELWwZ+> zQd8?M=@hVTYRUy=b&;zKqlM2L8so?TEqjkwj^9sT&_~v!sXmn`bjTtt?hsi6>Y=T5 zaHwF2R(;<p)M%{+>xO`)rb)No_7KhwK^coUd`p=YO|25q1R0wMF~KJiQ)^j{%2Ra2 zKrg%T4X3;)n5fc~L31AP3wCAP+c%2=_0alBnW5KLrFz0-TfW*m+7`cWVP|JgIgEy> zu`*>af@>((K48r)pd6dUP-JTdjord)i|GJ?q$t~RB+WEwstFAB?g-io2D!#T8b27V z>i9ozyle?%rnb8qPp;3OKY#i1<<Zdxvm{|jB%<*y$8q1z-<tS0{>H!Mu>5=f?*HrS zufOKTaQN&wmZ$lvqz<1y=U#YqeZw16e0MayhkVQReS33*-BWcUBx~>9{lIh(P_n;b zlhJPH&n5H9n$IaWG3lGjcu&5*yoxV2qhS_Tyt~G)gW~pgb#itR%Im9(%ZsZU*5~H@ z^5XRD^!W7T_~iKP{OtPriaQ`T%k#@~LalFX$5#=!1;%S_6leDM_A%#L{H3wAoA_=n zYqGVzu|@FsndzKM{&wnkiKQwEU>Z56oL%k{^jFvIE6VI2mU=JY_RMlIFHnhwL$I^E zy~zvyZG@r<@{^V0%>RrTxHV$ovnJmC2@;XELfDDVUi`+6^|(~<pEQe4eqH1G>e_Es z6N9Q^m4~l#qO=v0u-EL4aK6e4)tzO@=#Z$PatYYaM$_F<@mRFshq(Tp)O2z5oYE0Z z-}b^R;nRVJfDVmGy*8s(LCU>GN3Am*DPeR$D9T{ONIwcIy<A&G7!sEbjmt<&*Yy|e z3p5o6VKyeHDTC4!r5O!PEtj*%o(a&_Xw~VqnSy0iThmu>t59H5F-3z#@i8_CG}Tf@ z!HY%i95_;2mA-K$-rUTKb4#key2_(=5$z{sCM@zQwMhlzvL6XpDNNfw0;r7Z;~b98 zu}HrVLQSKgnXe}cQtsQ4aZ$%&)GosHk*3NZ?l+^2S}jMdqrGP6`rk3ykAl#$-x%s! z1+FuU_Fxa(6mJ;E2w$S|$VYJ2ZEG`b_bBqmvQAD<kB*PuAAR`6Pk+vJo`Agio}8R; zzcy6ApJmwg?FG<o8K5BuU7{gdC*8mHZ~mJad?uUwd+}R9b6%|!1QH;Ol)_9b&Q(L8 zTlOgHDjcWp@B*B!0XD+(2WCX`4S^vdu=-xm%SB@aHKGAZf|P~`<yb<2F-q-w<BCjI z><V3Hfn4e6x@ZM@(URbJ(dq>V1vX#-3@K}mtc|_|EcfuqV(dai00fnGYqaz|7%)m} z&31{*`m;g9|6#$>>r0r8zXVGXHHM`OyXYxKG}FM*f@&2U(gvJPY3u^$4=sA*BQV54 ztSo@C2TfKH+fqEGRbpUdjTtR_$aoDG*2g|tK;t^=TVSjbp(=N1dnX^Ob0_A@ZG7VU zi*ey-a{J_^$r}1rDqx|$7s>`fB@yfnnvjjk5VE7`6mdo^@Dhgsld@Y(jcI|`5|gT| z;1!{gDwLUBH9(MBe+0TM>|mgAp>m3cgO)wxxvxDj8P$=<X$$w|rB%=dQm_)Du?-5% zbjdQKa<7wW{>I;Y@B;jQ_}~3+Hn(@r&f|^x{QR7^O{zP5en^jd&e{3N)g>>&ypLjV zzO}K<8zi6Wo7;RnHs{T^-+sr;sGYhn=Y#T=dtH3(;D*=C{7K_@+pQ1!e3d<;rAvE$ ze)hu;-%~?zc6P>{&u^1*k*8(Wckz9=n`rMS<Bs>(o9iozVo_K*7mp*w)NXF$A8oSC zG56eYRN!(EO*{%HSs70&aADDNw#5o|XL`;zeoH*vT4W-}QgR&Q``!Ucf*?fx{K*l` z45dBp92d;$jHb(u^^KYqJ);$zWDIV!NOW68-2JFG$0_KxKYw*xg25}rA{H5_XCl%o z7s2S%pnO3CC%GslYo#XB#^LjD^vf&CMq7^dAECQN_ChaHhBBz1w%W|<5vDLS3qyT6 znY!4ebx#&)7_g1#63UfCX2mqtAgntosX}!%E=Fc(s#R0R1^IJW6oKfpHCpw!Po}W# zuz@V9ZNfH|ar!Qdx-vB@NbjgL?NXZQgf{$;s=Q>U!0}CW)6?2DivJyYA!svYf%@Ke z#H<?QvY!YKx-~jm52M5Qn1usR^a4B!W-PWswF-;ZvmJ|3yO8ek&@>50c~J_{zP!qK zq-Ui4H<bnUw7tIM(um#Bbp{-TJ~b%EZ7d&MxaA4=!NbGDuikvg)VOQ=mnpbkV}n=y z1W<a11~Za!0aI|>GekNdAeS{X+&CDmOWgnB-}pB&z~{35ldr#I4(2dDS`*WT#ejMq zZjh}~r2-JdP$)4F^g5!i7I;v=n00aaNbL;m3TC!og(DcHC5x3~MoiH_Du~d{(pqhn zMBXyCEi}fAuvLb2DkD^6pcv~x)(hyCfnI269TK`0L(6I?NIAM87(ylsO1cKoh9N+x z6s0WCXs=AG87*5@*={eSYoJCd?+DGN;G$5Wsx_LF8A2Kcc7^rHg=q(+3}_iONCs$$ zShqL~`MAKkVWV#by9dj1q3dx3<O~-7^un(0nxUZ{Mm6hO%rqz*;-Y|nyR8BcQ!_O9 zqKVCvzfVXrlu})yf$pH*L`4~tqg~J)RMx01aa;ss=bJ9(jZqz;Rs+)Jz6B~$fHY}% z9^p7@iC>mx0W|DS+Cn8zC63?()u&UqbM&18qtqET-Sq^$zQAN7+=RL=X@-C!F|j8a z&~>45+`B@Ui7r4TnKKqG-{a!@pmez&reljtC~Kx#ri`8q_Nza8@XHVXmA~>YzWMTN zB51t1y>)oF|EGWUtJBlt564HRr>E3F@c6g0x3|07d+Y6Q`PK%A6@K^bo$qXDNJKh9 zvDxBZvJRUKGb$0T|L8F@cupl2@apO!zd951LT`&1Z-ywTkop}39#_vVuCDLaHn{C= zuEqC!<I6iSskWXsaenb`TQYCHAr6E-v*3a=!6Bmr)XAH_xe6?44-O7=Hy4&xwYM2R zUWI^?IOs8Bjx0r#)g3|6u|R_XV6P*0dcP1r%ZvWz#?DoiuP-e&bjgKR&Bai(+DtJ* znN^EF?G#51-V4N!6&&)?l`<HCo=`>;G%As+RR}UpbxW}RDNLAX2z?9p0q2N(Lu%V{ z9L2F7(O8&rgcvl~i<)Um{Zl2dk_saT)ue}zm)2YgwiQs+gZo4cHbp5F(73BzXO+DG z%6$v94xol1U|vm|dNl|fue1tKHmO^X6{)bJmO0cYxKV-GsTn~%OxfC;3j$p=bk!In zY!=k18E9q;q&Entuc28Mjp{yyIx8|QGP3|K?@kB36I72~g+eHKQC@#Ud3848D{%n< zjX8?kXQ$;_Zg<4UOHeNQ5$MrG?%kj0N1$8hA?W=xRCasEMJ~0kM(slTn-&)6Mkz_{ zXS*dUOsOH`*h2h9$w4jwtP^^BTCOJuM(bOJk^y7w*>zM42xuIo%bkua+~|P^iI>U2 z_C7A$`@Z|`ySH!O`q)NTZioi4OB}mAKV+WR_Ouy0ARsqNlsu(i=4Fk@|G_`_2O4}P z>wo^w{oFfobP~#9J|wdXE{C#DW9i%On#x3A6u}lWtA!?JwLp9YzyL2oMS^s11KnXz zcC^fBiDMba*f5vTbU=3_Xi1B#o)!%k8a0qkfwIO_PGs!WIA38j!v`*%Rq2H#&}9@2 z;6fJ=h^Y*8Yn6zQ@j})MbVP})3j)Cj!aD1#8H7Wcsf<`1=#558*CHWZ+r(`Z^petp zHB8ZL3N8v2s#=Czx(wWQU9}1hA#k#xvF4gMAZP=0Y5O5HHESH5vKlBeQLn6?vz-dj z(-mYjnn`(azA#jv!9{(J2Wk{3DGTuhAY_g#@p-<FWNA>))fkKbnzhaZEJp^qQ=9r8 zM$yM18NSp4X>Og(7fXi#do+fv7C3c~9W9&G-@jN^3%tK+X?D<y_1B;*1v^>_D7`5- zz6PPS3z+$D6jcgJS}g63aE`QKVI#d+7^2Ii0u6&0SVqBo*}5D}^l1|Y2wq#%7zz-$ zF1b~38NUGk%m1T;gJ<#cMe!rY@$1lEym<Bx|MP#iz7anvjMv#k{PS5dY_4yu-^KBD z?qDK7Lu7oh<aWgnuW-J_WjW(|&{L{$7^ThC;6}A`o2Mi8I${hTKD;YmaI*0<w!YQB z05k3*5jOFkySVzXo2csQGEP#?)No9yexgyl0x6K43qjt0_<@#lM<oKFVPD~H*;*0` z)^i)G#1ernX2>xx!3elZ(?0wH2Zz9S;ESuvqYtON0Hef!<s}Of@!+B)S`;xH6eBB- zz)}I5zGYETJw}6yTml6kQ-c~aLK%!ekB!j;4Y)oCrOCku-@)r0-OOr8r+|j}=lFvl z2-qkuLU-F9gH)(~xRhXgTY@koeb~Nb#b))m&`zo2H9{{a$3+pQS&+fiV{em!Q_>At zdh=>et01MU7T6EE+YN^S_0SKIrn-GwW+RsCM?q*gGiwx>4tk(YH6y4eE)98fuwfCj zuj5sT0Kxq^r7~(}8^RC-R4zKQpG;Jikz1Oqg!(<83?Y-0E?}Kbt>9`GRdsteKi@_4 zFTlM}T{D)j=mnU1%Ce{8k0|3&x~F;phF)3JzoB)sTI^Fj#&sSU(=N1M`~pm?rrITx zfpKhs7hr|Va6iPJQBYIz=(=64Ldl>P4=wCEyeJsZYsPyik7QhbjLeY#r0eU~U*UqD zw_o5s=wk!M#K8=E+-dDzU$@`MLYI~yQ}6<emp4s@2trHbzyBwH62*Nsn{VE{ZsIW2 znAT7kpr`Aob(f|$ph`75s)Ukh3v6lwVbF&~RuJ?(72huC3wRL|@G=6eIBJVMSXCJ_ zWG>`#qzjcxW6i3JB29vF1mtp|&8YWb^>Wl9ZAycn2Er#%k6;A4IqCMojDV(wii~uR z8qI)c2H_wQC-VetI1P*g4)wHw$J6{1x+L<@0NuV+1!V<n)H~%CWjHi|QUhho5Hj}t zbP&`RDtpkFg~fs19=!ow{0!NM#0h4Mdg0JTEL%$jz@S>qbO-F|(keiD+*fONN?Gbf zwRVf<pU^FPKyCv`25|2&U)CXxLRnfE8Vu0%E&s*Eg;Im1>$$)_BC}|&8*-W9NQ-Ru zUYI<)JCutT5$u*;p;~=u?M@*Aqs$S5iiw_g81%?0(d4vZaf(U=yZ~q!M#IAaf(FDX z!ZY7{X|YH6n}73fsg!@`fBnC@xVZfA;luIC@ee<|`~Lg4A5PvM9e=o8yIJ4hSlnD* zonK$&*X%apCrx;BB`0?p4ip*1P%%0@UHQ65*EJF64pc%*sU8}J(uKR}-Q`vLn|^>h zLl|6KoMVYi#V6GD4X@ezR29F|IlgtxduskW;9N#p4nF@UcIJ)j{5K1^UnMOM4i3-| z84C@NDFb^(84~mvD$o+82E$PN)@fs^47UWix)l?_70{*hzR)_#N&<K810ECL;4qql z18(XV_<D@Hj;5F<8d1fMTJ=*LokCt(M!{U_m!NU$3>XI}pr<U$%hufmB!x6dI(r33 z*ZXddL(uvIQ;jggCUsD!!ZeiKY0LhZDwj|xJ_@1wXm*P}PE#d*A(*Pr*OI#akmmQ4 z9_UsJIx2^0hsvTUyVFFC6;^k|WAz@dQE;%%DK0|Qpd;OpW{P?ZK;;zjmVvFol|LWi z8xWb8PSe90S%-|(MOLY%+C|(g_z_}bPN{#R8_5Rfmc88)C^=1<avHXVG$X#k2yNzA zGBnTffHkDqUHqwqdrh^AsADl|7s1|aQi8kag;1?Rzu(j-6b^L;_gkf>9PO4I_xrpf zgMw{c&kG&7VlxB?bkP$Tds~!Th|pU(H}f~I-=IOyy*O{j4YFWB9F2+NOvz6>#S_82 z2;@S^P2>;%+Fzsl`LyQ}TI&O}<R}3Us>|)1Qbvb|2*Whmdjj@outWn9cZh&qW6&M! zs#l}Epv=W@j~WGf%=)BgJQy121t^=;y^ZKdYYKBgrABEMyETQ<Owk_8z9f`wcpzgm zu%QNaNncFWP?T}&r>04Ri`eZ)M_{8p8O=+VHF4dLX?qxIQjYcpE#k^BLC7*&oh?uY zdPXsG0cT+du*s-_p**+-5$zd8FDMNTj)KORDL}~zw19io*y8J3GZMN5OA0>r>04f6 z9D{?w5qdouHi#c;=flw>QU;6e^kbaDIAGW*HKfqj){`-6HAs&f9}ni@Pb|1G(=jwX zYN~}iQ1`not%BAccB#f-aL}x2^LoYl*Wx4iPNEs~USM}hKZH!=(jXhzEOdv-hM}KY ztNg`D+$uJ%uCDW6&&EHdJvurz2<`^KlOXI*PEVtmv4;`=9q#(t1~b}!cKG7O3-aIH zUESPXUf*64<1XH9uP!eyXm8>l-d^*1%;#?Xwm#RlF~rNJzsiYX<DdD)FSz2e5ZjD4 zLfvt?h29|&<$WMV`OgKM$8V>yw#b_BvInd=HcWx3A;$#Q?_VTp;slKUcmFz?IM{>% z7xs+}4&*L}Z+m-hXGa00AA&MUo9D!BB_$N49UmXRfB*i6AAX>uiY&+|vE10&T*rH3 zoj2~AJC=p31J@UxELi>cTSoCmAlO74pZuL<)C~C5q2VymMIfw+7-IYJ-urX-<|p5L z_2t)Jy!qnQ%V+z0J4Cy^+1^<9v$eifpUwQ)fmsM>y1xAcaHP~>+1tK#%RUNbI_&m# zUc^ccUyV`^X&cmvnGW3N4585mN>0NW9DNicFRQW!Q4h=GYuUGuMa>X#XTkSlAA;V0 zlJpB&^!&*+cN)ux-nGTd(H<RZ@k<bfN|3CwrGpyMtWa6#HKh&zXfXYrmUVI7uo%|4 zKFn>TsZS0zviA|1>4Y{sp$;5qsoaL=m>tz?N*i7oXFd8XSsx14v1giEvzXmO_m6%a zi&yOFr!MAx;ycl{3%10f&yR;IwrD+@G+}nAg7ndpJx4rQ#I80|HsZ&%;^R|8{EXQZ z4-VJY7neL%py7_bv$?guv-@oS;MuchWT~VzBVeDq)oZA-YX)ToD$_MwsvCAsLH>+c z{z4I06g^5Cii>-Gch@iDdT=4mb-wY_MOo9+SQsJ*0!oH3K+s+@T8OL<9l_Lv@kvUH zv61WPWQ0YE@$~{i^%+4;CTaDI(6|R>*-te^bxX)eG}J&vkPLGlN7=T_6w>fs-;b6I z<nmzA(q++jjMi7$N<Ccg5r$eFlJ;d7WSW8@Y?iD>#R0m_ZFoUdM(-%N0YE+O;KWC0 zAQ>jeWe5y{fD!|PfR#+~{DRBmJUKf%GyW7KPcfQu77|cNbDL0gj%dTHVbYQnfEt># zGR&PtaG`MLOk}_DZm=j6+tQusky06xA9jmvp}`b_xc<Bac?ghEGL)0MpPjP8ELH-o zpWs4vmYNv>!jgI%$|Do70=%akCJyBx3XloT^pB2?PEJnPGnCz;3>+Vy{OVV~`bYoh zAN}%|zvR^po15F~oxN?|wJ*6ZU7d4s6XW`ZT^GL}i!OI91izBP5Fg?=5i(K|Es0J} zk6bPmiup!m3C6XCu0sUP!{pK2-#d7o92^|b_4opom}v?45&@_!t8z)($>=EO2#^bV zl*XxbbEyGiMiIDnv6#GS(vnv_E?Cm_Td%CM%d4+cR{<C2CDv92KnA!!j~K-UOD9Mo z%0o%z91)fgB?h(>Lm4k$zWnmbFTeWgtFOQQ+Gx@eBrW<<%4|jZ5qLRqh?Jicq*e*p zAWVdSbX~U*?kkUe`Ie<MRI4z{?9gn+p7Q#r<#KxW&kR-MbYt(e{)E|~I2(ualx|J1 zgejRPMimN2mr!OU{O;f`vh8WZbBsop&*;aVukov-QFjp<RIBh~Kt0m>bBso-m{C>B zgZu_qQjbH`Dm*Qtu+{BbS+t&yf*{7}Tkx{qQ`hZTqRIizGOpWPbGU|cx5bMtH)|eL z{F6x7Xuze33%=KUuTgoUYj?V7WKgLAs6n9Z4W5eipZ)YF#)as2Xfc8bGmX6J#*~;$ zKIc66V}L!2)|6#xX}Y;V9}1xij*pMyC?zB<8)eWE?CL&+_#Qt&MrkNt|2SG`{2mc< z)l+5)=B;$ZsnJ;&%IfaR6P}jTNEra5R7guMX6-W{iQ?HIS5J**T2d_mIW#<bA-s6; zf=!8Dh?yk>$b=GPQix`@fF(*=j<uQ*?0XEzMJ1TwSTSe805cDwk@Z5>5h^>Nrz>=| z2j-grVpJEq3}IHvipI(~iUwa=WHiW;W&#G<8w8Dq0Hqq0bTwlg=psNb)bX{9YWwxX z(m3E{!j>U4CZ(c2uR}N*aLV>}{L(Chz6GlSG~iMoEZT=9jG#t_M2!KJp_hTjT?%Fm zJ@ja_XD2%&l<Fx7m^G10ne&c1RT2bQOGdMbC<EoFHMpZahSjkw5y+e4W2TA9OHB>g z`b!-U)RbI#?RLZlMz4X8g5yF<cG`dZr{A@K<iGOsZ&(k6n>8-8>u<hz{>7KCj!%Dx zZ!KS)#BJw_*I)cLh`qaY|8K~t0xxS|(h)1UyB(?uAC@JiOg-*E909>N3|TG50%3Ta zVLQdf2(Rrp(8y`t&axaL=;qq`*3I4e)&^JFoxPo16xaC&qIkV!^Iyk3lw%!xvi(A= zP(={*)hd_{+**MC^!(C`5(dPhMMi^6k=4bRE}QV{FTb=@y4aAg!j=Fg1=fcad%N1u z5|f4Z!b>RbBS%L^ym;^K?dN4XzKT)niNU*f@38#v;RACwPE4N{>1WT;V2=iSAQvu~ ztsOfw1$)<_5xQvKw>1}ht6hR#3S!szSwcjpA!?1`he>J4t1+k%j}+0=J4DM;XaIE6 zFTg&nJ{K~!=nvy_9PO4;fdhds1$WKBt{|&)YHFfQ!O>oDUdps3a9>B5!WPOr_gmDi z_oFEWoJB`K&ddR26O*bejC6o<(K;~Hq=y)`7nVcnCOw2=XdUfak0U}%U=V1*S<pfa zEjnLnJp~P3wCvEP8kCYljb0z$Yn+4lO?n8&uSpLvEVQ^o*<9%qplo2#`Y-x7zy!?N z1G}=jd;d#DwRCHF1=Bd4nt)3ft&GQU%ECAc^cDa*misk#m!uLoRQ4md3D7#4eh=nV z-D<f>&`#;+)z4+od`%&C<u+G+q*tTh;VAs2k7WQFEZT3|TkUV^f{uc{j>v}M#E;w0 z##;V+rFbgS9y8#5koy!t!X)R&l@sOf{oe0m#t^qZ?s2@nv2)NAk*u39H{K>Cgre;Y z042fq_xE|2|2u#0?-}7UnLjE^h{vit2Ur)Xp{25ZN-KgFEnfXGKp8jx;hQ$1M*Bt7 zXqCZ%BrF0$92-jYTLgr12ul_;4(;&s>ll}N)q|k1ZK0Wry0hp7c8M%@i)J){L2U)P z)R0c?1yUu`0hFbQK*Nyo5)9ZnLzZd_&8Cplyn>~Utv^981vMJax@cUW!Az>W-jYgO z4MtU>VXZ*pDY{R=(U{0u64T&N*-Kf*P(p#_sKs$gMJ7TlYt~?vh>{q5nqq{ZrnKP+ zR`to?KB5f_Z~}6oaUh%#<#}E+G@T0?l~`J~0a5Bz#L_3}H$#OQ(O0O!B1>^}mS!;* zvln`LOVCDT4Jp+0Y1J28i7zj?RL0*DYQ(?(U0aV|Xvr4x(>BuG+D-o4lA(CPYnMUt z<mWznzzh6M+|_XR^kIlD3r-7KArQo?bUFoicw6xw?dHLOIO6)+PcdrXhH`cu-{M9l z9oh=s5y#h6>RWJjc6-O_LK+6h7(1gLc4mF2oqKk_uNdv)(;^!r5+@m>b)(i{ZzG`L z=E6N2eYy9%eEIU#t5>`*b9=%7FO<l<z~JI3gHYd0j%hpwt1_1wqJi=!)353hOxm|a z6!cIt%dE{Rjw|xf`29?uFz-iMF>eiF&tc6y8{1Fi6GHsHq^H8&IE8u5(%dHWLw%iu zqRXf!LMatKfn0`}by%c-5-RfS3Oq^PEdM?ZyU4Crk6OB7(Sm;_dGKdw!;fTkxt8;U z^I9eQY>Fj$8Dcf6m0BNU1#qZ!CX9xbSW5hi_#7WTd^kNl^`_}%=iuPri!Z(~Als&H zj;sd6>sI$1Naf3~R}5i>i{INL4jS%;ZTPbpZ|jf3RH+!DW`gVim@XodY|?~&2>^jE zN@I>d=?dzLF(9ZJWpRkMB3BD6AN3<(V@8(Ml}+zZg7$RNDX2K2aqA>%7SY?7f{c|E zG$_oaC18NYs}fy(5u&oxmquR$x_dJG15m1u&;#o6owm@7CU}5Ijk}iM4w<F7%^f&# z6r4`QN7kSUlX8jqKm7Irs3bzuPS8x6Dlujo=!V=s2pS;JMQInBLkBjaRsmeD5$LVi ziEE}4;r$?I4D=yPJ~=i-t5zXHHTs%ss5B+a!4Z!SE75;SUmuPkAI~yoL`;ie-FR_o z!3Lt5Ov=Q|(z5BI)TS(paPEd|mw<uutywPz7qX8qj-v`dz>L}E-nV>ei4;^e&jBNV zt0c&6xFZ(DFVI5#1Ku6hY<+|Mv%a=T!Fidz-~aIr9IwH5*YRmT2t7}vyvuJJ5Gwzn z)b;HR@7lEfvsgcLc?Ungyz<`@$G;M4|GaABc5U51JIo1_pD@mUSQ{4#4t*Tg6u5() zp2k;*nGKqpZp_zKm~2F6rSos)mdx~WqVeK?|L>IZU7A_oNb6bwU0x%(g^>%8eX&Gy za&~sg+b?G~4jfHFa_Z&sB9I<EpQxi9{CWBvP75lTItvzuWg~t8jKbFD#{S;!tCuf+ z^7U6=fAuB8-fsNUV3IHe9KGvXxdCGukAc)#SKF(W1de_hEkx2(bC^*|Mv&R=EX|?= zWlKLnmq*cpcAy+ZQ~Ajl${@=_Ey}BY3I^IBvqRW6*NI+Fg}J1u7GOO~(5%JEnrCU& z6LeohZ&2}R(brj^vKg&R1`9^rVx+e_CFU?k8=hknZPwVN(E2OW+$QzMHFS8+@tOv9 zMf)cwlh4qGSEesg8SKu|ES`E^E$Gs)ZH66fV2)-noa_afW|1~cTD+bkn)R@|s$hqD zgAsdsd%W@P4}YVmUJr302xlA*CiUQ_UXV2aMkCf7`XbbPKjGwELOf7D3d*H!X!97B zMxnYeG8^G2X3WPasj2uqxk>@D?wKJ#)1;1ykHC^~RCv%i;}Pfd)KSf}Q6PB4&F2-m zR;8f61ki;RISt#R3Ccw<Dy^T83r&U$cZDL&+k!jFT)4L(=&QbDqhW)AG7ot=jzB4T zfuW#TOu%3k_P6eu)hanUrP9GPqZ&tHxiP2&ZKgQdtmn`GlvP3<R$<71$g~zFr7SYu zeJJI=1s!cAeDZXlrORm#>UpTo!3Wb+vw-`0=v1p<0bw<OUL`cu;I$&nd7x>#Ad$PH zSN5aoL77l-%^R-oDDzb>E~&QSPjKkcw~&WuyvSg{QK`Mb2uByujJkC|R^PYcXituY zfxb}N&*>x6YFy;Zw%94{vzB)e_akpv_iU|i#z~sSLmBy3k=VB8i4-?pifKb2Aj7=x zat-mzyXbY{|D=f+ckvTej4;X}N`v*g+x+AdRCcFP0|j9*@a#dLn<-+NwEjgUyAtoW z12qc-W<?7v^58;!c0tP;ML<KVr3S>|bYoMomwfHajTT>xWe9_e6f+6mjD{e+Y!KaX zWXQWuWdVvorbVUzTwcC>`Lmz>>=(cI#aCZ_75~WS?&feW{w=Y_7`Vx4Gsz5?&5{XQ zMxY+Bm`}q9Mbl2Gj3vNG?z_J&W@|v%rq@j{>wR>=qad;*j`q;{tL4R>W9oj6b2T3l zW@!#9V`>~@_YeF3qxDSbT~;Y0<~&Cmo-i7XsSc=N)Dxjs{_ZndYCltPQcGxdiy4`* zk?7W<(W*y=UU*szJEaXjp5Av!oJ{hFd1*GK4G%Q!3ISKd!{nK$AT<Odd6qW3bay$r z$V_<q<%YGJziQMQ78jrT4lP}7UgAdb%gtV(&~TUZCv&x*!VqCG#>=09A_!h>__Jx- zdUcqm=~;BD;XFaeB?`2GIOd;p)GKD;HQnXY#$2Z8Q7=uE=qtz-%HY7`7s_%}X0&oa zW*%>7^qBPqi)e0(*Tf(YbM78c(Ab*DFR`cu0<yO_D5cTNIhJLOR#zb_YSic~x=iVP zLE|M@SRDeH`f8)u2n|L<DuK-jtcl88%Q(uKP0`Ej)q?xb1;or^JdGvJ>8@+EBBKUI zQ>Yfo-4>S&6C01w>Kdw)Qu-xe)5o_3LK#gA2)z=T_G4K@-wYg-Mt9@5m>df=)FWl4 zQ1o$1s4g_SVWCRdw*>~YH3WnjMXUBvEOO}sRtx5ZFiHS<L59B6x6V+Quw1>+EC#M_ z+r#d~Rs8c=ZV$kgCkA=KBEQub@4ak?_%*}vO~?4w@LKyuG$A=AH`nn`h1u!dC;mhc zHdmK7XJ;2@rvxTjM9lZ(_^XDt*o1uJFD+|Fn2#}0)f9r;bzi&*ged~Yh1(k^ECQC; z^ID4Vz$?MUg@Te1dYWlsx8HJfk-6Q%e*Ug31g@NR>$>4q>4O_h!63G?_+n3-dLY0U zB`q;4g#r6Sl=1rYYhHlA_~MHfFJ3%<{v3A}1Ybt0JdGcPDXNtm`7E4o>&#J!6ksGz zyHncmgg6p&G`GjlB6hTa2}_0+(aIVMGd|c|5$s!(3C&_a<?`e52^dzIY5~q}N)2fS zMq^9Q;^>s-JfV;LW6;vCOmmyyB1~z+6I!^WnGQ6I#~ht0&24aOogtS>XxhADLqGJi zw8KB44X=##!$@AlQ_ag&QZ`y<UKm#UDQ$Qu&2*q?AJ(9}94*08q4ghzn&sr=<ml+= zH2=CjH!SXADDyd_(IO6%ax|oVN<I?AuB-bg_jF!@+VE%d=oesji50s#;E?oP%rsa8 zHnH#Wfj|wDWU4%!@KEAoO3mE7dWo9W>ClED&K#Z_e8f3CJoMLdYrp|xDSg6#s=-8Y zZ_n=l8%L@J1?>%`?C301f>$|eucLAaf~8$-d|1?guChb41Z0lNWt<m{_A64$z64sx zy4w4Law(_iK7}E?S|=l;vG`dWjffLRTj*^Z1@#c+CN8Ni7%*8tqnUcpz4RqWGa9mM z3`T36E_)>{JzbQJ0vaemw5%2|z!B0ZNW<nh?dl6tmsy&{go;zBN65M!jH;idcj-}? zCV^(OwVrmF1&hYMMK02#p?w=j)NsPG!wZ!N+Thr?kZb&4#cUUqx(F<1VJHLN`>HQx z--0ehS}}CLqY9^{tnmomQFChd?`)ub!gYXdvrU<p`F0xLnC0d0_WCM6@pH-R@r~T8 zyX*KD#qkNV>$}U#>x=WN^YcsE_%&DYPJ7E+G5X7k`sc?HbNF2i937%X%($w?7wh~M zaR`C~1yFMQnysvl_g^*x0v=iI3{0(rUXBn0rK}+rP(5VoxIBv8vZ19LW#{i~S11F~ z1^pfG@`G2k5ML^2-`tLOdx$sJ{E{)6k_|=64USUrIy*ZfGWV%3zx?uNKl>Rkz{oC( z=+ZhXgBK{12q**8d;$h6nsx$-O6X+;==HxvW@|t>nq3zADb-GwXnCm5$*VDZ&hZ^V zG)rRdxnluk8(x{L>)wkXw(6&3o*8tXMaR||R<bn6);}`)9fyLO)M5R$G09;umk@4C z8JTgJVi%DD<>=7&H0!6M#huWGAIZpfNgOSUrd>?4o6v?IA8<ulxFKK(-~ocZt30JY zrqHxQz&<Rn37RwkU*d4z&%0&(?S>B@KD>SVwnpm)N=$YXZ*$=8auly6FSNW}Gs<n$ z*Ea-m@z&jjKbuEiDE$s30{3RB@zH;}lqkjS6oO!k0Sf^LbWtMsWLzs{3eEJbEHcXC zsP;ORJA%ifs4hb|0z%2eu?u}1$W(2UiJC<)3&4>ebWQ3aXkZXwNK0kG28}_Wh7iyj ziY@|{ni)2tKLn+E91Hb$A&*)x*AzpQKoE?{9uenYRKe`DqA#tZkZB`t25z%Z8A~~= z1C|<K>Cv={aRn*kDTWmtB};fv9uQm^As+U5w9j-X%f9y#4f<9A-zk(t1V#(GRcGW# z>@un_#b_9eT80onv!XN#eU^FhcMI32{oreUMnmzVxd^Mo>?UZzX!0nvos5#9Gz_$q z()8^tX&6iwp&uP#_7Nx-#_Z<aR$vfnmG1Qq^Ae;mzO>;1l`PI?ylU-k?Znp(TV+{W zBVU?$1@%RgH&s5ozWN3`y!!H<8gH#!Mff1(3t*g2bO}a_hL^jGi%Z(`_zT7e+zmJh zIO*b>oV*O@caj^PAoV6W{5Rf;X{ea07zK=Db{zA&_)&l76-6i29Vr#sY`Zr@hWZUt zLw3*e*IZc$ubp7`Zhei3vH*Ss00GU~#yT>3K6JGSgZzT2SC#3tg#s!yg7rXLvxdvE zqksWjU04TXUWs46eEH(Vi`TDTfAPf^$Y}Ih0ug2zWywOK61_ed0!r&IfQ(HV<fthr zrP!U)h9~wd{RGV(MT^+c26CEB8q8YfF^qyVX(`jZF}FE-8}Q&l8=j#3C$OS>t7DF4 zF<>;qPI2E((Ra!y1rZcj5cCxgfi6l%A4Qb)kmdSWvdkIU@EoInv&QCy)?b<CHkpgh z_Gnx;L2tF9%hO`^DQ)<Zu+-%R=Y$$f^%S&-i(|IwP1fJ;l(>9%ROH@eBrl>_Oc+&L z#`ULw`_Jyy_WsT;E%G(b2B&9N=NEU^aU;Vk9|Yn_fX#!3$kr?oy^B8!W{lSMLqi0= zi2Nix`a-}H1M@-P^ziKzdC3G~atmP8g%FL8kB@o3KkJ~2QiBntEWxl)n}da;V4iY# z^Z^e^zo1n~xDB8Lls(4mw;kwiy9B&+EZ-`iC$bLpXxW#FCT?!s&-XePMs0<mN{3v^ zkvt17I@%Ud#2f|`-2q>t&4NLb2K2QZVG896UZ`Ox(&r+0e9Hx!TCs9b5Y47!-~hRT z1Kr9ZDz&ujsY*s<urWl-ocBo)Qc(}AX7R|HYqo92%kuhmRFAn9v3zuj!L#sj7M7Y; zRBC3oZ>35Nht$(W$u&o~LpLeq-nU2nqR}F9EVZ$o5h&a6!xRj01V*2AZV~w><a=fN z+%H}F=l4cwm2IcxU0lYW$>rLXe@*wn-xwIk`_S6$n*XLYzA>BRcYV2vUtPxUX1cvu z$8h*y8XsPd<IR?0*W(qP+2iFmetBW6Homoc%?o1w%yVwA_=)J)Y<$p!SHAI@kyq>Z z@RrHTI*UR5yham+TAfs^Qv4LR-~4xb<jTbRCtGL}p;}&0BV%qQ+VJ0qRl<u9p{=mF zdUU-SuxAw5mI{%rTVeI=D<{>o86jtP6Tf+DzzE9w`}@1Q@$*XFcKC2;kRy7U&>~jN zr>Cd9RPV+QDeX}e8q*yf?!SKh@|&-|{^E<*&-M?twl=oouTX5n@~quX+J!`#ZV`ks z)T|C(P0E-}T8xPls{I@?-sc8coqmp=pEnP}#}^GAo44$9dG0r*%BLdBZ#2~>F`5z4 z;{2V%TvM9oV)_)=vlM6$46FVV)@L?#6tqC!q$i>Rjuvpl6Xx}r)-T<X;7^#>TvOWc z%20W~R=vDBPc^SqvXg6-bUCd?uR-YDR|%B~$7U6F%I*5h=j8nC;`%DTn7={0xwHM^ z^{b!!?5Efp-y5ij2+mCr4WOaRnaE8RGQ$jqhlku2c}zG;aOYO};>C+L{MoF3`NeCB z@PWYVLY5tMH;cqk1YSoiJx`E$E_Xf$2M2md#%OcSFiog#KROyh0MeO}79}s<o(Z6t zqyEr&rR#+Z5YTO&>8p)os>sWb#wayI&jf2OJ&dwqv{M`f!`cEdk%_OyRYJ)F6J5g= zXxI}77=RjKzN7}+{bB?$sq<?1yUNXOh>4j>M}_Xr@Ry$eGqcd5v@it1x*$^`N`gU@ zm=KDtuw@+uEls477JCwvhHmVqZbzYE2m>8y%eV9hwj~%)bd<~dxkQ90C_%0ig^qBO z59P|uAz{tY<7hf-M$hr`+(yaKp`{C$&4K}K=4=yD!|_#VwP8ApvXMDc*-F%vkJp%7 z^OTN;g@4$_8tMgfjR_o=yx_zeBmS77%p?u%Z51>~??AZ>Tmb|^Q4{rBxl1G%W23LQ znCQ=k-<M#(J}l8{8-QUE7@~e!WDJBg$3Sp5J|OpbOV$k3RLglmTXBR$3gwQ5;IwFp z8iG6!GZ;1v#%;#XF^(e>Mb{nE+h6@z`^h5t`l~N)?_xFZ-Q2o+@pAvw>;2t>^^?<g zN2hVC*jV3PyW6=qzrDD)+FFm_P7&YiyyQKYL{!h~RQy9<$X_uPFXvn^vJ75<BZc*h zTC1WZEgD<O;7uOK@XB9;WtSs`hFNorXmQTn$L(f)|6rHH7;n#Ow+I`XY@w(uk0)>D z1Yv1d=BRV+E~d%L9<R^w>!fi(87mau;pV^D#&_1E4qlJ>Zyv86G%gpAgD$0Ti{<9^ z?%g{KsE`&Lwi7!6K`)5{5`?>}o9hcMadE=Z#c_9U`}y<dA3l8GHFalaj~U^TYkqlo zbN$c$*Z%AO@IU)UdpkRa&!7K$fBSF$bN~E5|NFo9d;h=x^glh17vMV<V*l`vJ<S_4 zGa@_JbKEyMyu`U(dw=x)&wlx5zyAK$Xs&PD|KfLZbL8TeZ?Em_A6&<G>Ek={t~13` zYJ62=mRPwqwb2}#^bqFUq=)FMSKk6duBTn~u}>a@hY4SB<pB+mbG#MMPeC-ZU4r%W zL2PxL>KD}?OFaj1%Dn_y4sj{PE^(L|vqr`jGazaFkV1kPFeIaO=mo%F)UrLQTLNwG z)x#)59!G7oSA$H!&Yj4V?T_>WqaHi=A@-t+26VNV!mP1Ds8)gdZ(cy+{)Ml*-Acl3 z!lL8Lm163G#!-j*_WI`jd4_II<$iBZ;bKQSjq_26DXpK5g51WKuVWK518k}V)>C1G z&uQR6L8Hsn^@HazCaW2Q+XR<o3h{Hz0=ljn?C<T+jhPH}DoAygWR%{khnjITZw0}a z4Woe?TW~)}bO-t_!o9)T{Jv#sv}IO8+~tO|W@Hcp6EG_q$r9rFfUI7PF}Jpx-k}m$ ze_A!8b{2*V3wC9DBObcgMHJv@(|7lGl-v!UJ$uIe^kDDs#fw+m1dor8zyJRG)A&<K z=XJK?&HpnYDdH~PzD7KE$h-iiS0p6`x8}e1AO45Be<r4Dd)FM6=xj+$O1hNJCD^kC z`>5_A41ueF0ggoQY0}^;f)~D)<OPmP9+VP@Nk+3ESBerq`w?Xi*jPC*#AJK0v>guE zy}h9_$*SPRVIv@dlcH6x!4&eE+HNGy)GRWq!E1wWyiOBAvnd$N;sF(86XnbT1LnLN z8Eg!Cs~Ry|k3llne6*gjF%<1=%tHH&-KYhWQDJB_uq&e!x`29&IciZyH)XrP!DZ`0 z?4Du&&^6R77B-SS9G*ulbY>?PO>Q2qHNFSNSAWn?+JzWxirJ@>-b$P`sk5FS>K<%R zmOMhU9@ihCSv*9&tu@<b{s*ZI0xEm@QRwBI&6vJ^x+9?<D&>e_$bE(V>K`W6AHhX! zPwid=A_QC+Je^yG>$lt*cXzk*&6bZVkUy**Hz6+W8+@D^ua|rnqsz`lk+X?gK*=nT znul%VGKg)EKi$oZKi*37OT_DI+kDpUw)~!Rym8k7iFfZfKpa~>8IVbZMG*x@74em3 z+V~AzybtHlRX(C!-FEG8W#eR_i)mEZ{hfJRuBF_YkB*KaV%`O~XVKEd5d&Hyv^lwp zZf<yMe)cThoOgEfE}2gS#LTZu@zNVVZA5S~==<%r-|{GMetG%B4?pbg?<0Tr_APJA z&tJae4Sd_*9g=?$>cjEz`=cWw-d^8ur9V44rR5#>;9&pt%U6_;zu@dH{{9n3V~slF zw{B*x`(L%iEP$I%6g`JmC)zljhD#jojy@HJ{T*j^)*Q82+VF%p{0nFnE5qUN*zq#S zF`}!IZRUlyN0&vIy>I&?@(HyGLE=_7JR%BR%5D}b)21<@>ZC|u<vkM_qMN5!fIxTo zHp5`l!mLY;PF=9qrM5w7o{;6`{diQme#+9zOYrDSX~Po;Tai~x@j3MAer!g^Zj`ql zecGeEB(Fn#`&hW=`YqqlCx84a9vA$ep^LIE4yI!##C>si0Y-yfB6xQSBYTSBLQ9+q z0-XMIiEQ`tY0t7GFtJ%{<Dvv*(cZSF%wkRn^2m1;$c`7SSP!%`6QaJP`9B1`?q#4{ zUFtNBUC}^B?q%<&IMn0x`_>JCKr|<Xyd+MhZKV<c%!`0~UHXkcx4EqhL5RRJlMi`@ z8a)qzWnf^ph_bqZ`|_G<n7C+MUbek}vG!>aN;Q%u4+4sox`+kCs9QVMAT>&xks6t; zp}mfnu?VbH=?gSC@&L+Fa6OT$YuF`ZA@?=lh!=&mej3mv3xY?@<3(X?s%Eq@F|lq1 z#Gys#0!)^q;>7Wd#m!~ZK$kuydfG_S9gaeqS^6NwG__>-uxDsdMm3@t7>!nRj7*6( zP)cM4$Vf9q_BJCjSd8}V5=<dYHK1lR#P*=&L?*Jkg;5sGH%#c4q6AzNAj3pqtOl)& z<i4wM3+2B99|F=+14H@d9M={s!wTd09!a>+7IX~`WeEgfDr|oOI-2p(`~EwSzmJ*^ zwwy%F9Z*||aLRx$7_=-DqnI&7MivSUEix$$LIg*vDu{Pp-c7c78)wGM@b>!d`ts(| zp9H(Qxx2i+<#UVE*3RzE{^{vCdH47Cxh(v-KlkSd$XhGXvc~p8P9joJ0EJZz>e0M< z_3E2%zIpxn^@|rTh(k0CK$n_kOktDdUdun;yzu<OEY>k02pZj=9D_?QuSm>rAQ!&T zhCiDMrO<a>(!K>pr(iIPqrIbZX`KnWVBi5lz?W^HJVmc5v!#}@cSJdBJjIMfUmj&6 zQ*$$2nb?1GIBIPKCxws&Jp!i;AYf4TQy6Vh$E;Eo*_$Gc=m6a%c^5&bSsc<voas|x zmMLTzB|_Px$IupKLIpRSGD^Fk<~P7^Cf#T;rSdvTTd4muT8M$B?J#dYG;6jxBX_zS zVzb0a+wRMCwY-08z>?b(R|s}o_wW_4cZ>k~a#9<CmY8W{gn0h6`&5iyfD0erEhX&o zF3U|9p$A6`^0~oibn)`O9!VYpc>!N9Z3HJEVd*kz4L%>xB?~r1254YU5NiNsgA^7o z8Weg#tVMV8Yt|1>U|Vrip<3uy(ix@U!Z>|Wz*0xQlZ=KT-KmymDb1#kcNQFTW^MBk zs*Z1zl{iETYBJ<K4gqo*s8O~R&1h?C;1HB$uaAfwDy3|+hnmhTu3jHUy|Osk<9<e9 zl;EtJdZU3uz*gZvxVG*byN*sVbrn$Enu2<|?na}bw*b&yv(>4ZGfAL+5gIG#oAYif ziF+)1)?6CUrBJV|fnK0;O4*CS!PICfjso;%pp98To1z&d{fr{nfEvN2*B~3G7o=G% zplte9;S;F5)&T5S&SFnwHcVYk+i(?}@53o0gghdn&eT~81!)qnoXxGnA!=~(%f->e zp(-HE@{EhO_cG3-7a*glA(aR!`xdN|HplOiq9Fxvx$^}WjlpTD))URhL~sZ}F9`ef z+tah-%d7M2o4i%sw%Z(zUZ2eyUK{zcy&r$)@ZjKp7gy|m_OqXHfCzhdc!-Ob5l4my zVn(mYM8FZ_=g*)2H2M1Lul+kon9(wXBjAF@N;vMT+!vf68XXsb%`9zr0?{g<GT8l0 zmL&aTj9D#EE$caI!O<x!<1CJ5l8>yg;KD&+lXw#WH>7b2gQIV5b2QU#QV7l>#{>0C z(5$=^Ahu3oscbgnvR|FpwR5!Lu0rRFfRY08T)cmF)p(Zl4g&>1&PfDm@?fY*os6I* zvMb*!p9BMrc*6LrP&LdJBMi+FOF2h#o6y{nrdmofozR9C)9ePC_D7>ld%?a^*(?$@ ztJ4Ru1<wL;G;;=}DFJ$UMIv;UQRw#Pg3v|jQ->!k<#{9HzQz#776!<IKCUJSqZ;5y z5TJ|f-3`l&?$0cJCb4k*$COS6N&{&YC{qVS?Za~9;Qc~CDSP)%CW^?{JX)53rva7{ zfs9;v9qq}|?yD-)I0|-)(io%{W~tG>EsRzz@GL^Lbo&P{x*29+oGG>V3e~pZmC;Lg zW!pA9K{IImp>p;sYpX1DQBI9*dmIw&+d!fQtgYE~G`okiu?dC(<<jI}U>9Oh2AXP; z9gU;NBxTC=sOrIGf7;c47OTywn?UPL9n`p(z~(_FBf$ZIE+++Mj{-+fCW1+q)4M>F zyV%Q7u&b}A=_#`*27%U3Du_dU{U!9d(rO$*77ew|!^$}vW#3e3sS?s7P``xo?b}bI z<xZAslpFDHcjM&Z`18?Vina>XDimsjV-eqd?d~9ASDI=W@x9{Fnv^d|vKMWB0#BAa zM4UMBQReIe&L%LRakzJKDTca3Blu$%zA>JiozZ%&CQ!_4zzFCGczu280&*5|6?94I z#J{XwZ(pF~p2KB~Fnl~!&5l49nG@N!VlEWai3@tmV3gWWGQ>m-&M4iNFJFH1%{ROT zzk2nGZY@`Qzt`VmHb4Z2rVyV*Op};c*1Q~jDhSxe{Dk<U2x7HQ0-=mHYIEbv5I&C~ zq9=Bp4%nT-v1Zp{&vB`1K6&$a1{_m{s%>r)Dq|+UmzSiTrF<a^Z`jRK@BUg!Hw~YL zKDC$&fmLGX17{FjmL<n$s31{dCp(264WRFSR909W-IqgcMRWUXTIdNa&5)>RA3rY+ z{VWD=L6fOQ)VFX?N=uM8siykv;T)YTsQfgH;37BG9GaB?>OX;zFI^WFxmu}14`~~q zr>g<Sf)*tjjN{UlII5Df+gmdiIy77cY3Xv0HsI&eE?A`Oa|4$c(wmYYFUM4)J!o8B zRVYK2?nO%D)v2FMBM4y$NLX&wl?WS3qD3yHWPk>h69IBIv6_Ig*JFkkLBN7(K{L=2 z45IxAm60+j%Tdcj$f8U@gCiRR7_yZ<DKKQ6JR5N=R0;*}?ZtN(W^p1@VpiRPU`cQy z(`Gq=*)0PyUPA+fvhVdMweP(gDw=knEc;QE)J9vV@7=X0qcpn-43!sM!#eTOL)tdz zX6%42#?Z$BWHcOHmky0x=`BY@&}7uD!%<2Ei%}?<_@kY$3IsPo1&4|`r7vbQHNY_z zWwMid7%DTcTSE#TrM!qw8DcK<gw4#YTb7`#QY^#Kic?_R(|mGveHU4KC^;OO%|{-T zjZiH`rFsS<OH<8J1{@kMm<UXhYZ^G^jZKff8Q17CEjDcX9&G$pkNc&lmFe4_(iiHX zuczd)iP=W#AYNA+O`~!A`{8_VTnqEWUwNFk{ph034EF*k=S%~YU}W^P#z9a|K(4EB zI)LmQjTSlo96><W_r~?O#l<bdM4Yy?#1Z3jL2dsY;w*mJnM6dug%&S{kvWC2Hv-*! zs^8h$*&z!<xIhFNz9on+n#04xFTecqCqMa#@4&Y=*Bk9$cLz+0_?DMbpP}k37wDI3 zgl1FP@B~81NPaBMbMS3h7w7#n4A{3O_2BkxSkDpGbF|?hER6IcIGP-_xGN9TaU?<! zn=8?47A;Ev^`ip%q2=gUP#8~ZKzYcNx@5mSmcAr%vG}eAdb8VAZgvaE`2{7bU*uRe z3V_T~D^y0h%h&%=7<|N{3ZIZlv0|=RjyYmc7SKB?qqHk3m(xrqwBZSTURzQ5<B>BC z?6#~A^EQjz)lKzD5W%*`p_X-c{(*k9gw-i`1+hy@qP!ZlbA;Rb{{B91C0xyzBTDXH z-br;VdyMPU2BXQy62VdAPk8QK#QoC%AfqA;r8ta6Wud00IX}EWfX3<c2ykRYz#xSs zanI%<z{fk4Swf)u2=skz5X(Hge3k*x9F0I}sQ^_>8C1Z+p&sq~*1H;l>1dIO+(IO1 zipmR)X4?4C0$O9%Qt0wn3=RZmOA(3<Y8EuwSca8rtX?ovshOx@v~P=;Nr%ex2(zY5 z)aUq2YSB!4X+;cWw9fF<ON+fjxe@MPR8;n$?7cANAlfbHvi`sVDu7R`YBKf=MD#;A z6ZoMHl|Gy@f%XJ6>>pD=Iz1YeqNXP57cp82@;W=$fgzU{K?5z*HPAN%Y#x3XbF%ZF z0o{dYq$n7*09Hmzx&>Vg3QLt1B7@jU=4s$!3pHdHkX80WB_u4%{3lKBTfH7j<?YL6 zYINOuL}%~NB0K9wya~5cJAM}0PeKF*7iY@skh>8fT?30jAUgv0EUw&q*w?Hjd1K~7 zThJW^>CNI7O|9MB-o;m%03~3apPsnJ)(MDQ(SQXZ6iRopV9cv6A6`2BARp)NqdGb{ z;q(6J=-r18e9)jjJ>g2pYcLUrLw4#MzM#2wL!Fyj>wH+}wRH>#pTESBllSWC&8t^j zXAk!FIG-s64dpVlv$e(Z!v5}VJT(kIMMA+bp**d)0{BS5T)0-FdG_oX@4(-D^UYUZ zeRZ(Ecd#43kZXHmeRJ)O&(``Ha?E)Sf=5YNGpMXpn!>=NK1BtGULG-W|LEtb$gL6a z`c?s0`BA%wT*Vn2H71~G(gHlz92XA|_Gs9mo(Z)5hqwzrbB7XT)YR2bW>MuFWuuqw z(AP<e3|c;lOtKIR2yPb62p~0jPF_wb@SvbH+7yF~(50Z;(~LS$lBlK(2&H)xrkLW8 zHbP-dngi2EeORX14@0Akq~0v6larXC4Nqvpk5BXov`k4;{b<Y{wb|6mkMBp(owiWl zQ%U>LS<8>&FUaK0R-rz5m*aBao%seKY~stWoU?Jo^4j3J!o8A*XzrDCIE8&4zyM=! zZJgkqTvV<NO3r;`u7PwZ9vg0j5%ei&-_hz<O1Q;xeIX@7biDwPSmP-SVc;d3ZcHvQ z?CRtLNqci(EeIHo1GzLrMqh=|MQL_@doZX_y-Z9T1vA}2gC4TbHq*|S6@yGNkH%86 zUnoVe7+U1sas+i+s@+PB#$$n!3V9HNCF>lMpTmF{D4=0sFNVK0<q)}w3^s$KRx4`S zaAJz0X&0l7L8j40RKSdVe`D*50Vf3-&(=9YdmXXFg_T!10vir4yOg6$i(K6n>oK&T zSt>~lMQe6<CdbRs^!Rb9Rf?U_u3YUaIFPG&Z=f)xKNdZ0cm*_eWu){=)*+LO!JblE zl!uhpNPy`mlu{!4V<sh^;38RaD?phW3HwA1VbOS%$hv@+Pp0p;f1~A~X$(f_Wml<M z$&sM-Q&V0FMavok`6ZkDd&t%he|*WG$KLR?jThsvOa^yuDC4hJf}<Wsa6|Sj7jG}% zqrK`??riw;@<&HUyww7FjIlHYzSv+u8!x<RObckv&oAD+`*8Guv8#*oo9nCFwU|@f zyuC~2xlc=vsm5P^&Mz=VY7P)Vu=GTJ@#4kv=g;G}N#{>XVM99V*^j>`yjzEoKxi=j z;)^eki9kI}=gpfpKmYm9|NNi-^8|Tz$XjsxTLYtont~Y+A6#3gW&eDLSz)1<AH}TW z6V};NVQclKXfP$GJ3||O$Ra&(s<H=2L=C|1rHhio#GaYb+~&Z2)b{i>Oh;$YC1#c9 zQJq|Xz-9(5SBKP#Xcl>zi;IAU)D&P1SX$T;jMleHm^EgOw9Z{h`GizD<NpRQQKkFn z;w&O}!3=%mes+ELN5U+v^Bbh5EYlh=D4Ob%s0e*qm^V!p+I#{TFDMy-TpsR9S{Da2 zbn`wFuPxehPM19zPHJv{fPp7CL%0JsL6m5WhB005l~2O@*I#|Xf6OYRq2(@4GC)=U zW#$G5OsTru*J~9tBPOj~hQw)rD`H;s+N0qSfv#Sqq~)<d*=`04G?P9NvZ%N1(WY8r zB8-9nQ}fuM=Yq>69wla!QSQCK6A8s*mWQvs<pQz-qr{{|HYqL8MJ5hIKzw8Nt%8== z5R+~$N$f3Teajd$rtLvPM$CwSeHoxMW_TtRM$3L+C=YeJ<)8%Ik+ICo5sFHH=QFkh z+ZUxbb&4biE*bc~FuOe4;i4H>SZ`C+(gn&;-?s`z0J`NxYFe;t%ow7}zQU4%)ffQ- zM@xh3F=a-&S8(H_S81FcG@^^Jm1%LTjFdsk{zpLLXjmq6nvhA$ixopgu&V&fh$XT% zy4WB9`YNLr*x?#r?9%0-Zs)ZyWD4*^C?!I!MEt8oWZb1>jH(RG(Bp-%xisrr)<PM3 z+QK0CDyT%TOFPozZX#V`hTUORNmo6%K2v<Qi|7yIvu;itnP^}%F6Nr`#<cD<WLotY z)3WL)rx1`<%U}K3cPi!et7ms>al>Hkx3<?`zj^+}m(MnLZmzCRPcKd>`1WR#+236A zx!c{2zkGIi!AsZ8?KPYE2ANZNJI*zZNR+o7@1?OI`4@)P<14(A`mJXQvtS6)HdkXa zzRk$W#FE8i+3K+iSh2Xxt>5hK#akjHH@Cd0ULj=gh<|g<_PeEJS-9VAZSMH~97l-d z%3m~1%*c{2@ed(_r`3bwg(E^;$2^^**qj=V(&^IdOTe<aK!x$2yS1Io_?i@R;lyV` z%q9OR?-p10jL59RD>pb^Tl;&@n317K?P-n+8U$+d#z#O>P}uh7jzyx3WgWJG#>gs( zhB2DU^Y~*<@7}$8e{`Z3FXfn>9G_C*_Fg1vFAV8QRcNLVtx2mvC|c41LM)C87=tr< zi&yiYO<@Z4gl9t6fWWOqVH6OJr=(x>VTD;S7eup>pjUNkl(phi&Al2YGVA8*anQ>J zp_ggPy(ohfVLh3V*cC428mtPX3^U3y8-|_2P?H{ly+hS1P*P?HN)PUzkzNh$6yuO3 zJ(>+JUMKYx4crgCMl>!|V#Co_HU%0+(|cT`sP9K@sgrgI`q~0MMvxj>6o*SNZ3QX8 z>(2~nP{B)BTxaNwEOuE>9eYA^8%tWzFk=CMi;0>Mw|A}1ifk7bg%SRp_C-`leQg!F z1ln33yCt{}%d&*&WQBb~>uBGOx)mn|=IG6&$?=EkXQ(WgiQW81Ko3&edO1S2TP}IW zX_NuD{-rPB>atx=)PUX5x>b9)zaL++&ad#YRw!9{jKBKoE3zPSjrB5%0r&Uc|NY-T ze74U~=B{*n%+tut(T5XmPh3AKm4Nw>kPq|m1@R5*iEalPF5qOrARP1bCpr(MPxg0! ziI^Mvewmn_y8%e4P*92nQe7-HHV6V;BZEUVidUKkS{4Rmw&HT5<W@u%8GCAGt$AVq z144$sUqM2tnZ?n*C8lA;qf6xuq4EAl*YXf%Im>@1h6`aW1225dvWOZ*P%h1g(i5Cz zDbg=+s793my#{qe0KGODa^clVV`%-wR4AY1%!M+}iQ!R6gAuNnqqI6A)2au$gpz)0 zJtjghf(KDwDLF&7e{+j{4I!g34jLj@o5x+t9yC+s6l@Gj5Ee%-a5PF8u2u*tmrypu zgbI~mA`ZLGXpSP3jg&mAulTNBbrI08AY~?w!pJ^j2X=dAl|6kN(Pip5GV5W%v3EfL zOBTd~E{rxQ@o-Ne6qaDv5@vDKsz$ZBdZQNF@Px9lh90s|Fmqv!fB^9d^!~lyy5zE> zS6?<~A(LizZ*8+1dGX-%L?0h%1?LTT#FAN?9Rnaj!H~hp%f&nLZf$JuM9mbh&1Cw9 zse)!I`6w(HVU16hXnA<sZ<PdA21?K-T^l;u78&o3hr`SKA_AX_iz_bqXQ$_<Cub)o zXG{eHb1`MEA6N0OpW019Sg6CpLmnl`&N1TVf>JM*g^Pn1PjFRx`Z5rx8D$>-t*^iS z`VZjufA7u9R}pGslLrM7F+_atUwFmJK0HP}#{aRQfKj`M+0jx?3(f_Oqv---P?|@9 zFIjMB7rBw>qO2}9XjB3km7hrkF}U(4N1i%byn0huzoSza(#$T7wF0wfwmP1G#-v;I zv~WYf)_EAe3bS28IhH-t)Qntc2@EyqH%OnfFJ{VU^wX-HO+hG+f?aIX)b;1Li#0D_ zoZ_+TIUBsX%Oe1*G&&HteAKI4K5ALfaM7zYGU^tk><w1W8$TsKXaC)I-+ll6_kQn+ zQSLa;o;`c{^5xli{xhK@Z<KM5^ECJC*U9~<7nA9x1ITKARN{i(=X004(Nz|9<FpvQ z44@3i#xa6*qsd!Odk{f0jSr5}7IZ5SE_4Zki`{Y*G_zo~2)stE0$J*bqz)KEv~<y< z!HhDjf0ony1u8yjh+*4s(n?I4YM4~Xy-;ll`dUdo{KVgZ1Pvh8E=LtA5e8a<amv6U zY|0oap!UFM;m`<&e8=<lhCn6IEat${>}IKS2+9m);5KW^1~m==OF>shkD$Ii5qAK4 zqTy(lQQXm}FJmM3U--~Ca|SA>)Q~|4Zk%*#I7+pku|(oI+HgWZs36W7+^!>oDVaYo zG6G5jM{y(wF_CKs&1gSMhPhuxTQnA6w?J>3=J)oty-<{ksQf6EJr-s7vQ+J#3Z;OC z$<Cr#St<horS%8M<A)M#{jiqxp`4Nz(bCUtW6EG6?4{bnDC35cS1{k~9{T#@$887h z?r!hy<?nEcpFqy>j+|3?+4fVOg{YL%n;`??Db1H&K0CV`@!8qh-f3SEo1Gd|G)BY5 zzcB2lvu7|rJ#mzC-T|_f*2C8A$xRVNF5a{se#lkAgHQZm`OW#|_38QL@#*Q&$=Unk zlOI03|Ka`ncSj$NPEWW8T;5#AZ)9F;zq*?H!rjd+pUd+L+Jn9Qy`A0b%d6*y&z>C| z?sFtIx7Kd&t}ZT5k57(29I-eYQ}Eyd8pv-r$G0VigSflDzkhIWKzC<r^KgIf_3M{k zef`CoH?MdWAs{YfXQs4a(|uiX7T4-WC6;=imlqL-?I9@ZumZ9mGX;(&t(Mi*a&=g6 z+=-dH<NmtAkclLd#C4<fp9sTBQ#}y|G;)ulQ)16`*GcBiVlF|i)iGc#DOt>DcZy|X zIj!arW+8GP+!pGDa!9jj{Tf5-|7f%{D<`T+^(=AMK4;k|<t(lbf;L1(!v!P<e+$&q z`pTEoA4{3E{>PXNwIu!`$jG`?ULxdavFyAU6}dbqp)fFuiA+H&nzha(RMV#Zv3Z*` zObUSr?i0)4I?01ae7X1R%%QkTCETjG_3Z8KlSKEzF2*$%FgTIX6q!6=s7aqqTSQUS zvSq#|C3dSgT5Cl~R|ALo(Lw`;BIUyi97BZ<aP??{;LB$p1b5bydp{TfD(`ZPFls?x z1hSA9fiB7%yq`5NN=bBQ(Ku^wZ(mf)(akVHv+L-U+7xQ4?FEa;wY-l%9TGJRX$G~J zTGFc2tS8N5bN4O|^`Pt_CdToMIsCjgHV7I|(F_4g9Fd_HG|Slc<mB!*Fko3;fC~n! zkM4zLz(%T3H3-I0(A_L*w5%4*G=9M-MBHu-p&vy+!w?3JiZ)Z)aAIv$9-5qYe94Bk z;tR4~)h#eq;}ABbcSz9FrOw_GjWJOoh@+a>_IjuYpuXB72ZM?;!qFud2g`nmKp`jB zP?=Ge5kWgL*nOR#nE|B@Je)FU**c3^WP{#G0qHm>9CZJz4i`rDHKSxle|>ZR6DaYM z$y>aU#+x&5QXH`iKs3jlQR|c!q}jr1(<?y6jBT0m<28F{cZ>JC;orpOhTV+wj++40 z-QLB!Sp`ur7f^3Ty+?yb(L9I4-8vbn1m1FojM*Dd?ll=9?gFu}`2|z%_x_{Yqod>R zzJ2@aUw{Ao_wPQuKRP`<=hR^(m_N5MX3nfRM(6pv2FXP<Rta1eHH5_`Q?+xj-@4|7 zxUde_%+2+?X9xRuy?giW_WI_VuYdB-{=pyo{F|TpBi4A)5`;$(auEvm3_k;wKPpb7 z7oe9{r&Zk5jLbAy6DCMo0?KBwGX3EI1iHC*17y%LDi}}$8bBL(BozUnG_yE5r43JD z3eLjdu-v|%td_u%Hfe%htHaK({a?9&p%$@27e{+xL|KB4U^in2aTMp$X$GZNScJx( zPem(XIaUjH%S&MjLuD*>Ge)4YS$EeQQNv+s))SiDgbX%A8~!BB=q7Bc36-UUk7C#o zK>edIowO)R!K`_9pl{LyXN_0x-#A8eQMTcwM81K?<}I(vXm>CFog=3(=Pw%XZrl*5 zjT1V5$}IoQSKMBs;PmDH!{V%Qedg*KUz)GT6&!ozo>tHk5%uLI@xhndx#BCQO~WoX zT}HFW_^CoBY*(8iD$P&|O`H3}c7&t7v9i#mLXWpt^Cz5;HQKj8OykE<>d0)NBo`nv zYYwnpQ)(;3Z8MjVE>9knNDK?DpI}pzrf(G%VKl=+X&!~XVArJJQASX&fkSFQM;8sf z_O%Ck_bJ3@G?)DTVTCwNnvkg;jAoKJ18a+7K(yQ`ZF`qlkzs;<6kj(s?jCm{phr{2 zbZL>Z<b@Ad8UrzL_mlzMA>*}x*r*gVv$WxXN>N~As6H}nZy8xTDm8MYU|x>e6-EsO z%HWWew&IXBpt7h4$bDPbt*|3%XbCJhQ^Smd$hpakh^f-UA#NDRgE>PcY#6x&sZxb* zp@Fn;16V4w;R!~=fF0OW1L$dqPx0WsVvgXBEdyX`wCNX)yatmT8<XenqY8c6+`n^b zFN{L#Oc>TM(h-pYxG!>d+&|dmeSB|^*Wk^qZSvl(t@FkkzxxqPku}6pl*U|K=G9QU z9|j%IPk<_6?7?Rglj*xk#sx=N0T%(;fIT?&f^o9FW~n%*U3=!vYw$(FYw(8;AAb1Z z{oA)c{P6vUqYtO&XID4Z@%Mo_F02W;I80cQkrz~dUY#ysF+lVD`SX`AUz!N206>W) zPZ-k6EcMPduiESr!tTC){qpC(_~~Ex3xDC8Z@zi+<_&pqzqq`<ylS^3!~Rx?)z8&d z0QIvpiwQ1>Hp+m^#-rt+uvUOj%16;>5jBJY77!V;%7Ou1ThYFCR;D8K?tR$L#NuIe zb~yT*hn?xyWolKeXLiactvQya6ClTDFqF`3)=72Ka2`fkC}{m34YMpSrpM`wSmLgI zE<>a5rpZ0V8R=KA?KgmBFWI-Byq-obSz&c_7qS;^ctRUanp@I_SEjj5m_`=$(o{(c zH^HUGSQ#`vIf);2=8lHUS<G$d@bK{2vuE5DHS=c28xx$LUB*vTJqD|S)_-bZi?~so zTg#Trc9~DzUAXbnrA0Of2FP_kFs#ruf-UxS74E4^Aw$~Gon9ZShDDfe5mkn*0>Mck z7KTy*5Uc^Ex7AsCU(p@GL@?4z8+(ZQYN1?mJeC5ehoqu`_Kt$aXfkKeTWU~B^*xNb z;C&E>MmR(q>=9ToK+qArW>d<*1w_V68IaSe&3Z&mvCYv3aRgjM#~v-Ayqam&iMu$8 zQkP89zLhN~Y0+5lEZP)(e5ldLJtQg|n$m_7yXp%|a@`nZO#s0Z8k8Urt202RCBk$+ zXW*G55>Y0H487}yQ1-MML$9p1$ibj2`_!vIYFb=$1j1U6a1^q@R-rZ@C1VE$0pvw` z+d{LxT>=J6Y=~TQ(UO}DFJpC;#s(#G*RqU-D+fC_juvY(Y~ePRG}Q`qVqEcK7i@7Q z-`d&n=X7><cDaUgB_|P<6c+EmnIXz%%dl+_=o$@KGV+6`SSd4wDg99MNiu39Cmuw( zNpl!nS|?EhPIG-Dexr5#YOegCVZk}e$b55scX57oe02WqhvV<xet7%#{jY!hjv)>T z?mX@@S<ihQ7g_}a)L;r)lG0VF9&pbkjV~_b%C_&S^B}@qk~e2myn(;_|C9G;v9@m8 zejhZeF=oAry>@-hz31E-J28<_LJ=GxP^2I$_LZI3STcp=_}UhJpisyo&q%-nZ&3uq zh}Z&`ae@>`%md;D46=g}vCY-BZ*}Uk_o`-H@@wtazc%~$zA@&WbMLk9Jr4i<?Y3HP zbuYf6k1^&LpTETM8=rjib3gkt-~8q`*#l!n0jv#!7;_3c`}Ltx^y!LuEF6>8$R@p3 z;;<MQVd@`&3Y%rN@{F%UDAZUAN+o?1jAjI(q^T!RJ4I7312Lt79^ErOE=2=2hi*+y zq1VG<c707GP&KZDE|o>EULyKt?<mlcv6m|WEEpvK;X}}@zcO050Zn=@`YwRxxdIsU z#$ePeXw3Dhu0jI77Q+<HXaciO(bSJe%Qv7&CunH~H0ix)5i@2nj|D^2j~l67S_YhA zX>G_GHvyq=!JrbEqN(pi<Qwp)yhJA#j9!>k>eM%RHBnI#XHz`=`ws9h6h*o1(~oN6 zVnCWDF^d!!{N1AcIgklVPu*S!Mk#Gdv6Qc-MZ?zvrE&o;uvbfp$`w8CfSEQvCE$+G zr#iryX$n(oCM^b<*_K1co`MQ!IwgdnJS6ZMpyD}$2Z(f90)s?167U3}Y~-qzqF42n zGDT&mN8Sn<5KzMyZfR`6S$OLjuy?{ZWl$a0Oa|zy84Rjk3p7w(K*-YHO?VDaAw#Fj z6xfs9UKk-t96(bWKpFH}9?+Bucr43H72}gh77)&ZJIzXgg!$6fxx*cyC8cZgg;7}Y zDU6R9U1J=e_R*LXM2zBOk|k*Bgh2#Ng8;M8L{2XNmbw(sN<nEA;-%c0O9(Z%+7b#R zm6s+e!kXQt#%e_gd%6^nZ-S;<4NE1gWl#@Iiv$=LBx2>zMK#NyL52(zk4mPXrGG5y zpO40?p2Kl-y|(mN1<SUECK{j+z%xy3hd9?9aHw)Bv8PB9tU9irY>zLmZ(@^dwHa>- zDv0zR%gC{Qw~dt9Xy1Aj$T82ini+M*CP946P+<U5=|l#uZqgi`Wk|y14#ReoqXr?w zUCfe<fQtCkl3Cg@Bn@Wq0L&TjnHmzssM;fgk(t}n`T5n`w<j+@Kl<^HUcP?)_J=?G z;memV@#OY_C3iGv?PD1PR9qH(UpFVM-5(u2fCNh?8b?4AE%J-=Q#uVpM+jS&EG(Zr zd-n0iAAj=6Cv1ah5(jxiUxuvzYe$ZDL(flvRxE7_#;vF)3w>m8?5v}ahK~S2KueZT z0-8kvx#On1*P?=^$K#-TkEOyd2ZqA6K}^bK@!bDBgQdpSQ2kv6y&evV@eXTMqSB3k z&`||bW+@B>;IS<9S(HrcS1y|9YeP$uXrg;z<psU&@zp+i+%Rf_Oy0nBcq(B=6UvAo zf%#pBRb|NwgV4iXh$gxhOGDige-*s%xVlK~qT(vl)XOlc@cyJk!ycPa7F6&f=+dJp zQuV03XgBhAfc@295BS~r_RefRql?`2F0U?5&raSR9ld@-aC*(<rNBjoYcg_>qtam0 z#a1da+CllE?-q9(U>cQvI$?e8=s}{j2MG*jU=&a-P%CKmssaN6xF(KvyeA2s43N{r zk|Mcwn@d^@H0xRdw2fN?G4&;~5}F7pQl2u<(j+Mpsm&B#$1M+IT#)cg)6|QoT!mHT z70Lxm5*7Nv><yp-iCQen7`ZmOAeWgUV|+nvBe3Y}JqnY;G~Ehl1}qQsJO-Ar3iJgt zBLH}Wj6bW$_y9>!(0AVyNC58eE=2%ClR4F9ghA-4TcChPWDIbn`}satAd|GzXbb6e zSKd9SjtKY`BGHckiKt(j5ilrPOmFEj?hQamB5^`3C~a?0J?&98Q|Kj{Xc4O%r(mct zrT~@!ARy%-v|pAgqa<c!8H^Sc-<!I$?7@785ZW{GYw<UiBg&!I6lQ1oT!B4qZ#LP2 z!B96n;yjBTkq@++Y^d@Jt^#3`TeSdP$$;$@0SgW*?gi`dHCY*%T9=RfD%5z|G*@i? z6NDd%NeOq)1T5QTZj=l^rwCVHY~z)J{Af}$UZ-*_<2)iH&LLc&OJMw5ci2QIQcwdD z<*5rZXxiM(olqG5$rO};^zFg9#)D&wZPvd@_pdH*&Q345aeemr%kTg2N1uK6^5W{6 zsbP5IgJI|K=TcCvFgI)0@wWN)*3RyHcW;}^MRx>pbmM2zxB~)Qpl4?%r>Do<8Ta=0 zS=mT8x8^Tiy!i0rkM{QVuzB<54Fme(+0$=+^V4s9`tkE;Pi9*iH`kYxw|Ib{t&?9H zGErpd=|hlycgBu*YYdYGILDb6hKpMdfT4*{?ZZ(4`@9H=2Gpu@Uep%-(pZ&O=BvYd z8C`%UKI6ls<DM6$?QCC_{mtr@K(mL#mCOWrIWkeDTZJ!?sG#qtUv>(7Vd~#W++WN{ z`&Gtd3Kt0}DlAPP|GSPaH%(vYr9n?03rDGZ89mpP%~hyD{=%eK0?Y~}X%-z;2}_Qn z%u>r9806zY9PP^;lRvw>;JAq2!oR-a>X^dYjrH@BGd9DQXXjVv7uOfV+m^Ri8?k{7 z@DDf1MmO45OOi+}FsYD_I^H$bKl<?f_$TxAlq;jW71X>c2PG89F@`$XXzOx@M7ct5 zQQVwjU8ImE)Fu~1ZE(a3SPwQD7#tY0zqj@ES9XCVa!~e~Nx|{)F*ZIKD>MsNXPS|? zdw`3``C0a07O5|$mZTV;ag88s@<4+NcOVLer<?gK8$SXG53n(H1i884u?7ZXwZ;dG zrv`Ss<dG?1kiHjK8V6(K<W-9biSh#RGhQGPCy)~X7aT!Om(No1LWVZjqbe^{86yfS zFX-9X8A1Y%=qiS1eIEgdX<k6gqoX75=ynHV46tWxGh3TAES+oQP<Z5wIc2LQ0!#s| zm17JA3X77Bf9X?9bv#(peZ))$<<Uoq!JX&+7?>Qih1Zx2UW_%DB!un!Xy*%Zn}pJA z3WI0{bgcSEpl}A0M7#OLIq*={A>)H1ph*zN3I+p&&N2*+nWWVd1t-)3_Bk|RpwXXU zDXPT`pfU*Z+7rU}6tm*>6{C46(8L8wSZwslY|G=&R4$O{&U&ymn)Fdiny#ygj0-&A zshcK%#{g~bD2y-Y`g-hS+X<*K6nC`N@Y&1Hqox6$e(())UU5@dyPEB8JbAjme>lIm zJoVk(_-kDDu{SrD7x5Yp+bEL5WVX29xY%#vH-E{vE`yGpX8tAb!Z1DnvB1(Ru3+0c z>_FzMl>LKUmI<ZgyRz}lGbJ(AdwU0Q&s)2@SUDz~*EA^xYoCg<@9fJrIR(O!rJ*Bt z+VvZjYuM-bSVu%z<GhZ=oUZ~PVGKz`@8VaBpcKFa<%;9~yh_9%JOTu1+#MoLWFOYm z9lc$f%~>J0JG1%0(<d*UJwJGQxXm?x?fSzP?|=UKa~=`)4)++Zqmz@XiwhRp@!O-P z2ZwuyPl%8kWVX%mdZPEogM)qKFJFGfX}i0($6C3$ykgj2zI^%7N1wcY{rdTf7vKN> z_ZgE9Km3p(<!18g&1<f)EZ6UT_q)ITkALIE2cH}t#}8$BI$vI%vltjFRtUEk9#b$T z5tT4Dn9XL(fB$n8I3=JI0Gu6wBm)Ne@c~SBHK$Zx;0Xe#Q^^Riww3`$sBwDg`6Xx? z9KbI{#p&%sk<SD1Z_0~V6)Ij4TZWbPL)a1eEaeO1na&JCY0^z6S{sC*pBMWz1rczW zV%0c1zlQDO-!smn1{hN_>C_s(Y>E*Tr<mSAq1g`(4qyliXrd(-mgqDdK^tJSiiuyT z3P|XejM^w7ae5lhlW1GIECvd%Wf^PWvPPJZ!crIGmmJtcD^t+DV6%jbZ6p}dAu&`1 z9Am}r(v#OXfM!+{;3})Z2&fu2ph@EA_wFiG2(>vyT<uq2X&gXL0gNMwflU~VMVPM6 zy9%q$UzQnJoOe*U*dS_PI$#rM1K^tuZT@bs!k&g|aIvYR)`KcwQ|%OGFv2SP*~aG6 zr%&nE$;k;ehlhvs?)3CD(hpzd=mR;on`cj+e(>IlZ+?U4lX$N9+kg9SzxVzJJejxO zsL!r(Gmk1aS~^Zh?vf!{>=%!qbd75lH+nL9*{At`|GR%T+`clFU-bZ40n;f{KxLIw z!*B=+Qlf8FFBQdOS<Rv&7!7D_USLyT2GtCpLV_hVPw$Qz8(EZGym;~A`Sa)d`}>SI z(TGD3W=pdk7&mSOG#Ht+tOH8o?$`PeT0F}rot7Zxpu4Xa1b3RsH7mK1f%5cgm)G75 zs$2u0eL)w|ED{u7cUGF#zjWM0CLB-hbiP1o32PG<7aK`AA2`!^B4hv&qQwm3Dh3xN zlmsx=-qA+oIAdA9l?cGx11&q+Zr=1h<HXofMRYRuz1TQtrr^>%{%En;0mAfZ;|c5n zW<6AaEOsR{F6JIoM&{1Gz&G6@GVNXWL8fXQQ6fgoDKMB0yTa6ufhq^N?V7N6tQa&U zpqX|s>|?RiYZ{-_P8qxf<b3%j5A>qZVxY^8y9FSKX74h|a->yStjEWbn7x?7d_!;T zc5D5{l46$_*2DG;hW%l(n=oO3+1=v>_a!Xv%liP>m&ktfHh&W6ngpD=T<f->9M@Ml zmC(iG^5U9fSb=Tm2pBz!(sE>mdnbe)9cOVZ+8V~t$1gKQe-)r&S;<SY)GysrN2xy= z2tB6j04zb%zVXi6#l_Xh`Nh%EN&HmO+oRL-bFKux_1*6rA0J<@<p+f>FK6?uC(ob0 zc=6u(`B{Fm^cx;B=oc%&D;r?c;tNI2PUugJ1G}B;>-o;!)_iAscYkX>-_C0z&nQox zJn>6PIB)iLwm*FT#m|2GTmRXA`k(se{`3DVtAvo7oAH&6#AGoLjT$I8<|QvU$X(u~ zruj}l{5B>XeK@|*-T|4Sv?KahMD<xi1kDH~`CWn8b8WXf9bg{SS|qSJg7Q^b;q%E9 zO+A5?SXE|@i`YFW`jZ!zCQXdIO1sKzDhErAN5Y3-sSD8<pSqP}Lof17kLQYJ)cGpx zRRFC9#Y|E1@`V{e`TZy}1FlN<5JatC%Dt)`xqrE6;9bReCm5}Eit&u7rc7`1C@k&W zH0(Pcg#KM$o-?YsG22?(+_<{E@lD`(j@aB--`qGqy*Pe*a(RBm-GyiM^?b<L-16Hu z<JD|R<!*d^v&O+DnWn{KX7Nfml?11i!^pXI&-LfAxVvqS;IvUnF+wes(G9@K4=9MT zlxR@KSXL9H@=jP(29OJ$I0nR0IgDOf7Lz#_l5!2Q;F6RUs=c9*War|}!Bav$RRkPs z%;*|sl@}PKVyY?%PzfYbp|)TR0G0Lt9(kItgavDC90m$_|3IagszRU02#ylMslf;l zE_dcS7EnPMA`2h_63n=n)eU$l%m~Vb0as-i(!MFklFKdDn}s1P0~myTF_dT7P|~Rq z8UW-vMwhZvs4zgd3fPP&FpKGcLPAwHl^fq;N>#u`Aus|$9b+3a9P#$oaP;!&5gUd@ zN$=Yq<gys%j_I%?P^+qvqRK2uxhff;Rz?YE!l53Is^sSODzdX(<H{KOvXF;RuOXBa z<X{ABlARF)HhW~r0eOXmsXP<L?7;VOc%YVMPl4IBq1lQX$}5ytQx8BQvJsz!b~G3w zMuQs$yv<-1!Thji;RJ%W06~+0OkI2&H+Pjo9yWn-*MiFccU6^ysQhn`FNOBHJ^|?v z>xT`h%Lxg4;Mkn!jx;Y4ocJuZIEv3VDZStEOdNx9*E!rL$Hn;-N9>s|Z#cM>#xeX! zh&5F)q=5&@zdo3vr&PtrQvf^C&p!L?M?d<}%a<>Yj*gJ<d~k4ZfZ55($;CONaLtYA z#f$g%4xemo#jATfWN&ZJ=n$RYa!WMFlPh7o0yvv-38qOO=`sTc#UQpR`J+duw8xQQ z!G(?S#~*+E;>Gj*{rG|g<P^w75qp{}HjQ<ae=H)z0BR^Sbq5R@w*m$Mt$nXco{mef zH1$&9{fHGgT*D1Z6QSqnBaU|j3IH&c;UWiWfd-(p7e`OI21{YI9xO1R`xF!a93`4W zV3b(HG=*lZk=KE8>AirKJ#=Y}4jA|H-nU#bWE-f|yc-y;s0=Wj5}*)RgXrZWvmPV4 z5nO&#Xfs8YvoNHq(%p|NGcandf@c5!182dZb_7_}EN`1>(lDBiuZ~B}Z<e+MO}z}B zp|OmHiyqYeqV+_Eu?!w#j*s6W;oRTb+p8U{_S%G5#EHiq%qpyrX(Hr)q&*UVi*nt+ zI#!-ACaaWEQ1z)QIW<uzO;w=Rj^s*8*vAAK<Url6q%^;SmSS3uOi4-$HKtIjJ5%Mw zJ+ATjoP??hC}W^11Kg>kVAK(jwhc`*xR9}59L%?`xoR`T^i~nW)V%`?GEW1l#$`Iq z1bjspX(LKPAyj!mEkLEs2+F6(LKY_1kyoxkQNX$?=%R|}$oT8I^K*Qy2caqp5D_Bf z@gh=wdQc&uj9D%fBujhHc~KPLLMWIVp19-z7=)%!4pWjINX(0k0Y`G1y-MChQ)mM+ z+Z~#80)`QafnnjPgb_<+pnQ=NUz-dWfG@`>Ei~)FK1L+bqzNV3k3xZFG!&z-pb(US z#zIM9DiO-lBcQM)m~={^pxJ!Vt4R}S8?bjxIv{P^c`dLc2=iXiq&?EHF^!M!+#&_D z$=tCsy!O&UGmiK(9Zol<kHd{|pt%l+#+O2s3fSziNLW-{(x{4bTv^%Ko}XR1U!^cs z7h7ZMgUUnC&ip;0kmi|9dBnUsAE)C0TIt=2BCqu*&vPPRv!MIZm|qSRc0{?<aBYWD z!_m<Rd*C1b@JB!V;SZUGd>eK~XBh!1r}Lk`db7885O;z6;<VwWz+FEU1{bZJoq7Ag z=lSk@w!^_vAq$p_8{Hv@onpI-im;3=*Ub9WrC<ETpa1Ef{w8~1LUDE3*o^o3cK5co zcVf?sJ<$L&h@%&W#{&1pbx@eG1HEu5dR2M^T6-BNekoM-ROYc@WT5!QMR~Y|Dg0f5 zWq|BZ>rsu8Lea~M0jgGkt^v;-z)FxBVG6Xmz~gRe$}<|!tTpofUd0RLt+Cjn9?F~1 zV()r+Urb@td<Zgjz-EiyJy(#0rl+|tJZah7(otc!t?rjl3wpkQd(L^FkM=-R%%#Ca z6tN6VJs7mcYG?*pd$Icuhh9@O^-m1?lIXR|5A-8Y_!9N!ST4cRP{<qil|d*Mxl7JY zA&1fws95|6IU{y<cCg2b>jlF2F~Hng>BwCfGe7g3t2h8}A`seC9UL5Rr}J|bBZGH> zl@IzRg9=Loc0f=^QB;`eYkhhtjFJ<|6^f=9)=IC^67)P!E4(7(NCcW_Ny=r&W(ID9 zRm@U6fByX0vuB5ghs+#fjWJ=F$WcavR47$N0jffpG&E5sl-I@j;rn4+iU_foy=NYd zJ`OMfRC$f3RHlRl?3a!|&|nG-3N-O5$0-HADN)0MF}X}vj-uE0CE?3@P)@a@f_qvp z+EQTIyGTLRiG<*!5NfADWewzt@fuJSmdbl-b4#EqWRfL_5lQG$Ommxnr4A*XUL?hs zO7zklijDEpDf*63FZdFUs90(Y%CeXg2YN}UhZjT)k|uZcl$r6Npn6ntfLZY(0wsFO zqM)f0;V_^k3m!Al0V*7srC*?$G61iEvL09!@un^Z%{s`R%n11|IxgIg*740ES$pgx z&o9qT&(BWI&rjJ?US6KvxEW?IlY7qin6W!d3JI@7i`tSt7S<UcRGn)mpzM23PR=-Z zR?KVsR&2=G@<kbb<~ew1yrav8i@kdNeRAyT+m~ca;d$q&SE+$D(S*`W+fd1fGI;0c zgGZ)ZrO@^KGjD{PZfrzfy?XWAzx~_4`J2D_-S2+)_3O7>t9Ezy_xBIk*&ZLA9=$y| zK91M;@TF@Jcm3w<>|}l8c4v3aK`2yo3N5!So)UOmK***Sp<{xRqd^k`%$_`X^1%lm zJbU)!#rw}c`0&MtAHDzHi)VX#JA}QwJjdhunuWpDpe2PG=TV@ujT=B51Lk<#jSNWr zN;IRvtmhvNQ(FV*h5tmui{S_e)zU#F)zi`FDZghNSThCAwL()*VEjUpu9!s7!VMoG zEUnDLvDAfrd4g0^=F7#OdW}X^*hB@C0E9|FdMp5g{?gQ>i6%-k{{hWnfHti$LGzgu zZ1dr0Zi8cMtd29%T0oWYpFZ@Rl`mSzd1y$(cYqcy(b6QEdV;2&psAOk-NN#c!g96A z%^iw_^Ov)jy9~|K(^H;VuWqhc)9`39Muji-o|1;zT#vuQK}Gy1eG%pr*ca-I{_0qH zV<U}>brhXmOsS?XNJlL-)?Q<vHcSU&<;KyggfJNQaS9sfC9k|JOHx{B83VNj_baA( zD8xV^U{Vbw75YYwP9+6ufxJRs-l%neP3|kM49yU-M0h;1IYne0GFE&Tns!8a!9+qY zy9T49fLETSjfZH2Ow!OVXjKHM8}JkuU|Cs^m{-+^PMc9vf@ehFW1j<vkV?wN6f{u* zZ?QD7q2?-Elo>Dr^d4wXl;NiaZ{b8xE>gSDO$B7<AB^$RQ5D6cK>!H`<ydIyL=#OA zJsE~>#4Lq_AVXM6qDPgtd`+rN$w8@PstMo=WeiXer+nf2uxWA^N(wSSAoWd%qr5_( zftH{oU}`o(Z{K_MPzYLkkYJyPmDUsqwW67HXCh~e49f&#dXqyD3n}gqDNnipB&;=< zbP@5^EBnUSPhQ^Uo4{-=;aTrDSC{cs9Qi&l&xMi2MJSAuf!_frB~P^Lv$ONFv-le1 zQ+DHL@j+!av>WSNQA3t7qS5zju0la$1aAB*<%Jhsd(;>fGXLE>Kh-H2B|zajM+NUG z;F1oQ2H(-;X@P#7pI?0b`OEKp_Xpqk?eBg5`R8njkB%6o%Z-h#{lg~*2T$@lDdHCg z&M!_+<Bx)muddtMO;7@|J<h1{asxLnPFolTgnJnVNIZ*?`*b36u($j6=*`W|<<qB! z-}uJIKmF6+WJ}DYlxi`6;)@rSf*rNJcsK|mY__@Su8lH1U5Z`>e~+cmW(rgmPz*?q z$AMvi60jCn34d2$0l*$niRim5Xd*16Q=q9=z-|JTgkXVz=KMu47w)Y+NLnL@4v+}i zL}_DoP?8apH=|rvqL;&vTDcNnQ?suELP0q@Jgtn(_;{wP1%0|mKR`)oWq^Dt!@l?) zB@c&gDMB@vqB0h9Ka4y@Q+JgMn@dqzEgx9GKcT3(==%$*+2czLg^{ON8VY&izA^}9 z*RnTpSzxIvr0K~E<y?T_zQc{lJ5g+ax8kpO_6`p?O|Ul*Bch{-7xQyKY{Hmy`bkfL z_MKqmg*%IEAYV~>D6G;#K~~j36FCN67c>B>fI^!^MRh(iM^c)^LDB=cOpI1HULdd1 zF*hYi!{$<9;qlU)_^)2Qdh;f}am0%|5<oXKD>_22f`UxgQisI=^G=~wV<Ui(Zx1^Q zY+`8~szr!)Bo}@B>~R1dIb)>(O@hEIMY)R>qDv<uM$IWOFfTko9A`k}o&u($Dg+9F z%`yf`a^BjiqZvyf-7OV~p=kPGhn6PxNN_B(h`0i3dn$;L<wPWotu1biGsnJ!Ff{Er zuv&l{LN6Kc0t1|pr+qu<lhgy(rH96hlT01uI66F|NyN>Y>lfJ>oZbA2T}$oji6Mni zmpSTCC@l#G|5^-G#=ML-O&A{6IbdiaM3gbc<D7#LK$3&hCaw$$7OV|WSXe4FCQPqN z!?xZ)lMW!YQwERL!lby?LCeE6AgxuAU6^qm#Jiohv4ds8rARnM*5hld+PPNPi0?&S zuXjdC${^<6JA&k2|FXr+o#f4C+fTLw?}2u2t}?pa@i?rn-E73SaK+Kag49>nR~MI8 z7wpgCjcw@V`PKR9#o5U@Bjg~BXbqRNj#{Y^iJnfH79H~!C%}eR4KEx{1{29)vkv4Q z?-nNPDJ5Os-sBtbSF8eNp4!eYFJQU7zdb&F_4@61zWe?E@2~#aZ~oSIj^3Wkw&pv# zd%Ju4+q*mAn?Fv@39`Gp&Dn8%!H)Qh>jh&J-wSqq!;Y7y1QK}-fs&Uos5>=HgeM7Z zb0;T9H&++iv#s}@J^AFL4}bcb-}v@V{}jjbr%%`(?{3d`=Cf_CU=*4^|48I_1qbBe z=!daDW9i|fPY<SkWXZ8q=&=eln5?W^T<zYmc<wypcsF29K`wTebGu%twYFaJSQuZh z0t@6?3e)MUqy|d#Dqv*l2Q<}2gk@7RI%n&^SVvGn0C8$qz9I-xh|wHCQ*GI#`5hDj z?VHp-4rmqwnsmTOqN77mN3C;AmmcL<Seok#p%)l6Z`b3i{+1r`&4UBa<*w18um>J- z4_tOs<k9h1jNHHQSOw3-T6K&$X9R#(QW#CgSI2aI8@CKGWy{di%V4KG!C`13^!bOT zr?CB{>1#mSyL0Y$+=J%x_ySt)P`bzWcVv*fu}7%jhij=eO0M$aU;zM2np}Tc`zvGo zP*osP532!m2E;RaB07`6MFZUx(i58_l@gnvw9vlu0AWT7$cIBh18UF((6riq$VSi$ z*whgmCieIDdFY?d=SYY%8tCSkz@SMNfvV_;At1D1Gw&wt!|}vqY}uGmfL>EXtqGfk z0!SQ(UQSH20Ojf0(3`0uf|9gdfG+m{8-2~F*HV;?W+ZhXsVzo$0sxHx_Q1zD&L~E& z>IV!UT7w`5x)+FpLA)Zhx94vpR2h2dC^JQsF#_^Z5hqWMcmc&wQP}{R3Zom@cPPHp zMrRd*2sDfp(6L7*Y#aV5n$du%`v{)YByvF_VTg9}_pV32=538c^eSzX_jH6lR74rh zBN)30L$fy<p(fEL16BQvaEnQeb5FD$BVX_kN3&B#b;JtQPJvlLucYyPP8;j_Ns!nB z$ESZ|G~!DY2^xzb_rMF_g2z&VA!oSc=ou}8Adk&0gG8C+$>h=qE5!vwxOWP}QUE+9 zCE`U2E_Ej-=WpMhwvBgwr)1B2L}v$HRU422@=(^Qmk1@%w?tYsSW?Mt{!W6VoJy<{ ziX1LzapgZhi?0XcS%K~A@$t!ze)Qw-eCIo#fBres`J3PQ?hk(Oqc?BfaEZeUUv{Nj zubw<PoX_Le@2{>dnEiNvb~f9JFSd^pfh;^{aAlKnFRQ_^`=Yx@#w&w+dpjR|@Z#Iw z{`N2Z(l0%K{`|?4Cq}@G%85XQttSu0(s9m=0kuVC?m=&GzrETiP?^1_UjjJl+lN*1 zyMkdk1(;<}g%$2E@BaE-V1heB<5qtJ+GqgYN`zW4YUbUhJ^z$ScWI%#iV=M-C1O;A zLNRK76<EK6Pe#r`&KkyNRJ=eaT060{7=*o9*_04T!J(6?okGXnUFLTZqZ<BGiJAyU zn9hpQ%9P|wqf+#kCVE#e9e^iG@jm>(a|#0(v`V;Ka0B8=HecKi$<fgf_PS)$xTkaO z++M}$LsMU1M-UREE<4Cg#2J^~?*QvR_03PYz4;cixv39@R4514x4POki*D$PDPWH! z6wuUw_$5&&C_@RLIm!zRRRNJV>#v52FOXz8tsZ${lQ}597%A>CG~Ff#Va-`@4Ag2y zQ%52&K5<V=Ag3veQ$dRH8Ks&6-mptyolq<-0FbV)Utqvf5ko;1fK9ouIt>D_L_(2h zF=okfGe8KBi}lmg*!X&3?|6!`0ZIrfQ!WlmH48R1mbW}p3+1J?W&ooc(A3d7g)tSD z++6uQ+GZ2LW2PjGhGt=F>+Us<3JCNCBZenl#}i|wz-4K0A7>d5glN416AB4bGk^-1 zLJ2C7n)b04s5XLVG6;#U3Sa(L-bDytqXAH2%-L33=NQANf=8vKFc>r&&>Prsm=YF4 zaEAgH%ve!S_wWYEV2!a7C52MC7>G%e3ZaBTA~18bqhG`CMI*Ef!AXD?U{5q8*wDl) zmfEn`kPwP<Za&*NK8_!}VdH_8DMn>*C}$bMU;oX2j7#B@kKaE&KHA*k+&nlwe!G9L z_xpeUKl9@sf6gZA_~euUJU%+7sM%Khcr5O?5K~`Z0jO+_kv)0{?7PuyDv_t-^2G#h zH*VJME;~&)ghD<7g_l;QcxGH?gjI6iCY_=im<9AB)}so@^6q+9@}=mFSrJg{M6!{; z48drq{q*B+uyhX(_v7z8=B(<q&G@VY>;Dq@R{m-c4;Jt@SGUKfC-Fky)j1niR?ErB z3Db?r%`-8b{T#MPN}Q9^Q@6(-e)u5^=9}OA=Brn4-oAZ{>a)*2`~LTT`0CXwv@~(K zi632V=Q{yi`NlEw6kPGO2Q*C$`srRk7KVYX!YX^NDKag`;`o;&bB1JP-WA|nl`)PK zaE2BiIR>6noJ0(Z=|HJgATCpl9e~6IAe0CqD=8|&`KtlE6AfVMd1DHFYe4jMLZ`65 zRTUELMM(;pi6%<8&SA=41~Zr`NZGhFqddX#Zqh|?8HE~cN;6@D%~jWjGJxV+9Vd0_ z$54(zH6zE+ucF1Qic|II4yq|LLaqM?qSZG+)nkRl#LJP(Q2o`c7#<%iHEX{cLx6#6 z5*~MeDqf{sjXr{u^D7h+7#5o{mf6}^zE0Ev%a($h{2`1f%3y^2?S&<%@fp+jpw1Ft zk3j*66;5C87M_oSW_C9azo4-UnrYum2lU#atH3z>90EhllwnT~4h}4d1x!qC4KRD# zJMTSz`rgxLyF2@*r>C!9#~<&+7l7nb4Q4UgxnS}p$Ovr4_fA~h93CFNe*Kzg@4fdP zH!to`xDe1+W08{!38sJVAN(g4_7$;tu)mjeL<ayXHR{Wqw<97IsOZ1;0A2<(iwRWW z(l^s1pb)h7Ad#siAcC-&ws#ltcLg&_O-G9ArV^3nclI(R(LlLCB9m5ksNk(V_`1A6 z70?T9rr(_-d>>8ff|~-ZRE$!ff(qrVeik3lK$r3=Nj1;n$0s9*UX_crix5jzn#Kgg zAbdJtue)9awLmTCg#fvhqDk`=1etyef%a87O$-1Mn^Lt<R8XRc@`4yds{9^UK90hq zFsW>{6$3CaT^aXUpd29u0GNoI0X2Y8Xobp^K$(z|Kn((H0?ddHwOPQR2R1sYtpYZi zAfP2s3z{Nf6QW9}0#!hzkSQ}LHWisclj)Iu3-NoX1@IMzel=;<P~g01(r(azRp_f0 z21&(9n+OXWB>tsZ0y@z!>|x66x4-*aFg^Zf|I_~olg5@m-T_{_VH^DX`SY!<+40fI z<<&Lokvj_aQ9@qPY@aA@R|6x+SkDM$GeT2OK%LOuKwkL*^5aj}H|>-+5!9gw{U9t1 zChec10Q*oZg8`?|ae~M@1#ud;2;`R9(=WuL%bf(o*LUYPfyd?YDt;0vFO@8b_${my zUR_>Z<b{(lja31UJKNLCtBbAth_w$WJUT$VVq*==Vqf6V?&UAu)8yIW&6_v*922Qw zknG0yLB}%(^-#vu^;K-phvjMz9~f*-;rNIqN{pHXQdfDvWdl_^MH!Fi(!2=o3AG&E z0xQ~MB&S}eRf(xfkIwK8xb$e!L=$yFasi$ZnFXd833I_*#bahZHEK3R3$z%&ue=BH zW}PS@)MhUPPTWWZM&my<7@=30PP%Fy(e^RReN~E8ai&3_!0b~f*HZM7biE6853FZZ zmMI=?DORPgI8|X|ZkKyt-}k5}H=s}_T7&^EiPji0a&p`JLg?%HHASRe9ExUt?*<!a zR)ukIlzAu~Gd{`q?-<$_niTsLAI|OVn<%krI5nHvgHjc}2V7gQsi}l=&G90`r5jpz z8JKNuL+fk1J3HJ*(jY(Xl)w9+O^kNF{%Z@mu^yqgnqf(ny}dmyWrV8ntXW1&-e381 zf7a$##OCg9yhB1J?w5dMbk!Rt@_x8U47}mV3sgu(H$of*1|`ulgN^TP3SlZBz@=!< zXe>(j6=58+10{6IF)4{=(5kbiJp<qixHPUa0DXUf@xf@Ev5DN1yv0BZ+6b1Bjw3Yn zFs(4k2_+TU0Bl$lR5dD0V+{aIhKUuQes|Eoa{z_~2E~%Fz#vfFVdSw%?}m~?t0~G0 zsOk+oSFOL?2`&>B89@W!xu+adK!kV^4b(Z3_FHxf>Vf&vLoF`GhxVxc_DP`_R+;+J z<Vf?B#$Q1$tT7~*!3+|3n|DX%451IxWelvOBxMO7s>PuL8l-Il!lL|JhjFst_%{vi zj%@Nz_*6iIBn@4Q7C<84hnNkT^^;gao5g^U5L%K9)*_c&A%J&XDc8V~P!0)cu}-LP ziDaPMByQ*jYl=u*fJs7=Q)F*%7oMHZ|LEWNH^OefFaE;MaB9!yTRS`3?2Vp0IsC>q zK0Q1<+}_@K^XBc@=^0^f;wN^9xOsJXy}9LlMe1Rdwjs@`$DntOTSO*rXrct6WR#Dz zvFWWp+e)xBp?YPofV=}M70ILOM=U4@F=R%EpZuL3BeOal3&#hhr!q@X+N9)LaQBRk zH(KMHz^F5RKbiSuX1S2YSBKqPGj^;8jG4aJ0s}4=>#Usk02%vLLbw{a#xk(nxd`i) z*en2slfr9P?5FcB;-j~3d1T=Umc;R~>7CufgM<COy{*j|myifgXNL{2^FkcL0x#WD zU=$T5nkX@97Dz3Ffdw1CUj{vD{6Wts7YYTT8uvg9d5u%is{1`ns6<<i{<{?DmaAK^ zL=z>bUx_p_C32Cp*Ozm^+Km;Y-x5UVL~AFA(6|Yjbz)?Oq;W$8?}=nbB`u^?KwjZ0 zpw@Vl@t%H(@Lfz%%>vE)$ETR$SHY1NO_XS&E|knFXmHOgjPP(vu_}GV8JBwdpn~uE zmHU}OY5O%mt}fku^N4X#nacAJVC_qU_rQo1mz#jh2ww4~;6~OgR-lg`ba8wN5voIz zf)(T6+c#0-u^ZrO%Jg(87zebTH8QzhoN@iJByT+cW_vd0DQ}N^$o>J>qpR!Ni}-t= z_@MD{-qF1na`Le*aNo>#>}vz;d%sAkB(gwJ5g+`iU-{F@zarX$cmWY90Ue7ch~b7u zVsD&rKTdhN2g<Sd9?F4XM`*e(2#G+clso#OghI2gj=rZRqFF*ILbYWBltV?8R9b+r z1`{AB0^<p^Q7&j|(5p%aBQFCqs8Ue@CktpZMHv&b&y~uCjMPx|!|MXzdm$7rnh1Fy z<Mg0_sssaLVxY~)w}e6!s7eej;FZfLDV0>{3*a@V;L(SnY?BtW6goz%AsWpxQ)nnb zQ)3YRi^a%{gh1aKD=jf&<gc&eqCnH6Fd7Ku22|1qzXzBNFz`Z<k&VqBWdoW~j%pJP zpwxJAAkjoa_od6w;*?7@m%_mz8YAU}%Su>#>AjFhm)4j>?nk}`#Aqc~2#{za6)}!o zQy1+Eszj5lu}6(v##Mg75%lKv>hkIw$!xy4f50|)0ql5D(Qjs(&F%Z|zyHZ6pU_|H zkGOfsWKYeSiYXXg;$%kz<ZFDU2<K(Uk^|TjQz*Gqrl15cKCW{L5L772pcqlYo`O6( z9)XCp3`U!xmHxG%&rY*4@&o{V`}XY*e(;0ufB*ZhUcF%#%p7w2<ra*K(?O4L+1eQY zT%726K$D@yk_CX{>FFtPh(;3z%0=6aH)e;2haZ0U;m03;41Mw9#eDN_X9Y~nGfEb| z1TE!*K}_RYvq7qxOQB;Az1|60#APsbPnpJ~4@b)aY)5|*Hm7i8G-#eVKK^tCbAhTR z7wGkFK}M-i2u4kd%wiiTzE{Zzn^UMVGEh=+mLlV|)J1znjG7~?@>+%7Y{c6v=6<w( z4rtP!Nc25w<u1;?S{Xreso5%MQ1l)c7T8ShFK~GjTJ#A_GzBg_Q?$8Ffa-S!(_C5R zxXx7=U72BMB2*4dtI%>$y2_6$3JuiW1D-6P6&cEH$UU$?s66w(vvG^!2xqdovr@N@ zM?eGQTx5N?EGQHfS0zeC<Qag0sHO~<8uy?Qhf<eHt@i5!Dad7Eq^1Tc;Zeg%gqET# z3knG$Xd1*g;nNw^2>3KZ({94hti0L?RApua3@`>}Sqg(>uokTtp-K>{YEz=kJz)Ld zC7%UGg{(1zxWlv9YQ6RS(io;B(h*8q(5u{qHY3X(878!N^?l4RcSzd+_0#lx0dz#6 zae!t(M<5SXtC_&D%}0W9@Ie;dM3h7d(qUXpgJ4iGD}LX+AJ`NK>!}S>DtG{+y)eZH zBO8zb0`M3(KJuv#l));LOED>42?LJGRwyqjpnOjYdKm|ljZIMY*f4HWU?4Qs3sjse z^KQLyNn<|A%v5l89v<#Ld-eo+bo7QR!Ka^o9I-mE<9+`8Iol+b%KrZT2OoUEj)fEI z<m7}s43V+nLQZ7Ym0rZJL&*ZxZ|aEUxD45eJKq?B1od-@5482V5MTC~2fKQE-9t$X z$K-X@9twMU4<f`eH1&hg+#ZZJ924Xosg66?cNlCqO}qlcMPR<UzPWaFbA5V#_WJG7 z=dWIU{_6G1&tIP$pPe0_U7TIsUdOkq#<!*2-fZQk=J}rp!lb}atrXapVtc;3wK+f7 zf3mx?|NPmD`D|xzZ*OO32TQNa7_<C7`sf4J-Y1`Yf|rqvVDn3i&ni$7kpX!L3r6SB z2+_9z+KZ<C+CaJ~m3b7FR{JI5IBV>9oenPJoc`>JoBAum-T|AI4Oa0YZ3E4@>sM<J zXwnrR)aV3JK1GGfsDa{pA+Q;y%b*RgnY{_vT#Dwfm?%z_;jZ@(c%HV#PcWADXgWSM z0zems5vWb8B~Ue@GD~5=5$>`7x>2dK>Oe1iI2@}fn))lFO3E4oy>JRI&Q2&zDsjcu zy#QZ?T(P+X0WL~h(y>(Hm7Kc=Ng~`b5G}6w-HX&XA}4ZXr-=c#r}TISi2n3-!y}<f z+uPe*RblKHDle=SQ7%<3W~iV78)-rL2&#w%WQ=ALXl7)oW>PHE>K&khn;n=D34EF? zDMqLTy(I?Pltem}Kr>;3LfxAvp(Ol=2mpC8J*pQjohgh~jxZ+8V0SPbm^Seu3obO} z`#3aRsep9?WxL4wDPvLgP!Kr=C@CPpv7n^TqzRkKLHWvqzGnF}ywd_y5o;1h8&%pM z#6C^#%80%t6siRk#HOHWQV`J-%B27mJOPc?TV}!lyk_vwhd@VAkpXdJl%zhOFmncM zie}N-8xSDTxOY)5U5b%QH8bQGj&m6+0jxj`l!LM<ROA9pBNQzIRYIW#B2sqE9vJs% z(nJcley(k9t*vj|K%YK4`1a5I)Gz+h&;9JreQRU$_PrNRf8iH@HqGwv{s-^<!Y};X zx4!jLAAR)Ex4-@EZ+`PrH^Z-9z49!p+Y%Js+M07hiC2Rua9N6`PLu>nmirOIm&HIU zI};?ll|VHUm`Mx0Ff10eJ=9Lo)ITw>Bx`e^9NXjLW3HJ98Cw>~(b4huzWe=O`^Ufj z`t#SXUcEuf<&?`R*HoSpIO$zT<qnKCEU>%bLc&n<bOPfu3O9Og?xcgVifCeqFU;ZL z;d}4B_x}6uKYRA<;NSp>!E@%@x7{v9=6nQ5XU+Oj8(@VPZ7Fo@q1QV>i#S20?&&+h z{h=6&Dl95UIKO!&-Cd>_MyK_ifPf=Lm`=z`twbtRiLhR*zi|`vUO+GGGr)4_2#PPc zj2JcVfq8poiauJT?2`6Scn`9dcWBa|JdC<CtyY7==!^zS%?heU^nUbVK}30g*8^d+ zhog5X9>yZ4h#bEou#6to28vg{6wG5@`0q9joa5ZD;d@^@g@%Y;nXmx}Sqr#pww6C^ z5m;}}Bt*cbGhSXTOeA=B<JP_e3yz*t4^3t!p#*RX)BqP%Ff_Rx%0LS=9jrnH2jwmW z2&)Oz3>Slh^<W89wZ>Nlp$G_L765OGqG{O5v)NODw(ON>u(lB`Ig(f%d4tym9;y~7 zgu>&cV=pYeBn2dZfIR5XL_386wWOJTkq9phKnbBGkpcSBDTMOMb)gyE%V@og5ik(S zF@s00&B(x*P@zq!wC^cEC8`OXYLQTzLV(1i2(4TfjRg{@Hc<F<#gvE8bq{8;9oHBS zfBINQ{(11#_1%kD6@=ggC6O}H#rYK*h2gURKzmC?PScXoJ8WbsNQ6sNQ>|vcTZmWR zFDSvoy0f=gs0ac{;|Al1MzO6!4ZVT1Ff`k#o&24RJrzdinI2S*TwkDjF};hD0;)o3 z=>>cV1@fL^6P*=nn_)<P)^dCy2Vvujj)M1>c!$*zOJd`eI{~{$W)j7RAAazQzxWIJ zH@yej+w))eg`cPS2mZi+HFGxn+y9$?>&5%;?`&_A>Z6Z7eE<Cy?1<PGeeZkUKRG#N zZ!(|l#J%K(2jYDDcm0<5xov5mFR)Dbz!prq{x{^W6HlRwae7d8^NS@EhFB>9=~{^O zj25m}Sx+%wk>7%FIMPK|A9vH#BZDnLKdn7bHEt2utLiD}Ywp2CjwueSc>6tR{uP<_ zFj8P8mzNg^7@?5gu3vGzxQGqv?e)#o<rSkgo3W61Vz^}S%w}v^H!pKrOF-tGfraN} z!5v9u;iM2-o3mH1UTtr0pPijyd31E-pIv!>7gY@Ny}!3Vn{N}@kG&u-5P6DTPK3g! zS)e{BUN(WgmN5l(qfq6mBd{q}#aV@NHqI#8NI3i(qag=IE+cSpYTV+QSv77EdNMdb zp<0@R$`h{Lzm`Hr(Ao*(EXByUa<%q=UY;IH;`drm@+HWw(F+aemsr&=qZL!MZx%{E z1u39am1g(YgR-%yFH<m*-;ZfVo2yXv55%f)qr7(v*QaH0d`9IFBp!1TsCv|R)>IBQ z_nnWZdz#Gh{zmFW<3?B1U+C?@s=oooU^yQ7H^4WmzBYO>MH5la%G3AGzO@sphEubt zz4HRfKw5J&1uop^Yheq7o{})mGR$nYHQU<S-r1gQ#oyXo#LwSfUdLy@0&OaD>q|nO zeKywCd0@HZzP7o^Jr26RzmE$H8T+aTuJB*`GrywbD<VdL1O(+S2nbCMB-|H$RhWvA zAm?W3``Tq=2pFNThXw^Dr7EW22tupF7!VdPjzBGPB-9Kv`|7X~Q=7%qbe1eIWq_7S z%0)T_@?J$8Lm?yx5qOvYYLSc>R5kJdh9<&3W{*C&mOQBdnoBY25tJrEqg9rk>5(zQ zv0Q9IHHbex%wuz7wzWCuaoi)n&xOk|Psei(7@F5tt)3Ao_!MXxcQ1?sV{I^%C^|4) zJ%K{tbR%JwQsbql(F_tF{Fu)<=FAK(5j=m<8<+?xgHMXvv<h5uIR`M4Y9DJNryky7 za{k*_vJ)ml1<&vlRg!^0T!~7uln&*1WkHf|!-fPZR*ipVG1?de6m|imw3V9GM!E+a z3t5UcCaCx_Wh0a`u&N#o-CH9ujZo>J3{e3|;~2O6ATg^#W_tLM;MUA&gtcI<v`?Nr zeg5LTr_Z1K=l<E>|9k)G-}A{g#vg(H)qnU8j^4cH`W)W?ydK{z_vYoR)6>)Ii+EvW zduz7Mr8<5&=W1i^YGd<ecW2JAx4XNyyDg0`Y2=J#ue`M}+uRx*#9VsJH#fGoHtX1# zZE?WF$viqX!?-_Y8|xmNHP*Ac9W_9?SITcPgxnOlp|eGdFUhzG8eewB>A<kFhwSMx z<hM*aN<aCqWB~7q<@9G(Sp&=rivga=Ma80;&9+}3y?uRjbbNAl#(tRNlI?J;B%Ui` zS+*C)0)}mkgeeHfot>u37<f<Tnd9*A5EV6OnKzKQgRmZc?&p5)(@#Hsc6h)|<|Zn- zxFS8zDA|LcJoCp_oi%FYhl8ZRlB#SjL26e4OPT6R0m)SObs%e~>!kI3A(eRqn2x?j zHAMbyvtJj_bex==9336Kefw6kuZ|kw`%#5iWT7N#K?Q_)VDQ2h+H26$FNgB2F4$a! zJ{Nr7?D2(hz|yh$iNdI=`-kYUT`2p9JC0Jn+d(7RQZ)4nXwcK2Ogy5_>l>a~*sOA? z_elUIe%k5!#zQUg*~aE<V;1|zGe7wpm#Mh<#|z*6^JMb*Q~w-nKua6;?YTEzyZ5%p z#f>{7O@v(T((oN%{e$=4qvxcA))26yxQ6;-FzI1P$vqF@-rgP+aLdFv?^$hA3M?A; z5*pJca-xAUHqnUQbI%L638<u0J;MXUNFt>kXwL{M?1kFXqYMzRQ(D^7Dd=qD7D2xZ z(%PA8R6`F`y}ic3>{Fm>TxSe#J@Q1e3x;**e8jOk@XisS31CoBJnIi%fxYp8Hc*79 zU@&I6$3sy<c`XU&MW8hTl&7-V31t2T7QKv?hQgNxX%Hg|ntcQqy^zx+l%t^vAue`2 z0xb^p%?-vJl*HihfXGud-So{CY=}TH@eWKzy=I(rAHf&2a;qFKWsxzg^IO(UibPAa z(7ueK149QXJFY2|pCgPfRfQaigsFg{B`RHzYEOmbRdJx{d$-PW<YGc8%)wVKhDzdN zlV|~E<pNkj7)*f~6f>xnM(bntxMky$h~<>m1cy$oh`0&(i_7@jukrEH7|LTkO$;*F zT}GB@Nkm492(7&crdoSqD!~}4P{s%%f9A76V-cPcu$v?A&TM{i9zO;Ai~pHl_%HtR z|D|Uy-uwLXAM<pJ*Wv!|zy9C<A2;j7zy3e`6|Tk@$4|d*ZoPW*`tu)uc5-(5`sJ&$ zi}UNt>)Z9U>)0LL%xAN`-Gi4eUo*w?IoqmO$+^jj6;5)7ihv9<b4o5^vZQx+_UrqW z7?K#4JU!3P<If9oImH{-4mc8a!5DinQQ{p71A!0~!4r&0d?E_w{QQ)4xV=5&7RZWY zW9Q1O_3XO6USo`i5un~-ez}Nk!^dlC!|Zcb(u3QZt6c33&H~iwQ%H}3W|PgFHU#mC zr|~e`f!K5ph+oDXd_|Mz4i-uTF0e#X!UaHsvXn9D6w&i#h}X;G`Cy$3>EV-u7cX9X z@WBU951$+#AJ4Zow&%M$yYVSylJW?`bQ~V;lj!y9mmh!p@sEG}<EKxbaz(;xXaC^! ztGBOSy<(b}cR+Bw2zz>Z3MGiYCrmGpaH2nX_LLR%8^86N-~H|HoSvOuoSz>ZpPrwd zZO-Cl3+iG@xUw*I)OUJudOKXtv+xF*blH~+ZHiUDJ6gb|Xdt3A(8?HrUen9t-jI@> z0y-#zP0_$$Fh#~2%!YKtj}zoJKg}^vCDM4cYoOuPtwYx>Fj@qifQ48#!o02V7%Yv` zOCEwcF?1|<Lsb(P-}`JeK{cVI1N-;@0RQw!L_t(#Ukuld3=^QK3#jM45oHWzfL@L& z!lhVse$g)+jRp@jl=YWTiUd{qJrqQf(OnAi8oUG;;KC}^ktQc8G=3ay8Txq<Hn}9p zj6nUk2%F-j-R=U&Tdd)eo`Pnx-q<)hKPh3+9>$Rdv*LW$G1E4C88HpJ5}ay}!A5*y zYayewt`B46#cc|`z-Sy+%`d>F%s}Q}c|M|Yz+s#+EGd#zp;k#Dd=jdpfajTJkv7PM zT7^X!OYVJSVfHxzVL%#&V@04I3e$%B61QgVO>f@3`S62}|K8vGdwCOy_joa*S}1X8 zVh_E#iYEtz)?gp20H8$B{M-NW--+~J8SxQlqi2=?QYg1T?}Di44?Km!bHCKnLZJYA zsSH2`kA2xF0Wd(-6dF%aBi_RlXj?mB3hhU#9vSrxO***u642Xdu&RE5!BRB!fF@1Q zG=6KRL@E@5Dr1B?83a6*3YE(MBQQQptG$4Ca#g{Ikyn8xDh&#y3VA&Kr&|I!1~Aak zJf^EzZu?JhlswLpffw?l`PHU}asW?BoO|*L0eoLf_@reb;wxcfK%Mr)A!(k%?LB;W ziexyo9|4sS;mJ}3M~;N@v<+wgGg8687Nyb@25-oIB%qYabFva?M)s6!5tNIn2guio zO4%KhFdzg3G&5K0V0n!Y`-RxS#M(d~$8FFX_d+}}Z)~-X2glE`v;_l*Y(1ufL8TC+ zN#Hs*JPkCp1k9bx2$5?M<+}nAu)+e3iC<-8f#P~2ez68)4~*Nf9H_1t#w~_~OYNth ze&eUU{q5boozwI4z5Trib#wDC{Fnc0%{cKN{s;daYmi&VPF|(q5zb<r&i41>t-NPX zpT=+5?C$LC?d~7!%{I0U;&%xU#CPUw&*spb`8L~Q_;$?W&Dg!&UCf?6dA7T~jm_T9 z&fZSEV@x8NyYV(M$IkA~Y<DL<<&=)Ir%#^DXImWbk(3Se9$q^;+jE%sK?LH`h!00? z&X|;Sc57_aSQ3=IwY@#3FYv6Sd_NK!E>IDW3b)wXv8#$3Wh}E;Yix|$y36InUN=`t zC=#qQqNOATJ*GCn+=N}q(a>bY0!A*{iI~6P>}FCFf`!=|8X2dhfU=V$IF-dr*pmc# z(!81V%u-Na;})^bV%Ug>FZP<3S2q`z@kZ>)@$u8APZ+WI;i9#8-HI-dJzuSkbslF| z{tX4YUpB_v#5ut(E@ICg)#qhO@R$N{foD_A9vJ%BXP;3H7t0u~>nmc;XLBOGdGmTU zo5yZ1uPuO{(tX(LcuitS9|uW0kHRPM*pDoZkTC+SJ)lXM_r(ZO5Y;9|@_T^I)GYgx z5%Qf4sgg$RV0Cl2l=V=v6g5+={S~k@&SN9zj0be=-6Q%Wn&VtvBb0qHT4tn$$iz|A zQ_!1%YK}5ibJh8UL8MHr#x~&#B?RH~80cb<p5C+m9lDVt7qHMxpn=9cjTdNE1Fv$_ zemFrJlmjifILN4l;r^@Hhzc!xiazNWrf7{sMU#0b9%CEm#=lQg*M~9sS3{S<AQft{ zPYZ~SO}aLf6w01~0yg_WQzDe8?WvmH2FNd={LdDQo6mawWmHPz;AV4uO_SSmsN(64 z3twE!=i9sc`}+s`PmWKHczk~S<|X&0`S#Y?*?GMB$qlT%ILKnk|074M4Uj>Qt>B$h z{!jneKcnSW#3m0(rZJyD!R-^uLcbdRC>aWTjX!-CfKW%z4H#<WrrVz?89O_gyo@R- zDEkozh1Lio=qOVXdX(aE{Jy6&8#e@*B9k}YW}3sLWQt}nK~r~7&M27zlzbXr<JMRP z9&WS|4kNU+ht6s&TukP*4CWdec%fNT)-3=K;S$za)uMu?JPJVILE1V>I8t#w7&9Z? z!I(fTkcVc9FeqVPiH_lrazFKFryLx3-}lg_H>L$;{1oP3v=d+73Ia3O#2dU*pv4gy z1$FjDt7b{CfhsII1#(ptR$B1<ow{30!8ibUg%UQ^DwmfbehKkqd{ossEPDV?JpN^S z5-l#AasLQ<b90Sw7+sPwtk(#+nuY<_$oS+8o+M+yZ(wL{a>e!UFxt?@Ty(kGXwdY! zQB7$e9pkW=c(*WWi%=w*9C%b5p~Ueld4>kDr_cBeO`I-EadQ>lN5$=hJ>~oFzyHBU zAI;~pi^~gW?5Wn){=h%K@HfDJ?XUbrhT2i%wDq#=q(FDs#P09c8enn8UYG4>d=Me? z#C|fin(RE;q{h}Zf3^&s-SXkV6aV}e;WiuH_;m7oJ9zEk=R3O*5MjJ~xII5OIAAYC z^zH3!vIBNs03}ojs>l&9C&e8z@`fZ%Lt-Lkp&{{)3!tGUDaCEiu5amV%ukFes~|?6 z%^>S020NS4DHaR-`Wk~7AJWPx$jOa&l4H`tYv_JIcT@!<XetL-wjdcN4-#q;V_Q_< z!j%C`nk{S@_g)2rg(g~rD#QAgI~&@Q<D=c(`R)1*9b4PDWvp%(f!XG4dv<nyesOiV zySLAVdH>+>;_7N=Z;##Z@lpH+l9x52v6iyPh!2w^zm1A%efI1bGss{vBS^Mpn+J#c z$QenTm~+O26^Iul6A#J^-Nfgzmw@>3509H1wBnVDI8u2ZbZqVuAQ!DYph+3Ap_%^% z<Xr>R><v}{o2glKR@KyC1k@QO&_wrwIeNG;&=|CKho$nRmiK^qWOVG^Bl_z2<=CUN z#c)B7C<7FNo-YuSc~s><DF>#53WXq+=`vsw`G!zXo1PtNO9+%d9Jusl+#ybfB`^zU z?E!iJT7s$&^bF%EKY})RSrttYSG&$#z|&uVv9v%8EsGYD+9{gNLr?)9fk%4WUDFfQ zk(H_26=fwVg3T4fAIK!*EK^CL>}z00#u^Bk%g4X_cob;DE|iRvlZE+?f4EvEB_an~ z*!W}tH(hSGn<;E}=-98l_ulip{k^wuUlV~R6z=HU>)*V66Mhjns)|=mZrMa%`mB<Y zkONcuV9D7nykUWN^*6wqhbuO~fKvKZo-4oIBc*z235o&8sTFW%Ricab@=)bH)n*Dp zLCdi$^%6=%6D4{Z1{!USVH7U|u+eK&M)|_`a)nb6s#z?euR$os9v-a*N>nKi(*X*X zqIYrDN>WS@9-i#A6NCgtAw$jb?F$1M1B3>wIz_KVm9Gf87rM!JD}zQ1Latpw*VcWD zAl@M5YL12JpoKoB5)dKdBh&HWObtL8$RMe;N_@a$qWwZ>msts%lNyve$ar4jF$_zz zAmy=b#$HQ=@IzRw#;D-<mP-kX7AU)Mi@>bMNNDgLq$r`rm9(I|;CL$60Q9_2LNx3_ zNk&a*G0>6#n}Q~x<jF32Gs_05lrZK_ghKQ7&>dRAh4P*$AOVCj<_N}t(HIy3iP>S0 z47K?ItOaAy+7oboupr~j-t~2Mh6e}x?1b4V5^8^UZ$8`lFZ^?VpqVDv0F%r0%(=i0 zgy1w~Pyq__G(iwwVl-p#8}GAbjj=1{EN9!9Tg~{3VR$6)Y(lZg`fvF+_sn?VLj6eG zLrU?AgWl7L=z7M5Qb5mV@58|JZeweMeKGr6HdOQNEjGCnz;%E^;zl`-uMG%!?y=dq zUtL}>@jS=n$4Qxn_<{k(YQ`GKKRKno8M`ks#Z0WlZaVJq%o?-Pc>bXtKn*}%)U0D; z<-*ZkL`))Pz&0qJD@Lux7BNw_W!bw6CD35HmDYn$P{$KS%BY+iy}h_RMNVHR8#$IN z2CwS-`}@bo$Lv~z?muCTvvbC#;us3x<(~oL%Qcf|?0z@5*4_PHU0tFfL%g}ayUn7? zMY4Wz$<F$MLYM$fh<y7uP+?60dLF0+t-TuBtg_4)fz}?-q{ur}GzX^Vi{6iP8k^N@ zshS!rMMk=_hdRGYk+u&C3;Go@@|sG(R3h%FN9fqQNA%V4mj*2DomtWdG>KdhV2Y=| zG9zeEW(7v4af`sxEb`E5_CTdp`Xx{i<jEsHf~iLZEURb<dZWrUf;L%87-ZzcWJ4$_ zPTAW;(D4hYMP}%H<9_kQh?E_gbjS{R;Q}5M{tngON+bi6kMYP2a2Ia@rO>D_l@#jK z_E`mHWE|lJ^kd%hcr=S;sTCGwuGpx;klO4aOenNzJ@9!0T6_Qf7u;k|Pmd8IKzng< zc6xe>ZH6&^dv@ZH04n;_Pyt`5!8_Xk`wnoSi8CJ{C4Gou6LgHGDiFQM=M8W9NHjxI zS_cJaP&NfsQh<wQQ)nQnS&l$6(aU?Ff}$0c2PLlt!XN-`Ns8WsRR$HO5YZD+M`~Mp zG11g<DOf;II^q);?(`@g>=rjv8p9y>ISB@d!%i+3<f@QYVd2&lgPAUc(!!&<iI1ep zr#hcNI4F?u&KO~w+K}THqOP-{=+5>Lc&fu#D3Qm$_(+?@KzZQv(GWR9goLJR8(tTN zVt{|6+paIz^k!PBLO95m6bX7SK+{mlRmmvPW{NTs3VTM_1XftlstXlIc>!&9{H|ZU zSqXs*67Bn@16xo96$(LXCzt{#?)U<D3@9d*0m}y10JQ=w63alYeF1|K_F8z++5;34 zu(cOa>1+Zcc&5mA$oC2Fo{Co{y+iyt>uhbKz4fuXxA*M5XYW0K&fYJ+^5OPov;qG2 z|K?vozPr0iVGawGxTK*nrsK-6zaPIAI%wju;QOxZE%Eie*4zNI$#LA)u5Z}t#9Q$U z34)X}^lb31s1*YxZf~JyXXhk?;Xv-paL|M&4hIZPcDB2_J3Ilg&yTl)GYA`9sG&HJ zj}9_Yetya~zEzJ><1J$pSuQ(Yyx}86)OH(R(~;X@Def`)>uV&!1V1aOgSm?3k{}4s znWg1`cVJo>@Mhj*1Iis}KoEF_q6|iiNZUIweoe6mmwNW70iJqJj$dD1p0h!Pr-LyJ zd9h`U;I*^8_vZCm#`Vpcx7-#^PEMHue2K<95g~>n3udcKGe0IDU*L%ZgX5DUPEfYQ z`KRNt2PP&SxoqN-FYJEVYh%e(+)r>Y3UmoGv{Cnf#U@3zBS-Z<=s1d2KrUK)K$8x> zGCki*`sO_d&xu)8uWD*ALdLkWl-`f@_+m5R3W1rrWSAww#yt``_U;jV5-rxoYLtC3 z*k_mqg*`B+m@uqfc~Ej7-%G%%m;lSt>SfcjBTYgM;;ysg;_w9^h+%u0SYD6w*qIH* zuh@X86}{JT>$Hbrsj-eA_p_~}6a?fgsb@fCNWMYd$URNmnLPxC>VsFoHph5ec+3|Z z2wP{+ay)heyyE!~U~^|SU@8$B1G?|kyM!75n}TLP@>0-ET|glyUO8yO8+WY@+5m17 zXsLvIgZGPkx`>Cm7w<oZ-san2v-#%hSFhh5y{5gfnX8(6bi60#>BilpJqK2WAsr<0 zC4|1Sk3jQm#6Oilkdh4pU4o%W_k1UTs{nmN2#<>w1)4s&_CuqifVYV;P$;9kr^cKj zLNuL)Uz6|qw;3^NbZm5YH%K_Tk(3bW4oPWbbd7FMN=iWK?iyXvh)8#XfC%{P^ZmV^ z|6s3e_kCX1dA`r%0QFXDYr2&5r=m|<RY=jDT>b0<2%l!LTer&#_46c7OB>l5TjE9; z;0sYo^BwS`(&iQGweB^dE1^y412X2n45EOUFSt!1xi9RpVVX?NAks11#+|VK?XR}g z*Sw?_jYVXbkiCFQ60a}Vzf7#LiUbSKvxsxLvAK0sFVRB<1m$uSNOAy!;e!7hdPh(o z?mj+yVY6C5Ik^TnEI#wXE-TF2C99Sel5T5hQ$~m|OE1x8tC_q|y~!9ME&gZx%9&uM zz7V|ur*zP=j+W(nm?v@+0VFq(uLQ_~@Tq;WH6ZbNRC&gpRPqtIjwlb}!tos4(O30! zMNYNYpnh7YvR@-PTI`)?M>)PL)S0h1SRt!a?)g!gL9`dyr<TAPJO_08KOOa4@jb>* zzPMa^9y7N&sI@ux=&Wl^(Xp#x-^Z^%@@<c^hh{akqTi%;^k<p<%h_V!bm|HFzhRhA zslZobM&B2H$)naxoXg~sc3!9qpnnQRHfdLd7ZCSxbmTJ4nVC@J65TK1#MD$#qaQwx z=zxF7AjT^#^+ztN;B8my=cMV^dIrE8*V>ldMJlR&@emG68md67N$=T6Zpr!=J=)1! z&bw&50AShs*XCtR-$C{yP?a=4$M^Q;pyX(BZ&RFOHkvjltL25*w;I0b?W!+ZPj6ff zNDJ8?n%bKBy3@bd&EMYoP_Wtn1quZKb%cllw;}sg>-yTxm<oHT>Io)j5Ea(%E#d*0 zUx|}G-Jdh9iJ8FX=ll%=gk&=*#UiMCphA~=GL<}~@{#{5im|C9urHmtcl4hSb_QLQ zNHBwIE1R93s^ym_PVt_vbr8`3Dd8Hf9oqj@L{;G}{faNm%uEL8CUB65)+@kMlQFSC zMvROL0bFSREn}XXCBamfdmytrH|GEa^Gms*rPc+a4DLfxl?6zK1J0=cWQcBIE~2V$ z7sCXh7}-~vP&9m392S!bt9Xyq>iO71{|IRUh`#MpP`^OdL^B5Daa%B#tSmL`RscOV zwE{yl5-6QP@$C)}8Of^YFF<uV4o2f=nSP_O#^sL{$~f_33Lbop^qv@#bs%-;0S6Bc z1R?imXN+sHg37N`=>}Mhg37pi(uE_qk~0C<-5q!rW}R{_+Lkm@>a#58HT);hqmz>a zWSYt05T-4jh9e<Vxm}e)6baE_#v(PGG9aTha^ssQfDA)FKeuj-aiCZoeOi;IOqZTR zDEYOo$c#uMPLD8L<I{|Z(Fn~8Ffyfx(LR!7(WL$2dvw@QDY}vx31LpGQZd-`7{D4S zi;?Y-i?P#MZi#lAp{05FzOS$lJwvvzJG4+Owvdy#GQfx*XlojauE}EiN{<#8s86af zr-*M*n(4>hpsbl$v^X_2g{08=MI1tadKRm#L#ZXw={6H~*m1rtxHy(4S)Cf`>yu1S zMVk&sF9q8NS$-8qo>$$}w%Hgc;dsg5RS><%t%tT2&4i_t!0;`7E)x%Cq<gQ!;`RJ^ zQO$M|qb^>gER7h_=a8z}2!F5dDwt-?Aj7Ypo(hwd(~aWQCGm=pP861i5&D%&vcnl7 zE3+mh`ps=SK8S#T07<22$SMfA#r${N^U;y&`Fqc`TUxYdr-~lF{Q)ws6-e`KEnRPy z!IH|$Cx94(fytbEU21V@nL&<5Df>mKJ|-9|%0ge|`$r;_0jxLpSu{QdbuEJkgTXO) z!aFmu{ucmw5~|{%B^{FM2b`lU>s_igs#EFpl7TEcSHzub-Ba$+aM5vIW8n%&^)b@( znL+5$?!;bf%W$c=<@!~|z5-LLvX+{@>KQdb{_iX0tZ!~e7T~v<wx-=xn5TPHKJ8`b zvC-R=J17r`w_L!;|AildL1Wx5`4JVZ-x8)NWso4ST)P1;@YsIiYRz8rj+d8L!jzaA zd3Ie>%Z@~nwc1bYrwasw-!y18k7=oCQs`_LyCBUzH>ev`k5|Oj@6hY$SSiDuX<GNI zFyRtt(<gJs;sO+(D&oG-MpYq(w-#1NMP#ayMR#SC5Lk`3Fjhrg8tuoJL)ZUZFaK9U z`@xhNM8<R{L-W;wW|a0B9-3>M|NmKKr`Fld3Kme=#Kr0R9zgirJg3;|i}Zo@ZEv^W zkuynmVeNsgMdQs3#$KWc!yQ;SEnH7HpYJM&z?auNVuO=%se%RS7$+CsgG#Af6ZHYR zRjN2Dc@Gaj8}|uQ(~;Wvl{oKrj;MgwPUW(NL!dLBM6q-hBiaulF-hvww~abc!O48o zK2NmzeWG)&*e7oGi^#)m<FEkl^Fa0Q?ZVKCO-}aMKv%g<&N7G2j}mKqoz0|J4jT90 zJ^B2Q7jaMazh>{CNUBNF^2-Mo=q|ZA@0wW*VQ5qs(+vu!zl>|+Q!sjfTRi|s+V>S7 zu_oxUTObo0;OW_KxBR0sj}U$c5=9bhxQLb&3Zek0{8fcHw@eNw0o@kMaRk4o-f9A- zskIy2*)cj}VZ1AO2l$#raayuEr6=P|TuxME#X4y4aG+oQOtl*EvM_S+Uue~M4PYsQ zk8n$N&^M+FumUGoGjns=xkDoXcAc?NeH=K1b~&NxLir3)nqS#emm4vgJE<#%AY*!g zMxZ|2Tb7?_o4FRWd5TN2&?g7W^nv4{fGAm97GwiM_%QIsU!3Ya`k%i_0B|ZIx9F=! z)KV3fE1*KD5y}poSk!_L+U*Dm%72R!w28xElurP<i4`TX^~=O)c)LNQ0k6>6>0>}p z1DfcRq^X^aUa=00#!U>(+8AAm@(H;4)z(*X*01h84Fc(j3rvmz%l$V<KE%vcxho1$ zqYM!=t<E;5P7n|XoK#Rk{?pK1F07_K-ct;;)O~m#{N6KY5OLRam*2o9AuaLD)blu; z=eSk#yc-hD-F6&v_h7otZP@umnSoTjYK-qZK`|bzi9&F5#aJj{W^89lz@$e?$EQ1^ z{%nn#)3p(k;zN8N5*Wxfxq80XpB?{K(c7W5TO@q^-j)A~U*gY~pMHD-At$+}4Evz) zcL*i&g^$6RvNJY5Y%dO`rtn4Uh~iu7!}s<-V|z>HHAp8;StV;trd-43a?R{7>!f1R zZ41ob4!X%R#G1z5f8OTUDm@lYQlb}cqcMZ59kOmi=aTTyj?XDjexb!iehm}V)>S~P zEYAL5it}_1c<&$VFZ*)qdMtf#@$Td#{m0#YK?oxC&ur2MNDm1W9Y@j&>@B=cu!x6) z&q<zd2m3erF!nAkl3C=1)vVU65)kEu6r~4r|H}RU4k_?uO9|EMpJ`?Mh|GU*``(c_ z%)A!g$Z;nis8opDHR8CM>Z*XV7fl8xf3R+-H2bev6jkLx1Gx^QW;#Y2BjN5uXd;`! zl_Tl%t;pR--=u>y2ZW9paK>z1NM(S%s3h7<x~b<%Za5Xb#f^tso0R^kX3}UOHWh_c zXEY0zxU0pVLuAVKw19&B<$MJNjA3q+k2D*rdiBalYl^Pz;%d@VByy8#&$N0`P~D8^ z^CZGMH41zW{YhK-9*GIR-{;f{aGd}3i~jW+k6#_teEjoDQaG^qbz-J&GQm$@Z6odP zdRxOyGUpC67pfAMyUH8gPmh0unwzG71>W9H3iv)|74&?#eLNh!T)}(w*|24%>7MY0 zQdFT7b0rTLPWa1PyZ2NTI9l+K@iO7I%KB+LNrpcMYJ(xQED}#`8lS9OrB>#KlZVR3 zJVibkH=votDp$ij(njIMw7c%|(&Lf>gH{!YYh)v!%_JWmx}|7SUa*mi%m5^7r1;)+ zbX(LcA(so&9YjNc^HGGoX{E${>3H<?#14EX{!B169te)wQHMo)x0ZtdoOXg;B;Dh+ zLz=jPoz!*GELtVb;^$6Kp$vmT1G_`M{L=`)1LFA{`5lc_Xx(GfylhuLA&CuvJ#JDQ zPSn>4JmgsDAH3&1@mW1l5pl1Eqdm~W{)8#nhJ&GD>X)eC<RP(iLSdcatn0?}?K0=4 zTa@fRg*AoCd2GIP2uT}F3T8#^W{^U~M^c3{a7D5TmwuG7|E4?(#^G%5Jv(#t_T2Dr zp@YCG8cWzJWtIc^AH%TrbZZenrY?m=(nMm8ysYZfw&37<RlbwDL0ZJ`8a}uvY-$#L zGH@gjhqmn&6+4TOA~ff=s}}PMWlN04dYnx)w;<}<$S2JY;D^N^XWx+X3-<!eapd#} z$$W}O4s%0}e?7)45&rx6@|q2a6B!a*{_(?lQ-{Y;l&#L{yLYPta)RpqtuOH5vuz;S zGIZ<j)$VwBI9j9W8B$S$fUK?a=U*;o?Yodt8!x>x+6RN}g<I_MPGYB!A5;$SfPKI_ zAN8Iw1ydixeI8VkypGTk$=`*1+gZu*aE6POEU||<ZU9GtzE2NVXLr4`#DL`fes&}5 zQbd!j^V7){cgU4vmN#<RxOtN^z5S}J?aU({`FdhY{C&ZvSg+F)m*5dd!FyB^ckCQB zE*K7UY;7}<IoHP$!Qz04)C>{4`z1>zN?N@ebCs0YM^FS+4cMq%Fe@CL4!-w)FxqVC z*}r?tcYB^MugI4PzWNWLGC=Ul9*V@E_`D~|+8Wa`dVzaI;tcSsI25)p-i;@fx0LGM zc_IQMUi0PlV02&q7~Gw=);G4k_74&eH_4sA2VCO40FiF|8D{k_(x0YD@V}JU+^m2l zq0#{OTd4q*?&z;o0^mhUoEzfB)zYk}y$uM5{+YY%X5Q6wiarND<VXWxa2`p0lS;e$ zo2>6dC=Uk9w-t5%z*9JO(f*bBi0a!Z{ygca)G0S0)!=p+ifv|WbHiDdTU7{-3Bu01 zG!k+MRLd%|T@kXK)7#Z^KPz>Hu_F3E0Csg}=COC>PDwe(3bT=x&lr%`cvIgzw*`V4 zEw_5VUO4QAw)MHZwcD|vI&?Y$PbA-QAz>g{D?=`uvcO<QgOgLdPzsjW&A?_dWN3yE zT$o2m&(f?xse)1Tw)DPG)&<)$BV@k^k%!`uHV_4Kw@L|pm61xu$HqXJ<{O78<3_$* zdwIWs)|{D#99Yoag+D$0JP$s{L?U?I)~Pq+J{E=bljLFfDH@UhNf$)kVM<jI7L=Gm zpXvV9^u%9OF+BrYOHa#4T757SvHVyytX)WT+ZT@6z0rAR!t7=O_}@b}iT0A4Uoy>u z5TvW5f=2Q~Cmgrhd6R6&Z<T{H%uJh>E0n}smYQAex3PC<^ca`^n@Ov|ij{#`l+Rdt zg;p^p)<hynI<|-+yMqIz#L&iUqEb*!>WzM{BrCr}tl4;fFOi%ao=K?$XOlp-<!s-` zLQQQxH*m*Cty0#AFMRci%=lFy1s=4J8u=E8CDu&0U<fQWfeqkKzlgTKAw0@p;pXnY zpew9orHSiEGdPoI-tGqL^I&AYZ_i+UZS<k!Wigw6Y-LFyo*cytDfTx4eXbL67=x5a zLb;h-+eU!cCx@a-be_Un@m1!(>@l7uEGI?U>;fDgSOBwHH~os-HECR`3sG(f(^Eb! z3a1L4lN9GgLvLJ9-gpN3|Be1P)03)&7xJ6$pW?0O1gjw%qfv29s`!a3eiX8`H=$ou z@5hcoA3FVHdEz>v@&a*w0)Jm6%~j&M&Yl2QvB;)EwIC`;NO03htW|LL=x?|R-6a!L zvEVX8#Z?cWJPne}f-Gl?aV><myETh$mBTQ0Bdx<&DJ1^709%?y_deEr95%1={2hap zJ%st*UP!H<`&W8`7>}wv=qMU{;NXour0(4h;@B%hT4&uBUbfFe{LQ-<S|3P+D|tF8 z9%&lZv4S&SpOPJa;71qAe;3g&{hl7k?1_c`ZVh>rZI8~OaW8%T4w<3u60PSy(WhYP ztA#``8moZ8S@z}NkG~|W>g?sm^Isc2FR^^TmU8zRfKX9{eWV8oemz0_M3P0GsoXWb z*L7|Deb1zJ#HGTn!{VU(hLaBOXFMu-ODEHzr}Fo5_WW6ua)Eg*j~=JWuHolTu=|^- zhTLwHCHeP+N;~|GDRoPfSS)(<ZshT3%j1C-;oymMRHmCoeJ1uAc-Km$ZeIH}XT|9u zC%jR3NVv@5D9~C4oo9?$%k0_uOn-F$Pj}Fxp(Uj;J?s2;h6Nb>>nBJ8vgd8Etv93b zLUD9kYnG=dwI)oRMx0waPcxVg&Idv2y5({L3pHQS#rs5$Tt+j70;G7{T@B?_z46>@ zV!`!p?`F@=5V$wu3?bKhJb6a`1tf>)hA+?Y$@H){qKLnEZS!>M%l+D&roSYxKC10c zgFW{u`$psA`l&_ZB-rl66SZnr$%V@U+WZLXtZzt!BGHwzzpOf16IR&q<1C<3E9+Zm z=&54plm?;KSEXhOz)i;ERn?8kMJsBHj8nViLKTn~n^IyZ^jh?AkeH`2LS%|*K8S*l zy~WNS59K#k1Yd@Rtm>#oDBlhQy;*eMv>t1(j{H|#f6P#a64hn@tK~f^u47%Xah3Qn zxF6%(+>wh9dm+FihX})1KivdwL2V<<WpM!bL07di=v{A72$D>HVa%z%E%}V>Ab@j4 z&iP>u#_x|iIE1-qONQTOWrbZM74<*qXI}K^hl1KJ;Ki>uO0^w8+6L4R*+~TveoyH~ zF!;}n#m&tYCHP70&nKK*{{h=edM$+k#-9UV8~2|~Io=i;l~9F>5owhMdDkFM#5p5M z#Ee-z){Z(p5Ur;#BU`ikQ-Njol<$SOj&{S7w4`+K)ecM=`}5^^$i4YwEndh|&2uTz ze|N@<i5b0eDBcz{*$1-|(7ECGAm?!UV*RZm;u`SDzFN#tZhDH(?%Fki|N8XPc$G80 z(u;t6z*ZpV)$+1U&A5sOc<UswfZl2wjc!pVKtmK1IXLW8^UcS{7yG*zZtR4sQp>h{ z1NTq|Q8ulPx8!2;7F9!W(%`h`eTek4cJ|}~x6E(qco#1G+qP?omW;{AsKaGk#;G1$ zL;$idQ?hnzIS1y=ZiaQ&H4}x0c<r7^%Dfrz-p52&q5hdfbWu<#nl<fI;-S#G?Ug|u zkWp)_zt?9WPwO?75}zS6$Spg~JC&H2<a6s|*5&^+J52ZKQ^EPk8FiO*?sRiQh=6q& z8i--3%4C^efH4-CE1BCJS1(KPV&>hLI9pkf=*+Y1{TY<+_G4<>`nA}Pj+r0VUY_{^ zPv}%iJRPca9=kQXVoKT>BiB#P%A^anU_I=LfJ~?Im=%@r{9DZq>~nFZzS87oKood^ zv`dpfKOqk~ya;hmdirc}!EwOU<@J6RoC{|*#CnZuc8eNE=rAXR2?<&dS2%;CRIXIL zmJMHrV<jBda^hd51mk9xll|o8Y!LPX<Pp7%Ovx;3eJRrmjLWJ0<8G4*btc%5qZ0mm z@JMW`dPEmza0}XW;LiY~rN_^*vq#ib1{UTt4m(u0a<4YhM&7~8Ih#ZTMSBQMaDs3( zKS38-ZMA>Q4Tnjx%hS<G!H5~lCGxM@=Jy@;!FCrYB)`V{9Xne(LVSEKH>2r1eChZ9 z{K2@9{Pl;oC1!qG7T#LqH610$$uq|<bDL5HAb%I^n)~<`d4aw@oMU^mt}ikN<TlMi zFDo`e%}945sr-SRXowjQb+RFr_hlWGgeG5*OrbNHUR$TOR*|8zH-9x}I3XUl2yje2 zz7(|NpobOdz#+4(2nCVmk|OL@o3jm2wDHUS)8R<RVBu5|YXdJvB0bsB-XxZ$W)Uf& z+$zRu5JW1<V$|%xn$5Thb&qCsi&Tb@;GvOJs`PkWBD%Q2`-|M)q=lTTXucHOS#kzt zIPB<55-Eq2#IMi?7;S!{UOUB($<|WT5hL9Pw-wA?W7-aNvlDi});ztg%wm085Fv4! zVeDA3CV}Le8QNvN$O|-+c3rZVU#(}<p<k}GB!V&drQ{qtvD6YaASl^{EIWY;VVy6F zbDT!Mw+?w&+>7M5b7PnxB@RW97lE3*Q9nP_36wg&gISl8+go*~zL=)7`nh)hIb`P* zMD{VE=QeA${+C6d1__^>u`3;U?quYzZ$e=gEGoY$hnB={>f1=}S{PI!8Bxu0*ix<1 zbaI#&`OuZs8Y(NrEoshCyrkW>jb~^rIG7w#^tSWk;MDt(5UEvZGPL%jm?L&HuLwVj zSRCwCWUOX#k}Uq<Xpghm(J#`=#<2l%^7Ccr?i`hKlgHc0P{nB0H#>o2FJ(!LeF~eh z3L}$3r-JQNio1O7cL<5pk9Tg6LkMSEmm0UlW-IAocOucCsJRQ5`#hiI+11kbfk>Hc z9o7}~>@o6YTQ_-xiluWYMMAfcR0D34mbOI;N_5pw6;~p(FCwFuTqbw}Cq_w%ApQFE zo>8p;RFj%A7NGXMs++JY3k~<=J;)dJtF;mI&CO=(Fztf%XKCsxMy}{pa|<!&%U&*y zwoL8ZNKZPzg2P%wCC3diF9n$8q@R$^)Pwj(<Q~{Hf*|mN{|chwf|O!Iwz%k-B|j=M z{P5%YUW;7IofW@#`B&hPKXp5gtHuPZJGHvXGTndy#H;pNR>;xvXjf{{DPr1li!t*- zV5>N1W~dIe6=E5&mx)~4zEvp^ysAj&j$F-`A(vv?U}x_>+PB+$3KP_i^maZz-1N$4 zlzF<*YaB7}`H*lV_F-F$&<Z}P6;>*Dk>1#V7I^kr>W2mP3}xDVWqN0WFRb8Ypqf={ z#}P?-m_o)up2UeSG|X*uju|FRmZeR#jZzO)jYv4;uMoF&Y{<GhU|GdI(E<1)`>?UX z-E<U8+WQTS+M*@=ta53UsjKJ?WMNhc6n7eZTNsl#M(jfR#T>f34|6RMy4nazs9{3V zt)O%UktjB*mHyWBy0`$=2zT{v9;fqV%lTzcrkkO+rzw0!5BlVzrjYyYyLyGkUIK-o zE~)slT&(+MLPVt5IvXkuu8I={G=9H7Wt(WA%1{7EYKwBw1a8G`{K#|#5n@FFQt9(A z-_4$d_K8fngjTpg{>3p_E5kCcdQovG1ficYqd%+E70ACspgQWz4&Su{KJ#0FM&uB^ z<hjNsgxp1XszwdwG2*xsk=rQ3Q8;$tb`PRiU(V5Fh1t(`DzC)f%4M+(sr>XT8=P^S z6tza{?0z2pcON1I0{-_n_1M=~5uTA4^^31^6Z5`~`pRwN{)94^?Kp8uaQesJ1y=V` zQWBZXyE#2OGd6kT;bj??j9dQY-rRqm<3KHB()a@?<SIUVX?xt=&=LGTSXDHWpX&4; zyI8X_PF?QA&kBNCQpay;RMVmpuoZUPyZWMZjpmP%Fvv@ZEp`hqz4uP&xh&lZL`yJd zq<8H?-esK<CDm=8OF~M~;eA$pS>~8NUCN<^r4U!00$}!=@hfFXjFD1grX+ku>n{pN z2zH^963i*1;ACxPrWQY2s=%6WZ+6GUB!3_|P`94GzIRt!I5N-pT<7n|T^N}q(0p4s z8<$~p{|>xp)x7&+M=eEtx1uZTH0)`l+Mzi;_idG3GghZ3BzUe<$$ef96i!b2zk<wV zwc#2Np2Xgz2sOisJ(VfrxmH^<z2&UMgJKSQzoLtLxZe2s2abR&+NvFt1?knAm_Wvc zZ{iDu>6#&RCvJ(W3bwJtY5+6s9Z_ZNA4~)2CV!FRvR8eT;=yKfv8ix}o(~E}1TAk} z1KM$zcr<61=8!ZF4tK}m=ss>_Bg@5gJveTmO-N>DBNQoa^Y@R{Mxf^lJ_W?o1L5_Y z5q*lIoDQsH7dh^IDRv4P>FDiF!J>2DfO&Jj`6Dxn$7(r}+zrf%Y>~<mH=Hn2;iBGs z;VQXE)06X)xuDA}j8`1ONUC+M|L-F*JHK5`o6SXeDT*)r7VEN%9hDk?&qRB>(Lg8J zg)2+5pF`|{78)MA-{rB<(xY5$lQH6?zL!KeNToPH*;$~mKbx@=kn92suIO9P3^B0C z6P}@ANzG9qj^C9?3iU;A2$K?Otdih`j2jBm6p@t|cEWK#?_uF%fEw*%3YyT<3yYc6 z5~h3yQ2CXLjaQuINh(Y9p_}PpDLM3RlZJCVCUJJsP*t76@tE7m8|Olfo%pa1w51q$ zgtyxGOr^*JsVRQ|uQjpkTc8NXW-@O!13JVoNSPKV`9PO=Qv7@;_GG!AL^%-I=ut19 zAp)+-|H8pY&k81(2vFB1b|$|S-n^O<)jk`F0g<q!8%l?5L`7_(dQ)3QQHD>bQn~Bk zyKt802#6R7s;Ou@@{!%M;EkvR<{^Lg=ff{jXE&tC4jhd4$(Bl@^I*U%1#^%MnX{Mj zudnOAWqTeBdBcay2h;r{FpI1W?W0}SUW^)KCCw-IM2RNsol%JQ2&N)0T6Wtf9Kuue z)dndlRUd0_YWW~@wO|dyJr~}}WqlF~+M4zR+w3*%ecrSaEDZnI40ND^wjkn+H~9>( z3spuc##r&T3gt+Gv8UHS)BBeOmVSC5Dsu;ZuXl*cp=@+4NjHr;%P4VUV>nvg@IAIO z${}SI{b!A5>_?jV3D#81u8;kCZJrDXP`=M)_jV}<@4rKzi|$WOki7S_@`B)Jir}Zq zq?NJy^{wxH)Bv6@oqI7Q6HFWRXtsk>KgvI~9XGvasYPCd80bMBdq3U`v$;w9Ge&Vq z_4V-~%FoY7F6(3pOb49)r74|ThNU-}>BUagP)VSeCy%Ed6i#}!{i-Xg5esL-Pk**T zA&9&qU4**M#tETTB6zGas0(wQ=%_--s(o<uJ<8q__}ymNy;MLo7>&niw0r@mM6ke- z!JV)&T9DG2s5+Lls$O9wz4QQl3=H3U#5pZ>3XJt8Q!>ddcFHd{)}W@k<A(r{*Q5JL zSVy2Hw<9m5N?E2k{u=*-wjJObd&+wexRUJuFLnY<e7QvL>S*(jEk5~BJPVtL&@p~> zSfxMy5boO}ZfEkUYtDl2e4%QS*>6z#iv=Tp9Ov0j=X?I?X>Z@i4e|G%`duK+N6g;U z(<<K4YQZ;p8}Vc8CzYGRUj4=Z8hw^;DeZD+1759pn8*<{K}Ms9Svw(+&ozL39;n?& zT>gs)9fwH)H5Pc$g*&g9_L}EC0X%_Yu7*DvgmAFz0!2kSeYD*AoV|!v3F-}ZnHMmf zY+@q<VkOL>k?FUIVni^}GuzSObQ8*i8w%Jc8<?SBdx~j^pw6I9!k6k%vOU2I%wa%j z44a5dV+GZPKYuvTq7W6-!V;CLbxzSaqyKh+FXX;JGhCI^nYg>lQG^=x9Q5pbTYsNp zUK3<Uu=7zwYKmaVch5%k$BGJ;f74K9+(o&L`<M*l+$WOYy@2`8rz-kow2%}3LD8|? z{hg|nB5+n{UF0%WZx3xyzwr#6aVDoJ65SvXHRQ)ZKm#Y@$QiBrpWAiNGcd@~v(=O= zqKcGIaNgH!;E*tc0$Z?nYzrxwX)+Ht7(cI&o`?zL&}vZ9x}NS!#(4~yyY4N~?Hm_Q z@U=fZy>0HM3%Qv^#^z@q>t5cny*U{C_xs;f3q%)@8QQ-t$a_VVe<DI0HLL#m%7f_h zs2u7=$-rA+EEQ5*eRg)Fqr6DD&k?P;W%~B*yLYa&?>pPN_UuIA-XJWKex=VHGFblY zCz6@?mSc?7hjLkmh2c`&-p;`ZLh+~$(atmjyFBm6@0s~q`>e_7Sd;uLo5|@8%SeRx z8%}?I`h=v(Y|C+0H*c4RS^tO)&ffo}j#)f~^$~qYiTsmL3n-K516uAHKN{&+x=ko+ z8rfPTs_jd;$BL_s5^UFA4wb8*g3RdJAD{oDwb@I>UqnoKZn#*T@H55VHd!cWd2bxf z*)J<8o)V1KY=cvH`F!qtzHKwGu3y}p1|zcLQ7U<&gr8podP#nusy+?$KVVS5l1TdF zw)oMyph3%wtj9VgzXq~QWHjBi3x1Iq{7QE8uzDZMYqRZyK8BJ6lny7X%iR2cEP6!$ zp`BK^%FBJ4bKAzw2+Oc1BRCU08YTLzk8Sj+mMk5qBW6l(p<m6UcL#N<WM_}Sc3oY- zE`|TqJj;)K=yt(~=mBKG!}T!6Pshoh`bOC@-0#)z1)xtk+~y+stfP%3Z}7i!r$E5( zZc|ZPLe$B#!)noB;XL}^)(%X$Z~IweVVbko(qpy?bhu^2%BcZ0A}a4Y14?jAKYn_e zm=2=id&g(G;&*nxe%F0>b7;A49z+`Jre{}N%=TyP4G~O?6;?vb5z01F^Vs$>{;`T_ zy}6ju0z(OtU(W&|k~_@GCEx%1#k=r7eedvWc8YE>vk4gbE_L6~i2fb{vtzazWmkg8 zw^?Flgn*_vlbOXqu5p!V9Gl%!bDKys#^xpiG1~3W2&q!)m(Z9qJX!S2TW|CTrg09X z*-F)(h;b}LfG~TBUg3QTwZ5{&yp}*N2c%<$&4A@0TQJP>&ZgF{krJ|2b|u5ANkMPU zIf*Vy${Q)F{>O~*l)`fT*~U^s+<0nw`dF+Y;w_2rW!#M8`5z3=3o8J7qvr|J9Exe& zH@TOoIn2P&>?>$PwezN__P2zU-9QOAhCEp3Rl+#Ow^pIjm7YaSSRADhim8wI-{lhH z33T6WC0Ap0q_ALSbX&)46KfTVg(8Gu$}qG+bt&eRQ9A+$U~hj}ssnf4OK^UAUf)Cp zM1BRH2RHWx23}GrN@xH1`db{is^AHbk(TiPyLa%r>dzhm{&NKJu=s#r^;oX7eVL8= zJ-@&_6-zD6<I}XSU4tt=F#FUUAJ-S%E_Bsu_TdE(2!Dyt02p}jk1#sNrd=N8zCl5v zqDhHg9K5i9I3VKM*m^v=+Il!jrA1tklngAxn1|qk$?_Bc4iWU0*(s)Na5@Uw*zl5j zopoYOcdpwW-(B^PnBD9q#nAVp0eRl7KxDS;6fwE_AQI_vK3Kzj^6uQ_nlDeH_rugH z-QlXYs@8VzL>ITP`oeXb9m$IOZErSvX_HEDEmp6%x_yzD<pEBlQ@eb>A>r$P&GnZL zo8yLjzdj<dBn3mc6W2FkmzLQrE%s}B_{4!o#^{egZk+%R59Bwgp|P`uUL>I17Dd#b zogRCCKliGj=g!K_x8TwS5b|&+7V^9w@_hHa{_EJYWd8nbf}g}DV!-TiFsvKbKaxP< z+@PBuW10y#35ck%L?7Z-1pZ}1Ngo^Aluc2zOEdF|9Whv<JzaGNp<&df_+tr9qe9vd zJOe7u5jYETd<r=R8q9a3HIwJenXJLl89R~fr-_A;WzS>uE(DC@!oSbOvmKJtRtk}} z)sgWXVkDWxl6(`ZSNP`=w$`g9p-u`%#v25n=3~GCX$x9}R2Tot3pmLZa_wFgd9G{) zTIA$?@%siH4=#V9YuWbNJ(!-U$RgPYjg&0&9Q{(V*Yj2rry|eBEYD$2d$``KETs_R zLd)hflm^3r;s8rAelUB4j5w~081@=SmfRQh{DT<_F*84GATs$zm!mh|^tBcvvk{}^ z+9sadH^KWwB%mXl?r{T&qLknAYQA0D7N~L<DQcA@#VUeI%(sOyaKnf|DYxwwOq{5l z85Y<B=}gF(ui!F@RlodZov#L*fS+7p{1K2#K@VFaf-$ni_&a_#h9$^V0LjoH=)GK+ zU2)oi7GDxTc4MD>nMvKuwNui|fGb}Qz;ZBY;3Aw53<GeU;$ftppPg||#GSFC21YO$ zjN+=;WP_0tL5m82J8K|f>l*;{MQ0Qxys%&Fju;OsCFVuTX8Z?+u~x|UQag~o-3dow zrITEI(LH=s+vKE3SY21DGP{TxDtVTjEOE<vnUyo&>wvzy6^kxmf~a@lM+(K_iC-R# zu#QZ?6i$kMl%xaZU#4Tc#z;^TZLQ4zyOg@Q)`uAkomAZB@^KT3Ndgqbp%zEVf|(n> zx=mUE^pne|sK;gEuysISG_t^q)B8m((InGI<ffZjm*1t8m-DBEzu@Qoe_G(n{gB-r z4=<X#e8~DS*7yO@DN;d!oD?!_Kd%Gi&crSx1OH~ZIA7Z*yVvE9<PD%ELCK`JGOc*| z+MX@Q8(x!+B12==J~G{?enCM&o}O~%qAl<2-)NYVW=fvkyAG_qo!)ZJ@Iv<_8+5Sw z*hKf?{O^e<0YSmp`MKw<`<szKQ<v#hR2_nS0Z%L9i!ILXv+*$wKk^<=QbSH=cs9mo zwO~^~E2lQ++|bK9Q_rSZRrbGaRe65kYrzki*=Z4zzCoV%58tofZ67^Ey;&Ju8CqHS zGqn2~>Gv@%N)OKap&oQ~<fnScps_(NpW_aCV~s+L6Mr#)%C2<BabSsDc^i`<x)zxM z0^{b5?K+GH@2lOAFN?bAmr`pXm(SN=zV*P{N0=txn-3?4ayMJ#+xNI;A1`)M?;d_1 zH(ZmjhJEEN(ymh=BA#j6NQo*Phtn10uesE7ZjBFLC`KmJTKa$Re7O6ETup8=|Jzg* z-zw_ab{*Fu^272YM+Pd&rAMP@qaGzV*0y4kX1m)1_rT~(#GI)*b*=@$)9+MX7@d#@ zqr?$TurP~M!BK<yv8In_bwUuYmGbJP#wEd^w0?AJM0MR%jvyY~9n2<^=#ho%?^amb zD0>Z_D$iV~A?h-^{9ECaMIT*!iI!a3Uigh&`?r428K;K0jFB9XE-fj9K@)Yv;P)+4 z9F7HICA5^-Fwl)Pqt8XbBUDS)$e|5PHYfg_BcO)%c}T+<1ht|zknU=K_Y^??jrT_m zKIqu5Ki)1YBU-fkv!$xpT2l)7_G2b9V_DaBS#9}coCmmB|8S{LVcw7jUbvzQi9oFm z#o@?rD)NblBWVNTh)dfl#TaIS6H3>@iWaKH*U)S<^be)X%X(9sMzvN@VsD+|iG-1V z802;1w!Hh#*Sqz=q`&=_mxpeT4{jcoo1qM6yi4G<-B`-GET%T;U$*+x6pYFE`F$RI zQN{$!|5|#k{|#PMSzlkcKdy(-CxnyHP(tUh(}tlE6)6~*%ao3Ag?uy1FV;C3=;DJ{ ztMP&({D3@`^U%!LL3JV2)NyYYovja2=n6yCwNwmzUg2OnERT5<g!otrJ*IF|C@N3U zh;v47{FNZzjCvuN3FEA;D}gJz=A_`dYxfK>)WB{Yre;1Fr(<B;I9!*Dj-EX`2x1)& z3lB@xB@!CaG@C)`bw+FY@{v?D#Tl9=xKSi*Ap3b{vp=QTm9P@KKcEh1n#&s+Z}zza zC(^SbLxqN%Pu_uJK$~BRx7T8O{&N#WU3)6JCsR63?>1wS<}9Cr8~5pe40V8_X1F8> z5Q>4z@>L)dK?%Vr=`fRZmbxzh$p6s$n*#hQ`CVsj1P&2CB@+7zf;y+wR_aa+zTFiQ zO;G0GosuZO*d57a5M4G-B`T2yWzZH`DH29#D{=YB{hnd^g|_W@m}^?i_t8iJ>5%)g zQt)K_?bXdyR*3(mFYMo#`2(&Y80;c>@NzxRbkyo(k#A}`F=^e*%=A0+lcLO$r*s_M zpQ8Tdldr>fcth^!!B1BUr>mzfUgQP3wo6lvT7e1K0`I6I65mO7%Wew|UOL(o581<4 zwkEc{5XUD!+D<$!$B(jQt6KvG_qzZ~zYmrcr-GUry1H6Ax`O@gcSbii&(3JgQrKj! zI~|9uo%-V=hua34$@@e)I9~MAOPUsGxgP>Qrm94nTK1laJ*&=<im71^@R$tZTuwf` z_uhZVO&tF9gdiO17;5l~4cOnUS~}pZ;oCmX-=1`)HNE2c1QMf91IA^k?xL!->c6?5 z_G9)oK2$+SwHcx0UG^(HGl*G_+kzy(fte`bAiBIYKPoBO{7%MtS>)lu_Em&rT7Oew zAj|x@xFwFCZmjRj_HgN9&cLUx;7ll-Z6Jrrlbn+cd`wS0ec9C-dp_81`!vzwKejSh zn~_!S^pR&k(-OO@gOUe&ngyk!9;7smGVqLhw>IGZ>Qe<yhL%zhaS?jsEu)$l$O8rK zjXrC)V@<~p(@p=bDa!75i*~Rv^nnLLC<_FQA=GV!xft}L)~=Y+C$W&@Kjqza;<5M~ zIRgs)NEX0CN9rA^0}4iBgQwrYd?~fE5sTP{JmXqYhCg`UH%{j$@7{Ax8FqE~z3V() z<1(_9g~v|gl4cHVQ^hPbHzw?=m7Vv6)5?zlaQEQv;f?k=Z_Tk+p_Lx-71ti<nMT_{ zh@}l3S&S^`4XOKLc>w5$SsxI4d!e1@2r2vso-PowK)!}ULP83p$$jIH2eIUg4vBJT zJ|Xj#WwCVruCKfTAttkH|A^#Y(vXMgXNrmL7hAqCY|N!O)XDAvo!@Z))XeoCXa>Dy zU8&~-sFNtfUov&IO;}h{4Kez8^O$w5$YBv%IoPgaDaSG!>l0nnMJ<4iQ6U;%=LxK0 zQ)L))v5j7vuoI<VS@#N<8c;|s^p>;xeI<s;YvBoaQYS$qwTY(oY<dN;Ft%>c0?JOT z(l3DKu|PLM(KfCJ)0XvXrzpTUUB8d~Ga<V^zKa~Lus~JOT-Ci@I)9`-nP`!UJ|Gf4 z-;3>N$u$1q?zlA}ECx<wuo4+&LSLh)lk-;xA$lHdtkmds3lcc3?+Zi%ch*}8iWPA5 z9YLp|*x|9N=ZrL<voLX7P|(QY^%SX_;Z~l8+QuBy&LLn+vyVl&^CuV+AWlhle9h~p zqv!4xrQ{xw!{P|Df#&A|hJKLZ0K|Y(E)eqRAW50v0p4TeF#t&e7vq<dmi)sMvXgYk z_}mq8S3}4tI)2&F^5cz*;c}ll5?$=+uj-0!Nu~T}WM%nd!6)5e)@hNv<4esqm)K6g z-P@zbk6({OJ7(~1;cJT5*A>TNC*f@pL-xT-DYbVUiRMlw9jiI6W(`jglA%*AqI;Ja z<Tuv=@ivz^ua!6vgskf!U2i+uV_NdJ53v}sY!Ix<??Xb^)}wp6WqQO*Hy-N`D&oSn zCmGAKH*G)vw4;y8ij8j_sI-V7T)-oa1#aekp7^KomaDSJRN8f&M(0(h60|;h7}QM0 zht2=4VLQ!w_0N%Pkfb;IerDeyuMA6~FTE5o6Yb6;rkbE_W*B$E-!XbgVJEd-A(17+ zOPtBwh26uI!^1z=8bRNKxMTzivT7;9hZ@v6m8Uup@uYD3zg9w`2#pMq0bY*R7LS!) zYdw(rua6vd&-Np&lxfmuMjA@_e$256S6YugV2lk|$y1w1=`KaOh!tE$3+FyND=|uz zQqvN%2OUYlz;xxPMFQwPK+am|FsiMTJPZHtd4}8LY3Ss9dK3})vtG3y&pPlAvai#y zsH!F-{G0O*L8^55Mb9qc%V#5A&7C9MjjF$u^o1ZLQI?#sz%usV;{zy|<h?h%(tJYw zoc=HMq=UI%2Y#LC5Oy>Rqzg^hWTHl|?&eoU)YSSKnaU~JD)6D>D5`QA>QIP1_Hn;( z;$z}VYe`{&wB7Nyo(aEAzCto<))-%p(tK#Log0n@`*ZFnzE1{YR2$?;>-Qbts+lz= zPc{ua1@k^n7xZKgM}HKXo}Nb9g%ik&?9snCAf!zO?^~RTutxe5Dm)V|c*S}j<p=Y_ zIOS#<-$B#Lh2!RQ6>7iTq{7T_Z3=Ta&@Xxc#jya*Xp}h9aL<}D4T6X!ojO&GW_H-0 zicTy|OhsFq_9*GUmVROM!?g5pPOzj3366^#53SR(mAeit1CY-G6GPJ#Dl*3jy%;N2 z`09CogewJ$c3KpB&(MA4gbL{}&s;@0Dxt`UIzgf3^LMd<iM~LMEZh-QRG>EVDEtyH z7dDVryrbjr4a%;$OYw!_E!u?>QUj$>lgiiHnUaMo$9~LEW}mIxsE?X#1YuY9;}PnW z^YLSXu~KTEDbmHP`%(I!<Be6focmiP7HXf8GUee6X+y~pXMPa$)<`5aev>Cs8tC6+ z47D)`+FfPaGUW)h3;QxpE0I!%W{M}e{mSN?GX?dh(1ctc!b1QmJ^6PF!=$e{L!AUT z^Xbz)W8Kf6pOAnULh{qy-66WC&mo<En4iN#{<#f;K|@K9I&Ev0uZzc+ZSW{Q7Wby^ zm?Y7k^`p4PYmduw9&N2#4=)Sc`piu~)~P1;Ah4-uL&WJ;#`mUv0|W4E*F+cH`1q#z z_@<I~3}63RH?0eiF4w>un`ZEO>7(%xj9?wFy6m+1H?b%tljKDMUiW*AcqjcV9R5`} zqX8pf){CS=_JXTD6HV!I0-vR5^e&nSb+ab9c5DRV%tPCaM)W?rx-^EU8)?<CYh4r@ z(fqf)8TCf^XRFn@m@=7I8lfKA(41=OpgJ?!1V-`RkoRD8ru!f?OD?YlAA#Z2TkM@6 z9em?`8Wq_$*zjmYz5U#J>N#aMVaq$>CkE-g6MLPNWB785KW{LpW>j3f)q(~@lXUJg zK19IF$D0ouV2iSnoOI|84vgUVvC)n6L-Re0#*g)4d@6KgoAHP%JKOq!{)H|)H8+5$ zg7S{Px}NRB7n=vTiW*lsY|%_%G%#E^$xf$tL}*)NLu4p}rrTjUhF^2kJ4ip4^{B9` zGM|wk8e5x3k;|9=U>vx>!BY8}K^h^dhO7a_%+gICgkICR#(f#rt=9cY*<t|gK#Fq# zL$^SYd}%e@H1NJM>|VS7wK9ad_XWIK9f!(%I?x0wUcs5*AW~2o&u$0^VJ~Sm%h=_U zbrX_{iY2K$uYW|6)LO7iDaGXQ3I5%Z-dqk?K|7sZV#TALsO!qXq{_<C<XoZCXeP+S z(_e9^pnj2p_!qv>S$x}K$=T+aIKKaKwQGc>ObZ24X16w3|IzZylOP-17ik0cdIGKa zIDQYRn54QmP&r!^pnnmlY%)efI8u%&opa4In7xq$ZTD#H$G{9aQy>a~KEOabiq`L6 zS!`UkO8<-PfzQP~6@G(#@$dSXB9!BkS%GVv<3zESrNVkrQNJ4z7NGZj7(k3%6Y@p@ zH%H4D6qhY_G$gTvLa#du*NJ2VTM;Ke;(&W%zRJGPPqzHBii30vx{yhz-y^8&z@uuJ zGs^U9l<#X(Y-eZ1%O~<ONSx_5(FE>>ElQB|K1ZJhBzZ(P0r1MRjF(J~8D0W}Zo`)l zUkd>hNPTVFIvIR%j@FJ;lqSxpY{7H6CPlLyxI^~()~ZrsO%ps-?MVuebtYdH;1S6# zQ*W=WEyc)<N65z37{3CTgq9TID7AHZM+k#V&E6t$G4&i4+rz7SI9~3x|B!k>B<}3= z{QUgn<as>gAS>?`a!p{NXV5jGX(XVt-R>2+J-70SDMi{NKOd>V*^BFO{On=($w~Hp zztM9iU;Ac+Dq)CLkjH!f0I$F{+5*jXWAl#o-PX;xCHB6sp1sBQlV^OQqnEC|hDdLe zfcfJz+KpyVvUtnPN8C#g*)J4Y&{rd>zG2$mw^uKo5!pPC-0R%%Nw&CUi($16yw3-y z8M?rMMnqZ8WxQ`BrY3W7@Hj-t9Mcu<sen};#9c<Fd?Ojz_H<{F5m^gYp|!|9m|W0= zkK&^VkN?7*;zO9o=ksME0><sjD&C<;ovG=1MW<@yl(xRQgYeI3dtyh1wlX8WN*VLs z*1@!1y{fbA<L5bvXd5lp)UY!fj`5k4S^9Z3DKh!v=_wo%cPl4zH}-z<;`Z!z=(oY( zh@s_{u!Vr9^xEnR$(P6<_~lBj>*?94=gdOY@o~fbVl012KInaPs=`WaKAmNTQ|SN- z&3UY8uN_W_<`aL!xS%*{q1ZtrlQIj^wX1Vwm7OS@)Wpkll=hByqg9SsyVN|M--+BI zky-j|_PdCIG{(X%W`BKPwTb$jweT|&xZ$RM%TnReA8&$7JB-y`g=`E3FViZcIY6xV z9OpN_tEI4D@%^f{G@+SPxz~Kst0dwIj4O3}ijq?rwbpdjxocl{Vq8kt!KGk{lZ1E4 zMr95RSw>xvWppeWFX$EE(pJf+2|)YxRb;O?=?Sbv6>Sy4Vj}b}=CNy^uXV^BckB7; zVIl9pKkP3SgEjPelwNjcS-(t_c3PK8bAhQ7xviHb|IA?Z%C;IxtFS3=jJ3%@T3F0M zAPihR#@B1KpiYkZTCgUl%mI;n*Rt$f$Ojt+QT-_vyi86FB%5@iVH$M-@Z>Nwb_sY2 zF-B)H$#oL$l_<T!L)E|&3G1yd%z@-^=qN&)4Dzq6P<Vm*SZ>t0g7jWdrb5LA&|Oj4 z+?H4rl`Tj1Vd^~A(=qmCW=f4Hg7irhb~Q6nhjSRNfxe=<Uv>(0t?YtMMsIIG`kYNJ z`qdX{XsIcEir|nSx<DeS#EQ;riCy6sp2V#RL^>iWEQ{zu&U)4xJC6xRg+WM;0#<Kq zyC$Dk&zxB6D~J;A<n-E`gP+QAK!SnqluN%g#^)zW*JpNf3Vr(Pb-cq7CDK>?taI7z zV5c+a&A+obUL#(LP{FhKP}#Fpb_<j-9R~t_aVe=ATky9~eiv9Urg#rVz`6ND*0aU6 z>f>b3W!5%crxZjhVA}B$roC^~+DKhbS1iHH2CmMx<8J+NubRz%4z^gm%`YgZGvlDE zS*}%5w({z1{_sA{t^GSrE~Z-hke@cazbD(|JBbhB(To+GoGYgB(yosp9-SH={NK}> zix2svP6~<ryyyK$wd2yZB=*iaddQ#LTy4ni`fBS+>TKeqcO|HS?G^TrF5#C3-&qEw zrLdIRys>Ac5AO=KQD-E1X?@K3;Sw$a8=D1CrL<7S3;&=^n~vw<C3_M!Wf9LIgLj`e zMsGl}rkKf=mKuZ-#G-$_VacMhD<dTzusQp&{;O%VSno$Ge0K$uPMe87!IQ@3IDDGf z*viG0#7;ikZSgf(&n10r2{+Zg{HX#rb^o(2vm|}s;+*(2H6=Q0mEum5`18D(4_8Uj z@WUPse~UKv7FU_C4?Yr9SMag+IFVRH9mgAe`Ocf{wd0Rbe%S<}Af232_P+vWU!8E| zkTll0=UWPO18r2~{wNDy6vJ0L9SS>~Uj8N6Z*9>br1>OQt-869h3?W~zJ@3xM{a?1 z%FS7$a10*2UOJ+J$I_>ctzD12^~&?OA?CTO#k4yoNUQY8yc7%pr%3i0dU{9_`Hjhc zk0<G6G@GwHW^U`7f4C5tS+rsi{$jt~LWD6p_Xh=%uPdskABk`x<+3}ecx6{KQUJyL z&R+iTBkun@@Zz1nR8(XK3hQjVqanu#mX5!jy&(p4!r4igKCsD%HC`k0g}dPaE;VL7 z@2EC9e<Sc{)DiU2mcfDD`=3QJ&wgU*f~z>XZ+&5-c$JQa{AwE<v(btM^hk^uJ}S$t zEZQ!NUYM)f#IJY52`zmb`ZoYNFSbUXabq$zH=g}~>h#)3V0O>7dm#y30uG$XzL3I$ z=UAR0$6hI0724SRB9meLsKh6e$hc}P7t~rCK7`UV7Z4$5(QxF*(UFvU(~GdD8Ng3^ z_FchcIgI`m2Y?`TF{;um42~iR)}Mqkj#1N>R_9PS&Fz@z!Fsg5sCKC+a*ivc$zC!` z*+>BxL$C)3pxH>)GXc^ak%>$&$<9aJMe4JK*-frWAr$hHX8J&l<E(FCTyxo0JM0+2 z>)7+nW;gSpksR3iCDN!jAHx#_sRU^uJ4D-G3~!r4S)VcvIYuIQKIkMm262d_qDGh- zGHWyD##}oDC#YY#IH%!qafK@)K5VU|mH)V=I6mBZd?fgHMdvCL+w+_5Y0@~zo{xx; z#&+*H`MNz=7udTa7$0u~LhqO{{dn2zv^c?<g2x|p7BbV^O_=$!oH%k!;@dag-J(j9 zTa|v6_)q(;&pbk_<Hz??CHFEsTJe5&_vF9EZ@+o2qgq!5keTley(OS+2m*`I+Hd2B zKklX4S2f|WvUIl!{@P0_+VvlK{*H+Hc8N~@tD=sG#&UQ<MB0pU<ALbSR&CNsv3?Z0 z8e71}E~!0N&y*jljL7aht0Q@y*VeG|@U%R!LEZSYt5s0E@bSeW_$L5}O52t8tz=KG z=qmrq9wht;tLh}{jSwB2Q%0U8Tal%uMaZ0c<W*&KZuemHvfK1D@78DZtQlNZ6xYN> zGQG(U8Pcx2m0yw8F>mtSULgf;&NDKbn9a6!8!Wp9|8Md4B<A08dONWHTIIW`q=a~O z4rxp`?@#CV_<DGx6g(zXR@7C*yLv}R(HWJ;eB&PA^oJ|Sg&WvO*X9%-(!vdR7lq;| z<npxHJjBz5UFF(NalR{~*>T`x<Jx7iioJ$C`FyCO2oeVowZrxtF}LOkzf5Ln?)nd2 zsV|}UBvA3k{WBWeq6+$d09`?%zOzFCd4&a4s}gCCR>&(?QV8n~N{VtKq&OV=YeF$2 zYL!!}b_(O59@E6b<E%nl?gkff37dV{cQ!50L&1#&%8~;FF^(y!*`r?ER#miIq=l+h zC~S?+UK-48$FD|=LSh)#G463U_~0IWx2bjnRE>KWycy|L6!gO@EMVz)iZl=OwZRjL z3pl8l0&U|GHo2N`0r}wl54r5qSA=ih9wE=ikGTC}NF2}F_&<MQ17HAPxMdIlTeMTW z%MCF95YaY}r=Rkm2BLV%%Ijo2QI#tCm0EZxO_2R>E4#D+zV*JQB%v2gEpv?GO&A8n zCUR9awJac%K~**i9od?{%z0N2Lc0S4N(&`BlYtFdA}GfO+QT^K=kYX9U5F?{mb40J zSwPa85t$<MBWIyXlg2=K2C)n9W)aqA>RyhqOa(VSmKivJ1gZfKA{fKaYk<l`Y6~=l z@hc;e%n%!FcqO9uDi{r5FM|*-7~{x;h(7Sh{l+pQWTcjhe)aOAOm6ruqLLC&254`O z;DstsmTF-b0S3yye?tq+d1w<+_A+R7#04re0NCK7WJLR7dW2gV0Bu%TiZUL7UKnar zFdeZen)PbnB~#-g<coqD2V6uNin}E@qN93xpq;`vqS+;?yv4k+?5h}TVhR&Tv>#Da z(0<I31Fjjy5e%>BErG^>?Zd&r0hXTlFkJl)pB&)w`RAX%eEITE{<r=+%_s4H{y+V@ z?Dz8TZ!fMc&M&VouGqB12UO#)YU3l(`32D+UZ=dgBrDGxxiC3F$Qv`og@pc+j-+R2 z@fW$+=Z$B6c77WBytVw1pxi#f^B8h=MtowDBX*FnF?5$1U#uOUsm`4(VWNbK%d_|2 ze=q+^lzw1J-i(wVe&!K^>ZplfMnBJQh$hZfY)Lmrh87zVFejXm8}ZY|Q47&A!-nJZ zl(J9Ru#q<=E%)L4kIvDJJ|uPE={4HeS?39!bCSq8!j@uUFP-DVq{If2ilfx_n(yUB ze6HM4jEITIl*rodnt(V^<*It7nqw@klfp{-6`){TsKGK6((!}+J^sm8JLyT7kdT96 zU_5zPIX*hRxQxFW&u#DQ<oGn0Ih$TUKvr^mAp)!P<m4DIFgZN2Ut%a3L@t3OV(xc$ zciBpLX0f{PLXIQN^ZexP-rg?zCJY!Q>VX1mP{CMsPeDKUJ<4E&RdTa{QT(qPs}faz z!Gg_D-hyzDfYu&hyX3{t-=)a&C9bZ_AT==2{?zl)(UFcu=mPq019DaUd=(QG!+Z_R zfT>Fo4xRQ<U@bMSn^PcPVQoTt`yN$K))J6cUP#*}ml;t;5(+S2On^<ay_po;RlJBY z7-3c3Rk&X}#YXoLXmj<L=6(DI`0iQGxgZNr2sA4wP~KB(3x`1{YQTj;nUcsf+}^n> z5XKi-V8h6}Fb><n;JVYK*EZFTfU0qeSS7Fd8X1_Sgq04ljH;=@6oeXXm3J|V_CUfj z3D@)Y-g}Xg8}oa7bON8BwBi=a*%5P1q^RUJo-2@tYPc`&C9pT<2=8hGy#DDY9}%v# zvi~j}s2zqX<jTld&3#L=9!Lmc=`ea#Gvano!bZ!-B6#n4#zEqp5+Qd=C=!4{I46hz zurU<Sx2M<}lRGX~b1aEQQWyimpsl74e^!E!;Fjmc#+U$=fHyuoW>9$CwMpAMAo0ln z#<B~RBs3-tz%1)(ktrUu$BP6isP+n@!$a}PZNl4>5vZV%H4TaZSPGk}NJsA+AA}YF zv_vSQJ(SUdmarJ6gCOvj5d?}aplc-ox<KvA6w0*(7+ZsqicoSN-Ktrj3*kSwR6vUC zn_q~^XtS7A5s(*@WI0iPp@e|hXXqGJ$BObWpm>^?X{>$q7h#Pj61BvE+7ue}{Z%5P zWi^YM#q|J#ux1mj5}}-R4kKt{pd)>uUjQ$7gcz{usgp1W1(q@y@(#+O>XW&fVkEwZ zs6=;bfM2=}VT=O>sz8JrfLtMP+@>J521Y=lqZkDNn`^hf_zS;qe0)U5U%h(ut#5sc zt3Nc)i?|y6oByl-t-j)a@aO;7#l=bd$`NaLJ>E&Xxr+Dcuw{EP-`d`q&#um|PtVV2 zZ|}yB))ERDf3P|Hh%QTs)b5dyz;A5E%xby4v%@9kj0<3R#e1YDr>FaSdt0*^LwtI6 zM#pw(=8pznU&R&_FVXsx*8!fPPma$>nt#l^Lwv65^UXPCBn3#Y!~pc`1cR6o>bbqz z-QA8o+KqRa=)yd{fqIMEYW{UDy66Qi@mo$?^NUMHBh1ht&)3WHON`_92HOh(%s^hl zVo2gcxowi;51WJL^1HgcIp_Zy2AI3jCfn^F|LF6Vuisq8?yfn+d<?UhVV5A@^BgYP znBkQjiTz=-SVXLtWx%U(i?~}`i>UH?5In!Io0?;e8b!7q-~PbaH=Awl?#-V*J^b*a z7ax7}5zN}ndVG2FPAsJS#pX-w8Bco@Lwa+$vomL}i|WnM+wI-`?VUYl9AJh)_*`CM zz<L1Jw>PuREe84YI5yBPo__%S{PWL$^;duOH-6(ca3L2b0);VmxN|`xS1r^P!w|C| zL!H%k7y?2abD$ZNfHFOhU`fB6EF&NR)f~}P&_04DO2SYm0W=9B$Vd|?mjc#LNs58u zQW9YtZWZz)x(a=Shamn+BB5isugXH1&?s~$Tg&S22x>L%sg8wGtvc_pfnv}@2`VNu z!?c<avc`G|NRM`36Eqt)yuegI()&)KR@!_Lt&T*m;`x)3V31pFuFCfCBMc~3jVDH0 z0xgZ^^=A|W#MNLKP&ICZxLP-4Q4Rh1MQt)jxCE!$7`V%5CIzedRrVwJySSOH#gSRH zPPn-=ZV{{Ee<3Qb%@~&f%7xk~m~^PdJ@x7*6pALwK}KFG`6-N#y;Q)To}R+=GbISc zg5fI4V+m^p9xY8S&Rm(j!n=opN3ydy<I4YyZ+zqM@GyT~_Tuf^x8M2BcQ63ii+J|7 zSb}rrnNckgYVc%)k`W3puv35gKmI%6`IXWB26&3B>25SB3kg6{d=KPMEMWk?@JK8= zV?-0GJ95mRCC7{=T6u)UV=3RmuoZlSiVr0e=OO5Wz!xw82xZI&DupN>hRE{36igc_ zXc}aMK2E`mP$Fmm9RY(XlBSMTn+7svBj88P#tksSi0UPjsOo{F9~`L0LWw=9rVOA+ z2Fg+eO@O^I3%b-e8wB72HGatz0wq&>9;a||JrrnCN$*mQ$Yn~7J+u;yP>v5o9|yiL ziqoVyN~+{7uZ(*y44~Q+Vu%x1_QuuJOTL7Kk{2bWE=mM^#p#h&0r@^xouSmm>4Sue z9amHy5aC570vYcPO`7P<;MEchzEpYvB-I6)(6kzlKS=ZCLeTR)hz)hk0KG=>Rf)^9 zvuDqqar?mrua7_e7$L(vo5ee{;9p++2=rh7EC1`8Yo3iZw&%0${OoAV@)etqz0LTt zq4;qm7Wl^cM*N)Z-ag9#n;7l&&G?jJ-hQ}MZEwdm5@u&-dyfsv9y{Fq-TnQm>suT* z^9OJ8L##yOQ7QQRdL(uukp!M|l+9q~;@HZc|DA1Z&bKzhY(8Tb&C@vh8TLL01lrsT z-_86C7M+E9COTH!U$LoiQx%`Congj^-Ns+w#@ohR%wv(?<_EU13@Llw{CY`ZUgp<- z!4rd#$>o$qZZh>PuPFeHcmhpF)`jl|Fjt7VbF=?ONgOQwE7|k2ix4gDQd_8uycB4q zl^se4LpQ-f=nnV9e;n3*CiW_tbd7QJjae$ZxxBhKJ3Bo(di(nItIt0B{M+C9_ArcG zOJgUDaeVsV@;aU!*W>)Xyu3)tW-XR~#7)rCp2nY{=c&h3VtjsaetC8I?Ai0}`8KD( zlP6CO4i26^eagJQdGm&PuoPS$EP!RldWM<8Q5D7ajIe1~o63c%Gzn-1;MG1HoLm)C z5XUQza?lisYRdH5FrA>{G@}8WF&6wlOe5TnI872dKES=1jV!;=QG=e2fDo+eY+YEi zDNJ3EKryyiNY~}YfT`3#D10EAPhwPklV)B@vJ2K=v$si)hEcPibgHdTHVb~F_7NBY zR45s1hVN1Gd!U)LXC4Uezc3@ZD(@r1e=+*JJ&=@2W+|MPRT%lomr!~?Mm7!$v>p+K zS^$qWpBdur%(6#FlWQ^*AW?{x=1zVA1XpsN0l1I&4U4Z{z2g2(C~SzG@#A7h(s&g* zK^9;}%+j(!q4<?Q_h)H-b=-Xf8Yn9CLaMYZVU@xr7kX8=SoBD)rEx$$3ANpCKX5#7 zln`3cv_S$DrjSm7WlT$MpYUaf5z;gZLgf{ZCcI6xSQZb`s)45cg0VatSqfy)YYHPk z3pR1I3DWQmSx$_Dbz)#}Git95fUoY1R02s4BLMjl8f0XTTnP->Er2G%QVHdnDG^8n ze1#G;fm2gRr?6q1X=<rZlmu!(<0vWGgW1WkTmbUkzPwy8012=v7+t17)wo4i(i9~x z$EB9hr9_n~57j{TKD(+iC?Elhb89DX6sVv|N+lyk+8Q5+1;+T)Mw2W~XvsB`M+grP zavh*aG#+j7Rl=^1=3@Q;zB(3~B2+am#5YA`A+61lq?7BMdT>NYosH-60AB~HJPcsu z3huEK+#y=24no1EDj6kD4-Y^5@B=r%J3I5A{n?+{ifv!Kfl0C0{-Iy~SHge5-~8); zVQquGNABt3XIf)-yEWU|+1W=JKO(d_kN0!q42q95GoJC!_BN9EY;(MP8$TfIOW)D) z_(G}~eMQASHvHy0n_C3gf)ZmRv|AkTb)dp^?S_pn_eFNLY{l94vZ>yg&2}*0q6?kR zcjs)UHzM8o+AM0#&)l*TVv9~46hm6JM3l$?GkW<kW41`KEoFpm)?x?Ca5+u6isBKU z0bp=o;u=5v(em|e{NZbUKszQcS0(rL*f_yN#Q37==qMwJF9z``=j5H=*aMSoZJjDe zw6zgG49pJy`s(WZ?EL&9{>&A9+J~33DK9fZ))_V!XrrVYM_4Xh9sjY2(T>!cv5luA zA&Q>UubcRmZMu}NGsLIe<Kyhlo<8UPh7qgG)0!hsF80GLE2a;Y9_2Ee@0^^SMvPcX z0ar37cC4m&U1Yw63xSxRd|Em_I%apvn&;fdcs`$9T%3RY`DaL&vdl%+cs`3X`2p+< zJRYYS=bnNZ^D;o<#R?uO<e@-=ScSv&wp3H3_Y%-q8Egnr=v^{ELp5dkrm%h~Ae4+| z1=KR;lHP-9g!>W8B+nH6I`5^4P>02|)Kz)y7fer=0#(^e!EFetB_OOoUJ@DYfz5)# zG8+N82BJwHhUSwPMQ_p!m}~ZKRom?Irbol5d53PDK&v~1Qew04B{slIf(+?|!iI+} z$g$UhQQ=2%R?Xv=&9f4tyrYiL6s<jh^D@Of>#d0rO|&TN;W$7?jF-ehgy=w3aSb1q z9}M<TE#aa0=(oue19W$HAIhHY`a1qt>+RdO!wZ_R%}&R-s%PZ3DNAigG{7B(rcemp z{g+??8PdZ@m1jw9n8;mnVUt3&p=pV!Y`#JXzy^C5gxp{Nj9xsbX$i&5Xi#j@^$rN3 zXl;(bpz90o4UCz~m$&0iT(>2F1ejDb#bWnGNr)hineKo@WYHI>74jviW=Vj}f&nd_ zCRtn!LSba>7yyrUBoWGGh!#;23We#)t62;izt-sD_x#A9&_oII+7~gB+iafsk!cy@ z7sV2$ER`232ox2x`V|8@@E{GFWl_L-OHF`WRT#b+jDV_fiy%eg7GX5d2L~hjtTBM9 z%#im?QGqd(^~u;ug^9EQ8Q?CIUP`7=-qWk$)A%%%)W9OFjL4(<;ekUQ2A8NN-E{=; zgQFjvYO6~}86-Uv0u3s-Dw&aRKs#qkZqu3zYO4zW0ZlxauK|dg0cf&BFOg5&{>-<& z{lN$CbB8!TKd1XY{nJ0q+|9SQ^6ycJ#Rm9a)l2-X|LAXU?_iG-Z?|3Dvai^QcX|(I zTeGmHsMt@gU0z?oGu9WE7dwea7R7NHj0vKdFWfQOA-_1kj6W#8zMXCF<~@lm4o1O5 z#Mo=IeT@$TBUi{Qv5R5FZE&o6U^CBSc6xHL&SKnTC%kcWd2?}bm4Dc~&R#vXsT8uc zu|40}m~F1#Zd|Y35I;V|&EwZ5S+~$4fnHvn(yd%Fl+7B6ca=kxPhM_SpzZv=zG3WW zaFxf9;@Hx~O9I>T>x-+~_1jHmKXT-Izsw*5;?}RNf^MSea*Py&3x2#I9DghwcXW)} zvT2q%tudL)K*eY)xWdt5>#?wCI#jv`!bD4e?lxv$n?~1fuHt*kI1AS8a$?3Hy!`P? zPHt8hgTV-#ot?oP9PD!g&xI6gDduG(J|Mt<XD6pb9KuFV83Dg4ZF9~BdD|N$a+saH z-Sr%MY{<v<`03N9Po6y4-Q9ijCcZnAII(BWdu}`~4DT2iUq+O0L<s@|$Oxs$GJ)Cz zTFPjzjb>_#PO(Z(eBGg=2r$B?sHRLct4^U17`B%P?4gyq=sQ9i6JY9T0TVQ{k>x7K zzS^=`Y8(-BLR)(gx=gDD2zxn@QBqJ<mZF+48VH3CMDt0Es&CQ^7$?pU8HSk!EX&jf zREbe@ilz2buedrs263YpP-D{C8Q<m|T`^yU-o9rZieXw>^NaA<@Lvd1uPPu*3$*qG zp1)J{>#d0fG-;yNC%nuE7?h2C!3aVFARqVLVFOIFUxzgHMF`!>S3dXl+TXwA?Jqvh z&kdAEyL{dV_k`|2L6#7~;nCINuiy&*wLkMK2){ZaIsZUq<cpFu?f}Dv0ihKXC`Bgx zJ7lB)8`|t}Y;kGo0=$h)VJMAZXu_B}!VRSgB}-u(n5espHucg#(2TeVRg~lifU;2~ zY}&7UTxhVH09EC!uu_0zq!nceNUa2vacO%V*aX_Q#t;x{gdQ67P^eZYUy4eq*~mD( z@6e>npcZPtqM{_CmlPc}D<G8f5HK%Lo~5J!)l&4M)I{$T#0PDOBwRBs<&d;B@|^@r zg2wV1j5V7gL&n;Z3iu2b(5y8EC=@xIF_Q8<m05~W5Stl$fsu!Lae$#mOa~RR+Wo`( zvK05{?X{UC1`3RX@+B0iL=!z2nRW?C-6AHM_0XwaC}ZE5<n8Ua!LY$NIgP&u?k#(; zvD?_(-Q3(;-`u@j+q$~hxW3uAS&MDU+Qt^@_z)y(WH#GmAG#SYC=iDhDL7zgA~Y{{ z^ZCwfwhfc~Jl^KxipK?+T=a)Iy17BPgFR<xHlb{o(8fk|eUpuF9r1fdd0bxSTdoM> zhm~$GudYMlM`S6BbhCLByuqF{-e=v|ijQ>f?jJsR_WbGd7f+wRw}1F_pN&1zICgfn zcDA>6x7qJ=Y;Dgs=UeP;Z@0GAVep?3i1CTP;k{wAeR<2a8+v_}HM8Zurh4ec?M?hv zAv~L7cFgfBO_w*f7x7C`9BqYA7MnK4A~wj^m+^gL9E8egS(ulc_Lb`s<9<mfyvP1) zM||sM9f{b3#&yFwJq?eJPF}uz{n=+PzxTZ#{Pu5u_dDPD&X0fmV-_d=@d8T>+V%Ox z>B-44Yc*m-*Km*DvgR5~lQqUe524QD2ZZD4hscp4KQhlM$Y+psUz#Z`Ti*{p_~6^$ z{`SxR{Lg>#$tQ=0hg=_!hhyF#!e>BM-%ye%U5c<C&_n}rKHCKK{8F?K6WAl5nO&eS zHorbp!BhHA1gcb+o|l=T4fh23P#LE)P?DFs_HNAxXd5>{uQHlwqOT3+jk*UYe=L@k z`lX{yF{;hM0VBCU-na+DXj3%xPdprlDVqAhXl@fU^#o150&NgGG`9&b?wPVQ2-i0# zyw_*sUg(tgXvgh<^UjMQ@WhmX8tr!;dGqP|R!|Z{lCTMydO%6kf?f!+vkO~CgbYf_ z6#|-!h4(pqV+gw&UNz;V&3OXupbR=Tm4e{hfZdSyh<O<H=NUTyk3>|R$h~?}BviA~ zQjEo;f{F}w2h2nUUdRYk0aW;AsuoJ2F2w`*=DY}8iWV|bLlX^?l~Dr<L9<I(20{$_ zya=l)w2_V&!BDqxUj#OW5{@bql@p`{7)|>Toi>4a&0;7(G|`MEsKKvX_uH?6*{2w( zVw4B;lHw@_#+WwMDw(47Ge^5|2~>JT+=1zvq90HBo&vL{a^dn<RjJYv$WLu3$x-Fp z@e+x!HhutA!5~Y4O06zX6P2)_v09;A2JNGeX_vs5qL~gTNohB8kI6Xry%8UO{PE_N z-zR^`sZU)Tx)e@NF0OAj=R5oR2T!+m57swkXBXFRk58^{)?(`yyGyj}B=@$t66SXo zG1xa(u^#xB&a$IpoRLVWgxxXYKaaoHZEqAiv!tsj#=xd<b*;z8i36zg0=eAUR~Qm3 zedB90;u^WNd2z))b7O;z_U7zr?dH<&@7kPQ#E%%Q!K1y6?|j~bve`O3c)GWDusz@9 zX3EZqWfjNm)@&;zY}(m`vxlG0;s*%X6|=>qo6+A(wyc-X==sH^TiH;t@TegMD{8yB zVfP!q@DyLUg>UYGfgKFj+{K+=oYBM}yL&e&ST^on<Z=t(Yy778+F+d%IDk{w{RwW? z=kx7XuU`M!ul?iS{LSBtFFx7cVi4ZGeaW2S#pan#<!v$l-g~~oWYr#+5o3)xfSd6k zG}~gH2Jmo%lVuSBP)A!=>+8So_x-+K`lVm;%T!1~Ei5Ozv<KE*jIdc$q^7M;Xp<(& zOdEg!6iH6k-SsM!j{q)(%+S!(kB6b+1WPpO3Sc><OA*#TVW`4nfbvJ7c@Dm9^oQA8 zDqjV)<yFkriawW6{#Z2U#s12_6Bw<JX|Bu@D50?V^`T|`9nbp{g6jAxI5=L}K$G5! zk!3%g@@NeR@3UM1Ar~vI>iGcBws=UmFL-M(&J;$5sf#f9!t36{vH3K=1dGrWU6{4f z3(b0!ph+jwBy9Q{2DQpd6+)F`*>?<VZ*SW~PE4plG!x-7K(8r?gBK%?J7zTp04+S! zN{oX%V>d*IgziX);O*HdWOt3$fW{H}A{n8N*~7w0t1%2&lovDr+5mV}RHzETJ8r6w zXfT5E5f$>yuA2pfQ2SdkX)4!IIh3Z7o`M=Kn}8<3D;y?6r@hdipgWAJo~jZyIn4-V zG#Sy`6a}L(1UMReDavdFBTUiMiD@%Nwp;L`3Pyz)Jj+`iVY&wTB9&XY(7q6H6R2!L z<$Fmnqb8t?vJ_UX7AUlGfL4RbB2#iK*>P}+q10exmSGx@2)v+8+JVPt<vJP%a0aK} z-8x6Bq(_7Z*op!~6W@o0^BRy8%DRG<3L2@`Za?|>V>SWj=cgaM|Ng=L?%wY1`PtdC zCr>CV-zwYqgMVn@Z-D>$U;oSTExcPh(A%4htN0_<^&7Um8(U|W=eIZUK~pw`H*6l` z6US?pr>AT**oYh-A6;L@>x}ESYivliXLBf9!FVfpJ^liP4Pjj3HaBkK<I^|s`BwIf z*Vk0CJ)hBytM~@s_?lVdYz=SOy5{wj5=a!EC&n%Rco)i6t9?+K|FSdeexWC)r}5$9 z*&KDeEgbvd__*=)4SUi!*astwAEk{~NUnC-)kYvLILtNSVz0#|Ij@tko!ek{J&!B% zW_%oX9rfD!EhR=PUKF_ATHlzl-;POOks-Osw>;w$+v^**S2ySJ8^!UH#qox9Rvh%k zFI#F~zQw|fztF+soD#7~IJ3fqGzB@;Y5*UraB@BtTIdP-Tn~Y{CZKl=8cMQrF;7tz zmD|oxB$!w3bldTXfc4qc<u&_%9#*bzcwV9M_#NrI560Ovo6T8=*Vi|*t?m820~RCe z))&|_cm$>R+4ek!z!#BOX3SswG5YLaXP-2F2^Nb9A$M??{r!EI-Q8U%wXs$SLelH} zmi4H65uRV*F7MEkk3ml;aXNrz1+Q08>Hvgz$xMOVI8&4gGa^XqdI&N=Lp5ba+Hx<1 ze?o&owXrGs?r;~))YAecXl5hJRgR7iOiz2JfaD&OfebW<EfCHL4MY=lSSqgwY71%~ zh~|?RO;3~N-O#2Pfz2;mKO^8+#$_{Q3XlB=bo@<BH!Ou!=gT<X1fx<%VGGmB#nSo- zveNzw3wk6*^}~#K0KckVE5~g>HD&BtK_R&3x&*Y5QF2clR8X$WP?x1eBG-$i60o&_ zSzNt$^2K)~XJ_XxU%nh%ntP^*BOV|UMnel<(O@uuD#74geF;{CBa@9Dy|8Km+=S>n zRHmS|Q0}9;HO7}FLbL)N7r=e7c%fqnVdP~Z$1;$G?E%ko<id<wCNmc|-3~P4_M6Bq z-mOLAL(L0D_7x2?Z0r=s7z_KWLX@5`exW2I70pTwRZASTJy0!$?yZqf0&MDQkb<hR z5qhDugMy~Qhkzhb25l)?&<>7UF0=qV!af=(i5N9|^b^;ksVAUo(eo}5paz={he4*W zM^m86!CnADwKWulmS%!-lqodz1Xwn15vzt&`x+L_Ob1nHc?#1o-qN9j^bHl~XxfJk z9*PWY8Z6112Fo#083eTU1Zu4oT1-=qQE~&`QBKhG9#Njc>4+sokL)iaproiaQOf%I z@$vD?&tIROp7L<dwF|jlnJB`e18aF>eRg?qb9!>dt%X&=g@S#;)m41TbifVQzq7N8 zlasT}S-i1!c7Azsj39ol;5I|<A0EW+Vs|I@8~Oc1%Grag$JZU@*FPm68%{PkxAA^# zyxTY5W|M*(3E5*H*zw#|8gt65MnJlqixw%(v{}E1->JA|C(It{`t~NiO_-bF#`@0Q z-h5|=@L0#2u$Xdd+}ysr!i6J#+$evOXft;BJKG!di(6;>mF|2ae*9^7lVi3&-#OUb z+27gT+n(>nd&0v(Jd4ZaS?iX6LEU{h@)O)^H}Ns;{LnbZY__?xJKx*eIec>W#TgGo zhP_*L3LTT*C760BAYTjsTp_s{QzKJ$adF9NJU%`-Iyyc%J7sxnZ|@wPoc`*s{-giT zfASAL`|S06dyl1cei`r9GK0q_Z(qH6d35~x;`)q9W5l5JHNRJmp^i1cGZ1+5<_)Ws zG2sgAHJLTZL6)PF<JWKBaGajUuOA&99bxdzZ+`RVfBxs8Y>#QO)U9?YmQIZekBl+v z!?4#xtO71^<Ijh)CVC|BHMLC&V61@6hXcncsw4LU%MtUHvGRJjg33G&R@>7r0jIB@ z{TlyKOblw89*8ep)x$xG5frL@ILf#1*v>u*m1}91Q6*m!MyY>ilCHwiari1zfbUm# z@6i+wK&+%hYcEbWpvisX>@0r%h%*jJyzCv%2V424NZi=N3<+2M?d{pl&dNVU^b!}= zdEbO)=65!g@jJleAR?i?QowtefCt(sLB-us-hxyCe6>X0Q?{U5LIFanhc{6*wTZVN z5(ETgW(sV0tkWjPuKg&n1~9-ZSSpc5#LPmF;%%CjJH7HLFaYIfK*j++@(r*_sLGq> z0ff|S5Tj`Tr8`l_fQqAyFoM9oZx$S95h;h-M#iNgz6=2Y47CAWpxz{q?65rN^OKX4 zQb}cqNhl-JBN$v_N1J<EB*Y;;)c!JM3gI;txEn!Z_!y@AV@M|2(ME-V_7%TC6JU&` z^+0<DExcwjP;&J)GEmM{DCmu$Bq~dR5L{fI9UdOOef!o@3H$WvQ-8*TruJHjRll=m z{lb0$?6+pipVb&22MW+^4mUUKYOK>HDhwF6^ZfH#U`bLy3YihOggM}VCZXsWa2`SQ zCD#B3Fw|qSB7?LcK8Ird4<5>FBf%RFB^1Ii69LZnAsRgGW;F|%2~-8vOtV<T_V%6~ z0W_^2>Zfs<bJvlSGmJEe&rmczhn6J~lAdOr(MLLAkL(@i!B%`}GaHQfLs-JImN(bd zfA(j7=FOYe#QNx?k3RY2lXgp3kJX;LudV<2|Kfick^%p{KmVuJ*_|?~8}X&d*K6_F zVK&ZdH@62*4%crtj*d^MVsHPD+$_ue{hjN}bGEHqC^(n>HNVe4|D3biiDRf8E95Lf z_SNwR#p@gKcIVCQWq#cjbZ0idUb`hH^4Z2_ycc_QjT}c-`~Lpn_4VZse(<A%gT43O zd;hb~e#A*Ze1bc$TuGqG-_kq4_~T6h`9|Q3J7v5heI1sJEz1cT?vc0Gm-*$<oAI5* zdHrXIDE{R1h=LhyT##eTT@}IMll@n(K0iM_i}xlsx6UswF3&HRF?M8ZZP|;l-;Ny_ zWiUVM_?{7SKrOA<2l5Z)ks9Xm@|-Q-=^0nd`RA_~*SBFb+-ooc;rC#yvX4dc7_7=l zVbCh97=I^I#3T>M{>Iu~q{NR!vKfCiy*Ari+uqxLda%E<zxU7lzJF@AGiN2R9u9W* z_6`r$u5XWzkKcd)1zxA;7wll!8^;=8rCi>8{Ebh^vNhk1HwW@3uj1q8m#o|PfI8C+ zuFm5{oEXpB_#_wh@Z6w3`|*!|{nvl}AN`|$^ur(g_`?rB`OyzQb0rhpuTO_(+e{OX zogl`6pU>|8{LGmmtV1C*liq{grANs}aaP%{nqSI;>eW*s-th@}`_jviOtTk5ub~=D z=@iN{LrbS5<HXv?7xfxN!Yvw2yl@sTbjFo1<>6=$P;ms!DV9rDgX;*?;5}s}n8kT7 zx#N5fFcUVdhX@MkK7ip8#A;{Jauqr_h@W}O*Nl#7YCoa^#}Vb;6N=7k>ea&)j<(EX zgcaI%&S=g8noYNe8i!Fyc}0H&$l`z)fv`x(?gf8}o7?u>+uD;Zj1k{i5YVL@Ykozk z<frH}_K1&9ErW3~_8pMSHdpT1mSWZTiwaA5Rv2HJu?(x$tzOeOtV1L&epPC{=V~K* z1E8v?_Xwg1<=8vREPKFhoy8CH<jKM2?HX73gZ(EvJ9`}5KHj`}`|{;WuGqO6*Zm`! z^Yc?4ESSW@gQvIyqS16(2@bfb6O%5Gl;wnkEdTF+_z$DXuZ+#Z{~vRI8f)vi<@Z6W zopbej?Y&QXZ&k(BC^9O?C8v-ONa-9`T{m%}021N@64+JcMxcQ50U;qk0_;fPBM^yi z2q_|pB0DbI<-SP>c8F~v5*fRQd~ILXy;b*~X79CEH|Og3jq!WtSkHXlIoH|yoKtrF z&pKm|XY^0=HqUI{d3<EIqmQ|QX##sFl*nUa69a8*)&wh*0_!d)1oAjmQ_xk*Q0swI zL9~Y{8}mj5T_~tmJ{*-erhulFs5B7eK7fggDddS?j{0g=af$)DK>Mx<<)s4QuzbKM z7kyJLs5mwYNL2Mu!p&l&Po7*1JGUBuCZmJ|;9iVNGyD_E0V7a(HP8#D9~|Xk(A2n( zuaLuxN|0L*assLaG4zZ0+6#DX22@mvVhWh`_Jo9LHlStM<K{M=vRl<+#<9w+JiS0W zwqN%Vqv}GXlkp=)V_-~1lL{nI)~5!zdjuH@#`ryb0@@pvrV*fI)IgvW<ZWD{soT4t ztvici_?O+_<HsnV*pQ0g@=~C?mV##E5?!t(plaMQ$QJ1{DZPu6dLqxxORFfuhcSW_ zs%<=~Gz>{cb$aY+(g1fOVX;8wj4d$R3$&c;Pft&wlt3A~I}>(kzB=%&-}SGNvG7ZO z@=xSV*+Zm^T`DsY?^1HjAuHm&Df^Ns`MGu2-#_^5^G|2<IYDt^HB8u3P9|)b*<Mo| z66D-5@kbA0V;I%NZ{(oiOm~}~Qf3{o>5N{7HtuujJr_W1C=xz*BQb_#<Z!sYo*f(< zVu@qE(m{AGd)zJEPN$Q2gE@yfUI2;PwK(3xGJazyx<yz|Q#c;%9mFdE`6hF0{NpRk zck`P$H!k@A(ye%uRlLv;UmK?Qz3CJ!7lCw%n*i1<{L#_rB)Yy2-H9&`qs<RX@5D!Q zqf>2W133%MCiUOMgPh_qPL#yh?_OQUQ=K%%qP$?<9_#EQ+`C|1Rthu4fHHdY+CQ2? z`$e#x@=uI>eCoU1Dl*RT95F_OsoUG%$My31ie2o^WasesaCUt)pU<vlv%C8{=9*<W zolN6n>f5_Fckvs|H_Q#^maQ%1ER~16Bl9o7VrI6sx6fXmal7L<b9suJs-vUl&tH7^ zyWcxGeum*EpM1hm_R&WlaS8jC@BRvBT?53Nv49ry!aTzZB_g`=E?DRCuJU#BTjdQX zixavM7-%y_$$Q2W?}SLOoFbb_mMFnFZqhvHLLNwAptZkNWZsC}Q{cE&mrMKfAdEv{ z-@70zIp-+Oj5Nu`lB3B9aBzJbK;ND+SfO}pkgKl;v^a}(LK9%))qmakF^IlBeR6o- z3S=bI+Pry7V6L}Av(%*=$MK(zxmL@$?OnjRsc~<Ix9llqTCOu6OnPAuzl$?m>dKL& z$?7!9mua(SVatSFZm^MX?uDUAF3!Mvd((rxDO<~Dr_WA~Pmhj{xs#dC?zkVA&E|3G ziO)P!*!}I@44Ny2EmiELnNa7HgNQ?kXhx<9C70Si@Q42}^sA$7fB_{K8hF4UfdOch zD=d3}u$u5=T9$%l35)MtJaHg2wL+l~#!-N0P#7KLg$jjA2~CV~!4i}_!#8k_sJ@R; zHZu4kB#yjIVQMfI5+9U7`6>t2sTO{KvQeuUFbGf!qYxTyIfFD|%2>uzHqfyjpAuqO zUJ7Xr<Uol$3{6lS1WNh}dx^e-dJqbyrk8+0v(U@s2bN}+imJzEG31Od1X6EDWiSb= zY{p;Q%*0iY+c-wgS8xc+p?jTgU-w}POA)%iyaUgeNh>=so974w7p<Le+ytt=%UbqS zW+j+MBLK{ZV<?2_7f=h}v2Tq9(!fOFXavjv3^%n<4=xzYT#7U!blNY11h7P+JoQFy z+JP}BvjJFWQ0;S&9+zVJHC|LPptSO6i!a)_Hl#2>{ZP#4CLk}JWsxuh>`9+LKjm*S zi8X_KGOfoaZvD)+{*?^S@E88vFA;=JFnF<SavPIdhVA@(>71zSyWhOIxV^dC+n>-0 zRQvn;P}ZtJSf9j?naEj=<3CTQEMq1F7dk?R7#l8g`76Tg66qk_2|0f`HuQ;;YIKTd zP}(pAWZ%O4A|WPrFpK!{aTQ02G9Vbc0fy!aAW;dzOdaEs?<hrHh9X<6OyAkydO>_s z#Kx2+W)yIH!zp@WC%z}lW_Ncwjqj0S85W!Id@a2~^02YDKP73d3Jh2h*038fb1Ocd zvjLuSb4zo3dveR(FZRE&F{4U5LZ`A{?|^mo5$;{^g;`CsGF=qCfE`(Z95=z~h{4V` zmToUD&I!4@J3-CpF=W%}UVN_EkJI1ZF~*blwEQkB>Uwrf_;~L<Co0B1y>gy6*zx*W z5J7Ss<k7JkzfFw?5~h!HEUR$;;NaVT@9&}A-)HN+M-9LB{qNu0&OZM5qpQmc>WN<F z%A`&r^GDaB@<s1#_RL#io&CGUS%+Fk0~#aLrHG+RAQVlpjFOKH@Gbg<$P7yn#sNiN z5-6ce0m)eSwZNo3?Gr^!i>l-YP+kVb#A|{HqZO^)FJQrOM0kd0zQTG9Fdk55HxzFT zy#_$YvC|p}Dx@9?<M3&sWnfUDV2Xd&$?1m$5QmJQBm?Aq)ML80z+;g`!FZgXj=5GF z7ni5dJHm63YK^zU(^VBP({i2py73&uuQ)Y6{nP-i?J^2`l(0A8UwEQ1r~SDIzJx3@ zB&<Nr-`AIyNVpJi7lZfp)$G$xKKta8Pq5^)9HHVJ9TsQ2z>P5PHzFWBS`Q__9Sd<- z!*y7RpZ|k@Fs#2a9yh==>=n7KN#3Sf5|;r@?ZbKbC@NaeacmD0>Vy)5O94Wzo!rfM z7%O3b35dj32(&Z^FplE|4`RR)@Qmr$UbOZyNJ=QYpr9{IU{j1?r3JNSr<vZ5P+rg; ziaeYXssKV<V3Zp{FeXriYIUJ<n?1C5)!MXoz?)-zkyn4cqeZAaa-p$8V6!iN0Bj=k zVnBe76jLP`nPMnj8-TCWAmy$EAcXdkfmVY;+4p9^rc|4rg7jE&0gM~RDmAlQ(NaIm zlN;cnL=5DWbls4;o=GPy27AVn><%em1zISMJ$)MCmS*@0g{f>>L6g)l{p=)-^;QyL z9LlSJ07p<-p-LccTta*KW}T>JAEyU5<vPM+19JJtH)%^)Do_DodY=BuEYp@0zJxtU z?SPOGO48Gl<7dyFot~Z^9v-5?fbAHJW=!eNeCzibQ~XDN`7dAq6SMsgFABi0tzbRm z5BbJI$Y<VjILG^?Y#KSF2#ek2<)vj~%yA79=@Jnomk?#Jc*u@Wtu%5kkcG8Xhm)nU zC!|vtV}O(tczIChlCBT4c*b>Gx^Avafl2J=!>}!Q7@Y2I=LE|pgUj%8258%9gh}Fe zkF}>cj~AO~Z2svCJ0OB@Z?PBNxw^cLQ~7OvU_5UEkaK|{RP2Zo_LPyKYzEMpsS`hF zgxcP{y^9SnDbQ+wWAXp^u`a76f!1E2m&lK8demVQW^uC^gB9a=|8RN5g1Ta44h~o~ zhp5=-o*W&ycrtVxY4N^qJWTrrDf`yApls$lX0w~w)%9V1WrLA_TylAEb5Jk~xaZ8Y z#mTkexBTR9`PE<jwO{__Uq<_5KlWqKpPyb`U2%iuA|$8w7EBx^<35fhPh*|^yT)0E zs(C;ekxG$03&7Jg<fR&*<O4?Eo<5C8u$*Gh?18GUDhge6N~BfbZBoB2x}$GQMM=QA z)Y^!iXW>D!D@%?nY0Ox$@YvM(y!RbLZBH4mP<&YsM0iRR$SFy92#kSC&lL4s`u1ok z6S$L(K>!R$vl!xC&z39d1mk|aOUy_3(&;)>%*r0u)UN}BYH2E2*9nHVam!dAr=2+m z@^u^FlE^$#UtwR|36xnyW{ok|i{`_0cf!{4<oNl~(ed8i{?_JpTrIETW1jgAa9qBj zclX?%aJ<lJ_lF?-6EK|K<&l$D!2jGI_<A0Kwe$`!KxC7C$_V6Yp-R$xsaCZEDkC(L zj+;FN$Qe_bRKiisi3SNkg#<an4QhY@LVy9Z4OMp{2H4ajsU@;7*BIps;PrxutMY;e z#w;oW)B-G(s0F>YpbhAGpcd#jhLu!Ug*53``ZXvQHnDLe1rml==#ssR`(}}@tsdm^ zGHBs(OpmB1Z6CV~lovDr@a00y8p9(@eXACVTmvZ*fSEO~o5u*ZYUp%tjSeN$tM^^$ z!un(b3}r2$r3~)yxIbo{pdH(fB?WU~&?l{N7-JBMrV_^lo;U&_RBcaXR-(75AV4js zSrf)rPE!?xaZug^8v|OZp^%IxQF|bd<p7#hc|hZJU=JfxX7~c9&p1j%nZfits^W{{ zN=adtutHJmfkZGIaqujaAOF$cbn@(I|6nhkITd@dSj-q)U&qI8**5&1-}~Q=zzh7v zKle+FQ<mmCz{KP)-s?I#I%0c&d&{xBd2(`caB#%6>Gt;K;^KmIj4i8_GT5t-7oJ2k zp?LymXMmS4U$6nB60)$*VIN2luIEe|83n-^15)qp?cq+r^vL3ge|C0;+}Clt12()C z=ZUTU-9;bhMVVytRYxpi7n+w$j438nH#DdDWMI5<65^(W%&aDAzPz~1cPQf<!|`Dq z+-~pbz+|$Q_M1qsq=enwDLY+8g&-7|lf!j^-T#C?HqY?<<xBqY0pQp?W4pQIJHTPR zI6Y?99{ci-6JH{0mHIYiw-*=Un_%q>k1WLZ@ffx@XXk8s89h|{`v+h?yV{E1waQm0 zxCZ6(qNjU%v)P=>`R?w71ODNjS%{;Zg*=_c3)xn(!-!^4WQi%vb#uouVBER2+M6C9 z9ltqy^IL!GPyLqP@>|&Ve*4?shO(YL1LK7+)#3-G38IXIDuEDHYrGwL_a5uym3N3I z?Tt33XhG$IDJU7B<YNO96<rrWM1p05C+syAQSPb{SSSC|sA^i`EDvfTFwi1t+<KJP zN?-uRhBG<KzU*01NZ!V`r!3h}yfyS1gGxvphfFShc;N|oB?x6S836yT8{h)&dB8Pz zeqM!lJzF+QUCNOZGKF`E+2M=c0R~a-B0JXwg>MNR#~8>Xa!a9L2&S@e%UBm@0Of#F zs!UTXpb!lBbsJz{llA5@qsao~c;JM;H{IuC&jyamIH%~#s|$9&085<c&D~wR--Z`g zVW$$6OE-n_)n7n-jwt}+2z>qT023M@swPyU0+On7Y@a4=Ci-SC!BW~cg%bNo=TUJn zbFhGe60x!{nouNKiZTGs1d<-w0Ot$}v|M+fT8w7$HUSZuQP(e<1+!?0*0Momhu2c5 zZH@I!sbQfqz?e44MW<|*T%hG%Ha#9=YLmkspqm;agy+7thDZsk6SGQzTw}Fb3gZi0 zGHP30Qku-Q&5{rV<FWxJqDj}d^{geKCG`N~h;ke=0LK9p+K{XGo&t<}dx4f4eeTrl zJGF6l&LG=`vHe)`G^}R~y6mt(1sQ?2=2Yb}U|9P42efC#P=&iFi3}N`N;DV<lQKut z-wFU~F{??8(idZHkTh(T1yw>9p_lGD0&E&L#AfaUA5SSQ%3>vhJ`N~(nm_UtWSOq0 z-{8y_(?M_;ni#Nb*!uqHKlQ`=`%_ji5-icOkO=O2#`5?4-hVy9E$}D)_<z7Akn0CA z;(&{HH$iM-_xBGuI&%SR`&<@yHnc?Jn#AS=JCXvzvSPz67cIWnkR1t27caC3QCUA` zFf}sPpG~d{JM2I(#*vk8Kyq=}V_Rac4V5nUdwbJ-hc#9&k&FrDU$WCD!!jV5@oqZd z04M6!-TiGmIU`;;XeR^)jK8d~MdOci6Z>u|$*O_hBZ?PHIR|Ggaa_RDWsVQ4vJ8S0 z7$uxDcmOS9GMnA(O!ltwr3oZiVE_god3%^~1>P~vI%`V;HY=Td0jjhC3ddjo^51rJ zr+W*f<Ys<*{^o+^`uz00Z~o9XZs*teHSahfvn1HR;>jd!ZEW+;eLSE1hVjNT9<ex` z=Ethr0Q%l9VB~Rkeco|TetUPnxxuPoBmMEm-`L#PJUcsc0poRke*XIP>zXeLt7DT; z@Cv0MChXUL1H2Y%>?sM_m)as{wZSA1isF?IQ1XF+p?bP5f`|mm22a>)3|hNOAru1S zee)~A;GlRIQ_Cn6B_9A)<2v+pruQRqoyN%rpsnV*_(J2J;uDH@M+GV52`w%$8VKZ# zTL#t2=vzD|M)|jg5ei7CflAa4ksB(_-VTqo6$Mp);pv#`=4IVGz!eQfUWSv8@~?=9 z)S<-=M!^v4>R%tHU7M7<I6-_jC84~qZat70ik7phK~&M?^oxWPP%f`X$aa$tBiz~M z@=eW~^PAb(*&9yR*swewHn@C8N%x%5xg_KlUySMMt;jY}Eh2{(%-6O7J~=tg@rk%r zP)&hQIi(=C2vBmHY1<<7lnxg!v{x<<gMolYWtO}_iE9`VnrQXnqKF)x0ixN%AVP`p zff7{(Rlr0mVd^rbiE)9ZP>WgdfFkuBSRw~>(;Hk+j@sBPXakG`gMri($mNNtFQW%s zok-L|_2RyPrbuOI<)J2`Hm3j}QCrBm0_pb{gaV*Asx_S|;FPHXrGkgTD>t2T?V)y! zVhFCbfL1e9#SdtKAVu-*n`KEz<~aqA)ISWh?f>xOMn88Qp`%D{z8z$m3VYDeK?MIy zWc)r0<C=a$c%%rLBmyLLh~SYs7c>D3LM@8|jaLF~L{DfenmR#KgVye#CH+c$j#OSe z7Fwz9A+}C9&60+YZt=&G#H@2{e}>KY;j^%5?xR2DkG+O(>2t(FpHL+gVZCU=cxcEM zC0P8Q$mSzh|L&St9^CnZXV0E}@WK0s`_tWBE(39SAcj1H#?62J?SAWb{i{Y0|KT6| z_Xv(<juv2uNF6sW9JY)SHXLn~$2Jzr_g}oYzP{qf+-HXn=9_o7w-@K<du$QuGH#qe zaAEtAfnL3S9b1$<;Zrl0AFEXe=xK(D{?a518(_M|Zijs@a(BXPNN}g1>wKOw(Xh|& z08?yRioV;B@i=>I#rH?!Eb*|t6F*-^_tEClufhy@b~cjJU^f(^_ATPLMn>FtYWnv6 z!9F{yI3LBgso9L}Fz54|dF*;IiYRd;({uL1^ctCeRFXk9IQg+TySZTtH>a83Xxa@q z5jJ-Q55WR3AZi?8xDFOrCtnw59oAVhERE|xsZPWg>+&)e?oojf#(?ojk4=V!KUUrK z^^D<SrG5Ot2Rpkg=7(8+gaI#R`{wR;I@zPv7(W+VjC-tku2P&4w>H}Dmjw{NbQNFS zp6pC^{q5+eEeNB%dGY3aHlMwC`TU1|_=j%h^KXCq@3E+U;wOIm;^Lf0+)S~mm{?4i zWG)-=b@0XU4r52ax^Y+s-B(~CcXVo6y;_g|*2PKlrtK-$ywb)1Wk;Y$V6+*d<i!}F zm};(zAR@uQpaOO@plO#*ltd_m8OXmhDvnIiN@No_bj%Cw6@O{hcS?8GiSF=4fm7gB zz$Oe$c$jri+f!-^#an}<;~-Fr@rqB=&Vuk+1yy63=g4;eUgnY_sbN`(c)~koX(`C} zRLU@h7So#K)3Ldi>Zw?((B^yy`%<7O=s**FHAJWmEqE{rhG0}1w~TdhdMFg@Ho!{8 zl*}+pE(bzQv7kv+T;kz5Z^Ltw@ch}c=iu}Ow>O7}$J{?~b-3Z;dzWu&#zSpft8ur3 zS6)h5E|yKL9MZX%Jy9cv;lASc{rt~s@D;IrGWrfMJZa?V8&Ig+9s&%?9>4%4>!{G! zQ7cD)4dAv3YEnmmj5&Pq(I$Wp9!CZOxj{h2Xh8t{SdP1lsveq+;l-PzQYM4hwE%?x zGh!C)k=X)e3}{k`D~V{$G=Wx%P1*)j30H%B25xYChzV#qN*FUl8WeOS2m=f7GMZtn z({9pt07LWW=*WV#K|*|>u#apR@v8r#P9z0X$cX@YEtR06X>e==0ig(utO4LAo37!a zLDhqel>p=eS}GZ6NqS(sO5Cu<D}E7yURxv)XfkwKj_udQ&(tei7`etR!_feY08}AC z98ZfO6bwy-3{fAyvJBD<KtLd)r3_(Bp+p9`Dw~1=Bg6ttnnyR(E&v>@6J7&Q0ig`( zAOgZ_j#Z5tfz3>f4=$u*WEjJ~Y~7)t!rCkz7n?mLBms$<{Nu>Lkd#FNzrW8`G~WH< zGV%Tg@6E5T*z|frL+kVrjb>uwcmD3Br$GOyU;JZKO0{%?Z7&ipEnFL}uC7SVc9aw6 z<>eLK+TWjk{@JJB``-6Z5!TL9#+x^9PESv1GOAEVo@B&{hYMwSo<OwG%z_X)Bk*KD zJ9~Y2c*N;~uznKt^74{sFJHdI;Ns$f)EE<xCL1LFDA;IuZH;*cM1UfL$&zB<b#pt9 z*NQRThzk%!5r^dXGLKL+6vJ7B|0CYR!}<9eN@GH9<IBSgd(`X68=j4M{P^+y!89Jv z6wiXjC&x8rFarjhTsi_!F(3?Y_IisQ@fBUosni9)fDH3h@vd>!S&vJiPAI*wS<n)+ z_A(eI2Sj%OFRrexnMwx-{yX3K&fosq|K(5rwx62cT+i}r(yURI1f#vXy~`AGf6B^? zC#p>*RKuS6&Dooy<M?T1s$%wC{PAm6i&snU^E(B;2E$%^YkTu{c6$(yo{m?;KmO>W zpZv+6B*C}8{cVh6f><btniT4m0mc;MiO#$=bYFora#A#I8SCO`uePU*Gt?%akAglb zQ9D4%R~l4pFzX_SNU&`1g#Fl9C<m?m7J1(uMlo7X86RkkDkBC3tPCXUfPqX6QNK=% zP{@TAE3IaP$%1LttAN*lQdTJ55s`ioM20fRUiByk)sX?Tf$1qAfXv$i-{^k^Bwdcm z`WFIzz25<T*Ye+P1N?}GHS%}FAU;hcYtyco$8~W)xhQmkSR*!771YA?G!gTKmII+| z0H<GgmfYfc9d{R;^W(Z2ztbNd{=$F@!RMd7`uy|H@x8l`y9ffXRD+3kfVXGYb5uq~ zD5%_f33xLiAt1v4;qU+b7Vs6Z`SC{|G&V69-^vOssIEyRm!Wi+F|a2{#bKm8KCzFB z+2YLsC_EBX*ke4Mg;&&Hxb>MC7;5MmLb^n{yCkGr5RjCTM(J*8>6W39E(N4(K)R$$ z8l;A9-ud18t~-CitaZ+JpXb^8vt#kG68hS}fDBB|U&<(ps(&Vm7`!7e8}SPRFgYHT zvzY)mJ`I37Q7cq8MzkdQFmq8WSP3^-Q!EpKU`uGjOMV6Ut`0ja*1{@=7)X~GTGn?q ztkZf%FwMc4z)LkdG;{%8=~Oee-xhkQS<JE-z%<^GLY`OkfM7LEwjk2zv_WD!KgLy? zIbqhY#cdN@O`KVhue+S@Zc!lE1gL87r6muKU7^@z6mtk}A)z`wX0g=G?Lles$Y@oa zF5gcHSSBi2uvwNMz@5eG51SR*$CR!?C2Y{FQ`;Xev5X<W{0`U@xlC288%(oyS6d9_ z81lWMC&bl3GDbOi5-bX*eNp?}53-}eCzAjhtPq<F4(EbI28{%LtZ|Nn()U^VuDcbN zI^aqn_vXmoedH3JsbuS~j`_t{nq)>~G>N>orzGSkGfC>s`8m&>?0KgX@yXbFUi`nP z4Nbts6S4yM?r?#RIsI~TpEx_)+c<6B3wC#bzQ)4w9dr9G9~@NNpd>N4GU<9c=Cqmb zR3=Pd?&0PZl2Z<o>soCP0#mu_r}K$^{zMd+!Sdm(KtlKnjS;mmMZTDrgU-n~*T#9p zg{zI&7>Sn_wS6${{JOlOS6wp8*b#fka(_bw>ys;oNJfq&_qTBi61CF%l&hW5f1AmL zG3UektN#gWZ+FDQh5VC+Yg=7gLp!B2Vy6aWS8-6NMNo%3x4@neI0Kr$BQ*VH9Mps4 zDvXUgOWi(@z^Ji2pjFE~U}$9mk1@4&*Cd*N^SGw!TAxX}VN-d~sC$_lNSs5+LF2v1 zDFj;$jy}A!wD7!z_q==^c-p>_yRY%kr$HqphBP8*aB^+h|3bf4)ITRb-xf7L5?^*c zR`obJ^OSk#HZU-d{CET9!v@_i33I^-Ew+uf2hPYpmK>kyjl}5jyzRTa4}3mp0CaeL zQm>9_5K7y+AUJoMb*lZU*k|nAOlcnL?nXbjzRLH|IaNGHDe+a4FCHyi^TvfzCbjnE zO#Ec_g6;-Jm^?Zor`xRsEEGvO-SyApVf#Mlg|OeKYKMT*{7(!%$&F5kvu>*XnXxzP zvM66r1i$em;l@@X!9~Vz?4|k5r#C-CHf(;T;YM*92Wv}(30k@kBQGBE*5DGR;L*50 zyExgFmC2!JB;;r2pGHq+t9u<*S0{kVu?%=@;i{Q9K~!9G3N4%U*%~yO)tRN(C+Us* zTGxLJWO=v^O{WOY<aei#%xpqbR)Cfg=PQQmMk-&r^)zW~TCSb<JYQa~hPdT>Kw3iq zHood--#DR0&>(!rIKlZ9hfdIgj?|@2p8wUs#l;29Q*U5jX6Cf8O8Vp&S;;xT4KWy5 z_51i+KNMN=NEk7UYRH=e1pAIY?F1rBGxlCt+~4eJ#>03e?g%EOqx^{L#RDzpX+&SA zAEv%2l!D|u$^hM2wdnY>y8rICh&ML!s;kQ6+ZM<XaZu%xXe!t;=mG}XVcXIMnyrLk zAB|=2I|7)_VqX{6Lh|2=l$Cf^bA$U<0G@USW&Q|Y2l{a{t*5pbtj`?t>b=wKdn#la zDvP-XyKAC|EnJo>fA+`Zk}lDrYD0p*#79K&*eW}S|H5seC<e4d9B!4&R4ZrY!oy79 z#xnq0Kr5v4lt^!fbR}8v;A8QbP`WUkN|z{LJN6f0*0jN*XZ$~m1jQ1oKpGXb<6mhZ zuNwc$1Ai?6P8ppp!AagzHAhNLdz0o$Y4?vo9TC+3woUQTOLl)7?djPoI}(oi45_t1 z>?7{akOa-z&RlgCF~mGgSV9E_XpV$XJ2n8kuR))qx}mh$+@RJE`KE$R)Ta<XJpO@j zt>4|4=9q?N9B#hBNQfRmf^BJ%Rq}1OX~E8rJCgD$=fiw~K>~qp-2gnp3nMrZMZiqe zJS~ju-Pc|h5lamfz5Q0H++#XaRP&q<(zw!}r7Twa@{h9nh0A+ZGV%wr9X{MP`G4ZG zG1w70FB7MU_jkd+_x8}Xqj86iPr@--#zfpLQDvL<(2jM1n=SH34?9;64|fmrtK=RR z_~nmN+`fNM_%O<%Cu?8gv!!?V<18j1s@-@CLU@7vnJJBJ&u}40ug3!cPx1eBib=bq zrM4T~GI8YW(^NdS*;Yn#oEM&??4*obyr5Y;$%YDnH6wWwAv=&%h<t(V6TU0IYqoo? z6osF+Yp~vO@HTq-hE@85Ix4L!8fuzEL>lsx)PNAL?7FQFXtc^xp=JEws&=rmB?xSN zHU&NEFOcnNj$)a8*GIwhLd7S=!%X4eOKL4)Mu`!4IH-KWklH2S9z&vxro4vG`_Kx^ z8k)*l!&``w38+MOEHb9r{Ffw&!vN8AbHs8DayPI$PczuRukPOCk#Q?n)a366G9{8z zVnnFV_l*QyinX6gh*O6fmJzI1Ktam-mZM_uE)3WYqARkJQVFnIbulmKb{@gO^Mwz^ zZE}&JEQD8%>aAv0?D(&JF-dW=lcBio`;$(oyn&c~@7d13(Z8!iZBD69N3yZcpQ=~1 zx+2+S=&L)yH7$d^cmM8jPbdG%Sf(dl{*Zh{FvuZq2-#kw3c`hzYhFb+kf=c!n|%qQ zscY`uB)FaMg@IALi8x?w0-}}4`lcx0ov9>cc7^;etWn=i61CD{IhxilF=@XDO6Xpy zipZ+4GT7Gt`~vUtVWQ1#B3q6qD1OJu-F3GehsVta6z|Y{?JCyu@pxsrZPb^G20GD) z(q)w3#vzb~D4~KtK1Y4QjsloB>S8#A%$n$G+fJb=7rfQwdv^5pbveNuRenKp++r!w zP;IAO^`17~oqkg5Ll4Svk%6jg3Qm%}4It<vBGSK4w^~N-x5+RDju{fDI$`~tK*z8P zZa!0)0Z1hWnd*9BG8!f^<pS;IyKcU^Y}1&N+Mua>u#-fj+s+_eZ1|E6Ltfi!qJKn1 zE_G7fNo&EcyrV;BzmR|nv9u41P<N%a!vW&$+d&&?5}kCPn#C3tnmcn<Jr|Bv`<Jp2 zlI4n2S1rMQP(ReW@rQk>F+zG=!>dqZ%by$XC+5{POEkFQ?8BkU(}IRnVVI3zo8GT4 zH(rl9<xj%XKMFOy+iXH~aI&PWMEZK17&O>1S{v7G&>1&%6Nzx?x<3641L1+7oLAI4 zZhM2kJTgsO$D0fv9gsS(#mVvuMiNaD6MOrhGe-ZzfO3@S7Yh-`0U_BYkDuhOfpXk> z2-%*a_u>LRqAOOd+34);9V=^V=dfW=8rGYn+*le7Wa?E_8w-gHCp_m{;;)*BmnIJp za;`=?+-f$aceE&GGQ*$UCa(7}Y|+6WOacDm8164RUivL7EHx{hd)lr8u5dST-}9Zn z0p}MNB7E1OG=6SAcl0~AJ75}m-aeiy)t%$9cGJq?PXWfbwvPQbL=zhAd@@C}43?wD zj(nGRc;{Xto_@uCHl8-mw31DMpZ(+x7Q_Q=uy0rV{rEC5{K=wOLPk*j-L<NB;KBz~ z2FZ>R?|yWnv&G5S*L2VCI2!vLWTjt!`8xG#4{A7c0Y#qNpF%NAsWIhMWqrSdHTo0< z;AXSgpIzyEePfXjfcq@;L2(@Zys>8Wf9$b;5g6<F&DaWBEfdWGs|2t7*94%K_(do3 zSTyK5N<4q4%v_!b!nXOt+J1<oyz{x<Y(Ujptb`jm1j!JgQPkAhTJ3MI3oU{T%<wH+ zg@4aAe@}wjx&^E*|HTdF6KoRF*H3312RT>QY(_@`bV~g@t`__Xf5f)cV3_}ET;aNT z>^#N({#-sUc_`SGN(~PuAt}aJMw{Ztyl7+K1(VgT4*vxy=oFKZ(AKyyF79c&!IUQ) zjP+x!)qb&`WW%z!Nu{gLm|hZQm7}B)_z;)Es6g5ME_5%`ArlsCfY6}$z!Q3o5@(=n zKgaHdyXFrpOnE9zH`WzMQ`ox^r~t=R1wRk?l)aBz%@U-{Gpm4{r$zN4!dSlW_@=b7 zwK)Lw+U3XyJm0)SanlYe6BEjz2(`|dn93;k!D5FNb;SLFGA4C*#i9i8z^mp^B1#Gu zvCr4OPAdnzOeB=~L_jnZrW^#fM&Exy__8a49TrQ1<>jw63E2(v<C;_`+1fTT)O#dm zcxkp)G~D%GIFx&Kc?O%7h8yH3A`-rUsyswpvTMJ36ko`OR^HW9T$Kkvb1Fl*UqZ^| zP(NnAyQ5Kb58GIjC9R)X%LA6ZB{A!Wr$3L6C%5g-xfpF-Tu+hD9p7<c3e82-|7N1K z9pIRcczA9Q4{3#BDUh9R^kXX*WcaaoDD%kC`ii@F)`fAuR@e6P|H_c|4gZTqcb6x! z0F8pptNv3z1G}|?bn{@mrEW+xGb9{yIngW%+YeVgMTSUDpUhtP@tBpw_veOnaD8jR z31V8I7174?)QzUXMkm<@D&|q^y;Bz>G<*2+ZH+<NDG}pOeQ4{iUo9U@f7~p`3G@cV zBE}{VlkG;jv>+jVEeqPZo|+JuhaS<E7wI-Il(er6b2Vq-;a(pp3dM5Op`Aj`W1Y97 z&S^Y4M9F=`yVt&!1KHETX&GK(_vV=@#Fizm*EoK5W*b$~?W`Z19UR<ck@wt~J+C7j zv0|d)ZOzR$4-Ml6Ve|Dut7CJa7%JV|>a5Z+bI|$9KGD>Fa;8CYC8i|(gTur#)vx&s zVM>Z;fN!;0)c{S_tTMj6)}7B%bz}VYacJ-)>f$4EqHc^V6opWLxOnDl$Q65j>UqfG zP7S*1B*id{@dqr5SkMDQH_k}mWYyBjuZv2MlSk0YxAMY&&J2OI<3^ROYAoPek_8f; zJe%j9>+!8fx^9DXX_=M@%5rF~Qh+KKP$*?sdE~z>W!09dwX&mj@~i>Cu1Cf>|5BFF zpj%jp;>-P`;5lRbs@B%w;R<A!j866bFZ-venv6wD%<Y^6RPV8m%UiZrKOS*Uy94~L zD8`oM2W0b&X-_7LhRuSfhzLrHjcX<-*a6N16V@6_24!rtiWaC^NsTyWv(31_dd<G` zjILr!PJ<n=vhLU-6McGK6gKUXAI6}QyiMnUa*~f0ROSR6+OctgY*${2vS*nm43(rI z&jVZjPgX%qY>)2m<%2M<a|%*oP>PXv3j`9~O<PIy>kG4?fx<CFj}SUKqwQh9!q3Xu zXV77rzz?Vri9q{c2T--s)@ZX#^t6tL`eCIr*S)r-oC{_?W)iBW{VDr(l(b=oz><91 zN4`p=_ML+nZP<Yk@_ETXf>GQrJuF`W2}(McgCgnM&=Ck<Y@v*OY_0lbSj-;LCH(YH zSRJE%1y-=3-GH#uXcH^4@z1vQQbJt(!!w+qFDdh|4?R?fdLCt<gp6+Hky3>sbnUT* z9r*`xJ${!ei4#*8fidb~pI{C}6}Dv3fWX~S0Ue?q{rdU{VHW7&Wi<XRmj6SxJ*2C! zKxsQojfl(9IzZ90F4b!3wSgerzyRVE2rB-T5U?30jXI=&Tc2aAe(iBigpwljK{=mo zLqY3-=7{RP>}w<C?Uza~mC0m1Mj4efyTjbgfgIR}BJPiHLS2pTL~N{It&g`ijY>4H z)IZbFGpi~Sfra7^-?h1}c8El1f^JxkR`NH=e&IoE+3IvaN9kR^Ff`<To<O;U`ORys zG<>{AUyNsun|Av6d*Djt9=7}4hWN7!8UW`=W_bpT5V5w<*%vxEq0udtoV9qI=A_V_ z9KHe?EEsPae!a@K(dtsf=<Ut2*v1X&<t*tx(6@KYS+DR7L?)4*NYQv1dfEI`tgZN1 z*vq3#*{n)j$p|>?$DEnNYl(@Z>qf-`(C1R0FmY?q1TJF3crCcZe+TLX_f|+gO1K7! z3i*qeUtP-DwzJr<7f^^MA}>e=OHEX^CT>!-vOy8qG+)_Z^N}K*TX-;!Cr~c!R5viM zOL@%`=VxlC3JYru@a-c~bJ`H!2s&wHlwsmNall(lw_xvTngWM$xKn7m*(F1&u?8zr zxv&C|)<86{_ZV)9Tm)bXVjOwE-#K!L<b;d+UX4U%xR3;%?;P$}Q|As798X^kG+R!= zIUL`R**wep>6$Jn!WK}3Jdmku^%PC!SW-gem+<<xK+yLqis6a4gQ6fsb?5w33jX)9 zmfN}*{m}9{L%U1>qpZ1oY|zg$Qj#)?rmvp_euxC6O@yco5Y0a}zVCr?YoPwZc%ky` zZGyB)SX;X912Jb1!Kp&f0L%v~HVDg*ZG+a_D<4CiJcgGQiN<)1s~TP8wvZBH!pd-0 z(w3&}R1{lDN{8m#RD|DkEj`uxMn5gA`B4lQiqb!&*(}EUg@mnCjVDD;M=^|o(UI#5 z@eB|LMK*+zX2?9hjnRi^%nFlDcU(~o)5|~Dt?XEn&NS&%WB!l_Kdtaemc%R<`2?Q{ zih*Gk%fd)?@j)L2!LAfdv2HYGRBXLc6xV7{?9h|;AqB8-(O2HR?-18!87UDF#QC_x zNQrN970wvmWvKKh<nZK#@ALfgNK=6G9_h__;1!t&s)1#5gI+I6bWSeiaY`^5*!Hhw zokSyA6lrQCi@%7N7*cMHZf`RgW<kFaTZ;vput=*WAXF)x)p{*eMVm&!AH?viUVovY zyF{tS@0MV(LZO#_Ja7xZ6){N!q{)2>l-hX3hz(<m2oFp|rNL%b=Q@1o-rknK;0&-8 zrI!YLCs)ZBnG)<m)=>Nb!>Q%p@faf@+*4K$C=haUcF5`^iYLNIhw_%MD?uuh5j3@x zi)5?mS0`bIhZAalBjou>1>3-r*7$F&07#_78i=>~>S>L%OhYIeTmk}upI28UA=7(B zW)23-H_RQ|D`Ttb{1Bd8f+Bb%aCu>{et%_k(b~}SOy}bBOYQr`i${>>dzygLzsLyL zt+zO7#SR(evP>0V4?3uCksECrX9QC)NRPeSTRN8wb+=W(=HJh<!20K)Y@#Zo)U5?9 zJ4}34wFMF`rL}PXA8`n^UieJ#N=E0max-_C^5E-i(HOEbRQ47K>))k9JOOLCCfbX6 zNR|XYHLXuQc+^5<-MJCx6nS|y>9u8~6u`6xWBEwIX*lGijA2$QzdmD=kT>gY=`3*D zN?MG9GxYRjiY6tPnbx}S%Rgw!q!OcbP6~F-Mgd-IZT)t!Q`I5q5hmesQbfM$Wu++1 zoS@CW5!GEb3Ljx)w78SPe3n7n(FQrYIGocg@;BIldwBa#By~qPk#VXof|@2~)#p<T zm1i;_Wls=T+>0_v=|5L5-iBBSf8f)1s0?-QzI2R}Q+hiT3^0$z;$39aFMd6B&Z`W2 z12=d%@U5)`pZq)8OA`g#w|c?6tV(!c6k$fPBHpR`tc<Eo9L6vSm-$TQGEg`w{2mM& zMY&50hM<SWCIM1kYAPwM|Hd#2BGl`NC4L9KJ0Qs?dvhLvtdyt?x$d!=BjG0Nk~orq zgd2u^{Hw(}gYn^!+O!ve4%ao2u1+025Lh=cRpP2t3PuEl40I*&zs0T!>W7pWyo{p4 z%$}GvLCLpXGCEW`<H+8Y;v8{s-r$ftHalnj`Lv<)`u6c_t+8LK&^apK%`moKKveBh zJvo7B!!Z|7B3S0pLz9~ObHPb{(uW=`=Pdb{zvcLyN!Je|_eNfVT@abJ@2TjxpN7t8 zd1IFOSWG%MZPKYjE>!~Wq~=!_esx5bYTqhtR#ez)G-@(ujea8#Y}(j-vxL|_*aMPS zp!UkdjmD61*(N38fNH7t9H>pbs{~?ej!%W_5f#{|Za2NXmdI8$RK}1}0;c(|WYNxN zh$UHNi{vdqx0p-vC2Fsrp+gZM0?qQH=jGpw6Vie4jar=DwS5!u8#X6p!OeEuF6va@ z%9!C-9%tMRd7d6Da}6TIzex)l+g}eE2pb`aEpQ3%Ra|<2=y^VGP=7E~{lq!QGc|F2 z*IDwdoZK{%3lJ*qA*Er(L~e`yhFJ8ia&!P@<-eX^K@hEyj$QsxOuoT30>+_e#gKuJ zo}H_!_!eaRV0<knk8eE^-O<~O9BynS%rw=<|MrlSMMit-!U5Va)}{kaXW=#fA*K{s zwW8Ga2j3aqz<j=oFyr>UI$YRqnAY6Jvv)NtrdAG5q7V`1Q=g7+W13x{^o!klU$DSY zt4(isuf#vi#Y?@k<szu-h%B#((OUI=X%lbgOKwo^eDpuk@dY;t4r?HA)Cs_(_l&Z6 zH{8F2(#-Ef;<M&XfCb|F7Zqwl!fk|^Rvi!GZ$eYPp>zQuYv5`1=vcwJSedR0lf&s7 zpT%hj7<LfVasyANhc71}pzPO3!FWB8LKqU}$MZB4qiqnaxDZ&_0a8W(H}qysJPriq z$~qlv654z%iu5%0d{T7v@bGwcxnHo!<0V17tQI`t!S35k+v5B-H(@4CKK|!SJ8S*l z0|x)I+#>FqvN{1myJc8kef0Mzsvv9~cQSA-RtwHXH4qa_0-#oMhf=HfJBC17bgN8? z35R63^xsHl))NR6R<#ex;`~XOR5*f?<o_U(=G0jPga&sgLnCWVW<!!N7<mWDh1#G7 z1DYI<e^4+rWlL+doVo^6f`kMF!2{oJd&u%-d<?Xa8mA;CuQbH@*UZN}W}Ga#uq2hi zbSg7)I#L16q~X_?)1}5y+yOFlf>pT_)CyIQuwUBFUloU{(u=iFh?f@KVZ~#Hjr_0D zyBnkvD2{(_0yz9XguU5&TjJ!#ct^nX;`O)9$%x!!+%|F*3|>7-(k!SZ6!tEy9FnpB z7G(flydX@#%F!4_s)@$ej6zn{y?7@VJnCD`LqKb1xuI1@hqU~qnpy0T1}@CF_OJ0) zlFr8@5t|aC<FK(BiNIQ5kh5rPD8FP&ZF^m3;OWNpeuE85vfbgb@W!!oi*si;&$p-_ zt^Z77UZFRgpgt5nUv(1Ii9Xaludm4mczgH1c<%2<^VMg62jTu8b9Q%W@89&ZP^V~e z66<9)v4i9}IZ0izC6>Vyw}V<uwe>RWrljIA{-x;!Mm)#XQ}^oMzkpVE>x3bj276X= z3H{pB^_D}eBt8{<?XNSSNZT^*51Tz(mYwbL;n@zhnZc~0rf2JeS?bV;c{#d1Y>fh| zXyIXm^ApMuHFm7<tV8$S9z`hTYwf8?(=BAj_-U78JXoMG8g_d}8-&o-qjYbKU0+z( z{?q^G@W5yDTO4`J54~_E2(-GE3n)N_2G4)zmI+W+Cv&)x-4_ey{BNNs+dmbzA4^{J z+e?<bA!EQdZK2mOXKw=y8+<>S%||*vIr(>(jB5qDIo9Sfxi}BEx2$g!%RM}<O<(mI zbaZMP%Je3jk!D|>U=QF)Y+1`yWp(=GYwyf!^^#AGO6MLOvC^>M=i%aYV<~mFi5#@n zOrbGKgBuzh2GHy<=>38J;K4z4u?l53px8}Xf~rTxtbH=_1jjO>@;1#g6RTv-6f7j; z?uTMmvnN+9lZ5gTUl=dNe))F~NW4|!TO-)Jcu=#k`DZd{=&S*}%MId>9MlAZt=^jN z=Z~O}yP=6sye)Y58SuO3Wt9LSDAcnDsaSDIORo*yqgac#rOI08Xf+F(vB_GJA|~j0 z2=+F+VhqPmc}X0Pv}smkG3NC80TDyP?~<=ml3;(>2iAg4Q0(z{SDga2?u9diles#e zXr8{l=g3fA7SgY<yGyoY)VhpU>wp|2zUXHr<#x^J>L2wDB33X92XQ_!O|Ak1*2bU3 zM{D9ouh)Dho44t9!el9Y{**>W<}ZLmh*ijOhGJ!8B*FQ6m_Y+jTEKnGiE1cTfrP4( zE!$Q{n2~f_?e5QUm8{kpjJeUWcvu!M(31+l>24WDg*hYKtP8mEM7nNsiUK(EQ5{Gf zXF)q5z!4Nf|NP8d9tO6NFCh7B^-=69hL^T%=&@47O5WeYy9pzJun&Dn>aN4K_&Cws zV9x<`YJ;TquRzA3zjZvqZ4$tdL^U%5GjIL@P05m2P*+nqJsB-~TNebsZQ~UeZMQ@f zFyoynX}>WyyIhIb^4ux`2(z#Zl^W9x;u_`KyiKAFD?0R1tq{bb*(eO`!y1aCPodne z8hv5=@X>Tx*VjI`bd1%7BNkKV(Sj&3i=@`mN`ooLR}r4v8wna(A&UWAY))?;Bg4uB zYs^EuUr=<+e*lnx$04XP7W9BlELOH_F_9caB}DjJL_L=#4!8_iJ<cq&iiIvnLTU(U zRDcxSGH^{(f)wRBc(;~=rQcQf`X*nmJ)idCt$EhOpf+qif*M=OHc@s7dwse+f06w= z2)tK((jagO4%`fUSX*0?Sbs}niCrQt>-xiNE!%RsTDz=ZmWrk%0)&dGC@LL8l@AVC zhi={PBEq)}0stChh^g1sAE*oMp9&<}mlv1YTP&N1^l{AaKhmPv|87$H9>-h}gE144 zbHpvibj3ww)zqW~eqYNl??pcqL%%>H@)l!7zE=}`{w9aLFgK=v^5Xh$d_@o$aM?AV zn%?jEevJjg%_~+Zj5Hb*)Pt;H(JAUDA_WU)P)z4$-yY45{jGT@Jn={Jn^3zC>8U@r zv;=<s0>BQpIIF~u{VddZPFm1U3nJfxQsMD}_!uy@=_x9ZJ3wdj-uOCBtlp_+0QDk# z9B3Gvea-&V-oBskIG=ztgQ25G`aWMsJ!<s&o%nXT`TcsX^?qI`tr6xAxI|x*^1nhF zmJTlZhjWjV9%g6Yy{;jTJn6nyjqHH5_kL*NWLNGTF9MUL9+m<McE5Sm8E5){&o@T5 z1D}MRXOXUo!0er!F~N$McO^If77mfcj8wSkbNc817G}o;<54fr3Io2re_ze7*Hcov zphK#`sz6HtmJ9u;<g)$U6u<%SdrQ2RZAAomu1Q*=3hfX$t_Y^iq~{X?9{`NhUK-ep z_l4h8nV(40pbCHc_z6O>nJK3vg*}qqCd(LMD3mbEWqW`<JGv=)?~Zs^JyFjUF@%A3 zDlaRlwHeXII$<B1RMS|qBOI?PkY^wjN*m{v(17JH(Nl7Md6l8Mq+W?m7=K}17hC%8 zJFhL4(^5)>b{XTL0&T#;m$UbA9@~y+DV8*UD}pA2uDXkV;Bw&U5=Ey0E)KqbWg5s= z<JTR`WPVGle;)dq`0@Aeh6Jg*oxgt@V$QvQq&6$aZg8TDd505jvO{jmzubJDO;o_v zu(OTfi1?eFsrEB^Kugz>`Q;q)U;KI-{RNNVH%>%GM`n^W<TbT5Op0eR1<Pwhdpf9= zjapg-%sKF?bMMC+bE3Yi_c__IAW(k^D|iM|hjY-Kz{jcxWi)kNj;JtONP<`zzq)~i zg=GZY@Drw`;W)I}lHK+rq*k9EO>4P843=f6ov<>AVqP8GEI+LuT@HZ(qk<Hx>)H$% zE2}7Qpp1W9!$Bo?On7V#P^Pa?bXqQu=65x^A$h(%=#aj)zd5RG7Nd4Wk>)0dtG}6* z)$#XtQ7iSv$woWfs4G>xSU<WPqQ4VprnC&=jlyTHT?5pVjfYAL$?Wo+!USmH+%fg~ zuqJ-t=8ot~l-Gb9e}mg`WNc1CqP@9!!VP8Tog#AaDyo7ySMHBK|3S%Iq!#@TnpfjK zfoziPM6YnnA7bG1XH&GpP|jy9n^xFWeCVQXRYDu8|0|%S*#O`fOd~bX`;%MY<`H>W zKR;f#pdg>n+b7ejj?PX43cNVvzXoL8#&5*}JWkQpr6l8M;u9u!v{SDBZVy_nf29xm zWn+16M#T2oK*MLAA-Fr;HVU&e&p30^Gv#+5jmZq@wuDLkOUv`)Z|ADR**#$80=ryI z9J9036)4S=MG!QiO<#Y`%Z8OxTI^N_E;rwX^agzN1DK>JhqbqR)t=MSU4E)#q&Rkn zcEU&iaw*V`0*R$PD$O<ZRD*bkqqc+R$=;i!G0Ch~W#Zf~R5T37+<biH8E8Dc4{dWs zLr0I>71=IxbUI|GNk9egDuZjOYsc6h$k;Mdk+sL_24q(550M5C9?nU7wInCW+Iy?$ z@$oh83`NDr9P<oiC*PkxX*@iCLM=F3uZ27vluw+=50E=}b-yeL=QhEn&8KhjV&m?V z2*Sj#fZ@Em+>&=~f}0id?1DuO5T_H94lh?PubTrkzx@@fTcosN1*{q8d@AS-uT9?n z;2e13K~0&Eg=R)SIqYjYtrLWRGHMs&bRjck$+jifo8L}&(rWlY|F%piz_Ay<UDk_k zw453=-7*6{tYVUsI)`*?iaizR<Lnd{{EiJSHk^=)l4+<N>!>M>WTDCc{E&rG<pY)0 z(y2cV+)TM;%6y6~S1if8{ZT@qX~g>b7vdc{C+!xY0yti;!2nJ+J3RnM%<q+Lrp7** zeUN20nL@^E*XVkZVPX@K&7W(Z(5113EiI`SS~GOA21)4Yv>l8#d4C1^eMZWq_RKXC z6O&P!CgTau2YL8S+W66^<8qGiE(75L&fJRZ3fzE%m^MA~37Po$6#%vy1w+4TNct`+ zgvCTdq+it*&DOs(m&YISrR^i=ny@)+;e@xtEv{phYs+8~hF>@_(*C3nXgvb|ZNSb* z<ABZd^naE8K7a1(*9LL86M(5uycg1OVqXIsu)M-)acDT~b4cjxl)MeG80Ym}preiY zW#qBer*EM2Z;e(D;q?_5e{)z(z`ox8ahN`edIdE_jT9+cj<9XfkE*wXve-iae}{tp zpgk3dQw)0--QvFtDWF@E5FX+{axH5}jUS`YmLAhID4!*r2M!OpV>p&IQeA!Q#e3d! zMa*oQ4xP9~M%c{vNd&f0yY-T@jrA8wN$Z8mgwkux52LlomZ@!f(5aFgqn2GtDZp_X zJqqak=stfaa*USYH|r{^sqlM2%0r1prT5u#QZ);`?*rleA0#_H1BbhJ*zxh{NwT%_ z_gI*{;EQYiH#<Aoc%o04d5`+N-oc&7zHU2YKsDy-YIf{{jjzpp0K+%Tt)_R*CoR5t zYkZSo3(L(>Tx4roC+*Xz0}GyM-&uwkJ|^$d5Y>^dCC82D!)ZwRk;;`ty#X6>=ffVq zp!P6&GT+Xt9-sPU@x1bwZpYTkVjvc$1)kB30)fU=9Cr^V^0d1|ogD7iVW}`+c*njF zf*um|p6qBcbO$ku(|&Pn<i{p-NU>LCqH3A9)Vb1R^d8DtUUf3g88|_S^kb=+4UiM> z{bd^F@<w9o&^b_zay?i=4Iz9yj3i*!M7V3s_9;RG-|6S(ZHDzqyBT_)@3600t;7v{ z?yX(ferOQN<;`t6e81Z?z%pP^{}#jT+C`C3;al+5aZon1M;8K@gD+fM-<EfzR}h;$ zVyuD4B0<J&O)96uE5Oe!B<)}8E4(vgwO4%+-WA@rTyZgBaWfHDZs3L`dA=Jbctv;B za$8vLSuw4rxR{iWj^=<X<O=3IbPXNW&kA-w<BE)as~Q)YB=f6IB8aANfA)2@dm7Th z$Hq;%i28<Dd0^r_a{n~J?uY4%)V(9ZIf<y^d#`9v95>St#oN50JE8^#8Z9n=c@@^s zvb3dXNIIC7QJUcN7`8_Q!asy!tSTWu`qz=+E)t~Et68RB`pMs?yZJ?8X!HbJcKa?~ z|3WvMqZAkX=3wV080y2JAph^|f$E#iE6Vl9$JY;Me+F^Xt8SIgjwEa@A5_U>gy<cP zYK^SN`%|07;tG;_FdCnQ1-rOE6o(u@lYa5&*}v1=zLO<cBtH9&Ij;fz0o{%3=S+V+ zm8qpNY08a4_>vQ2G#;nc>}cBEpjSEK`&785LLnoo{vO688iC$#lq<vg`d}F#N0cD! zW~zs%XoIzh?JhjnTAL#{ehQEbSmb5HR9(j0X@5Zo1C)Qff-G3&WbrZp-SXv9TcrC> z+Od>}JRy3oz5~z*3H7vtiXz>AD(J_)j#ggNPL(t7w&vnjPpAh}YJ|sUi%(dyyArTP zlJ;1T@G4154$w-!4h66odPnV~+3+~wpIf!uh_VjYH9)&DP*yX*=%|2d19E!%mwybv zgXvfRlScYG-U$-Ecy5K3dEy0!;d*?T^ieiu$mKAerilcan3yYlh!Pg2a`GdC3Id7Z z5sl4blVD+IctFy5HhV!4I29vAS8{HXZtgeffjif76KGForVmWI^Xs^wVFc>w!mLnH z)}9NTFxRn=Ghr3ZpCPa|?!h_nE^*1JlUFYgR*amwx@#7)H=E6L)Pb>#-Wx=#bk1Gu z9GhrjJs}3@FRrexh_$J$c~K%3&0?kb{<VnAFDaH4x8wI)R+16=5XsPwY*uzNFzQl> z`v9QvI$TP9=otCL8o3ay)G#aIHL1fB8e}~R7soWcQ`yWctK9mB7O(z)T59at<Vn_i zvZm&fJoL&Nu5tnXwW5!UJr*n6bRyIX@jr-d4AV$GMIbD_z7nl>W1bzK+}$scu&dDb z9Ir=--{+W)Iy-H&xU>?1@2mxP;V<EqllnWrK6duwb_%!Lyxll5@dixp=HXqHPGSFU z2XzlmsfRrVEU(8q0hT7@vKhHj%ta!VbtthT%FX=3zSB}D8Ce3t;*7c$KY&NwrHx!u zE`~4dZ1L_&{1WQ?iWi7(2(Mnfzxzg-`tr#>c=FqqOia+G66zr3TsR>Xx{LQ0W@SiL zxaSXaOG`5<(%2wHV3tpqE9(CqF=YcijczihAV*SAN+-uEA~u7if@CkU@lT@kbWzm* z9j!oFO0&sppP+zt@1I*U!%<{#Y*FOh?I|Q=tc{14aFeZmeR4vLG)dpa;G8~kTvJ@* z8Gk{3snFwGS*E(Xkpp#}Yx%x$qllktbTDaZ62^chyZ|-4Zo?)(wcnp{R&&G)=q-@Y zx4PWc90vTn#2jA~l;AolWR@B^c}5Ul8wobvs>ELvBhlqQ51EHCNn2IBaWU`0{B88O zn1k*qf1n+@)5Slal;|ui;ghmXf|V077@Rzxv{Tgq;j$z%%x$bnJSd9U<jrv|N`u&- z%crC<dPox*m?w_5kW0FUEs}z~ymoh*JIE4^9EGlY)*#~QA1gO|tiZ({j=0=_^q<OU z6U&T)L^nOnY$ntpY%AK4Y_04}H*c76)Qmguh<xA^WQ!DY3-F+=_5y>cFh-mk4O_dJ zW<9NOi2C(4RtVFc<rNaX6%n3P;rVVbT~I`VRl9^<`qjGf1tP|#@q<rUc-p)CvuZgJ z<!+1B0_5m5he%y3XB*ib{<|k*+(ux~;q=T^({qGc4a%0IUMeKiq&jQ{da!w#32YXN z;#$JbGuG5FKDCV+xzKVc8prebx@{dWYMal}5tBv4*k6Q>`JL}+T>#{oIwW<~FOPKH zjD&OeN^+V^|4um?dhqZ95<EsESE@H9c?Y~V#+>}2g|-=_Sm3a__S1Q&Yg$YJJi!%` z60@Qq3FfvR)6eD*R!qeqR2ykjgj%MUieG6~CDX}zm8mh^!1vt(KDnKR;G8b>-(HG$ z{GnR(Ll-`Hv!y-AIj}QF;4k+^TX2dWU(?!bcBz+a=xGkKqQbbk6m%)Q`OJTsv-z8@ zBVxd|`;-2~Z<ahaVkA0ql*^{FU~|)E1j;vT9Q5v?MBlGD!fIG~xjAqhD7BF3bkgS! z%!j^9@h(ni<(%UiQSj<p>$Ps<8xJgHDXsjrlDlFvu7Q^jZ=j~1u0OK1zyC6|FJ)|3 zl_SleO@z@t5yJsRwK7!CMkL)n6VofrQ&$MM7@e$+gE4)HJyA*4;?pr;&@lz6Osj4( zjdZ{I!-X?+_<l2x4vf$T9(m;uu#vUn&r^Yht?L~4Y)NMqI$xF5$SZ|0BK@q6@c)&V z5ETj?+_!tsP)>YOueLTKVR-|>l#CFfn_rr*PS8<I;*5wHCiv|v=!_Hk8=H2>Hu5IG z!UJ~ww`#PzVLKvmC24|x+i^=i{BsG+t2&&VoJ4N7LT(RtF8?*?*GT2{F-V=paeWV3 zYW3<&HiQPUyCRl48|2FAX*p38%uW-WK@J3Zk!)IUSvuPzT&8q@dop1Co*gv*Nyl;m zJ$UzHxib+*eUrjm3b`DL;CDJ^MyUr?Rb~<qeVL5Lj}!C4%HT3lHAZ>$MDDXJ%q`_1 zG&(iyYeHuXY4Wg7yabKItXsb2F;{OaNOpVVWr@n=ERTE@C^Lx_$>-BE^Nadv2TZyu zl+Ops!$x^DtBSTc@zw#}6%pFq7w<tI^Zj!<i)Iu(!LCJu#RcD!xT<Jn%cfvar19LT zDk(qRE@4lN6b0#&fUoJ_`1g4~wqu6F$(S1N%N%fF@5n>h`8N8xm>{g0IL658l~*QN zUDoa<M*w*4qhahn)Yz}pOp%E~0Rl1K+dwHY8h~rWTMYb-4wCVB`oUhI4n!O>>So^1 zNh2lPx9*ZVSSmdL&akBNRhL7x)c44gBICaySeJTad7l5kYsIw_-9LQq9=V8I)DWVk zy8Q%>#CBJe;}bNTomrtL-FF}LoBBbaVYXr(b8<b2{#Jg!M4#vFbaUX_R9bZLpSy3| zKNi=P<0wB0=AU}?e{rXIv-&%s%p66&pxDSZHr$Z)nG^S)gYXmPNZFdx&^(u{xq@hq zh2`jtXf271wXc2p=v;sQw#c)oiQD&%cdDL;t%Ql+p2?u>yUa5VB=ou#W`eb)FNXqx z+|S%;bvM)M41bLUBzvFO2NYF$E5w>xhMjYmj_D%GhYo$<__-Zk-B`Ye4JIM9X3Hj; z@tbcBjt=!!+frjM9o%V-Pxj^?;Yh8dC&@jb#?7-Z(bJr>Cnlp^cezlScf8Y)_1nVx z6NGv<bXw|mizsW^tDi!}Wd>OZpmx5p$?l8E*#Jzkki#rSRYKtZZIC8nT6OElx^(ln zrMA3PZs^Ktvp<@nB?24zHUjlhWfs8>z@xdiC9-%tLHXdTKe70~6DkM=I-&epvVWoN z?}(Vdqdl#Q_LvTD7eMB}=kjCG|NrYPKs*K*Z;=VOi^nHwCd}Ha`g@jmqT{QX5KI`# zlO;+(K-N{LM1=j<hrOg-pcDUjOR#IAhxSF`?lxh0xpgVtVCOYLJp5=SS9tsQSiL25 z{cZTCGvx4J|He=5^>VvIf5ihLgkdrE#jfjEm%hG!PEG~1CnVrFU`43QBNnS{O5Oo& zNIt8{z0ep_nqDtsN2M$y%MOzXmoS_c<y*d89NI;{WKOykLWam)S`5W{zT!a4R@)mp zbblWj>f_@{u1SC*h&607oHVUF#aE|Is)DZ)gHB$LlS}B}aA3gMygM~=zYJmexV-KQ zj&3FF{g0w#%;ZC+%PmKQ6&KWwF&%E4%@Zq9vgJ;-j$op2gUL}&u&^npn4xAM%QWKH zBILn)ddILZ>09Au*jTV;gFCFK4u?=3QdI}hEh1G*`BF;khWp}iWo1oPX!BKWB1<P5 zQRm1{v4xdbo2$O@v=L`(B+TnRYpFH+DEEe9^JcvDKFz_~C1|wPpi&h6R!J);)3RD( zf*KY~!=U$f-uJZg;YOqAr}?CVY_=T<ZHH=22z_Kc&(AR6@p{Z|<rwd9F5^A?e(fPU zkWb9ycrs5a!85O!k?IAF$@{j<(Q2iRz}f*5XX=wza10j~jf1?$T$MGzlS<&<aY7EK zGv@`g+NE{;FaHLd#0fK9;|GNKBr(i4-dgfeqov#%ycHOr=p7R+E&a^K-pdrtq^FBD z+8}$(2JClfS==lN4vT7S$uu=J9koUvw}vT`fBG?IF1ox}&GDF+39B6sMJ;g8T{fZS z{OeIQOyX(H|Kt@sD!2#ZehctkYmwdGJ_HJhXS(q0B;RDN9WF4p=NmmtN{#y<f*pTp zh-y3W@w7Hn*gu);4T#0n1@1KBzrwMP-4ZdRH|U%9clV%1SCTZ%TB&h|izSHw(+H|g z-~6?Zmit0#S^NRT7Yl6t_vZ-crv5padl6bu{O`!Wob5HRA}%8N_r>9%z@K`Qj2{M$ zVy(`rIiCoBH8*D+9<Ht|f9nvode5_ezVwb-!1d!se3TBxr*3xc<5mnzvb^|sB5l>e zz*{BGLj#_B^!w!fu$B*>n+q3n4{J|%n?5l=+-%+4++f_XJa2Kq1zbF{3lsb=yOH?o zu`53hwOpS1nAH~E{72qbSem~tSdWM%;5W3<f!MZ?|I?ucHl0pC`fbJjEl_c(fZiI2 zapHl817h9(J!qA0_Oz#VKVy5#9jj}CXu0$j;YE?d6lRs=w)AyyrVtwd#n<1R?glN@ z7$M?V@1;cqh^4w}+t4~1jjboBdVPG@8pt~<>nQxU3I==6s}j?jQE?t*z8(FECxFig z+-;5!rR#izf3Y}l_MRG<pm<ehz+813j>L04tNrhjumEf={qJEK8@p0;Z2p*H9WDPf zWU-IEdhpyUgOBBHZIfpgsgPv<r$D5w_yJ|pZ<??ACTI2fYI9(tC1`EAj{(+Fbhj;5 zjSDUXGl0BQ?gr`rKb6p=l}v+Kt2{-RQh=L#deR}{=w)#XvYDqEdnR4=FG;y|b#|$^ z%ec$i3hOaPW$<9iC+12;CDbU+RE(<BZD1Hx40$i-hn=@kGlPHAH0>n{jK4@H&os{j z!Fr(4sAW^HT2lv3c)y}J+V<=fL>Ge#Q9UDKQqjLqjSa7aU3Fk3qBuP(134mYW!1L= zv}+^D>?mb}i<1Dz4{X>El$(zGAGrC<KtUav*e<e<fl-<=Goq%nxr=5)p-G@^VS6q} zd`@t<b#X5sjI@Wv+$7eQt}ThDzFLw0r9qA~IxL%GuK?N(i${@`C+{Ho!u=TWB}RG< zt?k1emyS+oCL(1292nlUZO(`OQrcrIfdT@n(F~E0z2))ILvRz@5+Ro_1xhjBcTn1Y zmO2GB2qAu}t}m4hK4%8*<e58&3^xFFxVMtJa_=7Q4t64z9^YTVGqzJ{CF6kO-`8zA zE^F|sPUoJIJC(0rd~~3~;b?KAMa__x9H+ypt0}bU=3>UCt`bkd1m0P1&9Bur4GVeE z$h^1hJ^dCHLu-svI*r-n-j@$Gla}GH$0s+<vUM#zL1e6j31Voup6<kS*KJj*an;w# zSgCUB=)E&2`1Q}K6owepP(FEU$!JuxDW}K}`q<?tRv1|**f-aIZr~waJ<4tO>~gik zyBacL+o;r@*$^A^L&j=7gfp#z)v<v*co4ZyVM`$(V3L_syZ9qr2IsK+@wwf<t(;Un zL6N+TO#!jBmGOE#S;NG2K?Lc5B=l(VH1U6mHmTL|f7(DR^mp;<%J-6Jjn6|{UG9h( zNE(={it4RAI#OHu3Xh<t2~Qn=FNJ(Oo~Sb;C-YAo1fvUnSFfcmdL63Xks$87uCMd_ z&VD2FFvv&wT~yvpRNm8mp0&`!<4NFigNBsluXkE<+f>G>*JeLS(#o6m^)$Q0tL4Zs zvWW4l9{DGeyR<LV{`c$5a$0=kJFw?$neFEwSW8oR4lIXr6c&Zv2+T}az}$1Lq&FV2 z!b_5Y+MPf+nOX{zAKU(Dsq=L#M^)S<?rSb%?kugUMINvWmZ>2ppKUx(wIb#cUACp} zmIdtJ-49&PYu9J4@mk{9{=X@!%~tDE&GJei(OLX;_|*dzi$>?z2n}11_*b&RoXK?v zX4@crB%GwSb<Ir1ZAd~Q%K7~G<b`d*_4f9ke{(gi3%OfpSrTUt6vJM4JKt0S#h(dX z!bjuYv^{3W^SI1|pk@-Lb6~G?N}51cMPNA#jX>~?#1s|o1m9;8KDI&(CT^`2kB0nb z`N=!wXIkPE+B>#MYPkbcw{QaAI!c0H7{`V%1K`JG84FY-c3~Sen1@2TKwl<bm)5~J zguvD~P8z&5RAm)m2eS(tFzdJ^d4mxW^N9zne*tGISHDvyqE_6Pc(I$PS0+A6S%}@3 zh31zyV@o?(p9SRGBBdIZa_%E1YOvgobIA9*zfq1I7apW+Sx@{L0bpb%DTe_&(v%NC z<;2m1!0dwE@1~$%)?_GZn?{VIC4)aAHARk#Ejl3c=;-koocsdt;o3zM5U@nMMKBy$ zs$wNOT+9kEhtDUJqDJD>5(deUwU-6gCw|x%u#+v2D6{tRxLis>_S6saSiNEUaurdJ zqWe*=+l3nD(8%QZau$Ix_1!}9TcD3JzIXPvc07od1-nHxeFqRPMeicJ3tRV)GMQ-; zl@b=d+0T1&M3#;4$YL$6I8wG0ZuTzydsQ;RfMI^cG`sql@Wkb5GVp$lC-)}rIXm#Q zzhPdSC{Ic23%S?j0ZF8ItF5f7YCe-;TWM<<&TxmB!(i(E;s|}%hH$3KZ4?p3nHQQT z-)c*L4DHU)dm9v`fDHk*aYi2IN<Zf9*0sm#eF$Zmodywp*bVng&P&1Z@p1B32iL>D zFt|85C+;?@p>Ja92vPF<qwScUcGN%1h*;T1g_#F;#||3s27SglLUhx4e~-f^HRS4r zdUb@Cs=xjl;4ZMVDv>ejEOmd_V0!<<v~cE4Rs!b$*yQ3>gp-gHd9(E8!M>>69AQ;1 zq4eB(B437lqCryIL`V7saz-mKQMXJ^qs{FEp%8at!(9IS`2N9y6ju8n#CQs<ITE&X ze345Pu$fKse3S63BlW<r=6AKh4|Ez>yg#maSlmBPhukAOLZu$J8jyhL6CV#NMHic) zD?B{BcwBQNpxHvUsR@~_H*ND%GFP3b2{`dZs*YXa^dqk@BXJXK@xUv{UDFeM?E(FH zoyPcmV_w@`Yv6VI_4Ps;dfD{Y;)h4MTZWmQWKx}8v=r<xCK_%{9G~*GED`|od&-nb zBB1D-Pqg~<AiY;U_rN4?lbQi&Gcsj(QN;rt2fTRwo&1%+%qBKu`Sl|w_j)to!RN=` z){I1ux;HP1-do}zbS&SYTUU0}ZQh`~S}5pVGUS-<FuuE~ryvM0`=@umhKHfDdiTX< zO>#}l=J;g0gfK^95BmtSnIY!!lPqis-1hIr!Ku&3HV*Bpi{$V5qxvrs7%>`LOlw+> z<uCn#R#GVOiS7U<&08K;yrHw5oDn-xWDNY?Ba~KVyZB++^ilF+An;+}`uZA~VW4?> zy6zlb$kst1i3Bc6mep#mvO5?(NjSAkiC?DKA#Si>Zp#loUN@A_dCyc&6_)omH>}pa zuEWEXF}X)q=NvGb+Qt+LF6dW0>=(E+XKaQ_G9qBXV8J)w_iEdODcFY<UO!SlGmRKD zX1I|taY3?(G1Zp3f=r`IOu)q<8LLjZbL1dhkGHgmX@#sJJkzxc#3`}CScZn#miHKS zto0#F;Yr+F)x}w~LGLyR+g&4!Lk!7nV`t8eavP-^CgiY@HDghPv*78^?@515tV)~E zbxD_zSfMcK3i#66&DyPD_x^fKK99OTGa<(?5enxB-M3w~I0|mAh{<Dcu0<C1{Un^6 z;aPgA#!4K@yyy7A=NE2e?przF?~IrD%K0k*<wF%dL-2XdXM=>RQ^8LB9YX8R-3^u& zt;3f=4Yz;(Fzq7nB>kRC0}e{R3{{EP_;J!LH(GWvc|4mvdyGl)sdvtQ3LmtW?&}Ps zU0fLt_-8uofD?!qfBt=Yc(-%KtSzzL)7fN<X!<FXkf3pORce%Ngh(vNzG?PtyKZaU zw29uZHAWFA!>&y<(l`qjH~frBxtq(oo-I25%Yn5l9k8C|McqlZqA(H^#Llnux2Wt- z?g}&EIJA5|rX%2y!m^%QST`mon4W;a+w=U!r4KT#DI0sQv!~#9EPy{rbV{eLK&j2m zb*kE}{?sSh!YwVkeMO-cj?=I#HQs}8lI%49G)A&Qix@1H-y$(+z#T3w)c|GJkrT$~ zTG<pc9rC2LF@0wD)SfY*Ys3_!{&llbszn;FCd)^_^@JZIeds{`XW=roe+bd{+b-}V z2u*NdC3A<UMTvmMAwGd>D^T74LW0__YgVY<8Qw={^D%=KczkqXKAE(W4d<s-jEqDm zAdZjEcgNR!Z&xQL3G7dhKCH8Xs@3jf3O!U)G`HWvJM_u?B{v~S05pZYmlI}?gMB`2 zHZ{!{0MhfmS+{ImL(<2iYZxvg^BZO85=}6_qQVp}samCu(1WU^&CDl2`a1`)bDaCt z>^q*}*x+P>a%ua7b%*YYMw<u&zJf)g1Zl#aW9S1L_Y+%XGWy$@2Jk;!jpoX})+<4U zG8OY~P4y?`f<1m#Yo^)qx1(h6%KyjHS#Y)4v~8CV+@0W7C{WzpU4yi^YjG&Wf<ueD zyR|@ZE$;5F#ogWY&HX)VeSd*4*UX%A9D7rw5>u=O?Rg9H5Y|<xKiq)?MaaTQ@P7t= zqr_`G;Xg1=1U?7Geq!Kd8GPmYH#Nn+;9AC~;~X}@Y13LYI2Kf-L26a&0Ta${66%k7 z(OAf1%tGJf`_B5}op_rh?i^AGM~7?YpE1M%Rs$Ripk{*vl7Hp?(#$_p|Ac?h&r3|p zaANPTOIe9^bJl!Q=ZNtENFR*Ds3dDlR|ogmUp_#Y-5R4)U*Hd&x^-r|5w%1SDIbT0 zB$g)IGR&?8Sc1OE^*j$y6;{yNZ9||?5e{1xFqm(oxeGf7-{h@^g-uwsgi1y`B}J3y z6MUQt=28npvCynPh)|V?My<8;S0G_v88b~3$d8;<!nG(6j%8)8TVV7f?j7tPC|RlP z=+a>27PR$W#pAgteD8?|-=VE#cT<<f+`!O8IBV41b?2raeM$`ME6LjyKW0_`Sddxh z$HbNH`Eitb=OP9PX~g$J3w}^jBiKuGQ-SSg)QE;(Ko4=4qoWAKt^3sD#oEC;(ygCr zf@$YDO1w!tXRIRT+TAPe+fmH1tP0jg1Qxi#j$6U^+tJC3l=o@Y@k%Rwr$(CfAuC&Z z$3BQNWah=biD_r^Et&`ldgl0Y?~aB;dzq5axWd{iB$G^fn`--3Gt<R}U^rbxV|kS) zxy2BHX9uia{}(~%W0cdTqmTIS2OBJNG^!^yO~ybRMDc@7({eT9UcCIh&nApf+M-8Q znrdQOA`%;1FQ{GpxmGFM0H*@ZWA|mZsAZ^zOtr+@cxEKMASkid1V>UXCY3$Cf|lq* zidOCEsR7Hl*1`gzR?4M=_Kk~2d~m5KsxPd-oh#X7H2Oh{i&%ndewfUi*^r*ZfQwaM zIudz$DYb*GX??E@=eqzC9g@3gojl;a;Zky5s<9br%6r1sn}jw#BTttO4>vcb{)_oP zKDs)-KY8(_^=eJ({M$?pxOzvoWD-fv2{BQ6o+tQTm2WC29HCXf#6HTvLV+}p=XCeP zt>_?-*6#fnkM3j_v<|`CKKI_Izz&J-6_8tu{1qm*WI{>AyFfIERtJpr$pX-FI{+f{ zBAgut$@yUTVZ&y*Zj|fuqgji^m;Hb3DjXo$*|ao2-GUlL)7Zp5Pp*MbLe0MUhrcIl zTb&b);zjaX`qSAe0rN=f?vOkrAi&3Z7R=IJGsp+3mygYWv#BFb+1ApL|E*88Z%0q8 z=BEIrbZeqK-KaU26Xg#aZn|%{%P^8!ff3w^_~ZT_VMSrW17xi!E+1}waN?x+dmPD$ zxPAC4WEL+-boR}`VXxZl-+;6`QrbFh^n|FE+e954z{fB_qWWc-r!xfcd9T2=pn>!f zl!T9zb0z{b#-#nZ94}_!b;Hwb2?)Yb2MIMvrSn=(Uc+n1%@HssI*|<*T8SkAf-;$a zxq%p(_)ch;RnyZJ28josVqvbAgZmrJ<@=}9l9cOtq@`3lQ*1_I9s=*+KXBj=C~O=` z+```IPW}qJI5$?ZW(Vsl(8qFB)UslILHLaMBOjU$wqB&uU0JM`*>`xMQ>I6}LV;Hf z5|fS^%_T&c`Gfv756up?O$rws8xiCEU`_)XlAmOxS$EV?n9?9Zs|))=vIi62-N>LT zIK{h*{!fDqDv20DNUTDeMA=mpd(I9=n&r+B8<`d7e^&Asf6nZJDls;oRu2A=_raJK zwua>u6PlQhXFJcDD>D>iCkbr8-a(eapCd!eDPcLU^H&HD6YrNT{~nIu2+4TdNvX5r z!<^ji!n5xB_g>G;tprx3A&>#f$D@r4O81V0R!wKX_TW~ybUl;WS>9n8D?#ru(l1KN zDIvOFf$*bw;vFz8z{n<l=clGNGf9#h&$}Ze)1a=uewWy`V1okK^(VSS1W*3|+CDTU z1E_r<5;yTd3hD(M(ogx~U%QPlt#M+>R9KZ_tdC3uM(O?O4!6qh`bww3o_2#6L4<^6 zKf2ae&(A4Lj|$0>bjr+W=l{eWqpr_<jNMaRvW9^UdrX)-6%Vw}BJ-4KU1j+q&Cqu6 zt=xpohS;$|Y~y7W$4i;Y=Og!P`v)5yk8AhsysJ6c9sKL-F|0)!d!gMB$DylX#MHhv z$5zTjiV3qPB>ZD4#UD5nz3OJDZS}X%WIWl)`L_oA`0@t=;gFAdTOHT#Z!Flw!6*jP zqZ}k(8SC~AF7h9e4$%9P;ZD#|<nm?1Km+iifAK)(sj~ErQNcKqvd6o*jwSdC!`SqG zc2MASpZ2d87@r;TNK7bnb^$=fFdxO(*+$)I{1Ljyh;U=4s`l#bGB_ld|4SD5@m5^> zbiXY?fMp9HsD4tlIQc@_xt%U`k8JWqtQ_|jcb<fXzZxzxjb<r$kJvmCVOPwT$}Yl2 z3>9cH_mT{f0-DKVZhhm31b(c{HWb_Br`@8j3l?v0!AD4S?uN^R@Z%d9{yk5{`l!;0 zN_Z0IaqU0ZPTAY<p3VJ51unJnno3(LxHKAYwYtXCcBdm`*&PVeKGZ;h2ch+W1>Mk7 z5i%1|OUj$SE9)ZVeBN&<sofDyI`p(&`h>>=g?9Q!!)wCy6T6HOTdS8K01xQr)X`4H zka|uAQDtFJT$#)~PwE32KzTYun5`%%U1DnmI_5-NQI6`^eayx-U;sO462Q3ufdYY% z1-}5G3k;{e&Tb2%L~aVwWo*aU2MAmY-dZa~D{i%N`bvPx3O<{jmPkU{RqaOV@z0%? z1kr-0jOK==qZODKJwad|BMV?F4nj(xZ&rc<%5Y(LoB+IQ@Qkgim2+W<|1lUF+H(aC z33%{?1RP1Lhc~sgZB}Gyh~BU7?_W}l&dgYeJ|>9rXZ3G;o{%+Mfs9G-Z!SNWY=MG} zT>*fsO@fzAy^iY+TY<}>_t_3b(e1Xs8J?{zidT?3v;{3K!brf~iQ%?no9CQy3{j;@ zKkNBwKg9eJ70zyNui*v4Tcq2OPh=!O?I)xh_ExnNv3^kCo)`@Ar4EaNQ)(@B^Y!)g z5iSsER-~#uemrxn+#T74lcZQ}*RAadl$z}Af1C!990fWLj5M0`++zNuGw4+UfhQva z33WlRI3dTCx<A_36JbG~TN*G|^mJ>hQ8hyrSUXo=A_#~HzwwwSd=(<MyF{Ro3}Ot| zXBuIjA3{~LmUu&c<~TNy_18VZc0(y<j--WRY$5J7lkV2Gm4CpAL}VxSX9N@7V*Pm| zg~@`k$3zh!X`aS|MEm=!hAS)Mn`t>7azgB;L;akmG~{OeY<9ip8npmRA`a;?Jq&8J zP??KWj~QN!Hti3O(!k{j6;+*|_n4j$Zr_{QYK1$ROyp-69L`hqLG%7|-6LoMeAXzz z<J;OT)9r}SPs19mFCcz9cKBXAvuzP#sO=ZWN2A<0*XApLn)mUFwg#+I6{n^?*3jG8 zcF@e{a}UWSmO`=>xUx7V@^9_svO~uh3utqhT&78^9LqL}3YlB3)<V67;(YJU|83g~ z>k6NTy1RL5UDvsj|DIo>P*8wki2n1XtdJjmqM?mO`koS~kv0ZkF2idV?vKWIqAig? z=&eUN@9U!qyw8_U2r_LZVRicU===8axVcGnFOez7{-3R^NN2qC0w&Lex49qit6-?9 zIoejU({-}a9te%g4T|=cd&@Oal$PasjKT^1kjSv9T@CEq3+4&70o13XgLQuvq`)Xp zlSO(4xPT2i^`#;9Y5-9L6OxokC4mEYv1q8@&J`ZdPN2oinoVYIh9q|3*qvJ(Lmp&y zIIWgMR~_fiIQknO0c;RSY4=6o2mJ1Dc%(dhBTi3i<`28S5}-fJBpxdLiGi5oPlZ9n zTZLB|yl^@N%`EC5csz_qarAm+w3Fpdb@}!6fB;YUvC$=_2yEh;$<oPRirOf18vBZ@ z3&0JyV5Bg%GBHI~7#C`oU6EV41KR#E30!8zxIcqH0X{?5kbL}M)Wv^<xddi`GqcA2 zHAG;*I&Y5H=X@WGBuF0L4u6J8C$k_UhM?w3oaEB%ZaYgdB3g?9&#%XgVYU(A%^Q!K zwlm^{)a%*$_4>#MbiX6QcgGV)sJE@*_JcG5h1}lx!-JDm2t3iVVLF&#`OK9gXUy!n z<$+T%S!!vN0Xy&~n|mvs>V-1TbW5f$?;<(dHqz2u&8}5f)kvz!Qs;RO+s;i+dR*-v z8154}QY->;Eh!k_5sj*iNh6EP_mzMDB!2``f}Ve}p(XVtn&$}vE%1y(ful%vG_oWG zOQ*o{C}QhwGt%Wunc%ojL1N566vrZ`Fs2MWE64FAlIl-_qM}v^8Q$35Xv5YkNNQj5 zJyKcgp#F|w@+7j9uspf{zux*0V<U)R7(+~H%gRfbmE5*WI6bvjb|OSl?VX9AU*<~r zLV3vV?(Yp-y#pXD<3g2x@#82AKUiW&JkV`_S1CyCLhPWyYS6Jx9pe+(GRetU$*D$4 z^;*%lTgh=A`N@ll(~F&M#ppw`4J(XUf=m<Rv(Cf^g{Y%Z#+@^Gn94=XAO>$)<60v; zF}0CGkBr?wacEv{6$$_W<He?I?I0G%BUE+RKy=v=L9RwrAlX<?Qz5N<sF0NwkTBGe z)L~ai06j8ROX0SS;ofzuk!<j!({SCQ2<7Q^&p6veui+d^Jfep+Af|mUgT-ntwhOOA zFDu3Uyq%oa)Gn;yY>XG~z6#S}D{S^ixdD@jPlS#rmB9yDTXP9;J9Np1F{B3YvVu!Y zfumt5=xht_;}z|{LTU4!xG9R(PvF_71c(<0|Mjk+a^3vL=sbMJuYNt*Nu8vtrDV*N za#_+Vjub*rFsA=x`r+@@pW4O6I%{w|+J&_lE(k?N07OhvoHS7!x1fh^E$`ni1=Y9L zSxNEh%H*{c%gSSN5~OpTmJ0qb6#02Zd~?tf7&#luPcqw0X+^Kkf)a35rI*W)3?zuX z=kZt2oQqneM6zWEA|@7hs}&;hAOxo@>wgvUzeF6YL+8nZ<MQ}_=g3J#t_U^xG%A0E zpMXE?Q@=+O7rE2_*ezG7RCOl-(+}?#;lF<U4ZqvXMC0L#282D?9N2h*Hsi61q(><` z_fpniaPx{j?Hb!Ae3wp$?o}@HHoRrvdb6u}zEZ7~11+3A1YzdgIeR)pM;Yl~Fy#&x zTgqo69IyY*_fZ~Dc~LoMhVYLsuo|`+H?OzyLvD}eV%`oM^ABzFp;8H@YpO?f2IuU6 zC`0xmYypRpuPdh~4zCsK^>u)^5x>LreFTciMR%vIs4ioXSiAAP1?TIIE}r|lpXe7p zLchZ6`#;kPkiEA=MBvMvrp37qnwFU&Vq49&9Ij!ASEcpehhKjWRu*VE?&KJ}JiZgu zn690%I<UI-$Vr1!^FbV!3y$tZ2K`XrqC@qU_4Ovj9NmbQPpGyK9sR-SHT=&1cN!&i zD;D$%1sqj!Brl#>X&O`ikcmwM?fA|RIG*pB{lngp6N^j}2if^cPwU{gj5_gmw6=1k zGp0(k#>gkX=-q3o$KNTb<^T48pR}0=hHX>gE#DiegA~_r1d;_AToAUfoH9++j~@p* z2K058TiRpv1plF_wesMO#2`7NbjDP-HKqBz9dTkLdq2A!Z*9F?TnzS*#zyoAd!=Vt zu;j69%?5w|5bA#APIuXal&*$fJG|_B`)DO+d6};0U7pJA=jstU;qYe7V<JB8tt5Py zyVOz-M#W#$;=Dz#m;=ni^M1EwDj>P=Kl~*ed(+Ki#h|vX`Kjbj$rf9;0)kknFg<c& zSQWoN^wHzY;>#74x?%s1S!VIg=1cvM@1DnRi0$PvAAOb#`Tsj+cHAz1WFpy;_zP<` zFc^M8#@o5gXB6B}?|9ovGv8E(eml-Uu7!bSlBN7O`H^OWn?&*y<oRhDd<>^4lPksi zk&_mv3qo42&#u;&H`2po30yYrY$`=STw_5(?|eOdou9|hT1ZI14L(Vj7&jc-=Y0AR zYl=Mhn`gUMIr4REPdz493>(%%Bj|l<;`OcWsbq1lxm#2wWYhcTwd?II0P6gS9Vkpa z;&cKsCGK+<XHC`<aZ-D$!}k49872Whfjpr&x$}bf{)|EO$Y742ab2A-DgCruLFvCg zz>28TSxdxOgZn-mVrQ57ho5lQ2ev9_9juOhQV0aFd?6VkxciFluZ2YG%Lx4XjKur{ zCo=EzM5q7vNGbdDhSol*vkH}F2FyBWYUgtsEgFj*F`PBndRhvXwoKo>ejb=uJO^_$ z>m&*{r$xDdHpvy(jS~M8y#iO9^Hn!|7BO95N-B&FN|Q;MRLNxvW=ij(V0c#$C;y7| zfltI{lL#~UBad#OIqJV;UroJj9AZ2?%S9RFq#D}XEd)XoQY+9d@R@+Oy+^3XMj?vu zY)fA%Kxw*MsN`XU#K_Y>1v~t1EZ#LVjtH!>P0FQI9}hnf^~_uZz6(vvW`!7b+`rs> z^c(RzHFkVDxgknyc`OJ5o-MGh>yKM%LEqkI4Tlbq^sEDC_OPCp9GQLKp57l9-cGDU zADAqS&5rLx$Ss62CeF_tc>ePE?o#+5A`3#ZDIO6IENeIsm|E+7h<T3Z&=h(9&n#~D zXFGQCGsoSq`X*<^Z`%Q!j4ksIO5eTPy)wpbR&VXx2qzNPQVqr(9UOViwn7M&j0P(4 zCmaSnAbvfgJ0pdz{=`|$4<}r+mJU3QHH%9_L!8a>yD&dd%}s~bem2e=k|%Ofzw(Lt zNd~tqrm#fSa?uGg3}{rSFI<oz@;nnQPvr~nT=P}stS_~t8%$JI5D5!y{SNdv&QkU$ zD|;d4Bs42z71^+l!Pv5Txxe;6C#j1(nz}^hU&=5rG@Q&@`NnR_i4vXpIM6w~0vRnw z%tO3EMntPSoXSzXDKC&Q(G@oR--XlM1Ps$8^oga;=QXCu6t31iXt_9PYSkp6xn-pD z2@dBclnj|jd);>aHe8#K(DLum-0J!0YO9TK;xaOAy&F}d)hw)bUgxBm7m9AmE%k^( zjPPJ)@@r=&Z^1EMcd6>|gBDVj_H({fWg6-CIuEC}v@NawGZS~3be1EBvf)n8vHgE2 zp_tYL7Ld4_JFACvXeTm_AB0|7<OVqqfI<R(F-4sJ+2%pW`k71%8Wlupfpf_K@*iZ_ zNGqLEfB%WeH*)N+H3i#dzrqnZ-)M1jW&z|x(hIGT$sMmL(!nbunfR`qk|Le-hnk6< zJ7TX!_&*w-(^G&A7!TwL&(~5G*e)E2J91;d7JV)4q4)e{LeMm8WEp&(nXjBbNNjeA zx%COLtej340s2te^N-yJRZb{TDXKS;a)O6hR}~ew+5Da3f-!P8$lokA5PqTw+X>}I zM{{$@H{VQS!klY?#qAOz*0T=iU`xfh5L%+zfy<)sb0GBTJdDtT6+n%tEH=Y+XKCZ6 zLjhdnJOeu>iH*=RpuCLiDS*911Yn(s;5@WDv1*|k6#;(ZA1Wl*q7{y38K~*HD6&0% zix8X0F0FoL+4fNJ2XDinYtl44u%rVqp5q_@d<vSCbjv52j0PjjP4`wK;_Pv+G)wix z!VVk-x@;}t$qgGWGEwynTI(wfA)d|R_M`w0@QlT3>EjJm{7ixo0yDmR4CSjZc*y93 z@WDp}2#Cxv9X)Uz!^iTK_!ow`1_boyvbxQF`7O+tzDOA$D={M_CS#M#E{#g#s6qLM zqj<^n;?;X<me86XVLJ>33>rI;HO>;wV{9CQm1rp=K*kgK3#g7V$BO0T6X*94Cu%xT zkQ=O|eM#jA*0#Zv4kXN;I{qyBy3bUHK!u|-iUZcMUqag(S??k-TYXq@L|gxQ@<$$3 zZgClpb-FUC4h0RVAH+1Z;>s-&G~}q{e#bxZ?Y_;AD@u80{&Zx2LiBA<7W#(;Xoa;M zy1GM?4f=Kt1C~+DbN#2gyZk|&L^<`Yp5Mn!`9wsZiXo5pXVELaA!6dUvG>FGjU6^a z?bXmqjBoI1t5xq4V@IwvBW2lbUSlG+(1?$T+40jAqpz3mb+$5DdrON33omKj>=3ni z@t=edtV1_9vwA*M(lJlNMH5M9cS%pZgsj7HbFW7Cmo}s4xe?ylp6!Cw)5E^q-SPRe zp~KpUN7{c9e_v~txUrpfN5zap-d{ADB|Bo3?&UzNA8Kht`1tk|JhIlY3S+2Zn3Y;> z#Qa!TE1@4weiKAZx%&0jIip>5FK_Q|x`a>ksBj-;o}mn}4P%Puf&xh|{{^Tr>2|lz z9A{#`GZ|>-4ykEt>4{ul6$PIf*d_BU)(=Dgy9UCc7?;hpUaKB{0qyw9&|mfkV?rn1 z=w0Z1x(-^ER?g<$`-1CKBhX>*v3F_}#af}PJ%ejvXe8ArjPrvJ*#&|Z+ICA7r1^|b z7ZJkV-z;fa|DF7V!-w5ptq>gZbn50#VU->9dbnmDlJRFdp$GaFd#U<*!Rxmp>$|i2 ze7;^qv%0b-xCng%Z*FVy`+k?M_o)IA0zs@!K*(S!8M=d#p^eqA9GFzF%edA(Lx1?X z-=9J;|80b<+5uKpR!S6T5vOAryc5we6|5|kmHR8ruUY@iy^Q=`MJ@1i+62tlCs-;| zAsCoH=ix^MI?@e9dQpEU?wep65CteAL7(p7p=TuLQhsoGFd{Jzln-ojq*X*>mi2;q znS8lmvdWj}4YT)~gFv%fs#T!|#Usu(lBY64@pL$h1%zTfsd3CiIYn-0WUR5s<jMYs z{D*GJ(B>QbyuRu}*LCWF*%$S+GIos+mmm6xt*N>p3jSlwj&;areVc2`w#EVsi=r#r zVtdp5$g%q4gjWLRY4D3eLPGuVg?M3iS4eH)UEj=|lQ)+0{zld}7!9LR`H_y(g1(`l z5^(9|p1B8c1DE+khLb|qY7jrN6sB4)YZ6@ugcI`~Ssk!Rc9SX>X?Sm5%j8FW_JRXO z-)(J@O{g|mcf{<P*U0{WB7xIlMmKl@TEe*;4_#dK(786NscDM79J?-(8A8)Tdwz7+ zP&<Gt==>&}PVoj8#u}wm>I$x0{9LvJ%?k@FTt|n)=BlI)`(in<I=;>Zj8V*4fH8F< zFjA<kQ4-Idnv`07W(~j#lY$m#67Pasf6xs-WzbLk@`N3$lf2mm-oO?^hwY29Ikp{f z?O$lgMvy<3tWjP!*o>5I5rPllT~8QFY5)qqh(U1lA!;m%l6ozAnsa6T)7eBp8&P^c zS)_ux5X`d&I76YxJ8L3C<5`?x>q+rU_NuS?fqZ-l(g?L3x-3({JmOl*H;H_@dn&9S zF8w?zL<;o8Y(JPHxisoR0^;$4(#C>osOpHQM6SYdqWx}@I5-b+xD&C`&oM;ucQxB! zZ9o2YKU{iUeI>QPv9~+7BPBl(6%-cXTND%#8N_`$8+Wr4sg5M^Q~0-o<v`H|51Dxl zdX;nwdWIm*484ioPrNIkW<DJIor*3ueiUk{dvGy3Biq91V{B~Og?*1zEpGmZ)|Nfy zxLuHi+2GF0$paa+w)?t&Lg_%1H1dr_jx*V@o$95N!&F0PX|<`P>G$xWz)A0y)UPq` zk1ZV?t<8;D1CD&cy|_Oe-2a%mCq%(z3<b5l_7wEA4JC@_7}aVt=I6Mw*sNOODx@rh z_P2q2_Jzdb{HeEdJQB*waghQ^#oTf(^FCCxwSz{bvA<RPaOEL82eF{Vc7B^P-+ry~ z6m4l8Rb=uBYv^G}W^ZaWHWM1UKhiH!QVC2L;<2haFrs8oX4)E=X!2FZ&K{(=$`X5e zKAPLVCb?VcZO>M6Co=8c%V2&SH&&zG)3=JHHNU6?+!Q*Gu=(P(DRoq|%0RTxjyxA5 zwfu7<v3fZj?+#3Iq+3OWh4@m>&YWCY+nSp8&kmoC4wg8R-@Qf5YQrywhAv&32TInm zlzL9P>boQcc^|he$o#6jx&@$GjH-<$s%?j8{`Tf}%c$zTO~<o6&ux4o($o`WJ|xu~ z(Hxb#w>QxTD4zG;m(=kwIMHL80hIxxXRHOnv!lk-6~%f5G6K|yA#Q_RBO4m<_I~4J zfKX}KfKT5ykHb60kC8nCEJwvnS04(X6SgnQxHH$%;*ZUg@XV0mc%*muZu+TfF=l@X zb2T~XNyE=~rPYSDINTVj_to(j-6^DHfBc3D(s%mWbFqYUq>ZuMta#THjq8vD!NtTE z(~m+F$g$`4sl4S|oC>sgJmVmL+ojj5N*rsZ^_21|jS4ZF9En;*w7uUtPWtY<Tx!tA zyxgK-*k#Qzo|#+cF`6)~2twXFR|?9aFt*p^cy*eEwtxRJ81C7hpFMg@=P)y%1VG9I zKEm}i=Y4;z>|aFJdS~1<nQotKJJDW{rU7Y{=TzFqyq!^cXC!keRR;<(d^T)@(r(w) zAvW+hbadsgDBQ(f){G1!L~(Q`8sBZ0;K%iK0+CXx{>)RGD2Tu?7BAl*rNkrIn^TJi zTB_wLKg1}g)2CB^=7FH_G35z#Q#PP-W58?La3_c4PiqOpE(qN*`h$xD|7`#A$P?$s z*w85)O?RD=P2&K=KA|Z7z$y&>+GuJPR^?o}ArQcBH$`k!msCtano5o`Fxg<2-`m?b zE>U|h{BwPbl^#dg8pbRWg$2J2?ujeZUq@P|Cif-h{(i)7c3RVUz2hMQ^UqI;`+P2w zx=U*E^Ac$}b>=!M<SEddHJo~{=<a7FQEr%~!GEW+@)Kp<!@mLoBE&nncpxX$&aI*% zA}>$`_7fC=5gikA)l=szytrmcwMmk~QUTy?_~vF)Ob>EDo84R*Z(4hM^xL$GVtu1{ zzs%|Ah-#?i;9rgCVXh$a{1$_npt^l=5v#}}J8y24A|BOc5dt+~v~SQ=h<zAf5OHm8 zn+ZONxJG>5B2(qD|93h5POu<S_>=i^)j-Jg>FsTgiemD=tIJTr>f-d;+KO`FbHeGO zC>E^yU&MqV*XMvHb4s^u#CIO|C0D!ETEN=YES8z%p}uYt`5v#%0p?tP_P<&U{cqd2 zE4&T7C+Z+9bGgZBS!?TSKs*|ruE&`c1_nm)%br(%wy+3XOIv~@86b>;A~b51KB(`# z&J=-%=X~qBu3%_Enp|eFvF)ER;tTW*>f1h7&T7@|magg_bFr+_(jxZht{AcKejn}~ zwFcP!hLdbx1J8f{t=#=da9clq3W3zItbX*1I=PtvTRR#;T-}5Pt$MsXJ>7i&a&F2A z7;6aRj2#X^6CJod-@o^@5tIi0F=01Py=#BABM`0aRi`?%hyD4v_f^MdxRc!k*}%}C z$_5kTzJNY@w=D=0s%^Nrc`Sk^J5P3qLI6ol9c4TsW)!TsJI@^v$7<s8F$arVLKI`4 zq4<8T3Sj@S|KCFGuq66mhGkA8!Zi_*k|gUR?D;=@FNi@DwKXqErR32)py+SORl(`9 z_26wnOekYCh2xy<2b;o;5E%7~3`XC<_J^<Sc;?8*+@CHri!qX1jSa5qZ{06<AtsS_ z`>8LKJy`g?bOSV!=oiulb;GFXQHsXJ0O&V^FUndh*f+{~X<E!0Xx49tbTKTLgJ1le z8wPqU@%nHgm#0&u(tH68jJg(yWySaq;jc*YL+dA<oJfY=n}}K5#?$EI|MW|nfczo? zL%fmq7u%%IkNcINX{VJ?lDAg>0nVaD7}*+WVc7O?O+^iF1Bw8{768HL5Px?(sq>m? zGUJ?TVEJ9J?lv$ZeNI4f{DRLgDCQ>jblX~#Ef+b7A$x-sKulN=6=(7Eb|+S<$Q{sH zrBla*7#YTe8<Z*mwQVEd83&o2N1!<UZqRWd(p<Lvqko@tWy8o2Ie=(p-A72f(3T>X zW<g|3ApRomISjbs!pvoK_fIaY|B8nB88!U;hcIY5oB^Nog@?xa3C9zQ)Hn!BH;6|J zAJYi$rm0_UffiC^NDqKB5z?cXvfZ6AV@Qk#Ak8(x&+DKZr%cy9PaZh}JlU^yY1Nxx zmD}KckBKc>5|l77{o(19z(07z&@Gqw!)@QVk434|N`3M6%<6X|>o+s7{%}C)d&29` z!f#`iK+#g;hHOH@m(?GUtB+>w(p+$Lef>bm6>{PDp5o_jY5kz+cd1$nROV^DHXT)n zs0Cb;Q@HpVo19chcLwsc=m*lxJj`CGROw}8Dpp(U3$CtOd~}BCxs<gTuV>1996Rmz z@g8FkF^;<VNk*S488#4Z7BNiK(pKBlG4YlbbnMpbCw1|_cQ+;^0meiPVGkQ;zpv7J zJR0clu}33>Bp&!>(;iStch4NJ6!*sSFc<_CIleu8N(MIrPK53t5XjOoh`rTrugY#^ zbX$1yq0X-TdEiS(F}t8WiG(w0)8!G`+z&1)T$+}R9<#1s#=4V$bJ15Wkqz|0!7nyW zlixefR~>rS@yqI=G3?2R{PT3eO6W>(7eAkSD1$d0;e_}07GY^7$ZBbcieYAh(yCsr zww|DMx_ivKb-(wXpdd+TC}LYW3o>s>s^&Z^YZu*q>JjE-%hO^S03Zm{K<M#yw*6A% zl^k0d`j|PfRd7q%xu|cbZ+g9nNI_0Y-rvyc?&j1^18XLS65T@fh3S4JrpWYLwE}WR z8&Mz=m`Q7zeJiuxj;<Et4oPMNb~V5T==Ej`kY8tbYazHuzDpNhSgO=}9o2ng90Em@ z%J7gal5Wf|#fw1_71j303bACuvJq_pj(<)5GHEr(B)H<%uJj~U?K_Fbh*S^(CB!Qt z;-rD*e`v99qrb!8|Ke^i{Uf-{?Jkwjz(CW;<We`ks+o+n5$vyc-uEZS7Dd+QmriaS zw~>N>duDthCO8g}^7}S{Fb)?p8gzelJfuai{Gl6iAw!}W*lKl9hb9Tf*8kfmvzaxp z_ckjaoR9$%qltYZhG=Ky6$<qry`FpE+9oA6s>x5~>9BS-KZ9wd2%szTydI`_Sk8uR za{$`i!?l7dy7XY(sb>IGm<EK1O-X2I+M(cJV*hY6Tx$jp(+3}!Vx?Mb_&OliZ-zOj zl_PyfFS0v3u!h1I9B=7U6s!xr6DAWQ>8eJNwyp(<5#WASN}sOI<o;-cz=D>po195! z{4(>mkI9+_LAkY#Jy5BfBHaSv=|RlU8tMonRk1;YMs+Q2h>}2vo<EpLBH+G)=vfyw z6|5%<TE9r7xR6S95`x3nG#!DM3WooAc6O`}zb=aqP?Gh`Bn$EIc`b9O<QT{_jTxeD zXyyM&$*m*00rlch9kLWFr-Qf%wFSAAvm&_$hKnet@5|fThW<ORT@Fx?k&~IDbrh19 z27V@>+S;SaUgS#aHN!|19RGe&xWVt?GjU|}blUNWndI%r=&_c!wvlpkg!Y4_;9X~R zNXA4X&v}hrV+Uk$2`Xz2JKya-QI64$yi_a}gk=2F(+{MNUcGqP`>D+C-Ae1-A)H07 zME5NCFX6$-sWlR(@>eX?mhAi1AvkfOYhc;xt7D(rwj23GV7RQF^C}If#pbA4sN(_p z$`#Zmywyui)=M@-2Jv|!$sw@BFvZ(quCwRaP3%E<c=EEceLgdxA@B2mq)=q1@3i~u z??p#FW}@!8d0%mfWR9-ip4c?==1I{@FmBoiwqy_RLd<9#`sZ%5U!41*M0r26=ZGAC z67lc!6^V3t3YX~`X@Eyc8W>r)*Gs&I?!`?TY1}M#LuUCFs$q|fYhD}w8Y>Y>>{d7; z9WRAno3DJo&U(N;gghv9a7r1)7utMW8ybp1x-crciFzDcox435dxTfCfPCA(pci== zJ=*=tU^ta_(uWOl9IWZp`TZhUrR_T!*YM?vR3BRHTX@tY*m+R8Do0WI;#`Z}(bYS} zCCQhuZtM=lxpXwRySk40m9ftomJ!`A{;O7vPSF5;#v_T@SHhW!xYYjSj@9pqhG9Uz zyw<s=Fxz@BW@`AEBX_@p+Qy*G;>BILZ9Kab7APyCT6=0L+;4M84>f54J@a;w=!Mh4 zg+-Bm#e_%&QWL;>V}sY!IzPh6cJ6-d%0~%J?No8$G|sx93)+Sb6x2_&#=G8sycW=% z^fhrVDi9w5)GmRXGE4W#Yt1lrttrq{<w;V8G_{$OP2C*RuU0a5U@=)wBs9!%^V>Ph z68keZGSqKFb`I3^2KmFS1;nF70rs`%aS*y_BIu&q*e4Oj&_9l~LYCG=FUVuR-CJy! znppd{vWJ?6;<+6ZFV)03F{(WOta<#t4x<r}w8T`%dt6UT(F@pSht+2@_o9*~sz32< z5!x8Rfg`p~BahK3A=+ixVEc2*5I1E5<??0G4#}0r0Lv1NwUvSujn^Al+Q(qyl|b73 z*8a}5sKW5e8?<)R?wOo2lH4QJ4XgsOoY`#DD+H5eOaP&Na0YC-lO_CFAJ;9lT)#tK zqCPSke0LoRJs}X1@#>X;9V7tJG}mXtrLEJM+JPW<;>g>Ub$5bng4t*P%5)dHFqr90 z!rY+ICn*yZV}FrQ6wI%VPulpxk=2brSUA+j799h?^L!GXH^vQ~`bW*fbE&#t&qD0N z_3G}QAuUmfJ#B^W6vsltvS3$QI5PyrO0pV?hzhOj%VmvKtnPB~pq_73cQmyPX(j*r z*WrxX4o-N2F6AJ1|M$do2{>&}jLFP@ka)(Ws1P~CT4?#KUGV(Hiswuh2Il=nUP@f^ zTbHOYL5$Z{P4D`fp?<!DgXwiYhUqu65c{3WF6?fP>!{b8@!<ExT!&M;>f_M;sJKtQ zJh#5&6Ju>uBqX+HFOCjYyu1td)zvGDORLKnXQn;*1(rOS_b2>1zIvp1WuJMP9`Z~9 z;Lojb{aiKYza@C;?EEfGNrfIAPwm!LdKaqo)#?Xz9PQLv=c!{1CdbEj`*z78Y4SpQ z_Zu5nKy~AZ&nwoMgh38sOMAWRWA-guNDu7{vAx#nH$6Qsd)c2}pw6(PFnD6Y-%Coh z>;#-5Qc6P$0oszK#@?kzhb?=3wzTO_<>G5s@o~-GCZ^cE5qMnrO}wjSTc$u#Oqy#9 zD)PF&f@v=sh@uZ~_kNw!0zx}1dz2zW9ra_D9v?-TDE3JSSP!)o&m1{bS}zstb}pDm zFzeV<*kT6bTD{MuUk0x;c%e4I9dZoCaIf2^+sh$j+UoGeo<j3*OLnIN2{YWB&`+-J z1_;}mJ^oB=pAJEvsk~JesO*7PC;+lD%gR&xc9eq!!M;jg^vPM8G7a`wun#KS{e`y{ zpL==S0WGr^v~3N806coY``=C3DU1GaH%OH&fX*o7Ha)4z2)`;2^GWYY{2~56=!?>& zMA)aibPgoKE7}zH;l9EF>ZR{c@459%&pAx3?#(p3k;m?$(`--~y&?H=-m8B~dbF3s zJqsI#^(oxgfmnW+R0H`9j$|!{b>7eE#fl-|Snw^)&68eo9}F`<OYV#ii-ICYNKklF zqP1aQ&NHQ!{^MtKf<%;{eUT66UR$qjwsfe<GHWOS45o(X=YFdlKr{uUa^DhIyxEx= zCdQliWKxJ~FH91S;CzVsC+Xi{c`13;RYh2=WKv5pWdMy6lcu@#c@0j<G%FbAI=oO( zQ=`!Fjxw|=RYK#V-5uT}t4FJlR2&wZNz^yYIxudR=D=41vcdZEdNCj-@@E(mc{rZw z@11>MF+xdzM?LLAq{A}a#Z$K}WhJS*stK^zCdz`%H8+M*h?1r&{~1J?*P$@of{!Z` zL5>b~A)-dwjudC-*rg`pjiNCsnZ_ylAeIM3MkB%37v*x&^(~7kJ&Ar`l1UX>;)bg7 zGTM?eL)XY3E7V#u=#w^C?>?^}xtDmnv-CH$6(XFZ7w73AY$aV?Bn9eXPOiSxjYFF@ zP#8c=Q`+91kfoEY8AqB;wxzxPV+hCowa3TdhP=u6IHWROQorYp7f3AL+e*$WZZBrh zKmk*?6VsI}3|*Q-jpr|$9XnV@NB-UEXQ%EPk+pBp6Jof5-aC!$*`jv6n5^tVT7+5? zD%(_&|1wqR^jq(c75-Fzg?9bI_WgwHRNdsAoxjUxg&@i%JTw{0oV$s%w6-@ddNlG2 zrDkSBN3?C5xl7R#lC_nMCJ|k0CL{~qJNStbW>}4#HMfmvvQ3v~20~@Fkd(UWAC^5m zUxXWaNgqzM7tyv=tQv7R5d>3Gv@|h#ti>x?%z#Sg&;dG2X!S~{<5!&E?EZQot<;&} z3ywk3d5rv63NRK%qmZ4x{&<B|1N83s=Ogk_HQETt`{!Ul_v3LVVXxM|DfjUf7T@Rl z)yWu}f;9gQp<s2qMf3J8l7lXA4R3)QU!3r0MI|e%l~&4ven50|^!*)X)c~W4Gf`j< z`cYSmV1V!%8ztWHPm;2N0-9pNF}YX@ua))noD*dhD5Auw)~cweEJH`g!v1)yj|B6} z-*vkt)of=!_tsjnob>2z8!JRw-h8;PyFo|89QlJ_%XL}T$TK-Vxc*~f)%xn}6MeBw zg{Qe{7Lj*2G82O}V(~Pn5_g-Ke+rGh{H<MBpQL<hQ%%Ku#=Kc5$K10NrN>w-45)!b zGi3m_e;Np50MVinM~|Ih_xMBOpk-3%fhN+dgtUY`Pup3NIjU*#bt(N%M#)_1N<jNA z`?=x{pz&wCmHmCc#6~u2fv{l+icm$uS7$gYgjT-OK?sDv5LGtr@1}MHmL|%iduhlr zyKblyr*dRQAgU$qcL}WRR+M6MB}B=ECmQH>Ym3CsRnf?g*M=%)%O&$<%qr5|zjXWX z0L7iTbFVmzT5|Gq7GGZr=y&~LQCXA&`I*87dQ1cfUY6%DC5<roZD77rrB+7QlWfrG z`mYpD=w{G*Pu1A~;qYLOzQ9^j6W&#wtE0&XHF32g6;++Y_1Lbrz@(RS3j|c9CV?X& z*o-mJxhnQx5`VE<=et&CC(&=`a{$*`UmF3R{b_L|*<g>6!&9QA1~<KhGDwR2KU_;8 zIy1>n1+@B0NzJ!@W&6rc{R_EICTy}aS6prKgy7KJtNhAoJRwf`sTd`k6u~UjFtk@A zbu7Pg&<sRyfN_#|J{2HNG4ml^45-!(m?e<J+MZ-ZN2to4*LGt?o~8T|Pbf*6Aq++* zMIFpg%a^CoG($LeF8v^oEMCF@#41rQ9i}VDrjz8_Me^W{z<_fV(u1g>q3t`-c2nl= z3o<3G(zwzPewbN|u^0AxgBq6)GN3!e;9N~pM@P}$rn=8Pq4v<dV|UenNsR@Bh`2Hw z(zUimj@JI(-SJTFYV%O)w>#1M>PCLZb^RT9f?UVlkv3EBK|eFb?2dbhp7D%WAx27& zYSOjp8)@$?&nIHE14*@OYvMaSQBqaOR{jWa<>r}~#mW(jo}jCZYHjmtY-;-_$QM4g zzqe=JJdu5Q^kfOK^74ARf~>#dSA>OxAkG{HkB~qTj+f@_e8-4PGkm&u>Ya)_TAIF3 zbe{LiM)SK2jb<ksn}<)l?FjB95-J96yL5y4C#FZ6Y*aqZWb_#z8H|ruDX|!cg#v^q zsc)c~p0hnSksJd9gDj&~6C*E(du?q?kB7Q8g8Sn3cD<d?(r0Jtys#260(zYiWNQ~V zwU>-<Uhdb>!#EY-n!l%AnYy`h7Y5%1#+&4R?!wi(Uf5^9)ppD8>rI~!55+F&n;KOM z*gB)^C2GBV?BV-5w88jtbF;KLHFSGBcVbEIuKV$0s)3OKdx2{V{~pX&t=`kqQrqNv z6<>l}9|a46tgT%MiO{I$&Hq}D+fcyYTBUDFn9PrhmzTgFu1_aA{W;ao!Xg49K9?^& zF(O`<Ya<>}mS#|3u)XX2(i3fmL*}t}dweu@QA`8dCrw(Y(#|$!%iE;0LF%{1$isQM zdzNrQL`hxZ=FO5fgpZY7eWZOjK!?=On&~fmEEg0KFHDP}L>1Xv<EX)EbPuugZh~l* z_j-*fpdH~2BKD|X0TkLRe7Dd(K$F*Tj<_Q5cHw~`4<2fQ-xr`;1fmS*4hOW%B?0;f zh!T9HVu2y78{E$C8@uZkOB@;A#;_ba9d!~yMZi<8L&@qYNRu$}%Mts;D*Go~b>VmG z<7^C!OMd|L1L;p6Y-vP8+(XI=-n*BDN%^t^9dcS(Ib!X>^sACOQ!!)eS{50z6lUj- z!KV^)q~lRN{1ClCWPdnXe0eCqL?YC0kotx4yKfQzddyb$38zqFlvER5rQ}!z>icfQ zWmJe^_IPd@qA_LwHP=XsFD%TzIZ=EhH=<=r4ESa9385q)(UNLj`pl0_l6LerjdH6i z9MX3+y~#4WSTP2rQ<zB12pDFbJ=4iX*&XtVEt=qu#7f>Wr5Qg!fhQcts>qY5#zXo$ zWL7Wq+?I0shG37#a!#)#?oYuOpaI+<7r@1uc4!Tvc?0q((a8{o93p1lv}p-U9oXZ8 z0JJd6lo~phq{WyqEG{4VCrT$4N!D<3R)%s&Ez$%J#FnbS=CrdJHz`%BtV-l|pkPe7 z!D#{`@(lq@^(Rn+0%_mko}Ed_{+l9S475p7mSA(2_{aYXLGXNm8(KeHiI1vI4j(MK zKiSPi`9oi7w>}pcme@ohY82pAA;up^0zi<`%~63@YTS%(K+`^hKB4Q<*L{9^;(IeC zEBewS`m)t`=*oH))kcytR>>F4kP2VbRDGJ!M*7q5o#HKs;&EzyXLla`0_up06@}bI z&b}YN&%FcWH`kwN-Xk)W#(aF`QX?Dnjf^00yR4UW0PzupF8@!1rM1xdpON?7QW4a< zD{{B~dM27*H6i-GBJ4(PBlu5GL(@|s^;Ff}?;^-ZP+0i4M6lKZVWm-rrCFy6rTfAq zM{H%E^!;_%B<7_e=aejC9(i<7>r3Cm%IW}(+Y|>M|G~-Y{nB|6n~I=RPXzPX8ad>a zFYqiiZE+CpjJIL2NANoc7`zz7)NcQ6qla%^#ydED4DIE3A!p__g*C@ahVVujBlKr1 zET|khDEqDj>WN!5W6GqtTXaQ{|FFFBxHH$s`mVJuA}CmJSRJXOnKfdk<gCX~S%a7; zHOWrj;#?|r2~?;9y`3;M<zC3qdFsbNx96Z~=%rqL<VG6SLC6B3>Iy>%tIcC^+1SKU znGP};Qa+Z#YV=n7ej@s;=XX@3{q@F;W0gO2U&4{o!h9v|q@QNtsv%A{HPgcSO+l6| z^FaHw*JNnxYRF17R7-W7Rk%j`!nf4kkyQl4Cxv3x>IZm@sYCXK_x)-80f0DK`ARJ4 zw$IXj=H@JpjsX!xovO~<ec=TQAzT5uD*LYJ`!8p0l>#hx=SF@gdzCxUz8-C)LVaWM z+9n;w(~QI41cd4qx+sNvsO)P)N>W?g+QVtmbtw5-mjPu`%lRKtp9A11bs(*Ee!w|F zF~6@Iwn^Q)T@Th(7>g0}dw9(#H>f0pdPaJ;3pKy}^ZeaMzi#EThCn6n!m*8O{Z%~v zteR%U1Ko^5-^odWBH(86gv~libkG*Q9Q-Trr1dI%(sRjJj;U5T<CAh83G3Bf6E#yz zD&B_WG_CQ-H5SqHX`Llz<EZ-D0X?K^qk-xFZp$7};}LD=XNSZiv@J<=v)s{jyyIKV zLNBt|hWbtd!ta%Dett1}(QU5}aS=k5{pZ~IwAt-D(h{E5CWAj{4;g7BE*joO-f`Ya zY1ROLOVuT0q5p<%NcDkq-}%mjf9s=D+aUh%0(>Zp4UsRErAOR5O-rJL1(>h_d4zv* zgR_SUG<Ud?Y$;2K<_##aU_hEOg+<cvE>|c~=&-RH^vnoNV;mr0l8H&E4hw>;VRXq! zN~<nRj3bEo3EmD?pHcdjFqg45JfVV$6ihURhP07{Iwn<amPd%Uc0yYn7NHBu@EW?A zM9XEgXOGUqHiyo&+J$Gs>4y0Px{p8CF>O9u%1cFqkFTHwJZSYx%E0guFl_nzFPP^u zLRLH!;K3eC2m;b0@O&C?_PyoCv__XZACaG!P5;wZ7A&kuXOE3#ifo)1%Ejy0%K%}k z((gY~xus089pwvoMx0o3Zs!{#v)m0s)KI3olqMuTfpr#l|K>gt^>CfSiskZ88E%J^ z;UvU)U?b;!-&eMo_hqi*YJV}<1tXC6um^#rRyeKS-SWz`3mxc=5SMa|+n{&CEUd%+ zp`pR~(|Kt1($Deh$7ZDSbG|d`=ezMUI+Cr|*V^mrmgkU}eOBHEH*%i8XB0f=XYvio z-yl}R9Zq#b9o2aEocik9A;J6uE?Ln={P~!gAlCbS_Yd2_N-T77@qgXvW|L>g87Imn zvsO=EZggLM-0t~!Tcn{+?0pg1;cd6~BoY1UJ@6))t=85cxH@P=&~61szF1^`*3T-~ zSA23N0DF?Sm9FeIom+)QpRm_48T2Y#c?_DZ>58;RGqiI~BOHH3`f50_2SJproEYE! z9O?aqDA{8Qk!--2pT~iyBA9)?Pe-$zK!Bip8Ah3&>?Y}ei^4R^+d%j{JbZltnO?;b z=46Cpb9QGc!zCGOB*W8;mNTd&!2p9Oa(sN8Wqd*>Ko;@2Y;PoD#A8&CdW&u&txJe$ zi#qxlip(1tl5fSpSGCAdq0`9s#N6N)JEu2wzFJvcOIP|RdJ{$QbkGySw?m|7+RR2T zk6?`aom$N3=W;d?Fa_GC=fiKco<PfOtw|vw(_EaX#5F&f3@#9ugDorw`vM38Y_}<L z|1kn7$N+bb`)d*V;UzS^8N{b;xOK^Bu%u-FSYTZoZdT|QVhELuWBuNnJe1JT^xKR; z(ahKEveF2nG)`idar|SJCm-U`JRk|4rfi8@7;5^v><!@>u+Z&-Jf?JZ#_bJ*X)E0$ z2ilJFurj`%$KK!CvKlP0e#QI{xSOlUl-O6UvNY&l_xsVw#r4Do>Epy#ArlC%0|S&Z z`q)*(Zb5Pxz&akal4KkS7v92<&x;H)S>&>1@ZH4pQKkqG;S1GT*&Nl>c_wF!%fr0$ z6KnFDM$o37{GB3|3&+B7IF+k>3ACi82PtH_Mm_Mm-lGXK;KACN*Dd@mBJPpg40wel z27Q6pfe_V=3v?d8;2P_*Me|4l7}EeZfng{Fm-Zz`5#n;+NO6C98H4dPJ%<J;dm6?| zm`RN3$EG1eVhE=o3s!1b1rV1HcP)bTQfVLqvT`sjLr`c9%6|ws<~wA{Be_A`;fFpX zbQBbmG77~{h&C4C3yTjIDB`zTBT0j70rM)_9pZ_TA4Kx(!f#OP?ih=iNq~hjD3t*^ zDZ+19Vj4)!;ygj@k>;HucF`g2RC2?YbH0Qu=;U1wH0E3|tC%4OsZPOrow@sHot9_} zP0JJ|eMWd#4yg1xL9(@gP%Lpyib%1ys2GulhwT^`LA~(qPF#fdZ|oOW2)nE;ehm!` zejcv9YMwqm_6wmsecRA*7j%z)o1b`FbJE^ef9`lUiiwHly|RsBr@T~R5G5b=1l=>^ zSim^gkR>nL7#U_!ke<~>(2()oL%psmxe4?#q6;o}G$IvBjurd0#oxXiYx(ZB=>HaZ z*pNIpuH`*pAu{H<a;1MW%@~V3>7AgfW?fufUCdk&wX6QTvSKO9Z_zMn$R~2~(rMvH zV$?7RX@S_eY#(Q?Qb=MOz5kft^*6&L#YFts-w-E>14-4h48rB-x*KxWSFqx}thk+1 z78*2<-g!Iw8R1}ke*S{O*JAs3q)bP5GrN>ZL{P;*{Ota2>+3&C1lwx1Tr~6`oPvaX zbxXLPsJv~@J2MkY_%o4&7%sNu)z}EeN>F24{hjR>nnU6Sw4LS~JTOiQW99P27wbR7 zXjLq4&0cHx_<rDh+^L?u0JZL4Z{(&~LePQ#K(&iDK1ifj?<OOoXhJndSkR<9ZK0<J zh*5KWeLb{h__D!mD-eS|+MRQaEIYEdw|aVdJBRPb((2(ukCA|s{#VUlCv=o4sC?`c z+AfX2L~igvggmq6ba=mQJr334dXMv2PK;|uJ@9x8Zy5<r-nJE~`h%kMf*K-!+OYKz zS4MU?uzMrN{+3OMR``rMU#=R^<!|CzD!)XjB~4n(f$i$EmNfYrjFbOW%zXFLBzl%1 zbmXp_*d5LfvmBuC{GG(uzm0`RaQyIf=ZFRWYf{l0d4vUPB(j%DO#BF_d_u7M=&hn> zxD{z(h^qY3t(cEv?$-#^&)s6WA@|LqSoSeJMT&HBUYjyP-(WHKO@etf`z|uKNsP+? z#+gxXCAtLZ6?Q2yg`yFy$K~)+*1ySbgL>?*`~Ly{KmosZvcvhCvnQ8xx|7d5nIJbl zpf+I>Ic9cTAo<!h!2A305jfMB&&1?|rcE0ZbKCP?7#8_C6R1^YwGAcIvi4o!lZccF zo0^T8@Lz>enGVKi+}qV8<zNQLjwGW#LVGQh7){E?9<RJ>j1|M}Cig%B-V_GM2212f zfT4(q3W}wXOI1*~5|)8Yl$hnwgfSyb)v2~DflX9W<LC}_*H@H5QGprMo(koHIE_m$ zL)9V?=@dYv#F$c`3aX@<0wI7=h=I*?9YQ&@Hz*!Q8IggP&=iXZg(gioW;y(i0|=!V zc8hAYM5Pw!t`_v;*+WO6i*Wtu3!?$SEkmJlGuj+O)!3jUJtN?a-%)S$A7`NocpBOl zl__3i{Yd(E>K?&Che6r|kYFP;02+v=$EWuy;VMK=v#KG8Pe5j;!rJ`kgAd++|NZCB zpCi1zi?1gvZoG4aEIt4hd}216?@nWL1-NDq_VV(Q3&vi4<>9ygOTSZl@t6MMpMG}o z%pqXE$}WJ7A7>!q&F8bM6D#CwN!fDmPIf1I2k}s!)6-K<XqX)x9i5%MIX*t&wx1Y` zYQEFeeiM}|(@nfI8+~E>O^4F*>iT-N6;FRAEq!4Dvj+H!Y}*^L6V5k}C-GU+_|j1P z#Bh96kL?0_MrDhg{{)-xWkY+H8{^!-M7hzI__+oCQW*PTw!2UYjy*>_^=gCD?qqj6 ze%f_wg9={0e13Sae{iq|Jv`Vu*xTFRpR$|1ieI;xbG2c}xe(81@uj0Wh=Ojgdtpn% zjU<`lQ|P(tiSxV$AziFDCAibXhTv!CSKs^9_`EA-URKb$7_c0JW!Jc6thLYVV_3=4 zC|?)~&UZ574RAULh!9EF#90>~7ov^P)NhT7uWv<oB2=m%fhJ<o{2i=zbO+@Y>dl)s zY<=Uw-v|3lRjjl4_IZ2=;`roQe4Bl7OTd&l-TV9d3=xuC-tlQ?RI_XL!c6itHZ(~{ z_c<ytj$=6219B+QSQHfV=Io69@=iRJEhZFge4zjKmchr2ZfE)JR>26EAsN$kKs$yt zsO{-H0hcNXz!d*=fdo<I0!=zXQ@{HLSoCFQm_Tc<_gaVaZm`i5-4Hq5W1ubj-m#GJ zLcUV_G}1H37#0RJqdcKRVbLCC03uLMm(7gVFm@EAXq@hg)YTk-s2aZ|23cE_Q87)5 zoKwWRpt-H-9Z>azfyfxE(JT^UiRk1@^VP$NkVoq{ceA&IvK*k7SBl8Js?I=MF~Wsh zoJFC?dK-C={KM?(ibI$?ij$KQZXP%pb4Gph=G-9h+9BspZVp=g+ni~u%h(h+Ig?J9 zRF|LsgI~{gfa4ut{voJsQWjG@+NywFDK9F6Tmw)H$bzF{%;+;P0>TL0WfUbJGb>?= zOci;{n9EgEmU|T$R0C*P&<xnrz&i$;rf^EQH?=!)mCNr4L1}UyncfW*5Z}xhL7=5o zI7akm(Id>N7YJoQnE{*1f$<~IBBRu#fPfk(S0&_o2`DqrL<w^t!~oRzFccaH9Rc#e zjOYkcp%g-GmT?JfM%)pQ_h`~wpLoG!uty9eX&WF{;}WGMj-W|=%;+p&_A8^7Rx1?< zr3ia@55o#93)mZ0phW`1c=qxN+uEz3wrmDrrNyK;pxMIMB7@_fQi+g`koJ!;r7|Ff zV;PGz(xUZd^2(c0m$b|T^U`aP4BTZv30I-@H|Y{s2`+#z%DIE*5I8<OI6gU?Om}B< z?yIj2!dZeKc?h&`nB$(WCTz2}WZxD&$&)^1;|0%o46}dnU-;RK(C{DsM}K~QZ$Gw* z_wfV5@qO64Ir9)_i}-oo_|&lLos#3XQ78Prb9HfkbZ|g9n-5!ilf5@*Z}zAA@jg{- zqH$%1$!_%_V&t3WRJ*@_;HN;Tfz95*!2#Xz4Q)D-XOY;Z!sVm082O#8_{satd-Cq= zPUF{%ci4k(ZBDj#rtGq}cPHChY_q5F0&t9&Q$YBQ_~`QX?#+A_qPyFN_{HFOb2g0V z%N@)eecfeaP00AQ975c_`uvlN^Ve6GZ!Ry+&fmN~d;K|*&p-QgcV`ce=t^wqIqk&v zlNrpL+Zo$?GUu>I-p#EC{;sd%Q3zQ~AQT;#GA{(!FfW&v*O%Ax&pv;JoE;9vfcP|B z31gsc+%oWL+%g6Q6sp1jkoPXd!%z}gsGLOwg=c}qsIJ1g`0MI_R}4mYT{jC01O6RY z5(f$KSdF1&DRPg+?G_7lHjB4{nF(feZ+CKf`kd=C)0-c(kDpXxcbdPI&59y!hK_fG zcMcB@`I}59v-vze91yE6`pzsLA0MBdp2o)s;z!GFQO1;SZ{6MB=Jyd;A@O?7-v0jS zi|41$pL4KG_onQm<F%FimUw*f@Ai&dyW2a&wMS#R5>KcE20~up82$WeUr-nWy0C#M z`PU1xfI<8$B)~##qE*0Pz~o8w(S@1GFrk$Jq_c@u{%PnXnrH+<HEw`zo$D@BH58P5 zaW#W_);ol@qYg#&x7PyY3>}PA2^MO5AX(SnUQTc@$UDM1`DzfVac_x-ceDS(_!_)( z84C;?X|4=a@_LCJlqC%7yoQt!7M$U^o+=z*JpM6}i3$t)6f%OQ@EvKrNC(QG7?J!2 zHxTRtxN~3w{Osg(GMVIg_vY2B*KD2U@oIB?g^8n<Gcz|8anq7Zf(Vu;e1Q_Qu6oVh z*!Vg(z>A_=PsmynA*jSqt{rMM5b)XnT@Xr9DdFhyBn8j#4cr^ol`&wT>!7x>6Ae(O zASni9<n9Mp0H~Pd4pUGL3=7gWg4+@Mq9q`{^8~MB&lLJN0$#HLOzJu_BaFVqXaf|2 z7POl?(VG#i42mj|g78^r5khqb3ezgkYcoj$i(D<x62LoXU=RwIGN#uwVQ6BYu(FgK zW(*yrKzC^MdJN=+CK{osmoE}z5ya<smeCkSReCR>%vM5Q(L@WFwCNH^9M4{5d?jO` z>S>w5l(3)*Xx7nu6KQb|SE`;FK+6FI*jq4EMis*hQ)ZyFRR*Z#1T^b`kTU>O7ljq4 z<f4SD@YvHaSgvR-28NT&WV-X>8F$OixB##)u;DzuyBphDmUh$}o7J{0A$YtYy0tUe zi|5{9PZ0aXJ@nbx8T{|~9ZNrh^cVlaFKun^+|D_<(YxG&Zm<vEWTTs}K5-V>VE@P| zDkmx~9_&fE?0Dj047h=x&u<vy{k=odaS@8A>CWbaqW=Bqbbd2`{rZgi{&?4Gdz+j1 z^Ye3d7i`oc!44HOdX&aZf9z!^lRXZM7^GbD_nWbu*q!bnh#w$g%sBz?OxPZ?0cKlD zPpK(>q$<WC4A}h=mLBC$=YZ$qpd%O;{+oIJa#C!1<40}oZf<X8x3}}t)04x)c<=Y< zFy05=kKg}|&s^Q!kuSb|w8_5X{(*`~PnP_s6#<#<obmXLV*X;Ij0s%>$YX6~_euf} z7Am6dTwGq!Q^p4xqI_}>#xX-9Fu{#mMoi5rL~W};qQ)(w<h>(2%L$dm!^Ak}XYpw^ zqh+j%&-f5+jCJ<wFsM@+jQ@<VFnH7(;qKusS56dwNeugDT=c*9z3+bZ*=L&%_s==} zo}FM}&pDmMagrb=_KX9|8yA`gIW8C+Zq!h55XNzuFWF<jYE$JaL1f3?k;E7qcGKME zu{Pr>u)Te9eEjU$v*W|~36QhbXK~2+h{w%%iG*d(x@0HJA~IUhr-98%G<6q5`AXz) zHG`f34s1_B*?dJ1&eTwYGltMX{HP<Lb{#MnFbu2=$N&x1gfTS}$5cEWU+5_GZHg|Y zbPSdnRI?uBZCs)m6M0>nHS?7x$kotBRI`d#QgWH-+XBit;N+zPuQ5=i_hS};q;bpO zSk&@efv;5b8JFdX-xjP29c@<Ff~qoDhm5fTO})TMAt<@yQ#K{%bks{+%rJ4SUxn(( zm=X9kuFFzTl4y=(6d_vJ$cSt{a0|gwrz*;u#-j?k;>78cn+oE%T{jL48qT-)MV>@P z3UGNfm&P*CpZfz})9(Nu=FcD*R1u6&2oypo-BBn>QIVQvM*njN+KEXCHjD^Yj+)2; zD#(DT<^bk`!9W`_npdipzK|Et?8mVjnIR-VNy!xgg~p_KLLn?#sQv<7GE6%W7{?}X zKr|izZDh@DA!as-4`T$=Av6LM70@_M0;)1nSe6aGYPDAg4WABCN}}w03I+ub1TY97 zqc&&^Fca`immt0jD*L4YO{k8QOF7IK$a^&DVmzC)LurdqSP}qV(5p~ddfiK)@ML7E zpwcE{B{W+J%rZ=%i4p{XDz_uX6xvh=VM;iF1~N)|OSL^pE3;@?WDC-(%6<TAgXt;g z`=x{kfK|{70YV2^h6UF9at}<uX@#JDE;ndCekrW@i;vO9^J^$&+gDf#6`>OmV=daM z7y~(71C~USyXw8Y={G<6`1E;ffRS_Sd~$NazJvQ?w3N?|mvbO%oDDBEu=nC{*_p&y zksuxm1jkr9cnA1z{Ad43ym}gMYLOAsVCd`i4)b0YLJE$ava{o#+q*eO)tfhO_V*9D z^S`>f+MDjrXY-?@6YLfvO0+oA!R7V!o3nGaN-<tYAL3_M4-TfcH@6hdMw{aA<9BJ| zhkS{^ULby?hE2d`Y)^0RZ*be0#D`1cJ=_OIkg?+CpK{}q#~XL?n1=ZA-mM+nV;Gs6 zTqBV_{*8HJgA<$NcpsS!H*wkb&Y`gxjyI9x?}l#7uK9yO8_Dmt<~JLMN2lyr;`QeF zO`P82V>`3lRA-`iWR`oP8_M3<*~_tNXE`da1*XucVWMg7>`v}Cw$I+2$A%|g?86cU zFK7<_5Ok(-%UEllWsKp%7=r?I=_!cuPrxATJE*|`>*VX|TxY)yWk0ABMPruH4D!S3 z@xg}ti#2w47e~-G3p?I--Oew)6a4c}-aOpjgz?ta!QR2i@yX71eEM$x;E)x?Sm4d% z?{4qxO{V;@BKeEwvCL*@*`u;Gy|}z&j~Xv8`Pr_Un|KW+K204*yTize%7X(@3=T(A ztp1FT0bs##<UTt&aZ|lNnIa(~y<y!`za7T1=o46HQ1U(w^y&E>7>8mNFn&V&PH+Xn zK!uXQx+0xG+eE8?!GHnj*P5n~Ck3EsOn9c_>G;Bcg2m9Jot#ijGy?IP(K7NJ8^9N8 zkyYwCU^$@c-axGbyf6s96eK?>DPLwZL4GtRpcYuL{5oI{%>d0($ry22cqc3>8BoW0 zEPvPVE2pyWejon{e4&BBY^7z%IhXVjp#-#cLJ0?x%m9P&r&$txdkO~Q5D5~v(!>{@ zHRdw2*_(+lzK`#uV8AWV;X(Yw6jx!+!<<c{g7`(o_#l$t&IA|y#%qj3VZT^c7>M8h z3%{VjSH#-i0VYS2ro1l#sO@Rl2-c<G5)$DO$gyNBxFqCP(H_UWP?7;NwiKiwY-?l+ z^D=NY3pS}1W*nT7`YsDpI>M{%<3ItqIH_@&6ncg8GO&c=1uy_OBBZIo0G=o{#u7@8 zSSuwjWUzq6K;bh+bC-ekHiWWSpb0b+J@0t-5}_OrfyjUgopi$j4Fq{DM!7EV$YszH z)5?*QB~0IoaU}wIp@|YS3F(lKK}zh*$+?Cs+zn&MP&Y^O$_RLCs7e4u(q))PxhT&j zW-N*Fl?si=z@~A_^*a;<tkfAbpaJL&dU+32Kt_p{P*tMOl2%JVw$L}KVHz8DNC}wy z!eK!fpK1ak)OuJ%riq+;OH{Ya8dM3Cj@s#k@lt%ypMMaBspIo*8(<tm&;J8dK-K_Y z>2lY5FrB{l-iyP-Lz>)LLk|w(<IU&i=f}s#q-C!)nZzTe+6H)Q`_1|JE*BNn|K`SY zGG$3|N6vyhfAfa>@1OnF(nGNR+@Jl$xZ!@FYxismxMiQ+&0+61A8uyx@Sm-X?Km>o zTkgcq1rzx8?q+{~@71fbXV0FoL%+DVIDK|{eSJ+CsG+eJjh$v}q3Oux*7nW(ma7-( zphrhX4;%6Qj+@&#robh}nJ;HygR7z+Dy4V%CEoaKcAT%^I6!hvT@JyqUEJ7;?_|dF zz_xQw!$ibqky8@iC5~4>7})qjvPI2ofOA6<-#sBt4t}J_?+KFup>Kn;Kb@SNUmhJD z@9u1#U%Z)LUv2M_<M!h6Y=1iCxQ`1i{uDwfl+E5HR}^8BL7L3{=EeCXM+O=5E21;3 z@nbp6Z|^_->~n^Z-f=C1Qb}}g4XCwo%V6;|ZW);+&qd2L#%U~HtmN=ordCCHP;=22 z4mu_sehlM`5x(QR>+4yEir*Lc1bPG33DXky=JY5Zx4}B$YQyx!8sDO)58wR8N38SL zug|{okNzQwZ+!Ec-}w0B{R0k`SckEE^3@aO9b^7*qoR0?<o<4VIypK%p6=~!?XV_W zUJ9lLhLLnEdmI@Gnk2-LmBK<rKAXiWKCE7jxp?^}K55Sq-~90({|U}yRL!cx{(5$K za~o%gI4{M)7M+qlji(2yA57`GdF;nu*c57eIxzUs@R%(STnyHsB>`9LI$$thn3Pze zi55DJ;+QO;8BK&VNjj)!C8CZ6u*bI-8dl*L<koBe^Hxcq_4JFzS$ELdtJAjQUBnP9 zrm`Gms_AR2K+8ywXlLw16D3Nx6210mdnTuG?*e1?jH6f0V!p%%SjR#Qh)tP+%@|*3 zATV2LS#mEl10c6fc|n~~>KC3tmS;y8r>DdZ#R8Ej5jV)`jsb^H9k!wB%s@7`9`ci1 z`}_Ovy^M#Uz|3az%galyp<I39Gtjql<|xj9an*pv8Mp5p>0mr&BU5G}uLb<RpZ|G< zUlE(nPfv(DNF0h>yTuncaYM^q11N<mu|y<Ta<s!^@b<vPIDlqUkl-4l0esOyZ|@;N zoT@~?BVqJqkYH2C4-$BQoTfG~+5=SBmo~C4=LIkoxthjV*Dpdrl@tZ66&$(faz?|2 z?2adrvH`dolNFY)V$W)V00yQIHia7x7~M61aZH5q1@>r>q<Lec1}qrX6R|eR2?(wF zQ})<p?yc=0F5X@stTM_NtucK8MYIyLe!CBBqSf*CcAin=CW%70ZK~vH=zTvGvWz2? zQBh#wY#I~TBvx(%V#G*F(`q%-ktVzhRG_M=;B6LDHaHR!p5S0-`|;sw+7J^SmB!iw z7$ko0G(8?&lt9N|02p?B3CmnV3FSoKSgXPy06Fu+DCM@HQ6#swi~#k=iwjT&5}Gr) z`i7(G?+YVK#)q-R|Kwsw*=FqKc*m&Q8_LYS$G00WMdTo4y^q6AAXJaoh<^13A<J2B zDZ4>qqsL|qbDP32*gH51NzE<A-el*$_22w&>`!(N4h}qVVZ$9ZgTSsB9<S+MEFKR- zf^+=Bv#L`PQ;8$ve|;4%qyF#yt^Z?&Z}{K*FaKxP*H`%g;xwgZHji-;yk`UKsI#u= zKs?_n*TqBZR0BCGaVpDI9OnV{<eX+m?J-4dVYWD`FlH^Wbq6rN`8WS&BzSR)AMe7( zGnr$=s1`4RqJ?o}pu|LF5X$h`gwe-5QsC($ew@1iX3w8LBM1gGW18=8;)rDL9j}Kl z<J1!`AxD<nN^@N2It=91G}pw#&ffmX_5A*JHs9RYKHS^ip6s$&o8R4Ha?ji|KJ2XH zL0F6#YnRaq-`krF);^T}@9gYx(AlXlj5SO>@vAoM-M{nQPe1wW^{ZF$HDDyJNFvZ9 zYXC5~0~nXT!k!9k9w{}&PLg3{Y?mklj32x)a!rQI)@HofE+XQh24<m2Q?5|ZEP2mB zfd)nMcdk&;d>cxfpl^@p#wt*M;}$S(%psJzVxVAfk8xvxU0ubi65sshH-G4dzQOAH zp>KTr+y3i6eROodQlxj2z3KMmj*mNIvN+6GhRogN_0{$DoOFlB$45s;`-ky+zbsk| z5psBP<Z@^eP>>X_T%}~YfA#wHRs3%71qUWW#ddcmzIw2EH@}?|_iFaZr$6|+|KGp+ z%fI}0St-w-ot}MuhU@j^)tuFK|Bye1ooB5Wx^`Y-x8M2*^3@qY6SIQHEU1Yq2FUkR z7_+BO07n6jv7phU%W^8OX3xYSpD20X9AmX~y?w!Yq)(vg98jhkTFs)_(H4^?VDO<H z^$LrE!8nwA84QtUQEhrk7U&rFaYkAJ^NtappIC);_2e0E1?;b0J*C!hC?xjct7DSa z7mo{Lnr>ZxIUmYsEPVp&491-jUTenSDDI17`aG`dI5l8}<xGNQ?*c;G%~xMT^%tSA zS?lmEv2K0~My~jRCVio1Z%*hM!aSA6xfCH<c#4^9#w`t}#~=H#pP<Rvm}@24AN=44 z2=lFAZZh$v<1CWc*AR#JFi5dsG)RF9Jd_QBJX+4f|LOnxZ^C?aY#;2$*IMjYlO>!C z<r*j#N`w+>GJ-;Qz@V&~m~tF|yhZ>`lyIyEh$XYUaBV`d7sOFWJ@8DAjAo@`+@s<V z>covB&>k28DpSw~q3%d%BGeLSCI-zO_*U^1(Ch9124VF8Mq5izjv5rxqf|vL)u98# z3A@F>mZeOgmjk?@y<B%-VK6Hxmga?_FCG%808H_~I$@L-lv@DMI1jT2Wc)=Vp@Ot! z7`Ge|(6S#RSf0&_j|AT3Z4)z~8BkIT6xalgEzP1bYRj>}a!@jmbC&UBggZ?fDG8Vn z<AMF4SwLLI^b2?E0q~$3u|TFX)FbVB3G7bD`FEij!tpFL>1dtwNXb&BWMV_Bu@ajg z>=w`-#Ji)-v7sOT0T83Cq(U#ZYGmOA2$&0Ql%JnI`{0B3cXM|~Smqk}WN*S`IXk## z0nz>7w|BUAzQ4O+BfA@qjEarU{Cdv)F+3aR-!XUx_|N<aF2K0Qg3g-hW&Xh<K-lIk zDre#3yTs%I76WDR&f~X^*s;e)G^vWi&G=!LeZ}8l(Tj@^8oG=z$4bb(bI+bevTi&D zgM$_Z7kptDt8nL<O$GVOzVn;*Od@tL^P4;V;`vpa?RKYodq?{RM~8<8ZsQ66|7Y&c zVr5&l^Gs}Y*{y!}r@IZ$ZAeOjP=F1?YS~JvD$6!t_|1N+65FC|z&6|gE~5-L@Pl9c z=63^rFi=p5Qb}SfQZfZwh6KVa%PLaj<>hV8IlEnbc5C_j#~*X7$T@Saz4zT)s`}45 zV~-dyx`-JOGa_?lCgw3b`JWP9M+G^kT5s*fv;qq~9lhAxy4JS^GyUV(tj^>ls%cIh zG0xRgeV}wWqC@oXHZ2|v$CL5yXr$kdjYqby2*qnXPamN-PtGnb^z}w%TSFZcFocFi z(^tk)R7&2W>p^llVxSYHiV|I}%Nk{%$zW*TA45$j<v<ZNLbWC`Gfi0GmTu}P_qW8` zS*(Pwkg2x7xE56{>Ct=@;m^)bnQ)A12J;tRe9nIB=-$zv{?k9Yjn2kW6&y;LT=OX* z890nHd@$BDyaxJ7j=^ZiU}D@d&T&G|a80QsmU$TFLQHqoUcD}<3!n?5aRwhr@xRBY zI)Y>Q2Ooa;)vtc#!NZ5M`RwV_XD^?>9BgZ?n8d~o9X6HmghiQyz>}C-p}OM40yXot zu&bKB7O15@P(~G;BVZy>v|3Hc6WRj$)UHKePFNN0-Qa$+x0;gwT6v2}zE3~>yZBl# z25nN)yAbO`7k!2dpTe!8KfPZ6X=0|P|N4M`udxY)rfbnG2=9u%cJ(#4rBBg=oHZvU zNzJrc(Nx{~NoA1A2rW0gqbqvw8vWXNLLs9?xA)n2eK40tr$Ld;4lKGXaR>2|B2`?$ zlamun;`GbJ@tUBUCMG$R=qqlltiVWEX`u*x_OTAif8*!g(`SJFC0It01spZnSXR1h zo{Pw>2`KuVJ*>33X%;(lXl+qi1+|4+hjfmbz187rD5p?>W)V1TB&1|mj>J`IVxEqM zQmlaj`CATeC-6v|k1SWMxU{a#F@Y6*La}J9gWcAY{!DWyJQ)J~rw&43hT-Bl)(UMN zPz7uVvJ+f1s0H@GfJ;AsS}WHSP?Zu4Z40eUx^S(jQ6~>2b9x@Y<HXL>8-~EesJw;c zwKAY5kRwA5Q(s4@l`XM($Zz{6l>vF8Pm%~djS+HPC>mA+Hbfc5ycs~P`xZEQA~P(i zw@FeLlv3=EVff?l8~4I6()&XT4L3b1?0unhtf0S;sMz^)8U(@-h{ytRk^x<L;Z}i; z{Xi4;8ab>%QEFfbG{e<#<*4c8%sHSut?628QcP-P*D}h~@aPl%=vylB7oWY6M9)aO zyCQA%ry$<2AEt?CH``$nxVX3=tE0n%FMaay4wq(YgOeRw-m94&&G6(!EfUZNlKqkk z$t-3wU*8C%r-<WcROZ8>hSpF2wf|PcEcp9>??3kVse3@Jt;QRu74S!%D3GvU?4w9N z3|$uq<~ayZ(<7S!ie_whb#+Dl7S_>|0j?rLz`BGLQL@UlbQca`h=m+YiojOL0dit# z6=0&plddreNo}CR@o2(v<w|es=@P~<7ybC-jJ+s>1Ox1u6cJaCf~$RUgm0a}h3my+ zcXzS8nJ;v#9}LHwf=D(#XT8w*cO!a-Q#2`U+{~{xPEI%g>!+5YS;|wH1t=zyxE)Tb zwETG-CIw<juhul90E!jVlfZ?d5wOH4qGmUVq^1V7$rPS!L-ICwJB!=!tH@+pVD5-! zdSc{*Yt3nsam3}ixHxC{J$&%+(@#I$(a#~>><sio6;0QdJa1fYZEsypua@ydG-HEd z1=Xj@nXpqGfODur=^}hW0fUpn>SR)$@1QGT81ZPvz?Hs+*K)bPx5t>KjCgN<|KRYD zu}h|>uTD9NFZ8<9LK9z4Vr$Mb*7Ry&3=jUu$A35kj$Wg$f9{5@YTAcZEyV(Is-RYf zgp^V<sbPhhg4A!LM~+G1-VKgxZ#CtrWeAv>H)FU8bp4n~c?yl*_O6>RDEFc7d`DH` zR`I?LzzG}Pn)mv7KX9uPMcSV~L#%M`hJOErX(9Dt0OQ<6uOz?<rXUrvQDH~*?fk0S zn?PQ;z*?O<@s`&&plqU1d5`Ai49}v9oHhc46!ilW^ErzowNIWrv5?Kft5>gdLytF& z)0-J2w1OhkD=k8Atr6mf1k8i?b^zY14#1#@<3K_&+ezSPT{~$sO{t<)SiztS;E{y0 zHLz6|7>475BCQ5W3q&zfD}yYO4>|zP@Yy01BF)=y)B>vkTOqeTuBd`q0yS?YfuV&~ zPU`EIunw>SsPzH*PQ#L-9S5+~F%Ux2KSif!HD_)hu`(2W^HzhJL1?59z-N^iOA@XE z>ZyoM=C#~vAY0T$YN8NLFY}?UaxHK%<qm4z43KugZC7B6=MYL_S5}6H!iT2CMP93! zIz1S>1+^NmB!h;^O2U>T!dm+F3=mq)R=~Wp8=tHxEHs{amVjE>OrljxSRP@E69akX z1Jb;ke+{ca8~qiZHS7~_sceco>Q_J&$%JBo<>BP^0N^S#K`NL@6Czq49Ww|`YX;aG z2}Y?c=O72qG7ZCV=<@RN`1ts%pMLe|V3$xRP#X)07DgzVFvxw+a3I#CU2YXS>QZaM z>}<;?YJ~oYpZ@De62JDVziiJfYT(lz>LUNR2&h709ctYb-tNP@I2fv3NXRD_b}Nt) ztA`gHB-8@r@E8I@P>TeLAqQaK_S&2xw$viQ3L4E+TpL=BTX*T@#rb4B-q7zUZEx=A zfd?o`*Be{c99g&Yoz(iSX}wd)xYU;=0leYF{sH~rgrn7JxNFtKo9oed!U338ssYz} z-E*oBlw93xEHHI9P@z`eY|ZA&S0|^Oe>q>_E!~p2i%rB^;1z0NO?$v;S^sqP@dIN> zBXLuTwSr-}QAE+b6rEKKs%oZCn$=c(4LXj0Kx95G^c;X0NCQR?*AaSfa5$NaW3b)u zZ+r!s4z7d2P=klYb4A&Sk*l6K&_l}%A9{wXPk-VrR0M)(q{KL2rXY!ttVjM-9ba^p z2Vi|edZW+jbu`g?yl1ES5CP25;o;*)j}G?_(LX&sWe73N{cOnj`8fkj{-V3_2DWv0 z(e-i~rmju;wy16I_Ry-OXt=1hcdm4;kf7m~x6n2J!GNp6y%`+WRyEChx>cqva9wJ7 zONU}h($`+!zs$qbyqPxE<Z>6@*8$l1*eYoaDOG8w<Q;(*T;bLZ6)EPLnKg*@;muL3 zIw;j0ytY}zK0uLilJcZxXjI)@P1TwJsrK$5h-0--s+$aJ2?&)~;^H<9NC{f1LxCc6 zxIJKHJ3KsOEq(m>@x{djw|FQ^919(AThO#2@Kj=hq?>F!9PTI1(r1mI`T6(sGf4gx zXix+Jk|VI%*91mlqyz>{7*jXNa#tat@#ed*VIR^8wRCGq3*8Pv2t`6ax@Zp|FB=H! z+bUp*f!vhKfK|GJVoNc!RJ1%{O$<pabF)6eMA!-Nu4>VGhycq|*s6l=?(Px@c~+^B zRi{~QxYm4{7*3Ty234sHV}#-gN<{-C*p@<*VJNoKNMyeOY~6JT2_5w-K`j9_pPDtS zPuNm!E)5iYK%EVdNUymx>Da=QGalgGGaef#P=pDs+dww7f_XE5+R!a<J_h<OTFn`n zPioB&>(O_3<iHJ4t12sC-e?sQnAC2q=Az{wYKl+bVhdT73c(cHwFrybF=k39M5SP% zK^oF-U|}$20|AdKXrwG<%gtNCLP8{@8j!nHSiedEPJc-FpH&{K;fRr-Z?qauM&JD5 zZ~R;T)}MXx><d&`&Dj~Vy9LZp;8<K`1`l~sL=D@W_##AOb3<<qyA=RQ=K%bl;Ksal z5-8&{XAlZV7$j`U3F^`1=ZmN%x2vlw7=#{3Ii$DrY5B5-+Z(k=FtHy6YdRUkG2?cq zfHbkDK@nS`u=S^i4w>K|Ie|FpQglQcT6r`a(RK9YU@+R=8B#G{USC~JFQ>Dk<9ox= zWXJ^=js}CtV5p~3cTiK`>OjkI2t%cZTMsk6zgiABB&ojSb_YidBCg|NF}uE=)4rv? z&RXKdk|JlGAy@43YNpS8Hea|vwHsTUH%&HgWLLCk4@gh{boKEAV@Tr`D~mty_;Fpr zRe*%+Vj_igt@=ui-vS!N?*ody4&?y6<?CoQF*==YXoPcF8I$w}gZ=9AlA-Y8#S6wg zo2vc&1L&5%TrEDgrn#&C82ijgeRfxqU`HRT<|NACh-UzFgrM&?Hsh<ubwu6N(*UaD z@JtG{n8T_}eY=k#aej7Atli0Edq>YL!0Wr;wzt3Z$(Ij~4#$%T$K%m>yt%D!p9bX$ zLZS!5uc#jBk1Ey1#l=aEx3`6RwWfWjL!g;p{3JB&0!42fFsYd=_F47G)3Aj;c^~Y* zPR0~DOiGNbO{6^YtQC?Etrf$*cA@KkP)MDA<#<i%ZJ^P+4z2Vm^oI_U7By4D$#>;H z7#QnN2VzVn`nu?C55RAWyPM@a4QH5nB1zgsSOnr7;3B<qBv1uv<u^hsn|HttTW%== zy4{P987~6Va;F9`tYfT(WW@m(et&<T+dazM-2DWZR=VnOGbFgR6CA?3788UKr(Av4 zV)EV&!1cF416-Gy2;UOA2(rpTQ-tJ47i5-hSeUlqCanb~i6ZLPCkkrR8nyzYL6J-> zgvQm;<#Exr;iE`esD<#r$}ZZrmK#JgV+E9v02iSt#}Iiv4w3@P(Xl2xo$1k#I)-c6 zAR@=geGbq}<=P}`;gM$*668+Rv0$u;&^lpy+g{stCH7!ty9KFG3zGrnGqmGE)1hsx zX>Y)i8tJoW2r5}%R~Dg}K3&zw>4f6BmIG3<Ib%tir<kJby5La*Rs%N7{GlML49l|? zxc>o$z{-wjwWRJ4c2tBW8TVDof2#;u#e~~spSE%csxl(fRff!Z(5b~6u5O!I1LZn% zQ-{u?X&15)=;WfHLI8$hojkD6aAOUMrben&jQ_m_5^7n~<9#4~SpYaVIQYs}zVfAy zK6-Wfl8vqoW6e9g4(B5JTs0Usb8B<^;{24k8$(`~5={<QKBh9Mf9kKUJOceIfB$c( z$<zgkG@6jt5jp&AF-8<Z+;Tj?Cz<$NYvfLkTAy!mwJe`{ReH$LK_4JNIid-Uf*eD5 zBz9#rq97+CJ>x1Q00xPt54BX`0jkc7b-RYzpr@y%oH_`MfL!7;zdG0shyD%=y<|XT z3^6@|suM3~muu478gVKf?r=QeM2y4G7f>~r>+?AY`yfMkNhLA3veT<`Jq&)M-+I*t z1-7@R7xUB8v(xhnPE)kSerPY0oZLAr{~+Zp+JiXstkcI2j3JEzE^i5;!s-;L5q1K~ z*%dWY^cu~E*Kbgne={(!OEPbYPO3)c&_X!?H<h8Lh_l&rcXyAAKAX+shc_+|PA21L zPe1?si_cEaF1UoOnel7|>*j!NqwyrWT<ABpIE3O1$(DXhyDZ%xIzz#@#1?YJ8P~q< zbllZ+#u*hu4OcJ4krk29xrp~YM*4`ciexq#4IkWp@ZpCa9v>f5b#``!kiqW}<yi5t z3^|Fj_YKR0V#Q@jIDxl?{nxY)ty+o(aosbeq5&yc!NpYQY8riVwfAk15#JDwYpa?j zD5j+5>x2=~4_Rd<ivYeZ8Wy&I*q&<&N_7W%RpxE*9uL64RyB2^Vpg$M_yfSB3MT#) zJksbW7h6ElhX0z-*R0IP>7@{uw=k<<>e`$>tphNyP72ecC4WOy+lLjTTll1jP*Kyo z#F@dwvw-C*i#JPcMOf~*%Ug&t9xg5}xZ|_Rc>%Fo7;G)U4+?&;5jBT^Iz;k6`wKsB z+jqqF{{9|*;Y@+k$|6Wf4Yvoz)I~G_`GK^8c47T4(qV1bDz<<tfI>~_JF1+FGYKti z^{fCgLx7rmHAB#R%FTdQqhOLZEWrtv%2&%03=>wP7MgjsC{@^|xg};m>R19rlM&-= zZD=(sm^Twf0urN?!-;k5!A(GJs}?nqw=4G&a1~CV)-g2$93q(<>qx9-_+VL27-t1< z&7_H1XcOR2Fu36l1}6lhp14%OSXnM)SQsR$a*ZFKIbkR|G4|+CU_B@{l6%AC{(%di z5J7KYp&2WpU>%ClpG1MG<iBgZCveSPF0^EqwdVPYL`qdk>SF#ySI8;8>bPbAX7DwT zbkSdh2juNPqQ&1WP=$J4WHFecA58RTbaq_FB2@M2C<-+t548{qu!vG=K78GcmbhqU zdqZEN(|k1Vh8nh`Sa4Wkj|;PyO~<3*#~*$8$;Tf}c1NfV$6ETA`Wz`+@u}WdT+a9Q z_6dVrcZ-d!o25Rny1m5#OzkB*lJ#HH8YR&>0RQH%|6Lr=PPHU15Zz@=CKHNWI6`=o zT46COM^LJubuXn35+8u2uZMw48vMnO&>uH1ggEge!qBel9MnSS!NCFRl27s!G4uT| zKEyjlmlHTb?vz--#OXze;fhHge}GPmB|zUYM2JngZ^SufJf6=N*EgH=BDLfk7MdB% z3-aIyi{|#ukk}N+Nkc}@sOsB~;Qhx1;b^Sv8FiaWPJ7Jkjhp%Mn)B2J6P*zO$GMof zb$)j7^!aoBj6<A%XcSF`fs(lyJOY>mu057owC4{O`ahhkP;wL(u#!=qPfK;6h#C}W z1Cnpi%)dqBDd8CVZ}dlpVDuJnlrDPZJqKX^jn{(pVPGzYris22Yv<MJt5+u{XJ;2o z#TX)G8D}hFi}8FppH6jXW`-~};sqc(EImWdW9I$=4CCok9|C7|GFHwnE*W}g5{p?! zU=|q09OEAy4#4Q+a;BdYz8(yRoVPia?;q@sCu5d0|Ag2U=l1CprYr~=u>5UrGC66h z4&-=`Oq_s0R)u>T*hx+MKy50R2X(=0q$XI>f|G<Mle7=I3hS`eKj@S9!O=7Sq<!)( z-b5e1E&@xsSo``C&KXEWV-=c@Zw1mIku`to<qYX!*n;%YP(zY}`qGoOVY!9x2s_lR zD?ni9Cw?8GRc`_H={l6^4*F`GPfUfCxsZ8UxYo1c-C|9@;e?7(2q3ZNx9#V<^9K&p z3a7kcvTJ<{pl=C)$z-k<dH{#j^62OY36v_<+vm@pvtVj5j0v8G0J$Y-q5yR*D=HLy zbi7xAe{ToigZ(}J!Kuq2+hE>Bpd6b{q1JqYA`M`#1Kd2@w$u{#zZRIJRhQ`kR|Yyz zBrq2j7uq+)yX|#8wVEZ?XN!i8g)j*#fL77@K+PmjK%yIO+y&w7&{YP!(hc~kcfnYp zwiF_e_3g?~>;|+E;2b{V;@nOgv^KG@mZJ&9KMct`e|U5dhEZv<O^o!Pa4*?g4b+lm ztr;l&52e)vtsSy6hT@a9z@UQyfJe>1gK5HYkZQy+gTz8y0r)g=RU<DBEr+^DCzB*Q zZ~BL<D7weOM6epLVci@U;40)WScUE_tO;YEFm5|OY!0krSRvtBC~{LXiB>VefF+7O zWLyAahXzI0f+AW)OJ3RDI;mk-0JlXHpkoojxYi8RYR=6?dJ>v(P@@Q3w3-o~3NV7! za!jD;LsMu5s!x{Q!ab}iE)GMKi%A+!o;>-}fBH{<`st@fM~CO<XW=jYkMDfi<7}sI z#L){n2pK=z!<$jPJsNUmW^}QHvL|OmZH~w6<R?rf0<|82{zt#{4`OF8=a>W1#uZ@0 z4UdF;7^p-+AIa?M%CQ{U!xDKUUxuhnP>`dh+w3j<6O^JQu0p3(#1A33{{ilN900f} zAi+5b@~w-aZlUVr<b=8J9AHqWZz2d$qxSysJ-kswu3FXW4LeTJ)YB7CI%-S5za>IH zM;1_m7B?h7@VF@YBZuZs55RH;;i!J2a|l^1rnAe7ixV0bzrb-ln{r5@a^v*${MplI zT(i~zn0_Nq=L`>E5_o`GSkqoaWmlifU<_$AxSeOAY4~ClX`obefTpP%V$G!BZ8zL& zH}rQP1GUgA?>PX&(&RIJr~1v&(eY$=%ue9t%U7H>r||$D;|8FohX+7>NSJ}ad6glK z3kJ<-IJmr=a$b$0C*YHwVdyeMBZ{Bczwpa9)aiwx82O%b<m25s5m7!oI5<8&hB-Yw zMOojBy0=d~BN=7ptPbthDxSyZg!6KU(m0O9I|IK97QqWz7x&F!KQ-+GITS9S4Avo1 z7OZ1s!%4196=6#`(bu#-{XTgg?B7;3Z53O>R#pg8vQ{6O62p=%JYVdsri`efu?ohV z4Bi4OX(Vt}xHeW=+J)2T@}TY|4~cgNvrH4ML6P?32RHy1?#<ArPLjBy)qNde`Py29 zps`&apzhDw?c4TqU;cG6NfXL1GGtgn0m~pfix|A`>?p7X`T)#=_UO?g3?Dy!j3)BW zKmT0oZ?kQ-A1HCt)?;4l@MwfjJI`7u=I`qOy!qtu!@{n@zboh_xl;%XCAp|?chK^> z{9Z1gh?T)D2J>`fpg^m_PM{W{DQ&hStIUAxXo8|?hovquadZHGetwQ^ZH^GogBC&^ zG<ghtJy6S9cq_E1Lt8m@fUi2YNrYsZmljPcplK6>YnhVT8&05I;LwQyG@UTuPHY96 zn*tv!4T@M{4(JCftOaUNrP9DH0yd}Cp=o2}Qs62Whch)?m1#ij5DAoifJ(3FN%W!g zXI-=oG~0!ckpOkk;|C!02(g?kO4=p^byi&r2AX?h1$A7v*LfPKQB@FDC?Jo3<x-Mo zQCRI#s*$)+u5vBBY8wxhBV6huh=Pj=)U4A&j&mb<^x^Bcjn5JbSYp&V3g0k{PddbX zf&_=r-{l1t>(mU(8af6=)QrAy?(__b3LJhgiTW<e`~noL4_pLUWu7(Gd<&_AZOv?6 zZ(ei$xz=pm+V;LgwZq{KLxPj+;o;#|zxw5`eeG-PbUA>1@x^ERNBeATN%-nY->0O{ z2kOnlvVIbXmMEtffRhPlUG*W})JHe^ogq#g?3KCr|Kb1k{~SgI|I7c`&!fg_<y90O zLwBs#9QTsj;-Ws`8b$rnfFef)hKluJSg!G-YzJe8u0OG3pD4hizrVlF>Plkt3`J_6 zJ$v?*uY4JY{+0_Q)Z!CA=wJn6bll!e$Q=f^05t-^&<TtO%mJG4P#4jmr|^avp0PDg z&yzNuFE1}~%Rz!ZUe4xZyrF}M$9b8;C_I1ud^};1(Co&<;aFrYPA)Ozv@xGwUS6Hf z7gt-`S|mB-vH&a>oao>;&(CHrU!1)>yI9bpF#zzae=24z7>R}Jfz8tinVV_BR|>V% zH?z_C86?B4He<L*CqmP_W}sH9Y5Xp6FKXLDb*)OQL~#{>cUxjyXqOWzZwkA%!-|$9 z;TwcpzYjb<J3ApRBa=bSIQjBdzrt+&@WT&3{`lj2_wHR>>C4toW;UIkU+f(mk{%a< z5d!1ekZ*!y%hh4*jfNUYFpPvj{FWH4V9Y?_x8ubxk1>X~m@B;!ggLGT+nRJT+0@<+ zg|pLBbbjO4e*L@O{qFNGo>Ds*k5OJsXN<woc=y%WDNQ4DDDw{I%*2=%?e!d}7uLZ# zUD(96H6=r67wf&;;lKPVbagW4WB_W3taa6!1C!z+U<uS?&yt$<wU-{o#NK=b;gR&s z)4uV{=z=<jnmT$Hj%c`O%%->d#+vENXAwU{p2|sa+bWux>B4GVre%n*R!AOLhh8k@ zRrtDe!D4R)%cP+8T*J$4swI<1Lo;0kgM7MGNc!^R`r2W-HTuQ_RcKn-u)dy8dK-8N zW%OdpA_LXhva{oTGQ1OJczF5p?+j<?WH5ww!F|?M_+g1-Jp{PL6><X)4g~gwyR2qt zasYnt-~pKs7xQm_``e^s-m4-y?42$y&g?|NB8pS8TZ(v2=Scpa|NNg@^Btkz0e0XP zvR#pe;MkU6S<^r{fm9NKqWdU|z<yjzYKBIdZ@~+Pt#AnFL;!=N4vjEZ8B3s6Ff43= zD+E%3Ky`*)xE7#L>yW?GgSR)B+ME5SiFs?9F-1RW+Q2{5wh5FS5x6#W(oYtl6z!)A z>qk1Jqwq|Z!XU8+JF$)>&_uW?IV4;K;M0TQTB2B3D+7;*mcDhUsuQr>65zC{YJ|mu z)yzO^&ovlX8eRc(YBhTRr5vE>&@Fjh7bEP1R8Am)G6>x+c!IhW0D<*QGapO3sO5F? zj@xRE{|&m{p@q<_B{3K6kRrfsDzunr%I!J;W4PEwt*kH+$gz4*!WlM6Sh7lcLmSpi zW_P$3mxe#RTd21iiz}Unxf!s-=IDEP7~ik6y?L|6r7Tk{?nLoT#cX_c%I}Sb$UA1e z0X3WHjb9q=fHt8@k0IY|{KQZHyOB%5Z~f-qM@bsZ3xY1<2W@zCU|0q{cmNr@KTUzv z7;L_irD2?V^)oQspL{DtXm1n=K?C6lhY)3o7{XBNg%^h$Wl?}<r%rS<-DDj-M|ybK zCjlDlpw!wkLU>06t_97#Pd7pfP2-Jlb*w|fW2)~H;?OW(F6Qop7<^0Ji5@<D1iie} zd(Ov4_Yd~>7xTr77ccjB_dWBNTlmle<~zQf6K-p<xSn1uF3ztm&M)UPy*rLel2c}H zhPTlbXi?!-L91I;rHj@*G6%8)VayjALZcgNMbjQ$cYtrf@6fIV;Q($8M~89k8^YSQ zswjWOTMfxKy*Fi;4Jk5~^$dKx_{1?1EEmi3voppD<8XJf`|8z8Okz$kXoutR#B)TW zty%Gwi}F1GjUL(9$~WbRD5b~>HRk{rOgJ>W{2=82t!NEAMhE)`M@L8dyE>&K)dbws zgjy`Ghhu#wydyG+;Hj0DKz1p->06;Ttf?FO?zkhNzR)coTr0mDT@y?CT=lh=4u^6z zp|LDTjSB&<wAMjp9oU0wYublaEk%R16KY9KJ)64VZfYG+n;7s}?DJrxT8oi=B}ufZ z5(q5sqG+r_vt%85^~=A#NW(r4cR*S8STQRZ5}M(`B<|?dwcg%7DGgmfAOjw^_4<QO zsZ%mV(xp8p`J+>s6tf`5GjK#8$&Fq~WG&@z3s}LZ#pKniSIioKjx%ZcDqan&fGt4H zf$SOB@MnJhJv{==0l2WM&~M|#H6ym+@CcnmO~vR*odQb$JRPJ~HkTiXz0n1BRl`xN z*+Q-CB1pM?QY0Mx4(LHE8&&}Da<>YE^tEfPkp2@crqGP_frS7*tLktbh>^l=PXexP z%7LpuJ#cHFZ-)u{F^@t`6BJX8Vk=e+bX@DiNW<gRMPOG@tJT-n3II8hQfPW0k@__V zQMe|5Gr-DeVj=ke0$BlA4y;UK&aDyZkJMUB{pUvbk9@*wX%~SUP8n3UNva%zTBzZw zG_O%KVlz}k0UQG4@TNvOX)0YSNyrsi(lxND5c=g0{aRvk_l9BPL<+OY3{GI&58<%T zmRd60u!B_~|Dn$HS$iS)vp#<)@W<N772wZ7x_^$Izzo2&dbOfzK71cSF&VPVdl>&J z_uy&QV*g<8$&)7^eDLJq!v}{)`#S?^?(Xdodr1Sgw)K@eqY-WxR99CQv)ObxpUr2} zI56tDTaIcoJ^2hcaF&JFsXAQi0Q}p(`K!z8g)~A31sGb&AS4h=8LOW!4G1mrZ`u?3 zX3`3V$zlmfaG0IwTbDVh^6%c>-u`5=I~?jud@w~w*4&}EMriKu9}I`wsB|a8n}IjK zuM3ZV0OKh5r`4Q8m|^%KCKuP27@yPW47a}emPD-%z;Pm_Q8d=K8+LU%uHcpy;g(ev zA$)vKFQ*a~0X3CBbnpk|tV>Uf$9sd}fR3NeXEz(0yOX_`kJ81N+QBk=<C_;j$zgcC z+~SIH>F~e3Gvwkak2gl>mTvEXYfU|#*H4Y^pDu3?)bLftSSfU1<(fu6#)scm|Kgw< ze2eygb{V+!kg)%^g>7tG)2M-Mb)7~6BZRRO1Mm9s@^X5mZ-@Tk^Dj914)hhxgUMK5 z*3K2Uyt=w~|Nd}1Sj^|==Vw<}dbog18WW503&XG^hQ5TMd1Ys==i@ctF!ze%e5}Cu z*KTg4FKvSk^#H<xg)Kg1A6Gm+@w+qFdGh4({Rj8&-M_cHw~O`F^lH9fP1rcUy5dNT z;u)v(#lo*Tot~bWk%tB@Lf3+Ptkwca7OsL#O5q(*#kJc+3X|4MLaJ|{%vwK5yXceC zKXf}V&jqC?8Btt%OxD7NE#xxWqJ3!9QZyKADM@+<viH~OQ*254kZLVP_7#($m&}Cj zEt;v{Myc+gZ;9(O>2=f~4etmFdj0py*TUC*Ev!%q4f>L@au-<z<2mjkam~m$Ky6%< z(x0xX6?$+x-r{~PFcIRms~M57|LqO!0a)|cJ;Y;KdZY_w{|u7n5w2_kPo)h3MKhRS zXdRRd8@{&#aQ+NZ3rsMm8|m<9J2~?;6%z+w^G0pb1znIHK(^4eU1X0NHmRBDF?E?E z(s4EnuPd<7wFxBlVAMjGE;ZyXP|B6(mYl0jF`IxBQU&l<NVhPqb@6Uwl$uEj?B70N zkRy?5m0JxZ*IaIA=w!&;R<$2MyDYIV<p^EODl-XNSq(}EieXXUqICd_;o6)SNSvgr zLgls(q1Hz;YmHVB&7>fVWJSY?mGE^;SQ((_V*1JGQC|>70z9>bs{rzO^G#+T+NT6^ zb7I39U5Qa#SI&((w2KDO3RgKq$HiJ`xGLr0uQ;@%#aO>-P8pL~+XeC(mOyQ_7Rn${ z%8ip!Xb_UuPp&i!X7i?ezMdi-#pPxMvb<}RXV3cSr(gZ@m%sGz(S3H%m~as}HtPM& znBeTK)#S)c`(XCb>IR?}iFI1t(W_dFP}H=LDhTQdivm%9{HOk%$fe*P{^ozm4nEwM z*Qa2Rqp6%?s1pmJlLpNQYQt|LSy{=H^W?^re&a_sDimf7tc(uKaL7S|^ZXTeI2wf9 zf$WMZY@zscm7^%v!2bS`JtNEnkUJs_CWHXt0mB7-jwV$oyIY(y6i|hl1I1~AKaI4Q zzG$hJxnyT&oEh|!R9r)!f~exyGo4-Ob%@3MT1UDqb^vifj=l}c`Qmc6xVo5cYz+t7 zqvg%!)#dE`@@hH1x!%~McL)|i-vlMSpet~~U2twH+?~MOxaC$+^g6gZbsN^SZ`SpN zKyJ9`t8Bo#$khQbsMQK@0{gZ9nkFb#5)Bn1a8_ktFkKj9G13;VUY)#r`QrKW7nF{V zk00E>kLB6<`TpVl=9Yf@iiyAx6h}D2$Hj#nlV%{1c}%Zz0KS^(+pr>v8j{hGguWIF zk7qMXQ4CR*N%(QD$T`y<9~~VW9ALwgn1b1Kb4v#;LI8WSElk)IIB3muK~*1In>ty1 zcc_7ltJ<f+1WLKVT1i*<TCDYxw2MAD7lGa`g=Rc^aeFJ+u+E_`qS30QXmDOIQz~8u zzs_R)q#*MFFt0_bwV0g9Au9~j*WJY$agSO9=hH>s9SoDgtzx~jLK^mYXu)bwqc2ZZ z6~+lb!HnlDCPkwIJ1m6;ed>4n$*gL%ny(bf1#t28Xr2JVgkf)R(cLr{1D+6I9KX(h z#48>Qn%wT$FwjNrC4@LZ4W8xKhK>Rgou>n^gW8(`|2KZ_J^c*QL3|5z7X-~<=s6*1 zQ(L;#G#F8}ph1W=F~Xv#mAU}JIz;NM1!{$>fC-%o#hd#JA$>}(wY*U@%v+d1!X@Df zxs3p!b3<qy3r!Q@QYhsBMccxoZw35V=%Qi-tdmS8fWDcvP?)N3frT(NO{7UF2P|oU z-h)P83h6dug_aPlDgEOrkZRbPF>GQ`#BEYbOcRa^Z84=fCLuJdfaTUnIlS`(mahex zEo#VPAkAqPlw#CNp+u?fg-8;qX~<U~dbgm|1u!WZfg<hPy#ShZu?72qNt&=>Ryjk~ zA{Rk2pxbY)xD;Csjg~hku8daIS}=uE(;)zT)n`I&Qp1|59}Y?_p8Rjn6{P+uvpL++ z@1{gX6mRG)R`$_IFK~YJ(TDsUA0G`zT8rpl-K;s7aS6h}@ACle7_<SV+!Z<LY1v`z znUBUphR~KC1kzU=(|R_!?gPU8*iWt;fPd{*e_3Zy2MZvKlD<?~?i%<`g91lx+XCww zC}cmwc>1#tqQMoz76m}ESfPebbddN%%bX$OJ*W+sRI{tmNI%|ta&ls!ozrRPQ$=3f z3%Mgk)@3@_5DHKR6p^coX47~)d4sl*D_yfqdMv8Qme<Hp)i1c}>#Wp&Tw8AOYMH1) z)3Fr4^rbHm&R>zZzrWAr!#_!G?`-LNcv;QD0RxZ>XLD}S!=1sHOLumD_5AtC$>}+r zN@M6&y2Giy0oIH(gJcS~3Oc)R?;BhT(2c9h5W~rQi!z3wUAVT3yp9Qb<}yV5+f}Zv zeRJ5%<~2>Ic(c{K9Zfj$A%wG{iUFhN?ih_17w1o(K7IM}6~l~?xwpH=xOnmWDKlm~ z8uH(WE!@t4VK}|gGw_U$;a~{8UR*CVeML0K0^z@aBJ%}?WEhh%2nG1zc*LMYn>|O| z^<znh>Baygjqzl%ySE3?o5uP~!LH|*-%;^o@#t+e9CRhGg|8QewQZ~TPH1{2eI~OO z-Kx9w`>@te(l-Z}QWs@B=JNSM&||D-S~1q4&%Z}Vox|Okv}!3D&Exhfz&TZ=&_cXK zrhivy=3~igk!mf*)ZPpvz$t+uZ4mdhHK;w*i21t)UC+jPX@xZG^I)|4Cuv`v%y(Bo z4NdOOKCnjkZs*XK6n?DV0#!t@P7$q3QVF?5{U1?TkDdcCt%Dj=SqJQm^~Nef);eYl zfJc6Ic7_Qv$P1T+;iTNAwe<<O*1d<0B@PPy{h$3=g?VSZ<^Wu@RuQ!;G~m81*Sp9< zq0%WA35pQ^rdegVi!H?6L7t(8dA}4&Er7wBJJAZD*f(&{QmByrZGxILkyEs=rUnW| zDMu}a<X~ZXv)sz*q2^)Co5^Haurh}B26b^QZ55$r?8gpUaH_xwpoS!)0N27;j+*80 zP}B_Tq$C;C>LLg&A^gdSLm1XEZ#BbmKmty+R5YN<Laqg{vgHP~(3H3cHG|KV5D9}p zt}9Sm!<wZK&fVUGtpL7K8H&UT-X~>0I4GMeH^FMI3ia0j%|zX|-CFvI|1CGHW-CiT z+P)TPWd=XBD;UH5+(rG)MjaF<g<FMM6>6q<HnrR%q=JL4X^Rb8%of)t9`(e{Y&PYO z%fc05t^UeazVhJVF*{Mb>6dcip<H&&)A;TjUrL2%iO0`QJi@E^x~%$PTe97}=I(;+ zd_Lt&%(cb|8j%2bivHM7t~>($tH1KM@Es>)K|R~V${~uH8RQ@jz>400tjHFiM$snR zoTk&+M2{_%?_)#`69@hgr&c7~=4mnv=U(J^A`KLgkOOXUf)zpx@ozr~bY8tW#T7xF zKMZn5fdUKh6UX>DM-7^bjy;nJ3h<Z{4!L954?JdMMVrV4N|)*yTwinK&Np*RvC?5) zZ|mw;uIQ@moguw@t@mIDAAa=7WO6{KasWO#J)6!J)N&k|PW9o;HwJmpy?2ebRd6{9 z*FyLaYzQ@Oxm8#hq@kI*%Dib^+m(0W+Aff<t>XGZ@m2@wbAAWx+U7M~fyP1zVYF;` zkR!{TmVQ23KU<{d`4^|BXB>vn8;wWzA0AEi#%RVDwOlb@J;V5a98XHq5SiOQ-5-t> zs%i^7Llmlz0l5g^0&2B*g)Bzv&CMi^Sd=kg*LZY%e0+3#|Nebeo|p&=;!;IU6q#9e z4z(-bl%Q*IN0m`~Nc!$zt$`{)4~kmTknEg9t@h^Vnpo23s!y&<zPrm6L4m6P$dLYr zDH^Nj^Wz5AIrM27ty+o(ZlFb4^;<2h;cC~`H1l!swMexVgP#^$3*@@v{LP}>!V|cQ zu4m)5?$fZ(Lk%?`)ROVNqYE0Y>0QlqV3R(i&l-IeeXfub+F3bhT!h=J&??5yB?vCo zRcn!9F`;P&Q7lPn25g6a6j-nJ_w{X{+_I^C`t&KW$dic!wTCE{7Y+<0z?&IM!fOFm z|K891jOFi$?cH7dZsa=Lc3DQH&7=iyVN#&4EschOG&Jg>95pusGnS)Z!<5_sd&3;6 z(?Rp@M0gdDXBvjg0<LYruBd`B!i|s%oSoFJK+$eG0ifW)fzUZ1tQ9~C*TOobuntbl zJg(H^>n@6_n_D9cCNKbrg=W^mwi(5SwFeggp`lg-wL%dEEC=qHQmAw+2bQ~0z>=0j z$F)3RxfOuCgh^ZtwiH`B!=M$^{!||a8zdI`4<1joH-{joTs4_Q1OeWo%|$cT0TvoX zgs@SDcOYm+bQK7%N{G0YXRV|3A>0($Gl0*2OC8JUCrh%{pcY!oO)alA!^v&t$(xC9 zmFKe3iEM`S7d2c*JfP72V}X|M=1Osy$}imbdUgI-e-x~NQfYE-fgXT3|1NCRV%Xna zvlL^;k#)Hw`|)UasIRLz`0|&&bac4CJD$Y*lQ-<C2l`^ytvT~TPd5)@mn<g?DCooc zdQ5se8jQyy*53X7J?;(MAx=(Ts(bWF81f6ML>KH_pg-}`|4k=j{Q9r{GN){9+pDuB zawzRW4lIWPit4qdMO8oOZ4DF<QgkiL>1;MXJ3o&{p3C#kFvwX9t;`vc128;?SUli3 zPNd~gPh26#1WnXP35k3)z|X~nejbLqqhA|FLNazvF;gNa47XY)4BJm`xr_ONejLR^ zq_gR4ce2M=iZ|s(dQ)!6*xKCLmc#gxBZiOe4x$=;%g;amj0-}~lXLux&DCf;JUl+U zn9j5|=o$?+w{|udu8g$J!QTE6R~4_b`SonBcgE>cdik>XIh;4c?KEj2FUl%n*y{vN z?aH6d=`jUXC{67TQA1r(W)$8881treZB1izz_kCkRxOGDyr^IU92CGaPGCItTnpe+ z`3+(1I>X{&rPFRv)(zHqy~?5V5XOjJZ0~GMh9l~(E-p_`PS4LyU%q<z(I-z>dl-O> zklB2O6~mIo`p?dB!$6h9Uvd*Z>vm-`BO)_XBL`(HhNGc;#4$#aczYN*^BNt7J(C3a zWS0~1m;?FFw!R_`SDrpFcxGZU<IF>Al-_t_kXPX<yseWvKv&>xEs913n$yjvPx)?i zO)Pm^SLA~UiFp~cgiH2T?E*O-TC@+XT8f57a;FyOEy*ox)tIDO=97}Uk!mf*L%l}U z8ZIVcX<mb_rok*J+$wtY%fG!y!#)oNDHX060|xCa(p9(#Xj&PH5T^Fig4}g-=u66O z*MblpjS*Z2U>9xZ1hN>5SQ}2h6jqU96tq+YG8yFQA0VGkb@xYyTReLJ_B>3Si;Iir z&z~bi*_#TRL{UE&VNe9<lRxWQkyeRO``#XbW_5ME4irZJG;JmoK+;a7rXUZ%wUy-6 zJpja|5nME=wH2U>Vi$zA6;yrSz;7d14y<ff2@4HO3b%^%--35wE#Q+X80!Gb0qu2S z2vPG8Y$aws?Aqv)C!&=Cy#13QaJvw;C^|3+n>Z_KyTBDy_{Sj>i87As5)R}6p?NEq zmvIx+upE?fz<DN8!98Z7Gb9j{5RPb|<4m{-SzpP80&-Uwp<eXC>L@6{Fg05k#m`z8 zc8k#7pe|ZshIGvUD<q0EP(+P41D}opm|wIyYnv)MjZ`fbjoe}Q-~QVaQ#6ChjVZaa zs@$OyRmHVI^un#8r5qjv3qkS?qmjetifgNjYk3{3hE6ZKN9x^C6v<qF+nXF?kaYhN z#Xdj?$AVv_<%NtcI%$iclLmSOdbBg#84L&PN{{a!J^Ao4f8)t;kMrx{{&+GOj)&Vj z1I|d(*<6P(9oc<dIl%G9WZAsDxV*SHKRrJ`zc|0TyqeCny`Igd9LYu_J?-c-ZM<cx z3$|ElJp9yO{ck%N<2Qf(@2XGY9V{51oPBJDmw>6`r!(WXYmpBIG(z9d1K%vt^cw4) zj_5E583UwC1qVG+9Sle8zV)_mJcP;q8=g^u_4Mj$SHEezed+J!+1$D~KbtM)Y~cqZ zj;33Lgdgut&Q8xR(ME4J)#-GLp496C-0%hiefV}b+#&RIddbjWbzytYWQqY#96J9d z-gq9;BELE2-6tX_H_^SleG;al=r{Vp(}&*UBI^LVu|+Fsx&FHm|M7>P&~NkU0)B7z zU^E%cuI5jlJ>AyNbTK#?9`uoV2Dfy=vuDq)uKe*%HohE(xO|sq=VxR_ZCs5v0h$_k zjma&g&l_Ih8cK8v+lZ`UOvd<3hJ01sfol!h8kX7|n1`nS7FEZr13h23RWSGqw;Gqx zLNRA0&g+P84r_PwY--xL%|XMQf4GAz8HD%l-Jeb8oO{pCE*Lyq=h<xW>g3har%&h8 z+0nt#qeqV)+`m5_F-~TuC$E^SdQ15H;wrwaExc~g_bi{V6jz(0kqoaTfT<M|+dzUQ z>P#pXSs|G7`nd1LCZjDLVbCJUd3Sm>ee%JRqvJz5_5A#dNxi?nx3k0MXNoOh<SGEK z*FrSjk&}bQePm*2UKiGAUN4|e>TYcEe{bND<FgB@OcSLQopF`=Z-uUjC2#A>ujm<M zNP4<tjjJwf)rDJUg_`!ERZG#p4YWuDwdXZx#9>_uFwDf3@NT49i(!R?I){WiO0GN3 zSpy2Uims;7tdni@>X(0ek%oO9jO^7KNZfB-xF1?*bxRBBvqoQ1^k?B#frngFSraJ2 zBeCZ?0ZZcTgq0ZCQWslDF$!A00x=0nK51^@<=Gka@p`ykxkH&P52s(w!0>2Jr}|B} z(ATqLtY&C(S_YiO?A#O`!%+b3`ng~HMMZsQY<~RF2e<=nKqN0XQbMYMQf`z<(MLxg zM1j2l7rj&IVlO_v!f;_jgBlY1_x{GkqyRrwj=hM^MTTunYlcpbEDACNjKWl~Jma>| z@|={=&V(NDo)sP^xT4Be4o!qslZ${OCg{DwtpY2eIGmwe!+93XB&_eox)w^Yt7$n* zdIL76s@AtR%PB%J2^9fJGl(Tb4Sj?DZ^_*c;Y<kk0tyN1BTRj0>SSmn$jt+a#c8~W zRJaIHG(yKkGt@d67ePzSd@3Y^97BU5DH*jw&G<T|1fUFUjW;A_?6wQ~nMxKPx-*sx zeBuY+nDW2mP|lc0;+;yiKG$2DJDen;94Ocl!B4N|mO!;h;y4q(XG(WC2f3?YiE{?h z3}Lnl>MDc&M`*a0j9T7;!Zd*rSa++WT?v8ZfNn!bAXkyF=U~sgzShrg#$&PAq77}# z*TkZUgH5etliksTBh&nHV`K4^uYT!Ae&mNAKD=)Y$7DM1Y!B(zn+=XwMA%s9gMxa} zcz1VyGMSv7zS45ZE>%y#bKJX%Pwmbo`f}QMLrNz&U1*d@1E0kGkN)@nmq@4JZ~o$c zp9DVm=)*t!!$17yH^2Gpi>EYpFx+8h&S88p)i+BK@kYC7{mw0m?aPxFTqi~jCs2)$ z>ushN47Cgi+J*kb#ThY?aId2G7j)@@Q|X5Kic|GMhw1TPI9o0@u-)3^xF28erQbol zcX;pY;_CAJoZA`=)WKgKu4&?6G@^6QE-n_c8Mj0Z`m8#$>G|d51vzjG<}%WB4!Q>i z`)6n87#$oOzIyeNeDB>mMuNXRb)BA?=0>o)yG!TL4^VGR=_qcTw3;I^U4a5!vD{cP z(xKa2kNA%x@ce4NGulCZHNVo&IS;p&v*r2u>1a$p$7S?IzxFK9FnIOq6pjV$`Lh@Q z>JR_m{On@?h^%JI>U9?n7%11y9$GX87X73-SkFG_^^Ja{Gv4jj)z)m?(#M<Sw}G7} zwIr*c?vO6}<Xp?bt)h3H_WTa86G$eD&hyQ&KAV1c=62!x1%OW~Mm;20LY|stH+rI2 zwE=2rK45%2dU*W!@xyO^^Bdpz;cwo*e~gfeHX2PB<DY-_^x)w5#mkfX_a1STKK%Gg zjF8jw6Lje8_<}7>KqdzJg3GBMonTHe_nD)F*xx@mzITrptUjoD5oZx#cyq2Mjk8xL zjOt;003nwB4Yq`AE<XSK`%fNy@K68gKb=hW{?6a|JA0GemoHyot6v(MEg7GKfj*&d zb#ckW9ZmMikALZl<<%#g&}n*eePUGT^jn69hDlsv99m)~i!G36;Z~9T-vSMXMmLxK zuRZt4yFkr4z{NxgjUtU(E&V_OTm|G>Vp){px_5zQ;a0)5DBPRD_fz1a##+FVE;XEg zi=vQ7IfDoK=D3Zq3i<?x3FnDiPr<AM>nc-*OgyR?bugT27_L@uk~Om)J?jbH)Xrwh zfyDXrT^EllU^UYkc4C@9&6<kjD6GVlc`~l8sTroZ`L*ckr+<4!;@WJNi>3hoq0&Ys zW+sbNnNfg17PBgWBz_jU@JT@$wh-G80ZpzuV}K0<Oke(6%NsTo+gn=k9zTBk$tRy+ zbaHa?PyWe2VK*`!@3K(6eEE`fZ!+FHINY1hr!+3FCT<NJIuMCbgu)~Fr@#BV)_h0k zGr;_l%_d&9!KkZ}8m@9?mKdoC`W6o4STWq)szj;ogrjSywX%zGzqvhlwBV|`7D;3z zP&74Knl-Es%%=p#Ch(a_N+`k@mWPp0qzzo#MX9b}b1uIbB-V7FI3i5w3RYVSYJH>1 zqWKmB(xHV(lSu_LS*))+!o12h1mWWrwZxjBrRic;6=@?k>YfKhqY7#Uq<^EOmi$`W zkw6w}c~{tq{w9cF1@zLLd8p;Cr<3XCm{T`Q4^APHmc35IjbC;_A_qZLZ>-*%6YLdy z?ZUa>Ia{m2*RUkzk#p}nU3(Q60`SDFYQ;1$;fowe2&GuN!UaKLNY#>6+~`D-Pho{U znox%~(1V7MULSBwxxBhuT+i-5JpTGOKmF*FkJzK~cg<OyVE#zq7Ay5myiH9PaqQ>x zH{RXd8xF^e&Dm_u`7PcL-c|<s^zQ~&iBqYr;dN}z7Jg@mw3Pt*<nZG^`PU=ug5Uhr zzrDA=cXWJsetvd%czAVniBIBV6@y^8qh~31wn$<**ZF>X1Gfx>cno_BiQX{Okl>uH zkFo7+4@h99&oHY8rgI%5IkC}xTE_qCjpz`)i44>Nz4l2h`)qcYmzVl%?IOM##+O`u zr;UPM`@n`_1BIt;)A{uHaG$scxs`HW<(5X?+!RxYH=Iy~gd!Qh5ZMbLwJ1a7Fh(Pc z(raFk<oKu;xoP?qr%h(VPTVkdh)#*D=5zhfpSp%5Z#XLJyNL7(#C)N*<n@tkJ)<?) z*<Q}|E_%G9snJhXdh2^OSN~Lq=JtYEMWs9Y^orF=Z3v^ED_CA?S0Tf7a?mI5c>|`s ze%@l`jl|cZFYfz7YpN!qCk6PVAV$7;6jFzJEt2tuzj|IvB}y=xM|%g~{q}eM@DKlR zdU5&S!NbRo9}Ne?>D2|>xaZGbaOQmS<jLigo(DKNJ>S{cp2j2b7&8aGLdFtvJ=vSY zn;Y6MGMPM9NoA@57Vjl8G@Ey9NMbY`-ozl-VdTYU2Q+auugAl|@x4P#KK<IK7v~p8 zM~BazKBE#t#x=PS{pv!GS}<9T?;W3=U+6mqwEEH5=qpjQDDscHB^hP@R+m`*)}iX# z6<A+stTXJBcadsoVg^{ANTE}55%}tOx#*%V|K54g16GoB<+yl&W-={$2T({9QGcF& z=!?<klY9%eiXZx+A7YK<7)%GU6nlH1cbm$SWw#D%&uh>#*vJ7x_Z4tTcQh8A!u7xk zeQJu~DrVg}q@kHC>K1<|TKcf%-vDw~Wz$?V1-g~5LsNU(EvBw&d8?T=n)X_uSFHiV zAp>!B00W@5YWZ0%^yv)lx@?dR_7C^>_p!dXVExn&shpnbtFVp^@7=%m06&+P7v5q3 z|3fSzU+hMWC6vX@ao^j|ARQd+7j_kyhpCHDXOr?o9?XC>6BN5ZZbLc(Y9WmETNH$@ zV2LjPG?w`FsPz+=Kx+knlN7cPMg?^dD=Xlz_UT%KqW!z73)ilN&1={v{p_OE+<Sl= zpq5*~`sTY}6*FTs!xB*Qc4$dxm8z6Ll|j>uMyT92Ft4(QuN9!~J>a6{z*aD>?N(W0 zSZ>%=qG&Wa$pHILwA7Nn16DJNs0v{wDpw>R^LO!0V14%na1oU1rd#M|-{6OFa58EI zm?8~imE}njzNV$nXhO-s5+Fwn7+2OYlCOm=q)*IY!cA1fS<AH{6hbc44w17Aq{Ny4 zzE-Pn!?8_A=7@n#W$V8cAZ7#2@{2Cx_sIv3zwwQ)J$&?#&Zf(;ip{_P$|a&5*Efrc z%d;ysq@0uV1HT**mzS4U?3<5|kD9yy=6WA-n_W2hFE<wY4lKG{KAj0Sk;P*6lRv%k z2=s6K+J8LWov>HFy1eAB;Ew_hw+EbX;}K%^#N2xZ+~hdbkq;)^uo*q1$A&rD9sZdw z+u9N8)soE{j+AZ=yL0X|?8ixw=6k%sQ{~){5D~y*PSWS+=h*6)sgE1q&|*K5ttfg# zREGg#>5Z=?`=@gpF;rL$aDq=Ap5u+02M-<~+1uO0DM8`6Ya%BDC`H;!CTzUCf;k6G ziRL9pd;<C%9uo@zYEaagob?JIn!3K5H{7D*MQ#2c#kal2x86+lr&A6#n9zJ(W#k-Z z7R#IS3w>tTZjBfxa+rKlpv%wzVWKX&*6=l|Az??~^ln(W1zl+Npq)Q1bxTtI-V%Lr z-!I(21d_ZWE}8;HcvLbVJZHHa3>z92C)M~vsK1ciu!D==;N?vD{N>A6FJCcrjt-BR z41>WA)A`=L<3Il6Z%uY5)5Yb^&ert?lSrS@$hA2-O%MFzQk({`2PEWr5%XNLF}5*E zRUabOcgCQp4+#tgY;n{W%G;as`HUHTc5(U1m%ohRm%jWZa=8EC{^{A7c0#DL91I5} zNi?bmCFgPOS4wiDF%>HS2&#j&<oeqx{q}~Cbr0lu9kR-5HTvXTxUUj61f^WT@_IbD zXwYevw?I|lR)KBd-V7Xop$<yUNx62Gx9A-}AyGvAdG?_%hJ8kt+;&vZm3~fq^{Zcf z@j@>Eu|6_H^`Omish25r-w`s&I@>kS>{t&B6BO@msdesv75dZ^!&PyY?1Ob`8q38R zINPp1{{}5UXnCjGQ?2-^Q7YDT2(>MF>aR!BUaP%E88p`mO-3?HPA*(V%g-YAB<OHA z-P_$~gs=<JlLEsbW9Iz)0v!&<AzxliFJp4Z+#YC)fr1%gG2ZZr0+Z;y9f0@a9bm(; z0rB9W<}Gw>>Hv5H-kF&<13c%~Vr}0gYN0e%)4(?2eM}eDm#+>iw@w0AGV1`jtr7^K zm_Q?i-a%l`<`JeGwB&1Hg+vOu{Pqkiag`;ZE2Pjx*QPD~W`%@JP)I)PZn0MG=3@m? z0$g+~U>?epkWv6wi6RPE(?CBJ!czeuEC<#!kQXjcG#Z^`08R=QXsIQ?7OqV-QzQ9S zRfb!u46J};EuvG^<eGw(6?`b_eBz=Npj;6sRo2N`gMuZd2{g6T1#AV<+_2E_e6-IP z6grRt$L#{OqyP``Zz-l6xT;YQvKGcH|I})!&;k8cK1PuaVVtBHs1cR4Wn(fKAKyE? zfB)XS`^N_dd!w;F8%z7b4V}Y4#YzQ?&>W5YX<qG4S@+p7?C&3-AAe*9(b<^JL7+Xk z9=j!aNdQAVD65AmXFv5<{yULI!EgW8e=?uW*+EmM$7h$<Lw%H2la6DdGKkY)yal9Z zEVaFj55#gkX`k-J?x;;2>eyS8GH&AlOvIb%Y);BL6I9zZc=>D|eOK26%*Qj#`o;_P zew<EcGyN*k&5e$@@m07$@8~ir@iU)K&rVJ_WgZ+HV9Vi|(A+7HkB=$(JdcD}IHwjN z_fq1jGvmYyPb|*K@ap2`?O!JYrDv^XBu_1B0LC2^RT~#)<S^3@GwEkv)o&X&x}cZw zmKtg_fDYtrjQ-Vhc5-&1qf&TI;1i_KjHxboqhKbf6{1GPKDf4}6GlQQcW`&rT9oQ{ z!~62nhfFn@7P8jG=0cZcFpPxy8r{<C<?L#@zqfyU{~n|9kG}QC-~H})nZu7BJ$`la z>Z6Z7I=*-G^oyr|^4)Jge)90(X#dr#=cA#1)(9{@4L@_h=w;;SB}v7_y#T)xKb;K- z=ag9UNRpJWVmbpD4NxrwdfS9uBbuB&^zr+x?T3#ZJ$&$xB}GxrE;MTfgYjsD&c(&~ zcy}Bx$;F}_Ph+@odj0EmFWxYETxCrk0`<{4l<E%Lhh5mD&$dtAMN7?wpp+|E?tIL{ zP_%?@kx~b)?ZW174lb&L0*a;?y%w6@0TdEN)SqV`?v9a(C0P0j*MWc8j^&!s#n{G> z#PoV{Ad{@KU4xzju)P^Yv?}bPDD}V!eQMz#s&3xG547(9oM`DoLR^5vRoU$>nhN^B zLXq4GD`1$mFl%*eYgm#dRF;35C@%Ja`iv4QQrQi<7PR~@AW#6TW0Q%#KAlC5HR|Qd zmkb_87v842;p#5WV#%fmQ_SswT7!kOERO*gir{B|;TJ4<M{Mu!?V4)^riCt=x)y2) zjGI>jc@3NN0eut<o11s7nWP}&8rDZbUqHL4^9&0qTWF@{p{TjI7B)BRjkwTEBjtEY z3CJk+?<xyT>F2O(gQ^xRXSfg=TVM&mx%<KLR0gRG%y-SheS!Vd@;=5+2yF(q%5c$Y zW-M>@vxNyH;px^S^)1XQ<Te487=8Y;Xa=M!qotO73%0U?VR;{uMF8J|h0ttW-LADr z6NBqT5i7u00@{1|eXRz#O}NS^)d32YwB-#-Ie?#9Vg&>LP6nPT2L(v1+=6S(*d*MP zs-#(kA4^(bP@4(!+uYVF0}`aG_{+rHb?#3bxCQYS*w6uNZ-4ibPd@tK!zaU`KIl3g zvk6dR3EQMe2|wH*IfyC*5~}#~mC-p$&cjG)FSR{hT<Z;5^_~vP@j_>OY+Jj8CCpF! z)XD+)AOEAj#Zm2gvE198Os_6SgAw~_Rt8R<PJm1ZglGB`SNa4`Y-s4?pz)qm{7-`D zad=0@{Rs(K&*SHXylqF>fR9_3rnV}gqv$k)<_v~<&4tF`2O1rrUcA21FW}D?Gh(Bo zmT%tdj`g!5M6n-kkQBLDe*gR5fAQi4A*RzQ$#D22C<k3^9TXuHg}AfoCk)hAu>iUj zs5VZm&QO^&ps}bS*9jwjY7779FJ|-bihxl1<0`SMn@(rr(U{ZBTnf6W<Kgn^iUY8N z*(O2JKshP!FhZfGHKP7j*sfkRvGSXs7<8bN*5MA5x5E4Ka|fb*in2CVs|v;!0=VcZ z7gKJ^@r8Lfy}CL*Ib-NDj@j;SZS9<#p1eFc8I6V?e)Q32pM95eBZKkiaR1qh=P1PI z2sJ|DBMyG%dh_a%VUJ7~6xq(UK7FuUE(SXTMwcJCUouax%V*m#!PSt{g{G~(z>Pn~ z5T|j{U`AhDTrwsZRw%Ik{OFJVDQ3at<;BZaFE6hy7;#%WTRY4|26;3D2eb;FbjT^b z8=|@NF#fAL>fNDccTiWEuhA#(LS5OwRz?w3u-ua!D<~J2VyUhC)F=bsouS?i5SOAu z-$oB%P455-i6VOYJnx8+u98upo&)f!SFdQ4mt}4@tf*xTFZH+0sk2>!9E2UHosBIi z8GYXR<OwU>VP2{<Mb?1OQ0vr`nxJj;>9Ytx69_H0z9mTmWq%G=3B}u_rY(fsEsC^3 z$*{@C3SG4hZu9iOHY@}!KZ9nU$?%wr^`mjv5&HS_=ZqYduZ4cvpAn=7wOB3t4!{(N zQs3f{P<(IS0=>7VA1rnO#!(5w$c8~^>RMAkHc9K+go{aEi!ds1v8D!m#<e7pT{8jz zYJgUlLCxJql}*yn3c$s+P?*&~6t$lU|8@&V%xbl_lyrqquBEG5utE*X88@X|Weyls zNU#D$6tG&T3w8^2Pa2j08Um%5@|vy%RcVqGNitASUpRz@tBh6^$_Xm~<b{hsi6RQv zPoiivI>~_A8)&H|zZOIR*0G<|Z!xaTST+PM)={jJRV~z-HL#+}K5NwPfLRlunKOc- zYmF3|CS02gh-tL)87kWvtaMb7KpiNVE^r0Kt&5G?ZNw<v0?$xa0rOB#LCmcHQeiEK zLx#*gcyd6KtdTH}>_izi-eB03&gRq6Xz&%`lY@i(*x>5h!b2G~tNX;Y`NbFCXNSPj zjSeTQ>5PLaxZ*6Q9kMJ+Lm+Gh*s1CP;ekHr63e}u^T*cqfA@d<zbWGifB!%IzYe$c z?fv)fKR9{yiX70K>qEFRw}L8eE{p*sv(2s=|HxRW_&1JZ>S2YT59ae3*}!9ti0Ic# z)`uPK%Bv2PRV;c?dJIj_bd)QvwVl^{0`WmyJyATsIkxdW_mZIQ9FF4;?mzJB!6Z$e z92^`_{QUFJ;c*_lq!*7FPB`Rjj2VpYmng_vfY{+vwa8(B<f|{tB?Vq8agL!~;beER zt7FG-L`=PTS6(krEDw^5NW#<E{ME@hu`Nme?g*HaWRZN-PxSISkaO0itEjm}ElFNB z0T<s2#j=A^{cd<)e)>@RUmMH9+bX&>faF$Kt+!N}0bE5+s?*E(ezkZ_ieYeicJ}#a zpL1Ge4|o5;J*Mfs`}dwc{hT#nXIsb2c)iHaM~E=6P#%rOEFC*&#AJzwrLUP3Xq2Zv z0#s?X#N++w1JZy8a;mwrv441QdUEpM!Gq5}`|Q!<$LD9~BTm4>(f<Da!-o%#4i6cq zO!?V-t{2rb9kA0gCOE-cY$FH6WA94`xE~m>!K=|~c?U(SgHrvL=(FvUcahi2upubr z3YNQXZ3W+Sh29entv0OC#o7>efDlf=MP0~%C0%+4P)HO}f1Z8li$R|hu7#chFhgph zuXEGSudre>q~dI&UktNCCRt~@20aI0TR~gq*`F<x>V8<KPcwW()y->MS*<9GTc3Yk zmzF-W-;9CWRsH(@S4d&PR%vUdvRz@i=HRUlz;UnBzp;)1#sGX8n#m&fQR_22c6aw! z(6B(lnBo5Ehgrt@l?nYQz~$8i_i#+ZpFAj7z^fu4B1NjSiVX(u?RS9p;{a?>_8I|v z*LO&$Ypq5qW~|SY0CY#K53QLlS`!aVhql`mO*pjmZ34d*R!)610eQL>Tc|u%KGy;( z$AULC;JxvJw~k%8wuQA-_SR?8g>r2+Smt3|gpxxRT?=sTBoh{9EkGZrcLJ`m6IUfu z!+{cEB!|cij~~NTfMmD?R&Z4^R9Oxv+97bU20~n!F)TM+l_(nP+S2meQcJ!CtXxYV zsL~C<TcO3!rPR6zXePkcT^)+IK(m$qT13DCy9IR>&fU)`gj$X0=A%Xk3q2@nVO<5t z2SlZS#7v#1C5GGEf_1FiLMlM56K<leIR-;RC^&8ytys}qD;TL`z6-XY@!0Y<2g2Aa zaycmNuw}%ArCk?klWyTw0o~$obno8rM<0Fo<by|?es$*DqOr^2aD)}dJqA2y%?Ky? z?(S%JZ?YSoewj@6Sm<@K+Sz79Ojanc3FeP*+<Gx21mXR!zNA?nN)%mOFaFA3`R|sb z1OLG<{S~qw567IS?;Ra~@4MgOq{;0SZ(Mb(xIt`eZ?d~4m-y+?O}4}F4mP7vU(v(C zHqO8Ne?#7!l!;B|^Vx#7&>~bAC)Cpzu6_AnBe7ZZbOCf+hS|Z2p2YinhD0B9o-b~e z*HjI3hSXbE-0t*10!9j|2eENWZ<7F9sLRVsc<zz(-r3pNvuDpf{q$2pv8VSmAtpMy z0mc`u_(tQk#e-ZID~5C&ymh~%7GXJ9G>ASIMZubCVDow+!t>L!`Qm!67U&3ZHJx!+ zzPP+RI6Uy7g2Z=*`ogp6T)zza^7K3!6rf}95>%rmfIgDK2NNo7U~L_c5)17%o!enS z?L7V{yV!!&yNEAfYu*4{`NL655`R5g=#pE*WbuyB?*-Y<fbJ^NDz2F<GU3$d(p&oT zGRY`2ZyGJoUYN1P++hMUHW;X{^bO=w=EZb2KRrF;R5=`uXVXip_x5&C(<LJfSu@Bv z<?5)goZsy4?J+&6i?OQP;?1=_UA)Bv+RzH5i4#{GkPsV0jp5-ygNtS|N@ER**S7R^ zZVY#_CnBaOynOX?FdQ7;zxU+H<42Dl?H}yV7i4(Kf}>M6OPHX3z<g_ShZ8Yr&{o>W z{0v@~HhQr1RgLVxHw5}?5&l)JKlidFMn~Qk)z{s;Jp&h8a24H-2|%KSAa1)Zu7x`5 zeSko6)U+#D@x{A^6<yzkK(wQvh~7TWKL6witvwg?9Dq5=(4{P!UZ3Idz^LYSqZs<r za9w5A{jFaA8YP+NEB-t??zm)z-KEoTA=ulR1_qFqD$Rp6AavTADaGbWw%`F~zSd{Z zg{%Of<#`<&wZ>L=%7WAZ6bskDwU)1?W&oN-$V)z{=3*~yN3Nz1SKk954O@N&dQ+F3 zz+i8eoB2Mscq)-xT<F*4*eRgNI>!!TsoU->ULusaJ(NV_eqFdo+Y#~e{@wxJon%x% z7`#IX?4spXfYR(xR}oE5253t^nLc1rxF)FKfo}gTny`uCVi))^P_U-ws*5PdQ3YFd zQRmr${o@U{P<T4W&Ot^oHBxTCBZPKg<r?AO)|-XE(P2yt6vzk4bqVzX3lmn3fVZtE zb)5tZbPCr1O{{>6;cVpq45;<UVYFDmDAjQQh8Aha?Ut;fUT{iKfQ}j9S|igiibkW8 z3~-c0OD*{puu@Z_mx?HaS!^*mekj_|3rF29fCm7R^Q#5xgzie_xGG%8aqDqj>l7CO z>%+JTSkqS>rmh0q@JNZP>9kEjpMN%sUJ#r{CWA@QUPX@|3)WQG4_1b20c_C-ghaLG zyI5Z97EUc{dJ3`GCy_Ej_XZak&0sgScLv}1#y5WCN546lj4m(F(f5*VC(%PYbPxJ8 zcX>VE-`{0V5MNZRUy;QPf5hS#O#k>hjM?nEig<(QShtK*YV?_KaB%P!|I&XWQZD$_ zU;V$2hm*x@aei`gaCG>`-~QHkJR((R&b?%?!|{`a=$dUeNz#k6*?fCz=s^))al;K? zDX~731MtQ+jK6A;%?x{Uhr=g{sS5(;q0wFqWA111?bdoIj;oE1cItZH+h1*^TLXvc zW`W@!Jpy`qa>7lKTO+jyqaVtPyC)|nc&3+ZKu>8mzr9U&p#wjeOwe>Q(BTrmpby0- z9$?g|0cQ(5bgA`08s6p>a?MCnZ@mQu@m4$_*46ZKHl5L_@p5%s)7kXp$r+Pg?TIuJ z9uEedlPT4!uzBi0EdgB<Y6};<i)Mf(z}q0sYHJ`@>(M7)kA6Sz2YvoiZYGO<VJm@z zPUh-!iLGF`magGyXjsqZ8Xm)ue!O~n$f$qz{KaIvdvbEhX#DoK|KuCr{O11t0aJ}r zsJE0{Newi*OYaGnebjO>kFSZoVRSJ3=lYC2J{hfgeuPm@Ab?MRNq$0De5}0;PWFx; ze)!?P{FndohrasNZ-4vS5ANN6_Uzfw@zHEL)yFcguOB^p`1tW-91?3Z+!+nyC%)BC zcLf7X(<=6|{KXAOH86<aN?+A*U%fj#+T6XtuAnRLi|Waqupyw4MbyA@W;!MS1uaki zrVhYf(1625E@DW)!Zzjq9>}sm5xsq$eg11dwg0{YFawgo##lW(JY+p&Ofq6~H3sQq z#oHRJ&)-&Qn{My8WNVSJTMk=5UaDe_bm0W7Q`5c!aGyRGADTdDd8^+{gYmz;uwl#G zjNxL9R0f%kHP`Cb$j>~7Zyf`<A|MUTWKqw==sB8!j=yo2kNf`ev(G-mYBbW1r1}-` zo9hkMS0Z4F&>pZg7+PK!eWwOEq4*2G^h*x(j@bO*$s?Q+l>qeu0q;}{<W7jjSW?#l zva|xcsTJ(UAuItXAUEFv3$(XE0DWf#V)G%uBQ((W(gx#NGnOacWt>T5R2c7{vRE^i z5DQw{k{+30<tiHJF+r6zfz1;|+GJuO9-y|u6})eFIJYK6K$W)A(<%KB*0-=4q2;>a z@qiT!gDkWJoEWIZOEPOfTqtQ^tNa?Aot@b&)K#eACmkYjt%Vd}jM`xlHE<P_{-kJc z07=5OX3`3M)ZG8n(pV%=e`O95n}oA+f#j=$)^$$`G8Phm2PkvTwJi{Z==1=Lv+^ad z1mFsDisT8!kNwxc54F%NM&#RkOlzP|VmO5N)IbLlGhLuo`vl=ep4WnLLan{Qq^<kY zhAnCapotoQvD_KL*a_7AZ{EV-9dS)osRQs+IPvSRuXWP7k_ZXc=9)Fv+rus8<Ck0) z`Xc7#XrSMc-QL_{S)*^qyOZH${FSeK<>QY(=5WN-W*UwsdTC&})bI7hRW0v5;$X3y zUtOJzCqp*Pc=KgnE;NPd4Ym$neDMWwzj*rj*T4RCdVrbw;)~C5#nFosFJ~<@Eyv;i z<bV2qQcD{AFaGEMy~T94y|H<%NHO@??M8E!3w^sa7f1icsL){3@2QM7u6NE(FIc@_ zynOcf@x!N2pThgq3R?P|?|kp!gU26z^ri2A@AK(YX(;rT9$4ZQMH6sECT6_U<Jl4d zF-X{v-@A82z_T-suRHLx`sK^#Br=;_jYgB><3sq9lb84(4%sl3*E+e-ajmt`ISS5^ z_%Z<`(8cTu1_i7v0q9Vq2~aKwRxDG#WLrCBeM6aAkWHXPwEg+>=bRQ^ym)bRbfkWm zawgGKLV;Fu1<@xZicIKNuTJSmc=FxZ8UBC%vwv}Vp?AB9<>c|4X**9RNf9fxr5dX> z=xQ4pMM{`T->&WkE}+(|sY0(sjCuZrqT?KTmF2(WP&)@$(MteZx75YU3w_UL7k7kM ziwx98k398TdFngX*MWS{Nl<i#1HAyGX@pRFGktfIhU;)Vj^#oxE!}@`{3Ac|&Hw6u z?Z5KPZ+-*et5+{r`2W=({Lxpw^3{#a?Sq4(?|kPw$H({avNQ14J2POI*wdJ{^q6w< z$c%Za`vN1A-rLeoAQg}g*Y@=69OsNoFrVt1V~|qCNS|F^aTPQlH_ErE?`&@U%HR9@ zOvz_YU*MC~j)Mw|gK~(=L>dsH$ErtrxAf>p<b%)Xi2}k|*rHU`JRnslGXlvP^yufP ztE+&=v*9WunsXOwZ-xUQq2YvsSFe`JHmqs5XyDNbE#R<ltLXb3-9B*b3ioE%+SH!V z(MgYNUG&!?z-0bKVMF6zt!m_S0t}k9JelpSl^2F;SO?%Fv1oo57rw=;1?GiYMW2=B zj_aZ&EqOA`A7~e@1+{q%E2J7@CW{K$j9dEOa^T(uNL*{>G=yf+d;;NG_<D6wo4^y! z@b9|Yf6Y+kVw-O0TvmINK~#a1XVbh71XM8xxosg~r9xuO78nrJTJ!$>``l{x_6|_~ z{ont6_8z$LLB{voSFc_XihCv|2nos}=8+jWs+qVlFYg;0|LpgE&&)ewJHE(NAf(}9 z#!H|Lr43$3pk|C%-*3;W?kVy%lb{H2MHR3xGAT&8HGy?taBhh;EjQl<P71dUHmp6^ zZC7q4g91ySbtXyOZy_#2%1B`X32<X6x^+o)7Yuk9p<p@6FyY|V18@-vZ#in9z9Cs| z;A$;O^(wI4+uQSC#V2Zc>8V9x=MD`Yk;_zZ{?5?)Ff}a6Hi8hZWNTOs?A)5J!oNe1 zSf~i$>{iFZE?f)XZ342&)C`~rW?DeO&4j_+#kx_zY6cUnt}?6;{aS{)VNGbw*pJ(b z5EFRZ%3$4iOW3d!UI$u)HyG2j%?!<CF+Ia4lc?n&g&;i#zoJ$nbwJHiD*vv7#|E$o zuGOx_23f=wVVo0M@7PSI=VxaemJp6dqpyAX>GA!e-Q7vJ^2Z<4`93hydU^oBvq9xQ zrte@-ezPuC@7QVH=nYIFGAT|^PxtnAnVxJhKl|+a2M7CXdbNwykKA6dVZ~d#mAds8 z{^DPYGz<P8|M=I2gW*=ZWWBs*FRhEt5$^or{QUgv_}($0^*vfcMcvS&&}6xsP1*JO zro!HxiLCd2-7Rdt=d-2W$hz5h`QjBtgtW_RxknUPAq;c9W(0!-Y91l2puM4^&LQ)t z^{aTAp2%q|IUtE^E1$^iIpLHL8Watkz?wD9YV;vZfJZ_VMR*c6KNybCfk$W^@=<$Y zzPJk5HZ<@L;Xj=PiclwtE0pPm@tD>rG?(((^OsjsE_#^-2<^&@Z7Et(Q1cZ?)taD) z0(HR-??!1)z^?3*q7~W*an{=8E@-$3HmTjZGu^%J5TR$Cd|UMA-y;vyNj4sO8;C-p zi1eukcU^ec&@#Tc!2sKw=>_ZU&5f<OCLKrF8_v2+V&=*2-tLDVe#nGG`PHkJEE<eL zM$5LIVP?UfO{bSk6GlypYkbN%T?JL|MF+AMWbRLAI>%BaJ>5eGC_x!5D#q!U^q?4$ z$<5NULmsfAo*n1W@$un-eu0y!=~UlKHyG}m>maSSQ`E-T;yDGs0}Q7^h0t8npM-`Q z^3uTiU65<xR`oNSi*B#mWqAvA+%D{`rU17t;?qJ&LfD0s6Ur%2${l2s7HCT0-VCfg zg?m$!i&gRqAZ6Ip(-6kk*00mu!pcyqS!lRQU(~P;^uHp7PTGn#?})mpX5I>YRxLS2 zOQ6mnVL4g4*oQQCu@AKx6qFv=SlJgPRMTi$VudUM*BV8%1}kn8Ho>RO4J2Ifs2A## zT)Pg%Ln*DImfIV%62`nIDQgjoUvaL7To`SP{1qU2_)9<5z$!Ex>W4X50NJacjwU>Y zjMyuE23Q*^&+gg}=2S(k;KZo?xnKN6E4(AN?`gwSKma1akhl7#x!6`U<IGwVu(5;E z3*Hiibu(5PSkoX%k*<OSphYSCQ^XIwta;olVU`2)scC9NO&eL23N5B9&xjy(`qFUM z!B`<F?FyNI#8$xFZXQOLp*iuU8VpwTAhWzSv@j)B!vv(OE?tXOm5aWQ;?vg`CMpGZ z>ku7Afny}Jnp0cBWR$M0B{el%WojVA5WrB(DtQUOTgQACX$!0qcDL^sQ)>lNS`p$l zXruB7E1Lj{dC5Rl!EjxQv<hm4ECP5J9oG^&!8sH^=B<+^2+edM<4&!GMiB+<*(jn= zuG>|^Jz(BCtsXF3q$<Nj<m5|ByGR|wR)CRJMC(wL(pEjTqdgyXl(=2S9TSD+d`9fS z_V$Q{dw=ry@uRQ(&{x0y&96Ur_+W2;m$6Llw2^7f#+D>mFIhE_FaSV=D4A1599ka% zk?XU#Y+|21e|CCu`Y-;)zZi|iSC?1!@7+gXG9Jd4QtxmC)1#M*1^jq2xwyRi@gM(p z!(YL#{o3Cp`|IUghc!7SIIVH~_)xCi24=MIFB{^yzLa^sxOea2-rfP``}=zcc6ayK z6VrGSXKB5;-q_vUef8?()yos^R{AZV`Aqh)DaVQkP<W;@LQ81AhcQWTNT3h7tL|)b zuHI&?Vkd@VJf7_B?vI9Jy)(VBNt5G7$UI`)mf2Td>*%O#)h+ZkcI4pbsUVxCXg@Gq zoqU83VeOxUsbvwPz0>J*G#b$xGFMJiE;nwL@Ot=Nt(#w6UJM3YV!a5Wk$k;i47_~t z^8Auzu&img#e*5A6fp}*Zjp8uTrzZEObtv-jc!#J+CEfO3LMBTY9S8!cne<s^KUJf zkj1&9WGoo-9xCn-kP7dJUO#vGw^iB()7QGv5B^KF`1Aw7RBaEco}B7q0=i{$L_Iq_ zKR>&?ytq7hdBPQDEIoYih<)F1Fl6R2&T&GoFktlFuHJ0b@X(RCe5}3<6-E*r$Cw0u zBY_MQF=_)kKyGgDcvGnl^Ws{kR=pe(Gh!M3^fWbfEFB+y@BzEdgM-7p{XNvq&QC8c zFBZ!=;R%bi77Km;IX<1tI;?S0+6)x3AL@>P`C5Wu;Z|Xdu6`shz|%PfnJs!=xCcer z!P=bDzj`qgijy8cE&o;qrMwPBV->mnydiWs-v%tFo@?-gqtg^LK<|0q1$2!AtrkR% zLiSIMs9B#s4yl82=;%}-)m>XNZ-qXqmYiarCb+xSu)=HA+_6T}lY++@4G%2=VNJ~> z>Y{6nBI<yeqOpon-5`bDW^~atX;9{ADOIo>lyZQEn?VlmF$O~qz$ZN9#KeXO1tjqc z4|^0@Y0y8__bFVm=CK1|_~DRKFq+xZ8czXu*2AbOb<P32w*&Bl2lrW0-58+M;{Z&q z4hf2Gz^Npyi!=r}@2pA``)1Bi>!NGjS%4~pFqXqxADFKtfMN}s)XZA+)%M9V777L} z&0?qs=+KZ<2GqJOF1jj=3Vhr1$Uu|M_qAYKW@W61WgQs&+t3bybpS#P0X&-4x3Yme zed<2C4mPp3WNheEZB7)F9m}<-QG_Z$=*WIGsD)+{mSCGYAWQ}GNv#w9R)(2{ByT_F zp;TE79-S`eZR@xgrh+A|GF;md){uSU!D>*_2(gfADENw-H)Eb&wGObpfxZ<|o=jY~ zVg-#ZX>LdB5Jn|L0+W=tY8@161p`T!0*6M~{a?ch21OJ=rYfh66aH=K*QnHPv0A!? z{g^jnOA-|m+m7a5qksH1EE`P{(>Ee5791p}^Q(_O`6!n30?pEa)=79YEd<3;yn_lu zbiZ<kgy{&+ygoZSJLkW%vvJ%Rj*pMW;}Hj1C!l=db+O@4zvOv&dG!-Nx$+s{U-<{W z%*HjA%lP&z-D_Ae$b)?J5ddPaedMssAY+qEPAFYmOzDZ|&%dC_pMU-to}WH_>W6{- zcqH5RmoHy&Pa>cA9KnX)AfgFSUnT}23Bx!;C`~g@m$;eq2@=05Oo!lHJ-JxWUVj{e z9ymF9HJOab-##@CVkDrS^8zOZJQxkjYqBn)V=ET{5*w;xSU=<KZYyAgXZt4;vL%_r z!$X>XbaX^xQ5$aS;b*QI`o50wOAP||U<=Xb0&Z^)UcNj%yWr-%vIouRkw}57EQDDL zYXX!F2@AUdbf_wYRd4~!*iZNqNZayNT*qN&C5ZL={NHf^hNkT;T>Z}I^R%{qjM}8| zo3}sH(uJ~ZP(%pTK~Yr08~KeMs9>;jLAmtYllhxXnb9Zw^X%!<7cX9-%nUj_IOL4N zv2!tBWB|^=8cR3&ycl!VZjsX#dJi6-%tv))Y)|<YO-3MPCJCot0yBC&ar7AgjX`q0 z|IN+a-HDu(XHqmtIRG;USpv9Y49DZc!vlZuUQEe_zbu-yUP0VGy^wapB7!>!n`Dw9 zN=?nQ##PGGwgu*1;R0QKisTPG`&h)R;3_k30vx7Km|Ou;?m$t$2CY~WjZ%Jd{A)e{ z$JdPu<VJIxB%q2Sml(JwEzA~RQn-NoCsFD5=8uQ8LfO&(i+TsR)f~%(BIt!xUaROn zG%vRe2%DiPCSyLCL|t^P(aJxuYP}wqC)M(>4z68?vRs!^151)-dY&>a!qY7PhHV3@ zjR%``3gX*908ZjSsZTg^>t{84{`~oLIz=C6&^Y2M5HUTL;6a+#eA4%J0A}ySjURY( zMt-pmC?8BUtx+dupaW=<X9Z27JL<l$6VpW9Du6z~mK@9g7}T5|MQhqBvJhNMIj|Zi z<yCa6?Bou4D+*ab5r)N@C{)>m+H8wEC*=mU?rq>IU<pMlAi-81L*o4<KyD$mpzfa( z0`zg>s?;Y0*GR!SKmlq$HRG{CEfPBnXYCg<faNd<odd80Wi!w;sTspXM@fkpAn#T8 zN;Mohkn@2FUBMEYbYTy!ZRsFS{}ibOE_Q)}6G$g86kP?Z2CP7p<p5zad3_BMFt}t^ z0I3YklpHRj-vR5FLIXlrSW{q!wObhn%-7VYO`u5XT6oJ1;#yMI@-J29yRcePXWn;Z z@Kd-3cEJXP3sAPX@t<Vq#}JCQZmtL0TL=65>}K^&%Fz+~*O7j9MBo2RXQRc%Le1SC zlwAqiVr?|(QPzF3Lre&G!lK3@iv2O$)~|o#>%-yT{)77`Cwf72TR+h$A6Dj%E6&+$ zYjfwvf8yU!&JF&_@BHRuJVt|smQ6L|D3)&j>1UAWIpwrm(g@bjp}uTq^zy~4t)0!Q z%S#q~GJN#t5t^JrIqd6mgY#v)7pjja-@kuMl7pc>mq^ha2t#PRa=Rii3!&zz#Ty~% zI1c0f2^c6vI%GWI9=XE~iIhj<_{FCAoF0I|JQhEF96(#PogJD0UoKNKPKc|0dXovT zf@`g*z6%BOxdBaA21V59*uA|yqI2HhFiZl&@^N3yO8ZwyUoE~x@6Bh6o9m5>^UL{S zzOy}iu6Kav=sIY+H3NmuVoIQ0P@Bq7D~rnRHghY0T3CY%Z6;m0$bG@gDySw_@rH8h z_xX==pkRfr8WQ>~?sd8orNehbZ$7U>Z3ugZ7c>(^L~~<DufI)wR)W^+4OcYuVQAQE zmIw~Q{Ly{0tLe$f%Wwbjx4-pA-&)LP%*?%bU`lf#G-r$1#pO9$D>{ds;a<AEGxTW2 zC&C!i0#oDS;)0pX5M;<RJ@C(tN}nCj0hkLaHB5-Y3}p?$;ii7}iwhm^<}y<C!umC5 zb(9$A2S<ko2m5>bd;EJ99~hqMi_B*m*ZT5*U9eb5)J+xK8%fO=@Z?YmRc+EP`t(}^ zFKNC544*<XeXy&V0vd}I(QRv<2B$&`tq>HAQtqHscR)?icr(210XQD05r~zo1B{>S z0ov{b7NJ()s#}0f+&`8ikZ>3&g;n4XC-#GuI}<Qet&rZjZr=obRxLTjK277bv2A|0 z6F}1nx7vH||5_3m6>l|f)J4}CMbtrD()B1B4J?VB!wRenO1TX!KiygjjUozA>|S)B zq0qp0LxXiKh9#?&zC4oM1x1D;@J|89k7-GT#fM~&5HL(iASgWg;jgp~iSe_)@C%l_ zBXj_E05UKfj8v=vtYDB(wzIBcj#0#lO-$Ol$~-8!2eN1;>IM8`?#`v?ISl+Vd>3h3 zGs$=1E-r=0&`h5kBp;3oTvYR#erQQTtBe(>FC=oqRnWtDMb_=*eg;L2_F4ka376&l z;W|&teL2uf39tg1m_Th(>KeFXTX001Cy;od%;*#i{M#FHS7p%*um@~`+^xb^rU{Aw zea!1BdxP4W)huxpMHmaCQpGgv0w;y5kX9K59tkkt1#))?yiHK1=>7y28fnr6{pngz zL;)@h)I!%fAK&l*3XCzR(;%GHS_o%CDL1IEdtGbirLbz=r3srzuW5MpgB5^_pe{Ci z@AWdQTq8Pu4e(=y?0-q2Tp<1p9m%4G|Jc9Md&_ty@ZRy!*S_|(AN|oE`Sj~w)5&Kr zU@7-P<Zj1jynZRqQ2sR!;=?cHGr&;u)Z&~&7gy@uy?gO7;Jx$n3(nP?o0aS}S?Sv0 zoPF@imoIm=2S4@Ge?8JH_?_SRRn`=(lX`Af+ty8vKifK|kzNGXuP4Rchm}G7LSJ&G zp6pHr!vVHXav&Y#{1Gm`mX^gwZ!U2(y}r@+LOXd9#)J8ARX(}{4|PAdDjVpYv2DIW z47|P}XKbR2iMl#QEJB;(5I%IIfGg|F{KY@b#0S<#*oq6q$#|mQiNOy=;3#w&%J8<b zA<9(Ia@2@u*c%KAs7<F+iZq<=q!rJey||dJe+0UA6749RX1)v88evpcq^wO?!L?mj zHJuoE=+U>{t#ZT{T0w7dQ{+}iHJCJXm%56}W`%b|25Nzbh3lZst)XPU-VZ<_QAGM^ z1ib&M95$EN`fR+GS$uNeW{5FD8COsS$*Wf<OvM*3pOfF#&ejJ{o-o%YlQDzu^70Zh zEegXi+d`!uSBD;h0w=(HVNg+op~#S<h@J)-d&<}&V!~`14hGWkSY3L-*Y=FuSVqQs zdt3m<D7mu~?d|U#A09q<c<=MiKgVJ|n=&Ctm25OG^~npymJ(1aD`e43QgVPMva0X8 zkaXb!wJXDhNp<oMg%<9(?x1#J2B>qJ?gbj7ECM~_6NSPBYywL8E%0_GZ+igF18T`H zdWMm}>Xgf@g;rx}hh{O65|on(etrHLU14H10=avc7*+_|73QtbXVsEZw4{~4<-o!_ zV4c@$qCkiQl7>cg1BDFKMe{~obgf};T`*t^*MpW}z90f{+oJ1GZb_xofJ+Ir+|+^K zVa%h$b!Q2J@g0!b6aq%z){SnI-UaRM>Zg#9V~ak!8mJ#7i{S)iq4HDEx3_EuWkECJ zS^y7z=I4JN`MYEL@bG}Vf&Bs(Ns;PI1)7qg7daI!;9^<<_?$4ca?Pi6fHI+7YoRGR z$nD2g=m3P6SeR8XcOW&Pc4&&XwQ{2s+6+SAB&m&zN)Oc3aGq$&vcl2Pk>%JjMBGf2 zsj@>CZRn!)&4drZRiMtNzK&K-8oFzM3AJ4y#~}<lP)9^)Z$^4{4ir&vqfkywm~>)c zGRYg3)WFcTb)G3qV4D$LyVjeLwhGyFdwmID&~Z<~Te$`2gBtqqS%gU^En7=K)&k^M zC9G+<7L>Y33D`U(;YL2K+=6RCDK{X`t`Oj`Z~@x_<c`<^I;K`5jpz)4Vz<`Clr(%% z>w}fua2H9(RW0BrH31S)x=Ziyuu3Zo_ZnC7-`?&nsj~fAUeCv)Q7qis7nheu$46M; ziSg{d#Q;s8IU^J^F5E<syTJC=4*Dd9z_TE9w%90NU0t1>ow;x0XMJ`r&M(kmTPq#? z4l#y$MPoD`{^aT-(7*BPe|xU4+2VAow~zF;&?aZv;qG{MZ+~xgHH~a&w;q00$}Aw) z3;pKOVv79p&pspW$?56k#pP$8ea`ja5Po@i!NHpiF$_9t;PM*R`V{bDNl%fzr!htT z{N9lc>q~uNma64qHX7=~vUARg%jK8@|K=t<2iLRHlk?M4_T1B}%d?Y{%Zqc&^=4Lc z9f4Ag!A5A}7?yjad4s4{1#E>fwXuoU%@qk&NI26DNBXicG%13#MTe<PkJBF*o}Zs{ zmqvK4FXp9vTqC{r%O4Cy#s_g`vpE+OCf2jT7hgQRoM{V<XM8%e8OH+ThR{4!6wJ4v zoElia&~@_{9bKBW2oHr1Cy63jf!<H2#<eZO!nME^2v{N2$Om(`8X-L0%ed|J^OorI zbDQxx)Jcl!*KT|BK_O8@7+mWE?K)=2)R!0<ou=2hq!OSbY5UDc@5K&j`QF~{_rCvK z#?`YI&lwIlU<!}o8&c@#ovp#v_F(D7Dh6-{^;lwL(t8YJ78Yv#V$+sBUvRUG&-Q0m z@5FACIf)emmtoA{Bp2H1cZYGuX?U^Jhd8#jHwVL=$#{tW!-M_FXfh%vy*M@8y53?= z>uepFWIpPSfQvN{lA(E`r;ZufbimB9PD|fBLf{^VChBPz*S3IyZC{Jjq#F&)p=1uF zXI$F?I)w{FOrexJDAgUXY!r<*!`mK!S@X@5Z~^))-%vrAwQ9V+9YS!om{Nra)cgu< z=6e^`F_Zj%QSSiv=l`1ito82z3hr3-Z{2l0?~of<wLI5F*BbWL1%tF`tfEvmNMRm; zQ&Q7)&@}AUrZB5o86x*2Vwk}ofm&$D9@}O4(mvKD&bj~wSKOMPKYtGOD}69TzzKbf zmB%e=bx?%Ht@DkI_jUl@-`}%SLXr?72dFcMd<s0f08H}0jYk<L08MyY`Ce$a0j8LQ zti%N@^iXdoQ(`}uq(h)cxsWxl5M*r@*8-Emtpaa_TSe_E+}{ETNs<_#7)c4Pf;wk| zwiIsF4<0T83<dNl!f@N8%F5nPAh%&1u?3rFZT63gz#fd6uaVb9u`3|QkNs2R(ldgA z{aa`&7tzE7HE&PJ#8v4T-VBI<D-kULHUXB)br?F&6q-Sj9pwvQec%M{fW1Kt+J#B> zM)4AUENOu@Qfm)&d((pr6)9jLs2#%R6*P)=qhAWE{Qxqeoq$@oMz|45xdBcJw+csr z7P9~n&rRTjGi}!z&LrUp!45gHKoc1=2>)ENB5C*%7k({86P=_8P{*tb5-VK9gN73p zT?L`AsV`;KX^dMMDzo_lp55&6(eWo={^W<g_UXe%4=3y#cPIK>ZG3isA?<EwO=p~V z!cwK(X3W<4e97sTa75Px(HA3Y1+)3(<>lewK1LsZ{L%UO8H4P_%NIAxMa(CC1r8XF zbmu_%=;-Lr{kflX&c<*4#xE0YdrO*Rt>7G~XIC7G$uPc<3xf4vXCN<ZxV1CBVOPC* zxVLw9cJlbq!=0_22lwyaTrW>vzM`cU=jYR@7V1~8UXd`{Vh(^@03DrUfps!&k-HRc zbSEk_jY^L6+~iQ8btokN@Zm$u=_`)e-qW)MfAHYJtJ71=Nepwkoe>nr&c$#zLV_I4 zkTbL(H@o9KBwS^mPGcb9SmTXe!#_F<A&j_h=vnTaZF1MC!DoW44Lz?K@0^n!y?S<b zhT+SXFG-9JnyO0$UnUT3)Hj4NCh2633z3-qKKty8tNHo^uni-5K`F-Uz&U&uwo0Ux zX%~1d+$!8n=Iz8eSki%ByQt#uzpVM6v15f*db=Sm290N;&^q8E9_V2@jnQJsJEE@% zE4{W3D|vGLiyQy5LQ$c&OvAC{jHaly2QO>T4W<Eefq{X9k;WfZ6x9Vc*H@QU`-cZ# zeE!AB$*bT0SAX!m?|mQj;b3&If57!v#0;HXU7ekuO_(4N)fY*ZFaBP>cyYoUoX>{@ zVK6TjJNl@?L|>g6uRSsPQNzU7cM{(!&jL0W4Y>`FHS+DDzB_=3nq6vHOd+zpx&DzK z{*j~Oqrqs*d6>jmnl7j4UXZ7385SEidgfb6x$SExpvh3Vtp;$`c5%19<v_g{pn}>i zsIo~5DK}HA(IM_DL;b_Nj%BS26bcux2`J?b`l|ko9e@Ej&|Zzec;W`i90VF|@k9V% ziAEE(x@Ulk(L^PjOwRWfvM1qdR~k5hVqP(Cg+8m6oT4TD`M;(=Q{Tlqpf0Omi4VYi z=1O9<sxG?Lu){9$1&cQUewa6A4D(6XL2FvK)<RIq9Z=;NWH7Wm@L(8k>`Var5q)|} zFBEEP%9vyYql_Bs*yo>rjt;^YnCyr+AaI{$zg<orB~rvf;*E#lS~~50Jp#S?@kbvN zwmG|kxWHwCWkP1iIC*F?`kslnoG9P{p1jE(zScBQV`i4ZD!988t{;)3fFJas2y2>5 z9n>JbR#(~;*|uy=+3bd_4fJj3_M&WkJX^s<Q;?ao81z#!8Oxyw3v0BRhJw?;kld(+ z2fhR(36Id@3CjM@9-zsDr}f}^;TfQYD<m$)2C<;_5W!2%wlekj0j^CQgWT99)90vN zTwLh0i1GdmRgRm$n@wCyo_uH>umXMz+_o+gI{0KNS|6bm5CYl@MXd%pqy+849=bs8 z{)bY;2@+`CZ#AfLhLP!Q7umo0wM+}>yCKA_L$d%Oq*znn@sB3dK3zrTsnaq^Sl^&s z-XJ2x778B{?-vOnN+>)vrt~>u1JC4$``ar^;<$<JkdCQPoTY>|F(?@C*q|Kx?fj9z z0K2wZ==Q*eE7CzCHweMLejWE>duQ{*Cl9~+)h|DO{E)Nga^w2m@%^d307<_OOker( zF;Fir_0H{JsB21l88)~iSq`YnnTF!--WZBL!CCZYvnz%i=Qym`sQB61==_o)#pt(k zj-u=SNB`shgL5<fH~-P!M823UwNIrv%?~`Pu(2_n>iUj{gwppLzdCtAXg#KVGn>xN zuje=HefRedceY2D)A{A)d^DcSXZlbgyJLEo&g38b&;yrOSCsLC2bK$NL!29r_79kt zgcyy7)60wJ&z}?e;OG!F9AfBO9m9;7;$cr4xf=8v{h)n(Jm%xKUb*?v(zy<kEHA7} zo5SIl!9qUt#CW{RwV+4u-McrRmHQ6i;wyoGo;!u7&$-TA3nnPei4MP*E;!kuMCMqK z)pR<4@#2Ng;e&zhzSApx(IClylamwtU`U=<(@Qi7b$onGA5JDCLepxLasK?p({F$0 zvsbU?vw8W15<(JlW8qOo2%Ip0xo&>f(Q?x}fJbPpY-;~qILe!YdBQDQ-)y`}<9B^J za>hdw_YL#!1HI%vai<}%tK?lwhD!r|bJz;lp(zMIS~1qr?s~#?x4AtujE0?ya#|R9 z2>&<i)Yvz{Gg+9_wDD_S`ynRHC!c)srLTPX$)m@NaYjC4axmOIzW<OZK*CR-eSUCo z@ZpC~e((2w&o3AS6sT#=7CYjtO(llUt%2^63{<_Mr0=CyS{l#uE9M$l>Q%h$)6>)G z#ib{Rm*u^^$$Y9WfkTH8{_NSaFTVf9AN|oEefwK~{QR@$_wGH|yxBOvyx8Qd9M5&D zQSr)M%(dvG?26`V#UyX~9OiAur~9)DjnCU|zhyF33%XUTgU1^UNpmDn)+;)JHqwXs z>Gd7GgvX_c>nJ!-h9l2NL9pC-+xDg$+oXWC!%Pc({<oXop>5IZPY1dU*QC>mYX-H{ zH?v%n_h3xZiXvS^R&*nSig0utLu)oK>znnH$w2RjcnD(+(tkT{&+q6atd>?@<+{j* z*F~fDkZS3$<v+ejKnkgujH*NPR+(uY*SCwl`LeZrn?q9I@odisZxQo1Vz!x5A6u!k z)r}xd0SLL7GG!P8%pm3w0{|d*EfFbRPv>l$_V*6a^p=Tr6%)n`2jFMVUZCmKZ!y<R zoC)e!9$iF76QDy8bIY9`n*a27|GBbyXKWwr@9|Iig__B?_)Gg6rqr(XTJX1;2I+!Y zA5e79vei(xbzuE2(vKOa8A7PK1J?qFhN9WZ5Lm6QZBY-PwTKi7&@|95+$xGq1@}W= z{w)(bsZlCApbDRMi+|@26P4<&v<){aJaDlKvMm~`CfRm-PH-tR7CHbAc4G4yc47t{ zCKAZ45}?Yo3ruPX&}@Z<afg7q)~KhJmEk?{07Zl(1IQ{Y)}VG+Bi#ZQ4Vr0%H-s~J zb2!x!EZ}C=z1o5^G_|c6V1*i`B2X7Gk8Ugd26ZWP5ER&l4XL&R(?)?CfK#&bFwm2s zcrKEV>cT~p5c&lchO67b=_;;g499sqw?)gXq9>Mv+1lIPyZ3+%;l2IC-Qig8_wMM0 zFc#v$XvBe5%bE<dUd6|}^;Wj_ptwV>?}v^X7=BS!r1)qtk)(F5Hx*gZJq%$+qv33( z=aVB}sboXgi2vA+t$YdAZ~epnlv-{(+wt|!M6VIoS1)z&#}wjh$$^H!ys?;WEauwT z#(NV`;?TddIlJQ-XE$|$jQC&s>~OBF4I=bu)G&U7g`Mf84yE(B!kqD^OE$-3zOC;; zq!oS(d^XeG2rHCe=m|XImdz(T`3-eM*GpaS(JU$@kL#u9R#+V|$0aQq4JVhE)8>wR zqxb4HqGWc%0WCTcck1dJz0E~F^XN~y{qpjHMk{lD)5c<Vx4e@K;%mG$&Efa<4sb}4 z_~BrVa55S1>npO)5YmMCVya7Xqi-gAb#gYF5vj~#GFK)6^9i-ewYs=(ftH`d+sgY8 z+1O--Mi+PG<v{-Ka2FXx)CeQ=Ev(?H^8>)<872Ifzl$>VFacgCLsC<Z97^_P29*1F z^c_RfeMpNoIECuh#a^9o>c!{o?&QhiC!c)j6SjS4XQwZozqo(z=>GA&`E<sJon1|L z$CKFW>t#6&HwGBY@@6|eQo-b8)kMJHo5gRH58`K&n52y4?V%ovHcvKN@hRmP&l=<m z<9M=TDTU!+cW?LT_-Oy=Agl%t?mf6XJ;T#rXZzKwSIqU}d-wEeY5Ax^^g!<MZdN{_ zScJhO-$I|fb<q>*!7%C4_2~1{Y_V+XaL~Q@y>}M@3l1wS8*X~Z3M~roV7O?siix}B zUH>IU2fcpERBb1ju;H!wdN)F?nUp()8B0Khu!N;AS3eMMKnkv{nfHR%`f9~x^0?SS zORY*WnYRGu>B0SzMKe{geT`hj;DqT?>aEs7_d*+SL%fY>3hKeXf>?(6w?)mgt~HcB zNmQ!H9P#!(R0=R*eS;RAO`V7JVA_0!1J1zr?>~6>@ZrhHNxbkR&E<mIwD$RoW%dKu z;S=W$gaYu|WeIRB@H0REbA@|1lt-XTDVhOb`VPR!bmZm67QBSy4eZUZbI%-Cbx~A1 zpemh%RK|~sYbl7NN;2tzTEhxiYlWnS4Aud28UnSNJ*1x+);AMjiy@SeWML|VMPZ<C z0?bjilW0n5DH4yT&=OM4z)Bv#*ou^-*8w`z8kQt)rVFalxsmcNQeV?1UYbQhlH}v6 zwT5=yqG%e@Xy9UYj*BSMKbE*?b9mnf4PUH!dUp|~Yk(g!=qPG~zJ8_(n);@Os^1uR zAT*$LE*kK~-Rf8kqY~Fhq19>%YE57vFz=v-#Yh<Mwn|%ThJp-{8+4A(LRJG-NX>*L zz=lOy>6?N&B|>o)ihM9cfgF?wf5`XtCJ!IofAr|V@x6n+y<JYHjKk%eE$KBoQ2y9_ z#N&i<?o$U#q8qNxmT~%JGaBEH<0dnhL5!m7(OB<bV}c=BX?SmOrFJ;!QB-Epe8~gs z$$sJ|Rz3s#o4@gQ7>c8To=mZh<>oPmy0P}d7+_O-z0^Beq|CS@7xuw2(R;1aXbByz z4+`qLsBdP=c&T@1o4xhTY&!M6kQ>orK4%}!^u#Ua;hjNwz0!S$D|yp9{OX;pO?|~q zOr4Sx0b}cowg;wq0COXYEQz`)#vD{0H#g(a#Qh_i7%wEul_HQO99h}u!{~K0Zm!q* zRHV%3`cY-{W4YrTtKX}~IZCqP_^sD6)EhhTO;>D!{VX31M1f2$E-qmx&gb+R_w4Jl zQx3rAb3NEj<Mn*CF1-KrQVOkHDOy7Lt>CWcqEG(5pf;@oy<WI?Lm3M6Y2&ajB0wkA z-WE1Yb0V6#8xc_8il-!LB8v@EPFdn;&JE@a4?PjUfV{f8WZU=R#Y>LCj4{R`+f`1& zlikVr`8jsX1rEb_I5;@)<kHJJv6z&<&Fvdefe`p*Ug)?M&rU$ytGQ=JmHjYNAYQ^M z&*QiX1`vWO4uOD)vpe2>@$}iFhYy}Te|~v&@%3+fZF#-;*0;WWczD1d$I6pe0dC5( zx_Jd_3M}u!wOwRlZ8Rpfy~9I6pP#Vpn$v1J!H5N+yyi&$eJR-wDCIz__*$U9)_-62 zeg1vEv#X>a_08Ox_oUgU&lqtrB`vt?V63Cj8c6+Q-V0vqs}+~o=VA*jwJOPE-U66c z9)v8KscP3;VQO=}n8~6h+B*1Jci|V}WZ1ww4wJ9Js#2J!suk)G$X&%9lNAHFmL&z? z++zTEJh&FRoa@(o{GiI-?mp9PxzvX}S>FIRQ|T<Uj^Te0Z-x@b;heL*#Y^NRRl_>( z?*P2F>!d+u4{dc&GNrcaFC()D=oGF}LkQ|_GT%aNQp4uSCr$lY2<*zB2Z8xiLjmeq zD3=pCOic~=E;5i|O<bis1G!iOp#kr>iEg-*M1%rMfSmw@=3(%eI`FBJK*G?3i7qdz zSaj0ufNlX3bPP*Mp@N03Wn||~1tDoL#MdTcASXJSB!DdxWgR?LUx`noADEg)Eny*m zca__iRR{@T34GlZ#HEN3q|lmcVYMzWDO@-);QRDjuyW13A+(|dFr*=|SrXzTpteA3 zL_-TOx6n+N0(`od62nEyfrWH!P<e)0XgCwgO$|10Sxi3$#Y7P`8`iFVi*JCIk1kvt z-MgdKX)NzQIR5a%C-)y5?e30-qk$h~VC_c1*=oBKAgIr=mO}yKR^yyAV7zFe16h2@ zVFbE9IM6!}L_-sEz3s4=aknNNBu+9E1SDL+zx0>??Z~;{H-7z>rO>RUP9rIy(~12k z8&2cP`SuR~jp(L%%uV7^aecFh&FxZji==1l*yqzJH(<TFbbWIXPcn~29O<{Fvnx`X z&-Gp?o}pC1kR<10;uAS$IoIxn<MD8)CygT!<)hQDpmX-cx!y+hOn08Z?PZ7}fsgaE zF6-XjE)1Uei#LpEJEj8nSAu$Vp&9r@6I;#~ae&vTQ$l*+T(3lMCx)UE9aVmq0iCPq z)pUBrNf;AyW~OL_=*G_(n^lXYl7{FL*XQS#r)TF2eYMbSKf@T97cQVy`Et12ffd%E z)VI-J^WNb2U6kr~MsZg;tUJ(1g<9>c&@%7y(~?s(NXbm8SVhVkM#D7*g5V+T12AKl zVTR!H^5W&olg~f@{CnT~?2o?nM;v{>_Vuq%CgZdCeQd@X1CpT_15dyqvmr*VK7K!) z>GK7yDz9F}OGr#1qA*HD_1O^hB-6~Jlk{9`1rR&YW$ZyUQ&3>K9qjLY@bK{;{;NOO z-{1Y@lP`VeJKv$|qmMp*`t&I-98|3Y@d8$y$yIXmyY#JqNf#+CO7Di2ABuD}{otZo zhmcE<EsaLs@=#?Hu+V4~-yB{4YtiR_?Ex5?`ets;d(uR~DCI=Y0hl6z3>S-nPhcTw zG4BPh_0@{YsCTgiri>Y@rB(kGxC@x42P2DSvgp@U6EX{w@+u^cn@bn&_Actr45!<O zAU-7t7NxAMQA^B+*5+b4XDMTXuriPX4C{vHi`5J(i@RQ;z-j}=qX|3{jztgi_-vzo zj4f{Xy5qCU(s=Sq$^jK35aua?+CNr*<L7?X@^{2GdyB%hQCd~nvyL%J()#d>5HdlT z#%w9&Ko)(n@1muj=#x7c*Vfe00X_@2s@YYe_yePOiTe$nyOgS;+Q1UWt!w3_={L(Q zX)#dim}dSk20T?}5*S+Fn@huTG@&kbffcoeC8ZFs1lW1afT9$r<t;Fsm<;H^L!%Ko zB%~y?UIWyOnztWlDMzg{$%qsk3$>isU7)!ZeeJ?q;R5NTPv7!7kWD}-zcJii81H`U zIW}Y~t}KTd7Dhn9MPNQ9Xx0*Fc5l`KH=nMB3HP_HP6eptRxns#p{WVAEAt7t2-qrx z(A2LH^?-RnXv)4i?6;hN-l6^AgU26!_`&|cWG9~g4d0wp7utyGt3+6*IXvT8nbWU$ zQiZ;^Ne?K>+s%f5PRW~3?Bmr^V%-df`ra&UR<)6x&*pl=2S5IbCijLCYQ`bg>(BrB zpN=F8{_#Kh2MpR}yoL&VWlaGl&X~Az8$NaX;+Q%Z(gIrU(cn(N6x|zr!e_p@vE+|a zIqt^8{o!Cp#+=@{(e3T(SNr@u7g&=9M^LuW`l#gg)^IeEpLi6RLobPk4jrU7T_fww z=35?_ZaOOK$>it+>eMw&!(mWz2%70_`dDA0tJfOn;6_u1F!3m(+K!ASbC*Rt7!2bq zplcESbZMeiANj)}PGTZ#_$}+fVCUlE9RK>ZGySkCD&@1pF_3kD3Fr;^voj9wmz<h& z&sXXKmLyW>Ug)B0Vyu_;>ytp?-Vkr;r!Vdg0QE@YEqYF{+`>ey`L?iOn)mr>$tfBh zfqg(>mGOPHw50*%jir8yjG9eOt+VOk^6K*J^y0;f7ysG+_xJV=cG*@kh{lr<%woPg zJw2UF_86-g=vrPx34(`f=B7@yEaeM*$H10;*o?6ni;%Y0j98y}8SR7Z0Rp^`1Y_Py zfkB=K%`5MC33z{R@BY2xAN^B5`ts!Ecfa@jk3Rm0Jiq(B@BZ+Q{P2sX&qI$jMSuD( zIc>J%*Vm%y{wJxK|MI{o>0&gngozAgh4FfVf?*!Dni?_-lyaa|Ow@)o(C_oV7JdHv z7L?RCb8Ft?rr*EDKea6d7E`FxrYd_c2C9(yEyH)jYkjri_Pqlf^Hi|fZIYThZw<_E zJp{67rm9_k!I+!S){p?%pDkFYi?|Mgi^<otM!vz>g%dCzZUmMc77BWgg@#%t4n^d3 zf5HP8io5X!+tt;TzA<EDYkz<L=;#>Ao&m}EId^|{3pzrh?>o3wu;xY!-~qSba4$H7 zP2Sr9cz2>if%C3ViYYe(O$i`TGsx=pC#+zr1ZvU7HLz6|^o1GB&9q?K^guT`nbZ&W z1r+P58m=`3Yjpt5p{Zubb!A@D^b=vrSOK*>89;k2anVQxGay6Y$`WclM65=YbzDq} zK68&KS!)m3&n=*aj$uhDR110y&lYO43eUijE>O0<VIC{0V3H=JRLPUp#gyO;SLQ7@ zTxH%3N5b6pebGb6wb24Kq2-~5ystxDYyM5}0~;FL;7J(9nd5=xa8X=qxT@xXiw+8C zaxG8Zv?#5@wJ>=R>ACDlBNT;FZX71){*)BefF+3{ZSrghTX1c_2SwI6*N`2l>MnA4 zxc|WiPaZ$HKN<}-HaT={Zf!F**g<kS+VyfwAbOJXAx_v|V(S4@hnP*LZgT8C6^^3b z>AlhSRF&HvJJ}n~oZH+9N)ln>hFAjq^MB#5P)z*J@BA9k+1BDQbxad@@L2U-iY>67 zI^NRfdfBVv#1{OK|MiUy<eTvbG}{}ROg{9`l3h9H&t-hvH{KRqEasdQ*>-E^9gWqX zqEm*$tE)?0<xRbYMf!1Yr4{i4LD&bQ-8ohSrN!<O^kD#Ua(3Ebt}(*_8)f`c)InVx z!#tHw>}VZ^EMtTw1T=bEo-fWWapHcC1mv7<nZ(b`po353=uicJetr%e#qafF<>-Kp za%U16dUZ8DJLUX4jc>^=7t5YAPz?eBm@+gwh!AT~syn!&>g{l6h&3pc?+SaW{n2$G zB{h@$4*=V~)<a7{Ap=ecSWeN5B`I$h{TuC&8kDlD7>X7%Mq<)2=C>IQi|hGkpMC!O z|M?#<Y=?vK)#dcy;NZc72cZVAk{>1=gAuBaJcL6A8>15qrVY0!RW6saxxRmOzR<V@ zEGs+PTYh%M$uLvAM!kIb5`Fk_d?h<P3Jk%A_m98#{qKG9@yB2Np|5`bv+oi8{{4IZ z@?ZYvdy_qyK;~*?EFH`|#w;<&9M4FS-T|4fL#gf{E3Bp-yc2x^S|02Zz<cF!7pYeR zNK!e2!W6TBg+{CRhUogok@*(-{JVq1tWq<z#Kpc2qWNJ|sxu{6{;#WySl$KX*v8lh zh5wQrfSGVGYf-CZG0yvIkP2%dcdH6nG?T@+LkTH2G+Wn!TV>%^QC*-FFp$mQ(+qG3 zGnORqpS7Ut)|WVez?Ysm!gc3f>6Hzkl|2|doRAFTt`3jFo_+>+pYh@^wS`_@UZKNg z07GuaY&1~L1F*t}Pv9u{N&m*b|Fb`1wRePG+AnMyrEA=tngQm?EGerYX}QfQgr~pE zIPU~I4|KYyqr3^anV8biM4>hv%6qJI@CaR-^5km@(!2$(Ywg(-WY89@38ThGM;X~a zre;9q*@YDnj*crc_77ZT{{TY^?F4y_HcLXQc<TbW)qo|*Q`H6eWL2mOY0?EV3Qgt$ zS&^sJ;M2r3VL33LG!d2MDjTJuX=6sQB!!F|Q1_cbl^a#cZw5O7tzsXXhBe>NWG%Am z+%y>SXV7|F0S9tz!V;8W!dl}bt6ZBruuk@*`P8u-o~6y>)AH1GZ3;p9!5YR@6hTI* z;VR(k)zwdgx)3@y@m{UoyhTZe+^tQ{Qq1Z5_l`e!^60_+BYoC)b2%F7y<Kc@%ISy| zm_y)FpNG-GPepxwzkCqZ!M#vl&8Bk47Lz+4{s-Gs&KGkkwN1s}_7)utD+}%-+V~bH z)x6YukALwm{nbdk;J1J4A5g0|T-kHz%Oz>aE#)u>1A)=kSPh2oi`imRZ}zGdien|D z*I#$EkyTIVLx<X%lOOlSt!*~mmzNh;m*;H7alFuvEKSi<cZ5>2h7GWv#}7os%w==z z_gXm&>-VClLP-tbsK2$bqkG=<Y<|i9n~Tq7q4N}SlU8HJjZn^Uz%`<i-P@DNm{Enk zhV}J=RO8y|AyADi4zwFLv}bE$i+iYc=ITcEB!3<V?obbjv$M15^wNRspXe~5rmriD zw~?hz=cBJ1w3elt<zjhpesOwwetvnOciYsFgrJH!!gNzxV8}fG5b_733$zaP$gH7s z*U>(G51BXr>+{oxx6{584sGh|B8LB+QdJ8r)o+Yj{mR=4vx<_23xG0`9%W6Qs4}gY zY>KY5-j>xL@FRS&=(0D6qvJL6Wp;3Q^!(YgKl%1|7>(cm?q}y`=MNt|B(R=gU@|Qh z`o21u=`_o1#!z!!{o!Ga!%b?Y@d}ZT!J5i?jZHIxDd!iK$Pmg*gh6K-Upo)aJ<bxq z<onjQ{_x9R`4STi?_c}+*VwQ={o)yubPzwt#$3?=kLRCRGie!9QJFM7U|KUR-1hLB zVXdF+|1Q=`W6Jx&m|_mJ4){eerfXDKD0%pIwuM%PMu-bq#YEqHv_8x&ZTv^6jb8cI zw$>jmNJaSzU;dM@p*C6rnq0UFP3|_AaZ}b01X8OZ8RLpIRJGDCF*4!4%zrSv)>kL4 zhRRw*ZBff&T!b}9g|(2oRfQ~?$)aw5l_V)$2lc?KDHBa*9eA{Kp+`oVSRi>bb(O(w zx^NYoOoo65O;%!9E4bTn-Sg!$mJ#%AsPWLeoV3LqIUa$Y=!eITc6WDYv-!)HFOhKk zolf<QBwQji`8UQ9`4m5n=mezII5%AT@BPf*kcW4M-T}s)QDg<Bm~t~6wF1Os=H$q@ z5vqky!wLzu<6XE%x^OQTMHFZi6Rh}!3#e-Y&WGsXNwyXufvJ_vBRA6mSJ#Y{6Ewk| zTgZM;%LBfa+`Vvu+%y^8mMWkLRlG)-SS|v1yjfB!Bf*b_E$HiB0xnv|CeSWY6IfzC ze5?ndq1GfldM1<Xf{8&_kX2qFguX5m;Y|~kr!e`J1k_y@d6kr0MTo3I;yl5{g&xwd zW(v9Je#@wf@V5q8+hY2V>6s>@y0-y2yWu#bA$AK|Oih!Cumv7JMy*B_jCB%7+@*jb zIY6VNR}I6oz`23iKSk4EZuKoOil{-6uD+65L;)95PUeAYom_NQ(HP*^r?IJzm~I^( zA3b<*@95|NUF^nVeFGM@Grjq#ZxUwhW}wE9&<>KlKs2rNGn!Nl2E(hXtHDsO!MTCN zpz|2sdwcte9v|T22Eh4?i-URDUqs*H2b#sd^q2pddE?i9^>5>cjR{qT^$qyQM{_4K z(fx_jIA>4JhT1CYP`AbTU4QY_vJ@jaR-CBCkRThK=~PcC@9qvp<DKPlM!?Z%aDH(< zo9P3D?9<5+hv%mk&tJUU)2|7rE9n^IcwhzQw#VI$iQ{H*&FNuIuy~-u=^6JJW>ixI ztOM?FgfK|p@uQa^w2dfl)L>|s$1}>9=r9l_`}_Kx2Kym83>OQY%wN2CadC0(8SOO( zlf6BCJ2bA4&<eciZScq&30{M_zPPwNJw3g+nBtDHV+BXFe~R!4gaGDk55Rrs({IIn zE#5kA`S(3QJ<>$KO*<r6mCO%}^ivnRXvrxWWF}g{salv-l@9f{3XB98!1>fK4>2zo zRE!bE+vVleXP<vI9<w=|oSdBf{_p<*tIB9J{N3OE-6v0;FhtS!p_dhuDYK&&)UI%^ z`5BJmmZsq+UQ3r=k7L=<n2uF<F`xMWTy$a~Vo|z(|2{={B!F6Uh9mtH=k{QGJQ@>$ zasJ_lPd@$HH;#{vzWCyqoGfEiX9W=ye&c4jc1$R*b$Gkc8Gc%>>hA4gy|mFMcNYPz zMu;~$K@&UP_2tsAUV*&7JDe#{HVrH>TE#>f_Mz+FObdN-)+krCXv?AL9dK`yLZI;= zN>!_tE}}EhK~BG64j(2(E%jT5?}*p>YR8So6S@c$!F)=ZZfm19=|Ub?6|!h1i`@QP zOt~50O8{V!?|URWx_S*54p13Z)J#fh_#NO<2-Kd<qmcP<sgW>QxcW>MZqo>vEFKRa zbmS9TisN{pB;M?012DLE@80q8z5V_DSFc_nVM$b!_=bB{EWPfgh$R6Bg~Aijo()$a ze_sdS%_ol^;?bZ?9)_DFjixFoRip)<DI$r5_x6xO*8tX+SoClG0Q1_zt@B??oCbg) z7Bm&y5rBh=c_^>~zzT{y`c1b1FLuPWCPF9*p)P&=8x-X_kP;|Gn;4eYhJYef5kbjN zv;sV!%8WIk9!Zv1Xt@G}yk?+oi;?;OKNJxX7af!l(q66tyz>FB0*pdCflmssqKoLO z7?%?$JQC{|c4glF0SY8QMD%gu>kbe)F^>%lt%eQ^3ig)fmQw`OnkFc^7T!#nV+*GG zn$6qxA~$T?1tx_H9ZaBr{Amb4;<R04FHVz*;wriw39G=#$%#80TD!{rG053zLyM?^ zt@3(Vf|@&od|*J<x(e8#;VLNUQOqbvTt$Wm6X+leQ=t}GUgvKQ20cJ+O6n>*0rFT} zDOKECQiFW3_1JKc%u(j}V}&koXPOL@Jk8gcAhCavfiWKnH=OxymO96}V-Y@h@Zj;2 zhaZ0UAv?|o5AF{~J0~YEw|6!U4i3nB9-l--Z84WJQ-h_2PM}%g(bKBj03si~(-N&N zS!on)>-rLy%feJcNW%f+l!;1_S|%ojj4Sjp=V10rfAfEhlf-}czxodlUdQvvv<L~B zgrMJ$kfiQ8F}rcX$b{jV-#dPA9zQ^e8S2P2IX16{J2YRb;??wGdU<tuc}}C^hnkj$ zNBiT^?tDQ}%R8;p3c6q@;&!~VJ>vRr-0Wy0zO}iC9}cZkYMNHQZ$`Zo7Xlr^aXTa* zcqfUD;>H0O9Rok=)WFN<&vtk9m6CWynVx~++Hso2Ej-FLagnaYiXxh<f>4T7U0j^$ z*fG&_Pedevc+kDvx#lzd{5V&Kl;||NaWov0Ete7V%ggDrXV18WU(FUTUcS=%VGRgP z2q+<31Tadyj6==DT4HLo)K7+L(GG}GxHkjd9H>U5Ah_tD&Yym;um$D}6ooFWT>&H( zmhvi6j!shHPW^BxO+{MOwA>W5Y7>3!!q6r)1q>Q9E%f=vg8v&Q<=82@aeKe6F&t~0 z>v0D9c3bHU^lZiUpZ&9ch9&4rU;cQ1f0uF2lwv3{TpvGv%%Eq)0+fgPh~3uZ^opsV z)r64xY{Hmv43Fod{R59`7nxarOYAYvkVfdSs@b%dv1{YZ(ER$+#*L<|K6Cv4`xn3e z&;Qv!JAZZg?Qeg3GTD3i^5uhj4_>@_vAZ|Cn(LcvaALQ(@=agOt1g*&V#84Dd=jbO zg2!7IedE8+kHdLv!;`HsYYw_LO!Hp<<=;0&GpyGmnqJ1O87@}TyesT&9d7qRHTw1I z@myLD!-Y;^GOBBS7rGQ1#{HSXgxl-r>Vk%8nP*W$vj=GlO)I^`9ccNfQ46nc%6`ek zWY!vjYki5Nb{fzk3ah^Hv!fp-6VNfTXr`5C=KqGs@nh$}Me@NX$UI%^`z*DFs{qs9 z>ju25G+VIM<0eI)B8w9DVm2GB9@eB5#<5_uKZu{&W;J8)LG9t;aok&Po(nHof>;|V z0v14)4&SEj#6C&JMIw@w6N4i8o&Wd$i>h~reg{}7M@VO5xY|{~ylE;};-dPfN!r~( zEx96xv1Y<1=Cih?15yXrzYP<0e;MJd0EHBqL6SX)Eq8*e02>`|iHxu=uoF{?S*zPd z)7ToWHEd|xGz2apho@b&f~nDxNTWh6floi7t16OF?1*9s)H+b|PhnEveg^2^0X0S{ zl+j#YO4k~xZw56xu|5n{HZ(9nVo-|&N(hSZX@wfy>sxpYn`B%|uuZoSUkLRAD|dl@ z;lfqIO8~%+2MoOZ19*ghT6jW}zqA|J2|&4URp(o1-qguM-Ch`j+Dt%ZmA7;Slc=j) zOreqb$sjZ%UjY|^O@KSoLhB&0&`7!Y8m_0Rlsic0_Fy3~&2(Yq7Ij}`F`0Bo6#ABR zHm=&{!R{XaqG0*K;oe6defXs>eLR_rIgxSp8;!Ig4|WEV-3bOdQN^c58I|#3uHO7) zeP>OE*Mnlh?cCv{D7mFgM<JNS&*GUUHP#QdqtoeZKAkV)n~ilOi_wLS$Nzu*&;4Y0 zE%>c}`1feVEZ&Ir`hyS(4>+z<#1=#5tlNu#gDbUMAL_Q_H;UnD%IV3u-T~#VwyE#V zVY59N?M^1#9Tz(z&bQ0ig1s{LJY4GSS3NAQA3feAf$1e3FkR?9E;h^DAr(1-(+|3o zYL8#e*yc1ooN&jSaNHfhU!3a~5vW2NN~_VNqoCx8BT)6*&E788MN3dtK?wmv8{JGR z$MxN!N$@ZL2d=_|O8n3{8I;!Hhgv8d5@~n`pu|QaeMg3`ESKpNoSbv;kPV^$tV<as zQAvv2#Y!%7Ge(iG`bo5uUyF>=g5}*>x~p)jK+~aXYEaen)0G%~aw-b5ik7}2^?3;N z)%LZEOWbW&-MSX~qszp#xei3G-MC0l(IX+u-H7FJuDb7j_d8!a{p|bS|NeKr^CwTA ze!*yDX?pPB{@K}iJQpo(1}B>s=H2Dh)oy%77yB6K<&{3H@XPRyDX%$#4j_h`215}y zG9vKi1_NJ@?W!3n>$Ch@dL-t9Cr|F*e>fbCCZow`pM4)sbA8eJg2Y+4Jb!VBTl*w5 zLIYtk^6Cz8I~%l$i9WgW@1jp1IJX)|@<86Az5dI;?*Xk4j@vgr-yhz#1trP4a}0Q( z@fL%})b~W!_AxcEazCu?jbtj@_1DFyonRuXn?675q1$?l6Bp$o;9?gHYBSl2GR}M8 zcWCcWaID*iP5y5P`V*S|(+?6gqvbr{xd}3PU_S=>E=Fx>T{zS3f-^AGhM_LF7O-`| zmV;H?n)O-V$wWWp0QB<wrM?CQyT(?^4pHo@{HbDLaV9J;+H*{&zxX$Q$qMg??W3c^ zRy;S!5?2B9&`9*QBVd5_-8_RLn(iR$fYb-+#KjhqX;@-Vv;-PKq(BH)S#C{tmL+Bk zs<2Al_W-UC*AhPEHM$<mAU9kzs3mmR-L}-Ig?+V#J+y>Y19ikw7bZ>ySPrG73^Mbk zz&h@_x+)c5@CM*9N0XkRf9NHIR!b+q5*Q?Dj)|-6$8gb_MyUwso*knLpotpM0dXnX z)|v)Y=>aC)TGLL_3dWjUU{bhHOLWJBH3<a8Eedu{CTulOfR7YP#~ScX#ziZDt_073 z-MM);5H$jUP!W(AX=^@_wTYBK(T7Qza%c@11hOYBSG)idhpKKZ5-R{CuBG0^E>sst z6A;37N{KW{2GC<rB;8t9<utbn|B(A|w6nLjdvtvG=+UE(KmPd1lgDu>H%4Q9zIQsk zLUl0E&(hK^Oq3<w^z4p4Xt!L<2irSH;{xj)!MO4231B2TGZW8!L<8fZ?)cNUEIVvs zb(FkeGl`%0LC!Jac*aqG+>vL~Ia&YtzwlFTi1FM1@K**qLw)2+pV(!Ssv8Vck3z<J zw$Mphp9Mxo9{^VIdNyT#k&<RH-N7l7xLp6iV5EK-jP<7OV63Cx_7H!YJ2z;fMBC{? znnBB#*GqENrwkXdz1A80W=nx+HbYBkdqglDV;|08GOj{=HjRlwmtJ08#E<LhLinOk zMc>fRyStO<^Rf=eP`}tL=!M#w4P2509<@iuYI&{i_90#EFGzx(R~0El`vqkq?J^iR zNO0^W3Q3%wpK~jo&F0Gm(TB8wKwM#Ri)LuC3W^=cY+hZ?PEI%hpUviT2LyCWjNA<8 ze<?~5q4lrpGmT`@utwH)u~z>F15q3Znr@qJe<Ro`{nY46j6OLPg;_;QUy=Ge1o~?G z+U3Q;4M__6{Paghu0IBh3b$%qeMuPO8aM<eR?Hq4{<J=Eww%q*&(4@B$oF>j+Rtn@ zWe)0#_dGiFL?RCKq*Y9=_+Q&j%~C(B?ALc-yjI8Zqqld;G7(>k<tjXrkj~_K(MRdw zZ7aU&`C$Lx$>S%ihxhK^|L*s{`|!~tRy}f$SBDe@Z+LLmnQ_}|Dm2AgNuX6s^vNBl zi#~lPNn${;LroVr{J3aprq_S@_g%5pztZZ-|9zpSS-ps%xzayL4fkjEDr1q_RI8b_ zaIJeI`=mB8UrFAy0hq{&S=AJi_JIVrUzI}R!A<KM58N`KC_vFkSki@G6GI_NYhc4$ z^Ctf{1lhKnXKpYFR{`b)Ri=h{mIWAqvKI$<)(t#iMbYpYQadyvh%nLvDZ|-pHXe^h zL%n!?@7{f^xZ!f=Wdk6e`koE}H<%Cy9w+#>6L{1p#zLiJP(T8H>3{e?h=A{k?W4nk z42E|%9)@5@Tm{T0trInG)V#qGY@xgaumVJZw~pZ=6n*F5qV+@N7M4Tl7m6s?`cMm_ zH42nSHGrmj79gx)1%P=Gt%540)m$pzVySLWhf4-TrGP>aHJO{C$~>^9d9J;AD=TC$ z<mp(hb=#q?MF?-GN18sda#Fzc!i15E1ZC#K{{H^q;h`Uz0#-AF4qazk*TMrl5JH(% z(Ua*?BNec<1mFRo<)%jV1AH{7tVh5>Gqh<RFfUwVZcvOkr8ZN7x98M}`B<K_4c+1= z`J^Cx2y|>{39bUj=}#+AEY+*FMHE7-)v(-1-i)am0+Y6>Chr}GEeXm-UKjXUZvF6d zn<^@ncj4;nUeH{)(#c&E%L+DhRZ9VH9xC3bX`pEEZ!EMlj~+a@|AbTT<Hrvk+&erx z;2_9GlXKQ+q=O<nl%o+#^I}<ktv6Co+ua~-69u9pB#Y8gqD4SDihQ)V$6K2VPPs(K zMWkH%1X~oGd8AiffAP5bOMiLgTcCgYxBdY_808W0Y&8$?V9ySr(aAw}zTDc>Ed;yy zf|Kh~KWehIO_P<5zK#OTu;g^Vxv@P^|Lct#dSKgceajVo@XZF8Ei*U4(ayGRZ^IFH zGy1{@U5Dj=cyg0VHJ@YW?CNR?1-p6&Uazb%;N><xRy~<a;Jr1ERLiSNfZ63+NevVd zv>N4Gc?>Fpj1b_E7I7!mEm@CU>pP$K_V!rZj*gB9VZ-Q2cRn8VxnJTUrdD489lzR2 zFX;q=YG=sRJO~v_JgVC$**35~Sdms}>Ax1mT@yOZQ<99)DkhMoEll!2-aA&ketP6o z6lN7IeMRc?5a_GzlhcrJ*+Hp)JJ_zK>o&5Mlof!<p(z*lG5+V!%7|s<xwtrg_3GvG z=Py40{EI*S<8K`t9564&;|aq^Ph7AvY_c@%FwZn=^+AlyZT^cv4wymB;1^(+cnn>p z7!wVk02*FD_@-eWUrV#lD_nZDi+Ou`e$Hgs+vga*%b0)k_yLQ}>FEh`$DT1KTr@;O z0-sDYge^+jsC8~(SI{c{!07WsM@7uCJR)(b<Wrl}{93%9EUQUmL~24Q|7*nChA4SD zx0=>)XM#MRrcRoq1V}T0F!{BxRb_jZat+19s+o88U|J)io5=%kSZlPH?@dy7&ob9Q z5v~hlSbRs5ZFp<GX5F|8YvUp$A~exzH9%;_;I_z=;g(11SO6eF-@b65z6I--1RK~D z4Eiv*N^e=qisJ*YZnQ()ZjX+RSzC1WZQcQ<jkZM{Loa~XDn>X5n6Q8VFDzcNpg;GE zzhH%T#5UW$!bYbU@Xo-E0p=~YLdpRW7pWyb+mbqsgu-WSDtKWE>lH+N!9`m^?Z*=J zN3(+4iS^-u^(kUvD@6?<YQCt*xyD@AcspI-3PsowH<6OMs*eW_-Gb6uMeVkTR$(hs zBh=L>csIw?a7zI^au_@#q@$2nZlRPKw`P(8hAie-*&I3hMedrXr>972b9AgpG3C|) z@UBJEMI(9Sz&t`Or5WJ1*qm{KB(wyotN=|99%k@vxEWUgd8|CNP*=%a1BXBewSRf3 z@<d|5+ax{6SLHb+AcY=>)=wZo0l*jtDG~+VRn`RdW~K|vlbQjT)HD@T7jRWr2(;Zo z7o8QzKB3kU*COmXq0*8rFrg}eB=iy9rql=PCorrTJ7fqk(<#DGWXe;^mhRDmdyk(y z{NRHR9zA+=@7~e={ytZhl^?pby}7$PiMQgpAB-jw{Zjg3IcM~3vdi3|rEWew<8C1$ ztYQ+J%N3Csw{!&(C&~E45c$Spp<gZGj}^#Hm`UIN{`Yk*oFUgE&`P73#eez7R=x!5 zw}0zb5TdEU7odT8IlRHe7I^jn7E5-s2rx&JxM*(eZ0-zpF3$9!-%I|RO{pMH8aUV) zlJ15M%pCtG+;j9!@|=CP-kaLl<aDfW&>{|lm>6uX=ohY73{`gvSGFAE0j1b6Y|Gtv zcYp5yJ?94F522vu$>sc=y!tEP4{UQ$&~cO1gcv-iSqH$Q1_((e93*J2HLZquFnCsm z6q$+W+ab>AD}2zG@%?06L0NI_;Qb9)IskLY^!~k)OwSlQ0ce7vC3vvp4N;oifup=R zNUv}WGS7tNpjBK!UWh>QHUX9-x)P&LPDNo>(b89>J`aJu+HOA>zI?z;(rn`!!d(GV zQ-N902A=JlC4yZL+FmmmV%O*A=S)u~H0!`@wqUTGpI^K>IhkEvvWOn+?GG9MoK2ZN zdIic4KIrqB<gFtx?wG6m>FcJ;Jqs|raR|7ZqoWzp3|;e)lRoFSWR^3&GsXCVfP=$> z%ZrOAA3Pq7N34xcpMAj+!Ab(q!3iN?aA=<v)-<M)7)uhZVq(3tAANp^8!-!zI8{?% zp;7ZKylp;x$hiN;@pdhUn^)<On%08~WKk=8Ap5XuYoJ`XKwVX%WB8{1hKa12d1nu% zEjW{sPxGZ&Vk_FpHo;uW(VjqV+J)xi>aD7Uw)vWM<4u8+M0flroWIurU<HayYOIiW z6GD;IV>r@Xl43D#qO6rbPhY*noUMfxmpDChjNtT(Hy?lrfkiRgQZhN@>;ax0GY@<r zV36SXz5NdG!NI<{`bs-wGQd2P@K7r|xy%e8u>!Ch>MCG;BbUz56|C<W1!J`|36<M? zB936?1XWOkz^<$ewUAomu0l>%#!D3XkpL?g;Y{e`858ycJYo#4wiT?5+qJL`a50)9 z6luU!H3M)9Z{?I{Vp(M&a6YMN2AFSAKwB`O2*dr-mx*>UW;2RIpyohbpqV<jN<#w) zRZvhw%?rseR!(z5TQd>rB?JmE=s@AQn%1`tKn`GPVGY+B;l6-|LlL5YPxk{7g2Es% zYN2^xJ|YV)x++nd)V278QVU?H!UICL6oi)Gs$`&sCFvhnlA2ad6U#wX)yOuQIxE1~ zi24Ex0UcF4K@uh_8FrDic49VYFKkj9nrQ*KFQvx@;H>-P;ln@kXa3YjAANZL{{4wQ zl?wE(qx7|++)$*$nd7<)@m4TrKBD<$H*WScpIS5-gH0fjSi})u&-4v3<qXUWV6JdC z*%@pvujg?u<c>&ITb#Dy2&U(b*qeGGvP1m){_$f!zH$Kmt$+CUJsL@jTJ+rsF2cB( z2vKWz-LOdyKEB`z<#Nu9Pw4m-7<=e#s@PO-Ew8t3HaH-U20H`x*VF0zdZ`b`ZZ191 z6p799a=u`n&fn&6TW=U$(<e(B*bHHfmI$Q87_DT2fF{yXD<F5CbS&pvI+o0_GEk6w zFkl36w)gQ~Vd6y%6nuP*5Q+tLk>P_|fVU!v3llFg%s5vB^dV+eHg3%16F%cm5if9X z2*G4H)CZ68isbz4Lf?ROb#<fPZq{4;<mOkh&?GBB4)6)Jp-9Ta310A3GX<`)4oG<m zeeyooTPduAYg6YA<vQUyZNtSxS7P+ZsVK}UTKbCA=ONHn+b8GRh07Hn|H1m-wl(cl z-(+;%Y;IjMDVu=8{{G%TKQQk1X7#;R`uOe6@VnpnV@BNm{=sNGM$T%*#3Tf)8o+Ru z7k$~Fenp9S8L#_L17%n;dWk_}DVlM5=C^jX=d*<>;)~rRkxb*8*>!q$IvfmMp1gYa z@Bt1UK6=13(@>8e2e&e&N@jbT`Ae09CKVzUIvLk!6>o88KX=jVC*WFVVP3BwG$v+V z<DvZfuAoEAWKg5&p?3wY3b%?r_x<|qJY6(0+hp|35P{T8!<3+G{j^G?PQsE(-qU~% z6b~!b=%$#oW{gZpuj4joRjq|?g%yyXY-TOuMXFnLH7&W7H~GIg(za$aPgjvufSJpj zg}R75TOHF{%Y~;fJEE{F3RGz)wEE<%ofzC!{dFYVSVu#)HsgbX@)&8{dE@Ipnioxo zPa5i^aDsD~3}haCRvRY+{n=mmd0D<Q*8C2z8&LDWJd{MqAgiPl`MED(Tua_)vN<rH z%2uEO@Rp<;3UX(Il?^RVCN;xT8FNr0<?bmYIEl`c9HBuGIq7j>b^|`(B~UQ%P!|(+ z(gpos55N-VV8*cApy+01V{ItCKxo|p37S@Rt@V*aeY>|Uw*<&CK>ie6mDHdXss=P* z<UwWM039=2FRIXY5rhvF>2_dmgtM9rp=Lr?vCJb(D<qbOZkedS5*%6+E2l@#b3r|R z0FngCm{{HdwS}vi0Bm9_Cy$VDj^(0F!c>r11M7fnc&P~B)^ejZrwU53HjG5#WL8}T zs$7(Dry=N<LcnTJt0hf2)NmD&wMawKqZk%~v(22L)^AYUu0>rX)xxaYU=pr1G8S}g z6>v(74L`HT2>IZH55E5CryqUv!STTXhhIh&TfNC-%${<KlPdjob2A!@IN!`?b8cIk zH=7q%m+UiHfw?$(W?0{B%svmdUbSf~36KO4RE#68Hn?;Ne^&5?#fkVh563RoS6n~a z!^xbxMPw~7lG#lnX&r!n^Edt;RWbI3Y&blv<K9A(0Rt5^5T%=)ZO+(aqp!ZBH^>|Y zt#~8zhEpWlX&v(QVXnnYgM1{TtpSJOOHPXC7qo0Lo@{gWV<uutfH~W2{OjXTQx$Zy zc1vMA9CTcaLobv*<FKqppy#uD_l|vyJWxr73&d*7Ivlow<tT7b7(x2@F-_3+Uf;Pz z4sq@DjywYsBliBZNPVvN>dR|q^oid$CSPvAbTSf(x-pM9U5xp+Jms#XOe2JiKg!oj ztuQPq&V^bI!1@|(<bxf;vn1gJeKI5#3RrdL9SG+3N&&adOrx+u88@o#APwITF}g}z zwIcwJ&@dnMw@eqdY5`&R5Q?ZlS7P+ZsVK}UTKbCA=ONHn+b56yP}6EEtZVOGxZ%2M z+a0^Qa!mz&j9|?lBR2kS6(bQw>=xrlGh{knFumqWn5)an#eBw5c|M<=pPjNUFeMnA z40Psg%x`(sAtc=0Y~0NBW$yw-mJyFkuMdQQ2X1WS;F-k8A80kygk!j>ifM2))7Qdp z54NY%E9!UmckdtH+uu7Fk0v<LQW8;6rbsM!7n1__CdHH(t>O=iK0hgs?o}2fiI5I~ zcWq7ka97>iz>5-0i#oS=M_()Y-1q6neX3Mtl2G@aQCH<*#*$>vH=hlxTWTGsnHpK; zVl#qXk8t+-1F%Lz1B%=ex>Z~(=f4g`8Km+Z`qZ0g<&$X3oBZDjwG&fPf=NgzK*AKs z7Fh09FfUS$5Ob&$nk}s*%zEys-2Nycv`!j|+1R*u?;Z?m&TycgO1XFMKAQN~`L{X% zhnXM#Dt@2<1;AYu-fmfE>>SDaI{@$L0Y9KTRyzo4Autam19d}FYfV4{pk(Zo#XAgl zP$q57XxI9ILM;tOnOdV%G;v|lgJB&^>JY$ux`MHObhJ8`JiTRs`VNtXwl!n_brndr zz9coMs+B1wTr^#)0Bj5JOwkId3C$=e2iAwN+@OufQBJuHO=&OGRY}bx(8R4X!If)m zZe@h*DN_#2HxjbNR;KaR5c>K#L?o7@!liIekS*q19Rmqw2#Jn7X(qr`vk<i$av*QO z2DJvtMYIa43b)#Jn*j4!^ov*s2@PzB#O6q#mXJJ*`#GzU!H+MH>?^QdK(PWSpy{{> zQ3l~du*8gcGXSAY5@8{9gIZn+4J-us$wnFW;95&4A~b4E>jbz=z5%%QmNvPd!~Y&X zx3mx01T)aM7KGqp>ExMzOm0GRPGPww1oY#NKl=LDKAq1mw|4Yhr(BPn;SPtP&Fu{~ zocjj{Yyl_w_1hsA0G?roljY5Pww%%($k`tfiXqI|X&%35rxrqJQG}&o9BwzZ*_7(Y z#vi@rUYbtz^GMNHw2-j=FlJ}dsg@u(fPx3JJHPb^v=6||JISnL*v~lnVFl0!7^>F; z6gkB)82vFPTFs%2b`hCa-}&BmF0L+E2X&&<d%sLe`jhkOK(7Yqz0m9Uwx|m_VxOCZ zJSq*6r8zg7dKF-MxP5wdMlz(!i5jYtK28_2&p-Q&e`$x_*W%32E*oyhft#h{GTtYT zBQzsti%!$44C)w-3%Tbs4yB}buJuIdG&-E?K%<7lp)aKzKXL2>16@Jy><o6|A<->; z(sw+j7iOFx;(MoQH62J_#i3MP;&C!x=%-xbEnk*L#uDx4(t9TA#&mh1N44qC(PWG^ zZ5VNLXXm6R<jeCi)T(!M#L=+OpMD7Eb_OK_$ia-RQ^=Fyaz;%XY4V0>@)5eW4hPIz zxE^6^4>h$pfUnV&7=3ao3bTrqz9RK`2=vwV$u-CVE+&6hjCH^$L-23%>3J30>`=Ky z2t|E=;i|EB8jU8*70tJsYc`t<{?9*u`u)$pxH!AeMB-+*SPlm}j6J3YKJ?Xf`tIgU zmZrsG#!O?PF*i84vP7^dU~&;Z8wulq!6;QC`dznORcq?{mO9rCNh4ohM9;i>@ZiC> z|Kv}Yq0_6Y{e%54ee|V)o~hAd>s5$9nm~Vg)nZ{)BD&M-aZ%)iBbIunLeutlMV}wb zNfEdRNRR0p^+mz7W?EP;eS5ecltdHPjMIB}*jpEU?)&vio-N8?fT07SHChMGWTLW2 z*0#|Kpp+X}Qpw-6f5O>o4#2HUDC%|XfQyONJ}N=?P%EZ^SCU@+cn8@2GY}LLRaaFm z{$K}SAlCsG$*PnC7J@P#o9meQ`xfS_j0C_SVWv}SH6*M~V||sz$oqdFFBLYHdYEN4 z)vvT+j{f1HzGwsgc>s>!GG&cmLBe^uf;txaC5r4B^d@pVB1dlEz5NdGSHAoSVPdV* z_K0Ba6c&h*-6~K+A5euR)I~C*mLdvnCqn^Prwf#$KLyO82%*R^NzX{^BqcHqSR(rh z&H=Df!H|xlv(ThUS;p>%Vx*>#s%A%v5GI2ae&_*|osadMbGXqe??7E-4gk%_ORcbf zY7KZKjG<Dlt~&Jp&)%Os+qY%;ebCuw_swa4{r%mW_hzQjMzSQo3Zh(9DmAtRILreO zz#AZ`sw9W7kQ`F@!2}irAp^k^!5_c_L4*h_OM>cDs6`TC*+va%mz7zSm3iA=bGqH{ zeKw!(_|7%YI&1BHe&^)xN``QK@453g=9puSIp&znnq#lE*LHOiF2xK|s+a~8A)Mty zN^r#t3!86w04Eg}b)7PfaFS5T+nx{fqO1*+Wy&bx5X5e!*uIUAyi#ihnaBZl$OyDZ zYEB*S!|>#jY%qSy0yzZ~(F9orf-KX9x;TN<70WGp5E0AO-wDq*<ei#n+hk?T2hSxp z6y>*!ET?raF4kta6@bOA;;ac$>_^_nrGU9eb}N!ZR8KW)re;{uAe*FP{xc;oDkcU- zVjc@hDV{Jtr&MGOQj1nd>6CXpl+a(8>@n_0ZV{St+^hho7(4j;dX=eG4LCkN{A~da zbB&mv$mAIUkmP_!Lref~0@Pvzm)G;l$!lUZI_&`+_D9`Tmxlb4LYmhyH|E}oi{pCL zinnAG^M@`)PT$NUrAaD@uMdN;q0KZW97H%4pe_;!K(p)o*+28=)kJ~+`M>)=rB*B5 z?2&~r2QXF*5}*^V;v3t~^@CRQonGvU7djD^6NzpxWU2kFulG(VAVd$X%S55I-{_yc zIeYTt@%j1N&E9f!(Es5Ne=r(!ha;8=RcF)j)pRyStpdzW_v&)C&+w^d{I6ZN+3xH& z7_t_zWVEuGOlE`l(d@TxUoWnwy<V%=)5ouvf&Hq`=}fO~p2U$EdQ@AtSljzuj10*z zvKdDl8f5jfw7Mx`D1Ax3xVmijd%a=$(crzfmy5vUYRpBHHO^oSheKM_&ri*kjs5G< zQGYs}utOusIL_zzL?d-DI(+-~d^XdY5w5PTKK=C5%Zst1k9anf%kgTxfPXa}uhvTj zfxsBMm|54ctwF?mz9v*}#2E<ta|%#vq5>S7sQZCSOQLRr?x0HEj27j&nD9&t3sjKp zvAk0NKXfE$wiOH9M9w;821qUd2SknV$u?Lh%V*(Sy#gjZCS|J-_WqC$WECKps2y-~ zP65N8vy~#Z2+TC#;%9&vEIpcI;sLU`N||6?yLu^2R{_!*u7|xo6O3BS>Or?RJRE)~ zeDLjWf1BmUtY%8?v8Tn?+Oc50zc-Bqj$-P^&x-oefRmcc{P<^|CC5U+;BKd<c@k5F z)ij$;FD@?FNm!EZ2tXiq9_i^|?Pk4Ptlz$U`@R4C```WUcfb7dOYI{1KE#3ppgwO~ zOBKTC=OFC;ouQ&-nBgtjOM$5TQuIBfWOg0YNYrguKBt-3C7;`>z!mFoM-1wc1t@1{ zqcm${+$|HHPueI2>TA4%CIkgDjWWLsWK39<Q-CfL73`AF{0h8+Oq)n)?fjFol;(c9 z2r#B_%796lB`YZ#HAF_1L?Nl+76C=^D+XIYk*k-LD2=C(>ac!`0cyDm-S*A1S7o>q zqN3l~`(vXo{A*Tg-G#4MP)s3uXMwEQS&-Y!1gZCvoOKEsJAQ9G>#xAif*EAhMgaLl zh2|s?>&S$ebb%3M(!z%(b)?F2z(TTvcK7`Joc5nQd2)1g1e2nZlat^4&EG_lQx>}f z-H)bGu6+`ag^5CF2(HxZKW@|}VID=a`}h9izYp{M(d>5Gw1jG!@l=EBYz7>s@SU2- z%rfXaph)AqJ4!U%V%9_IEXW+oSaVKusfjYo#Bl&mVMDI&x@5~eHQ<oC$Yzs89(P;P zbs@+iV7d-UEpKEon7KMlfK01GsY)FdFi>J5l@(2xnc*Uk@&P0>Y(PemC>+I<0P<J# z+VY0QTnoO58n$0`z^;z!*jx;XfpWK=nGm@}8L<siA!UFVIMS@MTrsD>E6ugsYpO79 zkXLU@UP1t5CNwExhO>28-XNQ#Lp~D}<*aL2TRp7<%M%qqEK8cGq`3(Lj#1&4ktAvc z+`%*wD-hi`$Ch{^dAAkUDV#`!C=#4C7@**3yez3|LEuFPv!a_EF%>4o@<;Wi-|xM6 z@$BP|zw!L}v(ad%=XJS85(jdQ^G^}Q7w7mx7Zt>3V^%!P-;#}_-D}f^?n*K(ulH8V z#dJE;N#Q!894<l3oK~~b(#w%2i#fp=rr0*1Sg_Sv&h=?aeBaiSfpYa`v$wyBpRNsq zRir9$kL4$S^41;Tzw>whTD#p^uNL7vNyaLnt~%cB>07exwmvB363fK~Q<=}YjTAja zlvIkSpvNBDOPyL*ew>m&8s@Cq-fwY<ig<F4D#Ar79v&TIFDsRvw7LFu^*JzSX|76p zE8YI3xBl#%RPivOvVKLJXksy)O=d)xcyzV6np_NromNLXbHwj>dM)p?n$yXcQR6ty z^|IU5&sI@{fPVQYW)VWMtE)dT7P{fC5n3&;*BS-V>%Hp*y^I^Pb1t;3?yyZ$FJ6Sk zc*ihe9<@}uTI<WeKDN>WT#7WUPbPW*JT`{a<>kfs`5E<w!_nR~1KMgbf7YwnLNB&n zU#~Tis;AFG_~&{LA9!leQQV@zu7H9>-G+wtA=o8f(N8v3qU53Luvi_HqKa@iYfG36 z&SsQl-idb$7xp^`p_O0yptFK3S%Ix}X*u=2TIW{)(}1=rn*oO`fHptF!t6~!YF8}M zE&2=SN48h&e9`auV#!>c&ld!!L%p84|Lobb<KshI&g^ct_E|fPRy=>j7Q}JJ*F&v# z_Mc_!7P5_%6|@p8CX0GjR$Ms+78-5S1sj2wEny~K>&comM=bWz5sSIoW?d48&u4MR zhRw3q8}*01PM1xV_08s^`e+C(xHs0+I`;d7?14L65w*7fYpG?=YXE`(yX1F)Dv7GW z3W0T!Ld(@rg>3E=Fw?2wTG;8V0n>a8HfI+q3fa?Kw}LECH{fniH>W~reVOTOxe1Wv z>-JkdWlAv9exQ2R04OSFLFkY?ySh0QxU`}~%xz5rOS+a}PJO>BV~hR=BeffIQ*EJ> z36oWs$k|GZiP}9+{5WwP<+`_^GfuU%E(|9#Gfj#ax?0D13sd3f>Rmhqj7+!PLy!%G zeSjT`^8;YJV9Vkn%dw>N36U(3Qwq13hTvp?PPH2C+9wo|{Ubm3v(WDkb-^8QXJC;9 zWTV~Gc{71611<$FWz9p-dG{Z_I<b3JQN;qeT{Eo{I7><?S@e_52=OEUXtctt*q;SR zVU}C8!N`-k$Sqpl*8ugZ&|rgIs}8rA+Xb$b6;c-sRszbBnXV9|nS+u{1M37<m0>0* zw}Nm6Obb{(!%WM#)M?gZ4yE>qvo$2E>ewNVSJMX#z^$X4RPEh{Wm2XFo5ZrQlcB9J z*D9v~ndnCXl5iMwXm>g42^MxOV4b8!S+Wc)DeFnnrB6(gx=;vAo1fD=K$S!VqIRlM zC%{&DP~n%6ByL-hST*w!H;`C?ihq(sj90no#4WsGBvvRyKE#-c`h(;T1#6w<_){S& z*POYuVMv%PGxzZD@WqP{UcUU0BV!y<bm!baCQ+LW`!%EQ`Gd`*prs$RYjwIE4t88= z;vwIC;$wnCJ-fUlnkI@w;c|WLKgDbWx%xI;SS~I5`f}-XG9{~*U+HVHI!&(ia5C|B z`b-T!xu?{?67>AkPyRu&8Grq+|Dx=bACg1t6M2P-aiYX<v@I}gq5IXuv6!UdaJWGq z(N8J%`)Wj%MyW`|+Su$9_|edOL5gr2mm;uG#E1y>@Jf#q#jC}-+iG*-#xA+iZ;@3T zx;GjQx^gN0B&_Wa({ey3gGsu1PWR){Wx_+)t^MYFhQacdEZJ|;lv-O~>&Z;wO8&w3 zx@N@~#<z~;F>T1{4wY)_`E#B9F@lk>xgH2?P!+$$N+Nn7oD1`UAbp7>^*Z4_`IbuR zuhj10%8QHhtE)?_JUr4{teg7w@gCLYy6Lqb*rp*x2db)RsplK?EOdM#@J~4a2GPGQ zD3{VBXMs5tq_P?+MHS&n7T_9rBS6*yz@_iRJB3l}A$8XBaF`S3RFEaN!lhXTg7M9q zN@*D|4QNbCnSeXK6&5g2Np~T(h4cU_Ta9*}#bPoUzk2l*b5gUBiL1x`wa8eR4W=<u zJU)NXul6#hMenT_`hZW<lJ%)KKI>y7QZ(D8-WHs)E@+zdlx;%>=mAi@WNyVKHq@^q z>Mi=CgTv#K<5#a<qfhsM6(MWJvp3F{b9CWQvi!wUIaa2NY`Ocnp*w&~9X1kJVTQ-? z{gKr=YZ_>q3eb=V3m|W?oElN-CY!5R{tmcSu1f%HqJk_?k>3Ri*oJZn^3Y^XMY(Yw z`z>FtZofHeqO8+^lbLweL<Ku*)%Zret;C5HQAb(Q2=&{Q-+^4i)j>tSiJYw<m+tcO zLjz#g6k$NhhopsV7%(50p9M%UgDrwVWW(X`0EZ|Sjy?!p>q`?H2E2_>gv`;=5d!EW z^o@;6cYrDKvSsa9Cn+-K!z2I>Ly{%tqZ52>Z-E{R^d<wh4a{{*ra?A>6iG9IX%}TU zTh_J}R+T~4peWbPSqrFIfh+@}p5QEi#?g#~ccr`uQibf+iZlT~Y)Q-B$TS3?)LGZs z3RiKOk+W#Pw?OKODOlD9Gq+L({G4XEqN|W*xD@2>Aemu)lqVo#Nl#g5!=?i0EQ35s z>{~e2a2xM%&NkdyjlhzmhM5_OTZ7k<WvtMtOHJg|a7RpsR4OWWHfQTPL6)q;0w&5S zKnZ}TS9dn2Cbq(sl#y#WTgFylqfD1kk;%xMOc>4@i4~~KlO$0(prm}^4G&5-7!D~} z%OhhkGtG&r?2p>Gh#Qe@5}sY_TLwo*hmRlYM~~Quslomm_0k}EhI?a0*t0!@Ea4mS zoeqIqSAm~iexw_{w0W&Z28he_HrMNGq9Bfb?D2E9f2#67157K?kPM#bOQZ^hiH=!4 z^hSUB1}^@gYpK7qi!n6KHJ}mz|KES%-{<%nCJD3(qA#d#T#Y9Y&r*-bGCh9?=JT2R z0>|?1GMi-f1CUe55(mm`_{u^eCVfjicd93;i4_$U5=asN??d-H-T195lv_h++1pH~ z6Fn-atKPgt7`d9y##ijiIFlwr9@*4-KwCY=&p9<O(^FDJ%<&1wQlD#V6p@BKdJLW> zq9YnIdk^O_LhXJZE=)rm45OL^0&zDUxJYp@b0FTS8xMad0Je+Z=qtfZ?7Uv+e*a{( zT6BB*SyU>~Xk%Ytz(T)hrHc)%s4M&vtwkivKO5f?-WmXZU3jNz`jSCb<MR->Rz}ui zRI(Yl6-qq{JKMce|5j9VLc?L;qOgix+C0iBQxaqNbGDpT0Mp1>695{MD)xkIg0q!$ z7qrO)k}wQCM7=pbzxd+w&p-R@^XYWj?+*?S4_OVf`CQ*V*l#oMh<IbQUT^fH)+@NI z59U1G)<;S#AO6$5nikqne$zy3jAWgL6>^unt+%+hS<;KptS|BHH;2Q~>FFs!b-&+V zFW2m`^O+t;*IMIHL5raw6egWO+P3+DbSo@h2Sp|<AS(-)|DM3q+=K~P6JL~L7Xog` zouYSSEda_@NXtY9wGy=h6%A$m6<EMT&h7#Nw!EAIDT>JeCvS!z6Ber@7g@~6e5WAy zH@65vHVK%2lij|oZv-+zN8I1sjdHEjkT>fZ%92K?-!6OyxKhv%$kp9$hM7*w2=P>8 zm|wwz1K>j3W>_=Wx?fdjQijjxlU}bki}&gg-@=5ZbTk^x##4?`(40j$ES;R3khLV~ z)zuaJ*ccRU(5Q8y92x>387G-^qZkhIz~`C&;UE4V%cl26^Yr8xr8JPo!!4PvgCZn> zZ6bw9)=Dgs3HZpEuAr{L%M2P$W;&b2j3^i2Tc!@{2hdK9EDw=k4q|R7Goj;*m3%@9 zjh!&dI_sb`3z#59C#hAbxYUqSi@71s3HYSu=M+ReAu~yhD8GR@NM`q%S(bFxeNU`F znQxeHJ!-ymC-XK^Lv>^&6~u=XRSWHh%rODVbR8(67FQ-|EG;LBTrsDB1xAWM<{(Mk zJfF!LF7>4@XRRDz8bY`Z&mY58098mU%(7bZb9x7;lBht`jw+>!WtoaX%L`??glrN> zbpp8y6@CaNBvt_VL<N#WvEimn0XUiOhRigaH4<xYZ_pnh>+g{=AcQ5<W6!1cj~+ex z=%Wum_~3&_k52l1{R}3`IlwV$hPQG9Rg`8FuHzp)L8xBnCLw|?f<Go&hX%X)v7lC4 zw{;18m?Ie7YIU@ZbzPO5?zBWew3x3rfHo9vwXQe&aSuj!XgJNr<Jjcax*d#$IN`3A z%gRfze)X6CGGdtQY{^dfY8tPX@M^*jc!1s^Hks<>H(WW~M}u0P|L{qf_5cFqx`m`) zKG^hnU0jMJ6^W}4505z~>uFy-INWKsdhK?<+vzs<t|P!>p`jSV8Ji9NOea%+%Lca` z3<uZO%h_~{&egTvH@&ByUBOGbU8}kpa|mXg2u-~xg~R#W_juQ9eGPb{Us}>t90n;u z{NZJN5m#E+MRBjT&=^$xJPc*D=xZ=jiZnRdC^*Tt+89X<MnMLI1F^r+?&!x1udXhp z(=n5ZIHA|qo3FavHdEkw?|P{SLx*7XMur*T431$j{F)WvjXJO}QSS*9ZG$aJnSeR! z-Zmf*>Z+*lL(>hXlFdLNsY?xWw%|_vbx@XN%B|3^D6hhjb!2<W0@73HtfUpdG%^ig zoh&zSw>|ZA7qo-KV-L(#<{`rVT;|~5fH3s(@`?Z$5$$Dq7NdoTh{pa}5B$f|ADZe* z&YQHvWRyNVe8P}uC)4Wz;(iMT0|+${P~8A#nDB~aiTF<oKrg0l_2Xge$4{R02Sd&H z&9y#Wil0DZVXkQ}-n?KXAo`W2Ts_?dO6x#RhPz-;l&akiR8Q1x<ZUwxxLulX)-V$w zmZ%bvP~h%t9Tv!9X>4jJo0rpf!nMk&wNag{Il$RW=M<Pvw#=_*Gt;KJR<4^<b8;3G zj4HA~1{^V~>{}>C?0aVb0RQw!L_t*7a$9uO*$T>%MyS72`!?W9(%jR!26O6s1HOkN z<!g9w0DPN`n1O{EsjN_90TUSGQxj(cE~)HG93d#;I03<?G`*S-8zafy06_q3NjU6O zWBuB>K1}!F#Lba4jSQMuS;&}1%-si;`P%LPA0Ho?LMbT?&=O5n4(?7}Y9=t>6*18S zKqiY>W-CHp@;JTC)y;=62UX6NVHse$!la5HWuznKP@44{YBgY*)D<DLaTe!q2=f61 zk}kE*U7*wgIW>`KU{xmIXB)7YwkQhm1o$Q>BDJs~U4@bivWAP$mb1~7n}9F_CMk1H z-7DZ))(H?Wk@=Z(8#~y$<#m9pnFPx75af1E)Ik-}Y`K-tHL5^VQoxG!Bte+0J>$h` z0bp&JCPg0DW2B&BX9oOS7hw}NjMRknxX5rer@-yjfrdl{Zd8@p$|*>t1wyxw@-^5( zBe4Q?n?YF^ByIrtL<N#WIKf0J2qlJ_aGC{717{7%?CHHecpH**v6#c`_4OsvXV0Fz zeEIVD_>e7FF|6X(eLt~7sYf3rZd5X{09}Mkh_#l>H5D<IxuMr=5vMM7>rdA;hc|KH zV}jVEW`u2+ACr+eApLOG*9w3+ED{#6`o&W?*1&2`w1~z6RJ4f=bOcT%0RDge?O$!R zo6(klfGxLg&>YdMrZHyI9c0iMuYpa-{dIHhBOKNO90bTtuEy9fi66*?ps3U7anv3T zM>H6#6&1Ly*=p)Hl!+pB=!oaibvD;AJKl=b*grfx(B~12#_`D!hRo-)<KyG$Y=JW| zAtd#ud*QfMzcoeN-Upp-7n-&Ryaxk)mf>F01KdOJFx4IaCNw%)aeM2{o^K$_DSAR) z(JviAfF2RSBCp6aTtO+V%x7~-CBAV0th&>we*5>$o7WJW<oo>|l`+8I{aeK=rTKrU zIRWIAK+Mn39aBO-`4Fss*1#t01bN(nhu(Arc4-~Ct`RD4IF+mro``8FSODy5m!d=k zESxeskWF<fu991<V3#)g$FvEjS!X4!0H%@Y>{}+A=UWKgC^0I`obE#G2U^szNcEl= zwjCzB-AvJJHa|bV;D|XG9Gsk-o?nbxdUB=7#AK&o!Z%w4y$V6K9JJ0bll7)gXTWqa zF6OX4-$yAr)k<NriRcr%VtcJiq+XfHB4zWNFBYgmpx^5chr@nP@1JABp?N%+zCC-x zCSm137KfKiTXQ+R15}I}Rb+md0C|$UC){*~Ilza^+=@%-mrFA&PnwHD{04PS1r~Ux zm~8_Ol{b;IbcwpIj?Lzi&4h~#X!k2;jhwBdnLwKr8Zfg!6`Sq+y1bR>^XA<s*Rlb* zzjatFV=MEWh>xq%&QR8nyKheBXN2qx61Rqj2EerJf3jMqwlJeyYM5rib4c*aXGekw z;l9L{&|NK7z5@)0YvtkLAuEN=5dECf95Y*wWvJ^#ga8D9gJzUak+$Ga1gMCfpZnu~ z4B_`jv)9!NLY<)vtg%5fg9X6ZTx844Hz*}*KC0koj|@P=l<FOjq5_!{T9aB*H=XS< zLRJE_0+FkbTAtJbSr}Lbm~WVa<*o=#TlPuT2A!ls9*&t?;i4>H0zIy4K+}X94Xpxv zvW5*X)5v;A;Uho_)3CfDT?HsgR7pQhqmLE_$e3T&Bc%n%=A&KNp!By5!RG(!UudiU zVRIVj5J(*-E!%0h$lb5QGVTuDw9d@8@|*(ndkX0g8#GKi0fH3TZ9xNTj;aafyGkAK zvrHJ6#@!(YuoB=>)8^+CP-LQl3O{N`m7*fBj8lvcUV`O8%GZ!h0*Mu{qf({>OB#t4 z*wt=EDu@<=o$OXz*D~f<2DlX9*ZE?`_Q-(*L9)GG@96mO$&*JfUOapH^hvL;2#Tsq z3f<w1M_%h-v!)3~hiw-?1N3vkBkUs7T`d)$N|dqPtl5th$?oYq$q|q#6q^SVM)y^) zBW#HSW!%k#p*z6DQXE6|^siqQjWz;c=7vId6wxN)=)wm-`BQ&Dekt%b|K=}{A{jXp zs(I1|K{r)4dvWJSaU*=(Ly_-?gD@=l7D5s+G|n38+1}o4GNJny7w4p8r_<?RFyzuj z#2VdaMAVmPg>I7ihm@KP{kqhC+|q8KeL5Wzl7IQtmv7I`;JtqH)vMQE>2ay1exQZ* zjdNmR#zr7#F~s`B0juZ}2Ci3HMC}$`TOo+M_(N1h*VjkK$7s<zd#T*eFQfV+078GA z_Ss-j%(z5k%eA?&S@(Ng+)F6#LwwpK_V@Lz@puUk#^5nKXEL5#jjyh*E|<%NZvXar zOdcjur{7y&>(=p{{}cmrQC=_OHD=KnEY;AfL%t6zw*HU4mUhvv3ADQvOd(3?VRSNV z3%GPElEiIP_!Y@Y7I?>00^h|!z)uplq0$nP{2eIN(nL(bG%<GRr}K%rjW9E{UQT!M zD}ZSrPYTEOKzkcuhL~SZE7{E43OW}PPYa)+WF}LCDSUo*0h8&=3>=U3%{pY6idSR3 z&7LYT0XE%EYhS-bq(c<Ovbn@k)0EJ1Yqh4c36nMS>xk*e4`|C>12Kto@CDkVTJ2W5 z(~h4F3%ASvtQR`2PnbIG!En?c4%VCXbUy3#I(oIdzOJvGkiN$9*HbEL1ykS^DTdgX zt*|j$;nH%7!K!m_c-*(bBbz;=_F|Ns%`iX12AGEMdNe1eWnvd9@|b}=b+{B%<nM+n z=IRjI6l2GLc3aTSk|N`*30KKXkb6y<iJXcERn*ZR|5{0uW+rKdChRsy)op}&DY*mX zT5d<rJZ*zz%Gkxf8(dcGMrf+rx6rwl&ek=<DdV<RZt&0mm{S9(bsE-8nh}CRk_b49 z{n}jOKCLE75#9K(#3bL31q^{O7flDl2*c4ubFR;trMghAD#d&wwPs{Ow_stng22}n z0Mlr0($<ruZIDDt{V&^*v$hFP#e8p(ltSlzZUyogYM|&pa4BilW2-=j3zX836cw;A zu#0i4<>9!<wW7A*S^zNw08G~kHTs0lr3Q2si+Wq&iXi0!&bpRqw}Q`QN5Mz4M}g8T zZ@3mkq_)I>Ls6LntP@Z~>e90Q^0>e^tco;4b0U!C5y<Hs*j2u(BF&bIY&^)8n-5^- zv<~=~?HLH5r6v48X+5Qg-r;Q~3~f<`tgBeYG$0F@4=@d~sVrcDIxGp0p$U&WdR)t@ zfCWqd6FIdX>Yz%Z0!X?F6iF^ML5f4nF)V)vY?6`c1n^R#ZX<~X5-YH)UHGJl8x{fx z^t;GumdT?7$XWpO`(3=t!Rz2))F;I0wU3Vvh<m^J&5u8L`Qr5Sh$6hm@OFC&kl2OU z7_1W|s5S62NDUM_At1=16eDOB(-dJ5lM!qwR3@N`?QWw7q&Esjb+ZLol%s=$G8>92 z2$~Er0LdytP``1))UaWwh0j#sAo&yj((ey56MpHJ{^D{umoajQCPvW_wQzYg*0k4w zc)3{Q7cDm0ab{%|)1;l|-a#M}mZX6u3%}d$42Q$XWa3W*&~|imES<}_e5kKO>j7y3 zMX4d)iO^HS9KTwG8{(|J*Xi{}2cwIttJz{UIyjgSEiRT%pFgKruEDGIB7V?VFY1X6 zfZF<KfQIz4jM;Lf7dzu!&iZpd{A?q!kP|<?`o=fDL8p-S7}7McL0@;F4sZ(cGN!nc zav7e_^z(Q)c03->rg|LO+C~RMy3QEtlaYNcH~N^FQY76FGCJ@3xPQIr_PdDai^}?X zb2xiN#JwV*j-gOO`|&>$0Nok|bN^|8UL@)^u%9COUKXHV_EjAeC867>=qFp|RI&hf znQ&3YkEeetEQ3PpyxV^IpQzi&@@~#4Ft^OiMP<M=P-Fsy^c{j_2$&pMtV|f0nbRH6 zw!l9qXF%zuFCQ>td9wLPEn~{e)Q@%j==0%7?_6b@ir*R1#>f&|t>;Z`SqQdt^yA<7 zv`EkSuNK-j!hy_uT5(4r(iYS}OeCOcE$zbykYW}B?1;Mav(yuhgMNQ77(9Ob<mr<q z5bbVjHlI?3E=or%b#SA&HfU@e4+2(&q69eQ^!`wHc7URcXhg6F00Lw^=)mi)3=5R` zp*5kBt-}IY%mY+M7O2SIA1EPZc2F0Pbsw`T^E1qJEpzf%m=onSODfqypdv;#@$Vhr zxysH_43ulx@?8P2OUp1nW$umg9pG3)auIaa?`+l#KXWo+zKUyjZ~z?N56UQ*+dEr^ znb^-HXCGj%@Pv0=?@RN^lzoPaqA$BJk%aGw#I6M>vNx>F+ZtH};2=*a8UP%-i!^o~ zZCPK}Tc8_HpFE;%Km+bcw!;#DqD1ZO9UL5BlRH2bF@UY?eWU=U&4qTaERc&_x?0|J zo;1S>f#nVO`S;=~K#~*zr<uS=XAO&4ty?rr8WyF1vyNQRS=TkpF_E(s`AirVg9+Ta zFE9{MUL|t2+%6RjO3Av2Ig#bdN<1Si3}7NmO1tJ8xyZ22TLRK2STd&`cf2Q=l0BUG zvsf93S;kq-yr|ph=nDe?Cbcpw%)BQBa4ay@%Y+hK%lyi?=TeAVH>Uu36BW2t9j+L< zlc^XF!NM`06qrw1HV>F-eq!xtD>KWbRICt`mYJEh{>;e)utL&Ike2N+EYC8}VwrGi zokr&0fh=iAT_DpCS%!9*TAro;FbfZp#eo5BtZ<kZR78e=ax~)H)nBdj`C@<2efjc( z7cX8M91L4+Bt4(?c@s(qV+dDJfFh<JYlKr8MN9_D+?<)T!b~F$B%pG`$m=Vx*sS-+ zu<l}`Un)R~CiH`}tHo@!oD!EIg&t-h^6j1ug_G&LvB#3!n=RPi*Btbi`JGOy+qqsY zrkrY8&33n|7ZVa(&87>&&VTby|IetN@xS_C{3*I~Io4|=$i~Fe=UK#Vc<gdA)sny7 ziw|`Cc@0;o1twfOCM^~Pv~5NS93=4odgw1W8XQDxf=9%F{_@K&v2Z-T{NRHRzWVB` z!^1;r(KU74ab}y#;d(Zk%;u9`uR9rEGG4u&#_no-u~}aa2L1E%bFAg8j83_<vES+T zIXPo<bH9Th=8Nl28;^~+Qcq{&cISG(DQh(Zdh-sn_JrT~jo-k4qobpCTR#+xd5mDM z+dsd$q!dI?V}pug{qgZ3bqS{tChM*tL)?nTXbXQ59?oWrpe|nj=pX%m7=5}!6UQe< z*o-Gp+3vM3$Cm`ri}~vEa{T7a+sRCQ-`m`LFr<6G0{a6KfEcN|#O^@Z=Vf@v46=wB zE;U?agl}&xF{gMi)yy6UKpQDvaB!B13S50F%GH6}!hUG;%jqs;{T1O|wXEN@%BdfE zr<N<iG#`1>j2-hI4ju!ZIT@~E`NS&e0UG){VR@$+WoAy9nJgvi^cEM*(k~fM0Rpb* z$<Km1K0ekvnGX-X^PTVf&fobvo;-cDQusXUbX$W#Z?@FF$~>R30j)Pp*46bM`^;Ya zUb=xc?~^EJM}_dtKoJC%uu{y44}kO<e44fb7CmXJkt}DtX&Zs>fB$>G_{+cW=GE&b zPo9m(<F{|$vL8_t(L2{>9l%!cL+D!9t>*GtbRHdBMVe`6%d`mu%0$jqpf&?3UueUO zOqYr9|1F(P(NmT*$l@H*I;`gol$8T(t7EOFdv1<5$lF)um<h52TXClyK<D%h*blp4 z{pEC*!fZ(e8$CdkKo+x&U3z?;yg&TAxLF%!7`ysK(}}tb&EfDZur`#CLYv50r{)`( z1BRnM*A$d+ouw_zfayhq*cR-#SXgZx8-3R%m6p@oU$Ta?88#0%i-n|FG7|_uWJxUd z@hk={!2)O?T5IYdH(gBWFJf#+j~_o~Yx?zH|8-2_fN^zor3-Foqso5#a3eH(1$yE- zt5Z!hnBZ1un)E;X2mcAe?~mqaq#t+$wCV=nlEq37x%*F=1u)B&g$4l{vyca5k%Z&w z$ddv~0;{6XL>ZJ?vMdiM@-6#aaNW=$0-(WJ3@}mQn<jO((qabvvH*zQCs+>x<@BA% z!nry0n|LRv1#C|;;&x=1bpi_;=I2s4q>PS-*u!K=3jov7Sb!$8Oilq!XUW@q|67H{ zKv_RDT_FXz)U;Dt$xK(lc*)(C1lHyvU?zn5AZl-+E68=XB6Qypupi1yYtH&z6!io% zL76Ti^LGgtcT}%*&61VW#2v7bx_l-w>YNJ70#a1yEN3%lH%~35D1-%I68`xr61M4P zX{Xcfw442YcQ_oJoF0Af!HZ8m`S_DhzVYINr<|`i_UTPddK;9M3mlTQej6z*?a-j# zTc;uKzvu@Lv`8JcW7Z1I8F*IJbRT0M)3lECa4vHch5B;uX0LH{bU;KIP3otE<3ZW@ z)RTF;kN%eK&QPSAsMqV|Y|tZqTg+zj*>uK<5kY@9m@CMC?I(UOW@P-;U-^p|+3o2H zfo*Y4m8rg&6ZfQBei$3`pz$0hYK-#@NNO2$g#My|6k%*bE%1r9*QU#2QW~92A7~N> z;uSU_-CpwjCHCgc-h8p1&*@;i&pLjBXhXzDd*MvN<NlzJZCv*`^-kwg+Ga%hbi0TB zY+^_vf4!J5$?EfXeWs!N%B%TmzL+(2anv-35pYMe^`Sg|U@!&JD%1EV<dp%jQP3To z!sA0*uG(<))6TaJG}nuz9snUUrk5LyslF0?bu}Tv#~+L`ZPBKNuhDFEx~uCI2O5pk zl8)=63To~%`emdkol_HE13V%r6WK)Frpt&LDoO%&;%&YO)0Grwso)`yx<X+Y=2wu) zYDmR3fjY-1jp?nF;e#;98WuKES!|miWeOyrsFGMECa7fVu)x+@nF-<6S(QxeSlTh~ z)At>=fGJBY_l}BiNSWc6SC_9|efia^FPPGgPEQ{{dBjF^d3nKnW#Y3SSPR6NoME*C zY*wsIn}I@7XoIz5oq$%@2{DW+Aj;EKPjE*zay7?a^Dqd7tZR1NXV0FsTkT)}_3wZ2 z#g_*M2mPKt1;Y&BFC<$-++8Me*7~&)!+oSV!*u49i|&KEJRCqbT~tZoOQ?o$%&j74 zE6j{t{9UjC+d#=p5o)ukhM7?)=;`x^;BGsuznt#E&eGVN-3l@pF0A9uMz$c|5v7Tw zI^Y)TpeRwdfxISgVJDN&C@+%`OdfN#%m>i^z6`ZkIB?RmFP^~KhVAy0)!xRf)^l31 zDyK&FMrOjP3zMd6YazhC#O}ma01YgY+frWd3f1ugF*XfOU_N49TwKs`e<+rHh!gY} zTx=<3+DkNQWtPbx`$vEN=it9Tnn#D}lm28!SOBn+{<upnHLxkhE(O4FNTDHIF~r4j z7M)qZ!cIA+<gAH|+-SK8a*<Y%s~2L4APrxsN4CLCOd<tjvwn~pt-u;GLZx6m2$a)z zqArH2MBNE08s%)Ri}6M-GJ$}ZP7Rmp6c`IT7e&3BNo*p@1+GdkT~tni1#;FP#-RQD z7r};zLJ-T*KwV|yPjFp>I;3dMw6jJYN8q{ux;!o!WK*>oqTUv`)>c@jkyynzmN{0A zJ){;cBQqts4Y}wJ8L+FgQk}F+WQ52&V6k#)0=SQ+O+?`qREna8P|lh*2(pMnh~qq< zF#%|eeTf4ZQ$mMAXeLyz*B_4h-}%lbj~<;odVI<;ivalP)5oKO0b_zBaT;52D~@e& zA`B(~MyDbu_GtF;;-IPf6=d13DPoUiqk~}YUN08$aC7|Wfy(r!W#l(PsS~V`W@9f_ z%0^)u_2~&}*-&9os1{ipRMq6C;#wP9<9aaYibZ*`Ui4MvRvR0B@~3Zo2l%i3KmH0< zwc0H%ptOrH$73wz3dMpZC?g6b)`LS+I0xeugzG!HGEtq6t4mm=-z=dqYo^o!YIr|A z)Fgw$Wta#0{oa0)aCbHs_6Zs}4|AACV7=bMqYTV`YoB8-sa^8H%a6DKPNvf@zIt_b ze#xQ!^yKmBqes)}6?V~E3_}A~mA!aF>~u0|H`|?d7e8<Y)=6Dw^+j9v@HaA{m~rv# z-R5vGqB+{emwFpCe~l(0bX;F;#Q6BcqpkOWDWYHkDUQGP^^2*6F7<J~nC`drdoYCY zOT7~J`t0K3v(LY{8c%hz1tpl&Y(qiN>nnm|yfEiVzK+MbQOLB=?E<+eZuy4p@VfT5 z<mC59j8Z~km6$1CLMkYVOjP7708D3QCOpL-1gR@DWZ-J^P2{xjTNN?!ZmdEKFmFAF z?}^-yk+`>!%8E-&$`nXKVL)Qt)>FyWVS&0>g-_R@*@Bp4Ojpciwz4|v6%B7t_7X1C z%+~pG&hmNl=Jo4WuU6~j!NG_>qR`oFJ~}vLwIVE+X#d+sfX!kw9O`qY;Kk>J;V<+r zmnLvJOwPQdc%j|w==Z!?82ni{oGe=3_t0A9&pRe0TkOXle?$vkz4{8<Mx)_sxt`5t z9W7E;sFt^?v-vc1FFC%De=nzzns^ZERVsQ+mpNO(crhhXCg5y^`D0_30lL8!pdnx} z97qaXuZ7POb#GWt1-Yn_?!vB8eP~($86)Ml;m*P>C_fUMv<G&L3q^^#4c1<+f{bQ& z0KPf(ie?&##XQlcQmW$Br%Y(xy^n3Tr>yffWTZ>WX`UOIlZlEea;f2LW-`xB0GK)< z1fT(`vNp0h=0r;Gkl~EsC+ygoSn~cn8roItPhD8UGu{B<P>PHNsB1t|3iIm=fR7GM zq1T{c50$enRsRCmM5*18t$|;bQH995GtQPl5uFP4sk9;%YHo(df{|8{1x#ePG{YQH zjL#f5k+UW$fDf`UWsd1``c5Ebq<pbwy%VWgqrudXYYO0Dk4Ta$Eb-6)1d`~s&SoOR zBWpTU3wU<As9c>Q(#!!VTPmu+GNJWGz_iWI#sg0w!(s-sIT@BI7nu`<=|W|Y&4gv@ zh)Ua$Bm(8E=@1dDzucqDBvpk1k`9<}x=w7x-K7RH8D-y=OKq65nJ`@@qC`MXq6(Bt z>&T_jbz5zPHn@N>WQvQTE%v@}50kU7bAQwAb&ih@pXzrv9{+RS`S#J#(ZRvc-vQ<r zwOGui(<wU899yUL%fp<q;&nwRP603k+5ue7oiJ(LpHrHtQ2J)0PwvWD$|d59R=m-J zj8~<$Z5=GRX6&Q4)6-XH379yfav?yHGbI5Ps~8&z+xope0r=iV9~EK4d_Mn~-~X>l zZGpe@cYZngqVK7CbuhIfR;NMzP;S`iPq=i`hAb_HALK~`J=6tQM;FwA5@60JGdBmM zSACJ#Y(7E$;^J&L99&*r92^{AVW$8YLFT^G?e&IwBTl%I>TVG;e(;0e;Cy=+I6ZxI zcyKgdtiJm4%frJV=FAuK%S*jt3Ri~>O<bOiYMzrD_I>`pZgnVyr?Qv^WYr=5r{ny` z2~Vx-l1$`$eKj6q*nF<bExx6v)Kgzp%i?J<Imh5yjpvAuX)x|%>qhkJ*KdFLo1Zc` z2-87&N|)R14lSbS?b+FkA)GCBYhSO=!&KX*R?<uWdLkM=rknpY07n@qA4sg*Opv%G zewog&jFDKkC5wJN02OV9yd9IRlEwgSLCmEDY{)3{D{!MZEoU>5mQtrI3CvHK0!b(; zCf03*m24dr$YSWp*>Z{>An=LZf*5m)r9=^xBE1C!ENq(UPUFi3o5r;sDP$jHZx{}T zr>BpXbLKxGrd~z0Vc%dmXqoOYu`vN9)`k*R4XYAATX~ov<?vZo?Uufr0^inVo8yCT znQdXqur^pHXrk!D4?p~E-~J9e^H*QKV#n@x^@1Ed^qfEGz-qnLZppGYtj9nmiIvhj z5aQdBBno6^Chh~91mRkSi?#y!MBT=&T08j>0EbJGLXQGjSE*EdXaJnmZbi9?oNk4r zx53(zP@s~nV%y}u191gTNE!l_Y=$N4a8W&FdYg8(3^PH>2Ra>n6_GLGXu(wXFy%w_ zHtgc>KwMv}t(=yzyRC#=u`X#QFzt?L!52FZ$YO-P{xr>!Ebw?$fdXK%4uCD}R1VQE z7itHvV-bU}yg{i2C<R|z0DKsCfIS{G15Lxg-3u830rO43vAhj(=Se{}(OJ^~ez{1W z^p!XnaB?jZmZ=FQgpONfxmFo20_@|NQ<ls`1(jZB+W@7N^bSx_>H=h)mWjI&^@KQy zrp?Ypz{(-YsbS-RvlJPe6q!#IJ%$C0#JYVDDZ_37sX|c&f6=I0SGGvYlgh}oOxUCh zG$bly&|qXe&?YQH){;&$VX=BzX)c4JU7)mF%bZ+f0$4wO&cbHWBL*=}>RW2nndQ<t zc9m9iX4sfA(=xW!SyGFUI%`O-fH}DqFkwy|R+Zr@pqw>r&^V4_`fw#<p2prMG2NTx z_||L;20h~5k3M?&(MKOXfAO@<hTGJv*2WbtW8y-iJGX0XWq|6~W_uN0>H?`oDe~NQ zS==v8U;7~o?NWp+6Gb|bA`V@46eTJoJZtQooScT;M1|d^ZY^p>kkCnDFoj{)*ZX@L zt`fRbG#bQGT*7orLB(pL7FN3d4fCgO2f%;tZ~r1KH=AuaC)uxX-Hz`PLiY)w^`LLu z78X`3Jy%SvP#{Dvv^FUvMGs6kT%3&AWCD+V!6c02$m`BdXZk(i*=$a%KAp}+BmE31 zF6wmpx;mk14+pGuS6rUhoE)EW?Z3FV{QUFJNr@znk53+*p2n}UGzc9Po+2!xG<mRd zh1rYc-t}HvKjhLPZFLAB*9>diN=>7{zvR?8eU_|IrlH1uW2L9KXGG+1Vmh=s@v>TI zQi4`|Ocxk8r|NoRk6yrKRQ1{Pazhw=_V)7Z?1C9ZKS&9HN24Lqv)NQJ`_*Kz)VH|f zfpG>*#s}0BX#@(1HO=%FhKu=rz<@Fmx8R#F$ELW4Wh8#BZXLNZ;KwlCN>ZkPIrY@b ztq$x@RM8{DtFn%)(}dw{M&jN^DvMr&lqrye!iL1Ut*4T$!va~%dNL>TAt=HdhG`O) z))8|!eRv0`j%S$jtO2HZv!OQ>%qDZT!G2fYsQ>)4&-H9bY^rXi+iFqZCr8j=wQLKs z0Q(_25krsn3Q~Psr5^*wF4jA1PI0fcA+}(>0iFmp7C*gY+mjG`$aJ}0u$I}bUw-)E zcziXPOrAe~F&*mzHGP7$S~ae<G-(~Bi{-+m*fZ)|xWeOZW=>5!2=yvIwjSV7Fr3BI zBym4bD^a(xo9`=58ZQ|UfJ17Ii;RZ`z##Nh;T9n(=|kbml{6MGKNA&vT>)_R*ge5~ zqn2scB{iU}GYS*T$w*wzfgQaUjak9mAPYe$>(qL-VY?r8Vs`)xVeD!v6$f_7V5;Xf zG%^+jl`g=MSiEzA=z?ytu8|oG2J9pVkj4kob5}=z>NuGrfS0xx4ocut*ZwCfwWWT2 zT`$2(-vNfo4Uh#GP1c;ugfNFR+l0ly)*EG2=8!c9SQUp8bDUa|G-u5*R5{hIB8qOx z%C*YK3NbZTF(+rY0(nwP8d=yxIlUXm06Pa{rir`ZDuC*^TCOj_voJ}N6spe!%t;b4 zam}fKqNKD4eyAHYq}F=Msr^GK@>$IM+-QcyASg1*Of`913CQCG%%K)c+h0}!sGjYS zXbI+2QbWZLfoo+`0nBVhhzRC5(9JTK2O!D;uu;)aC$?f&X{9=;QTA{q3>T4R<kAql zk;K&UdN(ZKUesX?l$wBpeiwnvyg>-shDa0|G3a_iuG#4Kd%E}g^vTm_Pfj154u}0_ z{3s<})s7hvPTZE%7iGKMUfj4-c(cCtJ101@DX?)zkbz)aXa*$^T&qm$Y1h!HD|Tu4 ztOW26{lG#jj;I(VD&R;r9#4p)>`~5mM1~YiXJf>Y@^*)wE#hbKh9i9txmsPXmgq-e zQ$H{guY&lA+mAs1&A;)Ni4ZsIz4<~%QUtJsONGN-9Y<xAwq;JF{_c%OvM@h-Qov5b zvFJ&~v4T29T@N&+h>@j>dR;}cqZ7uaL5PaJ_#+g>9&F$b9lp!j_~MH%`1kPe;K`Gx zr>Bqb#_QK_KL7Nyet)#zP}mIgxUyc{wOOw8R$J1wUO>ej#n32J({CU#a2&dEWGo~8 z2|v?_CW=n_y7i>H!E?O?ZSm;w<LDYaLruiys)%Vz`VvEi;?N~yuP4)4+(IY2x0tVp zZ^u`9M>G}uaW%@QGM$dk&(F`!&m$bzi!T5#ND%-!#D`6Exrlx>I{MRZLTz6f4+Tva zDIbXLh_jVnVS)<BGDc#RfFBa|5bV+htgxQefd-1|rS<(MBez>lE3i(GOI0V3`DIuJ zl#3E8P|4O|fh>leoUIgTKE@IXL+l(a$*s^-F1mvTvUr9C%6=toe73}LS<IJbZ_j?? zH-7W*;E);4&J*7e(9<Zau}-@iw{0|4SS~CaZwP4CEDw{I+Yl&6Mz-na&}0>2ZWL&# zm7WxXZ<>`$D}w<oDj;VM>Gk`^M<<7eqt~xqvHF&J)Mlym9jf?;Rjf?FO58`9$og}7 z2N2kbR9r$TC}1Wnn#i0wTojcO$l5t|WQ7&DRvo+el%UF`YO*9&$r?XK0K65p-}=kx zL&2<+mE}niDAQ$pT>)?<o3U$Ln2jdN0-1JQ(}p=lVg<-)=0^Zbkr#MH<~Ft$?XuIF ztgxO|P#(lOL7F+axxDT&2hY$K(yYx8tuFxUn@9AKUL!Uf4*j(<^juwCO{de)p(`fU zQL-pvU9zNBi<d&>7W2Ng0C+eYxJiry5M%+gC89aO0%n@VN@#@XCmnN<B}tv7)XXvm z#E~>{4D+c=nmMEvizjQgAOw?)<;y9cD07UccO##(Tj3(7(dh*1sR-N+WT;4LVW;<m zYXLNvlXqA%%l!iCXTY>mms*T08i0gKeo)^EnByYLm9>$AJVy;PfdYYeF4TV<cJ-j4 zK6q}i^>IO$f(`N%GqlK5&uY=2P-jATzCqg$2)H_&EL?_E1izA+co4!jf~y<Z49fu9 z=`~`Q0}vyeFhQF6AZw@-Td}Lu{7MS4*%B%t_XvYc8@A2z<ysVx&805NoH~$CRKQh0 zMMDN`s(9PoMCeE`LqOQ;cZsH+J$v%vgXd44KH&(}?drI8e00?9_K}hO5e-4mU37~P z0~A*srU#0dhV8fpr3;dW&op8ncLYLtE?#;;5+^^b)%&S**CT#TmZ*$+dSIETl%rk? zv)h-t!!gs3C$;p&xropdy06xHsSHOw{q1dt^x{|X=EKoYkMgcKZW0?4brT!od_9`` zFWnA+|JL95EAc+9&3v&~udqZrqXS@i5w}&Bv)LSz<J}WILea@|LLiUzh{2aw(K}p6 zuK^qY!SR<U6sOX=FjSuBkA_^4mCEUv?xCEv=xjW|tP`1rO+W36%=La_j{x@hv!`@( zG9HhwuEtlB*<{x3bRRu>La0wnP3wgDI&f>S*b5YRU$59wHm!DxZ35@u^Tz)5YO{zV zfz8$$$LEXy1_!O``ks{@3uhD>v^bm2{HM0Bt}ZVx_!|uMoo9rlC8k8&LT0%47YwmB zv*u*H`0A@Sn2dERj_dKpEXroH$>r7g)%a4MHLU1va~;3ij7Kqmtq4UBVId8~SE4aR zP9(<!+rBg&1ne_%)`b0Fx{O!_Ldq8?GfjgE-(bWO^+42BftY1dSWmY?(xp=C+|^mI zm2akM2Fx^a)<wWArc43LfO1h{1uEG(ERe;}W1_+b(Y|N6x*0iN>$i9*Rb+O>QjIW& z4QtbFw)KdE*Ni^jnZADY=F=a2HXIDk-d?QcOO`Zyf_4vGhW9(YK6?kNfyS6K{!omR zt%)p3SOC}qhg2=<!zg_?#R}AycoEY7&31fbhE+;i>4q>(^t!FsjQ3fQlkw!}=;-N_ zXWHKP8iW48;h8qns7saQYN1V9A6_M929o8}1ZJDAAj`ZHNE#_$0?N1Y0d66!w5|aw zj%WA8F8w>()hB=|Dz63GX_%Ao&;U4Tslh#ksHa;&(N^dalwyWk49%c2))|z$;yrOk z0K66MR~=NbVWt5#gEA)s6UsdTnc(ull%RK9Te;p*-4|lyEl|TwQ@6tHxVds#CJb9{ zY?ZHrD(<oYhb(IoSb(~~eV4#yvs$h?agQ?xz;vAM)9dr|^UKRi*P;}8^vvTqGFP`M z2>b)>Cfu%zNdNH9{!#Pa6Da_OLN74a9Ge2+RskkDn>l2?X_kEfpVV3RAv2LQIOJKt zFcZQ$%b*r1wVkcNrFB?ahO^N~+9NX4+512pE|ABjoZbzoD8U>Ty%VkiXcypfBNYcM zVA@^FsP|NdzTzkh64%$Q5?mc1X~L><3M`3FqFjKftM4`-=~@6u*9DZg6j(!U(M;g1 zZRScGIt0sP<rXt?mQvDCBRx6Yg^HexR9u4jwl-%$U4!L~@G}C)(;W(_E}DLr&ZU{N zHQiMj)i?U_IsY)r{+?dTyRRRpK)2pd6e<7el_Q%yeK^q|ZIJR8Q58<ph9yekN;A9_ zfO0ow^bWt-{~1UIERMBsAjqUY&}#a2E|-cWrCc_8{m$dZr_Y~1{rHn_eE8u9Cnv{5 zY6QTFjoW?Ij~j#WFf36q)%7Dr%oqL~=pYmOHlbOQFmjKGN3$k9I6!l>3k?v~1FlQL zOb8^of+_rsXq@O*AcC7srr}q`H?n$vL#qUD2csie!H$7mLd{;carivw4Kb3?Rj<fe zXa&X~Z03{kd^V-01e@%Q*A1f9+1ceK2iu?deg6u&Gyd-1{uM&;{dQ-gt0%GO0C_CJ zsf^dbq3-a^W-|s3L+Hq>*I)hM2S0fB><R7b;cNYJ@68^FWb`z>mjWhX?Wo`5;7buv zu9;LJs3wf06*O}(d;9h+S2f(*?+=MGNAZ@6ScAHBkz!2DpX=##My=s+#89E_daaxJ z_>5j_3ks()F*!hY+TDe21aWcg;0Mf_PA3c;;Vn*PXwlB>){(u@P~gt_IX=<Q#}8<U z_vYx8SK$z51)kxQum8Ck>khWQp&b3z!q7GvA36{<xBG*o-n@+yTbCDCKl<#m@zt0* zOk3@e`t)O^Sb9346^3X*(A#Lz<Rao`Y(Xi#!wFh!f+7+bN<U>h69n_#7w9V^ack=< z1ADSqP5x%b2uty<92n~{m2yrC&W{7xS8CB<ZY1h{$nsWYord`p<f3wFL`k()=C~Bl zB1oA6mI39W#0pfhbyy&aF{3gKk!kdsqx~fo6dX2*EL%zKp4fr($5hjjTCMca8|y<q zNVb{I^@0G_!eBW3NB{62{_qFCd2xBkk{Ib#%sti`yBVv8wRUxRF`G`~d-CYDE!uc7 zgF_x>=?3q9izR?^8l)oOZ%W}b_3@bqOkslQ-!L-X)&J)0n`TRm>cg*QYcw39?(w6? z{oxQ1wgGjNMX9}d$#N$4ZL^iKFT^!V-7I;mk|tYg$W`76Br_5#V9ga~23ts_>0OrG zja~Y8@wsdOyV^3e3!DWiF5#g8@GiJ_)?ZKW4@R3RhB>xh(`Gv!=GC~qB&22niB*I9 zRR?^Qs!OSkd0v%_yEzq|=42$Up#JLGI?{Czox1kjescCU9_CLs<rd4Sk?DFjDKb+2 zc12LG0u2zrY=1`PeaswE%P_i}C;Wzax=Bi}IS3)Zxq_1e2Z^YpFa&w@%!=0ykR=7E zvXhg}099Q2wFSTj@x3NM8*~Q1r2#C1nfnO`zGbpCxeA5?vepCbj#0~X;kyb1S=4gq zilZd+TBlRd@q$)lbx>O`(G92Bij^BLETL}JlVM|A1k3?6kvSP;(UVn~M%cZ8Fq1Sh zp>tgmE+Pfy8@ZzS<x+~EaSI1cJVW)Y2jC*za_Q=KTFf_G(a7?dPX~edXodjhlOkh| ziJY1M$Y{)pM?Gm8J=g|KDGj+4riJ0yYZ{?K2_VCtsG`3JbLm2gKL$>JdI(F`HMHj8 zhDkkL+Tza>MtX{#8fYtXEJG`K6M<%m(rdDwv=%U=ZU-zt$4!_+bHI)@T?b;A0qi0p zYmn+dHWg5dtnEiRPR7^}k#j5_bv@7BG^_6>EhMFezmP|{e!LWcm^ms6J_YMeivW@U zSa;7f0t9~aYd^jZ+39s!dgTfJqRBz8e|R{YUY#F|dW1Br$fbUdQSbc3_3MouM&)Y4 zka4o&C?hTH7AriOOZ^S=l-i$VX8a<b?qsH{AX8)XR$lV($zu^SA$~Am+3)u#9t;Vz zUO#{Sd^j9@=R4ma;{D)*7tfwOJv=-J4c8I<>R$R<wqRJh-Q_&jB9tMXBY5p}dz_`> z!yW}U1oq5Ay@6^zYsS_RF(>irkXnRu=!p;4={$z%%fuLs?rXgdb)l0S3#8GQp+H}n zvn;W8mynIka-$JhOr}#ttl3Jx@~yW7FED|Q(^TKDHr(595>355KSTNP;pq9}qd|LL zcS75;aJraZH(LXu*~Z@Q{i$1bfPdjH|6drx!SJ}%?QsGnN}tUa%n7}nxYxhD<kHgY z_1I5(_!-~gs}DbX`TF%6bnE9q4-UGWu6h^uu-l!sZdK1F3<N%B=;$WL=kv3(ZmZkx z^%;1!V}!Y$^}5~1k4`TyE_&V0>B-6GpM8q=j}H&0;|U81SKy3T=ZrLmTO!WxtJj=* zTQLf8%UYwX8>e)0wU$2_Gj{srlARX)hx0l9Kozm2W<E2G4TQmJ?-M+)nT}*RgJV=f z+X$m4CGnv{yVLB@_r0}#v=+ws)ww2Qr!}2TiL2=;6M#8;cyLJR+1dGYI`0ogoo=72 z?|!>8TQ0aTzk2)n&6_vlnO>hpXiL*fT%54-b1S-I*3?t#dc0J(n>C$v`<K~{dQEjE zO#ErOvugCG2WYgH8VsVQ7e>SZf~=V?g+t1vFV=VU4-2FkOOVo^8>7*%snA1euqA4p z6gwx7!OV=fXQ&a=_AABGEt}I{xs<e|@)oSE4q8kSfiO)-#j(JgnxH6&-i8Az%aFAa zlsm(p3`Y<D8|sHRQCl)qP6=kJR!KQTZZ0!3>P&N(epDf&KbVDPW=NKyw`$4hZCC)% zHTRcVjGeD6vAtW29Sd#JppSooBO@68)KHYLa#&?(VDICQ$J&lp0I;jDNib{Qo}GRA z+2^lby=DEK96u%sef{Q3P64Cgpu>ujhgtFsRv%&Wa=l(G*NmJ#57LQtvt~Qw@VZ{i z=JV-%%yzxHUNT|uH4Wiz?JmW6m_J>eIXJXBliB=gGGnJ@cVI_Wx?1Z4zkZKkmu+FT zm@QUI4Cr<AW~{5rtM%&o@ZgAR&vZOJ7#^^<pkA}HJX1AQ<>YXMi15PAAUbP0%Vao< z1Az%R<<vx`ji{;*n7HNu2wDMN*9bUUf%&%0u$~H1nLQY7smY>I6`;mkjAD;T^E}*8 zV#+(gkI(j0(|=y_$i{UbW#Ov<S4jIq^$)}OgFp?Fj>dGH)9u{k-U=#C%h2bLG*s9M zLADq%(I%LO{?mu^@%$jOg85Bz+5@pDPM|T{q8l;;%T#V7wS%cg;g>LY`=8}%f0UV^ zk%A+Oox^gDD|i4Jqx7ev8hzFg*S?}Cnh;pdTy4kWF-w~)Q-%J!r~>pQ>b{U3Ys)Dp z`(IK8?9XUL?xN6txHmpQV}s=w&vB&<fe!w{5vqbO5Yr8Y7z<bT07AqYPFByKJ!e<o z!perj)gSkA7&tmUVe^^J=Nw?TU|&rpEN8YD#Plt;c%+VSlaxcqcziXT>R3WnUuJ64 z7Otcp^lAM^fBxrFPu>rD2^K?C2hAD?slkY8N%d*EK1%QC>AHB)2*Q?eMQHoFya8>+ zR{6Y7x%I5XX$5&u%cWVHvvpJymX#Q0zEcmdaIQsK(U$4#DAL?1fV{I1co=xfTGFs& zM&jP)Csu$g8nTio7hG!Cx1i!=XjgRB1gL8>$92mZTvV1UBl96ln_z00-kR2dKXDX* zwhWEtc1cZSRI(XZo~VE;0#qf|{gCCUYXX?g9LvxmZ5Hz7)RKt~0nreFTN@dY+2<jX zT!CA3+G#g?dItfLToVw~4NoiQFwyUI33WK==pqsyHmw#@0#E%^kaX(JOn_}{I-4o4 z26VpW-`pZi#y>^2fch4|PJ}}qTm6BQ>~SOjpQd0Uh~?{RVv6)>3&7X`kx8e`4mcR} z*=N4>?N6RQd!ipV8VwGQ4hDlk+~3nf(d?z+41ZL{MkIx(jV78X;ol+)ff2;<*9XIa zo<*Y1%>SnN%N1ej5;Zb7x=9@p#ax^d_0Ck0IFyuAAYxpPwP)`Wt<ffdUwkN_#id98 z!Wec=0wvTSh{;{AZ45+Mb6#;WXOQdV_+mO4BdmKYt>!hCnPw|Kv}pg-PyCE@75H0! z{g=4*tT+3LGj-7dy6qEpanUJmv<uRH;>Crvq)SG7F^7*B4$;Y2A6qp2kP;ndfVj>N zdc&cd+*ZdzlDeiB@k>!;A((9hmbk7z7$8&ZEBZKw$eiIL<c5P4(WuS@zAMYc@%nm& zNs3z=t@x29dfPraI95=q1Ep^L&*yV4gq#@AsjnEX^?ooc<Wh*`ajn$HZ9bSVjp#Y9 zCf8OIOHS~Zns097qWEw}PT-HR!~n9Ku()cUUtGL-^HvXNU5&Av)?(Ic0&ik!`Ne55 z9pI$73OrlNL;++FkF*5D3}{?xP9^nZegG;h*P!;Y{&-&DK?pxQ7`aiy^wyMl1yM(A z5nI4iBdx14vbHkwpDLL2l`haUFw=B~ig)xE`7GnQXfBkyFG{ryNhWjj7tHjhz?*p* zqBp6QzrKh_A*Z?dTt7TMnM~ijd2@VvIGJ2tU0t#tkMyfaLr%Qos|gE~H9&p#C3alS zy{N)8_AI!pw@@zqY9b6qyG&tW#_5$bJ_n4i-D|<=0%Z%i^2`^D{&4X0$<voFUp{&A zgp(ykP1ra3!(Ll&h~{r~y`GFYE9+L0d!f;nlLTp%e{M}_7o|)s3!L4WR<fjbz+E;W zx0bRdDu5p?RMp<yP+425{?PSUI4org)H#Od&V67FT&|q0V3!~6*xt$}<?8H*vOZwG zixO)~zY=k8yrY7f$PL*)6&noO2Enu>&0=K&gzU~n2__SDPZZZ9>%2p=u}eP{^EAeO zQfRMe!!i_kb+eyX(x6C7zTF=5denl$+IO_b0RwO$zPh^NLXISLNx4ANL^P66Zh``< zwI#r%Kl{i27{vRd$yS%h+i<J2XPewGz;v64fU_Jg09gZOwh};W1w~us-5l9mN|sje z1vEg$L^cUzCNST1jZl08b6iwLE-hoLWJbA)2^(*|5rumk`bg`Zfn%DP0qAMwgp?41 z3C`x;k+nP=iQX2jzyb#TG;~oZrZ_aIC0!*WTb@$`4Q?8m)MBPhYz3tm=6E3`R>0XP z+ydIAt+G{RTJ>+&EoWVtk+^}(v9>xg-$c&V$K9yNgK(GSZ!{nog}2m_W&(NB0Ac%_ z@$&Y;w1H0+eiU&$A!5_rs>Yrk`;0%~^z>vj8Xg=Dhoga_zZR3{x}lFS*9>H+-?Uq; zUIfru>+wTGSU|!xl(r-1ubxWYmS_8E!h`{z68>+t2}|g(!${pmCV)}&CDkZLgln91 z>WI|tz$40KMSSwfC!^8mU;Gz;H|fdAaktwU46(ecW0WRuGDCMx(XWpQ^wBpQEQ#st zAxLW^%u|hvvp4JbI<8zBzl)=5tUfa!f<*!;S;fGHvTMRp1UY4C@FLd2!-~OWDkX|F z*{3MOC_R521LUDm)K=WsS*@3pppl3bO~mkGF6IlpglVapEczLwHnEnxgn6s$pZdvL zcYuH87ylv_>+8kwi9vK9^%%e!TE;h`JrUGOw3$GbF3;nafiNm@BT^>{)k|?&I>czu zSL=SSkALx|9s#FcsEZF&$l_L7MN0lvk5o!0t(H#FI`+(FQ)1WC(^K3-DIEC4=eX#Z z!e^|BhntNi{>0m|M@}O&)d>mhjrbld?9uR$X@Nf?s@D?=bRJ4~tz$ys0u4`0Ha+g& zXe^d`ID$W7Z_4RijD%`oDgwyS*;V|6?{q#V`hE54)y2hy?r7-~`ViTm-haTUfO#qn zp`6}<vH)~OOwKBzgnuG<zVF|51430o=1Bg5;3AW#`+<JBQ6q8PdWp!{t$qLueWFT` z#z4-NiHa&SCH-~4I_uD)2;|nYuqy&*??(2UX;LkU9np2Bb7}(Q>qSltihR*WU^bh@ zcjGVLzI}6k{)R;{8tKBYTCT6gW40GguCbrS8q`waY9d|KZE1}Q=v1o#vfczB$hs(+ z<rJ$AVcE0eUQYa|x1OJf8<Sie8hRf9r(`zy<HMt;PoIAE#aCC8D}8pjzsLH;0779} z*5=EMVDpX7C$&Rpqt(Z#VM2mjP&fosvfz$+Wx^a#rt6>!QArEgfO$t11T3HO1@5R) zL8|`1_2`XJ6>p=?G34jnaIIWddgCfwhaFPK4)KJn8CV08CtBHJ?N<Ia!MpK}3T`4d zRQ6A_pFlQu*&MQ&Q-(`ZriNVs>P{3}x^>>6+1RDu)`G0TYn&`ghSYp$A2KLqKVhTr zmVzV%OPtH2Yf(xT^!4KuZT5$_!Y&XdMHTYw7$`#?g4Ft{OA+$WK&F(I&({_Ja~e+M zZFm=Rm&n>0I^%Db!6yaS2RJTJYRg<5l<nS%t@3C?IoVuFE9l2}Wnrw!hUL^SKR2BP zj50^Xg?!E$nTa0KIuIbWOw>py^D{w;>+H00QJHqBtJ`=Nfe=hctOAK!>aVf2Q?6nl z?*T;;pW84vm_ez9qf%03!!qEQ@VJLyg5@jrR8X#Bd4@RjRUPiqIuI)tWtu8ZO=RS( zi6~E?u3-USX3A`XOUtSKR);5Z)@CLQXUna)$nt=q3e2|{-M6FIdKf!uF%TX;vY^xI zbi2L5U`VV8AK~~Mt{ZRmZTAO+k%T<#N}M`6!{J~!)XSv?gI?S-ld8>HstByqv__vx zP>i*XMEU}xjVY%YR3SApEKL_YXKjz<0`TEPtNM_Oa)P4yY<6^X`0UxUZ+-id7cZVa zd-jAH^p3+DI>J3TiiWg7;j;+dqzYKA8ZEx-j!2l18m0Q#o7en{A*6IKVyAr$X7riC zw9KA<&I5fS+D*lH(XA%w^;$<dfaUCw7#5bS_M5UqYU5yMlPI-J{HwiQB?_vW{ej-e zv|P<~&r^>I>;0_Q&Xz|^NI%z`<xl_AA5yOh{L(M|Mfx+H%{f4lRe$1egC1+<4>I^- z%F330gMsTy;f=WW8>8R=7)esPfPjF^T7e?FeSC>J%`U{|^EopH4d`LWC_;uJQazTu zM+mQ@vYtTGU84pxp*}9`bX$7#y1BPpEGN?|T4SnWAcKzQ@GZ^b5E@i`d%Z>n6C%8# zxiRREI5=a#daY|`^i;JV<Wy!rI3dQ4@!4C%k0IG1%jJTrFbe_6PFvqY#&~STLSMXa z)5ZAe?b+G6Uhhn7EXR;CL6U>hdCgwZO3d@Qp6-Gw1WY?cTRBTw&OQJ;<gE~-yfy!` z4S*9X5RR=f?*Q_o_POEe8rK5v)b>t+_Xkr3BW-84Hn%H_gU)G|sQ`Y+O3X5vi@O70 zrx`iR3^!2*O4tg}=Cw=~F#o61$@jkZpU)SwL2tkn0*>yuuCBQh5MWXdrAV^rai!sZ zGB8+8T6(3<W|}5!iDiK9`bJ0K8(Ls`0d;%LhA<wpfxsLL29HippFe-DZz#kI2&`nt z^{Lk*T$cvgj#dnJI5%y$iIk~jLFVMt1o~ARFvr9$(5`w_%u+beq^?+pW$FTVRH-0U zf8cub_Na=tQRf)D0^qEqoCa~@w=yc@lCeX4r+>JPkXHE4hIm!J#&{>*Q6abGEYsir zM&ma{q;$c(@T>r2O_ZT(yRF<6pt@EaG?E2!dKd07f7}tnvpTDVU?*W4A=L>ozUq}O zrV$hn8M17nhWx-492p2?-oAb7D3Y@Tnh_up?slcYngImWy@^o^z_hTlU)v+lgT78P zb+|nwoMyNi5H`gwpnHggVJdPJ1hSGkEDWH_@+RP0bLM2a3@T;;bAYv3bGek%M46M# z%SC0V!Ztq0O#>5ftSu@fM0o<k39^it;e#}~0D_K#JbQp84fo3_pwzW8rwo^-%x%M5 z3nnJz0N5N8nU-1G`enk#hu{rdlrp#BcBz#sT0aJq`7Uy)i3$)ifdIa;SguvpU^rVz zfh(3<ap^8($x1~CE6m9JoR;`7;H0{SOX*9>7qu#|SlLSqAE_6nCm4(6@#)FQ$?@sw z$zageJDxU#3Y$(x(Fk<-Op<6om{Z8(lj9GbJ$?DXi<3vk{eGW@ClkH5m!dtQIr3^$ zxBl=wn}2g(Uk-^+;TecDmp~pD5C+=RJtAqGO$?*Y|MiSDJ@vpb1Bp(X#3#fXrU}#! zMx!TBAN{W1^*av^4qm=|xme5*n9rvUx-h<IRJH{HHWAa&qW<U|a<&I6NcfW@^vw5s z*zffRonF6-J!oU&)>l5=PgRh%&<#hUz_HN*u$&Nj&`E%%9_U&~0YxdI26{P`wnT^e za*=e&;kZclvc~mMM4OYS?AIkkry4x0wXj+e1g@HmO{cm46F>Q1m&O8r<8S;jo5YHU zPoF`cQWnxmynVXKkm2h16ofGE<|0iz=zH(j+0s{gxO!pn%?DU`0C_2kZePd!Wu}&A z7jE~a1QSz9p{YnM1RxkjMB>vHXtZ1-*6(+hD=vikDk35hiy(ZpS|E&uaJ0V6i@E!I z@w#jeU$7;u-wEbVhEbg=j2#3sgn`2_;&TL~Jp8ZEEcBIc-PC1RBWB)P5dbq(ttOE$ z*J0GfY}5^A^#>c8%`d+A^6mNgcsxM`3xXkIicv^gAncS$dO$$`=n;nC%c@Gc3%L}c zOjkJIR_31AQ6r|`EvUz(1$$56iA3ESZq7)oqQCb?MLv{?Q|?#vXbV#D*NR<jd7q&) z3n1(?6FI#DRF4`Gvnn)$tk%dfPV0!pbpux?1=<@}>c!s3`XvBnX?^+CmtTJQin#Y+ zbT}A}ke*KTwOcL7nDhFakc-QHgQXN3ly-2MXC&C>ywkCS*<H%1_IvFfvEj&uYj%8$ zplzyjRov`$I)uJlcgV0oEEda;UVe0VbjV-3)1EK%26&pDOeP3mv%SNgKFN{BTh0O5 zKSm`B-1iFKS)<G`y%idp0v3kwR+%JjgI-uH<qOm~yO63sbUl7e0WiHIb*-EVyYDC_ z>Nf5OfK5nckpkZVE^AYx!7-7z1!|0U;vE&-M5!TJLe}GMmQn5kAZsJd%y4PS)UeB+ zyRqGGyRp0JfNA$dle?JS=96WTJ7q~iFyXnbBOlAXO;BM0s=(o35N89ei;Ig3A1aWi z6eimdirp4j0D&a@+>lxg+syeRKlgLyyeIVH6OB&|K2N*DWHAMEvD+X2dwJU$!=16b zVg9a-fTFGPK50SVHF+XHwk!$4#xw<UYM4(IQZ-Nr7?hHlLkh}z%2~tA`@^+tFo2Wo z!4<#;xXAo+7MO#i`5+Yp601Ps#=J36vENxEu>$Y`tuV5dG1H~C0cJ=E7Rc5DX$)qW zAkB5R0#%e|F)KIVm<f=yuUxARiveV^SE*huHElSX`6hrGj#iw)$>~;<g)0?7?t=MQ zz!thRI9?QKDuPTPCPjrACV(qe_@rK#l(N4#%gQ}D(hmh4pBx+=kGkEKeg<+rSuAGr z#f%>7E5Fm(WJ2sPozL~f*X4Y%w^<$?9z1*g?AeQFC&$O#es3MO1DRL!Ap(jBF&fGe z8{D>sBv}QNiL81X-XOsRL})$?v9RSAy>3bm5)*js>&~IReG6~U>tVn*zx6R)_|~_+ z&2i}H=<w?5>fk`ns?a-}$?o0eWTfY51vZUvFIL^!D`4Ula{v|T(HzX?oi+ijKKJqH z;6+R(FqdImOLXLe;D5?F{h?XDWpLQ=>5vb8a*l?WA+vYrHMBUF7nfm@?XdwemFsx4 zrH7xXwOHsKPTg(~CoFZlUB^lybcK1FbqnF;@~3|0za^sz{K~KX-w5EkogRwGvNvmX zDKG<c#CL14O$}o$9^(qd(1)qoDB@hI&lBNzn}u&zs3zF#we=3|bR9wlP|E(VYg>F) z1^gfr;=z%NFbA30jCnPun^YmjC*{(CFln?HA9ln?5{g2p$*7}8@5#`eYDR-UTIQN4 zr^W?uZ=>e|kR_sK#PBO&?09??Hu!O6CCn(r%<E;ROAyN>VSw}qCARU$oJUB?H;O3K z2gUH~@pST|Pd~l9k~Vp<_+4eJ!hy<{&THXCeNCM-TD?i{hN{(sGhHrH%Kr~S)T#sT zh5AZqjqwgJRT6c7xLuI)fr>qhLWQUR`9zgK^{sp>$;#`*`(u}#G*R!1?IZ=}++c?u zkmaoh4WQC)mZ6BWTxz}v)8&+fOo}{N*JZ`&5s7AF##Ld?mPq`$TFhretcQn(O}%M- zPp>*)XV5b;dM&ep()paaz<K}#VEM-q7H;g9kTmcw%-FHChoevulGDdf4zuB~2la=8 zqmz@<lM`ys;!X9`W%IE@x9h4vAGs-a14=DmRI(r&3|&sGJZBBb?Es}z$+dv9>fkoW z+M;3^b<QrN>Xi<^6JJvRoRySQ5nodPY`;Y#H-<s`4luAn3xM7JOvJtMjtXufH^en4 znoTH}GKSPdo)ylT&QP`8R_^krYt>O40IGKG!j56l?A1aoJs|?&j^yqDXagD<t>;+p zRE+aRi-9yjb<&~UD56)2P=&J`%Na@PYCnm?8`oPjxGlF%scleu(TeG4cK>S&fH90_ zw!#t+Zrl4B9IS`7HKZ`%K-)4iT@koS9dvT5JRY&mdPPb}DYd+5YjBa_(#)?QL~h9& za6++=IVe$`ZOCFqIZJ7-NH$dJAYLhTQRd{VInbnrnMS!^<^X8?sb&J1iE!DCQRxO0 zF>uHu=ILnKrEUly2H(swC?d_JWXpB485JOJ0aCJvSpys+6eP74cEt)T1`zYigr<7A z)U@HO`DIYi0*09>vkh6^9druH#+z@zbYI|GAWCogr3xk6OytxA$eTh2S=6%2KvT-X zVKf1I&9kSEKKbPN$?@Rupg$V*27RK-#`St}O<>S&asF5>*95(U66?igIoBfq%f)oR zwdwY|y<UGX&`;IT0+%VmfVJ+Lst-D%C=}7)5+1oTO7)H)-Eu9mY~K3*Di=|VCM<%f z)6;&ltv8qIry+5h<QombU4~D06+rBs&z?N_=;N1<9-W+?9!L19M_6;L+v|4;U@(9p zV&HIt?tF$3u$eQIGDdiw7WEh2mR(fGS22Q|m{!vX2R_}WmB|_@g^N0f$+@x0=n(x- zw~(jany#>8;|1KIrehmZDMPxq-fN^d5bk287eqOHLO3=|DJI4vK7_!0HvRMSGsfcJ z@L;JvNhG3Lnp*B}u5lJ8(VzK)|6SEA@Jqk)mpGxenr))Jh_w}qt9|`q&AQvxWrtCY z`@tMy_uB-#ttLxduklhB=n^*aFBeT6Mil|?>xp-?anfa!v6cWBhuJ0uj=s<frb#az zM8xy>;o{;FmySjU^ZAT=_?e18o(drEGb<hr8|7*^jB?P;PP3)gy~fWqVG`OnSnFE2 zUg7=y79nw)Ioa(Ft~Z>Chpl#3FS^2{W^=w+TwGoeK{K4!dRLil{I2Myey>@-GfxwA z49$z>9Bb)9{5-NQ%pB`kDNF<;U%x&7%^&^fN~iyY<~rTK-dikJxR!2X6V_v_JWWHm zLlazKyauD_n$tV5OTcro0)&gVG~f4c*MZ6VM!j`geeXX_mIuL&f}Az6wZEEVJCG}a z(02=|AW&A~qH@YV5Bl4MU8ZWD1hN3aq+9!YH{1|}RiOb?+RZXfL8be3<RU8sREf=y zCfH~6V8x(6Y&Q1aygmQwtFPEQ4-b#@4G4W#Uw3_V2bV2RYS=B(B|CHrXag)O7Cx!2 zDG>}CT2RbU?KHFy7lSza>Twl4*0Gw+=j`*WFLnpc%4g^2gW*8et!Crk=%6>y%l!9Q z&N@1~S#6ct&FGmvL%Ri=lrps}U|l4t1dD-`4^E<XfG#I0U0G6<GQSM?(Lz;iowEzB z&YIV{y#F6bAavZI&MC0n{v<C0Zqnipy86dfS>gC^SF`pHglsJcQl^Wp!E$SO77cO1 zU{+LGr<A{_^dP*WLfIH0j&OPYi&2btCR{`oSf&h@rc4dH_VZm;9vT4e`T&J>0o*U< zGnPYpv6OW}Te2LlnVH1mb8~3cKFof6*A9Xbe+L+~RIvtR>_}80kljV<kEE?1F$;jN z?>oRd0$>`p9ROPqg~%x!>;@2sVOa<Yl;(;6yW!M9MGHVz<h^^6Mz7UvQv1%rz%(e^ zX1Fx-%gCjsNwX@`<*eas9a%CHhHKF}fC!ZWd%CkxE|?Ee{<Z-iac|pTwV9a-_~q)B z0l3Z_kXQx6yPCBTddR)bg4_xUvzVErS(~fmtYNXtuK<OXu~?WasAf^u95j%^Ni}Q8 z!psn7=>=KnP<G32&YGVA$E~<lhKshMB5A;6Eo7ZWXqEjm0pQr+C{ot4xt7yRRI+*g zS8#ZENJ=SUtXUS$Xf%5E?DSvwo!>b+8XO*tPEQX{9~~bY3|XuZ59rDf?PCrGVfH?| z=i$*nZ!Xx|BQ)ls!YO7lom@`FT8Hav4ks&x9R#ZEcldlS9%ri{d;ZoWbgv^8bLgu( zzw`;3qQlXU0i@v`kx-{O9QI#+@cffcKAO#E2L}h!>E!6>=<@RN^z?K*9^=p9a6lg+ za5%m8@S%+$4+FGYT(9DqsJ$2&0;+I++OG@jKRP{O@Zl>u3_Y>E67wivQvj?h1a|r8 z39UgSw&mCclV)H?yJXd_9x&EVM#UvW$2J}Bn3B|DGt*fx_OrpTKhe|C*S%gJ+g`tZ zjh@5f;}$WY-h<pEvXlc?3h4A<!~XtH|AAWp@ZbDfzk+Sc*^EZfgAL(iOx7YYM?Thb z-QGJnH>~kiaKu6!J@gA;L-r(0nnM64V+IErs7E2d1miMxc6R0$TD*PxmXraSOeXY; zaptn1Z<zOoy<Qg@W9T>hUT@H4bmK*3;Z@HIJ@ZU-i@(%*YyyPudeB}H^j%kC^;y4H zyy$j%I3G!j!Hl>Gyo$4rp2_FbO_B7dYntTx5_NoUoa+hlolch%HdThhL&E!oe%@K{ z&Hnt0FTVHv@AU@*dKzP$7A$U|7KEDDWRS<K9598jR@D7a7lxDJY)%7d5#1BJ4ovte z>ntgUPQ*RoUOxylmyuWnGi3ty>MrC704jQN3hGMKOd#bSh+WloS*sOTE2VY(pE4yN zc86KnY-`gxxnBTm85fmd0n=AkSBOC{+gau;0g4og#*e_wrgMEd)$KCjq0i3V>XT6Y z>b`a}YO!@|nZy@W=(0Egx6Wc24u^TlnQ4KG@t71PK>M=Z6su3d*pJvuhNDrh-=nK6 z&#B%!Fc}Pn?Emau81vDGAEB1r=KTCTt{sBaCa_tsAD4I)nMxMmQgg~_C7V+dTY)!B zxclBN?vO`ptHL{~RN(3nRz3`_m@)<GoC3GzTLykJQLDIJPo4l3>}odqC&PT^n@gRA z?-9h|Ayrkkvs*jyjtXw#rlEHQz%I=k%ajrIb~gH7U;vESwjAGLIW){l7oaUkTtn8E zPM82%yGndO1``@4S5n^sgu_B+=W#8o;#@I`pW~%Pm|8`}v7G9p=3CxXe*WM1H%z}L znw(2$01BmMRkAh(g8r~^K~MxuYRgEWz3XMTA{MjDWezD7fqd6M6&()Uair!?eUIN4 ziT9r9b9xnVG>TsZ(Qi+2go@KAryZ1$r6|Ud1{gDrenF?3LTZ!-GRR^QME0*N3#*{R z!;0i-+dXAF<^o_D1gPask!H;<HPFLY(mSe?MG_6jz-P!!Q_--zE-+ygur{h2&~Rvr z6u1h2Ff$utSR2N>J7!u>xo#%PbhMx*(2%RZ$@-loH7r0{?vzv%aA}!u!j6SNr<IdM z5<aRt-RS~0K#-*`l#)e&l&mzyLNx)(MRsFG*e+kuF9Z;?RdA3rLhu%B6`%^B3QQ!e z%0)0;icX+4U+_&>m~18tXj<?LF)VM;iV65-{n?~S6~aP_fL+Ia#94u<_q%`h?}*1y z7i>p#7iaT_Hm3G`wir*YFbdu5oA5DevA7x?_CI*}!NI`@4u=v-U%z>Cc6Nasgc(G@ zSVVk-@8`3*HaI*_s7Fl8Nb1>Lx`he)0ZGk5){qRxel5liUw&gTU-a7DgTsUMLJy35 z@a*|VAH6(1KK$gHpA5R3iuQlow?29P;>oDref;DRC$8ba@c8(MwN7<XMNq9Klf)g5 zp-ZckCT8<7(+55S-RpPJM&BosF>xkF;4q9M`lC9vpy$&G!n%{GpE7FESzJqLSMu$P z^UFbhG`^Z1jEL@L6zPJe`GpKKL9U1@ntO$B_w@cJ-3UcsMIcP6hFU|fLBxyk{Ih0} z{Iw*Q>^^<^<nZt?Zj>;u;`Xaz?`y6hR~J`r-@G37hrjn<{_mkG<FEeJzeMcU@AhyR z^B^ua3pC<(`qJ<9A(*5T>9)K!vE_p6jc(59W7h~c_u*Zybno}&2Om;P4=C$tc%t+b z!$qj6Td5eyf7lwKG$Cb|u(sJ`hG8XP_2JQBuir<8!|Y<FXSo}DT3>5igiqFrLZO+E z1oD?xm-E?@V{W_EWd<&$b965j%lTZN+Gu8`hpus$LUtBVbXQrNGa4Q;F7%7cV!osj zV|RM`2>)XsM|b?HO`_ReE?4@lAi84iY4z&YlGT<5OEZ4Y&%TexvoF4U_2$i6hGaaR z(nsl6(~Pd3on}5T?79HOs@KBP!0S)rS|IF9Kmgrz$Da{+zF~^RtRVvqlfg<rC`j-U zhpDw)$iP8!s(c&NaA{e<8Vsom6lDyS>fG}W1yr(rAO(Rk4N_zAEL@on$bxXZkhleZ z7m`rG70WQ+lG(5fmm0U6`yQxhPIlN5R(hp7@M7$8DJV*|!$q!QN$AQXF;SivAj?B! z8PjGu)v74MX=qjiS?STVhtp=QUz}eM`Vxq;&|baziXj^fha6#b-}idmZZ-SEzP>jz zo3R)<*s{|@@E7lPXk1-h62c;;r;XrpX<(n!3-IC<5;0O<ocbu19Zb(?#0P{iO5$Lj zHlWz*!|ZOacYJbua(bdA-E7V#ST~bP!#_yU74)ilaiyk+hNPkJ1~8M>!+Ez*kt~B! zYEgF=TsPBHvAp?Yor26P1Eyt6J2hyUlwrbVIW5Lc!f`dqlG!|W#590!&;p9-ivN7g zf(X0Bfw=v*9k|*Cqy`FWOEd8nJi#mptOUfhiG1~ss}DzgwpeIwQL>u9eSNO&vwq|u z+zVUlF8I$J%A)-$$~KfCwQleBAGX^RRH9bQl*Rvg7pDK1aT>slA{S-ju+-^vJ8hyq zHa#64?13_(-P9Sw91seX%}l46Y20)Z>nLYGmiIVE_!IoN)sd{0!B_>s-*x_}1<fhu zNwlEPRai|N2lNdlm%@S8=Uwr~6_Un~=jhbYZw)RO1^Chv0<l2%Iq9jf{eAWg4gj1w zJcl`Gz{G3<BG##wDjbe#(DVZuP}kMj80eV03`ZS}v+kexlYi3u_k_L!?8eAA1#YYY zn?;c&frSlcGZQgO(r0swsAr@FT!sr$rlbU>y_1<3gF^xQa;;1-Y-J>736{+ASqu&~ zlX`CXQ_@v&JKDk^SA;0j$Y`UAUQ@kXWh+8!n(I`jU(_XaMe_}}QclZRhrXU<nTek4 zw+yo8n8>P}rHZqFY)%11z-rBj8c73bCZcdVa@`83Wj`R`E|A4|dSn5&1)SZg#{#mW zu%S%2ZWJavQDQ&WLDPvUkSm(5a8PAB+n`BM9DL2O41kd(D~M8|kW6h+6zl|-8unPO z4vlLL5BgUZm&{)JhX5i33~WRF{y@L>tJQ-s=-F_98I5|aHi1fyh+;GvP=N-g^ZCWa z1?mR<0pf(o#K7!VS_<p+fx>KgiLeSEqERt#$J1T|hb8QNXd7{Q8V-(zM~EIA96Wpa z<mBY!*^?(9ynKFoa&&#Ydivzi>FLSK51xPPTOS`C4jcRFDY#}!FU{98c-Plh&J4$B zk5}|t9XGIq^ABeEUMn(`B1{!+_u;@WEcqOgc!)F9`T529`T5m&LO+nF6`d^hwM`HD z2lR9}7}0AMRvI~dXBFp2hGvT~cWjJac5^AGQQZ%YA&Xj)v#IPPF|~*gbW0pli2#YQ z2{b983pCKtZQy24k$iu(SpEJ#^godG1%B}t{(`PLO9@}=NLpM1wb^L%Va1!7`%c2p zs5m@hf-c}62s(>N5Y|ssjKsQZGdgjO=2h{1JRtp{9D-CA)9?bC&=y-JS5hsac1xe} z5%eNynlU;$JjC1a;YHf7bR@ghx7oSG#>qn-in*+n+i2*?b6N}idg@y?$t*t`FWZnr zGZr%Kee)Je7+L9KqQ?Wzt2Jl1^>jABx*A_x@OLqpOtF^6<tF-Z8~89$_X9m5#V&k{ zN!UQ|$Y%H67YYr8>}TK+F<paX5XiztC7Yo$+(W=1TRBLq09j9f3=8bCvm*RXRGQ1k zTnm)buLXA~+S=cDHeIoEmml7#r-C1&-AreY)icc-oz_@&+Q3(FBcic4p7?9_`h2b3 zNnc)AE|%?9n|M_VFOE9ibs?Dl5b&AvWLbV{QAciNZ<;G;B(-+cthN|^KPHaotXO>} z8ncK(?f#ukzu*7x<x3Qv#fxOQp7{opeyT0}X@%-Uz}3reqrllb3g(cyO3peppzFvQ zDyTPoPq?AnoV-`S+0<fjem37Juzco}(xPI4vcUae{YGLXs}fxSe%RWsMtB>_YRll# zov8Z(En(vpB#GO&CqEPfXR}?N{xbgo(~lXAu(R93om<G7O+-L@i>dsbK!(<%M%rFT zoduT3&_%Z3mrJ2Fn6+7F&8D5DckUpxD`o-Gz2Z}2OZxoA=D=nGe2Ty=lp5?gq)6g7 z^iaf>0<s1l70Bv}zFPg8f9g-EmG_2TxXM4a9wh5y(=mtUa|*C5%UjZLHZ$d<qW|U? zQ7<HmgN4O%Ma#Q7fTjp0be1t~KJGAWSOCNa6*oxS0+uYN^vhz>5^$C#fHzap4ErI= zXPR0_nv-?9$V3I@cB84(R=F;qG$XMJon~4d;1K2wQv?Dg$T9#rGc#Nfl(VKmu4n?= zoHdX%AG)0G0@V|B8}QwzJph4`a4c_|vsKaH_ExezM&g!`3JTz*RB#(O(1gV@Vg1hL z06am%z7()NT?)v$7p&WCHl;8@h}r))PR^*P%>;TfT?S0+gwCxK09{>Py?K3haej4m zIpv^#b*0DKR!hBLiLNnCHi`k+h^|(v>0V=fpcr`nV8nj|R4kW^`Es^UAi=4lPb|uQ zrLSozR-&AUl#rM?mfqt>U7B?m$%qj#9vqCGJbC=|+2hAg9-W*XKYsM2-|G_ne)Qpo z&z?U0-~-6VgT5l<<D<h4F<+-S81&fxAgH^En*$1=q*L1zsX{*8ug1M;J(7kS=r)FF z!s7v4LXklc@^CCx{Oz@yZ7MlVW3OO??RI<o&8G|a^t9g_>W*b^fFrPqoqoU3bZy+t zAx#glH1|0x#`kQ|kEQsR5N;27Y@rni@_&TN=)hWxG$%In{p<CH$Z$4a933BHgFZj? z?@MWxQLV+*;t%|x|GsQ5@Jqk&7xW3U<}Fjgv(cSm1*t{dfL+mgnivK2!Yw+hg|yy_ zkEj)xP4rtM%cz*95Lrf_i;lu{_Gw(FhvXZC_8gMu`u$<N43GF-H_t^N6;sg@Fy>%h z$c;|NpMpm)9FK(~)M>T-kv&5iH|BMpnuZBn84g_@;)7&*AYFU=dVzH`;-`f$iq)lI z;o{ilT;3z0!(3HJBPwn%zZd$s<dr_H-!w2A#&kNLPG{#Amv7&my*;}aPsWP{XLofC z<@(!1S`c>2{XsYF<nW|SfCK$dJrMx=52!i{BHgMd47Rzq1$M|I?JD>Ea~F)HVmFW} z7G@Qi9}mIK=63AEUl(?%+iE|p?=m0{eK`f5A$8oxZ)&WB#JvsVT~tm%nV&(Hjfg>u z701~_n}D9;Sg+>G`PJ3c#l`u2K4(RCS!hJIjYh9O&_auYsWq_JO#^83cr8$*9YWvX zRO`hS9blEJK^APpzg#=wHH4_6D&_0V^<t&ZUA1BA*ZcYh2M5O|$Dq}2T}{RqhM9x@ zfGyN20WAXUbMY(&oO-V<1K-S?VtJHTA?Y1R5;dga2f`K0)k9fbTjIE=E>PhYM~+*d zGz;7l_N2X<IgvV7#a8{%>h^ZG%7cdnz_zfCR9wTZq6$BB1V>kgEuhph90TI=m(H%c z0^p>rK&Th+r-{rru?rT?fa7uTe71m@K=u?@6N4fH+A`(?m}KdWOR4KpE!bGLAti(Y z0fBM=%(g)E>(9G=L(xYO>p=j-ks|>nMd3D0TAGNDzw~G-d@8c8|Ky+k)6vxXqRFYW zY&xI~uyrHAINC<WS<4&FW~P-uP{lNG5s2DyXpN~RESw!}Cid7hNV<p=W6TMu8+&f& zQmK(x!OSVJuS29%Q(sNgSGQ?8w;t9B7ARLS4WN@yz(pZa1*O*P)PQe$jKmEjR-w>L z;Bf&Eo+54+pxHAOf^1kMxMJp5(nJ}^xS}mIT}G%8QvOcVs~fIPihyNo6*MW{01)uu zL~D07R}p}&*9!H5`4wb-7B&GgKbL~ck@W$uplmiUKS(Q2s_F=t1ZT67TpEJXZ^BH2 zsA4*q6Y)+bv$MAsUw!rFtFPj5=CiYd(ILXa;o$W2^!P+S{2PCre!s_@6FnTn?@-Kj zPoSZvWNCP{SkDO5=5hBjzGccWh$h+5di_p+z#7rcK)})Iw1>mt)2B~ge)!_$haWtB z`uOzp<ml+|^yIYL?;IT+jE+WJ7dkxzTg&TZuiMdAIIoG=nDCs!Hl4P<A9gvO5?p!X zW9wx0(o^<L9EknlU7_eW+oBFY2(w_>ZxKVDt=1cKzFcKD_BwipR=3+B>}_|nG$>-> zsB3L~Gi^9LST0um{(vBvW1a%9n<*nD7(z;~b!^l9X9bREz&7NOp<Q5u0V5W*1l)!3 z5MdF)eq%H`fVZ!2d|YqV425K={O|s+|Ibim{Iy^H3pkLf4HQ7h80n|cR<nc6vGx(v z+KDC<z;fZid!8+vh4TJ@%_a<JWVm>#E5#>h0C^+<BW|@g7NlO#K)l)-pdSumj2fUK zG)$C)k#aS}YLVU+tJY(16h-S`ty@g&VH9Bv%J3X1L8XFUeQavy)2<piKffS~RwS;^ zD8%86uHW|4L*{zEn(!J=(avN#ySkd55&K?@&n_-W#}gI_0V)$(_wHpx4d_hN{lEmk zeuEAI)AG{&p%;6BG%mJ*)G)J#80cE*F8PP`DkerWE+p1AB#A&`-3EFRbwBLVQ%07# zkMKRQOHsvs^)rz2cOr{HXnJqMu6bhrn=UtZpQg(dvmVk6mFZn~T5AYk8|x+LJ$<`j zIiF0XS67#_^i#ckt`RI+t;Sf(_6am#{>R3gj;bhv$<Bl@*Aw;;bv)#?fVCItX$}a) zT+0Ib5R2_y-;&ej!!{ASU6aGj;o;$vr%y-2A^gd7%0|T|(e3J-mW=_>Y9)dY!yHl* z6_{@&6;PVh-V?6%W55+F)$7@`X>OB;E@ut=ny5gQsY|{St_xB=IcK|`vKYt}8Ci2G zsK{r0T><c}ail0ww^8ATj^Hq%w}DbOktNB3hX%ktA!d$C?}jBo%16`X`EN@MeXLyq z9Lt!NKmk`Q(?E;5H~^H3vH&L(Xkf{Fii=Ak2gUSRJOZvu08DBPfLgAIjGDRK5Jg|x zBhWg4-uAMM$c{5Vr&w>ooD63(Gn|m-fwRFDl4Rka4EQbrc8x)ANhz{Uki|@wVLsR| z_ObA!7K4eh)5|G*%aEehe6oy_#|!}zz{1E_tV~k{BFs!mAdok|4!7tOz(E+e6qs)y zX0=A*2ACooG)c3<m^OOuh@muK=8EVc3!rI^tZP94iy1IYAdo>eizQaToI8-U)sa*L zvKi2%nFh8Qs7?(?y3|PAa6+yax_z0~IBo^<i7MuUYh@+CnhjKuhMNV%5H=Hn6nU6H z(s}|`2LN-*uw=;Gf>pUlZ5IUdQ^f)Eg}sK}7_{HUB4Syc^e5B#jEF#64>_)egTdh7 z@L)6=jz)tch+(hOY?2aztX8w@)uKs9InXbcliB#{>WWZ7FCZb-Vd*v+gpcY%Q(bnG zK#XSd@sra}KKc0Lk3V|!=#)r1_P)-3i{S2>O3Uj7rzrxxW@~S@oUVx2HY?0HJUQ-m zI{SLqcz-;bFIVesPj3!Hbsi@C<1}0cNtgYn*R%v~eF5IW;Tnd3VZetfR91I9q=cO) z?m#Zsf>*2MU@+t?#ns{H;F!J-dc*Z{-D!96oxfqk|1qE>>&>3-rPFH+pgGCtl7ksH zla0n<f>>lJ5Q1hqAuH2#6SK8i>KnI2nF{^lt3>TizuO!9SAXJPmi-0(?LYb7mV;zA zwrERQt@UoJ@I4zq$5F2LNSmO0x0{XlYlQUuUYe6B#k7=+jC8-mA-W`VB$G?g>8+0u z$+ZBq`LU?vUjE>_Y0|}Fj+CpDAa8%@6*}s-oW;=bM+Zc=^)3Kv;Y^&AtkJ%$JO4m> zr5R`iy?OHnJ^?UA$nZx&8~@X2JXNm7_V!r?msjKS^UGJS-;A$V4KscBm}@ZJO9O=V z{3kycw3Vp)f%#7_fQ^KRmF`u4Z)m!LWJdH@+DOgWhV5I&t||}fRk%n-1QP2`>=M&x zJOp>>DHmn>p60z1yR<yi{#|zN(z9!-WO+1LNhY>pSG&NpDi;X0PQ-*&dcb4vTK8nz zEJ(d`LEr1!Ys_c!tILbobjtR_9M`rVb+nOb9j&=Kkn*Pwqx3V{db9(ArA?=<*?i-> zl5n9gkR5|my=7PAg3Dsjg7ybtdu+n`9bwiFi#hH&EB=kuv{<s57yW+!`HL5ipFCk3 zz^dW!K&=GmQ7l27i0XcJe~VrxM;T<*uaZDcca0ZCyO1Ov2v^M2L({F+3(ie8r+0wO zxi0h0T3bP_ToJ<z*yhwxZ{?<b4ZBJn902dqvwIv9bsH7FEH_8ji=D_~g>yJIML`Ya z_3l~;>cL%2RNzX$S+@(A&*lKKi3)pCg+Stl9#=FUz;s1tSzj(?eWARpzl@Gvcq!1q z{Asv93TF@CG@`?3d^&7}afnjWaZb=&MKev1g-%Mt2Ay&`ouB*Te>}0?4|=vRH;@VJ z*t!whTnHqyu;FZGA_*YSW5Q`k?3R2cvVYA4uE<7=F95V%gJz3?Y^~)<wUri}GHk#3 zIR$7&iFKl(P@(|XV!-V(0Kk^yqD&(|UH8Hq)4L{$8wFX3+AchhVF7@)Tx1TQlqzsY z5x_QQT}0Csi%O{$GM>S3vV}IDQc_@f0LQ6erjb}B<tBCkdlGdUR+9bT)=fu=iVSCg zs_g(`CJ;jvse9@ypv&%cmaM=N3<4RqMXKh532ml<jOPQT_O_X>OG*}kQdLu_1L>rv zj4VuQn1i)uhEzg@FXP<AUfiLLTb7(UBJRKgZO$%Vef9e7+l$M~O9dEFmy?9z&tY%S z?+^%c>{-s|c#Gr6Y(C|@qTdUiOgYUo2w_=1ev_F_J{uyoxuD;e?e#jNgTd%v`26|P zmoGm!Jw0KWzz4)&geZ;Xb*J09ZZJ95qod)$!GJ?hx7X$L)b8jNCezuBIJrL<sl)qC z&On&wuXNHcJ&N7$<7aj7Ht6(lG(d*ciabD!*4cBt7Gy&)B0%b6Way5MQ!Ff^bi(z? zWWtGx_^Z?HTwPAsmnY*HEzntN74C;1`c+5JN*0}N2pgCHo@_=m=nX-G1&{<Ve4o=A zTYC8idhsx8Q(skG>kGb{pZuwRH7N@G;(zdeM3=Thy$4W_voATZu27B>I6ty4QR?|n z=wsycJRwffmwxe~hA&W_t2u>3O~}-fh~L6SO)#?22?2RJg3lL=8P>a-z)U8XVNM2F zBsnG9Le$c5lxT-%Cd5{sJVT2`>qy#}@YOqj$=E}WdVPJmOcwJ)d=Gz;m0uc7+{h$4 z*Q~!fKfhS&sY>~uLaCD{s3|`b@K_7d^$=io7^VwWrXiwm3%2W*UC9OukgCJQKEDlH z_9alsW<0D{cqFzmBe4Q?J2T9$V7L9-u}cq%{BKzxn%yD)K<v_zhtdtXMPOzf75^Bf zqh1xBFm<@yBvgV+>$tmJrx|2f2A*BaTNrGfoDRscW?Id5FJ6^8nT!EfgR_hCgTn)A zWoub|fGl>hB;lZkDrU0SB*cn?U?Zg<)*hQdha(5o5o*Sp4>(_O4$&8hV@EB%C8!GV z{%2xcNYwWFT(I=U$CHzj7ax4^`qdlc+4=nmpgWa`GR)b^H=I?Ag%8X0J(2Z16t0-7 zm+f)ZNSC8+@`ke|vlEev%3}A2tCTB-Zy1{G^EOMC3DG;;nZ+u2XaKxj%Wmvyx5Ag{ z=4|e2A=k?Of9M_H8~~@>yTBSDtqZ5MQ=7d=SvaHM$F=A7ZlANJ0cvB#r$e$~8KWHm zFiZs4OnL#1A8^<i^7Ci_4hjc@K9c4DIIa#L$eOk`@P~i)XU%y}=q=FvBa;KUrA(L8 zOjy_)!`aM4EK8bWs9KUtjw^8lb}`d*l@vOwBE>Z@?f1-AwE|>~xZ9KJg2W6B5SA>b zw2Mvv?E!#hE2oqc&}dEp<A)?bz#2?bqya26z;UDSEmHwSq=;D<I2(lt=34-HQZsWA z(A6RU0kYcMu1ih8M?mv8?o>d-bT-QvQXLJI%_}1_>qT3Eo<!Av2Dg&402`p?@zOyY z=G}TS5-WOSA~P)joUOq6T?-mu0RD->q@+@pEb@jq)G|#<sr5uH3nZ~JC=G$6JgYL{ z(lQE#g7r&`d8PP>twv9>#$=Ezu|ucZ)g45I2ThJB#Kzrje>5C!ma}fV(eHJx*TjP} z{Up);-sR;*uhUg9qF+Vb(`$R@x)0oG>)Wb>e(#WYS3euvKNyZ4Jvw>v_|Z2${D}1E z;E)rPZUU^A`cNNf-Hj#y*4+e(Mn@wS(wp<Qrza;@(=nb{tXF4m&l=6v!RR2KB4yAu z8{<Hx_i1_eRG)9QCfyZeUNAJQcUnW3g-J@O=QFgFCFlqie>#5Q1yn^S%UVzzH5d%O z{PGL<%jKHjd3-e?h+fR~iczY>6ySgUr4|-Q6$)^#SD)P4>L84n5yGV<39!euBT0%R zD8@}k!+xh1^SjCZr(bE-B4*#%{LJtBLrEs^tAFMH)YvQ;wgs`bdO;A$kh4#<;;$L; zI1cjms++`mYuReuX?JikP2zSr4i~ZH*{rZ9CQSTo6k}pHn~cWHMpoe-nN}OxJ+5O& z(#HXc-(c$nU3xzx+4#I!f2MH}Cdn(zO!-j`jJdkv{3}iRp<R$(kwp_4eg4(6kW6M= zt;YF3RwahY5;*oMe`&K&vd;>bPG?u~9E5(4RBgr$bRWfKmN;@)f(-Rv6g~iSftJzg z3q0m!rUfe4-axtooPZ2)hr&5q5eq-yyiv(!G~z9$_y1#*tQ;g2f$*O=^>izC+rJ&V zR544pws=R=55g`jjA^}H(p~-9Di1uGTVa6;tf!8LwhJ;RgY0sdrYH(AjkU)@Bc7yG zd>vtcLe|-A`u6N>GM!#sT`{qj@uC`*Cvc~j^Rb+@Z*x>d;e0mRXAAXuD*|9`57)X~ ztbH=xm=I5eH1sN2?XfL1FP2MqaHNn8ac?soPkQmQNpt{9V4j?weDd)pufBTCj;+qv z;8=95K@5NfG)PLRv$?aRt_4hIemUI*SF9ryKOC-`HDD(O80Js}ld;IzoR*0)qV~h) z?Hwp<C|M<cZbhZVl<sKP0(Cqz0FEwi!7lyx<daRD%?>+DS4Ou8q5KZ_gltk}8U(GS zWM&k;15xjmd~V&TVKGgr(tZw7aR|7g`2eP~F4Zm&S+)pY-7Mfz1N}OR1dw58@ZpLT z>Q(6gm_?1SE3)LR#91#-=_&*a_@r?D$j|+pMBf{F1lk&%g4~%*8>Y)$4R(UFnTc4I z%ydSGk)$e_AjLtZ-Bs5G_zr$9f`j|mBJnRA!vY3-H8LJ817;>HTu#xZVT%!^7AaXb z1Wk$nz&zd5DBjHt)Ns)>1k*zMdK`#d1OW%WWhy|D)NNVbsMwiHQAKKICP>k5m`_Kb zefhBgMpg@Ld6$y93N!+$6Osn<W%Cj@#Nb1enRmnTTY(a{;?~tt*a<Vkr3gd2RvoSg zQa(`bdxn*yObumuI|ndcWX&hdaF!|_dT6QuXlH@#4^n4&msC=WvOtki*HefhT0w)- z&?Lz=fsNW#;!?>geu$WmPNPBZ0MZLZh>5vwa@bg|^zErPZ!ccIIU7&r3l1oI%T|1| zSFgZdOoxLmJJ|Wz*=Tg28)>v~y_rtulkpUlEXL8n=+V>1-}uIdAAI=1)2F8=Pfnga zc_hw<9}W(Ngd~KaECY_&t(IN@NbF2RNSL9ZI0A$7i;M4l?|Z|85pl`k(b4hoF&<&g z5}thd<(Dmef~a4F#qYYs*X!Zf>2&ISAlyZtHw0<=Z-4*d;u4oe;KRjLkLGd3hZ7Ik zVZPGB&tPvpo#DS$yM;Ufn7S9BiQ#b6Y&DM#k7)7W;DAB!j}Ifs1kmA3j;8|lvKTeB zVii-W_cZ7S-Zpw2ap=SjjTfaJGnzmNy&#pT?#uONKA*-%6^hH4D6HHLogVal;wOGT zG8upESN^Z8PaPfi*8BJfe}zrD7Dd<9dqw854a;dA+weKIv3H45M68RDSC+Rj3<D7E z%WA#SBkOcSQQ}%D%_-cz?ljx@wn;lpJ?6CEYP59mYA|i+3JPUNu~>k!2Bkn<>vXSI z+Hl%__F3X8=O3EG3Kg|mosJ%8mr2*lUayOv*6GJE>`eLd>`Xr@IGa!7f+|^!GMihx zKAMHQ-ZZ$ROs4bkcs5@!x%M~vP0bChLH<p>za0SIAiVMb&;<q;^RSj)K>G+z)&dpS z?KQx(yzSGvc3P-$t(^KVdU9Lg4*f`P=kLND0WfLiXJQw2`C%7!Y0K?yP2V58v@pX+ zX(cyjVpqR**%=df3n<zO+D#I-@z8e5*$lFrNSV4=1+CMoe%Nm@9*>_qdBTRk0%P-F zvti|;c{-c_r{De0E-$Z$P#5zhE3zFw?n@DSJqoF^T+Qhst9Z3u&Zcvgfo3#TA;dKH zb{o#*P=!1kS!Ks>Hjf`Y)(3!bO3@4R0+=@(4Y`1fuddj*u!dtbJz)npJUpO?)2v@N zOVe>!(_?PBTN>?pk^4^@WdOA%><7cla=HuUT3-vSFsn6DHqtXk*V2NMQxlmsin>a3 zX(sOO-B#qfpk$b4&MxFCnV_c98d7Nuj9;Sehh6>JrT?CMvWdea-T@B~1hdy>sLl@e zc*SK%G60!aC7>;ew!nIFX=z*%#{{Xt+DlZxG60&oZpeUXZO*!s=2%%;T*VgTQusiG zPCkM!f<(XmF(l4cIRK8mltTyy1HFrcO#nUCOiD%cpdl%|?bV<CV}A_#{m~o_`lz!~ z8lY9TM3!PVX_(elRlv+_AK5Y=RrCb9+yMXw#Ad25MkD5v8BAy#!C@DFA#bN3!!dL= zpK$O(hi)mb7<?z8wXbbX_e)kfIcbN}AxYmeDH($*Ea4ymP*^qw$eQ>F6Pi+70bzMk zPUk4G22yBb09k;H$H}b##?>@@h%iBpg#%$f8)`KKqF(YjuAtW_A?sR3Rs~!U<SZ#u z3acOx#xS=|bDn1)YDm&4%8|E+sY3UG$AVIjnP`KCL#fqzykOFO>xV<S_USYZ{r*-S zwcv+70S>j?HRy86L6H(_phhZmGsh*=y7_}i=lH{ftTTfOZZ746127vGZdC{ef72*e zO{8!?CPOomPz9*NFf$U%l^zDBJ`GqAOd4=2%oVz37Xf#ZB0NLtA~Q)NtB=?jF{UmC z22Z;QC;u=EhtoJ!MMo1%GiicD`(Ya6>oLbjsV8+Q|1YnXgei^o{(A3vzFI5^4msAe zJB;^uI_VEbtxoUk{Ib>V4G#|AzInU1oIN=`q-$qqZw`)zCnv{?<!rf}vD^m3!QtUi zyVGT|V8GL7&%gQ2kH7O@`PT8HQLo?X^qakYw?FKS4$(AP>GyfCIeyWPagyuw8m+wz z5lKrw63jemv<YN7?aqs5FOCk6>AYTvq+4@3*{}efJ$XV{E3Jb8Vl3(9e8Gb6cJ=$T z1Om7Zk0{cSf8?ErA@xF|nEY*GIQ+m&!6(d8b`)kZUT11(c5E8N{I6cWy1cw3vKkFX zG<r3j%w`<gkkQgOKR=Uq*UQb`>gwtWw@haf_H`yId%|a*eR_F$!5~td_ODmh^VxDb znZ$AMnjXz&OSXO7H6BknJ`yi3m#ee0^W&2vhKd0KF?`x^A_Cv*_PgzFYpp$C&Q7pi z&1ci`@B97#nmSnESO3~yVgFK$xVK&|W{cSrr?GW$_|yY{^NVf=Z>t;|^w9f0{wE&m zoL!vJb!M{v*m;{AEAfQd-^>@fAYm9+DYi7s!84erC9yAGjmKBas^PFd>~p=K=><VF z=A%HnO#1Xt<INu<&yaW@h;_`=W!~zhE8U&X7L&=e)$DApVQRNxNyrE!w52mm5syLG ztgiQ#5c>|ewI?yl(|(Kp@F7<RJsqH59ZYvc*p<88K9gZOTkJJj1ihbr`qkSr=2c@n zT`!h63Zt9)cz|t9sjeEj`=rzN#wjfn>Gr>vM%#dQ*qh?^7hrt7qdHqhs#SyTztg3L zUNzU)(@lF;IWwlr!E~9iiJyE7Rdt=3XN9RQvJ6p#J}6-xMOYByqdy%q<1$+LQ)~Js z8jL?zV9+%vY!iyl^=CeF!cA8YhHODDvXLf0g>NQ^4Kr=OnXiA$to<=h{LKi6eA!}8 zfJ1d!(F`n^r_46whAc(}^Kn7qlnj<+$!7D7T=AY@ZEA*s=%BTs#73*hqAd~epogjy zkZ{1XnHg|=tila3*8Uh*pRTf0HGyLiFkRT&*NCk33-E8geEr#{pIw}tpT9kS_2pO7 z>8!)~YK4c}-A<d+02=$O&2ER<RMM9`;`+}1tvGpaPrEv9*O!hXI^|C@AHnA3c+%;0 z*^V%eKJK?zums*S2s}XVm~?t_gsUJD&E~VGkJwuA$7i2^`kO!e;bc1D+HrDn!p@}? zt);xTuk*GV!d*>W;tRi(#$BDKxxyIL(&CUy?I_D+$;_-G_|{ua?+Ggh&eDqZzBoc8 zjw5*bf_HENl7+!0N-3sjT}BVYGpwI;BdLo3d=>)84Q++%Lbw*f;o&WR*$nCg5!?2z z)wSE76}9jDi}S8bQ@{|;+mD?}tK4H->{Q_zT~}y5U5;ZbppN=g!~$MTVT<Z`WFYDY z5y2Wja8q-YKb>IYoPrY<O_%^1Drp_jpuiD{g`}wvU&}%<&H69;hpd=#eQf)=JFvtp z^_tY0ZMm9>&@6St-V8wC83zbdcQgTC`>Hlrjw*WGk3VF&63%8szw@{>XcCCfStU6N zqHKwq*5(s{cI(C;{rR7V^ZsZKA^-*`#dOkC5^%PhVw~wR;MCzFn_h<wG$oXk;0v<Z z3-%6Cie<_v!0B!xMntfDZWqZ6b0{@o8B*XX01lE?1;Ldv^rhj+Y3P$}S%Wzy;FD66 zCAT6AWO=KCaO*}$2`(}+-vk=6&18|Z16{>TQWJoQ3r#6gmPv*i*$M%(*|kt;SRO#T zN*)?#NhzXf#?&$(7MqYN7uCxOGh8FnPF)xCpiv%yO^WJaA|mN+kg^)EIu+M|LIlvC zX&Op_N%+BDjov5=?TTcf4YmQ&%+ElHnH3<6`Y2U(8X+ybB|Vu&32C%z-`+|kp+c2f zKGN7=l!hJzG$QQ#?1CHJE^M_p0k8D??2HG8>D9?W?;9Vzc=YImFr3ZwVthq_$124w zxTD?a5d{;hK7Ib;o8SCx-~9HsFUD^=oz`I3KR6hT4mfP|`uwkGkcfupG|aQFXhCP1 zc&7@{k%m!_(fduN-eR#ticJ&in2H3gy`Fym*0*-)k4`!0)fCWokE5bGt8<gQqd(aA zlji7~`p<5!G4-tj4QsriS*JQ0Wk>FIJ6Mj%VWvWB{=pKeU<s=OCSp3j5ni?1^nEbU zZyFyQ9MEw%hldAGo;;xn3gccZ(5FSNi*IA%sG;F-gpb&1`G?h}@d+?Q7{_ELW&F{? zps)s6jL{Kw|M&jh|3;Dy{PJJ@57yUBs&!iXddyuPJgvEk#(ii`lYa1B9|X{Ub`g9) zkLh)*oqj4DwQiJFsIFIFYwBW*CLA2b{q5T~2Zu+RG4W7<Eb;u0i(G`e8eka|e#TB@ zOu+NPaSF`046uvVT(6^U2r|MPt>FZ%pxl4@SS`{`x6_Zqfg}vmXt4fJ1&h{kgC;pq z10%vk`SqLgt4qRRJqW$mXfu^KHA|ZogjSdmc`35*2ipV6G;rzt5mj94R=R_)l1MC2 zg_-5lovrhCVV7@q)zV1(SjY-ZFkw8nW_r*`VVYwgV3{mg0rE^;Qo>+TRvDA9E*xrv zhfW3*Q6<+(TJF%Z!_K>b!b)0hF{dUfO_v2o%Yd`X&M3##N^kyH)3}rfxkGr{WyhIL zW^6p{$fJXiJ_9SB-B_;XD}64$r(-#nyz~NCwjb?3j72YAs;Bi_94z&AfPDopY!g;O z%BDdoBLW-tJGLI#qC*Ek@#W<??Q)5F_WbFK=g-;OG3l$XzC1cOWX3FK3pN$DGWI|$ z$KbtII`5%h{STl&5&owHTHK0UrHWnr9~YH|JX{_%7m*q&sKa|*4QQ}SLAmZuJ-e{W zLAUWvwGVCA9;gGZRaMd~pBplv*&B3u!--j`Y3X^QSsUj<Nycr7`y)4ZPdrqfGmfj2 z(=t&3{EF)=N#D&UoBaR>BGZ7PxR~prpZTuNQiacQBhA{N{S-7=7QXKTUvCuLav~zQ zE60PmU4XaUL<L`40PH)!P$;G0a@!`#DL@$7Fh3I%8JQ1qww#KH(+r?R?{3f>zwi_? z%rmlx*&a<peVlMh38^8YV>~Pjr|dP$fM`vhq^5kqL70@f=D3zs0W2ZS!ck8xItAtf z7a?qZ)V=`%FloJPr)yaNgo1>`3Ro;RVZh%-7|6S>`Q;SA2M`#8|G6-9<KZED13r?N zY7H>6+0KGcBUn-(%qh+#`kbjS7y<Z(v%o|tt3N!%AL3N?ALjVXOlp4IU(p>Wson-F z%s`SfY)P%u|3WIYOBR}Ow<>p=KdHuDCg@w(mud#0JUKSQOvFrNz`=(WKm#y8*UDAQ z!3A*Yup~f(iQp(eVGM|27?d`F*?x;G;n8Bg=(Ia}$aT5u_xgGUwXuJEJbL-;<muCs z{-E!tg2z*RVUnq_SgiF^GF%-tL=-4d5KCk8<&-Wv*bDb4@^l)#iJ2oal2xMM>TaJn z?in6fDq2%O#oQyMr!u&$pYuT+VaY`w6=v!?s~a786p?96!-blS#E(d-iDJ^KN@U^F zgyTI)YCchaZ!jF7l%NPT?9B+%=d-gnY{#=1{U0wDbCk0|FXlv~t?^hdf#J|bDd19w zUAD8y{EQb+(<IjNM;B-d8=_x?)_RqfEQw#})rYc${SoQ;6Ip%L4KcC|H*+4&PyO_* z?*RYRU-?ThJ2t&udwsoHEcHGoHcQ`}A+DRx^z3<f47=L8`++&}bWFOBO63TE{Sgng z%Y1z{p+}Cfma15FaCm45hM1j!F5o>bT2zPjY(zluaCFl%Aq_@A<`y4Nmib202i+KP z3N<NWUW5x}daOKu2EvTOLOpxwx@Cf5LzQFakFM#v$CP8|a&i6ojo$pcSmN6SK0!<_ z1f>8tAK=iL(>p+OTVYEwvgA9|)!@2y?BY`piC{(<W|mVrm?i5(9k`sN{%2+Nzjr!t z7b?bhIh!M;G4!Nf*BQuUv8{;ta?J^hHO^6tX-VkCT4TJDM8J9gO(fR+V0ouh_cS1- z(I~IsPHXExTO~D-?W`1S1*N;hcJ()}tXn`@pFT1=TJq!R`26C0O2o;|IM)v*5o(S` zLpBz6S9U126;^SlrN=aA2Zd}G9$8Xc<TabTNA%m!qatMB0K{0xNKy-dvPlqR+07&B zZV`<Shr^@elY`MnkD@eN<I5{*_4)&h(N~I>ONicZ5a;i>{<_fu;?S<nr#cyA6x%}; zR7q3?yZ8@8)*qg@LFEIxuw9Z_zKR_?5b`+CE_GdVT>1d)aFEr4lz$iQFKLvWPzJLo z5x3ov<uk_w0Wbt}47mHTVd%pb3s8})<wGD<zbA5Y_rycx^Z2@AIlVuSr)zeRX={K3 zk!hFOQI@Fy0j})`K;tx)HfvBf0S*o*V(GC7lcI?~4)YwM5VqQ^kSxeeSMc=(z(WP) zP$+fVE-;+UDJc7*oLUKK7BDJeP6fYFHm-0!Jgowp!0;CYdME-AWL06C9u8;7WUpD6 zZ4RC00K{ZgfGnvwq!s`bc?;M=(*`sGG)GYu&SEaIF;0PtsB5OJwKiZG!;&E7gX0v* zoEqk5f-YkQ$TF(GZM+PN!NDFKwhN%gRn(2>0$D(jYvm?_Em%oNr{gs!FUZi8U=GNo zWf}o<(BST%*~-gI2$+_vAnVL9hg#9d7FY~8Ya?j_jw~*+z@-qj!C9LZ<q7bCbyAdx zOdD1L;l8+*?aWzVoyeqo4boMDnH&XV-5!xmyVGWk5M1f@UANU942O&9j0pJf;2;9Y zy=PBOzVq#G>^HB8`>^KV=!kSSTW%W7gTs?9=Y{@Je=uq`2|~E?>MYXOCp6NOU?U^0 zz(Ncm)l)5M7!gHQXb<ysyG>@rtdNwT(5>6kdS{bVg~AUwhUL!0G)Hcd3aLUEP6SKR z1&4$xgm7Yqht*KwL$7Oy@{qxpjIZLWD08+8vdG{Z=&)LQ4jhilY}xEEG}r45)+>!W zrEwTbbJAfg@<4rxpb?tz)uAi~P;z;BNz4r2#uR?=eAd6%1%tt7_hLpUMBmp#@;`k$ z0RH7)`imL@^zS#qe~7rhI7bS(oT%#>0M37elJIF_MNl6BFCqeFU_ZT}rusr&^H5JT z!H3D2wQz`_sxdS130Vk=EZ|-fPFMz1^xIJo@R77kpMlqx4(Ovk%!-@S`h*KHjRv8* zD)B$I(btwe<=QcfG-1W^8yxdR#mHkCZ7~X~<@MS5IS2F2o<3ht)tkNPCg<aBRKJzl z^814>=PKp8(b5C3tKFUU1pn?@<+O~QI!mxO>ey9xm;5`C71piII$?U2X27we(>j=| zT*3|y4_TEQ#k3Q~7t)w^Nup3<Jk<WOyft`sGA$Fgf*p3=0kkD*TQ|+Q;or6&zLD|; zCuMezS6;jsNb1|UtR=m(KnrrQSkCn$dn?lK|Hf~8`Q?|aQ$kR7F+yUhkA?>b`y)cC zlj3&3Vo@L(NZLcceiBYEjnMW&HZ0Xu5>S`aVi|<8t=7K2Ii`>Q^t0{#!SL|#==rl} z7nhf<{pNgu%5}Ulq0MriNA#<QPfIh($Q)4a_U4ukZa|epRj`Y{18%(zin2*%+p={q zlW4%qEhzT93hYwgx>f?pbQw`;3$$ZzLn;n!Cftj1Q5n1VyHK7vW%z_}hqhc~LZ5g9 z%rwY)mS+Dzu#LcEhFj*IsAzsC9xAUH8h|RN_e4~cJRM|!JgIW8J!FPUDFS!~Z<r1R z5@tl$8#rg0Mi?=U2gBiz6iHSnE0rBM9|n+d^{gtI5^_-mUt0itFdFiYo5{`RRw*i{ z##TO6athNxTjrEgz>&|b;6d+b_yxq=65!amIEXA&5w55L$e4fw&}oNSXBLA~hMAN` zkJCVgg0ur#3GGr8HH31lFiFV5E-JT6nrlIjb#u-dFb$ZA3bCk^^cY#**$QDB3}|Ob zQH6kEd7~5G_=P|Qw{tAuG%%S=vOmL8nGwpa^_{(R!wpkVr9Ta#_5m!G8I*^JPUWua zMx*i6cj`L}KNpG8ZvkR!lbzI>-B!EZi4QxKRd7XZnZ_wI>hFNn8qU%M7uA6u5QvVY z>%ID`_bKW09iv5`xahAT^ueMooqFvpMbxwy=k4%QY9;zA$b#s5g>ZAEAtk0OW_~6} zRl1QA>VNW>Hv8hQ_^L^BzoYL=%0k`WLsa()m&=pmV}cC^n=XuoLn?42c=Gt<qnD4b z_w+4NLREauL4q?wuRm(&LEu5ZH|q69Z2s4K&2C3~*<wEF_4Ld@tR21Po)l~Klqt<K zjXFARU^zZvu_&O^9lzAm=$E>7a&pX8NGu9XyVTPi*TsTXA}&j^`X8^a^&T%+(xpf6 zV)E(R-TRPMjwHyfctqsl0M-Ho=W&mhnNMG63$y2o8JiCx%rs7NRP1%zg#Kt+%;v-X zAspOAx7r={akd40c<Elak7%Ps{WfxIA8+fy9!1W2-xYk6%WvuJ@w(uuUtU3tJ>oRX z(<o~t;JFqZT`U*B@Aut$1o{_$;ooQKVTK+Pre)2j*gy3#fo=k~^r?aFo5r1Z7C4qI zFbz+rNnD|cEf*-rPTtV(l;{pMmnF6WeW0Q512Zo6B)y|+h!Ha|(DamZEv4846F|^M z!~j*y_t61RWSE8z7@LTA8|$?mfY<L}#VuvRYOQqr0WG!k7q7&@oG?i?JHihR=HY+( zhz@pOCZ0aXL!Q=f<K^W<IS#)1abtXdiJBh8p%5D1n2woNN>Lc>`+`1_=2~TK55lf? zciI#DyK9wG6GquQvWdElU0ryn{5z2qnm~_X4u~0-wvh}MrOY-k8K}j?V*w(`^kAf5 zdb~2M2e`%igSM%a=n^!Ex8hD~?*KXzwT&)w?#4YOahm-P$T}6j(O9wM6b9%LhBA7} zHhy_=aej6_iMW?Na6X%{UmhMEjmML?xW~tK?2{~IeJr<HE|w@|M`Iw+gA%ry`I1di z`pKflpp<oOg4D(!5LjPbUZ9L!p~J4->2k?q?X%y$eEAW3+UH+<!P#aw8XX)S%$Kv* zZ(p;M#aAN>uLZ1A-3zc?=D%HVtu5Ha-+?=%vu#FUp*W^3klnH!y93~@waR|D5BvdQ z9bsDC_?>>+#ovWpc5(?!R0(C_+>i-96Beu0fP+7?b4aP{>hM84$@Ku_=I)7y%V#3N zw3&6#mwIW`OFf04o22la1rS-%3%1|qfOMk=0ldd`yx-~ClgK#w)s2MsK*0j+!+^z( zfSHuKMUd3RzHLqgUuOX9UZFI1IK$bT)(KJrL$h}PMOj-t4L~L*QW1{;2(ng1sWp%V z)N|c(3b>Nt#1N1+D<p+uu`FrxNUa=LKdA`|WElfhCR`Nt1gtfY<xQh11aII{VEL3O zV0qUy0bo*;nSiX*%&ZXDX+lZ^;WpiXvW!a&N}VO8Ej!Ib2nu9LkwFQa<?L#O)Xhb} zsv=Ch0gSS$j9j`cB@xKV`sgoN+NyKJ)c26K01FW-1171fZ-u*0AE6<vL~%j@X7oEv zC(?=~0D4)xOvObRWHTz+vK|*@Bi&+IfPY<7f$NqbCjVdSlBfG<#D~<?Ffo}WPUyFH zy*xM?K0Y}<IXQUo{OLy@KHD@_y+McYX|cK<Pp0P=6UO=E<jHEu>4dPbOV~A=uk=V8 zr=HE~;^K_(m#vKn7LU*C@it;8E(|!07!f`bN`^#72$t<nEWien98&s&9_u%5d#0x_ z$PkFd+v)StP^VBMRqnE9h2Ko8pVes+8N-K}w-M7hPKy@vJl`jdWnOnWox{UJ+9jgn zxJ9t){UqMjFr!t}5XVlZ)5cyawrg!QH~=xKfZ<TjPRp1WEa*;0&kPgR(wuul6)dqI zEJm8M>VlpO)T7-hii+5Xz+%4q1Ap+p2{Yptf8j63bWkZ_V7u9gN7nZn5jmqf-uoqm zOyC&yRk&@bw_d3Te`2lt=^&7fAWcmygox23Y132NhH{F?YOvyWm>FdabbL5SPZ6d_ z3ZqjH)RM0Q<M9|tU~Mi!9uE@{(=tImmbdhkyuI0MqP_&^BT2L$-Y5<n!BlBLZ)L}k zPR*x6)Wz*gcp~k_Y^E<o6Wn7=Bj)7o0Qd&-;O!JWDyRYeE>KEckcSwUe}C+f->E0~ zYJQu5nf0`SJM5$=QMd6>`FA2KG~pSQv!sTZ8C#iUSb%xUq+vOumN~<*tZb)cjNI-$ z!JIQeT~ezhE$hF9JFTq)J=P3N<g8I)=5{mRFf*gh*^20g6j}+$Z)WxiWz`YWvP+zv zJ|YYrPbODa<MZ>2tE(#l(O$Q=iC^GjuW&6?c?d|+*3{>tTGwPzvREw%P_?9sN4+2r zpgI*H4EQom*mU)ID`rR!*DN-1;^2dWgW+HV2E!qyUtV2ZTwYS``1qKsSk|x!HHqFe zUOP~-;WqB)*bJGn4H!u&gvB!AuE5O@yDy|W?cW^$o51tbb#*sKTE{N^cLcyWHOfuY zv5S8Ps8R<Lfiy{M8`fNEf(b~f{uk!qOyKLF=PH1v2>402`-3Wpx*r}YUp@~jR}k++ z7IPI)_5dlgIR-SabC^7w0AYIaKxBDVA53Vj^~i8?@Z$9c=!CwUo!E_$L<z?*{H(SE z)&pn)Vbc|ST>)@|<1cO4R`*K%D|ML0atg{tWzYdqO2fP~dmysBiJL6vw*a&aC`$q> zA%!FJ8rmqK%PHUhXJH%-s6rNbTnw|U0a%i3P7UZ>WRNvrCMwJeae;PiKYS}U9~&$d zYHn>STahKBb}|^?6Z1iC0s;Xuktq|oApi$4gCaQf)H3b@1X&kxI3Oi!K1_!M-4178 z%+Lom_A@PN*6wdU`}|9){4>CZ&tI4bQ@0;bJP)xy!&$72@-1Nbp^ynf>QyQ_-v5LX z>;bPsvgL(pzd1z!NyBPGWak9~<sLF*tbr^_ph*qHXwlx*_oB8T8c7;}n<LfxbX%=X zv$faUYjL$Cr8g~YH+s+WX!zpg^WmU381x=LempwppPhfHo3Zo7#nmPA0?QcZqoWhz z!=-M#>zldwVSF_u24q^DpS?OhIp}uvZ93HJ^#+Z7CJ#Xw#xy$$cWn<LF=(~Zh1Q@5 zB}g)k^wgt9fQCHIU+RwQAUcH4+X`dYCG-yA^}gOHs9VW!{0c$BM)WKux_?V`@2Z)G zK;Fj4j$)m*JI%OfsJe}7hFD)kHXoVk_-Z`4B#VED^AT(A593?V0!C4^(i^-L1Y!eA zfm*A0@FCut-eQ9%MVRim(bZC$lHUUXhcq91sHN9*$F715S<J>KTqORzKmUI~f5yM{ zZ~eTQXf;>snH;#+So_2{U#!+l;C1m{Fij*3KqpyT*Xa(i;+k?T1Qil*^UruT=bA(> zWMos{D1k}8#+R3*wCF5tU=o)xhL~(9QBk;7-hiowWBQRbAH073+8xZo5NsOr$&_;` zv_4#DG|-G+FE1}4)Xy}r<y-#2!OTqPtRF~Eyrht(fjI!%IEu4q;_%(sZ*<<ConKr` zUcEW{(T_gG6)3rm<KreCu2*BRf0{5S^HFG`0@_a0ZCIY_vZ6=<tI-1Y1l=(~-JF7K zPla!JQUJ4za%oNtmzL9A{l%q;x{aOkH<zzla4U6Wem1XcZMjz2PH1Nlt4mfu6*h#A zKmPc$&psnN9#3Apcs?GFtpvcd9^f76{viB9gXUgZ+5&n^Y{4Bx+mOwxq!|^aS48II z6!TPEL#nn7<?aC7sI-y#%O(sbwq%XS<CD|rY{EXq=EGV(Jw5*BH^2GOCm(<K;fKdZ zr^KSvVy8k9r5K5yL#eKVUMlEZ?=^;_!}&^|U82MrDVJ$zw=Us0<Hd)Nv*mI=81}~F z%lSkf%q?{#-;4&MqobqGfAl%EXyw<x_x=C)Kl%IL|Ni&a%N3k2Kl>65YO6SW`T`4W z+bXbs5UZr_^%jJ~>+-umj}mnoY?xH606v?S1psw1!=ADIpb*QAZXb7FDD4DutjBa6 zS*!xRN^>`4^li|uRCXJ*o~Zi)Rf)QdeZ2(n#sfLcU8@kpzhy}?Nz;5NmNw?$F)*Lq z{1R#zu3krO?w-i<WvlK0D<~0#<xXussOW)Tk<2MYh(R+(q|jDUF2xV5M;4~ehY=u9 zid#Ia$aLca1uNlzF&qvL4~|)P5M1Rs6`Y-&O{aS94*|5XgrQx9tN}flOh_wC@b~}W zKeYUNqVd6tXUu*;#vO)mhYfRbS}rOBFC;1^vEf=}*E<z)o&1GDHZnYjJPu78VpKGo z<pOMGIRzdM2&&tDcL#(Cf~p5Ra;|7(dniRL%L5l-4=J>>E;8RE=en*AU|NjSMXn3S zg!v%E)uNd>3n1(V_^#z9ASjL6H%*xEITBz1j%9WN=!=UBN~!2H6O_6lu)AoH)Su{B z4{agI$bwFLKq-fO>nFt?s(kjv=T`Dtco05(`N9KgSHmHThoMP*tcS^p@HpxTSAo%I z0p3cPS?F*IN0-LyO;1xmKS>&Q1ow#R`u%RN-+uAz>8GFl@Z{v^gAZQlr^WWJ*}{mR zTJ3#moU<#<7SEo&I5;?%j2E-z;$U>Bm}j%s>kb(Am<yT)oz7mb*O||kY-Gd}$H&Km z(E(l15413&$_FZSk#I4+3<(BVrdGuD`;*C)?;=vf!H5|Jponvmn4W0WJ5(G1x4L?# z6k2GDJ%L*KDcb$!Y@(kCCX2PCbe@#+E{4g3n8w~`Y(Tfy9t`@-==1Y)d`o}B7@dZ3 z#d1D7JAX5sjys+9=wQ(83^v#8#-7e$4)j<Aew`9lP!Z>A_@b+f6{B|k_AProMV!wV zK2Cld8QINa5v7llkwt(~u+a}!>d|5#^Wq*d^q>Fp|9e`=__KfZPaurz8U!TqTMt}0 z2o9I4#fI}@<9achGde{8EX~N^_4V~Wf0}WzQDMJ69@%frS8E?J@z3g7dpKs`x1)mt zIAmp8gz?aL7594i!$iQ{r#d?2mjIG50ZdepHPo=NzgaJ*M@NU~@iX&-fwq_Pv&*QJ zw$MzFHgz}q22m<tm?lDOi~s@-hB3ZueXVAv+wD(hbFQ^ty*~fJ4}LJ7=<|`g1K`Yr zumkJB%0%6UZ2%~=Vb<J=PuA`ax@H0mIR)r9QQ=!YT=IYb7$l*Z{tEt!3V@kfVVz)q z8cae;O<UOV&ep-~VokC9f6wpvJ-_yAzXtK?r=P!k`Qqy8Dl0Lp${WS~(T(><W@LrC z{6jN|xF51YchhN|$XWX9Z04K5HWk;9s?|`Ir!OcW1<OVJ#BMl>-340Lo7Vn(QtS`$ zQ5<{Vix)4RJ$v@sfBSDgdGzS?^i%`a&`bVM!d8fe@K=0FS`4K=eeQH8GX=67ND!uw zitG|7L^+^3O|!kQBe4fgXJgX+4d?RSdbMGv<=TizT%q*SXR(lHv&r|q_r3qu-}`(2 z_#gk{(cnO5%HkCUYQ5NDu;FGl6tI6%X(`1F71R;luFLO&N2iYR{J)K)pNc?35~D*u zT#=%j2DXnoUZsjXU~Sd|lEiIf{T1vAfYF263|EI>I4n>BttaaJz@?Scjh2bruL`k= zTRT{lvc-o2Ore}5MFx+7@s(~A)!|m^$j#joS>6hFsm*Wz>{{hCk5@&H`N(8p6M!Pb z$l4pwSqUHuvL9HFTx|gyHdp{5iKTv5+@lN!u}7y*j*gD-=bJZgzWnk_&RuAw2m$ox zX+qXbdy8OymSx2Z2hM(N0dOaN!5p)I&BYo())K&G8PMJ}FvTW9!=dM{2oMWX1&Um; z4)+A0)3XiGZn-%$ScYQ_DI8}_kg@|pxGi%Gn<3HLV5lqrodqD^(*^e$n&vQxBF>;} z!G2DX6V>b2uQ89~ERr_Z*4hA&nba*$pzI$nB!i0fc^yb5jl~o(Tnnb`4$G~IBC>AL zunhi(2~E573o%BGzGQ!9<SfG01MR`37N={v03QzKKydlM`LExcxz=ytznu7A{<%NF z^wZ}ojs54(pA%Uzb2fU76Ptq$E{e`pD}8PCW+&DBVVdP>Ndyju2}WH7F!SkZIU|N| zb$bM9Oi9#sx_uVi)pWw_Were^O&=O<(42s1(esv8VwMW!{Xq=}u!I0s#olW4ZEk&? zn{ookM~_cmzy4w}y;{xnGsuq~ot&Rv9vwc`7j)x`yQ^y!OOxP==H{`{H{$bVdO=D+ z&Yt@Dr$2o9^eGWHo?-Xr=;qbO(GJ@HRw;@u;-&qzLeRABsK03e{yYE9zb6X|{HZ_n z$K92MeoA0W?Aq<N@t{8JXm=*l@oaph)8uNYh=rc+t@UhlgVl=8ZhSn^Xm@&qg)HmI zczSSrqL@1#4ebx~b!BY8Y3Ri&TC^FAAbddE$N)+)xaf$wpZ)AA>Q%_VK>)ya5hvjF zaxxg`&a)pZhd|7ufst-bgB}k@ahx3u^oyXbj#|};%MdivhG~Fr=?6?~Birff;|7lD zSVsW-=FQo~mA=>g8$bAws_T2j{#r4UK}yu{HlQt0x4{gvJ!QBEZ5Sri#dZyFjf*NN z9VdN%<c8i8F$y<;<9@}H<3cJZnnT`11rC6-ScS;$$^=89;(Noj?hpI_{@A6R2}YXD z&IDtv;u>5E-0|!O<_D=u%jqt#wNcj~i?Bhvi3((a)Xe=+G7mjo#b8&z^x#b)uW!=E zEnLvny9KBnUu27@RnH-hMjwCt@wdM9t>I|!(MKP#y?o=7PtGsivN^EA(V$;TViRcV z3{A!HR1dUpD)o^=t;PMNGT_s?&7<_}{7o!mJ!rFD=p#HXBSgZqK93g`u#j=j+1c3- ze*ODD`r)U){!f0r(`=2$<5#a<vDL7V?ltu*0BH8kl3hU)0C&JK)XxH}bj0qDo%1I& z(~$M!KyQgyu4*;VE&{+b6|D+b06jSsitbn-6KXZf6o7+5h%A<gUHx@w9dyA>7+KG* z56E`G)gi1wGpsn@S^&CCZ2U{WHCRa<y8?Lop^m10j$N?AoC4Vw$Q;nzf7l10?as}5 zFT-l<@QsIEpkjq^zwE=DW_~nv(<2CGnwv%dK(nA=`p!YQt}@NN)oeN%4Vf*hxPE`Y z@+SZ$%LSc9cXoDhd3ou%9k(}F7y8&5wdiC_S&~Si9AVU=lC8jxsv$<{*A@Ujee%du z?yyrff?!vHiP)E2Kne}V^72+_fDa&cEg0%rIKzB;m}!6#JC{CZj#CpZg|-rmahmyM zz@dl~8BzcfNmATO7XS=F^S*rCfd<IH$LTapmX6R(1UT1n(Esjtznhf+X%9f#253(j z+rx00Ko10PMcY}2yI|YMx-M`<nB^is)}?OOO#^H;ZTk@*OE2gYOsmQSDPqyAfG|2e z+}G>$4IDqKAiANz<IUT1vcHAj!vDYHfBV1rx3wv)uZgG5FZ3(NtHtE({O#f4h}FNZ zRn^{au!<YYH4Ba1uhVXIH}PF@4o@r=_H7ml0Wh5T`0DZF$3%DM=jT4gv6Zu4x}Clj zQ|yZ60C=;nr3!*{G${PJKli`0dB&glGyfCTDSHOXkZ>0xS&7Tpoa-f|Zl||fx_r#1 zi{*sCST|?lOSA3nfXJ84k3*q;@2J&fSx=|)gQH`Z9QaV~i@Fv&`&H=?eKRp0^Kg+t z5xszq0KK#22J*3gs9lN@H&iA5{)Qg3J9;ErVQL&t+iiXPfe5PLyA{H1D$<a@!e%|P zF91EAPT5*<0$EPI)TKqTv-t#9)8=BnypC|@{BrvG_3Q6_{|C_T9{^L8Gz?B~mQ+d$ zWX&40fH^tE+F-vg?&!jU!04bV1CBf80N9*zio6PHxFY~A`zojQ=l$V|_eb{sJ+VtW z6Kt#fjJ1ku$aa>U23R?DJ$HZ|ft2djfV``aHEm>p)Xcqsu2iv5sC9b309Y@Zh(#^= zrM3u89Gd-l4SQ=4I6gjp{^G^q(Sg2kGa7yS+uvrJWv4@m4HG>OY=^8|R`KO{9ItNF zCyXv4)pih%Rg<#hNo^!DY+M%?7y2l5p$9;SrrE35=ww4|To}qGtj`M9D^BE>=jVU- zZ~dLuU%vj~4}Zx1j5aKsEf*+(po%}9K(Rdl@C7yi^}XbOip;qucFvzrjy6)V^vghA z)oNf%RL2Yd0BRW)fS*%g$GW4UN^8)TyG`C#t~xAG2VKC148$z?V+6oXt-;QL$o_#Y z6JJ*Vyi4A*UBvCsBQs672x7nSu&==U(++@{IVQ|0^UIu^+S?#^GnQj(7>~ID#5|Xj zY3_C6^`CG!_Hb<{Xd(divc0;xdi(aAwKkj0LbE=ZLXuE}s_XzT8CHbZC_evOPneod zU5Jpp{(pb>yYSy1jZZ%Qh&k=U4SHeW0-ABp>&O=10wnDb0H0EM==Q+xS}+8b)S?t1 zNi8&xx|Y*WmcX_c_0s%y3UHGNKrI^sQPxl<+%?NMYtVgCWZ>Hsu0kKl!h{ap`cRWy znDMiK;nqo!N5=B@543BUa4B#tr*&AsaMqwYS(vsq7ond)1n}`mZjKZVV$dE7vKZz7 zI3sH_KWANww4rY~aTwLpxfJ#KdJ>f)y7<E%eSzd};kWQx`2P|7$v^(znaw8a6&IN6 zR(#jG)#<UUm#b^`wpOzj@0i)2%@+OPh*GZ4tnr2Sz5P96=2pCC3!tsM6+p0iP=zcT zqd5q$B|@|RWEq3K2u_xSqsv%xZ`kKz#%`k*Q&Gg_0HAiUSi)h~;^K$oY^u*aIl8Ww z+RDPBw12_}w1^mh5AAK7RzCaevy+n(cDuK4&ej`UCO-f2%|H1k|75eL3%uUvu48Vx zWP~QCRmeG8ar+8oItt_{BO3|WQk^ZQV5j~EqTJT|0DDlC0muDf$Z%DN+_VL;!+w3V z0m_mlGAd3(A`$n)O~v~G|0n8x*rnam7*y=9chIN^WHBa(iLxHjU3yq@6d7cZG{`0@ zkOj7D*$rFi>Pc6?+P0vfbwuc^G=c$U0_k!#XECw>;o~bfy^bENLx!_5OOm2bKKb~= zZ+!I4Z+_fnAJWqs?Tvo;cS#xxc|FmO5ui<Hbd*?+w+^3e46>x5qIor)tX7Np%&+KU zA6W0L!nTIaZxo@brKf&$x?3+-Z@+l;!{7Mf_rL%Bw{PE0=6VPQP&ADfq=DQcS|?jx z7wUZgf+EuU18pW;-6`;Vu>R0})4ByJfR94}@?q~g0^r20wVMSh$o;CwXMP1)pn|gB z0AiMWXaH=WffNm>wSO2g7g=p4zODdx7dCsElePh!F#>`)hQtayGysmddQ;tS(N=t2 z0WkKPsPG|jXURf)0s5*9VA6dTak1Ffmn9KT;q+iIc=qi1<HwKj0|D@xH)rSP=hLY^ zu%?u%RAR%xDs+-(dPA_Z5tF_mk|LG<{r&&&AN+%;_`cA0fU(<)oII*&n3On2#W9Lb z4clQ;%30H4Tk-`ke=BewrDd_)O1YMGLga~VWMPooEi>83auy=fwChFzS!&^2Qg1Y= zpx8~!C-t@qpTk+)yI=baF0PBD`$C%ayEGT!)hq*Oi=v#?flR#!rtPH2?V1T_%coDz z8?t!Jr^Be4#2{ReqD+&T068#@N;l)k0*hNTx_&UfX@V+TSCBkC)vJ=8J%94eZ+??Y z(RhsKH+tPttMQ+H_t%b34u^w-*?jWi`O7cA`h2y#hO@bDeD&&!$#}*|>Gi9(KlsgG zKRrF=63D2rJh+0ft{y#l#P!lWqAhIrrC<Gfw(7U=Tlg*fmjOTfKl;}>DjgggG)o5v zwt|~|DNe?KEL#(R!*)S-Fc=ZCv0dvtyt@A3r=N4)oiFrxD*>?52!IW?x}^O!P?e|( zN>@OqCTtZjkp=jN#2lw4cItm1vd;H}ciId%vOm3n^2TfvAoZ?>>-9~4%LLe3WxJN$ z`X37BM56A8U9B>#iMk)M{q{ii1Ct{cnQ&TmR2laPfGuf(?OJw&%YW!j^^(S5np44s zkOBD36pfp6|K8fal%7tpRBtxon8b`&uaA$9-(H;m^Z)!mcXV|0FZ{0G!LjOF-}x4Y z<7Qj$Cz~%99G^I9?d|Inp%<S9P-UH@&=3Z~oJ0Ekey7t~O8s)R)F=3hg+7V9jvp9i zd!Rr+5WG};%TZU>Zkqe6&E?r8(eD>ueDU31`_F#u*M5z&2O&BJBM;QA=)SWw4V{rX zyL-HL@!g#|vb2>$+^ydx*(&w(T>&t|W1@mA;EK6A`ZN7LsO%@QFVsFX0Cp`jm<FD5 zjA@kLSZ?C$3V^fP3f9-U)npr#jQ|RmW5AD23l9x|{WKO8otn4{@inep$kj7}sid|x zr*N`AE1-k9vw(@m>WkH?J7KPybrK*fr(>2*N52!&qfu7t2Oqrr_~Vaf(*-B|v$G2# z+sQ;rQhihWg61@b$<mxvk)<xpq1?8)(ZBm2{YTL6kH+cAk^Z?2I2d6frzXk^0~r%= zJodKOMQ{M7Tc!f*uL$Qxt=R&G>Xcf{pcbX&rj6N5?^Xe2Cct-Yh?K1Bk^;I0%+CrL zKQ>b~XZVbS$D8VBXJ-)Ffr=>CKn6+RQWuehwt%7bZX31>2$N=EPXe+w584W8f)oxG zGDV={N}w;dggL3R1~fe-wGxoEWl7RdoWO?VzEiPLeD@OlOwNx#`RD`TIUpoHKfk2Y zuRj0k;9&Ua|ChZ#4c0Zg?)$KF-g!FXz31MZyU`7xL4XtpiWEU&AV5+iEm4ezC?D){ zJ}9wdu~c?BjwmsfV_VK3*_NDCxss|>rBeBjPqtLHM2Q5!0R%uoq$G+U2oN(G=)Qf2 zGoSO$V}Aejf8Kqb^A5M~MK@%+%zvNWcki{=UVH7e$MsC_>-P>0Zg3Lq^*T>I^~}l1 z(e2w$GFeVf&+puM6^DIiXN#%SZeO(9m&j)?L}7$uE~|8WeC$pkiAvpW_u}G$ka>Yt z!-0NluvDy6swG_OUcWOL&saP3#>M88xZZ)(H<DyGbc;&_BQ`~RYIaXVzWwd*48gRE zJWNgVNl%YYPvWFJ=?w<MzJ6a{9f?8_(y#E53q5Xov7^@DLQh*sw3sPYn?kl~!oRdn zXa6z&7=Mia(XqF;<3#`vNpY3}N8Tioz&8ojE30Qfk%rl6@-cK?=K!xPOD=1Dmbi|$ z%04W_S?tlUu2%1lkB+3jEpTNJ{}T*}hsZkl*oU$PNtXf(abSid{}Hj^V1vBOl`tov zIlW&OW;z@@PFviZ&Dln+T;UMaY}MJ&pLzZ{SYCYl+t}#e`+e`db?est%{|x#BYm#{ zVxd&lmKz_bvV3F$BCsLcRS@C;b3&_D^)3k(qBQ*Dkv@Mo(3`)Li;g~W#^D){CC*MW z1_H;6S${h0i*k8+iTC@t&wcLj@DPEN(-9%wfGfr*pb3&N|3sEsWS|d}EO8y{==tJ# zB<>{Bp_{x6l$1r@v;%B?Qo$4=U)k4zG&4Lp=od;QsG5-QxDGIK2$A3<LQF||T5O7Z zryXF%X3{~)0K#J&W`M3X2OfThb{QO56DYnAS%L4c0}OxS0Sr9msR7aSB-3|*nMO>{ zxTqvkJo)5PZ+qL@PL9twz2hTXUUqu%ixNz&xSft-DsCavg{sO8mx}73TQ_RtjQuY@ z|9RqX9-B9B?4dCAr78iHp}MlK0}4xnS{TC`HbN(fCmw?==Vs~aFu!wQBk6jfkTefS zJeYvcS$T%Me9Hku@|xsfISFtABA6BX+Qi5NNFWP30&%BV87Yg01_inwflizt<VoSA z0Q`i+p}<DOFtZDi<$?=vLBmM{`#b64#LWYp>KH2kV!j_8hZ%;XhRXs+Qs{_zls&gL z?xkJ3@x<RN(zqXwM~!BUVg2;ePvYqA?dgL$da0&V8ua=Med^ub-bN)1+iJD2Awp0U z>z$pQK}0>IO(x^>i_=P_RIfMd^=he9VYCkhFb;0rdIGl@hneXFo!+J$RNd<iiHIY9 z>V{nqZ=9;B(MF){<Ps9cp+=dw@^prVP`0+VP>fPHZrq?a4UEeL0`s%m?Le8Z|BgoL z_`bGE?1IsUgMl@mk0;|Xxq2mkG~F!JJ00;NoEFhEG(iaQWJ!Q|QJx6;z+(+b!b5~2 z*asmbi4ek!hELtT_43QQyS~4_&#FNwbf!73%R-36Q9v(JlH?$QYu>)>v^)AapJua8 z7AjXOdUc9UM!2pH_)(T}wbP%JI7^hX>pOq}_;Y{#{~B6n_}hQ$=REkadRcqq=;-L^ zzxc2Je_8e)<B##j_@4o`cdmY_iq*jJ1*~&`z51=7&-bGRn131T>Rktx-7NNKSgp;H z<|(NqbrlkQfuDbzl@EcpgJobJ${Hl$H}Y|i7_w>}8SH2-Ygig|hs%H`g@A5yk<Iuy zZo>?;h{J88T4TE`RpeoE5}>}l8++_%FTC`^bI(2Z!i&%E?(UW<den<j!||kCt&PXo z4h{ur7R3exkJ$)Gvak752%NUc<vRNyV~;&~(3c<E>FY-U<kH4>wm1}!L{_WZ?CK}| z^u{vGckkYP<&{?+Jb3W6uYHXqhXl&9hq@JDJky~L1ppBfQ|>Zg%VO7&$~uyg$cjLK z2wV}(asC20Dv$-t30xMK0eT7n{p-jA-H}u<MG%;B^AYDhI_M+HCS1vXOb3{5%0%Q8 z20mq(l8=0+-vKVhi|a(B&~={BOCauC@Rm5h4}q@GtVfcNB57QivRsArcL-pJHf4?S z)T2|FeVUCix;$o-C~nkBxP<AQUb!AOZyr4H#1q58xZCaH{c?O|qA>yO00*-qBLwC+ ztjei@N25G93y353E&B-8(@#C&nC4I%!2uE4<_0eSjjfQG37td&8XLqj?)4jFf*Ft# zMTJDnL<DT&l<NpE9R?FEhY-7)0YJ%O5vPb@PPd{SKNbfNMcc`R2<QX+3X&|`a3TQ; z>!TL&KxmiwmP9NK$tDuI7DqrTVt%qLX8~lnpc!B`KLf(KP7=3RH1~*vA08;g?L?7< zRxrC=P~fqBh%bcbOvE6W5RX8YJuMrJ#{T|peE)58YrA=HaDab><0=<-$l$)L6iXLp z=QIH44Sot@L)=P+H9SP@<Dn<h0Amt=;e}^5QEj@3gFPBfm=eVTj#=ULJNNYZP-AO% zZ@aKrIy*l(IhGT9`}Whtf<By!D4I$2c!tNv$G(9~OKGxeAqfNM^}BxIkU0LQIZ=iP z{1%1e)4;*Oo}QB&Px@#x91*ASo26ps;!?kMGo1}5(sVG^uPlt%aYu!-3&eM@Gd83a zK-^|@NHPH%QX?SCT?s!ug^6qsBC_?y#;seoo`2@)XP&vWx1%cvs0xuD#H1G&7r61n z;RguOD3Q2gZ#bZh&E^(k5Qa{t{ovj`Hu!hH`(0GTasxAZvW}Mu#o0z-inZfqErgH8 zT9`_k8-MNR|5m7Qg}?iEex5AUsOl16@%;RpPP}pJHqGhw^p)L0$zO4gi}e2e-auKu z&7@aMfmLNh5g<)!1VjuJiqn4QXfW*ddV|RrnYBu#Rw~LMwMLU(V@go(bYoJkXkWyP zmH1)`O(z)*)T}|2&1JDf$Q2lql@haJNH3128+z}x@K^upe+I)J<B##j_#=W=Q@{I~ zC9WeT@nhhva)5!WUI^Fe>17Ax`Gq;%3@K#o3i2YzrtDSmU|vSzx#D{?l;*CKB_Il- zWtw3Dn^WDKVVyTK(6)pAnVQ*VB-UAh?TTYEt23*8quCq`d(}oAH?+~HHMg5LZ{B?J z=_j6k`spX1ev&ww?4Uoi18i$pGG$5n45Ru2B-yjriHO(%CbGGqQ_y&%t%q%m-Ky8? zP-*P9@@&~5ij(3vo|I<S-~fQa_wU`ibLS2YuwHXJ(=93rBEij}UD~?l$4j*<?BmEX z63;S_up*4+xM{A!@cy+76pKCcQ5|6SZ=$5o5f@B`g@VAulMktp$TG~Z3}lj(a3%jS z9bh*7OvJn*i}DC@G9P)X9N;8>0kyiGBxOw6P&Cs>9g*=xjjHsacW9TPM=9o5ke0=+ z<E?UliMYDukk*;OZS*nQ&XKdAn+-RiqB~Xa3Wb8cgtxo9$Kk(PsrUOs9AGerM=)f- z4U9ZR21%wQl9`f-VgeFcrmG_YKlrDg{j9UzBsQOW_GwhKP(a)n=%MTYwK@U?o>*%% zowSt1l<+J~a)`?c^JR<VGCZIeUhun8^SfSCqRtE|Gp7@#2*t@w)diP8(mY0rqmLDK z6HtH}34KS72nB6u;(#LbF`RfxFtFN^3!OMb00YcOGjuMG7NHDDLgKawFh4|Kg;Ul7 z$Z|n5z-)fxJJ(6#u$dFxAjWd9-zby!v$f?LhA0d(Hb*5mNzy2nC20x36*=yD0R=&= ztS75uk16BUKKJ~yPdxDi!<sz|Q0HViB0=qpY#DH4lP%<h7hb@f!<WNJzI*rX&dv^5 zM9$96r~);xDgyU+cTP@@TCK)bt3|`&8;%pzSE;lwFZ)abh8bobk9++-`)IA+MAK4H zH|?pBhEp~59v&W|73HYKSvCs_JUG;sx^VWY^;*4J+bk9)^7GgWr>vEO-mu-hBzJ3P zyIQWW^PXQEySwOWEQAHz^}cb9N$Che;#7f;)^3lFPcN9*Gz;I5VTJuD1q1a;(Dm_* z(I^gx(<zu8YXBk;sf+F-NfU5!pMK)@yWaKU6Hgo*J$TUCM#FNa*Smdi@ammATg@hY z#yDf6)`;2M)F(m8C@>*D9*$@uqZxrv7z{+v9Ia@JJCCJ{@o{`|Uaa_y4s|*bE1D&R zzxvnyFG|nxcmAutPVru^J011tFI1(<TL({Ypy_s5&nD$^6=`leJ(Q+^-WJ176S=`G z)(L3hk?dh<b8T#ncXw;uE`8D-j3;`;y;4K6_$P7grkH)Tu2R!ViyD)$E)u&siwZee zO>hDTWC8S{^Pq5iqO%H{@xo1f6u8@N6Lz|n&pv&daddcizh0|MXM>ZI*BRO)YA@k~ z@6>B8M$>S-v9rC8g@@yqq$O=CqtSq&MNR7Bc;nP-3w9%dhQvXd_o%AV+E^EBP?c7w zAq6du@cjILbnP0%-~3O04mrb7zuqWuPQxsl#d5#Xr^D#wcDqf%!shJ%_TT(}vI2jM zKgR!*vAxAozXDoP9tSJ|S?tkpb&^;GYPSL@;^k!-%xFgvzmsG{uoz|w*AmE!sstt1 zATi9Vc~saz0$v`WAdPTsyTSox#Zo+vk`5SvsMcJH&sdOVtZ?;8l?Ced?b{Dd9_;S! zwmY4z?N<DjT(RD);Q)X4cYpUg-}R22?LC%9U0IGASPWV4bIazGz1!<NAi~}N15Kwc zt>*<XQ@LFZHXC+5&IT;7oNV+YGpjQgOk4E^?PC?C6}4K09s9C<{>3kR>HPfk=>8Ea z|HVa{qU<eH8jX-~6c4!Jvc)REmc>>fNk|c7p}!jih2pU<T)UBz2e~v8m>IY%FoVTr z!lQqkO!O2Xbit$m6a=p1r$)kMICmMybXns{{_0`A7T6&ZF|Wv?(tNSl6nU#0U`9$7 zyN+fnyI}^9iCMI3$0!ZG1lU4f;g6aF?EZC+rw|H<3qolhm8OV!h{RaaU~_vpLz3mP zNhS_(wFm=UuLB;(@4dZ!9sW6DmaEK1JHY*(4x$?8voTW~0dcnMA=cNVh|}+gMI=Hv zP?5!954N}LE6}%Z-Q*uC%L7W9V9q5Zjvmo`A(_Ao=p<7GpqOYnJP;}3!NGzBNScQ* z3T538M`|Ht2+qwCOF&Q5uws-Yq&g_n1<`;Fx(pqQ7nCG3(J^kwTSSs$PKr~IByn;b z4`CS~hWZ&yAw;W;lxs3D|3df>phgx8SVBHxBsr+($O6hG-A{u};Osw#?&8L;i8x7h zNT`;It!DG|=;)bep85Xo|9)JuUSGF58J*;^r7==*rtm-6#x5={M$<{N)gqTsOJCD= z1VRT0eDcXBzwwQ4FvMSf{q<Y7Zee*WdvSbB*=D10a(X)G_bHB9aVQz=bPsJ~8$=f7 z#z|raYiu=+j*bwBQ-K1^L;P(h&pr3tojZ5XklGRW&2N5lYikQN+UIR_U<5Ob*aZ8- z!E7=vmP>j%YpXsPP6y*Y4sg5MX<uBHtEJX<3kQr1m5q?z+uPg2^~GWy4~#VSatwtL zXi<MSIXmmWdguQ6`2{V;amPi(J4Odj5CeOr2r~11m*Tzd0L$275NRFBLUH<`5B#at zR((32oSvWIqTjrAfGc@;e1tQvD*?r_9?M3O_J5^I<&C40leazp{FlD+m6u+4>Gyu` z_g;GGC90(glw|3NuF;p+QHJU`xVSfQ;F&)0AbM#!oBaF#-ruld3IFBa`Rmnkp?!W& zo*^D%Z&WE)w{~tI{OtU4cXv-ug@=P(sYwX7lDRHAH*em=Nk;PPuivBJF(A39flLjx z9164Pz5B0iZM87vV5Ixu3=(F!wT&xOB?d4Po%7A8KN^fiJ3BWZVzh3zOA|0!RISJ3 zrF8Z)6M~YiahlFFtRwzMeStNK`Z7Oji;hb06gEd28|}06<MXpiGWYgwZnbt`91KUr zVim_1m1g>79Z4pRIq~(6j}J+CaB8&l^-4@hcQ#_tk2y!B#G&lp*z5PZ{l4y^OM#-+ zeX{<u|Mc%l=p29ZZ~h$gez&7FH7Ha1lzu|eSQ1g)Z@<x%wK{XpH$!@xlR>|C2_r)o z6LtFSdaH5k_7j~>Z?>U(CbP}z=0;^h*8<ASx6Rqe*AtM5u_P@nfzc3@WKQW!Ini?p z7wvYd(cpYJkXGg0-EAxY8@e%i3DwT)z$}<6Mm^04O8gK4%=B6;t=V;}|NL+NKh?-T z#{XQgy`4R2wE&NnWiU{)*mW?}ve<QaA72LkR2F+QaOOj$7~R_RV+!lM<UPWG%?yHz zJu+5npKGt>I|S?OgH}{dt{Er}TnbZ=Mcfqg5RY<;aB+~Ym(VS9G9M`_dJTH*dsA=v zcs*o=f9k2H-u>P0e(!s~_xb0a>vmXaF=ITZ77~0pm0h@0)ro>4wrx$XP1QM&AfZ~( zBLnCFL!%)&=TF#JvN$&D;_GxW><@-x-S~w~%kX5pp^xEB3oN9Yvue5ewXc2k4}Sj- zzVVH(cP~3Em@L$2c+u(V7lz{swf7WDuGV#TBq1~nJ4{zQPRVYIn42!iamae8+<DTW zAtTPs3sfv}SJG`31EP71#FLL;Z)YV2he@9W=tjbvhcJ}|P!dcb3;VN4VM+WVLit1U zUwkEZ1qv#)3}mJ-AJHqNtH54Nz4RTN=zubGF7P>I8Sby7c8W}<x>1*h>FcoWBUnk{ z1=s;5*9@uNb^M(Bve<R3Ti+}v3CHZN0^^vH;G{qLMZ`rs3m6R8kT_wIMjUKTIKEPl zOx=Ci-Pz~(x3jYc56(io1ANIT6i_3=Icsq;<UCIYQ42GRfx)yzf0C{ug;3tIk6^8H zfKyG30F)q1dJuP#_M3+yw1kL}1ge7A3<xRW&cJYh7MhI^SPoz;rm}|VSz-yuv>M2# zETNUmvgfc601siR4v<TA(9O9Fn1S_&lOiO&_$~lu!cad$B2pwH&COz{f`I7`9|F|K zV%LHEEOs6FD)LzA07HS_ae!gzDQP*K;Q2M0wfB72yI*?8+sDHZj$(1Mz{c_NJKp)~ zo!8D!&u%?&yVvQSUtZufJoU`ez0olC3k_c;0CEsc5<BAnGx{OoFf(k}xActhpkJ%V zU!q=jqGuN&Nq`)Wy;#5cTRYqRfvyj67Dwj!`8n|$H*PS6Jcn^vp(CG4;ptv>EeH9? zsj$)Ejg$%$Y_{r}gcEs9%tMNBaPRaw#J9J1FE7t=<#u;>kB^TLczSw@CT!XLelMoQ zq}S_Tv~hQfuiraDnnxp37aeHYV4$UzI7kuTy?{tQ1X!BlXh;Z=i1zhb@q<771C3_f z0*%EQ4<Bim5zXNVk4;caC~lS~?e^u38#nLYzrVkC^OaX#dE$wuFlu45h;uR=j%&4s zf0GuIP!-ZB#z;UuT3}2D6gDZ9i$DL@uiXU30j`v0r$?{uY&RJogZ`vYtYE0kVzt-9 zB~%CD8d2O1aMlZYhrEVZ_BoV9RpQVY1{Mp&5u?|>#D62w?Ovh=7Kkk>ZIE#qDu{uV z76vLr6he?W3;j9XFiD$DT}reA408%Q7aiL<%q2)(p@4H}%VQVXfixnU8>41pqkVbO zZtD?xG{JgoIn2dEk%Hx70o_<4^sP8LLEBMzlQ}{~j6E0-i(4w4EBbLfyMNIZT}s13 zllcoXXhMXl8A9m)xBu4vL(QGzZ~o_h6(T)YFR8H^HClvNA`oE!L@)>yLZ6O@xAwM1 z!|q_v=?`f7sorugZm{Llo2`vmadV?O+bD0$_^V8&nuDb(>LDW=rqWH%FiP8ge>iu5 zIkwg>+LxR(%f-!Zw+*kIUUC`XY-aFVJ!zSXFhn+EWtIGR`Nz5Ftl^^<{`GhjA>#*1 zwIat@YLv^IM6oB$f|**>z^Qf(7=Tjv3&q;~!(#?N3j#YXfQ&U@1FkEDfyFJuKp<h* z;9AH(1W8DeLlvehglA_Lgnx|3#s5?s;PkU44pEN~WFtJ_tPCpj7+9@+uDzD;5UjJ0 zrvSNTptv<8ZX$70oFpFQ7U32wRO(U-loWB?!VQv4XF}#U9YOry;NZFEo_penTi^G+ z-_vN+8jTig93-gDFEVv{T}`og0!Z5m2aLEL8kqv}(E%P-4?q&O5k9Y<)r#lB2BV=L z)m95>a(v6W5H@bqYNy91_wU|2IyyQ(J-v7D-m9;^`r!WI?v0zn!I(7}32ueTbDAG$ zqjz(FTL)!2S#*#Ls>@>6k;Vfu9XdkOf_z1H61c`Jkt?#2jvPk-MDu_|Sqjzf<}t-t zUf)(A8}H&VToz;*0aMK2O^Q7N-PA{MY)kE3!0f6)D}dyMh<kGx?A=sEC&EcvP=Fp` z6s@aQ!y^=42&c2P{=!Q9QFDNSMG;!Khi)35ixthk^lmzFpH)1?T#&j5ovd*LoipQW za9+J}<A4w%d$->Kjtlki5ao>N|ELZyN$@+r_j{q%o5eK;I3IC+)I^h{;(TSK&BOsb z#G$y9*M-n6>nDSFk^_h!8CZfD0CbC@!Kt7jiE~pf13Co(0$tXkT!m|aLK1BW?U|^8 z5E!zB{6Ha@#R4nkGh@k$q8U=s!i_{HG=+!}yjiPF&xbCuj66>smX;-QSSP1cl=FZb zi3;~Xk=TmZMN)+0EDi5oUTn;!?|kRm-}m14V#<53zm6exx3@W{dT=lf&Mz;wTP^6c z=j`I*iKm|I;{(SdzQ|#ogu_|F6XW!3t>}wyeB&E8Z{FOPOrL)0iSA_^3sWPxn3oC0 zg!$@Mzls9Z4G`C)84c>KX0O+Ud4GQ&xAV2vUL*dFcf5nTm^sWbwo-`Xo}HbMb#{DO zud6K_g&78%tKb|A`y{vGDZ3zUGuWAXxLyw)JV3|Y-Mvny%_;w>r=E&4y)Iv&Tl=!x z>v#Np=}x<MdU1L0-pSGF8M7MY@q!RSW2qM}#+pYHv}-zvCWN*_KBN@QLm9mB*;E(g z)W#dzKm7hbxmnQL2bdAf(}1L<Fq3p~;@GWRE>4(9Q^}!!CS$2xt=4hdaDZc3k*85E z%Ng@yx>V#d92ABmxhyrRVmkhh|Hgj-Jpl)}T-><(+E?~=w`<jguHVfHoK%YC`e-;E z#sgzxwQ^d<YbljT53xp}OuckHM+%I|O1HPShq=%dR+L}BsNci3GId+88J8>irCHV+ z`&6uol)?c<{^o`rj_UgUYHahq{L3JrMov*d@oJ+mA`mw9Y~FQ{g=ia-R#0z@ZdR>P zqdpt-+n5nUp{|@>t;I#`$?2<9tPy9N>ciu>WH^-7;>_NoMEN~@owqiN(ssV6=td}6 zpb*w}oCw0*(SPGV`rFpo_)q_{|1kEC%e|JafFw|a5C-hY*rVYj5duV?j++fMoQ=l) zZuep|>}_mP4eq_}kZZ9l)G;REX50auVF?C77)@G2oG)uk<ZhQKBL|oygNm+X>%xca z_q(t$T&dJ!m^kN1h@pEn!X07QgaHJSk)<XeAN>Jr8pv@04*GbcN5pkuAs+8nFT^MP zi6}P?&`^lWjMG`WH?{+;E6up<v0PJ@>fkYF3Il5$;Lt5o-XTcE7Ua<Cl+1?|BjUJ$ zD3ImmEaS)|8>)F^D~5_(zn}yB2%jW|1nADvkXsT?gz}C*D(3u%y=-?K|4xIIIqAFr zw{98h_}2mZWU=dbJSlU_)BA+z<^c&jfDPExD~5|bGS=zCcy`3{9fEc3^7uDMhF%#c z0*ItB>|~T%M4~&Ak~BG=TxQDy3NxKq%(|_GFOD4S3%k49Kkz5N@7ArGPe1*1tJNCM zw9{#wt?2Efkf#Rv3Ol8UH(T4}Vr{a}oF;hvWIcgL4GX|bjVv0Ses79b<=-(52iW%v zoAG<*`n`zJ==}7I^U3Ew|M^#5`6dfK4zPEB<k)(Iu+b2$V)HH7S?e4m=Po17$Hd@> z`ywUt#lwV|c>!6@T}j6>j%3t18;y0+S&0Fw5Sk~Ff+@;g0=q@xF<cgyZkS>QI$|=N zlyn6-HmPWA%3T1RmBp?DvlF^_KBAM^Dj;8jCR$B(6sHIsx~|?N&<u$!|A=xPh{|Hu z@tt;n*U4X}k74;1o{;DXP%x)W?OfuFD5k9)U_eD!l`JHXte3M3F3{PvnZ+E%eKUYb z<VT>HP(YobPt#2}MX*_O%tHcWgVVT=F&3Byl(*giUI@{fnmjZO4;Si|#&f?Mm>EC; zBmw+T2p5QirnsQw=7_+hOf*c-Qx-rjp-TZ%Of;yAu1dol<z@IVec~tA%r2OU!=^?q zb+FrO&J-aeOG?a<va)m_l>+dS1g1L#WI3{c#IO)aa#F!{5)5B4$|}`6==1n&Cf6(8 zdB$k?8!YiBCr2;6?S=Qf@4YX+_~NUtzWSA~d<CzSIQ-PYNCjW~;umk<zRi|H{9E7p z7Tzx=@(dw#w_;>QwzrUQP8yWLYlU8~=;=zbm{%k*JCczGKM`67(JhjwjY+LiJv%!k zj=M`PGl#gpuyy0c4RoebTwiumX4+^p=FkQmm+$iO93fOqUB@Sf9ME@m^quNzRX39% z;!YPfXS-Y5Ov_5Sc6fBZ+1Ps5cfFIiErVF!SwdA>M?-Lc|KJb4j8lxZFzB;c@#H_X zFv_UTU^vVp8ic8Xh@?0&5r{r0GakuGc=9j4^xXG-?|XWEJywcLm{~+<uXlHnsrRWg z&H+VKC|7i|x7FM}JUnc*w%PY_NTw52jV5q1EwD4HVlH<R639guLa;aS!La|I{2%`- z3s3mFfA{B(AH3RX)Hz`2bTKPpoY^Mc$fR16dj4dHjx1F<z?h{{tk4luN>9-dREjZa z9Tg$a&CiFE;eb;<Y`A-ap?+DK4gz6PIg^^Q1(x744jcTlO+BqZ6EFo19~cgGfss~_ zyWjwmZq}N!sa6}>2vlIcULiq3qK_a#DHd=RFD7H1oS^%0EHhNfsHKO=3!4?#=`t41 zxcbnqH*2M$9`HjjiXjI6arWD@NR4JrXed%gJG<M8$2%~Dw1ok{c>dr2hu1#M^?&+5 z|21;4WHTOLr$|DG)%(UU0O^sNHHfX&a2*GXqEcal-X0FRr)S4hq#x=mRLg}DVWCjb z>r<PBa;-X!(;*UQ1wv>D^C(<j{a_{&4Y710^M%P<u9OA?eR_a%C-tHaO(ysF_}B`l z!8v4xEy^PWLDTw!J}A$?KmsJPAi~TEG5FOSl7K9#z;rOkg7cFodiDmxS6;n$bizzM zvnec%!A2Z@K+{qfSbbnJKV=s}Mg}3sNf6MGFfZI8Wr#R#AjhIsLQl3Y;!2bJitWfc z2iT$EEaQs$h{)BILf{Spi`A`ZT3(-(u#!pDyv}*7le3P09nyGMz~f1YiA>e>z6UcD zGz7>eX(XZ$r5+vY^hx%&e1~9dyXI;*2~0tAuOTGe1SD8_vn^m<z0AIRav_pJM*z!6 zx};0(sKKI9t5tTkTF*ZF^vf^5{LC}Y)S7zF5Ve@^ET8C^wXP@~NCMvn1{RK-*a!8T z7fH9s%vvd?lk>|986ggvOlJKPVWXyXRWB2<i;c!CUw7`@IXpc2!WX{SY4_MqS(;!# zPOP%p#iU8VbV5*!&q^$VtSojN)Sblw(khVbY)Ya7sW>+yAj`Qc=~%`Q0MR@Eh0V4A zt7#r0si4DU;BY1$!)1Z#hAHIIuGkq>jeCa>tkY+5wRc|w9ZiU2CsU+cT<s82X(*Cu z;!2^f?UyxEz;_FPYjg<K$$8wbK!2wlV5BACP8v>{evP4!S<Dn7K5k)u!&!t`I=-3? zP=Iq92L>EqT!Xv=>^s2pcsyUN=h5O~x*T9;nePC*c6XCOE_kaxf>mra8~lUBeCP<R zpgtmQ7!hmWh9!PrhLi+m0356>2V?25HQyof%n!%InUO}A^f4z%PbAk%rO@dKfIdk9 zB4h!0$g+fm5V}}%!^KG=jxR*4PlD+wHvvilNlVU$rY|EEahQtaiQ>p5S7I|BaRHJL zM^Bd`NjK4Mj=PLrOck%(j^F#e-}~a*U)<Z@KRMO6o}PZ@nHOJrskznK-P=3AxL~l4 zr;|#p`ps{B3v1rIb%0gzRT%NOpdQnJJ?YtJpCtrz1P(Lx;z+|bnNGHLwh>qgM-#F2 zMnkI}Gp$;wvL)84{?ohgby#YRW~0LPRwy)E%^NpwlEjnS+oxcC|Hgi=-+S_@Ct=>d zaf40i=Itk+e&*Tz{eyb5vAwf<<K~S<tI5&+UElRxFTV8l+fO|C#8Xc`_reReo_ONM z&4Xv3d6o)Vjb^RZxV*Sz(#99RTFqt)X9gF(*W-Xb)vphiIIoZJu1`)+Fe0Oy;f6nf z;fZ=MMAKRRM2kmxh!m!?)ebP@jiHP6*tyxCk@n=1PrUTfi??sx7*FJVF;-z<X`l!e zrU=X)(vHVOD~-k@EY<0BQTzP-g4G1I>Dhiy1!1S>qe4V#^JRr17k#PU!wF}N<%za@ z>Qle+;Sc}mV9xOAPyKRnb6Upvl<&kLqgk!iH#W=D$p+Qq3_(UJvr8ZH)<v`p4kIYW zs^@hLKZ<oQRL$;?STa>hAuXCx(ruAR71zye=c-;^Io8zPnCWU%wWfmzxeDWu#J|eL z;vqgl14?1gWmIEoW<5)`6=76X@$txoh@=pP8rYY^kd8J`XcHQ37PLmw97bZSBBg8x zQvd4ltI?>BX%K@`j49xdlubEK(E{p~ve6t2u3Hmmz(l}4bSvCYI351jkNp{mo#RuV z{#BWySe%Y@dN2?|s~7`-TqofnPLmMJoEpzIOVuiE<(OAg7gdqp>-L+?tx}=PNJSNW zNNqBl;iON-jDN|&hBPA{ut#IGrsQBSVr(<)iyQh-d%xGEceb|mO?ZHkNY>6450G1{ z>tK<@yjojil<4UAQ+YZrHOJE2M(oUt@MwYP*1<zvP+)Kb3iY---MjY=35mmr5eQwx z`@$+*TetIYjrkC)lcVOXLRKsXL>XE7Iv5%XuKfv?&jJz)IQ>I$L}YKsEekZoz_1w= ztf}{Lf!HjzfNxj61tziU<U?PHEPDyp+WrW5T<sZM)J`o7Mc3sa$2hTKz?|P6))h`- z9ZAWDw^!QCVNQ=L;!xI&;XGi=M^cjJ=ab73gNj@)n>ksO@`NJ7y4r4E4%n#rgW*t@ z%Q*&MNv1!bBvV1}kRUU@hK06(<;XIDvI4|e7DQq#p;3@vEyX$z-<Kk$&AOl;HOzW$ zw!y~0x<M5P=Pa?ayK`{s7HcRgP^dX(RWIneD!e$lTGff`ZDIbV3ZYXE)RnMq3sA*5 zKtTdwmR^M@w}N3M-R(2f$~m&^B{*lLsFlEoS!@oM1z9?fDA-Y55o<UUOl|r)m0~?y zfpvCfSY)y5@HXMP93lZ=mdJl3pd_1cmYCxq#sulS{fM}3wnyoRhvzP0o!!##Anr<S zABMD((4A|#i75h1*I8kXQki*FYc;nx*l^II3Qk!}F{ToyBaS~z8Rju2WwJ9Q5JERG z*;8jFAkE=l{L6niWWQNt4lqd4jdW;$$Y2FD8`W7g!ai39a#C%cQ;3)dkU-fqyr7Vz zVU}!)BkN$9>)4QkaLY#ra{?&Dqc1Wd6jzPu387FV@jwZAqBwMfELkDuCrC+(n;{P~ zWQl-zRC3Pjc!G(*`ZxsntUOF#E(lUqg6V6J%k|Sg0qhW_lVN3-LIL-6Z*TX-x4#Wn z7JrgM`FJupI5@Zwj^%^H!=2q-{6kzCoG4E4tyT*O+j`o;kK<~<_$Ukm+Z##U5{w6* zh`@GwdOF*japuOMMXyr1gg476ow>NRz0KL0zecl(-&+j_7~h!I9o)PbH+AK>;5JZo zTs+o>8uzI>IM~z$eK?-%-#Dn%o3xWThu_pdT&vOA+D0Hf+Qw7t_0W*AXho&1MtygC zm$Gcb$iH>#Hd#osRS6;5X{1FL?Td@cwr)%ZY+JeoJ1}0tu9VPe)llyIevXmi?oGtf z5Y~(R{rzX3efFuRo@i+I)x!vw3pOI;(rWt4YFonG=B1%N!Bs(dnnRb-DdF1Tw#ndL zW%xIk@q0IE0HT;2=#RiSY|z9C8xP43eelPSpYZ8VeQZ4JYyBFNi;x=Y8s`yoXKWy! zIPQ<n5Og9l4yTbgn$V(lyN&X`_MemowEYS!8gY$)<}!CtjOhzALI^W|wXE-8F-Iwj zlSVBdrnzowo1e0l?OF)=7yFHe(6f4jn88&L2^F%1i!Px?_IUCcJn*oHboHZJomQ)< z2IvBZdfZ*CLs4;4Zv@Bjml`xILYlsB9#P~+ZK{s$a7AP=BLMo-7Lq^lr+->1&hd}_ z(cg!z)-jF)$gz;Hh;BGLnLrY)hb-W_2#q~q(}&thCBhost}cMYu?;VZ^GLOV+e~k6 z&SWSVhlm_4sf(%%sy=5()Ic<oxZmxOKbcO{<IxJ4BlPhw1JYrRFlTm9j=274N3=$7 zC=kMylm|p+v7BS!!9dS5YlOt<7G`n@(I>>~6{FL$^TXrQZckU3p->H+#0g=JdYAFA z1B!*D5a=O<n5v0xpluerjw_BiEGHqOVvD)hmB_fS>!VPaS#Cr#EF=x8SV{jjuvX5u zE8hZ>*tbg0$Hn8;>V1cZ264<v;)FJ}5scp^))h`-9Z5+mu#CJuAQ73WE|O)$0%*!( zAqjCZMT~_c%q&@~a?DMP=3FAIB-L_tFdST5oO3p~?C8t<+KuLq3$Y?-qRqEUC>*2t zM?&YdkVPq`ym;aQ5lQFLSPV)Cw8*%iMd{Kfi=Ei)8*9-o6b=q<vu1{Kt`}jv1VKkW z`V#`nhlosyuY?s|MxtkYbC|di>ljwjEuSz|1oCkgaarIT#}#`cJgx(*O~hAn15i)~ z8!qr)!6jEAW4Mm2PnSSlbPymO#!x2$BAK}BfX$%+n<H@rB$Hq`nP<L+*=qVa{sppB zStmL0_zw1!G^=fj`@+dQm`si&e%p;BoMuq$@6ahu2++pNWYN)_%(q(Gocfp?^m3eT zv>mJO!?Q#N=LJqa92+P_E-NabCFf!F-g*ZZxB|m-7^2$)%)lB%JeesmSW%LuBs!p- zI`M^R2x%3|2ZqaYrm`uL00o$H8Tl!c?}nrg$y7T@7BAbKq(K}8A`%yf3Wa>q%qi&_ zmqEQ*EC8p&)R8G^Smts_7U43IkUS`2qI2`Gv=zur$h<tAg{OLR3Ga@9iyHg;dvAN& z+iu-HAc-^|&>5YKX^ilh&wS>|C!b_guraV#;d62T{o2>QhD*$0pFN6g0~3!1LuN^{ z-Z(!y!&My*M|(TF5F52Rbk6&gs{CXWrfS!MaH?Raq=sD08B}CY#k=!#B!5zx9aNWc z)gIgo&g$ev7Q1_e4)1Yx9^k#}(N1z`E64d-y^2dSo{aErws*E^Rk>1b)EkrGxLhjZ zn;ab-Q_24R4fwH-TRqZ;hvj1NC#k~`|KkJn^<g_b1&zPNk`yg+zpFQ6k;+zvP3Ao6 z;*jJ*{>pLVxLPhVF`u}7>-p!NC9G8|v%(CPqMlcUOLxV6y<j*RP=kH}DgM~A^+qZV zu&y|i(A<-+TFsuAr4{)6z7B`wSa+b1L-$Fm7@2rAjfO5I&=(jA;s<{CqcJ)%eDH%m z`H5fq?<q%%?1D}w`jA>dA4b-FW|~T8QI;_i@d4gHmSM|d9`Hw;>hQ5SJa`HchJ~@1 z2Bdm4d)<qEAI2xg#)aYrt7JHtsuz36l$eG=j!!%PvIR9pT&_{bm)MXW;xs7aFe8HA zU@*ve;|w+#4M#%;1H|bDUCW{{!K9d1w+W~V)2N7?pV4H<5M)%MPfRd`>L;F%uJ)l^ zrPS^AhXXwS3f9INR6qt@NbM{hQkhw<Q<j7y2aXF)eCOw^QK*aQm{vdfqyI{1odE}! zEc&rl(W8A(qIFrv5hBEK0NtIAEywz)YTV{&sf>GGpv{D>W>Y`2j2Mi9uTDoYenR=d zDBk0a91U}fp5>J|n4&E<V0xh8px>wFzCH%ynqkSFKlI`pdTOxAO0nI6c&7+<^|da* z$#PN_M->V}qLkpabUS*%m~QR$aDd|jiW`&Bc<8$^*noz6a&<c0<KvTycBiL1NZIqx z<a&5$aIS{TwG!4O9|EK;(+M3}0ljF5n(??z_6Lz+%m2~($kKJOD~9WTDzLCGsJ&5b zLB#>JhXN$reWqkx>2N+^BK4@qq$ME{f+S}h{c+)fsrWiM&{rbMUV>Zw=-AW+N{T${ zpSoafSc4?U5&=v8_OPyS66;7xTA5{7B}NgUnL|yjHYwK#_O);+N0yVR_#4X6>J+Ch z)(Qhn<QZ)in7D(%@ba>KetxM(uEx{hV91_Ksknm24yy%)^_yA5GRuNyGf^o5J@Iu_ zFT7tUB)uE~ExU8r7AmIQDXasuk8En?9Bb{^-QFve{WMc{-3=C2IkPjlHAmw~;4;g7 z++mg~tDwr3pgn0-uI;%JX2=pbtfZr47Ryxu5&1++%!ix~5+{)aHFhPIMrcOAUOZ7o z<58uodu-Yl<C=S3nPt#lF1vs%dl_0%SAZP#_<VDOf)H07#TMZz7Ak^y!2z}?V9Ben zTGe$;SRli;jx)pTp}9-2o+#|3g%d)Ls<I@Z+ocKusR*1v(=cF8LgLC$L~JB6IPPAf z(Imu9^mshnk$qsrw}PlP?*NkpGa+RyBo8Qm>1ThI@Xh0z1DuCfB_gR+s1j>a_C9B# zJ8ne{QvmU_Mz}0&&Vp{vC?U9E4)cHl@|<}fFpXp4gd~CONW`n28BoKmAlJ&kLly{O zSzQTG=mRq#Cy4?X$C9?u^;a+hVV)l4G9W6WUdMu*gax{laXgb4fQ`@$&RqaxGk|;} zunI+Rezvx@5JG$R_xEvtpM2^`Gca&DpkqKktNGGPFKuscpPik-e|dR{Rr~$^GfzL= zKEGfzBLPvA!Yjs-B=6q6Yknjg9v+g58XU)WcX#A|Y!({LCdrf2Q_k!=ySx2v51*u5 zEYYMm1j-v>_uJds?Q}Y5f)0Cod(?~CbSQnq%%M7nCnqQPtMIgNx#cVCiQ-nP1%vw& z#qbbOfMzlvX%QO2KN=3nz(&l~*Is*#Cf~fdZ=WCLZnu4OboAiC1ALXi5RVskd#n#i z>GqV~>o1op^}2qN0ewh@+2p6udvlxXAO3fea1PB2N&)nI=9y=nd;ZzhR%<xyv%zZ2 z&Oa?+o*0eEugj)@$2QB0iQx%r*po|hkWWJ(5C=#=L%Qt7jhnU%%vhST*oWp&BLzS8 z>5qTl1J`Z>|I^?8xLR0m&{*2VJY(yxRCL)MA)GJ9@fplY6*pD)Kj}?61q%~005Blc zQImDBOc@{m9siqx(Mky)k3E*?I3TY)Ov?0;Gl_hfjh_ZjwdOB`srjXn<l`w(W<FOO z!CzuH@JEs(5ha*e?2Cw!Nnl`vPz4kkSgMpcd&#raPN~Zua{o$2dO7-6b4jA--*%3N z-;3uL=N#Y|GuWK&K*>tER;@GOqvNg)NDPb_LkJ?p7|%>4N|Ax^AOG<`YbN7UpZ-<4 zk1lRh^(qGxRXYb&0P8>q1qtfr@pxx<pXS2MK?1GL&(3<?KJB}G`+yNa185OS(tV@R zaDX>UdH%<`7=jwK<!5)^$;G#&Pw?!k)k;6UD%aX>xuujtBM&P28j8#v#<!A+%*M1L zI#*|r(3b9$&cqqLSTFI@M(C6AgflK|G!SWwD>M;3UN**<w9+GpRp|KSWHQ@eUINPp z@Kb3hvl6S<TLk7KDM@#xB;i721u`e}3T6f==?Fl{d~yy^Xo#~SBuH$Muk`hTP9|b% z{sP;#jdgOqZTSldzg6<r_xoz-qQv8XU4XHQR{2rwEQp4a-yYT#PGTKN$#w1Z&@vJQ zcmoB{J;t0g&oZ2q5A#UEQ)B_Dh-WAkgOj<;EGE<<G1XI%(6MT-uWwbd8L^&hZEM%4 zH}pb;m86D}F8k_z9JxIq7CHqH&QXE(n3JUY2q0QL6o`E|v!1TV5zjRUU7)e4HtJ3G zuV%AJNu+5Jj(1gvaBhK9#iK14leNdi9}%=U>5w9X$xzEkoC{b<w}lhjaF7;QkdM#> z`DDUEGU0I@VA>VuknBxhEG9EXcbjto--ZLc5)^U6QGk&~NSt~fZs#l(FsDXM!~r@x z67<#kh%B@U>zc4YR#P9+SmEKhi%5D}ZD9FyM5@b;a_h2*5%b8*GGdrfxxr89!O!N* zVI=7bTO2!eJYaHjBE9ASOP~h-vIER&fIyPu0!JLaWe#w&arF{^9<dB%Fojyt6%{>h zOmyREp_2fLiHS}~GaPqTT5UmMfCy+gL@Lc^0q99Ma27C~2t?wTj0jagB(zvhEqEZN z<|KretA)Ts;93k>ApnsO3%H+18pJ7^ikspHponWXk83m-2WCb?>j?w=biaoP`n&m5 z3cr~NNkSw7(aKmjAfDicC!*Tm0iE5MjE!NEIU#UT8^e?uXl1wC+1hITzz_Vud*1V& zc3VH=@#K?F{<DAf&pPdPqh3EaIN+qrDu$jEp)B!1zhAB37uDIam@=HX`@KHBLS-lo zac6ty_~@uyDnGdY06WsQUbow9wKz{RCyE=J{lNe%LDRkf=b7g3Zs{v<P-$JQtgqJ$ zx@?90f^Odxd%ZrrThWWMo0?3cF)MaF-dx5&<w}*)ey!eslQ?BN?Ji3eTdF!^I>H=O zT`F#J7%vss+v;TD*>d=29^%_<H@6_3ot?zJQ2lr}ZV6UDJbb|68>6x*vnb%VH=7N- z8JysY_T|OJB~}Wb5EJSs?>WpU=6sLglbxA&Br6sDbQ7*%&~?X~+)}x?y|aD$_N`mD z4z{+M_!w9tit1Nq5JkTrliimwfNY9)I@C*_G6pvG_xJF4un)t7GU!0>cmPm}WY){{ zQ~cpzQ{?RI49|xNgg}o&TuY7<=np@G?gJnAQ8j9g4}9p)eDV|j14A3_usLmEy<nFr zR~U+NnHb2$GW!aP1><&;qYVu~I8Gy`qoC{Jk9K*v49}e{5MDh37efZ9jXGn<fsdbF ztX8+TcB@r=e+%`nGYw>DY;AARqcntu@9gNKpy%gjgfztC6J{(-L42gR^X9v?I9>|1 zWyZI%ilxm8gQmtPDB-Hn_3id$v(eOoIGfPv<x+v8+UeQp{loh${mc@Q^sa2Nq&I1Y z!$GIpqkNsAQ*WXqeSwmU3I^lx$tgo|dwYi|NPR3$r>EyyPw1C8@X<`_ao-VNcnA2` zfBlzWCTr9m93LNFTwK6|L1-Nj%m?CT{w9;rz0bI%Iql2#Xgq`q&$;QJ$i!bQSH`39 zg9i^-B3oNqZCv6)VRvs2i%iCh27QU~vfbX>+r<J5;j^<-8py2Km@<}V>~uI{dQzJ8 zT$4*PN(WhHHY=WV80&+odf*A=nK;#2MR)ECg~@1)D3p%nDLR9xIMeOu?D!dXjP(aS zTyQ#x(S=L~5@i?}tf^E<jp_o8@Xda2aCUljaoM?OcUTR)NMZ*Gj7`nfi*XgT%$H5m z5+%`1Nr-X+Qp}*n1RQsD8B@Ro8P&w$A#P3;jvWd*MXXppmv|};e1TvtTur`?On8Fj zIG*Gro}|D6oV$!Hdk%^lc@069y<W~bxD)~x!f0#;v#Hixz0OKDhr#p(AZz8{D4sB4 zL1zNe7jSyeFr=X`!?imOvqQi{PFW<AG9VFwDVpY?lBuZxp^3|X7V;2;q!n;(DxO!y zFp)+}flwrk#!yNyTVi%-5H}<%o?Xn!<fMVbumB`vv4|TmvouKp^O`#2{BwGGdgsm^ z7BT4id;9be8ztSu8mQ~4oo+l`#HOW{Cmvv`mMW!K<h6)E^hy;^QEhT!pcY?DXOVQJ zgz=n@4*Rk0Xa|G<$7nF*KML;d?XoZ5Jh=JfQ%}6`w&#EUv!CTiu)n+8>vdWAsr2OJ znEjOf$W5m0wylImLx=-6IYA28$ZEB$mj1{k3;irX=a%^^GYg=&D_sCYlu)Iq-p~Qz zS^v4L704KfMS>FQh3JT&NE6*bM`Nwl=20p)Du4uD2So9P4sHT~NE`~50ggjY>mdxZ zn(ofqB>l1JphKwSKWW7uTe;Ouf6)xzxmC-F>-eF^p-3YtnMA{0nguuunQl#h)q|fP ztfXp-I#O|J(mtq$>i6w4jbu43*OHJKLL3<&0#|`pCx!V1Q}a9i5YR3)dg*W7BSq0a zInKG2WC|Vp&_ryBXExQ26MHhs7i-mei-Tipi*1d@s&O+nQ)c1tz{t>xaIwE*W;q2_ zeJhi*9$m@*@C^EcUZ+cKwMu0$VqWVDP1u29fO14QwsGJmP6RL{y4@~x4m|(Pzx(gH z;cpT}j_+CYI;e)wrq74#=y^a%ppOZ&jDYFLv8Y5bk`oBb!?2*`X{;E|P4UDGoLqo8 zjYKiOhWY&Dv4F&r&y8`L9aW*{vp}NcBZLT1_S_)UNH?=v5H}}q+%>|0TSo{#Ntg)} zGZB(0Zu-g)B+e88C}JK!ZG_P*oP;3`6*<(1Z}#%bFXQO4$LK}&dY!X1Jm31(x8CuN zci@UJURkj0s6)pl$e~fgUcX$__h#TB7a~K}ZwR|B^fGi5U|7S?ZrAJT;bC?fHYxg> zklDgCX<uG4B{2u5XgkvKDjE$Mz&_w!a7B6}v(rHzk^r$(B-a>yz(9^1vr)`F)EY4H zuz@x_q^RloqK_6t&EaXk(>p&qqlT}1<tzA0&p!JsB5Ci|c9Z1c;US|^t_7}Fw{wnx zF50K(=eQZj$IMjS@5@`Gy)yeu$6WqJTWUkes;*cA)de%9v}_j&t*z$X-rf^WJaO~p zeygRY(A7g5)3^sNR|hF5j}UA~DH;ZmBO4(^8jHZAqeB#%_kT8G9ft=XQFaKh#Ngv$ zc<9KaAfgE4xFDi+_|;$g#f48{ee&1;ds>9~P>kV2&ruM|q9MBjI>(+VBdcjFkFm#~ z17#g?93%~)J1f4tHp1pHI2pIvmWV(_rTF5Mofb8cc%f9FDcx=lb3zC)6I$V~HM+?d zhg!&BoZth}E}wT;=!K|)9uI+D7Ge)(r_>jcb#a=t9d-)(ELE#j`Z%|7F$Fsj(Vjd} zk<CImo*|H&xcQF`IwCVFAToqehLM8xh}7$~Xk&hQN-@HPN1#9U%m0wtX%|W(nOYf> zbQ5vpcp%ZIlm+Y-418xX2L}Bi^MUP0@qzqO+JiSqG5+u|t2ph=#$Yr$IzHC>!4<NG zOt*f2P_4!DNb>M$j_$z<a_Uf89i#7AsOgAL9w7ft*<a9*xzFl>#b}Y6#vCV-wJOAA zvFzHbk}_&c@K~Sp$s7JtYUV0*57q+!28_uZ?{@nqC#NT;XOo$pR0l|Qjrr;vPZUXr z`t$UZyArT3vqh_~8j=U2YgsrUa4C=|fVgo*zw(&C6@!s0@kqcRS?tZh>b-fmY0Dw< zQ>%%jxRGkl^Ek4A)zpxX#s={uP}g@>VXb@)iIKa&u#O+3x(su!<9}Rw!o$TTEGUyl zUcwtnV+&w80<nV#v07@Y$~abGh4APK))4;DS8@ccC*?}@l~=xTe0<ExuzzC@>iPLO z4lrwm>!Pr_Gj3^cW}s;NH`U@8=K*$4wmcLRSM-`|BZN{d>(eCG!BuJz(d}rx>cTl8 z_7s6-jgyjmDBR;%X45x8I3}T|$JGLm=}1(24JPJ8L)=SXiOjMe5o`JvQTa$pt{)DW zK3QUpWr_jawoNc+J~YghUzf<u&rK5-ke6^Bi~MjJS$YApjGi&gfdW+R+DQ^7O`Kc^ z$t84h0VXboc|e(GneeDs7G)%D7hpRtwB;d4yAR_$S%V0JpP7iX*sJHzfiSM+1;}OA z)N2hE2cI*UQcM%h=41u2$Q;j47mFccds@CD5>>DNg@5PY3BBGd);hp|`W8ZCB|X^% zKm_RO5DHmlFa_inM2IQGph3%!WYT^@c+3XfFa>1k90j<D%FjiSr1r?n<XAD=7dY3P zfLs-x7c^idG#%u#T#EtSA>ar~+&m;*FJQ$ao-dW)s$Iks7c_;qiH0dArmPfMRmBx2 zx)4$cG8kULIm7RL@ArPs3okrB(NE*{yO-^be!9BP8NYMce(srP*=_cAcPF@|@kt)$ z0XrV8x;(!)Iy$<4@9_Nm0*8dtbGzMn@Zj*3SHAg`uY8q_<ml)a`r+Y`8HnIRo}Hat zUR=)ffW)|cehIzT?j9YTT%L)id)c{&+dA^E#(0dA-~0XFfAHW4V%+M~iP@**<KvS~ zr%R=HPqZVRqGe2#@85j@Wjq*Nwl6PqkLY3q&v<fvdUAGl-s|YyU|dX!Oh=Q^V1(~R zV{hHM{e>_5VXxQyp6~e{{6scdHd$0{w=dcM8v2c>0lCz3h^m(;t+zK3qK&pc!WCg? zgoV{{s7E(Rn{s(~XS-3Wmznuv{U(21&sS^9yu7%;<+!m={&q#1^b8(4MMF*>-PIlJ zL4Tl2*QL^UsCQT8s0;^m|7=QM3|M_S?M}VXOkM2Z3W($TG4(=8jRz<OzKbZjM9TO! zuXLs?Y#bdJz(2C^E$C1FLl}GwVROTm&Nn$;$dlA{LS1Ey3zN#{pfF~v=v`}FP{brr z7aO^L0+$t#5ciTlh9q(7i}~SIf<}isLj%K!#fs=or$-A^Z@p2+qeGvqEqtxoWTFQ{ z=p!Vcyg2j*sXovJKmD@1wXKGt95VKAz5L#v`RO11u^;=<pLzcee)I?b)JK2t?eBTV z)2;r|<w>`LsdZ6iLuU@1rQ$gP%EguV^2PZD0!0aPF$ys{gJ*0jgpngaQ8gRKld#!r zF+%WIQH*A>2uu0-o^5Rj!ACywlO`G;|M)MM9^Sfo$72K4XeJ<uKtezj@G#y8*=A6L z@vX-Nkxx9XceFd*t?iv+slps;HCv2Az0E$+FMHzyGg)?bcTUgGwzgYL(t5o@PiUF& zx}j~6-qi4tX>?e`Jyw1U8&TXTdS7>>UvJ`Q=vyV#O7;y10GotG^JQaEGz?<cQW3?W zg##Q(jgy%0r~#+Caif4S`~A`7W#{<l3<nr)m^{>BGl<KG0g@>MaHZrz)@qO)a0<zW zlPjQcCQTH*k_<&*DmWLJaV7*gGkZYNAZICIebuY5AphIO!<zg!us+M-0w5a17pgYV z;WAcJ=K>v9H^gYsu!|Z@&m-|(4^@a*2)kC*LNZ}Nd1JYF!aDjJ!Uf;3_)2|1D!3qL zoj@(p*%VgjBw?1l26^EQwUn@?$@{f1pk<-g?Q)W4CAf3v4(r1UFT8*k%2GV&4|V;T z1DF;DO=cDeHhk7St<J2~tVmu|wH>iMlxVZ+4p1q(zjjq`wPLx}z=|HiQUPrSEM9tg zN<U7qy|dlg+B(0ufX=SK0f18hx)w{<9?AnGL%_peHpB50<^hE&#PsNR%>G@cX=;Kw z)j0tyX8NOGp;7}OSuE)4sd+Etvz8I{FCr)S8uB&f!RgUiscH`cWd)oi)}W+#D&-^~ zo=+Ny;>a?Cp^{nF>Lx#=U>3U$YrYJcwve?>f`L_Fpa=ucyQ<^N0v9B_f|Or!fa`vA zOUDIHVwabf9OgNJa6aL53DuT{U$ZsbK$1kL1yGPIh(y5u<}dz5sr9Ducz1xoI(k~; zoV2<C3fhwkh$IH$7G;<SAf_x+++bh|A-QG)7|U!X0w*PO&QA!P2q6}?wBX9<AW?{? z2taKofeTV2a6yQKrW>df<*uqWEGJKa*~%k|Qh9-dj2JV35G?iJ0YqF7PL~1<6exx% zdAOkC8AE2LkQsL;sDWCxwzlrwyT?d<-}~P8p6`Blzu$lG;K9wCH&2d^@87?F>(;Hi zckk}+?{n0Kh#L432%~nZ1pndTAw1vu=Bp<sC#R>U$H&JAeC3r_zWn7cf8{G*f%(-} zU-i%H`88UYaX~Lm&ySA}nH6WJr?0*C+WmX?$bIeASG(Qr#koEOd5l+$>m1>|`}dDe zPdH4Uon0IsAHn+?tgqgA_0?~cN|npYi^IcXC|~{R*T3+E&wuu_pZn~;_$+#!9-Z93 z|KRTH;O^mr2e`^dhY#-Ey?^iZd&F_Av`dB$3^>DA;<cZ<cVB0sZf|dK!frI`XQ$_! zzZpeXk;ZbGhq+v-J$P_}vrjEyXS!Rr$HKgl#`%i~HpWVn1x=hYz5gsB<P$H(3#%6w z7qwc2O}$oUCsx11%wS;hU~~G2fkZ9H!RGKIp;+3alz;XXQM<dly1cE2db6>F5cnl4 z9=Ru^Y=X0Jsx@>uWzUBtWud@Ny-23sANi4=fSB;1ANiTz`t(17J?bjp-NKANq_Xj= zaq^A`H+4s}upuW6;~<}qI1x@K6tNm`dWo=lF&MMroPt<FM&tP1^mu%LLkL-NM`w&Z z*@svN)a`3agA+qh&_k45gp);SDyrE5yYW3g_#=P*U;oHQ-|@^rz21yw1?tWE{tNGT z?+?EJ<tK};|KXiJ?u+cH$wIAuK3HEP9?2D+-?UVV0iCWkd%aR)qYNn`8)IC%jZIcv z_5iK>`kApwt%e;2c7V}50bvU^|BX+6oVwKS;c#ZuIVgfDP|L&2#&l$>+1#Az8EHmZ zwzh;Rn37LF{WOQRZl{Oys>=-1+5X-hLz_~Jd2LtfR*s~4ft<!cDe0`pI4SEo04Kj< z*$z3N>Ue+vPN}2^5$TRN9Z@N9vUDnq?5s>SNu<AZ_LwA2_d$m+9!=+4Fwl^&eJ}-6 zfuf_~q}LmE+C5z<>vrt`1B-<-YRDE$C<`IW>Pq@LAW>nC$C|A!rRVV|K_Fzrfb{{U z=W{I(Wa$-7+!cj#Av>d_Qh9-StfN0Ja_T)2LdO+IxeH-FlE=z=;atfKR#WG~k;YK5 zOoqyQu&lsZ`SBh2sQ(%Rvhu{F_JaQA0a<zp56OBsTrd@1X}5<!It8-y9Lp4g#YdAi zhgh>8^7VDW(()nwp)jk2X`l5DCxLpsKABE9PP~5i4wBhGwc2FAY@fY@fYI4O5aq9j zXsyyh6-!=#RTqKD8Wg0km82BVD3~uqlp~^M#7FayOEDS=0XhevVSMYM+wO4G;f%x~ zs*_y`pC7Z_sNCr^MU0j4U=dQ>bbvXs*rS1xmau><dtPaxJVbnyyDDfbQ&z%dK}tFT zFpeW;!0ahEWjzMeMe%R0t`uK}YjCCN_&K~R02c>I87CdjV<p{0kfrBXpj`3H^<TgO zf5JL?(sltW`PT^nI?RPM15SgfK{8n>gRV-)^b24{W+)SceSfS^f$B%gIO-EpoU+|+ zhcld)4Qhc14`P^K6l9ABt{rCMt$PRft-AwEd;!pD5?N|lTsAN>$j8m;Fi$s3ac({W z9k2jF0ZsxZ4Rab~5wiAWd2>Kak!7TI(IqJa(8;w-Q=DbGVY<P&lYS*a5%a*0@=gLG zmOvJ9I-aECk`<bG!G&&4vQn;v8>Sd}o)ih>*kZCFGK6n-I_<Z;?QL&=``fFv3Z5$1 z+uPHFkF)9RC!aXKxbWe!R<G-aRA<vFhunG%5rfh2vfaM-;66?!?tyRo;&Yy!o-u-H zQLD9eetv;tj7y2@%hpAsE-%{*knnQPI_)mbFh$PKE{LC=oFNAW4z>C_$2~sB3%>v0 zu-_lR3B%Fhk^gin_w?*{|M~BJ?W<qA^V*%$lhb~$&%UWEw$<uuuf2{-{TjaSy?e)U z&Cd^yj_=)nFdR(|kB{2jF8)Bh(X3Q!_){F<kB?57uQ=GfZuk7`9G5%Zzb$k+T?8_X zalBCpYvUv!@G@>%_j<akETb@NHspI?^XL)&WMmA?CQN6I<73g3jXT(y-h)A(MPYk; z+h1UgM@4|{j#3u4M61B2Bojdb!sT#o=;K)3E`GSi5Ahv+%4;*8zg6D?=+U!+mm!Kn zA&U`(e+bGI>eEh-SbB<x`8%BsJg5r)r#}6wANtUbTc+`wpZo;|eo^ngmBy24zdyve zQG2!eWkW1(-{~5Qg&-4wG=YjxhN_b?;)_`zganP|crbyuZmGs(LA`3FhIILAvyJel zstk?zkoc5Af%AqBMv->=vRu+r*|e-&s`z~sB*v$Y3zOZC{#*a%PrZFV{N9r<{LZic zx4-d^f8m!u^{c=A+n@j1>7aSz`TaVc@WIo6;-l}_{KCKZR%fb97(hRzO9O`C0N>cV zfhNPgp0GnSV*_nzvTi42w}o|5LTyj<sJ|cwShu*fPlN>u`k?U~luF@8t~<cL{)vy- zN_rqZRvYT|(rSJv?Y5r7$AqdbKoxY-kRHO1*H>YRMCk+=4i6t39NdJTljT&mTcAyA z)yi}{?R9$9N|gc7YBkSJPiyonhrbxc^zTeNV%*K==qQ`SWAE|X%h;OQ-Jd9hnfiks zJx*ikbPp{irsT|FJpr{>DjI<hvGHg;Ad^uu8jdj>(j+wAP(lcF){t<3i-Z2C+Ziwk z^=Q>luNlQG%vM??6H(c@q4Hs1k(kR`g*CaWOX;1fY&>U_InXev6h=$XO?r6%{HZcE zVW~Ja%>J&I6%b3fROAitxcsi=t%7S`4iiY4lCRf9BO@(gT?R!EWjG1wE9WkQ+$?q- z4{?CA*c`6taj~x6b<z^QBkPL4A=VXKN2k5409piMRR^YI*=vwjG7EJBDV7(#hzKRC z@Ybz^yLa#Qdfly7i)HppU;5JByLaC4j(6$^qCKpn?IvAB)4e7w1<W#hW-SMkiJyhm z*B&rk{7HILkPwPXbK<I%dAd16&S*R$q$CA!h6nM*kiGpq*mn1J$vr+fuGMROeJDpO zPg;Kf5jrcxOQypF(?LGD5Kk2F?Tw;`V4;e2;#0lmBx$&TkBj9NAqQfj=NTRol9oi} z!<BHeg8dqj+mfXpsu-N+0U2qIWs0#tkD@{O4m-ekM4cJd@y8YXtQJDL$rGFnJrS>< z{V4AM>$<#8o}9s8=FGyG#OI%QbgRdf&w&JMXJz6f;A4!hsipY{sQNAY8Kj3ez<|o~ zAxNWPneIrU8y-L@*Kig@M?jVlmL)XNCW!S)&kE+*EE5WL$y0!nA>bN6NkYp>Fnu9n zP&*+MOK>Du#FHjQf^*%4iDFP`E53PavG5SWK+=@NpNPbr#lew~q~naFWFjc$gp%x# z<QOnyu^eFVBOh~43y~aT;z9l35B?xN*x}IwpF|Nt7wqot!q8|mzWL2>zWCyc5TT$F z6s7?TI_bt8;5)D18}za-H`*XcXE}-S*;ulWz)+?L>T^aW0tJ2;;6x@#*bL;O8@X|w z9^e&sy80znXCWM!xNo;^-NJ`Nd0L4;d{n&Mqob3}jbgt?6$6g_EVIaG5=PYp9CfVG zYHc?g`ic_DmW!1K_YXPopPrs0AE*87?Cj>v112!;Ax*|bfBp5>@oU)a$okTkzlwG^ z|G38}L-(R5UIDF}j{<eQ<ETlcvv7(4bPPi{jGtDbXDB<F$|c4Rr6B-0_zRF(1VVFN z7{fmLHKwuN#KsSb^+k`PKt~ZAFe;=7{84GPeAtG78UeYENTo;;0YuDZvr|0UUjCsU z`UqJGAN=s2`;A}whw&V46+Z=L9B5@w(?<L>ON>Xx7ekqdg(DW3Gz!h>O(<fwb>@h7 zO5^TdQT~tAS46jwDH!%t38-{B^ijN_jkM$AV>)PSYb(rxH<jIFM#bnFHGDLhl)mfV z`uG2h@An4)PrmZs{k{M8*S~(QA3?%*+T7^$PhS1X@BiW1&F_Evz8LDy{Hd33Jow!& zKET^kbLb@OME@2`+pQgH!J9>L2vaZfU$I=lXCY254Ph#i#es}N8fkh8C9x0ZCk7!S z0;26N5xIW(=tqCbM8l6j(-B2|KueDaA%}KhG2-YzF71VZ{vruI*jP+9;nU*+@i{TF z=v#{H?d`#=%N&y-M%&ujrsjUPPjTi~J%0Cldu!|X=&)9+q7(h11K^ByaU$H{PxtpX z3Yb9DxCc)Ab(=hXfNC(%I>3PyC8>_8X(>9h*f{Cl&yN8VCP`UTf;p~$(C^|Biv%Dl ztBV=UgrZm5x^{Na>9FqTi`%2g5C<3`7LH^<(vehG3i)?|GN-Qwq8-W0TwCP21Dt20 z8wjJQU?P}JWdS221@b(3EEG?82!9s4j&<~PSWxc`AuU%S<*p1tz9NVuQ`T~18S64E z%5XB^%oSLd_YenoWf4~goEzl?6PNLjtd&Uoj-+I&_Yq<Jmy4%4wG5b3DI?2R5A$3L z^{<=&gxMLe7~Nd$bXdgL@0u+=Y|PqHDV1*Q-e4DCDT7OYasFlj2tT+mV+&#xj@M!I z@dI`QeXr=s6vP3O(dR1)S&djHS;*MEw0a{7BB55`i0^D~!-+J`LadXlT`ZW#$4A@S zJJNr?{s7`=OT?1%APc(V`CQ@)$t?Ex{rHBk@KnV*@orIKOIW5Xzzk7Tu>M3MQ!pi2 zJ~0^U+M8uB0b>&`@Hn{=h+k%)(gaIzKc-~HH`f-J4xCJIzbAU0-w`A6#6{i}Sl~}s zM^6<kBNfR<*6}BQ!JwNAPFaMs&dCh%rczo0$YomD0j^f{!x?&$F)AX?p-j!yS1q&a z^?+P6FlB(xZ%jHw5mM=Q{2gHH;YbRNhtLftQyZWp1Eq1`EQ4eUS#D^s%L2EbNa8V6 zEUL&0G@LYZ3ISP!Nua|#5)Wa@MLv`y1el&L4pCJG4|GRTnBc`U@e=|k38~0!K>}<L zi9=_A5b?T9mX`Pcao~c<ur8HC0FNVyVo(&yoTxYgkW<oUc&G3E-tXaPe*gac_%&ea zo#1c!OE%qJ@3q%nd*<0^iL)DVmPI#;aE=dA8+aghUb~~uyNx&EOTe7Ci{s(AebGKY zJ+D=2cx{zZW!TrRl5)81Tz2FD7B=y;*uiKFTa;A6!DBGsuHf`COK3=FiLTUg<L0fZ zKC6Svr#A{X2jhI=75jEE9$>H6$2AB6Du*KcD@(C?mh{sIVG`X%#OEnjs(br;%~lIq z@E0eeF$S%aYj<A1g9ChUaL{NpTg@hxzP!{;Z1!D*QCyW$b-UZ?>fRH&(IE<Bl^{+n z)J0Eu5piF!XJb0-#@r@9;uCD%ZeP;-P-4l@*Ml1IlMm>PfcPbt!Zbeb1T)^nVAy9l zKr|tuC`(B5OJ)7!S{fk<Xs9)3G|`%qd5^kRN$oPn98xyMA#oxM5O#lB@f*MK@eh6I z+V3I#%E$iRCT^V^U_4s}v#zb+@Jb36jH@b&hU0=%(PfahRanyJ5L_3cuna^e!`1Y# zL{ITUb}71hz~GtUJz|9_GoD7(8v2eD4TBHMP$_I!6^r>Y2Nt6$N~y6g|C@i|r{A4@ z{{Acf-T&(s{t(yKjx?pH6t>Ca;=vccQ24Gt^-S<JZoKEaHb4J6ue3FwCY-SfbU>|A z$CA`YD`^1-t5N)nEy4=Lvie-N?#Bq@Jf{lKrlv=fY0*HRs@lX8CP}@X@&IW@m}|E1 z73hzB>>oI5W1^8myKK4?2Qaka7p?F+5l$90Q-6GZRD%)?VPat7jWeV#+voVT&3Z!< z1I6P_wpO!6Gts_Ut1=Fz;~}+HN@WVt#f<J5P2MQ^Ly!8?qZUkAJ-06n)zLc5Fot8H zXt7o>n9&MNVH@k|eN=`8WNViiQl_|^XN*QRsxugAV!5O#02e0%ay@JSszGN^>tT?i zQ+-yT!}dCeuVTp*F@z-F{H_JK##ApY;{QA`m$d>cM;2%{R{`=>TtUx`%j}9?7waho zECGteTAu{-7#Zn0QgL7jz;qKI5$oiygKK$oJY2qWm%}{rl!tTXu`bX06H+|DB?&bE z0RQw!L_t)^VFWt9jP>-@4si5)Mp2gp95;O-bnY^ekOjOUe_lRV$G;9M#}7i*jVtyR za??UY$Os1yABTA*9Wv$P853lnv6eV3Dzn+Wd-pg3u~gr^`=H<Ju&xXTgNuucVnJWT zC}|6cnHY;9%S1JPYlo!7hGb&=6*-$I9VC`%^whREX6dFDNeD#sae&Yd?CBnJxYxS2 zjS$MQpq-zcRV(@e<yNc3IRSZu=uf>aZc$;9MF&{I0}J#NSIIdNGkCmSye=n?EPGyK zqO2PxG{F&bM*D<y{YzF}atfiRq+tpRzT-{;B!g7%0zAK#!S+FJmWb8W$s~3O*E9jq zT^@Lust6$rmQ3@MG~k3{WTZK)zyjc3py$f2)^l01v5s!#*TJRo;d=gS%?FM%{!{TQ zNO^|(%nvS6Fix{N$8K-!TncS$%d!v;7*03^jpsjmW`o!=3<h{0#&K774mi({1?7MH zm;REJc+*%tYS%$cTZL$J29l@<V*F&!qUa1ZM{1-w9ZBHq#nI5d0n%Wm<+R_@%<qao zlJgMct00bKBbH@3+ZLOUlFmv69hwM&<%&7M{017PkTts7?NTp1Hi+%uQf`YmNm?v% zTMr8`bQnN5IcAGOg5{^O4p$=a=aHwlETX>kt-EY9)JyL9`8jI43ozFcPdstw&K;Eb z<~P3yGrlfau;F9)9FLOaaP9Pg#7cQM8DDlgoqi7&p}D<v<JQ4usmR|3r{uyW2W%Jy z<56!Qv(RQ_(k1Lf{rJ&899i^%jzB0>G4ihnY;4>=Iy^l+Wwek&AI{dgd$qky9C*T@ z50G&-^y@g?PJcMiZE7UP$9QlLs7j`$J19bkXxpA-uRB2I{d<R$ee%htX(OYi*F_P0 z{@U*DKEqQFj!vh~KmR<EIdL;*$--@p^Ey>qh54+eaq$6L!0Ei(?_GA<{UNO%c6;r< zejI4B8`z28Sf(H)@cwCjrCQ<-_aNSB(jQBV?zCyNh+%{VI2CLmz7Vb)!PPmA4hW}F z^@d(K4r|LG!_k21SfJ=WkZcIhoPv@+(l@=*WsZd52#d7opUD)bbU2<2CsR${s17yD zx@K3D_X3T@4l;2ZW`-?E;tV~rV=n%nQ@m8Hl!}b@(#DLW&Q)q+{NNT&Pp{h^^t(9K z3^ts%Zu^p!#O?RV_BN(#o}Hb4i*bDSu38t}Oa+W^Oj;^^@Bi{=-V=9r!52UFkNz<1 zsbNCxn2rzyMk6fq+9&@0Cr&cXjT=AwSN^q^Gb12SkNK2J7j2euy~2&fDAn)l3r|>m zb2f^X28Q@+alaT|WaA*}BXfwRIrI_wR7x9Vs)h#z)ur@`e!5t{UOZmh^<iVYbh2;1 z>8W63RymqUff{i?gFq9Qt$zHW-PS|w9wdVSqh7xyHX6q(-y5?B4;~yI9-<QZGtQa# z4DV33+H7t2#^as+8{J;7)@XGHeL4EN53fHQ?ox49E^btcvr1uBEpJw9C5@dLZZgf1 z!_SnWx~w;~ER0d+;-aJdkGkU)u0F7h>EqD`4!x9QB87%3RjoA`21vkgc<~JWID={F z)`*PX7{hX-@r2o=-yuVE_fiWE(&Ma}|6`2BB*@~49)FJql!y^7Fs=+5V#+$elf~vh zNRnfihwhJ|K>8{a@j4|7|7c=a&voH?gk7&0EpM(AU*LIkg!!+It-ypVI~y2p7&`KJ zpqeZepz194M+^&!EvUVKFrlDHJ;xi)i)ApsSh76JKqLirMg+18?Cou{@|~WZvy8pt z#g~8o_dfgOFMsv!-TUo}OFZG(c%rRyJRZg`j!uU9<#sK_dKQBX=;{Oo5X%b5Vge^; zgV^YGAVF;^(%M>MPiJ#vk8Bd5m7E;?*X{OB&d%`;`hC5u@%-~IeBbx|$v^++|5w{P zJFTrP7G_p`P64(9?Q)o~GMPe0{-+KsnZ*JRZ<L1(5qCEck`Ea_ve7DJ*#RdPi0cp| z;%dBQ)K$ZNLEtjO0v?zDUjmX2Z)hAC4C1zr_TWkOeC{$-CVu>4j*uU}49W@0Pi{s; z?j9#rGU;UwFffR7o{R&VPEJ(K^yJ)*Ck4#&=AkR}{6l34ZYOO>jikX)Pz9iF-f9VG zNp31`z>}DXfEZMQrKM89JS16kIE^J+m>(ip=0PPW5*kTXE0S>p%)Ts22*2aNnuHk1 zNpUJoI*^3TnveuZfoRIrf^HskaF&zK0*MZY03@S>yU<BMgk-*;*#Jc9bsRS0P!LOx zz?SI5RdGmwf_w|NaR5oPxd;&&b;YlHiPA@O-IH;1OPj^b8#nj%Z|u|2^+xsP!Og*N zaC~ySzqfyUbc74eM)AzkPuow!;1s8vMG>L;qx%o;-Myy=GeecQ4T!6<L2@|K)62Az zkh3Ut!%(SKusC{gNM?Zah68dqY7-X9C90d^zmlzoll2WDc=%tAldkh+yBEU!ZjUK8 z!BxolzFeha89QV%EKrJGM{xwl!xxjSR`b@u0e&+KY;=QOpJ{jJ?(6J&hewCyN@aI{ zw^FP2;~Tad>pPuxOyeOA1!wxRi~ei_{pl$zk-Zj+b<341%Jm1`F&l8)ztS|OY_C%+ z7jY*#U3}oazD!iDjwkwYRL=TUeO~zd*{7e~+1h#S)jRKe=R5Fv`lBB1rCg|58ELeo z)zS~TGBmIct^phVpx?s_z}&1WwMtdrl5VvsW!%Uq6ATN&!~7Zcsk2Y@t%iOKb~+iM z45x({W}{xOOY0bAIK$me54M{(Z{bbdym>%h{_qd~hz8aiKmHSc{?niOdpJLG&WnZJ zy`2eO?#5=l-sJqy>kX&lLao-oHBpDgZDb9L3DZ_j!rXc7bvz+`BEO>F^~EtHq;qf& zhodQ8(3Dd0i*S_GWrIN%kC)NGV8bV3Zj?*KYNfihwTo_g^0hzQoNYGi%^l7lTRV86 zJKOYagDz$)jYq?mf9BtN|BX!f(|`8&e)U^=L7hIO;Zz-CHe2z~w$S@V@79mLJm)|7 zuBXob$>)!#o=HS{HpLs>Eb36TS)AZFbD-DH@eFzlt;@^v(Qtq}xG~*igp7uhO1aJ` zm`!nF<3_RO^^n$4>1e>nBulTXZ?(4cv%}*FM*CO(?7!-&jZggQFHw#mTCLX6nQmls zV+pj4aXoFfyYU;y{&nu!{{G(9)($HieTtI0!K=fVs%8pMolbbwIz}Fj#vJ2jn#aXv zYwNPz;n;}LX-lzE9><CDqJ2J@DIE5D%)d&pFdGjxCd1<9q}@In(khxUVg53V8A(j{ zQOriIT?|-Gp5;=tR&C(c%E!>^rMvvHqf#4q)vPf3jy4mtSgMq3#d0NnU$MNoF==S4 znzr@zNd5E|1v;I6xm@e^hbQNkhsURfXQ!9F&aAjutyk$qI?#WNWdEs4;|fdqV>J5D zpx<rhEFH^Qif9>~1B%yDDI05!hK|2C&iq$~peCv&EonxGzmhM7+$Hm^0l<bTlyKST zESjr0d<a_(=|M`lEO0Hran}V*6x;+;114Jk<v+v1f%ODdeg)!5ov7e?xc2W#m#ngY zt0R)-&B0QzP=J4<21S(Q|0t;9Zr5D01%}`&LoFZ*(M&>2N<o^Vmd0tw6kruRqJ$u3 zNEFvX=%neIhw4!sdmPc~Ie!vFoMMt#X<jI-Q`Ewj`H2{2dt-P(vp|<bkY87U6xC!p zL|yLvAe$ETUX`0`GCy@B&ILq?Yf46C=n&(FoJ=ne32C=69J0b_>@zKx=&yeBwTT`v zyF7Yu$hqgKr=H%@53TDnCA}^i87Do?QN@ym46{t1A7s0tcvhDWz&;SfA`nwq2VjyM zirB<qq1#!;(1Eo{wd)=)O)EAUO%55lG>98K7_#-_48P;$cX4L8d2s6+ue|d73vW9= zySR1xiFUiwYP2pd+sN78-l<n>90bOrajV&4=W!#Au!>;yKxmo)#Ypofi+~u2Y64Lc zm;N{)xwj&Su2i{rSSdhx{as<Er?#{}%E~H1N9ghaHO>3QedI^9A}LDbW^63)dhG40 zE3YE+dvDf<`p|))g5^!IR%W2RPFgeIB955floXjv^|4HQ4afu#k&u`dA+re*n!`9Q zojZ$2ibK}~h+{THGb7)*iOqE2WF8Cjg(QTvf2g|jHyLXSmC-qZL{AfEKo2+$aU5mr z$Af<4G7uPkOv<dDdAp3X85zXG@YqfL$niBE$Ivh+#jkM31##R5CJA#vBS_wau6=Vx zRbPrp*MJChIh*qQOS04Lao*b6-mN#9!|@O<cF=KHn;C~1oXWc0u6;Vw>CHw%zomp$ zfBCQc6>In=!R)Qe@N;BjGQtqF+;m_%dJs1~Q9#&8z3!ypWN^upDO`>u{sjsn%yi^O z<~6{{89l`lKg`w#IE&Cp=y{nyh2!u+XwH0S&Xi0M&!`1JM^2WQ^BYcv3YkiIhExkk zoaQkSeH~~>$X=nXiA3NrU3_{*P`;tohIph<4*-qFen;`(;3h+j*~D1nB+X#J5u*6c z&dyiA`c)jiX0zF9v6Nqui%g0zUN>-H27{xcqr<}^`BH2oGOLzkG>A2OL(e6KHiXcb zvkEt7y+NN6bPUoor97GNu6+|yOR6XU9ynQCk*#**LLlaxG3SV7Ld%CoZ`dbpJ|K*c z>38GCja#>F`8on~tWm4eYCWsbZr{E8`u_g@&Mv-WE3Osmt^K%>rps3VudUP7kH>gp zii%X1HBkw9ax`6Zn81*&6bEE79gGHqW~UQaC-l&49E0|E_Ylsee&gUqxmq4ghdO$x z-z1VlFB%R8x)X@^tBV(UBUCREi&Dag)@?WB$gnXiWy1i9$%bJKr0EipT$XIV4+b$K z|Mk~(6BYNV-M%E`@6(_D#791I?e~yA^O=93b;@5t+AIzSLzdr4g^9VzNrhH(PGC(8 z;LK<t_8;-Rz5RL}cL>eVnmOe=rPX4wTG%XWw9-*=VMkUR4O?}sSFFRa(yBS}iRg{~ zaMbUQ*al)b7R0tOrJvLd(Ox9X-u=J+3qO22(|hB=@BPv*eElNcP1Q0$tJ!FEl?_B8 zMUIY(?|R=0^A|-94vL@u-EVa@e`cH0*;E%0XOn)9lg!0%z#Q3VG^?#vlgeoi<DOG3 z|KePi3fcf@Bb}(R%qdD0dfrX88{5pb*<>~zj=Sw{`=X5*Df^Ru=Fep{2R`xfUqUmE z92{I^8clrfSi1B^4`L(sedySeG)=&E3=&MQ4N6ecGz0^1(!Z!mXV8h2vhMuDJY;|| z>DbKh;Pq81xuWDDM0UaRiJ6A=ONEUJyO%~I`&LvScn-2@>Bqf%F<1)$LUnO#Qw}kN zVAG_LL6JJ^_Vr`V@i93Krs-sJg!4Tbo}C`!X=5qIfG#hUD=>7s{mE?e^!)rDE6&LY zvk`%eEUXd|qdL`?3)lQ*TF;?o1e{cpmymKDfhS5R?l2c&Ld3sIa4E+f$tXI(D47o* ziWU2#L0Kb9&yi6B87cOWEVhINBe>LR{x`a>y9#UTT?vM=Bi72T046TuA?;cZOLH@0 zWP6#&+}*42A;QTew37KSPnVdv=AM#H=EHSB!b;|cm05`>nAgWJWhKa64io=6`U1@G z=m>uOh2`ge8=DuW=d7IlL63ulE~#&_+LmwZ@7Ei3R?*=|7Yp@%iq;4D<ov58JO{Q` zjK8d^vseUik-cqc=|+Lj0WW}6OFQ_+CN4Ii-p1<no_gvjcCzPRc!7m_tJV7Am%fN} zq;)%8Jsejo9v>g~y4}41bTo|G77ao&fnk;+Xhp;f`EWt`1e&nSpO3s%SdhO~&-n^L z+{A}t9Z#Y=l9JkCV^+qtD5sjF?Pi8WXm?l*WG)B?959eZKc-wHgT&)VO0L5jGAv*n zKUJfTbBPlY2hnKJL%WQw@t<wbiy$|P1telFGoMA=l6{FG1PZQ#iG^J-J8?1Taj`<R zswY_OGB8JQZgtZkPIc_*6h*vFDf8Q$6d_4PNo|89c*`8%X0wqA4!ANxcd&^m0-ZR3 zhh#_)GjP&z!^yOuCpbx#lK_fgq9YXaz;#w)GbJTCw7~{*;>3a&j-&xab<D+*YdVzF z7E@GsF4<uoiQ>q*c6kjo#GOOFiiO;i1yU9f)C=A#N}h88&Px0w0TL43(wwD-G3{q6 z!{-CBH5-l5aCH0j!PeGRJVT_f1lQ~J;b4Rl2)^=_uiyYb|NQeeZ{B1OV`_#qqeWsj zH*i5t&(BWJ^o3`-#Xaas#SlnIpxTub9bHg~88!D_%z&xo;y|&&aK_ZiIxZiAXo!%A zk@A9@I$f3OYL=9d4zz-O2nU$jArf}m9oNMG>vlUdoKl#grQiM?`Svf~pxj@8_chQD zBt(0uNn$ArpumqAV}#OuI_2{RfhNF<Ukt0-9(Ne<F(}QJjt={Kx{S@%c=O<(Qm@FN znMj}>qsCc9+{PwuA4>?%ojhy#ctfg=o1=bbQUfxy%GyqxNTPe<kc_XD$$I#oFhay$ zBynnXcDC8{w|BOYytlWDfj{tp9}TN!_~3{B)qnaszrq0kM|3*XgUvXU=#SZ1+Gr~U zS^NkMgu7C}X@GdxCwn3z%&v=;Xdq+i3W=5jS$C=zv-K>zo@*OU^kO&$p+dhUu8#`R zm4NPz_R07m643moKJ+s`<9B+6li&IHr@l6fkA!Q;ZOAw<Q!Sd4AI6!^+U?f6-~a5~ z18zLKb^4p1dw|k9Kk2qIHQ`+95#)LebJ65Zr(3VqnMad&<ro=6IET@>Cuhg%JDsEG zZjEAAD;$0p7$tOksZyeo2cto)QM-BT<_AA~&D6jAv0u=g;+PAlkWoWbfc|n~<EQz^ zb+e(f%V3j?^*WG)CE=kI6WL-(A`(lKikmDG`srX_=+&c23>{p4xvqt9>q=xYW{UCl zaNG(|yVPsy-&(Co5^i;1T>A?1s^8+;m;YdgrZ>l1%~lyZl_}R~RGZaGRd;~VU}K7J zPP=I|)zKWhVO-^l%l3oA!`JWLJ3qfbD7M6e=r7~M9SL2ro`(<lv&E!bj7%cZKDXYc zh>_<p#YpsgQcb?bwFpUBkTWk}dOlo(Y~5RiL<h3;92xaGodJ`@u4AG324z?CW75aQ zTK!jobs&oc+z^nZm$0r~>yQ^^$p%S85y^*OrG3CdvhuJH5K}L!Js-XyzKtT+kSjv* zgom^%A4y60^OQtihc{$cK%Sp?2G+579cD1>YhNDpIhk;((KY(E4&1Cgtng+1(m|2E zP`ArsB|%#Z&WftVDFDU9_*d)dIJWiJ7O9cmC%`6J(g;~@S<2XiSRQe?*(i01ZZvE( z>iuE=iGzb?qs|6;_wMWLfLmLw!@~zn&Jc|{t7SQ^Nw(XUN5{uF>ZwI;o#6pSWFeGt zfjs>oNWHiqCul412IAIZo#aKjR{h7oLsSKM;SOUTkM7gyK<6JU36k9wu|^-H8BS_Y z1Q2D4b1fW@mFOva2;Puk0T1CP%emGtC4okEAknoUu0kqewnTBk$PtLUy_^{wf#NF6 zz~RPmvS26li&}BS0@|bf9awmnsvJ>tzzDAsBGnP$Oya(?96&83!CU13Uz=TqD{!1D zQ8v{L^0}rs7oznx$jyiOh)X33VTvd_A~f3r*9Jm<%5nr)4&DcB<|G$R6oyXR$hZTh zXNh?dB+Vh_!-s?7S?m!?Ig26*iTH42-1EA!#1fLNoFszqB!68+aK>=F>S99VAdOs{ z2fr%|ku@8@*=#mRdZa>Ok71Y+w;U>p-pEF+;kZNV=14xCPVJ^3!G0qV_YOpANr=)b z;Ntlj2~jHkG>2U_xU?=<8WFZhsxt#wei4Wyla^-US5Tb67S7d`_h{JvR6QFwGMd&h zL4YF2p=bCbiKB;Y@YG@hMiLHNrCh2K@>i|YV4yBrl7jVm{r2tK;|YH55Z9F=m_hf@ z!dB=UY=fTm{mXt|KT3?k+dC~9K^84?yQtc#5{Hg_xqLBf2&>gPlF<-vPTvNe71`+d zLt2;zYjk1n_uCsA<H4ZwU;Y<=Rp!fKIw?-ZSlf%8Or*w7^`I~IMk4(Qffng{fm~R< z1dB2c9z0--Apy1BaI+~_9|6uDK#Gf66&yvqgRS??vqsUaOn2S0)B`zU!Z0+ND(FGr zu0|i4QGEB0|KR-HUvTo3&!1|{3gjXXe&}W<Le*GoHoN<WUwRNFjCX(VL$~-xhVeZC zl+(jGoNHR;Qe`-pUYxh-FJ0q^AAf>R&k7ZAg9m7fkLFLPP@{f|Xo4uc7(<icWUw*C z=p9!PHC}-xt5AHxz?QL+21#s4NSsz+4VtE6F_%**XHf-^S>u%xB9uZ6&W@d~e&35T zCDltl#bjyXg{mHIs_F#_-(`*Y9s^IcBf&%!FR2zaPYu!QyR@CSixi3)7&2itmkBkn zM?=jKG>zXs>ztikoSd8;ADvWcbwpBdtj9!XIab#v#UALl!B62F4j3wGDLP;x#iFi! z=*UVWo_x3rvCe_g3z3H)E58J?*2y7hN<Mt65VBVw%U(jJ?%V<y_gkvcV<FRK30d}A zfvkn|Hab2Zu8T0wGLlMG4<w?KU?IK|Sv5;YS&pReJB_GQa5B?=O}p~MM}&l~LaGs% zllcxfhxlZ2et!P-uYdguU--h8zx>r#UwsvKn01e(gM#cB-g;O@LU+M(kN{E3OYE2w zA%r=BRgv9+T$rhab(O`<@TEgS$G5h&_V@P(@jM-+SkGU2>7^h4@gINx``=IG10VPR z440ReR{QKsFW}t1b$})dLo46LWn@gN?7t3)KObhrmY@P}1)@&D$xM2{l!aVJ9v3c{ z58a!9B=YGm!f!)9os#;+6odc<1EYezqZ1(_pUsrsH_w}gYg|T_y&hICfk6ncgU1^Y zQ!?%)xKvhIz?3X|3CJ`9Aeohk6S67hNl6AjQ<X`<$rhtQgqh<9A@MvX5%eUU5W)nQ zv)G%)wL8GBBh}=Hv(g}-%bn|_#|JGzU5KejVu0d^B_tmBoy-#nVIxdda6w@Cd5{GX z-AOp<W0WL<1d!-v19>7L67s^Kq%e;}aRebLo{uEqz!bxDBKfRDv^2w%;L0=viIV5c z!%Z+JFdJds4wh#6aNygLfp89)9Ypa3nA^8*9k88@ILotDY;5jqZzIpcQI97M1~+fs zL=-DNGO;#9LMUY2zkmPU-TU}2k~?33La9uvlmx^hDLPvY3@jonB_xqde0zJFsREK) zXqoo1+@gFKQU%wQ!nhx$Gxv2CUBQJ!ggJR|pjLA<M}<aB^WyaMlr8Gco!9pE_ICGn zc6WD+g-sfJd3k}ASWK{()|AN<rwqMVYM^ZBPA`9S3f`$d_^v8~IOCL0-MYiWDPE7V z>h%bkh98U%2>;ESH#TN+$Z?2o9NgI7+q-OE!bvH)c)BTD;Ex_tk4ORi0&O)eZ{vr@ z^=aG@eH@7D)V*N@w;Z0>wPihuyVvlB#*_G3)6`~^hWuM9m*64N?Y3+6N~hDtGQD00 zx9Ni){7HBce(;C>^l$y<uju}(`YwzuJv1ic!d_{XuCWKK62SXK8T!|ohqF+?SLgW; zIq2kG#IU%Vh(<+9m2t&t{8z2i%CcpcC@t}nhZNG(@Y(G4`~S>OU)}!Q*m(7K|NiIh zU_heT*$8lyiA+xiM%t9-_qN{o!I$-UPowc%>-dwOJ<@I5!tTyClwJ>~u``UP9xyOM z`rUrqXULxYrU@vGL3a1|>a{9eI37*9`iM81ldhVuBj9M#dMrTKb8;dCKk-x79)bSV zkN;yr+DJ&#K#IsLvHDSp=9_M7L@Q#{U57=%#;5>rx?YNwv9qp<V{>{10eaIJ=UszV zE<E#q|K<NrC#(}g`XiQ+V2z2UzhZ%7B#ojjIQ5i+>g4~KKg1qvGGk~%E<IS(qswZR z6h^xkFVjx@auC0^Ec&cCp3J)4Uc1x%#y7sDYYh{P8HAy-cKh5{XK7tNbgNflfk!IM zpW|9ap2rj;(ep`3jenMr_~)D%v_3d8hvQaq6|(j&!^J_C4v@&G3-s&Bgmv|<=Ks#$ z0bW+y$kIzl<KYpJ=g&k3GSXauL|NZ2SK}&$D-q(e^Nhvj!#9Kq2OOs+(;pSNS}ezS zync@c=CjtZCA=ZS0^naR!f<0dhB{^~8V<1_)0WMPMfJwPO<e{ov5}2>x~M&_l*&!L z-o=_6CH1Gi_9}$^X#$PrPhY`LyB1shgoP<C)UjqEQhRq?Vq}No0L)?=Z=Dcl{V#EZ zp!#Z!J%vNXjT`La`^Y~#Jw-$IGjzZi@To@i#*(+(G*qGTQ0W?$IUf-eG#p2i=?gH! zw}B+t$#sZrH?z5!AKtEYbnEZjd>9`|QC9SidJ4KJtHEBk3SI}6YtQcs<R*qhHzm>6 zVI9L87F>pnNkn!GO9Bl@J=Uk|-Gs!+Vnk_sUjr93OrePBP6FbHGJ;Vs-3E^vDVgyt zGA`^lNupA}Kj7eZd7-;&2<QAuY4jq?np2jeDRT$@RJ-dU3Es*(z#vP_n@Z?eXJTSV zxlX#Q)yh-y2oqg(jFyt{8Jt{ziAjzNT0&wlpgV$rbR%Q_(5!{C#N_#%MF<v%BwZxf zuM}|j5LjB4n71WMtU_W)1rz1rFu$>o%)`tG3<GC<huut13<+dmI!_Eh#OUa|<Z>Pe zVPg>o(D6?gtT=?e*hv;=W#~wT6A(cTSzzu(WKcT;#H|ToLL{?JWQN?nefxzMUU>W4 z-~P^bzVlu0de@6DzW9!Jyo2P^Pe0v?-%<_$T0y10{;P4DLW4MPUHQ<t#FKGAj4RVK zPXHf^q=yhQ5N5Llr)&a+Tnm8{It)-kUbJ+|CYp^yLt=H-M{>3*X;%AQ@l0RMVF!#* zkAFY&%rjU(KT6zeS|IjE6WsxpBSQmeq+A8E;-`ZLIK9<sxzViQqr$<$a&mGaMdA{g zRRw5*9IBu$tATtNI644ohhk3XiD7%YRjHKNs_E<P?Ja2WrC(j4SOETB{HumgmU;mq zNkX+)sz#3c8W2Y^EhUb6wmD^KPMj<-igchXCdKObIYqsss*h|V3i*DW1pkxv1)IE9 zfDl@WU(JxD76cUz-usT+?ca@!2S@j_Yj6}q8vJOIEM_L4uKDsGd^JlM-~I0I&I+EL zoiQ)qDwnJL#pjN7OP{6}X4&-``XL_o9Z$yn$q=u%*X_0kLzTjbuhcN8uJ540cs#tg z(6tph-JdjfeF-)irU|h&xCUF&*`e)BNRkjaVQ*a`p~(<wCZ-1LF@%-?$bzR*)}u-! zk;F(VFtc@WrrD@(6$-U#rCF&lDp(dYmL}7U@Z|NAOSYcn5HjK-p~EAVV4%vFAnpdo zO<+OOIfk_Uu!-KPh}}}3c5m+NZ0+ssz{ZhstF_l?ZcSzz_YaT0_KjD*`qi&@Iz8(2 zm_l0=05(FhMm}7JWlloF%>m-e!Gp&U#}j1<**d%usZ@x$lH(-EXRX0QvR1<amyu;J z!4?2cX58!euYLdXQSjLMXWA?w%YG}6weWghq`|NN7g>h0@?kz{Bw~s$BddN1`K%O= z65m<4BH*Nz2PwXixC|A39Hbh7C1{1wuK{Q44_+$^+S%FpE3drr2Y>K|Pk!=~pZnbB zj}A{*oNw$O;E1xc7B+QmF}wt^CONcBfJ|*9Ik+O~)e0G#3k#GZfC#0i8XaKc9OV^^ zD%c|sPSr2H^b$v-_q^vl?|%2YS+CF;1{UXg_aB57SNn1TG950!oFK6oPOd~&Ac`zR zmJuc10%YPIN6&8q7MMcd4y9f~@0et{`yLBPrjr)v0g(1n#Cj)X<2KvBd?X8lq%%N6 znvbd|Y@L%eR>Gx_mS9Sjy@Z9_tV}3lLpg4^N3a!!Vwwb_U^;R<(JT<FdMZT?YZZ8t zC~mcM&Zc^&f$OvC21N9*a_DMx6U+}!mR>^Qw{SNp&rjTdo|vN^!AYt%kCQ2ap72;b zl0NFu$H{OIErcQ@Lxx~F5jcV4rl;^Bk-Vq{z+hzQ098Oq&4CiyslAQ|m*8Bp<@rs_ zbLL?>Ar+Ydb6&WU76nB=S2CXu%!tT}QnOjDT7B-BXY|tMY_{Fn3OA%sEmucuFryKC zy-xS}=bmF?vF>Akq#+hjjQ9RvaC&xj+3vJ2+iV$higP78>Ls3%ASG*PQYhZIvH#MG zFTU{nvo~+--`L-~b#Sv$uMyeVMvcv0SDz=IjC7F|;ciz7^T`xRNrnmakV+KWBf4HO z{0)5U?VT-jX5tNc19({0FcO>D-rnA9L%(&5tJ2mtk}rwF$Ykzej^1FR??2D7pUjWj zztI(PahXXtBXpgNJJYo{8~}Wi&BCNyDbyPk`FrI;y;f~B>o30a63!Z4(ALgYtzJXd z{r$b+V5HyL)ps~HQI2(DL$`kicz?JKGd*Rh+jBUG^pPfle&V$`on>~mk<o@MI@<>Y zR3Suv7<4&%qloi}mbhXJix@Y$9m&9LUtS=HCNmPwPEV<kihlQ>{Koq~aP3oAzxk<O z#*9;aRE*ZEsVE<vi@y3C6d(x?V+N$SO2uLa%tIJ2J44p{t{Q+iMjKkSH}$MJO2v2E z^yP2<)EqptjkqPNYIK)!v#f`8D>Q<5saU@CzMuYqr}Mvg{>{(+>K~rPN4cm0!6<@p z*v3!*sH<jU+QIB7l}r2Y%zhBqxVd@!sn6ZTd>5DJl&v!?YE@i1IlDs~-AS>44K?8W zk}z@*iE)ObVNc&q!!w+faOTzbH53>P`*BxakJ+Qi?(R;bQKy+7{js0QstkPmWB*7- zi8*f5QAC!QZyQihp2-NH(7#Y{USS9Ui*RuS!sbpP#148)pMj{`tr#5p$f5;(dfgAt z>rHRXK)v=KS8C%+<LV~e{@0kK(`kFHT7yPoH5D`>XPC28Dap1P6PhWZ27Rg)TwYwF za}3O(-mD+?nPH>xu-<6Y>P>d?L4S1k;PBPgUcY<y-r4yjWhjLzm?UN&DH@^wQ9Q(7 zdj~jo+vnO}%vq_TFh-!I$ZndtN;`Cxasx!5M<cROnCGSlqsfs4U}Ts=OblHiibU-T zf6N58Z|QGdY89kwAWIwh;-PugiUqbg7$KIh9Il3}Lhd8}sX&B}fh(N>nxwxuF&|>O z6win2pqZ7*=7cj<G~zT$G*leIW6oumek~0C1yF_ITp}yOhhTwO<75?9Q?JV>p0H9| zz|xb&a)237ig-T!Hn6TB{o=?q#W+W?K~^j58djj!?{fxWkN)zPzj}0hIMnY5>c%e% z?sTH(S6SvlS%F1Ke{ofv`99a2|09gL;v%jdP0{+cF^dOa7*p}-1HInD;)$mf&$#GG zpBYC4HjXjd8h`pRcCFU6diAL%pLpSg=MnL>uYc{;Z+#P?J3HI^`@5`ks%hRXhjUGY zg=Dfr9%_p<UdEhmhJ|n$$+(W>Y`q$(R?4O@AISqfSq<Z6x>^EL+;L}rh|ix;V(Bla zE0Aw;zG{wAn!-6VvVzgMEA1vQ1XckFNeH00Bk>gv20;uF282u`zGx2rs6Z}Muo6hh zV%Kq1(RF0mtB@ELbOt1KXb1!^d16=wobXe-6$nW}h`FkrxOq4X5c=c*9nOp)TpQ>B z8ey~9+S=Nx)%5!m?C@gJYj@Izsl;}V0N5ynD9a(~I3Y+$@Rr>H&i-A3s|3WUPsf>n zyrrC$wkdEa;8F?Z1Z0KgSrId@1EmsNoPt^2b)Z<%4K^HLJQ;sjZzYl(m>mJ3*J}Ce z5K0MI`a6s_tjG**h|L??tu19Xfc4_AnZ5CXPwSg<?q&RAMD)5{d<{y$fH&BUUj`<Z zf)s~NMTqL@+2BhUkcRxIN65z$7Sux&5)e!6ySuw|VuK@ZO)ferwOXxf&bB@*v;tNp zA=OI+ZBrah%PDNi8^l_Y3G`hs8p4LvM}<nILhkwbx$g4y^-ZjLU2g*0a{kBG!z{Y# zF=N4Hpz1+l{bfgLDw3~TEKTqlaFP61trh%Ns~7QsYxOdJG#Sgc+wIfSQ`BL~A0MBz zFFVl}C8h<gF1{1{H;ToOAJQ!9Z+9+EPEIZ^&QYe`sLEZR!>tCyQCLr&#HX#1K&zR~ zfVyZkvm68Ct5+&GDcC_xli3SW3<)e@^c#LU9!%W8yoR6q`TvS#Z#0l%v>ZxoYjU%x z3sFRDH?pKz=tEl=PK+EZi6$OYXs9-h`tcgDPTuhdf<BB?)Q?Bukm`OZYFmGGTP!t1 zoRqEPRO@Zh(P)OXcK2?EnsXfAKMFOd4h1}J>Bpp@VX>vc(F3^ic=>z2D{fh1YK%kE z&Q33mj!qDR3fnt-^?DP984`M(6|tx?8*gq*>$P&NBF~ahfr4b6o}WE<@Bkf98&Rl_ z4oGI;z4qE`S#@(@7K&giv@#%~Fcbq#2xZ)8TH+@ToaKJkfG?NXkPu=z3P5p^sD_+e z`pwaB-0zLLy&->;D3<FRg~~)9{icU$Ns+&(Ftb~zLv7SNsMgBaoML1Q^`-aCf_~>f zZxriUiGaSHrUMGt+HU!;wZ+h5QWPpx4aiQXcYb#9;QryOuiyRFo!5^JPsWp3qtRlH zaH5S~&Ystxb-<b!ImNDeb|vx*YELBd;Q|&a`nIu7j_LXEt-?xa53gdu0&lH8kBgPv zv6A>^kZ&V#Ko!gIz*`A3IFdqRUHsdC^~{I=60lHFYC^uHZ?au)2;>9Sl5y--UIcvZ zhR!O=YWCp%(LeiVzx!*y`iXz?ncw-^*S>af-qv0hFDn^vBFY}YIvcXC0t9MN3wTqD zs&qe)Bg+2%{*4<qIKXfUedd{GSmj{jBy;oTO_o`g;w*viANYYE_}QQR*?;@r{<mR6 zPO8*!JgUuH0+1p`p2u)29*(^56t0B0-y$qXdlWq%3o8Y(lhP>|johr8ukY-S2#Taq zwv6p>fhJN5eNA=1od4q@-%ONbl=_qfh<J`<*-KbxtmAos3!v=)gTO3H&5t53ZaRR| zk;F*^qd{l<bM!(h;!sS4fe5oEL<$hU6DY=GjTuO%%IHhX#GEHd7TUO*$%0M`O?N4h zv<FJcf(Qj9nPeq;G8xIl;0RenU^bw*7GTK~Btl<uXvS)+J7hsbH*#5G+|yPGY2-o& zL|iYS=~QGQ$3E#13b+>20dZ%Ue<5NJR|V0=e9{qfrieqsZGnRFaU9K_seqD42+Py} zUW<uP3c#NXWt{<WD5k?nMHZWqy8Z@DS8AZh?Da~efvdUIy12Nwb@OJw*Q?iS!(Lza zw(2zw!C(H;mu?;0>a^RndYyCs+4(ufM`vo$L#SPSfeCP+zklyRr`<s?mAYPd01-Et zj&l=80(fw_TCL{(jeRx@{2Ed8yD@4YYOvj);pad91?YO=kOQ|bszq~XCm}G!=0m7= zjIalT3LY_|PF$xo*G71~G6eh9jhp)s-`v^RnT&L;e>@%?9v<TTe*gD>KcX%#FPIl6 zC&!oiC2sX~`1}_=J)ca!ph;n-H)%0Fb-^&fp{P{Rgx;Cp&o`S@CJLkU=FR58!QSp} z3qRqqeK8r2^n<Zde|qQ69jsGtG`CyZ<w}`FtBU8XXHaYP8op^^G-QygNVQs~|8Nhg z6&SOJTV_+-q|s~x8>-=$-PT5bPikth!)dpcEG$e?mM9g*lTokVjSF&`^?h6)ijO9E z=JZ0m<h;>pGzY!*KmYBIz5j!MMn;_D*M9ZC$F-(U7|tvfbOO!^7AMJQYseWY`8fhk z8<WwvbJ<2|EM6)UX}-!t2hfEmgI1MFRo9AjfnN_pbL2o<R!sans6<h3JRO&c<+Jk( zYNC5-Aazx%v}o48?6#U)bogxcJwNp4-gE5<=>DD0{r)%GG1+M*!<f2hvhAbyzx11j z+0#=*Mtkpm-?MsHCgJ2O|K!e41&PPN!WYzXhmm@nE)KA)S(2yA*^Hr7E)|$b+gn>F z;PkvuEYY9zQMppt-QDi?m@lfdQY}|&`kFKX34ijZ{uiojj$inPf1mCEH}>^Q-Aq+F zj(vjOA(!oqvlrSD$54c*N0MRey_v=WnhA(_Y`B@ug>GvcpPUSIp_cw*2I;4eP<XRY z#MNZksy7-tyF08EEF*aK>aS9HI+ObymFhHr-I!Jkq-nf?tYqvF3=e#CCOv)06r+oa zh0;VnPN+WRgo(W;li}I<@#W<?Hu1O~PYcYl!=vNZ@7_N;I_}_$qaH&E5t{4XSqXGa zJ`6yQc)nkOTvhMP9HgFp22=<++2R1qU}U7Z8S}_Eg2&+k&<Mqr|BxkdUNIDpK}=R| z>rAjHKo#iexU(Rbo&bZ}0?cWcLf5+>krW5{A{i-wT}&rKhK|*hKMPbC1zalrzml1U znU@jPaN8g059uluu+9!O%;w6wT_Il6fn;I}T?Dd7nr=AhQXs`)MncAvtTBg0EhE`B zOV8nTPju@LTOo23Cv=%qibzhSJj`QegBpQzA01a!N0?wySt4g8tDT1#ykI&G(fSZl z#KboV%QRA@fE9|gzB-@}%=-FZQAdSBL4Ieye|&WOh0p)t7r*$$$#mnXr=H}T%Cd>B z?3?;M-d^|O^1NIs9^5!UV?@>Kb=D7ds6nr%aX#JPh@xksHrdqlYA}*%EUlxa*t?3J zz|dLJJKYY-p$+RZ%N=W-#Li|MoX}A}dbGL8QD;}lVsFsLceZcL)_ibqaC&;mN=}mE zZfvwt-NE+P@9SfniKwOq646%5+lM8cFcj1uEu!rZ*^XhOZ}dkWMG+|O_Vnj`SLKL_ zS3G+Bhe%dqiX{D^7^a6Dv8CJ~W@{P<u23lu2db=5DFn1S@fa%12}frby#|~pL|}Ft zdWsm@y>pcs<~K3eulP+h(J(#8*XX8bh0nn}gxDwXfG8nR@n8_OEdDXQq6a7v4DiOu zwq9#!q{Ur8hAu#PMhhWeU?h-?wp~>Rh)0Vv`=fxTt?8Da0s$z5W}_k^CT5aDNWEG` z0ufFE^}0SHOTN{M^NTM1GmOz0{&I!mhwBt9kPtv6q;@J|!V<?@W~Th_{_5g)Sie0K zx3=U!8W}BsTGqx^AOs|#JMJPNC0)=&TLF-@5HS*e9(kgLBnl=V#Kahsc}o&=;Iv>% zjA&KONf9Fzch%A|r{@Bqgg_}5G+fpU3z0llvgPARCP|pBvq!%ffb<I_%0h$?IfPCU zhuLz1OK`4{k*>p<Fqy=mClB@HtTd4cr>xE#qn~;DDR>(3<RlT+Z`S?Ovon@vcsQUx z_0&@|V=KM@M5h3H1Te%;PEU@GPlkOwD5+`<qgetoAt{#H0)03b(5q|%PdssZcXtP; zZc|R99x)=H+L<jJe9>(()~zj8EEfbJBLhY95ml2>%ofBrF&k1^9}uqGxUtW^*ladX zs#>jVHMS6pe}zZaZeKqC{PS$<D32S8tKVr~#5C5;!%n9?)Lp*mNItN(J4Pan=Fqhv z2Y932D7UsMjaH@6sI^*+TD^jU)7q-l8k+WUH8=G0LQg&U)RRv>`QX7JGEq#IF!dBG zO<=DoAKpJik8Y<s81@)GI3t<_<;~#`SC)ld7LEoQIE;8K*^BW?&wV+EbSo655=~$w zg2EuuppXMOwxlo*dxkDp(5*C$HX#7-1`~}(-Py+I10VjG5TD`0Kk{dO_n&{FipS5G z8S7_TA>x|XD%J5o7voV9L4?#u77@SKO(aI2KwPJ1=`4oHbfQBA|HWxCgfku(8%!e9 z*NtmTRI4}n!zL)sQX4L}TvH+ve&f4;_<hgk9%0_tc=ezB(&z5bG*uV#kp&r3u+E}S zj9gC$=|gx?fAK>v>*LRJG`rvY*uQvnVC6{@i6cdY!Bef*V;C^A@I42k$#53m)1vj4 z=NCP_;@iA=aI4j9`L}!+X02AU633~yMtk+@%TN5|H4FdB$NzEaL>lkuX=AzweJcHf zNCXfe3WZ$Qh?pMove(z0<<OB@4NEljqC~k?D(mTP{mnMxr#|#6z8o3PFE2Q{p-ZFL z>~-57CZUE7L-d8+U>Fz!+3<^{n;7CTkXjnIe*vqycT+w0q2C*p$_%3Oi<A5Jk4B@7 zqvJCo$HymFOrt1n8snZPwXYsy)AE*W2P=W-#V`&)SE3#bE}M_6Lp&w-I9L)$75VB? z-0))i=vdcM4~&$%vc`OTEwq@dz`BCE7VtQ*hL)BO(Vr}XWCBUD^0k`*N*>O72p)we zj|DXn7~fJcXJ^C7gp3OPG3$L?sESoKVTutZhI|OjpAVh2+%90s0v?yXfDkNBhFeYz zf=mGx8J0L!9@ZAZ@o2(odwP2IwXc1hMUlmbB^o+A6zA(kt9gEY!TviMa=_5%3|WX+ zy^tfPH#P#Kd8OqaRv{KM6hMMU7l0ziGA=B#)H3g_jP5zaBcm__9b)530Yr3r{q?&$ zJ3F|?$oI2IUOe-Imbh0@%35Yr7|maAMgyI#wu#Pli=5083B%u9fyB0i>}b6ZTG|S{ z(R!7aBP_{r7B+Em0jb=hBJCYHtW_Sok$lRcVS@F~3(V+CaiGK+^N_P3#3B2<M`pw| zW=MiZv=97-g%epB<^csDpCU21vJ;DQOYwFg5g2^KDSm50KZV4siRUMLH$|nGRWYu! zp&k?g{Tc8fH52PBBLCih@E@4+CXr2AL%L=MCS5!LuG^86Ovq#eoNFNzheFasGq?)J zfyzgg!<0o4KoU77!hj*L8fywxV`=cok1QCVtDonql8FEv2qkeYoLmcEiD-J(c0imW z&_lpm07T^#NO2;Ly9oxAXoQfJpCc(rBwsMgo;TkhsaAz0^PwY-yOc$N@o>bkoq3?A zQ8`6&0*xQ7)}6ihQ6JScRga(pKA-QyTOfYlXrdc*K&=WOJStR=Fq-MFM2wmR;w<-m zs#Q0e^nG7lQ)RE<4+WSVqrq@@dxw3lUe$9ES;-utl1yfbfY8GHg!vAoi*<R}!zpWi z++g&BB7=dxP=`{4mjNPV!$fYlzL)TL1ja>#OpaVKZFjnihyT@RmiKS8ZXWF1xVg2v zSKHfHd~d(mYO(Fo1+p;)J~=<Ve{@LIjYjLnje}NeyHcyy8g+JNbj2RD9ac789q)-x zMpy=IQ3kDW1}DSuY&_kVkf-K{CTcic;{gLmx+5@AVo=MKz<U|%g-U($GUD+{75t3H zUT=VR!y$n`^}b$X-uPR8^Dj_5kLW|~@$*Xcb}_}tl9e(CNq_-n7DV{T4TE3(t^k~j zC5iwQnRgtT>lISm@M48ORk5i{V`{{>KcYJZgo9zPk4-QIov_Jra`Wc3+rJwd$A@>3 zj2a#)L`YJ5sHV57<#&g1l$=g0OFPoL-u-=K;=A(4vZULQ(}^y9u&8bn@ys?@_t8&Z z;nEM-BA?Ex)pZ@DS}DyYqh7DeaKm8R+gn6NOeZ`(>=b`^cq5cpK(SENMpDOCC>GYx z4uNnoZAp>_aa!k&P}#`JM+hlSF3{k(S`hGd%bNwg@k?uH)I{&_PNWaLUMw)a*uDmI z(Z;M?t+ckcbSmRKxltMqhTY3{uie4^m~1rYPdH7oq)h1xy}(U8EWfEIBy=gmzICCb zAI8+X(A~~ux7}f!>!+0~RaP4sdwO<pbaHlda(dD3j3!fAwOZpZYZ0<z%%=thh_Co_ zhv!56A8>^5I{>XVkN&53DB{oWR_G&P@#o}<zsCd}y%J<CSinSw#v_?%LA^KpdyAl6 zTv89^b7Olo&m+QRmyu;Jfl7@mJ%@{Ad4WXyBLyqA0PDF@Tb4>K*8#W73rm*$R=~pZ zfarSXAesG<tF0t{lY-WCyS-Pw{>pEE=C?olFFyN+pa0@lzx=gtz4GeidArP3vRPo^ zs#nWf+s#I^#@u6Vs#VHt;+^g#J}Uc-=VUCFEMHR{5qe$L|L&m2uEWWRIjUbvuT|=; zMy*+|AWpv-hZC*GX!z68*6R$%LpF!4ovmk|fA)Lc`#nGSL+^j*JKy>I^UtHIL~m}s z?QL&kb38pgwdrUQYbLo~=WSR+7I_3vP<EMjC}x4eeixa7&1mG~kBFp+%jUzCAZsPE z>@{#Lsjf$F{u{!zV<LwMS@w4lv|<5S#wxfUt*x0EA#C4?9$H^rrpbyu4i*%!5Y-nj z(NzN<_RQd_%|iqoV(JORVdk*m;caFjlqDqB5+pi@!~nD95TQmty7-o$xShKLoCkR* z1c;+FZ~>Bu4iXz6Y0f-73JE3x6BAF+1So(O5?_#GW6^#LO44RcoKbEOsbG=}psYiZ zV}2J0jwfP1k_ViQ<k|9Z&c0U0Nst=268UyzqyWiOmtiIIfSAISK)62LpgLTOs>7v- z)39E`eD2w2pjInoOie^~oawpQYP`aZ<elxEqCcG#dNP7hqY!rskB^TJ50Co&fo^&Q zV1QFc^>{0W;tcBqh>YoGt=_0Nw|BO12CCHxGaaqSrR@3nS-D&~K00OnfAHY2R;%Oo zMc2v>$X{+R@#|pxWHCzUC@DyD##HE5+}+)|b^D-PF5pd)#pclO>HZ#Qw=Z{hciHEN zGp%(ewyXD?nd4|dlks~-crNmhGQn~aiVUi8rM9`VTie-f)%7iH8YFuux5ToAxn|vN zpIy1z9h{$CVz*XvyVcy<!#{4e;%-@)0<-C?TCV7Ka`i?fwNU9mA4Q((wraFUL4d_* zb7QkK+bq##$vDvtwHNynp<B`1{u00o9gX$zCmibl0~K-Nr<o{$42n>Ya{%FR*c<dO z@Pm->!ymeKi}L+H^y8oU<S)^wdbG6^UrWL<9}Ur)T#cjLOaW~3*bm`^rT|*NRM#Cx zef)XM`B)=iL&FT6=pfuNacv?BBNwS_tZ!uFrZMIuTp2Wfio;x_&i!|N<a?jH_5gGL z)!+HuZ*^Q<^a_xb&=6$+dP1S?%3y@gZolh&Z@a$kKKSB4{i?>qd~M7I0~*s7v}Zh^ zTuc#IN@~`u)oe}T&18-r3}aXkP9;Z2he)70;Fr-ERsDYdr~mA~ZsEp1{>T4A^zSC) zlX_u>(<XJ&7PclSP7sl+P0@6K{i6kHV+z5TBO{EkGZIur7R7%p=(!BWb^#sP`{H$R zeI|gWGDMlp$PD|9qDVZ69m@-nA-Hy=js}zAa8%gTPllia#25wYM22X$+a-?ipzFfU zaD4aP>BXhKKEUcUS5;=GnS>!V6CNR|in0u;u@p+RY;DejJR&S1A6bWW+3TuHR2V|T z4CW`|+=OMyTZpJx$kJ~D>x4Y6=)4{BA@l^223dxaE3=G@`j*0C7lfyzYRxe)u!Af( z%g9LIG32XojYdj3YZ-Y{I}V7uRDy|b9*D|f0SgDdW$9W{2r5<WFJ272G&us=?asY> z_qv_VR;yL6R5-DWhJyyjkXnUBUyJiZTi#?mf@gnc7pas|Wl-mDa>a)}*~TT%wMeb_ zJ$6=O^(Opoy0qM6Nw;zY>^f|qtbQEmceZ!8wzkgWwKB49-@eT;18u!F0@WL!QJEU6 zdS@Y?fNr6+uS#n*wwyet<Ip2?Y7vQT0b1Oz!*bSRwVVW3l&a&OJmrc$k1Svfc|B&= z3ZT4!tuoRA9zj03B`h1%bgFO!WEp{_>+KofcO)w_-?ceZgucopNvIJSk3a|eA{Oiu zl7uWBSV$UFVNPRze?J@N*Fjp-BABr)4E4G`a04@R<{IFzMlQ+0pdW`5@vCeA&3&E$ z&`nJEOF#RwuINo7`wBFWqPaE`NfcLU3aS`nnV6EqO;Pz(U1cJmNlxZr9?ap00o`&q zClNtDONQq#O9QJ6aVN6^bDfc65XX+@Nz#_#f+?4X<EF2S<dF*I+46B~l3+SmNCH#x zEdp6y3~NVBq+U2_o#|#a5|5Fm5XPXA(mLSE+u39kW2j2GjKA{i(@(Ql*Q-?y=y+jN zfPYFs<?2Mci9^_mODEeqJA|}uqp->Nrgu&+&X13dM{&B1Is|DDfYXaUby3iu3H`3# z{cE+FdwaW$Mtw6L5aYmItyL~B^;5B@r{_3|>{!J@X)qjVwrEwk>Z5$PgqVkO<Q-tD zu2jmkTJ^?_{U@KgMTBfT&vKzmAylP`v$NBKg9C)<%2QlAWov|Pk?c~#G0h!@Lmp~x zOmWum88-{lT4S@dRc&q6^s1w}iW>F5?$%DGz5b}v?vI9SPG!8U>7-Dh!Ppw_w_2ua zaHWP4KWd*{GHnnMH=+A%z7(ic_33On&TYY!Q`1;{<Nz1q)41y9$jas^4lTxyCg>hM z6nJPRZmNV(R{oBRBy9_YPN%~x!$dIBI%X1)@d$VQL41jM_M4yl2Os|Eza~S>@f)A` z$I;)qQB4saJ*tv$wc`d&ivS@8L>bv8pj<qBJ&linb<WUAgQ_?wI7NEsV}#J~Eagh+ zUESj5bcSCvE0&7VmSv%!cV!r8cKx3HlRy2=>)*iY-TCc*{>nwHxw<&Q*kg<Vs<UqJ zAeS*rL*N>eU-<s-fAN|F-1+Li_}#BhY8-UXI$L2t7`wpe<WwY|cXO&MMQBNp*@iBi z=<R?FKk<Oyj)hOpPbnSG#L>Stk!(dv|LmXrHzJwg7k}{|xUaFG6{bdK5wQ;Bs;2|a zvb5M^1f`=dXe<)UNs=(*p3TAuFO>C4-G*Ld)<F(K>7fSnnoQjUUAm&+XgFk*sOVmI zG*w2|<rlI%)0s~M*w{K2OXa~J-Y<@?4=~y7{Ze(SwS^*d0%m7)U0iey9~>VZp1=C~ zVNbvJD>ca-jdTq(#zsJ6cK)^Jcsyd=0U~<mYN2olsLPSZLMomj>+lBIs}S8Htq=}U z&zce}S6HSz9Fn*SmTzRF0Ci{7fQgQn@`zZ+|9DcuID~l}9Li(?$5WQAml%kc?l8gh zhai<*z`C+Y>;i)m&NVDKO=ly^dj!SaB=S|bMq_Pz=cdSq30dJepsbU#4lcD4h%&Nt zAX~gpI3KdG>pK*&GsmXFvJ|iKR{Guk$<fjA;Zbbb8^<TdtcFiN^Yr22p|1iD2R&S0 zb^sj)$|ZIp_TgcyIbJ$B!{g18r|P|tL1lT8ybb(l%0hQf>sB-(HaF{y2B#ldhr%rH zxY_)%mThnC+zh<<;){OV3}^V(ty@$9Goyl4)N3hm50ZzNC;=XW7EwwYRh+xXN(OW? zA5r_)%*e#EfCUHG!U@;$tHeX$f>*i)f1XHaD0>NO$m>D(tb$Fw0*@d+(=UK6GU^-| zeSvL`b^6<|8TTAeI78XmM&ewj|APFiSWvUr^||k)Db7VQVXM_L9VAZW&U+tVTbTVj zz$BrweKWApnIscxG#VmIeK3cG19o|2dfa;OyOy`g0nT3Z1<?e-8Px4?0nRnD0s(7G zB#9ykk%*b2w2&|8EMR(ykd?GDk>e3bBG|$n6d}-gDhC)qNXib`NN}l?yAr8J;3Du- z%A(#p^4gN53OXJv=<IqE5hS`JNj>6301@~jQ;0%>g_vgn2w`9WtZG;p7H~bLIM)H7 zaEv>hQfsyB*FoVQ#IMERO~HdgEa7Cib_=iT=VJAfRHl&Yir`0{yH8~!3v|0(N!wJG zAB#m#<e&gaB;$NiDV*)LzHkNw1~oVb>T>9a5iJhR#n%Ec+ST|+ChEnvc=Ss`)C*AQ z^z`)N;sOcQnJk+H3an@dPp{X}9v3hD;`>BJ@)oEAGtlkO>2REfxT%YmP^wk&rAxi; zpxy4U6ig?ZB{j6p=$4trdNE1<TZ|K$LxfJ|PjUV1OSaz4H$?inD2GeUmwQjdWkG5n z+J+qI55*Ok9;N(ug%GRmBdpeRRbV*M$C)`IRQ2@fCi-8Tw`I#bW}E%~kS!e74#^0? zZjh1V+5r(K=~HV(6=+2k5tz+J9K=)Eg5LYoLg_xm!9q8d{;58Wr5lR9(YS{vJe|^m zBfKOGfT5<-gB#bqU*JcesXD=?@UVn|3aAkZ8nRfIv9n7i96b4SeE-=6fpiMcn0RJ* zHk`0(k&fPpi#m;JO*a@eW|PriIvEk)YSnhOn!CF@Oc`oqB49etFJ_PhCTK2(A~p_@ zu#h6M&v@)f2Q<#?n#U6s=1GwK0*qe67BH9!MO@PuLHZpheZsjr?00+p%Ss7@_q*-$ zi_6n)ucN#1arlfY32ap5TCK6w+G(}6%O#Co8e#+XIdURIKWjv1#n;8-HD(40aC@0z z#D{~iKB`r$jRqU1$KCsP&ki4)p&-&|i>INR10^+QA$&MoJcWQ#7?AK$iob<$jq8vx z&6NaMdanFij(nvFuG%nVLA^gZuwsUj);Y}=X9014=Mgp&Qqqy6Kt30ulglu}zkFoX z=QK=kGKG#{=VWSA3@4Y7WiKJieq<yi^C4h8VP*Etf>;(eRw5QyT|#BK+AI<Oz2E!2 zU;f39{nOw6?W4m(eVGTJb7RVRgZ)^SlZ%^M9NgolTv&Ms5zAUZXt7Ru<us^~m5mTJ zDB>dxD|4x;M|%M4n5~pC=w%OmjsM`_;JN3Xd*A!shwDobR7EmCRFX`RhPZ5kni|N` zOF+0`9y5b5wy+TYwvmaLBcm=M%U(j3y$V)4AHIditTXSFjQU3pRu4Fd#XKIIW&KTe zGPoWCNpc?Qm_U}!sloi}^?GdIj7&3R8Bu$hAY@rj#xO)?1PmU}F2XEGlL9smcqS30 zpv0uP5(S97CD08PKsDBH0g0Xu6EYcrq&hqZghDcDOx$o%1p<znZic+QteA=U$xld< zLmPHabZ6z|5Ry!Q0Z!+x1UyMMihJd9^3B8g5E}V7i25_+DHL>=Kvo(JHieO8&ymVH z*PJN?QOQ*;CX$O)F)0+En^n<#eTU+L6v2{27@(}tWLXHu{dP~scYBP6)c{tTeWlfE z?d<IMHv?GlS?h1#zWwscFTe1@3nXDE>Y2){rT7CxkaOdve%gm!fl9530cWZr!9<W4 z)`6zc7G#DOkhuX67+PeJY`67uf>xdg!fgTA$c4vxmMa^TDku0twN|RvD~)EAzh<kn zx4&I)Fp4m2e=yKWL5r}@a5(Mv#_|Zd(?MUq<DwT=yQ9sGVz<-R8`p8%k0#3Z##}qC zt!8{s4=1W#sWMU0$ae%z%!Z{4o7!U0DvXhVT-a!%nF#?FAd6CZT{ZrEEYM%HbE}1; zJ{b;r_-y53VJdHEP?$}(w|48bCdOcb+L8%B|2O{Y&{~#{N-?PhmCY4~%v^M9l}88= z%w|)Qv=1DbU(I(${bbCNs&0a7tc&v9!LXy>N0w#jK}K@?0PGU<;KRHtsTcL!HCDq_ zh;5!M9v>aM<P~&Tmx2Mg+>C$zMpLcbm1@0I){SUcG#;+b8sZOE7I7o>u6bc|hWC5> z;AVwEA5S!74Vz!}jEb&+975QT2Ak`45qj48o52y-Y(`5XOi70l8f+wuU@6kgV>M_L z&FW7lxa)(B>1Z|`G441ZVtR%Je?*FLQ`%}EfukP&EvpAarVJY-ipkBLZ<h2I&1Dq0 zM(cpW6hA+^gsa~hblSs{<Mz?vdHZrSo8b5AfCvMew4}mm68W(*xTRO&LqC57&}tzB zi$Ve^_bovFeb-0$qlfA3$N76a(6p5xD>dIRF(IE^;Jl6n_1^IBtpO?}WTZeeE^A$a zvmOgs$t7gjOK_#G9heAGsYFkdKT^o+oUl?)6FsBdsA$mDg7#Q&*@s|(%{3ZH0U~I` z5=aP(=M?KDi%_AU@5-`L4SGZT-fw>Mo4^12zyFC(eB$Kf<iUdnY|!QSSqdaf_5QHV zjjW$_UB1+3_MP-;1hA$VK11+#*>3kZ8gbw(6y)FP6Sjgr2EDnVPpGrUvd(hu5BC@o zu{^TTuvEVDo$vg<@B6+V_<<i_)8}Zkx3`C?)W}j#U0(3jyg6)&Hw0FSuE<UcMwWNI zPxJ9_11?VZCgm){jZL8=Zwctr1jIUg3+1naYXK{h%V5YP-E3hxkq#v*bQjDCLyA8Z zD44|p?nH;nU_iQdR|j0&N#+P35}FE(UXmPW2|b=+rcq=`+!Ayai6#@LA^_)thHnPN zMtouiiFu)+YBpPlnCLick(nJIokbEY9RWl_o)~DPBZOwK*vQW;l_G@3vK(JCpcV{D z#CA8E1v(z=0!2(D;v(>)3=+(+3|9?Y#9%=)F)`#h6R60MJX=0a?TLtd!(9u-Y`}D2 zVm`~Dh)Yo;&9PWRq66fnBs|2Edcg52j#~1O!Wke&tphy4@#uvYp2z!dH0mt3SecMT zx?HUy6gu0+-i>{n)!uNx+Kn9Dl&R=(++L^q`fGPyd+iP$2EG!Y7Z45)rGP&Dzq@_& z=8e6*-QC?C!h?gGw{9K0`(594>-Np<oh^1HJQn(jQq@}J^yD0c>B*g)U3Mwf|9-#g zyTMmY%C$X9UpE~smQ7}+=s{mI!y@G?w5hnizxTwGy6g(IR;!N&qiUSF*^v5!-n-uQ zE|@vZxAd84Jb!&C3&9Lap)7|%m$0xyxmd22D)myWQ7+Xt51u?IRtwXao}R+@9Q22s zi_7yfz0cV0^t-(Q+iMxyR2qfN3g$w_Wm~`gva{8qd)k+mY^QM(8PFAzLUC3u7yOkl z+*S<20vJP`CNrX>ga%fn0s+&ZEhG;Kl9!j4^a8_%fo*-^rM-yoER}g=FS*eWn#~3+ z#dU|RSW?3$(@D96I$C#`hSdDYU;hU``lqkGs`{DF{0cJ5@i}OE3LA2spmij%7Ggba zQ9ykVYfF^NdX3>&&_m2}|KN<Kp_Srjhvt*%7!I6Rx1OBsEsh8q`0eE~y;j17pkwv( zPE3)Fx4-WvzWYYVPdNF~uYK`EXAlj|LJ4gcuKm%7I3cANwUtt(5WjnYI>X_?cYX9v z9Au@9>D_<+vBS+R1YjFkc)lKT!fCX&!kn{`e&b1bv;zBo@rz$U-$uRFXf~NKSPyp{ zx3Je6>TzIsh2?5I2akI=nN5G<Pyac~G=A|H{{d5jKl*;AYXS7T?1L}N$qSd7c^#J< zFqOInC1YBnS~eZ9B#MP@qA&o6t8W7uzi};=&V?fs(jkpM&E86daSokMBt;n{&?u_m z6vsb|A|@F_2esrtkA^f|BS(XYdRe|0x`j%qJeh8cr;}2-Sa0aw2yz%6<I$8}qfNun z`0}!M@BV{(_Z~1u=p!6)UEYXyfT<AWJ%$mjRs}*4M|AFVd;v7p5jWo<n2a?76EQ`S z%#|=(KC%wkqmWBjCqGY>HUX6POmWh=#v9eYh=t+_Ngr1MoV48*w9PXtVKsdnzoz%& zz?xWEK1?f#0nv1ZG)0VsEJqAyJp`%v0@js%h*;=p8UjmB<2lM*srPu+d3?Ao!!;UC znr<vuz{y0!&Ut?5Mw)kzh=od*flNZF7_cRcJe}Q`kWrC#94ril)gA%*e&Kjjujy?R z*3XOcbC#)-<CE!Zy0x|4s5jZ{SY_FXdffq1k)VYYR*qGyLWRO`Fwk-=@hrwVk-Bbp z+-hHRj6FbLb)_z??UEzUneDYd81{PodcFDNlTWnU?bg;-v9$U83(p_iy2&2i(04aj zh}2{x>%$a9{pK9XEWiwohZa|+h!aBAQ;sJ};sJ@`#x4V%EOs3W^Eb(%$&M@lGi9;s zNb(&?NqX0jbqXxt(YUVQZ+$P<o+yiW1o<v*V3CYEM@C;@OIS1Gv1gtQJKNOS;RB{y zT1qZsp;_h!Dd|Y+$3y|aC?MZYa{0{QnPnbMoWxC>O;w~`=h&_%=3=|wytugNbo9%q zWO07sV96YH60t7m#YC-|-|d5eI9Y%3FaKp#^QKYM`<8)>FmE&G42Wnz+o+PdQJqO^ z9`k3W4;AewnocPiN!<Rui2!~B$`+G6)_NB=PnwfZfDP&_YIj+!GxOVSWI34%0vCZo zXddDeCo2hDhTa5}BJtMWjP+~Gl0*;1#6ST?@cb|0WBvAw8e)WM>LHs8WEp{^mEoj$ z(4T@(QW47uc>-Au6Ua3K&GE>iEJ+v7nC3M)4!<jc;;}_-&=_{Q&*N?_&@fKl<z}n( z&Ud}cAv%t$<;GUCP%fe0(eW`${4>u!^V#43{Xg-(@1-Q}A_}mGyK4vi0rkzMvwpA7 zv7Bv!wcV8xG8yCRR<q}yf9{!Qo_Y7X-+lXuo49cM`@5WjZ{6IFXO1cbJ$Wfr(U~2B zeJEP6@y&0(^3893^Z4ipVeM|4gEC$k9ieBG3e1xN(@bL_$^wdn0kZisozQDoSkE*; zj9mVou+yAhoUkV`lV5(<%P1VraBfeAlUA#RUxFIv=Vv=RJM~IsV>;Wvv43=Q^xA8$ zvQaU27{&-^W?;=$vx(`7mEw4FI4+Kh%|dObUfpU88M88iya232`}BG1QiW}g-IF~U zhhjLSu@k8@9kM^(zO`2_VRgK(;`!<2-p+2Vf?r+S*qrtT-SKF^K$hEGES#L2P&>^= z4J<L;h_CgIagZvVP7hzHR;^*5;Q+s-xU;>BSFd+4i{)mcDGy(xePb{jYE{y5In%4j z*b!%v$xtc{MguLb;lL1qf|>h+-q*kKMdl1%97bTweE1{Rey;X|ANtAP_{1;v`nuOw zE>~Nvt<hvssnxJSr`zifhr~-|yeSd!Vaa7jq&`A&yWI};jrD~Q{iv@Ted>-kkZEdB zZ<NYS!cV1;em1w>I6gca4<{Q_<^n!_l~V@Yt-FoGL4SDgo{xU-b>H>y4}aq~zjUUP z3<HJEpj|W<^;qzr5F(ZFK?5*Gu~goe-FnYQ{>1essXKRm|F^$!Ib$gYx)y-zIq1)( z6I@uv9rH`S)})oH%!-BMHW<xr9z0Ph*Ccj?4^OKm!%?@_={0J5<&DPqX&dt&+`7&A z?C9{AqCfSo{Hs}QfnWUC|DX}B7k~>}t)@Rfy}!T5NMHrt+1bW)7>Wr_$h_uk#!Q-1 zvK5#JqlGcge8WOsK%{@HtCV3DG#j<ic*J<_>3BB40_{$hjxJZ&y%;B&Jp3Vy7Gkzp zp+tFo2#)@))#xKv$FQNx^jlCP)`T(QnTs2R+5YbS>DgJo+iTQo9PLg{P8qa&`}>_v z|Ln4T=idFh_wS#z+oRcZFc~u68KOvwg-e^d7eL~e7Y%5VC%hukNox*K&-BR2KyDt$ zF_<GrlfVE)%;4lQEH=T+AWJVnCD3l^uTs@4)+<x8Wjw7Ae{sD)OGdO<Z9!RjGZduz ztb*I^KZ&3({AY3b&=Kb{u3}WI02~P!Dc}uBu`E*{4k@UCpcrUqC9S7J{um?a4;`SJ zlTjBnJSvcPrC&79$ZC&93Q|Fw*p9m4y_OXx1V@rI^G`T$!0#rzy5LdqRevsJ24MO8 zsorG$5R&mn{a6)40J24i!5m72;rthdvwcFBP$@(adPX?z&<yPHSw(ZYBJ2OqLCw6* zFSY%bIOqDqFJ`sFZ56~8Q;dk?zzimlMZ{w%nyod;L?KtemA)Zd0%U1dF$XosDaC%+ zm7||NXiug3Lcg|ReJLP*B>)!eST3{TU0$>wJUHrg2Gw$%KTbwdHkldwg6<V@+8W38 zN9{?)!eln-a1>#`(M7z9<ZEE7QFy$z7}XH6bK~@?Q#fL=n6gO5w<;=CeMbT5`+Em$ zcgLrvn<d>FuGOpK$q*U%z_jDC-KHU1t*u7Ag~2W_+s#^CEufM9RfuT0k~t$pG&7MS zc?vBCuwf<kg6-{XwgWT=vOh}^tdgk{og~U~GnxR!b-8IV#u&-SrJN2IYzV~3ga{?f zu=p1PeZ`-}TCyv0M3v-_lKEz)NW>rZr$eCsvf+Gni_$`X<<KOE*hIrs16G?3uwv`~ zBs5x-wE|PSpv8(DND)I7Qyhjh;?bEb8A-fiGbPLnO?y2N{Yh|aD51f^U%oEu0}@f$ z5qAV|NPsO%%z;@vis0n@kd2&h)+(hUM+=DL`eqv@>~uP}Z$HVA{`BOWF?{334Q7Fy zEFHQg^?FT@f5sQBsf*L}-rgREZDc|uq(+33Mf|OIfDP9{NF4x*lLqm;gQup?L6#3v zi4MgEf?_%p#{qH7l!g>^1B%%eLf5_w(-Wr=IoFWrD|3N{(Hv@O&ekR-I9IFZ92q5w zxZ&#nvqMJ!?M=iK<|BZ3O4^>wpms;hZ)R&{m||1AQJT<Ue^Zo05MOS1`q`)Z15Ukq z`M1`n5gr~L!%7zPFMZ|9xUY-^`q$&01(YP4JuU@4>Z{*+4f&(^P>q#|TBI1>?+Y)y zu(!X{Y&DocOwsLad`Q*{_C=f;Ei{_9S*x>w;fc}J?|+V9)(qJwdXW@UAk|{xLdYmH z@0<`zw4g)(&6_uF-MaPSi*G~cN<|*kY^>KoF9SzMhk7<UUPbQ3?Yj8c8~uz8UI)cn z%{rFC8LT&Jl}5SJEZ1Ar`c9+PYG`%h<jU!S#%UuVRAjPIkRzy1gBLevI7r&gnC6WJ zTT$cot()w)Y=w-nVSl>2v%|8$%+qtS?8dr6#xR><4Vug%f_-q{Q5<FHB{{GK?L%a- zt9eYq$&4dHt-z~{?WQxqh8z{n2e5HeB=j1K?y#Yl=<NKGz%E$WX*H!)JR&h1jXwR! zfA}Lmdd*e)%x`^M&j4$SRgFYKw@il=r_Qu=>P!&d`Cvh$kDvhemh_Q2aZn?v?qjT~ zjTn`2SKipvSDQ)|c3{Ng_YH=4T|<r-lj##n4si3iKl!IW`jMab(I5S(kNn6_eCR_z z_Ms2{=!ZZ2;~)LVPdfbQM}P81KK$bm|A~)$<R^&y$fEZPI^X)|pL(sYuRx(B%6n}@ z`)avLlXYD}cW8CoiZ3a%7ZrAPcG-66ApT=a%r?fc*WrF`7dG_~sk+_+FECm-Z2g`8 z`~N$uYL1Wp$}eaDbBZbz5fRr-HD9oy&FE`VNPro77)^FVu`pq_N*K^7MHUga!pjS6 z%*WxdkH1Su7Bb<iR%#4<-SCKYBLa1erZHP>Y*e(CZiR`SD_3<ri!&2#q{+G^952}8 z{7+}JwpOik<eD<45XBtncKb)T!e{5lXJ?m}9lDPtWE@9MGz^tv>gHf=vqT_x)XaH2 z5g&&9`k%)e7JNjklM@ppLq;+v5Xh1_n3%F$HdeN*km<{Cu0fAw)b9+aB8y#zYfo`U zz+&^?2x}Ypn8@ppho=LP<!~je|1$F<whQLOzY>XUA<QGO0Z-~j2W1~Fd;#V+GE(5% zt9Kb>WE>Ag#vRB=OUSYV$wdAt6`_c6G6C?i91RAnQMw4+?+;k&_V)IlefHVQ^RxIh z2Ayf)WOHWm8xKb;ab;c4)-x|G$a0RyIusRI?c+G3m63nvh+0(LLT8P}8*HN#<;bJo z*U*bI><XJNJkMcipMwRNrzdCUXBU*lS?#nhJ%y7%pv5Evf;=7MtINat0ugvvw*hgs zFkKYL2}z+=_&HMFDG@d_QOS8^-FS#H4?`w47cne0)snD||4o7}BSa<*r!5wq7KcX% z{CS;SJTGLKvJ&2TvqbQtRTz2EAjTUCTmbwFwzUNBQ>Flj1_w5>h>%O@;enDkz_yZ< z6B$plxwEswfs~`s`MK^H^yAk?Juf!&iA@#ElJk*+&nyXZ%bO0~DhD_loo-tS0dv3& zi+q7vA!dmssEP9-;!>952u)&Y5z;~^u*I=i&&aw*DWYcOis!?JAlR>vQRi)0K%QX% zu9{NlW0j!LA|i>Hhf6uv@u>d|v^BF!8Kyr9EPowrf5$C322ys}*mPh~5ZxUqH*7EH z;2t;I%}gABuib9b<Yu$U@tT1P5l&A0j0ZqGNlpl1f@;kfmXow!Xh9|*g3H5{F$0nV zL^G{?87VYX6%Z|-$Q9yhqo$C4qeaMbJ{$<AGNe-xldaqB5<vsn1s!WJOR<2|h!0i4 zPaN1#*pMTBjgx$%RIP4Q%d<vxbGuR9YT?ON%05<W+tkFS9$k^!#7WR6zA(~kie+RR zxU4z$VVT(4+Je8^ZR1K%o=VN*UdAjWsU0=K@5&Y+Ko**_DnX&M$VHBu1CT>;<Uj$k z@*Kn|Qt~@VaXABiizP%XJQSzY#!Sy~F&L;B4-^K<=0zDl_t*YQ%b{2M{jSxvde(u0 zgdT*hf{-kVpmySi81lq#C0!j^mQNOa5uExA7=9%!a|3}2>XX9X5ljcNAu731fC!q< zWO?5M)_2Cz5JweeRISxf8BRS=(;p1l-F|OC&+5mM$CG}ycR^|XPL7YxFV2wWS`vQ# z|L|9`YQjp4OdEmmi5ZzzHj6DrNE}X6$g-UiY)|)s`2ox-RpKxtwQ0z7Hcpd^p-xB} zsTA8+afsvA2g=Y=vdR^PqCTv}P=Sq+Tq@Qom3p<(C>AQ?>1MA#?skT~-iRg^_3@WF zj_%3H*=VTS&aVdU-o1N#e0+I%$z((nO|yn8k@U}lhGemS>984>k!3Fd{g;~nzv;k~ zED_0km;;0SvHt$Yfk&ee4H6iKS@s_ppk5Zs0adfuBjB-^6T%)VkYz6+%l@|N%421F zR}vqNOq(TS*-Loyc78)7Y553X)B%<khk*TpRfuKh{{8!Z@CSeJ$xnXrQ=j_O=RWtj zS6+FgRH^CZjaX4x`@FZZ?h!{I%U!lov0RRa{@6zzUJ{XS9cZ=JaD=dKgUQAue&fA7 zD{Shiyz!{8S!y&|96h$Tcfb3)zx%@<{_qd|&=0-*^2_`C`&K|pu(#<_k+S^h5x4nH z3ZkuV0B=}m&L%?J(U5}ZwzBv`WFmwxS(S+8IQOlBt(QVazN2tk-0y%0Nr+kYBLfRt z6u>gTGPCSQ2BiSSowPFFhCb_nz$}(Ss_wC1ixFW^p&>(Eza7(RF%dXORH`M$8)j*> znto{y9#0b&CvFFUc$h7lIA8z@LG`|+lHVRyKLQO<$Pob1c87?5VQ?YK4y0az9%9tx zZVVB_S&0o$ka#L<I-!#(1m;``vpJFwN(m_|U&}IR9Lz~8^8@Pxk|+tKy?Vms8Z4Y5 zPCgtK0*Jd{KFmh|apNJv$$}wE%;&A;r&=t*Y;?y0ogDth-D6dK``ce4iwL6-%Guf3 z&dx4tB}KeS`VKG!Ipc=SR2?A_IJw@x|A5}s1<knR$*_q~juYeU;NXC|7#qW(ev_61 zH1b;w{iqU^B4n<W8buOLM4g<Ry!P5_a6-|2HC&yz`xMLs^L~j2s&F7h=+cxl&7r*! znnwKQ!42B$t%U;oou8kxF`S$pqjSBk*MsY|+R@R`>#yIz4t{2X3WviUo8WXdL|MGr zc$!j|ef6v|z6Vy&19b?LFHFsJ*JwQL_i&Mz6ot(hV^24`aiey2TD!a3je70$^mIHN zW3zs5h?3PRvu_jk8Ce(_sWf&n9Ydr$SU1>Zu{Rp(^~_p*wo&jeSJ^vqqufDs2OR;V zrH6;!)E%N4#UUmW>i@XR>=S~!MiL4e7pKRwsos5}CyJ$VwNn4hPyf;fKm2E5NchZW zewA^7dX%l#8<OVYv5^>2kt-F{xtYf<9?JpIx3V2-!(&Y>N1Cz1j)qfx`B`iX93&R? zr4jxq4F<Qq`^VpRE9A^^_=*4KKmPxI?AL$mGr#evPyhO_{rWHe`X_$*Q=k5|-}=la zf8&$CLh=*8@hiXiTV(wjbSS^|nP2~v-<y2TpL*%~?*O;I{+VC<dMEQONfV+AgO$GU z{c~vlfA;<a*w*a2@5Any&z<kP_s!i6bYmb1Gzi&>7>Y455hE#5lqIVa+p4%Ku_aQJ zsw^v!5;>(f6-Ts_IIg5BaZ<74IAw>5D2bLR5I_TH3<L<0kVJq0A&}?+J-zwPXCCwW zum5-U`|cU;ySLwKf^_tM=k2@p+H0@9_S*Z~d#`i8^Bujkp2Y1|r2=Jo9x{<{{LBV@ z*H`C@mC?A|YBj66cY3_LdygSrSzZ0$M}AT|CV2MQPpEsk^MQF-Yqwf#DvT`6L2xD7 zb)+^4<+#YO$3XZyrhXU<pHeuM$GxJLMw+){rcDinNWzC;3XwwNc$j!MXnpL!)vOOL z;_eLQBTAO*I@lfTAH=PHWe#YvO7HU$Mpqi`F7(0v@yoBidhhOTv)$R>KX~=V&ErN( zKeOG|kue4n?`4ZWI)Ut749g^`MBQgCz@z#Ec#-@mTB4UimJcOlNR5m;L1N}>nUjj< z!lg#Oxi<ndkx?h%$p(=OFtJE}5zZ&Q7^k#L(QN4=d3upAN_4vJrg2h_S_+PdStPNk zbkR8G7tb?7&CKXu1ozj-Sb?eReJtQ74T&%oXqkp<fh<3R{J5B~$Gk$CHcYd8na`rC zPpOWMh=&gk4+uM1Eb*#Kr7E;ihb6H;=xbBfep7@E?FU!@H%gj_U~7ORoGsDiVf<vh zjt%U9y6r^=26l|bQG>$|%k0k1&b6!8H#axfUmA_$jrHs&RW-rl<c3wy5cyW}jgrm+ zKD7)qBr$R>O{od%Pq@#Yys2%76TOqrJS;4jAk{TNYPI<^k16>_2oz4~oaH<a$zaz7 z_784P{FI&ow%{}b=%hMx0BD1K10X{upt;lw8xMQ{a49J?rC3#tIhnn^63^FISy^2d zHn^t9B7AgoOeqJLPPfhE*Tj#*21?+ggsHAJa&WuIJhGobvbqF!5@3q2F6d}FJ4<D9 zGw?7Zcwk5=a&=4x?weDCBDd%&7Iv+ao&swy$T|hqX&NN{BFvSS(m>)^CNCNFltlnz z%$y5LP9ZCsK`KhEyQksZIY?rpscy88*=8iB;Ua5Rh4{T?<}_JKJ$y`Jj@N$YhFyWN zyMFyTMa*LksYs@Q<Kpz9+=z!5b0MH6KGf2eUW|HO&qL&79AB7SgFqp|G~w#NZe-rk zez{yFUP~5|LIXvAV|_fOPgf_K83Y1(s7t2;V`v(~Xx)#e#w7Ukg6NLxgV+whq5A-j z$SI{_p{&bZVvZ21#d2j_Dv#++rMy(D6spB>g=l!74}Zr)7KJ5jWm_4JO9P#@_3<wT z8yIhcX`K{56S&eGn(66a*h5Eum_7NN)DFiF&=`OQBmqQ-=?!W4$lzXjhgU<@_~76G zwe*ONQ>q?C{LeN|i>`(81gaxoKFy(uTGEX9@jzyPW{Qvu6Yk^R`>X#Of<26)Ei`mG zy64+H)oA73tpH?EivYl?j5`Ai@Pu*G5bhv^?kNt7FpP36q=+g?GK=n`RMq_pl+q}M zF=O$}-rgQXsG0@qxhv*Dr*Tf$m0bm-Ru~Q`=sVofM~Q!yNx$rcume{n9rB&tpwsUa zOSlxXyM?7eeYw1`$z(hkZsSM2+kkx|<`Md_pK+w`(3GNFGGPWbkjm}=bSRhu>gM6T zfLfg^!V?ECx&-m;(_PMFZG9P_1Hp?qi5$ia^frX%30b83`W82pm^RDx)s3~)?Rsrv zsZi_p#|Xag;!9uu#y4Ml@ueF#ZoTmQi!Z+L-QC@NT!(gSmJx*d^eH}k4rBj22oDf2 zZ6+{t7Wtwn`d{FCi!=}>fcfVF7u#H9#WToS%0U;-88*Htq$;is^31a%Ghzl=@jRsF zj0eh}3)Th_Z6am8U>aUF0ZdGaHEq1VzyJL6&wufYU;O4bzIEr$9j{JFELP17`F$p> z!`{&n-~dViVp&Cfs$8xuXCEw=ij_DUpk#dM(iP51z3!mdXd{2|;>90$$M^lQANr%$ z9)E0e`$D-^)zdn1Tf7z8r2vl8MZg#Y&_FG+(DV*FQ(YruU(bAaRKTj))WjPKyozTS ztTb?B?dtCd(!_J$F@~`NE`8&WceSTM%!`Hd0ShU`QP@UZW)vq(PFWlS{r<SmEu0+S z1H{N0(IK7Oti;+-0-dta$Roi0QymQ$Zp<lsHwob2db%_h`GGN9%l)CZoYfrU_|WEB zl%`(gYnhW$6LaCxgp51yBAF7HLcYJY3L1{-WGAqU2?SC_^G(bm$v_xX1ZJKNH)mv( z7sK+YVxDP0&vMLU1lQNs8763^ELrI7?d@yVt`V4}K_pA+juQqGI8oiB$r_<p;&6}2 z;@+Vjz8y%GbG;-B@laVk4o*&RDJfGWWR<l&opu(;(K?`rY`3kSBbp1>HPow#!%feE zE09u5!WjAp&_LhaJM3Xk0x;oV54}T}edxl43uF%u4-sBnUl|g65y24x=p(=$VF3)< z){iLYBU^p;#cMb&uzwCmOAuk#i2<S&+9GlxR3zo<p(1>kAtenq3@9+r2g3UHEM_xs z@l9!cVtjb4?^iG`h^+=7=qVt~gKs5x5?kGbhXW7OyK>2wr{0g4MCtMs<3n2zG<x~+ zWr8%a{hod)7Y-Zo|KaEVn&fhTPs)H3(K`T!15(ovr0P!Y8bmFGX$@omCU9w59{~h* z)|T}VxA^|TmEJ?w&k|Mi;rZ;lqn9pT%sfdI{I;>N;XBXaz)u$1ji7k#>dbe5@9ysD z?bz^@Vrg3f(5dLRS|G~SUBP;@z{f28{11agTU%ROx_zKfCQ780PN%t4=yiL?-Ck>L zZFOTqmr2&n1UA^{cY6$$h={0hEK`wzfT^}87d}-GfDZ=^=2#C|m|<!zz@5O%ROC_y z0S<=2L<#*tk}lw0_|WFK7J+f2(Oh0$Va+HN_1v;LN4!dn7{1lP5A~zN=I*_NPM1^X zQiE{1*RPaoG3~P<CWVf6vuk-4vNhnWP1T3Y=fgt%=S60~46@=GWY!0qJw+H;%t%$7 z{X>EL^aFI(6U^B^IMA2{oW)?n*;%9_6DeJUke!39)fr^PGsx5hGS=%w)>5>Uh&LLK zs+G(IGsuc3Ba$Z)LNHqx*#ud6So~v67JTd3umAdQeC=yrd-25=iH8x3W30}xEbvrW zsp}V&v|cf{btAN(<vwnWMu|5OKo%yT2?P*x<9b#?975O>I3oeJiE6dpYU#aHm^6nl zEk60=lRxq!KXU#0^{ZE}at`rZ_BMvp1DA*Um}O>wPExu|>Qxs4!%~%e-Ow~2?g#{8 zzM`XF4?8CllD2&M`+&4MMf>+V7=`BmwG3xbl{|JXu$B7|MO}{<gU+<cif16BUl&|G zGy43a>A4M{sSd%MXZ|zoF<6JBa@nx}-GO5<x&!QUke^7v93-LD#-qUWKw7mMb9<y@ zb)1YV*<!Om2AKB1&^J<F=Pp7ODZYS%OhPnu0!i5EDF|^P%jb~nNu_he3>%3+G6^Q8 zI%~j8a4k2HdWTG~7b3|gm_HY()GeM4OwB8VV}lb1kTn5Qb#j1%1_PS9X#@dTMxQu} zIDrA>dW)z~4~0VBGB~i=Y!V;Bp(yl76-0z1toy@WPoeDb@iChU!d%SEC<Inkm;G%? zXmslQI*t!Whf7rHcKV!-+xl{@zMac4Tf0T2R4o-}U&V1eaWNiom47V){qo$#azcn! z{E{jixA#c7IB^8N8{@pm(@GK0uCrV(luNjhSG(V9apLdynuId#cB|RZEy?}Su<uW) z<9n3Z(^(6;y-A@j-b?GC_92=hfW`(^3iud?m->S)o~MXLz1Ybl;*Fsm_pHa1>EV;e z3e=Khsmhj#TKYwb%_zis+OXrB+hzjfNvX(?QAqrZPt5T?Z4I6Y6nU2ACkzC9XQ?Hh z=I|f<ul`T;9KK!ZUI2<*(Y;1FDYQ9cljgh(z$7?$0Kg0r<T|=m)Xl_5$5*a#`Ur2( za&M_{V{hg+e1W@3UHZ;ijFTbk6C=@#c~_tPPeG5bqSP5%YY!9m>d9v6Y`lsE{fvd4 z6(uiWc3eR#rE*m>YNWT}o2}!jzIoeiwT}prG41eh-<tDCKH(e&jW@W0&_*v9VmTq_ zMmvqvOke{5ggG7#i;<<GW#UGAy*x_R$Awv~)N9pc-LpN^k1)fbm&CwQh{|{*dx;Bf zFzR)>?Pd#?QnSzH&(&QV>k`E^<MHuPqetMYPfer&g}lhd6wb`IF#uu_=9ao6Hv4R^ z?-|@dBV$dFadVjBI}1d|_q5OP`X0e^&tRAg=3Z8OX3+U_z0M1)%BUQ$Iiu#`^wKjT z95V-5@eH!!hi-aqf9Em{+MD}gbmzXZYBSLAPmuM*n9=;YU$mYG)1+=OGlJ3yn4jje zw6YO%B-q{Ey?y&O#0xLH@YUb^r@#3d|Kz#nUN|~x6qiaY_UsWXo?6fKJa?9Tt%kKq zRZn(i^<@#GF}4v-!Fnrv7z^RdOZzW6D)p7x+Q$0Eg{_SX+si9!Y!LVM4qBaFrB+{E zUt3*UTUlEs+1OZn%Uj?2j(5KET|fAPZ+rXOFJ8LDcEaM%Vw;wFx^R~B5Av-4q^a-O zM!=30k7vxk<}&@dziI~{P>6Hf$}Fa;pYfF*U6#*2lGh@5y`o1te8etkM`gulhU?-M zd&Wvm@y{a2xiflzXZYD)i-5w6%7L~>-CW`r&dvhKL7XA!BVtTWUk{u@Ik{mlrK@Yp zm1=1?>aVY_BS{ta4gvv`;50YkcB4Tdnep&AvGG_hDX=Mk_F&Qtj>3*W<^mZTmsOiY zP@K=GMfWTQfgYgtW~u=5r+`dG&BJV|yO3o9(avc~G>4*!&9E>W2xq4dm4vB=&Is2! zOWk~1&^B)tsLJaM8zmg|PINynU?e_HP{b9FN+Q5xNrn@TK^Bl<Ko1TMj^a63WI1ya zHV|tuzZqx_<y2>WU%sqwT*{!yb)LqZiu#E7;GorNz@&(+V`pc_lZ32mMRg{+J}x6F zqlDdvCMcr0t*tFC4PszDe=(+6LcT|dn40H#MBt~#S$nIa73{|zRN*~qO9XAvI$gjg zRN2_r*xufzdZX1ImMWuiWvNsi6^g@AkuzqoP$eegLe|aN<nw-x`$Fehg-e@FeH=zB z^p}PraFsEbgl!m1iY4e_^Q=^}d(QXv_UHm0W-s2{+`M@4BJyaX2qmP*v(Q|+bctXO zn`z4?QN61l3)1I=bpQCc$>{9w>3-n7y#o|tsyth+q5-QIP+Grp=gz^t?tzEa)*WBX zMZ?ekhkrHtaRP{WIsw~{Iw}Ha0}l4cIROZR>hL`Tq_QXGAuW>4giZkG5@fP^7AobX zPP;kKhx}nj4!#ANzT;$1NKQGgzWQov9U1$ahB(l)dNX^~-J7pYo^E1L5hJMrtbtw6 z5hy*Q2;gBV4J7Le1SvXJE{uk&YqfHv$hA_8JB^PH52Km;h<EA38{;Jm#&{ZKMDQ(M z#hHvROpq+Wv35H)pn>+(y<7*WCHum?7O;$a6n5(71?B*;E;3x8w8(YbZg+WgI&2Ee z96hFv>a>VL2yCDWfGoj$>;i3eJq=2QgJbEHS6*uzcL<?5-W@gCXlQr!AvTRtH<@7q zpmPzXO5Kq^EXW(bh)$Sg&K3KE3=B@w4`?z6oc#lZsflzJS6e2fCe8(2Z}X59&*1g7 zvIy>SKK;WEJ7=z!=-_N0y@#@nv7)kUvVOAu`(`M%ysv)stDpPa=SW|A=_P#ytP}6x z_XlNG@L2jtskO3FkFSv2{|<@4JZJGVVx7)FR%`gOHb?5Nt!<Ev4YzRh>Q#8O!pRCT z4DJv6$Ias>pM3KBzVG{<e){RRzV)sCIT`fR99?j~40kFKv#@y(X_{fAIj)sYPk}v* z7}b;Ttj`}I-caQU_?(956pjKAWMO8-XU42&3}?>{@AV8cs;JI($=u+WmlZz>Oj%`{ zUx%r9Nk@pu{hPj;IE%vM#Kq;q%;#Fec;*|-w8}wHM2mTMnMj;Rh0^BwCKJ9`&`Zaw zct^aTs~|g!x^43Gfext7<jj<c-~bPa;m$B)2#^>diWoWgFwx_>u80gNe8Vyc(ltTG zItjNcYbGbWSW<?y>M|XPC-`JN8gX>%57kHAN{W}UQeUgnad9{<l@TLUVP#?@B0wo} zg48#&)f)vdV#Z^PP^!<wXm<)UmKG6n$T9-}!*BE45d_fSc?>L{PZ6_>JR5yX)jdC~ zHVu$Voi&Fl*5kV7pp!;X3m+QIZZ2S}O2kM6mRx3T1;ugIE&FWBfWG|l%Wr@C+X)4c z0Zd|w$oj5e!bs-yty{NgBF!22kjPxRbdfb(&%r7!p=y17jox5SyQwF>-o1NIQE0P$ z^XBcBUw(y)WMyTQ>J+tFO-6?f#!nCpR+d-SR#$Gkb_2&g{@7#9Mgym8ZEbeD9k~a= zp(2dvUP&Lo#pgV7jSyanFY{82@tE;P{>UGB^PAs92oY_ykSJBk7k0Kk_l3`|EZ47H zyLR!?4%aQJh$fGYkDzG_HF&ICuk9TlbZJvA<bYqrkxVQ6f&iX{D?{`cEX_p%V?x|c zi<SrBa^$%HqjI^Zw~sX_MZAyj^0M~7E0-_cxqX{~Xm?uU5pi$v-rYM}7q*Bw@m~BM z@2Y;TR=;MX?;R8KUcGjm<p!Svh^;LNV>Tm#NsJL{nE;xET#tn4C1!;Jr<Iju-JrX= zf<3jWe&-p_(+X~l5QW{kzDgL2nb=;`$KzZj_>vjT<?-J4{Wy+Ic;9<J_LX1%+^{!@ zkNHYNRz>}A^r%9&%Vi>OzX=P6$;$O3Kd^eno1+-uDe5^7a2XadEg2(diV#Dm-g~EJ zA)dG0*Uis*d{<Gw|GBz4sJ`h>yyN8WAdT<-_LslC+wF9@W*ERY>FB`XRBu=6f{5p6 z#Yd4({E?6T_n%yI-3;IT;@|!1i@4o3`dY@MUY{8_P>=NHzvi5umoknYXvTHwPF%!Z z12p=j0xJzOoEcJIUiHkWlq(<oi9h3}jL$v$Nwk%VC9b?Tzv<143-f{bfA{WPN;fw* z8D*|V&F#qwfX5hU4o{c}hhDC&tx*LBdICVB2T+PNq*P%vnNKm|V;sT>jM>PGFt%FN zZ~8GZxN2+b!p6pCr`^4E`}Skku9ox^Ze3ffyY$g3mxT41ygs620^kO&ojdpT8qKaA zq0Iu$TC^1JYtZ*vodsQYZ{)flM~)Gbd*R?X0O3+-nh29*Ie?&D#vv&&T%FWJ(r>7h z0A<-LE68zjFH5GSlm5y<@o{#{oJn*1kA{5FVXfRd*&{qCuI`kqK^A10fH_Gf-#hqv zfDV6X5GHKRI-4qHGEDa(h~r9g5c<x6DSLpk^fAj%I0<gZT?TVy5^zzHB<mDdf8vlP zvAI}O#&9G9oEj84HBfFO`6;*-Ksco!t2TpJ8Z!N4Q@Ri_h1fBDb1W0yb4k}&D7;@8 zwQhUTqm(8@;fX$)=~4szM#yHusfcFHF*BtLdl8bP_lbnaQjJ&E7xtqNn+sR6nCZl{ zK(YtmD2t^c0Fmm3n)`ZuNv4jQ38;jl@jnY}v(>tD=Pnx%rPr@r!)^wG&6@Kgmmh05 z15-d+zbnr*Ueq~sG~{4OM8MV(Z(?$dYOO4li^RRFYb!<8!AhCMmVHE9Di*Szma1H> zp@GAShFd2aNbP{6OUo-O*REfC>dB`#P_gyw?d>r)G&DM;X5Ea{k=cT=T&iK9He32g z`{bF@^mWWqO}iA4MU3NajPrCFE>y}Zd?P}1wuehlTY%16_g9<QSNxv?4MQNyPmmv@ zRGKGDn*f$~De$-hn52p0Qb|teDWHdx&KnGXYvt!Zur`q8C$^Cq)XfWI+=-pQe9M4E z`eP0VR!DUufm}ZC#jw(dhd!GC@nUY8KmF3-O9Bis)itmhZP}vwGuFcKB^K_{C1WGE zHrC-|7)9tIjnn=*G-nT;ne{`#oS#Sf%~5^RelH#kw4$cR1c^F}L37%qS@(h-yWjAC z_AmdOZFoqOIOx!Pmdk;jX4FX_obNv=eFJ%peU!kG5m%t@{i77`Kp+VyO|{Gc(6d;? z$Hk<s2+Txnxuh@10ce_YLoP~UhKoonoQDPG%DdeJ%Y&o@CbVH02ze@C$>bBu=TnOT zXEnJ3&;~`=ptUW4SF?fuwOlc!VaR=i)O{e}xy>%iG~L|VND(`882$VE2c)#<<MNx{ z^ro1{`iv1KV(bT;r#Z;pxpU{c-~BEvU@bDF*cN&e@LwU4yST$lCrqO`3Vl>vuIgd7 zgw3~Z-r3tbV1r>bN84}xv#&q@{BtP0dGjW1)oRs^jrGmVjhA0}`RS+Mb@}pT;uSnW zD`+D;voUdz$VKW>JVHl5eLrzEF5y4@a*BEMdS_>cUPI6+`c4tX6E3O?gTcj%7l}NH zB+-u<#45CcdijohuQ=||OGRSizTQ&7Z~7TP77n&GH-wzVkLZl8P|tWQ>85XePZ%}Y zc(iAP97$NNGXa*YuWzhxtX{gPAH=_~wM8dN`YD=XuiIT;UpYEDgs<8o-T12&Pm4~8 zzqP8~!oW@x(lUhS38R31PZ*CW)mdm_bMs)SQ;Os|?bVf4m|RWudQEDV^tiIMwUutW zftOj1v^eUA-YC>M$PD<>7eDpB_y2?(Gr@b_^O1l2%YP3Wpgkz0hRv{rw$|BdU2kba zz%kSE5ZDZnw2{W?qVF$T@gg3^P7V@`C6_g8X?N$3{m{wqb*1yluYT*6TTcz4lUR{i zr*|eM-_ZgTtvvaoKm61Q4R^ow%s+iu-?9z?8E;8wc}eg4XbMRczSYk?YiQ6NXA3Rm zgWjOi)uW`axl|a(TW?Fax>%|ZLeja9{)vArYb@}&XFs9oqjz^kU48VbuU?~{EPiko za1L37)tE*ldz+F`GZ9S-$TJfzT)5zQ4p7DX-`d*ZS~xt|_ooz5NmCcn{$NT|SB(}* zMCmA`%c!ES$g6cdx{3)YZ|L0^K}KRAMIpAdf7tEy$G!f*`eV#xvp*L%D-Sk76E2l> zq%tG=PF76^GkUEBVHODFai2M!E;<X6!aOn8eswLI9@z%rsXJHrj6g|7p?|@ConYZq zMF-SJfxHdIEN3pJ>{$eRX%==P#B4ejiwcter!*{5^}z8um!7=vB1uDAMqIgEtt?Q$ z3)CY2oUZNc?b^>q#tL{doyC+`!lE{kyor>3{a3|FOq-oU#+rePEMt(x+xVNc3(xBt zO8QEXelV%oY_Z*}=tlu-l(Hrx%qrS#cfIg=u(<YFA(7F0>#<A$d<zZOZ1m=}?%C0& z&8(}G`Wq$4gcOZv0Vb#^P2vID#==50!8Aa>-@b=nQ)eSEP(}TAr%M{z?oW8b^i=9K zd|~M<#`F0L<rlCQ0X@lbBWcbXmQpZR-f6xlWEH*7h2>`vTg*cJv)M&BuYUOXCKB*x zM$N#&Q#jqMIsREN9|-Q4Z&=0bA`8vrC*?$CCD9S3@R|QiOqd9B=;2!6I^wb-%bcYa z*Gq5)%xbIk5=Yj6HvZyYdNjWSTw0EAa)Q(=<CG;RN`=%z0PU<xlgzz)_c&3}C4!Ua zzrGbrAmNoF)iMF1(i|)*!cC-j5Lm|c#JgDnmY9=FGLoGp(t#-nr|Ka-EsspFGnfxd zn@ROVSQWKAiZE?6S<6h-W#!82v9Of@nHZ|P#sLnmN!SFiFoc>9KwA&hNlk;$sl}9O zy0*5qv8hL4xgsGFPChs|WE^QI-Q>(nC61+C<l%c|N5k&!?u#$JNW7$<=F!8PvNN=& z@%Huwj@Kyw)`mXRbgz}G9Km0E?Z%zkcN>i+v!!v|VpZ)EP!chW^h*Fl&QCu1W?omX zUgbjjqkr^YzH(LJH2+ps^cgji3U%sFY%$S$pm$v997{Br;A{9`hYuY9SLhu9FoyX; zMUo!v@9(pzG@6aA?F$Eo2bV5i=A0SVZER!N7kmi6M#JJ#4?73?@}!Rb(KxF{e11ry zGAiB^h$t0P#st8lzHY454{AwUj4cP*aCmHCdVo`HZC&sBqZ@x#Yt`YPHy#a`LCnz2 zwY5&Gtw~VPv$9F61djSTQk}kyhGUi|78=yzz2oEK)p#0K8hYGLRUCpzA{G1-+c<WT z4BcX~_Ii3wSh1vF1NY)fc4-H|OdR<Wjq!XefRSi;{|8R|eh+x&Q~%J-0coFHkLvj3 zT8OEVy-7q@WI!DF0HtK*pt!TwRV+*@r_%|{V>%KL4*TfV-SLVBhvjNzZ-4#WfBgGT zJXLw`+h6+DEtH@TC8X$qZB8C8ecO-x>8DSAhWyfR{{7$Euc|p&o>>TDUg=GHG2#_Z zE2FdM(PWTadd!$_kJcNpkYgg*4)GwOOc`~MDfF?Q{IhP$_}phdjw@&pw=jj7t29Tu zET<R=pV?v?5Qc-Ju-tW-07z2ZRY)midfd7tCost`UAp97nB=-XI5>!B*r7)bu-VoF zkYRNt)J2J%qup1tnnJyGt)7W5VXj<pvo}^W)<}&DrK3i#(;E{6s}WyEauwxN(<?fW z^+ntWfSq-xQr93%yEHQ?Ea$4{6>lZQO9x8Thzl@eD9YaRem!uzc_P8a+_yhxA+V7k zan1<qNpO}FeW(v!KD`guo7C1@5vCpzQ}%#a&RitRQ+5$7um~1NVvFP#X_*?J2kLp? zc%4g6UU-pY0#&#sxy-qWeF;yd`W&3D?d<K+3IayP3NYa^>LjMb?jz?nYcn#|j4==J z@|lswD_Rq98pzu-3&b*N8t@A&!5sq1xGQaMZ;#^uT-{cuolWm{hw6ep!zx!aLgd*6 zqH?#>VQa{~9_$f~J&sj~AuZ}KARASJ4s9i@e7a*O)?*zxv}^EUYok8WknH`{>iXK+ zl`B_>$XTCJ%RGtDyQl9MYq1W!fz&%sA=7zCAQL$O_^IwR)W11cD8GPxF68Yok+O3U z;?n{dbHQ|&l{e<{^Gwr=swbRRKNBp`2^z$VoQ8#Gp_9ox%vQ<tEC_%(g!q`j{*D=( zKmdo0K^z+6Yg3wF2)KxYIunrjsCWJ2hfZ`P9_e>F5#vIz9yFw^s~gb9&-~mY`WYlH zD_vOuv!+@)BV64TNv+VDbvxzCiVkf7`iu-&;MNlmmag+7wFONRzQ_|&79!t-nIQ2^ z0|>G(7s+R=8Bl7%b%B}InXv+9nznpOP2>Rw`8@Ip>APzgW&-%h$r)>+A3!GoXzO$~ zF%gT_3dBy#buK@Kj{!xJ*@=LwKsau+TBa{mk{)Y-PhI9ci!#hGK_3=Tf;;cty+h<o zkVX(o%cCK)pNm8fh$Avv8p}~!X-p(qLE8`i@DHQy_U+qnu3fvv2_D<v+bwxSL(~3D zpol6UWvPOBa7bwpYf0&>uk%nQm_~*oUB>-kK~Y$owb_!qz>oB0&i+83)alNp_#lWq zF)r`<$8K7ozer(#o4_hsp$Q5|bt7#&Pmd;0Ueg<J744?l78PNZ{KHX&GM>a&HV+x9 zpbedH(h#5=+W>WuQT2EZ7SloA7;9ZakhIs0ZbpC6ti>&du#scgK+ip{l>YYr_TSA4 zCivg~C;vH9h|x^_q5^7NYBS&fvIxj;lP#R)fLBafN7BO7l98H5OO@(!MPH&?sn(V` z4!~45yOP)AxNp3oudwH_y?rU(0&uUBRa&HD1^0BaVZ-5-$F8_q!Z*J44c%+t4212W z3aY5v?aEiEuhn#ya(tmnlOY;n4<lY72xdQ6-P+vQ*}hV(EW_7#Yg?V3eqN|Qj?giW zexFN2KR^}tG%PXmv78pUFj0$t@@4=C#2~N-eu4#H0^;7awKX_gdi(qPjYfkiep{Ep zvLEam2(sSrB7o8xQ@XD&KHZgYRd1gmV;~0N{TyAwC}3=Pg-`0s%d5!HmhFMS%lHQZ zn3K|kD7+7Ka&nCTXqyTRVLHK8et&=g`80tnmSC8K9uBEf`g7VHqjPay`9E-o-V4rV z{+*d2j~rR6GsueHFl1L#4(4RVf8g=^Ff?=FSz(aPMk|(xxo|Cz<zq$l8U?7xGN=Q| zlHLbDI5@m@>()2E@r^Hk`O9Db`qx=M84;E>?UVu5G~`+TSs1C#E`|V{WI(2QR3M6O z9Jh`FEW%z15oVER-(-pAghN`d#iJATtuC!0p+ibgNa^Lvm!E$6=^yxkA9(Yd-@LiG z2@@L-Ko6%kR&~rs2B?z((<wEP=QuU72o{({R{YR#Pl2;}<#{?2%E5fg0B0W_nfBjz z{pW?N&mz-4gRJ<>a21v#CY9$EvynrW0ZnP%45ptC2~>ek)<*@)!{LCzgone$!kGll zTx9AV8d=~MeHTne(fN>S**LOv9$dV5aeI54tC!0U2eBg1F@IWUsMUb0zYgT<x^>c7 zg>u_T$C;CmIH}Y`f=i8zH3OGMhlIprM9ud|Lzrm+OQsa))I9-Ngz+Bo&`~4vFr|(V z5HR16ia^o;kV!L@?3AR3163%*LTH#)OUm%UcM#%3FcTLUio9x@Ln$(>_|}kGBy|(e zFr&fD0GJ3L9v-5E8IJ}VfF<pAcW>{2qGq#+V){XK8sgg7*jPgiwb94Pdvj}jYik3Y zG-S{UK8rXrYh@A8>5I@6aThkwc}(BBaN*{yTQISQY0P#)7}y)?>CU7`S_2&$cDjZB zpfX;nm5OzJz^6Cm?)Nbfg~^1EUqzx3m|?0M1;|nuvT0}-zTw*1#`d<JYlXEG;Ubug z<`ET<z%T|U9!I1f5XN06HDrTpgs?uDHw~Z}HR?JGLDr*yXCi*n?8Q6}<)A;*H&^9e zwN7>2nmZZ{M?H4fxIb(B^MCu_vkeJ81h@$*K*Nl#XK>ajGPI6Nl&BT5FtN>clEwas zhEk8*7>lX|z}0G<^C3-iJAI-vni>wj^zDC+Yz{ly7vk3r=^#j+rxu#kp&SN-%iBAy zHo@IHx1%o_vxL%;UI8>0$K)6-JjQI$i;0HSnBQu38jTjOPTRkCRajZxs8v@G#y7r* zXg6zXf_RS9s8TA|DpdqLMs@{&@UYskqzI?1J0(wLS5Vep_@ri1ii}4e5x)@hTN}K5 zx#^7sy|aM#&`cv}(9b*h%8tqI`9`Y7)&96tSSlBms$3k!0+&cF9(ji|urC`#YyebH zov<yoC(Q>l4YB}vBXxvSeh<%wNG4-CReYlnHYWS;r{Rz^T?Oce2YTG=EdPfV_Q@== z;(vi~k*`w#@rTYix-fE=VGQpd&@R|i;L8?5zxLPZ_u{^0vLu~W`{>}1*X^6PzVmy( z_w}!R?VG>-jaOcJxuGv5X&+%3=SbsdmY#Z}0bH%<Wc~9-h9oWOq58dHr`c&8w>r(% zpi2O(#kO24*H&t4n;V<k7uL5fEU&GXsx@sXC<*gqZrrY=zopVsPd!Bd{O)(Z`(5vP z*IS-^>hi@)8yuC^)+q8Sfh52lvS}7+Bm&Zw8yXWJ@lE{x!yTML-nKmE3jYhd5#ap5 zBxDp=lsvJS)to<>)xK~nruiCR!UvN=9Xw(&Q$;ku0x_ii+(mPnDVl&-BCPh|A)EL^ zlcX4ABLMVVM6LO7sZ{}#&<%X?+H0@v?(RbSe8v)xWDNCqf{b-$pfI&-K!>IG7cY>Q zsuQrJs{oGyoFrzZL<26BXu!-_q$2A9mN&>Is}cuTKBXo=5{82?_Lv!k0^JA9LJOpd zAXPM?wd}OS9Lh5x5Jr#B&^{Ae*rlOweDB^pPR7Vso-i0m0%OY%-T-Knudc4zq?oQ* zTWDkG*W-7F$)X|Hihc>%e47Bmu(5<vG}#8!)@s?W5Tki>bCWgw#*G_9q^$KU?(8%$ zuU)&wMTITYnubo{^Fdpb)2=%!+4!UmtGF^TiI^N?D0QbOwXbX>S^A)eZ!oG1hvhLb z@VHDwF&-61!@_u|-$vlP62C+{h<88iWVM|eaoQyX`KX2n84gWj9$RUv)zSmTntJny z=o<e+kkSMjS!puDD71yRi^a(O!bO<j3lN|dCWL#63^WxX3^dx|sIoR&1&usL63*c^ zrU`DK6h1>4@y~t#M2GI<ul>*dLn;F6$+%&OTLchf^GwXfl9XCA)qy-X@m{OhZFec4 zdMWNHF5@{~lG86V55NA~UyIffE?>H&(S))dfF8u*K+rTTGFS2N%1V9e)7X38`Z@uy zeg{bR)@GL#1V!k<!g{5S0-TD2Ip?4jg=j-31Y#7icTkFBNeSAQm)Ch!%QbzIyrZ*G zG<6?v(CvoCOFCfD779^L%0=NTD;Yznx*t7qnl}{=cHX>slO>vpJ3BjEP+ZQm!epba znv9AuX>}I^t?Ss<Yxa7brGg&mTrBC?=ha#{q|_G=F%yq0HPp@i5-&aTt57X0RUo>Z z!O_t%^BEa8ggp!{t-Db(XVW~W0_Y2LQj*V-<{?MqX5AYKnwv^#+Jwypsp$0~(=tKE z{r?+e-JWzDPa4j?amZSoL00^RA+Dxu#{m#zVP?gD;9;|~%*^n;ambnpkhK{PgzILR z@V3|O&=T+S#aoB0z=!eFXuyHwt6%-<m%j9+Z-4vS2Yb6a7q&T*u%IEyVhA8u;;fdj zW0`eD2r}$^R_kE}9&Y4W)7XgFhB$$&tgSAuuGE%SN>$&erS+fHyIiYk(~H%Q6VVe- zJn_zVzViov@CV=i_P1ZYeAxkT(hndIwms@pIL8ElK863i0ycvzGc&SAk}(0y&*UCm z7c%X?@A@<Dnc?cQ$kfdsD?T%rsGg;+3k`=U&D8Rg3n>AbDaR$loVSeUAw^`F!<53| zO5tEYN|s>37sxEE^WmYZj+T<4bO2z7vu8)%*VY#PA9EP`?svcI=akY<I9$eDv=*C% z>YoQ#i%tl7kv#5R0E#jycU%S*ODUi_u)M`!`lxC;pPHD9R1~e<Z_a}aflk{=Hu>3- zDFw)2kG0u;gDRv5Py{Rkq$LLgoO&W!8_1WsI)H%VNohXvj1hHRg%;s3FImtTJ~&KJ zN;x{iXPOcyVi+0_0LW9x$`Pgrpb#-iVIm2KhTH`5tnaMyw$rT}h}pJAqp`og&(YkM z(Bb}G<LGdx`-^+~_jV6<_d2as^Z1xJu&nP3Dj+Q8egsdZ%!BpYNC-Hz4rq~-*-Ko} z9}a5EdPWxpV-hw)s0t(KcM1xHYH3^<52-fp_eQ-gDdCZxOr^UG!-5GIJOW#k(-w6B z?cxC=c0<7~G7|xuk1==v!gjJ`P{h7$AA&GkfTlX$W`HP#gZJ<}exnL4!hw%5h@p*6 zsUPvivWwuL9}W2hNZ+*8!<jT6Na+R^+D?=(sWC>s!JB<rxb(Mw{%?@x@wfhi|J1G1 z5LxR<_JCBB1gsyLQqK^}0QoMP`Nc}DUM{hQmdA|$QYD+h#mdr<&`WpJkACZ)d@DpJ zxO(NPCLSHcvB@*Zj6BN!(!1Z4)iS>E>?dEfRn(&I5Viy+j_Sn&j`2z~&FIPoQeH&n zRb0EgQeRmmt<;ub#Fu`Hwd(T5`qtX&1_sdUZg={(4fH){G{pqrdO?O^GJ!XksLB5P zECmqs0vRbexx_v7)KeVPm?tj>m?v9XTW@>Y+oF_d#z4fYw8Y>N=njTGbj01x6)rHw zAAPju136vig+1uk`KnaagG>vh(Xha4I4X6zqy2;C&D(lVJRPxeW(?IBW|<YRos$%^ zGs{VheAj^L_)46tndJOpAo8z?w%OOCfh{qS(mVme<jnquf%O;}>klomZp<Jnp26Ir zyp#Vs2|AdNvHp-?uED2_@1ug(JvU^(vHE%GJ_VM{qoN2?r&fT%w4AcmSz)7b^y;gx z{?70G&OiGn|KvA*<2RriN5|E2Wp#O_TrBDCsKGF9T-F=3@dJ)}L9?i9*XSXjhS15T z*Y6VsG>(rCA$Sc&efASVTsGy^6%JhM*(sWi#pepF_EAxmusgtJ8Gp-L-a;7s{onun zZ+`QecXoFC83V$$JgR1%nF7p3{EV7`tIQ%RerVV;3D%sNaGD@LzQObDd!^rdH-MO; z=OU{)1BQMsvf}f=1~BnRu~6rwa(TJFTCMm8BQz}&eCg2;l0INi?jsGQuqZ;Ij}V;q z)V+C7!;b>$Gp#z4>5l%Gb6(_CIeqN0$2fU&;c@wK?YW1(L@jB8)G+hxz*JhH;>4%Y z;4Y*z57$btJZbU+GI^aLbstII*+rOY2zk#B6f!3O1X-A~CK*!;H<AfdglY3U+dx#x zV4bAErD?qeRG(;YAEnAI_#`cz`r4k(uTcwA^@T(D7cN|29APqoXy6n}Jcb~g!^1;8 zJ11NRO-Es(8HP6rsxL3=>$^1Muf-xzt=4&Qj6XOyJU(u=Tl(NA%+xk8IU=J+g93_$ zGP7x8WAg{z`Sf5kK5QJXZEoybzNEW=3We>97sthdf3-BF@iD6JO---+h*L71&n{p% z>Ug<Kd$ihYG%j7-*00yp^o%b3I#dPE6f1gmk-pu}D|}ewq+igpDh7jIyVq?K26#hb zD<ewRhmeGb@rih~T+{Ep#_h87EBYF<E}oZ*Hfhy&o)t}@4p$SSUA=nw(xsi%)#X}E zyB)z44ICUbI=xZ5+wXJ--OjMrQ)_;KT3x?j6df-@u$tJnG=T;zfuPIIw%g54w?WVq zJ1)=wfe5B59wx<YD{HGOo6F1Vif4xU2vk#ecp|8V2KJ=-b`lI<e4fut(5L-$76Mt~ zRbCL`R4szEj@d+~zzZTxc(aE<Kdn$7KG@n=Ut81LD}>1$36_fWLZMbDRhcC85nnDX zedSx<3=1Z>boDVR(o;YRt?NMT%6;a??c~k1jgvP(f9o4x(`1zONP4x<Yebm0#K<!c zjaIwgLqJaOx`$8Q7YMATAMw?&s_qys6tJ^csxGgrFR!lQoS~i|E&X{A*%vg$`n`@W zI?R&|1^rTYtKGnoMpNHJFp`T5W*jpC;o+#yi^&EJpGz3)xw^TuiG;BSwQ>F4Ut6%B zgO`_a_`1tnKfmM;H#9%7O_N!dphm<)kE*D$1_2*K8AO`f+dH^<^QL6t%kXqx1FfF} zY?DSu-Eq0qbPxhWq7AobBs!!tFY~X-`!Xn;`+6O4t%YfrDmv^Dpp%h#%g+ugnMS-V z6|l|+rY8PyW6FW^J@ZiTI6esXo&N?xS4!@R_T>pPEB+T)0J{q~8&{#=>;sWW$4z1E z2CUw(S?I71;Ij;B;cYZJ?8Kv`X0!d=cV77QFaPF0{zo7Gr(gYNyLb0E<ku?oN~y}e z#Y)J)c{yb*WfiT|h>mGz)aka^#@Tk_*rW9jokzz9w8dem-;H+_^|;Ui+d9#2764DC zJ;rng?A*PT)m3Ije>5ys$`>wQeDdvY{egGB<NM$Fj>}iCUc7v1^TO8h>Pmb;OOuvb zq;^h9RiJazG@tZ)3->f3nKWfv5?dtysPH|}4-<Iq<%vab-C3Y*F0$e?!&NYYNlSBN znU*WH>^HPoqu{`&6d>kRiy{EQIl)tr+0IOd!^Gy;KrJRb9A73zq9LO3M}X4K&V`ur zdZNi#-#Xx2QmWQ;X<->~AKVSe1ypq+U>egC?NKq!l0jXHV1{^HU-5H0bl%D>nKWD8 zNTm>_om$dW0Lt?Sj=Ga6knLRRRG}KjK9q1=%lLW&E@Blbs-=Ki0r1suz%mRZV?)-Z zq%JimO;v0^$m@~PNfiVbW1IkBrYXYgF`b0N83Lua8f`4Z6fsv|LMMd?=+HX(6bS!Y zj|D<s7{gIrpG+xE)WeSSnIv^Nx#})u{Z4P8xW7+8t0i8)yxZ6FsCIXENzwWA(@(P{ zJpTCOOk4;wV*>|hTL0!Zzlqq=xTK$~ix2LwitZ505KAD#3})oFw|7vwdv9-JV~cb0 z!R}GJ-8(!y>h*N{1fCuahV%euV-*1m6*27k^~ZkaoB#ar$Dbf*YU%;VmHuFO@#1AV z{X5_K=ap)WC>k%|0)lvgh5mpzam3MlR2b-Mie(~B!XfpS9`ko?Z5=T#$%|;Yd}VpL z9y`$B$tRw;bL-X%&p+30w%C3yU%JTUc<JIr3VXzw`h2*c!#j@U1XNn;4T)^p7(?ia z0fU&5#ZnQo>1MmxreBqEML&>Fn733MbcgM>ezKTl07r59$KtIEoBf`i<;zK@M+mCh zur;7;zWROOa*^6su3p(c*jrm)KWa8EUcNdU7kc_h!0PJy=E~~E(zvXzDGvs#8!Q&O zA(r6z?!CJQhx@E2`}=!OJpLvWvZ>O#=N{fB{AbT20#$UcyS0hqb<Z=S)@-#(`gy|o zQlUbe+aHWu?QZj^*=`&Wa$;S#*Q;W1xjax9Tq;EDgUh>}-cq6TTVMOlKmNn-jY*f` zU-{7we)==NqD`L8kH#yjYY=+;@fbH!y@U^2?M_`EY!bB=>UCyIB|e8HdMPxUEv7l+ zh2f|$leMIAv`3KDYBVqITt3`Cu9TLE3hS#Y_>j?O<*bxT_iopo{^M^;Yv<}(`&+;9 zd%HbdAho)B&N{HM&U_el+U>zm&VgU4yy<`NlOKMw?t3t9fAR1BgXf!LW*|Y~aihs> zW5nqNYf8DIk8{VvrS-Kf_)N9<_22kuMHYinkxP!5sfU9Wmj=V`fcdE#smJg*9~DZa z_{^A#k+re>(|_jAXKe;P^T}V-#U$ZUx836?Q!H`awQJ?da!pVE)cY^}{xZ8ywL+NO zZZ-S8E?yoEdIJ$XW`DU<<Sd3ahJ${))mmAuLt_mUdz~Irhh>23vD9gKV-yY!4)5K& zM^w*}qMw^Cmbq}SvOw4y-)-iCVo_nrunsU8$S^Co3Rl<GUVZH~I$o((SZ+Gq&cV^a z?YlSc-o0HYm*S@*b)A#Qf?_O1TAXz4km@3xtV=NL1Q#=XScHMIq`(}qn8BEMh36H^ zo-{kl3Xo{&i_g_r5#weNb07E`>xVgG841m@GZ3vzI9hNcrEAM8t6Wf=pebUH_ZIGT zTlHLLlI9Ug&~Se%NpP<-V3jtgV#KyAFr+2YLP1wIUcqL)!KAMXa<<S9wIP9QrqoK< zeI^Y}A?r*4!Bm5RaF$Yx1g6cLMX1TTlTWka8RYe-W)2xQfD*1&kd@{7lwmSSra%?y z+J=*eJz~x)B;)C(lb0Ihx~7cI<Wmxsg{-BMIPvZjU2`|w$H-2-sA2(E*A)_Q7G!lN zu=H%|W)amZ0H0TunSnLC2_x}E`xUUA8E5vDTAZ}5b`#%4a3(KRnFsYP8nX91ayS!L zsMIeP#fz0fLqBm;vM2LHK>SESVj7_-z|I=K&cLdYwG}O}F;R;(P*22QRlu(JE&rFE zf9c}(MP6OD%SL0RzI;JHqETU6*G4lQG+WJXucOmKfy2Xq;~MmEJnXYwjP$lG>akIW z)8Rn277MhY?jbcA^jdmHn`ML&wtKp#nOrLNb?RdOAkHqc#+GZ<m9^CiJKMEo_UPiP zuf0;ORS%C2Ha9mK&4#yo_6!yUHU;{~e!-=?T(7f1dx_I2QI8CU)<qqz;DF$ths7N1 z(qs17ibDohav^98C8v-0usl0#N6lD1wN^#>%qvC(L$YiPR@P89OIW7$U~FFMFe4k1 z)}~YqhLR*7FRatcw6mm9D;kn-sfliB*Tf2cYTiWiyiBMX$J)tbN(~ew%yNL#oB^&2 zm}86$fR3|LY-;h03<yp82_y|<pu2qH6|RU5Mkgj+kv*=52C-u$XZJJ{Sh+zqhVTBW z9wGuq0-aammPw367#W=<x;+lxoaZ<{aY{sm<6SNU4p*&alYxUjX5RFAY`^@Y9Y%$! zZ0{O}BKwqniIdYWOdXRrEW}-Agc5)0ulyBT@{lNPZEf-gqun<XMhIkZZ}W759Ryqo zQgt)KhbLt6%9C)Oncz~8>gF+*X;73J1&OvQBNGkGX3as~*<cIipwL;v^1zGZEGWv` z1I$dR31H1`h15iXuLM$nBv%Lm1P57h4zA0zcDrz#!i)usyk0QffJ-@?ZEbB`y?S+h zeS<8Mn+SwTt(GPt6P>nLd6D5fhbq4l3BT29!KbY|ckU1p`k7ViJJF2x8&t7gzwK>r zy>jJBwW=zPYG?uB<=P6DIp=JD`UEuT<2$`9(=<dY1i*ycoEk6e>>yTOT`pD1oUjQ( z*aL6hzPr1(N5JODDgp@~N_0wJDiGu8XY|4(Sw(?+&2bQWE?n5scOVrs%5Tl%V>)=@ z!iBxv-L0*S%a<;3Xzg}79IWARf^Rijt{#^q+YVhJ(osC7PoC9`)>0fSYnH}D%L?$6 z)q>XR^jmQ+ci5p-gVh07v-j2Obs`Y9Tb7K~wdJ+7HR3m7o-l00C{R%$D_3v1LO|H- zGvyTYbHrtAtJT`-+A4b_Q4UKDGX#C>>ucAqKgM9;YP3iuPT_c!3j#ma>qK9gEi5jK z3xkF+2yAX%z#fLO)zn%P9%c6_R0>PAYDuhq4@pLoalr-4D|)0bo0KBDisr)?fAzCJ z`mg*L)+W5~eINevm%k7bgT)<xu*<+!)&zsz)m!a)5EL5715Cvd)>$~X7lPSCQz5W4 z?6=`Xt~}_CnOSJyJkjYkIc>xc4Tt;RYF_`-Pp9WOudMZ+`;C`7CC&tTBS}$~wr~c8 zxrb(UK-wK${?VU&|6A|Jzu)|O|My?JfwB<RO%P##c6g0}KWSyy<Az(!3q9jXF2P8& z#hZSBDzY_>%6jRubSAB06)p1g4&q<^v;QNvX?*T8|E(OMfQ`{vtLcp-&0&-=%Cv$> z8yoA)5JJ{wvx&#zi@^-vpjy-0YDC86cx1Rnuu@%Kt}|rxg|<+PAF2fKToJL^fH2sf z0PEx5<>i%-*N}w+bRFrXQPbq%58bD;l<5Rf(szDnh`kYej*pLc>D%m`c5z9+-7gh_ zJZb-s20RbU0h;Pk7fLb7DF`1%OF1Imn8N8^ilvG)G|%5hvR>$QMvUF(q%5b_%}s-8 zNoOIj5I|^vvpYUcg9RQa7O>28YBz9B#WPIQY;-1S^O~o!XM}4R8H+~aN?rs@=F{_H zsuo$p+0=UCECN2ssFRpdpZyg~JJnSmgbr~0adY`}kss{;S)6Y0qJGV`y9kR)7u7j^ z9M6lh+qno#T`Kw_^4MXaSDv|8=>LV|KHsWEdN}j26aaTYh`zDpP|gLNy?TSS)s3V5 z!xx`_@$Q|wE32!QFI_>yy}NfR`sN7d0@W=LqUvTY#Q>~aIweFan1C5hHN)&K)sP*y z06Kn1Pw--b2iOe(t2C<g(lQu98rwsu<WGhld*bm%v-#My>&K18_JwUPzf?yHi#&S~ zO9NT9!g#)g8Z^QN*%Sn3C^hYrMJ1oj#B#(8=JOZH)6FT(SZ?EAAJCH&ikPTPOs6!V z;tBAlkx4%^(3w#)a6|4UP@`c_R(v*`q93SBA&}H2&P;m0T}e#9!6_~QO+qYW7HOm+ z%w{^}FH*!1-rU?|(wfP1<*da%NGWG^w85v!T%b8kc<>kh(j)pAB=?+#0T#%VxR$s! ze0f+PI-48*pi>Gg2J-SIf_<N`fb|=2oSK*mm!|4@wQ~_>3OFmH0u)VEpGpn4l8BTA zh*>gUloyzS<+J7|FcUDM$l!DO2%juWvM6-NXJKK)kYV<C0?o=J1`x9uh9v=uC`+AR zc`zr5nmTdQDN2Y!IKukQpE%1Bap_<U2UC%;F;X~r{u?P-x<c4%Ggwr;j4&292?50T z8&4?Ihap@Z9LG6;a~ek(Cv~!3$(i}^Ve*O~ytuo&OT3NRl@+RQAVMI9c{V2cp`Otk zYU783GzVxDfhZNoVu`y6$O8B<5$0OGc=6)3Yu9eyzD=-AzX-pnP7zl}vx!giLj~wB z>sOkHc#ET9X*ekI8ua!3Uku^pJEMpoc;OJ;AFI2(WgFEoho(7{dK%ypfN#An*f2m5 zO~57)I67+B|1=HT_k@`4=<xxKPPa`YMXZCr(ZMSmU!nCuf7EC+aFq4a9pHO?>6cdn z;E^)uI6yDT^;U6Fzvo8qj8~CtM`w@+5UqA|phpDj)?AE4Cw6ioko_kS&1u@l&10Hu z(4+u9bt78SBco^qhocj-kB^VtQ!kzN3@Nor#d1GBqQuno^;M?U>e>neu3K|;1?X*Q zjQrOB>p%ZCxeS+o^hbY?Kk#WCg@$c_Nz*95_|6~9{Q&US{y+cKSF;fb`+dPelO_Vc zQ55&HWsqAZvkQVUQk<X<<@{}kC57pLY^7SS)b#BawUGmntKY0b<^b&O9qb+)?H?VG z>>uv)|L~B}qZ}C;3jI0-=~BfOeI0s<5o@=)t>*ow*=hLoedE#cvVL@$NE0VeB#Yxa z6kKClTU!h|3XPZ=SqO^H0Z#M8NljaGb-BJ&(nHG`yWQQry}f;w6J+oJRY(y_RRBZ+ z`~<88a%#Y~0g9$1opsR^rX**eMdNI*bAxW;F=j6*_Tvyz`kNKMk&r6`&~}U4&A2&8 z`VT**hW;V?MMb|1t&ka+;q}jlMbMm{2Nzk!Nd21X;FQ=yLet_=z^bg%NS&Gs%glo7 z$fe9-E+ur5^%^o4(fAx>#b<_FnL@G?g3Fl&%KMbTVt4D-t?z#KyI=d-*M9RifAh81 zUSkPm1xV1>ia6QCmqpM}&@aa885-#oUy9ONfm(J+;B^CGy3eZ1DTRm^wSZ#)S=;H= z5@D~gFcEt4si)rk?svca?Qg&O*!2q+ch)x6y$+D#5LKif91G*Q7_8*^7gBawIFH3T zeu}T4qf0nodT@=o%-4r#Re*LM0bO(H*+E^>Ojp26^QVxQh<Uyl?0V+EaY%;E%|1Nx z9S4bNJ}@(%&ILt`0%PI29u%0?ldo<8rj~^f^Q>l~S{~qJ`#BvgtdMC;MS!rIQ`?UM zrIi&uOV%a=2-AsU%MxZe0Ha+IxR#L>Pmpm#xf{*Po6h&m0tQW(<06nLT>#|grsyY4 z$aICaj0&Wz?Free@7Q1(BzqDk$vc|}1{K;iBqo4Q6$TY1LrxYZStKFU^JpS9gfO%< zkU}GzN&z&m7=WYp0;x1-*R-irgkVu+RVJ2Tjv~+eW2Ga#aN)wed-ryBc35o*2$5t4 zQww2AF`i)QJKy=v!Tuo=wb$*l{Km&T3Q=er$;+27Q(YhR#V2g&A<o&|y*C;#t;a`4 zM`(b#8DB@F2%Q@n8(!IMBrP83`^Nj<{=MIQ_0?Ai1RBT97hZVb<(FT+a^(tFhjnuC zup_LluGDG@q%ni*h$iS|QQtnrX&Mf6vgfdi?Ce~?u$5Kao(=r=6~2A$x#t+P#~yo( zD}^htQmGys?sJ;Ql6qa{AwxI2+NIcYq<A=Dnqe;@l#YwK6^S5usn^&28&Oa!7c0o? zv)1^am|3IWRP7H4)0ioKyOX(s{&?rB#O8+1jm^z=M^DV|cDfsz8`zGQ)B}X|wd9z7 zF}&DTt|}UY!>YkJ!X?_oIjHu60u$r$Kq>BnqFyvt!SN8tBX)3bh=9YK<z;;bgQC%} zUoMS`OXF4t{lgkT&eFKo*LxE*-PKPxFeU1P(XiQUWA<<Tv)}lUA9)|lgdhFU4}9)( z&!8V0<fh5A_w=K`r26<gCM04M8H^MTgrJDwqas;s;8N)54Vv1~;nBwWdb`u&urU~R zO2tvBteeLWj?dKZerNa1Kl-l8r@)u46u$Yz=NmCcW6TUn&>UCmAN%S5$&X&P@Y2#Z zf8jrT=61Fb%EFTmMWdqifI=)|R;8g7B=26tcP?DcWu;Xeuaoy@x#*<x@PGPG|C`b> z!6$zC7o@qkR4yWn37V<MGY2$06|R>$2QOU24Dlt2dr4`R(YAS{v~R=6;zDOp#Z`lm zVGr{>dtQU>CPf}GXI<T#z=)}>jxuKP=|=E0pcsV#$43pK-`(BaqoYR5d3vXB<wo61 zRca*xPC{Sz!)GwZgnSvWs*K2Dl1wvj6_DlU;6&38Kzv6|e<uo0)ojRbo;DbXPcW1I z%Ggt3&1cX*AJ$LxX$`SF85t)ql|2ir#K>5ab{D~t`SiS)szuhA+pY?7GE>NePGTNA z&zdfNRG$E!3$i|^Cr^{fh?6)Wlfxsh=5#Ewa{*3~@Dc=pZ|z>Pi?GQ56lK&&EaK1A z19NKSp}N=Q(Qs5P>#3iJ-M)L9NVrlhU%GU;-C@6@m7;cg{dV7wjGCoWlO@R73>1>G z%6Xx46KZcPJE8FgEwWs*dea=IBg<Pjfqj9a7Xb$+t2=k@T)%$3aeO>p;&4)ApF<b& z0G(vfO92RT?!(PxnSf+sAz{hYpQw^g7h`_uqFV5?o=gS;j^XUNkkt$%Rz~D(fMB6E z4MJRi#>HknB&=-~ZYbYb6X(UEih2I&t++H_f>=Vv%1v749u$`VWtOo9=BE#zmgoHG zH*}a$oK*-FAPfso3wS0==gAH0XMXPIEcTEn)#IZEK*nuAU<9q2NKH<`%#<Q;CB{^# z^+ZY5G2kLI0W_H9&vJ|qUx?IVJ_Xj6ybK=>X%d)1zV#^?7r8owR7?Wwlubk)sUoRe z4GqCUMhXolS!l5YXHkMMgy)CVM!8^_Bxyv6m_{smdPR{53B(~--&`fWW#XZ{R#PC# z85@bUwKbOV)wp|>pp;U~01i+QW4*X}^Cm{^@97p|nB|gg{zWsLL-NTdpCn8rSc?wI z5~8!$Uc0fZXDlg}Bly|c+T7S!C*Xvjshyo|2n=S&*x%p7J@<C+_IiWopMUY?mtLW+ zKcOWOc-On$g`IxjA@;{z%@@#s&c2=|)x$7shyWO$%ZHeOG4$xtCF*4XFsg3dxQPt$ z1K~G;^xNP5_QS&?nx-R-Ml(K$rmntB+v&9Fb*IzscKV&pfGC@@I_X&Z8BSFTjI(Zx zirY<@n`~Ia{;1O-0`AKUJqLqu5_gQ&R#tJN?tvz<Vk@l>mME~njVfJV8}tX5#OhJ2 zS1|*HtRqB-)k^kgA_5^Cj(@03EUNpzb@yY5F~t(r8qyeR&089ge*O4OPsZwCCW9#& zkF@#_498gOXQ)sGAIVO;QPD$>mJ~LRN9FjcHs-Idt>a}}i{aHuU0?9%4vMAna((&P zXP<fRdq1cdHo^Pe_n~K=`8X2*PvUSmI2_Ofh7hZx90LG(%*HL);JR4oKoJ5BOjIT) zYbX{nOa$cZZi|WB>o<p^E-$IVEXJIve)H?QkNt^vWI^rPlW!@1`!}C!<BD>bDL7;y zULs(Q8`g`(cmEsz^Y>3a|GoS9|K0!XOWE%O(Jm>rVM7>@t$wzjQr!kEYK)i6!KwWB zhU#e%qrjj?x)dMoB0@M_(yvA1=b!ph|GLU1_(#9^Um;!Lv{R}S%T*0PSc3j!6*SWT zs}#k?yR9}aZc~@fm?0~gV|8q#5M7wzS8OyolSNinE1)_+GnE0Yn1fD9$9oebbU+sp zCXKzAXj#LCxJ$pex3|yh@bI|Z>W)V^w<6m@k2)3=3}+J(lPa`slWd6z49M5Y<g;&e zoC|X1Sy50Y^>@;AA{K$m93KL@jK^?J%4QM^V9gKIzX<53E)C^PB`bq+a1qGUXM{Bv z87tb&sClqtK0Pm{YLPYa?Pjb124&onP|-YSCdamzd*z^;{7$^Iw7|~w$mt?KWEcMo z9ylKWn&)Dw?-_Lx3;EgKX@ufOfV`qJ_A#SQf=iwvFFvGjn9MLu&qcI32U+n+EaE4d zEs(^_m%4zBVX0bMT|YiN+CA9q5A-Yv%xkt9x53>z92i(zsY(~<gueJY9<c{g8x1H- z@G4;fK%_?5KqL_yWLWUoA6fae<i@E+3uOQrwLZz<vX#|UOn>5uCoob0$<h)#EBu~* zs!n@xyse7C^zh^*5VugF?Y<3mg80D-z%)#oIS=!T7FBWgNuiN(2TARLv%_Xn5x6Zl zQW7)NG9c0HFPT6f(OmH6JS6gs<^ex73T-6L*+H$0I*G(br)fK6s)?+#S-g+|u>@wj zotZ971oS8uPCye^y9wW|5Z}qt=PO7uS1F<*oK8H_2r)PyE)AV7d|uV8jPo9VAp7t9 z%+G`^4~r6qdpBvoqCNM7)UYV9z${YTynriOgF!Y)y2vSTqafcdup}^@IC)|&Qt4E> zNIwRU&e{*hM2O$lW67z$0CPe%L&`?EfJ}nh1@?eTAsAz4Q)+@zQcnm7U!Ty{W0^c$ z5jd+R18G91BL77dE+T;3-rhzhv||q<F^a(M?k?34pdzKLp`NU)u*^>EVUcI)ynX8~ z*8;6jovBMaL1@Y~aPi_rLQ@R!ZONmNJ~wW+TU(o(aW1cMh0rvFg)dyVfIPt)$~iQ@ z_S$Q-xPP#(kgrx-TU&3nn&?3Wt58LNed*FAG*}O)*K5QfolcAD>^FY2HFjb=@e+st zczI{%BAu!)b8%8$B<90%Iz@VXe1x9;{r%<T6=F^TPQq!L;{uKk$vcb~f7>krVD^!C zjH8xo?H{PZtBe^7czo9t&ue6l4vxEVn>j23RDy0BQ>$ooAfpL@bUc@izB4&+rV8|) zEeiyV3^0Z@CFa0Vg^*KsjEwtwk`bL_Pp$QOY=<&{EdIm;{!ADH5SCh>$O#~8RZJnC zr&E|8^Fb354gv(y(bMd%V`8PkxR2*zGU_92oIr*3^)&)utyI-zx`PLp3G|765$(VK z{U4Te4j=l^kAMF2pQfjnL0iBC4#Qj2f_97YM$iC)EP#(~fEt?{>vRw&V2%r`74$Go zI?OSA#fd2%d!{FB-~9To96s?=?{H+h`qm$My71dy`c`8y`LTie#p2`d{vZC_zxK|x z5L&wP?BD)Be(DCL_{TPo;!mo;VF)Z{+n6(PT2M#K2fn_r1h?aDD%yOSgM)uUMnbXj z>q#g-`O|++btd?wzx!WOiyeR&z_rzjZwlL_wr*=DH@tG?GFj&8@$oU1tgfz71v_yL z%H0;`QN$=yL03lrJuz(uoc!5k`kFb}yAssmdQ_(hx&a;y;h*~;8*WD)J=urz_D`qR z+r77c=gwWC-%cA78BNS6LB-JB_m4pn85IcA;6#v-1InG+l9Wyey(44iTcP!U&^imp z%!^8AaP9yY<1-4gNs-4+QfE(rH9tuILZF|9Qd=pD>);rfXkaRP7Fdaqu_oPI1WV@A z^J1zNS;PHG%sipud9chB7V#HB>v*oAlrHiE<B?Hk1A3B4c_PtyNO*Ftn8I9na6W6! zkA-$FvS$IG#fMsqGJs$vbIG&Bv35~q7RY2ZPlBS1I*CPm5c*EQt$WQuz-_4jJImEp zquK50kyos}jCZryxOeZ~jhi=ErE7IPTBXJ-HUjUGi~$;^3`Vn=z#Itr9&d<efJvK} zLCWG!726huXaNV5a&F;-!`ATDx4Z>+UA=q-XR-&7vJtR@u=iU(>vk~~e{0APTN-+@ zYz`J9H4+_#i!i@*Q7yXQo&qZec8-~61oEzE4d$p|(yo~XwC7cppFmX>v^y(&Iu^;h zYxLT*v*1zbH{Uv)bt`VsMJWXwT1^0i6F7}CB{&-}$(hNNqC`g&#Pptcw(pQ4z+sh> zJhbPV?=WS?3fiv)88ms17}z9hur_4i{Dq(WS<62pO6zN@Hqp(P>t@`Z>Ab*fY9!iK zOqfoDfuuQZBA=!r!}5s$iJyqM$eWi^6JV-tKAU6!OnPl1!P%sZG%*44Ci0*(!4(rM z;AMrn06&m5C&6OCS*DtI0%i`W*3evO9_9mRB%OkIE)>NfF_9$EA$mBxxV?St>eWiQ zIOzBEfoZV-m$NVCv5X=>oQXUfQl>I|Ea5U>PCx(r^M{8=-42FjT4~N7D`6)Gbgmf~ zoV@AjV9;M%TT{4O)orx!*Vb3JE^HF`amii0xU;dbu9%^!uK{;^ofltxfzpG6!-M@J z24;DA6=P_INRJago61|?`c{Hrt~88UU0YsVT|pH#cRKneGocDQ2kl}l)0v%%*qrS0 za-B#!-kl;m#^%D-hMoZiUV7;zy2B<5pKyYna?uj54D`50eJ6o#5~3a*wL9%Wr%Q~j zK-Ukx;#iFas<0SndgI4<hU9QCZXCDlAEg{u6x%AUP&47EGO;ez3u8L2sDr@0R_XV< z%PTcvewdwZ8%ewu<0&PqBJCCn3Tp=&F#js;wr;orj4Cp_yL&Pt=9>wOVZ;f035zh< z%RR=>u=t9sG~Bos?_s#!eZxdLrH3Tzcc17HO|Y5~jxmgb;Yh##R;mtkf0usdideqi z)eY{S{p=@y?8iPTYjXJD2S4_?&pks2Xg7MTw{n;UxT9KSRx28$U5tg<k6X-PrYxnH z!C1$`!}M(q4i$u5Yir9(OMN!+(XgwBpE+!f`-_PlsekYHp1pbLUwYT&h;LWl_QN0g z?_C}r-Fp5;Gp6j-AN+}*_;Y{$y>E8(d;6dN;(zv^{pu@j6tCcG{9u}aAjOREbDHOj zw1hRG1$DtRHgo01G-LAXvs2V!ziy3V$aJqhGemmu^vC|hp9uppeEjeKHyoVGdc@jz zb!|-^E9%qrdTqH{sX}b5ZxARl$-Da5j6NF?7mgmXLMyUI7dUleV6(S5FqL$?q^~OI zuil^$FwEWIMLbM5vHa-hkn7Q6^d^K^w|U_W1;EU)P>Z80!zKN?@BaS5?OS(l-@V&v zbw+w90KKC@{hX60zoxDr+n{6J%V;_nv<U3Mdnk9x<TP+*h-H9wb};lW?KzuLrk12; zUV(_R&-BXbWNPz-*cp+3;WAxoz}4s`DNY1YWg$Xymc9<qB5j3NHD;t9U-;;}ulDuo z2i9X`tVvsoV99)XUQE>@Yq(vAsWi>ADP*NH(3@px_+rFQBD+}9%O42Mw!6p=TIJ_q zk-VEhsWLhJ0=<sESsEG`;>b;7QGXXf^7CHjMW!l;(`U#c|DYrdG4Nz2>nm$6EIEY} z9?PW^#ouYbr=h77WW~{)WEf@LPB-45*ZYqhec7ms2n#Z&6vVWuvU3$nE6Xd0sS8>O zV>M)@&|Av-VZiKTG<3#GCL%;vbw{Yy6L`rIH9vWKD*=vI%Sye58R*0k!eDmu)p!IZ zDd#0rXhA6IN9u76y92u<s}${_S=|$$bbtYFE0`dz1s4FzM{28-4ck)+=wn8mM6S6L zP!DH{ayFb5bTe~J_zez9<jI)SWb-M=L<2Ar|9($S;=aJyut=WfY#0J=J!LbAv*8r| zr04_?hyj>##RM*L%3KVdU|~aV?o1xqLUm>u^3`$$|LDtjw9css6N-g8=l+!y(r&-k zXf}_V4V}ojG<rQa)(p^@Q2}NzK&P8ChgN>}FaKo=JS0k+`X-^K1)v$=0=EaC%{LM! zqy*D>&J>cKJaCrzhO-_3a|{bZq^5(N5h*(h^r+@Zz;|jQaq>jIBQV`=LRN6H*ZHDU z-OPl%T4-R0QxxYD9Z)>dIKg26MV1GlLvU6H`3Qh}@wgfe(8#;Uux8UHoWc*D9`t7- zDa{L9zjp0SZ+a8Qbf%i^VahVs$s&fG?|kPwv6<)#17I@yv4L!}+5F}=zj^D{?bVg_ zIBEmJCuTWulorZ&zxxL_Hg$F<03Hl_$P?FT$IyqUdiWNxD|%R_X@#JarVkGf@fFQc z`rLERZEtTA0B>K|+1)=td)%F?J0Y)Mzy4?c?4RX~jwSY|qBVWI+&(%w;`omGURNJD zGtn>`dsG}JQ3Bviu7r&Z;y^ruCtiI11#H6r;(33Jwzaj1bBOUULvNRIsnel?K6WO| z+r4+B@AP)#JNlj#5gXtH^cUk>I{asuC0wHQevkc+Q7ie;M4I+76zgkiNaAWxRgDTU z{Kf{%5{z!Iy|%W}XdJJtuXH+k>^6IqKX#V4`%J1O!lCtzEn1+}Mx&umW0&jbK^PD3 z?CdaDiqK-h$To~9YhNTxq?>BDTBE1*k?K1;7wJAr7a9Npbg-+Z_-ajL7HhXI6*YF< zp2D8tn8lF29;=2ULc1Cwl(L^=;-^3TD<AsMkJD}*ANasWo_+RH;YNQh$|M}o$GAik z?NG$5z%WX2zK0C|<3<FqiXOf4(#w?65K8v<ckxfFdC2ID$3#y0_!s|_;(?gOLYV<t zS>L$vwa<U!PI3Lp+b-!5&uf?8@-P3;2R`<Gy*~QK-uaeG{<);PU;oAb=l}V0FE;R$ zZKFjzMl0BWZ8(S2R}Dp)6~3qo{&KSHXT^pvupfhoCn<%d3rvzynG0>C56&xkCo8lS zYSqezKKj#PM21iP!@q+QiUp#(QKQv9I@SZvkc}NdPYpox-Fx@&24@<^iujYMO7m(W zJ}E&48{&-vc@=-77J4*RFsuXD{lF}I7oRYr7CuL}J9q9d5KI*;C&hTc45W1_r^}-; z8Rird45v_d=k~q3ckk`(ajEJ@yiv;()yfx(jsA!05;2(o8PmWdrj{luCQbkoP#S*C zHZK#AYW+_#iJ+A9;UQh2HvZlx7J&dM%+&5iAF&^1nEU{HtoecZ7Xkft7j(EqS=`8= zqcg$6uMe4uK*oBIpDmeB&x@&AWR28rmQP{}?71&+5**wz3d{+Br#WwQ0GxnYBg+R; zHdXhC&tj_L1F=Z{d|D=$wQ~^``G+}7iXKm62vnK*NU*5CtUDCVf&~x*5_F{jy#Y#v zA}cdX<xp=Nmq!IX_>(oBDu+iLYL2)ZIR&v9P?47DhT0Cbbj|RJVb~IcVRn1k@)1CD zem!C3XK!M~28mByB3t%_!~KJ6*RI76TWmFt8=QGK>2d6#3X%x0yjS!-<~V*@f{JP} zkNhWrVYdD%i2&F}=F^GHG|n3U(^HCo6_Oh6;Mw6Szztama97RDr}klzCp9s%0A$EY z&x}R#9(oxz={qzWEU~~Du}Hu9)(;KbP4<N-&tL(tC;(=frFn=jbDOMm#n}r1NC;An zF3c{XU}U%uI5tRf0!|uJnq^JE%9)~`*e-okPk}CNZ0J!&G?P+50Y>LxX^QmbP;B98 zRLr+P0vv-*W~_j<0W@S1xw`O4;mlfMFT4Lbu}w}AQSZJCMTRfw(2>ECRDqw6_*8+m zug$kk)y%=d@JY!gC8-Dvl%g%wg-9c988c1WW}ll=>q#amooLhq@?Lqp%%Q~d2_Qff zl%Nfu+&bL^@-QJV5EJz-4O(eX&8VTlK;!$?w>*i}7q@p>%@#}lcVGH08d1esNsPfl ziF*<A><196=rpt&YwI_^`8%~L6J60DVoVmME}_Eu`kJDtl{#VAtFOL7NJ(8T3fgTQ zw}^YuPrvr}_o+n|{@uHGxoohRcnm(<38(N2+dF%EN7dRgS6R4A9}umr=|PB(J$4<P zoR+bXT5#xbyWNT>PW9Tvz!9;d84r;nfCemt;97_nm~eV{`Qi?eM9yJ<`SRt<obxgD z)mL975@@v)0HdG%3}-VR_xF!kuV4~g5N|O`qwLc{Jgn0%gRFa#<9n?bTrJfxgeJ<R zN;$Tir7_`Rg(mb_FimpJ#{(j<4ITA*X)x$=%`Fv%>l-VK7X8M<aql;y#>!Y;UELs9 zW)3zQopPnz*R57sGNPw!)w-#bg$y4OztAsed_~i0Q9oJ4#Na~Egrt=9YGY%Q;l>gs zX{*(wl(8V&?{+WlT&P4$qIVYJk>HyfTPrK8`ik=UX0z31KJIK^!V~RgXXoOj-TmG0 zd2wzG{9`}%(O>=5XCY`B&|Ixv!)C0DsYxrGB#5}&1-)vuI$=4fO9|r3mFmjs3Sm6` z(v9&Y`lUO$h|~~Zu;{UF8}1G1xw<(THE;j!H@@=mZ~e~Q&c?OXB_^lMSz5Yt>s$Zi z*S`Fz|LZS2^VL`OI(V{D)sHG0j4~eNii2i8lj1`_@4QCCVeDDwdC?b|#y@c#>wEI} zoOy^<m={rfg)zYSOb<MX16fh1!VLQG$Nm&`68_OI{=aFu-D<C{ts%f%U8BEXFd|y! zf@fc0$mlGC!nCQxm+F}(IEvF4jzUQoqxTwoqJYEffC;c)tN`(&&qEsS06l&D@yDNg z?m0O05law*i7Kv_;Xq%Dpvv*_5oRzhIBj=#?}Zm$V3IR)7)tEa1cTO;qb+p`B~DGC zHYPx}YnTaqwX%}pX9&1h3*f{OmIGM{WnT<IA-w3Xjug;tYYI{Gei0QjYJya1$*BXe znF(fEiLAs7{YrMmK_KhJq!a>}>GZyS#K=!@qSYMa*?FJ{g}%(8X$vM<ya54I^C#zU z8xuxlrUIJ;@<m3XEs&6^oC0JLk_Ho@QlQBEDY!>jCJ<_bEI+Zq%td~)<Sb4Ez#0J- zUTMp!P3pM`5CP8wQ6U3e%j%zeEoj;bX5n5y;Ba562&dK!OD4DqaFK>>az9~WCWL~F z17R72^F>Y#YnTN^88wBFw_0aKcw8p4TK2I<hn-0eVo{jcuXg|^p0+9oiy3JqTZXx9 zzL^QmBVe@_&O<Ueu;t{LwBoDAOc0d>Xo@gSj|0&I52PO^W>Jr042vfxg1z0n8#iw@ z8qKxUwTnBKs+B6Iz~Nv>NL*(XJv!=kIv2LK++;jrQ(!f-0eFS=4bUQsv-wPnSZuZQ z#mON%>q5|9ir5Hu_xCPcyvRB2;-yRb2M3KtgVp@vMRJ#@!hz?`-Mfd!M};Mw5?Sfl zJFviNIU{vDTFmJsYA5p$6Nq>451|gm>IIWmp0-$eC6B9k;zN))Q|R?Oas*zKR&DX@ zwEBc*s2j5M;_}o@+SJu+vYVkx%&acEp-xbAMFYqSf~+KU7oNVkI(fk>PLxIMcrkEP z6%j}VJBw240XzfWOlM6bP{p;N)x8;@ic$!~pq)*1EfYGVBynb88Pl%rQOoN$+=?X) z%Nx3#QSXV<UX~_Kt;#90#<7?A%Q2EUBO-o?KUyP3qZNG?!V4xd3MMn3Q#4sLG@BeU zk<>BClNNilEycx47Gto@=MbCy$O2$O5>%rUkdKbv@3}do763L8Tg`WR3aBEDfs7SE zLq?qh@}zlTb4alVK7={8(DW>(^hf&{oHajRJu!j#PNR~15+#Bq&7T7NRLd5s!bI3K zNbO=LGA;$FU6`bKn4eOFT`|dr0>PXF+rTK3n&#4%oa*qOB(#ZD;K+->=Egemgkel- z7Dv`-Le~CJpY$Fa9B>XMAY?0IS>zN>E!K2aQV2>3Q=fnCg=z%AF<-S$u-4Ey+9F^h zQYu$CtarFPu#|sT(2XBQL7r8fdGFyPi%x8SrY$`};_h7tea4D1;>IPdIF?ymUAc1Q z%JOoZ>IAVciBjMb{p#)3BjQ#Cu9)H~^q859uzFf4Z*FeVM}2fwjcr4RZ3Xr(zx*=B z5RFse__*<=H$6cX!|0u_&rnsmcW<9PC_Y;wXw$<LaV;0Vh8IeUDu1&%Nu^Su8ox|K zb-kyG9^J26t?uYc%i09lzf?6&T}0N8J$7YfwMOr_@`$Zy2=mZNkV5Q1qf29b!Ifye zuvCswRg3r;pxoV5D-{LXbey)BDKN2~XjuZed4)i%Wo3pVB;{es;ZU8}4vmZzPUv>q z{9(z9&4E2wA7A(SoDW9z+A>=+TPFI6{)>99l-7;8G4Ole`@vuPwJ%T#=vSEqRE`s9 zRNaUxg(gT%BS}R#q;v$a><ZJTe<Ll=h4D(ghGF<Z>u&|`l{souYjr)Tds4U2c<uSG zfBrYV^6_Us^YJfz@zcNZkN^HBzVOVqUi{9TM*8)gfr42bGla}(5eMQoCM3-0yR6C# z%k3p$6OKKxWWi@MCJPM*W#jm=0F`6L=%%<2f9%93z`yi&{!5xhfXd8#j*3h$3_w+- zT*WEKP!kR+v4v*hEf`%YsGMBlnz53U8vbipm;rpmWNP#{3rZna4VVvHS$<%<4@OA( zQs7#{Q8<~V4i1lQ-@e18hr{Aa=~645O8HBcDsshK$hJue=mKe8-bITv^y7^@TE%i? z>}UJR0&|f{PZt9kg~f37yf*yjES5kRF3kf|&0nN{ZY{9L59YhpY?^8%<`gl7Mf_PT zvgdSIc|JY8U#B3iBu|_XCj;QXBmgF5Nr_Y(r=HNWSY+q9?Fl3TwM=H<i9HJoC%6`v zSevOzsgb9Rq<>oY{Qa78MPA`-Y9wp(fC;#?UFy^@oyi5@n6SVUW{aFnI#VfYd%hu% zicCzW6X8^A93}i^@nqRVhW&&SMT<iT%VuDEdmD+}d-rxO?mY3t6C9<o>P)YI^}}?S zPZruT7DxoJusPNE(84?E`sx~IA+~AGZ0l=lFxeeQmnT1}#92u9X2*NJv4m<1uqudX zPtFG(1>p5Lfu;?L632vbB9p_ESb|S_23f=)NWHJjBHy%O&5QKwu#kfoQJvkNCV=@i z03UMcQEH~DPhc4cIVCh$2HJ#+BpR^rBIG4gb;CtTAYU{Km*&%{>HxlrP6t&iY52o1 z9D<9IPMkvk42=LCbQL6*mzU#^rbn`IFle{i77izCn|5_nX=w{sxna+v0X(XQVCl5v zCY`s%d6<uk#W?d}1Y#C8K~YG(fyg&B)$VNTlzKc|WO+b$%$Z67rO<}?ATdqkQ#)rC zlFqg0tQ97;AQgFBfjP)vIdEypf_(J^n1=NvCBU^(LlAkIK!wP{_k<SpGclT%Xkaoj zz$^9T%NH-LZ>;jFSIf&Q`q+wD%arBR3nHWxn2StnCN~oU&CFMpNPp8k6lOiOJxn&{ zI<26Jb(Wm~vq_ObfZ(yy?vX~=SRo~}tJhXwjz=8vYwcE-pb?_kY|}1!(2QE@W*P!; zC<3(B>9pWb>R{NCfKn9jitlIM=R;5(5H--yg$ozxGFt`B(JA=1ZrzF3tvh$_?C$RE z?-TGV=BJ2jnd<Uy06MZvIYmRGVUZWH*wUC7RX5@igfa@WOlz1^sg|m>a<A7x4_6pj z{Vwa;8ZkM(x_9rMe(<T$!1<(h9emo2zEo+5NR3UDMj3^SU#ij;9mfecKYYSorN{0e z!+H|-;*Bi2Ft7(Ps-R89lQjXu2zm*>;dJ7I?lI@Ycxbk#AHoncU0NzsiltspH@eWe zZh@WvVemKq=D&;Z6#mBF_+K+I;v}Fqys3!IXtVv!qJh>C&TNeikTU(?`?^6to40-2 z>yC#5IiE-nwdm;%y4`+fIFdt9ZlJ*_`cZ{*P(oiw$&%9gVA$8s7ZG_D^}|tmvKyC5 zJTTe>Mg2jq)owPL`jxEcE@@`3Ip_o#OS3{Zz{jBAK_*0avXI@_G6f<@Brztu)ERVJ z<3V3{9*08fM~sxlhT$P`^wnigZ?cRgv|qEpR=?sSXxyo1VvU)WydZl04zFhG81HRv ztzW#fU8`3H!yXqJC%(qfA?GUUVqvS<zJ2>Hub#dtk8Aa&L^uw2r8k1G_Uy0op<1bP z{qoYvwp2>4=DMEq%D`MY<IBjKcjAS=Q)&WG!KuNZOc7vK?2*IGk>=Y4Z)l^h15@UG zFHsof-zPekVR&^evf?vC%R+AHi$zQOsY}m=sn#E@pV77mnM4k+!w+;hzitCGlV-&; zcpXhlnVNj=Y#tQN)sL`$*FFET<<+Y0{9*@UdtyDlbL;N6zWL98>!1GCCqDiwhx-Sw zz4GcSue@^Q%9U!l^3sdnU9QFN0~ZSHM*h)Y2=u$->_}_`oCHYO*9^B}hcIWT!SRf9 z0%w@DjrFaqElw1y&lW>DGSqS?a$$S>skgl49q)L@JKy<EeeAKe!hXTp&cq`yrXs4K zH4i6`lk`bO*#)qRK$d^KpixZ4as!3-Kvq11MdOuGr-Hf(&gPkkmgof0MFD!MXe#?i zV4W#7@jU@!p`$|fMu{fg>Bit91Q1K^Vq_gVfar?gEJa9KXJS$dzUhYtdvkX31GdR9 z2Ovb2CV^LBI5sPRo`<$`Ak#jBtat`)H_4DqMw&070DKdPss2p5koZ#-En|+6m>@(1 z(`L?v#Xy!nX^d0DrP0)Vri}#9E&_Pi1WeZo*$ghSOvXBCp#`RCjbw%>$-rtzb(q9^ z4k{dUQEPj9n_%pTC!S!<W!@up{rYv{Ku*2XVs0SMDhW+p1S&)bhHlTy&ggDEH0Ud- zEW%W0OCav0B1e1$8hU6Eu)B&FfB-bhJBG2IL#udl)!AT}j+#h;*LSD1Nbp0EX+RYK zfz8+kFq5pSBaDT#3!f^w^QYS-W&ePnQT7#FL6#I68QFVc2<T~nV|Sdq34ND_1N}A< z>1YTC12CBwUbnAfBu(2@XkhT|F~E+8fpFXr1lWo$=ogFiQ%`Ga`aL8XqZf!lg!d$g zGa;-TCRvy$v}fdk7z^8sDS%R#aFD0_j<n&ZGjaJOwZuZY?^dgrbg~A<+Yv;2C{$en zCu~L!Sp<lIkhC5E2mJg0{$GVNg}?Q;{-dx~lffMUGz6SYG;n7D96W>O(4nwjZ!Q$8 zOXG68t<M6PBRY0;bbkS0;)Uc1*fxMG8B=v9Ox38w4}Agno-h=-R`gL*(GE;SR3fDa zn_*JR4zyaQ2)IXM0?Ozw9QZJqHqcXW6>K2p9N|+(o&~+3qC1QAATB`$hd1uidhC~8 z2%8U*&bh!I#u3m#tWEY~Bt-~#{&P{FpHet>1)aqodwU0WZr|JAJ7nG|Zr8(~PqgLM zA0C;y8F1#~N@2)q`o??qW*PRo)<XkL*;+ammPo0ARVG3tE1e=h5}ON4&LS(Gfr~5y z^2~(P;^|Glp|D9|qmXC*fkNIkBhP$8!RRoJK`b)@6FVzAGv*HQ?}Po}D#2OIFq}O* zSYZ;Z&_q@|1De2NZVP1G#h9y#iqVviI8!h`6Pj2RW(wY<fR|I`Sw+b*hy<UnzIvn8 zYX8D7{K9v>^PR`9KX&iVU475%!iB@b!%}wJju3;d(f5)IZH1@;KD2m)^IN@?B7<Z_ z-zUoAVN&?mgF>>T(8vP}X2GQ0OP4Oa=}m8X^PAuN_~Va5bDZN`M-lB(1)vfdRR(kz zcpB`V*Ny0UHuE7+NH0KEJcAen!CBh?oSj7~auwG_f9fd$aJ>EDD+`Cp6F??aH=GUe z`$R&B%t2N>4=&B8-&@Gs$yA5H2@FtHHiH;O%}GuUY|zXlk10;JpABfu+lqeq1>ke$ zc^;X%henBWLPnk(PTFwCoVDFpM#?0hl-^PW0SGu0S;-WV29U7==*g&g$P1%^6ppN! z&=zpkNJUPkKy#!NVXX;LSCLYGR5GC<fU1QIsjCC?NfT!ZxWY0qj@f0CZ`6co(rEC0 zr%(%A(WUmY1>9)L8rEQ>BI^NU%}>Ia0OLimZrmcHJ5qFt=HMP*cCS?{8yg#)R+FJ+ zjV+eToo)}M`}_MWg{;m`J@piUD{JMA8#mC#d}T^7o6-N<zx~^-rXIb+q*cdtC#Kx4 z#`K_tD)auhafJN6dv{r^@7%eI@WI|u+)t~=Vl|t38WxMWZVqa9UVH5|tl%1W?X??Z z2~S96Z-iL1NJxTLxLP>%VoZEhxQ%@1k&?s1quqP^owmYbjG+oGlFB3D6RyUK7ccJY z==Ni2UMdWF-QC^YmF3k}Uwv(B>q6tWxw4`Uy6Ff?u#?~mF$_b0v(awqTfvj-LYo$a z8Yu=7Dt;4~?aI&i#Q?lQtV=LFqSrVX2iEnWY;|jM-J1<I(h}NmQKNaxaD-vFuv{$Z zDb@!EhqrIvrlM|jF6oFrj<*b=*+RG1#@&iY35=rGUQ=)=U1o*BFxD$<hNx8N*Er19 z3t@mN5VKgb5sxLO6$?uQ$Se~2kWkMU?vfINsnU`@CoC3N!b<cG3u=|}P~WtP2v}Yb zJTpK0*-w7(gC7g_eSF{pANkc^eHPo}p72_94Fi~iY(*6&mD<pAlJ%%<y@DuL^(LZ~ zGr7ahbbU<Rr^jm-IVl$Sr<GORVF_N=$C2?y5Qhxiovq8EKwKHB8D{(+--qUep=V8( z{Y^Ey1w>1FdnoT-9}YysFYz!;$V8iZCk080AW&~>)!}e8YrNW(kFwk6_%n42^soHV zFOce&bz8^P8rF=tTFKI1EY|z+^dj0~O2j?P3^d(C65G+3eNpPfOP_zLZ0gk?=s{V4 z7Q->x5!i~ZU)Oi+y&-XlwpuNUR#(^X5=O`E{Dq^V;~O__-M(|r*D2SCJ~x*hUYMl; z^c{h8TpgPSJ14ow6DBX8isnM=Tg(CMq?Rs|2;k?}!VmsCDLq{|m~)G4AT^Osfg5<B z{#0vz@nS6UWAa#DrD=-trA9t$I*&#CStQNpMPC0YZ9P!G>n06nG&@1!=^8nSXj+pv zr4nDDUj_4!6`vWbnC^0{$6BiZdKUR%s)=Y*$kX|{WK)_4t(ce=SkUeR$7L?^%4cnW zlYo8$J}I0e5VC@^d6?<aJW^?bH5)EX$hc=lGSXRt1(UT1f{ml!8`kT~Y(|Gi2OLu# zyM9f-mVR*X_P4*C4esupyFc)bAJBWX>=*I%B7hmJ?<{T=Hh{^{7_n1j_e@#Xd|4iM z39&hmAvmV`;qlRhtqVx7U$ApXOdEw}6s6T#?fSLrguYu_TX7=Noxm8(k&h#g+YSB9 zNw>hkCTq@sm4`VlvSHec=OKwrfm4ZQ{G@4bpyHo@ToxeHV}){GU@B{b;QT&PnzDJx zsWf3KdkT<D!q%Km?U_Yz#eAA<OOW=n8DmMq%MnbE2*(?;;!oPbFxrA(=5WmBfCLRE z4i}oSK1*Pc<w+AkicAdq{oX;te`G&{v=%>u1Vx&6O4uYOaFbz%?6BQ**c@sBdtnw7 zSqaEkfvM~i@}+1XO%0h&StQL&P)ji|CXB3XqAhV!UE42>6HcmVf)-7ubS^v(EDs>O z9=Vh(FyWM<;0dk*p!4>CRGOGkLrR>5Fw8fQr^qHj!$~yD9Caq$aD6Re9NLjtTU~kE z+ulYPOfW`}!F29)db|63#G)u+^q+k4$$R(iK@f8~V52^ho5lSrU-=5_upT<qWombA z0CR@F)b(w#`>gb=_4|7SnRnwSQg-j|9UnIi4-fC%+ogz*_2A$@BK!L{Z{A|@CC)^c z_zi6_{l;_wwX|EQWN(CX`LRadym|BJ=#VPNhpI!;Mx)7j-LsmyVUOPRux;3X`SN8} zd@fNuj~>D{<cZa(P9G807jx@%bn4gqZrp%ibBgy{L9gBJ>Y(qpjbd!|VwBh<w8P-} zcz}aG6UHHWz5-)_-~0U@99l%bmXBhAppT)FD*cu(3kpW+$?`)n7(VTXgd)esx&@uU zn4pI(5#OSXG8!8#(K|Ij^O%D*^wet;okbF)zC*)Tb0G!|9L|AgF`HvR9iy%eg~O^o z;a7~!YDVMOS*{d`O>sxHq6Z$tZ^>#mWz!{2^R{da)`{|Gp85EPKl~G9^LYRJKm7jp zf8+~a_%!yA#YliW6*CV<UBg*?ppH->>zD4h#RZh>VO@n1gQI|4E@1*JRZ8`EZihgX zl%k5h16zXqFlmD!&fdchr%_~iI|?ypDPnpvI`{?}VVD4U*F~O`R^Y&QEofYHKN~$_ zicAH-&wk>UsEcx@TYb4qKuwJ@kvU^9q&LNCrOJF`2s!aE$EgCzXkjwlAnSIGXatwu z-&*omUDI>F-8)hnNy=4;0iGe&5aPPSk5W2D^m~io_x5h1*-}UKzK@P?2+=t;i!g49 z0CG}&4pNKG;u+Gsd=i+8rtU7$SOCN@7(gs&QHJTyq`5>a0LAnDX8o?7PxHj-K<pIB zQ#>{oa`j0Arj(;l?M+~2p3Y+te-`Jp(`J}9ae6}!)IX)<bZxU(B=2_fsR_@|Hx9Jq z<}fTR8gR^<#gzSI6Eao~C^3JwH1%s*U_rZ!knBu)j45VH^N`#G`Tl0C2{P^sA7lj+ zNXewFsnX;MaDrH1e}YS=x|xU&5x5@xHhr_%91X{uouCOVFKlk!xbYfmRIAzi#y7vY zv$ON`(@($p$}2>rRMCbJhA|vk$XI+!dc)Vv!H4j2hphJ<BkF1SrJ-8AMpd#a%PX9t zcDA>n*{h@>td?A~g8G_%*j2aBPz4UEsKSAV1Cra#sSg{pwr4<o3TC?0IBx(<n=YbN zI+!&Yh|+0T09e41An|9QQvXqxCg8l`e!2+%dkA2vLJk&yj{vl*gM6upvtU-z)lulI ziIjDti(qZ}G*wKH_OqF1NyFX%?x~Lo(4{z6SinUNfJxzdu5wV+$6RsSCZme$4CD<Y zsg6znff6eOk1PP*)bBdVP`3vXk(x9T6LSF^TjnD87MKFsqPCE+0*mC0yl`>^gtg&r zXK|KgW?{pu$EiV;#79F)ZI2oVAOMFnPXlC}!Y7@DO+wyAB8(*C9kovwW5P0d{RZbw zQkgO_Af}lvJPQEJBLI`4P$0O}bs>^TCuqHCr}yoU@QIuCPr0bIvb_8Q@A$rIrLw-h z&MX}lme$udj~d5YTU%&&>ZzxQyF8mAh<oWE>mxQmf9XqKs@IoUE14t+N4xyh8#xS0 ztJOrZ(`nzibBAsb?)tW!=25e8+|m#H9vmV9^Z2MiY2&yFLHJ6gh^rMrE1IIq6~z*C zhuwg-xT3I}urNLW?jm-NsCsV?OW17SqyQM$Fzj)bJ?YxDYZou-CxUPwMQba%w-bUO zld+&wKdBmvFZKg!5gr4&%#O6bf5^V$rCCq)l5ZIZMqf_VbFm_286S^WEDGhgHHoG$ ziRgj7W_ek+81=dxA`WU2MiJMtZ_xz&jkV2soncwUx3wD4^78t|`u6q(%wWK2Gu91# z2CMO0(j$C}ilYU_1r4O|+121c(6#t(q)ej2G?%>-oSTH|OUy3TD{?VO)f|7zl`&f| zO~m(w2Xu=IE@Gu}uiwSyT1_9+vkX?s)#FBEd1aaI+do#0T7dlA&w;`F-uK}zeBrZ* z$6JIE(kt3lYR87LqGhswJejMeP#pG$gZ=;>{cblqoFV80b1Y_vZm;j_afQqAv3!Qq zYrKT((1e{ZA#l{Vu+-}h)a?*+5q#ixG-0|sG(mg_bahR>+(H&UVhG!x-cmz>FWcfE z?gAieF6nI%70(91U;e@;FqCT}-gg*{23<N!rGh^puhdqSSG&Ew`n$x=-A9YRZ3`X0 zUZKX7zfb710soZ;bFX@>9t&6uxh3Ly`Q6|BUHs!u2JjV3bm3dw+`qI$*m>i%n>TLU zJU(u+q3P|O7%9CQfu15W%-tWU-LXbf9|iMDO;6~EFte1GW^33Twg}0vx#;V;=yZ(} z2~`+J1|p;9y<`WqlFrkWtBTB~KPFDTqBMG&rFzYLkofxpd(7RLN|Q68fyX+@1DEEp zh(C+`NSz&4o=+Fyf%>PEoUUyaXP37nc+c4>pl2?!;xmIbXejlXD~Ppp5XUfcrZB~i zHU-mW8rC_t2&8^Z3oP(|vTzFU^BPh*+q%;{;3Q<MfH_z=<$UuEib%79ym^zh@}*#r zJ&Wu&F$IKEyGh1Gt-8#H=rzIbn<9-Dh=DI%zQm#Eg%@5}Ut5EJ>-KGGRpX{JmJfaG zI|&0Y5i^+p6j?JVlfk<Tts5{6_B`!V@{_O`zqPTwbpd&lAb>{6M->Rvb~>$*-q+Tr z3u~(!1J~Khu$R+>cAU6VjJB*0e%#`79~9-0adS9t0Ibtfz`cgZ+Rb${5BOF!l`fKx z!uw4lW@PysET%yTV1_x)CO({09U0QZ&tsNj%#}<`Yfkzh+{7ZdVm_VinzYX}Iv18S z;>@Lq;UdgHGgHxDR!6`b2#yVe44fR`Bfx1q0)Y+#iVW*nD98}H1&R!qw%O?;{uv~w zymr!<>lw^3=&+|CHqmn*5D{1es$^PDI(I6YV1B+74W!sZqn=*24W_dpm4U1=Yrh3- z4}?>5039JkA*o9ZvKbX{6=1Phr0Owh@=RErT@^+MX0QYEd^7;23u)dS#OM^xkMfL} z<QWU=NgP0R`wgZYlIVB~lx5iKP!^o=Z+mBlNb$IFyt%P;aCoHW<&H;dYwJfx$M<%3 z-}08X+_-V$i6@@8b?cVDB#c6izkc{LEy5uHUR}}e12d;fOYw*xqLiYZid3mq``r%F zK)F!ZJJ{de+&VZqtg)WzVQl&ktku+S^(x3J6}z1-AvgQ{U^K)eE#j4Gx8EbeSXo`^ zkBDK^I*mF2rp4&;kc$eh(yODx<7TrFPiQD`t?6dt-1~D7XaKlnZEf}H)hpZE+of{B zH*A&&QHv#N-MMp{De%^}z6Cpujt;qo*){+^v;px6^FHAfwq&EDk<kht_QVKs*2mil zYGU7rA*faewiVqG@6`0%=Q_TMPu*9m@iQ~Ur2>4!3FeCh!f#fVUaNh4c(~te9TNaC zq}A#&>ir;SPt`c~FD<XG(v-&5Q5;)sfv%0%{7A7ZR&K)AZ0qYO#LWz*7qrf>;!^q; z*L(IsaoDbTGaTS;bq*OMhdsUfz+7KjU1NxrS5~XlTBFg@?cn9g@lj)Ab5p-IJK3{= z8@dob_57L7eBuKi_=x#=y!X8y^wXgc_ezTb=$N)jxj^Z$jVf15Rh=z#zm~ig24h^M zN>p6XPf!g9_<>rO!05$0K11fctA|e2rHHO*ni6#v#x#ikIf&4HRZnoj!7)P>5EqXR z4m%xnp9@IO!>Ux5xn^qhR=dS)uXB7^8n;_azHYfxuCFW);~VaZaGCU2&Pj*n87SQa zz=Y(O5`)0uW9Da&e*MdzrWTvV%5tsOYY=l{Og!3}E2v!6cMH}UjV4DWdPBsHg9(k% zMyI$6qmR;#s+7jf;Ubd<j8?1J?cM)I8U94r*UptIS5{Y7oAD$(W(wyr_?rLY!v5j$ zE3e(Wdv}k66@Jp27M@c~8AdARBlDK-sa+lXWX4>0ra1+;i8L>tismBjM%VX?sDdOG zLf{8?VFvC#I$fGIZhDd;aGw(gIA>45&6$R{PwNZVbL3}{)mrSCb0K-mtvgL{DNHQ} zfy4nJasrF^vq<fp7uKIzS=8JE^`BACB0R8N6Dhl3UY)z$Q$Sm(Q7_TVXVyfQPGPED zvPR09utH!?;wPkjO$$saP9Z6rg85WWdQ2q#RGNoGbI7<S`T2G;R$$S%AQXvUhLLxO z;jH_cIEgTA!mx(4R~jMiiuxHs#!j2^<k_5@qqnzrZr{Gms&eh>HCCE~gF_ZiigqsU zPz!AgbQzs2gE~-**hU5%RM@_X`h9!tY4Q9NWN6+ElV%t8(o)awhXyzU(C*sCdbi!t zB3af$``L+fYQmFjilb5d4u!y`a$%d3+Gf1xN?_cMw>=fP)0aw#FuuYL!1kIgqFO_> zIy{|Yd!22xwO4H0$%<{;HX7SbW81cE+h`iwPLsxs?KI81p1t2=|AYI>J+Fx|#wn#c zXnLo@CmXLV{AbWG2g)FUgTGK@I!YbFc<HtWlgc!?Pm+yo1Tmj?so83Yue!`CNP&(` zF{dSZ;(tnD9(|l<nb+`UH)s?**Y%e95cq6uDhm$Gq7ZT-_^$e6o;O2kVf^o~18Tdj zySI+;ir6xPeja^R*lzM-QR@^W4`ER%CRpw0RS@2_>Z^R<abwn35>5T_07RY$!A7!m zs8;?^TRQe2!UjAE@bX)-deCBqOOCk;lmlMNLa{=jzN$q1ii*ZkeWJOdI%FMKa1}Lw z{wVIY8Rcy~BtE6LH%0?x{34JPVGlw>bXY;FI4n&BHo@kbi?ls-kZiJ^G#m!ye3%Co z#;xjTUQ;-%IQ#QjqCn6fpwl!9uF7#1c0*<bXmcoATu;#oCdg3}$|J3AXx7D-gcDQO z$Kbflp9$j3J=~4|cKduk1l^Mwoa`O-H_U0vd}>#}BhJVa!y`Z7hB6xsC_MkS*Z1Sl zxa`;>T!7Px92RnD_Hos8uA!0<sr!9}fx?lPTNldkYXqO+kG~*7W|G27G8b0ka}nAa z(1-yUxE2!1{6X&jJFD1O+lwp_Kp6Ma#tj>Jp9#5Pgj%>O3|mgppbC+nxV#cW+V)1@ zu=?uK-pRgUe7Ww4pq0RmAgmqKY5o@?5BeA}ufVe<3+VhcI4_XF`pv^HJ0oIkO)IJn zm(Sk@J<t}xBxS+Jq}z~u^wZ^i)!L=W0-^NmdwZSL`&g#OSSeX9L<Q4&=I64Ty@Nfr zkAl07@V0tmV;jDK?oYkPA}wkbODomS#Uv4*a{Zd|hjMoeHVA%QeC%n?9I_-Ptw$FV zqtL}0<o8*rR_VPk<)hA@Nh(Ir77qfJsV4-E-?oq0gc4OPV{8+=wrbe_qENMrz9RLv z3;<$~E~DJ}rY16LrzvN&=^E-9v~1rc@>#(PhRyFd6DX(k-!H9%dAXsXM+S}Fp61yz zbLyoC!7(e)3rwiDISBprJU6WP?6OxDNdv-ZgT~zuMC6sb%f8inH11rn+r9e_P28VP zwSdpP5;2G*(olk^L+dEdi#nfmzTGp>i2?2e>n;Y*Fi+?AYbV$+;UHd>PkRHPH_|Nj zxMbH3<b2Q!U#yxcTDw3LFpK}Xqb?Y?91C|V+l<WCKiQFk%XX~wmeAFl4oC4nk^uaz zR{jeNb{TmX4h{A7DpJ$BNI#eBtZg=rAR#2KZ)n&DS|ZHtpGO$)vXP$=G0zA3A-nqf z_ix%a*&9P#@)T4>mLaOgDQo_?|2DmQI->PHy5t7(Y%SjL28Ki6F)?R+yS^sw`#Tli z`{L0n=(lm>#$VqMkf=)^tEFCFTxtUO<&^@+LKszL6^gIMRG+DaGl1HpCuO#VJV+01 zvlFVpyF3ymm-yk8JiK|014($Aje|Y5&$e3yT%B-nIE87`?qrpA@+nipkJGZJIQ#te z$}_Zcn(6yf{+sD*P$psmPM$<%X7J4p(Tj%GltYyq&<flGziKM<U$H7?yc8XGDx^_E zLS~HVu8MgzB#uQkUY8s8Ch6Ru-4Fv!Nrr_!cU^8Hq{>l*NJU8Tah)k;SvQU@>M}z# zH`A4K9^#*+(by>0_LdcvRaG%GHYyRC0Tfzc6hCTYc-8B*`ti14ZQBWssI45{I%55@ zg9l-6DlI2BUEINPFr*9f0X&top*#9`{w6L25aHuWODL%*P&Bi2mUkkiDqSt>PA-gd zp(6)HVn2+;dEFVdniqR|o@6yU4agj-%!gsZm%?#=Y<Phrx;n2R(L07YtQl;>9z2R@ zwNt_yR6m6fg1_c^rvt_-mB7D4{2^SKdno1mwRhXK$j2uH61BX1`|&E7(VTzfFeiUE zC_e|cp>67Krg*}z>e$J1Q4~p=@LkJ%NHrfER`J+s$8xx&HZ%ko#^+YLcE?28GQ4Ir zGci}OUWd}-hOISEXQEuYLE}R_!OW#eV`SEmPhUr8z~gi4#sByA>1@$<Z7Xe>Tzsi` zN9eKc=j*MryM;sf08sT=bSHhpQNT1~VKoHkuGVpA9|)JZS7={Nagn+EX3_q{&dXzc z3i16)@&3siRd5aUWF|7t|GOF<Q}lU+{Bj;U#wQ=Df+IPU4XUDw`A|DmPx~&FWexb1 z+8~tUU?sVN(nIB7)S_L@0a(vP=3{u{QQKsLE#As@grta-lp=t-ZW?vgmT2yt9i+>+ zgh_<eSrJ=tYb_&wpYlNeu__asfr9Li*R^5UOO&9~uUkI%>qG*dUgH-SjuUqg<QM7( z00j(QhW5DVl>g!D>c=b2>R)m39}tAQS#g1+@44<9l5;6ODy0(6J8dIbphYm4(yF>G za1qYA%`|*S!&b8bq&IM*4eIbFbtzij04!Gy<0I0$*k&abEKrjdKiKZ`D2Ay|R|1C# z2a~qHRoznrDU}c2qdub)VIr$TYLiCe%>gskL85;Xc0NNOc$IDY7Nqa2$H%Aevzc`K z*j%|h;eMh{);1#|d7jASR62b?ZHVj{9$YGe77-B<s9~*i|FsfOZ6`9-K51vO!q^yx zO33I*N<fr9eOQGHE3fb9L)G3Z<7T2t^bO<=aV(AYt0`r)%R#BvpvJI^0rYna_#DGq z5$}M{!UI}&792JR?@*ARJ3E={>g!#$PM>-n8&(|&2?<GMe?QT8?SK}^FI{PWCn$22 zYi%3#PyUv5v=z0sOd#(Z>1H&IF~0}J>wip#O}F!vOAu`x#+2)73X3bF<(uNI92Ut* z;9mkq#t9`>K3CIcO9IrqE)%<KfCpU%&NGH3zJ)8WU!u4tLaAcP2|fFzlLBBikftnb zTh2BcihJ^gPNjRkJe1G#<znsntLj<w?qbxREg0K1*U*1xsy$u*79dCMry6vjh360c z5qg>VHgG@s(tjhqcnR0{M_Twb7{%`~+bSR%Pn>Jl<@EWigH*cd?vTiBOmM<Lv2VlT zj{F``qFr~G<-V?DntmFl*Yk11-s8l}jxgpeRMKN1#St+hkY<TjB)+L^d~b@x{@N!q zrs`yEmOpf0j7^L`{rO|qvbNj^nc$+*2Th#PQsZF94H>v_=**b27)~Jno^u@}T1oU? z0&N;p0ludUGCQ4_1w8kf7E@iEby4;0a$h9cKBa@;g@;n=MmmX|#;3u%h`5h7@sno9 zj}V%u|MBkGnk^EGf9tOJUn+=<A+Xv5T=dlq2JQ0@OC1YCjoFv^yN3@{OI_W5k-nGX z>)|mo;c;74h0B1g2en#-&1fTLQsG6F31DSwuh5k1M2}11K;qP@z1CoH;3R$JO?w$r ziyzUKP?uV=Xr|fbs~!8nhM&vQ<Z1Gc3L81$m?i&K6L-CuWUq{=2nv9-WbNG1NNY@w zQ9GTctm7o}*rm8lGL|e+#Y{<w&tP9Du|Q{lV2cjo1u3`4QUdDjVue{D)c7E3jFmI8 zMX(E&Q6}T6-O!Y1Q=wEnr`+dGmIWBhLekplH<q2xh7a?6w7;rDT6rhB$r*%jd5xJ% zvu0IYPQHV{DG0OU<I>Yl>9(3T#rK5|nU0+Ji5u^vypoIj4l(wWKI01G3FxlcB+$PC zm0_CV*}ia<99(l^3GvK9vJd>m9Qz_RIx!4?)~+7^eeiO7O}?)YDoG84gwcWu9zu`p zo-apt?{J+^^jVVbkkfCWV&b+|cf0~vo594=YQ{=J{{BVRdFRc5TTd=Ut|TgkmO!*J z!K4;zfY)#yo)?W0DLs!(^c#MScN3zFTLEt@`!l_pyz&eJnP!;r#8b088NyyVCPEk- zX!Yszgu39><B%KR#Z^*T$$eT+dO_-=g7A}LEtwTL{v=fTiGR>l2+U*Lvfn<-2|t8E zJj!C@sBW1STzi*Rgm?>lP?Bjie7f0jh=Mb}g%+wn#2X2~H?PnE2C77Ih(-<GLij0S zYF7K=<o0;OnlhDpY5*ds$w)^Ude|-wTUbk7bnUFCQ3TAkSs9sj1&XZDrdBvrStIq4 zH<~_=t1Xnz1(d6+D}z3-WPFJqgx<VA*)6JlL3f2M$rN^u_N@HK$jF7dAm;wZrA|=J zk(@wTFi_1iDJ@2Wl_-A#R$HG_mz>%OHRZj$$m==%Enax>n9^bCU65~LFUv!YmO}IU zwdxBw;>>lek&eND-`mt$MnFGYtaW>-^eankCVspb9lGv>!qA-89>%WmNAT~n)6&t5 z0uQ|<|B`NI3rURkbTj>_(RsQ3j&^emI(yFRhzg%y)yR6{)t_QJNfcxr^;2sS&ho}O z3)J<cVlG`8Nl1u79_XKJw~zROr)KhM`W*Oc-_~L&^S8^`MS78CX5z-!H*{TBeB6FY zfD@A2PS_wqb}Z#-lV7!Cmhd`O4DHs05cV_H3ys~E7sEv9VGUArcvK+GJiU${&IdfF zx|$i^CZl{E!GN5YKmOVkmSWir+cW><No4qE6_5hFWRecu91S7c{kSu1+>ZGz*05i& zv7lp%1;F@AHmRYJSyCcaSYFQg7w@LPx@4@LM5<fO^xhdVxJvV4no#YW)ATDe^wUxg zg}u`AUjssf3A>_PpjQ&6?n7A>igp^`8t`8N*!zOCGUOm={3lU~28m^tBTe<aP3j8G ziQ}{A+5(*2n)>t!7+s!ESy1C(AGC&zrW|96d(sc#>$c(wFUO#>(MW5TL=&&shP{*B z4MZ@qaGa>Cu_e8#g>`-2j@PfRu1N?9S<<?~4RJLjs8F)XSbcA-@(aNA+~FCLMyTq| zH);Rji83Cg(uoVA3|P#;o>OR+X&slmMX7xQI|+ta;bUJ&=`_)*=Zy{=*e!r>=R>LH zDE9^?cFzca!i^5+ATWqud@_J%KcNP6Cw=gOWlR$xwP0KRmZ@)~S{nyb$TC98V6e-A zFP8z-^Evg=7|uiNW<%)8WC4PJgT9BK&+0C824U(`Ri{0&m94E4A69Z>lCH_Jc}N{5 zOf)&8;GcO#S@zkjXlB>tp5He`LCc=RgoKSB+5v}xK14QAR51Rg+WoZfxH`7YA0iby z*sG=1DtAxl_n(HH?58h#)kGdhfuy3$V?BcLINPY|_C?&wt>RfQ{WDxxo~GaIIG?-e zw)OiuW79!;^^C`WyOcRjpDuG+$2#NCllLJkiPxS{8DC;86GkhdY)%w>h%EyE&hhet z*p?ODcZ!)R?<rOgbQv?R(dNj1AMluTZX0K&K;?p7)yV=nXqt-?Pq2712!!{|s*mU! zn@i=xr*-k?S-JIO!3AX#+%@+TB7{n&Z3HhHw3lqwzRdO-oQQR92cHNmujWT&rv{&o zn5V|@1bDFxmoY9$Kf^iyvq}o;PkljiGX+QHKB1<Feb^K*rb41^_d^FP5ks8picuhg zij65Plme;zNj3m~AlgrFa!y?&9rA++c;^tE4$%Tl7^bL)t__{Vwd~9lhkjqaKtsm) z+d26Y<tK%+p1DnC9h69vRaP#g`>22h`|AkV%k|F3#<<X!ZLF@YIjvd3cT!8}aenT@ z{Cpw`+O3TZW69^TGQRTO-d@Pz_h%=7<)d<eG@|-W3|M_fth|pEjSNC42h2#mXt&0y zSp5qQ(dU>CpO%*_3q}unz=BUDlBRK;(M2<iKw8QA`g((YcT2y2@VWKA<fTlIv|n$p zXXU1?qmz@VLjRn*Vj0Ko_A)c$s2N&xscl&C&UH~OcWaviKo8j&&2fbt_wWURWkXM< zkG&#ZnqXB048oQ*MMc5)TU?6}T!K?G7rr96oPJ9i2Pw2=L-QU_nV^uZIO<0e`djki zaPqa#&PGqwDG&EArRK<$P3y;hkP&9tkS)Zb^kn67LA2Zw9NQz9;YiV8G?mx{WKS!F z#k(vE9d*8Ot^9?nQiB}NJT&#|7Xd~1y=Q@+MqfBaZ&NrzkHu$|;siIoH<7}({}KcC z5$26y<m%S!C=|(pboC*!oXR-BG+LAV-^#Xa4(T!+>r7oL!Zgc-FHzpf$DrG_8DDG6 z3ov1mrwL^iZm^F-01l!Uvcx1Low~F86Q1~qc>Mk%gj}Rf@-nLr(ZWbJCWV0S*#iT5 z3?sSH^2aFtkIFS}A<P0Fv<&o^k5rS^3+27IMvLN2+7*wyoDUV7d^PLzK5UywdwJ0A zjz2pIr5212N0Ig%vf2>iy{~Zw4iv<(O^gv-A{YjL_bfQ`$aMjx>yW~p>$P4y17Ey% zx;_2k=$+YSr$c^Onh3spV!MuS`t`sz2qCP0w-K7fXoOhdyaY3*qGiO7HXCyGz{a## zrNUB1Q)+T1wyI8#B*+Pku90=buU^?)9y?Jb<>XjpnsAj-WDrA_2}>5pW`>G$ii?(8 z)`n;tbnc>=(1n&6EfulF>5>cuvNLA53<H*QeD}1MV0D5KGC1bTfO|C@uJ9SzP?9?G z82tOzoLMx&<W)-N=WqYh!=R~hpK*YU7K^uv3S@8!Cdq$+3`?!B2#;n0>LKo${R?aC zrhitpbJ_+EX4HI~ot>RtnB?iLqCu}~K>)H!N?r4(*DzYMmnWM7eCZM9uc2$Hvc>Cj z9;|78Nt<?R$p{@t1}Cq7k(3w`DznLvT3p;*nDZkj^{(eO90V}Z<2EqkG9F;I#wl^x zUb2PG3Uwv53$Z~WQcx2mWarU^%0@6^vu*|n!FZg(4s#e*KY_I=k;OYWuD2<5*<fli zN~a$N1#DDPP|wG4d~lD{lLBbr4<^mDWghIs(VvLTU=CogbJQz)98z3bM52F|bsg*; zz}X`YW0d{xHbuCV>fcXc7f^$o89B006zPQ|7Dvbtf<EDzdZpQwL<>@>c?hxxqfq-$ z9)d5FeuB%+{F6&576}?-Chizv70d;1ki~#YDX?e3mUsBCbMc8Qqev_x6w#~XjZ>#e z6NiP@5lU*NiV)RKkG<zZS}*y5IhwXCFsSOBr7(jyUAAKT;G<RzmM=XPKi*#aAb8`g zJR>5BQ}^T4s=R!$w3IyOp*2=zI^|Eb0%O#6rxS)iY1!||6S$fnMlc%0?bhl%&Y!Ue zUThpKAEIC^w)#gJ>{LN>H1k2wl_UMI_iT~Dn!Typ+gx00jfVYlfEi7EF6?iQ+jp1P zpF2CgZh=--1ZEdcIYX6(A8Ym7^&X)?l{<^lKf}O2cdNG586pL%;>RoqdNx?PPBw{u z8I>P@FT65uD{Itj_8rBzWl?;-Q0Lc)Ll1mOiI3zob+=%=94CVubQ5;9tQ4%$y66Kc zl-g{q#7iBY-yeOmzZoXC7)DnCU$E2#;S}1N6yPZWr2ut_5?G9MLqw;uzhAFuu(E#O zf9I<@pGdcD_c5dnhsI7Rk1Fs%9{+$>JX!to<F*>b&v<URI36Y7mRjh2QTQ!d`JXs_ zwI(j}WhTDiYsAUf{dvtmtK2wk)#~FJy~573!1+M|4+e|(n4o{J!ypf8hb?}zvPKN| zEi8Ne1}N>y;j@QR3S94k9;%Ye{`dE%*1u+GR;bC3`MZo*ZeKdph^(hiXMK-yNe@bK zJ!Adg`vwL0w*J+x`-%CmL4i*Xg;W-4@Ctd&j-D^Rg2NLL1km!Mi{~}^vj9!{RqGM} zS_hnU5Y?!cWrd9z9RWu?l7f3p&jj1MhimuJ^&WQ|4ck^dh`9K5yLPn$66IfAUtRPr zr*e~`xAX*`u0ZDShh)>1%QaOtM-|o_EeqTw8K<dQIJ7~fh=Y>6g8`d5q(|qZ7)VL8 z6iP$Cs@0Cz&u6qXMsdtCvSBi*vfs1{NNDn6>%1y<(i8~+{S!{4aQvJM!kS0+bO+}$ zj%ZjMX7yNREehVJR{OeE(zfeuwW%c}0d(;6kgrq>a10rAN?_hg6izwFJ>;!T8w}QB zu|r2aRFdpEZIW*~!Ng1E3UWC6X>4>oj!S2CWR(hiFv-kp412n*6Jc|R8vn%ts<j8r zpN^>Ii(2V=L}@p;tNi>EFLn4@wRrWo;m8~I(W{CU)^Ogd>a%8^%?_PQ<o@Jd?bZBs z8fyIcYf;4a@JLHkg#A*7SURUDDossq(2&P6w>S{@Pwq8K-qNDAgTH^e6g^e~CqZs5 zeHdzOEg_Tb6TYv_Wlf*d_3}}N?dlWZW9)LmyC8&YeqT=|&m8!&_ar+|bKZ;&(4o6j z7FaV?2YrYcK-V&d8+JL?uS070=H~-{>j3hlg*pLkcnnq{2*4)*an$j=lp@;(baV_) zz6Qu)6J^Rma_^RW)K^Fy8kVub9}Z`k68x}n2<S?3YV>ve3pK<|03}~@<zUdIFjoqW z!+2;7*W3a7b|?oX1%PMu09h2n>#7d1#c~x<RKF=10i_0i3)My`dLUj|QA}31_IOq# zCnl6@jZsz&2eB2JmdOFi;35|-*=LWhLe9Tz3m~_Z&jK26^`ccDBjJG6P;bd>(h3DZ zEQmwig9N&*S?B^yD~6yUh*ypt(l-s{dTVkViqlplcmTyK5i;Dk@qsj2zkdIY+`Ksd z<B&ZtXo-6&t3)oThMOp-iJY^k-RoHfXs4=RiL>G?l`>jg0T+zp#*KXU?-TPQ?2r(D zQNL&osKDhQ{2MPAv=EgP;BO#275S4VJt$oXjRIsZX=rG0-T{XGyi&plE-f9dYUl(c zkqw!Szy^WkEEnVD;6i};9alx`o<Dj0a(sCo(I1(uQ(^r@xid2KQ+}KHJFIj+oz(Kr zr&afCqmk52#)VV7#F%!z#hZJtvfO4o26JuaJxurMwhGg8&ifj4hiut3j)_DxnIZMC zU;vX?<iHG{X`=>WqU1_x>tzpXHjP%`3UmLcXc~>62TwnjC=9I_{(7>zc$_BU^%AJM z%z!p9lO%eC(1Dkwf%oJjZ`B|n*KvEgrcW>(grI^hV9}oI4p9NI7%oE7lN+U%T<}$w zq%3n7`e4(izTxM>5u5@Q1x2vs#3|RkN`n>oGJ+hD>>BJ(JD)_1&Ou=TzA{GGcS$*e zv@Unrf+|U@@}deSpNq@s3H1?5(K8Le-^)tjgl}X#f-Kp$IiY_Ijg*hZV(rCOb-m5Z z(u0c~2t$Y=RjRJXi{yobrle2^d&Do?B5QXesd@B2Cbl~4RmS3ID>G6CK8Sv6+ja7P z_)3Fhxc&aIr!Pf2>D+)JxJ9&h@-RMU5|-;mr#Ck#wqanvfR+$vvbFJ~q)d6kLC>Hb ze^B-fX~T3Zm{n?lPM2v$_KE?8Fy-H#ebK`3ZrG9EABJ)=<#R&d>T?m*9%OMNZaovc zOq};^VB<3qfZ7A_J5I3-)f2fFRQ9iKb7Np4KvLBPUv}FYEyBDA3$Q#3hEiD1cBQK> z<F^V&;k{fo_dX<yW4czm?)}w--}4w(giQ;rP#)_nhlgdreKuqDK<kVqlczDg87bWs zh-|)kzp#DRvyCwx;q5}a;G65EC;WHrKmpAaeY3xR=TD)pi-mjqPJFwMg9DO~x`yyy zo=tsICM$#ijuz!J<05|0=E8aGX0jBUmB*F|;GiNqJ6_CjZN78{b(;T6F5Dn^7F;|! zn46o+gURsM({Bet0O0FURzg%`bF&yeQheo|C=l_kdBLaT0&E967Ncc93;dXB2<62; z_9q?|cy!Z7HweR!3~o%XU*^$qfT@J$jFxj2+dBBj(89hF*I}Lo68`gi<_L$=zDY=w zzcp>picrN@S0aJjq(y3<m=*$H^mENJL+fy!Y)DxYGloijGa}ZOD=fQ@tiQsFZLkeM zZ;63|`|U&lxS%@%hx72FXf{Fql*q$|T%($D#ooEM;ELR48daDKG<Wd#S5#*;dTi(l zb$CCM4T|Z=A|{(OZA5(F%0*4W{W57k`@|HLvHqgeMVa{yhYZ(|dXP39r}~=0W$>-O z?2fXZ+AtOxY52SnXkQp6HKw!vT}~_AHOS2T4UWxmM(IFrXzRbW1p9l%AH>14Z%+5C zw(mVBOG~5jnOSfgCat`z^!GoxK1=L>tY4jn*5An_((2+j+nx{4!~m0m17a$QM)Oq? z0kSucB`6669WlPQV9aZJhW`o}&G<hK^pzd{YD#Jw@oLscx&1s#<*(#x9Z#2LJqZs6 zk)o}E0Wvl=QJ)|!1mxh#7}f-;7BM&SH?0gK&`}S>4yu#BAh7eXbDfan5fZXBHmH}& zQ!#D7d5O+`Br=AE%11u`B{zbO?`EAQP8u2sM-NK~N5mOST`JK9Cf$*4kdF@}dxQ|? zky{jEebzRiRK%2nG~$VC3X6(!C-a+FU`B%=2hJO#5J{$Yte|fv!mf@!{o86^3+Ujm zz=M+teV<|IkFO>9J{#N2pq`9_fbA`a#SLz}Mky(Cmt7o@8Zk72hD}~GFYuIH$0uV* zqPmQBLg#Vb;b3ivGvk~K9d*0vn!@{hHt+Yh6(r~sC&>$x2F+;!^S;7=cVGNpUFQQ* z<eaO*#q?*vWAqNlG9?e(hPXEN)gt0hRY?>vIu7>H!I}mR8kDs-<yRCHl_SF5e$;sW znpXI(7SXt9jmo~1Y1t}j(^zTEzZK);=>C+Ym_S7cMW}qf&3t!dq~&M-kZxC1Y?=%< zq||~)|GZrG{&Ywk0Q0(B_*Ys+EDrh(S?1CwE0XJzBXz)8aPQY#S@{<PGRZ3;#)r7T zRGG%;WDFPw?wu@h^&1D$De26uAqkhHkGKq^T|$LyBM41pyW8LEd$9&u&3hy!<nAan zE?=D@5&5xt+Z-$aU1gDH4K45QS-`dwX$M&_)U`(nYqCa8#RlZi^&lbd@zrcYmii(z z&N+hZ4KE?<fO70-LA<R=zlou&fu%~oH>>19jkD6`6Z78>6ERj>Pho}N<*|QH0`R=E z1@bfR!lB36e-rL`OtO86rZoR$NSdj75W!Yp8Fj%HG3#@nLbw`83eUE#gkw6f@J6`% zZe(eay_tzU1#s9W5eRDft?xR@ZfYuKY4v~I51fKB*hyNxGlNaw+>mK&R_RXBR3FZV zcEue<i!S?K9(qM{le(U9rf~~vOkU-!@Z7gN7Q*k(8#_B!9z7r-1ZW^yu~0$9eRMC{ z>r2v&cA|6<kSZ<^*I5mXeq8*ORG(ph`xGiPj?jVjDwN<o4I=FreV^PLnCS943~kRR zY7kyn&(*H5&Ud&zD0i5X$s>4Va&Aw^w~yv1BJnIs*ojwUXeIX-X`aA<^$E(GLhJT+ zR1#AB+bWK4mGkWf^#p;jc7Wq3t$<2Ua?aH>!vP@|%!;N>LxXyL&55Wxc!q++l#&UW zFc{ci6ku5a0NBSSqcI-gl{||>=Z+O+DdY(=MwM2ZGZaL|JuFT@QW(+=KUAmbMd1z> z<Ca)n;0k(7h8pB!gsS5XX3CCIf+OZ7Ii2kcB1;t)Uos2P^$wupoWNgLj4GhB2Uqgi z8+o^w^gHjLN-BvCfTa&Ef*rC|EKE>I{b@VvMk|7H0bcEo9+F-5B(BXy77fy~yk@5{ zV4d+-zhS#3@Ao)n8oKItI8{UO_)+6c|G5Ym;jU;Qt(mg1K14<Ny!i3&LinCsxCI1Y zE$J9&PLP{><d8r^W6Lmuuw&J^yc>36ft!o{{dxVo2Bq<{IIStzMjRk=Q>4R$lx4o3 z`siNq(q4vg416z-0$|~s9kHg5=^DjMrCXf0F3_!1efRp-SC7kA049lV$AeRTu>@}^ z5@o=|+<0m-mz$fr-eAz{b_NWV)7BnGgMs<L{Csx$;wpD@w)#LPfFv4$06p7_Fwv}F zO{Cy^V%!Dsu}Uv1NTTG>MYJK&PH^dT>G;Ek0BzkUCb!6Y;|=N164o&olkBX~8W}Xw zr%lVK<0$LJxKvmUHxhf%-wIM;E+Z=*mEseGBtT0DA}ZKxewNe-MdR)=h!Y4SeM?=G zYP6e;Gj%a=27mAwg*6-5AJL<f#j|Nt@K8PLH)peF>BpKi<d&3G?Uc@>b*T(H;iWGs z@9#6%U9j2A{%5T}p6v>K=Y3CvNv6HNV1(WWKzjH7n~#acfV*W6QUz!?2gPAIzmw^( zNgn+3+M35?9ntB!v46j~FI69j-49<0Oh{l7P_dm620sH{h-P6UA;xEHv-Y|c2QAxJ zf8nqH3|e?OJ&ihNsRs**ah~!54iq3oGFYm}@o@vBEQ_d1-Kt79i(lMM!EwTVK~HLq zrY#9N-91?%6DVL+VDjxiwP=(@VdF7l4&52NSBW9!if5sVutbn#K;LbvNk`6xmLBqV z-t2l^VSoF%ZxZ@1KB`apotBwDkMA1CSsF1DUtbQ7GaHNQp3R%#V7XKSGP$x6);T6% zyXc)P3HCK2EF>{Dh&KaH2aHcviEMtp3?laEEECRLp-+gRrh(G}T3xCFbEfnDua~iB z#a8%)YhH+CfIPS>nE~(M-CvWE?~*Ka&RNZdh^dGUV2Qr?nY7yXmm<Ya1bEzY25$_` z7X!xml<xKBiLKE9m9!WhozX`I>^qxGDw<K2H9j?Ke#TTDf)ph6Ghm*Yl;pZ1U%q0V zU(8QB*etWXyf`18t|y(1x7La6Bp5%vs~B@0_@Jz8NMt^|^ZZpuoRD@OC#S+tt=3g@ z6`r<N5vYyYs%Ze2H3x9sacx-{!-n6?!OEu;yNl5nh^U%a60>{Bg5j=R($Q<6q<?BP zZ?Y~ff`iceqhPXxTG8IY!9=fib-?$92}X<xMOwH$tbj$nktNB_(J}51cJs21@%D_1 zjgTbHS+|Jf`fMlyRVjF@tpS4h8<aLh5~dh#rClsRS%oMgMztdl_nAfqHkJ}-QP~t# z7$gEN4k3L=picROK&Es!SD~B7nnk7nrzAaL7jkY@?v7X*wP~tJ>^M6Z#48KOfuHpd zxNjA>HWMkazclKgKB<Mlf${v?lYSP0#2WoKSMmvU75xxvvUy1aAk{6#iRx+zvPlf` zXeX*&EE`a$D;3b#!nGHJ3D$B-AxW*X2Fo$=a^{!0Z0RXZfwvysq?r*s*`(@%4XYA^ zsF_68{&$6+&@mHptGxpDcRqML;*~D(b{@E%HIlhOEW-rG45L-$k{_21pl#X*KKPEo z>h~9jtGlAET;JGuju3QwaCdi?&+obLHiDsyirqqLN`YSo{{n34?4)ic;I2oVoy3}G z`geeo<pxiMwFv##8d0wHLmIGQV6^?Kr)kmF1LO@;ZLDwOpEdMUsZU?m;*KdVA9Jbo z_UqyRHZ<5bIAquzpQyUtI5+CkG&(d~{oamLXViRBsqt{qCnRre8CW}SgB$DmZjD3G zg(+*~b5?%0bUO>;{{9!^ezD#N%Cd8IL5A+Pe8^IPvupn947lh#rM(9w04|&F^p=v( zeZHr#Z{^HdmTnR!#=wjtS@S%mr3o!D=S63pR^)a7zTNik3?~bVj()xO!N`5nYS+-$ zG1%Q&Xk;2kVMN=dFHbsCslNmE9O+I}0Fyy7_cLoQH+DG2hPt)rfZVIy)!Oy_1(1lI zOWf7jS%le7(wHC!K+Jza6ET@Z6E1?z0+WRfz?&(O%&OY?H85xt(I>G{Dq@&;ZdwMa zw^CoM^(u>@MKJPEV-3qUoCNs@I84SOF<lGG)*Nf=>x*LwBD@9>iFoFbrC^q=iA#^8 zu{bXLAA;oJc=|(u4}o_Ns3;>wUv^(ydJwaC`g|;<%aCm_vt#>D<HT0T`rY@q{NKCv zk9~BP4vR$Vy5C2?9i<~f^F83{hvQ*gph$yB;OSWVfMI;tJzes@&3FJrf1nNq7ZAV2 zeltTe$^v78()ddJTK)>**bjVL4}|{2wBZ@ci;qe7g5+`W?{)p<$Q>P%?PQPI4nLkC z*F0FOOSg*qYwP}gf1fO3-yGjUYtL3nV!k%E^L8J#P<(+X>hsfIZqj3`-?Fm4TWdsE zzVK_P@gPR2w~<64fdFr)S^m?6+EF>n(9n8%lXhg&9{E;8Dj&(wf=jTmz??d4zYfL} z+i*6;95_=5g`+2xA7%%Zn;*r%9!mSBL4Q}tLYXv@BB*}V^TT^zGACZcA3ya0HA){E zXD&p3ILtyV2PRL!Ok^q6#JkeF>man&DzGwn%%9Gn?6&VdO--Vn!q~e(OD(G!Q=&Tv z(ReO5X!!jA7<(K}0>?5GrUyC4WNSUO6{qXhe`Im5Jz^C0a4zd1hC6reIStAf{Y=0A z`!xRWtNxF=k`OB1qhuwbe&QWBLfkTHt9w)ScSK(hGg|w67vzNK=*_Pz4Dew|3FuH^ zNNh~U+A!CdVK(SHAL!!qNugT{?7-UdhmS*$?+<=Irh8O{iOv`xKh(t>1cPN^w>y^m zv0i<V8YJX!b}=<R&iv!`-gRD3IztztznIVb0u)d-qh7rZUtUs}mZczug#-#3;x4RN zoGjwW<tek0uDQ1FNjuHtRhLO|-S07xhj!JMfFHNXp*}f^UJv%eP%<j~j5W>=Iv+Ex zN*v*^F$E_z#*<1iW2ZK6nTb4__xZInZw+*!q83C>%~Q@|85#QV;`>AT83cxr3bJ9x zKPx4l7dcXu$9e=su5$!m-VD3~&xT8z{6&RB$>@xSY;0$u?&EAIs33JPq`pH2IW>Z{ zr12^Ktx9HnfRSi{-H3jU0uxSyGnbu}-2!pNRS@uz$`+ipIjcgxqfRMVw^BGKn?R7- zYoZq&FlbBHg>_`1at*GQ8bW`g<^-GJ7M;p-_OxE~r?wM}cE(8}leg7Wx7p&URKuvK z&P^-A_}DiS9{*h{p}OAaWM5~{^WDbRHx_t6BS$pT)JA63IY<#MPBAF=tzN_DieV*q zJ|~JB6kKlX!$4}y(GYpA+A5lyAEDHMore0bzz4ZoWb>*|Hu1>6<IyU4s#(jpei5cd zE~a&YFu;ucl#NTidE@CT2o*D-VcTARl~2&=XhLjZy~kIE@c4OaO%iHz4f3yJK##y| znE@N((~onxoqqLpe*70>>fq!{Ff?KY+KA~J7*sNcAu${e2Mg7Poj$(rDBV<57xp)s zosk-dlW~!Y#5&@D$-xCBCTxo<b>IK8Cd|zs=KUE)lGx<nYL>5(XAC)Cce=QYCHNvI zdYocffF3X{6mLFTt(l3}Z<$J@VnR{;tyu#P3BfK`uT8RaBZ#7+ge2USEl3tu7R{zs zF{!jpRC3xF5euxGrx2KRT9z^9zhQ*`^wjl7weZP_XDQcP0ZOV^=9ghTGnV{tv*+@` zcYmmdDkaG_(IPIPtX20I%kz>oaOv?#kTHGNMTZ8D{8?jc^oDdob@U+c@!<<6s&%jN ztNn{rumt@II%2l8cUZMi%V^ALrVvCd;!e<W*U=_Q=uSJ3TS2jY>$#<VYsua<1HkH5 zd?zDKQG)Q2EkC>zae5IOEUQFgw8|{t1Xx>wo62syzI`2iC94MicoY6a@bIl%j?ob^ zq-$bBgn8%a9mXE*j-+BKGCc0luGYeRku!-_>Fa9lc3<JCU`h?9a%M2~%7TEe$G|Ej zK`AX{HH}zyIS6b!>yHW%`UmpH-<;I*!@x)jf>6SbhzOs67AY>m<qu-$!DyK??<Wd= zG6nuov!4afM02s_9E5BzGsU2*&^O3sA{R?&_4{hA17#CA(r8NGimmb=-jkBH7-~;8 zBLU_TOvAvhtVB@CxClY^lH`@r9^G3^1ies~&$B0f?4|zy7A(k=Qik~<v78u%|EpK& zXaB!mg{(LnFH0gR>g1|oe9ZuvQ^$e-fO+4PcMaa$Q~`Z5iNsDkD0Nk34e81xxPXV> zhZpJb{>1ApjwVRsu{YlHzBNx<y}v&l{qYq3aM#a-w_v+w*l^9ZYmRWVi|KVNimSv3 z_=2VE{#HdElb6g_HWigZbQpf63`Ax($MdHH$LzUY+`Zn45#qVa56bEX<pGYx6Z9)( zsxQyxc0R3kcR?ULO8X3DI0nS}o*`*Ki9e9tcvo6;<+ntO`*@U{)5^z|;TnU2gpc%9 z(83t;X27yXMl@bP&%(jePsOswr_CR*=Yx|0E^X6QK^8K_L~CpZLi_Cbdlv+jXnd@K zr~G~}g9=z-ym@_(OY&i}jeYm<<!Ce(iHVd5`kD4yfwb*GcgjERkRC|T%XI~|#wWP< zu8)%$NGW53O!&&-RK13xp(SZK#RS9$Y+`;9Hr13Zq-40*0_R=e8P4jSs3`(Mc&jH6 zP}}Pu2O_Cum43bp#;mln{9W)T!G^|eQjiNCRUn5TnQd;{c>!=#w*s~{N5XF1{74xP zvx>O39h!An`FWvno|gYy4!!RsgwGGje1G>;c0g?BIdGjA2>7(^Rx{Mm>-KxPUwh6N z7}jlcbaWVaFu3`(yJ={kXJBYxXsBbTW3cEyjWu_0fx~2<3|el3#D)!x82^fU$K*R9 z{|w+F20FM~SXucRq}b`{5sXMe{?S)@FVl5N(>l^s{P|}p=DLN7(9V-@R?GKdXe?E^ z-}_>S3MaFnQEgw%FFQM<i($t|jC6)aXeG7(bZrq$6^sA^TEnM5pjsObISLSYhosIc z$8DiOH)}cFDYE@gb?;S7SP?9y)+d365RP1Y$OAS~Km87koN86}$9;2kwPrx6&gv~= ziW5qUEsJkP!n~;v5nF3Y)3VC6!6i)Z9S$h?+9|w%GB{)cxg!nRCmOred(dgS5EO(% z%Ox^$3y(p6xmbB0e`sc3!5?H2;n8W6DZ%V-yiI9Ru!zr|BXmZEd$vl>?goK_jlOvv zoK$Bgsg&7oh|{CHT;J`CtM$NHojDf%y6MKoH6IWf6e`>|*HRGh4`KfAQsBqe=Qzn1 zjPM=C7oB9~-Z07MS)$*gvj0)3@aKNwzsY&w54ezVrP^rse2>Iz_nYhfSbiLoXB3c= zaB>MM-*Bw-HYk8ROX#s}lU<?b-PD}3>#=kDDybYU{*dC=YS(Fi`_KEb3KwEiOK|I0 zr1y87z6sj+hzy~}#cI8xKpQsL(D!>b7e4ahy9ELoC<cr3j$B4l`Pnd23p`LreV04S zk|GRGvWH92Ea|9j-ez>JI_^8J_LJDIWdX`~zEbD%8E5X*&QAZ$z~j9<bH9T4j-gTE z<}%At3sC`;LQqq-YTP$em)eK0RA0$<-ocbOK7x~}VZR-p3Oc41_Mi7C_KwMe5cEp> z?ibA>==_;~A;SOcf$%)I1;(zTHbC@z<Ae&m!5MYqHyuH%krG=+zQ(_gRCDygdhjqu z>oF9EC6Mg#F#M-vE=zH=rr0e`;2%eBq#3Hz%~4-HthLTl0thVNb4n)7`FN~Q^Iy?( zAJrNDlHE11<FEsN6)sEwd6$~HbY~}rhK;NC#6;X1$vO2@Q|_^B+xDVJ@dpH>_Cl8$ zd=4zM3mMfc#mt7;lL6xibI(I|EJv^3);?;5pkM1SaYxLATu|wMAQPGpS`(ABu98dS zf3NOoY3Uj0k#Y|B+~Vv{pGPYy`y+R{NPMW;u6BKTb&nx!<Uz9MErgIWQ58fm%l0Si zB7}h?Yl@2D;1Ajqn|U4Kj3;;gEJn0&I0aXDw_nzu6k+nZwZWwkm+GG`VlehQg^hX_ zWLXqt#~}x#(-0KA#-x3Oe*$>oUlX+Z3`(lQU=>d6`NE1KU2SrR*DOExe!pcGsy?8^ zrwm+Yg?2l-!($g+F$l9xPiQ{~Aj9;QcEsf6u;g)0P&rhu*bp;;%ktE9q39}@Vgo7| zjgeWF@1e_C7{zT5$=WIu)|gRSmYwyJDFltn*0POF%rYQS1g%>swZgY3oC2n(vdkz1 zLBtFN3s@kk^$7>ZU9{F-NSw*RchfO+OLmMjwHIzYan;-LvkZBjf0$`>&UIk2{wv+x zlXR2l(a;B)kk*(gqdr|de(~MBYEZTBl+D2dZ8|IJeA?b<tFpQ61u}B1-z>b{E&R>= z9nAVGe4}cW1@0>3+Q(FkC;$BussYJ{#E$+>(Kmv|@iz!7KJfT}kloOJ!91ACO?y-J zZ_FpEwW~|{V}q*M`RcXIpsegpEJinDa5^;!9MZhiFj(fv#F3bE{J9uzTlde%izB~h zimj5)MGG0pG7Yk{eP%sfBVj--Z!}$96gL!|<W+*HS|UTKVIwm}$;kLbPcN1O>iGCL zhxxQav7cZ!7ukX=T0glvt){V9QutYq^Ts=Fc}>8qJI7^fHqudmU=)v-IQAf0v6-e# z^U&8nksohT2JmNW31Vba$p@PDRPA_kY^ZG(H>@TM3X)VoND!cmBF4hE8ET=gY-Rsb za)iQ^^l=#B$5i3x;==dn!uR#S<IFFD6NC)6Ucm|=laApc2LAyFuE#<OLM{|C)16`5 z$KgrGK+dRm4hw6C$O8DylAz=;P)qrBW`k;LZ&>{X73fO-kP8O@o4zjDzhnv$5s;in zW$4$)3eWN*&YP5J538n|h}EM^EjOIoFj@O_e+qnHgR^px;g>V%Ko-Fj!};h8Mugsh zNQCivosPe{R;}AM*0&6HR)^qd&D~dW@(^vlMJR$f;Bi8L%zX4ha4$aC)pBx*8>y`- z`QAL`)=YIs=5H`2$w!-<xQ%*=P$?TgZ)E@|_|Wyxyk3R&=uChCT0yxyB4!?Oy0BAg zsKmA)()+lQyIH2d4eh=i(fZ_}L>@rVoW_LdFQLMY(Y3f9tnSkW+t^#*EwhErx=xYK z1RK<kJQou0$3z2kcYVVQn9AXSf_>@n!O7amz(m++c{1yRfw_Ej{tFSanab9VUW44z z`X0OjAGXgBbRZ)hd<xf6vf-qrWdL>QDgVxkm=oJ+<zBGQGNx0fTWh$nwbkv0=Hu!4 zGMCSf>H5p`L-xI1n&6L$(`M~8qFOBUChZ*FzAkO~j&Y&yj|mX6{J$Sx8HqAmVrH~N z?JTAw?WDC;dqfyP>;;m#QWz0KsD58?EI~+&1!ixZeiNoPqYPH4%h@D1DhT6jaS=_L zd5-wXBhrq>yj31hHJW7;)T3`vK)l&(#__)S<8LP8ThhV}pqKT}qT@mnFC2EOD4dSY zAo$=T<}y54o*MUt7_1UG7A07eMr<9{fjaE4q<U1%IS%b+H5C0M4-|_cAWI8Def{aE z!2o|Y_89DU5OQhDxj7lSnAXI7@FqjkPt-LjuJn^tIX7@ubhc}7?PxG09>Qf*7}ImH z)bmt9t*+NuEK4#nplU6-UW>-cN&<gkJtVlv2{+_4kd`CEwVD(lI+YGVQvxSft(4(W zeJv!W$JibuKYJ9|xbE^x9y2IZMpK0e?HyWFMOV*Ihl;8w>OR-=x~{QN@Zam<KQZPz zEPrnh{*wt3mYOBhqk76v>~x@eKxzGYw|}}_PPx$Q04^p9`pK)pYr(1UHxbPiF6)qX zdvEV=+Y5T8s`k$f1#u0Rz$@&uBvY2=zbw11P>;A^^G5FyqnLo&bygd4#4&e70IPYi zR^tKmRtY?l31V_^m6olwCG=j-zO{mWBv+5|O|vM_N&aa0wnnk!gBVuiB?->zA{pWl z+zeG}DJXi?xu(W&L0K_A(nncam>bI|$$+kfa>+?BD}_g{5R?A4B6kHi`aNw=8@3a? zE;|~=S;%r*1M(EMsHBiwvie5MbJVd?k4dB8bEZ=0Ytu^T<v)asI6@#7ZDQf;WZ(mJ z!1?djGvQAs{{xaQqP|Wwqo0RuW7@2`up%~wtkvWC;M&y~P=31OlFwM|Fb~G2)N(W} zvxuS0&}tZIXc0{7(anc$5*T+ee=KTgb55{?jHQc<ha!c14y=*}ZZD~;O|o57g_mHX zJ#p>uI!9JVtTnO}hYbamx1FkuQR@@2pi`lyl(ew);|om=G?l5dh=zU@5Oe#yTwjA4 zauC7A*Kef^ytQR>NxiPLW;Y;Z@-6|elN!z5G}L<7cdxA^SMN7keW}AjPqMS3V)+(1 z3=~9hs=N~s#FjC&O6FGZotO_!eXoZffy{%TDucQoT2Q|l%YtPRgu?bJ+5j@tNG+HB zR}5SX-!|2Fq%sOg525oE&u$<}HW9B&MY&3qhEjAaEw$$pB;RrN8IX=0%!qRUCj>`q z*Rl*tH=F_3u_q9IoT-NlA)JUlKD&_o;Ulr{0`U;Khp#*xwdFkpM=FOwASY0@YTQm- z$x2xAW#nyzaS36kcB=H)HyTJ&A!rdEd0STh9+m1Q{<8uWTs6F2aoNO6-QU`)pIZG& ztve&AaINE`i$o3penp9XUT0T0^GY78$p7sG3J}&T|EmV$wY2<_|5XD4DY|&xV9BAq zv=SH~ezwRg{98g4k<p{sYhHL!l)6f}{*jjeK1w!^q#%Ya7?f*^;d*?29xLy}vyZ>n zmSrgsci0&_1XYk#j-|<rI1iN!$YCS?&My4oYBD-p($-Ny@KT)DgC{~jg}(A5I?kkm zQ3-sGic~5m3%eEF6|hNb4h7~~aXC445Q^YC5_E`}3F@RS(Bs|Xfl*BcGCukewp7(` zaL%|ZWh15Ff(VzQ#6wtQRj~G&ViWM*d}Ny$EemT&_Uwfm7D%9+h?Bw)KciD}ByVDj zW@oAhcHGBYMnThYmudV|OHFP94Co>f<Uwi;*_sUZm+$%QD3M8$aTj3-05E=3<Q#R< z;30E5@IhO+?*is!&lH1*CA}>nEnCI{mlt+1X24_9@)cWm-*<gyi7B#yRR?bTdZ}9P zr*o`>_Wu6<-*5T9z2A;AS?xg?lv*H;u`bwF37l}NiNC)==VRLRC4HMDYHZ&jcMw=s zJ=YKmq|fKi#eElP&)AD$*OetvquUXiM+8#Y7$vn5QT-Btwkteka^fxqNYzeBSu@@l zsOd@Lc*$?i3R#w$OAt1`QtsZTWIw8{D)$<vFHtJr<IOGfeZ<(-l)&KONesR(n{s=o zJ*O&5QD0h)RwqV8yGj;T;=*bcA*P00pW!@!#)oatHpjv&<HS@)SPTj?{-U8~1t@?x zNbpQY_?o60q{bjhN=N@5e&Y?kXU2jNng(pq&k0AvPXfv?`aLffzCKp|+piRUnkM;o zs$Bdx_*Fgd<oA2E@YA2bzm@-fMG8Gv3O`H+8dDLCt-Hk=qIH8jqdrl!%g4vU1zaAa zgs_+6W#?as{lZ|WmtEKVi!*go<<AYf08~=Zl3aj{3f00+lC_SRXjvQ;FSZ4G2!|P* z_4%fgxjNF;V=HBFQGGZ#>6u_Gc?q0vLHRr+?R*?$5TQIfkN~^7;)+^c!U@n^is0MW z&fM+vz<-w**W>ME>8|M+TJrnPmnS{l!ALX)wbDp@RI2Cn7M?_k{+1Z?f?AL9a)n|W zY!7>f`wuZRH1P|(RnUI$NIIbHBImhtz#G+L3}?1(i*cFn^9<Z4EMPCpw7EHVA1^uo z?o4`JgsBn7R}HNuM~5G6qo@>m7(!_-T%B6k3I?I^N5DHMc0|C_v1hkQ4)16b=-9+R zu7kpV7^04%yLIDzz>;97vQOdX0d8xLZW|6SH7t@?Tu9i035Q7Z@T@fn$4-MM2PKC{ zQ2sIuHH{{2tQT6yKsFNn*s5pbHl0c6yc?j(Hc}i5E`ez}NipJV*b#90je(DDO<htr zU?_kT=h3cfj~#f62i7lVAhr-IgdObm9PL>3+kc46Hk%?X7xKH`<pJtZ?o}Q#d^RE$ z9HwN}J!T@9zmHfVCncJLJ4YN)E;?Id6b|Mp7{_-Y)1BpTSE<MUgNsMcp?8Lb!+zRx zZAVnf1|F$QM@36nkV69!PR7+Pc{|oEVA!GkDxH#n*tun_StP2k3zL*s3xh^tA@0C@ zBa*w$vR6d42}ivXe^!dDkc5DQgowb*K_b(#Cf=y51}>Ph5yY3#kPoU}Qq-Z=pu?{j zLrA4k;TlW@q6)Ur-_o?qJws<Pz>JD-pxFIsK&q{P=)s5Ik|F><_1wPfiXDuDiGV?j zBkbC|TIf!&eyP|;ZmKoso-)kY!IZ@Hy~T;W?B5LF_+`x|VFxyn4;~<m6!rJB@PoI| z-v!s0{i+mMqcH+Z`CLST7Dgg@OhSw;3_MS0Etsd&Ep=Bki2)Lxjj=Zs3n=o(L4+qY zUEYO1m0uR9LcvZ4nS`iQqC#sSz69UZ1r!t&u7=;BL8eHJO5NY@=C3E$s74h-%sYT9 zPjREfN{onkgw&xUhFCKzvvphY$bq2Ndr|8SgP6&x!0bj8<y0)+6Sew(00Ke%zKUo% zBdb&?xo1~1<w~hkE~e7$Y|gIMzWmC|m1>y@kp+bfd0{9&v1xqsmdUE!JWP%3+SzSm zJ!IP9eqBNfW?_3W)(w8Ezf!AmS}`v0I_(7#cKT(pow>nwVK~PhXN}vYn;JFyOm1DS z<EBlMx&nOm>{&#!t*2ciLz6kjPM>^(6{J)u()KfFP7e<cp$s8h&XKfl+-d$tVT!LT zm+Y|?|H=w;CJ_a&1`U8h91~ef@b2&waZB+V?AKDeeaMXHmP}kqm}xOOpe?PX0D1Ox zJ@<YKRvG9cBSQ=mT>?d*U1c@j)vf^3TI-f{dSrN*CY4JiOo%gzLM%c^vnO@v2`Xc? zw1=7P1Flr2-lRrmC=CEC1I1d~xhzbQipa|53N*ZB-^OX6zkBBg+4ALBChhZ6RAnAH zi(xKTtzrBj#8Mo{CXz`JSIT}$q=8V755wr_=!$#a7z2_bMBrf#bw==a5Kz#Ky4GM? zpPph3cE69f*I<6*PyhH^fA%MYANbLAdBWgFKlo91e2nAIzW!C~Ap0JLeYpxZ*iG{I z+0<+yhjTk!$Jx$+ID_B%Zopl6RThc`gpojQ6otaDS=X-V+I<W*gc_~)|E(?u_|N{s z*RU@<*b}Af<x_5avy))R*n{DjY|Az+ek`T!S5=0b$sEWQ>~zo`#q}c~f--1@^7OKP zY?_{)e(I@b)9t~Nub)0QJ=3T+?Wg^As$xIz)H%_tpuMoos&Uu-O{9B(n=Hbv1MOmz z&f#@fCxXr~XfVV;t-vR`(N9i{A2xAf98qHENvBA^dN)e%hYOY?hQM}SIZ=K>Sz`m} zmX8F%rxTETF+{^yy(FWYYalA*0?@BmwD$E>(T~4hsU#grKjyV?0Yx@~q*iP9%SO+a ze&}~T_Jg!aB389E#w9glD;^E|Il#*8g}(I?CgoEz|8*o)4z+{`>uYu(SF<;L*2YFg z*p$5U+IO;WPj0ro&Di*;{k-fJDoQXv+iN%?4sbwEI{+M6vM9g=i_MMVwlrFE0Yt6W zL;#yPc7AMZG6VJi8aow|jaHLQl)G21$p&L|d~C$7oeZ-BW0hk+KtV)lO8|&dkyoV~ zF}kVPhjVR&f}yy21Wl9`gLu}4XLazT2t-#cN=74r9z$S@!AzY%KW4B-)_FnM0QwmU z+6p1p_TuhJ261%La?Cg><k;!4`?Y<M?Y~`?;_T~|mh8UBh5046I_&ZA0$^4TAe@mv zNSq?XRhJ|X0+N@^0nX>_t-MM|wCWHg3bFut6AwiKzceP|xD3kGm<D92h#-E!lN@@| zAxg4Oca$L_rzHu~$$_#mD9lPa0bLadA}SY75t&~IWqL6H8l_|s<Wjp@&ETNR;RMi~ zJP*(9+zBVrKq;U&Jd_eANii#F<s<ZvR6I&i*b~ZfRe9k6A_@fmhq#<!8=ZCncuPVV z85z;DyZA^@pu>-?XgfmC{MA=qfgj&wc6MfQahW*VY*^m%ma8^zo*W$=hvMF^vr;PA zqX0<2%c@sxuB0a0=-Us6_L>KKMibV0-KxPpO?w|9({C>8Zql|_J)3`ssabRoVi&!D z32=`I+x|X_FIg@wSIbqJZEtyC*wh<1cBPf#md%?-hewtdmvC$+CpOV%(`V0(jtryi z%P+r7i!j1_-t!*D0K!QU>ROr3eAoQe{L+fM)M^eeA-+V(9&adPCCr5;6oIbsfXQis z(-ZI4439PJmey2@wj*I6JHUc5JmlWs#n?;RE0pnw8FbB79hWAXwHNs=EG$e;ZW$cN zQ;4?W|KxJ^r8VT?^o&l7+pE9IrQy*L)<SBV*tCfSlL#vlUN0uK^^>q}FUL~%p$!@$ ze0FyB?Afyu6BE!$qAQY3xZ5S<v$;mYzJ$Z7h{A&dRBD@q`Gpz0dwT-{>n<Y;C*R(s zJW#3H3!jl}z3kpRi8UBJZgkn8f@0pjd*u~1;{MTVZ@m7->C<OMMn(rR1DNab%P+&_ ztCTBrAU)1ln3<WKpI_jF!`r9HIDR#nRjY6Ya`M<(Z1=zqeB(d-pa0=M{PCY2{6By6 z*1v7`ULQVyC;Xw0{pg23cI$tC+n@c}pXBoHs<@l$8Hc84y`Ik%%q30P&)#T=RcWv} z#+~oKyA46UFf_~`;q2TzUC%~=9I^<Bag2<PK|_=oF=O%>WVe2>>lWxg{nJ08D3zhZ zz#x*-?mcMspD~ghv|ono*|1F8JsL(ovi#WPVywVQM3=OhDfjZW7H5Z@AkB8IT6ee2 zXBn*=P|lv2dGg6;=z(IflpeI7@aY}*2(*3WnAz4;v0a+M{9lvSW`1<TI1baJH&&;e z^}y=t1xA#rh=$Qf3~R{ov2LCyJqqN<s!*wZ^=_2j4;L&)41sNJ{wTA;es=4NZutli zkkb>&6=w(mQ;o|phyuj#6MZ0t^Ro3rzhYEP7!|&D75(`8mC|@qDG-=@HW^Bi2-aht zi-hEdT4D+(vBr7iW9vgdIsFh6>j`R)0*dV!y0etDX}K5Rr-~%{+yUKpJXj5@=utRm zB4ko5_Dt#anyal_H?vW??)vL<x$HZxxn|3j$+6K<d;8?zU~VwW>cA|GpJFno#C+^k z*vf%PnML_WJRC-_gD6$FjTpOtT0WPvy%__H9hfaccAHr`GssfJrh;`DF%XDX-4kKf z6uUth2b>)U#%hg>ja`1l6)ZZVBV*J~TVyeyxNBb=sOn=5Qr;&v0u=;4-9eJFen_C; zNfC%1+7);dS!a6#%(yNq8m@u!GOPj024n_1SNPq4_f+?UBfAdzG2ODCOY8<b*qY6; zu~7-J0p>3C3tP5q#lM)IKF99j?71_v1{VNtqSay~b854BrZnfET|{AUv00%OiJ~}3 z_Nd?=UZQ7!(_1!gvVRGiveTut)CWk?3~Nc}if8~jDMFTO;A(dw2S7&-fI^&5VpU5L zNKipR6p%^V&N~V8WG9MNL~vB7g55K)jb*1T)QALyw8E7$z%0O~W&#xnVXVCY@KaDW ziPj<yfrvsu{IH2x{G!V;iaTB(fs=?h6^4j-gdmW)hB$B?Wxus3YiVhTP+3mAjUhsa zN=lB2hyV$Spq^_No|}zD=$kfeddpkha{1+#%e8|d9|;8*$LbC|5h9!#xW2eoV`CF5 zD@)aC{i>_pGCMoJyu645T&>#YXHc_PEN|L0-ezatZsYK=;bx{?DHewcg~`pEpMB<; zE8g-JC@4x7GWkM3bM`DUsd3DGMHWr;saQH|d3pJ&tFA(;Q>RXm+`fG~4WF4gH!@tP zR4~y1g9HsR3&xWJZx<LFc;gkCgDCvvVsSY)n8B$(ca9UaNRv6wDW%3zFGT7^VN8Ve z8tv56&rRXukp(?!PvSDN*}4;<YC0j+wjN38HfX&xIMu|Wl*;FGG;Pb|1RA1Mx@|9# zVhKuT>SGhRO_L+|{-(xCb$o1dqfRw=Wi$;x$2tqgv@kq2JTivJ75BD1+J*A?<T!*h z1Uel=NF0@@f_bG?_di}h1oY<Q<m5{)y>!`Smn|+XVg#BtJw3f;%NCMu(QSrT9kbrq zmv~ymMzb_NVP8%f8{d@9<SXUo*vQsWwKg^}div~HOpQKQUU?;QCN_=JLDC0c0yNZ! zV#Z{IpbYlM;4?Eb^dnt1G?ZUiDZ!w#3<Z!t^})QH^ma2eCTO?q`DEPwh7ByvrDzC# z^Z)&?-2V%~Fa5$lWIh@x4CRIj-#Pxo=*0LqF1o#~d$5&G)yfsxxNX~Zwac_}XQc)M z7SK-sGy#7SBAvo;ni!viP7($YvG(sA==u)ur+@L2geE85WWV9Qft1FNrM-+L_wH?+ zT2Amf%MnvcwX#wyG0t1L!pOwrmGuT$&Pr}(uwHY&aM|Fi+fOzN3kzor)ALJ<3@S#F z+v*tn?=;c*&^0FjA;#uH*wkb~%{EcGfLuyJ47mV`W%WYqrd>btvAh4thj#)`nmREx z_4WVxHy`=(k)xgx!Jxa9Kp;ug!m9q=5ZfA{YzPf55|b~A<#r+=*$=A%yRmk`Xm#T3 zEoBY)E>vzbq%SNZ0bfghelaLq11gn7zk+M?lPd<2Q3*-9l1VT=36<Lw^4F;)8ulBX z<`wjkqf$xqlhY4DngoW3=t%_mfnUj}R?%>y`t;)u=NA<TN-|D}Q;LupN!s$^=6o^4 z(6?VY0;9?UPwmA<Tu@R_)oKMva*0FH@|}eGH;I1wBh*K_LA#_$6i|?FDn_!TXHWSs zRVt;?(Gktwl)B=IE8hFw_g;7XJCVO_+cs8~iu=u4`v*K%)>AWStL^T{vOA1wcE?*i z<2H(wnlZD4u@WI42^qVutwN(&r*igH`2p8$_VPvBi>C+8-D%<I+ImB{QYy0Y4%pAS zw&BN&EGX0qKRvBw8f~@Qmsg6}f!wJ#PQLKM3$MKL3hO&7W~pL(Cn{p0XS)S6iy)<l zBe31sY6#9$t6dxmK|0mDUl65^R@akUdmILVaky{(tsi<tMo>FM096Qq4p2#1j%76> zwbu{Hk<4gB^dx%9Z&SkgQ>c+<uOVez$S#v2w%d0%+#{TwJl#!4L${=Zc02Sbn{%?L zeQC))7R?~hg`)Ie*7h*Ys?yK_M!{wk+zP5d6!?oH$Hj4x=<5J8AgES@gCvd7ps};4 z7gS2ERZ<j+xCVG3gv1e|+$1QjvSJp6u-|~jB6c2k-rGco^)2bxLoEoQUP5d~2t-$1 zKuMr@p!91mbm{__1!l<vP{g35B7}h-1b&%C5JeF}*a)M_C=6@@L~+Wb0jdSMcGZf5 zP+Sopx_AH-Q_(?e&Te+&e!XtrxwhMEChayG1~hHQvx1G84#VOyQ5~A#BjF7ofxbW{ zY>ahgH=H_{iBpO`Lb$SUa$Y&{B4VM#k2DIZznK2mlE3=utJhp}&AZ<9E^2}Q*=L{K zvUwY)6Z5_#qZKC-A@eD<XjD)f9*Q)YwUpiJ>uV%*-C-+%T1stbPK_`#y*FF9zGrsq zc*p$wJaaT2;Egxlh~{s+@dgb?J%A83kTs)NslN2;DI8$=Hp-$Q6d@urDpUk=+r6cT zB$aY{yT;-ZuR6e(V$-BuV@Jt>)WF2hM9bc}Rmm0FL&KSL28FBTQhoE}WvO<qTCorI z;`t1Z<g2wJb+iZa1KB)!>cv;|2>pe&=tJ9SCYFINZL^tyI^H#_qXYJ&AZHVn#05o@ z+1XhYr>)q$S}hM1Y+17Fo#unFepl;_QlnYU3|5Cna;4JB#Q2t6ezaOi4Hvd7E*CR{ z>E)7jG?N|5u;y)=oIn{WLLY!KRPD{>W{Z)LF_<aB0Kn|{`&ffshLcJug7PZp%3^JQ zHp$3%(+GqoN>qrmSS}XR_GC5j^uK)Y-#L~G!9V?HKj+6-XT;JXl-#;y8x$0zTN!C? zl3+?|*;DHc&Lh-I6Q?QFYTfKPG(w1K`8=!0fPNnO+~@umUyZ{r{K9_tk!Dwy8|+kQ zuMM*S8)caRwk3GZE6dGRBi*9XRJ~RzmR6{4U@$*Aae1w7cVt+1Q*qArB9y|mrBa1K zvbeZdEMjllg}~KfEShKCHAf+zMuoT{0_%jB3CS{r97G91JQd|4X9N%f5zFdEdiTE1 z{?e!R-@3!6lbAYq;D5UPGe>+%_-_ud&{w|y?-@cE?d~XoKK=N`5ZL-b1(WDkaBY5a z#XvGD0b(Yz@3V&w><^=6>Vf^c?)h@!z5^x@LJ8>#`Ri_!!sPfA<RB&GM74^dpPYU` zT2dK8)sjSzALR#8t)k&Z_36j2^DAlrg^Uv-0yP3GPuSO<oh@QCj7BIMLg1+hei(=g zN($(+y4*M+N{00!2K8?el=86{I*N6$=iY~ZcmLkbk9VmP58U$JPaj_8VU`R^3evN; ze3t5FGnY5tl@!~aojZ4a|M!3YyWjn8ebs_exRewRdn(pwP53mhT&<8*7#^Y^ix$jK z8t&m?{8$(!C&t-^*vB23ra&%d4sfPzlX)R;Kiab9Aj++1D4N0bEmw+|NPP+z2CRdK zf(<~S467tnu)b8v<?*4h<;A5lXU?2-U>Ta3o0Z4Qrpr~zF2a&TkdqzsJq64F9q9ZO zF&eJz01HYA)F_4+B&`QF?f|1LkysdXRs@Q&0-Z1#k=pAAO_RV_2;H(1=qbOQW~<R` zrR4?NmWj~*QmGMlAG`bTs9gXs$<Akl0G*^YEaCvOd!$2QV0^N5XT!{vgB=J1&586z zFwxG!Y?ENNy)oy)pba5FXI(M}c<Yu)ABz}B5h@l)(inkc;E94PH5HJACx9`kQt*)F zMD`s$6c?u}x;j4k4QL!B&NNOc;+RGna{9TxFsM>snz;#Ak*E&hR3sMa1WSVAFdz*O zK_EnhJtN4W+XRwk0yke!TnsS@VgpfSK=g!%7=WCpgdis*74h7zQ$z%g(PxoVB&rzW zkMZ5a-Ep%mvnn8hl8k2gFig9QZ)P--S6y}0^vqeNEqEX@kulIIOTWO$(1%$Kp%ymZ zI5sQui<}#HT)0?BKr+R3hHTxsm0Bo*aQxf1z3pvRUU}u~Z@h}+%P+s2jXOLH0}4V> zEfhy#A`r1NxnrXfGy@7rqz#W07*SL~?NCqySeH0v)2Fz^8N1}()s6#<&n9gF&5?$x z&d%hO(zDN>sMc)KrwS^9jVuuQ5n?1_*Xyt}LlrwvDMXCSIUjR?<;>#%ZyBFt(4;ce zbjGd&w`I#ldURwmpBtN*HtWsIoV)VMD;5@KS=;g>V{(A8Ap+Gq)J2mC(TZkLFS8F6 zz2h65u?!~>qSZinV4xsICJPlg(ddp;vthT91AF3>k!e@U@qX*gm3$$c%cqx?7B)?6 z9UhvfRcXt_?80KR-Jrz`8>&MfW~YHP4fR~xt#;W;VwaXywrtr(rS!%0^jT?35xN6r zSdc?g;HMP8W2Bi9rO`|1?Ck;F$DH+7mX=0_^7gL6T9t#vUiWzY-XnkJnJx&w@QeSD z5G#$?ca`vf&5N}A$XLHIl)WsuowfxeqtJZJ7PEe9ATwC2SBYnHgYe_T!ueaj^`OKG z|MZ{!1ACe#Jzx%Sy`r*!;Q{1ix9l198ugIE^<7?Btd!WAWLB!}a<%C`Iba)|;o(uv zO(LgHpI%um&CSg*)UBXxQ|w0cM$?vTj0V4}+|LhKUP&QXRU1UJeq;h6RPiL8zJU_5 z1d=Xi73tmg9scHB-iw)f?7;v08(;l>yWl%8u;-?~`_X^)k5>KSsROs{{><v7U^Zw$ zreKvO^bd$~_JkBuXmF8Gg_G?mmK$lElKrqMup4U^j8-Sk-ctI@*M^%&Gz9(Xr61Sk zSEOI@3r46Y2H$E2C8JeC%<Q@E@HaXm$1ru^{WslnB(9#ugM_5hH}BfTB!BeC5u4P2 zWJW_quVo~l@!yfN8b-B>qMw}eBC5<92=Zh6QLUokM)m2(&zz?!Ks2K96DU*)g)mTJ zh)z4PP>3oILPm^JRR~H7$Y+*QD@YO&hr*&_#S&2eCehChtBQK;dwA&!xB9r@;Lnfz z#6w<rpz~2m3eppmd^(DBYskG%6l*hpSsdAMU3cAeY>n8ou+~G-WIi!5!8~t*^xh43 zS&LGvKRJ88DqnLK>u`YU_PlPM<&_nmU0a?_huv>ymb5#m?fEj>AmwuQ&LCDC8t#7B zHDHB$qiSz(ak~pwn_UJZL>ltpfru!|KxBy;$_=qFvTC#R;IzN=(o2MFGhjG(?i@U< zO_Ze+n|jveyxV?Iwd6<?VdyXDVo?0N4lrd&!U+XfD|#WwjAMfiu)l{YF+PFm?LZv5 zprpcR1kDv$CqhAFh7bgL3_ayz%|@$E3)m<Eb}be<QA74^(E&NYS^FG`T_84lI$sPx z0gNBUAp?xvBOw&F&D!eI%jI&lZV!z4PKn;V%QnUdaI<vA<k*0_<PNZ}I1<tZSFu4v zfw&OjiVy~7!MHo30CCJgsHAw3K!PjhA&SfB-SKt~yPa#O0wP7^0INnpa$qAOI037A z3W^6xV2eRba77Iw0#02Y>jwOEoBEF=Y=V+Pw5~vx@DOssN7<mL$>O(GMIbs=1ClTU zC=|hH;sGY8Qw5x26O;wnF<KMY*)zl9$q-@8lSiWvh;zbBH$6RVm%p}dZME%gWZ0OI zXJ%$#fS*k^o+NbUWz|a+y1G~|*%xIHMOOl{C;|^Aq9F4!xy+C3*Ab2fHJHtC{%}%p z_Gr>)-o!XKtC|y0l{RvkksQdNr`@N)oXlXMl-+dQwl5WHnnrVoL@0vCwQbwBv*%8u z2F0n%n&Y~A^XAQj^Yin}+EAo03ak{%Pe1!Yt!~8;7)(bM>K#E%cE~XMBa*ei27#>^ z=KYdUDA>=ma)2i{Psjnzv@>Ic5v)9rZQua6Q&k*bQmkT)IzI5`H(o!xW5<q{Uw--8 zYp<D}IWsZ2saUP&3d4v(A3_?4a9V`UREK&{&<6@hGkei)Ev7C)=(LVfBr&o$)z?UK zW~^lgGHrZdcLkW{v|6;@t^f~aTlxIp((=N@IG*_^4sfBcX<>N<uZlAmV@fiHLaY;I z_SdL`P8C*rvpqMrFflPnUr_JLirvPqv4^!~TUUzz*3kf$8#-m7OLJ*!96it~E-!7G z7|Rb1luIl1S~b&d6jxT}=V#yYmbVm!hcMl*{nkUC_d@XtzxZ=>EOlX5*E0TE%=Mfu z*(_@Snwq|DdqEaGWmksbgda{Q_ucz|L<#@w7ybdcw(YRBLT$C4O53Y9{TogSIlJMF z{n}vGHgk)M^UI4%<woQ5*@aT2&beu)gZteom$eJm^e<M@xJ4pB2V8RdxuOHAcCrmr zCkhA=5H^SqVI!h2%HsqWEbb`eiXnu`71DP+GJjyN;!_8I{^$P3|MjSQ4FO3sCu}s{ zd&k3v4s`aFQ;+T6b-V91=2<7(KvMMr6;DEJYk;yLG;~@Ql`o3rMp~p~KdcJu#@Yp= z)rnKvk@bUKR3wN}oc>ijhM-T3KhPBk$xDS$R}8Ai>C$Bf0pf-n;7sP@4<CDQ?<zM# z>879jvX>bRHAf|(@h@ef;a?R(?NQ}{=<9D+KlE!|bo@kls3n$+MPks3ptvHj8l%dC zkQZZCy@HYg@|gzJYUxZI^qU{T{1$^GB+;d-p|=AJl;mGfQgCYaaez~)91f~I6K0?k z+h7()me=>a?|tl2*kzH_{)8ExeGUm*Ez)V|?7rZyHyf2&mB`S@2=hO2+XAI*OHjxS z4!BoHU_45>eL>dljI+2+ylJ;dgpPVtVSaUION&0JO@xI8u-T&u*oc!QBct~K8w%Su z+AWG~8eel@E656U=FA!NflWVl!$kyDsF$SG?f?TJ6^R%P4SoCt7*rf6DJZ!CY|sJj zr;i{Vhy=w15u*`Wt;m~%p7Pn^)f!d%A>ZBNjst9=Q#I#4?UA<+V%oP-O;2k|+kQ-P z=a);_?vc^R_|(`#Cc_fgz%$hB0=fIm!h~jgcM!JRt?zC-WVb*gP-6e`=o3&b9_ejc zZBK8pPL)b(91~F(a%0J8ge)OYfSsTY#8Ev^h`^SFvO4DV)mhkQ0AX2e;5ZXVsuaLj z7A72E&O^eWBn;xwUYSTN6lW4KI?Upi96^)-DhgvlMgSyzb~gfDLPAJOi3I%vNcMxO zQ#|N^9O%j-lmtR?DhZp3Hkc#Va?dePoDs}WW(!Rmze{c*4aZ%PSA+9bD%<;enNrDO zf`cC)6$hB4F8NZCMB^TlJ65pAaS<rrn0XU9%;OY+2fr5{+-b>w?X_2~dh1&>w=!cg zr^AU@#sEU#p$PgA!c0Z(=@RpDX+gbVPT=_X7$X5!7FFS7l10Avc!zSd=*;PJZ+qL@ zkfwWz-ul+JBAhCyky3zC2&6e^xVXG>^7NT{!(NOOHK5|XK=0ZQ6YwL)pX6>;VcEje za)4389AM0xN*4y~a%DExN@p54!1fd<OV2=IWw|;wy5-c#v+sDvj;X1sYp>mj13bB9 z^Gc;Ms25^6WiYI&LpU`;q`k`J3?e>z_8eIxVFSb|LK4G~)SQJJV5?E8H9k6Id`+EJ zj13&wGDovXcNFOT(UI{?I$y1%#>cjnE7jacfyI@wREls02BlRyTB#P+Tq;#9IEuun z7qb&VXI5$=bT<;<3aU!6&@?&`2INDeIyJT%R%Bsue$&`!J~vpemfMXQF6BybVRmjt z4^S0`M=}H1dedF69mwAQ8(q)hUI6a?^goc5@HE{J&ap|*4bm(h`FyrfrCXa#f^=&j zlN}heS8M;;uXj1XcmLu)u(iQ{hs8Z*8nIm&Ar3IPxWpFf)NV4C2Fm3!TZ+ZG`AV&^ zuw1S*>_bN~2y8IWci0m{k#rQ>Pf#3V4(9CLR|5QG2}**Hr7-GHMd_jdMMME17T7{W z!23OXpyQG}wtwiy|BX&JYn^*Cf;i2|=YR0tqldzsu2TnY*>#WI49y$|TU4gh(11xI z%GncAUZKH7LKRN7r&w+$5|XLZo;x4@-2<!lK&}bS<kX21fAYc~Kl<pGjvn^J2%^=g z3Odi_tQQO&NdQ3_h$!3z?ADV%Kn43159r5`6e#qgOO8{-7)VAXL)?%9yyyNW58c(> zHB%3KVAnl|-7OZ9tdP^haufJ(4sa^9``(9tulrGj6H^C&`^KNJ-=yFVItY?*-t!SQ zaVj3@QRP9<M$DlI3|8JjNr8G<O=z{^WZ4Yp?gDe=;^^l9OKcK}^Rcf33@j}bBc+su zl0MyyCTo_1TMcc|6hHehb`Gp!+qZ9LD@AkgC)qx|>$+><ksmV5_G@%>Xk>WM{aVW2 ziA7=A-9VQaw54`1n`t%drIl2~d`oMHvnsJJP$9JhV^B4YF?Q44&{RR32%Ja;Ce7`^ zLL6Y6!Ib@~ZVhHnTeoL$rq7;ZTlMtQPn!c=u}dJ!D~nqFDT_e(Au0?N1wdDp;%hj- zgsNA`K(Xxg<I*|6(g6^cVjyJ2BC%Fqa`cqnb`G!<gCXVsvo06hbzt@(I(<BwgB5oU zFk3PP7#muRE4J3`Js4f)|2hX46FHF-*1)hPYkp>)5FLRoD}DHhryTua;T>Qk#zHDq zBnnzW3j<q#l7!LeLybocL<+(XPShw{4B`YTE{cVnTL@y1z)*`QR#rb!b;}WFluaPc z2_`n;AzT|02w)E2BqxiActV7>D<b%k9Zf`xMwF#^2m$g#7J!caM56qH;-S4tM%xP= zqebl|wg4zL!8v}n#WiN=P&AQ|ix-NY#t<fggL>taS6+76WlX-fkyHUcqZ}7eGcUs( zp71~^#St<$H%D^%%=F^?0+Fk)z8YqHW-7h>^2?up{`s9dcOu6ww7T~>U2(+~l}c%G zX`Zso-AtN@<-9^5Aq6Q;tC=)m=47+7C7j+7d^%bRV8FwKj@rbjD2vC@x%HP)oTz|B zVsUYKdipHv*w`LaXx0fEjT(l*Qym!@!=;&@Uz}fDI6FPlX!={Mk${y{7fEMJgDk9Y zAf1C569L2;-JSNMqvp9$J1)8$VEeEx4)7rUZ+bA>&I~kl1=u8|vbAb^WO#CZZfX1W z%TJv;b;T8z**nI@$Ff7ioH5i6Tm$Xp0jio-W1pZTbgFCB>g1x5a_JhfNaFm{v-Au7 zND*w}u8QXd?Ppwo2xOWwR&SJ=ty-nLI5s})p4S~ur*hRwbMxe7)p{e7L-q9H;v%Au z&mh6nl&6D;0P2zh3{Z?&6(1P2nJ8JvVW0=;Xd)=g8VV0Z076g|<pIj0C#5KYwu~7< z=r9W|Zau=ND-7i^?LelL&9Gk5vn!>QWjdFta|Qc;bvl#9|83jvo`cmo!v<w-qK{pe zy#V~mul^&{MtL+xTTm_*QI({+h87b4?5}s-0{!W`?bZLTq3KE~EJ*IgB-RGE2~@AO z?QPHYQR_2j&Mhu3F*0WtSM084x11nfH)H!3n7G%ldAi1Jiv`D&QBoBNP&`iuKI!P< zabz1FgrcYyKq$M~CEXy4FrC`>2aDm#?!mhzZvRrs-a$=*K81%kp}!qq*Zs#1t-3k~ z_m9He?+UP5nuOTa0A)jHh_uC}45C<WClZpWJ0D%@T+QAfP8@vTbNAo#Q1ne-(dtwM z)3nQpV^x7}gblsqgz&ufiSav{K@9z>3+TrX6%|E4y5x{629i<95I5uifBex>qI2A+ zyJ!bkVG{l9d|s?AHi@Y6Kn0`3wcE9R?7H`O{6_?XJ?wh-VcWS<k?I1dp*excN|YGj zjJ8xE2oe-o6{vr`_=yWj2B3hn(o7YSDi}jJUt*BhBxswDd0b)#SU-0HilDYzHVrK0 ztQ{=VY_xPOfmMLTuDntlpBQ7>WC1O@_m#4(y80b&zv`;12w8yGq*0uON2@<hDLWj5 zv!2p)ycZl`*5A%1%1`p9fV*%vn6tgTTbj)urdwHysf!g8I-4Al*cr(rS%=uVwCc8Y zTY;=ycrPy7J+X%mA7%@O1590K&Ypq-KXPE8I`x$5wW?j)Lo%Ax&tC`(>jYK!SPUC< zfWs}>QXr;=>Fp>~ry3Oowh*DcimVfo10*5H3G^8H$#1mktl6d<Hh2Fu!t;Z6`DDmG zP?Bl8r{XNjo!T~>T<;KPfHC$!)By(cG6Mq#xKd~P=P!O}C(J&AKYBdGgHK2CV^2M6 zYF#u|_a)H~s11ZPLoHE~tYE|dvVbCi5={mepMy{Lff%A;KX9gDqo|%iTQQIe=omNw zSpp0+1c*U#_@g0!tsleyr-~~XvItd+szWQ{Vn!K4k`Pr2gi?a(<itip0k#lPT#*3f z3Ys_&Xx4F-fdOgaj6(b{z)aF<VUY4p4n#}oaNcWnbaV_N$I#GlHk&IJOUuhE$j579 z&?5(%Guskpn3KeP!VAI&1`7)d`Vq+S3{6aqkBkks>;cnyu8`%xqrB>ESK@%Il$Nvk z!7bZ1kB*PPV2`Xc*w4EsR5BS%Q>)jPS5_7l7biDwRx+E*ag?dGT16D@hI`xYO0`-c zoSU1$;mNr#>vCEa>~7&fJe;wy3A`U%ujS?9GtWHt%rnm}EG(TnH~p7?`S_pz`G0xs zwKtx9_PJMHd2M=n2Kv$xtz<Q+)T+4pW>pMmrtCn;V8&=DxD(qKaa{C!=-keaAnvzA zM!DT#-KaKNP0m`}WxN{fkRHfjrIE2w=)<EU<!UWGFj#Av{joDDVsM&mm#OjQU8ewg zj)t39w@}dwnz^h;<>%oWIv-4I%yCdy1)0CZ&`M>@!DcMkV6it5Q=FK64amNlV7em# zPP>9_4{|hzm?jH3LY717#e328XGwRl6$45iIj$68v^Jae!ek9&IH6MuNjTj-!|b0p z{h1r_{Mz+Oy;7`HOJx>U+q2Xg_O+l?n)-2>JBMLnVsapp<IJGD?VHAJQ$9a5#HPXS zLU%XYxSt`$Cq~CchKF+Qmv0nChr2($|DMl$lH=3&+(oGiz_0xB@BG@YK5*Z?|LXqx z{<V!8H;G|DwN9XoJ{Exu5eIT9B8q$AU%T1n#K9WYW%L5(ES9Q^OU0F9wNh=C$~7}g zwN|dxIVv3W24QMokj`ti8DRDjHv0)8n;XpA&+{?3`mH)e0+glDsb+9FVI&&@T|}sB z96$YV@P2Vz?#KIO)Y%Uc?&>*El8A8}z58<q9jn9M1CQRxm|)IyhXlrw7k_*gv2*WT zUpTaM{N7zYeM#Uf5l2s=uu=Ygph!>n?Ei*7=xL&GqJ0lw&ut&>d3VFkyYAlSqYj}V zVM6GMo>^<~BlLogFgdI-KlFo*-Cpq7YoPNbIl&Xxjm$tcof&MWGI)_}KuT-{s&#t| ziLJ{@X=Zl*^*2tv@Z!{qCtf;pcA6!X*>WH~U|XwNqgJl6DVUv|JA3-<3(vhUeRjHD zt=o^D_7+Y%*frwJ;BMH@s?8M3C`pzZ!1Cvoo(4>qi<rInq+ZbuyUzOPzKlrQ*dykc zrP*xQax};WVwjCqKF>1G`fmHOM!nu@!d+*-(oALZxzX{l8*aGauYvczXXiVw*}i?d zT{g_-hV$-u<$PXqKI@xX!&i5zvI$sYgv1atJL~_3j*X(HVp2ewM4{YEf;H;h5U}<D z+Y{uuqDatqaG7M=TTPlNwqW!mUWCPU*e=l>5DC+R101P=3<neut%&JlgHOLKptitB zbB95dGSGmky?Ctdx1vzp8e~yGG(95_r%!AIDwu@NUN^7^AqAsnMNE#fo`>xYoi7^A zx-f$xBv`}xuM>Cm$06OwRgHmD5kX0X5(uXvKyk;|16GHFlCdJtr2r9S1<n{ughMn= zLAUL+sfV&mg7TX56AqpgadL@IO-&s+a^(2&<EKuZAs0HF>{gM$tcRV6BZMR&)0ut~ z!t0ovoZP<M9`2o=pFMZ(T(xS~d5T5z;?A8rgR5+_a<e%*JB=^LG|0@@a34KF8RDQ? zt)4u25`XWFH{KuuohG0F5!@L3n8MItHkZy926B0-PYn&{nPIU9njjfbb8~a73Y5mn z#oZ+i@%iUpc=gp+hllOSXFN)DrZ6&zpFVvW=2NFmp|EwTgR`y&NvtPJM(qh03+j#- z-O2ESL=qfQcrG+hKZU|ZSqhRt1UBpjofQJbpb)1~5YhSa%P+s|vdf5&gg7%ZgGuQW zio=iHMn^~Kf|7e17DPITPSF!YG#1NaQfh=52~g01o`ut4wRHmCG3x_MBw8U#MWiq? z=?6m8LjlBUc&JfoEPYCnp;B+u8cpx+szopm5=WYt$r{WK6o%}jWrzjR8C8jBRKT1B zKJezvTMI)YID2@%nZYdE2zC!-QTy^Tn}b<1)Y5!uW!c_QSS%q><Ai!Obfwj=-}{UA z-GBG5{ObQpufMtg{Mu)~@XNpQ`QP}>fAiU2e~<$mXdU$X?(cd9G*FYR0rn+e!7PL^ z+#^?JIh@>D&3-;Fm#ds9^Ye>~bl`HCei<CdWzvJJNUTxLoWMS&Rm0NubeI7WjY1X? z>Qb15sSttKlEi57SZ)$ly?E|;WYzsmO?~YvcI{JpCcu~hBmogIed+!OrW7;m{nWjC zd^DlPf3?_o*P-JN<Jn(2$Sl!tZETePzal*K!U-P>n0nzEANyWG%;x7kp}wowb=!xd z_dZ9l_s92jF3{2hLCNzrK@8FG(jux%H2%F0mSC;*tVDp7fK`bkI~FEJ=6@Ji!p@#O zJ3l|qTENUn{FPT;(W_FbrSc0eyzr-g`lru7|NN;pPTD?-Wx)L~&HN7<_IgW$l7Quh z5C*_XBwL9`NkXy^4zx<L0U#ov8%olN=(e(K^EOFVYIul?frjkdx%1j<uYKn`-+A@b zS8v<4jg_61SGx!}L1-zW!jMoTgo>;Iw2ei+3y5j;U90+%)QiD`&5;1qtwcoheCLDu zE{O8fl)Dk27gPm+NfFhnViym42^QK&Ez*eA__jO;=}J;cC=%j8Yz$D*IZ2#`22mtm zRlq4Cn>7^#q6-uk0|>%FpnzzcS`_ho9h+i1!oU_FiWATk5kHWG5Gn!!zmh-=3<`iy zDzqq+f=v|1=<5a4tBB|@gtD4$L<BLmKvx9wDmSnx><6&{;*uk%Iid#!LOE>GjU;U9 zDe8ryEZ52E<rFT&+pfNf>C9dl?Dnrri*ORbQK29alDJ+JAzoft-hSEELVkFqxKt_E z>?xFHs#IQ?+_c3mR@IugthsD~kT`QFLYUU6iwK&q*QXYwp%_FM*c=mQSdwH*-%i<s zzEJ9Qdl<M-up4oUE9J{By8?#?*LP*voOxCO3bI;Aj(}v60@|wi0VEBs)8GUa>%=Ke zoP4T-nIt{VJWkaRRlL<+y{(<Oo{$v{mle~|A}ii(Y}q`X#R55;wRGD(VuQ`lcJt(A zwQ8$YZBiA@Vnv|}x^ShmoW|qnEE_=$;>eeJs|ui4+wMAMjf4R=6@HBH^wUrO&=38P z98~zB;I+bE7-Gf62cs=^OK_^y#_4L<Z7lS1C7o$z2kf?L{OCe{G&^875|^8Gv|`A( z_0d-DLcyL1nLalol@L2PXud0PdnHG`iV+ysh5QiC8>=`S$BIZtqrB^rRHIQVm5Zo^ zDK6i7rMnny9fXBVE4wJ%9v&{d{`%|Nw{M5PR4QUpnDGj8h0(VCZrK>jv<cfymVcD5 zHXFE(_E_xr_{8w=C=G8msBdr}Kh$&==hc14Cx?bG{IH(vBdc1GX7e|GEAGBtB<}u& zpF=DPU^=V4M%6>O=$kiB&d<+YcKJ5?j^Rr#r_A*9+~Pv<@oyhz6S6SBJeVt#tF>0w z&z*kOg1>Fo%Kb2g!Z2~+>dh%pup?0qqKqgi=!b6t%E2-+PT*BCiA-kqXAiGF)0>)l z;QhPqIU3<rafJZQ2{W0S?>+Xd$PKRtKQZ!=FS@0f1_CSwh+rbhs=dk$bYHX^p&}_9 z)DHBXP;NBLeEh4iTcD>79!z*$hMhZi?AX!oQDM6;_sc2&^JO#)b;Tke=u9NU$rFzd za)B7u36)KvpPVpkV&IJRv2L&e#<Y^cbeodO3Ji=)#WQ<;<Jh53Mx3$}2X49Xp6Gq# z4s<=z(y84){fCh!v`-w||Mx%k(BV}(hX~9>k|FIP7io^yn4`I(B*TykR2KcABtd&& z1{%8IgryX@k`Mp|dx}9Ph<FI0D5+eaBxivlG4$)N7<MNgqK@FP{iC;k*=kS1E8!ZV zwooHb9H>P=$$t8%nSnDz;16*@)%irnEP;W=jy2c)&{kpXz%2BLZ4O<LP%uQCY=e@( ziDyK0*)yHm_i*tG(ewY{Cq~`F(H-auGabnaK~!=S{rU^2ECz&!;#hz|Fg9%O>>y4E zkzB2kZ+-jKOgHa+?|Yd5S=X+5+gsgC$htY~)_4Efg=*a%Ic9ZE`)7d7O=y@r1C&C} z?w3}j$N|VFNf8*aA)%NpUdQ3dQJ#e!QLtG-x9-#`RdxmGlzmB<B5Wg%9C`fk;iK%z z*c?J+s|Fie6hyHrFqIr20;Hh~fHUY5Wk9APF|fi@DinvJB1mxgadht6TQ86!$v~8# zQct)ikc`un@DZ0|P}yk6Zn-CDz9a}x;1|TOPGkmMT^)UZ=y|&dbd)Z`bo7YKMWm3k zXAh}`VL${7*_(I9w`|#R`Q?{$mg!YzMCe544B948+Y(A4N3h>&N+o)k-D$mHchnPs z^7IRlU%W2@Jse;gq@Dd7L^G8$mYPjm5i9K=2Ad-sk6J4pAci0Zh%HR?qJ#*Xp`hRj zbyXUR6RNB@9obJ1F*cxPT6sqa^iWWdkQAcK3WJ_B);JtO+0b4w2R0E!5wM#g5XBJ6 z(hE9WMS&;OMN*+6Allw&xHi;NL?jBtBq#zfo9F2C1?mw7ZHWZHKR!M-v1tsCWnyB2 zHo{Dg6XLGuoTO>cnP(Z(@V6WFEnDp!S9my#Zv?_jWb@|DL_jd0F}LhiVLTb?LIR@X z07p+ns&IPg-fx_t>cF6Bjv6dZ%>R{2b!EAP7hNotmzP#J8!6!!%)zDz!YQui$WVl# zzlaMy=^l^>8Y&bd2Oeof60inXDKBEx0Y*N#EWJ3uOcqQTtR<OLd#Eso1DwsW05LgY z4O>)@x4cxzWrv3fG<=w)2MLI3U;$)iOnKLQ?-P>5q=6_Ut$r4aa^;FEuE3-uu_wT= z)6>(~U#BV(ATm`^d}x^2&Gkytm~nuS!~&KXXw~aA{Bs5iYU7aGRmT(#dAeneruCYW ztrt_<&$^{z8OaEuYMSHR<{?y@UzpppiABy<GJIgVrdq9Q?xQRos5zm7_R|IoSR$9A z-)XyTchoejN?Y>zEHmun<Rq1%Gn<>`<z@E^b`JkHW7q%NsFrHe61?9^v1q@AQykBh zk!k(X&J1RUQY_fkd-jVD3d4ZT$kgvI$b%vfhvE|sSTFWEs|&y{f95VEhl(=oR=$vB zH!w7mqk%ZUD=SM_1|tk)vejy1>cp$3PtD9sFEr}yO1*)%Z@&+8!A>ZO&?t>S0EMCI z!rmJ!I*3*?B!VU?=!b6t$`PlMfnwPSWbS-q{(;qv;?x7T?E1`+D6@(y1X6>@?)#pI zZoyyv-H&|Wz9-RBaJ_F}ScbBI=9^|~K8vV`YEcNHLXwCosW9OHpLn2`KNfKFo{#_H zzd6w3<HwKf-{jtO9o2`BTB6m3Fen`5H@G4ggfOrXt}?6-l=ZQ0^pnG>;bYx6uLBH7 zN?X7bCI-<Jf*?P=8wWW03~+A;I21&tLPZ3twOhUrm_w*jJ`AT=t|-w^2)P0M?868q z^h_NXz2oqUB9N2=to|h_2EwRT(U574Fo}NpM3GK?{Na@c<Ihk>aq#CSe)3B`-VJIO zFdcwGjX-hf91Z*FLras)gzyt8DX2Q1=;jC5lQowRADFog3K7%HF@%C4;$$0?1WtVW zd&&U@BkrXqM3hSwfM;ye1Urqlzy0l;Xf*uY?|%2D&6DoVI84gQo*u~B555$E0gty_ zs)TifMh1)wjVj`dvAP>%t)xa(3Zw(x8tW9Rw*BJVIdL*}D|)-tup8M}jxjsT#bWV= z7oG#<QvIxbvc9AZ9!nk!aI$Ssje=?cIxhf%1Ks3PaWC|AfCVwca4`-rSVOW$=NV&| z6)FN$Fd7>AyktxDhIWNgs|D8wIl$=Qg4HnQ05hl{5*Zt@iwD#WMYXf9WB0{=iP1&h z(VI4+8Vx)GLIwksXitJ}6a+*VgmgL^KM-|*pM3TOI4>UFYGxY;B~>>duJF82`w5Aw zEJA3!cHV(OJX93Kl2n$=Asr+^AQ==(0^vY)No_*lvmI2N5J)BvTYz$-%vQ3aUJ}X; zYyg=))-5C^Fp6lA^TKKEp(J4tOGNQ#s7Oy>E+o+KAV=*|t|)}cb-<)piEWcVL<w|E z!tBZ%>E<=_br%<wPn|q-`qbItN*PCJbOfh(6P_Z;rNxzMrCur57Uq{YaI1#LM)N~M z9Ags`lX!mHwr%A^x%_erjYGpcN~BV&t=OxIO66LWZT>(uKbR{JW+^r@Hat3B7#__G z=4y>rqm{}PhM^Owa%v4^R?4N7vfXsMTrAElE}TAh_Kj1gUO#p6)Y&uVW@hG>7V(8k zRA8T9wJ!iP-SZ3_^;VNZ@$ghb^w|a-m`m1+h5!QsjWHm5Lbs<(2i)&`_RP&HoFC3^ z05^D0w#89o*0A-l<=$dcZ=ev)W<FaOE{x!S;>G2%_T2*eE|I;8x=q(IQ?PDPopq`M zVyQYr1Z5$0W_}K{EEQKch}Z?hN*NcrhRjZ5(}M%qLOwTC$g)JaM>xC?8boveR~OF^ zZ=E%db=TgD#l%L7s#UxG??y#kJ}Np;DOuD`(tQfZZXtm}AGl?j$<(GlmOzGwrjc@~ zO7+Zu8ogAFNy(z6wAVE`KQLgero7rkgms;16LvGB`(okP*r<KA-2r|bxVbpG+3e6D zLNa#mR=d%pi*kdRTvpG(ug)GoRYNz<&dCB1-Js(@>ZITx^2`7HAOFg~_|&id@;|xf z?)}bY8^*8x`UAOa!M<HIV9l34G?^@GRK0F5>&gr=;Aa;Wi{<LMnK{mmQnixF4w5S& z)>o^C!9RG@1x9J#-4)&A`q66lq)Un2pZ&*O8|f3z_jm_#6xdvmqtAE!B>axQzyBjE zMYcx_9uy9JM1)X11&BkZIacO-35O4V@%EcW_eY*>_PF&Q|N3s<<N%tW*2NHvqeuu9 z2?%s0-&DBDd%$O3G}NuYr#A?%O$0vUeDK^3p0p<DFNUI^IYdxbCJ}N~oLbaORp+WT zC>I1y-~<>#QV~I=#E^u<u8q{kf4u9YojUkfY~1es$Q@o@9G;;UOmYMpViwje(i353 z!?sMb!NT8bFx&M)$c;tZu8ci4`vu0E?bEbXo1LA1_SxtE{Lla5KmX@HKXm9ne*No@ zee+NM?C`fApFVr8T&%dIaS+dxv4;>$kr_y5*?PG(F2_pg-ps%<WDHGPG40h>ougT+ z*UA+l>|O@bnQVroYmkF=x?^5jf620+pxq#6@nJ9F2YRMGG*Y<gZEwBd``+`ecfISH zYwW3D7I6xaNyxfS2x8qtX()o|5+1CvHYg(a^!EU~LJpo30Yu;01U!d>%J!6SUdV`w z3z8ExDU<+QIZh?QXata@q$WL`Zk<kCoxK5@I4Ew1=C^9L^U3%g_f=jryn#?cAg%@k zh~d0Ydx8+(2)9QhgaRD~A+Q0}B4!ZH5|WfCd@(oBLj?HjP7g^4h$;ZY6Cg?m6#)_$ z4WqdMWCeOG6pYCMPRZ#9@rx}A<%S3lXMiZmS_4Rst&~(*EEAH70IRjrWWr!QWib|m z*~Q}woSL1TJ9qBfNr$uUL6lOd#AdWmu=m9Q=1q#=-jIc>{N$5QKJmm8Pe1+a)YR0e zQ)k?xs>>8%nso!7xz4UAQjk-oQmM?%`j=1v`ABTd38|Z0z&S>8Zf<URdU|edVS0M@ z%;|GTK7IP^8*iL??X}lXjI4&+8#9iqk*@n_1+@@Ya{|=f5LYOKf-ch#;;yY;I1x?< zd28XkNR|>Op@_sOVyD0VA<6dZ00!t+UU}uFP2=!Zs`f}EMu0~a<Bw9IB1BOtJW&(q z5U~|Y3tADOl<vO9Z-fmVI3cRI>)e*zom6jT()O6~*w`4Hg~CueHNcu$vsYV?%iM-+ zO4~Yzo+>Dk1gdKDcip`J$eD28h$BfuhC82ShF`^-4Vx%Qx`K8kpIleGhF^^}pbO4y z9!R6OBJeOIR@}S9F@RQ2XJ=b+(XP>IXLAMgwW_N&N0Up1_N#-vaLY!%s!%JikBFi> zW)BnXg?kVO5akSW5aE!(^#Fa4Lj*bYAa}Wj{qy;u(b3VieYV#wk{65R`MHJHUq8vo z;cgeV^CdlyY1uEz{_KuIx(OtuBv5V=m>o-^Nz@vb47+dpP}eoj6ECdeV+UU0Fa6PD zo*>-%!P^#?9Poir7*(;nMgn>8tDA_^5a5b@&*96r-*O;+tJlsCeRP-gmTO2X0vu0Q zKPJNf<A_jVx!((rhDrGB1bjB|lWTzetm(5N@R<=)C?Z7ZYlE>AI0Jv^jwIAsK<AN8 zC_<l|07DmqDFsf>MBwT)h%H2b6L0Y8$Y_ZnTIvFD=Z|&!zkhQ7?SCBifTNG)uLnI< z>Z!b7CU8(vEd@$$2$Z5PG|Nc>W>?ntK3t<s=V*km-ddfpU5@r?t;x=(C0R-!o<4p0 znP;B)&Uc<Z^6kT?PoBgAoJQ4hd3kZEQLD3Njttp@OG7!^z+i18z(ZDXX_<vpdpt}B zor+*UCLsodU-PZ{2#Sb`C@a9GW(W2ITefU@$2;C}_0?DZzz_Vu_kG{@QJji!gW07p z{@EwQ_A}H-D49UjiH=qzdqSlGM3lh4T1b<Ak!aWxWQAPCK{UQj#OxzTPRMeV_=VNR zmV?Z$2p~&r>Mw>0dv(SPSrR3Lf?}5Z0J41SqT%=1#H?Buf#RCbwOTml^CL)57%QkM z0-(S^MGRKVp(#E}mkugu<$J;E=)jW_aJ6}Gx(2v@@ldXqLkNNzvCy#_#AekyDCzUM zMS*BM%70#nIlxmLTs>Xz85e}41Yc#RBY@1MTp1)lL;wSJf@@`^c=F__6DOvgfBuCR zUp&G7nbKs@=Y%AS#S*)DCQP>P97J#~IM}b^@v@=ks8sA@bcF)b-6(V>Sjk5_B)E%G z7M9Bu9Phcgc^$;3r)SQdJ$LrZbaAD!v{+tTC=uF=jfz#go9y5aryov~#)I2Yn5#pa zcByG<4iQnT{SIoQa@PPnn2YlqAQlQkT@J9D`Tdnlph%SH2BrZaoEj=(boUY?4zf0H z-i%S;CysiWR#Yj(a9Tlxf({S?Lf{dI1MvV=fvRLtTylUJ$PuAnB{y~0CCBuDeIlO# zN<p>0g4P}Oaa#AjzqEC(y&2FrB-mZ?c55MZv0|y2tX`^)IKCWROr^wi9~!_h#=&EX z1T1?jvEi~F${++$2<aHO%P~U^RQG#`^>VFVDV6P=*d&<=+&$8iF=w4oXPT#QwsUE_ zj@qu`UpE_euYJ2&sg|fn#tim}RwPiJKx^p-4w~rJP&nbY>J*XF4xQQeSN_F6`sIKA z$@@P0Pe1$5|B>YML!(yVXf<jncPju5q9O)tCY!6d5C68B=~}hfXr$gad76{#+{|n) zKUA*TD?qJ0K5+8bAZRrpqLzvnv%>{r_s3#y(wTa`|4qU|&>@|UKNj@CkN!hW4V`PS zp|*yZ&yL_y>3<1<N)C^II{JodhaK16K&Wg{LL>>bHx@<_r4WC!;cH63Xa7|LP26PV zv3|u=&|0$bwy66UpRP-LgJ}m)g^Fk}Ydi-iOHiq397N;57jy8W1bp^d`1nV<Z`%0U zqlXi}Mx}Oq_+z`eD);c&33%BKp4Gu;ziF75m|&G*o+mB~6A5Pj-hnqq0wFi>tR`8F z-P?C{_m=MJVlmZEgj(H**e7|<oIQT**i%nFb>f8+XV09g*Bbb|<YEn*{cY8(yJwGB zhby?ptfy{$wu=xz3pb*GB2qxWn21`v8tir`)D9TobT>Tdfy`hI7TYo8@_9A`xWQLl zW$%>Pv17+&mt7Y2JZ^wk5!Y55uE+<X2e_Kg0~L?K=lxX!O+vc@MTo}NK&;3{k!C;9 zIp~#e=%&bUlc2^JV9Nnmd}9%f4FoC)C!NT+!uW1v8Qhl4ZRR?=tPXt@((2;jPiz}I zoiU1mWat3V&x^n;QId(SsIFYZ8efMYKv{qjAY?gVzUml%KUjSoV|kK;=m5HpMc|nn zlnkLFK$?UQgsgx-k7g+@A`nrWiiol{#1Al$B0i%dA4Hob3V_p-dO<}3CqTZkL<A6h z%z>;>5lM0t32<Tz^Z+3p3jfN=%FN8nxpU_T-38uL)6>&u&YXe5Y&&mXD?R)AYbU2p zy!z}j&p-Xt^G_WA&f&+8|HXg#_J8^F$EQxb4E>dtUpsa3+>Cp*&+<}nX>mo<EOYMi z@-h+t!jbvL8*iv0;?$yFB^MSJOU2sCa*eQBY1XQ(Mm?2I4Kl4WY2!{yb2kQU5Hc5& zREt7m0YoK*K#Yb$h>KHkBn#A{NuP+a1d<RbtCL(+U_e?*E(No!7p9xNAxu21UgY9i zvLv`CEbL{)EIAYeDg{&#6qvPeX`!MDDKj@WM^aPL($W&vBcvciYC#7=n4xH)A|#0r zd8D<fEpn`(II%dS_UNy>g`0v}1+xRIja6~UVZ%YCFdzi2;3tX4i*1;6nK0zT*jn0X z5Fv@XO9Y(}#RSu6)|xf1BydKvc}CU2PeDbfk+OKy2)CQX8`XNF(sVD`?`V}{{<ewP zJVrFPE8Q-%j{|EGhm9(biOwK23OJJ+U=W2|_yKW<($F=<K-?3XcCR%B|HUtTg5%dd z^T~UE`BM@V@XvqoA6kERnn_P1vr%tx2I2IUOEtzb)tVJ6_2s2fI-RYQt2C=#YYt?x z{d`>%5QsaKJ(Qb-&vs2ygtF-4vo8+szBcCnuIB=9P$_m3bSic0-@d~w#>%!>2V}~O zq2aE;_avT*H!HRCx|`gWSzNyvVsW4*2Z$2FD58{P?q4}jsV97P0_s!Hc|Ico_nL+n zd{+O81kcnTfo(m^K>R|WDAE(*+*gt@93~bO43Q{g3ZF<M1Cj+dfIB}D{k(1Gt?du} zQS5h{9Us1JBj54rsZvkn1=o6ml4>bXa{XXEV)bFFmu)@uzaE5Ehqi|Zkck*Pp=m|? zR7b^}-s$Pt+1bU#MRo$(n?3jRGk@{_`|~HCcw%{JX>@3q6?b`YDb=#urC6J>k3F{J zmPHoiu%AIDOB)*lykgdLwrA`R>=$VF8#DtL9!hBdQ;N7iT#)5q0IoG{5<?@ythRW< z?|a|-e((o>aB^}IQS=mH09C6Xnz+WT!kWD%JfDLnIe5}v9lRbLL@6OoM21SjL^y~| zh{o56sHgzs1iI<bf&Ieb;5#M)`<cYORFytr<PZXSUqV2vpyGiNn+7i)T@ElH?i<m8 z7=Uv7fngWrhglkHp9h63H>9mba$}sd%Iyhl8x52tBq>S2fRGS^sC<Qrn2HWkCLl0G zLx8}Zi1Gjg`j|sfRA3H~Sdo5k%B~_134`P)0)1^@aM);wm=P#DC^rxl8d3vxeXo_~ zuxDZ2uRR=Wui1rj*kiIyyEy6Y#<V+B>3J&Qz*-#i3B%;%$<wp5^Bkv6*)*$9;mpr3 z=7)xuQ_+dxg2MrMX=R1u^^=r1{l=+NufG2JORv20%4@GtZf0)og%dBHcxj4*$n!70 z@Z!`74k9yiv!zOzV-C-HaiN9-(`v5RYpyEAm0G#fsMk`Bdb(0>x{HX-j)!Q_L%AG8 zWE^+8dB|1)&Q2b(5Y~%@fC*hr*QQOI!s6=A`qe9h;uI)IMe<IOtR9g9N?J)L933Fy z;d9oYyt@g=&-;=i9;5-{@I)6F*9dC`Neb$hZ@fg-n9Z9vv%nBRTNn_fBEaf!3ec<c zr}QD02%J=;IGjq-`=}>J(J1YPd**rd!Ug;SaoAWU8BxTEFfBSa&m>SB9wHbMkVO)C zDpD%jo7J)zdysc9ZP%Ppk<KJCl*^Y_il{O=JPZR1`SvZF^SMDA&7F@h>&Hvhbgahs z9U2<O8q|W~)mpjPs?s3)N^bW_L5(tn01?QlpxLOkTlRSNKqloreV4XJq|@zaBs-YV zLF>^%2a+@@VxZsDb?_j*P#C6XIGni#YVK={iwniq-#E=tueX<%R^VZOLm4{4$?#P~ z4@AW%*hFUO30jIk5Nov}7l(b_Tj_N{-61>^e>3DY?|hG)M;iY?%Bu)OAk9NVzIWgT zks)>Xxt=eJj>2;$pq47KYu6p0{ey?U{rHjDxdo0n&5uWp9X<NUefNEQkA2I1)sh#F z-FMvg@X_N(7nc`1$I+w5AHH|ro;`kIjKLRM2X^n;ckd%l96NS=X=#PS2|s@15AXf; zJIuif-D=OZY!F_R1bp_I@T`uRaQB_}KYaX&<13|QcPuRzj~#!4=I`z}f$r=vz^o7= zp}H~&wQJX|JMVq?`0?XUEH4*z&~|$8-aB_E9t>Xv#X}g42&&rZ=mm1uKqkHC-cQBu ze}43ci+nkL7xc~#-L}UIjlgI20`h&#p&#>}eZTSO@h6XW48o4$`0*#da{tfn+0(bk z8eqcIZ_2xOe;iXYXq|t!<ofZ+<4=6`{(U!Z>}Kvuhdp~fe*dFirFFD141nchoC{yM z@4kJz-D9+#wF6NIo9w~d1-v$^hTFMmBR4TVxoKk4*yx1)W}O}^<cD)vyPc|9D&r4N zO-()N@bb$q<00eCGFF*F-7diV7FJ^RGr+CNtgE(~v7@0fcXL&vR<UpMu|ji{*oPHM zP#QJc4+K%{Nf0Fr4Glq2*P}LIX@-*|L@L?7eY-xDbmf&-vP^52qF>1=D6w!-(Aw`n zQjnar0h>ZW#J^g2RXXt02q4N<Nkoe%4wT#|kmh3!k`pCLxWEt+w08~h(76I}#sK|J z&qNLnaYp$KZs_{>MPqe9gqBcWtl|)fnIH;RXtfla0&UiUBnIHvyV!z(*!L?JM48us zB!Fm~8kHLZS>CiA#CCE?xOK-Ip=bzvc7ITpk9FdvS+@b#)4&+kC=zN>a&6(T(H1eA zp*x6am_&?09VeRrFScbbVPdQ+30<9wuY$qJV#-rNjehDam#U>AK5CgrrCifdt++Qf zrw1AIBp2qFW@qM?mx{Hj|5Zgjh(KmQ=0W@=WFn0${nP{-Afh)wPy&8VIuyfm;4pXH zdF&{OhAe(~<g9`uRn}S+iMvMkfQ;v=)^1w^-d=0W{LD<fWy>UvCDS!iyz^xIz!O{G zN0jcxR$We8G&CQW787?(&fuj}k?J*yy|gJ+shIvanV8ocEi&ohhJDl?cHF;0Ha9Uk zHa0vmoG;i*pwi|g>Y%e07w1o&JUKr<OQl0Y_DSJ$=gzprNw@x*e$uejvgfP$Pg^D? z%(ovJwzn}=tCe7@Fiw0iG<GX))BnchbFntej0i+g1!DwnmR7J2VI>|KqC@SWZqysh zW^hLrm*!VimdJ0o=YAnFer&L1Qv-u`nAeMIY>iJ-A*1Qs?9Afw3L{{pRH@qov3Z6= zE<c#ZrNlL5eKpN&k3a`wD+G>>j27~F+F7quS<ADz0X78A8Ls2NBOi)Jo%&CqKi_DY zyF`pBXr|>x<{3&w!SEoY#?Eg__Gx(Cq9$PhgZTnSCYz&?%~ZO9qN(OUE<2FR4-eTV zol3>(x#_vrUOn~l%dgj}_1W2Z&WV+k75c8;3NOLBSf~|(8XfJ;i^A^f;_o~@@!a|D zfc8KQ!o(%uo!9*}n`%&%F-CVVq@}iW)+lw2h+F%68qU~g9zr1+2fk6}`9A#k{NkT} z<G|0~dh3oI-8Lq@WAFa`2fn$ugb#VgZcjcRcHeu{yS2EW#~$A2$qu{jeDv7T$~O<( z6|0QYtyJ{QrK1n;+wJamSP!CIv+Is~|M2MYHxGT`uDv_EzZ8Y&yY@eDXyM4i_uaWW zI{BOz;!LM@fA$ZL&CM@zxE~0P{MxP_8V2TjkF6}?elHg}jz9WwBRV|^ci-{I;e{od zzjw#Z?&j~j^{y{`^U%r>*Ze5N5F$OX=i^^}Vx@HG(1ShNP7gkC=o|A(_-WywA@d7M zQWEDa_66x+pS3GJKjIJVPucy?LgFrH^MKdg??M^}``C&+J@agxsRQ=x`|5FQ@`X?C z-PvVo9HhOUeDGV}DnI$vpWUdldhXoxJO2Cs<<HN}{HOo)ulL&sjtTzYT@U`pL*~a- zbl7j}?gx%=JhJcNOxgoC`<7bo)7I|KO_AQY_pZAhJhZ}4{0+tyog3hJI{R2pbyJ@( zGc&^)p=}TQAF^1v?6R;ube5_$8>dd4I(qcz;lqbtf9;LBZK%w%wZ+Zd8fCxKSJ*aH z*+H|77;ry76Y5~mMhG&Qd)Y9!W!<4{-vP#vvDw(MW!z2B8Fy6>m&l6PG-qEfV7JCH zPeo%B<7^Ue!YO;*b=O^g{q-cb0k&4`LPkc0*ha9<y4D7dkd)v~wGDL5M)@x-qM9cm z#iF4an}l(9crG421qLF3F0iF>TStFkpNQgYnTXKuEWB)4b&*Wlim*qD!AtBwwWzv_ zhwTh#01~y;Cdn>=!K#g{vXrZqC@Hlh0yda|IW+ES4<SUd;Gqc2QMRbP1Sir!EwU65 zgy`N07&t4S0C*@a#RSQOBBJC_BS}f76iJ1ElThcmlJHO*ot^loPts*#QIsoAO1b*2 zEo3Q9rFI%Sv7!(mDI#p56C#0T(k`dI!5Pms&8{hS<s5!lgR&&;N>`~w1PKxa8~jQN z#6?smsvpIG5TH^LP7*alR6)^6ib5zJ^shIncvh)&3ztKOIZv53o=+aX3UAj@>{$W# zHb4p@LCujsgkyY~jBd2W)O9Z<B8eNoxS>k4k&TE9QZK`RY&xuJ?^dE=WDyc?)>{>P z=9O}_%rx9|&s5TYHd86|a<O8w=0Fa5z1nd7Y8TdEDwdY<vT$I~8GnXp8l8ilYOKs6 z4V~_04M9nh*Fh(@2`^Pp8XBeX8S!p5Z5qG)^2@Hg@`_EHCYYa<OABZc9Yqn>VvJ8W z;qkVSfJ4N1(GRC|7yOv6rPnA@e2{gfnHg;73fbY&A#8K{)HITcE0uEDUK3v|F5+dk z>J6H~ltVM9k_c`VHL+twUE&Z)+PX6^K>J&bTC3fhoSeuE&?)6~CdCLE9vMP`O0|sL zMn>uBY^hvi6~lcVF60~a+Vu3<Q>RbPFU+F<&`@D~Vw7cwB8-ZKg$1mKQ;iaXgSm$L z^xx>{_{7BI$jDgUzV2(&;_}K;)t+mux106cV1{*Ua$;n-kSpZJQtf=D+{CY=XJ9Ts zEabLs-BcLDmv3Vt#ycH{{c+bT)#Y-1DV=Q;Ml#jr%Gv4DOT|T&%yPBz&g-rvQevDm zQ`K6tmBE1=z;4ZYtzNB^ipz~kHJeW5kk@Dp<?@Y6t-4YfXk~`8g<Lw@#?fx1hG}qi zkRlWy%%s{xXJ^i}>a~gS(XEr4Sa=)Nnho8QjcOX08OXNU>88CM(~f$hRjoDHAh>sD z7RZHCuGBc}4(>L34bVvg)WX7Gt3nspY1JET#sG)?iq8Pc53ZD!k@oVdufFoy>BC39 z^X&64)ti}-(aot$Ze(m?rBoUo8?LvjjB_MVDtWA47Vy7>3`l1;q<cg9V0nfmA-x>d z1)yBd>L3d69DR_vA$9|FYU+ij36a3LDN#UKzDx%qS`)i*>)-yn6oG*=TBmmOGza1Q zMMTeoQ-kW^(BY@o&Npc^0|-*XRP0t#xy*?o25`PJ2z?>}is`WD=wo>4g=1-#MU9*T zuGy>nu1aO4cHj92hYx+@fxR)q_5?oU1K&9I@SVG*wuovDP_l#fM7wIo&g*wMPIHVO zK7Q!Hd8*rS>w#|`efW-!Np)b<o{;s@ncYA0hsVD008X_R(i=N)eE!puU-^H~hPGdJ zB5)lTg9)dxnfF}VC3?p@-|b_94B`yqn7f+)uA8lYTg}$4U;W>Y{OJSd)A7~=-#Gg4 z-?d$m|BX!aE`1`FPp59a?|A9FR$UuAuG@`<)EONoRLps$gLuC~47NZzHnRf79d7z) z?4@=8*CR)r(uObI_dxf(3p+pgOLx??j)(JzrqW<7Mi4njvS29QZg)Kuv2*9UzTX)r zlezi+N1r_Oh4A6#-q^YKUw!L||6?EX8><Aql-=Ee>b6Ro5O+|o%*~N*@A>?TZO)gq z#jcH=*E^>>-O{aOas`=L<G}nK9y?MjAoeA}a7f|o_y4`GJn^mbwp76HKX3@I{|Ed& zgHFH|bl=3v;$05VUK35dK{1ZukpdgG!cdO*N^yyhG89-?DV{!a?v0bDUp(>B@$Wn} z^~$Toa^=te{4Z8kiX%g#xxw5}et0N9gfZD&46tKqR;u-KE7QbdWq;OeHwSYAY*7g5 zZ#*5^ImoUnXPbHUZnZ|WnSy9PKNB)XBZ%!FqoFW7IyyEnJUX5)46`KFs*Ta{G3aQu zY4hZkZCfw9;_{nszWJwr`ls=G8On@K*3@AZ))YIVG?C%L2u*CWVwxFkYm4(RTqrPb zb&%8{*!6J?(>W06Jp6i;*mZ0W_Nj%)kRT+^5$NF{X~f9wmd!?+LpNGNk7k8jmSDh& zhHW`T7z{cI**=GPM!*=rCpwdl*V4^Ay<x-C4h9ewML!+nNWQJF&TFGa#Ioh!U|d;? z+{YtuUVy&w!HP;K@3&rS;{<T>QBY+i3MJV`QI<U|Ayp8eY4{Grp<EJVkQFRK8WT_l z)e{#b*eI5~R6t-<rj!8?rA+9R7$-<}n0P=k?(%IXO(_gbXB6%E2m9TNZWCt`F!zH5 z0@!@4e_R6;Fh(g$1JNP20gB2L8@=O3g&!7-09gi@29BRNL^uI)6;~$$8PJt5wva1| z0L8~TzYB!2WKjwbSB)`H#EFbUX9WdefXzuYxJnFS^9iS0G!jDb#KJY8x-=0;Jv0HF zivBRsE_Cq4`U4?8wif(7mK|QIMR{xf?CcDfp0>x5=jZ3#BQf?8CUK*xObswFVYzI- zagf4!E))t37&?8#UjAesadLP4Ef$N*9Lvj#xR*ojt&Fb4_FIWWQLl}LS{;{+U5_pT z*DKXZv9xJy9AasCg-Mtd4<ZMi?b6Z`qY=+`a&mI>7JSqZd|(@&ZtPInP7`}?6Vtc* zLC0>>WkJ)AJMKJnKj^Y(NC9{IbZdBc*owH{bQuU7nA{z{yJ65(&@g+;hPGr6(0p9= z0vXuKZIbJF;O=J~`?Ui$*^qg8Xapg4)tmK$)znu1G(LO{n=<~IICbt4t6e*F-xgk3 zS;65S85$ZN#of-^gk7!GDpg!n79eC|oUA@#+-TRT^%|43`;7pDkc&!%+~AP=3IuDJ zouXK>UT3z4Lfhd9uvT?C+WN%-W;ZbXP^{LQl&|3=6KT{r%nA{(Z(y*Nt5w|EWrh&S z)@$WzePMZNdUoDkioQ~;v+J-8kCu363IpMKZwRGFeC)f9UDsXAw$mYT543Ikd!4@P zZ>9z%!_23{klP>_*FF}(y5#J-K4zCSo{Uzze0bBZKYm_sERG$wK5*y{-Mz#c0w;eu z{qcv7ee14u`VKqx9yoS?^m?<MC%s^K>0Lkb2Zz?*k{x@$aOl|m8*W1aUB*2BfZ6x( zu|peZ{&AY$YiLH`D*f4qkAExjed`Ov&g<So7#+qNLeJ)>?WJ{HnoWJ}(W4Q@qmTYc z?0o#-kN-V&t0qI=zrBE}2L5}3VA3}>(su6s!V~xJSx39=YsSaFwf|y%W^m9u>H;ub zPwNGQ+!&j+{^s8}{LPJ@!Us5o<M(nnElhqiOd`<hxK?aJMuvySMjP$c3opFz=%bJR z%YXT~mtTJQ#TTc*^z<x?SKhwNXFF<k0d|*I&K|{bU#qc8P*v8b&h;=Pv+A*Sv+G`1 zS}MC&XVshbR4~(rjRyC@;hcM%7+)8DygmJN$u7XYk!cr)@eysV&>}lAG4Ufm@+0qi z-}~Nu-SwAk-8M2boEyx#`_=4*GWHeP5uu(b<1RtlpmI<%&%gic1JvsYpZ#424b;9u zASw9lHx2Yfu%|bH1630SA`Ieu{q@)B_pvd%cb&aTaixr-kjoaF3@;><r3j-1el~0n zVNlPyz2&7r+!3M<Y6Z#`e0Ikn5rt41o8p~FGPzMuh5C=UG?75n2tq{il`BdVrf!Eb z3O(z{i9snC2suMY`s@Up_#OzkihxjKG8AB@Id(#Krhav5REXk)Vqoqt$HQH4pzk@Q zjVZES5WiL20ZEhC>BneYVo;XiB1S_MVcSP_L|}%90w&8r#jOGd)27o*B}GRX{RmxI zK*d!H$&f`D6o^JN3<8f3EvR@j1S%pRf%%tEqJlIr2TCA<&;$`(Q+#_}epih`lm|c| zSHh{6IM(AFX7XhUmOc>Sw{g(95@mC?a{<XEi;f0#9Ws!YbGP=;jp(IX@IL`^@<Rm< z{GQC9{XT*~{YpYOm}fc466S^q9O=OUoIoO_YGrX{nK-$6cAN3fNkIinH`6%l=g#2| zqlv}<bhQEy0c5cZ+1Hsnzc`vo4&)*YPCQ%MOPq$&YUnbE;LKw{PdgdyvbOoLou6wP zb$r04y^fnCWo1<Wg<51TGhfD5U&oWKH(Ql*tzK)g0_%QwB;%svvf8}?c8MPAp+|#- znFtbcg~A}UyJeLS3RRe8fqSMHBDSR=RDpBr?(o9)DGp=N&05x>>;S0Ep2L<wVlY)5 zq_(Ga&NZ`utCF)sp*y;e&fuGy=9MY~sm!cUDL0mvm*-~Z_5PBQyO~@@a)-ecHEBvF z;TSxWOwzwQh`#~r%|U40I@_o|rKgCi2>qnwhTx}<2z18yM1Smx-DHZJ(d)+Wcyo5$ zd-xm4&HU8VV+ZcK>-``20LLvKxNHA`0|(<j8KhFq2lnxG<IYEpeIa&@a%$?}V~^P} zm8=8oxa*sdd#BA7y+GEk&;H&6Js%FAI&tuzt0Gy!j=K*1UfgaQLys%SYm6DZ-yY3( z`1*;S&v5Vj<e^9RxwF0tKDUE?UwJU$=$)84_`v>KZh5~uZu$97JaF*54~eHvyzq2S z`4@%w{m%zKcX#(!yL))Rf9Gf2uZIDio&a5sw*2|DVCL^(>Julve(>v9`e0vEf2Hd# z{hqk<(X~u{%Pl{=PE&{bRs<2-PW66>a<1a$`=9uapG=Hl+WPrVeBy_H_=o>Hj$1zQ zi3c9&bqbpgEU6woBZ4GRoB~S;J5Tm4L~uE_Y}vAX`}S?ywmtjov&W7dJ96X*E-{M^ zD>XeuKT^csL6l0f=;jCgbtdRYR&TN@v7cozWvQYd>!w1g0MdbNkFDCBO$8BKR&%+P zl@;9Pg@pzC$j9OW8x_=}Ec^LQn<pnWPmYX_u@S<HX1zx3QU%YcSgw`pt-7t~2pk+F zBu-7?VBOcTQ8**@fY1J}BbYG&We9!tx`C;B!e=KyH>szTRHdej?OW|)H4%u~=Y&u) zDX63<k|PN~xr_(DMRb<~>2$ylQgs)PG=s-<aR@CTq%ub{KtU~_h?R>#6v{dl14&=f zwMP^XjVnt;B^A<gE7mb6kzf}A24w-qxN7=ngi?gcb>%!JCnq`UWJlGd4xqhOIDsHP zhPC;rNJ%LVm<y<d?Ju1w9_wUx9axG1@xvAvP?eCRZPwjZj4dxAfB_wV3c^OHf&nUM z)wn?^qEr$;2vsZ2fP*3MPznu+AP0t+d=TUWNE({MoP^X+T+C5^)f=)1MNyFu0{BBR zmW9HEm<Zj7BY{&${6Jy@vm$T?x<DyW2o(wN9GwB|EMR>k-65(|93``9(<YgeNm+^k zl%Y4_k%oXG;)e~_5&sRH!T9(%BX(?Lq}^-{<E+`G%1XJiSZ~w@?K4rsh5Xp^QaO{( zXS4aCyj?8CbsWsu4d9^()J69(YcP0N#_(@(N|B6W5aG!e3hh+0Qn#N-<?JyCRSF%X zvs6WM#6qWbbjBq^Z9GLAw05styH&4|J3BLj{OPl2SU6d_3d17<g`t#l_TfYV0$~PF z%xWFGA>Xc7w^NN4YvC~ZKp7skPZTl|u?#g*oZ1MXpe=qf^X&M@IEx~N#KGj8mOW7( zZ=bqM)n+qCYYMq~tx+y6jg1fGb6J)?yZxqNPJ4F1R`Eu?ns%4&8}&-9PM4MKBuur( zCb#GE_J(b;WC4_<c6?zx?R<U+`4lG$E3K4EL&L*xQZ;I*y(Hm5B_aa+uIUE5HL5c> z3BfP_i~kStfV)4vpXzXZDM*r*l2}??o|&1Mot<A<DK#5N%P?V(8<k^)iR)hik`{m_ zKGrE1Ltt2ytVlOKn(NwU2oy!SvHRYmhhiSvWBbQ%|8h^}KG=QV(Qn?>E#u%_lU*|U zs?l33dkHzc#t<OHRurc<0cqE!j=7w`K20-Z?tEnaf#~akPCRhSdp~_7V({MB_wdpe zy5BPN!25UIb0pE9p=tzXGW-5u{y@xUoO*2k|MXK|I+9Q@o!<2`c$jf#`QZME+rRAE zq;$8Q`yO75$j8x5?TuWgI&tuU-~O%7{C-r)^zMCs@NW(zu4PRfc>hhGaXR(21D<@m zPpyXifB&{Gx!(a)kZ|`M5C4DHy4icRt|)xH={sW<d+e@>pX!VovqHxXb}q-5do=%Z z_uuo7ex+d8P(^0X#~=Q^2NTNK7@#ksfLYZU_I<VZ;0Jw%K=0plceI4g-}Ii3-}`$H zM$Lrh_PIZP4&7bq>8HMQSWWlsO&~T81Tf=C7vhu+VClN!;pMI$CJugL?6xoZcn7=h zfAUcG_3Ov>kN%JUtNo&cOe)1bKBF6|H`TuL527RO#Md87e=s)E?!WsXMw+|x#o^|C zk7DYCEBn9?-}vdntIfB&Oe09|`)cewi<vsu$4vdZ4@TQGb@21f)WXwGeev*N_v?ua z1&Fs(cRsxIV6=jRKR@yl5BWi5z*~qQ%_&xlDMaf(@%KLZ(Bn?HTP_S%LFVQ=@BO_4 z@%sc0?jOJH%RX-UOA}y4`V0f0Eap9S$lA2fS@^(XV`FR>=I7@xyX-RdCtJ5}{l4$} zzH6?z#=VAWxLhsPS&02DGq&ff+1>7S_6as!W^6O2Srpw_5?D0tzLCgf0LNxO{cBXf zEPlX9NVn~NG}e2Pu-Q(+y={xFJW8_kFE1`lPfwqI<K&q$XXcj{&&^D)I5*qrW2-ho zh(JL}jpsJ5Z|A&bU!}-8fj}SY2D<rJ4E?{t5bF*oMoe`&czuurl~qJxUwt}I!KeZ~ zp*xwAU?W7AF+8xdItwDwvStbI%Sa7)z~z^}g|JewJEA#f7YvJR30rM@h>_mGuoR)7 zm3I=L0BcyMQQ+wpUv%|fENmyI%1BU++5nUdRG$#lBLH=QBFW@Np;`cOB%qimAy*OL z>hVyLPz;1o7<VTNAAqxky(4WzEFotpNpY?ps;(!<jfGJJy5Q9JqC%XIp@42g>{NHN z1I$pAjE)Zg#e5RSCJ8XpI)s?S4qPSYL5vMK3X>8b26&Q#IHjSAz#vnjkC??Hh`~xm zsuL*XV+q9g6#{1!8_XhN7AEV>n>ULtTLGyD0w<6%QI(v6HV8!&ltn0FGz)}W!OzYP zL`Vv*Wt2rWn&_}vm>p1$hBGX2|MY?il5{3B32MWG8Og<-RD?_xh+?s9Ke?p`>di(r zZ@-q=YT<aq9FkPc+QwpL5*rOwx8!a~VnG-i9pAp~G7ciFv!!CWQm)$9aGB2112~Wc zoWRUr!z8(7DP^}BOO%m1Z~1cs`+=5tE}zAN#YXPg7XL)7-Dd0_LJhWpld|?JPd>-` zhGN9&A1BI$i-%TF1Y4<6GfdNdP$-Oyat!A3&6HgVt~TnpzAS{TdV}f)?A=(YL3`sy zD(kLXBdu0%FcBjVt1?dPVlNKrP$82YY_cFS`sgA0glzj9l-+mD97!)oXQ^QYJ3rfz zgl@MXH*GEzphTgzh%PyfE5$}Zhdt!&4sxTwp0rpBP}lt2!r3!3Cr_R}cW$Ossz@5W z%_Pw|oN<Ak8tMbj(}9Sl(0`3MlK5g!0<t{t>GJ_o3(+`G?wgD~cRn271V8q<9^Nkq zEh6&Me~|Eg58Sf*Cwq9mpxr+D<<H#ofxBYw?A`mRd)Ivv@s5c5H+69TEjRwer_Cqv z6o>Yahkk0;EeGP=v*SY_^R>9MAc<X{{WnSP_w%>h_%V6EQ5^a5?RzF~dEmSwV7*wi zXVkWebRp6F+dJNG0L{PsreyPXe)zVV{dnrY=NN9j|DT-4`(4G6hwi!Q6VaDW?b!RF z>z?}JmpqOf?F?R@ebK-}`?2mpcJPlL^05e#*MM*R$j7zP5$|nJ2WRy}?#_t!Yo>nh z?Vo<=sB054Js1Z!-V%HI*qOTT`>@ifn`7^?PECFOmYaU*u#|A{bQC-M#d~i2MD%Rg zvG>E*J@wF+9@24GBi|S6V59fi-uab;_xt%De(y)Wc(^kxePgw6Z+`oWzw~`S{E4qC zs{>Bq-M)IKe=GtVTO2y^aCBK2@om^Dun@CDo|$2}ImzP1mIEjA#EBE%`ObHqdg`gy zUw@sw4a=n64xO{7v5-vvvS_l-0+iH#fIqU>!sPOLrpcaAMKU0wQbeeoA}p->2_89O zhR8ad^AAk9WjEEv%ca=x=;-8@&0Du`+q`Y-(C7#Y>19`3L2}ex79Pyuj-?x|CN4P< zcen?y{hd}iHU?_%37`F4hp*mkLIN<I&t5mYlmvYCMj#z*Fu5mzi9^&69rPw~#G)Zd zBI<q1>+H#u)CQPQq0J=2iS6t7__$SYDWDox=OY1~qe;P9vZf=dcpyfT>j%mZO1_Fy zsZNh%rHX`55S#dchylTrn4Ysp=O=W}y>3v%H0Z8ZP&^uf)sxmW2Zw~yp3q8mL;=MK zQIZhd&=WwUATtOG6GtFPNfu8CRXi{R;bbXSSt5p9ptwnN4AE_RpbOBI1;_;<0-P`p zQN*cIqWEkFQKTE8azzwWyeE_!LV$gkH)U<&gv9ZtTvaCDnbR8zI5Azy$HKr#JTS+K zFq&j8HIQ6KG_YELQmI6Dt4~FbIYLlOmeU^!xe^6XfI*rsWCwAMn74HS*2b;99J^k# z*AKu<2s5>4gb<f02%Q-FEr7X$EUYmyGNMw@sZQgNq=qHqQ*5K7qd3eY$%29eh%Abs zEJPq7q7WhhB?)1MQ{O6xasnbCv<0@%Q>ubeEWPMSoK~oHfC*75NmXp<#AcS4R;m?T zM7wnnN<L@5N&+m&m|_`4zV)`f!@0!*yu56myFgoNCkx5+(d_)3S<jwBwzq|(2U)`H ztyDx*ulfc3VUW%!sm7|8(TXJXhBgXnJ7H)hO#}3Z8c0JB9zX+CFo3dv2I{k6XU@!= zJ~e&z%<RH~{dl2L)J{Kez~AKquMgHSt{*pAaGgMZAM4Z=!42<>J318btp=WwfG-{3 z$pJgBi}-PO{Nd8#;&Sw5xvK~CUdPE(XU?3Ro|&B|zPPkPI5)pYQgY~saFEoCkryBC zacgVOhp>C-8?bBNy~hq6h;7Rc{`?x3#JvG_-T$eW`}^4b-Jj`k*K`zk4R>|Fw0Fn; zyYJ|6<Mx`ctJAlC`IxoWQzB@mj{NigXWT#C@uAyxyZP0pV@TfrojSPx#=CWeEeV|Y zdv3a9KCtWwLR|E|n0nxroBVa@UO0SDviTprt?!Gs_xwcn1GcHhKG(<l71|HozCY@h z?Y!&vRv&~m6Fd0y#p8~+|NF<z|CONvT8}^SCoy02)=&NFO~%GNqXn@iGz;<P(=kjv z@Bv1eeBVgxIym~7zrP_<-xf3V!Oz_teV93hcIu0_|9ryK7i3yzq%J^A@3}wbkEag) z{7rWs@r{eX=Q=r$|JxsrxxhQ_`t+S07D*0~Xebbmg3T!l3RSRLu?^U?X_M}PX4P}K z)w#L3mtTGv2N*p6{PQe-2r1axQ2l;G>mw2P)z?7XnsJwN0m~eK4iQeOBT2om5l4c+ zlFH&srQ)X`OCBro;^N}Sm^}$>FD}`-_3Epy{%beB_lN%GfA=Fl@*^y)tf~~00!Skc zhzO>lgZ-er-dAL-!b?ejx;6waE&(qt0iS(7c<xJhzV`t=r9K6|N(W5MNFao+-UP&7 zd+oJSX@%Zl^8=k>Lx(a>h$Bti4JUD!3CRK?GEUq!XLWCU@$gp$)CSU2gVNNeY(YFx zh)5`1qkxhmt{)nsiYtO{v{}`~AckahPDjrljRR+4JEK$)A<1ykCPD2zLD^`%(JB;= zh63@>g*xX!OpfA&Xr;K=0z^TACIZQUlMt=MKoY2pqNtgKfiv*LLghw>nzEn^s)bMx zQCg{LLVyJ67U&28iif1)fgyweK|%->5du-6Ks@xR=1NYpplTE%1_^@djm8C0T)8f0 zg@|H$C&y(%q#+obPNd1S0v@^mPmf7~lZ%Po%o9umqzmf}ngjeI<_JRKG-q;rg4Kn| zdT_vQA7aucivrB@<6{%~p^^OXFg{xa7s$P)50#iW;31TTNX8K*Nu_A3ida+-!ukOx zmd9MIE0~L}hm(~L`2Yn>#mEJAMyPH?0#J}IFf8!{Arj^bxl*|Zky-|^hdsw?2gQL( zWi$3pL|4==c%q{uC!d-yG?d4YCrhOeuDJYAC}5>jtT!2}<S<=Q&U|&|S%kn(JYUGB z(##~aRI54YZoa}5wY!=JbB(rLF$S2$I>9{;Jeac=at!8kDfdDSa`kCnyIHEmdBNfP z4qKIL)mpP*uiB!p8-CJCAQ=#vAj6_3L`>5{tUH>mh7LHR;9O*|R4TRU>DgCaesyMg zZfR+mZHhg^?Op}haxZDe!?z>hAxPCEuwY<_hS;I!L3YpMO~BL(&-mE?A0TO>Yd^N{ z&O3V?_dfjS!^c*Z4t*hZ=@akwrrUd5WE0eJAmK9}+<*I*$c@2gM)3Q;8S@$Teq=*W z0#6;>Z`UVHG9#RS$)k1T(XYk*l55}XvfPOh$DN;!U;aJ#^B?<SAMdw=!<WVfc28}_ z4vqibaLqs8&kVhqZ!@CJ*E&|KyW!fHQ}#z+^0B^%eR&9<&w0Q$w|3w%E&+b#Bi%0A z!GHgdX`RI5cmH<m%H)o{f9EE*T-qMP(-I&T*o@-|5lkJttMe2<Xp#HnbM<H^FFo(P z_J+;_pKg+l;D+mBr_3LJ(N3r+d``ea|Gw*%iH@nG@FgAA_OQg`6TMI2FVj-a2!((h zWb7Aoj)(65eD|*ndw=W>8?>@ww2FRkiWn}tY&(l4Zs*L*%-OSN^=1$v>K8bvnXLl; z%#%+(`S|0HpLpTLb7!Wj<(l3OoNA>9Gpxje_7O|>at*iK*=9j|I=Y_aj^XaUdC$Vk z>RPXsEBbmcaSkGAkDPoqx9zg+TefY*3C9&5o0u3G8yg+BV|sSx+{`owk)@Rt<`HtY zY}@wMtKW9T6<2KDyjee^+h)M_5e5G)<IYwD1v1??pRW_@g(Q4-0+@b7$3~%ku?<W& zeD=Cwb3`xr>;zN`9jYXp7{P66x*TAa*J`%xc6y@GQZ^boJfW=dyDYYU>{J;#NTz{o zPyzc%F<d;{6>6snARQW@q{3*VCuAT(MPl&{K?Q-5)QftwT=AqDfm4X`#Nvt|igOPO za&F@q>4zn3s@x<bBnhA0tw59>gYB;!sGSy33M136K0DEnFb-V*7!VE*A#qv}l?G9x zKPaG11foz73J4O21c*Th@}mMNNF)gutg-}<qvDbv$p}Fo#eq}Ddp;l<7rZP7goIF$ z5RZZ0w7J!R2wl9mxHvmI8`TFW4$&7&03JfGO1CmS5hMeWDn+A|3z53ehmnR#IESho z`>9|EnW-5Sob&SEh#&+`A~;=)SvsAWC7-j`p)q<3_Qe4Ewy-#<Le-I_;Xz0o5Jx4t zfZEZ)e8jAMUXN1Sw{NdHv3SBP8<$^xIWnnqX=w?c88yg4CK3c>QVLOafz$@7bt@~K z6rc-;P$QZkf$HYw=A1pe8ExTlfK9EYt^kCy`YkNX>DNJcw0xoiMNo_-O~3EDsy!wq zCO1uNo|u?$hO*aSusl;cMJR69&j+c?<l|&QWF4hx*bRL&10WyCFtl5yn0tFzVKAG= z8*a8Z1-ed26r%`Jaj~>aU9<vyn5<<esU3rgFE1~nn7TkCfuy^IjMF4~#D`q1T5r_b z<x*{KcJcJ-X{Ig)kNNO9>vtF^qS^&UfeM<vSHrd7O8M}606X@7WAzHHzqpz>+<Vc( z5x;Nndk2ZnAlau%AAIm%9XRlX*m2k1z43=d-K%)k@O}k4E}f2F%$hoI|CiUfp*k9O z&vw}7jn)a=zmGj+<IaX|a`bj^<g0NP&|ji=r$`qDGVz;iQzt%u{}<P@rNamAx<Yrs z(76x|`+(-(c3%IK=6@y8{OkK%m)sM3`S-y;3eR))$J5=fLEm}pdu&=zV$FWpAa>pR zk9%JK?TLr}DApG{KKRj_G#8)$3b0Q`aPY1@xBtFthnk~y!5>Al`S>IMSM1XB4t<{} ziCx#n{LOyOd=yW=&?VkX9mSfXr3-;mk#ypE^wfdh`hEL7-Fv@kFQ!vVeJTBXeC*M$ zbvHWJW-*5lP|)QVL>E|_SQe4b5{cUhSb3>k`zsh&RS8+SUVr`d=bn4vx#ylI!d|OZ zsp7awGV2jwWkiT>cVcx$O%}M!fWJxs)EsJLDMTifQU!}E%P4ZFl)9v+_8#Z}#K6{N z`{kEy-MZB|#^c%>P~8vx&=1{w^UXKhaKqJCUrjExt0KwK<5wI5SkC*v=U*SAkf<bl z_IDlbWb#8I3ZMO^fhuembw-YifK}-=LAe2R2feeryvW{+TwP+JE2XN6$c*A=6UhEb z4A2<~6sMG{?Gm8N>mW^))PyM+F49JNh#SBry7qG-QiQPx7@+D2jZ{Ec6$!&#1w|)L zlYl5Ht6E4(8a%XFhE^8Lgsx^gB?MIme_$gdPC=l$s9g+7s%ijTMZ_Zz2SM||DI#4$ zr9l)R0+1v1$dY2JT||WdHUJO3i%L+$ula>Ikf^98Dgxj~8T~o}ohqC>pDVa_TUR15 z7zZ8%YRm-+5(H|2C<Um3B+P=Oi7rr((5dF(rMNbt7$Kt6IwZhA5mBUAh(MI^00|d} zLlHj+oYEWy;t-XjB0>aWNhpjQ3`LSAlLd3MYSp3;AO|`Y(D_E3f<QG|!`%D#5lBS* z0kjT^L@Afz$RR>;LJShjNCZwmL9~$WDmXVcPY=L@YlL&fIx#eyFBEd;&YgjQS)Q_U zv$JQ<oI$b8n>P>SvS+4eScguXI#sS#wrtzHw6ZumKQ}%xfzriNiFOt+LM}%HuL}y@ z%u%jXU>F%4r9Y;orf{Sg7pNh9I7=AdEP_z%g~Js_I|gBhws5*OZ{A8MJD>(jS8xJp zCMysPXOdz)!zx&Ga&i;PRwmWT4Q8_TeIffMAzAblD_u4_FfxMMKUi<pN|hp&pe-vI z>mX$bkx!?zQ>~Svy#bEKq7wcl2BA_kq1)jBwVHX|QiHPtO>pVaZF(Ay(LRAdm(nk2 zPPnpM!mp|^PTJ^`8y*|ovV9vo7{6*?7^<+wwo>f@Tw(WnM6HUyx`Oac6B8`vM3B!U zlCxX3O_^GQo@>&u!CaQMqch52AL8r`Py-$~U8ma^0K~B&a_AWxb{b2YSRRT+``mvN zrBdz17he9(lh2-f<7~Cks8*WQO1);Y1;R|AhARREC{cJR2`CH2P{W<X2I9~WqAWlp z$P^tO5X}{c1JMB#ibyxjEyRJ?z6-Dm_6}(B<)7rV80&eAjg1gaPEKsuGRZ+C5PKe* zHjVc@C^-33=BhYj__l-GfLZARv19LtKXv!LciLW7(vrZ`)*X9(;=^5=`Kdp7#J`wV z3_x9sHnAhsJ{t2*cYMe_H%Xr|N+}+W#9r~>{*QghJumO%ShH1&YP50SazMNecMTM% zkD_Sal=v?6*S>O0awGanJ!;g^p+EGK$;-eJ>p+A;9U4?WZdbv?>Yp_6`l~IJvK@qH z@}T+u&hZ5c1eHV#$FZ-*E=<}-b13Rt<rWd2jD0uD=>Uj2*&fCiHU_lG@kWs7J14@* zV+40dPqo%$IfmpBTEwv{_W57@-;Ve1bd2GPe;oIKKlFEY*-QAD_dF#5wJZ7UFuMi7 zW)VM)$OwR$CUzY8O6=zAo!8z#8|XYcylM_UKfvzQ3YPFNWjftNq=&oY`Wz6Ypx6L$ zLhD$ubwjxZ_fV?6YUt+Jx1~<}$s>OezN*Thdwf{+Sg$!)`>2h5nOn6F$L=`a`Jvl( zyRQ$r4;R?sUkTwpB+JosUy;>qM4~9ynbcZAgryTdM4K6UE&O`RLQEH+I}6<LBS-)8 z&;R21kz?o1O|$$m7Y-MO2GX`)V)3n1%Y~tQxl*duD)t^q_udWNucUSn9~iV}gP{;% zlfZ#NNRq|DUckQeJ3Nd6$i$(|=JV`dX`^XUT&b{-vvF(Gvw6E*JUTM;_N(9eH-7Ma zH}BcCdDA3i$A-sp1NP0rynTqjVBdnaPda8XJi^Tx?sx=5Lchq2K%MKxnnA<Q24ZJ- zjeTUIK0s#ggTX}yg@YtS^>XsC5#kI&T;oAwg9@Z1p;hMEf}x^%5(x~*(GjHS2$I8) z6OppCdbN0GI8zZ;B5Brf_7M*~QCcolOXWf~H!(U!NL3tT!y~PFV=$c=DGU)|o0V~2 z!e$ubj+9Cj_ME6m3pB9V=3x-B7~altu_QgM+Aki-^VmbpP#8nVibZ-txxft@vyR}i z9b(B1!HrS_JrO|CXLo~&)N`%}Jwj3p#&;3WKtTa*a1o142A|JP08Z5|C<$Fj$_Bdy zqTot<^TMFy`awm47uP|Q2wRXZN)oa*5i!GQC!Cv@AWB-u0@_j#(K$(kqznby#RGv( zWrHZl59)~$BHsltCu)9FW6{J-Oog!6cs_&0r9UAMl?cVzk3(mrA<6dKy@_$0nPR9g z!am*o{An*~bc1dnpU*L=&^08OGu*6h(>jm>cyz=Oi&utXn201HRgkQ@XKN|TG6N?P z07;Y~mm(~I3kwUyV%f2oe7c%atcc7_2*F*Pm@sF9;?#m~r;&sNCRiv)!1<h;o0Bxw zFeIY`O`vRH$f{GvQA)#!T+|>!GHOpTIO!U7xRkcC!H*E^4<`(SK7yakLY1=i3UDF^ zX)q8XNmjyx&aqMsWZUV~m2Y_qW=A0U;-I24%&<`-UBsU$;54yn8jZ0ryGLC*pf+}( zB65K`l!gP0W~h~E^<dV%rA&y~=};$m6(`>~GdDM1tFhs5<HwBIJ<G*!<q9X12GYi+ zh)&bG5GAU;KJlht>cIO~9ZQ_j&71AAear<7Nju(u;kUkqrbXM;(+KB9%q$Yp>sr<Z zuw%#GyAB*$I`-(kH9u*3Q`|F|dj8nzsE8?+#L?$t*N^P}<O?$bgIuRls1!LH6BYk1 z)`_n@+WnQCHx=ehdU%R!f}1Xqt*}|hN4qVixV3!EwnvMvfxx!5wDTfaT=SB()>Q!m za~Du<H})j_-+%w5HP!!8;u`RWKDz#!3;qglsqB0K*mYa?PgtD78yWS7pX;6icV5@^ zRpJCfOQTq$)#4AOhzKls=gysb^2sOv<DVV+vp@aD(W6IaW@Z>aoG)&BV9P5>?L*uh zV}2`6SvOS}7=$c_S{B2`2_Rg{G>a)KDGMv1BBGm2?G~Kkh*G8SZ{51}`s=U1;f5Qo zyz)vG*~_+XA1V|i7DvwxcTEThK_5XXK@>e22CR|wCIQ8Ktd}xL9k7zyzODY8C;03) z4OAgz=u^6qK6SsD_-|N90U22gP}Gl<f*wktHc%4;QLK(j0o(HWXaph>#&Vs74IwW2 z8gQe?AZb3)8CW91MktC(MbVEgSZ6xG<73X0K05(P>jxO55)gksP>cA1m?eRpBS}Qv z2^&e;E6ya~ftd)QG?!#Th?GTOuoy%^MI>1;Sx!haRHP?@97TZmoz|V%#6j{&iY*FP z!svv^49vj@npt2V36Y76By=SM8$^l|32-`|2Z1y26OjUlRnn<xRuzR%kv9SKSC50n z(L@@GZ$(H)k%T+w<A0I$TG<6v%o19m7BLan!(pwCN!`b9;U*-j)l3c8<mMby_HDRP z*-Ra4yEu-XzOswE4TZy8zw98PlEe!m_Hrx?WfD5KAu!kI<yA7ERnWOxiN!<Rn#oxI z!l?xbu-=T0j-q+7h}*luEQaqqHfAq8kP~16aaDDty;{ZDqd3H15Nf9&Vyz1HnzY;< zBsCRMtC*c5KSW4zd&9Fm*=tYsxb3J7MJl0GN4+6;6tek3#(Yf}{R2wySi2flb-mTZ zP*g+#3KCJnF-W6PV+14As&fx%54)F&nHdn_ZW5sgS`Or_6dI}%iIW8vNg@DtX$TK= zgixJyXrMvUej^|&iZf@<%+Ag)FBMD03I{{O8tI2k2W~7mPk3Et(Aq$s7$B-rAReEH zsS$xMnSjrJ)8Q5KwVn@R7CfmBJW~QaO|b_5#;{}W7Y;q~=*Oi(7nJ{=YrF58?L0;u z7{J>7)f3U;>qK-CBZ&k%O*lV~#&+m^vFp0-w)Fn~@x`Kl)4Hq#TYx1+?ZD=eZg^HP zcdD@T(H<`<x0(_-{9NqEi0gKB_gWCUiajys>BNgqS)E>@gU{(MPF$S@l+>ieG$n>E z#2-;T@xcA(xj8@n#4N4ZfA`O9Yz%H3abK`6;(fB?y6A1`QA4c)KehWht^4}#B|!WX zKJolhKK8u@#uB4Ng9<QMip!<fUU~hAC%$v|@Zsm4er9H7))`M9wqWgR5V9GtS76!I zJ@-X@cg;JE7`x)w;Am89&03v<I7IKGHmxEJP8L(G%Ya3b5Q?C6yq&fO!dY<{#4P-m zU4Hp{-t(SayLMf7-E~)7am8iZuNWB~V-ql9t2cX({9q=Vw+rbu;MJDUK%m}_g@Q44 zqbKpgpemB^*&TRl2c8;%n{*8!mqy8wZ#JY7=vWeE(#6s;dqVB}9nr&Wplq9DJ2ls> zP*B@`sBpi407@wWd>t1Jo4BP)6c9DIqq)ZJ3@Xil*L_X+!U>Qifl4YK<qs4^`oVK| z`1>I+m`>e@Hbk6JW<`>S@&`&Vi|EP{-LdpQ;Exp#Lg<Ll7Z61kTn(NfWJSX@;Mlv` zE<|+@REu(xQ0)L7U%){{5T!-bGdYM;6^RofaS61->p<XC#1*v&(gc_3>A+JRLY5+L zDwwP}v1uJ`<h<4S3@{I~kXHzmI+yR9h3o*DL1n%d1el?tBuTv7xw$!r%-IOUx12sV zTU;sQ&bf=OcC)utVJk_K+E{X!WvB%qlnT(qVb!_jGt0n<3p(bWeU%W|iZ~sIk5{() zitUDQvNS_!`LTPD+>ONejCH##x%#QVY|hppil6`tYK0^V$QdcvgB*Hfmt@e25G84^ z-U5XVVJh^6JCbD|6`__vxXc5FAnVb5`xO~}<ma;P+PL|`1;TV{z^=eMNG8P)SgoM2 zdD>1Z{{ijnV19ITd~R+Av%^mVX{jybZT};sxy|kcTI3=}0!2g<r;LGIwSo{xI1#Et zALQWrG9*xdqQznvQBhDkqTol4q@e(G{?Tu)S`8uEatQ`D;(RQEp2Q0SqT=v50q*+a zh7iAI2&SH2<8`hPsD5Wvk3ifId|_7{xP}>&jNrrrw~UUDuO8i(vTu3+`}ZF>aIn`7 ze&^l;#Ygt}L^t-teMS`6vun?u-Me@1(y?pTO`W3`;-=bp{hs)=Y)xCo_DRD#m_kB; za=Rg}IO3i8U4JK<)F2|YrN7|vqgbT`h7b{=@h)_3ofSM0Jk|X?@9Gz$RuPk#ym%P> z$w0!LQofYpAQlHw#^$30cE|kRsjoeHz8@yqsl;8-?)^+s>8}K8ppbg1+XGIRI+!Kk zBCpf-LppVH?0sAYPT)N^$Bz#7bmQi@raRu{zO?0233wB9I>J~TluW{Ncc9Z82bINE zi!uxE%JTB*)2C0q_WB!dya8QHJZvoGL@0&)u%=6<<gmawsa?uwiDaqOlB!&V&=H7O zK{8!Y^MTU?nOq^yMrC4h)8&_6{`MW$+;GDUTefZ8wr$&%?c26)-Kuwjy5I2qRT*>$ zl7Xa2jTl6ahKhXG5NcE;2JrwaCeSl(GvaUb@Y!z~RE7GEK4Rm=u8A$*!ootiV((Z* z6Bx*1c#z9JlPwT>qMiy0Qdl}G0)^sM$EAS3mJ%!yl2Is2(6CS_c$4>mFP1>aLcW?O z{#bQDbe~8d7)UU69ej2Ii0Y}fC@}c){Ur!N0&y`bsq+wu%?0j`N;v6eSEvVq1VCJ3 zl@vW13V|X7B9OEYD$*0NTuC5|Sw^{QK+TMvSCm2saYYD;D~n{*CV&V@h*nt#PH<Pd zdLl4~A|a9lwEziRTkLlSu5ke4#C4_>vI*JP2i=($N~IDmP_<l5*(;iCIKjq9156*b z#yC$K3}gqh`PFB(#VH`o98`BT5>85yq&Pxcw{Uio$$Vt@{UToe7$Hhh0wPnHLcFzF z)vgt@GHC!1qNkp=WwK+L0r|W=4a;&!E!3#%*r-GtXC8-{M$t6nP(2#LhJQ(xQOue5 zKlhSFTi~GzY78Jr)i(U<HI8<po@zDHE%!)|efu|~_cL>ptMziNUTd^!%@!-EnZ+J{ zv4hpm7CNLe4qNT4eQwb1v8mK+6i*G<J;|nt`-vI8X47t9rd^ARi?lib{!*o?o<f+E zceeEx)scz9YKSW#Kh_+0{9jHBnYU4ImP_&1^3hmKI5IjkJW|LPvJ`6Tp&dV-X#wY& zg^}Z;;D$^WAWGpRR3r&sG6A2xir9Yt(xXqk9w95*oHh6_8k}C7g&y&Wj(~^mx#uT# zO^m&Ne-Af!?}4u*KegoZqS&$j8{at8`}k(BBlg*)K44n$u{9C3WHi1Wq*J?lcmi)G z;>vYyfmX_!c-`Xx&d{@hC-#@XoB&iQNF9Bo`*Go&`|rL}SrRDtOtaX>@4l=1_m9MT zvrMc*yllrI0VH9QGR#Y2SVel@FLl>4^(T+6=O?DbUC^mp@qoWaaQM;Kle03ltR(mx zk9`SKujjp47lfUkJap(=y^bz?tAj%ud=H?Fr^JbwXm1x(M9??^#Ug%9#V*^n+vQUA z)TuL1J@wS#!-r>PW+=kwf``?UgVi(bz6u*43rnCa<qo!}N8*f2mQ1pVXuT%PyUjLW zsTGJzAZszp|3EI=Xf>BsmMe`KuJ60vbHi0vzwI46u6gU#ZyOmO!$oefN;2l{r6}G9 z21p3foNB#6yL_x;t`NC+NNf^5y8|fBga$DHpXU(FNSv%-E9JhakXA&f9jmH#?Rki+ zTNQ^_7ZL!GDA<VscB+DQgFsbWJp6p8FhoKU1WF9b4e-<iXx<v|g*(Ne5XO>gL&XJ8 z>V+UG3>0+_P+UY9yeub8l%5D#;sj8FKuG|BE}ovyP|z3!lu|Mj2ckn1OteE_5R?qz z8t~;EBrr(!9Nm%~V-JK<AX+MjA`}lqPCOBb2V03p6hgrSt%<;+h%2-j0WPzvnE}cI zf$hx$ehcS3&8KxVUuSQ2Fz;1~C?kZ4Sf!N2y`wB1*X-;p9@M5yn=ZTT3cU&s9~RG) zi3EPKs&+{d7tB6H1SsyzY*jON06bnfy=Xx$5-7;LLqy8JsfmU-0!>*5*~;~#4OdE$ zgbg)x;g{0X4JXwh%5G`u`0x<nln{zT2O8wcr4}MkoL5^TkE)d`3xulC4euHcS*-v> z#>Pf!^-7~zX|>I792iUwX6^MGFiSpOB|{8l%zGc8F3jR@Odv$Q45f+)^%fAPq>WxE zNF$2|E-x<^?FCm=bRHeGS8(GVOP{QJC$@=g`uBku(M{F}p><9He<Qck%7Ad|>L$*6 zySP%BnVx^`wNo#2zhe~8z0N-B-xc$IJMbI^-T!<EAXCK9lXzi3R1|AYkQad|e*>Yf z=6vu5b?~G<a8i4~7w&Y5=kCq#v!d`hk-Ve7fBT*fB%f{G`>A`A@3g%kc?JApVP97< zC>7cjpSBWEDL`BX;S>PMO+q{YJsz1p@!VQp!MzBeWV=U$ye5Ez+5!Tl8><x07eOG3 zA%?d7p0El}wdxPw^SN%Paqol29@!WD-t4N(-TNLs{$RK3Gj-rM?b|s@c<GT*4bjJ3 zT(h4L<+s97-1+0(uYX?egW0Vw-upmoO56L9pXp)A?-G3T99r#f$G_F&OdW27mQ92- zral()GS_hv_<9ll_|-)N&HcKzPOQz0xfGh+BA}F(?`ExDE|+JgXI^{lwU=Hz@zP5# zl~#)E2FTSIqae#4@ffrk!p5@8>aP%i@{3qBRhAH-1I(<j#8p<i2tt7C%gXJ35YCkA zwS^V?=s)Z6w#&9(dDT@ru6^g#?|8?=<fi;kVSLjB$mVl{9B%6pG$Eq8l5mz-J*gD| zqJMYbt4u&y;=x>Mj?AKs2f%J(c=N!v%Nfvq_@EOR5`YM`vwxEU>g7h=u4=G{WFMtX zUFZnFc+dc|0oNIF5LL^?!(Rc8L6rq~s)G~?p+GBqb^^W~ox$W2E-8kn{6Gv4B}osE zD9IEwe0_ETF!uxn#gJ@rPpFjQ;ui&LkPK=NA&ITT*%L5O3LYY24nUwa$>|o$BB>e! z10Wd<73m3A)hfKujt)R<NRWIeo+AQ?WQAJ9<3@xTAy5Eutic&b2tV||Mp8t0f~fTX z=2$5r(pHpEyDAdIdFi2NFB1o@RGOw|@Vjz^8Rq7c4Nj-a>V{h~P@9t<Ye13Cw1uRy z6q1A|B#Fbu%mV7o8pB8{2L)kJ^Fb&}7IDoo&{<lb5YYl7PE|n!QCd_~9l55f15=oU z0C>bkr8wuzVid$(*Im0q!+CpKb($H`PsGSqUF1>_egKhD%#wI`w1w(aBRm30cmP!o z6^0A>AzaykjC~P`sWYEv74upk-fD0!IV260Qfb!16pk;xc;0+sr!8s#a^aylgb=9< z1*qC_*?Z$@i?Z4c%L+Ec?<E2q32?##kWUt+uq|zYnJUPI2WHxcWB{F9+Kcdog@rR` zW?p&u<g?Gb_~aAMJoTMtUWmPph>5oaf4Nj*DKD`rV1VfG*<r}Z2aX=P%)N2QI8li1 zM?eIk_k=H*fY0ur-R|*l<VHTjW7r-0aty$0+Ta;~-WIKmo@JBm1q@J`BEV-P&^~g{ zp1a}~(01H)_ni?5o_dLK;(2#>YgE3o&iU=bNdZ)l5*qWI6g^f#cMq_SfA1inl{2%= z*u-P%(mo$^5T~GIpevFDVv}fn@xGYTxMS~whnAjr_}=^P*k$*-+AXkm?7R2j<4cDg z+#4JFkA3blYYzRWGQ{Z`tI^HyP}F@u3;}okSj@|wO1)>_o%`(Ax9{U?9`8xTPw>4T zxzoq~>hVwyQ-5>mIHtZ+cHXsT_nrHG{o&*D-#l<@>}RHfzy0aMYnl456#f+M2RG0> z7zP18yB9on2RgM2*<9LQ?E%5cvbrrVFVD@*J^%dktZuA&_`nP&7D2`o9uQUNOT26h z{NBJFN^<y{#TbwF;ldW2g!(?Pz=)MTCaSaF);debhO3=PH&NDJiDI|KwFc6)Rx>j= zu>G>juGzU`$2;HouJ_#V-d#7nW5>?Iu>Fe7CPb?|K&F~zwuqd?Ayg!Wp2Q1-sz}0T zJ9tt8%0+*|&>YdN!(6)@%bSj9rNq%h+ay9LZaMIpu$7WytZkU>@!WL|^)=%Mzz;-G zsf&mAtbo!X9wITIvGf4ZxU=wDi1q~V;vAwCB`b|F#~`tQaj#JD*}V`G7?L64n%<-B zQNSGd1EA1Pm<3JfV*rIDM9+}`6~Pd~KmlTK^%w#j5C<^^CD#c_NJ7HJBeBl9cB8Tw zqJT&i)>iGJFc{R{zypZD8M6r>LQ+JaO0Dj7BgRiHPLe?s)vh>jN}Z>3F9hL++U_Hl zAJjYj2kp8eJEvy7VYdxC*QJrM$LW~djT2v)c-AgXT4$SOTFwEciEX<@B$q2pPEIl@ z6pPE#(`Rv<up85b+0^wyA!nZ;8XX-aR4*`7$YBFekVz@xvQOwK^V{$x(W6C=*q3;S z6B4)e#}PSD4<fy7_2viB8LgI<7M7NlaO4n%w&;df<}v$abz+QJj7rPpqKV41FhVvz zSSaMO1@{%DfdTX>Rqab)>Xd<uy?c3d)Ly<tlCo+A3{YsJ?w5u_sGE(Qli8%m@W?20 zCRSpgarRKen(crQD%CPatxnl0tEkNu<|Nx9j94s4qnr`!F8x})Le<R0&XsL1FBQke zH;s&K8Xg-*y-a$rR%@`p&(GV7tmo(FmzNgMq+YGG8ufOw!HT`Ivb4Ck$l8yRvM@HI z1>uvnb90L`GxO)p&7MAe?v2+^Klkj5-}%ndPd@pb7hZUAdU}RApHflSJI&l30d#Kk z9no*fVD68e)m;)Do=MyTy(9K*&5dKK`_(iWR6P;0XiI3$8vJV@W(^71kbz<n48MQ> zfw+14enR#VVd}91_y2zT0*yc^d%umv+`^Hv$*0xsyAGZoZ+3ILk$lkETI7GWOLnGf z;(8GGC=LC~KHlp+PCIYC>#hTb!d>eJ_Q!o+y6%Aw{8W$65>t^{;nR^3&TI*!iFj=3 z>E1`BQy-7{zqpC}?c>!C+VO?8jxRj;;9ZHEb8r3Bec#PKT@!sx{eZLcHxC{9=7BHl zkNdtjn4iDpwo7&S_mX4k-~;zRw9b*aK7_GKL{Pj^uT(i2Rdy|GSy+BqmzP(TPM<!_ zLdg=$iNn5zLB$qeD3@p0*)P;K&TNxI5eA!m2`QHwWV4jZ4%m}OtjajY19p#_Tg_Sd zS@)|{R;du$?xpR{DErhGPP4mm=w67)whJ<qvaF8{+lx*}u{mM8g8a9<<%(;szjoK2 zn|9y4>*{OX%7z4wYxUxzYY}C&I|2xghOuM_zYCDT&x@ds^-!lRKzkve+&2&UY2IxY z?e_@h(6VzG@n73=DiLCA+Y@F7>;kd7_yIIpXaZ&3*3>}f_?Uxgxp>$mf^_E-VY*bM z1Eqlt$^_g9G0PHRxBZs4yk+OkoiL-Z8QV>=Vj}`w5oH0&l4KauNZ4%TxzD#ir{yq< zUoagV*hymovecI{5J?1zQ>CEWX4idOS9L*`GN!t7)dDjNI<F|gK2@b+xr9JONl<RM z^%1Qgs$RN~B)P~06qf>kK7)?tA_5|+QMp)vibB&wAykd<Lx-7KB$=c@97w|?D5xfY zzzm{EA|xe&B=V_6kisyiAEid%M>m+IGg&aeh6U(TKvHyC0bs-1QCWyUIzXo)B2E`` z$;2al2o*8YyK@O3jX#DFeA1o+Ju1wN3@pSswUh;$ors-*hbRzgCk~Ognn|2mkS{uL zn)-rdDNck?rKGC;bm`0kO$Tuf=)~>b<QjdA=V=b)z+gMwt`B4yxooPCPv^3k++f<S z5f5?>lGS7iA04)7xml~1R?6j-^56WSAKo-Jaq85WnVFeQ6JuAu{i;oqqm>FCT?Lt= zBV!X2oACW`RMBN(Vv;puxwtYmF+MUjTE}@xrwFt8Tq<L)Nt|1lCoEOU<hGas25A=q zxKgspis(siGxRu6o-UI9ge1{FpJz=<vyj+zS3Fr(tU+_~SwQG_P6|TGVH_-i15cmY z7x$cxZI7*{@h#2UWJAnop}UrrR#-oW3L~2~O%@9H%yxyD?$B&VcaTIBCn>_23UFnY zmKWKi;>0#vc9}XokZ+}Ojn-hZjeSvTWH474u#Xk9cG8^Gwr!K!w{I>CWw80g#K>!} zzf`K0SSMMqi<M%zR<<`zrdz0MlOIzJCZJc{73QJQvE>!}U~sF&FditC>np`-rBY+a zjE|1e!5KO_ld4sV%|<1gY1Yg37HgdR{O}NAE1fA-YYR)uGjof%!bqvoJU6p=ZhGnL zxusWMJNNP{XI?*f?u|E2(O6Cw&Y|JqQ96<KM!^8YEDUQ7#<$x_+o3_&bYJajG;3Jc zelqEN;!k%<+rUObuS3(B4w5=6>~N(JOy2>k!4YYfPK}OM{=5jK1C$#8n+ggP5k!Rf zX#5kYCQg+q&e5fzJEEGu`<?Oa>5I?)1>=Vj)IvxcfzX{U9n*CtL(w(E5FsgIPq;?( z09iDOQO%+j)+`l?fwKz3QUyQ(08v7uTNJI<k;Ddl$2;F`YsdKb_!U=NVfINq6~A%* zvHd%)dHY+gxNLIM_{8|==E;d|TQ?ID9~~JQ9~&V;s5m_2LScGw$BjRE&k<L(sVBt* zyFTM9@X(FYiaUMVoDPf$LK;tqLD|!?zs&adX}X!VU)H*i`~WOaR|_OKXfp@;aWFu; z4rh@l#2h<p);7%(_0fjT7~?ds8Ibd{T!x<HHdW{{CopKjIYS3aK6FtSYrafCr{A@% zg#knO*MIXn8+@YE0q=LuJxARy7cn3++MB8fScf^~b*Kp_&oUa$e6!NWfBXW}SqnQp z{Lx+RVQb>9Lro{<1h<-+=@R3>#*|}-9clKl-3L>kFB3q!ZK}56Mm<sN`Hc%R^%rir z@$MsLvpBr|kx?3Fa*Yj#b%71z#3_966Jw*p$%AuNhmxGXy^g<j`==kb)^^S><f$Se zq6CC2jSz)_O}P-2#A0FgCX02m*=`JP8Xlh<t+%Sn#pPzIRTvq{4dqJZ6;`78xjFWf zi}Op<XJ?pNmKRq>hKAS`)v9IofAE|=duDcihRLGdtTos#r5d$%qu8vhG%A%;y}=^S zf`&t!&EpU=e(e*ItbMICTU5LiHVE!c+9s|qQ!jfH*51j{@d6vFW}}d2Z-t8WLT>Py z9dAdU<<dfacyQB}(V@}o#O9G}-*pXHl~Q^8)@@rRH#1ponVe)ZH0rkZG*COrW}D@i zEkfJA_D_#-PP1XR+wSVb&4(YPySuJ`go8oQ^WbFbd6<_-8{Iuza?Rw}(^%pVnc&#g ztsb2P8f^g)^_RK{Xi=l@L>F5UWC7X>Fze*xByJ9E5AW-y(Kd~_>IBsl1_mK=s0{@x zjY_Rm)3es)YJGljx!!758*Rdr?H~teB5br0ez%Em7IAw{9ooNDt7Rr&=P1}N8fIyG z@rVneB|g>%G?-A0Wc@A{i?g${XV0E>nX6}42!nxQkfmY>=1W4Qe4+y=>I{G~gh4&^ zy3S9P6`SHosFVrqK*RvC0pf7t%h7f`Uh0KNUE1`J)e};WvZxe=lidR_)0U{hqWfYA zz?_6?><My%OyITbyu^!$iUT5^DFQJoB1#Mh4^@a+KscwO!YHE3oEI>QUl9=KimV?} zGAaQ;6x94^2*e|P-zqzA0b!2=3ppcM9ND5UkutZr1(|b!^U%jlqlW#Qk<Z%CkxT`2 z?%3Ga<BuO%US4KC!Y$Sr$3(Ds^CmXgjB+N1YN>1=$SGAAmP<=Zj7Ef5|8;&GA;K2U ze8tYSU$jw{n{?W_e0E~fIP?F|aG_eOoIQ7D>ZKDcd)ZRU+*e#y9CY`lWr%J*vOS)w z!S;vt%WS1mtua-Z%i+4%n!tRG(a?+hn(e7-l(Ef~m8vtb+lezYgkqQ$A?B@P3v&f+ zl_f5llf(@siA-8O>JWZAD;2BdQms;EO+`Arg(dwAL#~`d{7378lznmm&)+UYcW%kI z-gCPIlyRqket6PArP<l>vB}}l(OiCb00U;SNNG0g2fISvKFv=XF-g18WFwXzw0CP` z9C8T}f=nc^fG#f=Uw-NJ=bwA=$tRxv&Uc=9{<$fVufB5fm6zXuGX|&9D%{4Kp0b0} z$WtBEMjv6hb--eZfWVMMl<my`RjYP)>iEf76wp<B@+Rn=@q3^Hza#`X4#{^QfBldC zt)DRAWSr0uKIcsX1BQ@Og5C#2NTPttyeRa#LcW_SN~IF#JFR0N`;35{H@wSyF+XL2 z5SM>G>_9{(5!!Z})I&vpl88{GKf;nB&S=;Z=N0&7A=<8sK~Et)joA;<gf4I=N~^W& zzJLAmksoxX4jw!he=H(_6OZk`Wz()tukXd@8vqSSr}y0ZsY~qtGC)6kn}3u&7*KXl z{F0-$<lXoGUi76_C%(Q8Q%^ni$q#J({?GLEelI0<T)#W{>&&GCQ<Gcid>G)f*NsZO zTB?>-$}7c6u~M(p>Xnt^(!#>RsZ*zp9Xod7#0es75AaKC)oMOxdzh_Tw_bJCm8_nl zqa!!maKl^QcGdj+Jf1VB0Na@g`vjckM!i%iEfrUmOGOeWRw&qfg~!V&Qmxv%QM6b? zK@?jFCVBP=dIe@SGvMyMGtbm+zjMwNjbnw+=j|09+qP}ldF_syZhG(E`oNEV-@9)Z z%H`QgF-X{b0ajt+RBDON6-b0LdD3KeQh3M+mk@Ribf)VN0-x;w(Z?<wXp7tPn72%I zSR=U=IWNp}@4TTCbWCJh7wxI+BC9rDZR>7UF>7sib3_RXC?F{dIBAy#8y@JG10~Q# z4M24^+>48gKHC9BeXM^+hBml-&mV}2h%N?|1<71&gjRqENpj7^?tCULW>pGIL_``8 zU7R4ukHWJ$h@uOP(Mnw(t-=XgC1NPmBE^7mB`t~2BFPW+s%#Q4s3B2=Qb~y4<aSId zecXhiq3H#R2dH2autg){5pz^HkZ|cKVl)hhWhoMB0iq-km^X@88-XZP+7on#7~rHh z6tzpzk_c?TiT6q}V`FUklM&%2h1H}66f-Shu~=r7&*z33%qJOt_jop+!zHGh78d75 zM(mS3IHgXeUAxwAgl>^AUl-lnylvOCDa$+#k)cJL2;D8k#LTF+dy-2fC?g{y+qP|^ zy-21koEjS>$#r(HcXvYpFc2rJTt;E@jqSp+GfTZ?w=L*=ku;!60dcBkQ9(GlVZuc{ zLP>xQsD*_`YEy(bpcE9HTmZe?;UxnY;74XS0RfSTiHX9{$iQGOGk`-oh;cdG6G?-F zt#-Q6!k=~Cf7_lNp2gM+OY=+13rj1+Po6&e{E4Y2zVq~%>6z)-`Gw^b>nNOT_m*iK zAM8(W(3R%(*HOvpr8!KMto`TCotvJX)(z5OCK1$FApK)NNQfvN4MDW+Akf!FtjHRr zBtHqCoq$AnCI=BiT%n76>5m^%w1db!(1AZ7rer4lp6g;4fKR;eT+VhyM6oBG{?q?% zc5%^eT%Vnt=UA|t_g6TGK)fUeq89$}PU@m78FJK%+H2Tz{Wuc)Fl+}59+qIvj&$Z& z{3iq^6Z^TzpAl#k1^JZ1KAa;u(M0SCNdP{5q2Lttu?W2A2wI8n;4&EA<t`Qqo|pip z7HH2UF#2}|(dN(vYT)jVML)E2;(@>SvD<&*z2mq1@csu5PEB>0W@>8cv4aonzvY&R z@f&ad(gl8v$6GA{Wf@1}%RiR{J3f5d?npnW?ZBrKa978Az-ONa#+KyoZW*Tj=xrbS zzTT!japK^?&+otGhc`{!_&<F4Fmhz2Bz%Dl<MHIH5Z+X1?FQ%^4Sn{y!5pH?lI%UQ zgZaUMT(i;EC+nYl;;E?<FTecKtFtrnm2&O%*G`s8Rp!T+r>35J?m6}w^=b|Gm^G2P zi2Vr)AW+NwaAC-<1f<zN+XX-l+$APgR(aMC80~U_qY&4=l`xyL-`o+xwuQ}w^NI`3 zL(c2M70WImJDp0UM%K1%m+g4x&L8-}zs_;}_16y%50|SI_CJ?jez_K6*@QTgtu_)+ z1Q{?`j7U!?cm1G>p77ak8W_?vM~edOt+-q8pt!pT{IMRmlg!StXxpJ+c4V?e$_&_B zRM`0Ca@kzI_XRMBvcHT>1PegC0DJa>3EdFX2WW$VG+qVN62t}+cfDpxM?*yb%?l94 zjg~HxDMFUwVgSTLu1R!&j<L{9(nN$oMSz%NA<!TeL;>U~NdzEJaYC9*^QlV=WNH8E z1oQx<2;o-|Nt39ah}r}|5i?;=kmc%$!({b>iYOGsPZLxf20>K~yTF{}7d$B<P|SiT z08UOPfr=CgfioI{sBpnCcEM*{5M<sUgor3KJXjzaD%VxJTCcM~Z@?TFB%Gv)j!c@w zH7bY`1|H0^yu8e0EjkpkY7M*Zk=dCMi0{-fW-T+2E)3agndBD2L+DOTyG0);2|ZK< z1rSF9A?h*YsFYfu<702#x>a;20&xnetWJMcD4acq)sHHfvi3lZckCJX?v}*W)6;2W z_KXS#Bn7EKgwQq6ykZI}uCs#(fWopw^{PFbl}-$Ly61Y*nqf_C<reb8L{tSygac8K zY%;5M!%fxZe-cgB^>oVKVKz8WAgtHgiwnzVPR~4X{5#J+^Wv+oyngn~EDQYH?9%kP z+0$pvEi5eK8NdG88!x<Y;_0WKJ#pftbLZ?!!Z!QcRecmOO$bqYbad2dy9(*k6KES0 zRwNqw@`=Ie6A1+7Xpu{ZU||{yh>#R93NinF{A-~*uIu$0tk9ffB#Nnn|NbfWVl?Dy zko5jh;gTcLA`K@-sgg-J-X8GT5hP#nMXNQ6LXl@*?A|`V;~m#^exfBMHbA^wE;F$J z2BcXgvd<H&cpvqY)s5AHf+w#FHr*xhO#EihjlL6YUFfu^XQMU%$pK1wE3DfNzOXA! zseys_{lteO-F@)4?{TldZXbU9p}RkN(~a-do$8aD#yNKHy7Bhg@BZ@9OYtGv1VR%M z{_lwge%S869d|d<2W7(jxA8l5$3{j+het;K=I7(R`pLUHufp;saPXu{jUZXIfK+?W zZ6E3~_1(^p!PKEe95>$h*M8!*U;5G!bA1I@=29Yl5A@FKHuNF{uT}y+I{}~V7!+a3 z0?J)CaGC6fb;J-7XI^5CXKvZNdCTJB;{5!=8*jYv^2@KBIC0|0k)yA?^2+Jcr(b^g zWt?94@q(K5Myl1Gn3!ONFlAb8oZcb#P7~Hg=5Qyl#jJ%ifMjZ=AafT)lFYGTOF$OP z$O*e3=V%$WZ{MyDG;Z3o38K?B%T|Z*tyjP8J@0wX_rLE4-h0!HZ++`q@qXD<s5rTZ zLZ;+X5lNs$4G^bN(|m(Kfu68Fa7_rIBEHz02AW1iY8utCZj!_ZK6~AWYKt^lq&Q-c zhCO9cc&L$1BqDw_pNJ^PAr2=9L?V|88+L$c0QyNYLe!!qj3l2OIirL?jD`Xd!jP5S zA%^w`h&eELssl+4zGx^!`4I?(T%cquR3t!@D3Bv*K_I;dBvVB~Zcm_qiV%TK>H(jf zfTV$tRH#xa9zq~Z)XWe974L^=V_j`_4=UY3QraR19%TV>f>4l1hzsHrUGN!^MhTu8 zfrudlUPMQTh(JlflN>y0-3UcuwaBU(nIQzO5?>_510@M%(GduD>;~1PIJruKC?#5! zQ|$EVGkCkX{7|Z$nVXwCH#3b&TefUjUS2Gfia5Z`Ig-$<H*3`@s{#z7pthzMI#e?0 zR`oB!p)iWzhk1N_9GR>K5a;LTPo6vpC;W&)0&?Jl4Sj|Rd5*l@MZ9_i35<<S*s_t! z+J$YahPBWR3I-rt2$HpcAvvm&AWonpMF`a*LbXv!5{W`Km-U#SBw5q1Mm4Rm=X#uX z=4L|j%~w|(I<+a}KvJbrot>SdBhH<hW<_6KUMUt!r%s)I{dHT~r>0)wAoAL4ub(`5 z>d4_^Pd@q7GtWHto$ow-`0&xkzkTG%C!Tu#xfkDf<0OV<T|x6owNxxEV|le51f79d zvk$}!6pw{T^rHiBT-O%>PC>~eJa+;<I{}(WF3rK_fCx#5bfPQQUGVo~*MN71OTc0V zN_s7$dfxG4-5+Q<_&dLREbv6jzWH!N%7KVRxX-x=ygTuYqZ7{`QR@g9LNqXO3HWb) z_<t}{6N3lH2q8`>CVb8LBt>@xR{=c^Xg+hppsbHY;Kg?1aJ(%$KXlt}pVz;BH36g& zHw5&=8lpCYo?4k28vzn1V&mrfyZqmj?(lgt;cT`BZoaKcp;T(>YhOKPr!#q|%@|{x z1D~6Kq@>gFPws-fKlX8Fye{~>9`Fn?_{?=6&c7$#vYtS7AM4gYtxCePZX8GB&-(BE zv3)-FX23V2v*8Kw+3N<2DXTHd8lmE>&*gG;XlR7VeqmvWHSxLUUO0O6*s)_zJp1f( z|MuVhTf6+bwDjuBFXIgBfu=KO&X~u=Ttpexc6)Bg-WkdSrH7a-;qI^IP~2{}YE(H| z?M9o`#=Q%J=CI7`w{K1+jZ&@b+KuS4Fk7igxmGS!QG0lFl)O@<yk*<A?|<L>{`%ke z8&|*M9SciKXk|a`+nY}8A+UTlrz5Orpd;T;#XTV_tsgW&p%5j$si5mw3pkynv(^sU z?lLz3t?xwCd?5Px_~_W!2qr})4D{^E3Zr02{3-$zml}#g#Lj?-w7MkN@WjfHLJ1VY zQVdo>%Vz*=(GaNp(NJ*g9-ico<e|->*~%52xa<-JqL`H{s7T;cBpNCr1o?vEk|VLA zyII0-<KUrocgmTA(G#i#P}W-F+M;Anh#3TByr5nn7q*^I*(74;EkdM~Mn4pC#iLx+ z5+Wd!Ra_Au9#g%eJV^-$5D_cLVn8PY5OWBDt0dkE$J+&;aX~=7v=vkxd)5F(c!&fB zRZ8fZ)z|(oC}K5rPF<s?t*nNSvLp(MsvrWfP$&!!52ptQ-ul+J;{D<SGvcx~cc)9G z((L>^-duhtXYW7m-1BUTwbSmpj=6~F%q)Y4Nm4SAkMRjr9Taz+);bz~IC05fMpVvS zF$O_@BI-NpB7}kj99Z~mA6>0lE1GsmIb5k_;i`6Cat6uNa+V}64zef(s0f)F5=2yK zs1XKA5s^NC2x_1tR;pC|+o2H{6-AN-&wfQ7v>)lnGJ*CGFS~!UkC?4(4#cGZlGR4| z(So&nW_sbJsn?!;=EWCZc=`0H>6PV5z1Gg8bG2$~Zg%O7*U#vIUb3do&A;^0D`(D} zTV5)&#FmN`oZji_>9c3g5uxMIin^Q*W&vp>pnxEKVi1o{xMVa0hypItAfiv44}o+2 zMJ^a98T#Fmj2OQQdgpaL9uZU|hF!4>qzC`#OP!mLF{b_apUeGke|Pi5#MtEI#Fj0S z9Gf<cvmSF0xm3r<$k5nNJVcFQprT7Zoq@H#7ku_A_I;$=zqdQQpR)0zAq22z@<HJp z*S?n!HKa^HxU`~?MvdwYF<Z%QIHf#1DGGbdK@>JKtP^d!0^Do7Jr(zWcYOG^=vQ#p z#J-0QtoMOcTGW|?FD0;okF5hy!<zYGFMqoA$L`#KuuBQwip2HbsjoeH)H>R$CH;Yt zYoM10{E>Z5j2GeHGA=!WWYq#%v7cm6#>aZY7jx%}opF~OPbYr(xjy;D@4oQLCE&9Y z@Y#+*kqc{=oAK<YaP1{nMVSCuoLTSKhTz$<8ov7KtIs_1+{u$Cr>0(h`K4FB{q1ib zI&|nS{^BnVA3l8i`0>*xPh|%N({0<DYUyP$v)w}-f4GIW%jT3U_xj8%ahB1gr3FSH zai_59>~4p~YqFPUYWap38bw4Gka4=SThP9R?Fg<fMW~pG5sZwCTz&P`Z-4vSH*K=l ztWXPOT^nsbfGF2SOA5qQk=bG+uv4fHqPZdN3cZP-3R=f%LYzj?q6=tL#(pC81*JAn z7TZgJ<*5a`VRKnK#!o~P>A)IC2tNaiERrVcQlR%XYYm_Wp|k{|$X)^B5dvEX1vhNE z_OhZV8Tf-J4PPRn2Z-(p8J#57VOS$D2p1ior|3xp&S)4w6%;1~B+1pbLt+Kx`b4j! zM1>@cWlttz5_B~d!7fzBL1D^pSlwvbeL$4hB)qr;g0+bUJ!ugmOx6fQB0y}esHqSl zLLdenga^Zlj&NYI97J@ytBBH#sly;4LLf#VV$ZA&G)2Y_8p?qQ!y$^bYE2-K>SQ9| zs(=_joJO!?2hL=Q_$2?DZD#H!hr7_|lSEiY2#e(slQLQLW`ikv>-KFhEG{j#Q<<@` z3H;)6t-iFhWFGQJVPs@DTVUZa(aihIDGV**D29?&pPNTGFXY;hq%UmhcV~*6XWZsm zwO%e&2nPqUn<uwib>&<2?c6LrWPT{0E9A0yvLsEX8b_U0v|D<B7N@Y<fI#D!u5z5` ztv1fQ-9^KYpw+=>G6W%6w1TNnN!XOsPz<@mb<(Ltu#pAOoRD1CeGc}XZTEj*fHuO6 zHHf1Xsu5Z(dSRn`O*f_Kahk&*)gg-!N?RMa4Q62?^dDY#erRZ9czBf1{pO7!TKd6z zX=!C{Zee<Q7E0ZIaA1JJpW{Fs6lZa_1;RA}&8=y;AvvsMXLmS~;~0t#tY(JmoDqtI zq!1P0cx?jdd4%e8NVrA%0N$SP*$H5FYR8839UwvyqKZUAK-Ta7<^$3FpFJXI=aE;H zFdRWu7vJ^K4@GzAQxE>jKcELyDQWelMqN)J`;vg67@Dl=G!9kE1>=r~55)c7sjokJ z)V2atN);FZ`!pVZ<ZIpA=N<d+{u#{VmI<vCim-H1ga~I5hq55bsyZ|_bOd<0=R@0G zXYXgy=+UbKGR$((y8MxJmCOU~tb=_(`_k!;KXPon@AO@Ni`IsWBRCyAeD)fMuuzsU z<79YB2YU}3`^vrh_PlxTL-Oh-psYLZzAJYB^PfEOxJJ0z%Lo*FelIwA>GY9Dzm~iP zoVW|xr<3UHt>duq)^#KwR@D0(EDITy^hY;7_=P9Fdf&dAF?D|)539BhJjVqfG3<BT z_33?yevj(5o}(X_n$&UV91VT;x?#(`eQ!6XSCF_}OumpGo||1rwKFr*b9x^5+}RoS z2YABQTysrnrS#$pC*FAd<f|{e@|S=4?I)gia%o`+V!c|oty$Y%EzPcIFg-A2w=ie( zIa{a)7-IH3RntB<=$`(qyH6Y1FYUJRuT-n{^SuTI>orrF>m}PQu;5ONPmT<a4G)bH z*}Qq{mMz;jwr<_Jyu8ekKE7#!(7m*y^^P6a{Pn-_gV$br?OWga*3FwY<D{`ovW*1u zWan!&0l{KKdP2GDhcA|Z&wkS&mxS}0kaiI^9M&F7_5zj20W>oZ32HO_(;-Fo=3sVZ z?2R%5DK<YNqeBxD6M;W~Bt&f$<S?rTkw(%pT{JfA0BZw^X;1}YY4-^r0?*{2q}m^a zh!ml1F+g-h;|P+YGL@9!0&J)1e)vb48=2O?kOe3RF%}AvOxO<y@v)8$P*5OL8csX_ zJ*HcfLRmD#dR|-tC>ELkv!_NTtQaIb312J$r~c|>7u2Iq)eFRBF|x#9#X3-NpGW{^ zX%%>&0A$KgAq29X*fs<N`j|s3*$ZNbhv<l&DC-oqI7I9aprNja+T}`F?*nJHzIGO3 zwhCoqKn}unHkC@Hm6a7H3%uMjXU`pb;yb5LpJ80&a)shb_3ZR4>&n$vzoX{NSZgx( z+fQp6f#^9pIx44;0Yd~wiwN>{-k|`cn1%@9A(!r;)a2yk<(FT+efxIZ1&t193j=MJ z5LrOQ0Rmwo37uRVZ*qyVR3Kp-jBT>Vm2sXspV`v@CIlL3;wKk53<h$kD=-rh2hgdD z2BIqU!Yn`}NiEcF{-pcqS4tvW20;!KjWi8uQJ8}Dj!4M?k}o##L%~q5yz(0MUs^1Z zlWGsZvbeBf_d?Gtl}cqOg~CuFKSJLYS1PkJbBz|(E6>i(>Sb5%S5N=8Lj+=2-T6!s z<<%nKRPeBY(hapJAeI!O1$#2A2Nzs03Azt6(=-|jh>%pjOVwCQ+ehyCT=XLFjt_mz zeJV7@9M^EyZC(EFW1suY=lu;4!K&1b<vqij1}bG}Q5}OvRnuOGKKp{O``+UT_c!&} z=YQph`#F^AI6GvJR_oip^xLuLsP`Ut_)c_yA%JA(adiI#0U+W_^nx>CS5I9!^qV{% zPq<1u@A}>Q_ngNG+<ouS1If>|u7NkLT^obc(6DJ8ekA@)upN8vI`FMSE5+rN($aEq zacSkq(c_1Y9OEEz^x;PzcE`PU?z<!UQmIRWeIJSaoM8U1pZrD8pkfp$nM7oCJ%0D+ zVnej+HeVZOZ)T6gg=6aYDEr_iAN-G)dS#`wyj<ise*B4}$BrL6{>1U)PagluS0DY# zS08!wE13GuH{mPB?bPG<#O<^9z@u;0ZP4nq5C-_{b%V)7zo!$jv;pD_W<nNaLS#~f zW?=l`S6_XdBzXDdm!Em&nNzR7@t1%3m%sBnzjOBN*}0in+)?-YzjtL}+caU1R;4p` z(`=<$Vlrpdc9M1XnfX+Ns8KE#<pTp2R&+oDD-Ih2B%lTq6XFymbVaITV-pNf>Lqu} zmMw38``dBR*$CZu<Biu}fBoCu_BQrK&~eoef;5-~1p3&eTQq@}n1IiI)1bXm^c=w; zn9(OL6hU*gh3wPl3n-x@*y<`b3A!F-;AFNzG3^{kD)-`nyKbN5WH7N2^zRFIAA6!Q zK=o7!h=_tV3_gt;A|%x|BJgOd3cr{Ex&j$A+JBT4T|}Cv4GKa6g<K>cO`BS&5rhy? z6;ZJyrE@p|R1wm|K*VXZx)qijX$XQ?<N(o$pg?F^;2{Y;=mumHA~1)&xWrPm^l|mr zZKCXh$%Q#4M@5hWWCztq7BdSJ2`4EYm{m$4fL|ahN+Br=s33qyE(N6kS*j7hEPkM} z0J<oFQ*qiw1U8z0dW>wDBJeAVBtnQ&BS{c655mc%b<8!)IK-X$zG)=I#-9$-I>-wL ztjP7Ejbefs*p#*hMVj^@94L%-yjr{<T2QOoSA^>g`-+Y+ceZ7ew89-Ak|ZL4S`_R? z7HUHw&e(&QIHrIfYiJTtagwcOJCh#BW%Jp=T&kVcmwVEw43Xufm1?CnHafm->-K!E zP$}DE68KR|MSIoo(n<;E3fnMcyKBexd#FY`)#;HH6j)hW-n?nD)o7MhiiGWEYbakx zwc5m4CPs#avjc-yUh$Sf4#zZKE|zEldtz#tpP$!L85(KOXJ%#=7Z)}7%@)puqb+J3 zA#6}+pcw@-X9icwmFc<p<x+WZr8vK|41+pOoNyr)mzCKNIuvRobp4!R5juJDB!h=6 z*sz%FNr(hWVPvupB|wK6P86#*YE}DE-0HS|+qP}Q*~HKT*(^T%Fd=l-NMv(@GV9RX zYOSnq`V~vdtg@VcOv*YvL2;#=&E;uYogv>&6P7DA8ag^QF*GtdJ~5ff3=~Th=+-0Y z%;wEo-HF8r$3l4i1x_#2LopOaAlhO#nj?y|g-!$_fT&1-nhCJ8H?=DZT%Y)}HOPSy zvVb)sG6{$XgD6T0qDY!3t`a|OqBe+X8+b^H9*9J+A)}o*S=d4Y#_3{kRdop={^i^E zM>c>v_y3Yz9-_FQQgF%?V%qi5=pCAm-StynUR+pUX+<=;5+Yi03R4-4;ediT4%46m zsiDROKmk%xY(bf5D*#%FKgdBzMz3-s@N$Ao2|=19BaUOw9rrzaborb66aL)P1Hbvj z8rA1mU(#s|Avq@D%lCC%LkG7Wc>I6A<0hw104EW3Nj*ZiTvP0WYEa($-k<rIU0x+X zE+bZh)+v|xJZqopa^wUFp2P{_N<^?a9%4B9XzY46!{L*^d*5#KmoU*(g%#NIvwwK> zP|{igs{-2Vus(y-Zeu|Eu?;JVsRJ)C0jrwIJy(E@A~TH}P7<zzDs=c{0_l`jNyX6z zws!0Bd*VN2#IYlay?bwU$NmFfc;K5$^9x50|G^zM-Dn*hHPl+@D2ejHI2?@NcKqpj z-T!PmF);$wV)b<(igJO;;p|ow5B>Xu2mDX&-|bgz1{sH^C()@?@<E5p;J3pq+|=&( zoKaZS?p?tgUQ5GY{^D<c-E;K8jvYJwv2*9ny&v4`j=R3_;DJNMg~ek>{_xISoLzmO zI%vI@70_)iT{Y!MwKJ(N-v2<%C*S+v@kf7lxBF(I4oszkHgRBD9ZGWS+4Hme_V~CR z`Wh`u+kpR2yeN8TmbFjM(5|xiQS9wZgrvrQPmmQ<;$SJDtI=n8cywW5iM<Nj!=<H_ zp`j5LV$(8{(SuP;L?qc@R7>U2q2X_R>s$Z%KmX^Kr(R;0!aOrEKF+8(@#2f+Vv*(z z7YZZxTREF*)~x@VyFU%K?YQnc!8@KiPjAG-10INh6e(FE2~d{oZim^jON>(6a<?d| zqADy>wl!G<6=8p{M5(HyBH9$G`q1t$Dfd*47OAR;wkWEjN*z*x9a2#4uql}U0Z1f4 zLU^D^5W}1AJP-X_>z{kwJh}Hi_uTjH13~?8k#FV7wN|dooqNc8&OL`)z|L4_bbPEc zI5e=yrgvv+v@<e3VOKUDX7mWk1&w=<Jz#9@GH*O`%+JsB=;3(|u^F3~m}F>NwXfg2 z(HS4x+}>JTUfSN>SzKH^b?Vf;_g(z1x4rcTfA9zY#^3lG9DIAenwmO);llXX<iz-t zeU#?VC=X!vZZGEVz`mN;-Ylj!n)#8UX=8nhF*c(61uzwwXVDoO8SM<~NZIS){++}2 z?CJ*#AwQJ-=m^F^l#(C)fpmD$Brko>aQ$a(b%Szfa76htyZoTxh}p`}GCSZjvu`KH z%-;LwcMpCBtFPdud1i8|Gd#j7vo{wV4D4=g^MtK+w@*UrYy9l*Y-_to6Juv8IAnU# z<A~Ue#_zBkvh(N9b1YDDC~4&pSF?2IkasgWBn8SWz${7CqbdR;k)=>;9c*;GDU-^{ z7eRosjbu@S^9uCH1-f}dYOY98+T(BlfW(kvTpTL3){!v*ZN7YrKCD)}^P^EHkc-lY zF6dV$QdBWh=AP8?P=tU`NpdXdN`qzIoti?~NGxkCsgkhLrc|pxXxR%UoC)l~%;zLf zZgx?qO1pNj4!JH^y4HK>d(2xt!+<~)r8hP}QzO=CwMgPn0#Bb3IG~&U=eU$SqmmNa zbN{}U#nshKE+8wb8;gre+*E9j;eYXq@!A^uM?>iWjv9_+;uASm3n-KE3QiVI6Apn6 z6L%)PSfmH#WWR5_U;ZTy8XYy_V?e2@&OV)STqNy%)gA!@G;v#^M_J-RiOfBTT`rcy zS2Ti<iFNDKf`A4`EI|>p%Tnfe*}xn-2Gv<iDD{pdy>D!+lM=Ewni(?JR-zF{K{Tu2 z$Hi<2h8fwB$@aGHUOJ9i%qBNH?!3X!JWxsyj4MeMVHPDeLK^Vdv*`<cG$E)}vJ8B# zTF)2flU-ZjAO2_mGJ6p?P)rxz|4Z4X=d&OB@!zTqq)(!Y2;Ku3=cNRJY*UcUPdAVJ z$cODEyWjbp-{lA4w}1P0KK<$6`R(8S^uPOezs=86Uwme9Y2^<;@u8*{GoSd-qrY1J z0@5nyr)sYt4LtnAAOFKAKmC)Bb$yI-WuGADM<4ykkACLQo>^J@+~<Dd6aSBo+|@52 z?Tasd_@9(p0k**Z{?Gp3|G4&n(C>QxM?UlP=YHcoExTW#;}T_FJqArThkP=R9k81e z>Qg`V?%LS<=8=cr^BaHkxo1B8{$u?4XdCbU`?c49KXXT)IDIhio8`y7+b5hIJJmax zXD0cO-~8YG?efE^`{yL5S{w{KS^xD1y?pN3&wSurNA&WpcYWZazx(X7Yiob}$N%Qv z{M(NnnUkFZO{C_#fP!<^<f_Qcnv#2~ZnE5Mzw(u@JoC&mPe1+i<;$0^UcGw7KKpa) z(xpp&zqXfoapwljZJN6|LG%Q|G4!jf?aztEW|&rK=t55j$k_A9LCKQ_N<Ez5i+}-O ztcL{R5SdVF<$>hPnKSp_fB!=dJw!4WE?giJ^07xRPYFlRV*?SQcLY*p3+F>`02^Ec zRh#;1et<MorBz|grwK*KqX{+1Mkrt#ihzKbdbg^-I}%7h0w^D*k;$ZrB?&WWV8YJf zV=YaBu*=KK2(z=Z_uO;O*|TSPe#3y7WbXA4$Q%NZEqi~bA*+H%P#k%z)yuB9c(Nxz z)3x03%o|{+q?MP+p_(#5l~yeXgaVX4A%=XzER<*fL7Fz)y8&{r7345wEM*a43sN{I zshqG^Q-oD(9UVCYpN6!2HMB-#)&q5_5)_;S7z^W4d{8S$gPG#16>Jz8N!yNWWDL0s zZqjv<&=+G5Wtin9V57v)U@5TIl+wyMpg0VW<(@1Y4{)2PQ(>7^_`y8<Z7~`Qlt3f- zcomAOk2n3wlak)3Qd0FD5niU(kCeLyYzqf=_7Ci9WA_jA3p#$bcK49?1_lvU);AVc zR#)wFl(yD3)^9B>Ub}Jq#?9r8&7Hxa&RA!PpTXg=&bYmlIy*b>-!m~aJw46!C5E8k zkf&rn2@c;Dp@Gw?P3y==N10P<MEoFdDl2nJA6NQhd<7vs)q|lyE_!Toxj@+qq4rzn zVM_lSVEZc$I>kj-H~Qterke*rXi{Rx$}{E}V^IERKn5svc|n8w_RiM9fMo?r4BR~B z&j9&B@cdb7LxUs3L!-kZ-1WxC_+bKwyRx=n-wwF5>%RuK5&0)hZr@y5TwPz+2VoNz zO9B%H4N0Svo{}m*-gN`y_H9R#Nhu*TLV4zz042u-Qr!=PkbU?@HCllxzB)AS-Oi`p zn{9y~e*FLbkw@z<99C)n!+&@92I0$}c=u2IR+5hk=_Scg@HPr#p#e6|PpW4;{GO5@ z{^7%)haYa)$z6WpLqGJs-)i0cI-h#)4}GG1>C`vDpIcgb=8K>Holk${10VRnPrd*B zAK>RFKVlp2r=D6~TwMM`Hr(%dq_Ja$7I0=J?ICuy=IGUrrl0z(4w}A&FE+gr`pA3! z&F7X^m!Ez{@B97q)6Xm~e~#4i%vlNLBs3hc=Hu9d=2cPY^42sDw}s+7_2KWE{ooU| z1KB^1{O~6}_tZ!3=zY3_13y*nf1mh2{mPTa9v36Z`BZHO?0@b5`jJk{il=_%`=&qm z#BFbaHPv7I$jR-2Kl$Ew*Z1U)yyp{t{5g9^_V0e?cYcjixZ<Oq`Q6|3U9azZfAKw! z^zpIQ30<%1q~_y+SFay`SzbSO%hs)#lH30J`sUi&20vR{J4;I|&p-dd(@#J9?6ZIV zg)cny!t<9$hSJv)>X~70XP0LSj#{LO%<}*xk$H;Xxe+DyJQvWNT6x0S+O{n#dY*N( zbCVZkE&#H<qUmQdPZX2WQ)kYdec-`2z4^P|^2j5PuoJ#`@#3jdrwD?jmNZ=xnS6BC zBj}L^A#Cc<B#^B$$42FG6iSvt26a-Die&91iwuQrM7|hA4pIt#Fif(7^JK=g+uwMR zVvY<B@q=K#JVM#KtkTmOu+imdj-$_R_U6r-tE;O-&3{2ar+(lPxZsXbGf9;>hh%-n zwBC3aTaq$R`q<Oplh$EfvO0mJ894*iZ&_qn2OA-GG%BTWlLS>+He$|Aq~_{C3T9TV z3M-Obg*0jcDIwLnbE~7tkqbS_QB92~u{w$XxnzA+OdMRaE-uBTxVyW%6&YOHVuK76 zcXumL+_kt5#oe`7p}14r-F@K9f0LV><nTD*g)n=swLe8yVJjhs$V&N$tr|i~abK-f zuB~`S5<7&>0(QQwiU+65#PiVX(oY?;hx7HD=}zHWV2`a1JeRLq3@$`aj=uQb6PN{H zE)D3Zk~q?`QI~9eU2QG5F{0*j8p&n~4wCUnppS#q{gfaIx9D8G=yR9qo84vBUO(h| z+*H}(U<d?#8?PAZw)4*X6WNtD#{b>L+|}RKmsdWadOy{!OOG|mIOXHvGu$uMq(pJ3 z)(?)*r&`0%XE)OL=({KYe5l)W>Yp*vK3mIP#zMM%I0WCgt;~5_U5Q-Zp06u?2?ye9 zC!sM9uM0r5ZGkj35n;l~Mv}%CRw%(vPw}N0@BfC$A@?_XX8v8W@Wy9h>zcjX9dI^O zS!29)a6Eqky{yYo)evGsw620T`wMl)-r6wISEY`WMiOxqWvP@YOTy+1iDB^2Y|QSN zN{Z!}Vb?~{Grr|l2<G{0+-^}kZec;Tk}19C)|0-D-**IDx8%KfH9;&UZ<YcfpWIV) z_~%v>>qqiK>G*Msaq|;W3)R(6?smTzzMbv_9!x(#7PKddv^{ZipXWXO4jW<($|5K& zLm`ih(5{>fMag*Eo}4W8C_XfPE!Pb)GQVs8i?_vz?A{1Ur5<6gR=>@j*DKFe+g;US zF>q)q-})TmJvWY$7##!f%Q%A_?NqYZ$YzJcz1xHGN*?49nKE!KK;mi;FYoNxd+T~{ z|7>*t8rvM`jU4##^-$s6yX_s)rOr@+Iw6}gN9G5<=QxabzoG0v+qhYi2UMCJ8d3V* z3$7<~7BNb^p;5kWa*Dk@a{9fZ7S&X|O$ELuCX@DSQw9w0Oc-1%oO*tv+{PCOfR_L< zN?#Z`>IeEKubmU^>xG!HwEna3R~}F`e9)HKclet;1XXQLiUD6%7IVG#i3R$APh+2r zeU9i)-Kl@)>cu!0jIn1R!}ITvUu_0ibShRVz;%KcNI_3o?(PRPRPpp{Yrzo+cOk^r zYin!b(7C(S{~h`e^S^iqxPZ=ix93}H3dh=XH2R?^DJ8!C8U8QwswP-j^r?xYx&Uj0 z>2iT>)0wJfoXip_i5Yo(1m$Nqw#4ZrTS`@~fpL~JAsbwx)}eFak`3nkI$;+L7dEdi zM*8~OhbF?p!bi)*ZM5_xfReDyh~LIe9;<ly{2IH7MPea*$Z_BqSq?#&axr~5l;Jg) z60kc+BjU#bsLn|@>QbxXywiYoQA4I1GXs`f8M?RsM%HC7FS4Pv!Qf4`Pk=9}mx=6d zG^E1|)(gy+6uSbUdQiO>NR9R-%6I46#On;Oa!SYdB>Igr@&Iu6*I;O72ZLobIK937 z6f+P=0>q3fKuJD7NfMP%QXZ+e!l3iJ=}VlvJ{d!sl}x|pz0Nf6#}o#v(>n2Qc>%W8 zPrrL!_tU$tUtNKa=RHCo1-XS1R)gyfPgot$&K~n4ED8#BWwew(tT7Q2D?n=xoyOq4 zy7xz@L>yWb=y!>6;J>jxI#|mXko@ql{E$d7cmtxDlLZxx<b4Zjg@?NeRzp2Wm+LUl znBQgU_8I;{tJSlly{&u^lTMlq$AkSzDxMpFFb+a*MP7mzHTHNm$QHf7er9Nq?~H8o z-5+oJd${zxGGtq0)aCbd0)!mj{5Jv?fv-cy$H(`7_uqmccS4fSt|SoVxGo(rJ4#l2 zNALrfzbW6ZJNB^kpg7#2I2|^u9y#VO!$LaoundXt2hzY#T6cpFz4Nr21C-B2C1sM3 zM6AIV7s`g7c*xrDtU(xO;JvK%gL28_qj0WHze2L&1V0xVb$YS^2JxCey5!3hG-&kH z{Ne=!$(f{S*YLbFki7caGh2^(9`PseGP9EtgIAip0`INz2Zz=Gxp`gg^QGv9(VLO0 zDD=?$o4t6QFMT+C-bNTSylf6IHA|lRuIhz*K@^P`?|*tU2{CJa@!x8QSMRy_Ecs-R zSDy#;-|*d7yt|20*m#O-TRx)ndEIG}eXD(odTaJt^nJfE1Ktf@__HVt(_pX=J<ipn zJ6?9@cuMD?gvR?fW*jpHm~MAbzD=kHB;~2Ujm5t&#lJts-wDpgi@j|nzczx^-<Cwz zA!se{1VN(ymCtpTk`xXvKUVj)CZ{$R&i{T8TsdRkEtpP(^ug|)EY`T<QLk@r7y6%% zUSHeRblraoy#KcGyf3(@mnI*MG$cy9W^*PR9e$?ZXs{s5ExG3Eg*}Cbs7sOmdQ&Ih z;c?n!xt6+Qt9d+7c!ZKE`cc*A7^Pf4)baJUp`%BTk4H>g)OCMt+4bS)B54630fCpu zHg_t8w~#6CDJ(lI7)s4pMOx0fs-%Rw)Yg$VC8nj<DjR&VIVW91gN-y-*Q4875`AU4 zg(;=>%#iW#`5`$)kdNTenX<E!^YpX~%_-Vf0I0t@iJFKCZZuhko>kw=MZ}(p*Wl&f zG3VtLj#p;sVK5_@yylyS=gR)xVP5X=hHq9O`y^i^WTOk5MgTAL<>TN^{R*bZM^9hV zRILx5LLe$Lgd7=q6(j9N2RU1r8M=dh@r0Gj4B~*zV8$X?oQrjobj7vWO+yx_DpnF> zV@Ngq_VC2vbW=WIrv?SL5Y0%TM}__-{#{2)LLy(5AyqlH8rpgKZDZYKpd{u;qL>gD zKr+RHgKX)=oOznDg(TN;@#KC6rb;K3P8R{3M4az5Fd&?$8iQs*ra?^#m_UWoZmg?o ztFJ$&#OV?iZQzm+5awCiD&&@s5at$MKUxxIQr1{9#4ML5)Nw!3%=HkyS+o|clx&}J z?pvx7S;K=-CUgGmpi@`(SshZ7F72yxSIy3f1jl*Gyob32?QK_{fajhM3z9$jdMr_5 zrI=*P<jJ2^tBC*?&RMcu`2#o8!{g$fAn5qtbjs4X-9>fvFQYCW2<Q8?0kk4=dlBe& zl$u^sUG3y<DKU#|g*Q?EAVwT#0VH?E$ubW%Pddl+)*Hji7$^s$_Ve80!VnWif@7rX zC+*we@R6iG7GET*cU_P#hwcwZzCJR(Sy_8qTYt}!jOvN+dR+#-c3eDjzD1OEnTZ3e z<TCk^*m!)(vev+L%2qjf>i&&;cRvX@Nb@W<ULHFR4lF5rH)<NYE=kL^QJ$jT2VT~N zUs~c9ImIQfpu6aU+bV1M-}JnTsHgrLAV4c2+^Fcb>s9WbAY+^O-JkfsT`zbF_6MAj zSACw7-8-LqGQjXae`t&HH5%~FDw0LE*5zGUA&!ZN<n{W-DAVvQx@Ji-%XN_`tg0b! z>L1R4=Y|vx5;DchNYB~xe!--~TinB4-HqQdbfRvEN-jZ+R_^)x-)k3T&ij&qCq7L# z*WV=Hrq%BZ!?VIfDuj0`CSNPJy#&br6@Ath1wQMazx2OfH*qrJ%v^D;-zC0FY(Ox@ zuFy7K%)5+t)%eu!d;@M7lXa$Y(BVguj{3Co{4PYx*8SJCq0I2x9p~#=MN8nL(|h)i zJ}r4J$><qfq*aA-L^R!l*?EB!o}eBdN{a(~-O=ywqN0{-ra<q#)XBiN8{lI<AygXj zw!Khgu;yLY_$}eo6y~x-4qguaOhLotGaR2!G4(Hp4LT}LhZQ@$CgAUIlqDu{fS_WF zdo#$+XEImZcM>|pJvaQZ#4dY(M-xKzgGZ4O1oq>XGs##v+mYetOsiCEB|fki(i*9- zR`}=BL3S>nnhcE$dV7p4u4ENB7wR}s@<QMTnAzWAyp>DlF(u-p%Y^bPI|NIx)$1F` zDpYAGKDBfq@_<xgZDwU*Twcr)3IO*I4&(=y*YjLwI2aa2Sd#}Aa9hn=JURiYND5Xe z8rAxdd&+#3RFs_|5g&u(+h(GU7uJ=9UxulwbR14xtV5O>;w|T><W?j!S}sE}W{BNN zS3$ZRRzid3l2A`|K`1>`T5+nYi@H0xwP;<Ds*sF0dW~wX0iwpJl9``Uj*OPkENm&- z-h|QypNHuSr=z+IrJg(IUK=z2LmqBsQPQZxVhBrUsN`nfa`~P2=sfe-ePQto{_28W znfyh=I2juP<;~D=w99J>q<sbLs^h`vFqvB@FUqSnC>6^Eqc@F8@})ZNj(N6yu!OK3 zrIhHgaWOd({#j_;={t~6Bh3E6-KE>xU8{($E`Ph;BkcnL!Pzo4ml&ZhZeg4xcZ%ao zC4Dg^-#N!xAtv$R<P6cVfAD<H@ebV;^5@fn-*w|HjtF_Se^poG+PK(6x!Bv=yMe3% zXC;0ol0ToGo*pi>V%SglEI0IEGaxW0gpzms6Ms=0cslwDy+y{U#S2(`+#|Y(pEx(^ ztiI|CQQ{jVz<<_4GYjnB#z8uDog+TU4b=a5PkNHQX82ieA%pMb-_1NJ)JA6abQFR* zm|;K?5C(^E8<td4vR4j(TS))hQD^7eh+s3E6P2R5-q{w34F!uCMk^Eu3Bb+wD(0~j z{3-cuAAD2u(Uh%ZYJ?-E6s0CbOizWbi3;e;qH7~5WUa#V;N+cZ4Uv&IuHph8*Ri1c zu=j4_fZ$2J<ZGzp<NK@n`^5X>r$5qzPNymkA*FQg=7ir_S~@}avCmSlMIiF_=h~vR z{McGl-oLJ>{<zc8I_@ag6fe;C`@_XM6P^_%rCs>P(*|#|fUSo-Xx(?fzH-mgZgRu{ zNh|=heP|6i^nUn$m?ozIaXfHrh}i42E)N<>`j`hnF&FZ)xW3+FG=7A<KNa;nk1joh z5Pznx<@q%p_Z=XPCC5MZ<p2?fD?V^3nwFXm_d|b))U(3--fUn-V8$I@57*-4y`b0o zw={{w9@nR9#<#zs@7d=-D}3({KA+(Z=XDG>ijf=6DY^kULGCO2yfPp8Y{}`V*s6Yc zHpwrCay>#*o{!=KxqVY#egHF`>)sjP2~6A8l$n^zp1-Sit_C0u_$%Mh<e_}&6&F`J z6T1(_>U^MlWwH$n`eQO9%-Pxd_ISOw@xJnYJ3s07l&mh$b!rO?SQ|_{>C8WSY?gi% z!#`I+M2~mdmKWZp%u!?21)SHe#F@dg+BsBhcy8q?tlLrc`ybC$94&vP2=HR4lX~k) zb@uN6ViXg%1Rq0VG6;#x7AmIaHSuh*dD59&dFy6hQ-blb>`hn5S!ys18UGlnFmk8+ zl45;-yjX4Idk2k+4|v*R{apR)*Dn=S)g#CH$f5(+?M>3fOgQ>PmgUA(WPV>BnK81j z;r=KBzwAc&*N2%SBC>ii<4eUT!M!)vQzKkAO!N)kCu&u*#aUg8PYpiFD`ZM)m5j!h zila~;hL8BsT$(s-_&-=zmiH{0yYQ_lSKb>@w|)U3bB;Snhvw>mdNYpv@7oT<(nU+$ z;Z-cH!cu5>&`J<)N848^l9~-B^~WnosJT?>@SdjV{8!=nxt0EH%2a6VG6ZKVRVoA% zTP*ozMdV+(?mN|n*pP~Z9iu7t+gN3_2z0g#JaMbKn`-IOb7B30F`N0W#^qjj(1Wi@ zR=`pP{(zNt>1COWCih{Pj3rp@NK@gfB_Nax<r8NL-!hwM6p)j>FqEyt@8+q1q><b+ zpFb?&D2t~(vb4+SYzkAbH=vMPk|9}C8OE_A?HOrlePji}ROyRw<*}*odUFdx${dp} zqODsoXog8)*v{|+T$C*F4doTAshyvjt#9@y332mAa4dSP3w%aqX4`GA|L!Ek+3C^u zhHvWXs;<Gc8`b3KaldLDXK>QdherEoP@;*YVLu8}m5whRef2aqf23L6TbFFY0)m&Q zoM5vuh*q09^Ce&LEyBB7z5)3M!Ns;SM0pw83r(GkB79z4oh`A5q?=Dq-xJj$4B%WP zW{A&XRxG_f&zjWCP@bMTBd<`LEJX+#7&hsg$UWt2;-Q{=4hKcTS_z@>_1)e!o=Yw4 zF2cuuiwmGSjl|x9f;v!z%F5lzVy5wX=jd(S<TT+GcH=3I+wpYbdRHiH2|C-4{gYJp zSbFY{3%FJJG!`kI*6_b<Q1l&nFgXExl=Dood7<IUCP|rO=wDn?MyyvFD5UE<kIR`I z-OC1U;9R7UbvSP6VJFV)gQOFs=MP($z8CJ%Gsf+b@pVDBN!T{m@fu7$$~!S(gtk)b z!VW_X)-Z}+E@Wyp@Z&5rcsW1->WG327Kn_)(1U(NkfyQ9wW?CYd#MmD5{0_8J$Q|E z_%<~DjWX}_nTOH$=B94l3knSMJhq(^CP?zV0NnzG49&xDs|W31){AdGhf$2T`y%O> zIb!ht-}`}Ovghq2@a_F%{ax*FZ-a*IL|sP79}F>Zrq^m3VT2>NZGb&5d|t1X7+!6L z-EYq+ezOwowm%$K{pg8YPkvTB$z6Y(TgA--wYO$x`(B-JVq#z#wK@g6=5=truu=@& zdp2{f`A)XE9<&zZbsXeIPzF4{KHV%iUYw64lCNy`1^FW!-2biiFI8Sqcw%35*-x7& zLhI1ynBFnJS15b?E6}0+(lC()c}fb!<*aLL9L!DAyj1LMN}*aZzg%Jc>;<!<HXI6z zg;mpiUG>@6+rrry$2^y&+PJH|uKWAm<t3Bx<MC60S~pi1=tX1hI4+GeK})A-ywA8C zfLSp9y%~c`99LTbLm6D_S-U~3{=lEPEVyMVVB*TZbpcs$<j!y^^|Z5db6gGZ50WQE zz@%4g*3He*|MF#%$+b6=!15G&9a#(!{AGLeTRps9ca|$sK-=Dq!w@~F@rRt`j^ywN zNeb?q&_OVV<WFiDm@1M0jY-J@Lo<rZ;!m0%_?A$J6-SiEQK}yY3sS;I_BCYxNpGo1 z*kFiLP0?Xkpri~!&x(vd!f`6M30vljc{V5g4IWQetSEgj4}y5)h!7#)dM$dF8n0B% zbiqNSmGmDixZQdbjP4X1LvEbgN_@B(ITZky$~^nf1_0mLNQVugg$GcRCdQ-DY1=?X z2y0Ua8AI)yQaJq+vC>9NIn8gtn8+j=tO*oDatXA$dokIW80fBl_e=bJvmph@>1*)T zNrrn2G_YD9x*qaCK03NxMZ%{meJxDfrMgI76=>u*%VAQKh8vz(_h-@V{<eL(0WLPL zbFcmW4@QlG;xBiB9v(gc0Thf3u3K}<d;Bk1l$ebRELS*C#o#BOy1*hjDks&g=MdPZ z+Q3re6swU4mU;!X4gAT}K-=utjV+9U_ww-dX3K8}%n$cpU_$M}Gm&mrvrk?+M6*v$ zin+!4|LBgFML#vC*S96QiJ0F;N)|8)HVY^W$uBPGjUWqoGAV`sE1h8o<oeTSl-KLL zl-I_8VA8N#Bvnzj84~_a^yTKR$$p!w<20ac6q+R*Tgg>alsY<8(i?l0aa^wX;W|;e zZ+skG*j!0U#NwKHG|x8(9iMA6MG=RbFFN{<4Q`n_r$(ve3x?<Orywvc(-9NMu>#>@ zn&7MZG}0WXM1@JVwlobnClZSrtMqC?ECgUl!5d5upwSo-Nw?t8mS3{!|CeQJ^=3h4 zobvO1;U|B^hqiqUAiYL{`eL2N3JZo0IDdbD=Q_=>rm=YZPqUwsHJkfb?X@trRfb2L zP%`n!f{2HX__>$6;W1>$8J65fYBqd<v|G5erc*~3b*-I=_E)wiF@Ehn2wlelYedOl zR#59#%fNMpGfkdOjiH^yAMts-_{r`EuRyPtLxsHaD5obp$=kp0?FR;jH!3b>C;%*- zJsPM<Pbuy&lNg|vUaH875zFz<usqTIJao8Ltu0&`eg>s#KqlVn?|>2v%=@j9oV1RV z)2K{UidzKL*K(3)IKQ(zPsnqFQO)}sC*{w83r1+j&xf*FqdoJU`(4UCZAky{2IL;- zJ#&sWhCQV(69;zRCW8f!ijaPWeNfZq&uiV}5SmT?Bq+83-Q(Ai=P-r^l>W*2m4MZ7 zrj+3u^^Y;D>Nz7%Txp>;B($QRxy`Xm*HFaq;n-+6@Ztg@?ogw`uZ|KrAp1=%r*zG5 z!vtPTh_7?hb$FivZ{!YZ$29lcOXpA}p&;O2P|*>@w@<Kn;Y>Z6+{N;!p6B0U$W20! z3d7?}V@E^a@f>k3?ZSdy=E^kYWTI$vbj#9T$TIKbil72VO})kH%I@+Hao33P^fU*1 z`&ELhfFpctK4FP()-y!;@)H9(>-ca_VGIB%&H}ZfE=%0!7-+miCR&MANg$L2zU5<l z?5no-^j;|jg`fU5%~Kck6VqJ1>&q4Pz84LA6B7^%<t7!2JN}VU#>*hKkBpHR9K__F zIz>y?4SIPh>&^$AWB+0ML98Vp;4G|-JMs&a$K1L0?-WXBKX++UAm6D-*azx#=Zb?L z-PQQHMj~FqG0Hb;tmo*e2U1>2*s=36%qgbENc9TKj3kZ{$6_I$#x+<U#Y%uSCgI`S z1fNI6LM-8Vb?4;}Mz!Q^v35}aRAFRVQCc};i1-L4VN<&%z{x@Qva1i)S`F(<rzQSe zvMr^Rr}C(LrPORk4(-qO!LPz(`tAjZ8YYBikiM?aKBK^|*Flw0M$w-4o-J*LSS!Pl zPPJH%rsV2sYFE8|6+em?K4!9?Z*Qyi+#jd<k)n0eje6Uy@Gajvsl<96T3aAb1h+cx ztfaDjURXS{jer&he)Q-(?HAU3tV1}JjtF2}ZgSbi&J8-ws{LuWhBcCh!C4SFI`KXC zv~mU+saZh4!MG#fZhq0hsHd*0PMAlCkDpr!uM%Hz$ORn7Oep=lJqQXi^tRf@9d*Ei zrxNlnfNjo_LO89Pi?DHO+B5sU*x%1g!Txs5+4Ge5Hk+LH{+b7s(kwds(>MFQEY>3B zM;07Jv+#{vq)@?Q?%5vhoG4kvrrR7PqnN-YG{xazCP}(ljK|UupM^76DLO6#768UZ zqF$pu{&X8xvCx?^6{+8&Jw>-`G2WI(>A`mGJc=Z9lOto^Uo**ceH4q@X&<S9^knNe z3e@Z*KNpih^9GM_Z=p=%!vTm>;N3`4hf7cj&+|7nH*V6ldAs8#Jo7GfhKo`EZpdrh zpsJd`H@XupJ}Jht03172BdHSFc3c_vmP60>SfM-Ab~GpSk8y=s_2>Yl(f0G%lmWYy zP}FxJ{LE{aClOwqN(|{zrEnOAFKpX5CK!lz_9LX0=p->nj~OTONL~8gz!HRz%Nis! z!e`XuZR_ps9+7h&2^pQd{eSIq7abSt7jL;O61P*bPz^x7&;EEO6b@_-VP!o{o^{-6 zil!}XmyKsjNDY#dURD-L!G&8Uv~Y~G-H2>PxWeP|HBlFOD=2%LPojO@RiBRGQ-X&l zL$eI}#^<X>y0fIB9;41pot=IEpsj*q60Z_*xEGD?{WH0L2(e;c5k9E|U8YEuK4DZ8 zGu78qnB|U%o=>Knj2PLfP{DeRknY`~cv!{4fzq4hpq9G@9X&~B^m}PJV5CSBfL-q_ zStKD}oA`~c3NLH-VtQ_Oi!@)!SSod3urG=1T!*=0s8JE?DJ&v-jEuMppqmQC3-EW5 z^u>gH{+RMa>6PWeFr`E`ej+MI@0-U6lU@p&ie&qAJfj3fw#`vQ2t+)~3w0{x%fO$0 zF+?p-BT(~-82MwbjdIAZQ8%}owpeuduE8&P*T*(4Wi$XSUI6ogz2oc@gMGdclp+tS zeQ6;5<pmep+7_f`J@336c0nqEfrf@z!_H1^nWebt<n6!1cm8JHndCfzDfahetgN<B zHrHxFPf$<O(cba=RIB=z<1c$V`-^%Y<@$br8&~f~S3esU9|sRJ9~-N=^)mbPIX+oK zq&7>n$1b}pQ5^CLTm4FeQzyp@J9`Hl&*V$xKhc7Y|5}^8T%D{;8hK}kNy$kp)lONj zxd+~&fv?-?J+Bt$MW@GYWjv0j<<h)gBOWEL0`Om9mUWB#{ax6W+_kr9FgVDp0MsSq z`U>+qNun%vIP4<0pZM8a{c#GUs`{V*C=w7e@tdP$ab)hfCZ*$&XxfrnB*lO=6q2%) zn!l)y?8mB0puz(FQdVgZaOIn7FwGz9{YWNf>x0i52~c`-)FDz!;vq?893F5K-%mg3 z?0Gz1|I_o{p}u1672(YyLuC;#rvcEj<@^1_u_l_R!x;Sh!GZOW7W&)Bn(qUY>}Aiq zPr$;5*nOzSk0aaNs$a!CCK2E*cxi|Z61DppUl@=B72rIq4*1Tp9?v1QVR3SBKylZz z><zyoW#IEQ<@;67!9rJK<LjC$u*>ZzxUSB5cX?TuA{7eU4~rJzndfj*)SR+2h-uqh zoH|@tHFoqgc$$cs`fk@PUI?VJlf*C`{h;vvYs$9P<o#xnej?g}fJJ{V#3Mctr#4U~ z_rB25eV3>}(RRC;eI7Uqk0tTA33=F%<mau*7{{z@eLO$EaIDKa*n$y<@W_`&QyG?= zsrQaduJbHJsw*u9|J@Uavjrm8Na-F0R}|3+O3EK8@uSayaZAuMJfw!AXW~P|Q*mHH z@;_p<;_`)poV3u@RaND0gIN448JpmENHFPym$!cDLt2;6IQN%B)^2d^n3n%(lJHB< z=;doxiqaojYK0ruYouy*Q*|lY&ZVLcV-0RO25HFiEl=U|;0w^yK)LnXU>d4&RGCn! zuX3pjJm`c+MOkP;^!0X9Bx7Qf8mw?d9+GGwNW7_0@HU9L@YZ56)bzzZh$L*Op@up$ zj`ddhxD~nXBs*HVBT{Kp^!U0=;Dl90D|BNfcztWQ=xv^4y>Ww-5QZ%ZX0MT8@IC(y zhxe}deK8s1tzoM7Ao)p5L!anoVYhAiM>|n-^EX_UlN8nTwwZWcc{e|Ho<y<kCYpw~ zz4M$eOd71>g?;I>KZSNX%@?io!?|~4x*HlMg19WR$8!36D1NX^F3U9trf~i<Gz6}G zF|f!REnVSw>#jeodenCrZ1g*8_=VZr?1_Yg?D6m*QUtAE8n8RUYE?i-udATj6Azc< zf(n~M9Bh4U&2z{vL_BFjzR1k84von99+jjoE%5O9fQo$Yj^`IQ=RfE9-~WMv!-d5_ zq~D#JzdylnW@nKgq)@@1jGCg%5L&Sb{KF*qy1jiSfBxq&S?B6c&+8VQ@cX~OhZ7~2 zYax5??-oCT-<&nf2-0To`O3*+PK;3E?E}0kyk#wOaiom0ttVRJ4EP0`sM7`VI_W`S zLKtWuC(@A?_K;x#tu7kt)t9qr{4k7=QX^MPEty{jWc($7K)G?Bic*O_MlyQEG?*k; zRTIpQO1ec>N!-OgpJwi3@OJ7^W4Z4MB^AySj{7b}1Gk~l3>|Q9MbBG{W$t4SWUI2m z2O&OSH*@2yhR0FB;(dn`(h_(ZwY$zdZ{2XP&EBVAE#R)qCsLKbKVCc6i>PZV@e#am z=S+-xEa08`sB|oE99p!e^WOXJv)}N(D5;X1S`g{AyJt@6z5jj(B+!O%zO737{ia#e z!mS9vA8k*Em{yi*f}dX__rE%&)1{L6j0`<j#>m3BtNut@m#)gy@nQ8P_tiUurzs!& znIy_j$Z-x%IXOAeX|s4Aet)FoG-`L-8H!zA{_1eJ@ebK|-zCibnUytz`#YK)&GId1 zavu?Knoa3NTQI_EfOh27cEW2KOzOGTXFjsP2W8;QdQ!hBjAJ^a8{I7+VKIuKO^lCY z!_;JEE<Y_J3j7rneRDVt7VnZMr+_8qMfi<>40o8Ql{OQ(#sKoP&z&@+tj`u)Z6U9L z4ID5L3YW@#?t)PlwaSpngYrSggf-!L+vD^@8CN62&b2_1(^a$=TU*=JBW3W+bDwOV z=DtE0!_ih*;Q2TDHEL`482keI1luliJ}of9EzbxRks=lk{Ahu6xq+50Fo^1FNT-x> zk_EA1h29e&S+;VY&r*--&pIvr96}QFz^9!F=lF$=fa>%Ts#rSV(f%8#bSqS_f(1U9 zfpG44Ux`W`fHs#y1koB((T4ut9L(m(lRtTqc<bJ~$5K&B=0<pN4Ripy;o7Qk*w9dU zP_Bc5!g1+6c&uno=~?a8eXDECjfCnE*fN*CFyct-N)dp~u-X{%l>;(_p1*O9%|>9& zVv@a6twbor#yR18-rt|{Kz}5-|Mnm>M%M(A1Osb^Z<|e{za}zbvr3a}hNvOjJ{Cf= z42-|lO`eF>k_$_Ou4&!B$}*htrX6{ErF3y;&#*VQo@OoUo}b#k{HcF*N!Qoc-%mQQ zgMybX5lbs8#=wm)1_lbf!JATK0$p~+M{fT9vkK0&b=?vI0)2bB>KC9WV@eBYg8O67 zyYzc>Vg-&SXueMU(5FB_$MsH^y|K!gZlAlc`RQp?ts!yaGK(m;Z%tGDC^XW^c-r{S za1N+TK?FhcUtV<J3Q+0-LTCkgk2VJU<jf@wpMW8wABhg;e_Gn(F<X9AfYzA7<4hIt z%y~`kmW2J3-%Gr8(v%vhWSHB3$5b*k;JI>$)u~ZjA>g#KWx=!<2`FIVtYQ-8;DKR= z^7N`<>|-JXUC5czE{F2ZR_uChFT@qb|Nrnd52Km^=m|MK!2S1`;zE6(`_YX0>l|=W zP!D>D%L2CR(t9pfC-2u0B%g!hUr*HEfNz!CMqTQ!ly41zcXs^1is<f&Rol&=Q)WgP zTGCOG3EhvTRK+;!xf)H?H9*Dzc{nCJU}ybpulj3|AM&X-q&hwC_3T@RU>_i4vjPN` zd>h?(<cw~S<eh&%kh~$II{I0Bthc|bT93cR&!>qf`^JxpqR9}E#<5~qJRu>5&zsMQ zYNNGC)m1G3j(Wbry?>mcL?{6L8I1LDYaGC!BqpCkck|jCoA*6$3wnjB+@Ah=O0>7O z4#E$ut^M+!hTccK?<=exVsKNmleu%@tzVamqGI8KKhPFXzWie3Z2>mF99UrTj+*B< zH+Se%jrLy>4Vm|k%v?v&TdulzHaLDHrt7kQ`3Kqj^3Bf1#>d4kiV9?#EG)z&CZb|( z;FP=P)xDKiHM@27dx3y_C7#|gbNRHmtx0M8vKS+eR1_geR+|cbq!PE7*-F%y2Wz9Z zw8Dp!R+s%Vf<W*3dC}#sCfNNpD+dS6Oa;!)x`)Mpvx&*UG*0edQG9`g%5R7SCELXU zy`cw_Ia`!}>O&4wb^%E3s$fUEAUP#{RUL8S&>Zo3A){%g6dE~xPHv>I$QrPID3>0n zoD`*LEGeVF4xcHxXQ1_(0kv0bDoTpEYulAdHmziQys(27m0E#MH<J=1t(zwGhJbuK zMh$l1i$DjeGrLHA1a=;NPpUPQ;x9F-(g_Bm|H7Iqa~hQQ!SNZnyH(cBGMw_pRjgr{ zfk9}`N3~dQN->=jR`?<9AX^bof-}R52$t#6mEkbg&e(%b=Se>z%mj(WKp)OSPL0)4 zV@%uvqR6odJUXci2y_OBMPc>8+GS+)S~|nr+(xVg(Jrow^wh0_t>EQ~qocO3z9+5` zDPM>T9^>LyTM&3d=I7lFmrrn_^Z=`kE6@EI7E+#Uif9*(0+zIb-HmS1<~&d`<plaN z9m~wDsA8{H-T$Le`<btUm<-*)q1w@*9_Qb1I?C$my>+i(wPBaf-gA@f;+JwcN(y2! za$?dm^huS;oSuWz?`VW0dEx>)7L*<J?PK}(NSOQk1R^;&E~SLm-`Mc*v~6u!Z`H!b zQN*>(2IjRKO&CyS`|T6rTAA26I9xPZN9r9HH};+*E-s+XTvyoHq}fLJhz#(gPtTw! zSe6Mc3BI0VFJ{#M6HBms>`F^F{}e*~<tO?Ke5S(alI&kZpo~0Nk1<`ZiLWhTcoMY% zPW1IWDP2lpp^`S1Mow2|8bEA0J%>`1kDe{N!!n6d&a#8C{9FzaOLmfBN*2otBJoLV z+4U)*w=f>MV$opT%uZ($E>$!M4M)L#h~`Sec76`4O^HfKw{QG?vA2WY_d|w>x=TaC z{mbNkG>Wjb?X$d9l7%tctPM3;rCxbcFvwOzdBGGK@TK;9k1+QUBKg==<A0|N9P5_9 zukoJ*zEo2}UL>z`ANXGR!Tt=|Z?S(Bs`Ek=nbGME{Rp)_Y`^F?45M~LKe}mRC|ko> z%i%C)$;3;kj26~HzpBS0zr(Oz&s}zOdM^9%0xw_QZ$9@t?{N}pL$CsF71ooxgFB;d z5f!nYP^`niu_HtY$?h)^CKy=m;*Ld1nDeb494=&Q=Z-ZoK-WsC=iJBGu5)gic8G2p zzz^XDxAsn?dwnJW0RgVO{w;{}O79->K3h*)+rOiscIcKjsMbDP@)BOMclPhX-!w^T zD@2<W_O2$~7p~?$(|1hM_b+T)NP7C_O+^Ei{gRDI6m2FU;qh-n+qjlt-wN%Dnj4yW zS_b$`xOkv-JDVM4>@W3si^dJed90s}jf{ZPlm<Ae&{#xVgg)!S-LGtRVPFuwus;2t zI?M`z737()TxumIqFcvLS1=4yIr&j&$RWrA&oi%18sS)W;&d<Y9r!V^%Rn<)DCG|? z*6^>>+tqWJV%&>mb-77>+!E87F_I$F%Vo1Ik&16w&X*4WdQ9dN@LyiMBJMnR{i<A- z1t+4RMCpM7xlBlIN4{-tBxke6EoOyJi3&>6!UE06p*FH8e%V&m#VOw(>E=pE{|!zE zwj0qVNyUXpPmq=l<C|s)UM`E#LqyK;l3tQ)G7ho3P6|Q^0Sk-XJ!$gaM)h*J7rGcF zl)@+%Lf^$O3IxDUJ4Bi^C;5!($ja)BUB%%TRQW$f9IVp%CuSc^$D~Lc#l{naX5^CL zz^Pz%i3|KpEeMS-*D99@Cn4abW*h`FgAxOx?E*ydfe7l&2&8+r^}5^Et^^OHGPo;u zYur(oqIo=#U0oAOu;AZX(iugI&_iw61)5*)J%taGlkXXswC|s;@yOrPHkX%|zkf%J zVJvOij&c6lw<_svI(}gzU`C+ker6GVW;uvUWvk!zlh<uwZf*`;5ZA61yC9KJ;fI*j zUVWUgvEkoKePD|ukwoAd9NHKb?R&#dk5ldZmX@BYexS?UV&(9HN3VaOte#ywl>IJf z={mEA1|HIW;)wiHYm@ihDJjGy=^3SZeLZvByZQFGL`OLG_wey}<@$bs!!t8+3v<ze z0<qR~<Ihm`@_yX!MrfE9tDAzt^Bn85k%56M6<$v)xt-(LQyxLt<VQMI@|rJLh;nMf zG@&d;UcRVRB3f?JN<CI{=^Y-y5NE;OW8E%oK+yA@9uz68x9E&2x?}zt(n6_E5GGCP z5~CG8Zh+1w0|;ZHPauM;GR3Zn9iadb+!uT%OU>WOW-Y3~`P6~2OLTsVtH^m>DpONh zXlIZY1Lb#6^;?`<i&A%J3Yh8&PAMl`#sAvRrb&snVvR`2b8fd1PNn?nI7>`!HVE7$ z0#VXGsG)7;D@m^m&}m25)c-x*ct4sS@?UoL+WLXj4H=fSz6x!n{8%fIG^bizEJkYz zNTaFJPtZ3>87xD%_2Drs365b;2n|*MwD<-a12mRo;`8swb_J+Zjhk^eE`v9|iUwB% zyq-y3F-K=I(iY=`7ZRIm(}xTI8AcPlCZW#U1Bmv{D~7L{TU_=UsV~vsO-s}pXPFus zQhU-(f#J~~)((eaOHOzP)Y2ComfZP%hXoPF(0CQ!i!Q<mPya>FI>9&5z=uHI72?hH zxN-6H1MF=2cNb)bYq!4hnS-i!3|&#v*yv0;o)QF_!#$3nzvASu*+$Lo&70nqOQ!Ih zO-+4RRmpgGURMYpPP_AES44GQv9Mpi*#5P<?>yg~*afi%cXh?aVu1eQd`C=4gr_oR zmSJe!Ellyx5qQbh;4wx;d^R?d)+G+v=AE3Koqgo_z^4;&Z_jobk_n3tK8loKy-U>f zG~p<}pyR~%`SZeEj`}zNhb;4}*&BqaRO42r5pNX+*n05u!Tw8Eh=UM?&(9<zcpezy zKk}p0Y#bbgw;2LQjbM;G(?>c$zV38Ct|$064Yrk8D69)1*lb6M+)@#6h@%tUyY@YX z5T`TZmj4sjXR|o|F(oK{o7ZMcO29O)QCDIAh$)VZ-lT>lKans2M%6}_hsm8*depf< z&Qb^@GkViCtT^&L=w}2t#D@+OZs)hMLZ-PKABgX8z!(R?huPfBS(B+(Ysjj2*Q+9n zm3|~c!>YJg4i8Rs1oWG0J|`um9@(B~L^_`^Dl}Y6S9nNqd^wwrRU$*x;(LBZy-u>z zh3rGZ^1*HnO+sf}I=TkbgqGIs8TNIo!A6U?pG$P5?r(3vbC|3sx!q)&1TSwxTbp!X z0L6-J+s(}lTABI;$K}QA+%7sHVfCkb<<ZcBvz&>{BjFc|^*-$9e>spY2sx<Q!H&nm zoD!$5VKU9d!Nb(jBg$9yn;pp2{AFmu*0%%MYRSpLp$gdL;&1M154A-KE#<elyINa6 zEgWfoyRyjk;i?@LaJTnIBsH)L9WdM{MzI}NXq?1mU}Ve`Z0?4JG;Nupc2yV0xLMeT zqJjjYIXjl;bzjInRfj`i*v&#_W%kb|m_VrV8(_I}do-&e%CY9oRfMJnYiKo(jz=Km znBj#GWADRSzOAcZjfY^K3P(tc@5FaV7z}Gxia^8zRW%<-2l?71L3bf@c$HDRFfurL z9C{R}oMnECX_3^`!h`>EYzKwUW!zV%!dR!UPWRj@m-LL88;QBZF;s{LMHvd^L>1v4 z>dO>hK|>uRIlOtK6oPM|&6l?}EMv`nDLrI2TK5G163OVle2W7YTqHLK{J`Ue=YtG7 zHjaj(jk_pk<(~=7(D`cUQZd@MbgOic5+CeAFRihL+H{kNzeUiuzAI(>KXqnHh5K2_ z`%y-AFSXUXs2g6Tf3*QAro|-m6}YOX+VkI2PEZMT<rVN2rSzwZP?dvWP1OBv;lxP_ z+zk$K+#u*Kq=_V*707L9V)wR_>sva3#}&qz<)}LL`TqXR3AtE1GT=-d1M=@xv-|y5 z#f|7ZQ%+3Uzbn0=InSPSvS9b;4H#u!p0%&~##wpUi~kHgy>G>K4WW!=9j#SWy<l!u zuGdBU`{C}cP<^0cs(q0Ef$!AOlA!4M=?WSu+mhmBK&Ej)=G+HRr<lwV@8}^@+-+RA z(98Y3k-@<)i<ei8muAHmv|rBtuDj0!lPqG)b+fDM>qf@LKQoBT|9C=<=jZR-w;dcD zIoF}%-g){B!FIU2=0_J5*7oj*cmG!fPm)%8qXKY=0jj3GY*CQ>19stxhd&X8uvmBg z54h5FrKtuo%NY5wxIpzLf!-xvGW(#4fCtaOhrz+Q`O43q_4G36bFq+-9ta5?XZV-R zU=aF<GUxzCN>g}ItmtWh&u;h4X`&{Vr^GMtDBJqKr?(E6!c{6~;B;NhmlH}PqgT+# zNl@XWL55}ag<p+RK2YRqE>6=0Csp))57-+yO+YQlmAF~Apv)3OvFe-&!!GH(uBYTP z&kDP$Qvyg8>3v#&w<5o%PDu<!FewJx>`UtoRX*~-A7v7Z8Pa~;LHr~|yCEinDL^4X zjj_oQ3P%q7x=-(eF!5upNk4;tkA+*?34t#O&5bw-&C;bH#h12TJr#_WK#?#i=j5;A z@h=PmvR{+{v*cBqLZo^<c9+uLs}xtuqDkPhbhQ&HWnDL;IDz|nBww}2w8vGD^x4wf z`+V)Gt!+7z*a80D6uq*N6`C?{VA;^oE+Ar)H!GEq{U3JjOpbxY^7ee#{ATlg{qSfj zf|8iBMbfG-z||G)kL_YLUZ1boynW3tHuHE45<fu!fvfFuu!=P%`l(&L#Er5-RyDNH zDs$Odpm(je)xkw1f6&s^cesb$|8gvq6$&q0&&=Sm=Iv$(mKq(1P80nan)n(|0k4sK zcYI>#V%(npl}+=4I?SI`q=)Zd2HH1j7%xA}CwZQ)2k?FH7JO?`iC|+Jryt#7Fd1H_ zR-5stX)!d>Pk?831|5qfRzq1$PHXEhGT9=Q@-Z=GrV-j*x`T7(Lc3^M5c3L6bR=^F z_BD!djHD6-#~)9l*az*nOU+Tid#@zUF{fF`9<tJQmX1aIh@vt}qF}*J33!q>n_&%* zLxbf)DQ|z+bok@^%^#3JTn=_GMDbo0khC{(^lq(D>;h%U?;?VE-ss%043X}%c89iR zew$N1j&Qy=3}>%9ua50OO+7Ud&y{&L0pE+;2=!#rbk!uV3v5=!{=jewhbI67K@1$m zovq#7-ObIV$O7b;X?s?GTs6r!gXLkTmGgCy7X;`@^fYg?&ryuewvFBoi+Zjnp}x7{ zWu%_V!QuD$8ps$UX?Ie}1XhXroX$dB53ha5Yx10`0ogL|msr8D^<4#RoO^JrgNog> zIrmSi0gBVKQ`f&pjQseGyBkAOCi++ad3rg|6rIswqNSIY_f^Vnx1;Wti=MoQs8H&_ z?A=Y2hydGf*$Ut5xZm6L1JO7paSvM{wsxqMBM5U6{lli`DSSBDPj$>BQJ)=Jkf8lU z7S<awhGz<`e1%6bF<af;HWzkK=5yuvc?D(ilWb^<!<ygOacXE6q$G8($M5RI741g3 zh2TJ)UBhE&SO|&agL9)9s)g|9i%Tur5x$D7^!{PDRwSzs!(>`>#ev%j7~hg&RGHZL zcqsnQZ3Ny{<{|e57IaA{T>t#1GP|}07w>IuZl2CzwB1?<Ynf)^?*1{`pv563t~3_L z*@+H6bkAEUlc_$b?-XrP;smn6e8fH#94}tQg&M*@Po1fSR1Akw{Ha|;Y{q1=cf1Yt z6siQ^cm$+j>q_%4YCpdc>7-&ETF@+`l&JQ6?`X1s5R`=ZZL+M67$lBH;hyr>*<ng2 zt}aOm{ZvAsF4b|S(bu6LA)@|I2~6S`_K6la>OM6~GLT42j|0-k--))++{V?wV6#G; z=hDbUJWN&cmnhO#P{jdSoR@&70M)X|3>btiMJe)dCZS|Mlu&0BW>M{fGLd^8pEp_% z4k1`prlxB>&ao%&3k!c&R>ls?yL2;LEo^MI=a{P%?lJ5tEB}11Hf#XKoS&ayOd>F_ z6y0vD#;T~OID5<V)b-8Vg`yZvHxka<W*gRCZn=~K5k6pOm=mu_{`^LzL^`q=Y>coE zC&F$012<WtF>d7nv(|cJOUC<bh5x+h7I8@t=F<%hmh-SCNIF^Z4tz4TtBROqlDbu5 zLq1dM41EuQtaaqcatO2VnE%}^k(xNbwGQ7hR81n4h)jHc9b?1TRFsI4MYU;~`7AVo zt07~hlPWbT*4j=NpFr!W(GO?Nqm)YERA7fj3hmo2Oz|ZbQPT=6_x<$e4=o<6)gOhq zhy?Y|YA3Dw*QVrCbmiL|bNULJAj1@|y%T`XaZ15BBKq-3)g(qO0-#Ee2H#@!wK2GB zZ>yWeJ;nNXM1nID&bE9;8`WJol|~RVU7o`C;3e?1OY%95(mSK-asZ1kyOEFsNYVP* zzjqLL0kyMNF#7iJ%q*Y{(<=QN>CO#Y6|3Zzr-N;MEB~OwjmOK&yAoDQC$wPr$}Kh7 zP(+5d?S;zsq1=y7mW>M`rEx3>oW+%D0jmmy=id*zE+EJoceL?bP)p7X*F5Kv&il%@ zfaD5?u3W1DOLG2H_gCI35~~KsS=&yOyLz18eNqBCC8lrFT-G*8Nw~z)E-CUBJ7zA$ zcD`}_yr_@@Pv**pPEe<ZRVBM1+;d++=+UUAKrfc$>*do8G?#bv;VRDkv}x>0iS-|8 zpzi>oZTxTyJdpN~?*m9Yii-7mYs_s4X6Mg9l2PO<G5Tdar#^Un=9j_PWxnJjI+lZ@ z!x5pl+`yMSR2#}s@4I7Y?wYlXI?wH&{X{CS*~Ev!^elF3qlf&Az^p=jM_jEBx+ha| zBy=%SW%Z3L>M5!TlY@hUw~hY%rDkU6w8%=Opb>Oa7nhZ|5XYc9!Cn;{^?0bhTZOj4 zw5O<?qH{F3I?)?NhXI;@!8C;s_<TESb^f!@m-FYMkS;@0Pd$KNs%UG^GK)kCCQFK^ zO2j2AL?nh<iM>4iP}vz@nDCIhCd4qq@Xr8maTKx7l!$zCx>Pgufy~H<N*=-wDOj5s ztGkr?RH||ga)E9RGM;)YAL%&hQ9$Ei3wSb`Hl5hWirx0ZXrKhFg!%~yEYgyErRWS4 zIa<8mx0j>i+Pp$>-XC>J23sZaH0=jPoZ#c#h@w*Hg3w0*^Kj#!7-E5x8ATYo1ll?c ztwPksH~It1!>fsZsF-95qdf4$2r~*w2)?vqheBwh4iup;qN~0JtEA8(E8iDUtDzx< zGKO#R@@EhEtD@Pqm837o9nh6L<^BoroS#puwyQ}QYV7HoaX3b>bQG^`sW%HOt+X2r zqZmzKB{x_WlckIzMPK@;3P6vnsax7x@AeQfk`)qflPeVSUkTtIHVQ`DJ3eNSwn}xB ziwjCI$i5$DY-LUHw9PNjwX9G18K~(S+#VTMXeX!I7A^JHe?ZEIO0c0aizo)%XKxqu z5h!CtX9Yp9+Wl^~tRu&YF_Upx&dfLZ3)f5t(L0O`%Oi69R}aC<Dg#aB${4i1Z$`<$ zg`;sob_u`n=u>VdAgzUe&MJCVz)1}^3qg17yZ#ANRLl)-QW>o{Hc-`JhJJ*K0ib#Z zg!w__hyyquWFBjNvWEBlQ%Zt{z0p3xhiLi}%`l6eRXmj{+lSf3Jk{G)?Sto{)%kow zREkT1J+uZhUUBdSN#nPQ#-0Wo+@g)t|2mF}%n901>ljm3c_Vgg>lAs0<9-TSBY>mU z*TLc|=LuQkT6~H}&Vo>?aopBA0b`sp*cTz6qbngvZ<i~2#z}mbdmPTO8Yd1?@TAii z`2+i(GnE$!tf<KVymCu*p0MjN6o-3Q_r3W2LfQKM_M#5$wk!HQJ`PRY@~W#Wky~H? zM@*sgA{d@8Y|4xq`#6})2G7@vnW1%qTcpQ&?)x^cu;yxS(a?;AB!6T#LXl?Ghz_9_ zp|Gn4_PkX&`lIbY8w7*xca=H2-1f(bEjNt$?=bLHg9y8$D9QKgU6OyEFk9o!px`<s z<NDk-Oj*h=(`2|dQ8M=$JK}tE_+cF$K!xOqRhBsTF^y46ppguX;?gT<_v$N_*FBEe zeYvG}6n%+hZZO`&%w2H)?cC`Xzqg8HZ?r~#3@tYp5||Pm7#?j_fK(~^4ij-zmYfia zJ}pI&+<nD%xo7sQLl@Y_o-U8GA7D-1VQ$=9@Jf$wLE0Fe>6yCkI`xhKRPA?r)0aeY zAIZ`Z@UmvN0WgaPO?>1MK`FV@#lV<S;0KsasDVX~8*%h$19fGA3O>sR77p?9V+qo_ zSayf#VOB}R-ur-FAthD0N(FvlLO+@g%T-d+5%PIo9oZl;ZWMnh&+i?eqXDC;gtB6W zf+ljGrx1G~i0wiv=F7*84aJ5Fqb21I1hJ*1TF(7Fmd?6vrOKKbs0rp*j1F#sUc*%0 z1X=CBCR;qKC(~WyW{l>z`qxy7;0nuUYX1hZs>4Y6Bp>D=6gqK{l`Y%~EPMGK4iDXe z(WGD7Uxor~+(ho>X(yT3(YLOW>lEj2g*z|?zv!IBwxeCbrMNucYbg{UFf*4FfE3qV z6tDOdDPNWpl6N<^>#(|}q(;8?vUzvxF~nx+L{06E<*ROxde4t$gDSRyz=%A`1P*v{ zu_FwZ0Y1U9JZH(jJY8#;o-tgqe+u}M>VI<Ax^cezp|ULhMK}ICnYmH$JZs;(I6jB~ z0#N@7e5WCM+5LMqeT#ydd6411N3%hJ<KnWj&f)*vw~K0?w!W%~$MHI(7%Ww^7cp)D zSPVS3v0=Azi{}|8@bm~y)zYvxw*QxA)XhHJ1@SvQzEZ?Qife&Amrj)ea&2)d!(o(! zpd1y{p7!7Ij7S&VhXmZ9i8&=TSRc8Gv==9M)VB19@(cIT@`(=L-NoL;V$AevnZ!h6 z{v0MEB5AB~-2FmhUO|OI6^bpz6VKcF;;{PQJFkcnb4>2dkTnT2DJc5|3$u=USF*iW zV1_s+GdJ^RZdP^<Ir+)b1{SoVMO{^0MJ+CF`3BwEi31-?C+ceouH4AXfg)DhPgx)d z4t)+%aV}dsb)03Y-AC=c%OLR&+mX57gqbUjAu}jqr`!yHT$xN4{dq*$p)aUZgTYdI zW(dWvjFP@G8}MQh>vvn?$MD6Y**gEj(OEw<`L<D9dUQ+YXb=!a3v44ddV~l_qolNy zNT)PIx<?I>6s1!dLApT+X_Zpa_xZkm!T90key;mm=X?&9gbSp@DzN8)E~l2eZ><Ly z=v+|FKB>W9!TO)sx!}auDFCp*gX7gAK9n0s`*yC7pkDTT$iC9K=k<B2qYynNQJfT| z^3rU_f$h|D>4X?0aNT|gQzGG1lF-ml;KdhArH*%nUFj2!NcO^Q^f!7a$WO5LoMzA) z%n{$8&my(a_nb$f>I|ejDpbmL`2WzDO~7@+we+TNGxPD-w;$GJB$Eoz@iOajcO5TK zW6(H(?*%QM)2EcbIvi7ei))89y(-gLyI)8{&YL7}d14Ip_z9s$Uo7|UyN5bJ3+aBB zer-H|YGuV=G`98rZ)!2Y%TK|T*vM2V(S`=oj5g$E7R!dp;EP?gaCw65`$%GETnK7M z$HbU-GnU-L4@puW^yGxg`j9WCa<;+KzMQY}2RImOKh#lQB|`$*S4=VjOVA>=M|f5r z;-6St@qYYb=#1CM<2zmM4xU@iN0~n|`*@qctI;WksFlD<g(dM+V;)DUuiQ|X;~X8- z=&Y-+uC=;S!sikDy0TT+(3Wzdmim!LuXPJ?k}(gI*m#O_!Gq>Sa|4z$_*KW&!@X}l z4622a%JOC&+ke&hMp0ZpDN0L(c~|S4y`97QVa_3(uXu_GVLnyv9=&Xr*6NhJu3f4a z;r6C9V931eYkL%X8B|OsPOr+M?zdv(*O$i1Yn2IG)PiAGC8Wh<UpdGQ8})3HTN~Rx zHg^KKg7$`nhK?hSf#K8HyUx3rk-K9D_e>8=o4dJLdqCQ^-vgGf)OH4gz~xfE!Py0W zF5K$I4C=cz`y`B>U36_Ow<L9`J9lmT_&t1)SlV~DsGB}L-Tw$^3$&M2P)`1{(i`4s z9Q*tM`@)%~ipQIkM)agW1U7sFu}mHu(CMTlw$eGO*o|Vb#>aZnsYf5`+5WcsQ|<l4 zb7yCVkB@KnGl%LQrW0WK*CPiFq*oOSGu_<>s$!C9@FLS!?(u)+R}0q1y7TI+udR`a zWN?Sq4mADK9+z6OEqPoKj@1{y-{bO9p~8}w+ZV(kqrus-O(PP>lpv6SaaW5(4zs~4 zSNw(|VY9D8WER=Y$G)cI=y<61q`Q)=w{Pg=bUe8V-a(%fO>6>r8RTm|k~j=fQb|ay zW1RhgDI&+dFtZ=_i)(2Y)04%;Ns7gJhVV*Ld%!VdelTPy%`QkR6o;2eKh#P6M_Oa- z#2Hk?$JGHMCyWA|8AO>haIupB{d8+ZP4Ucq!}5ELtBU_*t6@O~e$V|}{QM@?{%C!C ziBEWO==Wx~`Ol$W8sB1W;gQnV>>TnLF8Lqaf2Wl1_bhH}jD%17xWFkVsoE#-K{|4$ z<$e3$mmPTA0XXvjpk&ILQ|!xnBKfr?&c}w2le-D(CLW7K*UhJ&BdLFiuNB*fj)VKa z?}Q6+Zdyls6*Y7e$-GY9C~T+&7Ddq&^WZm3kf(*H{idGO4<V36WN0&uv~ogx(|A>P zkbD9sID3X=%c&CXBdL$`fv+4a66-tk=!uc^-x9P1zl`A`3#<J){|+ibm%b*|enuy^ zlU!F+O;~e0nD!J;Ff#q%8fJOf8lG|xPVwY+_pj3;R5toe<RnAW-g4z~=^nM}yv=Y6 z)uPrS7_R%`U4z@*HJSf)Q$K&<ZmZ~7IU}hh_bi*}qNA<xJqd={UXjWJmIw4CvQ}`F zxOzu(cTYr*dRceAgnL?1ov%-q0^!px)B!isnZ~!Nx0Xq|YpjBTrOf>|bX%*|;9uK+ z`P^jG7Qi;F-?(ACdZ3lRa>A*Gwc@hvu7%@HA)&+z?`mtWKT_2EJYEnT)xOE5P0>)- zAco<WYw3x2eiBT@k&DnE3tHhuVjoKjb(mjivPcK{a4@l-GZcPw^Xrgt4Y6{y+R~&1 za6WlB3_rV)-%nV5BDw|MIp;~X5-~S9c&VnANKj&m62FvB?)D@D@$?6E%zHP1@f~Rt z3*!7XDMy}>t$Ch(K?h6BWXCNgB9f4tY*$VjGQGh4cV|cb*}}$~jjp0PnKOg)*JN1h zK1SA?y~67jOowFjxnfCpAUbfx$Cp{&m;-eXSHtHDAvI!BQ3}linNwZto8cwdXz4LM zt2eDrWir;0sU$JTNZb<Oa)mY^51-DL9pb2z_iJ-LW-BYz5-d4ThkV~<qtpLwoJixP zCH`E)FpR1!63QH_pSX3(S-bL)NUh+T7Bt^!sL6}ffm1);;){V&z!!n^naFk&Z#9Yr zKT9Abp&@I6)lbSw<P`YFD5sj?VLqR_=gr+yBLS!_#W?>GOFR6r>UJL13oo%eUwB)3 zSr$}Yc&F}2gr^2K&EoL?>|XfG2v%?IGOVvoxm6td^5t#v{A*%t8s7KQdaX>ySm<6H z#)>PuBd%}Lj@IJapCgeb#fqP9zw0?hlPn%Q^=YCVM2d*OVmf&@IZl(K&x`nUhUVVh zW`HDeI1@Z8q$VcSZE%i`M@`Woe7SFKrz3Mn@O+K<mDg)d_g59h-f=s&u1FIM18@|h z&oRn3!U(UOoo8uAVU(f)R9xinUEZQU7m;WXd#P|N4TVF|oKY3Xuke&`UlbmgLBhRs z7*{BQ#Uc4HXQNp8!BQHIS95D83UCOrp4BF~?w>h2W84aob^d76m}F}$Dtl343}_=+ z;ahqdEs7o7GoH&Tj}9OcQ*<*=0}Vg^d0`$=>Bj`v;mzJZN(*G|N|NfXM@;1x-yAgY zu1K#b#U1}5!B8{qhR40DHzZ(g@4$EvImK?)ryo8bEUqMRsw-}r3pfsVE%@3}eF0Y< zfeKle=Yyo?T&rI)B=IcXCkgt=|Ma4)De#YYPlf)UIl{5e4;%=`#5sqGID0SND4z`p zi?vK3lWwZt|Czj;dlwP@ocKC$@F>4*yX?aUsUv2>i$BpZgo{pzNfgWYmqFUM)I-h9 z7x`)6z6+5p=3DCxJ=KUiZ8YKI+s$M}9-ufVjfHZNA5C#mr$*|un29=Bn5=jERuIC( z1Gdw1bPr?a;J=siJMMQq#e`EcDd3;u{^4IKFw!nW@&waLJJ=CgUx}EG<!#{b;jklj zbxa%=D(Wwj9BVQclgDuw=*h~@|G?G8q;nTDDQvVSX{pY~>~)wISDuA-q}q7?`tC>7 znp{k+VD)>8Y?l$ngh1o;u}Cs}LK=I*Zws*r2OEqw=}z+Z$gP>QBA?*lV+FF6CU+wt z!;MkEYQ~6k>5NK6eSqwQde&gc_w3Ji9&IT10{iE#d*oqX_wdUZ2BIF0@<tutZO;k# zca9HjP;lw8iahW<(MXmc<H2WSz(g;XJp>Vpmwj$<SH18XLVU(~K<Mx~Hl$v*CQnA& ztD<zVS*E%_i9z_i*}MATVbA+4Z|&9gNKG|hhBmyG8|xRHA38d!(kWIxd*q(=P&%Kl z9gS#KY~Zle$<@4nz%AuZOWgz)FG50whan1$kk;RxZErYBZ4&N&@LqjJGQZhE%Hj+O zA()t{Iq|24I3wK|w!pA#Ri$Egu#Eq$1}qtd`e3-gD%Z4Jl%)=xjx}4CJ(CQ()lWF? z*T^AyRF(HL@5V#xZ}oV70>ipTZQoH`wLC)rx3}Vid(TJM@$RbGhoMVdiYNWaocm=- zX4f&Hi2zhh-~U`!y#rEWlFcT^{lvCBqA~`jqvHVIfY~6NJybBj2#T2Z8Sy>=@@Gi< z0-VaF!TfhM55&Ym4$3mSh}Zr100F=HfTis^^822HhmU`Mi2qAj5e0DRo^Mp}dX`ax zcuOE14BE%jZ+jn=mOHkvZYw@;_tMqXf99p|Vc0OqE#O63pkHtG9fed28yXq{D_>WJ zA3HmYq<W5#A3(E4KOFQS#O`|~27-{p%TMC!!@tf9yTh6*COSI8I&OPz@uaV>s#qU# zkx@prfwU6}IzdCzOS`*_da(&k&tqaBLDBta{kzbdHHyTt#9|~POLkS@53&Nej+Fiv zGcH9*VHv8rR547v7h4Y$HLLdCJU7W`;k1j)a<ru(Vqz(FBypU!=xAn5vVc<KUq}#A zkd=v0JEq}W;P)8RIHrUFnF?G^yFCZP7*3jZjr+eiHIs{8<LSbYQc+Mump1hzSk4fO zq%}?q7b?SIV)7{Cc?2`~;YC8vY&h(QBjl$>wTzv1qu$3sDYmqY18kp7qw|F%>?-WP zVMB#r*_>Nt_y<*RW<dvi=seo_0a7j;ODv=dLGW=ff8e3Q6x-)phoatw7NmKjdPJVh z{WLw7awHI#WpmJFm*YQM*y44xjjM7km11z5g+h_1V{p&ao={K#RSE;}vmh!)F^4Qf zQNLw4giA}TQiv9yPG!#;yl?~VmMHlVt+&Fw(sGW0gSFsVd2Mi6FQFq{SAiaj+QIiJ zWLjR!qSFYs?*3StilEPBngoMv4w{k9L0`yxU|C%jJIIY==0FvGQbn6&Q!8|;O&e)P zT~U`T8(gwkCJN{;`Td?^Bht2a#EfNUbLn8bufXD@>9f<Q)iYmvF{?;Wr7yu$btGe~ z2tp;>BON-)`^GtedCL^qxbgrgg^y(O+XLhN%G!H9t{QpIc=wd%-K-Xb;Ou>jc#voL zRS-GM1+6%FUO{o1hPf*ObHo&5^*@AoAW$-o29Wxuu|f`KG(@p()$FKjZuCl$+}y6g zNCVHC^h~qIzQM~)Q;*YHVaax((e?t~a$->lc#x(YLfk~NgSvDZ!h27WumhK<!5{%| zMrPf07GRO8nLV*$TC}*X6`0{)HI^~u(U8@7MYk=UGC6PuZC%4P=Ej#0NLhUNt5)qW z40o<iC@hdU>NZ7B*&EbKf>Sd_c;MsZb#=Hn{U724K$HPd_djAH3w*H^C4g^c;qUI; z#qr3<)ZNA;fa4h0x#-^L4AGiZB8rRZj$mAd(J(SK%)7_NX~&V}xMjQztH8hG?|U{( z5Z0*9Pf_F8Wahu2+S1g7`Pt6M@u4=TJ>Ya_RIF>vGJjP;Z|3eK!tG};UGrmjgt(ks zOKWFIO`;ow;*i&2faQ(GJcR>+W3;-P?-SkGb_9q;c4oP*TB`2H=y22Ah-K#MqlhB@ z3Rwn^#npyPQ_b%8#9$FSWj{hUeuCsjCquKs^AmYW6R}o*-*g@N40r_JUDoPO=+&R{ zhR|?=-b&}*36p(yv@inr?LGsyF=97@&-`?)9^0@$2}*e>PgD@^A6hAKIVE8*%p(Fp zoSPOy^`F>bhJBb6;-a3;d%QXeoSPXxoa%*2;zR2RKjS*QrmieO!~O~IIh=upMzG}B z+YLifX~S5Mn(>IbJ=pIvj$m?>Ua?zV3URd*w92j+JC+624b`j~BF{yuhM2DV(VmyA zpt0zeaVN>6V)y~XOx3PDwj_eYUqlec9D38S*huM_r#{TMPc>La1;MB?gme+MC<i0b z30h=H4hyVG&$;GIVCi5)50qgCrHwkgV=emU$*Px>rTv%?=3F`*B92Cc{IdIY24~9( z!)q&XKU3*?lJi6X1&h*@9+$~(E<v=wSrMjrJv0_HDVqY;c&s6cB*fsK0T=cQ4<lh* zLk7<*MPh!ng5t?k+`z|v3p3+)@jceO{hD?&myg8d0<UPy1_B#o3V+($5_&O8T&Y9k z2zJwFWV8h-AH((ZwfP+E1boeWR<jVg)ccx2VNVL*x@&7H?U+nl<Sl9+e*b<V)A@Vq zap%eG^Sc|Z38m{F^R;VPjQQ5f0h=R<2ajuYlJxR(a@SXvJ_ssI{xtESZ?N(>Jp4({ z&RRekujgT{f%Jeh4X9c2Q=D?-EOgbC<^pAW&#D#WhUavVlce*X#>U520ie%+;N6>> z_Lq=IR7JRNLuaRGM{9~mCE-4Eiqpt=XgyCA!R^TR?tiAM^n?wb8w_KL*Tq2x-EB~( z^oEZ|wfBBfkT0%p*9)^BEs*{7h^D+))Jd?7s@L(3dSy7EWVaFK#<_p{rCx-^1|V0X zP((zmEGH?^bQuuiskAq>;)W<SC#56{fv9maHI!UDEl&+NaiEroE87t+X65AA8!eQ- z6QE9EkWn<OHju`}xls)YyJidHHl4&;6`K$gBX}pB97`Ca=$VlT2tf<4GLZvoeX68E zTn2LdF!otN2f#I^Aa&k-b<D!eAs63{&lIC&P(wTHB5R7um?E4bN2b`ZKXHH%ql@a| z6HwG3-dwxlzww+plrwGkPWUe7qvpohFfyw^GEEvSV-?D^kOMrJ#J<9W^p+*RSzozM zQDoLD{c4V3yNRw>2dcm7hJPH179Y>JCz-Ku)my~wua?)Bu2o5=QR+)n2698x4<2eI zUMQlbu!hjFCK0*4nZO@ZPaq~gg~<2`3j)WlbbR><E%_;N8MX9jXS1MKf!V-6v7INR zVC07j$|T_Y&9f2Cf^^hOQ2WndhOA)hYk?_nr{deI#`K((a|KFra#V-9^Lv=#LubKt zN653;O#pw+T)j>$Zcp>9xFLEGSuaMgoOHP?541IO0WPlB+rm}>b1lGqbaEmQXwuN7 zFn@QU52GU|{Bzp~W5ec9ZGn;$jM4s|nTpp^%eDgH9<A1G3Q9`vM@hfd*_@7b&MVit zM0ETD+SqPx4m<v=oo+->TD1FzDM~yo#t>8D8eV0`{A|7@$PNBD&|MdD@^;EF8J$-N z@H~6E(Ne$%LBR_%1}jZ<en!WU$Vc>D!Zyg)MFtPaM!K~^NJs9#exFVp3*1REG-)7B zU1VBOd=YV((OMB7R)CjO4vtT4gr}fH;pO~3$pLG0NyUUA9$X;<QfS)30Z75b5evh9 zSRCh!^IULIXb}%rI4FmwQjEzkBhjJ+Yhusz1GxyHIfh@rrY;iSzO%=dfN>6wkL#F- zyU_7U=Pl<IakB7=z|M}%TEgrFxmrzx0pB~|6_dapk!HlTl;BfDVg-DyYSUNpdWD^Y zJAT1fh9FPklSHoZgSHpDN&|_8QQ`0T;=y<V_P*$egaCPG+${?Z%#P56k&~W+)V${S zQDioL>Os^Ak+GAlMbUmft;T&ii!#V<DNh7uJOvPZ^&pZ4$WPUk4En~G5m;c94C41B zc_gSZi}sngB))EUjhMTU=L{TFzCY5e3$XU4TzI7BcUQ5jJ}6D_wY)RE#LM}<kKtfp z-POAn8~Ge-w_(o7r)C#`63xO+n1vxbc|OGafsYFfBz;z{&Lc-2PSIMkzWWLC@v*g_ z!IhDF^bTPj!IwSEo;V_HZ=z9?gJ73zf=zj&Q?h^9RtAbNZ#Ho?{<L6pVvhS+6#4<% zLCb5dV<L7vHalzF+zD*91ODrrd37@UqaY}We*v(?o&jVZa1tB!Yr><}2ikk?VT2`W z9!FtvujCo(`k}#JQ&CtBtIs$hh`4DIyY7TJpg+(MXb)BJJMN7l{r}eH4Fj;TQB+n| zmXcDVTD&LGgNT;hH;WVWvOYzHCF)B(IrCfDraz|nRb~j~dl;zk1<#8j_3QqApz#Og z`K9IM#T7G3$ydWxDk;%UHX%5wV7_$Xu|~6>d8J~eJp8YG_WZ$<swMJyoSX8)iwL2? zop;<-d5m39@L;77`3?bu+IfVnPvq6GVU;>FjQ}qddC=nSyz(xS6aLsJI5nF)h?4xH z+uokQR-M5KXsR*;+mL1fBG`?n#3D4OmB)zFOV99`B%IPRDs~EmewP^-0y?;;O4FPc zu^cn5W)e+rb^Vg^ClFzoXWWbh7cXH|!MOmOcEn;@S!qQTb*>s5hw+kirdHK4aKm^| zZqY}o!#e^kfLlrGF^`+Nv#b;9j4w@1?dde->mmxoQaq;StZFKfY+n_7exeW#dBkCz zwnTI-Pt_qzJCx!3sm9}WCL>Zvaw2=^R;|X50*3`L?w9y#XkYhsrw<+NoP1e~s1#z* zKUc_vV415feff1<647tdjp)B+wOvoYzRFb$W1YZrf5iw-a~>3M5{9f9RRIBFGB2Ko z=|i8cRbmvM&a2D@9mWix1N#lc{yTdGn#N8M<(YzIGgGrXjgIs4^IbRFVgOryT2Jxx z%zGl_=)=6F`I9F$rDf-?G3ns%|7_hu=5h-9<O~;_PqZ^$FKk4;GkN_gJ)?k<9!C@J zlVC#fvPKH-wdu>xON@qqt&I=oFyL2tAkc2~pFdjpZ-lacp^C4UR~jgOXK#_?3bp^V zHz5@#&GvP4Lm#Y+W7}KgFrtn%7sLVLeHuCNqrX!$yERawDwR7WG|eXA?{}$(PVSfL zeQUUhA`h;$O-vKYG)(MAH+eLP%Bin(QGX;#FbLu>GI%ZDi1>XH?oHeP;?MY7Glxk) z78Taxz!?Nh;WJar;<EDi`TiBW6l9Yy6)x{Abx;r)6lMlw2;=MRkx#hO+fOq2$i$Nf zbm)0pbU5`%_F&Io&hH7=l+BXTz{1}TFtZno<k_yvg9PqsVrou}n*!E2Ht9yg{>0}X z65jX?8hZp2t^>=yW+z!pnh^4Ra6*)XzEq3x?+A=<+K9oHg}dG8z$_&-Kd2*8-sf8f z6Cy+B>F!r?=Nb;`n)nnJ((J{h5zcUYHGL+y(ZS@5rt>jEq9!#bAA?1c^;i7!KV6St z^j%X^dK%1K%jqNx$TXS(ECR#r?aK@8ve<H*m18QB_2nc(4S<LQ+){!_ienl$i+nEr zEI5LLf#4l5qVbiPf~90qSumE>uXzU@xFEjVa1gE)@vc-%L*~gbOyg^2(b8sXYJxLn zN9Iw2D1vEAtix)HED==px){tNdUq&r22X4WChCoiv={U~G?gyq%V=r)>>OUMewJVm zQ_gOAYj}3tQqjbcy67j*9836~X;Sdr!-j(FZ-D)|x$VCY#@yW8dyAG6{*V)XJ;n2x ztDOPB`S6R!#e9hOyGN6+x&U)ojx<{b5+VEplstH7?LY;?wa|=fMDWv5PPxWal=Gj} zXhN&M0}#8$b0D-m_20_@`2H0rhZK-)`U++g>4Qk#v%^*iUbs}|Bsf3oO*q_aczRr* z{VZAtw`e$GsJq}SMjesDK{lMYnDQHl0&HP||A7p75?P~GoO;!!OXgdpw1#(+>VM+s z+RFIUMnW*%>RT<*p=n@DToJPd{KAae=rk*h9!PsSg;ECw5x*sgg)(fc?TF%dR0v6` zkt!A?oRfeAO0l6vz%}zpt1u!FpEREwE7MR+<~N{ag47QFiaFKkD6KFyPTOLq?SvnD zy-W9FE_%ErT_<Ky_i;3o!=dob=TxOmgbjiuH2Pd5Q2*G2tb|NlGp*D_P|zEmPDI4} z>`OMOge0REgiAn=^Ep8(j#m=EfV>Z1?KP|ZQx>T{>13xplz5tU`!OJJ44v}0&+H${ zxcUpYv38{UmdxJO*R(3fZcYK=>}4<5%Q;{y_Q1z4S${qjWI9>?7@6|N5q_?sC-gM` z#3+5c`=9*i%!&-NTc4iVetkUU@w`~x^8MngONM{nGf@$z^;Z8FgTs)EAVKYP!|9-S zL@W(A{PB%;hy{=_7z=qHCqW|s8kC0+V3F&ZKj-A@-+O5`JkZ@ewHF9V7A|}lh*m7q zPZz*yp#F=VHOmI?SH&CE8bF2_8Chl@ksDs=sE&mHIulo)QmA^6yjYONHF~Jgc`iYu zL$TNp7@(>?=f-=#F`+b4^TWLe^_-fZ4bdwDW97lb>6dKN&f4lp>KNAp=6tb-&XBa_ zf_0H)KDr9s#t(jI%!~ai3$UCRss4`Ua4f!;OM#LHbdq&MDV%PoVNKrgXOm*Pr@v;9 zWd=$bh1=j`!%>+d?4bPU)!#={lSYoX|4x=w+LtXiou@x~c|>;LUT`!w)qWv^gl9)i zinEqyj#8HecS|0D`wq<($!g!%+B_2uSU7x0r5*RD=O5m6kRXNE7};aur|V<AQfIL= z7nCn=)$C{1PJ7mRx|I+w+}#mt%j>HP7V8V9gV9gdO)Df7CFP`*2Esh>!W)Pb8IKaa zh>ht?XxCd-QY4f8mXwfy>=u4i^J})lC`=7;;671}QI<Bjme^!gos7lBhC3FtWlWhS z^z`J{xCOF)Or|`o)!~XZ7tfC9yGR@|3jRJc-D!@Mlva{cRFg4ZZbL6Cv<U-w<hJEI z*sN0lEPFEQLStxYUrYTmIb^3ou}7io^4&3x98Q&f8cCejPz!={GM;comA>pu$h#PN z!JUaGCnVb;Nie2)mwPYAOJlS_aAL+HBGlA2I`In$)(kq>8|aJHOUY>~ZflpyRC}N5 zS`A({<kG~8dgq)KMRiioY1C?JuYqIRipfk1Fx2pUMdcKw`d|4(L$4VjQ$L_@OttwP zpzl}C8aD35g9?oBj(s%oGwo6iqOkF-HMg|Xa9Nsj)R~%bB@&`u6ILDB%CzOh$iQ1k z-z%|2TT!1$71=;iMo55NlcTnJirM97P}Uy{wEubJzxvrV(&MpUpxle*62_e)f;}DT z#=_xLEz9N}HJVsr(|z0CG6|{mhlz{QLf4TzLCKXwYF*MhNN|g;xz*PkD`~k+o)yL2 zBvePWLT=J>e#%ce+t38Fa7Ye*A=z~4OyJy@_~Vt|=W{xzm%62eec1YWU<x2J%<LNQ zl`%1+ZuC1ztl^hkYttzZ!uwcVQ_7G685Xhb&>dCJ1YV+m580|q_n^l7qtd_2iGMN5 zmp4FGdEecoE_rh<;{DvCy25T6I;*Gp1K&y!7r2s4hQJk=4EnS=lr(UWzPSkmBp2nE z>UOtqbIL0!Ci3LGe}Dh{pV9RMK*#~EXhq*ENGG5&c<E;}+~ch@9D!!DGN{9<hNx5Y zM{G8rg=sFS523@_5}5}s02!=WTI^cE+*}%EanCTCY-iINK1-Hgi7i!l?qTy<8bObB zeq=zvt9r#u+*eAUD6zRP#3#b*>gMLD|8OAM6Sefas`-4upC1tCOu_v!J9L{m|Cj~B zXcGB&(|Xu7ke@5W2w;3NV~zwO+b$g@J+KC7(l>WkSE{gglT_qdOqzuF*d`Kgyg++a zL5JpshVa8Z7WU;pBfg#NRnMLiN4O;rZ9rZ*&rClCTC>}qtK{I`e#5aOd-4!~B5&o{ z(=jtU;P)p8Rl||2ze|jahfw+OQW`OId~&F|H{AZoeQSOEuak9;=^Yyigy_W2UK+iU zLcUBtV^trfvJVxh6`#IW)?-?;mG8%|1(BmB$x?k14%oPey>J!<l(uTP?DWwX%_lKT z<q4n>TE<j}7sHfRdZwavC`}z57FUN^sbTzG-&GGGS3(~Y7vR#V6$p{L*Yxe{pk(4r zVqOCl=7ehK>641|U}d?Y-=3_ZOSmS{_>1eUA28Ug+*|}o&HQe}utNZi&o&4>E-;9X zkU(yH*^7=@95F>wBSDL9<cnK5xJ(%2_L}rR#qW@k%LGyQ<c)xtWphoswCNyXpKlJ& zCJH;#p~;-~RTEs_9%=d`cq&ilIxy+nr07&v|NJna`IUGnJ?t5c!0CCZV{gvQ_hD7f znt{+!L4k=n;`Qd67E7M0Tn{nii)S=mlTG>aZod)c2tW*sZ9aIQgAnrgb7$b^JJVK# z?T6Of_T6g2PinaZT-j=3c4hGQwv(d!D$1MBRSZQ{rMN4xEJTszNmsqm+dNuMC~s0z zbz-*z@#OST_&`8Qo86DpxAMjorgCU99^7ba%kgPDDj>wjN_nu_A82BlAr8qZp!A;H z8WawM)n%SYh(w6Q@R_}rd|(-*Fl-6TNzFGg8e`qwh(O|o%pgmw6qZ`~j6j9xBIC;; zowzmmuTKggS2H&^H_PjH7gbe)_%91w@od??j6V<&6Z4)=Azh}81fUYq6WW5$@Nw{? zW^+{g)by?u(RIzuJM+p4@(>*9rUvB%Spi>jSfA)EV147=No0{($eld<P#b&%ka%nd z*PcDnw3lYyjq84R+G{1rA`YwmioL$3-DFc-uq%ZXqdP9;&oqrEpEaVLi6KO7%~IC! zn#ANdVfxeQk|F_b#O;6Y<viqelmLv8;^yYdwtq*ps?pa(D<LdjOnTG!sq&tyeYcMI z$<TH7eE9np#)6zY&ZhEE6z=4GIK}EH-z*!JS$YBAXqgA;#^#{6r|8oHuEx?Zv_j{; zX>d|(W}=RdGrxpcATm(K?JGjY4@+lHswI5fRhV1T6|GrQx}rnNk|GbwfJ%lbyX9_r zA;>$L?{%P9LEd81P6<3;evqYOxcC<WWD8x<d<msEEwg66edf3jvVqswg37+sB>cy3 zV*>jzv<fH7`6wBuFs?T|j&O#@E}+VcpG?&#qaa0{Cj&@Br>hJB;fFJU9!0V<iN@6V zxw-^n^5X739+F&4ji`!q8Ad2^4EoHsrASAwi6`I&%1l6ql0ZqF$0fZ6k}^3)ScMcm zV^*xvhiJ0{o@rOO>XX_^^EGy#e9Vib?~;@Vto~gUN=1kI2<T|-qv;=1y7<at+!RF; zT#)5!(U?ht>R_QTPZJ{9telI=Yb_^l`8fXkpQoxK5X{eOM`jl?+){ax%s5f6oQZ-K zRRbO4X?#e|^t`G)S1$Vt_)?8@l`pqM&6KD7>wE-bh1djT6qavaM~ckgv(mN9II$aF zf7(A_dX&2PnIQ`7Wp`uAI;}LWnfQqOS9^ldPZqer$V0K^jg(<tP%V{3KDS-1bJ!uw z%U~zVKqs44g{s&I<JNBG6^`vT^|J|>P4%?2eZht0Oziwhav`YxV9PVS!P4L(-J>=q zpcu?U_LIsUpRwP=#usG{lQb<Q^J6n|zaA6J?$@V30TEa{iYG=pm@|PNj7a+vI_PF` zE52PmZ3)>CXEB4S2wxjNOW-@}S1B4XRODT?X#}Dgb#>5;&bp7mZWothAV~3JVO}Iz z3gRBi`4_(Xe0+zsAzuffbZ<p>4Jfy^`kG(a+J>LZ+z5&|ea_P1TP9zLjdu0?C4x{C z`UItbgTuDrtXi$DKBOmL4vDX#h?M=At+OEzvuFY)*x%P)<qa?Mj=zhGw~LFp`^}5C z4ywh#-$X(?$n<;4r>DyN5eoMHfzD|jJZxn}4<f@`X%fq6&@Z|}fmiRnUETz+5eQ<V zO|J#*>mh`sVno86cLAPxw;G|dTDh^q*?aw|`92b_A~eGRF^-m?LxQ^M&QxwAn8gIs z4jq8+ZL9WT?{6G@BgYEyf|w$s<uXJ0erlZ>@~6#2rWEUSg|YVFK~jX0AYmGcK3tlX ziRf64i*NLBwg4_`FsxE2Z3H0%RF_q%vu5x_m&cY1>6m3tZH3FRW;Aw-0O3s9FONPQ z*$5Cfgw<t=;Pjdrmm9;wc9^(EzSr%?7EzC2Lu_wnQp0*t#u{dnQ=qeb2-YCHf&39> zT4GH!H-TFh$}n7#E3N2n$!oEL@{R&D2nsp<`z#w)|IU+#6*b8<sNecBP}*SvWzNsj z-?g0sjx#E+{T%77_uuCClyxcTFqUxhF1M!bbg^QK%E1Y#0LZXB!BvG^?uF;J;*LNF zaFPozhqR9M=Rpv897Dx6j^aov$F$C(BgYSmAGg<^Sv|8TMu*$4yzX$@&bm0u#k@FS zg+755Uci)QeT#MNXpws=vT2{{z#4*KXb6eZy%zEhwj4Np9YiN6K^z9}ml(P$0v&uK zmxV3kjCaS5QN0gkefCg(u<9|drLlvz-@6L~=!KxAdkxLby<y(oL;r51K-VvmKCX#B zHniM<!%CU$7U#9p4IFtit)Bb)*#EQ+$*g#q#Om9{?e^k@Ws8@ClT%zGukjA@`f*8e zQc~UCX3TqiuA;TIHD(Tu(@g)53$W5}G2~JTiri*m6b~W8(2Sv_Cn@Ze@^W&Y4fUiz z?6Qmeo3bl=2?oc<Cv=02io^+t$$DcGV%j<jq}koCvve+#x=cUsyy2=dURzwVvB%hP zMMp12A1w!wOh<5Bh6a|58EDrvHJY#z1i3UbF5Po++=yuM)2As2vwap4b*KzzZ+te7 zwsfn@wQLNZGpY7!>Zq2Zx8vMGD;g+!P<mnflj2}>L7>FjY;|^cXfznd)EO@!v{u2F z;IR~CH8zRXSdF$JEQQy<l-Qq3fXH1h6~TEnqQSffA~onSGrEJ)ioO$i*=XdHQLn&D zm%c&$1bCF<i#V2{d5a7TZ2-|xVrU$bV4_L>WGwa_>M27CYT=$}f)T%S!Gl0__l>^# zEBiwO+j0;tL-8p-EHK$dAiPKldpr|rcCe8p(&~oRE5--~ujM15PgD(O%ZpC9y%)h+ zU>M+TQ>)U%#$(ROEz^X0ORoL^n#UQt1BBj@i6|%FSEY2*iouo99_2XMhA@nZNQc$& z{4+9ztcA*plULKEDm2_<%@S^y)+#tfdeZ5&bmrzMYn)~T!*^_?wD;H&?!GO3%{42W z*6d*ME`rAx!mLHir4_>CtJT8s=Tnn`s)2{5FFzKf!JZk;Z3J%7VYgbXlKM!@#5Mm% zCHLI(hhZEb^nGuC0k+`TI?%|ur(>UCG<#El+|C^(aMP$BS308+c@K8@*Yst=Q-!VT zV8$hJ=8(rY=oh;VOj(*>t%CYAomps~xmZEBDVkN7C$?POaU?SZea;yMNN6G*-(QDi zZ*(HEn=*p^w~aH@CQitMpe9npM;y=JlC=sR(EDmVlz8=bMNNXtaKiUdZHZAJ8Yh?M zkCrLngH++1Q}=WEM~MlTLz{I)<&*Hr`(=tW_QhT;)N@?4xS&Vh8cS6sZK1=`K=Xi3 z2>Vc9S7$gV4Er+c(VRp&BlsXSi|^M0;WCJL>_LrO<Y!Vlc>*@Rb2V)?PEHPc<nrVd z1BI{(Qo3V7FCiH)e*u1{7cblZ*vWS<ph0S?+^{8xF{t;<W(h_lr6$b0Er_8rDm6BC z8Wt+pcL=R(v6=qf#=rBcjsZ0#+^yu(XZ1_B@bKU_89o=w2NcN`kW<%7;CRj8tvjYE z;i@5hlBOQ1bU!jF8-2f3P*xhvTFm&;G@8@M7+NgEoAe2+Aq6*x78z?q#m{V{#09ZH zQVZS+MwCdk-jh?O?<EB=-p<vr=Q`<!1fKR*P~c3cYzK06lpB<}!W~sl3zs)Y&DNDx z`f#R3ZZPqsN%plM^e(B`9xrIm8?T$sPefB)r&txM5Ff#5#{_cM3&0|HnFXU<>0;8b zgrt0raU=DMWO2br5ksk<epS#63AMp&${XF%91-UfNe5Ngrim27cxPp*x>Uz9Bh$nr zUv5}UIFCWAM%)}1+?3=Cn2F9h9T+dpNGvOK*6;uL#9}?CmzGDna!<wXWQ6Fyi2{)( zl;&Hm=NsdR&~(!<_=vvtOdj<#D5y${ay$5#$PU2mPqMg5GpU9?rKn8vyUh*e>y0OC z3RN7v66qG!{n3s_>6bD1@+eBclUSG;Wu{&>Em>d^vjPGv9;tIzy#UWVJUW#dMvT)V zf^JShHLP5J%5whulfDT@h`Wr&cvcDi7w!pH&7&fTRf+3JfE|M*1d0&w7o1|=FVp6R z&vDB}s7_F|pUen#cS-g4hnAk>euN5RkZLL-6)yyL`4Oug>qdbF@!yWGo$M%9F_$8a zr_3j>_G{cOIutS=TT0-&>{7(CUg736?QP(wwCRg{tux=e_q%CA9l+J&;WZD|HMU9F zu3IX6>gf2;*jAJ5xwf>#dX(@>Qb|c&SVeULPxrZxtIMd;zgXF#q)<@|2BXo7RrvJs zh?zIY6*5AFM=`g*kL|(<;>;26^YnZEQBqo3QBqP$vF16KdXIX(=P(U#+w&cV%wR!< zi-*?<G;hqGnp4FO!<fkGl2?_xV>9B<Q!KTgaVW@IJJnY>$S8RLtn!Iu#c?BdPoj`A zyGV|HfDMV1Z^#VJ7R#NL`geHHcg`us`S6)~1MilO!2j`VWi2Yv{QLvFpEsyO(Wglf znwmwa;N{!zpW^L*1Q-S;sCXrQpR8rAYPEvbfC2<(*x){4gq6;8@qC%4AyfKh&sV!H z`b0Rx!%h2zK)5gxEiOe)5W!<A=)lu_TrEkob%AJl`xdT+Jtg}@cUBT6j*pnygtrnA zH*53IFxs=b-2hw5NLqx6M`@PQ&<&DLf3?Y1ebus|Tj6Mr_o9G1auQ@ok^%P9^o<cs z+Zuuf8zgdK1MTF$r{Q#9PvBqpvD&?<kF5>DF<LxjF*<4KIc<_;!64`HQSR4C-1sOj zI-V`Ihp6G(h#=L_SdKu2?pZEEwoDJ=;-SI3{7Itt>9<0n2rSp2d{qlDfDBa^6(paz zT`nMjY+u_EaAY(Y&%{k=fx&~dn8%ps;6*UX;Xqo-sK1D0|E<^0^-h^fdn{d)<<^zb z@TxcSIsOl`V!n|TzAbq6<Llz_t52tK9f2_zuca@woR|0rH=e}4%Tc3yflrC3b|GDS zq1Q}qmmk?`R%A2+lUI40xFY1;P7RHccd{-%-{60~;W_#}QL5fSm@D*PC=|7Iif1$Z zHd)^V-D^%^0M$HykyYrCni$@+ICu%7F>-bwB*A@W-Wpq)k|T^69{roc@k(%fFco+N z*jg#<@Y$yb(K~dMyb$z1bZ|^1!?RJ{h;Yer&N2L4PiDsb7!6a+&Aj!jl%Xd)>hNK+ zKpF^?x&m1L$&p9>Uw`~wuzcn_gETy3TWDdcTRiQ;c~&@lM~mn718}1IW4`w9f6zHy zTL17<;yZ^1?fc_8qgOSef;Pa+BD?g-w$!9M^mt)<N-T*)Gfi^(;$b!>@($oc04$om z=<<vV`Vy{5)l45uoeDT+-W!cpC3M2g!FQr(4#V4{PG4~}j*RFDtNJ~xX<37teS@IU z()sx%>DC#lSW(23^{tGl2n$kGs;`9!>DQ(#x%j_->$+g*;3ep7Ploy8xH(U62K`FS zobj!<xc8nze?@$z{o+s-HihuSITz5M$v9_SQbIzRh8L($Db@Lf^{oh~4R53GsfHR= zrKl$*pgZkN21^v;f8H{p)TuJyh7}SXr-ZxkOHF9R!%h$un-O-<ZzzDCG8|E3-oia- zQ!pnM*i#dKMQpRk@>3|)NUD9g&&WG*3!pJM8aL(5Ov>Po*<JO^q~y4$Rs;wZQ|r9b zpRf9EEFW*27>!r#cw3rPloe(h%^rr0j!wyIJfKE0RgwW0T^a~eQC<9kFwsAY5G5m( zw)_<AyB=v)+D>}{dMO?#y0=*pDp&O_QFW6w&AIgM3;&~vEGmMEcYnA?SMCz!vV-9# zFv|yKsdmyO*v7V`fCBt|0|9ct%F5RwMZW(&t-KU41*Ars0UH;Cgp!Y*cEZ%{>F@cX zGCFmc)yZ2_7byo7Np3X=6~`kA@X8)Z;1a@64pjV_*m<^9Js4BD>+x%)eQvR0&$p_} z_<U7y>I`VNNhB0s@!RREH_<c@wV-7M;Wt|AR|7JI0346O>ecUwe>W4Iz&`J3*XzW} zrJ{Oy)35%G48Ty^t1^3j?(16|U?O&3{QAHO8<?7%2)SBZyi84{cv3e3&C1JTXUW~T zbhNdNFR!X%%5&US{r23&<vB1p1M{<ozoTD>yI0_T7}5IK+mG$rN<R)48zl`54`H*^ z!r4crzZ2Ll9cf7PcLq3vVug5XB4<yt5_$-(N<yw}Z0q~G-KeIu*6)|Gv}o8vW3f;2 z@GlZbm0CqnLF5wmc=4yisqw$ga*5K?gck3xShob#(d0BOiKmEVYa(2Hel)97CZg5o z>Fy5^p~|*z)1eaIv>;)w6>7e=p{=2GU+S}KcEZw;q6-3OGjG2=CW%0&eN%S&5mkq; zbW}PINoRuCzR#Q%&j`#g5T*K#wO}U*CqJEO;Xv`$0*H@A2z3-}_HeZ<ew7hFl2Vyv z$HcA*{7`3p>gAAY!EY9vMl%I9IKuJdHX1Uc^tGSkSESL`;4XY_Z{~>+Ybmu?{51XW zSLuAzoH4rzXSG6@NQXt`Tu(yAKn~2rN`&Vv?VFJ+C5ruOUFW-(MX;)NH?Kc!5Az1H z*4F}DO0$MFB?^Bi<Q+-Jcj7l_o|7$V2-;XrPF%enapy?vt4dd&8ULoKx7+$BFpdA8 z{D#adA;1l%2Jio<yDxp|s+x{g<Rj5a@-l!oAww;!D(c^`U%&|gM7A36wm+8j;W?R; zrc;en?>$IRK4QNs<`dS?b9tHMJJGV*`14LIJWRXfFlI>qY*Qc;;BWWx=<okUTDLAV z@6tatld?NBU|?VXD#x$RN5zzGXBhrX7v5CVzTR$edHjCyzTborW%dv1<Y!$rg?V{7 z+1bSjKWNeQDVot)u71QW&%Mrhw5_(pm6b=oEiD%Nl3p)BYu>#}!FyNp0-#*IR3Ci) zd}nVPC`j{9eQ*r)0OKqB?#}>p<bNOk&8=VE4YCJq702j_<uS9dFD@^xu3;u>s6*xk z2tWtkc9mwKX^9V%A9--umJx@+)B~-pxTPL>h|5D3nAn+FnAlmERu@dci0D2%7CeWq zmkUJa4|D?K!Q^g#tI7*l^+up?9l|K)fTFXz6($6;axp=AL4yb6iH!*e?U_)fXVBX9 z!_X7IFC`e~O{j@E`0f`Qo;s7$Jso_EYV)0t+^+zcGLS}!dW}KJ4@WLZD(uj^>#C}% z4<9}N{+W28CxS9&Dtc1(XEwkf5{+t%7elg{xq8hoOez5Ns}YtuHu~L6+$>k|G#%yj z6gBZ8KribEBWN!wT9(=b*)Fj8S3Ug<EsrlNQHExu(oZFjR=v+SZ4?@28{SK3;TanT zZh%)IS-0e~c!wS2!e7xVGhm3aqY}X3&+XrG?FtcNdh)D?k%VUrIBHZwiT#fRR06`@ zk^q>uqRvRw1=8V`0-9L8FZ)sKvrfBGtTL|mMm13bMbj~J?PTJF_-D?j4-~f}(OGDT z(ixigM^0)gau&A~q?-T{l1ENV>V0d0emo_hSYzjkiGx}q2S%K4>6$*<kRiP8Gi0W3 zc_?V32mr^`<NfzEOG)#Z7j4p5BqJ5TKyWU5Vmv}6;QNZyj+k5K7<Ov#$MG+Tag^D$ z#wn|(S5J<Mbs<aS6Q3FgbaqGJ=yy<pOi_H>hUbt1Y|)s4vavvChjWs??4XCjflU;) zX4XrMp$|hT?q>}Iw}<i}DV;2jQz3H}eM=2<fQbqluJ&$-0rSOW)d~aXsH`kbE^OK% z_SRe88Nd%2F&cG_r-+tWKuDm|FO^B`%W0NchiaGAs`^!Td1b=Gpl=y=UsaV}GZPBI zl0KiC@T%sa)=%5tDz!rU@M3aEmQJ+8gy>Y^`+_XBQvON+T~DHV`kmVZQDA><rsu8L zVM~GcE>7ZH#xr6Zs!CiPR>4X6s=iKM#HxTM)~JXJ9XZetQddEWpFwSJ|JUPAZR+s> z*4q8!H(B`dZIYr{TI-(oEj|E!tB{?_gccNL=VvkIW@j(2So}vduBcu6Brho^>F0br zmhD~Jd3AEvvoUklzjU>eyMFU4v-2zisQ;}OG(L&ev)R&vyk|d@{WMn}q1Mve`NcQL zYw6_|3#cixE60HRh1>+dpbva3dF>otr?|Mf$ic#~x@2L~H}?8us!VIX_GxZjo<+N7 zdgAXdbJ9VZWw{?UHvl0U=qQK}uAV+Vu9@9FQoOD-<IC&x&*PKr0E4NX9K_qds(u7) zBZbIow#FDuovyDhTIX*wMZdp3UU>qMd9m{8XXo{<OW><${e`xAf~}TM(@fd<`Mfgf zNMQy0mtB9Ch!QSiA}`Ub?2ep@&!E-JOd13?lvaNYA%417yOK1<`IGWfpec|8A1o)l zSyuWvMH0fxeh%;FuR1YfJZ{x&ktJ_DsVJD`xYm?<<)}~@84e>@^FDUOU=J~DK$qHh z7JuIq#6No-?SNS?ud9=#+W+XsT1E}Gd4*|9d6M)jRAnMCanX7PYCBwWpCgD#i%Ha| zEK>q1xU!t0WPHr0CKm952HgUYF5p}FfTNBvA%LZH5DGJug-2Wh-g4;MCkt9t5&~Gj z$M4e)+Wir1<}P69P0Og-ZJ~7EfBTe*c{tH=#&_v#U6Af_FcOkh%ge<JQ*Ck%9It@S z!Y>CjB1n?PlsTT+u+DPt5Pv7)3Lm^R$Z6PO1~1a8c>61k391|L%K&}NcP~m2RETX= zW2V>3r#H<h$+y0_Va-~RX6tnVdcbUJE20+Akf(X0`N1CwSMMWqT2V%4-BKr;JImjX zw<?l#9vNLO{Z$il{*Xy=j=lyl;%HPLg2CU9bv?=+E3{kOTWziX)c&cdwf*JM(g*W- zcR&z$FIuDY@8(p-UDOh&qtZG7e2CY*q+$)#_7#JvQ>WrEkLTd-h*qREOH~??KUB7k zEko+^ZI3j?qi<rs`lM)aPFHWDj{YzqNl&l7G>?NLH!oLtmWgANZ{or~xbG#73i!fO z>jEDLNC2D2!rWYi;QhngwX^bTQA^vN6qZZVFV)pX6NSp|ZQJ>5Q+NZT`@O3ds}v`@ zLyU?j36fmKkZ*p@wyq)1GtXr{g@{W)#FZ5k>$((_mVV#-*$uA~G2qxRiG<glCqU^V z;2atzw4$0Kh~Ptx>wf9($Tv3AAB$=_+v|o2nDpW1tP|3E+n{3V`}OdzsL!duN`f|t z=0u|Qeh%<94*w3`YLH=G3t<-9B*8gxNyj&{gJYU_Enw-~qY{H~*{avtbkZZZG6){y zj}2?JX<?Pk8SuUe{Bku(6*287b@GNWn4lIX^AL^L8Dmien!W4{bwBXWYeoGo<h@7h z_~2~;VWyl{rcaB`7|9(iK>b{}ybbNpq_tt{&GDn+x(Qk+McPP}ix)_j$%b0|ZG%il zAN&Q>)Tv}95cCQi{Y0i1#6>qtRdRL2omc^o;hnTU#n`=0xECfg@=1GGn^4>9z2L}C z(9%vtqIk-^M5JTFt7R%3I^)qQ;>96TO{SO+P-)+ja`tDnEX=-~ym8yco^6X>aj}Kz zG4F7<MNp?~DhoUg5Fx$$ZJ!jd&e>sreKdz}kY6k{=Vt;~WxJ;1fqSw-@<fxq#5ard z4~j#ZMf3N=)0|n$6*O)E$d@}MYP|F^M*`JBOlX<He9VWT3r-bx@*c!re%E04LHX+{ zKx}*r6wG{h40P7V-13XMiqvzkvCAziclm!?n<lM@COVQ#C!(C1m!n471nAF*W@do` z4bc0O8z3TD-nVy;F?%}bzYV3&MzQDON1S>(;|V?kF&gsb3T=21eL>fFL=h^v%WVhC z3hC356%+YZvfdX3L1LYk58Q*d9<2M`t-Wa^J^f?Z?*Fe$Yg$qgaBd#{*vkRD$Expy z+0f{%yQJH{l6`C4J$D=Ta=*_e`o64ltW);hA*<<MTw3k1cJ#qWK2%y^`g{_~mFO!# z6dm)o*f+@C&-*!x7E<0eYu~JqJjY`aRqT^^s}3dfOA4kGzuglze9TegjHU_YBj!Gf z*H6aVIh@R4`Lu4sfE`hS*zj4w()DTSzH&Z$pr4ME+UC8uU*8(U<-xQ2rjN-IoqEqW zjI|OA;wFm)!vdAxJ!Qg5;SXhK^wQW9IGu+EhIwRC83$(S58gEDrb;>6<3^)+6}h*r zUcIJ*M^_^6MLp1TTVwta(Hc8N<5fAJJyK0=7J>2NJ`JB76|pCV>u}Q)soo#5Xc?PH z<xP3Hd^7lJ<f$FLJ?ktTA*Tb|&%qp{5k@XbdY!3i=13iurV*Jj9+{H4UNX64s<K!< zn}XT>a0}un&!XR0DY4}<v|x!J%y_6X)jr?hg@2QL*%LLJ;H`PiR8$%(FJ~H-WpNry zeD;v(D;=Os&+{9HX$w1i3OySv8?T7nS!J$z-G&j+sG$ve0^(8;HAKKe&gx9WQufuo z)7&;jGbD_K4tK8-`DR@z4fW~mwqCLCZ(WpB-dA;@lzfx*AuSpycv?QW1rKA9)`##M zybO|^Dk9ZWuqc`F2uxZ21Eo!4seU(IPAL+fzOQRQ-t@Y}uZ~pp{12|LxF$*_Y7NXZ zlvq4tRAF3rr<kCfhQ4gaG46?of>70P%{aL@dJmtU|D`!eL%%B~80d`%D~PJwD%z#u zT(B1MADXE=nAD4(CAXwm85rTrdGxaOEJ+o|@UxAIy+e&500X~ESEH^NS7RAxcDrz6 zI|v}NrQs1Dh15^m@sCNa0d+wQ%{K1a9bVfc8sA9ulmhN<0-AdcjUEDAVq;c&B%6-n zdzTQdj=J5O&GqTgW?H=Fl1FQll#4%Q7dRUy&|sH5{5nf>b2cW9RR=wJ*|BC{jO4&v z)T&(2QgLzW@3^>cU%yOl=s$mD>m2B8@8kMEp3XTq&o0{Av2EK<8r$X*G`4LvZtOI+ zZQG4)+idLQJnuQ*d^7z!)5+XBd+oJ;>$+U4#Go2o8rS(ZB>g;6>%75RX6o}zpKPP- zbB*n8xbPZaA3mV@2scuH%se>Xguo*Jw_P$+eyo<4pSf)){%QU+qUt}B=(O<`0ZCyh zG--|FLqOih)u=Cc&GkzLp@IH=i6PAO?}yO${nHHL5B?tl#V(<dj|O`J=>RjBgxm`R z)4m>7Bw1yfRS<<cM%jc3;pEpxX;}84o+LC%bzHHYx}pSO+5tIr10|@4{37^<<iM^w zw8+tRD3P*^gHU%>*i-3oQ<VgI%4ezuM%nfixhW;WE@STmN}9HKG*VgiKrM^gLb#0i zy0QG^@^C7xAh!G^lMP2OEm3w-sbjZ8%EWQn0jT^`Ej=i8$fpOUZb~5Ys3RFLii6_- za0~XmM#4*CM+wTKmDzfjg_b#D*$64I|5M05s&Gd7?kuP~0~v`$Q9Yu<AseXQwv;cp zk6m3wGzQ5o6YrE{=Pi3NoFLg01E1)I$+DM!o@5><s`fF@{OLT;_vw$!(j!ARI?Y#$ z3sV8t9BJ%JRV}98BbsqAf2=Bgj})UO1Pd6#a>j>Xba0|Bv~Qd?2_nQ4>y5FKPHr(> z7eGO(<)2e^eo=$O#oh%Z6^!sgUzGdoN;H#b`=n_NRdAT;X6I1+IbWhNMaVz<Q}B*) zRCefte`rX3(Dj@Ap5ZbMLXK2xJWJ9n)(5}*8e=I>@V>xKmz}aaQ}l*4+MD3)m3pbO zzJyAY{#p1Im4;FkObLgLCHJ%`yQPJb8S-}*9WKR5v9k?0{xoEEreCH)Zgc-Km{xTX z$vag>=Ay%kB<?H8VFN;Jl*ElY!8nt>n);J?OGMGdo~J0j;Z*x9f0=1(dt;{$3wK?6 zb8~m&Jy1b*>6e<4vI=722sC}jJ@3So`_e3r!thN-+&T#bz;>uoc@Hn$Gf5@PCh<d{ zWs!H9)v|4DB-ZaoUh_%5s~WY;T-z|uUtikRR@EvfDmV`kT|{54bCGI|)ercYyT@M9 z(|ThUzWcn}CY&fTPBKo;*Wd7m0R!>A=MPp5r2ZAIQY+_4`Z$oyxAnIPb4^xKSDj`+ z#IRi}UpAM(OG*3dYvajuE}#F*^!4=S2UsDW%Q1t3JiL{>g2G-WFssDZY3#lZVG#%N zG|-SQP-xC2Q2DY+;b;mk{SEkfnEA{)avwoZQc@}hUrGj>C0?3ciJ*FBn(5<@eIOkT zK$VN9a)1*llew;-a}EF$Yf}#CLhUK0`;=1<yY=4+2P43|wyA-6@5^CXimw7&rK6F- z@s|z1i&IfBs-+r|eKWH5v3nB5BGN1W2vP$eAu7D?^5Xzofvptb#Ie?*=CbKr?0HnU z!FLfQAU@$QM#Ab14<tTg-3f&-&%n!|N(Bj#L<&q+Q=LO4CO}!u1%otvw*i@%R{cqm z$%vRX1OP>VS21ctoRZ`=AU}#4iRho_^!N0z0H6+}3%-FA->KO2P%O&oIR{>vrKgS; z)jSiS0YY;cP;td7;GZj0GnyR_p)|Du!MwjiliV!hMWUspff2wY*4*uF$Z;~!#8|OR zCDbWCc0jiSnb<2G%whV;A-yUXNtj?5344*O{{v3IiCIy{oZduTO=XMxt~brC<1P#- zm$4pi`89hiSJ?*kQjq19kvVF2v$W<3pG8Ln`xqb(7%pV1QT>0{0g2Rb{JAfAsvm(s z7iz-;q}`ivPyBy(!5cgLTO9fROJtGVO>uKMFZ1R*3L}0xOf_pxiTacd{6tnuC}(QR zg$&c7S<juz`L!mP4orz+<A?yZYtO8>7PLd0N|1n=nF~!o#vNM0qvoNJ#HDFGZDH!b zWxTDX%mK!dn4%>(f+?liBL+fF>*L~3BR!u?MoVk!+SV-%Fn;k52*8Reya#R<-2<O& zCo{PtI1@N*3ZDIG{$VWM0^Iqfk#~lDM8%eKq@mpcK4VFCdC>X0KyEg}c>mYp1BFe^ z56+f`mSIV^iIz=t+p1D3YA#N$R?gPZ%!InyVLNYkb5mDK=S01BUt%=S(cCTCO!aQl zYIaL9=veeE#5ZW@`NMbh_q=7r5&hJjo3H-`eSsr)odLH;fSu{gdZq3hU`8!BCxg%J z90T9*Qf5ig)iF<rR&?x3E8BWw00lQ&p<anC-CB{x_f+H2bUvg15?F`J2YF+j13o35 zdDJ7v7+S5O$tk_0Fw=IpYYbHg#**&PtP{z1rN<s<!!uY4#gTjviVzft=rYv6p0tD3 zK`w&GM0!w|gjYsUmGO=aTF$;=@-!sC*{=`fxHm>I4^yzNX_Amfd*&vBaYqqUGibmo zC{pN}E6^mBWqLU);J8>FjbN=XSzE0|C6$GhfB#FAEY1-2s=$W84Jgqz_nHh}2Iq<7 zd<PzY_$Yul7%$eSwu&WKMK`G;jCg!jR;MajK0`Pz`d9~_5eIAy)3(@8VhUjlS~%Bu zlz+3HB20<!n;-E-)yF(mgz5sxgEg@D)vnae!MgV1P(~%n%BLcPplse8<?G?mq)XZS zhKfd5G@`(RkhW(Ms?3bP*EcJ#!K<fm;Fyw;^LtBP)Nj@-1wKBGDQTqOzmmuoFYNO% z3{fP%f$gtI%_mHwt0>b$ym_rzcIzBw0ih5#k$>ByvXIrB1)fktR@@l`?Y}a_GFn-Q zke2(OnnTxV|Nl-{lB&JMb^jbwyjKQ<HYh<MhkAx83I&HfZ!X&A@=Er7l(KLK`CZYS zlH@ZPLp><PjEajUJ$iAoSs(z%s}daH@U^_-aUs8h1Rt^Hc%GbWBap2le}~lkA;IrJ z-@FlpZQqpEamg%nTO%@9>Y|{uDMPJh%fkbUlZ=kNZOEQYFVIVA=a{V;p_kcGO}zl` zD4|u44K^-`T)<V}b2lZ{1uI67ZR;_zXC`=8c9a*LP?|_rD?(+rX-qGD5GlGq)|s+v zDI_O{;RiA58zj1q`!`NsdwFx|_bO-5;r@7DjnDP$@hlnImVr!y@)z1j=F%tB(<-8& z)kJO(3ojkK!>ab7LH&Vwk#LuGoru9JJ|`pNxb5b06)Wjtb^7}0YrFqc)55|d3<loi zKJx+}9Ua}4fts4i4!x*)q_6)e*0(>=7v;XpSB-mea%y^N=10y|wOxy<$pJc$Opb1X zPCi&TIWoKJXpt5?WRf4_>oL-EYdQ1vwY*IyhkbwVa(Tb=B(QToN{&3k%#hW4k~4NT zw$;5AqFQ=p=59VM^yC#i_3wrI)fOE(J=XjZylKqNKe+n!7z^Jz*C<mHziJ8*5^Mo| zre0n}J6BC5XHf^(?lUaMF9?2OEbk7|NI2ixUBaSX0p25CEeG9%?qNUs;FMv@+a2!G zc;^4Kcx2k5G!!PX2a!?$SM!qvLBm?DlfcqRXgGKnTtgW9NMw8mBMFF!iShBtsS@U9 zQ#&q1aGJE%SvvlVRgQ9()VnE#L%}qx1P)5-1CAS_O)4-^utiCgL+j(&R^9{Io+Vj2 z@o5@5l)+GBO)0fTy786&{9?3RK$sA2Qw48;Fa_?yb#0BBSyp9;q4PEjtr$Vl9&HGX zvxITWR7fTO^H!ptvWimzu#E#f3g1wrqnx>|ybRQ`x?r@oXmb^`9JvU%zbt^0m|W6P zDp}b4z_-aw(iqUVOG*SXRwT2)(p+u)F&!VB9>JkJ3L46>$J?GcOL>NQLE1$*{cXFZ zcoa1@vR$;j7;51IjIF0xIH`(mv2qSsSZZl;4ca};-2zzb45lRS$7pCn+IDzVJ%iR2 zQY93()KqE--Mj$0eh%U0ClXzKV)kxU_eZ3|nXJZx;?31n!vop&hK7RRhNdRh@6YFh z#}cmYvviA`*9D=^g};CQ9vzw4TK>&0b<J6N?67nV6lNFJ@A9(o^(DkLsqmb`t}`mB zZRU7S(G%Lg==9k*$WA!=ODSJMU1|<&uUni*N?l%6c7B!5Um}#0lr$L`M+vV0d+i74 z=#gRz|HWFLyG{gz9>jzmP7C9JD>VNN5`nPR!{LLhhJkt$e_dN1pbU0;YARd6=c(uY z+Qb#esP|mRB+AIi84kI6Tb@R`)3o?yZH{MfN$j~B7=_K8$XT751+09YC)0nJ9}}}G zj2(yU259xbgLq?$qgPZsPXDj1<h@io<UGLHkwjoZl1{WbKz@PrtBe^RCS7bao}Hzt z%o-RHC^R*%S3zeIfEq5+gho=onV%H_qogwF%K_jyC<Q&(p(vZdRQ=EmvLy5JhJetj zP+uZggRYQ_NM)0nKG`$e$-qFDyBSwjw^ZIY%)9*gTTaFL7<EyiZ!Vz+#7uTFLfMk$ z;<SxKnJ!4UkZ6t`j}6aMRvWdbR5pI}586N!W-%R!<|$npI~#mmD%6jGafFzz&7!DL z14Cq-k=tYw7zu(gIx9E~i0)%tHFYiOha$Rs7{xwOF<4zKX?67=5L6I>aS+7fwWciW zrgNHjmY+0C{%wwHS8BbT37xXa258Db9fn`UGa_R2K@7#F;`3$Nvn9|3Zi}w=1raZ9 zqrkUA*)x>(rHOJv8ibEob3_`JvU(laoMp|f#`7~su6A0X+8>BZY4yB*6&7%y*gV#? z$Qq_inr7G2%K=J#W=>df-M;&nfRc??#hbU<A3atgu|s9m8~0vDy=*<S2KiICB1yix z0@9AK*=;7?j+dZ97BfRihxDLp)1fy<t`3Pn{n>+&T>U<=hV}v_thhjHe>ITuY*biO zZKH248%<E-g0%qlOayqOgV12W!>RI1Si-%QjiX9_`4vFC2jINZEgqUFJVARb*RFR* zZ?p2~I;b2Mk*I&<P4(ne^MIj=l#M@%hz8z`&_l-%T$pXV($w-M2+MGObX6TUhK}@0 zn*X+oxg2t;DkKT0;+}Qi8f4Joo>#Ue0uJTVW(vgP^8P~Yfz2yp0_cd(icwDoHSr{^ z->xqhM;Y#t1b=sp5Io|WlO7&SLGHt-_X}Kx$d2VF&9?Ymq6cQejDThPy4@Y*Sa9&q ze|#SDGCh7A`1HzfA7|0A>A_Su2PW(tzof}1Gv`$>omNydJ@0v9+uHGdT{ZKwk>>Jw z#C~r3KI^vucWhTN8+|s3rE}r`4&uDeq#F3W=0rU=%o+MjPUAM(tklj-G1l>!m5zg~ z@!y?FIGT3Zii@3HI4*I3u7wjJ5Jn@!UOFAD9^5+H_-uSBdfhJHy@*@v8e00AxLMew z7ILw(4@{Z4`$_hD6_A7Jc<`@A0UQ4GwcStaKx#qE#Y*kXTbK!LeaM;C?}#(n2V{On zp^dHH+upZKSL@&_S0Kwm9mNhf%pE%R@wD-s*tzKn$@!fQ7uwR*B`@Wjk0cP65ET^# zQ4|6H<K5Mr)l|Ym@CSMlH<*v3y}BpscD0?)-pj;{0o6dZi9h(HP=-{#87sRdcW+D? z$EuJtw%}nw@~zx#19*orEp~o#q~KC#zkp0E7~DRMT7^#>8@;kk1$+MTrhLK@<nJta z6710<g7m<{u4wM9B~uXVDY-M$qQDA`#F<j0-?9%xh4AUcvRHEmI+!AOWj4-tV!Qol z^P0nJ2ZFW^8+_~#Ckb6JqUsIrxHy#<`55OwQ8Y+*5?p1#wNYEd8q6~3_$h`6NmzXa z>8`{X5E7}Jp@XR1oht?qbE~>2GJmd4jX{ZAQx%q*s6<ex2HImB^JPTZpg`H6!?Vod z#Z(38U+KaRfznmdF6U>#2scpzQ(<LQayz?`tB$E0liVVEIG>83B3~qghrgx5-*2`4 z^4@{nvaq61?Ipm-UwqgUZEWr1;eSF+b7-z5dc+_GAgjsFQgA6mJ<i!dH@6lXuK}3g z^5|fjo(N9CtiZLbd!G2Ew*%#L*>UhwA`mV0Un0s9r=x4B_`F8!V_{w_9O+>enIR}s z6Pkf}Wc-K-ZgJs-zIOca0ps=jzfn^9u^4dzbtO2+=s@vb!?gLaRG|6)?1~uoIDP4p zeYZJ|61peuq}TUHyJ7ZKG6$C*=bP3R9PHyWNlz&3S_R81-l@Vu@tMGk?0l3zv-Rw0 z@7_b4;}OkRG4p>m3tPBWaCcwLMXA-6*@$NfUctPVa70tz;JRtCqykq)ax1fp-m_@M zsskvYC4N$v#sfu*l;!y8d-_REcHC-jCu;WuHu;}Zlb||lsXecVE&i9(TO$Jn7NsN8 zSf4M4zn7tohK3+A66TPg)FRf-ikQ7xMq|H2e!vBzvX*pj5pr%Oz5DPBZx}eO-%vn7 zuh}+?T)SQ>-04!S0%Buh5#kUWUZVyN$?IBEX~M#0a(I65@yYc9Crqnr+k(KM@>-+C z+V%C-C7Ok`cLvOmuBN8vzkFz*74-K(e6QmKrnP~RzD8p5)%qhIv(e-F*vAKd>@6AG z;7Il@(`4@UPGcPF`u27KP>_u~UR?Yac)HWK*zW5(ZJ4oNVbUNvb-#ft-=pStvADph zkb)+0+_3KK;!c{2s{|rb%jf%TkKQf6bTL6}EG=CllNfoRj3yl~W42J-yn!3X@|;Fm zSbY~p=ED0(OlrOiv%7*6L$iwRb+!!Rk!&%8JahXuxwC%3N)`~L9_UnNEr`3FbgWU` zAVnGsmO(Q}IX(;RwZu<|Ul*LnX0-({tC`G?qHuc#Bbp(BP7cs-r_3EZ$}yLejfcXP zeGtVn?AAKHu3{m{NJ>OCg#ySTSBc4r=Chtus0UqAo`5k$LIJ$%T+>8Bnw=$t%X^%C zlOWSnu*}h7DT<FGto(|Q85HGcjspR{v__jeM#*uaN5vr(vh09Rs3M9gh=(L=unHcT z4d@Pa5|pWB5w~nBc;{6!E@02HY3+xW%y~&&>j%M<g)-2((gzsGw_r3(%m`mbxf`3I zy{os+`cHj%UQ}a)VyZP;;t&iA_z*?~K1Cxx47k`$6V#^nUUy=&DGw=)P%eZfL4*HX zK3l#QYCtF`3Mk^Q{*YKDIW-lL;pn0eZ;tuZ72l+ouYye{VVU<YWS~110YY5@zDUiA zVAZ><L~(0uyXIaI(=ohU>BlA1lp)R$tY{x_sj^Isah7+4%HuGgrP^Pj63AW+&N)m> zRi-cq(9(P=VN_&TSF1G^t?*D?ky|h)J~U5ykcNF7I`)><4igIq-Jm2f943T&;73@M zW`5uIL*<MiXdMgY=q!T;bQjd1+P(c*2WCI9TTX0(s3v-j+1Rp<Rjb*K^BlRAE9k)c z49mPnq(IG^WTzpYQY!#}+g@o!g(?)E3YRkH*|qihbkp9EX?H6tD-+-BTi4-LnRT1| z%*;$%^j6NQ&7G}G9DIWvQxn@->4WJYBOjTcUy*m5$kCiYMuKkZW1&TkUdk45t(5ZW z4H%O!wU{tp?Y#)Mqe!teuXbk{t+_IEvB8hK{f~F&<h--Jrp4`M?QR|`GATc`>GB1( zant;`q{2Bh7;HmNzwqae?aI!_F&D6>6}wgC+gZyxZfs#8+qWgax$DEX!51uc*(4<c zgLvU%>}+lC7iet}y-hVTOr6%U)cknCWxw6#?rXE)eke}|ZS3M=VrLiA-tKuz_AVZ? zNR^`3;@}eRf1T?$d-AR*qjXh%oUaZ?OUm^}kXZyO&$_8$R}=cw?JL;UH87lVpV_69 z@uI$OqLZTxO`%L(HsNAp6cOW33|v?$zgRGeISgJ9dlLW?5X6A50$k-zqf;;aolF83 zEP1ElMa!jL485k@5s^=~nyxNDDr17Ag%>kg61yC1nn|S;`l1W-a6zWfHt9V?il|-R z&latMRUUL{1vw^KogxxqdrlEnNW)NG(xzp~G3TK2$ioQ?X8vQh!*Her-Wg5D3uP6T zF3in9-Z!WL!zUu`Q~L*4Z~?>bcnLgHNoz;bT=aIzC@OqZ69#3Q?;?BP>V2nVmDi!S zM>`ebWY}>z<>DdL4ro!4P0=x4j6y4`el8FBQl&iL2vKajA;L6aj{N&@0iqhOGrpdW zBObWAZ%$n+S$0Yz3rnU4X@9Xyj8cjsdr6orSz!)a<h_pI|2_ubrI-Q6C7AGx0{H%{ z;fSv?01=G;{e1Sd2OiSSku3>5v27C?B?#hN$V-(-U8Y$P(m}oNKD_FGZCxkn@ah+% zIBE*Z)E54&GFw2L3J1Fbkks)Xq@rCCP6e`mp81DfCS*e9l9g>@=f3bLjQ3ChIl<bF zqN3uRW>jKgvg0Q(Qk2Rp^bGW_zpt<8d!H2pH(77l|B5jWdkbJm1<5PPyMJ{0JLRUO z?XH0c=!n>|3#oayw{UU+krhAJ=xeI05gOhX>FeGA`RC1&s%kW1!ZNZD&;kw%*j9#p zOoTfNrAq!g&%Qg){@>3+ccbLM9u%<gv>1#m$Soky-OwN^cqs>b{<O{jF#>L_Q>aRz zMUY=)Y~Mr(NL7vXHTwOEF-Ur<4K6*vkV3eaysZY;GVsC>PwtV9FxqZ&3ho)TaCcu8 z(ptZxz`%oC6uu_#flTv<!7HA15C<kW%hk{-La{He-cJ&Nij$;hEV<BXu|#|pievf= zc7=v=@>F3F;j!={=kW9<%=uDT#11BH%=C~-Izu2ZXBe&6P~3~-SXRBPvkVi_h_)Pz zFSbA(N{zBIf_)Ot=RK?4{IF~n%q+*B$&e}^M4($b#Yt0ph-wk8{MvCgnWf=KZ3``p zON&gd?oat!fn!CIC=~ZNNc<oPL^@=eOrNkJNR?81FhWrrowWO(!AB}H7;8Xf%s4Cb z2qHS0*cd6yY#D{pTBUelqNP_e&Be<Q4)-{e7Ih&4#i1`p5O#GQx31)vs!5@`$Q^)& zBtu!29L{&tP{54B4l>29Sh%)7h&}OsmuG7In%^a(S>RG<x^N(;f<%cCBu~2sZ1a<L z7U!RTg=tz3wGj%~mJCg}6~-#CypUeEy)E@F7Ku0OM~!$Azm22N^7zked$dVDb5Nj6 zR!;D!BLz!>VTL?8mEeFhUSLZeYWtJez*Efyd#t@AfqW$M+#a?ZP^jsk+=g9-siy7- z6Z5-bym#nC3N~+X1BO)2%CQ$<oR_Q7agd9HKq^B7?7q=k*_6+eS}qV{YshcA`2^{$ z3coc@o{*M~8i0~6*(_!jo$Zk^l#y%6$yI7Yp?D`WA#st*PBRc0g8cYZEWf<v^dh95 zHIU~Ydr=%qvP6H5H&-HbP2aZ^0W4@8VOnssf$)+T=|{L6$bW1jbg>l#V6+l1Z;$z) zxZ#^~HN@;4AWiE+enV>u>%_Ya<xbGDEnISPtw>Nvp;D{#NWk@r>Z%%s?Jl>+adr1x z(_u~z7ZVqAZ*vQuQlPUCkI0x$PMRv1_|1^;cJK$-c(=ei8QG_$?;Nd>-ANQ~3-tTf zTWv8X5E)>SYcL4~#0gVVQC|k<Dg0pPWUYY~b)NNcSX0{Z*#moZu(zFM=dt$>;p5_Z z?gLN7G6yD-hjFQN_T_+#zO9|ltwO>L9w2HQA?v^aEw1^?y3IHIq0F}r6LnP&e7Fg~ zVIpKhqtdWu?$O=R)X>o}o|8^^BY-{KC^j6KEudpC`Rfudz8d8vJ@>tobIW7$-{B!d zIf>SFvSD%Dq&&fmV6qp7t)|fNjkH)L!X?y2tLBf&Sr(K5dA#(ceiE73kh1WK42Y;e zwj>D~LdrjMYtqf)C{^H6DJ{pFITiRNw-t1_qA9G>qjG`K4&n>UBp9HJcu%JjT6Ti| z3(la8W1FNEK(Fa)2OB$C5+rb9wUGmlVs&v!0uCmk`Nm4t2e5L{rVD~}wk#e}f$~Cc z(3W7j;0EJ#R#AtAu%sA;az<Q4q=@G!1_W7R-W4o@m=UlQ3tO!uF>p&0i|UKcsR$zp zc5?EX<NH`GX4^ub=E)_a-iJmrhk={a7~_Efd#l=dzTrG8oKJxjIMUO%Ph#(ND$O83 z1^3>VCF%N#MPrN9$Ag1RrSEgFw(_b@<n;2gM#rC59>6a|fNg*oLm(S5p^4NQr#@+| zu4Q9f`v099?VF$ZfbMyc(T1Yp9ZsLB!g40y$a%i)ZdqDqiBDV%OXkSY7AWA{_EF&! zRVBPwgv7-#BR2}Dt$}sFGldpt1wC2|52=){kWHt%W^yG|R)vZ8V7y!AwXWCzT8Pz; z3}S`-P+Ut`tTQI*=wE-1xk@mxR1UsSLupA&cFcw&Qv?=AU)<9gf58J>Vt{l9OmrwT zl2m-B6>?i~!LlsJIAt%b(wZAPWcG-7`0jW#z?KYMu7#}Lyqo&-!o@#GB3$AQ(;mZm zUG)3BiicTFAy7`bkR&&N%T(TfMN?-z=rk^YwO%XfAxbDMSTo!Tm+pRaiO?&AO?iG@ zq6@ewp$7u@tV%|mg+Z8HGQPmOyw9dtYe(zzyd3k~xMac<QK#SogpqZN`(<_SsIc%a zFSLVp8yA-!#uelaLYfAxaarqIl*dfGd_*n5+&F}Ue=zyZ6M!>s&k@0E8^_bWmSs-U z{d)=p`401o35{P)PEICUf}s^Zcq4N*6>|kS_<{0QA^*LB5Mbxa!`vQ=^8Nglb|X76 ztovxav3bzq8{Nfqh<GlUb0G-yw)FD8>}rp=8+p1%<qX&+WA6D!Htg*cO=>9o%x?E` zV*akNv%M7~kiVPzaXALefqc_os;Eyu?vXzRnwP<T_?}zQmdT7nSi|flpj#I#va`}9 z8EKKc_krUGZs;jQDnH<e>ipVQ9&ZR&Mh<~egKQp`SI0f1@xu|v{Uo!50#W!-0P6u5 zlPI$}fTdFru)5x(WjOXzEmdv;iea0_B|ZVNxC;3{k=!h00cOl)&UiyS!YIaQzxhoN zm17W0qAP+jevMi&pqSgej_T8Bd(sBAYW^9<<eU#qYBytIA%pm3GH|b=35|Iwk}nLU z7V@hY!IbJfsKZH^CXab5G+|8Phrx+s))q=Gd^}o9*QZNSd!$o)Q8Gj%;I*vjqXKmJ zQ4uH$Do_VolYM#;1Mboxh)s9e7yZ;hxBF~4ue|Tht1G25h8kja>jnF$kNd)tg=h|X zV4W<o>+OL>fXkoKzbE#zB?oQ+a_UT$>sz6iu2FYiEomp&rHLU9Cv(wS$TrPylK%G$ z4~r6=cQ1rMiFEF(`G!Fh$|CUMfc%H47x$-NNjWFUse$Fks|fQZYrHaaCP}&Vg_Iu2 zkehHBM{2O78A`QLAydKn*7(_IHs$dY18sWO_$JRU8YO*wPSpoLfTyuuzmG@%o?N0% zr171LH#>)D6NTF#p@f2$7e(5mRk@d?n3K4miQBoiRczDD6wO%(TBHlbLwpk^>u<|Q zwPILbn83_5z-{r^1dP6;u1|(|#m_~K0)?Fx(5F?z-FSwMIrKc!qpHLaF&-?-u3e%q zM}fuUDN`Y9qhNry<Ih3<j52NHG2bY(Q<!~HWfG-#3&z{UA*2)w7WTp?kH%o;9!vb* z?yGEIq<dOk>BiRXAoN?`P2i^oj4scb`}NgLkx&ZWvGre&XAcjLRiZZ!gaZ@e8ao{W zf?v?A?EH~))7M|i*GN8*{iyG9TT|JLM0=|Y_m-nME|#XNiYMScofplOKhs+yoZbQI zY$C_E4mLi2)`+hVas@nq6GczpXx-wa{?^Hxl%CBr%-V%FNgt#2yV{xi=aA82fItsI z`b*L1mxfZ}b5`fcf74AM$sSk(*6MoMd3oU?KeQ=pG}?@4qrWfwua6|_%WmMf?p$k? zq*BLRA1q~Do(W*R+8|P{@z2l-K*N(m096tSV||{B!FqvFF!H7Ho0ov`8}YY(&`kzt z#W~*Qa=b`@*^OzUKVtJZtH%ljx%lB`57Lu!0^(CZAv;MU$pF}r=^~NPe;7dy_H?>J za^O^R!RPbd0Q+py5*(il1r9@27S<Qg_J?Od0?axl@Bt@58DesO9UCY)Q&x}F3?il! zixtt7ML`7>F?YK=lZdspu2H^;Kj%1vcOFT+Pm01;@M?;`(1UqI`<)12avNcRUk?I5 z<4DZd`NvYc>33<rxYKDUI?R1}@#E=d^dG|V0*T2RlDk6YJ;gSkAId`VPRakt56Dv; zFCAcX5!-IZ*gnr2y&>+np~cQlHWUy}M$`KfD|PK_&(t4l3KZ|}+(?M65blS3ejavV zxbdt&&^#&!_FVzuASlM{k{U)^SVgC|TKvTlEObVJKukPdT6Rpf!b2L*gZhZryY}R) zR3P!9rMbBn8aWAO+|<l0q?#G_UlJc5UzFqHTXU`8H%C&d{g(IM1@qVI&z_HcuCKfG zDSVqu{P(Bv>iplBpn>cUT=ljFUWz5jW+kafYjv?PYprJusm|B}YwO$AmZN?iENqq= z^gtjtAcAF|xdJ^58d>8E=uInEEv*yseS7#QhXgJG4pZSD-<F>NW!qC5o$ugc<UY{B z7Bjh-IoUuf&Jn7w>EhQwdVpzJ?EoG@9i5R(Xq~Ib*J=5Dh_m?){IMY0z@Kk{=gkFN zVtm4jXoct<pPdlmmww`pneBUz-kbNHxP*N+RwDxpe$JeN*DB85NEiJ7xY~y3`_g9Q z<#v^>2mur{kHXRV=FxD)4DY{T_TUpme25^DNyWiX6i}Q%d>j5DVB%WJYJUrGQKlF% z;NoYXoJ#vT=|bj%1lF7M-5!jpsGCBLK;p};35#Q~s~A^VBOjJ|At{UwsjQ5iqXyQ! zwt+n`@SW8^utc=HtWE$DLJ%A9N*-LHBWqzvaS_<%l16b1BZSexWaFa&M&wA?V6-l? z)a9YaT2R1=ojgVuTb}GXj<^S#hN@bKE>6+|7;^>+`!AkjGlFMH24i525s*Ox)^MDT z6{LDJ5D2QCM|+uW0k0<Zx=3n5U+E-4Qys<&REZ~%#zU!!$k@LW<jW4|3Qtw~SSF=~ zun7;UYlxbXvDXLfx_c6ME3DhE4@dn7G4^I8Y-qWFmE(D6pXJR>7Rj~DF{uM+_a^Ix zX$1cI9A>2bJMdwfNGJKhul{SisJcU$Ig+YO7Pp#?L(VOnmN^^-Wu%pcRT##U7>Jo0 zN}w9&wevpSDIJN2lAHA;_e^@dWxJqrZu?K`ajZ%M4dJaK1$2dLJh5Tf-9}IzsMU7B z#8i;FoWb&p7gPiUdC34$gjkSuQE1vT&OA~_b(z-hMudY}@f$=e7q~<PWzJKLx2?k* z>VSUWq?$kF`h;57%t;A4Ov>Ye%yx8iMHpgB{2*_pb6@<yNll7FagTWwvb)Emq&#i# zzePlFfJ(QGWq<rl*FTF8TA-|yd2?<hidnsMV!Izxj}owWqkE3pKt3n&ERAUGWu|2& z@!zV#cQ=z`6lWN_`!y_s-es%s1!sY|Gv!u?nVlSJH;C%<pW5RsUN}TeC+cexY2>ke ze<`#untn~lP-rylB-hDWHs1(-f?vu+KcHyhC&@N5Dpqdy;EqxanYPXy5MxUX#K!%% z)9v^vZe@V|(Fcw!_#bn7OUezX12rK?SVKAQOmZ|jf1ogTu{@c;;WM(MU1LInV@6nI znb5OZfE$&Ym;h$6eSwt7@PEf#z3C%2Kw*4L^$ie21!HN^4{8%k9>i?2a}&LG3mN2C z<AuQPv+%>^0>2W7hkBZSaI~=WH1rtxg3A!;NcTNYc84AZExs$QuqsL>kPKraQvg1D zfN((P`{SvrDTP=vRDG`_ol1HjBma*Hc_A=yyBe+J`qlgWrG&GR{YS%JP^1WEeudPH z#KBZH6#B4e`73{f;xVwJbA$b9pedeicDxUlA&7l!0M=j%*?e?$m+73z?!jRVCS9D3 zglFZUWQq-O5F55g_Q}Ywf(%7uyubzmW~Xj3dJM`mh3;w;KAeQ2^jI)l|BlFoM{0by zgq*g^)v?%=lY7N=PfY3SbZH3VRX!6`+F*o?NWy-(H0mGGWu%g~DH$TAx`UFXI4e`k zfX@7YGWu`*JSo-E5vQTz7*iDy0$A$`{7rRs6xjJJhN`FVD%@#k%~7B=kueE!ZhfOF zrjz~r>sBbdp%cx<&34i+gh5mL?;8Y_@>1{mP(DJwKf8mQYYdn%Tczbk#V_ODd?B8; zqC+8${Ud{KBL>jmNVGxYry>MWW&^Is8cN|Jyo}z&&0%jp@B)*h)EyDW`Xh+BLNF5L zt9oX`fWE+}5%7w(vd3D^Xm**&jjyk#>+9pEr}MYB`SJ1U;$j;v`#SJnXT_;BK+AEP z*A$S|3zW?A*nYRovvqeIp3lwM>$hwy_AHv`yyyn5X@b351l0{5YObyj+u1o(Rokd4 zR3f3o{`vFATRq(*e^iWo5SX^^eD`@$JPQm)1Z)ERJ$ShITniCnXVW<NfcM|KB0kZC z=Ff6GN%}@aO+V9opQAvH$`zHA7T^V-#!&)osY^>GM|iVu>t9vjkp*9NH@2TzTDu;r z9lT#iGk~3*k?CI{V_Nzd8O<v*sRG~VMxM5l`c7mfbSgoBRLRr2{8SVLH5E2b_4mW? zneASVwPdrfb{sTV5@umgy)8Y3c{B+vCs)s8hQF}AG?!9gN7y>dNV$V1tiNEtA)@Yt zxZha4pQEOuf>C*saL~#HF__WTu-&;TJ1gNlOvyltdU<-=C1V9nwCSIx<?||N{bGnX zj@zbKPdYA}<0Is$F+=lRr%WkT3+VN-5wL2R^u$GZ^srdwSun@~-B>R*^uRNNs&FA) zpB4UTLqIx=m9sw!yC|_=1aPPr14_%LL&Yd+VBnit`>9mcNHrrHwL(DZz+S2bmE~m0 zEJY&LV!~M5lbT>%k{exV&)4PyqsnbmLs-Z%X{RvVGEAKFf6GyZ*4RKsEgDOZ)^Bp2 z8$cTx(d0OA6hfqaR!|!W*0u~qBpLcvgdlYU)P)0oQ_QqSp_)n*VGpX{@H{xU9CIO_ zhE)Q6A?$)4^Eix{HnHr_;*Iv(BT4CXrr2-N_jZW140IZ;3aBO^pSg@5C{-lOnA}mr z@t41D?TAtt$n$u8n!=LK&v38k`{^f_VR;%%J@ja7F^KE=L9?>5{?P<%Rrk?*K^vzU zHo2y8%x}6xgUa1%x5kCB;usS*KvdDuCpn`#EbQRr!SLq7k7B7Q{oo`R^JToGv<ULc z;A9;hP1H*(w92e1x`a?aM}tR5#--NIoqlMDmTlDFzRJ+BLS0a2nBtnNN;a>M1gw(; z(hf+PnT|D^=4L;PC)s7#8w8;JJPK#ct8wD5<t1As)mG)KkIB=5b@<-GI%l{0qk9jy z%W=K5Hqh=j{`lJ)wqr<}(~6^e6lnhDP5TT=gmhmhTGFMyWW8HYC4q3dx^YY2hpKQC zZ^KZ#vY945G2ay>U#d>gVU58l8`3HwScEfRk^719c{GuV^Xbe)Y;@R=D-9N}2BLfU zLw!OBib)7GDu$8N!r}<~`wlS4-^EsVxzq0Jck!Y3n!o7qJYLJR?(_Arwtb~z@cuIQ zTJ6DX&{Y(*Qma(2RDJ7D%*T`DK;!J`sqD|H`Z^`wVk9J<_Y&KOqNt?ksptRpP%f7z z_9i4CaO9hVQ|G1Z?;;5f-2LRw9}FHW94riGd+uzNdX5wFehGitnH7GeIyXV;8@pKe zKKZ@~^@G9M81O$`6)0Bem$o1UAFxbaTIa%Qh?k>&<Hbn80T@V3pmCJ<T`J%MGMbJ5 z0CAclhGd8(lrZFB>Cd1H?N#&b;VOXyc@mIos5Qdx(u*@@BDLI;l0kp-<?u-<jf;}> zEkmW1Fe@S?N3||7*%+XN-LUFTNO8(_^VO=#Y;=P_c&qlR5wG$jnr5ERhY1Q@uPzqT zx%xDfYMkBM<rYO!Gt^E)byTAGAjLaUa4N)cObJiNd$or2`Rx2BGT-|tPa#a<`vc}5 z<0K;VQUN|1yj7f{qETfSav==~1(fK+S~qTahI(54d&R0a;HRm*AWH9N=Zhi&6w&Xs zgtO!V3?i#y=EWvWCR%X%MlFh?36y-)jERkNy@oXw_MJTyy}~uW>o<y(C7n%&KMCeC z-OfS-m*+Y$kc%HgKWNU-+L01KFYL4_!8SW=e;X^gnB9HJDP&ujk1@%;_a-*b%cK6L zjIB)pkwcp3xXqJTZ7WgN9y%7}+7WNm$e>j@*-TR-G(X^LiD*ZnUn;zs^vsc7p&raj z$70zfvnAcGhR;a;_q1b|uD1v`nT%|3+8#Dp^Hhw<Fnsd@_Di2Xq(F&9mp8Uc1@{Ir zgc5*os>Q;Lx`(C9fUo-m#*n(AWz1V0sf}C%|J*H;Jwq#4y%{#5)Z_W}@v7u^_h%%I z7{8BteJ~996@xqx1S7^ybEB0ckNaUv!Fq4_>XVJUw&b_U@0CRhrQG)hJCN-+zUXU} zi1uF>dykm#yjo3ge$!}^MKuEtg@a<cJdg#fr1Bv{2Zis_#>zzeFQ>cz0#+Pz&i!t& zzp-j>f9d*OocMq3Ng?O*`@emx-3J#I?z~lhXST1Het$W=dW;!bJgDjWUkK%yg|qT% zh;*pIl6%LjV*w~!uj1VtGkHy>Xm;(^%|TX)=HbSR1q&5V#lcP>#QJLH4#w+iy(l%U zpZ<D*OtF3{L`XJ@qJ}N)%nAloKB;RMIbnq1(jW3lLYYLyqnQy##>L?pv+q|EHV2ht z9<dArs78?v<LRu&*YvcHYgyOBm*qu|6NW;D(&C0ry3YyDORzPM!<p^FrcP=d8pP$B zu!m;YC%D%SJk4q_X)<8OXtS;UHA325gv3~{8)%z324fwyMcubhWg#OB?UsfHM_m?C z8s(Qr!i*s_GJtDCa{C*?>mO|7g4`6oK32@!XILb@R+jhB5n!($6Nsgk7(-gz1}*t6 z`wy<sO*FPjUZpnEnbWzm$N&4QP%2LF>*WBOS>F(smGTCFlgi>$)P8~kp0eK@yIt%_ zQw&{84I)dezRW6*qfDn*s@x`pYX!GU*BaIFXN}1-lT&44lD*LsJJxoAQ%hzIHYIE_ zHTiD-tw=m2QY%lT%K(zmxPw^sUV+`FIK5&{s{!I1AJzyWRAIw(%+I8VXt|uxAj^=j zrWlcv)fX0=X#i`#+#rhM|31_)pB{7yNhaBA(#A?(E6Au@z8;XB8lhs`znx5QV#N67 zd#KQ7DoleNhslqC8rluix&J;^hN@Jg14m`?0k)u4tIQW0vnh@(Qf~1MH%*)#KIWal zkH6RkUEYt8c0=L(6++^X&oY8@;UZG?19N+<%Xc+i&-$-`n;ape4*s~;c%U?JJBRb4 zmL4sdnwnai^?q*-6wYCPk(*bLpS#QBI@SMq;u!>hg1c29PTdAVh)|e1_;%qB8$061 zYs4$8G7|E6O}O1O0UZ{_xFhiI`s%g%{@{JYVY{c(!|~<c++gSPb#_*dx#!7s_s+-E z_jY^D*w=`G&tWCc5SuOqx0=d6Th$vrYA?D<QKqQGDqgZJ#9%-`$rR+Fh5!h|f>D@T zgCbLZ7Q2d+L}wTyO9F_lB<IL)>PS{PTvg$0TIo5CpcO-tMK?%oUY{D7gpz7e$kKaP zDb$CCil*1R`Xcp#L>B=#V~|AJXxM=xM_4d6O`6I|vD(Vm(NogdRVZ{Gs+q*2c|XY- zI5xvE{qNN+Q(<O8`I|o0MUDp3R9zMw5{CVU^K5$Th_t+8Jwti@*t)b5yC+*5)9ySU zn>4hsOQhh<F-;Bzt#pYS#YMyoO^#?nC@7FO;Fs!gPE8DVB9ldzK!mmlYFzibUJUy; z(Gx@CJnMQr17t0W4)x(^;?_kyQDDOlge_>nvjmYCMx%46s1!U7vDiuOiSXNVNm(w0 zCVOIJ6P8(IfX}F?lfGzFl`R6@u%rG`HDl$p&K0<QEQYQ^CXR{e7}Kj?;(y<%(8xyK ze*Bl5&L4V3aE5cO$lKXr%$uJgQDqVtoD4-;^i%9}3XuapBE5(A?drx71+06hJKo%! zV$3thyCj1KF{9hVb)}u6g3KwqK0S0&p6te^bvqh<Z;F}!e4mHII`H@fdVB;avoY8H zQx?IeV#_*;H9dqg)w$h>qgb)NZPM@&5~qv=hY)YJ-n2F+Xvug|&hQh2d50->QT_35 z$#B~*K{E%KxO_dy{jaz2^768~+qXjsv0W1W42el23RlYrEP<tiCJq-Qaa94^$!FKw zJiAA6o?VL%lz)HXZ^L;7Q>Gd77cU#MtDSSxYK}uyF+*jg5F4on0skW(2?U-B(HIz1 z1&D&F*{PleF)Gi`H^5_YcMvD!_wtXl_TT1@-q&iSo~Kir8~g0<+^@LrB3Bo?r_WC{ zP%6w!7ftfaf(c2|0rz5h`s{>#(oQX$NJQy-^^Ed?c$Pg7oY_En=t9r3@pkpOzlk<4 z5)MJvPBBKq)*7QY5#8jv<WMZw-q{uEWz+CYB&p|`Mn!T?DtL4KcKso&(0Nh?VwlnE zHfk3Yyzm`lR5;{({Lkx#HKJ1KJ_YGi8E&W6geGM30=V_I)atrm5m|aUDS8UzTlXyP zn%2KP^-u#SqkmYQc%o_{Qg+ltF?Dk-z@4SFr#hi6mMxpo>}uqZ*u-#hz**J?+IYHJ zd@=M9X%p+opkidGsJQ=jTF#`E@W|&>HxhQDDgzAibL4%ryIr($83cTX?Lnr+(Nlzl znCwwYW#<RVo!ybz>mrGv>fy#{nVXrq8firs82@+o+g)BKeix1Nc|9!$FMe4eL`sgb zHfmZFwR6?q;nZR5^zrE>erZM2Hv80aVa;+tCACn&;t%q6`tN@vbXY*b4PQm!&?v~C zw0lokw$0$0gg?zdDs~I6D6uT};=OMw89%KXCFm;fqx{?m)orUiRse|+%?1_(;#;jH zh>)4h^YSj-R-4a3mcvFP-cuKiu0jSuGpP;Jfn9KnfIrJD$7If=ls7``7no(f`sf*2 zyt%2~I@eyUFZXYvI5usXlcM}H(4!4z=u4|TIXq&YIaXLOcsLEKI8O{UHbhJ-C5uCU zIfFv54T-xi$8F$z&yK+-(D!J?JH!M#-J(=c{yph=={-EArOlix4SU}m!sZ$ey%ZaQ z#RF-z?iX7d0@JD9#Eff4*pSHve=mALkJGa=UAvW3bIZM|kGdah{lBlju09Jkdj@SD zUpsZWIBt@ePgL8w-v3>XchU$XO@7`vMBHo^Pe1ssJn9ryD$XF(C+~N)5fN|odfe<@ zXZv)e6B7{-67Tpsev^Np1SbgbFU_aw6Pcf<MqOanT_`>A@^?s0-+sP3Z096+`Ft<q z&SZI9^MAbT6^0QL3UGhzd=!3H^SLXGx4yttLTV^u)x&{`zwQ3T(#7i)NHXTy*c}9< z=wTN$AyPmS-C6Ma9HoZf#-flc@3A+CVpOR_*`hCd;nobTm~Hie(qRuZVa@GdZZT*p zi&g|gB>a{1VmjL*nh_{kWMm#Z*8l5Ql-^=UslUR&XdI+Y?^chg|8HALH-stFvmPA; zxbsrA@Ytuk?l~|lc^YVlgc7rcHt3W~z7<?qb&oN+#Akdc4J-j7!KboEhm(VDBGyvu z<J-ttRRnC@JCO~H!~{Qx^r8Kqpah5s2sV5DcY3*>Ynud)5KI;}g~R+Q+Y`V~csKz< zaB!3Rip%e}8qa&RYz!6@x^x2-nVe@@Jq~G<N~H(|OVeLVMlJRBVHRUyCYdj}uo_55 zKM8VC+M4hBA!rbO=3Kxi8>NerebW(+$VCKCWG@iH|INNtM<Gw>dJqKuDZ4!w=>qxA z^uKrbdWrjfp%!`_tNdBpHPv8M1kyeN9d;Y%+w-3z=|X2`--V^;ZCvm^eH4W}qO|nL z!oJ(@b2wE9DX({^ZPM>KKFBjy$Ul}M)$aqOm|i!D&cL*0M^S>`5cR!Z?)oIx|5~nd zWQ7QfO1)q4*Q>`U5NGcD^s;tOeF(-|x!Vf_CjIR$^no6MhUoHpKX&-O>b)vjDg7YY zEwLZKQ`0q)#;ZP#dXII6jfLx+0l<n$u|0U^{eag5jk-O*jxr>bd;kMI?Wj6Hk!MAi zoq{ZpTrP{EER(7`b;C-kD?1!TVB(Xir!;4fdb88Q+cge%9rY^!PZ;vS&Fd1Rr;c%_ zby>++d|vFYgj|C(S+xJ&i}AdajsS7=4*+qAD5Wm~)ub4h9mIrNiIC+CN^SCPQH9I4 zmVTJ`{o9Rqg(O2kqDcMD{@2h{OR}4TPmVfb(r{6cwi^{)3_KbmRGyWO*&_xI5DwVw z9t@2cf#1xJN0OT^QtoPlP7|dhOU`mx>S8RKO&0hOU9+kK&U>x6Vnscc(G0#MUdSRI zDp3qkI>BS|iP|u{-^YlLD~U<*9!oICH}JaBq!1qGr4AxsurkGKq~UHQ0u@IrWT$<! zHwgXPOFa5S6&`nxW^@ajw!P%!hb6+#*fGOY&Ya^&UP8H((yN#|+r6&wlgxxfzA=Vu zWFD?YH49q5h~m?-199vHbw2$*9PwY!?-5Z;N02o`F6O%u<?75O`n>vbCylB87_?W* zxCh>IU`SRo295nO*L#Cun@{bHw<MT$__()$kI8)}>9W;&jyQJQMcwmjcOK4xw1$Md zv<(`w$;B5OZ1flJKL);(9Zk<}nDn4zQ&8+462E6q@%Q5mZ$Ch<3|HrSymsmoQ=Ig4 z5DBb3(u%cy6fN|`;-%&|5X#+-ClntXz2drwjy=yHoRqqNiXD&|<lqv?#-rvY?<-;w z1hEEe{~Ft<_wUU5Ieh41`0DL2)2(7~=6Lw@HQ?1*mn$d!OMVfrObC)UG@t#3N)ss- zNkzAu!{vi!r<)epgl7CQ<8K{i2b^5-o%i28fG@b@>yzH=hR!YodKfYh|E}UY*VpjQ zOAPQ|@4Lr$jSyB;)NTJ9DVGsRs!Q7F!rP23t~0#1$3<5c)C%#HI16*P(DxYgJZf&s zkYWC>*PyE{zLAlU%|5w(eOj9kpXX}=p|+XyX&rZVRX@E=iJ2TXiCoSu+mKEpge75e zIHNViHnB^BgYJzZ#pd4L=iuItgxZI&up^Ocw^zT*yQXjd@2PL-{uPU_bG@L5HHD|v zCJhJurfH(~n?@8dtR|=KM-a?-gu%*$25pLcIdjp}p<y1iF;LK9%5$gmd^3B|UkgxG zDRZaZh3bYE{3)7so${%@?94dK8t7M}Rl;ued0R^{%8i4=+IIw73`Oi$vX@CYrLjZV zbdI{_R@Vw;x?Bz>VG<58>v`>^hz`MT{jdoI2_Rvhl1FHvZVYR+AcWJ#-{g!}vdTcl zaT|VsKEAD`mp=>Sd^rzrOW~y+Rlod7*UYLxwdS*_pKW7E7oG2R5*c=?d(!RcTrSMa zyu1N@J7ir#-AF8csykB0qZu)43NNOf45MQ|0px5D1h9e`9+BdHX&sfgmVuWLXi>iX z9BDIlXC2>}*mFJAcFvHW<%Jp9#uGHrpyd}ayTLFeAa&AxOX&)E@0u?)d3njT0chQp z<FZIO_H%H222o@=Hh#_W+=gw2dFo?`&Q6+byak`-aHnm*U&DyLyE~cy`Ux-p!@YeE z`oAFmmt*t)7ffvUaXeyhq8CIv(W&*Gb9m3^b9M6g)<boQ=l`~lE9iCi8=EVr{s;9< z_e@T5ZRZ>0MyJPkFMCeU;l`In_--5isya=ek;hGnLyPg~++qGG9~4#`v-?Rgac|2c z!zl#HaHq#(O0NE^T<?S2&dV?t%feFS!cV^*<+|Tn5K+WsZj7k}$#!{q*vMEB$s>ZH zs01nPrG^7A%YtZ_Lqj0&pu_A753tnv7L*qWL=y3Ijp8+n#(xLq*XOEFBd78`FGHVz zm3_5$J<}}GI${8u)0IIj`_3U@eoVBg@PxrIPO!+q(=6Kjkn{?-oSwK&E!OEVqpxiN zD}^TYAQd~~(#^h0^l38Ng80^Akda-ypEH8xN#2OlNMi9g!=84;S}3nfxuKkq6F2aK zXkJC)rd9qiL1}%7a9yzk)0qBCNG0%*w-aqCZGaqRJFl6(R)#5Yg)PW~Qut>|C!k_x zZWEj+HQ|_urc=x6Ai|u`^7>ga(>$;JL~||X$_Z=QC^@ek+8AKc(B*Uv>flIYl^BLY zQQEy@@6qhl$q-p-n98rVlT%ib7*#2KvX!%zB=<fE`co4l-mQ5kcI}HbWy8{2ad7{U zkMAtTl}w&p&INgO33#thrgZdwS;+BNak+^XxLW2GU;Y)3s$qX_w%XvDE!oV_u(vVB z3ac9ZfkIAPwdY*FYEjxY(8UE4!%^L^Jqh?$fe<i!?SiXE&h`I#&HXyd{o20y-0uBs z{eBYq0<xsKZ+zo^YB4Q9BVPmidvmvQd)>jEAMO6Gng)Jr)c?cNS4OqjHSHn=iaP`^ zP$-n(?k**`2P<xc;_mLWIK`b(oZ#;6uEE_(asTqX>#URC`E{?^v-ey!f3i~j58B*2 zv^#$4b=ZY_bA#K|oCYhsN4<{(4XfEXv^}}oy@$U2J!}6bqxi|ScbNG|_x(<LtSB&u zc4vCIRkI`NivX)9EFt;96h7v;^oND?uh+UeaS5Ti!@Z49siJ!qB0d-G&QBAUTbC~d zJ3GAvExf#4blBzPpFl?LYpmBRdm>dwKCknCNn*^t*y%TRn<5<6+mu!r7?e)Sg`dpH z6B|(rN5CZmyDhqoBtF4SX?ET7r1io@=E)067gPM+3Kg(~&jRo$K1C3!*aRb8S0_c} z!CUX3I<tnRXy_)x%X2f=?@GA!RI2Dk)>VRKQW^K7Zes?1b`{NcAH|k$ah6G<(#q#* zU&}jV?}ED6;(%#LI!Px|g&~gGG)%1U1-<bClNj`dm`sD&V>89zT%>um@AeH<NtiKI z*5~}N_`QS!i4BWmP^6N{0PY3$j6!m?i&JC*r>wJmtYy7CWrGvqIbq$UdEH^)KBd)p z;C=^B4Hv<%%+O=e90JlE=88uyorb=uJKp!mX4>&AT|8YA8mg~N&i_2B|83PvWYgsO zHB1hizC(h%JMUFvS&;{yo!>R?E5R>V2M3;_`O^7CTIq1j$dF+J*g)4+2#1af^FL?u zS_{8-13Q7X9)-;)>4Fs?a>E?0@1K|G%dCc_mXu&+$0&48JN^Q7nC;3FM4o^myKdnw zD9i&!Ql(w8!S=)1)GlX%--yp^kYS+x^P#NhW3T9QFH9%6@shRi@b<Et^RjFy`igo{ zr=PL+oyV@woreGfhOIw6dqI(Pzxc=UvOiyz`phrrt+>0T>ic7rNp`uZJfeteMtMQ} zWx?|S9X)Ab?AlQBDm*;=RnO!!i6(3^`k%yb?eU^7sIl?3v<qi(_R}Poz)kIZovBkJ zQc&e+CrqbYlXzx<>K|I#(1<>B>t?k8F}q0I8V>{?U!Od(RO8)mcRW5y$RQoDT8YdS zli86EzJC@$-)OF}){4Z@nt?v(mVu5GQQc+>K{~S?vEWj>VBEmExFV0q3{-j4pqq8I z3#XnWUQrh~@bmKwiL+y=>Q!^Dbb9HG0^%|mzANVf5$Skc06ean^|RbB)2o^<u#?<3 zoJq%Zr|D>;)XxJ&!h@Lvkz8297e9UWesBnm>%_6;oNrEdoA-1!F`RhM5*Ngt%RW<Y z*349NNIou{I|>*Y03XxWQ_Py=-{P8fs4cODRQi76i?~5s4M2(5@4(<auvwf=nHzoC z?v+DVq$%^~wbfbU8m?5@i2S`U{EuDePF2UrEl;D0+dP9lHgKx`A|!G~L7OIh5?y>N z=_)Os6G?E#fTg&MlX#BXFlVJ7WBi2^q$ktwt5;Hl`4d_fd2^pb*hXm(-KufnvsY%t zY$5?#0$I&yiU_%}G<+Nv#;GJPmOyf4bYFG9pcM6cKAvYH(6_X-#PGlGrSdxv+;~`g zd;I$L<o|Zjd6n~a`pN&{2x2+uA$+UJPbuefCe>-s$>4K${+iXQKh}8bF)QSMb-TX2 zoG}X{F-HEbXXNK({VjP`-~Bh~coaf1su)nZ(P7uwQhJ;0(Ww2Z@tmQOvUxftC&cXO zp4{>!R-H)wbw5cE<7|D;^LRYN-LeYiX=rtJIN1DqzV%x1lBivkBkX<oZ*TZy@eEyK z(emy7KB0<!R$uP#g%?E&dUkI4Q~(x&!>{cHBQq-&$y0dA8055kRq};D#0Rl54ptvS zMg_)O9+IIyakR4{mt6UQMNAr2E9N@y%+nh);RDt&r!^0n@0<Gbdv-s=M|NqIB^F8B zFZv^ck}zoux$>nxM(qZ~xFMJTWTyBMh%+vm8h6noEwzu@aH%loVr|1QY%~Jl#HQ2e z97MeNe&*91(?SpqC+M)83;C)ly8tTK(cKJv-{6_SB-6=djKugvf5$Mm)P%0FwD#t} zJ!(R8J)u0%!UuYpXn;^q8F|cjG(tZ66cov2_ulRUGzd@F<28cCx;PR{`+Vj9`ev<b z{>&|>5CfRK3dC`ZH4+;-)h&S~daVhhoSLwNO!&LFa$Q(VPGJV~ZBvX3Ppu)23s>v- zyHeF^<YCE=D!TLrBst`vERf`Zk_CE^3au{E8o%F~B3T!YOP9V|=g&#jH%?iGE8f(K zNr>jVC_)NM6N_#J??2|UGr`=_>$tb%QzX1*?2|YLl3e6q5`&*N7`JWAs^bTk9|D?# zo;~xl%^f#*4!9{>JYuCCeMoSr9wVS}X^U{Q(%vYS<Lx9<n26>4e5{-?S!(%Aq~?yI zle|5;`xf8#+uFM7*qCdRYPrsmBO}vmo8R(2^dbN^C^mOT-5dZ<iS5!<kArEZZvAV& zt2JyEloC^wvJj_sMl)HePbEU{hPNvm?EYmBCwsh}pDFu2ADzsq1KZ3xZY{sgry3g8 zj4<i7k6v2o83x?l@xxZ<W;<LaFK!Cj+Ik*Uh|WC_!rzSlD$Dp%`jR5M)9PL-CONiY z_*k8j%Di8lWWT~3Cjmx?r9Me@8U54T?bIq(!aFmi8Bxlc;G`4Zwzlww=VMvrW6+QU zbY=AMI~iYIO-x*DyXO$$<MVNN+p2mQsY*hv8sA2D$ZBS`NHU4J7w14{`4DfO(Ierx z^@Fi|SY@PAqYm=b2w=pnQv@zSlb=dEv1-IOpr%GpnbZ7;AYnt2mx~7PdEDy0;vN~^ zo+)L&;nZXOY2c+>GmRxcjMK6tifiLKaYH4khQ&w@%$P@bhT}%4tSF}XgN9;doclxJ z2(U(!V$9qG%JrTC{1VGYM}skj2}%l@g1nnVVV3v^GkwKonZ)q9sKHK-N~a7VXrO(Z zYcNT!6xiD#H6hJt-MaZIo1-&gl5!Ax!Vql0AI&~BkP!k3Ev<J4E??1embdc)Y%ng+ zb{wsNjTPHca-VgiwB=Sgfn5l8Kbv0B*$zW_loZ4CX)Gg)79bYvH3bjIDQ%7pvbue4 zYdX&hPn&VmqP4fJst%<c@s+xuN=}K)sK`7ZMOD%HI3^ImPDmWgv?H+<A}iB)%w0`L z&UB4aLt^^!n*^G+xP?}<9Rkk9lN3W?T~$f9|0ZX<vfnmUPLWZ`GPV^4+$U+m=Cz}d z&x?>e3Oi|Hi1rXuydcWh+g`x5lVd?5jc%~UPIsr-)|9~@Gd655$n5v9E{37k7H3R} zG)TfRQ)kNgNVdb3tX<>|!Gh`D?lg^zvn>LGC*z<2h8v`E<AC^pRO1xsOVLO*^M8i$ z&ILVcr5uCB(OB`I%jlQIy>v1>n7${vK*p)!QXpU#>3;nL!fRQ=YAE9Wyc=CInVp^0 z-qAkE-Rkb;rmF_J6$A>!W~VM1$k?AlcWxTjzJ5D%f4wq-%6hQoq0`h{QR*G%bhf*z z_?4me+AwBKNt|tOH*`gp$-7Rjp~$;DYFiU`@3m%ma<}&8s1;MTKXSC)rMu2wh*R&J zzphIf9$!$bEq7iqb^aSI+OBWrD{JWU|M*3=Zrr5lt=8OcbOTt)pQ7syQCZ*;rav|Z z*i&f9<dc>AqMD>6VaSv~ihg#TLU5)M8VfWwqzb-jW1wfLWV$W~6EV=)w2h$ghxMts z>*5+|xb+cC7^W^c=(H}0Re@7$Ic`!;lR(~zWs&i%=D0mN_2}BDPJ0-PHN$waDpm3- zl4v1&eJ%B&ED8n%(1_-wh&7QtH3shJ(IY_4fE(RH2NRD<<6o1zl!;ZQNsfe)ow_aP z5Ct9=GB4kbK;3lR7MG4=yXeSeT0t|4mcA%{b<Me5igwqPXJIqz&f}`ij~VIsa`)(e z`;i~Ru;R51UB_lL4+VyMnQ;15kH<Uo8^GeEe>)thsWsh97|j>_tbN_-LEn#XJ{kI` z2-F#+d?gwa0Xa|NmIRigd=0FG#r|JA&dgjBWx0%x@<e`h6l&!g*ZDBI)fdglRy6_l zu|+R_FIB0oMNxG1nhFZjXSI7=Zo9r5jiaET$jZw4p~hBt{JUSyd0TdW+q~<1xp-Z_ z@PAtMzt4HQp6qy9zYz8R_q+#5{lu!g(Z;gT?DKlNKzY}|Yu|ZWUqwMhb@@7qG)@Io zI^XF0ae4cC%~0<jPW$(9d{w*T6RTnSE`B8S(|7@UqimAZmr%dk?>QSQW%f9YBi@)Y zSVis{E?6`b5)V<=*X)6*;YG8HdrXt>`a1HG?jI9>V@L6M{oO2hx}#d_@I5%1B^JH! z{(;dd65WY%Z_wVKtf{Es{P2=um)Z4tyWVgAI+Z`s%6?LA=_**^%3l7Y@8=iB8eW<6 zNKZ4WrF1c-s*bJ#p9MUF{3I-r6Q>rj31XKM5RY>(iaFJZIw%}V4DvO6zPdhILbS^b z&mve1HM3F(H?~N&rZ*8FKn&qjFikPaihqAtt?2-@sCeon2$-god+UJ1IckohJTdXt zz?ecB1GQKpv`GIv7d2L*D2j-&=mLBM1jGP83Ml3$S}n;^`CiA``|Qjri@NHh%eiY# z>U|5-D8=XL0j(DE%DNgm@=KUq&9`&Z1k=Zx7s~_x7QRA_y1%paJy;7#jS28$^q;^B zgN#sNu__ab%N{>)B^{Nk9RLd9q#n5HZOJ^94jD0N<vRW`jefSoL=ZlF6`8|M>kJQi z^})yxfhAR7C6bDhj?BfagD%augx_m_qRn@o=lXEP44pscUT29=jUEw@!8iW&z7G^E z{j3$yU<dOmb=H1wLvuEobxT*rA-akg<AZ!U%UGPrxos6bMa&3+&#EKF9@DxO!thHh z0wu-0xZf`oSNrsegi&<=_{Ue~urMV>hw*}I2Onm?EJ%+;9Gn4>b5*F{w;pl}Tm!YO z=y*yT_<FfqKec23P?4uYslvI09FB8{%CZ-B<W8En21E4arv;<&9V=-H2zb%Myd-<n zvhJUccV`|ZeautjNtDV@JK^nY6A8~Kq8HbL)<>yyr^n6JsuMxLo6c<R-a6*2I)9h& zYyOJg%Yvw${FLTP8BbB<eIhPv?d}m=yirDA-3vU>jlJ?l0a3-DJ}IyS`5;U7BZCX! z(V4pK#r72!6Yjzn{~Ig_0B&o3hK_?EEJ(FgvVGG5RfIb&sr5Iy8NXj#E`%XQ_qRd} z_9}N(fc8k|?q02jdUlj&*TU1`bit3#2TZ87|I4EP3$gztF_n-<7ZVE=FYDKi-QL6T zRfxCj-8mF0x`T9Y_W<yEe11s$q}=f^JeiffaFHv**V5>J;QEkY@2T#6y;<<Gy2lt= zSzSE{jP-+dSnF*SdYoL~vvhhkg(WK|@(GlOhO(uWO~qls(7dMiU8C*OIVy^ei=wX< z%o`oX4bK86dQWZEZwsO?_M<+F7MFUt{3Mx6)Z^yTseFYG$M%&|VB}Hfz0(3&)ip&E zeKKQUhXrvt+(d*%JW*1Q1&L`nZPW3CI&2oD)7It*j&_A_9#fkLdVFco4WY(~`A(Fv z$&$ANOB|3@>uwN?0cz6se9ww!@gplowbPHDO|Ua<RCbBr4vG)h#+!pg(_kTn)$psJ z72WGo#lVMqbSGB4%)UigQaC#ngHb|(1hd^}Qv-<qjagpg1#(T*MvDwB0qXhW7uVDI z#L+E)7!$@RJRPc{FkZSarlj2@*P2%(j5vZvm80rjo*~F@O~9U}<Pzf7fO=46xwJuD z1kuR>m;>~JzwyU*;j+oB)uopy@g(={*8c5^=l63o?1K<j`zQJQv8s9{q3HssYi(QB z$PEbCvEe|;@rA{RtLJ_|6~<3u;VaYn<-oekmBn@@M7gr!XP<@9Z+#4rV3n`eQf@FC zyz~pqzx`qvITU(60b6M3m7*t6U3WPY^sV%*Ud>sb)Lu-E3bpW&wfh6C%(rK1$qysM zac_QtkCr?)!k%nYs<N|d{6L1kJIk^de|kaIl5ej3QHU%qj!U$NTl>GIeM|b~PoOu< z{_Eu*QrGq|f}6pG+KWzQMVQ3PieIb2y8*Go&vR9;L6Vk*VyL8Sz*(So^uZ^yCymZL z_9>1Ly1%t*t3*K3P(Z8@|5LSHew|S<AFF?VH&YL^V)bH#*m@)X^y2Jo5Bu%k=6Uz< zXd>0y-Vd1KSoHC5`laB>{UX_a7KFvxJDDxw>*_S3emQ-432SpM9xh{?M`g1Rn6UGJ z^=rGAYY*rX_Ow0hE~bigeSGYXPF2oHxV{D>5i_IuuHZ3qcJ&xkR+cWs;sT4#S_E=J zVC>DnH&&7*>tdhryNI~B(N6BlB-fPWN9kHY|BH*4Keyj%?-9nxm5zSKovr4vsK^f7 z`Ggw?H;A>O5b~wSnOv)_#ddxF9zYy9n&+zVJJ+3vw&+)}&Cq_DuI?X6IJ_#WcW1PH zn|}^$o|x1OPr;<&<B=mt*8X$gtTe2{mY?)$IFZ75bc=zN!$M<H&nZii+0tx(lCb_P z=5+@^Z*0YM6fP+U*YggO$uXv5VDbXe)i?wk1#Gz=2rd4Mi1j*o3r$vd0Gmm?^wxYN zhE=3oqwY#o7kJFgSc0yILb`C1YJnm#P&oV)ruI-g1F`Rzv6)<HHl>?jYs|Ykz;Td{ zpCyW6K>Z<JihWcs>C#Zj>4;#aF;zwb>SbZ;<hVxc0;4m=6^|W0t$Po!<kj-+w6TJA zwG$3hvFKp+M!Q4{ta4=ZLuE26pG8J=q!%<3aD4B3?j*`ToxbUiMbtvtw!4>|Kf0W! zrE6x+i}@aDuFUy=MT<xjG&Zj#zqQTR&@HAd^~W;UR%6l$^ge}$670ZSRGyq}$_T|r zqyue={9w^tU?189rY<#{zDt)p%cWdAiZG@Cx$*P>tx_}xu59Ss*XQdLx0||t+fEXy z?Sp^Mo*~Yn+Hhhjz>@*n;es!P8&`MA*aI+|o!Tc8n9TCUN5k+AGEzPq=l+mC6n_zy z=LG!PD=g2-DKJ2<yOiRwFt?`iFqGK70TX0VL?{N>e&iFSA`NhQT7U{d)oUDFJQ{qS zZcooL8V@d@ZQf7)JA>havOjW!9?tJN+`Voe3uLh`)>^%9_is)hi*0h0bM~zJMZ~Ij z8*SZUv^P137wvno56=`;O(DMRKBL#{QC}q`nzcQBwV=A5PZ?S&EjOYu8H~oOzz~{% z%4yaZ8ee^000Y#|mtFRn=VG8~l=Hdj?Q#5>Y_p$uQ}Ai8BsQ;3=J+w!*0Vlb1MCHF z5r4B(PY3R6G$AmPB297rCW8(K+)8H2?e#bc!$~1+b;?T#`1{AGZXRqx$g)5XL+Aeo z2WcJ6^+P<h4s}6RP|MG}5P}{F)OOlIOZjR3e_p5%4kOugbW&9x+$icaz<}Cs6FBYE zI|QPk>^^jx(~NG0_)1l4T(icU!-Ys<C6|wknZL#WmpWbMG^o*N)cta>zUo6uudkEu zKTS7*G_D=#8T_7Y3CN7&<w_)+<mv=K%g7fo(Me(QSevIsT0$c<2#}`rItXgZ*;e5n z09mr)1IwcoZC3)M;e<ak^ismw=}yP6vfra8L`i>(scS^#)ITL6281|p<&edIr&EH7 z+_vNlr!MGCb|L4&GTssZPZp2PNDQCha3QwB3E;`D>rQBInBv7B8A<>>@enT5OzJbI zj+Aw=*tLCWAfq2o8j`sIHij5k@5Cc5s*UKD@;5~O01#BN7Fy{K{?|)QGHO+2xg-v= zgdt^F>Lo->T%e*~$SsqKQ|Ban+2M9<)!S%JV?39?40edYzju7`TFBlD&eg%|9h0^i zyhfRZRoZr~YBjw_r@Lkb|DiH>awKGTRJhoNU>rNZ7QpVz{^axb8?jo1&4uxktJ8uK z7~i;RlU5Zj@%a(p45aH!1^m@J+>TLxf|q=o_PB43W=mkCa%j#G05kw)h8n{*OL`=? zw}0(m{I`33-5*W-=~Ib4G&A1G$0dh&V@9Ra>#5C;^?G@E+4==M+pnSR<>VA(n^~f% z!1Q?^t%Y&uU#;Lv!Pl*aoG&}cOU-cTj1n|Z-HUbm=K=3mG&a_*p%qWb)^7nT@`=er zFwqNxCwzs9umr{qpDO3nj5q}kx_yNK&wDwPFlH+_?ZSYR-@Q`;)rKe$)+<t#nZw~f zYZ;_C7zMx+MHJOIGD7Tl><<H$Xz@lEj9!w|&>%g$NQ$LYE8OJom48iSf7Dy42I>}5 zh}^v2IUPKdrw*d+qK-ORqCf`316)HFgS=FI>i5~;<1u2nqyeO&BSh?h(hTNsA?ToM z)|P-1Dq_Bm99DUR?O<Z&gzy6QNb<;;aWcT{mt^q3&F9i=h)K))A;Z!PRh2~s&dcF^ zyk<!Cg<?hlQS18%wJeI3t>nuN<NCL|{Z#)!e>fk;X-x)Db)|rvAR@ODj^svyBh4tR zmAPlXGmVO^NaBDiQd(m1X9fWnjcrEgVO95+F(?L%fzDq$r|hf^LuxUDUA;Y0dsyh) zY7-6K01)>=^da7s<IXNP)&JKBmy1Y&Sveq};<y)t$weeszLk*q1YqWn0<u+40sNin zV{28}?urF0*O*z-js;ni+J61IGvnFRm#`=`%uT{`=5?xXNew;ds*#M#=#6JID%g}4 zl#07IjcD~Oift?qG!##Y4Eo#`jBN{cGtT=E2p5}M^u(<ixaf*{_<2pYl~T5q$Z99j zN93R~<*$fX3M;+N&^A96QY5jBQMb`e+o!+h<u6eNE~i?w*)(l39X<~;7TH3c|6sVQ z;UlHbb%4_31hm8B@}K!jf6tTq`CpvZ`>VmW<C&>-Z+8#S{$<+TmfC)~5B!nqi@}$< zYsb)$ITz>(#*bF-y%Ob%<Qy^PqQ;hY;jgEN1chhR2DQdK*c~5DyGOxBNc5#(``6cv zH%#DS$u%!1%XOz*4SB_R40wvG2N*TQEFX9O(UPqePIHblXH8Zw*6U%llh;dkN;D+R z(Hf=mPWM{OLlPXGKGa4IRQQuc%~E=!D{e{yWGklAct6CB{QKJ?!aG{$zpmBkY~=<7 zbq9d<yr$JdoqV~-Y*Lw^x8p2zBv!^uYW-N0S<yqPVOKGVFEpzW1Tfc}tvxw$`lZcB zRmP(8klvrX5id*GDFVi#Ag*HfkB`{o3xyOq@}+dFHlHCg-Ieku_PVM{i)rn&%@R{S z&bx4~4oys4);Uh~YDCMFkV+nHdTm5>2{KkAF{wXeYQ6RW%bXu8k*qpk{NG_43)PCp zhahL2%4)h><xn3~Qw<Ww7DC-MDeye`_{+SJt>92)a`hWt1Y!xoN+*Gd8#WpqUm!&o zolEjv_-riKo!coXHiYr(dERn@7qY?30U=LeK}HdIf;?F#uL)Fj0*^Vlj?uPVxg8As z0724zybzI90X*^t^(5N(6!S^3%Ycjk39?p&^VL@bibVFt09YdRqpbh6Z0DVK=iO5$ z3~hfN^nZT2@PC8FV3}Q}`D*YB2|e#7D#OP4Ndl3mtM}u2huvANuNW0OJEmcP7b2@{ zBNCb{-Jz9MMbR@srtaG)U#|%i0%%eEt;I(i#9L+a{cU!By(zsz#p-(m+ra=sy_F`A z1&u8ccHTTdhOylw6zfdxQx@~~0;{o3SP}z`PGKyHJX11HM+~2N7S<OQBHf!!qzOH2 zhZ;e2G|8AlqG_6?laIp4mUS_=OzLi;b`%E7{(zbflGy!h%(hr+e=SDrpZ?U3ZDFJN zM`XOvE(~+L_7sh=j|XkvDA+l0k~lp`dxs&#rxlIF8YONb8|p5n;p+2Hx%85Cr>l~L zMq0jAXP;w_GKITBBC?n)Bk{Wu14Z@E<Sa?v<kk}a2BA6y`jC}d2cG-IkY^Yku4DS@ ztlk&rTb+z{5XyJW@h&{@jIcP=-M{TA#(!ap0cE_7Hham@FP{xKSeae7lLNAL?fm0` zQ|PJ>qx*FG2oi7N&;PF9=g_SrAg4dA{72wEf|`zRL>-+{L^B#YrcT5&#4m1L)CZ|V zDF#HD?Q$tIWxf^7tm&!KFFg~O&Ip~p0*yb>j{DlJ{3}K>Z093%d%U9CDuFvWGjqmn z;`|;R;)sMO@n?;|fLpJ&5tmXbQufjsCzM)-Scyh0x>tdDYHBn*0lQ0QO11haZba~4 zbmWKsvnkZi|G?ev02YfQ>T}n+@v<Gw>VfV1@_2eZf1=H*)bV;#b(Qk1KDhPi?gv&J zHdd*aK(eQKk;KEa&Zkd9Fsb<Fzr(3E^+oJ~e{B?#0rpTM(H(e{b|MSO5i$;ctHjWM zSW*;2t*ZX?|4xpgrS^_4pu&c27ynQ~KlAorvHH2lP}x;;yJ54$tOqWY^X<O->vj-L z^%J&|kBfNSg9rUO4rjJb9)lTSZt#7|jG)>oW8Gy)Gi^3JLqoU(i_CQ`I$?}rh93|g z=?qQUG^<dhAgW)za7-2U*-snX)*F2pD;@*pKMYRk==|gtTTlDj(gj{)VM~+aiA|Kc zKufaIop0xB*B9;<a%MB34qzPd)M}&<oc*E^kSt=4rcHci9m6AIYg^b{5<G)^k$3~v z)k8ET8YmtY_u;=lN%t09DACFPR^Q;CEFg$`aLj#>|4{j6@W6Jmm-z#HO2XG67wfRc z;}jqFUG0WR0TvF-laegp+CY--U4H<JDwsE17sw_A`<Y*|g=%<KIZ&k)HE(d%bXDCu z9^J#ObM&Xye!7wL3){~w5CknMul(&;boPF_`b;V12?s|IMj9y4MO!9mWu1{6ZD^|M z5fWjEnlvf;wpLa9Z(APjqVWf%u-DW6^V7ytG%P<>^yOva?d5-TZ2QJj``dNSD}H>) zW#;J>XHjNqO7&XVedtDSZ|~FH#S^!2tCJzMNZ8@$X}l^njo;XtXL{Vsht7hSO^6}v z#J9D7{-Np_;&939J=8BhH7j?_&nZsWCs#E<62w|Dzc_0g{#ZateL}#Z{$nhDcjpp$ z8CF9ZChoDd?)jjHiAtNR{xho{NCXpK0J=Yuqq?H5dql|5nXi@;#&!Ws*_^b?`Fs4f zqn2xQHu8*6`S{mRx}*!Ay8PV0IP*!QS)(t53<NcCtAe1u)X#|>9IR++Z36+sS_1Aw z%*A4iyf~sEG9+l+sut!91JN>P)S7>1eptO*<nAdNrG^vW4RtwnO+YsxBC1qND7k|d zo1Vdq98uYJutd!k#mS1elF(4uPs42oJCR9}9AS|shmu)BiXpmxO}2WZ4!$48-aNqo zog|Y+J3wlQY^L^z3ZHBi)-S>;cX?{=bO}c0CL1FN8E3xxM^cp<izQi;mTayI%N*b7 zx)Im`CxsyqJ<(&M)4wSPeL?p_68p_bAP1NCaE+wVkX7Zgz3nFACkfGAJRD1INrA>q zU|6h!p7jbn=+Z}oGn(zA0(qPjwmn0+YEkeN&KDhI^t;&O4TgxZyUAEzJso1}crr8& zC+fD)qb3&)s;Y7$ZIrNzq3dSa7BlNNaH@14%~JClSuPU!zVG{L4}%|bg}+`?ABP#K z1F!JcU6YMNH`}mTz|Zw|3=q6b1~bTa#S^ElTbXnH=d0$0FtiuqyMP;7zQU8Um}(c% z;U`9{<)(?fbH}oS>CBU?a08ovyRj4EcYY!gXbEasWyw*Y<=fe$DnU>Z9z+^jYlAiH z0w;!{CI7Qc6(`5Nnb)i3g@50Wg8EOQ=bH^Ygt5mHg!Bcd<m^`5PQ8LU{G10C;1#`q z_Y5VTP#cUxM$x(^obj^0p90j4c_8c-0aGzkd%q30Gt1JBL8L19|HzwXzobtFZGMxh z53KRq%N#u*hH%t9m}WjP=dHQ(%Kdd><8{^lAW>Q5VOZJ!*j@Z;WlZsBI6JJHJjo8i z7Dye;Mx`ppaWsAv7`*wnhbl=B$Bl-R<<;4?ltOG^u|@uYk|MgQ34lZq;eUPjtwCPk zVpJ!hWb^Wpny8mS&EtvmrSqwCZR`TRV~Ju=fnEvquth*XFj{=Z5$ta8aGKXrm!1(c zv+^f)3)5yUhAxd8%?%wH6mR0AbTqR;b>0RU`~^QQ?1FdsPS%ItFFAe1$uZEY0cGo~ z$AaCcuz9x7Ep+#zIBD-q*L=ThuJPhWQfT&}1JWps_HnB~Qp+JMcAh09!26v?U|&Br zxT>FJ@DXM`LPrX(zYFTc>PZ(wN`tPDcFk`$(E2Ni%>0@VzO=ttqG@9_Y`cf`f7=0M zc`9`uX00ij<qk~#JIkzO--xZsCt3@0Pexn|ZSAFlG?w=}-sWymWSOZM*>}P=wal6G zna8=jtXDRP`{iwCV|?h9J~2-63&!m^Eca>=7el;>X-q&5%qfY0!z?<dy%{4%D@O;u z9_r|n_s*RBwd3spNRVf^zWm*hE5p2pww%vww}?KES9t-^%&zwAm8X{4QWmki=my+& zaetv6p9r4e%34MAk!%qvoNyj;4|ZPX%d~lK^zXET&k4M$!jqf(jCo<^n@9~m%n{hZ zyFIh_fBO1T=6}Qbw%57K9#j69?|Er%7Du13+1o3bZSdvCAb<8U-?ff>&o!YfO(|-Q zHtgw)*U6g}G-pX<SV5)eb3HAq5wN1?jqG-x>i>```f{ZF<v>P!ub_Z-yAyU#k~#a{ zQu(=D(#qILKs#3NqfX>(S#n$1v<#_kR#&Tzmb!;DDs<`&;CNKg34sXpV*?$#Nym2P zy#V;-pqL@7i?(Ar=NUviZVP^_M&k^lr;kp~`1}5U9LO|kLp@yZxoJvsrvdMU+t@W^ zYeh)~G1B^L>t&dtuZ2<gG^<roXeWky^;C{Hisne8rNj#P%1bK_etyoP8@m1bXE!D3 zGwqV8DVQK3FNLV)fo<fhcSK&@sK`$%r3V2$Uk5*vS2@psA{9+4U#)1C-^Um}76+-H zG2qFnoLyhOI8HF^0I^Y9`3LC|gC-9%4$+%4dnQ3KlQllOAlIzQm4K9ZGC1b+%k9SN znLo5{r1PHmO>$Q4C628&_84Y`&<pD&a6)Z^muwVpQCS3dg}Whk?FB&3s4J{jjlIPo zET#%lVG<O{aeORlcLf32(Pk9Z3Or%ZJmI!H53u;Kf&-(?<Zd%Zah<p{y3U4(YhWeM z(mTQUhx5V^x#1|5_XUDqkPtbLW6C`q4pm{}0ygwdEl5~kF+bX4LFI)LP>T0hSzZWs zD{RIGx#|3|_nA;*1!W`JpJqt0L<w-1EGdVH;8}@pQLi3!fo*<CkZJ$xMr$6B=$dKC zod8ErCwK~iv}98B7ve4c@QsztO5_~lKsAZ<(#;#KvQdul4NfW1Bw?J!9LI|#U07?a z`J+i!PimX{ndK;Q1A{lNn8TC;;z1_TjqKM0Q6DrSB;HS7+#ENUM4d{63bQx1*U#36 zhZ*fl+DfxCGktDh^2|z6U^=arkBf)*#RB*t&Z=@&@9unk??XYSr?ZS|+(nk)+2S4% zL*pR7*n0~@Ezhs}o^OUPzM$~C3#zMw64940F9@ubf}c<$ueYh99ax+tS%^g0JeBrE z9UFFv?MPqu-X1R&?oVpprh|W^>wdz9DvI_;gCTPa%X_g3G|0lIx;@<OlMPH@iYnF_ zKyO@)&r0$i%;3O)?R2Av#d2WkP|;i~kl-f5<@afrai)1`4_=MECsl512_QJ(?rZAh zXWjHxJeFh&#aWn3_bHRQ!`iuSH!8WA{<+SSnm?7P^qb5R-kby}D?f<Nj91FSqMgCi z(Yjc%M>=INXuf8kw$Mfu!Lmu&pjfU#b;!$tF|1Z`_2X)!`<1w$yd0t9`w;2ETP3g4 z7}TPWVwzl}2rHO_Q%|*|rO7t5of8f?5z~cigAs$>u3io_t}%ir-I8t11Vuy5HujO0 z=*(OKAIr%}PPmGFCC8mmkLUhMaB9+q+qy-Or$nNC&j0qQG9l4|I2<A+RsuY?q-z^U zmB=8J=&@zIRksgcAWG_z%gO~GedL~P=BT&Hi~W>dKU2i}jqC;h9RJ8jYk44tj(!Jk z2EYVN>sf_m`-ob{6H;PBRO!N0vM>eo|4_w$raox&{#EoCZR<7^Gc$k)!kTC-o~Owx zPa+-eHlVrj-MNtoY!uPl@Pz!`5#2WX>Exub;_=7d(;FS$vz;Wr^w(&ddbzjx@C2U2 z7f!o;;Wmh|Cl&JkC`*kVSCaBQLae94#R3)aX~6`BddYf}#bQ0CUNI~3={-V>Z_0nV z!qJu1+-$5rdgh8RsdZ?w@Gx1wRd^}%(J(bfQ4<S?c=M8-_4nP|Cid&*)uiabSt>!; zf1-1*j}}#Jj5#nw;8t$S$!ApXd$Z1neh*?58q(LSw!+tpsIM%=?**!sdEj&q(km*G z56q(FUXZ(^?JFBT%=^Izv5Lz5mZS`&DO<w*XbKI9=rSwRW5cAXjqHUS=QH9a8b>oA z9#L|DZwQZ0K>6CoON`cKTD3WD3Cl6bYK@eHo%qj?5MEeP^Sz7$_=n|JFJzkz`Mz-U zWkPsn<Rt#jx-Hu(c$M;nvW$h6Y$!w2mOKvZ^Ia4X4Z#9mdX0yeenu}Q5U2JkRSUQi zW@&oYLlAX(koZs4^jo=R<I(^}^=jTAlvtJq@@)PXf}O=JtdrOnZe4z-Wt{KCVu&6m z?XHbi#(Pbhc;QNDShDHfxy_Bm;{sD_7vVgzS>{QCxQq-5v9tpLy$#<8nZ>cl*!uy~ zGiw)#JYVzqzay~vESfl0(ZY;k@YjyRTj}P*du_C;oo+69Wwy#n;WzZ!Y^vqWN`+}y z#+|t3`vm#@1^bFI#%nWrE9AxD2rKp>T8_ER_CZ?g%;HbL^8^48Lr+Q~HOI?`-b<Ip zGproRg6*=`w2b7*Iyj2R+IlezA7k!nCy=wDTQTQZJAj@)$S=<M9ZCLQnyEGa@pG5K zIoe9cLL|)?0%m50c7;o}fuoS~PO;tgYwOTOqwTLk{;&N9IdAuaqOaGp%AQnym)p|q zJD1jKuc$1ny(r;lvh3<n;PcZf4|k8dbKz_=Mt`>fe7}cn=1*`pp{X{<LSEMqsmH;= zi1v8_+gH$5*p|?ZtgH<$J-=6tmru(LvbgruYaX64La?8JfQbj~DHRn(4Kf#9T|@C# z^HUY#DSQsS0P1*#?=?j+j=^&je{hNnxJXY6u}bLyfT->ubZenn={c%>0(1Cic}t8| z`8iaQ6A6i?l<iailRl~F0Nd_Il^;PyX?U%b2|}ttpIao*y!dDE=~(6)5hRmwdj){= zG-?>1Ts#r8UjyO8CnF;mD-^txz|=i09^urj)Etm=!qcv(Q-^onKyb9YUuqdQnv6v> ze6_}gM<n2rCROA}v!8o=NDLx1AoTGwX|J>k<|!EuJsW_}KA!XouFJXAkdPpn<iG&! znRu$PDq7J|uz@t}`6r!joqX0Cv&QinM9}%79blSLJt?0IF6Wd8ic|?ptOazkE%GJt zP)0lsuq7oYf!$(1<wXS{JMe+txu8}2aq(CeAMg0EO%Vp2pKis3*<t%Ur=7)JSUxj@ zEr8~VQ-J@x);#KUF@5zIGRUNyMU#;hqzeekWLD*+NU^k@XjTi4#3<t$({k05ggig# zF8b(9J~(~*g}z>X2G;LFP+k9WvJ3koD9!^q1XG{tXgAd+bmmj4$z86aX3Yk3!l;+M zo{d1arvaE9t@2d}9UhcZa>+0|fDgI6hM9TFKNRXvrI&8stdb8Wiz@dk9>zq{Jqfi+ zZ?w3&_?#wu%b?4c;4gQ4y;hI~l4?b6RoedQ095a22Y`W<Fmb)rIpc?krD~T$Ub;l( z8^sk@OC6j8<yh;a#Bo?^FiY4&+~eOZNf*P&(bc~Y%eLC=q>Y5@<L=-ma`{U6o~+$< zJ(g9@?9<=X{;U2oI!bW#yTT8z!A~eCd*3L#I4N^~PL$baw$x3h^q!nU`!h_BBAt)g zZWP#hIm~tYS>OKouh*S8di!8Idg+yDuezSEI206r6+??JpK|3Wq$d`0#*UG$`>Dht zIpb`9f@2@v^^@SnO0N_z9?#8{aHxe59K}wpX)(<-UMKH@#e#w^7(6z&6qI4Xmb<wZ zv74k@?z<BR4v;QF(j>PbKBFBM-kh75m@2i7DSfH)Hh41@CTa_rFU+d(Ect!LRg3FM zVbd<dIgaa1S?1QhrlkX{c4+M%-3L%{RIi{BiAN2@`y9p=dXV2`{ysn5oRa#SG=|y^ z4%FRo;#*LeX!DZhJ=vEq*@zLZ39pvTzf>bN5au#~Yvym4ypV&5&l6$EEtv6S-|!XG zfA=|PTi`F2xkAg%$ikN-FL0!zd(TP}C#Tk&r~GA|*WNjj3Kk}|RSGT6?=znj_vw@- zx*27zN7afuyQ!t~7@_giiSUt6>+u$F5virJn~alsTpn!}i<fd3BZ{Ld!hoH?CguDL zCC78oh0;ATWIk_9TYI2EI3$e)+$mBYN@7(d{jr+Yj@W5|hp?rzHR-g!|CP3V>uSxz z#bx(vWXelcZyz?cA~MXL4gTIR{Cj^cSG8ydw3g!mhKr-k)%P-ZPVKE6{I(#CdkU$G z7{@2%YRK(loZP%vN!1+9FbplY-5pLGOwM_|F4=g4y1!n-GMtoO??qn^L|>FQ9wyvj z6!%!aJVxqg?7H1YT@VuecJYwGEH)Pq7KP&RaQqORI%$~Iw)ygKvmEKKr1X_$qeGCX zb0M5}&)u?L$6teQ(if@=LS6Ef4N&)>xr7_uxgLcHs|?#Xb{~@#HQf7ZT9M1e(=w=8 zdb@^jX^xV$eFW(fo^-D;U0lg&zPxiGrCk@?87TxUU8RiiBqql*)z#tOe5ece`^e^E zX%TrZhW;~@tNek77|{DZ16F2&+lBd|U>#7V>Poy$)9;w&>_bno%#+9RxkyMIuskSk z&pecA&7ZjIAqF=hr-&$HFkQ@Ri0%}ge1RVwi!O{o!QcfcmXf}e)H<(B*i66UqAOm` z_bn(ONa5huX4^n6UtNTZ>-#6P)xKw7Z7nu$lNrdoS&A6{Y)>ROS#1w)F-i5|SFul$ zQlm&pFX~s(wUty7)FC{JRB|Yx6NYq}W6JwOGcB`>FOA_g6kNd=Rr1#`1s-W0)NkQD zF`j9k#n{o|kYLlHuYd@1s!eubOO9ajU++}Kwt%`jNCiw?95>Wb%K7p);KVf$c3b%T z-R!=+thwkqi9y<6a-Ftg&U<Ive3>#}9tZI!^w9MG!IZP_Gv)1?^zta*@Mu1LHV~Wh zc}kJ}yt4$~A<}XBQb-Fba>BaVKg1oei+Mg>Ap2hgxe8x-j^E?aUFX}2=-Z_KKnA<} zvA6r3XO;Ke{#n+`%YO*j9i>@2<6CALjs1gdDX~j)8S%#c#l?*=HnGfK&nj--m*6#? zKOTk;^Bnq6hRVMk)qPOjj#uuMz&Y7v`t&QqAL|c?0q4IcS-&x4Ef@|<r++WSsE{p$ zmxAS5rvOW-B=NJD8W+Xkq$(MYX;qi!^IG%tTjcQAoidxy3$BiP*ax;Dt&k;A$ue=R zF3ISg6@w1L?l`*NBuEA$AINAM`H)S{MwCcUy?Lc65kL*^qudNgRa4^7Gc2lC=gZae z&2MJ-IZi+RA)5?6W>aIMA)yJ>ceF~w!@y!(#xurq72=g?BDK~5B!CLXtqKv`fJ;aP zi~Q^>@rLS3S$lZ9G_)K9W?-L}F!ax+)Cts<ABZ9WY{;N60;d%t{NOB#-(g4q^>I2= z)|1TJz&tP*FXkO$er{6KtW--|$2;_+mL|LmS9}^Ef;nGae*<Jah`U~;p>&`c7CTjV z$N>`$=OokCK;Ns>tS~qdgC9<>1{KR-%C&#NkEr;uc`kNS4aT_!P5$h207J92L4hx5 zPJOPim*l>?Lu$TC3%01C0t)b4o4DOWIIU6fTm3x_ebu<wOwiwm442;Og3Tc>?|aqE zgYpJc;{c+)LB6F}sWdY-;C<?5_??LpHl-)5HD(BpSli)z6LqvF@}#nB(iGx1nLX*S zK36__n@&vN#Dwd*0^yT5iz3y5=QvAU-W!QSdmw~sgWQJ&rwf=3#T}D<f5ZTm=uo!M zv7hCM?2F??UnKU*Rz**s#*@1wEwogj+H$V3&d?z$N5)E>u-rxrTQNRrGYA@V#}70v z(;+q&LxJgx@L&&8YuXF4R@JCtt<>9aazf{1u}aWR-zFrIIw!#4Lg~Sk8yN?K{Q`Kw z(!uD*be`lt2F~p$bBHQ>{f17QbpVa>4p5Urpiz^4!f4bhWj<jw>_YdTGIA^A&I-B_ z7?at9fsFUhY_&~Lc@5J6F?1G3k8k#`&i>YhESmb1ir!*_K?W3jdm+EyZbYBMe^B~f zcfN@}n;Is0<j|c$*Mn0_s(zhA*Lxce+L*F3JDEgxZf~<*AP`vYevVViKl*+|A@;Rm z4?+pGl*($hR7^I(pJ}Tf0;nNBgW_;Yr(Iv}Iz1&jQJP-d1Dd;s#b_yhyBL-9AL2!W z>rSv*Gz<WF`{SGXBMKF~lFrI}{b;694t4p;CQI%{C{2sMr<}8@jpTV#-9E<mCGK&I z#%b7S<jwXQGk<kx!nZJB);=C1J~Aj>vs|!bhnr$XKhJ}Db?C3@j4o^O^0$$r$H|p) z%Q6ZRek!A^yuFC9a1@A?nj*8B<_2YJp!e1o9V#765rhFSTM=M(j(ylRkXy0!GeTxN zHiKkZehVHEtV~!S+r$}zuWe8bv#qYKb2*W<E{&RQ#dz$o+CV_nhiPY6QdHh}a4(^g zLg5b`yTWGo?s6dKvXix_Yd<FQxG%m6#9D9jl(t3S!MOSj7@U=IYZ!_7@KX>`A=Oep z-FGxL>Y8jr2W`LA>a4}b(CC^cgRZXW+m6&2rIlk!e2SYSTNWDUpXYM*Y|dlZP7bT{ z3U-R3Gw*dz=I^>G7lg%4E-CMuxbRxmm*~w)9v43eJa=7LSXg505Kb_F<@+k58JmXx zN*Q#>UhH0ni#~5Di@aP96aP^DnzhzZ@9y6Dyn9>V?S8S*>F;pp-sxPK)9Ly2xHozL zbJ6$4Me29vtyGa2m#0d%(nuH!&<KtY7b`3IgzldyOpPwaV`JGsc*VSN8c`jc!Ogtj zu=P;lxqY%4HiP&*JvtY|WL$kOh{mrXB`BK{1w=(x2?;%e%$MWZZiMrLeW-M<`NEfE z35AKCpw#rwSs`f}=tt)nhL#wm9MOg<i%k-JG2KP-MYEwI1rLNesz9{gn=QalCao+3 zFHD^9m5LO)O^$W<O<mIhJ@fE>Rg4L6-k8LySsou_x7IAc%{68Kzj%FHcMhVT7xuNU z&jp?+Ht#g#EcS3*eKoQ!H!6jQD;x^cj+jN1Ul&Lvo)ajp>z-qda+@}M!HoTUT##8L z1+#+kMhPz>)!Q36uCjBO3KtN+ne<oY#<KR>(2lorLpWC=xn|A#=5F-AmFy8df_v;R z=)ypA<7vij(yOdjBV#;1N1tVm*?;9V+rLK-(|9oIYr}Fc0>$845Sca%GOb9_Z^!&o z`mJg&$9D3_7Antj(uOg*hL45Wgxg|s0)xK!$|(rbUAwAJW{XLz&gasqU19rWbgvhF zN(i7id-lp6Bn_!sz7#WjD>L7abxd22y5m~pncFiQGyE|hn<c~xY6NMYJL}UXx3A_p z7eC-#x4eElp!#p<gTdq;$^Ai%naei|A&VDk^ozuEkNLWr^Q^}OY<+T3I(ZE$f7dFp zxjFA`FPP@Xq5irkc3gHW2@jd5DsX}ni@&4W)rXBvYo)42!z|YO`V^eUnhTqml&HtK z#6TAHO~z-}VbifPKRmA84#R@AA?Pv*J?G#+WAyZfvOZ0&I9CQdK8)rdUwKYDCEf&D zT2*tihB^6{?*<hkT(ko%p>$z+dIqLsVd4{L7;I{CcT<2&2!;__qg?c*UnoD#w;Ab2 zpq6^chi<JhBp$r_UG6XgbiV&pkJXN~LEaCvrce3O7q@+dpL2y52xY=*uxSTeIMjm@ zYIyVxPqAdL8#1Gay2?Utox-;WO(iaNQ{&c=Z(KU~3e1W$^}Qs)gVpi-&``NkvyyVt zv=c&Rm=`JtIo%r`M#zqBpVDrrp<37D>O<y8Il1o0RaKDc{O28DtRLG5RxwEx+mr1` zie9^-j_`M+>lNGXRxL7HwM4gEO{!{LGL1So2yex9b#g0@!dzXS{0mv;qpu3jZ#5BX z`np4ITkkO>o<D793LAM*<+7zJh^s0u#nna{TEB|IF2YXK>@~l)ynVwv^L0&I&u6+` zE^2yE!TM4JxsutrV>8_~#*1WWqkPgjb*BIHDZvN`vj_b6{OU#*gNtZa9K||z)8FjN z#DeED0l!fa;`iH)R$o6e5FOd2H73t1_Ve7F3@2u_xEn@@>Qp`VT|oTQKyvb<>pvOJ z3cUVEch{BWuX?d`v={SK14d@T4oEJh2uu-@mg2m4!uoQI(;2<M{yv!L`!LyJ1tFNW z$if~+CTV3KncJFIcV7y!;J=MvTP1@f)xJ9EgWu8jlY%ETc<*wg8y2Xm5gk1!RqU)o zpH^FI-j{}J31e>m0m1v%YTwcsb}LoXYbl$=cn7bD3L<GeEW0%YnE|D7qhO8!R^w10 zXVGCYk2uYu(p&}Vp(}TVr2)4YVtX!hxC(*glTtMh!httxzk@A37D03TRZA39?RpMn zaHrAINYNc0xRb4mN^ng+t2u~=d2&;Z3rD>B!MU^UMdn&-$F907EOp1~-p7}l@!eKq zPr;0^K!R_x4W--iMa>6RxawnR8SMLye50^Xm#eh^3&q{dvpj-9(l1`_2gKJxZMgXs z8d!TWP2DfexFa^7M!GYs&Z{sg`sKgXz?1--7GMZwF-n+Q{UVi_v=BTgD%<_*%M;8A zE97zYb9ndxmIDA=^i1nXXCW6gnZtm=o)A}AepTmL`b8(}k7{vFw$ZQkLGRxeLwhK0 zYws(593tDk2VDnJ4iIS=0|0Qw?(o1>V(f?jx^n#ZDe??w^Ym7jG1-E&nopisYolT0 zM5~;5SZ48e1CiJ#9T+Dpe+p2`GWvWl^fN%4JcZvTU#6!P)<R)+(aI?#rmN~;Xf=~$ z<d&Q}PGpjg%${kUs!gE8`1e>Oe&nL>I;+QR_9h?I1UcO{V?9hIz<DkzB|J+41||*V zeU_yhpo98c`5}dOi(UKUgbg1{lCZ*RjWI@n|2vq-v{sFLeB|s+NSbwUPz(7G5LbgZ zg&WL4%_Hl)!Eie^92^7gVUURfP;s4bq)=F&8(66;W&BFcMXuaBWp2qYYDT$+O}Yrk zX3bKi+$fa`8~a`v-nnz>y?ya8u3a-TUHjn=ZrRX3$pp)`o>K^;-uD}x*<@_UQGrTy zxEf5tD`;F#r@JoSAO$k8UkqnVPthse82_F)HSm>^hyFByd0DTOTN?vPsqRq?|5*=* zjmK`v9tU05lVYcFFxDp6I*R9><9>#0DPfuZO6gpRJe1)Ctjk-V^Ec&5HMB8pvFa;r zy|ctW0n)ET0}?a>@i19G#<VBCpPIOFgzAXGZ1w?3x3Pn+e<fct)-Q^6R@RO8dyzt< z2m&gX30FlztK#eBEtx?t(f}fNMOL>6qyS@DEftG$h!VO%5s%Y!Ay_v_S0DXFmMwR- z6BMxq?AB~`H9}exB%{hG?)x5kyk-S!kRT6j6B#Fm!f;gsfXqQ&QZCZSGMl?dHK*L^ z*8Couo{`X<i5h`x+wOoPdlLvAJ%5uUp)8_|X<KuymqUUjAwd5pvPugu%uCa$P1*%U zAM(ej<<4LRB1tSKp)%7sW2LY~LxosdB+bzOSm{&ON?25z(PHZ1>*KZ_Jg|XwNz1<r zSl!_q;u!=+g5?)B@UL<G1-M!|slga_mxI*)ORTQ|p;u#6@v_#aL6^ejMhmwV69xYk zEz7sQ867@<ft`Cx?Gdn=av02XvdUiF1f_5!6ny^m&BL6KI5NZkpX2g9gw|mB92-f} z!u(0JwTC*QAQ$WZU%WCV)az8|jt>|=Kza;mbahUPVL_iC=t&?kQShrfP8M%TQPzjU z)qOLnWrNOPu!d0S1tXXyR@aU^zM!v=ilD@k<BB}#V@b=43#_#6<&?9&EGMr#jW{;3 zR7#VyEs`ucrv6icwzO;eU0-vZzWPMEw9cJvrTpanF5;2$e?*;CR9s!Kt+9sS4vhy3 z?hxF9Yp`I!8i(Mnf#4e4EjR>s5AN>n?(TN?f9|>Cj=>ub{jzqgRaJ9-6aIFvO5|cu z>oKzJUrZmqn|qB(h+<&s<=NS43p$xlEe^zua*d9iD_3c`sUy+%NnSRPdwQIz;Fm^) z&DlLv!#kSWp!@71#_17KEzt(M&NnazI1)m@Sg<pWi5o9k!alJQs%3;>(!x6T{TLU# zL@#Sy_y=T8ilS;dRM-#K5=@mu&3z9ADvQ#i*{`YiW8xVRRhlu?!kA~?N?0b&wAI{^ zpAFtvs!IyD^4Oo;I@AcSvpk9oj~>9>T!Lz&d@~8qA{F;*D!;Lb%2*(u^3%NWgSKWR zStlOHFmkkw#pbULr%)jJpdlz@3v6VHYXbH%ZDOqL77@JkB<7?p!n&IsLBW)|c^(?% z42#rDl=97+N#Upr*M|t!_bkirziklMO<ecP&q%7q8O^kc&reJ`v9(j5B}1zjZjX03 z4)WU+e}b((4p#_~Ir!LEmKQm0rxDL{nQ!Kp;#Hh^6@KI1dtwFEhB9cU|4`FjLKW4* z-TSr}D*ZlXf2?Fq*EsesCM3^PpiT2HA2;6b%wX=W=OTi}^o>`AT2%eBlNPL17f&~D z0l93UIo*!K;21O0HDTBwsf7PF%CiK3(y~j#P{lm9(8kA{1JJdN`K^iiqQ78?jeF_+ z-G0tuGpriBU3?DAdRPCEeMWaJbF=ho7}YO*3n`GCDGVZN+*HUsB`w#>kLaQPp~Nu} zHa7-mM<wgVKdI@%N90w(UR-M^v17*zATe@*WC|Uc1P>8p`6K@m-4gYurIxzO-jWb| zNoU;M<C?f?y1HNiOb^n&)^y{AP$|RBZ^5`#E{cS$JyLY73rrMp9zpR-iu~6r-|Vs^ zG)_y(q^~AenM{>c0~wGWH#%W0|NX`2%kTZ7i6%KG%_<cjJ!cpwo#fUphK`tD7$#P< zdHTX8A09U9B$;=~1{992h(;@{)ln%2YAKHVGMWD0N#rWX(Z`kYsx)EoJQO)3AG&*) z$qCr$`2F*KBCo<#(9I!KM{9R|sC$v{^ynm44L~ag@pz#q^Bvj~XG_bZO<*O|Op=6b zuVv3~jAS&w*Y{8G4cO>r*LWXcfhY^Qw})+@xN;fib7jA3pKtenO{=;Bs9_{BfqUgM zXGnb_3zJfV7Qt}cU!t~SJG&5m13U4?EM;DtM2lqO3Xei?O#noTnMB_Pjqz7a$ZIwN zBg(J@=k4}CNW<^fC@=?d=$>rZ(w%z`DFt=>{Pg;0pdh*w1xmVd?Re!xJ58pR)>Re- zLUN7;NlE{YpnM_xgT!L$Jo6;0amK}_dceQ2@6Q1vHbu>>c`6%nU08FD#0^ULygsA1 zg6`;@H(vq#c-0K})sxOX@{gyh;Xtbp{Y6!H?{ZRmP~P5c&zn>9H@rBHZk33`=I-Gc z->!YD8k_%srW5F@2x@a<`{_f$<a>2rgSD7%$72yOg0Jor7(Sq+C4M@hTc=QJZBlgR ztYz4A@qPn3eU+?+yS*qD&$U_wn{%c&O#q_s#_RArwzNq4!%R67*NZAZu$8vzPO+(N zJ+nVP<^X_Ibv4k%M`a=gSyiOBW$MqXy#D#_Cmz>1wU3q+1m~F|ChzL`R#j5*v0<2- zxb?ZOKkDsG_yOVlfDF*9KLoaSiak7*wMj*huKx3kN?HR<pNE$KfMJDgU?=;vW?X1n z<+gXB7*XUMNFDdWnC%j;4H)~!TfB;8w9rrHBcJi#5Fyuqugk6T(_7Y?zE4f9r#17> zAvVYTpuev0>NdwGR;@7{wYm<I%WPlKrzv%zLXWQ{vrIcZybSD!X2@f8ns+xtt#5T1 zg0%=jAdx}_kp3?A!7HZKpXKmPT{vtSiA^cdvA4hjVCl1OWR7DSLyx#&24=U?moXJ1 zWNV$ng5*Gwg72&gd!n`@%m<maO3d+yXpw6SMttn|tqKZ;z(a48f`KTun{Objr?jGG zx0Rqf-URiwRa@mxy5n>u9_<bVLo(MF!!cArqQH%UQApkAMqW$Tz|W)?JI3E95Vvpe z+FGWVASP=u_Kz{YRT>I05*_pvze;TS<-3P=CbY@LB*mIlc-Pg)4NH5$r%2?vI=AJO zEQ}|#EQQ+Od3Nw%F}(ix$GC+uI6}CNkPb`FMu}uc=&Evl8!AUfkF0@uK@dhtW9Idy z2OVB3>hZIN9jV*g)YD-cC1bZ+Uuq25+RL#uD)m=y%?fV4N8;XF*rrSlad7N?c6cj{ z{ZBqMectiqJ5<hlW+#Lh(&VK?PAp2ahJE~>oA_?7`8elUUacz8pNg*^F1LYKsL|$} zXtHE$E26OH-N|4aO)Kg3$DM8g=Jrs+*5w7#fIuCg(ML^TKE7t3_n%;Ef9ar&izl5{ zsCn!5mp)^G7-mGThYJgI{P5C*xwW62jNR!~LTqF2T!=ecLQ>`Tq4+Xh7%sX~UTMOY z$oy<Lt}4M?t<g-2HWVX-!^Dn6Ta1)_uxxTQay?L?q#q)P2}x0ZL?X-o`b?@_Jtpl~ zSUhObGSgZ4M~fz1j@S}myGk=ME-h}2+D_aFk<Z1Dc<u!G;<L5u2x>8md!p4kE_OoA zsOwH>^M>`5|CBw*Td?XnXe<a8*E9kA<=@X1754?vK&_k9<XtS2-@K`w9dz1C)Dg=Q z4vEJtG|qJRu1w5>d;j1W;^3LZi&fH?Lbblk(@fBtv%yoWft?4~{xA&d(#<j);4}!1 zm6(#SBCkN0swi}0{nyEAY9<g}xIbS*w4YM?wrQ<2CRVsbOES%W-^({3?cWBF0S$#6 z^48|npP#CL-jEb4+H3D$`McWq=Yz;=$K9Xb(7RAZ1v{{c<b4YT4MNAmPs#Jo`g@Ih zqpUrISx44te{5_2iL^~!9MVWGU#SOf(;uq$20?pksSX759K6G&#^p*rh+oIp?*jnI zfSvRIOf%?4#<n?=P>{M^is<33#sMMmHrdMt!hai+fA;`A>Tc2O=WO)-cbzqr03zgA zxhp_y=YDe#!#6={eUTUr*Dx^D=pc+Hb2%seewN8ka0suTb+u*5AddocE$ZheYs{fk zj93;L`Ddqn{MHJo<P;=&gk+8>COLh$eGi%}E@<PMo12%H0Iu_17r!!bB{>U;6h6Y< zz;1UjQp)l~$7A-JFL)sFk15UsDt248FPkhM4oqcbm}dA)ge1qeR13%Q-($m-!wGxk zoYQ+cIf7l$r1+_3-Cq?IU#LvY^GawZaT!SiJ$jHx@yEMMAX>*_XV|G+O!PIz2;mqT z_LE%>e;tF^`<2S>rfj)J2qltcMTUo3RSIOdCcnSI>{^u^tNcpTs!HXY_H~w|D2Ypn zZLc&E-M3ER((vSNjSoRL!D|C(JNd`LJB%iETtdSi3mF70F@uz46T)03*5Fn7z<6uQ zXTWK(mp0*d;_33H6x!x(YoZZxB@404ZWXpX2L(IZB0UPFvz>HLFA@INDatX`of4U! zL2GbNt&pWJsvq{(=u!{k*;_ZNB&XKIqzcVyl2KxXAbOh!Cw(-*GaZCR$<WxoTSz`c z(fXjX@93j(LY9obSUTUAI?;Cy9UiRqSQ1GiLzCawuz&z737qS=8dQ1|Ho#bOYVzL^ znVXx@EMfN!rVC@!V=-8`>yhZM>m!P5UrOS8BQjXaqqRYaB?@=hs3Oj_Rw@)KOG0q2 zj9a=Topr<Ct|5}cf$p~Q1y%>Rma5z$bfaEFN?~Tug!ytf&6lGXtC=0QO5}J-ai(^Q zz?(2nqr-2^Py>P=Y=A<f@P6A^3!D2z1Ww9O{coW`h8<|BmwXCLC00npHpRL<D<)ga z@7)n`2YldHIJvHfM*ve^ZGw4;Qp6C+Y$S0jv$`4GGy+8w)WWxB7n5HLqp~}sDO%bp z2q^Ebb5s|-lk<BOLQOIfN)h@>CoHYmY?+JD&{*<El`RUgmrYkOvH6QB#*+6>!LX$m zc)>>u&g=!!9H>1RJz#prBfqtbkKEk#LKQI?0Rx1)ckx)*+Kgyub!P6M9D_u;%0YQG z4(7QJ+8x=<b`SF}C^1o#D<}4~57Lh9+&Y1^bPSDrAj`f{I|qlYZd!EP!fA9TiKhb@ z4n3uwj-i>lOF%u2i|<_boZV!7K|PtMZBg(8dp2ipw45_c?(<myO`o)*KG8Cf#aUVC z>T#ZIKkg9==B?v$O<b5p=YRi_<!yO|dXg2Edk~~tVE}fVM-76G(-&u*lTz-=mx)~p zd%&Fx)a{h@1r&iPN2AM(#m@)7)&_bde0{7>VgE9lc$ZnV%Lf}U23-EN(wHyw5fXzG z*(bVfR647$8dg1PCg*pQ#*7_DFkBx|P;2Og;=>#a^?_3Z^FF-RoRczrV8I}^GvI+L zPi2h4)5`a6dP_RVR&(sE9LrZzK1Xs9Gm0i`>7BAGu9jh%AjQkaSvoPpGg|SXyw)L6 z#<08tX*-Gb)QmqGEpQ<5i$w<Xo)8O-i_qaO-psS{v$?>GbYaXNSo<q{nC1swNx1%w zi)cpdef}QcYdbu-S&QY?vwfr<afMrI0SZHbo(Qx~-voD5%`RU>mzi7Z^l<{%2oz+M z+-@ZbhdjrGFA1Lk5rQm`Vaz1AXqos6_X|vLpP1GwwNNf5$`}$O$jO1G@usye*R8l^ z1Sm+4R;Gx?_F_s7WFa?7LMUZrwGvq2N36hCT0r*SSE{RF?U-a?4?9O-afUu-RdR=o ztQ>RH4*d`y$j7%ObEEgV`ANF{2WBho!=M~ZdKHryzIF?&+GpQtJ!JSFE2JfLqPyM1 zJvMmDzMubnE?W_=S)*0f0@a?wJ+sO=`t(*-MQ2bPf6sQ!Yr_B7QF1sXod*0;S+N2x zaXr0i#$Fn!YK5J}b>Fb(dDPFFT;V6+@2;W!HRIeX`2PDz>&?~Y9o$imwycM~fUz`s zF(-<QW}&i%e&>%GtaCI^FpyeVJZ=W8Nh2D23(>U?ryrHM$0MsA5l*<eMnF0P9*zv2 z*-4SCKY9$X$^Y^ahc*r5d}S;+AgN+!%fYNXMnc&zm=T*s6VsLQG$#Lq<DAg(Bs<6k z8HfIoj2*d?pU}i$Ex<Mwu9(wQ>bGk!2>q*XvcyEZLXfsbu*e#3sSzuN{tron_!K=7 zjrUzOdZR-a-fax-e7-nMEDeZJp@m-gSM}q@@0}(G^dq46DBg3wNleId*HEeEKF(A` z(ZFG=`XOXq0D$#AoYMlOjfWZDNte9JJi-#9)wv<>h|(hnm%;iOh;q9*6So<W>D<KX z3l5N04uuGXNJ=huD1jmnbwML4^O?KlJDx0JVGG%7m_n4H<ZI%LDA3f+v6bx_riDfP zoQ@^ud@nyFO&bp2ql^UE0~a?v^S=ki_4O`5Ms7os^vG0VE;U{h0sH>0s%Be0DwuU@ z1s2aN@^mJP`CHp^+<h=aP(8n34P7M7Ge@gJfx*=g#Ba)=4{2W7Mgg2a+D*Uq)(FSK zN}akphBS)W#jWeTO+$fO`s`Yg3kvG}Mn+sz&0G}rzx{)1rKTBzB?VjGYy<WR=gZGM zjS9Wj{{&rtWw#5Nl||tvUGmnyGe6rhK;ZY0l=4Bt3LLs)<na=MaQa7%-vqcAy}}`u zL3ylsXwckWmT`{YQMkso@arsMY#N1|%RVjf{W0p1n`W}^V6~GLP#WEomd6P_zJ!L5 zlQ;BdZ}~pr=UDx~2!<ZgSDmT2+Gi|c;w)`d<op<;iSCiYEZ1QotFbO_QGmF$h`}9} zJv#y0?KcS{3C!qBg%>jkJpJ<x?BjI#!|WJu=J1&H$|nSoI(QS=3}}i93}4G1FS<^e z=Ln{2c40g6ChtD0?t^cr1x6*cO%3P3|HTD;$0+&U<tx`+-XWWn*<o^A$dB8A_8+d3 zkt5!qez|%cH`v%6b?@fl%iKDGB9peIYtl&#w{_4-WmaRsJ_S9QuTA-ZaX>HO^}N@i zoA}a(7-petW^?)(?5L}?-aoIyhStlE;d(xa3d(kiV%~n{I-A!{_1_}Y#MmX;T56Yv zapxq$c=CSpc&+!ePN7zGqb6#1(N(v?WP$;n;y1&?(t{K3f7dv04H9j<dl$uk%-=OT zZNOv+Dge{veTB|8^SR;NK@I@<%>Iui;lcm?qUC-1{f58&nx7?8$n*7R=X5dcy5W3m z{hzz%T`K?Zwb@qyaQ)J|J)SA>_Of$B{oE1EK7LgHtEY?be5I|;$M$`#GsD08E;7r_ zdOXT`<E*Cy+NA-+BBu96PL;cJjl2Dl?LE7Eo5z$EA{Eqi1Mf7!z@Dgl?r^Fc1d)_e zXy%dY!o95u#?%oohwHBFSCTkDAdtj54enOru5bMTF-vT&dcG{5{na)$Z7cmb$6zuL zFqCrlZEYxX$~$o376%UNyY;YAEx6>(ENmV9Mz;Pa_eEm0RKzGW6Nic{QeL4OP6<2o zcOWjo#*xwr-z}!9wAAHHVX8uXh=P^oOw7V5bZ<94PsQaH27atgxOu0uijOm^<dK~` z+tbwx-)p8>m+aw?S5n>AJT|Rtw~}ftU{32iJ=P4i9KpH>!g`vV#I%l+c+a0xQ!t6Q z2gn9Ck~o`Veq$vtu?hy<O6hFap&48DF_o~rb;gMHZ@w`{n185^7x)*<sMh4G)BvUq zzlcj5h2TF*(u#;nENg?Av%$Z}a_NyLUNT^V_s||>+RGAOG9fPm51R<6dsPi^jGmLW z9f5BT?Ie^W6<$4#5|3Gj@Amfgk{q<gOmQ*C4qX>aUWqxJQI}yW))hO)$ZD+uMHP+$ z-*ky9kL}1BoqAD1YS-=Ygm=h*&2j=IL|<EjSjqrA3p{jM+}>=_=@eQ>tKRWS+i<Aw zq$(F!kF5&^X%A`u>P=MH1qxN5G(FU^jql+G#*&+(PvVJ^Lw%n`GoSX~LYh{&OSFUu z-SZ_x(?NJA@r>WpEnI=*kQ`S}`J__SDj-m$zsktI?X+Dmom3hh3jk>RDpI;HE@ghQ zFG6vsd}!kB`qe{(FfUGRaJVD-x>8!$4bprNU}927v6&%T=P(4vN6U0|ebyKF>T)%9 z8tAM*HY!`l(D&r&Zv>v&=KA7I-`J;vgdD~?gZy05j^MU4s`ZR%lL&JvcQU(PB7hZo zgMoE-bpDMr)HgG5y`*(v;js%kt>_26{PyEEZIJbV?o+$>@#@>!Y1{Rkz<5ok6gsIO z&_%9IZjQgMj4NLN+8zK@+<tQ{{C@5B_3OCexFXu`^V4fD@8_{)S7KGgc77d9wXIL% zqCdZ9&aeHaPgP8FfInLmemS^ve>N?5-QP{8bA7*B4qS3fitI(a{@#B3eW^mGeOR#u z?zQR*Suzzm07&a(Rv^g!&?tZt8AIJC;`U8aTPKoJBh{IL!hW_D)iiQTU$;`;(IQp~ zQb`CcONTwL;vq_@HQOE%qjjkt7i9+{dV(94D2>x*%_@aY7LajM>e(uZ0=9Qyh*wun z!|e8z=xqicv41k3rrAOn5jSkm3o;sII>ag)A&9L2O?;_rEc(3QZCUT<v{%i;kpH1? zPq7rACUBgJJJBx@q+?{bR(p}NBW-Bf%}4PGK_9v$QtN036g=Pm1fXP#mRZ{uN-#k& zfX1UItHS$qvysn8o%P?ab{7Jp&40SLtsWl0F+A7suQyoBQKO#mHXqwtuW+-qO_?S_ zyT0OU9>A>?-?19HbG9L7hW-paWO$?-lD0fG{f@hFbDcJv?3YHAfR2X7Lv-8Mb@>;r zt~iCkaPV!jD(?55=et|$(uP^q!ygU!(bt4dYlPsRA->(1I*&c9_i|bqH?3c82*P+q z9BArOJmi{Hl0I)w0*{*ta8)yd)l~wm@af~l#>2+i<Y^l}O@*Eh(1@--uid|0XT2Pf zy^i}l9HRT&0J1%rET79Z;rB7u_Y=VI<?iKXcc1$#<=L>7k>1MZbHDd?34r9$(T?=( zpVV~LBF-J+*7r}3)+SfGyJ64X9aMajS%Ga^5+LNW%cnx(8~nMrC%GUjBxGqB_?Q=2 z$b=@h;+?nVh17>JBIC~~x6K$6u9!?G(yaFZUoxm}4U{h%8Br;ZBSokaryZ9~6c<U- zn5rJix{n*FW$Ajv$}DO;T_7Ic8mZ->KnSn>F^GPPbw_$ZY%m{+x?Wj=Kc2F--PVhP znv)`MFVqRK1|#>2JluDkaJ^z`WEX0*mN(cTiwG6K4?bUHB9Gpc@23V~=%Q6GAPe?W zo<JRQAgTV4`)&W~_a8K6(Ox=3a4Zhh+5)ZfvA8+{g#26cfJzY-KO!bJ60}xVY{`=8 zM?K<1EL<RL%)0oJ$|bhU9NWt82VM<KkhZjv^4|^>y8E)UVV%7Fzmlw_@g<zc;+jhG zIE>0G*|F5uN8wb-QHjq9KqA=o&?T=);?j(yfPwNPX#`%ApRPtCgA+vVlJ_GX2*sJM z!C0^{k&%b^9-~%dPM9j4l>V-}m;!=+qC_y0_k{?(b@62kWFzIfwa)cpTy~9`N^J6j z+#Qqsr!Y;LgCG(kFZnVoF?Efl)S#G!e1w*zGMz9*bM$;lzQX~RV`+}lFT=#<X9|g* zHsZ}KrbiW;X5RS#7na&;rO}N8F)*YxV~s6`33mGa3QO0g72;$e8i~C3Ox#5%H|(HN zLxI10x8{{)<jrXJvqTWV6mgDhv1I+*GQ4VxRvR7ia($0`8&e9Y#K&U-Qoq#t!Kurf z_X2A~e$IXsVUr*b^Bolf@@?+`YLnbMRjZJo_b^_}NYG4wSq-<X;<%o$&!gY>`?6)v z0W+4&YlQg>{^!C9{j63#_hH9g-miaK5wosrJnx=vE{a|<OnLPWeB-Qaqg*#%U-@VD zMqS!l!43Svs?fFr=`;d$Pon<EHoF==w;Dfw%$r<-z~JBeMH#(Hpu^BFNwKg!08@qq ziv=5`X@?oDivno9EiH?u`-(rHR;Fo|`u1pwA!X0Qa6l6X`Rbx!m>S_!6f@yl@TpL@ z5*BZ~MTl$W6|oL~kl?{R=_J3LGc&hgPGCawC#;4<K<c9;3#VbSHO!U~*gmG>=u(OY z%}dk6-dP2J|2idO8L$m!Yq6CQlzp89ASx3pK-QwtbkOkk!yA)X_Dj<&?GEx#t-m8( zm)0q1pq6WTdhz5$D|F;0$o<PNHa0`Q6*0IXrJ7^AdTi<u4-GqwSwytTA1jI40X>R; zBLY^zm62Az!jn78r>qr4pa76<v9>QYO!R0oZ%lwLsMbG}b|~%%_M$2KGP{en<MY4r z_9=tI@ALI}fWu2D&B(BJAl4gk+iaJyk>V4>nPou`{*qfwbs{c`zgNPjVKP#zqTzI& zBv<oh<aPw*%Di@uDSFK_9y={Hy|qAx8GT_E+Zj|L1^3imxzi!M7!eTAd8M;#aHVP1 zb^=DPk|>v3-H!wNH31M)#>M%nKLHXZat9YfP0N*P*HbAJRW_DBST=|f&G5~T{)1B? zAC`sIta*1Nxl1OeC2L#4BYGuR|3{(VN`s%_ISz@H&&U^jDa1$&D(44B^MoMRkLETo zc=hfv+69McOvN`R)+0oK8J6W3#M5tkq>%D|k6!Ih_4h@lmQLMNPy8Yv`{g3+=I_sE za00JaVIeSO7udGny4bi#TYuQ=kNP)OJc50BIXTHK{P@YXYk&9lF`cIA`>sz>ubtg} zv>C=wtXsvKugCKaA8jYD+0B&OIZKCi`h?z7nE@i=A_yL~xk<J~1JTo<@|aUTTr!~p z>eOUNq0|7}9YU9qkh%&}JJJP6XC~c!HR$HhTf!v4&q*QiU_M=%Un-0WwP|1v%`4Uj z(Xml;V?3OXBjiPu<N(IEz&L_i*Y>x*UwkQTuA3WmW@KeJ-&B11hjbNsUpba$WHp$( z56Qi(76oC6+W&3|TyQ6tA%hN}vkz)_v#F3#8!0mq28Qcszw|GJVuvA&A<i-`(A^^8 zm+st>h&9j*l`m}Y!=Gsu;GNe5il;bSs9>nn=Sln)H>^KqS}NBkHWguuvB^`K$6G0* zS0)$94Hn`{t&ejsqPRovmGLNshKMg|a*ao)MOojt{bK7hkCE_vwvEEhj&KP4pc&OO z>_El1WfzFYjfu;5^;pn5V1)p1jqf{EURQh;e?N)(5^vWzxdZ`zuyj9O->r_*-`7g~ ztQl)DOUnP5%$#pqGkVSU%PfuB#=z*1kyz(R+%PQ58N*B5dB*r#oG@hZZIujjBSfsx zZ%tGlz!+waRMSB`EAwZkY%y*h>D+OIUOlimy5L>qD?yEu-ce!2Fuhc?Ou}*%T@OWp zM1mZJGpZ{u{L}=}z;9<>+m5_WNx~}sjCqxjISm)Om~q})1QQRZCBtV54}n3{#;^x; zL4I>7jOT2rctyRK9gFM9`_I>yF`Ew!CYji7+n@+(#>RvG;NYw2TfKiCmoK|54g1fo zL;gL>*A36EHe{qLp59NXeYTDdx&x1T-iZI4J#Dj|1$`b2HpiD6Y>(mw=+3*vmD7m| zvOp)$^K$_1sAB$K`S2EUWm-6vOTvOvJesXcqvbC@2)%ZPn5L}Smx?jJmUIFp16J9L z);}a&pi%DZNvO$cxU{hokv!ZZDaXe!o3T3f>Tq#FU)_AMmi*}KWd1L$V7hFxT#QiS zQ|;=EE$OX{536;-aucW4#R&eZ6kit?5N>qnv0V(=390v0R83Hh8I7T%9`Y7soW_&{ zSwWxa#~_tj8-YlK!@b(;49Q<wW@eCU1K^fQGD)9m-3=$Qd9iAmddy@ZN(vyxR??9f zyhv!>nXq4!HK3iktBsL#wZ3RnUjGJXbywnqIpPQL$vzWz;<9a}S2<&K5>pwUG3<}2 zBq@uu7jY<yA?c!+;|D`Z--7TQW)m*&KY9g0ODabA`}=#XCDvN3*|b5IN1HaqDHlrW zvT7SouDvZAdC`P#`M}GL;iM!StUwUUnq6=sbL@Lqak~AArensrg8~Q^<r4@O4uZJH zrXIg)D3oBNn3&FuDJ{AAI*xnBh%JlwC5|k}7ia~;r`D55o@<*$xRTRm1UTds-dZYW znG6!)N=n<qjygB%9-GsY7}32IXfA~VdAV4c1$`NIOx8+=K_t1ZbZc=06T`&QuS(}3 zzlkwCWXgHclUcX|K-c{Y^k!P|B>KMN?ola0^hzgk`-6{xC3xlrR@%K#;DR=kwNiTJ zp2NhkINkQH7wUgd+)SNQJWWdmXl9Gi{C7Uj>W@dr56wjPmTS&*fK8;wsQd8nFdUzy z^7`eXo9yl4dHr4JYG)R4UyzQ5MIT6jg2QLQ6>!FJqcIhc+6{(D%o;(OsTJD~+qYyP z>lnv5e+4y0(#X*=dj{w^PZs?lvNa5r1MaQp5GuJ^D39>WqD`h)2wcD_<W?WBXS0gP z-QJjwPq}3g`fIl=@EV|L{lTmDrH*feZnKUKBK|qeZ$W}HXckf3{V*9QXr}x(b-4M2 zn7>(%v5zuRElPovQ4C2Bb^<yOC@qvjNWHy1m|K_i2Xv$o6_VXMim%0KCzfsmD(S<l z{c?bs`6Cr;3n+##H*0B0qJ$k!)bEgT#hF$i!(+Ws3?>nHTU3G#C}Q6)XpmfLDq(H> zX#O^EpiNJ;rX<4*R#nvBHOZQYhO4~LIL$>dLdU6vZl~#DviivptLWRAFUH2gm{J4E zMcARRBeLItooDTRFcOv-E7?c}Bi+B*M|aBP7;#H0(0EtD=G(IA=s+p~!F1^SS#kIn zVqcT}=ht`#kxptfDLXD}N6DeToa;U2G1Q(ZM7%F_>x&R^K|TdN$q_8sn+gz}$=Z(J z0$U`dTTBqhKGPLE2VaNEAk}<Fe66RITI3WMReyK?xUC!VEXiwKU^MBHr~a{?`^gOY zzJD==$|+A4c$Y|?l0eS4Sb7im9woOtGT1Virg)|(=tpaHyn5^4=uW7TkJTAxwfKY; z2rl6p|C{tTAtVwr_xCVX;or|$r6)QU^;&MQ;uUkXc9viN#-&1wbE||hn(&Hz<P+1x zkX!6{P{hlBfv~<=%sba#?60=mIcfr$VRe>aMvq>S5bF6NHM5fECs6B#?v5gM=hWpE z=%3ZS2%v+-()Vq_NfkGA;R&ZBa_E24Z*%MP&&k@m>98*If|D19{jjSC>LpoguY126 z{Vqh0hKBxuho3)tIyV=Vv~xY<+Oos3R9M@s-3#<ESN44Gj&4HNYJLHyGBopf9I@nD zKb`*5+fl_^7(mEuL>}Ybf(F~Weh{JQV^w7*jF}l%HTab-&Gk{T1wx5A*N3ZO`FN*B zQxn7fBOcJ1J;(YgYDL|MzS0?^WJ~J)sY<g!A!4gSJrWxC8{TpPu}L6ET5O+&JSgQ* z7u@Zr!}ESB;;>b-<B^2NL=UJtIvk!P@n`{JZ?FscXWYRaZekh)Y>X3rH+E3AXqT_# zN^wZ_^YCIMTGg=o<o&5gt?72~IjlEK)FF|nt8C=qaf>Ahta+UGCYtW~Z=VGRh72`| z(&n*JU|f#gRZ2fkt>7jVtOPCXp>-<AnI(xe)oQP1e?bw0XWMDrGQMctvdm$}^I<Wc z*tHo?z;@k|G#&h&ifoB~p6KWdIo5L1fSGF}!&=%9*reK2yJX(k--r}3v8y`y?3Oka zu1t+4PMea-ZEL%P(2v_x%ed|;r(fsYNVm|IzaL$J<I?-fWnfI~o;Q|UWy$T)_@9<x zpTO;G<uap2Bj+ERKIiX8nkh41A7g-ZIVQj3;pa6RSM;H0CT=gP^DIrbMnOTr*Z(?Y z_cL@<U;#QwljY@i4_K*vZjWxpGCTpjZ6S;P>tNQ);D6~|XP)cNXKC{QvRhct{c-DL z=jL>|=4v^5D9QOQ8mH;oTVkU?28C9VoMS$?ILcW1mFQ(<(eq*Q)gecrN8)(mV@PJ# zvP>$2hF7nfJx|wbiA7qY)xKXPxFQo*C^RLI+<GCDe^-={eC;0F58&J%qD&e!E5)k^ z#R`K&YSh6;hHcKPAV!on)oabc=m8Z&S}bPj4VA+`K2*I5=z&@TCOPGP%qO&r)8&TD z+a!b)fzpaLIA6I^`$^e=zO_hV6&T|vsQ7}@=C@kXGmP!X<qoyep^S*>e^uH6aoC&b zB81T<q(Oc=U&Qycu5@gQ`!qo<J^wcO1O&u$T5Rj=v~mwcUVs2VR);xz5kU<>Cgn=A z;x1k2l*utjHJK$0UXaLluD|`sAA@Q)%Yt>B!lqG}m`J4VYU<SuG-+7GX?)uxFltyU zE{{Y**QvfoL~-aJ(AXA?Qf_k>JM{#9Jc1M&(A*}b6hP{w7m!iZ+4K<4YTWBI`72u2 zYIOCoGOAQqC%=B!xTf2xamq59?!r9=F*OqhVTmcCC!m!F7g&F(QvuB7TV8XdNaX@3 zwhR1;CvuH?tZY+@GCF!N;6>(5KCVCEW(<?CPberIV64`6k$TG2uQe1Thx>G>A5rfX zn0hIx=MfYU6MpA!gYU}OYovsiPWzz>9Q&+9e?LshV|E>&4o1hlIKPrJ7#QZ|&csHJ zwFvG2)K~sNy|C~4`~jH6<rs8FrOY?cB6JDAKOFo)V}_V>L}xM70(ZH}mI2dkx4q~b z3{gG|(?+ys$<VW*W$AGohf;p`usRrv#e>VVxZ9VJmn^{V1W|H};Oso%bw8rFs5kq5 zAJd2BECiGtSpsStSay@c`}vhIp*YA;D}lncZr`!6ZvcjTEckbW>hq-Kykp@?lkRV1 zF{W(0)-JzV=^NG`2$5QY(3nA6?)+G6B+8ZkWg@XAhO|o!!6cIG;n=#`Qs)D287}LT zY_fE)L4Cg0Hc^L^CxtYKvDG8LLGFbw9eak1*cumD6=SM%{s`!;c+pY_!M2LSuD%Y1 z`)vV^Cu`8Q-K_%ak9*whkL?d>?GN|wYwt(ED2B}E1+ii%iuC8p)=uv!zh|)2J@~2* zdRJ!eY_l-yr>qv?A1GDUT(W++mpGrRud*%kLBY3IxR#uG!>UPys&;i9e=GY*1C67i z4ZzVbi?IN_{4z-UJclfjWaLczpidLp^Y$J?4C)V&(Tj>V8Y#p;B;#*~lGCrtl#{K_ zcn*I{tB+1v^yI(j{+hw-%2MPuq-xNLVozG)IDx~&75+|=dRSp16;kf&AeU|Um3GGp z<|0oRAsS=>;`6jY3|=Cg;gPRM#M=O?Wg}KgS&CiacEli$l`~dIY*VDh_TUVHtT5dP zOsr|d7KUT#PilhyIL_v|qex!L&o#0wvX4<H;uK;xgUkk->QuTV>N?>rbCp+ULsH4j zCQa=A#Hgq<yndVLzm~d*r9Fa>O%l!IxrYx0*&=JJ4;?>^mv?dQfDtdNVBw?KE6|Xg zj%OF(9U0wuEmG@c@b!oB>sR&-G@h~8Dnet%{%vAKoKYb)2*EbHy^G1eo}=gr)Z~0u zC8+fs73;R=jv!}_V(E!EpvRC95loWE>h(oC#T&;OiM0x5g<oau7{d}MDKnsAU_7$` z9~zM`=3Wjl&IW&0#2YBl^Q%<aa&s0Rxnp&nkWV9Hqo36|U^Fee!FJn{aYR?;IS)1~ z_E9$ro{&e3)M8e?Dui;CAO7jxX>@nRDcl)cciv6;SV-Xto`A>B-DPKv8t3B8Qz+TV zw>S(@WrRtj*uB$h@~Ic?b&Jw)NuVnPVlQIsihC;4I5p|GkewZNqvdXs4)#onOy-3I z^<qpk0X(xLcPkG4xS`1ag!cX{-c0+H95&Of3D4_pdrj{xa;@xYIr0Icrf=ERcI;@p zjt?mLJ{oUNCqS|(5WQfa`7b}Evd!_$)4>6YX5@0x+lC$OSg`m7o>=&Iv8RzR=&9%* z6hg8joei90QX{m71R)~4*k{wB@{vx8TZ$i>%{PH9q~hNG%3kW4GHicP3lt;fZAg%x zhW_g16h1guF)WONoP@!giRq~ltt_7xDNu5yr8~aSqa}lapy{HSm};@O&7BORc{8)I zWG9>7xmp=}q;K7zKZ8F=68grPsPk1KH{%lLl!%~ORgTlcGh`!kU@p0J)Z)b#?L|77 z+$5T8u%<#kISmB4*|6eJ7$rd=$AVoFR^geVji_$ye%*C!1&MMLJm5;B7)p!YoUs$I zftMP$E{8&OeY;cVCz#Rd{QI0y!b!?Kl_v7-5n)A0EVe?{{(RCk1}$YrHhijXUa3TI zIpD<;Gwj;3i<j(!sdF_*uS1YqOSq0CFq-;9_LXsVefFPt!%KSR^NkY>^H(NG`ur#E zsWkOTTxhO(gWV$GG?0MG0cx$3uanpWmP@?W&F_t{CU(<bVn*N~Eat<Y6it2)Eluj2 zI))mo_>tYMmTI-E5*djDE!mQi9SYh!^TUt<Ci^5{(u(0&Tq5l<s3N?8iY8%5;e@+c zlWjqknE!S-9h9AdMOdSgv!gMg+tRJU^7RFcMF=m(4A%zDLuxDdOXU9^yZW#O#w!=W zj7hC{&)r|;${anLk;w@L7wb1J(d?$9gpk2ZwvTdAlLPtri37bAB1r>E!{y$FV|2<i zPIk1b7b@ycn8BDXc1{Ck0u6^x9BDs%;7-@~I1L+p?#J4?{rQ1R#(m${tE1<=6B266 zl&gjYfuls9*XO;}W!HVc5Mnzv<SHxV`LwmM1|5~+dcMl*>FHv3es(-PFVGX;zjf8- z+1U86m4uC9kNZW`Y)SvMF726I)7kG!jY3O`$;O2DU@Txy3wJsc{XMvYfX1S{t0KT$ zfTkO`kxxY3ncqIsBwpS#f#4C8V<Sg!Dt%85Q^`Y8$@x)aX50TWJr9+h2_i-B7VT(^ zPRA&r+zI41iCnd$p|Kdv)jcZ@RlWaM2&}$ryIeHSmrLBqe2^EMuNrMgBk9Mcm^z7O zEfB2NEh2aig^4F?7Ep?e7ou`^f)|KCQTGwR%I_l3H#2{v9>X}9awr5dlK&czo*y^? zO~X@6LTG($NRc30h^$|HOhxIED&28(n3`=u^g`lO+hWdGPh<yi{XQ5W86P(0U|P;l z^!f5ltzfo^Dx@|9IDq=Z=K^O)<;2#?-qF%?vEy~i=bd|^*r#gP{7pDb6I)MyPUG2G z9(TVmv&;j>F~Hh4l-Jt{dfv$FB#6GMs#hb_7d!@>d-HvzoNdsM<u8Fiu<&QHZmm8( z5;$>`FfBGU=-ZP78*pV-zD<4#J!ZueDu<@zc78IKTzK-t0BE)^t!eubtBqdkZ$#-r zQZniU)*YdWfhT{sn_gt4-Zt#%Dg-I<<UB3^&8Y4F6+niA^2yE3&TRc>K^`813LaF} zwTw6Kp@EibmPZhesq*GEbOvs3&e5sy-cJh1r)pKxLobsd3l}EQMj*wDq%T0{$R|yO zBu|IDB)0^E%k`AwUCq+SG9MZAw`LNxp_2mG33a$Rsr}S+;Ps?G$P{h_J6K$356}L} zZ@jzH`{&k~#-f)c9`pR%ioY)8`Fz*uA0_R6bFtkY)xLqbH~sbf>ak{D-t+#?%MbN( zx}C*Eg4vfR*29^egPN+ix21}A_`c&BpZ7O=i^?ghP%DjW|7KWFkV0B!k&>)=e!<v` zPCo*gW9KZ)H6iO(UJx%_R8NR=2q!W@=+ZY4&(itq*N@#4Of<Lwl^@+_2eV!${OBeB z?res9ZKmzh4EuB&#tc!}QXt0)XVa1@HbFZ0$pOptD;o(y|LgMSvVVTH8o?y!KoP$i zh`kE2XO1if)xvSrP4rQY>JQ|uz!oJv3})u5nO#aUvws%ncWbnmg)(t-f1Vu%os+8k ziVJv_ZXGe;3?ER+`BKdFN+jGypQoziO@+1W2E!jKW1rnZtlQ_hF^4>=MvggSKN&IX zp7vBK6Iclcae9PQS$|hSuf!=h*0tq8>m*?^Pc|2~Rf=P-hB+0<HeHH|ZPEICTuXDX zAUG!-WYxm`RW}2!CO&!?9&C2n8Jm;~VD>F*0s)S0{!`0RQi!5_#0|BlP>R@>7M?=# znQ!&SIBLu=cqeSO@GN&8)OEwr!=1;pPlI4G59tIg)BQj@6T~$FsPH}=skSGgRo07& z7ajcW56AJ7qy_|$8m7fROEoyVPTs^^+mVXdtBv*jo)pPfD?!vNdJ{x!HJu`LfH&P4 z2DrfetES8rLu7%ClxdUrV8x#n`CzkMmXhIOIoK6bKs&;N-AENl{5YlW8(5u56XLKi z6$X`*7{iJ^M|V9#hP8eZ%HHoHsaY-Ov^GdR*G5@$Dep1Lhf>FQ>WJ?n%CEyT%;%eL z(Jij9j3%rgX{R+*Y{aK0HF@owW{}6Gb`8=*E|@Q*0n%&nJ5-yz&CbU%mR)VyJ={I) z&ZCpaxBk<o3j4gB{MTQZWdUOe1Xpy;HB9u5^u+Tu5;D>@UjAI^w!X3THt%lATOpRI zhI^ay)u&ngcTba?A2shAqL1X7XoiAl(BXa2mk}V$(5<y%${%{7+dvv?Wv@aBICMnU zq_Q6n98y0Wb|g^791wqWw&TOS0Es!#wV-#g@2ZVLG5MB*G?WxW>2npC|H07Fmp#GF z4&cJVB{>$0EyQ4sOenfN@6PNLr^23cKN?73g{mOeBKc1KEX7s<)S|vNbipnMN)iAU zUG?xzpR)E+#L?CdsFFt#L9uzsQ(TG9ow$1Qv-v=pK?f71p6{ZuVtthG8#p|eu{va& zFJLP>)LN7rpC`S~b%F*$+lLTOfgfSdyP%w2M5!S%ZaxW`5wGSnu9q8a6hWR+bnuNc zt!`lGRq891M^61D!Q6X{YB?pLZbmnB)LN5F3mKF>i`*Wo>`UZg-?21_yZ#qBh4d-t ze~TsYb^+7I%p3v$4l36@m0N%Zs9KYH(jARBQCNInMBa~7we+y|*}US)_YXPoKiF57 ztBBNdR9ic>zm)$M1{4X#8E1%Rol9B1%`ew&hIEu65|rSDeJp9GcIie*oOGizjpTIA z;kDG5BE}wV3+<P-r7_cTfMii0xw4^kYrcY(<|qhj)-e0$A-b-e<N<5(fqdsg&&1gb z8VIBD6M#~iy4~+gmgJwu<I%||!T8!gM7KggA)&GH;1rhE?|(9=X-QCBg6uW<yR0<T zO%e5fXDKYsu0clfW0vEG;+s@ut%h-rILlN@@P?;^TrWfMzUD|!p`%9IxY4bB1+=n` z2)++)I5RoOp}-QR1I@OLzr9A^=lkT%ZdGcZj0!WE9$R#y;@7YG|GeA*&j0me_&$#N z>r*^>i1yEOz}M-upo|(`qgp7iH1{=Hzpc0eY9D{YK*zYysWGi_h>x3F(Yq%;CYey% zoO;M*1~I&3S3c|e47ULsewsOz*gdDP<_x>Fi(%Kn#C6AZ_9~zB#;L?AE36J9djWGw zg4+bJ5rF|#)ixZXY@HD!;Zy9~j^8*b5bsI>`ZHJ546Qari9BnWL>H+;V5+W2gDH`Q z<p2ndvtLQz3Df9Lq*Q8q|MmiWH{+tpN?iD2F0_kCOA96&Em}8BOs_jIH(<v3+RNj9 zqar0pJN*^<@xhV~MAPO!<R(?AiV#u-9T6XyO8E)kEb@G7wkgIKwm?KQf?<+wP&A58 z3zeRngio+skRAjZPz9I>3KhxpPBE$T1JgUhm8{BO=CW#0XNr1mmxZ5|u2?AMhyEI1 zm&D)HEK<P4gEgbpz7nHd%?D^#CPRUC1)dKDd8fWE*i~Q<^|vpx5Sr3}KtKroiL@y+ zj?V2zeSvR37_$@XvV#MPd`wC=GN4x>88x;0t!T=AHedm_3#cS#OBLk*Es9Ci-m)_d zGLv;M-+ytk0U3vK<q7d~viT`fjJk$G%zsE7#9I<Fz5scYv~tdC+-KJzW&gh__RDVO zB9L8%yaVA-6+W-W!1zZ8P2f+iu=^F@^6@$ph8x!MbG^O4@!-HT)Y)L%WMgNzmM<Kl z<!3!J#*eCK9+G7(^_050CEAf`$O|_sGO;LWc|blAtS-il%3uoBI}A#y#;M3?39d=9 zpx3Nc*3vHZc^upAkmyWfy1Tl0xI0~Kd3L?C%}QFo`u?_RtBd%${_|pka_twui5_^k zI9QuD`)YHpdiqi*{CM)R`Z!JVbzHCA-TR5q{d{e8Iu6_6EP>_2<;N$*SH;((v5J=^ z)HW!en~k5U+{Gm}oT@<F&Nik>1%GUJZB#N(7jp>)b{Ll#B7Tg0m`Lr+ukhT!c~)Ri zX1QOP&99r{tP&DR-n<XZI--emsE+}|CXIE9WUCQC(3yNe53%r(XM;y^<b@ZxR@eaH zd}m)}&BxQ7X&|(1@43$G^Coj6`%GHFUT>dn5Ap+LtW++LhxPetvDSBr<HOcTW=A3< z|DoghMD;^0hS>m)zb0IaTU<i$<c}UZgK2SVv9Me>tSl8nATVuvwDqsTmMnMClTpAq zP6k3SX3(@H|0A|^Dk5PkLz6I8!<nfJudLA8__--t^{M#gOK3!h((xiPN%KuosQ>Vn zO<Gp?B?K%c*}z@Z@j2W@GWc4*Tr^WWLKC$Rk(~`S=TwI&&aKZlWCazLT&t5~0So#h zG77(3e{51snMGPp#ANaxi*wp?UY9x+%vYdRrVAhBP@m(PqgNb{cJ>A5hu^<&O41!* z63E`hmqfuHMYGy`P|7vkDkBr4-f5~Q-}+_<rb!b!G7{Z8R!nm0-uR*aOc)!eImCLy z<5MgCq=_(W-Wq?Znj@qe>Z0{`+vbmPQ<q9dY+D`sWa+g1A?qhT%-bV?exc;cp@h$B zwS<?yhFx<E@+c``<W&7)lqeVfg4BHM>~?hoCtwRCHN8FVXSKUs`fW~W_`3hH81e-z z8yME=^m(;D`>N1bAjR%0IDb{^5<izFKKh^;W;Nqxh=OclJXmLpuPs3sy^D3chPl-e zFR*>*bXjLv1t3wv(O=N~4mxw;N!g2kMFM4XCZ$*E1Nlg3a>g}rxELE$BhtVYNhkgW z*5lc#&}((j6P#Pg-t2rSzrczE383_v1U5aLoo)X)Q3PPGC!UXX5!t?G3XnswUcrn| zyLfqxFyJ=b`WL*&8!l}czwHuvK(9SNW<3YIHzrpf$UHu5N3~x@+6w%9Nyc+W28>BU z$gt|)ujo(0C-`)i_?oN`Bys#navmUu(YT3Nju?_QtJQbT+Kj%W22?6ZctP|Am`oWn zXv&?C$4Nt6r={Oc9wMO|N;V4Z`=ixbDS>6G<cx&|u9~9?qEr5O1_v`3G0~?ti?!r? zmbKcrK|f8>{6^JWN!^{CZmxFawl5vV3^uoap@;Il!v|D#pE032eva$q?d}yxOp6K> zBoA_990||wX3aC<01tvbM}rx0CTAhd5WE?i)<R|^m&#9J3cokL%)yjZBRLN_>%S{A zH~W-{u-+px8W_@MqE9+5462-mTw}`*zD5~vGx~eK3W#HxR{0c&S|WlLodL5CWHOVQ z*%(D^@0u6;dA)b}+pSJ59DD#4`#Y(er=(w~`iIKKcgnnvk)Z~-ma>{19FU!p+haW4 zY(}i-t=2RjQ4B_s`xa+CPZ4{(_(m4z%CtL?R?qJ)W}7<*Q7oGJh;pw|BEfg&Q4suM z-IN3^3c>h%YV)W{_SYHTZpACa>=MAh11Ww}NlHiG>0A6>-`EvNVF|BkmoP@JO<3%1 zAxg){u*O{*Fd~*v^oN)YrP(+CA%C3iY#!ce!*VGg@r(rycGwRB%&f>W=2wF%u}zKZ zgPHr>TERgLgHI%!Itn_z03(0v@(|!h1H>;n=MJ5&<Wwk?7lG9xC2BAVVIcn(H!)L7 z$<EDTe3s+}uZtPvb@yNUoUla%)wFMgb5&-E{-o^)E&kL1np#Ikh8G8-$<M??tW_d} zkgt{wLmbpbS@7F{y2RyFn$d=^F_J%Km>yD`<+?v=Bck_PR_f8d)e+;XO&%<s0WXkr zw34L|+H+ur_XA$@Y&GLu0L!Sl>$+Z6%Eo`AQO$N;>!o#j!mc%BM<$lM38n3yBrVVb zjBVqS*-BZd^~b)#Ly$yW9et_!PmGZ>XtUG!Cx}&--4<mUNQ~Ni;!g#=b<beAS~e%b z1LxH~#x4)f1LW$j|K1|sAB5jGFFUi>89GHb`=k}jHYbz#sW8shsmb-*y~RK}IB=~# z*S2q?S<g*b-7v-^BxC{}4{X-0z#H4^{UYln>-~GgeBld5siu5l>+A$u#RjnFVV{hv zDCLYKeFoX!>1E|>va->l@KP?ugwV*(#MB&6P}5i<QpQgl2IXrYch(!v(V8tXG~B4y z8!K|C=;*q4-f(*r7@Oc}tI#>-#nTeGP`fZGz2b8o7py9L(C&%$q??Qi!;MDi#*+MG zqT4~xHPQaI(dhW4A9D23*DX)%h*jKym?Y7H9zH-Ym%)54mFU^GoWkA5@^MRIDFOhI z!(2I$H1o+Ms^;2J+EsZNSu%;_xn79aCKAAeNRhKK!*vx!lmv~a{?PZOUix4gT5`u4 z1RB(VghC<81(_S)xv*u(nNXe3^IFNESI3muYJ)V~`n~atByaXgS@)n0f>IWI>}<(T zDB-xQ<MQ1U(R8Ndo%y~FVEQ$a67Sta?CbTbT;%g;5Lp56UOC9b=o+;Pp#50PA;pW& z&)+Q_X|4Nw=na)22*+Y9EYDAyX)y=Vo|vG=qf+HLnIM{h0qmpZXXFO8(q<LKv(?)_ z$E0Y09#DtIRytr8_;~}A+RIOx?kAnYlQ$o)EC#mY(6>z4Y~|Z(-<4?SYVE0m=rizT zzc}<tK_Q8EOtq%l{uCgu`Ok&0o_Y4ugab%mZ26Y;6nYvtB&YhILw+J7P425=<rlj- zbgA9Nr)8SI?WJvx-`=x!g)4HF{7<cNx#~ms&-#Eg_33*5{nG-}9d(wa?+ZS^Dd%+s zUd(^x-!jLZAp(LYpM7`NV7k0W2FCTaAuR2KfIj(!Zn^Tq=2qshwRkg6*jiZTO^k<} zev;hQ`;7F=cK-I3^|N5j0g3&_m$LTT2BEhHqj&G~|M+5po<U#EhBYdb6crWSTsP_u z@x!9mU(a0W<X$fA9~+thm8S8-sIAvk`%A?eLt4|P=YFYR=Qg62p#P$gsJQL-wsF(B zE<TOGQ2enH355FN$p;S$S5YA;A`6#nGx9-?3Ob$(CA`M>4#-@E)ehm*<uw$LO_b1b zgASs_m4$@kZxEAtFuBKIVFyZpJVQ&&F@xO^fYcT9U!T`fFFzplH`IJE1JRM1DC#>s ziEgI%eaW(MGl0@ms3Zz1$G2=;zqYGFiWIFWU_9cPu|Z)!`9kDZF1RCow<p7qpBCl; z&izDmz~!gNv4-O?8mn{98zjw&GQ$NwLtedhJ!}RAEiZ~W&o4KVWOZmff%@wS><>Qr zro6;)Hb&aXeoQ}H&J+KCSUSgmO27B(H@TB*;$+*lZQHhObFyvQnmRSv_EeMIWcNSc z-}AgXZ_b<h-h1Esy4Jcr>!#Suzg1`kv5#u`ys;Y5G|>c1#uZsC&d7ShV%<WgEL_3r z^vtkP$(1@krNkPe0t~cBtFe{tbry><rlJTDsq%VpXO^LJtdOr&)-Eo}PHfhV;@q%D z%G%tufxYgpx=g7oJ8nae^|lZ^-LD5T_222%pmS<FdE&x2K>nk;wM(4raqR`YEKKIc z*010$eW+tZ(<~!^DqJ@)_E3@Vbx!2zD38;%J7#{~v(tfVA~wAfs^AiGwr>$(+6;UN zejZNW!2Ib}tQ)4U>Uig$q^4l^%wN_R3uW;z9yJE=3-&+M=zg(5=_WxWqQsV^Vp-_r z%f2=K92V!-Wf62`9Oxo?y$ru8^VT#7BDP#N_WXnti-DolMOaIpPB~WbsOxtXoLm~l z*yvn94CiNNvHB@y>DIBCze+n8<n@g~ouUVgSMju$?3I45w=F+E7Z0CcyZ-BE7vIB* zrH;uiDBkyQ!S`nOo2RTp0w~~B?ACZRg}Dn)7?~t`Y3~8sOY!rfWfnVm_<QGWM&RWt zY>&X3WMr9jVP%Zde!2d4TyuLjIJsH-JWMzX>Dn-C@BunKI_U8gBeFj*ZhdWc$(;e5 z<HkoUYRF7957llSs?DiUaM~DOx^(WJ9*rel<q`IB*%-{s3!=oeve89cWWRo^x5~20 zvz_ZDx$A5VtX0U|mtZx*R+KX+xXr-K;C=u3Yb5A9*>R{g=KS!yvg8?*{=cj`&Qi5m zaTye5HOwIwr>>>5r#hTm)x^$0hEk%3pJqM(Owt#d=&2x4>^_isp$|xKH;rguN0`_M z@NjpNC3UQZjV)&-8U<vqbwBPoPjL4CQ=un}R!;Pa!aCq3#?up-dS<)TZk0?_ggiUl zwnkq!B=P55|HUPtfGQimMGozlinr!uV9)o2HV<VB=8?UN0Fhp!AGwDZP9WUB*jqB^ zNqPMP0OTC)BH>#3GhP;cil5b?A%)tYZ2@_Ov8N8GFE5K`LYs$1ANj5+Qo^=KvF?xw z8o^zKlEF%Ukh5%%{@;Q5eXh<5PL%}JoP&8#EyMwKMCga(h*Pg$g~&ftDL*z9$ttLg zV1vQ`Of3lNJlAw(VtJsx&w!Kl(^Yz))#{*L)W10r4((<};jVJ^S_FH(M%@Rf%Kp|r zGs~xg#G)HyJw=|fw+kY(BR`)$!2PJp#s0p+JB5j_$oGNu?3u1CKpJQVOHRi&iQB;} z=XuKNY^>-Jo5TGG;;3gbyF8;R`auoK*hIylp71=r<VA0b;^~=QcJ}l0`}*`JeCu+) zsqo9tuZ!sDeOqB%3IxSA9lGC^BnS+i7^1p#93cLc|KL3PeKR8k_9rC;-N3);25HK+ zWk-EN&y0C^=PU9n@%h~KA2^-4HpXkAzM-a)RTBF7$w?HFj#!^Kpxb_)K^LslsDjAD zbFmNX!poE^1im(5DI}R0?F6QwyM94Qeo6)b@!SlmElA^-ksU|Ed5+ha*}5V~TN^se zotpWgGB}*0z7vvsx9k(U90a)Lz2InW9xN@>%R@awJl-ymOnB!-)%|<9ie-e<1Wc+o zDJ^R)%&ZyyJD`N+gSZ8lg+UMI01Nm2w=#%jw5K<0%eP=us8F}cgzZ%2X2f`@kzF;| ztCNe`m)@U=>V^u34Yxv|tz?6UV#@ce+;X3;%}H1v<j=H_u@aM@oGKz=Zx8}wiIY-Y zlEj(9&A>#`=ZguOFY--}m&ZH~C#N0g4IV0^XD<v@S(}7JpKd~^5XnWJtL2oucO0_M zb`#=l#8tXaMSEKZhKI7TOxEn_**8W%l3%Bt0@6=w!XK*tS4yeqc+Rc2y5J}pdIEgM z95it_CYc=N^|RYC@J=uOSB_o~mc?pIH(6TkPpG&pVYS5Q)ibu}n>&Sbo-ZI4#VW7D z@=?#z#Qy^V_lAb&6w&XSH#WRu31TdDev1gw<aLxxsXJ;5BoJRtk5~}b%4HEjt#3il z)@!E=Fm8Amb(}3m6W6(sZ?dkjPV;my&=ZV;V9i*!O8)8pEkbYLwD+oEP?;R7IenU; zOKmS$jhK0)mHhf|FZ0vl2<H1cD;Ug<JBv=Ou{P%{kVU!C!&7v-MvILh37ym++W-1- zq*rG5*Io(BbwqEcOAT;X|N8#m{@woN<Ur^~VwXOu5frHNJ8*sS?Gj|S>m*H!@%8;L z4jvN_@Ti=ksj!pi-B!*uG%N6SAu0HZTJIQem-DsT|KfP|zG`03ehFsMqLhg&4Z~KA zKQ5z%T$rQSBeVlLO3jk~t%B78uO|P<>y|4pB$|h#4kk)u*N}&ble!oGN>gvGjD&1a zYNngG?~NgkVO3K`)?RP46ql<_(<w#aC=UZiHH3giD$AnCc5eYc3D@$HTvbop$60xV zZz@ANH)gav>-hCRAE*Fr2_-r>kW!JFQz;EagMzaf%B9IkIy6H<Zai3IJmTtIxg;^6 zV`Jpatnm%vH!Vk8Iaoz25Fe7wK1E7QGv?URi`A<ob!HH}3ME}jK-5|5(R>47)E#v( zmdB<V9vX6Sq0CCwI<d%fK~t~U8VeDx4V_2(dX34_UW)g$V|+zP^=Ep2El$0DiYqzc zr_9e>{F!DqJ<N3$yO3tOQeE6QOd#$w_CAV!S?HCm0X$N4O}6Jy_WzcmqY(tkzhdW7 zSMf%75XRDEyeC!EZy@oMtE4wNoRhX?b@f8vN6Wc@69ET3l<3mw?yukuL<)<yq!|Ml zO^d4p5X6?5K!<Wt7Dbh$>AXL+{-CJaO_T|G!z*Tf%vkjJgbNju=ZTe>P6~sL84pNq zuNPe;bBsZ018U~8fn5>zdEchaeRH{S`HQ2G{l~7ybo|$EuYS<n^je*dzPs8az*hM> z3QEKQg8wGJmfsL-6Xl=sx8^_pS{^WrDpOihi*skMTbM~@83za&G+c{M;4h!wp>vN< zoZB-}xzjHuH@ki~tGLt6^zfRufg<mj+|KBLu3U4O(Nbx6p+A)!90P_7V>1ncnx4}q z_h=P2KvR&peS2wH>u@)1NhEw~=&E1B*USt9GroUYEN8jAAaDMHVUqpZ-4z;sL*sEw z?M+0x>wg>l>U4MFfAsDtXPA@!uZSUUDV{5<V~WFq-cScH;6laKrl=D)^^8e<OLdQn zwrCY2!E}$uM2-V02%h1irkfXS3Brrl6*9H{d^{`oTR}@fH@@76RCwH|0OMW?EQa6c z9Ly);^~HjKmSVL}rkqgPv2TdyytR-3>h$<k41l(c+Fv$xT<AKP@W1(#258D%OV!j7 z!RZ{COxPw?m<#RdR6lEjFGB?h<PhRJ(S&}evVUF|bS%O%1=AR*jN{Ka$VnL~T1m)k z9k}zjyM!`Tx7L^Mq8cvIn_vRzIBDF(v|uiY-4BE2Nw9c1R&{4KU>g;Zv3|*Ga+|F4 z7L`enlz>lG1bVccVKqN$4_ZO389ao`!=C*G*!Rl))@qzm0sd)?Vcz{@oDXT=y`AAO z*1-7Ta94KM2vPG*d`B(|%2Uju%D?p0!s?NVOG3wq=09Fv;D&P~*=dVAyHYySArD8{ z(tPF&?I*S%NKYCJd{e7rO+S=lP5)Bk)0aIw?M_5v9ZtB*M(YSso>}O^j%kVW(zOlU zNRZ+1SW17haSrfU8h?8oO9SQWlo_iWt;OM?yT-}1-*}5^UbH{D&^AcY(}fsd3Vwv& z($TxM1cT;IL<=n_ozt?)10%2`4q%VHx!Y)TqP|D+%Ra`CH(#u5$}nPqs&z^0yf3Xr znb@8$*4=tS7~-1B{y)h0_OHDjk}_)yUc>Fcr71wqFEGWojYSUPGSe*NOQu7Te+$q6 z^Q5#KP{wnMe3g2R3LgArs;I`S?qDYtcUU@mqgB7wghp#?U6;rN8V8ttFT&<vMC*x+ zD?(}tpZ+s((fX$QoJB>glc{lsH!TQgeo*zx{<BWkbE4s!!|M0M6a5oVl+Wq>e3Bvg zp_lR^A*4S@NkyRl0u1d_h5dsDaRVNIR73~9KmT+5TnyCd?&kQ>Bl?gykX-1d%sVt_ zTQ_Nx1j=X?@A<W|Nc&9@6bE{H04Kly7lQ{=l&^+-9^n3nPqk@SBqCM0sa{@)b7>UW z((0lsI-RKP-B3HL@^jkF!{S52iL%7vkBTP-{2w2w$)aPuxCSuNXkixt6pC_KA2RS5 zRj>&<^Q#zRZMZxpU+8k^m=e<pLIcz;FPo+i<HsO3<z#n~x?XaH3cPVy4hlyKqYl^o zVdx1!2CuREQW5yDbOjRd7e<4S-y+S*>RK1ex_VAG7oM?jSL+Oi7UG82&zp$k3JH&} zrZ9)dG+Dw)Y`9Ie_TZ!o^)DNfNYc(*4YQBQ;&UK{CwWY71%@*rSnMM4YQqVBmc40T z$4t+mKx$~WxEWT9e9YXk&nD@}bvAj6_NHeKlDpUQUL`j?0Q3G<n1$cP2(HJN^QU>5 z-0vm7n>>wo8^{q{E@XouMZvnlmjH>VcykOI*~XC|^9Te-{f}YZ#z+08_(Yn(=|{b8 z)7-TI@A|)&-^;qb;7NDBttf8vHtCZMIczpH)@&&%-G{73Jz+-h`LV>oM{-Kit&QIn zg1vJ7`WFv_OrVtVBo>&(L9K=Df^xmxgC%$hSj95*1J*Dyrv1*%&3!)seKlkIpJPG& zYUh@=rt_AkHp#;}9qh&8Imm@_ZD`rsf4H*JHFIUuH0F*A8n}z6s6$NW-$W_R8CIgh ziFJoAP#H%Sv4KGffMjfy#vgID!PD@#(r|DLfnh2Z-$X-!#+Hn5Y1k2enO&{YI}2Ka zzw;Ia>OpUMYnvg)f?~r>qh_?VWRTxN$-fs;BrWYdw|B}TU`Bxc+N@?G;iS+04o;Wb zkUQ<e?Z>bvjw%E-pt7nq;Zw`b@>_}w4PG>ELo~8-KTbq;UCJ+S4}Y~x)SOBxq|c{~ z%TaA=I9Q5oq|y=98CFdwLVTFcHx{glp3|4revlv=o(zp5|2UmynG!U(ZA7WRO*dcG zXJL3Ehl&~6RM;ZPUOH+|_Q!~b;ItQ%1p9h=6ZXxe#qC7|s{HPknkoD=XB|IM4a;{1 zh#z37wWRUiBXbKF#A2zZCY?{?np+w4AXO)9bP@?9Q|XE@X{`|W3fL`%$588hZ2QXR zB-ViS1O6j_L9=r&$Vnun?Dpt`wO~lY-oia-pv$OO0jL{#EWL&=0sOfYF~p$K!(yrh z=~_3!G+DNP^^hD(o3T;`IT14iYW`IHH5j<3;}(uJwbi=@lnuuWaS8ICa6|^nMxEJn z;dC-^{T2fF#%{YY6_TPMMlrdp^UMt@-KV>#_QtH1bT5@Na1i?{)0L6SUU17c-f)Ae zaWPq0EqWUX<d&&NRXm7%P12Vxa@y?=NjO>eXFu_yT`6PwVr9IaCuot)ZUVl6R&eNA z>92atIqZW=@|(YRdXS*S)>J<9xf=|H<C|se^(Gd&)3vrD!*@zRH5mVOoG~h2{rPj} zd$)!MW2kx6XW8mJY?%vt3`9%@Q#UIMq`;FiP60V{(QI-k@Xj@i8e|r%&wcPbw!MD$ zRylkbM!$ld(p}wd$B&Bq;Jqu@-y-ZxbM818PRlT$Q{(D%?eP0@eIcmjC@Cbw$M^p@ zH|!7m`nB_N@x-dScWC{B$Z`?!1N#Oo7>oC`w<Yn4Q|&A8YxJv0TrVNE$F&v_lvAYs z^KlR+p=(Sjs+60lOkz6aJmVcVZa9I5rm-cc7@oINQk%I(E!PQ~SsUEIjcKjw6u1{Z z_ptatDDec~uE92S8X=KWeyxXriY+MDL4e;5VHPuqu2@3_%!s6y&1EG?DU3!U6YAiQ zbX+-jJ1@gRn@ysXdIAn==Sm1CZ8&S#lFq^e(3S@pVcRLV5PETWx4y>ovzXC`)yG1# zk}y3MUN^pJE}pHcz}wM5@*~r4LN6*|<0AMl4%cE>dC`H4V+aJ+S5;EA8QTM~;jY+B zETnIy8r*l~&;!KO#1J%M{%P9xBvqK0@rm&?i4YQ2Lke?nvF_ZtWk-Ej#b53hdp3Df z3QdQ-`1%l<w6_>$=K3wRy@LV=q-$k6u=7Lm7}uC>0$XT4EqzuCJo;@n1~OtEAVsl$ z<tt-2?diA%Y}+L?K3^OD=?`-Im%?|I!v;7LQHE_CfxpB8{QOZF7JZtxPz03NGAGwR zJcY7PCyhKj5>lOZy(ZKCOPXbTyqy|?XJu?1sQC>#ul76<ZU51)=DEoNo7MIYyA)g? z^m_Rqb@VV~{6%a7H-F#L5VJxqwj!6$f1u?8$11Pmu(b&Qm<0|+Ac@tA!bz(k2}cWj z0W6dn3dDy6Fa2QvU{5pYwu)B&&2)~58ZXi<>l8KkliO|{E)Ea2CJ7t!vHjJu5)rc! z4ulp(Ed)n2`nQQ8v)Fbi#ffUFHe@S@!jResvP?(FLWxwMWBxsBl|9kV17Vr~An<fH z1Y-|>Y;>EDA+W0%0o$Wz6eLe>%gte9Lx(Y68~{?Q`P(T<Qim>yoiTg*0zRx30Qs#( z&h)!+7lOy7tKldmOPTsc=CPL4c?4{#Bo}#*<(cHTVEgBf-{<hFqn6ED?G!W4FKESr zw24E{dbP@jv~|Raxjl$2ru6ETG-Jx#&9mE@&jqGNW^q@WQc(3r#xP<$#ny%19*Q^{ z7$aqeHPeG+9n-ZzP(P?uy6F#~^&+yKeV|14Tj;)Jm{(_TLg-OI0h99LXSVGSZ3?nZ zK#<KrX0@M}Ma5_H>kF8rPM-r{n~4xUdhg}3&(pW#ITY>nv#-Y!8TkqypXBN4qM*<B z?cy*N1Q99vPOVqBRX{(Pc+7uK^)n=obx*V(jC6j|o0FfHrYs@@%*>z4-b!y!g}qHK z7!)ntcd}K=w~wPT%?O)-!X4Y<iS}1H6FbgWlduVQ3Q4kga$*2{TcSy%m01?PuGIx& z29B&I>Vr7*V;<fV@NEW4!(+&j+Eufgcrj^A?0}~f_nW&pmSqx9BnTh3$`ipfGrnx{ z^kk_z-a%`o@$?dl1Yewg74CLUOo%ay9Ry0LmPHuzDQCsCc&$Yse~nDn+f*W^nA1Y` z1!~BvjjNbPQ~ff3SJ2YK*2y(L!?!MinAWFFWvxY%%mwohin9*wmMsbr4_S~G?@LK` zce0|s7b=mV1cm6pBiSZ|JB5>YYoRgJ1X3scxHE`h?Y^6<UCfVK20i)>E_N=vWyku@ z3~}A%#(Jc_xnj?Cm{1TxxRmT-@M1}`61_9GP@D4-6bsJ4WYtE|jU6eAooEiqIE0e< z?J;^zD{kvK`q3p|zw#f!N9SSWFcA>I#<i8t^8$kPp)d>){n#OV*xdrF+gfRD4F-XQ z|7HDjFfRam2%uhzkV&UeN$>;d+i`@}SLQm~HTkoeBhs6NNY+C9Jb}7_rH#mTy^S~7 z9@l^RLSqcCheg1md#CgB^MCm~ob4wFK2BOwQc{Ar2csbwdW4=?!xKUHOAW}Z?LDIU zn!J6t^rWUB-QY+WCZ0v7J(!)9m-c|ZpihWpdm`FFkks7R9fQV5a9TeD1@wd&<hl@N zsA}Q0V0kdKh(?z)ME^;30FS=4hd4bFk!Awa?);J&$Vt+IjY;Y4D~H6?gpA?rD7r1H zjayJmF&Bqdl!Y0)CB{Zz8Co=YWF!#_gfrY-sJ}lHrk@_iW9!Sr`!sp+m@^%nrV2BZ zsU=kgC5d?=&=qI!S9E%Sck8orPRd4~rqb|&@Qc}ReZZ<2hq=bL0SYE+&Gec?Or0j$ z4(3p0$Mj_PD6q6#25yRry0mZEFoQy|k;}EHq>}!cQ&5o#h)9gXdYA;=9$F10AZpfE zHq^xS0foR3zX}1%*hrpLq&-GOV!DSq-5643(8x{oMOge{>=VG9t{CK>2IJpkHD}K8 zO|upz%;oq1nX=?%K@h&L<QpN;lZ~%z+Fk8~;n)M#?{J{qTNJNE=9YFw*V`}ZXl`Bp zB#~p0U5Us+xXO*^4l%KDKDrtaD>~x30V)LzG`y~dCu9GCI28Y>(z_&a-wW*2{RYrO zY%d?dRkAzbCb-4sIjWiHRscf|Ni;I!r_hq`fbSjI)LOY6y%Z~+Mi&D6#k)MZg_u@K zWZ%d8ieg1cFER0EOq|RP_W%k9al1akj2J7&>{@cDNP$!YL`)QB1U>@ViNuAb%7j(x zP%)CT1Hn|Yrw`J3RZWdAxufo=_86dHzdj^ac9Ndd#vmxyHq;zu7MPMCiE&K#C@BoR zw#8U)(HM`?O_mT^CaB6p*>E*w%GIK-d1x_&lZhInYbte%ahMR}yt=}tS1oPq75Caa zN9Z^<PsB!1qf76eM(k+viluRQXFZ9Yn32SVQzZJoN^I3`|2g1x8$C2(`F|8i*e^}J zJ|5Ik^&nDsu<fYXRD@`j$n$kL3NE&)Bc7kl!PEO>_(yqRjQL1TuLZAHH7HT;$NW7* zlBFv2_qB_LH^goiK}V%P%3vZos0BYkQV+ni?rGWo)GOdP2faT;>KCzM*MwjHKkN*m zyLoCtGt!62@_#gbke|nYz16`+u&A=esgwUNr`J|VCl^%fzqg7U2Eow7KYl6?b;M*S zqJHj}Q3uhftGghHN+9qvx5Fd?1aX&?JnXn*iQ8;5SH?!$2Qg1m>(6cAhsN-_wTunO zSO&o_P%j3RS~b5A=pdx4bbc*SVv{=ddtU$H2Nj20Tv42RcpNlF@)-0!l2ou97MX~v z;I>-rhzvuo#KF-nP;?&6Va6s<O-Pazeu6;Yw<Lyd8A(aSWZ2SLAF<(+U-lk(e$dUC z;TZ;GL(d|3Et|=wGf*?(A&{0ZmXrcaH5MJDAV^!RkJL?Z2p(Z-H~O@iGj>^Vc2Y69 zo^U6^q*)0wj;uNLNigQZHa|VW`BnS==H4H)h(F^PQzFHy0h{E7p1v|LuBlgxh_vau zPQJAfX!xIB>u-zrvdMJJ==c17@$4PdS=K0!FKVF{Em5b(IfM{M(2HWGLPnTuLP5wv zLGPj(EiAMwtR#LrN9Zp<33xTd)GrNMYzgwy{sC2P$JP(Vihb0#>85&vNlJiA3F^F4 zZu93`COp~_guUUkL2z$G`^9ZzLwr?=#H=;n4mZF{YLnSd5Gd5DLPN|%<^*{(iz9Lb zd3vyyVH_*v<V@P}7ql-3X89QOh-Z&SR(g|_=ySV~YCdZw{OK$tQUqMW4-%ExEq@d) z(yxXSqp|CbFB((G14KQ+%!l{L)X-61#-sNrso41dC!*O*HWX6@cvtTXTw>H8Eu>Qg zC;-?~if9}H`7r$)(4FLn6^Q#dI~#i(%;e{yQIW1%zw+VFX+|-%*$SZ#dl`>9L<b>W zQ9^Ncl~!^96<pz8FgMp|=z!zc-n;d}Tko_V{ueav)cb1U|8SPJgEJzy!+0Zh^liL# zSF6>s=<w29awHW4dln*6XqAVioBHHJja94zN5veLzR<4g6`Adobib7w1QS0&5>fPM zVr!p^5%9ZdV~U&`r5dQV!0@+t!N!Z_pe63jn8RF*u2mVLJs^e%{sl&w==vogl-#cJ zL7$p_;JWd9z9<beju;Ek6>+KGzPMT<Y=`&{k~cTs0PSb9%#kuh8Vi*ryglP&GHzuR z6rP1>)-6(~;xq-<ffGjRo--H25`rkl2`Qu-oZB!MqCN|+YFeSITlx7v6<Fp_{m9A( z!<6iP`rjcdv__rc%}BXI-En`5M1&F+gkc)HeQ@f*lKO(ah_)cLAzBJ$!wo3L{EJCX z>W;J3^EmxZbdCkM^Jrbeg}+GF3N$azyw7-+Dv2NU%n&Wd9oxMPtSk<z4tUJkiI2-v z*IdS?);||_mmXef3!i(}!H3`A%%6^o#9-<!8TGP$<-#O<yLA1y59}0Vd@z|6Wp{H7 z+2cao{!w;4H0&g*dF9tTtXsb`d@mjptAPGv6p5r!;7q>~wCfiR&7VR1>U%-3a#_0T zAc3R3eXTjPyy(sT&*cuxq$-?DVrmltI8K_9I!@H>%C@{|Bz?T!mWx+w0~@2(Um_^g zqE78#CeEaKb93y0ijAO|5(Kjhj&O(QjWH!gVvlqCFLBq-E=!&Rr@{*FDaCv__-8Fj zE`W@raA+=ZyN>Qbb6mTToktA;PURe#nh08pxrOjhoYRc<i7A1OP*uxrmJd`DZ^r>M zcT>6;7B&`+8u-j}p=40D7?3Zq3XEI6vuHkSYZR`vT8)TF7iycuJ0VsSJWDtj9vO(j z?o%B2Q2jB^0(sl%Z`ZAxyGzGIv{t?=jn0Pp_-`Mi@-Tf9EsWGSbeVJ#UfP#CSDDH* z?22z1Gw>XF{3c42;IbUrluWTZC>6P3A~Gj=VG~ZrB~OLgN;BtDZmnr8%{wL$U0!6K zU{%CJRalf+3!`*a$l7>Yq{jwP+Y&<Dra%1NB4o=yvfysTUTmOqK+F?`Bmt+rWGhpo zAP6kbEeZ~j2$X_>RkviHC9qWmi-d5o*o6FY3{h{!F5I-W)|xGp9J@2>0O)2yCi-Sa zlxN{DN;eu3&;tTKULSHeuf5QoZzmZ)U~X{)Sm+T>B!=<3X>2FI+8(WLU2THwn5SHP z^t}b-te4M^Iz22^8glG0pd<X{IA<UzY=vg_i=aF1HI)Qg1kN@FV^%@YRf+wZKhEN( zuh`coO8%^%mYvz^uBu+3nef7T@BEnKNtqQ-YjmGN@L0sGk9E~o6fzy_EBhoRrct4j z{_Sv9GcY$0ecM7{$-Z5td{<b(E9xZ$LAZa%dAF8bQ6X4){CMT|Pz9b5HkgEP2QIr& zeLQpd*cY#6(bI-xk;80b;kq>`Kv>dmb(@Ra$(ThMZruNKiZwKFgk}wCHga8twm8V* zyqg!Rw^;?d#fgNjf%g4V^nJCwJDB_*_QfoH;K#$Nq5lKM%+$$aWWx2IUjMZ}2869^ zpSa?%8u@~OZ<{*-Z<if%2QPQWy%vvOB+tW7fuG-KJ>gV{cQ2f7K(I;FX^`#Jws}u6 zeC%sA@GbCMT`wcF2Tr{l<+1GNiQCdtSXX29R;2r0%bh$7Fj?;$K#R8EqUU5<1ji|Q z2IE9pVSSqY4UhH-3~`$;Z#T-#*X^CkU7V1EnpG=#QJOIIjJ|Ez4e*=Ar=7L0JIEnS zzO+R|Bs?gzPG-wz?r^s@@ve>cV18QTn`Oc;;=0$v6pHQS>fE|fr6HIlM_{^g+94cn zJ68zrUU$R_KA{RXqyQZh{Gf9Pljj+<ebNdrzI7?r9_`50)w*ig4c)x<NbPj)v{30o z(-cOE1-)JMhHx9@HOnRgZo4j!Trb=vGQ_q+rzRjx7GHo+L-Wl>w^7lsU$KKOZkY0e zbH{IJfABissi&d;Gg%Q6d4#5>t*Upv`OVvrh!sWY07o+J0^Qia)b?Juzu=%DMX$J< zYe?jD@zDs;-{LVr3>wKn_o3A?_EvH4*t`;0gd^KY*>U{(Ng4x62U&t~TD;>qm}`qz z_7NZ#{l@!1wfY!$(EzamEOL=!b`{z9w8m4EapQNN(^nX{`Q8jK$)JYV#qD)_|FXgm zg4-j6(}u>cjcHNTvJGN)-I=_D$QhrY)9gTIFaGItu>#WN#b{X7Qn-LoK5S8*c1F)! z?4O#P2pb=9N=v*y5|Tj>aDwOpJ#(-vQ3fwlR6#Vp&T1nVheiDl_M4z@zc9sCE(9GS zN{C#nF5|n=(1KZxKu}zoIA;O`aV3zjV2ad!iT!3aos6eqP9N8!4oE^Q-?j~$Na099 zoNCa8%utS7uI>+MnL|`t*ibL18>GRrQpt*Uz#q0-r#a{>45$~B$B>8cv8ZWGa2QX- zi>H^-slIF|!xGGy?+bBjhvzY?ArkfU`gX*|0$3Gvk=HuJcbmlAf+Fg#b9>_d=~iPJ zJRw_^KZ@+;_nAe!B23%^C=7s~OynENk4YhlN%yyW;s>kZ!>Gp9u|7<{3R*E+3Cb_{ z;XjTHJH#E8#ps$a!_lozDDcJw;aycMy!QIopd}=3u4DV8W@1kH-l;Yc|Gsp3$`4Ow zNIoUm!s9$?K+d;9v@C?Z0-G>Q*<27HMmi~$ISWjjCef4~W^Fen;iK?ria)`MAYQO^ zT0tZShxpetwjR0+XqXBJhaEUULbNI53EDn)or>|7X+P7Zx2{mQ&6N?u93yNW#?2G8 zoU|f$SZ%Q(N$4;{&n_aoOSu*_$+sgORUdOG{y|mK%YD1I$PhA1=3&XC%!&nWTTDqS zk?}am*#EwL9Wa`6Q}FeE-2e5~ANcwH^55~E#HyKwazadIY%eXHfcxilxMw#M=IPnz z<CWZytMQo8P{8y4d=a|!yU~Hz9p<ZMFiLos15Hiz12|jFvr6!;%>s#}+2{>qJkl6s zyRS;1rBuxl8ASy<<lx*qU@Y_G@xhAltTpUeG3bOHksg`hp)b$meieW;AK5*i(xR?4 zOqNAIj{DojTG=8MXDUJ6yjX%3+dRi-sAW62%=D_&C)<pGZCquO2_AZ5Lp}e_iUp9` zvRz~!SVUM5!F_yyM}P7Kxz#9Z^Z+^9hEdn8zCh#AaYC+lP<tD<vLV8tuP-WJ6E^DX zUQJlt-8yz=<f7Cc`Z>Rj|5wFiOho;xMI2#gyuLhTxBOrG7fOsiWH;623>S*nSL1F` zxOb1O7mYg#dz$(o;}+zW`WonszMc|(?tvgQk%GM^{UFGZT&Cjh_(_dDI<J_4`f=dZ zLo{f^3uIH-Qqwi-Q7cM?tCy8pj~=@kwe@P1{KVZNYeny#7F!dsdP5<`fG!}*yG!X# zSSO%ZHYALM?m2=<(+lORym6!4Dt7PT#>2XhV6Q0HbVXgRU1n_s9Fs`!<7sMFw-sBW zZLn8|t_QKM<ilqiYgHDMvcA?9x3x!)x2S^#Xi<7NVMLj_RWZAf`T#Y;sSXDCRHr02 zs3V(<$m1u5{Q=Vt#rZW6nCsWjIlrlCAw(FDF@v8Q;lt1m6ZA_TUVry*i%{`oASDu0 zqnIoeqIOI3)D9wOV;Rz%NW6z+U#$@-di<lD=#WpID!GTW_rw6>mJ|kqytZxC8ZS>P zgW-TCOuZ1c`Hq(RW+hBpT(Vq84#z9gR;WH}*AOAP$OE7+CHRR0ZYiwrg&-Xd+WAw; zFiNHh;W)FL;7InAn7OgR<!4t|R=9Jly5Z_3nYU-~7x3kB`Q8^4m`34+66p8F$Rcj& zJylZ-CA!E>R#I2vRqLt1D;k|h%vY=UBR4&oJk|*hc-1Ubm9B}O)&==*F-;i9<lcQ_ z7fdCy56-b&9ZuJ`APTB^Cgtk|W4R-_Zk>quq0kzSsHWRntrNb*pr5_TktDkDYD5CI zz*uG!r-TE1E`ZHAKWdM2&e%$EP(2Us&Jf*R7#VH|I&^k<WtxoD_!mb~y=gewk*%o( z6g#t!a6uN6XWYmAjnuAW3;T^UFdR;U-E_$iSz*0PR6SqJ?ge*GnJ91#)7FjR*g%c% zvLS@M6x{n&)aRXv6!&qvZgtO#&e{q%crsIWk{<RrGIp#OMic2xQiH2QVD#(j^X==_ z@N-g8@Z)}S=kpQtGw@}abB8bRb1QJ=7=3z`s=#%3zwU`p;MX1e%gQBk$F*Ot@AYF| zPsf#Dr|<PAez(oDh?Qvp1f|!%dT=Xy&8km;O)j^UiUhTXFuFZ9g`Ovqy^qiBfWvT@ zQPiG42*7s|2Upgt5%yYWoe`YKiro4Qz%Q&;hA?(fi4`YMYBEX8s#S{M4mz`AG)yp{ z7lbVv8&6V+j}UBJBu;k#`nk(yJwr@XnWY(vLWC-mqjfWd%Vhl8u?sE5aB(VQ9+BJ{ zN3HF4R2_o#d#m{U&c~niue4Fzz}Mx{@%Fs!fM?YN*ZkS+#tByIx;i&mQY`Msob~F( zE3m5OwEWNFo{3#i7p1PynfWfeC|PGExaH!w8R%Cj5B59|I?O+m6Hfrc@1-b~WeQ!P zYla^_a}$uwrrs)(KO6l2Ho2~rJrWop6&`fq8wd}|R1oz;bJJCrqv<>tvS*dDSuyOz zio~wk6@J@-MbuoK+J6e()=Y5cH8*ydTC5JAUBMD&+hUN9+w5qfnzFQ|AiD6_Cb`B~ zq;b>Y&mPPD{EVU{TYL95p7OL>!nUHKT8qXkk&vf0WwTtEcRbJ-+oVzBert!(zgV@o zYn$C8;JNmMHDzUkf}+8mTr{FGhlujr3D)Lf#_F$(nYPno^ssG8EO|e~g=|CB$yu(Z zYV7M;Kl)2i{M(*?fy=7jzrv5D`@GMTj1I>(L!P%s`QE%dDB13yX0i+PJ<fT|eJ9`Q z@@$V}2uCbA<iJUkdw=O4{tpa43pLE;gLI+GA?Q2*(ufC+48x=#S%@Y;Z1;Z5AKD*- zoc8?wLv|)a_rHTFhKN6E)QLCo&zyun)pVx^U3t10(MfHgoUSI9{ACbBQ=7V0S=}H@ zWq!Fz6^4oeOx}Fwr^dqK@6PQHusRI>|Gols74mqit?b@M!qE`QxsV^~7PLc!r$jWy zCk{y^$hQLBWv&VEdN!+gZfkqbJoaTYnpF-?Qz(|B!f)>;_uqv+n7uSGNS?pL-s^c2 zokkdkdT+PugbTNbKj6*n(IuXjHqi44Hg534GrtU0s~~g<IR5!%9~tC3?*b#{HLUBb zof6srHB{14NU=$aGRd=t*oeHqQnF`}T!6J2c~HZ&W^HJTUa^s=036pC{BK^en&&l^ z+~5Ou>-Jm?7N@z1XC2AV{shsd8DoRRz1R@jgV-P1a@%U2HIY+VYuekqoyLu8WZ3uy z$P<K?u=vZNA<)0DSlau1Mt$Z|drgN>1~=xwR=w+M*stSPbxxKwjID=iO8$C%K$mSh zTuL49pLP##vxPmiDbpGwg@cWmRshd@zchAu$!ERm>BF$fZV)AW_(k3h?cu4W;peMo zzyJOHctODXUjOHH;MacaF$knw>iY!z@FWy`9<I5n>+zhsv2c5u@&8l!#(QIruqFGa z-}HpH!LZN&?g$^$uDaUteM*nKOYq`(eTaUF&uUb(y0j!BC|s^(Se)4~)(Ovu(eqr0 z@ccK6PHlXJlo@5eld$>h$a>SXd*X>e_M6_0cfMa%E`!BM>7_7G5!#XuG$tACg3(W& z`GB6xIJ>*qHVK7bj5sP<i(_YbFCCXX&qG;6R@m+~B+1Dx`4<xCFuSc{jjQ8ijt5K5 z-WYLFzJlY&^2p=02HIeI8afq9+(sMKFoaO}3w82F$rwU?qD;B^V|Gf1vh!VKx=xtw zueB=YRkxUL>+O}w2*REiwd*Ta%VS+j($uRSFnAV&9soS<s~-)9{f`acL|#AO?ihY* zjpCarYh)qRbnL^`Ow5J_;ME79wLf>Q?19kJet(_pAA6MFI$XP{hI$d(?9(z{=_6_9 zByEX$po$+}#U7)X3I<W!+ekDc1={ji>u0^kqn7}YHV;Mm;sy8`{w`6#>}?$gnF5tg z1}jltfe2i@S9Qw3qsdWd2|`RsjWkV*w)}#mI-l=0z6SNZNRsJnTwHpBR#?{qTakC( z*V&nk$xwKLZ8<?NkF&W!3=>^CLgOlPXA<kR$Uc8mUMl~Zy!=PV8$uSm8GpF!*b(r) zg`EBG?hhNEFdkg_Y2jATAmIG9pfxGISrBFLAULs^{ATn#jFl0HL@<82^ZweC-ppsl ztIps8X)fJi*Q8QI<mo#nifj_uu2>#kVc8ZUBP_9l578}MnNBu{AG5*(Bx`lhGWmA$ z!E3?VMMoh`{KbG-DF<u(opOx8r{TT$%fAkivxE!rk0PA+^9?aQ3#T@K71`lA1*pPJ zt1W8(?YuYNN-Ej=q?nSmq_PN#?L;_UUp@#e9(+leN^X|GUpZk#tz6JMl^8#W&&|?B zuLtg20*3)!pGE8LLVI3ES0e(!XqB&AXPGo~f~FHGIv>_dXs)iE+b}O!raF+2Zv{t= zYu|eS$N{x66_>l-erq%xSO|<~kYRE9?v6bmY01YgdjY#^Xxmtq=xU`oFZK);8qqqX ztfv@;sRy}T&B{)zmO{^jRo7j{%2?*{t)o5LoS#*XQ0GjT`b@mz9DUzDMU=Kh9aejw zER6{<J%s!9&v2=q;8X7TKFaM)ETdk^Rurh`=5@l?s2(Vve~F}vUUeMI5iW~PFe#B= z_u}GB+d6!<W*+^$S)_+&%Kp`n`Cz@)(ivNe-YC+zQ+AZxIHFW&@|d&($&hKz>#Vcj z{eDrA-p&HYsxsvbqK;b`JZ;Wl+S8U_T2c+22e7?hRhE$hfg3T;*4T#RneoP<MO-<) za`1EEvIK%_C+lJTPxr8Y9Hla5dYOgZO4fni1_C-k<be=`?n{eWBdtfxpR^qvLOv0$ zFd>oN9uii6!S+9ov(zb1!Xh_!&PPM9`x284i8vR<SUv8O8s0Zd0se6U>Q+b5Hg)!K z-FTr({oZ#oh8RGV=T4~%n6cy8O~$djyRDv<0EN~Wt`#`Dcgrl@7hNIh**&YLb7@<E z?lEOX4fH~>B6nS#y`ZW~5K{gE{e4vkoaKVC(d5_4<%9R0B25$R=fKUB#z(y_JfGcs zzt008m{XmBHUSfBJ~H8aC$<?OxBunnhYmZ!>y3k7%1SF-Lv!F;N8lT0;2kH~aqZ{J zY~bf&!RM0WEgub@+At8>L4z-{^~cif4;8EEkHC+>Pybm@eFlxuEH&%}mFg+7uBqNS zr2<9qIgV1ZIl^MWq)&DloK(^LyjE$#UXW_$dIa2)TEi$$7_ex;9UQR==b4*9Ap^?L z(O1L|jV7bnN>LQmlmps^RgV!+@mr7nf!9Et!K4))(}Y>(pd^>5?di2<r$?RwL@U&1 zYm&U>Y}*A|-1#q=PrCN6-GAS~jBBfK<mo~vQigR7J~LHn4bWKpSX;Oj;>UwiDDfnJ z-isvk`22&5A;XV62C6!ua_34Fn^_xvVFMfW_MFFZ^;j@r%7;P@KCqmGPT5pjW|JH^ zg@5{ngWpd1reLLu)U-ys6Y6YfF+)1ig)QR02V&MLwR3!=Btb1zdyE}Ud%&~g^tKle z>u&C)V2(!U7JG^-e4k(<obIA9xWntxwhV5{<kdu3RW^`$09$$lI29bjC9iV}L(TcP zPC@Zfwdjf$;M|hgjO`<OQ~1xw>NC)0S=)AZs(<YhOG}A!V9;AakfYBYY}tAH*qJsI z&B|p`4*Cu0xkeLB<PESL)NY%OO!E~`a;gzz5HM!_AwTgkcg8v!!QhGv+dYCuJ(mVu z;43f!Uhk=2P`z?@AAhC=69@*#Q0?Vg9+{)b`C&dY^0tos`p9?wd&vw{+>t8V!vif7 zIU1}}r`3l9k;T2ZA!9>hjf<TcM@8LYR>;SNF!iFj{b)=lShj`MUFyzWI9(Lls~&+8 zvaJ3<x>F$`I<}j2@++Q((!R95pspUyC;2#_sMN(sFLo7&GqOZoO2rZDp0cZK!yqOY zqDF=}P^1d&2+3zdW6^_Po>kXKVl1guv_n3CdyNKlX|cXoG<jH!Sl8)eI&NXx_#7Yi zz80!BBq#rLr<t)uR4Q_**5q3dtK?r$0N;-P6R3!P>S0pcl}LK6X{zz_m&+MvB-f<Y zJxxIxbSIG%o<lEk6zQph;IvgOGf+&0p1Eg>U%vV$wkDQIxuCO2yX%L#rs^Q`CnM9V zTwSUBfsDvkR(Rkg?s!j4$3O2R5V}!-*!|H~w=JJ7&$v@jPWP34p&D!n4v$FzzT)Ss zs?g1D_+s=@*Qzt)unEyCJOvKys=_nAe3(0lK2Q;6S7l+HN)DiOxKB)pWnnOBaK!u6 zloK(p33mrcQQc<OT|4Dha0(Zqw2h6)y2#m%8Zc@M)b=P49;(kwSwW^KpLNPbXVYUG zdq$?m<}Gmt$uRt&1hves@p%PN%Qj!kPH`s~3d#(OR?%MnIOh>`7)DV@OhR*Hn_W{{ zb?B16FJ~HG>RN~J(={262K|5avm#ALtiJ4-275YkX7?)4V9GFgQr9w`O#BTqz5pQ% zSOg76pyAP5i|umd^dSspV|$Dn>-L{AQ2~@{=;>rt))l`J^0Q-PnC#{2)jM$fEi&7_ zD1g6lGP)Wm=zbFSy+gC$;`z)0vhT$>bR#;&VCzy980boCbLvn?!sd#B)uA#E*2U}z zGQ!mA5v>c^fYhEtG&vQxA>6*RSZ~DL-IJhNi?sVHdy$Mq_$p4pp2W)e?r?#^-1974 z-5U~<=_H&~|Ksu@=ZW#Z(FWN3rP1mB<8;O+6spnXSIr@sYz}mTAa&XM+b5{Y-T(P& zt2({A?n$BWornv+XEf*zb5FT^q!3V}wTyIHB3O%bP#WZ5zYgw?)=l$-1O36qWn$kE zH7;jl<Nl<@K9;NUK!3~RI>C_fIa)i52s}wo9h`-SM^iEGXR2GLu`~YsbrWCB2am~w zepG@}T#L!aVYN_g@Z!Z{6Xm{@#Y6~ABh_8Tq?BhFmkn&i&6K%*vFU7}k)2TYCKD)o zW`y55W9$>bF-c=0ln<j1ma`$;wjh}V2aRIE-ic%?Hn<jaHDX&7E0Vyj>i<^@5~&h1 znHvUigJvsd<1=CJ50)?ydbwZ4G-2=Jfsmj@H80jxwtH8fvu-i?zCHkOYUR=tT6I0_ z`9o8WjqbdT`bsnMp?42iEBJmR`i1PX$r&L1a}y-Yf8JLJwmH06&hmC_&>{gpbcG3b z_TFEoWdT-!1kq}rX3rzDk%qysqpwBwIg8c?=3lp$nu;_>920V689|e1E_)FNX%5J7 z7~Sm<eK8WcbuQDCZZ*2dfGLEDR-ThC8F*dNDfp`SGpfS;>ZRF6t5$~8uT-HNbYf9n zXmfl$tyDnamZWW%;V1%HHIhC=$`m?59!EhlIEAukjyT2kIhtJZ1Hv|r4ERbU$9Wjt z2yWv1#Q`dR%eJx8<Q21)w77ZuKwR#3TozXN2GY9G#b&~p?$ymkU3?Yp(DAh2S(Ic~ zs{LOd*I%1~Z;tdJ<vyz`FEn6qJtO@b@4g!O2nxvuEuE%_N3K3`+hgMuM^#j9=86mt zRikGV-5A|CU+R1-KTKDe$h86rsp5;N_7`Axx_}Cq1ALn{_t<s*(XNZt52+QRV>d=R zlalQeLcJ?|Tovr007DnlKPTiDGzfBA2ZG-6lwTIF^zSPH)OEOJaGYDQ>2-@QS#5mq z*Ih&nuv?E*q(qkl-grG-My>oquVT~bAwN?yVEZ6j-maXNTql=Bike6zK*HarxNtCl zKRcp*Ay-D{>mNA3iy(EdL%$PEy^R|Z=iioM{BU+qzlKY*H6Y~9`Rii61!VZM(ScH2 znYPq?=T31`r`Xeh73Eas>+rsUygb*i_3jsUeIj_O<V_$5{CBe#%1H1h@MibV2Mma> z@Zr3hB8bTmEvKx&IEJaW@~aoCBDmcjiLL;Wi&gil&8YAg{=%Y0Nf~bbI?M*gXHLqa zrFuzCZ6epti3|D*XBio}xrr6|b?4@{*{y&Sx|D)3y#=DY4~c8s1_dLrx9T~&!S|}b zcGm40;m++Tq19GtccU#(6QUARgg31tTw~*Vw@+SeV~9XFwr`eBtTw5?4Lmm#I!Wa> z|0PnZGhyEoyYC1xx|O1($ywEE4QP5{>TXPMW`o4i%e5xe_j{;e=$|fc*FRM%z&~@f zkn3=k2t$c$P7=ZMO*}^`vtZA|Y`;Zr&;-p$z@4*Nom6j8<_VJj%&Z%fen!aVtx+lR zP~GoxM|9P0{iJK102F<^jFqUbGt$v&f<4rj1%z+phgTYrO#Qb`QXGVm3L{b=a`|az zbEcNZlwX6+Pj;OECRl@xBDP+R4X$2_VryvF8&LNQ;_gyK6M)g7!;2Cc`j@WpJFrkt z8wQCJ{m6FCvR|4@-ibpG)25QJ5Tb8H;(qpb?wrjN-0CEgx4kCRzyA1pLo$DGOKmNb z2v^YaK;;M?qA?c0mCS;>0}1YOpuP-3Rnt(&SK4kKkQRR3aqN;Vd@>w@xEPH~T<4PG zTDRlZ>ly8z<dawM@GsEJasS&@kLR@)D3V$AI1>5VtBzv2&-c4)2E+^mZ1y8e&`$5k zY^fl~Z#8JQYWWUSFxNTGWu2`@QdnlVI{<|3{rSx!lJHB)HV1(sJeAxQr8`Yqn;oz| znD{=C7&*>jUNnjF(ztfih!7@mNJ9pk5SdS=+^Iwy=gTVMPpnVMZwuc-RW4D1=~y63 zHTH~HOGIL(Pn_^5!0TwPmYZVawn8kbX)J)bpTf*!rw@*vSUPs8y0&I0s^AtfZ&$Bm z3PXo9W9!r&z=Y18M$u6&C>^57isyEj^aafkfF@)*b*=Np0oF<S4Dy!5wgPD9lw`U^ zG{8}g#g%vJryLDEsOJ(amHFZ-id2c|U80)p{piMMCdE=|<5AVu0}Uq|`%(c_NBKlJ zm~SweJ^I{}ZJ{a!ipWr8MXz1P!XjrESnW33$T+uw`K=#REo0etuW0hTtE-q|!fxez z9!w~y>M_z}YMju>d3pj{#uqFkES_ZMX-<bS8+bknIt9931Ru){0T@R=hMa*8hNtag zMR{}fBX4pe?Y_>EHJQR9?xsppGzut#*Iaa5n;Y_Sx&>(XKNal-n$sdN<MQTt(2r&b zC^}^_6^kV5>fhaomO-l_Jc=%C56`LIs;iI-!jboK+2M^+tXI3qjo=5UvG2;P+Nc1( zVrY5gg|`i3*y?!GZm1sc1A;Nd@!jX`>LI720R+l<IeUQD>Atiqa?HEz`nx+~T&Mky zh5=@o6|v$hRYj3Y|9)Vrz1cp#P4G2t2(j|FO^>MO4(U6^vz*J7TvkqVBe?NZc<`+P zL2+YpeEK5C7v>3ZG(2yKE)V4uEO-tSh4Y&lNoEoM^AiihFi6m6TPG0BSx~V|(~LGo z8h?3oG1>ay(>+X*S7jt~;hCr=*pp&$g8uO9J9tGF4Rz4Xyvu(6@ra!rmOIYJq2@wu z-^5e?s(nI>x^&nqf@g;=7fNI&+>iSg=R57XR$_XM?~$D9T^IAzy$u(yY7_WYs@EF` z57oBf4U5G3SsO=*1Jhlrn<<D)MO|7DO}CrLzfjShVe)B*A)t5`SGg#QP$mg0Z0@C( zK&q*z*IHMmE8lk5J7fbp-uKlAJGN^h#IvNaN2aB+8v|`abeCZm@B(T@b4(Rr0*pdH z%1fBJq@^}w)MqmnKs``YX$oo24YJJ+swrmz<k;98`;<Iga<T(m+25Bn4Ihj(|Fhnp z8-HFzyMXEd@(A{?TCKXXxUyUDzeRu1zd*7ysMWm)`hwrO22u!~-vy^L$jJE<o=LRE zX8R!o6A%(`Ia2@-E1u>{9yOIS0Z=!!Ksd|yfD)SrC&}N01)uR*jMHBJ4qwyP0qB2; zpRU?>MoHbM)u?6|=*>@q2F`iujcx<tDVg}$2mI^GPMXe8f0G3XX{tW)qgc$nWdXG= zaQ5Otj`kyC11-S#t&^N3B<41*J3RjcMiu;Bp^qG*WT&1(8~pAfW?3Off5PaotSi^< zt<kI|Bq|cVw8j#HTWA{~L=jqINj{JyVlYe<o+=$H7a=TdD<U)^%vGK{*}nUc4UAd1 zJSn2x6|#7DE|(89OY7$5(ddE5GVGvx0Hs>xcW39OlkgKGg$c^s<mgOL0A*}D>yVCw zNxL69q4n7TBAoC)3J0U~Mleb&=ybb|k+Q0-#+8H@&(7T%BFdNDOUht#kG;DDLVi_T z(7k2W6d_MI#6_=h?A>(Fa6kYZge(!y6M~@FmgX+^QMh-$Ip7fE55mEnq8y3yl2w=! zTDO>`p6SC#^PA<JsWyg+etp3Qe;`Kw1h0$T;p6c~-(V<Q6_dpxrxl8o_@cpH`%9UL zCF*NiCX2?_>IT;;K8r$yALU@70JO2BO3<LS2b@`QQ4rVdIjI*4H7l#<?JDr=uCwle z+2Sq`5Am46+b83v{e2O`-Z-<+l+RNTr#&g4$A+)^_Q>8E>2okgaK^2hU5&<taY}bq z!kYAkG$sBG@oB|@kXfBVuBhG>V@hMbwT-d<OD=!`*&YLp&F|M705>^y+l~?P(=nd! z>(n|!Hk-qh!p$9<2*DN|>CTJ0f+Za0qalCl<c9Sxq-(bJ%^Zb&Fpo#a*-rP*hyjFt zf69PNXQB^`X5VvDUQPCK4f5Mx8KPcC%DewZ)LAga)dpD@cXxLuNN@-)0fM``yA#|c z1PBCo_hE2{pdmO6?(R<TpnJcqt=eBOw`T6V-S6r1oDL}auowD?^lLR(P4reJLou~~ zLCEs8pwV$(3_ov5N(iHd<4bBa%Im@*ye<nyh{qq2{`lA_zuPy?f1MBKD%X}NBe@)4 zqv2^^F?A>rT#@-jZ+x66&*Ag<9#D>eD#l_^<TZ(J5S$WT<LlQbyThH!&GyGG)6;Q; zH5FZX??X^+x8KukrGvurUY|ueA#T>2?x57;I^a-9BV4@{5_?;ETVuda+J3(5aoM~K zym=cK`g;B#c5`(dikbVh`exn#yq1hstnK~kZ*uhb?Rn?o`{nz&SmOPYV;+UQKK(eZ zerB9Q1Op+GVS0=A*n@&U1jXmXB|F1A3QK>Az9GCy(;^!(A!P{YsU7p)c?I+Rsw1Zu zwYcoq3;~ZR^Gd`5?1qUUnDvY0nBB@o(JAO|32UlKdcOIFs~8<jr&yDvn4QSW)^eq( zbSUZO#ITNV%Um&cavZMo|LOvzM8qBC#uSS^M94h<z*r+yrfT~3qBKq#Uq@DRCO);O zlk=eIFPf!-BN+Rb)+m38W8EWqrB*=L;lKS~iEBfh<7+bO{^<RMMA6yM6GO+EFS02< zHqIv7yQl1^D(6mI&MBdsz{CCwqXe8OM!%>R@6f=_vtFfVlmnI_O#zAKvjr+6<}29? z_u5<EstvcGq;}L9%=KEl)Fu?qdB>_~Ofgb1HgqWQL&FMcJJtTFLtT__9#uN*QH!## z4KN?EVBva1i%R@*SCI3i(n#zXYh`zMdzLof=`bQ6)x_XQ%JV~+AH`k>A>3AGO>m#T zv8Nu|nsJxUUm#OTQnyv??Qg<*cB$W#KgVe2>(ut&KdU;8Vu5$}ubth)>B4Dwy&JLn z^0yYV3@VPGx*k!9Pvm1An#t<~%hS+?L(tXWGTs$;&qM=wRL>D>1G|r?*vr#jOr7xI zf(@u6(pIkFw&Ke2BQhk>7fo6$*Pb%ai`DJ2pE7xvJvWtXT%~2F2zaR50)6jTXf3TD z)H1R3i8{Cg6Jwdfvp6ZyVcUoCQ#9dA$OGmo@H+M9Z{0CY)G&wjWvmcRx<=E&ceQUl zZ;6W)wG6)7MX4LJI3-K8+fRH+Bu;rf|3msaHgeiy_oxW%Mw-Lbqo*bz(}rwt+n&^n zAI&1NNmG|MgaKYLW|VH-be`Jnr`vE~;pvWrlS6&tBvNx^?u*mefPADU!#L(B%h!Ss zt^NQW5Vg*5qYQ^Vywa2S==xGdXN`(X{t=$KSd&gcslhjOA>c(2?!fpBp)kT|Szx=W z24>OvW=G$@Ji>8<=e7?Dr-6n?!8$|6=w4;yt*z#sWm`>P7tdKptWq2KW};50GO+84 zIj&P8Skpy?#I}hdL7s`q<%6gHMU;CBmRWFpKwIEnt?kzZm$QH9aXP3qU=G=bi@#}e z-LGSWn0N^k%_bjbb<Xa8`D0=M1}xDJ*k6vve4(9Dw!b>9%#O3D{R5Pn3?~spVW9{9 zxBL9YFOO^$m41w5xsendh@xnRv?T5eP)GO$j1Egq3cA&a#fvQ{ST!PR*u;}gpCN@- zdYoTYf)9Va*ra8QZyC@#&AgG9%nk|a<|MWpTR0PlaVm<rQM!E#stpxR%YD+KZ#b%x z5g^BD(Qt)8Kfu#mCbge`?QyJ9pOXHC;i-X;Yt%&0p2MS*p5*M5F$v-21`D=QSvpUI zP>n7#gv)pAi)Z?O`S_u1bazBpw%^rQ;@srrX=>&W*)VeDH~WAZ;}ZE2Gr}wjFh*Ac zD!j#9Rn&GBvc1TWUh;`5xB$6GY?~l4f*Y#FH4hzTwTL4<e54sBs|2$__K{6q@)Nc) zFp($kJQ0IdmZo0KW{|BM$aOpFh+Af<F7g6wzWmS{X-6EX5iO_lJ|TCR)4(*A=9tIO z^Gn`QdZJdpU3QjzbQa6LU@&O|?rY3{GDM)ecC@HF_($R8w$OamB+Ah4NvKg{C~#JM zSUn<Go@y24S4uHJnQYIIwmjyC%j1Ef78@=AtLc?W$ju#nU@7*HOVDK$W&i|;flmse z)N@vQW(7Oy13(LYwDTvKVs=mKpVfO~Z#UU?NUE#)Kgm7&ae>i0!PT!J9{7os9EUl6 z9`<3rDWbKphy^V<sFsk9FG8#I_zm*CdqrM|<PBPKG!~4}NCvV>I4eIuAGg%^#3OEf zf3MypQm<>vCrduW=YTvn@uRB5Ght7DHcJAHZaq$9RF2T<`H1%L3$t8CLK!8<yT%@M z^2Zlx8=kDh0Z8HM?C*AX7CX|$07R~rv{bTdgZ2fs+qlWF%JI(*(Awsc#IQ=KY>CkA z^G&AwsYu~yqm{>hP&I={+J-)UWf*pY0X}8mWyDR(hG`tvz~EaQDQ%18a!Q5u@&mLI zQj||`)tk@ErsgP<MvWg_S`nuE3KQ%iTCJ{e*g@RL*I~64eb1`vrwk7UrFoknv4wqG zIo?(sQ;ep(Bg1U!Rn^9Rs@kFfg6*c>Z)O7HnBIu?k^HhIF`q|~w5?iaXy3wO>^yUd zBmOargaWf)7PTGej9{~HGc${MWfOkUHf|Q~46?azBq9lnlxQr#gQ{Q{LvO`$bo)GB zZ3C&+`JQ>Afmxdb7n_s*clT_P4!*yiXY;$?hk{>ZDV6^dhh86dZ)6klq&t)y#fRp{ zw4wX&Rvf#b9u_b0X`I9K%)PWVM^?LH&0FZY7BQN@VMnyeL7#&IxxN!3^Tsf^ev2cA zP_KTMA4eE(D#Ah3VNMlkvXYY5VmjvHIo)mFE)?tetM!qSTO8z4Rh5Ks90fVmH}iT5 zkq;%gm5^HYR$}#3JE0P(L65JViW60}g7^vl5C~`H@;<r;+oCO`S&bB9MPXzm3LVSm z5iEec(6ufSMd{R_JS4SkTiB2)!C3g}L(VMN2*fFkT6GAjBWD6>`an(dM%&=;;(-cf zALUe0&0ew+IDzYg{WK_@2HgA-zocl)#^;AsPq;<fYkjs^o=^y^@)Fk&vRrH$&QvO0 zFB$Z#yTDS8Ue=yI_c=J0Vsq?;0bDXD*vl3gZFcS{LgpxoL#br?ky=d`1=;gq>!%h~ zS+n&5n0InVQ0rFkA~yYoL`i7QQv8To8PiVD76DZ2eha92)YB-_`AC44x5Q}Ub<}aa z_&d;$o;>QF&QPRo_1gQ4LdA0VbL()B-y0jvx^zZue5IoY0W(>`rnU5zv$#W)!f6iT zXfIuA6F1vIKF!B}R?wMt{?2EZR-?jM|1QK)nSjLk!Pt*eX<csxhayL(wLJ$vFP;9O zH|qw9NfIQ-TI5DH1|qg~_gkgz9V<W<`q_tm$V*}h3HUy3DIyfZ1<E-H7=nD{_pvG~ z*|u_|zborIfD$cPM%u-L+8Scd(c8K%vZR9psjT4aU_HrnSd9#l&k`|E*an@yVJLP1 zyA3c<kZf0`8q#Nxkv!FCPRrgQxqWaS4}Spl5>V$8Q#qw4<>;OCXNmR66`XWsR3IhQ zJr&E6(aRHVh^`($wX|=cE*}hcZ;?Nr<XY|ZwYn5(t5_-Zx}@koS*%3c{x`@pUV@?2 z%FOS|TS2S~?RpG|VdH`Wu7aLG4Z<DZ;dossnrL(+NR61QWT?}$Qe4RNgTP5`#nodk zd^9^4x6-M_G+L#tw6ct96hENT?A-F4StI~y2<&z}(SQ@R;VVX=Q_hM^lo>n!@g5<& z(L4Bmmis!hh@q_7uoC3ZF7WGd584=>Uj+DKZky30dE2dYpl=f<mDFYR$m<DlB2H{G zrsPe^xgt!S;0HdOWNk7rqVL();!s3#D{s%e5Gg-B!J*C9OdhHGfOo1GwSJL8Sj0EK z59f>$Cv8PZ9TYlPr#43-WgiuTu@0sX2xxj()^xUaJ0B=Fx^GSc{gVS%DJcpAK?(1j z?_2C94;QT_2QNo|34!d;erVu!`E<2yfm2sx89PGgPV7Msy*ynzb$}>d8x+Z@a@(_e zJG?8C-pa6X95`*0M?rY2d6{%qfNw}h^;_HU2OCY>u6by~DBR(^quB=4jitVuP@smn zP7e7I6w}CM2^Pe3|683vFU!9K%B?ZRL@+v^n_aGZ9H}Vi)D&79LsN2by@bB*^3Nc_ zgJnIHwQ8e`Nma-=wbLe5OI;kX1J>GyxEB=L89LuTnmfycTRZts1y7j1(z67Ou*B|b zq1{BR(tFgFEkvuCbG1U64*j}KmSsfWf#w7_&dlD5KTttr?7se)FOckXy8Gnq^21M? z)$FZ_bF*6q(O;j?tc4-mKn^#vkj)uWZ6L)?>-#8$XJP<lk)#m)2?xB5=4y77+KDS5 zDQQ}*&NW-qRn=x`MJwo`>#<!w38Xpo=yHg{he&Xc>l`}b-xIG@1xU@V^<g(^C8i+0 zn(zqz>^RGZiUu5zno&k=`bp%@Lht2$4Y_0Zli(>MB&TEoo?JM2vUO5a7^D2nlVZtH zk)wR7p!~F!H!{}K-qZ1H{@SO`2~g|hio=gf0bn`xwQP8Ocfj&n*H!l7<$qqwP*<un zD@$2j{tb?+uh56(9I`#4t-%kgCO5&p7(^6vOc49j6{X;h-&;_&Itt843gppYV)y-< zaR)**nT%v-VH^rML&U(9wi-U~HNPwbc;vInIB1N>6cw`jqZ7_AiFY9Cw{%(6N_vQa zM+~}b_|>?5e38_2g%mjYq@sHt@ky)@OJ(HK6X!At<EQICCFdbAcYYWZm-KkjIJND# zgs;hlpjRTQ<7?~Vm~&y?6;~Tfjk=b#p3I?#wkTPL)*K<67-i}u6i^@*D2T)vlS}h| zd!z0?mx^LaY%E7c<5w~03$o%ORI+y`SDo>y9kEEsOa^->%gIG2hBCno;AeFc>nx34 z>Psj|j)CK;t20~D*C1w5ow{<k(&%ggwPvdNi-=}dDp6R@X^lzVu{oE$3qmgQyG)JD z<G6Vqg$ix1J*}(1J{S7pLAo{`S8va1F`D5Yu&JY4tW;(ZsrS1q9W?+G()DZ>86~_D z$Q7EkWVKstQAIA=alUcz;E98GG2*CoGG?25gMU1;V7o@*6e~ROEv_^q%Fnj2BXs{b zd9umiv|wO7O%&0-@{@P_BmR%Q_3eKnX?NS!NO<FVRst>w83oD<e5gdai_ZDcU}4$3 z8^g51IlNny(n?cM-Z=Nx-Kl(mgXD^EbY;CiOEn+ccBX9Kwsp(xZz5DrH{1gdL+Yf} z>5FN9@HhMOKb!0H2BhxL@ox_oHH+=dZ<iY_l=>rD`$SNaz(B7kdqktHG3a@j&RR{I z19yeIA`kyC7ILDix_M4(aJYOI_Xy9Ehp4m+gRPb9J7czW503W=diX(4pU6*Xzxx*| zbFuLGp&Kbds!NP@5$1YrrOecf+u%tU^SB`K)S4e2G0QHv#(RPi?XMi;`&s^LV>*Y) z8{o<anjN;2{EYsX9^`uTYZ%kpCMO-E+3J;eOyf71-OuSR|DHFKOs8DdlSiNDh4Tc$ z5w^%@B5ps|hYf%wxS4O{@OT#Oihq6qdmnRW-W${|1)lsn$ad*@zF$PU9l+%H&v^Xu zIB;_>;YyhAEuYnO=)6@MGBXOj{r*fj`S3NQa;XT>7a#2OhFWPj2!E~@uF1fH&zYG_ zZe`>%c|#a^To*~r49OZ|zx_$-jmz68TDb|N4`1sZDht5*U9n^>kGLo&CC1Z+iSvIA zjKUst8|mV{5Y<bSRF0_ewD?fgper5*I|)Y;3rkWK-YfkQ6Re$3GYXKv9Gzsj#*9{V zRB=aXefSGQj+Q@yOz3S|zrSr&%AMrFz!*J{0Dt6bPT%oyZ(*rOYPR`FK(uFyyGHZ; zjEAXjLuLhxd(qVvq%*`wmrUvvBG0*2eX3yjm|#$tTFbOwkMDVHsX+C=@FXinm%adf zKw}>AP4h7-uy#ca>4w=+1|8(qyeE$?wkw2b$k>R#z!&MwH9C-AJbqqI7aQv9S&aj< z{DcBxzG>Dpj$sC;SYG#~L^xd1ayI62!>;Md+h@FnD3tbVB200Gdae``uYd5$3Rgh$ z2MkH0tC|>i2gqdF^~&5^pQB!<HcQf+suW>#2QLVY^ZP3w9bql&d?@^17H71guut0> z54zAmZpY$7&%6H~g5Mvy&i=xTOEKqNFvsFjtgfvEB-oV0lqLG~mgKUv6+?v8cCK~? zQ8x|&B4<$VfJiv-dVkR*_y%xrJ#ofi`U<f5;1nT*;^mNW%*X<-chF0ll`tY9p(W_) zTeEi(0UVMi+gJR9L{VbE*ot~ISPI8MdZh#?so0y;jck^_w(du_I>UU&f1*O0h#k^L z`}UAJh(U}bsdhzLx{=5vsmN+YAMMK$DEF{Fy&2s0kxpMGCZ@W~W|ZY%co(w6Ohyoa zNEzU)hZM*;dXYS}^5CO%BV$=iJ^=1Z0+A!QCp=Q(>}BoaaFY)h6>c#|w{o4LwktRf zG8Foa6B$knU=(qRZ<7&f+-7;U={wgjaR&K%tA54SaZiyR+hLt`XOf?I$iduCQ?_8l zf!FJRe$I&X6&P(xwPYgtHu`N5Y%^KhO2&R+V9q10Hzp))^G|bzkuXBLb(eZnTN6eq zLKCSRp7rNd2GZgz;T4KBbFM1+gngu*FT?o72^MJd##|oj)yRA8x_61CL>QQG8YUPg z{f;`RKCR2D`r)NiW9W@8Y$0N>N5dFsu<%~UDGUG{$Y4u_xd>mH9EPqj>MaX|Qy%-z zl;7T9D0dE^$>sWKBL4mH0emM3mNk4*H*}W|P5oWadCjR3m^VDN<Mvf#wg>9(Ex+N7 zUot+yxVU{l0z2Sr@FUR9s1w~v7J-Ck!}<RCbOvgPb_FiJ!ESxM6zfiy^*Y>T>$b1* zHWsvP6$|LPdjll6uHV<+e&oT9WVsRn8W50K#T0F$tj`^umGzRf7I<CqOEFuYtFxbz z=&sOCL;qr0yTyyGaB+eat4|jWaWKo*bt_O_L;&u5QcvC{`PMSN^Xtmj4Jdk1d9Vg3 z;7qK)5HqYkM9d!+DdbO;XJhIG1+qpP9@kti--{VEi$*erJzmI)WCsO9tCuu9k9VYu zE4im~6U>6@ou+4H;=)ZMiZjluas`T+fZ=z%7u?lR@NamsxS5oS9BOHhGqN8!T~n^H zvSN!jJ&YfcU(HL`q*@EkSFuE3hEt-lZ@wjEFQ2N&btsK6s$d0NNqm3&7XCbcua01I zLB1@)3@m^1!b|&Dg0ZcBS{wF2W|eL<H@<bIJWpVcw4PY@vW$~azfM%b5cvgEO;<=S z->RrsuVYao!9H(bmK~n53zqc!gbWLU2#gma+Y_U-7!-RCG5?zZtow}7zE;r9TEkjK zS~MjA?Cu4`N=+cq6SF&axh9rV1}XmKtODQbs*%#At{*kggJ)Pl>DU`%0a_H{H|{^I zL#*3=iEh>r%;j)d?{56^fi*h{IEbPS1~DK_{Jafx_$o$itdzmnqA2K%(vWOF-}9<J z_QP+us^1l<ERnzuQlaR>jdF}-d`}b>Sqdih5!E5;?Mt#ptrSZlvn^n#hVhHgWN7@X zTKj}~BtB;UOabjl{6oX$V-q*r9b7!$xMT%`-|(R8vNrVhuI`Na_N2>S0#qw}qD?VZ z-g_LO_Kl~6UWQ*<+u@uy?^-1{sZSPw`tp3XoDOuvzx)s1R$DKD#ZRw0gCJmi?0WYY z9{XG2(3)o|Hc{!d%iH0*UcQ67+e4vJp<YWp12B(%`YzzSV}z{kTEM9yo%SOSAJB1? zisa9#7AMlkn{hh)I-p;jiQg-tkP+9Qi2bs9D~=S2Bw04Tg+!E?LpW8s41#)i)G$`q zE1llis)doA7(4BX$Qj_XSk^`ABvE!TGT!&XDfU^c1@gLI&<TF?Vk;7;MuN<=(h&2Y zmAJ?G3*+!A(ECK-xe6?cY0qr^kWT@sM|vDk$12DKteZLnIsW%J;okYEJZGEbh8jf> z7kQxhLt+$Vxnq44KNY7+SqVcQG5-{D0d|P+Eh20S^9pmGUN)Z6h%pl?T(O$>D9;NL zyjcG>soaz76jUA<TU|F*`?CQR!@IBMExg**gRC)+fVr^aV@`L(3CH(&`VLR_ft4Bt z!B3ilh{St01CxTS{h7c;I{8Il?@-hz#Vqe=MEi>U5StzrU*A4LiOeHUjNWCV%lF@P z={q#%Y40pmt^8D;2<lCQtd(tO3@cALsj1gsjiBLb4?G_{dgCzs--xzsZtFHtwDokb z8NKR$D3ZbMfccAV*LA?mbslML$16NhS3%aXu?JP~$+4*4<KBO$*ZnHcFkEy3zijc) zcF+)-Fe9x%qK5d9Ro=PJX5jUsT3O8==YT0*3G$J#zJ{{+mC7MW?08Wx;3R5SHvCY{ zq8Cf8VlKI#R~g!f>;8=lDR81#G$Kg(EK54eyYCBJ@??mkbuT#UD5^;UL&9CZV?0;b z^CvXrtzX!K>JUsS+jL9@Zq$`x#*?<;KbJ-gSiDMWsAL#5<>)2y;NiWHoQSG|jr}kE z3&-zCSiw!mSC-Q?UD}_q*(<RFd+VX}0&mmbZzBmr27Q7A4q5y?1uT>%Lbkc3nIkqE z9uZmHQOZUMi1Z=4CE<LR#UBIy*iUG$vb|d(6;|oVcSi0`I?6cBH;RppCq}!P>7ADu zL)%xLfV|4|HH?)Stl%$u0e(m|_`Gb*knr&P8~0~&%=9nP6z(UY3<z0piJH#z!b!v0 za3f9gD9m3i%oaS|U!$2ifzq{<WgS%#4pY1$f@A&x>ZlB&IED!A0o_qhz`M$wRE)`4 zQ)avsi3zV6Smc#DKdO=|7vzXcvZ4^(4a2~5gCS({#pmmsZkM4gqi%3y4uj{Q-*59@ z;u8yBsamgc(>*dM$=3c-js0jMte~iztuAnh?zGT3oBU0M`#2k=VI!vU^l(H{L8I72 zcl_jaTX}n=mgxw7*D(nk6#vjb$s`=}*YUHz|1&1!+rATiyGD$opk=?OYJn2^xHD|) z>H{~2r1mU>XJ*j)myWl?YJ;Bp{mJw2d`%@uUNdMRG&TlttX%$}Ui0j?fhoA`(D&1h z`!VJb@5>93gX^Phsp`O{d-H^V!wV<lgNt>S{Ef$l>})sTtF@r#gV)nVm(^hGm-}-} zvDe;J3WXGqG)_W1^7M`Qu!RTZ;r9Du?K`jN;-NV)8H3QOW#H=q_5()BdK-*r$^4LR z2SOO_L7NA(?LBgjaTM6p-8K-yDFj*$Bt7v;)co$dLg!DxJJ~;r_GH=*&Ck~s{rO|2 zh8g~4KT;We-9e_C;SnvR<8OIOEh(o=GUDVBkqNDss7@lPY-muZzS@ahx^}C_^q5{K zDM~u-Kxu*%5pVI7BIwx_81NAB&Ze{R$;{1(ShXuwAbWzq%Ri!-zD+h|1I<W;Z&(BM zm^XH{H-2%@wxJJ3A%zS?C_H--NMb0@lch$B9uaAJT4Fd!hOqk$umbRx+CFd|RogK1 zr}Z9rx`S8Tzh(kGN{m?<YN#VMzICg@$M%R5hU3%eZ*SApY3Wur{bw~8^;N<gX>^4` zbdIQnxx=s)phN&&%)EDLjqY*wuz|3O_a~wpl1ti8&PyOxy(`Ue*F8ym{^}6e0<<VS zv4ad9g@CFQ<qLDla$bF#TtG@&RN~&rtxaEeGB=WhE;q*LpWzY*L>XL{4IM2E^ab6W zOn`JwgZru6x?51xQx6BP9g}nG5mc71hcX8rNVi@|bIv&spe0v#d1<a!bZrbe_sN%P zt`#v?_6E*lFJTqZz9_3``m_2x{K({zI5b~*I}I^z{$%wm|LyBr`4-T~#sZk+h$}Z_ zM}>;Gp@c6K<GR#~Vrm5SJfJ8I<G*v!mFtmCOI`uN0N%t@mnr~~m>C-#+3U&7Fit&= z%pz}<D-^=8%7#{gFm{FL_p5}PnwY5O7ZX{K%_C8lAdZZ?M^gN8v~Ryeq%#KiPSgE@ zSv6*fSIlX?!n511lp?T+WoyeB#wdmDj)d)wxebO}5ABpW@RU!Cv&Gf8+4{yI*X`1p zDI`sp9mY;R(u2a?!fn?!blJMvjA4A8x}+g{afk+-Or4=%FfqG$Ls%0PyQ#9%hhHUJ ze5ja#NuBVo5%qQHk6<~-mHCghecq`>F1MLzu9@B$j35Z>z=PA$BBp^{z-x_rLGQFZ zXhmqqtedXZ9pC=BF;U7UlFO4d0_}E}*v5{bpW#|#UN`mAu5qZ@?F|FtYND%61Lq@V zJ^v5@=lXo#MUR-`LMW9Z$ie)iXro8D=`=ioC<5p`#0N1gC=PqR1uPw}c^wZhU0?pp zlzl$iAQSU6?)pX<YQ5a^a(xVxeDVX@3YiVtzIFlkW8I<0UD~ci*N!!%Nmz~`AU*1E za0)#)=5Y!+xD($bv8Q+^@O|<<`u>xyXxHmiUM>IS=HLBreq6JQiEUVwBtz6oUz%=@ z&P<<$z?Z%4+46**mlFUt67l%+;Rh%pE`bo6Sl3{2V(~!XodxoD?d?9hR`MirrGJ6< zGjqzf)Kx@}GCWBN(E#0dXDy1zd2Z?rhmb2WyijCZs{)4h**Dr_)TWseO3{5Ki&LZi z!Fe$?6(qL9BwygZli_SV_DskoYFiyjkgWZ(>~&L2Y1*zB8OL2=<JoVAjA*`W(OZ~K z0BLsQqGHksbyNCg)9tBe;HA(fWb>_*R}24xX;jvo+XwjDjZ<D~PFn)16Q@w7sNn{? zzvT`sS#b1DHQ}~lIfU-`715fyh1MQa;^8^2{dNxYwzlhiRg~HW^k5Qp^vggdJ=WU` zj)6}!Y(%AKajACgXUM^If0su*>$tF}_sYF~Skm$JB~$k@sZJ93{c~yt|E_7kkZ)vP z#Af^V*OQ7D_J~;#U{T7B#o@RJ!0Y}Gm!}K@7BJV4!NL<epe0UvBK{0?hOm{tV_MbI zetEa8g!v7JLLm0qHBJZ^ZF$`7&In0#D67M>EkU`l&&b4%(=EkqpWlpRrPLXENW?A7 zLX`3u2>ZORbfi9oQy`{`@NNYnqp1`wz}k(zq7TeWG)Yl>I_7(v^84Zlt}pfK`N8<= zki_8lvg#>>cI6|k;ET^gh>Uro<KQHM&+Y41wE0TS8@2lVEs$~7<aJ4!!lVlSOvqV< z*!RCN>Zj8j=a1qxOR^mT;@!zqI@^P>glI~AXmG=S?hEjTrLr+Hqo)G(k6EW}%Z#;V z!n4G*^?5{gij<$4ad<>D40Or&XuL-_RTptx`L-7V!>J{OEJggMT&|6kk(#P4?IR?h zp-Vl0r~yCEG*5(%l&VIMSyXJ-x?qVDQTRgJN|tMsm3qabDgAP@oE$%VD$0b*&i&Ax z8@dX0=fj1`*)HTjHw@uoJ-%mFw8`M%=F@pPac+OgGT-GYtjorqw!i^W@0%N>c9hG_ zmP3*K6&$%wHy2U?9HV>+4WAnS86XlOMSPe)jf}t-kvL@WQT}mwzkcWIOa5~Lo8vQc za5QnC9O^`&KS^X=vvarsN?tH{YkxLk|G`Kk@b)p=rTZUX%wGR{DE1bCbGq(NxVb6? z`xtPy&+iE=;Q9yTY5X0c%m;9plUR<68}<>S^vdn2b3B!(x8w5s?&ph7DP(AQrPH{N zdn3sJwg3E;z*Xr&)Nk(XmYCDHrI!;0R)~}GaAfbV^xKsv0eQ5vMsAlV;g~)`v(hV8 z1Dw&>uc~V9TsJ7ob%ZL9u&7o%jek+$;y5XI2_Xpl3MY0XB0RkSt`9y+4C7K5(hU%A zdCW@-Rh_vn2&Xxp*;$AuEG{XCVgEPlJ0^Aq+vThmj!{<B%wj2V(Z2cwxO+^lS6NEX zw3OqNrdB4JieTHKYKTOSmYEAcQhqE)2{sJU9HT9E^Cpm4r<zxj>p1~380wUtr;uMH zZPQk<f#EU(&53>s{M_Nou642Upc3n{gk|;Z<U6R3`kguosbEcXHlmC#ooOWusqy;} zOR!Uleq~U42Ik6l0!$uX9Y7H3)Oz`Z*wPB^l%@@v6t+JW)$eh629|l2!1F#bX{zk6 zIRD&+Rb(kqF4KS5m>d|Lu-Y2OkvUB4blc$Y9wm6MagG3;O*-FG4xnaacm=r@6i%9v zBYfZx$~~iDT6G2|9BIJ6+K3>KbT&6{?T$oXq_D-V&ksqGsAsZyT-5D17N;L^jFU)A zsqb}j(q0i1dO7pbgG84vYCV2%nTiw*Xj6!$3x*=4#hcC%@M5kzinI==NrN~`9I}2a z=y?SHllkI>E>E$Hf^ER1X>VP?>OrwQQ)?p@(L@bCPv2!ZjKjH;x9y~`sq5?r>^N`S zZ>(*dTw%~t$B9y|XhA)F58OvyYxj36YDk?AeJokOj;1d0x@WH~=G<PmyQ}}DPHq^N zmXa^aqOrAxnRQlkUH_iUAbM>52Ce`b1|iHdT?4Jh2fJqQ<WTRBmt6FCC4^@u-*qTA z)s-1-9qu(Je}TTh?i_Cte7(JU{{ZX|?0L9&eb#X?z7aheI{_!OZuaadot%So0Cd#R zgi@?Yqwh2DLTA-tQf}1u0(!or)XEE_e2kWCYISe>oDlJIAG8R@`^n|oWMQp*j`CqL zTOA6>bQA|#f;gF^7m?n1%LA=IB7yg2Nejw~11ch~EpjW4tJ3JkQkmB?wAnxgL`0AI zq;hyue^`6teFKFn^^Lm8yPoTlS(t4VcZP%yytya2<UDmY%wXeC2&vJUehey{q$j(S z4e~rNWRx^HK;T*s1&iBMfwd3&?a{Js%YR{57w|GlvSC_1=tCn0eyge=*0(!==e2bG zfN&E1w4*<7#^9hqz(dBVf<a6rI}$-gG=;YQ!4$vRnhI=D+9T<tLhk^Zq(MaAe!Npq z5S$uXktLDIH$oTQvz|%abM~13{U7)XASQ(sk_S4g6j|xfjsr#p+!~gx-ME}wHEtnN ztyRuVI<((jedxqk?BqP;SScE`&iRen9)VHRmRjwY^zGQGtaBqp?Gg}1zmc~Mo|K>T z)1?%bq*)ybA<V0xe3{%}?o^-77NvgSzGSF8q>WRi1a^KWg{ln3Q&|mz+nIRT=_GIa z^l7^hDUks7w#H9)!3?^>(!t@bClU79w`xZch;3U%hk61oEe;L(<I0hr-s<h)!62-L z@7fmJ1IkrhXn(1@HbE=JG8v3fIm^7RpHJ`Vm7_d<>$5oJ`w8Fd9?006!sjPW%1$hU zkR-jdw7IL5S<H6Uh+gX$a&#7eK*TGW0Rz^rEIc1jwT-LugncDZ*Nl)y{7G2<oy?OG zH1vduNanMScM{o=BZ(X!nyfhlYdtC&IyyOhEnv`J!x9gMD}&A|AU_YH%83FyvyJUA zG=mbjh&iWaDy<7_?2n{SJqNm?-U`a86IJx*(9q(`UTq()<-@g9Iz%)E1Wyu-HN2n{ z#VH8-ym~{iCgD~`+(woQWm{I=Q?FA#R_1?%m42^k!fknZIE|C*BQx(gw<8w(zMg}( zev-IuxsVgFy`|fNwzu<XXY$FkbP#;`8CFlJCG5lKv0aeG`9cm7s4hb?_pvjtsk$y! zQNWL@_`!cL(F0D3W}QUpr@geVtxcRhJ*#|v+5=}ci5hKXA$@>&zUW{ZPX+^Puh~r( z7^jcC0|OckMjkS2)!aT1rp9RIj;f(u>4pE9Y{f&OMOrD%6X&P7{LWeLMO^WgssX^l zsHt#KLDt*5lXCP?%=74)4tqlzv;^=M?|o<-`(b+7^K@2ghq<s1irvPTdKI$$y6AK? z?lR%+$?#GfK(6qL#;fGl*8S4g)-W|JPhWn2&@EvU6ej4mAeEF9O5tuPz3^Mq-j8zz z;w^mL+winA58*$dma6!b)s22c4Wi3Lk*IPnQ?icd%n#R(s@S9n1Uwmf!^`vDh&31- zSe<ygsa9WO&5&GaxYu9NRMjod1c}|+YP=Kzi$rrKbyP}Dk)^WsERZgpJYz=;Te7h= zw$9Vb1)NoXUl)vJ<6Zs&vKM6z*hdWzNc1}dwl2YOpV*8RgfD*y3(npbPv`ymyEx=l zJGDOaDqAoCKnyIJpUL%bwRRLwDWkdSq8hOxN<3`S)es;yLA(*euZVxcs*Dl!(_mRg z{1>9$*k=_5luB{>ZSpWTyF(Lm=F3-i+1G5(xgxA86a!0Tyj{yySq!+K`fm=Wu-6s| zR29|tzntLPa&v1@@9A<q>SzE!T)60R7<c4_mxPfoIbCO#<$~snz0<N0JqOV+$d<_( ztAsw6XF06+Fu+I=?hdW|%y$90G}K-?{_Uv(4o=aMGlryh0!`qd^}ze@sU0!5?nh{~ z;Sd}>)`EJ2R8A)BDA&&3qxI5l@d>j`e|som%6*m)?p(7=PpF*ft&xL<%0eSfQt2Mt zs_SH0d>*>9AGG>5Xw_==R8P?Y`?rhn+DhJy>z2in!usCS*N&E}SsaL*N+<?-*MFs+ z;Ye(s25^J=F3zmqKL+&u^F!!$^7`4z>09)9He^uNCcdd`tJ>xljFY|Tk#Y3B0*A7h z!xFf3waQ~Q*uvYucS$zwhsw+g=Usbrjc;!=eg`$VxyTbJw6HVMxnCEfTwET-;ASFx zNV-k-I4UVRf+UYqIsugok2BJqI@b$J38zYmUTQ`k(}}W??b5I(RLY0zXqA(^A@U@V z?bYwT`9)KJsWiUh2)kvi<eBeG9lwFPP_Z!CO2=wnQv|_d!Mi|970HQF(_qAH$#B|> z3pdsBBhtrl9@V$yLbhPFO#yID>}gZW%s4LD9*-UlRk=IfQ!sD-y5lcp9bK|p#VF^7 z8n)(4lnmyp<p^F))Tf8G(}o*bNK=|7?;4d~Eq0a^wH0xPY?7K*9gcI-+IAowVlbSL z*o1HV^-xCe<2GVS_mkfzFZ#_cUl8|0Q>)A7-;t?649d+OV<7K99FO(A=Dj60_|@f& zqiOMQ2SeS!HO7WXpAybWyh1JO306^DCwa?m3yr&EKAuTLt7azJX%A~yt0yuq3Q7u+ zL^oSxhN{L=eD;HIkW~2_B=Sg+GO>GVPnOwX=h?eV##EpVr!mz1t6hcRV3Omu`n#4u z@C6}Pr9eu`UUo+5{cGH1V<ivPQwVy0>&w8Mr{4}LS2-q}ptg^SX=yWpgf@38^HJI) zU1bC0ZpMhd*7as<#9Y+xb~u>YqIo1FFFbVPS#mU__o?{fDvMO){~lp2x2h@)Bsqw| zybIzWs0^A0Lk4ejIEEv#+_Fw&vpi0+L~@yNaRDyvg`8Bx;veM%fFE=IzjUH<$vGA? z_PtvjfHg7nt;ieYJ~n~<IS`P{iM5)}PZN!?8lh3)Ay54=yi(E&!(A0#H5kWt1EJa% zxGDD=^0gYtlyAC_2QrMyYQ+AOYfAfKqlQ~!<%_sqX=z<?O%T_Aa+mGqU$V<|eS5$$ zJkFg7BdyD<KEwFmt)924nGx`u%UN+)-uTTqF^u!8#I<6rARpo@=V}5NuHQ--!kMJO z?YVHddDV)x8ADYj(v6_0r@Y=P0pJ}yQR(j`R-CM9`6R7d4jz-t_%8%V$8O`W7X{x| zX);#=x<jYYuQa;lXz=0=$Ra8{(HJJto_0c9&p}->ii|lt<Tc9c^TCnQ9^od!?C8bi zc#Jop_;*rF;=E=ZGoK%Ufifz(PQ4}NA34>`Mx$2NqO}yZ4K{Aq9tdz3{GEWc&gEpZ zxe~TK4vWNc{$1Ok`iarA@Ka5J7EQq{YTN^sIL5$sW|=~4T=;tT^xuN0KWZiL99;qb zlECzddpS@oxHd49VnO2t0<^_{;h}=}ego)XjIk;0lMa0p^X<Q1Ux&cBSVvWGuuiMv z={^26A3W9WC6pPGS7AWXl5oki5HAhwV+l60R_SC(C)^GU%XGByTmmJrMM5#Ant`}x zYKT4y6)DCAAd`it`1`X4L)u6e`?8419EP=5H9j`hEBCDv^1v#VPa?(Vp>495hWllk z7z+l;92;%^F_x-D!N$rhrXD-diQ53(DNJl>_gsze@jAtMYyp){_?6a<(5YSNXQBuU zn7bWmz<!S`y4J(&Cm`%dO7$@{*CfSiM5g4rI86<#s2iFER?Nm%SpFTFt*PJlJ8SH* z40a)DjZ+%8A*4X?fs%|_GlJnC^e&jPuwvFueQqNG)ZHW0Wmhe`8%u_tMaiV=W%X-V zkJpoFCWNA^iGr&Uvh0n2GybL7C{;=N-z@HW9mV2B*#Cd$gr1t(y}>`|n;hH~xU;x& z^oic--_S}bJ$`4oxoHauh_gv2%}DsykFy%rLp~G06c(`F?Qe6(T2vFSwQu+#+dx8e z4{CJolrMz0<VMZo{%^RdQR+MzC>h6^d}ha*cpw;doE6hW2$<gddpfPP^Sz*lw3_Qv zc<L!)(7ql09SUs@er^$Qq`g@|d$_ovTgZC}^cO;9q{L%bR{q`aFp70x^`;0bfHk*5 zag+YO_K_T|+`s@bf#zq=TllDE>5!6VO4zZB0!VX=Yn)uOcbA@#?a5NAm{f^aHmuVn zR9bI9)PN7-=K=L5m-D-?rj|e8Vf>;e$GHz;Cf#yQFjId2D@HJ99^oFfn>;Vp6fXdA z9m69Sydf=yj<?LoOLA$@ohC%Fr=IdzY{}~en<EUF)8IiNc~(l~1C%SH@`uyoB+<a9 zITHkN97ScgWEj**JLrf2^o=l~$S-tghrLhoKNPK5>Lnwkaly|uJ=9^whUoC7%prnF zxF@BaIOis)lYcj%G<3lx#HH(*w<(4GxQ1qKy;}Gkf%@oR?!Z{>|Da*w0!f6O4%6o) zSr!|EfdFC<xBF;|&F^}9e|V&v_I{zpFV6Mra-Q>5HJF2th8WDWP0K%%?)<Y^kpQ;9 z#}o+UvcL<-y}t0R1lk-&`Sw2}tMYl687k9yNI+SzVz-2-$N|B`574VUtz0OnO`Ut{ zN%`dY_&S}VfL+x-T!Gvf>0p1(-XCp9@nkedf9A(K@9FpwZSq`p>h0fz?@Ihq+SA)l zbENR_8hls2zp<D+s1(D5<7%$E=5j^>hlE^nPlnL$t|WD%=vqO571%}SwamZuUGIqU z?d4Ex_Bv`1J#FbNhhTG;2S4$<Ft9fDsxpIjX!*fDg703i?KRsZn9!V&(Zy<ukF{W` zIFTC>E?+H0Ltf#|hYPxMGM-LRkr-4T)O!V~%_eR-&~0Hps$1cL3u_>f6S+X-%6$FM z=XBcmn@(J^ii?f<$>9qmv1KUUbWpkt!xGDqrzpFPi#VfAJ0yoKG1F0i7O8=xx>>7t z?uOU3WpK~Fb#zpLaDk;MgX^g(n1i|i1e+HU?u1`QVx<iEEx3oXW2#D2p8smTe_Z6! zp5{u$X@RdUb?RqLyv|A{-hPNmG`CwA(?5r63?NFz9G-V6U=R51>Da%v(C%zW5hsGJ zY}T;3&?;l%yV^9#WS*;|QdA3Y@xB$(&`L`}bd2STYAUYvU%U~0YPE(ny<1<VTh%@l zo^aOm7nCdOr#7$CJSbF<(T6Q$l6~!UvuPXQgfBd0+M1L^C@Qg9J;RvuB}cOAnParK zUyX<tW($%CtXosTTDJX4fPPxA?s`;6d0s9WnR5_=it!txUnu&$dse~r!yksZd!tR0 z&xQ2AN9~?%&Pf!iehV+u3L}-B<IBi50d5X;%($Zh+sBt7=%^S{-sHtGsAb#uDmFWE z)ILG?%bi4*b-?lD_4VxgLZ;FH!dj8i20>9R6q}!mG`FtDtv+(2xV3tsU*p{^`dxp3 zR*TwLTLPt6*`OIl?Gc1q2AZicavan1E&}{I`tS32QuM%f2}Bo7{_KP^BpSwfxj#)z z=R+A?v3R_50oM(tYlW>Fk-=MQl(y?PAqdNpj*Y<-m`k)84P2mTC=_5ATrCBR(l#io z%CA|3<_Oj{v*;8RD0ofNvGEaxaf70L*l5wt*H;Or^0k&ax<xnapDPmPzwlF7{<t4_ z60(hq)4F2GmT%Rv7rB5x1gC}mxu5*y6H-}VW(YG_bJg*imJHM<lE^;x?aYi|z=@Rf z#wnEzaz4Q4z6rv)P3aRWu`&+pnmoU|tJbLClx?(HS)ovQGAL&o7o43<Jq&wo2_Mfs zPe#P_O)X|I4qu1A4PX)ue8SrXsHi6ZIF-5nFZ~iA<AbM^^6-oHkLO-#7%4O0HaZuR zo~Q4x)Sk6wr2o=fy+32VW53?DKcDHb4v)+U78icYp({X4LBVOk;cbF2&gP{?vKQzu z)KNTb$8kA{bHd3P+}LbE%7V?QQlYfDi)G7jw8hpTA$f^LsC<~kNYpJ%jkzPbdnE8| zMng4QWa@4qB&loyxgAN~%$<JD&61i?pwN><YAxi(V0OHUT2XG@foD$cMk@RT(H<XF zh^C1Dn#5uYOANf#Z9920Sb)H}n%d~|A+Xw2I|;&@ZDe7G?$XXMqmfVc>qG+?4SR-q zUT{dVGOi%6W&gbNggZn^4wY@UC<na9!<IoTC+d%KT3RWDg)>9K=EeAwi>5aZsy-(; z=3sV7^{m>^l($8#{LQ^eygri!lYhipg6UrOhOolmK|y}Ra3aWKS9OTku{a1Z7rSHL zs^#RgX^Ti&UcyU>UMR)t&_nQ0Bhpg`n<wd2G&<1UX_?!~(bGOL7p?uGiHWTg2BcDA zbpv=seey_>Bj*Wz*vJ~`VDs5J=t?3HA@bx)H0p5DM)8^qzU1P1E%E#cI09(Mk?MLP zB8_$Nq(pumYm89MyD(N(?2_}u1q*TQ)Q@sk7)kx3W7268)po7m1-_OS7j*DY<9=;- zO*V;Wu*ee1%v!a*eJd48G+k4tT9!TP1;_dv+^_7raxYH<&MCC77|C-4E12Qz4H>?y zn16&k*&KO;pa1R{9S~EG+paJgezG8rO?@*}H-Vqt1}x+|MzJdL9sQx(uip<{*FW<e zD45C_DF-lA?|vVYs}LIKju@JJay0&lC`D&xP>r%oF_jj46212Uo~_ZMl2XL)_bI!d zvH9huomfZd26y#1Z4-5qW3<@b<I|l%jrE-)mU9=&X3u5>AxB;@;tcS1zN4wXr+)lT zHbc(>R=-v{ZuT+#3br%}&~IHGXD2o`kYGSw78iMAC<kfj1^0&DoQNnZ`JGs^KFtwy zJflo1P^u1u-Jh6uXUV}=4sqY%{rN1Zz2qV53#xPKhNaC$G#d)0gl*K4Q<4E`WEk|t z`#pKCit1-a426-boB-b>0%%DD|D=SahAAy8$5UR0|3>Gj4&7>nY%v#x=P7ZtbBX2g zGzL>Qir2Imyd|z6M=rC^@(4Mx;FG)-s9dz1q-Y9zLkjQVGF6A&yOhwO1GZo!8MOty zS=1rajm`bOkhe_Qv-j0@>$7QiY!^XRpN~l{ybONnG%mtC;tR)giZY1#GTfVs#wZaK z^9BfcI7GSU!gdp*$6ONoH#@rh;E^f#Kc!<<{n4ndH__Ww?fq5Oj_{?GO*D<+!~8s( zC>G!yFj}HpBT-pG-S=g@hTLOgAc{ABug%-dR8{VmYHFCXj;YseW;c-&ykqdToFTtk z`R~{<ZPl62OVe$EI90S2lj#WRzH+&N?|phmdh@L^%U76o{i{DPqB@;HzCb6L7@W$f zGN<k@C{e-ibijX09WX2wAqK>8_Iy4qre%-<h_tduG9$pAPqRMV#MTujxBee?PdQ<a z^kp$Z;?+|D-HAo-{_S|tIQWq%;QnkmnNbDF#>9thr<s^?BVw~F=pnCl_YLf$=t#CY zwBXw|e5{o)?%+!Kj<)uCy{v&k|A~BsE>%+J?4%fN*e;CaCM`b?sT$S8lmT#PgfiE| zu@hv8DqE@+3^JygFQQ?n8K_TdUm;ctg@pO8F{bX7Nb*4~aiV;l-R+O~<2=@2`o^}z zt<P;)o#pJ3A^YKT|62X0Ch^x{Y2UdVjDk6vW_Z?Pd|sXyj3koC68jE|EeI3sCD)g) zhS15OSXCIlex9h+{wdGd)XYq*bOUM4rN{UU<U*L#`q+-hp1ZmRigBWl@D;nW@TT@# zY(AGZpP7>bEL*hlY`?}r*$X!yMkSf|$O7qbL43WSyvOHb9&%5lCQFE)895$=+fxY? z6ymkmw9h%4%v&VZ2PdTuX>Tzg%FcV9{4~xhx9)et$bzhiG4YvVqyn$4*01CzaqRgO z+t@SsX|zvQ=ISL8TGL$)sXSXAA~m(b<IPKduaV!MSc1a%lbSd$>>7e`>T9YWPT#9f z-rz3x`av%CtS-+RgkxxYjO~Uf?(&tP3$u^~p1c8kS`Foei&#YpNj*|=B;hkPjQ-KJ zA5}I0<yVc=41d?|$5J@TsoUqwV&r6Ng@15&nMpD&1~7G!I7-iG&YtKxW&a&z)xc3! zXH3m@dmDemQL&aK_5Vj%LS7;HuN_egzZ^jt6sb=5779;n_>%SSRZl6{DH?Lxiyq#j z6*n`)>M@De=L6(Oi|2a*(z98G{WknyQTvotq|QBE6yHdUln6vq^<D|zv39HWz-*g~ z75IHLm9uW2zezgi%CVOuK>}RM7Y&ln_y!I<8bin@Xk}F-$K4XZnHI<(Ty}-ZS2K*1 z4di~P?q{-{2Bnl>hD~8svvCN#HF1BMVV}V~U-;50G}a0P$pcBWR9AkH+@!ZpccjKu z7i-Q6->v`Mn?IND(StXG?cW9CSl`9oRDu^9jniXWQCE%4!ec&KvgF2DJbZ&y)s|eP zCQwo#Mh#7B$t!Q-Dk`>(BwMU`GY_&-0(ifj9%Srqm?PM_R(T}PPk+R4XiLb<4ht4n zQEDVxbK-EvTV~G9!puIbT5>XfTc&HJb<CxG{cA>yc)08KfXF3wM34)gx&y&a)o<NO zV!(8MRd;+Z6bP?U1W>QrA{ZcA_yT{}Rn3>ht1P^Ft6?vptfEWJp4hc{IhTF}<HHz> z;Kdpck7B<7$#QT{8;qF)Jg5Jq8ci=xa%UU9A1R_O=Uh%!gGO{KzcL0C1jpr^dqgxb ze`~m75}@H4^xPyZQE?*&cQi|W^0whYXKQm9op6yrXPOmCdxPXW;YQwmCpoEAv>u)| zV|2nGe>D-nNGCk&h{EbzJ)VLIbsmzk=9;5sm$8x40|+>0SsUb=h`ed$e;Rt^>H^5c z_Kssd-7h+S3V*3fHb*(fWEswA!i<)yP##_q@B0+=jcWYD7}`C~0xZ<^Xa8k?cpGBG zgrL)$*>aUcu`apuPCsq@euC&DkQmnnL_`6>@ee@s0xpc&(JQ-%(T4l0EK04z9)Q#V zKBVWs>A+tWh<|TGyU>F%c4QCSzo5+m>U`_E^sllMRu+Q*#(uwcVS;d6SnDt}MIsRr zST}2JAa_$)Ns`cN6lDvG?KmtCWt*pu$vMf0>lXg87t*d`X$s4f5R15s4mGN+0xC=J zb|a<FzD9Fd{}HQ#k$e3&Ly6jeN>HGag;P4;gjA<+Mxkx#X*{h$QF1jF^EmP96f(#r z3mvE&iEq8H=VY0bn91HCbz3M|VKgE!AO59|6U^;=x)l`_sbpwoN1VRSNMO_Pn?%4O z2rd9FxWgJrOI8U}->iZ=d8v6G*RRa0-y-}Z+5Mngfw;gumBJ6f-Sgv(*EQxc;KM1d zpUiB+IInbl-@Eu7+1sE&QT}t4kpH8iQwID4JP?KzK`N;{TX8nokMD{EU+)k919NdA zEB>0I;rnDqrC?CQXL*yesIqQrLNUw_EN%-n_>B{q8lxgRlHN#rx&JnJw9QeKiS=Vv zEx!RN)%3oGdsQiVu#eGm(}?cbKgv~hObP7!g+rOY3TyVb!g&Sb-lFJJ=l8`4QQR<9 zEHkeAtpRX+W5@cZH_*}Lc4!JBeN&cDVeS>y%n3(LHW0$ZpBEL%ZMGrP8W?O-Ud`wM zeP>U{EA;4d085&&?W0SBt6k%|F&XKR6EmtTY|6MT&J5*FK^;|QRcRM!_`rr7e<{jV z@Ghup9CD*W-Y5}qLl+)ZPS~qQuYJ9@k-3ngJ0<gSB4-L^Z!X$PgyJOgoOKfJ!NSU< zgt%9auf82(iU3zF@-?F1V@$)*2m2XD5reBF`_HFw32{gajHLJt)kp{(7d5<>9UX#( zpn}fQ1k}ie!|n?EsG-?4{a3dZfB5l4u%tc9uNVBKFRh~G3pT-Z&ejggm^Y-7phVmA z3-r{-JtmzHnc_P<H{!Oa_5;CD`$Y+Z)cqGE5<==H+>AJLTUmZMjVaHcUuO2WXiDB$ zj=3*k!s;t^+Q0i^&1}*+eNE5C&`$jymd-jV%C_s<ba!`3NK1DM(nxoAcOx~_O-gr5 z4=6FTgwowDAl)@|eV5Po{tIid)-W^Ywa>kO`#7c|RC{*9jXJD+2nN1cI|}ZYcYJVw z{fnU1-xj+5Qx&sgaj=U-GIm(X(@qjADfS}EjMebw+biT{SAOlu#k6P@gE5bXqE`>B z-=oSPKNHtZ(*#TcmCU>#*LDp~hPEqC<XVoHYtl8Jo5D4K(cT|5cg~Ea5?#T9d7Qxn zRnD=qiJyh&gE{60Mi=Vd@hj4AdGyjF@bmIgkC;{KcP9o&0&X2*rZQrc5(Q&URJ-~9 z_SNiGo19L#tF!J^)+P=&(?VpWlKQ*i^QT$K#d9w>dHACE?OUIx*o6_FWpXashjOtC zI8Gc2w0Ff{W-TMRT(|X_N<0|V;J97Bc1iRct4lpRKa8fnlAG1maLLvm!=&N*IMZ!6 z$9jl-ZO7mH|JBThk%m=9<Tts!@gZ00E3A);H|OMj`?}qagua&ih}3TgY>IiNT|w86 z-p{(m)Dmm27eB=w8iS$gSJMhq8$($|rFoI*=P>YmpRGAtRqE%PM1lLNrPCyCoV6oC zs>0k3Jgf`C?c(t5gu-HqmnQ#w{14RmavUmrj9y8U?2NjOk2Uk6S#B5ogbil)O0({= z`SvYb@DVEv2yZXRsdl5fZgiWxw1~rXTN7{%9SpS%M}^!wk`)@n3D&;oCv_UgU<{FT zyL@+}5+gY{ce!lzIGT|<CKq`s)L;X|QIj$}DeL)`EItf-{eT!U2QH#&09^qt@xCZN zj&VVA>wCf4VKQT8tay0X9D$Ke-?zp%l+|;?7xwkZ6XBQt3gXdA$hmB#Yiewu;7=QQ zL#V`eFVD0Xx@0voFmRLSCc=zEby;u%W_a+9xkBUESm3MKUk7+EySPHa^2tAB3f|q! zuhciTa!fVC84*tf>&AR9r3Fi4s_n8E+y#Fz@7c9}BEZX-jsU600>4QI_kFcW1NUL+ zFMTU`%Bp~9C%@1h{WpEuY`R9RwQ#Ft@Q1IjQz_u=-jHjlf7Vi+k2EnQvp%Toj&}Sh z6nIQ9^O(Qx2##m}<o`kNKJTjtwd?xpg}dEDd*Cs|ILJ<)wEgb9>HK}ey?C;fe_o5} z+v6g$f6ZSG72=TY%csq_Ky2zSm-oZJnAE7nf}op!f<x-SFAFX_O=OSjJ;^3>q^&RG zi>4lI6a(1Um>98tSj(L6uYMspuvMaERVS}|k&wXEbT1()_t^i-%jhovbT^H6#tw2a z<~6Szb=Dnj_fyTUq^Xk7Oi??(1uM3<<V}DP<Oie<&W<>(%KLk1Jr0dD((1n3W8&VX zjJ@6r-R4gH>7-5G@v95Zm9}XdjS({~LM1Vdh7G3S(TZ1@;zC?eE(pIP=t$<i?w4f? z6R*u3k=TjEODF(^D#^yY`t)Lu)-jQMD~C+zE<X#-rl5_-%Seim$N_W4euVo<`3R?6 zY4R!=-KHo=s^YY>WJ`9-`5%2Gtce&5j#rknV>AK(Hus)|*83?71_Up;B{I4iUUSG< z(T}F}Z@t2$Qd3%ovksXUTYIp3(N*Zg?3>v+1ns+KrVTfuP9L6Z$9?b<8R4xj?HuOD zbn*{!AMB3EsJ=fBpv-DSrB}jQWi*96wj{ktygek@CEC`g^6cXXaoDQR@<H0cKg8?F z=8;jugm|w(SgdS(PzvJxwgsI?@I(7+qr~0an9(eYT{W3F{K*WQ4m_p6dVmr74t;3p z=*wUYiGWWdQC03K*3*+<#2>|mcZMU*d#H=H1C{I!dqdryu^-$+^I{4Nw-=te!_YwF zpA5I8!nI^chv+&c{ygxA8cN&QE-_i=u1#x>qmdu84J>3_&1g<J;(?QmBVo~I6NHZN z9|RUW(JgI<)K=wNVN}?g|3Yr7ep?ZqUD$O+J=J0VhH<;2(~%Cj$5qyyUD%kOH;+u{ z9&O(>owU7ie=&ZZ<AI(gJOr@mE>+rkiaiA-4OVWO!~HGua4=jvB;xCYoNt`H09X?F z<@iq>-s|7?B_~?245rQ9a@}8&Y#oEooYwgHUozdJA8#sZq8{`6UII^lW*YbDe=ztX zPcU_tYteCfVdZ1%|95tS$d7V6GR8I@U~e8Rr&hF}?oO9+ik}ZiLy{kTg}aZTwkZ-J zZ!iBVorwEK1x{C)im<o3?ydm)j+LYKZQu>SiTJKD-~Dv=_A@EOc%}NoJFun(u#8K# zs*NF0p!u@QPSh7NU5wF=1IaBL@1D%r((^@t%wA8QN_pc`Oaa`Pv5CXY&)*46%U;BJ z@OMPRn9K;JAMfeS#f_HoKl*q9QDdu^E%lD~o_^W5h^=H=K$Z-DLQE%($fo1Js_NBE zWe>OYhDa`7<(Ux!wA`%~avDPLuQtdZT&StFE!}>fz7}&V{}_Hv90Ys9MQ382d|6>9 zrbY&PB=4gt0`d=$MoWXp_qBL?sBvKjrs<l;q9VbBt5F_{e?_Bj2P#>8#@5(f8ONd( z>N+X;V%`2+4FO!1)Unc&_|c3XzJeF}Fmq!@&oIKVU!>}B_F@fYIs^9m#+t?GRn7Gb z%f}>3kdSq>Ne{4S;YnNn+q&PmngKr`e~;p|h8P+i9O{0m=}UHq>wO!lw4`ZV%rxfi zxbo2@ttIW4)KP^RGFF!No({R!qn2X8pK1m2eaZ08C$3OmH5KH%t}cO9Lzn(D*z=UN zaYgy_PiN3g-OFtm5PH4EuDwNWBd2~$8oLThw^xAs34Ptd4!M}Wvwjold6Cb5u-hg~ z%Cr@~IurGCJKy?sOPqqzgmi4L@I>D}a@=@@;au#DN6Fj#(q?ug3TdGGsoaiJ>y+h+ zF<`+*60>!L&ebO>JRw@EUg7u+enPyr2q7|~<kvCBtCdZ-mw(rWzc6ypn5I<KJg#FP zo(#(RJ1z7N7am*$EXwj>dW#8FKp>W+3snmFL&Sn|Wv*8}`lF@!bD1v$XAe<R3fkfx zvx3*(my%5h+kOz(kmVh4mih`%$yycB^&%AUG!?Qq={s9qDD(5LnEwu^?ca35C5otF zGJr>G;I|ncojwDt<iWaM-?A`Ex~Ft(Ezv}bx>ZX7=>BIFHhN$7H)m!o0cFZy?|wY6 zA!rttwezD2UHN}XcCg<LJXsPg?!Vv-pjFA9g4{^|%4v1q{gxOu4KN<VX;#b<sEnlC z4iT-Xs!QIOH~i=bk$nB4X<um{xMA-pLeb?w5Ou~<R?^@58Ha?@n$->f55Y*kdqhmj zt|m0LszqrZc8K~7B<pWqTI?e0w#JR5o1d@+^ki6Y$Y&DV>)fB7bq>&RK-Ku><c1RX zRPv2v8iS8x`rtRT;|sO)FGauzXu7F!UTVUv{f`FDmH5KB05P@6aP;cw@%kXPt3*>0 zOUmZJ?s=(SNV1b!N>K>s^{p>JT|Qan`4ixm6!-`|)TKly(10$cYV8acf*2&s_}DAE z#od__{&4&J>7Uc`dV+G<R$I&)5tz#B6MzS|H70=2*ZYo_)5wkxdIoCwWXGboZC2sj z=sa?{BL5Y%y5d+T;qzy7WFf=07hVkZO|GWBjS}mVrcG|*?=|An1ih4e3U;m=dt_!B zM1aZZ=6DgfhH0wJ#)M*Faa27P6j|%QkBock+xnOj2KT(n>{Dg1DZ(>|`c;h~EPwP3 z=@5}hxuV4O5qo_b*l1@_$GVmUI}EZ<7ru<JTQ1ZpP+LW!i2Qzs^TNHsE><c?+%9MZ zJKv_EB6qrtD2Ts@>XE~b=x$V8L)bJ?#&puUjvz$AI;?zm&a_{`Iq>LVobZX)nhNC{ zRpl|1)b6-B)r{MrT)zIh1K&K0cac=%e>(E8ylLb8B{zO!JV0^SOZLmP{ug0Pyx2a? z7&HdI=zeWO-Mh1f*%47Rx+B3ud%*{}Vft?deDU&fz4+^+Fg6^`akpZe#JfIVB~#T0 z`Ng}4YH@=j`*>v146h?t8WSMa>N5hXp?mgg>|Py=7{rGokANex7i1=YB%=9J7?mYi zD2>+bX5wLf?KHKk(Oi><Wi-8R9eJx#k(e|!eYhc5m92u31MFpO3w&8s6Y35E>f7re zSfoO|6Ea6C)-cu}ESKq-uL6$V7)a_urK=Uu+GbwVnO|3VPOh+#1peC&|FwJ6;;hf{ z*?_`{Py_z3?Z3CrAK+eFjfJbk&yie~!*!6WPl+;Yb6-hQ$P5u_t)ktIkmIVe$Ot{m zr*>=KE|Wsa(Dx8T6B_10@e;;6UJxa8!DQ0bWC!#^dOt;I%V7ip2H8riP%iDXzRVj& zQ<r@$T1mH#zqMOb&AdIHA&*soc%L3Nd48ZV*zf?!M+MHO9>`UJjud6n7wdR{@I<GS zAbU$%r^FgXJmCzcTjUOhxa^x7x|8{Z5EXoHU3TvoMzkncZu(}YzE2DvS=67*><Q<7 z?ecKz-Q#YvbQY6Oxf_v3KTdV6o9J8{nx-a7_vpnnB5mnGxrZI0PB!?7&q<$0K_#nC zxn7t{7I;7EMh~{SPP;#XR6q~)QCYXL##ZXF>glly+I`#gQF$KuU(mWY+kpPV^bR`~ z#`*EO`dLQAYUIY%IOmoo>a!&6e@QH+rVq~=)ITT-WgclR#p9<M*!+VuC6}r6A1h2A ziw48gdXOng>n2B5>*=db2H>I3&{m=c-efZHpbQW+DKHZ>V5}pLD~;DsxpRQ-w!Kt8 z|Me!u*Hddh+lAr5lXjzlpAaEej`4TMJy18S$?0`q<x|w4XW=Q^w_A!l;N+q-Rjf)T z+_c*M#Y=BI2n=~>ZyffP8S0Ldvnm3lMYjIxGLxg2%c7alB_m=iYn>H&Mp-R_c-qH7 zfZnN%+x#bnT-t$aC_H*iZYi{g5K65sp&R*=CHg`<DU@TO)*Lw>c9L>mkO&_L%>V%| zOJ`{TQDNZ|GZc!$5S1vjB>iE}t(a+jB6eYX0>}ss-;QX3GPhOZ>VV!w-m#k~LR8at z(`ua|$&L{ow#bPRoBcJHEudC6v2+`PoA}761#@HD`xn?wI<BH9%}`UjNy%wj@6|$y z*BEs8So@W6J=Bc{FvfZm*?j7Q$UW90nNUX!eS?v!s`)S*=djeT`H#H=q+n#TD%@M9 zPW|X=5%%1)>+w!Z3P1Ut-aL~IKN3p5aOQn|9vW=~idN{~kHglvx-Nmw>w;2I_d8>= z;`I`oBI4Fz3S%;(jlAsj@SWRD=LB~f4$r`u+HM+jiO5Y>3Ipie+8nf`sh=@w*K#Sy zdugSFRtwP=5*hY(L4+-M2r2^6GCNQPU+eO2j(!myb{8-3GBcvVKQO|QH$r(vm|&BU zBlJ>t%E8RJWhmL|Rz4L}ZRtb}`I>{aKgVga`Won0KG4=3(%rSo^HMO)32m}*W3y5# zGDciMTSV2Jo(f+uAUqWpE7@|h$g~JN#cV&UO?E+hf);ZO2&en#5K(*vlrwbLN?q5H zhOA$`y8|<cFh%+Yv<n}bBelbfZ83}27tqTA-o!JOb~`Gmv@pJo_GbxB`nn*@k+^!E zd3#JCVKOB3q&k2+ocPv8Qa!@`$XyE{B}l))*tjUQ-=;?g-P5_LhEE}5|MdX!xP2Ge z)$=<dR<LF?>v`wOf83rs2U9t`qaN(?)&WOCKsM`>9}5Wlr8&|>+Xd&4vDOov5}Nj< zmCVPIFe6w#HLU7$9T0^)BbLVST>i4_mXfU-Ety@Ii=yrFCt6oNH^rQM&K>q{lun1s zVZa+_ABAEQCAWvY433s|ounc$?(Qg){6h%1+(V^gwuAQT{=(pVeNxLR!0GP(XT!NR zs$EF($a?)|`le;h`j5ok#9*AU;>Ksx{inGz)?8zQqWq(aY2K}jpWE~O*<YrKp`P8z z>$aeOweagbz3UJVP55W8_y^mXek_!O*n7oz$Xa(WR&@GO-T*ndQ==2cs<GSs@M+Jh zHeoa-sUhGCZ70&sh8}J!ZT%71t<nCgf>QHqM@%VB7WnzLr91fcgp|}z;r3U=?al2* z+m#W3mmpvh6sDBJKIF!zb+)+cjX>^Pnw_zBV1pYDmU5mw^SVP4=VDIPW)M;lX)-sV zafa0R=`;F+$@)~K{t%ck%@cvFw9?i3`m5COoU@X)XNuV;w|9Qej~#>r=fzF&Jyh-c zS5TFIR|L*S4dX&`m4fdn&bT5kf2L4Y$A1;kIvcfF`1A0ATs~D;7KmyYFG^}&(v8$S zX({978>{A{Qv()~0e8;7kk}qck$oR@H9#lWLQ2G5=4l35DaiM4)|X5xi7IY!DQ4E} z2KpZ?DJ^l%ZEK0K;{j$QUUrmpRsD+!@12VGFJCLTiT6fUjjb!qH~iz~V^1c}*#2#m z(TptBUu%7-^Up^=u0I7VhSw`4!%rkT>8sG)!2;HH22qJ86cwsZ$mv1J!8h}|0EA@x zU&#Y_VkP{qcH$<0J+zhCptoz*ApYeXT68-;HqM@F&)4*}mzI!gLwUGIRd~OAGpCwK zI)k38xWvoB=<unj=HI_@3?eD>SX}D9ZVNMSO7a`>ndut*r!8J5aV<1Xi`};#_<27$ zHGny4g$<RJ)b83?Re)>jJAtrcKLVrq!b!>Mup!;%woFn1^`H95uPq}}K2w|6H|Kp- z!~!U^YZ=1-qHJ@1vjf>xumwF+QL|)p1pKw3pN9nDe-Kd*!Y7@*e}uu(yOfek!X~@= zj>GmoAdO%^qsYlW<7GrA;4#j=JU)q=-9uV6ZATVDxYiIi=B5g==){`VBxE<fSiQkA zF9LMoHI`Le`KM^>UNy8R@r0^zx$3dv@JH?>D@2`0H%(rnF&}2kBZnR(?+i*iVre03 zi~nQC0T`IKUvC!@&x>!5rfnPU6K%a+K@Sa2iB6ckjPp&9<YUW4x-e%Y>+k~h(s38a zsXX4o#kp2vb&mn8BJT;Ow9O}}=xol6Zu|mL3}7p>T4E`^35$I<@~*gho!w2nC_a9@ z4>WzK89GPexT+Vmz%(r=1G_aX#lt8H3cibq_58zpU?I(A*hQ7V?McY}#$_ZtW>&2u zZ8j<*mH^iQ913ylEi~;iFFs<fB29E7Mv!Nrx2)E$ITUKw(f;q3h&tbn%jNL>^*pI` zo;NKy?@uISL+;38M;M1FW@riIbFIrZI~&k#Dm5z)>L=GykdyJB?T6*!Wa`q%(k-04 zY=|_Yn4O~1#t4sz9dI<(JKjFpVGnOn99Xp8+J4megbW{jL0T_Z9M`?`!lQCnBsVv8 zrCj7B5IKI`NWkCYFlFPHSYk3hRo8Ii>yA16{2nUN@iTmZG*bdx24H-OsG$CDKY}%t z{*C$y#ot@mM4ntB(ff#Lsn=(+l<mV{<v88AjwIZKL5tac9B*ro=oEcF^T82JeG+eQ ze?1Oz47{7ztJgi)<xO@cqOvE+siAj0Ic%I5*l_++9daCWRld3X!Pm0jqy2jrOaUu& zm^C&$$oVAkqANtC2|mK`(p7?C3HfitW^dP1H;^jvYqa*C=3(Y7RJ}G-v{?819RM6f z)C{8duiFx@^ht46eh=j@h-PafC^2*qg;zkHJ$PD*h611T_4MtkJL@*5=`V?(qxJ%l zcAa4Mfe|WW`DW|L&KlWeJoNnl^Lr6`^}<$0l&s3^433erK)17bHyok-Slt+IMzv~j z8_Ogy)^a*e2~qa|gCl7U0^l+P!H|vgLMerZdo2p0tmP7><dLt4h)|5u#A(m6GbXaq z=^3^d*ZZ7JYIDqD6#@N_@y_5Qt4lmpb>aky9$}jOEN>B2NeC}41VL^eDoWLv{i!8` zYya%8NH2RUuBVsxuR;!AhBNiG2@?RVhk1q_at|M1Rgl#-{&A_<e6+|!<#dKc0*_~m zLxA$Yf;(b?l#)9l?A;F$b!4)b-80u|2w=$k&T}w1k?z>R`<;Vw!pojB;c>Zb8cl3Q zd#SJa2>If#(>d1@7lI;(K%JdrQQ%?gB9lOSIQN+2CeBPOSH2oo>GlsQ)OlNYfso5z zbgqp+(X&LH|MaD<Xmacbr%J2xl#oQO+k=X<;gVv~vzz$q{dST0>$?-S^A8wXgH}p~ zsZj&^Z>c4TTaWu?RDmPgiN7m4ljv$>fma|XRTtsVCA0>!V$S4;iu`8I>xz<=$-4au zJA5R_?3$0twt&1FkO{nu+tc8DlIDE}%R9u3dXi{M<6`K{L_DX}=PMM`1(C}dHSE2d z`{=ITuH3NiNDqM(ek@c(Py_i3DFAgmGPZCSQ7x6qLg7J#4CTk~Ge<oX-t;`tNMo)9 z+yTf8|LI6&L%tbCkpQbm-~5I+z&h)KGD7rx%VMa~6wC@QG<F^YlAjJNK5kx_1sjp> z)#NVZeL*+*?sx^!Am?OJ*PUMy_fT?S)l*65#!<~A5<*OG&aG?`OOJP`imRo`dB@j` zXe&_4cQ}n{&3I-!mR^eme?s6!jGu)6$fQ<qar;l5)#CNfD&vya{c`FG#8#~4ZnA+? z#HSwpkR1$I-WorDxB{=(n;knoCNoTX_|#9-{3zG4Bw3_RZ!^RCV}0?XmGP1S61WnE zY)Lx3*OoPM)fg{Dlxu1%_TW>j;ETA9Fk_&;<U2$iGD1NyIuxyk2lloD{!o0r`?pEY zA9><ZEMqz+r~QR-u1}nL#kkq*E6^mGXXuxJc+!cg7AOAH92Ph9j`DK8ciLUvlX?T% zga7cBZ_*VU_x_v%^We_D*Q=gXwJQ)hari<m{kbj*K@U$>x?R_2@x73{xUu}UH+9}5 zIjT(`;(Nbi7t{DPZUiZx;G8xQJs~m<*gu8ip~I5FM&^Y)U)`rp9qyvF&%QjIRFy*7 zi4M5sys)sNjVokx7qkUdqzVQ73)$wg@KsKwg`rlM9hp6HVDtOriqRhmA7_V*i>V}$ z(oUkov9k0&T#U1;^u#wf_pZxkb|K7?8Oj^kP+PHWCJhixLEpM7L#7dG)`jVyECxtO z8t{IMdW2KQ_5wHR*3`{jI+ma6av6hj%AZfDNBaOMLbgtb!2vG&yEt7}Y09|>#t$+i z!iUS6CdrBhmh&+=wGw>Vp#@c6bHe8Cir|Ilu$k~?xa|xGy(-xQK-n0wI-jz%3N+gN za%7KT&Z+s*U7XMiZ=WALf$)(@=a-j9!1npBY2M$A^^K@g$rc3;5q-CsAlS~+sOHr3 zh!ye~y9_(I_uWnB`x8sEbaO{s7{^bPFSL*7jdEU52d>FjLcNqa_!Bur2bgK#uqjJz zohi@3LL#+=siw_SY0__Hjjs{k`x9l9g!NlGTdpu3PYgtxK0KZ@)cgv41p7p3(Gpf) z<0P8FCX*pnD*gx*#pQ3*dwMfPSyLlmd#?};dn1Se9{cQIhuowCf%YcaCs3YKe8U=? zMzM#_R~qWCWi`}Xn(3GWOgqb-=FI`-9ttajlx9Ozd#6wE<;hq;6NRR-ALA5Bq#WJg zXaam2H=tVFD*qqWB)=%#)$j8f&O)Oj373;aBE$LAYP98Df4?~|U~S}EW`^UC=kR5x zS?u~)J-lp)5NKKmYfYs=(Kp5i_f|ZI;gRysNGsoiR?qPH<P~NIkKw-U({ue|ghT|H zwZf2D<P2p5KUDZb-K)$TOda)q5_J$viO8qk*S}w$swDp#&gCzC@{1A)5Cw{z=kISj z{OeTfU&3>k<T6s~G#!UClW70oPhZ0*JOSzi+(f(w)0g#)X_LasL)ba>0I0~;pI*h{ zWJcbcI<@gbkIIvQ>rEWOG%T&?S>Di};UOA)XiZUbOJ3@+W4z0Ioq0HGH<V-QhE)v@ z3|f>yp|oBL2D_<4k{4r@#NZM&ufzeIs~EC$NXf8II`~={W%Miuox7Dd;7CSkQHSf0 zUzwutoz}mdMnKCeJ--CU050Lnug7TN67Tb;3<f%9K#(a}A9gX}77)-s@4r14K79Z# z0~_?fflJ%%_{X;h+;&<;A|6pyr)G!F?x%0{UF4U>_DN0zH9XE<4PL2<>$y0x1=*-Z z#Z&^TnT43XB+=|y;`M%nw}-{kvONG@(Qx$6RXAR&o9XP}LslGTIn3Z@#_!jj)D)qa zn)jN8;$bOjm@rW8`4Fm%^&iirFJHb{>7jxvpMzqsM_(f({v>bhgL#M*Vdp}0ny51k z=*L2CeowFm4yH5v)F)+A!c||rJEFIUD*Q3Q9(3uW0)y$xel}p>n)b|~N1b^N5AO@Z zYR+f(5L!;6*r2KtRYz89XW)m7Uq~-Xjdu??IX8=9iAde1@G<RQ)}$0tcuY9AIRn+@ zhCdO(=HS(y!8TxxFnzXVF4w46BT-eu!WA;VqA2nC;bUy+;~3a5xA$nr4dzzFLI}i0 z=`+AA`W<Fm#<0Lnv-Ui6-&7X4#@Op`hp5lS8K(>jEkjxnes5qEtlF<<P;`t_L^vax zTR^CMAapRKoN;Ajm9MZnLt6>`tjGG};4+$jiOlnZ1r=xvX6UhExbCV5c_*U<zdCY? zN(E@&_-DtAlpW>HZc(rT#@>AUua>WrDu%66(}%hUWQn}T!^a%;zu*3vKF0wL>K5Pz zfw{oi31c`DFY)E@pzGNug?0@8(59tc>erdFfpbFST#eR}d<Z=4<Wc$$Jk)tpaiL5l zrhd4+3VR0vakWRee()*}P81@gM)^FZ7I6Lp`xA3dWi+K2*GSD=Ln|m==r{)sVzDND zXyyed*MD*HN24H{D~vTi_Po-iy%|Y@)45#DNV_T}Uu-|Jk15QnfnX_n>V8a3?xFot zuanKwT1RGA+K{i0A^Fr}XTQ`ccS?XBqJ*|(U1Hk$ev;>cX5T|!oJyHPA5$-a$2wT8 zzbCzR<^~D_GVlSV_?&Apsh`j<Uu0Szzc52<ZWBjSnlaUnk|bV-43oHBklK@)9`q0U z=q{pwFRj3UU8kEL`oZvoOdzb!oGhlLWt}tLmo7V%5vDCDikBclyK)MVn;rbxSa9#N zQ1Yp$&b+3x3u=xLwe_)p)dc--G7hBnOb1c9I>|j{sq6(OG*3g?BxkfHnW$nGEAU_{ zYV<`L)l>!cJP5?`it<NOkB9?rFYXUwucCly=;!dTG8I<ADGYIo%pP%%Cr%t1UGZL? zvIdu-_m#EAeDD8Hir_0fub|?bR6J<BNuVcpzKBv~1PtkM<@NmUj-v<EvR-FH9@RF0 zNmdBpf}os~csW!9hW;dRpt(uFQ0!!}v{1z2_A?Fntm6tR>h7Dvl8TttOZ@hK1!(5t zl$L?zQ6rOu%)Zi^Hwxy2It9j#nJ*q&airqZ4euPN3@Q;T@Mw3HhB44G>q1$ha-oeO z59r_Z(!q|2dGaex>z7D}+5!Pv#80ZQA~<@hlrywfw>O=<NBB7NY@pl5-omrX>zpgS zA4(D-z$oAVG65Qlor`Q=DRG`BooP1j4?1XxlO+DOZVIEjdOM;^w`B;DH`i`Uq9y&5 zzeeag@z!?Ga_zTOHrlFdQo{QEaWL5kfipyc(oecn8agD31_x*DIq`D7jr0BSAf_k( zHzI;Y^Ko}joYJR69(LaXAXr|V6okaz4IiJ^AyP_?B_jUB#Skfed><`?A8u@xmh3{s zM3|42UMb~9KBw+hb9G^<he>W~UST`c(GdmHFi3X9Y@_N?4C!Gi!}6CF{_TVkd?7co z{)L;=kY|UPQ0#aujH94Qm3r9`^{t&Ov?v4;N*)mWNW)4}<3zBf?)zH>){~J@UeYvm z%EmW6_*j35tfYPcO@zU`uXugn@$WhDc{f?BPA$3P{r%-OP}>DP>}Fz9iv#$=!;sg> zw+HJd?@ZS(*SQ;J|9yAd9{9jZ|A-KU0qjJjCLYJsZ54UTIl9y(OO0RdaAScU6xD}m zo_GHeto)@CAQqU2BM?HpwpEyzc9~)75;%VG&*yc-_GC!9W07%wkN<HLc5e$wbeP4J zz!Bhea_9%;PqPf}KkMIPI9{)EuYKvFn*KiYbk|}|9Pe=aGfG?p!(|zKI<E)5j&D_e zfOS9IdS=}@aWoMc725j7;TrMoGGbW%t9E?5c%pQ!fYo$>=h~~^@x)c+NyzlrO4rNO z#Klw6>BqbIRRPY8CJ8&}^Ssg-hSm`3`FZy#VipIs6B}8-=dsx|aCf-@pqsp7F*P*3 zARZbs22^&}?j5OLGJ8M=WHC+{{`4G1goR;-Ut0oSv=I{Pt${sKQjrB~Yt@2`DQNDR zmgOcHu@5vz(#Fq0VR>Wty&DvxJiHU2SqDCLno_CrgC@I_e-Jj@c3N+>eES<-_CQGn z8yR?D?a9rjTsx_j(5>9sF@c+~k<l}*-J6(!re^q?TiXG*JGYtj&!C>~yJK((SPL?S zKVVuLFI^uw0&D8GDJavHa!8@m)U0NR2(|3%px00}=WH@?X;JTZLU~O&#O!q}1C9pW zBgrMXEptuMHNU4dfKJ4hf+UAQn^QP7I)j68ZH0uAZ)Tl5kvyMoCX87Q!DFu(jC~;I zT%}8&2fMB_EJ}pUhzn(bZDUsn@th?^?r2Xqy^3JIhgyYsm(;Uosh|AkSl7_!0BVB$ z(Y#BQWLB^ePzP0z3TC0bG2C_#D*%fY6lQ~;cY4!SqZt=jDzf3&kB7g~{D<>44J($q z>(rc8TJ@x1xNrTTndL2%=Z^Zj4R=poZ${r0{eO<*!a_=Q*bOf4FYZqiczD>k$s{wN z$a^(2bbQkRRCB;YTZk-W#)bx!(#~<?ayFYkpSCvcz2RA-cB*s~#>uhs_%?S#)cThX zAY(Ko>XL)M3ZpuQToDyC_;hy7{B3C!t7DtVE>+a;?W1Xn7=P@7-Zx5(VYTH?c!>Av z!;>{=YfNg`jaR-aodNaWG!^|J;-6G_7)n)cMq3mFi_5&Mi~n7tq?6iyaT|EZX@pRq z?`p9m7lOueBoS^@V!_*P5VN^UtBC_n&)5m`uK)zZL~vOcW9Jcr{VO<ss7WSw{~hJr zD&R1)6yvFT8(V1mYyKbqv4S}|M_O{?HbAerS<6{mICz{q?Rp~K|BiMOq!YGp8_CW_ zGpbIrhVectgpgt>ABvE2AtlH9h|sda#H}b>deFD<8n9vK9?hObq4nQ-c6I&L;DbnG zK3MepPm608)?%~SM|c$N**?YsvA_WlGT&UzLeZCT;Cl}})Kq25VM?O9{xa%tLAQNO zo(#hE|M<At{bDHkb`MZ$0Hb&({J$W>P1_<aWzM2;$`g(>OUWncJ-`g~DxY6J+-q-_ zdUjpr?RR6Sh5UjFrKt3p$i__8hwG^xL$wSGHIz^)Ezo&8(V089Bu&(|j=B)SBNbq= z3f2#9zu(cr*kY<FFz}v|FD{87fg3Wo+Ycva-K-~gY>-ii|C4Hbg1a?msgMIhs^X`7 zuQg&s0swp4=e=4dN(!3L6ta>cKm^!z=D?7WL~ypELpm!nytGjiDK-xN5xX%aj97Y= zw0+Rb11_Htjtp(8ta-#chUFNrm`1W{wI-p~7xGs~;Ov!d^|+a1vCn<0v^Qpu)Y*vc zI`b086#2#tsQ>!=8nBvt)T|v*8Zm{8-K3{lI>xrT-0cY6E<9%aFVyDlEIr%}Ke?Io z>nV&Ey~PzR<SBWHE*5$icF?ClF-6-tc~U;s=^TG9?i0;+)`>1SO3LoXX^kiy13j#8 z)%)ZgL(%Dgn{d}(W_UHr!~a}}-rs|?rsQou@TZ#b;bd>+44UHq`a4vu!3D<K^W6OT zZeQh#Cx-O~#jkJ*9uDN(nph?)6MVn*aIT;XBiq3)`{dqLM7ZNdPviZTkiq(0(x=<5 zj?Regr~9q(C*S&wE^AC<$$~D02{8QD<@R9b=EZGT6fwS;opKLOd$ANF?T^lvl47oQ zMqc=H`L0SH;B}_Mad9Drt&`^8;I?xhvt!wP`kTXY+#}7EE$oSJlST$ciJC1ySWbaR zj2<WFWV6ALs4|B-^hzp!4Xz>$fFefB00D<lW}emYv8K9s`k!B3$O?7tu1;~EHC>b% zC4G@gKs^L_d?n?&l-9a*>qwwQ9a!diW0T-|%~B&nt|LE`*by{lePNwpeP}=WcR4F2 zc_&Nil2@%UHNQerr#jZ<Q{=Knt>qEhfVE|_q7^LZ27_mD)o$(zv8bSJaM7FrI!|{^ zS^#gN3!uRSGS7}OkusOG-VVBI<&wu$K8P1mSQVwiV`$3^{*aQ`rzFcC)fkzMxnYE9 z3$eD{fz2U&YN^tQjvINc@Dwt#9H{mmcPGO=*Yq<+)Sc_F0dY_ZiN@*uaTT`KF3Xlc zx~=a&mz_8+`sfu-bsoDLJ2MYaG=3O|V&vZRkCgm?8Gj<3OWwb!U}*qmjT)8*td2Bw z{8<U+tk>s)R|L$j!M{1cq%6O4m}I<U>VI*5r>SW*;=$#|{by*^TMwsvWB<p@{&(pz z0P{P(BJ49o*PX<#a+bE592kh&iBa(YpRP68^oqq{ZxwBX0JiZSG~lNu7XGR<>F6jU z*~vSiO83XT2VbT`?z5S@tKzWJL)8Sutl_EC7cw5SA1%3Ux6T@E)nr81I@P_U`Q8(H z+}sq)qJ0~M_C(WuLbmP0gQmMC!{Qj>=1X;bJ|a}N(bb<rS+3Ry%b=Z+CDj@gVVZLO z2DO;7P3!o}-1Po{#?HZToui#P7d1e(mA2LB5sK(I*~*5+RBmwDVsN~Oj{yQpSPnem zqhL9(fwLP^&Q<|6MkEd;P#hT^x=(8labV;)RCBrX4@*a(TOUt$dR6M|V0>jcUW<@E zIQm*(-}R{oh9_o%s5Byn<zP91*e>7vY-<|zR7=fH>Ggm!=WKp0ieE*n(%cul6tDd+ zRiux{s?;P@V0f*etVZa#?OVV8oAy4d83cHI83tULrOaUr&mv^Cg1X|4?C(wok_27M zRr{iecz27?{xF;<3h)EmH|w70b@vEK04}4FOkB$iUf;^Q!zB}Au4DvNcXG=hd4|i3 znW0ssu1j^xjD87N7P9Ub)?vA6j?`=AixTyU%$l<bM1;VNo22Th9gEpzQYZDX--I$+ zBMgb6#FD8)#w*Ec-dABALMHR9kO9laW~U9b3USqgw7OTT>b05jYMZgGz~8*O3;<iy z_fW*xFy(3{t9wVe{5@$}@QDj{lr~ttqCT@6&Unix01#^ke6)t29c%ZO|K4t4N1J4` zH9&eIYq*lJ;4>F^cBmIHyJSPcle7@|6PeunR;8%FS~}(ZVq~`+J7albjD6*ZFjVz) z4CbHB=vG=o#%=+(t=Yfzo}<-g5^w(FlLM0@KvTFzaTe6+{bus?!?s~J;oG4|9SccJ z>|MUOQM(H$z^doBGbSeKYemSl>y&As`#ebmo;_uQ!wjwUcX4%22de|&4+hX+KC*+) z0eif~hv&YR;(4VMYMgIy+$fCKi$o;rw&FqR8ibDHjHFl#rIJc9%TW36Dgsgy{^ktq zE<;%uml29;`7d{PX(Bi%9L6>xNbtS;TD(GWP5j-eIRrWij?Q7vn?b!d2;jsNa9<V4 zr#%WpYeT5@a<BHsQtwcQ57squvsG4pHg3O7bm`Me_Tyay65y>xri|-iwjj#0fcJ7u zCrKUR7O7POjV+J_8I$Y6pUB;YKe`#1y#L0jAac~yPN~L7ZO}lwq<DS&mhEmr5L>QI zY75eFZ|gptTdwesn&24gfPUqyTP{SjMe|`tJ)u&FqE^Fb#IV9N^Nlt#To_;1XP5y( z6a#K@GPzDdQ)nJ6guh38kElxsipWEdnCH=@Ixm1L_Lm-g&((_EMBF_`89+d(uW=vw z^MVyX?9({`uHH7zbjr6v^kcx!GfBjn_HS1O_?s(pS_L=&7V93jhce2S!hkR6z;_$% z^>zQ@c)R27AA%f6_)6d=oJ@Yytk7QX4k;uC{7KZMW3JD_buI4)K5n<f9PXXQWip0f zjB5-pxO!jCuGmdT2l?WzaImWv(hFsg8LT%Dt}~Mro;dWeTTA++UvI$R{ko|@w5>5p zr9h>{d%>z&!j3MDo42@Hojy!rx(N-aWHjJ|C>*83!eZhVJM$d=IOOuGstyrof9d1; z&&mt>+u<7nYQUT2;lB^tNq6k@VH1HP7ayY?9v&H1u*Z*zEH<QoDa3f@=|UPV9xL>0 z(c<HxBBNEeoT5$bCL2`*KAqLXiSYjIWO1{vD37a%VBH>36dAFiwL$DK{%B2@ofXQd zfM9MzXTma;UWX*6eP#|s@B;k@D?)G)lOAO0+dOjnsI6>9lXmWn4CmWl>Y>m&)}E>} z4kpdaN)D|?Z*|3y_!<~P@gu~LdJ(AA0&J7;8X*^jvbE}f#={|LHJ+nke|V{8AEAxc zD$_d0&G~!sp)~ga@3>CjiGjFS0U37kK(X3`tCGcOpBY`QVaj)$BeL1%9@FUy5~n-& zV8S?+Ep+_l@;lFCT`2CtWHi-yRMK<c`Z`nEG?x$vEBrSOyt^374J47I>p*l5fIr24 zM^#?XUsaRD=vFRc*BLxh{%Lm^HoE<zJ8^%x(bhmh?DGo(qwUvq0@Xg8#dqg0x~+BB zzARtE_{J6!0KEmUBG$KPz*AZg7s}(xAzOTxPJ;jX3;QE{q&}W>$dT(?Y~{Il@CA>X zo8@T@t~?0X<{z0t6n(ENMhH*Vt}022lSSL;U9BDs^Xv_vh`dEmH5ls3lhJBN041QE z<m@1Jw2l$y<hv8lf~>$NHK_?ulLNG@Mp;lvYL$+7$tKS;eQL9?K^|85lM}fmCNdlk ziU*ioDx$kdKV4w>B5O*Y))0{^w$gkJl#X%uo4D+EtmMSU-XF4E7@Al~GJQUDY`8yU z#KsJ02gmE+t#ey-c-ZfQxYV72x02A@Ay$bNAo$uOPH-b`KE{R|Nh)+>PiC&C*K3mY zaXzh>7r?3e6K(Vf(Z)Uh<KNYrUiX$n7+WS)V9($!`XEE%>D;gHrQ*&(02p{Z8$E1N zRO0rNG`T7wcP>5<pw>EwwvP1gf2SpZFQZKh4oj#vk2~g|e)t%bnsQKU7*OKG=iF0< z)aQ1s=L8uxgG)jfEDsUx@47?#W@8XJ=k&GWgJC3>Y3>&lUbgqB*T2<a3Zfbrvk_P~ z_mJy6EQkeow79A!aS&2Vy8yRQLUHG_MXYYOQC;>YfoTB;Ky&mRcbQS-Rf4nGz#x*` z+WWoFz$vi`JgI;{-0{cbOXx5lR`Q&k{6zmK|7))DKgsfwF1X!44=1KPbtzRV39a4l zi)32^k8j0@t}KHx?|at+)u_ZDFK#Kxtdxh&O}dMp`n%%J72&ErebQwBOLJ_i=2tYN z#F!VcJLv2Dqpv@zr&^Pu_?1Xa^-2=u*wVj!2wmJ1cwrjSul0cn3r8rFcnV{Tr%2Va zTA9frTeGps9zN2w9I|^3hV{)!s^L#e#qG)oq`06-`=vD(H3lFwHV+QGCNbB>bG95| z!iu`PwFQI|*=YgygGrvbUwZfWaXiNx<xN_VCa?huH1c79oRSs{-G%)~`fa<Nv7uc& zwlTNYs@3H^tK>WrOTR*M8|8${0)>oR|EF0(-cs+2Ln+|&Tygp)yvY3Fq3`w8#axWX z{0u(Q>p)poll%$l?wXUTIFmg)Ar|JC!5YJ%i@)yDO;?v9ZCaL|;<0!!9H)!Vyr|=K z8-P7u44(z5aDuMNTmxh0TC<aVRD6m(K~2gD@%$H1gm?GKyjG#vOJiC7O0`-Bh;4|% zAe~S&saE28sm=nD&1Fi?iFV-;quQ2(bZ>QM9zn)Tt_J_4Mb@rgb|4z6CLE_2EmtQ1 z>b<W2kG^7K!RsH3jdpdv?Y;hv|Na+@U*Sduk{e6+METfTIFQL)^YXz>m0u459cIBg z=Y>xse_TJGqK08~x&*nu^#Y23FaMVW`Db&kjCk(Ycu8c~^+!^Brpy$`XUdO$(UnW( zX{2rO1@Eqtgxu}UyvaiST;BE;H$K4BE5!FEpNTQd-29&U57xrHna}7zPWhpud}tZ1 zK$S2%628{Q(CTgs#Bx(SZ>7{MTMYg7)mqwf|F+-sXB9h6c!&x*wQIjE5~-0((5J}v z(T)7I7r-<M9u`@h5p+`)$KzQM$CG17y}beFfW8Nk3b`}UQkq~%&L$G5NajKSmz#W& zgq8D;|E@uJ{3|iF_Z_3Fr`~HX-6{bWZJ7j)bj=rPv5!Kt<x?4zhS~<?m5W-2LG1yE z@b7C~wVrG6j?F$fM>>@gDqHAk3b#h}F+&bsViU_MoM?x{&gddqIeGHT4N~9Pt!;=m zwn}EvfY(V&ZAe<QA)wOf)Srrct+ChA!;&b&rP0`g4WR|zo~9^3;vsUa2-an?>2a!D zGSUY&Awrr+H@$~os!}W2ceES!D^8mE@p{Uyxs0E0HKcsAHUgqpKVC^Wy7-l&T?od* z^dXjZA813ReTpMhzMI;E;XJh<N;c7-<|=x|>2`@4QJQKnmQ&_z@pjomret&Bz{mW@ z>u><P1XI{?^E@%an05vuc{z;`=}Htkc_g`j9s#f{$y>}}ST_<_ZQ}$e$-5N#?gqg2 zO-~gFpD~hOuUC5pB6H}-J-Rptx_%cwx*ByF(>1(fu%{;y3lBiNY2uMP)I=O^VqdhX zhFdsW{mwds!9H}F<+C)Hj5P`TOEkkCoO>s60U7q+dZZJyD;C3j>OE%OwCW;0<iGA2 zNup;4O<97&;)S9oA-FtZv>j;jB_V24pg1`3TD63mVy!&)Yw@J`J)gI%Bl`i+I9G3T zW`Xn2Zh)18Fou;Fsdk4=C7b{oShy^?tb&`oJm_6PjdE_^g8%kuq_%}m9hFOi(8ezZ z&i-ppQ4C{Um`4nL310|wp{g13&z}^5eE0L9dp66lF+cfd|3lt_e4LO)JM<iSlt(N6 zc1KaHd-2M@{g?%Y7#@e*sRmBu4SO>hoqTEK`;utq_uMZ-m0g)2u;lvlaix29G+Z?B z`M0hFhcj=PwR^JZ&!7i^kZXYhA+FBB|0O_vyj@_wUHrXat$iiVzc2N&L%0gOyXKIJ zn|#|2c`;qRSd3~q4NEa-!+$uc;kV_u2YI=WR3@eyXN--j)2}nA!XG48%6^*MuA*i9 z0fs_h1qLBL!Nms}sJS~whcH9H>bQPZBPGv<kOTTUl5HaL4kky_ORq~h#2;N7-#pst z<=2$qHJO9qw?~?Dkd|Y*t~uJFjQ{3`3(H)43+cn{D(WMP`){p^LI@-UWF5&ltdf48 zD6j6#C#S~xjLUO<SIudZ&)!1=O3eV~yav#KaCVp|J~{50GU*$_*ka2{TnK)Yt#7?D zR7Y(bMHNP1Sf=cm!(K<>K})*s)uS~IeBlXVQsZ;RG`^`w@&A<KuU;-5S@Zc<z2-jA z-q>dsi<oXNRfE*rKlSV+am8IWUAWU957}cl3MoS+iLKY&)$97HQCkRjFo5&8HlrzZ zLr8;=S~w_*E}2$>ctUUK>;0v`Eb;sQgnm{ZE#n(m3;#;7NukYkVPo_wk<~9u)f?|d zR7#Uy+*+G;d5#<WR(V<~f7%`FU2Ye8Q(P0zy=>Y-Igv8BI;5N>F!Upe%mxtc^jgPB z2wnT){lNOEw71K4KXqd^bt_^TXmP1c%25A%QskAX_XyUOR<v|Ndd-J4w>N0M{P-uF z4x(h?(m0@m*2-Zrj7<B8DMOEc0Kz>e(c-j6qy)LiYl+9wMmRI@p=|P7rS<Q?H%%Bw zF;q?x%@jjKNDSL}5h#=n@KU6?JC^_Bc5wlbx&7raU}a0JKzEQ{L9iZ}>Cf?S_N_z> zv`fxeQEZ_|R&2CJ_xAD9$5fN{?WW<WZLs8%Sn@`3J8Xyx^$tnXM&VuH|G>1p$3Jat za*c!JF*ucq6FlW8jJ{JVV=B}Lq*rIdM^Uoo1S!`OdjV^UUH*@(Y?Nb=BNLyDqt;mQ zROh4=dB>Pb<%M6ZChe+Hl}mF9`%4uGYw;1rHx{EXvIAzDT-1uvDn$Cg8)Mo@Q?$An zAff6JOmO6Js*aE60c1wD!f&R(o3s&Z|DvPOGt9l-s-1VjRmE2Z2e&IzPyL(X0bWl` z>JM5<(&Fl&eFu+isi5OY#WY~Wdj9&pGJ76;5?Q<RyDbEz3A=ek+K*yf=QWw}N})&6 zpq+VsjO6Apb_>u${cw;T&ZWw<<=_N47b8t9DCtw)q4@{cvx58+dUMi)Iw?&F>+~tk z*4v&gdWn;$f-X1Dx;k21LV}2+i}U-jgbqEZT8sUM>F?Q1sSAL(i|k_Yr7X^M={s8X z2}$XlMz_1e)WK(J`entD@o$>e-^*7t@WXkNus(YwfZ5B)a~v!JvW&#jt>m%`4iKp& zHB*hI1X#e!Xj`=GKWeM(Wmb!i_ulhRgujj)X|EVK>>d70P_BJXi4eWQpTRCi0s3!b z&$QNuL90Ky7<QRVgHxy;4Qp()aWoueWUNtfy`g}9Cte%%s27wH5G>i|pwrunffE0% zn~aj6ft3%;$jjo0?vLcu`*|<@l3vO&?j)-d4PJ~_SuD6G0VY9a>f?f@e>pN(T_pg` z7~e)WdM-xM5K#$E7v_yfXv<*?$D&&4gPIqSmNb}KD_`CF$Vg9irJ6KP9$2Ut=L_n2 zuF=Z^ISA=ybB*;&X+m-uYGC-vxDO1EFx9f1NlUnjCgaNi=qm*h1PX|pyW?CUJdZh) zgavo{s8GX51M%k)kUFko47TPT)gpl&1Q~kVgmqrdhU2XMA`yk|T+ftP3dZt(r}~@< zxp&H9Rrm*rnCHV-4MJ5?{uoFTTo#`w<v|D33F)?*Tt<AuQ|a+5)wd%?1YDv+ocEkq zW8vUoWGY^2SFk9tlvS>z(&d6_Fu!fnXY3z%FOf;n-KosMHfoZ?zZ|{lWYxN}spp=u zO_+Y}hOp!wL&9Wapp#NI$9=7@O=J19DYLru_BBCZRtnK+Ss-Obn^@TlA>wKD{=*_f z^pjdi%)xn8VtT#f4$-yyU%LaEb=-emCLVO3?AG47@OMuD<c}hIy_;!@7cTJ#T%9y9 z*cS~a7m;rMyJo}9Qq=gGfpPFQ`F3Oq#QZtFj6;vQ1*Lt-7eA{&GJVEV+3hrl+7Bgo z-pN+xVAu)+ZRfs^y8KLI{#**HdAsbC7w;kznr5oCN^_+lp@atuw;E%~v?8B#F6t3W zwbU1o)pfMc26Y90ho&=EbfOJvrP)*3O&Hw}p+0K8tx(A%b<m_Yr_Yro8>3Z%!<W+Y zjF%Lt(jiq^de;0^!#c1>Zam-|z6LGS^H)t~Csw%JU6oK{vySOGsotKSEeY+5Mc$0z z^@H<Q7>I(DjK?3~Df2!Fg2QYH0}lEdFo2!u+Uzgd9~D5Q#Z*I1GBw>z=r+av8zfqU zGt<!F=E^o>>(M5B4@5ng%+Y>Oo2Wr#YOC~+f?i`OhUPt@8J|&doAGY>-LY2doyWZ9 z_d*DY*L4-fROr=B9Ft7<xYH|Z*{^YszXgZ=M&T;4PD$&X1`-?@<JmG+#UzaF=VC3C zYXmG>V+fqCC0}vP{*1PI)Znz!F2LzY`cguIj<YoWGCA9g;z5a1Jr<`QY-Q2FoZl** zp6~s%Ry0?p;s-l>6w;qJ`QO<3(|lKlZ@1nTS}d$4J?Aa&w=N4gU}pHAt|{E%9_PpM zIPxm47hp2N9BUnUiQ5;<DvnP4W;9(vVV8PRUICoa?b+WUsOvs=rvl=9$|gWSh1>se ziBHDhYsV-m)QWxNU6DAdvlIh3j4$Hb3^-CMYKalarslh%nkR0@wvZVO4Su?`MsN=Y z`2Jj&LSAy<_ncrNZfBGyG7mF!?fAyg<M7~i>U;IDPxKiT$YB_jr7_(_2*x_m#4u78 z6Q?i7Z8`w?_YPrT_gf25ge|0Ir#Tc`PsmvtuA#IkOOu8LReSIWOL}R<ZT*k>`#(^I z7vF=sI-q&*0Xz5*rv@WzuNG{SBPyeDaFqI^K-<d=Wk?47$T7~_O^{P&rB>Zsu7%xe z$S2y%&OE=?N+|@-hD%3FQFzHDp}@XYa~I$$lQg60Sbi0P_X(Vmkjgs*o~~}`4jsRe zao&_<Cg4i_2;(9Q6e@*TzGV^tbVU9hGINuHjufs!_>^cbVbuhE)^`AM`X0xW;phN# zYz?~mYr4Db-q=&8Kx2KA>~e$*6^f<hx~?zb!<xOqfM?8}egqx_NsKZMY~1*=Bn3G* zG{KT$OJY>1q3c5)0R>A*fakgv>#OycpZ5h6oeeSjMVy^GZu>Dgb?{@z=5mN24d^Zg zNWF=Myi#C3p#DxEQtKv;3zbX7ZXe2!UlG42wJS}@jMpbM81&&9W{^~`b0%b|;?;%} zDd-=RK>x^R+QWyBlp*~sYRr;iJyj4Sf+Lj;X277#s3cxeP09JW?reDiccmUX;#54p z9_$c^C)R6|#t100lGibG>3woH`erNCUOv3!akGc5zj#<&KaQ6~{XYODLE66CDuB+S zDdpN8PmgY7x3<zP2c*)%vIRF?4VVGcq#mlif-<BvOfF{dT+zi!H<u9&&OPV^dg4a( zmwFtR%npZ=E{D8T(9yYvUVsLZQT<MM=3jb|<3f&j5_5<-nHreWDTqG%n1S{RIN}U< z{CmrP9)p{Ung7y>W@vG12XUf#pAW~9Ugp);U*XaWZH(fR1#Ib0#Uz9$sZ61E!)Zc? z8A37~c08|!N7Ny#1nP)?<+vaU+3wJ{>jw90A9m9#J?}gz=jE(VH#XYzu2CeDHFJgA zPM9YgZYInVuBU`+C(IMv^z`h@5dRG@B^d?b_j41~99>WKJU(iM)d;E33pvQC8?CT_ zwFTXdXDh$m8TO74b~Aqyl1i<AxeV(dD0v=cn#ldwUi_p+_1{^pOIaQF3JJ-xN|@Ie zM%j1f!H;XU=2YfQAzxyF#X;^bw(a*|`M8LiCR&aSA^5nAzD4uKfxl;|zhcKX-oUZ0 zPs>G8Qv1z4%2KO&0MC#PQBRu=Ro<s9Pg!wS6QNbs%b<%=GAAKeYap~CyThPAJB-4v zxLb@x*Yem`ht4vj2c3sD!%p;%Cc-WY)FItc_|>m|_02cmaM^P%nY)w1>csc)BFRg| zgsWf`yE{u4eiLC{o5ES>r?PE&)<%BjRWEonOqOfP7ntfSJ0;<1e!F;z8icl>eHr!C zZ3gQqn$kysY*tR@em`#yA|ywt!%VAb0cYkbZHzTcI}_<9NE=eA^U4evNbbc8nw-LZ zJ+-7OvpN@)TvK2@3`8;ghTnb*VjVYSJ^Ks}(0YC9psO_>&(*?f)K)Q7e=5Z8ho5oQ z*Qs-dOQ-NxPA<+dtMm!>tHN-Ml6Ou7x+uBi=^}800tC7!vpn2DIhDslNW$$R+c1A} zyy-E0KMoKm24$EJ_u>=O*>A%u)MY=C>VIl%WterQ8glB!V&+F1q^!?LtmfZ>BZ@!6 z@mlB$Fk9*8*IzoWLv6tqU>26klXHt6nORpKVcqtZZi_ijNT<LStP<u8a;#From(I8 ze4xE`=VSi`MPXRZTKl_Aw?Dl9@b>lFS1(>YfBg8d-!S7yH0K5MJSU@J2n2jsMtr#W zarM7?_2%Wv*R)jVEzyT+gtzZrzj^zL{I~CX%)b$PeQy8uH@|BC*C$+C$eXetdwXKG zTG@DS)`Ek9fDanmQ1#5&C6?BZ+U9!ER)MqS&XK`IK}ijO+;*T><#AN$SbfZkd11;f z$pH<m31`wxGL|SxGKxW=yT>Rq90kIO5@eLsIb{VMW>|qd6JB`8RFVY@Y~{Io=RPJY z(T9UY>oT%Vy}h6ugeWi3VZiw&Ic10}hk1Cf&i!RZl;Nr}Sslob;j~;fc0sEUNLOVa zByhzNJZW)L-_tY**Z=wR=g5NI<ltQo@S)2VP&0KhUo#j!%LBcNl{(3(2|-U#Pph0l zH#YF6)s(fRepMLQ(vvNufj+uXv?-*2YO<>df#pJA<)KdVB*+6Pudi|+h1EcyHN+L> znxPCww=iThZ3UNw9b}>qa5g8-u(dv0^+3;hVedt?8-2=y(43BDYdy)cI&RfeI7YNM z*ru@Mf4}_wLp6hEOR<;`SVQFj-2l0jyP#$!O+6?C_02r7r9YKC%sHHynU|W{!uu1C z`R$Egy5s)VL8Tj4$N~m3WT<m1)q0lG^K9wgzInqf)VnBmRPL*IvdCNYqs<ZVOt$>j zNA1rQgd}K4LhG%-ZVKvCnV>OtZu6YemF#A$Xk~v<GV!#cq*b4+>ggtQd%i%8CP-xp zLwJ&Iv~7%qj~_1bSCg`>R__US?;qSxvaRcrEiiwDBVmk?)*x->SGaR4#;rAj)*1Bp zq#N{1n}gn2zr9^xY-YH<)U!&urEu>-JQo37YXi<FN1F44@aD}M79W{KzI(g<D}&&V zQasNyk*?1-hUrujRBH=6n#~XF4f491TV`Yd$jpej(tdas*Drcw`*h=X9-*YI0tYUH zLr9{JZ5>o0H45ry?%$1f;|dx|GEghwfN=Zn#&gButdQM18+SPCsm>8{I~EO8CZX+U z`grTkhdX!OGJhG?o&NFEezjUVZ+A%c^*3MrpZ*X3N6sF%?*2!B-*JloFK|*R)AG{G zYcQUi&!2w!>Bk>`eEs_EoAxZ$V6(cjms{IAUQE!F<H?gJUw{2IPf85&Z~vcX`a8h! z|J%3<SHo$iEPZ03^ia0zbNR2F)o)Q_W$1#MSzoy{$)y;=bl4l`mC9AvNYI(Cv!>O0 zJRTAAFkD~1Mwo95MqDM#6HYUsR2N5KW?n$`%0o7Y;SZVJlC64(N=+^!&OC~7r4685 z-N#GM?eT0)!D?k^nrDZxRtfVVwa8CE4!1w9)o#^XA<tIMKIscQ01)P*F$#umJHAWK z6hOD1ky^vBCa1EswlmcM`BHz;E!$PP;|=1?K~hEt^Dk_`-Id+p$%dyQmJ7LmtX=ZC zcE$^2NL7zYHT6f8_~1tG=DNQ-#ay$_IXpGiKwCkh73hYvFlf$xQJBBBz$mL|JsuLS z66OhaCmk5k9klzG%j%R>w&m#5<)y38S3UHp+@d<Pj0>SUBEzT03Ul8fr;M!6sbpZy zkjp5SCSP?x>Gf-uoX6bvejYxyZvw|VV-uv`YWiz&dsA-R4<Bx~e^~TB$&8SBa;8Og zrkK#*J9Zub0RQw!L_t*eL(amT|NXm<e0_NDJ5KE2-Ft?&KQjFI@xv!i9{JS<JqIxj z%gR<^i)!@{)K=05CG?aHm34!$((N~;y%z~$^#lZ!E%kyvsjq_iHvHjDLAh#<$1+Ih zM<9Yqtuy%G3DzJx{#&p_H7W~;eg|a|s)>)c-t%?q_6NWG_Ae!A?FZwaHjAGL^BVK$ zPFeZ_Ty%9tL)!}<>KV!PObDS3^BU%?kiQQV|6Ku~AxXRNI%)txO&=;S1Iqn#yGoc( zgyBM3GOL;O(YY~l6x%ESLAka=msa5lWNd8}R?#Y1v$BE=&dS+BZ21D=w%z><n6{qk zR_polpUN=0OQEoe)|s@{cAt~{v&bQ;U(G9Y-y0-0Zz9aUut9$B7ZA9qeuB+PJVmvY zdi>A>RiPBR>@3$TAg5cl3WH`JGe_qzD&;CrfUQDm(qXk7s3TsJn!n1<YbMM`L(Wyg zJdw)+G31q=yFNo=R)y5(8DO$%><+9d6RovPc1)ibMt4s|4R}>TI$&a1de92IyPfoP zhozmAw?4GL7PR_B8I00PYd9!uozEfs(yuGQY8?B;`vEI>y9tYIOSQcK7KDrHE?wRn z&@2ni79emxN7LSN7m&dlzW=Epkc%&--&UZbLpr~H{rc6bS1(??(Es|xFB?Fr?GEXd zo)!vr6Ma%|7wobGtWIt}n$;u;K3M%+Og99&$|eDow4esk3hHZn1q>u@&LWkoR1?lg zsE+3T@*kSoB?Bv&2MEmBb2n7ZXsSNstVIrJJ)X>OIH0tZcE-!Yglnjbn}ImA$Tf7+ zA5695zg3T#%%H|Sg}hMnxK=koK09+-26bF<XsCKM3Tm#8IcL(U0JRc@Y=<tbLdvIN zU~RXs!d~)4%@vh0r_JQyeF*14>q$g#0VM}4&sb<XhJ1Qr_)-8%k*jek2G(|q*^^e` zQuOo+-6C8+2|3&+9`|!5PSpe^PCl0a0v~XG#@W45a`d5XXQk{~bLx0`+G?tvDzlyG zUdN)pfsk@Hu8h*|9n;-oXcM|%@nH8X!~n|>$__EK3MXN<nJ`b(yFs{K^}c-)G15es zZxTlF7$7riHR3vmnjW!&rlCz%9e!SzkpjgyeOhiH2$*~_JY$`G2^)6FEOuwYyf~yl zkydM$grDN`>-JU7Kd-fXK`-Ki|B;UGy0tL7J~PwuZo-SJ(?ovM|HEM1Q1UA4Uq3?T zhJUYv6?n_xi!Liepm|=teEHK)KmGat&)%OrYno(dVqe^Oo^Q;NV`WvMCJco_qls3N zZAPPUBa_T%Msh)|w2_(q04=%GwoPm9D3K;Lo6Q~oH9*m1Z4${gve9S&g+gUzR^=QS zbKH3z^>cr|>+#0--J2DOtU{AAJ{je8{P^*6jvqhnulqOMirD)4c<J`o$`F@gur-6v zup!Kd1>v-LO=}_oIrg<O!h_JNY>!5Cv;|e9=YNk?5q?m8`K4{d5QRbGgcw9TZ|gA0 z0cm}8BuaqbwiIb<Ar7=M#1*jWL|asg9`(zDKyB||tn>l1Cpds+J>}IVddU0|fYz6Z z+IR_w#RrIQ%D;j?L6NvXBq{9Ut2SF{;&Tw4zf$x$(?yz^z+ZziP=oZ6Ar3U8+RDDF zGN>(I4XtBec@?^TUPTAJ4p%5I62A=e84co07rlo6iQ%shhZeoT@+!Q#<RHj{722!+ zwS(zP(QE!+a0PNmGI#Y9)caew9&^3sUoo=cx+PCa!vONsZhL+v7gWRPD<hfetDxp@ zL8|H7MPr7jQdgoY_6vo7Dd<{3w`z!P*(H8;Xz3)R%$bhNV6XXqwlJ1Up~)EA`LGQ< zO;B>HlU*S$MOwRM!<RJuYe5DDX#N<xNmoV3z1DgaddJ*X|L27G%KwTuudcoLcRp0U z1%1`Ouj*3Jr{v52^?JN2c;vcU|K+{kv+|a2{?)J|M#T8qNcmUa5H?;%<;+6SaFL30 zb93&%`N9i6rt2<_DLXrFtFm_`q2%H|Tz(6BY;3~6a3c5h@mF~VxGU3!7lheBvbz*T z1c4b&Pv}BtBzvp@5YVMuaXRmRMs2DDy39t0fNG@3gxM|s3Mlh+p)E>Ozr_D$sCv=E zm&jiQ2Zi>Uiecu9sojL2Hf0dzAo^P4UUPB~WssMl*L)cUO+c8yf9O>%LJ@`GpxZot z398m28T7c9A!>V-PDiDxrudU4>n+I^wV~UiH1ZMtaztzpz2++r6Mew!@}no5L4L3D zwGnMsp(ixpaMvqkUsV}&>92%7g(0p&&({lY`)FlXL!-N8h(Sn(w0<STfi8Lt6+P7# z=yCtr(dSrmCd42jb`>Jf$`F^L$#lyQUyg`1#Q#C`q<>{#x{vr@&_!<=25@rmgO1R| z{u*K!Lm~Rgl13c|irmFBA_%`L7G_`Bx)h0Dgr=$yeQ0_@RO3C=CslboK{fc28z~!9 zA;OUAF9kgVFIyCZ#G#cT(&g3Bb9Vr}<^i;rq}oiU`l|y&m!jAFs{|`8wi$S}Tu?*R zLpZg^B}h|W*>I`AzZS%_;j~%CG5m=Mm!)#cY65BfWg!Y7RaSyj2T?A)m&NMx{QSyS z)N-x;Dro1H5U)~Ri5iBE%<xdX7MCBp%3qB!KqqH2g5%~A*zmIqYXGht9v-^a06q{% zm5hs_tD(ryX-=o7r>TvpuaBPJ-MLYQ_!4vl%2+SvuMrR#z9aDSY(uDGiU{EJO@D|% zL`e<S3wcD4YP$DW6{)tSR_!Z8d?mDT#U&io%;=>kb6AmTjHcsPLLwHL1|^-8hZFFm zp~o6Pnl1!*RbG;a!h(F?z4MQis;~F_XmolFLTgXe%Sd-<8iL5DFQQdTpUcqe_A=7z zQe4%Pcy>K$K0xEQ?x{jJBx#VzY5moq>lHMAF6Fn@Uo~0~QZ{s%%D$>H#9sleV~B3` zQlvHDZHr8o4!ZIoy4AACI|!!<ygK@f28Bu0#XqW3`bYYg^6#&PuD3jbUgee1x`b%e zu5W$+2=$e(_^);G&u)9^zpnh(`F9n1yTbr_&996;bN|}^{i-3;EGT;^A}1uN(*3Fb zUn!F3-IDc|s}Lq+)u##5%;w3Cj!d`gt2U<YsH^@Zfm@a8JZw_-ak_g&I`)W)uHA0g zhcEZ%@_&8rDP8>QzPt4jeFb_RyfV0YDSFKVFkV*Ls7e0S_U&IaTA*I_-vxTzFAzFI zu7N2CKM1E+`BF4(t!(&`re6^x=$HJfUqCJYQnfJJ+l<_chhIMMasvJ;|IUYp@|I}# z-|4mUK2H8Y+<<EB1=@ZBJ&8JfrFz-FJ~#63uL7rfVSB|gM8OM#8CpITU5N5l_fQE- zl{5tL&)-bVpzQ59`BS^987~@Ve}5lQH&VCa(yDt<ei^I&9k^VOad_fF9Us0v%F(|^ zz8b!&eD(OnzLQ~N3P*t7njpOf5xaddsY0)Qfk93%==@cZzYvDdbqO-Av<|{7)(L*m zE5lFgtHZ)}ERa<+&{i{}Bv7yUR|dA?e?zLh=3j&wp#sDI67-}y)1B%dngf04HUA>S znIIf}n*$QEp203b*Jvb7;$OoBxS=@=-H81)<LjI52LCJJEA{%N_?hxjMCO-*p2nBa zYx`?QH*R0kjla%OG+X??6lwj{q3sXdjRM_k{$FqfO0L(r6E54V^N{K<@uO~6p)V^2 zGbCOGTJzKnQ#JF;+Xw_rNr-Ow3(+;#MN`tJhy11Jle~%s!aeGjhdy%+V%067C-ln5 z=mybi9za`$EJiYq>|XQ#{87UC@`Q#1=oXn&AwdY;nE(HTI`s0<*&LEnO;a2AF9m(t znw86NWu8-#>rbkbBwbVe)uLQ$U#+|v)$_daP;g$y;rf1bSl-|@G$XP-=H#r&<;AUd zrXqg~iI|)1@Nn-e-3Rxb@v%vS)}sIAtp55KdhOnwJa4G(ZVmZ6Z=u<PHcvdxwnCsa z<$KkwOCJ%L2t(tyR)~OzP%a`}mq1h3B7y)Ah)js+1j1b_jj%8@K|7SBBTfwAl#9;A zgyF<ufD>(KrCzP7Ny&dzbdwAn-^iy5;Y6TyZ$!5*5XMxBOgNG35`A6pA)|;)w>&v1 zdS2$gcq){S@?ZFnF%FOPLh*uA(Zcw$sv=g|{m7Jw(pdd9FV%eb!K$Dt@gbl@12L)~ zP0&nK`vs~IhO|Z?NL5paKC~2yWDG$vK{aI~A~sk?;MEbg2hj|rYy_8L2oR0tXT%7E z1AUSWIK&7ex+R$LMmMC_rShX=z1PnA_*cQyMjP~4Uy2N;*Wm(<-;4(6vHBWBsu?5T zq}L$s-h2Jgqet7@+j)^v5|Xsr$_K6K+mtA;n64849@U51@zo(d%6MCbdO@`Lg6d9> zPX07b>(bC9L&$GsWV&U>TRLAbL+~dZi-8M5+3qCaL#m_0FaC~kH~v{!K@))b!to1p zIBmvz0vCvkR%NOY2+Uo?`q1LjS3=yQ$J`N91^lMJ5fN4nqO?`?DR1a10VYHAAsvg! zDyiByrFj5pg$P_F)<7U#n%bc4+kI&I`=E=aAl0BR4;z8%Np!{qSFM+BoYN)1j}lPr zX}Q=BFGV``<SvFIPjrEBi19qLui7LV(fn-uR6UQBv4R<eL2d6x^QRAvEWK{EWAVGf zqp(N4JYH30?OMR|$aI-qWW7TKnwTyj`fyc#*0bsG!otGSr%&(Ry}PloVFyq;ywVvE zi!;!Do@x>wnTD|1aKeWuuf2PA`{?``)JS&ACew$^<DmRid4AQ&{wn?L@A^idiCvk` zSD3vD`G{;Ag+OI@auAI`cTiwl=pdZZ|KfZyh|}ZVypYL^qzY&PrE_O!`LiH{i2kl* z%EU9R-BPyf?(QlLXMca+GIRw(=+!fSv4I#n$g7;ab=O6S#u*vCd|a_Ih!+1o0oteq zbSxssoLze{VX6&TkL2SjIx^0%Qaw-4G*Lyl{h`UULG?mZE`~i-Duh8R8b?!A(_0|y zMpEA<h9A!dp<Apd8=>S+459S}N=#OrmwjrTe=rXY4g{IGxw$!}37aVz&`R{k*zoE3 znQfx_Sd`Og_>&V8h@+!}m6esZ-*|I)Z1nix&?KInoab-fbHI!<!4~=X`FV!Wv|!>$ z5BYF-Sbh_WD)RK>$1V<s&(6zr+MSsdCC-2T5B?$LUmqir6Xj2v7OK9Hr9{`^m1$!Y z5RK+{sz8z}I3=dNmjEtD5x7XKR&8kf(6QL6X%ZJqu6A2v8W4a}+^UE`A4nQwuTs%8 zgfH%(D$1*?t2b}nTwh<0K=cQy0u^RTz)7_y^fDsfkS>V0ibxq^5Ut7Z8>f%xL+#P8 zzm-<&0KW_{aX7p9GhAqXVw!(qk!(7lg*r_szXY`PsFx?JsX~zHhAWb#Lq#}=Hbe%} zn)GP$AzJkpB9dK&T{LEhZg~~1GR^ZI^$O^k=rh`gt|81IbeIH!RQoX0`-sbn2&8P? z`_TQ;$E$$aXoDW>7oktM`hL0d(A%B{X8$U4)6+Bg+=R`#ebQ1=(Ga>RftMY5314X* zzXUNCGu7M+dzaE(CX@~@bNZ0h!IItXB7!uDBO+)_r4T8*!3l;tFP}k+yfO&C;r!Z* ze2BJg1iFY!9-?uzF<W&I_+7OrgJ!7B9Zu5|LK&jlv5U*CcF^>sdbyShRBJD(?5hqU z0<R(lZ4{}(RpYt}y7Z`uD1lzRqN_7aeKLL3E(ZGs_~`{bRz;WJhqOlQQuO3r&X5Lt z<yGstFXg`65OjrK!pr>P%>{>vAk3hTlPX;00GS^3GOprZHH>_1j};qZKE7xrIz6|2 zvbs}rb_tG!C=wNTwY>+Ncuum%s=XQ!kI;SPRfx7h`Ku@B%d`#Rs^?usI*4DC7X#>w zj^_co`JZY^z^@_&;RJov2J_b^+*gH{TYE$w`ntdc=Y_TqDf39p1z7%Y8x9T+94Unk zS}*)2pX^Fgs`h@>L6n}C!9gIct%O+Ydya%TI#zFn7a+q!knpM;a2U1_TnK}MgYw(O z_;DMeN)yTIazSey8!JW;W&E8kBGW<<rdAzQ<3pOzkV{bGR0qq?CgXD*C;TP=OjLtC zi%@H4yF2B^t4f2CMN0DOL&g;*nlx?u2YW}yN3Oh>f>D(eTnG#;EG*o(dDC{mt(mFm z<D=v9(e!$E0G<@v)jDQIEl_U1u(!7-ctTBe_4!3IXd*v0R$e#Z9{olnk^aN~=zkZ5 zUlSvu7oQm8Q{u(5?tv!Wgdo{Cgd2Y01-Qsu&>{K|86oH@PZN&uYZ9Z}%F@c2lp%<f z*{R8@+WJO5Rgxiap!GE+nDo~KD3cnoot>SCRq>)EWy!gUG*vYvhOJ{C#5P2F1-g(& zgx>`Eh(HyLu2uVpK2-4+2c3wetmxV`gkD(0Sr=hAIkgN<v26|hC8X)Xhqw*#C;V=C z6%wK{Nf!fwbcw48qY|^JYNLQKldD1afKGZqx^&A+!H|+bfTkq#Qrmldo0Vd((%tf} zfU7!QWw%>xWl)+s9RX7eTN7vv`k0Mq2@pg~*_H3Y{Pd`PJ(tU;Dd@4j6nzN*G<=Ev zY|R8xjhM3O>BG@+dFfFX3z>}PmQ`Q&y^H-JAQ|EcHCK-1%7&}aw1wy@?{WrPLA8(5 zhqPW=LSK~dJ;Rj|=$0)$E!2VMMIQ&!D+pbtFc>&;7v9TV0vs6JH*msC^;JNas%9vo zZu~Hd++}X`;TJStXlQ!A+)H9jGU%%gA_A`{mLYdz)x!9S7<4b_)d!%VCsEPk4(RD3 zlF;=Ndfdx8_8KnG<Gwu700+o)Cmqt-hpOyyKN}x$Rrgl`KjHxNSQmDA7$>{9igVRG zYU)uh<0}4DBeBFBfmm5tSy@}#umsul@a?l(9J)Z))z)N`A+)9o7(4x#=>GD&=pSsl z3JK$&d^fx=<IA)S;#YkE9<FbB^Eqw@eYw%fpvv~DB!jL%7iT7p2@^rMdS@p5s|&UK zE0zl3Bwxxf1`++;GDLd;y{}20I8=McCT9@tFbqc~h$QF3%s|3~REI};VtwdJzKj=c zR3imwKIozh@dEWFbO(Sm6$KTuv$J`{hyR=hbcKOT`iBrmj!=&vTgU3MTFU%GAJ(@w z87Ru@HOi%sC?>;Y7#C%6rrtbBYR#3TIp*%CntPBkt)+T$a(+_v`*(7BPP|qp$0r=7 z%fB+;;$EWQ-`L2wQMpiZvnV<`W}Qq)6i5AY0;5S6%#pEC(i7vO23P*oLF$g+Mv2AP z`0VW5;^GnuhlfW)=R;-m^$uSCzpjz^4|<8JUiumiAh=~HMxIwX%7oO#Wpq`8U1GQx zFT)wNH~feH(SKCu=j&o*c4oRIM-0bHmYBy;c9CvDTGRJSF2GHBszFngp*Dzxva7iy z#KpVe9K%Ty;0tkAGR^~jILaVhV6dum0wzoqAXNAE_O`aR*o|02<na+rf8%#8b`iCM zt>L757vy_XMH4Wz5REg~H^7I;N2Xf}RfqFpKN7bZzusM<#-qR*i9j7h&*xOpskZV< zKp@Hy)J6kjzElHr__b62JSz27MkZ+0XlN*Xu6C^H8T2arDpgQ)y{xU3U7`=vmJS1m z-K#KYH@>CX%0_hM0aHAijMfHrmEi}eCI=e&tPDbsuF!LN7p<Ct9_vfd^&fPP{;T3< z6IVt*nShe?8brPDmRCTNc;!iQ@o}co+(C3+<@Hq!uQbRGnwNbFtLeh&D?>C4a{7?g zOG`sm1~@@CZ+mT>UeFiV9DwR9_4rM)b}dLXIPZKdN|Rm@=o5p|vwpNP$Ws6(^Ly3$ zBG5dkPQCCdbTlZ@IE{Wq{6f)aYdT*F)&Ph#$)K+~hzK;XHo!h4pUe1P7Pw0ODh#?8 zT&0I}PvR?%tBWX)5(qPBoJMpp=vDHBWG0$G(AT%<x<HThGQuBhtvxP5uXzCc=us6t z>C58T{0!0KUSN<Dknd41<0}5;TIzYsk=sH4-FM%8`t*qlfJidhr$;pq-bA?9P@&4r z+FpQDhf-{|YF`<T(%LPrLRVY2ywEm?%eCos1$qK~FxVdTGOjdx1%^5=C<C{HW;jHj zAA@dP<!DsJTeMQOE8MCfkiGxE3=wN(ML$y+*tBEUp&F4CYGOfmq;W53u9h3nW#|fb z;nvxcc-czM?SZD2s}6u#RdC%XN^5-;*twz{6dV`aFl*{Z-O=G;=<-ae?+lll=h+zz z<q36q>U`0AGp!yqJgT7H<q8;8Rq9yv^_*#9GxdXMlM@r=+O0n7@>#Fl^(|jCey-Z( ze<LH4rB+Zl9q=ytp@khN9~~R1FDn@NsehixN*tjO21>b!iNosg$zd*6#&U9abZAfq zhes#JQ*ObNlcPh!qvK=qGqbdx9haMet2GxnlfmjJEG07aFH~_1vqtX4*Kf6QFY@Tj zEI$QAHG!I(oSdpZZ}#u~hyQ`<*T=}x(qjAzSdHOw&+g<FnUrB7x~LMDCnEF&E{JNO z3^>d_7;07715V`8+*3`8q)J#ct6=Z(0GOJ{RDCbd6+?uRCfM28QHpF$vyx0HsUntH ziF`^(xKaX6%1fbF#3JA0UU=23RHSv#|Dg44z52R0RK+hYU=d4M2_rHE7<IK@@X15r z7U1LYSvnS(h!NmMs%V_>yX94AeQD1a&6hPGv(asIi0~uR_|WuY7GE!*3f1i%NH(O) zAkvh+sRk6*_7~_iRHWL<FG17}f_pvcWemz!gD=)yw+sP&z3}NDRE5*mrO6}>8Y0$& z2hmyv^jzL0rh^{qOL0|vuHrL5v(`Y`gy`Dsf{0eTN83OUmi*wnLv2slk2df=XzEd~ zh^V{h)fdmcGDH`bGP_9YRVDNd#B%CU6~ux|;{)}LgBKu~vQMpQ4;L5UNH+9U0S8QI zno8FTez$rRs<EC7La$U25}+wTSCLmmzn24u=9KW|UJ`4PL0@$c5%`5-8CQnfjYFgR zaFxPA_kuw^y@r?3Yx`3D-KMVEG(oR^fyV4M)sel}<r?H|74Mh4YTgGmG&KERBGW*) zN4*SvtNnr=tHM*SF_qj7Vha&w6)C8lF2Pm4UB$mjk@z^m&&|!f_S$RDo;`CS!lb0D zC)J?kTk|da)IwKwL1enaX^2#WyX95TML8%R{$=<wZG*VV_*MCHrP-@c^>@b@&zt`4 zpaOJ|YKhv_`JARE461{|1bSli4U$2mOZ2p|pnQt(C1%R$>1n4p1jy|u-`m@Bu|bdl zzJ<U^s`q@jfNEu20<AsjWjMcgmDJc2<Qt?oS|u~&sNnAB8d<KJ<749^qvdo^KBRO$ z=Kfbc4LdY4I^vq=U{TBA)1yNtCPxSKgxl%l_>8;R^ppWq`SOa!7{O6G%NwU-BlYb| zcZ!kGyvyozdv<a<!JZ3m5q$BFaZTkKb9_=R(&f5&gm$rZDaWthP&&`|l$6FJ$a%{* zf9;@L=PfIe<tkU+YF6go*l6(tzy3RCYie?0ZgysRYSKlQs~jLdH8~kti3WGt=}AHp ze0DRRnVK#?WHnj-))D`mofhX8$Y^zYKR<c#LESn7g*LK4RRHRX0|f{Zk*&{MXf4C3 zCk=cZ(SXhu*2w&O|G_Wk0zCBkYj>Fk=Bu|C?$#g0fkJnHqfBn48kzI@CGyZ+;wl(S z?OJy8aH7!2DUW{4jGP#b5;LvnnnL9pDYaiu7&BcQXQQ*I?htL5l!Q~9sGnswF_@85 z*0b^G_V#uae@VU(z*eecl<_T`2!swlP>oKA+AzCB;zN1k5LWh?>k=fJFcj@WL&g=l zuM7tH-S~?!bIHs4x>x}^UZtwFD7sAfrHKE;vJ&XwA){6iRk1}tnW}}?ELH_C4B-T+ z2ATITyF`myA2OmQ2GPT%(2W@)NVQvDr9XNGVeCEXWwiLD+K8sVYqWv?T?e!p7b4^8 z8=bPtPdPGN@~u^y6&MtT{3ys^Q|u0+?AjOTvAz^dtXb^pZx(|>U&IZ_gn+B!@2Qc# zWWqt{c-6cMLx?`a`XG4Fqh1kJKH9oElP6t%w-uc#KbxyT6AKZ4BGWB{$h0nCy@lu# z?#8F9Vd#n<m9d101*%L0Cuij+H!xF17#|&haG>-Y8p{5_Iv|?BRqF^M(=CBHD@Bz~ zeU)gOrl(1UAdqSw8aHCCS3^3s?k%2uXjUSr+Bl_o0BMB?G_mgT@4|kli&pq@&B0Zz z_{Fn|R0DGn0Z@HWc4Sn0Jv+;-4}D@m_zhiwRD&+9N!d7!Fnn~YLZ6-xU4bA9Q-&bZ zm$YG~+J|m@x^NavM^M#0XzL3QO+bEz4w?W@l!Ivd58+lqdJW>L{B#c4+S+pNym|BH z{rmUBiS_D80cJQsm;zoE^qMT$5Md@8A^s!!%70xyf|XvEp#I1!be)8&_Mfl%BUq;w zzp(<8LqgQ_<F_(sbc7?H^Uol(3N?^POmt5*0!>?pv(w&>Z}mYJWqNhXt9}G)YHDhC zch^m6d3o7c9c1{ECr>bSY;KcG7rrr(Y)@0K+WC>HE?VC{jE<DAG&UtEfj_x%X_d(_ z#OTm@c}}^=Ip<mo<#Wj=rzdBpb2GEn(y-^7(YR4k>5h4R<|63WS}vUC$ZjAk^|)N6 z%4f{ERZh$!E}Z4c{PgK_SH#>_M1VgT7Y<LFdyVMD`Sh&VI6h&$T*^mBXy;G)JhKaV z<&+D0=Y{Eny%ENnck<Be(#)tNamz32>vc&hj@G@sJu{Wy=#?(Yu_7%nW#QA1IU?Y? z>{>oHIkCU9dvJWTys(IKdQ@(+J3BkYO8tJBE;?qs<pc0_^JMqn;D8t$9v))u*FT0t zhDAOQh$KBB>_YSN^K^3Hzx;px0kN--q1(4^PzNf^C>e&fK`;#5iW6K^qEjt%6};L7 zxbcOr^r}-H4p5jX0>X?K2dZDC6|FUW<3<opkT^n`LMR12&I3->U7)HJArzT)8ibxI zViAsf#8Nh>YE_a<6<QNel`5!48>AIlQ_3%oPv|}(@}Z$<zqkOW+DaH6>TQ%S_;rgn z_7a-%-fu6S0)psXfWt{OnbTFC@+zcDH>$Ccv_@20MT06>FcDBjLt4#F_@G*S>CKU9 zgq0zFA-WyYC2FBHrEKV9US+7ozYi@x`*4+Ap=fl<5V5Ol9ij0rl}{6N>A%7SxY39g z{JM??@l`LtQP_n0dZo3REhzNMaf4P3(TBsMlIL1=?}o1VpN>UQkLV4s51E%iSS>y3 z6>;I`ixJh*zERmPhTO^!p_`u#T^XgJDlf+JqHJTYnqDZkI4k>w=9Eqk-Rg_7Jo+y| z%iBmcE61nh<8VQm8k$Uyz77iEb2x~M?h)%lS{u<y>n?riL@Uuai8C6SJP-)chsN!b zZ%D`1oyib=NJnCkRBfEnJb<)91e%y3gy=(_J0)J7E%ZxpRXiCgo>in8<XPD`A(Xwn zxHF2@_foJMfj%TX0%ASx#q&B)?NJwWlTR7celH{=BP@~WE1P79R*ih~s@rraT73H8 zFsNg<Zxlv<fEgL^d{kx<A@Z#pMAkb*I3-*qe^q{3BaX#RBMwe-$?~6_o%K-5!M*y@ zb0(UVoD4LnCRWI_wq8Md4x(ELHk49c=xk*Z=mT@gLHVop=l`i)fR9ef3xa_v{Xz4m zJE$%J#9F}H^P&%0qddaORM8QjFgjCSbpcK*(9p_)&V8Ykz#mKC&Ye5&zWeU#>Z&w$ z`~BI^e)izO1AWa7Ajqc+e}ptq&Du%z<h1uu;XX7&eJFpB_hm$qKdxJnS+!i@vOS)h z%uJOxTFU#Yd1tl0>r2Ps-u{rw^vI}k`21S=7<BzG^o`Z!?Y$irKk}3AhvQ@CC#Nof z3$t@t(Mo#CxvKsF6?IDn#N3c$T{ZE~j3`6EjT<-cW06<%l#eWrkFn0H^6qr?P??|W zHjoUkuiV|;WhJ)>%T`DQb98KYc6LU|Tz-3*S6W>`mzS5VaecGl<oHVY=GwN7Nf`Hc z#N=doGuQ=uYI=ItEp~TzW_sGTcCf$CBYkOrmSc4qM_gh#12k`MZ*OgF*<LtsaJUyw zN|&LMGc>TPuQFqC7g$(W(3jZX|AXJh{Q4MLSzcs`_V|ZpyM(F!SquEuWF#P<%2YLx z@6FjSx&Zfa45ReA=#E31vP*X%F1!*o^6>}oG2=<=P5>IGODKi=QvYcdXjU3CU81U) zh<nP=4NZTOfz||Vyr5ciRWweQ=*q{FfPAZ>`-sSghNAuAXWUb5C0u#|R%UTpl9*8# z)FVm>0zMg>Qos5FT)SKX<1%HuiiS23^cY%37fz~HFG)mG82x4nC!T~!RrIK0hTn)} z%OGej!?+k4;cB*+3rE?A(%}MKrc#&6?niczL0shz|C`Q6gx~0HnbE~<M4%~EL>D;G z1Fd7KU-bgq{!Bt2UnE2H;j3PNukt_qW;7`Lmk&A-hU}h$@Jx|HW<hr`p*DmveXGG9 zQOn){`_SUq2Wj1-UJbUG3`E%oW%Iww>{dfGZyUmIg#1=sjO9fc|07d$T@WJ|c8lJM zRP%I9wed@N#eqZqSE&Nkn1GYB!q3u!+M|aE^ePutoLVBEWe#cWN_G+cV5xiNnue%C z<0Q^avJrj0HMG$-$y6KSVe^y85Pe8TVv$sBoYGvrSuNpTlpGIT6S7z0WL*rxxF{^m zb<{5_zXVr~w+1RmHOT(ft8|8(YRS4<FT>|X^<MwM(t2q!-LkBs0X@+5GcE<qy_Ahe zQ{sTu9q^O?Rq&-QO=pN!)tx~4_DNm}54#@qGUTz2foiltAKjC<`T`t!5X0Ac&zA@^ zvGf|mS(${FGA-rksN?4G)YQ!5$B%E`yt%!-IXykQv$K^KrUTupzXhtC%#Ip<Vntg@ zI%R>qR=aXyf*w=wg5RTU(B%S>YsibTTx{G$UAJB?OJu5zzLG0ShP!3Et;JTiv@7&+ zE=oO1nenECtDfUub^*S)OLuW_ST4Y{WmCe*T&ESnObO-dnHNaR19{Tpz6^28L_}Dr z3TCQlZiMpm?DBJqF3l@MqZ3m9v#}aLqK2Mw$Gdjz8*jb!y<h+J8>_4PhllUK_ue1> z@gEcB2I~+dG&8Mg%gU~mCIK<1!^8c~T)ZfUhwa;g{A->Uxgy$GMu)71QsTIv?jGzP z?H|aasqqO{N;zeb-dMeUdQ?7<YeQp{1B@!&2@x)P4x&7XS9-{Qmp-ldD=RDW^Yi?t zr=4#(fG|eR7}wOy9BsTUKOlW@WKE5aPr86-KksH;rR&AJBEiu&_t-M7>O&V81Y!uf z1Ru&xwSKot-#m_8*k!@&T=_G+ydh(Z@!uF*1e7_bmoFTbk7k$45zf(J5g4B=f6@2T zPd{B;T;zhj2pm?JCy)TLOCcxqrCe{Znwy&=zrMb{v9S@C_78S-By5<YBfW2;=^hR7 zT+CNjSM{am|N8g;3j$vsLpQFk_&@HZYy|IHHQ*%}fN1hE@iH(?-BkfR4lv1R4Z2M< z#6%0XR>~1ER5cZ7g>+A~l|Zt#_xovH7Zw)u5@q3=nVB&+yk$B9J?RVm_`P~XQ^=o2 z1BK~cUMafpq!AG)asy}^O1g(oa!Hp!wZ^7Ee4-gtdsLklVhClIXdhXJQoVp`8?~{- z3Z^w&`}M=*Dyy1;n8ul!oGETyAWVqDL7bev_<M#xOo^X_fu;e_SLta;_g3-&(UkQ0 zquP*acOEPIh4rp`kS6+NCVnPD3ZbpQy}doHtxJPEue~ovbaqQ>naI@O&=7?TWw(vd zEFY8JV%{x7=!Gawyc{A;(Da9?stj-%SZV&KYK=c>y%f<8=&G-W*4j#-Ekqwb==Hn+ zj^L-M5A-w*jVS#3aB9^kQL2Uxj1DkIIxhePsa`dY)(e@$B*I;DgJ?1lXuar{idl(q zrnLsDm?k1~VXwy-MEFtOEt`C*jTn4IJh)0vo3B3bsz>$V<sWfrh@Pgo5oV?|4<Pyz zhi>WVs~kiE2u*XUc?W3_E#Q6SaMj<GG$Q$yYCs;&&o0lCXuAY2&fG7dtGSDdk3>35 z65xYVj$}TqaWDkhUMd~Bs{9M<aXXw#O8={f7^K?GpCHw%{12Mu5aoCdt}3ppFPHV2 za|z!i=2HIY@yU?GYyD_qt~=%GbasX=hF%%n=WohJ)KM0M8MM55Md;F_UZ$x{*+*0( zJv2Tf{=J3^-~gAhClFK3UX-SAUX<q&=7kSkq*qFkC6pEHmiP{h)L-po!ZIvtcWi7T zITlXKHwRWn1)!vKxOiKlyFWDd_%l3O-@rIJbq&e8VyES2YmXduC#S}pruO!Cr2N$M z1mT0jJrBWTelmtvCPYb5b-b*FI%ED<)(FayDc9!u0nw6y^`ojYQ_~w;o9M~u^6kXk z{XL_kJnv#THTB-Dv%R|{jg*V4ivb@tx7P9J=4W`zpK7!>aXO-n6bv~>vOKWR1ahVo zlhUX3dhyKFC4WNSEy#!_C(D;7X=U-~s9Zl(U8@{l9rW+ryZ8C$pGQeRLv{Pi0n|f; zw*CD>SO3Y0azWxijwntJdBor->2yUQ$-S-Zt(D~!CNQ_Rw~6VZboS1HhY6mWoG8S{ zB*Ql}VAi3O$xR6^Y{ab7k+IRlKkN7S@aUayeRFkr<(uz*>tJtxesST0pT7U>*|RUc zc(}E-WkiO_E0;-{nP61O6PTTyb%r;bM~@!dxVgHsv+cq$Jv}u!Idyt^a$J6F$wl{Q zadE-2a4nmio#Q@^;pkq!qB<@5E~73g4poy=Q`|j1Iays<SzBLs5Bu!%&#4pbt@VxD zw{NrVHY=)b4U&ZE>({Rf6qm|m*VRWeS8w0Ct7_nEX)O_}tH6y;OmxhjP^HAs=I0l6 zsWW2AD4?fg^2msMIG>-NHL;tU>o`kG3tFE%dEzoD=0c<tB}%AL6)vi%U^<h<4V(Ym z;#|qzGjS*n0zT`7CZA&@Cv_pLbz*ev@#Dw0Zrn89wY4>3E~VUK1!sAA`N4w+%wc}< z#TRsn<H+#Yad{1*ToA@4%Ezj$JDSh04GZ(*r%$J0YL+4T`Aij}A+9D|0oo{bcgvf{ z^sH@eM26cewp6E3dT>UrE-fv&0E?|T`p^E0U(N-1#MpXd2eI9&TmTa|CzOEZC8Rak z5DuA)L20OjGd4g3X#Ca@Cv=)XwTlQ`g>(tR5i%3Qx+rraNsLG<L^2K|icc4l)Re%W z-CoD9_IxaVOsMHE(YZL|h8cbkmvG3$x3nsohC$?4SR05133B5g=%o1yHRS*lqtFQO zSWyjBqb-O)AMztNJ&6k$M7pPJXaa-i_U%@$LV^Y)8@?oN5E<yzE1D905oQV#jfij; zk+1#w(dKs$-T8$`VrIR>s1n_sls@RvC5oa8qOyCAHKuBjsHp9iqbKpDGF|kfD|)OB zGKyZM1AHqq18<y$a9$Cld)+Du=jDMHp$jIo^-?_U$cTSs_d`BMGUzd{cCyI?trz{q zn`pdnras0r1^8)dy#_%;>)u6^?{9S&xeW1S5Lel~)M&vK@|XHknV0J!mM-105|{gV z6|VX-9#`sje5mO2vk5fxm{&Xi2IVhs75@s9@y1jJ9&fW!qN-ck(qGz_DzhN;C8hs$ z2HUy}W@d<s9+!hyBzy9D`~Una+!y7A-odi|-vGb7<)^9YccLz!<6L8eUKRC6O?xRs z722k1^Re6-Gi8XY5P?DTnlJP;wARLNoX{a4F|Q*m$W{P$hVJGNVg6?b=%%oh#y37b z(T-kFnFV>2I1~lw=qYE}i@B+s@{53!;M<Vcy>KCpm0ybmjya)1WfpW@eSy>Ri4yWW za-3CGKkH$m+;2<vDie(I1<X2py8T0_;Twt(g*G5`eTRwK(yN3*f)wAc4Uc%HWJT+I z?ciW<VR31DdvjrNadTs1YI^$c=xB0cQs0b%hBD;QqTdV{4!h;VI67?jN5_YhR}cLw z4%QIqVoYwWE{(=A>`D_plLG4wV5Ai#&1fjIFnm5UJMC!d5-~nLIx{m-t`;K>6=yeZ z+$z6zbXaVqFH3GFdg-pppQ5WCyxo9zclXD~+&!jeXQpSUESFVwkHp8-P-)5weR3>3 zZuaxD^W|5ZcsMjHY;^^dU1P#91<I0gRv#Iqhp*>n=QNK^xa5?}eCC%kuFaf}4*?p+ z<jYX`QYxDM(vUp7Hgxyy-P^Zr-?(vOX>rMcd~UY9eP<v?`-kO5I$nMsYJ7CeO?7Eu z(LLF96tOTj@89*+)tfhN%+JnEO-?K?ExNTX&d*OxOuD$<xqbWk%F6WQ)XLJ*om;mT z-1BB<Z>+8^EiTT_&Mq%5F0Z)9ExE!`SgvgKO*_Ql;Q>8j%Q;uCn>TONuCuS*d+pAh zJ3<Y~Vg2#Rly_|FwclLG%n*CK`+Ix%E*CiE*1fT@`TY6X^74wcgFihzqjXo-!`-l^ zu@hZ>@wldG{R%FZM3`5iC7+d&Wp;LEZ*QL`@`0rIb3pXO&5cn2We7+K)4~6hmF1K3 zGWFazI4IXtN~*VK{GXbd<N$LxXlf6R4&Qv^4fo=;we{1p^ZB{?@rlX({e#V|?S+L! z3kN+hIVCZUj!$s(x_N75XLo05WqEFX?#a_9vS)E&aeZ@rc5YSxvS4Rt<_=GeT@_?Z zSreB*FbN|#Y2a?NJS<-bPr_7w(5fZF>IRiNooE=&zxVI|`w{z^7;$Y6m8oqW)ERmS zaj4E;0S-DqXM!8js^m1`^bHIqNrq2GM`BTkZo;ZvgpcT!(7IC_CDncbj$m1|$}}-r zR9~R<uOQ5&W}=I52!u{mSs5?*-PTJ%caOU06>zfKt2H4SO(4E?CHwH@7vQK;4PE1W zxvFjq!?{53?pmk|MEDByE?THYK<4YKqUmYnRiMAmPfo(Xa9$u{(5qh{UBd5kJMuxQ zSLx6E4kCUw6LAu7GGzp$Yc#-@$Bl+diKf5HK?JG|sW$nBa0a2NM^!{PP))CHX=s=7 ztvhAw1&K^JgXroHiplC{5N0DF0=>#bQ}+VgO6Ycc3H42ehAYJ`K&D4kq!&WROmyhz z(PXaC#-8DaNi6grq75R@#1KKM4X#moT=I`2<((D>qL<1ZfAC*f*8@uG$X?}NNAedS z1AI|Re}fwM7vs^|%G!sC(&wsw@uZdI{}E|w{0pK-UvT^zjBwEAWdK+4uYf#}qxGMj zF&$>ljhFsu@o4M$h7+HQ+mRnAOMqS;LOdT#x!x39l|T7+kuB&D#q?$W>XcpjulhFd z@9gxXn6JIciw<SdEs(Q3HedZ8bQc%spP_Zpm?8cOh@L)#-%8*~t19D_(pDc%stt|V z(7FdNbFR5OdVthxTW=L$*7iboIgRN^;GZsTP3@msgM*cS^|tBcmVcvD)4g+@vRstw z=QDFpYf$ZBd~|PrpXQk363s3HjM9dWi2gWSZ?&#)*u{B0%DrlMNV&JSdvbi_pUfzl z&d-jI4)+iCtIordBWjQ9X9UXc=ejuP=iGPm`i=GVjg{r4&CRXl#RYel)03kj;C5HF z88dDExx*bE?6W*OGvgAmzqji#JUu-@zx7oQVP!6gdj;jA`}MPouBPR0pN{)~TwWa? z38Y?pq%HfG(U(6U<C=1KNUb4L!I|yNgUQJ;mjPob>3w!u-eo*=zdA(YlvSUtpvJ_o zmlo#Sdd-|0g(I%JgfXj9D2{G!?tX3yt_q8bi>s^G%>i>_jz@_r7Dv&diccxRJ*V7z zYxUOc+vQ$3?ZQ6eM(R50cB*tQotx3Ss3zccy1>%>{F`sQdGqGY)m6940>t%-g@tlC zU0Palh2u=F^e!_-QPeHF6;D%l{rc*S8`o8to@ZfZTKX8Ef3gDHl_`;CMyhn9rq)B# zs9gn19^})r^*AB-_+~oFrd9uvZPDRoUTIh2z1>~6>%E=b#f62VgG1%n$*GCk-Py@} zO^i?6xqZiVdVOupl+j*a8W=4vE}WeS<)cTB`L?hy&pk6>zEt^-@Na8tQy5)qU9ZHv zME=ACotE9K{)Hi#jGtb*o8@vf9T_&`*cQ|7-kv5hL`yQ1_qS(s)SXVjv4Xa@x7OC4 zZ)~h@Zm!QS&e`GWMp3?OEFY!z?(Vj0`P|$Lj+>^u(<1&XZtv`jjE$JC$=Rum^|i;( zp9uT+e)Icl&!1UE!a1`rD;p0^4rivPws*F__~QQR_0@yJ!)MQ)Pfkut&E4Jox4!X> zXV2C*cedTI_YV)2mRC;BPG@H4OQzTTjjf<8nF`Znu~ZLxpa0G43pSvJo@mMSlFtYw zG5I4UPfp6`&wp7L;GyfQ%l?lmsW(U%%q~AZ;nWcow;}*q4GbrepqeHZV5KVHx4zbZ z5a0*_fkx*6&{b8{^lk;Iwi1McLV2%LWd%n`l`zp`cTlw?$ixSTa1f>`sdfr*Aavpo zNuaQ2sN79nLRV}Mr}aB;h%&YdLaA4XE~09X53N_KjkxL~(EPVe<anLPBaH6i4Uc|g z2dQd`o)={{|B51afd~wu{c2yIJkveuiUD4Q2w!Er5z*g-yYgM(Mgy5dCe_xI?X~K7 zabHb-Y7IYxvOBIWlDE;>EoG@PN`M1^6N@3ppv{QYVUNIst`dmwAZQ~Kgj3Aai&h8- zzl*N?mqYgmL#jbqA^cWex_*^e_^le^)zRehe@#Q5Gp!l{==;^;CVbUA%I7G79w&M_ zR=Nm3GO30`zffeZyQ?xy5c!e~l}|=>5L%TH?v`CdZP2B=xJpm>gWzG0dKvw;e-Q?~ z4d`#KhDcdHfO#33pIzsnen<ThSFh4fQ!Ot6olPx}hc4%p@D)D-jUPjhYH<0y3^`6; z{$1-{duOB<0;LR^7^F4m@~=XZ?{<W*7@aH8w@-!%<(lyo(Nodq=gSxr=mVJ^^)lN2 z23?s;*9(E<VGvH>ywt4*IP~`_7buD@ehUN9Ey4Lml6wA&lk-tZ9H&jRn_7+Euq&eD zl1;_|DL)IsF;(E0WJ~-Zem27T(nO47&Q3}laXhV>4~+o2j!zDqQpUy|{zp$vT`J0Z zw4)>Ahe!KX$He5A5{-{8FQGU`pE*YOA6}uAvr{wWfPQi|G&(#vHepqr9-SN<AG(8| z+9L$p=!QqjYA*dww>GxM-JKSe?mu|EI6rfEe7HEjxV^n?XfQf7dNx%4yEbxdd}Mrh zY<PET_weL!Y<O&ZYMkx8!#y&SGm}UA2l*ap`6|ijS$^WEejoXKcx+U8cyg>986UIp zxKEe&qutnDxJHM@N9td3tv{r+x3leddM<8bV~g{%0BAv%zT;Dq`#ZZ&pRW&}4~<W` zXivKD<~McGGxKxD2Zym+-nVs`H=pOG;QWo(UlU%Z0_R(2X>>-UDkU6!O^WG|24>c^ zVPk#UWNmD0xJJ5ZyA|u}MxjemORKp{`e_;&EAyCSAd{CfOufE1fvUdvN*7BU=9Dz( zLR;Zi0r%DC&!4*?Z*6U<K6>=%!RPl~e>s^qsPaCUfw<NZz}eZ^p$(0n@6)*=;^$-A z{AYzW`dz;{tgm5eBBNJc6o@mJlq5f0$n_%p&O7fQ@;gkoZrvIm9T$zwO&8a4)=G$I z&~bNnml9Wg+6W5^dS`E!q`Z-_?gBD)dTLf~@9yk7D!7)eUSB>uIKFXnb#M1zd}4HS zeZ%v-{QgvV)x(+m<iKt6@L*<U7T*!ip}>0D-xuDpGgy=yaO)Ep{;+G9I`F53-MBc$ zD>ynmlwbVGni8>RPuHG2eRS*Q9iB{0&g|{)@Q0t16VryUw|Bsh?q!CmHp4frPe1)s zE2AcBZEa0_%*dyoe)2c}#t;7JkN)ZS_~cvfd_!)3^WASR%+38b|L=chX1BL@-g@h; z2M-=BEG~=H+}r{`Pxi|j(Oga02&G&y@0o4^UteF>%aUOi$YhME@-0q^!1e3bd1Y$k z@c-@a{XP7zkD=9-r5<^Kc*%))5GLRUz50bD8MzgwTWgp~t}D$@R1v^Ynp8o@kz~q7 zrxjEK9U+q)CEb!{ru9;)X2mMeB|+<#GfAQe;IkY35G8>rNi}XaG%;m*1?DRpWfw6$ zh<t|-QG54@+R{Tak!s@B2mEdvy2Mo%U~~%zoq#A~ytttDAz=)nDuhLzDNb4K6vV_O zc=?weNQP+fNypZ`30#V<aMxn%)rhXbFjFR;wdF-qpi2goYHQ-E&>^(yj?RvZ(}V|m zU4;lVG1~Nnm=4ke#8?N+I%(yz46Uh^pnIdc&=J2iRrLk*^r()xLA1V2Lmy%{Q0-}a zIU3#45H97XOY55wj6Fmj(hHhoAdZ)+?HjMw2sliY@@4dzE`?Llg%XG!5QlL3&}XjO zH#EL6Dro?DrJAMM?Q&HdG=+$8D;qyVr+WF&BG9KqdDXbCoR^`maOaWK<=c9f-8o|& zIM#7~$dU8nXV+dr^Rw%GJ(eOaarG+wdW7x*n|#n?^*W9?r(SiZ{YvO+?qay}k$ctn z0I3e*t6qT1<LkozaDvtaUhsRH`6cm8{JXsZ`S8_nMKH4i2mA@pHq9_!5&X0T<#ljX zYV8bdxj{FvW8zYD{po_{5D7&q`~2@w7pS8t%;G`q(#|1W6ww;|u7>b&LUc<o*eY9k z7<!`*51oHdqD`{A-<tqjJZD~9<5P7HLC3DL5xQh(;+cb%hoi$);?SH40aG)RySuJ5 zCleE<puB&j#i>oHA0J$oC^jv8BSE{&DnI3AA)mPq9NPg-&rjxO7mmt1y|$0jv61n7 zH(9Hr`H3TzEAsHU>uY{C3ukw0Z*gT|e`kMWd}M2V|L*HIjt|O#Ge^ylp%K?=dX=mV zjSQV0pH56o2=?B=o=f-4+|1<oq>J?K_RjdEmdPPLpPn7@|Frx8*6S;)IH$)adk6cr zSTdu-BW^DjTFXiv8yTILn$&l6-0f!s|K#Xculd=z>Dig1gTsxj&F4>_&&|(IPfZ=4 zoE+@$o0F-@@&>59EIBGsJt;)FUW7Tmv9a#P;yR}^5vB<ef2pn{>t2!Ra~~cVE<euX zKI0bQa_DlUn%iKyxQ&=BQwf<k0-{unm(zPSUNqxq%6c*Tz#lS^Z&^VyP2jHk<jE7J zIe`E8@#D3p&oI&MGdfCp`rY^3a1aJUQb~i$n5!N4YHpPG1C$Ku#SoWrGc+inz(JE4 z9qGxi&WchM7~R;|(B5d{Evkk_-1I1Mi>4o;%AY7Se1<TE3rCaTQ!+6zIX5>uH|GX^ z_`wH1d;k5P{?>2(z|GXndTD8KZ*PBfb;bSA5%2NCN0U?IGt+Y}!?NS(_~7X9#HC<t zbYf|FVPtr0V{^>~b!xi&1QfelJKJVQFmu)Cry;m2qBGI_6i;ze)%W)8n`2|{u`ZT^ zZ;npZ*EgR%d-B?AZ^-hQnYrod$^Cs7&ULrlxy1#soL?-zk)*rvvSm01Xk4n)Qtoyt zN~^1@ZpB9j`#=1hAGk<AUtc>uJbJdaJ~=+|TR-^iXV0EJf4=_BZ+`Pn|MXAq-+v%J zd3kH9P7`mT5m2(BegqgTu&kSCb`Q%t<ON*Psze(;TJUut=CXb3)-42Y|MS29_oMJ@ zqWlVU`M&{Qc~BO?#r_4FfJ5Bk91a<r>UPP72t>H`B^(-5BLi|y=HUpjDq4w-PAFO` z(l^U8)m8%2gwrd09A!AI8p-g{#lVGpS~De~yJeREy`rJL0~|e#$g&(n{o%D9;z=OY zdQ`Pi+^R6;J#Lk6T`Xo|h^qAkan%JleF2@sLXf%YSN^p2sF&fwuWz8*Q+o01se>rr zE2*ATk9vesm(twvFm(3KK}4Vtebwmf65Y5p;PW#CG-g1RK{d^3N|{ubd#1_E+L$gK zufAP{edsD|V$>#>`o?sca1c!lBG8!K63B;WoDf}|sm4~8Tac!JWRH7ci-*cy^8lKk zpxW!%i9?81nwQG%=PP?XJHWguAJQd=WUs7o7;N>ZKxFLUlPO}I3vha+Y+`+=?<n?M ztqOW*@$W<QL?+d68X>&d8$|}JYjk4*8E8Zwq9m=|vgr>2p*;~1gNVSOo~y={);^rq z4<laEa3LQn9l{~9{{H~TH=kPx<S)GdzYyp+UoLF*g+7M*O52YKM0d;5T3-%t+PZ3k zR6&#N`K<K11YOBj!Ikp$1(&>!WZ>@GuIS2ou+OF7MF|FGEY-K-d3CvmqO3AI<?wO+ zyR52>A42+F%C9e&UJ_5oDWypZr(8!aTFZNOuC*_h<-N8+{+GrrO-gP+Z!LetIOkYw z8&~RXGq)2e9j|E?J!n2uJH4^@;i`S9`&?EAXlhGyMRYdJ)kp!l*P-qw$_Ru=Y5i&f zdqwL7hM??9hHwfG0T~+LxC^zh<Iv{mCMG8*`8kr2i`$LM21D+p#wE21ozl#9eMal3 zgUINaeXO+xG%(>x>Db|lC|}xjac*Wd7f2TZ92dp$(ehH@(O&s$BYEeVRYA1vD$({w zbjp%vY~@^9KO3A7Dbe(}Cpa#D@x>RfzyA7XpMCc2Z-4vIqes(|Q~AZI(V<~$>g4d~ zz$N_n1iielI5R(YesWrVmFN80^7Yl3$tkUFAX8Hl)6=ugP<H6k@>hZwxwg7`L+Rdk zV07n0_0m^<H`|e3S+DIU<(=R0vB|M<m)D6=m-FHB^IxYY=!xkmR`!n$kM_&27MBlh zpPrDMoS8m7I^NvbzOl0EZg8}Jzz4m^)IX~;yuQB1lGzk+kuO(>!$V<D9-31y9rz}w zzP~zhu<v1blxr2&@e>)Xx{%C;Ga8h~Cx_*24+pukA+&WmI#xztD=2T*l|5-#1j|pF z)!z!GR$gU+(38A!UD3pZt4{8ggay-B#GkM;m1!aaEwAV?9DHt+F;0vcZ`_-inIS+M znT)+%fKzqtr{~tq>u6w(A*#p#+C7=%pZv+6NQtGTC3mWiKKa-f$EPNDx3)#zyd0mM zioBT14dcvwp-;}w%DeHy!>)x?8OZ0Kf9?+Nx=5QF^@ksRNIxHxYinz+uOh&o-TK4n zoHqo{a4exf>#KbD@SzdixpRjS)t`O%^IUzkilmDr`RC7{|MqYHcHWp3u9cM)+T4nt zK7D-W&Mp3srx{bg$%_~!wI=%J&6|dQ|NedD!ot$d-obaj|Ld-lPo6xX*3<|E;k+PX zQn*SREBEf*!@O~0)fG44T3g#N{F&+5KmOxC{=pA^`1tYT*Is+=pa1iJ{!jnuADNo1 z&7IMaAvs*10{!3^E09?hC}3`TZ#Vmnm~eoAf#5{ah=?(56k^WX|HpszU-dM8J@hWX zg{laVl3}Qg1+~5WycoZEhUT0y(-}I5e7Y0vaXXtP=w)7Uq6)1fZ2VQWrvxG&VMJdU z^vNp|O?0%yNmc%b0}&2Vg%GW(qmqEK^tnLy9pG>fz;1{>Ty+7K5K5dFDr@WFu#TUy z5lV4xbeFj50t^NYh$z=uY?Wuqmw|kbs>nOQ0TUD&sWQ9gAnc5BrVIQGv-<S{I8>Ex zS0FNjWps9lJ~V#Z4vlCuP^C2rAx%o061X}>+nMoNgiY)fF{m~rbnU8&jM7q9;^3z# z{N{hRgq9C|e0>`YF$8_<v4Jp7#EPyu#UXkUFC!aMpj!16q&ir3^R`>EsMJx}(DV$V z<xk2GjiXmOwx%}T7=j3t57l+tXk`=YgIh@Spou}|CF2@IS2ERbn*OAgRx{p|kcoVh zLwbD)BA*hXs#<#i9JXrv<>)F&c~u;mp)RoS&oA?|$;XZ6kAq=lUx_B)D?2Y(bkX#O zXw~BW;6=+NlAcPJYh|Zw@o5%Aw27#V1-+(vZ5u>a@>Ot^d@)hJzv$XgzEN9Z%Xj}@ z>Aup4AdZ3V)#V;~+FmZtUw(eIGI1E>S6F&R{ZiSz04s9=KD#XPDKEbOo0sBeS=xQb zK9gDCiL?w{6?zh{2Ipg{0#(|Klv?M!61%Ej8DWMxqkaij@tfK%a3bHz5YSq~Y4Y(Q z%#=YDeDS=fE*GC;7t%c?l(%><(3p_tOE_JAPr11hn3J=-wBqV{c3QvMom^~Xd5)Ak zp`p3qWYtw3exT--;_^B(HRXb}x3lx~`E%#RIVbUj1=j-Cop6>{SEuW*@17pI7oD7) zoF+epM@PoWuT+hoC#R>}U|qb*mw3-k(|T>V+$-2J3T`OTI5{^u;=l368_w}=7j7E7 zU8o<mb=fwy<8u8xI662yK0V2W+(rHH_((>NO^i>txQ>=Lpz8M)CwNtFdB?7bV`C$m zo7+mcd31E3WI6QsxO3fUc|Tgt8^Og|KG@rznwd5h`p=Hf>EMG_KCq(PJJ@G&W^VTM z_+))^W3_&-5}!OynTa|B_uhD2N`nWSdybL1t4L<I5zcYci6zq^6q*ip%e$BO;5>s? zk{1e~B=5u~bO;J5mI34A0yuPVurIovR3=kglRi>LGS;$pz}69BG@8lr#0>|b$;BxS ziznxELt~T%B|o_rJvD7gf@y;N{qo1C$zTFb<`>~sR_5dQ*obi4jZ4RCy{m6VM1U=7 zm2QJLj~+eJs_)#~oO9j1*WWxJy7tBA_eEPKZ13*O&(6t;H(!54w9VS?{@&#H#Qb9U zwy@~^xBs7i_QN0k@H^l64xM67E$ciq1Q%DqWS0r~X6%?O@=6JsNP@wNgQdX}1SM$K zS`qv3!=LfZaFoW#L-%Jx)5S=sB4Z$!Xq@3|<!U1)?zd?LYB7ynX|54G=kQqhAVV+C z6uM)xVme%gF*)$`=~G7CGik_${K>QDlu(YpFkkMB`}Ie~XQrktsMXaQKl;&+{*(XY zKY9K2*T4AU;mpj`$>GtZ`+26ADw?@%T*-vZoo!Xt@yQ4g-*A}IOBZ3hefu_7tz|>| z`~UbKN8#7R(DKqkY$zL%QZ%7RRn+$K=6Es*hp(nnbW{-$fXJu2A>oh=Kb(}JfTOP_ zBUF}&ywFp16jU|63vjD8ntV8blfJ-7j^XIYIwIA?G>C>Et-XfMlZKxW>$bwB7hom* zh)du}pa1U&E8{=waX>YuV;3UUB_RHEiK{Na$)v=bW=#mTTu^JjUjQ0HI5;-nXrMFs zDi<Trhv<(jWrJ$<>m`tE<GmD-87wJOb_sf#K!a*E{zACXKp^8vHBCw!+Blq-?$9=% z*0HPMOOV`yrZ(01+3dy;NY|LI!7jO>3Cv?xL(>!ejoFCwO|=<<zWi?>i4!r^I0Mlz z2zIOb0@bRopmCr}M?Q3ypLHEhkZOxtAGoAsC}ktUZyH)twwDsh&W)}JbuPe-P<F+- z7_RO_XSyUfSNYkMOf{V7$IP^%X)w7SE!D>Yl2NWyCG#by7K(|`iD%43RjR#xY2f0~ zyMEMbVYe(_2)tTykbma#gC4jbnHEWbR(cNL)Y1j`E3S7|E<@%W5`-3ttHKt6LH#99 z>U*iGU4AB_sfC`v75;Q3Uj<jn_ttBHT6LiyjhDckrM_w0l`rg<*GnsN0ZuhYH8}}A z?gjrUB>!Wp8CB}oo0ykzmBNd6nEN504I#6juassHae8#cbM^{kU+q<@8(CS=+)PA9 zD^$ULSgJkhWspzzF7U}mRaMy|l-ZX8)n11>#wOf=lfx1L6Qr->jTMb>a>Y+mw{)*E zz=VqrN;Fk@$IsDLNzBpHLrqD52}}n(K!BjddiA2Wp8(GG)=m~Oe{cvp_ftz%9Dq(p z?Gop6bF=P0thg|6gT-8jbacACfB!x`uf6t~r|rhZ#@L8EVflF{8zT)o;gymYd53a( z1R=-$k@EAoBYC}+lg6v8wex7>iK8<o9k?B!%i-{-{FahdZU`d>s6yPkcaIF6nhZ^F zsB+UdI>~QApK&R7MGnwF6}2o9W==;VBIB}3p2JB1P1<#L+&5(cRh&O4AH!yds*gYZ z_{NPJh_$sf4meif)7D}b0te2^wR7mWehQHWrt|pV5694i(HWXvnntdb_g&f5g#)I* zU5n=|>TX1QCduK9@#f7N`F5*=96vX=)(`fNXqlavZ!a3YcrmLNu5u9o3UPP{4o=`^ z#UDd^>#etpt~h^uEVc-<$qn(>k##;Nu{opU35eCy)TE1<*3HdLz4GR#V1D}Pr{S~c zDyzv@lt;(q+L<s?tJSyw5#{c#AAR%@m)r@z`R==?=hxgyw>CB$^#sLSUSC;}d}dCc z?aj@Nt*zz7#oKr99v>cl_St8D>)-gB?%eC^>wFN^yLa!3WU_@neCE=F2M=!EyvZT~ z7Wd?sAiG#jPtVTJE9J+tCr@Pd+{_H?2YY+lF1iyFCaAu9T)x}P|HMkp^W4x9C3H#S zdSYbyaR0!y(<(VU6s{91Kz7?H^ODWM!O`AcS+LX723Ov)8Xg@pu5mkq8};Gg&fXrS z)3dW1YiqB+`R3z?58d&Mmp^9r<m`;g8(W*MyThX+>(AF&oSR+Xm7zVn|HbU=ykP#_ zzx#K8=XZYR!w)}RSeQFHDld677=8$DXI^MPi=MPJWs=!&a7=3!R0fz{y2$EWfL+cB z{Da^B{WN_|46QDg-vkFP2C0sXmy{CjRQm{GLLd2HWVpPdfN5@wO^G%JOkJc!(?GbC zS9}MxiS;2#99u!F*7p96`N%FNfw-y)Vj6zRp0wrB`MbDXe$(HFEV<U&2)05{()1v% z(nCIyph_%|0jXB0OZ4}_aL8n&s<d?nSk=GKk1#bjk!ek>e08MnAmV?(E0774vlwRa z<H8og{I)7k8{hbuENXd$#?gvqB?@tD6A@F5sxq((kks1tR=u*1WQ|289n-h@*#}(+ zB+ijc$FALONmALWDWMymR{<;fHdKF$-IRk!w6(S<sbYE>8FB)Jli>?Ri$m@G0_m9X zsurtXYL^~OdO<kp+p2xtTYUPUOVF!dm~L@PQ!B61BWINHAz~q#1EAWY>Ud))Rr2XV zPwiKL9~ltINcI80#-O(b^@=L~M?;vcj4-HX?ovg^P$V00JQb844659t+%ZCzD&Cud z(2%ce)HAE$xUgCUGU{|{N<JLmJ6_^=Ofqg|I7X7hC&N4P0vy+5)99#ZScYsm=UGQX zN97}wM&YQ<TF*-4WiAcTh9*za5g{2(Md@(ysYOFjCTWY?6$rMJ8I*y9Pm%%I3tG{| zUJcI3(2IA3Xv0C{pljEHD6FQ-@9gM{nYoBO*fDq#_tL9|acE|`{KbFSj&C9eki<dj z70n2{jV`JLRMQ<0njpvAew+`FPfnbkU30*4?lC&2G>3-hZ<`pM@y#*x_^`Z}qN^re z(XT0C!7((g`eK$CIh~iuAyq;YZvjC=Xi~+$>OY=S-Qi)etBFiHW>Aqw6wO%<HF|QA z0|*W)%Os7B8A7po5fieSJbbG+<?PM`KW$S43?vcewz6oxfU6Jv_~-;Aqo5&&V+Uol z@DkH1PLWYf7bP*CIDW+hPHqU!SiHi?K~1hYsHwU$$WJnkrvze=IR`;wK|9QG-a!pv z?ht&?Jy}hIqnq0lJ)eB?iL*DGj?ThD1HS74NkgU?lf!NcLdpkLe)hAUAw-5VE=x|y zZcS9FzW(~_2$w^xj52-w`VE&HZg7lUz7cTY{Q1v+PKl(79?I+WV}EEw8kY$Y5DqBy zB8g5)6BaZ9abvM*eEi|Z+@n@^-o{Ch;c!aM(D23^Z<vB|soN^QrlSib_|&3F^5o&e zhi|_5Cg#8TSO1Fhg1@-9aC}rg8A~}o#UukU<PSdh;9KAN7MhrnPQIO-oo=jeZSC$D zqh2iP_3YU*?uoNYH9aPRhk)S2!FKr(BULgqBpE2wihvAC69JdNr_Z050!(9Jg4<;B zei|P#%dF7DTY6@vr>db67C|E%8Lo*W_t4JFnk1?SpPn7lLj#5EGAcwelK?*%(u-QH ztk2HZNY?#|X5Go_)fNJ`HDR)@m!)?9)6ehRxg*rdzxa#4`2P35Zy-h?q-KhwpcR)! zM)?2Xhd=+;yYG};v0U2iQ8O-1MzghL7M#P+Zr;58$tNG#77h;fZrr%_=+PtBA=yhO zpACc(KELzMJD-34Ikgf`dh<;XGDep{1SiQWb&(7iwV5?2ehQ{LB;ooN<)Z6%G!WA_ z(U3WevL#B!A{3UAY>{4)!IWvD&?@7AOB#+|%sqep{NBBL%%RJi4v$PuPtDEDj*gF= zotz#V9oi&~-j(m#@Q~7myuG>ge0^<ta_ZKtTSt4lmJ4%S<)?rHf*U5nh`6W8T$mJ? zUtB&sK3bTYU*Fs~*xMhQ7(Y5VTv%FMT3B4$Sl`{=85tX$9G~#~tbaDEd=37?4?h&Z zqz7$Eek$oS1Xjq2146XvIX*m)Z)V5BrNRDW?v!h5&y>r{i>|(&?`Du)UCLJm>i5_^ zpFP`+8pr6icDBby$M|EsM<>Ul!z25L2UC+XuB}67=i7U`o;M|1_6{wvCr_T-a>+j* z7UVzt!#^~MT;k#G{*K(^u#%q~wr|)Lv>Jja;YbV|;LO<Mgk1}hW+O6#f@#VO+;oel zYBrzr{U?9)M>t;}LpN5hhiX%pa(v>Yd2NKjgzf@=Y_z=ilvS6BM;nP&G^UamME<K@ zfWsebO=t#j)diT7n1GI?CMYjuRcHzkl%~sIVwA155zU`iY4lZk$VU=Xi3MVqYL&V~ ze;=a9pqieHI(n-57y1#VCd_UeTKVdT+CfB*)?%-s>rWF%3F6r})vw-I_?eF3K&olg zOQ{#JNa9C{Qd5Jb@B?&11bUSVndlh=zSj5v>8R}HL${2;Apa`;UjiM|7mCLfsSZLk znxVEH!S-R(M`R)_2c=DleCc)t$oHs$aP@(n2tbcj(LC?NRs6&`Q0-}~h(P!$0l&%? zq#C3eTt#=$<}m_IEc4Zk!yu;%9pgZ+exb9Q|InqA%m_M_=meq3bW6|F_AJCPgP3ME z{s*z1^7yEit3gaa@&Shi0@R{u_T1$vCINi%3<3Q(VX7u=_*s7U<zgVvY=sE3ag5Sw ztu^URtrDjx1cYiLtO&F9!Us>>5YSY?-cET#BdS#OB0yW>uL@OPQ3!{}<-n~=_{t`a z32CLu*fGye%inJR{BEE;)T2L2(5Y(GJ#_dw0y_M@^1OW1v3w)TBcCeM;n19w8zsf{ znjWUiM7WT1gL_(4@wKWVnxO#g+%tUbY^3UlHXy9Ze>7%#A@D&U)dU2Hv6a4Lik9k$ zrf4JY@+~-gBkACh9ftpyh%&y5wN}iWJNJ}xQS@K}NoQH3#(`L&JXJADm9~tRHbIWX zoUzhG%;Zp|s>uNhCtb)m!|}~YOI5U;&vH_y+0oo-JJC=Yg(EcqB}qzjA*pJ1(5@4@ z;M}}<Q#H;z-s#IO#6x=UF)1;0RaTr7wYn$JhNg!MI&m;4Y2cc{sG*r7r*<73IuT6p znPz8tV<D;g#>Qr@){d2W#kWsC{q(nf>$h@@W?hqLkm1_q=K6X4CO^lZ%wTm`&~)U3 zE^gh-xrw=2FU*zS$TbhL#x`(xcp%-TrUYlfb^7t+C+q8Li;GM5?%lP5dA{-VdESF% zjw(J28rn&ha`#@h5%&`&jE+Z49~|xxV<mADSdv=FsB$b*sdavF;nUB*$i<SpARux9 zCgTofL}<2zlr4EUJ~HYaQi$<!gW?jJa%IlwLQw};zN9ueHNLU6X%{h5qM?g;vdcZQ zpxsy?!8Bz!pM3No!a^Yi98j%EvMTJ{W9a;>Yzvf_GUs7@fyzrEu77qmV<btffiq1H z>&1b|2`iH}`O`Fu4|$%a%6VWV#LVQ(($X@=D4|U>=t0nc!<Ozz6-g)nZkxx)<wttu z3AG8h`23x}^LNNdB(w0r2Os?AZ~mq`s*c9Bx^jad{_x*ieDTE>0`>aqucP^s#5NY- zB*h4-jEfH(i|0ySk=GYraFi1h<B}oHXUN1tQ-YueQ!fNpi??+{(1qJfWSVFr!-}S4 z3!3omzK~8Q|8Xc`oqT)%99@h~Jju^a&m8XVWQ)`UdZF1$7gfuLq$W(aaVhLFX`<OR zKw{!AQ0YrKVO{7Kb28uiwRZ*CmHxBOKI1$w-WnrGGbKrkMU|79ICkx%_jV%z!J#by zF?LGG|NQ4aC+6yoX=;AsH-1A(uRVLdy}RQ<Ft;$jytp(oH~aYEqmt^D%jk#;u*bT~ zu&evYu_w|HJ=}9eUs+k1m?$sty!P5_|LR}<iLoHwd++_%Uc2iS_~Re{==R+^wmAdg zAx{ih0uYOPhR+R5qX2r&hs(#j4S|3FYSPQ(k`y0&@~Q%eqx$>*^?!~3^)Ynw`i&l0 zmrW~OfDyo(Rze&K9i%!wR$k6A0sQVJglafS%m|nAD_($UQ&wd!K`bKB1rzzsDuF^* z=T#xr(-#fVoR2sTBJzVUPs-NXh-ibDX!KQj!sl435DmXje;<UJ61}2|7>?3PP;Ji8 z6IGhR1l2UP^3~D0_n}RFs?}^kcU;{vlA*yU(w(27HPNX=<3J<<6GGsJ4kC=OcQb8^ zNmbeah4Q(WslczA3cC6S!7DPM(~;&>!*8ukPanS#uZV7U7OAZ+e_38}5}I(T*<=YI zFa<%YAP7Y|LRTj`NVS-(Xq+zrF=Zmql!OSH%pkbe6S@!!QiTw$8u?_1DoN9=%wQ3H zW$Tz~gAi#-39XBD6b^(FkgWas(KqS{Ba;6ReoDwh08Xs8Y8ND<$4CvCKqih_t(0WF zN3!<l>7N)ckI(dlHbBo{j~^W|sR}^}Cgs#B(<@!bXl<q;5x_(Qs<A~zHHIJ@C1oR{ zLRX$@wOXJFJOv|`E>XzJ#N;%7Ksc@7p{_M<M?-BLniwnZ#t_aB&=JcK4JRdjaC%-| zy``|V#&qTjUzsKx#Q9nIn3+-I5NmNr3F#752=T1!f^dRHBSP15`1qt83PmI5V8;%} zbj~{l6}K*SZ}J93fPRw#m=TC7{1$=cQu!&`<HPa#UIR%QG!av6k{J;V#yB=Q@%VAM zYdO1MlCfiO#(79%+|VWR)r)fO&*2-NOoEoaI8fZUFvo@6z3ut=-n&52rn^nMyxCIq z#1mb#^39=;3__DKE)g&mz4+-IPgvX-rPkStH~}5;iA5nLe8a?XLDJDMS%gekZXm=| z*`nNm5{<7T4#FkDHNX{)5@$XdFv%pa=8*<Qc>;8nAY6o(0G%SKY6x`l3K3Nff>f1b z-{f?HNgx^$2Sls@4Xo&{X>_Rk<xCt^R^kj{+FW1Xc;gMq8Kv2^WNgxPqI_!9sP#=G zGhgmD@k(F8p`Y5F?eZ>P^<T@7P50=?ooaM^+`PLf9XkXY+0@hwH#au6+(p0j);DNI zh*bh&Qf}V7`SHge<MV_|pM3I3#w8$5<YWw)Jfr1`cz$kzoU_Ro4(o<bAsKpx%TMo? zJC(kCLKv5hgc;J&6f@yE!HStWE;q_Dp%FGl`i02oxTi`v0nX?+Gh5WIuRo^;C-aNY zoqXOICQlM4DVLWdIDn&XHPm~<`RUWATq<2o%9Jt6vG+fCk0-iNLO+_V=g*&0OO+~B zNh%YE_MB6KCaM5Ix%mp6Nqix5RxTJ^74Wy-dP@$t!4lR4JmiKrM3|xZxf$yP-_-CS zeBRPvfJ|6WT;-cyE>u%9Wkh5M<B&x2hqtOcdH3CSU6^%o$!BY2`8pb(Jm^a}IgBZ` zWN0uKOk+w;G%*1uFBMgF5v9zRzJjbHb2L9+U)KvKA<c>wb^`hu7sAktls1>Wle23> z<?me=uu?46Z70qkfECJB5BCpVyM62U@Gwh^8@g~9c*_$qQH7x24z;thmkY32po$Ly zXrj^aL{#aChnmKR%Kj;_KmYu5F_+tzMyi!XcIjb=OE@IQhI^lEVwBI^NIXsV+i$;3 z#&w#}?|%2Ynm+pIqs`5ArcaNKPp_Tl&vZ?WjSr2E%uUa%Z*AH=(EB^PXG7O!CZ~>0 z%Wr|PPGPY%QeM+U^MOuVnKgC$_HB2-)3f8xKD}>!J>6KFuSW|J78YsX0<14jxR<$0 zG8-394$B7`%4QBUYc-IRsx%lHRrcOw*MIc~e?ZmO$4l=3hX_W;de0$XFGS%Fyn~T) zWVm-gM9YREQJeHla(9{K|1STE(3PM^870c5E$Hd&5LaD*(=q(kq|8UY1Drl$5J~Pq z$@mGy#S14JF$nUJ1XX&1tMoUb58?OeK^XF-d}Wx>$5*~OqJI$dM0pda7Rr&ORr|^= zk&a3nDJL2_T0cs3Ti&7vh-#{brl(i0u*`HxM@@QJRJ3IWiA*}SzRE$QRrk>82w4|t z?Uvo)xAL!mK8w@>!hR8fKJdrrK$rM{P|d>tO(5O1+LAP-V?0a=32!*nau4xm5SmD) z3sg6Ii!OZ7x2e@y1^dCh2!m?1S&&u;zm<kSXU2;|Ql3yg7@sI1*0goi(xBQn&DA_& z1N_K<)=2gt{-m!e$r_0lgAKox>_z|`ovj*9h!};8j#z6#P~w5q)OLxB-z@NSM^GzJ zX6kfycD_EKb@z;+%}vsLolj5C*3Z(qF*<8<#*8=zd(4-kEj=vL5P7t<r3}B7Bx#6D z(-8j1XgRO&S)G%arYs_%!%RXV$Y`CMoGyM7#xyQ%b!-WZSlARi_T4I6T=+dY(p%R8 z1!T+d<l-a8s<n3k89<zz9iJYb8Iy}`{hO)f2W)VRW^81<esJ44sXnXA7Xr(>5Lq~m zBRph<|4Ku}<OA1KX;yXCiIwVafhx%ySVO08st)J6IH)-*P~`yRtjT{ynaiPpu&T_= z0MjwbAwwe;nKbEwhSQ@%#>h~f<FB#cQ;rEWTD^~S!Q#TQ(;FGW^f-$so!f8-6N@k_ zf&fk`WGE!#mcoj&9Syl25aYAHBz3Ru3ehZA#fpH|3`#4P9F=qt3IZ8OjzNq@o`<o^ z5Mh0tx9CTcQQh6$M$krsYD}OBI73sCVd_P>>%sN<)2uX@1-A4x1&(V76TwPuDSR_b ze0}lxCO#P*Nx?T$tN<qK5dP7@fvp%nRki?4^YZdCH|Tlt<caPg=^XsU!^edA#t?#C z!c0@h7BSVtga&TE{l=T0eEN}_>f+M8!|cZ9+T_Ia-FvsUHh1t}yZ6T9ClB{_58itF zjpL)!o42lS@0CwD1BFcRmO|hLKbbI(d4`$=an5i50(sFR8Q;*{;22t1Og8}><5eCX zoE)7VPK{3=b94WAYIgE)?`V8#?1T4y_U?DSwYR-LHaU9h`t8HxqaXkH$G7g@SzTJ* zJ3QFg+&Vrxbxc1W9@^X9ab3T5dgjJEJu!K3eB`ix{npKLh1lMh9G}|R+qO=pW+t~b zwjJtUyZic|{pe5UX6EM?=RW)7b9|g<&z|h>JDN{TPfQ;iAM9=Kot&R6&MnR_&2MjP z57Br&e0)~^yEbxdYP|dkv2i_m^uTZoUqB2>sD;HCZ{50OXlSFBPRVux{N%IU;&5-j z{<ibv*u=!n*4E$rz2CEz{_*es{`txI|N4LXzZtnU^p`(<@9j5Vw|)-y_qTR-B!RWD zFgM52ryqYjE0gUl<KucAot*6L>}X|$C%|qZZ>^d4<OVl50Ok>=h+P|zPS&6s(YL?- zZCC5NckfDR-Su)OHyj+pB!)9S)_bQeQ>+BqTwm#b^UXIu`|PtU=Wl-Vn`>)p<*)jj zoJd`(NfwEKYc>tZ4Yx0sqCfr9KXn01hHtEIX=R9A@`ey^<rtUPQc5!pDDe-EdLPeb zOHSe&ixTLkfec9<DP)vF(GzWt(pxuf?C$TcKYu<wJ8O;M%S$=>=)r^K)m8V{nYp=* zopPVlJxY@K%(dmuF=6C6TWimr4coNp(Aa_)1;PfB;b1~!CZ=YDXnuBXXK(lX^lWNo z+AVr+VgA4S|Nggk?%iEoUO6ASHaa}w68`w%BXhJkH*bJu<l)1ILT6IUk%04!8{*a? zCZ2p7I(u<Qz=zP3Br>`PAW!6mA?$6J_{(I_ngJTGO-xFQDk~xob5`H(?*7#DjH@pV z)Rq~kf5hnK_3Ki??bmew(I5TM^z_v2o43!doqzH8$=v)rLmbE+%lSCWT!z3LJ|%SS zAC(ty$-7h&6Gj5O%AoKusj@9+)BC^wgMXm>`WRYSTJDiAqx+61r+d@|&8Jiw;ee${ zydt0sOpmhhq1WXrUVyvZqamfJwQ3_uS%0)iFVzH5HJq-hlA*PA@FU-?ycCj2*#sIv zTZpcqMhqeyIhHC!LpX!_uL6H`lu4~SjuJ<;IYUoV)tC@Ir26XUdfo+9lxvNZXjaCb zR=u=@))%L{bd_ivt!=zyRD-S(h#o|qNvf6o5-<a_zCo&&q9<`76aC2tz;9(kmzlE3 zzasQXM_`xH;&I)E!t8@BMsTu&L^2v|A3}l20oCj*;z=MKBNjrLbP63kF-<ehrKk!D zntTvu<|`#!6^AAds!;{_5ok@JBOkRmkxZ8e^dbBv&@H)SSBYbWDO}0Abi@p5*Ir@| zBKs15K$SD`C)M=oD<gw$T^MCLtpPfSKk-2|3n6q6x^a5K*GBRaCbnNYq+3V%A(s3p zi}J@cN=fGI{KN(F^z8V=qt7vr3-$MVwK_(JUw$-!%OftO<>#_U35N57lJB1Txm0_S zx?mfSkvY#eU1+rp80BI8nxEX`UY4gvvV4}h#xC;w)yi{E%AxYx!tuKN;h*A7^@+#j z&vCFh!gl$iCJx6uwn-#hHK--36pB)t7bU(b2qp*0)%Nh@^xEmza4x)K^g5*a&w<!~ zqeG+U)1y;|=9QHdK`keVdTyY^MI|S~<})i!5=<LZ4t7SQ2{N?wA~1;4qjJ%58X(3u z-AN)6B1e;qMHR{z>iZ;7&Jbkax(E0opd`sFHyHB#r;0*+Osew6De!?jfvBw~@bdjh zM;3fHv|Ix+BF>P6=x5y|I<HX3bBA?S>^w$9Llo*5Csko;s`t6mT(q=miZ-JLw&(;L ztx0$w6E~E=H-6$XL<4!WFuLvVfrpXQi<njeF``sCkm+#f#9@>YUFgvoyGp&B5e=W_ z5FB<3VkHCD5r+mH)1_I=`Iy?>`j!Zbb#P^LMubns5NI}KB1Rx%S*w4rloHxl5hY^c zsR{&iC(K)Ju<N)#KR;`#C5v))cAD1p_2;*5-`&~S`sO#^-P_w)TPuIsXMJ79j<`wc zMKgz4p`2H=IdM|XoRa>GS|r^B*d<I-6G_m-XJs@94kk&#aeUX;TC%=or)Kw$_FX%z zve)mv?qc{q{P+LEjoUXi*EV+#c3l(?@|(K#k0cG3AKh7d^yIN?!|eRry*qbZ8+Nv~ zpFDetb9CbVx<4{jzHGd?vpF+4<0fydPR&m3ZtYG?PyFalfAqV*_q$f^(dp4!ufO&9 z+2i+q{GL(YxN)nzweJFaw7;{pdwPDdFt@m{G=H#XFy)$VmzgM6*3prnvSSEuGGA7k z2ob<EB7V9fS?qwwd|{SZsNd%-?<)=skB*N`jEyVpj_<wyQ&;U9w{D&s9Y22h1m}1E zjlX$(c(Asy?(*||eeLx4WM*#m_RU+%t1HKcM`IJ?`@4Jjg=*#APT3Q9qBI2@GgGRW zJ_#oGRM9-qgwLO2d)C2$F8H=7v?dc|AUAH@KqHdLns79cq+fR?C^XmTM1b(kn>YXL z&;HEa%q<$<<AB&}uf1lmi_HD|_w6KtK+;ypli&D_--x`+u&kJwp3_U(Yob$Mwj{qQ zA2hK-kL^^GL9Jdd`KBXt83<uw?!&r+jy%jdLVISpm5J5X&i3_{)$^fiPai)Ky`_c4 ziK)rW^$l6{;Qkj2ON;p~uEcXSHEP|3%i1)X2zOC?0z;Mn2eJuM<te}cZjk4XCBRz| z(=l!&X9D!p^u)GZXliO}XUDKzx$T&93kwH(dt(z5`@6f3pFTA=H*VdUtKSdb-6<D- z+CKW|BT*GeW509fj+?M0#xW)s0%I=$8SWV^L$5&K2)G$hHR(9I^WV^H9T6kL5M(;C z{W2jLxS@+t8=W3#oP@~OrMfQYciwsDy&wN2)AkBFe*EK~y!nl{x3+htrpwirEv0Fa z22{mo{_9SgZNY@<dw5d5x<VW4+%V&+hNcO!w@3*}_=fXe{G)$F?CWDlLX`izcz!gZ zoGvQeEiVOcl*dQqj0oY7Pt_pNBGoiRp8i^URS1WUeF$IKt5>924rkRUTI`giUgsFI zIg=*HJHVkEB6BI)NK<VDg(13D8ZihRBMGSnaTQUeUJzG7M#>(^-Eta7iKE)5zi|K! zEe@%^I^yRbxY09k*|@@K<zSUq>#J1dVVq3W(87Vnj66h-Y6E{TBdjSJ@U5{_OScL# zJ?b*(5)CohMVNhMFvw5-ygGQOW1!kIdG$NM_AgC&FeEadudJ{ig{hkKu#el1s_veL zLFl5cf`+ClaT`RUrxzJSgdq{GT3;Xn%0YzR6$_`uE&Nu7fYvcp<4r5aAT&fFkm*sC z77!+KP#|WQ31d0EU7*_~)j?=d_Q@mSLz-F%T7@X1Ba<p*ei2owG(|%QVg{(pbm$%; zwv-{DK6{M1y!)!GSI}}1wJeMkC)ZT1I7j7AdX%HKIAnv(-a@&DkP^*$JdFPG_bn^% z2?H^-Cl&&DLL2$wH`LG9kr!A@3YF;f^>w9z$Wk0nN}hNqPEFSM>t|fzX0S~2yPUns z?{PV;Gc1BrlamfdBje>l$PISmWP(O58Z)yjdSHyl^{v9=!{f7SXJZbo^}lPw*Bn}R z_sf4LXD9W?zZ{51&WFy$!jst3ot_L9L61{%*MBry#sA)yEqhNZgrPwqSp!y-fT|!) zPfje%%{l*3g@f-RA!7Q{05m{a!5K(T>Bz@P!><`^DWc6cg=O;U6q3Q8pD*9x<YW?z zp4y}2kAQHDa%$rk!e$x&Rnseh6$ITeaWa<hBgxy)hzK}a7mXL^Gkg}SWXWVzV<bii z0bS^i8-%GMW2fQ?AF7(33GxWQF)6y32qjvRGuG|fH_d`x5d%t03KM7qVTZqx4ddeu zd5)f<K^uQ~NEkm}p-JYX8-f7g&p-d%NF_WgdJ&_U|Cp?hj3M3<AR#xh>*}rq%9V*H zWKwVh#6Zd~vevhM_0BDqHm)Mf7d|4O=lIa!mD>}pc}jCHvjpk!<EJh)%gd|yo10X+ zqn<jR-nx6o0O`pvxx^^9A3uI<2$W}<xCHdeH~tf@ju)Sc(fWE&rcW>0;(YoJja=K@ z*gibkpPySSA22*0o|~UJJvm=qS-k)GgE!uMt^Tdtk^Q|xn~b16eE84>YHn_Z|1Ry4 z&PwI&jT@`7#T{W`VM(jJkeo-SC&pq$DskLQ^;Np?Z)~hNzSHp8XZPQJ`%RaBnn$jc z*N*unTt>$n|M@A-$v{Ix8v?#+xg^(@82DzehOeVB8m|N}aN0DPFJdmb_!%`}%0W!f z_^yst-%oz>69V7**0-ptcYw02#MVWH9t!P*CO7Y!NoK7{W(2SDE7N=sVR|@840O?# z^DRGBdF4276eijgPV$&L`gLbZU;B*KBqyJBx0#8<;lXkFfx5Gyyd*j~HGXn@w!O1y z*5(&x5B86yXC`;H_ntm`{KlL2o<D!iF;`zVq6ZHi(98t?dFT%2#^o;eYrpnuoFTTc zUcOq)v{oJ_w!AVrLl7>0YT~d~s=j#eIrqpIBPWd=U+7emX*vocCM5#(;PZ#J8Y^mZ zYs=cOdbhW>(BJv?w^==~JS)dmW!s&ao<2G~JdmjVot@cVtOS=;%kPtqKAK-#^n}Ro zAy3(k>USj;=F3lcv&D1qOg?1o@GaAw(Z%88lQOQUiOKez+vCHd+4(tl>7|wBxtZCs zYo01ZhjzDjp0BT6UoC&OcXf4DJY6iMjiDJSC9KeCzAk2J<osIsV_>5tD&_o;z#`&< z^q?vcj?cuBCxD-L0)mWrCnMU%#R@&FU%!5nwoDd<tqYiCX|}Sm^z8AIdvCmcu)BBv z;iDTjZ;g(Xulk!u@^S-V>Jt<5#RNlEqFH02zRLdMctbyPIBf&uCzqs?zGVLKAO4}% zuaBYS#qyFTW3iXApmRaZECxL5Q7^*<*sKc&VZP!dIzmrp8xKTV{^rCWy0*F)v>Qo$ zL?3Fimfmx*#T3w&`ZH4hZf&ZOPxUGonzG3>Lf;VdHxpgD59!zhiq#8FYwZ$OAv<rN zn&5+cRUOpdBA^U2qsIA4V4_F84633(H09Bsgl_y+#*I|b5D!(;5zSWPNH#=6G<5X@ zs`MbDq)CPk$<IJjWT14u417qdQWqN1m;MN})>Jix=;MD?ByJf+Y(;a^-v=9+eaGw* z=5q$CFL}EOW&)V>$To_=>4RQXUxB{SgGk3g(5$rqhmth)A^fXayYs8sQ`Z@6_$fi! zb1WlO<pz$j<y%qI=@M1Z*+rhIh}I>r?S{Y)BHybFfb~9sbPp$bx+Om6+bk$E91jVE zXejZiHLXg|!c0L1$n6X^PsgCE--(-LDwU=&Y^gLo?SSr}f3~-`>(ORzsXsW__oQJl z&^__gM>T<s!#Lc4#rgTOlb&x8)2b9Vt(b;@j<>2*dOFhVK}eNHEMbpl93|So)5@0T z>+0%_;_<2HWO={$d^jIe9GaP&8l4z-{dNLA+COkubBLapp4va$!(m!?+JF@rxB&?i zA^~?AJ}+ZBD?dyza&2sQEZR@bPu!&UsM<er2%H?79Gw^)xi)fqcKq{?K3rH{a>jDd z)X`Wx$jyQXIO<Vul~HaijPjpM%pnY)KOX1MVyh!0R?eHt^K;XaQx1+TF<gM@d0PKM zqwaMaz1JpmWaYfRzdtr%VC651IwBvP98Zo<oKSy!k^@$KSN;^o5!}|tN!mn%{^+r9 zBse%!Vk%iVI4Eyvnhr2bjuA!^rh!0n9*x7>GLZUWe}>6<$ngatrp)lmAML2$qN2y> zsKw_Y@Ps58`Vq86Nm>yEghG?<Mx<3W^7PYIteiUq_TDyEMd)R)Mw)RcbMhwdNT(H3 zNg<cgD+J%9tBbByUGiRvG;jgNG2^=E%MDR-wXl@<mitV)^Lb{fq&*rZuCklcr{g=? z(O+M!G*8V;8^>p#eMYBh?)FJMI!y;>SR^kv^@Wn%)8nI`zW?6d?*8j<yf!*A_VCez z$%(0Nz57k{!QuX2{`e=0OAEs?YjpUxfAGU6&z}D1FMncy%rU_YG_}C_d-v`+i1UzL zuG)Fn`uvmf1Jnqvf`KIXUwrX}?t&mJ27>AA`{?PD>o;#Kt}O9kW_EgEesO1a`{9E} zN5_ZPS8q&BPi}AROiYfSpIuY_wEUFLYeu2t&d#2ETwGjMng=tuw6r2yU53R>&g|{& zxTXm<Tl)ulbF=e%`@3hS=aW+tJKMW#(R}mP4RJ8))s^cfr^h&a%Oo10AsdmZT*|Z} zGSPyGk7jyrd(S;QsU_^<km)lif+GSrqM<YkMlAv^R8b|Eg!RJLoeT#|96q=08<>_R zNqU%2iX<`otamc1VuDk$Yhv=VPd=qhla#|ms4~H>RYsU^a_PyFCrb1;-uwn7nH{DL znK{;7t}r#xV=WjmpPxQ`HaEL~DYh2h=%{CkRYr~N>)L0ZeRB8iYtNrQ{nodB?cu{O zZrr%_$)`Vm>+RQ{K7A~JKmF-X|LuSK-)7es`IDp-85T___t@Rq+F4vEf7FN128)ng ztZTJogeA^sLW9w5Y?g0y2T4(W8i*!76Q;o?Y~Wfgu9FhK)2Z=^Ya_$1WM@Oy%Fmu1 zAFV7dZSC&Z-8~&VJ2tkr@U?ng*g0KLhet;|3l5GBkLurrUR_=p9UrrO>>nQ3KgpoA z?(H5-NY?t6wJc&i6Cnb^1RTqZ8-*v~%=F~W&erVo%-+GiU3z+UW^ZSAa(c@CY?nUV zKcJsowm8qq;qi%3y#4mu_5smj!o24`$*7o^R&hhKrMj`UZgx~-7uW^CiC6S!GAXHA zJ6cOLFW%%APoppeTJ-|vaI~`S2_oh^A@A{#A+yVeJ9qB9_uhMxljGM{Rz>WipMUuM z-}ue#oqZ2!s&3Xl1SKD6M$pDL%H<v<4<3}S6<~UBs}f*E&~#Ly`HaauRVidUGDg*3 z+6DN=@``6s-WMpxA}dM+IqJbQRQ_`aXr=!g2$cCqnEygcAfu82o?)IeF2hRn=-4p2 z9#qPKLPUBWVxy@JY!JrTqXv*J$_7<-m3kqR4O)d&iB6L$h+Uc>8iMlCzoLh{qYy&G zacU$kD~+{|qxX@#9Lvy-XyF)hKBU)2_mwpCwc^kg-?&}9dqH%4?jj>?Vt@mQPiRDw z;eYsznJB4#B}C64>N`RuR*9s?RibLq;U~7;5?^cNYYv*P@}8B}d<)S=JU%|Dv=%&) zY|1qsU;HP_POqIho+?{rnpgkPlh?naSsCAyo^6fayp1Q(&{rn^^B>J-eROD4SyyP! z|5nnUhsVHpdlNdC4_B4;0uuxhSlKjWHyng*(GCT~%#m#?IiPAMB@oU@eQS;qL=;kv zXlV0Wd%svX^$(q2jwY6B^hkhIwYCy6mO*f-_Up|>o1-c|7|*kl@_VFCB<0s!$k!vK zP&qM|xo$I_S*~<%L_r3HDQ>!nhLU;wJRyz`Uc7hI?Ta3S`4Z&%;kQxqCzoBVj6>#n zNS(`_%4uc%5$d=R6KEU{AtkT4fzL6Tm2bZJrbnP?2(yuHZ*MAjdh_OO5fc*^omS#F zJaLxtHqttjGQfnoI9z|~mN~I|>#esAT_|_=_B@zRPVMCm6C;iS^$Kb?M~@AUI7X21 z=t>H4P0aaQK3q6G>)5)vxsAgI56HQ>1^ldZhXBVHL3UnII&ASFPhXElo)|bz&XihR zfJ>^pd;xa2*?7LT<Y2qJ!o$7ooz0zX-VTk9Fmzac)Tj7k_Ujy$oyXbB1<~VQiPH<` z(Q$d))!>LTh>zibP_Qc|ITMf(b{HBf$0nY5a<`c9%DR|eT6767Uuqf}o}8KH&-zw* z#uv5c!$-#l2m42!7>-+$Q{$uZp<GMt`sIhT(Mk{Bv7u|uMvopn;)%5nW-#Z}c$K-M zQ^_l5GNr0iA!Ag|!D8sdL!K}`|CMMQhtj<RSBj&|tg(pR_TKKo>|FaW`Ps3a_Pz3b zs5^IVIp8`FQ?Hb73kyqczWMs&$4_OT2%A%TtWaisxm--oO)tzY3_AlH9Pb|N=Humd z%k0wllVg+l=sjCX^Kj_uw!dE{#<q5LhMu3D9g{{QBj)m8Z_k=8zezPSV?){5bJ^L| zYuu<^Wi1eCBdN~M=VoSR=jZJKYa1K1IW}=DnJEu5@5u^d+1lE$Z_Ll@vADFf;2ikr zryom8^DaeQTup&<Cndsb>V+3SfpxGmHKP5_JMXyWB_Blf_8gssTT}1D##K<@D*}Sj z-AH$bq_jx4baxI0h>}v$T~ZRGJEa*N(jB97qXrD#^LzgTuIn6jp68Cw-O(01e-?25 zcsh68A!ssD<8R~P;Aswab6ztyBN~0_<e8zblXd=gCqooM_<fr$mVx?f5Hc}$bYg6^ z8RT(-MATedh&H(xX0wir#N~=<Eb&PAJ_X3M%6)Y@IcZwoc+ZfPL<9Yggth?qiM}`} z$$f-$T{Z1@1$8}`k4fI!JRM_5KIChwEV%0Z>sQ(dTc%(V&a3KYzIIdBz9C<yh&`zQ z6d#-$cQfxmXMmLzytXFBD|qz9O~UhJqp%&9g+@+WfdRF}Qmr*LVJN>k`1mmK^zgs% zP>$G#u6LmYQA1o~f;Lv8x21Hu0C`oLqFa?Y>a_<#)W6M!sbo8mK-6%#k_5nr-%x?g zg4OjS=X6lL0t2?D?ufUE6`qgPFNMk&HoOuC1x?P$n=FqFVs8f=WOL|sDl}%=+dAqR zG}qQW0;UZ(xG*}@y(eW#YRK5O0OkF(ey)~U8SMqWBgpCi$O#%5WewUKAtof5cqJuW z>|2Sxve<CIWnHbdn9Lw60~4NPq@kF@{Gl=@i*Cq=52?Nh8;N@fD#Z#)d5cy>&OP@4 zzidu6NZ`%KSCBHS`1Cs<mFi5$#l%Q)&(6_wQ3Du03Qyx*h_gqS>Ep|#J9led{^52l zGsDJVrAH%Hb&?!SH8M%zznAhTi+(X#;v{O~m+FM6!|Kd#nbjbs-pbGC<cThQ6^r=k zcgtF=QRN)hbFXpxCl_>ebo$Wea+Cdq)b3@u)g3?guiyQ$$`*(X-nU~Qcfqoy<&qF! z*|YNX2f2AJbPCf_8JWYLkdyrSCEDZXhX%;LnaWN2iO?y&sR?rG+Rbw##om);pC@=n z?n<jyRCu&K|NWLVTh@dOflwkkC9A0hOD>JBs-|E%fsHmF4uQ1-7Ib3&`Dx^b8)^+z z^uDa>_!QHZrRr1?U%!kL-4SK339t(saCR~W%^q)5x1ZK^`S{+P8s9mIf-N!({5<Qk zGfMBaMq<T;0n*9H!|0LUcbSDx$Zya$N_@~A^use$ZxC^K7h{-nm64!gV;EeVYkBWB zEz;9fL_$Q!gRT5Y80_~)(ZveI9OD|Ns-_Nn<xi<np2(r=0XN2xwubThv9Xjtr7Jw! z)6&zYZT$SExj*55`cN<o#te2X7~^ok|ISBJC>8Z0O<?9*dhuwA@Mrrn7Oj2idTk=@ zt;*Njjm+;P{(E~#5Fub}R5jUB`8oZE1<ne<gN${i%pxN*99~=mk%zo=t!}ESzgPq_ z3{DT%?u(n65&$PmC_qel-7C{moZkPnTaP{^+;+M60^y4n1QD`*UF=u@J2$A+y!MC= zFH@4Zpo+2c4Er4B@#VU$7H_e%iUMC*fwaPvRbl+VIkxsT3hhc2D|q&`Y54~APCC}G z$NX^`sR+fq($@T&o6yy}*3{KS=>{`J=QtD5?PBAKhiXf#^U&?<cT?Vnt1TeJz|zv) z!^28<cRtK1^!V7ZjnP+rbZpEextA8wo0(}iUsaV*V|`RKQP;=ARbp-LYvJ#2WI4z< zy!Wzyn^xD2{1z4N{q|S6QUFt53;0sq6-7W;BDKvsLRqQlbGB9<bO<&a#lejuB-{lW z{}KY+-T+d@X~<h&ZSOEfTR@;mP~S4(cImu(DtN9Xv?aR()$6X&l)6aUKj&1KHN0=5 ztFK!Vm7bT(^yfz|rsz9WHPv|6B)8^;g%wW-ac-K>c}4C0#F!#%yP)7AlEtR)H(mJZ zT{Z!4&YK?kpJK7VVsQSE!^G&+j-K#fCfyX#=eP7SXwN;Z$sui}g@dwb5)OF5hzF#H zCa1i0u4M}4_ja*O<WR#FRzbb+%rg?ZuSP<-fsg%1H>dkOA=vsxY^Jsk4+soFm&$1n z5Vufx{&;SrKwg<p_zUeauYrS&O~QY-xf=d}<gHg|C-(a*?%x=Aw&q0Qet!*FUG0FT zvp}!<f7}Cyc;%6(BL}irrY7gLoHX*FrxL29vy7Y^z^Dc2fD_|m3nMDuWU?`dH-I)v zT3gW50h!B6EsKAi2nHrys^!)FS(i&Y111KnNuHOGo1TRYSwsG@SMa}_DEUS3xSFoZ zYI`7J05DxY5Ov*Tp9MS|4C0<j-WmqoyP&!ykw1bEXAhbCE}i$P=^mc$^r<>JDL39t z;p1vv6X&H3*roXOAtQ9M6_Ys}WaEaJqTX1059uW8#fX>~uc>NU2sP5WBLc`e!tc+X zv~->}FeGm;;(}C4K+r%3N@Ol94huePY4>G`z{RACgC|zMVgYt+F*gG=505XgV^L#n zH0!P&JK{IhoIw@l=3ub7&-};1Q|_@`D%AeO)AjnJAOMsdjZe0EWn*JAx^ZzaH9jYg z{0HyPTv#l6dA(R?L+K7q{A4u!lk;6=h4+ZKPb*5?zoLM>4QEAo2@ovxVRo<*4i0xZ z*mtoMA`|tA%f=DP<-ubr|2B*f)+lvKNwQpG*y^aG@DA3CAj_|f{A9)7QX#diG;k*t zs~`dIco1q#kTUS%nay&b7b48!V)NpyGEVnH5|)rbUEj6$%^t<{9wDV9$g?`=b|AA# z(*KZ$PT(31aaKDz!CR9<Ot!vQ^V}pAH~R6iM3Vo^rTrqT{IxC+5VwK+gL4@Q;u0wC z)?2qtQm_{ed?y?&DoU<pnkNb&M>w$;j$kCk#ZgK4o})~kyc7<`Adohn(_<=fv7l>} zT}glV`C9g}pKquCF9~1Qb<KUlb-%r}4)}PSOmyJ|5FC(5k|lsm3>>RW0KU*!0DN(< zWDuZfuBT<X2`>hs*2pI2bM;j{Ue_tV9<iBMyYU&3GdlFWt952-?`$2;g+@mD1f9&U zJsqge&&>mxTH(+kK(QRfUT<t{I$P}!<rQ@xx_fvGn3p8`4QD#*u$jm*)vJ!0wjd$S ze%~*XU&rCR-f4l+_!M-#SR#49`2SDTbg}5<A?VsB=n-`mbT$x^xi1ME&`|>}4|j$x z?HW|2FbV3R|CK)`p}*EqtLqIMvdc@l4Y<@QgD$A^rpE)S$4wXDP4hWhtz&%Jl)O`@ z>bhRqUs$;5y6L!)y#0%IaTh}dHe6rWKrHN|8=iICP*xpN7Q-9nP3|{-;5xSJwA%az z@nx=~PJL8!#Wy={f<(k!Trv?Gzl=d~LoDWQAZYqWZzm^53Gl<G&ediwf*_0X2fZ4P z)T8o%AO3U2G~hkabq!eiN2t?5e8uO$LCUL(!GT*Ktjk(NGV_Ilh%3u7>ECpGqhr9_ z(n`<6c6c0N3L%K6tNE8?HmyHUXRftiKG}`!dG#`yQO>R)k@wY*Y=vtyfRzy=A^A{s zJf!{6I*N-lTt)MHIt<D%W2~c(WH^#}>lz#Ic)7S|y7FZBG;k&!cqa>%9n~MXSmpTG z>(F%8OhYGTg`I26K~gb>F<7|c9b!l49+`k3T-sa<L<R&qzzF6s+PvdY>!{5$$CJ|y z+_;$WiP0Qf+!IG<h>H_DC*%vO$F~XE0d?{?Tul{r)Xf<%mH<@`{Eh_Pz*wQQ%L?bB z{GzIFg?uIw3xE09Ig?T?s2@gg3>3ySL-7d786&u9{#}MtDG5uzBHge?L2Ak0dW8cR z(}USYE2(dpkqOnzZed~#$QNBB8_*gy=AgCG&V0>4UfM1^4fTdAE9Jd*hoUx`eQ8Kq zpNGds8mj%llEpls2{Y$E_?q_pANPkaUa00g`)&XaX9@>Sg4Qd<2UGn&#{P(R4YOBX zcX%7%{ADBUxzj<Oyej)0E@=xfvLAK5d~d?);O{f2G%DIUw|jaWn>9f|Fo=ktDM*gV z6V>HaO&Ckqi_Y%rh{T%u`rZ98F}`SS<kk||7u+dg@Dd%5Tn0mEhr2&L*}T5z{38b} zmOY!kQQT-(Z~m+u5sMeu7^~DvGfK78+>JrXET|W7pkO$q5YF^alY&qx&$F9O4M&gW zQ`Zyznj(CVZ!}YIqbC2Qh#qQ(46G7;hkA(j_xI0G>o<`emJvbb5wW&LB&TmN#m;1? zev?yuT9mxy)JNVC*S>9@&M-+uLzvdu+3o|L{Y7_Ya2lS5AayCz`EXI_%cC<D`{7r0 z3||NrZksok-;J-p55wO$Vl-l5b#>K=3JAyR!jd`eG`9&r{kp8NCcqdREd2JUaf@0C zO`Ja24+t5~c)R<Cj1Ru2ul&N91y}pm&pKBRySlB*uRDlToL7|~%bs2}la7XvLr=^d zpE`)&K826C#HQX?_owIjZtA8F<=2%$(|Ze0z$$lmNAHjADeg{{1?!QQ{*ITI`@X>a z#My6v(Y8>tj<>M~RnV&+_XmpA3EKu)i;yq|yC;o~ya9Q_m?Os>e#X;i>>P=phlpvW zc==zPey-IVNK!4qys5mzXNJ%tY6#LHeOURHv^~GH=&)6#ei~xwuzY`dU_d)4lC2w0 zskmYr#VKdI+`a3GW|f78TlV+28xfGWEibQ;RISe@qLnMddfl&$<WmU=5nsMT`ohei zu=o7B#zjcxDoN1SZ1VM1e<pR#4aGU^!3x^mO_PV{a-m&0yKmreW;U0O3Pqb2+J4dh z77#R9=}2Knn(el<>-5Z2FR=nAfl|xHHWBIykrKgX+@_~eNLP?{fzcgY&;ci%96&Sx zxD>Zv9jsBx{^1zV^a2zbt^ufMr^TpMz`(g0<kKJK>gmZP3|)rLFy7y{O&4WV`rHr^ z?&|1NDywy5y&&0oAD*e}P0QD5yG_P9L_99$`!Mv_)63a;+tWQR_P<JO2r^Fb84bZO z-R9C{%+b8~)IOhzAG2egEd5CfEcCCRhz|>X4YU+~W$_|uQoZEw<GzBVGy#D+qho9i z2VeWuuAnEq6fw=93I@hboyKSPvo-P4`1z2o9Zzt;te#_Ot5B`$DB6G>oq9GihTrJ7 z{|}6b)R>sI`ApClN{F1cU5fcXf}OqR{9K0uFK=sX+K5vE^5mmm5p;*(k2w)0d)v_P z|HWsv5EH9C6LJ*x1*%`pj!vy?>{XRJOoG=wH{|1MsNJT=2hPC4%ZT`l0tWFBVJRrc zVn^8Nd*X!QPc)QyTZ`rzdUe@O(vRxt=p)N;AP06|yLG#u>FViqH2{D>9o-i2ixwB% z<%pyLcpbDzUW)8aew&z%FM*$~{V!XFusxM{IPY}<Z<F;5VI=fVweq{+9vf2yK19ZI zjC1N`s#A(LmOwbFHYO&<L6#zfLU@;z!wR+YGz|{|*iHkO=?-D=vJjf64~#*?@AqUT zzDLbJ*4{PKY-G5*^5u&VD$aS|49C~EFU>AjNcmK^0!g}LurC0F5t~|-Fm--MM8(AW z^4I4=PKGHNG{zZIG4Qdgjezkt!FfTWp%Z1`TW!AdCx)BI3xlpme2n+!1eo_FcBGiN z3h@gY>I*H>0{a#$z-k?hT#N6!2QIHbFFF}`++AYv#_1sI*hWaK->U`#r+n-5aQXPf z=%;sO|B)78me3|tb?r*)aa_P?`FH6JBow~NXm=uafd=(y7a5Rm@mdYIJ+Fxt5fMwv zWI4kc0`IcXayQ+#w2%<p0T*Fi{+FZTe(;^Krgekmm1;Ra*!F+nC$aP-PIcnzUDw|N zs^62o1y^HnvZr?Ptv73|o$P@)zDEDdtg-Z-6vDp9HC87tm(c>8OQ#|T8bN+reUnAo zz{9bPWE*gto`(Ov9I9GswkM6?IO}?nC>}AB@K%1B2zvAY-#-iwC)}#4#rm&B{6Ni7 zvN8fSJs{@jCdL5-+nwjLO|$Cymj$x<$Fh0QkO%5PcO7Q|6MDWly9TwJ9&3)opB`N! zJjVKV7P=qfc?ZU?*M<)hJVt@2#*)YU?)#Fr5O=RYyKc?P;|EW7^TU5w$G4t<WN+t2 z5@5Ne77IikcW(EG(!3Z6hNEP!O49meD-w{_xoC=B5HRb3n*m39@$4d73EPA%Vhej$ zY<DrqrfE^@S|Z=u`*fwDp|hpB-FKs<uD!XXar3xVsOfwMIfKgXh&+HI(}kHzJ5Kz} z3=P;Na|161(1I+ZFh7mRMk^QN=UVLgm^)6ZB~P*-N7bQu|CAF(L{t*=KRS>dT|XU5 z!mN+z4@w0jtV2Z{pl;=}OZ6YJ86w03Zii%2n5>O_c+GFG$%loZKQHqn*USf=pVDl7 zQ8{7;d_CLWN`HO4y}K^11=%?*=u;TdIjp-qsp<2r_7`pBjh<QWS?Yoqq@~3AlMc%N zW#bB9pfd=GSyrAZ!jgu#z4-yeBP_CFF3KWghJtsAZ&Py|Zx3sq<MGx~i+8Q8bH9W{ z&oN)B`UU#si#UUa&i0?WB0NjF8A`m&yO-Phe?-mh?4I%PZA`wx&S&Y<)gIu6&yKBO zrGE%e7#K8C$SMxenCW&#K9^24>mh*6@fhj6U61w8RU338kCC?0#IX&4ZcL7<U%V9; zTT;n=hEMQZg_kw7?7si$v~ZyjO0Dv|uX0Z8I~^3AF$>q&WAhR_<^Z!GSOeJKV+kJ? z<$%rN`E4<=dXup#GxEleOkg#4WCj#ir>4d3eurC1zxIDuW}ta0L7)liMWX8!#Gu_J zupv%gX_in!3r4d2ecsx^SQI;at!!AQNLZ^dpw7x`e(?v|8|JtCMQ%xRx|ji>^RAwZ zh?_^Kr1j~M#s1on&&W-j`h=0(aQS2bU1N)1x|n>pMIGICZAqV7y2dc^-d9D&7$v1y z7Prv4RiVXZ)0TmSFze!Bs<af>?`gWMM`%7PZ)p^0$?vP^I!tb14d^X4Ct1qVyb%0( zx&5za)jOplEqV6!t3vU5CxaYC44UT%Qg7kHW|OwYRJ8d9_|H3NspVFr!|Whcpe$MT zLv(l{{rspSC}65^Ioh5wM|4%OYj0wniLnsp3cxjvcVegXGH{ALJI>$Qb~~NUq}nGU ziNB<-S#BF;W8-Xr>%UJdfO)+hsRXmBuL%XTK2uZ4ixR(Rd^Vh1!=ai5AC^%J{j0@7 zl8g~NS6G$RTUDbN@}K>$|2_=|vUV%=HWBZ%;yc~s&nbOgV%cvJOQMGo$k6dAYKH$P zYqou5eCWrvE;9Ln^C12xi$*^%*4+K@v%&n$UqoQM(4Kb9$tuOgjnoG!`HT$k^-ie? zj`;PYsGtk9GJ6aHfCQ0^{s2}inr?6>2Tb4uVBbpUoZS8<R7(rFKuH`GkN$&X_`<La zOum<nCu(gW7C&_%$6WrW#1)zSOtwkTSkAcm{GatJm@v(F5}g=u_()7(d!HqEpT^{c zJKcu|($NC-)1Ln<H#ad#Xr3QFswHzc;`OMbg#O;?`TE{AAs2?GW>d2Dqpq!k&JUrC zxW3F_VeDwfrY56MDfMIn#1%k$T3Qwrf~-e>hz$5_!fTPlv>UHG>IQu#{B0wR=Jj`E zMouQ`>}l|6vngmV95|8-p8u~Uk~1TTgsPKE(UDKs5#U*HO9hH>TI@PA_6AGCL*!)g z;LfkiaG2#L(0T(EB5fpthL-<vku=P>Me>S#KnOVQrtXHka|%>N-)t8j5q#hY7-VvG zc*y@roSmlTwVRrJJR+6z;b@6@d|W+cmuNJ5_RjO9#mio9Po}GOp3?Vb?xbLb03vkc zkhwC`F~<2FfpaR~H%soYu!R;}L{>gAKW9`DYB3|Dp>jCu2eO0e)YdoO9sma5S=%~l zI|#|ywONnaXK|s>xK#D2{KC*C8yQIc8a=-Zs$mDRatjKYH=%EhMGxEO-l^{F=xA$g zZEt8m>_F)-E)NbAM|#fptc`(x3L&cqeDbx73c)pBw86<qbYgc;LRazsS&7kLu1s%i z2ss{zhvzv}Jig_I&CQvi@pb)=4snO*SHXlnzi}w6MqEuc-Na3CvUBxO(WGkWop-H5 z1o$%a+mvni&rWixgM8@;M>jF!S>{5qaa>vy-n*#&=U37`ZF>DYvLs};OjTZqTBV3A z>K(%bM%G0nevmoecEo#<BRL;=yI1B6srAWwi>0U_JFounT-@-26XQhQnacIJ9H6E^ z+6mfge9&KC$|B}`oOG;S5s+UZ&q?}@YsAm2NhhSjl{8W(^KggYS7%kP0hcjzCM-$9 zz}}IyKXnNq`W~sb)pA(c@;3Z6-@nS0OBsuDn$d5pz*vBLKaEypI{Xm0TgQ^9=SnOu zFL!wCodV(spdmq5+BDbRZWWT_(fTMeu8?g4{d+}r*iluN^W0E{QzdYz>>Ga?FmxFo z8<hxn9L?EPy1u+15M6_BeenjAIb(Hu;|iZZp68e6Mis6q9N{#G7mF%Gm=?RAxV(b) zvV9^-r}GNCR}`_}hN77TiP!yb`z6zdep9@Su8lpC!5|%U)nulg{b^@Emz7pGuw^PU zRhE}yPI}Jj%987*R%}e{*|BpQe(U$s(_>+MvHIEedv@W9Hk(ADQT4I2+@x>3Neu%N z7Y^HPgKdUnh64G^<$^xLqJc2~WOsWzZ!4$!^agV#L0y1n2q>_uBg)|lgB%U>v1+@F zC2X{9bNiFG7mN8v)0d+=2%DpE5;bk!I?X*B8UK4xMj!WL`oAleD|J^k<an%TM10(R zf;%B^wJwrVwvPW*ke${w?7^266%Tau*SO1>xJmZ0IM$8mZYaWW<FedFOnY*O1I{>u zM8pmwxx8;0L?xd#dP~!x>7|Q_b=#1b6I5?UXp0=iDaH*IV~qt7I~k<5eV|*B#h$Qs z-YxDW!-T4i$sG5`Rzo_=(Kd`=+su7OQ`nnX3{xRxA#Om;I-xk0eAo)cegK{iSrj%v z_S#h(_JB}cl1=0ow!f<6Y{SBldFW2Uq5_{k&t}7Kgz|<=kOaP1%7W*TF|cq-xc#h( zl39E-X<@cz%b2`%1UXvCroE!=#o8dJY$;9oA@L@|lfLRFUZw3bbag4#jQ&0Xt!~*7 zKD$vx9``tWb9vchy@L^(=azyp1u5S;ld5w*7owZ<ebZ5qoqt0y_F71IgV+9hJ^oz$ zv(PuKO<$OWN?$V(Jpa3=r+-3plr3yUj`p8hQc_`*js&%9L~v}*cF7)7&M}NV<!-Nl zdjwY%1fHMh7_s!u{?PEH+;hY6d7J=W>|C+Y;Pr}|O>g`Ht;*<Mh99c~OMC71(z1Gr z)6bO@aerah%Sn;{3B^uPA!)ylmkH?5l#@|$Fym0l3oHCDJD2J-SrV#@t)M8($g1<J z^df0qgCHt*PErvzsTO8!VfLFClImSl)~WH`Lf$d#no!i+(mXqj2CYV{g~uvKNp4fN zC75p5QwXX1ePKs7-BUfk3@IxO?+XYfJJsh&G<M5NLHIQo@rzi*51=>S;6ClAUQ%o< z`?v@nCJTCStT}k`4KA)Pj*FI8dT{)031K#tOae_1K5g87V&R~qaOynJCVjPV2~o5V zpsyr**7J3U9*d2V?%hjnuhv?A+n$mcA-lhvZjzkHkOFPyw~oQZAvyHoma-u8+Leet z{lrr{B`GXfVH-aF>`cRDdHZ8|8(CYr_is`ckVXBdY-2iOV*_u9+;()FFJ`v0m}#$D zG@<xKdRoq~=ro_0p{Yk&r`OH+@K(ZmA%1S-9Ahtg;a*#wQA&D#STH^T6LiOO=wpp% z$EGjneAZ?9L&H3b{%Ke=SSU<Ab2<V$5sNM+P*KK=@*JHnJ)X^A%6baT5N;>89IyI$ zN8H$x$z{y-4AQiQ&+tg_s)vzVWXzaRnd|K(LSOzQ`OE{LPT5hX+qNZshA(%amIa~! zwFtfmSb-D59@R}xQwmg|htK<8mnyYgx=@X-Za=UwZmkuWTTaZ551Xs&_c49JezkQC zCpA7t1F8=Mb;gqL{j@Z}jI?s(^s*{5_ZJiH9qe%Ef2fS;aZRPtGCtaX2BqyZ0oU<Q zS{<^AM7=AkoHGh(*d8LJjNd=V+CuJren>UqTy2hkMaXBS{}wP|km-9vbK7gtJMU7_ z{A|98E-RZnTSPA!J4Q`SedCzo*u=D@#?Qhk=;o`3e*t*@AECFqbCp@rt2tqoYI2+y zE^-Zia!oE?$tDj^Y8|niAD7exoFtTtJoMaeEwgBR8#?qKlU7#Se1wnjwztY=v*gzj z|7MT9T!@fWOdzJiX>g|SHUpbWGrh3RA}d}FmI`BDtmX6l<JmeUkdQ#k2nH_vef!<@ z+Z7yDef6jRl&nR(xLv!k2VEzxE$6uuRJi9ERMYhX@iz*I4>Q|WmsS^77fo9_?cYm) zuC+j@-54O@2tFI3S>xtjM^E$;+LM8W6O4?6Uaew_knm(W`+yyyjLYcJR&6OI1Gk{g zLN&G-w~3Z`=-uyR)Oj!*2rMJxqBCG?3eVpxG7GUac=Fk6%X_s1qC`3)px@IE;22n* z#RQ4i(vHG;uTy1B=t+zXI9!SjuQo9x@5k03yKSg~;AE1wkU?C^U0%-N;~4Lj_ECks zt*zR&qL1mS93;N*aF<uw?w!`}+QdRuPax3RG?NEkML0SW8BU&}QfA@|qBLC?shCNl zkQ^KKxwhtoCjU_^8OD7-A2<9tDWwG1R*}c%IAI2hQEgi1X5qWDf^c4>n9Q^c0RjF1 zU6!zF8gLKFz~}3oXH6Vu2<HFq#V%@(DsVrcy1ur#rm>~7ML=Abmz%${w%*V8Sj5fT zcrT7qzssA;!>MMH&V!AkT;*r&IMq_L#wU`VO)1sF3;cn^L}+R0K`Dz3-qhyI43j!M ze}zeBe`)F8<t3oWBnvp~`FQJRc?wfWNUlgOt*+~5nUYdaxp@h<dHe0n89$6&u}{d= z^_uIX$kb(R=71Yh9QKFX&#N6ruA)pl5HM#JHd>Z{-+zhgXl^NzSr_ADM!6zA|3cj) zaIFNAtP;~R>Nj^7o~3d_U?+EXIVK=0kNu^dl?R1fF!*fTctU2d3fcd1BJ>Ac0c((S zG1xZ9(bL^cEz2Qpx++lX+S1I;*&@Kf%L=*ixgs`k9tP|S)_Ltq*`+SK;}5aedYk)M z_>{L-`@0`!ef4V6oE$n|xM)a>cc8;yf}thSQj-=#pT)ekvGm<JZujxl%_OE+Ut2LT z(i0P}<2>;j_Lq*0Q#n0$QB_l;qC9046qu_hg|OqE9-vMj{m}HO+VZ5hoXv&jmj*^z zK8lqXgCtC(2&mbVl`+o(jZ+<5;j7bl;|l^yj%G931UW|9MGogy@+C^uq8%!dc)1x~ z-dylQjrNp3!@+~mK;qPV&*F+v(D}wxwrJDJxQ>odQO^0w2N19lv9uKC@BkRw9sqkV z$^*g3*Z9p&sd<zBoG9pmsF5^~hqg^gQ-6`i<G8isVyVGKJqL58CyV0i0tjT`FcNHM zYiT)GMny)TBX~eYSgU<NBg!3I*U}M_lRv|~3R!lGu(_%ewmMf(sFZ2saR}$tFS8v{ zl^V^68A=&p&}NO*J!$y`!Df%4A<O<I_=j{CVMF#Vfp1#~vut0G#TLg>_*b_NS3L*3 zxWIn*<(Sg7JzuuSmrxS!S=ZmWOyH545S6~9jEo5ZZHl^A4ekSl4lluvTog_Rwn9^A zPN&aQbGT@|>E?`PxmTxBX}f81N#bZ^Z?P=i31n|3ZZes9*Ol`jcgyah3N%0%&5uqm z?9~6VXsD~(z}3Qbdm_axm^^ekF~7hy9mwALvXyN`=@}f%&kx~&Sd+t77+K5~XbVK6 z<eXlL&(#i=cl${VF&pnl=DrOnn4A2Ra=2hi()$_9U5ZRliqms4tU_#oJx=*WI)xQF z^%?VdE^)99!vrCWgp~AFJ>R61w*J4{1z%*Ks8({nEV(@0H+MoW78jpIG=ELq##DN> z12LZ3mKt`YnHg9U4Fx+xVRF%AlI`Y=$UmBm>fi6o%BO!&<}L-n*B`pdcB`WDVaRlF zb5Tc=wG0uMEa1LbS>o>ZsFm-{*QeXR1a06y?`;CDy`9}Q4Unxa&rJy;L<-@-MOka~ zKSOPx!rqo;vO0F3B6ec7UvQ(zJN#Cf{l>&pA{G`wB0OeJqmlqUY=96@r_V8a`d648 zcIe2a6_zyUt+RBce!eF1bL7CzZ#miOTXsyHi_EbqQ(d^b>zV!%=-BIBAv?jzfs;Ie z7v~6Zi3l58rPJXXC}BKXY3CQ=mJkrDZ9H&m>F`5@9bF(|u9lllMab)Bjee4uCj|d- zH%ZpDDCj*pnkZpn>hrbnS<cS`yIR=p)PuF$^?v57XSw3Ujm5!U0F4DjTR(g~eU7Ed z)Pa2?X^0LXx15)s^W32-!I1&T>W%3B*9@MV&(dp!=jYcknYI*Itg3F)Q?8@gjET~0 zKCdvQ3}LJoFkL;&`s5UDrAX8J2GbF6<b&kX-cwf3`hCZ`$L{^EV3!@CSfdjG`K0*X zS3Xq6C2d72K|YrF!m0;)dS(s@2^H%)O(yY#e?JZkV^9GE9WawiQ5zfct2lJ_9QZ`j z!$#aN$eRo57vGi^qIIcEt<tFJH+%c{9l1Hl>kO~QJ>PCB9{Hce!W0EDa$qT$ViT{Y zue#3~rll5s4^5?8lU^3d61)hP^K3c)x4i(}gpNPPvU2#Dd2b#p%|uQ`mM#LaTE~y= zAINk#9jkO|>5ece`b9Vrih*;!2&Tcdceh@$?)_!EO!YRQ?|G{6_~c*p&V$&=?7-Jr z36qK{q<Z>&qi?OanIr%x5%4FtE+K(sbw-H{=Ab9k&C8Z{$DpUqIr4A#>h+&}|3u<8 zD5di8KsnUokC_}vUR3S0c+_2OF795aN1kE^AYM4N<Nv4n_jw|<kZ7BsqurKd-j#c> zpp*<=&@jpHKioHQCS6`Lt%0{Y7gLYH6cZQoq)j%bR1`~Su(j)f;@*o(S(MJG9g-j; zMgHEAxH!SxW0-kN1rsRdDh$3xlw&ZA!dT?+FSkIy?c?q5b`sS)?^n+b8`|m`YDFZ$ zYyKa8{mbC^{^RS*PyY#d@JGYuWfy*bCYs_B2{y0PgZ#06T|pX5n#%^bi%)`qC{xsk zBy#+w)4w^$^=SNLLIPP&{!9FISY^vE-|=Jz=mGLTV{usJ*CfpNrKVy@CO*bDgGXx2 z^N&36=R$dsHqHM@kBRdt=lEX^Sx)5DA@YxNck)~HDN{J=@t=Jf#v^2TYtq3?l>2Nf z1oM-!#E=JBMD;IOPPU}^kIZp_JxQM<h9ZPUkt$S*+PeCFhtkYd`t<J`NUIe0!fZEw z_0{`Bk?IonzV_yKcVpV~BYQ^^a9zOCNfFl%uWCt2p5||!mYFlsn(EyHFd|X8VWX@x z<~ScE*PrDEsvx$8_b|79r%fb?fi8W4YPQz}ct7JMkFdB`byHX4#mf7Oo#O?MRR-{Q zEVuBkVi4G`zRUk_Vq$^j{6=U?|E7j+0la{X)`IOz#wuXGe78H&h04tJcUNFhP{}U$ ziG$#uET@(Cxk8f)Z6nC=1{9xNfaLW!TAm@m&SoYpEgk&`_j6KG4yLkg_yHF<EBj<j z-`@pvbiBVCLv}<)=5w|Jdf0(lB00<zP05x<>l=g)+?qSOZ2siDuBhPP%(PJ8@I-be zIut0B#8y)dDpY>L!0>16VjNxAJeV3-5>a>0&LPRIY+8Yb4aDD<WK|$1WIXkguQ<#) ziwBA+#aYitmMks5Bc*3b-@TDB$ufn9Ea{ncxuJH$sZcALkC3Kypr%Ar=fRsB<ZTMN z8SiMg+G83lF%@g>s&5wK7j~=f@DKE>?dUj4vt@4!U&=KS1%@}C9tL7&)6<3N5_r{C zaX3?2+8drhWQ(xlrT<679sBsuLi0$DCJRN*z&TpcJxEu*|6PP!6?(@~QJI<;vEAn} zRSh;RUVSbfoQacs*uT4aPqw_WG74l&qWk*#{)wKoceJ%luu=kHSPAg$f|nN<oG>~w z7<ctz1`>_CL2|JfPDLxGu&|jxOjuJB31s$vR)bS!E727&!sBwp0`JF~YWE^q#3n{) z-HX9To41%Y-hpb38$;LqFb3Y{AU%mlMjNBxq_$<)=t&kMn+}JE`@*Hwdj}rPvK$I5 zqT=LFdU;9}htDbSpk_Q}8PPq>THSU_vNp1PdK&m&S?%I<4w<PH#%Exte4<o&(#hwF zc`bU7CiJo-`i8Jb>ldE&Z<K@|xh&a)T92gV38ceFaR%X9G4CP$XRptB!JcekXCFz9 z_=#bBnX!(cXlX*5<paGE?~EIgT`JBK4L;i5B}?%zkZhXEH58i(8<~-Qs+aqspsI5> zt%P)~<@kE7IBbI@0fvBItWZiv5{QP19Bwr;`<0RKz--Aeh)G?CG=a^5j3O(SrYRPz zne-AxL_7A`3l+Wm@$>_8$W)3GjpnO^WDP(vC!=8L;zqZ`|DyBFjzMtC=0uBYOT_)+ zH`?Zq=J?NFq@k!qt`ls+jJfFYkgct<Do!<?aH)pRwNY|uS%;_q7yE7cqkh={zR8OB zxs886(S@nw*;qD*EPVvFV3y0v1wHjm_tb<-PEJz>vpRGI5{N)K)s!9;7Q=XkBsG0I zsn<B?PZv+;T_v$aUrL{k`5IMDeheF?L7$kk&XA!8RnYm_c`eHH2v{D~n8EUs3#Nf_ zWFt<5Gj#ZBR$cP3k4~5>c1$Ki#bj~Jp@Y8R(7~aubd!yZoig=kq||6591_|FLo>v{ zXmVMtjoO=a7C52{9PYiJ<k<Kf=xcdY7%Yk73hb;phPv!p8)ps3PZ<~`j#gm3|CaC# zXzRyx*ZX;Anm&}4k}xd!-rNjl4>F8fae~!jNb})ng+Q>Fa-LH6YD;HL*=>+HE<+P! zU02Pz_{Mk%hIPZvUQAKVn0!mgA4i!K_wBz1IaV~4_MuFc39aYA!H<hY|4$s1c)rf; z3b)1g<0UmYMe{+~vY|Z_OP?Q$p>S?7%3l-mU-fIHGa;s$2@{(MqdR(_ssZmG#o@%_ z?X&|jc3-v0tWDy$D%~I0&w8%|`J%}DxObQ*kSiTm4MJCPzS02mDCmAnP~0|G9K^#b zIEb6BtCKl4#O%AxO{c-xXb~0O3(i~r<F*gAk7PIZ+fEcHg7H7y;nS@r+4fGYeti@E zVcfP>{eVZ(@R9K4dXl^n{%FKz6mA1Hi;U(=HvD3eZ~<)#zPA@26Y(_@I|V)mjJ=5R zT#6%S7T%WrqrAmfxU<OrchN6JM3M|XDJd?zzP!#71oHQ^b@n#%aq)LI_X7shZ2ZrT zAJ791t93O)v1F=C8O+lnwab!bpxnLdOKXo~>kngb5_b`3>&S7Roygvqs;9fEOrj2K z`U60&y=oZm%l)8(Eo`wTY@HN!2q>MEqMdU^MQ|J3<Hsc8V+<<rS5I`ksn>~22HS?P zq<s?6wlHe=tnHL~f}B~>+LzdGA5R>elzmia-peO=4GcRlkW=H;sJwZTm>A~KBi_U2 z_kp;Uu~(yrUY*5zgloj*k}6%UCqWjSt8{u;a2x<_rO6N1Pvg|K8ayV1KR=Y#;~Zuu zv|k4!RPO^NBKt6KJ;^p3^4CWGvM;sD@`n29i&9c<RbM|G+%C9EgeHGH2(3!ho_G_s z^WKo}*T;ndo-a$yF)}KCE5N7-nstb9N7`Ip`9&mFDxU+Dg2Hp||G+qt>3n%Ha@*PD zxuj$)IEY~Ev5Frio^bN%jNotQ!?Sk?=6ObWrm(><<7WV2O5$#7>LH=6!#8@R!^_9s zTZuyyI|nEGEH(8Hc}ZFW#*m=l`u^6|7d6aV9Il)?B?X-Lrak{+<`ZN~rSC8sCkK#e z^<WFU&vx-O5S9|fTW%N)49IoybX?&z+gkdi+Wa8h|FH6VyR;!pvx}lMpWNFC+$dN; z0P-ko`y3IeVH3ss7GK>FYl1UHQsz*YR%_=YR|BKJoX~Ov9?OMzn78-vh*ND;bpn>( zUtquBQ-*>&<99oxBW5kdN5#u?)n61sn1UOKH(3J2eP$WBN=xTgR&QfSQn%I~9=2v0 z;3sY(baOfcsd$a5Dtu<!1{r4^Bnb?0G9{k19UH`*u~~7HTqa7E8Qk`8N7ynj?BcxP zMz$a~gLdcl=$dSuuhWn&Rw+687lDqUN@=<Hu$AD(sKXeVcx~vwdn8Bnk<j&p^{>%O zPY_fheYBDTEI^J9Q&N%FA7m<xEccwY*w|$@B<%Th!2LTqbRxv+VFDl+3!3_)I&jxg zZCu(>a~Nl+%hRK(6KAKr<tdM-*QVg>mV$=?M6E(h%v_=m$`#(T(w-QNi1wJW$p!l% zuGw`j8)B{;Z1#9mb4H}fzvaUz=lg`-+$)3wu@Z+&GLWzy3nRy~%S7(i#S_zwa+M>{ zni^4`GZ7_8(4D9JZ;{$G+mAIrorDzA?s_hWOu?Hb?EiN8x>LiwzX@Df>%79h-xYP4 zFWpyVh+-6B=(qj|Mz2$I0OcK@QaGNzV{nXTAw1gVA)wz)+8`^y?7iuF3eahm<#B5) z(O`zDly_Fp*95Qjx40WcDq}(%rxGdR$Xq(E=9qH9zh_q#>Dwd<SZH3MYpJT{l_|D# z1^sdnpDZQ9FrS~~A(yv`&=NFZnp|C_=#Wa)`5sGRy<IJhJHuT_S~V&3g@L=9lMHd& zyz{OJeUgigF8Y>yGL;_o4nL2+7d;`bl>Q4vgO1-2hR~Z=zuOMfR6K2zBNr2g1_Cs` zd`h!q3^h<O?!&-{;K!KUDgEyIiJF5uJVLD};_&{U@3Kz~rBzL>_g2JxMC<e<NnKtD zdBpFjvm3QX34$4y`~50b@bT07NbrUa!LCAx<w{eU*1$=l%Iv|Xbq`yL!;SdKg9p({ zr|8g%$)Kmo8@`k;Blk+HT7NzeEv-`D$-qqXNddPRP{b@*C^*#$mFiE15=Q0iF$sqR zyO63s5;j8)n0kLR!XM&eY$ugk5<bip!QchX^qI;Pi9|cTFK*HKSl)2`kW*GkfZZh9 zGyZS<WWH*BXCaYkg6+$4=<Dj{!-Oe@=$cIa-*m;c9&u>xclSZ(_oD#;*r-9^LmDY! zQaq0D@3`Iy8oWJf_G7N&<FlMk!SiO#dAltRl7O9mIPxNFOvpJD$Uq_o)pI)$*UPvk zaW*z1z^DaP)mn2+m!X6^+e@eJ*!Ki8ngv%b9*b#nO#+Bj1H-x)e{Xv~H_(;qSss`< zFOXRDOe}8pjHxXx9*PlH!o)au7-ttR?D-_lLFN8eKP}tii9RmKNaAE?!%KokLO}cJ zL8j%A^4P`MB@Jy*_-Gy}lm7brw9-Qt`85tX##&)3vj%(~W=um?IN89wM@A>nPW_78 zNaRbhf4jSce(ts4pR3^4kz9uP9MG#TjERNHpc8#X-l*#saiUAqDsnMBw8j1T_^D$s zR@-7cZ91E({%=hFaz<WTf#;ey=|qYab35Wd=ax^ripn@Dt?ze;8WMvinw_<eqm<4= z2j^)d;}5lBG6&QJ;modxrjRQpi$#?~z8-WQsvzrCowuu|uO{|yDwdovbzgT&)Ot-% zUt0uE2t6&8{N?EQ+V%L_X7@RgA0Z^E8Q2Yn&J1RK+^?((rSI|l`Q?oiE>=WBIsB~? z%V9spY7CB0bT32ESkI4@b8$>4Cg!?lewLV_xA+n<EgR0=f1e_~kuU$P5h^}|s3@q= zF;vhS{Qz0AC%XNDAKMJgMNiHz_D5GMPvdJ&e<lh-x`u=|huTW<F{^$biBd6S?!r1a ztTm*Hq9Y@NMIG&GFvN*4%F5ee?nc>lGBBk54f-OPyItyHL=|KN%y#oX0{tIa>=3j? zKcTAEJtw`*JoV<aFXGc@<%qj3VqB_=qLzpLx1hBEl1q-(P*#>lN-eZk_Yfk(ajAy? z?DO#}Rf>4<DuvNEyp=k?E|El)PC+|L)8R`0IgJ4ckV##1KDUWUPreqI6qi9G8=qp? z4m%9J&y*8+EC!)-vXU>}_jF{-rNGlBgwW}z;9(Fa2;3bqP`8rjlCQOZM%bf-Ayd&@ zu8@k%Q+T-m0zvtz0=(zHj@sCx5?)Hsvg%(mA8Jw3*TFvcgccq%m3?x0lBxFBGGqw* zC%&{;&?6%Ebu&R`8Zm#{ZhSw0BhdJ5|L?nc9fB4n)MI<AGx@)qz0qCgRg9oh-2ZHM zOieh%C4klCt^+7$N<M7j9t>J)e3GN<%qGtfYkvAB*;>s^E&nkZk*<nYlfeBRTy2w+ zo3s3y>A13>*M<q!)dCD2E*_v(Q75Y>&<p4cVkR4s4RB{z1zpI=DGs?s1i&ZYg;`Hv zR?)o-T(bW+0DSXo@M`v@HYgARPRjG|YocSBYN}kXemZk>UTybSwz2@*Pp?Vq{T5MP zfEHO^d&F)3_<=e&ATgP*qq;#=O*)h2P|Mrg0@x5nE&8$8PZ=N4wD>J~%y}fZuP+a_ zkwx&pww<??_%;8Lzrai!lK)!3N`=pAI?3K;RF;(3`fDm%if{ju<eM)&it+@pbNm0I zux*$Xwml}etX5B!o5cS0{g>gzgRk=6fw{(ct_CD2l|Uc$`wfAT=zH$6>8WUfx&b@D zU0_7rDYg7LlE*h~#H2#utJEJ9epvdpFjF!CQm!*;^+>=Kpnc0o&d?vVR@0nSKOK*s zz8hlGeK^936<GlFT`VHBu_$;*wwB@5SHe-g2OgGdCVi8!roP?fKUw5V?U(Fju)s)d z#?xHHMaDZwMp~VTZDmkbp3%d?R*;GA@R?owXz@p^wgF}=$@@#qd6$yxlaAGgq+-W* z#FDrT4YH-9rp0~xZtgD3V|*I}HyIIy5Y|kVoa2-1YOJYg>k#J^^l9#L84uar*dO`< zwznS8OoxOb`+;}8Dn-&A)Y;O>4K&?If0?cmmvv1ioL$Z#FgtA8{Fh<R`NX!CSei=q zhM7WgAyvWw`U=86EK@qfLi@W;^&!e|%<K`@N50sLjMvT^nF_GSwOH5ZHPo|(xyav| zSr-gzQ;MK2newzupQw?4T=b9Qx$ZxrV;NJ$e$yW+BH=GP-<z#n4SVn1u|JAzAuzhB zAfxGi+7KY)nZ{(9^v?dbWN8%R1l8=J7fp`}2UZ@pl2*jdwRek<*?(`Jqf2lD_3wqJ zI$koI^_0{RmI!v92Mu>L*;jAazDRo*Xue^>*%%a$4TaJ!>7mmfMFgtQB{%7_@M&Fn zMRqx+(trK((sO#9e(GacWC9l>+YSp&G(qmYk{d60Y9nWJyRbkf0BB|2ZGVZloGqje z>zyF(;gd2R`a_wW5}qVvK{*SeqGIoo9wcwGMX#ydQ6FCa;i@_$S~=GHrS!&Q6TfKG zf_HOAE%O=U^C3(g8_!6KR!`I(zl{(}ci#s{#pj-I+0r+%GgEF*5?eYs+bwT|YVtSy zfx+Rp4>Ny%p0-NyJu9%>!hUWJ2zlFF64om37_Rt@=w2pVezljI7)?rjIb|u!<QySC zmoY}~hYw~5HQ!P!Q^G2^#_9NW5E{ymeumd$LwcN*^Yzk0#T4i0H{ItR60kSqU3s!b zSfHKc_bZ<#&ZoUoFfWPZFehayn1e|R=k3r!Z8BO@!X-`v!13>TTJz6h%*vvp5^wdz zZ@)in1J)YT^Or2&=7>9Daf(Yztu5>my<2tjwE2YR_6OqfCnq*Za%bWGKSJvsGmk#A zD12ne&cb7GgRw-mat<QPlB4c>0cUJJjc4K5`__lC;?@R&ZErEAV|shj@oTf5r2UvH zNJln`OmNr-S})HeGlv#@s}e_%f`9LhWr11}Y~cA8ZlLVy;ERka)lSA2QI9i*4!gWJ z=NbM8%G36V@g$9vGCQpN+11hE?`{wa#(Aw7tCSN_IYro*8CTM?wzf4rz0=nhYa16U z;s3a@9kM3|-R>j&YnZd%4w^wz(Ssjv8kUhQ8>UansuPe7zH^QHKp{SbILf%qsUY8_ z2T2Ti6zp<^QYwRTis)t%6w57gQIl2^0YOeq7H)1Pzp)guV`?LZ(rc4rQkE<9uZeTB zGleDF8rzz9MR*#U>#LjETs+D+6V9t1$2zxX>JT#rz^7&DhM%YjzRs`k2gqK`SPUM8 z7KI+M&Ywv(pOyNfcD=HCx82=_{}D&gMBw7y8r8yRQAxJ>%q@N^{!TsEq!Hb;vQqH! z3<Yf|deYagDgE1O=e?<2vSZQ;K9-wAnx#A==+Tqh(OI*z!NFGq8&3)u2t#F#G<+zS zm`=)i8;Qt1DVFqG!8SK91_m<z_-R3@Yxvn?2m2G}P5rNT4hop!bW>7P*P&C~v4%#% zQAv_k8iCC>;QghAp+Dsri|JV$UFMb^wIBURmszHOAjyvlsN!V-lX~D0fLD)QlBJRe z1S9UQ{DH;K3t)fp5(>y%V#wvExvrvlKm!3{?TwDFm6e083#d@1XAk2OK++i^xb}+~ zQCBxHKhGpTNF^Qswt%&|gDsDd152xhJ|_MMFW#HS3CY`Q0L~Efkosiq<FE(uSqns* zG(ELFopv>B2Hr1s?VewpZ~j0cLuY4`J33Ge4SQr{ndAViqISdE=SDzKd9H;g;2K&2 z0Mp!ePJB8q&Z97ZL134Ti{0_HO1kZ;fW2iyvP@tR3CLIHm>LmNkaPu{Ri?H5m!Vne za57|=_!4wug3a(v(apQv<LJ8UmgwoX5#zewNbrKd)($X>0cYY{z&38_LS&ycivi5J z3&F>kr%OpxH*S!>o0Ue$V!-+SCXniNaB1h*1^U4kWb02?PZx1dp^&dv16Kgo^YQY> z&7SpeDQt=;4pT@<?;H6i9O~Lh$2uhp&G8{x43ywHSW`Z7)E4C-JNK$PBZQ~DJ&i|L zm|OIya9`0ydBwxr`&|w>S#Da6$ik{<hquJ$q^tX}ZH~_`xa!xvS3JKrYwbVt*qfP+ zTkS6L?v01SVEtobP9Py+;S=r;H?greJ39;KlUm46$*<4(TjdW;l`Gc+!~udtMs_Z+ zM6xIeES6@>`gyvF@d)@iSuS*zR<$>9FEbp=@Qw7|E#<AQ%^lwA1(sFsA~zRZ&${9f z@ec2@QlD}p10|aHeCmDp#3ef(Jp<gl+*};09`)<tB?(&-`{!w>AGqOz82eKfZyiFz zOE{)V6xsz+LKmN?9D=Sb{Zm%M1B7jIvJkrz4u^-8_U}mXsAXuaJ`jK8eepcu75f)@ zxnFsOPjYdA8;R1KezkPRm{T+vNsbZ=I1+l;VJu;actD**YkpF@=@18WHijHc2VLsl z`@?l3!%$j!0siw#4ppG4jv)VBmYX}&>-*%)lVz7K|3K%uRvXC0<Y9er@l1`!bC)q} zmwCS<jziSQ=6L15(+)AeQ>^>!oAr*CMxR;J4ec0vM=z%q4wA-rKmxQ~ThAhQ$n65V zRX4d@#e^3mH)zijvtDi;uOwRsG^o7-j5~W5r!gy+8JzUo<c%K+dn2h6Ao%0`SvT-A zb+sGgu;AIa@yYCQ&dPBq&_a4`r*6F|ohqt4fNiBQ3UYdQ>fLpz+*KIzul*2SShu|J zEcy5L>sH}OtJxfq)|h>G`_sW*E|9<oIO{#*U}p<@?6<)^O3md^Tg%E=KN-uuL+#jg zNUD%!&%KsiHDJ^Eqx`+6xMfc39?P#FtMsJOlv4oo3ATg)c&qo$rb?@LxGl1Mc!JG^ zZ7rQhV9Pb0|K70c$}nl8Nt?8XG3yNIpaq>{1pRd?W19`SIeW|&e#<%2Qxk{<AKPje zKs?mim2(?@G=aMwj%f7#Y&`FJLY<97UJdav*^M*f5-6i2`g_>av&x~fBf8#0fHIEp zbZ3e>8ao*~3*2i%nFV<}VcZ^OH?0YSU2oyHUdFGN$wpGz_d>(HD8Hyos<7jA_G9KF z2PN<90$YsRb9iK_HxHz6#1pKqZqkpu6j$5j?d0oudjESv?NOE-)D|v2{7XyOe=9*H z9{x-EpoiYSwvg?OzR{RTfS2^LaZi(A)3NUdeQ_7(OG=5r!knXmajL)#p^sz*J3Mt_ zJ6#p<63<3mxw`vV1^ML`qa~QaJFu&Fj}*Y^C>!Mr+Uc%Xd@mgNyFZcL*w5|18E$Rc z{e)2h5F@2c8XDeTLKg4RqTsJ1DFzU~@i1)K2(^|J|DVH}GTMK>)HF++lQX@!{2Es9 zS=wWi<U8Nhdx=!bAG;ad%e-PXA=pF~AGkO^;^$TVih+l?=M>;YCp>HKH^392+WJO_ zW3Hy$!U4-ilg+Yh07r!VIr%jqaX<QwnG1*c>$~wkgmR(5dHc^q-uPN7jsz9#C&{Ea zFG3Xl4+25`z8(hzE+J$MO{OE4-Cp}R9-a8>Ti>?@V;5CRx+ZtKw>iBjJx+_9C!VCi z5g{od>EcO(qJLv;onOSWu1jZg5|2?vJOAUh=N)rq4Q`p_1#U|+vj9lJSrmc^dUIS0 zkX`h<DJ2C*%yftvKqlk*ntC%-AAiF}6(03z733DfN&D&-Uwnaw=Q6+_;<{Yb%6}cj z+s%$_@`-`P{FG*xb#27-rwj35k2!i+(Xv9D8vy6Ijp#||iDrm1o-e!wbSg!@<>NeZ z1vpP6)<eWbgS>GYk)eO|KmHHg`1Y{)5C7qRm3d-Ady8LNT#zIhBE<mCU0sOac?sv@ zbaL$|ED3U_i<7$oNIDXgM3B-}XHviIkx9yoQWb@YAo^pjnJt8n`0=P_Rx&Y=ypkb< zaJwY6bhZbQ|IR(3&?wUpv9C!z5e()JeE#JZAN}B$a_hhkSWN6FDZvhODIE4I1OalG zZ=#@6N!i-0?eBf>dt$-BXI;<E>q&*l0iM&3UnT*cqcG+`;ypU5Jr^4Xcxd8zPXBxF zy%%Dax=4|Br?(VF_WHrV6=FwCZEe+Aj86NMDB90OWRm2~e|b*N9VO+%JkB;>90p=> zY8#I0vowkrn<&(`)({FM*mxet7H5k)>%Hl4{;m`&wh7@#j;hd=G}hTQnnJe+wYaKL zZk`t^Fzu3~Q~O13bfW??xt^VH7vp?@+yTxZPXujGV75NWZWK?8Y39_LpL<zTmCI{6 zYL6yEx*fP3!B5VP9oHOxd+VF^Q#7}Kt;fSJAC}|1NS%JTSTQ!h1{bx%Iw#=rma>O* zVU|NJjS$`1x}CM#8<kytC?ROKl336s6T;&!zWlsx9Q8gYqY(N{htk3ZXrmvLS2v4i z7xjAN+3ETI!JdQ0`NdgpWApgrjpKZ8b7MT3Os^ccS1<b)rzdC2D@*qtK6rKfX5so~ zXMb<;W_EIZwzj--`0&AWG`<|xPnx0cZf)n?fO@BGW%c6n(nP|{pQ_DgUq1NW_ntj} zuCSa;&C|=HBlP`)gYB(N7t6tA-!aa?yS}KfUO%hgvE&e6U*cU`b)y@MhFVv_@o?O; zoVRveKdvSoO;dB%+uC^Z>e#i!h2-$Ty}g}%`04T4MgQDVGmk34aaT>bdP%Y4{_gI+ z1%aX}RDv~u{`J>SA3b_#->}jS@893w+vE9YIJEJ9^0S});8%WS(C;6goV@e)+v0lt z>Q!wl+wK_kB86vF=G3Y*5g^;T`GuHG^jcQ!jcWzq8SkN@cr0F1quNcDImM=nGumzz zZnn0!vmtJ6ZpI&FM6V3Xp<PDZtk(|&)KNq2nrr5q#UZ@1|7a=X44|Ca(%e3kgr|IM z^H;y+kiW;+K7#Dh)&5fNg+pZC>Dk?@vjR^<VQ<QJDP3OA&d+x^X%F;|YWn0<dAC2> zsW7&;cU`@#Vq1~Nmcxc|C2v`{1Y$&SJ+mt7@_RE~xUT=X0^jiJdcg(r?Z<C_^7$v< z`_A`1`{J`l_a6<$gNxIPdKqP{J}F=ySYNj*TALSiS{L-gUF}?h&(AOI3@*c?QGNTX zzJIu~?#jBkVJF;p`TWSG>z%jWeRJ~qt;cVF@$~112loe~zO|nVurrhB-Oe{wH)cz- ztML`<D{6gh`Si`{>c%QRdHC?~p`*{y(d$@OSN14Ti&u4t?%A`iEcf@`dk6mF#WUVM zdh~!}FOOcl^Y*)gVgKu|p51?NIJ;RmdiAn?@Wg&(m$SdgWqnt}NvHmff_Up8=1kUh zZxadk+_D3r<2u;e%X@%tULWIAX$}^AlV`p;;;MhX$vMi!#hF74`qtKt9ByrIeDTHS zuI^8te)0bM-}|5c=l{?5zyFaOK7alazjY*sGI@A-U|%Jx_?3{l%64tKQ&)fVM}MS} zf!)S#spi#%vj6()=jWG~+r6!aPaa)Qu0H?r=jSJ9YrXY%p1kb|guc45_Vt%v{q&QM z;lKQYk31+p`Q#HDntLg2_CwX0Rb%z3ZIl?Ip92<ko{4s5NfJBXi2vj#Klw|4=`V5b z(@#IO9J2aeAHCY$+I6d>lNIaq{rBJZban<{H!saQ8lre2(^(<*Hq1WFqRt|+z}XdY z+S)zZw`1sJ*ZzaSq7yqHNJ=;S*y!;<0oeAo>(xxFY;AdcFz!!=)76cY-rDBk%EI}{ z#m3h9^1{k!I-FfCtgJ6D-Yku;Mp91|H|U{(awhB~rUQ`=h*|aRX>cvuhO7b<BEZfd zy2v8l1r!yRV-72{6{S6`Xy89V;t;AKH9;5W_3iBTtPMYa(-waqx`_OYtC(5w^j>Oz z`@=r(%Hbm6i2$z`xo&28vDISFT+F4~yOgvE5K)VWVpI!9Ieu03nc@@zC-G;q)z$KW zSBUYM0~+FhI4KMY1CcD}$#ULQl9B{1o=_-c3qNNZCUw<J48;WTXV0Gh>aYGPy3$ps zc4;f<gAYDntI~0Mcmo_DWdll3=*c-*b%nE>ZNO+I3t)ra1#IZth%=ZeL8Jjimj+8o zwaYDWON0LeV^m8#Y@~=ZJHH6%lwgx3A}T>d#90&t3TWXJP;L~Z(@!(mE+X2j2t1ad zQHw&0nFeg=QUO6UHPMq%8UX#K0|V$NX+6krRxLFkO9SS7_!&=#l9SJ$o}8R97F$Lk ze3Kuz=?iB{3vT6}ot)y~9zD#VXHHqsHH1!<HuMY;HzZM7dDF^al7<a`<_jkt`;W{R zRfjyWQ{l0pbvq=YQ3!E)vyKQx2@22g!|_1aqFEc|Ks71@JGKzGhmx$Ku!{{{S2%_U z9_${()%rwLCgOIP)9(aO`rFqu67SLTmkEazl_v9Nr}a5}K;i!WJym3Hx2q@59!ZeS z4JvizN655^3qqDTf@b9Z@Q?nxviq%J@xT7B|M%()#<sS@JtoEJ)~=H37s={RBh^P{ zuBJEI<t2~pdJn+Sp}s3sn@bh0P2lc@L?G?0bGIyAwI~40cCMOuRl;1Nt<1I^M3CB+ z!}*4V4M@IJ>Z$<Q#0Hlm7ZP0+AXzdlJ8}f~$ho?%HGDTZc_f18`Sa(dnG%<Z?|%2Y zMx8?`p(++J$9mRepb~PsnCnn@TWUDF?b2n*jaSPMJxqAwvNE02Yp7Y$iMlDPFXa;C zGl~|Z%cXmV`)jKkm;Lk6a8f_<w7llXczH3%5w?AAdNHj&k+{u0KwBOL(g-&c%^77E zUCZ;(AuZ*#65_yJm@U=`%%w#YX32@#&Te@)H;^LE1Uhl}>hfxDWkdZsUN5gK^8e!U zOwH`<ZsnV+Do2}lT~L6@t?R0L;q3)DmtI#$1!BKyWg=<ZHWBqDx|z7!J4b@(=#HT+ zR;i%Q;<wqAEc&E=ETgKo`=}&bZTB|U;VuCDL|<R)m4~aVN<zHCbPj7roca)mtO^tG zM#ypt(X}_ECX)>aB7Qu{s@UMvX7<;6^-P76G9;7qn6H=ldyH*=BnU{c<8<zL=_2P~ zDqhz|u@CE~ZYu-YyIJ!8i~h)TaoeMX6_sg4C}v$2spTHJDrMS*|GOW2Z#b#faVXMe zYqnlUVSr0GK?vZ`tJkloa!zdTuUI2D4&P2(4$Uqk0^QrQfh?S!9-D>T-TEs*j_u4P z6|7JWxP(Y2oZ9kUxh}1k_pD_MMoomY5Ck-!>uSXX5Fg%uARKX3IPJ5_q{wF0Bo?!v zB$j?>;)jp!kH^lbQm685ICwU8cD7GX&$hR>TuZrg@8031^){%#UGe7Vm4}e%c6PS1 zn~B|CCmOTh1m$_h=ek;K)t9>4=U3~v#+<gcqc)Yi;*S<xuz+vd+nX<rUb=o{|7696 z<htVVI+-Z-I*->XtS<>)U0&AGJJ_o)-Pyb3O*q1&ie^?s8el>zIf#ZZ=yq)&DXId_ zhY#CRM{aZ5cQtfU^l;S<F8e2Er(3<v;dtb!kRPY9qC6FZV3wKSObnr<Yp12(R3fs% z851<T?7#O;9UM{6<4;Ce=aNTe4o14@W?$@l!-j~>s4hW65ENxVP=>QY-+AltvuDqk zqKXo3cv5`-```cZkAIBw(W6Hmy_}?wI1w>o&SuU8Fcd@BI%cxUUMsg^PkuZ+%-g!9 zys>`#`b~Wvti98<>J-#o*1@^Ez4h<@;P-y;%fBqqfBZ*(^t}&0c=Gu1C!c=WQ^ux= zEmLdy9NOBE#a6<4e)dU*X;V>f2d}+@{mqS@Sr`q5P9E%9F`g8*g|p+6uU|aBnO^N4 z?B}nDPe<eWdfS~pUZ{1AuPg2O>Ej0vkIzmY-GA`2&pv(o@srh!b<Y*LNS$3?*du$} zTRb~CKf4-FJZJ2z)~!RITCCl+etP{L%HnL+cfK49&Mq!qA054X_2xHz<3A9o!rj^3 z-R$*5$6u?(!|&zMkx1{maBgp3_WN+T^;A^PllJp+8>?&i`@ow!+x_#4t=%2;i$Q;D zqvy<VJ(==wY2jwW{xF*zpPt$g+`rxSCRbN>qlb?lTUtEfrwz9j(s+Ehf4_c8b765X z8p@>e<=V<>`?Zbf`Q?TA+P`<81}+Evmeqx&)kXW1a^jnkFyrdkq}v0tO{p<>_7g)& zk^h$blP8a?;-^o)u#>&}?%RXG$jZ(BkiEjrr`k@BkL?LmsXEKED>?N>Cpw)eMViZW z`&c6cGdc#=jdBb<6w3{Bm5r4(bu%nk{9&eCsly@Y+B-=7(aQQy14KdL)aH2<D=I%G zJjY#taY_P!#5#EWy8iGIgl}3nAd;08%?w3Kms%bo%CoKjjW$j7`#pvrM)7OujGz`9 z{-`RbUwW?j!cU6B*zilTK@_7XlmLSLVeQN)ofOk7+AgxObQy~t?JsypFk595qU$0W z0-huJ5)E);v4P0UlP6Eu;tZEaVWXA_;IO8PPD%VkB<p-dCosfH(_LAmFd0q=aS4TT zf?66<tDzV|F@q-5Zk&SwpGieOh}{5lbpC0eCp%$Rx0oXy20%~OV$kxu1{#E(kILsU zjVFkBDUUWHG;7g8!Us_jK-UrnhJ=&cB3j?kgC}~zZ`I2Nga``$<%LB%Wc{dGTjuhQ zpFdq@JYq7rM6_^}*-d4*c~n3)kg@@YTFyiX=qk!khl`gFMnhy2ogN#z44b|>=(fx- z=Sj*3%y>Xoa%4S;=)r@5QJTrxN$?m2@zxMFAX1~LUObdQSjR(_@`O)6oMUV46BaGR zdW}4Y|8S2sk3Zdo_9{e%Cc}Cai4}TWs_{(5SMmm|vR<$L){GV54lK;}B2m5O&ONdO z+0q5kpI9=>e5U08^pF30Jl`G`|C|5jA13L{Xy^E}K3mTf{+L1SZL!T>zkY)(pSDN) z21;$V*H;f8JZ>dqM^lBeY!Ozr9g9)W?PJ~hFet(njKHLf-V_RX2jxmuJ18R>#RJT> zuyv)+P|ZkN+u7jE6EG?}LYOVo>peydVWXdNqlP3DCEEv3e-1-Dxi~v_!ZTs<N*jb) z2w5%n=!x1KwsaXXsx+xWx2@zaix5mczxwK{d-v<7Q0oPO+cg7Wod&0BIHbmI&%_LQ ze$y$#{l07Y*rrFwWij6_w%3Ky(#CAvNaY_wIc<rK!UT>2Vw!R=9#*8>Lk}B=yPSuP zp;WUmyII?;KSU8A-sOQ64u=_q1`JYB$0e#3SJu|+C*7y*Zxy;~o}FH}%sZ}i-{q@s za9>S5B&fA_<vPbrUNmRRWijPyr=n2m-J-fF)s@dER7EKtqr1ENq0mDc9?9U{-sbM4 zzHA~!b>dOsOfdhxx0=L{jvqx)xIW9L7zHAtEW*sMby(?ZAks=}OJIg%1HbAunt9AS z#)xp7>NfK-7}RgNLYT*i2f~EC07FL%j|)4U8||V#o($zpR^hU@yyTcIJFEE{G4(=~ z>@6%hIa87+3Jo0St@p<5g(q}v{E3s6@^CV8uq9~iR$(lzTrX5fL>3PzIG0j39NS#o zTwGZ0PcLNN#g9Mrb3s$9*j~Tk6zf66TOrn`XD9X6M~Z}6dT8Uo_GZ0vezQ>fGRoRg z?Xyg;F4PTwGOLfSk+QCr7nadi7Od_WKe1i4S63<7Si~&j^O~dwBs5(_Nzk=slmCm0 z`oogyq%J7!eLPbH=d-hZt8UY0FZM8Cz5cM|!~OfGm#6Y9^Zm=AdbSJJ7w7Ih7z{7f z_R{jga4<Hy*{ds=JZSl*<`f2vwy*N}_9zC=F2^^U*sx!pPP7DVey+PNH;&E@$~!xI z4$Y^h^+OS|>N%l4dAqP!Kio=#r-<FghW68+{`A8SKNK&WOvrW;4i6+PE$~`bIJHhf z918;nSXF@ppFFDXcZ|h09ONP-IWA`hyL(dPinYGk)4Dz_wr>n_peCaoSY=q?nF1GS zbH`$>y;e@;!%cm_zMdR^>VYR$a6vtO{5V+xBJxNQED9%?Kmoe-TE@eNrj=<%V+g0k z{{H*#vyNGe6k3U{#B#-fdO4<jd&SZ=q-(d}9-xy5RS-NhaY;@@!CNI{vMeh}dvkJ} zpHVz|@zOQ;(SwJx#f5xLU@{szVc%R`TbUwt>2e?wjC<bc*_jLB?%v*or~cmF>sPOw zmCQ;dqCIFOP8_o~iL>^#7Wtnw4kwRMf3SD&z~y!@9=RN%)VuQ=y^HgD6~<LO*SY+5 zv5U93_|R&(F68!x{>A0V+41&Py{WFST>@PTak@z3tY1uBUE#9}w!`Aq&NkW0!R6l0 zE>7C$$%R~WC@%cHt<A08rpte?{l$K=Vs{<3o?K!l*H_!U&F#Hi7uPqZCp}(W*P+v8 zdu@5e6&;TqtR4gP(V+!iY4c8CUR=lzJMoaW_W1mC+3HID0BIfjZm#o#n*4XI72~Tn zukGu+B1=!A-rCr9XG1?YyoUmJPTAbvl8w^V{!%?{^w(?QSJQ=Me%19ra#f&R$aJV2 zUARgxq?-a(Ef$XFwS8bT9*D_4V3&sXHny@?<iqXtDT9U!mWI@Jw82wvDx5+@6m%sG zx7LEB@|jkaoKcFT!rU!7z3a(0FUV>wNq!PE8qmFqFjOz5Hyl4;4#ZDoFKUYg1%pVH zN6lOdAA}k3A3rce))23BS6Au<CbFW_N>}hC7LQmWPNd}9yHBxh6pzv1L<9nt0WA@f z?Oy#H5q=CbBXU3#R;zC3Cp>Kx&uz|W#z}-%T%shljKYh#eOD_FZmPObZor91H9c{_ zkgg#|LHiH2wlYI`nUZ^P1{;NNVRo4@N`uklpU&)5v~_em+C155K(}jY;VAJcLB(N1 zAPzfa*$lBcl*XC(fPn}E4?#c>{-;4`RPiLi#!rGEQlVf#(Gp=L0B0re>eZ`z_wJdU zm?ni^AokTxFnWyQ5fmP#qbK@-8V~}n5b?;i7JaP_edP>JV6-}|o4QK&bTOm%2P1nI z3ZqP*a7NkFuk5MSHL3-+{q_28%iM>!3P`0}mTqSX9fgKW0r#|t0xknuKwC;8QcOoA z1<WYADSP?yrAIA_>{&7diMV0r`HN0Aj*-n~6~{sc@@Z7YVko&qp$BwIv~Yk^5(XFb z`@yr@KNjVw6z~Y+n+F`udQ>$?GH|L=Jm%EsbW+7^RA?NN)r*Vz0x)qkc{8oo1prR~ zspfJiNqG=S?U^|K{F!|R_`m%>{<oCExTx*$davwuUO~Kp#J^+#!0~c%d#`?(M)5S7 zLa%GEK@=efM?K~O3^yR@qyqGqjDYYc#{kf8?bhEdkTML)0z+~^7A0QYtsx@$2n4!O zdJG|A*5W}o8R+T;rOIfrUQAUBm@F~@YvCwxVsb$XjhxdS+^aX%C>Oq#+rc?zr?dCL zX-2mR)=MC>T4pRJU7f4K=^O*-fk%%YW0oWrv$mtwM+(o+PuuJ7La3IHGAvKRksL<> zfQmc5(L)I&01u!$OrT&+0#Qo%_F=#`t!qX_+b+P%D{B+JI~=s15UY3pU1679Zm%59 z>WJo4baU-M17BKRzqlGZF6SL!k9-eTIHfhI?KoCfweF*sNbN64aF%y>Tlv;<s-v`+ z>VuWJ1vQykn;ovz^^fy#HkKFMtCm%zSjbl{8q9Uw!kpRw9skP0>U1_)TU?(mOyDT( z&w)|9=x|!wz|yQfLb<Rwx*DynIBBk2&FZBe(pd|cqo&(YpsuOnjknz6cU@O+W-{#f zMb*{Kv^;L_@)w63nLyj|Rh2p^bENHNO*sY6P!~nMbFO@}K;YQ4@S52s8_-plZW#5U z4r{Zb;(FaSCsz~1w(l`eN%jwqTj<S#gYL*tk*q7<>caAPHg!qc+1{&lB0mCY8>yVI ze|23uIJGo5N3+WZfnL{-sjQ$le4yCoc<2$ezjbeXGp?(?0;2q8sL&i7ZKJ6f^@Ac$ zDse*{I<&U$ms%+@Z`H8iX(A>0FsCHBQkFkUE7no_wqc#>c*3F`0B$eNZOZboDFb^q zm+TTQg2VQO1rH=?v_OFU9j7)ag&^V|k36mGM~N(acc%vr9(dk+deQH?g@@Ycq1iJ4 zvb$Z+1|o2qMmrP@@o1&Z5JRjpMCA4BS9|+APoIAA(MKQQ|M|~<?y_gk$#*7YQdLj_ zc$I>&3)MW|PCX(Xt><V$U>ZLU;WDtlRUeb%o0A`eCx9pREBhNtPG-mLdxP~coJsv` z3~^yHK^uO);h|q!IUEj?ANP&=3!n8pWGtRLo(P;#%+4A062QOuSO5Aqe&gS_%bCH^ zX!7*w(+7w3E0oa&M5GIT_`@H%_In}<M+OAQVfbgCefGcp3xEF0&%d-!tu3#e_s=(0 zH~#TI{l~xgmw$5=wz`4-^yg3SJ-GMc>lY6m9M;QTi?bD1A-h^zhNHoFI367A-COUi zU7TI!4+YhS?YDL>2M&?FXV1PmJbd7}{OPBktGf5zdw)D0zWeTX&|UWPNrC6jzt$cc z)R&ij|A)W-AN_~_(dN$PAN|1}J$mcW{?7i7KmPH~=1%?DqxK8fT6n!YsBYa|Ykq1& zmUeN;b0ArrXR_tisqf9JV<zMr9iS^|m0&7qs4TbVyH+KbwGTi1o~buYl&eW4YTmJ# zL6n%FpHAY4wb&Zy0to%IJ$dqkT6!!N6n>I5FOS;Km0PXj$<S)8zsx_q84NGCw|47K z+%K)7TPArfX!&Onc}_|6BxEL36lbVa|Aw;4+WBh!I~uVLvE0<~r=NZ*e9>iP$q9dK zX$nJVA|);Zbka-~Gb@Ud#Z>QbRBywYP2!m22{s9#%8JI10Vih+p+mm&o$t`ER#ECp zPuJI9e)**<2cPLNgbtT3u8IXQKtEM<8pXpRW^8bD0H>b=1a*l}ZWJAJ*ELjGD{afC zZ|bMuIfkAg%FQGGXub<5n_J&}vMK(c>)H>AWSioZ@G05Y>?zmI91#u}VnV_26H!<B zX^C@teXV{ah)!N<g+t0Vh(X}^@t~Uysu<dCzcphh+93GjJO>!UPh4vVrMFgJLZ%Ic zNP;3L1bzbDL=-qVtKaPH7+9o74Tu*TFccA^aUhgHaI%Ua7P0XhgrBR3**p*Jb#1H1 znGo;*h*6q>V6&V<qydguMB$G)U{uR_KBMd6(ZXYwHVnF{qKN29n&{+;8=rsvx!qC` zCfMkN;0K-Tp9Z#!Lhx%@1fdgQJzi0T0dNKbV%Sh(%ko4tsuH*a2k2p=p;Lt)8y<KW zYYffng75(RhERm*@-b+CSx2#9APx*+V?v$aF)Dl%`e%y^qv52tRX-+Ceze$CuU&;s zY@(xq2xd6Sa&v(;fEiGwjg^2d@hBu1&%>Wl%-l8vLJTubX<-p!qOm1K9I!$0DwAlG zGX#}NG{gj)6*%P>ARQgh2G7P0N0AK_%y9-DNGuHTVQ^LpR-z)V%^f%w;Qp}Ql|+gE zq*N2HQWerAnS*{E38=DUGBuv;S>qx)KdIkU;b;8eKXInvY@rjR#{@wP{dfPvKP~g$ z8Wz8v)Za^lCGrmE8Kk9dK828)p}I)8lvEaSCgv;tdJVPi9(W8%cU^L{7NaDGUKfCx zh$_=$pKKDU8~t5<RJUDbTAmk1llp!g%2j(3SF+k+J*qH7TLkOWje^$B?!h4?Ugxbk z@5&=2l~f9sR$cI@An!op;z6ul>@FqkHSgw0=<w;ycy(!hVW5X*j|9GLE^l5=FCDO^ zbpcp#haL<Eo4rl9oR*)u)FkS-TCx?u{9k;oe`bBrHQroI+q$q&ErVe`45_x2qIxTR zby=za%>tlIa+VkCrr{r*On~Stq_x;O1QbUb>WHBPXt{3JzFc&fc6qgwEhhJqy66%U zPUWXkX1-_jPF*Fcv=(ASbdpf-&j&9%#ZZBdZYFgVtam!Fw|6qz$Gn#pUBIe-Zgp3S zuhiZ`LXfU5*g!G>;4bajs*T2mo{4baHG?2ZN~(cdS-SwQOlFgn#g)nRB=<CJ=~<`) zYx@RdT?lLX%XHPQYOi-}%fzC~@ap2ayCQn$KbhD?B2#X0rZQw?VQn#gRkA1<Z7mU% zM*N$pnfqBkK2>b3rn*$P`nmyLyS~;nyQZcJ)#AOHU3D3#B(&vLZ^$ey&#vpG9950( z8B)sIYrWyG52v^4YQ`7Vm)DrEqSqG`z{2Rt^>w+oyna<-R$=6wcFR=Vx`OU(ZM7H0 zYV~C^fl%(uVLRhSws_kj6Lv-?RQuh^@|tV*&Gmw-uX>nXjq7hq)XOsbpC6qatgl_v zZ}?yD;@Tcr91i=QgRF0D?bLTc*EVdP*^9Kt$FJR6Sho+b%eqY<yR-9ao^U96QrdH? zD6i`okAagmbAfR?r&3+5h(gC>^K{U+(L18$^{=nK`ig$xKYsk!sVJvOnpwdQUcY=L zT?Fazc*wE98O5=Qd&yh)4V|7IpPn532mj&!3jIev`jOkO^Ta2ge8P}3H#dj~f!fS3 zuO{P~+)ST&Bq$sRb95#N9<JKV$mQw$0F5FEfX{K;<BA@a-YymFzB#Fn#OtDKpFMlV zCHiTmHb)0IJ=*bbbWk6Qs+WpXg|cn6A<W5>CvPi_fAepC@7I3qS5YKhdvtX4gJ1fH z!|{`Kb0=4E)%jAY-Qv2Cnd5`g<{$q455ND>hufPwUw-w)`|o}C>*rrRIDD8NwOU<Y zdG^)wCvQJ~ee~wZTaUi{;;ZGA#kHliWivcmp4?2P!|C{XyuZD_+FLz8KG!Z@FZRd% zgPnuHWU#Tm`TWJ#5AHwO+U|Y+*%#{b$>X>C?GKW@di~Nf>hS)7>OH?WRi*b1_v<s* zhX;$Z#nbcCciwu(qyOWdeEi<~?``$A>M3?To5;rG$||cbf7JS@qdCZW0T5l;Rsdo* zH4-a)X_*X18*B9jTBa2nx-LYb%r9~Ir-9mHZ@*vdZuX}Aiksqec~h47-4C^RsA9`# zy3_UwJv}LPY7rZ~-ixCdzai%;nsL@!taX#IOq|FaCx-A|&wb2odD!m{tp5G|gWcVo z!C?6M^{bVo`W`#|CXQNmX`>b{QY|-VhNuDaYZG7^529>vo>yv*X+dEiMU@)HP_H_z zt=g36=Pl=Xi<5Xth)!8$lm?^cr>FP!4-l~tNhS%>$(B`sr%OJ&@d4muTFW#M3NveX zK#HFpJhbXYKe$cu{L31cV^j{)onBYj<0KA}|M15IKnxH5)029`fQL*NLdhJ(C7gEw zr9Ly=iVY|I+NQFMCTg}a5pc+Qd&!A=#G@RJf{h7)4ks>HaCv?%Cx~#&@?gm9;2{O) zs!?=$IKV`3bfbwvXz&<?8%pYcwPs$p$8>TC=rO<C1G=Qh2H53EGHHk^Ud0&*B7h{B z5D-Hh5<w6mRg_?+oDy9_a%EI37$~RBs38dP*oq*|=4Oc}+wi0@Rsg(NF4JPHFxm!A zn^E-G4G+zT+D=L;^2tPjTk=ZXieoE0S`d-6|34uSK{~tTbo+5*-GqkN83mZ{DvYg6 zJt<R0giDzMMWUrpmo`YkOe*dw3{WB>N-(G3F;B;n{^fc5XiR;?H^ozD@#b6Vq{iCI zLp8cE+uhlpUe}kpWeJ;o%qT<IOz_hnUHBt=J*f|P#s`Q|L%_Cx0^t}=&Qx|<uCRgl z0MVk$KoAsCjirXL(HTKVR}V(Th{8|&DEzl~A;ObGl$NssbwUupDKUgWR|u>CUD~vv zM+#6Log9F#%&HBvgKu2{z|QV&O+ot}W4&{t4jbJukZj!UZEQ)bX_8f^g1iz09F20B z_xN`H#7UfoC^Uqpblt8{HIvu8bpOx)*MA(Jza=bwel?O~X>b&AsO<3N_C8A;liNq0 zYEl}%X{rOd2u)j!gK}}TUXqm;9oekJ)_4ttA@U`z)fa7v{{M$acF>8W)Pe`mvR5V> zC0+9o%3UyIIvwaI(|T@&=qS(9)IyluxN_A;&}MZN_Dpd0H!<_8*uu;`p<d+Re^cE2 zt7@n$P};KO@|-`He>JOoqC48HtS-5E^QSV>TJ<FhGG&QtL(x|5l0h}+`m(S(<ysy1 zZ(PG<*Z<)8-_mSJTkop1NZnEIengG+x<nz~naALuOJJ8JxK<aEB&S=P^`*APpP(Di z6eKrENUiO5J5fKnVWpvzRL}+2ZKz8=C}F-;bfq(D8M<o=q}v&l;crwl$j~&uHVK+4 zQvB({?1Cz2{6@8RA>psdefyw?9Lif-!j2?-Ei7&6DbKF1>+qUO>}tK$ZNI2@CE>}u z9OQ)+(;~ag0~)Ndo27+Xbd*f5Cl27(3-#V|=vq9quGaONWJM)%NF}H(E81w3Qt8i7 zu`ShgVry+<+}>OBDCzfy?X|P@Tmso%TWKF064C5>YsF4FQD^yRx~rzvvHtR6P;bGu z538FxtGqspIvt5*G_F7KLL<{xx5q3<o`P`k(eE)}N89er|1btNqj=<*I2;dzAdzkd z|N85%-)et-(N&7b+i$;Z$U&A=fO1<QJ=6~SgAJ#M`sl{|D2ZtEg_ClZ#^%WsL3BIs zQ#Ydb-+SkscTnuV9KZmWc2{ASb<da||M<s->Nj0S^|~@Wh}__+=OP@!7MwGp!vI0| z2xEmTXFP;Z?EZG}fAKH=g_d2n)*M9s_>ceCt^42q_kNuxRB_mY+#`*j&MO~%^ig^H z^y#ZtZpihQROyl3tLe~u<p-sI@{^xDdGf?F=J$T@_wu8xI6W%jo0dYh1f^<Q)@^q4 z%je6NuQoR~QX#v$`*L}Fe5#Be93FC;GrW>UGR_SW_1*7&S44>2Own&1-khG?zkiQx z+MoR7N3OE;JEj_SsIKa|{XwkBa8MVmn)7SAts-rEYG19dZ)|USUJefq_D@bu^M{CB zXKH<`_bcc0tNQVs^;P&_JUrOlUs_$B49D>7x>nTsW}VcX@Dz{0Ws>tBe)u6Ib1gJk zl2|kDc`U1WOR;TxmWHLohU2wWGgx0=J3T#f=I4VFc5UO8Sx{HR&89<=YRqZU#G%k) zI;1F9GLLzqKmPcq-+AZV#g*lk&z|oe-rL&f^+&_C<@$kZ&y+lI>^MBZ!^r^gtR^}E z#B?A6=@XHXtE1f7ip^itAW{JgGC%`*mIGXf=t7WTalLx=`mMK~TwGkru;`rJoRrLk zWoi-22|G32{90OW@5-;(ek=z^MmyVjZv)*K=xS1*UMV-O+FAc*y4HRreAIpe!WG4Z z*Y4q2>b#V%Z{({S93EWOM><Jy3_!#s*c6!MBX)s^0%dP+&vd~Jks>bbVKC7ILliGg zs$RXRzb&^)zpLqJWCi5%R3Ac<K!-fZyt(N$p7C&~F!p!%4AO5oLpTs~=Fyr;CK-ZQ z1rT1rGeL&5=(+^MkkH7&Q<LtJa+MEq%a~KUv&8o1mNuV2Gb*c|GRv!`coPoHDVJ(G zZnw=$H0!!7GQ_$(W7AcKYzbeD7@~n7FmxBGoq1M=V^WwC8ih(%JtsQb2t-5}9zK37 z)z%J$)K&qux1{Q|h8AqoT}J{#_%F`tg*>(ZZ*k83Y&9Ia=qzgCkaDTz85<rH2vwLV ziF?tB;sPU5+M+gA=;19Sa97IW<rr6WW1V2M1!0j0bLn<IAZ8RNaf`^DCJClBo+lz~ z+90H8fMdo9;4~y6kbNm`CntvD6?*bdL^tV;QA6_6UHniIdz5#Ou2k^Wgjy8Bw>42E z$wnFN+8~ko)4((<oFR*?^C}JpP@36-U(gH?(<Uf-gh@&lWC%nRL2&`=4l@Qg9`ueu z2mqcUBx`GOEOKavlhX3gRwPRp)QJ$-CBp48y0mCt!zQc1kebg_0to$(_>lU)zMAAC z)}Zql(98-Ah%}?XQQ|poY17i9MYo7Dr}z=^bkS)IX(>TO!S>Ui{`CI+`y%C%AybJ? z3A@UGW0)z?3Qa8Sv`{MoQCAy1Mx#H5@CQ)3Jabh^BTh%-Rkx%D<>Z|UaQ$+p`pkj9 z{z7M6h*0WJ8{Ynru#NTl<PIwy`b<k8S0Roxr|s8^>!G<(hC0)<VE{&x8QM&Wa1inQ zkN>a#C;GRC#h+8nHM7+&OC4T65LB0@x&Tz9g;l$<xLjv%Rn@K+1d84gH|J=Vg?3@A zi-QZJ^wz=amQwAVWzgIxXqMYy0KFx*k-vd3phI%E2`)S65$tX|+L~JS+6~7A41e;g z>^co{jc9tzbeSkCr0U(hGKPzyMo$|j;+ex(mKTbGZKbq4nT}Jucu;DjV$N1LzmB4m z23d5eF2_nUJfq2?YfF7Fu3drZBIa1<BD8S5va}jXu12@lB<f0Me2b2|p2wfY)sk4o z5xQPWWrLOaUiUnWkV;hJsrkMGAtr}uWdbpIt_84MZzN`F0#VrNWR3?&>DUabmi{DQ zi=p7!x!t;s*N;B8k%EkB>F+p=<EW1-)CIDv7-|2$QOiR+VbyNq3@9lXGmF!)qr<Ap zl$M7Mgmp|6mfLPswh6EA*P+#m6$ESTv=>B(w;7??YBtsQL&4J=sA%mQuFYo92FNiF zSiY!)%y_MwVyYo&n~du+8Rt9yv#CMsRtj4<_IDdf?H$w6{@%U*;Gzyg>nrDHms{KQ zT|t*yxF8Sq4^3D81k3);E^A`Uw_Y6&?V`hB9|evgW|wEUBWVBfe5dDmQm^pYe3`Zp zGi^KbWaUP7`K#M))P8sT>NOn9>!fYF+;(6R0!|cN3<89=`^Nl{pi3t@w%mcE$72BK z)|T2nR70l+Jg?$_bVWo}<QRupW;{ITaA|b&fn#v~poE|+ji-nN($DCN7cbD=`UV&E zRwpHR9Q*e7_a8rg%(1*<j7|zCqio4ZZ=>Fkpq4@m{G`nTK%(sXvcwq_I=Kp59vqxF z1E)<C81U0iGoAba0;krfhx~*4^;3#W<ZY|ZKmR<BMuJhoRik7XRTc7SSF;am+xJOp zcT^j$DEVNyL*!^Yc=NjM?QcDLOb>rJ&rjPU>jD%wg@)jn8m95=>~6WTe)ZMYPo6w> zmHNp~e*D1)E}Sy6t#yrbb#%1e+1d8EN1@XNDL%LeY2o!YRQuV*Cy(Dgzc{_Vnhl1R zE>RC29)9)oSzVT9%U84M>eAZA*80lg>g0NSc6>gZ40bkm_wMaZhSQ6|xgBw7wf$MI zciv&eWkwXz!c}Si!4G~Qf#&__=m;f&NS7!;th<t}t}U;x^;mp$^rpADZq;mVZFq7G zNB!-sU9AgJE?s8Fq)UbLf|L-t%%gi?8)CN(sq1T_!SLkl^qsffHV4nYe)cQ>-miZ0 z@y}d=)?Bt%>o;<{@1ypI<9dOjspThC&A~ipYZpb~xzISUx3fL2UssyHZGwTI&`cS& zM28cFAU5>&b)=Q?Xu8o`8xF>z8}vtJA)mQW70d0X3iEOpadD}bd?$I;eo0MxnRs~F z?`?0%RKCr-B#MPaxQ(Lw9xN-Wi)O8?)>mhiR?$yS&e_`AJvcl(Jbrb|ZT^Fp<0KFH zkDlt4!|WAR@b!iNx&Vj>BxHitvQb?%nT11@kR5<2v~RcbNA0V*z}v)RyI!(%t*GDL zp5>dvsxHbYAt%-Bawg{lIQ<YF8s*hmuilVHS8qai`0yd-H|_5rB1R84NVQ3<hZiZH ztoJswqsiC~VD|Ztw;xoCT12;E$<~^^z3jDc<|kLv$_L#T;xjrJj>kD=W(i~975=!L ztfp<qH-~Q`aaG;`L2HMra0qd!fJkySB1RP$5rV{d7*FCYJ#p32CdC9PZ0-{1ah`I_ z5dH+AjfT+UHtQ(#R4N)6qD>1Z+}f$1bc#jvyPg{jbb{K=^}3eRoOQuU{5NF~JT*J* zRZd+D;_dt-PJf&sj;=+N2f!{pL=dUf?ed>^%j32%5w*MpT+NOe4G=>_sDjg`g&U$l zn}pEA4I)}N3IrQjT_U_nmxxg%VS#u|u%%q>U`E3b1b?8T`~uLB7aC%e8w_#j7x<$D z5)WCAWARFx&=L+#Ig}+s^e0}UbOOvEY|+_)Q50?0jV*^L7gUcF#89G#W)sSg4GNKL zmV+Jm?EJERAg~o1TYyU<^%zBjkX5u=sk1FwF&1X5GtpVeORhkdMHJ$4B~fhY!nL~W zsvk(_UM5tRbr!YMVq+!x)8!H++%tW|$)bDS<q$#x{#a*`5)Np2u4_ma+uf-rt~Ep? z{P50O_|<sgjLNo^raNo5A`b!}wwkZo3ox*SmY&*AmpxgG##=)QPh4a@e--@8moJ?d zbwzPqA7?4h<qtQA(}}-ywlyyQIeyUg|M;K&-(~(=!{WzRwPV6!;}*Y?`xfuKm7m~_ z{dIVf19<zEBf8DGzK`d^);^jW&Y8zdec6xyx0EIoZLrE#yOaf5ITaMSjfM_9Yuh`7 zE(WC|53t~QV6dP-(CTnkZ;MsRM393!1#sMO6xPMs(QQqxY)q7!4LUc3)1{?z#~N(I zRcDPyXq7z>pWPv^xzun(42mh01WH9$cJ)=s`N`=QpgDZ&P=ijKY>D5#r<!G07qa<K z$mJ(!-Ez78=bLt|W@--MO#2H^CV}Oy)86H7`Oi?b(v#1==l#i+^U7rL)Rx`m+QG-X zaJg1aiQ=r6klLuFjby0$^Q+&y%?l>MGm4@G_3879eC|f)yj4TFoj+aam`6~C9K2e^ zxoUc#T-A3FuUwYgZdX>|HpmiaQCpB}tMzG5M_6YXR|s2%jl=F>Hm$(SZ1lrV&(5-9 z4FL#dkOzj-um`{8jh=mNZ)cw%Re%y|4Pmf>LI55BiT=ZT`*vQyW&CUz4PuLdu$7I* z6V8F#0gmQJj~=1m6b1inA0pz9t%q8tG()1pb9P?uhB3rX+qWTVT@q-cIs1_v7Emjk zH!olQ#;^a{?(Y7_AOD2G$B!Q#9zJk+e){xlURyZR>G<-}W_SJY;bT{kPk;7_7!xKd z37J}F0zq*m$2CS7vN<Z5KmOxCM*sC+|8)+)c}|ZIh!e>Uj#CKo#%)6=IdnQwi-K~p zD0p(hz+fBIbw;AlT@;a^M9CifU;fK~`J2D_n}+`I5C8D(x8HX4O?t1VHQj*7mtTI# zdACz^+9X6;IL`;O!}|I8DYs?y`1R|Dj~^esc;TAsHteMT$;Th7#htCK{d@N|9ViLZ z3+nZfzl_CUo^!y6Suj~L!yL7M|M;Zr-FM&p;<Nf57q{^=@u@4lU?q(PQc|QVpPn~H z)sY3!t;Dnr1M0{H6@GYlUs*ZPF-KN(wUAeqw>P&O5eAq2<I@xS?bgmV`sJVx-`(HS zVz!*r*e9QS^8Wkp%h+e1efF!r`m2oQ0mf}QWr??#>yofGf1!$dsV+DQ1~>T+Km5?m z|MBC;G)M(ON(|9V9FaEsGH-&u_~Hv)Csc<3=H#TNcxCZtKl_<vQle{WRI)r!OX2sv z_dT_3C?!F;1xg9vjBe%{5F}2mmU~$p+Jn9N^I9t0W5+6JFJ8EDnWlw{i!=4Vx3{yh zvUYiSZZ9H2C(i{U1SY7mNL49Sol(S0v3+s2SU>ONk~VA4I~315Pq)pDUjA&Di<8S+ zo_CJfD@(FbKS8IK=%B0}xjpQp*EV8}ID*s*TUrUk!xp2~1w<yL0`k^dZz)0yVmB!m z5IMH9R~LW`A!f=TsaOaN98ck~`1RLc?;q6VU)rgXYSU-m!2IIH3p0h&hLgbEjmLJj z_NJvOO4^w-ib5?b*l6Y?2ksq8zNJ%#CZj?CY#EhgvrJakl<6X}?mq6Yg+E0YPNC5$ zI!frb;z$|oZEZTw3@7so4}UPoCZ9R4Mdy+s-V&sWi7%dhIT{QPAKZ8TetrDLygYdH za6B9h$0PXW_Ev9w!<^PncHP{p*DHzhw+$)h59>@&1)*6)=mMc1&zqxq$Fk+NHc5d{ z61O>wC<;WfC>(zN@`dW!-#@Ub+U3IkrzUWBcMs+64xmM$A>x_$1PG+dl&OCzl4NY$ zFqCu=OaY`kBp)3Qf9Nr4h@bUJNBdzE^<ao^MwNjYAcY?rqX3;Df)wJE6GLsf%Qp}< zM4XW-uj;N>7BSF<pI|q+UE9IxQY{a%sWgJRc!)zN<P|&#XFAal6f8Olx_LpV<hB<G zI8(*bKFy0_Dj_Iw2EUyrm(M6iVMr3dU-%1u!Rj!SpfDs}g1P~=TIdCN4idi$C>=kX z25q`2C#?d`!(AZuKop~0a-syn4a7eU!VwoXf_O5~i~<PRh|jrizq`(sRu_MArJLxI zUKCx*lUslp4!9S`;4A`^&X96aq9DpqIA)VPdimTn)%4i}SYgydM~2M~Rc>>Lm>Gi9 zciL;utb1u!IhmdKul|{{*tO;e#dch|YA>i+@1BnvYwOFaD|UcxXNKnmEUJXY2Tn=_ zyKrsNk^q?o7;vI1OHx8ED{T_tv&DMD0B+R)u3{6Q&F9B|{38fi5n+%7{BR72fRbd@ z5a0mKfN7k-P#lv?Nfsu5Ach=<w|d*PO;F9-+BBS}t8D6dWBS_nQtM4fWz*=RLH!jH z2u?A|yppy9V8i3=#HFvk`bs#Zr2X6`(*VEljk1fG+d<If-@YL&RQ>n=?Eg;i+r#1? zj_c>(flkHHJYHFJey}V=hgeq+<2Iaje-WOYSCp9RVp6xSh1pdurMa@SwmvMJ?*K2< zw<2>1s@IO|TcFpgbheURTV1=lzVZZ@L^cEEMj0xo%iGOt%XCubp0`}rZayijTxM!M zT3a*3r-<Fmmh0e9BZ-3l6-B#q^4U7l!{2V|H}y%Zay@Ud<pVhjS8ny5d~(s)&}q;r z)D^epHY>(rk*r!>U9PX|m{9|!s#4Zu>pzv-`bUE`NL8Io>Yd~wf_DF^D;&hFvINWX zxm50MldFaGm4(rCVSRPs_;hq{-x<0nm7LNMJGZ&30<D*BbcNDhJ(py=|LXPV3Q?&! zn_+9G7ti=I&FFAgznCmQA(*4VaJYT2cQG6c`@`AdY}><p%c0!Sq^_@DfBlt5?BU_P z-rB~=>G7aHT;HfS{T#@wFHh%Q&-Ua=GjKHA+1VSnUt@NBX>(N-VjtPxu9wfRC+uIR zc4k*9?|Nr*=e&P@HNNU?_tsa|N6wl3k)z<vbh1)gXf1M6CgE`2W^IEO&ivC;7)GP^ zNwC#5$M<RbtyISmhm~P};6Uk6qB>NA0}7t)ox0|ETyeBbah;8_6ty-Q6i<4WRVlK? zSeesN`+Gvm%bsv~I7QqBYWI|9PaUmC9SS`g8})`EKZ(edeVI;C@L3CJ01%!CaXhIH zFt@TSXMh0dp~Uv*Ldy;JLmSQW=g(c|5bgMI2#49F88e*(?Qt}_%O#NH&6$<BA<kgK zZ^NRtHnp}c>^s>L@o)7uPtT6c)8YLCRq*Qd%gOj^YrE$ZYZ+af_s!0O`;XwKC+F8! zR}b#hUmcXLDyMd-lMUvaN@Yd@rGk4R%B-mgoZOQx&hsR{)=nhJp$Z!c-{2q#$?gen zRZy3I_%8rvv%@G(Jd!DVf}MU0VvHxc7`XAl2OoU;>8JQz?SAy5AL-h`bAY2W;<BWL zJ7=t}t?cdWsy7F9^=23FXw+KM>TTS9pVm=Z)sf;!<}}WWoevz~Pa@J~8YhHT?3##_ zN9NRMDotoost6STx(P*}3`gr5jvMPYv-*Ps=4E}Yx6xbs{If6k*xT5$KRXqewdtgO zkgN_03$y*5-KWpKzJGA<ynlJHyLWm~U#wbQTb*59kEWC5_FKNTn9@HTxq?as>*`HD z;Yn<K77IV&5DX9uDYMW8m9rx{kVa7_MtU%~TL0UB`)@r0zw@2%2<@N$^M7t47$pe8 z7DGVbC=d=nOdl(fgN`TA;gFr}dS{+vZ{ED|cqX#Dx9uvf>O|*&%^6nA3+A=@0r~p2 z>ZtwUw5`n@xxKlr-@32YGuyk_^)RWg&wFgt(@?>u(g+HTGg)-W1B%$`*KPXiLw7mg z+apHOdv&$Fxw*BoQ`_Z2`&3mfF7;HdCD68-i~aq3mej$);foi~;C5G=VqK%#W!n0n z(NUjbYf2^=f^dv`aM8hO<4Nit&L#A?U5UO0UBE5|OUY42)zM}~5b@hO#49eEA(W6x zm;^(S2b^q)H=_WZES@fDro%Mh<Pv6_Ce$bdCmu5^nY!FCiP_&w5Lt9x{M;amjz~Fe z(Nkfx90FFjq|G)cG?j)zCmss(CPvgU3gNjH(OJ8P;<Rdo)}y~ZRt+CbCeFD=&E4tw zx$H|3&74teb~c5lg`>zJRh;B4_oRX|a8?pHXP8U<0A67ZBt?O&{k`3TXV1U7cW~cR z?%{*S7ODDFu`A2<+k$rQdQbnVLKcpdYd4lmNlp%9m#Y}y5<;hhgYBLA5ib_G)Hw#? zXEI3-DItg`+A!o91jmqxOY#$fA*#UHY5f%pY-Blxfpt!rFX3Z=6QqHA85K1o84He6 zk<b~<zz{k?%5g$CiI^C9jx(|-fFYh!l1UE_5p><y0`yeU+ZsWSIXEb*ZGSdOHcHYO zr3x6*#v*OH^kbk$ezXi}DWL&iFa<)EAFAS8mVg-~iy=zlUM$83hG;;^%%bSxVFEv$ z8ATz2sAW2_U?8rABSvQh(2feG36Tcka2iw*hK@NJ;AYJdh;nR**mOar6~qCmA|<*k zRda!Ue0)p^=6BzHR}|Q25D}1*-R+&5%2|OS;(#n3(FH;0Nvumky^`2K*C;Tg#S<UI zh%H`ehl6o0x^{W{tJ8TtMdDfS$?hrdGHl<c*7cb4qhbBw04K(`-+r6(p3dBkxp)Gn zUz;v-aB9;HgD%8$KYH>+Xq0$DIm9}QJ^lRW91uGYBhUGXS<3_p<sf+g=!uRSR2j<p z3cmo^MdXIj;bnhkYu6%|<;p;N)6OOWo;`nV^Op*$##i-loVhpEr`c|Xm&3Q-dMoeo znr?^(tL4u_Z8G2lMMOlC>&gb4UHovSxm{D(CXsIpS&WDn{>eZ4XPCb|EPi@@RbPs2 zZ>I?_k4bLi?_9}gyLq{Are5mXDW=@GI8CrAZ`Z5Ev09z${1dRYvYOiBbRt2t9Je>? zQlvO!)3lf?`J{DaaoNSEY$-deO2ogJt$L~I>~;%iBXx)LeB@`FSv3CFq;mdhGGbCP z)qvK#+qjg$Xyi=noN80<qwMYN+BfQhfLHat3JvN2FIVjh(*4t){H$#>HNhzk<>Wf; zwBg~AaH^nMfWQOH$~3{*nk`7Pt9|nLZGM$+w~ts+C<Q#qh-O3xIvzs~$Q@?|)($1C zWZC0~Q_Dj`rJ)6m4%%&h(Ru_DQU7W0Cr4Yo9x+=UocB$tfh3a@B)bn5Rsgl3*eOqk zm*xnk#hhJ|h?}MT$e{;rc_Rwe^|Gp>rl!s=VocR08xpJZX|{vYmM!w)?0ltOuc%Do zEO(nr04IvY0QXQQMce)R_g=nuX1l;CsMHm_^3cx8T2h=RXh^r;zkKgI?{MB}1B11M z=-%l1XR?HhnK&E}v7tkx6kP}y;+tLgi!Z*gp2`0CKmX_RRaLi?)#Z9rWAkL?Aq@$i z6cIT000v69ad~+F2SND0E=Cj{#!2SnhhuO+5F`(^Di=k>!TFs>$Z?4VXLN@r;x52^ z5TK2QDr`2LytkPTVNyi{XE;DsGMVNuoeUZB+{#Ogd4*orT<fxh2XL&#QEw^dTq0P8 zH~^Q-@aI{Gho4Ln-`=PnO^IEuvWuTBJRD<-!*LG-S#8H}C{wA@WDgG@&Ka81#X~Ax zoLZwOg2hRR7GMbQAr%|D45icwk^*pH;uHc9<KxHmr)5#zd+)uU|NQ44ee{t^;6D@i zsiL1MQdA8F^-DQCL65jukZPp@!HJS&#sp$090-L2A<{q(&O~ICcwVByL#NTCPVyzw zG9iW2{32Rz{JE?jke{DZDW@T7rPL@k8fZhIUry{zc<?JBIuWIaMMON>gp5cb{?p@Q zvyYz=iKWfFYn2Cc#4+PUfl$~&n7`{q#1L8W0{H|)3?VW^1DzJ#4}bW>ycB}?lb`(L zSAOMJ6g(vuQ0SptEFc+xPzd26g>Y@0j5As|iYozsc#Bh);O5qbrDT4a>^Bz@B1RV% zYR!UV2_<Uz6UtpcziOZHg3zOdCzE_gurkT{=qF+YCB5Ot5L*x}O4=X+er7t9LG4H_ zvGmV}Z}|iKlu0HO37)J$N#hK9@?cSG6`0IpW4g26#ie+N;K!U(4t`QJ+xOxOuS@|P zKMfGjsnUk1C6%0*3;HRCgs6)%dH^0q4YAd&5e(?0Bn?jr%n%2}3lSqLh&bU1xeEuN z2jriALj=(Ur463>5?8FG@Ys?=6v{KXF~kH0Qrv@(HH3}Zx<+ZBN*m6ckEJoy!e?%< zPQQF68(H$92#sJuqdA$O2M=#EHKFh)I3$2M0RQUgGa{C-mR*|pkRpi){oIDo2@dY< zRhn)AJxD^<?W!Fv$;pf=q83ICxbXl0|MW>jK~#kmD_UBT1PIx90x$a2{4+rk#SNo0 z;G~mvY%&1Pdcg+KqUdT<43xt=hzUR(o@okabS90g<3W*Ohzx_w5r`@X<$x?fKoE2$ zAoO&c>2?e#9Z!Ji5^KK2MAQbs9~@^4Nn;#C6o}kLiBwYyN=4%jA{<15iIE|kz>vfm zqJ#;fT69khJn<7xvssz3%%hXYU2jd6$wll|jn)(^BnUl#a<+7N3kgvdJv=F%=%-va z)&ZXAjDBjFhHLQ{l?sR{LouhT?XF0JZs#!E=1}UIevnZ{lZp<)9H2)V$I^Ada7SpT z+$xpmAwrOTs<4Ea1BilMn$;C9uM*mvEh{rZXXd2?BC!sPx<%{KPY<I;_uG$1Sw5G8 z`aF?yh$mG2p?-tc#Xv|lI#(gl7PZ<SlF2KeOF77B@<UKPK#22jaB=zI@S(NGInMB; zG`9D9)d!x@r2dqV3vgwAea$6!>Drb!_M}!7^e88YQ>6)FRExsIix)45bLPdX7qrFO z<TKVyE8kEcc`%92=>O%P{u%uW^#ARD`j<=f5!U(dsd`SkuGVF0(WSHAw-sl-&nu?- z=(E$4nwtMyNBb^M`$o^w@@OzzoR#<dj_M9%Q(7unZ9c&CdUASxM$g{%&gsSZc5n0S z@?v*uo0W~#wdu_@EAZ%FGoee%XRl9{Gi_95!6ZReLe<Ib%QJGS{-o^wy*-mCb<?Ti zsVc9R?QwaCcp|%A9v{CZ=PG5!2A3B~@9fwie(C=G`&6k>M<V!VpM9>{dcAr@Ig5l( zGS)urhW5?YW{3lBM4^~4n`UN<KgzPItc8%-#h}`bj*hZTsIy!cR0D*!*is6BRDchO z7n?SfQTkVFgNAU)e~EAh|6o|VQgUS<K*un<y58O1t>2Sr8w5c->XO4M(q6_fR+49i z%+Bg&z1D?|Q4miiqx!pTcmT>A>Qmh_4=@o4haTD}XGQnRFTZ^M{rA<eofJieNgTg^ zJ?vjvwKU@-!b#%b-FM$5B1^n_^5h9~{IQmH+v5|=Bf5QX@|j-@Q5*k_s%py$4@x|t zgmOGW#vjCJ1=~JI=~|0{i1hMDqDay2h=BgnpZ@fhfBBc)fweA0Dr8u{%vx6|A;kZf zv(#xuVZ|s7hMIfx7ud8oQK;1llOYtIW7fj02aI}^-P@Nr;L*k<K9jZGP~!fRlPKk^ z+jQ{Qd2_N64rU17i0Dd)eA<`!iQl20aurB<HZT4F=D3Oo;SxW^3r~#Ji&@UwBXs6? zXO@{j!Bd~RXs;$vXp~Wi8Zf8mRZFd~(RD?UxzObmb7Db!{`@(+DD*H*IcA*L=+p&q zDT!smzO3ysnOFb{KM|=FFaAt)MyaI-Kw7fr3{n@Dcy8+R$0Rbd(T|@J%xxR5hc_ig z(TPil^qL6%Bl0#bLHNuQI3yy;hPdKCord64H7oO<1T)u&95ZUJO$25xQ9=ZQhm+US zs&@Ky0h|<I1wVzXqf?Tug=AC#pm0V#U_g(nhG-xQkL+Rl9x{F=gvl;Wk;;Gakla#5 zL@IzyPjt+o#Gl{<LHtLFl!Z@&0-zHeF4A}2c_&Jg3OCTHB|?@11mPfV(=VU#1kosB zcu?R>(|{*?AUY-HIyr34%%_t6+0FcKdMA9XF36IJ&LCR+_F=Y|piq|xRYqxmpco>8 zhbpZ=w6RMq29Z*3D&Zh%I|L^^Ty?O3P=z@m#2L_WY7?3v+0%_z*{qVTgqfU><xC*r z2@Md5DpO!;wAsP9VTc~G*dTyx_5^?^u4rZ}D}rWp6bx{tDKFQXlEerw=rSZrWPvUo zBH{0pL?>?{hyZRV8bqhXKy!eqjDpmFnZm$5lx$_xQqnn(2X4QWg!sdjHrj9!fyaRq zjGPlOp=Q%6_N>v$7z$1zR7n&>kz3k)@X$00q0L&*N-ux#b0c$<&=La81no8-ee{vd z3WL@I!VusLfDjiQ*xstM2c4`K;(*5rCE^N00DoXItzZ2W5oUsnc5d)Zmn!;0!H<H@ zL;Un~IbjZtEfWFo6fD&GLd+x<p>1E%lI0eDL-ga!PKC{ow!@_;E_IXuBF!`~tyMN! zJTV%IX`){j4<G{P1M#GeLJV*~Bn%MU;27ZHhohiZ`u^n6PMe{KbadS~3D7}@WW(pJ z7F%b9pV|O6Ix%SFLASGFG>IjZkP}D{fvd*OjZTkI1sMt)V4xvcB88q+1J|k|lZ8k# zHX5uWbU23S?=(}3P1@mI7XuuRu8Pv_c4ktF0g-hkvh$}DF>kESUr>N|+5jBjzpEdR zN>CXJ#64_Xa*QHQudg=N>(7qfB}QAGeF+wYKSry1imP5Gi_e~?T0HWgWu?@%9Wn_y zK0Prnf`Vs=Q3^fcPui#XxMUwVK0c<f*cKMACUy70)1{QfXpV0pLJZw{q2F|1;BE4T zjW(l{Qw71y!{KHB-u|I3z>^Db-T|h!JX~ytv9>)7M$Yns{jE9|*+5bi)IvNUXwJhT zmmNoFCOGr_=p{WMCa}d}8nD5|2&bpa&1V1TpZt@Wp>GY#fAK&5i)XLjoW6Q}^72S~ z@#eUHde*-<zc@QPKR$VL^y<yaqvKbv;r;WA;rXSj>2x@nj>gyH$<?_2%-=+JFudvy zu7{%=d()`etKksh-_y@NJAV1He|qX-asK9wlk)iT^5W#gZhbQyZ*8n!o}8?&ET6r3 zW2y<he)$6B;`9XnrK<?3lauq~({1NqNx5>#uAd>gnvSo=ZpzciaI)aOr#7zmQ-2E- z#prZwFTWi2-Igu}m;DZRXDgo3xIPGI#~)n2dBx_lN9`tND^7mRLH!^}{cg%hn-XVq z6H!$%y{et@=;(!KgKfwO&-`igtn%3CW>E#0X>>4|vVS=qTdt1F^^eDPkADARYkQMt zh9Hz<tKVf+0_~Fojk#J^d#%DI<@!x<qdrFK{=YOB^c~e_*VDy%i+*9L-mteVP5j&H zt-Ct;x3;njgW#FnTy6KZmatm6_JP@Tz0gsgj$0g#2CMa}t*9KB@MkRC$>_<W2ku|; zJsA!CgOn{B%k|Zk`^eg=8{AdBrnR`TR6nh=u}(|j{*_6AOvlZijs3ly_0^Tdh5BRV zxauP$(;<rUWIIw?R`#F@K%`<9^6sv+;{+^rN5i%K{oQ{5oQH0P{$ZQdcaWVqu2)v` zvHa`$2x5IIyjGLxBch<?d86l<VFPspS$Xp0(ar2?d1cW*A=}5a9O!Kb$$nZ-)^5uN zDx_v*I&~Z|v-aYTKmORLiC$f;7l;<?Yw!#1+s+5v;LOFv+3wzU`@on7zeCjqTdZ$y z)%V{hBnu$+1)GA(p-|f)Z6ly|zAvK?<Q0CvpX`Q)Abg`OJVp_<G^khzI-l`Kajd6S zJ*7~Nj*gTu2DsWrwBx|bYU8vAftsG?8?`}<BE}_x@Y*HY8HHmIL+kCqOoVls=|Ln& z1BVd}5sX@#Hg{|gJe0%=iWW`^Tbq+Ppre531Yx6r+73{{z`AZk0Oo*1(H2)h5F#AT zkQil&!z$9_r;9=hIw{plo1_6qhDg~Wf(r^;hGG$Li6J5otqGMJqhaop$ivP~{k=`r zv0=a#9$O6}1l_}u2xfEIewm^Gr4n(Q>iCZi7e&CRkZACbwxQANnhiI^D8Ya(L8igm z?GK;k1aHXdAY~G@2_!~45N6`)>_T*b0I5ZZ74Bt}PTuBG3dh5oA^cQf3*ZC<S&6tV zHf{i%u}i$;!2n4roc!EIWK7=BLoAI2l|8CtXkk`YAaUtX*g33a<*w;iY#*8`uZ*G> zr5WW(4mxo|8(D5-RBq9!jVk456rkLN@JNVB=ef+QQWWMeQ`NY>frPIGMzKNIGTriN zt~n_Q05eMT1I!=}Aes(I01_n-LvY~`rw~Ju(Ckzf0|YT%r3EP97xd$_C6W>mA29F} zU~rv7R0#mWa}3gj2NJy8ZA#!o;y{RTjFlj1!w|rqoKPk0QNoZIjYf$f6hoN1i=t5! z2nKZSMFhf}O+#y%QdjW`L%h|RILz{IAv;%~$frqH@Q|GUjAo&sW1u0ah%@x#!LJ)} z$)Q{n=<tXn3O*#&<^jSJIsqj9Fhmd#q>~l6A@xi%g*2ehM#Q|wqPS211~|=PA!R6a z66J9W5e483vvxeHqkK1yDCt79G{<i6j1q+72N{xq_y#b9o;LZ9W-SItas|&2h5SbZ zSrI5&s<eg@Z<M0|QfUL>FY~uLg8)P6g7}8Q2dyq5BzO=IK@|R{8@n0pl#oSi_6tg; zadusJ08UjhpsUS%p+}+70L?&3rJ~d|2FzMgEM`uVt4^Cy+PWGDVn~wd#1J0P;mLEl zfC$aeiB23qI70)wjwo6RQ|;whgF5HlnMVk_01rBV)1VEm#nVRSNQm(bf*Cy_8xWRF zM?!SD7dF0O>uRziR&BR)4)Hhuv6`Zpc(TW0OsFfD3gXd#2P`<Pw^cK8w=&V5p%$8> zU`x<&FmxZsMoE%G6>(jVNJF6?;LIp*<5C%GzzR;l^Z9IYa(O-lpuWWgim`$!JYlx4 zG-I}~@9p2KsBe>irDAA+&L1tiwgq?{sM;1C&gOEN(B*2vi8H!k_?_SVUC6hG<^SYw z{--kB4A(yHPGbAp+T3tu;f{$FgcI3@oy&u5WyN*Wb3oech_xvWhogRf)W5uPOR{N= zM^iVZhWIxg4G;GB)>c=xHhXSF4q+?xp6>FEtFx=%WbAfyetKdRo*f@AEzHKl!NKnC z=El0~?w0ekJ4$_vYPRS!dA-1vySJ;?6~%-8WH6k%Y)_^rF64DF8??LGq(0AFADLWU zT6ck|KgHnEv{K)oTwUJT+IAT;Cwn{Fn;Si{=F_dLf9bfe;HG(U{KiGrbg7ItZ(eV0 zZka=6HM=h7{ky($ZSK>!y5fPc>c8fttv7{nEo2WP7jYLB$Nrt|Eg3kxcW@?5H=^Z5 zKIB5^pJgQvz23TexNG@lZ{4On8un2p(@EX#uIqxAfAs~~o4O6EaHUeekGfvJ^ov4? z>s$NtLlgfXQmwpQP-kS@O}G&;%rBy5oOPG9x?_`?DKZg{>n-uMWjD05vlDl0+3#(x zZ*TR;PRISp$iIQ<TXfZ2vMLsa^`|f0X0I>%=cB<zeT(+WG+wlu?Ufs=>o6a#>X$|9 z-~Ge=(eQH6KQ~GW((t;{dq&p}i?)9joqzT^*8z{?dad74zb(dT?EumxIehjkx3+DC z7KLqLdU0_+tiQ_b@#!I9S=ydf*4CHL&rjQRZt3OA7ar>O?;mb&Z=IaD64yz>N~qw+ zBT{y0&J2g1ogOFlbXP=6uC$r%qobE_w{cr8qo=1QD#1V5)1{v{gsdeG$EFOp^y0;H zzTw>5?9pjE!&a{^STbhE(r|28S%P2Hs~*!TxcUvbn|g(!HZ=~;k7BZrttxKw9~}{d z0R^tjA-IXxr+hI-BwGo@C>$pSJF-!1h=wpYZ{@iXD@LnaZtvJ|#LxjYPcM524Pn#L znMayc1__<cY>P&zit;FQz(Rpg0!PG&AyI3yOLlg(>=KDWEw_`IjDmC{9txm`6|y0A zL&QPyLlEGE6OR=qRQ1C>M=0V(0e)?m*`ir56gp8LG-L>#l%mj#K{uniG!sO@$t%q0 zQ36m1^5o>?)FTAskjE?j7;^uCC#$^Dl69LJ4eQ1Trx3(9fI^&R6ae7~Aa9f#uD)8z zQ%l@yjubzJ=tQ??nqOVk0o+xeZ^<OULy8C_;UvJg6m5t&;Sm9m(&l+-2`4B4qOcP2 zSiu?1_)$8dZc|p8iSP>G3=u-JM~!t&v2CH>uQxOKMzg?)bG2oX|9q=$Xr=z9eL0Lx z7p|pBn{Fs^39N6_ySN#R6w{KK*H9pQ;8l3=XR+MctwV!w_>YZjhVDWPSu%OA9)IS` z5+)Uk01qPHsEtUva7rkLI{=t;F43mcqr^!CPd7E#$O4>*G~+iZG?2m>x1$_`7z0L8 zIt@4>ynXfR6$hHi0t!VT2?-}UiL*i{D>Ni7fCAzhPNowb3gw0<gd<WL)3JrfXT(mN zCrmIDW`;mGQ&A9_X#fyB8KO|z#g!R>V~|h!MWHK`D3XZ>v-H;59M$*diQqH}VVzx4 zbn*wM*<^?Yqf~L51`N6oQrgZjbPTjTeE3j-MJ+=Fqn4@w+z_zez=dz|=2Z_C$tGl7 zhVG`Kezv@UA$EC~mrIDm2Rh?VvSdNw6c@)bJL1Z_K$NiCaWVm%A6Wz_hVJ^Hjb;dO z%!b0IjR*#G%<R%1aS&CRrcQb6LeS4|e`5kPM=GmPMKF2{A;O7-0d&eCy6B+<@7UtJ zp+Ja${!TpnkcevoaN+>7Lc#;#O!P!5zC||l@Iyctq6Cg2^P<Lyq6-IPlQc+N3N#(% zYJjQ^NEyO>m!G%^f<zF4QxPhAODxQZD*)#e)A0dB3E&<)B6wJ*8K~_R%{O&Ik5Td{ zi7}vyt;JV>6F;3Xk+y@-BL#^?h@vIvMC(v#5gJXRAb=oFRv=8^N2Em8^~Y&P!HeAx zDVv*?+OpTYO-kVy_-$&sSwLA^UE5gSa0`|l{y9e8)S6uw4Tf%7lTp2gk#)oYZs-y( zw;G^;1O=o{7aiV33P^Q$xz!xQoIh*i(wl@5sa&^jT`_ld?gDq*Z&!N9VZ`2geILXS zACd~GV^NF-X;1)K#bBsTo^@6))A0&1S%M@ST^dlhq5Jp#!9OTJzBRZ2{|)mClYfRy zUy*0C^OI9|qWYN=kNm~D#kjP(XRa;R-$vM|Kj6m~F4xDTU9{8;$9So2nW<UVqPQgs zL+tImQuFP8B@?QnLb0>(!-go}rKOA0Q}=4C)~F#!;j`IJZ>v6bwzTX*>sqS>6hv>M ze#m9rZtQ<`w_NSDpLTJ9KYsnnUBcS0nXI4bwnFMtm|9bHd2ueyc4MhG`+Myhp{mnX zoF}xCmJ4`$I@&(!k>d_0FLa3F{Nn7<qX(G})0~+zPvFUuCn(}oG@f&(r>AcUUhVDg z$c>Wrk42{IlGCnLDg<uc4V9BO*Tv)Nm>jNDySUWKvF=vZbba{Z`essR?3Mb_>5_F% z<6XUJT#v?;<pqa@UT@WX+T5B@mpEl^Nm66^`_~qj`7&{;O%QgXS-*eDJtMi-VW50G zuFo|{Cbr(j#%6s6RqQ1+_jY-a>Dj`}Vs*7cbjvsAZI5A^-NG$rl4tcpS$)>fhfVFq z##+6gQV&N@=t>12_)~unWOb$QihO=X=g#g<9Zv`SXV1QV^zh-Tt$S4z<?34fkh5$M zX-Vc?ZR|x^s&}>(n!>jJ7s~B+FBPeim8)qq7-APE24Zcx=R2d>S0_0=xL~M_FTecq z-FM%8{`~p(zyEy)h26bvn#{g3AkvE3S)n!;#YQvd%{arBy?UgL4{aNnAI(WAnABcX z?Crj3$ix_rHbA5^AzzFVM8}3`2oiDK9GkL_*mv+VjXxWuh_Gc(hYQUK#s*Cs?h#8o zdO(ooT7f{~8#?8ND9>>j(54%gFl;(dPU=8OiaDk^V2FO_E$*R*LJB_|0?>106sA$0 z>k^NZAm{+X96?^eDFG0I&EI;uz|+Og4G4zH{+(-55~xMNOsYxGr^8SVZMh&xS5gE= zY?EHkKc34CV(k^}_YdP9P9mJt#mSu5A(;`xn4p0OB^2Th5n!MJpd205FE)|F8BZ`U zX9~J0rn~}92HH;y5(E%{p945C(3#jd0}Ksr@0LkaCRCTs<OGi{K?ojemj)szsW)_4 z;$AeD54UB>C~e_MIJ^ZosR~X>^hX4p4~P;@4-F=Q26*_%R#Yv<;F#kQ9Ku#20`XbW zv~XamX_g9{Y9R`ljw)6}tsAd&-I8d_jH84Z&M`<cGKcbManWPSD1c)CRI$#eKp+GY z3umH4se^cq8Aa0IG~Cq;n!Y;rY2yi;5<FsLl;!~D2xc|`h4}HL49u4*N(o_OR}0U4 zMFijs;8b#FXJ<lyM{|tw1SeU*A9TvmS&UKsbY0I#wi13c8zo3XOxp_VV7khHp+}D% zB{SXB2RB4kH=`g!ag5H)pkQM<Y$(Y99{PdBg-#VZSqy3MCyn#~T@WOCj3&}d2cpcN zizS{wWZ29K2b-sfa{_Z(Y@Qc*B+%MHOkpSz*H@m<iN`2$%K6D$Ow^gPU6oNfHc}o^ z(!wPorYRW)82BS(fdB2c-qD_%oV<Sh8XFuZ5urh}k%F*-;?YTvZ!}}(8--kQ;Gs6I zCUr>&k<L{(PGD3BTDVc#0704!Vn&Z<adi%B4e54~@(Mi+MB*oau!Ua6nz_gVg1jO{ zzg8DRG<3EC7#NB+blm_V=#)dk05=*xqemApT_UBlK{zuCI@wUd5acd1fOqR!Ym_X2 zban&bLF8MfL^p0=$a5SW(NNfohEsc2TOfMw(n*=ejz0hgR3$Aakl4bRBzNXenow=L z06nrG-kL0w@RZ($lgevJW=CBCYE9*MI9j*gmezvs2O-s5u2j>UVgsp@yAVzV8E5e5 zN*DTMI^FDTUDcZ$wT)}D-f;qknu1FHe05ykY;E=|E5|Ae#N07Q#G17g5Eo!PA(FV* zrV2jqHfK=enMIVX%}rs#U47fTg!LjRkb#c5!<oPUlFv%f?MuMjdPL!jE<8LD5kl=( zn_F&yQ3c#3;OT1Xhnmc<YuN31W>Rk^&4i4OhjN;=_GbtNQcNWLn#A`0Hk^2TrYer1 zXmur@Y|`>)_73o0`I~?JX6a_O?1D18Sz5SSa4oBM2?f1WKj>Be-22?E^3O;Rm?*VI zIdnd_7~PEPt;Xy6Z1MPNJgN^Fk5|^$2IGNzxyTNu<HglQm(=T<y8SA18tR7=rxQnH z>vCmzX*3)xExOc6YQ0IOb(h&#+o+!uAJ+Rt3$=djykjm{%Q9%<Jhf0Hl>M6H_TH)6 z&~knJmV>zg*56F3_wTQ+%~$uxYVQoMa#^8?i8F~>35c%Vx^DL=m%$BpLKpvfA9$HF z!@=dC|INSQpzq)Do7WfTXQrQ3H!0$KyF2@PJMBH*`p`9<V~32v0M4uJtxb;k*FshT zv%1PJEnW66<(D^3GWl2CdRti3H%7HQ@Z=q}H=G9-=T-vcmXZu;TM>?2R&6!@XC1Yf z$|o-B9ZsbsRi5}bD`$1ppMLq}7c^s#8i?oI$;q*YqWP9M*INGw*6i~~M1|F<p-j&o zC3Uf98|7+pH8OL9q060XxShnU*3QuWO4x#{G2f(gb!}NmFh{d2FnzmcE`0Xcr+a(5 zj~+dQA053sK6Xx8dGh4(cvK&X1MFp0x1-C*awdpk$QI))*ZvK6ckAnjls<m^*eVhc z;=OzKaArTs!jl|DVd=K&@Z2pg1vnV?1;f3E4<CH>_0#?Ry`TK_#~*(GgHJyF+5SQO zfTz<+`xy3(65}e5FvBnV7m~><S9d<RvGeEb^xWYl@iJkQEvXX%Hsbyz4@M!$1%Pl5 zz}qUQ_i42uN`)nDNFwa5f-(fju7uN3HL|u6h*1i$Ny5M$r0w_5&(6#zt4j3v&6{mU zaOa8mVY72SaH?2c#gi43oj@hmM%88lk5OHFv>gkxV0GDIH_kB10e(9Fp#$A0FofUi z#Cd>d2oHqK@QYLz!08l}AppT_6kRtsHtEtv58w$(kcdYEqmWJnM3q*ZAo53^Ihk+s zsxh9Uiv=?c$uMcQa01<I+}H>*hmAt?Xhz4Njkj7je!ju6MQ22aH|F|{O-Sh2Sl23S zS8i4$Hgw<tV;U$)q&VqkIxa;}SIb*%<)JMrCL}~RN9W`U50TFExa3IgpIh>ULRwf@ zb0T+$-`zbuJG0$*Fp7=$Od6$Jgz_nw#A7`%Qci7@qXP)Kr9wIE^_w>g*$U~`%|FWL zxocgBsJKl}7p!rya5aHwV<l;^b%+sy-~6=K#pa)wD7N}rxH!dOqgWV^>g_dZK^Ow@ zA3|rkErJ3%4dF)wkzx)-lHuxyRBDVTt}f^(SqMZpmNOF~AQCX7WrBWjX@zFSDaXbT zg+?LGa+wC1R`sKeEFzqUebOn7x!l2U=5zJ2LR$cT6awOIq()U8>-nJ<4xorDOM@Q% z(?bv)5RCtDL%9>`MtR4ECyr4<l`{Ya7WwHo1<4T&KrrLX)YE`7N)XBFa?dC!IHW6s zct`_Ja0(=X{E41`jFH7mA;3TiP=W|hqMT;4nG1Q-GzVSGf`!vSgb5l*Y46{^&np{s zy-eS(#BxFpW^DLn6`-TALR)j>n|f<**6v}51`*M02tq&Qoj=&L@u%Of!xe<v0Fh(( zYx1m(2GO8JVU1ddZlb0Qg@%|&TyQO1I8uQJMawZoZU$qEc*4hN6s2C<zJ1IA2tW@4 z;P^>Vn8gT5T8u^(9-f35h^vs;A`&7*VkwENZU^b&A%Z!?=!un%2tmZgXy*n%*J9|} z7{#2H>BxfcbX^QU7Z{=wWHg+*+CUhz;1@(fj6!tGf=xsy(S}VI&VOymH!##8c#^1C z1aM`59%49&Q*M6IJN-#79`m9LGL+FkCmu-GxjiNBI%11&Z;sHla(;GR@APc+=*>-~ zPO<f)iCcn9sC7Lf+WrwH2|;(3wvuZx-&`YxIk%m<@UUI&wPzWAY+5+Ft!87R#|&R3 z0+WL#?VG(#)`d+AZ>6<$D+G?eeEHJq&JRpTASLRy%fD89Ne(=>Yj|~eR<7{nde9$; zmua^8=NDU^9kYe)_VEf(F5jMT;PQ~VimLFyJ06f3K{4Z;(Zx`CZ%acLg6;|y*}BTL zH)D)Sh=pv5cXsQSU)S5K1NH>lm#BqudU|3VlXDVxd+qlxmsgfHw|dUfv?BHgmyq-G zv*}gkfq1FCQ`NizahM_D80FHR**n1h@&D#8wmGN?kY>1&P#DV#ZT@&_2br`t_ZF8{ zR#&PJWo%K}>uXKi?5%ICZ?0dC208lkuO+H*pb)JMxES(rQ*n)kqm6bfQa7F`mlqd$ zTA}Xm?a8C6;)lJ~{;GzqZ)S{eQTkTb>h0c^ss-l}*Wy;VE*@+zxL%<HY1LAg{TgH| zq}HS|D!<LunlR7%2M_KWQa`ec0ka<59_?<19#wVgYyWn3zj<xmLtQDW0LO*h296F) zn6rwaeYVz)A!E#u%IsPO*y5fU6-1D7yB<{a`F>K_Yhp{w5a0lDvTV_>QpUqkyJ@&( z?P_t#fT5-Oqe`_Wc!2f$7h19vn%n$Zc_=OxSpm8S2M3=0Y_&(;{8tU=?DaM_{cqjz zD?bdbPU}FpzOLwnv$9b?o#n12XX_r>W{Ck_*JLQ3`mjX(8N-XqbFDis<>N`cf`vyQ zG}oS1A)@fanly>C_Fc!d!C-iK*+-OPE!-~9G+QeENq|)$g;rgz7Fq2U@G^h+^!)h? zw^kG6xogqNJdp6r1qUozEm;W}4h25nCOD)8$%BKP{B!>O_up4GuF#Ym9PIb%uJX<9 z(|oI=Ns>t?s5))1(!Nk30rZ%ih!_Pq7-iE*ORy{5lt-8mfhY`R?)aZVa@0T<H3t5N zg6-tw#Qi^2q&3<sm*8RhB`yA>00e~}f~RG&9#k9v_?fehhe$I(*X0|#mIFFGhh2IM zDb9#9A=Q*{zz_!Fh;X*Flt(b`g^h;9$T7H-ij><FVzAa&gkXRq33wtBKPd!Jh#qlt zI0m+;!hlW?4+z4UtTn}>Md2;Mpa1;lDB_h&oG6A+01-E+2&Qa+QGt-f3}P!TaUi28 zx^Yq^kWype(ef~P5N}&_1*~Y3H}mE0fi3$RSzhswtbGv!fMdoJE85PkHq%}777>MJ zhY6MAN+y=h&tw&UWWxrRB87)ymN@{C9~Au2ti`4tL`Pw#1i~vt82zE}7Qa}OK2`KE zq=pkO9;0woK}ndS$Fhknqk1vQH(h#4;qB-1QH&~HTfMn6L995h+u1N+Zcy_@3gE{R z&*Ne2W)y{ENh~@m93z6JHHwZIqJ<m9%zv8_3e%8h&z_lmLlWrNB$IfOLxKXKHf@Js zz;CYkOja7T^b0vzf(K{-&7~?Ng3%D`Cd;JT)*xg#V-%ao#ej{VmIkWCOB~KarX`IJ zZ`!XLasWRt%8<l%(`}Rz$?3#(WgyN#vKz1hxIvt)IAfF)Jz5$Ju`ANVf|&zxj9NIL zghioIn^=s}kAXRAF~pgKPaDW)Xh;Z#w3WM7fkdc9A;llD1NrIna7Nd9IXpbHOEAh- z__an^5ldcHU<jL8lOGI6M@N`BDMr9UWvK=*z)_46u^yRA#z^spCx9&`5CI0-Or;|4 z3WM`qZmEj5f|^dU3Tl~TcKC)r+B!B6<y+hJG3msmYcyFh(QtHnQ1DBd?xRPK&@s>) zDV**DeC~)uAf!P1MC5#v2N}Xc8yqBLu2P${;Kw7bFhB@u={JOppTuJ>$}<EY7<g;a zt7zJqr4uK%_?End6C|#TV(T==G(e$Qix|Mbhp<I905_G8WS$5J13l3X2*z7V_=%D( zhzN-O$ZAoHh6v9Ph%CAyY`P0j#D#}!DQ$p9+li|poNz7QIE)!cU8*rdD2AkwLO5>~ zp>C|Bm>O*HCovKPS#*u700W)nLklFDwVh+Eq~s{PE4#f@=O}=gTAa~u>G893HE{vH zk-ZBv1A>?_z%esqND>r_@}oSIL~03JtvKUhqDu(wKF^;&SMXZP$|xnB8vs(PtG!-8 z#AO!+1GR4Z6jCL2oZ`KiUTv(c+XP&`nBLrQc%FZ>BtFxi+x)D>s2eMW(#k_wX<;Ty zh?wI%Fv_}3fEy)Ve;cT7zkCQk4h?<`mYhBCqTaNtjgcNM@iRLQJ=k<jkPJ9sW)d+c zhqbX!N|0|!2ppXu(~6BaVx^*O?A-nb|K)#);oHOV-}$?LYhx`RCS6)-KUq}2qO@3V zcU;fvn`~RV^+#WC7Coh=S4>|`m)B%uVN}1aT)#;*9u40dAMfq#)*D@`>uW1(^;=7e z^|5H}bUY1ZvHb;Kt?T6avTbo$#kt>kXt?~?ir^N3yMfb?%eAVR-LNusZFHBKTutkJ z%(WF0F?F3Ak1j4RPR~xa+Gk?>!~TugSzf%Nec^`vyhv1kgSalwy`9~?jov1$n_Jt6 z)2r+H6V|Rt?oO7{+DgBDSaf}TO_@2ox|W&);k(Rk)O*17SH5aS>YLI_8@+XpdDABk zCM)x0v&xoradEEPv00(I@@CjjF)l6NaH#$)Q@w)4HpE(jE2vg=#bYzURHaI=y{2U& zloJ}pqj6pV!tD?#bhF2q`}YnNred*43(h}2@9poYpTV%+7j-+Y!5desdgJKm)oX%E zN_nX#hHn>k?d%FJJ1kCVF@(-LCg$beJk@&ionKs7D96Vq8|xcieD#&|4*P?}`g_aL z(Z0!gD^q_DxwX13&;D^}GPQ>mXQidhN4=7f@BFuaLKf0yZ___KQ%hwb%X>KJJ1Xhg zAZAz78&$Eldm#4ls9v(EKTf{3I=fk%Oeb%>^~960-ybmKqORVvkP)?V-ab~geM_(H zSnTch+Kx?SOH_^y^**gI%(P9!{93(kgJ-8_*H@19_1SA{s3NMLYLmJ8w1`>|I0fSo zC6#T;S+U;<#6||U%BX$%^eLJ4zUllW40&m_R3{<(1*3K){N}~xVvBKLHCgDUFFyoL zIaPRUANC!wK<qnqAGQoJk$KmW71vgKRgx7rfMoB(oGl3g=rl@-Di$F&zUKTEH~1qP zqB8`fDEk)^8|!PYULBc2p?&}RAHIC~!W!{US3p^J*30&`vuwTpW+FsE6<HB!84_$h z3dnO_F(*2C;F9ws!TtTc7cZW(Vw$w9NF8a8x3?P|;ytn4|0QriLUMBY+0TB)dB;l1 zF;Om)JZC+{&$@Hut5>gdS!7yhPo6xHG5O>tgp(r0AWLMKkdsz6wacSu0i(QyV9V2v z0{|zWIirjw+d?kCZ@)0Z69_45nI|-;ikyatqstO{_&ER!@nN%KuaiwQ;{?%3Ng{$s zDZ20-F3ifC*RSpV>uYP0ry^g!dZj%*IYAscPj7BMfA*}t5V5{~|MpM($zjTyDoBz* zClk7?3kohau`t9p)rG+*L~BwwW>nXaLhF>~8Hk6IwDCC=u8S=Sg^Y+f^`<hqVChWA z-0RGB5Ir^u6UrP)UUaZaxM}N_!uq^SoprRVS8deqLR@!0BIsY85j=qE?+Eh91Kt*9 z8*v&~SzE7D2vtc12LOt>j!SUq0+hS7n9#rcm;bU+$UE=6BO#>Tdh4zH0XFnZ7GeSv zI7AYtrNk(NT7d)f46%Ya6nMG-LYy`_)lZ15#4*ZMpe~#eJSZ`pR0vARsY6oem=SSe zi(M@#Ug6K_hbmHlT118{K&7G{I6wpbn5K}!GJw<GVt)gkcPRA4)%XwK3A6K-iTJ=n zR%pg!ejy4~dbPQWMug{zhbndnYNHLrZH|Qj0{F%RXCUEZ#b{Jf%QQBs;%AaiM7jiG zuGOuDgH!mgU%&p~gAa&jtH%tYZD)H=vOV&wlHSJV*5-D-G2E-~tE;to#I%nms5R;x zqO@&`*eTA9&C}B}&mF{_o!z6OSM`gNYwJPo9UPvV)L&ha3eIHRnI^3~n*u}JkTKbS zixINEQKh0w#3&p+QxD*obVGQ6r?3YiKikIcxxB7>dD&lI+wfR)#uJXGoEYKa622tJ zc^)ees!Sr~!R4HjeCCX@;Wnd^Tvc`Zx@RVlS6YHH2{9B-2!P-uf*FE>jdd*?5d%E2 za7N8=L%h7Ahclw1HU+7ch&*`kAR8}`K!V&ei3B^-EM|eA6NCWC)MDsLB`;#qnV{H8 zx$-1F8%@HaHhG{BJ$keNkuw>>Mswno97YX^s4KZhg*j}UtUPFIj&Hw(juS;Jcn~SU zX^4pw4<a^#>>7fzC|&$Farv@U9&=Ptq9sBn9!aLby4c;_vbJoq9M6aHcw{TJ{nlp% z>IGZJQGVapY`3;I&(AK^l{B;ydcB@fi(+~8=;bR%vUb;T6t`fhv5hQRBlU?rZ0!W7 z%$4ZD{=LbV|5L5fAeFq<iG6kH^_y3o8oPTtgJJ*r=1NgJF7`GzJP7J>u(*Jt%ROFs zO1}H<yK<svsgMUz%L61cD{m<zQ2A_Uys3L(t6N~y<Zkyiui9NviahXengFu=N>-^d zN@vuf&_f(21V}HsE}}_MlPpqh$b6w>7AOIb%qHjd?;SWJsl9uLht$~|JT94L*98!6 z5{_TLIXt-M3FkO%D8)b5(7Fy$IGM|Op^dneZug35aWSguQZ0~p6@(O=w%`3P{tL|C z9+v;gU;C|kl2;ulu(~=)j7yqyY3v97p$>*aT~!8eH=lZ2UYFPQT?het|70|_0<Nc5 zxt_T=4leuj>(;;e%Suc2L|R#)kOr!%;_6M^dc%{ROY2a@DNN5x$(Sm7Cy7epglEnd z_Is1KvMej>^#SGetGZh*>bpC^YddM0xh_HzAa_7o%>fEka0nJ4n__LZ(^|}iC?Lfz zewrat)`K|<ohoz%slwpINR^USVJKQevjs;q+C=6jtx)K}##YP)f};a21_>RcOBK!b z3mWJFHjbOBuqvHOHGgO>J+=D9U`9P=JQ?d1j79UZCOa0hO5$hpt#GY~?1MA|L%OOH zUC?deaC(`Bw8E<YFV{ESd%gPY%HCG}&CIpcUb9j!gVe=dW@}@q4?Ww0M#Evr*1O@= z8a4N3ayS^b2l+}}dKdEyXw$b)uVlAcvk|W-fXZ%F(b`6R%CZgtZF!XQb}{}7o%6N9 z!Rm9@GFETTR`oQvY6XBrXvNs(0&@$ePJuFv0x{`0Wf%pgRzeseLP^#tHczAa#&qM! ze9=S7<{}|6(Y1^M;=0_Y5K&9S^PmE{eaDPH9X}-QbvO?b2#bg|5sop3hud)`n+^n} z>ZCooq6FXv!7tk{8>hf@S=a5vLHyB%fhw~61bE<_k$hG#+;u)|^2=2TLD#jc&@p)a zvBE2yhWJmjBv^5}fVOCmq9`Y&HAEq!_?ctSs06~aaQ@@;1dYR#7{V_`2m&9DkB{l$ z)rTK`XiXVqg~H^aVrx4u;26$~R*|=;Aq<h?fBD+}R0H7HsC_4#4~B?D34aKN!XNxJ z5H}=si6!pg4Dj42V(94-v>qWbq01RV#DQ++&L|v(=K8wBEl`CXFr<qZW+vh@BK>fF z8WmK!PoF;Z2!HtSVQvwg;_QC>@y8DzJ;H+%kNih1inwTt&bE=(E(+`qYyn2&K!BhW zA(D+7h<r2U3`vNt(c}a(4VjC~FCw18o7yPXg3gvUhN#uXG3x*h0cEZ-KmP<Tx@{zL z5g$r_{p>|S#n9%9OQ1_5*@~w*uN8PGv5pu}d%9(!IYz%4v!4h`8d;a*6bVjeUrU1& zW+n&%rn}e!Yyp%MTcXApi@^<PsWlo%2u2fB*dV}Y_JMQ(3Wi7lI92HU*TNMBZLBK* z{<9kg;MSecbV-3op+mGh=Np|Ev{X?NKQYiSpOM?C!Gj(>ERvE9IZRG;<77qNVy9n= zldKxEKcI6!p2bK6vu*$zN{9j4@I&aQC!XNc0-Tgkg+VO#<ivtbunQSN2@3Ieg^kb5 zK{}mqR*0iJP<Cz@Z8KbJN>$*&921>#AU`NZQRswZQgpjuW0b2#L7a@msKQ2;t**sJ zd{STJs!JUwStmkOl8GV8@n=FC+x*A#Ks?mKv4LpN)lvxHLSrb*{6R5a>K{KMpw>{l zLX6uGoN*o?0u(%ma6~vt*tDGpNZ{D`Ac`(0qDzvahg}GN@N0z`HaYM7LB~dwHo3wa z{pDE$I3OFy5dI9I*lZ<%>CkC2iS`FmU-Gy67>I`CArW<e4W*fyn<mB2Y!2xHJmMve z%}|ttKjL_je>_|Y=!Swhh#1o)!U}}iBoHM$T5Qq<$0JvGbnmLdk4I=2Ha6;lO+2G< zDai~Qq@`iL{cdm7C*VToHqE9W+YSb7h}tL&pldr3oEeQm070pA)Q`H=iI>l*)o>~p zLpUkXg)^bWAlG<6Oot7fV~8jc4na)U+?RW|+7hGIQjbdox6ZJE&dUT95lH5jLS1k- z7F~i(%RC!K#Uj<ZpyMPC+O*Vfbi);-mN<X#Q`H~TXOzT}6QCgstWz5e6gDL_r}ysN zqns_H6rz|HSI=gxmUh^fi(vDyrbY=V{!HuN{ri7E^lu5vzx~^Pt?sfszP^FTR(*qN zX|dicT&!<w&XyMIFX7ZTV;5XIs&ZHAJ-X}mi$}}ut~D<!f^EN9>&8+So+8#OE)LfH zx?8q?8CqOea-%&tIdyw*N3)%{n0S;;C-tLM&0>jr6x8*}BVo1PByyQ{iQ-ya&{b8v zzD`rU139Y~dEDpf9uCJ-5ulZS%QcP7czfS?tbzpD5ry9NkE`DL2D#GQHcb(!ZAiLI ziA{BxGmr(DNs>hK)B$3p_4XAzcr)dB>A<0~O{d}`XqnlRtJ}tH+?dr$Nl;mDI&(oD z+MA;O$wqq{x^9f4!LYu^Ab{DzR&TRut}oFRr}}Vis22iiQCb{>QQejomldlEFphdP zl<CXM!R4i6w~%M`dE|))m4nWPf4s%UB}3?Kds;WQGOa4o&T1Z&%%TJ?udLA`=<&#o zR$q!(Uaj|s1y)tBtXrH~DXQ6$`NB!7b=g{(jBW0fHf&~3+AE?u4cE()s*+6TT70}R zMO-B%F8^3VxwyD&o013c5+2b}ZnFCQ%ghUCCN$*-ciOzAU$X$wef8=UEoRfE=1I(l zv-X`O4}j)L-7%!4d00Od(vHaUN%W5uviz~_wzz8dF?vgPtFIl$lGbJufnd&CUM>9E zB~w4z($!vY2@%d|{Oztd<ze@3MouBTB4}s9+04~T(dHcykPX5XoKF8YVWtANV^__I zu~zpr;kBr0x@y*2K~5+2!TW~SKRo8ZMxi*hgZ@BEXSq)9S~wM>c<qux<2lDTaR2`O zyvD>m7G#)&2fRatE(?Gl<^&?x5RK9!u8gW88r;grQrI*Mr6rsRR+z1pYK^tGMCvUI zvPl;y8sM_T3T7hB{n{4dA%2Lg3WOjL6h0GC1LguVx`}9SV%Povct}4mgp*^4_!ADg zQ;vFLi^Yg^cHu;%i??tL$)0iu13#(do1qjES#&rC-2`3}*#eJdfCt1PA_PE^CB!_* zxTocVE`|?2_<#e-Ocaz$g?fAY?YH@XhZM~@XBdrsNK6Fa0_Q}!aVB^`EO_LZ!iX1t zdng*ESsO#~6I}*yrXEmqRU@`&)+RJSxt0<Xf*?bDB+epc>CAaOIn1a6E5^L3yH+PT zhR8--%TJJyjRICckj7XR!`8{-kJ|yvoL5~+3mt=QW}oL;-RNXAnv((TT*a+I6e7tX z96x3)Kw-iV&@~FeMrR;&L<nuM3%RQVhy~6fI-aoU(oad8LBXjDu_T-Ns!aN$P#2=o z(j{vYPKxrdiN)T?Vbx{rn3`yglMxKUhm;ToKso%l{h+Z?pkkSbp(v>-xpVNP2Xl*Z zUP1wQT<Q{zA4M0DpjH%CO3Dmi3&4rviB$G&4p>L%LPN~<f&qU@C9)7tx+r80f0Tga znc8R$z>^AX;(|jkt0hQ4mlaB)S#FI+oEzLDo(ZJ^jwg;asrfZeq`E=)?*uFZa3VsZ z#}G=g2&au8D;W6Dwz7(pIYT&g<FHbJn{GoC8nx5r>4p+NOX+PX@+}B)Ljcn9H{UC? zn9(^vVaq}7EfF*n2Cc3ku|o&~abXh?qM+gi3O&hH<~^yPfjD9iZIT>waez3abN((8 zH_~m!>yg9(;Y(NaAVL6U5N5!o&;y2&2X4nYfM5&6$#|k`C{pw*4^mv!6`fHyVrS?s zvli%P6iz2P!HzjR5J@wwhEi{Qz$|+yPRvB285q)aBDrx|Zr`mn>_m}sh+zl{#FEew zs{_kTyD8wKLTJROb|+b@PckO^jXpm|d*r8!2Sc5n>&w71DXSx)tkxl@C?&|H`b=>B z)``oD!-wOLC(hR9mSw?|6ywfPFXpzmDldO>euV<q%#f+cG*t&%xn46Hw)!>VrS_&y zgVJ!D?SRNzSe35owlb4j3aO=GF4X{zp*dJQ5Ja4iu;JHjmJ1}?>{#=upR@$m>f^C> zLSRA*%wzH2u7dUTyg)WzQ1mMyEfW-~YW8c5*Fn9?i3Z{wu7%TvsBCPTw9)*Z{k^|u z=-b2cfAY8fM$K-WV9Q8FR`1=h(Tbyf8Mscrm7TUzh*mpm=PA@0ZO3E(cekuJ$a))V z>uZ=zRO(DgslRqvb6--%mGtes`bH3bNvSh6P@SND#At~FmIoz*=TB{a3pKB|x0Ny& z>#S(&cF4WVmsWY!Q>`jj88lBT2)NC;!m2B1smNaBf7_dN+RJu8RaviJS1z1WwBjzq zw|h;meWVbv(dWdl0dC)lwA{2EL^2q|2Ct~w1Xq9!B614}eNMqyqy`bmMvO=yZMI;C zK3%g@yYOl~kCRn*ewW*tS+aSxY^DB!*@MISt{`V}a4*^R3UO?47_b$e;dTxqvx>O= ztaGitYN@3=IJR5L;`L2^6fm=sC0oUCeZAQ}63L%X%7iMvnY9lO=TVyLU+y7wCcuR` zR^WVg-?3)+38&MnW#Sq`9hI1X(7<_Y7;^zeSD_e?!oU{6%w4oumXs$m<z$<(Jb{e1 z=;ohlLkGIp&d=(*H1q=${+J{81Z=v%C^ir&df<rWj%E~s^k;V<&M~6|vBB}jZA0iB zh^!|u4--osPAsC}$3Sz<cq<!-Zt4&-sI0Y@fx-UH{5N%tvd9pA%%VUHJww!nlNF<R zhQ(DOprddM5d|kUU27$y5y1~wS9`kXm}3PSyX_T?w!j;p(-T0%tW7dABa`~Yw}RR$ z+B1N1AuvZIN<d_d@`9k7s!?gd=E{+|V+$wcfpjB9AzV1I&RjgCDzbnBt!V46f*%D> zAlhUbf8(joIwHd9#Ei}gK<s?rAx`3n^j1%~1Tbq2p<{yt2bn<(RMnTLZg&zC2(?ng zbVNXgC=bGauEJ4pii-$bRl{9+)t=Nz0xNuFMFld7O^b&W`i&+zbb=UCb_ozq=!k|O zWD&)JLJ3(!bD)b(N;jOu1Bg5XolX^_4IaR+C5VlOx|H(`rO_))NK4xM!#g-x4;a;z z5J*f%Ap}G};C3h=L~a9JEwun*2q4;OP!gtYOlScHL)y%Kp!DAEA&`zpC$@yIP4>j1 zs|C89Gt|OkB12IHi4uUJe7!xkqH_$ynKIu10}54Sg`i7TdbOl<WjIwq3ekGUPY|65 zN)*a~Aqc>4DDGi!5uy-eLsoBLFcb&0M(Ht1L>GcWLwG=56pO2Fn;5b;LX0NND4{tz z;~Ovpf^*wYbF-jSw{D!rKz{(9Aqqjq325VkKn@NLtR@s2(OLVQIrX5+0U|NVjiS`Y zFTYtYolX>PhX=(JPy!M{c;ZzU<iSwf%ku(`-zb0JnJGA(=vq>cZY82LkvhN_!XKh8 zu%YQf=;s)OEJK%<^^EHh3&`r`k%Y)1{+Ng-2@OI?q>@rah;B3*(x!_O0x+lT3a_IF zCla+0p*f%%B%BbowDHsIs7AQ?vSU+1e>@ap_BzA>qBe`7!#n+q!Z{G61a5bRcm)SW zX;%5#Fi;Xb*g)7oMrk&b(I6dA6*j=_@N>S?g95<@Fo=|)E;^%`P$rVY<i~X2F&fHU zKvCxr37{w>;k<nL(vl&Ff`Pf51mX-J9ucFI%V2PR8YQLek{=3@;Qn9VKC7c;TRScD zrUtM=17>ZK0H-;65CIKku>lRbh(=>V>+m~iPd%}tNE8j6&rTK2V!Ja7*l6q0-gFm& zAy9@J1ivdwRoV6b_9`=5C`QRs2t+q-U$l%kk>YPW;^HSB6oM#lrd4m$2Et6Rb0F>o z0o+mc7--Y7i0IU0U%(H?8S%zEpAk6zPz<G<Ah9KufK`5VUCf3!V>IG%9z7J|AcBAY zKmX4m-yW9#xBuzim@U@ZbR2Z$t(QswzCc00>NStLb|xf#u&QeLku-5JwFux^L^ZL< z&-SmrFI_(&U4?QzyVk<%)_RM$@i-jPZF^~-O&B`A>Xw@JCxXy**@4TBZvXPKKEZo4 zbAhWrb0aZoT0$oi^NCm<)Z0^)T7LRJ8vf~3`%?ici+Hq^-=(Vl+}c{`?)HnlwfV0* zB02(5ndr>1wiMPvGKDK`qpJgMh{*{ko$c+KAn4Hsp+OGmhZt(U*GAuoBL>$36j5Ua zl*F-g0cPcEOA3P7zTDeb7yoK~GJLguqRgdH)a?yAW{fh4qLr@6c)Yv2&s7#Pv(&<^ z4G%Cn4WZDCk_}6Ra_~?8YoV;nuImS)uci}r9JRUN5L7R!C<M{9f5P+6Z96ViQshVY z;%#qh3+HxeRL=a1{uG1cw?sOilvh~Wx~PINWKnmr%~Ww}5skKiB4rA6fs|TcSyAl$ z0z7>9P}FAMxrCGy>E;)P;D8SRLKU5=xRpm<Gp?#04hIT*dwZ)n)@|syjMazk{3oq! zM<FB>{3x_Ve>^k<;S5ULhN~q?U%!6MJqyX5#0=6vP>SqXLE^SL!B2`Ivn+gc+Aypx z*S!Uh4Ztx#7y=MJK<J51qg|b}=_ueNTx*SZ*f2*5PhJSjwo9|3s$?{XcucEmp;4<S zVlLtV%+XIIQWy~NOSQ8daV8uqB>|^|U<h;Pe8l(m_9X|=0aWVvi5c9xcP~7Fh)0lq z{7mqqd03Bah{v9A<TjZHbTSeg#KQ!Llak6*n~wZAsv$naTmViv9?TH#5tJD?gbx=N zbqfWU>5mjwnIKyM-#+S4ShqfsflhPSQb>?krz#pSYo#c39^$kd99*md4xF5v<oi4r z-n@B3MOG8#m}5O52WU<=Zs<U;#d-&bIH^KUq!9jdE1uARjq-Hi;n$*oXehmRpy@8) zLn=Q3YT-crwi2eca*hqqBO+`B;i}A<P?88Oh<R}uf;2lt2@-Rqu|X;yR4&@$A_ee> z(Mn+`bS?1&s6}ZC>ZKgoq(Y0CU~FmWfe=K*sSSmOw4mdM=u!(;R{%vfvhg!gDH3?P zK_aeA7mw^Q*Lek}fvPY^3EvQPEh2%yQz~JAqws_*h)WPHW*1ir(@LQSCv&{T)5S|e zXDf7B!j{n(qTjY)2pyY6cY0c1d_^QeGX{X!bVP|RA80lTASkxA&@ptLOPU#E4iBA{ zzc8&Gbo}Um2K*q}AVzK1LesT}<Z4QDd?vz#F8$Pc#Ki$%2&WdMRNpG+HpsTXjf`q3 z0qH_;8igb+K|~FqM<BXPYi&v?3=n7168Bt=CwGT{AuTBsLzDo>`FZ^b2Bx(<0T5uO zn1&Ff5VIk;448U)BoHoF6vFXi!%r2US(nA=44{DEc#P`e?1thq=ptf>QLWTrKuib_ zQq1uo_Z;4uS#0Kuh#{PK=rqbbfRaGsXH3JxOeYiFP|Sq~q#FvL4IAr*;wJ{UAxLnl zbR&D0A@l$}bQ;n|4}ef!ZnXg6rLl?gUo8<7BQ{86(}I|T7zIkDqX7K0Q9`qB6h=vg z9INs=6g=KCXI0`y3{cC-xokVXA>zjj$BC{mFa*#MG1$vDds{2*b8In+KiY&De+<Q? z&~-tqBO20$(60?%KDE)ZvQ*zlhjfJ@!)gOVWwyC(C?;YNGdvJ)wK$XEDA$F@TU`uV z-2#YSdk3h4PN)4Y&TthkJ-Si~SF3P=Ao2&qE+qU$yVzqikS>6`PfXmg<y<Mc;kCbF z>Yfl=RK@c$G#p8&7{o=EZ+N;Gr3l4B#@QUN40B^JtTzBUAJFkjX}oRG&ksU|*!na3 z4)AaN_Fttv1^`l!SPETsbUDW-kz_3;W%#l2%uq&?=tv1HS-@Y$Zh@eEA3sjoK=_ja zBKWBVc;-I1Bh}TnYKr{AP5m^Ke~KtSQI!HurPqfg7I`Sec8x1{K|(q8IVcO!g{<1T z^)Hg%SX(cJ%@(8TLEALV9~&T1Gzc;;(2N2&5PkxTwh$qRO{&&y0G*WBAyG~w78}$S z8MU1u6l{@74dqlMV-jNs8zLo{1r#a8zg9moR3Aw~=@5qmEyyfT5<M6|tQ*yqiR-B= z2`?n}Zd*SOurwQ74n*lt?(opmI>fBjCeeK6Lvo_aLpo!k8#OssQ|a<g9z1a^NJX`} zw&qEU(f(T$X;5NtWkO#Kv_(Y;{j_zIq>*BaUqnXN*6RfbJFM6<8tc*+{!T=xTctT~ z8A8mNpp&Afu1f6{YYf6M)Z3_!KVgtV$wVPe73*Eph+XU`v5p5ZY}^Y^e2WyoA0-j& za0sIi597nbLoPW{IesA;qLU|L$4o6lVn^?^0i#kRK<hRlTta~-OsPn20e)Ul4j^<Q zV(9om0>OZ&g~xwfMEK)rfx-%AJVGYI1a0)AXxTNT5aNI!zymPD5$PlX=+VkF{{8)Z zvJW0Sh#{*W?(w8cmli**MqPKc7|fa>r(vTl<uzH+43Dgm(3LBO5II96_h*RQQo>v& zl#h2U!tuut@kEqSL_tL==At=ip%y2cR7TUS-;cTd-Y<G=;h{eWIs}M9Hf)-A#hD`u zj3VO4i9t5BaLNH(yqGbVGF=%a<;Kg9D}*5m)!ymZ8CilnfkYt$8~uo(U=|eMG#mxp zD8L4oAOg_&i6{Q22=L>9@IecwDzdux(c?q0Hs$TVB^?AmT#HkSA+y}MM-}TVLLw6V zcr>vB#AJw+A%G{$C_q=M8(UgkZ4jej2w<Z@u9Pk-_+_36%y0#eT_Rt)<`^6uC(omS zHcGVU1mQ+?X~<A`;%acMQOvaI;>QNBRNrO^z2js$8PkG{(uTqfcq#z}j%Xu-7)mm= z)QT(0F~cG8hr+znA_<szl_4#n^~F65x(>}ov7vWG5`T;)Z*eSY83Kqj7{wM&6iZc5 z5S;v^lVDWEv@QrUh%5&Dw1o#9LKY-IfX7g*V~CzEs{n4_qX$kEI>6I~ql-ru1X)|H z)ZxJ&PIkE+A{;%?<veU*U?^5BXUvFjY=(j`8g06y=+VNXM07Sf^$CyvsU}^32PHTW zbk?=-u1gI(ve>j8!gRVu!=N=g{DGK#f=tt6z7TbZL<$iloX!5cwn0-_s*ENB06(H6 zmuJnNu8mI9hanmwWhk?3G(;^*Q(w-PqBdViyB0G_IJLTIWtGCv@x!%ud4gc;x}1m0 zzk&gjN7hhH_H8kwn@FR%Qyxgjh;Rx!K#xd5h{8B;G}g6uCo~H0TG6U2Z8wCCW?<RI ziU~!eN(fqb*0muF=2s>S=`szX%@72$13P9EIQ<y3L^uXP$2RBWQoZ*w-@a%lpKbwv zVvJN6v`ULCBsqi|&4j`k!jCiBn6OM)LIf1@A14qd9u!iRe`+S41DXTyXroG(5`n|f z;iTj(^bi3A)b%GZHvglfBC2<NN^OP^;W*=lt`fqayfI|6;woS(Jm}bjU&flxa8L&7 z@1EW`k>H_(2%2DZBV{UeNfpvQ%f@eARw$1@T6Bh3m+k1+dahA&*{@GR5h-g;5Q2fZ z03umsCQ<M|vp<9MSN`f>kvX|^qrXk+%s-c%n&8<&{SBo0z`detpDR->*Y(!oy2r5K zr9Ptu+zD_0EzH`tL}xeaYpX&0Q^o$ZHwI@L>uXz^z1^Md?XAtt-iCH(d&|G8>Eyco zZQ=R~tf^`ItIMlBC(D)fm1WwNOosbX`)fov7hIokxrrgRE3MSCe#60)B?sT@#rg(m zeR5YyXZ2QleSp7qjJkBWLK|Idzpf+<b1|O=a|80=ujp@I+Oa#K6TyZahzL*zc?3oS zbw)FV0GrkjJ=ze%Q^L2as})WC&8NCUwtV>~7yeOzG8(&?tV6~VNBlylsM#^flR8A! zyXbH&la`Hg>tFV<No;=jZfk2>y>gW~D<Nw`yqw9BfCwiWdVNTKp}yg*<%IM$r*8U} zmuoA_^_R!jR|oyU&d%nrerb7XQfE~W^B=FSNfEuITVU;t`u4Brsz_Xu$@oSknUMNc zczq~=4=bytb>iA9bU6C;P5lIPmWuSY>8S0DhuWl9%k!jBdkgi<?uN>60~*i~<-w)~ zp;go;Cnr*2v7yThwu_4khf!&PgV+tQt~_fEv>*MxzVSSE7^>elMyblH?TLrAwBSpw z_sg}>Q%+CrrJS)fP{nP4l1BwLL*X<E5d{x*xrYr84>?9ETN|8|&B733(qf7!j1)Zk z2%r%E^|a0q@Ptf>A#I0u8Lq6g-Hi|QV*o~JMvTJ{fC3EBU>ri^{{8!&7ID>uGt~ts zK}@|h3*|QGJV}@G;0z@RoNtGu`I(7w8sONN=)%ECmI*C3Dj9w2t+$*ijGni@o$EgA zoQD%bAW|4O#2j%5LCg>(5rx?BuoZJ{DV39WP_!|Pes*@&DS^19b2T_6ojI~_fdE7C zKV8gt_@A_M5;I)OL+0>fFhmND4!7TS#H3o6PL%i=Z8V@$g2*wr7A}*V$G}|PI{Wos z|8<vPL(iW-*SgTq1|edUeo9b4lmiIsTHqXn6MrBf14HS8c&H_dL}7^9&i^p$0!Y(Q z6qbT$=`2bEA!w<}3^w*w(u<13s2oWb6ZMTNcB7#l9QARMq7c;by%P_Vl4giwfT186 zl|3FpI%4=UeMxM>Ni0#tkb=xp|M>V=!m)9{kQp&q*uo5=Q<pZXBChSUVF(Y%<bsZl zjTQQ}Ex=kPrZPiB!VEX68!3<}&g>){9*P&v6U;;qF)*4~qL3h-$clv&bBJyE%$JNC zuSn?$Q43-v>54O*Z#W?+i7WIl;AaS)V$MrBwhMIDnKp!?Yfs<|1P~{M9&Pj|9EdiW zyF^7p7pW(Rp_q;*00Q`c!7(?)bUg^j8l^n?LAoC75PGsgi6An{To??+jl>eq<7%@| zNq}=qMX@5lyrvKeB>)3e^k{=1l7-U=!7O!Dv8HW`E6+i&A;t}YVTfZp+x1ZqIOzDB z&Dt)snHr<$Od#sU{}6TQ#|Z)GO}czG+I2xF9UJRfiPDXSVsC?U{{cgpI1CXF1lIyX z1kI6|V#PxzJoI#Vh5(dwwebfKkA@D1G%pGw3u(OH_`lQsiVVj<ii%xzl|>Owf?8dP zBGO!#t75&GD!ZLOajB^<9;wDa1fEnU50-`&jvtQB85CVDW|Sx)i%2$_GZeOPhGHTV zCkl~FhlK_~hX_r8R7DTFhDZTK2PlH*g*WA$-SVJ8hS+l7xV-F->WjJcRwUasM&Ih{ z)T!8Ma&=|qM%@l287<X|3$|d32L-2V%y>FMueaUIn)8^OiKQXNI#DkV2lYu7UO5Kv znZu$>Rj|gN_!;Q(pHy^!P6K|k+=WAxgbUxOwj#O(o;y8rl@_`7uih4JyQ`7_5vQ3; zAjJbQ%T&p*Y&-2B0u~KX%LF(0j|UNiVu&hd^wDU%w_kr6ogPYX+B5_k{~<OLSHS(f zJ^FRqO`#&CN{c6sk;RE2+Y~rDI>K;qS;sICi(S;D017>1a~(7EJHPw8W#C)G@?ZPy zzqYtsKX$dWQib7SSl{k$XQ{Xj0Vr`!3?=p_FGxkNPZ+lvQ`xRBH#1k4@o04a@V*<1 zrCEpnHe*W0j(FLxKQKs@e3@+9iWX2sr&$p;E4p}GoNqr7TvHMUB!Un9iwkyTyG~T? zBfhQz)|T6F{>)FF94;MX-Axn(A9-$RH0SHsQEDr~x{TGu-FEL9?>c4*+-BNG4`!Ue zu(sN(ulUtp;-w^W18ATps+x&9O%mcK9!LRRe$Lv@Ww(1NTfD98%UInJ&3xAB>R`|> zm9F|$-Gr0=TSit_Y@oB@V6?um&Lf((Hn;0bzZIr@DiqTvI+G$xPVF8fo?H0^;JTOY z?$!_JKYjX@6!Ki=0q;yizkea?`SVV$RJI_th{G!x1uajl4bHK>y*(SL%MASR@Q_QH zI~i6RNiBe6_S#^#L1(ZMtZh3|g<0KN;CAQsS=084tpGWR?rhp#^x(;o>v6p%u)H8M zt84Z7dsk)Ej8bRWx=!=h^SkZ_79KD`nG}}n1@v25=*o%1&i8NLy!q&(k3^(G+=S)F z%$ieYCL$30*{|WL0kdR?s#Xs3hoY9ly6AvKctv9Qtk#9WsC~qx$SCU=q8#9?Of+*G z*3B{uTU>(M@~j%J(xWWhMzo1eMDzy-9M+|TazlJbH*T8@3bTi{S({&<nhW#O6@XME zEld`<VN{oX%={#t*hAD-u=NvDXHoLt!2>xbh0|pigAEa#djt)!&b_L#rUAr(fKjFq zAvC}pkyYKBH?Pg_*I$3lrLVsFN<z#d&9a9lg7k1km$~=e`;Hq0J?8r1!-t5py?*^V zZs-Q^Q_KGZ1!Ro2ypR3t*|T@vd51+)fQQ4TGLOTx`sn`r(ZVzaEu3jtLgyP*5d1G* zym0rX5JZG55t^MjgupIhfG67Z`eF0=4=wVLP9pd%M*JA4!pW<MZ}#dQi>MV>WI;-c z27pK#DHS3)1e0y9N+tw9HVN0o!0or+ew#wamxqrYaeyqKhX!>>L{?cx#D;->Isq(^ z;)xW%Nk6*)z1Z5iGb!>CVp4=zYZMP+hN7QNqgir@X+aSe7kN$t1RX*o46baDxI`N_ z+PinP?=<G3$3tzyiw?Rd41p-2IRFpPshjY%?1oOn9GL|f%Vbd%B@A&uc^E>MaBGJ+ zHluQGIwG!(SAaM}^hexK!hsk{2q3!wZA5g@Gej0M5gO>nLrPa^VK&-D3IW&<b@A{j z(;=LMNtFUt2}bd7RX9A)a=^ek=I&D=@f-zn)bdlAA=(p&KoAub&CJDl7Q2-4Ss=_A zf&+Ts^uW<6dHM1s9P!nwSJdK%QzFmUDB&Kpc;X=(5B-5IKY$blB0_+3Oro@`fLKgW zcsk~|<Z0sJ5(ayzWhFUmMHUffn9EYTlk%r?NsA)A@IMWPXa<Z@61&tGvg64xV9t!t zVAs_Z7r>bW5~M^daBM(w01foiYq;&%hd+QhVR9aVVzgtpckeLT;(te%A{jFj)4DWd z|KSogn-7I3?5do^(glTqAWl5GAp#7BlJHo>7O9A2`whflJ^(l#oMA>W1UzC0nq@n@ zBuHJ9P;OL<6N8-alPrsn4sZHOVT$~2iijkWL5RS$a3&N+lt%**4y#Y2oj5l9y7YJA zVeb5A@oum<jpBhL#(CWsGS?VbfeTg(N0bEqG<}t>IA9cFYC`Oi#t=}|x=heuqQydw zG`7|6@YCl!Ige0}?7h8xg6LesCNi3Vm{6RBSz2m8!RtiMaKn-6<<9y>tW$KI-s^w# zi!fnoJFl$wlsXDSC`9GZRALB47Y{-HYk7h{T@2WqOnbeJ{$Nm-opuxMZEYUjyT^LH z8&_AMx=pcnRc{AY$w^~!mDvfv>Fn~)B?}}j0X3hpk7EJd7R`M6NCi?VW`XlL0Vd}; z=|uw`3YqW_ghy32D+mU--M|o_0Z~h#3hVa=hxhN}#3L4lm@{Q~Oe=o7%2oZ{wfft? zvNvjKrL&n<3}Upb7Vh7FK*Rq2f!RP2#hW*^(ofG%B}POjF&YPwd^mvMgmCrG>^s1J z^?&zQ$5(Yzo!&@p{UKnUO{U}R?fL^;yl0XVa8Ls6i~`_BQ!79iCZ+CF^-E<lft#TE zEvFTy(r3NRtrstkzWd$py?F6b@S~AAIIBDNqF}5>MdrS>Uhj=5p7uvm-Cit=Of*Bz zXw%uXd+AMmRoO+oF4b<i@_z5|P$A;m-rO4W2N&n(JDw%|OQolrDQG{<)q|LodZ)sa zs4_L@kt{mvVQo$E)JwvvD<`L?M)wa66xYk6qiqLJwX(8|zy2nd2fTads@v5!&ocm* znN}+GAyT+WLhmN>axiKKhjw*qzxQRnUGfAznO+SBL-kTqU%$MyIK7_MUrw%mcDGea zXKQQcUj16^8~S^_`b+&DwflA6T^rPHe#ObPwfZ^@4FcKd)ek2e-hartBZr7-YdfGL zcs|$4c?*vZoZ;Ql`o@}Fii7o$>4n*4|MKGULWq(yyS~}%ZLP1an*q5Kh^ZNmC$7`h zMt*BgmIY$k*VZ>ovAN#a-P=F7XRb|juebT^`3n(N>g&ajMXfra1oKwUL4*rc5_Nsm zEZWm;&^JL+2@))KdeS=>^v4s&YZ2Fl-|X0ME-qZIL@If<JVDn7;4@1yX>kIvXGf49 z!XTT1;|QWH;PK<fsyzoag3@gtCvKM{YdJ_G)iwg7h{dyR((8}Qsp0lwgw;`>8<~u! z95%}+?dfx++Y(hD{q;mKkId1)88}0EmUzV4O&H>mgBlMJ@#yB@Vrvr%etF>oicwn< zpDl{^jHv}%>$Yuh<z)M#fAkCADNw;@i$v+SAGoHZvV42FH56I=tV2@gGKP~ZBsVTD z=^ElED-?3z=;+AK;B?h;Y)~<;*(lnNWI4O9sFq4d)%aQ#d%Fm@IMr*z1Q_LsBrpMV z1&GcoDo}76l^=p0qMMsrPoBK>z3+WMC;if{>Zr{oQ^iw1o?KJY=6~v1zQ4bx{x4Pf zr401)lLT53JLtAIJUoe)hr@v?vX4vQ{riWL$ym-FKD3*UQ0nszt<3U)7Kr>vAR7=# z<E`w$QIf#y9$LZ6vsTCn%4qF)?GZ>M$=6l}Z}$^+dBtb`yZrMZ{vRE^<hIcV5AL6x zouX)2s~6hZjt$rn6;G5+5HW*zh*Gn>x@tb`fedT6wzqAeHbY(8qgg`4dfD$o3{m9{ zueE$cp_bfRQg7_?pH7;iT$d`r<QWd}Pl3RnJ%3J{?UxCoh^hl35w<2#$X);PlHLQ= zI~>a6Cdb+zD>mex8AEY^&e=;u@+LH<m7@BQLtP+~@l6TU#@v45!Be<CiZZJUBu)+* z<%kEO;!&}xx13(Im)47n3anOldmVmtWsM815F}hxIBabwHr0M`Q13VL1kh;;Y7=j7 z=5Wl;15XZ>L2|`IrZMou96>N}7+p()R9j`3B|Lit6F}6oS=~5w)uD|APmCrTcnF#u zM9Ph#n>E?MPk-FYx&Q00zkc}maoz^8hne(&`>+R`?6va9^kp7Vj4sZWuAH>n?rZhI z6?<b`t=Ds}oGWUj+c0%4I17y%?8bi{(#Q0dUw+A@7FK1CZ?+nAc$m#EMC<@(HUvTO zSxzKVmb3sfPFqJ+;qB`_V#IG0on5VNl7pWi6hM$gM57Q4yw!~x9S?pjH;g6<ndb%{ z;0Xj>2xiBw1?PZKQJ7q#bRwe2ze&+GDcU+GG}8(g#cE}OEJ|h*KmcYwY;D^`d13-A zJ%n&wpPirHJEUX3Zt<%&*m^a7XLs9>eb1J-<{7`?{v*JtoznKA#k06nFGJJga5$|$ zNjYDgrnO$Lu0J>ED7b;>k;fPHk7BX-hk>7V@)V&t;-qZw$s!dF&$tLdkx8>-6oL*X zOVE&br7p~f0B-KAYeSNs*yo|PS%6a;g+PY2_$3@O5&pna8-{cdr8oYdaKm&s9?)hA zsG>aL+1$*OE+SjeQ`OMk!A7JiY7Jp9%W;DqQbLHgGy}|93}o>D1<w$O^{6F?9_M2P zogUgybP?(22{uFYBuox>7L8)lMNg8ki3MQhCn5@QrejE|`4GEt$-MBEDqT~6S<+%x zkx><KBIp>{GAdQWfl650-#e&xbY_bi>peuf#GBW3kHGu##Zmoj-i1Xc%!`Y@gJFA4 zta7>vuTI4)^(Kip7F{*#57pKS(UrX$l*+l|fh5bk*lNeFcd&--Puy!?y*!$ZC-?Rb zwtAcSoA#~&s>h|mKTiN<q)SRAT}|p0Tl-OOePgp;+I5>Kf1FfTD|s8v@Wa8#x%d41 zqF*n8P3pigTkOua^^S2n5AX#f|I(Y<NF~S;1hiCNa$Grklv{lwPbjK8{|x0{x_rdb ze$cj#BBZo!Q<awbF&YeQK};#J{A-=Ia_VMTRhS?gre3uph9cPi@4xvs&Q$$D{Z=T4 zRVkl68nkepQ-$CB42A<?JKvd26XQn0pWU5(=c2_0t9W!Zy>Td*-7E^~{Ot1N<k(Z! zG_Gx|YXxGH@d$2zPQSh?EKy3!yeieh!~06r{BCV+|DE6YyCVPgu>9M9>#x^(sD#!V z>+FqOhbQCfX~lVWDe}fvjz}y^D3GpPWEH`)B;Z*mx&+a+l52`G+1ceWU``uBZPa25 z=WJ=Q_E;*a+NGl2D=i;vpj-8HQR}4YkLb7k1>4q69X@KoR2kPgQHWNEeVO`Zp{Z-5 zE-f6em`~5n%%x44tLGON9-_Q$eC3rY(Gt~IOH?Qq&}ii_CGvwm%)0!C59^**Kc}uZ z@VlyM>xC+L%huU~t@C-EBx;4*lH2}V(bB+qz*P0y-!Zzptl!umN?a?|6=p&5mV<J= z{7DuS1-0c*N^3cRGS|-2Ow_vfOx><$s^_>3qw1pl43(40WL&2}K?yLSfil)I1E+@{ zSxD5He1inp<+i!-55?A|h;7Jm!)P{V=ML68pp!Oji>smlC=3y3H}-P7&Y`y<)GRh1 zD8&Z3!(Xr97}a)&>=|VOKL*bR1<ah$OeLV9i&1Gg&7^wc56&RO>%%b(Vib@fiy6S9 z3cV$#Ud*P`83;~~8dhwdeDcX#Z@s0f{5<I~xXQ*c_e`d-5jXo$7#>D-NyR9IL~K<8 z4B*EmWJuUpxAahKaP)|JGO9}p@q|DMf*zj(MuAb<=pn9~=n^UZXyX9=(h>@wydD(o zMu#)nNM$rYZ3p4O?>Q=Vcw7>)&=etDD!M5nf(H&bCO{07P|HxvMRO>xULBF5!L&+? ziw7%?Xe^=!BEoLcMRT%2Eg~zd(*Wp9-Z0RHpPo2CkSfec5zp~cr6q0@Cmat3$uT2x z6&_tafEWdkBnoa6f|((OfsM8ZN)ZOO6jJCH?X7h{gpx!@6(zcWAdwKUx$)A2l8D4h zr?{}i0RX|@fk5z(;*ZdXup13VStQF)#C4-2qW~QU#89Rf!aYQDq-w*)Hxz2M9J5!m zNDtrCh86<{n8wT^9wzvPhjn<FxvdJ&v{osCAljIwnYNA&*rkecDWp8*N3&p!qTq~9 zT~-XiNy%<Ebk`{N1REz~6f>P+gLgnVI_r!Y?ed@tvMy*qN#VhH6<b|65zK@pQ2;L6 znG1j(({M&vu`YVI&p}|c1EZ7&4ADk;g>zk@(TO2MYIRLzUedzPM3k`Nl-PWk@1I5y zF>srErj_&A1EVB<YSDoVsDyll0g;r5EG5iv=BUNiO;AkZL{H#`aDwDBNP>zRaBP@$ z5eaG$6QH`q6KC!!VOopF>|n!BgNV!{qAuVGRnaCubQH`)*g~PxQJWw-9AZd|Ka&XO z8x0r$x@&6aQA<x+{1D9YLrLZuWU?^JgV9VDIuTt+rzALQ!Hse_vOv@*I1@geBvu!5 zkXV-lQdy_WX^o-)2<K6V1N?}(RHgn~nrk+Lpzr}3h|e_OlsfBzAZ@9EE(D`do)GBg z1Hg$APWs~~6L?TEgeROJYJ+ImimEt9f86GwHWnejpb8+OpaVS284aDDyRy;D3Qo$g z0Z2yC1BjGE5CyBf%a6I6i+BQ<6K__iE@neG<5=8CH~>9HLl-`6a@A?m&5pzeoHS%8 z78y51qG1HBk@==D#)e#abq@~iY5j9es=qRnk2DLda?^zBO)M6wG+Wz>tuBgn>WD?A zlZ`Ua+=xF4&%+TXN<60k9Z-T|2p;Ch1_87=3QBLi&$O{&!Bb*lNIBcbpGr|S8Dfiz zd%N|3){WZCJLS6A(E&Qmh`@ghCC@45aGIdR@(V3aZA?HY*TTicH#?#2Q42R@UIdhK z#lu|qb-Qd(3kNj!2ZQ^E52QXKJV7VLnK<7fE=~Z^U6|GTKs8i9jLbw{;;AE3(WIr` z;B*sXr(P)-P38}vC@fFfn}6r+mq)EOM9Z0SLlW}0|L%VV`S!5<xBuSXrW7znFQlBV zmpbY#dmtnpWGxwz8e%B&6^J4;WK>rwF((qTf~GU|M1w9mL+~t1BJe1QHf_WSYN?&M znIpB?0!YP;;`!J9K9xSH%l6vv{{DX5DoM0D<8Vv;{0yh=qaV;gTd8U}#cT+JhZ)lz zx<nLB&Fbx*Ro0tJN`MCZnYPeDDk&L=pst7i=4QPjdn-}3BmnVg;fRL(vo4yaqk4C{ zsfxL1lS9B;U38RYbN)hL(n}=H#FFH2rX0TAj>&?-pgvh-sQj;7RS3xgB}TeUqy6)L zgY{G<1#6L2PSS;FqcHwZCOYhSEy_Rp7b2k~!B7H6^iN7?2=Jr>+RFMZT^9&~A%1c` zY&2rvMrs&t2te?Mfy0RxLjnmB&8*-75Ii0O7<7pXhb(${P-=#5zdS~RO0JKn->wnN zEd!O$?j0vXP5u0tXY+mV-~n8{ef8B>$_&pt@4SO@|Ni}tKmPa!Kls59fB3^+`?X(t z{`|Rv-EsT5V0Jy6Jk(<avv`5^#a6sxB5_fOh>d$$Ydkl^x6{*87G1wtr<us?x_*I~ z2*H-&$_a|LlVXSxI0}(2Z@?(fbx7p~c=6%|9xIL^L-h%nJEz;UfKCcKwID<CCYGF) z0fo#Zifkr$w7PW4Cmw>joFQf3M5i2Er{54F3VJKZY{&DL1K@eN0R?liss#)YL^O$j z9<o}Y<;KN5bZo@w#~cx|G@~ST2<3Q;#u-w=q$IdeL(u^6q|D%5w!0xft<X5Y5H=oS zgGf6%TnKm|YOaM+*#@j&0BnH}A;sD1Q|ZvJ3)nRjeh?xE9Y6r(W`Q0!wl2N&Xk&s@ zbG)u7CDZ7bwb27NN|q{NqC|wdxy*}B+VNw+tQ)|CIa81fD{P2TM?X9~R1%(`G{ooF z1wmp9VCZ;sd4hp*69K1|=NRl>Q35ynoY6HJHxMc8CY^|Y43+8@PJA}%S))zrlnN{O z;WY(~zhj0Q!pz$^2Fl|GW*iSae8`N0_)G&4vKUfqTAV1MhZ!OqfGu%BV$o)3M?;w# zYXJsHfcV21uQ;%^S>J`DpFc+VfI(MD1mQsFq`>t}<tiaZGk{ymMC>Z2Ql5E2To-2m z8$m`Ro&+Wd1X0*BilPgrvy;MuUzZ391QCO7@&lIyLva;<#~jX1ihi6R3;+UR7n>o( zL`@J~MEs!>U@%G#=5V6KZEVd}J$z$PSA{@`GXVi*vPt0qSJ!pC?nVJ(*QJ>T4Dbk| zU`YKybPeee(S=8xNYr}PX#r=nM#Bd0{7g5vi6ba>I#GfP&5$l<a0;iXuZ^@5>@u&* zPdqGE%5rqMjVL$>8!1X63qe5-5kv_oL;w$jCv$`?^@EP0jiFF*ri+s{`r%QI5_2I2 z>3E{29Bq19xU~<ELdO#b4|*p^59oLdX;B~m9VhG2mKNZVWcwZpg-IHE!UUQ3=rL*{ ztTI3fPrM2=v$Zw-g69=UD-7EgK{#zVIg=k!F@%yp;23DLk1D99rVfEr=2U!eurGhQ zuU;JqTAeyM6GYMSM+<0ZURUMBht3m3ZP?%p1R8rCArb<|D6zfR4|T=fi3A~nv&(-6 z(GwH=fhTD)87nPql{al<%d7UL0w+U>w{TMsox07<`7sh9Z1AW;x5*QU1`s4|1S#P# zX01qb!-vzuJpeJ<W`6#jzm`;tM%*LG2@`Ybzw8lNUC);=@n<8&FK~mL@7w_C)(0V5 zP*82$1D@TburXsmXNaC@d;1NAepd%N@NnL~!5mE_dObBsZM`S=cYf!0Fn@bk{_Vf{ z*F^<mkL?aNH|hZvM-wXla3&-`B!XQx!GtYzEkTGODbK?O1O0hr4rfG~j(P4n6R}?D zv%+ul3*?oc(r6!6yS_NT$Z2lSuY;_!4lmCy&PmbS%{riv8?3}opo<Y=rvRjKfcBup zNizlrPqf&mvMeGy@3u-pp}!oyJ<Fn(r?Yyn5k^EI5<PJydbCN7i~(nSN>JjqQ3!t8 zvdi#OF~v6w1n~n507C#hwy-4xfMGP6e|xiu&mGVj&0<ba5mEV0EKPL2XhA~83;~9c zYPeC_grEHDHjDL@l9-5xX#=hrv3M6yh?9cQrsWTc4F{2Kf??};=)W7LR!+Eq&1fi) z@MI-Nr$CY`dJuKt)WW-938J?JS>lKkvS=>a+xb-<VT)R$wxQ<m{N?A)!?X6iUppGa z6*nH%Yd5Q_Uw-+eo$Kk-r+@Cx{W<I3eK<GOC{GSuiQS(S0L^ia^;S4#D4f`|9I&I| zOt3VgK=`c98yB_Zot>dm!V?s307fZ9j7|zWKqTH~p^`>9TX1Tv9SENpHR&vxg1nN4 zGe9uFN?e6^bO?p==HcWK1;NHEY;^KUH=KZSPL{h3$l^!Dj~UJxrg0h)2!zGM!+T$U z{Wbnaj~<y*6M-KCN;uiVCdPngxo%Ps1cP9iPJxl)Gcbf0ZP9>|Ea{@-A<MD&X$V3b z8y+oUfGvOs;&y<}(Bo>5h@(T8kao7<@vwLM$0Tv$(E|KD(MC29+-{<cEjgizEVYP4 zKs*Vgi!(msr$kWbx<HpXU2Sm8R6(Kv#Gj+1BjOSZHz~=a`m}`juPa?b(^?u_Qdf*d zVf=*Xvi|JZGo1OF<->;$U%q@v17~Ok+yL=S7f*Z$JwUTIX=IL0JWP9d*%FPy12jau z(|`i6Otr;QKPAzCMS{_chlkX1Ot2m|s+~EjrW40TKdE%x=NaNHdh{5@FJnd}#He~U zia%2y{&Yc9;gl{={<V3D|E8D-3JsXK0jX5C^CIXnh9Brg91#xS%<XLL1Q8Af{Mt+q zgkYr5BehyT+)<PeL+6PdKynlS{gNY68g|<sP{BzAU=uRP1Tjh+QLBp$v-}W*<H=C; zLxh~X$z(T*6QU~##5*f-4<$U>4yii0ec2JvudC%x5*0lFzf^EZYu>3%LYM$7atTm^ zPD=irhdDzDSrkAm9&PkTEjk{Muc*h9(BocKmaev@|MsaGg;E5fL>Dt>q6dX|^3$NK z-~|5*Yk&5m>6Yd9eHlYW&cm7K8oIlh6i5+*-0+QI$sk2SO=_Sxb#s9K9{a*JY#6X? z$u<mFwyY8GmHq^h@C9KQY_hvq!x`#~ndjsfk(m*h{;d6d<2ljQ(pB}UtbNvAd#&FZ z_VDZ{rZ*P_Kqp~NQKKe~4W3$Z4DaD<8S<Ey(n;B9!n*h-g#=$Hh#JZlaFWzKEVkkp z4GO6_o+L8LyLf0~7#eNCP|mLwk!Y)x`s;>If{F0qBf;!^tRkCkv2F4NIktqGW-h|v zo$_S3Xh9C8O!K0N)==FDf*|E(?|=${Ldrl0>lQhR?|fjcOKtfaf}p!eFw8O9RtpJp zhRE65(?21PTL2bF6GWnGC>$V4C#rk*?g;=x^6JujO++|_x6CJi&?e7ip0Ji?lFegz zVbUkOxQa+FCQEL`+INl`LX_3Us}Ft3Knl1~5-l&AQxc<Bj^^@7M;gK)+#<=N7$RNd zWsj|HyPh&H4nwOBAF<tW%Mmq(2^nfR+JZ!&@H7eM7ZVoj3SqbS5uMl8r$~y~!CPKe zuerp|kF2H%Ho}kZmF$XrO3lTRO%c$7-^~sNrT{h}d^<v^U+qm12-oNo%_v@L3Grpf zUe2TL-~IjH$Nc(q@K^rbzaogDkLsR2-<=UF(^+<^BLYKpR|-RTq;Q5xG7}7QLsf@_ zKSDf4&XUp1T{siag*BSQ=!>&cPtNhmuTrY>*~|I$qdr)FzHNJ*!n0>5^WEY7y?MKs zUs;)@28Sb&BdeCl2ELJQL5d$^N-Q-(;KC!39f~hJF;HgPf*=f`MPs!!8sN+MTGxP( zSi$s5SxHM76Ar@YzJB+$0z+)85;Q|fXKFHR6dB4qr$*uMWr$FhIUd7=!ks&}uisFR zD@Rv$Ux}xH@Y?;ogX{A#t~Z3!Z15od0sxzrObQ+&$P%oprK1H@3^YN}(M5)I$*GCE z*tRyJMjx}XoH|f`b!q0^e{)BN0xL`pT0?co@gzBw0uUz2yFeI9S$O3_(g8<~n3&L9 z>zZOi$chS9FfZm80>3}h3Kf|t$EcPNCQYpXfY5QV<MA*3rN89R>9P(DdHa3$-FH0$ z-h1!8Z@&44gua%oRyrKP^tQk$oLmb=RHeXmazcccI}`Qs&Ok@YqouB;@bJ3_(t#|~ z5XwbM$QEJXAk3zd3sGU{R4DJ~0{-Zuj|hRdwSVxz2PCbWU=5)S@K?wNG&^FGvWL*! zyLTBnm*E@D1V~{Zh1CipiIxO0kuoboD0lpN$M3_FA$JyGC}50Afr)Y<B|;>*5Qf0C zyf=@0m6VpP$ko=&Qa~gHOaXpvLcE$oK!mNvOhDlg1+6XxZ4ASfJrl}W_`*m|2Vmyb zUP7Bw7kF#HOvwnb5(%by79P#H+^u*>3^lVTkd2JS<Xsr>#Y_{X*jhH5=GNx1xj+~a z%1UR(QD~H<qkX!*^(UQTP-IuSW|<t+if*RNWKk2t{rmTAD-vklEx-8UiwcG4=MEK# z5*3Dai&IxyYSi#tV|aHq(#%%Hn5QF{gcw5l_!Yx^g^12%yEcU($krz`nkL1Xp(#iv z;@|3zpfRUkI+(I(2$dQgtqO2Kr+^K`r?0DMaOhALEeZ`&f&h&w4#On90H>zKlM6fL zhLXb<yk|CZ5;#n%Gv2J3CVX81BM6t~Pv!qAiCL&LRjI_=Ru+j-;A{zn0ik%vF<b!G z3WkIlAwyx5czGGB8c3JCAvkOcTg#l#kZxtf@4{Y7C4AkOhU!{`bh3gOAaho{NTIVO zr%ZAhLM1|0$mPR7@l8myJWK#}jYfFF`P79)nQUq~)#ZXy2!tGAsO6VJ5(<`O=21GM zwtlj46KYuro|Ouqgel{lNZP{NN`Z7K=<<kRl54!7z(dA^ElxyX>r#jzMEH_I0akOZ zbQD}mo)=bm(FK^52bP-avZ73~`65A^xlvhAD9HGt-P8~!zU5aprz_+MV*^LaXyO3~ zIm*f?J{PGm+~g{$OSoWW_6-5auP$F;wYrrh{e+FS+86dNa$STmM29@htaO3ciM%AI zsa@yf>|b4S?dH*D4L0vc7w_sW1<!qs-hTV-mG{f<zWdg?l^^{iC@A=bTFJ~ew4&Ww zl0tQowAno)Ab2kHimOC~82Si~QIR{!LfD|z_&i3n<<8JCf-r(7q{dc@7b@Xf>yIhu z(qYIQGL)m0(C%`MXx_Ln&$Z;N<fu(S8%<1$=v=&SaHsOtxgdcvF*RMK@PtMmKb}AO zMVUlM(nJ)j=YIH3NntWK>N0Tp;_UG9ER3RJh-ab;fut=U0A0fQ?a4(cXpt1OIgMc@ z+6l71ow0sH(|<^&vyc^*8p*ZmSFWrNTLJm^e*e$tW03y(fA}|6Y~Sx9#P#}#q&Zf~ zc?l<(ged(jH}ZJ;W=qv{S?QW-ZHr0u@rKkwxv7nt^YaVS`pB0Sg3M*V{`AqVYV-HQ z)cU-R)GTeSfOHM1>HI#xh1tS{za^p@=_1=eoK^;RDsGdA5MLtcu+kO3_GJAH^bmGI zt{W9wIpVWw<~-h?&kqC7o>3gF2w8!0A(&h)5O5p%aDVqyfK#-&_8_5?F9?Kaf>^K9 zTjiP5rAd+reMzBtTFqAxzV~ZrV`!=+b0C`|d9+fYRT=V0ZPkQ=E<jcYj)TSy#MEU% zjs7+TT6{F}HK!?P5!cARrOCDGZ7DnP0H#2qHJSoqn@6sTR*;04MhSUgMZs3b8&WHz zbZ{(#lns$^!K#w7Vr~dSha68wnK;F04W+>FV)|NuhNQ!<5)pb0gZ$ZNpMfHI<Bc~+ z{@kDYbN`?D!vnwZPygvZ{qc`~%*uJqkbV(D@R0VN{QmpzgC#_8w3N$Hw;_@|YIT|0 ziEd`{^$IP#M-Ltx?624O^;<x!5M}h{n{UD?wd8n!);TYDj!-4qGL<zel#s2%G#$1< zrB*k}1R14F0nZ#^D3Cy4l>#}Qu&!vupIjRm;zDa7NiZ+0yao!%OYeFZJjOVVzWnk_ znkKHWi)5polrYr|Lv13v;END($DB^WQpV6M1yF=7R}yjxT0^>oM&VE+6zYb9<Y-$V z(b6<3e!fWPlaN~~^!p_xYsn~~7f9d`_$9|9Y6U~mMC5m%*6JmM8Bt3|i*Ga@iA1Z* zyFyt-<wY3m_*)*UgCTrEqbVby@?JdFSZP}7*Vk8PP^*H1R%-L}KI^AT<YknQ0y5pY zT4-?Kduzg5`62LIB!q$o0+R_LNo15{LR=FEM_c#Ko%wQ!6cF=Vm>mjC2)Q8F>Pq3p z&E2mQWzLo+1rwKKl3!mwpbW=a1;RGM)8WGTuO=9p^zkH;vW7{>31M=y-A>R3MS)Yq zi&0%dCV{7*4q~g@6fhSnoe6Ofz7&L-7dpv-o0sP&^RU>$j;G1Qs8*MJi@}kZclv}= z{Y8?}rVn3xkqHnZW<;K(?VxQLghN5rT3tzrlP_{DVrvLg?r7r6ND&k>9TAdi>5!Bc z6GK{*5LCGoe{z%%(Me4!=8DFVp~BEw)eQl+Sn#L-ND!Uc2+y1^vB{MhBFS*PF2B@( z1f|=0W6}_lgz>fMi$sLt#BdTqL`?v2a;L4-nPXUyl&sML<CFrliGJw_-VhyR2yzU= z^f%jdFh)_`a-VW9T6Gx8mO{DU5x-hP!09xkWvKEb76}F5bi~$Z#W9LOnHLg;a>R5X zY<>fQOj9@Ihy=A;b!jGPG)>*iH(QSInV>1bqV_(?if*@^EkenXR};D5^8zip2!d2# z8#SaIXUi(&MzhidTiqm1jYkqX{HAP_KAt|S>o=~u($fh9Z7%RCFF_|89DtS~Eefa< zz{&!VWDZ%T!1>Z84{aF@U-djLJ@@hMT3l3iMPpS8l(nt%QYdB&3K`>RVl*8>3P1=M zlF$LJEyA@bPM@qFU}@#hCzpj5L6}(2A713{C!168kdRYQnMwQnXY^7=K)_NcauTWa zu*i@LL`|2%&6~G8rafh7l5k<v{>3l^#g<yTV18A1{atQEZKX3SzrczgVK^d0XY)y` zlN4bJ@oeL@KsKnU$jWycO3i#})mCgbZ{Bd8Q>ONNfB(<uuRwbN7H(l{{i~#V^A|vO z=Q5YvBjuo`ix`VTTNfq4l!JUq!>qesS{%yl!Yv01)J)Y>YEhERFT#eYFpA>^w^4m^ zlV;`=Nb3j}+w~hai0lJ%c6>6w1xJ6j#X8-1!Egg{@csY%^zol2vd9@i5StWMS*ALb zLYw5p{86Z(5TXFb%UXzK7vQVCmuIIh_V+FwUAC!QE8QFRZmhr2%E&*}T9*K!&Te;s zFzcXltwnH@Q5e9*2D$x~myLKw7&=xMUYvL>TR2=ic=+JO3s<OJ*b#+;{X_4fBb|5J zGZ#y{Rbj-?Vl5JA0Y>6<R51x(*VFLf!v{8({rLFtBN<^HJ$gvO`<jYLR@UX)-yw?% z2AY-^PVwZqUJ5g0K^jWG3dmGJ24YR6%Fv%$tZIm@u;l_Urm&4>1&73nWg<k9DvZ(2 zS+Lfssi6iOh_V<J5i~9WA*ZH`7^0NL%ocgEbP%^lbXncGbEl7`eeJc^zWw&w4?g(d z(@#Hr@4ffDQFLSj6hMFuFGBn_R7MDtt`%dk`p0p*2&4P@Yp>nCbLYnO>o;u{Y69!n zUEgG$X<I)w)&fHbF{LBN1vXEMo{=^+d27RHnR>dg`ugjyS<$!UWg$%_)I?a!Q@2%l zJR(FB%sPWCb^3vW0@%kUwKsJ^=^|n17K5(V?9^2s66y3VBs;n2o}BEy_1)_tM&*T# zXGN2a)c7hXXj<{e!l;<T*VVEDOGu|gj1sQsc0_>?8U;fl(M<?empQqvT<9>t6c4^y z;VGk)!hGXe%!2g(Q=zDNT?8vHay9H3Z%eBz6jf7hD^--@vr_v<*uR9p`HG-H5IGlk zAr)%0Nu(e`k-Yx;>s5(dTLH@m5yq4ec|+k;A3VQ}YRN5km~f<{ENo4mF3si|Z@w&7 zmEkmeqhbbPa&^gd4TXsa8FGrJj8bEg0!{9;49P`B$i?;@uuLG}jTZ1mM(MANc86GU zydnDLNJip^V6wQ74z*@eNm~OD2$_ghmmH;55hSQBcZOR0763;Gv$<x-BZR;+)Wz4u zS5<^Dz?N{LUrc-x-K>R7h;e@ixgpBbI5kIzkS5AXj-CYz_<Lkz$Z|5L<{EEJ(kwh^ zB#}}GLko~Ca9uiD=Oj5OwqX`h0T5=TIC5NJ%&H4E1|TSer<@@WWud@|37uw*oTRg^ zW#cd>jL$CyLRBTllnZlwUhsseVO9!cL(C(ZTw6SZc!Z&!mzVR$pLZkxZ8|WM;F)hJ z!@(e<y40e=NGBY;$eq&|Lz}#iNW`Ek<`wn`OTQtNq_2z5sV$I;4%>!E(8W;k<l*Ex zcQKY0g{_-1!XqG%<-#0e1wz22AiN@Eg%MQ|3N;gqLH{g@<yqDfm{Cx8i~y<?kdV0m zPN-F}hI9juNTSp(3Na*G3h87!5v<C`i&;y-D4ur=??##9nXeQEP`luFwW5G0uRETW zj=5tPC5-4yv6jaGIm#)<vbS3a9c3gYGzFT1=LpYm`FH1&l=#=ZcYOxU<)g!!w{F0D zb?K$sqqTp0{Pf!O-Kr1?5CLmrkbPH3?WVwKHcAaoA`A$Dn5mM=5Q1czGV%~~*=86Z z+AxjsHa~VcpI#yUnds`^q>{Brbt%(nr-<Ukq&XiwGk-nWg1K^Z?fSLtPr=ULsI__5 zrS0(Y;loFdXD1(BF*<*4+BEGSn7J!1KjK^_-?#hoxep?MG2g~D*+)m1J{-YH@*r`k zRU@?^_n5qL<?6K?*SQdqe_nxHN1h%(y?X8H{Pm&J7amJ<U3+#yVm7y>S|zomj90M= z8_^;0xQkDDBx`jM_UIu8@3E!$<j?0E9Tnx^ixZ{_Xj-+$Cr_*pXKBBbO8EQ#@E>7* zeLDD`{^ftmv`sdPM7*kcc>HAdX9im?LZgk*ZdpaT$Pj%{<$+p}T6w<l#v5LJ9TuN_ z^2zo{;3zdFAp}d9FGNm4>W;H_{;R59fVC!D9VuIL&(|Wh_dq@AE_gcMjIGe4e7+ed zkVGr|At3kH@9THn@2lyom|!x|Wlp)I+&hdCZdBb2QML#{=|VOnp2MTzA>b(h!A#`q z$F#(0h(h{kK5*!KD{84JBl@F1`Xh06A)vr1D3@Tq3XHre=?b325DBN0`7&gpY`^*W z=lO%o>&pb|sfONoW4_}@f-J{eNCz3!rC&(p!V6?WA|&jb)xC4)wtGNdWU_x)DaeBd z4_uA`(h(<pawf>!f{h62z}McpcaJ88P8KE{9iPmP)+hi4)j)<w&QG7+1BNonmrxC1 zbfID7LdX_~E~1=MF@Vw<1xv_j>EB(yrmKrLil;xwtDAR2d0~71{{3xvuW*KuAa|Y? zUU6*=-48$fkf!(EmDj8>rL)_O;<uZe3AH$#8vN4aS{FW##owZ0_-Or<AcfM$i${dN z_{A?M^Tqs|Z@!@nT-Y8*B%rt>?7bS%G>;Y@5RpTpAQFxk>Q*QUY~h&VR)uZO(4>o& zA@5rxl}J6?ToDPPPz$i%eE!K#eggL6k3Y7G6yH*(%$9dyz!YSOV?=_{1!72HwUnzl zOfQF=(tP@K{?;YpLbAZc`OZ7<&<O{@;X)Ri0udF42?Zp_YLaUnNs5hCPRX@!3IkEl zO~M852qOSEEexZWs#JolC7R@!lW<3}tql`F8HtcG%=g}Vj~pLJ;4qm3$BRdcNK&9F zLda@f3?zlI+>YTzN{E>7h2j0Jx84$!03d5ob;uVeZKZ&mu(|=!wovh)bj3fr;Khr6 zLBJ?ElkKdg!|&8_{kQ-ILHWKK2~85bxuZ{+umhPyoX9dj5SIV>GtmV$$*hM?!I%`v z;>1vp7rBh)^WM%A(Lxqmh9NMasU>Io;K6)VA`{6L1FFu#lcu)gQJW?cbz?4z$|yA+ z3tQKy6}v4SIkqs!bve=&59RbjPTpLT7^<s=hJX;Nj~2<=;-J7h1XOs2=<`lq%0Q6w zTuUu|L&YFRycB>_V2i?|Nhf7Pps3mM_%@(@>QvF~mlrTw5wt2vC?3H8S5G_I*3gET zFPd78XsTPQBEQ-wec)W+Ri2J`lv;hr>A=C5K{~oxeraN;k&8;VF9wO9IS@iaLXsDT zmrB=C#FVvM#Loqyvx>I6!Sh8e((UnqpSaI=F<RfC-3d!1<W>=4OIR-St0!L}7&U~f z1VXkcW27S<w*Y8_nWJDaB9|0pAPvzWR61vrA%-fTrNczBa1aHftVFKMFGD=Fc)_PY zf*Q@Qq2g3k?KX-j`10knsG1<8OMxw(-2M^<z`|o<RF~RDX$o6$3<XZ2%{3wKt#CqZ z^NTmc7ajb?_$iR55E)IU7|IAyLl~n)h;oVuMFln;L8@3&07Oz+L-ZHSYzihDF)So% zhBBm93`lXP5z<j}3iLAsE(=pk-?gDNOvsi(u`Qnym<3SS6xs-&L~d!d%P6;bsdcF+ zW?fV;Y$xYcD<lRW&5LeBgbcGq;fUN}LJbH7j*8F_3AIASS3N^aB34=@%u6xY&YpTm zE&?DIBze2o0{rv8{pZ(5B+f2?S+v1wFH-KniV#5~LG)Rvu%U9_NaxD@NcnDska)}? zTNP1e-byek!ub@aZ|-@yHLAiCcr+wsnx=pbWo4%zVCSs`YgBy-TU&i-%2c@uuL2_F zpHMCwK3XPaBx_v}^3^s`bUNWfTg>ju5bA7=ki7Zkn{Kw0t&o54kN)S>etkOld;jqF z_!#bdL5osMSC7^YKCN@VOMHv6`J-&K>Q|Su^(BN$`+GN>aTb<^`s$_Q$}Rr-%^S~N zJiqRQef9G8-8<_m4aYaG&7b>6Y6MNY;+d_b1&Cr&yLSEB<v#X$eKybh8?i;^;o){Z zpUnRJg;JjGAMT&d_fcnoLawZ0ZY4=XnuhQ*KkN9OjMfS>-=;)T<fhgGve$KzmK32b zeba?0a&h2cTHm_xbvYuZkfXEp6<Lvh(x#)%0OdptrrM%r{rKtb+a0Wgga~aj@sPLd z@(wNUgu2@c30NB&FAPJ}=o7BB=qwh)kp!(sA<_TAM?dTrbD&wzc*@&iJ=~ukSh;oc z=IvXzJm<}d8L;F}j!(QhUA=Pk*3Db?H{N1@HE+)IIc(6lV<o(2CnxkhX!`{l65wLv zMVe-trZ}}E<z-aLDpTErVQ6YKN6_x2tMKeqT~?F8`2}$$GRuTQ)7mniX(}miMN?9g zGDFOj%SX(fK6&!px8FW_{6w;HymE9!S0a}WFW<az!)iQzaVll!fvFTK*e}2Q^8NSU zcjMs*IKXNMvuVnaX`-z7^zG`ezWT~!i9~Enw7>l2FDYbFWsK^g(o{p5&~%F#k<c{c zY{N@j*Q(aysj0t~iBaBLLKKcJ&*2!FV!8*UEH43cQ*;iRDLkue%LOvDFm*rs>@(N0 z=9iAq(l-UnMJ`kLm4cVz#7K=MAu9_1=D+!GszZ?|*N=bvW3R-l2n9@s5FlImvW25i zMiD+7L}*lNQY?VZQ0t%2sIYZ0S_ho~q)f<>P$esJ=>Vk9<J)h)4S|}dDA<qkVxm5_ zzdCcoR@dE^&b@p0pt0h@oI1n_`646<gw>rpuRVG4)HJ^S`Wxo?^UuHViiKC&<Kq+W z-A1iz3awCe@*gV%h}e`GCPpdLMD8-3X<g5}94SlQ$xWYhj0%rFq9&>2V9k-hXiBF_ zVsyv%`Ms7Vr*cQH-@R+*EKTQw=P};A`e&-N&T&cN4cRPiD0308FRV9k9yFeFUh~$! zl&uMx<ZG9`Fn1ypu&5NAk!TBm5Tk~|PyrDlQ(#Do1W%u#)*KnF{*5x31#>n(gknWI zd!C&L)rIwpM7ryTQ|41`Vb7=gUc2GsJUx4U^_oNC@a3zs(=$gp7$@Hg!q?w;?dQMv z*&A=Zet7xdv(G;L;Dh%cKc3ToUp3@c>XrxBYN({VldCz2QMs5zp|+MVB;<H0w5Le4 zgfQ_8wUP=-j;#m!hVUGT4>8dylu^tE4o9n!9TXJcu*wU$tBOexfq5|_O^vo`0+9rx z5>trvsq6$-uDUJkzc_vV?77#%XS&+s6KB^vyVtL(ifX>W4yG{7tgaRbQas}1t;n@T zTZ+yEivih~PA!WT2nB|$)R~S7AbCNCQ?e?frN&l$Fcgf!sR(kn>vffsudFIBh9)nF zJAvuaPe@b!JDLa`Utx-;S-><wpmdp|VuPGS+Z410gm?UOo(K}5`OZ7<eER99Fs&l{ z!fGiyYHZ<)6PO&?f~Cn_b<h>FHgJw~3k(!<I`Y+JlBTF)I5I@;qW|d8LrdL1>)&je z-*sU<bUwL;`R6`n4lm6o_PZjUQNWNZr~P7-G85+hb?Tq2k6Po<!f1Igw~EeQp3bKb zyZ-H8didypZ8dXpGT$5I0xXmDvBUE`8ldxYRSmTyDxf|sB)Q;~$XWNr7hgCMJ%WGx zw}0FEAy-mmF<M!)N+B$V`TQcr_3J&9Jpw-e{BwYc<`KYA`buOLc<&1wipd0mA$6m# z>{cm2L3-$0V=ZZ}A(R3}oP>xwd_uOZ3OFR2iR=)+gcQ;z(b80bpwiUh#YS!vLhBhC zCViv4<j4@@)(>+-`9&BMtT?%oEGt6kL#w3e=%O5HZ{NP72zZNGG0Te=LQ?<`K6558 zJv}jk5qYk4b0=CY5+o8NOhKlD_~N}G^xk{#QHEpUng!EgC3Gfh5oO>Qfr-kfbi{^- zoa?vVdRrG|g0W^qC~~<l5!k!$zRL@z+<DP_@SWSlqvy|Fc!TjYdGO%j7oUH5<GK^( zncYpU-sCpf<Ht|#+`0SW`RT(4kG}ivfu}zq1qER1dE`|WZw~2`n2M`MR}S|*OdZIM zUvFdcGl}lu2TO=y{`ASQf1Yk;-qY;n&0C(gYauwO=fSu8g!c7}o1c1~o9!XtwQJYk zc=HXVlfFq&DCL!!QcGDuFmmiDHnc8CSM03LPgZJ<S6HK#O1vFp)R0|c^RzIwDZ^IY z*&wgx%v4)Cim#-9`|ti9wO^kOe)m84>$wDtK{C<3ac#c7E?lJB29Rytlrg$8LDpuY z;xk%ZC>ToLkgSZ>(x$M<H`)vv(&Ew8^PfxkUVn9ShtY1z5KNMQN!sUx(y`*(S`-LL ziUAmBpbQ~JH$ze`_$|&TFP>oK64WfBbwNr0Pt)`H5TJQPRY^GNOuwa2cxGCJJ!ZU5 z=7<Xle2E;>>;TlpkZ8-IRR|${ay;a8B382DdT)O&RTdT=UA=nE;y%aUJ<E&J3YJ?- zd5aS-@j}8UVJkZYbjw-QnsQNK)y(QLPc5En-BrKcflE#^t6D@JAo3uj*@>g8olUZi zcxbv1@CXixQF~ICa<i5K-Vl8{g4c4SJ7rpRkexWS^eHH&=_BWh+V{%qir{$DIv41x z1|b)$CgAfobMEYanry>VD^o^U@r`<#!WUSFGP!Q20R4z0xmLGG;t6%ZdRPf#qq3%> zXq&RYHV|*}nDVNUB@T)XO*|noN&--hqJoB`Mo!Hsi4m|gUH%FNGDG^cR;H9Y&Mp$z z0zmMUTEPWe0g)Iu!obm{Trg{VH|Y^8tq7T<fG2EUJbN}@F4;7J)WtYDxCV~etr)JQ zDQweZ`b0&@5J`|NHGJW*A`}~wkaZ=_B=3aUmFVt0#HJUdQ3wcHF=&lqHaa%}FjZy6 zFUgvR`HD4nhJeVI-{jP+Of5Mf6Qiu`i!KCGlT^OA5I}J<K`kMz;=l(&84ex7S*Yg$ zkW5j|&q+9lExA$1ga}h4+Lg|ZSh3ym3Wu#Y;n)-vL@N?%R!Fe{K{V+j%5^Ch7^o&O z22sn3j;*f+h?d*kQ)YW?8>Pv-u+1$YNfkDlLbD?(RV6VbPC_`QMx2}yvO=KfkV|LF zmt@PLI1zpvH0z6Ult(1gx*4Xxky%F89wIbTUHH;W2mdSJbtx25niyU-NwkXe{bmf7 zL^_T#Srejim#?x=2ufarNLM>>7d#e8LbSz06I$n3i%^ASWK`EE&20Il(|qw2?8<ES zD50!4mWp6#l4Dp^E4egBG?^PURGgV(BD|2abTXu=Meq$323tB5pndbrH~e<OQ!}Ks z2ccmyH$-1Z=-SomE|lJv96rn~7(2p_hD;4HnI*N39bp_@nS2>mWRmKDA?Kw~QH&aD z!HNn3o=#{Yfzu4)5vSzkf+q=+5K$)S;=#KvhB*f1dW#K@C?II$D4{Omlr2q|QXnrv zU5u^@<K6NhU=S;EjzC#&9MuJd>RKu=+0yZ5ix+SvX_9E`hC|tW!RJ@G6i1g3pDnU- zGO_f)iW7(~VNT^j2pn(G;yciwl`rCgTsoOg)mGh*Zp)^Ov@7G?A;2VkLv^)ja)&XL zf>tDmZ8#BLs1&^LOPR0qsVTl>@ze?uEw^)$D}qGi#heKS6gB!N;YLPntcKVsT5~5z zCkChCAQ6Jq!e@vnqyVWguPcm;?ox|LYLQ847bK}rBmzL?C=4y(CMR*9G0WsD<Fl{6 z`l@T2kbp=b1+H0bT{`jh9$PsUxuj&|y;>vzf@&f#h#J52o0M(HmKUTUEk_Iuxe)Wg z0XZFcN#FD#I-oWLq-%mto;|<3A}=Z?4C7&jul=6R=20RerO34w^(A%V#Vj=i(LQ`Q z#bF|MfP_Xd-4FQ%b?@Fi@hHV)ap6lO2-D(%z!#pd6jJ+pfB(<uk6`_^zy7<<j{UuZ z`J%$<OaH{6>jGUl#Lb@s)M$nBJ&}uvT*6H2(uX@So+l%XZ3tn|^OO1A%XGBRCf)Pb z3Br`o!nouORn<?Q@4f=fM$yG%4`jG|;5ePv{LPG>o>>$6hx-RtF3%s4-g|Y)QK|(p zP^V{?UcQ37cd$Q4#WLhwItUbeT``m+M&!%+E57MZtmo0vK@;nLA9+AI5LoW-&2N*; z7iUyV4JVZKl^+k_S1&nm?uyn<x4cTE&CEzhW4b(w1VbSq#<3_2`;FW=!lWH*v@%Yt z=gZW7obRJwa#M6!=Y5V^yDJ4*niHcmq&amy+`W6R(RoN?6klvbf-s_mgB&9i>5$t^ z{sE*QBxtGGM~@#rIypHud4~t{byEuABQBD}Oss1Z4@!Y788~e%B7pW19xZ_Hi9{B* zqVuR7rL~jQ${9gnVGhw;;U78x$l;?DR2V5NzNrzIp-SXB@{3>mqR-S}0>`K)9A8_6 zXsag|px}7Y+`oUHCPTr{6c||NBW2ee%8I<rV}yqfsw)&CG#y+Mip}XhAHlx9OW*fd z)|cO(y*!&WHt|VnR^NP^4i63H1|>W#A@6z7x;jG^3>^_x$xLWw)wwVDN+d6%c*)W+ zL4-!NEm5!xQAI8(ql#7?YALuf_Q2B`6|Detjp~XdHDm|{ScEMMP{4D_38sosKukyk zFIl#hiZB?G_eBi|au+-b(2xLN0ighd3ErrsmApAEJO#uMa>RCpvHN1pqet_HxPb7b z2sG(f7=#ok7bMD;#S2#A)Ch%9B-SB02@oxw0uxC=!!)XGp;Cj-wgo1^Fsqv(np%`! zLOD`K7+rECMBZ~+w7L`^#~VU{a6y>lVrsn9QsdVUg>1#6q!@svMvJ%Dv|@&d;f@Kz ziDxCn3SodGS6<9kH&!(9FP_iD!NG4SLu&z`72u9oy<9)h<G)3ca-%8}2nmL3qYWWl z#Ke%uA3S)#FTSAxK36Lqt!{ES<QT~Ki$sl1Y7_4H&A6;}8EQilv$s=26bO0esDL-~ zXor5`Rh%+{Q>&6j;V3>AcsPdaHEWoH6U@ZP6i;Y71gncE5BjQJ!H^(B<9<EYQV>|{ z4R}s%4U-EwcVgqq5UWfu^rs5z(;`T=?BKIP5KM9I_$A?m&>qhaAY0(shKv@>pXgFR zcxdzmhI+YD88ydnK@+1U4nV$s`O9D0n0eViqVRX^tKC;%9fP8RhWegliBRLk5FXl# z)7ig-rAFRHm{`v@H94J0axGvr3<?efAPpgE<aBoZwUI+MglSYdQqzS1&8TC?P?6+| zj!}Fu&`%f+szf9SnJXhr+e-TQwxl6Eh8)ksYIj8o3IS1S2ZeYl8U~KyGv}SY0666c z@`djK?4I(X)rER;?8QkK&)tmpdHVDibFhDS^Tw^?rzb9v%E02v(N#M`a{LlmNRUw} zaN+neYhv*7U<P}FQxFWouo4f#m^JZ;K`=$Kz-GGB0gGa^hA;pr3%*=PYz;iQ78$K; zmKV&>B(TCD6l&?yxrpz9ZnRM8qh&f@ARyrjY_Y{lpMEAQ@EzT~d*`jU-gHD*hIMb= zoG-0XTdr7JA!<4u@v57c1+yV*c~?dXLRD=sS14o@Uso0_exweBMmHRz<QVd;J{yTG z^T2nJt>3BHyW}nD>e1yZYI$<(E(BzLtWurk%h?B)A3uJgobzPy1~NatU}W9_W=Wm@ z#L?5^<L57)KYRXc{h=um)8M|g=M{Xu8_N@S^S01O-<-Yi=9@Qe-ne@0+R>FGQ+24Q z>(ilLzk5fKD}@zq!F$r7gptU#Gh2@07cY*k&Mz24CIZ5dz^+`q!n@eCYc(7i)fI>$ zj9`8328J0Yw1!o_%aSnQOKz(De9rA^OSv%Akg_QQ(xzrY$E3*Gf|a5f5a|kbqBR9{ z6nRQL`*jSpf9Lo9j6MeG-}&9YHWgX7BB3B&b-f%4G$r|HOF(*vnpSXYf@T@bf0hoy zkVo>*BxP;3W=}N{Um+x~3uIzC-`)XIfQCt;i<D#BobS@+U}kiElM~ULvaQXTnzmr- zA{`PNWy2RqQ)T0Aun;1W7tX=+({=(q-?cG+ie}$hzLpMBMz$o<k7vk*Am^x<!{Ts$ z3~zmrJJ;eVUtOW*sG?~JF`Ky~6;A@3+9baoy&P?R1q*XAGp$;3>4QpWRC0uTadG4P zHwlA6)D&Nk7v-!J?eUZODm7mW5d{QOOMzO87|$cQn6F-$CuNi-bFCrzB+)tMd`ZcF z3WJ<xF_6;%E2(Ca0--jYTw@3oDsb&a%g>&pg}xegbmCdD#jF5k{Q$|kM7((Xi+}Mi ze&aWOV^bD@(_c%CgwDX8KL)l?4KeAR%2U~y#VKKOln#%~cOhQbGCdd&A=s=qy?Jf- zqn;!TH#GXiP}mT{ms)CY1l*|HdC~U3_PDYs1euy4%!bAaef8B><NfAMEo86vG(k0A zyz?m8A}84*hd`eMfhFP5HJy+q<c~l87(>kvq63673Br?<G9t&5myY-`01XkUgKLJ! z5vwYbK7|5~L6GJ0?YG}n4LW(rD!=041y6?pST`F?ab~3g<e)GpFQDk?LQ)oL6tpr0 z#i^P@C=x^&h{<~TbbjOv4?!4PY$Pl8-Bk%P3C8;DD+rKvix!RxU$7`;IATDMfoN$K zs%~=1H0i^kZ}jTg8ivGxA#pNTEi?(yhQJ*i$>K2-NDRf7g`r>(28B?Bc#K3+BY}{n zcn}3pM)QaWscGlpvQ|a%a)(A1j!{-<x&8inbWxe+*~{H}OAc9!47FdhY$;oH<tW0n zWCkr|zKq5g1w}Jubxuwh6ssIjD}Ekn)}qqi;z6mAh`~gsrfX76`aAEuQ))S-smtjq z#ngWzCWs?)OcK5#`Xuq>TWn?@BPy8Mgp{)lWCO=kmUzlr4AqCNAv%Ig?#|S2+zB54 z<(FT2AEv{XmU)#i9T6d7Xea`!OW$bO(Z>jb7bh5Sqe@4CYZ+;?3N4yw7BQqB;gL}{ zQ46)9>Wq&G)^y-I|H+w%Arg`<L-D--{s-QZRYTTqyzvGhE0b7AG>c&pTfFmuRemEp zIpqm@(WakJzMK;FOeX{`eK?gO6FP*fQpO0oWkW~Z=wn)S%g?Mp63TdCpv)N-6&{sH zbWw+#P5}@GOQE$VNJ7{3F<ZGr0rp}B1kuMA7)=OtL`wqDQ1~W-0)0FMmjttOus>Ib z;z5w}l|rWqd1yRC5EvfXRyvHX9YL8pyxAv*qvq9()kew=A&+SDjyCW3Eh$8z8*M|# zi;9P-r-_2_izL;foJr{*JYrbOP<GV3_eP3FIsMHFLoRp$mq^K0jrh7~<0;!6N|%Xl z50@C}r-@f3U00*_U<yofDgZ4VqswAyXeiB%m}n&>9=3I<6+d%4GP;p2eK-N)X^N2f z^=tDZqN)VMuGHey->8&D;(<%<P-1xF=3K@s|8a2sOc6i<v)%9`P=-iY)h_d)hAN0I z`9M*AHQ((kqlsi)CJ`@V*5zuU$oJL!>cORXg<cCuYn{+yEBMhoze^a(i<VQ1hk_|n z2kVDB5?w>-Ys>EXwfVZwxL$X7Lof?Zl?2wpASsuV=QE+I0YUr~0dZ89)%peM-KPWo zt-t&C0{=DX;II9Sf0qv=GVY~X1ZpZQQ5sTla$dEDm{k#)2*Ysya1Nk`5GyVDCW-Qb zZrzyg|Dff3x1D05t(&1p5;iN91}O&@7!o>&0=jW+zT&$DIjdw5O)(^Aq6O~Z025<0 z^TO5zsMX!-!wNY?sBH-CD04}u`=@BuQ>p9Z8Z4%m5eYBi1Y+mBdO02m1%?4$xA?Vq zQ1pQ)0>2g$i51BNh;FdOX{Z&(3v&9|caBZ_%f`8K#e4qj1XTKz)qq3Ao=7jv$_8R6 zC@t4crQ*Spw4i0+tP~qE3R5I0I5k9zghawn!1lwM!y!6M#Hr<r;e>lW#adSDSA*u5 zn}VJbLnJVy%RI?Nf*=?S1&m<CnxiP!kbB|BLrY;rH+vyQ7|;rj4#`h{`qLl$;0NX| z9EUp>7@8DR23i4V`Q=3bUUJmR{DM+UI5xSKgrQ?peP~YBi^lhb1xc<g!h{^r?{nv5 zTAWB%oA-tglYv_|`?~3C!?zeP=Bt~W7N0vULt$r2nQ%?zyiU7hI~fHZtb7%LvH}{_ zWm~N<JYpuG@4rAZMN=8D^hp4EgmY>rqN$}IUpjc^x(Hgy5*81pl9mzE(#$+q5&`oI zM<T46H8b+jM<2O8h@TDwqplS1z4x9M{w;nu+2UQwnd8kV5Ih&&ii=8HsM;iqChqeU z0;g!#(9{H9iQpjrrAbJW-wXw&yv1Av7~&}?-Pd1#O+h3DOsES`%00`$GB+t^*${A= zo5zS6GO83>3TS+tpQ}c*f-jN}KKOt~Sr`&Y(UQ9v=rY-cxPzHflKf(HVKPLNbs?mt zM7g600TTkvoQhCOs9UrEN$6m-lgw^wj4+)1<^q&R3S+5_GI9hF8X|$5yzn6Csw5mk zS^-$elm#3hAq92zG9$L!Q8O1?3ZQ6W<ck4ih~c<jQ~=x|3@T<M0Kp)$sY_l8g{q4T z6(mD0bgfkfPRapBbhr>nE#<8(K|0}wtSgb$p`}HKvQglz>WIlkA!w5`WCDSt#K{Q} z36J)jx_KuQgTn-@w?QssL;-`CY%QI@*U0zhXTfU`d0t@ZDhSv#+ZVb`!A5Km9YJCk zikUA&ADIHBpkN4JY8<h}D2_7(F=xWdif$GXGE-Zej~+e#{PWNIUNIMtovwyLRx7;V zb@8AsAI(zK6;*NSHuV7}Btd*R;wWRtnU@qMcbg`2t!N<xj;bn#(6!h>jj_Q^kQJq9 z(xgnM2saS!x=iCqSXFrn=^*+AOieJ(Rm!Do)DRvcgpjqUz)(<Z2?NLHS9T=i0K-xL z1+{x9h@6~+{*x#3rb@wRP<gL(HnOgK8LqRG6Gz9~pDE-BkJLx2r2Vj%wE+`ChcE<` zW;{7!rPZxyxh|5e-53fXAUtBlR!HT=d*-N>Lw=D&%PNL)i(kderd)I*@f(GJXd)7F zfFjY7tW7Y#)AuX-7&jk)c>!*eQ*sQV(@<SJ1fyULkr*Omq8cVzS1VIllSsA%e}#;u z%(gfY3FIUVZGM>;(#60`QzTySbm^BDkm@W`j0jCxmnG@%AI#l@kiOWO=+H2bG2{$U zT`ej$EoDP=cn8ai(UuKH#308&*7HZBS14xx=<;_q<N8@sxy?_R?$Vw=D(t^PDk@^g zNSw`A0Vk0oiLECRnoc1?42jkxs*gn0%Ad+}E?&w=P(_ZH%ZDF+`1<-okF1!>h0t^1 zyGP$TsHmuwg9=FcTaa+<3IAwWM8EeB{)~PE`gi|>zX2Mz6&+1?KKy1%EE(y^p*gdF z(%Gg2Pk;I=Xcf_J{I(pmn=)TA11m8tnn_v3N(V8CF@!FLrwcg=CJ@3M@~WCLCKMz! zLZfoopb9B3%;v|D&kx67@g3a3l2E|28lCkcHy6>gh{6E<Dvj;l`m<*1K-+!nz6iC; z!_erRr?Y;LX7@GAgvC=NctiBb#RJgnv})m4wHB6OdVeU+Eq+AeHt*0eziZj|r($<s zWdN8LnrkV~RPOK1c5PG}EcqrGomD-NT)#fw&ZQ#}LqHHl0CWN`O;+cC#1kiZL%NjL z&~C12f?e%gi1V&RG*f0vL7`B==T44cBD^iVA<zjngmm<c5^f-nS!pF$@d-1*YmL73 z)?1Db#RN{sR)wpoE<lb#Gg%n71hb&+3Hr_Y>!$Q6KqE1OT0BF-K(;uG&=3=ZAxD_Y z2lEmoaV8P{M)8#t4ow8a$|>e*5>Wta6wd@npJC<|u+hyIG^xoVoEF$Jo#kXwj3$Jv z-P{ETp{SIFP~uL>q9VVzo{d%qJVWcbNQ|buGTZ(95(#2!M#O-J5l(?^`gjp)1xY~| z5X|^5fB8$1=pu}V_q}`f+`_l|gqC*<b4AdFW|UJnu7;RRdDBOVM^i8q1S4@n<-2KW zb$cM$V#{i_n0AZ5n$&I688vHy>Gljq*Jx8o6Jb=TH6R`Nw(K|BVkR#J(Q5IAn24+( zDeGo}Jln)ct|ct0S_onwG>V}tJZ-l0<5MnE$mG)3Mcpu{LC`fyIW)>N5jhDRjDXdl z)JRY|qp*I55K$ush4PN@DI2A;3b^}o6^1An%1RmGbEF!~(arVIg}TB<Oz6`g#M}Fr z{04$&zU9RbL%&I(2D2fW+yxt89x)NX75?l3I>Ihm$_(>Jf-p^=vrCIe5GI_9`1ETL zg$z^EW^3u%DZI3v&6F6VpxqEQ6GRe&AP7|v#N1b%#7v)ZR$BWDLxGSBWu)WmT>t|s zswN9TLj@U5VHY_yqj;lQJQKoAIVPT$i?)rTB)Zh-h*`3Tq>{oU*M%%ud{dyXg!V$Y zgqb@OIQ^?vuf6~N`>N4$`r!|M7;Kmr%6OV}Z{Obis497w;b_IlZzd#pS#_HIrAt9c z*Og%R(|@3Jp|L7W%B*xTNl=pR9^wSmnO3sYHcB5+Fp3yfc|wNG2*R*UE<E>Uv5}Lo z%A@dHi}8qBEizO9C>$-JAydPOqc`7t6C+xf7;>=W2$RIi#L4me0x+lQ(6m}|;vuxu zt<@Nk^#s47PFCNt-Tj`bQ9~F)bKOI~F9{U@O$-HuuiGnP@w1XnM5iK@7cvUU7Qm<9 z4odFP<FTdn<kH%kKny|1{36k3F1+=)o4+Z8bP=Z%j3TzE@KhBgQ5<#9l7rH+GHPB* ztu)CMS=|)GP({c^`Vcl^MHqr^n7YEi=websV1=<F8jy=n1HBAI7!*TwFgv>Bh>!^c zuwuiv7*bdOZvVS80r4mcqcoXdO20yBy?|P7_8DbqA_`C_+tGyi#pIU>9g-q%G~y^B zr>#TtsA$)3UiS*~{Pe}~vy&&sPai#b{N2L`{*kO-Y(2v~6N~k7Ml^pAOV*~f<$>0+ zns1w-CRZDS4AH?<YC2hc_uY4vD9M(!Ebu4mbKvDjQozaGnzV4(66W2WdU8C6#;z2X z<_KEO=WFyi1#aWFRE+-qKm0TL9N>TNZ~jdco*A7_Gn0cgG2P4S3vyyb5-=Zp3q>5d zA`k~2L75EKcT_NR26xHvO=O7?PIhZX_s7d@V8ju_0a-__(Tzx|qemGKYnEE2F)B7g zQRdoHM~@hotiRBE`S9|5$52M=FZaH9{$iBGKY!wE5}wcGIy^AX?72W@*Tg_magHz{ zBTRw4I-B6dMgqe;2}VmNg+EDSuLM(HIj94HpwC`fO6&J9=Y84+f#P7kcJ&&_f?=E^ zyy9RGk9fX>%CCci&I)t(^QO!;ePoEHNfhJ?_{zhFk8a-F{jMei|CNEYy~3T7V*g-I zxFY5M>Xo^;=T}?7d4Z{mCf4;pg|8UptVQH2wB3`5?abf#jYMp!%}y7UEICJ_#S=2g z9AO9u&(DpaTx-c=7;aD`o-{&5<`iMbL6r_>!S3dl`SWM<;KxMxQij<b+P-xtq^||i zJDB5uFGG$hYN4eQU;4U*1W@`k+3HddGo6%anqq#%nc+4RCS_I%rKMKB(4MZ3N1~9B z7lyiq@ZkXAw4``Rxh@k7C~5_%Xp-WHEh|GCNQNXd<x&NzQWB#WnzAt3NuoXlRwBhv z7ruk_wbx$r%x;C#1c)zSU4&ssA2Q5v5cx)g0w{N_0HDF~Kr%|A-6~JV^Io?qF_a?& zY919_$jg&bDQFh3N#Fd2gAtp16=XUjoYK*4mgA{mw(1E4Lz$3MM3W<~5uD=O^simp z{Y_Ckt4htbYbzn1KB{ZfV-jHC8**htQ_!_wM7x1dz_8^P&s~*~IKmh$D(>;=>qdrP z(&W()2`Kp0p?M+Uhz>(T>Kw>cC0+FT>#x%kSXT|L^#G8eF0{#E=|?<5U|5{-gyO+7 z(UO+}-c&3<-)}COMrqa!mIAr<;BdbGOo3~o%XDnHvu<56i<6GXE#uab2nnlz)`~JI z0oKOQG>So-GC_Gs5|uKc7N9r_RhOFBv?h9+1#P2-Xp)B<4?)a^RuqFtnY_`M_*#Zq z`nlUoQbW~;B%zjCIt8Cqh7?L_sgFWKs)whUBWeX;_H~uos9Je`skt1b5LD(-PJ_j3 zkuJ?PLY2|g7NlyxY?LyF1kbx}Aej`;hOo_SR7mv2Z-@?F>F|_|-oJle<jhH$i*)D{ z@)+#ti}_xH)uQWcgxtN;ab$GzSyADs*(NVv?OwA<E=Id`F%$?nf+G^Xz%ro#ghB^C ziLO>W=9H~a(@D9qOt$M|Y{)Tr5y@6zfb=UDim9-e^eKe1RHhWv03vF5P!3_dA+`;f zDKEekP>Ygd)Tcwkg25xoBu4R~`rv~P#0=98)ml+Tk%Qeks+KLBD_5?*`R3cAe*N_~ zu3x{Qoa+N451eh%ef;=|Vqd-LiKY}TrT*)RKi|(6v+_zUh8LvTCSB#Li~!7LFQ{7^ zQSPQ;>gmwLlL!e~1PyIGSZyZT8;*Pn2E|lfYTHVSbWx`(;z$J)ghUHjE{JVR)bwdV zVHjdIzbMzJH6S%YnuUkqTEO7|4_`|kh>$4M)ly@QCx=E8L)Z{roC1heT5|}Xx)_=% zS2R<PHw0>hxm%^uPZN#(3eTwj@-IMO7M(SKk%~=*v05w%yw;Gy92_0K+Pn1f(kt(u zUOl~|YQ2$KuU=V|z%ATAv#9&@`1sYOJrn71Wp1?3=7)rzGkLrwl|KIA<Hz^z-~alX zZ|;Aq{ra1G_pBRo87iDY`$r#we~?-Ehw%?S@BQs*<?x0)e+S5F6uk`h_e5Kz<~8Z^ z{7oFCAW#Pzhl--vfa+Q0%|%mVNb8-y0_v_w*u9ec@gM(jM>J(S5s1^w==0O>*VX*V zn)x$Lyv;Wf7K}O_*<T9lpOXIVzxQ|3|2660-~W&PCO0DBw~3dGuER!f2}xSV7AqSo zW?OA&!gRTrAC%o)lISQF1)7;7LdxTF?UOfNdmW}xLWUR>VTDO2WtuQ2p7rXY9JF-} zIVE+qtk^;u^P@pH+&`ddpIMme<@Uw#{PF!Wyf{qi*}Qb_e))SGdrtW8`kD%JiQAJH z_zs97)Rsk2y|(_?OkE_%HWHJC_bVjLv7&>v>TzLSCtmNGdt9gkWqEkp+1+fAe3_(Q z7bDc1GU)N|gla_!%o?R*v*1Z+mQK$bCS*+R+?fwMp#Z_;Qno?X-nX~sg<ME9<#n_^ z^1B$IkuZ$WRs^x>u9NqvhmNHDGn1V;p!gMo92ZV+<K9E&@Dfx%#PsTt$=y4=ynp@L zjq5ku*H0ZXQ}{in2afK1rb6C@wBjEHT|>N(c(-4ls=NEpR~ts_;jvw>$sNJ=o}xh% zHc3grl!y&avsvIf5cPZd^!Vn@8|FxDrAc$8GhcD+h3%Vf?%lq9M{Q-wRwOI^*%vF$ z`GIpF@^$74fc)c+KX%VEFW#Dpfjcv38pNzCNTn;z<#9+2(Kp|GGgVt}O|nDO=;&TP zx_tH8Ra?L`UfR3l9J9!;UYQkQR7mjI!Zh_8pivTpp`$EzmR7XDT?p7(MKm3n{x|2N z-EpvQ`(3$q_3oX!4)<$UubHir<KyS2FI1L3s{*@s?;gMK%|0P7g@NZq7oWn9fBa(- z58V!2t;?dWsHjE4Xv5%vQ`0uY9ZaQ@9TP)ZX;LtAufIOOU7UQCbGNg2bnoE>!`viF zA5;uwLb35nhi1XE-6F}6QR~lMkR~~Xu%|3dIt<&1x+{|T?Eo%-r)-Ftwp{2_5XQOH z?zzI81YuZdMJ{D=GDpA>1<0zQg{GLx>3m0*Qv{QoAqBQ|F#z$r>xQ6KB=Qo^+QJi$ z%MnfSz|3z%nWRu7AV}!|QedtXvv`DIipv6Fa*B-F3%U>lsY`*CAyz<0M5`5Q5ehHw zT09*?Uw-)|L%f!L39b|-45W)#0k_~o$Q=sYjxP)+(e!Qqvr`Y1`J;g^U%ma#JKx^B zf9v)w@&^wec+!3G<(KLv&K3hN%)w$D6aWlqfg45QsrZFQVu*>5vf6Tt=qE%Nwh{9Q za_y;bN<8n9BFCp-R2Z#2U3AflEwck%Q-ETi(Z>Y1ncy+uD8A{obeS}Fh)D@%8)X#* zWgnGAYhW^5^y#Ocl6?5#hlZLaXDKgS3kmV7T}bn8Uw3()tnn+Yd35R$rUrR4v_~jd zb;^zr9!IjEkjaLRnn7}E^p(-;3L=+2q1?k~hyg2Ft3q}pd=bLOfK?OORh$BT`|bIN za)44MM7ke+^pO^LC5ne5$Zx;9&x$)}TeL~EMP5=IF?6sCRkbMy9$A^6efF6{xV)%Y z16pdG9-T#nhhd8x?{B>Eh9S9tdgq;YRJgh!3NdODfr7t*Y@?1!n*~wua8xU{TvPL$ zt=c3s>2P5Y5u&V;Yb6*720nsN^`!5J2LAJ(|D4>D6rk2a-0V;=j~E$!{q;A;Pu2G9 z^Ur^Ia&mm{-Z!6o^6~NU(@#JB#M6NM>#x7UI8eR4I(-$2@WF%mgTs93s;44=f~m0b z{n^icCOp0*^7YqWTM2|ns9HfrvZ(%B7Q!Y3J6mzRv!rgjm{v(sa8QviBqjjn5Tnx? zU~9pMM2=&5zD{a4S_{Jg>tD+L9a}XkJX;C+L{-b02}VdO9;fT6<JoNLn4O{}OfC@f zC=taGkL4%GssV?|)M71KQ)61~Zt;+83Zf-%!C(jx;c_>*PY_GC#6vNqFPdty)JE8k zX=B1!hJBHA!scDr3`1526@L2k$)iUP)dsJ9{P+>ZRJ-t7658*+`}W3-c`|<c;9E5W zVkNY?<YK0z-|}dwaF&{y`~S=NoFk&=PfzB{8IiCRVa@W88s55fbB^{aUS^K=4(8?4 z`{c>-^C!noUcJ0@Hb36#w&p74Ef=2S`lT%c2gwu^z(^#)8mdGT$VH*ZLee#Hf~N_j zAD}Qt7O?GufkwxFiAA-y|7t#6>E#PBM^_GCyZie4AH1vN&tIHSdGhp;8}gN_m%XU- zrLb&~0O-_R?Zk%Hav|lv`M3WT`L9oV|NH;be=K78RQD#p^!)ILADzcBml!Rf>eEDq z#DT~&w1Oo-A6gTsE{fvFw)2_b=~G6moB~W_GSj?HZJ3tVI?Lus4*^tLo$DLdZdwBP zc?;<?6=&z~z6I)bkDt}KKHl@P<*_$^|CYpR6Mz&tM)?JT=!=#z5|688Qx4E5A=grH zW_1<=kv<%W2;knAUzu;N)2E48Sr*Vhks}iO)6MqMD>+UXg~T&M8)+2gyTYh@$y^Hr z2H^SWym;W1f>3=ZwM4XF;Sk~{{W&iH3@!e9GRlx6b)d|IP>}Dv_a4blfBMru_vikc zj6VPT^Y`C>p8|3=dh)uW@WNaR_T=gOIuLO2=t_zlEHp(Ufh^9_Un$Q!546H&RWNk4 zOlXqOq(Jl5otuvyKeS!%zIJDAjK{Xkm8<ikM=w>yPMmFg$xCv7?&9U?yfAF89i1k~ z;<2biRdLK3*V42IZ{Kl7a5cfO5+nr~2}4MT#Hgf1h4x;}cMh*!_0aY9^2{1>KYa4! z5s5XTFdn{U%`-x+!~her)MUh*tr(y|=Hjil-m3lNlTSp2zjn>hKQFhs63I1l5+<Jd zZt89l{n)D3L1XDku=PM+zLvBHgNZZ5M4HyBsT2b%br4uZpe${NhxZlkSdkZ}ifLWk zc~^u=3ZHq!;YE2}W#EYF?YG~izkZzN^zQB3$F{S?y(AwWU%h_aZIl-?WYoU0UOh!^ zoY(Kp_i9#Y=NTX2IpR_7qS6lX?$0mHH-Ac8JQ$nTW+W6<OUOa|#TQ>l`Jer>fA+8a zYk#5jpa?J}#htKiQjX+H*^C<{DK)S>BFyr*yC$|6$aPHzo;%&9h5{TCu)1c%HBk)8 zViv@2RJG|hr$A^1h`1If9gOhkQ!^JWMQY{_IAqE#mAcA8lPy42GBt{H4T;TYWnn1D zt-JuKeev0Rh$wuv<UOmv^2-*n!qaC6<ltz&d`8WUP-<?9ax6mEwZHfm|Dt8q5Bw{s zsE!}cpFA~3X2jVdB$fH<tFKC@Ad5#U_p?j$Th{hwrNFQihGon<MhcWmWJxA{%35Kg zx<CW~oTk_qa(83>aKYZI-9<kTUW_{HC<{AHH5tIUChl9qAyj!zRe&-D8U5iO{^7sz zZ~Pno>R<gU3(2kL^!W>?`qiT=^F@6Zqq9@5yN5@Yz3zT}@0+8;%dhq>ee>1VM^~@h zxpn*D<43pd+_fV>2?J~o5etCF5)q6z6{qa%Q!!ZZTI=fFci*KfB>5_-sGKApeDHzU zwEh3(zx<c-?C4WQP!go3GD#rY0$};Yt2V!UG2yx{M_@6Qfgy9P6h?KK*u@<b(8R9@ zmc5X?k13a2s2LS11g>Y}uYwC0h}8m|vQ~H!;Z)18$0$PxGzH1fe2K^C_FEyKifw}N z+*}7Z(#-@KD^N^?ilk2gGn;+w4oerv4}bVWnvOD&hd{_2nF~(2{^S?G5IHi$96n7$ z6j;eZ*zI4ZwB2Ek{P7?EvAJ+kd1?H||M(yO=5PL{S}A+WN#v}WM3I;~bEJ~3Llr|9 z5~Ywbca(X-TLycVCjO#@z%Mimb5)g&B5=o+ve|jQK8EK<Kl%|bKqx!FJ?@>K5X>(s z7pc)XI+&Y`p;jg|n7W)|BFe?UP$lW$g-zb<6u(ivDDbPrlL&Y#GOH$(-z^OI0?_Kh zsTF|8Efqt$?S)23U~Xu@x4cLI0;jAdhLUeYB5cSApT2nV5+I2L3AIeT0_9hPgj+S3 zhzbZOLbi06SVWnNka@~lI+T%Uw-!BmI^Wyhh-5`NzatvMaAU^cY|^}PbnWo+zSo;) z9%xS;LnmH=u3q!zaRvYM$%)sGJGWoEbN5zn<Kls^B~og@@_4cJ)<?(f^pf|fQ!l%x zRv@(N*KVH9kJF0g)aZPJ<JCOlo}JE#Ex{-d#G@`pmAV}?xtx)I|NJ#nB=TKrWOoVC z;(?HF$~4mft1GV!Id|8tUB7*6ZVMKGq2@P0T?9c4C?U$bwjsy}li}t!IZ|X@G4QTy z!8j`{_>MJ0^aUepjNotHykR@*(nNfj1#+8|ngH0+q`;N}SYgk%gS<E#9GYofT4R(8 zMjM*&IK6!J%Kodp$Hz~eJw183_v+x%{^_f;+c$1$_q+yQdP!mqFYnt{Q-qcQ5XfKw z5@JL}jxj`sTrhYNy9Q(5iI$p-1i8(uwz)7w4Twt+UzOH|R>h}JkMG{SV}edj=Hrg7 zS}(wG4kb8c+kFX@fwCaS5upeHI>{Yh^40x+{kQ)uonN00e)r$|8!ONu&=QNhb8z1x zlcCc@mu4j(Y?@iA5ku8MfmYB;z*d)LRzUFNx)r)nb%cWyck*7YjgkNy=(G93=D{@C zJ@8ghD2Txd#m_gRRxbX3>_GA0S%2*A##)+O*xd7_AxnJ4GwARyY`+0n1SFwIWQXSw zk3nLaOXb>=Wm*`O3xl{@D)ZzM)Pwn6-<+@#6v9%OB1lv${>|5!Jhe{cIgvbj?&7sO zG(lNj3uo3P2{|DuUpS&O#IWF_^a&-Rs|ePR83d&js;-$8Ro4Z(7xJo*`V4@o2no2z z;538Uc!s&)6vL|U1SUp?%maZbw6zCR-KZr#-Sxd$Q~b)?ulvBubrba@nsel=FPTpq z{mJn89rz(@<udV=E7yR40%FAp_|`2~G}i**nUVSW6L9h=(iHpqiH3<VBV9CJR<$F? zy_nY&&$HIJU{*T9n^`uxDzJM%UcGXCz~-wio(GdJ!z)KuPhX6VFrGa2QgoobasB4C z>+V>Nt=*4#^Uj5xa&du?@FgS)YD?2hnL!gL5(=&w-BjqfqIH>I3xwq0@}Us-_SX-w zuanx?%#n6J^kts(CW~?)^HsssML?QOR(20f4-z^&B1^?ZpPD6jyxyi*&LOx?Mw?^| z7aECBRTeWJIku{;m6t4>W$s2Kd?7+6a3<9Gy9m2aE0un7xnpE19%1OZcf!Xoccdy2 z@DQrQc0-!*R#h>;JsP>D&rkqhWrrw)CKzg3-npY=lv+Xx&~%YRsu+0)c*v<~by*<{ zs*>3nrO6|bEJs2`+`$Aza|;GxwqSCKkx|)!5=;RvSK}9mh2a5nZC&ew%CDAAk!<?K zHqPdQ+jdlmDBxY(bw%ZBtGuG6Ymqp5jglam{F*7##I-JWmKmaNNWkuxFja$uxgi&b zk{ajB7fpocZhb|0UXV&3P28)7teB8%$)`$Qs_mwA*z#p7!O4U#fMEheQ{jXClXdxS z8&U?P)lJh%^HO052>#a1n^&Dh-g2q+69MZ=edGFd7a9<(90a1hZmY}s=<><4d0?3u zXhLnK$_{ajM;N10c(OiZ(%gxV{LY;_Tr)2uDbsYh*9E1>udUDRoJh_O6J0pH!m$+$ z*D$rVFiNfJDGS1YEl4foK<K>j`s+=Qt|x^duzj@xPEe*>!6{5t*{`*Vr%WgS`ZAKZ znrI_BK!CSAa*c@>4;|)GD0n;)qON#Q*|mvG6L)gqH-*Bxy8BVOo=v-75ybP(9oUOR zVWxL|;RymwYN2U`gkcLr5zGQ1E2-fPz4g{xW<;BiCZY*eY%)b&znSYY5iP5)zWVCp zk3as`|Mh>pTl>53zDrF>S*`E-&JUF!)sPw!=cl*sk3RZHD^8W4im$)-?!EWQwfW}i zya}&A@FD(A7)37Sa750Q<h^&_g;}Z5%-~w66-vrm;wE}F`MReynovuDghyfbWhv?7 z@87@gfsT=y4Wh*(I><o*jpjvS(r82(0!C$ugrhtbux>&`LF7h7Qp|+4l8xvTbMt~o z@bq&*$0#DnW7mhC6{#Vo6uB-BhTzZ{jq{sQ<|(7P0j3s_iW#MrPWm%?ZiQ0tBI9wY zdv?0Aeo;tsbhtLcVI%+<8?-wegz7<uLJQIwFvUg#%=H$)`bN@veyzCh^e<nYr-oQI zUoJd5^>y=EAqigC6KO45t$2)fACuGifyf;}+sKre7g5z+!4D|{9!V+*HLbOs9FbT{ ztL!i3Yt>NcKBf}>k&{$Tm036X5mK-Q>uL>6<<=8J@V}Cjf6{Hbi+@*vwPv*Bx=xW6 zj3V1jYA9L?y6U#<#?VBhVC&%xwKs2Gzj4h=wo_;>$wybO%tOSeO)6#QMuzDlp&nhH zBkOSP!$-H~FMNCLnFs6Dqd9M(X|K;u5u>Y2bGoc&B>)_E>xj?_IH4AA2t%JorOCBz zt5wayNE1U%rn1vriS9Ow?zL<4Mh3RYojG1R%dRyFhuYMAJqJO>WXlS&7XNpC@Anqu zuS*Ai`LF)vHlrC`vn3O`P4c8P1R)@63*)J&I-*1rNMf{-X+{x4yeLr#2%7R#Vm)7_ zk&tp$_;lbvBhl)rJ54&{<Zyq!%YS5UE}gxcbH^F3g*xBmfAw;GfYy9wm2|$ncYp1K z-5SN)8y-tmk8b!yK2fgYQcHp`1twanRu?0%;?%`kN1Gf7d0s9CPY6v6cI)x8W09Fy z+v=5rV2V5yw);%GN>f`O{B`DijsGW4AFt>J4KiN~XSRKOwZgZr1j}k=W37x)|IFsf z!*U#+g6Ef~2??-w-g*18&pyTf)^Gjhci(+01SO@p7J&NjK3m<HGnQ*2U=`1Rt}r;$ zZ4}?EtwBq|-Vn{qh^PQ=lA=w595T*ZtIOKZm6X!ydKS*`T8gLugkZ`c2&^ZNT#Psw zL@P~8i4cEsa%@N_M^{YHOcsPG>-kQ@kRaVHi|Ni+CFV<UB=)(sMJuEkUDsk=p=hTF zd#^b1&k_3Ux$EwU15<(~6eAuhR+mCYkf(XoYem5k2{~j!&wE{d9b(+IHI#z)&94#} zWkN#7<)E*2Tj9dqeyiNH87)qj7-)`qvulcgI7}&YTAOJl0thx`LFyvlyceen3y|yU zTNBJF3-ygR-mt}Zp}b|(xvA^nP!^jPP7$UBOb0Qc2GiW>f;A*@$ZQMVtxkR1^M3J* zU(l?E9#>l6HVAwSg0FSp0x=34rf8uFjO#5DL6R6Ep+m?uIf+&PK^dY62M-hJrob<` zTo{UqLhdlaMi``qTO_;6tRnDR9ds#UDCdY|x!RSeQ4~mlq0n3t1yBWKRKb~CxqP%| zAu>BXgSd{#OAdW2WKJTF`8Dd_++_~-ov83Z30P{{D&z7hTA}9J<vVu=d-Ky%-+c3p zic!$g(V8r_+?p~~G9(_h-eA;$juuWUCk4@xV793giBk)M$f04H2;MUxnWCIm$u&V1 zE6Ym`ThI1&3%K^o?tC$KoHd>2zYb$}oX_d-Yie|n-9#czdrhdaz`y?5YhQi&CBr!) zm3_APE11Bo)T1j$PI6~~D+^x_9?q9MjQVFf#4KPf@YZ3;%Cz9Q=E!ZLN0s-M+UhUg zL0ez9qR=aWsBYf6Rn6%@LjtZurc7Zm4CzBNghxOS2`jC5xQ+*l7aj(hw<QQ1=>lx~ zWXp^0#Jo;^QQ2|ca^RRj0T;#!YUZ?Vvy2ilArTTuIMg6)JUQ38h`9%$BFI;}O_|nf zWPpTC8M&iLCPtM}ctVO-F$|s5z;c1ue)Qpo{2G;`S50rT4nTm+5kp;8`1jv`UsqJR zeYey5D&89`q3~!@14T_F(3}sBFHGGSTj_%jK5#{0Zd3|fzxn2ytYkEwgt?A-{BFms zb@Ig*Uy$hXrG|tG#n-)W=SPRsbH01Lw`bx^?wa%Yjnmc%D^qDnKmY;u+i$=9{PWMX zyfd+#0a7#0gwR6jMU=U2^~bQqtD6>Y7Vr?5L*qqNxuy(3BmgOp&=+t#B995JNjERt z;mK1*Y3eo#IUy#ix=NG+nyFnxL6<ol-G=bv_}m2?F%)MysiE+<s4$u6%2$iu42?#a zYh##1)U;O5PVZdvqE6jxQ@FhQnZey_VWTZV?dUC{%v@D0hRQ%fd7HHj|4+4}CN?gr ztuD%A5^7pRvR;a5S`WK_^Q4)d+*3~qQvgUox4uqYnUT<+zY(^Jea0fZsA3F<Tz6}c zc|mE~lH?n)T6yn1eKHq6?$kp<c^3)cI<x26NeI%Y%8--b`^T_<-I<${7`7@5t!h{B zs;VIBjM2pyvK}xtvMrA%aTMSiWthC7BwC}C>~~K|K_tqB1XI?Ei4eGrZ%eKNY^Gbx zb68xNV^dx$qtdZl&Dw6A7w}BmB0N&k%HAOpui9*NndtVg#@ovRX2matJIthU{w;^) zaR^^`LR?QGARS7;A$t$XoH7^u>Z*ewRvGFl7jWIb{rCQiJ_hOE{Tsgvx;#<t#blmJ znAalaSfSO0P_~=AjYJ}>g}KYKt|5Fu^MZ8c#t})SDf9Fjty{}PBr?y$=w?X4s2FSx zObF9`@#3vF-?TD<;$5`O5W~&IM6;~$th6Zb@R9g8ch;0JnsSG+LbVB@aY2Tsvj%tT ziO!no$JegSH~pw_ao|QaUtbt~7qjJ)i*eVeNG(n;gE&w~oXrbNw)}#!{^W%xDZ4HH zQe#NS3nIrGl97-wYy(j!_f*R8B}j9HvHJo?bTq%KyxVd)ib$e~{`?e1q6Jt+TES=; zl5>qld&wuxmoM(zz1uf<g_N8!D%9{X<Pct*zHkr`3OG$d3f8B`GdT&l%1{u--u}GF zU{YJaqfnO|>4u-0;|?Pc3S!WTt?cONVsx|8)$*mzm=G}KPE%DYECnV!E4%-!5{@JK z5~qXbNERl=WymefF_C6NPC6jnsF={9z}%g~Br@btD_;y9VW4=FBb5OtTTq<Bzjk%P zo6y!vCUYfXNRzEDk4%`8oUHGoI@CY;<deQArbKRUBEfGnsAYoT#cZhq%)F=-Wfvm~ z&5@xA>3olW_uaRARhblwHf!)nbX~2u5I_9m<2h$^Y0}|K%!UFKp7=Aw2$FX^L-=&q z8f8U}-^G0XXQ<ZGW!{Lis1$NU*`&aS)5BPOFwE(rG`YYtbQ=x<6);U(QcG=FbpM#r zp@M9bJTzVm37BhyH$;cBl4=V~Iw&=u^FuTX#LyN4hK`oU??)~2`IU`19L#U697)u? zM}w6q47Ya0p>XTQ{6!hnBN2egONx$C08|r0S{}J0d2&3zuz(jE^S(5RXIpq1>8_eg zJoGC<L(qyDL(M26C!xe05-R;jz*VU<S&=}1@Aa4@5G#kTTnG|~ml-bxzwsNt@!4me zc^49&1L^vFe{^m$773HBRe_-FM=p50d0Tnrhm9Rj6u6sdTd%$fi!p=@4dSBX^=muA z!wZ0p`on~Phae0?ik$g__3LwdiNPoa8gnmK<ami_DVr3F&^*c%F9t_PE8Hj@3}Izi z6`hj0Z&t2Mv|NxB6+@J!E<-1;@YI|drk#lQYR3f~_{=jzDO4Gu!l$;?L|dIxmgAdm zya7suy*eU1HA6r7$xlp^sw$M+Ta#=d;<v*}>)leo@4fe)YH&v%ag8vy*YDzrldVxg z;KhTI%Z?7$$|7>Pi@{{kC&zaz=rSayL#TB=TTZs>*I$4A%SHFs=Q%<6C;#N1NQd$- ze(?(uI9_q_*RRdrs!%|-Hj6D|8I%0MAN&CxCKp=Cg8K5yFF*P0QxZdFR<v4gv-BZ< z_uY2_Q*Eu+V}L4Szc9C)fa{8r6?1A#5M@MxU!)p>L6o&5ssVu}h6@#=uQ)(j6-*SI zj-)WcBX5W#O44Y{Ny`v5RLy}146m)5cdd9ZG?Oz7Ka;GGNhI8eL~+=rtcyn&-CS=t z+AU^`p}_IEW2Ku_L^B=fWQa&MI#_=<G~q;fPSDUcw9)?jgxZd%k!(7x6LMX)M(5iq zD=DMemVv26JB4%FcrSy}hqESs?ori8izmlWOJ}<0%b?LgSVT>mnpObX=PynKy1;gC zwkUA5D##FoO`>Q<C%yCfXd~++HHqNW-^|*n-n$ugARB^KmkEi@yG;ZW@@<(#phD9! zL=>VmFc*IJd4^~t=gU=>3w&~}v(?3rjKTTP7JnI)g%+=}gzL)+Gml7d%$GJzZ3V}` zx4{W1S7)|{Y`waJa(;8ztd`qxkOH2N37!sL<f)}V$ORrFY{f}Jr?3$QkytYgq2*_{ zPwQ?jI#TeL&OgVSLJUejM)e#@P8F`j@MrcN;Q#3F{4JS4*AY5q^Cvj<DkVV^YAaBD zb*XC(sI9PfhXTfs;}wtSL(^u+q_)wz=%S96yg9ShR0^4>l*vtG3+U3zSNoUNZ@UYg z#`=3Ryaxh*3r|vbRzSc4Aq<29VOE%|@Y)sQZabA1y_Ca8n2B?J*)?R6^B7**O6#B9 zILdt4@>Yr62gfYaS(%xIDd6=R^Tg+Re4PiQ6{;9yVJTSj(uD7UT_R{8E>OW>1aASg zr6GWFKk%S(C*a9_hyp-E=P^$-B8d*>=UBd%VEBsB;+ZhSi&HBe5~Cbxw=94}*<zN} zp31Iy-fh?9K*TJt?Ic<$4qdrC#R-Q(;Bxu&(@zO^N^554HgkI}>(VNWKk0hbc0@lp zy7X#pu14utb%wT?HEV<^<BeK}>c&b8f)Q9=bkk%=NR!Tj9W*U9LqL!rCPrzRUkY03 zyVD4s9I}~mzhTlP$@BrwDFv4~L%O5vgk2$aykQX+;t78ex4F*Frt;S9<$1j~O1<DI z;~`V#%f$#m7R<Hl^Xr9Hr1t^kr7Xy9)e6p>j+z7&e{?uMG040CWG7A@F(eQOc~l}$ z4jB&=qw+OWf}ns)Up$oQa4j$|Ck`3Qjj)2#%mndh)Lm00#p4!84WCn*h+kBAx<U%d zoI;>UE*KJ2WeByDX{KYy@(V}U%{AII86u@H)O0hE5g~9-ZLbL&^1w(?bCRtupF8UO zqqP>yKw_L>40R;M<3%sRUaM>NU<D@^_xdsSGboOs!^?+L*2BZovr~sAOGBo1Da^jc z7#FHqDR>!?tG2b*sct<;p9`*U-JDy#M2wmm9<?Izaz%l%Dmk*6P!e+-J}V?(FC_F; zhMWY?H906b_M=m}c*GH>iU}4VY9d(Sr7XKnsJ;LoQ(ZOE#b{lE2uWz-nSkXB4q{qK z2{{${#~**}bxTs#x%BVexedp~@bQz!a(Qv;5kB8JKR!7=I6Qdr^ocp<x0=uSd^W#_ z56z@7uW0QNyjB-+N`c%9utYG5pe9nICc88tSZpNi1*3uyr1<HRVCs6q0mzE?0zk~2 z6{Tqk$j!?;@4O?y4860FR8Q?N>+lhh1;B-ueA9%X>=~prin7&uUVB9+X=Wi~Ooink zas|m&F}3jfRwo^D2wM2uF(HS;1Ve~K?j<z^Ji>@vWxPzv$myiZ5kM)-FWjoss#PhI z15`l8A+I=12SfC5{XTzl;Y4z>A?GaxnpQqJ2?n4;iSqI=KLlaEI>hi=3X~l|beLnj z(_$ng!se6-9r0*6rBf+r0#TgrzMU^@HI=&^z0y|`t;BPoZRx^NYK$%g#D$b8Kp<pp zlt)8APUrV@MnXZ&O$r?WbHph%6dE-O+Jb4(Hl)0~Xvs|?b2(Dec48p<h%ysHpkh!U zMVmx0{9<YmeWRiZXCo4}S|HkONr+*^zB3mXqND5=t>U*Xq7&2>wr;lL@4TCG;B0A< z3!6|kv^3KZ729xXqto?$(Th~f5=ntF`hIABU2eA+qK3F`DVhjf^07LbZ}mTa{{4>@ zi%KNTly2!<Z08RbEy|?Sn2@BfWv4rm^{FPP#3=(uhO`xdIk{0mISW`Xj3Gm{mMEQI zwQSq|;TS?OT8lwEB~sU}F~pEjLKGUgNnb;A&ZNec71BlN6GlR!vjQ9@$<X{om^n$n zqD=?UsbbJ{w*tl>%#`W;XC>f}G}oXqnW1MV^CNtV;G^`fdS9T%;ibLj&z?Vh^3;*x zV(aNs<n#+894SvqiwHMT0a<TCj4q+Tw7TNQID#NlAFw1^I%<fxKqSH|RJ@i@I)%{? zzHWYNNoYa?{&M}qB`TPatka1mgmkQp&L#4{`}@B?MftU9z5@&qmv3&g@oC@*#i12$ z!I9$)NkdE?fwo*G8xBUGc$K1NC>{cjMj;ReSjpt6rA7f^8pQ|zS^?lgV2(G6QriqY z0z3QYq>M+E5(qiIXpt@|s*tG(+mM*?B!M?E*XECL?{*O(wSp%J77^-FbBk~>5*^*Z znOvIRi%@}zKdxPO*-m%;1#<tTU=ictRJSVNNo+NE?y9^rMX3JS7EHtn5o((PXjNEC z^7YqWdkw~bau)$kE<5d(1!nk_H3j&D7%iN@wT<Elm)-7^Ob1~4g2#}Q&Q5sw;PmC3 z-6cyB4mH~kLlZxs%XX1XH8*Mcl=H3*RYOLEdFKe&`Vp61<->_uOKC=R!Fz<zCxHwQ z4vB7gku;=B&1mxSlJ8a`yvGm5C4dz*>%mn=%!p1=84|gh6G@m%gjZK(@Fv}jiVN2Z z*DurOW@!Vi9Ong0n^VPt$#5cBB?1^MdDjtEl))a)@1@Vrz9RY+Gor?$Cy=2cw9@7+ z;(SXAi93ugO$-Fls#TF_N#+B$p3l#}ZE}DZ`UoQ!LYjgUp<6WX-Jf(VgRYV!!syFe zR;=lE7q=Z;(W^WtG?^?Sq1me7$g$u|haf_uJXSh{N0gBv5;)WZK!-5R0CS-WvqF)R zP>yn)kTNEGkr<_)f}zZxJ)55t%@LwmNLpQ*$}8+77<kKSzWxF*1q3!tOvo5kju!6# zo~!+BcauHO<kg;9U#Dj-RP)Q+o~sPkkAd+kJhsKp%L;9Ru}WJKCWV3`%*PF`WrhH2 zg`w1jFm#O4CufeCm&5h*nT9MOI^^#9hPK)w48LaK>G~rvK%~sDJ#G{a!4RwB)H0#K zTs<)s&(_TfBYqNqBmz*zsmEI6+brmkdy%tjz)BV`fEk)!IhmSwKj4v$b!bhJ2Zb<{ zNiHAFpO_MA;9N7rLlB!_)Jm&MX!N5GKlB1aXnAvu0b+w|?R~IbMDg~%69B#a&O2U{ z7?K3l7Ze2i{`>EH-Nk^yXr1|nz)D>A!w*0F;SYakPZc4i_fk6Ifl2euI$KPH7~~~} z%ys!<r2-^OvT~$g#7S7GtpsY@zC$vVg7ZY_;7~AHtJK~td*KvSYmeN)W$lqrGHU&3 z2~Cqx#1~BpU@fPg{`99m``OQa{_~%EFCVM(-&PeBWjbD%fzWhBcRG=4zxn!W3^lIF zIi)-f)+mWAw7NWEI2Ecc@VrDtjxhuc36;K>XML<EvMwPtU4;dxESacM)A8WJ{4PB? z!c-Q9rT|0DA|zCE2z0C}Gbm;}U)C7LC}m|wl*PudCHL%j0x14muw}@kut`iJFQ8Cq z0!f)|6H2(?XJ(;sL5HDGwS>AQQdxMXgLDaj1PCX;<S7&b1q={mXsPTTmkjY~211A5 zO*4F9Aow)NBSVOs@*plulvVLWSy8Kt*GdFYPE+ZY_3pK2Del%bow~?SM9pL;X(-a= zJ&=n-)0xsvBmgOFIx0_sDu{M5``&?j&=F>p0)A6N=e&1}d4yFilWv-<1jJE7jyfuL zQ?_b56Tjq{;0<BuZ&2D-mtH!)F(?ycNZUePF$}R{j`C|r8)dE<tT0>FieNW60@W3t zyfh;^t6;M#@F~F2Mai{nwb`bVe1^`vR?GnsjoAevp(DbA(beY2s3E-3G-Zv+S4m;4 zpOxJ14y+Y6H9;zLD@{$<8p1dP$W?q5^7}6YQ>)-*y|ob@O=7EVx#N8^0R_Am=oGn7 zg_p$nAgUCMk}%wO@{5k@!mQ1gnbP84S`&+C<~@&@Yw657SodLd_`QGd4;JdLO9%h< zU-`G17yrcI1+6`+CY*8X1mRCXn<^5-QXKS(m_#NCk**v>Z>oAa##1mihFB><=DL&r zT4Z=FN0mtz<!<lt-r1|Oy@S1@t4I5X`!6reZ~Puz5t15RTEB2E57)f;^?HzN0}k=1 zg^4glTOzy=k_a!k7KuSfTo*ZpP_$^$TlLzXKeM!(MMRiwL=G)t&i~2tX9tIuCFz_y zdpX~B*gH7f+dpuVy5vea{QSn6f6AwQ{Am87I!9FrAQv1dBfnmLJQO{-U42{>WMQMR zTW%#H1o6y2NobRtoVaQ{^aRJ7WtV6Ac+*WyT22x|4Ef65DinaT`<WO!BdUf-c&d8h z5nBgAMH}XDZ09$7=le^xz0#?<i|^r!Q<^htFJD<|FX+ITZ=qb60t_5zm7Qz&+Nv?7 zI6Y%1uz}jYbn@(&3h;x&d7b7Icq@5+Dfj$)wlIMk(8cHqKERx6@yNW*ifzZPFM?>j zLbzOJD>jl~Eu%~GXP!=9srkz5`HSaT{N<y|(trHq(XHDzotrmr-FWu=WdC4azMgq6 zUn$g~H44GMgTn(!5|W%eJGpW52L9@`t7k9gW5Dc0feBu@c<)-HCc4%G#!3*6o7{va zx3y-}O-j0QVasrI9zEoa7cWDYCy$?ak-~^pX~d=?vh$CXNM3*A^($Ae^l5+(AI*Bh z!*}xHxl<+JBw7XGH=!L@7y^(BKrRk1&v)LW?;pMDR{APK;i@-*D@TtWKc@M_U2|`b z-zQI>=-#@0`^L?iQ;?&}6h!N=fBfX})oa&*fLe1o?zy98#oT@E?#z_Zy?lA?`n5OT zdXvyS+U$_$bj{k#pfJoGMrEEofA;9{Bi<pHm-)qo-RG!TF)!zbA}pR)uiW()&f)RN zu~7)KPSy`u%_2Ep(la0DUvEaUuGT@+l78}J{{9?laWc#nQDB}4h6F!{?3^3(;caTA z8U~s*fz{3-qxe&nGplHwJTDK|S@>#>%Q<;?!IR_1{rVWW<zhCq(_1{Q)K-_N6qr>< zVu%oZ`Q?|6Aa>85&tKp-7Y`pjvaZzO#;u#DFVC)Ay9yJ&15g;VrPnu~Jy5J(sd2%4 zR_Uer(NMQ`ju4?FM8ZPX*=4aYsT5pWjC3G)cVb0Zcv{N9kDr~aX_|sGas9Jy)lJ2$ zC{w05V!m_tPEQDiAp;Q@o<xFT&~@aJP~-9Tox88S{>EG0JKufpjW^%YwF3S7(T{)Q z%GGP+Z@=^Iwd*%1z4_MLBtQ7U4+PmOC>)r5FZ7*v-obb~MHq6UNO(durxv_zqNH-c z-@bF_{SQ76`A0wafik`h<j$Sh5o`B(3JbVrt`wXYnBEvMbo#ombUHDFgv_Qgk~=zN zr{<=EEeRdA7>gJK3M>%%P8)__ef5=DV|f4meG)^SO7m^l_5NmvEx#B;^u4c=00&je zRxqZOc|sQ~EuzVhF4rO<p`%M^e`(8FNEQYLNN7?piMr(8_T?xVslj1R6GPL2VXJE) z(PW}})JR08N-e?&ZzzwD6`46lUQop*H9|w=gw%vbA1pO|2y_sJU-%8t=hxg?T}lTE zef{;<HWzb%-p`LN&&qEIu~I7~g`>921uqO<jIy=M)W7*MBfy!HAj){QN+A+Nc<0t_ zwnf6D$lG@k0Z89aq$_MD+!;-RFc3%(bFLw4;fR((qvdM|NOjXzNt#*;z-iKNF6dCe zP{^;A8X;N^cd)ue#Y9U@<Qox2)GUByH^eq8awY?M4vW%9bPy&GRyn0pJa|E3X1^?X zhA~+U;-ZEUq8D>P8rsErP5`N4wjs#KHOCMl(UR0fYHQ*UW+$>ouFO*Otf07{*10&J z{kAhy+y1*+_rgE%s4^Ow$hEpjw7aO*h1@@n)Aeh!Bo5b?+Pb@&`Qkii1w2+4!cMYk zFl%Y!W165pT{lz=O#y}uUf3QPbJsn;g1V2H3R$`k&UJA<c-C!=^z``)i@|a-*O2F3 ztXHAsd6@MHozq>DImb?pkWg1K=FO#<5(ZxV#jvGWSDLyQTTJ!v4AVht(&iy+{n)V7 z2)TeZh7;QE_rJ*P_Z#cSWJo;1tY;MzuYc<eV9%O9IX+Q)@y;z+1)pozhajDu*+TP2 zDG2PRB?s=GlXsFlJ#%SZav;afZoB;1$*}=X19ugbP>uPj^!g2IvpTii-<#j^bVr&> z&a&LH)7F)X`cyjSkF!gcd_E?1?O#*@=}XNqrBxQAl>!0${eSomwZA?c{MFz6tF7bl zzo-bFKAGS6!Z>_IiKnK@o<PN+o)XaYym7*I?vpdeh@KjKya}V`dBcR90=e5vYdY6i zaY3TRV<KvETFuMS?)xejm^>BI2<HQ-C+u{V+5})FIf8o(8xo%LJxqS_Ex16C@Zeu0 z4_z%o9vR{pQafHBNuL}V+vIdG0wclaR5+K{(jcTvvg$ee0SIM0s}R;1wD<hk{17ZP z{iU!2WUJJYa&uBrH!A#k*v~-_ARS4e0zeCPVk4Bb3l?NG0b=gtXuo~_`R7#tj?r~o z&JJWQW)EQIzzc~BEgeF!fvrBppzB>!o0>M)%ym_}iV;=~R^B=cQQ)qU(x;PcgfBw0 zKDK$nW2;a`@hW4(Fh_7mB8G@2!WaTRAnVm#7eOfC<?75Wy2luBYBGhRP@INOC&Ti( zadTb>!_=kB7b{&1Wfxy^S26oV1zvyswe+hq1-l8EN-=0{8IwX2&)w}?x7~+?1erb^ z<W>#e)tOow>dp0`K~{we9B?{Sa%#2q6n*W3hY#h|o)w-KNJZy}1iqy5LPrcDp;Op| zS~vCiDc*CZ^ubz(nIK)>>lVg?@4h3n@VfUKS{b}@eFTn-=301|8#kr`)YQa^b&KUr z^<22c?3xJq=Rg0sA^7wGhy=l`{^1MTBG+{YKvo|C5EffbSsAsP(1#y>s7q*6FbXcm z_uqfNB0z=-M_bHQpwgKpt?Wpyt=}@pq+l=+A@7K})&h`)W#Z)r8im%O7LG1hJY{^v zfnX<y(2ZG1SrICfEF?%%P3UOpn-_Wg=5PL{2n=1DpCh`lA~^J>$ggcS56pEQie?<` z?_Ik(f6G8Fyw7y6Itb$@Klw>}0WyeBKKbOge(SfaH>ohEV}dY(5ddDP;gFa+Xf5xy zk2xi=0PrLtheLr-UMeX;hPpK0c;j_bBa$jcO`PJvy!-CEwg6@Ip}%{#yfeu0My-KJ z<P2GH0Y`}hHj&(#A4U~FtK!sVF5r(o`bb8<^E<!eHSdEDKA0EO^@T92LV_v`6No+j z#TQ?wc2M%7M!D%z!=@es&E)ouhp*K&g9sp;zQZX(fDA=0Bx_zg*1yGxr>w}IefAkm zN1tG5szW$tM_KxHQ*!v9e)_4HB~D+>?I|Gt^q>CIfAz2a6<E=7$2-jJk0DVL8&&Cu zSzZtbjkZCW5iJrVzZ3R4Y3XaZriND*U8KtkaJ=GZK~ca9AV3R1JWG8ZB0!AN!5dX9 z<|O$Q8^6*N9%QzBi8FnS2ak!?Wkp{`y*(NQf<#^z%njXIKUSlXghtD~fZK*Z6oHT< zCJ1j-S9VIxg_td~>dXqkhX&aY*GLSYc!!{*wt&f%pp8Z@63Uj4`xsk(8CGq!0DttO zAMs1as9DRe#dCE2p;iD@MoZtQ2-Sh1T2W9awwS~H`Peg&Gcn2$O+(Ny6$g=*jx6}q z1#4876`l?dNvXNz$|Dy{$muY|=b|ort>6g}hD0R!1(;eoc;->viD@B+fDsj*P;B@d zZDE5I5>miyDQ|#Un)IWKe9I4&W`Q9k0<!VJ@=Jl{M!FCJ5$7hXMMOp+q=w=fjYuM1 zt{yqMckj0;t2uILz}F=#ut{>#oKob@kX34Bnji&9@+<9fGEXS{N^W<V3~)=Knxpki z(V^UpWbJ4YYIPwP(zbGz-S;z?WHZqwjL0DbvJnNEWoquUV%8<ZTZi<k3`r(<P*wt4 zsg)fy3K4Tu0kv@GBs5xrOgKszpkmfF8X!5Lm5(8T(@;t2+QPcx$x)+(h=RyHO;Ql5 z77yK!r%%d(TgkI+&;P2NRvjd$b#!zdl27J~1dkxZ8;VFK`Sre2kl`S~I6xezz#C#K zJA|*o;xU9FREojhebUXW@W8h&tHR)-14q`U^D!<nYXy%{Sm%G&iF{QGS#$LF|It5U z`0LZ&|K|VrzXb}N`(~?wqy1SZ<=iAui%2f!vk?%K4ramZY!L-riD4MpcnN9pLauPg zkS+uaTPDhZ_U7YMhL})hHQ(1*3!2XQ=IP8$L+HxY-Ln&K2r)#Qk`!Uxh$b&m#+wgq zGhqQ04+P$+CBL;kc172$z!5netEYTv(l=@dPx5lUJu@pW`D%AD!)cM-x_QSf(86^o z`QW{Gs1+x*$$XJucHH@Pis<r%A+&B_TK!*t{k07vTFQhJ>=ps*y4aZl#6<AI=1Xei z9>Yv*Fmenly#11bmPAHIs}&vbgB36wk_9+F?Y0R~(GmiY1)b`g+Vvarr;N%@@Kdq1 zFmwg!u>R(oZ(L+ut=vlKpPlZ$O9oa*G^?smJ$fA<T65=Ohv(?-o!kAe9KX(e@pNH= zNy1#&1z@Kcnlirn6AwJdO^5pMPM^Gj7!vS{)2S+<p-RLl0_epx1Ob=@@r&*1dcnv= zkw?N{1wmQl;_AbN+<)-lM{-vR2qGkuyQ_>Wm`BVxDh!98qFDeg{nf<#hl>&OQJ57v zCv~OM&i7~67e`=%qTf+iA`&zzB$~Xd*f;m@QwG9ZBwXM{wYi|IH3ivTTR+-lov3+^ zfI!o-;>$}WTSL0NZx}^lfX^0VR4H8Mj4~97P=)8pC{5rLxFa-2MGk?vbSSVDn|Bz| z(!m1}C#zy>d8j!<E|3%u1-^g?tTzYS${Pa7kAM7QF8U1uj!ZFd3QrzAwzPOuffD@l zfBw%)ft7hFBtp^B2kvE@cQKGKApy%!B-?tcI2byI>#rIEVGb4)E4$nJw1fz$@$P>7 zhky8oqUB&dIDP);{3Vy&`C9$@jKMp%Zhw96o44M0^WL}j5BB!oc<aqCKmWoK{rt1f zZrzw)&g2v+i<mKd6`N31#%d9at|2AmT}Z;9qX@R1R&11+i%`rEq$5J+lqr}9lB%)1 z&9bD%gg)Z^kN)V7yqZEVq)=L}ZDjRiZk?Mf@1L^92;<(j-)uO9T6|U%I2COQz_~cs zo3*6WLKVEk=?IUZQGo#wkC@A-Su^B>>5C?Gyk7PdD43qy0O?!s0%Jwl5EtatP$c3h z3`9-=v7%6fS}~ABB~ns~hWG_?`fLtiVU$jzG~tL==?s;ZTEV$`WB!1as6fd}%NL>s zjiikF@`P1=bTF?;>Mt)FP*Rq$`fyj|f%6L!ovhDXF+o7A2Xdo4T3S^JKHiq6V^6*J z_B+-s6SFB8F$*#m3=tOsU?n!bF!b^Eogq9SSZkg#Ui!)lP}gL6s2SB#{_L~Qe&aWO z1EWwvT6G=bmyn6}=B@dZHN5zBTduO!Z3Z#)g+UJIV1LdrP7O&GRZ{htNjiT#Q8t7Z z71!a@$*FX-QU=8%9SmZ~g*poWFA=;<)wy+u$a&G$RaIydpsB+aj|o*<nsjt22nh&@ zZADWs%^IFW3?v8wr-CULqjV5hLPHdIL||c}b`v>#LYfhC-KfQbA!kzX*=h}yQ~^*U zB&jBN?n;ej5)>?kRg*=crAf#{OIZrkS}hnv0dMF}6Dvb-cu$Q!1WPp6ztUR9TvHZ< zxg)U))YD^#VJW0M5ns610Vmf*+}Vr)qOz##6sL){(MXptD0~5<D_3_f{8?cHfaI0Q zuh7ZyT>K&mD07Lk0!WT;x@GkI#e5-*gpScPNrYhy=vpdT>kX8GJbE<0JdZD_(2yZ@ zL*yI6rhw;509vjQh7dymL*In*b^reSPzl2c{k$ex^HNPV5FY6Za?7hkSW!TDI2dv( z8DkzTqF@*NE(^qa!pef-7bO9OY(NN{Isp5EMd6{9)2z?O$Gg9Br+Z_49@3@x=%)GW zWn9Pvv;S&d9ho0Le|BmA`{j*6<Ve0QCsMQVf$%F+F)%D<I+^H3rJpYftSDRO-P}kl zdlIDp6%G(4Dv2-?|C9ML7RF(sl`<DVz{=Wl#EJd!#~+K0JM#bU|L+gT=RvmoQYL2z zSqqltU;0abNln;F=l}U%|JRe=uT6XZ$$$2Lo=HA`A>^#uoq5GLKWLf~3e==GW*4Zg ziQKBGC|mSEF!2yj`YJ*P>E=B(=6I5YJp`8I@ap)*NBH?0KI`zM;{}*4W<-nnrRrU0 z6>-$o^<{!sl%xqmppXDexo+vxp$Upaw7Oz5w0AbE8M0COW(d<`yK*rh$u&B8F<<KV zlQcCEPix4mA0EuzmqalS<|j9H&x0r&E0~oq5N2wz(zK~79il8GI2M^(IEJzasad<t z2&X)jAf5?BL)I&u>R^a1A;YUz=U$Ri?Z&uH@nxF<A%V$U`_4P#7t>VoC{8?`mB&m+ zkt6)U;T&y<P`6Pb(S#!^+s}R4Hc%oPZ+_5b(WbefnFabD{O(4sYj~qqugt{-6hHy9 zk|P{*s>>G7drO!8+3CzIIelKVn-@4372~U7LO6Rll_V*PgrF$UkLQsBgmwJw9!M9- zr~sHq*4)X|^O7NbuPf88pSUA&xIhC7Tz8v3t}DyYI*+8^!AJkbty}Y*nYPJ%J#i8Q z!s_Me{7T`2^;cd1iUfkXDWL9F0Vaq!@=gPmrjlyKU<hv|;2{?wo~@`HhuziiWlGsh zb$_MoR_#hxMi#APfl#Iifk$dcv`$IIQ7Cd<9)(R4AmvT2Z8n=|hitj<MTm^*vf?Nc zYTlj1sf#C}R&BNJ&4MJi!dqa3V*cR|f7s%o%vS4d?YDpHCn|5b^1_9Hz2O%j1&J^L zE8lb1^ZBT{cxBPbOQv*K(Wi#bir?!uZ&40k7W7?<7tVZdO|n1&r0-$%`04y9HBejq z$q`NZG#PRs{xQ6KbmARvJ}q$fGlv*cz?KOnC}C^?_iQtp<|5au6jOxdNS~ZJ7f9W- zgd$O>QXtVaO+vB&=;O%+{9C{ETSdY<zgj$rcgs&c`9!N$fA9x?z?T@jl>YF?KPXy& zl(ltP@nvi9MZ$#^;OX<(vm8-Yd0UUN(InXdrzs?}X)$>3wLQIoTduNZLRsW=@Ku$q zcRUGNGt6~MxitWaj_yW;2qWtxOpw?RrT~gr7o&yz+U+|$mQIr;V7zLGR<Z(Ue!bW6 zzJGakA{{sd#;>k<F>7X1m%dRGL3sVjynrz$S09*^tr>>YP}Pej?t__7b%0=}5Msn& zvv>g}Co~IM`-0|`!#U+(0@um~2DR!YVBSl-r~n$$(h-9p0pQsdiHSyrRG1?tstXoJ zgo0NVP<Uu`sx2!D2*{gnz1|COt|8C?f-e_xQz-_9%5wQ|zSagX^Dq&^iDSL(up+_G zq$6JlvJ+v-6eL2KIk^f@z*C@XQW%!0%2TuENh*HcOMgpBFd`&`42^>FZtJHih0g>} z&WdZ@Rf*l7<4OW20>zdDG2etyL-3)AAK$8jTvXakGrm?gT7yI6%rUvx3@<W~f^3P0 zpj!;OTX>s}w#rD2noPq-Y5odj2#O}YRl%wGorwP=(Fd!ZDdWN7o6P`Gd@b)ZkuK6j zJGce7<IZV+J_q>wI$TsnB%+0e7Y4etw>t^R5k~w-Z0TzQi9gui;iGL7W2s04jn4VP zLzj<+PdQCI$(A)kZ9Jzg(dko8zrZp9h*4yc08t7U3R()f5GbI+z@%n};Tzp_P);!m z@_WC0sgm%@iw*{$P<1h!vTa%&v$t>GVp~}n)#B~1z;%;=LTvHH+^AKjCN?7wCQ;#` z!z*)v=L>&zeFDq;toHf)Ir}*WUd@*h43R%O^$t8<3LXVWq1%zuL+~&YR>NFpqKoj< z#>J{L1woQ<=Lixr-jI{l;RCHF4hbBiL5<_R`R=rMsA=uBcsfc1->BQEV}Tb|_rLr8 zkFy{kG_@+gkeudU_zQo5BWgVU=l{)rGhTje+WTMqAO6>+il)CixDW2!m_P21lz<RX zLt@P`+9pqkYE-yNCVElIM7SiGLnF)t!vq<^Gi(SxeG2$ANk({N0nIvtLr&-N`gH|$ zq_e#MBVBpCIGrgOZc(t9GFqwZo>C2MF%XK1WRhPu;4KVEk!Sn-={$WAiSxZBC73Xg zA!^#ZpU$rq?1G7k%>#xD$hr`iu+@KYGJg#f=~5#XTcb3W=ZR_|4b+Pl&kiro)Bw?L zg~cQR#YB!;{4)9efv3gOY`!*4YNqw+lj9pV=412=6|$k?!D|ssJmjk6LVtQT_~ay6 z;q6A{vO)~m6+Gfecu4`2A^1R$B}8K9c-Uxr>%g<3pH7BRfys!bw-n}h*D1%xR?PCM zYe-TU`ErzS6xMfusp;~l#gj0HNui9yujS(S#EorW>7+&hau<F2kTGnXBh;8^scDTO zR$5jFFAMq(8YVXX^{cx-!`p!ZL>DG=r9e#7Qx=5$sshIA2M`GW0maH|5|f;AA^w(u zS_y_BC_~BuAEtTHEge*G$Ps*PbxV$S%OnTb<N`#@3qUZ%%*1BlMLHC^l6FZYx0@i0 zkMm8c%`Y{)f;iC0DT|z6w#@~!g5gM!LCKoLsI}c8Zj@RKTk+tvoK{ti1Po0zQsejI zk3UvD6464VK<E(f`_*uGp$z%wKmF;AYx6_V64b&0D^4wQUMiaKbm7Q?gaTzc_6U6C zY5~(PFD6x$qvxkDJd4ypf&wN~I+LXi)P#ZYS|~iP9QMMkI|J1bEu9tsDrRL73Erp} zo*kc9?p}i_h=-61F^Gg3AqGOFmLq(%rKTXdMtg%&E=6O)MQMt&NfEiJ*A*>W40BBD z4LEm*UoH^+N&$+w7EfY-y}tgW6A5G>gu3&qPUjD1=2|=gNUn<ll&=@mhu_WT*5+DX zNJs)MNJXFt7Ku>4(){3q4|MO{yC=;rzx<M+S4VTlow;M82;B9T(wXDwK;sC$mXI2K z!D~rGNLZ-4gjE2KimfuLDxPwHx2}&zQR$LP3Z`_#AS4ot7EVW~uuophO(=Y$+NPCS zD^?}d(+Z?BYv5#74w9n^2#+r@Fwr8CZGr$kKbs8#3NlRK7?CT5_U*UdrimO-Tv*k2 zZ%r$tpjt)Z!~+zMyf%C!HeEvD>1t^jZN3_+Tr??20gw8ck)Z-30nS{@oME=_fAFrl z6}B!AjMA}%rez{vxquSq`kQDoeau_KkXcndLZhrg(>2Px9H|vNC>72S51cJtQi4$^ zwj@9x(6?^s7kmiXiDPxONdQ(=9-&nkAlmrqLjp>-Nbn>kf;qxNK!zHXBf=mOR)~a7 zB}#~wqkSqKnk%~RpVyfKPe@-#5O`EZw$23d)`Q@+hR6xiWUEU-3u;0<-}NxXgI|&E z?y<-a<(4r_T~HJ<r~ju(ote;~K&?n1@NSf_p%^4=Je?$Ta%~E<thVq{Xd)7BL^4<x zQb6(lL*D@=i2=n6M&tuNf8=FsD;KrGlgO_iAQCTK+R!kRi_=t=6d@OAS-kR&29KNx z;bs!Usr6upEoEIHRRjtF8r>8yf;7<-7R>Gom+9-$!9&nRx)cy|wy9w@7ZkG6LPq5I zMKpycB&2JIgcUvnhK4XjZr*Li4Hkh4ZH|HqD}fFw5^ZvPWd~(zCq$b*I=VJrID^UR z=wL1Ed3oxuXYajyF=q%h?k*o3zS_HV{M@?QZAKIba^Bh+z-jV32<tbe9z2+@U?OPr zx7aXk_EOfKPsDr!rme>{5P%M-)<c@%V9s7$Iyjtfs_P0st72N4A_SVU6PObftkLJE z<4C~d!Vo}N052G4^-q5C6FNMS|Czl2|0n<1e>xE_;+R)H(DSEL{e%>#YLRF*9>r@t z(&U5isv}!l9l4fm_1yq<6+&x>x$@28J-<maM{vkVcs#tkzc#SmkRi77n`#So0$4x5 zIRR~JXm6?+<p^QYiFCIizH&!Wj(E{}gl`}yIoqTC`HCrG+uAaV7DVQRxuB2l^wGgn zsEt$%pzVh&EM1jxk34%e>pOSC5Zfx=e4+*<LKOHyTR-!8zU<G1yTfZ-FUm@I$SAZ8 z#Hd_&;k_km?hHwva4t`Kvv9ZNOFwfGSyQ0Timj*e_3N{H=MN8@Z?FiU2RY1+8-`ld zvoRzNSzt^EX+pLP+~ecPXIZXoPXR9me8{{|AfX9dx0|RgUU+9O<`RR_Y)ID-C_?Fg z)dE4+uFk=PF_Z$Hq<4~n(H4)>-)^tcge3G=TytWoi7ZTzi!yv!n_u^4IuZR0wQw9y zN|d>w%KPry?_g9FAP{Plr67!EletkXp2Y2#0;hD`a0zKjP#0z%;Y6&O=wd(=3ZS`& zM{pX&M4NJa!N3%ZmQzL6%GVGz$`NG>BwVYHDoOL5cXmGs$%F!e7C7O=x~9qNkYWNf z%YFZ_A^IW5kRvB-uK~*5A8mqWxf)u541v<J;w49TLSd8+r*JqGEvPl!W90#64Y*Z% zF<|J0lP^}!p3KeIkn~%G-09XT4(8&yVGFQgVkqSNYPr_JA*aks9~x;|)y;x5BsLPa zOl2eyq4@E?{N*oy^rIhr{`u#^gUmH^uFDJAcM3?YuUs%R1t!ZTpC{{DLRx#usCcx( zfPe`EW{)}ykXB}8nHS544<T?(xg67nu)V9`O$VXcmN*x+plYQiFByqpw(~j(NmRg# zXkSZy_uY353H}E^_`$RFBe)0-d?0njz!nLq^G6uMK7O+M3v(z&JR<jY&6XNlb?$l3 z&`JRN#TQ@TKm72+9^`Fsnr56tI_f4KASGgm0!Et5#l{?iN_@+g$ArlfB78F<7(=p1 z^YZ?joQ8A_DUP<7&8c`yG&PG;iA3cESQid`m>mmZqpvj`kR@vdc~Ochhl8Nb@4x?k zU%U``5B(M6tct2s_vw6C`0iIsY32e$ho&_q2DYtRA-#TQe%AwE*a8p+TeKB~f*}(4 z&0|Xo6v99g7@<YQghvFE6@A`yKl$VnVbd|`=E#sbAZh>^B2e$XH$Uc0$XzZl@D;WM z;ggq+q36%0>=+W|GQ<}NHC>oY+V6%)3^CLSjE+)B8B;E7sc}aWPp2$|q_vj?%!Cl2 zHUb!96cmyXp;_QMKxpJE<K3pvWuiD0HY+Wj1e2Vy)C@5xa)7#UU_vk|%_=~jf}s>- zBoS5!AOy5|nNZHxe+pU>31X~R5-UWj_$ChWR%bZ8%TDzwsTd4R70w?Sgcm6<5NN_= zMIskGA(Pa8g_O=HhC<n41XDfn7m1p6xD}0Bb=Y!5tTw}#<cJPsEy^jPv$aF7cJn^$ z1>z#Ya~dqQgQK}YAv|!S_@WAAurAQ0^*fp4==|i&M7|_=qd6Mw{kG?y_=1#@BD`^J ziv&V5VkmPw34)m~ErMWFTi0ZbqeZ$q?)(vnLf!(iHbOw#s1|=Q7?j^^Q@ChoU+7|z zqttS=4Xqf5@P?3~KrqSq<wan4JAw}0odg500MHKSaL#jG2+rOCncn=3s~MhDcDWq5 z_wTQrzWd<6T}VN3)H=_5Gh!dvy905aZ~6mr;qF1%gpyEr<Biwa0(cu!i|op`-g+w> z-3%wXS1(UrT=EFkwKolc!WRsX>Q4yMA#C$LJsE{)g8~bUvO?KJAAR&u+X}+}<G=c^ z4E_4F_rLhx{V(&nrD1P#d3b3yc10n_q$Z!_7YPt6Yek@fb6!J`>b45CbaF9X*BY(6 zgIFM1R?ch0MD-Ej{=v+F+OBp=yexJbG8{x=2o3)JJbR)|h!njp(yc||Y|03q#Axv& zl9)R;=0OWhBH8K+zGStjq2Uka7M`b4s6|GrlBrc{Ym3CLcyT=U$SnYr37zB!IN_4d zG@YK!8WN1Tpi}j90qP2sP6{NLzzY&@GzHs3Yc|R8@aI1C{QIp^izpb<1*qL{yu;4M zUK3szg!vL%$|OP}6c2)9<!qtSB&1Bv5d=fzbQm&^K{Sge*O<-}@vFJ`1KfKx<u6Et zubW8)p=Ji*;ICi1wE-d~lgwIgTX>M^Yu5qgWE_RS$HyYP#q1I+5r+kdb<%f=QoE>( zEC$B}G)&9MjvHTRyZ2i<qMD4(=bD<XFj!SUYNckBK3=&pp}hPI?T+e2uC7`ph#GyA zJ`lW7yiqQ6y-AWljs|Vj(-0l=#oa}Hp-y$qx6fv4NPT(%*7nn+tkTh@h9N{1!O7bX zhkNtvhJ>eMh-<B2wyuJ^?9#Nw`his$^&N>~gHJQ7F4h1IC2#f0#YC7IlHMqwc@q%4 znR1AWhevM+-gbc8ygJ|htq7oy1po&~_$#f!uWQpZ?@bdP8r~2DJdfn`L78<=J^PtE zt6k}=cFLcA`ssV`z327s=Rg0sTYlGN!F>Jo*LQE<=14A}q>SL;?GZ0I$|7vurN&Tk zuB;!sVh)yEJi5#|!fZvWQ0iHoL6s(jzSV}vjf!8KGy#%mO<d_4B9SJAA_R*JArfi~ zWvbc&u=ccg5-+_!{pn8`0`YDGQ~aNO_F3RaoJi>a>T)C`Z_Xw{sPg4kw9JiiU0L$W zM3*Lo0@EdALLa04hO90wps69iOj;z!S{0;G2w+)7Ex&LOa1uC#82WX!hE^&=5VUj( zNjgSlG@o?5wq6qDqJ}s70?=Bed?}Q`jGkSZE0I}HN!}Gxmx;D`=(JW<8~yp8{I-xV zaxt?i570Sg{gjtD*=h^&@X8$B0wcr}Fke;(L--`tr@-h4qrd1OUqOmrh2iM3(w(tI zctRu*T~KV91R_(3U<|=0q$xZSe(gsROI->gF>6|ybgH?iD3{Ky+w=7}-Vq5y)u1mb z-NIv~N<zYW0hSBzaEhveh>bFnEgnOyb`qEnNSXx-te6z`Rs>{-Bj*e?kyB#=fiNPW zrbTpWAw$RuG#O!1+pMUigFz(A;qIbeoOP82r9;2G@Y1A!N8%)hEDJ*dpueiPdwWFT zP{x-RonYZ`7pD25BVa=+MsCurrJzXg5JZCTT88AnFM6kpbhXRRZm$8?(j*Zxo-cq) z{Z~maTM8mclP@zKrfyVMB2q(mY9e6^fjc@?z!0Z2YnR;+O_FGQpFavW((OCIc<nNp z07kx^9m0dJCUWGF#C|8C!z7Or>v^)ezd|ogc0ZAaF5*K@o)8bs{hXs-fJt~HTaw-E zH>X*Vi-baQ!l}io2A&X;M3)*gY84RWF*MZr3@3yMXFY8%x)3}-t?p)C`eVF)qyirq zCCSz<%Ol><=7PR9ISNo)@HrAW5JFw8u2F^*GARH;j23M;&d>Rg=Jk`Um-iR`QjrD) z639k(hW&w|3opRaU8LGGzU27Uxk#>Eo8J~e7fo~pRu?Z$CKyB4ug~eXR`l*A7TFY( zjUt95;mn8eobH{@N4@M02T<{z7q(1W)j8=zA^~{vd^g?c<MWH5?@2-b%|)QZ@PGd= z{)<WP*QUMy%YXiVZJu<B(h?_m@?a*OutJof$O>*UUcqgQQE4EI_yDrfHA;d))5QRB zC_qNK1rV~D3ILH9ZMUpn|Mm!()kckpp^>l0158ZF`64_!{eEGAjWX26$3#_t@<w&V zX$VnHh~eVW>13xXc#`65r~nM{r5)vi`Kk$H3Kz*JWP26zc6@71`O*4{ey~OXMjZqs z2(w_|tnZG#n5z#QAu*)M7MTt@ox;?N!Xc*|ErcBu9mUs`9Uc0Vr;IQEM4bucg`oqG ziPjLm%h6nU59Z@ecBclaED$E9^YbpKaI_>T7$rvnV5oX(Vz+qffX|mSh1wL*34v3^ zbUDKl_I89<frGu>6FR@zx`ka?xNgPb5BBE~f+$CIDX<a}OyS`Td0AKi>|VXd3GvAG z1|F>Ew-#SgctkT3gxS7v#Fqm?OBp?WI6ti?YdkA{fwP4}O--1$?+mGome57N)n$Sl zA`}p-{ECuC40^g=ysHKw3ITZX;@OsvT*_SlT5_!+ZE^@q$g5Q^V-&X4MU9S8XuXE@ zj!LsIibP)3ias)goW))?pmpUH7zN$bSn;CeQ3}EkEsrG1%LNm@G7%fOI4SeRJcgIe zoPx?T<d;OW0N;QAeV1vl?$d;lqMxt%cIC~R55JpVpJM{e<+!|nPy<L<eK6F1_OqYE zv0Q<7^JYRHK4OBW8RIhk_;`Ls{o{{6256Sc#fz?5efZ&rUR1o0dp*-qvj$$fHNOe( zHRIL({OpVq$wPB~FXMFHRZgBfJ-T+)WA*s?vuj6J9v{zlqy;HL-Z3I%F3k$tr0W{3 zGWXWs1~VxNXp~yP=&G<TMkGM!tG}`+l=M@;Kx>anQ!dg(5OjH@FBmjgEUL>^cJ#s0 z)MYY<?fGFvNCF`V<<g;FSIbcm(gCH#OAt??i4YzlY?Rz&u`;^-;WzCse(?*fBS^r^ zx%R?oW`)!mD-wLZ3L^qeKcb);(KM<>Qr1%7PQjHFuWk?S&v#`3Hec#MlT$*iP|0PX z=2kxD!Q<IDV68VUsEK4%boVtTUCN+r87aJWdw$MB1!UKx<Etblr+C3A4ul)G=XcAi zKwAJ$VyyzF!@KqA6<Rv7@B)tkLbH^&ZhT~jP%AcmD<c;qFa<C1)Z~bg3r~yZ6tAsr z5a{G3*yUvC@bWyeWkjKTv!cdIMgS`jD+-Sv%~xbl6+l1?6@N@#1gQe}bV!<9P|iR* zSE1+=8ro7oHW$84BnAkoC&&N|l|o&y!DOXGG~wWdEu-*TVDW~UP>lHTS_<+4g-6sb zCc+D4Z7CoOVk<)O%?ma9Aw<-`MzY?Zbm36eT4n`ch(4hdU<%SGkS#oNqz=|FFTB%d zj;9b>CW!t-xf018OiY^Xnlyifgi%HmAoIwIFOEVBHqv#DDMjmnCM&+UC`~Oj5;$Oy z^JLsypm1vcd+2}QJHU{eVgaj_E*B(@bbcv_A&+czGv7ey?D+LbMbSkUG9tmiN9A>J zm=5dR*J}`+JPLpgO*-TlbEhnLEd>&7qe8t1PJsmJhBodloagBv=Hq_NX*v_cqT)AH zyV)Y6z(q)hJdi?FA|Qk$p^+=8A^N)GW)TU3iC9@n5+qNJ72-upNP(JkFjk0p*Ufx^ z4b5+O3u%9EzPpQN$-JCDU}^f6yDNwDOD<l3`5M^$SGL)!^S^^NCJS(D3AbDjiHlf# zCgb!%O*Z{a=sm#cVS`9Sc7hk7O_vVJ3bJ@!oOz~S>ywQL(}@?bEiZU#o-E&f`)z0G zv-#xBT?Gc={B+`_+XWMhOBa3ofA(MgmlS?|I{0^f_pj!dSHYoKdZuT75p~=*_jt*3 zY^W$F-9;3TtSBRzMq#R&w&j%^(Tq3B789)25W@~%k+BVY`PzA$|D2N{<}~q?F<UUm zeo2_Jq3B`^X(IAXGuIbwOMw~*qKtp>Z1-~ohA`?zF8E*rTq|eD0v-fo=T0d^Y`MUw zzjx|amtL+lZ;Q-6L_37FCR!F3W5XNOzyy$-ntjEDJ8Kj;p{*;(+!->DwTQmf5MoHp zP-?D6B;(@ctnBpBie(5a7cNz9Gg|sa#pBL2pYM9Ue*{+I9t=!8IS?ig9w}%Ebva@J zCj~qg3fL=zZIc3_%|J&NG2Z}rx1wl*?Mgjks{%%~F%hS_+{qLs9{9=e1W6Jm;Q|<8 z3XpTk(EO02l&g;}^B&|D28NXiSWe++DIh$ZvXCQQ-DnCMucXphzh6AGm4z}uCk1O+ z%K!lX^hrcPR0wmt`D!%3H*VdO;mun&xuJLU+SO+#^D#mz+LxB5xm*r+bki02^u-rn ze)+SX|LpTGzECME`{>G%rHMIMAC_y~U$zz22l+mk&uW?ai$tr)x&jj_zK{%++AIUh z)*5i=d(oQDMt%hl{+Z1&PutVGuf3)aLgo6_?c3Jz?3c^)A<6Xd^BWKQ`zOy%u3Wt$ zDJ$~%i}@tsOM92@e|w*;e56bPLzxTR^`X9Jj~>s5(;9LYI6gV%R4_A79(D86UT4pq z51<4I#lu{9c=+>~K-aHJmCn8U_XH!zr^m;bufO@4nrjYZ%8*sX=tGnE{JGZ2W`&p< z3qXCWNeftI6vSjzB8(;R-FFXeT)*W=vmC5VjBKAjd$D)P$?#H3a_QCHSs&x~@@zh^ z_wwP3(--RlW3L&$edmsuQXJ5C?%sX)=#g?^<ap)iipQrn-ua5M!mcA`J|fxW_|gCY zLH@q{6!f(#^W~(Mr}O^s=)pq^51=4Ls7OUC5fg0*SwAF_!WhL^t5&JmmmQ&blP^Gd z=@P;#*+xm2XqkX*om(nkjfPBa8H2Tp5goix>DWprOgO*!o4?7{#(C?lw;VzL{Gb1G zeyNEKfr`q-b1G$+(jnnd)|`qV{aoV-V`!#Nr)_I?xZubw_YeNyUtGH;o`WyH{E7lc zKpsBqm#ki4xHvwZ&!+*UlB7W51%pQn`NdE}baay-$_R3`B2R*Z0q2*WeTJa`u(C8| zT$5<=B$bioH}~gP5-{X^Q83C8TWv953@OfQuf5i)Fs({QLfQ1$>G6it3Ink9VEr&B z(G?^GE<_Ht+4oLvvdm)@xP5beaiEZx&<_)ZZ-`+!gmxA*Ll}~>vp6Xr^O6^ab-AF) zkl(E!<e25;`zsnN!u^AJ{N=Iw;4vy7<>YvnKvslfg<1TLK*?R3BQ7A2<An+zg%hR# zDmW9$G!s&jtXc(VNbp*QhM1uAdB+gqONyZ`xvrKwl$;g74Zn%Nhkz$ZA=pS48O4)l ziyGorY=Xo$$_s{Mg}Hmb(xUXYZnUYX0|hbY%3av_l&cH{g%u$Q&90z48daHU#Yz{C zFw_wJx<;Akg2e;GkpF2)6O*kjCSRB+@TERqsiZ~-5T$^czD+G6u`8K0L~U%=YKe(L z*wL#|i+00{I2Bb>V5k_T`19RDfIxC?T2*5nE`S?a-gf*R2TO0Ky~-6D38E@I4B_GB z*7;OPHwC=eVWp~-%aD0#$}$WeVU)M6M2=^IFwHVP<!ux%hDK4d6Xl2w1|=D|weo*O z$Pk5`TnySx-VmOxG!1d8n|=z0B9SP|RvF58Gh)A+V)J4p)3JTX1xY~+L80Q=UqAn> zDD2@}^73m}u1!I8hE|od6A%9Iz&5+IKVh$MW^L5+r7bq#&BYp;m<^$<(rF_Tl5BDw zZ``<k_R@Q=d@ntFZcAD>XHTC#xqM`1>CZ<c`)B!_%`Yok{D<qVv4dS6Cybe@MR?Uf zQZw}8{6Q@M&j>r6cc-fa#jJFAlD@Jm_rLr5zdxb>+H~+A{++*h<;tAnD!(Kpe(>bc ze8n0G(QFl{_(X;g7Q!Ud3b9A#MidMYt~3XP?FAwOKgELNe&EUKHZR+58;_qnWHBG^ z@NCK<XPWej3Ubr8wrld;5WiYA+`0w1Oy-wuipNllz_gPOO1MOlWIXQ)EZ4<ieq-s$ zljEmPy<yDX(LMjDE9zirSzAGA>C0U%S_v2(<ns%S(HP1qZglid=DQq%bT|FQ$DcfY zI4=?uiag3>MKqMJl{@4Uw|&?2hYub-c<|lni!<*J$4_1QFYoUiP%t`6`jS0)Mq)vF z5s;;OwsyXM`Re7<CnoWPj)$_*Cr_WSvNo!7k;HJVhO=GQQG&6bqoboM5_O<iOJ3{c zzwWN~%hOkI+~3!vH#6(iZjUm780?y(%WmvPj#IIUUlz|!o_m*j{OF0OwBBuKdfzb0 z#_l7LfihgXdY$Ca!^d~--g)x)siWb+cMrwy{>j-Y;ck(yv*t(uYjuoVI;KmDUzHg$ z#$d}@vbtL4m=+j)XPuVX+CHk>!S_-ryb~_-SNHFKD+W$o9B<gq>%ed@IMkfq4svN< zyLwF-tTeU4?5$J8dEd9294D%H;^Gcx9z2)tef_nB=BeUn+uxsxu9$#7dicnz>Vxm* zWel=q2t?g^ESF|nD>_S547YCHx^r9Q?q2ui_U!rnd-rDg6vgYGrRXkYy;&dY7p}PC zaSm*U@~c-`G02PLn#a<WD=KA`i^nJg@61o_KG$n_UKCHyobML>`Y87KpyNjmA94y@ z438f@-afQ_*2P-i&V$2)!&_eCCz6p{PQsp7O)JA=(i7TT>>ubZ-jvMbJ$&%+wY#qY zynDy0ctYaJxxim4?@X<ChW&%9SLVwE2^k7TU`LmacogJPd-+?x`CCAwAVWcdRpD>G z{zm*vzWVY@An(5W?mS`E?>br}c879V25ZUf-uf&FD+iN;k%Pm1>-pL9<LlRNy!QGX z^K$S0*Y4P_E}hMCy{w#jFXolpp?Rv5)`sbjsdU7{yCT2tUFG4Uciw*c5C7%AR1g8H zCpQNz&P#iC#8hSyoW01(tMZ-Ox6O$Jz3Sil=AOA*Wt-=&q-Q~&fBjp`R<E^$vCull zFm}CGB8KLed;a|EufKNs-CmysDtDT4_n?t4i5mFl<<Q|EdtLxCCp<r}g|NGM*fIdu z=9=dy&2^^kKHB|fKl_>R1n~2p|D5HAAATsLo=2!^Yv~t5h6B1TE4p1xF6M>8OgSjN zSdn84d0H`q@YA3E^hZDXk^A?@AAkJ*`|lT_$C+qXM)T=GQif@$`-eDz;F+g}%Fa-u zK%%L|dF~2Wc=*j^5cc=IrWy@Uoa9{hH80&vN}r+qb7y_56rQk`D}L34@b%YUchw*# z$-C7cT2JRsKmD{xY-WLThiF#n0<$wYBFB?3L~yjd^oqyC@uiX?zk0NL1Ed@RTEOc( zJ-?44JfRr)q62}Xq+}$F6!^k}YSZyzRJ00W;#e7a<Bd0HG8_ks@OfDmy9pZ$N(%v# zQ<_zV4$PV2>+|8dB<Lb0UcTHxz$2J~XJthxf-Yoe_J}PbB%@*`K|IpTDP)UErsfEa z;v)e7p+hrwBzQyg^CCQaa+nx^c_%TX%OjpSrr>pHW))QPi&{&$YY40^TWzp-L;(e; zMT9X?P?#zCde6a!Y^F#!C9&8Hi5ZVkG$o}_tx~pPn<M5Fv;s2}8rpIxJd)57;<;lo zIsYl5K%ZulLPAq1bW6XMS|k8EBoeG*F@-VFoTCx89ms_mr4RzOJpKu$2iu(A6sC1! zdHL$}`n4OL5$;PQ>q2ozhl?9GZzwHb)$L#PpbBMxE~(pYbTlvRdEy+Jmigrh_Xr!% zlkmV@as5J~!YS+l36I{6tT(TvJTBzPfWBw4yMvAhSAugcv0NT^muEqsCc<dbjnPe* zJT*9w`Bfa#s5qXFOQBz^Ynkm9*tyA6ta=({vUL6gk#xLoL;}`&aKei`iD_*`ncSwn zxxPrO$nzp>gb_f$k@Vu(d~yHUm8+h%cop>$G5>?K+WD_nOHZZe&j>uHoAvEC_(VHP zbiH~gqAQK`99A>Be&VupQ2JaesoCie041GuhU|V4a8rw<T-Zo1M$5}oTE7STrf>h% z%RQ&{)hpKloX+LWDjbJKwRo}4t$fv9w9Bpk4?pW>R=y2oYY^BqGqm#C?NCB+j_Wty zeAB6Dk9#ybMUC3yUL@rBd;j1ctayK2+WU|HZ~ti})0uG2Z~RxU?w*Kd+GzV3uYBqv zN+dEw=zSGKxoSda1+WsX(z8`iCYjqY-V@cD3lh`gprGJ!^UGiU@}nPoK=}CaBc~oi zqx4_BoP!lUD?*r+2__J<$~wgR-b)AEk@q3Ip|Xo~p<%kd=!#rO&;($CKlV_0`O@As z)oyky@4WV!qmJaovu6(;J$miV9e1>+$Gbl#%Mgf6@uISk+<Mi-%f>H$@r!;-iVN*l zL#>k<HRXbo8U`SQ&p!LiCF6JgNB`rNAbB)%v$h{c+VWCoCN9mKs-daVu7lM7EwxwI zuiw0P@9T#TACstwEzDZAZd|=#^sBGF`RJn$?%n&A+&jhf>sQ%2kZIzrg(puQnU<Cv z1)-|Hbi`v`2o2$dq!rah!k|DdO;&ihSkrwoheYHOgr*>HZr!*k3!7&h*?T9?T*vq3 z!|Pt|ot`~^d3MRhxpH*P;d^%aisbU)mA!rYX8-Kv3!{$yy-NoqZ@m5%96I>t&rYAe zIALWWnQra`Y4dwne)7pDD&|NMlBrQxaSBFYf~Wc5+lOXQkfkh0h7#9OkOCc3V07yL z?Abgm7LibHFSOW9E{RgK4t2S^e&xs^KuB{<>=4_x)*ltv>ZzrG=GQpy-gORoMZR(E z`lrAA?Av?y-+AxdH(!5aUK73gdto}AFDE#DUhP?6^P0_2UeGK{>p|l42NTvFLGvB@ zd2sUd^2zahglrpDv{Du=Ce3mYj38lR<TdNg>*A$XM_%48ABs&RUgNyGi{#pk>n^p= zPhUKJ{N&k-`58hcz{TKDbF^6rA^`{)@q&k}u!t8<w@?M6w&ZwGLHOYhe`xv~i)PmR zs!tUQZL1sQE=Iti0Z|Gj64ce2Q{bjmY;<U{ZGI^O1VXMdT$?*tGu*tmyGsOS;TfVo zRxjq;hR_&RPorEg51;;qkGi|7?!07M&8OCkb@IYB&qD=&eC&{XDJZLt{Oa{Nwcv=Y zY0~9FB7~f_Xa&Zdi4Y85m-i1|xj>lpb!9qz^^#<Nt~c{%>gS7Rr!S1|9nM`4PG#f* z;UUP^YhDL}WK~c4UjOdhyC(o@9MLo{y2{mR*TNxJG(ma_o*d5!sTytuUw-+eRRPBe zu^G3rZ1b-B`WtthH_g7J=yPp_1EfR25ECKcNqCIWBJzl#5<#H6=5Y7m&_X~=!X(sP zsh{4zf8Tqx)OsYFR%@@xr6wdgOr%DK1cD(%Xh<+}4{fW1ytGx78V2Q5tAHu%HiSWx zB_7Y*EYJ~^1I;ej*7+*(T$QLvStMc*8)ZW#_xSPr^jaRZ#e-Ca>u<jK#_?#VKcB{n z2w5>H7n(*T4z2jLXamG^jSpFuGFx5B5g~=to<5uRIz)kFOB{X*l$l@*p*{rBi@Iub zfK#&`EGjLvp7J8s5(Wia3>E-{>cG&`Rx4j|TE=wVd+)vD=ku#ikZCdpt};xtteROv z&~klrI14qQOtk_gfu@V^VBuN|!TPT(H0h84u^l!ma$Wc(&Wn~@3!yq_vm%kNsHmYv z&12r_z$C<53;^-ebW<j|c71;O7vZ59lDh@-gCG1r%5<Q$ilo5m?w!~1)R^#M7E*A3 zQzZn1n$f~;UzCer<V%OV9Fb8&+Pa>DY*}%kbifH65#~ZXcp&tp1`}VvolB<ji!Z)V z5Ng7xp5<G#Bu4QhbT}0Z7aVys=z=wh0yip7F|#Epa&-_7*zn02A|COA6e>+F=%m0G zM%a$f-}#;2`J+GjBd1DVHER<2%{87TvH?Zq>0oyQmt!Cl5O0EA4*lQ4P(Al*?;+NY zyP`d7B6ffHqwuP~z@&re7gef!u3;e)%7UUnFR|-md-uKQ!sqM!^qN=MRl?mjLX5bZ zc`0(Ea6|K2>NV-n;|DLEpSjC<s<^GW(UA*p(px|2P}ccXD{VnGI_Q(~+^pET0nTff z>&8nrjx$dzXdyp4c`>j3Ud^t04$gy*d1#;jV!DEMHL3!@72oWWP_u?vwZ`bnOP5eV zC@>Tuq30kSA(<U6AmE{`X&EXnCR*gSW<A`zaYHl)%oYvXL+R}tsh+r3Ku|_U<%<{h z?tg6ybhwGcl}~KE6byWGD!iLZj(_-Mo}0}A9e%Z_8q#l6x7eJVkgZ{S6`-I9YGTu2 zEDSofgG}K|*4vqBv5nkcEN33P?s&g&HI|TCUb{B$6vxNUo*X~DasBoyYjRe~-u~X9 zd9emwoIZ0Kzjgb@^=mir-`;=l@X>c}p`!Zc+xt_sMHBa`9$vD%<2`VH`?r5voOUk# z|M!3Q-=+L((!u}afA(*moXmF>);e~STQR0!?!L2hUR|=B=erK4^JgktvTt3#@$m7Z zCl4RZ#J)JSl%733RuAzpQP9p!Ji@GvG#hlAn7YsB2Qyunq0UPi*38(>XD^=Jx^r8l zpIX5$PY*92zB)TqCo6DWqGq?7P@(##Yg!$%uHydb@}uPL<0tD|d1A0$X91p{XoMEA zdBr$WTpd(XoK8n;QDBaL3+09-;6Pj-c|tz-jK1x#{?>xYIe9)8O}R)4g4MH3=h$N6 z)t5(;=V)W=v8qeoXe|<(A>r}fo}^=Tt@{r?_`nN|E*&MMfX4f}-B!Tdt)=qnVE^#s zS>LF8x+YPw^T2-eX#VP>`6XFjoU<8Lz?bHN=$Yk3#l!sg$<tf6?|6MQ3pcOdAaP@! zt!M!&sKe~l%lqGaOKu-3`u%V2J$U$l&RcK4{rKUdnTls_>n~oJ9S@9|fy3h`$1|t% z<Cgoc&gLszmtJ0CJ1=MMMyJ-!Dfyvu_;9{ZISc-5POHO%z7H^OGDnyDQIk2jW-%h~ zTeF|{EVI2!b0?#t4s2)np3VvN{MkGmuU=h$kK}m1`lZfCM^`NsrmD#NyYC*n@rJ2C zeDb9CildwJGkBhJ^Ia+byc7U|iFj8)el2EEao1XEx`jag^oawP!~OZup-U6(<-;TY z1T3~y_W8H+^7y}eFsH+;cniYIiuHE)&fVAU-u?8GPp#USKkp}M`h33CNmGej8AJk_ zQzj0kH{Y1o$XVsHK`kY3pdy_wCeC*-FTI>wnI&fq1hhBb5w%FDt*_XD@l@{SJ>Np) z^x4U?`Pt^jPpor0%EV5Xo+9&3w7z#}`2luzukXQ14EO-8hR&?O-uBmpz^>ux+SO~& zX!3G&`G|sipFDm{7$)VJ^6_#gHOW5s?mO`;;Z$iAWWEoK2SUxHa`))rBf*GvDUbPF ztZYV$)(klrTy~w=PB1quN8FrrFI0&dbA>vwr)~d*EDS@emhHT_D9F<%v#(O~FC3#w z;ne7N-+tTotLLP&*-lQlo3*ztyQafVq-%~WPK#>FvfxRSi_l`mYacsW=kLMJX18p$ zs=AbC9oivaGrxW77N_^`-RH{#-${k}_WrjbUop&qsP&IAlNPYJ;V6dK4039#Qk)-a zk)uO-zLv6d*2R=np(0(a0BAZJ$<3Q|yb!`cl<8nNGE|(H)J)54*7aotNtt8|`TF%6 z_9I?2Hf$Fa|13*<M!MFA`BRPJ;e{T2^@1j(jq-(5wJ>OEO$0;cQqYnlq>~jMVKOId z)Pbz^q#)7Com`G9g-M4T;D+gf<pE(RzvPvUoN{E;qe07&t~OgV`7i3xPzo1Kc-I9> z$1J4mYNZt(9q|BhBB5>%<syAlzPi`1&d=_mz_sCH#4lipbBzHDFa->Aa_+RkU_!VN zVZ_A>ZPYleK0xq>l88r+1$I2&i5g1CFRB7sL?5Lvv>wN@Q>gp*?^~_{OS97H(z48% z2+R|o4w{92;TLBx6l5V(fvwo*ZPV`HuAR#~O_+ofFk2)ThED1jEute?)YeYIiUPDH zpI?wh>2Izt;&1XyC}U7KwO(k$p+Lf%ut_mr35}XlU5tP!Yy>=8*fb}CC4pf5w4zdL zRex`Fu$xMRQ6*_A7h9vr5qG9Q5fXBNFyhSQ;zTzzX<sN8O_WeqUi3*Y8z!e1tsvz> zvt^Gb4+=3Mk%iWp;WR)k6Wvxtm|Da(N61id@=jA;B<f>`{=~OZSjF7^cs!=yG0CCn zGVHx#+iN6njM71ZgxoyRL4+AnBTreonBgN`hW;yfEzM@OwS$ov9GkED(_e8Jo-9Js zwFOtQyB((mD^8`NGbrapTbeJt?lLu`c;x14sm*#e$@=a>0&oU1;N7!SIUz@5u*%MA zneQH0Xr^KI7s=WV^TRH4%c9`$AXz^us5^1akK&5saK59vVjCAUBfOMN9Qo#pP*<S} zgM7K&{m_T~MGkEq&g%<prqyBYJn@JjU+Z_Cdej8NOXd^w`P!5CYj^H?Wb+~oa*Sdk zXOU_C|I>D7Kc1%7eb{T?x9+OmyJzK)Gb2)@DJr&P*;XVtvIz)|6^pW!yC8sbpPLxS zVk5Sb7`e!mFLRLqiD4vhkQne^AV7}9n51RWLk?%@y{oIb_I=CeJl|hEQyMwB8RoG0 z%z4gp&i5?O@;-0Xuc{Orh(#qtqbaUsig6)f5|FHcETqJ*95Qrx@(Z)C6QgmFs5%)+ zzKXy#o+dH`A2K=K5WZq-zr&IQtR+dO%@WtOYvf8T8P~#T_sND|@|r7suK=~?YQ9{C z#cV5RtqS$r+pVKmJUJQ)=yIEjABllP7y@|v?YBMYZr;4<&HUTH`J2?fIE{YicYeEW z)*O0IuXC-w$*n!`&QLD_qg5@3yStYphAyTiCpJ894iDyLXQ=J&Y#W`Ko^th^pPic= zpHO4-Ge0*sJvlXe(LS?onOeK@uoUZ4i#4OihjocOuWwqO*7x^SGmhGn*hcDdu)pUJ z@Cx<f`RerKw9A|aBW30oYX$H1?9`pMKDc;R8_vbI{dy{Iuj9^z+Agle-bUI6AG(;I zo2?U|J_9Vak>jJom#Z(HJbpAiJ=K<n?doW=uvNZ3vx{NrxN}4p6{1Ip1uyuv5r^xo zul;ZxMpRoHn~U=cORhnalk011Zu#}Ghq*az*WpLxHjTIRnd#{XZ-Lf?>34&458mDZ za${v#z=F&_ycEoo$mO3D+-Ci&&#*d5oI>qh4yV38HZ;VeJgOk|aoKt?sGt4wYShjq zUh?5dB-iEZ%emQ8cIXMxH9|0W?bhbj!dzVed9jY6)ge1v*CW*~sxL;=Yi=#6`U1-E z-tM-FSwb~UL$#T!+VveKPbQUiSN57$zp2b<_1mg2k~*+zLqpb5&0Ev3K(uBOnyAFD zdb*|G?hWM1PG7eUlzgSXJ&jDIvq;rUu6k~6ZY(V=a$|CPB~30rmYlUcGCGWDFQLcv z^I%@t&(9_%>nn@xxH}^Euj<}j84mV8yTFB7P!;o4A}^((b1%U70&4Fe8A3{zlTn3b zq-$$BO&HOn;Dp-R+A55pp|!O&Ol;$>_H-k!Qg!&WZ@k!Njx9RYbc@3Dmgkxd8&E_; z=eOD)CUN4_*L~VCDh3Z}uQv>11s`7<vprqn5hEn41vn<@#6%Z~Q2ZVklpT4JqDcZ- zSEvCb3_@zMzP=8DZCsETqNZgf&L>Zv2pB9rP)KFA8+kY(QAr0Nf@4W=p;b~kTHfh^ zZ8fWJ&L;p2r`<2gC`m#}f?7i`@k)(I5C!^%FbF<dBqVb9^rO?sC|_FUnOuYk1&2h; zy3~ZNl4gn!taK>oGKYg=qT7&)7*=qXq)VuJ;z@)gQiz(aQ7&Q_G?X>T5i5)-pedbl za7lE;*`Xro!r-_cT7)w*(=T7H&dtr*kMr|$7Ut}1eXuGUv)xoZ=?k;=X?qY7fyxHq z7Y{SOf?V3|<}J05#Y~b>Y7oRv-hvvu06^$G%Gw}=qc}DKU;VcSQ{x?o79Yd-N+bx= z(P(O$x6%ZTp@3SjMNG628m;%&Mm^=IAqtrtu&e|IGgjnQT}B&H1%ppnC<LeCOF91d z0VP=ytu(1vMbJc>ArdVid}>-eVQf2*qwKh-DPR^P*ANgP38IE{O^nzC+;!*!FRVt9 zbbRqMk8+|FCq5?RsR<LX3P`8bV^9#vH8Jfwdy1@*h6uw5*i8sR%qbAEGQV+@GA6<p z)-$@1u2IBXn?;gIG}QBQ_k%{LOPG+5;He=Jgb5l=ZRE^R6x;||8BM<AVC@d)17v8K zh*)uCLQ|zs@FAFLa#Y1_^9xY$3<;@mL5&>g<_q*KghDniDhZrP*FkIv)l&s@TPjsL z`T}Fpd=6?7lMn>~q(0)I!%#Q2l&e^6lagnqxF(mo^Dqbwe=aarO$<?HrBIodgoNm1 zs8dW3SRiy@GNeYh(Eds`iY;Vlp~!pi6pU(lgaaYv#V1X1LZHw!6AVo}1_&Lb%OpD5 z5MODLzzoGHO%lvif^1Y^y!TKe*9IpQYwCm3LnJ7$Bt|=tIR9Fm2FHGxHG;#0Ffrqc z>NaJCltK`YQ3N5$#wkf!&rCYug@+GPi@kEE9}@^UT>ZC2R2#XsE(vsGEf-xpf?$s` zkBhYQO_o)vi#J)Um_RnFO9+Gx!jNDr^_Zgs)&d+ktuHRS5qYoL)jGy>?HH5n7@%mU zwms;HR$r~)D;XuoWNPi@K*k4IYe<pJCOOijqia-z5SaJ8bfat`1w0D?P5_Nc#OblT zylfwN)uc(10D!Q9!!UqxftV9&n?lV(U!E~c4DqO?CQjgxYjk+9$Wibiqh50%Df08@ z&tJZL>F)O*{>{J1>WkCpZ~W!os9hzN!}c?NEeike&eT!&X1SeTw4VZ~Po$q59(i6( zPfXTl*(WA5D%1M;()O;q*FFF#aIZsN@VydO!RmX1^|D%DB*L{7GCWj2hbq1Hcdm@q zcVDbBci55qk%oHh9Ge=S@BnRJaUAmMr7-n@*ZTRx(W&VvzPvfX<gs4AMbcjUtZt<= z)AF*2&8sXG(G{6oSs|z5_{GIV50ZZMSMFAvnm{*8b(eurLvXb9fV_Odkz~%acxqaX zbe)fo#o#uNhb9uXhS<hD4{wY*WD8NFAZ&Y8i$^d;Ylx1((oOt%kO<Of)=gGSx)d<+ z#Zi1IqY~9no7v-o!|9osjkR?_%+z;(C&-UajweRP=H}<jjtpxa&+9i2Iy#g|47T#C zR~s&p!mxOuwYGMci_PKwUd_~5{cx$)IbrqGcc%6ac&y*~SueqANBg*brBHjvL(o!E zgi$UDBBj9hjcrt36jaF^8PW|1A!UWtLZgr9h&kYj%*rDzry<PX*G6d1OW=ftfFPrJ z$1s{0-~`Gjxfd{tlbk~0B)10OgTf#n$%xQ(-+@Tj;OpCcgj`shpa6D;oI={>rEaCK z+HWw%{P@Q|w%#znwVlKOK!kWu{DcQ+`Y-?kPP0DPad!6b;ir!tJ#xNyrOXkty1FW) z81@+G3%gf?-vm!+NY^ZAQD(sqg}4?o1XbliE3nKaWja-(%YwwJO5BP}0aV;6f@l%O zC>)EN^4#1U{Bqpt47Q$2?fs+&#+@)Ivyz=HgEHOpp+&Q~{p{(BAlr9Z67J$C%OFcG z?hM72npVIVL{pngG29sqKI#mjBj5xUqDg{`!pCq2K^CSyS*Ki-oi^Iw2pG{1zBtRl zr3=wU0VZLPo5Q-4quw>d1YyWA{NmM$>%`#pz)K7fE9S8hzczlG{{fATlmZ+zVS*71 zWv#lYSlrR9a$VH9%0-X~b>p<fIB+K(M2INJvFk^OVMQK~hOW}p2=O5|03h)N+|pHQ zOB4t-5-}r8^p!=x6?2<nlB!7i)qOI}VhiDsWVIb6a_LhJahL6eFoFR~PLqDN9*Hg} z$^yvBEFbNV%*ILjBu0zc0uDtXL_r%lMlg|RVfKJ~sJ#M+Btpa;2?mZ9PeNHK!i1{U zt=jb~5Zc-^FOeXV()m!g^$64T)OL*1$wc#IHD={xZHG5m0*DSG!4qZ@=|qmvO{kPi zdPYG-PTvp-*9oJWPfrbArARWAYQzO%2!TY4+?VK+N6jeed=MhMYTL;uiMHmf9a;D` zX?4^<wlMG}OWP)-CIV58ErO$s7Y~qlp%W{7Vh9g5qo4>anT(Q$YI?3*kt2+P5-E7< zMq)I!84YDLJO+p?2<eDZtH>ne2_W-@p^OojQ5(~e@MN+5Nvw_33Q?;$Zs#YE8#iv4 z)^zD`nkB&sS~M}8M>ZD_XDl@c^z&WZWMN1E2&3D44oDY{7O_=cf!U{^>}bmjT4F#k zPu4O8Sd(|Tp`gW)(R9;xO1|`Y31)<Sk-!PXO9!EY7~)ZKN6`rx4I0u-w3lj~8R&Nx zQA;G3^7=x6?XIfPLD7jV&8t@2jnuosXVk5Dj814UG+gJ51!c5H$d^{ZwdRgIi3B7k zJR;Xd4$3~#Ldyc?LJ_jq;t>g$#PY}rp&tr@wkg$%MsVbg4DmvOfso4M+ghuo-k-4i znoT&CjrglTmnDjeIHjfw2P}p7HKfI(q^67DCyXQ&eIRUOBF?miNcvMIYamdDnD<}^ zwFpvy)VDRuY2<h$HJH5Pucn-DVkdHFA>BOA=up0U_bywT&c^v!{SvI<fAHV_H%F%@ zUPUfOhP`S|Oiy_^;m<o8XI?VTF3v}XN5&?`hcD_+8+(;)-%K34XfL$qLl?(~N20Hv z8FoB*_d7W7Xquj#Ri2%_J#UtFq!p^bo<C-ZTuSwmhgP22ctnkjz^TtEo}SFl%{+ec zWM+D5>3aR<N%HyGnZx6gq59nJ7zCB}oae=>m&=#uxzn0oa*v?kw^^*WW!1FvIWf}; zng!Z?4!)71th(ldX5@0uG-qP!FPbbYSbq*y0q2C((#azhJ{|&dAYM)|+%cz#XX~<_ zpOwWUR-V&YTMUH(5DqJHhIAa_Vi1505D)=V*0m-OG^3Om8ikhNvu-ey32hi^iOmp3 zm*(kVy+_SVO)uYA*;s!yJv;NsM<3sR?LmG2c68+E;BaSeR{`f27tH(i?#|)<!L{Y< z*A|z|5&ewL%*~!09S@DvH{PuWn)L}~_toK{^V745smZew>tUbf+`_z3R$5jhhsQ^3 zX|lD(geo>k2~zMVyaOn5RYG`WN2XF1DXD5mxps4Vvjv4x4K*}M=jP3ul&RsDmzTZ& z*iMS<Wlu>RfAm#SxlESbe)qwB^3>K4cjkzi?bpMD24AbTB%&n@k%Y_w1ZvRo1!EUk zF6wtQ4L+eXxVr~OJkrE7%&P@G@+6YwArkj;Mfl{CPjYZGN7Q<om4nI2m8F=X5yID! z>moy}k|`Il(mHVYqGpJ9YB06B7LNcFoCyU{rR=O|LK6T!yCWt_XNZ;8Y*Rpj=R#_k zTvnh$x)2nBt*)Ue`tYzRvz0_eZmvxtO)k_SlLgHX!xUCGxlo{Hezp9vT3K1iMTC_s zfJ2CPJoBVRKhsA|7?4R+GJF<Ec*+TYA#*{hkD5?0ibNs|3W$lQw9t^Xq1BCRgo#3m z91|IdJSzb#A*V*knd{!UbBA9%zl7qXOl|=L4KXnkf~JLFv<E<<rG^NR(Wn78k0kLT z9W_kWLGEE|@xj42u+JWcd%K4zzU-96T%@FiY!IoLBg94JI9%t$;bDD|i;hv{Qh5tN z0OjNI)$VEx-6<jo)9Y_EkuX8RU>*eWl+-9+kVR<6W%|Ua&AAj<P#9fgmLb4r6&I!w znm1=W26Zb0p8~7Qc=APEnGRu(3a=~_NOXlkA~t{#CK9bt47sokiJ2D(@>q44`0S&b ztYV0SK|+%WhEDXMWk{D=Ru>(-(PsKtQiy_46x&2XuFhI9BTNj@Y5PM4h?*hs1eQ}g z&2;fFDa=mQJX!-3Y-$P^YcgMP*5y%4Cm?36++3d0m_(&4)>{Ey{`GqbVD}E|3rv!Q zAZAR~Y9d4;VTA!gI6YbOPI8q<7*<xzSD3_bus`?<OrizSYpZU$<n$4q91aSvMHJEs zUdt*|W+$?e6bZC|lhBDRodkmqX1Q^C)USB015?-x4N-$hqDw6^o(*Eioe}0$GD<CH zY53slB0NeigwfZECta;k6kdy>6I+Z3lcTP90?Q<FUDa>^dN$?VGKZd+je<(S@gyeK zkYqE;BM@W(grP}+oFTG_>@^6UT)G}ZhCGR^D<BD509svu5C~~@D4_-|w?RRAcs+ae zOsJMtbhOQRnE*kAslT<y7Pui{WTBF$B}~gi7}QjW#95IlksE~&O%y|NLOQyv5@cKm z!w^a2Vbo2Vz*r$VOwP{+Ce)M^5e6Arz_pP$&j}MqU@_#()w3HSCVZi}+1l4AeiIuA z=7rL5P+W}E4|}13B!GxMd@HBN$u(Z&wtwoZ%LK2*lVGTkXla@VE%QMFjSQJYHNSd4 zL~KJN7j6iHQi!AnV1l#~q#Q%pQLy<eX1w*r#A=}c+``lCYM7>61pz3G;FDv*rwGxE zoElyhTCP)72yoPgL^UjUD>F~nUKwq8HPkXx4QL25KnR6jKMFZgA2w|P5E>N*Vu)z+ zB0;2X<cB8(OCPTdkwA`>+J61(Ux%Xzy8qoj{D(%rI1T@UfAC*>eXXCEJv*)6{Xbft zlI2yN;-<m9%;hN{L11z(Q5r*dI;ys^a?`6(UTM7E!0`$MQ%j;GUX3QlC%inL)-QDN zG^(O-p+KCpd~5P1rv`uR##@O^-kv&M<fev)##GhonU|%5z5Tpa&Cbt}@arX9i_fnJ z66A{)&+JwBLRByKMbVnn+qZ8!fVd#%4n8lE%}qMVlA9hab4x)m)}L0ubllbGzj*N? zL(!~RZENDuqetGg?%%)fO$M^oGJ?ZUt$;_Lp~ShvBSP^I(o`JF!a2?heO|yi&FOH# zgdAEHT%skEh|%Or!Kj6+0_*GR_%2i#CKlSl?3_1Vu}Oyx`Hz0|qpyDTtB?VjXkqZ% zvvy?15hyK3E#vz1DIO-GnFWJ%Y35LfGGUv|3Lrc{T|=xkw`<aA5^B{d^#Nj(Q2L03 zJVS73a!M}31O}}eVqoIse&fcC6xJFrK^DO4ufMLU-h{1<EMqvVD2o}+%zUjG5<H23 zso_cDQB-0elm%p6AgP9^Vhar!@-S9IL!9nxZdmui&kVAn2@tI9EkdCR-t=)t$UC)E zj2f~kIHi^fq(nT%DPB^k1Miq#b_)^@S=ej?t_?UH^2|783ef0Nu-|!+MM9zg77@}+ z;<|W%x~z0*21nA_I9xn_{MeP9+-nS{Tp%X&Q#Ta+WJgDfM-aqd#cH2Cd1Bk<jJDV4 zL@i-dnc7!s@r1(Wf;nHh3P=qyNdl%BWkTJc=~9q|=TPn(@-mv;p^QK%P{Tl0M!Xzp z(xHrm!8>p>YhIwCBn2cMjdpobFp8%DK^I6&FuZVW2yq$&I!IZ>L!Ml+mW*0gx~S_T zYIw1wIFOBUA^v#RO;iCSw{bwJ7?b2H5{sX(*MT7@CaFV67iNM)FJG=*TUyRt&}_c> z=9^v-W1h3l1aXn9Cnhc3dgTVfDen$03bLb_av6%3bPZi~n&1r~=0Y_Z&E#k)5~c!# zsQ}88!me>#sHB74dQ)VQcnp50)QUVsCXog2Yin!qo-pWy1fv@rPzgrM1v!b3QdnI& zN-c57h$Ly|aO?BV1%1T3t)ZTHR^-%Dv7xgXE#`6sVv-B*su5(9YmNvF1y($GYm#mG zxO{W2WG<ml=8i8zLV{pOH=`)}u|;R?XA2Rb06J_8dzWEKbmMyM$Hbr}7@_jWFA1G^ z!N&`QNKo@Ua4l0)sdNg?m#k@8lbbvB2g5mnDSqo*>2hYWV&1)wFdTDlY7#?Nv!Kw^ zXNV`MI-CzeN<Gz<kQYt~5tI0WgD{~)t_^`j%n>y;NmpK35_mWP0gDeT+ekP<heuUR z%J^VXphhA>yvViT6}kP1!@(k_77!#0ElEmelp*~n^Qet}A`xNq$(i&~6kl0sE&M71 zi7Ew_JSG?}Qb37gbRo0tPMNUP2FkumU>uRhFXEI0AkCQIkxgWXiDkyzAz&1*KHTA1 zr9}K9a%zM&V04gCF03)L?6|XS9esE+Wr)5Oh-Ib~5);Y^2@W9%xo(SYkWpaM#x)%b zNfJyXT|b0RS9Tet#*i>3+=T&4hk{7@ridIBR{biI!2uh!c+`bPPN?9(VIso)gIysr z?=fV^UMAEH8WU&^lKj#&L_!{78*@S}iln|VS90Q_5;PK$g2XUcFo|DXF&oPLNA(Qp zk~1NR>z*Sy9v~<!VqzX0vm~gZxhyGWYI1z&yl#VVAY@e-wS=-y6GjZR>e0_4-t!pB z$)8B#8e=p`ktc<0nIwow0Q3_u9yusvs%y(oGn7>)5)w|Gir$s9p6tmhm`3A;cgkEt z!-FCWetiebF;YLpI5@`!^2?`~E?aXgFKL3Ep8KqBDVi2<z0t(mFaN*%60D#9+WW6I z*4JOY+}L=v<^QkNSD!zB_WbGOl*H`7`t76p`+N1bi1L$q2YXvvn>#z(?YVrkw_l%V zSAo5~{ijc!uC2ZlqStAKTYtGGH!r~Sys|nnv>-NLZM;}rwGzlx8>S&Xph^3uAAU49 zSJMo^5T<=Zl-l9u#ui(eUbAbmPugcA+b_GSm+h02dNJPHtC!*Wbm#{ScxP*KV{doo z@L>Pd`r5OnPbB#4*;AF5TK)9w`Pul`D35cqGsj1VV(_*;Ix>7wzfH(_<iDk}y|sz; zqOBCw-QL>U-E(XUukvl*WARv)(%n0EoR#ZqYtNoNyRoujvdMq?)1TJ%Yx<I*ppcZU z(Et0p-`#EBm9i#kcR6v|$~`?j7P<J34i9*L`Eqr0b3>^G=>jmAn*BYaf^_HE*{N>@ z)T+srYug?#Jgo>-kdPPP>M}Dmy}7ZO)7%xusuHlZp53ms@@$D(BJFKqacO>QyTVYS z#rjh@3;bFJ_03<0*zkpa^$lPPc*ve~@{TKvY4LhkKVMy`Tm5!JeV@2~diL~$Ej4ZB zvUgyR_34Srfhic#<`?|5-{Dk0-#a-mIX*T{N1D@iZ!4(-iH`1A{pkAW%^Nr9Fg)0o z@5SuQ?EGB)^1YLjBW5O%wdppGq!!q0{kpSh0gILb;msQ>H*Ve#(!$)FXKXExnVHG@ z-GUR>mzK=&h=aR+*>e40_M|7`^pv+rcZ&L*SL0*U>g7@e#lhUoY<g;*o9X(!;tWOU zgyMCgz6s+nb&3s6kg>7)G`?kE*-TDO`LD?|b=Lfi8};o<Q)85^)ox~8+VH#~M`|cM zbF%`$Jm!y-G9)*B6e{QTK;_h`l)lRVd_$RW3WDU0j?)kbO>$N;qqDrc!iDElJJC!| zzU2<hY}Fap780X+jbB>2CIwd$qhMu(H^iMptc*BKJXSBl2smU&Yg7x(C`lBUYem)T zfVe;cNT@v*R#A&<A*o?t?KuiYZ3ia!P_5cVb93|Fn@opT%om=P3eX{J8MwnyzYwVz zU;+~|r<h<$Tu6qfCH@47gh8k58#SM`n^PZ*vkp#%Fd}Cq3*DTb9I1l?&=3XG&g;R2 zI3Osn2r?Z`@$D$CL)B<Vs79lSNP2kWFJ8Rh9W2-UI?$A^M@SzOeMx!9;e&uE#20LM zj<W5YEsSL-GrQ73VJA8hrlw8Vkb?pbJkC>3mCWjeBS)}?f{&?bYxi%hBBPjy2Qi_O z;%iBCwRE)9vK|bP3;X@|-;Yyd6){&~kL~N%uhR@EMb;Z$@dF+cOs&QCW%6ih2|Ljt z(N@rxH$Q5bizHaji}sBsk|1Cx<1xav40NTe%N$P`We6iA71IKY&~r2SB1{M`YdVzW zC<dCmiz=g_j0TV<kLBjdqUw@NdTMKwoJ1RQ5<>`+(fUOfZ7y^hKn0H^9z#QsG`so; zv{ENvYZW8Ns0AP2L3B+)G8H*Zgh8n@Iekp#s4$P~YyISS$}OV$N@x&J&=3X*pE+ei zZDMO?@i{y*LAr!=IK@KCWc4Af%15Fr7!od+WRV1!FmePxhFKU<z!R#Eknl+a4>sm8 z(G5?i>bk+yCDi4Yd4eI#D4x)q7!86pjL~!r;kz)dqaP}uOF5mcMhDLYMwJMYxZ+1S zLy_x}rz=PLT3OS{S8bROQb05fp}v+VK**?WBI%*h&yp|{Ws@jz5^_2zax2}y3n5Ki zL{1n@!Yq4Cz_q&F9nItzk0e?`(Nd0(G9C_U`h#yyHo_J*MhVqVDtIPs*2-7raiD%B zUyL@)AD35a59PD&%stnP_{W8RO|#UD3a@^Mvr)3Zq&QN*fFe&8(V>;FFVVQ8SZ{H` zG<3CXem`3tByl9L1Q0cZAuw4qI~8=JzKki!lq3qG^N$>F2(LAIcvyeV)4!(0e4HOs z;8YZ<)5#Oi`6B?qklVk(M-|9rY&TYxC*0`jPf1P8xDC$EVI(bet3>F!N?>a1w*m_+ zf7(}3hlentYqhVRAyqJ%cC~0gQ^0uVp$3P77T<nN@M-j;R)<vm@z%No)92A>^H{%Z z*agd|00XOJK!m|cD<uCwwP<Tp3=OURa4DR2`z}dMgVNRoK4lnev`(#(gU2hvl#q+T z!YE0E>aVH@qx;~&1JmlnbMO5tzx7)I|AI97tzY<43T2Y&&t1;XFU-$7ul-+=PLo7n z5%)mX*4AFVdPU#Ml4xA8tb^$p?*P;LyY-<s2n@Y~(#h{qR$HFTVddFwf!-cx=jvNY zE~{Kr9CbIXPt*O;AN|og?|j)co+Fov<>h5VVC%QP)}N?75~tfUFOa?Y2+tdi>j()= zt5`fIr``?f*C~@zqwc-Ji3vwky0>oKlBP(kW6|EcdGq=6=j-e1u4~e?Nz4#5CaycW zgo>kUi9=`~U%8iOTa*nUJOp0211=r<34<4YrA(4TAyM6H1WFO)qNO9|<>k6y*-q57 zkof||7c2VN`ARA<_y_gNRO?Y^QkXMgPMM}K$Vu>K4bN)j`m!Z^=l1Oj8|?J#jkn%( zS-yGu*8bl9$=RvfT>UQYvGMv`!071Q!u&bm)YSEB*Z3~irfg({#Ji=IBxj6P6>K4L z7Z5lrUfq_L>3B1fuq@_8+*-kqI9+NvElJ|K5%CMvxHtjo$~`qPs>PF2kiMzb$}}k> zHKd<>6-xCK!CY8Nx(aAT-MMqe9C4>*C=5d!K?X&5*uLV06be2$hEoy>T&pCL#1q3X zsXx~#J}YWS7(te45b9)W;F)m>Vngno4586M7?@gCa0IZjvf?1nMQ^<EM%HIagd#`Q zFL&gSg~TsM0>dM&jUoXElcB(Y%TWQ1;t5$%Rw$9s)D;`1J(%k&@fffoOsMd)wgo_L zcDR5bhOMpodv3tNGNf+^8fEUnAmFU*krr49wG^NsLK!I$Ob;FfaY~p40YLUN%GVSP zWuG$PC5hzC5Fp;EB?h~gRhFC~ys*ic#5R68E#E`+X+t28wHq7tl{hAp`DK-`5q(~m zk~F5ioD2{#R9IFdJhEa-C}72*PiP2(qJv==6TX0_tE2*u0uZ)=6%`#O3CvJZmLNwl zM?%uJr0U?MZxp_+YHO1eM@{83V#OD~pMLsjmO6X|Bv)hz{04z7WI7I5lC~rVuX%>x ziytp+GiXZ^+EWmcommD>L2L|LcD2)aF+>g-BS8yENZBSvDThJi2o7Eh%z+~c01X97 zOF|(5(?^8ShwN=%S0rEh(w8VWu9-9J6kCkM#bY#p5M&x^1sJ@aL|+?*VFII1LV>1k zOc1o35BV)z^d(M#t%~9KrJ!yR0^t#lF+o<B;OXG)4*KQs^t0WEjD{hEsRCXh0LsPs zR6v?28BxY-xzKhpiU_q?34%{Bx)ksz35MWA$h}qo0YQl;?hJLSs-UTF>p5o*1vr$Y zMj<!|6a9EeV38vXLp1?H2SaEPsx};3TGsS=As0V}q&XiDIpomvRLwZz5ke0`<+X4i zU{Xnb;VCjrd}fM?Q7ttTSaJ%?ySt1sK|-Q$tD+RDCrD0$H-j7{7$Di^(L@+S$ekRx zuC^stTZ4iwN95_I8o;-=>thAoyaz@>riP*hhgFteK*%wK)KZ)VP_x6991qP<Dh7nU zE``Jvzj!T^bjdT7d4Rgkkw9P`D>^ij5g|?BU~MSXi?0r@B|+&L;)oS<Yl9U&rvx-= zIk>1HI>@sr?h*h-RCvN98%;xal#4E3N#7_~j&e?-_=++$Q-={%D$q$60tHMWCxnyK z5U1pzNW_!%K#jaBAlnL#7!-#vE1xF)l!XZpgrRwMS`rEkV=yDg`OgbRJYeHUJd;y{ zlbj|=V#p}!AYFcPJXln$v~)y*#2FJrEhYd2?7xlw3>=wmR+fq^s&?&hsq5TsrbQ7Z z05}jFhR>co%Zraai#%BJ1TiYXJW!g`&!}Q*-qF$FaZAB_l_*C}PtLYBx7XKS)z`|; ztPRuAzT0siurrgBzeCPluePkUVk1#@3pnn`1%S~_4Ahu#T?t>7w1Q}42ncx)GMcHx z7=@N^iFq_@Jw6Os_9+XZMu(7VT~O+fF8qS?=5CJa=OG6%B=`hCIZGl|Vo=Y$gSt&+ zPBGM&7}XULO+v3}S~%Lj_B+25v@b}*fA8=9Z4RVoW$>qhy7+~q#l7~CGbIpWBGdI4 zcFht*uA#2uy2^HOR$r_&DsBiuv|Mtz)Z*prRPyctTs}{pKEJkH?>v-ucD5`*uB}2v zH!&_Pi3$$y9u#LM=d<nmDz2egQ31?4rY4?9@Py)=nw`RDjfzlgdEPLmh6gKDGX%lZ zro@h$)zwvnwr>H-kx)F;gw4du5???L4k}<3W2?=1szj~}=*>6Z{P4pMzx?GdfArBu zZ@>Mvke)t$nwjQEcv3(Z3rK7b1e41XW$w1OH(hsJG@Yd6Ud}z6Y2vj~i&L0cmpeQ4 zqn<(vLedniQOdgf8j=NYvj9+cVsvb;{!-Av#Yp{)(DUJ;;q#07t=ShtN9_+^jf{^i z&dpEH%^vOVZS8I^Ei71`wWWrK*I&N$)`g!_wCB$~_T9x6mX>z5w&oWXhtG$0_V?yz zW+!K+cel2o%}vihp0v-M0p}O>{r98e!;@pa#5O%S_(-QRYLirEUsZ42y7l<+V<qy+ z_p*J6mx(%SmC<CWhB>8a2D4+~C=^X;lGms5M@K*Y_+w8RRx)_>=#e_8l{HM+ymM+) z-2mn}0NfA>TfxBLMPM`ufg4rcax_)nw255IQpmc(7$xBp6DuY&Q?+17@`SKQL}Kw< zIlQpt9biS?cBKo7xpOd46N9Oz!!|1!V|h@cucfxJu{kqcU!9?Ud@}gr2q*`Ug8b-5 zKXQ-%;DaB1^PAsvzgM*Fjr!6L1pzbR8jiJx5hM~V36RXrPJ8`>4=stPm9Apqh02ho zp_I|n95{tY44F-2i$M^-SyOzG#CsygC=S1Db+e;M$e9q@4pO$k)xi*0I++EIGG9iO zizEA5g%v8HBKn}1P!<L?%fKQ5W$##ZBw26Hm86p_@Vp>}g&-qCx_!RX5l_xm%SCuP z6ewpo5egN^=1%=7bqZ=CyiOD{%j6ab6Z3WV?p-l}0zwB`KnN8dPg%Ka5c-6MIPHD~ zjNuEcz(|6_DmdEAcqjRa1Od^u(2DSe(6xm{hdg9KLS~NV8fN?s4BDf?kh5O=9EkyA z_Q~Tt!7yQtkqB}$k{FT^OfERZTcW9hmV_@>X<4<9>-yrj<H&>x%*>KNuq57k>#ewE z&I$q^;U!{8s5W<qcTnP?iJ{r$_zWRlm}4Nwg`7v^;e|}4MQ%k|gq9@*Xb?gjU#nZI zs2w{b91-H_So5-jDgDH(p62oO*I)O%fUIlX8f6$4S;pi>^B`jd5E@6&5J{lAgj2SV zRnn6hU`9=o(S#}hOnBx-QxnL#cnVrw3MniQwN(lek?o(EG9%i)XmuGfiBr`eOl=bw zC=y;07-5nX9wJZa5|XUdjhrvay>5vg56URzcqGpnlRgDQS~b_gp@!Gu=>V5Yk6aeK zkc&s<brHkfqLmxhJ(QUwJaR2tP%^bX$!&99@Yak~N<mZs0iLe)rYlW^K@^NS{DI?T zVTie41nB@|rTz{&dk21hV#W}0ov5@jGK9!gCMCryh$>-HbNSMdY^ujlmr(U+awkr{ zWS5Y#0vQUDLW&k-JfbWBl<bTqBsfAMgiqLG2pTywq{}r*{dKjS(Q;A6YNQ)q2q1h= z6!;>M1<JOHJFW%8P_nw*B^Z*l%$WqXWm8YR$W1Oe9(5B$lbo713SA!Nb2K|U_$V^v zxCnw%CF@gRb@7zVugh-~AT!jao*2RR_#;Qt(>0YTH8l!^bVz`N$otUoQI#U3n<1pj zD)Ot$<kaA=;+s3mLu;}u4>eaMd1+|^PkGNy>!Oaac!Wf`1zEq>LziZpVo1);Yya-- zY`^x}YjWpES7me=QllJ7Fvyc9OwdpixDzBuVd#p14m6XgZOq{4GX-?4TP-U?wf@@A z&Dml*Tc7>%Dgk85=wzM57p4aQ6%Izh4XKZo_iR|UYDE(`9lTKoDaMS)HAXkFp_+{5 z*C-~3L&#{kZ$w|q5eB%a!BA!>63U`t&NZBzEtv(UnbvkoQg*B(h-R!(5Ys9VTS=(S zpN9`067v4+*|YX{dTJr*R+%o>p%@^D2mUv{@eMi<6ybmSr~kCF`oc8&%fIxe1t(9Z zp~~{d02D#%zBiZGu3vW<k&imcIWft{B~n;&)>Ra?YHdL+UtcDtuL=?trC8mDwaH)5 zpdj!?c<a_}R{{|Lak+_*Uz*5~*wU|whl!4l>d)RVSBpdf79UIz(h)p;u|a#e_L2f{ zLgm&{kf3KkUMZ<1NR(wk4YF1WG-ECpwuru=cxma^7s)6j3`OuPcg?cLOt6qBOGjXa zFtI{$%Fq!0M*HzCFUfS|D?ImaPTOn@e#t)Kg|fUv$Q{C1PnM>8r_0TI@4XL@8jyff zumNa_83M*opzzjc3ETa~^}&#sNNfeR<MpSp#?Oc9;=Z{pua^^3HPQBp=kZ?Kd)w`k z+g@BOiG{^Q4{7h^B(6)cfI~lML*A~<XnSO`s#CkoY<*$F#uy)?u(h>af2Q^F8((l_ zp=ccG3fNK+q<j&EA<edi>mDO=E-*@ABIrX<*Z|r*`v-&X-I)S_kk!E)v2qo2Eift~ zLdtUFmjr>rYXemYwl`jc0jS6r&w4rn(~`i{a-?+xLtv;2U#OMf=^3YaXCQ=t47qSS zsWWkg5L*h59zEm{z98kUID%n94YHV12Y$)Hg0c#%G`1J*PmCo^#gQ_Zp_eaL@feHn z>EowxfFy-vn#7Y}M!ArV`eZhZM!7P&{8kBlWg+CHg;8XbBM2CV^kYS0ebVI1q|kw& z8*of0UI+og$HT-2hgBSD0ZPg&s}csRig7`b{fnWWofs1-vqEB{W0%>F)-b<n4&ON@ z0LlzuhM~_;%yAtwa(;nV9PRl{uBFK^JhhN6WeA3*X6k#Dgoy`XkT3{^t)(CxwRL<s z#7Ll_XfhG7g2dJ+@Mt<o7)H}5CRyO=6N&_Q)>W!aKM95iTS7xtT2_9RgrT4<v_D0g z1SuPWkTwYTOekgb5uza!<;bN8JiZcY2&O5*#3UYdX<E<BbyG&8mWQQ|2gPFpsQKj- zK3fV}nkJfNORJ`yN0fMshM}CU7Fs8oF$_Km4^U++R9!kGa8Uis%jI|G!>Bwai8RlH ztE3iB-lqc;29Z<f@~EZegqDh<17k?bQ9=^D;#kJ?EpKw8<cI_m5G@eYy<`*-Qh>=2 zK?{-4q0h^oB&8M@Lz-Mm7DL|<5JRdY408lQ9j>}&mD!{$U~)v+C|jlD8iFnbJi?^Q z98`E7wGn2b*$Rf7ITt8V(dU9kR8?qK5ptt(hu7kBdIS^0iY+GVBp@{Lgz#Mn<cL%t zGmhZcZK(+pnw3NIViGM&LbkST9Jx_Ab)!SVV+ijwP)Se%1`9B1)9nkaa1aIQ8%@AS z7KB<tr4Uj#gc*h;S>P$a*TNK-Nij+jlzbBj9#mo=X?}`K924#g#T-$9ChVj`9=}>V zNkH%!iZF6GBm&cAq7_4mDPT;h%|txHCJa&N6n7mKla#f{Xyh1V6!D9?4j!iL@Bxpe zmc%4VQvejQs2bAXJE*aZNxa7pHS8jM<S0W|$zf(`<)8zedq{?Kd9h%)NVVzk7%0d| zA>B*?!fOS?+^mU?Im%E<(c&t@2*ZRx4!A!aHotNAxgm390gzXfFE6Dij<i`k7|PAO zT3z7*Okgp@^r7f$*uu{`r>p{6`$(5^3!%cpqc#z>+3`I{P{D-L>p({f+>vQ05(?2t zvKVdTB+YQ-=#YY;`o~ZIXX9E6{?WaBK9o+P(>Ik2bdWJ5sv2uqwD2otYFX_@`DNnL z;?eJUO--nYma@?(%OdhBbR)b%VUl>3ZW1BH1S&Y;G327ctG30)mT+dK)<3Jn91x4m z(UDoEFN_%0>@@J8b#UfMA5ZiC{rfa?7y7Gz?XR_xd{G+x&ENdC<>Jb^zP`4xQGZaL zkNP}J`?I&^^vLO1e=%jp{FoFE@~zEHVeWd9QSRD8?ZZOngRetqfyg0HUi4j;F)rT@ z1y^%AS`Wwehhlb)j}A?yfAGEKa_8Uv-u}V<fv)$2^ZH|~XD&L{QN5D!*FNuldVY3n z;NpD$;9&o-{&^XzKLaYVz1{nF?kp`W)UV$<t+4sp+T1ujIp%S%{{C|N%Mx3g+RCnd z$IsN~0<pUK!aMoq=7tK$f~tQQXNq*z)?Q*JM#mMQ{sipt$<X=5*vRPk=-9;A`09%n zB%gl#$+g9$XHTBqx_NVJW79?8U~ixNq<%KlyI8#<99JfXPaZ#>ot}C8@R92$z=xlH zx;Ve^YHeM#o13rH<mKw>_STkHuIJC5jSLTMym}>mJH`f_otdudyjSbV=@-vl>}+lO zS3f45AH6<0qWQx=`d4bpDa@L$p<%WzuqH*jySImtj?ikeako}Kxm_jo7-?UVGrF_4 z<2*1Ww&%;Wmja)fo?<XOGVH-?hMqoqW*0Lb86A1C`ob*O-K#HGcXoH|>-zA=*(q}p z3MN?5Uv0cvf3*(n$<rqfKYh5guyk==o0Ip1gtzF;2#MEPOUPz;`0$}PonmIsilT<- zkQntmaO2O0vCK&9G=?NQyW8!6sz*2w5~*2-CVFdYllkOi-Kd~>y>%4S+}6FVek@!) zO@YeOv{}qr4II`Fruz?6%1@s>u~w}#Q&u0(^S(4XRv*!C2b*nTFPV<|XkGm@`^N0- z+{UZ=14XU}6XTP|M^@>`{M^Ff!O_U@D2aczMePPp^W*w@r|9j1ydf)&g(_JkN@eUp zI##JHOkF#`9Vpgy-LdG{?Xt!=m>eQZ;5%(Bd-AiBI#^RTn)WZNoRZ{P?(!&Y=f;rN z#Gwl(UE90u(a*``gna97DxaU#6RUp77mV>qZ{jq7px}op#P%8f$hja%MqKOWNHv-m z2pyneBfQ>z54MS8=%A-yRQ!lJ+gMRHnj_Uh;;WKvU$%^QZLGvY?$uZI=%{dN#f6~) zudh<NZFo+I)?TbX$1hTu!oX+=<?D8<vH=$ca7>Z{MUKb?Nn(i53$T`7p(dW#YR!Af zE@q7Ga{EoBf$A;8@EM9kMkZQDaSfkB!1166@u4W74yElxh+NPUMhI-OaB!&@TkbGi z2p)nqSs1c74G}V|Ujl#mz}GtaHCSqt)y(8nD3<|qjnPH{f>zg%*dW`^(ga1GWJN-m zW{)Ji<0X$_WqkVdX`o_=TCRg)#%bgzeA+1BQL`BES$Ls@oit~r>cz=Yq>}}i2RR{X z@P!=0CrxdN78k5i5Je*l9|C1w91h7{7)CMVT0=|#k}FG;<2NzHJN)RgO@f9<l&JGs zn)C_dOZRFUC@Jfr%rA+2?LM&K$sJ#^5D7IN8ODT{ARDEhmJqQOfKlG@tl&gQ9}g{> z&_W5@%VY|kvJe`I2?^pts~bty0|gWiUXTK&@<E`?P&^(SB$<7}q%25Ih4eWhJgz@p zQPWC?ArJ&G)9s{k>>y7le8Nb0V7bVQq|2%ksL<AC-B=<?kd877j}@M|{X#+qZ%L2` zioO=#BC3#Lk`j?O_<Ab{FPJFkB0NnkISN!Fr$bH>OcI3YhFw962*XF7uENHOYjR;k zl1M1vB}Ks=_rlX2g@Y1R+>K~vf+Ez?7bJ>8Q?K23HKg8U7zUZ~O5-vS@~%Ulyg=J> zN~qC^FlxZHNH_A1&`I|yk=(s|Z+B<kllR8T&4q<U*d9F#^Na2Za^lu$3fmJ|x&n!7 zwk^P-23#KkZ@E?s9lXh1*=P-c1xU<SeOR~t91+d-@8Ys;zwbBTF%OOwelqPtNLPfc zs{AAMFfD7{;nDU{YKM}8x*oN7P6>mbPys4z06U*99pqkPOJ<2$+ggiUYr$I&9Vg0F z@v1p95)f)(0od<qQh|A(<x|R4hjKE~{sde3ig(lyin6pwj8Y}RXqyL-m!SUT2e#|O zkK^#FjQ&+UTpPVfjMne_Z9h`$pCYM;uJMV<i6~A^xmJyFEX=9tX?N^7r)%Xt<aWKe zwP}@m61#8KRYh8!8lEP{UOVdM3Z#Au)8L=k&Of1_YMZ2Z`rZ)$G6&Ue@@HBIS~^~3 zHn+C++8;f26^M(nZBy0~uY=t-37H7Tnk{C6Fis&lipH?l6T^g%8U;Knh&S6`a$%^j zKeL|!J~=-0b|DlC#Y@HG$B#ew;DaCj@P~Kr-0_;2Us(0>#j008?^H_ZrOvC13VA=< z-QH0Jt!bj=b}kv`wV<6r>+9<n`4GxnKF)oGMRdHqxUhJC;M6<b>dTj24<zYz)TkFW zZ&`IM^3K@G<fg(<kVX-FJV~v-_836&N!JW|UG#qS$tRyYdGdsLVYUy|aL14%QPF2b zsNSA5<ldktyCFfwGx4~Rm-?tX&D^ovqn<u_CIuIcd{<3805erGRZ{JvM~~o(fr6=J z3mmK%#Dgc{>wDk(o@@6{fBIAW{rmU7|NZaZxpPZA-WWZ$>2U2dS5G&F1kat2fG`oj z`uf_(AAg!n7<>x4vT*0{svwMb6qtf|%e7}HP$PtyQYc+VMoG#lv?VQ!?d>g^+<~n} zc#A}ABK-8zPx0i^7ZNmv!r($pv?NAJWW)<wLP=TEckbM|ee2fH`Os+nMyR^7gQCw+ zNYMBaOuifr!L^k_a-_pVz%-q1Lj8k3_yZM?wTB-U%J`F?{NxY6`+t4uOJ8zpGMkp7 z3czGb^Vzd!a7-3V#X$lv`tipfbAe~#-k^rJZ{L3K-~kiLvPP2C@|$XK8d!u8u=x_6 zE)bgHVT-^nU#}k)5DXooK+^KX5EMCl=2BCCL)WigyL<Pp6{4jE&8=%?WrZ>*RuEJ` zH|Gm*@*V)dkcr62^4e>!(UFJ!ckk{!fzdRCxHdb1q9dJz7oM+)$@;P6t3{w-RJ2`^ zQJ7A9ZF?IoB8)y4!r&!pT2qV+QR4_<3?U3T9bROCR{@nwga9$TBg(Qip@^DyHtR>$ zb}Qa=v!X+S;ZEXUwGaeDO<|c33V>P-jZ|#GM|j>*9A%oc0rXU_-{n?ceHc);rGOYV zwZR=uNJAs_p-QW$<vMsaCrCnuyrfFhq;DN&0|u%S1(;k^^6j9=fuPi&5PfJ`LxG|X z$|fQqhafNr1H?<JG}`kFNWf7rng8U2AF~o6AssWKXwmQa@~fq02!w8ULOKGl7{r;m zU>kg+LV`d)fN_*8#Lt$YDHA_UQ)Uv`QieklLZXT}%0h+1Bvqx5@Y2Q*F`-6*ytgFe z(G2N^tV0UXB<BlqO~-M4O4({O7b5gT;6nWq31S<ZhF1&_h9ZQ}0lC(uq+J<NGxYrV zbKsP17CKA_Y4WQ}O;@e7O4KnCs0y+b0fR{JAqpg_0XFkR$Q;k4he6UwJP{&YwlYmr z;!!1QMyS*x1VWy*6cfDqaD*``W_-*ku+pZs!KXu$JWwHgx*i9jO&5`{MGPy%%bNpg zcAtG^0XWz3uB9L<3Q{03r$90a3S&qZ)L?SNT-$)_YZgd?vQ~SBbYg2%D?%+HD|`#2 zuJSfTBGm1U0%-ly)J3d}hBjW+k8r0lA!`5$zIm_D(MUm;p^!*0plDtN<U%V3a*SL^ zk~N;AWTz`O3|o>6Wt2N!tT%k+-%gJt4iisJ7sVueGR3gMYw;xM;swK27J?DK)Dmzs zg(15n$cj8|rxctf>X;~LB0@TdP!~A;fTRsEL>L}vrVf+^CUJq0pg<v08K~xMaM}bg zP$9wwKX?$J&zX2Tb+ALGqomT*l50g0N-o0K-5dNKJCtNor9c_VXd*PK9lEF^E;=Yy z<X{OygwgpoQouzRCKQtpry`7NU7-S3vF5N$2;(#@A)RJgghz%#18HXMytZVXfrh~9 zGRG&L*kWQ*I-`SY2F(n$cq{&xIKD(1q5F(g3_r0MO)ebSDI^7WS^rWm1(&NrzDne& zrx-5Pip1+0E-sR&8Lhl7zuOUfUAGkB;mxw81&6sE;VFaHvZY4H!eE#+iBC6s2a%I# zEhNHp$#p$g^T^1q=h{#Vbt&+IQ6D-C@q#=$tPcPRTm0n8Lcx9{M7pAKw`WeD3y&6Z z;4w+ox<*q;$ho|c3*cw<Gr*(2{ulr4mG*0IuP<MpUznern_XO5A`rp(*|~E_1m;l0 zbGeMxJdL>8OTbzKp=JUUxpeEk=wxi?h%yV^%bB3PzFMJPqLd%+ee~9?ThPWwMo-Po zQGFM2w7#-2JUua~RCCiavvtXxnVg!ezf0UcvtHiY$)zr;pscz-{_&3unG8ii7<1!= zcYa}EY`lIOQ&rvRI5VRa=aZ*T^Cb!>T73IPZ2Knm@Q?~@ZEwxZ&shapF?)-C`t0fE z)|P4X{!f|V_=Fq$j5(`cOgud$;F0=mX(JG>UB7;IaZXu1I5jjgJ3HNe88J=zHJO}E zO-^~In4LL2KYQ=}_q~zcx_x_YVgAMH>X+aB%0c^Xw)bP0>#ts^r$p#fWn5ew8RkIx zO3+pZ`L*lIH*ejVUtEC9FEzGDC&%@YeRL>ILwD}oU0zvv?Ty!e@fUy5q*Q_18->>M z$=u<+=Hb;WVTLBB>fK{*u6_d(#w#c_3QWv}ZiMP@MlAIA-h0n#24cy&d62+FOxpUd ztF3v2ocpeYKdOT5Y0b*p9mD<t`PN%+aYP7*<n`BICu9g&7`fR1_b$!q+u#27y?gf{ z+qCG$jT^u43%~G7zx-$HQnu9c!)!qE>IetES3x`l@0Q+jS-t!2yBII$^x=c@yiv=j zAtA|HNPG!fBsB5zGA*)Tl{7_5nWLme4R5~$q&8vu=_#e-1yo<&X)E`o1&$CMXj*c} z5=jA7KBH`dX@Ot}@xox`n01imz!DqgjW^!l!uHtQ-15$yP@w^5g@=Z~QZt%U&nQ@1 zC~}l|;+-!{YC;I4if}%-B~#XhsG(P{UMVAa98t!==ZguFnzf1&-p0lTWcsGVxe13* z-OLLG6mTF6BY_W%iIh!x9Fg;dn72Uc>5EoZS1DLaQh*Q;Yuhd&uYeli8}{Jho+98$ zcvqPEgK+f;n!2P$Em2VmP7AZ1YRS$nrb)uDx(Un>*vz27k^;F3P@oK_VGIZ+GC^@i zN1>7wOfB1PLZOmxKOaHJBtyc>RFXuqQ-iNtSK_1w7V&}(_V=>^@yvse)biB_nkK?1 zL&4PH+2#>Z#uFMs5sHTuk9a~JF}ma!$|PK5oiLXO!sv3UWu*&Tn#w|gw`QCe48>#Z zWj$1Sm-vRXx``xpCPWxy6d8p^4c~=GvO<bgB-Bc?VTw>}_N=97W?>RG)FR5dl=&5T zf+yD%Eqz%#Lv*R7Tv66?O2L&P=b<4nBz_(ZDMG;0rPGrlNAcc5u9{O2032O9@`@uZ zE3g22nhXtvC?Ekt7>HUHrT|Fhf&>rTa$+m^90C9{Q-r+WZM~$aB~dq&6zG5@WGGZt z^zm_#2#qFA^PU4d*>y^hfrrE_a>PYaqZ3CxDu6Tv%n&jOMm#j*nr5aT`XNJT(6Rj5 z-wmdKk_CMrsX&TP2-9jIhlyzNWt0^(%DO=gHSD7Kx%#z>Ftvz2SVf>OwX~24B@31< z9daJihRD<HaS9{e$x(z_a!h<hCkO$TLTvj`%n5Z7IbnDvC_+rfCt-roN(}?qkglQN zUqzOq1Uo`+QD&zLgN(w*Z#>eBFMNhVc>1OQZ$>1@#7frc5+)rjbDEg&K}HR4Kye+4 zZ78Er?k40r+x0`;PJ=8MWzRg)sWdL%yL2UJr3fitB-ApBjA|qAL}Hbdc2f&eRlA&D zL@i7d;_)hVLrmv`kHo-)93SK;Bn54R=~By5j{?G{sx7YpI0|5X=F6zcQ0vp-o)D|h zz^2jI=-?dC1|*L7)k08ex#QcCtH9E-WkR748!-`i{FYK>VNxt1%8DiubtqnYSRe3n zt+G@-HJn-=-#nadZEa@h!iQj3@HxKvBL=gzwM7^OVUx6M3fheb10*Yi0tT`na^a<J z+K|Y#sW~R4z|+TAT^RCY8a_E<6o)(YA-56g8zf$JE*}9v1dvE5J2~k%i#)BEkgTt- zyB~L7iA|_XC;&mybaSSI*Z%fj|Lc|K7pCFA|6lzbp&-F=FB5Livqz6>%16h%p$(m1 z4A-9q8Vc`)YH49ndv<a<HZgv<f3SFM>G-T_?MRiCBD(0CB+q*inRw~-#w$;4UPZ=- z>k+uWyH_uYUa+PnFV4>E<C90nN=H&Z8hU<_za;FH@}j=~Uv(EJd<D|gl5inZ$*2oz z^L^+Y#*z{MIlnZ~%a<?78FpLx!qa+J)OCS-`0$~Ju3M)2oJ9j1pNveKRY(o&>2WPh z)02ZQPh~@xJkBv*iWugOWu@|nAwg_SGlKB(#~**~YhU~1lTRpk8T+F@`lC1Be4SkU zFx68G0L_uW*4Ea5aAY0i1f&V);Gn)*BRn9=Ylug;`LBNUtLm)gQl`n=G?@hfSZMMW zuI=J^Yd2V-UWDuqeC`f*Ox5V(;^vLzy@S1lx%vIWgOQ<OFY_Dgugw0@!J#+#%~u=C zH&zbz_Pxe#ZEW6qaDR7uM@c8gCx%9bj}MRPM;s?6w|95$+`3K2Ebs2`SyATNs8Hvo z=S?(M71-rT*Fre;LTgU5?PV&v>>Q&eLMtg*yZLE#DXW-yVWLokJG=EAc(1N_oAc45 zM=D8^mq78N)QZLsW5(@gLPOlKB8=<IBSXj(+G49$4(p1Gl$s_lbWDe7N<3yNATS+e zhX?f?V><M;6yU@!G%l!d!4?ABsc93sncr1zh&!89z&siRVuip_BCfUT>#r09EHucV zge*duz?t)9eM(;q@%5#scCph{f3WV04Da5(OUMwW1qO#Z+j@JqQUk?`-{|x*Dt^u> z5-qFtdnsz)6@PiiA}=8liL$(SWFiHtT{p0bkeV<z*XGU;1yE*0D^x-evNeS0Com_E zjZDIY=}?oPB`OM9$Q)I0BO^*-NM*FqdGX?fbAD#J9MO*&9zK#RHRfTY4-J2Ebl{Ak zAR|@+NG{4-xR>5B33YC9L12*0qi(XJ3@vgwnoY<KF~<}`=0=l301>nnV3E-Xk@S;w zx5A@=YNIZsF9vETazvO`B1y-PZcNr!Uz)YP-blK#$aRfcIpzo%nqR8luVzLlLt`jH zPA$ARjXOL!N)af8vA_(m)itUtTKW{Sgp7hk7&<6W*3W|n4|q{$Ya_n|E1?RKq4@D! zASRGAq(vl&%4p;v!Y&VQw6|zxvVPoD*uvvl5d@QbqtG1Ivp<D3M1hGC35lUxsENlK zGfIs+44p*fLE|A}!%CKr3s#DcvELIs5c%eapc7k;pg~AR35F&i2^T2S#JizPad%yD zH%b^u*${>>>EK1hL>H5T)Mm{2BO^<i4o1GrIf6!$oX}9FQrMYFWI4qIe&017)5613 zsF<2-<m?g>?=(Sm9W5PlJT<)0tdnGyNT?Z2p~x|6D^A`)#g{HML`Q5SctWGv&ZIp# z9ef0u8bBcYij7}WrasD&wUHCU21x-);A`<I1zv30gn=+qlQU{XNBn{@3QcVtws}}6 zh=b8_hnGbjTPQhp*ig!q0!kdFa~rI#A;c+tOhH_(C5)sn@R=tzWE51W^E}emrpt<^ zZoHGEOD9lbU<=uhn3aOiC_W%rqESO|dW)#h39@c%wE&}l;xVL{x`gx*9QufaYm8}v zmUBCm;T`ERr-orj62O256GK19C?-+BQ}`1!?EYXXmDj|<v|wZ;NLfP=38F`cKph_K z!@~eHq{Slvcbz~t@#xS+ZF5jPk``Jm0JbQ~<S0z!D3Sn%C;VJ1=H_T{ifYqEksxZ3 z05LC;#bnpyJk(WcP{~>sm5ZTzA)K45-(YM3K%iiq=YB;Ynh0O|?e7@t#urI)58?Sz zVY#a?WD!nIIYVkkP;M~}!lq+q2`Le>MRY7o?eNfO{f*)aH|Rm@wO6zk?bpv5RrrzN zG3~zVar^RjHZP|Vhfe~$pe|n#xhB+dXIJ9Iz^NM%lib<p_X-<LOOl}wK$J>SP&Zu& zbfTOo%Z8#xl9i)Nm^F_VhEfk*R1AgNHb{zQh?*(TI_MBhupV2v4=~|0?zlk8-r}l{ zg1-O$`_Pz+@PGJ6|0v*JkVb#`&;62VSzKDYcmMvKyLYB%rq9mLyhyoFczYSEzw|XU zF<Qqx-gN^n(AlZ_^5^tKeS4E!^hd|_r~GDSXXvQz?A)wHJvLr{QEGQ@*J`r3OlJG^ zd%a&>oYmW|T{SW~Jnogq4bs`=27GW>kJ-^OJgLQYG;~(B*H)HIkz!?$QOTxNO0kuf z-QAt`=TG?Z(!Ba&Rat4$|Mb&ODLd}7AAndEo(Fj(q|oE-^RcNl1!`uCl_6g6ro@xU zaU&#{yE|o`^+BId%NB@uauL+E<+#w|Nhq@oqp(^a=GdF6M38CL-Pou<&;rNX4t<&s zgi&#}ZO@QvS%}A?r)GoU`7%nMCY?M)ZCbYtL#ly{qFRy8ozwa$=Hc@T|5NQ<866&x zjMUF3NUZ)Enk_r(mG$uO*|X<I^`qGb2fKT(UTwU1`pk9F#g1g{#j06@Bdhh*wIi4Q z^ZMqDm(eOyy8%0QMfk}_A8l=I@3ycH>uy)S48g0_*l>N7PGtlpRHfGDsl!TAQotw+ zL-QhiI%0`3Lql|=rZv$j=2gKc*GETn=k{b*-kQ5c4<9~crP^_%+PP}rwdMjKh9PB8 zU=4{x8xsl;lv>RB<cI|&q%2DrOWjc;RBh|l$D*hS!)4NbKRR;U)I8)n7EU31KuzkX z9CG?tR|bS}w!60@ew*K8&!sSrTlgY0r<@8*Jn*d$SnbD^ZQd%WmJS8VT8mS7bT}1^ z*qr?KQu56TNm3+k)w-#JA>d$jk5An5EJarEE9~TG1>mhlOuFQDQj4LET{xsQ&?vRi z6&P^Hh(y<rmWk;$q{SQ3(kH=dqk{x2SrVI<5M}@JqFfmIDpsdU3&V`ttwG?F1f!b; zpg!~&W;xBxdT@$IP^?v}idJ=Ne;rZlAAroA!0V4fU%oAX?M}6X2yaLtc%w4JCr61` zV3>R%AP9uw$pgbONW~BaR9Ynd5D6317C_yEID*MUc3Kh@NPQa8fYRk9j5ZV(&{7<R z*?pm@iFz>iO`(NvrEw7`IWm-vkaUj<V6esnCSVL49;xBARi?|km$nZvC+8(|q)P}2 zV62ipxh}$__;_*ziU}qrMxkY>`K;L?rz3uRhA;^OMOf$!b0BSBU&~zMQ>!Q(9n|k) zv6gh5V0fpN_~CO$Ie^+QhJt`$QqY%x%1#(7OcZ!jZ6~C)p%jEb@R<?I25dm2Y*okV zYUJ^o+^<TQ)6BzB7h&Q(Oy>=WkUmNPT?mSr%8=mA8U<kpRR!Qj0hNO*vmky1L4v8O zbp^-qt~JrA2_Y+(>d%TAb3zKN@VpS>xh7ALiMF{K>_<>(L*$gT)Zn)e>h3|3r5g!N zRi%ljB}gr~$tq8mzS5#RVA;~-x+E>@OpS^2CQqI%&sQRZiD*LBCA>-rCgfnx6w{A{ zK0}K{J#|HrXCK3OzY5-q5J`ku$^vFCB(;sLq2{5EWrkgjg2}aD2ty68C>dcOB%O4D zL^HM|h0^9!w?`75JT+_<B@9B;)Kg#?3J8jh77avK95H0B%TQMql8t8YdjJ&7R6GCb z;7SEzs0ETRVyi`gifz!CP@`})q{#o@seU<#`-9d)+_G}`<p$#EXS5+zyxQQo=xO7n z?3)y2X(4?1zLeKb{GLle@Um`K^Y-U(xr=pEWLM8Yt$1S|GS=Hrfi^1bs!zohD1zYV zHmCvk)qkob0+9>Yj6guT+P2VY5hkyq;bImS>*oh4C@-t5d`pEUeZp?VnF4wO1VbzF zrs4!(KEO_$-N!6gn*e}SP01L7mTup7c*g>{V2)k1&%H6bQLAhHTr+Rl3!#n-)%C0X zxgk|cGF(3ZEbrC@#mJlS#JHf`ZwN7xbUIAUOskHe(eW|wGYl{4@8_SIvAu)p`d9Ne zS$~4qKWg-$f%T7a9OWN5*qRb|HjBUh{&4-x;WknA*LvYVqgMPx{XJBpe5nv2EAMq% zJKLkf^@A1aAOogKVIrJnCJ|3!h=RK5ninCdTS~`7M9pD+frEtH&F$8$Tg*vV{mgy| z*02Biuh}{K?Ke(ox4oR~)L(X<otim0KG|%)*?70TMVNVVZ~9i1b!xM<@7y1^4>=#N zu6gaLZ~o9ph73L9J*Zy1cp+$VmubAU_;U5-sRxFVjE~i;$m55fe)`F)jZM4Q`*GU{ z!}y(D?-RTA7B)Pze|Ye6ZOx0Kmj_Tlw9XwalqPRG_>^pNVrp?=o~Fm4*#70e{FjR9 z&EeUzXPDjH`ZgW%Lef@q723<QaMssfDgNWfPhf0s?<lmlKFi$#bLDILu3Yuwl*je$ zSubvh!bNZwj;AgClM`E11-wdO%yLbtAbZ$hLS|G_j%m><tVlli-~;b^USRB4LPHh= z9c$PN_)g7EJyU7c?r7v-l9VMlU0-4tT3=gx{^EtLbnEu*z1`hOw~gat2`ae7%8MJA zki6f*sf~&9GkCjubs=ld0D(%(y-gA9MP=Dof2BlDK_2a5wl`Pm8;P8n?#c0qr%#`* zwRg@3_wQQ_oYH~ABO3wlwx7<OYd_Jn(_Yu>QPYkmtLfzQ#QAXSaiebMCpPQUj9^Bd zuRfcdnI%6vbzYpS!JT_|o$;0gefyB++`{~fcZ2h@DHrbZv$6WCM<Wg-E&k}Fo;tSf z=EkPh-V)r}%e952MZs-uZ;?QN|KjDUjgT*%p=?^Mf?)DZW=SE8TDhHQEqgUFQ<#__ zd71Q_jAj{$fkLig&MmJG&P*qm!(GlQytK54@how?T7h}#17FCKwe!umVuH1*fbb;% zqY2L_cNV81E8mbVO_5|sM!CqEYeJFO6!bBR?VU=fS_(+0l)?5=SdcNNHc?-ioD^Q7 zotaSwMQ}S5XGPwg;2r}uMSTa`1FqGn?yU8n%by8J3NWRrt3=EaxtPf*v=v^LD&3nm zZ{}dNkmy@EVgp41!wL@^gXq8Z+H1@yJ7?(IP$p5z%1Be`7}5k7U)hrRzLWFBknU@* zy>6$=MF=KKnk^RRM#bx&u77rs3Dp{#o1GB|CdC&L9NM~N*%)Qyms63{MW%gi8;Q*X zDS~xKhXNwh8kGVBh6qSYG>@kujC>J>0*S0mTow!>%q-Ip6$E57mF#j|%0N(OP{XK` zM=;a`shG+;KU+Ur9)tkG;WuAC;4vW?5|6w*HAwIfs40%qz#}8y+)jj<@u2a=JVOa1 zyf84K)FGs#S_;goeC?j3s%BhBoN_1X$B*lSPQVStqeyfUEn+Sy0catF2x-#qPQ}9o zA=s`=%@8@v@zKGr-px|9J?Ug>;wxx~6-pRv6BV9>7n+c@2^)hTKqhgpOHd4S2rYF` zFnOUC7g_nxQr;ktS7PmLkXm9$Fp)D6Fk1`b>W~<Ku(}F@q$wUT;8`L1nKd}%f@JF` zlVd8D0w%~rg=fMLpCOu2wm0iky!@eJwse9_L6H0gs)bX$5@8Z5h9Mq^c}b|zPb*)p z2{Bh^ffb=v0KAYG4O*aRCL}~2WIE80(UAHHqZURxe?(570ualC)2tRc$d><Houdqy z1QWFeJ6J#McNZ0PeJ;cUU(Lx?i3?d!2p_bD^cle<Oq>|ql-Ce_tuFA)9fkr;A<+?k z^E{{np}^>igqn;9NurbN0)i3@N_KseAv6kMplR{3!t-lsaSb`aXsaTPD1<7vKmH=h zoI++0&!Zs>D1hqL=aB*vU1W<nPY{V&ON7y38%;47LQ>{h7o&wnA%V3QzrpE>94hS} z3R8m>@g-fmcHN@G*l1#dKvg~AGml5%=_-hu#^_j862TEyL#vXqqUIS3ioDH6MLu+4 zvi!GpqBs*XO&ht~Hwqw-hI8J&tLdRw@65d=z8JFcJs_3En^?P%71f0h71s#J=P*O@ zrC?*@*2cxb;hy)%;6TQEQ>Zm{dK6!3B@a0*E-solXo_H+=xRYpO1TJAGzx_7@U1LG zgq3+CfmyBy9~@RJsCX<y-a;Nck(syIEP}%%73Pl{$<$rC%28jOsBZyBt`3rJ@|ycr zHns?+mLte;a%|$Wxhz*x6TfDkQ#U$Gf~My(*Riq~jAjPuaDs2MP(;{?oC1bPQh*;X zgcy&KoD~!>VuP&95nH?xc?>OI_Z+WN$V^#C$0wq_z|YRi?d|V)^&g)Y^#ZxQvw5)J zj^*|guvX=g0JI3E+zmMu-Tg!^VBMeD&j5e*YhQJ}wD4ZOT>IpcPwS@v7Z&f`f8e## z8{5IrvHR@Y;-Z_5nLj)}krC$M<0r$TV-r);`-ev}bMxLo#Vp%{{e#*F^{a-@yoLHF z;jz*2ljGCLiAgUu^{vJ;PnU_0KK^L$VBa)PPEUCcxxTWjot~YxuD5r$cMtY{^ufO- zv03I8=U=>hv2?9|lau<IS0zvsU6YYHPNh_h++kz_yiU)|%vKhA`-_W9a$JA4p}Vwn zZEJhSa<8k`jB7z{%GudD@5${qU5oB)dTRFg<k+>=LZ6+Puisj{<vskAT;%vij~=@8 zwO^Qaa&}(74B7jM)?43beQoCC(}$mu?CtN}x_whi$A#Yt7i*n8ZHN26$i0`E{;ln8 zr;U|p9azB&i;FgwGsm`eGI}9jSy|rOa|5<AJcDcN%18>9i(8{>-1x-g$=NB;XD^;l zO-?D};=*EmC1zw)ot34&MC8C7u4P(3oIE}?J2yW%HokvwxU(xlD{@jnrlx0}zgV4Y z#d-4dnToC4xakG*)#j_~E7vFLXPC$4=I2K17vk10rc<u7HsuFLhw}^bx9;3tURmDV z-?QQ5!qNP~g6sUlM~__bUwi#^?>&3_`;Q(!zH|4kloywlcK7zQ7QocZ^#0zS>2~}q z-(0c!PR?aCys^D$FD+hQB0n2CUs_yT+gMkFvB`=0yU7dnL%Bos4tZqutbz8S?Q^fi zMzu;kH9LL%+BFecKhAP%=H%?`?%g}L?%YxQrR&!f_OQM&GCf;=#nfC)93Is7gz1|j zI(1I8FD2UZ0P!55jJD(Hg8BOT+FNhE>3QRPw0KPAtatbJ*LRG1GlXFGGPkLxrt6Pg z%{Wi$=hN#om{8ZdA~d;T2pxxqM+eN=^2Moq!R1KON(Z^tP$0*1vC{syan+%{kmqq| z>fO9^!~g-{mg13CYGY#-;qr|Y`%!u~Zrzmp^z4jhxV2<di?{MDA-mFQXI_uh5l2ED z=gI(Wd}8eQ#8e-72({-(J&Go$_^l7F2-20y*)7N_XuCTOwnJ-0sHEH5+t(MDDm^P~ zX!ycHu@Gyao$qXKV-(0?dFY{adN%B#=R(u2gUoxTz+uLhwV^8jrN|V}(KU)pA02)T zi2;J4ghZ2^`E-4ql`GEe`eUipW*i^gKiIo=eW|`|F?{j#*^}$bb?(!A_Tri9DTJ)V zeR_UoBOD$d*^KRRS6|<)`;jA9o^2}i_~j079=!^htd}oek|aX$7?Of1%NGI!Mu<dC z&0<htCB=&$Lo*K*2)f#&hUml!AXuZi5D*5XhWt{-D3qfn3k<AzWWtc9htqL=l%T$u z&k6!wcrNagNo;{6NSUqUdFgunL3L`X9Rywbg-&8f)+jox4ABvZAq3VM<^{tqIUFI; z;fn$uK}eg#Z{NO6Urq2#6q%-?aS?syDOVza8K-!#h#|@D*0yD7eY(wEE(`18q;AtL zpjM!R(xvwN!fvp~a#w%@SpZxBq$_cEnp8<wI(Wg*q@S=wNQlvrFqAK4lBCSarN;yr z(vm00ya}*UJ(@5P9qC7iaxb*w+82xKt3PxgFk~Vsk&8zRTx%1yAv$=Y^!Wm46d5G} z1ygM12oZ{Txqg<uzR1g#A&{6@RQODRu1Fw|(2;_g8;alfLc(T6A1q8|^eO^YH?@L8 zpOq946F9jV(obF(I$8@r5u(E!tf>Q|y4lX2=FYl$j!%x){j`3~hZ|5GPR=){w?mO( z<|_y)08@}+BhSS#brWR!Nx%{C$4B*JUhS)DgU^zXIC{6Xwx_3NV7QOvcj>!0wC@~A zO`MgPf14XyB<))-^`R3uKpM{A2B{9cAgU)*k?0zdFNxR$sR&}DiD-7BMouSFles`O z2aUu*2rxR94HF8Ijhs0{a#M*n#Dpe&z910lqG&Q_NZy0j>T2mIU3fZNASsYrV<b#; zO)j;J3LwbjaSf1b3Y0+wErt-X?D5geK>=I{{w3gMSi29h3o~VN#9@oJg0%z;1(OM$ zM~1p6iIC%Y30k{t(ywJ;68$r$C2xMMmU<;hCF=QMu?->@VPcM>hBkQpMsaGj4A&!j z)NQxE1qnwI?H3LcMqck_p0?Js*Oa!nJ){K0n<Z;%>l;38u`;#R>?>;y63Nkt0K68| zX5m>GgqDA9aazwxLbqiYS~q0(;FfP~XThU{DrQL~ctqaX6BTu>a=~^zbI;VmDR8&$ z`ccQ}y}jMJx!LXQE$1$YQe=0lJOop(N`%14`LgE8J)sC43wyi!-WRwd_m~rj!dgGJ zusK51=vyI%%%`&fr`9g&-WluxrJ&3aG%YBajxx5jDK1=G7bYjh&7~I=g*X<rC$Ach z4BuE@b}^cpo!Q)YwNxhcGNs0@jP8amr11H&0&Er2GF88NXo>=%)<t)FYm0n-c8<h? zF#VKgr)LcL=M9p4Zf16Sb8ByB_x{~`yW2Y}*Owh?2YdSxfmUzbr)NOezVX`Yo^Fs| zt*=MT+k+>Z+hYBJ)Ui>ob}HbON-{k)IqPye>F_ZdLlov`=S!*9PeqN-H$|)sLjQD~ znMTc;*DLqKL-ja1u~6%{8=vrkX4kra9~>Oknjf|Y=fTNFYv?<F<7e|Tz@vZV-~Frn z*(2AkUB7?-!QH#}ba!^@`>w|)^{cGMyckVQY3i0XUVq|)#AIJzUY?s@u!R;}RVOCB zZsmwK_c_0y+lPeCBPR&Pg0L(sO3U}Hx8J;R^M;p$i=hiINZUI*o9!?E+`4_s!ETA$ z^?3JAuUlR<?G9)b6Bhuvz~^a~hZz@En+uIwln1Q?L9yz!v$mND@Ge%b8YGS<m7Sko zAT$a|w_V%n+@z+Z1{44E=~J4nP3>ED2m5;m61jWtj<sGld$0J7k}|@mz<ck#XXD+t zabtCL^~Q}AZ$RQt%%V;FA!x{+5xmy+V@_dic0v47aROYswj@+nURn^OqqNG%oNMN? zHgOIntBAtgdw0>~RQ<%V7XlNZ1m(3M*BLu9y76iw<|NwqH9>do+%ZQ$NR-rjl(yaO z2ET8Kj+PE$i%<IE!IOk{Sf~bxt^ml*i#R=iF&}>T;m`m4&;Q^DKlu9BzyAFB^INxW zrF#2^-t@e5)i3R|J-GH3QIRZEWxOGiSP#e|6pv9ZF6v~sNRD&uXYoD#=x8gL_EhnI zyG~mNV*4JWYDl5paoe}e#caOWDr0?tpuL0`N(zP9o~b!QQ+)1FTPO9kf79pCY-_J7 z6S8J<bTVNWhFpRU0<SO%;=K0QvPhPe7Wen}$eYhx0tPE8<|OK`#e=m78%{ko2t`Pf zcTT0RCWOo>6kH=#xtT!-NsU#l?e=wU^}#Tt29~B4CPQri#qU+$an_!*ZY}k|Ym1~_ zS4gNyp~ajVL;VN`D3V(4m%r8pCI%oB?wBX3dZO3Izl#X@rO=}Vhyf)pq>H>{!m&pZ z{EHVaARE<<A$I|Z6?xnNCkz?{b%+j0GR^#&saDTC*XxFHd2OrbtIB&Ar;M!POQ<Hd ze7Bbea(T(F#XGq6#XBOW(_GY0vZkN{t&By9kPdlFD051IGBSkMhDe0LN){qy8>lFA zfpp1H3u<tqQk>XQ-~|+rDA1G_KnyfGa`dWWo3f2xj3Fj8Dd0ohT+DT^YPqM>hO~Iz z37e~;2-E6{M-3Bpa8e({5kTJ4MNGKU60%JZq=qDwASomyZ6wrm<C;*ZD~?7KT7H!v z1Ky*_HOi3fPm&sH@%>~7evb-oG_7t*8V0f)ufm2PkVsSfhz{H2B~C*WP+W)&WvRpk z!UR)P<e)I|<pHEkz7z~$gohD)N<o1H#TSNV0J|5O2v35Mi%|$#qq<SR$CjopFQOF* zFNSoH)U>)BL5qHfvTm-b9#UW#dfLi@2|n%;AqjIrEf<!MAx=rS2p^)ai{|F*x)Nf= zBSST(08KXu67KBmyn6M@>q_K^M?<NemW~#VBG@Us8`TX$G(&i3na#`#HInYMD`Voz zkWz@8P?uri><TgId1Wdo&?Lu*N5GsKrAA+uA&-b8wpv0~p&$nwMFFy~mDH${5P>o^ z&QByxLv#oe046PSYDR%@YLqP=zH~^!IBKY25&$wJek8A85&}dS<xa~4bq4Vm&Cj(Q zVUjW?uJIjNi^#*!Oa)>XA;vRZOCDh#QUsdhc$mUQ!gsw?KNDq;x+g>a34|~c*m*ht z;h=;nP1Qp%BaZ?vnBtpN%=_~6&p7^1{!4<frCQpJbhXXHV1XgYxl{6~FzFhl*6NlY z)~I-3UZQy~HSYsqh+!B)=J5!jWjC5X8<ts!Ydlg<yj5ZL-NLlJ2+R#-RX`(w96&l* zhlF^GA2y$alryA_2^?(#V+%^8R%;Z<32XJX#{rL)u28}1LSyB9Rj&d&st>Gtl^Piv z9UmEWeVw0~-P_;adbJ_{m220Ru3sA+svq}j<MjaLr3!X=@8U6AEb`<+ZL$3&NWP4^ zP9u!&M<0FUk(5)>z3YuP-oQIH-+JpU`idh|F?&MYyLT^_fA@1|ju>3mgGp|Yx@vk4 za<TMi+t}EUnoX^ATEXbDr7xJ#v5~`r`V0;N4k4996hf5SqqweNbS%RxF-cuDp{6C# zRb=kyfc>4{{Tn1-oJRlhw|@h^<I5}R;^KmNbQ9j*-n#AObJ~rcM^7xXE*givRb?ie z9cT104%_<jXZ`rL`Ko_}X3eC4VrvLvX_B-=Jk{#uicWP}$xMu*XWHa%=FCSX)$EEu zpiYNcxs7T$Tz<?Wlto~OW|g^?Z+(bVJOp?_ih(3uFB{%BTMU+Oy^wRt91aFxz#|k) zRpIgv!067-)t7ZCTMaqcYwFr|6&PiY<ZML`JPL-aRjY(1!l0NS$V@1+P4Kd)2ifVd zBEQ;L=hXWH9a~GScxj~`oO<wuvAefFGd(jkIW;#scYJhgTybqmj_V73^&<eXoW#_V zs+Rs?zW1nd#Qs%WmTrBe(8XnRd}3^J$^&Wm?7U6{^Ef|Wf0&0Yr-C$nLK22<<l@&R zFf&Vzk&96&2r|WC`}*szyENEx>SJHo283*3S_#w?*;9?JXC4!q#GVYk2L`zn!4U~Z zMzy*ssRc#Osn$>%tpid1+B{h;EeiZ*B49#D*z`%fH!}xCg34bbdr!-YHbQA;Y6PDP z8Q$#c3LYkgX3+34fti#kFrh%wo`!?(O_5NhgBPl(l9z5qbGRrJhAk^$(9{K@6jAP3 zXi?(9WRw*X@hF9YL*oc<6r)Y<afgDyL~6`+2?5fiqnnlvOyGt{F!^R+<je`-t5Vhj zhIcI<u@V^_1Q|i-bX5`_?H?TUDml9$2#j1e3V}tz40wcc3^5^0SqzaRNcF_fB#cRy zQ&tLl(1Bo4dGSsd_9-aBtV!9C$4l^y2C(H(U#P}+*CL4v`W0xSgl!0=R*H!TgG|C* z3_CJRWfyAKfkRGch(y~FgcLF_bjoWhh~VSP+6ZRV^b*IY^HCQ#+p8{g@xeiak-M=9 zQm7HePykYkZHOc7Rb(xb=;%hD1kb#?P;e4MgefDTIJ<fDnQJ2y3?@TW;>(9ONr+B} z(2;pHHiVa#z0WYdbdADSd~yu6;6T<zN*XUr0>}!J`67?UL|8#I3Qvu4^eJZu1qxvT zD44{f8y#JkQWik!laquMNibtbnI?vE;*3NLc!r6;hiX*ITnhowkq))^?V2PA2xU6j zEC~`ihD3tVjdFxqIO^#kD`0>g)1D57JW8}(Cx(!dSK`+Sh86G((L`M{w)^{oKeb3m zVl;B*C{{pZX9&6S6v~yQi#T;MaO5;VBtY!Y9J8!q5(<v}<(6rbp{{M{LFws9o&chW zPqYF6+e`;Sqyjy#P{+pzfF?fWr7w|;qJ+&nB~oV+U4~$J)KcqVr0v9n1ZLmeY*C6C zb3~Jn3p^;q3!)zde&tSwl`c(~j#Fh!f;166(}95*9CADfxp=g6x(T9_NCMScBzFpM zFaf~}gNOR9MP3ds>R-Me>z^Vin0v9IDn|W9Tmbb%>q%iiAztLwBOwX63t&T2mI|cB zBD`W)=U)yRM$HbwXN;-HY-r^goIrJ*vkQqx{PPHOy8hLF9VcoGyE%sZYLI+;0Vb>p zwuum{0wUd{9|M}LBzC&n#USiBN+kRSGu=ympwO5qTFg+Ekfo9>lda7WVf>QoR_!il zfr6T2$VI5D_<*^F>Z$IA!WRn<QZEkFlej5xhty?tbl5%$ZeH5;+P{R9^+~~=&Dtw| zapC;pY`kFWNA~KQG?No1RlBjdxqM^g#*G`-SC(I{tsR}zXVdP#_F$)dttY#Ql@<<i z)**7djIP#M?s@7F>RM^`%bRb$nJa;=AtxlLM~@ycaar|>o1YP5>(=z)haXb*&TRDU zx8J7VO5?D4`0$~UQ*a7d*m9)63*MV>ViQc_;hNmbA08QkuMLriU(M+xB<4&`&z$z& z;B3sgu48yqf2Qi{pR#*{^UsjQ@SVT$GkO93bASF<M5CaB@D#~|B=1yND6*>fE*}hR z$mvLfL`B*Hx^U+rOg_|lw(=x21Vl^1*Tm#l`|3iWktBeCn~Bs5ABuSjT8<iFdRe0; zLbhs(5*2;&?v!T2V`#&W=(6HB-f0@87Cu?zUJg@Bh<MrEtsf4wR&qw;qmM^iKYsk! z2C!nh<7s)3C~!K034TafbQ3>cz)32|wlhscf;WmW#22P*joKT@8g1{?vw=iZ7A~FK zxiPXxRCwk<(9+_f88nm_0!!`X%a?ErfdXrNOZ?ik`qi42gUUCi7JyMYBq<a=;93$y z4Nn0qOeWrf>`A*_d;k9Zr%#{0@x~iGQj;k)n5>Kf^j-lIAbkqbu@z-49-|IWL(-2& z5+ns)D3D{c;f0nid<+m(N^H!9nia*huDLFLwC-)pkx^EJ2t%KvKAHfs5(Ehu2}VYS zQc2W{k2jj?5#lj$<STJjNu-sqNLQPTAVi2*X-U|&91AV-gx49q1SSh=@X1*rfQUS0 zhm&a{kpd<z<Ru3Bpa|nazH~4t4h6&=3BsV51R+A2VqlV(brGEi>6jXk(1gwk6L(QV z7?OZ9iIwhYeNlGOzH=>JTU&Fi+jkJ0V=+e<#24>boLA)tatNQ`DJM4B4aVAN2=9rK z82C~XbxtYbR~I8ZCz9~uH1!OWA$-yagUB0v#lX7=G3g44J3>120b*KVs?H=RbB$3< zZ45~|&Q-s<<b8!05~oFyS<t0`;+keTXqc@q6$WKzo$0|-L(~!y1)84&iJ^M{HN;CM z8ZQ7m{XoSwWLIiMB|LfIfu!2_fJ5je*<Xl9auS-nP}7EiV3dxbbhXJYMUHX+8`!{$ zcDQ}}f+SsPVnZexpA#l=QsAXSb(|1kY7(6Q>S_^5ijyI{z`8FCO&)V@1YBFVm$OjL zE{TvN$QT3-jusCgU$9FB=zz*}FeJQM5Dc9J778q#5ZEXnT`uS_biu&Wj1?WixMLy= zLUq%U@E%QVn2rg=)>~a&&Cc3xfA`Xp!Xw6L!cKw=<3cwRjmhj7Mf8)hIHRn)yH~$h zkr0uf=C&#yCPLk;|N0PeyDzcLP{`}6lr2;X(i&D_9urAN4#k%k<VC-JOkin=l?1sU zN%~qOP9PX<mFDsg6BuM+qynhxBg!P=#1p2@gqY+Woe&9fR02%2g!Cb+9wy*SqA9O1 zguO&~@}v(cI&cg{$C(M4+$cF7z6hzQDkd8_cK|Ix(!OrI=P6s1sKUchB3aPKlkgj2 zD?$>=6gm+$|AS+&xAa*>A0v#$k6qMnVjU1kCmyw|I+arZ^~zclwQeW{j2zR|DyFxr zo$dN%he%)vz!3A)B+3Dg4hbI9j0Tg1q85-)#boX-2KjcJ$UE~n`Zvl6;}^wm91RVh z!xc{PmphcBbP=^^My|17Qy-L&Vx^v4h?q3XI!|bk(1}7A3c|386gJOan(9E9EfA;C z$LG;cPM;1r*M!!NsP^{{W@e|PHNP-xsSb}^c*k!)Vs&<OeBhP5zI|Rl0&(g_Y2xPQ z>-S&eBArk(vs!!>JcgswvlEX5@`<VX6}jG=1vy$Tbu$;kL(iW-_cBa*<!0TDclLH| z0<iSik^`@Dw7>9@5(!%uqf1TeWp#OZSyav$b+E{<U%&1~^y0+}TghSagCG3h_kQp9 z_<iS{cN~~rbVVpy_i$YZ9R1-R{-GO`A;%6Y%D?~nzc0tx*%{|p!nk|)u2PEx|JGY? z-MV#4MusR?bsEh~&sMmNxImF-vM|uNpikoVaZ(?6uCJksT*c@}O*|1YuWGly+nNgh zd*As^0KXuO{>6XiFRD}u&3EFHdER_PAgd%MAetDV2vN@Bppdi464n)~Aw(X^SpylG zQC-UC_2sBqf`mLqUpYJ;;wT<->A?&1<hb4dJC(<_xDzu3U2=&aUgB<$WP2pgA&enn zr3*Z0M)ASvJX<S6g4PxUz7X)mrTQ}xfeMZmPm+9HzD*Uz5(LGTD`<4I!Zwt!QxL** z1*5#Cz~j=Mv=?S(rZ+ZTdEKx|@a>oJxR<zIaP8)LoF|L*4Yodu)r#OMpn8G_MS|i& zolCoYwTwQ3hA<SU$t#PGL_Fq*oZnWE_QQVd1Tkd3f<}`erx-3!V1dLVMp78@SXazV zG@-7r$w@3ZCL~Ov!-dMzRD42?1V%`rt4MeZ*W}8`X><sYutT6cV5nJNvVcj4CSpZX zY(}XWqEAP6Zl<<07d;n5&Wa8pHIcWn49<N}YOV!EjhEbAC>UiMLkuW7c;%&|=6Jza zGxRCwa;l^>gB%7_+yyhF8%8kEgrky?(~KM+WPF1u!izykuU)$)5~WB+5Mo6?0c(+{ z5TQ2RC<ql#AJ4qIjzqHBK7=S!(DJT@pO$8L!_<O+1QW_~LU`5A`Yi7)Ks9G&G%d7b zM2#f%glTqk!D?AWQ~kB(f&$D40fq|wlDa;*jYi@$_v`^{t!C;WAg=LQ`50E5w&XsW zHPrbYl~BRb6ig~ZLLmiA7a0PMFp(rXt?=YdUgc}AH%4K`1rusWNR&|m=)SVM$?3~N zSrGkvEQ%%&U4=DDEx${TGBT=dZU@_t2?CBU<+HQt*;?nQ=R(e-IO)VTXtC1m%9!Aw z@X^E|`bb`sbtxzXVyK%(3??lhkDjccSTRvF!i=&FzM+_O(jg4bwj@o>fyQ-~ocb__ zpTi9-d<-JjMQj<ON~Ymx)xl6whNdNCh0lVIJ~iDCFELLfVMq+MS{Bg{;SD9VJg34~ z#(2St+~&drjZoy7=%f&nR2Y$5Z9`o`8F7d59Ru0nqh=_MWM_!nPSGWVpHNXEF-pkX zG>P#0-~YaJ-gx5;5-Zj&W0jRpIV+Y6k|1E1hhaiN%P)c){B$SVpT38KhrlF6B0Mc2 z*YFAP-g%fu2ZIQasi%)TTr9KP;g~b*ItU+I)TZdfZS~DJ-+cD$nNW38u7O6Q7^)Ax zIV_4=a*0|fqezvsR)s=Q%c@X>KCR@L{gC*L#*tA>>H`xW%uxK2XM#||V2EaB20uR~ zmj2K4Q#p-#)R-R#Ay!nUr>4D99Uj!5X`Gyx9382@+Bn3}TH>qzRkr>)`={C?o?#{$ zNWzd#c-|9Im7^W7f0C%tPnsyzpls23`BB|gNV8DEXG!vpQJegWQ0;l^xkm($cVU=) zz6e!bscW)r$<x|U(TsA)kTyc293YrUB>qqoXr>4mijahyUPg<*jPn13Xd(>#D3_a7 zH*I3TL;>nW{b+hwwL;c{p@X6y3MMMF_5vI}l%Z@)LnutOV^JHdkZ2;K@xsbpw#&45 zvC+n4$w9!-FNl@`COVNra7DDOx3)HK-MYEAw|nQ#ZP&%g_WfS+@%ka$(aCyuovH5l z*y-76eI~tOnj?Mzifw9Qa{2o5-0bY(ffwep#f8QC5!_mYLsRv=jS<TW@5MtqTc2}0 zAmMSce%brsbo&$WaE=b^V1b-3pSAkc{nmltlE1#b?jUvC+0NOg)Di~y%a<<=0a1ak zfBow}{NWD?zxmB?{_3y(s;(Q0Q2)%I`7;ipci(;Y7k=RvoHOKq;V=A!Z++`qzx%tt ztNUxe_G`cOTfZf{Kl^9@?03HN9k%bi|L)KK{LhoW{r21Mz4xAT>}y~98i^tA!-~u! z5~StrVYIhf_Xni537%8CNvq~suM)z>B<!>E!P1hW$bn>XwREbm?I#e~;?d9S1^74q z(r<8(<Cs?@2$88B-<e<(ugKA<rB9Pw^de(&ba`<^wJzFDfDko9yy${0<>SNE)z!So zM2B1p3LryXq$&(TRdd^1ds!bYRRTK5Xo{s34|grP&nUGc=N*Gc=#wNEjvyPQoR|rr z#U#0~5*UUuwOnO*cLs{EcJbxg1w(3xT-X+wHA?yU^XINaaE^}#&#<U<x>_Gh_NsPo zw|+gNwJv~sSC)d;X$wC3@f#C5{I)FXMk3lMa2KbDgj@v@ZQh$Hr<lRia%3G_ogJC7 zb3yLFA;d%rpF(2bB}-E`5@>PCoEpL#x^?T8<*q&-ee}_T2M?Y;eTo-+E~a$6LSTeJ zSaG%>8RFALy0f$Ofjt!O48^>)wPj~g5GQ3rh-)XIL<nh8kcfi=h(rWK0WVrQ80PK* z?l{3G0b&#&Fa0ngf!0c1SBD%xVulP*Bnpxbt^=V@jXnk%o<3v}PU&c)zy%OqprvAX zD@y&@Mxw=su_F=*BH;^;MFpQcL?Re2v=nH@SA=*WiGfKJ5CnC=#Hkie&0>4D=}Iud zpdsF?bdAZ77M}nN!NKqdoFj51&8uC+ir@Mmexpk4(gp8vK`rjIQ8=r=DS!CRJMVn> z;fLNuT_11Wya|U>_2dOqKmu!laf;aL28||(E-Qo)492J-EkJEX4Iv?s*rz7QbX#4@ z$dJCFEIEN8GZiRSS`?h{L4(f(lRA@QAP5_iz{qoGkn5(f_~>JTkeLm>ZcnP*Tuxl9 zbY*P;&`$tqDU%qYgNK06;*6tsq=}TNJ0eHH2Nebs!eq!6ZQ<0R#1KiuI-hTU2Rn7{ zP+*0p?SVm15b=;uyXqH(4?do<Hn2>PNSGjM83h}t3{^_aQOX`n6f2ZF8e4o1Sj!|c zf(&WlC>mwvbTSk)usx*UM5v{22yY&F$xu>`(}0jzcvhWB>97<+Kq}PBX9@|xbb)7u zWLc8i5suIp0^u><6M5o+h9SqqQEU<35b%&9P$1WKWuzK;hzHgXM}&s>iY5juVRwqI zdci0u9a-PGb0^Ofnj|!<n(fOvVgQb}Uvz`amZk_nS#P>bjM9vGx~?b~CU}(ix%NQU zO<CZ?1<9#bm_|*#aF_t+A|yiO>EL{DP(Yv%9c`?T%Fr?T;~)R{D_{AFTZHVG3pkqE zka(^#h7x%t&~{1y@zD`5Qa1%5q@QC1&mH|}($N)$b!AB)wsJ)AP7NQAkx*zQucrx2 z2+`3R5_yuPU?>v!go!6;L7-;d70QiJ@J4mv1kk9VbWu<6Vz>%OfwC5#sNj=?XDdg5 zp(vAFZBc_9OgDxEJS2At`<pj*S~JfNULiZ*Vv#j#l`MCG4PcG6*tF%T5uqVM59g8L z!Lx~wL>o$}2c1ibM4L2IWCbLopCQ!i;Q5HpP{7lT&YvVE+JK<&ZKM!FB*2kp^+kPV zc(BG$)Hq5=(G;Yif)jjw#i%C5sDfaa7&SG@LQ)Pc4dJU<b6)9$3F-1;)iHFiqzxKj zb`2e2;4wLQ2z$j4VN6`LEPL1Fc8wf-ERI#;#IV8&@7lF%Mw#%Qd9+gqU#-7lOKy*w z{k$)@SnTfC--6xT+H#rKIs~i?5k7nVoWkPL5@d3F-!58SS$X@dx4l@p$+!<Y0lbvn zzkh#aWyK4pw^sDkuYT2AtFE_JFR@-q-+Jq<*Is+=%U}Mo?l1k)FOk3h{`*{DzWwcQ z|J=|092dG2y#3z0cMmfC*I$3#8;UqRc`4XmU;5IQw5~L~dm^}~yGl(=j=S=yg9A{4 zUf)!M&IccS@Z!Y_Ol8z=SxTX3ZNCieeqd8`l#QQ~qAW$-vkPmWt`q5o=&LO(YOG=y zli&X9Kbv2IHT?Jf{@>|A1ig-jqa!aTqTwE4$fJf#yt=5G_!Py&3z1w`o<Ou=NNPqe z&ox~+(1btIe&QSv#!>Kf>8qxfJ!{C4;!D*YKY3=tlpbuw-Cn{y7y#l)*g^mmnwhPy z2!<C7ObmSt%}TvJ)RVHIsmc2FKZb;4s7H(O5b{oFU*&uK;(4{PW-YQ~OF5Y)fRw_h zC1Ocg?q2ZdT$~T4{By*x#aI(B9^F7qPk8_ozTCa5(iFLxKY8-RD4)?xH4t~!Ywf^S zuSBTAcroXF46({=Qf{WzCC?L1*t!@ofBf;shMALO?w&n+cK6n8Xf_5-AsJGcOg*Ac z$edsDifXu4RC82>7l3r&<3IW26Wi6+va26GdSv^VYx7INX4}}<a17;x+-4jma3mLn z$_$>L)dE1mOLn<rm?LUpAdFM(#6&GK53j0Jdk`XWP+47E(Bum~bMrnuS>Gil7ZOdB z_$h!gQ}9!qn!NTt0EdDdp>*cm&CJmtk(j_VDnhQA@9mWrqmCrD@s)HqLKs%P>#Syu zX|Yscby1cmxp+8A;+c2Cgo>C%pZ6X%d7@G}3JRWYV+ztVr6v%V&;grJb)%DRvdg6K zPO~GEBqKbuWR$vLjM5aRXbEX%<rpGQkTJQ+1P3waOPeki5F8qoQ?`kP1jkTEpp552 zc$`K;hu;)mYIZIL0jG)L$PinGS`^n>aT3xG6j*3TR~UQklMdt*EblBWR;Y)BbmNO= zCI}9B&bN#zks)Qr8-;90Bz$R&V&Gf<hVUdP6%Yf%cx>TU5kf7Nnp|k`dDO)-6aXeX zIa@0{&pC#D)>!FsLBG3b*hLiLF%$&^2Qr3&78Ji`!QO$NY7>GrDgeqfqpUs%IFIs* zU;32ef`m!=yF8W=M%N0#!w1C?o)DBaPOWMPV6)O3O#x?q6>7YGGx{JrhJnJf5}QJ4 zsp%>mUuIvILI@zj80CUf9+5~GW;9)g618k+u;d9tix+?}s5vvWp=MpgP;3-}nK@;G z98+eH#1WLqRT<|z%_yfD;j^5?lZoIWP=wUj{z-~ojuI^i90VjQ2Ld8D3ZEl#g(Ac- zrzu|yga$c4NP=Rf#?UsWAaaEgn<q7JL})ZY_AUkPa^|QxWoTE6sl}7*?blZW5h2&q z(*5wm4>>ZMc%i0Bbm~{4Ud~HGWrBFblSEE|NysQeZRF6j9;vp5qvLzu`<~maY4wPd zU1A7DKcov8;ky?e(+wY@skI<eHwt_SgG8NE3h|^|D6!R+YtJT7BoNq=0O?K<%}&Wq zI&q3Ho_GE6p{p#c;807<Q3D7c&CSgo*Pl+Qufb6uiIqqiWGR!!77Y)Lnt|}hXb3`Q zfN(cZXn*sD{By0u>7)*rB+johsdR=$Sq@!{cm?)Gc`<Z0Ix=3rwF>I+dHuHIvEh;7 z`t9$Rcjv+KNC3Jb#|Rt4g%(dTK0bIZpag?5s{1GDvqUb79HMV1WON{H^QfiVUFfE^ z4d(Mio}sky67vk9$WbwE2X!(UP1~e796Z8k3QQf`$nhv@MirTYb7=r^=`p0lx{;Lc zOLtPpkz%Jf!R#G-vlYG`qtwixHU~0yym&qu?W>W~dg(nr%vI1v$TQTj%oZ%oK+zAQ zn44SmM-Y;Nb%mdup0RD=3j?MLtvpG@=1KD_fBw(G;lkmAVI^`8I|^%SYf?}LH%4;c zdHLjyat<`X@QW9r0#cT{U=mv`u%SBE1dNxCFoXn(5U(r}0S*%m$@tjhr=NcM`0-;3 zsgGdX`h?B<?c2BEyTqCfuC;gW-~QMC`d>37^#1IYB`@YALX}0zi&R4xGt>3h5{%&E zR4|4d*W|!S5*1|%JME{7rN)GU1TnI6&LaxK%c;v2=0E-?|3^9d!ZiH1|IUA!#bFNA zR}fOl=~jEF-R${8B*>vD0%gjSC>C2qv}kn2jaY>t$!VU~00f7*LTqntNsnuJMiY}T z=%~0kP#wkPf~Ey0DiKqF6GL;X1t>_Z(H_J2MD1<Gl@UM)x@@_?&}1l6Ed}z~nR$#M z%0@*9kOE)8NnqkBFmcS0xb_el&8#qifJf@%y;tOU7cx3GTYuM{Il_>jFtUJLsF$vf zjt@qM>u<waE^0eJzu=8g<&6qS+e%gIUI2oZrl&GPX{Kl-%BA>_TST=wIig?jkB%-b z&KqSb03jt`=BCxg$ZGQzA*7@*bXMP+Wo|iwlBvWwq5wxX#e|bd$){H6AQEy6e9B(5 zoDozWJb2K4yuNNTyiiavGpqF;BC71Y{xb~Z0-y<bda7Pl5w)a{t}rA;P0DfI$~Elh zSzKBmF*SlwObVHCj3TqO|0x@-)ipeL_NQW8VCZP$kt6BQPyI<Oa+;1ap+0^3^xnOD z&!0cHjK#pOLSa&KR=028;Yi|fVH99O!lPuQP50^3CqO8OjbD7?aZ+azlMzhd7-)E8 zNL0xSxGpq?VkYl<3TBReazR3)1BWBU5hp{+On}fggJQ!7KqPWcHO!Y5FHQ;!;jlsp zAjv}30yi%mR(&efwhJ<G5Kx%3c{8WXR*qUciEASKAN=44KlgJ#XSsguYhQC-^CbY0 zz%-g!78{SkCQQwNKsH1_fWfDU5|3?#p)6F&!sAqnpjoaS1~v#-ts;=y9V)4ApfW+L z?YGqOf`AZe)8ztwkTGJ$C=Om=nKdaWI0lqu%&&Nu1fQ}E^8WkpXGs7IK7Col5h$?n zNJ2+Ely#|*q&|ua3Qx#IO2>;?Ht$?>p^Jh>$N7V&sZB_|R&k1GCaMG`3ku3efihvt z6I;TDW0YJ=PKTyh!_YKM04Zx}LeuJoGPw*T2q7V9;jpF9ttz1AT{pGL#>7ZDF&E<H zWFhAvd=$WhM^ot%7&Q99M`i~vskoy_pMvAUI#E3yQ&j=bF)D0~A^L_$%(xYmNzsz? z%N^=*YEeSfnz+=#P$GoM79dB0)N)Pef#tlSR;OS4stslF02hf>ttCv#8Kq{lmxU1N zqAX4d8KMlCJRb4pom?bA!;p(s>EuF^qym_Xv?07Ydyd#>j#;+KVkJvTcuXL3K`sFL zx|nQg0q_Djhk#^Bm{3T-coOe3F=wmGBU=(tVUkN?qeC)1RlhyKC}m8dO`7t8Op;o~ zJd+#SL<kKTg5VjK&yE>&ws;U@c$b})J}BuV7?`1W3}7NeJ(v&^iL>QP5%>~GieU7r z2_ngPYm{q-z*P@fmI)Zqr^#cy#}*Slsadn?fM*MhrdIvmc;gMhh(Tb4vSVcxyJFcg zBmw|pqS-nzv_a;vyDsnbN2CV16GB6nEH((b^y8wuw36t4t`$jK(81`E%N;^fs77Hf zi)4|QSsYU-*L;%5AP+tonPtPuC{w#kiw~eS-Pzgts||=|yvH!}!kIRd9Lb{}0#%W< zzbHmI$wnE$;iZf(i$<A{7q*dqjv#~ya&VA>ba@}em^M%;O5~I?nmSa`FYmX4nQN~P z^kX6zGo{X{47J{dv50~IFeV7kOCIqaSe{MRjJ?C7_ziJnz0tH>RfZQX9Jyj3(Up$9 z$z*(N#E$#Ym%jAf?|%1Je&tub|NZZ~NH}2}FP1$kF{EO^1vxjrsGDO18ZT~)x`z5O z;w%sYh0-}aovL3_ZPqN~`u6hP-o8`ZY&bI(7u^`2OifKcfBx*+wd;}v2*IOPUeFwF zkj3-bYp-R&WP%K}8V|o*t)p9}2~S?s=y<7?sjf(zB<^@_NA}StA3qc)1f$+E;6z7l z)l-_P#FnzE%4>3_>UQ_;T{rf3-g)PTKm4J)qH3!Q;+K^=q$?8dM!*5$VG4-?7jM7) zw!p}#IkesF$!n9gGhD#<pb1HAl=1Y1;Tc4T7vBH;zx)&UUz~>jv;X{Wi4P~B92Q(6 zYr^p)C6h-^lCB)0DTt(}MQ80RWLHTV+JMU+0uw1QPliA;WG1X&_)08ELa^v6Gd^BV z$Gip6aorT5A@S$}VQ!wd5Tr6WR5=ouE_WnZ85V(M#L)av#*<rK`}_4>FCgNCW96A$ zZ!cP15yCM&EgW0A_K&!z@orUV@rKNkyE08^@B!jQvb40EH(~L=`R1Drbh*G3A^zF3 zXPyMfg+lx7;%>n8f<y-|23tiJrWvsYc)@(|!3VXPKl$X_zwwuBU}gErSH1#=kUM!v zhg#NmmRG9uV(kUF*%6_rXhtW(kh-BtSgQ5cn`^$zf-;hboKAKZ3Ctk#SW9-ao-`6q z<s;Opzl<0{z%Ya(K|{i$sjJ#rJc%Kd^gby<-Mnc~7(TB*nEcQF*+2XBU;p(i8$uHy zo-9{Y6)h`{_V#z?=I1xJHlUGk3S3~Rzl_*gPVhmA4cg@RgbAgfAc~+$&{UN&e3-H( z2PjR3=O+~^9ov{PSaL0$Lc9D94+T`2UU|-82!(`%Ef{r+L@<|7gN+7|5K$0@E{1DK zaV>qM)K<~=zW2RveB&Ezg>A@s<5&C%47e(3@nSgIuMhw58>cWcWs2Xw00Bg7)a)8o z9PzH^$<a`9<PI;Ml$TRDZuyWAWI~biq6^ASR38B|VQW+YM<?n+gLJz-M?y{Fgc#uB z<cMEug9NV{kh8G4_RKIUPE!nlT(soeF)tsjjLITx3jnfsI5Ntq3NXw!#|TMy)Z$4P z0@o^?7A7?2E?5|00HKxzU_~h-P39&-%c<6od{N?|AV~7umLwG-;UaAkG)ftG<<Ral z@`9Nv(Fq#l&GmYYhEh5p$RzfiLLYCzd(M6Q@KaU^j~7IlVOCL)K`~TtL|NG>sDRNv zI}ikbNxtTn8Yt7<BS}U8b!n2b!pC(M((M~JtwT_DeS~z_;stC?GRM<QV7yqa3QH}T zh}`@df)h1i$BV$6pGiMxh6phfWR$i_)^;2dAPJZkqh=vzg%}8f5CsxL$twy7T0%;u z<aBtXFLJFg45?ePFsjv60gUtCT+_*FXF?eP<T?Z&AT?;@)Pzk36iH>$HWaj2MIsoa zONdcwR<-~`LXl^RW2oB^*pidPo%*PW7%JQL6lTtr9MO~)WJ2Z=5f$DO?e*7Rr?2bb z+j1%r36p@J<(2xRKoH0&^cbSRZ%h!zB~Mg%a-$fLAoXD@9=5tU9tmw#0T5<#O(kT$ z;HW$%i-f+`Cfayan+P#CBlH>O)J^W>M)6vsjv(2=;XTM&Vc68pF+5wE$w>QZW6f<u zg!G+7`AQ`@@4};l@Fa*1^UfQRJJ+%nzmre^xuu94j$n=s>(~S(BYyGFq`)>f-H}oJ z$!SGG0#j-TPA<gIfIIMY)zFR;?fzbU%@p`YAARH!%(WN-2uIf{)rA9GcXqDc(v6a6 zfoqu<Me!S3@nDWm2VdFGD2gUSF;K%03XiZ>&fdO*U005VcmYmLgmrqicc<vX#MC4X zosA5S4Go{yH$E;-Cnu%_xwm_8X7KoIy#6fiBpp0VOGsdF5Rak-2n0A^>5{86d|jJ{ zRaQ>UaIP^X$b5kktuU0-klLy+L*Q(cD}`d)s}x~^=L=e;&=yH^SC3}yr~yaR5QYgT zq)S<s75%OWKQ7?ViT<_4#r=c9pENg0m>l`#h0qY?BzSguv3%o39<>%KiKmY=Dcg6{ z5?c)Ih_<fk295+^LTxL{NpUh?<XP~Rw;{1{Eda1Kix)XvL!b!l-0XT*lEN^Y7<U^S z+y|sXC=6X?*QKBvObQO0>6y9xqxy*k^2xD!_DzgcO}rn{xwf?AX)-@E>zO6a(~I+? z<C7o#=tu5`J3Cw7`qsZ?27o+#_=)m3cU=&?q0i3FTh5NOgM+=z?M(qIhzpX+NLeJp z_{mRx!k5Ies)b~cSipDh+!8G!Ou$N~OCb`mDV^3330|BOsI`o0l@dDVxyv%+C5uqq zE{5vZvFcRMb`}hM2pt(tD7?kYHmjY27Eb~^5~VZOW-W7SC-cIii-ChqizhLIbj0aY zvFv%bS|I%Q|KtC}>WkCxfBAR+3*nl@o<>!%eeYfsFg3Mp^C*OFmX0D)W)(v;HBmn^ zsUp1u>6$0z(btNeTy^BuCy99u9r}hUtQO2w#_ht8DyX39TV6^-u80`ZY*cK)*Y54r zN9=+L1W!4&CeiXvo>2w0is&RA-E0-e&^nG5GM%HNd|#{HU9A{}vdXgqDPZ7d=Oi6P z_~}nSF@O2Cwk$sW_+y%CYewln;0rQ|t_|3NsfV=Gz>=%0t`yp%WnZ$XFil}B&6l|| z#i#(p15;JCyhF(D<y2J4esEluC$Z(sYWQ{5NFT{G3}I-d{w8((dTl}}^G@03bVnBw zWU$<EgcsOp{dmmaVW|}xwG@*AVZw-^NCJYmCZWJ22{O+n=QjnR;9<n|AN;`|eCu1^ z5(X#*7ZQcc0wM$gaAI=IlXh#ne)1{>hfIyKxd5Iyq6`6FI{Wnn8jc8&co0C!SL>OD zf%gKObpn|_1vq#U!3#s9y72L;y?1#vXOcLzNF5>so0`CZW-%lwJT*{=6$u^S_&f}l zTVvn+<~P6l-S2vnv0p@<#c469A*SPSAtUiGFV&Zm(&Z7LR+pO9<uDR+))MCB%a<4+ z5EN6(udWz4Qav%S6(LOFsX)q0qD!A#j#};<HEe+kgI^x0jZId$D0fZfx^S2y;f2VN z+~IUz6xu!-bCN0oUSL)T1)9=HV9a}|N$4}wB}{gZg#=I$2;+_dqK_mlY?`qR&*Y;1 zgkvEGA!=e!JzYcbsH-(}(&jhj80$p(7LT<}K}|xuuqDw-gib1!kO-MaL6-~NSRL)x z_wYlqNQ)?|nAVQgH68SwMXT#;tnd(|U`Q9y%)DU4scoL?GtzRTF9lr;7ty2!!4v>d z$tq6UN6-vWqeFp^0v;xc90EY?>{Q*Pxp2PeBDVBV^f5qCguvw$??!tmv~dbS8xW(G zMCvI*L@j>JJ2i#?wILGVVR)nl1eDZ(kTB;o3V0-aqo$isw?#VmGE+bZWoPd|vloPv zwZRcdz@wj;vae;Ay#_oLpsz)7p`~mz;6_2=Qvpx`#{)-Vg9a86CS^FfT0AcpCL~D^ zuSJwefTQSyPe|d()i#>=RG5Np+(`;AajmdTiaKPp`;Gp{=l~PJCk#cu6G^MbVB1m_ zYSPz5V(9Vc8ciu|RV{rbGL*F~0I{X=3QLkzZ5F&h64DP^kOgD8S`zpcT~TH^i<xa^ zM@W?Ida(S)7Xp>ww|DBt!QeQ=oC#nV(qvWXwF(a$G-6Wuw+a{%4>ZEW?5PI|FA^&p zj&~9SEg6vrsYGq7vNdtJ(g;#<78dJz3PDs{xQ0<<LWenUCZ<oVVDd6EU0*F__>FIT z!zG^1AO7JVzWeUGi3b7|(K6H)U!Nkb8X|`L0ym_X$p}^2jqs=EpWQSVVjv?!eUYac zVZ5|NfxZZt;CZq2v~gW(m+z~mXZ38tL)Psi$0RNb2&Ruvtq%6fDc6XEA)&>iP?W_$ z7<?^F`x`>e2Qei6tOpgQW16Vx%1Bj(Egl4lTnZ$tI8q`ypmcd>n@vZD97B@{{OE)X zX`xXt<ju`xRoAm#kok$oPe1)skYezFAY_sWQu49U3L~(Fl4Ir~Nr^-^a%#73-`(8Y zGQ=F9C!Mf$=}@2sBrX_odgsn<yit@;d$cJ6HL#K;$3UP4*=t+gWwILWJNn`gSWNJg zhc3)`eKid}Oav1GeF_MlbpqcN_4@LSo&7yA>rS;liFbNjUl|lLTWP~N*sV{QA?tZ~ zbYgdZ&qTPJ<%>{uioCdnNf}dNv;*PraR2P$d~vZpu_$su3LdfmvOZ~QDYF$bh3To! z?n{Ev;t^jIdhrvUQOhX`Ky*1u>6{F_AVQjibP9i_swXnlGfh#}8p^zAnRMc)hXGBC zCrRXZyT)F~`2fn9Xte|3BClOE4KdM@tD%jcXq=M#qyP1PXZ6Kt^jH7<uQ(O_lZ0*L zpUKmm^(5xlYH%)?e!I)V!;ZCjB=5u#g}aXY+mN$G&~{>Kp{+yX?9Bf0-sGQ|+uPf9 z0=kl}uGUY+T1M^6aXpf@mxQ6IscF;U;nx4P(CT06NE^7;q$-UBbge2aO3}HdP<wI= zf<>GiRl8bOeeDXx6_TCRrgKsN)6?~7D^*r~P!!a<S6^aab?NI`QJGGoOwuwJ0DQ`Z zATSZ9AX(kIb(@a&c87=nqF`B@bu-GB1woCz<)w_gv<a%s3<pCJ#u{B)due;TdbPf= z;CbVrKC-v7H#<FJajE*A7ZsN$3wvnz=<sM{c;w>zg1n~5>2q>oKK2g0>1CQ6#MZiE zO0(7?G~ubCz(DXT7Vo}O6Vr3EbE6|;$4AHYOSy+fXQpTBSHlmPs?qMH{k}xPq0^I7 z-YpXH1e3Ycr93`1n35?Mg6Zj3>#rK@aa&ilwAlJLKR56Eo1U89-`l%+<L2s%Rs8JC ztT*D!yJ|?me%8fgg{Y*G>bfhm=ky2{FteCBIzKxX27DQ{kZSRhD4@UuZ>CI>xiBy0 zRHR_7VH4EKGI$1?ogC0NSL!Fd9f;f!rhr<LZo%i+Qf+bOlmt3FRLfhrywo2Z%Gp*L z($&_#iy?)rzsKzDshw_F1Cl~n3Bo`<ByvK*IJGHAK^=6(-~p3muezYLK}ZS^=G!mA z#RQFEQYI9+fHCm%D3vCLCJ8mJC51P{U4o&{JTA0`x}5hIiYE$P8AGl1PKk?{kaP+H zbA(}%Qo}S^T9G6qwipU|tm;yWEx9f<X=a}$BoehUlz>q}GNb~*)G`mUp`?%?BT09( zR{Cf9Mh!(jyt0R~eoQlW93@T+9FZeIlE5J$N36mV8UjcHv-^tcM52po<u^?fC@rGK z#84!7u$C(WT|x?of-sOF0cYwngt)dOf|f{Pn0#RdDzSB)tD)*5OwRDgLwMfBpDE4+ zkqgF9>JKp02!5b+p)tW2O#ld(Q6}2>!sJeg;U(e8$Ymw*ARvT>r0+}!rY?f4t0l=( zTvw~hggoiABx>QQo*4&%?4#I54F!`eo;hOG(*zP7abgsK0yJ@!aU*~sCUCgplwm4H z$V8Vy^zo==SwxvavWO0$tkVqvNo$Bg_y`;1;Oj@c69Uh&HyV6$Dew|2WR%=-efREN z0aL>}wWJwvquL+<^n~cV7Eb|S>d?Er6@QhrIqgt1^T`fYx}cOuF;`bt@szVSMQao> zM8acElO%u`Pdq$%3~du_f{_9pLG}vJv9vt>@igIkS`k_gPU$)g+84(m7$Pt8ws*Pq zyc2^_uz3OokcqY;xjdK3piMU-N4i1dMHi0*0Azk{@S_<)qX~gp@bUItZs808-nhAv z<-|ms7#An6<pLHMW!uMFla{>Ya`Nc$!*6`!>;L?p|Niys*G|t)-hcnS`T6=7ofijl zc<tKK_=I3~bSEb#p0BP7S13wg!X)7O_+oW+YI<5XL)ImE{@Li_?D;0<q>!uyugD@H zl*L8+JYD7}n}|ssktAtlkqTP|*O#v)5$V&%cPluq<}#&5=vvQeXS=>w?3SDFNkS79 zcQBDI!w`IOuB~x*Q3xcSOX4DNXEw2H>(>R>YkWQ5x3{<M-o3*_QnPOAGxf<4*&$A; zfmLJ!BJ|!Z29d+mmPOf2E50nYwl;H&nK*uV%*nm7vf?gdm)*Q6i5qYz!1PvZreKN+ zp!+9qdv<PiX65?w?OV6~b5C1YURhaQPJ7qO>#bXax2WE@xvZ3ct}ipU!9@bZZI)Nz zJ$?F=)AsIQ_sO+xUlxxonfE1c5H3;fRNgEIy{Oy5cybEvJa`KK>R<h<hYueba^EJw zL;m>Vk6ZPMf@aEE)<dt>*LJpcwl=qScXs!7_q?+3e6WA$id(-yb$rrI%+=TBP}l#g zN|D)*R@X#*4F1CFFux1RIyZNEbbMoFMM!qU$<eVzyRo_DlDsg#&`yC7*Xed=9-f?- ztP@Ic&4JA8D(EhFG*j!gzMN;oYB8;}JY3A3#cUDANSl3aMkdDUV`LVP8+DxpHnM|p z=t3GthxIF|b4+_1KJY3&<z=BVp)Up|`RD$c%egl3xE0%LHlanudv=5}^3F-El@<vG ze1cKW#FjP{CPzSWycklwoQ=&)XfD|G13o6bE#rFowXI}A->4id6})%1-}xK=KFlvp zqu=~fUl$)wVo0nU2*N&0aJqenT7uSwiLeD-pA-sc5{^9kUp@e>Z(G#*unFlxphl=o zL7h9XMPYhtd8ASal`=UdunCWO%IZ-iZ08|ivY@QRBWePR2{c5owY6iPWWsDJPX(GJ zIk^b?89{Dm^2-V@HNjKUiidIotjCYt<#3F5Z}^05I>%mr{dH%PN1#n;h};2cOG^ZZ zAva7L;%eo4;&`rYU5x#}g?x2K&dW8SAVnqGM1p5Uh)7^+PtPpt^Wjz>^0;7vBtk!q z$V2#xllruz2zeB?IDseN=)*Cj3xuiiTfvR5;FAm2(vJi|7M?bN8Bz*_3E`ubTx`D- z(2CmIt1r983ZSz_c$8JIndX^MRPILVqkxueYS>mtg~Yp-g5V>RK1pAh_*Ru7*&*`S zYVmBfy15JExo%0+y+2Ua05#osiH?M#W{9C7fC(?i2m^sKr1rI;!53Vk97l@7yy?{5 z)HNz=i-bg>;+m%QW}T2H47o_(C|jBCwFM6fa$DQ=Neb1boSM+5oaMnBX7)%@P=7o_ zZI53thI%4Q_#%NBzx0jjA`0Ot^Ws6In@AYOHu&TS!c}}BWmMP+7?dGaK@LbFK>-YS zil&?Fx*<MO!wXG}ZlE9}0CH*}l1{D}-4S9%IkraQF@T9Vf5r)qx{esE+ispwBv}fq zwEPB*x%e%%ATuEmUg+qcHUeSdq!8DpK3QjeX_9-8&(6;=r%xE_CJ0YbIbV8bE>0%8 zhVX_k@G<cl3G*li9A*fgm>~qSOVnYy{n;~zEx-&BV!B$qgby*aB&adul!C6(bxkqI zH<3VgbYOB~=o-=`!~jWP**HkixK7vs#K#MLMBfmC&zvNVr~yIHjGA9U3`2y8oH8OY ziV-;>tHcv!3^~RS7cq&ikWpw5=wv8SC30P8j!ntp69%SX7wJYB8D$$67!>_1p037S zD5J4L(b2_F%Mzld8%?lyQ3)wJR&wTx8ikmHN`hzS^?XEx6oQE?k0>VwP*Lj?ciIqq zuap4U>c*p^(z}5!O@R@jR8N;2FL7;iRcNw-5M{wwMR><AG^3(&^N|_^`eI|N?1m^1 zW?{oj{JbO8pumd!+V%Qd5+ttF6tW8vB##udvY?Y7vw(TQhjbA&=33>ojG1RK^9($Z z7){+Ugd`S8_(W^b9vs%^XaMF_UnJrLh3Ax<M=8?>#g+m?F*{rS#lQI8yYIg17C|34 zeYS{#*tF>Gy?d$$ZLR%^Aamqp2_T7>nZVTI({+flMQVGMvWk!)n(`D6q4Ok1CBLE- zCk3PKRD`h=hSsBPeSQ7r&0AKnR|zklXQvll+q_PmUz~aAuoNHMe|=<hcy?yq3m=`u zg(WvSfDFBNx!S=LycGCKg~iOB8VbN{@<qoeIYT=1sb#upddXx?2mj!~gI1)$TEftT zV_v+hs+HGQi~=GE3=Q!@rxw=20>23J#v5<kyLa!-ojcn5jX2UJS1wRy3Y7Zro4+?E z$X4|_mtexF_0WE&1|p~I=73b#8>tz$p_HPNi|@(t>H4d63qWzK1oY_9BXeyuE7L@{ zuCP^qJVrMXEpT4!I9K$%^g;lY)gmy3szu)@RYiTG+w=}z9SP~2v=2V$;-lP5>znXQ z#Dg#)oHxhwp~2m0CVQ<JI?nL?DRoNZMf&9QWOioyqJ4+SD#~6Lg*QE2rxza6_O6hI zy&6+-cx5R9$)Z&Xu!-Lg!lR+#^P~Mk_X4{E)j8NM30h%OOPtvSN@veHQ=@D&`VDXJ zT&P4YFF#e2vC)IQ106z1kpss_R9gYG(&=h-DFjfQhFD1fW)<|ZywnmQhQi)K{gM&Y zwwz3{G|eMG5-lB?Qn0OLA*tW~>%R;6i_`Fb^f&(l&Uh7*h!c<j%U#7~!o8pkkte-S zB&>u*M@_X!jFrssB$AOHWkF*^4_xLBG&4bB^MEx<-=4RKDFCVHt}t}6Wa(fK5P?yE zDby5*5IItKw4S2IoDKxSY>!%i?GptI1qst3Zx_|6FgItrGI0jwT2GT-5z0%D4X1tA zezJaI#~C4JM~MpXLfH^~f$@dt6WXNjyz>qrOi_u!5Eo$8-+}e%r=JP~pg9Jmz=DJ$ z0AXhqm^%UJClUHWbv!vYuFciQJcP#=kB$S3<Bu?jt3wjko}ASW&Yca_yAvF(m|Icn zb2VD}sXXPRJU3ZC>+9$dFl4S%lhmIMD=xJ7{01^Gx~T@jgt#;Mxu}3-lnJ7MSSg56 zSvbTKrvf^oH#h2M-ZDFc0y7cxGodsYQn0#oPudSG?eEt|w&+MikO*uNjNe3pmzT!| zs8n8St!k4g1ZY|j64KZGqwoK~#NE1eD`7z31!m4HLDEd(Mwtwc4sKNBil7Z_+=VF9 zL>EJ6U>jsj7PTajQRZe7nj-KBfp-g%gq$!6&)T1q#1!D=CIv-^wl_9mk|2g8YAb7M zpy;QtF;5KE7+zpPwFSgujzrkQ17(PgE)(XMY`S!LArT&YjMgZ|EIeC%k<BQWY=IPq zEe4T9&Jh!SDU%=pQ?LNI76V@t;3ODBB$;S(=DK|yX42{K#a1P$r5e<bA>Du=CYgvN zD+MiDUaDWkL1+|_BWfIJNw@=o*P@;MTIalHvf`Q}Aar7j7^W4Tq2R=|HD<NHc<~|% z<aA_>bYDDuh9Mz`#tV{^lZTKm3zdR>4a&^UFV*j22+=1DsjaLriJ^P9RKyR#D2X8o z<Qdf_O+2Ssj)L6L*g{Le$w?3s!Wtc}3FQJ|C}dKEEpZj20|y$02_8-`sbyJGQ{luZ zB%0#HaBA^TFzSJYv8oyN#ehegCLLr`;}I_uw2=evW#LzgCsFO>MTd|Hp)lyA0!GC{ zAxxaoOh%M3;t?mFB;XjtJPcx}1%jX<YQg8uC>*w^)v_K3Mza_wt7<^#GYpZljXXn4 z=xb94Ow{NA)S4r4CRC#+qgh~LNEezGpa3ZIqW<pR+U9wXV9$kq)Q(T;>lD$+5K4|( zL=%tb3kg02%84Wj<l3wXH*by{`-INSJY=Z_!B8B*A*YklwL(_i@)2UyL(n`~EK5%W zON${8`q26T9xIX{BVOoal=p-|zb46bWvcFi?)M%s<aRn_=PkYp)TqK}1Pww3^v8)i z@iWYIMGVxqa8KCUtS>l<Q`n&B7{v&qBa4j=33|1$#uhOlG$d;zFjFj4E+DgVt%C0* z>jyvhfq=bYdDWrw<jE7eEWZ~}(P&CsrWod1JA2ob>o;ZE;PB~?yX{#2e356%^C(#{ zOivEJ@J&boku!9Z@krm}kI>TM!s@!VP}eq?V&j(tFDi*ASuGco)j<q&fY>EoTBfF^ zuU%v1eAs{b^qKbV-Fu$SR?6byg3H+ae0^`fqG~_YFFU2+PB7e&3ycdhE*%Bu%Q<XD z1aBy3X&z@r$$1x>jB+~VUPlw@cGC5}%_E*i`drJJGND@GvmJP+ERsxgb_Xi~utG7R zgUQ}Bgb@!b;YGrhqf)3(5!PV~M;GyhzkRztx(o+qs>;jQ#Q6H!#{S`f1wfOPg=8fI z7Y`iNBT0_x1CToe$0#8Z3B!Pp3kHaNmuCbMa+vh-^bG+tM42RYFj}7_xU$*_L(syo zHH4{{+`|v{F6twE6+`{z?=ma3{dVhEnqN@u`Pn%$ZVHZ0>hDt=p410_ED5CpYnBB@ zIetS4%p;+Ejr_4ET1u^A<*QNoYq`{KAg|9|R;_~2Vl3iI0Ni1WDpY3N=?hbx2~z}# zBmkO`a}B3FjgDNL4<EPBrDoolXd#otSDUnYstS?|ab_r^owtky!x0^e8DWfW?$l?( z&6>4st16cQ=9r={U}_HMH{X0yS5^P<KlwjJ_{C}Tmw)+Bi(5cC;*&E^NS=5?qe^24 zk0Gawsk*d@iMbrKBs4PtVbsW!hwP}!6LWZF<pzcoFVbTO8Cez_HSEC>kGlxX9|YmC zRcJ$O4Qc5pP1NS*YPUD*iW4mFse59>*g1w`F38>8`ceB#9wHBMWHg3Ziw(1$WQIUV z3J*<e9JRb_%C(Rw6Kdz?>hm*BQd8~$U>_nOfu+`qfJcO!unJG!idJb_oUAxyVnK+x zw$}dM!u<U9_TU$UT1h!gWSuIBCywxRfGg8!B~(+)5n=TCN*G#DVy>s$%<TTo;Kzee z<Ta!1YXnhF3rD%^xc!5A+oVaD(utv!Zg9RBjTIfPE&Yn7y^4q#wer^`PdZkG=Ycu3 zJ@6c;t|7{J^97+5XYhhVq5>2YitzZPUVw$cDUZC+M;N1*F%Le_B`Q2Q1ZatqBcsq* zWpcHI9N`U(jSN0O#fx0b3rCdQt5gXfUn1lSAnWt``+<Y+1u+4VDrsBZwHPP^q(3_1 zK~-PjqZVO85*}pAQ4@@)xZ~HnP}VA!Vwx|?Z@lq_>j=%twjExHfx^OEeZ5)CKuD4l z0!~gy6QfI+i`atVOE9S|ImQqiwm|6X;v=DnL6k#XPPuEca@tBtvgG0s03qu7381^f z&?liUSvtwWkRs4e@STYQCI~b`;aMdlfHWb~On6AxM#HNHWkVfG3%UIk_bOTdG1R1^ z)n%UCDWh`NjxTC#sj*_7Aw>DJ#n7lsE<sWsCc0YkknpteZf!{%@sh$))+PYv2$Z3W zsw_ijKxk_52!fVo5a0usJ03EjQNox|1D=Th8wHdwFo`fO;+hFQYLQUZ@&Uxm;$ae6 zYz(s+voV8XC<_2`r=&(lcyUdFbOkT>R7o4}hEi2%$)!^iVB#yvmIeK*LqSH(d9Bqh z<N{#|tL+hf)6FPNPVqq|2{<w&cij-3w0%^UKAlWT){?{p*1=<vO5)|{WS|LwU-hJu zlrh?#6sxPm3!(s4H_CB`;AoXv%L{^o!Ur6MM*=o#Dm@?b8=gFMjFMyuqO5H&9^Zqt z6fcxLCJ<#^WQZD*gxZx+n5gAx!b=dcsAOa)mB&!vH))c94NiP%3vHr)y&?pB3$LD= zh6ob|O8pH{%a*ZjJ-#`G%r8dWZrr$`n<uzX1rO@vw7!*Uni4ZZU2+o0^!qG;WtHQI zFoaiO#5)}UPy@vyp_m=GFahG3Q`0hZO95qt05_UYbzgh!fpb-~5~S>r2iC-yJ_vbJ zH40O-bUyv`6GJy|-hBT2`CD(j_4x7Q2M->&$igI~oH^nSnpcIj_4?Z%%-MSAW28w( z0HR9pJc>;`JZ^4mC1tIea2=wPH%Wd|QUq$NeTog!XNO!c2*V1AL_DSgJ$UfiojZ5m zc>S$+-~Gy$-v08PJGYmw-&nb^@+*J#&wulqf9k>g*WY^kt+(F%()|bbzxLIyzw^$Q ze(@K7(aSb80gE5+?*7g@?`Wkj_q&bm-Mgn~E^-{ng0fadSy~uH7QbM`?-kl8-lf7z zf^?K!d0jS0y!yIWDzb&70&8n)Y!!sslP6CAVrbe~M$I5Yt(xm1%OLAStyG31m8qS1 zc`ng33ry(Hrv{2<phnx<8cpFb%%(tuH4W`0nI>XrrP_ivvvmlcvO<{x_%Jc7kdU;Q zP{a!y3UM93T+olNL@R(Si7a4mVidCAO#~dHB-Emer{?vQzDTrL5<%mFuQ;v!llzkA z!t|8=Uq3F#UE6xhI5mS}o|&qj^<7+8q<{PN?b(^xSKAu`Y=PC^I&m{HG&fiKU4eOY zz!+6p^0SLGCuu4vo>0~&@GkG|$msCme0`9IPLk3JMz==W45nzznY7(qKh(fP%5)HY zJWZq^+TbXKdO0B7A%LVZ6ruwyOb`rlfwEych!&r2NSaxJFzIsvDr8g}K%`5D7wHHX zi0*fOMjwG5{#*aaf1JqD7m5kyz=jl}(0T0<hzZ{{Nhk<WxRhf^K^<d40*4jl3{mEb zqG#pAczsP&6{z*{MJ=R@Fw_o@>L>f{Ve3ijP;h#hNJ6#{#E|_XlBK1E)zwwcCPN9k zXQARW6TcQd1pLxc{caV(P=iAgSt5=M`gE*RPzh2tJbK<Sl%TW5#E2)eMHw=NUld=v zyX99Hz(4rlgZJKh5B`sS^rLs*eHU_$IrvH^LRM0Pps1qKWlP_A=iT0B7H1_sR$plM zgxFl)oST{3-K^iF#oT%NqW$Jxp;AchsZ1v8eB|6IczQ8-wWgL*;4#7wur?_WYBpA1 zEiGLa6~MevC=O(snIScjo;AGPz3u7g`o6BP>1!!7p&*RR8ZXHXEZcw(sx3KKBy7hP z1XWUGNtqF&V?$MH!B`KD{*{%LeBFq7Kp0A)1@C3#VzPb*{opkilvxmuDFZ0B7IS_7 zha+-0h7u<<u_2}Fl>|bcA)ZA1*B6(V=eQ(i$OUjOoHPezzkH!``kdB}0MvoPJd4VZ zE<WprK6kNVw|}rJ{)9@dCDm0@F{=!Byb}sW3jt=XBl0Eu@WT)DCxT2$kU4^YxSnqJ zM!_hl6pT_!ROD)I$P#s|LwoJD*Qg~Iqi_gQhoIp_m{N;`oF+AaB|8cvh<*YFXb2i} z?&jJL1<{OhY!O&Q!Z1^ubQE6^RDe8}2@<0idqLz@5f^N!sTf9V6xh<?G}D?dJ?g3e z9TKinE79^R9#)Bp#91W%#6u@0kQe9b<9{^Sk{G2-le>f+d14U2_*Cr<iAzDWaD)L+ zv<!7q1c8ClCc+dp3y)3=qd*^T6h22|t=^HKB!bjLOGmWu6%!`p-Gf?7h>0!}JXkF? z=7gfwWhf(gA<D@*F6a|-ApnVFqVa~b2_{MD3L`Oxso<_KXUCP4Mb0n4<j$`G3L|S3 zIARj-hL{+|V}P(?LK&}0l)2-Y(3;VuAYh{;6c`GxQ-iPcku>2TIuOV?4O(=17<dxM z;YEUyF9nmHim}b8fYr*n%G8U5a`%;Of}sWz2wMuN8;ZLK@v`u|kQ4?bNTY_B>rx|U zsGi6M4>A|j$m#1QY!dQ}G9*b1hy+ni*20c2yixAbX1-YAApoQk3Lt%3)$yw=)-z?A zNk<D)9SHMFuo7YXBBOF4?<OH#R-7hUUPuyNKKA9HhDk2G6x>S7gQk}C<>z-e>eRE# z(D~Vruz}?C;Ep3`!0k=B&?G_7Ou9O&ws-`b(S+yT;%?ym(96u*Z@&%D@#PZl{5Ow6 zf-GjQWDKnki3k9nQUnC$MF>HTP6gTC2e<|zHZ4qDiJYFCi=V!Q$0XmtF$<zi*ujAS z2inbBE0&^z6fZ|aM<QAU^gbp>_Yjffk^0FeAN|^|{p#=i-tURrwa1GeK=}PwfTpF% z%iiJ9n{Rz-W4rzWqC|jrzB9=e3$g_;^c6%qKQp^9SD#~-kzA6mRxrXy3Yi5^k?il( zCl)bMPIhc{O&^}7`alpHHB0a4u+AT+<Ls=9#OceIFAfflyd-)(zjkf$CqMb=)YOC* zH1c=e`AQXLcguvc%`8Jx6Zr~{P|PG*t9)_lkt!F#7%~Nz1cNb0(s9Y8kB6WFR%~(< zZBjOh2qj38`1vA)tbnZe0*j=~5nF&XqbyDU&p<H0?xe{?c~zc*m7ptlP~O!cn_q!( zM4ylewY}}F1fz^nrbYpjQRduH)@4g)a(e3Ge0cw`zQxz)U63NreGEYZ!Vr!wM-1Z& z84WRK#VI~sv>YjQ%6|X;ef5;4b*N2JaE!vo1jq9w=@=CcGDJbe@Dz+9!ph5o`|RXm zcqrfXZLh8u;XUA)T%6V=c50$7R5M;uMlN;^c4y~jtdP06nP<;lctbIJS`yiqLm}9~ zwwK2OoXPt2I)gb%oQWsf6GejlAJ+aX*7htt4ExTs=e^H7-=XfUv8%et76*x>S~4XD zhA7K&L=A}_@{$0C0UHWp#1DSSLl6YW00coElK@U)Q;r5WNZ=QP32jTHO^OuRVRzTm zRduWGbnZR#u;+b-{J!;_v-?u<TXWUz)!+YH-@Lx{t+n=a%EQgr&1LR(d1~-tq6u9% zb0<d&`WdH-*atO3CIuN5qcGvdT?^S3$lUD0eARrBEC}!bE~6KG?1={pAeiqS1&VMq zka{qTmTL-)xzNm!p_{qeEkkdb2$2%3B1f`8GRz*WMgge)hyUrH&EEl@|FysRtCXb= zF^hNG6`Np8g#efb_a$i<4#C>I!{nQ+9GpV~ErX>aToyI1@+||zPfN%sWCV0(=J$T@ z_pfiR>eY%#pSiwTs4mRU&Wtamj;q179Fzv}TU)a?<<*#yWV6?UZol1W4SR!HqpDx1 z&d&yayl$djn4KRC`;*~#eqp}bjZ0eED~@``u#jua^QfSxiC`EoJGp*xa(Z!bX2;hb z9UV(e9-2_wqLL^XOeKsXA1)VcQ7}(uXXhsO^z_W6wpy_h!0XF`veP?kiLi}-q0?-$ z@V9^K|Fck;Utd|9ou64*T<#BhCx^$&t4l1eH<jj|(ej<o+icEBN&77T$z+3M@WJ7} zeOgFwW@ZPy{_Om0tKB&|Ih<dp3@3wTtKA!PCzn?hmz_#ge83T_Ys+&|sl_XBDOr3} z2a-(_;pR)DPJ9x7esa3GwKblM&d<(S8?SrK&m0~ceE!AfTbr9^M`~YQ$Gc3EtBK<< z8gi@gwfu$Qc+|b<>YaKNzVcq)IR3kw(9s+8$MJ>d+s4^c9aMMc_-tQ&^_2yXTY_A2 z2(n?J$rqI^3>RQAG2>=I+;gcAg?@2$X*et|J(f{OZkj>fVIk8H?TV)J2c?jP)MDwu z5-ih{25aPyP$v5JO!jhb@BHG-M99z1;!?F%5oZxwURmuAdQR`ncB4|QnSJM!cBifU zUSCDn0A$N0rOdKhUymP$C}oXsD`*hYa(;rwbeJGHz*^cVWfCuP(RtJdTRDQ{T4SmM z2S?<I!^F<c4)4nGfEDgtB-r)i-`7vRnw=x0ri{i`VqL|WyKK~(^9!@1;dr4k2R=DH z8uW)7n``Ii7dJCkvomvgb3cVuQCuWAp<Z9zNPMs=#^%0>?GFayk!ik~xtY1XnW*vB zQM18aql!+|)_8S&*1gy+e?OTctl_2^;h<16osT(>8rTBN6-|qog@noaD@vODl@BBs zMGrRPXi^m6S_Tc?9?w*8POF{))ak*b0T5`3A%XU!q%>8Nwz#~cD#lM?#YA86&ia^{ zk53AWuhi99H{O~n&BA=M(P%Ap`u*FF?wgu+JH9SR4#P}(POGYEZu4NTw>ap^qbI8} z4!6~y5W$d;LnM$J=hn$3?d-XponZ;>Et^)o)~MA*9<}+1b=r(i)F-2sayY2vW9FU) zhC!*Z9|6@GfEg5W#Ej%zpv>5EQ=3W#glVNEoXsO%^jc*;UI{`EFDBT@2Ve&$4FHWE z7rf~vp;&!;&DPRdWT}h5v;oGF#{wWq&LH3sQMf3D&l%UyTZZ~{*=ULqmMJkU9uWXA z60VmI@xvqb1uHH7SB+J`s`#N13+Bdu=A~AzpP!w??;eR*%-94RzmKD;T&m&|Jt@kD ze&*&{?WMzUEcWY|Rk=84U$(0r9_*{bc;j$&b!m-<)VZ01*RNqJ3-dMtJ<9lhQJ$Zp zMIZEnj3)ey|H@HlcA>JMX2e~g{1^;4ya~?upL|E-KVI<Va_r1-73Tx_Q}%F_jb@|W zZ1J)1RODX0(a1MyT*mT`mYD*j*r`3|D`PI6(n-R{seLq1!5ke~=)Z``#36RnyXakA zPk30V&Nr2fR%5ZfsNPzAVf8{?WYj7=v)3%Txxe#(-Q&UJynB9nbk-mC+l|i7?sluu zR0UDQC!K0_Ub7sm_h0&AzIZntj{K*v*XuP)s^9MsYZowOgF&BRvN%es_?oOZ?8ZVi zt*w@&F?#m=>GAOq-d4Nm<VDWo$B*{*UcPww{L$mL$T>c7_bBgWt*k^8Tq#`@TCLcY zCX<$%r+l{LosZ^tU1g+y$k61!hAZD)p%>Y`SFa9_j{HL}lo)ZHo}E`}Rpt5RtG$a} z7tH<hi;LF>`|ZWf=JuAEIyyN%JPs~*zJKwDfAH2@Z@H1$i{-*cAAMxXe(Se>>+k%X zzY}?07Rckrk5yE#{uh7o7ry)5KexHL_2>TF&;5<R@vl2v{ra!}^}qNRzxNmZ!Y_UF z(YJr*XMXmVfB9E_<yZdVFZ{wU>i_D0=hxo<;G>`U_RoCpFMjW@{i}cN*Z#_{{ru1U z{I}l!*1K=N>)+1S&Vzdo-g*4agZmFQH#Q$Wc=*mc@7kM|m*afAxVR)eq|?gE>e|}6 zRcSpcjEu=w4TLQ!SFMIdMyVmPE)PG>fy~Y&41aul{NlxnAOHBrpM3J^-0b|bXV1)w zwEX<@&;IC-{^-juzrgr=zxUr@`RD)q_ieaOpMLZG?|<K-|Kf`;dj0sT><0&jSe`$B z@%;I-*RS`{tJ{Rjol;CJ)LGTSxk-q!L`Zl9WuD{4$Wq4=D}qzvOqWq%H^f3id4<50 zHCe$a@^3%q0ybpHSV0_@MF<R$pDK*PYXCGF8V%#_?yk6riP3xa?g<x<z*OV4EVLBM zcz2Wd&80c@#7@#sacmw}HX<wJ<~s2bU*(di(zq7q+b~Seq};`*pqD_o1R&hnrw+y$ zW?HvB>fy6-oWEv}8A&4`Lcu)3O?oDwKzU4;3D=T6)s?U7h1*ejY#eHGRMgoxqKT*b zNU1`m2Ng{GNMtEZjBnP<Td(Eh#4xG{qv86-MjS8W+_m2u^j6nb)kY^dE7DG~v9Znx zt5yZ%B}rvlHw6Snaizkci{<HQdd;+SFpbxPBWGr9wT{Zlk4cSBqqI7mH7eKFkB?5s zg|9c7PNwFb9_FbFjrb|F#=L4q=zRR}m05E#zljfD&+<9WX*W&^vu0M>=1j3IZ4gqP zLY9EVz6pasgaLYFnxG||W}7S$^e_?qvX7&Y5|Wvla?ClOOf-3j%_S)nr3YRr4E@I6 z`Fm9V^lkRv`FH=VqCFa$pdz65<1juhfbnyzSJ&n{Ho3}zEzM;{FJy^{EumU*{a9OD zW1m?!RRD4<(R7b+eF_%{O~DHNrEmv|(oj5ON>p|sH0}LfFE&S~fr|@$T(q2UX0EF) zzLoe|_UZZQ>hkLT;l8Qe-reqZ`^TrpjasACX^FZ}(mOqY(I%i45&+WVWsPH)x_MGw zv*d|QO|gsL-HqR-9yDx(H`n|72WxAqF8JHqTaq~E*u>=PH#TMS!ZN43<>l3r6QZo= z*`uQq7v^?*@$~d~dt>wKZ=P&#Zu5eL4kgdNdA7c}&gR48Lr0X(QfD-9?Hk#)ZPE@7 zz25D2Kg<JN%vL6>a~Rqg55paymN&|@{17dRMI7a!+yl!Nci4@MO|V0@<>x|YHSu3q zBo-B!jvnQ)NmQnVOBSjiFz|9tOycS?zM5T_ZB!e2*XW^DIT$)FJ2H`_Hdug;VlJ=b zU-Wt;nut!TWo5fhpLe?(lBCgasOpnE9L8&3Wo<CPRhDW#QmX8_t?^N)Ee4)4i6wkz zj9HU;mV`Lu<U&dxFqYis3@Ld8+ARpTE!oIPmY*JJL}1>*q=}*EmGu}$WOc_8hhB2T z$0#!lc?73Df<ppWBduC@(p84!vYS|SVPTGc7p}xNv+L`tcI2l|zg}5cgVD>qlcV^& z0O4e6xl9<NCp=qO7I*8V5w9#B92}SzHgHp*Fd{>v;bo7O$vGH=@h%bYS%5@I6M<U2 z((erym)fqMr)S4P%C&UI_B0sw;B8?xvbYA{%yoO`R=mSw`PmOqi0kh5*6v03Y&aM@ zXu9O73b+(=qmIGKDH`zQ)fir5L%rFUjK;2Cj=wg-(O{_H#t|}N7KeIeN9m12_<X!Z zZjmsXZD0U*7;lkgWZ=02X7;S(ex(u@@VjUr$R0h_7_A_boJG?;k9WE4&!TMw8AA5p z!GkZq{8Acx^UXK*djz=9OOM=2v1`PZz{cenJK=i9Ag0bz^5|lZ-4@6b2TgW3GMe3^ z<Kv~pMfDBFJh9bMRC95OuxVAGr2VT`ugne!s!ch6l=Dq3-ZYb$w8RoPIa^#@W;RRM z&m^#vknmB>%HQjAHg!k^8@;)XTH!+0>-TL$b|F33CYLo<?5t*0SEc4A7FMM@nfV!Q zEn|yjnpX%GmzJz7E->DTqg0~eVyaPOhV;2w@!G4cUo32X{`|SHb4^cj3Z#f?4Hwuc zUMLVur@(%xSP{q`1n_!{*d;<tdjBVXX(?+a3E<FP#O4CbqG2N=lPD}qH3UwVGv<ke z(NZ8rEUB7azL-8<r`RMTjkQK)IBPG?&z;K-_V@2Uc;LkC{NfNI+&$%ec6NDbsoU$p zH(K>pL;dW!I<`7(YvjCpVO^}OtzJzo<A?Q!BkM(tVs^ZcF+Ya}Y`-46EzizbSw_Jw zZ&sYq8wZ)Po3jMQu3c-?5BCq;ZLCU%p}iL`msXao%EjfS^V2gD_Fui;xwi}BNacd; z*o1d`cjxm@Kij>3&uS%~9DVovf;4(NON(qHAI!ql<rVgm#uwV19O5!rt+0m|an&y` zc=heG_4rJ0=9@5TV8K+w1z#FFU<kN9!g^d;UHa;)FE%&Vt$U}$dR3_)GhPaZ8DEaT zH?!BH!8k`*WmlIOBBeIpT-~_nI!ic3xE{OuqRUIZ3$?wt(P|tY9SlZ&7UC7j-k{G; z6^s}B5{EqhI2XagEH1WB&tmDx77NW4NP3%n%kcH<*O^Z4V3wqHt&F=da?M7dZb%{R z>C>mu>HhuuR>aGfFTeGzZ~gx7|Nhq2mOTIPqi_Eg|MZ`&u5HLPi=9}CM1y4aF^gh- zeVrnzHN|RqZB<&>?<B3<)5Mkm34idx2iS!XMzvwX*~zKfQ?Go5ipJc688clAIWICf zSB-Xjcmk6Idf9Ff(T);^Yl;9B_F_}Xw)4~YkqD#QN5*D)5#(azJ{BI)PTI4lFWQSM zHd8E=l0Z1I@<9NRiR}-6_(Nx*JS33TZp1fx6>y>8qXI5CD3znMlWGmjYu4J-{J%$H zHJFlgJ@MS$-sT`7@C?99zMG~|WXv`yIN&rMhLOx5IY$B7C!c)s?mO?>8RJht&0JL$ zYG>yslkwI1#;Uy)Jm`;_Ew#60S7i(qGHKKVWco-8K-?hH1-6-^Ec?t$O!|T=*|9(} zER94AS!Cay6CkshDZvym?7}5WpFDYD%CIA&kxWyDJ-y4F&QMy2OEDCDy40w6>E!C# zO1Dz1bT<X{!3wg{VXSncXmE)b7K+H^9bed%>Zm4}M&_ldi1i4tq>tf4`HHwukdU!r zq29cckDXYK8$y5`Kpi{@*&q#RRt-vas*wF|kA-#|HA?k^QO#6W-dXSJp87_ztPn04 zj-C4w&$?zFAt{p=EHOcZ&&HcXj(N@u_KOM=oW9j@i3x_+^ND}5)hWn9iJhWB4ztBP zy;EDbOgphK0Hfj%hMQlzxFFs2q}nf3D)tu*alTU1_;Ni_0|#bDo#$!R<nU|Y#O@3q zFJ8n;oVBWL^yKVx_ujT}@s1X~$zoE*Sxr`>n95DIiLm1z+b%BR6R9XO&cdtgwA=B~ zXru7fvPEiU+20?<(T;=Mfe|_aJ%ZCgz_-8sZFtGX_y5ap{zGzp`ZoJN{2%=f_&|4N z4434(9dTu8$wX=;Pr`FPXaEMmBtL_&z=$Br5GWHy3B*ejAFybM^^nOZtYGw!#ifB^ zNF&p%6Cz}+;;l-zzPW)w(DQWy^0S7LDftX(RO=N-yyUoUxq7u17vsI_c<p(?1+$^p z-P}aYaHScK&s^8<UO%IY8GJG5kz_NhHY-kQcEc^sp}hRw9n4aD*@bX29No;##@_*} zR%XjPS~3y7>JqRpe>ob@RTf+&7$a=)<K|_TqQ#;Ga81y7lp4*k2uP!h@ag%vSXWfx zn;T~<i^B;Q48wjlfO(-;JX|T|3w+OUO*M?y<L4D=5(KpF08^F9@%Ez#<Skklg_>&7 z&d6I%yX7y(GJu8b6jEetyPRC{i%0RUQN2;AvtgDEqCszEes**@nYp^2aTF^T<HgpZ zXs0DD_Xh@#$81}YzV6#LjN#C{#7kb~fG7xg+@Y7oIOUWd1G5{kiY2B4-sCdIsKbgt z!9$7_z$Ah*CGvx98p$w@<El-%tc5$Jk%q>e$6rAZ0XZPANV|x4^`p)r*2pwpCWw&S z03b~tMokRQyJwAd%e?o716i?9t9F_#{n7qGYq28-o;>|#ZF%MN;(WOizxgrj$JgvD zbMc;=h{+<b*q$AqfMt<LI>*QBZ`X00GYa25J73*cmv1NMXSIdOd9O>dQIWsAxsD6q zeEcK>N(-x)7W2zaeR<5CAl_*aJrNLgRf#(uO9D(>CzqF3-M5|R4-fZOSJ(Uft^<5| z3n4z0P+km;4{8jDeT5dKB0ibOK|7E*IWf?9Th{Gmr5ML6IB@|k&5R^qIY=-8HxV99 zt4G#0>y21DVe_?nsH;}1r8v@lGaNbx*aGFX?BlSyWV+_0T>g*+E`6ynQE>Dg8O>RA zgaZVBV|5LZgl4mGa&l@{U0YlK;)@?Ye*E^{-pk$HdxGKIwX~#yU+SMfe^CVcUx-AX zC5=eh$w3cai+A$l_s=iv?m-prbej{a(F#%lI_*V0JdFMpj`8@ufYh>&zIydi9`^bd zriRk#1y~PeL~ISU=6N^Hg(g%ELs~m#(+Sd40<y5!oa{+PFV4HdE&|-=cCHsNUP5w1 z&7y4zOx9NX{Xk_;35@sf`DLx>#a{&Y$S}U^c}<j};mndVYc@GzB8W8w)G>0pzZ75M zO?X2&9Y)dM#lo1JLAgp)nySe@GFcdFx%?6Yzj&(UEN8<jjIlsYPVDqHV94Ac2muHS zdcx_YB_dy{pL-fz@J12iO3MLEMV#v$2A(J^k->KtU@V4^@f{hYp%eul@Ks!)ZTT!` zM!v#AW@^D`lrLF??I#BZuQxW<xN?4eYD={G*m7}kw!3?u`DG*ZKUFc{TxC{VT(mF8 zxLU1-H3)V};SIP_VWitQ$AbnhuJ!fJPe1+m@#A+s|NPT;-+g~|b@|DYZ|JJmn^w0; z<0xsYIzNx&i;JJD^2_HhT#Q|7k55mQI*Sgw+nZZw7w0QW%P;m`-rLzlb98VB6E9{} z76!d|ePL~7l@+gE?&(d9s$iL;6dBh``FwD6nAdODW=FBp;}a6V4sh{vGUsO~S6uDp z=Gz@HJbCu)o2`xQhmRf{9ULDXA5`Y6m)9=*&6&BIT70UZdO5zjaL>8Cp>cQnUi^iV z^9#rE_#8wzlso*<$TnWM=&D#~T;SQ(YSgc8E~6q>=B_5!-TsB^v<vpj=X)eCb(UM5 zrcv?__m57_j(2vqS?kD18ov&YkMbpkU-_k9{^YYyj}MRb4-X#PyDwIJ8H|P}N5}7d z@a}_q4?q9nGe_c||HYrHF4SDt+1wxYzWU<H^6Ju)FTdW}+2qT&KKk$%{=%<}ui`{x zE=)we^ke6eZx*a3(-JSiz-Q;@<$7MVH<W#QaD5e@%2`=n>kqm&*Rw|Zy`gKEi<zxf zx+}l(&;rR-EQjT!{Dh=SvpO>WZAq+(Wm)!RL)NB-i#-_GBSCZB<*CO01t5V7%uYEL z=|>-Z^!)jA=U~ejhIU*ZfBfmc_SgSLIberU3y?r!8J6F^$+DI!$eMD6L#dQmdT3HF zj8SVU&CbRbTy`rrPc?u>G#U%x%TWA=q8^-)1dD^le(Z=72?pfyrz^cvOmginSqsni z-g@gT#xRUDWQG9tJ9a9V$f&?_X=f-u@S(8;r9L0YM9faa)bY+Jq#!`DO2ptjG62S? z$0@t!F)_4j0BuUf9#dut<Um^GMt4~L_-zJ<MnVYJdt|VQ1|!yUoXm^~t8jtgiN(&f zES~Tt0!`AxBSr%z&?vmd9z)o(rJWQdqaHo6cmal{qdBdH(jz%0Pe=fZ8=17{5c7~3 z${9>Kgc#x%XAvYB78ttFCs`VROM^s=QuN?a(jrPp12#3ZFxz9qq|7fH=rRf*nGJ*> zFqBr^0?rljLf-8w0%W3u&zMsRlbKV(7ID+k&VQ*PBZ2X3&IATyO!wJ9riMKqbNzye zrA5OfhaWwDNUw&H&1nfC9@QLckiU4XO6pkBYQ{yKb_qbEB_OqmFJUTnG|ne7jZ6g2 zZ;;fHiA4`)r=C>^n4wmHbD95{U4Z}B|EvE6(Tvlx$*f!d`qQ{$#9K*_(_mrXX9k)Z zM%gD2hBWT!r2@QViGU}hK_)v&NGuvmG2mZr!huYPQ8I}-QLy>NEvvlChd>XXLCic$ zVpYH%5XPULx^&UrR_B_H-bGh3aVOtpvZ3Z{Bo0-!h<-PIW8GAxz%-05GHt^s@uIxC zxn68{Y+WRD`@LqZeWRq5*Hmn!amX*PxPWc9`A(PZ5SQ)NM)>;hwW`fXR?$M8I!G`3 zrCKJ9(bQ{Wc<-IJO^WTAwIt9xKRefKyM)K<PYwZO(q%)nVT*ukm9SrqCk_+n*<b_4 ziyo!J%Es2FgUHF*>HXb%jwx<yIVsd}oXci8)6NX)rwiMV=~!G`3ezniRUU)XRAd=_ z?TYR~8&PsV5eJ7PR*AM{3?G|tvBaooWc<;LCS&&Fg)yg8Xew8(K!C{Pn#uU^4uD38 z#EtO?!sT+HXDTj$W`$tKVhD?{GgEHh<scX!)P!S~Fgb+Yip5SWMwe1B;^OOV;%S5n z0|LlQm<V94>Z(w!#rp%|Z}xd@j&90F0r{wZ{_=%mqD*czqT)}65o&l56M^ZgjB*tQ zJk6*aHK#@$;Fecc#M5C*f6?p8@N&s=5RM;mz$L1<Sj9GtE-fE(4XQId&AUMY@OyiE z?oO`04!)<S=ZdpKu*GKwaRIgqlnB-Hz%AIWyN*2$<>g*r&$A`m;`MpF2AhF6FU`gk zNKFtoF~neAz%VAlj9atJ6IgiGy6lne>OUNe9oJlP8*C}>NIR}s0gf(L*YN>ruu+bf z0=*U)P#UMmq}QZ#-?Zw<*Wg?Ah9e*eoyFFmKO${uapn1or<)tw4y&sx>yC^k$7l3b zEA{1-#lwT+^1?#Cys!{2xZcb;T#kkla>U*t#->%PSK!B!;nK?5>8S(db*IyEwHcL9 zcbJEKvA{gJkcbSt7)r5mKfYil?55-RINqq_xUeX(<zwXXFt!eW_;B`M|Hx!zNG%6Z zmBW(LqbC2A7qL}mEMY^C0um`#wl0t4h>7^f|18=?U3^{<Mtm~1GSmu=k9V2Hs68{~ z)#Q2jX)hvJ2p4KLkWUotfV4SM<nCZ(j_3uu&avOwcV}lO-`yny-Y8<$vWlI_TbYY* z)1i48e<(73ygG@~^3>unf>S;LvAEQh+thIf4SEMVGDQa2w52huwS}{v92lYi<Y<s2 zU=%1~vE)#Hczf(fE`20lx#6SqNQfQ`iQQE+wVPi8<viE)ybvf3iW|!0LWyQ=ZAD6m zl0>#d80#_&6BVIcfMd0nzGOW|XtO)prb(D|yACcVoI~Tx!@%sVO&IIXbyt4E$jn^V z_wMcN?Y+*6@$1)n8yj2h;jLD@lH$frx{I7kqg^I<Rr`?&)*lYO{_4rMf95+by}S4C zJ%9SFz1VRXR-N+w-ixzyyF>1V_66CKw%b+JG<%$D=l<)%mG!mVt?hcN**m}3KRR@2 zo3B<z{Xu(aQ7_kK>>x8Y>nrj3&-05@UhKVirAoc`&ih9vF3)4v$WK51OudN@fLoPU zGpdw}r7P>Jz31oMGnJX;Y;)aRmLiKC+U-{PK9yZb-G*OUS^oN~Z(5ypyV0&TZvUIP znsJeg7q+YO&04dy*fP3MTTtDs3e(q9tp>xj%?;}W)nquTH5>PLcAvd`p<;Ch{fGDN zU-WyOW@|7W)hkstt}U;=I(XeX@79|2>&ca?|LM_*+U6P!hUt$6SK~`^mX_D^@5M+D ztHxYN8yPNh96&7%i6m!oEm$Bn#rWBja?w?zTy(|GX^4&N=Iimvp&o3F+X^4vzi(x| zdi6?*dUP31Y45)KZYr{f%8H57LB1%l0Rb36t`P}rg(5J-p6ru`*M#I+BZ?OQED98j zX*M|svWPVrO{QWrl&gtwFhx#BT+VZXN2Yp|?YOW*T4F?bq;Y$Dn-(o4=;5snq2LER z;knG=H8y+9ipm!nxqy+1EJrYeM1;#hQRKzMBT;x6U{n!MhcMbwZLEq9fyfAf<T#oX z3+8wU$nAd3lBvrYGGb9u0ZG2mRGmsaf>8n_gJ4G4DknM`;Q?8oioDy$X-l!$dqjX& zPYw+4(jyk8E(VKCI_nW5XDP}ph6H%@XdqJ*03|sDqJi-UnZd`H2IRhMC|NY78p;N# zPp2>fQ09=w3`NczQyCwx)|LAwMmEb9kFp}u2F#MFF`AqwMDC@7Fr*1Sk1}E~bYVn> zkvn=BlI|PL#hCUm0|73h>E=v%wFO{EGX$TMsX{{lL##U4X)ifRrXrS5p`m0OB!Hb6 zYWP%|LjI-31uknSa}pUT=2m)I63&-~I8^|s02`$OY?ZC7#wWZoAfiMdz>ts%!ok4- zd#pP&@Vs7I-NZ$g)oRExJUfeD)yWX0<zjBz<q<_E=kWn`NR0$EOwwb?C{gt7Z+|=I z$k6}wAN-?m@276FfB)b4x74J?c3V^gpzE|-F2gQ+@#UVf_87q>y`U(*`kV&Ncoa<* zADy1)*~&zCbq$=+K@U!L?xkWh>20>@P_7*8oCgDBfUw#xNzlZCOh`3F+&w0ScGCk- zvLTm^K{p=B5oL1^P8FP@f+)f>gAoX;p;Un^qYtCUYdM9??QN8%lRZ{}v-mVV1fs;n zW-_fnaag_ks>agl%JY}cob&Q~s!T<epVA?U5MiWL#()id^UXKE`mg-uVXx1&j4CAg zS!FT{nZ$808eFcyBxL-VBnTRNjI!tX^XG5B{WkeFxsN{j=<Bb)c8+m@z(Q1dI$hX= zkW81+sa_W~qCE0+%7Q@IL<~s1G!i0W$iRjW-%&<|HRKTuEp!Q{AxL4lyt#JJakzIl zC?8?FacHQ{FE}nZj?YyV953`RXWa`D2qzOeU1X+7e6-E5lP(KPc=HoYIYIDX0YPSE zvXB{uR?6p!O>z2;tWn-^(kMztv~)a!;1P^oFVvMvH9mAa966{t8aV(R?H@S$JbLgD zY$;hF;C$znoz?^1G<zC7GU)<LgO=VUU`YB26f!pOLXRxzvyqm7421QV4JPH7M4s}? zt_<%)<xw;?H#c2E4i1iNf?HcV%gc-B=iR-%7Y@NLL=wF0cdB7rXhnKuMUdn0DC08r z>S|u<$~@RAM9#v$9d$Z%jZ6awq7h)x<=g&d3XxS1X;AXVj*+v*M;N2R1!gAzMsHM0 zpxs(5e+fHU;x+1cClmmZ4OuUGS$BSVEUO8$j@W}(JVnDOdvcMo%8**05sM7C`vwt# zOwvd|;}J3fR9@TW9oN)SFj28QOZ_AhWx6A0h%)a~$E|oE!irVg$J~%(zHTDJ2ZIn2 zchQJrgfh*j*5f5rwI%a8E#xV^a-LOoBa(x+yd;DjG3~sDVPP^NW(k3ij6^^b#A*3% z2v{@9W}(A{m`sg@@ad7qRwus0xxc@k6Kc^h1}`Dg+(wxT3bN6NuM!~Og$U~z#sHL5 zzyorY)8&iPI6a$v!U+^r>laOi7Y+M8QeiYg(K}a^<HuFk)*8&P#U34f_TwMF_27YJ zDwpkd4&4JQ=x!}%PfpGhbsCe>epVSx7^z^uL}4s71RfV&QJUJ5GSiXq`1Utx<Qwyl zVUh5P6-Ou{O8TKB&`epL@O*MjRVIhSzB5>-(~^4Am1V6lnH4Pg?ce@wzS?mFBwHFL zwt5U&8bA^H4EtAKeRco-ed_d2pFU-qN#QbkBt{-+xPaiTw;qVR4cD2T&2}ylKK$@Q zGVLbRJ$drvd*AyW0;BdXqq1drak16u^t)YgmMHz<@LTV{FaF|Xw#<TsG#U)7lwbO# zUwQic*^6h-T}NH6mRDDr^+sOsw|943p*OZRUEYsQjyKlgqlUlqOTYB;<@2@Wwac5! z&p-LR-irVJ@Q?rS*M9ZaYRy`w*_mCKy;M1FE?r)YZLBSwUYrg4eJ5GzPOo{loW{eU zMcZmL7R;~XN3rel`o<Nv*=aA##@{D%eRUOgAwRu1ccHZ(*_!q6s(pUit6pnPt}f3` zP9MDWu;1-1E-xMKA5?19y!>yjZ<sgz!O>x>(Y(5jHy8!Hq*zS7n7?@O0{qT9?^r}e zpFMjfwl;2y*A)D--}$|t{n?-W_DA384|@O2fBk!3J^AwSqql$MFaGjB_|5<1gKxdR zxv_O}di?s;{$SYeb^E7hC*S><?;al?S^drU+|4D}F0s74^zp}^?C$Q^tzfLP?d`4M zaP;KKS6kaVy?*!V(v_Isi}gmW-RiVEEz&0C<$<f~%XpbTe(&Sv`sT`9NHC3&5=^#R zG7{dZmud1)0w@A<SQc^TdU9#=l6aZ_XcS@WQp-Y6i1_GqWL?O7G!E!xMY~YBOW0ZL zjQ-gxXU@;h9JLbT5^I49;PTRH*}UQlO%EQ#FI4A(5>j%sT#Pi9DseS8uZ;hxEx0U^ zTdOd#*@CiOScrxk#7R%u6wWuFxj;2u4#MMQIi$HWt&bi(B9I(MK0Qi9xF}*IdPp}- zVwu4hcr;)bCNUd~o;vpEQ!<Q5f{kLa1{omW=$S!IxLvBEMhmiOBOg+aETvhkh}pw< zm4U%zQm03s&VtcX>M<(`3FuiuyPkx!Fk$p8nJOZOJMaKVjj8C3!ZU+dau8@~aFQVa zlaPQ>NW!t>N_vmxh%_+m1R^E`kVEh+=NdWKQx2M`99#lOLLL&3N#-O*1CI=hl1!yr zhVSm~IyJ#aa?4ig(nt>BIR$ARV4=JxF>R39O#M_ivb5@Y=EixZKm2cb;T1sURP2=3 zEFfTB5r5k}I`9jrmb@?kES8CwOpz(%R(olQ%<1!}$jJ}^^q6rbpLy&Tiu@>w^&)hL zQ7$d6m_3vhvi_~N-s*PaSb`WMv+>GRm7GkE!$~Y6jZ>6n^w<NFL7>RZ#beIk|Ls5d z$1M5j+wA}BKlt~1gT6A|Rp_s--HSS{cok%D9`B*09b8H~07A(u)+jOfJ+j_typ>n7 zN-va<yhWz8g`P4*f|hF_Za5_nZ#EbaL?C47b15>Wf6;Xzmsm1VZ`6uKAa){1rZOZ2 zWh55#<kZW-SK!!hG1G{Eii|HI>_<jEIVd;FkKbr0*~(y)96`ei>ST=L7g6NUn;$7; z2})dSPI?5&cY0wxkR}_LcX%8h5>Vn*XMh8QQAY{{VQo2;vWh(zZF>(N+~*hD*h~dj z55~)K_{;;s;p^_?y?AFM=`};y=iT0J`u_XxGg~?S&Ud~;J~@ar+DQOVK>|w>sqqVo zM}GA#y2O#0S&<6><7K?#cYA6Czyol_7bZ#?V24RJ5nu_fa<oNE9YBPetri!qCYLv} zGx^atSNeR%U@#iOEL1COFgJ;*R3j_|5}S^vc0GZ@o3|<X0AqbN+wndp!^F)Q4hyBZ zVW45EQE6awV`GEN%G~^96ki80DIO6J&K)r0sfMA{DA>@<?6rdq`>mkW<rV$O(ecYy zd-ZB<c7BfiR@vK+9><S}-2MQDvsb)kA(&*cAz^?=4M9YzG(&n*###|$25Xg@EJ;b9 z?UsHvZaX9}GUbqvLQ<WTVqpRZB$gbMPOi0T<M`xo|MlU`%vJd);^Jr+VX#~mDs!_l z^OslSd{?2-Y;*Z?;$Sl}>O3(&CuTF}XWeojjQ0%l9YO~fn1h4Y)&&DZo-XE5D*m<* zD@&F#PonZpNMi@Oju&nP7CkOr$VMz^`2J=(d5mA$xxCGM!ZkxVN-Sr|Bnm9N{N;PE z>&6uypQ9xsKr$7iff2LTBNmB--MU7W_K3M0pv5DDY4NC~cEoBa?S>dR%@Cr%Xiyp@ zO%F!n>U(^6QKl>MkRHf*GdW%mj0NZdoRmRP-U@zj|FNxCV~?aYt<09da$8lwNWKPx zfh8tRREzL9$)%6tz!$t|$l)(Wk7$aI?2U5_BvUC(M+~7%2R%moCs#5DMm3g}V&&{h z9RlohrCtQ$pE60yS|_~d1s`m|G8mbLKnveXqljN71x%WTE6>e{Jz_^gBUpC5_pJ}C zHCGW;#X?(IbCFz8Hx}mRk55mm)1{T=MlF7=#HdM$GjZ8*nKxaG)5xS`?(^LvdPl7J z%I)H!no=wt<#Ul1auTTrGl@IwkGUv6!ALm!RVsnXyQ`>DWPbs$!H|o`=GKO*h>Ojj zKb&8fWAB_IG&AQC;<_?3dlSFHQNBup7nhWl@GQyY!@P_nGc*8VO~9>vzPPyl!Y}-S z*ycOr?1UtNN$gY;7*7rZ(kZj{@Zm$YnQQjLeCu1^%6j{QAN=4i{iVM|0vD(tQ-s@# z9p{Q#qwZRJGaFxh8coLe9a?h%lb;NF@4fd9j*gC<CRMhjCD-P>FrS~Eu5D~woSp65 zyJz|BA0Do+y6PNAs`zU<PoM7}?tl2fht+zud*0o>zx(OOpKk5Mf26})^e$$uXDrLP znRusKRjJ1>R>XVJU>CZ*7cccJQL)u(`^%u$mov3W{B)SykVW}1Y1cq_*4l|kU^)Eh z`PupDS#MyK&0Wvlu$G<O^YcclwfEwMmE+1i9FG^<ZSk^yu>V2%J)y6^{#x!>6y{6h zKltDSXM^%HOM4>xb3gZUvdDeu%P+q~)9v;<tq!kM+TDBG8|zz^bN8aJFQ2c94>MnM z&s@US)>npu@!qQ!@4x+izQ@~HY|Y%vot>ZXQavA!E>BL6ROXG%HI*5Rw_00RT3J)) z(W~lesj9A5y?fn3`GQv+tn%9zvZ}kV$P+2SPIH}W2gU-C67pPj@k^e|G?TTlx&}rm zPh?2eVO;miJI~TGYmv1;j>MC4w6Hus>BFl0+zlI8%VyTXl&f)6xn?7N+<}m9zWIh0 zQFZ24Pf8t&Ml1r2k@DP@6w>c*n~)YAGS*t5%wRLvXs${IBgT$*Dhfa&cMy9-oDo2* z4zP+S7l02x{Lq=rnsVeLjRYamvr`eE6gwCOJ2|Nctd$}ZM{6v4WRw!(k#LRiB*3I( zEGc$6BYHG=0f_-;%W6PW&XFOL!gv{|=MMVx7c2;gL2nc<Vo2IOnsE{k$Hd*eaR)$_ zedsO?Uc-Wt_8g)*@urMnFjEUP0Pj)`*eDop+LJyeo&<nVJ@e30gcl_w0vJHT845$$ z*e`AXvyXszIjx$<qyeXE(+rO)J(+lPjLCzg1VE4~5+K&90%#0?pK8a&5xUU)BpNd} z_S5*h>RnP%ibhFKlM<shnljlib#2;U7?XIE04$j&;!LAQ&YDod5x~o51ezg=7^BCi z$Ye_)D02vGMdt<B7MA8w>NKd)lB?UT2NJPKL7--^pYIs4P~BeY04ybv(^LeS45x@F zLoUEfCDZ7C^nd>+<oxt)_V4_yzfo&6mO7oPwN$=qYO@iP&6W5G`{~DMZ5a8nrMx7= zIM9RhBTTjdYkL|XjjOp%L?<yC-?)?$po%6kxwL$w6r&KJWQHjh0vF)9nfQ&6fXm-K zV|p$>qHMJACP0ay(PB2WjD;tMKypa7E9)5sqt7%YA=3^^d=x4_m>q|Um<C8adzeQr zEeP7~%;gWP8+BHcBxOZ7)S`8+ty`EbCi&e(mCBLNg>hkSp+D&Ly8V0icN_Jlt=<8E zo~_MoTWEY3$D!czdU2^!uQkpu&fIJmLND|5k|3f}US-Vegkg+^AdoY00W(MWf!oXL zkZ119j^$*NzW?xn?fl^A@X^EgUP^p)v1E3*Tcl+#EQ!w<fze=GgX|eLLJ{NVbcokR z(-K1>0w}SH?F|{RFanfva#Mj6RTu=^k@~y$?;W3=)+^P)c+{-bJIhPG^NYF4LVkD* z#wOf7J0D+Nq9M>ONC<Y)$jSN2^k4=DDFTozPvWe+5+7lL_n5ERN)@XeBLJ`7D3%nm zwZ4%zRgI!-V53;LhJ_ipI7Oy?+7Nqafj22c8On-~mCI)Dd_xGb*_$Xm84$$mNja)& z3eOglWsdSlN(fO1=v4?Z36mi0WLxw%ab!;$5JPGRkiiJJx?^Eh%eVVP!>C8@Yv^HU zVabaZFO+!n7*i2SR>?6E9P->9mC1-c=~q|zoq6u*Wi*UY=^K+Yd(&t)T$itAZrY9J za55hD`U|z{s6Q~vwS~&Hqp&n7-*#4bcp4gS=JF?P<`&$xZ-(Q6gX!h9JfB;r&eyAr z`N|x;%y*a}K~~52pB>Z6CkXT;_eaC4@g#nI@-lw?xK(e6xw9klUq0Wf)D{-oOXrS{ z)dqMp7*DPo&~Mf^*T%yMywRhR!}!iyWv(*s=zKX*C*qf8<NMaFMmsU=j9=2NEr2h2 z=gnrjwb;VZ9dvIlZ)(lj+|68n)SsW3A6<^Xd|sGcm|RcLRBDaW!?TIgd3?M3WVy3A zz8>dCC8IXQ4{u!B#$|(}jkA3DzIS}Ko~KramBQ1dcBj3xXpQ808C_0R7MD&h&cWs< zHn#FoMILbT=$s$$cHnntw!<|WZT*0igLv~+H2qg-uh>bW|LPTzM-HXN8r23bg68_V zf6=ehYhoVXtx)kA^~rE#X3e;{HZL${mR01*G4q@GY~yh5mvX9l?!INI#nRSFTE(sr z?<+ok)~MFSxLIpB_Kydnt=;Y3dG}^+W-=UK^t<qDo9m0M&gIS3KmUV2TwGb&+1xfW zFQ2`*nz>%?Ea@LVeDvh$*WI&=PI-57I58Kq%~m6>L;hD<guJ|JV6nI#X7URNt8y2I zZ<ZHiJu(<Q0!s$o$y*PTE=YXrXe@RZtBlJ;IS^Y}@(?D6(754Pbi~>YzVn^$Fn}$i z(V*_q)~FpE96fpR<<I~8FV<yhqa`*rQYKhuREUy8*mSqWtBJEEY-hChu@DX66!DRf z;?EM=jjAVHR#FU!wo|)eWym>Rk>T3-Dt0l2@vE=Ca+;xtaECuyh%$+P@CSc@g?FyU z*q!E-ETegtrkYho%_Eq>*t34Zli+43AbIP?nA;E<CZQJ=rm{`kgw*Kn*3S38|9xiQ za+&0m>mpIV_j|twNgzs=V-e)|P0G3O)NOP)bbg2rhYPcF@&_M$*zKO5oSca>vgKu0 z_o}Fx3)(XpH1Z-=MEM8_`9jSwv*uCWx{P&}UBF@zQPRPZoXU6KeHW4qVnUjTi4yjO z_-=o^<K$Y%L5}0{h?4s>N<7hXMnrG!#>24^2QW=$K_pQMJF$p`ktK$#ApLkSv?YiD z$?QZx7n4#x%Cr!rKHKq0{PqNl(52&A`pa>QXoNz8x98Vt@fTJ+!jrG}NDD_OC4>sr zGL=k2Gvy1+DT=jN00L-^;8`UJ=^`)<wx1G0EMn{c#-JyBXJ?1|02q|$1z~n(L43&1 z0{|{EjS`q#h_itSXROhTCx79QX%v~?j3+sqMQ$R9B|MWB87}Mq7{)-R9C9^W($W^m zDKq%?+i!~of#gtxIBCcaPfLAEfItN4Y(64mWR8*#HYCoZ$uy5C4N^m|rEP@dBOn`5 z9`#9_NG9n?(5D3KdN6gA^3Eeg>AvPMCk2cc4eta^h#*n&3ynr*+Miq=83u!l*;IQ3 z<d8-b$w@YCcwwjr-FKOpG_<3~mF{FH;F*eEe8B8SgA&r?)NxADCvQqd$<&m|HhGn+ z1`T3l8r8{VX3-;-y&feq)v3`VGQ`-45)Jr4zw0uUGoGSIrqp8BLuxSac%9ho?tsM8 zNEBWsDIoexBvz$8MhQuQ)8<i2YmqTECxV^mVF=NiHDqKO5;QOZlIcxj;4uzIasAOe zl8MGBm?$+TPJ`v|U5g1jX`GCs;L8eyln|AQ@N^$unW4hkSN-7GW<wV%Ej6Mcgd(b8 zFp}&7j38^#pV<ZY-~0Ff-RVbq9A6ws9T4Tp`AK}+WMMXrmGFwA<BOx%pxbM9+WEm$ zqj}I#>znmBm#2GtV|_@!I|1+^n;{J#lyBm*!B8!@+$JH5P8gG)r;6VYi}!y-A%*Cj zoYVq}@WST|iR{+Sw$ej8cD#tm%&A2w;$jLW4Gk|cSv?v;jFKF@yar^h>!q@LQLPcb zs{|hriZ$+k=9}*~o15Ei=rGdq{Jd+G!P|5ll>6QDM&0E(eh<+7t$We0)hj#O_g?Nj zcL1$a=Wnj#Z67p42Rdi^yOv?33?N-(09bI?1MtWfKyNs(%{Ycm51NkXj>U&3$7X7A zW!WsFaj+&QF0^IAWEeF7U0hB$!g5!6RlA$`2nT}OH+!`t>vZBH?xH7R%)l}p#c9t? zUQ7^VBP5#unj>P9C8f!wrNxz#v(we(m2SURnP2EEE$+X1EzX@*`@DP65SLojHGXn+ zDbpe#H^InYO34SCAj{Z_n!alxM0wCepZjah8nQUGj7E|t{bdr{q#1$mHq^HsJiw); zaHHw3XoHcF1D{^IIShxlE0acgjgo1Irx=9=ers#Xc@&1ytI32q0+kP=rZt5VNC@_# zJhECd<Z8;V%tHbh$qVjaPZ}+Q8Bw-pH{uukG<Y(#xcuDhYNBK{H5yUk0eZ%$R_GZo zP$(n$%g2GpWC>W0H|>{HO&hSI#(1nyMRG`k$z*$LOO{wyF}u!~wry-Gga4bK>z-d+ zUSFBz8Rx&@h=s?8M`pQRt=-JdT$Z2U2WuR3qHuL|9n;S)%(~QC7cO1S;<MMY^VNB< zYnbbq{NaUdBVVe!F25<Q&zJ40_1gUG+;BX~?@`OHjMdUo=jF4P)kbx5ZS(Nt&_%S_ zX<nRO&@~>6H?}vrXWjjy{f*U)gX4pH+xO^AORDo#S3#FR_JH9hLl^AJX02Io)zMt^ zFKjoiCwWnKRd!)6-_5+q->r3_ER|!<<=LfL1S)eik!dxWulD!W+y<R*n$6SmQ`ye` zxtSXt&CTA_tR1_~WJ1p2@zKTEd85_b+1j>VhW)|m`C0FxOV0A*((&oZ*2bo_L+07p z#pdRw8B|L~BUdI@xF~^^zPT9;`qm;$tJRiw>Poj8*NjH1&Y$a<t6_gM81?fzq^yly zVP>9pm*cDa!66p1WPYKtRDR={Y_-X(%7m^P%fbR!!Icj~2ZDw8gYA;4*b@nv^%;gz z88}UQt>jK@E3#?t)hpWBv(#B$T3I|hIj__fzWDsh&Qe<>PtQ-TFK<@XmRFb8Sa{y+ zv&~g8f2Ih{TMr)98r4o~@yRz|b<catt4qA=4|{xBSy|e9@jMcyoHC`Km8hpzlPY@g zVj(lYMw{)p=de6iH(~?~hKW^IjvD%`b!e`yVo&kt1Y;pfZ)XA+>pFQ2X)s(?tXy|( zcJ>k1GeKgGYul?=FL!qCIiyu8HD`?BP$G=-HB!qqOKV0<JXxa3(VQ1HT6kxr>(QtH z&gBZ-_V#xE?73?s!&s|QaZO>#2~rtYwS8|}?Gk}xF~okp@R91LPoF~42uTj$!}mWR zM~z|?Gq|ae*pV5=TmjT49tPQ?$8WuS`O@tghP5s^B;4GgYXAVLa!Eu%R5L>mXygSr zrswMF=;#RV=b!!9&5+V}-g$@FpM3Jk^XJcDFlI*4#aZm6InD0vz2-}Kscr76{DOde zwzJrJ^3^x?mTE<Q&edzp*}0pu(~HBS{SQ8P&m8d=S0<;RF^K^}1Suv=N~;XrzrUNA z03*~4U?c-l2n$7tF?;1ZPz1J`4gLzUDZ?TZWd7{W{_LlpeoDS6!%L3f6OQ1~gSP~b z*i=Usu?Z7`9*h_Pc8t{pTMUxh52j@j(u*bwzPW?X&!edo@srnu47~<O*!eYqRH{)# zPPGv)2LQ5%PkTfFJ+FyncJ62-uPw))HX%oEiqSwaMtT4wJYsohR0=^lbVmIzCkMo& zQNcTTYa0~`!OZ1j6Ib8X*8=I0D8ym{&Tz4i@w8|F7>yt4CJch4fguF1_?RzAPAM(s zD3h547DA?*84ZquGo``gWS%^G_Dn+ZF};IFkFscwD_=%6wc~})c)l5J_HZY4!7~XB z^D?%`*hwi1r{<;PWY@r23QzeOnruuJZKlc!TAZB4Uyy~DE?f-IBTLm9SWgi=7TOs@ zyBroP)@n&fK3yIekdeud;$<rP;qe-RhcP71ki=?X_g#pl(kRtDCK(nI^f@Dj;AvzG z40<`hDljAoMPxKA^rk3yyeQGIgn0lS0X!lj0X=CNKtsS_)*`@eM$oe)9WjcM4Vp*6 zj0<pS6h&z6F1Hv{?6et*|C_z_g+NaX(1RWMEOzqK_;kc*nh}hpO<_(Yzzo{;U@8vx z4;ah<awHF#0JBdf0N(8A2`3qRei8RUm}2{FmU`r}%y9umCXr+#u}*pzFUo5)Fe(s0 ztSG9Ndm=Lku{0F(Oa`lUD%PW(3oz_~WI0D%fT<$_=0E<2e?}MJzyCk^w=ZuTDjbjF zJ(GA9uq27<nIYr}J6OX*&3X_HX7LBo)FR+Xyho>%4?f~`^sH6lU^f~J^W8{&yvjaz z`vX5IlcM0dYcS@(Pz3Srvd4MyDLOtoJw7-bPR5Gq>c;x~%xrhiXSr*hD_{JK*zDZe z=7uZ!_kZvw-~H})<qBSmW;E5M@x;<)N^;7jpv93d!6L(=heR*da$j$HO!MLEeYdIH z$<Dg*32+TrHZVrfKrEkdMOez$i~-|8yjNhuc2+?7)?06xd&Z!&bHgwIFO$G>qS21e zW_z5bzD5gTXW10a5)wEPVHAz>^&3Md(`5itX;gy2+)ou)%m^-t76m}ktH^-a*|n9G zc*U&z6`i@6_yz2~BUrcl=)K43ps80h$cZeOn`^gjKU&OAQKiLU+5!6B{T+B@xR{L* zL3+n!W~XcLXaJ5T4(q$yyZNEDX1n?9n`aK-{yXoUJ7W9q;_PB_HR-fEu~X09xWki{ z^A!@x3S<M=*#gXWHYgSjLneY-xt+jgC~T$0*EoNtwN5G+Wrdq7j5I*NR4$O8jr{a0 zSxD}*m!7?R8B3?6v?<V#r8?}EG?^yOA(HQlOKtO&<;K()HI-mof|GG386%_~OfO1~ zz>ut$kk()p3oSDcWocp9Lb(7F#S4wGXk;U@%x4D2$Lg-Ht&~TP9`RICi3T%}(U_L& z2@zP7<fMb~*Fh?=-7?ASa}$zek5gmxxC{}(G-e;|AGj`Wt#4Et_3O!HrC!@yTR%BJ zJ3Tti7u04K=2amY@zxuTaq;&{7v>f!waV<x>}WE|-UWANZl*F{xw>&Zi~lSiwNrst zKFwVyc7~Xl*?aL~d3CkbX!LE9D!c8ZeEOY9Se}0UR9>yGuD{rOaXG$hby{TUuP?9f zKfFKa4USKb-+uJ=*~J-&-G0|a5dBhTi9JSTCVla(!O?^O7D4I0oiekt)L~(7&}+9k zFJJFnPp;OtHe6wkPLD4~lV+#og4Qd4tK52HU;f}tt=UkuCf8RhON%e|_O>=Qj?2&Z zxqhp4M%A}TyjMK$f;~SIe~|3_<P=`jy`B}>cwgNy-i*I~xo2M1S5{xV+Pk;Cqe8YD z&DXCFt}f%V1}=Nu{)MY}{8j4ts#9;jJE)h7yX&HBxr_Sk4+v><Gi*LNKkZ-i=Bo=k zo7-!f>oBM*a|;*!?&;CVa58GEK#QHL@x;uoEUrA?d){ew4vr6Yw{|UvXJ0>Sv>Qw9 zrR&-2^ON)Q-g&FuT3vP6a?Tj6EUlh*&$c&rj!%zVO<hOX;9Bca&7PU-S(dc$x8iKa z7ZEr-Id+Mm@r%zs=i{&brN6xU;Qn%F@#yp<UbJ<MuQ%*sZs2mY$<Kz<m{mD*anbwc zn<wA>?$7P*y->lnwl?CE=f{WOwbkWjt?D`}G31^EmOc{LD$DgN7!ndNU8GXZqZMI^ zp+R8bU@sNo_GK?}z~n?e&%{gbs`ayHZkrDV1C_xQ==sLRR<r2}#8|sh<>=_ZMOS7z z(5equs3VGGfZfN+^=RFx_K*}YMr*g57Z+!)&ApzJdV76+l?0{Y2S50cL!Fzr8q8kH zkX{%UX>s`Gn`eLWC*ObPo%htgm6bImhXgSJTR)E<zmu^#IXU{ycfRx6|J8r__~Bb0 zeDt9;`}=?R2lA~y8ZNav`$vb1t+t(4Hh%f_6YE!{Qb`=66@rHQp7Ub8-nQXhUG2Yq z-R^WYH#Ssf0Y7yYDu0dk@L+#!W4+yM^@oFenapWHzq-7VKOYEgkkV{C`SPpy13%?Y zbT~;I9L0au?AFGXv&F&d18}?9o{!&EuiyT;#IrN!cUP{unVOmD*`K=cjUG0%m^U-S zlAf9{KhF}BV;fWa9!l3v)Mz!VRIuKzbbNR$eyv7}WTXCzFXqqBpE*cOCd*4p`v(W> zYinoc=X|u`k$-%0LNECn>+1)Hhvdr?yG&H$c4u$@we{OsUOGEIv4X5zYgz8gVG(w= zxw(w(Rd$)>Mx$xl9F4|$_0=vR`z|id?YZSI{@U-{Mq<N?&+fVGsTx;fE4o^*fUU1~ zvtz~0-pnm7cT|J3i_`hpg{76n!N?6w!mH9_C%$+~rt01@TQ=?Zd>Xh?sp^f=!qnJZ z?miYICjk;3wVb!1*k5ceZl^XWTOKbESSh*T8kNsB3)d|vol8k?-w_$P%@8>${~>Xa zAP823Q7}epft-Bp#=;RV!66EPP1Zh+*E*s-7jM}R;#O&;k-5IU2G4S^21cNfDSKhq zX=jH=&m*Tb^%DWSQI4xf*tx6+=Q_ns3k$(tfBp4`AAV>dpl3X3M3F$Int)NC0Cq$0 z8g`HRe58*18CZ|lsYA?1#|aLmQ{*Hb0ZcwlS+D~j^*IWofypQ22S511?(Qx(_x9qK ztDii1;yl13^v*Ek7($<phy#;yY9J|sG;wB)0l2iZKjnL*5x~w2nkcbKln|tR0);dQ z5T}tOXpnjYiJ?~`1P$#wJ3A(w0XZW?rB$MhfIWHA!%ic>C?K_@WMmp6S(Ty2q9;&+ zB_}nagq(&KFPC4vdL@A&CA^e-{ra_087PGS(iPsQh*`A+YIxaz9YLBj^%Q2>+>}Jj z5W@r?3mZJLoRJ>o6->msL>oSZXz5qB90g4C!6Qe;!$@xeg@}AIh0(G3{rBG|77YwJ zY(N|{H5aL<5duRU<1--g#|0S7JE2pi7UI>C%IosWScK%SROEdpFTl81B0lyAGCc}4 zrCJzWT+o=u43F4NvDKvK5&WOo1^D0lAOG9=(LvYX$<R6O$~MM_VfiD9VxfXCkp<?J zHL`@Qd@#rCW)Ro}yS?NUI;A<tI;`Y%`l8<>8OAo5KPC~sh_k$G4HHfdm?>t6Kp`k` zj=87NBr(H~X2F?5vMUONg(oM<24iJQ$(ZwU@Ye$!wXNj%GVQ~MWSZKy-+nv4U}K@e zP->D)7+qAru!=7TsE)dM86Rx0G3vQ*J}%44=Q)4fK{sB9FY8K_!~~0INFV|c8zNSE z8HyyU#|o#BZRinzVbEAbruI+%<WH#9B%-x69>fd4)R9SrS!Zg#{E3SMkMQV;IzK&= zV(2x-Ga%CxfwZ#;B|9#@&}-C9z>z{s^P8*SoAS3J<Ndcr-SGlO4j6TCaMbwn%O8_t zwP#NAh&1MnM)3mxd=yoOIolGz&gVdeY?{g%VvqdQ*e2iry^QLf_ZAo9weXqCneMQ= zFtgBHY|dTJT?{U+Mpp}U<!WJcHG-)yf3|Wtqa2K78##n<nK4Y_m(`dvVmkC0WCTu` zhyiGXH0K@6;It~I7@jXoy}$bad!9i#NKQ&aLlFWjqMf>E9*$z~$wmt@!ja``W82%? zh}B0!>ZVaA*5}Wk(PbNxicHFhR@dHp?>+lEM?_Ljy9}`q1PY@bWgZmxsFkdVq~#Hf z9C1uE1rEXK5sWySE|!o(MfV~;FGn&)?qlQ>JOj*ftcCIt`~Ca(KmGJmjv#pFop<QP z#S6(iUy1Ko*(Mo)S6WI=>gclZlOx(Dln^YBA3q)r$}64D6E;r&EcTM1Fd}|_cDA^* z<ly+~^=pap-S2+)lTSX0kM<14j&RGJ<(2i7g;|%bi<zq#^~F_ceQW(_|ERsx9&`u# zn5N~W<HMtT@7H1a=-}|Z58lr|yW%)_GaDb{&+mMSk{Mz4{@(u1{hjN{HEFJD<hx$3 zZmhN&?R@8Xt}-_nPL9uxUFsHB7G2F;<X${|@y+vZHeCm|*4LKTPA^X3VYWB6m4&VK zExaxga|^T2pT6iUwWas-m(SjN=lxcvIT=}RV^>huJcrR*qv`+}FF;;iqIv7#L-A2z zKmX#hwUyPAv(vxui+|oF&I+|EUp#yMgCG5%QEOO_t^_~(=f3;>Kl<bE{pG*(&;F}_ z`mg+zUw!%f#XtMq-}$S*`d5DR$;VdiJMX=l?*lK)%|CeXR-?Z7pa18-_1*7$_x@Y= zyJy`ePoKQ==$)r8o^Gsej4nrutwj;$sVjHAQs3H*A1`$oUTiNN9v^)8!AI7b3-gyx zzSvmXbYZSn8!+ih{Ia#<(d_K&{r%;|mGV<)@jmV8@!87SGT+4kO<rhm#RYp|)&*yB zITB&BNn^f~&k}QO7R>3@jGd@CU!9M4+RM9P@xlJ`XLT;iZ{34i<!|KjF{_qZt#?fl zH>qf8+e2Ll)oBL+l}h2!Tb<4xwpztQ51yO3Igr)!x4-Wqdo8_OWmc%vvPLAcW+7P7 zQvKe8T^9j(#FmvLw`x4<ohBu)74*dyUsyZ8@+-gc*{7e!N9&_W-)q-6S5SIoIE<_B z*_pkgzr4J<wzlFjEckh@vSLWkEGw(kzHHIi9n>WbQm4`W;>ELOtG=_d?Rar?<VZ1g zBeuF+jhuGCcF40crR*~QoS3svt)?E%o}8S%dbQ_3xVyX4Y_{y}V5`)P#_sCO>|Clc zs}fed%c0fkGO4D!IwqWZvEEvi18jn48x{fF-+Q(D;Qp}JUtU{%{c_KFK<+f!trt(9 z>GNglhxhKEUYu9w=iRC7xlR$z58&}Y%@}R1Z-Db<?);*J^8+rL8tsOR-Pqp9&vD4= z&T_~4wL+`&RVR<~*^mLa-m2HD3kSysP9Spjt@{sNzJ5jfSy!g@YRyLc=DGUd>UeYQ z+F5na1e(k1S@p+%vQho<A8E2wUDD?l8D!~#tN6_fJN4{jxw8cM%}#sNAMn~m_v>d* zcQ&`2g&NhGlaIs6Wqj4brf5aP-*k|-DwV1QlYbGws_&P-n+h-YOu?W(T3KCMURo_* z@|dgE7S2vDoK5rh7o5D{<5Mr?+9oF}^LBYzW`Dn2n6q}`MFE$2_=W1iWHhPN;=kS? zE(!6~k+^!tn<4QAthIOd7v0HpBh9Z)=n-3wvRMgt9uOyU4Jk|IDnOIE5||Bo1c)sq z32a?350~vmj}aGXXe>R9Wm|COh|StEgycIsq!sPzTg2bqw~0a!O5=^9+lx~+Lwc)& zUh)BAqSx4viz~@A0?7f`7ry-ROFObhhB-h!c<_Lod6~ENxj?U7&!ZXPATo_=X5a!4 zZaTochNJ~chJuQzQk2uysK<L{=+Q8SsaQCU3#{Q{xkrpY(Q^0U?NkI{DrDkOLTc#M z6GB8AW!i(C5I`E1N{uE`pLoRBHPXOBrz)l>n>$Ko8x<B3vLTxaaa`er_+ZDy7&1A6 z1zA#NL+?>w(R)lw5>|C(OR|{Cyc7@x?=b_C<{_T?#Z<;1MuQlEA@+DQO1@EWh7<vM z9!W4cpulnyvA9vqS!7A6B|9J-xC^FUOHYk5Dd!6>33e;GU?^oab%s1*Njds7TOYte z94rxo0YV254Ps3(dbXvIBoP1fkxXRdV4+Bl5{o$CO&55#65sWR)XMc}6e9^}GNgE6 z1O&#F1d=iE8jbwb04yPdMvpQ9i^}iTK$H+9F{EbN!NcLmS<xt&-HX1nA}&|6!=rt2 z(6fq69w8P?lz0tsVRv_z8RALTKl*?CzmWa(ZT3I-pZ<NCGLF<}^a;nPoU=I(AI_8) z8{`C7$Z&dOZicU>ki{?2L=nk3Be3`!FAtEJZcHbJ<oHWM<ue0zbVEuTnP4hBQb#iX z?fQ64m@65{DVz|*`AB;<7<hW4DKwW?D@)5i{_&4VhB!Gn5oJ}3a7t0;ok4OC*lfqk zu{I|HWBM=S_mIeJ)*I$&rF^f(%CsTjLSTX|Vl~e8VB1i9Z4B`a$kn*rTC{oC9*3j8 z4apW2e}v%TbSAEmv5}!KA3VGP*Xot?v+m2i=imAE&+Z?*O5T&>vz_hj-uXrRCdb{! zMKTeyI!t585^2E&apR_NxlgNt#_}73@^sMaEiNysK=GTjlL-c^(0sTf*~r9J%P@)t z4(aF-(i8ybqD9cwmRBw(qd1b3%|8yWcFegs^HtVfl;GSOgxZ2Hf3GiI5x{N|Gk}6= z(kY77QyRS(m5af}uv+Q`Bq8v4wM-j54D$d+Ez?S?k{?NRG%*i0ZpRaS`7UC`(Ztcm zr~^u)+Hi2$d;Y?~sN$$rFb>>CNqG11yS8-)9q_0>>J5A3h$=7Wa#^~bx#_gpt{h5O zd$H3!zZjY6$)yS<C-q?Yuu!do9cAL<ALWlc;mwy1U?kGb>`cD1VOm8%G)_*B04~5z zw7fHqrkHATEm2irQ!iq9loV%C6(2zsLoq?~@y8#FEfy`pQW`)Eozd4f*XCyChvPx~ zZA`1!1>QbgelpF4<m}@7<mi}%`J1a?#~gOLM&_l0{k(Q{v^rcZs`c7eUwkQTU>>~n z@b$qy0~pUjcCuFH@WR3oH-`q3$|FN+9KYJ}{kr%H17D=8QI8x4BYyhy=^y>kAKklm z?|a|-9yfpIcYf#XNAJiS{*oyViE`R__3G6x|MD+WA#R3520p!(zU@xDMqm*r7ls^G zoKfC;?>)K{6I_|w7&VtqL1P$e(Tf;ZRLi1?&jooTM6~hJd;k7@_UPSe%$*|6PNV2e z2Z63VqG6hBnT}06ySvFNGDdByoaMWU#6m1Wk?JD-ClkC<&JdV)42UbxLYyqw!}w;i z(e3v3_h0Yq>@F|I-b@G|?Fu4;n0Fp&p-$MTCf}ocxVVTP^?9|o&jl9p%N2{`Y+$NK zc>bnp^m;ed3?|`RP;j`Dj)Te9=aNLPsquVN?P(WeqxlF%Ltx6+gJITJBN}W*$yq%Z z#-vDTu2CT%dgj3#9>*{FV;2oF6Q)c4FpmV2NIs=l1k){5NwoT8b*s^|9*+-?hU1ZI zhBa7z*EW9LHV*YyQT^`kZcA)t@I_dtph#5RRfvrQd*i*7D3I5a_#NRp?;xi+V;27W zpa1jlFJHa{6Y_)q?+<?d=YCOUxh&c<^!dKMIvRf-rr&d=ny*$|4)Yy9l{tS8-<8ir zC%#T_edRiW#$|G8b>-~%Br*1ojn%c|v*XdA*I8bKahc5TVB;-ydYsoYmqwCj)u`Dy zyslBL#rQ)HsyRHp@l~etGxoT!xnAOBAv@8K;B0L61>BrwLUPc&SOvW1dqzwmWx4+G zr=R6(!LmrQefZ&rqJ##<6iX_BB0-i~q-uzpwozdeVOlbtBA<&i<7`N8NOQ;3BaoI< zU_mBr%pf3z;6eblgGsSQvmT#AyY|1EcBkcl<|@6|SsISwWigezTB(_zVSFy4zp}Dn zgCk+;nzf)YIQ`W#h8E7=>be}cK;}oR?UHu?MziK@;GAG*-+T39eQndJz`p-_f6w70 zJ<>9NNYH!KQ%5W<(~{-JDoQYXG%EkGXAIG2V^TJ7vk^HAPE&~`Fij-~7heqNX+JwZ zAr_#e899~cDN20N5Jo0}TohY!km-dTk~9W;%tom`d2yL038RNJtx`xYAJQ;n#rE5) z9lbKuNkcqEuh+kDQmQwqHM@EFdBy2<J^IqpHjStVYiZ1rqA<jg$wHU}5}CXjMt!C< zd!ptX9tsg7HMPiwrMxH(#PUKRMF5W3xw|M5m?<F{(w!7rY>7s1(RQmYZO}_Lp+Juv zhF&u1WonXn)JRC)Ozd0UGWC#JvQP0ah5%9pKrEOXWEu%MaT@w5i)IxYMG2F_jS`Dq zs+eU42nZp<1s0YmZ-~1Sh=t1nLI_{5!{ExHbU{m&Y={XF4K#R-W~ODET7`y8j|pq& zJ!;5O9gG+f!f^zK;8T0bO!-Es({hiqapVz#n=pC=xf}=~A<Y12w0kt9k!(MrF)5QQ zh35r0XP;`Lyg-&SqGdpmMQ__89E=P=0wi|4;!hC(K0_g@i6It15xhq&?Jw5F*J$B2 zKDL_i`3v&xl_bk#a-0@2Pq1Y4h=L~vKzOz^HSOeVj&dZ0<n9^wi@V%IS%_neNIeUO zk>tDS*j~A23t*BZgOPcuk#II6(|e@I`A}NIVE-ro&;N|HpT5ohZ~mA6b1FqPBgh)q zoF_@3R|sHaIWn6c_r#H*==q%cfrIkO)`kfo!DE`9GC%w5vrto#UQ6F%6}9932~U(q zNTcG&PwOhR!_dg2y%#UnR#xW9?=~6AhSy_G02)Fvd@<D)c&Rm?fBrf90qk^AG()*z zCmH*3i7Aa6J8^<fGvWeM63#utA;wvaI(xQ*f^?w~rL)L&R6J|%(z>&RRYLvZ;&Q!S zb@D$v+&AUR%Zq4^kKIPLmGXQ&)dflqhWX^<&uon!efS-iR<onfA08Yt)kef@9<hYA z@|a=FgV6wVTM3MjI<6vX8yhZQwgub!WHgR%49>*MNHf<rtxj7&;z!lXZxlP{u{uA6 zP6%l^5t-0>8Z|>SijtlvSD?$WB@y37YcyJRZ8LyTJR@7Kqd<$KIJ3uL!pYBB*^0`A zA!3%6)W<?&#-BQ)`nXA6Tj#NZN-!95as}#TMNG=wass%l&ei6}m*eu+RY!9(bJcpa zS#K^>7xrK6*PHcPrFL}_|IJriQ)_bzbB@1b3(S?cI^Sxv=PPrUW7pJS&fCIVWpXth z^oD3UtwmYKFYZXJ^KRE6NadDMZEL~d+Zk&zk$>{rUJb*Z#ib<|T^C@16=w(T(ICFa z?MmtF;xY*{doz>oPdeC|JGsXr-f3W^Q_g?z!3Vjc$N^FM(T{#)iV=v3COBeZGZqA) zK%bjXq<ncnjzA&JzTT{zpI)4t9lHQG+_+k;mDN>iFKVr2h|EE_yxYL??ai%{%U3S^ zd5t&e;I|$;+&?_{(GPxTjiY?~-FM2bp7!I<bsWVvg-kc&cXoDYXOhiB3NhxBPd;(P zaXF#Qxn*T(l~tP2G&t#{#P`4deRz&@GdCW-A03`52FOwx0I{&RPCR+?1gw0&`|i8w zEpSPvM?($*Yu01tPri^ra-?xNYwD>!IXTN@6K%niZz5^NxkDX~G+fr5QAm>c;`S>y zNN|XJ`|Y=tZvYxzP-KW?qb|%O(`yybODvhl(1?$zvA$GM77`u~&ei7TO;G$HT$C`< zL-b7P^fkNXl_i(9*ZZ$J?M3s`X|*jYdaW!)iAFRw5`YL$Aqb*m4RU$^;N|(*;lqdb zU3UpbkN2yuzWV5+j|7lk%*MzV3znyDEDs;WcMcJYGdV`(Azyy?cYpWMqemu)UhX3{ z3+9eM^CD1qF(T&md+)s`$T`vGPDu4&CLJBb=LG<Q%vn8MhE#0kafCaR5@jk`)o8`3 zE3&#YlvI<ze*0pocFXc;j(8+j1;>)GPL~%KN0Z6n{=RDQ?%Qw2QHUVgEh06VeY3Ob z1DR&i)NqrjkR~e=m@XJhhDz0~SsV&dx`5G8ddCqHXE{I`1<U9C{ez{}k}RIq2bIBE z11o(Oy)JxbX;FPR?_PkHS62@9U)ezwU+Y}pEa^Bw*mIpbRVR0$c(3%v+SpiMzv!J) zAHR}YDvbJn<Kl|H{9Gkn)^e_2qqNhTf20Qum?g0zlrJc4tgT!7xsT+_1n~mF%v`G# zD_wG0CR`RM-bwPQ?|L(6y3LM^Jw1*KgRH=1D1X3HiL(lX2vQhD7?6*xR(#x)WGXa6 z5#PI)OY|N!uu-!h{^#fMN6QFjhFK%fkVi04EXhZ($g@P=o}FIUXP-TN@!>}wxLko< zrCe6+$oAs=5je2ibCFL2(gq%79cHS>X=6{e(YQa3zjWo0s?NBL%X6gwL3m@wbOvxX zfL~aso}9#=guo?Ynf9qm&un6;128^wp1(<uzB7**02waYIfN{1%`I}~hDKA8kEw`Q zuvl5qU<Mc^1mp4HVVr}*idY%Q&@+G;3@HBHwiKd>&cx>zf|3MyqV(t)#z<}IS2ogA zJhQJS#AKlqQj?YRhzUVyl&Bm!iC?0bU0GSBb}}*1!gx~b5+(G=#e@mB>=vM&1OgH1 z>7^*5T)u7!$?<>5sp3&2SgOv*sGQEOYH5~1l7-H47I6AJazVAp`I>r)oeGWdiO&Yk zX2@fDs=?$aIb_1HnUDk^X{Qbs8<H{U)6Hp1FEnJgs6X9IRstwV&W1Rv7HQzrf)a*m zl<13@w|DqtVUIXqQI^3<0eWFUoHn4JI!F$&$Y8_-C9>2`K50`e2=EGi+JG1`$qbPL zHUyalBQ^w|8VSjkGD*<DIbY~K=BPeL;jtT%lVBKAEFhK@2Vvw1`kYD$$&slXnG8m( zM`I`zefi~=c}rrFQIuMGN0;Ui%x3Q3LIc*4GL6@$hD-~wOI@R2+9e*qC_KtE2_sPn z7$qEmp<HpPH`gXdP}+*l%FjIIflVgsZM#Y|E`}kao$rV#vWulg4WLm?CV}Xgq*r4h zm3{Y)Myq~V?(o|6RW7cGe7zoTUw7JZ5pYyci;P&f9ArGP1R6q56a&K4asj5|!Gi~a z%p~~#_#gcl{T<-{-T(f7n<1ly1*9{A0?6}TcYbEJwb)shoy%|A)?3X%w>P?s-}G~R z(+|cYz1v`|9U%yB-`J(}nL_}5iCY9wUoD@erq}s~Qh`9P=zRV4*J6!0{RDIV^yFlz z9q%rt5Oxv*CRVl~AW8!mO)?v~wd4RQ1IUrk09x3VG<eC;*x>AW*1d2^VH{#K@UE+d z91%Lr@@?Uh6W$R*EZgwAJ`@4B8%FwQB5|3vEW7AQQ^hO^fQS>43pk=*7O>=VV8X7E zoF{1pn-Om2jF@<j05mBCuN+Nd9O4(MQM@40r0_I}C3wNeNF#)UfQ(f(Tw1bY%n9<C zq3}px_dGU!)|wFlA$dxOO&v@NVxwjOFZ*A=-izp!k7Og8Mu{l&fb`BIpzTIF8|8-8 z<+I8QgF#P~sMS;)F0*ZcTc%y`U~JQyo9p@OyMs~RCAQY6y5_mo_PYactx_+`Di+t= zjO*OYVy6>JSrEif8I?s&<dezj%8Kp9X<e{j(A0{LE*>#u<v{63dNVsynO|61S$0@- zC`32CC^|TT>+v;-nb|lQSoaQ%@vZmko2&e5iv8YTG#)nU&9N)>&}})YQqDz&RL}jq zAW>~*EqF`g(@#GI2)NV*7!}66Rymr(U=haYd}XvbYIbseGL-Wo2?3Pm)Pre3FVpfY z0`7I=564s%s;*lL^YOP&YSlVxkB?4nX0DG8kMBRYHy%y$eUgiQw^6N^UkJWhSziVB zM}w2Y<3_u=yR~z8as=O5Uc5Ms8)p7lvO%x!7U1&cXfB5R;o$!6z5HWQwMN~c+zc;u z7DwZF{aZ3{gynjVoRv=OfBpJ(W=>wi3>DX61MByCJG;AIefj0m^0Ev6xnrVjCN2VQ zEVE|6*Y6Mdee>=h#A}hab`(}{o^Nab;wIqm7AE0lfoc)^?ce_G`}gm|7!_Dk^NYXu zi_e}tb59dYwF};z5T%U-nHf2Fy?=OoBu^HXm*mgE(c!Q^aLtJPxW1BIyk1#aZg*Dx z_>Vq*_}1HdFJ4;6@T==<U;g+DvD(_$l)dMt7wyH?<@oCL!K>;*Z8(aedVGBJ;K9SA zqr-RKeQ$sN^^+%GKYsjZZEbxpaJ-wV)vCkc=<MtiytLT*(Z_%E=YH-xuU@>WS{(~D zbN2BMK7RYXw`Z<qR@PUpC)a!Xd-F5%YnyAAqswoeJrj08=7{}F5fF18IT^@6`6Kuq zc`av9N;YW@$cwA#Fc*R;l8{VAMj9kWumz1WzUHSY%-yhO)*f>+cQtc0>W}8D@!#FY zEicQ<Q}IDN?06*ry|jz7#x}F#Vo$OQFfFD4X7)PHQu!qg`DTTV21Buh0gJF%FfSrp zjqi-ls}y?HQXwl+kz0WS4ZslXN+>O5q0PB9$w7PH_3RAW<1$)aP+D1B8d`rsG8x;m zX3F1*wHa0xYRXo|fgCX;mYw<f3s~|{!2r6XA{w-6o!e#B!2IC!@$u=##@cW=7F6}n zLT|ShrD~_sW)k^=Lr$)X+<j7oxr>05ch1pJmoPG1?BN%@Sp#TkDgu3c0``W4Wq2z^ z*oDZD1)|jFL?8>wyZ!y%PJA#yr9!Du$2ErKj)0f%q_F`pe6tyU5I!3MeF|j1wZ=#+ z>HrK_xH^k1*GOU&Mrr2kC8IDJr3kSh?f^9Bk)y*CE7WmLbv!yc-re1?J=*cu*k~vZ zbqd`DXjXb*xH&Z=#j>102AA;MZnZ`kA9l{Uq20b}j0_8WYG*AZs{pt(v!mYT=+wt- z;_s0J>Wrc^HSnad!L?TI_4}4se6W9U(RrQrd@<*Z7vjs0&;+)mvF4Ehj2A1e5lDr2 z(q-th{E5eM0cN&iba3a@9p+YM`LckXmYAd2_#j3wlw*u0CK#siflu#}Mh@^rVk-{V zc_%Fe0i5h;z*-7yx8tXn%lSA`7d`=pW;2T&Cf6fhJWAD~DsnF+q#5FdjCQ&*$qiA> zRAl+6C6``IP{PonunQNDY_fI%5hD#t@}l8UZVmLNvtW2M31mxx9L4+QqlSPqk(o-+ z0Py4(GJSkBnsoz)5G{%GF&*)UtO&Rb!nE-#Y2ZV5kq=JE9@8%kuSZ@ZNEiXw5Mqrz z9EY?uATXgRN}nxRwA7MZfJ7FOc$Fcne4~+|{r@{ch?Z;WO-#b3De;9n8usipHe&>k zmg^KoFB&k0G*Pu8luCH6;UyC>nWBweC{htP94K3W$AocZ=yICmCsCPfv=obO_r4@x zj7I`-X&%8^Qijo`VMmr?X<;NJYspMGSW*ryeQMOe5$?N}`_&Vw<v&r}#LK*}dmP`* zChe^J;g9w5-A0d=27i&6T)l}VFr7_B*}~S+(p0?Qlpk5)9K4`v+|Fb9i)o5L*kfHY zX|WSq$v5A8Q}(;~qr~Oa!w}2P3=2R@W4K_U<(Cl{$-DpXH-9tK|I}@E|0?c9R4&Xd zsG^*qn}XqZl<xv5s?IAYWwk?FZNbqbj&3GhqPg3nnNt(vcRqg72+;t%BE0-*lG~h) z$GN%gS^Tb5Wxg_++<s%0kn!bhMaGzc0Aq;{jJ+X8IN*~YG1HcM(aV@dtwCUYp^jiM zj_pUd+s$^oGZ?oZ_Rq%a-s0}Y%eunuPUG4S&w3_>kB+L>w@T;@8mbrOlQ*r^isoo( zGa#%h?^=hV>v&66GxR2XN<gU>pIWsx8jl>yu5RLmcx2@w6$FUmv6Nr{M!-V;q-}g! zE5s&EHlyqpUb6|G!Do5U;N^7j>6ZGAR|4R>B`Zr;FQKLB<xIX!fa$hs^DARD82#jT zwhgtb?MtV(nDBC5v>M_|=JCoR$tWR_5w4k+sx#!w%;?JbM!7dH^Ve}S7J=D#OHz)_ zaZ^-<i@*gXZSLyQDVT$U$v_r5BKwaD$LN?s5@H5tN9B8lM8vne!r&XxjG#+$yHp_J zpa7P|9tNWktJ&u0%^eogn%^^5L0zob$s(}I#|Kf<8x=FtUeNv#Ulz!$>%nk!wd3e+ z-4bX$JA|#QIJ0(zLJT$a#nFiGPBs>TqO-KrIz8<!EwwK$`ncHZ?Az<b*H^05xxpZA zAe!Q(auu0TA4QT(cuAs1Ea45oi?f(JBRVN6B8JR`f`tHMPMi`WLatAGXU_BUi`TDT zbvldd>#i|Fn8U-Pot^Doug}MB*E#0e`mNL|`CYPlwSI7PU~QdUoHgss>CeUtdhy9O zS3!Nd*&L3?7iVV<S<8!yODik?_3!)+Se_jm9hsN+zxA!jX!KjZ{r`UZ?T5`){0$Xm z+hTdjR9>)|@jQC`__2_Rj4LR>BY1!B)z1BUpMUb{TxG%a<K^pD-}&$(*OJL_)Ef>i zM`JlrbK!9jD&Ne>V;NqsASlG9LzIL<na)>3m8rZ)p!~rPe(=k`{L2jZ7ysg4eDJ{s zkevGb^Uodh<3?A0Gn34B-+h-!j%zNP$7iQ5NQ*1W{fqAY(cz~*`na{&SzBJIx0>*B z)5?|U4xn2*yFdQy^L%0D(c6!Y4i1-AmQRmQdV}saPoBzY7eN=Iovq#6G#AS6*18Pa zPBypJ|L_m~XnSXK&>!s|yjqyAZf$RjhLf+q`D%Wy^46mVUwroY=H|M~)Y``C(ZR94 zd){-U%9n@Whbm<J9(8pxx;(pxpNf@5e7EcH<>26eYn<hyDG&<b5*GR97UY1)5i|Ah z;X^$dkwGQ`W(`JTFuXn=T?<_p=*rJ!SW@w2hMUWkrPYaxZ+YozzWkB|3vbkza#kaj zF<Pq7%GxR4*(u-7l_4e~etGEln1zFGZ!jL21sYVUrPURE(H1%*@~TBC(Y<bL5Lv#= zAm1S!f5}Nj9tnp>L;KF|7VvUB$@x-<<E1b4;AW=LYW6O=FwJ^nG#S5oxn~=3d&El) z-_wN*pwKZMp8bLYNm1_l)|c}YEsC^K7ca(E7OcV5)fF|wC5^E0cw`xMyK#UsDTL=q z+Ik@ktfzu-P7zKojG&n~^h^TNF58irEUAlt4O)7w!B`;fx~2dZUg-g!t0rj#N26K; z;MEAvQ64cy{?H<kNZ_CzG23EA-~Bdw3ehK{Mg_evC<Pyeo3&=VsK*QwMC{9#FHIJK zM&U`I8e>XJNAR|qox!lzZY`c)oa&t&`n_STUa>~TlOg!>YFw?<8_n8y9Bxv?_cVqO zk0Pcw<dI}Dg%ncW>NS*8*9>_~GXOd1XgpT#-eD%6DD-^PTQ$idCPvejbYEYqHmrIF z%F#If3U0koJwNN-#0iCc@t1P*Ygy5kmu&E|mOWIYsqg?P2Wisj$~mRZ5DBD}PbZ91 zrb;48cI4RSZ{&EKHP}onURG&oKMWw<F+?>*9t}}J9W8Re>|>!$@|Yt-Xwc&#A%%E6 zJ&kWmfia>{itSur67Y%-`I3r{M$6;v;?kyuk<8^xe$v>J1XQQ+WI?Z`8R)f4ROT6_ z?#YuUDjNd2jN)R6siECyvZpjk8KwspRnag`@ktM(O}R9p^pME(;3P{MJTjiYMl+a6 zNuW^}K}PS9RmrH=k~gIx^N5D1sg^e<E-}b7d6-D_TC!{GWRf6|03b>eUbdw)y_Q_b zPJZI^vDg(ah>(DnK=`E5!z4@>vMB+V0h&?MjR3nxG$a?1KWXS8v1sU1FM5qwFh;Ps zKp;KjgF_KAco-5g!2t3tCpuk#Ov#cNkPTV(8cHgNVmTx^38y6*nzRRi0N!J^#ApDq zP4BP(1e^g3CJH5XjWPO+m3&Sz7%VUvz^Z|f&n&U@AT#pAUVJnOy_H3yV<e3Tc6WDG zRNmoD707ZQoSLVBvx%EBf>;wM?vOJW4dWHF_<UqZRC{e$6<NBvx@K>3ZsEw&r_b4p zr5G9cPat{#N&-Ey1OYM*zIg%u&42uli~gUs&F<e^kFMe!U55=9f;=e9$5(@fm1@m~ zK8c^>yUB~zB)-@jX_0Lj2#k&Sc;h0ChQ~5(NhSnZ5N9ixbX8AmQhF3ea8?R1B)12X zad~}nMj4I^Un#~n<%ezDlcq<IDNRm42}Gq{lILgUqPE{vs8lVuqsxgTitj!ZQ=`aR zz5aK7z0|U04oG&IG3Khlw`#pU91rPAS40Vy=5k0lf#hWBs|$KlSdBkA!rpR?3(Byp z9KdEP3)OD#!lGBIos*1S#hZw?>w%JTtU??GWvb3&&c&?_Z(L|`0kYi+DK!qPaY|o_ z7d3)D+jLYd#YA#8j3PO|Fn`wXv0KFW!X#TRE~A`q^OPibYmN~&@e@;M2nn;w6r@J5 zvv!2&I*LfbGRhFK!lutT)$5%793MNiri*u2N{%B%`8Z$Ijy@Q6nhi^A7{3V|-^dja zqxEWhLmNDA-<+GDn2oUnwts{#^fD&><(FofvcTo2p|qz_jRT6xXrbn+bI?bY)2gLY z+O1f}_bBN8jmn4wvxaAmk5Aied#z)~NRE$2ZgEjH6jp(vI!|>ZYh<Q0H;1QBpEA!0 z4;dQt_9Uao9Q3ikcy!!Hpy3sEEa^oaZt~u!B=JZgyLazixh@iDA>Y2#WeA`ST5$q1 z9IEW|<qg&AZui`&75$4BdrR?mt!D4t+j;%^pnGw)wYlTq$jfHCF>tvY^&7S3*H52} z2G;4#yKleOS&Db{FM8*neeyZqT|3FIRjQHOlS{F&pj;JNjpozm&%kfL`;PfKIXj)7 zoog*N|M?&MZlm4USY2~<R9^D>>TvhXS5Ioq#;8Ad`1sMmtJf}*#|QCAY;n+@e*Mk6 z@4vVA;$?o@^Tpmv2Wz=u_36o%6>M0jR$jb#;TpWMxa5N5B6`-nsIzV6X1TMd2HuqK zVbbfuobN=UbbWpN@U3SrU%0%{{^IGgwapDzYnScwlT(zgxGU>xFqt9TUFs~p+J7zM zH@CO)FLHy~z$&oXWvkG;_(Acvd)AdZDp#x184U&&Thm5(ef@fGPo~<gt-8(i_0i?% z#6@Uh_2AV(wNX7gKKuDU|MQ=J^7%q-A>T)}ByB(H+F(4$@3hw{@m^WIQfqcv&%S=T zvc9^yw9*~)+KpCk*uS1!iBWalLcY9--wKWm*j?K8<7VzGD8b~CeN-w+P63yPd6PjP z4$oh{IK4QnSL#QnN7s|<cKpuy{QB1V>zA(`p8ZE|{uf8|xfz*id(A7Tc;@$A?Locs z3-e+|)MSwq)pjHPl+LSHubQp8nRMYF4#p1UdC+$yxagiOc9vmYzIa8-=Ek<TGMLx7 z*sTkz!18p3v!Y>Q-M&%%oawi=;!pdSjjQVk$z*bWaj7j|a+d50@%sUlxpHy7bj48< zM1$B|N4avXJHeqvPq6sx?d|E;Hdn1#D)_=Gp)<-t5)y-j1hEARIKMpR+C(YZStaro z>cpTBA)q~9Wsqz{!H|ib8HmvsHHo5;atKdr$zg+rg#iphgVIGhbs<KXTpAh{3Yr|y z=lPg$259K@@C+tg%a?>0^YzzXW5LcC#m7Y=KjDIy1U<3wYRfpvk;XzTMQOycP=jQc z7S`Av;^*^j(pqGSGZm7S<L1SXfG`6)I89RGcr8{Ad8%vXuzngJR*3^7363ODFXrN7 z<>hNDlXw|*R@TABmqx($!12T$h2yf-h%cuAgo3r4B@hhAsbQNH#7J<ZX44rte^}9a zAtpl*_3rxg#ErjNwQ;h{4$3O~3$f4{B8vD0<B?vlHVvuXdC^MYEML+dO`sG3G0B&% z^0LiqcE-1D%gqXYDoV>~1tgN{qAD7CJxh#YOyaaK@tH;R8U-*$wDn+0&AXm?xQI>f zG+MOt^V<)};}t-r%2n)Srjb~Z7mdd}KVa8mhi8Bu3tmV~<QYSn83$n0Qk_Pi9+wo_ z*w|2TBrt2`j2ymy|2}o5FE>`US)_oJKseP51E*>}8p;U*6P^tv8W_En1e$1&;1Rq2 z&3Gm~Sf4|XqCravgh@sXkdm=awP=}&7$LzZBO)ax`eY{%SB5B81bmvEFiLteVIWCE z1`sGAMU!OuTdj9l1fUmXu`#AwBvYei6j!>Rk6`NsW10$pXR1d-3}7U@$EgY}wPZ6& zg2(_gqmYD9p`m1hQH>BzaT!hKm`PXJxJFloA{SAL6@*No6y-7X5~wkZmds2^!c9oT zSkly~k??vd@-bVuQE1XIG*qNOia5?GFbrb7h7ukNjUKUp5tFR<NDfPorOhmf5;S-F z^CJ8u${N9LDAOA;7#=TsIF+^)k8d*;CVk2Eg`O@wVy8Zrqu4Dg<;U&H1-RrXQ{$7u z_E22=`-eG$4AT>t){;pe49YYnU9bjuni=~K{>h)wuRtGN-VEI>%LO>!k%;%j7UrD= zZ%NAHVM<9#LE&1AWhE32J-bEamikY(xYSTn;FO3_ZvswEV?$k8jt%wr<V?T1vJ`Ll z#d-)9bYfK=-IrzrBQCzKVZ{LdGuuJvLgukB1a~paQE)Vh^_;nz3r6V(zPk&aQK2*% zN8Z>|`BLg&@hjw9#&6ZiDn}j|8z0FbVRpv3Svrsql%<8%+j2iIM3+}lOyLRC;>$&* zQwboPUr6Pv1tU!>mBao0_07#euP5(}lIf6_sX(B}lS3LgkxzG}5E2YI)eeA111>HG zr3NXD^n_?IXfOhjJsr_&B4%yig~>!jW<ypNz!r?&f#d8fJ`;{cQpT65?!LDpv(Yav ztvcxBxn#Ti2C}W!rn2t%e)pXUEGmviLdKJ!$cecFg*kOZaOiN<bwRqkzJhUqadC<d zCfvl5IN5*A5=Y>Re(!2LaexN9s5GiImzn$-nEY)|uocKZjxv~PjcPqRVWt7mLn<*A z+p}+;hE?T@pteI(z*Gc+fO5*7qT;+h8kLVJ5F+McOJ=~G&XVh&@(zwe&#dEk{9u5< z<{_1Qip;f%c2ab-^#~9>v+&@-gO@K~Qju@zI4NRuk`ujefBV}`ljYZv<EUXCF=o|6 z|HY5L+S-aA<&M|(8dX9Z#50jhoa2PFvbCEXK4#rFB*oI&X0z_<Td!9S4vsc9)?i#- zKl$V{Nms4b-+ueilP|wUGwP4>cbG5w7b}Y^KmO{+AH4g4OIK~7_VV>hm$9wgt=a3@ zR=eSVYmXoH`jvVu|Fn;JF?Xj&$GZ>iyL=v=9Cy#o`=g<<xwN`mZ_JG*Lm`%ea&%+^ zn45EDwz|M0=fd)Wk*rm5h3nH#K7aS!cR&8Y4?q0Qw=G+8%>K#wSrp-Vd??<v%eCmd z*Bx|wDqcH&)_GB|$T>VXFp*}o)ozpK@<cL>g9iCFZ8wj8uXq2!gM<D3Tqj0%wzr?Z zcrhFdwzjuTfW7YQ^mJo$bMNI#la(K<=GRx>e9hCX-5puFyte94O1rC_0?W2~%eAiI z3VnF^dN>|ztZinVADtY_`EI}0Cb!cb_6P07j{0-a>(;Bale5#x!raEz`io~Tw{|wa z`25Sq?>rg}#wTaT_jc}AY6~vz{b4V^@jf>b@A>R*?Yi^VD^|qSWO&&dc9%OV{ZVgW zwlcmN-CU~qGcJ`z<DH}^GLcSpCcBRGSSw%V&kqDjKZidw!fvs^$mF?N{NC*P>iS?b zxEx<z-CVtV{_=X}dS`1#?Vg*N1DBs4vX&!)twy}TB`d6VD_spQ*NVBDt7~iDCBr5; zDc@z~FD<HvTf9xwVL&#@Ot6`;s7IrLD~x<zTiek0dM2<ht1T#tqHMbHDz%l%U=_&% zfy|X6=QS(q`HR=I$O2WU(^+&QP#srSSI*APhr_`r{^FWDRo!T*B=JFglTJ(4z;LP5 z1f>IP6+1#nc%=_bv)$Nx{Zh6YVgtQGnrlDHFCi(1VI}zSo}NdPX(S9eF^{{u7%k_r z(cJz#rseEPgNY;9^&z2@cj}M<vZRwntVaz&mS4Q=L?%R8O!Np)rZFCOx3)~WAyM)u z!&yamN=scZX>-^Re=jH6mtTIFe^LeSAOG<mfA4$WW4y|PK8+D8Wy;#WWh~MF>7Yl9 z8st<sMWL>I&{yHggB?5bev)qDMaEP^w4=cSCMv`3F;hY>jPijfl<>HOD-I#EZiC!M zZYz&<UygKwY*M1y!<Ri)CdWq;sV2>{Nuebt4oth!y}!S&M?lfR(Mi4-r>7^sxvkG% z=#c*l)rz%XbyycfjrwsM=U13=w_%Y_cmf)vh5(q9Z-$N#7Rt%Y8Pd!?GA_eNE;QK) zM49nNKb5cD$+zg@!%Bw8*CRGWilM2U9`%H1#0r8;%ZZ>=d1Qw4BY{VRVAM#!l>*Vg zXPS|z{ycyF97YRk?p)T)XR$q6O30SW5E2V}*i31eqwpfzorFjUmH<o>d@dRE0%cw6 z-SiX?qKJL{`Zd28j0PhW9u0ZaREacFU&P<a&pv@1&EB$O8zGso8QY9!vOtP}2IDbp zGsJ+@D~#wx7@Q4R(rDs5T~NsMU>JCC(g0{7kQVY&9XUA!FiHy~E@m)NB&iS<W~X6# zt>}-2Wr_qKMyZFNlI3VN+L;HL5y-?~XC9U?dd#pRCQu^^G6klo#hdv3=QI^#I)a^F zBxfA308pYqK#P3ii-gI38ZI<6f{DU~5{5vH((H}u$w8A*Wq{-nF=8D;jB05u00ANB z_26vqIU0Z3usBOEfDnu<Pl3q@&o%%>DMSwmNJc~Gg$|6J?>Xt#V5=T)CVNyf(W4;> z*^hqoBfeW`Rwx#hz;h=bwW;wMb!2J`NE=wFb^8}CQI)#eOuQOPkrQ}cfaRmbH6C3$ zMcAoXl3(YsxM(K<G5IJd%4mZjIr8R@VEyJl{)fnZ`ZoK2{LO#JLsn*tGJLicQxO~X z&5Wa}<C>#nvsPc<+H{0<J$50SxRxNYh26}6S;_irA-7~?wl^P*a)x6Lg)6H|bF&L) z=O>~Qe;IYIG8p!{7yZs+Yhk`R8V?)-Y!LeR*iy6O=%YH>dMfi(hc(B$@#P2{ACN15 zV8c-l-UWGXHojNZy*MLtayhD2>h1s+=RFr#8eQ~h9FF?>YHh(qX}&Vo9h7(NZ$v<< zEyS&JHZCoWSav8A)*p1|XQY}9GCmBsyt-<RZGv%KR%Gtrez&)@vTRF>KgDr*)oi!G zj;(~}YYLK5tn`sVCFAvOhWYD93X0eWb*uc@8?bzpQfR<AJ2_uc!4OQY@c3X-dG9pe zUjjQu%R5%(hFY!H^znMNeU_!=^pGvB(o7Js^iC^+iHjWV^&h|W$N}0qk-l;fjd>Kk znVY#rGtRPv;Dtm3w#UmT4GhU<M$&~{Ie-KZ?od^>;kliiE!r)$^NS0M%(36{b=CRi z>#t=`!=<#<Quc&^l>#zz6<=%+2SFnrOuI*xI4iT6k+~TdwE!E{xao<X*f$z2J-=P{ z3`u;)8mtzi!!%VGi4}o-f6s-@-1RTIq8uN9F7G|Xd-q~n{%FVC{LIDK*+Th^X&Ea6 z<29D}ec4H;y>xVZ5IH$NGaQV?s@05N8r<C6R06~~E1GSU`|3`XPWvmQQ|4Q5z4hZC z|Cl`@DOP-R8bD)I46_yhuxJ26%1p-3Zb>whkeoGN2tsN67E8P#V><XKP*}v1E@{aa zlWu6rs62^`es_2K_?VG1<?oa(U5y<#8)s)1%gc*KT{*V4cAh->($R2zeRXAJ?Tary zhrfS+SNaV4UG*{EG$}<hO=USlWeaBogoP@vQL0y0mrpNFRREM+W+8t~C77LHcYD4& zMn8G-gb=*0svmvy(SP}0{L^>ed%IR`SluEo{`pfkYKS^uMpS^?_wnXpTNQSBcyMqa z@}fb${2?$k66;Z{#Gk<kaz(HzM>EM8OoAJ)#1mWjyuQ9JbI#6A*Vi`=4-YKd<>jS= z1Cj5T8fP8bfUN{99xhi-lbbu6-#mSCul(^XL2$ZqZIH3F2%Y$_jbZFzFyD_)4rvjM zxb}biajvYdzWVB0-};t0C4^y!QL@(kUrp<t#|LFO^7!#%lmKoL%PBNT2@c=K@#Vut zqlsm8eeKoDz2()F-bL3XTz$)T)Lm26nfR7MyzF>0nvCohq?u3>C}J~dEb+*4>KLg9 zo2+Yh?)b_;)C77VrC&+rNC0@e9MAB^{N{UKrRLYvb2VpjebGBVKfQSGgLhAl&uqF6 z@4t0)a=7>6)x$>*5UbrPnH*kPT9KdNcDpHKorPF$)yvg#n_z-%CBCMcrPXqvk>&Y@ z;nYH{h>bIxYdOGiLv@nJwm0VjbYRKdb&zscfA(y1Ys>5|ROcCdaD1Q&vVnH?2)|pB z{^H`yo?>TV&tT9qYAVmq;v$z3<GbJpBki(_F)~fY3bNp^${o_`gSWLhuGnv_Exk-T zIXPWfS$1{r_j}|yl0|VCkMsMDJOvXjlSy_pefaQU>LoT~E)JSga25@!nItksv7p3m zvOI!GlSt^}Gym~h$}6fCckCTt(s%*h+1UZ$!pjoZ?~}tL7%jt#(rAh$M}zmMKxHW6 z$E(YyyR(p5ch&+gGGb^na##Y8NGKHz>)ohuz5Vvv=!sQ)5D>_6kJza|4@Rj_F-JUr z;-N6)_k{W39H>uNKk5&hF_<JKOl661F<!VxvnZ_AjCm?`0VY2KlA+eXD47lL$QZCu z%j)##STEA-G0U_|3bUMWEU98o)>p@1?r;Q4&Y(Oo05;<+Om&bMWG3N7pfNs!pIfTf zdem5(jgR_nH?FVjjNB;ncysEh@Q4OH^@TKgJFT{}kaLmKNc`=_W+Q*0Jzwg|PwPZk zh|h?HJy^JJatDL>Gn2$p$^ebW#8MqL#|r{lvG0v$R2(c}CTWZzK`Z{oX!3;HcMVNC zzPr2o*=L`bI~Yob!}!bF8yg!EiAT1o@@?e!l|*6GGHzN5$sha4_NH-oQ&F}=YUO*) zKe_bENi5<CLo%4NkcJTC#7*&F03>>*VxdJ3$r7_b5nc^33<-&$5hewuD2)oEHoJVB z8cd)@7dYodl4qTi&&Wt9mE-mTrX_E<SIU0S<hiJ9OoXRND3LJ?K9?Ri@i1u22nz`z z8Kq_@R}ErfHJCREj1mQ(7NUe9&Dtl8<He|mGe+u=37sici?X`P{8WJpz;X0MB^Q=d zL?cYvprrwC#++oOM)k|E5T&6k+(9$7ISeZ8)|dDsmyEC2Do2;YxtsY)ePP%eO|HlD zGYg3yjQe2gD9`+P+IQ{*=W251KR!KynJGWMn160f&>V+UBzyPkgMIz_=7xU%@L+jy zi8PdXf3fddv+R)%dS-`V#b9C4TPd6sQjUn8(U_EB&%vPD_{q`Ya^k>aMEYGh(~gFd z@_nT^Q=Oj1H_=|cd`<%S8EtcsktY*gio#fuCXO@&|LK4BXY^-~{ty4>{}abF57U{@ zs24KfE3bRT5l1-m4ibu&vZZ(38edLelrWa%TncV34>_bv<bElA;fc*92N2frWa!%F z5=D>sh#1Yg*Tl8K6~k2l9<02hiEoIN1I>B&Y|tAzQmibkc9z=vuMWV~g_?^on#=Mx z`(|dZU6{uM2SMw{N^nk{b8G1LMYCqDId0ioO@L|ub_o3D`HT2#fVHN>OttE)IeT%@ zJ2^Sp*w|u|49@_nKvlnElN57^i4_&!`IPCbju!%)r^`2Q+;iPEU4j-|mR$13SC{cF zQe|Oy6|bD}Jr@ZHnpI@(O|zEirIm@e;?4Ed?FXpDQyB3|Sv?r9qGL3dH-ja-nKC05 zfGci!uO*g&qpH~fyBJ#@uEb{3;Z^3T=1j6UX*5}2NG8eYNZC^N8Ag6o)hJz&@$5ti zD0R~n#kC}UQiTvKXpF{U=*0yRpy#h4^eLPKnDDt=n-OrTOhlZF<7EPR%1_JWRWsgf zzrI<hRrS5$z$nM@5{{85l0Bwj8DTa{Igc!7symp?0)aEGTry{aVJ}}^ahR85=Fg=l z^DTa(yEJmFhp`R5Out!oh_<)ifAGN3*2Hw28l7g!*^Bp|eEh@J)pb|CqoWh6LFSyE zN`A(u-R{_`o+T{};=DL5D4HN-qtsj*WjT+8%V@f(5Xc06C4qX1-kCre5T(}31Y7_+ zG?r#HKHz5_xi1JBUi1iZw<ClBIVlcKkdENsq=&a)%bIr3cVScI<3lWrHREP)=6cqe zU0Gf`IXzlkS$D~Aw-#MHT|ULI*BzKknEs#(ZnZ<8vjTgF&7Fxoq%$L@kMUptBRTud zqsQeF;_>E8&V|NcLX2wcoE8%_4<5bc78-x=hXswM`fP8q(d_RZ?CflJI_{<2{3f&N z5N}^B#G#)+qB1QRLwnkpRm&*VqM=yliPj_Y^iy8v?`O}RnG|ail6NA>Ff{6$_#7VX zudi+D7dy*&Er0s#>w2x}xSYA?s<XMZesp-UxYVvz;@udLN!8%=F=3uEQe&G7Fm(*J zop2n|of)w(3KUa0B`x{I9lSD}5MmLen}p!9&67h#$~Ohr8Gt6}Z)Wnkt9rQP-OSG9 zPf5jZ!e3u4wmZ44Hd@U*Sfm_`0P=-`Oplb(MJ5azXmM=dYyl!rMSCpa)3bOHK`LUD zayh@l;h5ne^J><Xe>u9Eug=vgjoF2n$?$SG8FZS9^;QiG<3MoUi$C<D&dXkPyW8zs zi7w6g^HJ(mt=3R*dOg`CC8EZv3_>AXv{+DLVnWU44}bW>d-v{{Wp<iwE(CF<yspal ztLy%7U}qE))pal$##Oj{8Ap6X#*S&Hh}s(`0|^{g?yQTJn(HpBz<kXsG28HqhUv3d zsG|incNhlFsETLKz9~iwp9_3A7++qE^FpMWnK7%ug#x~_*wQoGYRy-C1eOG?g!=Za z36JD(meQQWtO=Rbnjr)*2(;v#HWCuB87f4|l<TfXF?9L#NLrbiYw**jPn{4*gOp{Q z0x%#IS!mYXg9i@~r;!@oY?cyw#z2}i5inVntxb&(8X0dCBO?W;*@(3%R@{W-4ge$V zka~|OF&Ywi@v%D`9vs_^wl;UvvF=5GduKCVm?*ox*s5>w*_KKCFac4D6~i)sa+m=! zifWRH&7c9$=;vmm0#nUMQ>h0}<2l`w5z9KTlPLM8C+CkIKRnn!GQSt+J@%MW%P03Q zXD4AX@6JvHio<gGA#TR#!7z-8IF^Qn<ZP{G6lcaWJ6&Lm70opm#4rH!0$>tA{L?k` z2mq{wPc248Qegxu`0;n0-7#u)XAkESD?(Lq8CD0ak?Fx*T&$p(+4*|;Gfs4o28h}d z+hx248ed6>!V)hHFo|9S{a%zxA;mJ?_0s+{?9G-o=j_W;Jqw8<mIMUpSCSDWRMwGG z1cAz_@Fc<cMf{zVlnIb+`DoN3k*G{*iKizYW=iid6PR|5F?6M~km(vZQ+oI`1`LlS z0X<8QCF4|!AixugAX5tlUX&7p7i>~284Jy*wPwCvzI<s_(nXYpI1R%~VDf?qB!N<< z(qb^&7+*Pi<0`Hhyj!qwl8V_BIyDf&J}BB+nvsF>NH}Q}rTqeKlscobP9*6y1tu4U z@x)R`2pV=`;l2iG>fzDTO9%|_2qy;@33>ukOZt)xoblJ^>Pz4CQy_fGD_tS;2(L*b z)fGU|G{}HzC1@~CCy`-z^CftIO^5r~(WfKf*3A4^R0iXl+3R|>QEODe?ilm43;8=1 zS2xb{b5TvoY2SXGw*dFgSV!?mtEQ{0U3+6|Gw%g3Kl<e3jrFb0(xSboH|XaJQsdzW z<>R*=xiDLsM<>VkckfxDuEeU}WMr3#7cAJuPCc8MDvV%ZG+!Q-8ZO%tPtVVmm*Xoi zh{ZqNb%>=JfA8AFNptik^qro%13C+xoX2O%vXP({0X<&fHPM9Mzkgq;6g{#14}bGN zig5qbZT_$S&A%}l*Ee?!ip#$OGXM~uHIDZ+<983h{<T|8^KyAP8M%zcU)EvYT&-HU zR`tk}=U10kmlN~>+wEp<LYkSszQSmya+E@O<A!2Ga(YnX#v?`Rx^Tr$AjJopughBo zuGemkV{+{6@K_~Cs}Vnl={O;q>eWho*eKril!oPp#%6CUzBs7IRk*y<k`I^GZJbJ6 z+?;#LPkPzO#(L=ZB}k=zGIl~|592YB#)R?$nR}*Vx&^F4UAk&ZXVo!OgqBbzT<BRE zIes~bKXz1J>?(yTq!eVlMDHIM@9l!HHM(O9a_j^dz;XF=kYg?i7YoO(ngTdK3)$<Q zdk&|ruZDvjlL6$!8YuR}OsS!<m$>r9-{}E6ZkLIO7=j@MO>Z8A7km8m;6WdOn;MgD z;^SBgdazJm#}^^vpZhiU^%*xNQ5Oajy_qvtm+@0lj4zL275cF4=DOW#Fo_Le-W>Dh zBt)&caB+G{QJhAs47+-K@pZ^H(+3t+9%Vf3x{iddqfvP>6(vb*FbZ*P5U&V2<wwOW z6&MrRal6%KK>TcUeACLLUr}w&NiBsfdb7>Kcpb$*YlHR0H3Ai@P*(PuPTRJ64&Zse zAHN0F>z!}L*?O?PZtqx;E$C#rx{$L^a*+_riX5ecN%`ns=%u)%Yk7-?uS%r*iJVrK zmB9FXxc!|4Oic$N&(F`|bI7B(*Ogs4luB2%=Ir=*YjaapzkdCy-|Mmp3s~l`lP)ae z07S(c*|6}&<Movp;i&{`HJe5m!!Y(h${;X|`bt7S-moe^799tpm@K~YcNBjyYo=DW z6JJ}8Hkd}EUf%zV1!{jHrtG6?S)8a!NsVJ`*?VkS3jz;s{&JhiJ;ppKsUB58TZKM{ z!rzN?HaJ!5O$y;|tlQ<U6VpyIAU7mNnv%7Z_%NFtF)O%T-(wV#@+%Hfkgk}RVnDuH zp{d+VrBNYf0Ad>?B+5vlyN_eB+!+)v>kx<)?IM72eSHnr;!=Ef5k5AI`SNkEc!}gE z@1pPsQez=55yO?vqTz^If<=z2C^9;}ni!FDR8@Fq7v?JpRln~<&Z7CzFpl^%Vq_1Q zU|yFfwMBqfW>W#C%Of*_vmB=g<{%O1&oAO9g@>bffy^2fjf-ylx$iu4h(OL-iB=ri zrV~U0VvX2(J+2LATXl4P4|guzeq+N^zAN$4WE6u;34n7^tyY(kam2fxA+A=fqvoTV zjZmmE;cvX+X_p_Lot>|)tq27lMU{{3c6{kkQQ;#M@J6ZQA{BfY3~s+gucghbGHW>V zGLr$!i3Yn5p^p@CQc=O2;bK9}xl9Lp2ne@BS`kQ^C%9yaBOzC=;|KFa1EX{^TCE0q zM7|u3S(x@jG|OC?J~7OxEFrpm!BImnA0KAPy)e!{ns^{Kb?^x*Bk}fKJwCCPjiMke zEt7#p^f{-LlDt&@;*Q50&1Oi5N-%HlKN_TF?(&gFl;V?k4LuhqazZ7oM8?@PULQ}t zaM6wuz&7-HkBH&3wPO9<{wzFE)_6RZ4?QLs<5PP&Xf0?NE~3&}Fm>SKP0m?(7ZqR> zpCMA6IKHwHS4U-&Sg|c(2}+5o*|Y7D79%Zbk0JJGRM-zl!=j~~8o)A>>%>(nRogzB ztZ)etADXP!J-W=<vjC8i%9+KfMfTBXb;Oi8=giNWQ%-?7RZb7ra)2)LqBlex$5F!Y z0y3uguCXwiIh0N?C_PRmRD42mxu0u*P+eAm(dir|arRSQ_zXCu(%KC-=B2z%!t1ak zmH=<cV!td-6^v@2g2neJBC}weAIdE`b|S~FID-}KK`y&31uL%nVqVN_8lVwKG6OVl zx)9+iOFoh5wTTm00IT51N!Jp9Sy^6}O6;-QUR-nm#u*ZCv6YD7jp4f%?}-!%@Yx4J zxh^IqkqlrDe9jAGYSh3HkU!m$AbX<Ntk()hG@^{^(@mIEq0hB29fdJ!B_dP6VaV|) zM2tyFLsJVik7h6#0Vyi23JK+Xc(hT2?_TafsV|k7kbFU3ZQ*PbVf1*jfm1&19;c(^ zq%^!1xZAG<#m=LnBUer7&FqW=;#8;cLfWT<oMJFcD$-9I-YI*M6#)Tg@YzVdh3?c% zx!9KKG|SiaiXFXx0}ueD7m5DSQ4W3ag;#aC9E2s3)4pR^429xIpYly4Pcd2XGdN*F z`Swj*(U6w45;EgnMjbi90bi^SG5*ISB}GWp6NX)!$4hnUiLKDKg;sFzMa;{WR_dkx zn?H5WdJ|rS=XxgomcBCxm-(ed$cp>eV`|I$PZkm3;cuL|uS_ILLzY5ejOA8}vG~U{ zaXPfmIA+XQ>lnl4(xxheP7gzJzEU96?EJg`{r_H4{*-P0*Z<~UkJ%{ya=}KJ%hA8& zKop()mqWHsa5)RvhU4Qvkmd#^$r9rqdIX8l$IQ*ep;-?WJfSflh*~-<g1Nh+#*ZN5 zi>w##+6Nw`MWRP$)nN%uCC}0&t4$YNi6p1&tc>$WOB`h4U9ULakrOPpZ%RZp%=p4< zX`69FS|PmC6;nx5q^f`NHvh%Xc1Ai+j7B<hHWvS-11d534>ym6LM;$R(SXdL0T63$ zI!;_fJBpACE>-9z&W>?doRe&Z(x@m#c{eG-^WPMn$_K|<y3+;kF)4F4Az>H>Hp)DY zLc&_^hx#|-pk;7EN?Gb21+6?r#kpO}MNRSsve0M4rB52WzS?0nO$2vL6F@`%CNCiM znkGHilx6uwtUjuVN${p>j84quZ55%2nJ*rQh)J>PVhR!Jrx=SdL+2m2*p;cvH768@ zA>!c$rx<n9YBp?*>V<{sV8=WP820etLzvtx<hHAnh5#i@dNgewQ6kff@+i6TATA~z zxs!2DJY@DBNdPE$2&(a&ZCAdL8#O(LhX=i0cX@e9FYp8ivmVSrjA-yOTg2GF5*U^X zZ!s;xPN_a0b9J1YoY;_fq&DSM4GXgogbf8?uxULke<Yo4?4$_0M}Xd}pn=IKF(BIH zwg^CKNe?r1GkIZ>tksD>Vzj@%PlZG0=H@0D&!0bc!N87-c`)EqA<1Cy$~qX1Gm;lD zS%o0Epyvgd@4ox4ix7+<4Lx=FW_#u>nSv$*(GyZOxNu4Uaq$r)gH65pg52BNBLUJQ z`Id9~NDigEGlbD&=1-=Io>(nu=*`cDz{{vyh8amT>?FY`K>p<QfNBJ0Egy46^jfY* zk4)kPGFmdo@Tnc1C?;VSE)tBUC5VxcpXN;s25XRlMg>aR$0H>o=!?=g&c@r!@gkA6 zDJ7yv%g=O80f_B0zD69SfOqf+tS`Z5IXP*qN48-h69!pGF2w{dN@inZWcor~%Bfbu zDv#&^cp;M!rI=_&bAHjN@M#8EV-@d`g+Of@F@3t3>X-qB#Fbh!0oO=in3lQ#h|y>O zq5wqEi#JC(%jFcC0>S#!o2tP^S)Lg5bg746cs&9Qdjf?j7>%ao49mEsg~^hm8W``i z6&Z2ymXHF@+6;b7dU+>`1bC~-BYMsnLM5+~5<4$a6!`#;n%G7x%0%xUyv9frAsRR% zDZ3D)Qe@a!3zM%tBtFb5LDoD%YB`mLa?<Ss=yPgVt2df9!xLCsk4BVM&Z6;s4Wb|k z0q`YXZ_<b&CmX#h%kjMrG;|q7FI;G_fMWvg?kAc_rNVsV+~HzI_DRWX#0g;62q*dM zEPhM*)vH&+qF5myfr`Qu4ZX%S6U*!psE9+3CS_vGzLxSy4y*233el1=XE0$vPMmb% z9V85202m2D<B{Z4q!k*xu_ND^dfT(Gh?VMj*tpFQlyOYD`N?$W90h-QRVxfAdOgC! zP@THaBNiWhTB|SWZi9nfGqYGS<pI)@5N5L^iM2cdVsoItlI&Da<dJFy2wfs`6p}!4 z;ESH0tlu!bEb3d~g-bK4&&R@X`<M;o6a$#L1C!FSC0UMYEaXl`kEe`b(wpoW03$Mh zA%MrJk!-2f;x+nmOp1npsLUB>U}R(vS?*%h$vE)X^jfM&Mh!lVnG&$XBOzj_8HJJC zhyiqEkdwIRigN`;8jMjbjX{is1h7#se9G5?|1Q)3Ln-aeUbFPTXwup=L$iu=ZOSO@ zFaQL~8Tw>liJli$g!4&y1c@t!lO`|FXdZFt(<(sXJqGC=9(N+AEr(P9)m71uw0u#H zkk#r=IAi({hyx7OdMtV|QKQz^*Ac6D@h0ueb#*~{MExhEsEzP?WHuqV*qp&6(D6t- z{Fjtv8%LIB*L>|DRI526Kx{~ewaiT<=Eai4gUtEF;Z_nVTrR*%<~fhtfA8P?H*x*+ zE#3k4e;m*N%#B$pWg@N5mNbyX;@d*0K_WJPQ~C^qmZL%snKB76n)J3EK;}mVE(I#w z8Dbdh06jcLdTBSBa#Ac&ra?cQm~0-=Bw3D<Lnd80i)5O01f*%{7aB-30K#GNc!3NC zSt7AZh{R|)I&En{>Y@cEUIV#XC)4IJ*-=iLN5ZeJC-q7#K4^7Uvj7^g7MPyc6rSvC zE+6)bh-HIkr-q9_J)~YJAdPw~1wD>X7$He>1Q7?ak_JE*_OR>?;f(i~0VEJj3QQWX znbG@y^0Sr42$bL_hFC2v)Z60{nBs}m-pq{@o@AOw1XCCR`SK_6C;?hptKiB4k0z8% z1T4|G0Gakc=DZM?Q<}N}DI5VZ?C>6Q*90_Mb?2}0PHfDG0}U>cJt{y<5^6$F!U(uH zBOrvp>?1nGVE9Z$!coE)O<q89r5yAyv@i*=A!Huu(l=@iCmus8EXsp}0|eXK+hC&_ z7IHGwkOJ?~Y?4p79t>kN%}W~qhBS`rGk}m{0)|0mD8(j?X4KWxP@ezb!O5jQ00=QJ zdR)q`h&5_)jiE6cdS+<o2?V6%G!GD;rfW8r%9oKy(AYzQ>W@Z9J<>}fQOt8>wv+^c zKm==RYk1*NqR}H32R*}tR4`2|Vl)Vd)yyN+XwpdPijA>69e0U^F-i*zJUPfRXdcb4 z4Te2LIcCFv4Qa?orpu5=u(+j1NnnU!Cik%XT`NP}$&+-_q?=T;HvJ+WnaGd^iHth{ z7N(Kx!3eK`^;}@HOaP;V#6ksuq~S8eupA{er-SjddrV9sVc@Y4;?@>_O}e}cY+@lR z)hJ?sJEr)=M0{|yylsxs@+z<KMcU{Iq?$W?PXm&j=rr%u>piohp*b%<{DUS92<c_k zGFIehON+~hBRk6_83D(IG>s<^27Rs?NG_6qT?>=%e1}9#AWT{dpW(vG$b5uHnG({f zjDON-*pm!QFHuRau}V*cQSO6zmnvZN#hlQd6M-Ed)ASlQBfaAf%SA&lrPLD(fG03z z>dA-H8}*o;7GZJBO$))vXsB?-dk7XXYmMSvU0s!*DOnadU}5nHj*nbk#_f)%luwk# z3wecI<7Q%vGDER7WTrG+hSDkk3B(fa5k1}rY&CKli~t^S(q~wvW@j_By}gAPKmyey z<a$@n(-=cJ%gN&Z(^~SgN<ik?fq~B<_}j-y{7^PI+VSzRUZ4mUDDsJ#N&q;KgpsrH zA{XM!d5-Hb5}3|v>A1!(WB{rlS<VGB!k(l|%ME4oL{5szKJnNSqtV5-bf0Q?@RU+R zGwrpMpO57;a8ZG=2wfuOp-D+g3`u?s0sXQ7H!{-|#N`j65gA>)-L2#@lJ7wSfW4f= zM_N)8v(rwa`ZO{P&NL9%DFHknB;PF`7HZQFp&1N@>Wwu@Fx6s<o&8obN@S@>BMqE> zWh$m3G$=WkT0+^KIt@))lI%r)6pCa_dP5$Q(P$#|DIr@LkS$>}Q_0h2C>xk4R)Nha zVy@{^l$I*=$w-t(J%c?W^9aa^(~@fn3lUyZ7F}s61Yd|N<`rKfB|MtJ;>Yc4D1?Y) z2Gb*5NsLlH%jyh~N2AH2*ODw2+TCdlSxyH=Vsjxd8%riLvh)<jqXxhNnfN!`lpu-I zPP%Bx)B;auUmvMZHW37daFrr9awHQXFiSK9Nh1eS_?y}jfTS_;8jMHiBuGrs=+%LZ zjSYpDc{@8he2-{WZ9~^AMkz{3pKxjfWQZUI=j!^hG9O2plJK{N0ob1>uBimZ<GQ@M zq=Q8s;TPs(Yc@)9yVWUC3gOOEgaa&;2z^Op|A!@w$D)>k;c?NWht&VZ-~GFQpT3ok zK;I=z=r4<wZ&Qmk0GcFYF$|joD6LGcoIH#<nnRk9<s-bu6pPFOG^>^AFiNS%5{uh= za^k04wPu4I!Xq~EGojUr4Z)~Z^xrNREivw#@e$kkIc3bI?Sh4IzOvvke&yBS-m<Zc z-CVmFUB;)8gPkIN0ZO{wmbMhG0a&ORYL*{4C<<>IYZJg?C`F|Up@p-B9>ypMFcL^c zCYJ_JV^J_(Y_;RVsbvY>4j10EK_6mEiPU@K>J-M3qbQRFFMITmh5&ln0VYnLl=f8f zCGsg>o~0asp4c}VdNO$d$d>q`t6ZFJ(<h>#AuyyD7K|Er+S^BxH;Jc|3@ZY|czDvL zeociV)4=fJ36s{M!Id=eDXLO)QF_c+0a7x5@p?4s5zH<C8k7KJDL<`6h6R8{7+bBT z;*iqdu>e@2<z+aB^d#itbh0#(Qw8DhFamBa^3f1ENtx_ZVn9{|I{_gu9<i9y?pgdf z7J$<~3zwId%PlK@hZDVqm%yoQ4y-APkX*}_W2Ro3rx`*}42g`ADh^}{LcaYgZ78A+ zy{yoPMTUiB+p78nF0qX$0X!m0r74{8F#6@CCA>sUn^8?za*nbkmuB-}HX9&4<|u$J ziZqYR(1_x7rXXNi)9KC2At8_{#3L0BrZy@rq<rRyq${z@C#U$1*AO|Ur>D87^BrKp zNo(<@7bXQSF9489Lx>9=SVK&85^EmyBxktT&rN;adoi+&Y6d_Ol{Qb491?7l1dgOY z=1sE;9uiE5J{7^I4H*PYtjI}400c%o>ZzjzWr|8NkHwp?B=L~Q$VtiZx#jX^NlKQ^ ziN|tz6`t~vomN}1kyV!vd`~YlG+;DLin%Nk%`kIkY6z6-B%6*TNbN+WJ9tU(NMnH` zm-4kLT8J{OFwD-pLW~kU`DItW-6L3nj3Snp)8b3CWYl0Zyg3(G2uT)X9!UnIdB~_n zU~=EYgEf{L!U#a7Pl0(#NE-GKVkiv&WA|vO=BTNcC-w_STt>A7vZop&VsP4@(o!HK zAutRp6BI3Z-)!SaynG;rNyA9f;gM?Wfc$6%^DG%@{QTJquqOV9DaFMGG)3NRB}b3} zY<J?bHb$vVztUPm8Zwv!h=L!)&p<>m7dJzY+#~@POe#$+SYS-GWB}u(1-*GMzk3vo z@04orV2x3T0Vyz5q$q&I5DiF*XrX#xKB`K32f&3_DD*}l2{+0fL!HGAQLflTAx6O3 zoX{jdPdJjq04QQV31rfqu;8c6Y`C;!pO5cQgi>+<6zRc6GmL4W9!$HIjN~9oy&ki9 zOk)y8T!}xg81Fx4<w?gaOpkB!CL@Im32c1oFjUOO_Zp)S#nIwyScR4CtW`yD5tyc? z{pd{}nOsO;Gz3`?3fE806-93phkQ({w4~|vd(ib--CetU`eUJdu_ZqAgi@m}Dam0Z zzw{JM^(Gl0g=>iQ)5mEeA&t=sRN9vEry<e+Vc(zLFTm++;=x){W<bE&R8$hc>#fR! zC2f*vM5VenWdcMG3=bv^vYcn*6`!!99F{!Z61xJ$D{fLHzN?~6V~5vJqS2G)G1&pk zOM?j)1hz>(HADkok<9jMs{qZ^!W5z@i9}_#rx`{8$RLrK9rB4n5czqxE(~diQy>DS zzS&UfnW0ZP6zQqJ0-!pDurS?`1~cXJ3t;YGq}ro4JwHGiN;!BLlJ;OpY15W?0Cm&H zVr;a0)Jpu~4NHs8sSFIDOAyABvGMYzYj~Q($;AxDBumx}uwcY@_2a$SC`xi$4NQZx z<W7SRAcTjp9t#o;7?P#5G#l~itr5X-0jA3k<-_vvim5v(N;JUesldygoI8{9Z~Vq@ z0Dk&*djU?B%uQ!BT9ZP1lOQ7nNHQ==X6cii(b>Qndgi7yaLzr-%W>S|a+DB>l4&Hk z9+7ESV2}YOMX({dus{wYg0YXLNmNXQhhd;UT`Y1Gz$(PKu_4yrZBR*UREp#Ym?DoU zTq`2O1&s0e*}Kd{pifcg^)QL_7_Fp2@}?X^X&6j$<s%?mzPfC;;_qd_q<k#NXmqO4 zC|-cZV2Pb8yeN;NKtg5=UcO*YdXE4EFes5_r3UMnL<{7U3@`b~n;4^jghTzENufBb zbqE-j*Q9PSTIzxUWCN3sqkN+-n;|{RSz`ZAvIt9Y4NN<eLi*jtqlc72Yinys0D~BS zkvFwkov}PXRgT0%)7WY?T=R+{GH}F3<qpkgbbD_}QGk?>Epv};0s^4XX}i&^PsVYw zfuSr7LyvuRbrlPGqh?20(UcW=Zd421ck@eW&R|5Lydvwk1Cv7pQfD;f1G1%6?4g<{ zfYnIlcoZ+XQ=NwZy2zmjlAP3z9SfT4n|K*GEddxJjZ%E64qk(2h6dK#2CTuw@-tvO zg2AGu6NrUX=;;E(djxX_OcB+D6xk80n4}VFWNL1{16=(3Ns?>%j!jygeYWM5m7}Ah z{r!D3Y64@pDb94|jHCg0lfKo6-)&;N+dFM2k(n&fQ`|G#*~40Rl3%@gm2*LkO&6C; z%il(_;f27m6NB}_QmKZI<O>B$*n@^-mPi0da{({CnE_s0jQ5|(&nYGr5<S&mW_x76 z#sEUtLrBho$E3lSkxZB<Txk`9QwTemM>3cM*^9*xGW5AY5~znnrsaI47I3BqjG<%{ zKuR?<EX>(wfIb}uK;liSIPPRih)3+R@#h2xzuoY7@1&&6)5(lX?1lMwgOu=;OfP9< zg4tgJ6ALq)LbJ8KNfcg4F3U;uD3c~V%15H`##aG~owTsoXxf<sSXis2zglN8egzFZ zOq!%eroks*NJ|(2EruvX$w<xPbh;tADgGL>ZT22hEEX7zJ-Eok$OQt^5g26Pd<5$w zBITp1DcP*ir9nD4VnU;(c_~w)D`$Lar%~pmG>>VIh8Pzhjn797J$Ca3PS^CQA|1@- zrY8-%4Cm}{5Z?;Mm|mkNleNUA1no^l&1OSDI6|O0DKdtz>yu0)oHRgKQho%{Bd!#y zrDP$}0NAy}^OcdrBDQ?em*eu2&Qsf9;4?nX_tXhdt`4qc7~fo9v@n<rSloyihaNsL zXgGphOUqLce4{u!iIetiE!9(@AxoRFOcgQg;NU==A&M8)yC6gARV_5rMn$%qJ(g<# zk^$6#1tE>msDMmG9`!6C88LwBX^#eg28?CCykJBu44~+VA8Ha$LQ)QV>as2^?o81T zI2R`I46hJD<Rl9c)d-B$s&SFdM_h)%L|OZ3vqyNnSumlg7bcM?lb3}s=~`q%Ik0J@ z2D}hA3L(u=qEb%UfRQc)nwW#r)0CDCO_*NV6r)d!A&n(T1D_M2O|4360mZJs7|Mnv z1DN!Bj;HTaOnRCcQ;sA|JdaX7u{nM49>E$IOAe)N`h+2A0TVJE0y8EeSPFF_Q<^@N zCQOmhR7X@k;!63D9@ErhNi8U|B9V{{W41IEU=1Q*1~@6%X;g!uBCSeTujME$sR-U9 znrsMep*PYM0X%zB8Wm|+>H-9{+d_N-{3ol%5I~bHgs=@p15jP7-JWk@ie0yD`j|ud ze8gSIqj^lp+TPxtB0wg+^7i%X*9hpasNyS}MH(`r8fP`eST!n@vzC<-CoZ?~@^MbQ z2zaN*=rM!9;1mMM-}qsU%lJhik3ktfRsxPpOFNB{JQ&0&D^xDb_XgdmJ9-U^mQ_?F z;aLTyi=zMT-~QW4_EWa`U;mrGZf@cQHj|P-yz0i|IEDBZnOWwm1YBV<e+6?#kSwz0 zru<S4O!;PPd<)LdT=}saaQtRj`AI6h({^S4w$KQQ*rm5Q2Y?)+mA85XgW)jV#Vs&9 zL}XBY+Qr4y9Av8D(y-%_fQU_+e}MVf_yhI~XNSjHrRszYiIiK497aM?onAAMs$0%b z8j~tKve_Mp==|ZS1mdsd-`HkvLR0)^>MYD9bot5(ZoZed6(d~!SqNeYU@rk|ji|?u z50&(NBiA(uBGLv1Xj44f^yT$X#UdhH>=jZ@*tY@*)kT+3p#hMTWB_D(u%QIT@rxVo zUBT<0)#!drOX_8VmiBne_)n+L5KIvz29$=4`b?V3NqnI{vg9^!_(GVCE#>4jUQw{F zG?eNmg0jp)1vwt;^>{CccCz@HQed*~z_Y|q;R^TpRbp#iZo;|A&~Daj#XGc>YMfxo zucyXuk`px;LMo1ttC_TRK1s_!z-a7_R2vNXFtYmWJbuTI#btSi8BTHx;1Np{9V)oS z9t4`x9{QX$WLgC1uCX>9(el7VrV=K0)SFUlk**2^<z{XY=b~D*s`u!U5s$UnVrTLA z<j5qhtS+m@Cnv|?#ifqk!QSkI{`qh)BV+lxa$LsGyu~G!($s7AbC%gtW*$27%B1iG z-l)ma<Fa13Z13j?IxHAq^bUf09tlMjHN3euL<sI07DMoq6%%f2w1!g4xdy-|j0OGv z!2!vNwdSV!?AbFkj~+b|K$Iyq?YU*CReSwD-R(}tp_QP8YNfNdsLnK8o}K&z*|MU2 zZtncz;?cvm_?4%2Lbz;xHDW#H+z~4#X!L{ekXY<X%gZXg+nYX?2bX7OAq`Oq4@qyM z9>3zN5keGy^~foTXxyDmGY%Pn&{BSNgX1EvN0|`=pv<g8nFl@xVyQ?JnuGzIl92l8 zNzUWO#s(Jh)4R+`FpPZ0MX#wu%sdfhwmH>j^3ZOG0m*{bW4gd3J=Yrba$vp5O(7ck z1PD<o(3mUh7oPC=J@~s9p%{>qL}inxbP-P7-89AVG%*?$ykt_E;Y~)5X>hF?-|;gf z4v>K<H%1aD3R6pcV~J+8-HF#b3}GjSRq2|BGJBW|T`JYUFt`ZMN9jr$3p2HHhzodW zPfxL@92)aL4?u<<fl(%z2$pE*A<?868iI^N8VNA<<_8`zQQ16dQ4h=XnPLW{k$|Zg zBupizRny05gJFVra!Mk3VD@yetgo-<6@n$?s|<ortKGitkn@X@I(n0(2)xyjHa8kE zUyNaG&PX_a_ZkNpl97SQ@whM_1lTjGM&Yq15{x({C-CrL{Q7iG6PZg(OZl73;OwWf zlQLV)_+U9X1QMHe0z@E%6J-d@R7gJA62m1Jhm~q2zBsCeL|Jy)84O3mI6??`$y=g8 zqv2?IX?Zf9h)DOMYa_6q+Q>|vbSWp9*wyW@DvT@=VUZUfJp<@v6&t86nr|EPt}mU7 z;`^+489@jwy>7SJXwqv4(kLW?daV{)``x<GNb{&=d|&_`8Gt6Hsl48o^a7<f3L_?f zj0_fXVnQ3`)nSK(8JG}GW~s075q$&>Bzn_@D=3wenFTR1f3d|EN6I#JS$0PIW_TB~ zTMixoOAc4EBTUug!)T%DE*TP&uPOUCv4h$p>TFbaW2+7I#X@o=-*7Y;j)$%CaxlEP z)25O&NIiPU9Mx_mlvForNKE*cLy$(NQ4-G(bk`6hP4eooi@ZKlkr3>9qu5iFKI!E~ zE~S-~6*Rf07{#su&;ShK(&HjC*>R;hGbQj=p?_rt_!ttHQMmHl7^Y4I<29Rvr>BJ= zOw}7sXAvY420h!<697yU;(C1ihXH8=Bq1EcrI>i+h~A@7GeuyU4e$ub@k~ov;Pqe) zSvHvI(6k|72{XWiFg_by8sfAK0SOdAN>z)BiE=YfzS41_vf%Uv36?puR%=yJ20Mg! zEWb+=ft*zof^6Q9`1uEE$QsE}lSJ3l^6;TJWpV|9ZE7sTShBsnjiCJKRQ#+d%gW8* zCcnLY8E+29+trNacPU7bIgUF5o1r5%gUrF~GrY($Ag0qQG210&7TinFfLW6F2wsW2 z*k@o>3wNb(C~^dbk5Vp{d?eEB&A9x)>f&NYb|H{Zf9r4m8GQu$ul?)4o*`q_n=RJ~ zAV-lFL;qVAC*Lv)k-=yP^ay0X0Kpptq)aT}TKsvHC=gRj!YBy@li)Gc%~j$LPKM+x zVs|!>Z(=M7B^6f=5vz$cAz^VTi-kFO)pVl)@v*EZ6%C<{pBKdDiZ#xDLWm`k5YvS? zJw;z`5kF~U7FF@eRys~pV$xJbqT!~N#JFf-7x`L};mtN0#@7;x)weEdQ-M<$kfSy# zcrC*MFq)C1F3DinpB^DdPjd*IToIh|q7*v;*l`(RavJug!P!IxJxXK<(8Dl_*jtJ> zvPe$?y^tvf2Am63)gWXV2QW-lE|#;+5O%t9z2VKMrrGGHFR>#)h6^t^k6g`W!`|uQ zXnitAbX~VCDzFJ<CJ&5qhp03gJ0QKz(D6=rMU%eBoXyQmxAv^Lbmgb}ScL$9J$*@Q z#Ro8zpADl&O%U|x6X1dfIDTE+eUCANgN2-oIWlJ*82Ge7u{%6C%r`=hj*i5{m75$e z3@$VniDHii<9tPqnWP1f!ugUe7aL7eEY)P;kSXIkfv;b`W&jo%fB3^6q7fV|ox(^L z8`2{U3)LwZ7nmaE0bs<94LH+=WFaJpY4nIbiK!r#_V!}ON!l#4DqmkH2H$?CF)c~s zae>9E9J^}_V=C?N2L}f*%qtGYlwmYv#$6M!qe-!vQN(VNV1_9U2=HPg@bvtYRd~0y zw%AOLYdHdSK#!5N+{|~&k=<NHt`eTBfFd>!%SejA7?}ZsMspk|lXlKxL`EsGISMd} zSd^HD_tB$A2w>cAjb>O_2w)G`bO;4XENEZ=ko?lvBe1j}Hfo3v>;RYy1@q9uP>r2l zuEAu?(<2R%sAj8a&$aVmM-PcnW1*H8;Mm`9fBtcGFo+7z5?&+=GL92PS1J-=7<y^x zb}#g-VjHJqzDM>Gh(5J|$w`A<VDim6cyS0!IT!Mg5G;n!6HdFJ*_CrT$R{C1p+trz z$&Bjp8q!jTh8`ChFj36oRKglOIcXkB`5>tT0U+`O3PO@$VJa9IAylL#Fl-B1`4{Yp z-n304jRdBlG?WdjrEt24O78>~EVii*260YS`lyEiq;Qm}cYYzVPQaxoE_n{f+*U15 zPvh^$cx07Xlf&JMc$JWLi^UMK3=!>V7$F)UO+7g|#z+wfC;>u|MIH?<MkdU>5}(Ln zj~aT@noBiRq&uksJ<RdR5hGJLtMHnmufP79@o5+gu9SeQQI9|N%LRC$lZQ;o^2jPf z^csS^r5VPz6+GfaLsSSU=XEd%$OuP?aq0_8)Dw|3s#qb0M~^JUqV$Ne-HAo|>eVYW zdYQw1iWrtN6|TO~;#cKMBLpL{=vltHx(Z2%mh+p@v#Q}KN>RA5XgmU^Oe_M34A)|( z4THcV7IvCqFng%;2u}N%y0jGEsfpK~%a13)8%_COjLlXg5@8-oU}NWsFTK5Sw16)| z0l*XwVwC;j;NmeQpn^$MAYlI#pF_8!GqH>1YJwL53$jdK9Dvb;aq(+CCgSSyY9f6J znd-$gm6^bF2rwPhYiUWE3VCZlLF&OY>WgWyBJ?nc6c#KQUJ_CoIoZ<%LymdTgJmYC zEG4OB`zAyg%ymkLmKN&s5ljn4TGA3Q<m56wRgPe4p-F>DGt3?`_;ef@*wiCS!;%pV zUkstal`4`T3p;>qdW@E*CEyVYO1hH8q#))X8Z1U5mr6Fmn0hcg0_tQq#{szL0#KKt zn3NIAN9|2OGpc1w$fVS=1p^Xk1<{DosC5Z|%s8YyL;*5H>9tLVOi1SGwKU0)21ut8 zHpE|mMsxy+oc4qt9v%vmA?7hm#J>6Fo8^`GL|8VIw3AGoXfQxlsMsQ`fGgv;l=YOa zrR20t^N595qRNVhn|uT_CMCiZx7#=v#J)cq#P1FYDoSNCC(Ghps4m!2!{NJPf|1_b z4v>NK5X%4({*B-GGkOR3Z~eXBFcY9Og)*UMD2uh+m~*Po<Rq!Tn#at=5Tj_us}S*) zS-fXvNzBYv<`?2`F`KjT1hQFg)GF1h$tBqGnhysfC(=EVwf|pxch+UsbzKJ-C;){j z^aKckYHSYq)zL`uCz266vMpP-|9hk)8X5{ou>pueS7<BW+Vj>yNw3nA@0<d+)?Rz{ zyE*6Fu6WGS!3+mY#{9cMe(`E%;?m_yC(ll9-n#YqqesMS`nma9E7c@XaRm_n_uqYo zdGqL){=wP2`f~m1wRtt;!`ZwNb9QM?@DKBv>*4&(!~=I3+4FK?R?C#tz-*BD0Pz4D za>tw)*0o1Bb;AMkG#Q>B$GXDgLeUT`#1U|mStp|u7N7Iz_WTJ1p<g-s;Lg}_&FrQ5 z2+q6&z~JshAp|}di<=$l2-XrR*P;@VnPq?FF{e+4;yN)<A*L$@wD1r@6+fGH!i}RF zv%|*kv^Ig++FlR7ee1T?(Paumb#vZD`QU8elvxHRwKs2GJbylZ^`*@9`SHyZM+qRp z_{l}f2);z@MlzT#KLpT539tE|>y07yC%{!(giN*4U(9i<7-rA?l_5#5dzE=GFq!LP z(o+x%bA7CV!UwgrTyNdHWwFlL{B9PQ#C1)9^l!OQo|A4aoT;Z1$Em@lz?>sCQ3Aus zX{)eWGE&H@h_0~hEW)|@K+H;8l~FyW<QqGJcB4Q*;$(2NEKny5Vj~RHxnQ4heiM~y zaFJ1bQF#EE;6GflG2M8urap$We7P@mJS00R0=6$%ARq=dbL&a?XFvOyZUW<uBU-v> zgqD~GX1UKj#L<y^N;We`;z4jd?fFd%YZSE+OX*V53?X=TIJj4n8tAHnM@04s;H-eB zZomlI^5)tQFPLl!>E}QHxiF|}iD9ZF3r=3MtSiFQL=ni?s);taYYE^pc=Oi$u&vp9 z`qWW5A~$Z_%*E6{;p2F;K^t|4?2u&NFq>{cT&LAXBneN8^ZVcb{);cZaGN636kjV5 zt+F^Y5W*0%-1CfK&E!>&geMN+L1^-(i5)7K<P{2s$EPPxh|EvtUKQuj@r@%lqv~qO zzkKCcWxgcurpLt#ad`dO?OS)OqQo4h0%JM#VNe+nnG3;u_0`ubE2D}T!m;1PBQ*j% z3dXdnn3m1AZ{|y+Y?|&I%L$cDxnoMfG~s0Q-rY~!5Su-7Ye`?bIu~7C`+Y7wSLSE) z!zbXeI+HG1hYUxP*g9vJLjUGBzfnUw&h;2m>p^BdIWeChn(s6F_xkkB%NMU+y*y=; z!A~DN)cxd>`{o+Q>YknT;Zpu))s16UiuX^R{E+n^9$~ESMO*)~B<$DqfgZDe_Tt6M zlapsgiMg3LxIBOFPuI}(L$&hwbnSG#V5(?J4QQoMq6zW*z6xO|t3_Z&<r@`KfB^EQ z07o56%2a;+Ra+?=GNB~1{P4-ENpzW_rD$lDPuI6dvYu5;OEN{ayz^ZHbYegp9?lIP zN7OA6ONa`~Aacyy#hL~3==G)A`O`;25{V&V^5TU6EzCIv7mR-L$vwx346IdmDz8po z<|90q&z?Io->zq>`M`@&OW^slmzJuDU`Dl-owhku^XJcBnA1CV=6lOGZ{D)5<`)*< zy}ozvE=2}yoa;x2_KwYBUOu^h@ADr$n!j&%)oqMK&Gq|NtH?r4cmmd{o?V=UCl@6m z0PbIjkx?#r;h2k0*WcW8mfGxQgggPe-ub}7$;oq}+6A(3wp(nouFl+JI#lO-m{~to zht)Wn{J=?WMqXQYv#;Mu@b=&Q&Ceb``TpfgkMYMI>ST2L_N|j=Pl?U?zjW!F^#{^T zmh)DGCQfY1Zobxzo)bn?_|Mi?ml3)Y4GGd#B`@)8H=sM+x9_ZZo4}}P&Dn)-G)Ic* z`|7K&zWL_c*;eb_#T)Z7=q;hDrJ6gb?%cg?0SeoMDzkY>UMAhVC`b-T)<i3S{2UQS zxhCRphfbGsdy?fhZq~0|QKcV#c>4J9V`t9X2wc6Qt|Ao4;q}9LwRD|nKsQTqhR$Df zW*pNH@Q!0tHPEJ>SW1B)hG|rb0|-H0JkqsjYeR)8$_R%TaL0(Q6+%~pE1|h-%|yfn z4hv*3?ZKI^b^8HEBS|GwkdUZw1cbR(a0?G%+Y+!U98C;n%d0j}hY4%ljc}dq&t|HP zNnlGBZ8XuM6GLb+{N@Be8<Jx}iWq|g&|=V)9j)XNn}z@Z1O(3-u?cid2d4A|nMDE! zd>+}9CPhp#d?Dy2DzgA+LpeWn53gN6nm;~2Xa38VuiP8ty6^OuwJ^Vl?J8-3y`Eny znA9f>F@R2xZu}w$NFg4HyXIOv_<1@**qDwEOH^#={BDRW9zA+=bm0>;EIU!jrvd`z zLOof|scY!|`YqKYiz7S0$$@O?GHb|$s@R)(GwI-`fAv?c@;v_fH~;Iu{MY~d{Mq~g zKNl~%%;ii0?IxK^+=6}f;+cDE23g~s5s@$=LS0@g%e?ky+p6lX{_QXHE71S#@Be!; zR80g{5(8b(O*z6B89Hm1RxV?R`P{<-I_g_DMkI#0(G~$k=>ZuwCCn@uNTyvj=CRrl z;#R?pCkuvH@YEFV6kWRnxm0I;;GDjAse}=e+C(q@6%3lY`9$=2>k?of?xwqLR0B-i z(LFCnyrf8>BLj#?Vsa`rQ*LqOXrnti=ZIpaIhYVvan!*Y4=0M+O#mpSh1j8m!)fY? zwvN@u`pZ7aBwiF)+8<L0t)(b(lDb>Ickj%P645n80Ea<wVlu0n>~vun**!vl*penb zI*Fizr7_or5I`X5#4<-o0W+>8#eO_S7?TV*c{lr*WMIWG%b4?JdHfpG;t`IZ+AQ(8 z@jP08Ws1No&{Z)5@e<1$CgSyGniP^I7Xcbm%m^_HfD!735IId4WS<NUJI)2dHkZRl zi#AHq1s(^Td1Pc2VRtj6#Ye1+=84xMx-QAcXNU`Qx*%GTbPb)pny2n;D7OeC8Bc@= z+JbQm<$$B;w%e+9C7|wX5*s7Af>Oa`nIi$?lXqjsCJXopLjaD~hYue*(Neuc9{cm6 z*B`GFTB^;$46GuP2LznCwOz0E;0RbGaYQk8=!$KdF9b2JiN&d8`OO8J7N#!A`1;}T z6HMvj#~|881rbSp!-t7>{k#)`)8vchRIOrG7eP0HJ$&$~ZYoSzJV556J8L6v$VfBS zDzFU5L`)1q;#WP%7)3}2Kl7Lx0wYG*<Qk2`7og+LE}(T$*l5(Ff}>4#hHNH_M;HV+ zRez&6ve=x)KA^2E_EVw&pKD8EDtTqSgnWMJ&G6ZHG{hh;2t1aFF@hk5kB}xU!pRp6 zgtfGA;#7SyI=0uk(lSEEkhQHPsc!gLDr%0vlwH*6QUS~@HZ8N!5+2DULI4r7!b7A! zn7|r4Nh&IFO^Yyf$fy?02q0(?dp$pDFp}CZW6d2yHnm{Zg=qKV<Ybwm7|G~@U4TE% z)<=8D6ShvkN;4!ud^7>A(L~Dv2uV8?xH3mN87i0wj3aiaq}rIQ32e2@%;r_wsMv`( zS;<rspF6>mXVxQI;-^BLSt`VgYD1^^2!5@r%$hDm1u;t9`J)AVg;Flr5xa3b`->ez zB;yMt1-gPEDLkW-_|<u#B-JJ$9+5coY*=>C(h&p8f)T&D8Lf4C10o<0UsOP$?C2O2 zAwC)E=yZ9{9><^f*6yR21(Ny$vzTcySyNBO#lQ|DWa&~dgh^7l#LqH;ym;XbTgsyK ztoYscj|IjQBU-7^HIyX*XlAqU5DtiN)Q52@K|He0jx;0VN%iK9n@mv8>SfR<<N0d> zE3?_-IA)&_mm)38@`@d1Dasv99l^33(|z`Q&KWsomNA*i;RBJ^8XEfDdll!A`ta8b z&MRN*B;=G`Vo3-5pKE7?<1uClY#~LG76DKtLj<H_RGp`2%cd4E(?T5SMt6<xKrv3W zz{rHRp2lMeGaNvZ+ze{bI0UwC%x(q^0S*C7F=t)nI*iaom;&`dn}t+3Mi@*f^fvqW zfJh{p(~W>lAV4R0`SOC64nkK*p*Jx$#RJRl9~lYIR6=OUM{*KAFHvYrIdVaO*c5SH zfEXuZ$d*Y3EGN0gGWly)r~WLgTFqyyOf*jBh5W@9Y=NX44l(k)WCO-5BsOBd`Sq_K zKYq+CNldP_bPZAD6vtt%rN!X!{MpWrZ<P^aM_@PvLSq6W1YWF<w_w_**{U%vHFl_w z;V5O9zc74u_HzD$(Y3rtM9j7E_3P8W{_DTGbLZ}@d3#`9YoNPk?Dg%tw-2xH)(L*h z+WQHBYx`R82wsf->firD55V&s;7NWu+HLt+&}w1X>#unM<SbA_f^bE%XVsLLTh<)p zWMqzG#m0{AGBTD|FSMg%DvsD@S9)4$kJ_4#@tJ@wU;g3Q$&K}FW4C!wKD#s@2fBPP z?<-PtmNT+^?H;$(k2Unhgv7J?-QWS3-y9@HBM^|^2onQij=}Y%(DxtSU)p`R{{W$z zFa4tZ!!%?ySh+l#-uWEF!R|BnLeb9Ki0gy+^ER%Nk=WI%M~CyPzY5RF+JK@Gf*RA@ z{Tl}#|E<$x{att`9tOXpSUfsr>b*f>@all_4_|kux|^x>ZG!cWz~q%LEzh~8Jo8qG zI7GE3cdE3iGJ7L@?ZmJSP*pPSUPuj?7ddrG&cti;+cqnB+0XmQlN1jKqwCpoXMTAY zCOZmE{^}KXjZW>e;~R5r<0xTlPKDtJpr3fQAYs<<m9@O{-tN4pGT$z^b?YY1?E3W` zbwkVE!8)+!F~ClAq6teOta;3-$hl2>0dw(Zm+~txH9-(tb(mKowA&GhDMF)Kl2&g{ zlfdEP5Fukh5~gAqV+#4k{PCDKYeME_n_D+;P2Fb==DSbxb~KK4AR?#73U450$r6<X z{^-myc41JT$q^oY`WZ(eanP){GUl&n;26bRTXXm7{;Sg$&rY5{eR`rBF)7=Og4gws zhL1^$aE>rJCgt44rW$fr8Cr%|aPz?kBG&8zd{|YPDFIzZCfo~0|Ej@zD=Y@(t7U-; ze9Wj5gH20$@fDW4)H!!rvCIo~ElFL9F6>cEml$Cxx)+&DAttKz0E~}=zlHkS-~RT8 zAAWE*DFC6W3<%N%?CY<;PE_J2so<$C3tC-TBss+)qtxtUa^$*;sfJOZPK+ro5Q$Bf zWFkQ`#WfY9TWVV_^ZwQOJGZHZAua$jmct={a3jPK6<tGOAj4FO0AzyLlmS1w1auRm zcqB#LE;LtmX-<YYP|rUjz$_X8)U^^}9}~e84hzg8CXovdglGXLFoZTk2<4?48BCUO zEDyKH5l~pI3DTvTS&JlaWEAkx%9WextV4XlDMh>_YZ-+IGhtItYKf5IwiFEkf^fPd zl@44Ss1t@QDKfd!5|x$_Kzl~YN6Lc)5Ev!H6eL;(<(|d%WPV=zO5RD>9v;L%Y)r4! zC93IOodsqnZOW3sC^D`a`wF#U8+XLSV-!cJ8RRIN1&6MBQgn<c09`a0LsWFLLU43b zKuiR`agEP~mM>kBYO8v*Qcrvw^S;*RZbxjAK*p#rV(p#fQyW^>w;_e1EeY-tf)gOY zg1ZE_7Afv6QY2Up#i3Y%K!ISzX>kpHkl+r5B0abjhr*!+3iRQg_j&$^cjn%+zU<li z)0#cA_WI3Q>xy#QAn~z!?k_V2+#BSBg^x(r<Ch&W5fU~3%pHEx7yJl#%y?{6?Y1{? zL1z^5`{upJ)_Aklyy0ng<Ker771s`-vxyWAtCkPUX99O6cwl`c%0dzHjnBtb`H^E6 z`<;#2lTMlVrni2;@yz(3PVeBpC+R`hMCPVn@@)^;tEoSCM~zdd+&O|6S0VaL?q@0p z3$E<z>^0^kITM3k6S4HBA}{vYPjzSKUn^x=PA6C9B7%U`o1$0m6mIR@Cn<2XlC!m} zljg8c@6EnTw|B4CI@7y|)%0#qHJl4RZI*=A0W|kkQh~5joNf;ipTox&!rw*t$zNki zhBtHfuNtcT+t_h4b4l%`UxyS;=$_HH%S03}5bozVZcPRcY}Cjpb>O~+k+!-nykEG! zzGI#yDyifIVLi-Sz|$FB%|wjn8%HsHG(0)2t}&+iIf$~GxEM{~i;j#aH*1A;^GH)b z8MqYKvJs*90qtbOE4)dC;!#iY^Pq_e`0}60Ro$rikaDx)6=S9l2Pzh_BCg_<_=0FG z;bV2qI9q}ZVy*(WSHzmeM&6$cbhz*yj|e2pGd?F(*?z(o`yEi3WGXYQds)~pZu8kZ z;5D_W;!70-v1-7*(o`G1#+3`v)O0vtx3O8Z#!}wbO>O}@rSQknodoHwOsUWXEgt~s zTuCO?PA$Ay`}<jI+X628_h}GbeFTluT~1r!>9xB02v^*vH;FGy$r*igN#s_pdj?9c zX&&uP$}e}lbxD%XJdfiD_(=48i7&40L<TMN_uEtXAwN}jQ6&N&w~2&*j8-4Wc^nIe z<QTk=>&npC`|H;8Uw{5paA_6}d;KUE2@l#N*z*8IDj&uVSLKN1I{8*Ka_GdT%uHXn zV}YNp>dW$Gu*kt7K;CJ-Y}a3>9~m0zc5hJryE6-4=16VJyz-1K&IK_#2}cz)#mk;0 z)RSC4*BfLsph@!)+5Srka-nCB4@g+QJmJ}Zo*W5TtqYmc!+*KrFmX0A#iq5(t@17G z=)}zW##QBHGSrc9b!3p1+>kTyOSCIg8<=I4NhgZS!=>mWVNc>jgnUGx)yc;LCnkQ- zUmMJpA$PA>5rip+K;t4mT1*1uqakjea+a%11_oW&_65FcWS$f%a+>4DKi5&i``n+D zVFMUz)n3r!CK)7?>9^+))4BDHZj?CkFon_a;*&#Dn1)(#N>e;pyQPV3k*KF0KlaL~ ztKKhPFMF^)L8Gqw>rJgr3CnR>QNn}-YWy(z?2K1<BQzUxx(h%6@aWU}YwHOX^`yf7 zg7YkZM?~D_yw#F^Py36v!>`5IhhGFFDanv!%+?E=B&0>B{}z;G229z=UYu@kw~1$D zGA%Q29j^ZU7acn6x>U#(02in3wt%e<ThQg9&IVK@4a>9Zfa=~+=nVR(ZoUX@U`|y% z`&@q{n{auUM7#z2NVJBAw{r+*^16UM0h}&i{x`qp{7jUZ@>sE8mf1X|x&gECcgf(U zvlfHX<u>2bRXKquh}+4Z|H!QWnFpnCcf1CFV7uNCQLv^2<g20+Gcr&*E%xV?TzrA( z&)v^HHGex&rBO_SX(9O5nRFN9RCA<rWKft9umQ!&NbnL`J0i|(j#DvkZpvTS?~y#s zB@w`6y@)K;mN;#Pdj9i(zMLDob>ge?)~?Y6dU=Chp5&AT)y|L6l*vd(jvDixPZ5J+ zZb)V#G)FIRwt->672Y0Zo5tDx1FQ^17Dt8aY?C-1XZ7~y%HiaLigR{MY!kA=>UQkK z(28Ky#7n{pOg2Qby?5rvi7ZcJbcuk;px;QW0$)|36^Pw%APF;rsKRHMrZKDVcuRS4 z*4H|aNM&Uo7f&_|p*?Wbw$e7uIZKQuRWht@K&`OCB9gO6Uy$T#(Sn5IEIk&C^5H(2 z8F<Eq8=1urrw`)l+oj^9amESUDhZgGu(vbq41EOlDI8_0ZgYeB-isrj?ricVHGTzg za4L;x_4?nRj|p#)t=)2avwCm4@%m4LXSiZClj1CYZ7($*9tKZ#rf5Jaa$lDx7oxt7 zg`lRM^p_wh?PBq=Ir)_;4#2AH@FR#t*1>tD+pyHuQR+(L_o?pRKYwfFhw3f3QgX1l zHE4rLXgJ(j7U+&u4)`RB>yt-f?N_^ee-9*NK8MQd5x|Wt_W*WftvQgjzdHiHKaI5S z+m;hh5+J<Y@k)*08+h~Q=U(8i6>UCOK4nK>xtFVq<NVw*FS*yQ`J2DH1Yf}q<=&5} ztAW)+Y`TNq-uTFK&}>~T(apV#dk+fMwEY$+nO%r7hA9$2uzccfcAl}`9`5Rh#i%VV zOz>p#oo-l0m}oy%C_SN)nCN{$bfo`8W<lLVrXfw84RlM;qS-;=ak#!ml^wV>jG$9h z9vmNLJ@5ZLUE;eP3Zw*>Y*?~XHI!^Gd;~y%lIUnRwHL~gI=A#p)iZcG(IpK7Ra}Yr z(TsFdOK;Le2Km%eb?s3OM9L-UruM{`qT$#hvwvi9z)WF<n<I`c7OlaGG?}ipbuL?4 zo)a^NumCZrIx(a;A%hA@Y&;^)FzDN@k@~h09AH3z(A}(fJ!hQkd;TDv2HpqXn@u&Q zU0c^*q=4KaM;l!(E(8Q7`*`&8W0h=|N#d54w!gFG%SuTF{kw<eVD2@z-s!$QBt4#r zCR$%v!(WAeS7dHjIiH&5&QJs~vB~1SV|Ng1-%u6IeJ?MUcd&&Q6jV{}Gn^7e={|kw z>LcB4_t(N~a%HYd$IK|3wx#;&l>WwKEqg=g&X-(Os=}O{>&>BCw3AZoAf$u8YFHNU z_}e9Xlpq6(y$H0s@ly&I6Ij!$=k^=gx}Jp9OOVL4M^!&YwlSnH9A7dRvNtO&xLUf2 zR+M(V>hv9w4<EMG6Z<aGE;3(JbGmfs+A^zUUKD{;k8&;UVZ70|z<o1|9rb+Ong1Ew ze9>aNGWEu~L%Nvi7o749ld`CjgN7B8vBhvvgqMT{DMqzviK60F5nM}tm4O<XHQ_T_ zItH)y`z^Nnou;`lE0BvLrqMD1xl+^SAzE=pY!QROPMH^vi`&3Ht2w|waXHLIpcEI6 zoh{1<z*0$5XatGysY6<w#A6l)@&*Tv(&shVNtj9^QBH_=Dm7<J^M|ajo?Y;_-k`Eq zz!(BW#T+;z<?i8v@`Te@!oXF5=fUC7<VF>#qV#~s*Q>4Xg_j(m7S4HzF=q_O6N_LS zs2y|N?)A=xx0>WBJ%M({y58`T0rFHjc4e1xk#}XTO5l=2_IxT)Q5s`>h8<m5SH3_4 z4$e72CVs`#jG7y!_u$wxCpzVW!k6f%Isf0ps4~CCi<N*ihMk0f15dQVpWBQ4+if0h z74t=ys+zeyEffN^!;dvis+e$&adrBthT%jz62Bu2z!d(#meZ5z>~phtL?lLE1~=sl zc@YSk&jZ8S-haspaF~ze)j%}ZQnkiTz*_i$B?tn016$X)0;)PgJs7C7wcdd0r>@)X zFi=@jmQqpGsIvJeihGbTTgaI-#}Qi>q#?q@*?%OCedf=cWRI_e)==5l8~jj*pD!L) zr<e&6dk{icfjxQ8r7dWQ4e0Rv6fYu>^0SVybP`mKbKbFWT6zfP8Lq@tfHoaDD0XxM zD>WOq^eqg7g}4)Fpq!fiO7op)4WqJ#)Aa2oIq_RowJnzCAgYO%`U_pf%-17@vSw!& z^hC$UIhE-*IeHwL&L#wfAr~%#u^vGTT*7)$LTbeb6sW!+H40nrY{EsaikD<aMbz?o zDm<nygq*P`IwgS#4wXmb9uLhfbYyam41XXy$d#VL_Jml_CW0wBWGn_bXe8pZbU<J7 z7k7WRH)^u;Y0#y~J_La%!UAT~TFac)DM>V~t`51YEwjDXrcCG@M1ppnUu#~F=?mBE zxkrC0XHDm)zAI!4Pgp#zS1}EEF{MaHWQIvDgVKNXL7NxwR*;v@*~%HhI|SO7s?i)% z3G0$HLeps@Z)POu`dhh2)aF%EJ_9|kt5{x+CB&y^P&>0u*_5G$0ckSPOdt6$Eoi=E zY*6X)lHbVN-OeAs?TRwCWdw9~JSSealA8^8Ca+y|d{|tI7(z}M)9#GsQi@7XW}J|Q z_EaGxC(j%EOg5QgiV_Sehh2#C4$AQ&G-_Z}(7mMn=+AhJY`okdV!xY~i*xkv^VClg zRxURG+4Up=7D*>3h&%feT^f+Za*0w^=SYYUoa^>@XVWX*y8dwK!ZW_CQbE}}KQU%{ znjL?#i>{##lPP9Kt8Tqmt>~4Z5ztCVGKSB+tOwGh2EDV{R3tYRNra@PPrD=IiQ_jD z(Fq<sGL4SlxLxYdr9~^PGyIJtiJEE`Q2RZpI$pU>RVjDFbb~HhM&!d)+&&y9|CBwJ zgB}t#yqU=Iv+eh8&g<RBet)AhS5vg<IGbDSYXaoU&NJRk40okX@H_NB61m*jIU2<x zWoxLC9UI9|c|}1Z>3C1GLhlzs7yk3NRk+_cMLhDvJZ@@Li`<2?S5&6^ZX1{D$`k#o zHi8N-$+-Iwpw}Jx>xXA5OOv6h>tZY{@cIk(@LjXBrAru-czbi#n4{Vj6$_Nca_VnZ zd)d>EU3ob#n|SgUPFJNX&+pd+vnW^(pNB8xm3|N<>UqhYSs%1P%PhyH{;@~?#3&ew zyhH}@wCO1p=IA`5tV6UtWOWwh-g&PC$7p*sI77$(1hTQ&V|{1r!+O&vhU*fugkUOF zcJOre%uO}UStF%>7Bv{p5!29xTcvA)(b$KuB_-fLbAH%h4>!|F0gY-73v^s?STUJn ztM$O5T#mOcogJ|#54N(FMCWe*v2pPQf9U`<KTW~p@r{OCu+w9Am)~=_Q4T=e!`+(> zc+`$-rFMTk?kU|Ej-9*7HD~Sf-+8a?{{ty*YCeR);w@GZqAZuS+wdBDK<o5`%xPSY z*H^BAbTKH<Lk;JJlV?dYX&)_pzoug#0kf5Td9n~p(!#TChd&0>-VjnethZxY*KhRx z`fX-hh&(T*PmFLT6=^gclhwm(PLZM_8tg&oB4`D5>$eoy)mRs*3d)E?F-#fc;<Cqs ziYDI|<6Yst%K;2wO#~E{7!t3NboQJWpO#U<AoG+3npIUl>5PjTAy_)kX$+rnqH}ma zFQ=j`MyFndkVS@qO&;~ZSj<t4L=i-Av2*%|ZEsVwNH@sJVt%W4SzlA@a+r)>BZav> zU!qh~8p7g=KvJ=}aIfFSnG%A9`K6RGDF$mbHkSk;O52Lj5HbV=oA#1*wPtb*A43c2 zf~MTTN9lkv>}bT7FZR!KT~)kC;qv%Rh^*8I4tqOpPB>EJB3c9zU<CkhGl$^j&(qgA zx?<JL0$$ZWuYv=tZXpBcHW7{TM|QD_5g^FZ<S-;*zQ*dvRsohltIXM41SkVpDje`5 z1%uf0F;9K~FfZchTbTA3bqT@aWe>1I!g$Vvpm)c?Z0~;)7RM<iSUZ2uko23}9A~M9 z+U`7zorR>a#;UFuF_3H&_|Epxt(UMjr4ni+&Pun+t|@Evrh&TKPY#+8)Ktgr8N%Jc zXY2BA?d+^Va3{x2GSLUPJ;FW>kI^`2fV-S{OPd)HQCz$-bPZ?ZbTpzWlQ&n$8WX0e zyqiDH!AMOzX0GsXUI>Wj;1H;-SaNPZSc0grAOy;ok6AYM72|9sJ%tzP#qc$qxr@aI zZ$LOVtQBP8d3+#0`z9b*wNan0dFGS;$AT?WQ!-@AkB4b=KX_TK7lY3BKMf5@o+z{? z7YjtwkCSr?Ta?q>XWJZY4Dms&ff1&XNnTCudYwc1tZN;=;|M?0DT(+L*1UHFJEke= zg$CXtR7l6fBLXtsQ^r7OB44kS|Ljx|65-RFAb{6k+ZT}&(eGHRgYy05)4K#_g3p&o z6ikU+a@SXDGrzukKN@Uvbg&{5P<y)CpDjHN=+&Xg_!0J&zt}GX9G$F!(ZVb{@#5IU z`3ah7MN{kXUW{6(fD|k7{7N75ylC&I-!RcuXEKPRP1zvpHOXaE9yWX;N=nWjc$Gnr z!(T^(&zrj7$?<Zg?p8-KHt{FeELQiY-}NTiEMl#b6N8J>1;pXAHP>*gyf0(2Tjd;7 z29tnJ`Dv4>VJ`;?QsYV4-X(HajR}^q9~cq@!+Z7zp2O04dsVp(u9O@B>dO=zS#?)_ z=8Cr5nyGpZ7ju-vB0Ucz8@;nrwqt8M+LDZK&A7Q)*xiT2``|EV-?=mpbNwlsf`8@3 zS5uq2Z61ZYmD7-bKWRkqjUf%*_adndukNzfgTYAt%-W-}d;Js{p<dZH{|;O1pgC*) zY~<f7cLVMcLhlKQMxa!kw<j6v<Jb0-#Ld``93!8MxRtyR-}b=DpGG0VUo<pA{}u2r z$azAw0`u;oX3j9JVe688TdI;Oj7uVN*_nCsm`Q-lWcuHCSb5)5_adLmGe$|3oI<YZ zbVpWE>;?Y5Z{m=j;-kp1GxmS`-#E>y?hU(5{QbE~s@;})NZDJOjg6%{_{XMu*RZs{ zEjfuDA;P9MFD$^uAZzM3lV7g1T3X1FYY?)0hOWM-eVf^aXl!VuMmOcfVmrV=H_w3| z{(>xO%hRFAyM}ojE5Qsmj^uKNx#Ei!$BZ{XUxs>*N#T}@Xwq5rz+Y<K7;LL;Q@xy& zB;XDTW};$Y_$5O8*F<C_wht8G&c$C%P}=Nlo75eK$2li#lil4{mUmDq!4~z=|DMNo zfQ`fyN=t7laF8_*Jp=+zHx|DnVP1D#50-tEj`X=<T8Sd$>s;nFgT|m>je5ks8amI+ zIk^Mv^)hBNFFwcUbC(VV1S6g{ux;7r0GzRkX4_Z9>uB?RU|&gs!I`PBzOgcHJmR-C z0I-F_V&*%33AGy^IN7bHi9Mvm{#O<kT^$Dyy_FKSE>(J+(UFx$95N4@ZIjr{2?wPt zG&a~IRS)CJT!%{}O$5cqHdU#`1Zzd<8;$3-uAl+VCx0!^^SHAo(?aFRhz_T04NTgh zHuigq)Ttav!|U6Ny(I}Mbo943hqZE2i`BA>J97I9ZxCy}%^^l#_I8sl9*D=KIK-!h zhe+{?E3A{reZ;UAL?L4V*v?DA0D$xxBcW<c1uzv~M&RQ{;ffMAZtyukB|#}6Df-u` zvr<__QF`<Xk8m}vSf^aR^BoG>^fc2HOz=ytN-iX<9TKG89W2$|&^M#=Gy2!42qB*` z9AhCiY0=Y>$qLRDq$d#L{DvBFROV#PQ3gDI!o?EKSB5O))jdyf9U*>9jB!<co;h#O z8OvdZ2W?jeZG@#@a3IAZoQ^fxk=A9*DN;z3Nuhn)TTf3<hg5A4%b)mi@A8_b?u$LZ z#(Tm_P?3B$==6cwoqF>lIkbxL*Xf$1792O11?CgxUwF!6qtYZo1D!XCtmCh@O(F;N z)Kf&c%y8pXdp;+G!Yxn@ifg~Og#sQxcaL>`Xwxb%tE7F6Ao;rK$i(=y$m5#0<SE8} zP?AQOPz4?@4mk1(_wsTId7m191PkK9UO-7`e3&<wbU!oiueJpU*LK3IFPR7K(7vmW z(p{~{YOG|;hx)7Ht_^Fpa#3*-Q6f#dCUT7dK>vIKh*;*5c(?XzQeMiHrm=&e#(yUc zgF;!WJKMjQkVakcal7#ie^|`Bo_$<PQLBHMm|DmyK5tKuCw<6|&aRpw*1u^dhO7Tz zu}pM$6;5k$JKTt^p<)$oGJ9n0WzVK?xPy8tCWm%w3@jQ@PMjW4>i%=Kdbd`28G`NH z>u7l{sq!kdjhlk_WVI{kFrwsxAia||ABJ|H$rR}m1P$?AUp}-1EzPp&t>#YpWxUOR z(p0W6lgMN^XeBu7E~X6vBAohZ)q4ii+|NNT%=H9A!R6ZQRPS1Oi`}ZrK31u5!-|WU z>YrR$;7AaFriM-qW<$G%MD`4^E$Q>v;V6BdB86`4I5To}!4WVX2RS~*`+_DZ9=&8@ zW}5~o{uVp&#X@+UQI~Yzvm>&ma01XJ&@flzdNXV$dPRb9JOJh-7KAH0Geb4`YuEmk z%lRkRb9Y9?Gi^0Ja>4D+k;>Zreb-wBg+Payf1ZA{fyDXSz$hr1)9iU;ef3Yzd#kS- zBQBJo9`#wzXGj%$0BO-uG%=qE5{nNma%8t~115{RFS}TWA&f&Q{_+dhdqt49b9w1i zMR*2x4!O^}6!!|~5#K`2!mpE+-zOcXtn#<+chvK@m!ypqA78JH%hg>Zqn{l|J`_rw z@dh3sbgEOQY6DaIQTXQw5AXJkjh)kwAIX?d`Q0h@=y=n8E}}wq)Q?XV-=}F5p4y>k z8R`Sv9vQ?1lLI!3w$;}VA3G#za($}C5``fDJn_y}aJ=uEWy=+b-`sAl(1~b}hP!A@ z+H{9s57w%>6KNbv``23MV3VZs20+VZQ#AJXS>u*AK5a|*c@c@DINn+k(I^U>%7uWq zz$2EY!wG2Q)ZH|7z&ueuu}CZn(gUMYNb&u(h|Y~&jPr4kGz7xHJAgna08B`9F^Z11 z_7)7~G19fKj`d2b^OUQR$zU=aJNZzFwHjm+f`A|`fh&tzL48_#ee0JL*7id%LLhfU z%z|lf2k_>gd6mEx*vk^~?L~{{$6Q%)vKJzTL_$Tp#=-bh?9Cyr?w+Z;SK&<;pIny< zbh-{zvraF)-of(IZN55(FHK85M@3J}4Xmff8h6a8w(9=7Zr1@<`v~?@`pEJrRiLP* zr^g_|F-oLP&^EjtnP{#<7pNnKJin5<1F2K74iNN#M$G0nKdWDzq$oFXc1FR<R=WbG zPMafx2?Tjq<pO~zm34XP-n#2I8=YU-%~x5FCou!-^`T#VC50c#1j=Kf93Wqt%rGhp zpD!GM&#ck};rkZWZqVkO5xf@$%IKX*GlJmN+wD%fq+|%GiD(&l_{w>C*z!!dL)!is z2M6|p3cu8;TQ3Oy#k-@~6oZMtlt$DJPuWa<mm=YL3(#SBCLpFk{bQscNTEwUR1B<S z4_CHUGP~N>53RUzJ+JY?*(yPzF8c3}Th=Q4Kf+qa_|r4b%xGW9zADv8WpS3;jBpY& zAb4n^k-0Fc7qK@U1Emkgrm#Sz`A<%o)@l`6+@5Ks4PkvAAH6F`CCH0wZ^ojG*y2CV z2O>qrQ!QssJWEW{i}>pWMcAtZA4=?;=74q<{3!=qM-S@Gs0Ey$l|3tn<cubY%y6gq zE1_9tJa(cW+cwoCNOU-2-OoV-((Vd(h0jH+CIsL}I6WG+qK%n7_~Wu(c`?%b>;uI$ z5<&x@BDk%^+{~3B_lVw4W7wiBR6zur@uuOk70nYt!C??jx=B=(kwq2q9agye_FO~Z z2K^5snx0G08@@-)9Q6hzTdPE$UNE0J4Ohm1B-MRpuv*5jLjX?_K%6>efNcy{Hin?l zxjqLV`kR&wXW-y9Op&I#KcXEHU6|vitQ`=v#=;4j&eksm%G;GyF_bpW^dI2|TKNXJ z4D9a*L#(5!;(E2XYdgM1X{kqZa89M1Pk<pR(JV^e#;VFatZfR!)4p$>?;ej`+F6}n zk%Pl%{e}Q!Q8XI8$G#0Gue?+Vx1;&-?A*MYpMW9QyQ7Uyx5R>EsUlX-a40C}xcs*+ zZri_PWr9wOUh#f))>`@Om=W$|aR|C^i$(>DEofvAP6;xirQREtZ#1&ACeNe38@(0L zc*{S|jn7YP4TLbvJxgX9lJs27wGrDk{Y+fSt_ZV@q6Hc-{B8QFcAOhoc4W+CN$-O^ z;bT<m&slJMdMu)zIO?(4BD~w8DXTdyu<PItc<7cOqWlHa@MYCWnX%83ITu)8`6&s( z8~I{kchW--v&OM)eb)vNrIM+J)gd_Wd(`o=g;f*T`#B{zqLDqScrx6$Dh6eZRbCAf z#imZ%O?usO4)pr8vS_-YHRVUkFrg4-u(M_Wq5K8?ipYqnAe7Er0+#x@$&#HwU66Lq zS}a1{fFg8^3@Q=dF4#wFL>%1Ju;!Q5@QtscgsZw#8DXr0Fn8qDQ7drud6?=;Cxl<G zlP8<i+OZhJP6Bq+%1I<I>?3DWzga)uzjnJxooFLv_U1{je33631eSQm5Z!X>yusxi zpGcLY)YU(j>BGQyc*vh?Zst8vRoH!h<My*0f{ly2<uCp)(zw3b(`FZ(?k0a`UtEO} zOZ%{yXVpy1v+g_jRIu`6Pt>sqb+@I?jl%u8jr#S}pr<yqn&JQ2K&bnX^_5_J5%2%n zpT)gLUjKKhR!{fe-T!mOe?9SkkLJIg`2WrmM6Ia(KabQ{kGOF7Y!!G93#q23TBB?m F@jp2qp~wIL literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/BendingAngleSOFA-COMSOL-Experiment.png b/examples/python3/tutorial/formation/chiba/BendingAngleSOFA-COMSOL-Experiment.png new file mode 100644 index 0000000000000000000000000000000000000000..1fd8bd0eead19727f1a132e261479a245098cd29 GIT binary patch literal 13247 zcmch8byQW|*Dfj{-5{OPf|Q3)x;rHVkp@BH(5*;!cXvp42-4jpZ~#e3X^_7AfW9BU z_ug^u{l*>R{=smZz1LoIu4m0P<C#l;1vzn4Btj$@7#LJZ2@xe2m<P_lpUdNiz!T+^ zDLvqy2R2ILLNLXH#2dg5SYtt1K^T~_P~=NpIN&#;m4t>33=CQu^zT8JWu5^H47-Y? zh@gt&+nwYa8`6&CpQk!AWG{;AXY@R{rY4?_??ikh#zh;9RUwhgrc=Tf_EUcp0DA5D z2wuiEg!K!S`R6Z|)!s<@#2Oln)em|emj<I$W0nV(qQsa>pXej%+N7rZ+SrKSaN-y` zv>iG+Ji1UtpOldw%H=<dA8L#T-kc@o=jY4Az<gt)=JXKuXae-?3mX@(fPoQ(se1r} z1G@qbqks`c1S22_eF*p9zxz<k@XKL}%M5((=Z%e)YLm_n3EdNvg6c_`+$%H^Nl%jX z^}-dAB8Vn~dOpxy*Mhes2K|hK<&YRL2hDZ1hDE^GJ6G=}eU|dT`k`sjFJ@qs-wcm} zD-QTrafU>M%_pTI&SaE(gR9JSxT{dV5pED8zi3flyLbl5S&Dz}hbv$iG|B+R&hioH z!FU}$5r{|24yqOzs8uIooKc+pNzLE|YZUJbrp%astyj!8?p(k8RGm}@gAoY@$#yGO z^UE)%<7|3kbwLF|J1T)?X$9ZtK14|ctZHgJUm8^e*z#!%yQ}_*%nzeg%nJDHeHEX- z4cDYhS2l2DL#R)KdB{o#f05gzmm9qorPKl$<<%!|pD4oyI!)LPIKS~9THO~b!cN11 z-O4K}IEIyMXmQP$Hu-90S}QahH@N`w8e=+S=&53o>^TmL#CaIaMA&AW`>{%}x*0ez zFF{jMnY04u8<K&3!X$g5eF9BHBG*W<|8DDV*Z1OiF06HWjrJ!f!d2LPLF48@>XG!B z$JH6d_-3CZ29dEkR0&5TjySl<Kv+z{+~MXdHj7BV+FxWAC_{W@ghd+DMcn2#1>=`$ z*-}?+*E&n#rUfOc-e#NTn)X%@VY-vf+h#?-iq_1-%R2q4iDg!S$7@;<5hwdrxk%HJ zF<?5%pUFWFcRJ_`Hq%Hkc6#NLu=g(v`F=&!yJNuFnL?IPZXRJ-z{X@ue;*Z5MQxcu zD(g*{_?+?mwP-PXAIFYi^kFCa=P>iHnqzWfN#M*FzgKYrDsnsc+2kKMs>k#K3#a{m z26PrsS23xxGUV0Z8ZyVpq#ufx4bUvBdRB84@JBdau<9qN3%)lsce87Fs4i&0%ZE?3 z0S9`DtQV+kr>tTs(cr8QMOlE&)#m@9q536VKZ;QKadd)xj8Sx=$qj6u-i0znmBKT> zoe`KS>PaJ2-WFStwYT!)k=?kPAD*hWBP-FA>#BZ^UJ*eWF`7vk)e|U~hRXYrbsnBG zElu$W6IFNTU7fv{w7syGk)0h;0ePd0YEY~iIv^)Wwn6+bbxuV#a@<`J`3PB9c_SW$ z*PN};Ejq3RgQ_S`tbmlm+N<Y%OvQHoGd9mNl%cVz<=2s0H1CZq6lNIG@j4ky%)0Uj zx#u?Pgp*Yj>Cv~1;VCAZf8~&5a<9_Fg&J3smzd~y*?ku6eH(<|{(6O7k-f#0kJtQX zmtrB3r_=^`!q@o?VnK(N>KD2ZiPnN@JNwQFn%DeB8Wb9&{l?Cu{TPc#{t9`W5vt45 zs;@(g%?Fs+G5g;c!R>5Hy?MZ9tHIjOAm4A@K!D8M7?5LHV@g@)A0G6qFB-#8qckHS zvgct3TXcDy)y_LfbDBOhvp2`I)kYFO(%w^0=MBV;&q@`v1es+0_&{6erxfCTY!KMu z8uN28NKdUusy()pyK34bzg#oK5neex{d-W1!AE_A;uOryZevPu?sO(8c)<nd`LEj; z0~8=;>@1;|yPTrIN-~TwCZzJ8w8=rJk(W2-R#pW3^#P_GXkkR(K0)FHUKKrMN}k3W z3xFdBeSGxab!7hwKPaLB#%`qk(m2MnU>{@X>IDZs{}ev$DV?Z=#G4uTF8Em-(~Xr# z8U2TL;n<Df3Y01snC_e}6^Q~09Bh>BqS|>Sk6}z+5Jx7KVt^kBY%NAXL`3bn2g>xj zOoX+59Bqv0^*(@D!|RSLsi^Z^9VuILO@B(T615nYOW;{qEAhB0jAKXyFU5c29VBPc zY(zqyb`Z2Mp_!-XM|!`--~%zS?jrCK4OG*mxajCZrI&!kj#mGqfUglFZB7m%s9i>B z&FCmB4ZDgMw2*mJH?kDM{x}e?q*dsI0_3yL@af=lsmVSAlK~l6|49iJ9smEYmuFWY z`ynJv+f?P~b*v~MjL#lRCw!{OQ7d`n>Tr=4$3ip<EGUeq?MLmXXDKz8NB+TA@sJ2e zP>=_GKyRnLdN<!n=X0*&N^&L!>Ao8G%N3U_&d}z)6gn`>{V(%gPI<&st~H@{$;r7g z1rUF`|7AoQEpz1LaP)Zlcq0@)K%8T=z?q;rSH+>ULy?Q`N{-9#hXc;Icu*yS)DWY{ zyu1&GW3aP0k62Q_4o_LTIq;@3liU}G!LrLQt|@E`vJDZgkjAE}2))^XoU6K;ZhS{W zp7w=2f$xgO^D@+XpR#bq=eoo;F#q;#eYrJf&%i(?uaoy^8Og0MC?YAohNfqeZbTvB zlP@RSd}1NrPdQ8nvVZQbRWQHfz1y;(&_bq{=*amfrURj=uA#QRMzPJm<8;K5-7aL` zw!oSDdT$F`pe&zRM|%(HI@ugynWAb-CSP6hu+&wr`ci|U9}T(OTb^Yb8+$|dt}A-u zQ$Af4?r~8~8^f{Wn%G#V-2uvX7Q*(1rs}3k=OTbSBs8gZT^H)vWTzCUK{}~?LKSbl z@5HG-T<sbv-Q!(ws0lsbU1+~NL69&jKCRx@xMz6Fy6SvfF42`f?w5n0GDlbbhM<|+ z^GQ#-`{vl>ZJ1u(zw2r_&D$ewv5@o=eTFFnebhW#DLreh!gy$JZ?DR1$}t)I2e%;0 zE>$^KWa*_rko9sE+GxUA@r7wZWll-SZgkkEPY>{My8c)|6Nwr(Ac<;OCt@<sp{Y5A zn5roLP4i}A316m$lv+9mg|M)2qmlogZR;#tX5hc}5}iL=+jYeT5Gl5}=IfC)G+<=e z*x8w@v&mIRz-Y=7G2gwl=pg<sRoUOzG3~qyu)yY^(xYvlu}s%krVhu2U0=KZYoH?* z9#1AkQF;XtPuJp8+v9e!N)0}bq*x4gc6K*6w*y$;oS|f1+L&nH9XF8^>F`7#%X0Z; zN`xb?5pec#u<T33rhr9d?Q#&hF89UR@sY{TL+#VZNr+>SaKEpNy!_ZxTvJ(j`Jt7p zS{GI3>Ql^VmbVt2Jd&oJ@UvNv=cbDpSWFqCwmnj}v&i)MiiX%TFPzcfbs<Qa6`O0h zU92_I1uUyp18#&lM?yh}K#``yw%$u#?EyHmgTz>qkLk^cT*M@#X7Rg_VSFq^v-ahb zHA2t8(*9K=b+Fp>Ki+0+MmHQCW6X>0{A70P>xV4P!&x$nL!QQ7yz&JeurSd>f&E60 z%W?h^eeD-Rjcm*Td}k{a%_k9){nzKb#(c!Mq5~hflC}j-tnKyV?!029l{$~TtB~g5 zk2UnwN9|__@W%{qy4}yfZ8;;V<_Hc+rW2*z=@o-I1%4S;?}p80C;iUMp#pUpAz_{( z5{iowrjoHL2zM)CV>)=Slum^&I#RR1oXRh!$zJ0=ae&Y0K`~ZnPI2)xc`gqA@5svs zODDz3dVIA(5sy9xWE40?Kl{gz7UAPv!<6yZ;<X^at1hVJh1>^0PdA(_nD7-RZ9vp1 zZc_@%`D5@809?23VBJQkw985*^_55M;B_W651sU!&^_n-^WwzFmbh11_x&pJAm!SN zZSK}Bd+n+t7<hkvHr=znb?@TXhO<NnESVq6&;^nvbj5$XSnA~CzW(i{F_vviDQq?l zj;P;FLhk>1FZ@RC(#gfanVfHwkf$MhL9ILVzJ!Omi)6twqZ2F~G+CAx&1HRgKQ54} zmhLTr!$o~1d6#NAwcyeIaZ~wK=E6<sx!Hp19<Vu3-~INff_nlF(?O=9t*3Csh=A){ zNs8m<eBE*3W^K^YeJEu~@UBPbj*~5g=7a0GXJ`Z7cR{z}kGD3RFWqx!niv`6zO=x( zk<p&}k538l&IUpLA#_MT(2oHn8SBKDx?Asm-B~)Ejjb&ZKAD%9j7`mYIhQBKoXPdp z@E><4&+g;BaMonm##+_qQ(OH3wIQhB)FLY2J{q>Vi<!wDyWyGG%4H5|ziC-Z%(b*n z=jd=t%KveQxpl3SyRLn^t~S3V+>S2Jk1!R-pWK&Y<DLC=3&%A0JlWC{)v;+qZZzSD zmUXN1zP1^qD2<%5nvqX(LTj5Ek}GL$B;1_-1JS2UKUq|N_aXVpx7QoR(1=NxfzcdO z$nGmb-x|Rwvry#SciEsAEv%i<jd5QMWiQc-@`t)B5A>ehdmMV9+vBXUxMo5IEZ>YP z5qJOIHWH&tzm5&QtZf}__oHLGkIXVyy}aK1J807r!O!fxR!H{#<}mwuJ4|2Nj$QaO z6Yaz7=kTJ=pUK@n2V6uk;rlF-X6sS`#knGi0!R6~hh3uKaQ94=4Ad6E+2rN=F;31( zB%I{_8-zBYSh<<~r;o2;_NzXawKsC!e=GhnUxgux!R2I|fRuE;{(@>WfsFs`ZAPCM zO7euY_-A3`)s}n6Teo13CNwqiUBkg;Y^`eZyIvNF#0C@d6i)8yPWnP^Avr9uY|sVv z!{<v6y0On6GO}!#=+qx{2je*;0Ut|Y0Rg4q{3O8e0UYGdD%ru<8=@k7$>b86UcJx5 zbql>c9<`-ERE4|sFIsz9H8r5C2Qp<$KRTOoCC&Pq4z)?3`v{@~2^n)lV5Fpe`NG3m zr>m^^slJpUjOf`fu4PZ!i<2E}LhR9n1(q1Mi=C<5&{F2a<HDx1O?E|tTQlIbX2q3? z9H!|GriWN}!pR#M8Pz+8(sBWT=I3D9&^YEn@@}HI!$E`|)UcY^-9X9u+Y17kn~_8_ z7%&BUCuPd~8&9qePb@|gv>WV6UOB5U{a%TTA9Rs4W45^Pk2}SM=CIo!W>6N^CzX|7 zg_2=-vF9sdGSR_1Zm+R_aVgi+9?&O-kgQ1e$FCcDCzdG=BY%T}ZFFt{Ye$cU7@!s2 z&uZ--Akq?W7m+qn%%^$jQ_B^T!!wiLxM@%zLxCWwjnktg|B&n?Lh&ev*;C<7R?sRI zQMW8SAflMoS6+*zD4a!1(s<oACoUGZ9J(C$HgH>s{qN?CJXms&Cd4{NM1B-H1n;f3 zw5Gm(TvHO%LKpmtmpVT|Q|tKhmm^J2I+7RLj^fV+wB7F8uc1?h{j^`kHv(>%)O_^u ziCZ%mu*EfF&T2)AceYfYfL{>{<Q<G!LL_tNdKEK3i%nYsWDTYR!EW+_84<Ve##bc% zMrDv=<)Qj`D{tvlcpExxXE{aF??V<KY5MR+`FkId#;sg@<=c#1xs=v+qurNGF4V9B zNSmM;9q#j{_JCW>OCd6$!O`XD6t}B;CtnU|-x<4J`+3F4+EoE3`u21N_sBZF!nIw- zan~WfHMW2w>a9RUuq$GH9G0jdG|;;#gV`qu)&qaH9l^VSR+mHAy`3l<%&~NWC|7=C zrOG7X{4<Vf(AW#|W4jX-fb)sGL9FajprRK~lb5A#kN*eb?xvO|qT>^lGQCH2J>N)- z1NO7NZbdcq(eVA(h{fWi^1J0fd`aMFra5aU-0v_auUWCTsmZscs(zq9OYk>%k<F&a z$P64ZCyprFWYAH+YVzXO%}1Oa{3m*<9~;=aZ~Qt@98HKl4IDY6){zg{XC|_9MU-z< zVysT4xIpcd{axS*4~b_Wb4V)N>;Yn3*yM1t9v`*Ye+}YlxXbumQubn>@6KA8r<XGY z2$grn?olw=y}PH6bV|2%1x-%GvitnY`bfL!_0Cw6v(j;2=+f!y5L0)t{Q|$VGUwge zTc-~#81m&)O+=_RQz}1mXKdVf);lxbYzuQ<;gf+L*<oGb=l+=JxU?MIl(#2Z9}>yH zq6-uWOUu$KXfIg;mVkVRu%(*aU?B~%ryMV!=LPZOhl9DT>^fg9vgp!u4lHRc%*kmg z8@l@Ap-EGHxA)ne4JTryMJ~E40F7RS%O5@M9H6|-@78#J<*_x16#8Tf-YQ{-D;}#X z^7GxWlk)cllshGcvCl+w&Y#L~Q?EmP{OCx8t|>7Ta~rVoo#)Z-jr8t4xGh$)bXudd zUofH}&N%C`dO~5yt{}=t>!U-vJq~dPUi>4m?ue1<Wqo3!e}}X*CAJnPaonY`nDTGu zJwhtiew~a=pJk=(mDH;2mWNlWtIOyDz+1{$^r{eb2a^J+-EgE-cKJmW=w?rEVeAdU z{Hy&sI@ECa>D%!#>iv4q@!NXu>&JIZgrF(13{^_l<k8Vl6BgU^=T<v2oMkdjtPD45 zTAEZ$on<>H(;!FIXqY>T4|ZgG`I0h<#=yixf~jz;t)U1LZyAba;uZrl?yYM#ZI2`= z*`E2E{`Uqds+t6sKIww)Pb0){D%;9_83u4iHMBroc<PIP;nnGNbb2~Q$rpoqRmmcz znhw{h_XvvQXE0SsuGD(lo!dEoxya(WaN53Cto`)>HWw&gAaynefw%G6-Xh@@Q%osT zS8`B#zg2YpE}p7VL923BBdz4^ekuFXLbCwmg}FBToZMU&7Y$2mX!^fGeW5oVLl!aF zz36L}k>93=4oJT0T%}P6kigjtBg%Qks_Ku_?Z|9%H%%cea<t)ftAooFy<(Qt*P7tU zwavBNlHVe!F>9!Ss!(%5)t2!#rcKtb>XY5XtJe(E%)3jZ-yeH<w2EG|f_6!B81pTg z&Sh{WBo2K#7@!Bxry*cfR1uY=155({1|6)A<dBr#gMEEedg5(4{VM6upYNG0A>J$$ zYND7#jEFFZXXbdeBo_W{%%W+gZFGrq-@tFm{IwWlT>%~q(xr!iVkiw(Mh<{jS?9}J zm<S70*sRa_d$>lSGVk{@E@#lK9Qp6Fr0U6|582K$27EMaUo=1{-~9*)%Xs`1F*gIt zy}m7{;By5ujz)GxZqBs<wF!BVVzZnYXaF~+6$-e6fJJSih&Bi%f<TVB>=VS`M+m#q z%f-328TneE+WK6X6aGs#dJRch7pgli1t|FL#4$P_jBY7saW1&5nAE$dLjp9L3np`Y zD@-y<ac+GieVrua2Ja{1Vo!kGU0|xGy)8|LS>|3fa<B?%3O9EwUx+HUaY(BpbwbT6 z2?9IC=e6#t>k&W%dk1=fBV`xqFVZIR0HGLw20%AZ?n*>bH3=xi356a*!8$}<2g&;m zLnEcXpLu?cPf9cLT5G(BaZK$+F-=ijQ-d}RLF-j%)a~gdsl&7>ALh9=iOgdIfRm61 zeU;aQ5+VM%zLr2yZYero>5<k1!Y%mWsNUNO)lN&z+Ll}NM;nVA0FkCV>D&pXY4FKw zoaP<bfU(~nb~!?Pvzh)lz5Kf%KNI=Pg;vt+m*y#&w!D7^hWl(HYC^Pr(jku(H`CMG zlf1F*L$}Tra0e=)yibT0b<x>8l{i0_iz<$H_w0P14#4urESszMc0jdww;-#lCP#RS zsMxU=wa-ETA;FE(?NETRpbTL8VWci~ds>qqQTZ>zh+h5TqI#7sP0MF8DP1DJkLBOE zBTLJb(T#@Y(*Xz7H&|On_NPniDAp|=ZLh*pAv@p0ZDr<925+un>aCwKg+QZ&<(?kH zgL8}CE)wJJ$n4cO8mW-4RaWsHj0H_C0%jfgrGE4Xw?}wNRqM`!3a8w1RX&3jSgDYz zbH8A`+*ZmQ;%~q@{*rTVF8IldB+-Xyt2#%iUT8uP?^S(ZN`!SHXi52SUCW1munV4> zMat~4!$~+aIVFlAvPK|w13d&NKJ<g?)8X*I3_5}L1JSY$n$Afq$bW_bMKwSInurd% zyC*N4xUWT9E8?{B&+F}uEHczqg#K6ltdbl*E$Tjdk^hSwQNDQBg0?7rtF~=EvrW~? zn9K>tpqd5iFxyNvzICXaMXmP(oIvx=)p~VkOpIlI3Y5nhBTOuzSLsT2TY=^p`o<vr z&3D+|{Q4+$BT6ys2be@k#Mjj|M_Fv;(PqIDQ#b|7gM0_jbQCx!k7cYMnOOsS+6xv# z12dDAEvBfT*@aIImxPCoa)$6;bVGB=oE0B!)qG<RTyrTRFlhig*Z}buljy*}+BM7! zRn~7b;*Y8e@6^hiSsK@;a)BuW9H5k+sjRbsf4&=wRZ-d1xgjZJS{zym0eQFKLtv^> zcFT~rltt;O=Yrl+*<dTHDTS#D%f{ag(g@Z5qe|9y2;A+NgyGRRu}6~SkD~Sdn93Z> zDaMFTpFWvQ75f{mF8)~(cbz1kT2S%Q0eydbMXJtEpuFqw88q`6^+G{Ky*G}&j=s@` z3kagptb^U5HPm8d8pLGV)BCx}ybeg&h?s$WZGZ3tqH@lRfW;Bck04iDuKj&Hce3|+ zTN>%C6jxVQ8DdU<_7Vt;NSSBWjZ);?JgKfpp;Wt0sV>VMK$+v@DLnRbFc~|#_wSUS z@s$yW9hCWACx@5N8<;|guK_uE`O_1Cn*qY9jGWv7&*~DeBHA~P%PorwYgGU=x4EgR z0DB%s7nLlkgI4YjUm{8uIRb>ErMg8<SEp26nkU4hY^8tnpa>uo)kV!rgmAonW5n?6 z0hIJY9K=gaSr9>vgoL}LVHKSHj+uOclK@B}P>m(bR=VtM-lL8j=;otCNyUNVIanpk z`83M9yrNy7BCaR%b9#DhYC|p_BtV8+%dQ0VD}&QRC4r*=<!G`~IvxzAd~;UBl7=1w z4z7+umBLA}QmQz43=5E8ZT!1%9<gXKb-E~nQv{lzK^aiccZbaRqykBE2_;V(g6?3` zex5^>)A-8C?y~X%6V#DbT~k=7GN=x?Q-aiVVMJq3Y<<iIPD!~LnscmNoFs!DB<O$n z@)}k8GZX}!dPrD`A3LSsPjxpa_r)}_pL;4{)^yQF<>Dj17coZL$#T6fp2ZpKad>LH z;2w$ZX(Uc8XHR|sze0n95&`G*Dq5UU$;%k@Nz@jX=$juqkYvPimDE8UP2jKI9NuQ2 z?0c)8Jc%5L3DqA!U2ha)zGkox%Q_44_)Sof5wJ^y4nAh6SM$VQ+odhE<JT4rX*zmt z24e7#1L<!UO##x<(*vhR;XMRQ@AF{e(YcC{84zC_i<i-IIA<rvkLLPbBLxcnk+A*} z7MwZEhS+}Lqgr%!eiRN+Iud4UHT+gC8bMAekuivY8h_?>CI_u5*RXF~C<HEl)-nSe z$<L>pBZRuFA<(^nuMg0M0cU3O8INjG@qbt1-h0WCAC31o5Ec44z((ifV@tS+3%*D7 z2n%%&b`?p7W;A~oX483Csb+LL7bnxji7ILiMm~;4$^jz0LMZM44JH#wqo8TF(#B~+ z;=pnJX^sXp@WbC(39uzd7z51)4)Dniea+T&64oXN(+S#?VE)kCW44G<q_LK!dR_}& z^#CE1yu9}wb<|du9{#WFVpu7&U}D)NXUjK5=u;}`b*)NI{(dZiC~|(VOgr5Wn+3EP zWHc-qCtIp=z<GgFtfJW7*%E)X(7;;X{yBA4vo2w_PW<y^;0$20B~8A|<^fs2Q=8i? z0BGw#DZ>QHPh#=|b5*}cMiazq+(a~Owt9~y1{P?G>dLLFW>~fIRp?3qT7Za@)M9UT zUKTTE=`Y28ioHHCB7NyHFK?Hsq1jaBdR^<d1@1$i2+_TxJGgoD-n~o1?6Br%%Ko8x z*L4Y@RXE*)!y-KYdUTF6FlvY0j99g|IU~~b+*^fCwtILuO#L-4G`#;=O6Mx9bMXz+ zR02S&n!avIPIJR9sHstNH&>&KnF#6ArN{h(n>G8V^$dRxkx$H-XsNaRDNp9BeY|p{ zy7rpf{^ZSphE>bZfc<CX#4_Y(Rs-5w^YL*BI(#0Ny`2+ToD-=}QsUz`wzeW^xj5W@ zLAcAl*b}1!BLCU>ATvY`_6ElVAAO*UvwJ2TotWvSXgna*whu7m{}AOXS#(9nQ$YOf z?ffGvDd1-d71=(~{I+0Ioj1T;XH*y&6y_=7yd_aP`-`W;lGE?@)!plZ$EK(*wQEaG zXU?ZU!IY;+et(qs5`A;p9^g2LXwk&vCs(fRJvAD6iVv3m0G!=rV|w<wD@49_@=|x| z!gj8mC9S^+tigD1k~r`(H+ut}rO?+`e0J8e^55ac&sBqiE&vA<Qh52-%Ki5*e{8GH zvtBOKE?iu;v9j__c24yD3=Je)U7WCvCi??CJ!8rvOW8x@Jb=ztLvI4a8S(6La`L_Y z>}aR8`WNkh(A*h~3bS=#z7W_e2C6r6({*y$1VDT7E<=g)T+X+jbhY|{x?j83IiVw8 zUV>C#VUsMy4zwqM^b<<@igwxnoiB$;$jwRvyG!aKEvKzL6-yfAUo*8Xaoes?l2xzO z;iC<HxYAjA$iTOr%gZ~J&mpW{2~Dkmrk1k6OMHgD@`|-@gUOeed^;p`4)(>$raq-6 z&@v9%tg?T(@i3qneD>MSm-a@s@eyb9)q|ajm|xpkxuYn$BhZX;*9#J4H{S-dQbNDW zqgVT9$W5-+QKodu0v7K6plW|(u3~6jR0wDSs79C2)J6{caufpEu+T)1Bn)W7$Q85Q zwSHy%vS3v+S67Yf-TggOV%>e;y856~w!nYsar6oeecxm}l+r2A3G!6yQgw%(3x`cT zDL>@=VCRHLaZAlN7QhMK53RiXaupmnw9v<r2Kd4u!qU#|yfv}C&D!2js6%A#k)?YU zM$`jD%h<Q6OSGK4saMO}@RN){vqk(^UQm$($Qd};3hFTbT2m7*7#mR<8eB&8h@Bml zu7h_YhA&UWefXUNP@l;(2YOtN#G{Lg2BX;T%tVt;XfZt^C%R?t8Yn^UX;B9){6OL? z`{KV}*f(BISl+Pn=4&*+2Z$u5;(%$zf#4q!3Dy9K2t6YBD?Zdup<U_A9fr4gO#DE{ z(rc~3?B;5nJ#;TJ0cg9p9!?l%bV|jMOh6w0wd92db>THFk810?%eC~zguqlT-X7P5 zYPq0mD*pU@a3L@9=gb767HIPg>OdRDRUt6X$U&Qu13xUumT5WFKpxG#H5#wmlasep z5-9F=2Iy?(v!onk8SRu@yI$Aa1e?jOemg`(JKY!@v||{+z<UNQLV^ClIHA0g(&1;{ zd9LsKhwE9L?HI22jRP7dWcQ<JIh$Q<$NJBkY18vda%qtNWo9(SFIOc85_}QlEPj(+ zW*NC(JTmG!w>AFB6Kw=^)1h@K;G_@QBU8s+9d?>`U1b_a2Ravc-9(sP`2O3bU!@$# z_W638Ev=N?AWtQ9Hh5K7{cEOz_6nEZt$@=zYZ12G_K*pB`*y6&#qP(y)@HKI&B}Q* zCc8T}F^2qMtI2hVmzranQ+kdF(e;O)+r<e10axq4P?K!8NiV<Dy3we2c0N#(mwUC3 zewnq_X+|<rMiqoky!bB>dHb$5N27B)nfxBV<#+jMQXq-D_07G?t(CY!rb2|o|I_@7 z`!9h;K2SHBk&=GDVYx{}hE^cVvO#-18b>E5IS3&beVhMQiko|XA1KAHeyAZhR2HoY zu>;1ws-TwQBHxJ+^36IM?(QT5o7J<39lQJCCY1lO;Hp*s#@}opc#7wMzs}h8$75nO z&42ct9Uu_-YtPzfNvALOc}}La&Q*7FdRn)?VcuRSxINuK=?=8Qzt7ukj_6nr=+K^j zKC~Ufc?7+v@MlkDub5O~YPORv&)PiBL+u=F(&J}q&o6&e#E@bZKe{I`(OF%yY2uaZ zVvC&{!p*7&I6Z!j{QUD*pwsu~Mu#tCyubT*EdR}byOXcW$y6cWU4gpVVMiJadtV}| ztJTS7<`C)3)%sBFu-5glgT=N>!h$1s?_UF%X>!(5*Izbfe%R?>_UNiwJO5>Wj0WN+ zkD|#sV(IyhbuwC=9Bw66lPGzw^@iv`>LV`sy!H`1gFh}yA^&ymkv(V9xLAZv8}071 zH<pu`9BA&6|AGC;bM}T>yNi*y;iH#t-QE!*G*gS;UfuZPjN9Xqb!JWu-XNw+>hPFa z|7&5vAHCKl)X+)QPpOL8bolm@``m64lucBi&Cq`!DwWPnDQ>#PPa)ZKJ_*M6IGy&n zIiL6yZ0CX50$fW#zq{w+R<gQwncX|j-^6v@uKjgZXUUDZUBE+!DzyLZZbv0FHtyy_ zTzR+;XDW#J-L}!{EqL}?Eup^ip!@EY$K8FJ`JRCubUxDQ-=(g8Yhw#nHu9&8@MQ7# zZp|!E)e-PJ?(Kx!w5j^IV-H=KpRCNPSe%3t+`CKjM#lora{lFu(&d$Nk0l11js0eq zo10hlR{M?W=I8%0lqCALwa=BTpOMF)Sr`A+aes&Zdaa_X<L7G=z3tVXc=*Ku9Z3ID zLb6U*ug%a1xPw{UQZUrCr%NWmG_FfF7}Ugmet}TiJG|TGarGei$DU~QeceUtD5}B< zGv#t6Q7(oT7Cb8X>n$=CcoW?PN2%W9d){7mxdUS08OZi66+ndUrd|s$2v5mcHrIwT z=ZJiLcyGSux>YgW?KXv<yOKUIFr51*v)f`tuM*x`K!{Hsz=U-w*69*PmK1&;&?SR` zG1ZDr6fokNXs7wsa{C(+4O~AB{6F11Eg}bPhYQFxr8Ag^xl85Alz3Jr?@{B%l_!O} zch^QOO1gHfyVCU*X3=&~TOIbH1|o$bh|2iugv+4YANXXmXFGFFPQT!ixarVlXo<}G zAgD2@(BN+s^+R%aSpD)i$qOCMDSJOF4%WiCF1<9bVQ8MY*Y`Wf&{>pOA?10GZg9+o zWWm?bB!5C|Wi-c({d9$rBh>G*@4AB(h0uEs12mDZb5}ee3Y%ijOQdXl5&|#jMzFKX zD$%{2vp<kCRjweebdoDx7&_rrt@=UsKJ#9t8u<@C-`FD7zkx4`S@R!NpYav?I?928 zt8oAe)<<y{+24q0%*gqD(<;o<)f*H_32NLZPm-*86GQu6|EWv#`?QZxWp!IHB#V3s z-^F2<RZE{TylkK!i_F`wDxfybFfwd2^!A>KF3NVJ8)ck`Oj}fUv43gmUWd5UQr75E z9!?5t1(G_E>Xpq;Da~4?6X(rU2QJ_lw0XN=^<g>D*#yjK(97$=WtbABRC+>SU=kj7 zqr#+-lY?MBdVU0cBRvE^f}wl-fB8@|+LU$liOckJSK&&dC^c=tHUWzSbe<p-l835H zaJ!Ef5$F?3?E4u?wD3<u>{KbkCHrJi=U-%~l0R6<IinM>`0hD4Xc86|t&3o#?()=> z0alde2pl=}W<8jj95modiM6fp1m#A)h*Y~=p@@K#!!>~f?3uN;hc~XT^dU-??O8w( zexVF1Y+wYZ#?z2ILR>G=jfl#h?Ex{u`0bS(9l7du6DA7L&rrj+Xf{24K0-LiwiU3& zg{{1((X!u3<$t3!6?)b5yHZb56pxXSUUhmOp8&g5NU@W~Y0go$!|VAMo({>__JEZm zsTfYPk>+y0BIcZFgW7VhO)<j)`eBT)#5G|XtBxFfUvaL?qI`8Fzghf9sdW2i3@bn3 zf=aX12h>q1{0vh48VBe!T5N(1UuP9}C<Jv*hOL&3cE2nl9r!2))v7l==M~O`5I1y= zfV6B@N7U>B`)BrfVns-LoK>6;9RoMnstgQ=>|&J7SR>0tYJ4>D*h>-~qCTiI<%`m% zuv75&-}C6&##o9R8R_iJ=vmLhQV^|TN>VM@oJ9JPgVyUP`vF(bIi9I!v97bco`7Q@ zrd%^aroyux-b|^us1SMc5qQj%&NqQ8Y-!A#a>AoOlmh-D%~HJ|EjvwuSX1zsVF(7C zRA#S%*GZbpB+dY<mn^F|EMu<p6T%_2Qkhb^$B#w~YVE$%bFd)JrsweLQ}yK*de(o0 zRFZP>Jw)+-Fv9V8CFl6tgH~271lTd^|A#B;|BIWQ|Ltq<i3tSA{5u7%oUgCGGu<F1 zXlAGwFfvxih0UiOtzigO#qBm~9!=Clr8Du$xzWiv%RZUqG#Ia%+kP09NT_&V@`YUq zFaAvnrr7F{TBPN+!j|o(mHsu7gGq#}DaiNT8#xi8ju&Om&L{2J*i^T@3b{U+UFVfz z<W}T4eS(bpffW!Vo^E$<5|7a!4VlLt@b0b+!`iqgOfzT>bLW^#>va^^Gkv%QEx58{ zmsVC%2fU`)2(^8A<oKoHgH=#ZHu$<N22mX`5Uzv9{_Pat1sTx-Y;wt|JoD)o5UB)( zb=?f%T3>$)fCnqHM}>IF5XRu_n?F8K>%pz#lG!%!j74xFF!T`UT=VkC#5D;B&`%U% zht+BFBzbEPRaaN{)#daA4%*xLqF(wCvISFSsv@L3D*u`yNJ$S9Q^YG@QT-`7o#7~E z{EtXQEhVwI>0u<6$2XNI&lo{0U-_z>cXXATbL)p5H&6&Z^bhhIr6KR8lFbk~%Qn(P zV?anrb-T1gy@ql`F=KCy%;k>MF2ub9=-85zy?arUr@|&1GfG`fe@SIi;;9KQqazE+ z=w%?8({P0<`X?X5!G1C{1~n@9+n5B`q+{@^;!H#xYkI~+Cjz`<Tv(8p`{@TRnr#L@ zt+aN(Y*-dKTBHeO$s9*qpaCB_90>2B_F|4+rjTH8#1c)`OZ9Ve8Nusk@NaTuPj6f% zLKK;`YKLcM8KY?4O%-eB$|Yk37N+m}x@Nz^sV6J^W~8))^+8KQp)>+Q9n?;^G?pMG zE8Eu_{M6)zmW}c^Q8uFL;{%Rpy7$a*RT*_`ipf9S7G?%0R^UsKbfZlQmBKYfLL`B^ z!DA^Yr0E<F=H}*T<x_A13&Rh@w}}~kl2)K%HqqjHE7awr6+p6rMFLlBdo3a#)#c;% ze#VF=dY>*4YLJnaFEYIJ-PQlOnqKkN3txPsP*Vn`*C1&P#)2nU6;!Nv59=+YlIB)^ zH7Q={qV>okonkVsqc9?dW~N~#NdHVrtA}I-<ps8yDvIKPxWkBsDFM#+<oMXSC>_y8 zqo@GJ1c(48B*nm$ke5FSOPa7m;Xgv2Jo@j1hW~94iGw6@+xT3=z<g94OyWMgd2qZ0 Xri=|*Zv_6+4UD9yoJg_IJJ0_CYZQMZ literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/0kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/0kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..3e5cc11b3de13bab88f8a36ba35516144246ef53 GIT binary patch literal 157289 zcmeFZeOOfG`Zhc$hGvCm+OB|cH$#J{P-rGJvSddMgStl$MGT~!7?J%_5W+E>Ww<Nd z)r>4a_Gr$SfPj$XR|%4{Eo&H{M)^z=u$W=^NRSzD7-rVuJ@4uFJkN2wf4%SX*K-_? zmc{2<_qy-v<Gjx6yw=n&Q+IfCVqTTL%JcB>;JuE2cvHVU*Z9hw^f!6Db?bORJRWZ* z&(q_1-ZXqPn};9%IGyK-k3I15rh@_h<Ku-V2Yq>7_}U}*UIhN~d<XHLIpm`Ue;(|> zgB^IV0}poK!45pwfd@PAU<V%Tz=IulumcZv;K2?&*n$5Wb|4}B-PD~qyB9wH9G-Ui z;puKR;c*^s;ipW#`(w|rurS{LVi4x+C%f{1K_I*E;Ln2{c(4NxcHqGdJlKH;JMdr! z9_+w_9eA(<4|d?e4m{X_|9f^I^tsT`@aMw9pL>4c^Dl-!zaspF73AS(K!-q-3Df>g zKAVQm!7uQ5&sE^R?ytW>zV7)yzkc{nj={Sc+=GdH>jB3=cHzOF2Rra!2OjLegB^IV z0}poK!45pwfd@PAU<V%Tz=Iulumk@`?ZBs44JHqG50U?G>Tx_eWBfO=Kmqw2e*?(> zZB=iL{rUB&UwJR{rcawj{>2|p{5xajj2WJuGamNxdT8b&4?ptA?1yL1e)O@qa~^%n z=dszd=Pa1xGw<>F^XEU}{ls4uJpPxtkI#RcT*PBKe#djhtQj+AJ^twIM<4(H{b%Yw zJfE4<|1*O(-QyYFG#`)YJ|0uoczmpO1|~1a@Wp@s@tB4+KIAoX*2A;$0~hD;rg==C zKFxDFSv7uoAHL7?^qDdDug^z5G%xlaUe9Da9{NH47c&KaJ9~A0+>Lv}Wp8BW&3bsj z6MuQ~seorifs2Bczp&!Pm0{s8N4@f@Bw8A?A%5eggw2Utwxw==GwrSPw|8e{zn8N| zzW2aCKm6$9gNOdb6ciR6DgL+m=*g1OvQy<1m8Z|0zi{#EZ!Xo=efRyfAAZy~7#dqz z+uA!if4O<<x8HkB<~~dRz~HFWHa33WKH-=o&*g#V{2zb*e6au5bNS%8rg?f!_w*vq z<uNS>f2aF+&iL!|56z8?_4-G~yk|l`nECkM^1nEHb(UaR+`aj4WZrmqfpGb60i)#6 z+)wuZ?ZNW?x1Q{OKG^?yu3NlErh{(sneM}*crND@?}+xYYI}lpiYMPBU`q0*c;>S0 zjftWWu`$H1Nnw{WRfg;-9vvjRD9`rQ+FIGvqSc#~QXy+`T{vx(TBdld;b%p|EmW7m zH%qR_Rcz-)`f5_?p`bBME-qI+#XECsuyi+jTILuqPw|W~+U6<V*P0a9g%c0SGxVZj z(Xgqc84JkqHwK62+8lh_&nHw(1#BAYJTbjVDW%L>*VyS%T#6~3;w6ZVjNb54i@7Aa zo{>4y{CJz?l-xIK!lVrISNkebCNB-#qdTeK{odml`YGPhpjqNeCM+Ub%*b~;@(t!z zDn~S_>$>ilxy7N`j>Y0iY*$2>iJ_OV+vn-~r1&i=XNtEjkcU-F>XtRJrb3DEFkQu* z&_uh8<Jsa21K)L??c#+lzv*n$tn9T3Y+~KyK&*or64#}vg>w~mUAoZyvjjFFmK=+9 zh_S;P98<hYcv5S?GNZNMV^nW8IE{|9walL0Dc-F@sgNvKJgCFg%=U3G67tC&Q+`mX zk3(y1DaVz3=^<*MjJNrlI%cIw#qE^{>A}HoJ4b?|O{_)Tw^1rmvD<n4K|HXgP+@Db ziS-pG)fDfUcuk6WikBS7JHW}??%~R-7UgpzG&XFz%r{@ppW^K}G1FAgq>MSxT+pm) z!oA|8T#*nbSQS%44d0hwqgD1P-u)KUI2K_(K1XWCYS#slBN?GO=++n>GqaZ%lCw@G z;Py(blC`oBBXbCQaAG>nJTbOZk;d*;szU7fjzU?6X!24&&n6&-RJjlbgeSrIUb32S zjk}*0QQE$ZNz*5S$mUiqv|??QLbgX8H$&D<4k#i<Y#h%pY^aBkUZ|j~e!SN%YVBN_ znmbn`5wTg-Z{e8n$V(T$M|H1%=$nuJ-X*2lb?mYNZc9RIglEUXkG~(e;vKPP`L83P z(XMZ7RC{Oh7GF)WHR1e(cO0`vm?st3I0H2zD6lKiis1v4r7V1Bci*#Xj!DjrguZ1J zGm2rUz?n49F^Zj7CBQy^*3tgiXCECaiA=vAedhu*EEnQoET!7ZtOaL(BwO_1m)owK zy?ptS4MurE)kL<7KRmc}^}Zu(W(kzixnU+eBS#M$-#cG0Y!fh?eUaJ!`Meg{lW%Xu zY56BHQaBM`-6z+Mx4MY)-P!ii_|8Wo`NhvVT(tuC?TQAE7LWKl*;E`lch+@j$ne)I z8fyLkW&LiYP$^r69Z<)u9WK9Td$PFW9R0(~!d>!=t71)3rqp>&g`-MHn$fN*u7sJK zoZ{6cyK-XLkCO|UZDNDCb_H#eg<iT`;r~*<Nl7h3kWic3p7Q;+z51|(!oDA?pgIyH zmHK*|Qu5-*2C4C)i=UQ#@nN>J?weBv^Hm`|)^g%<<=9OsCt&@89(KFW6wee+b;QQ} zXRp_HzrYjzc}Rf0QY7#F`m85bq#MtG5!x0vL_B3Q?NNGnD~6+C-#4=Vn5@pw`(`-c zz(YbNM*aSer@SY1IuXul)rxo@y>C8oo0SM@S}uzG0>ypGnIlCbWYg77og=M}Zjw!= zCob6R3{ea5vs4J1s>NBZ9T2KGxkHf(^Ebw%O*Xh{Vc|_H`;{_By4ipq=&gYJ!u+Yb z<?6KsY-+wkld7HcqZ+KejI5i)AGPPGfv@(>BsOx>B+q_*o}o{!Ntxn(6KfD#x7?Qd zOSEQgIBbg7e#0cs=d7hR%3SU`U-tSeS1mCcxk=(|nBonUNrahFoVe6iTdxfN#usa9 zitbl6FtRShMBAbdJm*S9YO_N-h)e0?<h1qYl`ex24rgvPF|+VRY~K{`l=gCkKxIT= zVC03>9s&9h(E%<I-?H{IQf&CGjJ8p|(8plb^NV3(RTY*3M1e$vN+g2q(OznkTx<PV zN_8l#sxF5D@%xlSRLn0Hsr%x!Ljn>q5)sNzf90b`_Ru-f5xq<WBR7PZFe9<6E;m!2 zuXh^9wG-@IDZiLMjEIke3R<1IOX5r0eqKppM~;22DkRlENs%@}$pieO7zy#=!}x~G zYSPGDhs^CCcopODj9oXl^IW3dsq3cIL9)=5Vq>UmTx)BI$<5$KuojKh_VfNH%?AAA zVC0NkThAP#a`0f)tVxr^NX%`STlCq!8d`0V+I!);ue50gUB=)rvA*nege)a>TTXVG z3Z-l?<RGa?6GnAN5%!V2vVAiQ&RT@@P|9I3vql@15l;{HvL>9A%chKZU5c1EPzqB= zw99a4FDv)B8Ve9vZQ@3yER-5oB*A~#WS)PD+E+W|A4VM4tW`&4(njRg9`-_|NJ(`| z`{Z;zzB5oJ!E?Be@d(T`oTrSQ;*D6;&IXr}tt3gV^oBva8xLN^$TKBQ9oCi3)ij^Z zX_1e*bMV)iWZs?^Ki$yOo{GK6{%}TC#B#R#EOFSt-ZKY2Z&6ZRdXbvX?ykCrym9(S z(YrHE4DMnsE#l>L`&_gw?+Jykh}5rP0~%K7?HL9$jA_ZxvFpM02gSN>DW6?d)mm@g z^i`xUj@r;C5oWYmk0o_>2$icg4SRRffC8tARvZhLAKvu1c4wVNc3bL&(_MlPlW=#N z?ji#W(HF^`iSDfk9279pg-WSF)r_O@t*)6T?MvUy7Bopsd0{?Xa1^ywUi5Bf9D9wv zOb)xg`loGiI7F=-PU0O*g%<6%?etBNMx3Q_hhB!J;7Uj6F)aDjgcthc*<b!1CPqe4 zQcnBki)Vihab2)25*uE;@oFRQY(VHq8<i8K3gGdF0!b#6XFs*x^B|Wj#kEWYY*G=- zpoH799^uKXkIIy1aKj&;q+o#A3DacD?1iwlo&Y?5D{@ECLJF8k#4bA-BLrfQ_-Z7R zwUm6VQua&?J!!!8;e_jgs%Kn!q3M!P)pS|oJ!ugYZwe_bh*dR9O-zhJ<yY3J_8cHs zL72TQ?z*W(C+Cj{DyLm3x^ww*1wuuiq>qM=zx&OXig`w$6CsKGXTlaA<=U}5M>6H~ zW#V1VI_kHDIu-Ytfk3)_!@c(RpPDTGuIule&DLI<OV^zXuPM3C`KevCBg4HHR9u~; zZ_^TPp$<V!79e43iOY%`tC}vc-9LU^RknGv(R?*W#~t1DPQLyrx*Eycc6zQ1P)oC2 zvhj^IbESQXk>-kCXCYQlIgd?Vuu#Bu?cMpkHdOZ5+c)%ZmYQIaRvO24ezY|uztZh< zD>-@4_K_#}S-0yB*y-_~&t)HSeZr?$0JSO`XJgZVP95n<_J7qI|F|iz_J?~%v|U^z z(sJtdtU4w<HQ%stil?kL*IwMQZ$l}UtEJiGe@Fs$Y%#?A;HUX`pYNz6Q?5zP?p))g zJr_On^O#&{L*6-6G;n{^vEX?JVg<<>0K(~OjmlN<f20Y^#ydEwgnC^!qPT0?3GAm_ z<T{Tn+F)M3K<YA39r6rE7JF}<uL295;$0V<lKbfSYWQtWV=ge(<RNOP+&P~&Ph!^l zYSIwKNc{Ws@V?VBVmj}_x`wpu?g|q_jcXl`!OK^YJYd#10D&hPHDSF>n1ES{Wt`G% zPjK7KQt>61ZX99eph><Efu*K!_F;)|w?RiD`!}0RN;xc$f0+p{+2N~tr0CsQt_xNZ z+qL>H;e|eWPp!4po+;fZ4iil-ArY5^N3GMoWlNzVwE$s5Wv7Q0Km9#5I>etePFl7c z-dppX;fnG1*|IL~u8_SY&mPyQN{_q3I2B+03~dY(Uz*}|(A71E6;B(@LkOR+Nev?v zYA?q)y{_FbWdHV;UYod<B-b1K_x3*7My*sBxf<?he8E*DFngEO*A2Cnxau^sQ_dk_ zX6XAA)(_?jmCH$jIg(`zCXwxo7O=+Xu*4di2Ek_pEfn&Q16M^)@kU3SbxLadqiPA? z!R!~P?3y<l$!X>wW&BtqhBX~p$jHX&!TxD0O~67xJ2$fA2<KS3T$mMk3YekQu0`NJ z=Rk1g&coUQJ>X7!cDXGmOrV@a5bIdEp1Ty+g{Zt5F@W#7z#vbA*fZ&-aHUji06aNz zXgzIQ>1zCjk6J^&+Q+~LELj&sg&q>xgp~r#$~)v}%TO$382Y4s6q_>H7=cW^r1zB6 zlhgtEfgYn*&G_CXJYOs_?Fg(u9T2Y!Lu%J#O!0mV*ET7m`*}U6;<y+6B-uN-b5ytF znRxAPdzNCDTGphplWI(uua7$X4teIw1x;+v$RY$)jZ~<zXFoK>>!#1H_A2g^#Yu2| zxwBDh4344N^{YL#h#LuUk$nLXE5!!^Csg)AgUH&evS;z6!hD^}c2d@5aMp?H5aCjq znEgv4&qa%MA<gA_FBTc%RAHnD8NOo!d>bB<<>7A-{{;I+^&;~nAv+QHE4^<6CCAeY z1+u2ydK2vbzo^>PURtw$qZszKfwSRs5^Qb$X~h(~{Dc>ZMQ7t#UoN$1t9LNaJU1ME z)^`+XYvV4yS?{b9+7>#ss7=a3rKSRVhCbGjNmmuH+oL_TLpTxw2@VMgn%UchKvt%L zW@|qRSs40XuX_;mhiY=YgwHxFdkF?k43J_!Ltu4qwWWd6>XF8QusS50gaz1H+~=1H z*EOY#0d|$Ho-br%q2)^N$+W0!Aw!_zw3+x}<e44LhQ*<Pbd=@uqBnl*ZL*O9E-QRv z>(%W41`~hK-tS&%g6}o0bR7~XWg#2_!~Mp4zo5uwm)C5*C-%?XB_aDn<@nA|m_AT5 zbE2g+^6V6E4UpTOJ62p=&Yd}zE#q%_o1dzr9RCnoqq*eNJ!z4x!S$C$YD`uO9>cew zGclm}`;?iEoV^#X&6NPA8H8BQ@uaHV+0UDkZg>6tZ$sBQG_OwaLYjdGh>49F=e(`^ z$CV5D0-NiQuz*zbt+HiPytipnxZR)#%JscIR`p4=DUS=IXutOA`Mp<`PkeYsI=*>| zckXqjrM1cGx<pJpC+XDa@t?h%Z&2rY^k#=57ide@)$xwap-Cy`Pc{y`kmA2*?;ddj z+>m5ho1psFnkU{u?#<Wx!fPpALUY8nf_mFBVpjml7pl9~G}(k!mqEaJhf=|Hm%m)I zP9q!7;H(ur>0c!iv{{QyJCe~pFJ#Z1;F7ARWTPEN%1-@(tw7A#yK#0(mqWX1<9|S3 z^s6{7wvRT(0Hyk%{FH@$;?a>C%Jv+prsQT4gT5{Q;W@|N1A3HTiZs`l)!z9pSA<Q_ zS)Ho_Orxum-x{xFa8o=xz@=DQk7^uM0*>)`)P)yRb(vgJzFwH`$dm$=6>zn!z3gqk z1~)W2QuKzD%0ZcvZ{W^1Bb!^w0jo*n8VY#lv~%a-dM4Wnsnh68lT4C0C7Nuca_|fY z^2QimE)BcfGsQ#BIYM7Pxza`Wj#C5+GqSOfacw>76Gj?~oWIIlVeI8?Z`0boXVZ#F z4a8T=l(KGl=7xm`n;DLLJyxi)GqHRm*=5|`_0xM<U`>L!fIlqoc-0?Q($pfZtrEeN zM$Hr&4nX0c>upGY+8(B8e`>zoY!rf2v8c^@*W(i=8^2j86Er!CMERsN2n~ZTJZ=ya zG!<}(IE^Ej(zTvA6hz8pO{XHAmrO_*Hfjv<4d-h@WzN}}m=gAO0XPw)2@*ZbBU8MH z?Yz0bUm~>);c`{btcBL4X-aA`-K-ZXQfUi(_*N06?n6=-?Dn?7ngekYr*1Mm<_^xd z+R>||f)64-A*aA?GXX};4%oLbMsNTQP7CSrmVaYixLt3S+<jN>47H3+4n@_Qaa#(E zHGE&Lb^g6XDbbJ<#L47L@k%IX3hS(xMvrGo?SSsbL!*0%AD>()!2MRbbO>x<k5K%> z)7c~()9L?6#2GLRz;Bo~lF&PJx2%tDMQoZFlnSlAY!CT5fbn1{Be~xXs8XyON8Dqb z*ojyEqeUGg!Ufr62~{l8BD^w`V}PSA$5B7*c4Qd18g_f=>^*l>;Dg{_md~>nO2}$E zq~->0JHqagUe$!Fj(J)1XXR&21qtEHD6BGvWn=UH8ec|=$b0ENqGrF%WP^PjAYqY2 ztf)#s!32ql<RUoAY!rmW-1#PC_&+MANhx_BGEoSQ;z&`PoDb(X)`P;Dwi@k4?|Lt5 zg2Ql86&5RE3t~iv1VvTjSK`I`Inotp1Kzmx3l96t`5$p8*M8r7;N`PlX;2f9ics7e z(`^a+TSo`g)w!l@U!FH37g#BCsef8e#S2SU49^r=?~0pf$B3D2Y(9H74<Utyzo^?j z7}%2VX>Q1=DV`pW2q1U<Ky$fabm#XSSCTUH6fT|QKE>q4MFm&yB};tY^9EF#L~&Ug zd-dLiO;=dcyjvg!0FaF4AB$EbH=4s=s`+H^602f(7CG%m(GRn|L+rcc**D&z&vPH{ z*x@@_{I7S?3b=i*(>i3h#ZO%GpLy@2V;08~e0c1cQJCV%8^aNCvr`Uj3Qd+DLxnwp z4NH8r?Dw(Gh017fW2oMC<!q|^uTQ~`F)_NbJxBNXQv#!AB{|Hj+E<#JyE0|LLro0T zy=ifI@s=%Lj^!k@08FK*k&H|+KQYz7l-Z(5V|RR}xKP43An7|B1<DwL2!;n&n&4(Z zXVx7;8E*@sLUOf}p=G5E9b(T)IvG7k1()KuV^LM4f?Oz_ChKZTkCQ$V50dwcC(I-~ zPuA7i!zM=tL@&5QFhUUt9-$`=SeWv?ycb&|ENoVJ*<6LK`Sc~gCBN(l{%EMo_dNu; zdKH&wU>i+egFj@#kh&L4uN?LIIKtQ`^O~$Pmja>Li`pi3U-NO~U#*n%5jz7uu9b~? zeUzH_qQ<*BlKB2=lekXNc-H&}_ATl#p+HXGi7zMR`(zs1SkPcKRUjsAetY$QLqTU+ ztOErJkk#h5nCh7*1DDxpF>rMFSjdOF4VE4~fT-GQc*sb%cka8Vp(Zq>^v4S2>%Ahg zy<B4j&B}AxpYShkMp&g6e{tnNGfI4eknNk|jc2%uj`?Q%S*|ORy&}!KZ=vAG{w#Z^ z*^oTN`<FOOm@`-ANnnsBTc5I}J;_pBw|&!*W8Aq46#QQ<{)@>v@WHPWlD|9S2}um+ z12sPO(>}p#HNmq4%uH}Pj_ftR)qI$GkNcSYGH0LPhqn>s?%1e3qiuUnmHC$i+-7pE za_wMm_0HBWE+i~EmhJq;>H_3)8YpuKl6Xu+lj-W8Opo)BYd!_KiUdC|*ZGqO2pNQV zlKW-{%t75&z`og7<E!Fo><p*@>);RVZM*1d2E;6&oz#wvO^EU-hwH2ZG#>7sMu$e{ z>Xr%$IJIHD%)40RvXM-{PAZ21lE)dkGX{2wo2>1hRu2-Igc4_6D)y@>8V}Y!R09Cy zAfLvhsr%?o7&&lq#7s9dAYlu<3U=;Hwh*;~Xar}dQ6xw1;I7~d=YlQ_t%>x~iY5(6 zGQbUa@4ne1wHV9|R;h?x&V^g*7jreZWg@7kqL#r}y<cZBcg{_vo!Rm76fY$QX((70 ze9@=BdzQATy@1;**K)`<Zzue6tGHNn-~`YgUF@q!O;34xkIcTekVaD^MV<2I76h}a z8ICEQ&P{6DO73Q=+o<pyJ-AwHE0@?JXJp7;^|qksrMbxLr1UrfD+7Io{OwL317*_$ z%4igLn!*OLk$`%>S~%`Y=s!{{{#W2MJqS)GuyHIm!fm1NU#slRTW3W<in1}d1icbq z%Q-R<A=eVt2-Lp8H+w@<6?XHaLy<BPIPKa<pY$9^kBuhQq;+MMGTy=1V7b{4tKT8C z5ff+%pWV06<|4d8hr))KnQyRkxv5BGw^fU*kz{Y%S@^eAtOL4G=1m)%CDZ^zAR*#G zq7)!GcT}QM?L`L8<_}vyrub%gATKFTsMs|11_ScexMDksUU=Mo?+_Q-0ixq1orLEq zl13dF!174?BWPs+E0C(Rid5&~xhMw-M1q~mMcm7kgo}*k<dl5%9J$sp7uXriqR+Dc zUtvJmo{H2=1$Jq@Czq;7DfTUdN#hCD1+4^64z9JdNCbQ`#k<hYW6cRR6!y|JeNt*9 zh$1JG=*OenM1w9)o(X_w1o;bkI7zd8PVzgXFs3@zdswi>6z=7U7CMC8j%1tfDDvI4 ze#Su)`$GaFLjlGmwxLNN3qEn6nUMwW=ktdVya23w<|EbK5anBdHKjpPL60!YV=IbL zCMK;I=Hll3j#JGx;mI&+2>l)v8<pWG@^2W7hPi)TD08AaN85)%5m2`sOsvQ?R$)Tn zY3!z}N}9nk@vW`spl!$h((Y}T$8L|{>sBuaBX%{#>oRy@6(s=v+T!(cE(u9u^;|Uf z2zqU1RLhzxOebbNThO4CbvX(p1Z~Twc<&6tH|6}vI`UPZE0oV+_u~&sofCmdDs-Kd z?y2*e;<bnyT#dX|Wz3*B?05Q)N*F+*7`9iXYPJp)AEkoB7sBdnKgaOKy0-mZdQUOj z%1V$0mJS`PYtOFnG4|~{Lw6$;7;>xw_mX9>e*R_DGwG|JxSQ+sWeVteaO*KGQ@jsF zzbD?Y2|y1K)LZnb{s;S!b127OTc4ZQ4hKp=a3ECe8y`5oZT^XWC*{-e<d~Ocj;ULT z*D-Q*7y4Ar#q38jO&u5C5;t(JIdUdp){fEh*H-B2^SEfSv5Wg%rh^-OIP!agh>_jh ziM|OE5Pz65vdb&`@>i&KuhH`#%hEoUBwyg4Tks>Y853jC{Wkw{-pt_PUh7>HiprQT z&g}UesG?5uey!MGVNJ}YCH4(JO-I%*uxJ16?8V=`|M+#YFfUA~q0u1ie8FAFGU#q~ zA+s#$4@~1eEkTKTgFD0Q57$n|7w0vhr3qUG=3~w8AE_ce23e?7hzHXS4t?jE&3CO^ z2$mAQUo<jlE(IMm)(Q?ks-*Gl-QB7DdL(<dtCXPxi~wUt8f(LM5U;^j#e&wQ!1*IY z9$_T0nQ)rBpBEZKNQc&fs;d%cR1LZ@ez#*csJJ9j0gM+WO+)bv_Fq|Q6HoD$aYq#+ zcG`m2fhtqYeF-#gE*}x}Y;YVCC|^3*TYxH99_N`E+4r*9h2~gKae$P7F=SQPDBsqi z3MTAt1X#CNP-Rh807GzR#j9rn!UV5G#yQ1ErM~aO;1$DaUj)EZ<N`A|7Iu<G@LLCz zoxXZ5P784wA???2u>k-bAr~};3?LH`9&`xqmA$HFL}a6W#fMoQUc?l!jW_U6DwM!s zXqGwc<~DR}jZMg5XttV4?D+=JeyChXT)%w!(i{|;W+Z8|9uN@pj=(BJUJS8kQ^Te_ zsi>ftp-^9>uP5Ni*2>+A{{TP&5s}nh<{N%GHHFxYf7tU?^W1?hQKSx#_;OpPc!X}> zxJ!T%SKI(sI#VdM#v(g~N~vF&QV=?Bu1xG|d>vI0sVuRpX6@(=v;IXAhlR8aY<Kz% za7YpnC};CYx~GwmP5#D5^%fR$=hee#i)d0tC~~Z)(2~K!Q#l(Dg?9#1p(UhE5e#?J za^C^*h03}`YLM7U(rDTZe(dKM%}lOcRE*MBMb25u*SeuuSOofudueA~)d$pM15PTj zkIpQy_OPj$@tQP}m<CG~=<txJ023?RJWGUVYBLhI#72&k;DbawBoLZ`nsf+ZsmM<q zk~rXg7V*s(6FeQn0Rk^ty*1A9xM;e$Xj>DrjsxvW+T#|j!#Y?$3W!5`Riog~Uzdwi zl<5VW8tf+9_;R1bj{bGFc8<;zz#lc3I|H`pyPvC&-XGG1G}ufxQC<w>8_hRR!dBd0 z|ID88MU<sfvz>oynFCL-Uh1q33gVr!x027$X|8ZtnD9K+cp(q{AT(w(Zt#tgVxl6r z7&wih?4)+A6spJrYVFn%CY<*fDHKAq(!Z@=_Z`)R&L81*qfJWE*3@JH0ajA-$f$Iu zPIFr7m!jzbjTcWSl)jCdXZ2PH3+!5$?hzOxK(#au?Z3E4XJeohp%)9y7UkniD(--y zx?KJ(FEpH1lWb~`4EK8!j-4W1m@`>pR?~@Ti0Giov|uYvVTmVZwKn%~=ju|tCr+<P z8C#?4j!e1$CJRu_jNr5XC3?=Dv?kTvT?%Ups@;H0(&TYAcHgV{r1b0*FG^<<wWi|i zywnL7e|jwJ4l~?pKa5RSDz4+1D$na>jQ2CZ2t{w;wmIN5knqA&t#lQUUQi?E$bgOi zfp#G~g4cHC`_rgx&!5>M3)z?6Z)1;4hJlhq4DJ8Q{}|kJAPyN41*Sg!S*RKG2^MA8 zLRH)aI4JS#J4_{edUj24n1BxcYQ?3qU9V~{lSbD4<C1+}^lz!A2j)mU87X(gn|m>e zLG`dyU>#i9t3+k)NQ-<$e&vb&l*>22L;>Cu%^}+Uy7;}$@2)(3eW9vBDFqI+lro#L z=INb3S)~C!U4$*_2ju+sqf6IpX7+%IyZd=Y$2)YrM%IOHXDulB7TnzOxfN_;I0O<l z>hAH?^TG3hphRH~t4NTH2=gSipsu!KD4jAK8HDXPEdeh~TD@?Rgw=Bp$(-1M#8^W% z`mNG{*ANrnw`gJqR~Wrm*NIsst<ffc`DllPl?a`^U`~2*<6lm5fIcYHew;v~09`pa z5KlRLkW>)pF_fa|12O{<f;)F`A+rY-@%hfx^AOHR1?NnQ@=ry7J&l0uBbww$i{TuO z5UVoAe1mvB*~qKh=X4-6C2kIXw_*G>WTk<!oyigt{VUWyNn_y31TfV^JbK%KZ|=2e zl3nvS8_l|E&el`H{0VO;O+bW6otIocjk?LO-uzB|op-UH%LfdS&1i?mT>0)^j+)BD zin$ReN8sY-;}2zf8~X)}w=+G~p-6%sZnBV;sGK{8V9^eGW$d(eNCb~i#@bNn8keyI zAqxpNPXW!Ko$G2ap_;Rb?rm`Co*|H|y1Y4BVU<!tS`rP>7$%+#y#qCLT<ZKL4<X!d zz2`0zKs^LBt`gS)s*+Yg))sCURVFC810$Su|MF617Sid6|7mG90WYMrt^t4NmbF-L z?UPcnf+ett<Gcub1V~!42yN&-DS=u8$9?|0ksoVt6X@$b(b0vc5&AA!Y@C=O@l6*( zhsDWT!M~xa>qGL;Wbi+cs?uZ{>KV|-dt*uYh6I4JLw?<pxG6vy+D9iy<_7?6(^6{R zES|%H)*Crm^zW4bt)~1|5eNXdSYp(!cL>n*poR%y6%Q>9_yW*!2txzMB?0KRu*<Cd z8tR+@{e76E!b*+rjKWcDj}-FjnP^mj%j}BeWlhQwW!R$825=}kr+xK9fS+hg#cjD| zAWYyguJ*bnt(ZGgng?_Y0Sp~n0(%!B6)hPUSuYbFLL0qf{R~xv6j>0~mBXDKtOvh^ zu6kDPsGg64W*wM&5S>82r#0`_7Y1||uU;@*f2mhl(&HyVPDI2*4Yz*AB_V4f30U5W z2OW>|219nHS}M8;tqpH3T>~NnZ5^fx5C|9}ggY7w6<d+W?yBP{y~kC4U|%oL_v@Hw z@gZ>|FiwON#ZUfqPtrF7q2`I6p;lN39(cd7E^j5FEV-kS_0(|hO~ABr2+ii9!^P0m zDgdi1fjlK*J{n<62^?QSzD7D&NPBKnq6Z<PYKBfBS?cbUXqb3K3VZ&<qbRwTZez4N zsC>dy9Uh$hWW6qQ7O|(LLGoU5nZ(tPfL3Lb<8ej!X)B_C)Lgk0v8<m*s8ov<MrJv_ zbnBWF(v}u4cupF?+ol+W51%STw2$d8X*oe+SHO<V6K~Ffh%F2et<dAzpZVR@n2R1d zyM1r9|MaiWXY0aaChFJkz-J%OIlde@%NLdVRrT^L@IuVR@nr8mD0EiF0ZbRjpt(aV zq1szEfcwP)vo<_yiM><n`YbMth$Sx9oOt073B;F7IBb&xu@cK2vdA9Rb493r1vMov zB=%muc!1k1eTwce!jjOfjM+L6YgcYr*#fZu$Seme)W|Laq&1=W1C`tqj~WWZ7uhb9 zkBFzpvZM$N*nQj+8I-k5s^Hmh4y%j!4CzYoxtG6i83LX01qNRtr$F;F;`D#02AlAk zd~#XTn%*wdaCIQ3;pynuIMU<f{<*MmTmoIG(hmf%nL|!vx11gdyfnX;j-WNeVZ^Wc zP<cS-hj0T07>SlrPk&SuU|C@IkPM)P$dghkkYWMRUaoq$entZnGd@=VG0{N=tc}`9 z;?Gi8Uk0hnuZp!pV%=og#@82L-QhbI71FpSZFmq-AQ2DCT8a@MbG4U&88W5fMi`yJ zT|3|kkh4W25fa?Dq!%ti`{85AsZg*&)e?|kMfpOK6d;?)7Kq$7g@A!iU@D2L7od>) zQ)qKUlY$DR8CoK68%`#Ew-GElp>L{5_>~0%{klH(<4L)bVUX3}LZHJ<FwH8q&p3`o z9BGVYlWc>^F4|RBwLg*wtk!{>#7`D*b@ABmdfXB<F61+TZsZIS*mYi6I^(80kmk4@ z2lvG9<p)Vk&LxVZ0>D@_C}WM{U360vYz=9n{kn&nVE1KWotGA}w<G}Ks?;o*@W@#M zy2B)@L!q(Eu63i)gw^vL_^65KI$#*F=nw->+UzK{)Ivord<E<{*Ts{eDFCoRoKHjB ztuc8N2!9)ufsW$OXboY*`mtuvuvG-0xrJS#VeFx%5ZG!G8(IR1BNmvU_mc_d66$jQ zlP{vz@(dNi$+?kcBC<sacA-2linPezNKuf4WnAUkVJ$}x<M(acZ`1j0(LY;89?yJy z_wxg1u@wMbgJPPx`EEVJS)zj;96DIA5nH%;v$J$f_i`QDbFz@;0yLfti=P^#o}q&& z96>mBq23UryH(%#W@MkdkgR`ziCqoKKzR_613Cm62D2(?<_ZK0UO`iZtD%?eBDzFp zBP>^LzCPUrwmeuhj$XZ%Y{LGTz3|4{MIz^XUuM0BX!2^D#6F15DpQ&l7C3E>i4Kk? zxI;S>G%Lc4;<_tTDmd}5RT`Bsa#AX;#gU`=wDENT7oIYX%Ipv&r$z#qn8SQewCR!W zhswOyOX5(=2A%N;kdQ8!j0;ahUo(0ZKqFkC>6BtP90m1t4`{}2wxXPfbv-Ue?p*RX zBVB7-ROo@~S&@|A`SNetdD1c&U+Z+r#xo^-31U>f^kf}xEW~Fb^QDT2o_}z~o=7+= zISae&j0^x*NI0g%cHJWrr)h7a*&t-L5TrNo!e@^?8q<0AzJKar@ENOC|4z=hC;?XT zb&+Bvl1OdP*kpnhH85fJk_M|EdIC7bF|g?ldpk?&mG7(-ux5Wm{Zn4CziFS6{)WtH z<lnkWg2;?4-K{P2+YUkK;Y-*QTgWn8H$kEnX3wzs7YHYxz{cN7x&L!ap6rjC=x=dw zLnKIIE|#X6RmgM~pfV{bOw#Y04qM?*k~4j$pINtJxwRKf3iL;tmGzTS@wem9+SRrE zu={x16CJ=2O%sS&pXawR$y?~AmnKY8yqk-ED!t4A?EL+jO;h=78G`CaFQa~_(l?XV z-_ADQ=!(zpiGAI&YQ?%3bisQstGL=5{$+hq;V~#U2Da|-8-FctGTKEr*O(;{+giSS zw**m}HKE6XT#>V>_kbM{0L@}j?gnJ+-Be|Pr;A1wSAC^z%27fSn3!4oL~|13P1)Z= zuam^R(Z*DW;ZUh#XQ3{O0zmAOig)gW)E0aqh2qTFFc>3ZZ-ahrCcP|8b^zq7;3`eb zN|!sa*qn99&uq`+rNQVW+t63m)^lvibJZ)jnZ5i=7m!fUrcJs=iw*)rHJGfu&_Q(U z@G$@jNuX{dS;0mGuthr^Pi?~ucKXF<Kf86bv%g04D}Eko0rcq1hLq&o#d))9W<Ygr zalp7`lLK50BCRpp@x=EnqJJ~c*l537wT2VIP+Yc(zGqL`<*EZ|a9bSN-F7*QnXW!5 zu_As#b2UdIWJs24qQ((o71en#eiWB%mqe_IA`K6Q5}+5`O=k?gNQc5RZ9?|<ct(1^ zQtWUUz;d~1q|M`g)r<^?_AI*HnUL>5*=SJ*@O-eJ0Iu!mHjY&SZTo_bt>Nl6!hO+e zM5~p)OGHbQ9Qga>N}>TZx8-x3EVRm?YX-o`@(_VTv9^>bJJAH+8;fL^GOFL?n!x2< z7qCfLJm{FQP6W)gkS=Lr+*LCpUF}IKIQ$~$Gldo0n8R}Jptv?7h6nxAx7K)nx;O_q z{!EDr;j{D#*sK9A1?pQ@mIvT-{teH$KvJlyu!sb-UMpRIhm<3Y(Aj`wa0|#T0a@!Y zjxZ9K2VIbAoCtEQ0Dod|4a2ADsw$Acl2|=Dpwpt^gRj6jq4Hu*D5(fp2>3am${qxY zvky7^OA6RrlCr+e0vtSOLDv^0mmF0Kx*s2-_ixG<A+K#fI~WYJ8UYj0uY9smxko6a zEXOx9aza+E#U3Dr2Ts!!n;k_$9~7cs!(<SqBG-Trn8O+ZK{zA=0z<k-<;0=8hDJ5` zXE{VaJ|MJ48_$XeVA$BoMFcWE+wk}Rr^Nk;&NJ)e%3e+MAOZt+F?Y9KG}$m%t-xuE zChL&gjEJl9IJ%Wk5(#J)x)Dckl};@@7NmzW5!&2Za^hj~oVsi=(ycKpkb!Ou?Qm;9 zXlc+IpwPf6!UC)%a2J><rWybX@UySRis0HXrhW$g8vt<>yNvK#Jkr2+jg=T#^IRc) zxq?7`Iml^(8m&Tb*B4(Uq~<Z97E&0eF%)cLBkv~Ha)2BxN&eB}o5_5}huoR)TpT<% zyg$5SG@u+2)*t@R8U8I_)eCv(OR%O6xh9uMnBE6=1A92@ef>WE53`+{N$(30Fvr~S zUv_24NU2SrZGf#xlC;Rllj#y%N{nA#KVx8g(Qqm3Q7SAVB^oiKud_XImnNbBm3kEe zKR^yLd~jH2DOGGwP#(dS;+Zc7PA|RpiKBRH3aP43<#)E&uS;1~x)7DWfq&aN)W?5p zi(bsQIlGR8w$``lckdwq`jfEK6n-dp{byxuz2$#;Ou||#VG_Gs8g#Fnb(&~_yUv7; z%ov{c{$|h&R%Bx;cpduPiBA_TWWt~nfrtXkgT06<wix`;ECEqOf`FWnq6Ss_5!FHm zU3FqR#$nLO@kPOkWtULDl-Ly#bobA5TjDjTnX5GrzT$DK31>?|Y`yp@86?p@6NysM z7)*7QyT+=#L2SBgh{<gkqyt4d=^-d=vOyJp!`>b>fR}_bHDr14)#t*%@FKz?M`&hZ zr~JxC5GP^beToq_d9xPL+}$C<rX`*y=??L!>H|Jvxy_-qu*v-TU%(0hv4SDt<FZ6Y zB{xK67$|_E9KJfvGsEGZrY2#4RduhDqEPgL&c;MnE31rrts4fz+6XW<m-$>p5jdWS zvdLwvjeJo^Dh5#xK=cs68ZZ<Z#=)Syr5628bRfY(8ASKu(b@yhqc0<^v?raw3j5^# zX~kd>t^HUt5atLvuw6G`Z^g*Ah!?OAUC~15<qb}UxRLZSaB03BNr`=fZVkt*5u|hZ zMqoY)th?*{7dRNjh!bw&5B;l%byc*?!dwE$>!>OqxSq!iqb!B4E|w6&unPlsE`|p+ zkJOg|p@hR?)V}mT+=ZeTLlahxMYB*y*$|S+o}0N*?D!k|pA<6dd{uBLaifrA43MyB z+{)pAA<fPxP)sWB=*B|}v09`#icP@|50#S<qKAoO5f6uj#`3Y(P<mwxpP1{`%8+Wu z=c=#(1eX;vJic_#iHD-&WZe>HW5G|Mut{k0N|oNQazI=l?FqyaqWJ};4t9RviFpn@ zfH9mX0-&)15?5@04fO?1EXO@%A=dStW~3$wxJ9(a_OIk0Y=N!@0!on@fqrpw>E5v^ z-k}@Za0?o3gbD7O3#I&ITJl4oNu|UplINn2GMT>NN3>J3DqxqJ1BLl~Zi`fcfcFXp zprj~@U?Q6Y08bdW>f$BP<3&Og7%>7=@yMsM+|V4Dw;Fx3K?Le%lE4xoS1kBfE(#DZ zCqTcEQBD_xlBc4_`NhJ_Sae2(P|bkU^WQEJYU@ut1oA1hknVpRbx(OcST@u|v>&vn z&bqY8Izc5*xvG$^E-&-phGTeCd#ivoW!a(nYUt<1q~^DA$vy@Uh7z^8bpW!})iXdS z*;-N5v>+I_K(Cr%hyo+38qc_4aR85ly7?wI?DzELFO767tlo}vzt^XDeo`~ItW~o& zww!3cP%*w^rdv~%$hR+ks&ivO3~FcxYO}-+*~hNPh>x=gQQ1?wxLO-?;M!9OzuqOx z&K5~z?vLBYtLN!0S1E8L$5YuOvhgf~tLaJM$(IIDzZTAs-hWbDCp+H?6)8MA(OFj$ z(8j>>t3H5ME_;T4vQBsz1BjH`?+KnwT$jqowJyNJotlFX&>zc3hDS%T5+3$tKThDb zzprL+&mH9~AtM#LGkp5$%_b8ht8)MC@6Fxws?~e^h*eGx$LCM1uyOlf>Q@5!i&x4Q zGU31)e+1Wuxto>H=Nb6L0dM?NV(=|IvtVKCPMv(~vEK%e^S(@hlfw7woBlW#Da=eb z=~{Kbcu9limr44{$Na2rpq7g$x>3;Ee|QzS0UHDNgg}AtMU)e@x*^a?=OkK>Pcvo< zwU^M?)mn`xATDplyp7V6kl2l1@YNRBxAv}n)7Y<-ci%11P~%p`2&5Ohkb0C`7S?$t zVZBY*`K8Iq$pq~7_x83GG>|qA#_Pg+FK!lpyQvi=Ur}k+Gg}8b-ztuiET0Q0fjjJ@ z4jfSJKda||+=FpBQg@>rVk}O1e!!*|0B93}Z(o@6rLM?lKM=xIsZi+9Fb3K9RuF$4 z20Y;;CsfT4`$6mc4Q9rWrWe}g*_rjJ=r&`xaP(?lWFK8^9Xtt%CwvoGesE7O@f#sV zO}V4%J+*^9(AS~nhb-_*eV@#!3t>}67BTX4qV9m!Lv{*ehsd38V<Gti)rhbK1C|OZ z0nXv6P&NNq`S)#<6O|%jz#rppNT5C$3={T1;?f~~rDqoy@Q=XEB4PJ4QBcvLoN^%q z94Xog8n_pyLXZ8t-@98zc-FDBo|CgMQFxf3=gyem5*w%?qKM~k4i+vE&7eVm_U`o_ zVgT6iRHQy`Sj&;z=&V!i<1K-bK{lE8GF`(QB)s#wF%QCG5|U*Zi{e;TU`N_*MIEfA z026CqqWCVxJ)lB7ga%{|e3HZ@(dczgte`apGUYA_Vfn;^-s7NT_AiAr6M7vGZhPZ# zEHThgstAN#7dVZyj(VZn3Z|q%`ux6)q>@)4p7A2lo~jh<BFJ1@_S0=g?#bP7_v<Vm z$8ITi2BU3_M=3}88c$6U%HcWaBZBl4=a=q6m%S2)tG#?uO8O$GCHm3gO~>toCByh8 z>2RXlkSl04wC#OpK5|<i8FkMqlx@DE#r^&kCf0$8<fRnY3A=@%DQGDxkQpRV1e)2< z0on%s-&vH>%$gy62n*VC2U*T`Vy4R&j9z$v&-Hx01^#1O1TU(#1wvSK!bVx4NQW^6 z%!ND=!uq+OLiA*p2)YtY@t!8KRPfpEcB%6atb-`ly-;^tE^)6TG4^&ca{j^Id~l9g z9`9my48chvRwVJ^oH#G3klR;-v%|)BOQ9@5^JF>e(j?135fI|N4zh<nus$mVWd7Lo zxW_|;UjaUs2HM=lc*E>~V^MOM7Cq_fo^!!MW5PjOe}HKGG4t8Km!~9vj5}9Kv<-0} z80)~bo$&gpPpEaq0dfM=tp{ywXExjbXOsr&o$A;C({Baz>|XEn@^AmnHMr^~`RkO@ zv6rNPI>Epx-Lzlsz;DRDt-5vsm5ecy5wmN~PrP}9WcDB7Kl?+|t|&Wbf(pR!*+Ip* zz8%Fc93CpT(jm|clFW(}qj_{&6F~ZB9V=c8=XW`vdndy~NP7ij*b|cokV8_zwIg>i zEhp%KaG4YVklNn2fI26GhhG;xQ(MlRkwV<h(d;s()`IAMq!5=8K#J@SE~{F5SA|4h zjW26bVeiK9wEHUTd6EnG5E*mzPwBv1DWoVom1W0&6lu3Xm<~OCw?(c<Q)B7_>4Lz) zn20W?L0tFHJ7`%670K5!BZah(LG-mA0;6lxvNW9gJ(zFpz&O;67%D$+9hBXL2u?c; z{TikncwIyjIDqc;6Ow!o1JKf&J6Ew)5R&2R5Sovj+_&XVEf2O<hE-Rcc&r!!4E=mO z_YwM!ctsRQAWYk$BTZZV{voNBGlUd^w2g_$TeS@`praCad!SDX%FsV`+IR>^t_(s< z(K$dg;kII9mxD+ku+_$5NY&0LR=pASR~zOPh&&q}P*vjGB)x+{Xzu3qW$%SSVEJM} z1EN^wPUrZuQ#?YV4FNM>JCi=H3YINnvCX*F{W8h3XNmTJ5HIbUA3HJ=kuL%5MChK; zMF*^f;%`vaa}~QrMrI9!L+qfn?2}2I_rJlA8Ff+74(fTBNYUfG)`+!f5P%TY_PE5a z^OjC-F_6XXaBky{zC&8ek=0~E87G^t@%8YOi~CLjZMhk|sGM#n!-<m7Z0dmTEW^}n z`<`)?pb6<j+_=OGKC~3WG0K$-Aqc_8Vx!H^KNsyK%qgI;%_M}d82(68KZE;duz^#& zeK(%1;?7&F{byecKNM0*jAh?xXuwK~8dsbZW}=k5iR&y9;&wm;uwmk9wSTiD-tTwm z3*d>&Bn6pvAKI0n=-j3R%VAdyMPB#yxcCy2vMA4z7E$Io4`W7X1X{G*C#MU#P>llF zx}W;pb!#viuJ(&(hMF}oOP*LfF*?Qj{WaW^>PRTA2N3-Bi61(<6(3{ZAqA7N=FVdP zi!Gn8?ZfVaJH-@0p#xr`fe4GuD&xEzX`7<yY6QP1q!*O{`ud;4g6h!(1yxf5br>q_ zk4j+r0T>)Lf|?!tI|3Gfpvv{}YEOCyaNP|!*GNqul3Vrz)1wruE;~u+6H6HnJPGIz zGJ)d153ycbkNk!D8e-0agyA7Ar56cTi+T*501|XDs-z5~Cc0q1>w-vO>p^tkSi-67 zZ7k*>NgFXf9g&PIimwM#0A7!@CJqsjc-7d>6UT^Vr#p_GF&Djl#Cg`dv5`-hWw<NG zE5WfGei9f|D?B!U_SuPJ|18>y#mYAcnL|NmFpo3b4`$6bOJWaNUC{L9PVWijzQ+c` zK(~=RY^Xqd9P8Tj<M%&6J3XL-@_qbpf{%FaW>gb{tN2M;i6%?{kLgTb^=0|NyNb?q zPRDJD^qXPxO)8KC_-~2L-WKpFM2w{en)c2NB6;lSM)_&iDDtejUApk}rTK5dlsEix z6{W(!MoZ6@_jIEJeDzwdTio!Tp`nzU3BRSdp4BXDO=U*@Sb#+Re$6;T5QX`8Zjt9b zsW{)E9sl{tWmc{DYvi5x{Z?Qcynqdsbs0IJH=IvL_QR))rz3=1L&=&;d25zm$<vSg z$G(*uZ?d?q_d?Ch7vo1CD%f#4eZ}8?Z%E#E<j$(w2PMNdz@Db}V`Ofx_FB!Mt^T9F zbLea3*D~MUil}L`AlE>ogiso>eb;%{tBgKIyY9f>Iz@~Gt%)2l)YK4=)*_%`pke#= z%$<S{Ms<I5=9CPaljLl>|0GCgM!L@eB?4SJ`_ANx|G7-h-J|STw?-E#2iXblB{eVC z%6vQQ<a`FW&K&Cd#Y2}JXhLfCxPH=(x71S0;;y?QeQo`+lefU@2w^wwNq|J?XB_I& z-2L+7E*bk-cFiLbiec{2;&d;gsMy7~w$$(bt?Qp8r<}=@1StOX!)V@1cORpdHRx0g zaD0N3b~e}K)rVH{527;Z{Y-H23It_ACBbjKz4ZM#J!mNjNDy^E$W>@u){qA&0&$i1 zD_n;xfQY@!`82RPnDoKHs84()5yEMW6uJi2#}k+TIv~tLO-e$MveJQ4m+)KLP|cv4 z#&(5k)-NA#8VD%?q1S=oR@=nT!A`Lw<V(bd97slD1|!=0K<R^5f!4aQ4;!G^{&6wl zZR5#Dj|b_E;0p<6g!p(o<PWFsuFVFtc=G_=Y$DcKQ(T=|@P`ghcm(PC$`=!}oed(Q zvZh;QZ24;b6QGw#vtSX1brH_Y$2UW;Y{p4$0n=E*ph_e7dF}S*)MZV!MWc?xGGDaU zg#fDt{=E&Lcku{K;ix9iIH{N=b^sy6xDgUgMhleTHF(yspT9)8wZo4Wiq1<fLt+hA zL*5^vK!_^#gEEBZ2}~%A<g`c)kW%hI09@^b0#7@P*CRk7OZr;lner?{2^lrzA=3!a zL;Diol~1&_Tpc|MTDAbhfPWI?X9#aY_&J<A+&*XZ0)ZAtna}RF1$l#jX^lbZ#Tw&s zvE=<iEzlROkFx0rCml^j_<FgARd{K`W!CIQdEl^e$(WxBghiHIla&1w1$8S_8x_FI z<;*(hM?lGu8~Hdi$;&1dAsz1lcB@=UI=5E*k_TTa%t8kX%EEG$eO?>cJmSyoE@u67 zfocNm5Y<fP>3Xw;yD+JN7M0PFw%Q8^gRxZ%c0%mfA%$#_k&$lGjXz@nZys=#7;z0M z3iJ|&f+zvrDuW<@kd#J4$1zli6E7*iJTA!|U`jY^c$(Ux7akLy@WSsR79e}dR3n&% zgvS1TIf!6@7${Nat~A+%6#|?TC?;<B5S6pqYqB<I&*0479+@(nCsqMm%bbp=3>;PQ zCQ*U?anyo-Jh!wL&wPT+UxPv{diQq<8D}U+cT?cB%CmR|%pY=XC9KYMNCt~!q*l7t zk3R&O4#Su;VJr<<WFkl-BjX_`rdsxkm@tA1pn+=@YNUY&$m}eSk@e_hH<9<%n3$T> z)k=tH4hf{tBOH872!YP6;dwX&Jdj)li4MqvM7A*%Z#ua?-SmyM7m%kJsJ<EMaXT1* z$>4HE4hBkn9la)E@ADiv{wWY58fD$_SyxgsuDXk&mA#eX3G#Xb3A?+5O#{4J?X7|u zd=!ATkl;sM7PguWoSybQLzm%=9o-3Ml6PoQK3=E->11u8Y`DzghUJjv?I8p^;gH&v z?|J=7YdusN<E_w?c)cj*QZegiB3k3h-a14qa8h-xxzLvjtYlunTnh1{YMreY8pq3o z2F)yPp8NLJq)a&wBO+)3|5gg#1JRiJUMQ#`__;Ag^AaC}wYuP#u$TX>a&EJ8sTnMS zN!nU8Z-F|QjXD8A)1(<DVgDR6ar1c`8(n))a0NFZ1#Co@o62AyTiRgQ0p@xD=Gj}( zdloHtxT<UHMA*Ry$T!_}g4ltS1OQTnS7L}kS-QDUQ>EqNpN|dR%A+|J%mxmPKweGO zzA9vvBVgeWmx9aL9?pP9&sEYxCvQ|4&+>ZyW&A)QX%i$<avZoiAjOI@1!LC$mxM?B zD<)P6i>m>!o#FZ9Ie7v4M9c8<23wE}u4w)|d#4=$1atRkGH8Vf!BkD)orlCuSOv^0 zpwSlVI~UHmiA>>6T7cJMaur($@Wzk;u&(Wq60;F&Zd!?Eb2C6IzM7~{=yh5#yNd1r zA|uWe_-S>u^T~6OX7(q-lL2vI+?ndwNVra@Lux4`V&BTS$PWlgRek>7eyTbLbsW`R z4w^f(v|wEi@(n2=+5xplg^Xc3Ztn(^vc)7OD5iLM6%XgbCUL9JwSxosw}2+0$4scN zg-utARXB7qQR`d1|0m^-gtR8vC{*=~6z*5-tm`NMKaUwmNEAY=9EaRd1b1o*=T-V2 zBmK0?4$^+(Z+A!c*6?qHcrd&e1bDS96k3{IM9-%U?q5@0oTj^(dkL?X!B%RAH{jm# z{Pq!nouh{bOGlAM<k!7Kz5LseC=kbse#{-eIng4cAS-U~e0sGvu@Q_h4x(n=faxg^ zm43*RO9o}XS9G}=XI(-tfRK`$d;DP-LRBS|6B$LQ3T73DnB^c7Es{~ZG=r|5?>~t( zY<>%FG5+)ZCAiFCV7d~b(klVGj#p8sn!gxC4<0jSfxJotx{<&r_xQc^KG<*!1Wa2$ zW*pCA$9PiEq8RQV#|47(h7jGaQ0XG5_LdMhIlXC*=_H7V?$}tv#$6cFCeXSq6AT6+ zSfah~mJ9-Y-Ijp2tZ?U4j`WSYyy#FBcmoMu{2{z8gdjmHMA|69PHx<V6nm!(C0TqX z2H%vWCt>avv_pY}mM-MUi^@ud<_#olO@$zu-CaEhhG65aRV$*Giqp&Xok8bm0uB(# zAMNzn2i#fo(6Q6T5~J@u$OsblnQ!fBnI(b}4nvV!B<$p2@qOuF7-`DZ3~qVn=sPW# zFL^)cp9q0>+mjw<HhrEcUl4(cQCR`)g|3f2=>Vbi?<Wt-&h54D{3rp=H?sy+rtjfo zm<z(HBW>$E48@EOUU^*kzTYYnk-UyW<6K-Ho_77Io&TzTf&F*}TmI<_Ar}q43OfIk z!885OVPLvR8uWhhnn>jjceq<^ClEv6f}WW>Q9_ZrV)qr^=tCFTkCET*ebT?TqX5-| z_SPn}klh75-gE=1xUIN5z$SKjPkU?foeb`->++KkbT{1;M#AJ!*>0PkxU_ZX*1BtR zBSoLQ&;Y+pK+9Wn#9c0*%G?xka4coE-Z$sHr<(1Z8IW8;_hyAwk4R}wWuO1eIPdLE zHIS4F)@h;%uFmls{e#p9t*{EVBS(2L`R&13g3I?hj(veQ6S$n4k->EsAP7F_yw+t8 zn;6Hu1$muL2&`Ra?)?0%7h|vX{<Ma~xdK9<?|Ta)U=D7p(V3QXMYYd7VZ|#y7P_^P zq|G0FC01(ldxT3ZfW)@Hu?Acbk*{XIAE#=lBY<m&lE=f65&|2x9Y8%Sk0o^NB)H4E z4W>FP@HSp0!wr`}bVVdNaD&3x&&m2;Lo4#>>g3(_BhTSD#aMIVYbiquF<OPX>1v1A z_!WYESkS>0U#1ZT{S>)P%9`An+9nz@P@*gAQMsTKh;bC7cDzmhiY#|SJ1tEG92$b| z4e|-?Cwq<`fG!yUj{q(XjbxZ;;1z>wp|8U{gUwY}0x=R1d+4%-1$tld9>AYWC-)%5 z8AJD@3j}cw-uN=w>dtt0N5!jFkTmwdX}9raC&hLWOfW~>OBhc}*=x{8p}&+hAwcbm zS6W$HAejfU>P1fhV}X)@1z&+Zv4K6Y9vom~LiDWwJ=5@pjs3I8FvY=c2}IIuyJR{t zL*j?dQWBaN{K>26%^T|Lgc@oY77Ap7t^m>tdSyG%0V<B_A(SBaRkaX<fW_w4-fzep z%la8IGM;UYCKwN|eIV}-XaoE#jztFmJXZnXs{wg{OJsK{1$m^FM0{=yuNd=q7Xpqb zBAHZ%fuEQ#^Y7!uOlN&Hq;)6IlJ^$9(k@3I0?*k1iUNXInBq}zw<D;5{gD@fi_w+& zc|YGZAB{-znwV;3Om4m*YBz@IPs|c3qlHYkGMXa6J|^v6EKDlHHO9k81etp~L_EaL zA2iYpF_L2^-oA$%1eAhPvmA$Xi;2(w3CO-2@AM*BIfjSBhO-l4X%`y3uqIdI0k=5h zHj$nd2h0U3L|&6)Ayt*63jkd&EY#f(M4hi4T4ciuSro}=$0ubNfKssnypW|^uD$>B zen=s;_N)msHH-O}=tjn-Cqqdh1+<kRS>r{LF=QO-ps4~gQ27pUvXEL@0*Lgx?f~X< zG3bVkz0g1Hw)PTp8m+Gayh_9lN)jHJ0J#EE0*oK7wkTguG-;#mcZprDn)ee~?}>-G zB*2B%m=tJEh%^&%cP-vD1L(p7(cuqP6PwiDw%bTFCzEx|EKDWj@&_@AM3QXdW+H<x zWY#hpVA6=_;Kzvqqy%z6bX}wXwLH?B!vizxaUo!wY!S9#3FJgLp4OOIUqOVEV~a3L zuEcDg@${7^we~|>OMYt_5v&7)$EHC&S6}r#v@qert}uaN8&ohx0wCA;LgzlkBdvl} zVj??;I&#)QM4XdpiTOi5da_5{x#-?g^t+Mnx5B)GpGoxG*BXNto)KDp?O^oX*AZW^ zsMhcw@b0|4=)36E5f<na^4uP`xCz4@ZMT%Ozz!XNzqi6p%;m%PH$AR-wtyZHR9Hqq z`#~uU&Uf{RYh9Wy*CCT_9$3r0@!IV+;hDXZ4`S1Z9b?bJR%n0l;>+pbGROuXS8^R% z>s-PRXTxv5@@;18#E+zMIz7evZkt$>O8D}`8*h50-A`Fc8iqJ3L>6?8jgZ@#R840> zsi#Pdiuy|Ktc!M~Q~y2$mxtXFYnCT8dTqNecVq8GQ@pfLcPm$6vJRnw`)A7tIXl4q z7^Q4}vQdO_elTywm`|Q}eybd5Ky8S47M}s`0fR!EymLDL;0Wjmn+r0I0RFxFE<I_c zsN1doiWumRdyU^s_t)jU6i<XfNuHX8D8e-ufHPDl;~jD!s8sLQCh1EgJ3W#2r5NIP z0wo@i-r`kmnF+_~calLCz(mg!`5vvF;@Mh&<mzG@r323)nwTA<V1ZgnV9I~`&5dkJ z%Da~e&|8jW>*!kIj!6Tk4fd|ZG$w`^24%Mi&A9cy?hg<zW8&#|@lJ<yN#Jh(lKcHj zY0Pr{dr)`l!Y??=dUv49?(5D4dEY2@P&wqs3jD@P;Sn`tdTOAw$n$8?KQYO%7ZbFE z`K{f$TR4W<&&=3HUwtVW_UUK!?nR>R364oU`a`+;yb=31pmm+ES%EEcq{~PRDG97q z#bECbpz}abIb2aZSUPF`C+yD{O$ymv2uXOxKy93LA$TI~q5##rw_}Y|vET0QHz$?R zcB2rY-?|gtA<fK@f6>J@gn~v|ZEFMY2IeaC5ETGiw1#^_qKLr!cP=T5hhf+GUL)c< zja1w)sJlnPy&(u5PRu_XNrTXao|&=GwBXXZ@hpnXvIPbfG&?AqKZj6>D|PWelLGWv z2gAvb^nBs_K~Nc*5ru;HgN%mF!lo=`kHf^k(-I`L|H-xGjw~nz`=OvHlm_qzTe+hf zdX@NkC5DA*WB7Kku*2l-2>AVYl#KgHCkFMmv+=;hfK_4LPq+-ax{~UML)#*mCkc>> zK$3(*L|!=Wb>tt2D;wOAHehaSWRzw*%GkBs!?YdoW~1S(U;02@;nD0iFyO`Uh-6Ep zl2elVvZpp1Op1{>6}MS2VmUK!V@qjk8uKFhN&`pVEsH41cB4s2vR$3t`^jHS%9(fC zV0VeW7}=fPOaxQfX6v1*y<Z;>s8;!+B{S$P_*q%~$iFSDd9UT;iy?QHQe-BFj9S-> zbRym7cgeE{{U2ky{)O6Vi#&U}s_s4RF>7y~)zVSk@?QvFi9%GP#K%ac8WOKNbrqG# z|3lKb2Siz>VSiAJ%vwUNJ_{JX7y>cz3riD$(W1sd-Qg&RBBc;ZS_XnTij0fZW*W!< z5?V9F8S$K^ph=d6fQfR@G!ct4B*;k^V5aZ)On>Zdn=-ufzVCA%uKT*K`?uGkDP$W2 z+r$0Gu_ycPTw+kiP?uh_I%gsCPufu9tI4Mp%>At^c>AW_=7!@)>j?`zoT66@83C8K z`m4MuUz^=+kavE6H;q><)n!rlst4=8Xx0IJe5F5U{8RDvA<+5ON_ncIBqBWeA_KY` z=%P&Z$DSkb_T9yFXDfPFg67&iMN4Fx%m@U}`oh^2I^}qDI}rFlSGw}hqQ;dsRcAJ# z(k7|HSmNww9BKtAh}W!1UfPpK=MA$cwPKZ<N;-OuxFX=dx;E!CfapWl4lDb`fTqP= ztAt%Plq&Kq$0&)iPmIJHEEpaOzaDG?R=Hp1RK7>JHEmDq`A%R#WB%@yH|1N`Z-tHy zLFk_El1&QEymYXRrttVTURI6Dmr88)U81UO%}*H1lV{q(24O0GeCx=(c-iwU((|Z# zV57?p$!kn?Icqzlb5(wn8T`OtBxZb?ljKc@!!!;egQd@SmJSv3Hc{~~#fqPFL|6?k z=hMGdF)0#5C~;g!KEQ=dWt{Yz3Yi#Cl-P&w2N=IP;4&G=NsxVHspb)u5Y3D|<1tm8 zxF(+QKDQe=nYiAOR!KD4hW@U7ND#P(qPZh8W!R>{;FU3;Bh?B$<>Z!P7@5ccY(>RR z6crN)e=@g*Kx&Bc{#&vcY5|3ysP$kxjw8e|x3&i|q^Quelgsb+cgg1sGhy!U<fcd3 zRAT<bw^*B$&B&35Q%xLf{Tf{@xVX3qgCHr=;kPn|(s!AB%*M|66MtL8g$P}eg>7oD zvDK{LN}+Ho^ONbzllKTKI5FB4`a88kC`yA($EaY1qm76ePJC&~FWU^nul&<j8Mcr_ z1&Okp<`A*PD8{9&hW+p?I?{TC#7O+mOe$IP1L(~665(2(<uArJunZt|W<P#ENi~MR zL?Z`q03N7o7X2{1QOl{IR=i?0W9dt5qhYS54a0iA+TYm+cjsjfN?NQ)$!7R12ozvd zkjxBIFwQNek`}PCFLh2AlnFs1M71O)%q_dG2>S}eqN#K;7&6dO+zbS$6mo=m8>m}D zans&4g=e+-LsJVwu|R}_t_knn(79xZycbSG4qqZUPfYb{#`pLuoGPIRSm{ltaxt4= zI>-fZzV!U!@k$1l1#yy5u!{=nwrX&|W&!4qL0mL$2u6glvp_MLs)f4oSiHZgv7uCU znCh=g@?OOlm){{iYw(&L4ppn*LJ1slcE!boE~1q0Um`x$CkgcvccRme`lE#M%AMJA z=3*N{il>|lWxhn95NSzr!n6hibRn+}v#F-VHv9nShxlCKTe1VK9h_$UrNu9-opIZk zPhEPfX~pg<N!x1ix8g$Le;#>H?lvllcQC_-im-&UH||u(F}Au|TvS>5)GblwS92w8 zit+dW#H+&4<^y>{{(E8XpIY)#r7V@>p^II)p_?f=!|!0<@P)Movj-K{N{BMrFLEYV zI22JTYkn_jeX;#bc#LECX7zVXb}a|ZJ&{+>_#a@?MgG89WHj4vHg8!**>8+w04M5` zPweyURK^lpZd7*8vSPU!v%T^E1-ZU9*UjhnqmFLhSI4VBPRqVwNLm&3d(i~Seg#T( zzp<^Ee#Y})M30@04UAp6iOcc2J7{r~I+zo$$P(<GhMSvy&&yeKSW*kBj7Z~~cCJM* zD(5{|8!3s7;f`}v!H(}Sr=^h@3{yVpolE6-eG=kn-O!;&hnY%<>h(bU$_e8dUTTwj zZhJW%W!v}9AzJggq-$;gBvL<@1xmYJK$2H2w(6_LPGnRGP0{tRx?kaFGrX%7?UEtm zjcAX`S=6DFs`IYq8Y9vrZx0bM7%s|V;EsqFq8Jyv+-m40bRhnar)?@^Tqec%idlUa zAyW08{)baS*eP|kplG6K5Y8pp!tU4KZ}Btt@{*NMYw2it5%Y==FQiXfx0G{LJg4^c zmVGrZR9f}@l5!FowX)*`-R$fp;Vp>OM{C8>bctpX)!zs52l<NS1I{n~L7Pzs5+S0M zO+`OKmFWa~M>oAM(Hog>n#Q=fKvR;l2U5Res!}mZhX6m3mVxR_xO6VI&JjR+PiMcP zpMiz3MNiW=mZCB}fgKZF;!>U!LsdaJ%5Z{;6zP=duQ^gAeqYcJVkS+wf|qgE;?TX- z#U543J|z;RKl8h`M4>&oJxgDK6*E5#pBBJyRl{dpuXo@bC3u8Kf9nePt;Tl0vbECA zm%0q}46SCKweqB{?w11>*XY)4KRZ4E=`{BFjC}_d5E**9K3-58a#um>h+TOz|A^vP zC^^Ms!U@=M(!h)ZCo3Lx01Mm&nEU?xPmliJ`zudYT5hrufso^d1fIB7euyBktu14$ zyMw7PqUuu@(;gn(hso^kkCUd<sLn*OQAl>}_*cM&vH6od<QF}kz1e#u#i+shlIpj6 z-cJwJTk!(Q+gxMH9X5s62x4eRT_gE09FKe<^d)%*-5>Bk8Bl4bn)S`mKciiH3U$l= zmRLux)MBUBekScI)H9-#4%rw)8dwo8?(|veaYYVP2HDE}W*M^#j)-Ysr1?lRPX=>S z)r&-<{~io&9enn?MJRsMkEJ+`uZYm8iO!lM$Hu}nr#kB@J$BeQ3@rFt5?d;N@=oQW zaCy%r0{CqIe|4`(QhAxx%ZxTwTBkB(?KMWmU7T6gWGf}g9(bmDqc*8Rg}eoL7r(vj z3Y8XH2edTC&BZerHxYkMlR2-7gx1>{F;TAepeRI+^X+SM@9|_PhK_y-PH3Kl2Cq8n zukNdXGfypDe`v}d$eoaTtnGfdMKf;=*0Lt|hnt?PFzuDnQxDJmIK}A^K9j8#!iq<< zI2|?v{{uO%5PD=`H|?)5GgESy<T1ci@1y?0fe|km-n5lM*(5tGp%&da8nH)6cerJV zQP6kcOo=!5xak-qk}xIU1iccqLRW`Yt`)cz@dgsDf+@#j7yT$6tj1Rf6UzmO+1G+6 z@lS*i#G+tZ=1Ey}w*m}fG&xBk3}@~sY}0X>hx?5yQaMwJ+$+!{Wc1OGQ~Tk}NAumO zATG>FIM+Pj%;3jtXG%t)rDW8=OWtKI)GxZI)UgUCgtT06$!v(^V$}pg8K2Y&N6)(I z?8$Q?`r8@b^&Yz*I7x`AyR6+fqMctWt%NbjR`aYZ_@7*b5>D+8TMRasuVoA!uPg(u zd!~P4{}c_&Cld6rloBqNZ7SrThB?-AACQ&HfPK;>hT#fFx5>@LkcSSMVgGaqnu=K| zrc-)YfWnSTq`D*h&B;ExOe1<J<9Lq7Rp~q-4~__rN@Z@xTkA<7uUd$`2i)=qY8!N= zsThpdNmQU}Vn`~oo1445++SfX@qio{zqc>88RtqN^3$N<({(QpR4*3BxA>*i?=$kN z8IAH+j#Y}pdpF)A+de|4>XmO3ZFGuTu2}n#sTl%hD#D1wNBjP6yj@i(!>QLN5~`>H zSP=4U5zjQ0))&3OAOln8Q5AqJb*9_(F+2ref(JelMxP8>_rT9AOWs5tB^|C>u7k>O zFtC4@3X-x}fWXV65|n$_6iCeK_{Bn$d%l2Udgw|MAKs4xhgq^fNjzGH>7u>D_-zga z1_Wh?+sjQZI;tOB`KBSS)R`qPWr5LB<LT{Z%@$?Guu1k658D+d(tdilMoC~GBetaU z-dym-%L%lO;C9Njhwh&*S?aOy-RQ?Y@w}^Df(Tj6H~E{rvz;#2RdQwyzO30ioRN9w zoc%NL8)Wc|zV)ges~WuhAYwq?G7UQBx5JtWUsb+(zkFP&Q9F&FPEIOSE$nwrwsw;n zi^J}Y!bgM+zalurhr>Q^1)SozlD6mm?-jMQ|5`3-)aSw9l5Zn+4{L4<Is$XQqL#V{ zqF2icjL{AT*{t6WkP8f!?|3}xeQwav%#*q%(;C9xcbkS?tVEjG@=(2lhm#)>T>PW( zlPHz(^WFKuM?F_oRF}c)w#+D=?;^<Ns<D?D;G9w}4*68;uE$?g$bkydcYf+K;V029 z>L1O(q(gP0($QjF`NP1Bb&F=q`djiYoXMPmDwn3;G+QY$gk`Y5V!bTg;*C75d%4{{ zuvvHcw-MT1&NSc3m8PE@y*z;p+80lMpQ@oi$OnGmG9hEQ=B2D4M>JfY^lwdjz6zc~ z)1$z?axq&d#}c|6mUQFw@L6w+nLL{h%g-kt-yl7&eZ6a6%=N`M=s=&4Yg0<;v49jX zR+-G65sb1lI-j&^!>n`(l`ayvdcCJaX$jOtkV0#lG9-$7MxyD;;SS31;J5Mn>GXSq z0T)r>A8=f}9AVD<89s0f($kFZ<fa(f{nhEf>lk@=NK7uws_`36?8zn1_t(%YxM*JK zpr93qBI2>{-3n8T@8+PB`&g7z0Qc88Ou^pi7O=(edoJU|h}anHoqB!6kNQ?adX=W{ zx^JZeqc~xUH`?il?Yj&J#ueil;P>3L9tD=yi9LBm<7I-~>(p1rAtXz_B~gfeA#|2Z z+<*qP3~)u1@sou&@!=m-t@T2q0)&8~J8+ku`KAv8ufT6LZZ0JF6lf-SxtB;N%7c}5 z<{x$6Z;f<ZX{lvWLd;VrM$0CbUhiD%y}7~xza_gJZ=JpTThGzNN-Hc*`fD%l+&vtB zciY;opMuVeIgM`*2a{46-W#$lNWa~gI&!ei7(sR4UsIEOMDwFEnq3!iDloJ3eA97h z!-r>P&%i_t&1X;7<Ks)V(DSH0suBtcPd05hz_N}u(Y+02R9<TS?5__C_3$ePlHLE5 zpNYDdq;mW7M4{+xaUx5oP&P}S*KDk4Q9uteMuya$2^s$kER64kGQMJs_eaz^r>BYz z@9?Fo+i!g))9!cyQrNH--jJ>4(we&@xfVW)V)E>!!sKp+@N91ZM>(|xk2wLNP?cob zDT^JCB!>4i8$5(7fO(pI#%0kevtQl=cfBc0qh@66BPjtotHDL{?QSf=1hjVJZ%N83 zT!a#7^ouah;kto`F17j2o^fwRe{+)D(7v|fVb#+6w>VRcq6NRO`N#4LXULDi$F|vT zs|z_H`ZZ#t`(%$P3<wTnAYMx~kWpOD^IWK$U6!`9#NyTLEA+lR+v-A5L}4Z;R(F&- z9EKAI8~J6;aYBEUtp8CUlnn7Ez}z10ffS7|bARpLZPdi};k}}Xk%XL~vooU?sg?dq zNIcw<R&j%?vme7G0m-N{-Uet&a332str1IHUhX6_^5+u(z6GnqjkK%ClJV}Q@c9?` z_cAa8w*%%8LxK3gD=A{^w97?B7DuEQB)aBuZQ#>@Jp#z9R=FMpxG@5}n;S#M&F1ea z92bo9iijlMn{hhFNE0~Bk<$Q~W9cyNog4!*g&meO^C)gX)y@lXKp!JcM2p9$PQ@6E z+jQWNTrG&7Fj)0jzEpBiz33Z-^*R^{|3lXWRTyo~UsQi|B9YRE?*Hu=fC35crlFw& zF_xQ8@uuZM`c~#Usg!3R5Q@aZiUnB#*N6{-QH`v?sVRGcQou6}_0kKdm%D@xnxW(A zBGNB7rOMKt>h+&#dPKbKGy?THnj<^OWT(tFKl~0xJG}|{V&X{aUAu?!rVM8TXcmkN z`a|m&^stu$-4@%XLSc)Nsw)EwJ7l+=%x1rU@X0=ssL}HxM#$nfU%@RA*I39cVv;nY z)sRMGVXWik>*7u+XqayiwEZef7k5cPGzw_{c$DoZD!3Z~;_eVW!H5_$Lla8=hr@&! zzkaB8*Z+ZV(JNYRca+cbppGDk>gjliG7@HmCTsa^$|*p|q}|4_;H~{#m-`y<yiKG_ zWcG!hJXNT3iphAR_4<mv_UjaOv_Vq**K(=LS~*3uy$#o~=7-Z|4P?Z;h?C^Vgp;YR zuhmWc6R^-ME(r$cIkRR*_4C?SY9n--dH!dpM9wFlxnSXx_3&5Nl!kW!1aIG}9KEbt z(~n_Qf6I||rJuKX>P^!=c!7Z((_y}Pj_QSI|HNJ_xOy(UkdUswQ1U2oU3=8U%H}Vg zC6TGO3eIkgd$D|9+?Ral8Qx9^_2p~rF8U}JR0LfKe&w&ekqRY3WjacQl)rUfHCQe; z9Sq)QKxht#m!+6xRT?^y^i#-y12jlrs_y45OS|XL96ZS19Bv)ek0N$<ai67q#C5oN zRlgKG`L`s3*KQl)n7O!?1UZa}bhJ>G>u+qasSK1IUATO2zv^8vCs58k3T*q#A(DV- z-r}mVUrTI6_iAbu#F8Re+37S>NDza8+-lCnQ_-(E!`E<qikL-BnVaG-0Hx1=g(wu5 zNPU|9)TRf4ydpL?jCrXQPCX7s^lm9`yXNQiSy71A<CrCmo&NW!nppQM15^2<*UHc0 zqbIO!&EU2F!G$%m`bYS=Jv?dnXlGtJ=>a-~OKl@hce14ksINVLU4^54LJap3<?e>D zSaI#E{MfakGK%#H)$UaTxw%(qEualrP*I8>YbutXb!EK8*%BcnW3R3LQSIJhQK_QH zZeMIUymn^=!__i@Q<m%W%)2<xjL~8$9fP4euNO{iB^7v`QVKMAlU=>z%p+W~{NS|% z2-I${GD*xE7z&A7yRZ$Ya_Cxi_GJ1Kp~E2>CFLb=r`;bfJMPcKHtw{=bY2)b6m%!K z$?j<*MG}Hszn!AZ&#9+{Z4P`xHr}C@L+_|SXawh+4||?l6XMKQ{)Yxi^z@OOlxfb1 z7!w+#mgQhyDz85Xyym8s<0;0SEl?*$@I=s1vV{R8L@CSpTxLFFa;TjOLP#4<ghJMW z0gRftazBzX`cLNxK6J56&zaJ+@ML-LLhea#G8OlFNB%S1@zSL>KSyb|tUzOD5kvTp z;=qM+IgocQh3z|2K2EJiR(An1tj~Till6hLUad_^^0A>h9~)H1NlpVhU?PeBu_0uF zd#DPg&(&fiR86X+uBEOH!j{S9d6y$AYL<|=J=R<O=47N*fJ{9$^vRLvfX)DH+04#t zN0LiB+F`Z%JQ!?@wYKRz6&hZiy46;5PM4Sa+=>+Avl=WhjjtZL&B=6(m;TltV!XJJ zz){f_Ja?<<gm3t)Fqd%}s>6Iw*oT3*p)T#Z;<=zk`;<!^{W!o5W7Wf68sn<~&<LvX zb2l9Pcm5wE_jRfl|Fj-Y%x;LfexYVi*)HzZfz1_C_Hpc9SI*ntUWmEYP#hCG8h7CM z*01OW45RPUVwrn1K^7jZ)nGP75@^p$|5uyX_`(JbfjhN-9jM(#!I2mlG!{oEwuV{w zwZp1nf$&Bnppa-jjo^I{6KkaQ-S$@c>iVN%4F3Dl?y7OQbibA{fQGzMHn{1@Mos<_ z99g2<e3i{p6HQnuoWny3h%FVLp<WaOmVnjr9^VLDIUP8J8I}Zp5?yM=#XVjv_(6!* zF1ilgv_T)6wShfbASwDbb)NvYvmX=5v`l9`S4`N!He&-Pi-#ld<pTOsIYz}>!O69t z7=uLMd56=8B@ngZ3@}xBxdUVrWn7*?h$m1w&*PBS$A+o3ej@8IS1xA}in;2jbjSf% zDE^PdN#m$TiW^f$c2#M9;L$2b?=N>uSSUE>$n*t0Tkdv*+MYzq^UI!C!x;241jFN% z^8+xfO*c>|@bT<R48Nxg;(1j1tD%u%YgcIOQ;?S=3iC0~asbf~{S(ySZrR~}3W`Tn zlCwge!*~UGQ|EqOaJ6Z>1kRAL@$EsFa8STUfD`E72x5-}j39YCL-sVG8YB6ZWSW5p z{qO)_r-a!Hb5l0LRci}5%LqJch~M>zQGMdnNjxxVH62u^U!lyR=+v`A0(G*m{e^h! zgKUv<0E&3IIpZtMu~wkSi=PJAbe{?Pl?%^Hr!vz9+}~Y|lR%hcs-~iXMU~A1vlzMw z6U!mC77-vU<h>3IBV0e@36^L0FO(ZwRh9rHqK#l!E$`(%N(Zk&zyy1$pju+M;3oqm z5cH<=<O&cNe%)4Y>L>zx(c@yg3e2FFNxNE##IjE)CK4U(UEND8wYz$>MEYb?SDEc7 z`eV=hBdHZ0d}S*bCWof;1_rY}XlYBaM-7xG_yyyG47;4P9A(q7q$E0fehs_h62mhC zL|uZTS=>o(n2(b{q7+tHcLYnxhzXw7bG2S*Fb<1a!t9@zF3e1YCP67k)SX{j-la?; z3kWZsV%ZoaV2UA1;N#9SlaI6N#xa6Oy|nA@)I{QRvaeO`y@^Rm(=$!X<%XE}@$W8% z-jodp^7XNdp{Spl2E+e%7Sh=jsuSKquFCZ0@r<F5)jh}UJj&;IX}*3$2|KRot*?7` z?zWx_c7MF^RInmh&6GXv#I}jb{`-)P9$d(1y(3R{9b6Rh0FD`metUlOrM~t4w@t@H zjZ@!WeKO%j&-UrU_*iaKWCeLB?mso(b3T(#ad(&$+*EyX(IKp>>@+@`nn%~pAB}yz z<$4bw19V#6-3MRK+L14vFLoz6iWKd#qkLpUn@vPnefP)q=!adNqh~SyJbw8jO+Fz< zFk7nK+q`CgxxB|@$n<UGmbEUshad79gw39D=&SD=j%V4u8x~S&7k}Us9yvQXS}H@d zuhM=mD@H5tb9d-26paq)%`F3+eRL_*a8*6>Kcv_5wD|fXZ4>V*vw+_^LtnNr^sCyG zL09+8d$nlh$unbXcsCx!*SvqW>3v3yd_jSS%5A!Bn!@PBq^Z)%=lK#I-OoPGd4kMj ze(g6))+k#-h)}1&qi=c2`blyw_eyp?D&_+ypNHb#K7De5^wA!wix*l7;1qoM#Uij2 zk2KVP@E{Ijp<$<L3$$<#++;d+=&gz8{1b+FbxLxpjg1!Xh?o5h#%_3Z-9%SqvF`F_ z6ku-Ig%x&_rYg+=vy#zdF3cNnASS7hT=U|D2}ST&74$EZ5+JAd6bgU~)jhv96xly} zBa9fj_E`s?{d@Kkz5eRB7uD&fr^UKBXg@de5wmktn06VWy)*1-H<Yqsk5VQO5MzZn z&EbKgeVB6mHIOPS5#jf~Cd;rNWw^~Rf9N~p)N3!+VqM{d5;S3kIslp8G4-dXLkU2x z+)UY?<;23oe2MvuP#He(BT-@J(t;k0JOMz5Ye8b<9E;dZjg`wuEwkiFNuMhH8HBvv zkxktIeC(4V)=Q)-q+jyPN|;)==N%G-iz3tCGOoOWz?8xW^Ev@tn{9ex=QHovR6qqj z9XKt9EO0DN7~jCM_N!b1KeQ|KbB-1J0_(13PvE`gYH!Fg>{iWpEGjCFUh@sz<Y#T# z$qe;R?Qu>)Rr+f2#G>7oYr~>XEs>AXAUdvB$NRgd)nrfcSF;tahUgFokvHvH_7q)& zHt3uKa8qY~@NR$3nAkp<9C)BC6TNxRN3S;Tz9MuE>8Ul8g@-e3ZtDJr54t!8O6QXa zzdSkY&*Q_9f^DLas~bK@*jp^ZR**x%lAHfw9@?CIUh`z7Z6;n={A<`+$35#dTzuG` zY0GU98y4EJeScs5;6h@88M;E;AS^?C#hvGaba8}sp`iDTc(xyvLVuP=4CAO4K1<OD z6@@>7xo=u^-GZvo*y=eef$Yw6K;!B=@t@*?8y9a2yu>=7q1tS|wa<26OD(1Vw_X>H z6poNOcOIaJgj;-=;W4=y3k+<9bM-x<WoC-!o}@(QEul;Ru=))0j!oq$4e5%(z4HX? zdBeb=#J?IJ&G@$ks)3r;dh9!R(LY=$D{3Eb(hp}?>01lI$HBJv!s5)5Op;SxN|75s zpF=9{m>{2fMO!GE5WbF6mWtCMNq+p^(oQXvss404Zv;mf*qx!tVXfj~VcJ+Hjr4dG zN+W&>j=9ZGpj|!*8vgI9<zvD4Ub-j5Dv*l{h>Zx$pDJe!h*-_9;5FGLwX><9a&-_M zT(D-h@lr{VATyX6c1}x(Q?}NP8%<#nH!QfAE<`IW6M5m4GR<9nfiK7q3y%3GaP=4h zoYLh2o<pM07q70xIwedFF%mr(q;V4zd>y`Z!x^5(!M*!{RZOeu_?ifPM^$bb0elxC z^X-sm<#Hyi!QKq%pn^Bv09-PpUm31MC?j-0FkbEDLy1VV5F4B4ZGap7YT|^@7o%R0 znihKNSuUu_a+F91YK4vS7M;yVy2<9@wetnWq(ww~=kaq6dSfWj+7r!AXkyQ~Jv=1i zpPI9d60gY+K+tH-MbIsVADa(9WYCPXOH>(L*fNxB0>nKIZdtoWBsyJ&M>b0|G+mv0 zOvj*$3CU}+TBa>}yhRibmZ|l;V2Ui$&v+RG0F>Eg*s}GeOcJ`60;f!?WdGhSOYt%5 ztoqxHcXeR^s~B^s)>|e<)!<HO)o{@U0iJb)nJIx|Yhw6aW5sBhVInIS+<BM8yB`{S zd+m%dS)x@r)ju9R)CR(`?NQmtt)P@hrVXQ2*S>si@c5*r?q|#YlO%6!cxwHd`Zx7g zzV<lFBV7B%ed}o<AssQ7wsN#Y^3e6Qq>dzw)g+;{Ad)#Gmt=kV^}ZSlQ}5+19HH;e zU$&1p7<3m2_plUs<km~~q~$4>pVg|FtugLg+Wp&^D;~f8Ya6yQ)k#ac9DARyX!QE% zA~0XEyy@`J7DJsh)?0ryZAY*1UJVKHc2~xx^;5n+{?jV?pS(?HW}oe2OUG_3K=I5p z^`F!HPu~9wOenUE-raWa-|Mxd`L3%%?s@f9Zh&mX^zN4($3^F>zr5M-5xLFb*mlpA zpoWfN^BlG;6t7=gb;)r;-g}x4Ly0Rd%hF7Df>sR)Z-8Lin7Y=?cj`*>1@!6!CHT~) zGn+g;IBr|5%*#V%=~cCt?>gt~aryWe&m-|`U+=<W!SRJImsKp^Su{1!6a_xZ-&SdN zm9AUpe0WGK>e_YEBXMmNRV0sGZk(6>jqWWOA&4=WC^0DAwY!KLV&Ki19=zIxg)xK9 zqT0N)2(2Gu>g+?Q?6ts29s??QLw)La`t)g_wSH{$&?feOF=)Y`5Z)>RDqzYJ-~~MZ zv7s>hoqavsGsN_~ge4cm5A>Cy=U!}?82Lg+ucP$RlKIy2uI4N?`EWIEN&kZ@B_;)` zq11ZKrME|+ZFBTs{u5S^k@)bz=d-6w*KQJ=MYxoUAFGljBXuGg3T>ZSRlql5bI$7~ zqaYIk?K49Fgu@Xz9e}(_LfNiiD>S=kmUARn!`g<+ypM-)n9%NVp0dyUduH`B5>a?( z1UozDWRAEj<xCLXYXi>&zbpbKw0hBxe9aP*dja-)Ej%<AFc_+Ip))TAJPRWMk<f** zD`;KP=QJ*v<p1X+6c1{}XsI(F<~X<S21^+YXmGTYwJb%vt7i$>(hd#)Ov(<CG%=bJ z&8d1B{Dq)3T!P#)<Yd|~q_sLTw`10$^6sw1cg(V*qfL)jw7nlbP%AgIafg~hYQ>_Y zrb(488-UjU0qC@zY<e!#m>C2cI{v?5DJl2+U)wV~rN8Tkdna}DLq^?s`IArut)Op- zF@*a2n1d=>gQ~v<Y57^6iemz<joI}BdPBRDaje+ki*eF+<iC2US6FamAQ$>PxtIS| z8Q31>6(L09;`k3~12Y3E%xK_NXnFu|^CF>omh+mpQ95+z2MQR7(L0Yto|MPe5!+gf zcVi%Mc_f0FBNFf^`$FDXXs(My#|c2{t`)d^FmErv{GK0EE!(F#N^@M4X3$5b#R%4g zk5>!bo2X315*%HGC=+}%Aj~8xtxojT#u<w(Q}g)ubw2d+9Cs4#Dl>Sx943H|gx|86 z-i{QXVwRpUIj~rs{FDhu8}$^1yW(heel2HhTZWxv-cA+Y6lp2f29P4~G0EyA&pzfo z1xmRgS-b1mg+Tf#W(<#C<OjaRDh?}{DNzBx3;q~S2Miutp<Rr(sWe=`M4X0Q*yM>< z7kdb_yRd)2pl}|>5ynV@eN6pS?!1J+I1N?bX~Af3j<<!NYKXbvWSl2j$6b%}Ucm+# z7n6{fN~flhr<VxEdYnZ#MX)(bt{P|%k_jF5O@MSQ?h>5N&A$OMj~lSW72z{ZLFcHV zTT6yr(<;XBpc*v8@Zl)%02Kp2Qetab$KC>Unju{>(vp0H)|g4h_~9O1*eeVWC$?)` zHNyMQ4K0OJe`h}qGOA%S=eJ3Kd@05d(br<Z=z%;+6umb=Gbzybup>$Ahg-$%ZO)#! z(;h>=w!p;55H1aL0YVz73Mva{Ix%vYpW;R4M--=%;fVw$f)8#s#Hly2sPB}@ZI?B< zpF1Ot+6xHCL_C(zDi=_^3EH&Z#$@yw<7H>Xn<fDIY+(uiXc1y4AIa$7k~hyJ%O^Ee z+U^kTUjy@t^5OWtEv0Qc%bJ-0-6^xmk|y=ks<F?3-fs*`2>a98@OX`A$K2nEKvlh6 z^`pvl8TYI6YxP;caox?)9a0qG6b`2|FId%uzkfPe+*>hOdcEt@(w))vhqg-f<`cvy zf8e+di}<-MJW<vPRYm?hI6#`?g}>!fvp?b9TRVDLMZLsM$+5g0I&Jgukqu+tZx&yJ zgcVl4mr1Bi#W09M)t_F^b1a{+WH==2?=J7#I(~xL9ugJPn@0{mU*|ErW_L|pxGC$_ z<3pY9$9w*Ypq7entK)=}6kPeT$~m|C=<*-MWtlXk%Mqg>#BN-DdV$*;KTmP^%kY2P zG)?h%3TC`ibzs+2ZeU;iYp=%oT8QJ}^Lak4&Mr%_@tWzW<3w)cP&z$`oqgB@CKef< zOGFXV<qeB=D@&oeAi%&>un+Uvb;9$7j$|L0E=;JF*y`4>q~VBSpg|*WUQZWqYS)*w z;9pD+zQI)<Qf_hUgbV%16Wo|@Xbe;HwAtFC$zWT7Oqj%2ZLzgxh%sx~0?emcB`RA} z<kUc$I=WTg73QK#C_3F2T=zu+BunT0U`2-=zv*&J<v$`7&falbxRERu>CQKw$oe>m zr#)ko?Pz6^HqNWg@$sl~cHU_p5$C8Fha4JF5I{HrsBskBHK=9;1e8W9p^IhGM+jo6 z2$lZild}DczKC|T0L-=m$$y%m_?1)kBhd9hEpmgQ$SR<H0fId{WeWLD9B|Vya%J#a zOG7B7i_nPj0~0h&(53LWC%BGQ*^O7>1mF0avqP~**?(sZ{@_vNBvcW2zvRF3IO%P< zW;E*UDj1RfPbMn(0!J_Rqz{+*L060Qa}4@?=5`Icn8CLXf{Zs8Pq-Xoc!oPL?BXMt zl`ed)LrZq)B2^pM_eFSs%;^ihwzGV6Fz0^Utgz=kX1UuEtDbR|_J{+-+@v^c?(T~# zVr#{0Im<tMmeb|`c<k+^CNcXlEbZP$;_PkQ&gMwfTzLIzL;Md0&H0k&W)&6?#5g6? zR$=d@m@ZD19Sgl>WQKjM>}z{~ZLz!h$f_SNfkTKXzD{%ZaNoEo3g$EkOho7<primN z@h`mzJaZq8C~d%K6}XcT=G7W1o^Zh{7^Yo2pPV8th()OVV%M2uz&Y7H3iWdX*eigk zL@`OYU2tu2BfMNnM<5DJTqNvE^ID-Z?<pvn$)(rVQUFQ9=?|F2@mS4yhunH4_ZsAW z0-3zGojIet2JRPnap=Z^rCusvFA5o2lOwr&KXX&1^-R~YOO01aktutqhU9`K*`MZ! zzeSN{-hoBHC7bh79b!?c2#&<}Tt>Ae=Iu6!EMKDe3aGT_nwcdF1;)Hcl|0jt>>wJ( z^;ZE*sox#p@(lA;MTdd{QVg0I2W>(DY{}x>ihd<hbK-m}7$(weE@>+>40TN9^NBrj z<G=DCaZG#n%#-o!!6MV>s19)6s-9rHOhgf*q7to0J;7}(!-gC|U|Yoiq>PD)h7C_7 zI&jpX^d<2$i7x}4v!Lo+mmrb=3q;rJySvo8DDiZWiv?G^si%2&HEdq9IDTm}E@Cdb ziqR)Ai^u3jeE&zaSw^&lduZyTL@lAk10ZU-599u*@d21|Ut9j>QNuvbp|H{kVU$=J zYe>#Cg>K9i61>)0r3hdk(?b6U3Gxkw-za3v66xg~T)MwX%6eNd?qjrm4@8K*l0gsc zprDa9aSOPKz7yr2bDPj9ekOiqu{CdMJbzJmBqy_A{Q8QYOkpftR#&3#M`^g^4W2wc zZ{z7|ye+eFg2`I>GR!#i3D9j#-;QPYi}yRj^9cFdT{1TNho=>XN8B}TO1TDB#=Kru zf%mZ)En&t9ZTIlzO1My)CU!r!J^0i0yT|75IM;$kQ`BJUiZ$h*4ed2J>6Q*wa=Q+s zn)*w7#twdEshRw;y#0bUC}kw*`AwM=S{_v$>u<U;uK4vO^D*^t=$kaIr39O*pNGzT z>)j_ejRckjkAI6n9yP1lTk}NRZQ}M+{z{m9>*`m!51z&!1YQwOqEqqcm!p9GSLT~P zi_=lkmbut1;E#W$$wU(;Mk{T8(jUWKlF!}F6VP~VznvCdPkm{+B=}aisdy|Y7RFka zzcp*Fzsh(nru!X-x&(`N|1g+tMbpMos~kC^e<rb??IXCq@^?!^YqzEN_wzly`PCqN zkFJ$I@EP6F**s7uK1JQ;-}X+7ZYJvcjTF_qqNY<9TD$AwSFyybNfw)+fAnkjwW!_0 z8Q;&3@-2BQ6yI*}_U-_;<C!>%=&K8^Tf8;hcLK>lhb@3>UUJ^#`5cTmzolEA8uYuU zU%VznyaYXYhx;lA>Un>u3GyvI;um?x)!Z*`zU?^4n&EMZIQK=uSY^c7B0~E)1Q6CH z4j98Mty7He6f-Nxu#6FfZQ|$@Yxv0x^)a|W%dnFq0)D59l+1ZcMz__)Y(X3WP>OVh zCAZuYh(2s-h<ZzG!4l2_s8d_(WZ4t+;G*fQh0V4kO``zdf@rG735@;Cpr6Ybf*Pm* zr%N<;FTke4>t?t==|hwYFs~xTghRaIz8jPAYhm<=ZV(!v1e~73G(P=eBqok4e$M6E zbm>ZOD%zxvO{^|pzHV-G4r$dHw)(^aTAx&_EN?B+Fk#Gso@evn6FuVe4cEhXB|FW1 z=>Igf2JIXmZ!Nbq^@ijBy(=#E7`|Jkh@8Wh*3pCcs&!#rJ{S-4W$RQ!+5l%hD@#=n z0HU?WS^MRX#9CFbG3W4oulypaH95mhcdd_j_tR^d51-&<2K&*{%WwL%-uUQcd}Hym z6i->CS}_qmH)UxjpiG<^r($E3*gdOeuMXCQyWGv%<Ol8@3A3FtkA%Xt;X@N6-(4+K zLw6pI>-%2Y4VqzWoit!4|9PowEH0MGKP0jXzY8U34asKhH+}xE6Hf7+j1p9pRby2H z)^mjt_5GlXxpCiHVMMSdqrL+qk_gv&M1#xFc)4pCOgp&VP@0((C;RMrJ%w3K6P+jd z6+FY`u9-1b>_iAF^)f!@t&7-Cy-`f0fDbnur?CTC<a`{-5k1zic&E(P`pwL{#ZA!$ z?ZLc7kYt2strW&@iw+vxazwoUkP^j<p=5|lIVy(U?q{8PNqpObmYP&<?k9yv8___l zvW4NrX}-`(mWgxJ8Vp*c2+O&2hr$(SLLo8c0{}v?*M&-!L4n}n;N^MWEaZ>VO!86- zJq~gjXpR#on0TLKDmKaDeg&`4tx1<?j_V5hJy@2Wjo3t6$V?BYRVlqHW?a1L2w|>e z;cVwF5voLYDp5H;PJXO7NF(!E_1(DRlP0QD_&!tVff{cBWy>25o`pA_{Wx$UQhyUh z6x-qInvRuJGH5*qVu%+kEDw@aF{Uw8S?$93sjq&I5Gwnst;<1VMZBN<ErZ5U*Uw0< zo%A-mGrmfB=3<QW82OX<g)3{A3-o;Z*XcuKdXmI>N?z3PkGJ%9Z38nLa48%=T{5lG zQ34?X<{0wN2yI}@CBddzVZUom4L8m-Abe?ebF8WA8@;xTmw_T4$nf~#6<#S05}z9E zIF-sl><qE<wW(x!ttUSRJG#jS?3OLI(M$qZ21bngXEYZKXcNx1;wG4VK1tipvf65r zSiE;r&1cfOqA21Zh%&Sc)CST~C(qDj*KwX7jttx~K?RD~?`x^~$v+_-rV-Db+nTh| z@nubyR|`;H9ua6cj|PE2`lQck3Tnmhb(o{ufs4sNeIG+b_a`2|kC4D+8x{dV5m>dG zqLwo`;5@PGYwJHvhYChCD^9|`-73PL4$Yr||B0{IR#H)CFs<1l=x14L{q9$m|G9HL zHJi|Be>cvcS^6olaP7`$_t<^G{%ekW(3s#2Fv5jv#FR5nW8(_o0RSmJt$jH7#+}N* zh?`SCD|Fr69#ve~Y-mqb-4&9&{%b|b=BGk6VnYgD=r#9&D?=TWCFGb4r$_Y~o@B-u z{X3<%5rHo&X0BqO3?J$q@hI0R#d*u9RFo8E4R>vO&0EKczqtvAa!;Ho*RgJ-e6+K* zJ~Y3&V(fb+W=D_KgYv3|GFHO<^<t*C>X$VQuen;kDGeC_yp3TmLv)!3tJ6d&OFb9= zt-LAciOzFV9y??O&kwdCXS`ZI{y)EpKfZM0Rh5<8i^{yXwCm?QE#ctUdy}?#%(fD< z*>YXjw2`T>ZkvD)uiv3!;~r!jwe^bN%e30o_B_AEL+}64)0hIU0`gf@NWh&+tI;cX zuul8SE1cB{pO*Yly<*+t&3YIvB5JnJO@CO_oOk@+4T;Yfww!`(npVjh*?ioy?4<S= zjqA1+(E_)AmGMo+XU@os%drLD1bjE&PZsyI+?<@>nhMQ+$$FGJ7;c@;`CM`m5-^ZW z%8*D-9K5Yd=FjZEr+TINi<aaA1-F;?cTD*>E-<D({c+M$AON5s698)n#e){B8Zl`3 zSIZ6*RphyrqI<i}A)Q!WSdOVr(w_ed`;H3WKs-vHz}KXD$obPMrI`c;Mh%;a9e9{T zE!7`IR7AMx2(J>vL}u2IC$4VQ#nI$%33GZb53bs`$+?^}xEE)hQMUPCpQLH5)l8bh z_(S9!CXy=65Y47He+PH{et`iYP+HH8&;BMo^~T>433y|v%MlhfwdBL*7Ov+$$?mC5 zz_YmiJK=BU?ok#M?R;{+w6$(3#AV)jALxCPK4yjTXw^>putlFFy*|w8%S-8jHu+Z7 zjEgC*ayXaG`KBk{amrjyn0muELqa~}!WldKE%~M)Wb%KCE&!<L!j@VRK1F0u`Za`1 z9ERWuyH9MNQeWI_;Z(ECuc9rWCFj2MJPblCQ}Amq(SB*?EoBD7jN>fZ4L^GS00;iW z2NA}*n(o=Fm!%oqtw*CAmn0Ob`&JL{4>7RMz#tW-V2oVd`yp%S;=971aTu8M0me^k z%j>yt@%Uf;>7kg8;EG?_`h8p(dlz(Jo1cB{dUW|fZN?8Rg0g}QiimYx-&c&DW4QNK zh9w;z?=Q+&hO?|gxpLOl6rt&_m5)aIt6EuX9}Zl_2Zd*@e6XIs+gV7|5)4v4#uH#z zgOe1@KL&4|2v*HqK<8o`KGXb2%|t$#u()gUpfgpu<u;j{H=)^E#d$O9D<Og!fzGv| zz<qOxUZoC2@SF8_X@0n3@*nUwBoLP}@SU_8v+46>8L@y6av*-K3gr{q+E9@Vcj)mG zlxRv&ywPJ^%@Js(6>{5nIjji~ZT@~teXoZuOfn6bxkx!*^!u@uyE>aXMbO|e5oZgS zVC{z4M<hm|+S|p&3(wSk`8_|95XMa)k?a_vdL#BHgKG=H7^8Xe4@|Z-y7kvBH(yU@ zDk|ILuaN4Q8i)^&%rkG`c^PLWVh@dlKO+T2%yQ<rox@Xo+5FMJ%Tf==+O(H~mHSe} za5>=jN*U{*fD9Jfl&Qs5Wem+-Q`}w$80dA#ew@M`i@YilD>oC2HmweL&zFT-hA0IZ zKs;=zMyW4sDxGRt8x9_2Q0*eA=M^%*n=YYmEdUr2EMtvX?p&B98n0kRkqkDKgu}WP zZrBddz6J=jlM-4~wq*+I*P+>(dVso8o%#FZ=tK00;v3>_Fb@bOfL4*7+3ZWhD3DPj z)E%O{lrgmbip4hH3mYDdu<FM~B%j{_3dCkfW2;SNJ3c<mxHK9=D7>aCWEq@jV`GRw ztlRayF4kCiO}5G$7ZW`^r+Dq7Rb<?)-mkEmz%sRhMof?-oO#J!?r2&?L2m!vNXu;o zyG2D4!+-2oZ*MGQCkdCFabx75YH*LkvCTgg(+TcX3L2<-_2^H^M`Sg_?A_D(zY`a( zE^WVaO8KZOZ@_@MzyAH0OYt*!n}emBrKt<p>2=5df_llKy<)?4q9)VNFYL{i6`lg6 z%Ki75vG`iNA#SNQ{84{KyHHADejp>g%Vo!Za|_BdEv4r0`B=VFZ`VEZynL*D4y^33 zH+%Ed-S>2#%z4|OKc5R5jP=CYKwadPkO;wI8!UM=kCeee(aM3@&yIF2Wxlb>bnHv} zjDi|?;dQuI{kjhV804AmUp^RGbss}$<?JY*zSg1R@EE-dtE^5eVSf6caD1TTUU(L6 z`lgX%Z!Yfpq#&1N7!W;h60c4!GtLKOWQ~b`lWSZ4XZHmYtefdXp>h1!j?0NpoalQV zDNCk&^t9H!%i(NV4a$=JN^+bif1r+2k^6ZbgFf42mM|~vTKsVC)7xDCmi)wr%+xN0 z*_(RHv-MV8ZAit=vC{hk%oz`)lJn-w{`ErG!;1>7a_~!DKb?*&ck9dK0RAZXi;NGu zepxnyDQXK#6x$sGfubUW!Py|cFDeISCg%t{k9mio%e?i9i>kTU#u2?E>hI$$k%KTQ z{Ez1V>`Yb1DZKl64Wl5n0G^DCx3p`#YKrvD8xX*F^it!urYDkoCYL&T&Prt};Y!ko zo0P=t$D?X0slm|s_UMEbtyvN*hBdc@O-Ee05Y>Exox96|9I9z(tGxe=)2Zwbg}45D zPn+)&`%$5ot?>5^*+{PniB2>aqW?Zp)C_qR2I^G?3WB7$3JIVFcT&JeM*o1FaT4w? zo}kV-3!No7@*z$4EGdoOC}*e9@-DM&RjJ^(xIZxioCNy<2!+MY6JBpda1TW?s6$dL zn7%jtg4S(R{w<kU)D^lHe$Uc1vK(fdzP^6Kw0IduNA%rJnS{=_;LeKkSyjUHVnFmu zWUn<Dj?Yd|%@Z(Sw@fYHHdvJqKU3*QFSu+xex=1MO_DanHP3<;k@hA%@XX2yax6i` zF<nM640{QPoi7K`Mx8<?j<kOdal<i7qD0CN{jK7yA38tK)K`RtZpw5-8dZa5!L?Hx zH4PQ3SGuV)uY=^nj1z>!z|5-cQJ0%sS1edz#?e>_>O??V`%UwRso{@9lLe*)L{TNC z{klV4RdyQyNA3hKDIivBOMed^0%GVcMyDq3HD#DX{yQFH)%ZDZQ&1fG!6%4Q*Q(=R z@*YEaK97yb1NL-eB*rD|{3}PtA($exT?X6)AlbCk1Exw33|d&~hpz1*NORyI|BD8Y zy%dWr;i|HD$V^~nMkiFH$-AswRi=f@DQ|%BI#~7%^28ga)0Co#E!!Q5^%hkT(<^h5 zzQGjMRu{GmGwg8VX69|iyM$+OOYqwg2EGi-#E(g4B5O5mSE7+56$DX$(G8=|Xb5?n zr;j|_ZmPl?dH^ZO-@=pWEN`<PhPzI}nL;pVNWApj!p>_nTE#A7<P@SxwMY<-v3e_$ z+*dwYrL(^0YpG`>DYhthus}sPo3Z}RT&fO6THX~~3(n`zuM5zDgI1DA-QDAzopZso z2I^XcEdUd4vLE+%sbQx=;oUVEN(g&qDJHTR9g8*?(Igx&>I&Y<@hWs~q-6YaSojd_ z_*`NXcYPNo?-4JEKx6jAP*bTf+7kdS1+lw%1g1+DqWIQIV->xZ%VjY|#&%Yg=$$T6 z(e!6305)l0Qw^y%#>&T{mdv*||CKx#0Sz|*QpSNkpvQ4Sjg6{VOR%u7l-2;17aB}q zOVBdK+x8hy?d{U}&|Ef(<QBh{u_hI`m}c<);@>+LbeLlf+9gbI|9Rh>lV8;eQvST* z^tVA?eNu#n(pGTM;<gDF(yR1{X)+euTp7gEZs$DX=N>hWoF_CvO>R|~5S?*jZwBpo zN$@Be>ihr8ZzQWxFEmwkBv{<vQ7#=x@|^!uHQl_@qjGk~Q;Qxcb}slyzoFq+3vNr} zHK%^#ozjd&E8MzP)O_W!V8QL7YRFVzM8mQY(@T9$w>RabAe6q9^Lqk8;Nz7;bBAVm zlsh0i`=<-aXia=I<w0m;<6WCdR6lJByUq0<y972o)%8x7`&qr|=<Mg!9#waCzj+?R z?c~WWd82p@Ic3?!z3uYCq<z12EtKDU{(EDFe0(6^RHa)0G^27mUFx{wh2y7c+Jcu@ z?V-SzUkcH@s~^j-Junachl4gJuzuL(m#exLbrhg0n{Ucb+kyAR|5~}pL(}a*<v-w1 z{7AV`SzF@)`K-*WR@3Ps-=#Sg)nEF~;^xAtMPENTAWl@Z`_I}HgEeQ@(B2(y5Bg-U z^panI!}eKsT|<()K&vXl{`J4+Wk#w`D&oP~(u2+?){Hv+==JJ}KHHeTc!tu^D=o*a zDIM5=TnPY#hkIde*SDPkIBCno;CDzqC1LG=$LWS#fXCEZ9yxzTU)}!KewaqQ&IBFy za49xer3y!JQGspsj}A?L?uKDM@4FM{<;ERC1W>wP>^0Tp#EEqYE1;`OQ{8t~HXnbY zZ|kn!@!9dMHBx+`S}Qy>UH2~LC*Qh~M!8i7=;GHD?YrUGQ%knmZvKUH$N=};MgN7W z<b<-w?G(FSQ&^khX-bpoqlH-zi6`||M$HD<RHf~n)|)3YUzwURE4(`A^I4x?@{ZkD z{GaSM6zD<_aZ|Z<wFuy}fG+3yqEDtX%uB#KjuM6Op8RUz_iqCBPH29_G_2#B4(F+# z(_rbux1;~0ArelOZ3r;LN}9&&euAH7$JibmpHU7nX!zL<IbRGilgTdTw;ZFuM|e;? zHR;0_I>>-5z?v>b?OVNL{kg;8uDh&<(jl}QaF=D%$9u>6DaYd`{md`&=6C45Q$ZK2 zo&d8BcAUe6vUZR2Ou_3KG7HRmh|cPuckd=6@3`SejCkwE%cp}h*oDx{nM?ss8)OB6 zdc)LQNLCsD`zUv0mMJ_-F<RbO|H-F*DzoB^apJ!1&ZZ}vPcFHbC(Okmwob1+myR<a zF#c%OgywP9C<{taKK#}rz9WP~?+iOo;k~;6{1AuDdVeuMivmzFwE{W}7xWIwyvF+U zDwo9_b2tNUrQnB}alF?l1(l(u<VfR!;R7dco|eLW@KpWc6*d0icY;T<bR6}@c<hB^ z@_S0h?S-F%T1@<n%}U%W!keZY`B8AjFQ_iLtK}K*<y{PiO@Q#==-2bHcn}cVn(h}6 z)U=?NyPy2s#t89<B_Cak%IXJCljUCRCkh1r6J)(#RoceQnCu@~DV|?RF@`|r1R1yi zA0%#(DE;~Ac&CR!8g_$2__w+%P9NJKa4%-nFE=;Pq@il_bXn+RYQ=(=wUk9<Qev!m zE|(#rKcE?ml*or;{hY>3;l_E%pK<R*4@U4Bi(34&!l`B@35PA`;=<5*a1O+PPcQ;$ z{uauTG(%d2H#r$X3DRW-keW%;5ZeAN`K4n5rt=WFxXe|uIBF(2$t<lxY@^E|FhQ;u zsLd0bGTZZ~LW#0~KthKPs6<o5GoH$Q?PS`nVZ{xJ*ow=(ElPkRYI~tbI*u8GIrId- z0gU-14iN#^=kf$}6b5;?Dk>mml3lh2T(!hh7PXq$3=Kmtp^>qTGxq$z%Sig=epEAy z1G~yiGp3A1i$dWCovNum2AYbXtBut-ARe43@BB(XP^)*!w9Q~HAA`mkS_+Rj&cgF} zFTDW%49ana1Z()J48(+XWHUw$5WX>#rBI<GLe*jo=L^#Fs=E0~6>gZ$5}qL%4xTGD zClsSUq5mNFjS?`C(yx}OTfkKdC%$%W|0DKd+NN*HO`kw!b~3$LG|Lnz=uA8>Mvl74 zVzdol07tvoj0;Fj^*M6aq>ZptTrTgi`<~w971*7uGS0*$NxXS$%^_n6w%^4I>SM|o zL-R6NdkggzFkkL=-8<N5V?6{NM?_*)LAK<6`IzRJki-1}G!v^#r;4oK9+Cd}9}m0c zy~_;HaoEky)Z}=nhvHAq`L}-hf8hkp&CEH8zI|2W_medD6yc!>^ZMd+t|O}_<>|Wz zn_MUJYF&x1c_pOo)=MctT8*2C^v2;eXPQ3U=)@~+1DmYYr*XjHEUL_QR=6wuuAHo} z)WV<P8bTKSvgk_3$tu+!U(9E|`+zOwyG=G>3u=<L{WVi7Rzk>-&YnJ&Jo-A9jBn}Y zBe#1LSpg3cZmit7Z|;cV<(c~7E&Jh2dVy=c-Tfv564~iw)mT)R)g2KWc?G+gi<}N% zkSAsnsF>o6dD~BhwDnw=_pZ};*%FRx%i*+<_iDGbr2IuJ{QdRrBAq}}QbfOVrOVn) zK18`yct@R*@zq<mekxfd-(7up|F*|&E;P|WUQfIs%_=AC1W@1|b?~cxFl~LZ{)g@H z^)ZE+t)xI*{MT&qfTF}*i96OS<~Qx5LdCesOg_6$t+HtK(uL2hzZx|{>=2g3SK`xl zKD@UhWW4H;wOG<ThW#-ltW3w?@6rbTwN&rf7=0?_S6Tep?{h;Q9?c&fKf&CDSu^Ov zao1a~>i;_5IrCWA<}X(4%YSa#iwD4X_>wH}&2*e+4Etd7i{6D5I5EOHjPm;<{Q2;0 z?{yCY4*e~8KKSCcMHP28eLiy^tRp~s%E*i1-1e1!#jpA+iha6xGKp{WaZdhmzcpj? z|IhdpURoj2XxC?XZ+V3=alh(+^5<ukX{W5%FdR!Sqhp{=M4Em3h%5<%<EG(FV^;t# z-n+A}bk&JUiYc>fT1?K3AL(8nSyV7`a8c=BGm~q@s6-*{8Lt{FHa~gOn@xeNGHT(* zIZ;}k7B<W^?j;s|$4dXGF1Kz{MsJm-%Hq>x@iZ-aFIX3h{DM7olH5yP8ZVk=P=M#R zO#ne(z!uA?!j(gVmBEpytBP4y>VwwpST!@PTDNejYAzG7f|Z|cnZ{y@uWc&*APhJ= zd$4ea7WJlLdG?__q@hY^tXOBr-Sp$riAO?~mfhcydo@qYCF3OeOEj56wFzMP`Q&q> zQJ9UWxQ~DnIlE3M?W>%(M^3WdzWXZOW^?u-t-?`m40F?;N+NzI=QWW(3B5d!IwoL} z`9iaDz{eQ|34<Fn3ezS28oRlpWzH5JUEyxIeD1QvlZEKCGa7JuMH27p`5bvE{fqWM z61{`_Ng)tE+{@r(qA_ybNGE|O=@Q>2pgAp)s#GNwZ1aY&5XpG2>I9q(I9C%<vVh=4 zGNLpeaEZb@wQia*lI6w`e0&}!8;A)IG9&n<OQus_rZbDndaLTG^ik2zA7r|kG1ETM z<_10(g2BbT!2xb`63D`IKPcpYa}(s{-r4|pvR>$gZU(KH>;Pj1%$&Q(QJ%Re+RyZ- z{NBp1Vk%@{cr|YBSL!s)_s(Rq4OVCgODwt*XQn+^J8}20ez49MUSraz*K&a7$RFiz z4{J$r`e|;X;Uk)OdiCB`wYIX2nurW=yR-;xt6JWz=R13Jzh7aV4T#k4wrzZmd4zDZ zfTSWX<+bIj%TWRU>qSBr_meLjryTA~1D`Ct9^r+b5gLjdl?dZo{S^Wq>-?JM%x@fg zZxkrO1{8g?(it?SpCO^1`61G!L?RMaW{f78&w$SHq0>1=5A@J@#7;2Sr6Q-v(jv`= zvILVghG?g`UpNn<e-P3V;m@>^qi{@*z~2Ex3M&Plh|Pv+6{`N`q2w&Nm>S~MJyzU; z$t&~AG*f5*YrN=PDK7B3A`-@-^>ma>gFbyR*Tm*YsnD(pr@Iv{lO6h<5n!hB8+564 z&G`fJ2l}ye#;r)CUDWaG`Eizg2m>9c;G))SxNa%NF{$#tDj}^E7E*HKs|<Zv#_E*S zUc-R0{UTdVNq0i!A^6~o$R&DV+|Ec<Ec#1n%wIx;Ebz6w7ilw&T<2F^RHi~8=?PkO z+6|6a0i-*pw5!=uG?#+#w*qhV6@r^0f$mpHbYk&srHi$@%8j~i9)h1(e^HU_dNvxa zwmIB-G#5ScYg59?EA`l10mG}vYn+F2AnkO#ZT?g`&lm`D!|5Z`*Zh6z&5A$^+TG~o z1NhW2@KFuDw@ZAIRA4+2@r*Ef#GIV9wOTD8ZLq&^p`5_phkhLygFh;snLTmDnf0=x zyaq06^E{kCF#{ibE>s4XiFhK++PwN5@S1ZF6{GqB4*#%87*UOXON@>bb_&I9lH@Gx zf<Z(YBv;JETtT{;8h|?S&m+6aH<&rJ!{wiprH=;PEG)PrW3RMrtN^z_V$~V<w{Pq- z9-b_N**kAI_0|p3Gi9giPv0J*&|m08Ra`^+keu_4U&<@L|5kL-IG!T-PfgEw?7k|D zp<oUdy}EP3u=K(gfN=*EZ9#@PEM#GfF2<}iawZ-gyzpVMJKW#9^~#4w-(h5@-UEbu zrEA}4V5~ahx{3=F7Su&fY)Gg91s^}1|JR>hTVnhFBVd7MTEBSPQIC%ltye%yIX~T7 zudutO0X<BOukuNVlO#bi!K~Ex+J-SVR5s=n?Ls9>=hoY*h{x{1h)2i=H5;rlS^ZbR z(`fx(@hF6)hq#e)s=p3@dB?OZn`@)LWB;>gZEwBK_LjQ!1E{qGaY>gL`N7Ul0UBZz ze4*;4U2--7w74&P&hJYASRs>^az0JfvS>>3*;|&WJ<O#zKd1{^@<=)wC4iyYlaDrh zlkm&ShnmOw#7{>F)%XkD@9hY8m5=Wc<?mtDCR>!+w8A&lu>oIrg?(w*x2mPlPJQc( zSLJ7F9Ph@W{4$1Z&%b3JKIN;2lZPzNobG4T>r<N^HDmLfrI{DhTVZC1n)6Mn>fDj; zy4QPbDo*KJ>lxeD$6TM8YlP73y9oP()LRAP^GANx{IRMzxku?#r)mExb$qC`0kv<w zG^XR8L)~lD|Ht)#Q!@JW#?@tKFkHkY)nN65=INoiR$YE~SJR7f%4en-SKq2zJ9#9d zVC2VJ+#}09U=2jBJt4~2(dR4f%}>~a#U+$?LPIdaz>5#ZpFg_qK<1WIfw^DXHeOZR zzdpsN=phnv<y%*mZH%e#&?RVw$uZ6s-|<>La_C{G=1D{5_J~-|kHN>Q2j&N-VMOGV z8J_EY{1Y9%e=P&e;#*58Rgc9F)LgE)J=CLH_C4c$oxFU#>DYILu5GccJ5>ic@JBa1 zaM?LuITI2e!kf-jrxc+!>t65jiCi?|Jmty$&giB~%Y*`%khIm0T4*YY0IK<B20j<^ z3(Z*K0ke^In_@ZC94FHg@}!hT6ef$OZv2LTS0~fz1FBa1q89Yct;=(-9(LA%nSv76 z09N@<<bF;jdX-{VrN#gPhfLUx(*p@e2X;L{kwHFem5+2-tY?Y?+NeYd-u0@+6&^Vs zPB!p?3j&G-ElBL7zG27p#efHj9fT(1)SaW)FNm!!aH^n2!q`82-|e%OLPNS=>_)fG zXPLs3Z_dJ;;qu|q`BFI2(ry=}i;u&=tV6Q~FK17Tln!0fFE_!04T|09<r6u5q&cUR z4v<DG#WlrsuS8S5VzB&@f8g54=Oi>#=;B;du3uWlo&L-e21pm@F7KVQ;r(0fy#5(q z<ZCLJrymW$8le8Us_mCkFUfyuVh>94g>rJjckx}{X)cUxW|AQ2kJ2wqQ3maWi<`hn z58vy3<&7FVoCHau_N1^0R*Q(@b}A|j<aKrECi>*WaB9GJJ~{<HWy-1~DAze?=E6y$ zGeZ`>e}o+MU4~4n(HO&)2nic6;Ht%zT84r=t!`N%ENyHL6s9A1?l$8hndwMd3`9YQ zKqd)K7cRs+Ax!@k4PTaYv`R|@Mz1>w(K^8%`KCk4P7F-Mh6OrGE^t3Hyz$C_nsSOM zIxZ>jk9qr4C`?_cG0baeGdWhG?icBiPdJud2}xM+98!en{WIK!SmGczGq&6XmGN(h z1`|;8HTy)$_WRLbcVH(_=D?yAA-^MXicg_ymP9Tx9o&?B08bs5>4G!|W-eH)OL=ng z=6`HXx9EH8IX{ttKQ~5#9Dqk-n@YkJ+#2~J?iaKiy_`6E#)TF|49m~9B`|a%?IV8x zdALmgbdU7H{%PLTA~D}}5HF>H&bW|4k?<h}r$DWP%RwZIF~sbco0*>2dlgK&)k0jd zah!T*sOD;6<?t;1fB5m6nie02v<FjzIAm_z88xPRXjQd&06CR><q{3+%)|*~-a}L? zP?&3r(RLoVsP;(jRFz^I+5RAnp_8iMq!6+sM(l@aaB&YTU=os6Ze)poRi<hH5v_O; z4gjVo1s|Kkg{`KeiqEQXpHJZfDn0}BVD7LkOo6aWI_mmyHg)RFK>J9Q3^w8U?1?bG z;*`s2_>cHnhLb{W`n7SLxwH1PVQx6m!D}Wo-WWE<;b|Ct<3U9I8E1%Vp~}`<4f@Cv zHwJ&3nNq#`3a~qL5yR@A`jy6$?_lLxBkME74{h{{$h2QWuP)3}Mx)nc<g4Eb-yHg0 z57x<W)FJ7uTiQ<KiY8Uy0<+n4&_A@IOh{4J_8HmyRPGqce5Hnoa<?|<8~d`1Y6thF z@@;$|gSLp&N?W}~5W!pX-IY@p4x7;?UB;xFC!b`l!2LBRJo`HnTQk?q01?(M<tP`# zRNAq&IYP_h0pgjP%hGAhP;FNH&KG!h=E%GA;-w+~P1yHMylt8xmS-ntZCfoK)I%`@ zEccUktQ??8dOJvS#*E!SRzCJxuFb0b>Zu!3_(n`B%3ZU$s7^h@m|Fpl%gzeRRzBJT z;-o1~Xg8r<9PXLz^^-ji9h;WGl(QU<#6aoek6KDJAJPDd6jPuD7Ok|VE6{tq@iRQ5 zyYv9V@%|#3v&%pzX(~d)&nK%)3mgN%xbeEfmA12S>x?gU!tEcWZm;p_tNE<Xa4;QT z{@kdZ=Hu%cG+UqS$F0cq!lDYT=I13_8TPfW_OJitn_mN*bIw0$C1@!MM>o9~%Y4~0 z-S4fL=K{|>GkyBfl-8REQjUdnY`xKVM+N_wujFu~X(-M^7lG=;`f%bi<LgfJP2ck9 zIaAohd}-fb2K(<1t>|wj)NmS~hf_E{f?1AiU>dG8gU?-(r}&3-`G#)$R0)wHrb0eE z`+#4}7k`{gsAw3qKWVqS0&jcKY!r@`-MQ)E^r%~U<__^OK?Aue_5ny-ETK?n9OR!S zEO7)maua$O^^Fx@{(Js!eZ706lOA|{#DbxUXbm)lE_cI}il%=J&7IgiH8lK^I3r>m zK*ng+&OffaR@9=i6osGqR>ro!C4YQ)=osL``zy6{(7!gTO6f<URx289-^=_Z@q@pL z=wH8I_GjUx4_5ziEx)zVWU5sSO{=i~6*cd*3pbZ`zfq-CE>mgUQ>xixi|M=IUr@?U zLg1985;grnKU{aJo^XJKgGJMkVp1Ck@MZuwj5!tF3=qlJIos0oMEF>gpnUezl>b+r zbO1JIowHp9zImXh;_%1OumDpxRxEjw3~Cb2tiYcZt&FhTKG$Tn_*&YB;ej+pZNJOf z4akUoK_J;?>eS;iM6>P=l}Twg@f;_@b5=UeO8;?AKq6fxGritbp7kvuv|bl!X=A`1 z(wD-an7DQ->57OIrem2Svv7Z6rt)1J%sJXB<UaP1&qOeVes6TA5Uyf~W^A0!&k=0U z3T(xf>Y>o&qko&1|Bei!6!d&m332MUHIMnGE2TB`iowe#QacnV?7ZA1&N*<lBn~-w zoT>J&Z43w?fg;SIN`~i}3BK)Yi!<<MKfk#f$~$<#$<rDE-K*%cFC6>yrnT2X=&-^` zQKt?3Z&#ueR>%`W&G0FihA=B@Q`zb_q;aH!3%31RKJrbEP^MCIcV9iW{%^^@x0io= z_5JxON@L2|mERp=EfN2~B=xG`=?I}rL45uOku=3yGFG*6;-|ueDO#1Rnb)q(x(MVi z671g+cA^uLL>rg(;$)fGlT*R%&&6LkR7qm|hY1~LaIs3^9WRDfD5QT9s875+bYXko zZ4IRx`zm?7^q1~fo@>QTp|Z0l4`TBZLE^_BWi4b8@<5=TmKdKyJsmyV9y`UU+$3@~ z8>m=P)I;7w!D4esOku43748&sK>HAWpgwV#IViDU)siIFboLpmk|y)6rZDHm=G&KM zw@u;Amtl3LLIpd7Q`&Gt&VRQSA`H^0TuIkDy714&Pk({=0b{2k5;6>X1UWGVF-S?P zh5={(^0@9;NDao;aK_N1Rotpz`r{I*=w|X6%L;?0U>3&mg7HX&gl(wS2VE@#293Pe zMKhFPsp<MzWraWbV?s1+CWFO^6nF#+zUyZ3fM6K1Xd!NdeOl1^xNuyQPRc3NqJ3Aa zY)RYcOByE^;szo@D~0kJ8iXv_pv59mcAm(yjfM<q-*w3#nguQVKsX?h#9p>wr1+5> zivg36s39hS<}ruq1sXWiSB-UEKFEt)lnzacF>zQ5B#$4y%K5qb8dvuu?yt&N?AI%F z3W;I1*@9B7v_0ff{$*dKA}i3cf2YA^vdfAgbmTp|X8dz16#9R(pW=3Wn8)GQbYpBW zlo)1HnB_Q~lB4j;$qOK^eCtOpHLfNa_$*v}=i$Cs<)2T@7p;Z41KRoSdKs?e@?NgM z&@Rn7b;0`n2NyPvoM(tpX{imq{%o;r?9zT=`+q?HSFmG9@v`(gUY+IZE=Jg(5HUBx zxHKKNm1+c$`eeahqH&WOqWt-@<t^G1kD@m|=c2&uPb2m?Rf-xX?;+BP5^A*VX71<9 zom!M&l)VvTG{M@RzRpNnY7A#$kXQF${44|h^ZZAC_bBkuXcXu_OYpRhGa8oTs7@Qa z_HW79u-}#c&(e3tHGQt_gTg`dv{ckuD-d53%22Sy)<J>55e-2xYy?4Cfg;*gK@g%q zD7JOgL_z{ZYl3V<!GTqVQ0s^c4I3ArvO!ir2xRnkJ?Za{^M2m8K$35sao^W{4N>nW z%`aZCDCuOH;|2=^X^39>3_dBs<?@XvVcZ2c9W{YVszT>;(ARYnzfVMR*O~nFjWmzg zM1msN$m!2LAO*cbJiC~vqoFY+v(uK^KTM|`Yf@c_o(NDroW+w7XFfY<`n|*m)`}U} z90PnER6~$3MQ6_Vt~tML<Mj7n1=<NchuR6hj)chc=Kd({y$3ll?(Yh2K`>+hnq@7D zKK5m9sFB1BUd$jb;eX`N#eLmYJ@M6~-Ca@GF;twgCb~_fpJd{0+jTo+YcPysJa}u1 z!#o-KEG}6Bf?KZ+@8Zb^Ed<`OUnGsajaxmOpgTj3n*^+negbsa>R&g@@WANATsB}% zEjn^@)(}KZDbxo<F4^EFWy=pMw(SpaDAM_~RFrrD<0J7qh!f|k|1NJmai+9jtn~To zifgI$JZ#24IjS4g8z7?)4vO^?KOYMIFoq_hO~R~U=A56s3;mkMoYk9-J#HKJ5xg8& z{gzZ_>4Xngt~?112EgbyYVC=tvlA<~xNT>OHdExU)jh(leMeu-1+_#0iw&PE_Yh7E z9riwva`A16&g}I1XZsr%u@N{dxK+mTeucgCby<H)snlU?E2k6Wv$0j^8-#O*4}6t> z=KJ_EWpyc*;o6?!b%EpYX@_h2XguOyd~50cO{0m99RW2uKwo?gj2Q5OZ{(zRCf<4z zJ&EQib?`c#*W4flES3`fS3&c}ToL#7ny*hq32Y<`lz60q#ldyupfv+MZ^<DUQ7+-X zq5Umi2w1De(iLg}usN+9GKe}Yzs6A~8af`$MFk2K#=)4hBHIF1Myvum41>+h@wfd< z0rTKORo_4)pQFL^9r-n;7%nwvI}1p{4LC^1^!ryvH&iLK0?ixebxMtD4&f8B0pq`2 zf!|v#)lJTtw1itpknTKoVvtFg&Ci$1Hc}AqF%u1aPH&6gi@^y3E@o|-Y29_fkP4zw zhO^*_;P3kbvO$68wLnffns>BUr>)&dXHP&k51by~=;Nf5!T_F}=b-F!g-PTxe~{m} z_s6BRsd5Ya3XaU_+|RG!WF#>VFgHj(UYCm=oghWRzru)D42*q%K%z19{7>7jxDEJ! zej_F{47i8>k_(#Y@P3NT=6`o)gj3;g;v&}izh;ncM;g`10|m;8%Tv<%HU08!W7tzT zz7hXfK6znGuI9`Ql4|;j?wOKnj9g-bIgOhaCr#0(-{Wi{pj)vpB?i#{7>!$6`rLt> z?^}~z=MV-o-axbzp|k{kQBLK^2FlJ=p+rVAH-wS|_c|itu#{p=T?}EX(d9`VJovvh zNlWT;xu8We2stAgA5Rq7Fkd;gPOZ%#!V9Tl7SSjgxu@gDsN<1gjj=w|ju`XdZf!yF zlZs#RgXtZyG0=3KIH`XoMU<bTA!IH@>rzeu-x<_7B^q)vwZMO4jL{0sVBHz+OjJ!; zCBzFGtezasdeGa!q0o^5I{x({iXs3gB$JWkgX4g!1KS$w6GVh?P@0RO>bZ`=Bs{j} zPysL~FdhQv${DdGGmlENors1c%~22-|9tYifPwK;b6Q-NPOL<5a{=fQITAQ&Xd_4x z6LdXLg<`ahXs-2m94X*9!tMhCA){!-JT|K{-~fd$1#!sMU}<P=VWrUc8DvSEDFo)M zrJ371r@TY`K_$=g&ltPEKtaV+7r3TyFPbE@vL!@g3j*f*=%}BFw@OBzm$Eix=+qtJ zy9I26TLhjg#`kzM3u)MwaI-JL3#Ukkmr)5;3F&+Jpm~A3JU?tP&i$oO<&ioA(|2t= zG>}J5c2AnghB&3(D+l_tj&fc3o76{1+A+=#?l&uNk6BQ;IcmCk<Cex+9q(!gbGWv6 zi-M>mb|P{SM8MZpwrY`}>h~$lcIBwz`1ykWz!ha^u;m6GDU4-@&HLuJB<kGniz_06 z<7C%4lY5B7JBYY@tjCo0Ct|&DnKI-csU^*nA6BJbzk>lWSsS91_GP}^)(0*yIyZhF z!i~cO2%2O>5J9X1_l3(1ubArVWK`Lkk1W75+shI`{KkjoR0no;+Ar+=3?dNX%Y<9Y ziUxNoBN+q4M$ul75~C7FhSr?j4rrl+z*NnymtUm+4)OzPt^AkDJzHfT!|xm4DfEm* zBa3T*NfC>})S)KC@odzPCDu+SPFQ|@)t_FC8Q}2Z-Csm)zjh-4>KZh}khYQT1K2R` z%c08ie}FgyA{c59_a}u+BRnJ`TbA|Yf7*}|pRK+Ri53wy9q*T6^gJjFf?S9&Z;^iF z<<OyX7_2FLv+U;ShEW!kva%Xw1Snp$;Td4yMZp4~#H0v20m3uFrbg&^`GRhIuBN`z z&xN&!9)RDoD$E-X<}nVED~0L~O1cpNY2e!l0vDMuV`jGf{JO}fy6e9rkVJ%v5}T^= zr;6cfYk)X?eg#8xv$;~P>*R$XuXkSiIR{{M0-9uMUGbS0CU1;cW>v}CcN4oVYYfDO z^5<%sCX8ERUtE!)TXlUR8?LhH+kCPoD;JWH*$8h(Zve+U>+H-UG}!=m)6k|N3F_!r zJOL>kiE~M1L8Q;}#5gHn-h(|s+o7s#YH;`J=EFHZc8|7PSQMw{!ySE;fIs7`R>sVn zxL5L<?ZJmXte`zN&da6D)iLQ)p)s@9jf9=@-EYJG(fZXBn&rq?y}2^G^8P<e#$Ux& zKS;c^JD3>~N3isoptcKd2fwm1IflL8n*+TCwIr=dC;mvOJR`*Tm##U7yOb_oy#j0e z>D}{f%>TQCsM49}>@{<Lw62a$e_`-~irjjf)54yv#Z|g-!IF<R$^s)Ue6{(ttZ7u= z4y@McCmSDd21J3xYEFbyYPXOr>el1+AT$6PZC&wbr&$k!XQx*fw{Dl{zGo@F$z?d5 zzj@7jy|*X+wqGtuqldO#q4MLpWkAH=pYwYVyp$eZ{gK>clua$=kGZkRV)W*2b8r1t zGO;fvFZZS$OKuTgF2d{^L)8`>u;rIhkP*wI$C@rPLN_U>J%-Z&My*iilGFuzG66hg zu}^yfP!ALfNSS59_To5nBrr`O&CYc0E{KgA+!3h|4I@NtGTlU54iGy&rP*RiYJH~a zHR@5KB=p~s4;SW-ARIZtu}M3v_bqPzY?2MjcG_YIFcXP5n6WhIEG5C`gSi?edgg^Q z%4McofzOeC*%3S;T;jAr0I-6O*G)75r=}50J8c1Ohq<DpCsT7&<cY&+;FVz4e1z12 zb`7rh4%fBw$sB>`%>c`SQlvb^m@D6<EI+q|sEv4-Ac9^73>Tra9<u^>ZC~gh)y<dH zVN7G6zhH5U1Wf2ma$tl{j*d>Bqu?dCHFkH=gyrJlHKK+dl~O$FJ4NWR4SFT<_Nu<0 zIEZN*Qungca%tyCZH6mBSz5x7hnb1rC}4cULT{-zOOE*dnHx+h_`t|_nFMk<_;B)5 zVYmufUD!As#eQyU4kbv5KkhGANx2k~vOi0o{~X2G*^%_N8h$TRr0>RuBVmQuw6QEr z|CqW8`1&Y1=>ogcsBMY74_((RI!_D=6GJf#9wj`c`e@QF;MwZKT>)6I|7;AY=Fb7A z0hl$^ow=atBw78WiY7OxYkVp^8?3QJ5bSK2D9gbYi|=<3<vGB~F$?lm@n+S4jQ4Or z1IJ|ube*(meqQj*BX&+&P9)rWswo=-MO2zLIR1Q5cgE~w0^KMhwnOmFt3*SGAiD@p zfVYl@PU!YD1|3k$pz9idT-(u*EpkTpj&}!rg(jR@XfhX|1ye?F9wDo2%3!WW38-aA zL+>%fQhj)e%v#z!(Cy-CUhS@}Tn6L}CP9SjhJq|{lmQR3yC!g^#W9Kr$OnR@Oe4~< z!}mZ<K0fklD~O|Q0gfeL*I-eYvVgmF`Y=(x5^pq3TC)kNl~@8ZS>D&QR5%h4(I~af z$E&xtvZxpYAqe9-Q5L0%EAp5WM6}~!U|0)!<QPG=2|!aUpwHEwP6LG*Ga{@`fZqh^ z>Hj0<vsy5fV7F$-DFVe}Xn^ZBMX*^_p;xU3aJ$iL!pVZ+6`C{+22h;Rszt_41H8KD z+dvraA*j1eI=-X;h{7-+PaM6Wl?v!31FpPdmd;pBLa^yG{AzV5IF>M~<#2%Oo0`Bj zF3G<KAO2S{1iSb`)xE6G{|n7D&*l^bXk)KZh^!x>9jAg=5ipHI^>UOSCvR4UP{eo* z6smI$_P*Oc!MS$_$6`kNQ@ZZjkn)KD0Ai{K@VpL6Fz%g&^@^rKL4d<9H|rn0LNc4X z`Nufx37Z0B{!27YpX-;;ly^4}W>O=L`g~0$SS$j~R6*ZTqQCp@ag*Da5eIi$ke|ZN zkf|oe*-_KLlpYYziTRC~jjj&UDs;EKxjWJm9BUPJk@sXUCLvb2J+AelHEc6J`L7ob zl639IWIU8Ox@maBTd*B5dPioYAnLE!^$rjS%+T38Qjz7mf&H%_ev*219j5CAO0hNm z!eCBf_$;^+f+)dvobZ=m_)oJi89w382~&^#qxFAnl^pm&2l>eWzy8}ryIE2{smmO* z?%Q#G2NogGn&TY)`s|00te|IB_x`{@;fJ%E(-m3cVd>rD5b=rUzQ`Iq?5zG=@2bY0 zThL_CIdGOltvsA7f?p*Zzi-a)nZ0eH<Lty>l_K}urDyR?n<GZ7-=u=yPF`X7Vf>Hl zM&A2(sGaeB-krv&%rU~xu7?F}3~DOgd;hPDeIaC^zrs?gP}{!CcH4IJlNRC3X7JEF zW@Aj3b<}@D=9)0Rt<9Q;1E(blgGxYTU!PINm~J)3LR|!n5h*l>EjQu+=UmCn!e?iF z;T#P^dQyCPJ621)%;sv7PY$ddieK}#2;k(<pEGlzvH+HjC^U*;ns_|^LwReS((e{m zpT_M9;HeTy)GZ}XPST3&-rVNqkJC?I`D!0jS|1ZJ&J$nphU)>`8QvPYH~zd4SVd*z zDaAM}n)q$bq=<HKHE~6V!+#5=D~;u<H)Fqjp~4z?ySrEddecoDcbvHhGJZ}I4(ppe z|IrS%u1KouQTLkHDh8fLFa%TEFIwM+ztLhz4-0;YXvRtw%OSt1XO7s(apb4>`6!H| z;zo0DYd3uvykxMv$3RyZIZKEvR}UVhBq^um&lPK54tYom<$LJBW9zmD<9OOiYR}o_ zyT(<WycpBmSB6gb>r{UAcXlDKG1=mLi<*wp>GyNIr<`&r-t}7C=xfD)a#2B&)7A{R zw?%!n7A*%4PugrE>f9T5L*91%6%_mC;#5k<Jz5&DO&n{gm+itDos=5y?-^*eajp)c zn@C!*m9D~<q?unMvBT5_Bo{4&4y!YoP$$}3?1#A#j<SC2a2t|>it#3PJFZRaU>!r| zjx3y34ZBKFa{BM!^AN^#;lFBI__LzP0!V?5Oe)9W;qSBs2@4lM&cQN)HaU15&SWoT zIigNrB!S+jHlFkTX}WyqirdM-DXc7*plm%VwA^ei8@lrKlE&U<^StE?Ina6%Zj$%X z#ptxKLGlSCu}csCSHj5Xa~ITr)nR>dP$2Kggs`TZ%1@V@V@Ye#BFEqb-MbVZd6AZE z5CW~-+;0}12I(4wf}-5~nl6*_s$gK!{LZIGDRceBzkv39_yt9o;I~EB#iRt`KL2Q4 zAL}8hE5+1Z*dT-GX$kM~raV*>c2!B4lB$9tKkZj?m>{!^(Z~||E_VezRu7Z&uUCLy zh*R&fM*+}j^$kq@eBbTD(0~HF*=E;(*!jPb=GF`63&|5;yK{{3^iY31#)KBuIW%He z0<PgxJSUDa$bn8~%4>0HqzR1#*MW>V8o)9?gGO8#9QxJ26%1$-NF9#JBNw4<665+u zUkx{kRMmIHgaP(jcqTOPrHQ)+;Q0nD3b>ejK^lMfs4!`ZC60^m@$3k?P3WJ)xy;^5 z&9HUeCWt|BH%UA}e-z=i1*r-dY`9sP(bY*^`5@V0M$lDeK5t_ozyO@#MtqIb1jlk& zQv>n7;qOPzcVcilE=`O#pdAF@V$0*;NE;+Egh9l)6YVwXLX-)(ET5u@FV{+i`V3VW z8X3UFdTJ~u5t*f`ll1W}ag_m~UxJ4PgcNR)eW)8z=a_e?9|*LnWlvLQFv`qfVmqs^ zn?HBd8;3u(XVdpE?kIFng0%5-AvG1k5wzca{p4!P1;$x*ih3E+L5!$Sx=n*T(U~Ya zWu|(lMZrKGZ0b)j&GP<(JTvSF@hH-KW}*{EEM0n#%;?CI4-g1J5oCzx=mr)Y*WI+B zx;H19wSza-x+DrWoNx~cAQ(yENrvenB20!sGL{B|EDBpHH~B{j635W%S6kbL(WOKj zgij%R>iYN+P7_j;;9ZJIM3Y&1KoSHq&Xh_x+=c0*lYy`kzE(;0$EOpHtId|nfY?X2 zR|S9zsCb|$L(mtt|CA`b!8mv|=mq=2#(UW5D8du8!>gb2uro~$`JCr{HMi2(?GKQF zD43(<rC=Qfc0vS8ul5-UrB|pVHTWeeDJuXM4ILA|kGzK=MMZJ&J^}li)7N&8)>V0; zx8=9$N+d_4kIzdC`sQ(a+c<k4(Yfvb&NW?IQLX@k3vd#UK7ZHJZ0pbywKb!a)rirW zHN44*MJ2(4%F|o~pGB!md5T!aKttK3e%{KoE+%}TSdy+eHX~4F@22kbe3e#+Ayseg z5-D*&x&jkS&?1GRnRYbq#prPzFq$g(@aozW(DEyxC4yu4^l;krx3$5M6y?phPSlN= zSXr3W$eyCMR&$0ghSgkI(Stveue=$n>fQ3$4M@X(#}4-+6QW1AHjT2@o-HBKAdpQ= z=X&!3lW|A>Thv^%vEOR|3SmEK+%sB_?TV$W0m<5~W}}2`tKN(5q6PQ_!~{nrSG$Vb zTn*O4_^%6(XYG*wC?tp&fni3{Fluz;-M9NaF+<{1mRwM}QItDjwM9O>U*p`=b(IjB z3{1e<pC+2~9=BQJY{(Nf|4({e8nW<LBZ1dUBNPe6ogs_<o8_8V8!FriYZt7xY;3SD z<;~p83;ML^Qg5Gg(B4{SXWd!^bN@yZ)u_RKPd;rSzUOj%3g;I-axa=ZbQInbH9mH= zn6X`0S?*BcaKSFhQN}P$NExS2->^QnuWCJCpBzs|(?`2g;KngJ{Pq*PSKpBzD}gBq ze=D^3;Sysw$B<$F+oz%nwAg8w5o}(i>N)6npALn*j);M*b}2oXUYd4m{H6zP4^#DT zsLaJ~(3z3FsNmeIUR-HEVbiu~>;pK>VnR8>>CIV|KHeLC-7ddK&Uv^8>AC9gf3%kG z_Kb^ae$WVVP!zVJ-SAInw&7mz_Gnwvt=)GmyTND0*-^Cl`>?qC_bhq>ckOQzA4qnV z0b=bBro``4rBp}4Y(h_B|B9!mSqojN2I>>eEk0OuujKxX5&B3@%r9>ZPE<KBsfj=g z5FLW^f`XPvIq%Wg!}m9;DdjS2!0FgtduxmnFUI@I_1}!0{&-#g3r5~h*D$r}xGDr3 z7))1!m&Wf^iJ`1m&KcD2e};8FmJRyo`<yV2SDw}O@8Yhcz!fA|WUw0J$KF;Zahdb} zf=t(7|21k0N5BjgQ0*n(0vcx$_R6q1!OzkJOKrp+XuV+60X`Gb-q8^T0QW(^Oh&Z+ zj*C3J`QGF@=L{^pwQRfN=+cy?Ce9Tu98a7%QE8`(1X}^b*z)S(-)a)bLDXftEB|{x z+^``nGScil7FX~yGc%vFP<_%;;F%GwyvdVeq>gD4TjJ~X3)dDTE1T24=A4YJi<@f9 zM&Z`%q7Sk~pBJ)&P=4W$<V8QmD!~XLcI$F;AhMSLD7=pj)YAkQ01?*gsWz}F*3KV5 zlmb#`Sy_MKJ9RUkwTQsCfSANvO9{aoY4w)KV%<b`*fOhS-vl(^8gV7PO|xW%;O~!x z_4_yz?}OH&Z@@o_qKg;Lu-xQfw8N5EXs9&fYR!2Sc~l^tuz`UEhlUyo+j2M;YJ>mg zqXMX2r;5iZQUqhauqgE^Rc8?$_4Aoe1wBxGhXpt9Lci8SjEiC}BIQ`s5qurJWGU$m z4u8JMU^ap{t<(d)Mz6tA%=l9AuA;m%3~-N6$x#I0V^OnkgT$I@Icc<5h;JjdnU&Fa z7gOPCIxc;DDnet%o5&-c1^6cdnCD~2HlT%bS>w7@2b5(tyte@jS2&nRg9wAD!Dt;F zChn4KFjRPTAjZKhD%gt3Pof?N^PO<TSnH8p`HxnxrVY>Ilc)j$;+J`%d_!rDFI_gk zchx!z{12>30j^8bHT-ONT+k9jG{}K1$Ps*&x*dYV9@s}8#ie!~IeCzDNgV&113Mye za}uUFf)us&0HmV{&SS2GVHHpdKvi02!NZ#oTA@r5llKQYKqnJn%rMx-ISz~cy8^8_ z=*0jR_qO0lW@2m)v2&IS{C~-lN&A;8!FF6msn3@H{ouQT%7oEOk`5k}7bdVN5_kA5 zg1iT|0i<MF5Mc`Sgr+PYBQ>j1$;0)kU894?hALGQW<`<^3%)fY>ED;tP(czP1{_l6 z4)TNKCMf{iYLomU8fScM#Dx$n5p?F1G{_)&vl}qWM>H!G;)8;e1`^}s>bk3k)Sugd zOPg!U5@p%3Ktjn0S7%Gp+%G94UyScba2OVRjIf`zz^L~mNC40XxO1VxN?P%6EDV4( zQ$u0|W3v!<o3A;B$S~JYHL8nKzBTL0u7A#$@W3=V)4)@{OfTbYKT)K%1TbZA)|?C3 zNmy6Jjz)^Y;Fm;cfOq0|xv>iHdMdbg`(0sU28kS@3V%N=EgIV~uw#HqwpS~1gD?Dy z(kk;dqL88W>7JywDn&s|+F(Da;e<xl->tp@K6C~_&PNBEvC-`bypH%rQXY-<gM2<C zG2(Mx;-A`lBWJdSzq(H}hzNlhy86J76b7%rcC0U&@sg0&2Xv(_F2D~2qERPrxyI*U ztY9k}skd-?!J0;ZJUJC<r|J05xT4*tSHpwX&BXY!tjTU7-uIi$&*n~CdIoHP45?v< z8vJ}>7EnD;F{8e5<sOOkLnV#@8M+V|8u1<!h_0r(t4|y5x(6?_vJITBCqkn+`)aVA zsZ1yjV-BhUMT~R=USJ-h$zt>O+V`RC^ZdrwcmZ%~{L^39MZpRT$nO-G&ua=UdNm^o zeuedtnUwAslvMq>&X@F~DPMB`r(kLv@1%RE-F0zR?=z^!5u94euS#k&<1dKEo5CWU zTzB#-3+r1edcfcV9+~&cS5NA<G8L7%2D9PrUW0tp*kgU0*DhrmI{@dT3{x*-;#M2L zG$$*yUc1i&(JY3Zy=&95WCJJxdj02v*NVgRr)L&u{#@e)y2n*vOFf*NF!z&qG&<>? zB>O3v%tjygTq4Ddl_h(-8ACQ)FdqEigWdOz=ETmqy-HgiiF5_q9t$;rj#TsI+ZCY$ zdp0RPJJY?1))bSkdUf=-#o!*&iM~-3Gv&Q8xPmd+U2zT7s8mPv-JCMvRuvyjlUe$n z>T&6G+63eN^KRZq)P6996;Est#-T^N%%51smpctuY;{qs0jmzVIyi#Cwg}pG;%y;R zUSgypMwet%txRk&Sw7J}N);<MU<XY))Ww)#XO3JTYRBm{#(Tdmv34Pm;kZ|NE;;l= zoPKm`|B1DBTPb3l$l3S(iI(HM44t&|!u%Jnktc^q9%Fa8!)?<uV+_?>ztHn{xzz_0 z@@Xa(>D6_It-ftg%H?&6RkPv)EtMwmkI9Ldr(tIP$x;4T#cH$L7@NbQE&qsVgnOe7 z^UvXFbo^t_Lh+6Fa4XZ_vhHy{h~IfD1wrJUphNq2I6(%lDn)O9$yaex_MDWvZQdrq zV{6*gR!Z#&gZn|QE~Brzbi_mb$zXRVX7{jYl*-Fru96MpH%w^(kMZiva9lhqD8-H= z#B>oPz2wAB<0$OWWhH-af_oPDG4^L&0a>aLnW52fcZWV#QA0up#;AGjZa?Fkt>xz6 zS$VVuTH`xxc15Tn($B(NcF`{3YVPy!Idlg!_;M(H9uNKRJ|?ihYs0Z6?8u4M==04T z)1{^cTa*71%zZZpsrXih3}y6R7878;Go3apmk({sZ*+2keTp$f;%LB4mk)wgfuU@t zhq2Q}C`Yk%ok1#yUb-FL!hMYGzS<t%x0aHG5203YLwD*(FfM5j>w9bmLvUiee_D2R zO&xa#{{)6_lKt{Gfuf)(F+8vOE18PBzMKv)XeXr#;ob2noMX2_A^zbr5U?YgX}5oi zTlu44g8xR=DDI$8`A@DscyvWas)=LBm}PpZg7;o{wCy12!&5At|8#$ra9fGnFH~2b zkz8sVU|>I?L1YU?Ll+ZDuA=<^QtJ!4&msbDMu_QU%qkROsM#6P9bBe4>RSATwLO^& zCnSALUmCg00rJDv0O6BR<+$rgJ5*xyn;uOPT!@&D6V+f6h2RI_6OE`k(~=D7@Aqc& z>92gMUz6L<kN6lS8E)P{zDhDrCNxDy!zQ?I0L{6mS%ip-WNvWRCjArN`y7%Qkf@C& z(U`D<Flfi3S0jTO?i)ccm4x5;5K$;=(??0`0qP>w4qDR6{Ckj931J~f)M_6HKx9;u z<5$6hK;I|=@}IN@>Q-2bA|WS>MWR6L5&WI0AE73Les*NDr3FEsnEj1a*?_aWFOYSP zxdEl(C>5VX+#jaD4K<9T9#o-tE{}yPQ7#?@sfd_`UFs%wpG;EmD#~z+JC1{=j{6={ z1kAyS4x=l5TP-~~i7F%W4{~{OvyW?VEIt}McgD=1I%qwtbDxQEauccoTm$i=>Z1z{ ztWT<Y9Uy7yBu)<6$m&92Vg@BSt9q->voQFyMAveZ*E26oG(+c!N0O!q9Ys<oHyiO< zBF`V0q>qEno;2|pN*`Ul^gb_aVOZ;UVQUt-|DSBg6@{Ajgj(&YH52^24IqLi%La8% z6mIg~V_c*^=fHp883*^C<>LnRYYG7p;g3R!Qxbo(^sL6M1d9aN<$gb5P*sHMqL8dL zf{x_ZaNDMxGUDUXiTUCmEteA*(_DGEdp8fmbrRDqp-a;}?%wTqfYA&NfS{<_t4!4e zZsX`48Jw49d-8w>hiCW)hg2xMIT|(z`u~kM*hyKWz6sORLgg<}lCs31FN_R{uX`OJ zrT?*YFzhB}QOur@LMS1loNxg<9KF=r#Z*#;aFa$Ki-<{zVxPZ(qL(ZLJ0)Q#AQ<ys zzShr&gQ1C`D<XW<tpKPF&v3fV4m14(M-2omVidG}z#YH9tb3sRajJVc$Q!$%z<dSo zQMZ60H+3jsX1h`IN0xgVRee_}V-tNGNE~*xB{3kGj^b`UixmLdg*p8G149T;ai|m7 z)}{gVs}uEHxIm0Tkhebj#e>bkAzpQtQ>8``80Fv%c`%FDf_x8X9ptg#k)?N1>(6$_ z5vzBBD(m-I|1)nRlxJ4Xf_(=Xy!3r!d%a(9rO0(IHc&P?HTatCz=Su;Y?@+bNlnll zcH#FSo~D`yfKVJLlP*w89Q&?S4`bnRPtkH#1N|!HC)5%^Di_Zd11tEM8zzpPU|APj zNNEJ~s+N|y)`s^wztJ&Sh$1?M*wUJs1TC$WIF7<|t!69i2u$Zu3l{@ot<NU*To~Ja zora@&M^;jq4Tw~PssqZk$n)%h-Gg9~LDseB_IUgBxd}!xX*;*`)lFdVCJ$?T`|O4v zh7d8wy843VYm@@YLWhlU$KL*$KK}*FXt|6r`2vi;68Gc?t9aDosLqCEX7{UT)eSMb zkEu4Wt<2DL*K@1hsV-un9xzzG#s0(@>(`}KxEpG2)}0+TT|Up!$(~oZY68AeWrI&H zNiItir?C6;Vgv|GF2Bv)u1~m){d2WJ8-4FI{n$-P{6AxI0upxmZ|h^7s$Bn{?Ejws z@#?q69Xa4nrK1IlkDYiq%~I&SeBZT*oqqISdVfubQDP|0=0F&Q;Ia0&s+J}vYy>ti zS;yrN7q}%4OcsmX;N>=R&gX~gkrz(M`wJtyo=G*OfBT@{L(X%_{jSAtDnyH1rk;dh zG4<b5U&TAg6ONBPIC$K4?EXd9?QX73aj;`b$2ocXa-VI8sTI#A&!-IgO4aL!vV5|s zAoR<W79>^h)*)a|8(=&GCK+Iki6uKyN5L{C+B<)S)T73C6_~1nj{hyV%&byrl8H_u z%J)j96Dtp^8*pD>jGtDXR}V-<oQka1lnM>mTj1g05&0}#6}Ch@dfMd7Qo`RN2Rg5g zfSJwOXse?<w$=J-Pu0M|7&$u_^LrdxfO&r&pja_Dn#6bh+zRDV50-4G7=Ea{_3ERZ z5<SeP;I6D$1vAa_Fs>yGC}Q00w^hp|h>3fHjFVx7ssp}fb|F?<Z-egLHEM_KVhziH zIYVlUxhKM!!R!BM<)UyZ&PPV3_5ghm9^$EV!Yji~9FzLCWcI(TK2FbOhu#D6U!~ST zyMehaUdQ;mxF(id6oe84CCOE{E8k+uOyggD1}wSIY>qb<fs1%34y_G{Fc?AD<S-WF zJr*s-F2d{rI+gH@9q6#!%xx&pi4xLJ5wPDnfIt~O;DLi^jvgY(3UI&aHrYYohtynB zd_aj{&Ou-@RNDQ$E%<9v+lxb+2CjWfpCY|lwGbml5Z7M`SAp-<RlX6aW*Hth73mn~ zf-%u(2Y|YC(sBVlf3Cx3^Le09qGPh9b5D?>K?_EBnDU|_Cq&a?_`QsFBViA2!z>8x z$nr80uw(XO4v%c0j|kv05-mqz!oYEq(IT$oC+R~BfJw9^6W<Wt??`@z2iSdJ5kiCw z9KNF!{C9w}5P)Iqtof}(hSV(G7wtbc6K!kK8f1R<;h7PO5+<PmBEwxmkOW{vkT5zq zV^)+siE!CneAc9?A6b=#7#H=i;d>McVyOo}1oL@}f)1EUvxyR8mR$U1XkX)}wjrGs z>mII2Ac`{e#w?LJ4{Q-vGVDvF*10*U7zboH!ebkZHk4y*Q#@cW)kBdMLx(AwCy`=j zPhx;k|J);g%;BhAja_w_GYA~fQiO1bF;5&~JBEs*z%OyNJXID9NrR_)vOWjjI09fm zEa<55WbBYxkYNJ!ZgxNjfD(|@D7z<9T5|G=Hf+$=V0R~d&nHSeYW{sQjh}|Y2dKnH zlk8tk$0ct}^#z9kjcq49#%6Z=D?$6jDJ1Nn+yuKOH%JQJDT-^qJ(3WkBQgeM?oQL4 zFzfxlc6<l|H(`>j56Ai@vSFTjvj<swS5RTkJyBzA<d3Od@yR!v7n7d(*p7#!hBl%T z;9{r`9nDazKf!U_SM%h0>0XK5Yr6E3i8HM7rmDj|B^2{@6anO$@6FvG#55rv2{<^s zJJh}3F~JUn3UgMBd1VGC)@d0nwf-Veoz3YQ;w4J)j(v%Sqtk~?owUZwU=OXu3RjgD zUJu0(0%i3}Fey_BmM$KnVcoh6#VCj+B)+Rb5b(EM1Fr%_!DU5YrZ@j7IuTr%vp#0c z81DE>aKD?B_K0W17);>o?a5<)MoI+Kl$L$H`~I8p?gyN9X;=Ve%E>ErS4|AosRIZn z#cue>kU{D0SxO}VCq&?Q%voO!aykRo7~-KMOkX{_y#7!X^)^?s^A7G6B!vgt?dKn? zU;}DBCV9xjR{A-LgK#qN+`{5<E2y1|Us<}JZ9K~a{+*8SofuPGsuepA{Fj*hV7S!j zEm#nSk#wpmY#H*BX{3ZDJCjgpKyL)=rabMm*6Gvcnb$N>E6+)rmFMBO1bb&km-->S zKJyx+$4HrNaC-n_j<nPB{$`q5ZH3@NrOdP@-gojIQtwghO~SrdA|c<9pH+;-yKsE> zs9geweg@QVdP~{++ka7BG;tQzm|S?v?5~2Zd$@km4AnVJI350T<+nNVZiZsdnOGxG zYWeh0K)K43$sFsui{6wxTKAE1bNS@dg<0I`qLdo-Rn*csF;BZ+ItsjbEd$CY8|y^? zp~yj;5wuhI_TViBZHWZ(_KK49Dt&eH`GXJj9qw_Aj{X2U^-?gzU*hX`ovHH&xRyd( zesAVJdG)t@@4ycSOg`ax0v&-Tb4E>XyM8xs{$SN-O*zdmMLHG8&FvEFW!%6)VSHrH zx6t$obn$-MV-7?VJE6NM;urS>Dxb;+6_&wr-=T!<+a}jdbwLz}Gt-6K`!MpV+E>*a zdOfv{)6xDe?K+y88#SLj2F3;|C-J{XBVF}=`9p=(K$Xoc(b(4HuRquhw3#y6S=wit z{gste3URpY2ET}I)`{}=<G1`rzOveIjAhM&fqXlK7PFP0BE-O183m^dLk!7;m;sSF zF>^IXibJ{@*4~(6;aN@RLWhcuVg_Go7UW!$m@1R_K#-3eVT~vsgxm&G<>UvG7O=LM z3!iBI?2Qtu#?yZ3yXC91(ufU&|JLLlfd@FmIUnOp0r!z;rc8KqgFAb59WcZ*5_o)L z(4F6iK{j*iUtz?y)pR`(qWT$stc71UbvTU+MzD+MSUo4Pt1Ms`6J2u+(0w#pa0T#U z;eHD^rKUsI7`|iC5qd?{apaF}$BDk?d^0CDMh^x>dDyaScfFYL{yOz@p1Q2YTNz}Q zaixYN{AILOpRi#c?E%mM;)rrGFHS~Zw@U*T0LRB3q)$G*($WX;AA9=I!1Z!iCAOg! zM>vr&!{mbTjDqk7ZId>$3GCH{2iXs>v?ObjUA20nQ_9MgNDa(i9J3dMYTQE+&>IEA znhXQac30@sh8}=1f>8@>(mvRVg@E|KSYIjx^lU<fVw3nJtWp(rPzkcGVA_X&Num*) zCuXC*zl`L#kE!6m5$!mLw9OV@GadC1ViE?NBL@rW!oWOCXwg$+q<Dn|17PBS$=9q! z1e=Dxg6MXxA95vf4)Qu66u}G~q)eA?ejI>KwM-1Bj!gai`;Z{w1T!#{)4HcnI80J6 z<70yzK@(R%WTk@rwo@NdQLS3e7z5WvfTkO88ODw?k&XQg@C|r{W4{h=bA6uJbg-)e z>OeYm+^w;WODfeso8gn|1Q-Wjx#k>h^8jOF13cM%LFS5C*`SSA0%06CPaa12X{q&y ziLy*Hcpsy~spJDHhtK^+10p`~V{RwDca??6em<#0DRhD`>k$TnM_Xu;1dt(XvmqS< zuRX|5L;r0D6RHeTM*l1_T42wY39tj!Zm=NFfzMcZ34vdKuyoGUw)|KBK@bl${8~}j zXECu9`Cima7!WZ`nGla>G4T%wUcz2Nj`aF|Oxj8DPUGgFBJiL#=m5(GOV1`7)KR{@ z2m@`>T!3?e_XbKa*zZV})xpdK5H~!s$bR=DrdFX?1Be}k!xMUKI=*{+W*A_3)$3tw zakFo>G{F@syp1gi1fA({NpN${Z*C~3@!I8+;-6jw9;sTyMRDE(L|Z(9>uBw8!_>=- zA`-T+ew3+P*6Zr_G(N?4ZL~W}FNK`XMo5vt<&Mi0a=&zsgx|p1{`ae~vfR8DrgUKs z_)J1{e08O4h?k~Y(9a7Y(>&D*w>vnhh%OOa%*a-Qcc<_!UeGXU$cfq04dFRY1urU8 zB*CgLuVh<J4EWuNc=Wf65)on&MeQX!5&jI~Wm^_Y;G9B>Vy?i?V!4-j{62;f4~n7= zR5&=|1*+V{JqMQUo1uJJVaS@Hm#K?$G1Z;IkN02P%UIS?nSzeFj-IMI&3{vjXLB(3 zQ{i&SN2SNo;-wumB%d0O0kMav3E@)HcTp@t5s2ET>hPW%;{crjsx2<%)EX6)p}vNd z>-5v?E>shEk2UJ1ib*Q(F-kkg99zRDdt@VEBnBMhmY&^e@>6Yu6jSFbHFkG#1L6ED zj+D4N+(dg&X$bvz#iV8KbQ#tVoHW+`u)M0fXEXg&Rj7ypRHpT@m{bjG`ez+f$9NB} zx_(_^ASHeLcyo|E{0VEz`P=2|ag83X@jOT}g@muZjTA7qA`R)IT3XgAcrOuA7J<(i zO%2^0OFhA?8{B71yt2~xE<@~}8H{viL2V}C6NNc|RTJf%qMCz%=ci|>k5g8m7_cj& zpxTkDqPf{JoWN-Urm1!mF-+WQ5~Ll;;b!MIn=j(!+0zl`r^7U68vAiw#d7ntsR>LY zAYof|UOjKRb>^;RTu(Aa6CgjfiEpw-oK(Vu|D?Y4CqZ|wlZWd_u|E<sQIgTydeRJ1 zGRrWNy}ajc8$C-~LncYjJQrakymXLle+6?GY=B?^-5_z3Jp0X)_my)ybKw}$D>1#o zXP-l|fD~QW3n57GV=uz*cP%wsw6bLCgCm=|yC4}EA!8;moSo6A#7M8$rkcMD88lww zlZ@yuiBG)K8_KPKG2$yG?>)Tkvzl(Gc;Cm|hE?14powZEgZMn0{66ZLteO(Pu_^xB zyqa%|K;oS0#72t~PMAqp&(l4}Y5d@4?AW7g$f6x3UQ74}Q`Wp+t#Cd5;1KDfhNUr5 zgPM@OgyIjzaX!9J4D-kdZIn;imtdda{PDo|IFtV9;PZvep0}!7E6pe{SN})rU6&GO zLqwF^O<59$PU8OU<`=>Dpu$&_QLl!K8S8;bW@V1UlE|5M@a=KD!cQV>sV5VD=bJ6i znm~^Zp0<uC$Z={G{BgLX63rL%*eMO}7}5Pcg@euBve+#dosIx=Zq{tS@p5yNt~Ku9 zAX!?5KC=usonDve)Cc}^L3g3~S`*%SP-H3T#x}y5J93O0F-KLAI35^;z}5@l87%H; zc&p%Du>b;lZERMSuhqE~tno%ok!<}7wDk^f+Dy(Qd3B?o$Ip3kbU&VVYz3&CxTOgu z%^^F0cMBx5gF!zpTXn=ln^)hqn8vjSr*4=o@7Ufwz<C=<J7!mY{4cufljKqdDn7@O zli2q8>52#Fd1eJ~E6)FsLvE5{v|Hi>V8B?Tu+FC8>JZxhhRJ5NYK6;(aQp7cU~$=Y z)zgEbVAV|wka6xm#_5GmbQwJ%Dq?=DtmiUOJ|xk)A^9b9!AwmLH6zeA1DopqkId81 z{-dKHr8K9g%UFxBpX`R{Hsnn9If+aeWhvAqhOSy0pzGj*nQu+*P++==VPC*F<u(}C zSm%s6>3Y~t5zaUQgQ23AsG^B=3CVQA2{s9vbjozonK(@0$u;M5XaTB!(geEDfF1y- z1i1@U5+tf_<o-n$MP}LlzyWYU1>!9tz6ruCEJD0QI)tF}$oURz1Y@K|&7B*IA`Eai zEK&L76A<JW5WtHey;PXUdaL2shGJkoE-Bouuf_G;lc-M9MCf4&>j;p1I%aI-{Atj> zkyS{{N)Wk3&SNKpOCJX`E+2%aHo72(Al-!;r8b+Xm$BNL_+-yUfU2j>>4jq%YM_Z2 zJ5uKiX4m-iWd4VJVNizAIF*Zf72Ucilb9*EARvKd4W+blDqjLdg%mn3eN1tz;b^uV z7KEx-(Mt}INe)bZF%l;B0`Bg$oOG0YxUFF;xKA6nxk+FOw0LRBdb5IBCM`EJmI5v) zv$vH^<!>ZFIjn=9y3TuWj_FLAqAZtzMT<4iiK+u7Q!NR?G^t%k0jcom$&g7J7~vP0 z^Jk;n_1gZ?!uUpM5JA!C-dsnfp7&hD06|$j$`<wo&mYYf-%AVyI=hjqgAj;ot3a6P z#^X%E&|puDYSimk#NnKS?>V@c!j0Es4hQ6m+$Jq#r_<#|@XsgQK{lM<I29@QO$c?1 zZ~Ru~SVCa&2ni#dmI{~{lQcxPD$79X#WkvUn^`V1!>c3)LaagMia(d^*;R7@_bk3r z<b8IHS?Xtt;6{SvAJAUt(}Va_WJlnoMI5X&An<&q61_5G-QD`tCq`dDu!=v2$<rx1 zdnLMO4v?Fy1GvpK4#9P-b)XrQ7W8z{Qk3W?q+@MI2L4=|d@Oi%8(lF2^+1j&6#3{V zy(1CFf-9p{aV!D22}gOthjs!*t)$QQkB+}eHm0w_%S18YI8<i29>!}xuX_sP$<oEq zODH-Eu%k3Epm1?uV=w&b2+oc7b#q;&s;eg8Fv<o})B8d2YlL+@6)3y_IuOu$EZz1^ zgS!ki%P+(j^G@^w1gsq|T+^BO**zVRk!XAMdvTQQc!Y!MNQ3<QF!wO$_c$j2LInlp zIfD@Dp(qa(IzMA|YXCFEfndeC&btTj(B>39)~AR6lObe7iHOsU{_u^dA-G5k<9RC> z<6Z-q^FaJ{Jxy|$1>U6?L9Yd7P0TZu#F3%dR{xp@Nw451C({uXP456)>PbxG(f(-f zL07yLb9z^R4#|jI@HriZ5~IQ2Y_2@afoGFM!6y10SGeB}{LeXB8<k^BZuW5cQJ<FB zkJAmE?4qEtQ`OcS#ZyCL$Qj=>Fn^>v8LQ|(&bf#x^WzD5QY-6BwSgi$*njY7?uk=Z zJm>xf{~Cq-Y?NPj{gN6T;V|bvoPB7#*R;kf^qY<`A+WlFZ9Po?F70oAAD#7mjK$P* ztV~g4dvNalYX{CT`Z3t6T=M3iWSv30_if(0C9}(k;=OUWd6j5;Fsu%xa}i#N{dU>4 z2jY(ZZR4bP3{qp<iHE%8qst!@(BFpXrEn;7r;u5>N0BYBc<S<63=yOC*^n*AeYhZ_ zSHm-M)9}u{t7lm?)n_O-XHF&>bujy1u%|(6i~|hEHkwv5GJ;D)R`LYg^pD&&1~h+D zeJvG&|H0}|p^WuN`mFDmzgcS~#fa}@bWB|b9`7l}7tJdyC@Y{x-5nq~F*<du@O4G9 z3oRMsik>UKcVAuWj}Dq>auFUr3G49Gz3Z&WcMCe~M}o)Lq%3}hGRDvNxSXUMTTInr zG5eXaj0DoxSvfzUPNe10q1J!Cv-=tY@HrUdQSmYaMhR&tO<19Vz)PN|s99NAueaYI zm$k<ZeR?u#G3XBF6RtAIWGv+g*S{cMA!cOTmC<~ULk2dd(U0RjHP3S)a+Wp^qYLJf zmReBU%7y}X@}c7SBcUo~%!}P>nG4|{M;?NUlTk{0xE}g@9Iz>p4%>gUw8xG=SX`rc zObT?AZLUr73pDXd8;D5JrQooAG#)70Q-)swF^&1D@7RMvyNVHrP00|nYN-2C*&`qm zDEQKZ_B_%OqTL)c_T`anD|Njdg8f|UyXq}RhWS%rlRj?sfBl_Iz_MnZ14c*2DsJ>L zO?%(ZI<5+g!kY!jcLC9>ct>c4p9n(1B$WZ63)*=iE+#@TxE%ct5I>uWD-g}LNi9#Q zss+A_4ti!ZX~8rg4qS2gZpe)}i(g9PfVCIkLBjzLZZm+Kj>WU*Kq${fFF9$EcoZJC z_@U^OSu{7GJt2xk8<XMM_^8BDVRdh=KA8sl;r<1E836>?pW78u+@GG_N%GgO6asTY znl%94x4X_k4+4VqUxcdAhHi~0dw!Zhr?-q$M4}k{ZBWeM@P|6sba4$VXEDVicUGUf zZZ#jMHALLdUbj91kg2sEP4v^$$LKeW(4uJIQ%?7k7Q+PRw1&PCvurzHfw4^e?o=$q z>KMJ*N%QBL%YN{pl@<-z7fns%#>1th%LZ~<juwLS&cnIH!VBk6QRaW(EN5z)UI&h) z)-0XPz~qnwhP-d$z0K6~3eA_m;U^vHcKE%sVO|zwrK1l^KQMh7F^*bXjY|rq{qFu| z88YvKeGE*Z@dXK(GXtM>BgG~h`aBZIc#(jz0KJXzVl-re!}$P#UR-2N5~95~BA(;m zTvyOUz5{_)sT`%VO-aO`H-dtkPyrBDMr~kb0%QDi`@1T`rf;|g*352_!4Wf{@nl5g zR~gS>S55x?yZ{EJ#)vZeVMT&fd|zrkr10&wvudW#ANkLQ(#sjfGtaYSJ)n&6=l+A~ zKNDQ&+}%~p-M=nSVupZYRg9~t*lN`Q3UbqdL;&dvV0v?Jw*(xaPC6*zQpMbPQ?#h0 z(@vN%y(>?nbqDk7scmRl7RWFC3US31>PWYB$j)6WH~#SBgz^-6(O7q8zbS7FhX+=x zqPqJ^#3dQ&VSKjXPzBTbu_!b#lr#Ob<a`lty;Gg;^@<*zHH+M5X;7)rjuzQ{aS!z! zzTw_K_;7p3pt5=rR6<WDvYN2SxQKqJO>P|hUUlg;4>M~F<6Mh2&J9A5g>`w8R@Fk~ zUS=l5$=H0fSJ)SW+bXjg;(u*z%juq3j0}2G$TDeUGd0GfepRpLWXx=U@;-d}Y8N^s z28|R5{(Zhxjqlo$d)ML8=|b8l_i_iPKqI_bukehUP7rm~oyDs67JG9*|8(8cx#kDS zyPiYzrB*+VW)hBr2aZvGWmNZ=-|e_zU;6X)HK@Nxi<emW)o{!G+ne@3-T%{#(*Vb? zCC!fx_I-ZMoj{NRCd0zXDB8n#ne*bBE!7#GUgm4h)D=b$6RqTRaC!t&7+(I-rJfif z#(tay8zoI`>-4`S<aQIj8~BSPNY^ueu6&^hlG>mR8XB@S|E%})*{=HBf*e%`)+c-~ z_gjK@aX}}tMHGav_od7}FLU^4(zvc+bOgp0$p$`q17AE`s#&gx#~@hRQSWnZL^upT ztPfM~J6N|=t}k?o{nqXr3o`U5M({zkwCmQx{8K&0|2MHk#UDcvQ#DCHf~KRXYCa}M z#HD=gkJ+Hlmr)A^OOsRrOh9ny5qD&pKTBVZt)^SM%30GtsETRV%kf8ko{&b+N4r}> z@r~%I){{2;#i35sZI!bqT=gaQ`uooXMmt}=OFMtXBp4{oXj#JH`-cZ_K)XnT%D_9K zka@r?V|POwchP{MhSKjwyGk8fye@k7_S@U<hTm{b@tLu9ly6!ptKUywpN#^qt>n1c zJpR-6D&sD@*dzRvabQHEh?I39bZPk3%!%%DRS(?6`uA*-AB%W9Vsh+*fJR!fOAn|3 zeWnLiO12LKhKI;j$L(J@ceC5?-Pyu{B~s3tJGAO%P8;Cq)O=XIZN}1jA(XwJzF=C? z#btGRZk#g5WG|1SORvkWgYC3lRz5COkJi*kWKIoe&gvNLy|!TvVEiX1i+2EMMEhH$ zH5Weafo9M=&n@}q>@W;Mgr}iJ)j$O~*bA=at{c3x@@t$04C6IPwdQz;EP&oM*F1p3 z!O_iSKoc6``cMx8-z_*E$(`U~`uRf302WkW^9(v_jE{_?$+Eul7?)DaI1@4ywF>xN z!TiGU@A*!}FPK>6z>9n(5B4d`UZXigy<RN*<&A&k*}YAm^!y=gP;NV32L=O?DaeMh z-u)2r8}LI!q?X51upjuFy3yEVxZgt^?Dc{`w;qv3p?o$*xW8-QVf^Iv9jQHqHfEDl z4)I5M>6$9HtfY{Z3R)xaWHU-g8h+vZQ^?&zQE(!w2!#QtAeaAwWaI|R8rB%}SgOXN z&~5;qF$&-)CBvi!-2eu9^(50*Sz1Wguw%U%QE0m@;&3q7pB2cv0S{`~00l(p4-N;2 zo+G)C+L0Dws_7JM7PECQ65vn<G>cTULypj^qgd{31bY~cni`SWjsb1)eHOVOK~tji z&wy;L-U7;#r8B+~+@H8sT4zxS+S3Y=TeSq>DMIU*H(XOmn9}e?D8C5!gW;?`?jP{k zE>93>-I9qZAQ@l!I~rngK&c0kr)IaHa|WeM3-y}nRTPdCh&NH}<U&ylCmRgn3X%Se zOBw09Gz`Y-`6ux=jUDhaC}bMuV`&z{)sIgwIr1hK5HKPGPAg3r^b97_pUenb{Yrtd zhKinb9b(?V>n8m$p_Z}*0<Gr`N8?d;)Bzb-r#|Y1(VJjM^v%ckQG|80h${*#lM>nq z_Bk7)a{))O_b39Wa4ov)MAqEM!G~dFFu*<l9Dz~tfD9`g&g%Nq*#SObWNFd3*<4#% z!3>~#OPGl|^SvVwr%D!XDQ<2?x>xPT)aS%<B2`X*nST$s)a6AN^OMv@9rDX@c#1#c zlekW=J3-gsTvzVo@Ann&;~Egkfz_JKan=Lr2lB&zm;ZRd$dD0hw0IWFssdBxyCw0C zrA<A}p-8ewRbgHcOh0oq$YGbUpxflp^rgt@-2)@Qd?`ptZocV!Azl=SyB1od>tj~k zE!L|lj@OZ<Rx%voyfPLg*Vq~(1NzPOs9}eYJsrw{9+>Sx4CPz_!pRMWhQ<x-h^`1$ zDX}9%ORG{aH6X+&E1DX1`(Z7dK~KQRiC|}^ptoZEqqX<0{hwc~xsS`MkA2}a_9MgH z&4^Itr<+`Z*Ao+Pd>xO6zApNWp?H9B-HU6ifBdd)6^7DEXduG;xWm$)2nm;f-3UX+ zs1wDi!3-!@Ox(ys!_)z5gyGMLJNRRC%;7%diIX0_T7ZyiBXXzWYA43KnyHYY+;84y z{43($0GJSq8GQFwoWmG#dtgAJxGVHhfnx=4oYA4Xov)c-^>&kT;ZG4tC_Dv4^%&`d zk)?&dIVeW04WVm1xkl11dc@}(MlSMgPlge42QYK?E6IfYZ4Wtjw#88abhLT)I@PoF z9-cislkyCw*SZ<L-|x4_KCNJ#stOdXLVpyFyb|lXwvjU*+Wu5^68gYe?w_mg(T-W* zyRneL(*cISgBRz~CV_ip;Q9I+YnhFEQ2{Smr^-o$oDHEVglR!?<;ld{(HlD^3p<ES zLVAb*EAz-gb7Y{lOoF(RIC>f^8lxCz-DSYlax;&t=E7|Y0d@?>Kugv-R0L^)b;_HC z=8G_1g^d~-8_1jf9gzC>5*v@CGGvI()dslWkvch(Q*kgK**C1&2r$7YrjSaSE^csp zi1CZHYe0go?ozhEUH6W4PBJ*My+qbf5-bl>Fy;5(NK=gS^6jSKU;8c<Z8*lTvv_VX zZ>`lq=-{;H&W@j$&Kj?NxL{<JC~hj~JG^3d+psDS*n{gd^<ZyJRrQL}j=f`U;I+JU z8GcuiME_Hec3qMsf68$%=#c16@gXc}XQ`i??rpbzP;1F}^{H=}>2JteY?2=M_U)oz zTz=f6lP`_8Ngm97AA2<H6)xGtNog`m5#hJ0lK%)^AozSQv)287UpW0)yK<xHZ;0HR zJ*UBRgEzz<QVF9E8qc0jJEL>t)7xX6h&YqLvO=l|Cv<=GS8ImrjH4C}*p=by@VAwm z0Op9)f}2IZl^t17Cs4BGzl^5_jq6UG+aK`#I5w3Vwb&3c`Rc&<gz@&R6MaI{UvKRL zk@yBmh*8LFC&}M@%i~gRBwl^9qQAN!TkP40sY=Rh;$93r?<gKk#5(NdXZYR1WO_yA zscy0qMNvMkMN9o~LJ~D72F8W+Hj<+atUrr?r<g)h+#;8Tu4w<yU2rf@8>SjKhuMs| z8jGo7G+tI<)kfFGBeXB;F9(d7F)w`qi`&1J&IQj6qBp_q{yV0wxX97n!i<bn?NPJ6 z)74L#hCyDI?OK>@N+Av-5GW6S0&Cc6&Fx?59XW7r=#5;gntM0GiPec&6<xIgySCIM zT*LVkHYvBojpiS(<D<IA*~|#6{<TN;{s6i+v#~Xo<*9(@Fj5>v=uTGg{>YDq3EjvH zX-De|Uk9Z~WSqZ-1e{@A)&aCJ{4-sLHl3m#4NoT<h)fzqc@Bf;wt$nvj0D6yMlHZ` zoS*KAK`v40qox(okVO!zF85B6qN`Ju7ilq#G5WOy7&cT1(oT*(Qde>O^qU$oO@Ve2 zU<sCPunva-U2`{XEYtyng<)?#4`}`?=(W{ByU7P(W1<5+5=Oq&89R!WEeBU`64kqH zE|@Tcqv&s{WrE~i7tJ~H0v$I|rig@l7l7|X<Z4<>6Bi6ZZJ0Qu@LB9FW)K0#7KJ$} zq;g$?<ATwiDC1vHKh&bDf)&Em-XP_|1{Kmj^Ld(-t{5|+DFdkupvu!+MYiD@{Gc3` zz_2Y}x*m3TlS^<C<RON!2H%yr$Q5>+ump)Q!qrax{a&1F?z))PvqkX8W0@gtJcABO zvpPHjMrBB$AaQJHzH>lM@giTHI~zfCI9muDFB!nxHCTBwOP|hm40QcoY|m2PU|OP9 z955$iHsC^>irgGLDYnyw1wDm!yx9n6_^fy%Y2I-cliqszxGKm6fVKk;gw_TRJ*?x@ z`Yy&eMB5oo+D3p+pc4jv496JOxzv`%Cmy?~E@P~=!isN!X%4D?1`5EzeOiTALniyV zIC}t#c!Q7!n}iQ^cTL+<wj6&T`aHR5(Mk2adF)gvF{-k?C%@Fa;QiUd7%}Eh?y#nZ zZ_C*xsUhRifC@$Yp<t;Iat5J@<|%9Tm=>~AI>0r<lf|C?<l)Y!zP3mGca$sTXKBp= z`)+fpiGfHgjh}$GCRLv)Id;2c6&pe0)~vaH(|GoH`=e`dbWag`1h=0Jkcr@(a=iz> z=hfWwBkB9bISI5b{AKX38eIeHzNz^7;0V<yaSOUbsm(R((bIu=2AzO=Q3v{@mnQ>3 z(jXJSPx@~KFWrT8X$N5d+N$C6-o5tE{k{rm{UL;;j#p|13nLeof0}mD=#=_~P8`;r zf8bJ)sRk717zvFfXW-0g&9dH%lRrlsRo3}&{<bIVlrH9H7u7dMIB;?2-ss`NA=w%w z&R`A-p}_c0ry$AI@1DeI<Y$)QGg|2uav-4x3s%L?f9|XP_J!GDeBX8WlP?K|@!&RP zzpN33GDc5*ek)aF#_bcW3EO>ClJvfVlNK_+A(J=HSRp8<@n{AiuBt7u|6`n-D|V07 z%EYk4hYlcZJXlPs06T2#?3T!(YAn5AVt(dR=RbP7^1~Cc1P&69jOmSHSG8{}PFysG zwu$NH77PO+prg)1J6B#BeAOVDW3Jgi)cBF4a-mO!(OwAXQ%@W)KJYo1kFXwcJ`L|` zJ(!?>{cY8z<V8VyT@Vso9PnqQ8xTE&sw$_h1Y0v{CHuwq>kqYHN$<C`EIWA}dNI|j z7#+Ay5VBhqb7Sj*u%#H{`0d~)Es<MzA}WVS`@ZHgjh7k09_Y@%M@&lkj(m>phNL9` z)F@rZ8`dH-=cRo2uZgSlTrKzXLNpSco{cE^lJzY}Aq?h&_vD9fkwxL@;q4CL;nv<J zL_})Q>nAND)WH~|RANA@Ow67%|LpI^tq^r!f8kILFgJdHEektoCL;q4JsTm5#-N^T zwpgMHTZ^{8w-IcK9OOM96?_-yV&Kr}M8mi9*ulThQm%hMU-*?v&+R+>u^l2-*E1<m z+2gqClCHxPrM*kMP;DEx`>pz7|1)T~f@Y6(KH|JT6`Xp#W_Oj*1UL81?tyjh4)&MA zl^xeK|EBP({|iuvuXP5eqq3xot=a9`W>=;xThm?r6a7zN-j#_#hxMtCMJ%gT=$`?v zwQr`&dlURW=vm%yFE*SO<wQr?DNaA{uCm`Qg_Kn_m3Dk5sY~9}jRPG!(fH8${u8uY zBA5Q-^~va;eWyBHkKye?jo0Q>>~#5s#E9&eX4mH5Yb6h>S5$`vEq~C!;=CzZ@a4tr zXkTtYFNokG0(!|0KXTA(siYP%BRKQ#{hOnz61FO-W*L33q9WH{O(Hd()=))_sM>S& zTZ-6-bEllA+Us+$ta-&@N-FH*z^)~w)x~4dN8;x<edWgzXlduzbC_(sjq4i2KB3R` z?^y}M+bEx1H%`pehR>CY(XSVN_5g{Va4ro-OTH9zFTSgJ9?}==>9C|0lcFA;3bG~y zkNIg6$`k;l7vPtTdw%xd6a@S@7?Fk`7<Hest2LjrNFs#T8NnPi_s~ML&jOHH*@8sb z?*@>;^b#HvZ`54}l>wNPkY8zG?fM7Z<&CXMc701N?rfhqhwIO7NUL*PiM<nnj}BQu zjGE46tzOV`9KJz#?ty71dR686G#&@x?_F;<ruSmP13&rv44)9Mr>}7uh-YNBA`G=6 z`XE(979*~twS&{wi8kxprc=0x&{f*u6pi(S*+<|((j6XO4Xr4kGbm`kBrPQFWZ>Fe zut7m{s|dn0<h=lS0Z4UNfZt<!)_{n~b;0upcl?;Z1aQ(IHTPnm5MP;1H0VIgSx&_a z>0db5o}>=*$xR5Fb`+uc(MP9!n9$2=xnSbT1lU;c8uq2uIU<)HVulUR`CiG6Ur+si zakCZ@qewsMPk7(>EB=b|6qM(Q9Ms2fFGu$&Mvehii6vW8P!Jnx6jn&EfI$gv3sk27 zg^eA6R%L^(4b&WiaX>bpgEwQ$Ett6j0VAI7p!vKWG-f;-5(AMZfZ)Cmfry!lOo)4$ zElJk`*_MG9vNz|=h{3ee`q$J7iX}^WCvuh5B~Vwm>z=|54xBv58>Ds^g|D9x&Yu-% z$?2_Q**GZP;lOeR2B!})FU*&ImJM()B_sY6aM7urE9b!HmxeSlxtuT@oEKwUSctLu zY=q-7K+tI4(N>CLNWMsl1r8Mt{ENaRIDswTJD~oqmYQW-LKEnoqGj2V5i}jlIoRSB zC}0?aX93$(%*=;%b)NB&fL6y%%L3~F-(vF5cvl*Wfdnn45#+$mWH^Hxw{2mVZhCeV zj55g_!h2E)O{0e+w1q*j&`NUXKOcnE5-c@PEcs!eU5^7W=I@qHP72!p`PCDC58V!U z;y=;S@Z!z3Z+j+mJK8g-aI-}9ecSYX&fGyD_=n%2tmU(4vB4FYAC7I23prW4pMotd z#a;F4s)fT^#^o2YvE!tE!&C3Kn)<S;Ik6G-nD=722l$YC%kJjV|FmW=51r@{%kCqn z!eAK-q1?hXaueLCy}91y<Mrd7(>NOkMy|w1>ZKr>jd58%`52DbKt?m##Wms6!S4lK z>*@)jdzJdh_HQR|UiwGtmtQ!<@SaaU<u?I^je-!^%L+#Jsh{8s?9Gj+J=K@e!kpOX ziMAcz#G<c}Yh7(qRxrf|bP~-8^FH=v@cNB8@?Qv>#PR^;)bc~vOg3dqtNjMl8G)<7 zwA@Uz?dhcghwPYXvTm3@CK-JmexGcky~1DtcZVp*Y@+p-U$9JZHGy~tICxO^5pyeL z*qrS3VN0;7dYhUDE*mGibZ6HQUX-rQMddPG?Wh1~*4F_D8XZ{lbBvLIc<d2ma4o2` z#*lLAp2X{Ui-JdS=ArIn3l<QrMH`3Q*|uTCp6KL&@o@lSO&oDYQ^RsYBoXuhT;k0Q z0@cX||4Sx-s4SN>F_uZF3Bho$;PMc|69Ifvi!{7!O%+AtQPEnZqA&_Xu*pAe6Axk7 zjC+?XIW*GvnE?jy>Iaa`RLlx=A7+UawPCvYxMxX*lZ6O*brWMG*AtwNMbo#N0$}#H zX21aB%3Iqi#@pgX%=p_?X6l4c*>FETV7>&Ax0Di&f%>z7;ALNOMyx&_{rV0m%XBa? zW|+oA&YqK^mIEj8@vw~XM*8sVfj6U9jn%0fJ3#BVVKF*E%3#Iq*W!`LET!YGi;R!B zOkLcL5<j?)eTdT~Rm}P;b)u#n@*6ANdWc7C?cKt-C`sV0$=67^#BFFCxkTNq#!=DC zq+PYA1fn&b>t~&RY1H<G((O&$Yes4H?XC#3(P=EMS-oz?yAu(yMl<S<T^jK|)BR}* z^z7CD3$41=PO{)s{pz1g4<(w8^PY!bHla90@6U<3?Dyqwf3P0$K8j;_j`vPYr;jsX zYA{yEzYbNI%0-?(?)5+Ug#*1^658@Z;A2j-KMY>M2{#UZ^Q48pI-&S)*89VfoetBF zCiv-I_vpQOwc!)3!$m6qv81%%;&6O~o0$Q4wM)Hut4-#-P19aIgqywWo2Am%ptNeB z)y?KO5$viv8Xa{Zb;kkLh-*y_ONVsuTEs}_q;ZodTNlF!T+54^nt-*d4j%ni0gYAg z7nOV3uGX&BPYb2c%NG)O)vFE{Z>X@^;5K~?%81Fr`I+NN@n8e!lbwFy6D#Xw&|_H> zR*0%2Qbb9uZ~X=*F-;Vl5me2~Onsb8;^T3k_4^rrP|R*e!Fu(D=F0HHl(SXhgXmZt zL$*2?B8nca@IfS>iA@WeE3oYQ0qtjV)}bs&{Xb6cMX<j$C$0YuQqsw(u+Gz>R5A*> ziztWHWv!fbP&KcGSEeb5AQ~h#&wU;f;O-?$a(Sc)&BoA56%o3V2;^B3LgD{!N8t=h zRb)7D^q_Jb!hXXnyV;ft-^q2r>}~NfA0^a~oejTBvvh`-Ce#C}F!BG0dK0jy>-GH~ z2vW2nkn~h6o)`jA@q`{1L<UOFIEW2{C`urel98H8kYd0fRxagC3?PU6${?E}E@@VZ z3RxBoSjeKLM@3~vWk=ST{;&7+yRQFreU~yEW<K+NKg<2x_x+%N!Ijd}TcaBSK6K8) zvx+sBt#qg9GWMm4B*(Hb(cW2s3VP<KZSVli1Bk{&C??1<hM+UueFxAqbA}%I6nAsg zb$PJN)qgYutT0;i_ZFAP%n5Ok!0E;>3&e-!Xqv%NTGqgjV;PrK3F_~{o&Eni^xi+D z{n}+yi~y#kOfP|LFRPQM^1x~40j|<UL`@-Fx~K;#%)lr`Z9yea8E_KN$1{i34TABl z&<tc)e%gL3KK1HS7HpIYqL+==A+7fgQU4aB?=1(YBTgjh8IiZ8oBO2JGN<J+AP`Ca ze}?$IJhWA=R?i&HJ}TVJ=WAvdZ!zDN@qI#r=JUXKb$_)Hl8+EqS9<easv)*N`D3@c zEgS(Y8Yrz2NlNT<V!3R=Av|;<%-<~=KFjDf21Sx)&_h<pCLKMpFDF??yYwEbLK<=w zvOld=ed9{+)Ga@kIva17^zcoJZ+o?_z*seWtuHC+Z~m`*>Xf>Wfoa|ISMq|y$s-Xf z%N_n7t@MqD&fgu~_phXmVd-nMaMWB)1s|2P{JbFSH>uaGUJg`Yob9D$nZZMEE?d;S z@FTf{oqw~;P|<Pv-26|OnLwNA{o~B<bBJP_6ZTKTE2L9$A`CI<&5glQU$!`$50CEY zePh{+%Tf<Knd|d=kE;0i{7XNk-ujPm_v+7veP9YXee1KR%b2+By41zEjUzHu`&C%x ztm`|J|EF=hHsidQ50oU{NE<2XY#E$i><@uYZ@lx;ri%wYSl`;v({Lim>(D>`ER}yU zcdyWz-9g&Z8d^U#uJ|9~-NjXWko}Lc8a&Q5>kJ<sTN7+|Q?oB(&+rCa6tg8V=`{*; zzUsiy3iUAh5OMX6XsN_zTq&M;2BgMDoKWCwF}Qj1hY<X&d>=0@>0RX_3+KR|R$wzT z%#Z~6d6|2T1<P858#3}Vw)+e=<eZW=6yUhSev&F6;MU2JtofE@E_&))I8s?$13Q`D zN)6?u2Ch^;cFN;zNMl)w9Dmq+O|bF;#=MiBT1R7U64{Nn<lLMWOAxpWek)boHN=0l zqD+?M7p~nSbR$=T@M_e`-G|)Gv`E;U*<jxKY9qOtb}G0gKHW->_P1C_HDv>>wvP5n z+;JRJP`2=bGN3MtOSByOa@9xW{)@KZ`RL)jFJ*&U){;f`_P*X1))Xn$OS6!c!>h!> zPG2-f-yAgN2K4*R$J>jx{%8KPlP>v28NbAU^HzS^m28`lAyeq78vX9Xk9`+DsJ|2z zzHQ%rpDiCL-~<voiceIOrQB-%Ja6!~@nz5dG%(S&TzKGD-3@JxOg4IKl`gGrIJaX( z%Cl}{z<rERKvjJn&gpm*m{Aq+eMz=8jv<0X61%VDt8K?lq)H9U&U@eJHhz9w;qb{f z=@ayBcu|JF(Hw6lYm86-Dt>9=l3%*-VCMnrlR*Ab%TD7p%daEY2qfUzA8X@6Q@qc8 zjET6p$oj_ZZ!PM5K0)5S=E<De1b@qcB&Wa3{6Hskk%E&meQHD1u1M?t6FW;T4S!fL zrnAA&(($mre)(17FBlML5h;YbseLC6e)?efmw&GRK^tyL{bl{C_SSP9u^&69dihJ@ z925UJ;-B>U9F<Mns*b+@$s4QJrVW7JQBo8=hF^78w){{`MLOkDCcMn4$smTE%;`hu z7rsnhAQeJDhQCwNf0~V{rhCz=7sdLD{`3XDhYzL?uU54jV9+2twPzp2yQ7(}ra#7H zH>g9y2{!xPNnqR!&U~bOalhS&Dm3<7x4}jBxR}!uBI<Hzj_%4MbQ)=Vfj^&E`tbiU ze*RPMdaTY4+{)8L9O*o->WTgq&kr%3yH>s|r}upq94N8sU;o{JZsg6Zzthh$@?qs- z_JU3B?R;>kJW$PAFJn)}mCyOz8F2Ab=Z*kM28xC#W3mDojUH56_$#}v<ZucJ&RDXq zpo*5^ic9u@WTYHYG3I#j<)N4m<2trcaZ3ncZ3VP77#F7*R_1!c;xU_Ph;mwI`VZ_R z@}1kjhN)inUiTg-p=Eb!s9a27@Nu1`j?2YOPp_KMk~9A9TBMDqa<K4I{$>g-g7Bq! zjOQcRFN>24FeMPR>TWl!u!V-Rf<s26AWvgpaPDCHJVfiA?&fP?k9sGhVl&iKw;NOo z?GygAWu9VZ@T!rDfXqRUd2U3aw*BaPGO%y{Rcr<pJSDQ8ndUs`Hb}A?g+~)f6aUD5 z1|I_%KAWj19W*Z?IzGx^8#~Kac}%pWD@Eg#!$VC^Wo^ZIZOU#RYH{(&#PZ{6YFh5y z3vOLOmcUFxNz<~tfnh5)-flQkVYtamWMQ0yI?OE#g3_g=$V^u+M*jKYCGBOW*uHXz z!hKh(8P+gWV!y^Ry{lJ%H78(gTtxe?UdbmX)UikXg7ZcHh2oC$F)?s4-BX#rxrAo* zTV-jM-y;PRD8>x;a3zp@6rXDHq{d;?*rDl9y*kmxGcN!!Q0!%3gGmcE-CL1qC^#Cy z%W2k9%rg=niH?kZf7|S|g0|qqlC2GAZZZ$3nh}*yHZr%Z>`XQzPt)$slF;ha4%LtT z9T6Hf67IAX;734C^(DQ<OTH;AI2iY9SD*7a?P9)A>Y+;SpN&;r=esuax}2e{&@G7l zrscCfccURcM%9q<yX?No=5~BcVk$`GP|JcfkJ>snE@}2q{XFM>yx6puW?%<skz4Y4 zsdV_<S)j&Hqpjm4_CfGnk=b0*I;-72i;bKqdR1Mge%Yhk_unb+s(+m)w4g7o+znRQ z;`aK{sfL%NQiC_s-BtWq&+@F%G5L28*nfPH`3Qxk_}gq8cTVoBI#ur6$>26iKj8l4 zqmJ@5vu$?HwxhQD=M2G6IJVx|>Q)%NyvhV+Nw3xBbwwPd4*T>3F{trOk%WK6EbxO; z-T}AU^PxPZ^6+ul@vUL?%MJCnd|U9jYB*stc!RR+=c((P%9*r4R;@*sT=Jy&#2C;O z-K`tJ1kY&=a0qUEF&Z-GCCyGreX~L`LElT!<nu5f;I+(uS9~bjPRy62S9u*`2AFeV z;REMVO+%q<qyp4I@7IB~k^45MJ(hMD6kmWx88n|^0YpxvUYMkkCc^~^vL$#K>qxfS z$y}YH>~-b-@TQf7HIosW|D18sJ^<X@JazI}x6FkIZin2p0pnh5!l0Te4u3XK*D%!Z z5TFi@GUtly*D7UM)MTheBs#=~qS4igg7XJ9#Z<u_-z}86P+$6T#**Vl`r#MXy1#l+ z?l_&1Y)+2aI}CJWiJuj-=?b3`XKIOV+E2C!kZ)rryvsWV9Sg>Bc8UM%7??2C@HY>v z4~E~NPN}qK39r*SgaffsR2GV}u&^vyAxLo^X7Ot*--tr(jm9r0cX2aBlfL5W!IX}< z4LhpRE>kfKWoXIjup@Gw`^CSz$(UOFR=q!4DRE>m_LSBRt{d67@`KDz_PzAIhC4XT zc&$wAKPZ#p3X*L-TC#i5lGO)GTOQBZ*<Y!!ZSDGC#e^Z)SoElJ*SdW_2FoM=t9n`$ zz3KVU8Bp@GKRss+W_A=k(ZkM7pR1hC|GRt74TGKHR3!EPQ9|*QC3jrX``?O)nSbIA zuAHc}z4k5%Py>N%79<olBJ>{JzFx8se{zoQ(db)^`%1&vToO>@+nqTj^=S0Ofoemx zac+xdL>pS^>{zyT!R&`ib-`WV#D9DdW9QdQZE?)q@k>`oIq&iMmA8J|-YD=<rV62s zV_s6bHH7Xt?~-``K)|O<1|=!{=Ib)ar&GrvtK$n5teY~0(L1TCWYe!-!sGG1SmX}| z`Ii~5zH#b3&2HzhahrCQ<Uh%LBAB~9wIh8;H#u+Z84|8@8qcFk*W)+WSh)0yWnz2O z@u1-;>B@IEz`MG_PHy{^xeV`n-Sa97&C#lgBVFxm_)hGxUz(B+ng!0W!hPSl>2t1V zmZqG6;2n{zk*IEd8?RNq?fvX*h3~M9;Sj-1<Dy>bQ9~U%b3k?G_)~8h8W|U}s`U>N zw8K)@YhO976*>-)1dpfxuK2g<P6*>s7As7HDAuDue4m%ee@0}#@{1XFVLdG{>m6(} zu4CFdi{+9|kySx!?GiG4l2#Az$-Lal76P9$1ET&E+lgQlTFh<jh2E13uIeGIBF~d{ z(*WQw`7oXUwic4p$Qc8D-1%@^v(0cz?az33@o3p_^zsHW5IvgoNdU-P&e)<g1XW>& z@pl2RaPwbgS-gG&OkK(5I`Np#BNM%yj;=Etq5`QAa~th0hTD>K5NOE6>3SdilrBCN z81e0sWL1Dbt>SJ%#{BA2DZ3hS<<fYfVKMqW<N<;o%w-m)%<;5mu?*pd))|IZN^&d_ z!f;mp5X|&ExQigdCdUrWJM}LJ@7*A!LthoYq`R8;+G^n~jW5+v-*^Kha}h@>tWT1K zZ-|7n8KF&XJ+$wX-J>OI=s5GPh)?<P-%$iK3td^3gE5Nrl)mweC2TTkL~#lihP8+i z;vJZ$Sd}KoDW{Zh6b*M+t<XEAlaln5)RS-$2p!`<h=o2d7i})&H#Fz!#niY?$W^jr z-61hS<|xC2TFCWfc6Y>@2|uu-bharePqCvqOJN*0=Iw1Fn=wyS@8W4&Nb3140+*HC zl%T+Hw1pi~1z?QFU$fkA<?#F`>u$KH$3L`zCx<NPVe5&VTUIB0^W*60o{mPfl%iWT zwRy(P--u_Yk2ea);LeTO`sYT^JdT?J=CO%q^JDmg!Ajp)L*Dt##VZGYTYRq!<?tB+ zm)yNf+!iXn%c}eD4Sr$mbE)nSkDQupi}ZA(bN5Hb>nqh#-?@#wE=Kr5s*yL(zjftU z+oxA;Z(i(PbLoduGRZbd8Rw3MqRE379_*56Dz6;^>-0Pmkap$R+2>jNNc#Hx_XoTF zGHZ5q4d2nQbI<g9Jw~Rk8xcc<?hoB~PxZx(yR%Z{)1}uKa&~&Wq`ZB6&6_rROI>#u zS3g|x=HUGYt6EZQzUSN2N{7~k52$@#Y+r4yw)Px7>!NB<pS|#MQ(cb6nZ%c$XT9;{ zmduYkjyXLX36-T_N#Ub9uRR}nX=2%jC$mwgINxfaWE6gxf1aNw**qA-#KgFgh<JAO zJS1J~Sagg(f{%(TeLSQ5g-XwNI}+NCuDr0f?`uZ!-UlUdw-N%r@9EcgF~}6g9Sx1z z3u7z4@hP8mp@s!Z5^BYGI1hBGK<ZXbQ9(9>*O}EEVi%IC_s8QA>d<cYo4kX@91G2G zG~PVb%|VvgSiwuamS3P{!drwrc58CRTx3RrWF2PO5+5z~7##JLRR8!7G%Im$g=~?N zd>Ac8NHm_c$Tr5jtKx{r1GVrILqzHQE%t(c>}u7fe4dNRYRcG#kv>jhnESLTE=;(D zX~Beds4DlSD@#*$NeT|}gt_u}%otiS%xgS6S`lV_*2~29>no&g`5JNAQ0(d9D2rFr zcpfy_PqarC)L)Zgb@&K(14c~FDepD4tvUOxY|E)waII|XzN#cI>;FcE<5T%#l~`oN z4h|)>u|;M`H!9$^Sf7yvGc`Zlnv+XLhmR--P)wVqm%HiTy8B{x++SupXXItqbRgns z$+wHABYE=2*%SD2nGe4)GT(S(MYgnOR-}DW!wT@QdGtC}k+Serf0@BvFpe9I?rJ{! zYR2JmADSA@P;=t2Va}jpWXaaZ@UEu(ZTpTrJvh1ECrv+c>1h4AlU|_<wk$14dlMlg z7zAxb$v<Y~i7L!^{LEvUU$@zOwQ<e4noal0P7_i`e(aqZaJ?5ilpf|uL8RAfO`abh zmsZ@RCG&Y$l@M`n!JOY_dxfoEfkG6^^}C5&FJy1S6@BmbD?A1Lbc#0YBC<rRW3$3m zjd^Y8MtAL#pt7zLx}x`k6k7_*+0tk1S*WQzkrfx=lsLP6Nj!uk6qO>17&I4Z*PhnU zLof_#i}b}AJL|OW<%^qD`Q^0A)ZOg3>|vYUf~C0~Nn%H}m|Um>I!EKX%2su)&RbAm z$Oiytj@M)uq#DSN`#CW?g@s^q(Sm%VM4A$4^j2jCVnu*Ml6JQ{55jLumT^td2Q&I( zLl8kA<iM(kF*`KfbR|v>*aH-sg>K3-b_VRIJpKwG?WTj}O@EdLKmA1KRC!5&szWWS zw>K2Iq{(snnKR@=f(rNC-^{{98mH#agIgb1OYb|LPGg?-2Xw4cXN#J2qOxtjqY*D( zHj^y6$~iMA=`krL)TGL~`1i)T46~2yV7+5Vf3x<;N<n`4T1G`k9V^S^qET6+sui3q zt!hS9TBTNsyFs1PdljZt_p9^^sj?t(iF-v7^&#B}A}{k0I(g$b=K=hhqfG3bP~-9Z zr=U#<`6#Xjpt4}TLRs1z4}imtzY?Fzm_@PY(3iX6H^C@|VA*lFa5J9b&}*s$XOn%1 zdWlZVY(kX`l0@Y|T^{de?bg|*LK<Gh#bMqjEVGzaJ|nt3=9Izo<9Yn<25mBACV0_I zN_|Qui+nQ#ugBCZ1w;;E1BUD=`NighKAaA{nC!9Fs?`i`5O%pG>ZR$IkfmIGs_3K` z01matvU=fLt&N?qdB5aPut85+n^`#onMeo@6JnN0;5utOlbxwVa?zD8++2-wkRO|e z?o_`5u*P$xDHs_DN`NfrZI&GXX3p7bTc}D(w#GBNQN$NKE2N&@W+|W1;`;_90C*-( zCS<l0I7OMNcJq3?w=uxmijI>H8|RkhKYMCtk(BC*408P?<_0GnQt|b16zCbbi;nub zXbO&}8`9<I78L;u55~kOW*7~1(Qvmbq*bt;Xoe98%SEFV;jYdzy>eFX)rkvgpM1E( zFh7`7P9D9L(RbpP#l~xgP?uq7(;)yyouCotKKx0#&e22hX#WuJD%1xjb=B<?2aOZU zo42l@y7H3xs`^#^HRs#41HYeDq)VgUXMIg+DU(z|FZlQB-$!IBy{s-zb0rn?kr?^v z#Xp>qmo63*?oVos|2P}4xf;TG#v!LK<6+|oZPuxy{<*is_t&33w7V&D&5H8-J9m9} zbj>-<(vnZ(S<sj*t3MGs_{M|rik;UpCw^0x`lsmkI6)0@kDbQ!xO9E89}<-wDN2ld zpb@;vMtxQ8rvC6A?l4;%RL$Nk=ZZXKCyR=^>woiB>^`<p^6fdb$_0+<z|`_s_tD?O z>J4iVs9sdwxuxeT7Y3i7{_@&iW|tm}B`WGAsW$@GRLEXK)aCH?))*;_<nl4Ymm!Fq zPXearXP{HU3q~H+Is2RN-3K2rDscEn3@9GjoqzYS?={eB2W^-SPS>a+A1gf1%*&kd zT2Z6(MA!;!)b={Be^{3^Lsfh_tumF3BM3roWW{IvPjUb3=dXM3AOK_wYGC?`FV;*k zM#<c6Q#@{wz(+TBWO1vSgI>YgaULfy+R-V3(?W0g+@+Whv^H0{Dd`OQ^C}MuJj#sB zp2hzLXp>)*J7>aZBlJ0nO{hgRS+1nA0fds35bK3o0YEJ)lX5HxKdwL>kl{poIo1Z~ zSdz}l?Vjy_l6})F+@J4kD6ApfO3?G{nZjJc{3EFD8sOy3djExZUo1>FGggarIf79T z##VWXP!*Sa3@QOos3^p5x)|snL$s?@;jtBoGrF&ZTjF{peq)%5lFK|jI6lKU%YU|w zC+Y;+ZaP+fe?EyxRC3fpx5&2cYj&P;@ToFDwW({TwcXx=)mll}(*-`x?GI-fOQ0nM z=G7%RjBdoa_<x<!rRP#zMtY#{Z@!Rtwrky!<JF}u{#J#@e71dfj740CKR2-v{lxE^ zAh=)Omw8lC5FXDE-i~-V-DTVM&a)#^aF!RFU36A;Pf(W#u6mXC;F5cr9`7yMy6MqN zGj^$J`j~8KY2T?IO0RcSeK||_QuO9Ktv_}}Uc|gkZprkNB(ZGD+`d<oP2PuF)DI17 z<Fbn07Zy#FKw@rQqW5`LcmqFt^Vt=1Fi<ucuKn8kVs>0ZnMIrL-0!vZD^9Cb90%2m zj?hcGNo7$7-nw`rbjuUxwp$94t;ANa{+n*JKKdqhTYA!39-btw5(e?tGM|sj$wg?m zJo-DLUp%8rE%|M~>#-Xo5ood6Qwh7L_Kj~C^QgRVu;MN=W`o6Jkb5bt`-JTcn$N>- zq>SqSJykxLfH{xYw94_73pR6mT8qUankJ?=wv_fwSFJz`Lr$x+BcLfA=L0WMGAe8> zG!ycUFrbu-WVq=8k4B|`nK}K7znVAoD<W6M&A}w;%r|-2rn>DlV7suKGU~VfI{Lel z4Z}8RS@<)~Nac4_a?!8dIJi}FCGD5jObWTC{5a(&-Zoymh_0{dO3@=#yinwILY`9% zO@N~N<P=X{^oUIdyli|ScK}}1>1ZITqyrvO6fi=eKhzxZ;uyTx#k@}@R?&M&J<~eK zNLW%@X0J=dxb+kfb`_Z7wQIXr^O9QY;RhCdlwV7uC&gO+$VwD3Vo51xE<LVx{!RLY zIHeeGDa)=1GywH17KB3{Dwiwj9GXWx4bmZuGsGz}dyfWvq2OBxvKN&^#d~_uwhH+4 zmVkC~5jLnsd)4^|j4C)+=Bp{N&gY$vm5%mtfdz3Moy;Dgg@1fNcp?G!R+)&oUb`h2 z?&3A%kb2c}i=ANVK(Y}cQCwVE8S6KuQ<Metp^R7z-{n=&KGk<JI~01vjR*v!p7SIO zCYn(8G}PlZS;1GI925jFO@gPAA%p^6myMJpB;iQ$jA>5f>dV@|V)0~HPFNDKiBkE^ z94ivJoXmyZ$khy^zor5&^bAm;RWQBc{cKG*`ojYNakQm}a5)k7%t22{@&=2*$o|M0 zoy8HF$!j=WZp+3GIRfVE9Tstw=4k_90g92aS3nrt=N96@boW@MP!}E2sr|0$0|8cn zwlB9nud1DEG{{VWKU=VzudZ_L#?n$f&m9pKCxMZSyM?zi2Lw3zFEcB%X~?M1F^P!! zYK7CDv95>DLw1&>j?kDWyz;-8+o<&xJmz~432JTo-F}+C)HpV!^NN5YRUM({M`y_= zceQj%Sn9#id3*?~&(-t0q;F>5xc?|dKFVH*M<=2N*R6kL>+C8BRCrBtc6%J-zgyi` zeXzU!u~oC`XH`*B?-d9k-4TjMl?N{#X%EZ1<)Yp?x{FG|HKzXbGy8oKiy;uC8A}Md zO`|s5<5zU~biTS@irLxGA(!L-9jWV^<=d+HX&d*n_u21-dL}%T7U1yK9X}1*zqH`C z?&iN>q0z;8cXwh(@bdR3UfBA>v$Ka68!vZL;Bc<u+3u~6{Lk+nWUlb?N58n38~=ZC zKR;+VJLV_v@;%?Lf2-(TigD{>!I*5&UTAspY1i+EzKorJ?m}4Y<B#>y;h_c?yE?<j z@yuXDX5apz#&aVJjccKEmmMFukJHY4)y@*1eN5a=sCW$0EpMGI&&+uLcbor{zTY_} zy3~1O%%9WjYSHC5sMwly<Lj+Z+%8SDE@cH)!%)MC9O(xQZn}4wnus?`Kszy}%OOVo zV7-m!+<|f*fIr3E<uwCEH#dx_|JTa$_54a9XbA=LE$Ld{=8`6>UB@8E_?Gy%4JQt+ z(_FdQ$SnHn&_BZRRo&BT*RTtcx+5vFTj*3j{<Zfx&z7$fR%g%ioX#I_7N#Go!~5$; zSC;hl?`ouVIoI<rSp=o?Ctlb6^6^VMBqZQ`V5OYTd54{MUL9<UPJbT9?+WQP7VS(+ zhq*tjR-6r%Ei&_h8Zq7exdw{HtVN4lEhOrFd)yt%hvFPmL(lC)3p-8j0CIe<5JPEK zIEa%Z#&K)4%OKd`2E*z1VJ>9#iy`Viok(!mwPXH~&}OQ=T?}{3-vKgSiXXtbK(($( z7RY<q;_ojA2h;cwHsoDh$|l>i%6zKN*pobrUia}|@h^ffC&iFi1bVCSbnKd$lpEO* zmbcYM`O8cxO|E^%>G+rpuM{3Q5JR|gIY{=?I+T)FxvS-$m;y&55lfdt8K#U)gK`mq zhjj&`9Ha~-TIl%6XOPDchr?S%0D0@GlHw(kWvo3K&#XCPdAA~zKR#fu$4xjP<MkKm zdP*pjo;riWgB+iZ@jDqRyBwraTgGg=r?t=(r_5=j!9}*n|2-&}jw^jW7E`<nQ}0WE z`+dv(jJ}xYIZ5G8?+r~xK32xj@g&kyW|w>|4Jv)cSmWe0c+hfU_F7~-!}{s#&=c?; z=<e1D=}P~nyZ&~q0si`5!04yd{goFy+N~c;wAK*41zg%vkQm?P{N&QP9hYkoR=M4} z$1`tqbsL6l8Vx^DIufCnGCh3c<$x0HZ}E)MI(~dlJHHJI523cV=Ir!2Vc*_(ye9j% ztsQ?$U0mOnNi#>V4YQ*+b_|bvZDLg75?OBxeGfLPUS}d-N|^U;_j1jj|DL+IaR=H? z%Kg=8Pg+TQB_Z0dawrgn?|NN|&vYdGv!UwdxXz_&W9L#`6<Zy|K2lcP2xM`nVR_ec z$JWF(%A-;6^|Bc(=~Vdpc5g8A18YEqe$V%xgQ5Q4+_-Y4R-mpTP(0=hkv66*dA&nZ z`Bw3&$@qjExp7tH;QP#-)-B80SFjv1nzi>1sc<4|1G=IguT6QdxNT*W+_!1ER1~h) z<&KLjF{QbZ*HR<^#}($yp_}e&hAay<+wl*2p9`~TwUWJ;&PPK^TR@Fa%r*Wj#-=}Y zRM*~cLi!!w-Rj*B#!4Uj7bF8w3CnLgmVMbg`(#s%_!t5k4j-+^z7E5WuMuep&PA9H z&MJDmrWfGU<Fj~**JA9h*BNH!&TR|7%<u6M)Iq+<Lx$MHf9wC^*07^sy93E|KsRKk z>1W1(5H(izis}jL0|je*u*q7a6B<<GSuy@IgL)tGsgSr{4>?UPn^CDo2Fyb{G}?Cr zJ$<Y8$WL+y5rDc&bbz<m*a#4Jw};=!^*}yKz3~)?rB4|Xy^eO9p>=Xf7|M^!@T)2* zV_*Z@ab(wJ^(<dGMjzK~V*c>Unhw~O2Oc7uM|k*&*et3GK2a#CnBg_ZmAi$)i;d_a z#myZ2U@<#4RfxCqdhW`Fx{op=N+?A{uZ@HBZs2J#nTlJ&C?kUdO8(!+qA!_cQq+WM z;s4qM>AyyUXTw!XDuTeC_V@|ZKWvYrt1*8?DN!w$E}<3?^~F-eg&+^&)d#McbLuMR zHs(q_O>jN+g?MSgi39L6JKcRWp80g;WPDy3?3;lWcMD#(l&5i@kpX_#l2nuRiew~x z!rRy_mr+9mfQCSnL*&9NA!nK$o2f?d5QtAdZB;&`a;4S~{vfcv=&Tqxfz`nL)@1KX zxtzVTNI2KF6cFCRTPM4TfXFU0PD&xog`Z84i|DyS9bay>2>ZqcF<|>k-xtVQ?#QUV zgtxdhrRrqqg!a{u+aI|=y_K;Ferk2X_#=kQpTCxUC%Cu+aX$^N3)ms++MrrXS3O?g z#hJt}JB&2`$j8w~)uqNZqmw&1!!X?I+WE51WpsUM@A)l7V(YHXC!<Ba`das#`_f%; z8rwT}F1{m4t@6>*QT~G!a-(u)O3&&BQin2bzWCc~O&hAxeP7&KBYkR6{cHfb6ie<2 z(PwJwV%7SMu2guR^}zJ$o!Sy_wA;Gxy7X>zW+V&CSn>4me&p_rYZw(-OA1_H>`?Z7 zf9P@4{Z7oVYqs)ybREW~w{|=^)pZR4jtnrecOW|=;i&G}gx7oGH@AIf?Bug{WX0Wk z_7kXM)1VblGN#t`EPJuF%%OC8bg6I2jz`vR(Cqb6@U0tG_g>!h&+Zlb@r4cFviZV$ z@_QFPnAL0iB~DCQ6t4u_?UH`+{oI75g+LfYk}A`7^0tELfBgJf<6C1#_9Sk*yVPc2 zlUt?)21f0GM&$R$!FLm#Y7{drGj<oJs`XZ8$EZ|_p>_Fa??}c2UyqX0SNrD9=wNim zsoFe7&>@azRKE1VqU?>`VedDV?yxO)NG)F-?^YGszxUn5cZcOIN1V$ePVV_CURgC` zYZ#MmVX1OzEcbBw{J}PH!=az+&KKk+k5iG7D8p?H5Cega?$jA0v#|Ti`GgCE(<tsO zZ0iVy<F`<o)L98|{4L>OAoengbtd7pDr(e=fkYR3Da3im)(~cOOjnmdouAt(c=me# zIWEXEf|oUDu)G%QZ?^>IUCH$xJ5DWSjhd204RS{}R)^q7n9B(FaN|hd>7b>T^VRu= z<_a9xrrC37gO&b3@GQv*Rvpy{c0b0c9whxDe!!9m150{DxgdjRxqPJ+(tL@D>j?`b zPI6lt;8PK{$9tS>E_tZh)DpHGu>6x{CG7ISgc6%>7QR4v{uz<6e9>#qXa=~&mGkgr zQe`gQVoh0~Yi|@}P+?nKI9W>&(ghxhAx;z*y21@vG|58Ikk11HWOmQJ_rml=t~0un zZ#z@(c-)?(uw*!WXq1p&7#klq`BUegX`RNe9{e=U?WX7GW#`U|F2;`1+k=YkhyNKo z5bb=krH4Z3n*OPw)EmvvUhdGXpBSB)=y>O|?1kN8&+Wi%!zRG;20k*Wy>f2*)*1OJ zb4NM6+*9L?$QcPQ8xFs%Te8Dw_f}aw{&6kk&c?4!<n|>lS=#;Yqg%FZyv>d(fMfqx zhl^9)dk(D4#DjRP=(>2z(zD@ZduPq{k*!C(pA;S=WG9HdhO}XNN_p<4$Q|Ebhh2;= zCUUfoQ>%MYlQsKag*C@qYD)D!w(Ng=WD=9d^(t_(T)kjPRo(doFmxeRhl<qL-~ZJ| z@tBT@2CGdsdiu!BRuBNf!sv$wc3w$RZry+JR_4wb`KQZLmWZL|zL?MjG=&+%n;SHr zZJV@rvUb6nHPX|n%6YJLGJ4#8#d|ZXYeSF1(k}8AL%Ws~X)ky3e*votbW*+J3)@DP zX8#uN0@;EqgivM~iQ~%gvR^0-pA}S%DUI>k(75{%9`afB(n>8q1T1g1ex=@-Eqr2# z5+OOUsC!P9+vgia1AwW2=MCHSV^T$8z<8xfapy+jgZF*Pp1CFR9{6~#QFT3N;~M=M zro}CAhp@FO>sVgAik$%88P5)72nu{sC*Ro7qQ3e&RcK#v+6Fso@zZ#xwG`2_#aa1! zKeM}`FrJe0^^ln5;ZIen1J-^W(k8_Ju8YYQh+_|n?nf-OD7KfmRYC5x+wDTJi};<z ziflaAie?zh*Msxy)5=!|?U{)dOAE$iHu14oyRyJ`w4Vh}LO{eu2H$NaYBRtldlz&@ zBPDPLD+L)&nfO~~D)41zvR|moFbj!BU(GH;lAmQN&Q1|LwTJFvNU!Vp9iEb<$>F0g zwmlL<t4T~?7HT($D{xM18av$veufW*;H9lX!w?_mKpmZIGt+o0WPdw+5#U069(4<R zS#;=<D=qV%0}js6x(rDV<A1TKg9DK*HU=*czGGQqI+?!S#a0rDm-G2v$e2mJtjY;g zc>!FU%gJ2`gD4E{7)(Yuf|s@4fFUBrG4!&Q2yY_c?M(S{DOHaZLpur}vvpa`GBKye ze7V9UXa8pm8R0cBV`z1UNaqwDqin|E{xe1nBKX7yOR2-I)x|JA*YZCySr-$vza_|v zZ2T<I1!%!bsN?kxRB=VNK5V0kvb=4F7VIV5)III1W>#u-rF$%G8AGm^tnv&fa+D6X zKGj<FnRJ3%UF^ei;|DSA+Ck<1@P7$5iP2-ec<iHZ5K4q9-_prl#<S9$ojK?55mEKl z8X`X3wB7hhwC`l?{3T~5f6IV%Ukr5M%HSD~_J8cWSe_VdX)2MB3-#bXZM-H*(zHXA zprS|1Xq?3E!-)D!3`HnKCmZSwA0Ms%c4*?Mcw4r<6GI!cd8rdW-E@od-t>Q|dfc6_ zz|EGwbk`)WUMIrczTINLAL%1&(X)Brb{enbGphGc)w4mRrGzZD`3`is=k6DEo=Sux z!7fbG&?YHw?_|dQ^Xw@6S`KUty>)`m7@E}mh!S3TtGy&MtI2S@eIB|gEwrv9O}3q{ z-TG5?ba4YR^AJ^(+8O~my+RwU?9|^jZ2Eo*>j}>Z4@)5_%5pnbyCGp{Mx*93b9b+R zsyiLZTU%?|=SMuJ>SsTMKJt}>fNM$D4zvFdk%`QCpOE`ibxu7vxVL+DXK+c+G+MCD zR0L=dqT=KFdK82~aQohxlH9X_XLrGS$*Vke<&p0^k@k>u@5b8E<xqk7M};U3v`W8S zqa{8iDno4Epu3rIT%_k7pNjE}d{8Iwj(e)`wqd;`z2JttDEkTTXl12&eEML~DsL7% zEz)@nO%|9f^{Lf(SFjH^bO@$>@-Deq3T?^;FOpL^8F9Szs6Ai9Oa!y0{I$v-<BM~L z0FS&<HaJCj>DWT=w-Obuj4ZrT(4JSV0ELIQ+d5t=3(VC)o*j#m#vGL=*F2t+;XW-) zK<iEsW=?B`5e_XvY*~3Q*%;qTOgzx&R&$>ASf8E#!V3%q{8om^nYu9!94Q&+B0dKz z(^2mO-?LVi)i2Dvi><y;Ir{G8mj@P&|6I5;d3*ef=ZrglvgqaZab(eHf0<!Qe5G(x z?vbDDU9A_U)=s8j3|_`7l8gcwdars#3M<@Aj85U&PBoWO*4U16!6Iy{Kbmo|NKT0> zxB@K)wrPGop*Fe>eynoX_fmRK7=wuG_}s0QD>!psS|--^b>8oM>~>$}6jt6GQ69}Y z4Jx@;FOPytG>7KN*FQPzqUB^F&?4YnE9-dJ^LqJ8-O>{ERyH$Xe4ly)%%p7n#wEXa zC8kC6{(C*dAx1*AM7G_<y7%>^<!Cz$BgdxCxpX%&lS?R!kXEfMwe3E%vsBV{Dxz)9 z=Bj4d$R+ju!&^UDvZa2^XrCb1M$EH1cVOQ!t1nJE#Q4L|>p8n%30Vys)N8SL1?Q}R z_VI7EO-m^Al8f%3sUYs_NLd{A(9E}5RxHx&_jO77-PfsmOK0DoF0~&v?0^Gnq<#;N z>-q80jO{OVrgW64qI=}*JpxFVjtoT}(!T#uWPESAn@DuULi`why`b<SLsh-y#{>Z% z(Ij3E`LkGeKx$>Qt!n7}M|q*%VYh>=-bZ(CBs-D_bK=Y_-S(tOT}F-LXP>-w=Qp}u zQi);K@&Da#`T6mrUnboc{vj>8>B2xJqgv<788vsJOWDJC>btMz6@2n#^AF{}-+j%H zeauZQyPBuAMg$`^1TL8R`+3#9a|Y*Mz7A77Jv5nd5vyg(vF1CFnCkGUi}qXGy!R_? zZ|UFhNqUzdQ`7Yy9yye^EPOJh#n^-Y4kzJISIEBCj6Dj&q^28n*{>PCamlv!?8_41 zNz>4NpNb*W4PBoU-2XjbvFBqqA^UA44W2yMFcXh-;ljigK(CzCwk#X4W|8<rF+<ZA zC+U$3DHK5g_x%Wl;~{4HJW;9<_c7oQ5>>e{@D;=3EsorF;OC4L7FR^uwYl6mYZ+Am zvF-4XF(QnQTbC@fF4&;R-4273gaui$Dp&@&yHl9l+@t0FJ$-SXOn!<*g`6ztEXN@q zleZga-5(|OCIT`&Eq@7=oV+SZg(BjfhQHT{?{au7C0+g@&^a@P!#(X>%=S!d#*DQ& zV|f7C7}Z9&PUCN3-;wq>INmo>n3HA4ImC!jTdyQP$0}`Lb4~D2+`D+6isuTUrZ;Dt z7O9T(3(W&&gkumPV<^PFtBTohYLciR)j?*Ut9?}l)*eB9vXcelEy;8Dv%P?eG7z6O zp4~P7VI@(c@FSTplsei+3*y|-ZY|+mF`Q0z<3IezTbJk$1Avk$i`|dC0yGu1DgRFf zyl0koC9OjcbMkv<2bsGfa1tAj`09ARkSo~aV|cp=977DFS?+m>n#)lR(9Dvrcy@yB zxT2vxb7cFCig;<=a2RWI=HPU03@f9#aiM^J=~lby*%><;=TgmT-w5-!Y3d;euy{!+ z+yEV)S4ixVI(D_sbIEybWa*&(c-s#rxlVv&WnPQhZ|nZ?;UP`sh}99{-RIpqqd#N1 zV%n$Xt*?!)ggs@@atS#NKi|T!rR>}C)lsG7r1Y4Bz1jQSekEI68?ptysc;#DkeAf) zvv+S~Ly_r?dA!n+nAp941+9C{+(&D~Qct4y)R!+s+WmWzEqfOgqWTNun>hP{K%J(w zeiib`)Nd9t*A=!nH39BN%+qDA(!`nA#M^-E^v5cNM_$0VXVc3DetorK9p$6{>@hq9 zh`g@$R($c-s-X||G#0t!c)sAKqqLiX#7pnDv%ro8F@QhJB|g%6qcjk(ZLUtKcQlUy zb9P9rOQmL-B*{09qiVoL%A!&AP*UWcH-I#@F_$_mHzg&2eFkui7siCp1zG?xDeF!L z&EGA)Ew6ohEPdf%)C#V?|60@Rnc4#&ceb_1T(Mh2^p)UWLKYrfEhJ3pd7=&<zz>{d zE|4qkRMS~vD%r}W*Qh1RL&GJD=}Qj4zaGF`8ULUncMFfSD|watD2FHKWHbs(KH&SW zK9G}9MHY-t7n>^0-}zvQhumYHq~0%l9nL}|&>?bf`_Uj+%}zQKq#c-?OOY-j=awGs zTw-6)N;bmUA2my-El;mV(+#yPO4daAE*2(UfrU%;Xgr~u+9?B?Ea6Pk0BiHDeJT<F zirWR)wh*nz8An};@zsZ`$Cs)TU+q}T_Z9b~<!8mMhw|<%sre62mcOHN8!dxqS{}(R zq^4`<A_A7IVp=aze>v$&(s{$4`c)_QJ{~=bz9l}jtfT#_eJ2VzAk*DWY%jGl*4}mP znwENT^X4ZbHbeL48!ATJ?rX|7jUQdEdGw_B;?o6?Zf!b3em%Xe^3RT(y0R@m?nCRa zH5g7uW58(L>){)~g*?-i1MkV>d|orsHsLMQBKTK}Zhz@`SL1wh;~JLM3}h^*+gzX2 z!H-^FF>PB*Cc9X0OA*Y~vh|6MH>muNNKzikn3|<BE4(FNRTkB=7FWdy<)F@0BLg9x z$JPQu^!zdIc#zk+o))ImmFjQL%ix4vTJc@Ew`kAyrQUdB!O^erC>?q(M=hVeCe8R3 zImJhO<-TuiSYCA*gDnqhEcnu^JkRd6@a8JkSu@CFB$#MsTMpT<$D2j6;Hu2!f?-G9 zxoSQd=dfFd>9f6sqX?86&`8KPgm2iTV7Q}Ta>)}JZ@s%))DC##e=XW2bK)W_{eY8= ztd%2)yPC1qPAup%ezTk(d|2R?<@dbIbtS|K!Z)&bD7C^-#Y}566wU9<UW-#98C#@# zBurAA5&Y+jZTPz`YUeRt+e2e>+R%hTsbm~HgsT47s%+q1NWT&_B8<wMv6wuiZ_*x> zJEszaVQ1-=KaraZ{43?|fRw~moE-cRqaCfL@f``?g^@qBirwJ2dI{Qq%s@6e-Vqj2 zO*)~m6|<_WtHRMyC5Tql>6fKjmX$jVo4J6=#VfI4U&D>@)?6t>F!V>Vv!o|P$BOo> zI_F;%q9gkAWXsUzI@Lp$UJs9b^91D_b{v0o%R(*Kz9i4MstoI?v=&;@CIu!9BWQHl zz{gSwJ~sT$q1XvA3NNDgHl=ujIHtS%=n0F^3G=kOB?l*5fkn(+=IOK%ocLr^TYPZy zK)4?7Y8Cw{DP!Rh!>sFccceLsr{1Z?7~&hH{~{Q!FWHIT<2v1JVgGcKC2}oK`RdZo z^Lssb#U5m77GqmEWf(#wq;JX@%YTJXh%&+<c7S*pn6t$>SmsJIDtBBUVnEO&mwLEe z+@W0!IXQWW0^_Q;pAb{lT?6_OJ8VKFe~29`=v`-phmE{+`)#Ms5W)84Orv_p-81e* zuBtSCk$sS#QnAexY2ViJ`BzmFnSX|yqPcT*5>y))J49!Hno1$&zbZr}?0wma@T){q znd1qmU2x2jA}pMtViaOg%M>lj>T|EcZG2(H927JksBE+REg+A^R=ArBd`#BSkn_oe z!M68#C<~F#KqmMWJ1J*l-Ql~YRD0-&dcR*dcUXx>u2Y1C4fY>~C|ms!zYbplVH;sj zaNR9_nIg#z2(x&gDh4*3Za)@;pE?Ol=zK2OuRnGoEP&WtZy)w5;u?U6_#%s5orkTk z!Jf#3or}h^P~5q;@(rgw317#@{+^yZr+OhLY|kf-KkEXwN!9-imuUC)OW=Q)NIN2i zXNuehe0g-~&!|`x>a5Z%|It_iacors_O8dDV&KmAdwtoIZWeuN_vLDLV=Chcz{tQ7 z-tO0KdmE2!bPhjP-IDUDyfI}fW01>O!1Kkr+788qKK1Y~vo9il$S`P9qaW-7fVxxO z!n3>?xn%3Q^5Gem+<gqMc3f}ZFbD@O;E{}>2z)<|s!OV@2LCb(>-x(0URseNnyl3z z+*A#9+lMn;Phd&cdxb)(NoV+uyA=0f`G8&G5Pb<HX+V?lxxo~LL&AcZI5E*AP#Shm zJ)zx5i#oTSg$log|L^&}8HVCY)$lsz2knbH84o2ztu05Fi{fYcdEwi(N<dQ19S>I? ze`n=w7zD-+d=V%A2u)1E4qoN=C4>?x=en+lcm_lR<tyZa%^5GO;vG~l|1W8r{Yn9o zg=LbVw(fG&l?aIN8xZ+dlu1tO*aK(*r_qri$5Fo5k;B4)!At;PV9kb^kUE6y<O+mU zIF|9uVVSAc^(>}pB-^SgkI>fkLx!}}h&pD0<S>CnqB|EbryA<+Z|VGmoPs>gjW#(| zui))peF`#WQUo<XWsyL+lOo|3fzr2H%##!*R^463Hnn(OYNNXbof$P{(@;8Th)#vk zFI>$gcBwgMv0;U^k31ZLe#LR!xgn2*MP|J$EP^CmKm_U>NLm{!Z^DL`t}@x$Xz+I- zlJz7FGsYS{Bl3$s0TUV+F@ZXQ7gBa=HD39^(tL|^iR$rUGQ<&r+I&E6JSP3$;n5Pa z5PlHNKwG!IsSe)~vCC8V;mP^rE=A-Sp6lLf<8iJ)YA3?~Atrw;JLUILHDIevV!LzI zQq}i|H#`(ge=MCqtC^}l{d;>j9vntkGa*`}<UCL@PO`8TABN_>2sl61pIpr)na=FZ zC0B74K0RR(a6f=~d|hw3BQD!0|1qCH@+C(1{{Gngm?l+u%<Ma_F5RggDfyx>ThSl) ztode+V=Uw*0Vg!&$0GOEO3yY`EAbVe7(7>t_GH-;^4l+d;Zah6(@uA>U<D!SLGG$^ zrx=~H$J*W9MQB_+^EG0YNi!fEz%Fuly}pbe-QAGdAeI=fLIg-b&*a_$KE?FLyhIv} z1+DJ0k>(<<OEZMS(qj=0W@CK|yik_+$V>OEjgtadr08UL|M*l`N?8`;!}<)ydh>0B z2P3Txf6gwCQzCG+Q9rNpTbZzVRCGz=OKpR|+w1<kJn&Gh$MN|#EX`_*2BsnzWc)K` zar-=v#fSsG2&t<`Fs_Xeqh<%*jKGmBpCL0K^7+nKqFfj|<U)%T`&^^yqO2=KgRb5^ z%GVofe857CXk(X&RLI^O`)S#c;3_9v6_8%C2-&8VZWY2wa#e7xAe6s)agjY#q9CQK zoqQob?Pn!>nwt|RVGx=piez)>uZ6*^4GA+_+!jr2Z8~5%CTocjPBkw*-o{IFcSCM~ z+Iy_)AwA;b#bOxjc)3x#PuD2csggM1yNj+;$Fg$h(PyVaeXNUJ_Pku84F+gpAmUR( z{N2O5cZ!%a{+VrLjLb!o&oI1b%+)bDiu0!kr(a_?{hpK^{1iqG+x8sYuPv|<8}kNY zgMt>=vq`e%j5R@Uv;zLgYkadTv>2B-Gx6oN<Yo1ugB&3(1X<9p`6{#uLlH;nTJo@Z z-jryH&MO6P10J)q(a#v35$vsk^c6g&ZPFvv1L=<mQ%}?ARk5B7t?yaKZN}n8h0wp} zLF7o<l<?AEchTsKQbT#?BS~6IO6l)|su91zO%G-{KQ!u*t%wRU*SEF6X`^N-R4*ad zRzVvhMr5mc{$OJNybP~1-9s^|d03zjF$Y&tmPqtYeJgi~abb+y4VTZo#>io!{k7_r za*17nF|wQ0gV{1PU~OD+p9)X^!2!h8=hR}Y7E{-$E^l*YAgbMl;fOA@ZMjg92+H;Q z5S)1OfS<IxBPF8GS$6d)0-l&t47bP(r+ZqrNt<?NH3z|)PbWoXpn|b<KCez5EAE!b zc^q2>F<98bD7t&-FSB9KWPzMP5)=QgNtZ>Ik5P(C$!45RcV<p3k)papA~#QR69ZgH z(%KjbhY3SENG;U#!dcVIi9rz*dQ48m8jEH&&l!))T?C1An|Ld!)eg3Gf*NRe5i9RZ z%Foe$P9RS}X56mCWZbj_k+vq%^ue1jEmxhRiI+*T8H1={xu3ctclemee9!2h)HMB; z!o~MCJ?k8c1sK6_saSnAOEl;Naj=p0Mo5uZr4u=ZTlgJm`lf0OlH{ghDwsISvA%Xq z#Ro8dbyz@t)OL-GV+^wn-%Dj^2pmS&fGAuGi?dn&M!9L%Gm!z!AUajk6Rb$k06vLT zlmBf6?S*~J;Sf@wxYcrL=N&Vz08LeqOP)Sw|4umn+(pLc2713nb$~^q7(9iyGk(0o z6a*ntCtK2kss;p6T4YM49-mPXAAn2IKaaGnaM?D_+KH$OSR|nCoc;SyycwJ9q*-kL zn>0?W85?fH>4`H_VM)b&H{fJb-TT>5Pn~ppfm_RJ>6{!QKGF-WsOgj4=LjGY;xW{v za-2+&)I-`(6wT*@0W*Tb0(EsLc&=C8wtdAs{hT-2P*3UtSqzN(M=bb`SISeA(#=64 za+r^_?ih$gd|a-7br}4a%HF~|AtuDO4!cMVCHJO6nIh*6pa5^J2)Z1yT<D~@zWJ2A zi9Et$qF8T~rxgXb-y?ghbt>VX>;2z&q7=m1GDgIuz~4x)_KX|HWGOOhk=YA$-YMRR zh>3?>05WKHGAuKEQtKw!3x}&kR+h2DRMy~V`^R&nOqq5AHtAw!JdRRTs0U=3OBPxF znP`U%MLTrNl+O>JuK=Uk)jAmgv5S@k?@b4u`u2PKxal~)?LY-fWCaj7ZEqhE!nu_x z$@N8&5k~HG>Q>XJKNW^M6U}mgy7y>5l#kj|jhB~_nSZ|TN_q93&egfSJ*B~&^P=9f zV*KZXMDm<c2v!P}ZkbJ2`<RaLP9;neY(((P3OwjxmN-*TPi?P0W%n8G^xC5qd)^yX z4PS0sxqqkVJ}Id%)G2Zg+omc8b?0H5ueoxFmjpR2@OPwOIr5XjGNaYmrhm#KnT{Rz z2<gZULWj_zYJd1+SGcbA6wDrOvs{@urEkkGWtv+*?sQq~rhD97PNyYSW{Nq+iNm8~ zx-rO6XTGzAok>qlKqulhv;eCBsC{R+-EFGbc;ihs@}~Da@wGjfT_bNmP8!2?23{Kp zFVu#Y-*r-qey5?!t}z+?PHQxMH{lN(XMCah-paVM>DCAJ-Lp^kx}+uO79>J7+5OF= zz0=od|1e5tR-(c{_vgDTTe(>(@u;G(jl)u@X{E;C&(ZD24AL9)gLuY-27WUkBzdZ- zBHNc<#x_es6TYu=QMK_-16#5Ar*V(v%7|!FpI2ql#7k5I9W?mZhr+Td77IjC)qr5J zlE9^x3`N4xkPe7qXCX{8L=`LI#8Jqxo>TV`L$|vkXi|%!P!a+j&6Q#sI#d%rS&XMn z5SW6%3Ga}2S^8NbB2Zr>uRk`LP!<ZGFdOGvvJ5I0HQU@N1o>NX@g~=1yj!2kPzFA| z+=ZQV(U25-RmLy#TGW^&vPzKCAm7}~cTN!y>WI}~65finEc^Jhm2Vv?gjvRW>=*If zcETY}60<4Cg1#5wzDSG<xQEYiU@07DnX!vkB(?)G3L?b$7V(sUmywC~aClnitw99E zlx{fMj~s&?kpnAH1S;YMkEBXkDef^vlxf7)DL7(8i``r%XFinJx9YsFTU6p&WwVbq zWVi8DZjSYlvaC`abeCBq86S|!xsCZb`=8Z}UI1lem0vH_yR7SKP({M#YD;lRveQ+K za7~1sgzhR%U^l!p8-wJ*0x3|v;1pq{F*FjOi?sr>r`rrT!MqZ!=~>}ZrRr$aMDdg9 zu2xSEyXOtILY~<NHo^3g5=nU|QxwWBYV7p5l-P<GnnVF(%QZ<~Iv^Nze+<vLYW@Z< zpDRA?@^@~lH4S-Gp9>a$p>(yE`*qkU7uk<Z^x}q45)U>M2F*8l&rh<MN%@M|konvB zMCH@j*kGZWc2P^y)(uykMHs*^+Cx4ieXNSif&G`*#k58E5$0@R?IvPv<E>>i$!Azc z=gybx{{}XcI_FN|&X4GIUtbWFxvMBw4^gI>Z_egjtM|Zh{T70uX_-b_ftLm|v}uT_ zwE@i8wUA%Vt2OMS;AFM8nqr*T?er&ka0x>W=J!m|rLS>MvtzA(Q_7oapUC_^Ka2`i z?6PxAkxz-HqY#(^OHquyjcnqDNxDQ{HUP?iuM;<)8f>@)3kix@tvBXRDI4TaOfn&$ zWPs3)ltkXkIcSWKH3Jy^k(cu{g(1mtx&BOrAUrT@-Kp&6gicBK^?q;I9T*Km&r<<Y zRO)R0xGJDHEr!LPioykx+~)wx)#T?z{c9YE6LuROOOgB_@~hBl`qP8Y&T+;pFYsXc zCb3gZ9`KXk=-R8SCYl8#VntPJ#)J3pM%RGj1-d+Ak7z~euh0gWfv9QEm6^+pU;1Q| zSME(RuDY@1o@%gLXDk7|+FpKV{`~mHk%hSF7`Bw8f9-#7F3kEfd^rLv(G9O#ow#0D zXIzQ<UwwS)pmz<sa~icao`8y@JB_NA0^5P5$K!w088Za+KVA?}yxS5SAFRLN9IRdJ z*|LKXP{&k=*m&s)Dn?(;>C;lLd60z!{@RugSbWkgv)rl5I44-%R4(AMY_#;oH}b^x z?flDvuYwDJu_cpf3p07_p@154#@i+J(7*^mM<!0YT6mq*n8LKZN&lUY9%UNJ#PO0G zLZQexCkkyI5|5ZQ4J|r$x|zA)I4#1~S$7c{<SpV0(F|-teuX|31fD=kh2?6?O?g2| z@~3L`%wwp=ouXdjaumqv00E%@FE<fN^`)9S)u)o3mrxjsVy>MfpP;6usOPRdRH&-L zjEujxMHy0t<s4tuWC5>8vzQQxLMTXPJgTHCsBOuyZWLRC20rz$%&|IzQW__OUhDv+ z9h8RRAqVDIYT=FiDtCARlm?<)Rj=z}Q2n_r;`J$<FlL9%Vu$-scL`Hcl%0I009JZW zFm7AEi}H!x;^OHaFd6xxfRoX3{wV6qwgaI;4T9X%lY=K`d);+aeM#idI{!t&+c1A` zD=HMOG-d|mmR?a>WTyu`)j(E;LqfGA-of9R&_!tOCbN*nUCcC0bs3-317+Q>1fG4m z`rH5k&R9CVH%xHg?+fvccKe@EizIPt_|ivvF%T8r4`Z@k<+?#|0M)>7iq8wUCLD}# zSmAwHzQClt?(}mHxW~jiGQmZmRCk{z-kI{02I3K>#X_9QmLW*<d((Zm!GYV?(kyt) zpa7**CQ=7G?!cU|i&d}g+bkNU7}v&DF{4S~3~sk6WVJa5S10(ifRs&oPR1%%Urg5A z-M`Q|#IhsU^7cmVevZGGKKV*-2h9iYgCknxP63*|F3VL+=@8wSQBrI30L_D|{oh%b zuJkuwsDcvBy7goUuc@g2J6@cA4qE}9KeA${igDo1I6MjY)fWHR&Ky`y+%f<N<0%|` zQQ;4-rOw@N$-4NHfjI{SYtoA{8;^0P2uvW;;VzDrm^@#>RGl%9+vD!OxRpsH{kO?? zhw2&_CHU&3S71=f(aS20JxA`p%^3<nz%MEK;PuAkZUE_`fxrNQy^+UR$D_!D?8rKX z-dYwZkN-;5ALr<cLy$a>kD18FeG;@%#(u*>m81QH%|_G5KMQ;^`r}qgul<h<x3i<B z+S{WL8b$6f@zwjKd)x~rN`PgYhtD+T?y<NB4(r8P-LhyZm@!sq1;DEl-KXqcX6%Uv zKgYO>ip5p7=qGpeo_+td=JdL2_Z?vB3>m#3H?6YZZI|PJnf;_X|GjFsEnJovQI<S< z`JRs1xa4N=+>t{O>!~T#vNW;L_?-5fAz%*VcyFnvbcQirM6n0c*O1*zB~6v8D|Ay) zysm2(XUm6Lg1t@71L-ekD_aChP<Kw#5wBf-Vd?<PRMRag2uZs#5~70?TztzXJBnOl zA}aci$p*D^?xcA6m=3Hhp~_Rc<DVMJ9yQ!oJJ@dY(V^=605fFirmF>+2Z&J3SMLzJ z2}k22_d>a0@yjlbTyEqau8UvCT+?_w6DT%$2o5ATcOwN2(@Vh~UgZbsy9sHoAhp|o z*FuM(Z8Q0yu#k$DlwwGfn|b2+VLp9bYM6zZFBa^O_P1gOTeQi6Ov1}Sakd2y>CQmC zI$hL45!K9{z>%!XctiZxQ`~Aaf9}+awGBtkz*&tYFN#8Zq#}h1)Wc81<i>gU5~n|8 zH<aU8!mKdc`hjr?p^sAFgBfUb%@Au#v;lkqEd(gu_cZ9#m4`tZ%wBGXDS>2^p}^*= z%z6GZyr+Or^66~m?|=-5+z8f~;1G>gVX)Coub)0_wvL*$Kiwa5RJk#aX_E3H1*Thf zIn$e?M|zl&Hj-!mejj>Y0|s=ogjHU2i_~N|@(6Qe<ITDxPVlP@5*##&59!eh8x2+> zH8A}7e`Pv&G5TPOns^n16WVzGor1#pOoeLrED44$Y8s9_<G*AJrINpx^VSAiJ%83N z7Yb!%xzKJ4-eLN47afRyEI(?WYZQw8n4qA={h$oM0MpvN&E{0&lfj;64uQWp*dsrn zY#EAk8XnIQE#VEssSwl#u`)^2^yGMT$_D4Y8fGr(3#{yF<O{XXF%Z9KW?tdH$VxS) z4W{nwVAi`oU!lT#_)#CJ%|m)G=j7TV_^e_@qbSSe&H$mdL)n55MnOGWDb(dm*8Eu8 zB6gCsw+5JD^LagZC{}Q?S@CT+owH?3p&Wp)wL(Y~C%uR)67nLRD`CX8<?oEiq(Bs+ z0`Jt@<aPoU=h*|+wL1A*A=<(LtQqFUI2(ai3GEl|CMg?ijXk?v4l%)#UK>ice?!rO zdvNALHfSbGZaR_!{`MU+laGO9FG1--Fa*(IK5Go2qsgZDGc$c}l>t*I5?Mto;~TN! z0Z)gk<&`|Pm76izo0})xIa6zEvKE=Y(?f$6WzQyUFu;C6^&X1GwG2g<;;tAL;xcs4 zzQW^Z5MCb9Gz`K<o|Bm&`7>336_llJS%IE79DK(wX5@f2&o6~^wnXk$&y1+{%p)g8 zQPW>=wT({?(F%6$(;)hZ_U9Ul%%`aERE}_pTKP<XAj<R;(08(<-u<w90^LiYa)r5~ zhfUs9GpMhnYRycH4luUblX&T_irv~Xd2pZbm9@9Jzq<?xDZ_6a6+*^OB6%)R%7V@5 z!Z~=sS1s_rY_d~2-!3@vtql>U2gS#6QAq@w%NWc}=?^s*RN9(zDsz_49HX%o!-xk1 zH#Xn18SK~LVAhlWT<LY286760CwO3G5v9crs;-?7phv5?+A%A77<j-bq9&et^txNG zkE3&@)WACq^}nE*hU24<J<dEf{kg@XLq1h^hBjZL>7ce#c%4A=>^ZCuYo_nUr`yH< z2=RpXB6lbLFg?Le1$i$mpLWM9^8mc|ic1v?3Qp@>pJj?6Ed^kHRi@3balTdG{e5dQ zECKQu>=2T$9un6S(T$MC(N%>i%eY1;U8wXiVw%`!xbu~${pqU@gfObs!b}7Rn^}2S z_yXuI3K>0QT2e=VS=yDGgzfy^DQoDia>fd<A(Q8<);VW7B&{<pghjnJ-Ao|TOgkR9 zrwumbiBfSBydx9?8%VXn8bpHA`5mW7u&<3%Tnf^}R_y?-HJvv{HNF{3m%Z*5TZLMH z;cZ9^_k`(1AhR1ig|Op|Oj=SwAY~BKzbRNQ+2VZu@Dn8y`nXUF!UrpFm1Fo`;5fi6 z4M{dlvO;-gYvUMriTNe-EL+@I1m>scj{(@t*6u?+Y%PfP*l!33h!tk<i)XdU)lTN9 z5M%#q*W}VGvF2`&tArZ@z4hrJKe*vy@*yM@TTq{&GS)RK?|S3@2f&GeT-Hd{fV-L4 zAgQ2d0j*71hqCsNv19&9B&+cf=tjFnt6oF!*9&4(<!yZu34@iWWuS!W`o)A7D?(fo zsMByEvl_3Y_9|xCi*OLvu>?urA6!Ns>Y%^pP2+d6we1jVx@Fx#69r}vFUyp56IX<H z%8dX^=k~^2`0pm(_g;$iF){c(#bQkdhz%rgtrpUKjjVYCyzii=CKw_XFb<^9%oH;b zmEq%q0=A$G<uU(f*m8+7Bs)Up_sCha>4n%gG?~)LHjDeOF9Z3I4&u%KvO7#sbxO+O zCy;YF7Fy2D{%3fyZ}2bt0VpXgGq_+Ol{^Jt&{BB2*_!^Oh?x+~Eo=<W?ctk8THDbk zRd2r?Wn1m)1j{4m;7F@+oE={SoDiBb__}-eT*wkbvbPDAohe~lU&f@18<55P^LWYz zX(E^b%5gf}GOv`K)v_!yXsp15$T7xo+PrU)C+?vg+G9qsxNtvnxVy{5@O=tl*wOMf zFWJf)mmxD?#f;ch_np{hi!n27!QiVw!>p_HfJfm<qs&{NTn$hkRmMR7r0b*(xf~lW zattuwBr^t9J@UZZdpt8Hia0t7(>s1{sIBzN2{G7=3rahnRduuSqi>PQwDBG0d)ikd zq&~_G`1aeXe#mn6K|z>h@#Z>O3*LTlk#AO@#U6KPfQ!6z{<FvJ%Pooy&z<2Znvx7h z`<0YH;J8<a(=~O;!<tGgza<3m{{=8_1QJ~yZs9HC(=BndQ@(9IwY1AJJAA?oGu^|f zWnE)BClmFLr`B!1waWNd#Yw7__Q%~^kJ0gGYxw3xqBt&H3U{W;P!#drS+`N;W^tTd z4xZ(!X&0(gJ$@F)7Cbk%rLOE6*0;PT)%l|>o4kPahSr7Meep}fd{c(k)gSrsUB#4b z(!L0&Mis=J>NWo~Mo_NMM}$)Rv{B|ly1vjY;?dWlxe)gl#{l};Hgcktk`jJSlZc8S zEi}ADh72LRAb0iE0^JR@h(@>{Ap}G^O3I<=<!=+RE7od}9nemhT776gEy3n+BGN_} zI?^Tmp>t*{w@G=`_eZh~Ul2qRo}1!Ty^Ao*Qy72dD-Lz_LOe??-A1GnHb}nSk@G<c z2z4r^Hir*eTmcwk;Y36z%g<QP@(oOLGYti6g@7H~4ls^CU+lCllktvI72GbBm7OT7 zj`H|pML8Li4tW(zHNp6A^RrVqGJe81A`nnMc93vfVCDsc3Iky$PiEmJN6SC8V>wmP z3o*!2Ldnh34Djmy3ytdxBZYEl)<PhV1s-!7`4&}_54b8yRK0)X-CU?*R5dX-P1p<$ z!63a-B%BfO@F${BPxvwsV&xPQ7w2Dv5RxifHe9k+#605Yb*1Bs(bM^C>}-AYf$7bM zQX0fx6Sg4Q1tMj;OM7Z|frBdD>T{l6)_@Tc^Py%pk<l7S63~2h<4I8xhJ2fc8VI@( zHjZfYoH5F|MHngF4e|qH|G;C;wUwuswa*kfS`60WCfg}{lrRW}_3m2UK0jdwmgr6w znWo35RQJ#+i>auUji&M@k8G8zy-8#@;q8Da+2QFtzb$^B_xhY^<5%&N_)zWvV?HXB zD{cldZI&qxy7OlI-wCe6;LY-xLyvOj8i^1X;W%+dqGkecMVY@NxH?$Bjemx*h+!7$ zVTuZ#e!A5cDDwu=8Q@#|ayQGB%gd6A)Y`i{A?aBD8Oi;p>(K5=8XjkPkkBSgNwy&- z>b$c1g!N)zYrU)+?ovmxB~c051(vPb@YaFKG`8Ll<rM%|fwJyWj1mtq_&f_^?WMR2 zOkfii0w3Z+FC{k&IVM|65xt%xx0{HS<E@)9{wX%KNw5S0!uAS+CleWV-Dg4WZD%oY z<Dc$Kf2w&Cjk)(ff>g<_oYs?XNYy&ysXgnutKa?5H((ucjK-rlf1=I3JSf+4NNgb! ztr6&pc<Syho*Yl*F{P#Z;Ui(=oLTc6NUU;Vca(9QI@vk6M)2Y~L9{uFI0proNroCs zRw9nCi4r;ZTf6x5?_XFFZ2l&cipxd=iXHQ{xp}>~?)BFvEMT;3B%7=1&k%WrD|+j_ zF4)}HbWY#Ity~4l?2_Zs>DYhlyvFBcpE6T>mQnYRs@|S<WmNSjbpHC0Dhjp_Lf<$Z z|MB2|xQtuq<y7a`%-dA(@`exMLqz5KIPTc}|BhC+iMT_YC_b7+Z6^L%&z*nx)-S&6 zZsil(pwA540q2Bwse~?_2W!jA*?};&u5%7463_63*lP!v=~ygVu~vu4lqvWfz&n;| zj3u>A<$@@;s?%uTp2Z=krMIn{mA$T`{ir4B47n6oeSGXD6q$sfe2ck)(E;aZD3)ob zuYxu6fBe@p2;~2m>KPS}Wnb*&MwsNiY{O6&FaK`~>K)WSK4-DAVLNDj$zFF5D9Gg% zz#r_0CS@jD!<o+@N0q<6JbY{eL=$5e+{NLx{|s}o7LO7CxMYzejX4Hwp5T!f!NXew zdN2M#sF(x7miDh;SpmMT9E=EAX}%Q~9FS27kh2o#l=uZU^8eBFE^tlP?fW>Dg?1vf zG!2=_a2~PH5^(a#ui6;OGta0&tH6k?5QJa~`xrh?N!lhG2hrS2P9i8Fnw)f@)tHb= zP!N)XGMJoUgB{rR@qfMN@BeyUubx8OK8N@FeqZ->U-xz6OvU;l-l_=*cSW*8OZZ+> zP^AIsG7V*M(qV!|7?~&?0t6RNJaMum@P9lsS);snh;=C_BF!3)b`&kD<Vb2<BJj@w z>9A&#Na?r)hWi_+H;fSQ+>ND+UN7OGW8$3dK+)^3_eE!;{~I5*<r(G@D(SFGg;i?z zY52EC!Z8cddc0s&`fH?394a6%J(aGXRbyemQwL^_P;a5;h}HeUP6^m7NPmd2TH2x& z=YPe(T(H*hEaqt8OOW1+l;|OvxVaft9YzmwRscAkLnv(7a(CNne8OY+<DhgRs3q8N z?dWUU^vop`G0;{d<6k=Dkxo3!VG<Vy^BfdkHWT>?1g;C_Kg3^VL#Md;1Efc<&v+eK zK3nPK!v~<B^Z?Nq^%s<)(JDCO#iVF2lx<&<p2gH9uji)_9TMX&^nsXlPOJa!Jsd4M zmxxR2PXHc*AQwcm*Ea><@Z(mBCl2F=*Q|xCAq8C{u)24|{nCrV=%jS8GwXd0vEZu( z15flELnE;oge%rG-Vj=KD;E_9->k=N-~@DZFU63D*V6`|ES8CsMs3~sa=33})9mu1 zEQ>x6qFca>eeSY>4*&$n0$}IzV=6V=4NAB7v@U;*dn`#z9eXe>2E$sAVB#7*!d?$u z17FRH*&K%*azgbd=)@uoSja-agd_jKF?s9RF7VNMuQxcOci~67{;dTqAKU;w_z-D3 z#BbuE|DN^jKlcwayZ`#!J45d+-VkhpM)<T2IsDFUawnK>kA?Wlao(0~ieQ4Bit}Q2 zMov^LC}aR=xaK>iUF@@6V827KfJ8e2Zc<p80-JfO`j-w3tJU+eA`mBZZp@v13;64W z(wmj(qt>+Es|`FHsBFoUfFK3+a-Wuy<#8$=!b`Lpdd+-k`CEAVqfO2BdH$DUd93>! zlp8uGDizc-{ae6WOoD#x_R;?-!xdx!^X9~<MlN#KV_XDjSIms#k3ia(BJkdTBcsvJ zGw*MY?%1+Zxsr9@kTV+4@KDtR|EV!B;0U@IpHbiYSI1c8>Pb_{Ag5l}#lFKnsf(-O zb4wMWi}@|gQs}sqq;wrm?6R3uX2a>589%e*dsQz!ak(p0g9S%X=6sr+tpcgLq1?Iu zi!W+_XI_%8l?+h<ek<`p5*Kc0cMrc6H~Z_7A)OTc8#|hhAl5!S<s5_)MyWRKZe<KW zlHO3>0c0CBJM6*k`x22R`*z|c0hV78;2EQ2puvQ16vBvj=ikM@j2w%lqfjNmFZ>b3 z)u`?vr`MWenu9xi?SJo}+eI=_+=jNfqq7ivV_>v62~rh=_80z-JpP5@_-I=t?6Xi> z;%X3JE@p6)@Vf%mfCC<w&ECB2hh$$k-5W!Cc-zlwkyRIDZ3dQwGLd_0n$%lhi`=~F zd4RT!N>Fu#U5w&k93io(C_xJ@bkk6S7ZLI@1ZJE_mBPGSHjrLhXDkrGRU+=(xo5<7 zfH$xcBC=s&#)RWj;B)?Wk_j`P(WYB_{BvL6&tciNNZWxxht79S<FU~pXdX&kgvLzI z!e@cZA+*7@XmCJ?@J0W?ylkisuoRhlju~mPCu}()v(T48{I0<S+Q;%mI55utPSs0- zXcC9}Snbh;NWlG%yN$<1<1c+gWRHyB2UE8Yb^8A^0oc9|s}@rCaywp@4@R725@h0k zd|saH2Y@o~K&-)#?Vmu47z>YJRCH=d-%@uTz&xma+!pSn8xIg5b3uU>KyT>+1DiA> zW5wmC6J#dd!-^p5_$w5t56$9eaWoX;d_>jqtS_O7!B4<TB*1s!XpOBh;x+nlB^YQK z&uhI-LooP^WfS-T$Gk{zi7bZtvm17i>@|47{67<jmW1z>n=T>^DXZD}GZr_pi-db* zSp%2A7!<_ZF9DyJc2D}N2E8vivKNn+!h!*LyzOPB@pi6lF)@4kpq72E@5XKo%+B6V zB&7AcP0t5GGPh0nDRGP6T9X&1g_2=9)@LC5%!?@fqCe?E)QVN*81R^i`A|kr+FNSj zy|)l!X=~y!NWR8v)x}5MpKpx0V}Iic>u`LD4}eHnbTy_;HU!C;*H(WkSjKp*>@YtH z3JFse9$wotCVr`@z|bWP277`=*aT>9s8^HLCc85q|5V7=LE*fL?|~q+zB%@**s%~k z>$~v|P)T><7kWaz78&KWQ~EHAoPQ^R@4|Zcbo0K_x~+@Lqz|bd@oKNl=!e4TEcIWH z1u|bYqfyo=9bvN*7Ibkd7o)NGe`_D@gtE-b=R?>O-4=LXs2QRDoVG@<{*;vl49-?i zj+sII<+~II?XTY&?y@X?bgGbw`P3cK$lHmJ4|i%)BUAVR8tA!<4XAqlaLeZYJZB^% zk2ga7p^7xJQzk!6H#mi!mX{vk%uh_KA?X<efZj#fla0$9uVV9LX7o`bXOcFsfY?2J zz)(tj^?+(|Rw}aOH4xAYkBF{doU`&y{UO6}XI{xRsVTWR!q8<LL{CcPX3p<(Hq_JJ zLofQ}JP0i|(5SP2d~L67_1>)-jxu2{jA}s2brg+=ZyWe9UAVyWszw%?LRA16HS|bh zD}>>Heo1*>E7{^WJ+$;2RZJml;mf&|D%L<l1Z2Y>lT8nA`~sLp)uvn1LJLwb3@NL- zxr%RF)mp<vjMyva;hW!I)3a6YP%QbHZra<9$x)IlpI5imRHM|{)_iBW{kg_)luyuW z=2Y;&XyUA(WjF}MY%3cw+cdR(+UEMh>DJ-8{E#~hNzeRq1~F~58BVK&FM|eKcMfmh zVIip~B;u{@77_2?oD+Tm#p4#?I!;aWD`JCR7rqU_1`?y982hY|W{jwwWFSl>|8dW& zTlH=n9X6-(!8wReN^(0bs~(=Cns)LrxWzsuN1NM@E7BXRS48qw`g08ja|_W!u+8|x zLc>+$M1DAR;>XPPMXV`SvCtHanNCP#^j0vk!ct4f!$GBCN{V0^ac5P0hMK0|&2;PT zKrBtPL4JFQFWgPvxHj_hbhWD~xL5`qzq=C8Gap7M1&423_b9b-W53w(4o2M*XVCr9 zbnEn5#0ni{zg$v8J!Fk2v*tYb)`KM_k8j@^4-NNL<K@P<7V6$(%-%yd9C#O3H37O= zbmzAF54F=^N-^;V>hd~}?1V}cHQ%ROD!(#nCLP!aoq`T=V+kT0xqy<W%CGi=l;G51 zYG`Zn_kp?tewyw8Z&_0y)eP)jx&6pk5pec@3B$Ruf8fND=%HMB?LU|f4dwwc#=s|w zcZnUnnW#{RR{X2-o<fyI7huyFb<$w)_Ct0UH#>EjzOl+#ykCfU<Rt-{^nXeyw+<Y8 z4I*mr=L}P|2kTyhEi_Z%aouRww$*qYOGDH(!^m52#nr~qH~bzYax3QEiBtmEDl(N~ zY8<x*{;}hh_>OsTR=uUcZE~Ns+j`*ZyJ!TW<^?4&FEs&{o&1Uc4Qb0T9rJi~bjfjk z0_%qo)X6F++BF-6b!#tc;#Mi^=CU`%26|xeFuMHVs`@uFklurWcVlxNl~_LDu7x9y zX{k92WXc1+VcQdzkqb#{S@s*>U?2Y$Z;E40u8t`rJo}B+$+IzyiO8O9kvMRqogET; zDqH$trED^j=wvoYTY)L1J9RX{zF7Ghum$sXrJQNGSI$hgWCr5geJP#{_}<t*$g*q> zpbSZx6?;npKzu`K0s5n8hN=uJb_hn3cXF@7^ir<`NtM&;x<v3}vDnR$KWtXET;j2y z8^(uOx&@pX=`<@NyiWpWuX~0`YF}O=skU<e=F}c$4q8#Ya%)klFNqY%*NTDFU?hYR z#n?fC&xPrahAmqI<{6T}k2FFpS*8V5xHRD9y^Y|pb!)KtE{YZpzV67fN8!QD1NvEB z_Z|MS($t7^e?(j-_LaiJYDqYlq7IU9!qW^8CH-2?(2Va!rS=8a_CkqgQsLlK;Pe?e zJH7zNQCKU%WNhQ&ffj0y@^#U1{```?QJ7$lUO471l!}@0EprXJrs8npbaSk8jU&X? z1%(b*1Uwu)UGjTBtiH7OE`&o!a+1#hb6vFA?&`C~_V?$$P!WbIc;Lkc^OApf;_|XO zfi>a4G(D6FiX{}&vbkX3Uku~vNh}CHO>hjLPh(KY7eAWaB%fFo!T!y#m%=UV>Q+a= zBvm<SOB3xK{E>5ndLUrlV1{X?efgLCl@r3FbIDM&ELVJ&)_(aM_3*>TXl*lEZfc=D zga%JYD$sXeXe0S{#&?FW<{NWXny0F1N{OPBfpN@GO&L1@15|Gj0@p>ls^mP!vb+-$ zmN}z8pazF3sd&%leZrTkr=oyuXXE%V-1cK*rx@mhyrVtkY2oL0aFr^oE5e_bvTE99 zG&_<Zt?UW;XIkR2-;Wc8&0b>JwM)C*b3}jhey5B-tXG;*B;eVA_sPTyV|rqUeeu#4 zr=Sa3S!;Y>B*)-@#X>h88vMy&*uZnN9V}@PyIZ9_0xs&)<#3GK4Psit4|q$Y5T=2# zL=UOJo(d?j@J00xyb<%wJ6cfCh#H|f+j!q>kD`1_!VRCO_cN#F6--o2BU7?^!)BU( zxViVuxzYhSq}?cellYT{h)S7B6W@Q2{!Ud(4!V(-=70eGYGHNN>xn-rUd1rDI@_e_ zL|EjXq+pGVWo=pWd|r_TH6G$n&{1hRC44LK1yrQQzCe5FkiFb~O=<t;g1W0?(we<M z>j%(=V^_WHX)y72x0#;1$sS?k?lRsB^1ZerIMP{JJ3JeT=NhR;8}tx6y3=gh>tGT+ zBZ<SxG6~$)Kt7J?Vh@zFtKV}!*fpY3f{2kigv>ewu=p9thek95U$G^A0h&n%ouB4P z^z^^s7)5u)j=?y9cJI|I>yd@<17P9eX&KE0{##hX1#61d0W5^y052_HEEah4Jx8ji z(OO>}jfViQ?u<Vp?;94ssk<&{>n+3Jwc@}|VlsF!Bi!Z|23^m!m0M)KUD%9)ctZ@H z=GTi`<~s5{QLeLmNL(H7se7oQ$7n`7AzO9Cu5#P0o`+FsHh_APrqvF_v8KU3!y%7{ ztG_{qMRjFCW770T9~E}VR?nCSq%c2dpXd}hSK<ezGIv|A$~jrTL|q47FQGwhFe|re zY&-XE*1V+-$5uwAaG^1vtGQH1j}#^CO6E>gpVd006^IdUL^I$wk9A3z_5J6_JnIKa z^~V`cTwaNKl)5xY`)luY+I~4jFfNXC#369Nns<9*K0JsT{sQRiKkcq9-+TWN+v3{Q zI~XoyrbeNE@s`4^MXGMpxTp2Lt0rly4C~BC;8U4ReHlGl0L(t4R1LN*0OE)eeABxq za!GuL2gA|rDT5{JB}wFi_Xa+%u`RN%xqe0Fx8mQOI?%*;iKuru$_O3S+DJ#xtiUvD z@1%oxQ@hwtTw=@Uhq+wP`kqa>c*Olb$I&;}B@RVfB^q?E-S+h?9v}KRf3Rd=bJxKV zA3vtf6;8P3Xdt8uZ_=NsX0?S`m3vExd?ExL(~emjrV$@Am=|*?DQWcdUDzAF4b(GE zm!nPMiOc%CGllL+Lc&QMiLS;w9FKN(3@RcK6?W}5Skva~4!GLiQU3T=t(2J-w&*2@ zB8pRZ(2v+J&U{qxyG@#sH9I1qH9f)D_pXKm13EZ9V7=+$gXp6kUX_wSebYsxhrNU~ zJl-#F=B_E+>#;7uoDc$ca-O?+tA>q@{x$ood&!4mti?k-803gz2FNiavY{Jr<7nJe zZ4Tsf@V|&eT>SU^20T94hfhQid(+oN^oX<uBMTylI<9dr_K0y7W)PKQh`btI4?p&D zUES#~;V<dSE$_1GBo!^xw+&y(eEaF&VLa(baF3-X%F&KC)OGgb-sfq{=TBVTfOzrS zG%ND;)$Br@;{-PndCj*|v66e}5{YWJ>%h;`_$+4H<ghkl&s!`d@nzr)<gBWd(KmLS z>ar;xQy}3Y1JtL+Z>?^ABn}eT-m%<<Ch5|eZk7GAv5&Uw8GaL9_b?`&h@=ovOPbC- zaoH33J!>g<J<j&4ZcNMe4pVUQNFaB^)U=te4u9JG#AV)AUD5r3iVdnBaWK!e)N-5l z5nS4>MxD0`sc@$w(;f-G-0~|%ETl{i+WE23mOYfx^N*k+$DJ=Nq-(mv5^*qmZ}-(7 z*(+Jbj)5ssTbFoY?6!dras?}U#2ba;`hW$JFLbgeF1$3hO=_xGsT#6l`R`&eT0U#w z<|8etSTEoQ8{3BwwmT{vk#vhkdvM3-)>|h+dEKqZUscL#ET7pa(f65l{v_o{I(6bd zdb;#g+Taz!zS+NxK4qjho{m#olrK2h;jWNJ)mPcZc(!GUmp~8OUIx<h!%Jb-mNaEk z5g&<`-f){fh(c^}Oo0^7d)_u5vHDx${Pp7rJTB%ic|6+=`kCA=Y-Yj@5~?NZkLz(U z8ZW711!DaJB21+0KB^-TMo*g<%`+gJ2hm=nwV8!QZZ?nI8nb=tLVVIx)GrqOp}e$l zIzrx`32tx0uBGEM7R9W);OBKe;0n*GT5gc2P5jYy44oZ-Str<&?E+lV+jozPH39EH z_GDbq0#|e+w*v2>HBBu%uNtZSt!fWzB>ivW*b|pEtYyr)qTeu^Dqs1^{qp3f$ggdt z4F#@(y80Yh*x{!S$LkYEhJ7=X+C4j+yk4eU!_bB~JEf-J(Pdd|nIPN%Yd5EY6`lSP zRY<Nw9%p5@bJxyuAF_V6i5?i={=_Bx??wM%{Sop!uZ^{*m+-W!f3~@j7yYhP;5v}= z=uI8k6-p5e6%nz>dW=0gemiAj^$WiM5V~CA4e-dyCRFv={_z*7`!+$y5mo9pUfXSb zO>1$|*P`{LG(U~%7=5F|{=ywsMjN8>t{Fd1{cTmAC}T8PF}bm8E<|0z{EJ$AlEVfO z^Ch+;bNma$rsEmMWIU`PLTqRqWhM7cs3PXfTiNw-IbH*osa4v;eBAD9Z;lQc-y2*r zil24<v_L1rE7(9@!6{~zFbuMtFL#u}-AfWI!#cbQWOk|uxrIkwIM9f89EY@O`=<`6 zonqPlLV&!_+rqQGZHZlt4v*`rRM%eqJgY35`Y5l%NG&R+Bfj3<53refrI<F|fOrY{ zCTB;AFO(f$hePjzLPU3SUol<U@xSV8(xN`>rhM@hdLZK)K@01Kk0{(G*xi~o@LUqh z{!M<vfUxPDnex&(G7+&7IHtjp7H$Rfjw$FPwCd5Gyc^HQ+%8PJu!eN;d*v#z#7gev z<6=GCm+AUW-i`H;E&u&n;Clbe4ih!9{;IvY&p_G7L|q+LYdrT@KvkeUM{eR*8SSa> zopWZmnTkl}ZqZbx_Nti9a#SIchs-4gF?5#j{8UCA@Vw;B&Y36m87%CFK<U0GF5ijb zqn@}#(9de-ab<lC{?v(;b#6kNIb=Y`YwBfXOlLHzFM%1~mevU-KJAGvnh*{oOfvb1 zn78G&4J6I~R#^_5X1nEBFKl7eEHp<p(Ql<k>*oZjE+wR>vu%Un(~`$+Tf#xo<_+X8 zD`_;^q;*BY`+xC)haSEyHABu`C16^1JaKt=bT9&o;ZZUd&tHYp^<jGT9DujkHyqwu zpST<;fM@z*i?6ygvdI%LbJZFA;Del&jr7L_dNW-^EsJpcG*`j*l!htX;FTfpo~&zG zrz~yDohCN!Chf8ch=Uf7Sr`rTGIikVJ=d=u#@o(eW(j_;%6mS3+NI?2y*bQ5mBaMq zwWDq&Ta7kVr}D(fl><?qu8@f)?lPgM5`&l3CHDQ5XPfs}kjzc%=tDL=1cW3BP6J{V zc&maRA`ZV2{p;8Fgpt7$M}dh)=?klvS@Pc%q5STSBxTI?*8RNF<H-k<$_L_4cQfjV zB~vx}zK{k1TO66~9`je~I)sK9r`S`ivop-hTI@4rRY@b3+vm~Gu2oGD8Lt~pbv5M) zTRMJ6YVg^ttE}rdKCO>UKAirdGMlu1nI-(%i+(sg3x&`Qj+64|Ls`;$gv0-%Zvqat z`YbdFqef2}!V`q&Ua_rC;!51SKRi{}W<T%)eY=Rhx!S(y`!~<N_CcE3Jkz#L>QH1| zI?h~uRXap2_jJgTR=X=l&4mKyK{N}A5(3J@O#6GJ5*-(dk{q`JpNptLcDB8wv5=W; z=X~!rZ+%(nTSEn=Uj%jfbIlLkY96zrUOxG`qdYSCqpJ=(mIrlVEw2CXqa`iTH%7H^ zdT&$%e;3K<wgP4?Muyk5PnQLD**?yjq{I{{8RaOvt_mI&&$Q1yR^z2R5CF@E&y8QQ z9H+T<KMT)Yo^^P`agJv0L38|391ls#ypYlp*DF;S4s}lih{k3A(;K))I5dS_zbnCP zS0S~6l9T#eIOV?9T^3aa78eZrX#mgLL5{gsMxuYO+gteU`iFW&moB;aZ8LKjIEN>G zVK{B{VaI#_0-fh4S@Fg@a4)Qnq=qu%*3Fh@I(hQ?p8_-}A6gi>PR_KV)>BaGIGMy^ z4L39n(qlKZGS&LrQp-zoe*gKWS3CsD16B4XE+to)Rhz!CJfE*#5p(*r3A@cicYL08 z=|oQI;0*DBH8wxXfBay6z&8w`7hJ;U$Z^_)F!XTu&cmkUk)KCIQ+wala?D-0H^3!~ z=KSE33X3Z{mHk@p%;<Td6yHZ3-~;I2`{s`d2cEdRS$(ACah1vQwkq5s@~SPKD}T?V zYKzqWK|gC>##I_#Ib4q>4jp*lt)M+`>_=bhfv-qo8jja&$Q?*3Z5xU{!g4v2-StkC zA|f15RZ4fBd)xBAkr#a%0>|1G<SHLrCSSVM6g#l2SYX{Xav7gKYtlZx<LKT=Bx6fc zlNo0v$s-9jg?lbbf?sTEAW%9+!_F{=+dsC<jEW22FvpKwzUtZJ6TE9(?Xc1O&wnkA zBSEf-U5!gUWwbTYv`;b~aQox6CarbWh@+&Y<At3y?6lr@&^v-s3%cDRA*?y)ef{;s z8LPt59`BB$`^>`zmKepQ#e;gs8S#{l{$8cY+nJk*;Bz8VIq_Vh&~)6w5AWf>a4Z!Z z!_uz<9Ky12(<Nr>qf^4~nHed4{Audo6!?iOuS@YYYkIaFPYU?w6WNB;u`k#to$|7g z_Tx(-Dd|qmU=7Y1L3yyV@#`eja!1lW`d@0fBW&AY(>Y6s`)fRpqwX=cA;Dr#Z4&>T z0k8Ce+NpM*k@1q@uEwu%gPkc2zUDj0o!91X5PB!CtcMMSre_V127$|!6Rm>Qs)v{9 zFG#M61>r8^vcyGN+wP=*hFnMcsb^6bic!x|4SNKsKEGwkpwq4M`+xW6Wpi3qEPWqD z2XehmDe>@NXwi-pv}=o1u5rkz)=q@#uv{f_ReY*&v(^@sNa|?ER~Yz&88m>nih@ME z%hWJ(c`7r!UM524prI>;vYB~hMz^S~rN$K=Gb98Z?Jc30lRGs%XmuQB5Gp!um2y(r zMH~ZnbuycPvgN_ZL1RJ2O+*RT3&pJ;dl<O2V^LfyIK?#B>YxBjiMDYZS1z-b)iXCL zVb}@PSvg1`&@LZq>sROfN1e)hxSFq*GG6}afHsqv8k?3}uPWmk>iNFkROK6jKNBp2 zh}Fc0jJX2z;&^<YLHw^j92BBh-|G#Hj<Dt-Pe>*VNHFO^*dPrmBX#`lULUygl<PoE zJ2m5lI^#=s2Sl%^zKd@ukoc`wy4_QXkr`<u*fyg$zC$<iYL&Z3=<N5}9!$gEteWE4 z!E#(K36h)cUOkL0k}4QRu*9s9QL9pqD77O(`P)s5<*GTOfo58;jO<aRwRihK^S*2U zQBQF_#1$lSCd8)-qm{Pf{CRBb?1It}*VN9R?5dYKNIyT?k-b-5{L5zgr}D7l!=r>0 z3=4oCAv_&egBc0vqd&Ps3}rM5_@=#hXd-(7hjY{Ibw0)<d_R0f?hsnB@C^+YG$S2< zj@D3FzkG?pADni<Z)=&xqW#SM_P3Eu{WKryKbv;79b72BVu9Rrqd6kQx3eJv3|g)f z)*_F)rTZNE@Yz%f^FC?xaKp%X8Fby<Rw+Z9PJbltR2{WTt<MO+Xc#>elp;@VDj(el zW!jA?7#(B3eBL0w*S=6$Zy1C)kemd>D6K>5owej(maY9Jj-9~763{$3BC-m(I$Qdh z5ze0;>lB~MC+&xUsXGQFk<e6(!{grd#j++}({8IwY;<TDzg?ACgPvU_4@5I(P*qsm z5#mUo_`k>tXYLk!VSaV@>9o5%8)doZr;`sjO-%H*bis(*pZhiLr@$yI$Gkr1r9+S+ zyyDrF?TJ9U7ez;40l{))gxeEgoItsQMcUI{FpL^*2+lH-*8A+8p^zoFwan|RqeHoe z>o>fKKgv`@7(}VqO%Q`pEjXs9wpw4~hg0w-G;2d&S6-%$<r>+NM{Yhat0m~|xA-jr z$;aM`XrB!h#wi|dYcwB}M=4IZ4s>5^wTk!rc?>E(UeUfJm*#K<pRKw=8YBe6nvW^g zU)mWU`Lob?i~l1sZgH=2q`W$^htD!)5hH)=0`tKP+im>?ATDlSLoiqQRU^h2!fd)7 z?ax%?zr9>D(|Q=*l{lw5OW4w`na5D5H{FHI1mmij=*L)AgL&IfGW(@#3P)hcCPw>2 zliL`yy8R(Oxs<-?Tg@`gMgas((97$w;w)_f3g-~a?Z+R(LkwkUsrg|44UQ!hbP-l* z5iU0NL)kXg$ce=7(GnWG1I0Qc$^Zs0kKxz~*8W!N;m=<)_!7@$S$b^fHV5j$J31|{ zpLT0a*Y?(1sc%O$h?D&{b4R5|=*LUB`%rNwQoTmc(HE|;#XM8`C|r#qv(4~DovTaM z(zt=?XB|am1;{JBUN&fB@T^7uh_w@M+y&`<B;u(l3=5wdytoH9J-Azhg^>F9J?wVG zMLlYss8HM4{`D~ZHC<^&|066)jPJwK?Ew8wY=Hjmi1=^uTj1DdMP9~$@@_2)1y-sh zrzWjN7iKAgZeGhrAXi|rmLn|b7mu7mSb-{|uNx68cClyTA{@3t_T4KByJUXedc_oU z*F!zrx5WJt6W$+1eNH{k&$rSe=}!G_B2-W?N{?xrYk6s;Q7fBl->TOlJ7bz{x2&Fn zA^Rb{HoybJaGU6&DyvYp=7afbO}_Q5@zq@k0X3zTWg|C(DkUpN(U)%rBZ9S<A7?B1 zA3Zs|#q`s+FCpYjVm`ETvB89I)nJ-EqIn&WG($7U1Lf5L@;@hS|Nc-v*8ahlg#V)_ zUHFDAOWsX+PvKT{DFzunv<FeU?W-M1_7$V|c##mcUx=kF_;PeOR+JoxIIIPuM0OJn z^92G5Asn=jV}&eh(W|@%wm-S9HtPQU+?ffbZ8Z=w&?};@%WW%7UzW=2lK-#0fj_-I zS*pX)(oR2qV<hP{-ri_*X2z)TTCok|*+xVSmi;Os0jr>H>OpFls<w3vD$A0kr?}?V ztfwqW^C{AwIksBaaiEa%qv~_Z(oa$z)$-jBCyDp`tn{b<#Q~WgKT<3cP5VmLfwRC- z7F4Jg4+#PSJ6q5dhowAc)x6{%hZy5<RKODP-~X&g%S#u3bx@~FzOJ=d#tJbu_MoxT zFy=OXiX#d9+C&cqS^m$Lkgbr*BD$LwNCfi)N=GQx1{^#JK0WwGn?v6oZCh`DzBJqZ z)3bg$(wHs*)QZGSWeAzs`#Y~o{rUNcd~drMV;SSF-p7Um2Y$=q(*z;8kDv{yKtI)# z1RV&QiFA6h=nKq`FD<^W)(!_eu5^?#(+AS1hf`(rJ9OO_x<qjO3P{-|(ZA6*Pb>|W zxJ?pygr+gW=Ba<lLT-k9OsBDr(;XU&*T(up@n5u3!*T4-`Oi($=73hYsdZ#^F;3df zKv)OHsPPJ<UfblRp*!J@2Og8J7yy%Z^XDXOML`TD%3X-yM$fZoD1)n@J$=`=ZhNK= zNG;L9RGpMruyZN50teA$c_eeRSZjgxDMHH2J8L-5yCVizSR{v1#T!;;!ITD4_DMFX zyPCEMkl-(W+E)@x{d>0V*Mkeb4JcNcCYs><n1485jWbOrEAv)G3tr=?w2ez?kwN^3 zvPHr<l36KycMz!vGAZI7_nsU*!j)hjFMg3xE6vGulvfM5GM>k&aA^2WaluQ}qObR- z=E1_Qg`E<=xhV~NXOSm+He`|3p-0qZ@epRfJiyug_zGn47<C64IQQaC)9PC`Q}w7i zjhl9@SjIDR|FB_A3~ujA<w(t=L>y3R?*CKg&_NZC7g8|HE}Z6v@=rtzXi|uE%PThb zl`)MTD=TG!Wm^z15M8?*-4TfEA0$2mUfR1{L!o;x5L$!r-+7?8i3ZJIg139`9x8+X zhX6R<MFt3Rwj#uZc^024IoiHJ7HrrXA~fFin=1?KKVAvXE(THoRA7+vLGyv{!4zUE zc5R*S;|2X3OX(viRnIh4LNduM*UQccy8iyQFL9{rZh<Tg6QcynhnrXH&{G6B1jSP> zeqcst+jpn7BzA?t`eWn890lZ2B7;b2MtBA+NV6Q?0UgaU;JbfuT{(+>K#5hg%qc7V z8BN9&_N&f>Kkga!L`Hia$}AONUdFL|7AUtUL~J>o&B5--&p>Y(A1j{jCpAdeEa=Gq zIVqXKd}s<sAp&6oqe>KpZl8xs3qogY{FlB|0};P;!$lFc%A}`Gm4RW2X$%6$ye$=> zIruA;A|-^V2^+CQWCDy-=Cg5U?&-uzk6YU%CoKY)6dMX{4K>lbF-_TrfTqAZtE1j! z96S&7EMt5!UdPv5l@T__ZtbXwVc0UJiI4_PGjT(7TUK9=SuXhc%osKHv=*~AU`~Sm z7L-YHQKiyB*Z?Te?2lMLC7@r_fhc*v1^rG6)&pczAh(@r-d0)<^E$}4*iJqUO+t!L z21d`L);OqD@lbJt=`PsF`iTl`G(E;SP){wL^3%~#<qmBE#1M`>Gpg8_At10t!N9W` zCMJhwfqfTdkyZdmOt4goK@*6u!~zcBdm-xpPO|D9nAprmt&f<Q3xN8S)g7D2Ziiq9 z{i<jz5(|g%Z~CA=_fO|{Ya#B+BGwICkR?pup#`H=&RYOf;*V|^{P$86d$Y`oHbANc zXMo-jz#HHhJlu3Lh<KL(BUqqrK?7VLly4|)A)1mK#LPPUPCRFr(*Z?oEn2<NghUU& z&nMMMj4c2SD>hI*cr-%o6PKh-&tEg3B@wJUo-A`Ql|zaxPP>tNnmImxnB^fNg+Ew_ zdj+7n?Xz0OgCr-&rIhO-%$}5{CQ#L(JLr*$iiE_EtPRqYyKNuJ<7fyb=Nv3Cvmh2D zLWo--F6*4wsrbB+c?jQ#9v}irk|(bR?t@bcjj>$&)jIgTso%m&-Pkw4d#83t)vX-D z+QZmX<)dNiOcZ5^GFqe*pGhIY!u%MG17QX~!z{K(y=*D(FtZzI$UUPptvePaJTn?M zDuvH8#w}G4v|(MfHNOY7FkV~z#UE<gBmcdq!(0R&0CvM6YAf53%MIL_&fMm_%~dUU z_^z2bKs`KLz47m3H>9T(!j`7$d}<kX7qga3>=Yq_LWFVqvPs5`4i{KM9vn!gFNdU> zzp-sEl3IKInTwV3@R#Z^n4p||pk{8&XJ9#gFi#Xc1c?W#aZW}&WD5+Z=|;*SD{2k6 zX?p#MOZu4B@`ZMWKdpA0hvvb4Adh2T!8@kv&Ko~ZSAF??btBwh50daiLPm0K)zSNn z%+|Y}j$f*USUT^$g|OFK&@z3`x{k}dW7S&g<W><q{`gdXJq`>=pgLeSNjk|vJ~@OB za<a1qqMo=c>|17An|O;GeRnB#JT~H;>H2dKjx*f7oKxNXQ#?8<j_$;#N0ht=D;<<e z8Ub)lgEDmb_bIE-n=ZM9Z?FmktjoNgs?~oLOh-&N`Sz{EMMb)E#1*XCm030}IOXa_ z;HU%GY?slH!04esiQ3Q_SQ7cFI-k}0)?YtdJm+T193`{VK5?9>-siv9g~u7a_A|{v z4P~XFf$~Pn9x3WezZ8)S2=T<U@E|{av5a-=0MEWmJ6rTG@`|@SK1NxyP9lqzDppMU zin)J+{&xWZ=c1mw=u32(`?N+NBw!j#?|!Q^bG4-Ry1%9O>^^4h3AbUjJ4mpxFp8O( za4ffjebR9k29fWE&P2UsIrcn3My!_b!%Q}bbr=^NByLFl^OnRw{q(WVU#vf7Rw2F1 z=Z{wX_0e?g=$vLp8SPzu!VY}Wj{S$+uNakGoHj<Ya$xhI*MsJaIk_EgaYIY1uB*;H zgT=2u@Tuia*Y*VMk>RZtzl4kaE8$rNHPcCOZmF1Khc;4V)qV^2Ys)MCqh@B9k42Vm zWgWTlY7(MA9;Gqbm0mmKU2ezhAdlWdp(b0)(S%mxjpIy!*A;P)0mS8TZ5eeQYOJG| z_W#8)X#bdbrw09Tk|D_Y0+u9R#Zo`=-Y&R|(xYatSRiV6xxqx}0B@u70<>VM920)} z2Y%uAd%G+b9-a7{kl}Z8A$G3d5MFaT{V+T+6WH7KrH!dlCvad<UA)ZO7mK$x6+M`U z#wd?Z^m;`Ovd!V|M~v!^2pu0^NhS&@IFTt<G$*OrzigGOT^%ds^~J(@U`XU<Xt#0^ z^bo6P&InwS9Jy8B6~uQf{ni&{hNa2i5^js2qTj0gWA<gl$kwfR&!!5>(!E(idZt1! zFqMyo+;yHzL=q`Y+Ij{f2uZ3JvZ6}zSC*YUp@cSS+Y=YO$AZ*=11YvYCYsYY%0i(C z+?xP)GiT5n0VZG^Mo2i%Ho->~30Ny#RBX+AaQ4B;KOdk&RfC9_kJ%P|e(xQvnA^fO zsxb!~UH*y)_*)UX7X>;aU~0m4^uXs|n6-WI&8eF6TIPaY!NcZ8{?l=GLoYC}Or%pf z&`Spkrc5a(%~sI`Bf~%#tRU<Y9l#0<@(`?gmOl*nv|PinP1`PdZ{b`xSwZ8^T;ju0 zruS#%;9XV~ih7V&1U~MWbENCKycSW=JdJ0on0t0re>wC~0m#a`)$0^t$6_Ey(D7hc zqpY(oR94HMcKHoG*6(?vOA$D}kRzcw)XYVC2(3=pTmzY-geE==k*PPB=-(HK*wE`? zm%s{&NOw{1G|ZW<X3N!x`9Xe%JVbLHIwi6)#L(?rlr<6WmvoY+IR;A{${*d#c$353 zA?UP)J8LUcS@=!hV6Bn4bmoOHDAj!YNI?j8>|mP+_ofXh;ez3US_L&xE!d`c+fzwr zFfqUdohtB2wbx=rT6=@KW3#jF)Np}Xi1WCOHLhittvJAlGzxM^P)2%l#=&~PS06%z zn&T(Mijbh7Da32$t6OsM@-#Z0Efw!J6BP-2xekH|PYHGcdi!zFI@l%1BeOZU;^7CU z0A_zq7qFFv+ivY>BdPS>^)aB-lunr+-b@Jw!Oc(c!>z$9)CM`iRb1<$2hj3c(PDwb zVKZ^tdAetDNNwIX*Pu6Yu=9w5T(B3TOJrn9MSkp#EHvUJ6EDDiL<TEXxEE&G3y`FB zDZt4>YX!dxOm8BGJlQs_xF-Qf0QgZ?JM|T)TEV5kIWaAv8+MgFd@js8@!6R%|2!Xv zaa#=T2yuZL+J@u^Dfne0WoZ-QC7Ux9LWo?PT_QLVdr`zy93qp(zrZPij&Xyo17``E z_gzsEg4+mFV!<B}5Wd8Y4Fm|r0SJPozX`flj1OKgYm2~#UQQ%s0RG#i=4M|1xVDo7 zJpAFJF>$C24MD@q0s87jqNuwl4s+QC2Po)Y>>8^3X9fI99<9W@Dx(fA1Uk7Hxtogd zn-is`vQY%F;-C$}>BWO6Mamoy#fQ9<LAX(nEpYz;_A4DGpBe(`DCq9bwlNWDTF#JN zI?-#pHjcTO@OgeZ#lu#y=)>j2Ul-=(wFE}nZb??{g8NuI5h<=9AZ$NrAa18kaajVG zJ)QCZpR{Rlc4@1Y3(x=1SkWo89P>=OxJSs+&MJcyQpJ2{+h#vkHSq;ThIvGc!g7d^ zy}P!@ey@pSgL$zVF%Ki1|N6c)?!=J}fqS$v4y{pWoau*CF6n;UsFNvI9O7yqQLRAt zpdwTeIeHI>poxbFby5^_uYxpO!!@YGeL9-O$Uq}B9+)>xid{pZVknlv={2UEcBtL4 z#`9yh16hKT#bh%%*;^HO&b_C%ACd$DG&W&Cp)0-<d${-K3^rQgys1ubBhHPQgBqqW z06=<6aLR^V9)fm(do(QVwRLAV?1a~(2H$|_@3k{U1l=99HaeK_M0OAxJf(_=+)?LW zFpHIj(l2^hjSXiMzFnp0&w%!X0P6sZuB?}_yh$9*m+{xVhOU0HXwX~o-G7g-0WyIh z4{|_htrOHf#lOyD55T7y&lD)|tRMi~xzpyk*zlN)ZFf=#SPa2qPC{`hsVp{$fH#VP zDbQqF4G;+<krl9Y(UBzyu#Pr1w|SF2rAbaLCc59JiytK-ERb6uU4GJf9Nn-b+ND|d z8lUSC2^SJqH3r^k0Ufn<`J$<6AaI9HhG}lBDhb~%^)5h4*yV)EMcAux&rHIL2bnV_ zhsGKA4ufbE6ubg_fzHeAxWIlTf(`KeTZJ46-e41-G`U~KEy6G%=C4r==L8N!1XR&R zsTsLvpAI`<D<-;m+OQOXDoCJ?!#<hNbMP)hAG_eMf?C3103T(U(}`gh79w1*tT0A| z;ULhe&yh}vFXk!WReK-8X)f&HDw6OuxM|>7l7TG&^oYc~b(~N_#ES(fD9SLE*nch( zbVG<pMU<HCZb1TqAS4A{X}~BLj5ceJe(Hyr&2z-ztRHK@kT_sD#ucQrqiqdawg%Ix zplJ(?AO^l{IL<D|63Ac;twdBg4&fKAhda+y42kN2R@nn~fIfVkBp1v9=sQ9+5o6l0 zMZVx=(c3}pHZvA?mEj)MBY=ktT5ie4u3+edEy(0H>d8braz$`ogK$kuJJXE>h_ql9 zDe}a03^4JSl*->EvZ4P8-%@d}9Oi>;NcZ%3o=f@=<ZudOGqo&ucCwBnTiwcu%7D6P zRIhRK2o_FBKWso@o8kziaZAIC;Bgy;{ROBZir?|9DjV*r1_s+0C6={_AL#r6zkt;* z5twj*o|}t8PCc3y>ZNEFJ=;lP(M5A$n}+V{NoiICU>kJN{hm;PJwU*Q!F6Muby1GG zdl);)XC3~r934?u<7gW}1LDsZn?YuQTts2CjP}VvBwG$S{2{nJ;Wn^!@W#RQr(5l{ zp7J63Us#6XERJD@QRUf84e7|)zay>TS6BO0($`M58+j1bN;Ob?A=TC72LOT27i`gO zvM`ZSMQTkQGXGDoZoWoeAI{4hgkf?*;xQ8=6;u$&%Eq^2CdOp4QOOW!aUUNZ^ss*E zfJcb(Eh``_gF0^UIeYD31bMFLS$YPyO~?ypZxs+MS(-QlLtxQz4v(|DmYlUB^$x5t zA9(Hq{=!8MH{ABr@IVGjS*W|0<Bsy_32!My3P`wFdKfPGPUk-ILgAAN`j0cR8Io5p zJ=lB-c%fUd2H@)lh6ZL}Kx^0$SbD(=T&(C%1N^X!ky-!>wos1@>F|(dqv@0Aa}dXZ zJPG$n^u$GQW5Ylk9Zt1#`uj!<SaAlhOp?v>@vB87fG;1ut28u_#2z%59~@OtJVTry z{~J$p+)|oT5fKf@m@g`0&tnTsnkL{3qqAL(T804Ax>1)>8!*=dcxvpnU_71labd;T zRTGh$L}KAY1$pCe7ON|Co_QLe-!raO1?JbJX|`b4p0Wme3dV>3f~`3K6J>sn0Ns#M z9HyDFEv2C~fH7J;!jLU%K&0TaF2>x&^Fo7OE(}QETnPGrEPtP%2uTX+DCFq*jed~h z*iDw93iIeIC=<N3X%(caDx~1uYtF5qvg5l!7@(yP#%M-DMik-((YlJ52-*Pa#cM4Q zpeJw~W%xNr7*v?CYKX7W_9Hz@aVbl>5P7j8mcsai)!&J=1DZq;A=@P5JKbDy8JJX( zW*ybI$5@rsB=xOuX6<+4y)YC&jm*dlb|Y&mPN+tJ&TXIr&<i89m*sVIJ0@HL?%AXP zzIJ?U@0^bmR6Cc1`V2TIQp27~*lIx}-%Y+ATTTiq!BRaMI6w<=>_%BmB~X;0f~>We zyQ5aRAB&Q-IEHNEyGL<jKSY-S>`9;b4fh8|%vO;27gW(&bY~K4UD>-w!g1-uAMejP z6a6X<5K_4h)k%}1Sqb|+ZviWT<gN$k&1kT=nG>2(Ngcte1>seJZ86+o8*i|9AnIK% z05HO+nuW)co3S5vLFQ<?g#(J+g2rqF?RERL>{Jd+Hb^-4K7wO!JkBE#tvLu1h~BUa zV)ajlWdzO%_%4ts;A_Af0l|Vgfn@~<KJv00aS~~}c$h}KguOHj6^YkvEh_IMl7wJs zQ6gS8rg#nGKNZSqnUa7x9A2RMw;-45BKK<4n&Z^0L?jJFY)qUn34+as@mDq>*q~KT zQ=_#LgpjXJay*5eh??_WxbxuU%3$J&1s69wLG~wD#?8-{AeJRyEF5xnZ-39B@7!M# zO&u^yCp944sXqy~NWv&)9<mZrwMP=mBMVQ2bap6xW<8I>w|<QRG8$Hqbm1%&N5}zy zyBlB%*^KO6M}cBQ^4XB`Ec*E=sOz13xeaMTDnV|J2r>u=Ba?g|fGUIaNt(*cKG#Ux zM3IZQ#~nBcox2>p<XZofDa<{V(n*bG!&(GzGZx1j0@(0fCIY{O{O`0&$dCMYQAhyi zkWThX2by$H)L<Invc;c=XGG=;BT#3e={!{r&;k#ULD;E&016GKBT|JiE!J_Pe?T31 zo*VIKv7<<PXcqz#VwbH_%IreJ9@1!Z;nx}FVzLrypEkqho@f%@!TZ9b4E=>fQ;O!2 z;bCUTnOBP7!gk9gg-_w&i^NB_VgMQGPQ{ASqI{>IeSCqn9A)q{a0TL0*>1g9>h4rf zoAOwF974nqDoq<COVkl*4?-AQ!OQB|Mys6*XX~vQGbU3aaQgQ0K2?^@IZ%gaq%QaI z=K>%Lv&|s0WjRPA{BZUlMc^;!p2eC_fy;&U6V~Uy`IyFx1kD*cM9hUnu&E~*lf!-v z!|mO?DJ*p3?K6}0*n5Ko!*HNSAj$RuuZJd~7@UV#hRTWOr)yBPL0>9Xem|vktSIVv zmhY(mjz+3^M&<`u$k;~&-uWow5fa$+az<oDVanK8FGExnX>64^`Q$WCZ_pC?@vbd& zuadB<b%tI*ClnhLVOXpb@KzS29SDW!TFm~GrFj|RH@xcXIop)=7=H^-8OZ6DS@2cp zC(?luF;dOW-OFF(=Iz#w?p}kyPCFv87jvHhAxoE|l7ZzI8jr_L&Ni|k7bxpciH8le zvmB06OBW0hmDMETE7G5t1PLJgmSV8lV8bKMHK6>ZCxKj8FL|lNn|i<_rvqp}p!)=d zhOq?sZxH-&JCfF8Qb!88V+?9RgVzIk4B+1lYJH?v=&oTa;Jawoa9Vm$YQZA%m+`3> zvUeo@A&b*X*z^Q(NSt2Nt#%z|18WsvNOd$>3AQjkdsK@ZP2sb1)A>5Iuw6DF2^j|H zJNst_Q|E5X#S%o8gPB|g(#-!GkVv-sG(JT8c+jNXN)LkD$qT^>38(X#Zu__^@@#@Y z@L+6}-p}c-;1dBN9eRz|8f4k{OI0L{Wv27o_o2_#;E8`1htgFCQdXUVlNdS#QNuts z_zp|Q24{`K5uP`u26%>RCB*6sk(B7`d2)ckrx6f)`n>#!%Q+y}P|OiC58JIV4ZqIl zO7Wdb@EkNfyD@pMABQv~ECsgsEg&7JHndnGEN4S!50b+=4O<Pz9?F_$e-8j$uttNX zc3OQa@m*l3Ef%9rh9sb8+jOmN4U+=`@-{V$QzQ*_+hyonL;Je_l2v#(VqO}o4WW2a z!SxR&zn+rG0D{Q;1lN^BMS|S{(ibZOLn)`|9d@+0V>%zMEpZe)Dcnfb|FL>5Ir1}Q zTs&~8lON0{bV>pX;E7s21=o#zNKjTB!iW<$#HhDC$J9N`N4r0ajn~X!A+t1c|By4b ze8D6%lcGrG$xI;=w>2yWBG+f%-6z!)gbN(GtTfE%<l!}=$qmtTGf<DVPU6pj1P8x> zgbMvFl`oQ~mrM6S0*?b6zckg#LUIm>jzqI4r~V+AQQTBMvU#L6uwP+8Z-A?0Wo`dt zmU|k+dRCgkiMB+SqrqN5D?4H-Mlk^V5pO047~;f3Z$hO89I)sEwgG%1VqPOOAwixJ z09&0nR0{Cvymc+23Q;L7!*e`Kn#xFiyisRdR1C-_UWeJRCy=2aQlLU9bqMjW`tw2{ zg2Rg<oluI{&0I9fu9NX>mdEhqF_7~C0l*J&X#Y9p9wakaTnHPM6F>ulECT=oDvHBY zM<Kwow;v0+%mgqYY4zDLU-udxXc7ad0k!e-TQrU{EL((y)e8}ci;x@ZNq-+@9#Xmj zn*z^kk=In`zAF>3QQwOJjbgUqdT$@$;8WBD^B_xueVh<hE|k8S229{6$@;{li^HB{ zk-Uuf?J)<ovXxrIX@?F-S4tj2=wlo{*MPL2E}$*qAyT-)+`zIx*zO$X8xS`FF<1kO zzW6Y@h=sP-0ja^ph=&2d&Y|&JM8OD=c=y2Q>O0Pa1%EUM;!Zh);amt>9k(KYgmq2} zz13`qlI=m`@nV#q7iLET?2lo)FEkL6pb>9>%pX{m>ct8odw$mjcf~pqt}~Sulsek} zc@A63X{k{$$A>1-8t(^Emo$xeA&BHiXYE))R~2D4FU}220xmoAqR}c7Ak!z$u?m(> z*nz<vpo=$>HsiSpU%f=21QD115qk1^AYQ;bF4vuT7EKkPjvWugh!9G(7oWLE`B2`0 zNSs7*VI)_>Q3-!g4u~@{8WIMx&wwZ}HkyG1%gDNJjd#aM0uC6rf$-^h)(@1*GAG9* zLI1L+yw>^3mjEqxyLjL?frQXe)4Pra3#lW1N$_fLZUePD$u|+#z;@R{WRBvbHPRmE zB2v&;wN)qrY1^(nHFsQ1Ql4#M8ZaCzC?bG9r*Uozy2i-`<1xnk^BiI=#5bT0coQ1D zDkJhS4LE9S9<&hc2mC<t;v?```Tt*?2nOItEy%$bhQdb$L_J8p8U$@PzklhHiRR)L zkqnZvM~Ouns%__^gbXg(S#TkzKr6=HAPD0K#qY^-@k=5bFd8s)#{c!#L*s=8;STet zdQzIkb`>i&9s&*IH0ap(FCs&F>u7H>dcsGv62Pp^7a5c_rg0Fc0G+LpGe#C+*F~uB z0!G9h#kh(6IBH1JOlDru7!)Bu+g8kgl&R9V$A9L_zN&PrLsSA@5jYCAw}V;cpe_YC zI}<M*&nOi)L1?RV4Za$EdR;gKe~#n3%b^1&1zOl)ECB=u`3tnO_1VcVk5qR%5Lf50 z$gu6M3~nYiOA%5sz{{<iD=G<PF_YaDZH_B`J`rFHsAC8;N_QifsEPJ=eMnAYguKo; z7lbbSRn{Hg8qiJvqZi!c&a^w9EZWUHq7h~_NPBRIgHJD(6w`ZzfCnssr1DtzV+F3+ zI>0Rrntz|o1%|`VVO1NM1<n)EE(*crQh|h01U@A}_)O9*PQz8?0N8gOSc#y=7d+KA zga9oEA}C~1P+5ctnZJ>(cq-f`9&#}6PH8rr=k0|zg1QY63n7`0#c$m>8K$1Nj-Ls| zYY39~tyJ4Axb_gTqAMVcfmcwJI}`cu87Lv}$xhq@Gt~8Y)ynFs!*%4I;#{=oOC=su zA>_?0uPYi!maTMjlPLN4Rv|mnLugONwUWI_mMY>R7IetdAy7nci1J5uj`mm3itMw= zK{u%7W^iv~x80rwxo2e9JLD2$`G|{fJXRohU>)C9&d>YQo$lw5gJ@lx=DnrwlSLrJ za)NZq_wlo<k-L&gV+LCRG6j49Tx(OuKSF;=9aM`<B_@8zxBm)+z7Ed@gHrGUo%{vt zY2d^|mZ2)c{bYBpvKq@12p|Bp6z&>V`-F&we1qN56AGtAoIw#Z-dO)>oDA^5)gX*F zi85yI#oN)6A_YvW2WxdF{kTUMfmP4SA|15PqS62(Vjz}fWNTwj21$}J#RE1$uEdsH z#L&H`r}oRWBzJV?bg_px81?`#8jiZi`0ZlYzyPPWZ>I-SyI?&H4PjZHbf-c96Dv}F zp}kxL1j@0pUCD8DF&*)du1>?@3bAE~bY~Umio(nWOo;Mq_6A_iA~eUv{nof=sFsLR z^*`ZVBlH0!wILq6gH2+SA7v_I3xSRKXk;LM4p41?Y1aA6ZCfL=nJg#66uij#L8EPn zTx~0-408fD%mQL1IOPD4&#8VlTR4PP0f0Azw7`KL9Mk|5&f(+RGiA}m10nDJLw~LX z(Szq2In?0CE^vHLTYJ*1u{&P5e(jSdE}T{@v1Nod>ZKpfy^I^8d-#DRTYq8xRsiUw z4ND!N;yrGY7y!9c&;}O|GSgPC#QMpk2gJie+tMtR4SeLeP-c5mRy~+P$E?852fkII zE(Wm)mWxu2DAJcmXtWR<g3W%5@hbm&z7ZH^8V`5RI0UR?pPc4uFCjW1*5g*xi;8*g zHdw*yWMNbc6fWKB?fR5JM#M3~j;lvMnhW0Yu?*0RkRS*Cve`cKLkS4tD^$k$D;wF3 zSLNMc_S*g*2iBo-6mCsy5G=ciOR|#k5N<$!di(!WG0Y{@VfyqEZB{NGv9nT<N!w#D zORFkYa?2Q`QN@z0_NlCiWHp8xiNii&hPAj6+>-8MR!xjGtC{4wyXN>Etl2*##Kt26 z7}Q{*3lR7K$VgJ76?952s~)l-P>glf9B{_cHz+5fbE^3?TkAzv->pW7z_Ay_!9zjt z1SnRzk_wOt&#UM{w1o#sCPD_TX*IYC%`aHYK8aMXa(GcnPdL~fU~WJNrh94)Nv_Js zDHMwo>*1VoquuH~7ZEu6T-QI}U|%-Ob+oOz*tNh3a8RhgnP!XRF~@#F$cf^effWtb zdVhh^b}Q2EDMxl-L>-P)dIDdZMr1}&n_+5*c~Dq-yLr3m`w7@D!<~d1m}>bZ5xmg| zg&ITsnU`y!yo-dRHI3W{B_rPMI~D{k{k38oh|a-LTnY!%b!<dTE_$=n$*C>r3$#~& z2>@0m_%`FfYByk`R<e9Dfsd0deSu?sXv&u*VtZeV-Som&u{=G4jf1tcq)&zI&Kd$l z@#EfVlHNq>B^!b;3<r(5k8h_C%c>-xOTduTp8TRqUQd(BQ>$^`EL1OyaBSVH`2|#Z zmEuL}A&b<Gn_F=}wSRT4=eIwNvq;}f4<8%e48^-xh`fie7n$)_=Sw+&oo>rv!|%1+ zHal23`ozUGYlr(^p~wO`S?)AApgMmEjQ`IP7y#<@3O*lyRk;_nCuP9*fC&?!n895F z)4W&1F~t<<h7bt;5ciVv5!Dr~4TS1%5#ZLc*~(s`QeT4KvLV)HJAQ!QQr5SmfFUV3 zk>i8x7Br7+D_cg*12X~9)DxGO-5vMQ{;0Z&Dp5c87Hx8m!8JXgZCfOp{D#}A4JdoX z(#;fjbg(qUStAl)s;Sw;orZIQg<tNdEMffsGDc^kN3q(Zuv&RWj%*t!6}_yN&k8*2 zf8wH(mH=FqBkn@sm@mqPSzsK;Z%YS!Jte`I*oaWYTr5a0`WeiX*r=5<t+4q&j_`z0 zt|fqkWoQ%#Svwz;G`^HU7%W46s0dp#U+QWvQ-Mi3{Xu=mX-_2-o#Z_U9EF=eeIsi@ zdV|sA<X}@;4gCo=5A?(FRETH&KV%_MEu_l6VjpHGQs%mcuz>kqFE1l~Zmk)Jv-oUM z-2110_v-f>QF(I`@0l?eDjU=L8;)BV)D47$1WM>n3m3e3#~O<X79gM(<zjyn1F*nE zbDwxvk5r}VBKkV+i^RfKtc~BG@;D<8x(re0Dsc77VThid@NQ%!spa7{ph_d1h}r}& z*+&*qMgzSk3fmz0I*pvF_&jyLX)4<MzYGZh4abvEj)F}y-=*&YrLpiv^#n0_XG7-Z zL8@96*7!0<Mt&_ENk9*Y_TwMoVWtHx#RC^OwaR*xg8!5u2*X2sX1@Y$O{kjiCdr@# z3VbSC5pBfb*40=~aL9NXgq5Uz<!FnO?d(<c2i(DYZs)2~DbC2$>k*3m2xnG-bv%=d z%{5$-9Ms}yuObL91c_jWB*(dr%Yli(hk<{x1Hn}Gif{fB8fb{dLqNnTJLkPLPKc(5 zgXf?ngNeF3J>hfQ-8`YjXE!0-kokv&o?31!Z=Umf)cW^we|j+xMe4;&xhP%WA$J{O zO9lzVB;$m1{vpdw^mHlfQ^*u04zupOQLP7EI-5dehg!ZTe!2P=Q3Ic)<T!aHt?eoy zKt5eVDcREz)?n67n{bA03{}5JN|jGsHes=p$%obJ45ALae-V_t5Z@>#^kM5{U)%wm z-zs23`=Y_pM?rX8TX)X8<g(DyoH-5Xw9dB!qY0j=j~#7;%ZT%w-iUv$L$ApS)PVJ{ z*J2ahNi%=a#2dx2g4O>WRig}nf{&xkCwasA?<wmGKn8djRJICF?_dAtPV}e}ph#~4 z4~-4%2G3Ne69~HcEv>1)uW|(p`TzJWkod2F47Ld!`wKnqUOv%j=xPYZnIIA;K}me5 z$L|~<J*wse@V9R!H9-^6V`1x6<U(EKkOQPRR={6=dt-!D-|z`JTNDCfKm$woe|FVr z*`p}b1e0_lJD%XlekJm8q{t~9=7ZQ`B;NH!Hm|r(Hr%Cfau`3=O7#_(dgML41T;8; z34&{u#)HCZJNx*#7goYH5hR*@3~yd)C$n~u<RJQivw<oZQh*-#*QH*->N@ciD^@U$ zAln!uXQrVGp0Z@#2U=h*t~2!Rj9kWCq6yH0@CRCKap-<EbIBJuCo~myYep0AQOOn2 zs3!lum4raQrCcq!FM6R2m5(l|wlS{bGFXhBWSRdGPels_D?6>Xe~J6_HrOdXr4mBI zmN4%E!8`t7jW?`9VQ#agOHGOd>rx2wQY>qrd`=AQZ&Z`y57HIVYJ}-^$XuZPP(psU zJ7nz>mnpe~xj>L)vTH!8{<Yky?4K*a2tdAj%s(^zdY2B(Ro2Q0?@6MAB7?gRk(db5 z8-4q~q}+uX=F*TGR5?g@4lbfBf^lEOpIz>RCj4ox!Gz4Fa>q;A@Aj4<N2tJ4%cT44 zm4|JMhK8A)WZoOh&dl+5_+5}}$;~8(c`5@b#FaG_%hiB}2#?W$Az9%*t9Eq}ML_p| z;q8#hrD*12;1JS%U{TC3z#?GiTibiNF*H8)-yz(VLaCD1=kvSjY{F%Z02)9YLZ(K$ zHEv*4nl`6H1CjJ3o70AZ0^coPd$&Mt{?-VU5>rwu$6Z`R`RIbCYXesCnAMq5i5RtG z|9PY3FA<mgh;eJvtWVJyEwPNBrxf80Sv$%Ujh-XoJhWo>vRSA;VpcNs&>LsP$#n1$ zjy+Q?4J7N5T5&*;bkOkl*U*Y5E|X6`aj{PbNYV|;b9p4Q_N?HAFHs=w<&u4snUT#o zS|Fn>xZsO8sI%tqIH|dkDO4kF9Qy$yo1Ew#8@oSm@rwg(@|xBwCBp$Eb%AJ0!*!!U z19%nS8^>T3S|j~a*zai*;uJ@T4@*CI0r2oiKg=9dkb6Kv)A;KgH~ZTOgx%s^B^jU* z<8)kUcqJug1`>q~bm+Ibb)(=ihWrSAXDqTD<)5hMLB9k#OWStm6Mvy)E&Su`nz^V7 zc>C(0->R1=sT4haeUOaBY-1RIyx@n6QrZQ}wMwumA;hh;80jC%)2ZB#TnS|(!8Xz> zNAG<4V1Rl!O<pUlSCyuKn=z^EKM>JyqWvxRH1r6zHoZ&AMYIaEN&F4Xqc4bF-G?Xu zGCVDnD^kEVkt2Nxo_IgL^bN3Vp7)BA%7L&D0^SE+am?IW^U(1=su<&Yh4VyQ{L#O7 z;Aj`xFJ~OhQ?V+4QV~a8Xg&akZl~JAP&lk3AdNKU{3;m=#+fgzYq}7QcP3t^hy+j% z#T^dDyH5n1a%Vyhq#v|bI14jHM#{ElpK2rv8H!;FNmcWvC7us7@xai7nUO;u^V#k8 z;FZC$Cc&~Dcz__!Cn<Y^WUs6Yme7_bF0u`%XS-(2*(Xb^4AeUwOv4-=gC8~_zW~AO zE?s0x-}&m$>c#6((vl%jjf9=fW9IKW;VFVE9a?T0;*RfJpi+dL#fRj7HplJ`741WZ z15<(%6oX$mM}|nm#LIN1(CIr*oi=Bk)x@*KNro^4-X#P_l^~y>oBb9TRxCt0naUw> zoRbymX8QBNeoc1`(cmmW*V?E@p6%LkMEBjBKdE@Ux#pKO;jAn@9?lXSR0V$1&K$PQ zpwRWX$*GQP3V8-k+T#LiNO$=PHgY=u;+Jq8P`gJFk$T+DB?n%YeIYdVVqPg&61|~U zuFc2sYMK(z%m!a4D|Z`Q8q^22n8X`H!x`n4dj(iph~ZfM3x3@>wqX99Pb7Yxzmk_E z9Kv$6S&9C_cl>Kkt+eh}FpV8q9GuR0{fobo*tQVPiH5dv_qM6pA{5Vj+)$K2YtfRK zt7otN?1mrS@COJ@gSq6P21)2Qc8d%Gum2sBAth~VR%qtutw2-rkxt}R=o$$HvZPrP zxH?jVTVkJBvbjTbB+XM6I0zjQJ}X3rzlX*W&7-47<|^wOmxiMdz3)Q>MmJu3Hju!s zVRYP-!F4=KN2@3B-iIh<UEZxj!>Wh#%MB18ETy5+3G8&VeW+NZ#QN+!TxVbe-hcU; zcwj%dmBtoN6q-bZBH7jeE!YVXM!Yu7dBDuCLZBqDyvWccS)DF@gq;GXL7)g!jysb; zhA?=gUvn!D*QRvU8#%H=tA;KASw`pvE79kk=RYd4aAdy76G6$6yz~yjXt~uhg^y#^ zQI;=wC6_jKnA3}0g{;(zLy(76DNs;GT=O{x%f&Sb?lD@g2LOa+b?^;{3ccF$$x|^M zO0IfB7D<{W&js6qG#fU@ujU7fkw2L#i1P3rV<^%Tqx7aVbX|;wF;*f16=n-MLyBz@ zUPjQAiYxO=VGhOtREc-Bv!@~(p^)%nYNK2SIzz$haOmRQU&BgW4O->-*^T}0psa^q z55adYTG0f9lx7WCE60G$)$Dz{QTqX=uJ73HiIl_rxU)lO$>ZmOf<K##zD^Xr5hik& zdnAT6fleavImCfjZ%jcIY%^h53GnGE>VCHVq>eS#01?ste#BNJ;uBHbccHR_nJn=m zyoj~c0Vn8adKsbm=XdGug(LkX@OV%OeSR^qki)NKxDRuq5%x*a@7sq?7whl`p{0&O zpsXsG)=os)<K0gd<AuJMg8#H0lml;y!#sGX@@W+UTjU3!idFqp((!L)WO2fMx*t*S zUJWaI6UmMul#mHS(m9@#Q<3-ly$21bKH(HQ5AT;M?55))h#M)NUp6G-j3ZP_QO-aq z0y;Juu2Y}4DfEh|2>b}L!inCV&G>hq?m$nxCw<;_NfXs6tw-#S<NbdvoqJr=W%kFd zbk((u)GoV)(#jZlWf!c}M!vbZjf2wU6*Y)Tj72L2Asxe+(pt3(BLhfi&bWdiN}6{? zlf2Z3n3JFqCSo#(fZPTJ24<$;`;5PT_O&Js-+8{zbDncP=kxiTMI9=B-pS0nej9QN zEjs#n$^PlE;JjJA*+j*Q$S~4GN=ka|Zp&jCZRASyA9#jL_3412m$*7Rcu%*<wv_6o z@Yp3fApNy0&>>Lgpid}UB_fFVY@b~EFUG45{cx^zGN)})0^fh(!we;)?BtyXob|eW zn4bt#AAf7w`CfqF_be&*P%Fc1Cxg8;Ywev65Ee^+>QI8`TwMG6{HtR`aT$d4kH_&5 zX8&hDrIBrP>BE2cO4iQ8y`D`twD05l>oE<tMEH?KTM=wggA984@j$M*(2fBB2;t_J z{z|ps>%Lg54a2qSajIq0-ynb*=!=M*Vo`=`42uk7Fh1Z~sxtaxzkS4LHIGx2`OcLq zextSOwT@I%r)D7M(yWCf{k#7v5?jOxc4F!S({)%fr%rB+O;sw{eMfPc&<W-ejFTno zl*`8g{A@fs7b=lyy5{#ylR4p5$<_);dw%)Tdn+;m*a6VoO7gvzA%j?A`*TH>ooyR2 zd%`2+JT57Wxh3m$cRrdt-_#M%(bhREYWIvk|7A8J7{1AR$F~!PFQ;qiV`3H$zqWBu z9yBlB)9$70Ww;~H?DbrG6#Rp7K{M67h@}M$W&Pa;Qgd4)o7|x|dZ?BHqk|h@n;XKw zG)h4dgN)@)B~)|3qKuZ*__y#AZ>bB%vQ)H$qJuwiq`s6-UYQGtIf^wieM+?-ODhL! z_cq1eRao!ttxl+n=If7yVDSHi#n2ItuKXhC#|a_4yPD$woA5)nPi%edRK0HWi@tT~ zwbbzHHc@A6FP5snk29<g4~sH%L){5B2kyk=27v@c@U^+~mWF0+2x52idnp1~t8pNG z-lgf>5HpP}2Mbizrf7<f(MO8|ujH-nNQ^JKZ=q0*)4IyJ5ZdVy4Ks5=5FBkI!rpRd zG|G=7`WUb1TfJ?toF*9uj;RXK1>0qJ&V7o`(5=XEw-!zN`Ig4BNySSl*&&8n&}NJa zw2~sJy)|<Z&(yI;{xcUg5igiLKYUfg&Fz~P(RRs{xo7cnmT2+;P0aBz_o}!JZx`;l zwdnPe0Ts%=A}PJbx#cjGfza~^m@E{gzU>@cJB4rf&MBi(a?H{sZ0E?Haz|J!F*FVG zPPYE*l%9m%MJ<q4Ohw^7SL?7&hmL`If3fEPgH;XDZbPhDyPcekH?eBR?wLuU?wQ}E z@)pX)#}r-<lO|eUJ#EJon18k%USoh9!r#W<%JW{K{?cxP2PNVHS&WOB?-(10aeQLt zs|H|j$~k0K#+Gr@*fsrLI7z)$Mf=JU<4a=-zw!>BBMdzOczph-bIa8o^Rm*QzHVbw zX}$X>(>YS1uv~8rhX7a<GX9~=r?su~BdioqM1Eg*8Kiih_;C$<vc~Bc@;7_uEtanH zt){%oIiL~8%2JpMJdtv*tIoUIdJC5i=eWB&Kp_+C-9Kma9{xg3XMTLLn&vW4Q_+yI zx6^Na+24lgW-^d%!xP$O3enNc5#17&R8|)OrNg<!+C9adI&Sn`G~X)nar<={X#a7| zt3=7i@V_MUXx{P(8=GC(IDV92X#628G(Su~>2IvBUe#B9prBYekPBtKsH~_ik2_31 z)jZ`eN|9s2VZWE=ZA+nvge&CBi8=2oUp&D~g6hUMsR0O*X3f;}o1bFI8I*>ViL9fy z){|6FtST}QtaW=~U%;p+&GuS*^T7uXR7uyh_lCQ@hmXna{9n&>Z&SZ~p}Scd6#Wbm zgkM$}T}k-9L!2uJ4xMh9?C4%;Vs0?PpY-$Q97}yS7s~S^0w{CY*ei9RkIY=GZG~^3 zADZi3z%Bk+PS4h2)rNt#r)Z$~s@ljlm$ltavA^$wydtihg#39fX%=Vq3eg7FuF@&< zRx|G#A8R5>{p!r8LsB9HZ`@v~g*?xb;Aj1_$8C9Y(@Hj$C01B9vm>oWAn^9gT=Gw? z`Y7x(P0uX$B6S5s{;{h3TO(fk>F4q@qHL-z`yiKAepXN`H#}Jl*uCdcK+C>dPV<;e zT(_03<aFVBPW%r^M$I=%ICZ?gHD<3~W$Iqk;WRXNEYS{qJ^t5H>&++A7^v`R8wHJW zO#)7i_ld^@T$~aM4q3Z7_GD5E(umzQNkx{am*`>k`)=F`*Ouz7zr7hnYnnFe&yqNO zaiYeVqw_v76`2ZRNjma!d5sJEdo*>FCtXE7Yfo>QjUBnrF$eB|b`y`5gidRT=lZur zP^t`31B6SVI4^u$^L$R{XY`#-TAX7X6mf1&?D*B*f!%+=JTPhbFEo_8ZSW6<e@a@P z-u>a^Qf|LQ4Hk<-pV)tP9d3@p0#SL!r41oHTLDDY6+d^O|JuXU3O{Xgs1t7Q$IT$g z*})jv>WJ{=iZQpCwqGf6LcdQpdVic*Uuz!wd_F99eR2FP0+t&6hx+?@8s2%$H&iEV z$ReiAy>a4ZO|b4}W4K?4a;HLtlnV;eajsSp&h(!)X0&K)ewD9fG0%R_TCX^UCJP0f z(gu!<A!<dYj3k!!w`)LN_L^ZU8h*T*LG!CFMCNY*2ug_%YZ!ec_h72>o!(gAu3zff z#0A&X5Yhm=+uU><eTsh)<SMi7U?sv<`+1W%Sw0bCI<q2+o^zRx5+k289`o1t=PCEv z1tZv=youH~ovX@n-fazG?u#QzdHpnB5C)Xgjoy>d&$)aTB7KjI9v9GJ6Cwq7#BREQ z3vyxcl<XWF*UV}e)grWk6jLiS&Q{>h*R_j!(nc8Ck;VOP4j=b&DRRV1v~*)vLm}&5 zUsz5K6yF=DoQ{D5jBX~$FkhfSs5a+<_OABCT^*gnCU2@Lsd~MasqyE9boQ2LgF0?| zf4!1ZflFO?f7>h)o}0QbMe&hccbkSrVh*IHBS!9QaEA9N^6cG3KJ4S=&GpZm9x-Je z$OHhs-qoKmjuYGe%J<G)>UC03bUf$%c{O*RZ<mr?ceL+5$Thr`-BA0DdFFtH^A5oA z>I}Ni+6=1N5m*MmnBCJUo1B1iDWC$A6Q9NY1bQ+r-<j7vi!ECpM7uycDQjMaSsP@P zLWwzqnbVgGSs+2Kd2;H}*}dp4U7(?TmkH<QhUv7X8xu~}T=eg7M$ltP)S|sHok#jK zALxd#<x89)!gn-nG5-Xs%UkU41@Psre)*2BwhHymATaR#JJj7rAom?xjeJslPQ6yq zKYdj=w>i!m>E1bVs~L}PnOIxt3OH8eRG(8>mUF?fbp$~^lvF%wzGb;&OvK=58KPJB z4Nrgg<^FahJE%FByGxqRK5X?OY$<mUMP+x#^pzXr{M6WbCg}&K1RRrb7)9MhM_<Nf zCQFS0zk?`hSn%j;bV3uj?{{%5jJ8RGN&Y1BvViavb)%xWH4$`r9jJeg*Hd--VQ8Gt z!uulhLymfyKYq{D>wB5o=(i)wp!HS{Yl0QQoy1wa<<DjqC}^xe#z0~{2Z+N-TJ?a* zX*RVJ4d!7KhbsC?LMXQ+omF$Y%al1+(j!0W4o<9<43+jGgOBA3bJ0NFEZf9rqs91E zTa#$3f;)s~^hb~L$?wQ8GCc#Mdd~Emq3;`IHkNCj15|B$QPK<Ng}g%i(*UlTa7VC2 zYX+4!J7_S%Y=U_b)b+g#Lt1103;kkW)#<5ffe&nj#TG@w9ov7V3L~%O>b3_nmG-5_ z9hPzGvyN4IxjkWf@u34|I(6s(nw7?57yZ4|TM)zqr-**=nN>c%1~`vYR5^U9y6Wzp zUO2FT7#tCP(_t<hxswiM6bHFTf2tV(E^YY(lI(2He9Bnfmq}S?3><IoE2-g>VJwT} z#P;ysZ_%7Ns_JGX1(Z0<s4Rps9*uWWcLrL$1D@Z2ChxI85Wt1D_5O4H{X0srUjd8o zgl;9JGx^33M=**ul`4t($Xm5|`}6U9;QHGmfi_Z?cSx5^wl-CXHi(0*cj&E+wn+&t zvj$ZHhl)n~pf_lNXneu!&fS6U<Yg}#+F|WBT^Eb{dFn)?A-63E_Mtw2s29nPHM5&* zt=T%5E1H07kVA`WZPWGt^la!0%?XzEXfz;?MYdh%J-28Bt}$v$<1O-}2#?ECIY)?v zu3ET6dQ==p;_nYRcXHp_kT{{U4S5mmh~3(;UIZ%T;X&yhLy5R<P_i-h291|6TTG*s zAkL*w2SyEx+VrTtneK&^mE_1xLQ--}f~hN0P2GxYeDTo!2tP@Sxkeb+xmG2YqRdCk z&?K|U=^UiC5#eZ_!}xS*`8CjESN7Y$wwrjZyA2C^%&g*RBx7y(#ylg?cwN7a{drt$ z;Tz`paj^JDaz!XNc2u)GSM>2JqtO%H<6WEDV1z^?Glj-7#+`G5`+wQ_Z+ECXXA;QO z^)49IIc@Mt<Q}i(Z&B@iA-`*Kqtc9WWgDAQU92{-Yp@GIuFJuJbcJ{4#Tty7C>D#M z7ZY=!PQN<YTT<g%52lFqd**ZjZK)f{kL=QtUJTnRuDg&X?`RO!6$VCU7dzEQRHi#= zKbbYJ*i`HFi($6<0&+*gJT0bx^9)TC-Z3qV9)v^0%i8{@k!i&|9l{}E#qHF-#Jstp zZ=u7Xzj9dQN9ACjw`QW^(Hj$~6Y8w3zx*k7{cAkcZhTQc4@_OILXzZ${C!!@3<5UE zjl5zk&@S1-eR*7dJFiO^w%u`)mgv;R29X3(Cw;}OfDaBzh8(tY-F7=m`b#g}zG8F+ zc1?v*e@n~ifIQ~c3bX3}xoVyTfFNx?*nYPqx<{nh230XT=<8PaOk=7Pb^{QkcXxqk z8AQDp*L@Csp3_+Sjj;hi)X4e1QZB$=Qx;YNrthgimkr%9Gr%exLq<jX(lcOzP|YMG zsvkFMKI#+pMEx1FehEwH6O($P21_G|=FQ9fU60~=G#3bW9?LzoI#1T`{ElkNILN26 zh6St7yKX<I`|daJV8$9YbCY{(CU&nya%4Ov;tKxRNCz8@{r~=RW@D%)3Qp6<kih9y z$a&uYpMNsk7OCeWrQb(TL*ydW--gVd>AriqWJ_O}U%&`jEbxl=Z9!v3p$0H6AI=fq z+~W<iF+_JS;Ue|Xy@bmFq27(tR3=zc>_ui-eou3l{3OTjsr8n59mZOm^!XusI+8eg z9K)4^2Jvbc+G8QRT3SsP2X$EaC^Q*7)ZB~3Z5QPXwGDTD{5_3*(t+t5zWQ$lYOrh0 zpN<Zfc*XsblhLoW2u>`ErTOjnQ6_5mS`>L*g~dQOWcf;+H9Jz>S>K~nA{-rZusn^` zA6*4+#6L6Jzt!bLlf}B)QK4HGnt*+P4_|)jdYp(Q3#?pQ00;i@T*t$l3#Ylzbzt<! z+OEI-5cysrYkJpNKbam9kJOl(neN&9G^P#b&EbLNf!s%Qi@kGy`O_t%lIGn9(1_)Y zNYc&<{P<4sPHB@^k8jr$;B$>I1aKGKW!<(ON&n<SN)Sk+p2ZHm)h<?XxXtZesC!fe z_cjUx@PHPuHbc{ClI24g50tVr!5v6IYI2i57)ug?^y4Uz2jXFka@gSvbT-Ok9~|af zlm!!JHDLjV@@-280c8O$L0YKWtbk`yBn(Ydt{(QrG&Q0q#bGC9+0}1&8N3)aq`PpJ z-`DjifKP;H7JkLd5BIV_%&ABuPEX}N-@Npf=!G$4U2-=~2>f=BpH1CrA9T&4X?~GF z6(0N4p}i*=5g$NS!f@1t%SM0gt@uL&i)%c)C&Nwlez^;uTh^8A0_UOo&I7aDc&-1B zx^I-yXmua>_GPCl;4G7B((p96P#CiYy;|$@pp$W|lZlwyFd{wO^KP+nH?C^;=^u<m zC-D6wto$<ZUhKx%>5GE0+b4^RfkQym({|z8lZ)QIW!xc0(-7Aj7G9j%jnf1fbxNxZ zly*fyf*Y=Whyru$+*0Sps<#i40d$Ai5tl&_i9E8mEOymo$9JjAfwDeQ|9tP^WiiLU zVku!CmcbzRTuYjmFD0%CyR5|>^$)#SbNkNw@W~TUZrzdBca}dM<&R+NZ<8j}e_9^H z6BEyCtl2@{GQmguS7dp33jC~sny&B3*!7gL;!wbGvwRQ0?F`NKs~UepRDapY*R?YP z3r&Db>2de_=iaL`6RNnf(9XEzKGM@HLx82*psMH?<F&t?07s-hHCnwRuXujEe?Wa8 zcOxX|j?7J-U7TgPXB55vV(-2jbN5-Ns>+{=!F`vtbMkEec9AfDeJ93zg=_p8Pk__+ zx;yVd1WNOVrleF}d2i#HM>XBWH>wy2U@htvK)ZQZOEmFML_6T_-kP|8<s)I$erNK| zA%w#b`t9i*G|x0*lhq{!X3+<jq)L2{c`b(xUT#cSrsIG4Fxa-}?cPnORHzH<rtt@| z(01}nLQ$2yo0I$gh!>{RaZTn)dm$OAUK_=b6{|^~!nX34CxTc0w-jRRqugY-QeeYR zZd9ADPxNi)WrL=fyO1i-DU?)FAkH1$N-_gEY1?%FC|I;|gCBa>(!RWInANXq=D)4b z?xjd$%>vtAyxjNsU>I0jckSWkkMfZjL6FoN8v=LsdveR(?__hp{kR62@8D1BVx;Q9 zH2tQf&#It?ffkGXNr&N`X+t|IVm*BOdM_QGxsS2fry5Gq&l05@HxHgPm~2F1e$AEG zj#B!5J{K>s2cQJbrW&?7PnT5Tq;Tl*FPNn99Y1<W<G&t94oMf%h9BQJ>$7hQ%oG1Z z*xoOV47+>(PUV9(uHq}x+M7okg;YG3o?pn`;EcmV3;I_YoU9nicO$15RDtF)0BV+W zi50#3aX1~lA-a)jW%IbMbmj*CmdnT1e#4!mc#^h^n^KB*2kUUROlZzC2h6()>1{1H zIakGR!}|tF4~L^DMS4Nitm+eHBO-%h>0Jl}r8X>h;9Sh=I~Ld+gZA(%=_D!o>Du;5 zo+`+1B7bf^U+{GkwID8Bi5NO9=wF#a%neNSgSYv>xp>{f{jq_~6{EMQ)vkKKyIMu> zn26!&zWvWYWx^zJ90@ZQcnP-3dAJ~uC?~Dlg|symL<(xap0883LC{wMJ(ChO9bgl| zC1lyF&_{5u7A3!8Urk(|Be6YS6O<;m1J{o%qjL8`>RUCVidB9!-bUpzY-N!<-VjeZ zj(PIG>g$yd$SEZAS>Ao7!|*pq0ogtjO2-f=|9hQdHNkor-C$3L&dMv`s1_7t2b=%e zP7hWBaL5#asu&L*tX0FLlTOJj<s#z)ZXDp^r*WX*nJ^F5QvA@+#%aZT5?F&z+RO#< z{_rAhVo@exA+)8RGnzKI^fe(?P)%HC=yGyUnm-g|DQDBgnpQvepY`8q6=FGTgCd#j zmC6GUyCi@lr)-J0uaq$+G7ALDAKa0YtN^S07rF8>r}uTAC2A(H=ioO=4~)WTsp<TV zL0=^5xJV@(T*hUPy2UaH&=^w^aA~ejmV-dnzB$rT@7EO%qXf>M`|;^SmYU;fr1ac< zR##o*xgqW>T~D7k3YTk0PIn|M;;4k5yc|zqA?Y(W-2zg9GsvS;-**t1DhKHN=}{_z zTps5+ma<7A0?~FrVOZ97DKXlo;vS_eo24p5+J;^oa7!62awSMh+~40M_4?wv5yf9n z^DuK1<ZyO`A^LSdm{m#`fd<T*VBsYhtGqbq5_Ct>EZ$;?cDU<Po!Y54YnY4&lfT5& zB#vmc2${D}RDbxLwx{t3Fb)?ZPJlbpF*YZ0fxZBObT0{(n1cYGx}{%&o#s0{4>|ao zs2vzv-mq;Zm{0RFq8_psqGU8oW9D?GBax*^t^UBaTYBE<S@+R_j4gz!*T7XMH+poS zlndk7)6=A$;&)OQ24tZhwRb-E;A97+K@nT>cdC500;QI>Z0A6G5Yj#P%FcQa7U@$3 zd6kK8`{(yea}9tu#f$egdlqQhS3@e%a<wc2huN8^_r{<n$Lt$_C3iAu^aTo45Tw`c zY#Jc;C~OYz#+6-x)(*<NUB{{Ad{ih)Y!ZE6@sSs6-tdX<7!QIV3Vf+3q_tua{>l!J zbze3^PHskI#CQa=bUo(Q{PIMQS$Fqu;-W|a1f@i)KB5${uDv8HMA<M-l(hFU0aYlw zDQn$#w@k96q|w^S3dHzh*Vb_)f8y{&!}n30V=?pr8pEu5^F?@tS!{~bPp)xEQx=7? z)W$?pD0MD6qb$_`I65krke<)!isFK1iD9RWQlES9_nsDw6=znGGAh@nw@$FKg*F)C zJl!jdSraZ@k3u#fwj=rsPJ*%L;23K4?z7j&pO|({Wg%)w=F!HC+i~u7=!L}Du0*ht zLutjlMO!J-3SvoB_Uj`sD(eqn1GMLen+|Z*^pzNO=qc%DLQXICU+kleFzK3&5yZa- z)*7i*l`2pkOrhi#PNI7ge_b3{6_l+)QM=3Y-w9wu%)x%{J2O3%6;!ZQ!Uwg)k^hpP z!Sj{5>)tnAC={T9qG8>#iJO3yKe;p&z+?xtqfU&KK{JweK*2L%6lC|9^HTi~3W|PX zfA`(T27`)neGertQfhPPcn1f}Ip&LEt_2h#llIK>SWc7>pv+HULSb!S7jI9-0ja&{ zm>I4dH>2;`t@2;$tN$(LX;|31xGfQ-nDvHtNe!7WZ|=*^@lG=5nv+Z=CZo_F5Md9{ zs;oyK>)}^sx>G@_AKjy`P!z*c(u*Awr=iSLO(>qUA(Xb&;28ITtr0I6D`}<q-XxBp zRJ!J|b?kT*`8NW%s7zJYAU6*}{md@R^`4eFVVAvl>b7S*@MgdK(M5VHb#AQ~P{IJo z^hNAFn1lrWFxHJ2!9+p~=QtlS+IY=xSJ{|rN*LDDkD?&$5i*VoR9Xz3LJ6tuD%>0J z-w(KxbJ<s+CU)zZW(<aS7KsQ{(K~NwKxyyOgs;|FmT@Y@Ry2}k<det1yliIL^sfJ8 zoOK5+tMSkwH8^*@b|cOPUq_CE_?TVS4H;YQE9fP>mqKkDtrbsCpSIuPG`1ot7!tA) z=#5awJD_NzSl$0%Zq_u|7|zoOj)P#5O1>CP^%<}I9m$LODB8rXc>3bZcn|n2r6{<A zf@ar4AyAq}Lu}ijzRh0#e}-{Y;Z@VA6HyWmLBiZ^JA`kBd@;sKrwYyX_320cx<_q@ zm8;7|X$U!kGK#W<2M#YYolX<EH?gCZnsQIrnx3*@S8?G?eYj%uaZEJmGBx0Yr<Wce zQu)}-Z+m|hTj+5=fvbrp79QC6RVyEPN$dCuf;2zD&0VvZ4i3Xeh33tla>**tSrQbB z=u2-{Ja77c5*XqTBw)@JpIAIY`#<KLnC_VM>&QEFk|9O83wso&c8vurv4edWX#*OW zl}oE!*AyA4oZh@}oZEC~Q8T|!y|z&<8)3@yGyV6(-+2tX-=as=gq;Xt%U8cdTzHM^ zn#aGcPn@P|l`d->;pFM!==ZGs)NiN(zyq%q@LEn8y)Wt*O7M9c#!9EJ(g2|$GeE-; zt6MrGHH;6Dl)EH+b>l^eHxTJiJVRi)k@p2p@b%+&t?d`aa!_SngwM>r+ON{})Z>?{ zJWI`eXmiD85c@3=xUUcdkz?YIl+!&^2&|G)VH4wY?0JQ@;X^mSz!PmspXyX&*GH=f z;%BX0qt}M@Tr_>2O`Wx3aTc0!|Fo)!1R6*9iFZtDb2o8j6@(k+5Vr5>diP#kg1g_b z%?{_iQG;oISdX7D5i!pu4=w+pv+)D<I`@?SU1dsOz3N!b*M9%3L=(7YXgO|oO2hW9 zdws(mt1EoZZ$j1QW5$ZVR9B3LRA__I^@yo+*7)H@n{C~D^AYLS0Hk=EzG#1_#Np$> zZ}{l8xdE^SmdGAW`tKJ$>vbui_~sl=P@VrkF<euA@7+?KtzNS5dJ1jWKB{y#>CL%u zAGbZZ2_mBtC?FpAA&$em=e6|HmM0-abf?fT6;cvU;2N;g_;%+)#3D^iy9EoS4Pev! zV=$-}qj&?&;djU0Rs3K@k%<dO)sk@0llglc5{_pIQ<r(EGT00k&-b?Af9hPz@Akg< z=9>2CC;F<7GzNh`RyEUbA(WJlXI62_k!tUcT#KO{$mk$Hf(qTf_0Z2btBm(7(MpN6 zWKVe87;CV1;y+;p-8JjO!Ywa-`@&?!@#aA@*?`KNa(C&UZP^-{JoFQe-0ptZYov7y zsyvrjs@rWlf5jQ#-=#TRs_QxXI6aa)-^+NVVBX7S?cmS0p)@bi(;Rv|^nC7KnWX|2 zksnwVR{>GcQ@LVsdx0gY^<?gC@-EVz_Nj?R6dPhs)>?DT%E4N<*ysGTY<{mE`Zet- z;D#57C_{CB`eIp7lh=OBSbeX)s%3M-3|m6bZ(wEIMHPh3Y8uQ5H`k7eTiqT0kqOE- z7Zo~;$URHc7yKTsvI7(i5NMh-ux&WhvS(Ht{*@2Ev#E{^oHs|6POWT<E_Xk>vAL_L zaTgi~fEPYvXY}%2^XLF{FPcuwul;6OS@VvEHm&~QsRK*2s*O+V1<fUoc-MY^0LRb| zY%SL4wi~I+Ul#6TV#ok(JMKm7_K4wbx|t^~*V?{aI9=*<qBKkJscAOO@afY}$T6~H zNj57+(Ah&r^e~<>wZ@6<)~5?$X+n<2K%#qkp6N!+=UAw39LPx=NrIu434c4&>Sy2* zrBP%4qBnKhi|)tdi9^e;=7`DX|J!tI$oQecxVo?zll+nMDHyb>tY3)pdl$7Vn|I=1 z)u8KZ$i^|Pk#^`VZX@flg1(BLJ40-4F7p*f4an_IY9)feeaA37FCyTS@jLvc*QJDV z{j8Jb+#X%amD6xJEWs`3<vxvUFY>;4;>Z!X?I;_g=%9Ac3Z_1|q9It`K9aaO!}3r| z<(HPIKYBcRU=K+~`uT&UaflkJcQFjN1828+=a$`QG5t4iwKx1R5g?s6of5-HoI_Z) z%(FHbTEigcLi4y>-W!^u(nn%Kx2-<yeK=LGrt4Xcha{3z!_z{e^fA}ATcW339#a_< zv8t^5$=TL<xJXAwPjqOb?m`6cwL@HWv&$$s8iubMrKzbDfR-!4nmto(?3r+TiShQ& zR>kAq1v!9}Z9On}1HC#bEN*21HrChYoe2(!7+zMgT<Q*d-8|<m`Hl2AmI?$(-cufP zqmLuCOD`PL+HVZei2*pLs-!%cOK>TyS3gi=d!AYk8kc|4qaT&luP?5#_xjXYM0y}H zBHvFL+a16a2P`_Q1xrutNpGLkGRD+hv~J$akHVHYOZ~jcq@sQHPp-~?t}}hx_8}D? z@4X`^W_fAmxGDcDzV~&&vzh`1rvoFgkA2#Mq736gN%ww*6B!rO9OkBXdg1`lrX}Lo zA3ch-WiJ^0KPZ;?eOVR2NB_?h=N|cOfVXosZPbf*YJWA(+g8;QcdqYFZ*%Q;%-%J& z7w&m>Z#!l05c(JMq`!Y+4|8`TTGZ)kbINOFaff+_Prp?GOTGSGW=HnFcw)%yQ@W$h zog=8%W(~fulF5?CybrsEPk2YGK3jXhOx$y{4KUL5p|%rKMXWT}Jx}g#x<d(rmPaaj zDd7%9UUnMJz4<47KS(jfrDX(bxetQ8nr(+YnaBJ2$0?5{&F%1XB)<Y~b$<%y^ybb` z$ANO3JQ@FqHUW42ZcKZ|g$Zj8PcEwnr+mZC?e29kkuToab|Wd>(V4kT;~xCx3>fG6 zt=@Bk`<fiawOui_0qo11ijwb6?ALWob-mQRv;)n9XnD{I(#3e*P6lrK)G|p9gg$1L z@$_?@!9Onx7<k~o?*q?ITJ0(7T0A4@PR@<7rAp_K72_(%<wmh79V_0vuyS2Hsa&o- zqq>|DhVHAhXrVnSjcc0-8z$)lW!qzBPwalS^KXI9s++U36!(K{iRtoNo{qJ)CLB0m ztakCU)ptGL9DDNK&gegS{3#{db6|eDS8b%$Ui2yyp83FhMNAu=XFNTu^J(wr&t?)v zkIEO@@kaZ!mS>yOZ>DbgV3Trrbx#ya%koNQe0SoYuIs3C>Qh_iK~+~#8~`17rD4>V z=OQGqN*~~Y>|Qsb{;nq@rBD3;W$o3`#?|j^_fQ&n!}8O-=PVB$boD;-ZIID3<~h9H zlc!YJzgzik?{fhy>#0Yqu_kIPUcYtGZXJR`Qy>m(?4w8^qlWr+1{pq7b@R0^{^;>g zUpDQmNblcX{GoO0d!4(so4Vo;u?F4`r?FSV_D^-arh8Q9-E#+imM5;6R401CA~R)f zyUs#Fgtb8o2krEz&VlE3okt5tcX~Ch`K<rWl&bwtew@&jqWy(&z3w#r+Xp+^mokiY z*dIN#)*-f?c2>!jOOX0atJrC5smhsztz6_q%@w<)qlAbC8FOP?Lkqt(At~WmW!aE_ zy|`8J9NyW`9qJzU7k^W0=#=Ly?*uii5y1V>U6~SFFvFYXoVmh5c5$0vK^{w7o+=hM zVH4hIwx^#zkcwJ92E66o63-^Df1}DhrEHM$r9PPR5I&sm6sP?6&9{u5bLUO@$$GM# zLdx;EZ@B6(>#&Ih+Qt5c=v+fgw;|3x4QuM2;LWS}M<mfI!dTt5mG1}LDQ`KabLBr} zl;0e~PP>%g<^T38n5PZwOyB;~GWVSg{MmM!^$3`=JthCyUFv{i=2Lvk6%dA@ArZ4F z!6pRac85KQo6b`q1ck1Rx{BuCKm9Ux@wz8^1y&Wk|LJPx0M97D5qY}L3b*DH_vy9p zFXxa)2V7GW?;78Rc*lA-+nLp#S=FpuRC9SYZX2-hFi1lmIwmV$t$N7tnBG5S@>gNT z6B{Ri%~tKm?HtjvU7HYaW_k5WYx0=69UP{`bxcN>_0bE;VqMV<dsgfTsGP1RPCzb6 z)md~<4EN<m%x1!$m`!$M-is(dseGDWv!&H-h-rEMVr>$7)cRxYft|{K_8l+kzkR*- zm#+pJ(>*_DhFw_sdHY`P?vy>AZAM536@eA^$LQRexwI;V8fQq~fgaqI-O_}MFTY$K z)7RklDs+ZNpZ)4ZKJ^i!^?bha`&@TGT1rvpYwv!kareJHAn0yRg?;avSA))lEM&j8 zo$?da%E<b>t9h^>zJlHi+mJhNWpvOf`|1z(<97V$?!30~4CmU&mD@h-qWgu;p^IRY z{gfkl!oFA&zrBo?6}H?u)V9({w*}=;92-H?zUv5XMfC4!apuC=%PzmXZ+Y(<Sy{}g zTD+FMj5MTO$Da<=J=@~<Lua+qZ(TAm%4s)j>QEQTzEbNl94D;ju?D^maOSo(SHoO| zL~t+j-ou7ooloWgir)+ngrBc5=07m1ByHcGJgEG?-hQ-fTgSIXZfGs;UVHaz_osjK zSlW@qL2$2W?C-3y8WoVV;@&jWsX^GEn*-{Wo??$sqO`5(+F*Rd-OpTJV*aDYk7YL1 zM;(kJ{edN8oWkY4>X%xS>FH<9)jyUM!?{cS=xMgdcJ5IyS<Qay;<FRB-bpD7YKO8d zoy&$CuQR9c;4%2oS`l$*N7U)Zz^<LW*X5j89S}(GKH=ASDRh;%V<PczeQl+3Bf}e) z)%z<H_?~O)=geXCqe&qcCRAZR>==CU!?5?QjjfXASRrH-O@d_vg`{%jP=BTOTe!9B z{%Rv*Vp@)5sxCiroejyo3f)ggIvVt28K*zW`j+qaDfJw-Mwj2_fENrfblQS^q44T$ zb6?>nTr(rjyq9RSR+g7;^7c2hGO6MCECs(Om3cy5wxnU{GdpJlH9yl*^f^R-9L%Cm zN?(<@qUV3>y2pL!{_Om*fDlcuDmt`cqb>}K?HS0^5L)<<jAuLDM@Q84D;h{H2xis) zrr$mDWT$SI&|>oJH+7#mW0({BXlu_prf;p}`tZ-sh%)AeCI9MT^v;b`#*)utfhG*s z1|G9q2M-ao*Ehz*6Q7X+=ltHW`Ihli-<7>Z%}{`@_jX}WtM!w&JnjI$I6y}-&Cmb4 z+`-otr=jk1mf8OHy={jpKHxFus_sK{G1s=fG`Ds&TplP=aW&<?ge>nqIbe>>k@7r6 z0crO-aRj+axyX|AE&r6Zl>2#KA4)lsWppq0Zk$om_ITC&+S~6X2M?kDBY1HlT{FZj zu6Ug(!U6_;LaShm-IUPTecCXI=zr?qYQeit!EX>v_2EUWfu|D?NvDj%MV^FjU4cEw zXBTLQ_RqPs(qzpm-9xgC%$~kUV0!29aU&Nys!(N76}gK?T+i$L?0@uz{^;@N+Hebv zh_2b&lqP^R5Hlf7zxx$#%_-xgJll|{d3KxHO1D?4>v1Wkv)k2AcaLvQ0Z<pOmP8!E zx@rY{c<I~WO&m^aIRugJNQ^ud(fX3kGNmZ^<lq2EH}0dO^JuP+S?Rjt`5IM)lfA>@ zAqcm2K6&~DXbDiIqHrU?y^mBbDbcki^v?3fHokus(g_V{AC4W_eeUS9YmBv!KRJMG zpzJp*1AcmL3v$h^?y<1FidEes=@fC}N(}_ZVw&<}pIiaOKMg)r#F3qlVy9ULD3DQ5 zlx<KPyx^Pvl%e-PLIVYQyQNQh1DUBYw8KvT>Tx5k=5>DiVs_8<%cq=zrkLe;bz|f; zU!h#^M~|==&w-r--LG%d99X66xBOM1&u>^-7ekU8>8q?rAkXiti8)^s;C!}uucNhd zb`$3wlzcF)ukHo3Ap6u*UIHdI9yg=Y+4sFc_j%zO0`HLK|Dri+tF}ydQQ#U1=fat3 z?zgT~Ta=IqgSCNd$bk06U<LVyH@b~y4IT4ss+JnJ(RqrXD{{J#630Sxf3YLfz;Qv^ z2<mg~!JThhCllI`IPWTNf9j}b;O<B~k5DdO?ETZ?ziJk#j8|XRqBzeAs(8kw9OXqp zG(M_1-#vI@(3;V1P{4_xxURZE{QExK3M}+sGdoKtcaa6ft$9C9*ZCW-USut^YCLJ^ zm+j%Jj9(aDNWDV*`~C0f@^-DULQlAuRB-IGT>Ynphpy~KiSQlH&V&O4cuU)GP3K4X z3(YIdQ>N_b@U}V9=R^PW0hd>kZ!dMvX-!H8&?!k~JD&lw^%2Pq8Rg61s58p&Z09*l z&eX3YD>N0@a<>ad@|%_{NqN3JZk5)1lHt+@@MSItq=qY|Eu!46>fMDxOt4yM8vu`9 zD6H^4(|PD4rnL@u`nFt$Hl?Y`=MYro*}qlyx6Z6Pdrt<fdw!Gz-^N6J#z)_uzJ6!v zH209!$IHLAR=h|P0~unQT&rh{eUAToOq$J;u6PclhF7HD{L}Yp$jhq3(=|lytVBGB zxCb_XwNBd;&9(@9WN%NtB2@^0t><t5&Z%k{{Qdd0-iJFk)K7M-j-b|OT8ar2w7qn^ zSy>(ScbbS3UNGJx_ieti#;tnlE={LJg=bn>xR;K?&chHPJ8b{1N<up{QL&3MPjSIh zAKYyGVPtnE@8;i~(uQ;lRLHTHbr)LvK0cwcDCSekeHi5KojSd`&Gu4#<VCwbbt=6| zZD4e<+7jE5NPw{0MakWm8P=RoKhJbS_c<(h)m~#)ZLN(g?zz=BKKS0dZ%V-5#ngPc z<iwt&oe5QH7;MGrC5&{!0%4jd;s9n8FHLTQ5+_E~ggmzKvX>WKt5<%XwCFmA9{)1V zSmdB<iERF&%$~;H$-(<<D(}DL1{zsg<bw+{?JGC*Au}8z<^LWgA82~QBLn<+*M3i$ z78Ms4{Q7)TvbAN~JteSXg=G^ixSD`2Kx9QfJFqiYuQF?&{q}!6_=G^~bVifx^4;m= zZ6(^CiFj$Un!K&ZS#A?FGg_zI$64LBEzdW7nC2exk7!L#@6Z;<QiK>a_I!P!keTdF z^;Pa+N1pjADE%kP-)Q6=)87jYH9`$NvKG`{_OL8I-SAyo$G%9*7Km2<|5-kBsXO$S zEfiuudHv!19H}->p=<AB97yw=M@#TJ3$!hVU&V4Dz^wqd6^+&~wvuiCyW6yneus3y zQB>s~hNl)sgAc-}eDJ`|fv3YJ4K|(`^n!Ft+*9Jxp~raWg779YG&gj;@LT=y$Ae~u z=s2q)tSe+8Eau23gXqR$m!|b~?<=Nyu9@hnNQX7_{I)IknwHJzRDM`T&b8$DS%JG& zJm!2)K$hJUmOt)U6Xt*NmQMLHn1R7~$lWeuosCLoZBv6imas-Q-#I=-c$|Q*DE2Iy zSK0peYemWn2UmNPAIE=Nh4V|;=^UJ2tBx|;V^YkgPwWSlnbFF`*Rr##j+f(p8t9#i zb$ERsMZpZW%~S1dQV>iOU0=Lq_DcJtuTxZV$xm)|Bmjn6TSqM~{r1;-YoBLU^;I2g zJ>x_@lO0f@KC|basd}_a45x9^7V#Rd%oIVCFQK`jPpTd|*!smF)2r!Goo~p9&H=%H zwfmFdsY{MccI@Cd4e5+`pcMOi*t6!FkkP_+`6e+c&eG%UwDlpubWa#)^XFd{q|;6G zTuUBrj7UFc3dipG5eMns@AvMK1DB3-l)tHXp2TBkXFyAO%2*cdW_cxsG&IzfpJ*=G zJ#at-LyZMxsPuHL8f(0wA$JZLA3S(h>w-nsnjNiqpXAZ>`8_JZwVqU~GrYOT8Prs- z4f}iN3s=ZuKD!#pt!IhanBmj_-EY=kqkD*Zu)OMN@P-KF^u5Y;m8E6hExLAhxp(yP z53eYd?tiw}eRgZNQiw4nK5lO5E?eunr@eDh#<W1FrVXvzwz88QU?od@^CNia0Lo?! zSMziDcd<jIPidRwj9GGY+U<_2zco3`O-ko0>fXqOj#(x=Eswx$uAgKKc>X`ttG&aT zA3hl`HV6}*9oud!$ARq4cy@D>1H&2bT#yh#gM~v}yDd0v-iI$0bw(RTSsMpT?ow!g zqBhFW1bDw}8-B)mASe|zP-F17Z$Zy-B>Z}^rid|NV^jV9sV<CNq6y+&<%%y0+z_;k zlC;ByQ!3flE1XIOaC~=iu-(08ma6kuwYHY%{=4dgr;7gSePW1UFwQ{<u<N+DyjN!d zFqw@7TgJVU^hb}D!|KRn^-?}+O7bmf$=33`Fpl;^8gV_cQ&(+&OdGJlJM>DR_<7~A z)oddMGf-XFvrJb}vKeb)7uMZ-^{(u9bFYuS5@$M_erEicRvTUB0an~|XC`#!M5F4P zQAi4AEU>WCyzuHr2+x&B0h70IPy62nmU#O@-p@Gt^%Kur%HtvU8U<C|Hdj5VK4pd_ zhF>(ASi@bhU;+~_U|Om%0<!ew4bop<kC;Q)BJe9{I1GveeJqD+4^M&fep!;Qrn>a2 zxY!VOs!3ypYu%k>g-#WGLL44tg&5C96H4R{%m*3`LufFE&Q2M|?qK~l_!!HxWr}0A zjZfkJ%|!E!MJWK4ccY={<G#?W2*uJFg<s`Bs{-@_n<>c6m)U^bQlUIPnc&M0S22V- zpn(={Oc!sCUohMl%(4`{ZY=S`AKI6!O=Xaan{wefo@R_MSQ$QIL;)_q5MX(C;_7X! zzx`kiM;4xdCvVac6h#DvI+bMsSu1`J!bK9h=cFF+Vjwow;3tS00s+;o^v-&N5q2%9 zQ>X`t)0RI?gdTH5K;61+kGkQAzbfU$_GG0wC=DioES%eZBZq4Nme|KI6u1kai6A=- zCrP3{36;aaEiq_-p_==MHN8xf3o#wN@BXse7>0w+>kn{=*ijaPW|#so<l@wfS3}Nd z^LjOI5k9f|!K|VZUxygXJZ$YgpbGYvjJ)%`DD)^kkAhUxK~j^RO@a#QyL%+H&1ak9 z$9<GmnCp>``v#`kg!>%iapzO%8>A^t+X?0dTRhLUPpQ0rU1jvpi3>kB%^0zb6#gTW zfU!XKzBlo{!UPp0Cale}0PiHOglVwQ;C|M@w-Kk-kk@-c74qFEks?QAWHRLebVr68 zm7;-|R!nJ9XYDFh<>Pl35Hg0{Aw-hxSjYOpElpZXfjtYtkS&9vd%R6Tb{@_Bi`x#P zPlg^h9!XEJfZc3MJo-vWD#ZY*G~WwYnlFtIXQ>I=UYi2WXS80QxnXcpf~!9}*C@*C zMr%{Okrp#dCMa{X=5(mdxPxh~R|@8hi&2x7O-Rhr12}9UQ-RJ)MT#&Y`?Bbc1biX2 zInIgUwc2Knie(0>fjSMcaYyFtkY^9V%;0bCFx$?)w#>C+W`Kwu1Pq)#A|`Zjl(D|y z#hY=>qZ*;!)aDAWKYGNR?$VlvN<I(+V^54{%<ih+v$A{tCOfbum#W^qCTe=|trwA1 zMDIEMwc37|cO^Nd_se{9%`@HU7qDtN@JEl8)xzEg#uk*7EE^ZNbu!j<l6W7zyfn1r zs6Q%FUC3nor#ueJ0`U(-U$06I>O$l~x!i%D?)dX>x1-$^-Xk!K_b6tql1$CE#B`@! zvL53u1clx2aU|&zilD~qx;5M(zP?N+f!gIe+=m#ZO|YP;F>{l{H{FIjsBHYce~s&~ zLE+a9S3=pT+mi_}ypyT*ioCFo`_xJqI9CMKNjgP_q0#S{FgPaLAIc(^N##XVLUVeD zc>dAxzC9BD261F?EWO(Cu}i&8eXt=k#SygGmf?Hd`_KwV$MLEXq6_rI!e7dsaW2Bs zG`$G^IPlr`QlNGuv7eloK~1&dfb0qN*1+SGpv3u}Fl^~#n%d%?2}Bqor`HH2lNrx& zNFXSb<ikgW`9iP*hV`6djRl#iwRYK?X7y-3D0cUP&uri=kdq-oVmLHs4(RzpIRA|i zPqLXy#;2r}J^zdx!6;5Ur$ek?P4|G&`EmvmES!pNdw0j2k2NBq+C|@=dz2|ed`HyR z9IU}n@zf_QrAQyHC8zvAdoW4}w&wA1o1p|5;<AP+-UmeLHbD*9W51b9i+WPE^Fc)n z_qM|`S*tSpVRd4JyOOWMj3a)(2v%ch>YI)d$h=3(hSyAP%7tYFEmOvi`S6ng<M#}` zYl+3RV;%qWIxnj$)a^<(jOE!RHD*8VhlMDp34g3Y^!}wx*@D7_k)jC<8(vi6OqLCt zZ4X=>iunRv%}K&JKftJl2XkTRiTX)`#kT%X69mcP-A_=t9QhQw_@VklIxyG7Y@-Y} zhqOyQ7{L-&i;WwT#oCS^ku4%u)<{RbW4Xf#A>#hXo8;cv{*Suwa))+ugskKut6MVu z#9M)SwiU0Vq=IKYI;~jY&Sri$A$>!_MG;m*3dR2M$cnw*ob!+aThDDhhi6U^mRcNv zU2rOix{{LaO0fGIz|RQ2eED<e9wk=j_kH{fQjXC37s3_IEJr#E;c<Y?P8B@hjg6C~ zY-Bq9RL*Cd+?1AN^$#;GM#eG%AhwmR<MLtjms}^sGsx-rYW01qjqqq#nJ6g)U+;wl zQdQP120-$nrjd>{OWgJvYd6nKZNLx)kVp1XdZ&XT6Kj`v$sli0u2~XXnLS%H0BL%q z)|!S-t)K6z;q-Q&`%Abv8pbdl9lHU<=oeZsnu9mWWm|OJ_}lof%MOhi8SF7~4R}Fo z%zbJ%tKsKHu)<uzJm>8P`@j#9AkL#k4DU;32bSR8b=}BKK!}wJzPoT$geBH`L>C&z zwGMAs9)0K&Z_R8|nrmUBx$UC@^)Qo(XdT80Z?qA{(((u+Q)H45GqhfQyw)-n4TDd8 zrmp|&Qkq@GYhYaf`1gRd$mDOXwitI?#lLOWB)GC8l;5`ed7w~yIucw?h|82KUFYO` z@SN(i)%h$o(U#o{t#JpZdM=xoy=eR)aLb2G=psAvQ5AKg@j4g)Cy3r_G5bcbyF8U| z0E6F;0SVwpgUXxSrjVZUfOi-4g8ApZo4Q3LSD4hZDlAy-wl{cdJ^~j6RnGzmTq36D z=rX&YM;>oSSimTDi#&N#REZPu-X??NdYUbZ!8VZy5iYiM5;x^I)@~c|z>JdakqM*< z1YmJ0?~aa4^{Yfy5a?oe3-}<|Kwf~mh55BS`vf(l63S-`OG$Qo<mrHGsb72osoWcd zr8M##_NL)BANqqgR(Rc<5c5jVC%`-4!^`Y?BV%b~8Pvt4I~k5%)pi>6$J!nL?_#vx zm`<qA2%We*97sXSPK{K{I`OGjhQ5J|a*j-=B=>~R4QhllSkpREUv6x%=~CBa%mnoo z&88FxnQx9&m+T=Pfc|rgtdg+LW&FrDY*TkSug-T-w}+z!utAEaLPN|F{=-D-g|4F* zg~v@2kN{q`7BHHym**Q_q_5>0Vj3>sx*O<|`16!@(31~XG}%g*ur(Q1rIGz)Jg%4L z56HrOB+cgUBq_x|DJov)6EYGpf-vgoB^%$+=3t#j_HxP8k1{F>9$nlZZJST|K~14i zB}+C}0tyh&b=V{XUtA42Qye)nR<{-<OdgYux~o)PUMKAu(HmhfUShJFuj_dW+hI>0 z+xFH7`y!>eoxLmp&}Ddsd+z#7YaGFbzDs@}6{yg8cQEZi0_*_(@)NLAwjggFLfh`# z)N=A-s>Ye#Nqi?Fgmf)xLdFIjg!hEoZ1L=#2|qX|B1#m_zOG81x-0Hq6IF=LIm@ni zc<qULC*_A6x**JMT>ojseAW)VdD~llLr8j=Ez8rzYbxf0zx&uCT)fi&#pUc=!AtE0 zgA=AlNCOm|V6VO?3tu^)S<55~*dT8>pyRgrr?I6B33WK@iSE@Ro{HovC`D6!Nv|C9 ztv~d)4Z0+j27CyCJ;xJ^bSAr}NL(aGk7RU#Bp#6+q_~Z50fX1S9CR?1NwlPSWQ)uI z{hqwuvtXdDmQd$jBbU_-LT8qLJY5K2hlb4|lTycac$?$8&h6@<?#t7|Z>A<&5b28z zh9=$@d3w!dbm~1VDN+p?NtE(V_LgZIn3VFPlOHC9)Yas{vP-u+Z}VMLsXpFtfz#1# zMNui)&fNPE;v3`feAQt<SHhJ<jrZyc9&jK57V{&_K+HL-$%l{^q3#i`qD@_BJ)0`* zYhdb*B*wwIQ6R9_uW04rpOiuKz5@d7*sws8fcqDHJ0bcHUrYib;f~=bDV)y6@vG0{ zc6MKlV{Mulwfl95ICw`pQ6d(zr@G>&%j;$@C}CM0OW_6Z)I3sp^CkHq;a%S|wvd77 zGRCbkiW)kC6kIZ{%@cWdyTo4#0cXwegksta#5f=Cn==b*hQJlR%N*(rLyQ6D8tREc zkWT7&?*eyXRo4N+0O1p-h){Ad7-QJk^1+lA;wA8+5L<Eg<Z+Z*PxO-yDhDM;1%r}! zVZSvECs5Kk<cqoK9sQf(c8hYiBh$ZC$l191`a-xRV@^-Veg~ay8AXA9G40Y)Z=;ml zoV$clPY!cP;4$(0O-<A8_tGy@dL7&P<I;x_jr&{aI~+=!WxN+~jPo**YvuBu>kw>_ z32;!<#%n-ui8HthvCq1%MIXPu=5IiE#r!nC6HEGVT+A7xOg$pR^yAwVpSr#Ta^1!m za7Y0jh5u&94JmfL-eAm@e|S_1ZHOL-9Dq7_1(pRmb>c*Sz@2tGTR&_;$YN+U1S*`m zmCL0^9uFk@h)qms<@ZkI2uwp^P;13MbMrhBAVOxbr0_Ch%agRVCUL#5B_xyDn6<Nq z)k@?y8I_LuYeYIcAaE$N#BydiG}%+lMM7JxwAI|n!H}o<j~)T}O)v2CPRQESj~rMn z-&A3WuVKN6%ySck;qxlb-D@I4Q25=$^?)zSBtnq<&SwOsC6?gCMj>vNhsS=&kt2KA zc7L`sBklNpMagWSFr1qxvz~iEZNDdFwei?iKfw4hZ$&B0edDrQ>cv3O&f7#JGM1ym z=Ink)dcX}FwiU5R@Uh(?Abd|nkGOuc@w!inJSjlTP%4F^0=bw|KGjSa!dzoI9;};o z2J&(nsR@T@JJ_n9?>Ox?G7-TH?j!?-C=L*Zqr#B)%Kx`47#!oiD{wRCZjv{Ot*qut z5DjQmR7xJ*gQU2>YzX#pq_;8>nvx3-m-6tvs>K1|ctB`7y~ea#=nBY!?a<<JmyMHg zHq5sbz#}9Fl)9KR!$ry-{B_p=;~o+4vTu4acNrTu$q!3Vr&CpLrF^;vemzcUE>tdw ztb^$?!zG{zy9rmi2llSxx##X<Aa!g)QT9`>n_q2dM%n?AG-C@175!@%^7+CH56S%e z`$NF~@*<+@%n~&?DfD-O;3`Up1afG8j?fq2W#2OV*c{<+G0L{_zLFzHjIVLPtZSMP zco5qbwQaR0Y7>9y)2WK_%mrTqYJ=4l{^L?4Q}mC4Rvcz)ZviPRnZ3J;A(BbJ^tswU z(>A~dc%+8Mk|OM>5@@Ws>RL`5QG?11IAhvXfC?5K5_e#}SWdL5zPiC(!=naep9tqg zfVy*q<5!{aE#+lf5H(^SUJR%qNMsfD$wq_IO0j{P{5~$R71O_4cY`fM23^m_xnzi1 zGEoj)!!|97BhDW({8|?;b_Ot(%X);>=2Y$2yZ2$iEti2v$$se$VEge78uPAgHx_uV z0VK*7TpZ!!K>`5scORl=iCrAIbV#!4yn>`!Kc}dFk$zAfkTC6saU&M~bcN|C0{?K@ zI-L8%p3~KM@W$k~1QbU`d{XlThyIE_`8WFJ?ytiAMp1Y)E5E@x_EwPFjaW;(fV#80 b`S&P8Y?e1R@jZGMb;OIhDc7I*qvHPn`}B_; literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/100kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/100kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..eef677656ac21baab2ec223271c414a87c697463 GIT binary patch literal 161836 zcmeFZZCF!h7B;$3ELx|f(hsMdK%6EtNEN2wRH4x=Q`!)!6G0TQATt%qP}?d9#aPX@ z+NnBi6WIZo*qTrQ0YRu=Rgg+;ZDR;+Dxa+t(2@{7Do6r`kYw}TPkP?>y{_}?ob&5k z*Q>3HkYw*?J?mNPUiZ4!p8je27WGK{%hH!AA0Hp;ANY@&zWtZxmv&~oPEo5@Q=t?^ z&8B>Po}*^qtGN_jd?1VR#n(Rgdi}xR|M~TT<3l{k58wL(ezpR?Dc%tNc!Yd)|JQvB z+_%7e3*5KBeGA;Tz<mqcx4?Z1+_%7e3*5KBeGA;T!2byrNX~jYV_W`?1<(BjtDSjx zrk724jG`8N#1?qJ_WjFqk<|ZY5FXh}ta6`0AXd2l>%Il<Tj0J0?pxr#1@2qmz6I`E z;JyX!Tj0J0?pxr#1^&;mK*V1nBBK8i75$gz7Cg5!n*9G)viMohArNK4jK7nA&A`9G zFHqE9D)FcH`!A92`~I)*AO4+V@UH>)U?xAh&oK}y-2Zjo0{1O&-vak7aNh#=EpXog z_bqVW0{1O&-vak7aNh#|zp}tbxEo9!P!Ev5*Y`Rfnl*8o+@OH`8^43e-}dT%jsO1r z>0hW9shKlokpJ<^7yr+iJ!_V)@2m&?{2rM7hX?=ghq({Vo%_(k0gpWN@VtlT&VA&G zN9H~H*yE2s{s;g0e|+MxKL$MZ_+#Wld}iW3zO&}cnl<OKhvq)?*#GNa(_c~ZX3zX; z7B$o7X==tipPBP~rms?b-0dt(UXbC7|Ld2}4BX=bezWI1I2SKC{|Gh1XXeZqzB9>P z<JEicbINz#tbjj17xTcQ3IFtaI{UGR_X<9nE%@8%D~~5$zblM<Eoa}H2cMY#$0wf( zenu3sFm%aZpI^ExD*DCPmtK~{N#oZhty`bGA!Xy{j4iKc{wwQ^9l3e$<nNU4+W-E) zKR9sk(0^EUVbPJ||7wmNFD)xSQBhfS^32(D=fAjcvA*H!Z?1m(o&K7kxwWmmqqFO$ zpKsj$wa;wnw+;*rjoIwu6ZagG&MC4kAFT6#{`!4k|F?C`!@6ep`p)$ABkS^+k&oXq z=lRb1^K%ab#3cCrGyBn}Bi@_+*xw31JAGx2ATsgp<FDmhfA9(6lH0*!WNF@&{XbjS zzW+}v`(F$D-|M<T{b45Prg<~xQ8eXtd2Z%NElx#-&M{Jbg+JBI&goM|i)?0(wRoCh z1eJ?eS@%uGC<`~*h8op+zGq3*ijID!i*{NiBkpNxYH+2W#wIUlS7d4erJ|8(YG2%d zZJM%Fa37V-?o%6W=4t9kQH78dXB+wzwv#bJRys|+IZbs+Wp;5h^{BDea-GLXMg`MU z3Qu?G_+X#sCgZS`*xXH1Su5umw(*!De4fsIPCYr`xyj0zp#giJQdaN6&tsWk+FDLY zc{-bkleg=pBBI3?`*1~OICSS`+{fTCD&}c9D@|}_>qVMrYH_I4YO~tK*Ep*N3uua< zyA9Kn*xf)W<HXn8&HMbr{3i<WhG3aE*N2zww8^ulDI?t@jh&{3>HOdrvCh_J^jIB& zs=oK8DXXq{rEj)Vky>z_$22PG2#v+SE0l_gMH;?l<vdunNSN(pE>&=LW2NKA8G3#( z-?5N;jWN+-rM+t;FgbPFSGz@K*SqTJ&UHIsh7(1L-W`~+GfYe0l!%J^nHqN4P$O*2 z*&Ri%MY)@_C*`dClYtr0bcen_L8!<a4Y7$Q2WH6V7SBy=<Uv6tY^bxhwN$xHVSDG$ z`Lkekd4a*=%o7$E@<hc6-Ar4Q*feEb86a^PLVo7uC`M$FEu1?yMl=HRX$$4L#%bz{ zLMn!*NFNP4Bp}<E61$DBahY71l46%>B9~&S$<{t4*QOWuD@N#^B%N(6!Q^V1VDu|} zS;Z)~OPYv3H?EV?*_LUlD_+-Pr(Ihp{xB^Me0i`xserS^vvFpXr<tlqe8HKAYpXoz z#cSl+EtG7lNQ0Z!X0TG1DWXoF@)wB(J9TdORqp7T2f99B@~b3gE+3oRx`)Tj(>b)M z+cyj)7%X~`+pfI4=|{6|q-n7H-TZ&Q-FR)J&khHAe{7nnc5xZZ_z&mb*F+>QH@cqa zd8MlFf@ex94p7)+J#uZ@+uv;c=hljsbr)5pOKKDAKcN!g94w|syOZypDm!}Q6XB?s zmGFNSs*Kar2AFu7dZ{g3sJe3`C>_4vYF5UX)!asTcGsJigI?e9ZT%~Swz~O0T@f8R zf2^24p!WJ;n%FeKOod(C^0Vh`$uG`qgVo7gRC5gySHt-CuPtq_tu-s7=zRW&6^F0M z6Imy6<rYj{lJ56N3WRXusitmcktKfhvD2zW@>RwGA={Pcxynkovn`w@`)E-O^Y%HV zEFx~2`bj;KyeChjDc^aZMJtP7!i_Baox2=u{%aB&bw~L7L5W{>X*gwpQs&HZH5(e> ze|fD#>9#iRsB}Zuk8;LSd*SrITmDqnw07`v#&)TteSSjwJ$h*H;Aw2?FS4mj>DslM zJ>4;x%w2Ywd2C%7(_8mymq6vg`KssQ`qYk3hV_@{n=F$@=irL9d3TOpoi|O@s9IDl zo?eZJ`>?X|<IN+Vjx)nTwI_Xa1#@pe?bybjYMRKAzT*16z^P-VsXw>fvJ3V*6d8;w zSo%+R1}o{8a&<;~h>IQ(Hwla|S%;I^fql82$73dbSVsIfS02FBdCb~$4|YG*TuC7y z;T%^?U4uU-#|CBKaF3b#sswhifwok5a*s!u8&r4ZIX@xikg<BUP~=v*IkcRsl{u~J ztU5=46gz`Y$+u2ZruYoqB~^<uN~kv41-7By0(gtS=B^i;!eD>-x_=0CoNJoO(U|1{ zQXzARmGv+KP2AEznN{yw;5;nX-D@p_6<nt7X=<S1@Uu=<a@L_pFXrm5;SN_Rr9x#C zOvozio~aA{E2pVOrOY)_ZJ>*}+Bh7SOwGD~`1eSK1x{_c+rBG344aHMayNC2Wh%!u zUKWp)OjFArHU3oenpAA^JjtCYn{8INsJNq&1SetwP6ak4H-@W?qU9EYtH}|<`gwXi zOE~`##vDxvY~)aSB9F_7yJR~_U^p^OUFr>tSjtA-Q;fv9o4VWFO=0u|iR`O|Cold1 z)<I}O45={i-RH0m+1LHt<7!W8PLgg&+~mx9>8pLq`q(Ie66Qd1nGC@Rl_Sz2==UVq zzZYqI8QTxC2}Q<)uOicPPVK;-k;iWZ$hDcpLS~|sp30Ju_nPP_>l)eSS>uXWZR%mE ztG;g^6NdGEfqm$T3T39O4to5-u$f`BwZeTCc5yZJB+#ReI@mZabE;u?fq}=RvfE(B zsiq#0bDFxL8#g&VVwp&z+LOtdUiykD5N>D28n)<*{WLTZMkHR^AW#`uDcz|Ubrp%V z899u}e=4g#={+94#vPJWrp@yk4WgY{d_;wgc5P~bb4+hTBy(o{jj8!q+!P_@BZ=H) z+GJR{c&NrlG-9?1iC2j{xx|Ilw1yXy$~1X;-RDk)z&d=Ay~r!%*fQNz*1GT#&&>k; zD*qW{2Sz4R;ML`?U3s-<iOSe1!iE;TU-YGNNBnH}wV|7^<;fUVL+kndEqK4>SX^M{ z2XAh+39!rOYEQ_VGp|?-zS>kSeT3U(J@<k}u-~X|!5WH~JoCNhZb-IaKUiss?d;a0 z4dw#F9$Mov^r<~e@%lxX_7#ZAi*Vo5)b91+#ra}pY*463RirYPsueG}=lCHA(3VeG zNnB}-Qf^kx?z1C!swX*1#-z$|RBVeu0xRZeQ+4A%AOfwuvIq9AR^jp|3Y<lftI54@ zv}G!#L39KyXesfJ82h%J-MTc}AR_1^V%an`o{nuhQS?31ko)YZx_O3s)pg5-HBYr$ zg=&Y+-l~cyMd}ib4C3eG_K+F9Qw=0|A1UJH$a9jAU6A?@(fN`ooVSkl0{zN)<x<3+ zsjNhK9@#zly6xD{<UlEp-J^5lAfYuR!5iJBj-mx~60zM=rk<prw5OSxlDYh0;qiFd zQZDJ2=TgYsB28?L)K{C4%hceC__Jj0_N~Q=O!poW-?M`~HI%$|=&-^zB6l}AM}wuM z`V-v}VScs~9u+sVC;1yTE4>k}7KM+bVopp3jSR`g51NT_l3zWdd$3}s+u*)N4_AzJ zJ?ANpmNShwKi%A@BbRwQO%HcLkZUU3dNcdnuBWDozdrW&E>BvM#-i_sBi1JjFc0H{ znwl={YlRuDWkm%m>htL-gSh#C>$MTxmp7OE_U7<Y>&idk(#kl-ea_SUI-nu|mptW+ zOsKQ99vu8B7RX8;7?dV+KbHCc7QE@>yFIeWqM`Ilb~>M@NR!uTT+QQkA4Ev+Eq=v_ zI2RZ<c=SU0C6Z($sSUOzy%AFSPK73UTcbgsYEdIgIR{f6|G}0WN_N}rw52Rhe8Q@G zV`H&ST=a63`FNbTK9ruwtGc!|26$oU<_?3f=-<4eT|hbU-yXYsV9&kEKD)qU&g)w3 zSIo;{dK>I}=5s3qb!)$vrc|-^(BP4yYa=*QVAqt%eJJpWF(<1Sb>s=Nud%=|5p*P% zVsJIDF!sy(3Gy?=xBRG-(sGxnXWd1!GS{P@G9XO02MD#98ku(4EwuvxdYWpZyMHU0 z5$C>Uw$pM%!O)80%Rp4s{D0YT*rSzE@FASh#kBPpB@r^?t@L7gY?=aQLO4wpBI+0` z0lKFqfqF9oBe@OaX5y(YXVn#p0W&;XQngV+oE(Q@%i8lw=>lNnMtkVZ0BJv>otWV5 zQ96I+A2-$nNVkfaaTAx)x$T3^_Qji((Vgw3HUdhd!n_Y}YsAL%9;v0XEa=qTujB6Q zj>#0c?|S;Dsc^?3WXR#+Z9$U2-Vd0LE7^di&PQ+GRHPqVz|s@I_xxh+%;gJX{Hf&k z|DmNLmWfr7j%?1(af~rqFq#xusdz`ukgd&?`W5hj3GLiQNuoR}cDp3Y8zTlQG%F99 zm9#fQCFuDhZbPVSLf6QuCRk$Z8s%PrRw~pvm`f^7ejWK{qBTB4k*VWqPwA223UQ`- z5trb5Iv)R$J@hIw^t{B?<Qxo6wlRZc+B7QCXdeIy_jhJpj^6zQ?XWF#H?yy#KMinz zj1Wy#S)51>HOfN*Y>CI}Sz_y}5~^D4f;hK9c$^7~@<y`7Aryfc+6-;_RK2)f+|=Dp z0=p-&a;a0B$~YfB<<`DL#fWYyOO?AAo#na}D2~(t<Wx*k*)CJ0CoS>^Rf}!VCgE+D z7g8nxLaGgkT#@#wUHoARb`q5gmQYbFEYJ%T=^l5L*<*f;0v;!!Tq5KXOBMk#AaXDO z3HXa;+K~8GJ}x%($PqMS4+B&5OL*FJ4S$6AUH@7XG$c)5&wBvA<&6iX`jzugz{Io5 z5GxvhuSWWmI9;{Oa0tcH$e{5oe12on*jI-EwhQzk&yq@f{u-ZtIigUsQZ`Y5s=;pP zPs))BQ6}sasXY=eCbpInh>5trc;OhlV54-J`nFAM3b!Jy>_F|e-)&fXg|Fl4JZTYp z9CJCMVYY!crpFC?mSC&dcx4ofdvS<-j0nzE!b}wUhy&z`)I!lz^T*<PREd)H0vqb4 zH>-r6-jTjaI0woNu2vNm=QcS9;rj!WY@$e1>}pmLC!MMfIpD!Yl>p-aG>nG&he>J6 ziEAh!d(|y0GK|dDhbU<)^hu<<5hGWJ>NRFbzhV^F8GqT0N)-_DnRu#-I}_(_*3!Ub z#%Ng2Np~g)S=xQJWHyjuabVVqUX;=r|Ctqzel+Pwggl2NlY!iK4+$<SWsyiSwRyiy zQ~nvsIYNTRfeOF30mr57eAC}`&0LpsH#LYM$AqM#T%U2rzZ<j42B+R+)ASbSA$~EB z(Ic|toX+F(WAXya<{3y#Vx>aBf;-%3OYOVgG_3eA&(FQ;eE7JO?%=p(eYN|yeUtX^ zvXRl+TkLGJUBJ#UW6M1|s_*rT29G~im{?4&4RT$5Cn$By0LbZ7yq2sS-e^8@p_7dP z_%8M!M<P)5C!guv{n}*miJwfqhoy{g2Y}+%&6eK~b>NQL9L5-LYkF$;%XeQc&-1(Y zW{!kUJVH>r<M<~?C3miw_l*Ed^5Dn<)ikAC|5itrhKJ3$dg|G_r~b7mRSPe))17k0 z${k(zq&V%kiC3WKq3W+Lj8eWaBo)`w!{uu_b~mk%g*$LwjZwl=!(Ya?%9rZ7vs_BY zoCW)^lffyXKZ|pZJcsjq>aBRa*WQ2Yob%_C_0J>qXCs%pngwbvlu5R<-<4YQ!BR=W z-6luSbDyh?z<kC1(!h5Qd?>VysIUz-*+h2N`;#-dm*1TuWaIk0f#!!V?N@)4&u@*% z7mW(QJ|tEqr7tv^fLSzRU89aW%KQ?)yTFN(wv)kKDr=--twh5gr7b!H<OGia2f~4< zaOQL+0+pKEC5c7)KWhhTA?as~uvSMq3x`*vb1xq6^AD5VlovR2NKE(UZlsDKf|J#p z99ap)0Pf2!zDRfna5b`UB=95I@M5v~_^tT?qzK0<iRav`5~^E{l0ydwlh1<<@5CeK zpq9GyF|x&p<~l3PhDee76-(oA-U`Ze6-s&7NrHo{<@7c3VgxAEMZ@I;XQ3W-lOn|! zy?zG$G#!rEK25z9DitD0m(RO_AH?C7Pv|b5z;blM^my8QA1<SS8}(%5#(-eBLk>AX zV0Nwp*AeN+T_b+ZAr?}kPc{5Q%42M%7DS&gsQ^U5gS*vWU(`-khFt3&XUl+Ht-4V` z`E~)m8mt)MtW&0@X=>F_+z6eI1dRZcIwZx8d(5c+O4&JL6_ShE!8EcT?v?RJ5#iO` z&j_ytA=6a4Xv!1@U{#@!6kD3y=g5awI0jj{+JxdV_bZjjjuJMNY*v-|0-y;>FmM@C z{%8n7kVIqQ;4ix25EgqDCUZH0L8Ty!V}W%3I=3l879pEplXUmmy#5<4_yp0PUCyPC z(t|n;$Bd_~`%0MwbSavur++#DLPvo!f%D~jSl2H<Ecv}`(%n41%ze>pyBE{Xn4;)W z%X}Y{7Yk8++03}%PPz8=<^q5nZJNZ)aWbbBJj{oCzt;`9uenty=Nka1kkL97zrwfm z!4ljwmRyGP+M>pBp@#-Ya<RA4&cT<yQp&=Z37x0*q>RAce1t@VT1~Q9MbdH0Nypm8 zcg{MQMm3kBf9b2c+n$OM3<t<{!yq&Aie`PB7qrAK>=YuxS`#J}onP;C*Q3fLA@FqZ z!o=_N+^+Q_MfYZ}keUfq0UAm)(u26)q65{}@mA)(IdnD&BFjTR_++!MBfUv&RPOVS zKR>4WphRWV;hLmStuTyj``h_xDuJ&7ey;ty?7=H}{3+pKrb{ZUT%?%0b>pe41vjKy zg{XL>VSTDSnIn!RU8lPYV;{bx<2L-A1+K=qZpwR^`OgzzZ2C@p$-fn(-W=q4_3F`W zI)td7H*1%V!l&E@IzLG)xlPa5sK2)}yonKcmMW`{JZ)Kc!yVtY+f*-_YEW+&Te3@E z5LjNuGDhGbdhpoxrE9Xjh>*YIt%SwR=Sz1gS1%<<B3*-$p#G(ngifKyt<6BFJDpKI z^{wNV+A{T|`6TXT$N-W}8PBdRf{Q7msTT|&H)p}87hy9Ju7KPrnIpbtW@VoF3BO_6 z@`Q{t;E<Py5OFV-%po-?5_@u@9EYozK+<^SkSr{oq6f<*m&;IQjsosfn$>$KDN6I9 zAw=?;Do}{7hW#zxx(H!qusnk9QP`^WE<-4DtHdY7E^c^!ZHNz-S)7)6K)jlFcaJ)e zl`g>bbCUmzi?|w?sfKEw_R0O<tcX=)@EgI2b{GP4S`{M=rUxgFB5?c|4mZ!j(dQn7 zK~+yj1^M?PWGxprg!zdq&O$(=YEY-LiCk%5++%NSyHzD_P)!ci`tX?G0Ll6VDz_oQ zz#kcW&kr?7?@fY=2GZwdS`+sh?R2&frrq=|SNrAM+v4nL>J1a9;MO^ze*E0-_7Yp) z$6}!T4GrJc-8hwjfS&iG>~fq4u;W@E8(->M;4uh2-Li%CmicRthHE~lyeHkX|5y4C z&Uwze3Y-;raCY&Jijmsz|5}S1wn#Q^+&0zx8EDk<6Z+r;zwBGxOYd}Le|5wrBeWwO z@ueVj|8J4bC%{sW=ysBx>!zPMP|j?X(m#s;C7d}5TUke5h_!*0s9S2}%8Rb@IaYQ~ zBREr303HiCJe<oDpn5(3Vdn@M_JiLEenesGLi9kwRE(58$P(IBi%4m#5-8(t0Zls? z`wyo~;_Wz9-QZh3x6_l|$prFioVh;8R65Y>8jE`(q0ctbXzD?1u~&sP<qLD9{9>Wb zj*#oEA3}Ua0ouXA43#M|0ubC63##oVfHfVeKH#VPRV=a-Gc1U|{13stZIKAtgxfj7 zxN|C$ILg3x*bMi$lJzIIaaMWiif?|RR2bkTZpC1TlxrgDn&bdi*2XB&2ogt!lTBV* zr5M@O-$=VIRW~^^;dcj@|LF=MT!$K@E-C<%qv+n_j$+Y%&>cA-|AF4FwO)SyE;I61 z?C2Lb>6gFX*Vl3v<-FH4N3vTh+%HBSux27g1C}O;G<30SUl-U$(Eg+&5Fj;^lFc0d zntwO^Jt7`EC+(~3V?j7=p*FB|xF?lqgi%m3)TlTQ=o?+5l(ZvU&2@R)WvS3(W~Brp zvQa{n=RaBybX)^)42TZor|Rq6uglDF12eAXz$!y#yO5mL!1f#&S6im_N8%)fkvwnH z3n^h009#z`-UTX0eu5LBu*|-qL(DY71#+DNf>+&#)=2z{g@u&NPY3L&=IXDznx2+L zI*I_wP;X2{0IvGE?Ip7ThmlVf3o8jsA>9h^r$|Mfb0sr9>6%zwqY@hlFwdX5Kyt^L z8D0QzB6kuU6C0u;%G2e-<MagCYdPE(byS$FN8)OxGIDUoH`d}!(pVIu+>NB5%u&RB zcozV}NFRF;KYCEPtnau~e9_%Z3GJcu3!t|&i4r?!1A|FVWxARXW#~@HN`I9@*H}GI zkEA{dZV@$aLmfV&N}%&P6o9)9=X$UlJsprY&P=Y(Q3St~_OJ0RF!aY*+OgwhN<=9X z$R(tT%JreA>IpH{$y9qR^SIGTcZ16FDykM#mb5c7kcttajgVk*>V^in%+Z1UTm#dz z@(I`pOrjc;eP0!7bdYtc*l0?*%$qrzg`{qe3Y|mCg@y3KEZ|Phk3NXTgw8rP&mhu( z-T`VHDN(ibu0^~InV}~RXRI)|t`TT!Z`Jfm%}ljDw9y8}810#G?x<p<l-#=Q026Tt zWhdEZO6mfCiegB+%nkP(E(akdL6tFsxm9t)Al!jaSrDRf00*swBc<cTKR$2{X}2k& zLH6*@lgmSy2&Na{`4TLUpL$a_Ebw%%K)k@eL?gXumiXn@>|TQko@oN)9Tm9P<R_mg zKebiuEa*0YY-B4@aSy?vu`H>tTF+DKxms|!awcc5X#bU6MGp5lyU^xt?$q77a4-{2 z;Xi?$iLcuF>kF4s&=K4Es(W?EXZwvxFwZ4_NLzYa^q=ta;h!_FBX(qZ#x_;oHvN3T zxD&mbI(QjaJp|~BliYJVk94)To+)2mq2bOf8<?j4-S+E2t6k9avq-b{`{2)?aLaE! zB>HCQrd0kLb^(r%HbarNqxY`L<X0d@eAp+aJCmNO`><}pAk>b?!;l#xTiCP0%j6gX zFWUM}UK*L@+5FqQ8wOqgStHzf!=`jZ=F|bamTO2r5HJB!$5R5exzgRNXio1ddHBFr z)0FLTWSUVNK;@VH4##)&3b}|7Q?B}Fzuq0_`f@!E@h&Ft-I018;W=?{iVPs^nvaFY zHw_H_cdefHF19L}<Tz6g{0>$1)WtrPBUcKBm}x2i1O&nwwMcldGBO`274hnG!=K(1 zdaS4$0)x_vMeeiMLrcX7DUT6}jI_%snKDHJiRMUL7i>c{Gr?%+c>sH8$*oe-kwz8D z3+}9E3u5<jQlsJkp#1vtb#m1q*#3*61@rW%571(n&|NBZY>yElWmYS3ND`$yo7DOp zF_Psd1E}A`MI~TKE(y?3J|AWE3^@X}^;6^;*$AVHC{glP3`yz1GC*w{|9oK~{5ZTt zjp$~pnFFAWg2e<Z2*il6YgX>$`c3WwsJBCu%gk6VVTUxN<pFk+AxWIH6l+0)lXG07 z=D6iDFZ4kqLKcv(iRqWC`lT{b&LLcXNL}j#n|PM{nG_^wx*afjeg#$%_o%wBp!bOK z(^BEe0fa3=nFbyPyr@3Wcit7aS{tl=q!6|Tq((2|^`aM?$SaM+*gDVIlPE+Hsq1#* zmW0eyxSMc*6dNZ%;f?p{E`c=KQR=`uNP|LmiHlxvR2Gh|r3eu*ES|RNJWK5O>f|jx zQWxV&R862<rs)>7nN@{fQ-f+!ahi6Uj5~uU4)ddGbUx|;tvbFX?s36B8STl?jgVjk zq7_)?hcc9WDo+ON9)%mw775{Lh;!?{szYRCrXq@A5pq6KfJk>|J4u%qTLR)H3{9yP zj~SP!Vg2h-tA$+jRb;Rd7#dtVf)g5vNNM%7vVw(+S;};tV?jWwBi_S?j)l(ZHYB1E zV<NS(ClYlX-pwnbNr!mN7)PohjxlM_#6}=TdV~}Jj5q1h0<y|+_|a#U3i-%GDL84> zDkC@?q;QnZ@NI$^My*bQ$<mSM2tB4o;HGR$5ccuW^a)Z+*@lY|U2Vz#91Ef+k10ky zsRdon=!S+%fX3)MZTfx%hvKUnrE$g%Tz0v*Y065xwiJCkSztSt3Dmuf&qc)^E#%Nk zVM|~Yoa1RKZ6PeXSH!}DEoDV~jZil%tPBBfY@ui_WtviG`kA(P@%Q6$hAv(?PY<S9 zcKbLeC+=rpQTJKZ9<aFNunZpi)4;AMtb*|UqoJ~}I5SI!VQquQB<{S|mJK{(&W5E@ zI$k+A<SyutFR+J%kj#m&BgN+&r@Oh4kH>v{i^TlK6Y^Z7jUV<tDA>pHCyF*BJsin> z^tENkk;O0Zp?VOMlzg@j*{JX2#Rr-*avjIZX3P=SKU;Hmn)*)}%A(jN4|cJ)_U~x) zbzcX8hu9A=tLM$@zM-(qL7kp$*9+0>j_$c@`mo~kdG_lOspxZ5S5Dmy?&$jBgW_lV z<?0)ZzDzeXFjJ-Sq@0ij%7hAl2e71$T%S!iSI1%iL_EF4>lY}iO|FLO_xMwWXRGc8 zwjYW9ZW0@h+Aj4RInX$AIPcHC`r>8R!{xpJn%u6W_l6=(LYoXa5;f=PeDkh68+Qli z@WPM9&&I!-zT&%wHlk=Yxa!3X#~o|Z5X@G?Beg~16J5_<5u*W(on9QG`(`Sv{7=p? zCx5&(diU5BqCf~k9gFR+L>(nVuw3|37WdfXE~M27Z29p1pX4}>@ttjrf4#jY=(}aN zq+y6{)-wEYyzgYTsmW*;_VPWhss%bkh?E3*{@k!{@4T{sMe522$(-qG_#WRUxd$;I zQd#FbEJLHHC&9c?N(h!3z#DW5sX9Lm51WgS>0Q(+lG9(+4!7(#q904pj4vRy2yKMH zati$?fvyD=w!L*J&_9|I$(sIkhp^tJyiGfWB{N%4)y4H8HVuB7-F`U6O3r>SQrN1Y zWrPLk=s1YBc*z`*r+3Qa%CdBjd-ZdV_o5!DvTB#?lZBCJTdTXWW@CkpPrRB2Y*WBR z9R^neX(IqhOj*~}R;Zy3aAmE()nId99CEHK-y_UfjdgHm>WBF^-?)%X&KIJ@r+JrP zfkx%$r}Fi+Z;-?0u_XA(Z_~~Pe*yaO_6?bw%U6Chv&>9ASQ#)%^`N0VJL;6XU!bR6 z^VSG;pEvr^HyVBT2p52L*if9cJ++&o4}6uNCz_XPf|^qjAgm!+<3e6Pa3*{UM~1CL z%)~NLN4)pw_rBQ%kZp2A{=SpC#$J>!IHmYJ&~>45I^U0^lQljZTEE@x(7JdjW2Aq% zxGAj6bMu`hu;8{n1Y&L43PNc~5hfRcv*PMu=u)%~+u-yxIv;RmB!Xy_3F#`I^jzLr zs5W66a38U(0(bN?$#!d-XIgRmQRuO2=`PY0ni`boTuous29)FoSEHV^HBX4I3AG3% zUM>xqqXrc`u)0#9a-hF)Sx(<O_K3vNuD)V1A!-iP)A{JS1+4KQ5~r3@B43cNL1!J3 z1p&L44=W*Vv?k?9EZ5O?&GmVk3Bz(&;Qk#a`NN^WMEj9$a<H&f12d%HigKmC+vQqD z!^1L->_Ifk*b=Wui!9W;Ok=#tsEj5Yg|3O)1?$yDvz>Fq%}9ZSh-^PBwfyKqkOMNW zteaSYgi)Qxt*pkW1r7#-#a!~-%-aO9NxvkK6r5_~Nt;vz6nquopR~afX{`Du;K97L zCN^H61wqBx_KI{kB;=Fh)t<CukhI(`dEvD_{IzD*B={8xvSxS3PV|tW9Xl=5#uoaJ zvxZ%^1qVq+LzkI7mN>+&8Os#zLZ({BX*x*K^`r$M>45OtyFg8jgJKIlD1LXZqO@f0 zqk4dJP^^_g^)&VLS_E6q4&?z5WGy8#W)mtDgnPPXnmQl4go&s@$xNJyS2DX75YU98 z0V0ZP;6W16N9onOE)GSluuxfgmvMu+;ydnDg8YUadVbgu5QA1umGx)uKFsNDVN2O% za8rpUHUQ)w#8mjKOq_#-tkkw{V9{p6&)vv-d+r80pF6Ynxl*KZ>r^vo!}fBqwFg|! zBb@6zu2V1YA1oUqQNfCPTplv>pf~6&2fr-in>Kxtb?e=^hiG{gAiXm)IC8_}wyZzQ zGk`wBs~7dLdpF(FYm#yp61&!aQC%8bgY8L)fOYl~=Kg6&x=g^6C|pS!Ark2LN~?TV zA%CJZdg{^jx;tw?DcS+ZCi3h}@9#EUAW0F$a7x$pr>^SWI89o8Xq`0mFnsrTm1VZ8 zLagHH8VQqOcjP2xI~lvl2qj)3>Hc*^(RYpk2B*8ukytd9wI(;ftC&EyC$dE;6%-JN zPw3P@i5MIg_o5AaJB-JG?j+RdZ%OE$)eCgSf;LaO4i(XHSon9{1l<{@yCNACH-QF4 z_D2_X#WFgZ2U?4GZ|zKhO|%cG?Nh+J?f^o*0;K^o8ff{MYAAAmo3f#}!TFsuS3^;x z#PKEVHBb~=;(T`)?u{bMqBolft1b>v#wrmcfUbJvxe|C?57Q;PhZ0WL2r<XF^5m@* z{yp*{KaBvlvIxGNVgTOPKqg3x5C^A_A;@H-CdOgAzWqt`7M)tglRHhlR>t}}v$#^Y zb1L|v7La-1x(U~~2<tCefG-w<Q$fU3MMR-XjR3UFZMs!yCC;P;>#9So^4dYbw`7YR zx=m6F2+&2qWvu8L^vmBR0Uo4(2q;z%j);;IpbHG7Y0V!Ns6FU(D7KKxAweaBk|q^D z+Kv(%0^(x9$0*3K1S0`Kq|oa~oeA0sSJqAZaLUWy+RP^*xG;Gmlw3F3CTt+#3?_;| zoAxkYq~U2Lh~|hFfIdL6WpHK@>Y>;IXMopZnDI8CqT0NFpv_?=o+q2il0X>>)1x`- zK(is!<3276zvd+L7YVp-&Q`RS1?=kqq2RE^4f%(m--)BUtgpi4x(4Az<{1r*eoY0b zxT<_?abx6G??fXWgZ2P-i;5bN;SExKrwFy1rYUEZFxR;N1tOt3*KPOj{#_G=98T8< z$B2qAS0LM?TtFcTSc!M7@zPB)PgSDdr<1MA`Y)rAk7ayO^!>Ld^t1=@BqdFvvU1-y zAYVt(!)1BjF>iFXUoR|gepR*l94QIq8=#tC%h)LylC@da!k(-5>0e{p4T5O^Z(n5( zUAemus{yhkeVU0p-Zq?JAw;{ZJWpg2v?Blp``%<U{YmJbA~`NEjI*st5avp`&rxjT zo}*Z%EgG$0V<nMbjp<jSouN$y^TptxB6Bu5tuiGO7M-E~ah6<Y8&EDEH$^%Mr>gg& zeWOhakV;Tdyof+lMJeG?npWWF4Fk%({`f?omkPpNf%HO-V%NeuzR0DTnPN*DYF$1F zF%&&HfEOgh=12mmIk9SIAz^0c8Df?~!9-3mf}Z;86=9rSZPd~$+D4>-JFpWEm!c*; zHY-T|tN(+)bZ?xdvNkBVRvC0xccrPBqYLbd&DA{*kA18^V1=gH^1g0(fqHVds!JRh zbb9kM<z;%|5$_hgcG6<|^l7qAllGL}_sCgDaE#Hd4Xurn0xhA|1`}icZH8Xx-d(Bd z0)jXbDqXz$khlSo-S=8|CV!{<iMe=5b>|(HsoBT$ygW_We`vTi5&lrR%<8n?K)!~f zD;w+3Up;37`#=;BCyI(g!~Z+33x5fv&m9{QK)55%w_uRAnG(sN)Oechy^%QNUUK04 z!kiEPJ3c!sw|9a~M{B-5w)p6q%+P4##o-^s&0>R~njg7*{+-SO6JPTVw2>&*@_5Ca zbNc1^V@&{Gk?ctPzE=iAYr_AvtN30~Bj3j98c#4;fM=H`%_?;BHl^GfL=Sk2G;ks; z!L@$ZfnQ4C4|lQ+iIOU&#$(>LDLHUr)BZ%lKOh7Q$!Gp|yfVBLuK~RXXu0m<E&DCC z+nM+6V1r&~19EJ*G?%~>owr(Ujn^jVdlnfWfHr{A3XKYi12ITi_RU9SVBf4bbw<c3 zhq2ovj*WJ&So=3-f<xM=TD<$<NE0IYDy4r<3=ieKtZD5}Kk1jZXB)UP%6~lF-dO(( z)S*Tvs*@e_xY4W7rP$~R6zTVVXgIc>?gcWnKdaWpO;fkgyZ9n6_LZI&_B_h1c+^Co zPcn~9?qVLwu)F6&G1Nte#XIN5>5Lkr-rCD2CnZ&KEf3wqiwMorls@E{<16Mt$0-3H z9?^%5Od&mA9J+|;jBF>nn<#ot<UX<@PTUl3R37TR24d76P^Ki&RM%KJQfB|1ax$rq zQkS4ldnXYekO9aB!L!t11`!Q7RldOnpotFg0QCWCN?ErvyA9N1J`Y`=68lne(1ZoZ zdkB<7v*yeJ;#)$Zd;)LY6`>A&(IZ8K_Ed~S*V^RJtmBM@gQD<gbz6N&$~ZR^CA3+w z`1O4{Ba&Z-VPycS1EA9029*&KRz$9AMZP&wUaJ)T96?6{5bfc%NL=5Owx`UChZn$g z5y_xl5N2Ni1Fv%ioRq#p1c1oxw$`!+h&F)0*Sas_zh-Kmlpa1d?@DkxbTuYtCNH}k z@)!nXbVnP}=fKJECUCIJ;lPYJ9$6*<o(78m`<RHz!*XS%-`%8n&Z4)a0vq_K{B?c% zUE^qSq;6N(N|j&|Wnlm#%PFZJB3%wshsgcXb@ZN&M?rmIg1m%>gBG2^A8wLk{J_L5 zT}3j`%151w%+b&?5X?B^T&89f_aIgGlr(Sy(5PNA3RBeP3Fm=lfY=19Cs_@0zG}t^ z1Ez(L20d^q;Je?b5Xz-?8+verWh08}*O(d-Qqi0+f=8N7=&gYUfQzB4*?Oo^rLhHi zRAtc=qqBl|Eg|W09K1IWTN#cPCr1y5#|#VEQe8`LBIysI?Xx#j4qH!{$fabKE0*>g z1g@z}f-Q*)fGI}_BX3uv=E%tRR4u^y#3_AVn~li{XO^TG^%QiF9&dFe#C1k~7c2^O zuD_SLl1B!|^iZh4wFx|$<8H#cQ&t8*nou}7Qi@CDtbbES(or<^vkHAUK-D7QuB*&F z+>x{B-_Y?_fFQ?r2WEbLek`zz4<de|;5T)P^WHkAnBf;#^uC0nt&75vTn2FiH6A{h za^WtN1KD~@=VHgl;iHWvNWE%m(_1{204aJTi%ol$x9b|UaG~;K<u;J%Fess2+u{Xi zI$DlVv<Z8O6IvPqEfn;jq{1@At6HkS^pmRry?%X0o}WIv!m>xS=Y;dAXy&*Cm?ImN zu(RTuBWGlJylg$Rct1o>y|X(0mC=VcDn`(MC!3v<WU#$=O|q2~nkde5VG1y9MgYL{ z;=otgWqr!k0Fx+i2oLKb6hSXJj!i{}eq6&Yvl6zelW48t0%k))Oo|+*&T}T7DJFFk z0ezj&4yheGK#oHOn`!xR7WtmShR#VKAs#VW0_GR<9ocPWRR-v0Cz@R-`WtWv1}i*n zh_2Dqyy!L&3KsFRI-Z>^P!b-<iTr9rOku)XSbDJ=jdk^C8$<;t-Sn1ggu|*&oQWun zXynS3@YI;0K(9ltkKLgc^DlW@_&Es{&q>r9Wel1>8qx(>OqwScFe&v4iYp+a8z6dM zi$Sc-bf2v>+inqnqXi_|OZdu81Z^nsO*>If9i#80Uqn$*FTe{5^lJb!$S(d~N-2O% zroJS)AvhfH3luM2Crrf)JdVT|q#5KMM%*9(-IeSD^eA+SNQD79pD`_E_bwo%eYYNa z%AFFjs-A6jffFBbA`dzXf!a|}F^bkNN83@)E#y-1syYukHx)#(olI(?w?g$$jmm8j zzDCSkB9Mi#VwJtFYX}o4<PnM?7PjblV@P6e4$O!WO;ho<UT926B6&@P`2tYQgenkz zY=v^36tku%K@}Xbn2(s3)en3l;Q>`bqj@xeRIbB1!UK*U1QPF2jB>m7Gy~P&%yKok zGNA;R0hJoO($%n!i6D;AaS@H+!3s#=mLV>JIl4qH3FevFM~_#MHkkY=NEKa=d)tW6 z>w{6OKu7j>GQt7ga||KX4K9A=;{t3GVRo?*c{I488c<8FW-;kZ5k7YSqf5~1K?S5k z@_?wo1yO|eUh4ArIwE#C2g@>w8Y%Cc6&Ymfz&WtUHPDlwZD({2)%eXEdy0;j9fT?Y zCug|jM4fE%kgsm@e)uwso2)UsDtYm#f(5EA0f_fna+_W8RiaTL8$D+cxni@}qy@%< z>ASB7Qcwb+lQHB!Wlh9oAn}nots;-B<da88Q#@G)p&i`C)c|)^mVs$y<A%V+=ysr6 znj=Xt1UW+}k{6LjuKSIKM$xul3SyT*cDclU-C{t85m>*HoJ9#_%a~5Fpmn$nH$Ftv zJdEv!cv)Xn$bwAxxun?DAO`n`9a<z-h2umu^{jz%!#j;8e0O1iGgm5$r_f&*T!kj2 zbuH{44N}2@me{$H2PBe_!EyK)F#40ROrxipk8_xh4{fFd`wn4{1U(@omKU-2(aGVh z-)IHu7dtj<myyyM6B^FU4e7(eD%uuE?RvYu{K~I$)9<|XJdPCI8H2lhR@;_$XuNKs zpp!^8=mR5A1DVj%#wk-o{}y)cqImTQ1M^QIA%zwL4jnlZv-`W%9X0cN2e;!}%(KtD zk|J){Cl#J%;|91^h}Psq>mUB7Z6m;zEJAgLEG5Hk2u@~);@P=Gx>7cVw(^ZK+_7A^ z-%;qZI2qbb2^$SQeZxFcU=kaBV;}nL7x)LPI-~8*z%%-AVXk&n(NELV*U#pog@tWv z$`dQ*K{nnl1?r)@TQ53OzLxqHT!%*Qou^bEWbTU+B7AsJLhsF*Czn(Sj^F-g?(k?Y z^F`6%iXe7*d>43ZtkD>44?knrD$Gg#Z08I*LXLQ?MKfbKG+xz^tGg6Ocakf_?~|f> z29Feg&S+zm*eNFJu#FNFfv`v(@38zZ0xVS4csDCADyaW!N3VuofQ-HF!wqJ{;U>>H z&hq*dv^fwq#6#U5kKaRyM)Y!MlI7I>cgARoO@KJlnH*lF7){;J)pupql5i%**jxQW z$wpNYj!$h~Y~brfu8SC_02r)0aoHC;5D<kvD2co$bXIOxa?7q*E*0IhFlceR+H_|- z+KV?m2>}?$I9%E!3wP+OjzZrr+kT~qAn-&UFAEElMbveZ`gKbZLS<9#lYUbT7q<D0 zpepT==lzYI(7E3}bwyO*(u1(v>xYojTb!VWLxlEDp|HyA2h?!n`GKqJMx9+U_nj4~ zz|_B=<00fY=(98^uQ_?!Ep`b~Pg5i=trwKc2AT**P;pg~DNAqAge)zIq!kwc^k{dG zmvbQ{)yjZ35x;D$hfsdhxAm#5P?@pPel*`aX;d5wP@IbB+1rfRe4^mD%6|2o>jr4^ zkX*4tth|t*f+t1pbGRT>yDOvu#C!PvB0{)Jykj&?xjy1~22fOxVEzyd;t>O@)`Tl~ zPZe$xXFB`Gnb4Ee3t0_!3UnmKm0;1u3)OmIu1`9&1&VaYrDc&Bg{jhhsbeUfR_>im z{HYKlijV5o(3sw2ZUROrG73%ZL+Dg2B%1Xy5|H=ewrdM7r;<rj0=hEMI4bU6GfRq5 zBrdiJ*c$|!GQpy^c%Z&F9`8gF8E@m{KhA{FPzpeSV)iNov}pu|8eXbFF%B-ATD*Cu z8QqvI5=dy!0}Ymlb<3#$0Ol?U<Xi@@fKYKDkQ(FBl{0Z<0Mr(Ythoxlm{i>6EJ}n< zb#FLmA~JKJG9Cx_Y1Scwsljz`Zc%x*B!gVdAc=)Nr6&w}2budVc@QLsw^|~q+7_i( zU9)R#pK@6bS_%}P8-sc>5HqNjMK(FRW`+cF#hKiTRp@taL@}*IArBmnG-HZp<J>x= zLI#3-<Qg37e31(x56D6jWqD*eWdflzK!%Rud^423R`h_~2uSpgOs5>^SSKzpZG|Z5 z60%fSNw27w;FXn+K!6KD39Rnbi>!sYp?7@Wiys!<Qp(&pd!Mub7avV%;(pdc2CkLj zu--ZLC^rJw0GC#|#-%)rwhe(Pz_0|5T{9DP*os)28v|c0YAinqJ<XMV1s20v?hY>W zHu{MX2eDoF9)?uo1*$zO0J*?EkdQEl9u|c3elOnEO>!zu-gW(*(}orA1)&uIeYXOl z8r$XVcg<YdIBE|#i#Bh3_x!|-lR2&Q3R(aNQ0Vg^h6EvE0f{$JpkI$p(Ro;7kboer z_G10SHLI2(+JO^9gK(lqv3&hfbqiS1)2HiOD?GUb3m^?Ep_K<?1VuFF#*jMxvK3sA zi2JD2wH`MM8grPw_1K2j$8FfK0$@K!9w^%VM5P3J%`<;P(~Tw)1aqZT$hjsD5<PlL zGhg*&OoQZz1ESO2P3V_zM_-rJbX@J}(vIDrhLB28pGodr1=7X)k0?@$*3Zlbpu&e> z4^U_$a$%UR`D^YMC+7xf&vn3^VK_poB|c!9GLg~j#i-iA+a2n&FTi>_(L*4pBN=3Y z4)>P0b3ciAEYlUwUk@r22NpuSz0rTX#~7tT9I&So`d<dagB-@xZ%7#CBf)fZ$p2~p zc}}3$r@6BSGY|>TIK;ULonuwbxn;-BrnoMeId=i#;bAPW0wJgNT`pkRND~9e9B9Fo z%DygIZj%B=hCKd5DH#BDaZpgNws0H<1C!|oPWMaCknswPZXdNmD}-qxsOScsY?p~i zje!mObs?+hhwn4IEVx6g4i{Vf>`|`cXORiZhUZB{2L<~%jzF6eg?|_pkkMS!XBw-X z^lli=kUIWUjW!=WZeTBB5Ic9Kl)Gs|mmO2!dzWT3*uzV)bI`#fcX;K%cYZ|IAJfOf z!0}z-o@x@3y$t!PHjYd1oEGW0X$n2IlV9bst3^bZa|>1n=p(c)w{-oAZa*mZNv~go zHuLIa=oa9)M{=bnox~W6+|7$t|8U?=?-rtR!lZ*Ns2s48Bvk#ClkhGecJ60Dqm#~{ zRIoD`Y|3<ERk<5VYq-{Zs7PF-gn^pkOqqI}vPX84`6b#c=m2FxLSae*2tE-07`Y`E zhUhLyz2ky%h^XFC4;fe603r?Slt0m{cR-*`Ix35Xk3zCa0-}j_Io3$?tcHH(m$-qs zhj*{E_5NK-PF|7ajMUQg*<@Rya#Vr^W9rNr!PGqd<L2<4>d7|{8z5aUdz%BWHDcjR zqv{UoD(>g&q<%BSi&bEiJ*fyhE9bR3G4MADUwsM_s?wOHzEy98n5#fAPc=N~KarCl z1SzG$GX@lC6ilWVLa#vL^mGT|pRS8-o(5%9Xf$BLhJVd~f?QsR!BBMkp;72hB4iGw zgv$(8jE3w(?@1yL>BXo$A}Yj=Z3BR7KIp$3kKV)A$2>o~kCnMHQD0-X)`9+k>bLN* z$AZH#eGnQ=?aoQKtdW7{z{t!(o5F59fs}@ROEV>bp@CU@lJM_!sk1R3<uMmF$C<03 zU^AZD_VCW5qu&%?H~CF9IkN&Yh#YV4@}=v}e?AuUN#Ml$-m_kSv6YL5ZoQi#RK}|$ zUBc@qfX%fdI~R%5w%)shn8Coq7pNvfX1<S9!$%0y<^@mG99bF!*-389nb?vCSxm!! zJalu6vsD_P;QQ;w^9PK?2ed^m4R7o+y23|8ztVO&c64=4Q)imKzUbck>sw1(F1dtQ zgR2fzus1F?)*XK9?GjS^)}3y8J^f(s-2*XYCd;TYiUb+H=Cbrz?PukYL;U~n&#dY^ z6BDet{K`Y0+);E8admXxZ%oE9$@<n?ms{V;)PDCu(-{+AXSoKB7xzJ0S02l*16S(~ z9rgdH<{$fA^RMpcHKC(o7rG#W!HJ0yH{Z$_+k1Wd1<w-?&0mK&6D9ue)%pedi4ZV) z_jl=yJyV~`5T#!Kr0L<Tromm?eiq^2$b=ljeW>D&Chz|jGxOHiJN1EO#dc3E5m#PY zVfEzJ$uFy=4N8W-{r$Mzz|{`P1?b&7MO=IB-v>v>_v|pK|EByJ4hb2rXsWq(^Ktzr z?pHh?|26#Kf92=D110EeGuyc1cF!k-q*+Ab9ZLTCu7U4O-~JSS?gf`zurCg&HP%kQ z<3(G^>3%!cvHp*|(W!lX_oaHk`en^`1)ILh#ZQ4$jVc&BrC*LJOP)<8%F#}=l*{&r zG{INV?*R(zT>n;=C(>hyi~+@lIS**oCh}GkRWYx3%g3+}{W!oyGUN<G16EhjqpI#7 zpACHA%PQHP6Pyh*FJzYYQr!z<GsMN~iHm(v)QP|`aGK<Ec}{W^`b+vO(%I{j#%m%R zAAk7_dTgLnxev)S+=TyE=}#{YLM=FNnmQf4``dD9e~jx8<fyKOsr*~91;7e0#9+>Q zV+c#=DDIf1GQnbyA&bFduNHtaAYhKn$0TLM@VsKN&b58^#hEA)Z^GM6(V(C@lkSr8 zK?U@>!G%G0qRW#(#qF_<m@5%k(f$y#ieHxiBdbsc5;h>VfEy_Td*mfEoP(AQc^?Fp z;5}qvs_>Tmqof>u4=820tPl|ewgFKHw*OjR>23srWoFyZ3zgn^(-0rhSnIw{1QMi< z*4vRz3ZQ6$r{?<j>99IP`q&^$=7eCcmgA78dPy@WZxGo5Zm@WTtO*ZP;564=UxHEf z>W7c~{v43xSXLr{f`OOa$fEIvUh-5XP_$-cKn&nQ5nc<r3-f!W(EXA!;6$O1P`gFK z?*+LH0Sl?^$a&iPtRC{0oHb);XcjUx$}+G3o(w$dgr>O^JPPD>=R#Z+evj4>$R_Y> zEhP`2kAZ1f9WMt;^&iUi`9nDXq8!NoS%PrcrD(NU!9P`UM$*6k1;yOW&)SS7Go;{q zn;}>L$vaW>r;1|9)I}t+mA-c8Cxj&Nni5@;UWvxWR3FDc0H!ZdB_fy!>`2VE3h-mo zly4CX3KQn6@jbj-yM=#=jaC`U;qcJa`e5i1`?eP0o?W+##G6_?w<JjBK6jiBi^5=3 zfw}5YNJ#LBc$R=0<O~dN=@^D!8_$*5h7A}h+m1#JU?$1f!(c55;g7~QRE|m}lJi`@ zgv<E;DFlhJ9g9ORK;_s0ML`2~!DYg2Ri7Lqr_G3_9Ee#VWKVmaL<<3(XWaS)88o{Y zL}hjkpN{4?(HqHr_uYFC83&=&g2BxZfRtaNuws0%W~N)!t;cg&^!x&h=MtG7>Ld(i zKzwpZxeN|Olyfjnv~=NaQ}>U);H6CWpfQ2yS>#xVN_eF|5kXZ$gM&Oy^ysSwbtJ~D zLT>6SdFU<w7MAHrKHa;OWxl3C0Yhinll;-YcIe6D8R`<Q-`U)L4*6{yLKc&h_M&3+ z+%CunAj$`LM@3>ffhh_*;T^5zG51o$*M^_2KeXZ|M>=cbX6Bd1i$ngOquT5Tu}q$D zu%oK)G>iIlWDV~sb0aa~nQ9?vS1%8hE@I>mZ8iwcv$5ncNSwu|MS`E^Fc9Okm#JF- zACk?dJyx!r^GKfmq+f<Uso!&$X&|LBl6a{rmWVXhI)l;?Jpfy+CrEQRQG#bF0NkJj zqs@IJCb$dF@@RqIw4myN;Bx(~^XTtP_F_U011vb7DV878pG%D5JMa)C><OY&XYtRw z>rt5z3P77{>N{!SKlk!WM29BF_L3RUChq83N2(;bDIc}I6tyDEA?Ft(ZIiiJ?EdNG ziX3@a5{gVz*gv4;&)stb#rt|Uu?g<>Fj2xoD^PUU`JV_7ZHWI|5<Z5umXYThoeGEA z`5dD7F@L@WBDaWT0}D!t@J=so5FbKseIw3jE36wyTDekhaXFrr9@6sj;&&7_sTf1- zT<yU-r~_~;jugEMoNpkZ9fRWDb7cfFNt!ihafY{#WR6ciV<0>+$*bAUyj`-0D1h^_ zB0}22aUcd6O!4_-Rvn%pLX=uBq~ItWVTOifMv&bdsDX%D8}BWAyd}ZqukqJ-bB@Gy zZE$RGQ!LO8`mSfI$?zQ>O9C2RMO%#}Y}t|1hTu6{q2VSGT&9(ctV3;vo0Pc^q@2Mt zuf;&LYx%*{j!n<09l$1tNVNiE?Kj`HN`#12%b!)_bQD#-((ONyeH|0&mF@->#{@ly z)etLD{y2N3lW*WVolhZw;b}@ZRS-Lro!@Ul3~>OmLP3Fu4k8ix4@eJ!rM3_sgo7f; zE<)J&M-c#K9UNdwmGNQ}n0QFl05g#%@{A>5ww1zkR?|e0kZ)_l05{4>*+kA73Px*2 z3gQn7F!zxbq2s+ffHn<j>_)_kn?op86>&)1EW1@Q3$B-dkcla0LVU#*t@kN}AqJY& zEhm!H*~0R&kI6^?rk#>Q@PUiL#x`s`%=cyzY~?TUTgb^)3_yuKqg4*AKpNi_JkOBm z)4%@6ff`w9uLS)A_G||FH<-~FiipYT3k)2&W$VKn!j>AHJ~jB>C&3?S(_+fEK0096 zW9}P_o%|i`lGFBE?6Qe)XO>^FV<7y$cHIgvp*`z7$*Xm%@f0JlJ!+JVp9zaH9v7a1 zakIC2B|YV9)Q%#iMRun3^Cu6lwwN#z_RH;44tFA^Qm!gHA>DzO&>kzPAGLY6pVPZ0 zhdXvJ72k_~0l~tI^cmh#6&N`%`PXoNN$Cw~R^Qw~;ZA|_-3`An+kyS9U}rzuTJ^89 zo`zOBpjRFs3+&ab_=Hzr5@wUgM5;X`Mx3OL>%+fEpEvnImxO)S-*0f^Iew1RdaeN3 zB84Qt^}2idgPZrga#8%`XPC!@oV}G<3?G4L&JL<(^Nt-GU5TH!mwBuog_nAIOySoE z0}#n+aQ^V5vMXcCqT7SNDY_mg-@{a)myimrpaI<caCz!=_v$JsPm#WFi5zUOrTpXG zBP@d5Taa0-8Cze^)MR~uMDn$0^YI&UW^7_>mT(R@3Z@zgxxYjR#+Hm-F=HnW;X1=c zcVwP<C*lf9EgZMxS9Lee;G^Cos3GSmwBqi5imA78Wc#Aj&%$>OzFo#j@xUr5${R{~ z{9$@uZLgFoLVBw9sta}cbr~Q*FsNd01756Xp0yL2C6u!V%}_gmr|_h`80;wU@Ac?4 zkRB1ra`F})4yI+gow+-FHhcEe6(AqMQ`d(9fMUph%6JhLy{1UpirWgJF_!>6J-W_6 zoX$IlslyC{7}20jiaGCFVDiH>2jHc!uAG~JCNG!iIa{Y$!XOnFIJe^|JQI22%vXo{ zT*)LhV(kAPE8?`6cFRUgs=TEGf=z)Uf5J49KpLl}?l$PV+~-b45Hc_s;}r#Znf71k z#^lN{e}NXoARd*6@t|M|`5ju#eligtT?k-l`vGIT)|-_e2*Kp6e4=k39fszDD{~F_ z6SPmp@cgu%bq5!e%s}nvYS_(h{J4+E*apji=Giqq=*kkh(>6FpP&ST#F0^_W{%;Rh zeUCJz2o$AQDTdDQ7!;5kpxc0w<{&s8L2n-C2%K7ggu5&w$$5DwlnGYb0B9Fzfg4n0 zP#q6^B2+z#q8c3&q#L4q>@BzqhGgYqupunc77gMY&l|9}REeN%Ko-cY1ftTfd>nsb z<Zjox-=9%a3%c@PpXwUY9Uk9zw$fX}A3@m*BjHkzgC`*5Rl@b<u8RX;*(hxka6<!u zOLsA1hONM(B}{=7p4FuBa?`Y20;xVxJe|O^J~rTqTc9gOLz{3i5g|YV0hb}xkhT>I zNh~tuT10$!Gae|Gi`Eauo6o4i@o0_~Wjq7T3St>l2?FI3q9O`HP!X`p0YR$-h?pN^ z+!_qAHciGuR0NL$c@Dl9z&IRg7%#@bc|?mAyVKEuo(v%*5m_MeM+FEa13EfrO3%aP zm!l12ed%hU93U99scr8ZjC<|Iv&xi6R0ILUW?viAqZb7Tt#)jON-9Ur2N&FcH3*?s zh^I1iU}N#&xsxbLps5%<<cBpwaJObwJ@QR(46leDyDq{b3VKJdqWyS06{H^XB_OM$ zYp?Kf(GkRQN#`-UjaHUdmU-bSa2+09m^m_l4i#~Skc*%RL9w(K7%*`-DfoB+YSX8a z3V!ogVyq}d=qW4I%#d`i^v}14MlEC@$Q6EqxI^JNB#58LMc%o|{8;c7J|v<460c++ zlyRbCU@dt__psDr;&W|v33n}y;&M<nH4qaiMj9`DgA#&`z9XjT5#hc#vlkA}#FXC! zGAb!uFWg5z4Q>}bW6w=(dM}ANYW_j=92~^T*0NmYYYFc;Ohbm9dA6|CMw$_zYe-AY z)sQ(Vt|!o=ExJX0l^M8<HU?ZYDPSk&{&1Aw2{ZrOjm9Bd+d#0g1@SY(+i)LA{wp8; z>&XCBNty+P(qFUS!@pM#rs$c4gPZpwGSs3Y*?1TdTA|8XvrxQRRDd9lLIP5b_fMj2 zI1B^%H0R=(0YV1somqO1!C6Kmh&P+ZKDvu8hRpLMkjL%kw9AN~6SD<ebZz3_TjOvr zc)*!D9>MA;@h6x|wNLo}F^!0d(eiG=pr35MtY3n?sV34`Fs+wLkEHFrBUagi12z~S zDTRppqH1#0HmFl`pc-p~Vtal%V9g{Xj>rD~*_NN~fMAcruvX%pVp!S&Z(W6`+E?@y z(nK25&*=3yUv6POnv_;9w%RiDdKn-wfYda#V^1>M2~Go#D)cO=eL(g|8crjm=e#2R zy;Hp!40w{AD$M!dnCfN33BX^|)L?A3o^KNB8tb0tZg}S`Tn+U3Otc6PXwnwu6t(Qy z21bL_UXY<<OE3n4)F<yc>S<u`oFD$%Iy_cVR;a#S7Ds{_AQ^-%q$}*uZ`u;vj*z4J zLh5mbSZ20mun)0vlK!C38EVByqhwQBe*);gL<`Z~o!@{;HjV~ZTP$FY>{<UcjVC~E zk+-PZ6?=Hc`<I9A$@v<}f{1A4>es$OkA0d7BM+C@W!FWhA|N#Hb)TzfmJX)>a)b}v z3&!3m)81IGv-f(^wj)3!<n1xP3bkxlV*Q6f&va~V&>7>cO`UQ=uB%%<;~T4m1ojc- zZ{i-<W#v4wiQom%DuMFR_a|g;DQU1BO+p7r?tQB1iNePsjn2?H!r!|bAQMKakp`6U zb3VtIE}po-zw!!-`F#h_UjWyfYlHH~9-{XAqhuzRa(ydG+2e5ocz6_M?HO<=+5%K? z28$sWrY{Y_RuN+5wNk_*VlwLIM2R<@C_zvlHj^$+TQpvl5(ty74)MuQIf{5#Y0@}G zS#+bMwVo0fAbpA6;``GFy5Fl$g>B!y_$@0?zv7V8tUd($RU#~wW3e@ucM*+-oQ}aC z;5^VXLqk36!@crc<UPT0rU?%c&07$Vl#>t~v}FU4bAj5d901;?9<L~W<HD|_G4jy5 zf{v$<%hvm0Aiv_HH#2ZJ&B4gQ=_AAMcjQ(rdRvGjf&OAj+mi11)z4!J$IM2LmMXu| zKk*!fOLi5KXpr*V#4LMI+KQ>u{qlFtznj=vaUQ)d$kEG_Y~pL;hU&wwUjd=9Ynu8X zFZ@E*Cd_==1j^+c@oz0$MySZx;mjMlJZHbL)s5D|r%-x#uln+KTl6$F+u-{YyHQpx z`zH@24W@|;h+3x4o5AvKSZbbl&JcX!yx1n!UDRRf2^POY=xl_}Xsh`&J9h*0M<51p z33N)!_C=9a5MhO`_N*9G=o2oTM~Rnq8IPb`_CHuU_qeFb^!<;DnOTuo`K!RO7z9yp z7t8~WjFdJG>JCQ%6RDIX)6GOkQDj)$T@S583?NIcGsGED@mPu`Sr!7WC?J-KV4Oik z29(px^m{+k_mA&u>#M=c=kq-G;kvKux|@HM8wPrq-t|t&TiCB(J$&Yg3G`vdIoW>K z{5)xjjXs?E7sC@~LdCED?Z{Sti*cKP_j`vw_$WNoVqCCSW-d4N9h<PCZ)$J(@SxSd zBMcsWiL%a7KZ=5ffphtq57#=IR(hxu%unK4Esu&8XP!D+?`Vt?AD^iXJzNNRwVQB6 zesm-Ft>2*6+$kU<os*?%_^*;qYPP}xh1X5IEppLsLjqHsT!j|Av4>70!piYkEslv& zdcbJ4VHi0lv$TFPCI>$RB$(WL-O9h7kY?l)$;ujr@RRa9`Y|7e7Dd#AioTkYvB|R@ zoDz?-SerCqSS~HY64hOCFXXy(%%cn6`OXuXs_p_R0Jj<Khu%{E$!Da@<GbG_O{W`s z-=+}iui3jJEB>hW?-GKKNFF*VL=p|6VL3edlpeuxUWLMM%~EOrwCU^K*Wv*Qd=^%x zdw1m9!iP+i?lJY|1`F<t4F?{W2Awr3$cHtQ4D~^iDy9rek{_H@*`TV_!50*`R1#JS z9FAseolcn>Uee${0MAY3GP;p}Z-rbg7(@NxQ#6@QA)+H;o+2t9XCa?WtH41HZVK8n z>Wu)+Sjl^PTkG};`JS;x-ITrUkIvLZ2L+AsG#NotOX6P)6{#Iz5ut7`BfE!(B&z3) z8_}o4VbsXWT+aVd=xg_2>?NS54ahHGv79PwhL9qF-Z%KUZGNMe9#$;3cp1#`a8NbI zT9n5_X(+r#1bB)QD-*&<yPd;Pyk1c%WsNI$n0ToTXh+^9Xb}Txah8Zj1e!Uhb~Wck zm@qu*Qb~n6jyHZR{dG7EU{$os74mcPZ;3XRlY7W2!iSTABAhHxMq@RE&+9f*AjqXD zH;K;2=%A=Fo3VLNVUTC@dD(d?0}=c%SP&or|M*QB0S!A6Q4?KB8)efAUw{(cQ9F-0 zI~XO6*OKofp@alR(Q3i<^ZF<bP%=j^YIL#_Af1&eU_G+3gRVHi=!bcDG%G^4bpiQ7 z@}PsTY7-*J%sOc|tUaEyLKqzw;5Uo1?P**(JWp`XG}S<d#DL&GR`!`n#9B8#C?Q$n z`h%u8>seE>Cx<K=BLso?^7?=um1ZWdi|i0nF8%|kLxt?gY=5BlkA7ZM|J2)1_i%Z2 z&865X#y3$ENThL0-Z;ct7rjJ%z~wy<Lno5Cq=p{`ODdxUpa<8y3I{cJy?}xV7#k-7 zZQ=`{rNU>h;;mpHiM2qYU=ZroibW7j7!W9BF@Wom)OCdOv!X9}B<M`Z-ifvlscM7- zBM>oK+91$A=PQ73_Cmyq?|3&@LDgfizpVczdmi*ZzIq6)?aiOlE4Tesp$OO|dX&;H zx;q{=Lu5qnpHb?zBL({~OAoa4wqR<<#_F(Bji5K8A{}aX^0WLx15zJI&hNnHT+=;W zuX)6Te@o-1bY=H~HaF7#-3!jV+p+FqA54f+#AYie-^npID4(_***EtBrBd8TrA&ZO z9FrNZF6ijG{8ifK@<rogy&=T;0Y?WpUu2FIb*I>G_JuB3m*?OBr7IuS?L6!?{@ix5 z?a+(K9)%ULB({rL?rVg;CM@h^xJr3PpR}L;r?19PX5M#AJDmKj-!mEXI?h;#xhCJq z&0bdGkvO}o=U(LwxEpKM>DQ&vk1;?IF_7BlYSs&iCu!*i9d2bVP9@wTuruk`ZNAYK zto9b7I`>33E3U*h6~3Set7Fwyi(iUMxjtr~7L$sEaGzMXM~98!7<yW}{6()PL=l>2 zc&OwR({(iXr*-=zk<@G1DwjUqx-&6qtAh`L?koRs=F{2SNF=X1C~L&7Jx!u;SHvxj z76aB%y`%$>+I$r+urm*k6l6+XD$$4mG@m~|R`f8b&<zB>%;cvIBn8z8%m}6Bm@m~4 z1nz1cAR-kf)$35I+lagZo^$st5e#!tB0l$;y-@fUKJ{lLz)7OLw8LbBc5hSGn4KPK z55vj*X%gXXPWe*p#dv5jW?7~f$;C)%S7+J~W*HL2PEYW`K7nLH2Nriq)Hl{Uw_1d* zGzmRC=WxlCs7IX^3Rug@!%dWhU>yNLn`EGPiiWyG&>Im|G#&VkbO{HNaLJT#72RHr zvGe0;&A>4@#4$ZEcJPyz`Mkrw5OS<V)iF{LI#kZtl8H6Q+kz{O4|e%#QBNvydE0f> z*i!ttSK9DK3Z8>9?O`DOQ+(4jaliUEyf(EruLP`NN}i?Mbo$t;;reA^g4|obd~$$K zYeo2rCyw|W^I0!T8QRJdJCb#A?X;igSsJkU7}>)$*s&%#|8|7W$B&ivQ)rdStcC|( zz2<2O?=I1fhycHH*8M8!gGNax)+Fn6J^;>?D}B}0=Bqo;<_$%pR`a5=wR6t5n{Su@ zE|CUWdTT*&^qRrewIBChvVW=%&z(fk5~p}*Fr7Y9Ron^2KqX7?yIVLF)&1R!@gVVo z?M4gY%c9n~bLC1|FAVbg59j>I=wzEPm8V%0KvLL%VkA7S|ErRW(MoW2T<RE9Ts%{f zix*E49UUsZTur;>T)i5dxl(HGRsQLJn_h}guC+-ifZOxr+J!Cenk_KC;(?g>aclm0 zOx+@8O61kfL!0%loavj%9}TY$Qr+vGSRu1Sq5UQ3g)F4E<q)812~R-bCaTH-X<yB` z^@>|mx&Oo$96=yIkTh7^a>fX%<r>NxB^Tc#gld)MmS`2kRv`4QxJ3MA>9s`4N<Ca| z*+ty~T9+Gpl$o95kvk>#R#{7@twBE1c8{DTDQ|7Pb;0D&r}$<j1)S-$2-u8SjNRW~ z@Z`^7mvLm>X56{R2i8wT%t2+dNIDOPba7#hSXzk1WlvIW*jUeTfZFFv<yI~{hu;cr zlsUj2!v@47R|x3@l737iZf>vfz_wbEZGciVeb<sbc)()t_I-!3@oJ+`g^H@}u66Fq zROS&>GZM-zUtunIhYBg|CdumD4I4We=qG6s9y0fd>QLT=^*6>AE#xQ-m?AQ<hB^cV zK&XwS+IcdX7FeV}bL1E!YYgP&B2hv+nyJ}}L)3in?QemK*g>Hce6j-P;bw>qrKy}c zG9B~3XH9~{7$6c_7<{#)`7H$%@Ju^KFMCZ9=eI&ZA$*8072^X*tODcrExJS*W#5HD zlki;<!L^102I;s}0-x+T5FKbrc5fUoJiV4Fj4GKD3LD_Z%C<lXDZ2eV%|?;Pf<KeW zHQtp|fv|d9RgQ(sw}SpI(+Mt&$mFtY3>$uz3^u4XQLt&A)+BQHb#XKy$U4jooQZMZ z)_VnQc;rgQ=nH9A6sSQJp28_udTG(53L$IoAUW{6@)5jhNZ}8$N&-}aP^01$^|UGw zJTPnmUUX189hFcORLIEamIg5=_$r9m)Y23@C)YbkLO@i!w=<&^O`-;abq!=ed4*fE zxowC+P?`^E$Z8ywD-K+%L6nt?Y^V|n5kC{7nG97-?=@HI{a&-2EYN1*k;s=^-U)?{ zECJDIXnl}PDum@HJTa91Jnxh`2H%wusTr;bSxlQlMt)k8si+oHO_j5?7!cE`z1Y;_ z28*ydiYO;!OgTCMJ90K}FdMnjF^YdWkX9kT(p8?p*c>Db@0hNouC52>31~wCd}vi; zcx<P29zvP=^aSZrm$-1t_pdK3FgZRB2kq%Mo6^5%UKTM;1M{e2MqRwa=Jol53D3IC z4r@6p2!b5fV;ak&6Y;@Cs#w6#Y+Ryy29jGVLVvNHSb9c$oRF}St3vV{tU$xmFbX?X zf&|OXU_+tCfTzFauy^O`0)54XR&;dqJdE6aEzeWQ6V`3VHx<oRVN;EskKFP`@KyVQ zH=jm$puRV@9J{t~4$r*p4MDxS<*Q?qu)?w?wG5o$QP#C`sg1y>um&wL|7-rkb>@Z* zs{HD4rn7;vL)^#5)IMa;7v}%Pj-R37?Pt)@3)}3x!@pEG)TIY3l^tE%^V%;(0kzF% z`lkOb`B0qskVT>Y$}Wx$tx*2Dj$!CW&vyCh7rZ9RUhtaBgqH%lE`L7zcggYZ#=auc z<`rH1QI=9?Sf@*Lt$8ahebWPvjr{k4=6`mK#!6MSIDN+h52cf8TDo;q?_zBVk#Wy5 zM@A&C5SgKiL-OnCQA^NIo)wc^wK?7LQ|PW0)_GtRb+%7@{@(_M&x$s({=f+lD;@j+ zrjy286=wv--x0tP8VYB=+DziCf6h>h<h0fjsd@_u7iaWk2_HZJD3s2Pl_jQFH=Dch zLc&CSyBhO%ocO?u{rtqG!F<gKpI8R&3C=~Ul>@dWS!y7ohoO~14qz0@W-4L+6Sb0G zsc}i+Y#iA9Ag9V2jQtp9_qY&jK^*CHuLzEosjtv<PL}m7BjVpB5Bho8BN&ajC(ZzK z9Y#3{*@|@4ULb^6krLii-?g0W03`RU!3CvPzEW-R3ge7@6CIrTffj#CaNw_9ti5N@ z%XY*b#Z7qAv@OkP6^#3!^A@4Z1F4?~5?C}nZCC={zdYGe$_GfwB>o7HCLc6-H8P#P zY+uHSqkr--#iW&Ijpu?NQaZgtsaMQj3h^J(;oJaFpSC*a%PEm=OO}~pm*|25h-8t= z{DUMxxIk1WGnWN_=Jmpq#YtWBTX-Cr3nfv>zir&Q@=vSYFK2zh<_c)o#_slxc0d=? zjMxtk-!?-XrpB>^T`+Xr%e}bv#@b%F9TlP&BX|~X?tXPr1uwKEb;J_B?OI-JQD}85 z4)6B*sbq&I#vtQYQ_6N8TeS*_BeEtwXX~xG<MvNIb5Zw5-B<ySGW;{coyl8Qp4_B6 z@oDa1&o(dVE8A*Ee8)q&T15rX_4C2QLtkzD+yKNb7|zGuoC+s-)pa!jk>HPPSM>%Z zL>`G&Du&OJkJGDFR5Shz6MSTpqUv++-wLcSC+838SL>9|R5#SmBy<l!zO<5Q`omS% zUp>B4uYU5GO5o}Mdsb(PL42j-(iItS?FsqDYYLCVsb^?1NOeWA0_d5~8`d+q9GPYI zJluypc9eKkj(sj;X8fq=?Y8HvgUfwqxPL^y=EOKLa?@|V_3v%bOPkNYBZ{DCyQf-n zsY%h$4K~7@*JjFCu88pl6XOCF1O0In4`)ypQ>Ox=aa>|vn`EUtVHZ$KYfvsGO~x9P zw`MrXDM(zfZ_o-V?gdzTxAwf5%x3+CVV|OYp(F(9jyW7Fv(+&KZNY1-l<4b)1`FpZ ziUe=8{JQ^F%gfQ@ua^U!0a4Qri5c3@X_Y6WJ*<~1bcR*WNCw%Wc`~kwqWThEkts+_ z#29Nx$1)ztMA#_+!9wAXj(|)T07=Mdgm8c^T_2GdSUyg;hEpgr)#n)<NdJ^xtJ`HX z@svFpo<$J6Q2h+cfo@?{P2GltH$Km~+-f0q!hbDBLW7d4J)mw7_b3&GD<V1(k0w@_ z?D)p(7|P8q@UvM%^Fp1%B>5Z<=YSxX6Y#i6nhROus8MP%F2wSCpnKbpxsH}Il(m*x z4k4`40DHAh8}(5fA4<v_PN~MnOfPIZyIQP%E;n&gL3D_jVYJc-l8NZcF^6-KgeEEa z1VHShw5d_HapRczvqVKtNs5IO1<qf42}<moQV1Rm5U^v4&{YIp9V3Wq^}r3-52pu; zH(|iDzIq&O!tzw$6k|u*=nDj^BiWGh1;_#0Je~3g=byy2KxTZ!G)*B#Ni9>HO{M@$ zSOYTx|NVqVN<g4WQRN{oNQT3}i9-WIE8ly44B9w(nPNc4PO1niOoiuph0CbN36J&? z<}#I{ZOJzbw%TzT8i@=A)y@c}a&_FfnPAZgJK?rKg2DK!NS^$(gJnHhuVX!}H}^Ih zDH!3lK!BJ}sS=t^>m)fba<+*#>0i-`3|z?s6CMSLU}aP4)k1>n$|gQ|#Ug2d$-{8v z@sX`txRELL(IK;bQ`oP+7;n_9Up1tULf)acM-~=s&fm5@qaOU`R6&nSyMS}lDB!N4 z_e1sSGpf*^woJadW48X!HEUBXiY5_bm8NN5ZPaPX@6uE^MYE5~+`9fj<7aIP+Z3;_ zSM=Sp6{Pau_TJC;Z?NBd31-(F-^V@o2*hy?-tWXEM=>2LSAlpk6oE|FynhZHC3tYW zl#<u@21U^+Tkba9n)&wr-b>ErEd;5sDa45bu~nvprMd;3NaD^p8oLkQDy#P~SG%9m zwWjZH?)iUn{V&-Y%CNtR3W9~o`zD%DH$QRV@U<z!JXB5*(^K-=e~AN%M0NJbX{vZg zUgE1BpM9~xCIu$C=6ueGZ>?q9%1!A`QV}k0$BfD|e+`=Eou<LacZ2})B$agT4aGE4 zvO#sYoRZ%0>$hQUubx=1{tx@lGMyxU(|jr&y6+&pL!`cfjcWZYJcsytxmho09&*V? z&I-U2-;HJFGWli!)Si;*vi5hy`MsflYCyxfS=_AL)XO3z-0pr=<!HnM&DeGHr8#By zr;2VHV-X1N=Y_66E^JMVrmu$V;^p?zoZQ~Al+}!d9zUmD5#7UdDXfsYQsw2WPn=L( z;@wRMivS`+U6>4^WFW2I*pl^3oQBUGLSesBQPvi;`T8gujj<+q1QEB~EH33%e?C5q z!hT2Q=u!0MGA%PoW52}5!A`*~CAQ>Pz$ZbKKvS6UW5PyLgbtO#X^)*av@(&!!#%uo zN?MdkaKB+;*})6Ww!)J<deo+HRQj^jroD?M_-h<y4VhbomyF+7Ko)CT4Hw*UEQgON zy4DV1QWQrM<QuPxPlLiDN){rrjLVZcIGx)J^h%UEXv-fgMxql(;P4~{Xp{ETnj<~0 z_6eUXKXg#$1`k7<=)Zi&<8EE4Rk53cX;s4E)(JGOg4v0!-mBB@TTbqSS8440#P==T zz7tMLS^CP+%u%y_9g99bF?UiGwjJe*Su%$e)Vamt0dl^1yD;DnEgd&px{79XS?~u^ z`?Nv#+%vo{oD}?S1dPk-Ty=Sh`-u^mWmN>#o{gdLh}&Ah_*qJ$onGxD|B^{(_`NTF zd)D;ciQ5tM(d;#9tjgLv@bB<B^IDQLo>zG(VRJFfjy3#(SW!dkJ&XK(>@Usc$k08_ zu!H293x`uI#**8XN1N^eC$(N5m#<!M>FZzAbf!krWuV@h%l5Vag`4%qKED0)!J=)S z*VM#0p4M9%+l2iqcaAf!w!^+I#@O{jr4(iz#xhg}!%>T=`Uut534mRAs8Z46EGS;W zSv5zuLq(e>s!3ezveq;961S1bKtx8cyhHF`>Z!EM!^KY6v<RZy5T8@`2_=}&etZ+V zNb!TBONIvm?Oo}U<k3reyN<&}7Ib9Gu?r<X8qOxoN9GJ0eJ=a%&UcI11YkJ{)^6M7 z6!T$-j1HmJnG@HnO5yIc)J}m%nC6a3_}e-?vzVP6DWbehf-fVgTN38Yx>WFBnry8t z-qbY(spiEoSDeK_K%WMTl0qj+=$zGpd+IunVlIZc^$+8C);aD#gMEp1sZHf5s<|%m zF_N}Lc9c^qXvM_;&ZI(dm~;gKYdJ38^eZ?{i5m?-{*}KRbp-rqPu%+bD_{dzo|8~# zWGvTvVS5`l-4c-@1ZmHZyXnt3&nGDo=DP|Z<b@o;P{C<|8EQx$Vs2a@=t(s$5~w{` zsMSC>0<~YR^@72Jq1E{2LdqvRKbY<-G8`13cCZN<!51=187^gJeWj~Rh-)AP?p^dM z!#Lh4Fb{GlfgCJPLg(_xAhSeD><D^d++^%}@diz<NYQDlF4^~1x2dUwcQp4YfN9zn zO)Qrh#3R}Erj`4-oIA$35f;0mp1`-l?8zilJ5Nl#xBGLi5q<LQ=-sT+L>D2#K)??Z zr+<iMGj2K3mU1JnitnsvKF#=J2xl$p8_DMy>s13p=M^ra$8&%(7`PP_JVx^6Lg<Zi zdPzwc3@*b}6(+E}_zn$olDOsQ+7jJNkHsGg=*Sam=8;%`p<MiTLHR;SDEK0KlZ-SF z!v2Zt0CsT^lA1Tr(;+)?YEfZJk_Xm1Kj!(j=CX&WGIh{J?8|`7QsM-60f`-Ns@fMY z9_j_n8{c3Z^zs`EnE#(S8t<to+Lo|$)dJPMAI6*ZIwzZj+vw9n62Dz6rhqn|!xv}p z&p&1L$@ErPW?9;hqE5JX!HFl)7DI<N#VDPGF((<~<`6iuk%J}%5l0A}U1g@zj2q1+ zsy^-<>&5_T9s$u>Efuy16H(ZYn}<a0Nqq)uMw|4hY8(iRr#U<#xhhHg(26jIwiPSg zq9|y#WaV_ulK60YY(Hh1ruMLPzqsaRS#y{0!_uceQ71O{dA|na#-*4d#)y_j)EUO= zfpp`=qL+1R?x~CkJ?*JGAa9>)flJYNq%+;cc<9zHx#Ne2I}_p`<6_)BqY$g)ExC6S zdSJa~whl3WK9Jm8Wqz^tN)ko*@cLDL@u77&h*D!(Ut5+nq_rq^uUa0h;XlhKtawj- z{Fj3cN36ap=)%v<aQs0rvE)hkNAoDl`(~WK<@R)a2wF}SC<toA>dq}5$^UgW-!%pW z|Fzp3x$@|-Er$wz{Ez8>E6=MZUK**|{+q>~vDy2UQQ>8Kn$0G=IPh@aAHM$1GXs2t z0xdtiIy|(3)e5Fl$4<VQRBQ2e>}$5P4|E=!oq3`9o_d^RapPaS*?#xmczwJsu(>gO z_fzkGDu%yXMbvos4-WrBFa0g$4ScqBj}|1OWxBfe&!>NJOuALASBwmWdZiECJ|-v% zqHaGF(fiDar`;uV4TY3{<=6()uQ)PABk-~iL8)z(lpcKW)Pn%z2Fo_KdS^DJT*#C6 zd(NnVsW_0uM{b`z7VxR!nr^=_a5~st`a5qQU2AR#?K71YNrz7a(qzU8*MP3M9P;I$ zm`PXYcSHtAxzR#KSwuC<u}L#rTJ$JXtGNpj<K?}bLc!}fTTiiQ%<@~NTCjCuMy+Ae zAE3x|kal&!PEnzUHd@RR38k~C^krEG?UVx@De`kz$H6WJ!gCt?3UxmAprmSu$1$Vc zs1xO~c_ce=CZu&reib#gv1=jZE1h3&g@c=d0I5$K6#<n@*v#DVq8Z`Rc|mI8G7zBI zKgOWzVlI!zNy6}DbDicANNT0CPK4tSC+RRk6x44lPPx9~2O(5BVCd=^4=H*fPK6_t z&+&2V1Ih=Qp*|z0$T}zpgDF@gy6-Vn(m;&0-5&X}3eQi3aTQGYtX#%Jc7CHZV?BIV z5oN}^Xl)PuLCaRjOSN7pwO0=xpLhe*g$&kEcRKXo*d+m<ien_r4DjdkMJpFGVPWm> zA&-r2GO)l>0So5(v!E~CL5#jx#TdML42wZ^UaP*S%Kn}iYCxP};L(9x8{SxeQvM~A zSj)-cx|HkV!Z!R?;t4;JS=f#l6RH}S?8L<?Ze#q^AW=JKv<1q$irOK5Ud!!cBQK>o z^!+4ds(H9*N}d>E7d6%CmBwZ~{Wk2(xWbQT8g$ExofEr*k-pX3co@*lrp>{kS!qA$ zN08vg;w=K|m$~xE`w?$-E$u4E2#$U+!<VPZz}#}KBD`!jp~CkxKZ*Q)>S{6)@sNpY zoiiLhPmmg0&hNtN*-EG7SHCTP3U`!~Ufk!Rx5f6z(A9}842ah%!J(lP#FFT>XVYc9 z)Db8IhxzouoF7n-j?v&kcvT9jL5MZow;q}jFA5a;zGCq+kI>c%!75oo5Ca)r5V(r~ zhah3CoSHT6f*tU#$I`Ba=^w3^8Aaxf4K%Mq|DvEmIAFjhW>uhjR%%sII}Iz-e0iBC zq8x5CP#d@Gmaj~g3jsdCnCOa*T?A)-fx3?#yQ>lIXM`aZ!0!zi`x333v=xe94yV%n zJ5o%ku*IcSFA_7wC`OR;F$<A6CSOUVaIns_<G>Kek2+0b#dJVY6JWZSjSm?XQVF=Z zmZ$h%v#ci7iWjJzM|xi-*fr-xZSxIZpN}c8jEAQ72-YG)ZGAkzdNn-)Q_B8p2j=mD zzTqDXas&dFM_%hvhCKYR#F;sOg^09gI=PsH=$QkSfHSo;V=+po0Hq=mM}aYQq7`Ob z14uFbOA-HZJVm9GB0tL{E`$;hGXx>$T8&Stk=l-|zedq;NtqF_svHP`JUf#9f_EH( zFknVa#z->72V_#_Lo{uS352~|5ge;z!5WkEHbgLit>-F$>~Hoe@t}oX%$sC(K{j;w zN$4$8hIYu<hey-VpM!%24`$?S_wmOim)Dyd?}u+yX=@ggJq)GpF(y2M<6^Ca`plKh zz)QZ)ELxOjy%esJr^^rWv04uW?HT|$F)Z}6Q%N(`G_sDmz0Sg-m{;$>RJoejZ#I)t znf0{Au7MkTh}uak@$*v!#KriHa==wt$d7Q-W*0?=6|t<or*hzG)%r#WLkf;O`)*)A z53dir1M6e}yrf}?aM3!k!9IGY5aBG6`frO?oE#h-hb6*OwYfk5O%aaW6NixRM1*%3 zRpb8NBScDK-&R5dKGs8%0?e&<bt_|jSkrklXV5m_mRrIt8_n4x4O@Qf>)0~1rM$Ib z&Hg6Eq|o)-r77~>AxhP&N2J2cZu~RF_6G>0jr7~WSHG`#Y?E^7w*_hnxR7tR?J_$m zxmd^E=q`_!-XA%A>u)maqSyMk^ar;u>;Jl2fpAI0)r9aB?=(*dY^y389Ml!xyz?;S z+l<ySz0P}Ru1Oy;Vi;(kra6#)Zd}ykD$BdlOO|8jHIp<YyKq~b__%6dd;2hlH1_tk zujVpX6W(prv$oZHcUE+rgv!DB?Dl-v*#64e%Uc6{HvFF``+w68gC9B;NVi>S&~}q6 z!tmJB(*%U+HoPi!AG+pRrlwj#mG-Z!&WeEfGSp66c`DW+@S*g4a?9Uc|B+h3^gVy& zfob>2a|e<={*zRY<aG?QmAe3l`=7i5LYh7{weC##bW6C+tDFVb3k(wTvc?yR0(7~y zK#b8u!9L-&7Um-vf{W-zi?G9GS_{{M<Se*|M5)C%eRm^qD{M|}$;xKkQ_XI`^oHv` zQ%E!Gu=J6|#KpWismI9FI%g|m6=q#X>&7O#!x)rih`>VQ+2(IK=_M(V#n5xWJ)l>W zsNO(yY3wTJ%c4UNzil)`Q0PPdH}tn%#MCs8cdJ^SHQGxLE#66~?3t42R9L3P+dsj$ zPr}^N-#TC!Ucbb8<zB83qR);YQ1`tq)9!-?reQ4H2>8Y`{wC&SC1fCme#U)sV4Mb5 zoTZnrYUGmns7(C-iJXq$!!CPlL|CRW-w~g!F0W!qSvkYNdjWL;{vT}=CA7jEN$=2~ zXL-(jvYl5%bIu^fZA&U&O%)FSl~&vhLI0nLiw<_jlpwzAeqp%8gNX94fOd&PQbbd3 z4$We<mt)>XpH2y1rfLgRXuo)wA1tMFf0A~3^*BOEj%ex$zf`8hMWetrvXSZ&KG7_q zL8>g47%r`xiT{Yz=#*(yqd7iy>PA@dM~*g*z2s1z_Xo2HOUnHS5J~2-=bOrgo)=OI zL{0ze4Nm^`?dc?uZ_;<Q-ukfl%A8MXNMn|eH!bm{$Gs+m5<55=pWl0<Pqs;%2tmt$ z<ahROb7+3T6LwqM$*t|2a=EE=SLjHA9%#=TQ#94w!UKh{jyqm^0DJ)w;;S4XNL^M- zC_($G)O86aaR}@zT|&=JNeHYqkq57|G>)S!gTH7Ow}Ycm=Vt@!jv~LP#Y(@`1#SLW z^ph~w!~m7%O3WKkn)9wYXnml4DMkhYR$IrM#DcGasUJi@1INU~6`B-L90aGw^*g~h zH{2zwkwy*O(+yoLaDp?-!_HSpAuS*U$h>YN-1SP?NldutGKr^%Vc8%1XQ&0?sAz~X zVc?(!>NSBc1SJT@O{rwpVAoxs-O3`eRW4|Y=)k^3z3+JyOYT;n2<#i2Jo(>Ride?G zaXMVBpr=hF;6W#2A&;(LmmonVWLcim+2UcDHGyK3p{qAUke08TML{AA*6?=(N@JB@ z<+LKxo@QZH;!lTzEB|^fwaX}d#3RMiLuwo8fH6lr@IZO>BdC)r%F732*<MqV#ogeE z9$_ZW-?vNJX9-u~`&uLu(o-xC1O!D{3V_|!k;;XD)fLCZmuB1|H@}O&RUO^kF$5OB zOU&WkOT|kN3!YEzkwNb-bY^Tp%`M+jjw~d2FJ)^Sz$Cx(K<o<kAN3($r4DJ&lX%CG zp?hw$ii!jm^a~6-CJ~7&bE#l)d7&KsTHGM`MqD`@8jNwtf+j^*iTql?Ncfh3=IoQq zh0;KFFA))K>q?XZJW5dlYFJ3ZSLODkR>fgumo*+#BTH+GR*$*_+<!_$MgV1G^3|Mb zPK4E4CkCSD?I4JIMsz5GYv%`<I=Q{*LHs%ArQ*A!+X#fR{m}a-_yEu-DxdQ{^0>uL zdH;>FyRb;Di+bbAo#J;KL6t@AHnKh<ay?mg_uDQ_5WB#Gn3?icBJ2luS>Ev!CEB&j zfc^jePm8g;CgG(Dn~Xrh*^`<JcOu_U8vgB;d9hK+MeGi9U%SAdQZD?5Mv-YBtGxXB zkx89sNikmysjk_OVbt&yp|>yB4Kt&MW%i`zWXr|YzE^s3`<!*fbtOtTV7D*dec=6u zrDqjsGUZm(ZzcEQq(gS}bN`Ase+w@+>YMQLeU2mP|6K9lZ_;f|CLgI`tt=t(vsr6W z4_DZ~>Pc1OSyeJ8)%;;`{?)GMv-c%b)?JMRO*j26iOy8>j-&lXuYT|G@(Q3m=PP$Q zX@>mmIkKe^dMUNToP1VY5ZyT-LWnu$tdrtuK3?J?@i>gy+*`3&=SNOc;k<cH7QLwe z<~aZQ`gRh`WU2i@SG7kLe-k&2(f2Rz&e=(#%5tA*;YuyJnSB2+P-TG9XR+ZYKFD>! zGV(AW5-jEMEp!<@p~w~c8P5T(2%f^AakzAY*4k(;5SL*+aJAAZyv?Jcw==4f3SFm* zi=mo$gI!nN%acA5v79;<PjHpEWG?$V(}p7@AoIu~_?B@gRuK;1m`9?pw$tX4K>Ye8 z3qiRW7Ix}XPAHU?Oo@DX(&iCFQfZYt$5JznonwHil+u|t=|k?A;XD>mjSMr*BcN** z<Kb4u1e$IE4}_z=634ss5HUJTDFpHPu~S1Jc7lLATCq3|l|FXeU3sNUP&XWAJq{Xs zSzy;fi^9k9tkV5QEad7aWe#}*)V=oXqlq`5hU5z$Rw4No(e`5J9<7&7eGXq%wMXvO z=OSO;blAlX%89RLxOC-cx@p0h)$VmUKCuFj8xwb&>#uz=N=EAeTr-fS9N_I`fA3*% z^4RA-nwx*EAV~nvDDrB=>XZnFr4G;IztvOUv#YFSz73G4*AFnFd^_b1Qj?mJgyroQ z{RaPOZ@3+Sf&I;)*q^NtSD)U|`0`ZNm1jJ%Xb5#tt8F&l{BlF+(B^V!g+r{DATcr2 z<c@acZCR=4YEG^?mhmn!Cc(*A-u1#?>?rUB4WxO$xW0^4Y1Ezw1sH$B=SxNs=Gljh z>{LoHDjIHJ$vq-m0ucF?@Xu7*I5r_^gYM(L7nNOxgGA~C{$^|@LzkKQ1O~DgtoC=w z1}bLlTr!0|{EcQ#3!7#68r0rXG=lngESA4B(f<ym*wQW)Hg2Zfv?IgrM?n9E+r>#W zT;1<F-<g65kBk0%VKQKTjYmz9QG)}2bJln_UVfN!=5lTuPj4^VRxvtO3I70$WCRgX zjpwATC`_Gu09R2HlbN=)XcgvyMK3Yl+zgH;9!VTPr8y=af(LXm5u~pH^%(|Y7nF;S zp(V2T+054M9PGNxW+x&47SPG7&HAONh6Nx8XCYQ#vx^_IF)B`2^4O^cTv^~G7P4+O z52xb!oQlegfun}yuR^cOjzA$mRgKGVq$R^x=&L|SZGp&9oKnJ1`+osR6~f_yuNWYw zS0`1oorGUJPWUPSdL=wcrrw7N%DbB!gaol1aSHrW#*1-j)e6zc??<3VA3PBIrL`?X z{*t*8DG%m%(7E9~|FNF1;Bm0=?*RhI>vUqT3}1R?r@T~Nne}R%SivER6MdS}T5gJ- z6xp;OQ1NI$L?%_Je?<VqmJ4W+O8hua6)~{JtWcOb3q`se6RPcckUc*U7^)eHKPyt} zqptb<sW^L(!05UzWIbD?xe1%!)p4i;?ka@tyD^)1XOtI}&oK+xH&vAH0h<bW=f{|7 z*fCD0LVT3`WOFT=iQ&?dpL(n2malYU_qFIOIbk6VL0T`pZQ0VC2VkUA^6pDfz!LS` z94%f(^+eNawFx(!Gqw`_c(hJi?~SV~xNe$jKe6)^8eK{eE9W`H;lpjaE>G^Q20)!O zlwQ5{Ze7!)`wMsXLNqZIO}g)WQ1}*#B`NKBF@GZcC`YQs3rKoHh9&C2R~tvTBR#I? za@|A!Qxor0bAh*ks&}W_`3JXYbT`O06V@fH9ZJs=O<kU-L+pNaUHasIt89lpV{bT# zR_WyZSI^fq|MUuZB;>WIMtmIy1M^gr07w60@+o50c3SM-{3>X3_g5L2t>#_AgzW0~ zy7KS0f4V!?>V5=uvrl$JI*GA|4MiHLv+<h(R6F*D^T$Qu$h|rD(06!Q5gWiZvz$!7 zE_&tGG0C?SoAWEy{LOjz$2B>JhcuC?SoZw4VndsHr1aiF&&>Ds-Aq=BQRvMZ&!j6d zPgUtow=E9+->(7Cygx0!|32hBL5TOSzW)VwlUDL>>mmCq@kh$DkE+%>m6=W*wnSts z|FX#Ocgf06ypE?&U9u8jZu!^KCH_ibFXixq*MV$pF0WDy6kJxtGspyb(F-3{RU7pm z6{aya>)=0h{{Es-km*pOS&mbJja1@R)v3fD#6lEr5T?H|Lsk{rH~L7My9cs=6}mOn zQ>MM_qofBssh)N9R{;qu?U!8X<Ue$vO>ivWhxrF=1kZ4pc6rkh%xWm3^pq_{Xf2Wl zdCg;AY0+h>e^s)3i7f;pL*Rbr3!jpTTt=;DJVu*^t>5PBqwCZGD)AAsMs=nQw&cg9 zR5(eb!(+*<z&6ivrm>?^I=M*{6#V$a@}EjccZ*Z5kFHVq3-4DJl28q?7DGTl2eQR^ zJ47mV69a?;*_08JKC?b1H`i7B<~wE|;ZmiK^-gX8Y)KXxOE*_BCH7y=dR^BeV>)yP z)b2UiEq9p|KZ#lRiqmMW6VoUC(yn=3yik6RGC;LB)}Fl=go7?Gov))d{rgo1&5`(B zj>%z;DBj3%=CqWsoq29zvXDy+Aw~-_8aFSJ=e(!Ep*guprPAjJ!O@6|Ll#N}bqF3h z+rUi!B8S~bcQPIt_tVlAU6;_qCWOb`vV5WYPW@YXM*AhB=EO*8-@L9b+ulDzi8)KC zhkUzYAgS{R&K18l<Leuy3U4woq@UcV39=pZ1|!CRIAPTe5bQG-if85XyQ++G3cE@% z6@m~+7=x2jZt4ScYsO2d#qhKy`Cbrej&>1Xp@3UwR|?N+10Xb_>hlG)VreK@NQVFC zsVX{C21)d)i9}kI-Jv?gT@6beiB-W(=F7U^<fbe_T&up4E~44o`aY5p(N47HvKPZf zCwRG%AhJkpJJZ7$@e`Aw-A#iqiW$ys-fQO}P&GI}6$;j+EN4W*$r2DC^DVf1nqe%Q z#1u;|>T|y_E$03wVv$STM3PyckUznY1-OJ?BrKPC@zY`ABuY_glO_Rd50cF{7BKJT zdrnXJxtG~jqHR-tP>o6~Bi-L2GBYEC=Bi?W;cRTqdajpOi-}H<UTNyn6$`&HmPMm* zVMRtQxCpZ}YFoxuLU_RJK*BmNG>Kc={H1sE^z&UW=tS}Gt+VjP%;9T@QJ?Q2g2r{= zMV7J+@{8<012rhJ-{FdnfG82Hnv9JAt;sB?pn~7i%;8>Sdyx9<hTKX3qR6lqfjWLf z#evc@j-O{SVjt-B9N#k}5C}mml)3;1TYQZi7a$Y#C|Ht+!5jPs(Rt-ES4P@YzQ{({ z3h~G2u3%@DVH8%~FE)?h3?u(uSnTuYVrc3uCk@PvOQ0v|d@hQ2qEBB$ixlQ$?VYPB z6m<*X&M^oW?=sr<Nm^F~uQ*L|F)DMhCfb)aoTW-wHjEkvQqTmGy(Jmn+S$oh^F>iu zkX)tn()&G&UrD35b4wB4Q`{y*PKly&N!}T>^SZb8y7$c6>%FD5Ghd49<Et^{qWNtz zt!OUSY224K?{DT8(1P6Y?VB~OTK3fwsQc#Dje|KBg%nBip_OYY{rA;3M}J&r`0eFh zybqgonbOPCsnXddWQqIkv$-J^8%Dm>=nF5NkU|VT`%~3*?b^Ds`yWDHenjDLJ9xZ& zZ4pf`rPXSigsBnkM2pS>2wL~2hBgkw<{3Ub^k2P8nXdV&*a+9>YWuLeY*r6t*2b1& z%SKl7UK&?6-LzB5zx!SCv?jZD@}F<rZp654xblnOuh47L=Kkb&rc^hpAvb+Z+r|o~ zsBt~fPsY;o1?YD42;SiAV(IaUww)F5xMFcOruB}bjtGx!Y&fyF6H;u3%rImtG)KUG zUPbolpVq4zEXFTJ9R+CEginZc;A6<b7o*T|V)b_k#<}p#4|)Gj06<}!70Su2%j?#C z6*Squ0>%(88HnK2+Yyq`Pl(_-mfw~(AIrC4K`n2GRmy1PBZkXH1{O^TiG6(0Qa^z* z_MoWNE2`Jaq~~eB`{O@TworPtDOV5dy<qzxe3C18$S6$x$&UitozosSx@U&Jc&@42 zJVhlRgzLj;OaFokRsWBd{NKH?$d>UuuvgZ>e~RgYP;C3XwX~(6Y`AjO&M_y(35k<F zv-P^4rZ}gnkb6)|D}8;%&zj;QDq`W9`^aE=`Q=wAzoGgtVum!boPqNpZ^qfcDp33) zFeS(qjg%uAEkB4kE$N%gk?;Dmum=uMwnnV)%+W!krc%O*I0YTvHDE&d*-rT$lfhHd zBbHm{G*b3*aK%+s3hJHsUDQTQAb~x&GtuHtJ1kz~PdI1#6Rj-A_CFD=XSS^ny3$W! zj1EVmb|9wO{9>Z52Vt&0&_P~GSR(Lwq0!Lg(3tzo886F$MD%|s>&y-p<_`kqypg8) z-o@ByDEFBwZ3|Q+u@r7|T|#7V<#Q3uxdhgphCg?{<ozGiTkPDLSbI*mrVvDEJY9-L z9h^?{7m&~s$v}0C%dcv!mkdwRmw8cf?^t(|h5yOUiz5DA@r3L2k&DJzb}NyHBb8sQ z_Bi~#o6HcMtMe-1yI#v3jWIc(T+89(cDNkb$GR;YKk}WSzb03NU>+r-B7bS);o}Y~ zN`%2oX8pC@&KWz$k$Ps*r(}lKE20&{?eBZp8+zY9O+e-V=3Wde9sHIGpDD-i6*!be zPCgE1GkDrUK(?l+caB1_;&ckr2PvRojA&w;V_P?iwc{uA9vyh7xhW_bjg_4-zwi|V zzhuy1%Qqey#c&8Wy`C9g*Oc8XHxI8Iv!7*wFnj@9m_W-3-@e*7S>s|_tIg#B>(p&3 zxwu+7_1z$<`+3bptX?3Hu{nU<e<D)GX-K&F={WwPsDL6zcc97WyQ#S+2jRzzO6(dc zCC+;I5}~oY_hwZGs(zj7)Bt`Z^j_>{Max^u9-p*PpU#(`b1V=aw`_!YIQw3yv5?iM z6_g9iy+$ZTAge*ZFJ_pUh*bgUX&2=>E@6T|?7}T&WD7QCS^dY}$I@LIZ01@Fk2aYb zg1>j>frF9@GB{-0YRh~oPqBS<k$UKF%i!0k`O&Jy2@$*;H<!^WS+?!qSm}j6IPv!o zW&rQuSH@f$ukB1Hp?5h~ONj$fMWWqK3(o=$5~Z5KqjC{TWH3izvg)yvrcB_Q(MNw4 z=FftLE0{2&$D68oYhhwe$okVm1egO{P*M^+$8ZTU8zx|ihMSs(n|r8}#eX8fV~ERT zzPYry*vK0LvV7t}AY0{U6P?fu4Sx<b6Ke;dZS+e9#Q0&n+z{;xHG(&krnv((oHq5I zawP?d!5qUf1&#4qG7aP?jj$cT)*Q8Ih65(kywbA3tE_OZnooU7Hm$YXq#m|9`Ano) ze2vK2N%vFco@t6zWV8xNG*bu_xv`AU1msBhX^NHhUhfy`Mh5(l)uMy8SS++~*GKWB z_mKPV<O~Yt3??@xS%KVDHeBI)nPGS_52UzFqRq6|l<5p$EP1=G9-gXUx){JZp9?yq zk)Dy#3t7jx4U2WWS4CB!EbE0$FGvRu;XB1}IP8|s(L)2A*K<8Dlsi8?T0j9%zw*%u z=z0P1x)8&j)L6%zGb25#V>fw@EM@$a84PgcUK;++Jog+*<H{EDvmQQGc+8>Z%Gr;m zP)P{QWu#Ng^C#M^OzGKoBF?B!T{U(W?Dkm}Ca*3Fz4nQ|>66aJuI9tTY5LVqpcc=n z8c7fFi@2v;6SFSQZ|fv7j+2#)<vRaSPG8sjX+zzmKfT(r$z6ddW3r#NUU4rtLfop5 z(9*OTFp$cUza~C#iw|CpvisUMr%PT5RdX=WdUocf+~U?07n;hozQ=;x*Gm_LHu%WJ zl=cZR$@g}WEwL<OVTZ-hu)=@|&4Yf$-jgc%W_C!@_c*BEEckP`kjKM4O6CcxSu;xu z++T~cMN8rAozW~1(A8G450D`3X7_EpKp)~cBJ#4P!Zw%6v!|DJ2tDLBYBunvV`pt& zHO<m)^4R&Rf{K6XjCxrTbgCzsp1RK<dC>!G{pS1lGezrbMZ5i&5w-|^+QM6P@P*c- z{`T?jlA0#$P}v*9L*7=h-`l=%@UP9RSzOOwY}cOt_qn~T^Ulc{t$>~ASf(KS9+%<d zQCRt-sq#Q^ZN~&)DFVk>AN(b+PnKox>7vQgChZf>KTM_sRD^LZOEKVA-GlyzSN@9K z*ZUXxIE^A|UJ|QWpuAiWw{UZ9ZIw3h_@*KOOR(W42E*l-XL5lJgw#6>SNwZu;149g zM)+gD7o|gmi{&|Cprsa34gfb?@<wM`;5~tVaP|4wl%91~{k$$|Bb<YgN^KrT4kjh8 z$&{MDz$o1Q0MczVaRkPEgBbNy`$`%9P(>=84L);h-IG08`Q?}m6|UjBACp4LdVoiB z>%{9m@K@r}Dw(nPe8{d=y8P*UEk6(>CVuQG@x*8#?gkfCBySw3a*C&2YV%i;T`J|3 zD<|-rx;m$8l5&b%G@00C<(Su{l^;HC+vk!WWVp2S;CKLSfgAw6LfQLEtDVaKhAgeR zIe!c{OXWb-x?~E9iW`t;(vI0^x*f&zQ~)+HXQqM^5kZqZpcaaX;<Us-?5ttXk$3p4 zgHwrV2lUV(xY4U_2kCr@e9#~ge&RyEQC#>Ja@#|n{!%T=@FTp(L%2>r({nw+ai->% zrv_e{o4nNcFsJ^zkaGPx{cBkAkX#5_zQ!x?SfDc(pLbo;F%qWeX^5HQLAVl#(DLqQ z6b;o*pLU)isKy5zx1UW*LgMmec1f<h!F7OGf(t}x>YLNok+AEc)r%+6Y$<rc(Kzf_ z<&?n54>$xUMfmLJX~0p2V{|FhJSyv)P&7@ghhD<2lB5(8aNWim_Cy|_N^J{eOTXwS z)o*Rr#X0h)4(vHK8WufofFL1AG2I51WjKZMakhfI!CPY5w4IR3`<8ba1Lt5DE2tlW zpN{$pLoXf6xNTU;nCu9?1DWcEwI*Os10^(~GKRVBEZu@mLQdrgG#A+=Lb{{Z%49oz zVAHMvN|4ehfosqsp9cv!#zErox&o03vsy^zTx|9YuO|f4g%AtFCzfS$wg}v!H1;pI z+2qeubhwn7<hsq)_hkn2YA)6-uOx&A%o?k_^qbB(_%MnjiyES-Ybz8zcVp$zz}#RW zf*q5ehEDjF7v+PZN6byxbj+G|b4=EAM%5`iq^ushqG6^I5cLNVmwu8(x*P<kbS<J7 z29lYJY;<wr;;3B2NFh@x)|_V6^#Rq(6T+PV)R4tq^QFnc|5AO|zY-xbNVkTEmPrro zo~3)XrLchv=ZtnfP_(-@*b@>vR-y(K2Yy$I$^iL?Kfza<Ydtae-cGDgYco$8gy#&9 zuCF8l|8)xRYHZh|Q029bzM#X44y$u5W4xiLpfNCjU}^<|xRTPTZ|>sF=sJ(nSAjW0 zk8AnuvaMWIsqvbQ{Mddd#(Uyp@4V(^MGt3RF;z_6RjvE(jTPqqJ}H{LV8yZk-GXPG zIYhuMpad|pAscT`-BNX7;oOYFw-tAb<UYTRpIS<~SbwW<a6!|VhGXZP%qIPsgKI~I z+-VlwFO>ZJ<<8>Ellv|Kg$h+t<d(|kg5S2!&b$`!$-Nk8O!(!;q#vD<E=$1;C(|Lw z@;|a;)cfzbE*N|Cgzwi!Z69R1&g=hGeAZ81bv#izB71V(=QmiqFmo$r*go*&s?F@0 z@3t=45>_9bUvO^PkAwS~$#h{MYwH!K*Mi}mI`+x3Fd}XWLh63z-dDPI>fV3h<Cv3b zA*5|(#TRk$Cvmwt^Q4~$OF4C#dyEIK{wHc0O+qH?CAC?7_X@M)WQ9d3-@USO+9eR~ zWd9pWF2}5~?+yN4vb(*{O^8A|5AB%zuY^C{{$$PSt(vo`@M!*?=RJSM{3T0Ibq~t4 z8a6xf%Xspb?`jBo?5k$Vur9W5(=N-K4J4+jK6w@6VV^a9O+EIZ+rGLrV5ck_(XI3t z*!jYWUj%~GI7|%NI#TJLl{9SYzRh$+24l9jKJ9Z$yneOxf{x8bVZvG3Gw<s8zyG$z zebCYAmce_M^qQgDjkDDxrtQtK&697(3~w|7kYEn`=wh9iKwyewR6N<CxOr>gZ#}z9 zH|;wT)i*V1!8yR(-U2ZB(}(}v7!WySZOe1=(r)?sriIHc-Ofm{t}1W+Z?C!hScEzJ zQy&MFecEX<AO#6cP&rfoK36Q1vuNW8GH$NE<IfK7g7`vY!8ax$@f@`Uf94?!^+*4B zZ$Ct~?1D5V_S7rd9GHN^S+D)Ug_rZ`X#y|gTAmw!ylPw5_DDtK*l~<uMM+5P=@OLm z@0IqL`E|d*=EtrM{vV5$`O^?K3+Fd{3J9a+4iXOr-qzt$cH(PdnIdjxvO39W<+NcA zQC*tEP`*r-?hGN7_n!D>_CA+UMwplWVp<7%FV1Jq4F2<d%)S$kE3JtelSE>N_u)&M z4^jXhvVHf)#V^M0E?-_CXe?enALIwNd~GUoKlH<obLhmEGjk2Y<w&X4rYE`>JF@4y zE^=MkuEVMENm_6yfe~8&P}JhIGn0oaXNt7Crv(=iY&+VQe7{QNlH60L^Z(#Am4o7R zT3J`uq6T`q<p0;bsva9%<w$8ot)}ihTD>zzHCyGvhYplGxT<wwMEOg+fM@sT>Vdz+ zt!WvWfqL~W?;lcSTS(C$JxTThO&kJ`t0gl+8S7L(i4G_`f7P$kQA@1#z$Etl(oN>s z+{TSit|zd=8Mhh&YlCP>^V1UV$HOpREe0X_gm8qZh`p(*57;vQqa)k(X8I?#L|%PV zhW`++LYj%F0IAn-nQ3<bO%R`%-Qq;mbD~Y-OX7ZFwXSg)Jzpk#Rjoke@-B>3pV$mY z&o_!~?rAE>i~Kw;5w9I6UE)orw45jGq_FTo@8HLR;rEoN9@jX>d|D#GHef|7-lb2{ zLq;py_vv2ftwxNgQ}@}&P6d+M!}YQnmEfu(qziH}k}MY-igW+hQ~07H5D94NE@&O( zuRpNV;zCA(o@P;M2?C=P8g&zf2t4Y0hL*ULa!lr!7I-B|`CFFVLX<&*J7!&0x5ETn z7-4yTXcK>1oFVES4yw47!c={GYSphW#RPfg08Rv}sSw4<J5tE@!^rpP$J&P)gXiL& zy~q|7fZdTez0&G!Dy$D03WTrn>i$vCf>r+I3N|-ddMvlmq^<|O;rWxdam|asb%LQl zpBMm@+uQx&Kl(S9(K|x<418={gchg9rBjs^3)q)=Eid4PG*c>sV02FaF45>GIb!x% zWA$LOOU0#geU?u2K)NDx`N0(NRvYSc;OEPUd%p3;ILd?+A8`J@DqRlZ7VdE8=^;fN zKigPCWyucqT<wZ<sbP@~n2}Bee53Hl(e8EDiCS2fh!)p97ZGjkbjFKRi$TUjs8S?l ze92xynvGjDR9@V3T@&eea|tk7c;uONx9_0YSPE-E7igk3DV?84jVz?Ga{P`s$zcvl zf=09GDBW!dKCju(96Sor4(e}>%-OcD_TApuSTMBgJUkDbrX{4tBEL0NzpW{0TRWd* zDE;xjcFT;P{7E@3v%P|P^V^c5m`3lNuFv*>wP@!JFi}5|8K3{K|J8w2L0{r<fq{^t z#k_g)nsFx#1BP{+AbQNG4bou+YrRo<M7}{HPtWjtTYj<o`&YfiS}#Vd9yzB6x2)eF zGaz#PO1b8ra?y66^{ByP2lsmc_UOayzu!D*&<l4+)p}8zt+uoVC13j7PHCTVNoqc= zJ-?uYK*;N~-d0ZmWmb!Figz^jn!9G)`iq(#H%7|8-c*@J<yYGq&XVAs`aYDwKcEyT zqAKd4YS)Vy&X?U`JAORZ{%zxnf8)B9J7)$r4Q{Xj74zyZnz>eoV{#)~=bn?DF~Zql ztZV5p2@EN|cES|JVbj~^k(GxH#qQtSw1EAd3U{x8gQRI(QyD1wmU!>B(b3odr?4X; zdE>p`TK4vtEEDy&%pak;-Q2;}XyC#0p0ZzfoXjvpY-45DG0%X<|Hd6Z2Z!t7sF2sM zEjCV3#IAiB1|VK2FYSz9aet_PM+qD|Y*s5)_tjtcIeLK945oFY$Who~Ks<+|!n$0Y zZ}z7u3Ndw7_R=oP!Ncl2wf$qEyeFYK9$`qqc)4`^iGJmejr(8vWKDSf(UHAe;{O`H z2VDE~yM1pQ+)=nzH<uA<7se&#_yzVxrPFrj9}Qo8Yk5VtVA(m@`Py}yJNxwN0NV#I z?^MWP?1{)jsVF2-JWw%EVx^RO=KbF#FNJQ~_w)RR&MN+VyXJ^*S?pSA3R3DT0`b6* zjzF64KGN~Y2OIQLj<elHHu;ZUS?zvt=iomdYk!yg=pA`?;?PrRU+qYG|B)%{_*{4e zeHDCm_OISm_L`Bu9QN)w_fh-|$^&LS>HQ&>8xv2)MTd8MBNj$ixW)6gZ!6b~+nHaz z7JVb*NdSWRGd`~R&(A;E&Z7EaS7qiYbNG~q4D4XEg)=?&?NmCAouJMSG*ym2ez3Vn zkwg{@!AOEk$Gz`xnQj!NufwcNU{~p*jz$r}QTIo06s5yD+(p$yO>+#Tg8EN_7kW$t zBwe6uq6U}$tUgx~Wa6_e1qE~)8SF@7wloEf4xFY-iw)i0bl?)d{tD3VahZ#CL7Ig^ zw|CZ1u9UKzL+7;)-`{7|UKv;O{e3=CIoSopg0qvl$De@KdO+v3YV`dj-ijeM*k@(2 zD~>r06+q@3R9cLFM1!GuaxGK*%agRE7Lj4%_%4+3+NGvaZBo*{NN-<>@a?i-#3gR& z<-0py#zw9|<)fx$>+0;SSh-@?)oicnlu$F$yr~2{_H<-7y$rhPzK1{+vwA$;Tv(fb zTTqPu2Qz7@9J65%Rem|=G@eTWkUesALzw9t`p<$eub^mLn6I7AGGB%laaxx&qz>uD zFtzEtiv29Y`Ooqrkt>4=R7~l*UO$o$_2Yk<`!FXIZdK!kbQdnF6dEK*6%JwVk_~wh zDtTpn?OLXY^dYQJ?k1{};y0{c!waq+8CqmNYq*S^)anrd7Pj$G#aK|3)CpbB?}mK{ zHY{{4^v=b0%8_J|6p{8_cr4Tn#+pofz!bqP3<DhowKQHU=D!(UzX;+ryNKcq(OGaZ z9aQb)bGFdX)1m!wZlsx(4KcWBomh^IBYtZ16TV6FEZYrYZHa(xA(wVf--~bt+fK{7 zjbL0K`O1D3)z3l~iN3p9uOb77$<hSv+1liUu@<TZcn()#@`ekzXiN$+ej#_h7pzij z#&lK!`nTc<PR1RA$R8y*P4RquU=<%>|A5K}v#Gs;k-ZUcgiQbMtnswO$bg&?Jk2v* z5o@g#)Fgz*X7<%q(gIj$8=-@*=4|8`u^t$`jU$ARK=4$BUvD8nlfee#nK9h?uQ*(8 z(_y7r1yiEj3PG@-qxXcdH{GaaS>s+IdHlP7wIXAaeT*<5JFHW-moJ(`h@k$@kEs^0 zw<t#t!aG~#?ZriHqrfD#<41=<0?j@=?5m=+yK!|aYcxc+E^;ZrK<d@J!=pF3XIgRw z42=coJFI-NPYcpeQ;XWI)|Wj$@HCKYGZARPYgaVsSu(6c{AGe!iiJ#|iPN<R=f=30 zI4Pe9BgHDbUnALDo3IWGm`|p=UIvL{41Kn9y=7grzvZMz!efwsS@$yWbZ2&otq;ZK zR=;te23L)p@nys7S7eQ4;~~~v5R7#P6i?FS-%l(j!1sqcE#r&r(|+&<22JAlbu|~w z{GgAdjXATQgW<>U7geU<eE2$?4cV`xnv&eFwQ4u-_6*S@aaVl%6q0RQM&|w$GD6j? zVM|gUfvdazVf+=iah$gFD*ud1|5U+8&AnqkiB0GyOUwrrl+3EOcq#7NqoVB;KAI!O z5a-$TKiB{H*abmipm1qD^w*t-$Ft9xdy-QBq<%N1W@5?4k<_b)x2}=y0^v@GbSc%1 zI1cQ{tO-{NEfy+DqO7Jo40@~ZH`&UCn(_IHvGLUGsGpM-zLKD6sBp5ssYokUp8Mi0 zQi#|H94;>{n)i|lpNk%9<rt5TzxhnXqwLD7&)h_9j5nTsb<CQbDRbU?`6Xo9aad3A z%D6Tq<+6l#m`RJ)a-^u`Mzc7r1IFUJ>rZZE;=K1Sn@8TNJzK#PU>2VoD!s_0L-<?# z@(9Oa{5&Y}bQ8`}Fi4%8gTHJ3Xh=o(3yI7e9-^DqcokpKoLcW+)>_6xE{`kX_4$@; zc=5N^KgEVmnb5)PhHhl2bB*%1k}=hJad-e;QS?7IuwD$9DAtcD%B99}jGxHEo&WfE z-W&Q?Ofgt#iYSEo$2Y3?)`wTetA!ju4BpROw~6*&^74!K7u)$S8SPa)Zm>JxaYCN` z(+qJI4}d!#?e6RuWeTc|-@F!Yo+WoR-A#Qnn*T%cKcdbHFPBdm5^A`%mC^ZmC4oyv z3L3V)O5n0YV0L>K-=~AEx6A%m+~8R9@?c1Ber<qpcEjiD<Kdtj21W0!^P#sd$t~eq zws?OU_Ekpi<Nrpl8v2rAli!X_qozGCPI|fI?{gBSeXHBnG%^-uTD8YKZ}X1Nzo7W| z1id4hzZgAGt334WF1axOnG+k@FNxBxFS+XIU)Be0R{Yr%-n8)jAH32IWIP>_4jh#B z<cO=;whm?Ju(Ub(U#~~)d6-a9yeh8ul1ylNAN=YRpVGUbX-!^}s)cB5z|-o<?~=Pm zbKF15b8@T@_DwXo%=Dm=55&IvW<fdR2?4}T`atKE+)hGz>^Iqlc)H99qA+#%^{E9t z`Th=LlgS$IRkDIx(=VhMlRgvhqe!nVjqmuqsZ*LJlE1!I+`OUI`c8OmI_s*SWsb`m z|6V1&r;ieC-S;8D&P2w^9vBM6I&f`gglbr^?HtzhULQRqJzv<Y&DE(~=P}TmC5B0Y zl+4ZA>ZA-%I@#EyDV1V%E^zm&^mL023459g8!;UEg@JexU~2FWmtT?11~1EQecs|V z_l7BEV?MFx1PLQ#nJGr&U^Cu9)mn4I_oozpCp$rzwAMJX=YLi9-dGa+g;bfjoVC_Y zf3nNv4Z`A7TK?|)J<vk{6TN^@i_xOP<2f>6qLsT6;xrL+C@S(UuS7408D^z<_R&Hn zaR5#?ewWnMGfuZ6)ikr)@Aj5E|M>r85Ra|;F~i9EHNiyx88<g-G>_}KWP)jjs<b;V z4)zhrFrvrxfA68^a~uI+IiFvSvvqIfWxcvlEE9GfF0DU-w>pZqhj}wbU9Moe+p(N% zuTXvtBU$@{<g~M0Wjwx_oxlW667+G9D|vRXoiK>JK8io#u_`lK_*d$kSunasKMPcV z4dfxU6S-Yj50t^{^^)uY8}4yQ<w=E*e6#tiTNhj9jF6tjJL<HYa_=~7{3s<1Lw0zF zO<${9N}@A7y|x!)7gK+>LO3`iO54HUpmi7WA)WEvIiv!lm2l3WzQS-42M6$%C3k#0 z;bg)cCuEBeA)C&cv*!!7ijX9xvD;S+siGDOSe8$PeTgUABiHc@VeGaWkZibZ9ZLIM z;xV6yE~o*V??l-ldG$GeUXG&kznX*`-EU&-jBzrcKW3X!Ge2;pz>vfq_EDk<t0pq* zfw4IC>LmX1S3wgi7TIAudX2r}jTP#}!bw#RW8oQ<Oknb@c~aKXB4MHfMOO;eA~SXx z<1h!0$yX`NrwYnPC@i@NNgJuu8+Ez-;EPZgXix<Ayv~>gQpVHm%yaVmUGg3;CU%k9 z$pcvZmam504ShA4pm3;k%n*X?1(@MKB&>U>QAV&pbVibNA)oOT@BT^$4k_BggA~}z zLwUq%omUi$s~*-n`!O|K+DyxxdGR0oN#IrCTZjO_&{uN=BL>$3K>oJT<e@MMZpG6) znlgHA3WmaG;k`|~;XHg|`QKZ3>~Nkb1Mf-C=y&?szBONFU=?BPp*43NJO21(xXS77 zW2H<eot-{(uADfKta?0dw|jqsyW)(+NY+RHX^1|*l=nl*7YbR2msX(`5FfTIA$(G~ z)ti9=>_pq!<K5Om@kD@yd`eS}0L@((mX(Xyi5kYL;PNv<463@9;ZmtX!cmR4Cj`8^ zvF|Jk#cTt6_Nd`2-G6CjxXS6%3`LnMwQ=&~S?p6*1%7ny-xZE2;Ns@h={EHv)Wi9) zN976Ygo!{2BsEc)v>3YOXFF0`Zxw1aU~W`F6dTgsx=B8kFVJi~Qt-OoT6r}Y11pC2 zo9T#Oc@IFhR*cN!-dEm}q53#WhU1NXiS@WnDMH5GrzaEo817lizTkFjx|pnXwC;Ic zEG3Mf!rY;ui?5|%7u$aj{8m?GFO{FQY^8W3su!Jq;2*G5FoM}#BhE}vX-!tCNITTl zUiC)B*5yCPGn!1#a9$UD?XN4IQ{0RHgRqlcy)Ai(eu8wCc^%-C)7Amo){1FYOwheY zDt{_9wurs1ZPt(I;N<ZAP{Hb5Rdoec?r~huj150~N10@kd4c-$e>~~>FSAv7Wu!OT z*`{l>;8(47fM#Qk!`DT7ms5ob1uK$F<!~un+`UcwbOF<bTrf=@d^jz6^H}YfHZ{M@ zerv?t5`EWCM=XmiQMg5=1${fF|D?)oR*rU=3cy8}^mtx9+GE@G?d!qp@hth5x4q^1 z?QeI#t)@NbKM&F_d`e(tM0_x~?56`$+-sW7*M3UVK{r%3^l^H1W#^;$JMK*R&LO>E zPgAnAd&d6WO@F5k(mr~D1t{p;d+Kh#SG+a9Avc;kFr&Wz*9Y?8{GlyFnvbdR>oexN z->)+@4gPOrPI$-W>Z2d~#SL#{hDmkj6yGbKvRMDVsEy4ry>oZTYS*%>ZJk|6MVURD zRT~FY&W5nZ{nAdO=Ew<3rN%#M>%aEuQhL+UR(^Bh>xRyd03W%XkBo+C@ezaj8HXgn zW3M%bzv1GNw6udbf$Ia!&Wh=2lFFqN(&07?)-;a;NqaNJ#8q^!+0Y#mpZkl5t9Y!% zNN6r6F@poUahcXUz{dk@LpA=6-{jZY{GAknXX@vNoDWXLcIJh%0}Y_}>as->)N~9M zOOWBbF6mRcvurQ?4P25Dh>!Y!pIhmYKY5Zl@<j_f0IW>8Wq-L8?Shw=s6WyF#|+6U zQ$!(<oq3U@q&64$thM$buzq9T(iG?Namy|(8ZQD{AXDlZI{o5A2)C#Z&b(qLT+`X% z`~wn!<yv1oSg&TR>YYHYGg<0MjNh2)y@=dew7#s-PNXRC(;O+NIc|4T(^PPYj=<Qp zNW0f{6)H+2?Hh?l&rG!l->YA1a?Itp?4ALxxRRclgBR<ufBih3W+t=TC%&Mtlk967 zl{^5I>B2>g=ff#$hjuWmGGwgDx&OsKlE0q>qAEO%$lD*ztx!}W?C?Kbn&#295FoVv zn}e2%igRHe|5weQKe|9#7BFtIDD66PW2!x?&8^-lz6u*OJ;uY76>=M@?OX!+LQp6A zJ^I*Ga1qafp>*bxj6Tkj3F06LMGJNee!ATBn-vbWtO1!=VV@>}y-w?OgKi*wE%p;I z=Q9^Qj}DY>z!t<wd~`Mr-mpA^?r}kTSdB0K^V~f`3Q}8R3)D2yfZNBTskB8?&wbW3 z=F`HlK^5{tq{>Ec)`f8c>F?noYncSER>gW?ECB!xd)aaoEm~$x0=|Jjv)lN5WZBo= zR#aiiz7s7K6Xq=B@0(BV=}g8Ef%@P;48|oCOlMG1S}cLhdDb48+_SknMD)W6k4}LN z`<{S8g|GzG!OlvpM(>LuGL??&I0nhkw7Zapw*^sJ3cn`-u2U&mixOC$lZG_#w~-P8 zBj_X1&}ph{AsG}vE#ix~OuHnT$Ryub<D1mYij8YW&4VIz`dO8kFH5@x!NW>D5nDq- zQdnm?Q!@^)GhI5}dnSX|>P7JFuvMi>6-m|DF^cYve;O%`^yYm%%$o>o*``{=`7hLw zvt$$tOBqyJovl*@aX?u8V3t6d3-L$AM_rVQE^`9fBZ9qGQk;B<X9FIRT9x%oAlWFS z^`=H}666qo`HSOfoz1ONc2a0ij$MhBUwKyXF9W(?F!2N058li}#Odps?wY8#)%y;A zdw)&FwDhKKu?&?G@2cPc9uQ64P{xmczBKK`di&lXEPYrzl@YP7<1?lC|Fd)@P)%N2 z7Zt14wp6rQ6^Ly@K~ShTf`Le@hJZGLB8nhw!BW&pnS>}1i?z;)1d!rDka<Q0iVT8O zYnU`;Run-AL}o~sGxXm#?_Y1d^_~pj8}2>#oPGA*=O!f*IVlA3t!sB4{TWA<42(Ku z1}(x8_a=nx_ig<$96pd0)=#9P<OZ?rZqGN}%SkB)_6raNavl*ulapN}TIp4dFupT_ zbc5zX>PTp*`qAY)vgpL2CCoL8syfQZdl9NPJIz-<#rip`KD7^8F~~4T>5JS})oq%4 z;@Fi8_*Wqn33fJ$$4CYp!Z8lU44LW0>bCs_0yJcB(O6x%F_(jaw9y%qgbx9YgyBM( zv+oy6yh-L7j~g4bCz-~K)I|c{WT4YbvZchZN(Nta(yvT|0yCOh5>43BX+PyCW-@LM zm{z-ys$52ibt1M&s3AQtByU*nq8^@tJEj^sKPmz@1w7S;3sT<Cc)(ThM*#h6Y*0#A z+x?l8KLHA%z~p}|B8DcV_@lj$$>|=N=DrqK2^PSK9xjzIf*AK_Iihi^ZZ%{-+WI<) z<RHj@2^It*)cq4l$YiOA%lij#E7^pgiD5!Gf5K(ku{NET2YfW$@oppkWvDGEn$Wz~ zKs7byd%1r4RJJZU{$^#9NH$_#?vloq*_LPTJM6xs`YtEXamTFh(F~<x4QrxCZ*sJ_ zGvN*}+<GRc8)&zrq-TN<h(Hce@qHk(xsz{&|NL_3?a)2__TMARu$dsoddL|+0B*j; zrR$yHg3#4dcaoJm>$^(t#&0q2<S`0g;EH9Y4P&n|2E65qNroie(l6_(45v4jEz4$d zQ^mB!B9Bv{i>Katj;{ZXx9~yN+5PCURAR$$XMFSns!yA5SZ(In+pcq{pfy2Z{Yuoc z-~56N<-0eb6W4ry1Kol$;<EW8foru?<Q^aMu6HQg>n<P+^5*^b7g^GZPul!A)vB=U zEoYn?8ldtXyQAR}KE#2tPAEmP?efHC%Tz#4i245b$4++z3t&3IY3*;GJRjcfNs=LY z|Jl*ae-sEmJs|eUXtO<uRaYf&y4=0#_xfonDk$;#x;)RRXCn;PsneNa+BJ5tCz?7X zg!`s>u7fEYy=xrg9iBg06O+WW`fVSP;Kv<DTOyIvOyFWU=r39PtL7_7uzxl{I=JwB z96NE#BtgL<{@4pQ2LR+G2wH`$uT5r;N23=Awr{UK=~~Ban`^_eu|Hw~b%%z}8Kj52 zpfeS9^CD!i8B~O2QpBsRJRkw2#5rt(u~Cz=%U4gZpt6wn#^^=Y0E_-+If((iw;6!q zqGxu%Z_NlQMNM1)aFkiR$uK=xaB;Ozv}-#gECw~k9roRP-X$<qc$d#SL%o!yQC`@a z?XG4-B&88T+<FZ4?rvE4yAX|cRr@;l=cyE#3x9`UhQ>u(;B@x@73F)%qNd13W1Nea z3(*1hmGyNnb#j^IL$7f)+4d63<?fUdm5fMe+uZ}&&?l*BM=!z4A8GU{<~D<eojr2p zGVWI}idD;1Kf1)ZZ=P{J75tk-uB39cf2HFt8?EG~!|Ml;qoPMP9^*Q>aZNkxi0USY zYdjp3_=)iB15fXV%kB+TKtEDY&|$_RR<n(a$@is0^A`5d1ei90dIN8g{s7+aAA-4y zsXWSyPF_r81b}T2VbOu?MrnptgceIfX8<J+qEXHNN9gK@{hl{7mJB(Ee*#h%aJ!J5 zv5XZmh&{F9IgD4TcJQ$})J=jU<OH#fm6OJ^rOJF>6j;zr{xH%aGwI;I1^PEyAmh)0 z#lTWLde)cB3fN}g-(BF=Vfs88Uhw(`DG!ep?RC`LxR+KdL72vA0M6Y)Ad+0z73U3a z!f1FTyKn?hd7~QCxC@{yYhi`pC)LO^n?>8vt;S8PL5O!$kG{D`R1Gv;*h_%@4-KVj zD2QbQY)35F_9=ca5ykKS2*mC9^AHJ$iHn3kH<1W$K4rtd6*feG#)<eqi}765zBsJL zJFWst8KgcT(wTU!nGmxtG$$SDe6HyYEk-JbbO6CV5J8vo4Uq5gKsE!u&}bS1XhjN( zM=TZMMC{^$lKOHw+W$8SaAohfNm#5@k>ehKA3m$^4B(K|rV7!w|IR`c2`)7(nv)>f zo5bmy(G6T87o|E83Isb(AOc`sx5kg|efMlOwN5dPx|(+#32r*-aTqy=dyNzP9WgQs z5JUVP!Xn}*N;bojsb^pOZoNk?cr1pCMARm}lg4;3EAy)-$f!(WVU32u#Sjb_>@i~q z4fwT5ByJHD1W*uERLYu)6xZq2J>)8A*=NRtXUnysp0wq)!3-y&1$$s-Ce6Mv^s<M! zI<9qNr^hF@Z&fQAwAteq|I-R<bvIZgn_wbu45*gdSJjuh+h?V~Uz`wGb7L@;dvg_| zjEtTScR%`q^j-adv)+NkSX@OcA>-9Y0u);U0uF@MJrO*&T%{RWxxO~47L!uer+Y)e zO4`J@a(c1pPa*VbBpM`LaU(AW=pK^xzhW#>Q;LJbo*%U{>%tQL5<>%1@b`dx;*NKl zW|S0y*Q{Emzb{_r&GD#OL4M$AyT)6O)GaI<Nz84kNUF*KbxC6xKbCvxw1*i>IYs`A z^sAaDg1;f)LT%(+?Yi|S`++ma1u6)cssRo#kA<ltDbp{VcAp@4E(in7?5{kq`Fv8g zG~Wt0KELMlby~b7Nv(+mG7<h@;+YFB09xb}7lp?#0uK06$}#na=cGKYfDQ1nr9N-L z!k1MI5jyAy%>XiD3tGYbGDo8-KNImIo8%POM<%Z|v@tRvM%E{3DvA0bR0!ulb*<ht za+&~0VQI&EL(r`Q;H50B9hC(cd^3Tlw9f6H<@vxjDu5mK{gI+stc351@yxGt0BvBF zx<A3n1@?7K$syEf#&AchbDE#QXQQY3EH_qlVx6JM-Wp%+Zq7F^Z-3`dj6*KoJ)rs3 z=dxR}$qSP7KG@P_YGv5Kkq2DkwK!zc!92VQ+w*FWc;G$s?^0@FGC{YlM=vpOhnA%@ z5vC2=Fa>agItEFp?Phc!%}Vn=QtoIf(4h_pIJ&lE`M1V5U%;ZlE58)UeD5-V5NT^W zYN9i6+hKCW07|T}=cgv;6AFbLN!TJ=B@@5BTUepf_gCyhRQ24~7>`h`AO4$iwkn~Z z<I=e`X3A3ilZZxG_#|+uHlY9ZjN$LH*iH2BjLXG}U<sL}ki$4Hfp5OsB9W9NSp9sG zY!0Rz3-Nx^ddjAl600%GdY&!0R~1t9=$glY_TG}1ME6R%KX4<a2PO1~Dmv|+Aned% zmNi&5)oVTZlh`^~!_t)S$c>Uy-J-~o*C4GOu0zi2^2Ixy^LeS&<@4!ND7KFk{k<r& zt9VM9^>aY4%U;cgA}B^yA0#->@%}OIF6N_;jouk%M~Spg{gh8p7J*<=p$g2qWJ3+5 zwUo`uV9iw}<H>+%^Qy7O>Rr=c^gdWE7_w=f8Pwc407MkV9=Z{KFt-P?^p|MCQ2>^M zptu@p!_)$-l4w+&0!uicqXUb#ws0N^Z<x7G6$l~pT3?$+dfeM|1Xh0tcO~3hU}ymS zA?9f@Dr~o*^K+hS!ADhyLAh2a4j9F7PDbcWuV~qK6Ze0c)KateQdFpK-U~4+SC;u? zUhIw~oEXD%OE}Tb#`n(}6J;=h4MA2>wJ)0m?k95;3bS1qv&I~^qYavkc^OzS2MM+T z|7h%vM%|c4TwshOKtlC({}NU3r*<@l{3kGX7BhCoXRBEHEaxt8hOp>nRcN}6Wk_E3 zAsODLi!+kwR$MZunGaU9F=j+LFK`$l4Ym4v1nrecasU?sA;_51T5g~oe!Oh7`hRB@ zij;$`H;+b^1tTAZ0o>uMBP|TZ<H=DZ-R-UMM?K0)(Cmc$PgB+gj4;D*UF&Cq@{O+7 zv~E6(<|q>=XZFY6q+jEJNK8=`q|dpGP6Uxk$L<0|jt-R!95UN$p#8n!1kFJ-z&UKL z>F;4I0S;{VaFH01@m3LCrRI><aw0a_L8Dl_9nh(JoS_7Pdp~ECybo|0uqeQ61p5&j z9Z+0>hm$dXN_m2|05*V0m}dT;)}2OWHPUw%LMsEGos^{E!`{QIv0w1zR2<Hz&jtJB zkHPcy!e8&GA^!xT318v3ZA$@waGKEJ#K~vDP-Qp~FWrO%UjPD<;_oS!AQ;TjQ{zoO z7sQqGq5Ojf)E;fM8{Wk(*!Hl^1gMYC%#%|y$UoqUNCZ@dX#XNq5Y83YXy}<>cq^<a ztdN!LQ!@dI5Mm$9hCzqd-x-4(_Te~SDC61K0o@G3vBw}yjq(;vVoV&E^tWdEks}-1 zx@iT*+dTl;U7!)%qD4b|v!FoO27znLN<7`9Fye!r7QFx`H-wEc*rKDVRFotvfF(0i zQH2L{vkAEo;!iY`au`;CHgFKg*Xdp4L<BKaU}d=tLy2VX1-r*s`Gli@{sY!k_>n!j z0f^r30TV<+BLd$E3aQ`W?t;a21M3q2E@@~O8lWv3yxmVZjs^yn6mQRRM<%>CYUnda zGw|sG4uthA13VDLB=hSJW(L&DrozJl{@EWX!X!=v52IMOhgYw}?gd&w2y-PfrJel8 z@Iy>v8@^to%I#NqqTbHWFq|)+)!tkB%lACSm!R2U8R+}SA<NVAw-KYz<=zM9ko{!> zvS~($+8b}m{;l-LBFul-uG1|7yXFQ|YjQ9>)Q>e>3cMfZWi=a(#KW7F0<K<+VOa>t z0j~S0hq9)_e?&&viW-6z&m;{FE8dBRcDi;p&4gzv2SE_;AAo%bU<z4R#+%*uL5E+D z%}W)1L=30!R^b_$_wC-LeGJ94a#6Fx12RMN9S%0<NsNzWgPG_J{-$D06#CZ<Xc<A! z)J?0qP2PlL8d(ucXVD4=0|c%C0Cn=%de>N373A=CHX_g$ATK$O_x-B)r%>8UhtO5< zKDfTuQEccV-b~om-M4AK5?%+#yx8q2TS*ne$39PeDqNP8_G)ct)f><Z>H!mx%$~G0 z5pnnmjaU6x!-MV})&-k-EN{Ahw~oviB_#f0G9oS(FN-YAu^XZOVG6Ed(%GzF6#b~o z?mu&{S7p(GcmRS{3GN0R%4@HNJt*-25VQ;t(;W~=HVDdw-_5&VK9;rDhwfJi%!^QM z0SoS?W?d;xsd*eN^Ihy7R(hZ`o|F(h``NK<kTT<XT(W<CO)r5l#G)pyA=}uEn#4sx zgo9mfa!F?#j7La(;@vU$jEwxt@FB;<EPV%-;o3RHpTTXZ0vOorN@Wl|=&-%9aS`gv z5|3F^PucTAc#oaXxDvF02f0N;;x){m-EQGf=&n9k`)1A<zq4X+{hd%d{=kap$oC}; zcwhi$#|Ki`_ji+FXpNhB71Y2%*D#w9$yMOAGp{<m2mQW^{b&XIiW#lqE?OZ&WfgC1 z35TI#Jm&YL+L0(@`SGx`A2(fJ@5@$9AO7vFP~VnD@dD=rIM<}mzpUZu%*QUf)eQ~a ze5V4!G&2P9$B2_~v)L8;ZeGd$O%YpjPFJ=VtkSXmJ(AevmL>gjc;Vfa4KK&qk3O!u zE5sxY_ww`aeAasNky}^Aw6>+*e7B`bj_ePKVaxBLcE;xLb>US-GxMXIM;h4KFHw@& zb+OlV@|7u}wPDGxedH|d(JJJxVgPs^`37H&&}WVd5x(i4$@Binds+Ip<I@VR9_6J~ zG-4x-($_(f_!yUR>As_@Lz&WLvE5Bbtsk1cbE)+GRJpM!{$u+FHdW;n0HfD_v3JDo zvFY6(M%Uatq6?L&1=$YLT^~4hLy<-FA85)rfor}g;<yc_D&UxfmTSq9y{pHx_8M!l zIP|IrOmGp-UqEZ@k;GO&-ZE26uL9XiDnzfqI5dVL-Y#%7)P8|=l5x}|YwlSP<&=Rl z-z+Z|Zue_6x%_2DC^)HdLhdJMdqt%qMm5F2GHZ#U`Di^61|lG5MSY)m(O8a2Z_A8n zsfJ6KhF?><>-ACAA2D70D>6k#2j!9jcc{EeFeZ8bKs(xThuuQu62$rLdTbTkiy4UU zan9dwDqz5Av}8V`F6h~N|8RB5=f-yp?v2!{sJmf?3w4w<O__g6{>+|X#sMKkqgxy^ z|HGrKuqmpx1D0!QRqKKbbdQ`gbm8h9SM3ARc{&=K86Vdc3jo0}h*Vvg0m}9b7#mNH z9zs~K{8MiY0lhJ=C{2VTWFMFq|AS&PEZ~g+;yD;pi0{7=YypDN=iuWGqv@;O4&f>U zaiMsVm|Z|GfwRLbnJt_IVQ#|~N(C3XP;8?Co$!G>QwrOSaSX|P&@0;)?-8kw<4$w* z;iJQcwxANdZNrA($w>VzgyHDu!+xY)msx%h^Wrj~ore7bx<wGkV~q;VXlD?oCU`hO zH;;jVNa-*-3l%971q~OFah)I;jZu(x!a=S~nEwXD4W+O*0z`w8vzDQl+?AkB0H-Jk z?ivLy^nIjB#5B}#+*e9GZe7T$!T&gsX{m_REaR{Ko|ds7A`=iKLH7PEnNgaKD4I+F zSNeNnoD44AP0r>7f|70*K1i4|h4K|dEN>%p;C0c8Z@vNGBj!iY$x1LO5Qp}q6no&m zT2OMlC+ER-!qX<PAHI)^P=GQqYG*U-ZMy%R8$w!}EqHEmU~X=%r>Wg2v_LIiTs&O! z9`r`Pe?Q9$HbK!WeNYkV_1=I@x=2J3J7JJUpY<5}yx4rv{%5#ZXaU%Vf+mJY*0iX3 z@sC_Q*o(B6jv~@6Qes&Bg?eQT4V)7AWOJHGo|Vx9@(JNzz|hM+=WxtO@S}h!(UX6H zD&I$5!;*r0Aji|{W%>X1zG7DSGGPAMeUMC-fu2u#A~O!GLIs`Bs*&XgvCP_nn2$^7 zr+&Fwwg^z$S<O7@)S&uGq;;_WnhX+s)opg{?8&7q8xVRCtAJm*?`ztCWDO+*JbfUa zIJ6G*;cg{{8DivMSGMu^#f^3#qDv#NkebCRWWLgawe7l%o<bip(r1Ou447RpRQFKy z@j!&ckc44VCkGG6ti5BAhx&;Q-uLl%K&YkY0HFZT|6#3Rz=<DgH^0OtMXd>f+Zg)C zNZY}e)%UFCOn9sp!>6t%Ts|ob&)vc40pb<?P0q%l?d47f887g<hTCm3k)y(h7#(xS z+%Iu0wkV%q^jzP9q4H*;Ntk6cvVU~)cQ2fuSvc|W-f;|=yw-(61g2kVmE+Ax$o=4M z1{DWc*Yjx*7)x;)BE{z)3iy0katLfaEwIqhqu%eO_8{H(?2hd+PGlv*i{@jY0GXB= z#Tx3Rrr<AN>0#hj1d+fp>UgZK$WA`)!i5~~ggyAQ?=`I7m<+68Nbs9~(*|HqjL?v_ zXJP0l@(VY3q>~*%i^N}oS0fP^cM!nNs`k6C<%)_S{FFjG*;j^?S`527;01(56AYs# ztO)3B#1_~C7MJ+n)R_+BIb$#S9QGdl_HjkqCdRRd`LO-~{FLWXjuG6FT=vtiIXCqG z(*iO=-`xDvt#tnMAB6vByT1p!*Q7#yIrq8eEszizxN}+GHh*esG`!k}mINl;)_JiG zJ3gaV{%CUj(xvq61^W&kf!zpZ#OtFSzr*4;ous<NOIiX;6MKGLO6pb}o_&$F49ja* zUvjv+4NQHFCv?tY85DM$JC)WpR^5e?QYI}#_gf6W)mx>^E449D{yZ}I&%y(YdtMH^ z9ctyY#<D8%f>UwgR;&enVfI&<<+~h*$FcS8FWjqrg0<suykV>KFJt-Ye=eCWVz{rI zJYV|&9Yc9TYT<+Urx?&hlbcF9@TdO@Tyf>(4K`0%5zk(`@c<PT9+9n0Gbf6DGJN*9 zzi=029DtBK1V6r^W8;mlZ++6i8r>DV=eV#ol5DgX?*5V6sTs$lF933~sB+Wa2yH-l zk&rtNF-PY<z4;{})%!L7>H12Kd#P-hPv*BaQCU8B-P`EGJ}Kd5hVn;~CcYK4ikp;c zjoLcFEJ2#RR<~jYRq*&pJ=g#~hW_Ey5&FcsYTExyRIdjmhqYh2x|9Dj$MajEJ<fwJ z!5celAf}<$KwiUtT9-QV)#pZ6v|tv;0QQEey@`T=kPDg9sP_~8nKxfdoeoupB@0|Z zhn4W9Y0Crj9gn)Rsb~X;u?7PwVH%T3-qSB8e^|t^d7$hCYB}obYGgxcpvj=Go45sm z8<guk+gM-K;87ryyPH_rbQ`z{IDwzMYjSKV*t2vo(h&=%`W<r@kU)=`1;-#zGR%mk zz~aHY4rGm+Fr9XS1Xx%lqjG_75gY+t*JXjC3<<(1cV@1w?WT{R_@hOYUAXwcWJh<} zYn}j(GIDI411K~7_x1w+jjDx{SeS`sAVhN`e$xeLRbu7$xW-*+BEuzaX67SKOe7-u ztZxA<EMOxyeHP=Qh3{$jhOT>OflETnM~QQ)i+v|zJTOUDJCF=8z^R63Pm=xSCNz0> zd`8T!nt${C7Sg#4({yr@C~CUL7*j9<e`760MAr`MYEpkDQsAj8FDh!@Z8SGq*k2%k z)6_vQb=}YZ4NB^`u~IyKjhmIrb~~&7>OM<p0N#1lreZ>{d6VY~U6b6@YD=Fg+u!K{ zZw`0>*;(LKB%!#1+&(4z>2{=rwa9yDfb>)|7zF~(JIiQj5S)ost6n+*hZp+lTY#YA zMv%L)gn88za;#B#n&x{y;{{Jhd7XK8o|xHYf;1no$&8HH%>X6fU=qkz@hB&yxA1j) zE>YWk1k?dcsYFZS){3JJp?4xh3na8M9&7b#bSbNWX`?ADfP*&zP&Exc1yT&^+R}h- zMw75|d!%SPST_)ZommRsP9nhY8%W&JV6P>hO!q36Xj<CaZ-PF75pq7neq4}%gBLPt z3_MB%{ffas%|9QhPXBH2NH2L4*bwu9G+n2_Sw@rel2BoIoE{N`dJ%pT2>f^ksHXzp z&nH+w>`qSY5%$5tXLedF8*o^Y5HTMt2N<a6`86YnqCbpxcY(5xa12-=B7hneqaE3# z_MYa&VTHpVvf;YMHix)hvcJ}4!1f3fI)9w>Fk`V#K=3%I8G?|dqs|2)4`~o2iV89x z5eFVjz@Qr?-swsBlhrmVEe2*sxRb+qgBXg9*&$tWW1OM(<kBEF2KyXI`9&JC8O$yP zqXaL7oB)>F(2EdQ0fBY^9T}J^;#w&lHX=D56T*H9R6aT#QxP*;)~pf?ame1(_nN!V z!R0}e7nh3`V;g0@QipOjbhCaLgw-+#G#J3bftuF`RfcYyT8II*uf|_=$vdMaKV>SO zf$Y@qP}cHtz>9}!xo7`pCW^8m^XR5~_+W6-Q8i-}?tNDbaVAa6JI(WrWNW*ks<1$U zF$Jc=a59cy?u6ZN<j2{TT_yZl4uiXgO?e3jBpl2uFpXF=8%)t8+(%3|mLluc^w(JW zU%ZH5uk%8|R0|10cV27-;z=&(4FzSSlQ0;xklka8L}Hpx`A=(Q3gz_SgrD3^+^c)M zA!zu!q+ap|Q?LN{pBvOTt&46@xVxjkUK+E}`WbceV&SC;TNLvvGzQQ{qs<4+kObkl zg<Wyq_}JHM$_!|~xW$!d#X(hmaP#%xMUOSSh5skhdT$R)`OK?e<E1N?1#HTnG8Cog zc`*$uUTbpxmhho_K_Bn`c+(bjJ^fcq`4oYHgAOkyvE}q4@O!KBb1&?>YA65FaG9<{ zx`bbaq1a3sk@S6dhpy?CwP5pA&>C13b+AG}Xp=-(uEHY{mgN**G!_Ad!n;G}yH~^* znj{`eJUb)-@WWN-g@JM+2p`H`=!e9^n!$lIhK`j71QKsz)818lF4hvApcCL^VYskN zIU^eMzY@WrMZlc_vJ}SpDfB`o;T44P0al{6#CBaiiDHgMkw3-&R?N+i&Dqq)wm{<| z8FF+}{wQ9_kr8BtLlV_%5;q2nzz~s}UvcU90VpYoqM?3dp=q_l2XZ|tbITPlu?@o8 z2}i^6huk-NuXhnv87FWW3<rz!?fy=UlGJ^27*;51^no&5;-S9<7f8$1N6-7OHcq_s z;fLNcC82?PwsEr|v)2C`hF1c<1-z=Uk~>ogovBO!F?bq=MOoOhJ2Pj$4rZ^Mj_LLI zBz#jy?AyYofcI_D7h%%B)>|dfp{N4#%t(}%^>I!G&KWa*%N-266OyT8ept4_6dhN- zRIr_^Jg+F34BP5f&`jmop;tNW<8dvr9ob_8LjAnZpGKL#2N|0WY+OzBblta*B9i8( z_@&|9l+UQ+t_vVbl=Y`KhB{+D%`&x{0Eo^s7vP3vQt0*qUW3|htla^|mPRv0ShfBx ze?67$1l^$mW1~$h3%gJMX@B!#W50nukK0iRsnghVtIopPvm2cYOA9Lscp=CI?T}Lh zH67?*c5+=cazqr*hyJSgesnIz`(o{)R}6pD@*c+%*6g$48^f#OcwJ5-!niOHL|Mn^ z!ZO?t`5nv*i8m;%A5JSMEfOq%O&}`!hzhTu;ZMqM8~q6eaT()XMI~D&)V?rkaA{<l z2LuJf3A{|z^FN!MUMs6GV%=m*SKfiCJ0s@qQ>TNB+6HNYM)g54Wu_?490oI_b(OWj zv|4?)kzR6|SbS?OaY8(Golh0mb4QWGv@$F%&GS=xp#|pwa~yE$MjK6VG9WKECTf37 zWE3g`E3j6xK`9gv(H+{hI40o~mMM9C9bH-Yo*Di>$PZ6%sN*P=EKpAnrIE_uAc_Oh z9PjS@`ywJlh-T_j`rhCBVF%RS#`fP+MBnU{q;g>gcVM<qe-Uskw?MbqfCKv8Crw6+ z$D<G2)DiqnvJ0NQi9LlGhl-VtYs1Nak2?d44mikVz`oRFHfBF!Y$gCh$EGumq+yRk z7{L*>3?Ms9;9NMv7#gYw#(wO-gSr%A`SF-%J{6<m`az$D%MlYX%j$i{!Z&P-5d0P> z+0X5J%AD_G!Y9TK4AXMYzU9Umq!`T<lQUT=B(taEM_sVL7ia@3M88n#?CBJXr!!2* z2t}Sq7|<iiq*Tf{K_^=A8Oj12daL{lc2N3ogb+z0>^CE)k;GaXTj-E~UyrsW81_WU zrx0LwS0h8ZE@0_vA$Y#p(x-#u0sKCMN_Fl<BYX=sL!fa*Ph+@%DnDI==D~gBp3#gD zCVLo;jOX+P8OfZ;hGpTR6kRBTR&$5DmuMmADN7KGDpVQlRJhn`ZXGHvFwKBqqum~< z9)hVE%Y;RL7L7T^3^L1*_*zJn1&KOuSk4l#K1!U(DX9fwfFK!#CnO&fNLm5<8qY=% z_a$Q*w)|G1+&&_Tm;#9fYIro#aj0B`Vi+a)q+cUAc&mWOV(uYK{-}v;0&=Iu7);|6 zW_qE}cV{Y>u!ya-^87Yk4pec(3lNnv{N{#~m~}p1NpKYjp@~a{!#3S3i5n7}lhkU$ z7X~xm2{|)v3Ct!mYb>&mnSoLO%hPGZT4ODE>HumclU~f;oY5r^>>lRIX0UUcekDpp zGQ~Y5*$&kyx8Kxy>u)r0E9~>&zfmyO{=u+g$xCg2dW?PxKlq4EbtjN<RJW1Ma`Qiz z(0CX6L{V6N=r38W4wyAB77TWwwT)e$Ny19C3h4;A7%vUcfYCy@XUqEji8=Srz-T3g za?$X7tR^bX3-fttxtxH0mSHls5RS*|F%|+|w=8~hQt#frqCK|Sy66|dk0EG+Qt5ln zZ_1phQu<W~Gh%z#hvMf=ncoSq>RZrRBw%&ncV*mHcK!b*G<FpNRq=x1eg6$-PRWPu zm;QZ`B8pw10j!!u`iG)+aCEnKd`Sk|OLBhM)Clz$?9|ZQv5)VcL;?k6lE7)|c9rFV zwcdpwY{E)?L(<?%2@Jt2Kv4ecL{f+T5qBSQTA~<kwR-M0I<=5r#@7EE>ond2LJsDK zJ7IA}%muqeIOoFl6gJiQbAlI;G3-B*M+~D1s>{s`x1?kg4q^*Sf>Ptn|AN9p4#^5i z%SH^MKa25*AdUkJ@L}KB9yvW)smZI*h%C*%3B^3(6LK~L`2A909WY=3yY?A99CBd* zf8q`a_6jG7@O4*TnsN+(p@rMXGX2JmCa^<xiq*R323i!zZ7T$OJl5R~@|~;nClG<e zs^(!nkz4_CK_1_kdx;EpIS6Z2?4|W;SLf3hAViR104z$i>|TuF+EX{4x}`2T6-%@+ zs&0=$Fy6qa5i7<IIW}~a6(JR&T{KeWXZK1TG<wP2SQ5_ie_C_RIE_;+=L{DdKhe%a z`hZKR^2hubFi>GeP<ilfJJX8UEy5g-hxceN<*3mPPDk$)pVXaX(JSDnILYmRGR7R~ z1Lo6UHZ%@=q(vl!Cp486;a#;dB?vmDVE*?z<Vvn_4B$#b&~l(tlUylbkP&zUxg<c^ zEIHm7G|q5NK>tGCkk!sa;|lySFR?liQB<h@Gh9{{^=^!NA|6Sq03Es^hQj-BR9^qc z&nMT5aoizw9&0Eo-PV*e`dJfFtXGT)YL5BD3%=FprWpOJITd&d${I<3`BV%|*MmjV zK~4`Rm`AP7jPrl?#Fl)9Nx{jy^9X&;b-NKDn;RNX;YQVFF4BuepAm?S7>LjIXz+Wt zEvh$UbvFfm^4J)6%TBb{UR1rqBKeQsUa*kMXe0Ed8rq~J+{bqTEgPaGn~WU-|11pR zbb<jZU-cuBg)mz*!II^KB^^V<@OAV)yJxFovsg#y{ySyN?$#Er7WcSm#V6tquD+|b zX~kz`@%rJlLK$xaPe-)z#DX_g7Y)}w4imq~(ht}@dh({e>UUHdAZ$?+7Z??Sn*s=r zTblP=C!(U@kHV4bK2#oK&~yRH%53=n!f5{x{~UJ(-FnnXR7bd$UHrQE7Ir6$fnxr+ z+k59$#)NnN&+2u&8OE1{UT?5!<Z8;8KikKx>>3hC?!@!Lf*gN4kTj0`vaBZHfMlHi zp(yC+#O6`aNo1^cQeOEtQ*RZk!vs%<-A8V)!+g3C6@NHOCifzCdn7oDJ}3sn173&x z`Q1YC{A$GZbikX?s>u5OdhwvikFm1w7n9vqoK?VL@P}HM2zk#0Rw~+5vBL7b$EOL{ zPJC7~o=t2zRe_!ZVu{NW#;4^U^_R~okqr-`<}wG2gYy!-CY#avWdU_%C2+X4LsFBF zz}p>NbGp%Z7K4Y)vl^tCUBt)*$uf~O7^6Uh6Qk{BVBL@}V^kyBePm@>VS)hiTFcGI zYL90YZ~k~}#<L!sKv%~fbW#~Z5{-3KDoi`KQ6NQye(e&!HqGyaurAeF$I<bJg*_b7 z4r_8=yY4l2m<HvUJJOYuAI~=$2zwlNJX#%%?M-Y+upK865*qEVEr$Yz%z7YN^4#73 zs6T|84e{GMDB59h7Wzk=lXF2ufz*(t7g(h%;m(w-nFZPnJPL3W5W>eb^WMB}w69D0 zR>??0OY~EyndPQYjojcM{U96I_y^8<FZ`&2lZhTFbaLzKvVA{e_8eP=6P5g=CM)1h zwI2&L1+_t>%Fh;lE|MHuECSN{=>2AkG@vRbr<ZFq0<Wwxx~Ioaw30y6QEg0n3qHEs z<O$&F9{7L4+*G_h-u;9BZ2;6c6SrbKKw1OvQKD4@=^RWHF!)6i3K{{V8-u}sThO`` z3kouvpGt8KI{r!6H5&VRh6Rp$j8^Ay8KfqG4K;S}zjJ5^%F~$tT?Pq>6Fv<@i-h?T zOi4W=I3~xVfk}TR<RX6oK>-~%c)#^+X#|LeC#Yoz5f74z2e6OGLm&dz*ZDk2K!{)% z=_V$g(*#b9#9ZPmaoG?;hzL!@7E*+*L|X-_MPjdqyn<whG5`lPye%4Ow()E(p@~kw z_NWKilPp0R5c`Dr)CfKm)%=~1Id8*rx>yok1H)_!aXo?W`Z)i0n=cyj$|~-HcB&kS zs>`0P>87{Ap%emeEXKi&{PXyMY|qlth7$=9D7aaaj@+ZWO@=Vc%Gaf?RIm>O6TI%y zJ4m~*|1bh8T1>6w{i!V=-CdykKiX{qFBLPJAM|mcJ4_;yIB51!$daI%K1W^RNE^dk zV!5h&rLmU1F1tg+`28!0?kA!J%|_i0m`6v}D_~%SuEF>f9Ba|=P1Cw++F~>J#ndsy z{vo!m7_f<+zbkouLTPOtq#zb)<cODb!N4J!lT@=sk@l~F)yO9|Cwk4xjDj&tD%@+t zmd<^U>-)FMvQwhV1+R7=Z5*smj(5Ap*8jESyW-$vHzvkd>ctFGK34Ab>~a{BkG*6R zBup!(y3lRAtZL^p>%IRQQ!qAP>aiTYO8MmYh9X|rrUk%QVkJmH@;*S<iyL1q9{nR$ zb?>8IZ9f%gKGOmh@jB(Q(NFTjzO?-T91OIP(5VlK*U|0U+4zH#QQUO+5u2^cX#$4e zVd>u$`QbS>DSD@hX6B~FDWH9~q~#sGH${27^>aLlZEA+FPQcnss`}yRrd`GC%NY1A z!HM8w6zlGN#%Af!@Ga%CF7|7ty4+r|D162Hd&tucpu_zOgX8|e`M0$n8|dV>+3GFA zNy$rePWiN0G^Nuybh-2N0Vz+%2Bky`i*~xdG3U7FS$JX)JYA{;{E^Xl7XKigzbHt$ zG9*Bwa5^9rcTuZ;+QvGD@=$8HN6z39^2S=zLv^f9ELZgIs>>q~Y{$Go6QDorT-%1z z_*de2n2i)%1h#r@#t=0MK_nh)KYv5kFtFYsazim(F}&<1gZyH@hD}yAwgHr>urD4a zyeNEPZ;B;17@ko()FNemnt9+y?K_(d)yVb{ZK0gl5bShNEcs5@r<Mp@w!O3CHctao z8WUu6xY9;2qem$&Hkvez|J5fT=NZ*(<{FCuQd0*Et_=F?(5^(Qf#5p`NA$ksDN(y+ zF!ILzG*8DYY@b7@1-0zr?#7gj=9m3%F`@;13}{YCA|-pCiBY)<Vl4pQ6L5W`q*K!| z)EnFJfOl%BXPqf%$beos+!?cEg?XGdG85eGLGpL>t<WQS!<E<@32Pt7sn{3R5Wf}> zf(I%gLHIk=V6Yjd3P9|l#o#VL$|Ag~c#O#lSpVb0dXT9=0D}O7UQu9+22{8#2c!^9 zqZhfOB$bIzB!rT|+up~9K7eQXdFnw%J)>S?pQk_g=4R0Sx1`0@d+4x7tezjLCB&fS z`iXt<pkM&ZduGLQxM8*a#IYf!Z;+I8S`&jz9m2U|M*@P|=o9O~AR~@zrM$%RuCkMc zZ5jlvXa9-N5{K`*2Yz9Hp;kGUmqUVtj|JB*@#g-ko*hWO>}BGMj3uiYI^+NTo85u$ z5RXn5_pc8(X3SeYdQ24Am#>PbS3aQ1vF=;#-@#&->*+aRXY>+iaP~oo+{9{Z+Oh6H zNr`~N;22?n{$i5C026wRAT-|nAo1NdT*BJ%#p@#s)e#D&y}w_$sG13%Z5k{`!EUpA zzwio#B`Ebtq0Z5tO-)QmFDubHvSh}iD`7q+5C}n9R0d8P>sSArUM4n6Nw@>=ch}V@ z#9$<llyTG?>W8(oAlMXkfC%Y|jy#ys2;eCON9HaTfu;&%+x{%Fp6FRtELu?MTk&T{ z59^n+#$FW@u~2+uwOfb!H&}5;{yVQtIG1}I)%D%c-$z02Q9QIqj;xr5EXr*v;K1F{ zxmT8*IzB4)fhNbFsSKJ@91D`L4!4g`CoVLXFYCJ}qVsK{=)#H!+zrN_ZfSF?V(%Tx zeERP6p}d)1b$iftD@pKSw*W+4Tw;sM)lkON%eRb+dk#S$dem_mMaKf=11#H$px4zJ zV4j5FRDY*pF~+ZdlJ)k_;UqcWMl9J~{m;sLI=Alr@u|bdt_=$n1XFdPhaWk$^ya$- zYrJ?Y)01{<=*(jnD0SbyG){PvvAn|T&_l}Lso3*n)r0uhSWKZHc!Fv7paV0?KHg4} z_hNX_l#Rnd@OZ+}G7=8Ao(XkT-P$0$@Gr|cEiSdMAzUsdk%f-aq@c$t$&e~PiEuF7 zzS6Y5{43=bt>FfJ<vUY;u)_VXk@8iCTI0o-m+6S7bw43$XrF+|e!1;4uq8m&7CAWX z(JuT9ZoO`hzGU9pjM<`z7hy+)G~4Rh-5OmX6Emq{q6C0v>^XltvQal~lMW_^!A;^l z4Eq}HZFgS7?fZvmX!x}u9tkmE1mA_mi#Se!ycHxE3=oa^y9>YJ6<v*)1nMK8sR%B? z_`nHv<&F02^|h(T)Bc^q;0br7O>-w@nVq@-P3R@?AK38-bLx^3?Y}nw3uhRz*Tk4d zMQL2o7-hVn1bZmh?HpejCUPfod@%n$QM}EDCqF<MKWw4&kOns608~e{S=>*!l6AnC zK`fldqw*C$a#b0MlKj0l5#z|TV34Y^Gu8x|qvwp5{vD+JnCpp~*`<EQ>qEyIXjIDg zmcUc`wsf5;G8$Hj%`E99HaHD_G1+xVfQ*xcf<{pj8d<H4cLF<iKREfZx<%x&lCX3z zRS3`yhO{882=-{BTZIPu^e5na;3(WX9a!!LqW_**G|)rHw*r}Tq-ziyAtfc5He?~= z&(G*UK8`XRoou8$9mJymmkpK&o`a(ZZqlH(^s!M&LW9FZmuO5(Y#cIWto>wwT0puK zXEb4Xq3JS*u8Jp?BUOFqjlq=(H=qS<1JH&Z8Apkj@UJ!>jT+#?<ja_|k+5Ku97(5U z&94RFlV6uk4!0JRoZ)?dmT;Nb2@5(Q^ydR;Y_ysbo`Wgo_fgEd&3OYxrKKgp+JeHU z$<ri(Yhk%*47~ri*MDwfj(teiU0w(=60ei@_quQD+nV?3&yJPzBDMX*M!4Ycev_!l zVu$Wk4GF@>H+)~LrGFJ!Nn$ylOlJY+G1KrgL@NBIT#k@=J+e}rgi%J0nH{!CFI2hj z!0W?dNLAp8)!KKh4PO`X9c+qsyOMo+T}TFB5RBkVk8wz;bAxYQvcO@%;wnh{Y^rGj zFoB4NL*^!{&1bs=>@f!q8!}stGL5f}KQCFX{vza5pEXA5Y0?6J4$!Vs_e)~`D5R?S z)>oiYr16L|0z=+#Km9j5xyq$7{G)Pt7iI(c#=$8Fs%fjrrt;Y#r)Dha7bRzbLck)2 z(45;68bhstGl~dbkZp!DNQ!}CXU0tPs4Cqp5<Foh)AZ2SJvJdFsvDk2^Dko!^rzO` zVGJ||Q)WsF0M&QpB_~b!rZV;X+T7e-ITZObJRS?=t0Q?k@*-&~nyw)M%@;sYbTUlz zY;n&qQ0A%&?Hc#;Sjq|uJ3OAYpr=PG<`y2Kw2Slt;2UPP1?bUG|DYXxVFt&a`{b3F zfH|~9*t0|Fwr^h!hBANnA;U0R&5fgnZzp3{%++dcc6v|xq-W2?k*kvt8`qlGT}26r zUpwGrOADCxH;VN*9=dI0$HRwX*I@qzv*J*p2rn1el6z=mSO3ATR<j{$#P*{9u|N-f zlha-ElAg8^(F!66OE{0Bu)wfW@{V%_3-Azyc#JOYsWBtM!z~-QgT@<P(l8MlIe@&? z&__EKoB_(8aOrqn{$lF1Cp~;ogQpDl>IhG!$SSM{)e%q2(`8jUQQuGb=CO?;4Wfc+ z7b##5PnzBxkv_WZ;dFyhn0yk;3Gh?jma(ZpZ?w9(W<W7t3k(mJG%{e}G<j0(4K>ch z{r4X0I&TCI4Ey-%{WJr_;{iee$h!|2mEk&tBQd;Z7LUD!>U-o2`ep;FZGV&`Vx*DY zhfbC=(Ov2VgEn{h&Y+mgt>)B2uima^zWrRTs8UV?Y5`DG<JSm?0YH|*Tj{_5F}uf& z*>jv=zQZOTvsI=8L^F&1ct7p>hPQVXMO}04?XlaOHoO>A0=8l~9|ji)9m*igwWCDp zLEeqg+^w+RhM@_*0h9P&mUcH)Mf{AO72+0|n~b3~Yb5+Z;<lWHP=KC!=<#`RvhY!y z7tSlQ^6vLJK9^#h0s1VX)?DJ31zy|arHHJqfHk)yN=%xXLz2u$sPz%&?MR1=5Q7Oc zuLyFv`TF^jrT3B10Wc%a*9s6AI-e*X(68zzDPJ#WO39$xA~hi8b9`XU*FkH1iVlN8 zg$7Qny8GvYuaifg0(?vCYaMjN$3WrIknU5Yd#HMXWiu02)h`&jH5dkflkfqE`e{ca zRZg<8UZL93k+fFE{Rr|HRfX~tHd+xd1#NFV2qS->i{PyF-~I`U0_hZHs{@rJ()qU* ztR74&O&`S@!L4wC2a7S(_u(I2&j4_gZx`H4m9NFsx*(CLd5usmoUvdJ?f(UKvk1|( z)4leB>sdRu)J8uqYO;YyzW`vb$&+OSzq3IytnjXw4Ej#No|eSF!8ORlikO?enZ5)< zk6i6|t7~ZAM!$;38Tlv6y-q7DW_;A$jwj`fsG^_S$BH!xJ7nJShNKdeD$v||SFs&c zNDjH|G!c#%Jf8`0Dbe=8m5;d_c*9l_Z=MJpvZ51T1C_$`7BLRVMo_%5n9!G*0UW{~ zbYkHjT$sciieT8-Kkq)kM}LBdO|iE@_M!~+JrPRlc$Y6=*s974kF?QV9Gw-ToHii- z2RNW(z8QMH^#ZgvdDRr+DR@0-X9zY<yc;eF?>dp?kRTR@n;vUDxmlbnqK_hqSE1Dv zBe}nuic{${MYNkz*HlrEM5<j(>QcK}hm_qLb#MAI<MFp2Uho3b#_@hiZocV7*!G}9 zfKGy<<_Yo3v?%=45xFpohe5x_2!ype_5$qz6uf6^WW5uBb9#w3bBFmT@W{9D)qMZy zzW5_dr+*KSZ=v)s;at22cmfHpS^64XCcLP(xiMOtaJ---fgWf+MC4h`7k~)a{s7-C zuRx~lCW;f29)H9Z)2Q~=IToh&NA>1c(vTp7yV~Cm6*2d(?Y$EpFZ)Np8G-xJ;A+^X zyt1FV8FnZFE(3{<J#!{j+P7qfvOM)BmO(9m%nY?ins25%6rGW+-5n^%`Qe6B0U1og zb4sB%%o#ePko2_+=Z7;weBTx3Me0Sq@IYKOTaSS%s(|c`yrK7TJ4NL_<<tnpWB`iW ziH3w$y1sr>cvv!O!~#CfP$L?=*hn2Z&>#F*y(%94FjD!tn+*BCc#EX>_U0$20w-29 zpKt2~g_b!9>#I=q=;MjqO=at)ec=YY(+a5aU}X6uukl#Urbf5I+norK;X@BT4tOkZ z#p2_lc212+TbJzhF5J??Cm(Yo7Q-nJVI|2h{G9Tb>iSrR0n;WW@jtDEqi;OoBmhxP zO%;heJ}S(c)u;1A)&aH;h8;C92&>GkFKJkR(IjsLc}F-H^tE4rFk(ftXB_5C@#+io z5;9eUZ*dLtgpu)pmzyr(MVuu@ExAG%2YA-+tl8xF>&FD%i<;^)`Q98>C7YY}mAh-d zCW>7cocSroobGKKgOrBwWjV<CvQp=CB~3<EBWohD9oeoih*OFOcx<WBNRA?n6F%T( z^WdQXico1H47!r)GLDj=tyR&B{opoAFY#=+XZsD-U<<~qum0^vk=iB-PyZ(b2OMP; zF;88&qSryKphzgv=iHwPp!tVHfNbIvx-&{`qJx8n$Fh+s0z+owM&H6ZJHv*`(z_v1 z!zcmS)0)0#&pjkrOD)2OG6zZB40XEOz4Kh~EfD^D4;34&B&;$`pcqUsAaNjA-&T)| zd1!z=O5d)FM92pA=pNYez@f<z!xaQDLPbb9ql1PE(di};S`M6)NZ{0Bbl(!rU?$IN zN<a7(@Xf1BLr$}MHN?n(9w8UTqeVgk+sg|u3`SUV!ko;VGEO)q5F_kB#Y~(bcwKO$ zoaGsY&|1qTA-NIUAK2uf+xCE8o1iUU9W@YzIy)U=tBh4D2^=jkd$79+ohocoS1tA% zbPNHKXg&_Iuc}V64uTC`0L4MGHW&1ANQ{dJo{!PQRM?oPPsQW1h!Bd9QMbT47QP{r zouQ`iT{HbbZ_zX#$vJnxB{yUzyC|fju@1egh077ws~|Gw4&LSj1L<ykY~>r<V~eB6 zGjI3Q5u;ayiegCwbQ@GM@~SQ9xyQQv(aexlur|PIh;Tsr8;gC)q>u3F&FmH2i7WAT zHp}`vO69tU{p(eSv1f4v08XNpO#RfiTed&CimGl9Y7AIH#%qyKaP(y4ZRC5xsH!$E z(Po)aw;|NIvwvYff8CJL^knkQE?Hmlz`RSYQ;qxY1<Hn`1o>|s5ZJ%}e(L4B+5^f5 z;~CKANR5U~4|RDzZr}W9@e5m@9z=K}m~CrJ6X`Kpr*iTJmv=2ZfR%eO8u0>0%#1}* zU`Jd2Ki6$MX0QQaaIdx`*z?<sG)j10j85F7&G-~$^lyde#xJjDZgKl)fGD*U<1alz zlGLWEuK<bj2Q-;PJVDV0V>%i4yRSsPUlyQ3s>%h@^KjDwTKT95onwows1xyS)Lg}p zfbUFiM&~+7`AXa5>I{!6ITRaRWGykIsw1I3UHqluuxu7Z*kh}$q1*dE4DR|W#X2`9 zm_}@HApy#}m7ABqn_<y-mll;v?msa&GB%12k>tc}fTuQMl$;>rRjgdr+}1b>_Qc@r z!)NyiopSF{n92oHLCJkC{~m1=(}vL=CySH)#-*X<GUa6_3gT&eq1I};Xd>W&U_NqP zMlIGH!2>bYW);D-N!Y-m4*JJQ`MPzJVf+?p3E1Hp>(d9lla8uPw%Jy0JEHY&M)0nP zKG^YKyTNY7@Nl7QI6=M^W`rf(v1LE)<F#<XNdZ<2zKg;snfDYw>IVl;0-Jk42aVK9 zS<N7Rx7H?Hb1Ya;tXd>7(jplVYz?aqHm>3i24nWFUvp`ioMd6cCg@!wIm4i|5*Ndu zu=>E-Q4xTDbgPtj>G%u+uOYMr-pv*s1$=-T!;UFtm!Q%?+KKHD@9*N=y7MQdo&k1y zO-6<*(>fcmR*}OnC+K1CZI^h&Ah7c?VjmjpSyeBU6A+}{pZINePsdz_<u(!jp^zj= zK_T)Da$(A`?2MWt2ZV4~K{q2Q9_}ZIxN-(W5D1H~FqNwFL3t7)v!#qS%Ps69>%fg8 zja^^-w?626&UUq1@UKJ_D~*+_hf0775U8-DBqP{}G+D0)-AYU`IC#{D5?FVyTri}w zeiEHi*!pCJ2Oh(I&Ov@;C8di8ZtrKeS6yR+R-R)%xEhQMILQsS1RhVSHOg>al!Q!0 z8@U(DBsusEiNL7yphS;C3rO>%dT-krK0(_C8W$J#>f6;rX$mkm@GAb(5?bVY3z4^p z(R5LDJ4m5xpmo8iV%leqhXo<|k65+-yVDC|L5#%lJuq|qroLzx(?}5pk(lxdlkv+q zgIu;Fuf%Erw{oAoiQ~QOu*MsO&0aja&UiQ%irHob$@r=3$oLwPnhX9MT3pAkEy64D zIe6VF_9bE@1F0>ZOjgGM1(U+}WbJUcQzQWkAN(w=pC*HEH4P!~?*JY()xYLGLROsO zpn#AXnd?DSP3!HzFUc*UawqWLr)&k^ymlJPP_;he$!Ua-RKI_PP-771=N+;ki-S<8 zLMnisQJmw3$aiqLv><4ki;G0C0sn)B6D}9YQYI+2SU}Bi;0iyo>tUw}PS@~$qXXrN zk91jEVXXCrb;yaO=clT|-^k_mHQ0}ec?N5vzPrc!`whFjovE$>p$C^m?@NS|?|eYD znhJzy@lpPLhS_}FI3?EYm&d*n$?<kdc$VPMg4L-ccj}*=^mJ(t*vP!=mrTx>n9o34 zL!K|0a1ifwe96pef%DwQ&_pI8tOoB&`*-PwM_^>$X#8m;THdWzaEXF23CtW<{?vQ@ z3vU34?U=1&cA?J|#Jo#@TrqvmY%MJsGwI=_xx~Ob4sxw2eAM>nPYM0XESU#5Zrgwh zL|zGru3=1^*YELQcAdd<!KUm=0bW$|?Y#|=jf8}aVQPDzYJEdSAw_G5Le~RlSutW= zU2TeklRB8eKJ@F80GTY2H%FSTfE8EZtckQromUG7MqGVt)`X2#17ixK3~wSq(52Pt zaMA}wo^#vJiG+Zfd3J9q^pkGm315#H=$P}L*3a(2Xt8Pk>c+X@P!VU%S59V6ug(9; z(TTCE;8pLS7hZ+Gi^s7HW@g)T08HNUjHXVHuG}#db4L`M<RPMiN{yF&J@P-TQ8*pI z;iJ^ypajNK%)J2yPH!^a`p}DwiU``@!#o_^RdN0l`%2);fuOAUQa(6y2&=l_9Uaa| z?Kg1q>2ZF@WEQlnlCKijbs+I{riA=iv{<gw<voy=5yEs941dE5JH(1-fHC(v@78d( zcfm~zF;Gl<+%Ng#yy1C5;|vR}L<;L%Fq%AhswE=4I)jZfLwgv<I61#v)Bz#Yc1rar zOg0}X<$kWTZZ4x{uzlc|<O6DSEf)_aHKv+mu!%MC?!YWD{g#HJSM$PdM%FXqcFbOm zt0oqqu-!pM*}T+3xGOQ{f=*XjHHr!Ur?3Vg=I>~Ou=H2HKLwpFz`IoKXzpA}<+uOh zk&}t_I64JzDsi-bWCIbxrSB~+=_Zr$J@H4DV9sn^%8zg?jIIf@IKk3q8sfk9|14An z#?a8SO?<>UW;BfJ%#CTSq{O+M%NBeKx-3jrrS1{?eruar$~8Z9b}~E^m2-}AyPVp@ zkfwrkB}<=z2+j?cBf-l;=PIrx_DP4i!l5oii8lwe5FF(z3ImSa+Jys9IF7--DD~t} zyOTCHs2+Q$S71>tR38A!9I1ZCw_ux{{SsTI|F(e#5w(#7`g$PI_d*7TU?N{l0%Keg zx1V0aW1+avIv}S3f8$E5$ZTOfpiURjol5}o@TZF~FotUsdQFJ%FtSG=asp;cR29H( zAUP-0z%x4Q>onaC7-8ZEn6TgZca}j-q^5~OO>eC0ARV9VjGt$(h9e(#nA87wcEaH% zoKA^YgWEo+CN%V9@;%sThCK>hGyot}k|Ka1y+<573T`TU&?v7H2<OGo@OpRgKq~AB z%Oss+vTf(|`7WHk7Q)>HrQ7-e0`}1fzHoXZ9(hhnnqWQ>V=#3{S;Up9RjnIS+oo6S z!yuO`o^||@Q_CJ3Gu|EI;_Sh|J93HFgP!k8sq+&SG`GGC*Aw{=u1Xh<NIc5in9(6V z_#Y>ZUB6C|zX|Ee%Vr!^3{RyV2W4Df3IBu`x%b~8O7Vpi=HOw#5z%K?)C-y_cF=4S zXBoQe;$h@|;<&?kZ-pO;-U@ZveD0y#fhZ62-Q~*Zm<CpW#Fo$xP!bxH!KzhsKB+uj zrwIB@bfhuvs`{Y)-pEi9KfKYSY;<E<9B!5zOK89#T@E=O(=S|BXg>8FooT4PsTX^4 zB_o(lA!~rE$}KBV*rVR`CpAT@eS=M}?&PJ<Xu9DtzTg5aXPaW-L_mZceU=ZNgus3P ze)DCVT;j}F%F_|xlmpv*B01*r$kLV&8-o{2rJoAw`|g%_eh_6sbnyg^%wJ)^2u>^) z(mM<i$aTHaG%f0yI~MiY{W*HD97ZROeuz6;FIQ^cNKGLYg+%nf^>D-B#?ObkZZrH) zBmSK~@;oNFdg4K&iiuQ5I`ib`P`jGlW@(oHX?^HN-7Yu{H|(*M?hCh#?yZFNp!Zoo zbq~}^qz5JXr=-u}geAF(;1?g%W5pGw_m7HvjpC><&)IwKw*CFGa|;dy^m5OyuTB-I zQV2;<or~lV=g#;-?jjD^8)}w5=M%o)#KnQN1{?!uV<dTYg&5Jn{t`bpm^O_?5LEA& zEB%Ja@(r3u_fP?A%tt!Z71VObgQfQe8&VTeT9}@zPkzY&&k_Yz;9pcm0El*O`<A`> zHvMXC)}J(f6)5&bY6f~#CU&ql!XoEZ=>Oyp1ojTe+mTBUpu8&P7)-K&0^AO?|L&_f zuxf&9SZq0?g1qiE*jXvza%s9(R4uwY=p~h9wphi^?2E)CZugtab}I__H(0nlKH)K2 zW4r%EMk)bIo1znSr@ILU?FZPb1j<DBu3jDm>5V{KJnkDNNv+n>Ug||+^QJ>xL(q6f zEH>;9#>8`snZ|KF-2L^v$n=719wI#o22ph8?6_g~1lQChaCSdDUjmLFbV@lX?wrv_ z1is^z=6?Q<Q-=9^htp-Ln1x(T+7^Q;P%OepB>u=g9*24!F5K`hy>p#wVTpJIN{_nD zCGb#u&;ENyk(t1h9a$MH5&^}(N9P3OqajP<k`h3v5O@|dIIgm&fR+0$5AH!LT*v@c zK4rR8f4`lRofJ;@xD&bQopRaGB28~fY}bFYIeSvA-qNLkGYtKj&vg`BYI<{Xl4G?} zV235kHcMyIBe7d7QGmyM_f%0=bd_Z1TzX02nwubR%+$QU5}owS|A>L3S2?NuyCBI( zhIAyw7LiJs4-zFbocnaZ!lnpeJQPcm4rWEGczxD539KR(Fhbzc_5jDvIpVyC(KM0Z zFy7d=cp5?(&=S!bh;^(vO2xff)3EZmrI}VS=U<`0uw`%pMZ850HXM1kzZfHYQsTht zLJ&5JGxRpjJ?xTRxAL^K(OYK37=I?od0|Gcno>m9KC@XkMW(h{ntrwQ;@F`)RK!)e z3t08_%CGAA>zW`M0_6q8%#0N5{mhdV^oza>gqhv+Cpl!RAmUEI(jn*FaPiVr3LTVj zcpz@z-!H)ES_DBmC1gmTZ9UI(x8ss$WxCR>W$jqjK{F%nT2juK+Lixu(d1}b@+tQ# zQLh=15JWII9)`+2qrOU7n^J}X*%zf}Zq&Q9e=_JhXcJ3?rFUUjHdH3yY*x(-CK<RN z?s1C!TB8){O<4k#W2^0L420a|NQ<^68qlft7|Iu{gV~xGjXu0@>E|HPtJ-biXo2$q zRw>45T-o!uZ39NJ+mY#YqT5lU%~VvIxUL2>Rcq}MM|cL(V%9Fv0yv3A6b8k@muJt` zb4&I`s%mCG!W%;Vp$~7Kgf%eC$E<URkI&r0>q@FkNj&r50@`~!mbg!TS_7ET-gVv& z)TGIqefDGw>g=U_*xU#qOefQo7or>j!$Q#um7?AIS-tzI!YV;lBfUmzobtPHInk&p zm(3hUt8%njQF{<@5-PD+{jlkg+KFo;!YApgI=CN1WuS7o&t`NGo*k}4ZYpa*&d_+T z#i&qViJT3&z^xby{?`Ys>lI%Z%@m-qVV2X@m*1uyf>5qi%B^IyO}dUSUT$c&XAG`g zihd|XR*wjp3*e}{cf_2pv>r8OD#Fik^<N`oqhIw7%W=2q;sxJ`l3hD&Gu1;}<RlIG zLE<^ER;$JwJ%6n7&g_E*4hLb(K%BA~-mA@2;z)>%fcYJa;eR=Gbwv2hsQM;tMd9!G zX-n*YM5OgoE?vt8igH4&<5`1L-haf2?|MKb&O=o}Uh{1SW<e{JPz2(+ef__+(k&&- z|4oa6;SCPxpwOrHZu6fO4|qWd4aO91U7E5-U}-u=lGPZ`cU%nFnw<H#W0)oosSj3= z(yBgY)cj)Eyo`{aX5KASum&YOb}{X=$-C*RKTiK;xtf}Sq#@|2W=%KS2Sc4!W8w<T zgl8Z5nx~neWcKIy4?m2mhmz$cACIvNXMc>a!5<Iwy<@B&@jF&x!WtVpcvC>Kguv=O z+Sq$@wc8yvCM$t1Ac&nZzPl*J1}0XqQ@v-RYgWsc_D^1b9%5W<3&22i|B}W6YnfJJ z3OKkAv?=}6+~*7nbOT70c7;FO>P-eJASQN$b(JwEcVw&1U=<<|F?OQ&AA5IJXYhbT zlUruxaw{9BZ%7sp1Z4Qq`*14LFlP)jkO!D*;vJ`Nefp-`J5L0W{R7-!{e67yYdMH` z6O2;cHQtvjGS+#t$=~{e?O2LpP!-XICxOSY65elW223b0dF?l&nG(X@V#XOM0<BHY zU=6i`|GeD?Ap?QKfdv2;O<+V8e8n0I!A=(`DTbOFFcG|I>0Ob;%tjym5^!9NwNS({ zi7S8oypBW`12oD-Fdc>oMm}`7I3CEr0}vfiPZc-PfWcaEV=?uhg|+P?M8Lfwb@o0I z@b7fgqELirlDO!sHK{-#qmx7D06EX%F~Wzfp(hflhZq<+aXrRVM`$N7Y!t<`Ma~p= z@>EV51VJ65eWBI#nTK!1)1SDaxx<82Mz>a&4_(GOrneM!0I#{Ff``nv4CQ5n^a_h1 zE-EiBHaKI<>Kzn{Uc6wKMj;&lE&BAx(1KMXIccD;;Lsjy-Qv(r-#YP-Yi5nX;hb<U zJ}%`o-i121ETGdpJJ@4UL5BqlYI|4|l>(O^(_2wEfZ~qc=!p|%3}$%(mxT&Tkq_mG zu|$YKfa)mDmDzsv(aia$QPuO#1^Ir-u(1PNO9=X;uE;wVWG4}*IjCvjT}-y~aJ7UN z0#{^Uz1h6t-41VK&*vsZiSI^`ZIl-4xZMB7EssYl4*(Be$iv796*}>P;=Hz_E%OHg zJHFgP<s-Ge9n$}#RsGrMj`2UDxb&sh*op^KknkrOO2ogH=n0ofD%9<z0xoqjva#sZ zoXTW=t@=a3Q-%eEc|(k4<)8H0ENt*Bh21gWu~V3XQRZTgF3fwJF^UQcj6c7^FIKO3 zQSI6J@g^A5^thsI$Izo`xry+6mtz0<cgrQP>tadq%josAjaX-&v{{6+;|=FzWHO4O zvFG>3R_3jLds~I4E9(HXD^%Y={8Xj66)tq5Z$1EeDdZH0eep-Uj6rxKM}0+SR=Gu4 zQNu6DIuMSaBg);&Zb>S~`!VDcezDo~)we4moz_eVxKjf5ebi)bl;2O3*Jh(U>Nm|B zJtAW#JqIT?|D~H*6eTu{WK?4Nfk&#muP<3ozKto1b-ns}QV0E~yvd7)|4OQrH`am4 zjMON&TZts0Ea|Nq=n=|%6bWc@o3&XoxM&h$)Zsw-KW&S8?4`%8yAm4?!6bPYa`Is$ ze7^2%sDA;qcf)+cbDBTN=uK0t&kcS&g5=^9M*8+if*ZglRF`id=>m|i==6X7rl-f* zc%HCS7I%S^NA?ac54Ugxub-pYG-8z^`ylqT3zT1IUj&^X>^)4WAbsp1#@WfBoGSx9 z8%DeEkp7C{FIQN<zRBRwgk{s1J*Cdg-W>NOUVs>^0p}bp7hDHo!P1=)@Z(DU+LF(9 zb+i+1I(eTA4*M#Xq#2q&ysJ+*L^}&p3xK|FKvy&w=VQc&3_;Kwl$h+?2MR^p#~5d# zC;*9FE=Y@l;-$xtZUB)DUSrH*hhcOBV!P9z5pCC%{To@dsY}-`QUs_}B^_<u`a|GE z5ri5VqXAXB?=!y%e!KD_Ad9+O_FmsFXSVV?N!eJMyK8&ci|WA5slF<7c2yE0?iij7 zgh71|zVFZNs7dh+TbZUT=s-lv_^2EjH%!88{>~xx&+6-*u%Ol0*zF?8t3(+3zq*`J znoge@{2o!k2y4RHm}iN(WkU?Jzdp^MzMYxU1hW_~<jurs9*~DyH0V&k7RW3fuIa6$ zTTMplni7VrA@5}e=QrZNMXF_1-T_tSKln2}=q%M{f4r%GAb)x>po3|tTZeXbpy<t2 z-gP_W6j-mw++Zr&%%H-Ah=c*W<UaXs+9=+9ge6wYOhLLgAKl3r49#%gC;9%JX4;wJ zJ7jobGvK1cAZJYjFivEjt0ReuX_5rKnV({^Q)+&4f%iBYQ^j&GbjfHu>x&q!jCMkw z@?_~MEbX&MWDKE&!l7u1s>ICG31fLAkWXp&{=nE?sWw^Lq4-3Bze|#}Zd$<12SzO> zgt>6^({Y3t2Gr31xz!{b-TjOnrIxb@h~5e|gS+;M<bbCF-wu?qDT1GesDz0UAN023 z^Uy=Vov-rl`V{%Ye2&cE6@PcD>Hk=|5~wDxt&0i;v=u?r*OtMSAOQtl(K=utP_ZFV zUI;S^(jpYmR)vBR1%g<|Y9b*((Px6ph=N$GiWF)ckimu-r6OvWQIIf(4Da8U{_Cyv zR$DTB`M!J4J!hYN_P+a#x`nyzmr1Gd%%3d}rmFXdM>ZOv+PzkqS+y$O^WIqSL!{yt z0?@r${c~HqN6|hb=G48rm>Gu^TWBp|ApU+NMznZ;D6>bHh26x4o*u*W`%wL_XJHPt z;0BX1TbE$0N9Ui0)BsUW2#Q&JpK{b%q`;Zxz|w|JSsgFKMPFsy$%CY_8~(bz05~VX zN%C@qEZu0jU4|yJ84%>>jy7z&9AOeHt&ta)fyrk2WB~L%I6H6Mwsrne_;2!tVNoJH z_RI#dyMR4>z>7IUT_p6jhT%4WX(1$cmqS=v+O{Z0I9A;`sHE25(~J@nR3f&$^xM4{ zRj}SewYC5ok?FdAA(Yi9_{VwQpyPsrx`OWxVU3hV&VGGW#XF6e%BQ``Y<S7u9Uk2& zXukvAJW!(BkRug37SEeac)wvPyRpiKao}6tuiM+fm5!=a-W~1?yN#WL*pn{~Py8~n z;?bjX7zvUi+zcTBv#YwImhkp<ZTs`zJNE4QOzg3ZDFC)WlT;pu7C!B_nU5j7I;)e9 z999wAcpoU}eVmt>yMBZY!O}?Qf0ywSR*k^D4UZk(3Y{rE$03JXYwEn)%zInF`<Ss# z#TWv}Y{V|c*y`7-PK+&Vcb_cQlaZnuls{$NlzR1}?t5}8ggO$Ar0QRbkMy6i{qhM# z_|Y70&KnvWUuqtsx-#=zxqe^B;sXU@JxWzGkonFmK|J<D@ajKHuKj-&iV^sbn>!vK z@8iA??qoVu&sLMf^l%6@{-FB8s}8GFzxS0<_pN4Y-;%NGAe>7$<F9TwC&JWITMeGo zz_Qkv;`>K3P8_KGS;<@p2MI<{>w9jj-<lHS_EbPK=$sFV{#egp=Q}aiFEm2>$us4+ zQp91B%AA=&ya*icktB1{Ef>`kG?#5y81kxch^;!c{R$1<oTy2(44dE_CiFc99VQ<P zIlJhCy#hUx(*s%hd+o6vMAvixvcz_Dg1HOuj~j&1P4NEzi)0Ng2!8J30%Vs*9vUKe zlw`c|5eH8g)+o==+c8H0sN!(Y?GwDi*TB`Nke(^4nL>G4i<3kw4ibIxUjr;lWP_L4 z`_Q3M_ip`^muYi!8S)x5?0t9MFfo^s1<SS*I7lp4IDoky&5ddmGEKl}A!5X$A~G7; z3rPTcVA@I;x`X&#3apr%)`28^fci6_1zBTQs(@9%d+$h3#vp8=3h~R|%hJI28-0sz z4gtDAz2#b<JQSEN*FsYjwA@-RhVBR?M(i7k=2u36=%29-rAEQr^{@bwe&DUbyyNrM zOH^D#J7hN)BR%rL_l)sY^I=tmSWk7Ass-P14%W7bD7eN7GdO5Dx=d*COhcMv<CCl1 z>HU=;t6F*r$S~|me(o*F6HrY-*B)57=aAvdcls;E+h%0PrxC-ijmyZl_;X&1gdZ(_ z04yHn*mBgB65PSj)&14S%$HfDK1dn3Jw0_JA)Rj53}gdyiL;SN%x70K1obUH5NAwM z#rN?fNL1w0E{YXXSA_a19z6roxrY$ya7+JYjd^Scxc6S&A&Im~0gU3{sQmN|?~f4R zirZ&Jhc#|Ll0yRLfVv1bc({Ht<oPbmCW_on2AY3_McY>{5WW9b<u(NPPA{fu$Z=W0 zS-2t!HPGuKUAcP4p)mEuTLb;)*JHjLn+#VJa69DJnllJ8O&~v%PcQ7H_4~F(v>nL3 zCjk=#GLjj=)eq=D|EO}hCDyaGkVsP-x+$Vsjs8r!zUs`n=XlKGlp5qo*LIek>YOai z>>s>M77lz+EuHsFn_D->e>L-n&R_Rzr4a5K766MCkwJ`8Z^J6uZCB#<%gM5e`%a@z z8GmQR$4wf%98+x&Pfyg?weXs(1Zq3bdhIg4(Cz%<zFFGqOeD4!7?D;O+30YTO`ejl zW<r2ZN4;Q@K`kKW=<9VPyxAlxdtZ`AACV<*h6p@GW6;&{vFzuNn=|wE=v-P#4X{|L z$0R5Wa>=9f{^}3(0L`?p#?R~e3frSd5qEp0VD~E9Ik_cXamfl+Q%{wI^z3&&`qBII zU1M!~Gw7Xu4oowt-Q`zKi#@y!%trX^FE3iRInY8(WaryDw!Au8+J!k|WgRC!=SKRe z8*%n-8i<cgM$<vw?m9BRG*dSdE-B*hC`Xg1!5a({AtuohBP79SV-Vk{IZKt;`=>h^ zh6I)Sc62kfQ?TylILQ)a<jyZJW=?QMFde0lA=Pt(yT#ahJ2}J)1bT6xXG^+Ej<5X> zmI#tMKiiQUIk~d8g!;VS@j7Og(4j>Y3aPlv?PbUukUKbRl+B@_SROPi55{LHhmO{o z;SVnugvd~I-+>Wjg&gLvm0DT!-5vPSN)(G7i$3fg^x~Nw>^R%o_jT)Ed?;1nsga5Y z0=Le2ni6-+R&1hk5q+e<Ub($()LwNb6Ve@6n6;dDN*_>aa8-dO(f<B3+y9gNQYl3f zB(hB(lRNfvcj7mZdOaBHsiT^a9Kx+bXL#~2ca7Sgy7Xhpe#y}AilEyNu%Izv)w8!Y z*7RBwVAZImq8;E!SU^oEFPvJmUw2ckbR~KU>YKk^kN6u@QOy>O!E8iOIi7h$H&bN} zUD&MD8014BVs*90IGb(Rd!iO(bHoo5-gt8spJ#{EOIc0Wqd=3$E?tW;b##=7fiCVj zz{k}$9)ebnxqVOt))wMbBRwP~yUBj(g#)Krv&ol&)4WGcgB3IMB<uL!*fPz3K`IA4 zsz*MYIc9gsD%13ZS(p$6I=hMkUw{*fjE?=%SAQ<%7Cgr$$;GI7_$Wj4;%Vcg{VmLc zdEnp;H2wb1Zt_U+fJS?x4lkF-@qCpG)s57d)rG&}`pDQQS;eLiA4e-w?RJet4;j4R z8pV$xD0|TAl9@y;0qPAC%>`s=#}C9S<idaD^4nxW$JPtb1VlfGNt-n@utOPwGuF={ z8LQnUZm!9c4(N(i^4)4<nqU%;m__z5&VqE_c#ArC@9pPf<|%-$p;6nP5zv7&YY1xu zHEu3wPCks63zo}4H$fy(uS>yA=%b&139(!A)3kdywwvDZqELiq>`EDX@W%KejrV-L zFi{hSg+z+zHN*Y-NMnV!uNWNt<;*rwG82YQWGS<7O9CRr;fH=P$U!3SZN2zD12KDq zoXsQ?AKHLh=5iui(1pQk7A3VOC&3KuP17^vF3k3O5|1RY$n!H1ry6d-me9I0W%O}O zM0yf+Pz+3{+(e7-uYv&+bg1dG72)$j?d@`5_J+}utTh4SHk+t?B!MZ_I1?dK;>B=v zMbEMr$z}3>ThQ@~AafGo`c-Sl(9jMxG$MvDP@V(k<~+^KbP0YH03@u+4z{dNRi|fB z6p3LuPH$sCxx~rb(jAB9sve%wi74m`J(n*(do~yMssHl4gZy0ZcA89$Ads?fAr(K+ zO*GF$RPH^XRrE?yUkG<|@s;=WvWPQ@AMab9al}If;RkV8dR4?oKPjmgAxBip)%lqF z{(7UWmC$KJVCr<Dn`G6js$!g0(cTgpXiL2B=>3;kQ3%YTn<SRfU-~M|moWEHaLLi& z1C6oYs+FOPf`I%~*(O*kS@1WGR=0mo;7ttI&Q3GhuEl%g*YNV$I$gObnh{()HxQD9 zzp$1&ebDjt6Fj96Xp>^826dmNt#G=Q7#}qX{z$*6Cx2*LAYzMu;FX!Hn+s)gprazv z^!xAPbRQWcJFa-RFVMN;+kIwv7+mS*k}g~z(6Z8#RbM3jb#e5;&Z6#m;iw1l-9^{a zW;;sa96$2Yy;n{mBpTI~H4hU%9bYMK))+WrkQ;q)Q~l_REtlvfa8bO9T;4LFY3$O} z*RT*u*!CbXXenp_P_;;pL=HLJW3VjF!0Wv@&oWP)dm)H{LwZR45r4-Sn};c_WCGju zCOX*)i+rCXOS(FEEm|{#Iyrj-<ijEO;e<(so@&t>vNL9Euru1u`pp}I7VBv=JVvR! zNzotFe5X$b1N7<q)P{Vfm2~UB&9@qRF4zD|Tuc~g3F+0rzh67L63d@ha!vA_q6|AC z_EE%cM%X&6S1~U?m1tJ^iGyOF#cxx;I0JD|l2#|)={BhC?RK@wgd_%6$PAV|ERu~Q zNY1rF@Bqe}Z~xx#!;jM4Li*=OUQq_yxMLUuI&C+R%_DPvA}d<=9FAJO1sOgTCy@HU z=+u&lxiR9H_E**u^qGiSf;zzveZIS`SRvPNY{0+<7Pv$^p`MjOvN)1eYr%VO0_4d= zi1WY#b^hO^RK3cy$^-zJi=77rH@q88p*1i*!SFXfP9{!T({^AjX#TTLhG2z0R1N6} zWkvBktFabUMObwFB$&Sh<M2u1CW0ngpfJPUm1T1Ww2+Eup1a`)f@|2^%yLPrxx~eY zt%Qv+lcF4Johys%)#2<uVxAL*jw~J@xQ;@}1{B;8F3Z<lXC<s3gg%sgeQE=9^>Fov zs!(x)jlm7}ZXP<EGWf(`5#$5+JC9x=;4$Aj_64`V9LTi$##x?P^GVvZ6m=;`9J3MH z|5%pr=+aReeT^l9Ha1#bahoXK948i1f0-{%{DRrznmz0v4R>ObDCov(&XqDN#!TKb zd$<~4|MkcQ)Ljvlb-Gs=V_!XH%97oIpDH5zI|+=1NHzyp!x;DB_2urbAY7xuZI@#7 z>-D<sng4R51A<}6rhF=dHi1<##MY4xbm8I9?Q*Mjw|*bLI~!wYBkdSo1mi8f;&;ob zR1Ed>|DlOM2)12aL%Drh$g|ssaD)SU++y5j^O;aF-7aChF75!Hnyy0KWw&Q~<)q^6 z#NVZpgW6*X+)1{5|JC%_|NIOG?Snf=R#uFWk1j6bIox<^ZU2G(QlwUy{z&8ktiZw^ zb|X8rkG(BzMcttgqc81m#f8SrB^ThnjpJ|9%)nhXtyvXK;AbOC2$`*ueHpy_K@-;a z@GdBzM?-8R`fJG)TH<@XN2)C2_65mTmP@3-S85U1EDAz%M#RBmthjgI-6k0r@@BsO zBJKCCCb;pV7AUj2Pg}HqSqlo8P>(pr2I+R@3N+8#%Qa@+pR<>+om!39mS$RF_Pf(9 zNNz|Zzt+W?Wwp;7HJ7~EjKbl+0HP-UDqk>gc`@DjU&y8K8Wf<WvA-P}8@$0JnF5qz z#x?)b(zuoIzQQ4fLUJQ=r@-LwYbmw=QumYWY`8&E?f1pon2B}eWL7zlP@2!T{}*Kq z4b2G>_7Kmm2Gn922;&th7=vLA#2(Qj6T@-j?_f7F1z+qpcsZvX-PURb^bGqQYPCoa z=n!y%&u=pQr4Nct(&)hr6DMK_FDsdA#b@Tu{TtZk*^%Jz;%z88z$EkF(=EVj<l*Df zk<lEuy7Z|g&Gg4mrvdrJmd%#j9#G<t2(~kP!vfwSuw{T8gY_ZW`QrOqf`o@yk<hwi z_Kp@g*JG6n**%!fsb@7`7ID3;L>8&>5UNAwf35g1(PJVF7ztV0zomUgH;~c{$&d^n z_&#Q!Gb4otZ9I6&<5xdPD@v;ytI@!wI*2#^6aY|2#XYo*v2dTahaGOJMIuOYv<Sea z?D79;l@ADc@c65iOsART{i|w~&^;baZgfBbYo_tE{LAm1AFCO!*;cqyeVyQ=+%&<J z7hEsmYiWc}QP%ZciWv(2eX-=%x)?cQs)%-aE?@rf>RJu-!gG;FmUPxyVPdaEjs9&v zIv=EH&X-tzzq^jvhXghv(`r^ag9^V;g`Ash-=OYw#Url%M@Itmi^?Lh2?*+pVqKoq z2X?5KJ!iGqDH-8dA)^n9M$EbxAUj9)INs~;`$o`92I5oIXaAbcSiLwj{d#_W-k$f& zUp1XPo$ulj-)!4tapMk{$|cEeK-mI1`-EZ7QR?E6plFG$*<riw^4_PR3Vs!4M^S%6 z00pyC2#5G^L;zY{!+VuH7{LieBh(&ON3Ez=sP494HAJ<i2ruL<_Oej^qQXML>dKF5 zaeg!vqke&yN`$Zc!)~Dkz(*DUElD<%%<M}b`HBVA|KC{uqmx#mv)}!Ql={xFw90m- zMzf^ap!TpfZ;;@aLv)k)Jx%epRqMo?=A1MT%T42pWCovv%slWqdhhn!7G8s;a`^yj z@y@qv=>hE&)VE?TMU1_en|6r;=^f6lW2Z4e6Op-HD1cjb>bDb5dgKE+^;efn<a=YP zCDUcZum!E)e6GmT6X;4;i%dx5a_jWWRWVMcJ^4%*_+f7~)~Z7anMu$@jO8dREci(` zB=<eAS<++5^{g?ayparBw0q7ob&#0EFfDb?WlP**mVS$lI3bwfboJ+;-{yke1Da|O zZOWb#JG@h#(%j?{z@!qzJqRno1`f8|p~p$TVmQwh&U~H*<d|&%L$ipI?;}q=i0=%v zw53G*8XI{vxeIz5wWC_a;m8-Yb)0j?sr+Lv2%7`nx1GGw)wQ>|MO7zIPH1sO<r1j& zP7+Y~uOv!NeKyltv^2DJX)TC8_q#h+Jftrgscy6yC!_9x`=DW{?#Gl`DFPWRis%`x zjG_MfqkN6o%%l8T%UnrVYZjmG{FrMozO<p#9q}Oo!j&5C+tS(tCwHV{_2`@a^og;M zN2b_l@L*G~pV?Wmx3l!*_q)eFOx%@+w!_9@Yddf2oYr;SMojRRq`)I5Th~{uEJrnq zu(W;nEOrKz;MHxvZ}1Yg^Xy75r__13#&3qAx+*c48}d+ce8-B1i<s~1v)sgN#ZlZV z|7tYRV>Q*pY75Q5wvTobXYoE%QWu7j9ir%K64xX)I9t9q$v7O<$>inN079Osril>& z!Pe|JIkY2a$^n8;lxY9A{G1%FHNeo3;Xe{LCe|Ne3)aM|7cL6k;CG&aO&$bkT7kEF z{V%FFxlrwEtfHta+N(_WrgnyOx{DEYOPz$9bT-pduApT?a3Js}c*%vA&TNI4F_YE% zA)E~%u9Ck1D~GfF%3y%5W+e0GSt#Vf90C7`F?C8x^WF6j%B)*IXY7i}9a=?t_PEUs z|9ODco_E&t1t7bdvk0o+wE7(X-ex?m#&7<o^`j=R=^ID3L5=y}fYD3Ro~t|rQvL>b z(4#RH`(P#^Rmn0ycZVC>rTXeD`*YG#z%3dKyc9Hk2PFw$mtf{@ihvZnihfU686f)v zT^kPMa<s5FS%8uVH$E9U2+#yXWu=P~<jL7QK7B2`VbBs6>-8WMXAmyU{7vMHb2G0l zP{eAJ8FC%uzC9StK*66z5Hcw%-1iR*31Q~}vfyBF{3x85q2<$>1gFEfS`hmj<He(t zE4U2EIanNq_KzcUB!)q|SHFOrRoGFgmJnJQL@28Xckgr$4hVPw0k88tsE6%TpjPD| z9RC)JF1Ne@$=U_1^K{-sb1{;b5quxHMsjrv1}`vs0aX&QG7kI!T$Ym4Yc^uL`v#oP zw<x4(f~$mM9PKW3zCQ60cSIY|QAkb<6HEjFOCzT+lH=yGF;kVH!h9ci@8ivEhq5rl z$XI{{U5&b1@@K~V%2FH3t3e%(u-xCNiX2<BVprI-JQ#BE@_zoN)yJMgpj$V$X6&ff zxK%1BZgXRsq3m;=<*2PT4maci4aK-4exqA7B6d-)%aLUrkKP?pLcTCcGde9~Xn2Ep z(VZD*Z`u0s97aaC>!FS8+#9AD#nLk;E<+Th|0w0<B&MgeF&i#qg+b6;9PGJ>l3I<9 zbPm~o4h8sW;GoP#?CgZHdj8<e#8D|~<tRnWy!yR2nA(ONTi%yywp{pUN+HcVC{^jF zr$Ro`dwE~HLz!IVdH_npE&W*rITNb`ZGTuPC%Roj=plxjY7oZZb%YXtWWUR!;67!! zeKnE5k}_9&wd3%h+e5FZBW=agpuqulq~>QJ)#!0WlF4xN`b=U!NXsW}5X^q!h{Adc z8fLjqxnjLS>+QeM{(%iX700K?@J9eW5cva}3Jq33CSdjLkDHb%pTHXdc^(QmbM#a( zVvVN_&H|K#vZ_MA=-ZEFK}74e|4(bC_q!qUJ7HMXM0mk}r<W_vW3bZ{IQegWxi8S- z_S}$t?9-hu1=dm19>Z}xN;=SeT+`6Q^y+)54TM>zF2A}y^~ux?jHg4-u+}s<GXh|l zW(1_Tf=qw3I7R%>M<vCU*LXyK5-<vqo%(zziH_5t&VVZ+@%hbahmES*mBfsKs0<aW z|3(eA!$){P(2$B|;0_k;Aq=<38J>=*V=P-+LY>2iqA%FA&<9Y~T^!skbizrHb$&PI zVx9w;q947n2$j;Ohyza8u<22Xw5K7Drz##A0O=Py!ML>@s<rsNnvt@}zs(&wFe?Y% z^1=3?re4QT#kMaL8Z@-3QCt**w}MSvhx{>pZcfMVKj&jjyUrbj)S@~lrFQ4~_Q>6s zSRt7Xv;wj7N+hc2ik0fWvn@w5H6dWkB3VGk6={%nPBL_{u;(`d2a&w@JN1l*K5LUU z5S_Wwp8TpcgOB8yhP7y0&*iuvqBtPs=)b&^fTegm?-!m&Umd+y!X6E8aG;WRK0#8V ztT^^VA{T%Jfh1sajZi>WMHdJ+Ko1V-Om&(`GM0j@C1YL1C%=43dEfQo0H&#o{M6N_ z-`SZ@ACAIWnyrxY_-44epLRX&vZc#Lc(T+Px-=tX1O4Y%%c`SyFwDlKL$T8<tGB>) z+&p}y;LUeGzrI7OS7L;fTZ7(;qQ0iv{FeQ)+NcAOnq&AuSZwXI*xrsEqUmOCYAxv= zO$e`|KR+8I`ta^4X@X^2%_ybNDw_omoY-xlnsHhks%Je>i&is)$p%*P-g{GkQ-Q8? z1`ksV;21v<FWWxkh(FIm&yHo5j%_^!L#S>H&VVPEEHO0;Hr7&$YT*$xTSv({1WH|u zH#N)7`7EC$+(cc17?bZ^ot(aLVBSP6Rp>~`I&46qIJ8eSa)4qdh;N!k?ucH_8guzy z5|yzO>gS1JF*>!>92nDNxgxj&VMPOUK^Zg_z2-(LV~h=3THwOE5pzm)P~g=z;7z7k zWtwM9+vroW9d)Brh^|Cw?vwZ!W23p*E>Ru2{z8tjLJuNv7!Tn>|5xW{P+Zc_g6V{r zOEBOeOuo%k+Xq}&rX|DW?J}!c4)F6l&BBG|=G}RPIYktVy_z~R>4!N@eV!g?_F7|I z;0PGKdLw`g!VFT&zMei2@4<V0*>910J=fL_<ORR6j^>vigFiRXwYnZe%8?OVHOxPL z$H~)N#YR|w`Xh6L^WX1B-!+bP?F1CYfUy$*KafQ<{_VS#kG20S^H|*C*RubWaPu89 z*Ut^%b80^aLUX*zVqcYEYgSduf&OH7pp|!VzCjwDUy%N{c6M&!pKvlJJa6oHaV+gf zPx?(f5R$dj)93N_Jze{F{TG8()VK*O-N|S+`hPstnUJr4xLt9)p&Ta#Xc&c`Hw;oP ze&pA!x#;)N)bXf&R==c-qQ%g*$G(6tLcpCr;`fwaX4+~9?Ry;FtB-a^Z(`feq`j}k zKulgjs#m!h#xZk#T$b@0#tuw*j2R@!?o|uw+sdEex0p<op~;G0MJ$a<TYkQ7@Q$N^ zy&<dr*7?=bMmu4kraL;vV{D2EXtt}7ZEZV;*eJZpG)?FqlTG<1k1|ue-nSaTZ?@K! zS54q7g;AC5nC^+u32rWbMBlJQbA%#Nf8?}yuRsxj#Hxi=28We!2E+_a*Unf^FkN)u zP%$)+wLl&G#h{#nfR*-SAy$2U0LKfb@-Zrefcu$lWV}|Yj9|Tj$M$WU#AO6wCOs91 zzqrLde^#S8t_#m+MEBgqrx=7eMemnn26sO^(A9}}i)hZPEYW52>=5TKq53>x^-$3D z3?Tu(9&>-y|FMzx9{EHZVOA&Bhv3z0U2$)XC3`or7zDi@a;|V=&ffi#Ocb3SOsPRV zg7{M+`j;W_H7TqO&|`sJ4(zUz)^O#7+ea#5sEAO7EJ$M_;tb}2SO=8~WO)7v@z$ft zYB6%CG{1Sg-aKHOQi7Djv2YT5GFP`2LZ-Ntxj=x}n&&P{uxD^LSn*Mf+CI;%<;Z!q zA(RfxC-P+yV8?*OD%HJfXA0*}7!gOPL{>7pOG;Y$Wx6B%0GfLLnSp^iGKur!%>psg zhEA`SG-RPu3v)-3cT!StVkqlMks7FbfQ}>?<zc{JAQ{3MYau8bGcN>MgtlNRJYw`& zYMCL^1zie}y6$WqQl%IzU>w<-RG?IG6LH#r2yWG#wJ1uXaVJRw3jH;MV{_QTKY;Ld z6aXAL4hD?=Icm}2$4ytA;wU85g@m1hpJz*jPXnfXp!10n=QPs7%cM0h|Ai4_Y6s{S z(y8lSdgQgHQOj>|kq43wR}2PsJa|sK?2j=-pymLJwG!4w>^6Vq2J$j7DQs)IwA0*< zu8i!9pOn1bWTC0Uf5aHcoQy<zY;(Dx;$@H_9xvK(c<%nY!s%zf@7y&Q`dF`D-W-D$ z17k%GdEAt_>IrG3A{0v3l6F=>%OSV}Ve<-oG16dwIcr7mDk~?75vE!|jG)!o?gmA^ z0KfR~oFof9T;7AYM+9dWo{2I@8QZJF&{C^JF7wj`Hgc!A;}#m<UL7lwj|MJ9Lw5@O z9{-3k^$Xnn8GI0g=7E(AeZ(@b!z2af8A7m}ujP&EQZE`_wqW+ez1#%%?U?g@+pADx zjdsvq$0ZV<w@4LPBo#*kRA)9QqVa&n|0+A)cPh$fZCFcBG8c8P37Q01a?SJp$0;?R zl8eTK8PrDR)-rtC%ExVfdQWgIbHGgbi4h~iJ1xsr{eVye@IV=X`*5w>jtw4E#LiuT z<Ip*Z)gBVi&}YJ}__d{_aM^PDS|iZ*E;5)sjNWSX+Tx};0rkUJo|4K!i)3&<y}c~H zUMw-6+F#ULqa9U)dGhQ0c6ZR70Zr4;nXhYo8+Kc``S!STKlHl5ufDwRS*F!(KHC97 z_qVjC=7+p~9{9mNF5?MU$p1|YUvsD`Bvbj2oWbd7PQRCaK?wg4f$=@w`=lEDyt^HY z=Y0+iR&xmkRI4`9?o!YsM3_w+xmA#Yo#Rhh_Q9*ykHpzRz)7jFXw=yRDNB+QBE)o$ zu1>-Vf4I+F=UHw43kLi?5TkeaJB@kEPE?=l5ig2Up>2tQtQV;&MeMl!X_^P`&E`R? z>dT<6Ui51^p7D53z?k6NewA+#(`jyOJWwII2Mzi<r1vFHf7>*|q@<b6Ldnb}z(RN` zTL2|o+Lb6Fhmo=U>JpqJF@)L#;etkVu+H*`k(!oz0#(^|3@3xIVRsD56XapGb0{%B z<vORuaQBgmC!PTMwA8_>A20^b*c?i>t_!TedS<vGS4gsAMPxE&D-v{0II!Sx3ff0t zqYDSzNuI(8W`!y0S=~^;@BGsP5MuSlZh#J}C(^fYBPJsgmc)WW6%k+4+)OI7Gz*6Z zP)YKsTI39w+Y8W1C{!|B77>HmO%yT-7x)!gcMIzCy?cb2F8ZbjH<b!3M+U$a{TmEZ zBL?~v&5fQZO~`+2wX8Cgbvqb5hny^Ziy|7P#;y0PdV`FaRuM7Qq%zidn0+>4tZ}&& zMqarjb6CD&W)Pl4Osf}#kQYXN0U$@@3EjAQ_d!~<9V<OM>(U}stmRfWkug@PtqnHS z)d>Vet(IF=Vxq4yP<;%AWya}v1E&)w^XOCQKLgPOnY<P&vMLgeO~fNUi5?oiLiTjU zoBgMBG^v;#0HYeu>I_*ttZe}@Fb44HG}WD9dFgBRqw9xXm)!dxFCSBp=;>$+6L4w| zh7=|0jK!W3KrN!!MH3=1&x8To=bYXR6Hb0Wa9;vf(cHWpA^*~TcCfc&^*Xa4IFwb- zMwkX;-W<C=FDSghb!R|hPm*Q?9um`kn67y9<u!nP54^CD`#YL01T$!fK}wQwCWeO% zRhc8Hz%Ok)T`y9JXD+>`!%iZBa`-(LAZY{1&dJr+qX$>|%zQ~)VoSg+`IoERa9sB1 z!di<vRxq_y_;|B=+k;)<FQRJt5;D|bh>FMK?n%rPv8F%l6Pw>_>KB5YMtId2DoP~* z+tH6IP=_0HNfI!aghTFHA&6Iy5!|j>h{%OwCQQh2i)uw7+5cbOWHaP%bD<L+22V3~ zwTm_{@t)J_hExxraKq>Lj&CP;Gh@gX&}sX`KXa<Er}V3t6FrPP*WO%w0Jn#y!=1X+ zTT4UN1J^KEFfx2^tbcUk8Gs4_bcGVbgx?pfzuRvve@Soy)wrg2XBnUE$W|Bm?&e>E z#0(G_qFU^4_y@9KfbwYBTc=<VW8E?`yu#?yiNS_VP!cF2`jWl}mjgmP%pmZ1AY-IC zR}T+f1X+?wu=?L!-sWP+BvUDbln*I?NhM~R5Z=9-$?<7ZqU}?L<C|6yqKMp@<gQVr zg~qMNDUWEIMmlg~b#!i@&oQ7?8u{rV_DeiU{KQ@fMu2g636u1&$-zq%F->AAXP}>i zOktd=g=s!?_re*L4jZy`NAcu|bqkPfD=9k}CXy~j0AVznJehKzQ8ze4>yBC!5)O%k z$hQv-A>vsQ2M4J80b!kUL2l>9aE%Z#aJu(^HSPu#^%Ru&q;|nl1_(_`336yc3mO8D zyb%C4CXm-Q0Z$>x;>dCJSzv*KWT)9^S;yBQk^)V@UGPK>=RuvH2nTi~>NK)rP*@zZ z-ZQ^7nj3p7XC~RhjMxw2n|d$*=*1jY!~hpe2U0PxU_g3;zPzd}c50i#q8l2|aX2VL zwmj=%B<v$6F-mi;=27C&&Mv~FTm8=bRF$2;w>b-&hKS#W%4%0<gO^(^#|s@cscO+y zMO*qM4s~Y(gg)Xkb!T{$zKqY)Y%<;F8f#(}l=vMY=wRM=VXmJi%0Vf>PO-Qu4?t4` z^6A9g&53?^hkr<A>NKj*V1K@zOboRHXcPoRGhN>LDh*%<wvtrVvv!%W+CO$GjKIwp znh<_}oM>xxI3~yO+Wjp5CI0wg+^#rm#s=kB$A6B4beutkEW>|<O3VjkhmlzGW~E&n z-k};CkWWat($47fGZtoSVVyfU<Wv<gJye;JS2JqC$35Rsg$0fYg^9m%F!DATi$kL! zXDZ+o#t4wEqSXS?v8kI}Ni<u%Vn;JK3K$xhe72eu+$CbY#aH`QJ>LHBL^%`e8ueOD zufw)DbTqrou_p+p5uVIabLp=rWW{HE>`Dk7Wm^90?cHDTZ{6I+#X=n!<~Ju=4|E1e z!o;)a)6x$I`9Bt%-4S-gWY*)n%7_iH_kyePY1;U*_A**C?^@pEVXvU4X-{9M7vAc) z7I9pf9EZ*i^!LWvBhFMN<i&;7yjyWN3i(PO@0a0MPrj_bV<DG`=fFZJftZL_Rx8(B zNGQQD2-^XWCA7q2j~f3L7Wr&8;vw(WsuXjK#?pj%THg=Xse+YX?W^c9b2AJ6$p|pY z8|>L3qLTINSGL_DOsrr+GKCnN6B7;~dpz!=vL(FZ!vK&5o}(h4e}5~q1R=qIzTvSC ziO?4dZQDrKZ<TdC<d4NfIoNhRV5QkeMyBfq17yvJ3uouckWpq@nh#S7exLs_WGsM9 zj~DeQQ(BF=A}s|4ZVPqEETN+ot&Rr>4I;W=@HfE=tZ^PkAu7jQ5J9c7HzCL(_2Z(o z2M;?^b1!~4^=l1QBQPp3g!pfukj}JDX+qJWht`t*G!3pfIEC@~cgW6l4Q=Mel+W~Z zyKXSYmrz7L(S+gxDKXELLV@@UnitQI;sa|21P&s%9uggp10eqn+XZl0jTmym%@v31 zKo?kZ%nNV#cvL_lQzo{c2X#>@g4=m4P_G&swd7t{M^4n~-!+Z~*2W`(<}r+|^YuvO zfe13V$Mh#eeSThc^65e$kdjM30mf)e3^#1#Q1A|-i(pu@ZL1aq=iBL_O;iM27cwCQ zdPSbbkwxZ}%%?{LYcXJYYnktvyGWA|gD{<wlkYu5DzEey21DakI558^bC>LW=~UL3 z{h!Kzy<KB9KJiQ?od~2)fVfcl0Y8@^A6S3{>Ll;>hN-;i=QMBagF9=jM*7d=#7$to zmKsNjZOW9vCtd({?0`vQ;>P>21g^(mzAEu|-Pak9rAt(sT5}{G_u^hbS?wJhu?~=M z$^DAC?aJ)q4(VP3>G!t%Y`Pn#ZV(F2$_=j#-r2q`J=6YvXIIz#{GsmgKY22Qi`cid zD@I^Ix(UyKS}&?&)?6u~EeUbOBs%t8y3lWNULN5CfggfW=C@d<lDr;fZ+ms7>9jiL z`t28tzy7DSj2=;H5dT#&mnOIo0xEE#n|KEeC&|?1c*fX<SG(@L`iSM;e<SrR@JDFl zcMP4MO2f#S06?!se%Anrz=MEW;OaDQB6J0|Fj;m*VV$rW-redKX<O<`Z)nzQ>ZVs1 zIp+aJdqVGrio=-@yJ53s)r})P$s_1vl6t7l?`_~yjvqx(UkHdMe}1bk=`}#43z%3P zq<ta2P&o7lLZ%l3RjQ;?E(7cY(Hl?rQO*Yg@z4?T(RI&Is}ln|b#D~jj5FC^S@Bjy zS3X^DfVRj7Q-Ej84M#~e|0H%mOuLn`t`JY&pNu6HqsK6=UeBH&t%$(hj@&r8{>sL8 zD2++duaLYbK33Fgh`~RkXx9NY++;fxLzn=B9nvc*+l_uJ94c(I#yjINcW_EBD*|yT z=3`Vtcm5w_`-k%%q8@{+ZY_3^_EB2(-R-HPt#al#7P6M*nq_FKlOY0}lR3aP?`6$r zS&;kzG-B+JAYupIcG2wo1kzhAsC2^5=t&QzZp~5vRBV{7E9zIoQc@cibkXX<gj^#g z2gN)<Az&Sd*>zgb6vQgDwYGTf#nfDD3(`X!^^cy5I1P@=1TnXDHzWxdp#=6`23Rrm zSLP=KOprQiT^=Av`nsHHaWKjk_>~)w0hfYtYsn+FFbR3_(8H)UE*PF>;aWzFIc!2O zo!Wc=e<M$Cl>Q2|yL^TUAOQkec|i>aV+-3%F@s2Eh_669CYuS>H0*Yi$d}iW3>`C# z(0pctN_u2PlJhF*>i`+N;i1*3nJHZ_AbG+7JU5h5hh)KBm4!@g6;w9964n#Y_n2eY zr!{uYTzmkH0%YGH^aIfER{vU>oYh)zTpdKt<e;Ih($kYaY?!_fA~lf=sh;#)Q)nrR zoIl%h6F>4|+BK-B?vgqq=ohd0J(3nxYx*J@tx2cV<BvW3xIKq)iZD@`_`e$S%iF!1 zvScsX##X8ud{(A+-_R$Aocr3HR}NJ8kBm(2fjtUn)>vl)6^|ruI!+d#LF9J}nj6S2 zq)G+0|L_~#wg?^snRPECJlgzzalzo|zf?aS-!f)Ct3B2YVh4I8<Zw~dO-N2wf3k+g zg&dig+ZY!5`0#7NS}AHTztK}FkD|CAHBMH9<K6H57J3;2>?sjqQ8B<ru4Z&*h?8J) zurlSXyxDOkUn%Rm<t&&oDCa_u_qG@hej+$}OyxJWW~t)BK7UU(*fyzBp(rwX(xPi5 zL2dbvpy(N<-*xS445(E;B<+C2Dli34NZ<U@KTc^c>Bo=;Ju}d;R1o{lkL{fBpCR0% z1cmicbBEtshDJ>_ji0PInb@SgR9!JbSA45WxVy88j>qOEsx5Eqoi`u7yY6os5WOd^ zrS-3sqJnN=C9?{fITZ2HA}irPhnBjI_`o8qzMdq^WDEMU9rbU3lY)!|7BHBE9li`K zE=JGBjc1qB{q?L?dNvt!=K-4O)j45|#NEMBZ|Te+ubs1X!5s$pd!LQf$T<vHz9gWI zT+hLIM-o(==3I8x2TW7IlR~EnSnWQrrq%6mmt}p`%$SDQY>qJbL495>IXudj7>~;G zTX3FvZa$US$3eFQtxZiyj$pL$b5=OazeHMf?gI!WZc&Y!$>v0j(3}HCq0UKe%nYyH ztI0&ja5>$>PnW>y2BcQp1Y0T`oF;{yD;CnEb~we;ka`O}IoQnzgjh2J{2YSHks4S~ zpN-O23!~ED$Hgo?h-~BdjJ1Z0E?Gy?rJ1Ch<<v|M0M8plg&Z#`7y6L9$pzJni9!Nw zhj3@&9G!IqqEGN}iO$JN%66oJBe?j!rX&}iGNy>pIjySL@pA)d&5C3F772k!Vk8O; zM-C<Jvu}i%Rg&%9zTfJA84Hj0*)4ZCs0xq^Y~w%|?a-oA5FOyA)IhT6A=8xE=gV_A z8-8hr^IhjOI;5Z?NcxRNe*6Elw2^_`op^4$F2tDG-wB~Co{Tk9-$1ytMZKrZ%P!JS zPjoMfEbAJ)eK7bwYK$UE%3I#><;2~p&t@h|R1Q_i8}0g)x|vF4$lB=xA>4SY8TFNT z)T^(=n>|>_HOVLuZ=jAdy>)kMOhPEz79zHt+}P_0`S*)R0^c9h+Q>ZsS|2g=QI`}e z?@Vh(kTY9utlDj1;n@@hLJi==QtO#B?|){F<((UQ5x_8gA?KAICrrW0#1T*}P~!Qt zmP^WAiQpd@ZD_X72+e+*xF_C4eKCI9>-s^}J$<X=VD_xVV06k}$1h)Aj<T#A1A|I4 zQoW<3+@Ia`f`L(@(Jt<ahX<Z_{5jjRw41{F29&+I8Bm}4mub(VA}8q^`@y2g+p?== ztoSueY}gJtnUU2scDC_%QMpun;A-BTjmLC)FaY_KB4XRte=n^sk+}*qmWO~ADsbY} ztUg`x_XG5ln{x_H5?YRK2Y`MW70u-%R_9jn*^6C?D?Pe&1*&lZ6!-sDwYwHvth<=< z7@!Fj2Qc9r_)4xiV<WqArSD}pdp8b9((DTwx<;ty5gC4K!p5yIBql1+ori)omvtO6 zp0H;NW?mqc8_*kpNil|nFz%bd$m}7Au#ia@xPt|nEyaL+iN@z>mzFt^vm1g*A@nVf zH^8}zzfcSLG#6ikd1g<{XJBUpk+e}LC_jLr!et3o=`9M~668U2VCJaVXafI*g9%z4 zvvy}l6QQjMfe5P@ywrKHQV}uDM+O8i&K$oobWIy4;I$&s8Kw=<F|N~&g#+9>G*=H{ zsvzSldZybYDnE&$aYS<(4P8({bTNToLx>dVV9R2Mo&HD5&5eg-r6$8F!xt^>SS!2; z_L_I;Gr;EO(g+A;lcQ=P2iP^dh0ah=>ytr$FJet2n7JAUFL|6l)Kw3S0O_GD_Gb`B zId~T&9|!H!2;!#2@Nz_*u845a*OX*52-+dO(RMaOi5WNwGRZ7Z1SGv}r(bS-jn5X% z0|69_5Jz`%D@$M!jx&UVtcoCT4f4S>T1snTM5YVA4U=Gwu*<ASA(Y)a140(`=M26W zm=BL85o5fG5~DSP>95^{Oc7dK<A*a``vqc$)B!nHj<v`b#S01oOYLVwX^ccc$k*fu zS@U13AWN@EGk*`QS`2G)Me(9r%j>j(a(>z>A*^6V6-ZL`g)cLtxrlWnSYBuqY|pwP zXI3H1x=ElvVqhn*6N~Ef%+Nd$0X9tf82Vf>D1|l)ffq92Nsg02q({xp;bWwf1-J>? zC17_UP+}4TBcyZP{YjKXIk++;Ku|u@UXSW%PnIsw*FusF*=}_i*|rtcMPAkxRR!M> zT6;A$%8GcQ53gn$(wldebqw;E?C01xzhQl@l3AOoDv)yYngwGV;Pe1r;u1j4|7#>F z7`AkSd0wA|q1XdCn!r|(<i6|r<r^`?5a|Ut1*mG$T^zhZGJ;@B2BXP!S<d@5k`TNv z<8h}SGxQa7<?`OOqQNL|IQER(D7+S@g~)R`-guUYp$A2*?N&HvNM@*10#wlk_~{@K zp$yAT#W3+pPtRK`GT_r5>o=c{J9rkr+JfmQH0Jy8QQr?rh6V~0BCT2rcxa%JOf=zL zH~b43<Fp*&!$Jm*Uv-!7pAVog(I|2<4nW^I+}Y7Jigcn1Fsx1Z+LWt{P8e$B88g;Y zYFVG(U#H$|{-2gXm+Rrks9q_$R?&XO(VRY?dDFUoAU6En!2f8&BZGeEg7<cTO0A3x z@!6wUSq^)a!-rB8DN+zb`PD14U^B8okv0rFh(!9{ms)LELgven2Vl_{@k~GcUU%^O zaVeqz80a9CTn@QaF^+K;wW@U03}-CoLAPP~GfnNP`a85cJy3y*lMspiBa2&roj_C) zVAB_()H7}DUa5f^l$Eg#!?91d2!}o7?~v(X?^#@59UO|b##%VkLmFaRe+`m$42ofX ze}}r5Uy~7c{Pjrco6?2S{Gmo}iqzx+cMP-a=97Qn^a!zy4^?NBPHb}S&aMF^Tq(7f z=2<56evmdbfTjcfhvYwCLnr-t{1bE?o-1Oa(|(i-yqfyUV8bO)2Y**<n)uTU#BzUZ zto(td`HJzaW8!GMAqpi&#nLza_b>1JV?(p$ELbj>w;~BIV#)ZrUfLsiTZ>KW)J<1Q zSHOLFp>7(-ceJ&=HM<G^B_M$`xccPoIUflGqGAFuuG~LZR)a@`HQU1O>d2nCDr<P( zU_SmASm_w7bf_HpQ-3W%(`+fFZeu=C_g`N^6lqVCLFQD_4?ni8L7n{>z{+}C-i1La z7Qk2RhjJ8!z3luNr2;8>_8Zz1-ZFUE;S46?+I_|p(G0IJz>DEVu)%{0wG3H?IG8-f z!!Cxt5)wCl15Nb%!dKwMy!6x_YoU?yED-4l{+~m-e-I!WbRjt<*v~mYtT~$Tdi>3+ zQ5$H6RCaZYFmDh}>seZo26=yubeygX_6H~{eUr85AeXoIpVp5Y2DONk#juD&XZ9LN z@aCEQPfIbl4M96s=xFgAw+TMG7{3B-vBe^rE<UZnM`C7V%I6YQ3}rxk?K@<n=yAXS z*MW<^t&rL0gJ{b10zDdLc_6uHf{nO1^CV8NcO_vAUpnOWKdlg;nRp5)SJr0fy;AqC zFswzKO9cm>1EnRX5uQge1{p{m5N(u-_-8GqE@qL}W#e|fyKEMMU2Uqh70^#nJnlrS z`RrX_6XrE8i?#yxz*S)29NsX9>2hbD!zogj%0xoX`8YVY%dX0OQfu++I#{UizxG@} zm1|fMoJ+CLZsI5Jcc7zb-49II0c8=Ij~G8NAB7rORE?`Eo;3<trbP>Nl?*J43Jb*$ z{fhyNab(%Cfo|tB-9+RwPPTd_%E=Qm?=GCKby<KmO)Z2kvXV58LPtTk@jTmQD<JKP zj`{-3W2TvcNoWH=$|Yc~3)I_4AYL3C+l3MY+d!97Z?n%*pjv}kjLWHEYaDkhT1XXU zx-J;V=eQW~GuZ`=+Usy8vck2Ta}XJ|*bd~&O@W%3zW^o1PB59~gtE?-YG~<zN2?TR zmBU+t0Qt2p2KkJwhD5606t{MW#KcvyLDFq=fpBF3Wd3ap8&?2Led#0g2B{hnSanq4 zX&EBBI9&o`(UK$zA3Lbsn<VhWgO8kvib#g4JTL1~3bJ6*#3#hc7@a4woO%?3ZLLCY z%<AcUNQj18&B7U`+AnBz6sT#<|C5217d|tWe@r*SO~}!d%sE<2{B`UFxdL3AFg^Kn zb-PbFDY3J$Jh72uFu(W`dt(hwEhN}39~RM*$rYi<N&Wyqme@ag511yih^ysG-+(nn zob4LNgyl=Tm#V{^Gq=`6vt_xM&I8Qh7_ObtjNeQVRo{2fhX_#4G?|w-kPo@{$%iUo zlB#t$ana1B;yCjL&C`2u*(3HYg9nnke{)MOH5Ht*;=9vo*M~r0?<Rc;#Z}11T+xhO zE}x~PPAqF*hm@Yv{VX`|g%Ph<yovU7a@V$x$yV=viw%gBm{IzacZzOG^M1vZ@oT*K zo7t0MHw>M=?f!{(>w^<x2K6_pcsKWgC$R~V6Uyw{yW3@LiFM#(jT7y)E4SLd5qH3a z18^sAc=f8G$D0RG^W#28236%jGZK!sq!|JSEinJF13QOgcA;wy9Vs}4$+;du{akEF zjK~Q3?(XX+Us5BEdzCAL%qP01)6kB%$fZ5$NA?E?K)PMUw!$C23?NaB8(aEsDZk1l zvF^7GFT=Y}<tXW@37B~GmM)81<o*8oM0y5ta7S$B>5*z*yUMjnMNc`H2PDlb3yL^f zIWK#rczVSY$!a|;GzR0CtLRjwHHiEBMvqq-9DegIbn_y2#376VAiG5tjR;j*s#>jF zbw7XLU_uF8UctPC$YaO}-mfoHU#X)<ca%ey#(p}Q!n0EUNG^H2l-+ubbPFJrPlA8! zdOL59^Tsj%x6{rdd4llGwmbAVIZx^amR+nguEt&5@gRLns+$tBFHca5J9VvOZH;8{ zx^Cmhn>#>8#tfaR8vLvLw4maWKl_8((ouU1(wZdhs-;yVoJ%1py)YCUo1L;ZNt9N! z3$#-qbO!p)+InSLzxP1P;B6ROL^Hg1Z>iyNz4KfFuY%>0whA1M5!Qw#@KdF@><NJC zR4vK$1ag%7ZbIHKLnYdnyuo5G7UtrrK<Xfb5(p!hXPBXFZHM7b94TO@pgU5bRSE!q z;wCDMcp&t2<us?pMK{CbAUy7w<1K_fZBC%YAs*^(bF82)CcOWWEF?<cpu#*1Gha3Y zOALmiAj$}UMnIWmEg_pi5w;c|<c3YwT?cOh`W&$&&;@zWCL5-6PYhzUrCF%we6Lyr zHYPe0g?QMW+9(t7)CVtP@sE?*=3O3W?Of43gn1(YA{PsoA*5iZu}$rz`MhEzk4%@P z&~lL|y;vAGt;H485tlSWMM`T*Ey&PN<3WGKA^9Y@WTf<x4E4-WA8-T0Vq6L4jC+Jm z6?G*ky%{4@P$`=x-M0~+=&vW8bbbQ2upLrAX#`Zqx*)9z7u`$}bqV-z9{MY*UR#im z&r!q}8<Ip}QUqF`z~MAmzQurUt3fyf<c=v7c#)++?obE5%%E{6?>CDWMQ<I4Q`|t7 z9Zp#WdKo1MvIKZMYU2)0FDM6f+Fzp-11r~y0b<a-tQ%LTsOT88XjQnvGY;|{BF`1N zNRD9+JAlhlR)pbz+=9Id1%jqtg@~g&N|=%M4cYEf<SKaA*6I9-$6(_K)I6!oe5|>N zlG0>yX<!M^5li;XEHqZ&=#hhvh7q_0H=q`oC}-O_8fBWq;FQd=Lw~d`jHrs*BU*A? zPI_@;EseFX^H4MFpw5$Hsge6*YJM;K*t4bTU?);r-pq6fg2tP=%NDelEPx=OC8<E* z0V!f`!##;%fGapRA`kdTTLk)8d3H|fXd`@OIIh~DVB}(rw6&t5(J`Jycfj*AGI)vK z&BpE6o^=EK3Lz6sk!1j-&RAqSYJ<<2ez}tsVvk^lW9KcXo<PgNoWMsKp)W(KY2*%U zyJVegv|O7TH|yi^kb7;jWBwZk?)(lWm5MnQ+$K~_sr6t*Y~AYBxH4CmE_5GQ1EaKD z;o0<Lz3MioK%!BHO_2V}vca*Y-WIdM8@RHqCSbJLFz<kqBJ`$qgTHr`nmS|Sn6OqI zygKz@&a}vqydvCSoSN@F7;s59lQE*Ig9qRc%N(SU0!11;`Y<v>1jyBOT9}g=>f+~F zo@=T^@1FjWL5cnPtp9>R`{N<E5^ue_cV}f=fyAqY*Z&i^>zX6nw5fumM2on6Z>CT6 z+-oYqSfL!sPnhDvOgtFriEN0$2D6V>a*N|Od+|p-?g^W5qk3z-?T_xtO3Vw{qoi|9 z5GODkk^Fe}O&jg*281~|Ch*@M_$lPKuP>F@1jL=(_|6I$pcKbb?1a<x_DgSyjqkPW zm)%RoXPKmN4s~;w(HU>!k&kPFFv=@Lqe}jB(aQ4_b&ZrTq&_YF_-z<yL&##qycfkw z_ExzWDo~Qkk!4@KYZdYO7ft<cunBl;Q5g7*T>nN4&yw)(YOX$(5Vm+Cj``xo5bzBV zDbn2j)iNNTBMAJ4*pv9HRXOI!@G6k~?ky@p@&spxL7)BC<E82%{|4R7mgf$8ahEF4 zB-8BRNuUXIRK`B`iT&wU;y4SXB}#|mGd-mq;JgT4Kv#jxI5ACxTTs@~p~*F49i7%7 zt+`vJrqIEaAGblD0!pvi0_2xGo!!wT|Cz+j1`(O?REwzmBiNYeH!!EMO&bxX!EHoG zG!6lXF*4*rN)?C$vEV4c@I}{Msqn`0G1Xd%hRbZEPkgl<v6J9(KpMh4Ws=@2Shq6# zZ0r?-q*hI#&N~crZBFr{1>qrMym7%);wWZIeXA$atKme1^@ua087yN!NO%XK%s&AO z8Cr&6X`cdN!I;=mlwzdw0u&4T7{@{cU{%86@FLR`kuHXy_)rOD5u&TLeV&l|Br0IA zQ9*x0b5oeK91@}ul6f=fDe$mErccg`)esOLN3=#{MBGML%50%kt4<*?W!n+tIM6LI zSc|aXL7+#r1l&r~iDs87dlOX)oH?{w9>HM*4jqUgOVw(*7h*AfjoZPw(FfLXoH#LA z`u*xI&badtF%!MvBm)Ft^9;8GZj$Ka{q%bNMmz?>xZxsm%v!Uwwhsia4EPm=8xSms ziZB%JLBlZu<vkqPqPn@XF?JWz84qtpS2aHu`fBzN&?gAOs)u0up)SjhH8n<~=$H}2 zeaVscl2esLL4k_e!_=?_gD{(6iA0#(0XA&gA@{j(;}SrtKtD4rG}9%Z6uzu6Opv*5 zCf$MXIpJj@M@FO1b0tnVCL17QG>RR_J=76ETcihuJhgz-T)I){Ke$6XcF#DK%A2jQ z28w_z+QS+Skgk9hNssp~3H{jdvaB0IR=6|r@k@pZ5o8|<AZ_t$mYuP}ig^Ey1MDIR zU-xXqe3?v;0AS@Oz-N_NS?DSV!F1Cnw0AdN;u#A~ua1#Vv=2h$(r?CXa5E2^GJrj1 z0mhQ2OH7Ry_wa^o+z0YKJ!iu`wnJRP7?x*J&GQy(3n6}CJ@BHeHCD3~Xdh6i2}X>q z2H?Pb?~n@dF-SHcwP$jg(DSD*GQw+ts3_p&N%+#>WO(wx$-_#lOT{6c9<wyGIs+N5 z<Bqe*XDozgoWc1W#NMQ?deedfh5&U~9;U#G=xxnSu3s_TQkpDneQR$BeSijSzXE(L z-|OyrtPv-(AaSs9P*(OC*>fwvL)kru#2%+w5F|?=qUFq5xVp9IEAPP|@a~NmC=%vP z5GMe#M7(Zj<HOuUkU@}}nnkFUIqKj~s|WLzYoT8OD(o=mTb`&bW+T`b%O`@Aj^7aL zv46^S(<22B>;=1EFBYr&%w9!C=7suLo>i5C8JiI2EQ1!_$&m7h6B;T!U&4;;&jSbh zmShI#bKW71+u>$L4`@3Re>tiyK?vh*7=$8-Oo}+AHsq`LkJW{-rFvbiA6)Mp@-s)i zLlTkhx<$RtqZOE(z{-6h^tl)#M98%2#_hy#O+~@$U_XNuaf!_ueR>D9{6_n)ANbrI zq?XKTuv2&Zx&6<_<wr8e+?E%EE-?pA3_$r&YCS$1oMrT97%<gw@5eYUilh$K_07Wl ziVK*d#FzP#_QA$=rF3)~T3AIo9T}Qm)ghW={_plzg7upyFJCa0gG!UouMi7*TWA$M z>n-@iLqiIeS+p34F?W)M08AgK?O_}@8oVq5UK_v&8*qthZyq)@15?UGei{ft(n>yE z`35^Bkb`b8$XH~KstDxjkuxCgfFd~6Ou&gksB43AYX)2a3;hXxNv+E=6tF^sq;$++ zz&9S$6A2ALGiNSn+5+Po?P3BYBc5I0RAuSC%n=IHSy}<4XGjND0N@z;xlD7>a~^J@ z8kOozR)7q_1CrWsCe<oMC)X@KjRIdzGJwv8x48pWON<sytKxM<7<ClQU_{XY)NCZn z;|)0^90C6^;W-)cS`gZ_NN3;h@nk68z820gfRK@`ZA8)x(O=WAkv0)uC$Rs}Vgmq( zX6!6#ZBjQ8yh7lBAFdAG=BuiUM;ib%ee^zXpDZb9+OczEi>eAOvRnh3y?_Nmj1-4N zpzDT@!Cry5M;J<v<Wq_m>Er=yeB7njT`c`Fx`g<N;kid=_8ma|4lZMeY9cEO=sg|& zkF};o7^V<z1esnm&pZ?O|3}~w)p~ilLc3T<ta)=ZC`!~l#My28fEL-hjGJeLj=BdS zxD&%<sMi%yseBfi7U@Z!9{~i9XAC{qm*5nPBrVSd$WjJ7LQExT;bQ&KRJ@0+NJ#Q4 zBQkoM*odW`^SoL^hRN~lvV=pDSnyrH&pQ0E7f;d!ag8C~Y`@EC`ouyCUjoA4<_~k~ zg=Z7y>tfoq%R%BYVqAwNwG7LpYaV)v8;4lbB^)JuK$z4u=IUV7n*5B0e9!sZ7{;^> zq0yAYEMZuJ$r)(@LN1n}&K7o-9<us8TZ$wx{n!iZZm@Lb>tlQr59F*CK4`u7OYoQ= zs#BL>*qRuuy$ELBh?K<3#v+^D)#%9q=S($0K1=&qpbeZaU^;>)gD%eiKj{u?8B&13 z;n;MsI2;#AyKBAICjFSc=H?m96p?L32E5OrCE_~23AcF-dZ2ZSmJ9J%2rqH8OB<@w zNT;p$EYk1u;r$486mT3|0?>YPqzbRTjuLGBlv=dNV9s=F`=E$vib|(=*|!IC5{wz9 z^A2`zHHZ4Sd@v}h8y(~(?5O{r5$3b3gXT*pC?3n@Lrm%oUE~wg?4L2)U45SkOP)Uf zMBzi-VCc9(Ptyyr%nIwEEI#XZ*r|Z8#KFb&Uv@SCRx#Im8n|PgPcPHlU6uD<sMn95 zWg;hJ1hPnXm0hjv0SHY-PEkR>FMV4&Hv8ap+qGG{ViQRiK_&z<tKUAgf7Ho7d%fpQ z%Yj!&B1#BzzXa7|w)3#u<mpEHoYZ=BbtdqAZSCJ5WKv#6ASa`D)%bxb2gp#o!|!A` zIN#{NrBRFsVE}1CpdyA>h()j2Qiz^bl!B*u6sRkc`}lqboEQ|HUG6e|+4>da*Z`|v zrkp?q7z3Wr)mH%|uTVsAe2Tp0A-JFtBB~P{(rcq3_(3cR1)n}iDnPrbm>W{W{0nNw zq!sF5XFN#IC({<-<rwk(F3C!ao$)RY(&3Uyh+8q{+7EO-x?bomf)?%I7%}@~09TO) zCQ%mp90lrih2%55h^Avd`8RlH09(!HT`Q=an>Ta=Gcrj}Rs<v%);WMgqkkgrC(T?a zazh~^7%DY%WjF+d99UYALyH)Bd4{+PIHIp`*zE$>Y$u9omX;OX6{{`e!PL#W2fBSy z`vy$KU=3kx)veI^2#6uE5cnjTD_VpGj7QT6n42^qQLzC+G#~?Zlvoo;!2(>KPrqx0 zX?X-FbuUswI3<92h(M1qXD>$YTWlGHhzq4vEyO-H09BG(aWS2){bC0=`h}3WK+*_0 zA!K|LYK;&rUEQLA5w69^iZ>QhwFoG{z%krRiFzFh{QIA_sH!y^&_r|HLO+>9ehVQ7 zKrupuvKK2zoCY2+0bPKpW7&e-3wkf+p61EnW%`7mrb18csOA=21&L2tmyC!M5Za6* zJtT^n82O}P#Nh5Oz_(w|(otA9WMN*Wirj0FH@a*j?H1C7r}2I_n6T=h^@<0Be?9Dm zLyDw?@EM>K*+%d`E$o+Di06iOAc#=dL!NKr^5v+-EOFAj1YUZ~z#S*SDUh?fS|eS* znc(R-u-LD%E(w{I#!m)G8nx(L0hDPivbGE&UnfFCm57y;7&wGE!^C~Nx=Uw1pci)% z(VUT&lFC0HBmJ?^5+k&9y^psSAc!qM1uV<U_u>uIQVl6Fa7<3$M9n&k+w0E;PLP0` zPZRTC;Jg;A22{}p;B!Dx1=|r-I-5Nyy6L%mA%$o@7}Fth#`)*&3eTeSM<cGQ(c>h( zH`{%1tY$lS(Vi>N>%m96#gxxNZfs7<HWVWp2>&T9R4V&bKFWU};OlsHaNU5V7l-VU zysSeD;rh^JtD{fAZ%pG)fe1WASXfLdg32}~4Cnhez|X)A8(4L}4{b;w0Z$;L4l)x# z8!N%a%0W@5^CuJScp)LP{N96kOcY{J&BbL~x(86R1$Nig7{ff*bNR=Jk6280nZDoL z;e1_3=V!VSh-Rzyv-KPVKPuG>X1YlRuL_`?=5^=8=UYD=ocM!Q2O$PP+w*yl+*j}_ zvvc`re+Y3U7CH4r^H~@xA>=q)n-ZNn{aER}c}HsCUTe0u(|q*RJ=~lF@@bsrd`#4; zdk<+A3Dh4jF|QyFQHp{LZfeXl&CGS_7xvMK;R$mkzv^V;r0Lp+Q(tsH>jDmqk>_L{ zIvwH=O^dL4!$f*&HR19HOunt4Km1|mpN=L=JJ}SZSSoDiBL2OBNSnQk=Ld9Qk4wTC z_S9$1IO?V7#{snHs@b*WefQKa&G9=;4(@Z_dJaQ3&8X1@4W*GM-i_wKW{fC8`!<BH zSUUDA$^2MCE|_u1l)ycQ&A~*G1(Ib{)9lGmj4K2O;0GV()S?fdWp!~|5hTZjh>ITo zj~=3719Zp_xCK4|z#Rq!2oCsLtVy&tktPI{oj@7{bM#FjVi2SQE_hX>x@-H5LZ&1a z_cO)|aC5CecZr5g79tf+7;tm@TaQr=0vN-MQLp2l*-+!=fN-^HRtuIoSFr2axHj&X z1|VsPkYzP)k(Uc0?5lsk^VF0~Kah2fBcEKD1D)94O-k|kQq~21tVc5jCYX8>p$UPV zF2dBJlrg8ACGf(E16I{~z{LpJ^-v{Xv~c&7w^)GlKq2I_LKKmtB{rDLtHIxU&Z{a2 z#%JJ=D~Lz5g~8Yn4iKGL)S$t{T*DUAB}R$zGjy&gYA`(G2pkMLxnO-jXA<-z!cRc@ zF|R6@?})xE*_{v(%Z4fkZiy4p8;YPom?Lx)9zdCn&&6*Q)B|okLqTETLB)Gp!Mm*h zI-yxeawxn#Z5NX^H$1gqE>i*}0(b^622wXTYQ?SrvX$8vKcOJkZItf*lI&z~H5)yi zU_ua?%g`o#3L%b^qtdg~(FTR=vqD+XN&?TNR0=U9+s6V>CM(3t96Xm(pri$45TBNt zl?AF8B0L1!GLhzKBk|j04%s5qkN!x_*Mr62M<N5BX;-5QB3!NlBe<r2ZnEBMKN(A? zm<uUaK@Wn`IO#JXuUz`AMEM^H;5kT@p^Vkhovq;KU7bJ*`zjwoj7MA7Epc`PJ+m&{ zSPL(ql4a4j`4kM^qrEM%lao<ihZ`?}0-v)!*1T&UnqJ{LKeNZle_nc!jH$4}p@rrT zK~52lpfwlla7>>fc>!%5j>}tmL(Vh?gQ7iG$`QDS2Eg-M^fAE&A~D{j{UT&i9K4K@ zq7sK&>U>y4;(|Zgi%ABzn2-?r6dn1a6ik?nTO%#cKuG?<3Jt^8_!=+5QnfT*{JK|> zqDIFTB-b-Gbcgihp9oXuFnXutSrM)~hP?0;139(8IUJJrQ(~A%{ZMFhH7+-BAkdDO zhm-s_QMvJ)<tXH}Ey=1wXhn{UW<WY7@`cHdQ6I!dwSu3&1bMINHV)JETTRJXV7WSQ zPKuGf%D#p>H*789czM*+T7EHrAWMLxtBcNMV|qBos|?E00*nyM)>$WU*ysbP!_s!4 zxDk0HG*%_S9vZy9h&=;ZnuWZKt!we%qQ;uGegUL~6MB}KckuIKFro?h*8!xEKbWSF z>?2S^_8)ULv%v*Fg~8Jvs(BQYf_Jbd@A0%1l5ZuN3ZI`6WTnYW=rLfr^QHf{MOdN6 z=TBuq>O(M{_SkhCgP`}W`)k~Wk&zGrE^^)8#=YFPhnt~rNU|tsu=y9NR?oB)$2lsW zBy%Y@u)JK6+)RqYg#IZCA_|_5`z>YN%>zZPgAh)TJtHm_K(uOTs2UBARFF0X^L)=? zidD!Ps}Nw==sb$R0zPxS&oM6~l-P?lFcFX=uMkS;1Zl;f@)INzq!Q39#3S_EyK$~B z(kc2sp56p3>Uw?uN7G|kCvwR)WGu#T#ZpV9k&$oOIH+gDCDcSJF`_I(F&#xdhMnV5 zGBJQ;=8OS~Tau`yxQwO+1LP>6hN-CRi!3v2!z}(^@9B5_uj^drbO=84nfLN6_j5n@ z)5E_zmwS61cAW^#g<TZN1=`d;4lCtd!s{!U`hMS%j<4}|#b%%fAv!Oni0{=aez`9_ z&kP1H(9;im$IQ*gqJq615#^?lWU1Hlh5%e3=fpdR?4{1l^l8zwHQb?OL_<xQRVpXk zc$^Un7y_UP5v9bKU)CCLA38M{%X$DXgHj8SrTm$pva<(ycSEe;E(I!(Z1R%pmJ`d4 z)EH*eqZLxT$)Cpc`Yd1rz6z%gfN^h6A@xxbXb8-niy-$@x<MF4Zz@U*OkUo1YENdT zt)vfnjj;K%oQyue63^)|fnUOCtaP0A!!|-FAuSJ^21?cg&PEJ)8ySH>R@YJ*A{WK$ z0CHXv$%x&X`3>zKB&-+@Jz$<arctEfTUmO9uH07r{sUYRnw!1U4uUnvT`I?E==%c3 zI86^L-;;YHpaEb(>B4Z7{g*2Xt@RVwu~fpX#K2ztVUhdVDXOhU!{Q5X@cZk4W}*No z0yk^r-qB;lh96zyqnjo`DSK)}k$z&ir_NNfr{`#uLZV%>R2oLk-RC`b;P7PE`^+tR zqK|MmJEbOY9^r7-jOpE9>iuGE*>nP;cz_hZzqh;lp61GjqI34*@F#kT_+@!d8Ny{) z?BMr@`G$|9Uo&_jLIzF(o8c@Ozk%79GgWMtsIK&gh5?eIp1C0AcAP%`0S9EQ4}cFk zEl}iWTRA8f`#t}^g-{-g7>1BAdAN;WGKIDux^qc-i!(C{v-0TlRk^>(SPs48Nxe~Q z-KQfc^Z|C&T5DgqPqvdDGQuGkVAEnsI>1=_{=ChdlSX<!2r=Ah%$QNt1gimt0WxC{ z7sgTGsr!h{4Mn*u#*9w4U>(zY_c*SUSEA=f9y=JO1kNwvGdg^`bH!LFG(^rY*^A1Y z19q~9KT?!_==T9yj2bn;%-vrD2h;uAoBAe;Yjpir6(W*@R^cN#Nn{mg5;G7x5vh2a z(0e#^x`&FChO=0&1P~<)t`2?g@mi>81*6}5(yb&ErhvxaqT{H*iCD%G`2OcW?FYHI zZ?_$t6FPm6`RCB-Vpha(99(_9Dt%M0EPJd9x&MJ5C|%D_58`r!gbl~JLhw+%Rr1Ou zGF>E!+m6hc&qd8h|9apDi$}n$6}4M2haRq2?s72izq?-S+({5sGI`WjNI(7BvRJ$G zc(d#FDiSh7_|%G~JttU=+t{wkz^3+XPRnDr;HNYHT#S#o^ZBc4=yBRLf7c%~_epq2 zwu=m6@JY*S)RN#W9bPYUZUip8f+iu;Q}~H(q+91BeMZ>Lwk<F#s;TzQB~7b`?KGEX zamDj>8#Nu<4^~6!Uhtlr#M>vSq%L0Kc@4gq{oGL^*$S(cEUNTL^?V8tpB&eR5f*uO zh%#Yo4Ow>p0T=47W_&HFKamUuhLHm6y|Swr@IX7a7P9CO74uBertPkvN!v<wJ62@e zcOU?xNjkN^$jEL6!VrUzE{H|6y;j<}(8BZeT*t8l$yqR#o~|OB{Ls$>rU*I<ZzfKy zb^e#VDBb~y(}K<ntNA@fW8{c`^?N-?fr{GCT`hEXUQM{ZM_#W99n?7#ntSgzi}2{O z6`W9h07vbSlptHd62T_}7_9B7X^-t9*4;OH^)>i~z-N6?(OuxQ(DR*C+jHbjE@0I@ z{)H7GQLR`MuShG9KW9`doeGi6<Jiyk4>EWeBy0Z(h6v%NKCPbnmWJrQL`)-?>b=%l zmvj!^4oB;8f9hhw<D}B3oF#&FQE?fvmAjTWsh+N-9;<LYl(fmu3zfp~GL8>!Do4H& z6>1_LFHT<IawVf7x!6;N1JESovuD?;N|VkhiTa+FZX)ARad^Oj_5BF`M^2WZ%jG@y zYVfmyj=-P6jfbf)Cg{uC%$2QWKZf*2&bN4zzz|5N&Z&pJ-PZfJ9c{GR^}e)R<y-@} zS^%g23D_9j(QkJPa`eMJ<Gv);%qqblA=2%txR$eB0RgW^&aPo7@@S_&cKY8m<E6mb z>orIim%{WwFU`Gu*4nJby^nK!e8bf<L~`BZBfhF?m)aToRHXr@7*rhUj6KnNvn!I4 z4+(2<Fu8ARL88(WJkdWfaN@N&SD%&1Q{Ycmz~TLQ&K%2l9xZhj_$I7)u}*v*Rn6eH zPy|~qvXid*kO&L~?1B|<3)7O)y}U<^{GcBeBe&;8C<1kD1wHS(kM5d2XwV?sE@mi& zK8_=^&4kH(wIS+Z>S^(qpXiAq=zu)Bz<hcLy^W^4>Dvbur3b>EWy;L((>;caZJAdI zl+tOuonG}-ib-%tDIOlxFf8Mh%g^{DJ+Nljf`XT+BMBgN#*-}kbZ=Gb^-U`|_`}_S zaoZ{p5pv4>%gaOVjoYqF+|jmVH}jY^*1D90%iG*X2}3A$a;WQ4=ABxoOfU|ktW{Eb z3?W(}`$N3W96C6S7Z^X3lf~oNeg5O$jO@DT4fTWYkL$tE4jH#S%!@m=6G_R2ky95p zo$Vvr^@-BO{aLg`l@@N=q%75dQR+jy8tz#;M4n^9z$GZhUuX$-XQRn~G>D!(Pj4#` z-IQg8x{IHyeC^7Htd=>SE-QpqPJAE~8#{E4GY6Gx=M%u_C_sx58H*Q_{Zfa(wfngP z4?k|pZpX0hdfhiNHoj>_{jBX|nI%A3!qBLNDI4Np`12PF)*-ud5L}@r+Dc+DEYRiw znv1lhf~`a0m!s1oqVV8Qh$2wTA<_%!17a{7tH=k018=jqw(FMDs*Xpo2&3m41tC*( z@Y5w58865NCl^`afWh;Y;3s0cP6IV(is6JkCj&i-NlkeCBN~ybdM>Dc8a7T)RWi%o zF3>+NS|Z%v?0vj~pk%l;^I!#%is*vF=7MKBr}w(r8eZ6=Oj8oF(TiwA6cxfC2IeGQ zE2WMT=ygm+k)n>&;UE#7;3q8-pA~Yn%}cAFFZ$>|{iochmJ0<xA0or8m5f@(+;&HS z_vK+0sEh#0taD;=c{t*N`gxcv!dy$hjM{|EWRO%^nVPFqy@)n##hYM@2}U4sD@}MH zukI%La7CF3vu%Nbu6lve=%P~84QMhD={56`<O8IR0vLf9%~`c=0Ql+3)0*aC<3upa zM^fQi4C|BG5S$*Mcy)E0A-u<XiC+m<FAV7Z6s=xG3e@9sSnWU-KhJp?`}Yitpnt1b za<DNg8U`!VCkvR5!gT_6g?Bun-<cc*FQo4&%A`B$MUzO%AlX@3BMx+;qzb0_pW;v! z?1&&Xnf@`L{ms*#A&~F$x%Dp5pelM~AfQ-cpr3AIufKeC<CFnA;K=t$pHwGV(lm)M z?Yna)UaM4BuMm@-J|}}GRrt}vFy&qi={t4F2>ra`?Y+hqQIkjDl%~npr|v^~O^1;s zIGFwX^gskab4&)9$`7_L_fmovSON)7rU8=a5M2>j5;&FvViQ&Abnm;`6i+1vh!;@= zMloWBwR+wFV$EJ8IO%T@-6>~@%o(#miG%1>K%EI7;MA`A$;EN6dAl3H)r$Z}fR*+d zkF|Ij*W+J)aQLC0oBUf~`VJWvGBQL4)9eM}#-`dH{AR#*xt`6YNnpgcB7&t*8$Eaa zYLN!s(57tpTyoff66ZWSKy!C)iO5@KQ8K4*D{bb~g_;0XhlK()B%D*rnXHg2y13`e z{!Os_ZOF>O0f4vKTL9A2$8Y40UD)UwK7J#q{-~!16^sOqe6xQCAzNn(S9s8%6<J7& zGitz@O9JCHj`7N?LZ^ETQqqlwso0r%VR)uK<6zIlU?C?Kkm4S276?Q<aDFtN#udI` z6X92%?rjwaWL#DaTN~l+XB$d-D$4UuUGcWpaTFe+6mIEvk?3pGj$Z^<*@xVu=%{6W z!X)S9Xqg!Q12c^4hYoAU>Di6iFcdCN%kd=HAFa}+-Hkw00lRxhdDhNxU!)+rno-}e z#c>*sUJXIlu*UH#X$IF0o^&4y#9FR18Fr+vP*`xgpd-*Vv6bJ}BziO11M%GTbGXX@ zVPOJZgV9h`>L6_Cs#1xxv<KBafmi3~P=A~zbLDL6`%i7Z5-eaXp4$;US1srmJv-BS zy|6+w17Z7#YM>nEW}vK?D}mS~h`I>ZBCHyz9<uxWE5NMu{BQ6OVd*TBv2lJvnF#_P zqLEqYzzyx9Z~%HHN>2m)lN>@zN!gxM96I$0f7gjeUYlU6gKAJ*#!n8n$#sGNsi)WR z^fkF;6{x&4jrml1>0zK(;tVI98p6mh#1>%?QZg8UmT}uEgyiue)oof-VevCL9ho^H zATp~Gh(=Rhx-s*|;XSF><?uKyi-0D$$HS~Z%*fNyJe)rlRX733#R|!-y*);*tE9;6 z5p6k<C^U_99_~}@!1s)ZVnsCrNCQ=-Yegw-7VTsCwUlZ}q?6!q@}rvo$(T|!OGJoB zPXk5juhP}R{Y(}@+wCwhnZ!HZHj)k64^cSyjb|~D@uKkkcjn%Jv1zk_B&@~a^v(-{ zGMX|dh&Ds<qB!nFb~wn76&@ZSm&#f#HCf+VXBa}XyGvXV7MJDjO0W%?YkS|*8X#(c zToP4dh35?JORg}^2t(z7Nc?G7`lmxkI(z_wdKAVbNq{w!@j2rE=f^%xm^I{W7;}_y zlbA#cHIZ0;!RJ4d#xACUxlP32*p0h$OXm~o3ANq2X*ko2ki%PdW{4*Uvg(?leWw$i zyOuA=`#^KgbqBaMV<Qo{03a~teD$hQG+E(jEmuulBI`_YTX(drOi%b95!`ZR7mQGO z>@cx6gD|rDRq*k5a1)+=mRmp-9e(OoMXp}Q0;z&~fLu}kS55aCpq1*Kq>We`VrXH< z$O6R_VNS2A`}FX=Ki1)K0d76SXj*BBWR&*~`gvXn?5u}xHwS&;M=bX&{$#3mIbxN| zgXJl09QkB+-r;c<qAS>Ij))F+RQ^bEEaayOMVsEOH7`g<4jp@oSd|SB0#Tz=hYAa# z-}N7Nzr#<nh1cL%q%#azuEtIJ0Rls&NLlg)AG?Tn_B^j^t^Ik4h92Ph$s_;oBGJFp zS`w`&AS_po6AXdEKybuNem(e&=cg-+1T;uVL|v_gf0`<19}@mIe}R9RaC*AJL#KL= zZJEF3WsuklB&WSS^{Z7YUL2mj{r%5FHjXof+>Zf=1;0u(x{rRh<il>zK6o-e)()2h z<gt_R>bn#>1!!6X7%RU|9GKLh&-@cog6ZPa2Zb(pPew^aj222hk+N|26GO1*)2OC@ zodP4Rq|#M2Zu__Wn%pwGe(@di5_!zcjrY9AHvUSzgQRqCOy_@!Z+eEc3Mntb6Ma|| z7;!!muP8j!>{-QEIV^Sv8>gsDZoawbsFZ)W5A9Np+<za@zU#Ta<fM(MSs8Atqmuv@ zLgR6FKZ}(L6EDntI&oGhGj1eeTO=0n@Br<!R7I@0f_nm08*uIGUEbD;Ha$unolQpf z8EVB@41*@ugO)Zv{cebyTX`1c(1(EoUE#w<vdKR~J$x!d=gd=q*7;rYiCx&2d3Xg8 z_9*9|U|~~#M#P={E)kYq1W9%Kf|RCNY~qaise*_@)L1Es(+wj<e*?A$@q<dSyaeB( zK|g6E3{_IdQoVEpfnW69Q8g&aB53p%u+lH7y^`&EmS(i4@NxkWOZ^r;>i?u8>4dd& zsbx$7MIiReb95(n4ex=H8L1d~z96z-feHPQy*itYWfhfCOt@dN>jQco5K#Ia?2+b7 z<sAs%v~>4J2&XWFR8188FxzOH{L{{qAKOFhS156HY!}d@Kvo6CbZVb<byoG9Da6T0 z>6f5$IW5}bR*vlLW1a(nv^`0*qLTLrgvr^qU%LTRW=>DY+rU8Nse60#DJi!WVz{A6 zQr8`tg;}K?mvJOQhyvEzXTA};<_K?lQ0~B{HiM33<xOjK+gL;s8u!3>G$qpSM7?I} z!Zi~M({}~Gg_TXu5RX3L#ZB3U&@8t8e+esOd8la=z$#2xDOluaOk_|W!?aV(NvEL2 zGz=AZGML;Oe(A&!dq;Z<`(Lj5r~2fG;>m~M`)S5e|Fjm<CQtoh@22uuS=Xla?u#wq z2q^048lyO|rRD$c>er2@mI50enVWfaf)Y5wF(Rp?0u#iySwFm-D~_@ARByvy96?c{ z&1=f|!c5#-!e_6E{9TY%#R)%?PH-x@R__m8u<ElxYAO+Au(3-<tLDZx^ZWgltKR}l zE+Np=5b5=umgG#4dc#xPL`@n`lr*Ak&SN8BKF-Rz`j{WQg#sXgz5h}TQ33<JIJ^u< zP#3U`g;x?PFIQo?nd!4PeG-+G>(>zG8#qsCCB`T4YrX?oAR5m0;%u(x%~TItaDjs} z_gZM^dvbzsvRIYLO+~~KIC}Ort`$~S?Z~eWT;AJvx!|u(A2skjHfZ;79$h+UVZfm7 z<%51>MXr|&Pfty_j}22zAN<6Bm4*9(wkDPgk4q__$noDnp&`F}lVfO8LTBy%N<>7I z1}P=&k~P&WOqa%E2iSsdYk734j}d-zd_)>Sb^1N*bgi9lOL6$(bf`4@4)EfOre8P) z<*Gb)dC=Ehl&(`wEa`*h#xu3jQ*zr&=fT&C7_MorSsGIv_M`K)#K|w6aXpxyxa;oX ztX=4*t%7}Fy`pqI8~&kbjgO%}bCq|o|IXZ+pQN=Q+A+dijQX+F$JjdKBG(bUf_M&E zGBaPqwfMJXn6U;RoKC^+=y!u;`bq60C>e>-t_`mUc**Fr{gnNr+u993MD)J*@(n{F z0$2~uuiU6GgnKVo{W45KWE2IUAu6&^o5n-*m;n>IAd)EJ#DROR3U^bcpukV<pVeJp zgtMbuJ4ao;l3i?r`-SkA2WXmw-GTWa8W#NYTRlHw0<LI}<bB5|6SC;zcIGCk{nGjS z1@Czi3?STQH^%Qx)EF{tK=og5GK9Y-n2o&p56mO(q~e(f^W#qGCP6kzQN4oKDP0iO zbCJAkS`1w$3r5c0#C62x5kLL_LJg>Yi+(%qmh&@=+<r)>QE5{jD~23<Whc+!I0Dvs zz1>Ek9T#OvK}XR<JnBU&dmI*4bI0AJhlovmWquB{YZ6{!E<rh51S=4*(X28$ayQrP z?TZm}t<Fp&x$jJw(R#HP`xpXt@u{%L3gW$jB#1MvXI1Pc4R?q|!4MQ0G|eMtx1;oN zchmFmQ4Ugr46bsfwEc7Mh2V}TuOFE&q9o+a=RD@A)za5&AC6laMxQFSg_37G5YQDG z$!b)_s=NiCdyfU7AsX|$hW!ov_Ic1jl0*C*J$YjJ3{mcBhp_0u6Un1_7(p?WDp7jz zSrwQ1&J$llayN=7NEBcB6k;C=dmEv7#sbkl#@m<b<G2nDy}i&0J5VoPb6>B&hOa+X z<)p*`SMR;`TyPcC@V(SCz_g*`h_HvliMr<gIkWSce?+ze4rUz;)!On|0iyv0Gt#&3 zg^itc%`*X`B!rZ_=S3%e%{2l0^xi4;Fd2<6<8*?8;FnRvgxns@p`^%TcVVve2`dI5 z-fRQe-9PW?Zn>vnXm<Ou&eZ8!gx{;6J{miJ;CqQ7qOL)l<tXSku&aJ{`@e&jTeooc z&XFVh80_L|AJ&KFPXaNhT&rl{)YI=JCozfbp`g5a7a=m^MFa_k4Z^F*DP~T5<aKOj zHJJS%c!$ilr9b|RIIvklqK*p4WeO(UW*SJ>F8KVITpv2?K&JlNCC92tV=%&_>!N!n zq=OJjLwfg}K4`%voUl&RyO9{*%3<hVqD(YaU46EnNFSO<>=sS`o;>JiO5TsPd*7el zpRCxC+Z!&RGM`|52G?xrB{9jY{8TMOTzmM3x|Y8e-)wvH+~UXmbhE#d>s1DcS(*S% zbNcw_=qj@8@!_MnJGi04Jx@}ZAUzkU@jyXym&4K5Se4}rVxo&cpRjfK;h4JPu+#48 zLkv@%a?fz)KlJBWKm&*OeLh^2VoEk&`W_!v-{=|JwSSG$`O>Z9c4O<9^Ncfi7hbY& zLBQY-N9#ium$z)MkFZ|(jg|vfL{t6kc(0q05dKr{(D5bJ*PdF`F}Z%!LEZhk=lq?Q z{5kH`sHw$Dzn!^(BTmDTiXW+`=M`M}Y<r#Zes}{IHb(AYX6j1!Gl|(%_U|^k-Sc&+ zKl~R|`Od`_DU9}nypzlitgD_^(WN>JM0nF(W}aSgd&!aeq&n-ve*3OMf5YL)-S_J5 z4=Hz^IG@0;J5G-}-r~PGvZZouOg{M&SRJXrW8W-UKcx3Jz6@D<7<j!EoxK0Phacw^ zuG2_fm5+(}`rYU7Knzt7>dy87N7m&|dgz=?c3N%<*u2aPVNtJLbLKuuy4{-cJfh6S z?+l7D`<EY0z7S*YPA%UlN}m8Un-nu)BOg@g?#@TYHNXDIYLHe^poavT9OfHBv|JaE z*_SXfX!h<ADe%1j*_7kJ0uMOU(+rUk5}mx)b}y_QV44U)NGh?#6vGm?iS~-cD*9=0 zz!PjECqlrYCgk2l)PX(cb2<o|j?+fBdn7)29Jn~P#6qnGux<`?v_w6&lioMP1Vg+w zqbxg*wwXJn#<t=>&zz@NuPNRXY%%-O^Zp<CgLYwv8<`j*5&t~aHNp^O=cL0&<~V7m z;xuxV3F4oxGvC?EgRO?<<!sT6+g0Th91lPN{d}PQy@`_tWR=kyBLW)R$UKn-$gEdj z{x1Nr@ESIjqSssxb%s`!1_bh<$>=A^Aw9Xla6sM|{=_gu|0JqW&kSld=x3nwFQ(@# z^3l@|$=s_nXY2~S4z=Y&7sU0lLN2bC`~czsAg~fMp488_l|15WBSR`3rq34(;2Xgb zPmxnf2PiyPnYgQRikHfhA}%7QD;wrJyXViyf|z^zPBVn}JO-qZ9%yXLq0i?|iDH`~ zx1XO_1=4bw-+`STdF7aA4m+!#(_3nfow6|ThQ?mQaJ+mjI}v!#GuQmx(+&m|v@3Rw zw+op3`qfd-j9mQv%td~QyM`SR*lW$c$3|Uy$NgKIsq9ylhy3F7)!Ey@@Jq|fu#J|! z$_7KhF_&&F==3%vJ6@HQHmvucp!JC}8WwAwipX>46w?UJ<e35M!sap=<kM2A<F}CY zYajC`ICyc?dQI<!pS4o!m|UD}bS1rv_s)F`f1q(UbfZ)1xA$E5eg8X+hNo`ey}MG% zwR))+{9g26PMj$JuY1__W%?Nt-mOCf)Oaf6KlfG*YCF2W0=dCu>_d9F5VP0!lXrdc zAY!aLcw$7ymB6s@OY?TR1DAgxwH$QLbmvSN+_0Sdq+itUbom;~#@km(hxK0{y&v`0 z0}gd}fuFS@H~GHzwq@ihv-J@Chb%nSC3{d<tH^Kk6Ba?yns+|yyWPGUJb6*go@Z)9 zoda7Vi`Bip=x^UfsKt@EmJ-~extxPA92B2e8gR3iw!n|qtY16aRxaorT*GtylnL>} zkX0L+aF?#FDerFX*w{L{7>=?a!BJyASRH<W-E}>ck$7&Ndyx0mFXF8;W#csMF?K5i zl4Huo_6N@?@;fgw+d5=&#_hQ5W0mMMgdI_}crSK@B@Mgt4H}8aw5O<Ao|wmUzC`y; zl7Y~oGh1G&L=rfBy;FAl#y<b<KSSs>$C4s4*VwKkLzYC>$_?eXv<VxwjA~q$4T2E9 zVdKrlM_%%^^DYkIsEctCGu$<<*u&S{fBF;HDc<rSit=`sX}+Iw>D!i-0oyx`T~TkY z8=5%z^$`lYC^%M?G?}6{JgzWx?bi4U3AC8v>QN~zN-%6cePFk*rmR7|Ip5kog7j*q z=(3$=Jbr$+BF5~yPjq4D1IAT9HLpfv(A@>Z?+%i_bU(YfC{bObpHYm?$H_dOl*P`0 zEp5-<U1E^Lh`!{ajPE9E_H=|+nRCv6lYH;y{|MUeTvWPF7_t{TpKmFpWZAcp3~ZM? zRdK%{uA~x&Vu%ufR|N}?Evqy~s4uo8U%Dz~|D4P%Lhqd#1r&o2)3O%hZ>tu&o7Faj zZk*cRR+;QR4Gb>IL#wxpuy!V?D`&K~4>I<1`ZJX<`j;HFAIt#0+O_!Q(ZMa*m%wqa zeJb6MC<xHELJ#qzRmNd(*Q1*1B2QAki*GvrYw~@|mP~DhZu-eH`Uy5UgK_PCLYUt* zKI>MOD)`tVukW5Yq7SAp<JTE0K2}v0DX2DJ4iVvb_xHRq!&hqDGtouk8Drxwp3h{Q zj5J$c@9n2PDcV7;Ol(BXoiXz@s!4WlT~HzLPBUE4YjR(e2THyf;uz)d?aQVm1<O}w z?Q)!v-8l<{@l)PDZSr5z<*ZJO^<mo>#h(NQ4+AHgtAYX?PdX?l;52I!f9DH_iRs7@ zALlJQh@m>w(tdN7!dU-sMbt(Zf=z+H1||Qb>NP<6ZOTS!H-;sjN9U+trgIa0lp25f zwSJha*;;Y6$;tLZ)=iF#;khA3cmEw4cU*v}`EqK<H@-gCvvTzhru6HcTuhtJ&T%RR z4PeUls6V-H85|z(p7H{4;kHT*-V7+?2MAEtyi>Yzm5(<pjc97yU8j6l9Ac=r5dV_S z_2JhW;T|Yo4snENdUx%d!Gxk08j48XYJ`8+9P4_&Vn>Mg!{HM~9dLG4+9xt5O{&3N zl{z%9R&8sIl|2>rmLfiK{g^h^<0h3S1P3D?kSc#arY*+Iv?znB>8=PY!ph29vf|b% z)A~4H?ksP=qV_v@ugkxpGC}G}()hecwO?w-oQST8pygpF-Y?K?E4kmiHOh4>dOY*S z|HPz+J@UFgcim2i;*DjMOcqFs_%P3*?CO|wZ?n69gJ~RPR?WC+cDkuFvJ1+sx+?qn zC+UAaqxEORh;x-Lx;kKCXV9pVUCIaVn(Y6BZ%F$+^|^yQcXrp#$;ygL&_wMk<>)hY ztY8>|P8XR-++`mChvKwcT!#*e({0VtbwsrmtqQk)(Gm|UD9yha!lqiJG<ExYuRZgT z@p*I0sLSV<tkQmA671&Nv@@mOym$1Z(%FLDu@#>$)paau%`}>l#z+lc{Zm1@sc}!7 z8|)a~RSfZ<xviW|-l83xCKGi*-A9i9?u`qVUD!y|MzZB3lcp%wS1&jn^jLlWOOA6P ze;_hvOk-?D#{?-S`|CKf!u9TdNK#{j+-3*ijKk#I#?!|(l%Gv(UR<(lvzS`#T&1*8 z?)>7-sa?4@@9n7RHaG7j_!*}h+a*9`ZtW0&hL5k=ao_q0ScvATjcb*Sc?T~lIF-M> zwg2M#RrX}Ftko=++|4XZ=1JFX&8<v*^W`_jGZO+fmQUk5U$$1tdR3f4bL2Ywjm6Rd zmnfz53wgXLL+6-@HYU0hYuaxcj~kLd@rjpqROs=i0k}xGH&k;olJ7}dOj?EE)kH1e z2An!&*O1wN#2MGLY?+So$3qXzns}SFx)q!69uWP@uc7v2i=Q1Nj0%rHC%boQHU~YK z@aCz?*0Dw!i>ZIf%nSUxBJRytmRxwlr1fvEBmom8^}F*PtMTqy@B$adBxLbI9TsC} zG({3)pV)U7DW$c7QQV9eZuVYzOZKJ}@42e?DY2ka1m%E>vE#<4H@7Gr>(lIi#-JXG zsq<qPMYLNY5h%|+|G|-U-x!~48!p!>&Sd+!*Q<y1caCdm({D86MGf(hsm;peT^r;y zG}{HB2?sFjWb*w#vyE<qn9L-97Wt|bV(VE!1>wxKqQQ!{m0s)C_kHA58kZ!%u=Vfg z4&7SV_2KMSetW#)gjKEySci^jG==z4`-}^_Hhv<HU%G3^W!fvT?{!9)>qA>7Zdzv0 zbnOhL(LtcHM~*t4Z0+kDm4W>_TQV=7rIAZ#4*FknPVuq6>q@u@EV4fA)L&g^F1&Hv zl$H*Ml&TyQCHT){bV8V|rBpN_h|2Ff#+uGGQ`dbH@AI=wZf*O^zl?8TmsVxE^GcS1 zCjVce1R_=rG7Sp)+Rf9Pt9va!U^$$A<?s(UbS9b033k0kA-!;R$|tgJ|NjYRl>qPI z?7r-&#~asWzOZ0lX?)}hD^`hBVJyv#k)<!pmp<Atv?Pjwps>TFjuHeBPe_-hMh8V2 zTQzyWEQ-@3Rjwb8C?KfyKeK44P@drpuEl;lIBi+}kxwJV%Ws=qYM4eu5&n%{RPaia zcdnbdRIir@D03Eu#~~XKlPBAC9*3U&&PmsPITO}OF5NhG@rC#%N>c=nO?8jFT1q-w z)biHa8%hvQCPN2|3d&2qxVI~<Gs%_EKpdiHuvIlRwRgtE^?vXo%E4{B4+<6d_j~EX z4yzoCKEAue*gE1Qh65(OUb<Bno`?j-&&R9-T}#}cG!L`fZyl;mi!m(f^IQ3ITHmM+ z#JmJ0LUIq%?Wi;;$6hKH=vnc!?Efn@eOx|>((uI&fSM{}^H8vv*h6XMC%1epPf)+H zFpshnz{r%8)5gzl9xIf7`?B?VX<wfg#->s0f<wr{?Wh0wNU&p^Gq}`r<D;C#d{p_B z)T@uYE`_cux9Ez_Y;F=`KV??59?+S~_J26JVlsDA*EP{h=Ph#xJ0-{5jHM5bH_p>_ z%xk^7Z&{yi`QU+Oq7XDxC;^-}kzF=1uO!dmnDJ2bp;fD@rP_jh%7;TLAi5S_htUd# zAcM=VJafR`wO6rLK{Z$YYXltzMjo>SSFxa}bI7iezudpO-!!Q7>Ir{g2X}tH5))x` z9mQAP-|n2Z#wW?L_LB~sz1bakbg-oJotQj3(YtHLXJ;++J%fx%ovBMTJMO-!@9Ss0 z90tM#?>Vcf^OfQ$Z^-_Nx}2k7VD-Dt@uA%Xw(_r)y_(!l-C1}`BlUKsg_`B7g56SA z)v`Nri(8+x*;jq?>)d#o#VSvBmp$?_cGoRj>eotSxi#SIpCJ!6oT9@wQ7dY8HVP37 z@{+%Ao@<X-W#V4Z`%%)F+UM&Gox6X2{Umg+g)Y)Nig03Er_>Dwd1sDJ{yk}*))3hr zbBD-LgjcYC#}U8=Y=po+D=Y2dUQiTvtHL8Tf%()E`9;t~82I?}eHzOjnCZ31j0etR z3Q%aC<BfGW>pER}kjI+5VezN(9R69ieAl-2+g0$M?D#|qM@b_WDVK+ycu^WSVSxYb z?{2MBc8@#!SH8`CZl<Zmt*TsM%<23_!Dd_=D*7vSqRlky>G-1aqv`um(M8FnZ0~;f z$m_|RiqACz54`nvqtcbLSDEu!ouAaDPUE~}$=qf0%wa!o{8(p;kE+Cn=4{y^Xb@kF zBkeh!*vzPx(j<3*d%S*~U*enMI9S9vt60;W=ig}T^Ifs(!7$bPzq%C?^-w-3O~xT^ zNgbkl<n^CEoX6sh)s16+3Ux2DZgxMv;di|zXYzzHF8!kFjrf6+Y!WS09q+bArJ-M5 zZjW*w)hfI0#OFwtUcRN>%EeAL6Y~7$En2(hhsNiBJ~BVz_nQN;A(olFWZh3}Kd;s` z%$IiCl&^d$eP|r4fkJ)kgs7e^w6QLK)FM>Bv~`*xD(w|we)008)b6*kZz#K#ouM6& z$ko`n?(gG{Nm6TpK`MKy_#<{QD!Hi5@pPG8n{w`l%{=})=MUl?;ZVy<Bn;gdz{!)P z*7$<>m-Ncp;dM)wNDXp>R`Dwr7wUrP9qGQV5nx&~a7IU+@1Ld*UNkAk?ay^3{S>8@ zYo1x68uiHQ*}t|t^71)U`RzYTUo}mZquJ)KUsqu&&ahTcn-|&G4rQeAIjtV@X^0?B z8CGLAz-~-oa#vDp-AkC4`@>HCB^qvgO|G2%Ctb<0wE^d^y>hn1T-A81!*69(b!g$M z-PdK+PK&v`Yq@eTtl7$vIFr2&B+k?cyq?Jl&2Al=rtDt2n@0Lw$BU9Hv#+04MjjsV zqOwIllZqRkoH$Q;U)Q#}u;Jz^W!mwv>}*u1d4ABznRe57tI_@Z#LLI*F|O>{D0_t{ z%btDb<awRt#tH4vWSG73Bzzz{W?0i5r(8DW*+%y?!%OterG3^FxXj&WE=J9VeQJAc zsdP^s>+-BP8~UohEBP}I3^DNU=QwgZV;V^c-a2Ade)wY7m`ds4C(mQ&nEksdtiIBi z<NLqX{LSI#!kbN7{SMshnB0=z@YBb-_W1-sV*)O9Umwd76ll7ZZ+zEctt>qvQO_t$ z2r+n<t(<FEch6nSQ4Eu#+ht+y4I7hv9UyI4`BQm{ang$N^tV6vOMH&1@9l$@M(MuF zHnD!O(c-$kmE!FZy<bD@8Fy6G7+qtsw02^e>&yp`0+i$N=pFksYaH_Wca#mU|NT5O zcFc%wW?!GdlP!G@?|-P7#{{mQ22c7II$iJNH74I5ax~}T#ihpEcU$6&_I^hB_U=2r zHI<FVoPD>zEIx&u+w5KvU*n#ZUfwbLOm42jzXO5VZp*kgHI7c)?Wp$k%D)^Ju2}=t z{IG0gT8&^Mm-~h*-OoMpy6|_T?4uj!*HE~j&NeZ$ptFALPsPgNk*=huMCs+(Urh36 zkMs-8{_avPc<Kk<Wv>9$8pDM%(W{XL1}`x!;K+UJ99WgJ@z-#kly!jCnL9z6vKKGd zq$8(pM7ZyAS}I~Uj2PHn5LGqJm@~)_C$-MGIK<>Uq01K+^OrS0Epy1~j^8r(;`(fy z>0V^6f?~f!!j~-$tLt=*Qzj^?lmEQ2>QZ#XiT&k;g@>PTj9mAcpZ>Ksj^$|1nxbc+ z2y!mP(dTBJ-IZ6>raYG74J{)(zKJw#l}fX@V^jj8csH(B3-az-|1!lXkAc3>(AFv~ zm-XIX9x!|97~|T)+$VI-RX-?~NBk?hZ_u$9Dn2Vc!#Z94_}n*VzIObd(Rc?XZs+Aw zt{tQ4aA`Q6M^!@2aFD)iU&D;1y*B5}Aaf-jp^avgEAukz6;h6A^RpSB$hux#ze1K{ zN_c7ZuF~7muj@5!S&b1fuJy)g2+;dif2eZ|se9vBwfy^18(%#tP0>H^{EnF&v#*+@ z>hL>MRqkXUE{`>dxmi~v<<xxn)3SxdW2O)6n)k37$1$essXLdxYacMD+1~zaMf<+S zNZC@I@pk-DH4A$_vh|VIClRU~(AUJr-BNedJZ{)a(MqdjZfOQ#Ep6*H*`?1bKQwK5 zFx@tww%f0MtowDjbiDl1;Q^cT*U_$jEn;pmS1zw^!wBz&ua7%)MJ&v+bN%>lN!lp4 ziWUZ@LZnES<Xs<g2M<R;V5vaT$E1<&8{IEnlBIN%zp>WYowA#Y9f+mx_tyPcujVM; zSofAG_WNB0QiU_L@jLgaGs;uWOIRTFRg9h^yv-fu#E9O~&Aa6;3VK#ow7Do3SAE^C z*Ho{_F4@@?+Olui44GrX&^NC=bwK4VJyhOu#QpEgSL1RCw`^I?S^V|GkSX7oyKhUW zuDt4VosH-2OF<KK50`RH*ic@45n3;`n>$vtEQa>gbhI2MzRrSuS<@Zr|C@2M?+opj z2{KAUA9ruTuzqPzY3>R`Yxh&l?v9PVufOJgc)rB?RhiSLJGAk`u}4+*h}-cW-@)s8 z+x)B*Mozdv`XsrAgD%y$!Zm#w%kDYeJ=G-t*|7vdUAM+ynlbQFMDLeoys@Jf)UID@ zl=;_H*WA7Sh)kSuVo{`KPv@C4uJzX%KUCrhPdUqt9qU^nX+rs80MKH?L}<~?%A!^C zTjKvTJZT-Of1E&Nyeq;eH#+9IcbOy72dY|n-k5bec<<k)UB_ed>uguoNSl6%IbX3i zMRIO4bt(Ve*SLRvOkY=8r)-Zk{!jPQCwEkAoEYheV=9_dEPv`}-kX93>eWLD)g(|u z4ip3v>v>mlL|5OOh_+At3duQ|l2%~JBJ}CWzZ<>cs#H0}akuSTgUmLwyWAnU_Kb}R z_<iFCQh~)%nEhq^vy8*2`x(Nn!;)P1W&Q8Ei^_lF*9xy5k*YG8WUg)RG&x6GHvN*e zbV<xdKcjl9u#B9bbLot)N4N+7dO`QAcIErad|J2pS>1m;&FbzR;h4PT7b)MerKW4_ zJ&xJh<p1NFXbe)0b^|O1sfKdK^3ID&Z&mNi{<ZI%k6caLV-hHbh1r9hdrZG)Ck&qW zwDyGs+ez~3FC#;#bhV<z>Yfz$^fCQ9dC8Gw%tb}*B<=Wjp6{{s)A(n){xiv`Yuvq% z+Y!c$1VW0x>7*gjsGr&VmD~GRLSOmSBg^zkd$X9n<3_wc`<M5-TrKbPl|S;DTJm0! z2(G?W$?W35&2zu-)_u_zlX(lm6dpszv8hOL?UtQPvl^cXzNhS4_iKdp-^UUtHzjw* zINR)sAwNdHGv40)=@ELR3SD_ZkA5d_(VFXcN_i{!euU9SR(9+n&ml0K=BeMu*DJd| zwrqLl)%fP=q9w)9|DsSr^Az@t%U^P+r4g-_(v!|N=@`HEQ=}Mzv9@Cd!Zo_F&`4Gb zUm$n)zP2Lj*TgCPdKo5lAPB?MEkPSRoc&XP>64XPLNEHn)P_Q1^lx%*tst9>7A5wF zd&VhmIWD|$ewwlDH9j+7Qe{F`S-vS+SrzmjBCp4Y{&lk_PG{Fx%^^Q!#xCx9`?tx8 zZEfW_>R!fr`3ak!mfR%TVY12Bv@el<@lU8pP%Crd^684PI=BDm|8UR!k1E$y6r+N~ zI>axDk8s68p;!}V_@E=zlwwcx{`b3gR6er5!saekiT1MD!mjOykPy;vA=}q7_WyDd zyirlzDO(L-iE#*8zVVqgj_7rt#2MaBrs68@G>wmKmZBr&T`SHFp1DZw{vGM$N}7`> zaCXi!S8HC6s8TFe_O8!aoaeLtQ){pszVa#8-+AuHgZEmN9_}@ef<=8O%1YKr4;6n} z!}yp>pG5~j6usX-;G?awZ@_8pOr7U`@dFmWqWn_WT;@awbb`oh0SsJ6d6nXS-aQ+} zn|m4mx|M1oGVeQ7)Y~2AQBm%vWdnj8XNF8%K;A>6bpp3?ZTM~DFSn(S;X_SPx?)NF z-IArLezNIP?{Smln}ZpvLw2XcQS4iOJ6p1Arkw1W_ux$SxS1~h1xa$wja*s{An-8o z*na24);QdA%Z@w5o_Eg0TH|k}xg!lrcT|b+;z;?dTvyJ@nqLz)%zkA?CB}%98=A$C z!Me{o9X=-KNaM3kz4Y7IH9oYDdXMFyh3MS<*D&6yI5lBZwqUsI)H!mC&$zNr9+Xpv z`OCSD&cIb_|L+9U6J0vcee+hS)LNIB2MNEBYJ83R>-1|)Z(8iL%Dd*pPb8iFs~BLP z`61ORn<yH}TJ|Zz)>Nxr`LDv4vLc<N`FBsqUD=9YS=uA70e?9;Q<a+Pl>+eiPeaF{ zRz;HgL9w8-HPxQjuw~4D^7S|GMSO#v!1uFO(Wg;i^A{J#L@gq7^F8HuYGjV*{0y27 zXMx$spDUdwj)|FZjIynC=oe_ZqIEB-tDN5k)81}D=-1LzTcwL}ciq`?&-<Hu2IaUv zZg8Q|$(8U(wKOu!1CZI$`W0bv;*H0L0!u_I%a5*fzp(6gmciT$qt#ZzI$cYB%l*Qe zf81p|cD^QZPz3cV_kGmqeYf+?H+5yrzsqdJH{H1_9Uw}GXIa)4t<uJrKdFR%+{ybZ zZN+DsG`gj4=%p@)C{Wn)<}2@iv93U^I6bz4QjX_W_N1*k?O(b62ifsIj`vCPzx6Pp z6IerYTBGY&b90%|t!#|LG>=76V!v{SVU$gt)Kme4-fUmf$2q3?`L}KM?^8&yJCnre zXw6;n^HYn@Sr+5tSKs_B%b<Dq=^G`?;bD&Jdc9P3*NtMQ=IOlm0mby*<Hg++*oZOU z?1!4KmyR_^cLgv*g8dNg&>_;nV`owCEPsdgAgqreaOu6%A8r@~i2RKkf!(7Qk%mH# zN`FMUG$pUs(;G7`zbYgrHDeidx6bGsEkm@=U1m_z@#se={XOiIZ2ui+XI83Y9VZbd zI|}M;auiItTV)NZIi+zZ7HZttmvaPUmpG}yE<(R3*SHOfln;KSY8OQ%T}H98X3x4k zdD~wvQ*5og9tHD}>YvfME!6yA_Q%i5!M9GfoA|9898u8g;UyVQscv`o^WGFVk#^Mw z-Y>5sz@ejXSj0(}@x%x}tGu-reSDfb+!V)u&VS~<b$ze3!d;96kUhHBYCF|?8jC18 z)cLhOm0hiJrzw+Ut_iL?)9?A@xR=#G5mA=$8`@fy2VqupQLM_fwi|4waWhq!lU@H) zDk)4Eq+Q1y?(n!>u49MUnxc>f#1|>ic|<Ax4oQ9(wwf812gBo=T}$HQjMR72FBXoi z4$5I0S9GoIrPugxT_)a#lg36E?_4!{#Xq+g2XHj6Pg8~Up3PmuSBCI)B3mD4=4>hK zK{s&@=8<Q8@xd`>_feolG*i!AO6m+Ek@)YME$KJb1(aV_p55$TyfK^8UXkkW94h<Q zT1)jOzXU}I;Y;Z*%oO@?y6(<=4t@tB37R_>t3|k6f*GZk+z^!n`o(m}Hv61aK{aJb z&eyxf&}g#07!|b!KijDFH!nQ$>M<r#U%c_-Nm!SiE$X$y;zr4(kBJLqMwq+S8rbXb z;_ZxTR{7wr3o)lRRP!Qzbf-I)1V%JgEPKv+@(iSr55ncwoOlM8sdGeu>3H1EBzyOF z=WYEf6F2Bgos;bi_eTuX@jb$PR<pgxL>^=vD)pMzurpWSr@n1$FW!^nOF+~d)GiH- z|MS|3f#x-X4t*QnTwU%kUHLINPj);}=QHr!o->zvYK<T1$D;gGQfP6TBmSk3of5oi z#Ib;|w|ScU1Gq^j4X_9-ee>;9#j$sXc8szc?{2*5|3`M&8P%_EynN;E-IBrw-p5yb zSyE_ITrt@!U9~H95yuaFvaaIVrz?XTf4qNuAW$cPukPk=MibeM6|@pp<zt0HE2JWS zdh?0Djy5+3HF6gAc8%!RrqDh4r~GrtXQz9qrMns}6A>AlUhsFvk*+DjE}S~ivMU!J zWBKc+D6ocfeJ}|JMYxs^!7x&<c7G9?^})GsHki&CV@(gWE&9AyRrjaaX#VNjXV)XI zjpVP-_+~g(tozs9lFs-i9n=4ydN38+vM+8*4!kcpu@6O^o8+Yotrro#C2;cl&Ww)G zpuclnr_cJHj~wjVBXOptqatyF)a-6LJoe$8%(q@C)ckAl-)6y*m_}`61-5lf>k4WX zGzxp5G$UPl3@(?!XA`qb6L-AX=h*&E)nBrf@|f9c_|QQ_VCkxt)vs7k9+x^ywwwcI zN8HD+GJEjJg^0JJz~liT3j^)`fFQ^nTc#P64C*l~(QD(w2kYMJc(rk3sO(|Y17(1w zD=GS_bW=$jWH5F%J84lZc}4m=`}gwYdQIc*MKBZG5#5(DgKKQFo>pUyAQAv$Hj8lm zq>%4Aai9X`i&g{@zpVK}_rYnuzq;RU=qPUeAzERW{>>_tryxLzoh#kc*aRmqJig2@ zUXRz(e&S=af^Ar@oR3EwOVkNqyd`EN^i^zAR;8<478{8AZo7A??;Zb#(G|ODYy+A* z>AI>&oa8jQo~@QDL;f^&7+Z^yoZlPWUy4?iZyWLyK&YI@RR}hX?KE~=IS_ZOaeeB| zhodUC`E4#N&D@Miu|)l9)VPL<n>+l^CrA&=oH_)XDSVJ#9Hk<63VU1i1C%5BPv*&y zSGyXpa8Jj+)=R&Czq6~UJ=&jFHMy3g{-5JP=QhSje*dtP2w}2cGGUW+<Y=%kH}OmK z#Nq3Sr`!^nAAf0DCtf~osWJZ)uBF+!$n`+FIayg_Y$`saX7!)8$47LOTGbp3MM2G3 zQ-Jq4jU#FpnmiCIrH(6Krd75saN6wFa0}LhVKx?!{mvKgbi3rnPYfOaq8dIHx*#HA z*r|t8fNJAyGCx`!UpXzUq2Gt{EHJ#&%zzEZ?`k>q1?q5=d$c8TE85+#HHCNfcQGHS z=gJ^Wdy<9bB1@rdWESIY$9GEY<?w%w*^>~Bml=6frL~p<1XJ2=l=;Gngfy=h|6*oh zG-D^?9|`~jY7JImL@QHl5%rCp#+I|nB(|gLy$;f(D*MjU)dDfm?Sz4B8ZR}==~od9 zeppf*$Sa!h82hWtq4!k9)<V{>I8q3z?Nqr0ptwc>@86>e3hn-H^cq+Kup_q%HtJa_ zo&nH)7OUyFsi0UZE}E;VzniV`=plH-X6k5m3IJ^qUGVf_HIL0_357J|Xn_H6>5eeo z4J|qvjRPhNns416wT~Dt1N_QwVyrEJo9Bo~>;_HwKsmKWUY~!1>gO&W8Q+*dg^^qC zY$PWoegWo%_3oj|tG#W2bEfvBYl6Tje%w~Pm044s4z)#|kFVJ`p3u6Ce@1=5=l27g zm7RzL<SPDbbvI3N=IY#w^5|NCwXA?sz}AOB;A+au$=l`VdgOJR6B$j7xFF6K=1l67 zF?p3F17M9*rR!MnY&x|3M2*%_aJYZbn@w^0IBUFhT84yAcKm5r>aw{Z{p-E&s(QhJ zKAw2QqiDbAyt2Eldj8HJXu{1BQW44|{3AXaPWB;#%GpMX!f~75L8k>JT{~5@w5bEM zt#0e%5dS1A>=uiYPU}oh-(MbE80C{1!FY&7Zy?YX55xm?4G#d7nZq7^wa1GW={f<5 zAdnA9jI~wk+^)R27kye(K3`bXGLecd8m3YT(NVb`E*@WngT%?eClns`4RDojso2cK znY9op>h~Q%BRaA_r9FqmmGzEuc9r@5ZUVDl^j>V1&NavUQ#2e^3NvD#Qm=N&3TMC5 z>|W&D-LOY!4esOsyBFP5-<#z8GlZ`!+WDs*iO(4O@ZS%1?r4qq2q#F~xC+tz6PoQ2 z8(ir(3%|G{>mC>DY$yVT_3R&X@_0reQ&v6Mp;s(=zwYRkgJ#Fu>yG}rsq-CEyCpv) zv8F@Ux^RB%`IEY+?#qJ@I2!)M#D=+#M=@lWgT}mZdP}TV(iCS>8>6KWbt@gyyM75i z=l|tILWl7m8zJRhHH@z9-f@<6W9hb~%c^$?rSO!`l*A)%aJJKHJ9MYc?NC-l#MDJQ zrmZ_+Pukre(SgIi%CgKTKjHt4*M;-H;*pokqmq^VDk4ErHrw)WUqF6shrY@852H2v zRJ(WAN1DNA%Da;|n@7Lk{5pn(ophzgEt3Pnov6^47nL~*r{OTJj{5T~vl?)A?r+k0 zgS8@!BmS$(8y28lJGN||dqJn~cl?e24!;-w__>!<zJYJrbtg>M@xRtnNl!F9InZ@x zlG3vJkyl*U9<yL=WqOWD>eAxi#`}LY8~MG%2!Cth1iheJzCqardsyCOuSk@+2lVi5 zHo0{&nf<A=-7~l=<Zq<c`n|k?zx(UNj9qDkzImDE*5*H=dvR|*n+-GR)x?bC3S(lX z<NJG>-_CYx+I3hr&QW~*<N=TK1U=Fsf3^~d+N!Q^P(P9CyNQyBVo9t0T0`;&N_(}V zvv_vvr9Z|`X!bS5-oq&0&qVAOU8E+BBYGBr<P2dmR)t>qQycoX^jmf7k=;(q(@V1^ z+htuNm0jWSZwNp{9V?lRHSB=R&Z<pO-oUk$yPHKz1zJHT(qdL+93_%9Kj`Xw<n{aX z0~?+3*0l!!%s=hQeJ&rsBW?b-FRyl|I2sa>Cc^Rhpt&|dzs-YAAEw@FY^tAf#Ia@M zn{RZTt9au%U-@;fHb<Ccf%5)m>&~7?j8h-#?|(ZsSJI!J?3W-ovMeqRcv{CXvkZ%k z<uar$u{A9!x!5}M_au9?Y}@OEjP*{t5`6Q_ehohrw`qIwTr%BCmuvOFJRivWS2T`} zHf_vBp27D}IFbrtUyakWuFz|ZE#KDXK)au~u6}aR(5~(3plh!jKS=ImbH!n8ABOyf zI>}^@<|nNYT5$@rh#k0(CTcqa{<!HJJtTexmU&y#K0pZmpt&k6`S<T{x8gzue$otI zNi`)hN4py(=%%j-!LWu}TX9En-OvfFTEGp{^}NI3h-JBtZ&WLHoUBurmA@P{N%WrE zMh!+^HIR@%sPp_2m`>hzJI84lT3Si`zwzcS0JU<ntyI?XZG?TbJ*^Xnz<FG_2t-Gn zxET>kQvfSIoacW_Xqw<x&syuJWS-e%e|>kCa&3(T-lwaEd$&KfFg(PKkgFQ2@r#hd z!nVZV2&3gPQ140g6ODzxin+_18Qx1MQLo*1`-!JNo=XEIgL)txI0_EFa#$g7{v@*} zOX2TpjNQ5N<RZPY-4KWUP<BU!3Z{ck43@Ye>q_4H$+wrNd<@g`sGm_0m&Q8<aH5~R zknA#(gx-C;=73o58-&OtEWNB0&IgcU(iT*c7V}lISwXQ->y{9<*z1_zYBwx#M=%SW zi_Eo|GE!=9{fAd*JbQ@d1+7w|iBZhGTBWfK^ZD)Pjfd8Oe7WvqN*GZId{Y<zl_Cat zk-NmJl*Zu=@+`(&A96?X(g+LKqphlWMFr3MBUy@(+z$XsZGT;5IZVO;(q%|(XAkp^ z&J&wE*ZA1*{aW*k$1C+Ss9wABnrO!{-8%$X{A1B<C<-gci%+V*Y;2&8P5hw@2u#!} zw)!PL?&LCQWsa0*iWn`bFa@wR$~%7;BG)Xf_YRumr{|esS>u;4Bz(cn!EnmPWw7cN z_tyt#lMe8det$_FMhH!O5LR_jzGkl4X~C1)p=vrTcdnmeLYwQhC)jb)qnxO_yYUdv zFKXwwdF_VUo|!G`YIRkfRe0~^13Zp$t;xLz<U^_<fz)eBbJ@##R%TzacVmS?H%)y; zJd`%0BxIj>54Dgr_&elR|1_b96i*vtV8RAW1}S#1j~=S8Y*(j~j^&=pv5n`Kh|6n= z@f0zF!pErz6~U0mM3-=^TMLZ&)@68LLKtEZw^X%nfEu@5xQ>=AYCaW*P7R_}(&p!K ziZmx}merr$CvjnEj{nIl7xXfE4j0)|iKsXc^u1$VI)|U4%gAID9)f3c>~eNh67JpM z97j0Y9H{i#%R8;~-qS$LL7`_+);y3U{e{a^d#VuxtYeWfMy@9<*K0UW!9K`2ELPRH zo0Rl6Wj7@d?y(k@JD7wqP}iULL{5mhSpt(jnq%lo)KB~mT-`Zx(&)HTHTuU{4zcid zsfJZOa=3F|9w-&<a^!8vt|erZ5#7J?5F)kO;R$bQ<-{AE%C+Dtf?UJ|6Y?g(68n`g zp9~^boTf2GR_LI`$tDmv+R8+C!t*{~h+!qHB<^j>_<X|hPEa`Om7houTv#U}$1HP| zJ$`wwzcPFVXrTQ=`_%+YKrg@u{;MQahE)RDP)j6*0J>;W^OR$aOh0Q1Fx|jNGAK!W z7H=sFXdvkku23(**FB<F_31uEcxZ?;u6CN|24ezH2b&?n4ZbVs6{fVt*~USsct8#& z8Urw)C^ofdMd_KX6P&I(dVuDC9{fta=e}?*A|(kd&*FBK8qcts$6-m96pGU(9}q9% zUexBj`ro1!qsPCo8=0u_LKzn%tuUgT8h4*zOOocf7oAfDepi!-0VWow1B_9FOD}{0 z-xYz!AaU%fTqECkjH5SMu>F{gGCRql5b_5H06=(_fg^00Jn}-~x=Mq_W}}@xtq;sk z03AW`M<^kN?{HU*Y-Fvqk`#~b6-YC}YN4qhPH?3_1Z%R&4-P$cA^~k4=wlJA3-ou7 zMU*V`KXcB$RTHc-StMt&+*(W91&)D@BQn(lWF&ek1t-i9;a0xmH2Xsko2Ss-F~5lF zo=}wTdG=dMRWw=}BrHPsLV)<UIT)j9YJxH<t}?>bLlgQ|+FAMe@hXg0NvG6y1)W#N zSdJpL>=Xh?i8Hf-9wYHI2wu=|2Vi)Z)UG>M`j+IuBL=t@rE6hhYv>5$dxm?d9MF`Q zAu*f)g%DjVXgb3$JzynrPc`{s@50ci_R=%LzR&^jd_55*46!cs6=~vx55~AQ_Loz$ z4N8M(L=l!G4fK)b&pM$*VZAaL+z8Dd!Sb<URE1Sa(FY3_m}m4bjeepbXc5<P77cW( z;O3et(kDH<J4tc6f-hZ_DV;5!mXz0vW&mm~dmnQz1|K55>J+b+FLjUG>I)uakHU$H zqi7_DPmx3M{f>~XWHQVM>?jvev`p1yl2B~IXup}=F5|Ba9Q$GY&GHy`bLRja50+wb zbgI%swM|$dQXII^B~)$2mB4`BRNkHQnA0rd9aa%6kVj*@|9O)#7UH!M=T{`*l`=r| zMBFKxr}j%mpQsmh5M&Nv;AUFDxCe8BIi~;*lQE0cs(I)Z6E~sOP6}SCtD*}<6EKOh zv0LaLh}oaB73L9f_}@aSyQW*DDp_Xv0G6=4AaO%BmD;pU9x8s3hcms5cWNbD#tv2D zL4{<La-4c7%i~GTr^xvyOLqZ%i4z#K1n%HI#%(!DqhsCEDnF9T63sYfIN%8IAQ#y< zu0K4%460TrX>!!vR@Q@C@5t3PA<8Y0AuV38i6f+!YIC!J8vL2-j?qG5@$%ZGBwyHF z)>yx>n|%W(XIf9M)p=E}E^^^mq<Q3AJLVlRKu1dMjHmgQ#h*rp!9U8z>%<xJVS6wE zseL@RG-B60yOkq{dAcL(Y%bdSxWeKG`CB9_aEqWibPF)(>_G*<M_*Azz&a1{l}J-L znUKFWAy)x=SzxZ{rtt0S2@l9$Yv!sM(IapTSz4%l6(HMP*!&K*r+K)SF3zx|m8Iia zqxQ}%r+nqecNQ#k=Ho1c=mi2X)mo1X6&+HoS0B6Qy3HSW1gd2RM7^cXljPr!9H<2g zAt7nF%PG8Vn2*$rAp2v85E-$ZZCAGazq6bwGYTLDyz%cq7LTmlw)bCZ1=dx>l!%rv z0nmXe?P<OUaKj_7^QhEIX9@T;Oh0;BoN999ax>bj0?uGjI*Q>Ql22o1lEgKo^>aq0 zQDCW!ZLA%KM(7mH5;GN7p=^Sv|2BDY6L#Cth9qD<H5gdMto+{@TtO;G?xR~dA2%lZ zm&scJeTF77=-UbB5^OaOZG@+Eo!@d&kLZP)cQJ2C{98nzi5GuFPe9P~1w_P7RVE?@ zMpXmJ^bbyN%Rma-<1Bt*2m;tu1T#m*f>w2o^rrTQokA2AJ4|hq={@gN%ZAYHD-KTB zdHNH`VTD*f7Ibl_kMS%uR8(fO*hS^pbT#jv#7X@-ME`q&fVMgBfpLUEzLDZ67ps+Z z#xzvG%$Pop@8MI^9H&PfRgLh!b<ZYG>`O&%Y*CqyaW!fsKDI|**~whLGdAZbE+6s( zFy3Kc{j(pm>TxBt$3-l_x%s-!tIgwqijvu=MI42CO~ACxMUd&m-GniB09DqzoJk5A z$N5o$n8ro#8&J=|(WvX}0ufWNw4%0*q@K8AI1v#sgE_e($)jw=nmgxY^(8z%%wcjo z*yNAM2Eym!JlJbQac*bKbsZdSYMX~v1yfly3qL=)eufCq)-rHQjYl5tMaV`+kcjpO zh4V#>yq4RSR7_Z2j@n`ODWO}=gtr=_-HNX&r!H^yv8sFs?K-9I0HChk*+L4_km~>S z*}{mYg2~oq^*8O3H7g1774<8h%ky{oeM{i8nD(z*L9K%oBsEmqg{55^9<|9|KeGX( zMHF2EPETU6G}MrzSr=BRJL-TPmf>K-g8lDA6XRp&U!Jd@jX8Fe8n~fsT$d-LC)E+> zCJ7Qkw0l`bsqJ5QWRJdHT~>MeWRkpwJ;ZlO*eN0H19&PN9&cAWI*7)#SVD1ae{Mry z@}J|h9$}<Um5JYdO$hcPDT~7pL0eqb`>S6bA==8@W5oSofF_&w!z!?Eq`tIt%kZ*C zNi6F2sRTnGA99%RCqDe8uU2Vy9z!r66K86gCpV}AvN+ON-InH3t2SA*TioDSl6PhZ z-PT0O(K!=RJ!;FOHMT4PjaiD=p%Mhj$RBFN$td15V3JZR8duPvz*02(l@aU%(=DDC zX+!?fDCC)-h)>vi{{5>O<o1|JF-vGR(eC8PU5NFo6T2Til9rVU&vk9$ubz6Js9WuC zFLO)y(mvQ}yr2r;{-6`v3I;CJ8jw^G_4Qvc7P<XiBA_7JmUS>K#^?-xvonbvb9&Q+ z2N&wp)*+hL6q#Ilz5vorOK3pVita_Ky{@del4Y{8`L-c^0836Jv7!P**GM-?;s;wP zxQRqupqSkSiv(eUykrcqUya>W1$<5T!+7==S!2SvJmI!>LM1%Vb6q)te?oL4F>rIC zVP-ZY>vCrstjRrtU$gjpu0<zC3%X2*g8dj5T9t=*%Yo!bFx%RZm0T*qjRVC324PeY z34Hq+xjXV(F{Ko<!vEck*V&^|?uzM^WH)$%_OP6+?*df*%>$<K3YZin+921-013{S zE@0a)gu4nwgt|Y;9@}*fjM!F=(09MF-yxKC%9-!yIftVe2c#oW;tjC&(wW0_3j^Qt zSJAxb0RlfZPfVKZ^~j3~0~fDB!9R(1T301tMz-`16D<pi$}W*3-X&2^!I~g!D0E-G zUtsg%s&KOf&NPPXt>B;{K5liMkoUi#dS~cnPmr~U=#}#|t3In)fk~*z6!8)o0X-$W z$yu8pZ^=t75>eC5NvIu^+qYGV$zjENcaw6R7vFPdQr^@?^c(>O2-fI{))I_TRlwvC z#4#ENa2R9qgMR)1#?cC=`*%ps%e2n6s9*pIRaS?|g>po_@@36wIqJV+kI~;LCueM7 zRmRi3nCi1xfZKvZuw(tpTm3f|p3+NWEy!C|5XwJb43kL5{5Jzp!KmWCI87A?6{qkF z4D6H0x94auhBO0t`VFOv?l|TLhFl1e0-neg)2(Jz>h~J(P^`I#UFqs&TlnIJ81wWa ze0OXMDWQ49_ethYAUHeQ#NOAtLxiRvZN~27=(l?Uv?55Pd`0;E<ayJ|<|?e3UaOP{ zbY$%c_SqME(pKSex}#`^*EE;-pTzVceOZ!aRuE>9qk4|@nqEnb;&eA~)qCqz%aC9Y zpLXVuaXA-Bm?M&bJk1$;9k`-)%qQH5H|EKymFT4aO_0)4G4pqg-}m0*Sg1u}D6kn* zLL#YRsmUdP_Tjb*@g)YGLBb$>hR7q>d0RM3q@W_F99=&(ai%P&B;Q!*3DT<gS$cgQ z*LF0nP%BaOC5+h@M!swXI3@C$<$?V@(1%DSQIy}L$d`*9($7%VoQ<)k%94na@x3Dc zflO4jhsZpVl2K<K7Jf0yWF1C26)DwM(m$Z3OjU#om0!NFA50Q8L|Jk&5}w%bob!~w z$Hh(|-Q$R*uqMhP(GgvhR~_mP>!`t(A^_q)iGhc`x+=&qC)J3Y-B^zpQy-xpD&|lN zgA*+p$$pvVv{!B>OTg~BbhaVEM2UJ4pb`M`8gqLYmh?9ZqK_%*n)_&9AXZM;l;M!1 zH03Ooy{0<;AsX?*owdgf>hEqMa3UxoydM?>s<h5+;SlrTZf8ooO$foPMXXa8RZgc! zBo4c(-t1TLhN?pv>+zTbQB-^2A@M14eFlGUojk@al5!q%_Qz^tz9_lg#5C)Q^m`I2 zlkJ}H2E65t*;SBDftd4jg@BadkLpTwhbe$xUuR{86Zs&Uq!}wZTaJi5+9O25J)eM* zUCrEg?eu~TbeCaO4k*_;M5mrXT3wWB@D6yKmnt`tMF|j*NgGKxvBP?CGz`+kS%%p= znZ?5)fd6q@FyK`3Z^L1Q97vdEbT6{>5nJ2eBFAwJn1LirW#S|v$n&Hpp`gxY?4n3~ z(xr9+#<OJz@a872<74h>^?0Q5ohuy$D8&ynf8s3=YQBM5sU0T!h;OePTO*J-F(w2S z3#k=R2nUX$p<0pqFAb$8x`sunedIu;Vdg?kBiz3R<F4~M;5*bIzz8ISxNWR%GkOBA z8np6c3XXV7TomGr%7;euVq6<<cH@bw$<m4(DZ<y2^*FE_pDG>87i=<i+Sq$Ppr3IW z>?tW78mBM$vc5M^&>KerKAuU+@5vm6TE89ie%peoWW=qgM&du#0~MOu35I0drz#yO z;r|~^=K>aGoxXo7O5F~mmTiUL#@Kko4b6l`-rNquVD5N6B~mL!WTha8qrjAQ&@CAm zL`2sa6BJR?Jf$E>S_vcMB%r7%s2oN>Im{q1%*@;W^PPVGYp=`QRhW6-@8LPz&;8tw zxa~aeLawfKzvAmp7g&|t8k~w%8;o2#2NGD2|L~1mIZ_`H0=;1rSFlFyMM_@NbIIsf z7P$xN3*N}&0HI2P=0yP^dH|dTSp6JUz$?13!Dd{h7?GlqJ@avmI)jK4G+wsae45Fw zHei0q&sU%qGH-1^j&GMXcoiDQ<g}lX^RED{6g?nV{}4&1%%1H&flU`yTo_|_=YDPk ztIQLaHoW$<TrbS&s=oj@*Lf+fp`=SN*eXMn=CXBovLhPm*sjeCmn2s{<So6j9NxKp z#U_A>YVJ7=UVMlMW3QqPbO6i?AE5`7(p7O&BQ?r4+VaHW?)yn97g!I+Nb7l)_`{o} zO~Px{C8+IcM+tAw0*P=;)du)%L$CBgZeOci0C}PYCh!l2(M@)h62%a=rHbZRGDLj2 z^#-kvj$OV?-$Q^9e_`ACAb;B%qx87<XaYPg9wB~aJ<^#m7|qnCO`2k>BLMr_3PM=? z8lVTNftU&mYJE;OF^87Gi_DB`pW4)2%W-cISbBBnl4=2c2l<ZkEIR*vps|`r1)ER& zPR4EJGF$O#sqdqCqotCIKCqvhY|?v<8YN<=Js@Uw8w*s%X5jF!R^l@wNP<Z(@e03@ z9`h<yI3<@A*Ni;oSkJ;IiJ5@ui;yUr*DuU1cp7_ea=f)Qqye235k}a4fjldL2o_i( zrKK%%9PvyX_t#K<b;d&~E4GjCY@7vg$=z<R#{rFV-B)d5(K@LXml<<hqa7vGno*<g z%P=0i7+Jdj_%JDRap7z#SLxw-YtISt<QVpBuFD!60=$0lk<28dZO;(92v4>p^IZYL z2~Fy&RRUR{EN^fAW!n%46;$vtgwYaRTE&@ut0S++0+BBy>{Auac~CNH>b&%3Ra3@Y zW1VLqUX94<j!F{c%#vJu@MT?sW&G7vVhQZU0s{T|T{owR+PsM?W5666+N#Jh^t^|# zxxKcTmT#>jOfF1XZ>-<;ks;%6VB-(06{qQwtxxG2^1KR%$cPC;YGqJu5Qc&`jT~9q zwJbfLw+CE<m$K{Pb`Q8xqDn96Iw{@D?R+3gB!PCWew;^8l<pLIqaBJ8X2e{A&tCSe z`EX9L5U6<p+?yUbec2Sot%~`{BQ^B)XA8H>VE9J0Xr@O~LvRy}%k~fOc=<c3)Tj<; z+(lc{VIG!T>4&(I?%@v>f#l%##|Xy5=<R{DE}HNE*3@w$_OR6jPu0-lKFMp9CI(zP zcID;?yUomb9OnT^MbG;YjY!~RdAipS)g=aWefK#_6fU+`ZczK@zXy~f*n+ZMqcGGn z&QBaULf5NR136a&#XtzAh5AVW*XD?Z$w90ZdOezahJji928uDNo+W((So9lID+=%c z|35S-;z~1bqGxSCWrpWL5FSA#k#2#}+#d{KU?FLV_O(GJDlaa`jX!HvBtEwKm-I7! z`e^Sy2{Qb{6#Y`$>W@*A%=~ZT7)cB_M48yPtKRf4@1&82T(SygGo?-XkKXzICax`X zoZ;WE7>xg6|M-aN(0O%6y)#B|Hm3%<?)$8U6(s6C;x9&5<Yp{7l~xlHn81PUzTwk! zy})mvn(7|scpIT{S5x{K#Y^mlr?y)vn7#Ni0J9guo{D6T)>9y51@uNi2^?qq`swmT zcBOE{&Gjzx^}SG8Q9~FP)5_t-PFS7x=5Mx@WV;Hy<8(2YyQa=%d4=U`+A;Wv#ah<{ zz4MkNqS`&1)r;xU;)b-S3KR!QUj`p=mr>H?5CrZ@`A>gVw%BuYkLJ`6*s|u6ByiN^ zQmk@_HcfyVgxe%j1l$X4T`Z9PkU`FNZU)8B98fY<5M_@t&mWZ7T`>{Au6X|NHR7lH zda)b}n^)b9=7DqyQVGxagCDzR#{w4%Cp&4Rwr9$BqKNapQ?iK%-Yb4kJ^~ou!ywv~ zhuQftUNr>IlK2^`cKMEL)rgp$g}603ZPlNBR&py~yKw>2=J=J&_JQi-;1j^g6aLts z+7M{B5i&4bVaE!oeJj4GKVFqQrLWtuzbo`W*6$j$l|-p(r^31MgFx|#4Y{0gX_)%< zow|&lH;H1F0P&Islq3SX5LNWXb`S3;aesP~+y^vrn=Uaq*96eH5b!Y@_k?GO^!>En zet%T)eF3<Ez3*Rb%Q1MCB$)cbn`{9O6BW6#&?CM@5W2**){$EXAS(uutLqFf+D$_d zm&s8h!u&nP>HJ@JN0Gj0U0Hsk>gNewg25QZTdPXlRQY3I2^`C9ciZ)4tFSNN<4|J* zg~re-sjXq!vtcnP6iK}{kqnA*5K+~AyKeiacjN(1v?a6wcs2DcCwXafKxakX*8Q7R zC*@1z{#MNP%(>mfSz;>l0;%0#RrVIpO2HJ&Z!JJPqI$oDM5$@Vtd!pi{-t#;!!Ym! zi9X`SZy=I#(k}SjvYxkEVf)og_S4_5F!ZSFkxvY(reskW`be}Oh*WwOsHqlkK(LLM zt5W?;xZ5z_8*&GG$=jcm1ZalP2X&H1M#na41ylO3n|Oe1QA}I3R~$FLZZ0=U$0pCv zd<z318vgL7!O3_&tG0WjB&1ob1f21@_&F!sf%K?3pqVo5&p$wT(5Od{h;JJ9&*9+4 zPMhdoK|(7goA3;LvNOY7vOwQ%una5C^6QWtZd%*KBQ>g30pxOd*K?y@%C7ei)xx7> z&;{PgvLNb;U2nbaA44E9$+w)!mI;0q#^KIzi|}{FLS2KZz9rG&Onrk$&92j@9xuKX zAo!(*9@Q^MPtd7gAb+~IT$icZ8SPBBye*cS+&%4w=yqJ7(ycGSPMxGMzJ~{5u43E` zT=KD;t&f?5CfXbV-sb*{go2?_Eyq8|2O}<LsHtOWf?ysnro|Lsh;gT!2>>?R`&hO_ z`f^mD9lHmVa9B9I_{uWr=68qgejwS}!1B0v-`_Ns*@d~;gB(TULrU(hl@%-I+UZAz zuwMbt6@wx!8(v>W0Ac9iQ(Oi7A?t0sgC{*vF-0FVrTB&@?i`>Ke){>@<@0S`U9!Ah zi`0NDkS7mlKWP!EEXR-Au4-B1dZN-3)s;mS66>dr&&haeEww`sNj>vY{<-kiLSha{ z_*z>Yf=>!Ks`cp>rDuil2mO)nAkImGro36d<Qk6i#}09DcfLQ~2scrbY`8zYznN|2 z`y5t3(_&0C^#NMr^PKjUrLHF`CQ5a@_&+ZC8)ErAmIJ(xNfTcaHzNy7_{sW+D$L9a z>}sQiX_plziVxot^i~=7Whc4|GKXdExogxCqBY444;5H764E*T8kBO}@jElh*Alv6 z3rBrxj;LI$3v?yR6dB1eXG=#DqMU6?k4r4J=g8V`%;PxV5Js%`GiT^j7A~)-6N9t} z^q}zBF$v~zau`!U7U<%t^j8Z%@{cw~GJ7bS3}S5k&L>s_lIM~7QVZWh$&Y8Pm5HOO zLz~8YoRIA`1=#CJDh6l|T+kG(-)mY$(L6ft_eY*G>Yk(`w?Y8db*R4eGD}Pc@=qlq zmH;hlNWzf?caDG-!eSIm)Z9%U9L82GlnHE7Nnz}4YyNA0pMg0gVft|vECV{f8A*p5 zh*YNUIwOLzDoP`4V$Y31XL5_(p2-N0)~}_!<K8fNVaY2)s#25L$4U;BNpC|zlyXlA z2^4koV9d7glFuLfs{G>nz!n``u}FIUmJBG_1!E&!<N}m&?RTD7ybbtUC%Okkhs{{F z)*2cOLFgK#K@LAz(mTZ+!>Bdi6M99>#Bp-<jFkQVS}WDe(~`}lM)Oq_pEiaZ3PamW zh@-FYK1$Y1oQnv6w#3h!`EXZ8z0Q19B5hfNN5rnoHM%sEYkzwY)+<z3&4~E#8$%@N zUQ`hdpd8<zag`map&Q2wakcD~D=sD%_p~#hsYGF)tr>gF92OE-8Ew!5#kFdM%b5Od zW5^wxn`5XD_OH>UTTf><rtHJQ;o<ESp-n-@$4p>d>Yw+)kyKDST_&_l4GX_V&sy`b zK8Y0qh6=s_14mdDKp$zXAy`!CTg18Y^foK1M@x4GE%noPRqQk@tc*67o8LTaVuu=X z>EXgHKHMiB>=_FQFykQnqgu0LPze=85bL!Z{<hY+8s++Xs-8Oex8q!rRJD_GYn5?T zVLuFlXZvEPpJy|_jF&}u9z!MA7W~)n9Xt{9u+s`PgbLVV&0&;gQlrvkebeq>?K4_v z_t)l~DK0a<lIBZla`8Psq-P+j>5C|r#2jT)I|>yJOw{}U0bF=`?=0>}Sgw=*vw-HI zGU)}$xD&eFZBm{t8us)xy7<Wfv}cHZvKM9!DSy^odJ}{=_<-P<Fu@Uec;eAN`}F?> z>}IVmWZ4p*1dBUX?-y`V80-1+cY(X#`}@%=R>I+9COtb4O(2gwJcqlrknAj=JZ`N? zvEXqBz0)JvJ~z>{#5;--1GNRS7*$hO)<Y_Hk};YjBu1(D&97EGdiRw$0T1!hofpiW z?MdTJ3s+{8P;!-mj^}m!iX@&3*HuF)mT?x6|A$d_>l`T7q&OB#1TJyw!kj0}I#rxg zTpdFH`6T?R)sLe$eDs(}2XaeDidhb8IhWNvO&9;++$gEF+i6G5A*k4{Dn21d)ztvM zE!TtQX8hbOM=?l*kVid7y7hEbPMXyD=pg|>B{iHGre=Y1<>)mpkErz4*&EJf`pF|R z$_yUnJw)>?J3hyj_dEEVVol&N(f>TZ;S9x$T*J?=*eN{wbd<10FG(%CXR$SBk+8&Q zx7CAJ*LQqFj<BTD+!#9gku3CDH^bHcjHCuUDA3iZKRYBJ3F$im2XMv^ZMF>753u;f zIiCSKw+3mQcR(<<=$};AOKpEKuR(L~eE)oL`}*dKvi((>|75V$pd7w-?2JMLSOZ~x z3cSPHVGs8d8?gVt*q(@@0;#T581dNWh1JOS6!h(d5+*7rdlKd)F<@&lGJ=l4wIN){ zvEAfXz-q<8xfwrouWX+jkR4!#h2&7Co$PU|eKN36V+jsA_YYjP4aQoXS-u8hnlLXY zF`)emtAfO7(_~Nri(f{`i=><KQBRcn*e>k@7H0ph`8%cMb0)p~^}#S{&}7$FPLYwm zkvbC8jk>9j-QRU)#R=Z%RoqqBy~RSqY)iZ@(<k+D2RHNHs3=j`2Nrex`=qr;!);i` z?8>8g*4umC>nRWkZv0{OGU>~A(|m&`{ky-{(g%``-dXoE*uLfEy+aLh;oJcT;+Xo0 zGUMgRL}Vk(?U`x?3^=RkiWxKfaNk6BydihF&iG+eGi4y);tk_dUZFGVQgK`T(+r|M z8wrZn+F#*iq!cFxxQAV|1hldkg}T&5=SR=KGyO`_5rBznizp;p$CmD`t4!Dm>~({c z;VTA)-i+>G0;l<oH_~R7U9dDrOrzQhe!lCc)sJln9qZ;wj)h7%MAOg|7M0Z)sm1SD zC)Qu3kUr|SgGH0|euJFL)i#Tq1BMhk(|S83(A>S!s3DG_gg-82@QWo$52s}i+Pjj# z;{k~&o*E|&{(HS$z9ABvNr7phH-nD5xWJ{yw60iDj@#9&?Fk<XJt-Z{(xc_O&Mao= z!GJsUI02wWQH&78gL&563wGU>S1yD4p;v`#8MfT~$F^g@4sYnYTX$y6tIB2P;>ep; zcy0_H-Z>uyo==L3gZqopvrh0&oKIx?ZF`EScAi>A@kT44hXW+;nLkb5*L=}}?g8t> zwVM3m?)^k3AVOa9*S+0?AG(-xx^gj5%bpUL9Kf$wzgYu6Ec|GBc={DUM~kY&3&Lam ziyZeBoPbt)Q>0Q52lKV$I~{mDsV3$8=)U?#4*MWCwdF~S>q|TreHuOCHw7<XDrWx& zD6zI+eJpW^tpsQ@7BiXCO^VqR&%i|C&$|=m`M#C$>zqx?9Aicc&t&i##o5Y^@qEdF z?{U6}RjUd{eQKIgz;ugFETa9wPGf(!wTCt1nas>H_-XZ1rWZ2+_ii2+5nNK=*5>}I zNCf8lk|`4zDh7Cg%RS(LCpAOaM>-q9gKfhm4?85%HZ9mDJ^SX8x1XrdJ`;Jyby6-{ z29V+YJ}p$)v2r&yCCQ&JuB5M^KSLf{-A?y;QEo_^C~D?EY<}RH{%mBvnx&B!ias|P ziObmO*4s-VQJa@?B4sJ~q$O~jr&uC8VJf7$eu1F7QrsQq82->v!!LLaRz-i0b2uxe z<K^p^|E&0h*n7NO^~;KtCUx6Tdb2O1co;cwvd<PfH2{+Solk7h4nlHSt_BYal4>vY zS5djwmry&UG-9tf98CoY89lHH&~=dmrF#JN=neb5@9Uldg5cvY1S<CGKNRE)J)Jmg z$`6^Z!)vt5-kUac#C8SRxSb5cE`ITFqeebL7{ESj>vGpEJSKE@l&vij_&a@L%36ug zppvG$=@x3=o?isx3FYO=jCm9$i<rV#+*J?kh}+;~j?5)9($l>}R2M(JQA;?>lm0O6 zVZ*&rFpNA#1K+m>t)di`F3z!S_nX3CpkvL7n-Y$|qSY6tg`S?)|K%vw2={K)j4*z9 znwBa2s5ernq9>NQ9@+rf*2e91i?X|!I(^fQ*9J?+xLu}ru508-6l0N9QfE)s^!2=A z%vO-t=@rJ=_RkhuO`3XIR=M~5e%)!@s0qw`+&)>IEz@JDa}~n2hYg7biU@h_@R0l0 zq49YQ8f1?YP<QCE657O*{gyLK7-8Q3B|d*ec-H+Uq&XIvmb~`N=}UT|rsxEn!$JxH z8+*y*AqG~c3ec1bDzZj9-=9v_isM}H*|K|c^(|qSO-lw*4fwN903TKzx_{UqLV6+y zFyD?d(5!BXM!7wis-Ki*$xU{OSuio;goHN5X`FEePPpqNXnJq#5Y3PS9iopMh+Suj z=^ozrz(8&98g_=?poeRa+ZZV#iu95>fyaSHN$!EljpyW8_Ns34iavr!m1+kjUOm&j zUeub2<a1?9@eVIBk!QY^C|!wxw@v1U?!n#%%<ruYL6*@JPINRMb@1=6>4^8x)ub14 zrsu12r?>vMC9cX0<{%%nidx_UGhUtLkm_LiaBx1B5cX?dP~uuI6C&~Y5hnt^au*<r z%ORu$*>HE4<SQ!IqCyP>Go(-Oqw^GL+Uv9ANK&A(aH%ENNT_jTrH}<sabZCl?{8M$ za%qMFx_1bC{=m*h)QSPHJ<!)6_szLC2j5yh5Dvgl$H;DX;1<&&%un0(#Q#W7ESL<) z#+c>54g7HWnSi#Sn`tC<nAO(ii9tI#4B|1Ga`o{)EN=JYa+G0Xgl8(dCgrXyK9xo? z3(QneuyD^)t23ck)Uc8|=hNTi+)yVrYDH%rPD3|GI`W;$5*9A#x|cQDFE95?w&EKx z-Jlh#A){QL$Y@E9CLE8rfUH}kstrTI!uR_OaD!Pu8RhoO>-a_A5qJ!$$3z68`QXvb z&QI<6!oQc+2^_tmC%{&fht+5Xk6TgOqO=D(f`GZ^12iacH(N5RRy|Z^>ZR_Z=9w=& znX>NBK94RqE95SYgMSjOL%tOIk!&7x?1~NMEFl4u-Bw7q=g$ng{*rTf<P}0%ScYy3 zx`_fW+7ds@^#1NY`%Jr1FUZ870fC=?V$r<qH1r?oq!{ypR$)#JAv>^{1-W`|caypO zhlHzGn<2j#;HQIKPg<huCeNvyYOhBZ1M{^f(Wm2v6^thK@ENg!V@B%MZFv#r_|$=+ zZ~#6O)Zy#~&w1%qOl-cNdDvwyPqQxV`=Eozhu5u@B&1tukrCXhut>FPTUM4btLs@o zItcx~VZ-l}JKjGFN8z_>F(C4`HaO3GJ9WE!G@39Q(u&Qq;$W&~EIboSXDt;+{r;=7 zqUCF82rFDf50ng$Q`%;0lU$Mia82A1t$%6^g=>cr<6y4c*Ihe!^iWdJvC!lY6a-&! z#mrlja!vi5ZcCV&BhBk=5lGtD88kb%HclY$C3oF<aMmZ54(;1%JXdRx#}w1MLF&Y> zGp_K@K2IOG<*B_Y!fu4kJU3R5B85`wv5dchcoiwK{CYkj0$lekVKLbaoG{{Expn=u zNe@4j`w?;4@827!?7&5W%IqyJv+Mt=wA$Sp>IKcCw8dmx(<5DuM8k)GNMST|5=}@i z;BnGmOI^qAhnn8A=d9HJckq)$KFn*O#f+{mbNew$5Z&oFzz#Sj&h1ct|8vcf57=N> zDvI<iyVW*8t?VH++ld~aATF}HzrtV-Z+!3k#-^|ruV6UVu0l{dO3Vg3TP4a(t;JY~ zw_67L-WwY<(d`K+qcDrgCYJIerpNi-8&%L+WH{b*m^8uSH^36GRn$|rP;y$a?}=HT zh_^ikUHxv>Obp2PBG8(l>6lOvuCl(+LT*E7R<!z82a*^eVbyyGLscRI)*&xj<)6~I zNu%i9vYnDqi?=#kuf6fR-`+d#_I&GO*Z8dz&sfdiKZ88@i(CqWu_tPa4Dvf7RWQ3^ z=grXQA=13Kdrt|u4F|oUjY=5_-yc*uW~hhN_Ljc9bRNtYQKhQORGm4$F*a;CbU<Z# zf}LV1GZSL8w3rzJuCIBt$seR>-gIkHzRrKqcZ=cnW{K-5@cz+Fn-)e<{H*#;-(<$J z?JIm@R`&!&k2xTFS-_Q`Tru$qDxtu6^=CP3dq1u<18UB9CT4b>a&k(K^NV@e4-eF+ zI<U+UmxX%^7~1fbF?lN0W!WNmT)VXED-bcI{9tpPKj+9xgVcBVxIo(kBh+n~?kQX) zEZK2rttZv4U-BDYZg{K8JTM2KX8a$A#*sApL1TTg__FS~kN6g9C0PxZKgysqoAu)H zrC1~P(X|l<E5J_aeYi~UD|YGDctb(gzQBK<+x%yr0lCKh((RclDot>3;zVIhy7gY9 zMPcq3VG4(U+j=+$MMa3##I{%raQ`Y8+Ge{o5|SFxgiriO2U^P--a6(VW-ePh@vc%7 zIgI=CXV0QIMBf_f2?F4E2b}WUn4T8vjc5if3z`TaC4O?FW;!Ir^gsLjf>NxA8PwO) zjy*AppE`TiG-dsteRwhg1rmN1`dVU?JZR$-tG%vLpQIAlSiJhEyn1$jz`V7U0$Qpw zw8DjgI4J3qUB_GkRhaB5G`;V)_wu@PCq(gSmj%ckC=g@E?6%odNL0n#_by){$3?Z< z5+J{EVE@ywk>5WK^aus|WLU$%myRDt@UXSWTSuMS7~bjJ6rU5JeeS~*gccOL5!Qxz zcJ=LybF0l+t{;Qh>W0hFf||BEvr2|@9j`CLCeP=ltIh+OOmzQ<TnMY@L}B)5!00I} zPrp)Z^1X3IjW_fh&5;NGwnz$|c$d<J$T&7$>K|zE#9V{L10Avv^1~aO_`$Z;Vt|nY zX%PpfHEc-reeT1HwA)1_Q+b63et2ZDd)NY$4YS`X=GEpZyPMOfkweH?(<H1JCX=g7 zo5>>W3tH!z)9gW#lFqm0w_+`~AAiRKki^=mr?V4NztaVDG!fZTHXiwT+?lR?Nl((c z5D)tie7{tEuWK(>yzun2v6_QRr)e52Wa1FD_ibv~wwY4!dH~RvX(h`ju&3+?n}yag zOCN(oi8@hSxJF&(gWabFl^k3;lW;F>qKX6G@V`vIZCj432!Sab^cLpF?N<9x!1$1I zqI@LBFx9{wn!POf%hQ70s}Fuhf#kwOQDZU8s4B7sYwEmhVF&gq(IZBALyo~ESP}Fd z@?Wy>(b)JsP_H8Uypu7ziZ)h|tZ{;Xer#`j)$tG91!2|oq-iLDEUp?juSAjlQ-_6+ z5IU<KtySZ>iJ;kYMOC%WiLQG~AyT#LtHbN}hE?Zd(!8MuokY=FHn<1N%x}$}e%jo( zO|eFVe&DALh?pAn-a(d0*s}&pl7PK5O8J|;frY0Kh+Tv0fYcJS;qJRw%qlzu9TJq$ z_fOeSpB9b{6{Q2ZLZHkDe#?Uz<td{+c*;qv-5xV>_r=U8t0|<m{M1_S_qhs<ug)W6 zRAbm5+G_&~gk&Oqb?Wd3QZF&Pv~7l95OFY!5}X94{kqC}++d82Gi}Ey5jY1>*&|&* z$Hn58`bIoG>YYd`5SX${vLL<_g6pQk>Qz}@9vfT(Ug#G;8+i&^7H+0Z1nM?>j^&|N zBP^?YG}+vBfr7kB#Me-cbWYf7)Odng`J+ZNOiL7i4I_bv$hH(UD!*l{d+Qy(FD(Rf z-i8Omb&dpVX@PQDZ+r!xGysb42^F{|#F8K>xIgN4ZjN)AR`|eO3_^_&+#;@@l5%yQ zd~j_P_*H;GL!Q*c($vohWyu?e+l`uHoqaNX23aV1o1oWcaQi&x`yBGyq<QiG;_Wqc zuFdp=m}1)a%q@u$gmC~X4UWJMekTN&##ubFIK}WojuK4O7WT<+xTaOo^+%GYVT5PD zdO_k+2=nQF`jZe^x=1<IU2U~ETkM!-_>lDy>;z4{K+_Y{xL?;PP2D=yy3Uwq<c8Sz zW?pf>W2A<v{Py7kW&ozeGrh(t1+Vuu$}Izm$-hN*LJb`93Cvp}lHG$Wjmj*)%@05f z>##IVRuOyi>eHaxtH^D(Q?<(I&Rm1gBlhv*5k@VH!f+X7ULNluri@dS9VDixyE?%s zuqNgnkCtMm!Z@`<pnZYH@mSVI4ym9ZH0^kB=r&EDLt(5;_JS@c1J#NZ7I_0hH?3vH zTt}TS0isAr55r&obF{nk&Vv(&W{}EE_v8I4wKb?gNcuRRc&$%>h(GAJe?4Ditv%;; zDwwGGmFPthdOPWV`s{jiJnY<}wEigGHEA766KVPjQjbq26i}Gpbng)3;*_@N8$-=B zBchr37c=@^LceGu9f+ky+G3nd0ktA4EY*7sn*G2|E=)N&6d*dC^w1T9tQ-w)=@vT~ zJL|8#pJ5f7{@UGHg+>}Kv|cp5FB3$$79vpuBBIT{`;Jx|&Kp%^oW#EM*kzIM|83|- z0e;`3aY*WInoiR%>=)6_FsEKDf)H>4Sq7S33=|0h;4#!pn_5aWgzk<u`D%$DscNda zEr|1Q(1a+*QTW89?dW{th2{BZc{y!E9v+ZeAxy2Ro!6ffxHoJHCZ-`*7>l_Lmzv;( zjFq>}A^<?Cj|@JKW|)6zhO#Nf5JHC48u%=bqk`WcX}+KNNl2i$)o{I!vB!{qDOdg2 z;S`0wo!g&19g~jB#N4|I(QPt@$aD@$_aQZ3J{AvY+&k_R8nS#Xx%1$-3BCj{UO730 zVifB<3(fCBP32A~Ia_~>ihxBRveq&IZ0!{Us{5R>Kf>>vEUyKAmO9~=X&Nqy9d!)# zK2vU{o<QuNQ8R3y7R%Nu-Pd<_G<}xsmtpmZPl3c4LHjt4Pw<?|YZp|Aau#z@A*f9E ze&-~Wp*LnopXic@1@{$Si(e0fi#G_KoFX+cN|bey8cKmu9TgGDCSmz(xfFFi4URcZ zmd^3u%yNe5Zpk%WUIkZxE-`n8c#uTA7q-^Mda7T0s(u~E3+)rn(OpyK+rsOOdaoM7 z$m{X=b{H~w@@H?SwUnI@CsphcY>a6S>xN<(IlNp0(`L(<Xz)7_g_(8U#GyYoT*OFo zMb>X0LWIE{!$t(o+1U@ZYAgOi6Ci&Lj+nXxmxhfyK-f$}hAGC&^QHF{3|6!~xuGcr z9#8AX?+=541zH5LZie7H3bNk9CV*cvx*L3%X>%Xzku$|!k|HEH!x3QA(RBzO^G{|Q zoKMl0S%lNISpq~(y2l7PL7w)&%Ln4Dv@*rI&JR5fHb^d9p-CimmS@EaDq#`rO}f-5 zCtI1ByfdQfd%y?yCo<u%sb8H*B3-dk1}ssdw!!54wR$+Qf-6@YK}!&4Q%A{!Pd~Dg zZY7+GkORQ{HTPE_QY$k2hW~BWFbPJi>_Ou+9}3C#3eFlnOenvwGY6TWm|_x~chO35 zsVX%ITD&#l^faP+zUS?xXv&eIC)Hk&?<F&hVafedraco#gDkhAKyBtMh(gPlk>A9J zcUTC+`P2kJE<_pUy!JtfWTx+=4Fcx^^$-Cd(cJ1OnV)`L&_uVGc`(yvIvEhD_T2dJ z5wqD_qhayiZr0W)pllpf@$v67cuu-j)Ydgp_uAnu8fEhYGe@uy4jA*#zyepDkIukU z0YqU*LEWmobSMzI@p&|JpfgG>vSCNGXFvNzuQ|NST)9G!D{1h5Xn}TYDez2;l0)8< z#~;i~_A`dNT7stBsb?mqX5SgV07u24&5xf{dfcheGLQ-(`evQH&>!-D#S#69K$apY zj?TRM`s=(tY0_l8PG9)G<3x|eLks%DJrX%7z2!4$H4{JXDm*7&5n&FDeDNlP!u=E( zdN8}r3!jDxzK=;*{uc9f8ifP_jWw25F{J0VuhZ5yTPt5DLhcev%FV%f$5tF(STdjU z<K@<QVzzR1^FW!*S;R5Mf_|#WDzp78*ho?Bkbxhb;CGN52eS<w?N<_I6D!A#%!h!Y zFi=ut!k6W*lJJW7rO%M7rm7*DZg_c2gmy<@+Sk5Yn{S#+3pr%X6sz`V8>2YPf?kNV z>^vAnd4K@h3x@r8t0%}^Kz_pWmqm;YS{(7{Jo2BpK2+?uL(RT^ks6P|$3J-h%%7q( z<Z)+~_}NoTY;YW5v|8Cg?8xxDUq%$)R=-Da8CE}pwLP!`L3Keh8mgz?^sR}Cw1`N& zWmJZpnMiCW^o((y$VBrKAJ@y5s`6N+RIe4=rg6bxTd*l*nPM=VYp`@3NIJ`Zi(dJI z`6NnHdUq!(15iAinXligpzh%W8r+;xII)gCOOl-`ho5`T=G7m6u0LrPCLEn4fUhe5 zH*;~aXD~yu)Hqvv9PC1WN|Y0(Tk~~KY7`kx00s9^7VLhdyJX6ZyRSZ1vEUjp!Dtp^ zKHZl$>6}Az5%Px3_4IbnZl&vKpVe7nD1&h2A2rzxncH7#`eA@GUK1NY`fc4caZDhm zCoX_>28KGixDX7>ZCWrZu6YKw2*NxDc-XXgm1{3o_K3D&_^5%qCXK9^Sf>jlj6+Xg z*!!B42CKNAv|k<640k1^OILZGA2$E(S7+xR{cqZB$JUj~^&%W_+TPeUXFE5E=ARnf z1|g>NdDcZyAfPK5C^6uV0VS%`g`2|dIQW{BUemjWm))I^eg?@6I9FvNyooSQnZoZb z7rZUC`{~!2Od>j1I6~I@Ywj>DPRfcChRN|~pATn0{Iz}F6--bEGGC<GhMtiV?~NAs zEDle9YuNO4Gt!#1_cxHoBA`Iqty_d;Lr;sKfVqj*f|=!m$5<A>7tj_)hZ3BHN^Z!- zVH<PP;oxvMtj;?etg_H@^9<<UqDO=iLg-$*e_#|6He7I1;+xMDA31hK;kl8Q&fQbe zEr|K5Sbr0}c*j7T#=RZyTU2IxCF6=kw@z>_51vHw7_VdNLrw3F&pi$;HgYI#i>T$p zS#f9Hd%n08mCb!GA&x@C4HA|ZWlif36<kD$E+bN=JCnaWwtTW;IkL}PCwVX~`4PO* zG|f`@%&`bNHoHsqfmhbi{Y8`%sqShDJefuvn%)Q}cd8g3UA^SqF!%gav4UjmU7V6t z9i+5-Z7#(CryXwd$$A!E#2Z07<tovQry9UO2Fu92KXOc(Kp8@SLk=0<`0Q>!2nIez zwT~RtCPE^`${$R46S_};4PBWTVFklF{iCVdv4u7I>d>^Q5s0w}1rKf(jp8%1URt>4 ze*><-^LfEnv`36Bb73)aJin~)z({ahkX$jdl&68@hy9YO7Wv{9gPeRmPz2`=WD$Xn zY0(yL>L2H$40i=%woJBV&q(>Qf)2E?I53lm{_hBjv3Vlxa2o<V<9K+dV<di)w1#6B z{At7Zq8`N1t`h=Lqbn7+*-|h3N2fQRo2AGo73Nq>$6+-A6-5FiSd3S4Cfm2gYla*G z<3xjyzf4@jkV3j@YDB%$NK3`(y(KAr;LJ4k3BpX0*4RS*!Xb)mhc++V4OU#qL;n@p z)t0z^%S4eijtYXI?107Quo=osSb#kVmLN**rgY#q;YpF}=v?CWYld|g1d4&c>LLNQ z!+-G0R}$HIn^b92BkWi`C%SjDaPB6uj?l0h1fU%tsW(a*XFZUrxyjK906Eeh*c*72 zv4Wm=u;^nHqIdLwrL73g6A5x<*bSe7u!Vd+fNIIRgHk&6?iJX--yg}kmIHZ;OM!*C z44D5$(nWGxKXWlwj4z#Mb`ZFKI7fSJC+go4crY<-xs!Y71(~~N=mwP7=$FK(iU{YW zi#wmO6{19m?!0K6gGycm^^7kha;6%v-G<l!HDM<#Vdyfh!k}DZ0!S?om*~3Oxl+m8 zSxI!3pE6Et4hhP&b8XP|Y5+9JNmOkTbp?TIq(zW#GLtc!)+3BwE{&<59$q~qpVo8& z9W(LAg4y#4Z>XBe*_Sj*V*tEnB0rITDNWK#qLkib&Zhg}!e`GM%w0t%5yZq<gKlW( zV22LKKa=ewzFzKdgIOVvfdoClpP)QRH-3M0Fio41PAR``Z!&7T<_XLnP{=l9R$BN? zx?U{xq%LI!tX1~N5T$6?@RVeeNR4g#eX!ElQns;%;t*qi`2H1gAwmqQo}09NhcI7^ z(_9cBSMHNOr1c#XcB9mG!(UHRyJ!WqwFT~P9P)L%25U%~f0A6;6saCoE$DEPCvSE= zlh1fCn;BCNv_b!`5L|SO{Ng{_69}I;*N{ECj~aKbo8g*$D4S?@Aber^kgyWfp-KkY z(^qZoHobFEWiEE8)^i}{{7aEuhrmt&K?!UYggb0T?M+WjueUi=hbiJDGVgja1JaDT z4mSDF=0}mxXee<95ZAbPx)S*tvS@ce%SaLK;GnPbCy*c5B%^WLgf0IgXKR0&G*R`T z#Q`<QRxL(i%*Y}jnz%f-BYy%!+9<rFISVrJg`NFy{xFjC2lDCXFhvX383~4LbJ0aY z-IqFblM%&r0j*38gxb3HvnytJC<H=+Kr#txtd0T_8we6T!nnX9pB7-IaPV<pW8T_# z+wdnROEB`S_i3m>l7mv2@U7I=+b;Sfk!2%X5lzyIiZ)?5W5Yy<cF|n4^LwB-0k=<8 z<doZO8HieKfg<T`Y2Ksuqu|JKMGuUWYVAj1-m2y#fty?;o1x8%q+x+tv6(?ltg9%= zLpGgBRhxc(>gq839z4_6f+KI(9Tq~+VD7dXUO=(VfpAH?h_&a!8R5^#Zw#_1wiI)H z=bs)gl5@E#pS3r6H8DxHAe@WxIA)3T85yIvKl|)vovEU9|L#M(5eHLb0~a(SHnFzp zie2IL+oW+;0tET1H`?js!roLPDbyRoKHZDxLti^s{6~DV7yz<=2NCBX*f-t75pHF( zNySkM4~hsx>5-Qa7p2c2Atke5)(WcvOq6GvPf6ttbFUC^O|Um>?_Q}R<L@4bs_pOx zyv<DBCRT4meVCk=+*8<U^Dy-g158%{MD&1&pmwd%@N$68$98TP>>2?LbB)SElbQ6e zP*@H!RBHYrEFB|VPU#(bSRDI-66t?sPt(G0(~Gmn?pTY40XHmK7u*n{@;0e9hgrz< zs*{+>_N_Q*bTGIA1`<=gdmKsr4E17FyS5Qo0mv!?V^72pGg8n&BTA?OAPZD@T!6f2 zY4|#0wcI*i7!IP3ii1@w=Bz0y^NgB-;fRBg7b`oe(wpX{Mw8u({#oRD2C(lG%?9u? z{k<)4Fp9CvMP^Sl`GZK08AIxC&^HRzKChD%)7<-!%fz4?g(*%r@PHp(&(>gVZ_G5c zBDN8_2!NQ-d%4$q-Sm91L)JqR5{+;qvcCt}pe>cMGY9Dz%Yg>!(Q_urA!~Q(*k8<> zyqdkrk8Z!PTR{SCZ~>>kQb`5kSyMPHS-9q1(%QVu2mkY5df}vO;<L;E_c1SFG;d4h zZsq5n$W~<=_2ACXG0CHBC4T8Qa3HWkM3jaSroH)qX1jtnBs*KiUT5wO_&hodNQ!eN z740^k4F(%)0z~Rwfh9ST`<O*=8##}YGJPCeV!=n7N<n+6`c^4UA;>%W2h)gl<D2gq zA;e<=aCjshy)knhd7BXE|8D2*$&;$H$H$Q>eHW{e0<u-+c+z0Zql?{$p~KQ4yo;`L z6(`Mn3c+J*EmMK?j*3r*3rJ2$8jmFop@3efOWf_B=|egL*3nxkwz@pgXUl|uQx4@? zuiuhIDmgczA%62>04hGq+uTcvo}Bs)AqK1cUA{_cuqZ$fq6flRZA|Te*!7O#r{|7k zIOCdLsX!J3;S9c1*zoB8Rb@EiQ(N@}<Duvcjim^H6+GAS{a@2z!?a`nbtziZ2TtCN z=K0{PFjZdquTr!_e7<zHD5Iyn`mCtWmnJ+=Vv$<iKgzV4a6hMe_Jyz;KP1*jXAFZe z3;%q+P4F%*r+lfGUwNC)54>&Z(*N?+3{O4AdZ;mU`<FW|Jb!OGp#pBVI#f~k*R@L@ zRh)72t8dVR$ao8s39}>)>fatcH!#)VdQJza#`I2!9owWIxuH>QF6yunhk3!NmK~Fa zbqg(bod9d%HQl2s@;v6``AZutVHp@DzP1$(MlZ<(^}38pMb4q7lnE8B6YF-|G|yO9 zF1}1O;$OPtcuH5FG~Ef9V?*ITLQzPZjYb)m>yQ8P{j_>nKz7ppJIi^=G1BcNjU2er z#DD46b!~Y`cKjL^09F!{-PINxIydE0hapTj&?^0h4#?wpFl)`+-Rky3Q?I(Lg9*3H zMe96*aSrTzYr&nPSk6_u&PiiITl}$C&*zno@{eR$Kj6vqUDon^6}+)@L5p?A|2RS0 zXVr&fcq7+K_rA!rt7q4>Cw-Z-R_ZZ<z;x2$sJ|BxvbJQKMP<^{B8&Eq2wX!u^NYsa z5~oW>L5{{SHgmo*YZ}cWxAei<+FEg$mh0j!mXEuTEc8NAR1x8eT)im$k*~hhAIfk| z0h|4~Y;CT5zP&n2rH?+HLHWyD9Ii`L)itQv#4P4Y__Kl_<?dw0+v9_gE0{DvN8q=e zf0BA_)19lw2NW5m5=q(2*;4lG@~MUiYhMxVyXl<lczyi(Iw2QH*au{?Xrp5F+v#^@ z3lH2`6LH+LJC*}o`pi_ppo!NU736nDuAZN0Gh-hF265>kO@m5$&?8rW)0>$aXYpG- zc)P$)B1dZPSs<6zRU{k=qBw^#6u@KY<`oYcf-<I>z<}T)+MC1g#sI;RPgU>L-u|He zxKX-$V<gZUR{dOvLI)*b9#^7r&blSn2V4_pIQY@<=0|i1t7kcg^<@VsK<oO1S1BR9 zA#(mhv&^@jS-+Tx83<lybPuG+;Y3|$gGzVM@|^CuW1B!iaSblQ{tKU~ntlIPYY8k7 zDuMczz%;2~&dqlJ?*y%D;2%vG4&5~k1mGq@lIlb$?d2==>tyBJn*Zo4bzyo}jMh-{ zTy<~pz5Q)tVeqC{B0T3CLNsB|F8x8c{Lj~TZ(!@)7&a;Pa+SVs^6N;wbqyv{8BJKL z#7*vxYR~wvCb<K2H45&TY!6Xp*wREre?X66P9d|Gvm;SWfpgcYd&R;}DR$jD&w6~J zyuFo5{?C={U^)T*Sh>K9C|%4{>H8$lZ`8%dhM};_^+@WQ&J9+bFO@Grj-m9!jU}#_ zrtx`Z?xN(bP3ky`3DNB-mXWV-zH{*Oqf6%$x7@5;3=PYuNeRfBdCfielrcOoV@5j; z%zZRtMp{AbxKb+jG(rg^6aQ#&6%gHCC2*i6!W%&xYd+|gHx*-IY`qMxEVBI@5b-S6 zZ|`sct0`BI7+5(;vrqJVyyu#=F{-Eb=WQR;V&_n>ZcG3Y4@rc7(kjThN`9%u+}flt zmkL4#(1~=<oc(sj;fymi0f$Ax`g!lUaN3w!$1g3Y*Y`I0=>?Lv<DHDNrysZ9H2JQd zY2jwKC=5RjavE3+#lZ;yOaS!O{<kDdhWLEc3#OT~=09E5xHA7%fDbGg`PC{0rK`Us zHm}FLc1C5*53OJQ^u|lMtDo4NqK87P@jy$pG|nOawri2$nap`6H1mwNyU!;*G2@qb z;!T0XiV!;QmssicJ0B4EaE0auw2fRvG!G$JtXHFsE$W*!Y;s5cdPBr9q7G!JVi!Dn z-A-$40~K-Kca0(U$JUVe*BzXT-d`gG9nwMhYW3Xq%Tn+fCm|@2ok&~e<P@|8FAaby z7r;`^7rs2fde0Ch^|XUgiTtv=rR5=4P|rhpuIQt_|3dw2=AV6x`Ni#JiylhZ9`=t9 ziremK<%qou2VH*tSYWjy4D<W>y0WztMhL%=`=4#N7geK6Ra=02056UmI-u}mx*x}L zojq5P10*0yh#kEQbTmAOXhw2GWvVUf^7tBR1oHl?Wry|i@;omlf9p9+l9lH<>ZsfG z_zLXMF5U}3+gyG%YSy*X^ED41Pm<aXkN-+vP^zUaeq!G?>FSD~I&Qqm_mo%A4)R9; z?8}_1RSYqm(bhAr;nB$W5M`S5y_aciQFw08*55OXlOqA|Mcl>CL-RNH2A^gNzMS6f z7l%LjV&m?Z_g@Ju@mwfwX{zg*-#&UrYTyTlWc#<2g!ZMLPx<2hz8FjKAKNi>*BE>T z_BPpnzsp%?st}pRo)v^Gj$tW_6J4Ww{-$;2hmKy_9r~ixGm=aG<&5@;VAg}i7tHiz zZj?IvH?0Zj3b>q~<bKwk*HuEHZkO<E1b3KqIGcurIJ70uH?8G|^6NaClYRYS73P5n zS0DYe&)?@&GNa72#n$ys`}nede0_US_G89y<EyP|5X1*hH~3$OWE$!z`7vjh_DQvk z3jSBUCxwy8mi4wB!PN`XLfj|sf=`Q(Vt&-T64!`TgD0wvb|~NMUu?5q8l;z}&ic+3 zw8}Tez4^Q6!DY|u?X&$ar2OBf22Y&>&$!DM!3n$D)2TVAX-wXvqdIrYs4s|`|FdiC zs)4UKPX~Umn-jfd$u#}FOYk8c%fG1|&G~=y6-|wyQMWw@|GRI}|6IN;PyN{^*SeWq z^#>pwBa}S0&7hAMZuJ{{s3T1aduCHh^Bzy8>QQCe^S3_{vZ|j;u0)OUZqCh^|GtrN zJ2mTstL-S)-y%M;@8uB;&onFbpQx1#x@aI7-cNk$9JoORN2^iu9=z#89(~(D@9xiP zr{h=Oetdk}xSm(G%38N!y7}s|TlFi`bE5_(d@vv^Dd7hLt618}miZo-DW}^%Hw6+) zGPq6jX2+h+L8!alw1jE`m8=7YzRU4s%l?Y^@YG>VzKzM-YX<OKPZ4J>`LoYgFA*jz z-0^g6j~pd8@3w@Ux&L4NC2OXlTG9n%y(b`LCZ00*Zc)mA$h8LdC%p%V8PyU}{J!}s zl}<k}VXx5jT)Al@<}3Y9Mps-<Tp-@ynQ>Y~nlKQ~7tBY^@Am#GH3ht=IY1#&4DC)Q ztTL{@Pc;5>w^wifvTlu}i<+Hx_mB4T57&gf7(3%}&(t3<Scl#)AGQ8Gyxu?NmyM&6 z%_~we#QptiQOzSQ2PmGUU&G#s!)j$F@H}I`E_Lj4um(+fx8u;hT#qU28BmU2%PWs6 zdw<+Q5w2U(zn=Vf55u5BdcKHxCj0cbh9*azT%B{(`hCiO%$<hJ#Z|cg0e!QN3SPS5 z-iCT3Eys2cYap~kdr4p3bO(Ne4LkeO(b{4;Oghr2liG@dzw8;&ZhCRvJGT{od;d;A zxY_L9puJiec39i{wsXd$2p#Q}YoS5N+h!S~A_*6AvBIKz=g_|5TWa?UpBK9qKJ`uV z_JKqG(WUNYobfEf%@b!QI#|r$aelFmoTfp%dt%syl&|i6d)*oTcs%0bjxj@xQ)yAV zU$G%5FU?mVp>v6ferjoUhCPw|f~PvG;~zIOJpa-7Z<gO7@d;g0a#mWW)AyXrc#D;n zr~0o>{-!u~P=oKi=L;kq6Ro@yKUVq8i!j#17RH@Hb)h@1`jS0)cn{*zTKc)}@<H&| zwncnwJzKl3drtdXr$ed+1j5&bGw}Pb{ud_Sdm(wpu=};Zj(&e}7?!}+<dyrm3wwV| z{d@A?J@xC(^?vK*ly%KAyQa;aUo@aydoL<F<J@!Z#*hj6Qe`VJ9Q*vVbx?yoxUI~{ zyzw3k3QaGK)9HTT>W&7FD-h!`dcTsNG^|}NS#FyL+(2y0y>>CgnFRgWXWCzQbl!xe ztLp_y8<3R?8>fe$mvW%}PS=Wi&b}&bR*}mI2p;5%pytuieS<v3gl5a>*H*ULWZ-i_ z7;U!pyeao5yV};hA=e<EIqYT<`p%5A`iGD+X5fMQ1A%IVjD9!m6>p5-{cPWBK_%s3 z$@IqcAcW`zPy&RE!jS7`$64U+sA(LaN$nA<>eF5|Jg2wn0*z-YCX(GM5@#m;<e8ug zs@M8y`nnx!`U$uQz>x!bqTc`F%CK11?CWtD5wN%-_Iq}{v2{&Uu=WMm0m4lk%8SN( zjPi-sys!#Ph1?^kqEb|g_wU=5S$rnjf1+Ggw;o*@+M8mvSIbV+kNx0OzyzvoUR6Un z6ZFl^zTaCxe~=ErVOpi25Ht@{{^3{KchB*4Gfo`u$h!hNNzxDb3OLTDNJu$#>oJ;A zo}0Uo8oei!&G}fmbn&_PEN$t*#4FB2Wv7gnL!h-~D_sFCBN*+jpp}U*?ym{Bc+6{2 z{h?oP3)qkcW}s_N7H1RV!G0s*(tQ@B9iYOno($We+F)B(1}Tm(e#Dv({hTLat~if~ zaU4jVff2*cP-llS(Hj@zM<~*r*%^80o72z36;^(lO!TBLGPvfDG8HnN4Xgk8(OaEa zH49A-Tzc2Q?V0b{FB<%c6AFg?VSl=Iu}w23h7=Tg5Fks4ChpKEp~KR8Ah2%(AMRs% zu}3$oDmCh7&lCWU1$tb!nKn8k3FLpaOJ=3}odRO>`549iejVZpes-fvUtR93^-#?c z9B9$g%`HE$+jzNEnDH$j&fzV0*1JExxz*;W{dv9{Y|ojhFcX)mXJdY%SIyvw!k$<A z*@@$Lg)jAHRxQCfZ$(&%^<vWrzNS*g6m1HlyvspiKO3mltMgIzIBBC=Nj60VTTHKN zo9TYD{m(u-l<Dor$)JIBs^c+XDE^R8#l8K^mlfdyeZQLU(zRt^qc6vb;!dR`U)64& zn_?K?dfY7nY_O<oqWa{_DAxqysC4HFZ@e!etviL?!{uSI!LT82PW4@_$9DevlyQ9i z-PGZ+h0C%UdIr6ohG}iH8mEc`$<r`6@@(7ToBAu=)r%IcVJW2EU~|}4`hZs3S_s3# z)@(LEb*%W_SV?}m`pX#3Lf9o(4Qw)tP@FiV`j;QWF6;QU&!0K_eX0YMq=&>m&{me& z{pjhEuk?#=STP%*R*(S1fogCgthhm<V-!B#kA>3L7X?E4`Kv#N>3gj`tl~AJW|p#N zt90qiO?|&JNb9spcWW_Z^lzF2TZ;qid~6z7v%YJ-GOc2jz<&YkaSbND>)#Pex(rG6 zx}-ReCYJ%t^J9n5Z2IC51rH3_=kJ^q;b6<qilTx+q9}gATN<w|JiNFgWBOr3nc?Tt zeru)P#L8r%rOp@z!5wWaKC~&aOZAHD33+0jF&tEQfzEuLWpe#HFXQY9dSxLvC=R{5 zuI|Mj{fzowj{a;~Xa^Wyl-bZG^4n5*{Hm|9Z>#4*lRlPqPRgJRU2$yGqLPi4Z*QD| z8ASI6&~GhJ<*j#$CFG!EdP^BvD#C!|^Ig6@k^Uo@aqEiw#$U~*4<6yDT3P(}qNs-r zS)T8n2XHm&#?V4%7lDJF82F>KMYm%8r}}=8ID$SgC`_2kBt(dZ8_rzIqJl*4I00r` z^*(Ed`CP5tx<C}{8=Oz-!0>Z2Zd<>}F)&q56csfOViTNC<jzUAz2u&BITtci|9X)y zzQM^;n0*uXLJ?cXuq9yw*2&xE#wmaGeU1a&F$_8~ZPjc0)oESb0rEFF^5B?nl$5A` zd1X<wk(N*4RYYEP>C*h9$Jh8pxkvt(L>;&?Mj*Lu-H<qTcRaSDq;D5DyGZ!gGfE7T z)LBuu)tyr38>a8sn>ZH5g`=Q<`r5)n%5PLtCLL;1Y4-8kCgumP;X!|(UDA+ra?Ooz zCWbxL^JQ;~JQ?$c{xXCRKCC4$4|kB?F<O60wwy-4*)k+ofQSW`ucuDv@M+hVu9+eF zJLbyto5%<EX>Lzl$y(|TeRxz5oA$dB=-D-wf43&H_}0{(|At8Q&r4bSL)k=y6N>OS z`Ki412a5{EbY_vLI@3Mpk1sv&;YCVW+qUc$MX%!)`QUy=H#RSdy4Kp33+OEARK`$! zB{~bP*lEvok5;!Ue>oj(?igdr<q!|LojtH${b7)00J7_AD5j<^nJxcb3?X%js3Qoy z{O}5%uxW?7P;)b*+s>CDrN^<b@)`#>dunbSig%kINQVDf^11nbjpnAk78%0KW%5&F z*9R6F%IswE@TPIg*gb}${gS4!f$QkprEFD+O+ZKvJnCM0i725%r9(CK>Wt^MSGpg+ zR7ZtxAl>!rZ6<<vQN{Uqq$ccdA1*J6mD88{*)jcVPO|SNvrAik@coHsnFRuaiLt$+ z$gEiDRf>=<RX)CE$7p@uPw0X|dO;K^8*-S*TR-z=kEU<7BB0%PN6bn|ONp4&glBPF zC}`pUQgReZ8jZSv>LJ&mLl#TCa_Q#zEBUnOfd0f|QD3W=9*J(6d=*TbucXZ~v^e1G z#}j<VT04rrOtxT<CbqSF&Ut2XZI&Y4ZHf#-H6Sp<vzWrC2yZ@kb;vj5FUhYAIl!RY z#9NG6gVG1x)GwBxg+17l`ANww!xwEuhMq&mbb?sl86^rqg*vnQ6Am&dH_CA+ilYwJ z!&#b<O08ZD;M#fky8i5=w|vLmrPJ#B1B*F!!~*Xru;{e}+3U`xK48?Tiq}sAU1!ZI zaK)w6{%vIa1AO$&-9X$J%HCM*T4E0%^agWl{efR&u45E#J>9d$ZxC~iVk9#cMm{GR zF5u^=J(=y-UPTl5*KLOo?k}ysn8zJ!*|Gd6Fq#hE*?PwaTZKw570b|_hwsQyXPr0g z(uriX4Z>GONsgwWh`P0PEOS)k!kMkPJyVuG<V;E(kA1P9eN<$`rRmis0y{Ku(ZS=> zkw%k*0@i%W?M>ay33n&0F>M&qebx{dy?m9O=6@J>O{W)EoY|K=eA}7==}1u=H|oGu zzpep%5ev2`(Z8oo46yKyx=<kXu5TG(E<!5+-3@-y<4!M`o7Z{8f1{_M{iv1GbL*Lo zZ_<l+UTcaE&sk71TRI;0oU*t0!Jf4u$Vf`Otu_#QSNl?jaTx*bjWd;L;X{RfDHj*N z9I@lo)X^`ut{(3{yeE;ea>lI-`>9lhb00q6r3bpSK?8+yI9ubM+1}C}uWmoDAIA#b zKGo*QTlm=aKqsC2znR{#Lb9?qbw?~l4JerUU|U&Q#Dc`vfA3u7j=MRc&eT8b>DVKD zVUbaDe|rJfR*`;rNv%N@;^*rZ@Mw_)0mEQDO$X~(Aq`*MH?fhrg9EG)TF|&9gTyot z$YX$yxTm_!@!uv}U(dLGE*oZ${)wVzU@;yH8E+mJ9mgvnq4$RQnTHRh6A%0pcbA)A zPe|e>B-&$IqT|NL5i7EubSKDdDgFdC)?m>(v&HnzrQ|Qpr}au3D>W)Zz&h0s!RLv| zQS+;eN@xOB8E&rop#YM)|HfNeaSTcIA6V>jO%{J)L+Cwp+T?>dl<atJaS-0xv2M#G z!|R5++OKb}4X-;@xtIc%HTdxfzAs7T5U3SBp1QUg&9d83f!ydV%jaE7Hup5>$~S3L za1RS;n^B7s0s&&Uv+u}PwLKsBuAd8*X&Pn{ofYaUsPBqU-m_$~@?7zAQR1i1PD!+j zTCsmrHpM8)q{17FN;md(2m(Tqs4uXDdlDB-Q~*X(NG!8APYsz~rRjL}*A*qI_*Gdm z97=w`uHV`+q553S(6y^L>z`-MqmbBrDNoS9wy7KEFsmBKk7<$H^r?pX89XJongtrQ z=zYz%(tqz?MV)ZbrD#u$b*wAGt0aTkhvHJqal4|bEsrO$aT5OQlQVKNye3YIFqCtr z>HMRiwZxMpIMXkd|CHRjxjTw!1%fWiL;PTN$46kYrC@N!0)<mlAXhT%Nr)%%US4Cn z#T-v-SMk_#W5k7q_{?a76+u?^qZfcRk`i^?PwAF!=DMacUefL0ZHVYhoBtw>;!0@7 zF=|;mCK=aePt(e~n7L6x&02Nd3~*Ih?x}GOUyB=R_+PrEQT^JJ+<!Nri>&Wypk|Bi zu3!)!OjPMl?chRt(Qo@O@Rw7bhCY-1;x#^T7Wt^)7v8ui^$Hrpo%0!`8c46gd<-~e zoUH6U-$xsmY@9yq6w|3yLX;c4$ZL{dwG(AI6geKXXZ+Q<<qzw?qDA8??>>BOb*aGq z_{9AzZt)yJ!V$nJ{ZXkotQfO@@FIN6?$`Qexz~_4?3hejxfs8~pa{{K)Le(g_U=Kl z{nKZkFCm6?ALHMO(sIOJ<z>^O2qOd)N2D!g8FkA=i$`T>A7m(y{e?h5SI#j{gQ!Z2 z6U$*vjn=0!g;MaPuF=XfXVg|~4zn5L1*vvJFxQ-)NkAkWiiseS=1Wi%nv4Sp?Zp>K zmv|9qN!l>4`1@}t;XOU1xQ!*i6jB9Xd{Gv0lhA^Ow7^@}hYWx41B%<w3`C2_#QI%R zqNu-ShzUftoJvugp#Uxxbe34KNvJ`KetGBn_jhc3gC^KPP(e6EQ&qopGVhFjGqckd z64G>q7=q*-ZA3#Ao{hM7V`U#GVI=6(i8c!XgtBlOB88S2D5oieFTFcLjxqC$G0NUT zrca6j&wZdCPvdzZfZA&l97iqj`!6hk*-;ar@7>Bn{x882fU;-|VsL_#ol9919Fnk` zIYJ3r?hX5~1b@fCo95=X8Gq438UK8Sb_Qor=OtakL|-9NZaUCB2^ns|<&LI(K4c)n zpfH>6WBX&t;00MFpgpy9=YJ-%$T(8Ic=tRg<X9^T$t;Y&)*=5Yb{F*1!W$;4AeIq! z3aoP9gW(`Dv~3*_%B?UhZ$Fde*&e$<Z@-WIhLy_r)r^jjQqZ{y)bb#YgpB%R@uQ|F z(Zu0xc1UWdj%l}bFH1T~Vp|qkM|KT&;Rd+g<BJ_Z$43Z*bi=uUZ#O%J_?-=FPow8q zd(#+^_G&&CYrdCja*+63Wm*C!#NkAO-1nbDiP%WYO)=Tiy;KE5cjDqQuTHO?XF0U> zA#v954EuL!z@Jm~oNb43J;qQHW<$C>OV4zodJ*(3@!R>NlrDS`mk#ArK8^*Z35hNi z!CO|{5q8St&BziL)6PQ?a~xTSySRI#_INmSMau|EsoqE#!2@+Vi_G-f&I>tPgUIta z6u}{aLh(_~y$VE0enyz?FU~-cXf7Kqc;aHN>drK5mYB&w$HCi(20}kH8pfg*<g{r$ z*8>=1i{-n*PQ3P*S1FWq1egTXh(dHpXdk1^h$~@*B}{uyq4&T8XCmc_a3^|M4%P!I z?k#X)DomGPsW3-|$vrd<I4<mgz$>WBC|B#)hx&-eLn5LSPXet3<r!CT+9+LQOZ0p+ zX$^l7<0*5&o8xSnnJ3Yjvo+*(q#PaP8O+p0Gdsg=88%M@MFoMid|qV)7)8CA^oXv# z^CAE3uQ2L`gj9}eZrcQI4|yuyj-DqH&kXsRdP+U}Oq<ZY2ULId36vKk!~59xPo@eh z>58fVLyp4&@UmvlGjo`EK(^-P+2xwv?@eZoi_Uw=V;iUW_^PN~X-IKb&x)r_DbMX- z`U=vqt<qTZM?AG`%3j_fkELUyCn<LJQ<${EO8sAvZZmatxNlLOarw}pVJgvHjcObR zAQ;2SkORTJs|+>GfcYU}P;tN`GFSyHA~xUCdx)8fatv9nmsrrSW6&AATs${}ISdx{ zKYcP}`y^}^cW~;+{<HuG(`~_-FWsyW>`9>&D<87u2Y9(Eb%}lEqA!9yqA?}`n%-^U z1Yl|KW{Ba!QR4w~j3P=!M1*NE^*eXvCPfvkgG%QyZNN_pe<?r?X5!J=$C^u*etgTp zNF6L@J--#_Ie&WkCQS-qm=FvGuBI<A2Sb()G<iULO<S2$TB~)@tEZ=?MTUJb%tPA? zOiY?Ya1%m?e+8#c-*rKQB1W*bt9c3sA?Z2tC|*eC7triJuQ1T??6w48f3`q%S@Q6T zCpA*GLU=AZXECQjKUvsRQ=-&L9Y0k>Yp(9MMHn(4d&}Ni=ANJbFY%_t-PCO8qD^aV zxqFzTL5P{_yGCB`aCTUf=^P^QW_uDeJ{#b(CDDjezxTmhJ>4w17>6>=2uL$@X4Q%T zOJ>4Z)T+uoe^?*~+A#uxbs*!!kzexEli?t)T0*~z+o1`>#poI}Gj#sR6x_MTH0op2 zL>U;(h+yxd4eRs1#g7D?`_CMce45l@Q~I%L_KNU&7t!e_2go7uj@QWgD!rnhh)O)i zVHl$@es+DMaHFdsmm%6lh?33;#V$}%nIqh1<7Dy_`PyvAdrY3fUeTY83h1y0|6%T4 zPJb32vPR=MuYoOs{<&8qqqk`;D>fG{Rw+g&H*pax&dVaRqRK_6@M)k4n1{DcdRu=3 z%^s_qT?K>+x&Se-mri@c1T1|q0<pl=R1wZUI`pe@)OpQT0U`M_(U(41?~8Ng{|G%n zwCE_m8UVMEtWI}PMg5zEG@Qn(^pb7}Q=>BCzoAog1u<2<-iP&HFNukC=u%&Y_=xs} zlUz8*QRi^O<>R(j3YY&!=#r-i2t+b0tb19+(6m)HuXu#0{QZ#l36!J*Oi$tpk{)cx z<Hs=QcVNa%i3(oz3Z&#ZFyUGc{+I)XDp+=a*-L7Ipz3Vmc9?_m;3Y7+i`1IqCE9Q@ zeFS-8BGEqfHMEalR9$jXHV-v;kZS<`@=6R{OZ=qfa(ElR<lTJ}J)-Vn2LstG!!b~9 zuPld-yTWpTF_|RzA@Q>^t|0^f%@*P0K-wTvBj16aOG|+e(&2sPtD&y`72P%ECOk0X z(fM^oE;`gxf*KO4(aj<EQhBOW_FrEaal%DYB$k$lg#wYNS12KR@9Y<N9KML4Jn;8K zVh|(=%0yRMWMIA`oink;MI4B-A2woyJ=NYHr8yCuUZ#7iPxL08X(6Ei*-e^nP-xo3 z<ZP5aJ^v&n%T%@^&2k?;o75SFkED@$7ybwGthIdi@=+yzo74}Y1wd(p(I!zIj(lmR z65iuqa|V#H4~l@E%m`N@jA|3A3%kPIPSI1I8buo}y7<LXnFDi+HYP&t`b!r@vMQ+f zqAA4a+j(fL_iY`XUd|}?#b(Z${Vux9y1G?1Z`esIL^o<emwB0<+N?P^#1}-doFk$c zIq{~Q>8}XZl2*l4_92Y-M&8T|^1<{864x8vft}T%Cxo4KErEo|u+V_5T#7pnzLEyx zTHsp3bi<|;q`M>vUmoTRi~E@5M`*$hiG`gr^f-K^Kk``LNeWlzL7%v5bdu5e&3W5m zuFV&1x9}sG_Bc>0KvueY#IG{1Y#9t}{}^V-mODm#=C|^QS~jps9Q5?63_^|<^aqF+ z{L-rqA7TV0nX@cujn}ASuo(x}aI>?gWPbK<8lOelN8($amTTubqaaCgD`2Za`4-&= z>V~$zVjO!#gp>pv4zqOyFx=OlmhGjhUoX6)iUm1HYj2Kg?A65_&4yeo87{r8fq5B% zWXoXz=)FmQ<?xd}+XD$DY`8isUMhNG1m5hh2&VYeWf%x+xJ*>6hDpr<uh!nor&k>} z4mxE(${k1u(nsnNZC^nj|Et(5OQLY#{%X4A2;0f2KOj8B+y^qe_RKr$aFSxL&Ep<O z%Z!()<0-v^>ldLtOssliuA#f*OryRpe3;O8{TFD6fAl1zEXbbClf{DU7vo;UeZxvl z|4o>nzrI9F4dis`a6A>?53nxt%NpoyLaL5f=Sg19w;BHI^LoDbnM5L{;~I_ZcQY-# z8~T!{o4~T$@aCu6H1%usH8k#GZ_dzDy0?~|4SF^?%|W>?bygxhzjRyRj`!A4>LWwG zjYWtyEqQZe#1YnjYld;Y#8!+MM3{9?a&^y0wTqso`xOx&<1d7WQ)iszjk9RyX1h|C zM3(=T^CQs!AEMZ$1;hc@S*;$TRa(90MclYLfeFuVocW;daUFMEh;E3=kcVaw@XW4? zkdfEv(jY<*HbZFaE<jrwRL*xCVF~G?m^;{Q|5SKHVIafrfTNPp2v0b!j1(`ASB0eu z5axup2>RH~=mruwztm)5<#I|*{R6M!Cs`I}0^XA3TiGT$@0-CfNguVC1CA){W_>oP zpGAc|aK_TB%R3`<jnI=hTRxbVCQX9qen~)mJcU-iIt|}1^lU^!@@oS`JW0)_B{!4U z2e``Y!`FCwC6PMk{x$smFixFR9(&$t?HPfJ6mHY|9*whWgTiIE-t$GU2JAGd_x#*Z zoAWsgPQo0HV$yRnxJ=snbZ=2D8_pRP-~$6-Xa*3esX+Yp8?*l*0+5C(jvT)u=5=5j zhI1KV-I|>P|6fbz6B0!n#qljX<VjlS5NLC7mpm8?DTIr#1i~;DNmv-91hKFX^hXbY z5Kgz;gBxs=>>&$RH=@W(2Ny%3i#ZA-%^}3Y3QKNMR?d>{?(B?x-qdv&=Fk4#-|u_x z`?4hBuQH13urC(7!fcAgzGPcG`Ja(1wpebm$x^1}tPX+f3YjyLsNas9MzMjuyul<) zOTrAeHjR+n2Xo75u^MpgR=F*}t!LmB!LkFG=2t>24pTnJ$^`;j)bz4vA1kIF60g1Z zzY3!yz}Y~HM*SM)!1kgGX1$DD60;4^087AgCRX`Mx482-;>N*+K(MorQvtci0JFf- z7=mttxDerLrUYajv;`y^hq4uts8ftj&$DR2?VN_~i{uNWi5u`XLP|Rn0AIOF4luS0 zeVKu0q_>~Qkw93Mg+^0NKIM9EfXiwA6j*Z^&Wbu$GEFuINwnxfn2sy5HDN`DXy7O# zNmPyKDJQQRyMPlC6c~I$NVwY5Xko_#oYec54gU-<E|_)FsYxl1{cfry`qhTX<6ueB z4oI3(mr!ARix>8#$n5*6Z$^=e_=pB=IuQ%o{!}R-GfhI^R!l$VKa|j6cQ(k`cS{9A z041eB%VWEOAti!y6Pb%C-vzP`)3aU|>Bf+<o)yJ_=SjZ>vng8`=bY9#ykLr8<*)&M zeV%h4MJxDlexBppSh2&bk=HZ4x!gR32JzILYwvD~XL}aBBqnxeHVD#CEvf#dpsv`G zYdVP@eV#fgW4pca<o<-rxr`!hRh-V#TPF;yl@L~cQwX1P2Pv@4e9k^uo$4xz*>jfm z(LB$RMDy*{U->(YQhlKyfQbNB(F?}M%7n9ez0au*MQRnknE3|NHMSSSs<Lq#PDHlb zqA%P1p>m{SExn*WirEK@h$LITG$L?#+XUb6eSPty8oGDmlMS-5SJi*OU9^7waN{pF C38IVu literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/10kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/10kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..cfe3ef63574bc27d83f5d7bf6b559d295b38f42f GIT binary patch literal 156881 zcmeFZdstNE8a}*G49yDB4!Z(|-3$$4!WP^KG`XOtVNmx7qNqXC79y&hfe?=2EH<`x z+F{0-0g22R5)cuDJZ%NZ$#ORgP@^2vL^NhND##2l%xUr6FZ~YJ_5JmI-(TN#{jgNP znKkQu-sf;X_jA8%=GU3q)RNd&MXyqBZf?{Y_>Y>o^OxpVc4xdrQ5!Z;ffPk8q}<(B zQS<QCVhS(*B!hCt*KYWF%YOg=`L*BCVQ<O<KYIxOwidrB?_vD0gnTvkYt9057MQcZ zoCW4AFlT`|3(Q$y&H{55n6to~1?DU;XMz6{ERdM-e(KKLU4E<ng4NDHIDeK+c$A|2 zK36JczjhB>y^8wZ48oFpVwE`tfmmVg*PI3BEHGz*ISb5LV9o+_7MQcZoCW4AFlT`| z3(Q&I{~Qa1{3RqL;xFM5e_7?XYE1<G{|liKs0Gj=5M{!=zmf0e;d}546!n+m_;dE> zuaKX+|F54P{DWigtO566B>yzWF%T=v{hG7DoCW4AFlT`|3(Q$y&H{55n6to~1?DU; zXMs5j{Qt@VpW|+D@_>4P{Jo{u_V9wqJLCqr<a_+~Cx2V2-=6s6=QF=iFH`g9%_INg zmplGnuyDZwclQMkdU!mr@Sz7EdT8;3ix)rq$kHVbKjQVs;>AlIU*fgw(Z?Qp>><x5 z{`B~xe_HzJV~>)HxXs6V+!ribuwc=n4=;ZB(f`-KX1=Gq7S8{E0X5(48ET%F+k7v# znJW|rce?;5FUaAG|MAOh9`5l0kA;gKT#Of-TSCoqn?HY^`+RcOc=cZVJLT@RVCkP% zMLn=A?oE$pG9L~3r{bH1+?P&Wek}gleO~C_vkDeH`1lildh#j%XZZok16Tj``88qT z5idu-@~SXK6uT*5^OnS|+qUmWO?xZ-?TmMJW#@dDyIZnn-^c&@_b2-ge5zCx79A@7 zvgE6yW#tveDvwv4IDO{qx&NHMP~Y&wk5~TtldehM+}7UF+135)^&5A7?=zbE2L^|R z$IX_B$tml!%}&<khIRhWUw<s@|F$kKtZSaT`+Ro~vM#rIx%fTb%YDJ0S3R&aD$e80 z%w^An{Bz->FDbq`b$JmtH2(f$f6u!1;N!g2cl^i6(q>oo|7>9e|DRU&zZUkt*L8z> zXg=sBulZgSO*tKMSE~AzM7b-ygyTFrL#c~)w7PVzT{G07B5!q4<_tC7P@tzf_157v z4KvieY{@ulv1%?JH!66l)){JB<Wk8DWo|2T84t}+lfRV9*=@E=TeirD68faLj8o$_ zrPRWHmEffx(9cjW(jygX!<`M3;KB@LD$i~*%IHbvqKe(77pr5O+F)0TEA%*5&axZb zj1tY{FJ-t9b+VViq+@IM_gRdki+$5e_{CzD?rG=BTU0H$g&8V&`F-IG_1>@~GF2(^ z)=U^&$zFO>J8ROFco#O!P@Oi-@Nm8?jO!XGaWs6vGv9U%j5?dsOL!{QT&bi(#I}LR zB|>keQAYRLm<hwEkj-nz%Vft|Wa5xgl`ExWi$ESEc2z}s={Us>gDpdBo}nb(g@$Kh zoCbS_SY>4<+w%R)))}gWwhzQhn9KYzUZuWYfHlgAp-flZykR}O-8);vADyAP5;Ap; zW=cuhhc?-iLPtZ@PL6AJRUcmKFlg94!pNmjIlL^1G`+ZAI$EZ|MYPJz`;Fv-6JUH* z>vgPoa2_4nqQMQqxPoRFQWs~FripmIOtGVZ;#S?pyQFDRjtj;a>RQhG;R5Ysp_}&% zbwNHuy_2w1#M3m+P>DVqfmy-~55G`n8<?TwR~PJe8XW1-%thsXo~yT*V{hipP&W#x z={|UhU27i@Dois}H*S5sg_iKy&yLbPtYwCJ<*GYwH_pZkV|y#Mn)@vDz!4!??Z^>I z<iP%7_e!h*vS=Bs<S^XYEOIvW$zp~Xy4BS~EtOhYk2~vm@>VP|7Y<qF=Q5h5=5lON z1Xbx1T*4{dWK-z+g`1ttRJ}Kws>U8FMKjb&UiAm~i&^n39qLMZPe-;W^6A%ou$aLW zLp$9@mI&`W*(VEQdmkvOqKWlsyEfRWvHWr=?b?8Baa{-#MC1F$y7%v|t)5Cbr|*~k zzL0P3WlOrgP1Pq^cTNje3iJc!K6QA|ZB?tePvs<A?fm35ZCXM1%V+nsn4Nmq_z+@4 zz&}>;(<eMO{ibpe5BA|+JI;LLDiGW52-IYwHms<PYm_v2pSRYF1INE8=iD!P=k*kO zJ=elh(~gX!=e%@l>+jTstk%Gt8s)97UVHPzk=Ss7Z9o<dm;Ff38EtFK*;zhAeSCO> z>*j}w8@5c=Oxx1QwOb48f_5}~WtGJ4Ir%x0*4fy^Rnk5Bei3_$mcUZ9*(dXf8#^^Q z8SEMO)Ul$$_>@-<MT|Mm%3y<Au;PZb5_%#nv-ldzE<)&gGu9r_DP3=r5kdA3y0dFT z2WMo(H<x5DDkU0oTkKCAT1mgif9I~RFE>=%6EyWI7N28?sLJKo^@0Y?-{4^D3x1oS zYLv0dClHPU6;bJX@7IdB<Bw@wtL2E{#MjTA*lzoWK%K-`M;kx8lQ*vW{cRq0{k!5s zS=fzmcpnUl^z_l-TZO-5i6<FLTR5EyA8d)BbKN;3Tp4W}nxUR^HsrNQmNGS1SGM5{ zKGHQ%3_rr3{yTO=joX+;rAVN)rT2@ROk)+@c^Rt}XdUT7d%e*j(DvYhv3!~6wrYlw zF&f*zE8pY7146sLQ5!<j>>f#Bls9MMml&gk9yuZsWQjaT)=cD&It{KT)-UW+8Dwkl zeZO=(Kq+Ed_zHm(fv63&X4*6p?W{{D{L(DRl4MEE2wO92g0<g+tItqLgOtXVjyvsj zo@IJibEz^6k*H=S4eT~VTEuyGg-xAwP@;fk!(hTAzNykw#%yS*_+SNV4yPskOg+{= zq)xGGZ!sSB=Kol3h`gmqEMD}B*p|N8d4Q{NC6OKbrF@>KTxI2$e{`ig%#0zH>*^gv z+R<iqC@!<LF@x&iFlW7B+Nrf?Y;k8sxGJmq^=2g<B;l#UcyhKOA=9M}<I2RrEpntO zD?L=P44G0X4iN{5Z%G&(o7cRBDxkTpq#5d>GB(|L#zJ?_Q0?J?y(RoHq%TvagzM7T zwV`;se~i1P5gx7$k_W}~$sOvn7_&qv9f#|;NAToUrt!oDFP+JzBuoE|w!Jm!QNp_~ zQNCu&VhmXK7MKsQJgH81?K<8kE1z#IZpSW$b5*T2g!#^+VO)y<*?@1?^Nxv*>3GX- zhz4}-xLCDJ#O-xp-)5-wgEBgVR*FMgY&>Pew~M$WbD6Yutrbo++$U$ZOU=l@7P^c1 zjSe1V+G%?R?q+$O9v@?N8iK@=*){X~<Shl_9$Tg!P8HxXX0oGnFx#++>$<5<A2rI^ zuSAXp5uM9Z*fdu2my3CajVh}&#d+2eAVcm^N|X}R+m`U<tZ<CZbs$kUA)y?Trk6Oh zFl_t<uO1;!nwlkH5DAB*={HsE_0GjZf+lA@ZTdK;(gZ6pjWv2B6BLd7Y0}u6gFN<4 z|FrOS7vJpEPGaXzy&*fFm*G)dL)#5O-@b8Dw(D;TolV0xIgPT2D)$`eLZ<;CP+j`S zzz_eq^y*;;s<gzRUvW&ygvRc(Dr^b^dz!xWUaj~?6{>ue5KED!7FGCn_Wrt~AdKg_ z38$|;7T5oL{dcv}QTuL=RhpzhEtp7K`x6uNd%G2{{(?VMG+`F`myhfD_NJ-L7r1KA zU?ieLIYpmF>>n+cttQEzWU@6^uIYUb(+W<pAXCR<Zq88uDVz>&yts{v@cgZ&_px{4 zdbalbrso&;N14W0(?;Ka^nEro`q$T{t$L$qwsba`g($e1$@YQT3{K0*ol8Vh)kAy) zmS*CY)2S!#?oxc`n?4qRn!BFV)l21zj2511uW!oeFro~1u~N{i#GXYik!0I=*bQ}> z7q<5~giE6E{zmux>NF9lgyN9>Z{s47Ua(%7;X0s`hF=n=cQmILM=rCG)O9FZQsjLQ zg`AC`PO+!UVo|F*vP7n<^XblO-pVK}m>wyYrmdxKF)b0Pvt@bn2f@PH6kO7g#3pIX zhSusQ;zcJ|i$N)J!lnJiWi!-Uy+UJ(O@W(wv9D?}*i(PZrhHW?$?;3L=Jd(k%R#;M z*%@`eR?;UE8R4pvIW3|S2I5h{Er|PJ(O+A%p{*99ioKEG=+TW%t)2}2_xULrP-qoN zyI5eE^Mw$pnYDNQK-+f;GWA<k(*-OusnYXZ*~(J(SCW{E5{ok(-+l3q9l~$h)6Mtz zmKkcOVxuw)ephsuXBP8&%UWC}ccqA5vcA%mEp%KM{yvYnSSOs$<d>8VZ<HMFLzpB> zYLFVgd-~4j(!GZ&yh%8qBK0RcQc^9@3_IbDBb6oFBCgC(si$VB9qhKQpC@+mQ2Xk& zf106mpQF5PYJOkRRZ%6%5fsIT4~P4y_6phBbK&p*V|$MzYx4!Z1r<4W>qb%H$<&I! z%X(kF<VXa*vb5BmX(7>A;;m$A>LS|8T~29=%ULIGcN)G$-P-^llNMlkYExjDO=ZJt z#I}shbT_{0HH6eiGEiP?!|)p4B*0l$YR<F&<dF?iii3e|w^()bDAuQB+GDGp5<Y7a zXs4E&g+4WzIuCn2-KmRQN|*377f&pWLeg&$2i1sp>ZBa+teq%avmkFF-krr%%VG$w z5_?M-y8(c!RaT|}2F8m#irHGRZD_qL#<;IlZY^{xdzVwpL+UWuiUbP1QKAO0R#tD- z^AvEW8R~9e$1YS7)KDyqTiri@{+4|$=K*x>^?`>zakOx3L)-V%NK<D^X=48t@h5bL z<RkiCMch)WeDm}szB6Ho)Ph`Yh_(Nw<22qkxXvIXQl4?H+1=Ou4_abkEd#Px`^c4R zx|};tB61FCENw;f?@xBn;duw>T%To^O*Y(1jj~)8<^)EbUOs-qRm^VP<VA9GZ?jC? zqthZpGy<i_KZFhv(VbW4Nz|zb+;ZG!v3Cx~UN2}k#j&3ODCd{(kw;;Fk+*NUz4^R1 zGA{ZOzP(xA<T6o!_U3kL)+TO2xF2w^a?`!{b|9>~NKL6JyL(AUx*xN%S^b6|DFjHB zZDndYh;$@uedl>sZwc9_q4JysRv5n1jh7XpWCjgEWlHfafM~Y%B<^4Vh4j1~zJi?b z1*hex2;rlariB`0VMbT)SOA3&Aa$@MmeHW({E_6At90I(SKWZmEhw!wHfwD;O7Wx; zIo`rE4{M8g>J;Z0WsM|L&nb?4Y=+uBLs{C{l4}A^BYKWTxiu?6!H$Y2k!R6;p;9w! zN9luXE-J`+GoUm!#ZfQNhJ*{6xxZR$>SSR*>P)s9r}z?lNfIw)&sa6PT%QUITvxKl zI}^~|YD0&BNHXah4X50dLQV;C%X03yn6(mtHWce}>e0qgAtIWYp#*TqBSP9~k>l+z zb_)3=?r58=@YT{qT)D9fu)sDX{$w<+pXA9Jfcz+<bhHv(lP$w%6?%s;+@dyH=&dkt z6p`*K{TYIH;Gu_5_;YpuBZ-4bNosb~2h79bb5F;rTG7VE=^QBUxPMec<;MABqe`xk zMx(QxuNLu8@9YC{GmuPhMwYWlXcPJq;27v+I~01vSbd~drM(_l`g*$nf1$GHZs`Nm z%ZNsb&R?O!{tV+PNb|?waPrU=r92cJmy+yhZJ}Gd_?Bpsu0P?R(9z6S=c7v@4P4hb zm5amf*|I)MvP|!?pWi``8fE!wvabu!FV9eMFhG066!S^&n*(}pHs!kD0Iqfnn+OEl zmviS^kz<Bp!(TstdpGZb*{Iy@)Yh}E&EMO1{;>AB_SLURco$XHtf&W?`c%LpNU*Xk z59{PLkB4#DFuoFd)1w0n-*{jC@3UX5W9d<rBnyr6Ol_Iti93dWr|xt7Z8snaT#;8@ z^zPleJDTe28@~Qm_x|U21<~RV5m(l@@5)nG#)r4~rZ~SvJpeSct}`6adOY{W#ey*I zMJ0Vpaxm(&n7#h`%YB>!ue&!~lI?vy-0!TM-70d=)F;_LT>V-756t@_pDzHfT}Ek2 z@tHB!eCGYS^MDJ$o)$yv$=~X{cfZ@J0#uqr`*k9D_r;eqtpGsqpUPD~iQ%4zCm>cw z^Us&$Kt<A2MR$r%*JrZ<KDFoPOQ+6)iAZ#4?Qd>ZexTB^r)##tW6*ST6-^bH^bT!L z=i;qSZODn+Tk%8G8jfBp+iwJ0;F$FLkh6G(GQR(<OgxFgzv8-cgXzZb>nSCUdOEj1 z@zcB)UA>>3?IjHYs{F{!Mxpy5>#Zau52>4m_eE9xj82MQ!o#k)k_r`iZ-t&c!%8|2 z&}M%jFxyA;&@uZ@CiJKzx15RwrqeqN!7bIk=`I3nhAI+eyN%}oNrTX@`9CpF9O_ES zVp@=M8XXgSv_q{HM1;DCqd;g7;5lXmd2uE4C!nZy><OBZ^$Tyies0XvaTM;%MRQ-7 zRf*O*Bn(}_*W)C;@Bm?2uvv`3Q|oA^cPn%zb~GHWkEoxa4wCKx7E9#Y4UP;`N2X00 zo$E`|W!J0b1bDmHVU2tYWdy#NC1UHWg(6PLQ_`^(SI={YPU$&zv`hYL!{}Y!q|&8~ zab36U)szUd$OWSkE{6<Pa~u~FVZ&UvW~iPH&BfUOHmssenlWJA9^Gj=7(TBXj!anI zFT_V=N$=qun|I$@x0U(OjGW|3aZaeL$^@`YsGt49I4m}2K!;r#D9^sP_j}TTy9S&S zD1Fh(SPL$u)|lH{j(Xl=YS3&r4|A&sVbcRZ?7AsUL8>@bc-MVbr3)dZMiPXH&24Zp zesR3W151}6J)~%0@fbl9wwYfN?{1dPP*#mSs7xWKch)0P{|OGN9B(J&#!zJm#}!(J zJl7pT@hxDi_DC{qK&hIGVs;IC`hY;slN(%!`VnLiOCYR|%!+T-igr4)Um{KUWgMgw zK5Fv^e3b*)*1HIOkXjsSCHP(@?yE$C;}W}p-r`x7D=u@2`NiHyb`pXn)rDK<x8Pq* zn$ba7xZr}(Os<`U21CPs#Z)7G=5WSHwk8ajx-jX1WTqM{fDP@TVKgC2a!|}eWTk)u zaVQfmB`8Iv0k#CaF=^(!&MFxWY%=t<=3=?;Q4v0tP;?EV&3vWkd8R$$JYnNv5Ky>u zQT%SB8RdS4`kq_)fnbg9pyaC>puDjaPc7zzw$zsWgfO`BySS%gkI%`E$5~c{iUF6; z?D{FGV)4@n$_AemcMpoNR?=wqGa7rw`mWX2@9i)<<%p0WQ`g@P@9<XX2G~(g`%sj} zu|am#{mvSV_JVl|ULQo)3!N)BJlG`$bs=;ZCJ&M;B$ca|6%5l89x@RRrcjF3pPF8A z@*QoX?4zx>(YLm$N5h8SyZF_Sgc<6IvxkrOnQtq@@ycy{#K&{a<|_KX>(G<P!nr41 zoGGR)`?sz9&PLIW0h?yL&tr_oI5M_H%uxICp4>6tr5-bU;k<&N{^A<;ASB+j-%B{Y zVuO0O^8)Gl;&Og}d$Q$G^GaR}Yx>}cjT!$rgXYBlwYEm#vxgD35_r}&V_dUvm2j)7 zRRd%LTS`wcq+yQL*1VJQ{zYX>AIPP^j}@It-<0C$93L;8d7~TH8}nc+0OkyJt|KFI z>4(Y^<EFmjMius4ng3h@I?D+xzQ|vg$uH)Y^y3}1W$c5bub<3@6O}IFDP!x_*qar@ zYuh%u14Wdur(;pdkOI_5HoxS1x}Fe%>>GM1fw>HxSDl=r=8Ui2b$ROHbyn<ZwM;yk z_-9jlTYiLQ$?jcE7Cu@;AVP6a{Z3nk!_d>c>5jpR9lKl1rXEB(JvhX2@3$&IRNVqd zT0b~nWfnB^<Snuq3D8U9QRI%?Eekw@TdJH|+fckD`yBNOTN{yD^gdEs7o1j_Ohv&N zK`OY6%tRX<^xa}GYDqT=!BHqZZ5gkB#MZ`+U0SB+O#S!fGM%?Nb*a!>gSK&%t#I9~ zg^o&54iIFzz2U!|E2W(~_{FBKyJ+uw30>75Q3kd|ouojrfm_8svadO))MZNT0nd=g z{4Rb-|CH^%(D7+s-O0R$>aWe#^~XmNHvkcw`Eax2PlS}s<rw@|Z5_+=Ii{;hiSj5$ zfT835j(^3=btncL=M)H5Fz83(rxWkgJ88U1l<QOB#A;-op;o!iQ-@CZOm>)=me`gr zheG+k0(ik2nE>S?!G&RQNI1G{P&o(iLGSWQW~lkc=T+K~s|GZ#(4+M2eJvJ&KJX(X z-dy%fi_4j*<Gaot+gofP)QT;`bk&^&ol8g;a6w2-Dukec5c2S|?pP%d8>$*fuN7Xb zIR=h=NHaV*Z~1MpEd#k1tpqYuPL_m=iYy|ufT<!R%z43i9y?)atNU`^LZgHxDW7x! zjs~XWX+2LfY;-7et{LjqCO->Fs}cwHHL-Nxy~L&H>D*KTpn0HJrEu#lAI;ryAl&{f zqZJ+sy4YmXOtyX7NP8=Kl64#aVDV&5l}Fj`2gJeK_gRrGQ&LhyJQnedsx9=Ef;cme z^zHO`PriAdLxHy2@oaai=KK4S50I6aMy!TuJQ^|f&5@TaKN_%CBNd!Rbu`jf_Vjak zh7d8`in+x#o+eGsN>FhmSN&W!A8isefe16uRtDXGg$Fp3M*YFu#{uK_xq3w2jHNvt z*|G8XXt`wo4TXfK8R03#T11PP=_VDqvSibbWV<%3cpgzaJXs?Z7NcPu&0mRHG2DmP z-^@cs!rWt*vRwV}I4Pce1tPwMzISASWeHP#kxUP20RdueiO@qDrN9xD2Jb9_M1P}0 zO3lEpr3K-)EqqdZCGir44vkS@%<P<?pZP69fTZL(nW;ls>6>u#&eVG^1+Xii!I%;5 zQk^Yw*ae1Qf<n4uDaJ0hrLRXFVz;&TApsKi2?72^r7!WJLam4CDarCFGhwR6$xt9M zUI=bPom5Cbk&-b)<RJyLN9=Q@!+AFZ%<I*FmI9n!Nq23A!MDW=O?QtQ(FSmaoy~Hx z7ZPC!ugIgMUlh4)mbQ;)1|Q=Tn{@HQOd~;5g%pyN%8C!{ZIFTR1EMi$N}@9X{J^@o zfdoJ*Ix)zm;SLCDTS=;BmvCbgr{vjYN*yi$vI8cBVUMD<yOkhK%G8@WRKUup;2>kZ z=yjzQHuVwmuTsxP(X^$%@*TAmgQ;vurp{ZMOp`j7m9P}I;p)9vx)5|A8%G#{f&*NT zo)|~*m=QtKASHLbt`Crjdu<tPt*WI8wsU2dE?x?=@|0n>0r?!(xG`0Wc{rTJSGF5? ztAxyJ{ILLZksICN4UBDIqfnq=(N{l%(quNUHza@ssQ23<-Qo4(eXW+;$7Wl$;UTlg zgaBR{Fkjqi9;vynJD@#XZsC)7{3XoUU<9F4!kRUlv4HtkCk+Rb(y_bh)I;i&(c7A7 zUTy41QdgrehsVwmP1{Ue>s1&k%-+`a9x<ncN5Bjci5x$o8%r1O*_l6ia-H=shFwGc z89jNAj|VII{mWH4fIL}j9p|&Udz-AwfULtt-tqkOtHM=;xpAbw^6QfkobP9-KfTjX zH}&40_2U4`Rz-Ks+stY0uRCNL-Wem4o^IW{{9lT$Y;}GxzVdTsuvnTx`ZyqH#vZbt zePQ}o7ZZ9flduJbu))Uf&-ckci4cDhROa9nzs>+vkEr+kxaNM;f*xm<FhiiZs0<H0 zcB=1-bys$YU%aW_`y)Z@#amCOhy~IlbQ8ossT<vEFZ(nqbUfwXihgFQt9ZzqT_{Te z3@5>wklQC?J=YsYMaxM;QuD~+%ON6H{SH8B@!AOM-dG7xm)bMbz?ya^=40inGLYUf zQeN6Eqv=*<7=fo}YKEU^&B8{uBZd$Cv9FAyf#gsWr_9;R`%$h;Y#+i#3YujvvP=m* zil|a&c5PXWzqQN=Z91~mHDK4eo{Z*Pg#XXxYo02VfJfA=BqaRxsUJvZDFCGa)N*en zoHj2@XtH4-+iqp7W2~zkWgSEU!u>{JRKF0J2XA&t(|cv5^MPE!69M-Oi~PWVp#qYI z|2edmWwL0DV8V<f4cr7oAH*VnPWettHQE+-yAUjk(;}1GcJ@oh*b+Tp?;lABy?{2j zMHZ2Vgb+sB>Y<JE>0D5eqef8lOb8wF2YNgN4w=!QlYMT`!nO3_HzAJ3Txl>*3Yv8Z z2Q+p5B0s#MTkp6qs9tD12PCxIf<}Pk9#Cv;NU{L$N?|`!4Yak<onvXEgIi~ZN<w>! zJSc2<w*V87-iCcBahzhZwhdeav4wYTmX`rL+~_h1iHi_lMjzH&{WOdUE`6fil_oSw z%wo7h9SoR6BJn?{cPG9Vd1HEpVWy*=XCB081gUqbB2kVq@)ev2#><Tt^Rh(b#={1` zU5X}_@HiGhvz&d6@NT@>%*lcE=vz{YHHV`y8Q9uzdfyE7=XMJ5j#fmu0bGy4T8N=2 zMpMD0!*JQL6G&j}80HGN#x`%|Y}&1nv)4N)^b1b3n&@>hJ1~YNV0NY8XR~y)96^># z){PA;1WLYz?P}Ory3hzJrPn#(V3RR<B@?fjD)K>JCFF|vCHR4Xfb~hVzT%J*--j@h zWXK3YtV2qCw;CUh-bB!R9-Rre6btg*822axT6w^JVerBdF<?7Nb1|CQvX(Ds)7Pl! z8p87+y2<FS8kA8KP!cmd^iQL&Ks^05x=r?a_h0)({U{`NrG7%waPMU+Xu2Xjh?b6l z;s*L&yUjNRDHlisO_6~IUazIh%1pIY>mwf**!sY|DzxD0Bw|&(nz<#>OtrJyLH)oM zf<X&Hc81!;Zr|vxOvZ=QU>5+2Ek+GC+CQ|_MoS_WaLfi*8s|rh(bGo<=Y<(<f#T3s zS^4a0UjzdhlK;$}HTr1H$it7iVQI=TWjGg$Rw6X@-h~p36}hqlAC+<tVqKfpeR^KN zA^E#Mfk~6aIDamr;;>}I*eF152H<rM3IOd$+niq@3XGv87&Qi%ha;DdU+&+ua)-+# zHeKDYAHCQSPvMwfS*tAK!6(JC2)ZkdW4|2fuDJUR?ha$@wlbMGC<0=F9(}U#-+9UY z)w%_}V=D!QTSEUVDFf95zTD`s^Y`Ef*}i)pDr|?8Xb2;Wv;?DyqKkJlUf<PZZ5Q{8 zGG>S4TMpIV`O<lS|1DT6_VjA`G(B{L%919N68W@_U%bV*&&ug7eQ=c%@b$Q{s!tBT z?N}<w>`YoXQZxNg&Qx;N8aNxOPK&Ibo-C>?>)HG7;cx<1G1Z^n5mf0iA`!!fj%9W( z@-staK%k?#C@V(bdj5rJ+?QrV&`{^!@x(?r2wIkp0wuBnceFNP11bzkCytMueesFS zax1$XF#Fb`K#@RBX4eS4t_03SkTXi5Pvm2%(>v}An2qu+4Zk7{|9o%7H>d7*|7#+Q zYxYwTPNdtgjm2zEDFk<{DUN?l4~HEcY`pmIBcIt1Rrg0Z3_)R7`&&Y~1R@OR9l#R) z5JNH*iN5{>%^)bCEGS$`t}c-HA<Q}fOZGeU2qVIL4s03FSi#W%ae|0D4sv-?{niX+ z&xm{sjgJaUJ%$WtkHd<+Ado>Xkaiu6An3@ANtmwbBbVuE&C>w1ewc)sf58pJxr(i3 zQm6=x^O}qXP-D&ckB_;MH({O$6Ot~&^tC!|t2*ZPK35We??Rq3e3sVWsnd)7DKREu z(lm4e&I6ltf`d#ulGi|Gal-qxT9d}L`g%WU@xAY({cs?0o{xMis2tq1HEYWwa-QZ! zB03A_*^?v3`^cS+tWaann{*L*Pij8rH|h-L+xGwtawghDEAH-mMC{+4-{(+@j7V}M zRA;EBobiEwy`g?F77ezAYX&nu-rdE{$5`IeI}=O}l1QNB^I^^cXjTYNPn@B)05+T^ z#vCmJ)zA-d%Ugz!6J!=JvV50kAu7ul=oOHOB@WaKpccZmrkHGp`>N;yu|3_@eEMb5 z6r*O{5JoFliz`_u7$Zco{4PNQu@ou<NG?;y?4tF73whWv(-AK~bj;uPY+O(;_zsSa z<e!sruT6-KL!F{G*$O3)XP_$s3$IQKy_bToGjSVj^zG7l7+2Vsk>x%lwFKMc_H=)t z0I3dLH4ify@RFGQ5pXNXH1LU_W}^^DZ5|?pNA|C46QL_x%392rIQKSCehRXGrb<_K znJcNtV@zNODMzufW>dDHMw<XL?C7lbEP;#q;Oa=fu3c5UefWD8-xs<;bwa3srkulo zs-VfNIkX1!=|EgLoEJ@D548+v7`X^jf+nLS@XDfok;4#*>9WWVR67Qk3LEATf#C#M zk5mY^pk08_DAEg<S{zhf(6wP4py(D*6#Ordts^>yql*NX@^Aov=fS<kdLRNaR`Hc# zAgTa_|3`t|c-6i49gE<s40+(Vaz9$CRVYcNi=aM0*T~cyjd4z+R`A)EkK+d+`w{uc zlz2@sr&vfJT6?VAcnn?q)dd%fz`c!Rkbu`q_@l$+UbdpYiv-|;BE1L)*yDA1b^!6c zvl$`NS|w<p3c4`68P_}P8bYKI1`BOVs|CXil**(*H;uX1G3y<5AWA25-e<HXRMk-) z@@+O^NCB=P)ht2f(SWkfo6vJD0dC{Ee)R9Wg8f)z^C`jFloAdUXl@*&dE5oq+=R@# z0Q)Gv+c7)n7xJAGs2};OZ@XMIS<GNFV4F9J{<XlxPuB%?H{rf=y^FZo;z%#(k<gc3 z!?pn{t{)BuHC#_DfTkPDGU7r*(K*r=pQnSwA+hQgUc=~$4a#4o9qYHlh1z3>{Mt_X z{sA=Cbg2*D`I2w$!{zUNUFdcN=!AGhHp*Xr;_+XnANgSz`-B9iRwnE@|Ko3qw?c|z z%OHJtzTgr9kpMPCQ>%o?P7JYao!Q6lrm9-@=!uvuaw+5EA6!gu@+1KpC{I>%eng6g z!T8Qq5m+nbrTlJ02Z$K>w8YV1>-`}_vZoMD{2670J;=VBe`+88B@rZW@wSe?${VxB z4Lq<R3R3mYDq{u<b{o%;NhlfB^<3i=!{d?=SrM}hFvxaS3dDV_-+lq`1su=V(%HJv zgiKIUO@ewbwcCX+A%CtX%OCnWTj){z6oG6`Ey?s6r=@hBX9y4^oJpN5cIUiJ?xe*r zL-ofJ?HVXX5}*?QwIXm%p%8!6V=crXih)2?fPd>}sA9Oj$(G{{ioTd&um&PJnv|xL zkYO8Wl}0aHmdIOS;|v?+Rt@7yWgLHtIE8-4+|II_*iOfH;GGZffTN%-bTkdRsnf@3 zq-YRR@^GUJRvzFGjb`FHBN-3a9-)EHFnZ%*c)nU0V-!2ki?G)>v1afW!KB6N)cHiR z>Bt-4#8GySO8NjPC$liyb7%qd)(>7-nx_OJLLfF}gF;|Whl3JDHej9EHoh7AKZ$6E zVup7DF;Sy}1eCZ3-eHVA_*~35GNo4DA_t6`+7AX2S5aKk8W8EoGHB#9q$X+XhL9ur zQwUgcC4zff;r#yq14pc2Zlfo2_$3@%z6@M&&owkLnKm`S%@gHu5SpM+F?bI|h8<56 zb&kf~kVn8H%OLY$iDv&qRm(ZR^wbQ%{4u1W+H5!67J8<EN=zwwOX9&Zg5iTth;PNY z%e~QO5+^W~XYIA)Rk{5V4(_v4N4jc2sUV`71HZ4Nd(jekl$iAWlBIE+F)%@j4rx+W z6k9727$#AqJ<tchCoHU4ZW};MSEw1JQY57w;o2E07?MepvMy2NQX#E@#bWx{Mau<x z+@ZEmzjB96!UxO(8nq$Z#XyrpLbmOXE+X<F2eBQQsbJvIlc?m}6rm}yXZWXJ4+ypu zvdqwt1P%NOMUS@pQsepJ_!Tcbgdcxkgo<6OGEVh@j!CAkEMi-7$Yl2qn3U-GY&CXV zcJ^5GckSyO&$mPVs616$CR+r!RcM>UT^%agWB~JJ3iY!DD47t*QeK3x_NrTdULpF+ zLZ(JmhC0(fLpjnTmkMTiGC{-hsP!Op_$85^=;w&hi)NJ^u@Kf!BJXU}i2(B;W#NKT zvNs?kk2~eJ5)@ZAe4^tibOPj9tYn+dDlD5YA%E^r7%%`b@Qc~g1)rKFg+iaDB1iKY zKux58VvNLoi$wr$TgM;mJ9>MGo{Z+K*)tSLQ)SCR1{!X~0ZaypE+jz6D0XJ+0|MYZ zqeE;;@p{+I?2T@Y<~-%jqaP!lBHc5cg^(MF0?;Z9*UksfGaGA*e^dvlV&zSm)G2_B z*#1UCh@2#d#CQ*;c6Zj|!L_|_@}$vZqo#W@feFq5Y}8Gs|98`1mH<@ecCn-0ueL1d zzH!fgKmSU7*gGo<J+#VtASzGi3E{!<RC%lN<Yo7RB9lI`vOTY5>%cyO=}#E{6o(uS z&Pt)%VmwE{z0Xq2nGZ&YADaHJlXe`SB^k86$yeOd{pw$XJ(D-|OW5e0*j>8*^~?cV zmZXTov9uMG1#Rj`-}jQbOSHDvq;uKmg5x6BVQ;0-x1t}Gdy!lBB06Ay@$#gB+;{yy zabhy(4K+cfdITM4;!XyM$pX+Y5RdUv-6f6RF7+2vBXIqY(Xd%O;6GW3maeU@?)eLs zj`J>+9Sk>YRK@Q@7LZRP%Vg@;vz;=$G?zhOqVEZ6Y<Qs#<=s3iJ}(`WMeXwa##P~t z_WE7f{>kMCi$e;%k0dX**ZfP}_FkqX#(2zIcYJ$~kVd1a1$#h;RLWa4>~;Xv-?Mvm z+>4j&!ZzE|lh>By@ZNMbFaE4Q$i^V%)P+L6!lA__pV`!h4MejbMIU|)L;$o)`1h<W zueh^GX8e@o)AuV2Vs5KZTU)QkOV&n@+YazPU|OIPfnMYd%#296st<50eqA`~yf7ui zkV^#w&sEbQ$R0j9H_kGbNbXDQPh8GZr$9qZm<}YEigyrUXYb!d!I>R|80%_TZ~egZ z3oWFLNOT$MQ~ZX!*m1a}>ulW#cFFK5{Wk`86bux%)B7Sm`5{EagRH&vIDC4WNgr)y z3}DyRgGiEMnzHd3$SIBBwxS_)vle-)FmP~c9oA?piAW?#>r2#`p)IBJTQR7Dw8mD% zGmG}}H9TdKn5Twno?mjQ>>MGvm7DARWMBrs1R<VdsdS<=8ja9E{Rh2zec;DgxE_-K zA;`tAn8BLBfdb}*0eNC_)My@zaUOsoI}jg-3JJuVwV4SL+cS8Kr7izS#3q`z;!QVh z*w8Vq#Nv<Tc&i8?-%7;Cp@4U5F;<v`1?i*hI7<NXAr=XV2w4s><YOU;$Cj+!L&-*r zsxb&!K(3^?Rv*V5XI?{1)ijpkZVEhctN<<3#o6BKCzddZ14o`Szeo1x5Ws@Q8&C^` zeiSCQ_(`@TcNwto2tDw1j)2U|$E=w;B74DPR8LrmtL~Y)0iC}PP%fCgehnQ50p_Pn zHm}a4dBnH<H<^cZ*e?(hDs~UF{Xlml(GEu{J$o+y0nlKBQV2W5J?&T_`jpbekE3q2 z%_>WC!E1MtY4<hnaeOkwfEAPws25!g7%GT~l(F1>)<SSYwv3G;_aZc;AePfnzrh`U z6c`OZ5~47qqnHof$3_Lr!lPT8z-JGLu|iB*2rgI3gIjQa8{IIqAO|=O<?KK=GJV{s z1v4%jgCb_nM)!lW^brmtpb*<Lgs#=4i`I5}_nHmXoD{SbSk{YyA|A$cG?ZrU4DufC zUIy*2IvI`x^gJx)TC+AT5DAc3rKI@83xOVGWvI3T71R<!@o`4T?!zKzWK`Cir-c1d zbN+Keh?NYZaYRyK%i)w5nQo+FKTPxiv4ojK+z}#2>(e4*AoEYe<uDGQRCzgqUACgH zkc<M+?y<G`&r5qa#qlqn(BYyHKfp8#mO^3?l>fpDDPET$ayl?WDFSCGCx2@EM^5pZ z9sp*pG|63nGR7W+b0$1l{)>;(pFQz`&^z<8JECfO#nbWQ|8-3O@n9uqRV}q*1L?1h zilF<TUem-&jEGFKBN#~yRk~K6Pzte$ftdN=u8vS^!vidc1~oivs3MdZn{CGtmqX+5 zv_iM5(?V<RH5)p7amXcA!#TOb_m<f9rU@XqIA!(p-{}wrv-?zyrR~xYw$0)U2jbB7 zKy+PoJm1s@91NLZy)DOGp(hfkflBN%^r!ve2hcT1=v=lA32?J~nw7n9p%3>7jLbG{ z;YYnh6WI{@8Ik80IgyjgAv*9TqBrTi0L<Fdx6e_i;bo%z76C++L_+fiB|D}fnnnwc zjZljO7o1H5Enqf6w56JfHXvkMx=D+)uznCO7}|pAwS^3$Zpy%v@d|eLsjLuWLC*S1 zB@CiYab=@BvvD8|!i!9m#h7%YmzY82DAt-1WZ`Q&!5c&0_$(ZM2;CJObkbll^g~3? z+_VH>F{oCgn?wHzx)Q^iO$Kk!`phsoB)DQrtjYz(1&J6zI&dUG9qva86T~lC=mi?6 zHPA+)X`gB<SK4E4lRNl2OQIPd0~n0Vz_Vg3h|zbd2AT|8ItUb-GT#%>WT>)OIE(GI z=m!RI9E8LYRyD${avFkm1G@k_X65@4@aR26489%I0}extAqvlwxsp2=i1!fznu~a` zf&ILSr(EcVZh}iHWtRwIBk$4&%>a{_B84IlMVSBM{b;wqjY(6`4}6`ek7nO8xGI4w zkxW2&z%yZFFz%SzdTTCTH(euW3R_y6!?#}mE?2ZeagT_p0xUr#t_SG_)=A^IK$v$_ z#A;t524JXWBS(A*Ox!?X6cp~}4`y$m*Zy-6Qmm59_^PV}pUjeA@gjGIhAEySu^odx zTZp-qXx4S{!y#oJ0r;>uxZ<Uisun<dn=;Ouxqu)RD)RvXQ!%2wcr={OB#IT=5NC#Z zx6BHkt7{?pyV^qGPNT>u$zr}7q=0!z-*JGgEmezXaB639#A>!DfQ*lCX3;QBeuN2* zMSI|y?&<AGV4{=&szv=6S~pC3?gyMYiX$IDJR!=6!BvIz`?)IYFduINZ+qKifJhd{ zz1}EQ#`Lm#;!qjYX;{we;&O#xQ7NTZT?Q2%x_r!QBmq>fzpoH!0OymS1&GBz&uSZn z8*x(WRyBJ5J(MzH`yNRSwx)D329LUp0A+wN4P03)g(C`q^rRAZwK9+n#o9_A5TU;? z5628(OgJ0JXO8!2T9leg`48e4m?Yc&cM-3ULeDCW<tq2XQOL}e?rdM~Fn$w21g5Eq z_Nk3faOArmW2!6f9z(X8IPtAVaWoDNF!y4Yb6jaLONAaK{vk1gm@!xQqV01Sw2>Zg zo%4C2zgKHLd(l%KB&Z9Uw)OS&l4u-l3mcr@p7Vuodr~`d_H3^s!^67bt5Y4?Q^*+* zVCKC1qxxCRkJf7jG7*}9wl1eDIU{bmp!?nwrx85pn^Ac`t)Dv8i|!E9Zcvt8?;Sdg z(WY6v;}UI4kKXe+oCK@c7&$|I`(3F1=(-_+HmKULm#0pnwgUL-9L;qvhTeM}4MQD} z%jP#cC$sfDOW+zNqzou%6WTS%c5~u^wuX-E+<tig8dLd?W-(h!_q1K8$zqfFD*q2x zO~?N(4#w`a$DlV8d3+oU|4z&Rui)@aTa|U@6XhcA(QuyZ;^MJKFa&iR_=7c-rrfOA zHX-ptvVjP9t9-*H+Y}sNqV8eC)L@ELoiwgP6;3SKTYMLb8q|93fEWNnFYm&dguU$* za_fheQlPsSa%i=iftn$I0WW4*Yg#HbgC@ivJ%@J?(<`((Q2u-yF;7H}B9Y@vg5jG> z#De=mchqWjk0{|DBLTMJxXx5}o$q~99ZqsN;TM`OZTxdbxq3HZ7);X)r3tD3Xo#yy zI?H<Ybf?q^U$E`uWeJnss^&O1{DTIKxa)-9@LBP+9jkx3yMvi`FYjmH(J_pfaJ3og zLycn-yFIbxE8h6!5Fkz4+mjOmcOA6mPKltN9;qCoO%)3RIm>L)JkIbi7^lz~YJWAr zCYiu7eMRxTgrJx0dj`eP=QY_vCzu$F&h5?Lpy!}x)!9kN@z6cHqtp=PV=oStajUbS zO-3E*la(qV=L$j|94RlP94SFza78Tiy<s#Rp<o%3qmbQ@Zwqa7*KF)wj(mtr%j`kb zdc-Uy;58!r961+rBw08qE1-r0<`F%hrR{(bgO~<#dKBu?qSqyYmJ^gxw8j9PORwuD zV&{O-kqD|}Elp-=+xp|s@CpdK+%Fl|6DS2N0j3b;-vW*EKB%xUYQF|g(jr-Ac94#N z$S=q}TdvNB3QT2yenr!W@7JrWjO(-pA)^@y_=@0TEK52#ZxMFR;RW{lIJC&hN>WU; z*&Csx2CW*0!NUQrg=1x;B?j`5s4qabjmlCSD8Ru5!g>u<(4+6kW~T>g03`w+J3&#* zwrzh8Lk7Y12o}}`x0XJ57~4l%F(B4MA#Q*+h%leZh1^n)%jjBM*+*e`2}ET9u3k2} zipvCv0w^e(fj)kz{0fQgp9s`A-WVZP&4#fK#a-EcbjctOc_0M{QGvIwyLHz+OHzm^ zIh8{L6@$4tA$%6P@gsi;mSiENBD-Vp-dUS42LVljHDYf8K~q&a2M!G)(@T?um!Pfy zf~z$1t`kaj9{mCeb7GvWP^*h(MzF0%D6tQi<w2wXGR*r=wthAQg7W$3amaX`Ht6Fn zdox+(3NCodNO$N-T}c|NuJ<_JU9l7cuk~__ac6s&2{zqsa6Rd>3;+ki1EcbQ5$!+u zlqk#`i1^F|eF*mX8ZvmlXp`O{2TO%xeMFm5T{<6Z296YiAe1IQEzn!_{%c399Ka%g z6KqlEHAv%&c#4iJ$t(kdrimOlooFkERz2urFaY2$r#8Bo^bmaoGNG;etU2ykfI$Q! zlKIm7=S9&#DkFgabU0n%N=~!{%>U@e5Xlp9tR-zPXUEjVlaKrW7hj5sN61w3$bk3} z5qpF*T9y@qj*o_(%L{i$c<geeZHRv0x#He5@KjKiK~r;K7`NE1!%OLVl{ahGI+6<P z!=Q^D4QihqR>%pMmKW7&={w#%63bNM@bsYTrV2NTe1ZH`zx6Nga<n+UL&m~=MZB+S z;40;Bb-O|duSdF8*Okmh4QLq<oUJvQ^B@=<7n}xi(1||B<U+_4@Z?EQd<t>{fiF}o zU4uk|rJo()JN}LvGnJE;%v>^s*438ot+9^gKc9EOid7=54)}{qXttnUxsDkFQPTg* zx0)P%dDc$<2L!bQjdM%s!<tZ6IslHB9(o$0xPYhn?1~#%2K+EXwc;RvEr&m4gg(aT zx`Nw3@%?)}5;R04KSNQBdn^km0Iv!t;G8zP`np#8`eE2I3o+@C>KW>XC^Kp|@)Ij@ z7WrjgN}Uzd;oChTmT4_=FYY>YdV7>0OX%M{+J`v^X4BI2F<$LQ?9%X{M(r)oqQLV2 zH=rf%fiwqjBY<^t{$Sp;Q4QriGeyLInNU6;iJ(#F>0ZO%Pb9wP*>TdY5icAva?aL` z4Zh{VbvX8egQwt=2UJZB;7k9l=b8l#SoXO9)n@Ry%y3_6`Z`2B8hnTaS33%AAU+@+ z$6*NM%cR~Z9bi#W{DxgE`&?;Mjyg}8ZZPRVJRc1wt%CCmvbJDE#de}v-I_f~gIQij z=J2H?#E%ZzxL+cw-MXM>GJu)R#Bm?c;dZP{oyK`b9L$vXWHG<_CP`5mT~7+9bi{Vn z!mW>-F#zRhNx=6VT|7qG7xdhdif+!cCutnL4<*MCp+lI=X5JA#t;f{t)S4GO&kMZ~ zy`;HOXA7%%3c~RMX3S874Sn3sJa`H2)!EGLCX<YGRGWZrlkWC);E)gLn4cT|7>Cvs z2r7gP4n8EVd6wu)#&g{F6pumJfTV*DMt#2aM!gt5YJTK8j+3rvF{-~?{L`9i`U+SY z&2M^%3!O&eaP8Nh5C55c%Z?#*5g$gX%>nQA2Z$W0*apJE)q8TOFq+9KGY`&-;NW2e zIuJ^FXfLTn@k}+&(%UqScoa>PjKtaOOySh1I&G;Ci9G;m(_h4Ul!E(!Iy9EC_4;VV zRWwb-Kox}Uunnyv$Kx@0<Y1nF{^bCu$-#Ny+@qKV+=_eEP9cYF%}^(AJ$@YM-mLL1 z;*4K)N7ICn47y5lIRuI99;vyy(%wucTLhEq%<*<tvL`-&IS?6&;L&0F_A#cWa;)?L z@E}YHPtlIy0(ukZjN@!s3AkI-uMY52WwroW{=$)W0TC}=9V-J*qyyGGP0PNNo345s z8+rUczT8ue*FmAfjiOx5zdu{B?n!5T;ES9jjj%z6?&x-AcSg>FPd+`{d+r7iIzjBS zF=f?%_52c1e9u<>4*w<S4r)pZ%8OoqN4pwyb9~J3_f`I{ojXSk%^70L_@g7+yTlVI z_H>^WZY%3X`|E0%H0I;+>AovZtydZR|5c8@J{f|+X8?Us0#}pb-Be`uuemRxNpCPb zGSYiJ_xIJ(`R(uRbn1i9(YkO{5_7z59SN9F?cFf`@|5Upf&9#~Webk|d>^L|k?_W# zHE}ifP4r%0v$^Z+mw(;x{H@=2ukDyR&0EGlWR6j2zZ}3zz6WHj*dxE9+20U+;OuYF zs#nH+T)helMzZAC9&|2zxKPoLNHOVCDV~O7$NqIf?}2lQLZ1o6_nIjKrrF_NCz$Fs zeLOyJ_qW`#p^&|`Kdcii6$xy-i|FfsFh&OMJ$?IgUw(JrDF-t)0JriUCsp76$k6J; zbs^#GlPSpt0drAfkVT_T_DhPIB=)YuCoT)5Psul&Ef5C@Q3{vAHfT!;HnDxN=B9-? zz?}N&<Q<nUJNyHE&Q*kJ08#LFfbz~}T>g_T91#AfkEntyf(F-P^51_?dAoRg4EO=* zbS2M*_9O3!+rM(pb(~uv0<iVFsA{n+|0(Hek^O=1;$CZ-Jw1vfNlW5%>}NasnL&Nv ze{ld0X8}#+I4v0pdZYv?1&^ax^(I8oG#UCpw>-SpbF*qgg9Yl$NunaD<Vlf|j1V-K zoP`Kea2+^8RdTKQ0qg$Y@=K)IA~AkQ(LMin&ybI*QDcBd8swq(wwxleSsci$zlWmv zF=6;62~p>c-H<58ju@4f)YFT-Km2MZ5;{h5DIr5zyubu}+-b|182diu)^;+1t4Hvn zFd8GM={lU;g`6o{G|Mb>m<fB!w1h+Bhnfw$4Te1F&?7pJ6$w_MP?_7HyfaFZ6M%-` z2vvOwCko2;jSCL&$<tCoV){tFv(dZIt27j#U_uFJ7V!@5ZKhH|b>mbw$fzSi{>>^J z4!dg!Y*Z&<jt{d_nBw4s8en#evw0ts5i7ZsI+Gsvlh6BNn2<I&W0?++#+Gy}yKK?( z0M$`Z`{N*z(DiS=;72-hH4qwmI)W-7jMwN8Fg`(k1f~Pd3JUQE7%ymJMBX`gIzn?n z`16~<5nBT0UBQ+ZLdq~Ijf4DDiR_XDbg`PLkIvdzI&UG+4+K)`<YjtTzPb!Bdv^bE zA)ZE>&r^ZlW-hA31H~2}FCE8qwiNF$Y4p}1LcT0#@uU_mPU#WxCFm2FMBvo(ln@4E z9!rC2g3?ctC30vT8Icd+cE?O>7b4fh++%<SK`sSbl}K9{_u<2hXt7D>fgu8%i#=UJ z&O%W(p35cTDfIqA9-dW!!>go9gQ<mlw~XBbz{|x14*|Abwt<Dk0O)K*-o$ZoH|c;; zRISID1=Lz}tD#`0$;Azm>a<0WP7<h@8@Xuq?3@4A6O(@@{ZFMHFq<<%OQJJ7isL0k zyi6Sr0{whE(&H9XZ7@w@CC<+RUE=^AYmTKrR2>EPP9(@0J~E`xPGD9nwGU^KdA{kz z(MkxmALq?Bm=ICue4_B2lF=cAYYooHV$5LatAyuavM6ciL4h)WS2_<sn%&PFcfcV_ zm7cdY;V^Qx-q|#}+hkO_2y!PpPG(czKI@}Q4P-UIF||nkV(=X5H@Me<{?WlWFAOO$ zE~ZVr?2XNC-d-rTX;9XJ4L72f>4p4-u?_K*acr$81_2@B9=#acA;~sw=kDlzUl=64 z{ht1cT8Wx-p3G|@{`;kI*N<|JW>!-8det|Vr|$g~Z3H=LiZz>z%5c6Vu=fTiW@21N zvw9>}xd_j&NsjV8OlTnT6q;?1wbG8*-BVJF@#u?*0PzIE>DSA2t*GA$2vmD>1Rt)& zV>F<U@c0Xpfm4iarH*W~2&W~GhDHK+-%T~+kQYwxLU<xt-HQk%&B(UR&EEf&1eYV4 z3!BEsUm()RN#P8T>=pzx4u_VhHh{*ebXuw&`Fr^;Js;=tZ38}>chGGCrvqsy0&jl6 zIGR=Z>zEIhhJUKgBPadWlMc+k0|)S(7PuPg+Aj0F#bnX8fpsP*nlV^MbnUgT=6yqs z9y%sK%6pJA74WyjL`e5Aul-xOj6RJ=Rd~yBnClESZ*x{r>s#Wd@qh;rrY#mC8LRg# zHxCdIJ91;rM|Ur!0K*8JT0D8FAPoC*4DJx2d~gT|dsf+XsL&AfyQojLK><QDR_iWJ zMbg6APzh_s8Q?gZmy=B&3#=D%vcKV@+H<S8`=BDi5$*4=T?Qg7)vcHP$!Wm09BcX3 zR=&|}M6!f>6}Mur4VXH|f}lV$%3F^~G#9G-z2etx11W6>-P|8Hm8U;r)qw3R!OL)l zE{;H7NvCIGL!e|S)Wnd%9p|1?BBZ8G8RSSNaB@7(5}{=w!n-rA^0BU$0z^9?K(K2u z@=!Re<`FTDrtmbw?K9NNCvf6HhjhqpOk5s!8>*~VF%)Py`of<O1BoEM!Rw-DM{5c( zu@R3V$*wl>_Bo!XLkNjZp6LRAh|{^_86QFmbYTz&@uZA%0x5YM&we8Gy6I~rvmh!- z$M55)yV>nKakZp>eE9lbMtm|sm7hc6%hW}G04eURP0MGfA0yp6n1?wRd!yx%UYEgK zkY^>4lOl=iX}K*U>UmEbWd=u3E+4}jW%lEvUh0U4Be18-mHROr#K2x?PRL5Y9uO&7 zGfpq0d16?fjt6j|4L$wEB+dXR6Tr!cA{U5&2;7mUMPkA>>fwLe#B2m2U#u+QyPRdM zNAo>zNiYSlw0+8h_>EV7oj}F6OCQ*T?1~0cIEH!s{8mc<TB&%@j}UW1U{Q|T-Pv|c z<iA;8&r|N)2f~*yNG-84C=JZND9ev-UryhCROIjeD|3Idi?j8@wb8~VKzRFrKS=$W ziqf)no~&K>ct}!|Nyl*PO)EZbXiq&yj6Jly=BtEpgNMCoL~Fi1ULn_bi~?<$%9-BM zOFImy$}&_qdxN$r<MdYK$pit;^=~aG!&OgWX!{&9Qn68EE!xYK#h@P7W`EyWurr96 z%o(E}$_YNbI}xTnlxaX84h=%$z9^18A!qo~6SA1q5-ef62pNCaf9#QxiS<uSeddz8 zD|a8Yd*aa^+jTn}XI1R>JcI%!d`sTlzFyID`PnmjGdLjQ)~@@L^E^&k0;9N`wdvnW z{ks2=9cDaxzw3+KH=)`zr))LM3QAI(=jAwPZkVdupSsVm@A6mVSz`5mX1<2>JnblZ zl5M+UZnkTZzU?UA*D`+T6qq(={cSwUi}Y10Cp%hSw<P0|udLf}w!5}&>^5YK7nInJ ziL`g$X1Se>hFiP28`NPqFOElEfm*{u2ewN`kLSH~spDMmGoxcad>HX4WazE`gmu(~ zZV35B0ETIDtC?41QgbwS*U~^5m>D^=(5<|`u1d1&*(PHzTU+nrJ4D}E4QK|c_{@p8 zXWttfE7#y`J??FGih%`e2rNf;ItyJvWOX{mrtJzmw&QlrOF%unpvla`&43_gt~?#{ zR`TcpJmaI>B9MooCe^BwF}vV^ts{!SLxp%)19MdGX!vQ|qu9S@DYSYxGtNvTzsH)_ zJ&9q*shs^Y)Kv!ZU%Di+=AGY!Q-fE0Q!z-s2>Fuw(wEbViE45L^WGNGivE>rT&b7` zrC=@}YhQQ!IWt5F7)|vcSMTk}QUvd|EhYR6pbPGVJiaXxWe(14Xeoots}W~^K%ovD z+4iLb1qEVP&}|~F8Ixag2_K~zV~V`li$_rZwBo5QK4P9ZnW;Gj9W{B*2hj=}g2LBa zbsxX%4On2RAgso&6XW_VezN>U1VVJ;use-sgIKefZZSrC0AwSW1+RfPSk(%#&P@fB zRe)W5=b3K^xzQdryoitEc}VEw5gqyD@OZ1s<ke(O_%H<c6k`cgzCw@~xsiAn6i@CT zGwCwS9QT}BgXS0%uMiV!9_;)9B#L_=n36H|Ry@=O2jO6upp!sT9F&#(0HIlE>Ntq8 zIObO+XoF=D%H7=A&8uVUuevXln#CcN|HO^dX21Lt()O(GvkBuxaBs9L3I2j;Qy0Og zIhfei0imE$fr542B-%uo95Vgbf2=W>`$`w#(F&?mX%f@};eoSCv$A`SN;H5Y)G5+` z4~z~sVq;pWcrc3vGZ<--#vh0K>^f`^7wYciWYC6`pyNQrgxNyGTOgjxEtq=CA}Fpb zA|0R-eJ}Ky;HAn5{fPbE7U@y!?S-v}5|{20ZnBZ?4X}U=*3lf}AdA_Eoy4(l2qmyn z9kWA^p^8^$JAL^5D4Cd!U89TrQM}+$FXAaunA${8xXtC`pvTtBM1IJSao9nou@p!K z@Ob>1Kpl-|#YnO+EF@q<)Gx+4pFuYzLBGfZ{$k&0BMgUDIA++Bi!JJH;Noukp=)+t zV1cs|Foi?juU<ViNosclMbwoNNITIBu2)8=>6JiF5S`S>@}D&6MC6nm6QHslOn`ub z@K3mSHqLIe9+hzMI2UnHEVWl_M^uey48jsT?l6;3ES@x!y+&ehfmVe>B-y7S4rSNG zX^XWjC>dm=Iu<CteS%E|a)ee6p&*mY4q)PJ>a-AH>BGGb=}iWoJ@QW`1K1y*Vyb7w zGbGIGg6_96TDfEL`k*xZI<Ej(0y@0nNT2l|USi;*WSRm!s+?<8bcv^oUU+a(C@hsN ztVO@C1Pj?zyW_PM3p-GP+yktA5L4PD%!E%fcVKQ7t{@XHffPZ|Fu$-(<^iR{EW(UI z+ZPn8YQmFRfF4<P%X93r<jG8!JH#O$uEs25@R3dL0t|11e;$niiW%aRBuz;D2xpHT zxGXSSuz?SZglclEaND7sdk;aRgZcpy2(J!paTzh3f_gQPPk&Yk`g8=wgMj%@25(?V z4BCgHyer={lAEa}*anApZ@^0+F{EunNlDVx(B)%E22lW>6xcR~Nd;()kA~~hepQ`U zcH>zkCGF6OE5p&h;V~gxcG=S~l%rXWFF+%uV~!iw67+qplmNf?24&r#-ZU2wo<-j? zKWxVR(~o&LdAS(XY6;-a@!PZJS7zXA4LJ>vAdM#F0f5BOVA0&eGp2Ab=i0NUazUKI zU$jMerF&L?KpyQ#8e|E3y0P1lC814?g@${t$!$aa-lcmI3wN+MS~YlsREoO4vYo_i zT_WLccseFJ#Gp9Gck)*(ei9@h33=dSywE6wtR<$eF2sRH8X!Zj?Ihr?rK~VdSFZOj zSEmA#Mg!9e*G*L~0vN!Fjtqw(q_Nuo&a=WZ2LUtu@|P1k@2z}(k>Kb1LQ^H4VbQa8 zLo6PZhmwMvscbZmL#thT?J)zpNwaTnu8p(!7P+e4>}Pa3*RC>0){i(X8_c@8zXBS> z-V>}D4c%haC#weA-hJvlgc#0iAurc&6rcDN&<cWs$zLvbLU6BJuXZ$nZS_9d&mVuj zdO_#Sk9aCq@|&VKJ$Qk#)@mLAQC9*g1PGJ>w?cKAZ}QSvUkoFu1169hCJ!!?#52c9 z6LzSOJeb2L5dxdPi|E|VIHPJUWCk1P0z{|82WrehrW#@dJm%?93hnPCl$v8zIP5Xo zD!_@WOXop#2vQOaMFI}QLAQ=lD2epCdlY;k9lRF;Fq|#V_V*N)5OD@T{MGs3@!~P& zL&54T*@#&!pJa4wSnz#jydkEq>e(x+H#r*u0t5}H03u{x=ybD?OT1imo~+<~p+C0n zkgBEhn+)=}9@0#F(c22?+HvF2PZxbF(KJ@!=h;FBQPAEf+7dwK!-*3ox9klZ4!`|> z(RA(sQI~1^2gTIfBGhav4s8sAsQ8AJO328D4THMFQNTpnl!&Yhf)GW9ur?1h6T>Mq z8R964n5R-C$ubczk%PxXRL+nfg9ro6^!q%s`}^zN*I=0W&hy-d>%Ok*hI;9iPc)hD zyzJriw(V83JjerE(v?Zl{%cby_SXDP^HKiJ-V#M&xXj&7l6q~M<m=74^Vr`ke#NP^ zMWSrU^XRgTa1dR?^q~7I=om$flM!%XP>^{z+d-f1-Q=DVv8C>dzWg(dEyK!(b;B9$ zepn0Y<9ckL+-{gG&b=7qEOmD1Q)M@gxV`4>QlRSh&-sPKAP38^GmNRqzj}MIePiY2 zSE4}r+rLeUG_|q!3*zdw{l^=<k6`83T`ZY@Cugd3ENsJv;oE~MPv8|0c1HAG-3_v1 zMnhB5>@ym@`>6$ehg*z$!m8bw5*&*Qm84kW=OeUzs^Z4CQhF~M?s<xy*t>P?q500Z zjga4fFdVbjt~#7;r*<5~@)9CMh^)OT%y?+M`*dYhWt~kz=0558>L;lQZy!wePpsNj zw#JYt=0rko)4uN=cs8&ug>7ow)^oOzS~v2=?S$y7D+R8RiO8+#%OjlqNWKfH>VRyF zOb$B-N``O~xzQ9|hZfy<cw4yB^r{XCG+Ac9rTgBVYTvlQbUT2>QjX_}s^nn<AIbgq zSGlc`fu5Vt?Px4r+(zy1?7Nl~XKQ*{n%hp}p5RNP!K2>@G^)2HX_~yf*NXbaoBk`y zs03V3JRvB;OWZ4sOJx00>`flh+6fEVD%g?RUqrlP8bG<1D`E0bAu+Xd-C>dfX|v!Q z3yEk4Mi~%D<_RA?YY;D0fy(klpA_;Qgv8fEMLA)@8WJ3{#-C>9F3AxX8Rrx6t|oZ_ z2oU!!hzk+wXl%>_^i;Uy<0^^g6lXazT`^W;uO8_Uv&%>2bY##Sc!Wox5|#3w<E*tt z9sC{v7>gk<$-TD_M*>uZa%dhJwM(+(KTOUSGGKvp5ye!`av>%<QBpqbKC^JVj1{i` zpP_=ri9cDCp1|ZZcOrEmoon;Lk#1d*Q8=;zsxBi>l98KXdktR7HM+rW@uuJsBRHW_ zOfx1l=&_}Nk()fDwumd2>bw~_7qG_v08Nc(D^1=oy!+4<W7VxxO0lHdsYk%>OfZHH z10GR2(Y9t=gD0eXmO>mX_t)Er$m!q6FTjeK;>iDbcxea1%2q?W$6^XIVkl1}mccwK z`B0z`#1_0_k0qi8Kl1w+!h5CyFcNMC#>kK6e@c=t%}^NP!bPnck>oz+iCpYTy_ls& zC@{XkNMk>sDj#^+-yl<g5$Y9cY&A^9lJVHK>3~;e2<$n)`X>ugrrPhPh7%3oauKBX z5Erm2plTg0S9xPh$B;j@I;fL}PF!9#OIp|OlnQv#6eFX8b}4`|2AYTuBEf~yZ>e(u z1@WOeM>tTUkwFbo@d<OM2vaZ2h~(o+UBgcPTyYj%y$XY}=NYZ^NsWsF$`j%&;Ji-U z0Iyyp%oa>f=7(6S2iR4-`&9aG6hLnFhGvWFM<mfrJe5}<@bPEI%G0(@;*Rj%Glfq! z2Crn=VrWYy^MZxBPaOVRf$~EVOC+g}Zz=4|7aQB4a0rqK-H`f$I{Q%<b%!=PZ0SX# z>?Sw7Thw|HE`Do6b9K^qN0UN#r02_=M0gQWd~?!zj(UQ35N`I!LXYCfllGU{8~*JJ zzUkhe6_O?xlq(MFqdJ0LnO!WzRMHb)Wce?zzg$gnUgcbTGhf&H+^QABWFeGjwg)oy zU;2-{l^hADfU0!v<InexMFvzKsIrdxdV1KZvC$L`X74^<t^c4iQ$i+xbA4Z~sG-L> zVD~}Mw(`Z@pMJM$P-<xQ8;g_K4EN75Kg2l9@NsF&5A`-z%r*uxhwV}Sv41Sg;#Px- zmcVttT*_aXM-7mq%c>i6a{39VwIivuwzU5Q7<EO#SbWy9XLu^XK_2v1D|@6TcnkBL zCSdONdj7=&wuu>z+GVrE51?vn*3--I#+^44wt$|x5t9f?h{i`Xs<<T!Ow`-wJ`uj~ z0_{Fb=-)M)JOF?s8d*LgS!Uh>2$c3a<sfBa#y9({U9}&seV9)P6310vKgWT<t;*}r z2bt()SIdlExl<{0Xu(8Bn;<Zn0dW77I^z~IB?aXW!>{A}sW5;qs3^GNdJ?zjypESh zccE09rAcr~!LN}SIJvOB07hH?eoXExct2>qs=#xTInbHPUgsrXqIrsi+iVfk(u;WQ zC2=TJmYke}dZ*k8yTT!%&k%=vQa(mT{0?y*lo%SypLrqxevHK3y@m-6?Wgi#!+~?R zGQ~8*@d5vu$XzLz=jx_XobnG;3XcTyk9a?nr0(5Okk}~>${)8x`wYvmJAL%vr*@;| zYvfe+F@7IOH2Lu4D5HHe6MXE`gtLj^c>cxjcwRvv@iYtN8aF!VrVIxwJu`)emk!-* z5y0R?px`>6?<8>&<>_2Y`H3^?s;88N-1;|B;0|7FS^N3WmwP_AmL-YH-WdDnsLWy0 zd*$c0w3pJzoIWYOjK?Cr<gP^tNU=4o^YF&Y54(om{Cj7L<<SIYucG3DQ{O6V+FM71 zvz9hRSCenJxTE2}y2U>V|Mic*PoJElus5-^_KDEbkLX8?Fed5tR&LmCw90l=uR5W< zpsuC*O&XXx?N^;_V~I@i(VA)yK;qPut6@V;MxYIm=01=>TI7&i129HK)swJl#Z5zL zcZtG!&#QZ*tiM(s1};VaVv0_<w<r&my?9UOrRN*Up=G4b7K5bs!W9mOIk2k`aB~>z z#vhhuzpB7H0WQ=Jac}m`%^LdMXPV8c-gmTyw}DLz#|}Hzw+#+eI|70!!iIN9>tp{o z1qVp;a+&?Fubv6pjpj;-1~2BOU5>lZCghk<^6OyZap!sq2Q28B?KRT*NQRPhrxI}4 z5c64veAA{nGI*ilG#%=*gh3&Z=<q*lr?r5x3UOIHVYJnvNhLW_!^GPt{%>->qn6}H zL_Zc6(mFQJ$YD6N0MO%f=^tIUy&WlCV}hPqmCL)DY*=_Weq^B}W}_XZ?4k|2v+h~- zMO-8fM~^6U8{td}lctY_+0?|&XJI0VWKZ)7(yty)t=~w6gU>R)j@2X^m|PbYRs5GP z%xP}~y!WMC2<H~M6l)fvKRqoR5>J~*UH8+gMRbNz0ma!h-_ZG&+4ExXb%hB4H#5Pp z9~fr3Cjx3nd|YrL(y{=P{>yCl0UlV}L0csxYEW%*^^`Uu4}1kdM;5L<gs3ijL&N!j zWmd-fDB7?T72eLUbZyttndGB$>=Xx~NGMr>+v%9p3|5_2gx|^A%=;2bhADSAD2~}d zO1Nbg=_nKY<uuv3Q^si|JN;!MlE09$L{i-BDQ2Mq5NR!kv}6CuFK0~4E5}X7I>OQw z*KVd_m|iAtTUeJ5F-&gP@4W0QqBXDX4+xgG823E6EQ|FLK++Oh5t<%~Sf`}F-@)ij zf(lm$#o4|D6s{>r0i+^E`PLu*clzN^nm|c&X$Nl`B^=|!sdPJd?Q*F(6_K*cud&|) zlGDhYCcrxK0>Eo*Q;(Sd8v=f=@o}>sB}@&Ppu*D(5qsi|N43_rGG1z$K(LxIDxpBr zw%~Hq?oGo?;-0UhW1=W|InNEmfT0GGHHolA;bVY=4^|L(*Cs`XG(m)$0Ua7*2$UbY z3QC2+#*2uldCmBhlrRb*-hroq>H*A@yhjMV=Cl333m^#QT%H;;iKakU#+XWP_wwz= zH8MGY#K-K2IFa$~_11J-Yt=k7-bu_C^l8nIJW{dau5lkBs_&CUJGdseQ@g41eY7T8 z{yy2VX;=~~$3KL`@0{?$;0rueO^~SfVUCDdso+#<7Q2_HY#y&`zC5vHJ&d*;ty{?M z|F~?<pjRjG8bP)OyQ18YwO=_MGG0wlVz$*T`Qb+Iap|P0>w>*k-KOTyWY3*;KGS0@ zCHD5=jGi2;GsllS_`R^OXz%Po$5cA;EMeFgvd;d@)~>d}hYL)s>sHmN+79<uw}!jA z{XRB-%a=kh@mN~zfwb%NDI@7dUFq85Z}qOsDHu#0Gc?C5uj^#Cm?5{IzxOOc<*t3p z&>a4MG2dpTF;8FI`XAIJVU>?I)%|7mLd*D0zp5h4)vLZ>nk;m4^PT_pXUr!@_=fAi ze)e5aXIp4bAKLVNwS{uvuC-Fwhy)WV^)Zy34v&3XJdH{d#woe%pgyCxG(`VQLy-K1 zElrnx+l;?k!Pq>?Y=w*V(X&p|o=QkR@p9%-xr6-Cv-Y`p1x(=Xlt_=gS9N^@D3Jci zWaogt%u<TS{>HBqj0y2Z*Mz*l6N|2IKvQ?L+QuwUWJ9mGO@CJE8mX@W2d)dZ3wj_w zm0DnYZ9YHo$|a^=EA;Xtx>7&|;W}UQ<0CsEjL^LHEC--uvfw)g2Y_<?XxIzXo;NML zx!PfpF8!4SLJ-{OlW%|J{@Z{w<gL&^zVqDVue$Ot-teo!)@p(R%Y5f0w~1Ly+vI*C z*-s_o!niabfmn;c$BWi~I-jNeUM~O29F#d%teM=;gq-B0ABW&UK{QrF)Z3COu3Em@ z@bBCSib{l#iWZv%(6umAT4u%VhAM!axdIS4pAVm~3{p@4N3s4)sq%-1=HU?_+J1sM zSReuwVL?10zn>`A&-zt@3vZw+9o|IRxW-0_<qY?sOwl^FOKS(6jE{rZ!JT3{*4JX- zXH&5n9xvbKx>-b*P_OjFzszEGqJm?ggP)#QGR!1iv<Fu~GQ{7rkqOZ(ozI$GI~P?2 zy)`eX&rRhM`M_W9;5|Jd&W0aDRgi8zfB9GqXhyY{#&<%!pI^{hqHFPM_*0|t`I=Ua zz*PVj2hqR(<;OZQUi6H!;9AjP{8UtTFIfBUO;L2GWM(09%gMO&lpsAckGwJZ%c$Kk zy(T2Qsw3g!Du+pLtSv66zPFzU<jVF9o?5G_RQdiI1;O1#I@-C;^FVX>^*UBA5U~#E zHl~>f2mv)4Kfd07;!W>AH{hvuj`U5WX=@!g_f!}@3y90sCgG?1nej?a&uz?vxt!Ph z6VmnGoo;r|Y;GKTTlylplqJr$GfHG_p77yJLjb_@lRNAU?HfG_KZN=}UDjV2y3jWE z1pPvq9vIe?w10@(ZjI&B2sYuyapl=Jg9G%VLB%NWu#PqESv@aCH0CnN^uRqD%&mm} zNS4KO5gitiK+-SEZ1h;xpgn;P>HApRVL@zMH`XUNRNEh#BN>|)!&3wb406d=$(?4O z-}Je%wV5WfdR^UvGn<Z%(ChJHkmFn{*8g&(8b=>;2E)TgmSzdjy<`HoGN#Uctj1#V zGi1~-`;yi{N7$5jGENl)#&V85gm~ppEVOb_0;{xt6K0bn?(V%!b`?T8vKVrRD1`ll z4~p@oANF(xp%F-afq&<UXtM*1eT$8;2L`BZ+|oJ+MN_Ycvdgxa&R18?A3!?U2DX}B zw~zuMc$t-d^<)$>5UTBq6k<X`|Fz5l)+Hh}8cVh`b-eCiC#E~*IKE-S1Qae^Ahfb= z;<a%oC>Dg;U`OMUWlv#QI);fo=TSty3M=D1XhH&6k6aCd(ag%&w?)E9H#Iy97)uzx zq^yUo)Tv1(SFAQ}Q0k|XO=>kh+aWVs(0&Mm6)#bg1uIgNFLGhhhP5rs3=8E*dN{#| zGEF60++>q{-q(U*3z1kTBO$VotWbE}&_n1~FW?g}J#*D|1QAFFx!B7rRb}FoVX$@Z ztl;g)9Lz#;l%tX2YichH<j(lyc(<jsp*HY2Eb?wV69>mE2hXt!1P`Ej=8oXff>J56 z)|ItW?}$Y_#@*cNgflxFH6mo9Vd0TMT-QhXGhk(;4fGG_A&TLy76&s*f7)<B1!`5d zoUNf$&REa{h!@nyx&JJJG}7W$h!Db_MmnbVg90qR>O$+E1rE^>Ai^q-R6zS7nknPz z=BBOoEx1U;E%O|YC0BzSK^@p<E11`)L4jq=b$+74s`Xh<xGiQq2OxukY!NN%Qs;9| zF|O*v>!=&BVLyiYeDCbt;$=7!Z;PQr*96+Owi4Q0Mn9~|;y;lXM6@)ia)a75rE=?x z$#v)@!_0);M5a<7DbUP3@7u}q;6rW+{Fvh`zEc_i=5`CHPwyDoAZ=A>SYpEj6ta?! z+32ymYg1t~J~L@tEzBM%si0|-_gl)_$HQ8`nl10ttn!&kX_y&Z#TVM<bM=Ay;LY(@ zDyg0&bdiYLW2AhSorQ_TWeP_vv#-*(Pwnnlsx?l(KYIyBaRrzWeSu<R)yrBJ#X}0H z{`Sp_vL)$tu0Cb|OsG&Ns?R?+Ppcb#9{#yc%GhsfRsyBB04oCxX52+(pkGuKT-y=+ z(w~2sJ@}^kCB3#gS|8)bWTz<2n!@BH)7zKRF1D<j+adSs*Qj2fo721T@b&l3Bz}S~ zqQD4xr=7FXe_XZp+OIbxW90A(V*9nwds2~syUH)E>#o?=np3W66xZeT1C?FGl%2fu zqF95EqWS8k?2e${VzO7<UXUPs2e44i+4e=2F;6k34}Gosz2t_mpyKfd#Z}wh)#`pZ znus!X!LV}dU&${QoPm<pB$GWV6?~YhE7KEpE_>duhj(5#1#)?zY&L+;JltE$YX<WR zgwv?mMg}~}BQ}nYs<5GRt7h^|wy7w{eL_9rO`bSqmu0*aE5G+F|I08|sz#Q<{JP=O zL645QN9P8r$Ij6Q6)<E<X%z#fmh#^Qr>kFbI_~v>a#I}*O}_D#R{V!Qyn7ul`VbK5 zex5iy;_X7T@)~Ww^|dIRuPz!tUVzI)vZTCxEYP?iV{*2P-&yLU?hDi<i#bN1>W~mX z;H}v1JDK5>sGS+7$IB4cO=&1lG2lxV1@#21mS@y4$Wo3E?!TS<cpAPWk_>_Sn*k2Q z*@WoYRBmcxxvv;#AG9JIBSGPW7FU!1Yu(J=8R;4X-^@lB2pP!pRSQgKH0mK{B|tMN zDQ;^N*qZPa+6`Vxo+s?I1Tt{ALk?-izA}5671Z6o%+7=1a3R?)6*X3)XwBU_O~MQ0 zaogf$S)Q-+fBrHv%Y*-U&5i0t4dXw|;yR2$EOKg#0$UJ9wH`S2&qmVIL-|;>^D=n( z&P#A-LR^QQrp63GI3Xy;&nD=?RHqVb2=z`U|CBjcH9^{u`}<KLm#cR0SC*UM5VW%$ z$vVbzrRFx%1CbRK=KU-IFx)R%$mQO%<~#^Xz~#v>x}8SrhxEjB^R6|k4^G~FX#H`m zQA!XBmhc}tPpop=`Ye2S`n%43|9-RXQK-Pdo1@mfu>Ch*S(MT-i&S^YX~8$=SqON} z81YWCK|goDR+e*q1yb?2>gLOy>!d>|htAR{V#HG(G-6M*>n#kiP3@4|et{Oyg>4VQ zAaWrYsJ*zar$c?<de1t$l!gR*)n@6ys5+$laz))k#_*);@uweaw-k5j;6Wl0{Um4z zUTsxN3!sDN$?w}LMWzJ}GT(Al;jtNGf-$d{q&~g@90gy;2?3NlvLhgIMB3Skb7O*D z>kwFeWxat&ft~9F<>Q#nbN-|W>-OGRq<MnTgwRG@(Q7c_?_L*icf@_iIOk*CS9hQ9 zmRxy@no9s>xoPK7Wia3{LOLc?voVafvmfC2;j=UJQ4(slq`n;tJ+D;zQ=mn2D`_*} zR`BlWFtzQ*R;r$&H>+(tAdj^X4g`&E?4g-(%_6?0o)-dwYzGE!Y#-1oA2saWOiqGe z0Wr#z$KtC1Vd9HzMED`*`eXYg+p%W@8E`UF<31p?5c9f#4B_oH2o_WpSy+=iRics4 z0c?W{h+03J$p!B&)(j{{JDfgpN8^KL#28_VXU_kaCf$XeywV?TBB!f1^RH7nbq(G| z`JB|>u^(X2NcO|`%nUe4aA|6`M{;F5{Y)D395I;8#!f+m@O>Ve8!44)B6-@YNW?SH z&l}oZ@6lFt57dK6<BgpBtUKcb#`=EM4%6WTp4fihueyUxI3`9jl18uw=n&8kcm~bY zb{M;R@o4{WON0yrt54YV8=8ZX1=X7cleL;+Y8MkbTnwv;F8#JX_Njtr=oMqSfpTm5 z3P{K>hxiF^xWze<V0)Ch+y=1%f_*<ixOWvFldcqcdD9ryCu9b&yQ5&|!pN#Klz3?f zZDNy`CV75!2NNN$n8b_#wigtibwo;z;lWAn^pbxdD7XcmSdCRP0~wA|bp0!4wh>}X zGT#XY37{Iv8I0Z9Cro8-ijN>m9<8be>jlu|mTM=`1W*^vFzQZ}Cfb+0cg9+~=J;{V zwpXtzUQD2%*dt#y6BBMm3rvzP^dL{<QfFpZ3<4k>GfCIV>AaMHJvUgWCM=NL+xSy} zQe$=FU-(t6aKpo?3z%WFJl8%afg}|Q0h+JX`J4{2L_`3CES&A&lecjQ)eIk1Y8N6V z9>?ufeoPwum9;+!rQYl|u`{J|a+bwTpsT^T3*j1td^(ON&*;XVjfvW+Lkn<@mCt8` z%LQ?p6Av9Q_Ko_C9{X8&awJ08kvL!wV9*6+CkoY?(Sl8nP8mBnL<zHpZ-_E(EFyB{ zll^CtW*otk%u!?M>eFNY;K>XWamy1v`J#2~rzfwnx=!li)}X$3zL1aEDw?ID*mV(u zvQy1f4?0(&UZzFQy*6%MbatbA>RISUF(!%m)kUA5u@CPlZ}4=7H%mr7-SQOLvDZ!h z?a@s&13i9&pHUZR4qn;aKhz)8TkuO&)PqNs3xhNQ&n9<dW?bLA2Ur>oUhmf<agO7w zD(~<6<Tfm+aE4!(PQ54Hntt1(yB1N4<mu1jHcH~IN*+DX<KGF@x!%5L)y9IBwaQY# z)9c+A=DOrxF5aDai+g`0@qWBKN2-6qlUfFCb8+`gk2G3$gl?iBbqIcG_NuQ+XO+j_ zbR^-%1WQZ8w;kwVRC$398?D#I9Nw%BF*eYd4}ZjgY%Trf1=eKoB?q&?(W%4iWZH!z z0yAZNTDJB6bdp`=fu8X9I50g>!Q=J@KV7q`%8&=kSGG^Uuj#2(f%fYf4PlCopv`u* zs)81PN9am?ZxG48Z+cnd``T_r-VT_7=5LuQ%d37Js6|UPYS&LKQ+zV>0OuF;rF#CG zP}QTjE0jxcZ2R(w5@sG-+$ka9jXmErL4nPt8rlOBPR1G-M7=Ku*5n-T7{AcP?jYBc zT|6si?;h{gB3}!|KmEpI1;}bxXc8jC<a3U_G=Xg900-2l5t7hHUDTtVVgdl`$c|-+ ze0jpF;Uadq$fn*Evx7R<f*dih4YrQ;7t=$*1;hW_N2>a)<Xv-Icx$ko1ogBNzBJ-= znbjnU`WL7%y~d2;1-~k6LTl8Wd2VLfZLU5}Od)_@(I||TZ-|w9zB(0%n1n6zcd!5^ zgWg6qLoF^7z7=-ahT-pK&{&kan9D|M<|tLWXZ%~YttRq8z<3QE>?yCW4Wnut$O}u% z3N%nD4t#IL0n`-mUNR;&aYjYw0r_Sk7L%$>p2CG#a}vr5IrHtfx0e*8c(<tzR-+WK z@v?Osd{~^KbYZ6ZZN^tv<^*B|8qk_UID^)oOKqOun~*-zSAm`F>PbK8f_B*F$eq7^ zE^GAUIKx!Klcj5V{DlUS)MZ}SrYBP~b-{~S%!><*ky#wsTDPm0@2Gl|3x=bwg#2yp z?h+7s7rFCdo*m0OR=+Yge71>q5Cpyt03EgR$$TGnt`G-u;{F&(^6qHLg@a{sjr0KY zUpsp*imx9ZT*Q-(pAm|nClpHs%o~j%1|yvY+}t<?cxV(NmNgAbLp_O0m4dm&QA!Z{ z5F0vUM7ICSty2l2`$A}Fhtk<!a*@bUFT8k~&ui~DiFSQYkX*uJ%y=7m!BC8^g-%AS z2P8Tv^zDOC#Zm5GGiG1$7H%o#>xns`KokcC4HxJRgHAaTl5%0Q#L`sB`~ZM?Ex{gT zn80{`$~eHx;9wK{B^;B5m$Yyp+5!&VAu#^s!T|FCtBi3IXxb{;M>}y|ne-K1Xw4^# zR)X`J60OWyBNo<hq=A^=qRUKMDk?N6(rNO*yQuy$tap;QiYbygd}HM<`8w>f$rtM3 zxOD|IFjYY1Jb1CLs9GR$$x|R$uu3RW!EnD$Dr~<$)}x|{@vpK5?KF)U-Fp%s=5XqR zAez$ZCfl_)nI_OHc@8$xcpQcv!>)pPTWYnRk!1=bgbB|jijoK;=i$^w`|TH1$@BF& zkYlm_|C8Us5JJRz=2CgM&~!}@C86tLVO%N1KgaX7hR%=FENRs&X&@;vU`myg{KKT~ z7jQ(l7$+^AGba)VeK-#6$yzxclWgbM->NW_FhM=lN(aQmwEj6ZNKhqZ4X0Htn+k1p zv__*utty5zfGK{}9A2^Jfen5Z>9BXfqe2-MY@m=)vM9~Tj1Xj86c+h;lD*=t-IS3p z<f?|(D({DY)8r_I2&Ba4Ey4f5*kcug(<y9yxSBxKa?MSN+h7n&C{m$9Vj^G)B9*;3 z@yV>y<x(~=&|c5u`|+h4cO2y_ei#-UuVVo=KjO)V64lDnU>65wpT&TI07fxVLx>qI ze|%P+P<G(v2ep%eP<800{%cwoo`HaFmJVDw{dbm?w51sh)ywQwZ+>IS{Ujjrx+$$k z0FCNkkdKy+46lU;)h*o079KuQA?;W*V(CAKs{-RfOd$J`?$PE}xs@ur8<=>Nc7OI$ zqr&HbZDDCt<;E20EwDD93)fy=@^DGTZtCE<jfs}`4%#ewU9|*lhuRo=P1;&5z57B_ z#n_Z_met%&h+F&f+any#fme#N*R|dw``uH}JguSw8fck35`&!O6H8at&A|XVvQb-c z8PQU;G@3IFqhtR@yIB1%V}`9PEp~2y__Z<yh&XL4B`G(1`(I{}2ZAndh`0M&!HrVo zA8vn+2aQ#~fHfi2#j_7;hqsh606T3rU0Dk5da7qrP1MTvxL^))sB1Xh5=ZVW8Q&f5 zda7&a8?IeJY-|6Fiy!{F%{MGeS-ZH`byZ9Qha+BGI-e5h4gy4G^!apssDs#cl*0mn z-bMablCDtLRZsHGNpJ+q4w$=Q#z%R(oIiWooseDYlj3&5LM*v}^PBPXJOGWF)iyhO zyp$l7yHck!;0|gnd3VCQ<K?dg;5<|_&0h03i3t%jAf%IqtIpy-!NpD@PpFnS&E|_G zi;D5wi);wO&BR{4EkxIaO960@FLMo>V1dDBpeQ_-JIxA5#wJ1oRsd0^19!@Sr<kzp zFtD~7B_1v}M7U&?8|!VDIrsVCS(-&iu;=IB7)@*2PrAli@w=}5j4P5QJ~ZN<)&L=< zbr(Dtbe-S(VVVxr?IF~2uC<U4E|FehBZ-SzNd2)d{Ll(H`AQ8oyXiF+pr?&?7d5;1 z*__x}GP{-%7WP6ROucL_7`}MPD3f+d6Fgt#2ZAAO;RV%RkI?P1Z;hOl%siW9#<aNY zT+E$hbkpRi+;H0InlQPzemNo(ieX5G{F9;Cbvp~`I=PFA+d&DEJh?LiH%JaL8_>yq z6RXzepcy-gW~Si-ogOj)eoZ^|di_V1F38Q;H>YcZtAE??qp8koyu069w$~7`5Dh?t zhobqi#mjoyNP%3!^R5@hXZC5G>e_>!R0?}A=-@qF#|ct4LCH4>xE$3(EmO{RwlG2C z{TF3?P8N<mGda!ZXazS*0IBlC^NL-$s%hQ$ah;?jOA31{IC21k36!I87xYQ6dJN4Q z9cnyJuWzqzXQNTn-Rw5iW&r}jQ9oWbW0k^XaqqDQ<6_0MvUi41kt7{`#eHlTSl+Nu zK*)%2|1z`7GO^B(@IXsGy8XqLOf-&uRg+1XJQwmE@tT9@ytM>gKb<095)hOyI~S5V zR0hs~oU}yH-TtS!C3@`y&@mbS3K1ZBP!<4Z0;e0B@@_Ng5ZI~-?sx(49!RQWHiY52 z+ndDr9Udi$yCto9hUFE+({%kDTu_VQ>;n$t>3vK2Bl#tm1TwRFKgl}OZ-BSoqmZ(1 zj$v``WKnr+(77{iZG$>RUvGk95K+b?XaJx@hRTTxh_GUOC}y?cDbPY7lVMLIMyp?U zai5h{z&+^kLBsO-TVvuHnGH#7nd1xI7@IAzGeL}h5gl)Y%pF3>={#xxq55?u_}{o} z!K;fdpUT)lA+d$tMUbZkVdXGrym8U$JN#HSmo`O_vlC>JH@Sp9p2d4kEQ42lwp~yd zg#innZ`sqlvL7xKH5m6lyp&Io3!>6oy+SI+ctvs2f%>+DuYD&ehGGKR#s=z50yy!8 z+F;j~IHuL^$C*M>q%gf@raUJx+^J@S0a~mQruJNBX6q-7hJ_<t82FO08EVsb+wN$E zM9cvYn||hrnOLxwwh|3tK4WzL9}+c5dGtcp?0XH^!NyX;k-tK1CJBzhFh0qQUin<o zq4f0YT@&Kr?8%X|^#ShjIB6b*${2|$jk@?sDl?v5K*7NNyH?FNcr=3@gNRYaA(XIJ z9lCDRZ3a8)N5VnW$%*sWgK|Qz)msk7&RE~O&34M&2TO;=Zd~Y{v}KKMBekY<Hurv* z?X}tmmkLc(6Am)3D02Hqb7I&%%iHhyD+g*WW&00*xo@ajIyF*Vr@hE$Soguv;*`;? z&ysF-indO^^_Si49(x8~Na0s8r56=U`_)Z5`VUEuMREqhv%;my55q~e^V^E#C1G_P zN#IQhp}OZje!9Q%+E2kH;TQ2}G-hA@PdqE;zQ7r~ic7cDzO3<FL&CrxV&>Xve9qX< zd;URrx~%0l|0G-<xOI=pYrZ?Q@Y8GajaLfg#@{|tuS=tKKCdLiT-z&n6y3*`Y|VGd z+trj@B5l#z@9!S#GQVb}cXd;K+@`nN_Bv5zK^EUjFv`GyDr0GrRnvg6FL`?5{sSSr zMW3H%qVEUxpv_zE-G`$g$A52^sxa5ZV~Kk;((9}s`-65&0y&yaTl~)Wuxvm&;$-$+ zmkODna9A|+C;)eb-<ktfpsl<(hWHtNS-63e0J+3khg*cn9-YG^=Caks?=P>~Db(Ve z9u$K<4D>Ihe8E~*B80<qxh{Zm$4t5{L@<1h9;`o;EYTB8@(RSkU%)9^S=^))miub- zCOfS)fzj2vKt{?AW^bfJJ!tpv?z+Jeje0Mw{z;OCpnYPZDb`x$uwA%Z+}f5bS+<R< zmT9&*zmC>Ngc0i0baMwQd^cEXs_cE$7i@$~%kM$<AMIXQOiPjHV|I8s8~yk<hP$F$ z5m0q+p~ZE3&CWSd(mPMDc7k2%yk-|K8SHOPuPD@D49!^fM>XwNAN2NzPrvAx?d!l! zRHP&{d(R+DQl{{L#m^PYdRF#;epYGYw=BawZUU{}>IvS&qzmcxjP{oQOahY{BBuNE zxSpAPj-=9!`P-}7<-49Gh3WXb4)dQemz3O3#FEVLtZ(C8in?7clV5*c|FN;3uHtIl zXNebvF3g?1xc9pUOm}z87xauemx77+W=0!Mv#1gt44U&cY06JC?tOkZYa0XPp}3#* zaS<_l;6)^b8(%LgmQlW6bKGdnc%8{&aOijX7{%l)-_T#+$@0K5dGtFvg~v2}`#1GW z-Cgb4l==D$f2BaikBmQ!7GEqKy)9d2Rgtq6_Uwgjjly(w+k6r~>3^*fcL7Hpp@{&T z>R~Xm>m>&7?C^6}5-fsc{d9()<zKniX@}$R3ev}gW1(RFXcyAXHYh4U=R{3k<gGc8 z{q~yD*ICPuYU~&Ge-Om6)x=O&(5YhNE44`YPJhQtek{Uvt%ik)N0-bY0g5)?9nFe@ zWB1<ssnx_5>WJ|g%@QZ`)G8T>xCZ96zLR!M&T)goy@j0vt!#G?-cX2%m>3EaaxcKT zv&nRfJzZ>0nA)0pC&inD_$|GfpB?PcT45g%Xjc)RJGG5p)=Uv_Znwy|Q>doMAGAly ztok)dVcENZ(;3jlQ^zB}Uy?f!wC1*AOuteEV#~aPGKR6KB#mZsKcT9=4P&PkCZ<#h zg6qyW6xKOCV1jQV5Z|zd$1&JA;=H-jq_0!E@Wwg|J-~g{EZwXFI_?$2U<bwjJ>3SK zEP@*vEdAtb8L`W`BGuT(9(R&toncq5bJBn<2t(`GKtn?M(S%Kqpx6NqHux32ar9-X zL2j2s*zpcE?BLTEGsNMJWX73hYF*}PFW6XJqC3T92<6{ki5P@a3yZW#VQbna+n3)$ z{5BO#F+MqOO%cpMQ7i~Lf4q$xVmo322j9uuB!sQH?D4?=(csfDY)68HGOC!uD|hd1 zGFrEN3DG<U{(VJmuF}N^MG5_)nt@we?q0P<A+0?)>!{570s3b`F=uy5&sH8!Lg>tG zd+$tXEq@RzHWdlYA8V{ChvHgu>__GoG4u?-3H2*_e5iZf<SUU474{Z(Z=K1Jx(Gha z7${Ad;+*XZl^P5KRxumbU6R}Dd+hu6d}}%G{N~?5a0K0$2NQkeq;Y2V5rU3DV~k}# zuD`Z``NCz1#v8e*LONPKFOt9ATbvbq@#phtcmMSjk4Tr0Asu%Pn~UE1+R~vzkDWS* zkghTDloT?zUsc(AzOu337a32n!&tU(;v(bIE*a357*w*%$@uiFv^KHHfxjKI`eM!t zm7*@)xe?s0v39@ou6<KQ-R-E#hjsn+7k^G$_299+`9|Xu%+&aKjXcD|MI|3sqX&zD z5Oe#?fX%oSD~QFABkf|@oBn5VdNz-bw5Cv^gZ5o&J#t~A_O#H1tPvi<hnH-5*c^k& zG!v+Viw_dgu0FhxUUNL?@X-MGT}>Ac3pwVE0R79p6QihZ>)RW<%ul==_rxljiQi`| zAcy1?EPLqid{@D1YA66An2(iz%9Ro&_q54b{(*L9fico&$^(c1H?Am0JF)DGoe?8< zQeWKPTH;<ap%qq%fD{$jFbgYSL0+C_Nh`rz4p|LZ$<yn^teWX!Nj-_iQ<ml6foh2{ zN-_OO^PhyIm7FDw?=yC1KKpJ?;;sq5h&f58Y@mtaa2PaEj!VtVK+P_3OW85tW0n{r z^XGK)(Z1qhD0{}sB_d@c^+(9Y;UYgKBnNVF@|k#&8^BT$V*Qwj@@HacCb1C26kq|L z%2m5EFZpqK+n}VdKzyvXR4kcjp1+)tjF@b7?|W$$vjra&y<KeIYm=!vR*|XT13LU; zIyj3Py4Qim@B5%c;ft*(?6;XUEw%pWu5GgrgT@4IG9KNvUSz&=w<MaKOl5Hj`(|w- z*A|5^(^q=1I?P3=i#5E?W%KcwghKU@21VJNwR@R*h;e0tuhNEr5psA)6N9{Jx~s-# z&2G@FD4~5MPoNTm0$ldRFAJ+|k8pp>wunkgOhIlxC{3+8;7N^7Bi!L8-EB8um^^w) z%orK?bplo&_8mE5JTsN%OE6sNYz{9Nl=e4=6wckV`UruLS$IKQLwC5Y4$@rkeEOR1 z!dN${Ay(s-a%o}h4G>R|QT0%q6#7?6f)k*FN&T7=@y38aHeqM6&kH6BLL79BCImC| zd1Ie9*e38-S%!ty<m5@nqaah<K@$!howPPpq!(jZHgq7&nvLZMeAf;%8D(R!=GFvK zVyNWc47y+u=_>^MR-f^)k-8D{*TWqNnJj68I?u#}O<V?1F3y)|z8Pf4i1=T*kEe=< zv+W!P@!{G2;@><v4aW{p6Z1kjtf5RJCc&RGIi9Zq6ZPOQ!9mhx<GSl>ZU@l{^ZZ&( zF3*v54#qIE=}EdRiP6mYFHqXSXB8_vHE8?HDAjyiSb=$)PJpaE{;)_UJ`#V@$;{Bf zDfc_Smlp}BTB#PWrMcj51#WExxY&@&%_zcKOy)Rx%u8^TAjweD`{Y<QLsQ{2_;u<( zMuC$EX-bGP8NyJU@@HQXIWWpg2WeT^-!vVvrFFWQhF+O(nQ}2-RjRNFgtoM724^$B zmbo&!A9y6SAPM9BG~*;Edi;}*Jem0MP9gr7T)Ty^LL?SGfhm8xKplZ7ZxUZAq^u3> zb+$B_$8`^$ZLb$C3P#2(-V4tPsH+6$;Bzdq5RW)CfIqD3=CHdd`yTmDgd+}!0#Ioh z!{xIDD|hm*c8JqOJ93QyxaMV5v2FuTJDyx^hP4ZHDAODv<87XGJBp>gWM{^w63S-# zS_W;I-cA$Tw1QAc*Xd&haRfr47LR4ZgixRQ<C^B;wk!D`gU*{JIu=lk|3rV-Aa!Ns z)c|fnQ(n+JZw&|Y5<_CHHpkrUaA(ut<5gEY>_(0hT<`j1)~wX3c=uE^^P-?FJ0+d5 z*(gWhA=;ewg1ENZmV1+aisF1Shk1YVL8DX}ziwO9)+KK&DEU|Mg4f?x><G3hW^@e5 z{rTsgKq<06>``8!x~*Uj#DVo|RX-FbU0dkiu{78?W9$@Iu~4rTWn>GoP2nRoq)w@8 zg--fZ6(N=~wchX(pyZGy=*A=G&gkfSOMRk^XB38Ke2b27*p{-`y3PIyGiB%Ivi)h* z!{g;U*M&_zb!|<vJl@gp@&2KmZ6Z*9d|>sD{$c>jVEE)2oT$F)vG<6INk8FwBGi#I z%tsTi=3J;!59&3mk257NV2fn%s`E0NFO_TtJ5}ZH_{ANKVj-gzM2UxPDt{Dfu9H3Q zjwu!xmjBCW^?f<0s5;W{vg-ID<rOmiT4lwdckKs7Sr&Eqy@V^nzwSM0ukn_&*nE65 z^NaYRYU__NAJz8s-dcZx+ey*TrCpUWDs|c13L&K;F7aH9R*EPmDPrsD?;hO#W$W`h z{%qBO9A>odIlnzR|5m~?Ru!>ttUae&xG-WSLbF|Y@4wW=clLU{rzi9L(FkPtdnZko zFSok<j6{Z`fjzCehp1LK`*4jd7hKH87lA|{D+u_4*tgSJYD$%!a1?sBKo^Leg|V_5 z9~pjlCgQ(AXYr`WLYl=?ScZ0s>x7Isf0<P+H;)lBh5H%q(Rz>rK=Xy{8gMUHC#KH~ z0Ujil3X2L%XO8h<Np3(x`KHBG-Gw#<`}tMklO*+gYL$&uwcnq4$<*p1iu@#0(^L;o z^4iVpMk&NtsFqqSW0w6me|7~2c$Y+zGVx-bkIF~+fN3NB2YU)ZA#+72Si8n4@4(q; zKqyV7pwak!bdn8!CUgt^5T61sX$L_+!u+@1SazW8mT43x)AJyGs1<sArUOc79Tu{< z!jkr4eG}E%4L^Ns*~IC)lv!TsKSOMH)!LxoZ=Rbx(#Ge=n7^FXLjnu3U{YQluj61< zMZe1S)JVUE%F*(JW;BsHxYHuaE>F(fwaX2(be5SI+IP#c*#boq;R6VEG4D=X=1Ub^ zAv_iTGCO(Y1L>)bgt*-s9sBGLeK6N36><71U3HfK`=9(}HtPkA^r*59SBtr|!ue{8 z_T2SW%`^t|%(*LA+IcfLn=2J&QiC~HXH|rp5JR&c;x2cu3p@1jCrA2o%2zGoHV$V@ zTryR1K-j+aJ1=p}lLHgSK08BLhw55O98Gm7xLAABqsj`rgv<nZS_jE;oUGnn%uQZ3 zN7?>uI?;uuhtR>tq%qdGX<BPfKx!B3AVP!qN6-gm6&LsOKijL8S1>Fa{x8Q92Xpa8 zoh$L!U0{f?jb~z2b+dr^F?zHbQTa(-6)waIQG5vHDMi7fniRRm7Dl@Zpp_@&L<nh8 zFIpMTjs&3rC~4c<mODY&B2=7j&{q{#KsI@~h^ufK50N@(n?8I>BE6Iz2j5%VTG%4N zm?nN@3OAfCFbRJNK1%OCE1t`|E^~xmbP06wA9H)gF+heYRZM><o&gvF^nHO=4G8t- zX6}rGl(JT&NAsqBEMCbj<bQ<jq}u|O4;xusf$vtT05i%1d5;)!bc=|zgm$j(27j>U z97g`5KbqcwuUMUUYkC5C5JdtjK4@~L+(BS}OT(&@@D@!z++xpH8Gi+1B&=k*8R4NE zVks*&q)taVt0$uv=>*(V-o~JizXF9vOa;v}K1y0A?qcXlVI<AcUJ6~|2oNg1V6z`P zXe9?(Dw19A3r;aOX8?>!I-Znl$s%zrMTOmH&DKg2{v!*hnZQakJZ=CKxwGZWMVJ`r zdXlj@j6pE|%F7wnaqhVbnA?cI*IwU|kj4b8{fhZI#ZboEP-5E|WU1sH^)fMD)^`Tf zm><nYgspIqQspL==UQT6psj$VDuEbvKrB_9{cCI9;#RPuRJ><AUw`Ch4dk>T{e=6^ z1gu>}qO~l_ShjKVI>pGon+Y7XAII79!a$-CoBGM08&|z;Qr}!%Z9LT>kA@bNu=w!3 zWi>^```$A~KFWe1ykRq(*78F>i-k=2beVI9^u<jGN1BR%xAng_U2e0mPS@i+w{*E$ zda;BR%Zxg{a=UiF@lW8*uDh50uX?wQ4Sm^B()U;y3mUCsoByeB*^(7G`V$tH<=+8K zpR|t(>Nx3G^BFjr0F;W-tBKEjt@%``nQ=Em-K1Ho@08OZEqw>D)NXk0<D)(D*$3Ju zUOx0;E?HgJOO!t!>fR-|R-4bo`@d<xV!N_v<bd(Kuwf$7rzdv)xCY=N9HW}i&ftnl z7Y4lyG3VALN(Ub20XTv}?@7pLj=Gsqs7pv~uA=-~+4Fq+t;F-6H?aU-nKi~_7c-T~ z>>GIQ@E7-AsSS7OTgq9eQ!E_LI5C;gz*UYWh1WrH-x~p)M+hm=^)Yo%57_<s=1;H6 z9gnN;f21sBz<93gMIiFg?r??N`jcaN?Z<FfBpKBsd++{URM}Z=5q(yqW%tU;H6L5m zYz`i1+B!G>obA(<589hB(+YXh`O812bAVTN`8c(BzTT$U_0DM8NZ0IhI;Ga-GfqEI z249KGz6QRDOgHx$ceQKE`_t(*QtNGIR3nFE;tPL-Tdjri|EVSSAi~m1`{>d)qD`~` zu?c9%wib|FjgpD#l(zg4Cm%2;3ymMM6=f-wziWHkqzt^cO9+Vjp^lMDJQrEIV)4-P zGAG;r{alynVtyYm=iyAj9BU~T8_2Izd$Cv8%nIHhS=i7%Q*NhMB|jc2O6XN{j2kE} z1#M!9z23<TFtj3X2T>BUHz-qTSN2MR>UHmXUT9b+oRwtIbY=Nf4R<-=%EJH#7E1%! zX60Us=!VA1l-%OzX)N~>)AEN%egnEr{t2ESOyZkKr7MkYUw;qxAm12Ty<!}!(#M26 zM!YzYewUUKX!YN>v=>3SB4&nsXN*|DJ$Pi&+q~tlpY}gcBd3$|wlpR9s$weO1K$gW zO7();5-c!Q_*+0kE7y2;M@f<0(vejO;Y<whTvFuNkacXxL_QL$F@7}cTH`WVPI4n4 z<YW{U$~s%v%DVvR+Xm&?&{r#a{_9<I=-{*CwO!CNw5LlJq(4;etgL7_gg>Kj1(=WR ze1ba%_7C#Yx+AUCq?*r?&MOvBG!ZM9RWkQGX#G<|$nzJto;|(a)n7{luSAdpL+xAm zE>y&~5zuwT-Vp2#|DS$%_7^=N^dW1P-GCV=+uhPGmAKlq<4B4JGdA#oZ)?x>Wcw=T z3Ed8&;>BVp1|J?}3Ed|dN`QOJW;sbDcOX0U?NttDOR=LZ!iyO6v0<k$i=`=&JG{j8 z320O0GSYRYs@sy2u!vP6Fa~!D^PJ?#?AO*BckAfKn(L2Yh`>z-Au$UP@mh?z4x6B& zAL4|g10b8lN2|atDD&D<tBhp_kqIzJaWKQJoE88*0+Ti%LP@NrP>fCmcG^rzMH0um z5Gp3KJ&FbY3q*|DP$}1%sH0+c6y9Paw7j0ph#*L%a%1JNHYR7UFrCHt1kNC)k-{NV zAdnbQ!IbpGXo}H~x%J-h%A6g7VQ|V>D&^(bTJyg(jyBi&>GDKD-u*4E_zBQ3X{_$2 za}LOokkyGzsg2wPNqRMpOv!E`zBNImz}vzg<9#%8CX)tP(c(h2JzfbKVs3M-j}KKj z7U=*9v3a@}2@X0ZB)bDOL!Pc2?F>3lmo3?8t9M>9Lv$mWAT#;w8W2y>$V*aLp$73s zOgVF>@K4gy0x#5LLnCLvcT$8}GgP+@OIuj#06$a^#_`XhoZvk4GEkPrdvV*uY;ZVA zI9%C{EtOBe2AGyV2D~-nZRvswJfx#LI7VdJe7G8n-0r)jUBK|20ln5A#PV?+uEr~k z&*gacNQG=K=dJ0POWeyhq{{*=@OAB?U~H~l?cT=SL2weR+R2Oku(!8xWb2)+l{O<O zOI_<*Rl+K|dT!UW@Edl2y4l_A=UH=P20dyw(x0DVoe2I#1$nl`mvWxbet2YZUr)=< z3a_u5>n3Ao`qSf<pJ_HnUZ?~E#0ORo8(f+3t_!}`8!inwowK-2H5D9kyr#2cRbbY_ znVQUw*@cI<9UPJNx3B*fB>xi|zpIOL?7IV2SupB8fb1-;{_p$WpS4hVr77q;gIYR1 zsL40}&I8R%y_zLaomU=JbOg&M?@-2@HnZ&smOgqWZ$;<~vUSX^oc56Vv~vrEN??4; zwLdC33#ZFIToF%!fOiQu!b+do@W?x@FlTccgeL2ct3v?I!>pRUIhO~&j$ahHcR23L zhug|2w1UQa{vGpcQ(&Fju7gvMVD+w$U2}O@GJe5S@D-1iSL?bThFE^`!0z0;Lp#QI zSKd-svte?}%P|Q9=y)iIu2p}1E5Vg5zk_ANzqHI;a2ysp9vhb9J2L7VY9Bl|XgkI{ z7CHgnZz(g7X4l1d7=k|Es0wsna_`_1F;m)(|5t#kWlEp97+MS9b>z|mBQaHL4Zq#8 zRf@*xW=89o*G5*vf2Ys-<fZE9^~PhyJr3I}+vIr0%OD9GkBH*ly(i!CDUX-1&QZIZ z`EuaLv!_?RGu5$i{n*kL;j5P!6Z~1Pt=;MRHqC1%B`Nf@C?yIu6nN#=Y|zIBo_HoJ zaKqD*82_fgSs?&CejP}Nxo3(oJv>KP?|Ua_FL%{S(r4O+asTJD05BU77R^_nT~Cj9 z*X&>0RJ#~|am`Y;4>J`(jNvg3rcDNm_gwTWpjmSh+&re=atB+=PAlu^E37Nw?EA_T zH<tBHms!Wk9A>_so7>_q^OY+UL$PN5kP}`mKsfn6An0s79q2u6!_YfPjeGp7ywYcU z1Y~GWfmarLe5MCZr3*<!lU#|q;5ux8S_41yL(?pPz1v(%N@4swfIvm&VZSK=DU~<l zfnBt73%7;7PPUU`;CyiZ?AGpd1_go#SQHmw)t{#|mhGB)lG9cc(5A^2@{abL8c7i* z!E+v(1u%GfzFQ}ZRM|Eu8jm!?E|rh{{t1v4<bF*%j1gw@@oL7cx#l4J6gL<<HW*`v zd0SELDh;tkjXkB0-B<VBRY_Y9%?)W`E;(BBd!w?c>dn<sTwc!vG`dGIUi+$mHOEMg zFS+T?9bP@~rB3;aJ#z+Ho_OOif`HUeR&i$WBazO6RO=pG5CaK-l-sNO_JY%qEyX<i zH%71|yXMCAgRdqH8p7uO?XL0~6^ZdiBi$lkbIl8QqHPwbYyFE;c-3HsHyP*fO@Z^$ zdJLNeHA|hB;nN@hvZOA(M3t{v41lqPvH*4v$xhFk%%)D_so0K&!j2c{u21B+rC5CW zS?*MkXa>qRAPXbVi<QLHVh&>r*V>pZ%aDrj9L44>cJVgbLNNIo&ryMHM&tH^;I1*O z@?h)*zE~!8)rtb(Y5?9r0tlu`Q&wSfyCDOmiaVPpIK8|N@JZY*a(3G1k92VtFjt(g zxNS_zf0@_DnJEROlXmZc_)KQhU4n@SWU(;+f}yUjX9{mMNteSQ__X*X{yu5-7R4i# zbR>-y__lCD-N%HAs&3H!06?IEGUZ?lAVw;IcCis(*>zH?2(gL2Jk79tdcr4T1nL~6 z$wh@H+?wH@OGh&(I3}SWSiGGs)e`rwhQto`TF@CmuFQ;k&M|8x1gvE<ZjS5Z9exla zk`NTpWU;NN#rS%$pl)KdC|I=RoalLCdej;VQXt55q78D-W$eb$Z?X;VX9tZ)RXtrD zVy_rkQF&ygK;?em;JfaBj59P8!(hR?i#jRWkFpu75}2jp%I0Ly<kj#ONb#j2r%KcY zw)*CgziG@R+Tqv>t-_|l?^Us<2Q78m4YK1wrVe5wdTt&baT3+yJG>(RTtS8y&j{x) zBN|~M*|TOB8BT~58j>k|^W<~jp<da8XXW@Qfzn)Q()PCE>FHAZ&11@^Lk<`t@NtRo zwJmwz_}l+&ey!@Muv<xeQ>7p2WaG9G+fLlOzjf7#%XdzH+LrnVM<v(FMfW3hZHEt4 zOuJX&zUsl5UmCn6gZDRxwVnFTwSyxGJEQ&QwY+~uY!_(eP%fRDqy5$GePg6H%7h<{ zm)|tdgo_sZRKvfHFh&x`=6ryk+mruPOu4>BueK@pNO^5>&$PpjUst&6<didTxH=1C zhgVof7jv>16?2yXWCAx-OjnX_w;k;ZQ+=p-GO7gp@F|QrU>+WpeledXSYS8Y&y%?j zce%Ox!vPK|v2K%1@YWrCvqRCME?rw&n%v>|;H%G=OXIzY@OrG~JIC#%8&aeX#W5`V zCBYVMcQF$I9jbI~)RXtxv(~4SkHoJZ6E<5dH7d(59-U$EZD`)|Hvj=~(S6;OqYIGt z)>M9AxT`CxvfB3G(JyQQ!zi_S@7*m@q)8^#YJ$y{m8t!7GHn#I-@d2FpC&uf9v}XA z8&$%R2A`TU51#(*OZ+>dh_m7Z)1l;+pFm8cYdHQ@sF%tsu|KY;dSf&VQWw={?~S3l z$=7>c(x(<@VKaQQBWre6oMd{i*E@whkxshor{_iUca`)&%l#QCibC{#j@;_Vw|o*~ zYm`}@Z~UOXH|?h<dzRdH)J*1h#RUJjdGft0XAVhbWf|AT6O-ijgNv%erJTk*Hm&<) zFZZ_m;f3uNQ{Yj-3b^0ny`KH2B=o<`&ahs|EOFiG%j3IOfTo{T01r4`%6PcwKXC^w zt!@@P(#a^9f00*xm-t)te9k+n(y#6vo*c6I^s2E*x9r#$&{uJ?P2<)~N*2(bcPpJG zoG*QpcYeF2ZQ_#32XUQQ?lJOrX*)Yj8Ty&_Yd6a?)1t~kswdsDs*8ePeoA^Z_|x$> zMqY`(t8Y8qxL(tTS0&>ThY#xdV~$4HuCMNK{xL4fp}+{YnxTdJDQ8QU<F4NyPi=~O z+ik)*W<oONo=Fkr|Bf2M7(_cd$^0V#u78r{TG=IE;^btX=c8yPFi!As;=5m|O12v- zj~uN*T*;dvX%<jqUbdh&1(YG~71G!WuGd|bXyod9SSjFyCc(*x*~^?UCo?#Zw&A$Z zBdTH6X=>y#fSgRgpeW`Ku!K9t&qSfYB#K11%t9l)A!!{^81cramBXx9P|NsZ#z(3` zRG*sU?-LL+sxtG43a4{($t2;e*snCttp1*%Hnj3EDicORyxrJ8U!?!37g!y#(ir*j z-H*Fhy3oxpl>)53L@f6uzPWtEezudAEIn7dWcyF-(ur*Edf?}o%F;sP<33+c0RwHe zh3y&i(c|Gfnr?wL*80q|po&zx=BtobdhF;bpof0-c+1F;h=_+a(#(`LFB;A~ay8wq z*A#ApCtiJp?7P{vQSdCGFfHz_5uypMU9H>D2mVtfBk!dOQastWb}Xa40V3j~w!GW@ zFO?9xwZIZlQAd@v#EbT;((wxT%QqU=i|>SM&VbTovXvl&5Q$;+8QPRsWDH95-3SG| zMSCLudRXA+C?MFTw$1q*@(6CvQfcL~r`r^_60{ChtRn!+z^pWs<vt52mx(-5u?+${ zU2X`6!Al#HZ9$xQRHLrTH5ah?+lUsqb6i8A)9r+j!H+h=m1V)W-K`>qYymvvz+_xl z&`9vBrFm`=-ZM0iXBw-wxer$3iYC0|A?Qhv0Aq-;80z7<+zH-uoX-thkxQc;%<QUo zqt2_Crijlphw>>f7Aaa%gon@eI)1*~Op_o~99S7e1Bp?}p)@3qW+KKE`I~&Sjm1<v z&INc56zgM;oYx6l`oEYa&6<Q|SUSOb6fLq4dMv~@Rh%D2Y_cr4F~fK!Y5b1y706hi zfd}fOogS#%@ga<r4?9~zFP<u4-MCz)?GVah(x$*Ad17GOwP0!4nBp++*Ws=N4zDB2 zkwuv|(9=yFztE}zF9o=ZtwGPf3F$GX7&V2TW45&&MCmEUcBaCnOUQ;7w%~c7$4+h9 zX)IGO5Pmz8lx*as3Nx-}f5=nN3&c_h>Zr1G<sT>$Q-z)$CG@R0>$vqJVB6_tBi%T( zrPkYx9>K#}^uACDv?j)qzwZRSn#m`#&(nG0M+vGcySSz@cv)UFl@K}76JkZWX>_ky zvh&EH{F{cdQEo^)G*Z@L{*bt^ys5G=S94E#6gj{Now1FWQSrsuYt==)nOX2%&jGn~ z**)pme!a>)n)Mh1u<E8`7<FE0Ij11_rK=%&suJz#w2LLiTDyMokH{0k$|G>kQgt6_ z5{GS$$$XxfHV`^XA!^zm{okvdsk@`s+trz(^`^cc`NO}H#GzB`F8SQdxk{XEKd;#~ znzAvZRip3_|8Etpc+L(!-|p&2{ayKsbn^IdQSfBa*5{Vji=Li2M%cUuNnB5p%jXra z4}r&3uqQfagNCl1*VZ2W!pr(%M{(nP(XAb&=1K5X6rJVVH5#+^8J7)T)aD4EtJEgD ze?tp2sF{Eo+7}1>GxC+$85YyoGa=^uD_e`?MO7dp;&S6I^P}=uWoH3dG&jex1vVA7 zcnw+nrEvEzqh8iSj#ctbs2Pr?Rr5YWJ4}Z);{;YEV*AAY))Ul)rj#7-u;87{i)+u% zGbTQjfTOP=j4u!Yoa%=SLi`;ns^PD@)2b>(=U?Zhj(qWyYD>c0I``=Bw&nHksPUbn z7rwILM=ISx`?85umQh95i3Wx?W5h;9j%)jt?CLjU=@<aN8qle9g#|iR^YGGJK8(e{ zp$kMaW^OZ+L4+l^@YT(BRijy-ZK@ap51|aVPaEk?H@Ynm5!1cU?wyet_h#*F^$xg@ zBRx@N*U#)CGowjvdBM0=`KWPh=z&pP7S=WFcWaG8@+7t5ne>t9fggT7w=S%x(700x zQGj3AgciRy$FD8R_4-whf!n`sl-P+mONX*`fT;cF;U7KSm8Uhux^Wshx`wM|s@t;E zGn}t2{=5BqR%++mv73=Jp-N)6>A^#j9#?YWa87?|<OvK!cm{_XLfv1nX|j8FJ0@xn zl<Y@7e=xi5x7)z8$1ABvP0OFUYOXFw-}jpKnd*s6NnxMZx;%KY@a~)4^B3GPd4>c# zLJvE%<TDhEJ9-piW;+vmHb~zh9j18mPc)`{l-OBvnru&V_?y}@xkiKBW|Eqe2oH26 z1uCj4>=?i6Y9U1n6^KWebemPR2_DYh=Bgfwosu@LPuHFmuk7PAFEWd7le64gI8Rwo zK*%sVF2rzkZgYUHpI2}e{IFpv5x7(HWnxCDW~YQ1r^%b0@vmxek6UKShoG1FV-LBl z8gD-9vb8EV%2L~~`9ZsIyGfV(Bax8YI?U)-+Y#V&;QO^sEz6&0`QCKxa;y5cQ=nf8 z^zKHzm}M=Cgb^5vp~24)9=jq(Pt8dts-#z*^%IdTc?Q69J_?GkWfmFp$ru$X)6=m? zmwCm_H<QFUW@Fg_1ZLLUP?<1!eDKi0q@5w<!Tt7!-i7c4zcMJqa&?9J(nyR3PCh-5 z(d)1)|H%#o)`8qXlgf$KsEw90M(R>=Fg{E2MZ|MAuU>A7HG*l<m{9qxxfz(V*6!h@ zqmF3?ubj0zXjV@g=kzCtCiDKjSrd2WC{8F376~gE27x%Chc-c)V0xEr32GwR-&}QK zob@Iuw;D5yV6y8uq&x#xH%5NIWY{{OX{A@i)Y%D9Ac!^1I?N)9ZM>(~$mm_yYSC)0 zmTZq?rqcdxtob@zv?VuI?j?bYA8!#$2(Z3IRwF2SJTEglK^_*0GCb38j8N_eGD<(= z6<xK=5}6yh7W=ud=NYa4o-RA%V`i_egMT4REr-*^%#217My6Rc&#+wPCt{CM2p+KW z(eYKA!CPVuuPJ~WwE)Hi18PmOKm{_1h=D-599<r^Aj(mKum^)g-m@Z<h=qS0*F07) zO|WDAxsYoxrKUYa@&O=f8qW&$KNW<pY&OyZ@s+!k;OEruTm{3$uTCVQ3Ci1?)RjGM zA)G!z#BJ3iTa>u-{Wc>NGU|3R=f3T04tMo;5s2l`+C`iuUt!DJx$JLr(Um|v>;wZL z>(=2??kcY+Pn@2h^PPx|stWXA9>3@%JQvv8P9IH!`WS;OgdH`z_;ywtMea`^K#?Cw zpzRJ|Z4_aEF^b^zii!fx44p7ggrNj!k1$WhTmr2ehOb$CPLpn;2`lVlI4=YaLU#~% z5U-|4>*yw<V*GefQXiy>Hs!ER_15(4$^Crkg$p~;<kT!lrs*wbnb0eNM(12df`wOV zlhydp+r{5ZiCT}s#%YjsjlK-jd8Al=&T%hyFAvuwzt;cRx@VbzsLzR|th0{5%?SUe zY`rm~!*fhM8fCM2)6XL=odc6@eXVGdS=eqcMq(@&{L>A5O^oZye6-KJlz6^So!v$? z=vtsr*rQ#>4`#5D2wLYByIV5AvON(=<Pts4PVO%1SAlUJ9Gsio^jUnwny_6u&rS@# z;5NLIVSQVP8CYbN=|}GSIG#yiX0FADw)4tcC^m-&hvPhMI_Qo{j|v|6SY-PZ-aER_ zgVD{N?SJy2;h7y6Y^E-m*9Pfw{CMGg`&$QHzx*0zU1XNE>2VT(7S^GKJIQYb9sYp@ z;N3fZ6}cUy4<^yWamDUicb$J<%igo{gxI73B!v;--|Tde){WMbNKETUSB}>W_mq{t z^pwJ`kJ*M`q_x+9d}1<2Mm(65C`L_8B`MxZRr%X%wHMLbo%}NpmCo3Z|JD$3C8G7( zzSYMwk5CQtLZztctTNtGK5W?i`Ip%ZQYt`F^is*;xg&eWj;BCo5dX67@RmvzmT(K! z`3<c6z#A*|jKX76-%Ch?n6hj7=}RwR$`P5hviK~kO8RUg77Wx2O~9n7%k7vlq<m-_ z@n%ZG3%nWOtiqsEoiGwQ(D<jv^8cK6&w((btsRscE<FD3oijY^ZmVjZ;&}P^gTYsW z4~;)RQmeePZS@q#w7Q1GI+k<R4bROfm_PUDGaJWcH%Hf%7}RkuDlG_tT!gTuJxhyz zTK{MVZZ;LV*Lt5=EtecWsZzcuK1TM@ay!eOqaiKAdiW!m4;C>6^N&<-ZoK<b(XovV z|0#}o{_KCV^-iIpX<M*cY0*D!8U5(A(zRcn)+g?`VBRIAZOdu=?FXsu(vsWMK)1?X zKW}S(TlZ$&ChJUH(*0K5u(9vNA9rWI_sW1aW6Y@~TsHm=#)S_UVjO%oy!*NLl@%IG zebl7Hfo)Mxn9Gj8>`b%{Xe;tvm7?`x8k+0k=`eq#5slJNocq}rkft>PCCRTnfJ8q+ zI^z7?HnW+u16cG#S1*J2D^(TT;H}ZMnyTPC%!18YRvMb6+omp?BpZMFor9NGr3gZi zCXiI?gx^@o4)=1lPqCzo?SM8`^^C!4G^{-^mhI^AQQXP>XSI#%E=5ktFK%MW-;EUI ztmmQ`7far&$XUlA+sVntbja%57~B^(zCevFP+Gg5t~{T3n_q-EAao+t?sPeByp&tP zE5!d5D>7=ner9A2vtT$m0@*pZpDeoiJy9>B5o)y6GCpsb>FK5H`OO1b04;Z4=>*2( zCZT=sN}psqNqUK~ER`GrUlqa*gIquI9#rT^07Rz=KZPKC<Xai;<I`nGV$BZ~RgIP3 z*bWDTXh8Q=l<`%5b%*TD?>&(l^G~%b2<{mb73UNSFb*bq`x4T%r*nLU>@2Hns$fSg zmJr1t;U>ggGx2P$G`{k@JJl*m1rha!zU0^FGNJP6gm+!7>UimfL5a#|^~BG~d1P}9 z5(9aMApHreH>u$n{|$oB$zu^TCWW*ULh*l1Qxla*`KoL<pQsz*k0noO#REe~bnNrw z?xzHZ;oW7f6SI0$g20`nG(<#q$f7OFEV<jMjXX}aKCFh9(#`6k1B1dAK-jLPEFm{B ztvjG&>F-b-qepBlt_UO47!Zg-3Itv96J(EvqQ(nWXq3#V%2P0)Rd8rdtP$uOx^uAv z51Swe#I-oIpJoQXjgd(V%RqT`fxMsA3-B|>AAam0Nmd$9s^lrHqQOfQe?xTDN*jyn z>%z}{bt@UA*ZB)(t>=`qhQWAe@IqIrq1Q0o_Y$C_q$o)&bZWs31B}{LD1Pmr-IPPg z6{{w<)BJk)ghCA_&$!oaF`I$mhd`KWws)%Bu#%ID)Ve3YQFJ+B3KIF%Ktv@;h(D<< zS@Kba5w|eJ=W@Rfl}j*0<OD!4AF|15j&A15bqkS_;G_57^Aq|8?wGgv8DU#4=I1;h zC|X=WjT<{%Vf2&uTGKAzPZiGz>v$h88aFB#`X^{%B@*Ji*LD8*>N)St7juQ8^z@l) z5q9sCDmfuVaO@>O-~b{`C|XP-bFr{4A<#k>I6W{&DJ<|2f$Sw~Mfugf@T?3JommOD z4>SxkM%F(^_vs`w)9C@j)qxXXDn|Z`i+8_JzR`H5INfsnh+Xlm*E{RRF4)71V*l!+ z-sk^*S8ae^MdRP*bN0cy4BNeT$GlsQt1MloFvn2F$mbTG(3#wNe%MOl-+OK5-mG)6 zAtxpsj}{gAssWOYd-vdtvlf`gLETyX!FpU>C^h`$mcrj+eNFPkG}&=L27VqY&cy?J zGPA6sBr$L;{vS=>9uIZC|F2@LI=hzI+6vQVL<+mQvcpi?F=EH1QX;#>O6?{hrZBDA zEnQ|ZZmUj4uDQf2ZMkG>yNp38*KShHxK79*hMC#l^F8PL`{SI)V=Lw}pU?aAx;`&> zgJk<Q2inI#Iir#)hmpyIJm=O8E=MCgC0D=W=olsK{Ic=!5sy!rh(T1*gr7%ExJp5* z@8GPeLvI85!9?=>sq$WpeilcqYMoxKyT%MdT^<}qwJ-c)2q-dZ`rY5P_ozuCpxjBv zY(*0ay~O*an3A_33H$oKzx*sS^sB4+_)79#3|6)-9P6^iDglI$KVoRNu$fB2)zgRD z*j7>uNdY%2k+>N=wff91H%Oe{q%K3niZg}IbwIzoi87>qikjeR7vU%kcM(#uH^V4N zj1PuKA{t>clgD#@M32vo9z}<vdf8mFF8nTvWjtQAVHrSFz*<ESg_r~d9qhuO*^GVC zR8@Gsq%~G#6>TaqA2y`Z@sXKPy+Q+@rsiuSYPsEtwgWk(bKlJ~2|P*8GK&yb-P)}l z`c~@x@zfjN+|23-!}t^&1Nj-Otd#~&T_PFAEDL`NBAo~GH4t{`(Oc%DFGdqIPv;(X zPV8+<piqygX3;n`0-#?VlXGwAXZ<=(+~D0%sADk)v7@&M6>{18raw3a6@pV~j&UbO z@?LRdRzZltikFljS;>b$?iw4Nf%2~Y>tb!qjg*x1F5Y)@)>wl}TS!X~UWD+DqEO%V z%q8X1)DblTGkHN{Z+{4r{G2?pK?IHbx!Z{BKNSy)CV1~#*56^cy$&|LL8<)oxW`A5 zRx7u@$ymt&6h$-0&ySK9JZyTN-*sQGx2<N4b~t$ELC`avAj6sTzyp&U|C{Yrv1f#x zVvw@(%irkrCLFzGI=Tc})mT?mCokffOLmoCZpsT_YJUKUAD0BslWeV<YT@MbY1%U- zvmF1Pd(RIolAS55Q>a?SuQeL!y%!L2*Z%&619?AD=N6Fn6>v56Xuj3vJ&Cw<%-4LR z2>>%ni@v-E;UG{Ku=r4Bqczq^Sl@R=eS}s&d;TTmJjlaRBelHLWevIN*@21>1jhr| zGqUm-#wNi!I&|PgY?&5ZH@#a72y$Zyg#<6j%0~OxZ41O`BUm=Ee1`iKDIbDF|7Ynz zqT4nsLPss;oJ8QrW?82lyT$h!eM;%dcAKpa7_b5uVW&BibS%I_RMYvey?n(1mn0E- z#5OT~a}vP~&m%!ANwoD~xu)G^x@X_Tz_p5H4PNdkX};HPf-GiaxTKT<{b|AF*)-yk z7tFvxCeWbQ@k96%FyRQgi-KvP?Vl-Vu~WCrNb%{1h|sZAbG)5{*gbE$L%`$X050)t zCUNCn2Nwbyc6T!?|C7>_6Dy#n*9pu}YEvI4-tAQa6HstKew|Eiz72F_&FVxwjJIrB zyy8)TN{W=Ji0XT-s{;5My-WXp<Nd?Y51>~VsT$o}W;>_M8t)hggbzj+r60(xP(wV) zMrG4jxcZs04k1sFZuWCP?1)Hx?M6vFFk76_$LEdyBdFn@Bwsb@8VVjT6&vjTlR!t~ z!!N>n1~^wCt)GSl8%sOfS3WyxDP&ABOV*+dOVswJ$Ydt<$+#Mb;l%PaIH7zTX6(t? z-EB~Nz`#QX5J<SRAh&vQN(jgaM8mAveD5u_fw<SmT$nM>hE53k3CcR4=!r-V5-fT? zKF0=*0+9?NPx|qamalw(W1EIZ1c54}qZTkZ#&Lq6*GG(g?WlzF6eCBr`QPlhgdneX zVc?A&7Dk}11NS4CAPXrm=SGsj?Lac=G0!077QQ_O^@Y&sdj5U=r8i_!nTbI%)Pg4{ z)o?k2z#uvV&CJ1htyw-XZ3V3qIU<w=IWFsjKQN;Jw;9zC5DI?*Iw)*wJ<psL@%e0I zu3n$USr|{S#kDwoMzGWjI=JQN02VNY82l*3j%>^On02Dg16&C?I0GUJDVhba-SV+I z<SPhU0_{s6$k>~;9<=~UTUs=e2_0=IKZmE<o&%{9kSG81d;_Nh;}1peRumskya20; zh#w+PZ8KWJ=`YE?vWMwYufwrv<e$STeL#w(49k}5iG4nNljON>$TKMs$L?b`;^mSV zLf(UcW7svJKd#F3TnKq`xbRLv8xVzrSMqS%;5yFBtmjk=WmF*(7TvSn|GIX)1asa| z+9?T%=LNd3t6#hA=ab!!v{BYMm|}J`Jzk)Vp^?zqLruh_$D?|u8LfTYYk%ZD=BYx4 zVbK;cF~GnqP%bSpcm(d2Ar{{a*y&L`;f2H|pmm4row_SlvLhJg>XsrDFL>-k-!gZq z1R5m(6Rgg5*sX8ticJSOcO>aRIB4^Wjkgp#cE?D`g>8T{C4U`uy^!?%*lHMxnGxzZ zqe%aKCjJ<XtJO@O!JitAo?Ka#v#yS)rxEdSdx%hDd?)JhX@0}z!)Y#3Og)Dvj#L>h z`(f{B#H%1fg2`(E?Ba0|85-wvP{7?bzN1mq>&;tr5O>?9=xmA$AoG0uM$9E39c6-9 z2e$x5nN+R=f(w2uiqgf$^?<Fd9{MdM1ZswOnaE6IQyXhl6X7iYo(@HcF;oVPa_Kn~ z^|nX1lO+v#+Gg$-(mlUD@HL?x<VXDzyP=#tcJo_Ov1Hz!jfoSN@4Ha)*~a&4%Sj!} z>~1-8A@jnS%OKLW>`C~P(olNDZJhVji@Wrb;LcC%VwoM@H2RerEeBsUEi#pgy0!k* z<GY*YF`c#(l?$%DC37ts2+of!jak-YfVc^)%`cfyx3O6EPcvAY-cP))XYapx#A^I@ zXRh3trVoMfs0r4cKwkOe-w#_nI%2CmHsdwN&fHEmI)W=W`NK$*s>B2eqgeU-I=GI? zTBB=w2imT7V26u{g!~h*EA^e1<3(cv+$NXycj}1ny=0mJkzCzBYBtDmQmPZ0Wz$5w z17oo9)N!4fa0Pb+1U1#?DZvfa+ag*|CcW^FiR^OL)HCt2-$r<UT#a>ptJ>^douDVF zN&s5Hw6x59WTmE|>K34@a8yMuf7>zgi!EEvC>g4hw)WX}T|V-ok_C5E``?xpcQ+ZO zAI6aAwi|ss4Ck|K#f5g9#1-Q=AJpn4474Bp%&lecFh6cms<xk;emC*HAUgEp?alX? zy)RL)sUIOo#$dGnchBZS`L^DU?%4PDV*dK;W`@8clW1>2#74XW&4~N8MNHE|GKA8i zUXf0xq7*O2I#^pzIj@{73AwH))iyitfiRvLMuP)=Sr^a3!MZhS4>WqPhCU@NcruGx zKrmdVwPKT$0DH1oxUVRIu`vUB9S*|1S-+*A*-5nE{`Sli(z#GI-MneW!E8QV2nhCu z*1##^W}Q+ocQ<$>RR9KoO{?nEnWLNsAUq5@EWo${j;zz>62$O4?x}(?iBFjaTqfW9 zUoB&bh*ea%b|D;}5W|&`Bzc-?gPqS#ffPmOJS_z>A;!eU1`pLlq8!1NGzmq2>B3s0 z2}C@0CP10;0ViZjlYn_!{q;g2*@hWPSCzFkq|b=T=LANm4cT{?#-Kf*>EgPr{N!(* zx?FY`10id?Va7l0MaH4Z@dwI8Z{3oZS?WzYH9A=ln8J_#x|?Iomhv#v&W*K0&OJFK z!Sfl+V-KNrpb%QKAO2bKqEys}lmW8T>b<l-G_ac2SW;YO^L{)pAJ|3BJq@sQl7woq z9sRWrk}TG#DbOt<UgKGHG#>EES*jPfeId}BfjE*T0pX4yLlY-C!faipz>}ttn*?Qu zsSt0BaWxY`WVG5-68RhWQbG7W5Ux`MN|2cXaWh2OseTsPl|-YI8QLS{R1hAtE$AIf z2~hI37UC5aw{XG1tBnVpi(m%zm$o=LL8fUXLq?fljM0U?DHrOhCR0!?6I-}x>Ju%7 z5oX9_4T=STg&SH)42C%x12QiNUx6&5!NFWc=!5|}wC*5PMg;kNnFJZVLp_9`-Hvg% z5peN*prUi2+D^h1JqZ*TA55HKN&^(JR59Rz{Z!2r@_V$C@WKtZU<_^#Jr2}@^g#hw zYM&|}sRPw6*)r@0AWw)Vo`r5d9Pa~^lO`~>#I)9uIOFos+M+b5#4hLvuaUUy`S&gB zMz0H9uV7y?>WGb;r@`$P1(FTD93bZ`J$eGNHV_<c;60G@%){beW2!|QI(Iw;-y7FW zT3uW&MB6a4!d*1;)CR(gfH~R#NHd35*en%bas<f*f^OZXobF4$a5~<Cd1LUtnN4O4 zmg*Jcn}9h6c8?S+j9Pm?2vAjJE!>%Dknr8rh=0DrWnda?wg;_Cq(J}I__lY&pCa@9 zH(BIz`-$UU<q7Mp_CU>DWE9@s8vRs6V12}*Z5hSZ)s)m;rjQnoQPvBMOQJQ;ojjsT z?DnAp2SO#k<^r`&1Od%IY>7Thwxlg?mHR1ED>+!Zynq6<D-uxYdMQp;W^jl_{;K&7 z)?E`x?|INDDE|e#qvu5HzgsXRUa_xVf&&QCMk7qICm|_?8%FZ>ua*w~b?XUnh<f`n zh9vBCZEP?&uZq%N1l+E<xR$9qjQ1g6C6AIs<ZXhW7EBGt^M;ee`y|@?x@r9vbaoi2 z|7|A1rt5!uACQwAEK1+`gwf-Sc9UN$-b1_yK{*(3IJ@reyhE$Z#hH{<vB<~JK4`Kn zvcAM7#?IsqVD~<egr*%ohh5f|2tO1sfm2luXW5li>5Yvx)@YH4L{?N_V=YdQe}wNQ zDzRj*;k!z%NRBrqHxx!5{iet6%1|l94eLy?lzD|^hsQRMmu&4!QKxiYisZviK!e-o zW@SQVtCB3%kFGTmtqCtC;tQpw?>0#d_r8Yg%P46hcAbmbV=T%rGTEhoK?YPu3RD%P zx)1GXi@2%NlaianoNE=@U50Vk56V{^PZ~!a?YX~TQ3}}ow{QZ}!rN_z*KV!Gi^2g| zq166(V;SRD?&c&#e6Zn`l=@Q7TS={vLJ^P|S+}qlRF~p7Ic=wRXHF6Iuq%DsW49pZ zlfHSAj)51@3)rdE4X}?{A_(p9+=6m%-I|I{@6C&^fR_~kFl2=9EBbZT;0y}aly~p- z*ZkG3IjUE4$yh-4rcM_9kK-~R`MUqe3su*)$MkZ`3z;4}3mLMNa%iK2okq^r^AAIn z(Rl+&VhDU{x>E4X<f1!WFWT?jf22x&CpP^{pxzGkKl*fNAd_K~R_l-U^&^imRVTCP zANljKd9J9?xs;O~h>im7CGtST>m`#%qxbx)W%3P^N*R4@-#d69=!QxPJBsP?K9ese z6Qy@PriY_hA?t&?I}aJj&m_vD9}1rTtHm4{Kb!u=r>i^n!TMuJ*nJTljoak)cdUQn z_P=c#JHM}8?Sh_wqxcyX2KK7oMtuKxPh)5&zla~=Ooi<7k?7BS7IWN9z-+r}nu#HP zKda$#g=N>_cz4B@WKcts4cMFuymlb(ZRpTAU7vj+Ekj*Sx-zylXW9qL@{UL8M}B=! zBF9QCygl=xvCeGlZ7tdBTEpPK6J<u+i8WgIlB}6LKy7LuS<64BKMpV+@JZy%<!KqT zCba;;qx~Ne$z4(yPD4x(X~*y%?t<x*c@zhe024$UaEif>;>7c8pf81;@xNL|kmD%+ zy-u2!OXj9Kycd}APouaSDD@<GYsx_X*qz;I-4N~i_^EXo=m4TUKf7@6U+?J++2|BN zY=jyTh@;5nX>{vkFs_(uXIt=3&(>Rh(IO{K%MnfoEH1!HOyJ%@Zq($(S%ui%sk-5n zst&f=dgn9{teZ%w{UgKJkXd`$H1EgR$OZG5X7gw5+?YHe-!^7|NpMDo12UGVGx9uv zdyWOTnq2-+iz@wk)OtjlWR#2sMWUVn;MIVd4h<;#=ecy+YAhTAf8<l)lN;_Qjo+2G zl<eHr4@e3Nzvlorf_5OaAYXyXXNNiv1m+$HCp5Rj3duyCvwZvKi$2A(LKj0wnGJ5g zAtU*`>GBS;=>n>WiG>St1DJbF%0y3i3}8*0?)1r2IU1M<I_zSK$&9|ko{U_bfJ*^? z%B_@?rn$)zf^i7lV9`WW+>sw}8R#Dh0AwTzi@s)*0i0*>xv{Ua%|crc%Hm_jX%0CH z^E5ew?E2|MYq@?I7ot~~eWDFV*uhF%)3d_)ED{S@Gc5z;!!I#5Bog94z!jq1fHR&J z-ysD+A`BeyM%we53e6!`{G25JbFhB`BM;2xpHDy^4jvAw9cV7G>%c;l__`9QK0K+@ zc^cCTN=*U}^4A3VpG^J<DmX2Z5a=Tkf+#;MTc0E&4iuSskuC96u{%a{if@lFX$Ss_ zA%sq+LY)l6q|@)uGZ1NjYk>TM`{4)Wr3u0G4;q<hV~UI{O$eBl$~~t4<_aP(CfPuB zT|r-(GGi%tcJN{PlXTQDc(5flEbBzZCZKTBGsv!;z;qz2B!M9wuxw!%G|44JK&AN_ z!{AbKWug_0FWJPfkHL$FA%*#aG1Iss!&94NBRKu>8Qo8*sb2<uV|d${(goGNAxS=i zOsHQ2Bpx`t9GBMO#!2tl=0uS#=f~B@3TpD1e#bO~WO#`;*mDKF3dAN4ton{E#P5ot zP*5t2S}c2u;ZA3)@r_YsD4E{kJtRl)9W}X$k8^w6mTh7QgG9{XF{dQQslonn!M%u_ zVajHl987WKfM2kquI`xy17FMt@%yhwO3%GsF9AUveJdq>=Xnosew#WwwDWT+Z=5^z zMm~rmmc|)<Y-g!QmgxV*#W%244S6%7q$mxcJA%5~+WvA>i8G?EQixZJv18hG;`8r! z;y2=pvJ|~WsYY^?QZ&gk+;WY-1rGO$Wq|Dx5kqp&D_-OpGAJL=#ZSnVZ#i+~LWFCY zD@utpTryrM7>UWRha@mT1!n{HJ51#lRMn!@25p9q;>l+aDAf=F#>hvuWj^P8b961* zD<OO;Q6(|yL)g7QoAwa)N=>hs<{8Gm@Pw>WRziFxbyu_TgNCmKH3>|##&wVo#c~eo zb!r4hf{<82Eu@BaD@O5+>8pmJXp39%6jD@zTWW(7{9ninJ_4%~-jEkQnkb7x#*Arf z7_TN@9L@a>m%z1eoKf15fr5@`2!gvf`CqqHYNEsq%bH~DXVqmP%F&{+4YnaX0(YXx z8r3Vhn4iO^2S<#GU$QGBj`(`_a4L=2^as_$V_&^tlOY^Cvj1gf`xAX52t%AKg!<!= zG4AHGgc_59y~^d?hy%bo1T)R7JWt4hpNs@fxJowyuJh*UE~!Q-I^unnw0cN7x7g3T zYc}t;BsVJyh>Kn#cAe2;p@wfX4c?Tk@kj?c3kDBl>Y0}1#_Oru{BGXs#LSm^;c+q= z?JCYV1>zhT9gX5`OERyg*xj5pe)8_?Z=Tkgg@zBjUL+ia&e#V|F<*bG-*`WCA9|>Q zTQRcHId|w^-ssYjeG%CAA|);PF3LYs&V&TdJar=MAK{Dd?sd)2g{gw;*rg~S2A4AF zkXJxE0p`?-17{}EPSjt>6jk)8O$8qRbCq3P+QpjIMWbU*UV)nKc8ISGL1B{=z~k|H zxi?f(+eR*=iB{%BKt8L+VA;i<xJ#y)x@8w@zm0F4vf)vyg@4J%9{GW=*eRO63G^00 zlIBN^ALhL)bEGdNi$Wn}*T;FEzS!4Z-t-fWNt3Ij;NaQ+vK|U4N}KjtlYzjXwyV?% zvh$q^!Ile8KJ`A6Jj<1`@p}(Vbp9IAIXm@3^-snRfGC#NuAUT6n+@#xifvP~rf0uj z7_tMlefI6Pthmqr6uT;Rq8nSK3fLdef6cE3J2u9SYY6B={b|^qsY}tVK=islCDT6@ zPvW`rIvh}6WBTOsSfMo!^QusFX~G{q1GohcjD=3mf5D9i$_&PWPYhV?94|H|G2Kr* z#Cx-o8?r8kVoKim6jw@wLlK3riVuG>A9DcGwzh9gTq4Kr7tj-oHS1?SID#0<n;?Rn z&PeGA$AcZ2rhGQlRdPHQj=R|U0l}NkG2XFGyP(CQ%V~RTB*P_=;O%=oJ$+0BJzm>p z848T&)k*RW>S1%7V&<6PK5Mdnq-9;J;I8LPZ?yjmR+b(HkB%xUbLHnHv(QQ-0TJa> zY*riGj^WC{T*;bqgrbb|_1f=WdlD`8*5<p@STM{O;DGkviZYIk37M<xREMd2d<USu zDD*qUswN=+?Pc+E)k8-s!JAqIq?bAL7()F8r<QOXb`#R6uLjhaALYBo@|WVNFceUi z|L0{6Bb{kzpbt2`p$UNvg>?eqK@&`|#sMoCl9Hpe3jT3Sh9ePu`v29!*|q`{fpl1A zS{um-1v}&HMP%iS5kvnE`C{k-hW}4cp2$hGkTEY-!jP5EXVO7ayVXAzTz?RLLNa>r z*b|`yBnL{7gqcBm$0m&1v|RfIBJYje!+f$30m_6f6A%L?z!lgjnZYX~Fm@b!%xBUv zu%*<pb(JFEd5Nz9>o_h)TtEbe$Zat0Y$8I?0Jcj1^J$U_s<R+C-)#~^X3D~GY|ylr z+8mHmC^Cc;je>?txY$@rAA+EO&Zq7HEe>8RC{vm`MP{g1{)Z!IMg1OuFK`?W1cA{P zP)CRp251p==U^%jzpL|cG;HmOa^pB;|7HTfq0u9YfM~vXhBxr!7Bh1cDH;->st52! zBx1Dnm9+ZIR7ifH3SNz~a=Z~5xMXwR+uf?>q?@g3f_^Qi&In<Ev60B9ybf@W1zP+n zSYRY6$1wuI!vPLXBiojHgba{DfnX=8hp~cP&F3M*oWgU%L1()o7y}HCVUVOighkrt z%@DVkaezF2tUQ1SNN&isTg%u$&v3tJ_&;^H^lsD&I66GC6>qWU?oPzciXy^qN{d7* zwFR1%5b^FJ+Pk;<5NlHA{=|<Z?rkLQ&``kR`FVO0{u~M}d@e*BA{oHSVS3+@tz4YI zRBk0Enhhl2y~fyY*Tl4ae{ImBM_sB_+}XW?JGy`S-T9yyk1ImW_PyxOWTY=f;ZV}K z)(*PsB%0!>^!=DzhwnyaLH_=QLy@oebZcx?$aL5j_BDF%e+7vQY$oL>FW5g}J;}?Q zTTo4DRL}?Wr|jGnXJ1~moihvv-Lc0-wHew;3jR)f2!h2m`<DXr$v|kJU|LBQG~h%* zzXT4hu~)8V3K%!J97X5^05WaNu}S>m{BZmrulH(kzZGp#*#LFzUaSD{y?1~m=Mo<T z3V!kP?8@BT0iiq~n`*JO29vi}wTj#s@oGToE2aFua}(&(iY<f&hhZ?@^j-CWpI!$v zW~>asFX|P8q3L+!`1_k9|7u-Hq6rnfJFj7;2)9u@=;^9Lf^sVb_B*{i(ZAU?C{wLR z@2yD<uo>=};O|rrg%yk($V5L|{ss?Lq(M^cV6I#&QvOB6P2-2MBmH=`=PS=HUlU5J zlsunS;7;%G^eB6Wkc`<&;|O8}y36sV$$_&M;xutxeJ%T&l*6BW_f^M{ilcO3&&OMa ze3O;F^4IH8nuu4lS&#iG0=!Ov01@FP=bXOq%c5VtKviXhyXG4Z$(GpeGYO^=-6i6i zf<J?lVru^(qs!P#BJvCa6I#$>c?_$U<)K9UqTSP(%J&@Z*#a(4Ry0-Kzt58IrVSAS zQNdHE_l9u27q~#R0}dQh7`<i9JcTy^xXf&Oy-F(&caUu|cPFl3d9;O;Uoz*iO_MZ6 zWh<7sftBDiHT|YwFf}^wmloR32W||SDQ~Ht3}wbrAo6m7(-k$|dop%M_GFQ0P;Jt7 zHEJgyVn&AXBZRW0_*$neD)aNn<f}2(Q{UZQrasEV!%sU;ASo~H>%D|`+;bKli2n=Z ze{y_<QCD*&6XMn)XebZVuAK~?-sfB-(kVD?MNJr1bFS`Dy(B+3_1(SN@0w#>l5YP# zW*CNY&_9*d*_g*lzdYy}mwf*z%DDL82$LlrA}{>Hhl@0V;7XZehbKy&=jQ1Ff26)k ziqn0L<H0scEeWna<QKq8akPqm<Y+R|eX%KDWOA{X&|Wy8HR1@Tj<D|AoUk80W>b)$ z{)Z6Z+Y!II)GvHxe^kD$>m4=6JA^i^*Ni=Unr56oS-n}nY_F&r8Z?JGk2G&Vebfeq zH1<4VN_a<W*J4gk9P8eyroxyb^g##nVMM0gzKz%Y*mP2MwdcS7-Olv6d+|IVcYJ{X zuMIHtBB&pI@I^K6TyLH&xYAxMIb1$)ES&rS*F_zT5n4#P7hGqEvlN6@ahH)*QLQu3 zr&3wdip|dJ44L!<pd^SyJei}HE+EIm#x{{!_yyD0h6u{CQ$D{7tZipAwgko!&9PcA zI~EQiBytv&JAv4B+2XnPtbQK$?Mt^F`z0risr+*BlNq%FGB$Rj<{bok2LKInV6)#i zX4IaBn4-QM`*9>I<W)q%18!UJx1KYhiHW&16+WdOn@jYt*8t~LDj03Td=3&D*j18` zr>j;KLV(0TjJ<RQbo9wW+iAhrdRlcEDTk_N_l%WIPI0TYQ?vA4Cj-r=wxIcB8tD;- z#mAMyb45l+x?e%53)|RF{?(E{{#*Se9I@D-!nG-m%5)!o!M=c_m_a>iiu5=BxTq(e zHEfzt_Dt2Jw%bZ)12)0|WMgYJMS}oxJHMVco)U(8i}CyvA1E>C_`~gqwCm2menGX8 zR)vv3CAH|*e0nqv5%CMdsUv$Wf^#xYZiEdOT-nJQnBE2;7*ZtNItMys(DKF<05CyB zMR_x!&>@Ko0MR%Dl^L}9Q8!d!!j4mm|LdCxFcK~!-XE=84mLzB%KGCZDK)_$K`YZg zG6ky#Hz5|<i@kxig90i^D{g4x39TDbYFh&DM(QrX0grV3-wNSxsKsUe4D$%cZQvCG zXuBH$Dam3c8(S#sM7Bh1InTUCM{M5bgZb()GGhj21>1bFC2J}a*!mz`4I!vo+v6P} zL<#VvOdyV;#R69h(|)KB3%Y?tC>}*w(g#yZ=tqJkho5C40oMQujG~3W2R{RulBgN| ztM!vN$>@L;qM#sJmKb3RR7!vWHwx2T03;{6WY7tq_Y0sMBjuiYGfD+{j7wN?UNE17 zJQnmQ->AA-76y2s;hUXG>XTEzrOhzX>|T96858}j&n;$P=j4ex6w)}PE`j1%lTBkb zB#*(HC-+_}1iPrqBzgg=ss*gVC}d(XyqR#!oPm|na=uqD)QZ4vV`D*5hoeihi!9M% zj7NUqNFV<hMA7aRvZmi&Cn>;<&n+xovO+W=>koS_YvkQqhdQxQAT7JNKouOf;)4mx z=ASZraq1{al@9y*n%n>MUvH~;ZVG%OqT?7ySU2Rouv)?JtFqln2-5~0y5V8^WS6?N z*pm?s_+o~Mf~+$a{@^veOg(()0HTzgg`gqR6<47^V(zN1X9()J9;jUKNtSx!i*W-T z_zX1%K5&B_KSf;kcBO$GMMud~ACx3sN`x@+prNr=GCWu@>c}A!ZdgK0x_-^&5M-e{ z;B18-pAPt%t`q}&kZwLPaDs>THW9J?Z%(fg%IZZg0vPIA%q|7#sB?=yUID!XIDEX> zx$%Kbe$z(+9*CE+HMLPGDISWTIfBs!XRN8Ac-KLm3YAFl71KXK%fs9qam2UD<ZT&5 z#&E~`1sU!{#ub=xd>ntv>t8|<F_l$8a&`ophxJ4xu-`LtKg19B;s?piEyM((TR3cv zhl)+p?Quj-vWUwU3@Dpyi^X#=LAj18b6^Il!GgzCr~eU8Hzd->f>HwkDjOv#4stW< z-b_ZuR~W>RV=BwDb%D3EE-_SSpbxih|9NZo{X{&%7&YGh4>qSen*H|+La;)3x}qyA zHwlqDp*C#t_t^AZ%c_B`?(ZHhy<jr&XHo20JGSL)YEDDxkPrW@`dXrCb|P#-Jpb^9 z?$vY^R2gSs+6P)DNt+n_vf~40RZ^y^_OuE_OrORDP`CH#PjwC-5i>G?ZYPVcIls^I zMi<8VW;>lrSe}-Cb_wqggfWckGzq52EKkory_{B$F#$)WV<7fKNSXPd4`+tnd$Ggk zjgTVS^?7SfbxT-pMJAr#e+9jbrH(+#Si1HWc3Y@EpERHL>Z|>x;<!h92=^X7>WQpN zf@)3*fQGV6^m1{(RS-9ZieeP8i#NGK7WVw+$7`I=MXEFJ5~bA@cnAv)iF;i67}6p> z49Ua8pCvN>oIcXAJyRe2ko29~{$6`QgSXw`4=lj1<`3<+L{GVY2mtu~LvmyB{0ZOr zHn1?SN2h&{zv<B-=jxUag6Bb;8m>}^B&_!h*-EGBU3vM8kH-5|K}mQ>b~4!|%KgI^ z?$d*W=ob2OfyXJ2WxTl}O>U|HAwsq4>dZBZ=wH*qKlJ*2aLjYa&-=+CR|AK{oqv&9 z$25+=8Y6rAcd}$N<*)tQOu*Q?h4Yn$U;Yx?1PSAPb#ct+%;6Gx%UIJYX(s9Ny6S5W z^tuP-#=fOS*58IzAt*--cvb-$+rQ;o#24l!EkM#iFZRNKl%f7@^Cs<QoFS4C*&k2y zpfLqc-8o2#!<J0PZbL*GRYg`78q`N)kR<DbF3aM6#3bOcT5w8;o(dF2$LfQ03>me& z@zgIp=bQ4efcG3L{SLBgMk&8sDLhpUSepgj3%3WnJUFdq2G8@KnX$<cvHVBdb7=md zMuRZ1Qkr-0Q>m&GSM?m_HH1Xj;h6d2@A-e~s(*6>Zeqagw4J3^T6PXPj>3H<GrS;C zjf0H6{moppe2T7`S+yN32Vh#zNsz^3lYLJK=!7fsNNk<arL+ySog!i88aljl?|OLC z5yKh40spGB<<kdws39O@YJDv>fTH{X%@!=}LR9tDru)C@lK;c%Y^z=<g(;D=2=X2N z7$Li5ijXK@pyism{v^k`1g`glXC=wOpZYojvLzgkqQbHPeoRSt-AN#%L%?9Erw%R= zW_g73im;9*XCkSY;eJF53wz;I2wH1!=E%RNK_$KdUZia7OlXAJj~6DIK%Yovg)zl- z4C~Zt2GElX@DmYwPZO~eJ_suTWUNWn#n26a1qQAM1vz?^D8O$uN`+uIp&Ae<4<Q*b z)FoT^46>sDwi+E}u^}O1%`h5KM3AYg7~>7#>03#Wm_6`H&j{1fwkJA);~Z6~0K{aM zq~W|QU7U9ZVop^LhycVWNE?A}f_`vJi)pT^C=e6%On66Oz=XmE_DX8a2ELx_it;3i z#;GRw%b9xABiMgpCC-5o`7nkaiVzP>uZz({Bl|fpaA$tP*KCU+Hgv9VI9P=hZ6BU3 z_Txld6|_+ZUuFVZl7nQH3&S25!)Cc6YgUrd1I)T^p!@w12JEwz=D~sqcM|Jp<*hy~ zjQbDsbGX>LQ=t}vvV(!(hiO8(3*K6w*Og*ZZZ_5vY$oHIIaIJv0F%otnsF@_i+FG5 zXp6-R%+Ya&j5ov88E|SMl?wDJ(?Tn$uK=bkE%awueiIaM3sP9#U_%~<WrQXB569V4 zC*K5@gil)QVG*_i*`;Qb-ZULGI*&3S8yG&`ZtFMcC~8zeDiozUOW5P<5Iywl;KUCf zKXY@%Y+AFfg@yrUZ6Q;)WEYZEma+zrL;{Dv!fo}#6NGqy1a}An{J+X?H2AQS;1Lgo zb|A5*!UP{!?}2`3<j9-zca0e39p=*5M``F<w-h`bBzjuW6jVw(%=RkO?wC*DzX=h5 z?S<0nHHO$PpnLY9_=3^cRNQS)<rblm0tl>)^&WFTHt;B@UNeIu*Fl7l%=fK}T$6Z; z(CMo9M^Ub^@5MY1@&Uw*aID#_EPQv@-Dr(P$5l4!DvaMCbp<ueQ6dX#J_LJ<!qnLj zeZI7_l`F$=YSg5*@UT2_e%}{Rk4+LAhY=cDCjpg0q>s-;$`U<uiEZo=R;;m53dbOu zlNn&6q@sVM9`C*STrw)*skfuF@K-}=G3R|b6n5B}by^F(GmjqB-fWX`_*)p>VRtaP z*1I+j(~8VkGRW%A3%o`29DJ_<?9o{J<SO~HDy6(n^*+AsL4(PIo&BZ)427<jU7&?) zhfiL>%R$Dw!&N;OKK9d+ghWiH_F!8O|7bt9QG9ml%M(5W!Je1Rr|!AS`{j6}QK{ZG zJ&T>K1v(!12ObNa$KR5=u^gUkQPh+zqdI?V2^<*kvrM?Zg}KQjU?z}HJfh(bT>^m! zEz%BzTuz3&-d@D@1cBKSQxvOel|l29?OvPa&Hag1?{^0NiV>brE&xy(nra+yS*joq z<1}};@J$teq2<+iGlsgfp@wa>|Lw0GNI8^`bH$VlRJM*lp`v(SF~s_vz9`b>%n?7< zPt<T6lZMTKt9sp(SGY{m()4>K)~z)w;*3?lgRO|8z;%1PrNb$`CjJ)WuH$13IWJww zojlOLYYBKO2r?b^lLc?|2Y>2igym0O8%D1qyvbCTBiZD|{hBk7cHur{e?{`(d^rP# zW*IxC{&f4?JlK&Jinv>fQ-|2lAj@2s`6=;FtD_cA{W_L*ofNn-)7s-(cnz3zT9*D8 zYc+EHqen%1d`EH2{sv^>pbKF{90lMX6b7Z7DeKy`BkPWbDOVJ-LOI&!Q8F~Rsgl}h zE6j&Y^ljZn!cGV3R0N*d7U9g%J{TbCVZ$qL`u^3W3J;0(uT2dhV1(mf>=KWh`54z8 zzo?T9RgZs|w2I92Y889+2c|9}`*eLy#BoHPLMl(14J#15iCQ-3u&0Td6GAZ}KTZ@t z#1PQU$xhItUcvsfft!<ccs69tpgyYe5bNk1brnEfz_~bWhdp?+Tbyk|LZa#AK7il7 zNVh&+U#ydGdac){`q{XbRY80oNg>GujH&uPPo4B}uCk9UAf1z-I(KwA56*$0BBD&m z+irj`rl-Dk0&(lQ`hxdgvv93B4VRJXz04M9alvXHSl`G0Q)ix+)BN`w$pCIK@{sS> z`Qq+QT)fqaGO%PryPIzr3-4{0s9*6g{*_?HbWyU9ri$QnDx$*Pz88$FCu769D4;(0 z4iOwhulK$m$;?cJr{>$;isy%>53+L`jR<H9>}#-rHQ=r5dr%}scenX}z6&9c>=jIa zH9~BXo8c6sD3&0q$nuy;J`Kqs5CuUZBs8}cxAJcBe-H+9k{e)&E+HzI*+@rhl4o%g zF&eHSfe)gcFs!VEe0C(>9Z&;^K-qMrKY=jguaZ@`7?N=yo+l-OFirSbM7MG;F+fK$ zV8}oKW5e~(h(kw@hOUL5^IRi}yb9Xe2Jk?@9daN@cCk0U4&EAwQ&Wqsp(X9yc?q6w zXbWRe1)#NQg85On*a$YLfD{EYbTjZRiU}pf*GYHk)_^O41)#(2-HNp(!RKL@u^YK; zK$y`3K07`|qy7%K9?(hnl6~Y+*N_QlHh^6O2R$AS7|19FA_T<*HVv?JPqoPe9Dy~! z0`EgR1LuUL*qefF2$Z~m(g0Q%`j|)iX5K%)m5rd%mEQ9`?kOn{XBY{fp^jDOQ{;Et zVpBw+9(F3R-1EfVK4lCc5MuyMB11>B5+w~bAhb$??OToQJHVCtgqjUCO(ZSN*EB>V zbMJ!y6W1Pg8WGq@g<t^zUiW$+Q5*9zkpi1+h+w}qp9Wc#>8i5D<h8=UB~pu{vlu8A zCiUU~_%Tv^Hm3VT@C_me!G=htMDZ3_1TN%yLF<5r6UM{X699B7%?we)>KI00!RG1S z-{aC<$L8*)D^D`g5q=|Y(6T9b5=0LQY`jS9ft&cmx&_z*rssExltc4z3X@tSR{&dJ z8hg&Y3t+=k@mrfIn}k8^P@CXKGpchoyav>52H}4P{@fS8Q2p@3qg=ETZ@Bi-vhQLy zJ)}K2^OaH|CHNE8K6oJt2~pf*McNJ9_@VFCD^bm>OaK1qwER<?T!HG4T-H>$6&H2m z(Eh~+ie%JFMhMw0#AgV&b*R6$$F+1qSS=`=6vYVxQ%5;M3_RKtse&7Up}H&9Ky^ki zeh=v0aP>RV{R-oQga6gq%hU!xXjDXgSp;t|2GbgH_D7r3ZzlSmy}(*Z$EFkEvs(bi z3Qi3G9vU^Lzj@vP0e(!d93bNAi*um9+RU=9_=tMoPk;VGLa-z!QmtZu=Ov?w@f~s_ zpMMVTyPwa~;Z+uoMfX*Q+>q97{LVQj)-iri5$66B7#bk%g_~nyhhZdO2@1pi#=SjB zjuR@*SE)Yg?VOi*Fi>}#??{iP{HwLNaM2I=I=(m^m=VV3t0yeJAOIV(A@Rk+?@A}2 zb@&4LcoIF^((#)x5hBc22g~1EyQ+b)*~)l5>(q#9;#nlSt3eH1+2}9BJ<LEx>;_)b z2f*p&&4>Ubdnz76crKvAbm-Z`d})M_d7%Ub-*WIE2UacIG;gA?XPI=h!XlfA0nrkE z4u<QX3%4L5r$ts^DVUS1ePbSoMrO1ABI{5cea2MP%(s-G{xLFG*R~l!)9iQpw^wj0 zpB}5o44x4I3a|w{j<i$i<GzK}5$2A>uK-<@g$3UZ*6Ko3<K@QM`om^SoO~$STCBXS z(<0iX_@Mjo&sO!~Kt?FXT#zk>yiNp1S9PfDQY?z(ZEpk(g(+LGo4<EQFpox;Oz&im z6>Bywm^!T}9;M#k+biS1+&)uQV;5)Kc>*YW+ypSPr+wdW29rLibok@UyQZacDwVgE z)RO58u@DeO@yyLL40+#vJbdvTBqu?hOXY0+pj^~lmZ3Y;TlzKC!>xTzH52bDFrF(m zGCK;&FE(60`tmEe(MRE12(%vEd<%IU@zjpawO1^VoP3`g7OwO9>RTM|Y4KPWc|m@W zjm@4@%ra1fL$5X!^?*UL2cNkFgHUkA@xZrPwC+{zYp2npFL$zZUK#Eb8(pMwS#L@* zOv_rr&U9U`{e5IZI~(eY_xzAWI{wv~g_jDpIe~LxJtkL`D(P(@WKu8Tsr*N<`G@kx z)`$Kg_rPzvaSM2$?@AMZtAfSh*8iYl^TGjxS%6#c_A6Jk@*NzR7I+t&{sXYC52CRz zqDYe)HR}^hsvQjQ%5MEpH~TbFQfB1#8RYL>AQP)D1^dei{T)AJ?E<uyE?01HcX)^8 zMI@X;@?v58mXG#k`LRhTwp1cA;t#QY<Jv=jialNb^VBhldjVcBR21EL-wu?_a3K-E zZTZ;tnSYKc=xmqp;p{sGqK%{xTHnuepD8d(0j#x|s5>^_n*TmlcmoM5U`2^snTS{& zjo)3m;UT?CME>wPY7<;1Udqpf_$A9KHDXFT#0;JUtu-2L&q;mt_n%^dIyBI6f3Nb~ zZdW7~BC=Sz?~p%<M42MBstpMf<+`R@NR4l&OobrP;I&A(^N!P>XA*=lLgXX`wE{MK z3k|`Gvdm2q!OyE(Y-UIZT80JuEbeTu;j=I;1>EaBPlb5S<q-oS+Z^H}MdY@3z*{Yq zxD`+%yr_w0kUcX5J<9x5wxm&EF%w}tKNb8#d>c|p^n(HfX*P&Y%gIpXrJL5er&Nql z)fue^)B)I4V>yeyxfCo!7)|jLanteZkzsIik)lzoz&!;rVyHHT&9uyHKEw~5!&k(x zZwz;KLL=7oD}C@1(UP@VHl@X9(xc@BHJBO6hJL1788vk`(Ody;n4DXpQHH()tlk0u z)Sv<$fz6&4(%hH2!$2PKf+2Gipk=~<+^1&FfUnG~&B1pja3JTk3r%4-2<8{@8?=~n zBI!L`kX0h0n=@6PmJMZH+@7&uM!5Rg)nQT=;Rm-$xyKfQlnK6EN*Ctw1Q)js<Shjh zSTCOCLTMj5SU7g-0Ms1#_P`iH=ohFZu(^Tg*lR(irrl5+^kiSOfYPWF*PepPz|5d+ zZaCteE&6OzC>TO9KO4>A6K5*N%$Atcz-f`3GPKa=nJ%eRP6Uid=4ita?l{)jE@YXI zb<sHNw>=4x2Y$aC!d4atE%6E&Z*ZaV3TajW6d#aD=>KUlTJ#_nxd_}Zer+wYreV7@ z8ERVO-SJ=l`*fYL!9>oU{Xb-WS0}j-6d$ZGHyfF3=T`n|1k9$gg1=r?2wZyvK>Ko; zmEF}iCoU5!H!>0ZoAWB4sU2p7wQoU^Aq&6p*cQXp2i2po_}4(;%e#I`vMQopY?%mC ze(8KwatjbL{3Bu1WocZR9yZXx#Rvw}y}-%lG*!qQW29V;jb^{%_P8Up`%2@*b4y<{ zX<|c<M4ZQx>2uboj2iJ1%H35^mKDh8vI6x+bS$YGHU}zD1^l=0;m*{?#y`id3goW= zt=Htjgkom?Bcs;@eYjF~z%CGPPbR29IhXcSfjo$pmj<jxu;uFRXQgbTwzk_KJ4ite zx}NX);;ez<l;*T;Yis2YAR9LSUG>KsVAKhsi~Xs$Zz;!wd%NzRUASgBilsF0NO9;{ zLteV4k}z_qxro>2QkW~5M<6G6`pP-~=P%KqF_-DibKGH-%lbA+byK@b-Vy?w#XFy% z)*KK-f;c$qX{kqKZV53sQ`m4}<G$V3&!J#Q$-`^dfwJGDsQkJ9tMyH1qPv2?@C*m0 zuoKPyuFuSyc4Z)TziS$P#XiqDgt{psV{J#?#>x1QH5+alg0@2@7ueb#Zz#PtM~4n& z4v~8@WF~YzB|DZN44^DoP!s%O9(}3`;T?k|enCn!@;zKBf#n=XxPyOZQAkejZ(n#~ z*9{p=OFu2V>i8GN2nN5sf;-ND-<f~4oU)va4YwpcHPbl(7y|3#^1TIkG11WFG-jXH zGA%Y}S&l<b)@3;j*~d)ADI?9$Eh6O6nK4qd-*RfvMaW<RkDzm?uj#n(#<J=+cFnJc zID=N})N$rWPbe5_yFcjP57UqJY*u&Vc8c(z8sM*-9X}*A%gJO-^#(A0Q*sI?ZMGlx zZaE-L7}6gPQ`L)}o0WS{@Y=UatIPRNy91mFz!I5~{*HblerO1Zaw;^?JXT*-RMBO` z(D|d9dU#Q~dgGBP<KW~FP3tP~x%7`Hpftw*yFMi{qwk+FFYg>SS@!h6Sm(ZGyEg)y zYZ9<t0dJStj-}2xVl+zL8*w`Ml`~NiGA$dk6|6^rT*|f5g15`fTPtiPGy3T@Nmyr{ zM^p0J_tAnEzof0I!PvSE`!r#2RN&{#{U}!1x+ChL+PKN5(-wWZ=*fdq?wsfL6{sJ1 z<6(ZI9J`i<hbR|c2c~=BPPh%JO=H)z)#yT2cAYndZF)4}gzOC8A$8lzKL{6_FuqBS z@xN%GVKsncxDm!W8mn?-Nl5jSWD8s`p3OeJu1!Zw=jLEx?$hso8EU=Z7>*-IfpLVj zCI9=Rr%Op|vMyWt%J5u@=h${&BfHEqHqG<b1@?e69`&)2UIziLuajn<{?QSyq?Ks_ zUKzZIPt8^w!!|S<JGLfOfp;|b%nUQwQKdk|{TTko2T0!qg++;;Rgg*<)p2*aa>ZGo zS&zJzfH(#5vKbwdpR*>fz?ZG~U#%~MQnP8HaL4OUk{dgIMbx><O5C}mHHWm>JASbF z^M&YZU6R}KSo<-(V@GYXLpvh1&wR*IB7r$9f5lix6e&krM{=Qo2(FIb7J?)6p+wdZ zZ)oL7G-LhLLafr!jvv!EZQwFZpdzSwt#Hpvpu=MbKspn9>Gh-{9=5<{*Nc{-MXbeP zm?H1P{dJ~Yq=S961;l1LaMmQ_p$i%ZJXn!xN(QGcz>Ia<qC&(~r$tUG#mLENNSM?0 zbdm!o8Ng5*fGzjJ6Yq~3nTX>tc#(?T3Ik*0UHHs4<OIXh0)X4BnTy<ZK;v5<I(1kc zL-Y`$ZkUMWjGDrqf;W+f%C|Th%Q0`Ll!K@YN&?<MuIBPHT(Bp`^+jn5YWSz5S-R?> zKQW$7ZosBDvSP*p(mh3@Kf*^rzC{Z*phKsia}Q)wuBIk}nCV0mkj~OVnh;Q7;P!I> zdxroF@)XAPz$;DFCr?6*6@@15NQ9?45Ud;+Vv|FY24<d^-j($UbPRwO34iLmj^qw8 z8e(7bE|`%?^Pxz3c?52_-eS0!V)8*I(c~s@A)Rjwkm6l$w!l1nla4l;R5Spx<s-Oj zY%%J#<^0$&aiz)dR45^4yQEZ{pyL-p3oRUwY2ex^VlR<T;|`Qq(^a%bW6Uicb&^8M z_5FmjRFIN$^zKuI8vI_~gg}U|_|b!xWXyLasdubt$hV%NH}>47COlt+ct&f=tS$MV zG>j`6(yUYgY6ttWULNi^zRRabaIY~mbekh8X<RqThD`ppcaJmK8m=*D_=TZ=#T5-` zsMm@RYJ^W|Ng%-Z@G8uic%o<FdNXP@3V<eTI|A`2T5Va2*a8~ap1BX)d_L@`gf_>j z*UT`=HyVbJef^rjk)@TNg$mmUoLw`;bzT|44k2uXh(dAE(s((MUxHKQMEo+qZn#XS z9FbHOVmWfQ)S5Y$fk{S&My(c{@1tc)Ij<QwGZ}4Xj`k^e<LW>%v(3TWx~7tfpT#4L z5B_y9l$ZL^5)W-9x*80t`qeJ!-V7|y@yy#WJd6y8AH-*1Y6K%wyZeqoNgWK@uRTn& zw$luH5;aNG6AN@>!}F~)9+>C2oZd^{PY>l1SjgW|)ODUa?_y3=AKQ5c3Cl4EDru1Z zv1Rb>x$ii(7#ZSIunhO=3_u+NK@R#5JIZ##DM1Fcd(BqaU$%B2<_+2r4Xj}J^ldcO zI72rq&$V@=W8Nf!c=S}2Q%u;y<-O{*1XO2O?#lav-c@rFYfaU!I?UztRxC5#y1lz? zx&Kw`KRJ|5=p|ad)yA-}t%X))sc@oIS&;u|`}}?cv<zTLs=S_;<;=t_8DQWryJsC< zitx0F+5Hp{0{}3lkvpw68AW<(-}rL#rdhYhRvO27*y0OziWd^?tXqT++Ixv2Z_X*) zJBP=2<2B}>F6Y1~_ynh#pO?*doB7t5>5jK>htqarWtAU_>&?y^CE2I?@PW>2^(-J& z0KKj`XNX*<QA)jqMRR#=W;39!v`VDW%&2km_Y>3GyC#30`fTz2b(H<hLC~mTquBXU zPAV$ez<mhcCbiaE?)+`~>&pXwn=EPhQHa$wU|CJ5IPvVGZtRcxNI~`P5dVw%F$e<f zc^^dE5}MWQp|R!kXc~lyfjx>Fe@i#sTf6?o&FbbTi(ZURfc2{>34Ubqhj(uFk>9VP zFk5b<4)}TU_`O~J;Z1w@&$g2$te1>Ji$~K{@9=APT!N7#R@kH;bDe%T|8LR7$(FYt z&%7(%d1}qowR+G#;5A{4;rkC~5k2_P{yU>h(LWibPr1hjLUIF8`@kzL{eSJJ)NpU{ zzKHqW^?eX`NZ%1aF>`?$iw$r~zb)CfUcmKvrufp^^`mbWeGz@nw7y|n*|rZ8Q#xJv zU=u)e)z3Q~m@ND7!_~L@`>ocj&>OUt;Qkv4?rx2G_1f{H$OfrDmro(n@wAk=yY(g6 z1vs6Pz&tfciY>STBP3jMsLi3AZmE@UE@di+zt#UD#u5ccE&13{0*0I7zmhW6e0tqe zck9J45zE_s5@i)(D6)op=v+bfQ>4zsTbP$1aK){R5Abq{^xCvSE3A;PZ}6}Sxb{Cf zUlTxqZ~1oOmsPmW(s~ACs-9RcwP>9j?g-JH5?bG?Q>zY>Mh-_Iymdxv%y;UI^OI0i z&~0z1&78ZtoXvK}_^LO41Ll;ff?E}s=%t9>CI{-3Os<`8bC*Isq~JyuH9mNwu_ztR zQ_#HZn8*a6s!7dm^G`m@cjMAKTe0`5zCu-4x+iJ|ln^Q#Kq(q+ydAC-d0Hk=v=G7t z@No{NO4F4VIDXxRoZ{6pNU9q)MH=pfb|+F18zo76AcRZM#{92u26-Bu@8hUDG-Ebp zCB65*ksKW@+ib}BH|Fss4z+07aG-6S4AetR2wqMMu*m$xePF#tkOOiHU~EIZLKX0B zGeplg>a$RZN7Mn`stFP>c(%y+v;oT<QaOmsM5-*Ald%<lY`c}DN)c9Re5N-CH35bq zE{M~_JB9qe7Jy=;M=pZ(VK5f81eunD#RF#*O71ZzfMYHMtPD8{@J7Vp(hTPjqmkVK z%Mw&$ughmmPk4z)rGardoed=tD6I2c)kn}n1g1L~fR;4X?~PG1q8!v}F{lyRx@qku zOu3PI4)SVS-nYui<rXu5-X<HO(`jK4TE&mm>s3+-KnE7$Y=Hxd3N<%`1PhCVOPhP3 zw=Fi$Ak&kss*rRR$+9?67%w2gZkBtaj7~^kg96($9qP$6N~OsefPAsgI&(czt>*DP zXAr|uH$W&bQ#eLF*Oz@d(-TE0Qbr%2XL|)WaCdw$Sc*=G5t%kY**j9_B;fJpL$cOb zy$^p#9;EdzYcfTb6v0$R)y2$x59(-YsBo{UTPPrB!e3cG^{`3u$?vA3{QkcI-=4lj zMzhiQ8(GtX$GKk?7GFPdcwkSg#iUQzTlR2o?Qs>lpn_q#+$_p4fT_v@x3DCG7PmKc z>qosI2~#SU?d$pUT~$(x+RwMiGSz%%=H=%NCcAw0Fu;Q1AY2a$UR`A#$j#KZ#<2lO zbK_-Tvp@)h80%>9g7)jk>nq7ggRpvI*^ymi>>s>q`0?-1Whg?G;cXVN=qO<+uDo8D z%h#-O*x0&ovrwpEtc3+I78LF|jkYydypp*4>k50PWVQgOT{*^^NX>}~Cw3NAka-FA zycJH3aK^{s2&P4y$j&QwIrPGOcx}7{To72D2-DOd;&4+;n@ziZATYK50)p;v;e(fh z>?9^FENpm2n@hK(94nMU`h|hwi2!wR9(Orx-X_;zVR19@h1%K%M;d?<BcmZe^+WCh z#esJRE$eo-6tk9%KOEkgyaPJ{jDOP?HS#f>@lP~Yt#%VqPeG}r48uXF=J3G3-co;& zcc<Z&@a0-4CxEq!Z{uNUx8@8JypTHlI<KZYXLvhHpnb~0z4WlmRWJU{^g-zG*s`Zq z6-oFuj#!KBAn(<~_C3tO5Mr*Dx=Xf^+XZV6ob3kt9;GvF%JCvq9)SM>xzojL-QsU( zd+xUje`?Jol~(CR+5D>mH=FnQdi!JV!n7<Hl0D~D9n@J&)EVTGtITptkMr3ngi(RY z9Jec)VL9hy22(lj1t;CzS`Rd`AE3r%d)}YxMyv7zeCQ-{d^VqHVPKT9<;FY+c6qZS zD?YyqxXwWT-Z@ELn>IV0x&oH4pYCod9yXGI7YwQlT0wwuhsP7_WQubdK@hb@xPs&{ z_V&aubVex1Y%Zy02#vVi9>|}DXkWN+y<?J$eyVRq=m?npUStIXFou&3?s*>H?f-bD zTA6mrssWm*M78s7hgWC+y3uE-%N!u%R=NSZp^4$U^q2N6{`?k?k&yIIQ&G37n$yLv z&AD-5j%-WjUG-C}|C7W<f_UM=!LZyLz?z|~!09tBi=8x>_TDd?J)D!k?rp8W<7oG5 zGS9&36m*K>l1i$3c5ZyCb0ISyTkew5YaRX-9V>st3=O=U*EPv^ICEpyjBIq{#x3yX zMg#F`6(m=VkpS2nFK@@YVw>8?_82_+&jG<mKY@StUy2!iz&gHY!TnBq*ERcD)`MW3 zR$(ZJHxiz<I7q^%L3`gsa2u@A+IbHg0kRBxXKWM|Av+nbUvAj_idD}#N4fs<jSuxq zYdp~CTm`J0Tch5sdLh>BQgz0Q_p6O>X12$y`HtgA_8aUTU$M}LzNdO~^-i=WdUvT2 zXxpx#MZpP*4_-VJws1LRHq+Q7AkxwF!#N^vlAAE3w}g*9XAfihuE6xIyX!|p;A5Ab zJl=rHz*`#|5~7O`Nkm)mOCleQ`!0Jkh9@74!Ho4hFE7veW?dVg%o3D}!|`qZ7zD@R z7^3|w4l-~lo}N<{*>u%H&sl4I`T)yuN%hsjD6t(QcX`IT*+dkSkQ8$o^BuHUMyQVh zE|rmiRDWLhc>rl%`-Wh%1>CO8Qme0KW%IIPT~%ah&O7&`)>(v^f#>9V&z61UKBY!3 zExq?HEF%j3^%_hx&Sb&<p?z!!CZTDP^0#~}hon^kq(YMMJ<?JSh$bQ!W=qyDG|dK% z2>WzL)_988!j^*G0UJRYhQh!uhl{<LlqM%#I9U^L(kkMs+|Kl7U!>LH;~8W=4FpRP zV+8&xZ?b0EVKWS!8QT(|F-bGKLJZ00Ql9lG46qCdlnUsew0yZ5s|v3t+N3|OY$mV2 zMu-yzEei>_i-U%<?wkc=E2T%YaDY!OkxM~zZsg*m!1UL1mUMJ3i6$k`T=NIY3(HFT zSalHE;44&KFP5WXuzUDkW@a|PEC(t=SdbUTMRh6&zzyNqf-!2Lg>+_*O*@d-BJ9hl zP>CT`KK`W#0m%yp;Xuz3g6bjIQbz#F0jRDyhUpNlx(;4=W4@niD$~wl<_+{_5nB^Y zi$=wScSsWh#Sd*6i26Fa7;eG%3(^2~mijimS+j@@HU0}7b@vxY`tX;=M2BF90Pt5L z^K)aM2?wMuq6oQ5n0a}697p8Kk1|g}3O|K^Bfw0yI%}nk@_Lavz{BGrT(Jh&ZdmsJ zNWgr;C^Lq9s}_(TykI75Gf@>-ER%-0MEnAU!jyTNNg)7|209yg|K272O5KmH<2*-o z%pg&N5u&B<$elEN_?eA|a3pwIEcFw2-=!!g_%+dtO!}Y&4LUp~LGX?Deel`FO;G=) zFk2#@zv0!nzIHWD?sa>6|NFq8zI^uK%kMVdX87?{y>jU&o=rsUrO7?-5^4K$?u`Dc zC3-=mkeCx_J~C6~|G|W&He+(<ejVP))pe%TOsW8Qvn9zxSbd^MeG$1eZ{Y^V4QF4m z_S^`wc2#qxLR62&^Hf*6MW9$|@c-bPmZ!%e$6z)2vWKBbd~C$Kbsc7TPp&a-XlP<3 zgytQ!!8MmpH+`@6j{t5^P*ZdhEM0mH*R=(4`}@~Rsz)ge)kx;T?c(;cho7`R9oh+l z22d#{_~-&1pqm}g0GE!4g%IyWV4zIhztXZ33Vcink)0w!SxC$>%TL$rH$S=OE)sPE zq$M4@_Y4l$oHmn}O8E;CIKc2`Xs)nH0nner9ddtK>}mHiS)HAnTuujc7`sK$utPu! z>m8npPPw^a>i&^$BV5fnz`V4xkx2m-)S&N%rKyzXKR+kfuHPgvdk|Yd4vFqz_&vO8 z7njWrepWtx6Gxg<q@#4sQb-YzG562$YPxN~_e53$U^HB$Tk%KZGlu@`P#`T(?f{z* zepE_qvc<F}2m*zZ+N?X9xg)uW6mJjvdTI`QT(I0*9rg-P4k9!6+V`x|y+heh_Sa4n zC%g%s`c<lIDy>-ec@P9KUg6N!MviccE<CKHjfk!h5K-il{IbRn@9+P^_e}8umTXs2 zot`(-j8S`fV>y*G&;_~BkSVA*cD6KwnA815U4QBtTQ@t#L9k_*NSh6ArbTo30Em4` z&G#V+z~Sm4P%#GJVQQ^`c$VZN90yxzp$-NTr;l6k=gd41f^+`7=Ef!LhA5*{C#!iR z$uIi{j2}S_Tn?;e&R#yEz#O3oA%<gYdu-{br61;W!1ZR8hdLg?V#y9~6ELHFMAHcr zh?IHoT-?kw)_&y|8v(&p=(Y}95G_#H?K;|_a8D74oQ!+#btS&&I2P+1TG+oX!kLD~ zu(oH?X8NbSyVl;AHa~5C<0%w8{?!UJRfMCidMFz`Src`jefs@12pgsxSUeQ}$mykI z^xJJ?oj&isLk2|-ic<7{F#UK3V`FJ(RV#nr3l<)Y6;%Q9UKKMiVlwdIg$2C#S;D7b zZ!jMHliBl2Nq5ZnDt<Y*>3;j?e=DM++gn}Ax}T}fZ)YRDb+&!l%Wvka0>d=&Mc^r5 zbC<$ZX!P;lyqZJLKCn(xw3QAc8#>g>JlWBl0p%n;+AMa?NZ6b2t3SLLSP%2n7)m2= z&<mSp9I~;1_^N%i3wc{rN{Wo|%Xb}pr$75{(KB&ap`UYfD1EA~m)Cf%Z_QZ+OSEG! zh-~Qq?2k(xx%Y7cUvFqU3~4(JC;c8#{tdyqw?g`8547MA8|+Mr$}5kfg!T2obQ{td z6DiwC(y_?4r;<VNu}6?4fla5_{YddKA4!fB3Sxnh?EBA{7Wp`8LhCa+_u>r1tkLBc z2iz!VsZ9}I33R*U6Y`Q<vLv~%;Kh>i|BIjFqjs1r?%%Gf0DJ*j@7Z^NdW1enKUuQe zGGt81uA_Wu*Q0+dP`8vW1^sEo&2n^|y6_Cv-TYQTd$gONn0&oPX6ug|0{a)knK+Vy zDFz*^%4&Mzt{@`OB7dBEj%82ETp-FmUISt^qxBmyXxM=PK^cbOZBGxb=Rs#0p0yP8 z+lo+crU{(Ca70KfnkM~|cM#t79i*M)+GFRV!Mn73B8%s$k;gIA!k*hnSHM6Q3MUre zmtg`GptY0hFrq+jTZB;r9|EYSl$DSo1qu!mZUZq4U~#BHJ%V6~qe{!sZ5`e|yX8Ur zV$_&aAhrx(mIxWmA+*MsxycR03)@NiAjVaY_4uToFKZ-20kE0$O;thomQYRwTZi46 zgjN?YSF*t@R;WW%t6<xKU)_Qtcv|759<rl9Ls^Zs1u$tmT<kR9sg_27U|PQDq6`pd zRzt}OB6uO`;BTWnPeO7JSMa^4ay&;XOIK-@9`2fmfq3c;RphO3KPg96#hMoDL0ksP z1X5&e$8ea?pRY_JAEi`iVHJy}u;L2tswXk9jDX^}=@XBWcPGF_gP{r#P1g3*ENhb> z4*W-5G6VnBx(RtdwBR){_`Ft=z$VZVtAe$_cj~Gxgm6@<cDN#9i`pM&%Gq2DlX93F z5~X)cC?FsSD7rUU<hT1+02DAVV1q}RhxVji%WpaQ3V7jMB5j0M9uV$k3^Gcn$Itq1 z_HtlZ=n&|z-)Xeu;5*8e%LB2c_lIpdL;aV}@>4f4kJ}%^x!*D6Ft*?z>l$)Y8{DmA zx*F3wf0<#^)g_a+^F?pr)Pb=Zrnk7J)CV#_#k@n<9U-5#pn{Og>Q;A+74KLAZFG|5 zF8#ExHsI{o(ba+9zW*rvDyOx8t0$35l2v;YsjZGz&LeRYJNH7thHK~euNJU67ftz_ zhhIA*adKo9>gU26aFSpeG^ga~9XV~=?Rer}t>1q)e^HaD#3*E&@a?+4TmgxuvsHD{ zvP|=lb1D(WAZ$<00T!@O<gK@~+?o0~&OCqet~nmmbvXv)9~025!bD?KJtNQ|hVzjA z6KVp@#KdiY^L90;yaF}5gZ5XE!)I~V9DJsCyY>P^R#SZS9dj^RF_+AfE_a+@jaYI} z0rMfapV{&5WRf{#z-7yS%=vmca8>8x?NDV&YCRX59EDASq&@J<C9Lt2!N0svZutwt z9MV=>ner>UkEaATW)xH;_Fc85zry8uiP50t@)>3azg2F4vX|f1>Odnue?Yk~7E`S* z$@$^N`WJ59%)5h^Z<Gcy_veeF!OcUv0c!2z3#lD1O7T*G>jB&O+mfr>UUT%DKztyE z1~H8S*=I+dagNYLX3j}1=;8Cd0#2^SF=m?&!NCcK5b@CSyX2=ZcXIjzIWFHv!aWTo zeh4IBK&^!_Qk6w65?O@j_7}@>&KS<x6`286ju1%VW-yKMv<Lc(PZ1M@PKx|-E^H?x z&=$ngv%nWKw#}H;o7~t1S46PlGax)!;cfiSX=qX>oPaMffV`kg;96iFWetoiBfZDF znH~8l|5N-K=3s1KR2txO4{Aw^g)t66S_)CdW*Ctw6$KIu6Zg)<=fJF*@+wEYqxs1U zR?)aQ%6UE%ms*xX5dxb%Yd|tu3HIoEBgW)2S+=LSU|o9Z+=95}liG!`yGHcy1-N~8 zdp_X1D5oHcVY?2v&yI`8`FI`Uuf!UtvTGbh_B~v0ENNL&rU>1S7YQX<G2A&<wC5&} zZvdUtz;j0qRECpRkd{Prs@$gMykQJpGAlVB>iA7^<4xR;kHd<+g5mZEp7nh<n&{O9 z-&53PVLM7J#NVnu&h=Qv?(+y(&?*u{)U@C8t{Blti9Wm_yeSl%68Y<jm1xxk2>&Q6 z>x+JANJ+mRzYsDojS2Ku%s_f<s4BA}FtIiWgTc4On0|1qYp))^|MdTnbS7X?mwVqI z5OV88AnGZ_@x&mD3n%QjATm(WIG_#SZW5ImnU;wVqQDqdF69uz7Wv2!tGFSGrHGPg zB4DA2nkHbfgMth@4Ab+u>AK$Qz0OksGyng6|JLtPv$oi*gDGNv^Xhk|Jv*x0+=He$ z#^g6NuBX?x>Asa(yFcF=_(JHKsYR!B*9n92BvBJ)B{ZJ7+<C9H{6NIm_a1Ln&iLPS z3-@YjolyN;RM$--=Tx;9IyVHc>(qMM4_u|L9rRDixjiAXvago$nd0rW*Y>&}dM&nm zN@<DK_1N<ukIDOCUI23iSZam|)o-0Q?=O*2DJ{=;=FZQk+h&M}Yd>(kMS`wcT3XIW zC8xHcjNR^te&Kuv2W)*yt@fslfQaYVRaERTdWrWGo%f?D0pn+SdF_ttJv5wZM=?l! z$Qmi(n#jF*L-og{M5@rKAH%+#=*tsNs4~1R{%PlJ)QqA6J}q!IM3QdkRd<fO`iCfL zV@ssQ&sU7!zU;RmKwd1CDImlgtM%}T=o1f$y?%ZyOG)PofeS*5YQEUCOk)Fy>V;K0 z&m#CZYp9mvX2I%vfNd#y5XM<a(|4>tiYUK$0-_yp;FJZ|xLWDYj#GAvfEY70AS{MO z>Q)So+Gh(#1W|pE$Hj(j?TU3H82?X0B2|>QjL`*P1qpADm_C7jBO+I1qySNn5^c5! zved2k@Lg^NiCiKKK+HHiJmcePRt$HQsu+OI>xUTSSI`W;=*KiK{HAy<<=$30!Hf#` z#VF8Yf_QKBy0&Ip#(dSwgp>ylGxp{PdkRt(Z0M`XtNq2t5s7FHBl%DeDeK}*)|Uh0 zEH<7zs_bo13(p$Ud9aMdj0`Pik)HKUrYc)RC;@iS^48%#CiJ+F)+&`nixs!KH{pri z2NoZtkf0Msy^fJsiYOc=>p>n7h4$5E*(Wc{R5_TXd{CZ}8ru>s|9wESxVN}rg~Zc; z>k$#_1}J^P#ll~A#bbh#vp^ZzNPqRP;At4o^d|hvonrQ}z<6hcPP&8ejzYExQK282 zn7EfZSYjrGSY(h$z&OBCZ~Yh&zROVJ_~DGNBiW+9ajVF<=H}90G7y0+Vt|R#py8aM zV9eB^x?mxw!sN_XVYB+kPjvolI(X)Tlh!zAYevD&(iW_7v&iwB92^-P&Yyo@?vmuv zHevp*w{vC&vDBQLuxvH!F#%z`FyAO`sa}`V(fm^&H~gg4%JJRDQ=keA6wFV5_}RqE zpQRua<>LJ??#iVN`l$9B-nDbfH_t7R?SCisum7F9blYF)u0~F4)!}__IX{^8#!~N| z*|KL5E}jjGH3^4z{WXsbxS&VodflHKd)NJ<i|1xpLc^7D%f2s3e$zi`+3)rh5&NC8 z4f*#cCv0AEhxYdVn!B_6sRDF`xjU2GF3k>Boo2jqinmvA@wHgi3rn=&)89S6?8)%t zoUUs}>sxo#v%D)R(+8cC=pB)8JTSl6&}RVlPu1nES&;LHXpj&U&fuof%CkYS+`Q;% zNqeehejWOvN86Y1g49COK7~0BR$#yHe#y(eqoNoI<-Hs~Is~lLmS{g`*?WsX(tFz> zHB4HM&r57&@bdj&nnr@Ew@r(grJD8m!=1}yX(DtlN(nGG3uOTs@9VLg37Yt4Hi~*U z4<Ua`IJAx*+WaD~R^W)ZtaRdN$M^xK122(pa$vUrbp=Wf{12s|z_#WO9S(8o;agKY zrfa>|j^@;f?OiF?=9T5Kw4djcD_X8<ms9JZZo@u?y;*#z1Zx=gA+*3v>2B$8<$ZLJ z)+Ms+k}0Lj$r_%oD@0l>f0TMi>*uEslk=+`#f;&D5&wrRfnUdX0|Y&7I<CRTc5?`* zUmbF$T}|2ewx)%zbLY-zS&hHKQ*l#na!J19%+EXXU-S&Kt3Cv-KJiR(!xqs};6_gw zIxzjOqH&&&+b#ZV@r5kuM$y7$G-UUwI!rAjJHG#y_pVXxj}XJRTJ`6Y@k7T8CvMDC zg!P=C3AR5VBIZ1Ri;W9<M(--V{bB@1e+YyMBZq*0Y0leTKCMK}aL356<R5J{+p%Xw ze%_vCL-pW85bMufe{j8Eq<7ltn^#|Xr&u-Z&~wM6;=-+Z>1b2%T3U?2w${(C4VDmz z+8YPEGpFR4S0e5NywvsfcQ^Wr9&dfp`&aIMrCaBN$UXk_D9<9q-t9p`M^drH{iL;h zn<E=9vnbv|Q$hLDm~H6Ht^9bs7sFjtMg@T4i_qUbDwvsaY(4X3scsXaCDf9Z9jv`s zldL-!_n^cKnJ53ntxszn*!K8bn0s%a{ma7hPaEUPwRhzl+mw{ResOs9&z<?J_2QJ~ ziZ=Ny@2Ia*zJd!yf?3VtTFl|*i&!dHNyShx!9F<6cQA=Zq@;P>bIY3JfiQdhEWdNx zQO|k%1ntkR@DN|$65H&`v(k>6ORtJ80#*b8&d+>(``GJFkatk3Z--t!{mgB3c(&)T zFn;O_af+e(uJNR}xTh=sOC`Ww>YZJg%+)H@`tn}JOUBa|$3A{dtN!4!TgnDr)QwID zSBw8~0N%eVbSpF~V5ux#FRD*EK-Zse*y<-drG##nYym`Lb)D#<+1cmR4pn)^Lh50> zN!tXjmaO72LG&bo_`*W!7|V;BW?K=SKzED9Z(JP@DPDQ$=p$<1<;I|70MLjw9{2!o z^kNZ@S&C}DP`d~vgray!`E2aa)P~M1pi;|<&5^z)do5{J*JrZYq?q_y5_1!R|Lt1( z@hAi|tbEOz>NIG;MCqA)pC?s`?c6fvROB8&O67wE_L>aL!eJ)$H<`-u&|rlr)HVqb zzOayI=fE8a@w6v<E_Gm#=<%ZZShg@Bk?nGW+>?<Y)d^QUJ{+W+V_Fg!pNHgBb&H50 zeW-<YR&|S=UODa^Bs#GH?sj8=ecqm32oHx_Rm`vE7o>#p|6#Li0nHzSuW;KT1B9j; zLl^HUF<w^)gBXXBjnWG{*?z}X>f}S)Q=ePL*x6<!|Ha986Ey5-)x^30)e?5pK&TE0 zDaEKJq3yaTB;I;XjLUo!xr-ESJ!p{Q@J-4+QkPT5QxQ>4%<C0^tZ~n9Zba+o(0I|D z0`ydPdhO$X5>j2675Om=K=GDIYVRgtQ8Qe6??GxU+z-qu-yrY(WBt0G-{CKZ_`bq& z6#rC|^nu4s_^f7Zm-?ymIP7*nqlWhAJ~zG;e)qr1SA@*UF|g*BJ{US2B0u}lPunRv zM%9WysqQHlNMEW8xD)#JpwHO8r&IIvZ1Ja{EnFp@-1OhB?y9JN*|x(zdTYbb!>Dz9 zgx?XQ-}RTYr$W{EheCk*RsD_c#2o)H%7OLKgPULq8p5|-MlvGGM>k>9X@xOnGbiU; z9>HMgmHV?k*|24YSIraS{!n|}rqE4;=g@iWS9jWdxVCTQ!WXVBSo|ms+cbUa{j83+ z&Sa}|D;QaFQV}CaFt7P$sz%-QbXse#y6eh~Oo!ihwJb?`wf5cv>}Ob!h|7L>LrauJ z%<8k+QDROE?=Q4%TkAU$aZA6Dr?H^GLpiK+Fv33cWyRn=cJ9}u{PydimKn9PHjn%F zoA#x>HRhj8-P1d+Sf*V$*Wg&S`RO}>v4UbcP=-p+*EuTLw*loN!5iHj)+kG`i@7py z=7vt&A{0Y#<7scdxBR2!`y=w)mtN}Icw%+GHd3q5w<cVw_~gk3eWU2WS~Eg>-#PnN z;MukPp9)|B+a#P<3xgi--TUZS{WtnR(hV{JTi5y@uRoW$bao>sZZzW|gr~@BN@SrU zQ8zFA<ubUYv;$`H$SFa|OAr^yzPVrza@lq1z42R8XIL!BzKC;Lnw&*7Qk)Hb%RNdX zg~LL~kRF+w>SZ;??|n^tmHuMs_4ywT+z`%doj3G%&F5C(e4c%@f@5M>+m1N3T)-{j zOHF^lsa9QhR18Jf)M|+mHqw@+;WbCRwLANxC0aTQ!8L?h0Xh+!zGE}$kXuk`(yu^w z*<;;eV?9&e?uzI=WtrL7CQB6Hvc!;<11@lipq#xm05d(-0qI{{izb3g;^(7fA?lx< zTpebJYGS{GgdK{8eH|!H6i9MF;|d^&Lt19)s3SQaVcIlO2<Po+&(Iu24xxO-`=4xH z-D>3-I=O>doT163n7-|UK|7MJ#69plrW`u)o<NJ(13u18EM%gLcF6qq{RS<bl|7F7 zvSaR>n)and(LM*!Z^gkNz^p>~Nq4{Wk;VRkpLYLmUwhY~^E2%U(2BsYh_OQ_@^w=@ zpF4E2#O5njoeKfdY8bz*DXtQlAp@`9UZ<Do8&5bs%D<D^$%3<5v2O5BQMI<IN46P< z<}7G_5(Gj!A!9?v#?qG${@*iDz@1j!9a4?-O!e0twmvC7i)~L;QicR81i}h>^MA5x z6gi5Q2@~sDvW@|lJC0)WaEyC9*S8_4PVuY77p^~D30Udl(+4><yhJ+ilcum`huit- z-4`COx)NYtJg|J=lM`Ewr`e6va?{KsUWMqq@lK&d=)$TmtOA;gT5VHC8SCJm9C<LS z@poxUU0QC{>Jl?r#4iwUD~%MX^W=y*%Mp1&+C%f5MW>@WIz7AM6vI^;WyA8Qfd5Ve zVk$7Jj#gaCaC$#B^~>3+`73*yS0lQq2uL|3HTb+s1!g>X?!l9Mb^mie^97wenqGsP zM9POMbfHMvue<-F6*BF{TGTXP)P-Ip!q7>wLK#jDtrt2B#;Amm$#ieuulPPC2!L=@ zfNHZnu#d8SL%|-HmUb$rFJfdb`7{NlJ&0IQB(U{E6Q->e^OEP@0L@w9&$C45LB=M- zTO!c^T#!4cD<zprTi6QXib?fJJGl%{XuN_6kEw+)5t9q(B+Agnw*BY`uUI##E=}Ie zA{tMok30?_9`ZgR;10ocMoS@bJ>bVeOeUdlEGo^#e5@aX{QymftQ0OKElK!a?3Nhl zD276Eq`hiGfC7zfR!0bE^663n+nt1db~ps$q}Ra{m$(nPTXb`QMK%QPa^{F^P)}vs z>UO<G09KEuZ<M?$AF8(xcUp9iF;+9m>_DVT9Cg2{v<nec8;l>fO)vJ`egG%phE}J| zYZ5-G0vnCI2DSo-e@04H=>}tO)0YT>*t%wiX^+{jTbB5%&4F70^NzQ6P9|4llSMV; z*Mm@-aShfy6}z#dF3_l5l=8lMD-JCiO#Cg?w^`dFfZgI02#q3M^3%8yH~g;=O^ebi zWk%Pa4y3n@$+xB0jxyGBn0Cd0>b8o)qmApe1T7>~7={AOEpV)&h&g~!8$sx{H(ajN zkpO^(W@iCp_A6O4ZrexBv*a#&sgv$zT3&R4axhaKz9jXK#Sad2%r7ovGw!V+9p4=@ z@_pfQ6+1M*i~b63a)Ga3_sA#3J*p@3>v$&}<@NV&MoF}zZ7bWv>0J0w8=ewm=){Bk zcJ3kd2Pa$?cO64=EpCH8BDRFBi#$9~xnqiQ<QJ*Jo;PK_eO#H5MP@?7@}Ke_27Mo~ zwy%5S9>dbGEaj#iA<eN$792TH_t(&o{6jI_J)Ppf7#mSr?I_m_#3u#5cs3WL`+cTI z1)ZDhPadiGBK?B{4er-&7kwBww&k6m<S-c?Qu>-3Ck_REJ>})f4E>{`Xtgt4XRj=G z9}@9@X7DY7{jTr%Zm`s5{p*(w)((2*3T5E__&ISuEImE%>CAVD7sX<c(OwlX{W*l1 z)wz)MS0)~+wb{%{-Y-Wr5(QB2z*TQ|zp(!4V#CBtmAz_~eBixpJpCqyotCma8@~N$ zmEZMP7HK^P`e!fgyZG2<`cQyDizVO_xA}vfJHA@#T`|9UH1h}0*h8=7^aLB<FAqI* zrQpfz{@7NK4$m+(duMjX*DEgEb(?RD&1=-Om#JpC4oulJOLlwNQ!)0xRflrZ&u*KZ zPpY28)3pr;ZlLEar6hd0Kz?vSM7J!#{OuHAH%_{ads)FqO(l{)pr}=uysNL%0EAkr zpnUEDS)fSvSRFO6QDHZ_f%S`N9d{d5wMDT*jLs)6nK5Of%Ynts=2#Iar)uW{K3v?y z%yf)>wCWY6@wFV%k|l`9&>!wY%%{@<ciG`hkc~os=kf2>q-&$iGxRO4m<rXK$2|cZ z6%Iu&D*6+vWtgohk$~~drz%uRF>4vc?I;1&hnQw+v@7|-55A<vb*ywU`pOv3g00f} zF5L$=NFWX99W~yjS7S>QhJ1?717oCEFZh*sj2%u6-W$yx3OBQVGCkt?;zO8T&8Mhk zvOCt?OXPN33vH407ka|2*d<61;DiE?WP`qGs&@XIC_SJAXSgTz6}LP_ix4)imXveX z&+|PSYd_C9W86vuA0Z*{Fw7<8b~hR8Jum521b+fBHEdP>iIqMt)uxbP8MQNRIYims z>GXQzgFq}iKF-<n)5?^Wg~`=}&&GjsplF<VTlC7Iy{{$a)hHSPtWRdtTQo7`So`TJ zaNTa_>N=;>w|=4fF==mpjm3l2oBgU3Zes1QcI)w)3xck6d}`-w_t_><>vtOKw>)T_ zq8=#kCYKfF{;alfbMBaPSNYnZKHHS}vY6{y)v*7<nt+Gn`lX^xg+0a)F**5<yOsGn zoYS>CYGcZ|6vno5L#w<2rc@JypjtI8TQTfjjK<OS%b{S*h3W0g>8o3m9l6)G-k)~+ zs`SIk!i6&3X06g*dshk8s(t$7qKP{!RzA}Vi+9Pa6w^xFN{9ATh9tw7L^uBbLK~#x zqF!tYv^=pPW@SDq<3kUr+shWg-&1$}zPGJy-NqYHE0mMJRrbzVv9nhP1sPCQPfPgJ zgKbaP)UlShkZYN8ZL!D$0n;ZePn*|U8CNU|wORbU*f*SJu7^$J`c6lxzeKINsnp@r zNcv4N<)nUceV5vfVc~4!_kMQPCNn=<D>X!?iq~<CvrHop7LXDnQudJ%X}5bXQ=ijI z3V`lC?{>G)kp`cSS%ARz(f@vKlC+9f^8Kpx9gi*gvZqq&33BNw>1V6v<Td#9Qv#RG zcltFKS3uD`2d&_DH>jJ+tCv3mrpx-V*CS?Orbb0~3d#l(KwwV5Y&Qt}51WCG0@yMr z*;2seP!viMq;0*Vxg1V<R;XEU`1YG7OwE|@Eeb{e2TlYb9ouI|HM;%0CAagkba1iA zSd&~u-i2>u=oB|9g?m|;3fLP76@jtBR;Yk&Y7pDa`eKzRv-*ROr$82cSVe2Mg>!Gh zBx4)xkb>MtX44~|e%f0i)65^nC;X_paLh_6M#Yfz03-{6ty;3HgcU32?#N)tl7nKV z`<AGC<lQ0hz9S;aQ}$KIprX-li+-fO>AqhH-vYeRp)aUL&M#88{5HEUhl0E|^#^R= zN+Xyn;a(_SXv#(xd6DOwQNve$jY`q!sPz<@5h_xPrzhWxDjEmJCSsHT)2wTv^iv%| z5N$NAa20@KR|dt+isaL~r9k7+((K>Fv1l^Us&!Nb4>d7=p&5kAq<}{GHTX#fu6US% z+=hC_oKz8OT%S5-ux0Ij_F`gYUXG$Ke=~if#haz3e+f6%kfHceGt0^jcF{vQOzcq= z)qehm8`%bKvoP**s`@5sgRUkuy~QGWu0>|w#2aCqe@hs<E-3k15}~e<ZihH<^JR;q zkzagVJGj3`EDFnAJJc_1%4-gM;oW><Ekg(nAlj{~&a@^4{$YHfh%9qMGkP4+9Iu=$ z7u&YF#C#rQ7Z7fADiRFcRc<`inu5m+WeS|fJt?>o6w5zNO!)frg~$D2FZj=E-ee5e z(x<rMvg6R|=wIYjVkcXcBfGY^ch#vK3m$!3ygz@lPhT6yk|W*S`{eeCO+CzAhCTXh z@h?zPD}3W>u{UJFQkTCB`=>I6PFuFM?}Os6cXVFv>~mhO{pFvn`=P($U#;3vyp$B9 zs$qI7)A!zqIgsL%-x0R2ZPruijcD(S&s?tg<W63VR=Qg-+q2~vmEjq-t^ayoeY!6g zXny!0Ljqmv^lPDOKp=xBE1$)FuDfU-IE^oZnA$P8F4GjAY_XVy9t(P4v@xq>s~p!A zmq$&@8+;)r3`ENDRVVjeb5UQ_V>=O^P%aeNPBvXyt^dxa`d<vn0kJV?5%-G4!6{ql zLyKwj{Tah@6+NXT{>wq<pd!!ZxFJ~N0De85$aGN|S$-a?9Wt2UxSCm(T#A7n95YPt zNZB~zyd421mFm;U+q4dnyY;@5ji$0AU>lcrl`v!)k%w*?b8kr1_|@YuIw?EJhtLrN zgKyk>n~-U-92(fkfM(WApn>^m%<wjve9G~LMnY{K?pJKX6e@Z@aZxlSYaOQHBI!GE z9O+tI|Fh#&j*Ie{0kt~KYuU{d3YOt{jxih8#NA`~%qsX%H#+CuT>5J^Y&W}^=A&7V z!1OhA9U&L`F8zg07mB=aD>bbXgR^izEo&o9-j~lx1f{69;Rl49Ap<-IlS56$F_D-r zm|3KkWi4x(A<o;Y@R@8i=^RHd3G}<doLb$DqZF52Af6;G5%V8E^|_K%v-#8o@In2} zHj!b^CiYzIl;z)wcu$ng#&tX6bzK!IZcFj>zre`$CM-PB^{sNnyYdf023wcDFLnQA zM;mw&kaJOOS*UU#<F$!P`sdQ_{=?7S?uok>^%Ah@WHGd^Im<5VUUkj$muBzS^*Hkz ztJQ(UHirETkxA<0(|Iuki_%MXE<Ksq2zpxdFf*D8@;X^MIUD<q&Ta>O9h9`_<*T1k zr$dipL>)LZc;cjI`R141Cf@yNLei!NPdD_DHb(r~vAO51J${}4bG86!b9e&`=AT=i zT(8};ns~77?wriON@hk}XEeng!u8nO@2A_3)6c%<KECK#eOF@AXIfMMIxEhH+iHv6 za<`3m`DUSdvn=dWg*o>e#l%NLRS}<eZ0*@eQ#(0nTXEwbTjP3-8`y3X#-RZu1|Ks% z+%XZwr}{gCU%zC_g1^P0f79u2ElDJqf`Cm)lpsMB8dhcj7FF2j6z13-sm*~9`rY&5 zPz9vyB^j<iIlFh;y={LH#U2MvPB4+~czBlN)cO0xk=I@=p0if~g-DTQi(AW2M3kUN z5?7Y%*`aDTIB#;JvveaB-X=FIs^^?<5L?WuI~M}0SFAzjNI)4AL*KuPkvnZA7i31u zN!#6&gp4=_3ijNnA+E3Sy73hPLL!`h>?pRo>G<lhBg0W~v<xsjD7%qK4a<iz1p3*- zvR9KaRHqx56@$R55ULn9n1yW8uNykOAAB#3F)oJ2oxXS*Fp~WivFMEosqu{*>QoRg zl!@Xp@zULD1*<13z8szW;mI#T5NYbF;zhw!-Z}`s(~FfpvXIm2vblVTcu6c|E3Mz) zMbxClPSn2R7XKBHiou{|h%;lg!$Mo4bi<;c<u@x&kuG7}!YP8bryZ_>!4m6X#{jbw zpE*p}kwvvEWNo-nSih~K9d_ltz5;F}+BJgRRblFLN=jyFOG~(0DH<^j60sH)#GT<o zdyU+;iUqLv4ibgZ2lETtR5Ql#C9tV1Nvk@zQYH)?5PmWmQCXA4|0*KIxL_)Bu02p; zAx;fv_y<f;gg!F`To~4*b6>(i0v=F#cl_e+fF?^Bur`!!!|R7iWvQPr*2|H9B~;1R z*qDz@k_`(#uUUeViK$Z}==WR9f44}xE7Eu3f@U_!A?=IQuo;Q~i_f1%RXzTA&M1OS z<Vgk!zbOKGFCU)c(>`UB`?{#0Sh*nn%-@wMUGdvyne_gvC1zS>Pm|kKdRU63)=RTL zI=u-5!X{CK!%X1Jl`G|U?u-rW${qLNDd9#avLs(njS~2to_O@<CS(6mF2>k*SLw!= zhDe_e3{P5BAr8c@xqJVXe6YF5vI#@Gnqm^2P}@3|YvU50q?Q{O<(_t*Vp#Po<7M-M z**)=Sl1YmL#;;3%rrnX4Iq2M%c<;sz+vr;3dEQ&G!?T#r8~XwuZ}x$aUfi=7a#@mn z`}8McCmmb5_Fj3k%4M`1@W;LKqO(Cd+4ndTG~oE5sxP*4C@Bk`f3RvjBh>and6><~ z%*k;jK-+oz;@ap_@_wi)2_@8MDK5t}pQ+jrUBQr~2+47HQ-L41q>R74{@GwZ9ssgW z1>-d?DewNni{<5OPV^|J3AfXyMQ3LHU+0da%5i1-+C620Lr)R$)VtGpykcZeeT`VL zmiGq*dPJ41-TK}CHgPou%V)`F63$QR48i$_&MuU6IUiW*mvt};Glw(O%CnS|+TlN* z7%a&Sw+EO#{SSA$O?fqeAO6^J8A`NP)u1p)sYstD)Dh6n#g&Uw+CF_$Zdk(So!P?j zd4K(%;^j?G(dHL=hT7acLDAV+p>jEW?9!|CuTG)0)9RKSo$8Q%+cq_9j6)WCEV@#C zQ<_j*$M6gGlv^nTM~RE*MyJ3{AGgi8(S>cQnYAC6YDN>7d;kV^Fx2(Yl;QyQ5%T5E z;nE=VJ+eZ^aePn#RjTeQhF&8O-nlvPKN(tYp;rzI?Ft(o%UjTW%n5ewfXu}{31}3I z;sd5vUt`bML^iFeWGno<5QxcI#;;~C#6uIetIx)=QVh7*DtW8}eOF2evm4t;b(s_w zUV3%UMcQ@Yhxn_+FV}<PZqNYGBJX}leD>y#+|`gF>59cX%F}rII81r$fuKQ1^%Y7! zJz{u-d>^Hq#1eU#;ziu?ZT&*MVX5AabqzrgwWAm>iM86?9iW7d!P>-T62j{YxEhmv z4C7Z#d#tp3)lt99@yop>Ue@8EChz8a<N)%HIgp6PYrOW=o!ooH{ng6C1v#E!Syd%K zi-zT{8W=RQjy4$>LF)cFzr*a)536aK+xaHNq4pj3Dw6yzN22+Y!t(GW*DgFzGv}x3 zfJl>P@}7))5hiXEl7f}$3>d%BDk{p8p>7#xw|BXWuFE5^DcuUHGz0U6%5{Bs`JO0; z4==grbw06YOosG77b;UTinf;NGg#7q!MOLUdg9}LXQRbc5yDq5MemSl+7@<{0O3;y z7p!hCJTF(%bkRK2-#I^3XrG3c@PIKZk~;Ub_pG^jw%k2(j{LMr{tPdoic0|<VNW_9 z2R>ik5Wpr^io;Ou?Hq$#kS&i5)o+u&Sa@Ml;Hyt<Q+5clTCG5G3<SM(?cu$LhNE{v zHg)}(W6QASNQpr41iow7(l^>YZ?k+~$R8Dp=|{<9K?6m`dx4HE1#Sad^qy{jE%DY^ zmoP`_m;kgvsGf3SfOHB79Urvrn6%$2U1VwRpQli5d=~XmjM45#+N|l{>RWT4)fo1y z&vA}#3Hbx5Ui=NHG^6wvM_ikrSN}41t5A$XV`Dak7>5NorI^73{#l*F+>GKIaaR(B z)P)p1MPB-r=3j%8)|UeP51S09zAWd-2KWe^2qYohAnObSE&HRmv0Mh&&bZd!vXS9+ zd4HqOy<ni$S+TFjcY`H+zJIo@QDQF5<S=X{mb+0R1)*yVtPjp~8CFK#_+|G4J+c=t zOra_X6*=4ZIRk>8-$lKxrKawNCk&FRyr)_3YmRLhUF=~??x7$P5I_<`-;sCPScQvq z=4eErx`}lNP5|&czanQtobmom^L=hb=&2VC_A8QTW^-+n;<J+-@MVx1ze!V0fj)ep z(?Q5~GVLA>w_~V^nYrG3L&%%mQ&ooX(q~cn4EB?%!6FeA5Os!itppnWy&va$pcD^f zcMDMzxuRu7-%IHlLo3%*%J`s>sk#7^E9*h_fb}Wq1c$(_tuJ{)T+UcbDB{G#L87s! zmbc4(U_bj*H`ql?TIgVEF>OCAUbsO{ta~5gb5zHr^f2W_d_09JK83^uk0+_Ymm|vC z*qXzE&<#s>GIV1QGMYXE5$nps>FF?FMDSAxtG6ZxsEc~K3?-0U_0Z{b0S7H|**#ip zA3g0KW|uGFGri(###QG7RH=AASxOH}@eSPy#@*0n=ncOCjNtdx7kkdNsKS9#pBUGe zI!jq^0DRoAd{<q%0HUSNT5WXF2xo<V-mTCna0nvGHct_KOmn7!`oJnm{{@k3i54}2 zQHd9ed)|w-=v&;@s57o9rflP37S5%uyB&BY=u7ouMc6SVcy+eZe4MB=$J&0bNNy`w zSSfvW=<;BZ^YuN1F3hW_L{2*Qq~EdC{W6F8O<s)-Pf@_cz3VlqaRKG><Oa{lp9=Mf zFrzyB9mSx(s!^5o;7uKBwg0F!8}I7+UpRN7y=n8!{vV-1w^V%t`q!vGisnfWZ+~Ci z{QyIjJp{l}+oe~28-u!&p=`LiP#y2vzVzO>vZ6g?yOgMn5ik8<c&Ed8Z>?s*Qt!nq zu-4pLvw85XzSH-NZ=<t%=Hwc`_=2SMEq?}nkuvctMgV)3M$fO+x729lHzQ`}a9yI- zS>bb>pL^(udh^rZ`EDg$f36a9ZT}s|da|b2KC2tp@|m+)++~^iql1R?R(U<+Y+|0P z+)xvVh$>W?_Ivl#r%!yd`B5vN3Td)Dsj(jb<)ww%midjj+`FJdtv*u81MYu=z`V1U zW3Ke^D(}yl{I);-wKBFfQ7DGCjb?wb=5L9vn+H?4;MY|ZYx|<Y-O62t(~#ZHnwahn zy8~Zj^Gg9T0S4WZa9x9Zu=kzm9h1u96chn#CNobeFFT@1-SNLlV?;MgV5eQVMJwD2 z+UK_^m4=W9k){^t41p1$x!paLjSG2uN`PcM!lMj(yd`VZY!7mgn#qW1qsqU989mbD zq<bCzEM3KvZ6pFCHdc(nY_+?kr<1)bZ>}B)V*1>U%M*#ddy?peIvs%82Ush;Ot!@j zARN5+qRW2bcQe-HkQ6lgTD)UWaFxNuB{VTj=jjh8a357FDj?jXL_{Y-Cd`B)EpCMR znV-RW+_wAy3iIAw4r39KRrufXT;x}o@8>ZZWe;pmWsKGI!`%N=wrTqXXe`Wgj;+ws z8f4Um?Ol@twLyU<Gxbm`mI6#4Os~+y@yJV5NE61J7vJ)-HvdH>aFaH6(hJ8N<Y7zb zvj#R!|JMD$M)z-@2t2FbB07w0E}S<Z356z;Kl>Iuo^$q5Yg1#z);eLk&_)DF4DE^e znHlxY+t*&byy=)a4N&GWEKllk%Zprcn+xIxwscT&gO<|Yav0IwdqdMQS{4l;BWgn^ zZFu6P!0(J3LZ3BWRzKM9CQZM*iLjGx>}(_p77WzF=zYz3-`z_azkC=qTty@%teWV& z{?eWmngQwT8;r9q9RDqN-v6%KYj!{h>Tk5~sGPX+%w@Ug#TaJnd3w8;R=C`F{&r04 zgxPNU4EtC?yUdqI&uhKz?i68ivv8aAK`o`@$8ak2IHs!ynn7o@HvMZ(YZ(G0VocQE z?5p}q_Y>&{^<`F}*e)#?zr9oXc;e-cH($P25#ED?5z(#i!LBtknJ;RJR)v<2dGOJH z%b&}9&*q`PVd`D`zkXcw<Zy$cr^rHiN#4&KVkS<hv;1o}g}To*x~^?@Tl(mt&y~3q zp6X39tCg?eL}lv8>-p@`q@n60m^6dE>*8MwPiU$h&x|}Yz1WSdz{r7Ot$<x*#ZUaV zJ~6)rC3k#UmD6t)E*&fy^9S>+p@-X^XwLnWrP?Yii!f(R8F*@VGu>!ewv=ndMM_ln zwjCb)KILr&7UU2y@z)#c-C;{B9c97>$@V^VF@0w7ka}o)#?qL%5D*b~UB*LO`61L- zZz{*4&{eNu=Od?sZh$4Rq7LywQ-lq0(c4J21ZOJTtPkECA*gTy+AEBL1~&N>vz9L4 z@^K0IO|C+KD$c-qH+2kO#DQDBNXro=6B0-dY|u5*AX36WOpQQJZ>WAXuku(iD|O-; z)c`;ElOVp`8YWnQk*vDIx;dtdg)^S_#_xxJ6+5364?s;~tev09_m9UpFG`Qiqgblm zU}H*uj3p~P+6_897wvrDWVtZFMqFA?=+fh)blyp6D=cw_S<2vob%mM?mK0)0T`FPO zmEz6dS;Nnq72m<m>>-R27J)9QDSYV$zxw{T+mLjQ){ji4R>=X%ggAxx16tQ_EnJd@ zV8}qikxBIxyX`gJ0(&eL;3!vq%QpqR!fc-Wdldx|;{yfql5&>}Ql5=xgYO7V=Pg0o zZt%0cIigNWg((P2K*dGpg1oNbJc5>D`8u4?PhmlgxJ4-%cR{|&OS?}kfT9$<1*7IF zODYyKX)z?l4WZHwP^|G2tklQ<N0chY*0>#z=r#rc4x)Pk`C_*#>1XLa|J5z8HZ9}& z!xcrw+iu5_;FUk^?cU$DaOGGC4|NB7`?bUow0<<s@q^oc-c}MCc_I+!pzU}dAd*`A zw)@m)pM3pzp4&yArO`v8Itz2##%?qz*XEh@>l55^V@Xj;#beIq%!qTXnQ>PibXh5l zI%%R71<gk%Us~o9xwLKbM}cMr=SaOGOEHq{UCg6RYc(D033=9aQ&Fc_h;Bv)cV^AX z4SfesgsVH6*V~J=ZG`mSpD70iN5dLtTiWcC^7en{Z_d4+a;-Juv#{+X*Vnuoor^w* zd~3dZTbNlalc~k6_fp{}xk=r|(ZY7>TMSam{52dnLDbGdbnniaE7o85m&M`sqM*pn z?%{Fl24wX7VEdj+4rgO-44S0`M1H*W@zXg2YUigfGUp4YZ*%>9*BTfSFt1@FeN*?N zM}(*S=iMLL>l<$eiHp{qeP!mHr3)_Kg`j;NJa>m!?6*v*fJ(sJ&NU~p{!b%Po3*O` zpf`?G4{*0^&uSxmR$ky~-UU!E+s1{O*Lo!)^6?+Cm?sm0!NXC=HoO04N5zh=oT;Bv zTI4Va4z06N$v`F*yf>+BQD!MBXjhhW5|HrFQoQ}rI*qHAi%>vKT4gH5A(3@(?u{QD zfqBGq2m3Ct*cl@XajX68hR3|R$rwp^P+*$RbkTWO!2M~`=se%0Ax}4+XZjWLqRZmu z_yNtlrWxvITvI^=Mz8h*)*|784BaW%wxdQnq$PX2K&;&8{`nuaX|5F6)xHx(J3zRJ zS9+|Ibvk5&x|n@~gbdhKK)tlf<E=dnp?223ORtJ6GSgjrXlRbxDgZTyhnOsM*$-S~ zT3vi;*fU58z7s6KFUwsr#nRTTV68*ys0{4^c0EYHPGFdyL1vXvh+*1CuAx&ldnhOa z{^1EW<kJIr0yWHQa1&6LqvyU-+sF}d)uis6wcx9P2-LCiJiV+DH|k3J**)11YX59` z$j^=)C3Y_JG3&KJe7MvhW@vTlNUmE5pLdO_Q+{6LbBX3S!Y_}G#t%sHChHY;p;Ih7 z8czH*DIcGwx>F=#md7Q$R^cogDv4};mfQ3D?Fdh^2~+I$JV|0BTOn_&zVuDrrBfX? z--LZOu2>j!0(`!{dR7L6kMq;-8LgsjUiwepb~npnx$ZqAa;NZ}J)~*qN219<m&}$f zKpw8j>zErWP#h?UgkFyL?@(%?bBDh*o8MplmKfKf)xm#vmb@1BAor`NTc$(`@wh<Z z9=+IWo#c44Jo35o7D+PPV~QJAzHls^3`S4Z%1V$Q`rtt^{?H=EGEun;ucayE#P)Ix zF_Ylfa+0R!)xKpv?5I%6^YdZi>kTny!33!W`PTu{8=UtCo<4aty<}l^+~lxl>N3Gt zUj4VE|Ak9~JD&c}5l2&$<*++j*VS{{lZAqoZ`k1XUgw#=oIjUKK5<)78}!rN{F2(d z{FocM8`OWIa*ZsK?g{zrh2kfP6Q-=SPtq#}&$VVe%iTM3YNzv~e9h>_p*rI_byRK@ zuq&RLSgYqB@%et;4ZB(Ee~k!uwpZB^W+({XUd(H()fVPH-h0KyM{$e5CQZ(ByU2Bt z<sM~<!<6?><a!)UVyXatmX{r^`Sg7M<<QLV?d^JWT@dXf;B=Hm9!JADs*NdKcW96L zpu42mecD+npSYzdG$n&k0TI2AYod4F`!Xmce1=T>3$4<H)Z5?nr}2`REe9(^_YcUp z255xR36G$dLN3?_w(vCcG_kAdZx!7bjF)hjP-Mh~36v7~u(RTTB-A;15t3p}rWo6G z{w^PA6mwdp|Hm5pLpPVR?)Nb3=ns7}TdN-2v?#7W_NLjk;!CciP;EB9mnn41d>KN> zV7bziO&Vyz;FNKBIE-Z$GQQhNR-yu0UuntR7ix|X!RSyOv$j$oL}nQ7fEkXX`IuuW zA0*an;hHTH3Ux<BCk?tdz|+q4fMhGaPV=1Py!iLChZ+ZoUhsJK)5D|xy&+y{Bf%Dc z`ry9sW(|8KJmG!SD~rXeV4~qMUIy>C7o1p3^%h2NbiivwOO02c1!tX=HXCVvF$yiL z)~M%Iuc+Y-UuS@j!H5j7wjX&#pTWu>=}pAN?36GVbb6jtvme(-EXjpH7FCNolP0kw z$f9n*1j50jcl?`kbE?VF(`wxcHo61mVS^tczP$JZ5y8u;1Tu_Hqt7XO9jQ=r=#$VJ zQw*Ry%G5D+7RuaC;f<X_39<hF02p|G75xQ4L8!NyD;s?2zRL+x0xE9$8hRuF?s9yk z5GbZNGkYkyAYQ|0FOy)N#T_=1`{0rsh{5Gso1W(0@!XFw$5k1?NUW3sFk0@~JJX_e zLR`+;%RP`iMng9GjrokBwBIN{zbIHR+jHt|%F}8)vc7&TIDF!;4#b_3!2-?Q0oeP3 z9-o_1o8oO-pdAfGKgdb>eW&zIg_!_nm4hT{zj4H{uaQOB2LsO>44!JK;Ub-{+Q|?# z?~d@Ly4@&<5j|1wH!MsU8_2!bRx((6H!tskRz1_66UhOuP|YfIk?;Thw<5z&z)hQN zW)}bY@n<^>MQ8g3Lfx&xHAQLh-N0M(?eq5Za-|u0sE_B)>gc^T{oK2n+sX?m%$~4P znEw0OnEeHJ^ETt#odk+6?z+*nJ{#)q-DL;myOJ;LeRb=~yY`jYo%n^)THW0eFDN@h z8@G6Xj-Gq#QhF`BB9DALNF!a84kle&vZC5_2+mk^hm;TYs<d;p3^R92aoZ7%rq_r( z04idH{0f;VR2E_$t-F-WMAE+FCb9sfask5&gD8$wHvL4hs?%Yp%IuGg$b4b2!KG|< z7&}rp-xS2+CTC~zX(w=o0#&Ur+M@rfgIolJ(Pl~zLt=WBeJr7IsMQtwc)1G<hxzkt zX+WV+FuJn$h7Y7b&D7TvDFLA$@dp;?Lv<lo!pKq=z2>LHS|NY=a^H!vxHeANjNxz% zu{Ek~A9qC1+9+OL6#PQ(M09G}%Thm^UhIF%&ll3t+4197AzfFEy4?|j&be0?MF!}q z$T0PegCVU?_L9h`-$6h-&8zEln08gG#DFOxflsJ$WwvZ}wC)cExmMvJehiY*ei`FH z=b&O`hdW%zGMnhV>5<kaef?esee3me%tq^e1UO8L4AxOF>J2$=me05%*<j7%IyC{< zA7&e`aZ5A)bz*Mdg^KLXnKI60V@7DV4iPJ>UH`Vd72)HS^r`yz;POt<iS(7ucY3(J zKXm1Y?sAWg2?uKr&RH-tXNP^~I6i#)4Hm~<cVg~~vCp5XN7|zQ8b)?(4d~kyI(gu& zY&)^OvF((9*4;Dra?OK3y*gs<zgA;aV)G?E&jsely%u7J80J4|%dYsBk24bk*)!0* zDr3)}_q@g$us;R%dC{VM=B9>I=ASy5svZ3ZB~hy9or;E)v0>AS(^p^anFLbYmY5(D zH0)sYgVQ3Cl!@6&O2Uct$LSEc1}N~~QB=*gFSxy)Q>R<_LCN|$6{=;Nf=xpMO%a5) z#%#uZKiC~dpo*h0SoCUBXUlU-pxY>!T=PTP@c6P5Q^rDiAq5!=6w6B1)5;CY&+(&v zmnWwv@V?|Tn6EQL4?T>nw2J6b_BQET$9ZV7V|urVfEbM)h0_kc4{0ASA*C>2O6mH? z7+f!lM=FS1HyQo<3vrR-0LRcrGE3Z6?2jD45rJoEX<3AD5eri;EwkKhl~fx@31%BQ zkMLXZ_bJeLpAy3&9B~ndnsW3JKq-dIOgC-=<CWt$8hH#`;ff3>AOQQtel$bhjL-t# z+9h423Ok<_Mk8YYJE58I0j=ISL+L@cbIpN_K$=X9>SUYQjj)81nd}hRS9y%D)yBAc zYZtri7XnIw2p5Zw!ZY0DG1g!uE=)5YmR~HGq@uS=43XdkOcZF?n%>8V_Z1cs4J#0v zJp3jngN->KHE_^c0tkW6K5HLj)dFz13DZg?aWJXHkivM+uVk3UDnuk{a%=Gj>~V;x zOC4MD5w9v?BsL6n-0||NCt$c}3TJr}J{KF`VHqna1-DI#ZjLC@?nmbY<~<+sSdQ(W zASRg&f&s$w1O-dWn@g{ti7_<$2;1-<Y_;BFEL`>(ie@(sr}&v%MM8|(LqRoKZVZ@c zAvV!V(V|e`jgh|5vczMxKu!xh%S^ZHE#4{b69X!aL*{ZTO+_M#U!3!iqd2CaGbMOy zD}~Ni{hRGjEWgYUqb7vc3bgZia30t$RJpkBy2U)rcrr1rcPpg{Q#lix(R^|n<>U~_ zLb9go8e)<@jwaRSnje^jt`b3|a7fd6>``Mcm8?n)vv`!XteHjxO<ZWXe2~Zy=OAE* zEUQkoGdGK0hUTS*Wr>Z_i_DgK=y|@Vjbd`bOnF)AEX&)?@xBwrYy`iP7`^wFB1z~{ zMsIPal?jhORGT^raW9!xXK#FidG|h&bLLEU*Nr320SKdbIvM{!o$UF#+GYmh$O96H zb--%*1yDuM7oNotj32j+LI5aD{VkCWpn>q+j>GHlRPj|y7aNC0oKxD&WQ%@0H5Jfm z_D$5KaY0**uCtbDsmE$ozm`J+dZcT0L*nF|(r%_KwlZqtieKuOF$_=j!3=!0(7Io^ znM-QCn3d`{#mZAx(<8@I-KFh!sPW?50fW@nrlqBhUQhj!JUO0ZeIqs6+YwQZt`{yZ z3Q<5(CQ5({IxH<b;^2f^2s4zb6}x%gjO6z<#k5y`?nZTW;z5mavn&{7TKZ(#ncl5m zO7rjSi<(kiw{D#>>^+7X`)euOe!uh+tj|AR?@M2Acco-XTo^58;u#>Ez2L4^H6(2Q zaNzjB$CcYJyTz7EJBsZ_)NJogQ_b3?o?R{&CM%zUV~$oa4jd?WEDwqdR{h)Ha{H4; zMpxAUD5Bs(4P^)1>0$wn;#fQFdg8X?6)$ansqA&tS*G08tf8C<%J;nU%)5vK=WRu8 zb=bGljfP?qIMK<mg%ny$xamIDj%j$ZUBvr=MjOk^LV>*>lk(H+53@i*ZZojm$zVmW z!VYBn(fUO?4YQ~lLUFd!$?1%28w;HJd-L<g&rla?lksdE%7?!Ob-#JhRvTP8g~!Uf zqlp%}fuimN;3^oGFyRUvzt{?Z1;5kqgCkmvEN#@-PSmSp2rGt~Y1K6acs(LJqciH$ zx&AE43N^b&yOqL9>AsCNzc>y+n*k>*kL9Y1o;DoBO@ps_IEn-1u0ewW9zX@1u5p#P z3stZIQh=RMwAmmqTz76k(RZR`fXj4>JD5vZ$_^FiVn1kH@N3<nQ!(O6rs^b*WGYX4 z$Mi8Z6A;9Qc%Jc%!uW8=&(J{O5q1R1JvPtcfHxHccGg!AI6ihOkhrxTV4emn=K@cq z7U5h6q~=k&9X8WQfLf309tFoD+6^s~VbWX^Uy;#NLE`RLgys3-TBQR@L4NqUqFax! zPqF`&bZBt#NCplTj6TndSQOjvRY+8TjK#=fKJ~Eqix50S#z1L_v_rHV?Dd>$uYtUZ zCvJ8LGmGm+Lx?ri9SR?M1rL4OO%u_qce)kGH2WQ<;Rh{ZR#bq(T*Y4*^AgfJ!#G@R zs-Q@+>0&@J>{o@?;4r$)U$KaCIcw<wJrjGh1!0!Z!frC()7Jzdt=Y@MBbpL!k-G2) zp8w4SBJ$yCC<K27Hu<w|fQ%w^`zE8W9$V}NGEC6djII*7=D<cdb{t@o#0SJpl|jKk zv&R!pJNKB`WnvGQ7&0oB=<njHLBEfD5Xp{z#5whGO|pt<V7=)`Gz(zz)OI??zwj4w z!~E~2wB6^Z5yC+_46v_O3|wz|k-!-`S*%$`oYEC9Wm-bGw4<@8P4l+ZqMewBmXM#F zJHQp}#Op*sk{B!;I7#yT&2;fZz7#^rM_(Y!2svs)TJ*JLP2|q{Oe)YA)FO>-2NAGD zA@>OJUv)a!PO@sK-bZz$mS7Y?TqS;-<3HCW``+fD#ZRz*=3hc)5HRIM@g@wi!58yK z;}yLC_=llJe#M^eiG;jKrpee*t8X%ikG<JE%-}}^l~<YODiOVu7b23JE_OP?$VcI? z0Nkq<SVsP03ExBBgBxOR{J2lS%==eT84K3?aAaBKcWcGF=lpyOA+g0?zg(eqwH|Qt ze(7}>*OCE*L>!KuHyOriviK=}mj~uGiI2F3G$l+(g>UItD~fWJOR|DfB%K^z0(m$s zVYfP20psyIoa|}oAnBj8NSp5j@7X^*bgH}3>8cgLj^!F1DfH+mX__=I_dwCvC>y(M zom98pK2{8B2xfQfb{*`3gnh3*>2ssqN7W-Qb;95ShI_v@_aywzJBcX>vKy=Pwda^% zhjZ8Djfi6<Idn?jxa_7II=q<yu`s-;X{(DF>^}HI&Dzb0dFAiPF*p&k=evk4&<tES z*6=E@>9~Hto2XUAP%W|b=3jJGa3q(?dv+fCHp){7B9(d5O$k%NTv`Cl={ci$wpk(N zE+>d~<jjOXV)c*lCblJZ_r!(~#EcLIJv@bOmtScIuL6=n?a^~)n?%VfY8tw-+2Rky z^amBGhtA}fF6^TI_*NXvWlx0K&z)gsG1owGcEumbidQbATkj`Hd2>p|YTr|yWT)gZ z;(|e73R|Qrj8nHeE$n8fX=P`nv;#L+%pjer(gUAKp?yMvMnmN_LJd{qV86hE$KI;L z{fDi@Evh&}SE}j1IX*J6%dX164zl)^jAD=@)qGgOoIj)#&{^6%2UB_Xwp;au+e`Ru z91CXg!#G3E;-9W@1TygxeB~y|(1YdTKt2UuE&vT|$7@qZ%QgGcg-9var7l6tkm_6| z!gz3v|7V&E&b4Sa#Jww|%sYe+rsf!*KB@)zDF!+tC_9v*YV}vxCu7Tj@pRf^e!w4V z3u%&&D1Y^)8T6WG%VUd)ihoP~b0?gKv_>ElO~g)xx|EeLT=QUV0vvBsPGhq+av;>~ zkJS_^bsASU=oNKD(aC~pC@y9R)_WC74>MTsl)44B0J1>JYn88)leFmyv2CF9Yl!Fy zKh)%4d!$hyre&JwEyK0?&O8tUlegWRz@b^QL`$E~(}qrW{5A9Fc}=KLpaH;d7^}Qs z{C;@|qiL~}N#7X@tkDXR@bJ9FRgAQS0O)cpc)kts<}5$o>{8lU4}-T{mTI}Tqku8U zp%0JzR2!EcQq)S!zs`H3<w%`{Go81sCfUB6rn|N}-8cpgmElb445f|xe0jJK@Eg_Q zZD!q9m!+Wk#BA7`)40Y*MS;<nY5u&LH8DFOH++)<%&d6OL@!S2lI)wS!$D`4kVC<Z zmw3*V3e2?p?#pw<otb;nw*+wzS?VEJ^?vo0P^=kAn|z9<?lNkJOc$M}XCs!wQjxx9 zd2i4aW|!D_GQD0Ksj!)8ZUO0%9TT$)E8nI2d1f3Vr2dZ7F<I9l7D6FlC)NKRgLKvw zcY*ozlO1AgK6WIIC-8H#ZUPqPhi6(_+cQ=YQ}6UX15c#AVDu@4j~COmFVRwBsSy7{ z9jO?GP+}Tfvrq9o6IyXAH+9@uovKOdb8>Zj5pbN^2D6m~iPk0JdCh1NmII3|Z>iWB z9KHI-2c>d){GkAsXbrDz;c$ED68#DC>*L?a^d2LHSDF%-q)NY$8T<*=EUN+a@vLQI zt*8XitRq1JEu}g*;JD6ATm#PrreGw}7?-a<$H2M9_jc2%am4{OyAfT!rkvV2^{_oJ zm&)o>OJmywl{v7?;~iq<^6kPsti7%N=R77uy+K3`e0LZC3?KjW=`H0W3|sar&&xO7 z%}3g}k?9ft>bkmh`s26P2ps3+;8kIfZr|=$IU3C`IpQ2mbK;lBTujxDZ4Go8J#5*N z61u+kTlKLR7Gp;B(@d1>Yid8Z@aR?hSb3WuGl=jOFuf)BtD^i_2W!7x{pf;rfse?3 z{}<o3(Lt~Kj#-aC;cABAA_58N!!{*LT2zlR{^Phoc<Blgf)w?I94^Z$alco=3s9a; z%Lz&miFuVEvj|M=KVlM9j8_0ofHR)K-ia+Nrh(!y<U)2q-XXTcZc3oeo`KfBS_V!l z-S+ixVI?QXzR6NL?-^X~H40jB6;8Y<L4=*gOdyER<GH_*m>Vcc-HGY`){i~lKVlCd zlKf%O57x8{O&DcyoHz~a;EOygFS;ko)C-A6_y8*>8$mvDG3LvTz4*_JmER|x_R08# zfV1EX3j#emz$TLf>+$bXX!!L9v-(+2IU~kUDtTEpHA0J=qi)iGPZKqgu=_>UzJPv~ zFQ=trl@8@IH*W+9)?Q`#Pr=N_nG*PFRN&BdZTe0Tgruzy_BHd!hRBC!B#ig5Zzo70 zWO9Z{#lsM`S^bRfMkWh^=i$c4NEt>E+st1kB{f$**eOr;G^q#J#f0UyYmi7O&7SWs ziztmy%Q$ud6x0eeJ9Rf?4+n%IDZKnjPJjN#+K6qK#t#+<M49!J0OA*~JVTp~>~iWM zGci5kjoPt%C0D2ZK#M<vd_(}5a*UNMuc!?%N&$2L>k{jz>$d{dHSIF73EYYhA6&?+ z(cD~|CE-VPcT657pxOB0E`WWs-xGdVT;x@Lnb=mD1#cN%(-X&t=*-KpAY`6SLNuQ8 zV^r_rJ$77Q^9IenrqtbO2W&OMR<l1UfNymQV5*<-<bhEyVcL){p{C7D+by*p$cN`3 z6CH?XFA`(`;iGoj4=3vS$|)PCY&6Fnv_IZo&73kQ2?>YW75I0{!@Q;hF<p-*zQ&SA z%4Z<}KiF@h@ElRcN0la#AROh<pFa$wu7r0QqO>!4m%5~chD97z(<_GZS;^Ax^nk>p z!2J}M);j8yi)fPq%q^k0*eCgTm@`MD#n9rZia<Ggl_Wj_#c|qxw*u3v?6pv$g8&B7 z9!DK|uxAK!zFq;^P}uPx7(;w=7AF-1ulJY<43R5?{X7IGuHMMXlL;0g7d%788q+y* z+5LFWvLv8Aad$-_B5cK{=afsbixq9nUy`M!Y_$HZ>$o49RD?8Z<Pjm}H)SzFr_?yu z<tJ7!C8rinY9e@=j}V%R-an7_a(8vy{ae?v<`|FX1{{oI9M_F3#$yxf;<gN<>$~nk zRBa}GTIQz{bT%$JvnVJso#I&P`kGGh6vCoL>dNvi{8Nb3og4?WZrh{4z7C9A%WCWv z*S6an$3vMBJ7emT?JG2MpSej31!{*ksxLS6hyJ`87R);J;9D1l*7v5okk4xBI$)8( z_(>_N&|svXxeJDXVBDf4u!IetDS6lLr#WrdkPZa|-Xa0Dh}vvT{hif&Zs0gp1L>Ig z$|__iHHjQobaNm(D8K#3MKrsUV@u?6&GuTc`wRfqgvnyWhN4I(m<}SM4qM2>i-oW( zD~aD3CMf+u-d3w?6CmKnwxivCu1*tU3lylSMnN26$|L~_2hyNsDC8fWq&)^!)rw0o zLRWHl?NT&Q>PEcA&*Ru=I!7R%Hek#J(1R;QEIiCVQ2?$)t6nS`jB9Wx4kQbgd&|4V zNFt&FTm%x7M1=)8y8yAXr4Sf;7%CI;Nn%8aBO+sa%-iZK8D<GcnS^scQ<l?975=#x z%ZNwmYxaNQmkww6<Jrdcjk9kcdq=z!7d3z_V1ByMsQy#@F@UKy77P??hZ<p$rVni( zMu~oNScerfT^W&1U_62KS5=~xv0pIK29fWDvo4QL=Y8<a8O@?QlWeD=z2?4#j+e|( zU(j&oLEM+rgX|byh)F!Tp@==?$V6$H6$;pi?sW9v_2!6D$M|vYZ=Fp%&+K<{)s+da z)zn#@Zji)jFo<SNme?JYc>`ZP_9QioVltlJDZr>UrWQqrub?s*wSnRi2<h8&->G5r zp}6kY?u01!3b-IRG{>wWOLINiq{VOClEwQ@y-(OVQmZ}gy9VqjeDT3jt1nV_GjMe< zvX{G&nio+{KcW9U?r(`#MZb0YxOeXZjL=hLQq7qDQcRtmQKNXaOs3s^YFRVFZz=Jk z=HB8#ir1v*xVd0t62*D(O4*Sn%YVs20or?vHiYC0_O5Me7~j36<z+RK$wgBFm@=j* z$r$F0&?sKS>?35Tiz229XKNIaDP~1jH+@N^iE-K2WE1VGh6YIA9Csr%RSR;+#Tzhg z6DUA%5lW_;vQ7jljHhn;E_1`xi7&r<-1VXQ*=5<c`Lse_4r0+-fPmqlc4mJ-YjV+v zK=>D#zRXpFloP{}!LDHuaS<cIPaVyhBck_k&FaA4YPq-?jhgQGalvRm5rS>TuY7Si zG14_L<1>CAMI<h{e52KThv9U>z*tOrN*N?4^)<2RiM=CyBq2-u1{`s$Aq3uTOl{`- zTjXF`_@hgP4XA{QFvUFQ7$?EiB5rjZ_ho~fc0eBeb=<p{Hw<h-<QRQ(eh2M{qob}^ zr4fu|j-S#&n-SLr5i^-)4Le^abvMllybCIWn<k4aE76#pzMEg~xXG6OZTW7}P)1yP z#hu-&wm#b0*R2DLa=rCyeQUup(%?77AVXKD(@1GZ>y!2B-qxQg3$Gg{jcga7`A$&O zbj%k{x?GzFwoF4XYCrI_n+n=;5_A_q?!CJ;^&y%b8YTB*wJ~t$%!!#(=4x7a>!L0D zM%PN87lT6A(<!R1W-*1Nl3D05wet@iMj}dIi#m!4Ax#=@q5b*%K7Juv^ld_{WhA@$ zwGoW{(#7K6XT_&d(n^U93x!rE0LEfU((dTw5k1eXG!F$YX_r8;b7^NZy9rsCNF=Xr zn&rn1^*gDmvWN1IvO=j4JQ*96jaWZZOo)Jr5)0kUSaCo>nDUtbkO9{Tpb3qapomSz z^{WutYy57z6}uU!&433ldU&CT%n3Y>2edF!NDL|c_7&<e_<P7RO%7dH7$UjO*CoG6 zF)Z~%&6`$8f}ZXz=&p*9$sU%)wEsgPnHhsxc!=aAlw+t8l6c?P&z5O)!$D_FgTj}K zDdE{eU|09*QRl6US@G_ux_+LTW^uJp&Mf$r<|OuS$rHd17tpDIHd8Gc<v6f|)x+VX zN|2OTN!F&0Kzxh@ay+IHcFl5W3*j*<WJo-n=ubeoitGj#lKduSlqXqP_-{>3z3&IX z0Mucq7#A|8Cy;0lM1a7AD<p^}S@ggp1|~V8&*~S`K~6K1z3Sz$g8fQ!O0>i7MC|dG za>KUW0y??oCX*Tj?Sz(&J<*SqukhMNuVCP^$9_ls)+~kclB;BmQ&Gn)|L~9(u7)hn zPw_Ihd_pN(g(5e5PqASQ*^)z%iVOs7&eAbJ8>%XI37QjmpN5idY3*XBZJ-9>7K`~q zI~PuHh$NKj-60FDUt}4}b7LwQKD@safqyaohleFQ5js2|8ZXrHtaQkjH&6K@^$iZg z&E^iCp*1C;ugMZ^cE8hnTfD>NwV6WAl98H2YMyvw@kPTUWIl~HoUeQ`dX%9+3+qud z=_9y4kFu0RD7R8GF=1DoH&$5-)k|0_?0MR#f!u{^7A^mae8LcHmwLgH92g_hx*lv2 z?awMAngqiFaftbA+aO-rfkYGQ;%R^RM;N_4DJ0f-dM;rtb_21@oumdXPNuL{)gHZS zE?Rmh++ND{)jz;foXYx_@tbJig%`b-^$WF4{1KpoX&7>|&0B#?8FTy)Lf;bp4diM& zN=RsF^9+2M#>^EZr}ATq39Q16ZuN|r)+s^B2!biSc9I<RE%TjDE{#6G(_7>9%Vkk7 zcu8BD@;s$O+tcPd9%=$rb^xpB<}S?s*fTrgvK#N*QMt=O<LV$mOH{9H<n(MY6d?gM zWnIX)clj&v2%f?H{_sc*v=dj{$(=;SxyomyiLwaGS=Lc&caL!toVIw04j2maW~BPT zAnle0WM4s%_YJquUyJQNGmbzFk?4WD$0b*S;nP%&Qr@hC+;HJvK4rRJUS&E*pr0Oh z7JIUC=V9fglUG(#Hcy0>!9AW$9Nf<~0L_GOUS@A-Cg-Ubh0f#m;UJZ}<QLAjPYR`i z(ned%VI#^CMH};oFm|VMljtH<^4`!@F1A{WPCF5MI0nJ6tY?dm6n}xCV7rq?47pH% zcNz269;u@4LE~BYT?Q*I@$=ks`K;Ym-s{DXUe+&82O${7aJ8>_vrPZmA8zO6i1}V` zi9wh{71Oqyb4sl~Sa7hZW|5Bm>SV%7Nhd0!jC48i#J-H@D8%_N+xU%Xa>ITF2HSvx z_z^Mv7Sc0o2z@yeXO_j>B(`J6NA=!}-!fc8hDsnYApck_+==*$Qr_IrQ{%-Ct%Sw{ z(u3L1PzW<$4*~d)g|I+Q79<++p-tz37agh-qsS$7V#ks&NtC=+yQPal^7@5n)KUt2 zOPr5}sQ!e`kci0nDS_quK(i524R*OUDrxdaLhob(BMTwy|47_p<*-yz5~wq8$+`dl z?S84=2=p(R;ia37sy@_A?<;1cGuS4~a<%Q8dkYAQWRj5C?579^>BVemF;R*)M~Xwc z>N2FxtYxgG9UOv){IU>nO+lJSuGeOlOadG!Z)a@DVt_-)6b0<BOl50aYu^v)Aml|) zU;|*I5WkA1Hm$n3TDhV+V|Z*OQ04nUnzQHhFq1+7*tuLAf&JRDx}$k>(RV1}3Giqc zkBY1lTT%Jt-pXz5Im3({Zwo^{xT-jsY|dU)rH)(c!uA671axt5VzD;Aesrx;L{X1* zaWSx+d8FT>i-H@2`m)D5c3tqjhPp<%ofm{YXix0>(vc=?cQ92UDX1c>8{1qp(N~5x zkS*9sF5lI(6M&c947RQ%jv@fP=tlzsbUpfjWJ4@qJeARvgtFSf<{H>dW4(1Bxt?IX zJMU%u7(__09_3aLq4mWxCSKBy6QPTa050<UVHfX_bhdUb-jU{}ey6>y_Hwp8=W@cc zbc6osNM<u0*EJ|?%q>goAXU^4n@RzEt9heRs;|(&^PEAh(C(M@gHtt!pn3~MMxnuS z=$j*8fcxBvhS=^L{ncE0;Yc0UK*w@Sy>sn+yv!alSj<m(r-YmW=R!!I(CuxcUS(SN z3R~;Ej|5onaSJ%1Q5O9lvyuS8D%$%DzR-&I9?l6D?jB4TIZ<vcuV00#3Qj{SB>BgF zX`k#@YzLRZS-2JxJEQA>52=Q7?0C#hs#)o2_2yHkV2!6;XPJTt5G$oJ{_X_Ri#}e~ zCFce{7$B}e)f@Z#eXmI(=y^XL6G1X%M#}&DdV&b11!~gY26HQg7ysPO904>$8m&*7 z<@+PprTK0GO-}(u0(($eAG2+@mZ0*79UFQneCX9?>h6T<hy`&&6WT#dw99)Ae+tgz z;)uU$l4Wy&dEUsenSGwUKIH@w2xsoWOtcv(1RA;%uB`@iQ8XA7pxy^H(DL7+^y9uP zX`1VnriLlaCDaX=zx~XR^3E|P!E%0v#x;Be+bJYYe6HvUD>F!fg9Ya6%jQ;+c^M-T z=#af$Ovq$0YdpQjq~mtZX+;AW6xxI->xSX}H$>4(wY=g}3(<xW(4j__M$`4RF{%4@ zB<}^*MxKLqj8;DD=p#8dpEkXx0!Y;x{v&`ear^-J4@ZCw`sP{5Tyo-7n~<Rt1XjRY z!{D4WX7dzmlY<rZL)%3GMD1hA=?GwIx#Cj}On>vD*~Ml?QO~KJ<{qg_`x!$hj)6hI zViay%8^Rs}z8>R-HZF#8%GQ_XUN#?Zm^s5%A&H@{Fsre{4Hbka4s$}h;r^}3P>~2| z$9BMt4D&D}r@0C%W&(%^b8-?mTTeE{xS!it$nj<wEE3YMk+*<6!3ot@d#j0rY}th+ z4`N1a8T;!xoko)z@JLKG6_RJd+H|<fMr_P)SdfCVFL9YqWKCKk5)yQUQf%KgEzK(K ztTZC`Y03$rgVVaY*X=S~XZBVP)TyeHXJPk(aU<Y%s!dKSB^Vz)OKD^B{(L8bfVAg# zR|f~tc{@{bquUpg<*%T8NJW^9pX0~vY2KOR?>?tC_wn<)bo4Q*Nf2QZ(Y?-@A=^=x z4v>fD9(K8_lhSEnmwEIT%!erFkN)+p;7-f%O}Q;gJD??In7ep8aG}S&H|UV1l(Ly< z?hx16<kK3(z`3UMza?+_`j*P5gQnG1WFGAxz(tym?0{+}QQKHAV>w|iM=oxRR2EX| z*zECqn$EsmcH}lQTzDp8NDp#J9{%RQMxjAoD@0lA1R6;^Fcd3(K%eBo56z%gqqkU= zyjf}$<J=o>Egf)S;-Mc#qb0oTYw`w<hf-!EWR{nt5TCg;^aZ>s4Fn?)F_y(P&c-*0 zE+<9BiVOx9Lda%#V;jQX5rA0WoiOXQt~g&?qF7zAANjTesz<z9qLfSvt^l1J0b_L8 z0-VOH!Jh}SARej98nh)1rQ8}y^BXxPfLJn)6y3SyVJ^bHz#!m7@Uu1A+F$P$Mva=} z!Rt-wk^hw$$H=48XcG%X6t|IBQ#lO#)L;64n!W_AsWbf^TP@m+iXE+OBvztv1Ey%J zXyDc<HUxDdxS$Bq4p2&UN<k2!m}{}EqHQ9HfM`vuAfTvJ6qQBe9wKNeC<v8J0ufLG z2?Rot>;HV2-~X9s=5Z8~d%xvf&U@bT0vLr=n)%W5zzJ6fEb6-ZN|4Y3%r_SEd=QRz zAAA2^YT_7o6)}(i<sU!9U89msh%we)l+n6CN#^dX{ri6+&f)rbf8}r=_9*L6>2$yS zQpj4LJblFl{}lep=@zOr-xFk6qzB<|Fz%ON@iPOeupOqke0HMYzh7BH{{Ikz-aqO= zdU4($VD%HV37G))%F7=8b<+)S4nPix(Ow|2U3K8|RG@zC5teQa*j?rCoD;1*s*?lB ziX9PCgWZ@qlt6k!QMMy6*OKaN!UohW`Mdv&Y}aXo(WFg93vK$Hc?yK!9+Z_#RMG~9 z9)KL_@_k*VIiv}VEDx&4s7pXe6LlK$R|I(^yud@eo#@1ozH+*78WtJ(y{V)CH-5E% zZNG2=b_7-5JZJTCF9b43Xq*~n`oS<JL$9CMBeXT4an#8hngpd&Ml}Gpl{Lp-kILMP zdchT)QH)7<ph<Q^@OK#`HI9Q5kC!i563Q<`vE9`dk6Hwib_ncs7T7*0UpW)i1wG0h zsBZGfBcttG3ka5*^W~^h=-k;I<fKC4@DwH4Jy{OC7~~J!08$pfjzT>u88ukY?rbE2 z6h|;$oCuUhyOI(MViY8sq`(7s%F*JE6M=xUumj$17rS@vxv{`s7L&*vJiF5Y9iY&A zr!T5q^X+R;??XO>#<;bvYpp#K2oldifu52aXFddHY^;H(g*V|J5TKAc!{=k^1SMk5 ze6S}nY#K5S%BZyts(cA;u?C`{z!IaN)i@ED*_*Bu*;uN%E*5bc44V^Za+QEn(3k;u zGJM@W7hD07Y0ec6cM!?xX@V#`=pxYD#scPoH~2D>tNGlS(ee=^W41RLZAYsyHK=Tk zVfkxsLMRqZKQF!<B&<Dmh?UOfNTd0-r2hn_?RGl^&Dfc2^}7Fj&sHy=PlEIOLzy$- zm}j3j-S++(kX3iA!Cc$mRq8t4J!mRJ{0hn-sHmiU|2}`FTl55EntK7#tw1~q%{%9- z-ut81fpK9iC)yi)ZSXSSwK>aSsOCq%e@}>38OZ%rBE<Rvhjk-(LVRP-qWqwBn5s^^ z7gQ0~zQ0!fwNb!Fc@~P*B)Sv=U?x@9eELit^X8kJd|dHBgu^(32w8(EQgE1^*J>r) z8ptFO3>3h_i__<qO#@(=;SPQ6oaI$)!u~77xq>>*!9GFIT`-79TsK&Yp(|wpp8T0? z5M*gj-29E}5|BKexc)xY_8(l$^4(I*bcHvN4kd=YMu1W>gdqXdlUePAWO4$LQ`#>< zU)~eW_%SSeFbMjHOy7?iqUfGG2*Q5LtpApNrxXe~$va9<EHi&395QKn&|B~?oUJnl zq0Vmv9}By6?@xD38g*FW6*?4x2usaHXr%PYoM8SI=nwY!Aee!A!W*NzHZb=TkT*d3 zhhU|<-3qc@Oe|%$o{Zn{2R|qD;Ydud(jNZvBP4&-X@PR)y_Z`s)VS_@RWh!WYf#PJ zm?wASpdmb*_Fwv@`&s(0&kW4SskZ(%N_iQtoNiyDt;5T2*63CBh`x<Wp407NBfkiT zc5EdFBr5@VHX88XxF{1dwE;c<s_DwJH+v*1`_FxP3PE%&=_fij@K`mnE);=O7av3q zA_8=}GvR_%5{T&qE&P6Ih%CVDdj<--3kx*;bO`h!{Tfin89epw#_fwk2eq)pJzluP zk0<y|YHp&7E64=j{CEut&bBGsUm_Jt)7umRqG)A%e?<!`^4|BMY8XikCBoRJd0TGN z#<_@bM`Lg*^cdn%DMvp#^%%9;q_{h^Tl;O|Fp~3y^R%)(Yc#wo9kS9&clKx^LPJtI zIb$I?EC56R<cWUHdukq?!<*&F_|slH|16>hp*zWhU7!IJ<FANbSMxfJtYw4<D<@`7 z--yVZtF&I}IBmos-wJ!>k7~#Ss(#tb5I%I9ThJ$@g<wAmL7i;v;I#<5t+3^En-CB} z3?b&B5w#2|$01<j_Ixfw?$l~ufND=U1_q+o6%E)@!ABqjOC|D8fWSgo@KzF!Rv~yx zSSv<f^C=$CFfmEG0X!bUI6aVmx}jeTVQ0cfKzSxiZaGT9aqw&?kr155iC{_h_S6up zXCq80uY4zC(vkjFCrD@JN%h!wM?<Z&8hVoGYGaP9L0X7t5d!l-{?4G<19!Y+BJ`E_ z;(m~W3dtQdDm4L_W5qFuFm#gLuE$8eYZM&?(BdTd7OhtBOVixKCjht{j9zzLwm3>z zV{F4;VgfHwt$>22JHm}inbQ~O3VTv)x6w<90DYq+Gi1zB;)nexOf@I}A%gu}q6~np z3@Ch`8UywWqG^(sfX!0ww5J9l-l>TqVgey>V(Eqk1QaX}<4^&4>{=^Z#?MCiRUGZX z%~)eW;Vf<I=LVGQ$v<RpZ6>riMiWd!SfYWN8<fNm-5pxPRC5r<8<!!X&7V9sXuUg8 zp9ryPAyr<dJ5Q9;V$cs&WbA%_E&l!sc)KEYw7jN}xi>iJKTz^L<yVc*F0lUs1}<E| zbTVsd9DhA?i-#=(^LUQ(Ycw#Ued*Ac%|OtC9~p9iuVzE^m4MzU3zwEbDLxG|qxyEw zhL8;nqN)4YLYoiWspf2#LtO?}q8wS#u@#uZ`bIB#o<7d;x6w?Jxb<9?&}qw`&@n?1 z1`lE6SbE0urkoAemb^1-6iTzo3{GNM?$fu~kUJw-_`DPH8#`Xmm5k;Zd@$w@M#+jd z*t`Zj1`|X(RyEj13X-0F>a%3tDQUYlJ?fRyVUJ<^MbPSQs$8|~Y&SV&PsC3gW$iW0 zK6j1&Sv*t9e03Ry1Wb#OwQdkG;xKm<!UdoZauO{E6E6IEqM~?Y&9#|O%(8w)*ky_Y zOx*jC0WI^DlRxR{-XWaEU-&Qev7qol<r}F%9GPfG9I~h|9eO6(A`bA<xmFS#IcMwD zriV2ZheX<eT1!&*>eTlK-d6TbPpcyecPY#c1+}|nCSdJ6H>@DZd6N0weSTk5s~#h) zt*a@<-u?X6IZFn^)RX6cY!63i{r6dfgG+nQ*JNmXiwVGl@@nEX&u2Ut@gSS8D4mjk zMEW&sL8L(VwLX5Y^=yt(s`gZ4L%k)@PhDo8xVpoo(afaiWGe=Vc~b!DC{|m21=9xO zwMC+XBD#0_9-RK5`)=*uq-0Xn#ov|NkLlBT0+?39-joFJ$}hiidb`d>|9xr(AesPN zotKC35a-(-+D8#Q>^!5q@Mv;{J5!rMcp>_|$Pr8DV$oxEj>k<u2$3vEKC7Retckss zvMAdhx-=EV$2lXf=QpX@wp9gWsTI%);?Wnb$zcQ3HWP{r=unqPzUuT#DkvB&AElW0 zJ@;&3XHZRfq+YQ>&KURkO&B5LFAQya@BtfvJSi6^D1FeO$RHvs&gG0OXg>wK$3*p3 zZes@KKBb*gKOHL*Oxug?TV=!b3-`q5Z#AOD9CxV^%^#TDx8jx4&Ak4>Nn+zoh(anW zWg@&j`=<0AzFuROTlc}y%ZK3!Ck<!v+V7=a)dlm%?edN5ufDmxMC2L^>3DR6pn7GE z30<A~asO~*B-AWCeuV;R%&1lcM-j_kY!S*4Q2JFzY~Z)Kywwc3n%F-f*Fyp{6_$=u z6h9L4FVl46;HIg(+xDjiQH;FuT>tJDI%$cf^Px@?5q_)f<&-KJ^Ujo2ut@?dRFF)- z&LnkTrU|JRS>8Z7#bH12yXfnbLC+k>{oTh!<}d=e7!s^qVtsSxN8|Alx3eZd{4YZt z%Tiigs*B8@Q5BLEt7bW(Q$D+q>Qo~3{#~)=+4I51)?o!S$Qu@(@SWR75B(rOST4Et zM9~l|BgKV3N!g~1CoK`-%$~G*<|akPQRaW=rL)AT8R|&TxV5?y3xe5m1{RrFq`+S# zM+re3mJTm4mmXQ36z5HiWD(h_!-9zKZv4?35~NLj<G?OGA?$l_q_lkj35ekG;~yd_ zNd9&DHJQtcO=P~$g5iFGV#1kfM`ICqB<}QQ72J6^!e1}9Z$7$<;M}}6S)hV`y*KEU zQ_ZYiqBCZ34Qaf*`K<wdMi;;RY+#EBDzQJH%L#<k7vc{`9`sf#eBTO|5MU>3z>>IA z_|H!M-5}ei18-w)_>;@E^xqTau8{t+`D3a5o1+vkqHA}{M>chwnvP}gI3-|P6=2a9 zZC8y;-IfGQrJd9%&@`b*OlRSh>AAZK4wwBWHN^Q=#Cy2r10IS3X?p~*XCZl7QkjA} zj#+A(O|khrMGW{B$RsEVd=!&d>$kL2wz#b>6_9$odS;!53rK<Z<(>Y18<bP|{mHjW zP)qs>bF@()9D>0ZS>yLHk{tqBVIs$|NbBN}z5rco{*72Rq{2L5gbPqhn{!ZHBVH<_ zM+S-f+K_S!xs|G<&3}cR_xn`dCQT2<v3S^qkt=!x&CWN%cdYnHYM%@cClvZz1LfBB z4d#e}+cK(&sm2EroLWQ7KnfMDos808RMz<$IF(W0HxYQy>sxDPAA72xpB*Y$%<SAq zb?4DNwMxhzF2T#Rnx9j>1=%xqWy0`Wcy_qU-gP$LG7*U^;lfpc8?nXe`5g?*D<|Q= zJ7;9*gQ!M!$uu%1l;lsi{4jEfO51kBT75OJ9*+%a?0dB^uM@|<$CLM>CBjr!CA(HB zH*dHi9p2Vk{}}+FGC06EsYB^;WzS;jn;iEvsuTi{ut$o-ZIb6BW-2Xz1-9{7bf+4K zLI7YhyX_Qb#C@!*h;C}3?b`yaAG$PNUIkzJ%IO0>54|j+9|WwO6q-fuox+<f`qF5# z*w$>}keT75G2pNj)Xe+b;@R8Q0xj=~3WUAqK!vMfCPCrGT3v>iY&4yxQe4YZwi))c z*`F$AqaXwD1SK1|%eC@$!){u{5`T=ic1WqRf+!~W+L)^!&$z}eszoFD0IH-Haf0bl z&veH1+e>~CO7OH1aJtK`{iM9nGUj}_z3U9FBYp-uL)TF)>tk&0im_;Hh|rKA{fvw+ zA0D*qKi}5ce>RbG1%pCGZ2)|=tjzyVd;Q!TRTC7FIK|t`>-^j-Y}m^V7-Mb*PpN0@ zkJ#Ui{MR{~IY8KQMMkQAt0VLS21E}*A;WU$ob^rh0d<?pJN%?qPHv8}jVz?Fd-L?V z#MbfZeDzp2e=K1<Cdos~Yg6rat?zzSepzl^q?M5hMk0Mv&<`0qnXh9ui2@vJEFn$S z5!IV~?VlS4b{3C+el1n`{NPrZfK=0LKDmOVPIas^Ir={C806G3Q1GKil>P3{q*}ur z#`(IG$x}|OoH`CK-(JXp3(NwSPlYhN8<C$*=$R&cPkQUfO15bN>1pbkDSYGTi6+o_ zPoUe#t6B;dm@kgrDYbdTy}@_RcK#XJBH$H3m*q-kO7`9YL=`uGfa;eC(+lnuUAvz0 z(+=O0kKWrQyGgkt>U?kQE2pm|OADvVSCQq#mpf-)yLwG1C6c0@Bi~PeQ3~k-MF}*W z*`@YB+Dc74sY|F0sb=Aojb`2v-_KHbs*yv@%Se=Q#>z#yYK>WLmKJ?Gpk_CE9hZPF zz)})P;;Xo>fw&-#pRfM}^?V(wYjL^Ehx-`_f?40J7mhw33|qfT>V+W&ad+gFczfC? z5^hWsZ#|)IhhK{;kXAkXo;)NnorWU5b^Uj(mBinj!8fCRhbo?uS+w$%(=R0hUZYhn z7Cu2Y&tnZs5efMOm34Ss&0W#&^xM3zlUVG5nKBwoo(jf=@gZf=dzaZaR3E7kqwWP4 z3}2BT=rmww#nC(7hhd33z`Me%U_$^{gbt@A)9t4#gIMu*yCWU-F&D={Fg+;R-2P3x zS#_b|*K@fS@k%7J+Ngtc>H6vRBdI$%vSs$8W&vtQ(GBRD(Qo=w{AlwcU^t#0bTV9% z`<`maf#RmfyYv;)r;E|&0vnplZargB{&3;NTDf`Mz)*vMa}iCms^$V<b*e4a=_8{e zj%4S~4|L>bxv*%Zn3TCtDaqSYy(d)B3ag6S!9JY1nQnUPE|J6PKiEt^FHepR4S(<p z^+c&gyVQY-56GgziPYIUw=A=|rquTM@a)1>B#+v|Aa_y@CEcKJjt;b<?c&)1^amJR z7u!IK1KX-SCFQ}2=NzU5r4ZPC%<8sUR{UFMtQp)C@np+wKYy9<*+&~ldzTv;gb>d| zj2pRCF*Ty<_oMfO)V~+rtQKdtL}BW!eSs16MEmes&PdU-9PGlup+N<bKa*S8%g8%B z6lEM`oJv7D_7rlB5#wzw`jEb>>U-9lgCfXS95xaPaI4lDOWGKyNdQ^cdupUrv^NN6 zT*f~y!aL4WI0IN0l58;P<agX6Z0_4(EUK5(dKx<?b}B1Mv0y;;Oq_GM*SBe=4Yg*o z9MkKnmvnl%BXK>q_c{|}&Qv2psL7l66Z-;vV3CC#m4-uZ9raXw<Aw1>pc{v3AS+<( zV>-oUUs&hd0aR))KMzZxT`FWA9LEV2rgZ!^eP9j$0&@)TW~|0jojr69Xe?!<W>M{j zQ=x4D-S=hqENuXs0%bxq=3|H>)?AwpbIFf{ii%a^*U+hsI9Fg^H-<`n7R?`G9<Xf* z$ED^K0k@qQ*XY)d^wiggo-?yADF1V<ly8x0a;RwP0~FY|QxydBjvx>pJrdRW(Nhr? z&9xOgs2IJbi?VOCH;d0B8{ppINL9Cy5V)xWUgAj?FjL>HtIlxQe~!~?w?;6H!ba_% zyS|f}*m4tdkNGDltzL*y2uF94*!q$q&AQ-nz#|fkJ$G?MEwR)qr!B?x-@bB++R0Wv z82CsvyuERZ)Rw+lW1Zf#D!xmVzTlP9_s(DxtT89JoDE{)YHUZP=IDW_gQQ338~FKE zJOJVLDgMfm*8T8)%^EBRHc`X@{_|Ty??Srdor3#H*Nh5A)O~|8pY*bQ!W?<1`DkRn zKVRte-p27z1wH8}Fq2P@G;U+2?!5!bXMzAK*IKU{YnUPev+dgKhiog7tQRY4Rj9jE zF9m+lEIvoQ_&L%&+O}#=N1QE1%J|?JJTBz0MlQ9%5Z|pIPn&maez0ulG<DyiJk&4N zT$`=b%4!V`J#qcXrzA=_VS{C!I^_<-SF*DFA{+vsCN{R0F{;*b>=_>4{H?k(iAC4# zBje9}i(h0He37KTf9|4j=acDZ&gv=S2<y9(nQI-!6T(K}9ajh~&N_MlkvWGUlR#fW zqn|U9J1i6W9cAH|An4*0KQ5!9n!N>X!jXXQUsoLc?|WO3`Se^=o_}zF+cNNu4xNwh zKxWRDe<33xG}qReV_An_=#O)jI7XRoLCYn%v<T7Yp59G?_KZ?5&k3HkFLI%tW~zo3 zH3g&nT}XGe`0fr~#$8#;{=UzTE!sqzla?}fN5^Jk!T-*#Sa5Bbj&D+(_1kD>*B8EW zTGS<uXlCwBx-nC26DB@EF833=lDq&S#4|^W8{^iahX^rM0L*KaA`HNq6@SPatyGqH z{>Tz<sE@lHW0-O4gZm-EC#|<$YvUa`tIH@Dz1q+3;@aNLmHF@bK6{(-0y9;(9zuqz zLhCVADT?tww9GntOGpqRyHGXIgD8A*xcIE<#jbV{C!=-EBkAFz><sOwmhlOsBDLdl zDm7lEIF7rQBZXOCDRVhnYp^IYcf`Fon!F3)cFHgHwSco_^b7%I#5Qg%&{{b?>(8rS zIZY~>${;zL;lq)rz}q;;bIUkn6&I@^-oiJ6Q_O2EiP)nL6VOE(#&nZ5A6s?uN%7f- zed3k4c^=Jb@IhZbp)gi*6e$+iYk7Oj%O4e#%UoU-+O9DAQ6d^zrK~7^Tundey?#mc zZDaD;H<SjYAH^)f<WcvLX)v9;Lis}?oSTldJLkOBo48Xcmx(otn5cO5S@0(eHS!lE z5PF#Ty-VZd0G-Uo_Jwl>Xb3uzy;ni&ezb`DVozJT`xCEEZ-4aJ_bc*TP!JV~PW^3O z(ZAxJaca_5RYc1z9R8lNsZ>~=cn#k=L&K7C6d#u&qAc^%aCY_zSJ@Aq;ha}8+!6r| zyzG@zycMD1IbgXUjrY7It`d)zf74wWf1$vk`~Q66{y$YE^q#RhdG<*5&<HhhL>m2x zeTPzsy24mnS*iWkRBf~785>qt<z9_zKSQvdV?Xef4AbRrt9roFCV|n*%ux|J#cju~ zZBC-*Ap|^i`IXb>r(QX=XWKqD!PjiC+^u5{Q6u}sccbj$|NHn#sd>>wNcw%+h)7pV zX9MlPvnGa%)uUUd1X*^xVEmPXH&v^rnAi1(9F}O$`20KPD%CE)R~5Ah=f{1RSGbop zc&(rV#dk7?dc<_HZIa1rmHoGcIi8i;mw%s{4v8Cn23w0zcJ8hf=2d?kw?>SH4?|OU zto`XxMDUIQ2brT=xG(OsMgO*Fd0|0T@?PuCM{(AF+WfwW`DeI(sn)hK!uGA%drHF} zNH*dvd$})?{}7H<Y(9Hx86o0{STKpWvFF67tXGw96-Q<CG}MX>Q4^q=6M-|jFxAg! z4#@sDia^2iKtaI^Lw}#o$%B0E;f_e0^gGzm?2?1bl?v*L4TXhYeE-T#OVK?podbQ^ zE4o&;22y4S4Z)F~HL`idCJ}XUXf|9ni2L!l!xmT7zrVjWF4fyOd@tkgGjuQOyPutH zZyQd^+ahjixh|~nO7lPPgr&3134QFaaOG2R6yG{KWk(9)7~eXWNnd1A$L7-|hz2`K zWfOGeCYXVZoNcg@tLXMMwpp~tf`W>r(bTi=1ly41`V>;_>un#ETJ-^zH&upDBdS4( zf057Lv^Qp$edI{?i_7gPhFqgxGx4cDTze~?5=2z%Cn^70Dr~k_XdA87g?jYs3_$sc z;YXZg_ZN%byk2DdHesIXF!k(fmD1XmFNN0G8_{tW`SzdGeQ}%qc;$3w-Oj1<A;j(T ztkU}*z(KL!(u{SBN)Ab&P~_DUH>f~6b^(?!wtv@e>TJKGBvJ;Ar<u$AT3kD!a#H`w zFS%K*pGWyN>3@i`?Kn+G+up#W<G8)eiwsGo9E+`I*RS_RdtNXdrqeEsy*DO>3s^hi zNI}s;Z;`EXB)Q<%IKR-hS={Y+_U4dpro?Dc#+S!7JpZYl8sl|tMr+(30&n|$Sl&;U zyQjW>`EqRNv~dj|)!ZM(Cm}?B|LP$%>tA%VQaOpyZk|+nQMUBzXNyVv&oXJyz^?9h zzB&9*Gj_+y1XO-Cn4^=7q7=dJ#cAw`sbfmLsf@h4lZHhS7r9+4J5GNf)@BdX9N3Z@ zc6jvfzi%LgxaKO2`PeF=-6=oa$dq=v6qm;JFe%9q3g>7Hc&%lR25c_<zcbMV=JzLA zCIXTHvuzaGL}1AnDvI~DI{mlHu3N%$oq?*`o*1lxYNhnqE2rxbL*g%g!{%NdOQ4&O zVS;YW@80RNx1MV|GZJb=R!g$%C$X2v0CSGqLibW|H5cv8Ys*KLwx`rmBL!!^N~2U{ zXd2;)UVDx#Ueo`HPLf#rGD@m5cCFx_av!Pd{})ssbGxsF(G{)cfV!CB?u0+hM&`@Z zHO@C$-@3)M{rHv1k)=dDCEU`&juBydQHW%z&?U4foKQP%u(fQ9QCEC%mOb~{dz&os z{LHtHQjf2mEqH+R7>$vFRBqbiN!H2ZaR&;r&1~kTWTQ)y)-rV<#P+e<WW{IzBsMP= zFMu4w6)8lq%5bEG%%auH`mHzXRa^E1*CsZ4+Em^F`iq!`iwqHixy*@l>6Dw+h>}g} zJcr~c?<Ma(6qt)N)=jC4N*l2eb1?twiFH1HK_#`S%+Jj$RsW?r{g&;y?&c<`7kJF~ zhyfW$H2F`A3nq+JA$#{=#6{7;*iSU1N;T~#$n?S{s4|DP;%@P8b@Q~;zl<*tZ*$5O zb=AK?;uU;qPijltYii(7vq;BBmP|AePai1O3{QcWJ9}P4irdY_I+^ceml9;1GapS> zd}EpGJMa1r%eYN#e-)%bV(5zPfUsF*UjQV65VS|PiklS3(l)yN%yAXW(s~B?A&Y=b z$U<IzLTaw>Z`x)5FrbA33W76OI%nsir-cuKt=tEbuZ>e+HcNZObJ&(F<#V72Igd;u zextGOl6O7|mJeg(?EF+D6f8wV_U2bk+?OZY8==v^a1M^F$l~_Ry+4wyTVhc<i67aq zQ?-Ce;j=Z64pio>kk|O0jL`9Zae1rfe3QBpTF3xp!`#C2lvK|0;@wGe2trm8S4nV} zoLEeCyiC13`}MRudSHeE{DL8Ng=y0NjpI3me_^pJrMH5Gh)=7a?gY3B)s5~1kz{D8 zn~;60Iia_TB*KHpuPRJ0sbn<k$gjI`jnu=1;Q}D&AxKtXbp8fWtfE*TH#f+c4d1pz zK-(7=5O=?|JolB;JAd#XhZ`F)Y#5fU!y0)}or~|!Yu~%S@3?h&%g>O?!-djW(`Rlf z9Z7lybQniwUN?Aa;5m|mN(^e!U-YeS!-1@FS}_a^dDv-zHL9m2j2@VSiq^1<uQELR zc6eUvi*4IgZ`(Ff5W#idk@-_PbI!+Iic6yaaX0Wh_ZBr3c{~3XcpF?H6F%8E6A0X` z@ZJ)U+veZUQq~8_0WwtJ^dzQXhatyW@c|k-EwQSa*5$cReVIEOn72lnQgpIavr^D6 z3-Q<`a^`*MfxfdH!WTJYT#m}2H?C5IZ=jnxZo?IwIge&}3_WP=d^{e}Z0porr)j^t z6A(H9Z(ugV2F(nazjLplV#W*lHC_l*2wINnA;rHFWD+T6Aa|6??XQg|=01+f!CKE_ zGanwk4RsLN2BHvMSF@v-`;vNg#a6{&<-qLdROMX2ajZ{0-{%*4EaQUn3q)zCx55X5 zEUZc9;>W_^4oUOgZ6$tmzusuOUAhNyU#y|(W^pZpKq}u2LM?Tv02x8AP>#l~<JwQ~ zzLCFjD&9lz0|0ht_(m9j-iUSI4o}NVdgauw70;GAo0wZ;aU_ali;$ZWPB8d_3Ky7x z+Y0}Kf|<qkS5DCJ_LG{^27Zs%aE1vg)j|l(k0#l+4*ZT5(pJV)jR8XVk~Mw9?D^V& zQv2^oM>o8*RbTxKIuFpr6RBrL!0*um+@?I)QY(7~sO}7{+PsXq8~2d~-+sG^_!k8C zY;g|vuJQwdt>3POTn;w)`S8xY^R=7g=H$nf7L<F=qd%~(&4{>H)e=O#Fp#cL8|R-W z^r8FiDJm26%O#l8F+b(zs9?H07#)37dvr<(LDkbQXIt+xVfgTufxg!}b6z}T?iV{} zb9M}}(Wa@#NON*C^utIEc>FC}NKiikO}pSUS0}?ag&fchI0NWLjy8u#hsLhc4K$=j zLeJ(=fy_ZO-v}4g-4)a~?3FR>TS7I~xAgEOhTGSo^T5J&9dCx9rA)ZH30#i*I{-$Y z5#JKK*~NL^&=d4KhAL?IH(bQNZqtY~v>fG%V4@<7WkGOOlgE;l4UT1x89c=W7P|tx zUb#ILvZLyL_N{HptoOG7ir#4%GOZlVI-A5b7%=M_$y%`-w`n8k9T&WD{*)*~>vnP% zD+B7l(EfZqE23ssP(E{C{QhMLwIE!!*j++B6>ziCLvroMDks5#4!Dd0N5qUy;Sg#f zC=oC?($DW%Ca(%)L<sYQ3VH@=w0LG(X)g%oC($4WR6yVnwuU{7Cd#GG^HqmOi<zl) z*AoOw=$o-%tlKU~Q132^x4khEy9KS?>2$papKiv&t|H{dR($@_QwZH9BFt4up%c<O z0J*?>kb{g_Ub{xa3Vot&>L*L$ZVG>%tWq(}X*3GO0=?)n6c*>A==#cOLL{+i?H@y6 zA5|YdWxoifddS^62-1ZiTdl#W0HeHp0-p*Ls1LIU%4$pA<v+E0tJ}5Ltw@1(ZFd2! zILEiODzlWm+s`S~!j8j?a;PRzNVv2F#fSkwjEA1ruJp3cb!idkEk_Cd_7s<225mzV z@+b~22D+>$kqU8W6!viVQ^j8EqFIWl4<F}c{ZrhALN-AC1&y}E*irh0dS-XU<%-Ml z)kfQSP&Ul;d4w_zLR&gU$0V_SKw|{K@gc1Q{4rf8>zM$LwULc}5*h#BRlx=KE0ry~ zdgF@3_s!Yf{PLP=rdad$N2<P#(N|8}a1t&h&9nL2j{y?(tv7<VW-C+o^|nRew+WGt z>;iU<>RKXsYr{)g1XUZ-ph~|4sbG2T6XkzYId*;P%YjI<=;!Y_m+IR8qpVE)M6?uE zu6HfnzMavUz4^ZRKeE86^_jk37{Pd6`-fx#7c4@;<s~!3>`%eo7zULkUbC*x%zfh3 zMT>@0l^3Pg4}0F8IFfA8T-dP@j8aT~v5)R$J~Xuric`0{u}lDzM7QG&#XsRK&XJyA z@bsACD9~SUMHETAKbbYcNH>GQPgicgcx{Rxl4WMz1Gvj<)UskphBX2IqkRnmrcEhR zQe}b*QB2s*4xFg^kXyAPG?v*0F|q`-${z$e(F9<BjuZU6<b~Tk?%!*eX0eM&XXL#H zBU>#gq;Dmqe7Df*FMj(x=4NOKM=k?X5t9ZAGO%4mxGnL}2Sd{-u{F=N3!+2jlFxZk zB5uxlsOb{6Rc|0syEww|+4`-@%b5mf@wD&!z>|86fQUyU{Aj2;&-A&p5IK@M!lF9^ zn$~pCX4)F9T5mL~g%$m|bGApu&`RaytO|^^{_xXZCn6_S@R_>P-s0xXvq248^;!LR z@*3BCjr2>(G&8l_{0Ul`W5~oKDDxDNX5|9)7UnE!uDI6opVyr);Ot}vgp2=H%tH#D zcC&uGP1>@|k>Q<F!lg;R(ORQYnnvNIU!2Fpo(j9VuNInT#Leluadbks8D!*P#@wZa zWZoxiBy+Av$0{7&Vrc5POW<8CNl1%OD69}R*CReGUG!UDrFPIz!XM^cp+qH>aZ$?e zh$;<~z9b-MK(2YTs^fTA;ZP2ReVnG{X4ngGSmV_sh(rO@(jh`6eRH`oH6C3pgsE<_ zOm_?}CE`P;IIgr++m;ue`(zN!yD1MQP`afvpR!H0g1LFhk9c3R5(M^ActaYM`S^?` zHG17N?h+R=nz1hzV>>9^HQAci&s-Zh^=uQOoKLqDgU^~E818Wy*?4Ux3iH<Q48x9c zRz%n%qJYQFCOQRL&phjVF`;Imrug}X!6|j2@)+BybCuxo*=Rs5S(*Q$C-yXKj>(~S zp)6z6%Y28{)SyfQn}hu4$Qr-uu@luS;%}P?m<(;Paot1J72SB&WQc8WM-ekNFPn9e zXT<U4{I7)&$I}Mev}6x_r-1{bKAh-K(iTCWW7^}VU`_2L(0JK8JtlJFn9AVEaqXe9 zhzAz&0HRvxJ}9`_%3w9g-6HUCK8m_v!&fT^{SEalL@u2RhyisdfGRR6aCnE&cAXiV zLS*yF)r4!??cxc|4N|rohSKohDb5}TJ(?H-f9xtuF2)yQfP!^!8B2~30!PC1U^g1^ z<RGJF;6~kjZdzo)U^I-c!2g?%n+mQF%Ppcw^=PXMj<ZX2wA%n45GtPJ$LEtVZWwxw zf-`jTV0G{I2tYJY!c_DgTULnrHik%IE*`Qa$Pefd#Co{Pl$@O?4Z$+-$}fBzh3Q~= zh=+CKU7@TA#)$EO50pdjn`r4o3J1B#@f}7#5t`8u1F_Lu`;>`-6e{0Aw;M|L$A05> z0vS=Y1cUm>BI<XDJ50A22CWHt2D8Em?E{T{=R)TEM`YfGe`8YbK|2^mEFbR={V>QX zg38n(3yg3Fr5AtBSt+Xlc?W?Mm`>pWXWO7W22Vd9L&yuz&D)umq3!}(@`!+;lh+_2 zM2X|nr<0-bNezSUjci(oY3`1V%)-ampQ3BtI-)~G9m=EJ99Su2!MKxk!j3!)x=awj z4;a_|B*mHT>2P@REO4Ho7Hz=ljFy9(i6}p$Q|(T&W7@_TGk2dii^v-Fz%*ykH-ao; zdK5n+0)Ucpaw1qYkhk%|+?oH84h8r|LQMY(Vlj?+Lg*n88^HzCIkeMr*27o$!C?rf z?%)6M&h3O<xg>x^SfCB)-oN?z^O^xThh`L3suy?j)>F@pNmC&(4okE8$qn58eY~p~ zFfbCT49l_Jwhl(=CdJMkE9MguhuNf;TemI1(<SRQ;APjAYsXk*5keNk@RxLf;jI9N z5q}o8tT&|TWN&qIOzw!b0PBcs_~{?R>;eR`zYc`RT$dgYaK4x7PWsZ{(*N*8aMAUM z&u-m*X_<Y?J+h6xXaj_#V28wqi(FVHHeS?cZ@X(=Xm!hf<#aJ-f7e!i(sz68hu?cq zz_%_-Iqk1C@84yk)u-u!f9M|GV2@suVU{utiF>GpvA`{^KzyhN=a^R^e-Zo2X->~J z@n0?Tw?EC!`cpb24sH6w-uVfhW%7ULn60VGGVVd8ZMo=oa{lWH3yxryqFB%X5PlUk zRTW1HEg?^LB+~545FDSi5yO7>0qIT*#KTS5KWsrs=#v?u6r;E*r*-ohGE@@K46deN zjfGS%$lw~`#e;TC=Z=W)KF|E6_-E74LyIGrvPShvEYU9mQhD~{NUe2pIzsu7Y=JWn z8UX7+yeLbI=^@m6p*zVZ*ALP7lHx5hu4a05@(b8alkV1TZ9Mxg{A6mQnmi5vH|JGr zDSO2YT<Knz9YkC_9qF_<LE=@S8R!9S2cNg6@z(incE8FN$HgyC!jRb%dT=pg|C0Ka z`p~)6?N2w#{G#^(V1vszr}0GD6T}d51dCwHkWxppUii2_8T=A1W!B}@pPJvLQ>2}0 zz_VYk77R4pErDd|mirgFJBPK*k71KhxW`F{Ws?9<u-+?<olzF_++(2QZqUNrTjXPi zc>!K(?SOi~I~aLi$IEH(650lzSfL&iPsqdUY_KyO`f@fTmC#rNPjYkZu6yQh`#2-_ zJEkndOY~L^586$SB0Hx1I(1#d?a<xx9;p|Y!lH~|+f)+YWQq01%jV44rY#FA2=)7C z%H2gPQ;x3Qbv5~ctu`$6tAYJrETwO*DV#2~N7{?}Lb%o|eF(w;eUU@HPUN2EGYQ6S z0qJ)aC2rGRNjO%N8aa?ubM(R0LUbGaV(C`(U$TA8IZCy29s|-a=%l;i;pPOWH1UIB zc_EJJDH@)a<txde5BPb&J}|DURxpjts>9%h<N`Z8+Y#aEue>v*wGxD)!OQ0&swE#_ zv^He=l%&m{T><EWor5X5xr$wP6J@FY9#~0Y_ep<~h$4$tr6BF+<{-fQYUBuI`L!nq z=}U^u0=8_^`uXu{9bGM;dQYO^T{V;-f)Q2ntkOe`0E~xkuSPe1)8&U27**|#G~u)@ zM%e0)w-j4ra4EN*QI>#7jXbQF$PO1mFqx=yNtQ^r__g1QP^v$Cv5h>3M<5&tiNRop z(AwL7xc9sUpHgH17Z&%#_@EH=6WBz;FsUSBZwNdv)~jj7l?|7<`;sVcdeCYZjRklL zX1x2rI2%HXzR|^i&VGlrm9Ev5;{3ttl0o%hkRe5e1o-S+;?>-~Al{Ku+cpgsXc0N) zqSf@)76C|3NpRJb#9bLMiiHS7k>j(D_uN)SC7T@-LTU9$t!LXNWtd_-N3K-@bfKTC z=$g~U@78FjY%}I};4b@{07>*9wASav*P+4M1!5=!uGxl(EDx?rd{<~?6Z{@>BxL#Q z&(_l4De8qoa>zx2E~ZrlquTDUsmZvJuyLya)ImkU5!}dvYDOiu^pB&Un%b)2B|uOY zE7%aw^J|^uplFhogN#lFb|X--lPFh!H;B>}qN0!>HAVXHUuKSbPm^p06X~LWlVL;9 zDn#*aybaR8D6+>mqqv9qHJ%m`<fCnx&L&H|1xK11O8Q7W?NPj%=fEjM8TQe#Rew&G z`74mnQDj;#G{-0dl6pivF?d=sy+Qwb#$y##Q*P{#+L2tftfRdJm}d(o52iwtQhedc zdm<yGE@Yykusb<yz`0CaA>ynBD7JP9*7tE7ysT}ISmbG2RR-X0=<d1KIX66<XTnMG zK(xRoD8(R-7<?qLHH;l&Ls1yJV%rB_WW}^<5S0*;>!HF`l7DjSHq4bk7(#<I+y~;h zWPC>}V!$(`iPEYxJi-_<wS8N@!*X#E41~|w@Fuf)1n-q$$*_;$BTLc|tZhWB$SL~B zW^p%7C-EGdKR5_hm8TD(<xP2QuYr>`9%vW%s(4w5*^uNLo*2dvjg1&(^FQ`UcY$G! zQ9OW-DkN_t(#jhL^18&ut45v*ub(d%tE{BmbvR;x0h%9KbtYRCa;fehHBwgk49WQn zP~Dq+>ALq~TNTGNiD_CV>ah9~hff-!>Jbi{=Yo9OA-BgcK0z8@_UdH-I1m$wBc77T zsCUj7;56A2nGT|KByya$<RFV1B1wRkFkiC3%Tym~q!5D80-n+!=z#4w^lqoXBMS7$ z5m<d_fv%>jY3OPT`(OpadRNr!c>qUkesEd<#uTy)Ic{-~ee|{4?5}0C7sUMg(3}K@ zE$-T$8XVY0#7!V%k^H8KE<|b29h`pfmzoV2t^!$c^k-m@^<R_c&MeNskuO3Ypd}#) zd&x>bxQpjeL~oJ^rh~bI1CaA*lEsDm6ke#ipzrxx|In4<7x3hBGH&oD!ouP$q2Z4) zOmTQFg&4}VwhM>={b<h#-~o~kyo3=3Q@>oX5rkvl7j-sFj=_&PRtI`gAn@zJ`4#X~ z!|o>_fdK*^Hec)g<3S!^<=NKxQgqP%kA2ANp}i@0BI}+gJ8r~sX=ezrS7q*ic8D+l zWvbon;;v1jJV+Rh0jdbnD0`G!lsF1m7g*GQl%T(#3)_(u4{Z~kv_<3=gD07fqezCX zOYYK7ae>fMU~Q9#{B)SwN*u6Epb{bVuv$LfkhT~*ra;7t&p?wxuB4vw69BWlf^S^6 z*RC7Tuu(*Ta11)eEZFvo$D_o2Vkom@aH0s7f#F#ZPh(tR587AUhqEWzM}O1F7E_(S zD~ApG(|_I~fn=E#IR0uuXA@yWfL-NisFIx3auT2biFd~Ha?!Oyf+lPy4;_{2;4#)R zfH-*xVgso&kys;M%~nzdg54v05ud@T;<Q^PS@8W2U}Tb^_fAOjV^{|fHJP9^fTa)W zv=eR=P&6W<4Z%GG;HW*-qtl(}55RX6By1(J&0F-2%@6AVz=S3O^3{j<TeuK_xPXHY z0`Ibf66p~TFUAqbKeXS)t6E09Nde?r5=Yw70?ZhmOa6%#=YS`g!Sqq^R2qmO0pB2p z3fO76Q(8br21iB>Z6lGjt(<gvVx|FzFIZ7!MS+?H69EkzR>CSA88~%pCRz=7*bWgG zSy1!>kr(YnSST@=y+uEO_=hj@0~w3WJSx<c8uh>*300?IiBmB!W03xprU%ge?u6XB z3H=Fu`(D!V|Fhx`&hXJmlMNG)VqQHqfiA|K0tf{0wc33!LFjHI^t0+EALANATJfn8 zBN&H{5=BTvEr`pBe58cm2pL5@9kG)HBO*l{B$_OID;~;Uj8AK|gVciu$IMN;j$Mfh zWQ5)$f0ot~8%NZ^bL}=)n1&1-JFPXQ6UrmlVN3!U8-K&R0Vxh{D^@4b>6Me808x~Z z2kVC$xr{a77z32-40{gCN5DCB-ecs=6+rc>;n}he^aPPW!i+hF5|Pg2?ifku3u^&x zJ!qBKTP_yZ7fr`VeNt>?JQd@!Tm{xyluUro+lW9<h0zAA?9Bj=Q59g$k<Gu9ITl!^ zJqjH1g%Snh?~ND&uP%;gJt@Nk0Ll}Xq{A8vMmzEK>P}E)2^SWP_9zwu^F(uzNE4(5 znn11@s-W<^L`x_K9;#Xfad;tI?iIAbx(czX=*0yvfZqonp3{;l1MI-U{%Wa?qSt_P z@}Q=XrySJQ<O@v}+)1j1zs6!9O##YE#>G(Q?$|m-)ImJbd>k9-cFX7%fsRj9nmLDX zQC>MkzH(w0ee}xd2kUgx97zj0x2lFoejr^v!$i@r6y7c%zoMHU3UbRhS^^^T1}{#+ zvxdcxI3|%)0=bU*^=QuH66YeqGeJ@yD&q#*4g(=3V;U**QFV|-wo8i)Yfw8f`!%$= zV@!mhx{yPrG`0|7Dsi+BeK)k_-P4%(g>%INoxw$i!5Ku_vmP?eZWMqSRDMKtHmx_} zi&c(6l_ZuXjlrK!)H*AHgx*|5M&MfSV_>r-UULC`Xqch^ALQ+Wt`1ndgdm_lCX7GE z0S|O4#!xh@j|U#HUX(e@0_~A9cVY7lg!@L)ga_~%9TvD!D7)_&PSm&wz{Z2WLqo6w zvV;w5eoR~9z;_1$y&S5SAT5i~0E%$?@rx5QG#o(W#@J1CnV>KOKM#xYIZ4ivkqJSs z8A+$Q6YA7>@(02eU@M2PDvqPu;4^znE%Fwtir9#aCQ=BH`M_6z2R`(mut|%5s@@04 z+g(C?*+T{E$?-uw#TuNszl&{BBR<D?=Z7e2jp{LJ8)|wnS~t?($%;o5r-x2ZG1Ml2 zN`Yc#LVrMxKLJ*FFi8$13MLtk>w%ST2;_}mC@Y$&A-%nfvyC8FF)*w40>14}#8ld$ z%!M$lK=mC)u?qitY=It1USw>6P8Jw4?~t+vK?BLrJAY5)0vpFPXF~E92jW6tA0Qpa zAFbX8>#h#o$V(t3feK=~v%7*V3WDhpk%*uho%f*}9EJ=)JDjjfYumd<jgxJIf5Fs+ zacbZtI>)cIGX9dlS*;uzsrbv2UpU)Ls1{+63a~<~iC3SXYfY#7;Zj6f^6J7Dk#aI1 z3!+Hcr-ZJ3iflC6{v0cUgfk2=FVhq}|1v}@C<D9`y5OqGLCTV0wR{0OkmFP9LvXm4 zCm}n4*HS1=wVBs}nRO$GMOb1ZR9=8O-k?fW8_hu5955QKUECo@5QsKn5otw)y*P9o z+Hh4AW?iC|yAiKPQtizHzk(kPyG+^<e}n77QCQhCp3`WmRFL=?{z<N$XxYKT9kn3J zw%&X0&CAJ^!7&<VCbql<PG^zI%c=-Z0K|kFn=cLLLv_lt0Dr{Vo;k63z_~d?t5+i> zl%n|kkR?InPzn7QH2k2glUjfSsQ}5~Vu4qR$-VEuB??{oq<Z}sQkUO`X0>|5_ON7h zoqwSjKv5B-m_FQDygdX=*G?@dmcR)N_lOAEXGB|RHV+lHO1MHuX=;cOCRm}2AFvED zfg=^W1l3Iv_DZdX5E->_vk8Wcq*IE8Jd=;v-`I%Wlb;9@ega8Y!-mVjSZYl2aOBuz z#;md1z#^EiZSP7L<;CP!+Dv($m`Ko+0NbyJb~<ooakw8uksLX~rA#ynpsg4E#pO<= zaEuO$Um?ybT?sAYZY72qpuwpQ5_3?R%D8KU&9hpTrQT8{Tj9k=^<9GDZY30V0g02m zLEpayY-T8akQnz;qC-Xn`D7QZTT=B0OivMf!7v*DB=J-E$a<*09-$w}*|a{`@`+d% zz@<30(cg{Xp@Xvn766yCM+LBZlN!E+V1wszym0z_@ex_Tomahb8mv8i-3@JzjwT7< zh{UtO<~r1$jqIHD?r4jIi@Ya=o+3ybb%EN$uLW>qB=RK3rTZA4rJ!>z0C*~U1W$+9 z&jYIh?H5ckhW;Z=D)RlpH;{N@TWx#&k^P`;185h-*{k4@5IsA9acsR9%b`U+mq2R+ zdPJDsM`-y9MHu!LU9I-8c+E_zO146(!nV~>Uiy5xdIIk<VBbLy^;vf|aMK8ohn5x6 z^jMw-0Wlq9&;%SBV{mXvXRI};-PJI=2zPy<5h$Ag5E#u}Ih@38<9-RpeANJly+>z- zEfJ^5gDjFPs7ti{JhXHm-crNZ`D|Qhq_K5E@8eMjYY=1TN0HI5U@(#k3pX0mX}_1M z2ye(nNEU#}Xe7+(#nIT<wR)^uD&nt2glCo|gUSQ>TfFphvfmqV_zdpSYS?4M@_s}b z8moX~*n9HzKQ$iUP{O{!n))B48$ja4rk{b!$Dr8%DRcM^I*tnr9SWJVr*2;Ci36Mm zCLs>T66kMQkROqP4lGXc%5q3>psx}C<eSL?R6wi|V0hf5oX>AU?q4uniar{={6-A6 zan9ypgzc3!ETl+jODK>nW||>lBEre)V3rh*YseWZ_D`RI9n&2jCwq((E*7~iRkp4c z3Ljtxpz5LY&QnlNF$q9I2=bTkOm)P-OL~VV;f^lG-$5P(B94XVx0phb$9lLhh<3Xc zkUx_wq#D63o>z&{%smt}Jki3$jNZm79@<cXZ4@qGHsN{z20ji03RXO>QxQ6%pk(N7 zf8~U+kxa?LLexDZ3-JVUIA~B;7U5)(NUSPxgXBLx({Y}m7mG(5sDdyOOHSey4ZDxo zk$Mm;NpTq3VJqar;&32-;tuqjBRs|uR4<vo5vJxnAP-_d+@K`dP9F@#-{WF*{!Z#& z1Gw`3V3xoXUcfhEurC5;B^T|54z6lG@+17c>d^J5gS+-ZJHo-mu*iaDqBYe3q6G0` z=zsP^<~*t$?kRu<xGkNmei$a2`6HsxNdmYql4!WC!ektThd86qL&78D?0_W(AmrCV zO2l)E>8pizfomU9GJTo5Wqp*l56N3#gVAm@od8_0VSrbl*VTE8DaO^ykAEz}S-^Wo z!5jdcS%6D~`1l}4b{EkkGF)_gxHB%M&WF<~aTy@4jf;=!iZm5{O~?+SXuZvH2*64z z)<W>1*f1R1wJywA!_5J>%)<>pxfCZdn8aORCjv*&dP0#9vNPBT9flKa7I2LngjK!~ z;(^e<s+QLv)2NZ1L4<J%LzaBF#26|v)H5gD0I>}eM|4zuK9&h%lR<L;v(?rsJpy-t zD-L+D8v2fY4J?O!Ht0#izS28aLd{6Q&6BvGk4ycz2DV*}-bFY?cFt;X2T=qgj+#uW zgO)PoNse_V5>GHrq{HuzLw>~@!2>oWjm2mIKm)h|-O$w-V2m^#mnkPIj3`GT$U|W# zfp)fUgGwlhI>c6D2~VQj4Q_rPW&t8Tzn3Pkm6`Egq{r5J+8By@6yf4&1=Ju~9dJ?- z-xsiyszwsj?%)S+(vb9Zm<c0gEw5-Y-wSeqBA8KoG%|k>GBvO=`5BKljK^TjP(Tj` z8_7E_A!g3Q1tMgmBS9RuXqADBs7`F8JkzI}h^N3Yf#!_p;a3y5ubcvL$7<4$_K=JQ zzf_xUlg?NS^GX)x7*t+ya!?SqFF1iVF6;rSk$JBPcsV$bIsQfnJVG}hXQjdi$?O8m z@T(i?W@x}US}!DfQA9a{PogqVS9YugMo5I!i9WNuCLd}#3vq(K0GQzefl|VcQb4Fs z0H03|4!H){SugAttVDxg4$K^RRN|QQzaOe{PXj+B49rxdUr?lWMiCtPX(#X;BzYai zi%4e>ACr%97or42(rB)ru$h-2YO5#f0ooLXgW>X<A4rFkm3AAFCUP8`5PB=)i0BKr zC39Uo7r%@ou@;6Us_~D{UlYNv;lZr1g&r6doq7;ZDqJT(Ad>r`ysw_Q%v?Np$^#Au zHCq5zKo^KtvBu1F!gxm!Rm;=(+0axx2<0vOGDtJPEK5+e`T@Z{N}uVF09iFShK1wl z4g)$<0Q7<6r@3=+t7+8zrSK~GhqM#`aAM~iDX~{gDF8x5Wzrge;AEAv#}25OVw)uq zHU<rDco6)kBHC4eGz@ynCd@`1!veR`9qylGApY?;&@Tm?7Pe%#$6twV3j7#JKSKPG zY2yStxdEa90HBCQ^em!{56Ru>dk#@>_-PCW5tiKGLa1>cU@NrNVOS%+3+`wmK_L)0 zpc@)tqN<I+NMN>**Cyo?GRWKUqmZ4%mt9hV-$Pl0(;Zh+35k+US5$Km*CF@9PFht^ zh64cZg)LE5nm!{C0#p(dR9_HMSFk^9=@2_cJPGsxdA;p|)bNl)k=Fzf>GO%IJ`w^Y z2)GtG3AUl!imwD)Bo)N~JWLT}!jLWwz=H-xx$-eMXBl-Ei&Z1lA9udNgH?v@LA0}g zChe)q>rmTx2&1wih;2ZQCqndNK{)d9BUku22g;5V)^#^Wff|NIPXdfb@c{6<Kp#N5 z4%K9CHV;WU*~N{W>S_F$Xh0=NB)(qQR^+5;ttRJP#6g%0C3FkCO#%<2?I7erJU`-H za?~qMES*XOYdGno-;L><H^$lEfV9Atu?~W+>IqMST*tdWx(a)xOAs5FoVw|y3L0@b z-n5Q#uWnp^9parh;U1U(h8WNXRb$Y40ZpB^XVTC&oIn{``?@&~(OEi#n9{15`*{&& zf!cu^VW>#JLmV!2sLqTH|27$x2z*TxWLnm~7aL*}(N~PRqSta!H^L2pk4#4yzN)9y z%wxh(T*+V&9T~{nSm%o1@oZ8L+}e$tfxpJFJsoJ%P%TLvq18z4!X}v-i6bhHQ0d^W z7H$EIXFunH^#XWrzj%E7bkr8e!sG5j4c$?-$C=tVP1yMaI6`0B9?0k;g;$zp^0|$? zbe{FfA`M;|NxIWArUapVo|sIVBlWR*e251kLRw!9fqERMY?vTm#MmvNZSOjpl|%v% zxWxt-b;rjO1c&hl6s^MeL4Y2_&pn4;j`F*@NN@%5il#!{H8Scoi<BkiBfb6Wbwril z00Ng1Ya)Km)Ye7<(dMJ$z7<RzBz>Y<dg}(*4$s|F5p!p}kO?WK9286J4?(zadJ8)m zJf_R58!7BVRfn>=)qlrrwy7J#y^6_f7E(lTFhF22XgwLHhakDTfV}hE$|E{Az71n* zQMvIJG7bK2@Rg0`fMIg_ym!y%yTirW2)I*(cS)0a(nAE6Ko2jdeT0##{7T9&P=A%* zc113Ih4_|xPD%iWkeGr7MZVA(1cw;r3y8FG_aUf2x=f<-aDn|iFmP#=6kCI-2Tm01 ztAtNJ5C`3YLvjd-ay7XH)f9RX1?PlFabaFBC2@A>Oe6*aj_DLCLkWa<DJ2Hq!H1yA zhINCKj?2q*xMUsyH=q!bGpmS9I#)1ZNP|q>8_q?3`Bp@;gW3aJsZ-g%cAyDkEqegZ zelsMWRRn{q+=9b|q0Wy}EmVhrX}l`<=CXOKTnq2)h#$fy0&c+r!a0fiN(u&mbpbg; zZUTNWCccEBMn+@k?y+_Ix)#wFq9hA}UbGU_st7(#IqDtgo`$niFCsRyuEv`AGj|`R z9s|t5J7Sl>>e$EQ$6B?mDE4Enqm-b(XHMLxN&Msqss6z!Hi<HM2L&uwQu8B5%Lezi zq)Ruj?x!D69fa3_p=bAJ++cy7#2ArwWMw@3s%r_#F{QX-NTT~%0=gllK%)44L-**L zkq`tS!u--Z50Uhu@HZN>e9z$?U8w|lq>4BkMJ8geNfvlG(APvrLa}%!x3T+=h+s$y zO*({<VMaiD*q$X<Pi}GjE=bh}*au&Y`I%jxeWk#rwE&)|7J5oQ5WI4FA5vMkP-NF% zKH7dQOo{@7j4E5ti|kbG^&mnBu$Tn0eInNYPi;bkh}B7YIKtLltH6>p_`;lukV}Pp z(UvmYgNM*!Lqr<?tIu32;LgS-;7fd|`T%1PF~vAu7kfj6E|oAq6R4+(bRPUsJi|~p z)7p{eyj!!7PF{dlf~<8eVN??k2#{H5M88xEGEo9)1Fl};-fv@K3}92?SrS%nJc_wJ zBrzc=6SV2uBrZ_yy<*c~cKIqB#lw}=Y(eN@s@-R!Ak1(D^&a(_nq@~nZghZ}Zd%nB zm!b&$D1>~%*$p-y(o;M_1ebGGGS`(LeDi4gxuRXw3!ot_`;q{VNYS2P)edQg(jiKL zW^w)>TEgl<{;~?=5+-VZR?(4NcwrCs<8N1CDY)4vxsY3o(B*9L$d^%Q3REIYM}mot z#y;r?A9Te5Tmr0{;?Nj5!Ku#tkKAFH>tj=u!O&NqowE>JtY*y?vJL`wc^`04*(#SR zgg~zNqvERtQ6vn&e@)2u5Ne}Z3iOa%%1(&E`EXpteSH&fH1nlFnm;VGvE|L<-j%sX z>43x$e5WzU!hacGf942JX=-s<055u#-7nQ}*p-U$dW00V3%QwNzM%VTS6Yc}#r3N> zfruTEL>wNeVO8c%W}=06MQ06jLl}f=COI#ekye))Ipf!Hs_WB#Mv@RS3cmlTwC04! zmJKKe1ti_Vv!{4er?yLw%svcX1QNg>aEeb+Mkstchl{|N1T1hOaC8rqw_3l&ACp-L zfJu=bAq70*m19+1Mji+@3Y53H-a6OC!}L#5OCuS~hC?VJh|&?wVM^8In7>d|eC4zv zjT-Hqw!r!>>^N@(RKb>YW8~J$r;W7wu?napM0`otf7ANGBP^6zqfx^}kJMAy+Sot9 z=<;iYkcgyYZr93qO9tAA5I_Lx;af)tGC;~az1w}?UF>dTT0bH_<e`19bE8dl8RUS$ z+Tz2WUy~WK@Y{&#5m1{JAt=*!oISNL#jpCpO9piJ2X9JNy*q(pLTfwh3I#ZJb`63! zBr8QQ!iYa|^f$V`B#}2z*3Lw#aXt2<h#(Mc|6m<i>q=MK;?+2tDYkpNeGC>f?(pHA zkUaS(p#26Sb#R&ZzMYV+i_j2Np<HR;MXc(~r)V!;042D$=YVi$!u(u5qZ)Q4rvnC# z!g3hQzCTUWu(DCq1@z=%>I#}EIjZAxlF1SB;N4e*J8i2K#cNp#|AYXzAv}`SHki+0 zq8}-c=rX^aZ5%xN8F+yIXPOk@P=m<Bk4Kr1(N{0-DC(S6<K-P-E2H$k6K7}YTKj|W zLjfeP5S1uM4suzn$<sLJaI!ZOdg<dw$)W4z<_J$*6AWlaj_bKi9Oa5qYlj^4Xz56I zzX13V37(i8O|k}o38YKFZiHy4&#i*Lw`sU?rtz<!pGm=3=7I^nubmDTB{xK%IE?mi zm@V*LniG}Le<7W15yBrJ66fssmkA&|7j{t1NgPw%{BL5VtL5mGf-MQs#G?m`%N#iO zONz~x>T5IUz;HlF=w*+v7@z;*`=-l~A{A@B(DWJL;y1f|P-W8RfG|lhdqLb=*Mf0c zNTZCfY@~T1Q8h3FnEhfd$#9T~j(XI_$!?~g3W#*IWOtWOvR#Mo>uUpAp%Zj%#a^Kg zV97#4=qQ`_hpcxw9?C4}aO7?(+r>hiaybe;tI(h#AC5Q3@CiGmgCCFqEtFlRgz`&C zfMXI-)=|cuSn^%yd_`3H*Q5y3VdBbs=K6SEoP&I#1kf2Aqlwz?@FU(Bx%~QJoY-WZ zOkg8$KRA#$H|Bfp3b=w~5{mer`=vLyE=uxD_~LLMNiZH;jC8BYG)*w8C?6&6v`9$# zs1^(#a{i=R!^u(sWqL};<N){Ju|+J}GLcFS=bFzQ9ao%VKQLB-sh9#zt~CS_KwPOH z4bTb7%^K3GQT7+B;c1tx>|?^^ti<@wR(SFGc#iP-;^}_^lL^Uh!s)~?NXaVkO_H3Y zZ)FpAsE8i-d#w;vK=e;T>LlZl8^99{!cn9hLm3S#5G+7|@QDYk8G54N-VYQ*RC#cl z<vo50%n1p^5dwf-4!0i?c<Y}r*mo?fmxBW;?r~|=Fu8U<2}c?NyCVk@9o5Benh+6T zF=Z6utNG96cUmH}(@vg2-ny95LWD4;CZW~XihB!li!cYq8C9y8XO7ymmRNSq1w+Fc zG=2O^6ru^*M4Z{_fsuASo?tBQYl7HRMXn-LCyrlu3)qN=l_;8|!8c)9MzssDOLc)w z%Dc%ZD8;MCCO}#;fz+f&@15uVR*cLoj!iK5ppqpA8_qwlxRT@@9{5s{^OG2S1-W1# z(RVg{!IgSKb6A!_uu7!BIp`6(Gn~UwZV?W{jR8}zm2ZFjE&S?oQyWfO;N@AF$?h7? z501zT@Bea1J(z3cQRQ||92yabLwyWV_qAUSoV2}1tDiE2;o-q0%d9%IA$jhylP#ij zqTorgI0=H|VEzffsg-FoDJet@JgOVP$3YqL<s5t*8^%b`ai9#RTjjupfsURm{^1Ju z=cKrjf<9a@1zw({WG3r9iSXSXC|5m~s{trVYtjNeD<df^6}kw343J8lmO?O2wR@6A zC8>panFm?U4W420TRSc$i2H6D@S<5XbUEE7JkB#w4?R_IcW2}yy?*qE;aGhyBNU{8 z@5pkMcOrUUIo0Zb<6!&jU`|^2vn@FV5MKMT)T$bs+CdIxRQw}Z3Kb%a$&TbPF<{Lz zfp@T6NAd01Wz@@Kt|><r*`H=JVZgVA9Vc!#A1z7oS`W7s8X%*!KAb{bzvQg-qVXYM zO-x@0H=n^tQe|rCo9mD&#A^}J#dA;+W<uAv4@}FOhz2@nKF|qEw!fZN+8;jjD4jV0 zT7x)j8{j?Dv<>+3cd@v5wuzX+2IexQxMJb08>{TmqXG}uiXgDim3y|BBPDT~-t_S6 zr@d7BL|F>Qs4tbdEWqzZOxqy8(Gr$%!)*Nkbx|Y*bXb^pdYS+^HI6{|9A&?p&x%*G zWc1&G^QSDOMwa91DXkHn6HuvQzR{Aj`63it{8Q1pu+;iN8=gnTpBc}_?{!*`3<94& zMBfZYxY<YQrf?fl8`F1SoTQGKco<)KHMACCXfKAN_TSIL6$>s+Lvz5g&W0(tRBIj8 zA0UNm<44LVOFIw^fI0YOJu|Vw1tgu)Tv;M`{V`lEDY*i5bUTm_S3dyjikH7o1&YKE zt^M+4T!VWWD$sy3kWnyL;6zl&@(`9REQo%RTP{<>e7Va*Nr6wQ#hKj>*aNbms$gMm z_h)`#uHisHsk9|+bo(q+wL5Bo&F4H8jtKI8gHeNAI97qwo*KzB%zJOg%B=GFxXwF% zXF$mmiTOZvsxn#ImrOxt#EMfuqr;S4fu=^@I%KZdu|R5IW%%bJ@F|`H1m-`Z7;n1@ zpnLY8(+24$7jATg?yArNg=<1Y2q(AEdKm^lIqI1wX;?1R?Rgnd0mQijgU4WQ^~Zit z_Gh5QJ9}Inv1&L8*|@bR*1M+c2}T`GGM=-CIYOTalu5tbW1TF(ST@Ak;8KYr>{cSg z5iD4^5j9{GYZ!x;L~L2mOGKqQWDIxTr*pVQ8=11&eazc8ay|T@7fP|mV@{}(P5=vc zJDSA7J9lc52`zN>t|9?gC?(|mWVH8{eV>L020(~x$*EZ<i})~<xX?q27;ruaJLp8u z8RtKi?aITGyB#Hc0a~h5Gjmew229D_KGCAIpR4TJwIWyv_Ad(>&{AqW%z%)EkS%b& z^B;n9v3^mC@Sj|9Y<bv*f@~%-*D7{Fki7DLI-r(JeQ@}9t<ZeD0%i%^ImUL;7#{%{ zydwg@BAy4vJg-eT;xa?%d6UTK)nio7DQbV7v?k-F2QBKfkMPRoX;Ul8kbt-1wACY< zcZ-sV4Tu}*q1ppuT5*+m-r~N+s5*&bV9DlV3y)12IgR-nsguu>8~zAY#V}cj0@bN5 z`lMzx-x-|vKFm2lO{AKC;(Bs$$`PDXBQS~4nAL)3z3|6!#QT7!z@5AzaL3K;Kxakl zG(qPL>?%igc-paseM9I9#VAa$KL{s?ec&8kPzDWsgs)+A_E;l$%7h7qh@mK7z+!`U z>i`&!IVEL`904jX0tLeo3#)6r-LOpyGZ;ruBoT9MM+ad|Qpq!2Lz`gOF9Lc<yfBi6 z7%myHgJo{ss7|RuNN?;=+GFh7&P0?zgRdOn5SC{RZy(S>Uk>nug~#71ez^~7iYCN! zPcx_ezn0EDAnH1M|5lW`eRnO*+BRfd867o+5;a9+bk`aOwNbnPrjmiNXl0_LW5~2p zsacE+B9S)Z3SJQJT85g0T@W!R!Mh?Tml2fPAeUh-{a$DM{nJHZ=5u+!&-<L`JkN8k z97-!vSx9OmTFi;v@@F?9k5LzpRjmhQq!Y6JuYnC`;ZazaOk}C2_cQ2l_e_!)srbu+ zv+<b3Y*0}2JzS>Bbtv@{=z)t16<IDnfy>}u8E!r^x5$~#`N@p)Q_HM4Qmh}GZl$tY z$i3QJiAmcdJ=cgG@k&<E*ImCd<eYH~$2l<VrP2@Bm3Faq9{4mXW!L6}|He3%yWc&_ zZBhGx9u+l)6brHSVd?+q-GG#E4s0>h*O6&Q!|G@=B<KS6L?{OBtSKJEZ$aK(Ec}-4 z^iOYx(^WIaSq4sM0YSYTW}dOdb{dQp172viusa|g=mcc|1Yjg?9=BYg3)KVb2GOyi z4yMA}+qa}NT4(dnm(EVD_h?CdjGpVov$<U^KREp?l_y=9n_~yRs7#n&tOg!4>6$Lu zuptwHOjFIof%_8lbh2YtXnYK<XTr`t9lh8*8RlSP4?@UJzt}$+Dc8uUQ9J8ZeE!<} z=4;!dI8`Pk$K7(*M8ER4RvQ7f-60I0|E%KJ82@KCf!j7)k5I!607jqVzgGSniWHHc zpYKodwh92^a|OV3Cvoo&FPOI+XFdZ2*~VFxMJL%YHJ>JSi?BmKcDpiEX<S)_=lUi4 zTo$gCBmeN6(4WB-gmcEonBCXkXQOc%-aC>0;8n@rXnZ^F!R)wgX@3!#Xa%i0el+jd zy66HU&7>8Ng-@9>8Qg@{0Q~8h*e%9oR_h5p!&&lMGColEVqZWFS7mw^j)^zX!v<-O zzl8`q`0*Z<sXari1A0_TyvzupKdNp7bY;r((50Okf6fg(Yua5NY5chv3Mct6vAU)- ze_oE_o(VR_YHX&7PWRRl1Oq!Hl5gRj^YFh-AWpe?FC2Axi=+2?*Vu(NdYzm?ZfFA* zNBrx>gNt$}4p6of1Gp)&V0Ki@ELzjuQsZa=2DhACdo1UV2EI;M0<9NxRoPBl(u{6D z>9}zOt@!Ep^vD!yBqp=(+&QgXFbZ;zoo}URQqIDXW<BEPhYTAltzJS!t=sK(ZtqUy z<&C8|mazoK4lVkMFZd!E2<bkRcInooOWG6raAwUPy406&(fea9r@|7&s$N4g-7Bc^ zJSQSvuY`AD<H20fC!RlMIqmIvs(>*{PaJ&0VYv~J0Oe1lC^P#zpVxgcdW5z%gyNFo zY-rEWq49^*UBxu4VBYfF$qH>313gyfhLO1>AMrA@j4!!<$+O4>59{3wHVR&KtqeMv zxAR<r{ojZ4Rll6<QO)lP&8m!GIHS1b-Jj2!Cqql;SmfD{fBA1c1LU};OAR5s$`l-% zR^cGe-AT7aQgqVdL`%@$X00$Zf4?u}p`8v2-Dck6&7r3Z&%dW)6ENDo%c{oJJ?77D zyXgUYQdI8OWIc87N@_o%QC$lsK>>^n9-Fd7rB(g9gnJn=ZVzj<akHjn#08p80rx#O zAV5glZQlK@sZ$`0+bm%)ON~L{3>|blye>;HVa>Uul0%LGD_UJ|9!i~*5-WRDJt8>w z&u&kL{Y(IgQoAUacO@EaC{>!Qhrd#K)Iw?}3OP1-z1RRIcKKaU{af+t#-2c-I-a4~ zJ2d5@`q!s>PzWQ8>xzqv2wz;$+OktL!28@aeTs9TVJO=}=K*0vcMR2kQS*k?HT-F9 zRcfz*dR=<Q2KsWj>O1dV)05@t>G_q@=UjeZv3Atba>vTmvwyMJc)D)#QS*v5dp)uU zrqCDwBBJsx@Laz<zvFMSKDd=M{m^%*`jC?c1I7xu*3hxyNYboB63Gy`vW9BDeY<eb zPO1{iE>_)C7S)Up+>lM$l`)WcOE}<O<%cXV*J>A@OZ{B^#TD8J4>E6qx?CKZW9hrE zD*dc;;3a8+^N9tC>Av4=M!?q;W>@Fq#u&T2zRcmbV1JC)CwPp<1&?>`?4*>8mkzta zj-{V>|57LUdDEpADxMozQSR8JQzqy-Ko_JOyTKHyBQYO?yQ707q0m34P0U3(ck(bR zq*f5feKbxcBxJv<+i<ve<R;C+L@-~vqin4_LH%_tqswqsIcA~Dd?BouB&FJYd#Bv! zd!a5^<Q*B^T~o82lPou`jL@h^8&%E8Af>NgYVEr_<|D%wX%0h6U835X^iQ%po6Q2; zk_q3r={)(v>sR^|8+b-@zT*HE^>-#S<!_1-x8N|xiU%H*SNM}S$(}t|{RL*0`Ylvm z82eEq*%^*tO43Sn8~7=2g4XesVXY)2`J?t=VxkVv_9tzGH~+a7MMBWrwR$0mP50eH ziT~MG3XAji(Ii0BvvIEBJ#f<<apt~_s{_nEE|j3y!o-y{twQ%N0o<+G_FN}q30>z_ zjY4WojJ}28r_Y-EQDAY)Kgg^)w^(sx<%t$`usO{Zf~flBj$Z3ar4=13%?z%yHmU93 z9qrU?xF7Sn;b>8P?@^jpNrm%$HrK#|_p}Jj%eQcM%v{}ixEe+7tsz7$cUOw1Pq8v} zEW>-)VY?Cx$yAzApqgpFrC}sP!si(uYV(xs=%Ipc>U@j0zbmcKd2Tx*_Sb%i_fPkP zKsp$~VD`z?j(T;cE};5Es`^0|Hc8ylJ`P#z4bXf~w=^UtnGEkk<T@$IyLauFSKv^7 z%Cscha8r^H^{rgnBKwY8X7x#nd%?z#W{6r!4PR)0pYB?+vfrf*ejDkKH>oT3Swlar zt1^xMNbe7Up~?>ICSFdg6(#ha(Nb~mT6XbVz^nzvqN`LH#W|9YLi(D$-ZejOTCE-* z_3jo$rZfnhCyMb7C8GRuDa7B{1WkMgv4*x`le%_PqOgF+H`XNlQfmAy`1sf6cQ@jx zzzVnAo~3Bsw)i$E^A0OH11yzu|5K8=pS-+VI;wd_;n`RmbyG=HM@%|-nth__=bKIH zb|xkd{>MEj_lCj0*r9%5ajC|6vR4548Oy+b-*xINh08#4OYCLB2Kg-f_kga+0&}jc zO~!I)`cvDIhh9NO8($#C$WeS${VB8mm7MgFwS-C3cD34BN$c=)7&Y!7V!`vYi#6l- zeF$Y~$!W4B!5&I@)f4`auxjgE(<B*)z)AQp_~4-YJUzS17xZ^8A<nK<nYHT64E21h zS7@9i5h7k`*s_jKexzc3YCq5wloGBgH7vy$GuK`HENLkSa8RfE%IwK^j<=E)pH30h zVdY*^{2@K!yc;?4cFf+>tn`Vw(_-e*37uTYdVw9cH?4l|RkG4k_G-r?&B1o(|Mk|v z&$3g`rjAuKdU*;55*LggeH&1*<OKQCd8ElUNDfbJTfOCEH3kPL2($`^?3KL)tGUNk zE{MC~t>R``rX53$zuZN>@)c)NoTmM~<&gX#?syZL4xtqeAN=^Ot^@m};nNE?i$+CM z+M~Sm-G3^q48vjNHoA)TsE^VT6|MDf7*ts^Frq8u7ml085~!#9v{o#huD8^IHhKG$ zJ#7VyVm--rL^)+;lfOUMbVWEhMiiBntm)bq>{-wW2<Jwt+}^Y5bb;Oft3WQ<mXqO| z8PUS`C`f&rn@jTkUS;Z0eTZO2gSr?>9F05LR|7asp`zY<+z{%F%j_rFa2OaR9EZix z&@p*D`4<O%8Lu?p^6lkbQ~r#52^b~dOs}pu73|4w^XKa*?FYJqa3qbb0%u&fZjI1U z6w4&8K$NK?6Y$?tEy_S(5{XzRVxLEvihlx~n1?bH)MvRB(P9Zd>ovm(vFlW>HD1}n zWk*K$G+)mo^IS2HSp{|y1;kBkgu!$0>mF4nQm>Y@k}Sc@gIE7`8?1h;nFy;0UxI&B z!dcPS<!JHcq&hLHHyu?fm)4=(a#1%P80YW@YlKqT-Su!skIIyeW$Z~@G0LOCih$Y! z2t>ARi3=D7jz8LHZ|YFB`LXVes@DFk^Z>4)bx7r}82UUg9(N0GQ%!yOG8vY?g$J#m z#;eGy?e_)68%9K}ygPyy^HO;;$#Pihd@T14)3X)CE@XXZO&^My<as2^>MQhd-MP~T z?7p$xq*Y&i@MpIKE~e&Nza+od4>eM*j%lBrue`2ywen^zB^$C51rOL~lq&hP?N13k znnz81+?D9to8DhYb!xCh7`A#t0TfxKMf?i7VfN~J1~6G-3LH0W$Z;|ga>Oz9MHaD( zlRD6I#5C?;5WIr2;BF}$vKmZ`K7)b4`Gi77>JIk{2+tX?Hi=CCz7m4bjRFWK!rXng z(^K=rA-#oFJc9?#^hZMgD!qOhwd<jiEe`>Lw#ItZTDGM-b{P+5ST&Z)Ru#{qn#K>; z<Zt&kZ9t{@hG!lTwhWgA$mggs)VH?(#S@pdtOf%@4)C(z!^)+#hCR}I-NNKTnZYgB z)>X&M=x56(R#Tj(3w85q@YAZ}X7Iqt7#Ml9{YFe{=4o=|s9dePrI0KydeoD(;VvO4 zNR()Ylh?jC;)=FPx|ZC_m8G6wgX<Wg8Fq%-$mSeBBxWr=F|=RY!?Yp&*Q$?DTN%7^ z0%H1f*k(}AimA;=kX)h)M?EyrQy`+&a)wN9jX_QLz^+wFH~20!Dm4XZ4rR(8M^2@) zScwt$ag)%QDL){jkrynAG>ruDlADAtiKEA8C<7)s=#F<`vwhOj-_9Hq@k~g=Q(UGI zK5OOi`kP2U!z^%S_;kb`CnBq)Cv9xo+~=JFP*%iqOoF+zyiobER~NM<BgCw+2>LIK zR1MTIRbvPTvCVhIlV5DoN#MrvL8_l2)L48QFA0QpPG+OhOpWU?IOl8HS5;ZOucftA zC)r9}<PIQlUq!+y(iv%t?h;jK*9LVZYN~@e<?@Nj<az7~^-6cwapJm3575Em-uT~* zk^u>}xO$dfbQ<&h)>&l9(5kJmIM`l^-(ku^vEhuHQJm=fk@g4Lz4{^l-5Si3DO$^( zU=itOIEV!G{;9{RzoC<aiwEy-ux!sLTKPQnjGzA39z|1SnH;5?>V@s(SSV-Pv1)@@ zX_&M_X?BlLr*~}r>38QaPqb*;?tj~RE?r{6U_Q@!0m};q7$qbud2(&ZupOh%S~_5; zon<5EkYK7Zr<!{T8jQpPE>(SnpnP@H*X$)<<QtLt$nM&wEC1t3!x1a@PoC^Ku)ZOV z=C$~Z;D1R0IeWcL@@E6{?ssTJk!p^Ww?A~v7QJxDmdZm>;GUL88u-28RxWEVfJBgY z>6FaTF!%&ox%*yzBKGo`6P}@?4uY(6I%asA`TLkq<Z0XoRSw?1#@8clY_gs|o?JC@ zRTa`_k=}Sy>TqpLch@nls`Ww+{C&*3#G9U@aTq|vwYP;|49*c>yXKtou#vMJe7I=l zNk^hjy0^pcHMi@Q^wBFCuekX8gjoulEb&6*0d3Y2=NRKV<scc8iglvzp5^=nn~B!# zk57rDb1AxE*M>=(G__DDB`ZX^CBhMU$t#2hyT#JnYeZPLm8=*fhgRC#{ru)7Q_$!8 z?+w@T_LbRgLz6l`;=B({58ff$z97-JMa)|$TSd>#p#x{FZEJmj1&gM}do_<&xSbW@ zf*bNTv-~Y0V6}bwY`H#R_G1a!5Fj0n>>;tRe|bbTb9mNzMJB6KxB>q^_tH-&6Q@X? zQ3D}7t>C=$B#x!-(YM7|MQY*+-abrAMrlwr4d(X+`KYhAFyirO>ISjvC&J5@*Uqy4 zcPFos3G_v9q!w6R8zOHTM0G*=&q#Q-ISXv;;Mym`h-f?=B6m0%Ln#HlQtXU>H-tlT zHyMx1A<}a0laU2Amap05e+xV8bu&6woE|Rs&(f7I9nw-ioe@OxWIy<1bS!vt(q=ui zgrFc-DYqd=^z@N^4c=d8xryO-KHd7z@cgfEll3*}g?t>vTw?U+A|K_*3M=;9N}cS{ zdXJnqX10$y+qm5{MfWgYs<CColhb!f4H-4Fh#RIFG-s6T%4Z4O6lRlY+Hyn$PFhv` z#pcH@2@y2eZh=!lO_Q4cvEdo*OP;$lE_l2hLk$fjKU7YxO2N+Iu}icP4fjJuNA28f zD7gv_#4VJmD-SFf9}x~M^9S-tQ?fm*|E2GiIx5-9H-qN{eqGPojVF$I1(&;$<H+@P z{>PRU;NMzpw4(Up8h2%s7~&TvhzQ0Go0<%Ne^W2_0bNi-JbzSw?>Wn>c}tu;;<%d2 zIzRogYu7aLHklv72M@a+2GW2NJ^eS<!}b<eTG6gT7HjJFO8W*ZBiLmWaacJiZXL+J z)6^8eyX3{l?B)D<mwyprkvCp!Nxb9=NiVU4(_=u#X>?lyUBwf-Uok8^gk@hUrsxE} znu~+BE>yzWlxR1e6j5IsrM?j^P0vVzd8wf-QPsYg`bAJ5(YCs4g1-4}^EdA)en=gM zfd$>;jv;Av-}lDBsXHGL0?7IC&`(z%l(|=eDCKf=C+HOg=`5e94k;-I>|3(t^HO;6 zzZjOg=Vd6sDTPi?0$4kKhPexEqv%FaUH`8w&~wcbcWd9;-!jw4Jx-;tLmqm9W50QS z9f}CqWl`z#5o#pp<Y4mX)tD*z?G%7gm8Eb8?f=)Wj><!p4nGaYEIA6fy3RPQEL<1# z0B$#a8v85_Lsa6Jn+8ajp}JWBN!M#Tvwc{+Hh!Vnbpn@?)(c;6iew&_qi>ed1ASHC z+2}0PU+K;%o_t;>)cRe|4|jiFy6QGM0a6Y_g7MG|j^j-em94x*NURWjkH(%x<)h;| zgehM%Df1#6iY}OZ0W^jqKik+Gc@4KGM$rIX9`)F=2*3;b9c-)={=F`+!!TgBHXxh6 z(r$^j@2qbN3@UM|g*fAzv2V@AYd?<KzdOy>5({E)Lm{!D{~?Z`qAb-dlK#uuz=D;v zfLWdWf*LLo+ys-<f4;!<TMsrEjSH63<)W#nSD+}4sgy`&Y4lV}nh`NubvXvZCv;r{ z9|}XCG_FkT?a2pk4|H!i14~NSJp9h(O9^vttl2xpwO%O|OqIP#PJ526nr~;Z1gpf$ zLe2!*%*ovMbZstO{8$t8Y^vR^xTrocbH@n!F&UyMbr{21ik2)~(mk`^jz>@<`PvD? zJ*)f0*~$|DV-*m%DW7tcmt&lPjZlIl6cWbrYDU%s7X5WMnTce!@70gRunJ+X@%(jC zQqI4t!Px^ZCCt}W6I&nc<oRmnB8@MP#Vb6Ea-R5~J@eFh*VnEeI8cRXU>Y+l#27H8 zM?1nRMP^5c1VnG>RuU6RL>}|qMfXl0{s(4UAZpAB3ExEDGf|8C_=zf%YcnVMNS&+P zq!<2A^<GX2cnp&7bHtffXcE1N!EQFtuqxA$7l!P28Uu6>CqsMLrEAyuyJ1IVq=a}3 zSqjU*0@i4G@f`otsfM=Y5@F7#9^5>3N|~b%Ocbxq!)z(~H&hAHSCSI)(Cfa9b?2Qm zjR_HhF3-X9LJBPlUVFEG48z366$B6-?NwZeh(A2UqD}W|6+`x8*Ww@}9V`5NE{s>X z+w<?%!QkPsLX<8G{@v8YJCj&KeaA}PnAe0z&FYI71!R8Fg#0PVI8j(mrg-!P+}dw- zo+MO{U@MBus1eZ<eLeF``sKgL@~hd|r#@WkQq<oMFUh<beP50LKoi$wcNOtsG8WX| zNB!W9j$G!J#D7g`0-q3d$d3ErYbRrkEAo~tG{^4u4=fJZBxVip9+7<MGZdCuW=7G| zU|I2Ue@_p$BW}b*j=G6_B&A_S5$QI`BKmOIJw)Qck3Vb`_uD-A&VutIxx=LlG97;e z7?3b$>CNo5lW5loy24aSQ61TK_NG<L-2uQtTVdY1p@J%I!au_2OAT5whE}k9{)`hA zvY&vSEMTH`-M0}YX9?>Qu`eDj86-9vXi=G?C8AGw@RsR52RS{yAZRgl-%cEV6}Pll z`a-$ZHC}T)l3t*dxEt9hGXT+r3gUiec59F0{G{*<4X4-@9{DCVaEM3hKWq^|ZS?`) zQ=y5cP)CLjw3O~B0JNC2P%CF|{wTl@FZxJTrXS)s+AZ16S>V9BfU!eAHHij?r&6bA zDI5Ma$Wbpk2V>f2J-P9=fn^yAX^^i}cqZ*a0}ak1t~%yrmwSbd;f@3dGKNl)jyrV2 z3u`yFmZM+6DNpv%J`QnYvmX6r!?+S-T$YqlG75KAtJGY2>5>f$qDaS7iZD7N`1CtZ z8y4dQ1Nguj^UGdaucI<DN*2|1&S-6A;`k59ZR4hzmO_SM4?O(Kf3KORG?=}_4~EGz zT%#4uzhGD^ot-X3sskgqcD|Jp9HR~B`h0QavqiPj2NYRwM)l<?t-;2IaKlyP*r)<$ zN%jI>(^wB+8syRc@z{6_j${k-4r%u?;)UeVuBKtl0FeW_HYnRiOLjmp0Q}@@nX)|L zL1e04n$2Vysx11pvvKxgDZq&lKyDV|>d8`OO79w%999a+gsgN<?mu2o32Ux1-+vEK zb$?lk#i*?aS_xpVQC!GyT3DoN))8L609tR=iAja;7)F2!R_#ErTfl<^3TiVU_}tV= z!+e^$soFRr$4?`Gn!HG;VB>wy4AZw1;pWdit)Mf8rve(OCe$KKvBe|;AZ0XaG|O^W z6IX+Akx*P<;~DNHK5?kCZ7`9Bmqg(UBcYi1t_~OvirkU$&REs|-);DM9aONpydmcP zw#`qbSg~S|Xybaw{A&v-)Qy?_`QbXUVNu3xMtVk#XsN$9IBEH#(iC&5EKX0lON@Lh zSVV!u1HcE8+7JulxW;?^Q}x~~X?!(%jsL2h<%yGBCUF<ID2$|u)Zh9l&d3qG+gNi_ zJd=;*Bx*17xc`WXp(Dx#GFY9b-y)U?Z7a0CP2gZA4G%ix1f-F<unc=1>Lh6Mw$K<g z-s1#Z3D~Eg$ki;y=Awz5(sl}B1(-Hli62y&)~=<))n;%Xt~UgAd<;B3mzm)q1r<dD zzypZKHy8&@Hk$?X%&v4Q+DkuCkbXn*a>S9yqgRx4hij|eQ?-^BgBD7oy2+Lmz9!R? zCGtvi>NGL9m0gy$3&!%o5EBk}cpFQEYdMkhQ2}pyh7yX#hW;oMKLyy~nUac5pd6Al zgw+B?5qnT3hh+F}Iim5gNHZEf@xu!c{nF^On3oaa!nzqGSh?dm{C7cYFDuD)ZEzLb z(m0LfBnbk)IH^vidVaSM0hj@4IJv!hks26&mp7r6P6j=Eg}rRiGymz3_Iq!(PougV z9Kg@0=8_5NqI{V<{R!m>^y4IDMLy`n@dz+<#miL(Q;G3$U`=eY-JYLMQc1)9g0-_* zd*^088S+YbSV&ElZl_HR^)3i-6Bs#Ry^U~AI&18#&g;{ez}*1DK+}dapM^%4G?!}B zQ`0SiLpM1N_PQf}Dm*fr-l};N-X3)mX`xho7`UebtKpH5s>`3y7ey0Wz)id%6J$xD z2%EFbuTKHBp_B8^aEbuZu9*SIuTr^OxR-1^P&pks5XTYCuGR}-#)h|KI{>QjlJ8G* zy{t^e8NpKTHTB;H7P`UpGQ8LV3R^|f&;w8Dm<4ZFJK?Kvu2{~yWp-59HTZCIq&SYE zz9qhBr>6g`wp(dzgCp0|vV4W)Qm-_002veYJ&e6VB(%hE=2a?|`vjl5fzNivQQxE_ zv9KkoXGHWbc52w7>VUkW6*6=aK<%yYRSA>9&ItX456GR3n!Sqa(<gf0p0w-Z$OGOV z@?|!(YM>pmWp@{5;sDb5{`(CN)~i>xKFa-_EnZY_$sKLufz!qPK5Z5FstS}%P7j4= zW4gy(*75OwFVJyy9k*8i#ECj6bkT?@d#WI@$tqw;-VD2s9w}<cO!mpH3O%!FaNc>8 z1^RbJ+<ohyx}>>1Pn8C+^haFIv<pEE3zAq+aqt&i1tZo66p#s%aO_%!(#yT*qi0+% zwM<EF2pN^jokVBGsJIye1A&(|Ykp0aQ+{EzKOzBh>~jZRX#CIwKE|7vT)o$_SP}_Y z{0lx)6{`OZ4CETcELt{iSAo;vIkNk^&L^sRh7>EApP??`Kx9r_mL_Y>UayM_fS1Ag z+O9Qw$J+_JoHe&2_Gp{C|MKdMA|>CMLi0Ft{KI7)JIn7cFU)abc(5#nl*czY?nY(m zB=3f>s>>ZK9;=OB41EeS9huCGV}&H2%Ze6!tN7_8$L-2N-~A7#R#ld&JripOfsEMT z-Or4R!Uf^if1m<l`S|Vhu0zh9>J{@JtA!!VnobRl3Owb8e1U5y!^mDP3po8uVKvdC z?;A!Wz3^RK>!v8qxSvk)7&g3TVEhH`oAU-5Y28{CYR}wot=co`pvL%9@(ZRa&l_jq zf6#s^4$1H_Khb=(YkgZCusi6*+EPvdsa_nPv|7|C$IB$VrE05NUoJD;>DyeuUQ~#L zF2qGa>CT;M{MqvYtI;{1Ifd?^)YOHMt&w1{vW2Vdb<)TsGd#kFE=c$L?{-$usZ==; z)E!NpxikDS?)*?|cWpr5Dn1GQd<$bP#PZ7wP|Z>%X#1@msknAJY171oY<AaCC;a(3 z_1&3Zh))8~P>d{*Jffp<dz_h_FVKqDKLJ{^>)63JQ`ZdAh7^w+j2zB&%pB%_dBrs# z*XA}OQV=cs>qbV>Px|xE2)zU$F0MPxvl8Z7g?;69HGTL)z&>!oz@Kk0If@*JHG_K0 z(tUl^+A-=sM&`0l;<CCo5?luu8p6hY(i(ll3Lc4HAFvFpB4tX+!7yUN-lnrDC5KA) z5h|QpUM&{PKOD)Ifi!6NOi%s|x(C1At9{~p_8**<HQP|x&9W1dgK+*a{iRLO`R1q! zN1VYoc^<iULw_UOtV_+SFqS<Xoi>PR2gtcuM^%a4^xKmCPI4?Bnar7(=SHNqTk*+v z*9mJ+WhJWVA62Cy`G9u*Ag9H)erb+r?5HJ8w>6~h%)r&$-M?53%=|%pLHmWS)hpj# zK0Rsd)f~6$o9FXrb{o!*Hn?A?@iczFy>r~%sE`7lN+yV9b>F3)-VKW<^CfxF6#S*y zfa)EFXBJ0PC^I{daR+u}CTNdr>T|=@r-hLkOgg!`0Lm+erN`~aSn7E$a3kV;w@N_H zW2aMSS<VS;KW1W>fH{fxnP)lAf)Ov_%n-kM;Ox{kIm?S`-`kmx|K>)|bIIRT^Y-d4 zicZf{YP7M}K#@0uJ|p;<#c;<7P8ihDbu4+Vmq_BxJ?E>N$`eW>3qzW<zR&2z$)e&` zp5fG5&}LE8u%K2%rXN1usT=-fZ=HI5(#t+Xxjc{v@?f{qUH+_V)DgJLo%>ubqpTq_ z7*~9Ry!a#<L$cbc#3I3zI7}dRa{kieyR<3!t`{<}YyEd0{BWGHGvXWH5j2~hJvKJP ziaX}>#z6p8btsU93jOSNNW4Q?pef9!nTg`h?K<$Zp;0c31DmAO-DO7Zf|(V_CpdjZ zNo`_5v$1o)<TB68e+@G{DiA(Ro;+Gw74fr1mCR?bY~a5NPG8!de!gN*Hf>G!QOb4v z0!s4>0v{ZuGHawXQ5smvYG?R<>;X4a3O-66+Frk5xa52XXiL*eZ~2R^Gh?E(MOkwZ zb6<*CE0X^<lc7R!a$m*zWm><Cg{m$i3n_1J%_hH@P^-vWGp;3#ciV1Ok^5{TzmP+t zI!6pIlRmzGu=8V8*7#cj7N7M@0)c?`oK;pcs3^ba0M&!%cNo#0Ra)oqTrhxGIdvw< zfKA(OnW4GYa3>?_uM}mSnK=anpTGCvPcNz-9IYH3Vg2QORfm~SRy@nS?WC_Ia$SVO z!q!~OBW*<UB^I4~AEcC+%E(Sky6Cy;2j5jL9WhpYC#LSS#?^XL0V&ksx0R80hbyJK z)ERjrOzmXoYV~Em3-i~tePJk#D?WN(andxV0g5S`_bPIi6aBBEH}_B1(gLtyI7;V$ zH<#F!kbKVb<Zbocn)q?*wd0HBvUJYDoddM5k(Qi0G-(Y~iPzZx#)}VZ*DU+WLT6hd z-Q^YFE*<1rx<GFeXy1-$?`T6W)<!<!rcj3@wyjPs3GH5D?2HOtpuBE>pZH+B)F-*b zuZJno`pfTQCLgR_bM`fN5l7VRKf4vCZgy{WcE6Hq8FFjM2u+Q9N0D@AhDpf^>{MQ+ z{=WBQ&&NH5Jy3%~FOh@+7;({&yB}m%8o$%qlU^^4o#goCgIswGy_3(K?y>Igo$0#@ z?F&O=5%cX`a6z|1y+6FEGpOdpQFwD!I}wt&SESR@!1S<fgZ~dE^&vUO^Pv9IgMGny zqU%8P^_ZXF-M#k9`+b$Vs_8t15BAC!^T&(+E>C?*f&MiW$w~UGkH<2wR6e}g(y(6g zH9TkyW#bCUe`LZ-h~kuqu~~>w(2fc9@3N)&T<BA+eJ*r<yQ_GB;c$0Ot{mO<h(f=4 zKXh)*Icx0r-p8S~FE+-7{@nGex-O`uN859bDyQTe(;$iG80X<Y7g|V@JswlbgL&#Z zo0AnqzG+1*y~2ziV+XQC;W`HQps9YOJ0s)?Uwon$#g7lIy~iIFbarLST-bLk53}ss zR@)j~XB(jOFckoFZhado_zVSY)B~Q(cUP|%n$P<^)ztFZ>m2{Cchop%hwklZSfqIT zY=8Udf$^`<dQGm0c?mE=uC}o4oB7P(OUm-gCp9=L<BRkP3$O8B`aBS*vkjoVu;S_M zl9ng79WxxM_#|dhs&2!HN$7l!rSYAny-&I`T#xlTp7z2o<)i-3a8fh;$Fe`W4cgPb z{DC5Jw|h{MDYJB9u1=Lk6@gaOi%%uH&KX?FW#tonEU_@K-O*NIKoulnRB`UlZoR&* zPMT8I+R>5oZ`NR0bo<-QkB`gwvs<4PHdM^@F5-F7J^A>kofXY-=L|Q&=}wjz@PDl~ zWgF*7p}i~~3mFM?5m)*o|E~UP66N!T6H|&{j|^3N)EZZi?&mC+#;mxr=6Bsq@4E~g z9`6H@&3LZmes6RZ!z633+a^ULf+NC4PoFKP=NV#K1IP>5r3k@=p}A)MGG|EA=&w$# z>&%MrwLG|9!1DN?A<pnQA*!TBHMQa&`lTnV?|KRz-gI}3-^Q*XdT1?!i}%rEG3?O5 zu;2*)v)ii8y1g>)0Pkt<vW`;X19W;nM(~N9?`{oH+?8$p{r5}d_P18Pb_Ro!=0ool zrUn0dH;cN6@qF#Q_RaL9hlX1s&99}OKSnj~{;e(A8P-&-J3_mTBtAf0zPm|nC4<{% zsWhH>xHZ=D>_1yyvnj6kk*p`h^IXK4J-my_ooWBqM1kIwRI%LSnNb{2C}ApeUV5Zi z7qkdQZF<vXecM|Fp}GJ-NAV1|B%eNDtUP{Z+~;RjxhELoO8%BPQqSr2&F8ulLl4*4 z4%dVz8aTy+HUu?go93@;sOxaOX#e%Myj)Uj%&TaI+b^UyM0n;ct)}4Rh>GUO4qdb+ zN>$jDGUAO8s~@KeoYg0Ehh@ixYnzu=+BGk@=Jl*fQ=iPXwgP#q;28wonB<u03~SV8 z6XH{7z*O7odo~@cHg-Itfx<;H1OiI2{Bpe`w72W;jJxnW|J?1kuCo=+p{y_Wx4~6+ zjD?o+-%gJ{mC{tKO3yw^Xf60P;^>-!z}8;zeX8q5z3kxQq)i`Em8ve7Q9S-uy2Cul z;IW@3NPm{t9Lfi^MAjeC@?xtl=5QYFpybV(Za8zQ(--5_w+>7;={);K#w*CeO52w= zIQljWNIGaktO+U)#RD%2F(kss!jN$Kf5x8*o(LHIUd!_Z;{Zpkr7;fmEqD3AqO~5M z_p9b!=_pog+A!!VAA@rm6C0AlSYy3-2#d9ijX7Qc{8<DOMKcP=-)f=9QLPh_z)$z< z{}b}h<^f{Oue(~M7imOJ(P3V_86b;C_vy+?!?%7Mlg|tI;Jf<$9fk&V`DMHAc(vcf zk3ttX6J5_1E4HL@0u2xOf#BtE*Gz<!?+YkEK^aw@+`4Fuc2IirH~`bk-(XSTGIVGz znFqE>>V=(s1t_W703RT;eToSGP)1jHzRYb;XmC7zBcSN_(~E8iH)g89w#>}#GM=}% zHTb|h!dx4^T{EhmrSLzM#uA;cRF++H4J{{9-{>4Z{>$a=^xs}BQn^~!ma?rLmRb&5 zmY!X}MZc3eMHIo@KJdd@&lSCZ<<tCIU%uy_=y|4GzpOB(isJw`oY1p^i(SRKdgI=t zf0|!Z-<?+VB8y#<R@vH{0Ml6$7#HxtTgekI7_<Cw*rCj4w<OE}WHPuuIQ?aMWamtb z7Ls3TS<$Qm0&3jve_h3T{+<?{?MwyQtU`1DW4JLwOX`Ba#{=^i+IQ-dCzD@a?q6H{ zPng{h>)8?;`b&KtCFqVm`VGz9f_2k%wT3fKADBl)WYT~0rGg`6hwizgV0)EG{aAFe z-B4ca$Ei4s8_6-zhY{&T@`dQj>&`nBBlYQYX$i$F!n4)x8(LlZH1m{$<a(&d^u;QN z>GY=b-;y7bp_?0*CknTycF72Q<(7hslmzD{RvFe^WT?`**Jff{GBv2^$nMP%YmAmt z8wGU|Pm9(1MBhz14}dB?C?|zo^aK)<HI-khj3u4Rr68Raq76ZYRg&x9a`iJhX8w2f zAM`wzX>cv=Sdn1NY7brQ9L^z4Z7bM~jdQNzT<Fg$myr$w0>z1NraHJIH*~-%!&$Pa zInyWGDLxb~We}H025rBPlYTewvr0#0=f_J17NLMpf4AGX#`k~coqkXB`|6e-xIs(N zQ3Mr1y9_bJ+603@;kz=Lf?WT)n3S)w{1m*@0(gFs7AujMFXiT|gTM0l#~0jJb$*O^ zKZ~wKJHx}N_h&4+HP#Yyrr^i{8|GtUDH0h&juf7B4!%nW3oa+|VRzTCA4gC`bWThf zt3vu`Jw~`{-#No_H^V}EthwXoSE>1u%&+gxqGldk)7rNp<`=`^rpAKHg#>OVTd<#^ z*;pTaGIiXPTy@<xAcP<DJkP(G79)eRdUXFZ=?D6FsE?Q4GHtiqJ#@OY%2;^2FVxcW zc3atL5oB1KhC~@gxD00loPJ|f>qZTMp>tnYiDOtP7Ow#5P!r<sG$qtV5Ibi^V|da# z->h;OJ2gpa!2B_`vLq{7a?qyfgt^>3MXImAQGFI806D$Fm^B0en=I72-JUOZlsGc0 zJpVfRU{$q8VFn?SlskgI4Ha|M9>3!RfrYE+dja`=xPPsx^Y;TqzRQc_?{u>Ewpdz* zJ0GfkZR$-)Z446=$HtM@>g)&Zti0A@?bHN%A$gi>P;#tc2bbO{$){=Qt~TS*n9{LT z-LTCdttyM#b@1)<D%FOzmzzTW`eqMQn#O=D$UYi&BfYgOX<7bT>A!2W2Q>n;HiZ^; zFBW2B;L7}u(yG%s6Pm10v!E=rDp7L6M>%h=tE;@vUEbmKKhoY9vR*C&w_3XD+$x4D zJW~v<skOL$a;QNpQXZY-2Ua)>zA%qih4txb`J<A_l?)6ak%ea*@NMR@xtebZEC0G! zcYDoR??T+NVq&u``~(LKv2~gsHmvhqmgi2z16{N?!1*WjxTNW)QT<|l-pk18sq}~^ zue*XD-z4laOZ$b5nje;2t5V;Ix?kpLb&kg9PK-Q-q^|2l^Wa%+$TIimUYe$=Q4q_A z^H->wzg_h`ucmt3nvi(H2P{#mYn|tav2&^`oP%T4y4fO^-km@A*vIQmFTdy-*b>Mn z$iLM0>WWwPPHIzHo^nl*{oQ-X9$=V)ptB}K<aYwDo-&qqrp!h-Uu*CtDsZy2`!&vj zhTrFieqxJZX*%`#jQ@1F{&F?n(!EgK+wpN#*#`v;Imz=7+-9{5qos8Qb{9L#&BKqw z_afRwyZUTm!kUlgm{(PwynOHgfU#Z))WOZ%-#IZfH<v)z@Nyl6u~u=Tn$X+8B-!%D zmqV*dlb&rEW>2>N2A1SJ!6?($HpFsFma=>wmZ6Q`dt~to2@`#L&)0>B*O0AssQP7w zNO%@hLvNGieFf}1UUTx+>W-27lOJ1^*<oIk!v-zWia8?&lc35wl3wqQe8zdU3M}k) zj}Bs3@z77PDTUz&-@CQHy`m9AD2TL2HjKPE<zR(1-UoN*3VT(~KRRBE?R;TBHLG1_ ztL7_BjcS(r8?%j_;j5u{*sL)=%REiU<Ezr~7z(bfI!fFBGUWvDxzW97*p_0S1SlRr z8TNL@d);{K;PTyU*O!)sB)nCeTX$IKrzK`I%&j08nkCI&Ov#IERNwjMAJqiBsNy_! zg4#YXp>(2;d6G%vgL)4NUH%+OU4My(KMjd`>c<Obs_y(H{&e&W*OWV7vnrxgmb~{s z!jNqY{rw+*uXJisfi-~4?~fW>W#rsTw*RocA=c=Q1taq|Hpjnd($y4)SUT)poUpM@ zJA{wDtNv_t&|FA#gOU}iD&4oz-6uO>AGflex(F?s>QDJS)|_3a%4&J-=O$22qNqM3 zo}-=?04%%J5em3~lqNF61Bnk6;~oI?P)=-_P)38K?8sYuO{=GGQ%a2cmM8Q(S*g~P zY39iav19T{ezAEfvB0H*y-Ne*{2#lG2K*+5>M9(JE|K@oxw`TwkYjr^M09C~-V7V= z_w&{KTh=?)$KG>Sq;j3)P#3AA257*G%T^rxjM;L%SM8`{wI3SEZ!lto{>~{oZ<h~K zv7vG9*1<b<d@MsLyom44=Z$Y)&994I)ES}3?05UeyFIJjcQrLPG=AO+zD(EZIg<5K z5-VeiX;o<>CUDA@qIh3+?mU@e!Ey|1U0>x!MGAv6L7(8oHSuRf=s~}Pd<9_pTv}Ae z_@U!9cb;2*Dp_N6In)4**MSl14GqT64ihN)AM}Nv58HC-Lf;JwmfH$4nFR=swYMQ} zPk%5QD1F}3BTLad+gVT+b2a~7_+rb`Nd<wPXAOO|P@!6Fr;nx3Zcuo><cwWW9C-S9 z%C+Wo>k*NBvnov%#~WCoRl=2I>s}##j90Im3Lph-0Y2u6A1mq(@u^oA1a&5k|MEj^ z^Ode9cbx0@7nbqlv6~K8KbsVMLL$>=OVm8c%SEb<O$GLWA6hUb#L5oSD7Yrjx{dBQ zE5PIKH-E8bU(9Z?tyLe5NmYM#<*=26A}{@y7bM%9=RL_R&Nv;Px3$t4Svfhh@4aP3 z^oF%I7~bTIEc5o=@KJ6@Y}Ka|j{?*k{-$iZdKpjIOsCUzZtRRX;{()REck~>SK%7n zypN4pk~${T=3btw?6mH3*!7BDNxk~zJko+4i4mL{rX8PE5^S&VcMqk}%kdGMgghe) zf1f|QO}7+HU5y)1uP?1W$@Bc4X&%20$7@Aqc5)M~uQGYvqPas9czm{5{czd~KX37) zTa@XS?wfXX8|oM~FSHLDei${Mz0*nyeS`CyVSs){U3l^zey^Z@8$0qoT4;0Z^RMEg z&9)-GLecuO+kbi~tjd<c18!hV+!bP2VBh(he(2fX?J`G`d9t-u);KtEzkR%B1BCvc zC#>p%9(WLDn6wVoj&GqUr6xVN8kQ2?SzL9psl52^O9gF~LMcPYQ#%rW)x%ID6<};= zEeQDQ*FOp#8#-iFL5XQ(%bVB}mSZ4cIuhG*b$x#TdF2TkEpK~SxLN0Zao{3(cQ!P` zNSC36@p|fLh;>JB9H+{hyZn`a;=5~BYgN3_Nb)#$^bK3O9H7jTWTD{+fj$X#{N8eG zS$<3hvj@Mg+ue0;XGm}6*?`bM$P5EIqnqP#7f<<S{!dHWKjpopPT80%owk+A44*IU zjOVdsP9ZN!GIYSwQMbt+=i3&AzUz~qgK83Dj)R7lk7UC<e?+~W$rW&>6~ac=dkkwW zAqtWT9uag2b(5zFm0Ow0q#Yg|XC-EFY9Gkxrcq#DhC3fWSE!MHF>OlXeP_MClBSAX z32e+mz>&hfUG@=sEcKHYReaVJEe+!fx_~f|+}tM{6=XzR8)nD^lSz)IProh0w>RuL z{4LDVnY*~To3(8dL}dzp?*p;->-|OxSI4iA_@WnyWw|o%p%=q$VqxPDz$aPStkSI4 zyU$tZ2MaqS>LMdp^jif)$)E7ddv=cjQpF6S@O$?tZC7z4VybbUje7uZw0$6v%vk|a zm6zi_y1j>_2B5hxQ7&Zj$u<ik8F4iiq}%s{3^tnyGZOi~3D0QMaN7erTImmAC6-(5 zWQ2?rwR}~cA2>I=Z%>Cvi%*%x+<SZsPlT6wBbiC#%*zy(aqO~-Op=2W)Ag<is+8KU zaIf%wf0V>p$BF_Z?QG7paYZ$ydOFQgmgOKI-(aH&L&f`Cx1v;a=vdaDt5t{+9>c>$ z!lLmy!?W`qO+mUnD_!S2hPx{~vr=6fb4YsQ*RXmPO9Qxr;uvn@rHevBH1krf%=%DV ziFq4osIEZ|_90(ksD#)Gu*x~fil^cM2%L5lCru_x*<l_gkX5y9F2>h_Gzmi==LuGs zWJ(cJMM*^p2+$H(vIFWKYZ~^cqyk(*LdJP^`Y>AL!rV*97I+Z`0m6v+TKv1|sgZOY zuF6GT+(HXcm_iY?vrS5A{3j<Z`w{kRiwhN`NV6t+Kehy-x5I{@)~*GKOXEJwiBDw@ ze>?RGXpuOrgw%QB5c^eKr`*APOuLj}A&`NgE4fw}_Lymb3O#44>&MOA&Qim$7RYJ1 zTu)8pccz}SU#}}Ef%0yMz6+Gjk{JOJ_gP2U<*Z(7)d5vVXwSlyvE16LcqZF4e)P|L zLX@KE<u{Qc3B8d8g_=B)OqeLF;R$WQu*DrMotIsS%Q8CthzPlULhwDk=g5hsZcKN* z^&u*vs;wRG6OYKPIudWVMzw~N<jZe>DTOUpIy27$K67Yw5hD?SRTe^mVSsN~(#99% z4hqts9P#L`>KwHXm;1f@;}e*;dyjtJ=U_PmWPrMGM(1os{i9)oSP?PeUO6Ud7wez6 zByUh)8j1oo&6dr2%o!LQT<7Ym%3R9eAXa#5X|_eYhrvUR<@gv*@?&Ygv32ukKe`vu zq1*&Jn7@4JaYM9|y(r(`a#7V(ovORd`8V8u|3*fS!06?+HWxSMkbxGA(6tX~DeAY6 z{_6pCK#q(9U@(n{sus@knsw&me0*Sos<n?e`sEo*vP*7JwbAE-KbLcJLlw)VrmVKF zbJLo=5W)h~Y>i14j0}iT8+ivzTi{PPahI3uJU_z+a-Iny=_K6Y*c)8aXlZ@yLYyf6 z?IW>u#D|k>p9Y~L<LzNz@zX|(Y}Lmc^n`)hriGj^klo0gxr0pEa`aPrUd-?<{Jv0a zRb&d`abEKL-Z~rc!XW*!aAA`hq^Q_Krk*G5YnF@Vm7X@B+%zv?F#_9OPGb(;CiT^# zaG7|+yfox4VuQhhn|iM{@N3-&SZ)xA!|-XdkywiL2}>QgDRU+*J=07vaW_k4df##@ z`|BO*apVQnth>g0l)^S8g_{Khk%$hbivO53V63`8m8E%wH^*CRl~ucK^P?(zeh5VA z6?z3P$_#UqUw{2la-8Q9jNWr&H@;j{bJJ}Nc+Fmy<o=#L+p+9YdSNXSc|6eIIH5+c zX)ZhZE|}kKt={&71d<Tm0nXs;e<^M(DtYj-;)q1lx;GtE*0Smdec8NDmBVrG@m_3q z$oxF=RD;ExtKk45mP!`Gt!rsp%j7**Ygp=Je>oad?qlhlb)V3%gh#{i3ll4)A$)1- zm{NcdN4!pcMs$776QtzlQ^(Mi<RbR%sqMF(@&@5yF&0<EFr{eCz+VmaGDBm15xI?! zt{;~2J)lW6$n4v9?1rRPt33?ZmpmVEh}}V=LEKf3IG_zlp0}(Rev*kTaCsHqMXsro z2AhGf*${mCZH#!u>3PH$P?HMQ1Pw;C(sr#Hib?$~ap)YbZo0K}x_;RWw^@xcXii4A zS&+FT3FXKFE#1SdK=yJU{YtLW){(JPGHx3GYzb??UY!pT49-oQGHhA3@40K9Ovq5N zlQ7)o96PTI=vB32tc%&h1awgX%;C(^0a$UosJm?a$me0rO1gl$Q_{nWo1X`eK`o+$ z0-6<4ie^N5q`O(__Wh2FtUoe!Xf28+tXCvJ2=l$Y?9Xmr{qZD42Y?_fIx-aJbBJnu z;r_5+4kW*Oj_)9y2HEsli$9#-n{<<7Mebie;W>eBy*Ui*zoUDA_aw;u*V9O7C=2@$ z)J=~bwwz<C7iuDo+;0s1p2(j`i7w@$b%xcMj|{a#l{tsUjxfkehO=Shi`d#4DANVU z`)_}}hdfD`OHkx1vZm`jvG`*onPY*I@yR%M9Adb{4qDML#ViK5Yln`+PiBATyB_v^ zXD7qUvO)x-9zT>bO^kO$Y((>xnJve~T5gavfOxHNJNLlmggp&p6eJu1`#ohGR%sN! z@JaL*o6C{0z>x0NWIlTEL5;JG0vbl~&GM9W`J7`zT9J~<{6uTphnfiwW|(QQiv1r? za|;i3jYjE5n?aba;k-hvvPBkwY(!o>^O|yP-@x(Y5SE_!79-t4+l0u}9tf3hPoz6J zhM2Sk8sA>>RVv@~4iRgr9lZ})L!_Exxk@%5zcqtW)g0UMfVMk@T1A0tU0BU?3)ilM zEdk9HjRW(GIF6tpuy)k-G9nMCwwN}K<^Ir1oZpV6hzIi0ab1}oWKFjUt{5@!m6sg? zsvqTx>+90^uaDWBD4zi+bb)Ks?xYW~F(zGBkI>}{mL17x1!>SSVQ>4^%{VZs?+=C) z2IGq$Aw$&EATo1ka}e8CN{zo`45wv9LHQpq^tTHkI0*M%610xSY%=O)WU^Z_mZFms zBhuKdJhcY`r+0_edRoKUnE1NBA^Ebfqj}K-BTec?3G+-*urOgk=z_4RTJZ!nv7+iM z7*?nQT}9J<dP51RRVF0gRgYL-X?Nv=*M1~T#&hW%>EzoiQOW0+p`-NEV3b6Jn@6h$ zrNN;dAyy%KlSX)XrNi!-)VCOlQeSPXPG^D5qC^1=T283bKmq0IHy?OX|4*Izyd5OY z2=j6%^A%z3L+m!cB^?P9G~4?`geE~RZRfLbC_;1Kg-x9&-i}DUGA<Ijgwe}{lm$Y@ zR<HFAo}pI(^HiBI*~HqYoy9Mqrhg<ABph4AKJicOQO0V;XcB{l`d^-JDWs_P)*E0} z9m~pWMo%OK8$5G!oa@*w%!x7CI*Z-=sWgWlZQDn4zCZmgl@U6x6_Mwe7e%rrQ0bA4 zs=CezJy{%>Ve-}#h5Zy^DiZ0_{odp>_6z&8F+P;WP}-#sHlDATgvy4l41_x>hu1%e zWq1p_ouOY$81#w`ifUNF(m!CI7-W=t*9rP0EHzF<`XX(K{e##@UharF0fy`(9;4(= zXjyV)dnuh@TPqa~R#t{D<lsgkIf)o3a(Oo~fQF#JV`1lAndO<s6C!2dMdqwHtJDo3 zjrSVlZlSuJwA(?NA{603-WMfqw-Ku(tw4T8ExeO*Wgbm!a0q|_oj3ZM^l4?oEA65g z;5uP*?yY3Z(xl$RRq>kO`T=Ul4u_)tAZ`hEKc3OR!Y_p5!KGcr9BSW=${<2O1b@dN z&zSEUg}#dR3y7EjjV}Qpib9!pMY^z0M`9o&W;pq{Ckn`o|BV(N3fs5Ca*G=E_Cz!s z6je1l{bC%35SX#mD<=9P#4_}I1&f8XOzUA)JS=ORB@cpcC7&VtYQ2;hP5Kz&bhrx2 z$@#yk-Z44E%7Wz*Cs*xxyjKu&cRnO4F&v3k&yQ{)F&Ur>g5k&kG2YJ@SYof_qIT1@ z`2@DIcWeZCs3Xn=sroc#N>Ww8R1%kNZ~M>K$xG=v0gP*oCOvqs{-=YrhMYB0f+hMi zQ_zwq2}v!_aEo>~>~A^dFi7q29N`N>)>GfIbstih0<g-lAguJ<YO|mzR81n#Ga-RT z{1Vm;A~&xePXYaARtXa%nXW}Bq64{+$hi3|0yS)Bxv+}VuQoAzA+RH@fQNXEbCJTW zmEr^m0RMpLth%*h3>3!oQc*}@UiWQpjq@0X3H`O2-c0P=DsBr9+#e4FZ?<wc>Tb`J z;d=&0JSi>w_r}@lyd@Qcj(YBo+a!1C7!rA4p*cEDiYh&sOSYM~rpUCRp2HYH@88OK z<+6r~$FY7Y;RMHJX0<Gm+rsaFAnb_mr*TPo7%?Y1h5YEk1~3BmNEmNnr*)aHN$e*T ztzzH@?=pGO<QB?t*0VhNVdUg9IAl<sQ^v(jO-n1poRw)Qag#m-RHX?kN1wbRL}heR zj?+8j;&b?Jp{3kA(G7D^$smWx$x(}=0K#CI2UD~2*&;DW7IhiFG0bBaVH7EdH+6^@ z*i9qCiexnZT1ob{pzD-v(o{ZHy-X!xmXkJ%B<taYO;gHy;Y-6uUg5aKII4y-o~*3e zP&6=dmB+@rs<SlKH5-scv*gFrePUH38Io-yBj*Vklm>9!)tq~9z?{#45xQ@|^hb^_ z3qY$(FBB_Sp3w?}l{Y2jhG1O?5I*TWxsukrZJQ{l1$AN(4CE+a^|+66zyL}}EOal5 zex<jTG*nMhg6ANkd`hxqwgKk`K>J0KK?qGuqF`LPRDDZ3OtT*AcR<#=<)lTPX!|)b zPlK&`4>@ME4;!7}lY_s8JUsvqBnKTUx;grD4zht^5|mNDfAgNKQP#UWenM(Ied*1e zbR0}Qi5qQZDf%rVGJf)Bf(T#-r2wYKzQEDysy(iPfL@OHLDG1JZ&)0z^^+Qen%sGA zm=CN;Qfs|%1vQiUkW6-+CAt_aw`WMSespoWvoxdtSJiE#S*I$1Lv}rOw8Yt_hPaLt z1vuI!MMM;@iho_?OIFYDA@TI(;aAWe$}@f9lhV<`?R!%ouCyfBL|P+Dn$Wa`!(@j& zv=~hQWI&1@SQf5?-FCIX*WjF4vac~>u$J<P7pOj!C!^PRM#9;Dw4&>FBAADRj6)~Z ze_zYk#GJ^(#kPVbn4{;+S9;xoR(h08gtm*08a#4okqf!~YVh$T|7V`$4fXq&e{m&q z#Bi)+fk%=otdJ;$d*r_84Ks>;nA-3IL$T1S&40gWiBsx7o6O2cOlcXd9`Q7luP{%B z-GB4#kkkC9BulR3lZMZ+lUd?DKGG1}0VB@;5a)h8P@M}Ew+{ZRGurvXsKKsciXI^h RP-`CqgDtJ;YyI>3{{x|i+K2!E literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/20kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/20kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..e7f85b4ec42af8f5b95e3e3745651cea07d279f3 GIT binary patch literal 157846 zcmeFZdstNU8a6y2hIS&*vfAjlo1sBeC~%k1=)$6g!E6LUlt6Zgo5*$sLO32~5w=Tq zH6sH^qd7xz5<$$<Rt`Ct)iA(zl!K%RXv{Di5@ZG(=CBs;{iE-F-|PDR`o8b4@48;> zpu#Y-*7JJ~_j5n@v!;HXy2E)Q>J9N595**N&foD5XX@??&9CoD`v-@!ZXG9p!{N-~ zc(}dDamSw?;o!xer*S;+XE*$L;{m__`RB#QhI~1m_}ZiR-fH~E@g2hdo*;jk`88vK z84Ju<V8#M77MQWXj0I*aFk^uk3(Qzx#sV`In6beB2^NS?`!Hok_RhsGzJR-(b#T@+ zn=qflS^T9kfBMfJD^~_{{x^g0L=Lga41++dF!O810y7qvvA~Q4W-Kscff)<TSYXBi zGZvV!z>EcEEbxDh1%h7)4i0-EH0*^J7r*#&82)|XMRN1Ap+g|b1oyYd-`w$c@CzKy z3&-*Q>94;|zV7kAzJBmej=`%2+=G#PYldSWR+#xUV}Th9%vfN?0y7qvvA~Q4W-Ksc zff)<TSYXBiGZy&&l?A@U)nN00^AP!cW3T<O*%Nok1@g$>@t+_0-CF(L_@7^&`i=7% zXO_D=`4_)D@bBz7vuAsF%zoI@^PxG9KK$sTk39UyBac1q^TcD1dq4ijBTqc_g!jDp zPd@qNqh1T1ero>HKJ%ZPPu|3B7JkNK_T1UC=gxoZk;mr$zy3A#1IK&LtRH4`X1P7b zarbtc<?S~06NihdosG>4vV8G>{c>~1H9q7yXYRv~;05QO;JCZZn&s{>i(EBcy$|2# zczDnD`Rj{o9-0^Zj^}gf^MgOh|8@@V)zg=sjJbZFAM$QS?%ao;TJZEU&-y(t@Lv+J z;%_g#yfQTGwTRc>5JifkHpIqljNi05VQb2^f26*b_WsVytdFyINq6u6^k1KSejxAP z%7Vh8L&aaK4j(HmE3c?LUUlNk*>mUrbKzoL{f}3E`uP`KlfJpFy`%F+*RMBk-Tl4K zXzDi)3=WN1tm6|8Y?F2exi2@|=l}fm=Z*c}?#mnZ<?i7z%fpl0mz#Sw{+s3PG5fDC zKIF3|+Vh?CdCvuZGH3p)`QM(tJeL;|bN|VAGp;}U6o18CzcF%a(|7j&?8b8cKi%2? zy0QO#U$;1q&H~-!J<FRzaa>L-C3V)H;ySKu6i)UrW;Wuu%TUmIe3??xBc9^CIi$VS zcyTDw%-q&kua+{sswvJoe|HIG+w*|#ZQjqM&_k|sRee*OT3NE|@x0Y^&w96hsm9uN zO7E*qRynoKv{-?r)k>MaNsE!HQ)J1GrXguK?a<l>-;_%NslZUGbBa@4Y2eF}*)NYT zwz%*ezx5vZcACP6{WE}?$PjZ~XQwz7h2oc0zUg}INMD7>SC*<`&*Ut(PjQC&N^P<v zd?itx%tnxF**wJ&_La<Hr8*O95eImMn5+1Vkxg}-l^>Ymn94Lm1MU>BRV-}IrMh+2 z_9>2(KfxcfD@9YBQh#@9LMa<%H?tN=5G%dTo@%uikMk{4oNT8yIC6?(J}U8@&uQX) z#jl#;3|5X9acNne#m_tV%x${C>hJ!tqIHV%pDe*B)rq&h@wT0|S)x)hME&dCT=T`a z&rxBWf3H*9BQ|x=mbNGkb%P#z@<W(=P*WVoQ?yp~DO#pDw+h|(3pVK3GZK5Msbi<T zNT4x_*zPraO`|-Dqi7{p6rrRIVG47Btw>PZFX9%%By(I%_{N4GG{ZtekF>~xwzS*m z#%g*9*NM0Ewa7+Ry6X3z%M|yE1upAxd|91-ZT5k_UQw~hUgWz7M>@1?iZg2B1h4F~ z3|RW`K{sHK!_i#F6o*-`(EAt7L|Yh#4?_!FXOH*EVJB5b{x23Wdy1{=*r|WsF4Wr7 z!abBSD=e`&Mw)NWijmxwSz8#B#5~36t*_=J(&hUM-BX<QFhz?JR=pt`p&V%&d5lrh zaNMkDs&Zd>hkSid!>lMJhY^-<#D$D@uVK%&Dsu$6k{-H6y!7o>>(Zy%+1(pEGNk#} z9@2hhj2ykt)u#3O@FefP*)^_QC5W-Q4oq=&jj<zmyUFgoEv0()C>OqUaQGJM+b#B( z;tW%rm-*^cX2lfeP*x4!UYDorS1h^LK5$<|X}HCFr6i5ZtYFOWw(CW8saw;^)4mfK zMZU@;179g}(L+<52bz(=y}SzDOP`zd)F{u%&k!+_QyloV#$k@Wtuwx)g3mhau8Tbq z4NiA;(#M9$RKcy&CRyNlIrZfGy+f>?ax{@pD!Q^+H^rG}c<eGi-@xB#&kza5rZ_Dt zaa2uNgS&O3Beh0(o5Y^xGz5lv<MO}BGTzwz^H1#aZP_~Rh(N(4Gnu$ni$Jv{<@>(t z72A?U{hNm9i}ICl4W3SLUuL=Z-;FvZpxvfvz&#iBO4&D#)FN1@PP;5cV==VWzP53H zYke;9J$%03KjP%89bV6cQf7^6a|oQW{x73FBKFM6KI_s2F*w4go?o7SvICB`dxxWr zXAPKpV&5xFQt*dw7uYltS8)K@0%qqioWN+ecgOtf-bdgz-j{uqvJrd)<Cr-4?k?8g zo3DQsF}P}}?$QFiX;SWGPu*gu5&33_xFZPCDNd6A-xT$K*Wq=ruaR!2LPp_ETC1~O zcyZc?Livojm_6&7;?#W0v%r{#()Ea-ZpM*%GlfLeW_~(5B8Knw6@B#uw_lo$yK^Gt z_-f4T;aCJdlRQcdYg|@@MIjPa9&$-LlcL@x5)_**^V4<gDJC&9aTdE<EO2N;TCD++ z30i9v*7GHS!wCC*4(i5UM8X-#MB%16BaL<VD0M!5s<lGm%O<j-V&ugUqlQUVNf;w- zZO5T*=Gy$N{DKxmOMy*EYnaM6ADO4qvI$~8kzhoq4QU}kp;SD#(u|CWBlt#1&zAU( zT^7<#36m5)fA2*S^Cpc7mw25my_X?Xiu$EWvDu#We&juVflZc@5C5S;Y?*pW3Qv}w z_#xgZ%;VvsVbcIHpID|M%dZ9rT4o58gtQd29@}#&*eiI2mCy7#nh(yUI(6J)91ZO2 zs8_UDg@$0sM0)$;dMjnBRQXY@a!Cl2SYW4z@OLJp+C9=`SRG2TE!`lG+TViM?IZz_ zEs=|P<Yw`KvLrEIjcjP>)(KSo;;1_!lRcAU38PYGksx^q^210{JBg%Q4%e|<l{iwF z=4G=bfsuW=IO^Z@COyt`l)Z^Cvkyv8%mk__PU28xpH-k>>*?MneKidV8*0}VIeK9o zHJ+G`lx)(B@=1<XXG%Ora6X%zhKa({Ws6cBa3bjxXF1iWe?3RRChVKyIN<+<BKFi2 z=dbL@0iFfvE4d#&x(v5sn&SLM!BNg3y@&)3k*XiA)I%G?{=S;(k;1iAd~TzaFPBVc zhWd_4x*PKm*30@(MI)^G2dC_5M$y7>4_d3F0!f_dd}&>TEKx~U+i@}#s2X`ZITgb0 zj`mcc0-m@y+amTD_0<e7W_l40oi|d(^tc2=C}sLay)79oMZETUQH+$z_Dw@Qq{pv* z&7~&msh~JDlI!LtHrl@2I>pJWnfRAS*7x$AQ64y3c+T+A<j<Kz+Ud7G_go1vOuSQ9 zHS65{uN0cC_<)w(LxOtiialOEQVqG*x>b)4H=W0Unl!HQlWBbQo~IYfy@=1$d{w)B zyN`$|C#8E8waY?tRnBJh4aw?VJOvBO*3>NFchpu|jS8DZ+#h$5r=H7WZll&C3&pPy ztrZlnIw9iAQZnEL1#G>v=<T1{#19=29+YNCd>5sv_!?BR!pRBhxjA>p1sq*J_RzNr zZyd??RrHID(sbQIZ`*5cnGa32N%>uY(<co>b*<``jr^xEE{iGOx2o4=!-YQEVSYF{ z#HJZug4+-93d~tP#d$0qZ)q+UBS4uI$BhO1I9{l)?ULZKf)>;`cx=40p2}Vrmm{aT zI}h{$6AcTSzna%tdah`(2p>@<mvq}TC<ebCA5ho|IXjN2OxJxijU}GA^Qw6O6V8hR zR^dfgJqPcgkJzc-AyB=#fx00Me|F=g#oF@)w(OmkxlD+%?2>w46g4@iB$-OB+~?4U z<UbBY-ceJ5V#-u5IWd{BZmA6b%eT;NL)87GZkwaY2n%<;w&T8%)H#`D4bYphcFVe` zdpzWo7CCBLe6;TOM-YRi-z84_hS6+p!>_+}%AOkfm>TNqC0J_}_im$-)^$&uEThMJ zqJAz&Y$%u<S~-CvIQUIbd~v$-`>+1FHR{}HO-t^mLBXnSe1Oz;w)KRMgs-G)j=L_f zOkCbF<Sk#ip|pkR789_xE;nqv_w#wbI2N6J$S@&G9vN=Yn#y;-d`0YPSiaV#PL#dA zCiA~7b%;Huc7mL6QSqrH(L=@kw1Kh@zP%tuW{Dg=G?qz^Em!WB?$I3`N+>Ka#Pu~O zRYD(WQS#)_)whpqe7Q}uv9F-D0RDTZ=u?HMb9nQTO{M?29$0#G1G^ikyy%ABv)Grm z8ki*M4TZoFD@)p4^bI}W&5pv9Kr)9aPTRhmykkZ9_e<$U#(Y0E9Vb^X#d*#TxGjPt z(FnQ+F5ws?f2l!aXV85Us(1MLdI1xHOk(P=h-d%gty_3ZTI5;Gbr^zLQH@m+rH7oF zDC9^pr1V8(Dc6%RI3(#tWYLu_gFQ74RX~k*Y>(ok=AT7TR!nhHt3MJuoBC*Ysimz7 znPU|x5v<gnImHRF(G4Vp-W;-r*KG&jZp2Mzd|(weUl8tOM;Vgukrz5Uo;pKokQ5S! zb_t}^aC!LCTNY1oqJ<g6vZ;cRVZjx3%ApsL+WW<CC;Y5c`D!K%wyZDiCQoo1Pe!gv zz5Bt~t;yUrIxx~zN0}=T*6XMTNB1T7ZE_hNwFA9I8sS|`s+|;6OVE{@{QW;am2X!k zs#A-dNG%^vOxW@o>s&m1!VZL2_FG4oyGLKMPD8pcs*(1PZvEvejRmb%J{+ne|CY{k zRCoZz95*FDcz}4dE<)3Q5;)YR2)bI(>MVj;yX~1AJ>O~uTB5C2D|>;eM~3E*<8P@> z*YVS@d8F(6WA7)}aWF1x70-gplv9DF%DL3Nqa2Y*$5(G#CQBUCJL`l7N2=fIg)g&* zrI}KnHD+Bu{UFoLGvBNOAckdd^y&DGJyTi_%voJBmsiljQWKin1?=YQ{X3KryEzUB zF__ZWvUUKe!kM;lki@na9BI*Zr4(q2y?GsR+*oSBjWWHXl=&#fo3%1YA*~iyGp*_0 zi{q+Bz1hIG^vT0Gy#2_fFxF`O_k49yjZ(x_0cczKC-QX&vzC>vW>|cR;~nme`p2GS zlEkaZU~{w>0``*_)F8(o*LCi=QIR^zQ`lgioW-d2R5t$z>0VG|cj}QGSV^}&MkG-A z#pB`u;WuA%^Q9Ya_M_|;3sfQ%KMMfInT8L+i~FjUrzk0V+J@hL({V@n%9TTpp&qy8 zc&&~!Td5AZD@;t?5UpL+p=l(i+#f5WUDlGhBm)CA2=RNR>P-uuejwC3QYD{Eanea6 zi6#aIuVCx+;ZKORZvb``q7oZ=B$Vqc)9bR9+Qtm%_)NHhWdrV^g5yGi9Y?-wND33K z;qUQx8`Jyx(A85MZPB}-lr-)RW6XCIy#tWq8kgsAr$1S0x(*aYfb}7Ic!^T-yhFaq zLbrtSOWY8Cc>p8RPSggU%Z4-J2=K~GDX=gTQZk32N(-=@K}(|Ob{eT`=5ikxIWTAG zWoP{&^stV!7!f~R4`_$eMsHc^F!ay^_3D+RW9jU`;npywc?Leg+Ui2LWHv!Ia{eCO zX;;E-08W7tN7{y84df<gz5k1przWw9P+PV1rpqgfs}ZP7c3GmPp@2zt)Q>%Fyt(D{ z9XhCGf2(pOuC+pgl+J!p;#JY;*SGdDZdAcNE1Urau2!_*vvE_S)Trs5?OdM^`0|&z z!*`ToVUx=+L5i-Lo<KTWf8YFB=FzpS&V9G@i9?}NuC4vO<!<r6`0{-TBR3+AR$-H| z!Ae=Us)VS@719s4HGdnp^-Il9H#DgQwhTlF+J+3-C~$Z6sprPtI&JLUB=%U8@)4X( zowTQO^yi>YU)W^u$k%6^^g!<(J_7bj(j@m?S~>a2oxcnppW>Y5Dd+HDdYPy=v1fGa z?te~*W<7tJ-Ji`xUpj_2j&xld4t5NM3crWz8Q6sQ*RuKykLZ1sYX}Nj=_255^V!LU z*Xs*x08fzvk8drmCvc`B|HePcffVy~{e()e@)%Q=^8JK=c8u9&N&o2HbW7}uE*a@m zomC}xM3}YeOIb1ym$mv<ZIO|#R-Q=EnRFZ1ec@e3H<q&XF@Brm5f)c{uDtTD#`V?5 zn%gL?{qg^qJkizEk*W;kE4{jPsAQxqG#}lixY8Rec`{9FX`_O_Z~4hv|Jb-vJjJ2m zcGt6l6)#r(S1L<nQ-SErmB?ZE>B&h2;8;VXkuklkKxryAN&yPxdBQqg0h5@qF?*R3 zX_q}Lvoi0-W}v2|yGX0ts4yOTWz%AU<qv5rSG`7LBY6NDFpH`DDb7vP59$=}CbaH~ zZg!Mbp=eCB1Jz#lrQzC#(3{rrZ^nqZD&IX*9ONSUHwk>_%~@z3;7T=Ma7sJKA5i4_ zrI~gkLBfaf_1s>Px2XLsN)*L~OWg#;e84$tJBR=rK0ETe1WkT*0Xmz)HE4>0m_%6$ zJ-pg%XH4GqbUR@wCJGbh2(>-3>6g|peXOO@ioZ+Mi5hFWvrx><XHWBUB@<aBCWL*A z>4l|82<xcfvW#c}Yy(P&Imh%kKv}^~E$GKaV(A9uT)sRM86dU%Bd=gsXRxer4f-RU z)6lIKz}WZ7N%j<|d_NLRaXx?pO>r8It%M8pgRY>hZBc<91g_JF_FyqZlLplM4X*vN zvsn^ITJb}9T-Uh8r4NYgD<Ee9g5;yQeHJ8m2V!g3U($UGwSe0Iu+ExC29%Uz5TQk& zW#4CFfjkubmzByE6u&u_x*?^9c?u@gIW8rixm<YB$TA||bbCG=RIF`LPLpIP=ymJe z_-rbJFpH1bSKOK_HZsNxIMb?tMs-SYG8~SE%_VFXZV3={r_KW%9X-m!HS|zczqlMF z-9s3d7D*3*HpdyGw_bn*olmtE@xcsHL4>M1D)RN#lPVJ9#vQqXTNLX3ZyLqU?=@CK zYiX-hKw2iP-TbDdPmSh7<3a<}ROp7XJdw|$eKU^+;3zC$f8>%nlg@OVFWU;*&ZS>1 znK<GP=!<(?2H0cX=q6O}(=s6-{cKBvhhDZI%aHQH)}Fd-GI+Yi5xeNTv%o8D#&xo_ zq5iXeY?OMcY9#_@Ma`z=+pETE=rJMSZRxe~-_{;CTKO6T{2?>~@9!*H{=r@?u4v>! z=Bekpn3ORcoEx1n4Iic&Q8Nm+KNWJ>L!DIV5a1+-1?$@Xt{i3p#lrgRq#wq+xxcJl z(DrvL-*QI@zv$F?qL(RPpL+1G?Wj}0V6BXKgk{nTb|uUO`uQ;u4ykx^|DB$bRbr>& zIfR2StGMBI?S@Lt?+*%$vfr<m$*r3@eD<#YPQh+AaEk%JcD%-D#@~K>lkrBQ_}yXv zsvD0WU>}sPALHikeP*k#ItfOA*#R@s;##~dh4*BFO%lQAV)O`Ou`=HN)^oXHUah;M zYu)(*#zzvu){8cdpL&AcCe7EI?XpzE!ocXA^Rx0+qbr1aEPV>G0IDD%p}(9d&oU!X z1)n{ke~x&RY$Pf-iY`VEyWX9(wwB$Dk&W7ld^2_^qpCj<6mwO6i;}!`(FWo%Zw`f@ z?x)+MwoxshN6pHdxzu3!8{jCN7l(j!-2|$*US=ENNV+>#xV`Vy-9ZoYE8Zql0h7cD zR)n-vBAJvI*fir;bLO?)1S?Tnc}2~WN3Pb>Al2X@M%I+hB3`QQOqb2JNyU}bB9)Na zm|J%W0k*X2e(!-kIrUv~rOFdzu;fmaP;^(dm~kO)5YM>J&d$Wg*S1*wm0p200Q7j9 zOlj8Q^%hrM03Bq@5)?c2OWv<>M{bRhM-Jf!qzjivKFLY|uMtXv<-3D^6!Wcr^9Kjh z3Lte)za=Zl_M<j%)w{dEswk09qDn;FFYovk&=T}Vv%d46vhM9*BrG5*k{%o1Y2T@H z>JiyV|F{L7$pkc*LGElgq{LEp2XVryQ6XcTdUZ_jxgf`WU&KE&@k`Pg=f8W*!tdLk zKcCsF-P{nse3>B|`MM@s_E`JYj#GX6n+WAHGTb)N^7OqOrQqIH;My7rMmA>uIK_Ef ze3uDW_x{?8_X3T~?R1@BbWtd&s)g?-6fW36Kq5+@m3>(E^`N4D{UuU2OrK6C9lm8i z=@l~F3E2ZA!LL*yGsBK868oU&7L`u&CerUv_!mvgPo(QZCsNo1llhXWU=3JX*QY?= zQ6@_*<~n8DNMF;l15`(Rs|TB0OrWIQZ%z7kry<0aZ%1Mukrvu{1qL)jCeVp0Aac|| zmm!GR2E+*)>ba^j;($4Klyd?4Qi(fMw<EbAaN2olQ7*73Y5=dq{RTKo9Y_%{lOsdB z%$7bYZudX*y$+->{Gh3G;NI4Hs{pN2D{~uMUp?o)^^9>3#tf;>W^-eRARn#={%&B0 zHk&Huj#7h1ci!@)FR7^s+1oeD78TvedujXnNQ^WtUApwyE2rEp_lx>PKpfQoKJmIO zUe?8(B^sMj+#mnz>cpLsLAIS!91prtxj*c4bHx+~q={`Lj8>uCyFP@EE<O*V^n*=w zYP(rWDRY|(7}iuchle!tryr|J6|GiRvpf_H(c$&86@e?JAvLffX!XGenA;E~r-MkI zJ2K!NIZ}pio4?5tP7|4Fu}H|p{H%9Zy6SkA0ry@u;?Hky!9eFynX;>uo*><#I=v(P zGQR*VCvuy)oD&@Sk_2srqiH}+uO4PMgW8G$Nv4E#J2DdN^EpXt`X&7Q>(1|s_!&}f z6mA&Gi=UC8cV6r(nbRh@O;=lt%98yyaCdpQ(A55D92$ut&Z1=G4z8n~e}r6f<|Ld3 zBu6QejPnl8d1kuc4h@d!$piya6SN8uz%;ltF={KWUiuvFo%7WqbcyWl4ZMO@b<|!` zqpwndCs6N$F$U5!So)4rQWV&2#Gcwhu^=Dw7BC1Br+uNwYzJ~fX#+ioS|aTLm4s1= zz{*!r!DSZLq|xgC*@0=aPVSonMpDlOQJczy9PcY=Q7XvY810%yOm}_)%w-S9(MbQ@ z-l(+`)4r~U`!Op@=DLt6fa?n3B4or+8n7yV6z*6APy`Y(=Pz-4wU~173tE*2&{@ze zQJjJnMu);#NHFNtDCL|1ASE~79bg@$q+i$^jU28bEL_+oBs9H^^skFBMFS*n2J`}d z-hG{`lH`U8oAF*%t|<-xR}JZiJT-#iXuTjm+y^;l6&bU&M3D)A)Y+_PEeBc>g?kmC zFDBlF7x>F*gbTW6&|e{#DEa0y$n#%a^T>$%VzaOgdCD?GewuPwE5w50EFj!Wx3jLS zw#n3=K1z#`v2*!&FC%JPSCD`(spH$c?MewQ9amGE={6W<{^=&z2SsF`vbV*`16jse zF1DPEPZ;xHQ*W6ISe4!{MK2g#a$h2pr5r?~i%$z*aBr{I$z+_P!`vU|)aLg56@8W5 zi)uv>^G_UF9jHBxd_Mef*YCfa-R>^k$y$&a7IIPsXb)FvZSua{$DSI-k!Wd0@b_D< zOmWV9bLhn>&QHTJ`&&WDJRx=(f-gp{UNQNZj!Dwx!(qaBlY_q>5ajNf2nr;Pk2Ww& zo#s~AXZUQl<g*V;<?Z*j?4`%sZ95VtPJJHOXAx+v%m3gPFm!S3-xSX#4;S2)d_1N{ z5;CkDe&pUxJ2C?h+E3BVp0E8r=a0p5+`fbYPcTxK_L9g015txLEke^+Zbt!K?;T@@ z<F|xGlp|8WBV;Y&6f|`$=Q5(vrQPSx$zNBnyJ=b2{p4A8&8_dmY%Q*k>g>9<dNJC_ zRr!@bsbkH4BcJYTSEGl>0LE{lCW^S42d8>OWFUFnWG8$%!n-95_!vnko;_1{HHUm! zN;)_RT+T$H=y`pg!l<N}$IEibArQhliGPfqu!y*z6xak&xCd9Dg6WVR%8*G=+}KmL zLWy&V6NC#yyNkM_C0zv0K0fZFIelo%fo8!-mloK3q|@cKl38(#0;57WYw*O{K+5&G z-vW1Cu`j#r2{9NrjG;jLG-4wCT&U3C`utTfKOcFQa1|Xn;(mmFAQeQ&{j&YGgKq#A zufT_y{vhcTbe~epG}8z^EiTGF$ex+TFc@YLc#n5hU>Lc^7i?n-Y51=VFx`zxky8(g zY-SmW@dKC-ffwWP5v{8M{nU#KbeP`+ThWTL)mn8g1$QUS5F?AjmQ?TwGRPXVz<oIK zRcIyTl+(UZs6~Q(L&RW=V2)6VC<16V;}YnB=EZUp$PgyQLZe)~AGc{vUoN;^0yM}4 z(D%y4d@d#zxLU*yW5Rd=9Z|ZS)`?UmJ=h%*Qa|v33I|aJF@s`L9RTdndXrt_`Y;Tn z`l3X7qMdQ%@IZMX^wGd&$Ls|wXTsgL+wvJl0ZymdihHl1T_2WCaf*|1IqD=N7t$S7 zjs}D-#@*VKA}!3V#uU53(mTaTVa(_>t59Sx{jz0(GD4Dy$DF;Ckl&c~Oc&;)05YiR zC0V3E590oiX4u~ijjTZRXCDP0uPz0Bfww`HT(txwyihOHlA5N@5{!Ur?9_wnzZ%Aw zPETlz0aMB_m@Y%>-)>fbGs4fcL|s7fL9<Wt<a+T6R36OkLCD6>Y7(XkR5ggZH<8>D zyBykytY7!ODqlIVBM_q*fX9O;<r(iyEY$|J$U%&1RBu}OR`g-Gu&yvJd(&RTWp>JQ z__-J*_4-<%b)X*<;#e7D9uk@%G{DO~NLqYrTNuzCXOq$)MLq}d4JL4UfYgye*Hno4 z86?F6QrD*d^0Xd%xzx62z@3DY$aS`A5f#Fu;y(Tv(5PuBnXO^AJ?{`|gQJvG_caf? z0Vp6qycqbW4sFqNfM)q>?2p$V7~dRlr-GVL4P)o&oXr=&e!9+C1H6I^j43W>FWpcf zX3yH_NfUS(y5X4k<&IBg>CqULNhUIZgO8yN3HLO(=8L>k5#Fpt14LMI1fR%s`(Sh^ za@6ybp#e4P4Luv$RLI9;tR?E;T%LVNp{>;RULnUX^OEma?4i^8v}|V+0_HzQmLA3l z5YG%>s6F6X>by95k7r$uZ^ip%WJuNUJK(CaqVMl&7VJATcUfSc^&aMmy-tjVPi<HG z;)hpNqNO3g`*OH%(Myp-^h6dPn2SP<*%Hc^|2g^5JZLM+4Lc=NZ;Sguu`NsE6?ExJ zjR?&f)18r3`EBpM&tv3~uK(tt`yC3O2sM-XP69+Y^yxwP!ZI}602dq0`&)BYMS&H7 zRWbXslK#2!*2%z9c_<I#W4v%6>>-fI29Q^&Dw|8&6SwE2*Q*_khSd-yfaqM~)UsV0 zKt19pghML{mJ~2&t4!|SXdc<SiaqOme<<`N*+}Se%DL^sTa(FG5`3Q!`OfPmm6>qX z@wmWY3Mq)tpO&FWDjkUk!_Bm4Y4&5UEI6O^?pj44g;x`BW-3pyE0dtD0QTJ-H)%Wv zs$4jor()I^!54&kgPmS9i9p`$Y{pd7V(f*|0CEM>7WEKiH$#JC^IPL9i$EbF=~$iV zmTbcS9cTs+P6Xp$vIZoR(EATAqPiRRv>Y-Ff<`X=oy(qCH8x$rH?y^sxm0i{HHfL- ziPHqm)BxjP91gay^y@h;!)=hs0Jfu4_Unyo1nmf6wn>CaG4vCl(@0Pl>`eC>5Bfbh z*nxB;7|sRHV*a9(X(+k+hUB@>mr&47=$~(b#ibc>10#(W0V(7;{@oI16Cuv|wb>#o zb?y}62k$q0tllCtIMZ-meKmjCjKlmCZivciWm2-LJk#%12^)UG@b>{G8V>>$zRFz- z$z+GHg&?F(ebx9%zZi%SgT~$B<ac%jN~j;8CNhG8N3Xr+=xcZ0!)FrOryQMIMyyhL z5Zpm;ov{8?Kgf+yqHFlXM+|-%6X3QJ(hR~A=T|!PODv*(F^DFx^ob~S!~Bw2O-wHn z;vCl_qaHV^>A*58b$zdaSr8762^t6sj(M<rwO7xyU?x6d(KannJZ*l{KHx4zMv%BZ zk7iCpB4kEz%!kxT!GQmSXByR`tdL6CmNVB#u-Alon~#`}la?Y@4wwP$6fMV%yE$N9 zWZO`z9I31+9xbB^R6jldzC(lpl5&gd0xC+OR3>sXbI>loT&CEY5zDo-g$6{rFrN?i zQqz!efd~St)E)>VN{|HUvj>_v7f4yIsWEh;9sDC!GYriZY2bwe?qVJ(4u67;mB?aN zo|2l#ZzneaUpryg(Jw|r1`;V73MZYZ{Ux!)s+BrX>%%==r%{@U_;Yd6{_>acbD3zG z!hO)Cpo9$#g;MD;fT5UPp!e>PS#p-`J3*$Uhq97wM+Tg$f>BI^K)0PGpu9(lLJZ&k z5To1zTULzNs5}6Cg9tN3an!r|pcRN!igBS`VW*rI2{Ny#AaUUDj+W6Eq!ytmh!RMh zNQ%&3sNth9@q7-PTR^I1Imo)vQYMwj#F#gMz6TJ%)o#S#Re7LK847DnaefG(C_@1m zg14iW0Vm%bLP(ud31&HtW{mI^{p&r7qwU^0(;q0!vXK%cp-#J^K!t8F?gtX08%x}& z;3$4Bu+`vEG3d6yC?)1{{_df!i^i{3lgzc8(ykYQ)<h7JW}noB<3=&R<gt}J>%Fa& zmn~vnka*~To_cvpB54={D+^e5{VYCc>*L5ZhhqV0np3!q${a2x*ML&MU&C*`vI$oK zVZ(*TzN#z+`e3>_e{X}|9~}OcHRMX}oc!m@S6-0#!q*9XILo%@n+OffCd3vE9nyOJ z6XO^-2pGQ!W$bR<mEXL0fZjniS?Y+fL{v=dOg-40%6@tBpYc&^H{;c0LiVoKQO}V% zl7n&Z(&<Dy0AK1~?<u|m8~(l>?4Wh&z`_j4Z7Jyl2}O`NY^EO83vOwNGNT1f7=OJu zKH9Jqvpmq5L@wpZi}?O``&)ZP4e%68J96G3&Cn1K0h{d5Q-j~o4OM(a6LVVz+mIpx zc-j?Z{@Wa+X)+{&Ju0#mmW_3boI2|wsvCR`O-+xf3BDs!)ks(KX`+fMuzduymadEY z`<y;VXw1daL4XOWLkslUjsyIL#0+A%KCr~Pd@o`gB08u}J{Xhc34%qKCbJI<-ZLs` zN7`Fp`!&E|i$tnt#U^{c?v0~RAdHJK4whqb7aYpBuBNS~4ltcm51P~ZXfiJxN9;ov zk~$i&%cY%WT#+C#0rS831Yj%RWC)1b;s^_wZcdwv5Go&#awFzzz<za-Hlh8`_7Lv- zTi8J_icA*p4&bgYB80VB9vGd&Fls28@PkJ>4*pqTwCUGo!R=8?(cnYpX$4?LvVph< zsR=$8gpvUOtIkTE;-LH-DvEapqhv<@#N4FLr&M7>Lm`I8AP{3P&EEF9SFta88B05p zcrf;pcj5n1$n`K@$8=*T(x@bHkD9tJK#Msx^auzuq^ArR3-ud~KISpt2LpixB9s`m z6rtK0Y_jBH{EZ9kAE~pfiQ|2Fc8x5Ndr|Jy&GuoaYWhRb(!*j9gG($Fkq;z2ianKI z#GMv>?it`H378~QVI@?s$aTqta*EcYjUX&kg)C9FjZ2|Vnn2@|gRb8KQVcit!4Py+ zFaY^ci=U4a>VxrPUV(7A%}9r-(1%hVt5b1=1As*AW_x<a7!+i%J`5)8Ln=$d?R|tF zLmJP>;fX18nFd#>&WeF)2-wFPO>y?d<+<t*bQzNVXi)!F&7y?Mt8AlCn|6ia#Lw=X zo{464?hUVZJ_bqzVg+`0{F6+bKxJFH^%+rN8{2#i^9(aEAZ0rGPLgP04Uu#LhD7^~ zLnwelMYg@S1^H_(ZWvt(zYxl|(%yxfAk`&svx=Z;Y~EBTI%@-&a@GQig~^F}LK(|N zUGyBSqNe?<BV9+@fRq9o8j#i0#AkWbjfatPP)v~B0684>U}_*0WlWe*5$XmiGWjmz z;hN!j&IyvDS=DuDZ~zn=N*=aI3pemJHX!zpy|Qf(vJN4<4#z@z>yND3xyk(*VZ97( zVcL3;vl)jNn-hx;wif9aS!8gEGtq`ZfxCkvuO>PA=9_S^hz#)E97+m+zxj>k6hhH( z#zBRQ4A7`eew@{zxZ?QN?rNSCmrI_NIGtjQ+%w`=y?Nrh+TBmp-EA5<DeHZwU*e&$ zwAE3;Yw2!%!WQqbFIlbzMd<+qG`Ud&S&GL+Cw^rvU9la)0EKBTcx&qcw1G%NP`rva z-r3)T7ekP;v8d-re|Q1Rw%mWQ`H~sh=1O^ucso%30mNnn$=wx&Zf(0#e^I`NX;{xI z4dils;@2|O-zK4^8Tj1st5Mb^d<!2$mfl(aNdKxghE_ei%V?Pha(#~6KJ=;P=A{(H zLKo3P$r~M|_}te!EQ)VXntlvLHjyZp$sy^;AAGB@VO-fbBm%ZM_g$SL+_|kRL(CRU z3kKmiKJP!pZLo~AHMZ?J)f3D8u%NB<pzON3{Q0W)kOXz(vLx=UF&$r)bo(#B=lU%h z7IvUpYN=Y?9rw=8kdD>23qTEKW0tqQ)EOnVL7bCsFY1r(jcW=5Sf~pK6<yuEytdp7 z8W<fzHv%9~3@!T<=XBy5M^4zs&~PIn4rO(w6(@p#H?^4pg1)|X7!oWK+@`Lb*8m$p zg_h4+4)l?^W(9G_WkaFhnS$WBs+edYnZGl}EdHX1d0?0ba0ufmz(PXhS9$uhd}v1x zm?X3>jU{se8?`<A)KJDE@7sop_uFKP)%9P!O9e`aBcoSH{HgciSO`+5m3MOM=o26B zPSI#tV|rIt@1u>{$=6E3IEGF)eeA>bM<O+?gf^`}wd^}ped+ODk>E2xLJH$$Bm3~b zykl2ChI(i^D#{Y#N(H0->c~52i5n568=xguV-i8`rBy#Is#(KjTxH7PKeR)xW(<>4 zkpjixo+`7>WY6MT^%TOVQ7uM$QNV2N`1n$aQd;z3r0{?dC=>y-eij--+ywMY2)~s9 zbBxviDd3^LpYDo~=YZVXOhNk)?F(udsJ09Vi(j-wGJ!-zG`8WM8oumZx+P3GM_32{ zL5@lsLURXl2PMJLd;ur;=d>9>XX0H2hGpzX2_juB=9BCSii!x>#e|SRC?k>e)+?pp z5JvG$b&)TcR~q1ohjAhsx_+Hd^FF$VvU+?FN)MPR8)$3$<2j2Fu4_DsV?<okeA74S zx(z7QTt{;*$`9c|-B-@T;Bq7uoU*YuA_G#ML?}_81<uZN;}(N)IPQ()eJBfwy)FR9 zj0?~&<Ulr<$i;Bok;a}W0d2AYnHaKqkUZd^Y9J?sz9?TGVF6g5mKqfK?$q^*Fh)7N z-c4|upv@!<G9;+=N<#O7h2EP_<efFg`SK`0?<Go#fdA|0-k79K^00L%9aqDYH=smn zfVn{LsUq_27BNhghf0Hgpe1e*FUh~m&saa}&VCfdI@VHy(8)?>5|J-4okJzEO>yeN z-K8?L4VdtB<fCdX6!G8F5Cm||1Jo2;4`PZEf+i}Vr_U2Mfl&e9qv$peE=OvbmJJ=p zM>4lDgFv5Z%c5N8N*<;zZ_o?XN$7wY(Sx|O!8vp2!E&U1Xr6e}llJhZruD6m8iWCV z1^`cK#@nKl;>9KCCIiI*;=o2|C7)NW3?zrIjH4Zc;ZIF}KC<2tA`P-<y}GXuz6|Fg zCpYUK>!McTwej%Bu+tBn_K>BjxNJo2ZV3u-TOQ^EwK=c6lI;B}ATmtbPW6c6`^Fq= zJn|M|Zbbm4AzL3I+X}0fc)dQw`B#+?Anq1|W<|~NwYmk4VpYGyq!YN#$?K$;9+Y7o zV6?UCg_=fXlwxmIa!a`d^DOk2XgWZ|UpK>{mQy!kxmZ%cL3>8ueTHf;#my9rCr#9h z4cv!#0ooo2k6rcl3s+vm5G=Vk`7IRqeGOMo5vtMg5dp`?C`nf<zkd8x$pqKAiee(v zDVQqNtnnZa9uuZU#)y8e^n#*gzX2UDc)E(Lyt<e$<w{{47%8G%t;iC-bSVN!LkU@u zu@th)!bkTriJC@a0i0uRrJbOVDhMrtY=_unyEUK^bRD6Q;0oE{K5Mut53pH8=EXoU z7jclT!M&y<w?IhNj@C1f%o#V6oWI;(4Q?M|0@|VH%X6Lz<r5Zp@US$4z7R*oQg9o= zA-EcvXoa5y9VqC1z~VODcCwxl3O2A(748j55vbZBWOBkqf-ltuLO+6zZhD}S4kZV$ z5spfkhxg+`;DEsvrW)(l9dOwxQ<*FgG%vK1R}YMq%Ds5Vb=Z+XnTNWqSU}qAOK2!I zJL^EAh5)80bMr7d#tPAw$Hd5+z{Y5im1PP92pR=Y7KqSNf8`wDq2h4Q5p)EWK5#*% zvV0<oIfi)=x%I>$a0guWi(?WBNjn}ic_Y+TdZ8Y+xkSb%K#FIX+efB2xn*ih0?=Um z76v8Au3qRL<&cOtwbq4kKjf}NONylz@scqY_LeRvR}#S7m&J!8F-D|QNu=w*GziDu z)yPnIwO};xB{2q*V04!ts0d?Vx{l!jdSwiJN6Da19+wBX2I)x&?SCkPo*nmtJQVqf zttaaWAubkCPWC^DZk!6Nv<L~ApMVw@WCGn%N!)aLV<+n1VlW%v9LRh?J}p7Zh(%*8 zR41av3bJV&LC_VE4E++xFzjv)&Q4=bLtJ!46<~S|iH$6o{el2iOxe5*6#TCf-D=U+ z7VsoH@%2o%4YqVWAK{Axc`KTarWoatFz!V={usLqz7l<AnR?rLawDR%_&WTU1lX*x zXCVaRTbH($?H=zv(35yjL^xQ`<ZNx@jmVz*N9!Qsp9aa*$0Xf)wzf<jCP!Nm^=OUw zFJv7{;rd*Z=I>948l@sQ&)=O2X*ssicns860BUKt2WA!1t%<xw#HT0PN^yo@AH3{o z{474bv*j3M4{t!S(Uv1nVBca<DVg+P2#T~yBEt$_jm9Lg<RKgjl`Rn?9fC+l3#&rE zUD=uFuHx?*I2IZZj=__LJrf3vBHkdIU&#4D3FI5L2k@h3eIZB0Wt<h_g`19-pxe1N z%O5BF+=fB8#+sKN=F9&r=_~nmEAVo+4@MHJ%}i$LJuVc@qXGJh8eP(Yf9*}m{?-8T z>m)oF3d-6&OiCfqP9cpHeZI3T>%WU0+qsUt@g3SY*cdRaC8BoEx{k6oZFa1X`aN{~ zmE%Mdh^kPQfge9ZdtLthl?B>%xK`~!I-{)pYkht0Bgb8n_yU4-nXyK-ECpL7lGVS6 zc}mrya$%w83-)CxI7dW8g;bW3X%DO<WjtnWRY2{UcOxO^1S%`kyss=#O3Ayt{sW1( z@--_U3F42hfhAj_Qf@=IQCa-<dXc$P`v-CC%_azSFztzd#8+D^HtLhUn0(6u(y8O% zuD2}Wmqa@Ru$ynq@5WEsN_&$kO7FgX5wX1AhFff>>JtArEIbGnGUvOruHHuZ_g=4B zCf*i6H~`he*;Ap;Wrr>$77g@1-lrTIL0@fu$8SyM)m$-^j->^q1dR37k^<-(NOMYL z$5@jgG9idj3z)s>Iz}(7Z@Qg3B!wISw@R!UrrqwVlsGR!xrE3(kq|ldUsN)T0^dG= zNqs{S?1eQq0M&4x_s>X#-gcx$LLxNxjiNNJ@dWG7tL;iqi`}75PXzumbv=0kq|L@Q zbS>BpJOA94!Cwb6q_oyzBxI9s)`aH|ik@9EDP|o?X}(sKynN7F`OQmWNa#*g(5b(j z3b~?O<Eu^qK@92i=u32$1cqKVH2+`gC)F!mO~&ISGj%$vsO)FS=&m;F)wuz!deTH! zSM^~qgS2-jy>r@;DhZLwM-E3YEL*c010JR-8X8PsOps1-TI@0aNsQv{5CzjQ*%HQ4 zceP-aZ6IvKa(}!R8t{p>$iaNH0GQ_yzIoeh>l0Xv>cck+^*jcXD?+ytMIbm-Nf0F9 zBvo=XzO)S>$Kxs9F)4gljb_kp7O40LwWumSn}V8GGFPZwO)saU5oFq;q+EHn0D%4> zbXsP1lq@-gU?6&N;3h;;IdgFh4-OddshJ{v9yZ6Y?PeKpyN|G51wL>YX+aY}zijUK z2*d+vJ&};W?@s5>28hMmeMqK=g#C7lB^Y9pmJ*4=fGL{iD6}3@9oJy$$PmY1(b50{ z9B7;H1z<TxjAVfo{0<7p@KNX}bNFf~;1bgTn68!*4bO0CJ3_IXd;ei@5`kplXaF?E zpW1h9TOl8JN=e>Bw66EyIy_zDrBDYVBiB@+><~Ph$w3juBszVx3P*8$2SSLmoX!@o zUsU_-YZ`*Sa2{Ew%@ZgoRE71ZEvTa75DD>c;+y+p)7g=*)1E{?(>Z<MOB-?Q3S|9` z;&%IWU7QeXC8rI$Xb^y+l4vIi^?gjY$OD^grRd24m5ufQEwi%%m>36msEEoZOi>aC z;tddMVjS)wLguIl_6%xKf&!3qcW?<#ZHM0}p<S^HwcXcd;U<qp;xJl{-vy13&K>o4 z7el-NYxC)b;}A?1N+{J@E@NBBNg&-!rHZZ16KZ)l6~B4#GH5hW$X5l-MHf^u2jZ<1 z+U`?Igq~7uHgP|$rF|NASgG43voJlzm=7$VM7|PxxJr?)#xdK6aDUfO`z_!RZ1Vx! zt<*S@7AdXm?C$j*fMHcU`2n<uRZwZsLj!K=w{={Y6PE|n(t4cCp(5yED%)A-&jHSo zFt;s8<Vtks5Wuc6vzDAN?xQ+La!{-<Db70+9kD(V?0g}oASw?PSyMktDY(~@jJ05N z7E1@5oBPh+KUs-BESL%bHtp3f{p-_byG0-jF!X26-SmUYkAR5B?hsj%&B(r`yM^LN zHe6bwG|r7;A|gd0LaIVttI1rr48vZ;ZJ)f1xsAyvrYIsZ2gr!JT(Aka(?DS|-$vaz zwr(qqljOP@B2znd<)t!ZXdf0K<j^p~8w!z!FattuA{=Q=0kbVdUxV{@A+*hZ0yWC{ zRtbv)6OWXD(}jjG@-M4Xu?tQHInE-G^3$sIq<4Wf(BDswq}9`$+P<xXX~y78b?u?9 ze6)^aUWau0XXk=0i?Xt3zSEwkLHHBqTFjh<8V&QM=hi<os_{j}@WHF`vAoh2;1=Zf zc3Xxh(e~hiLmQ~Lmj|c?@qQ|5L&;+|QLw?uVhitF!6bxB=m8-LR_Xk9_Ws75-qyLU z$xz%=1d73AJQug=@y}L5?T8=3PDuBftgP8J_aU4xV~7fl7hHrDW}}d+%q3$U8L}}- zimVVEw)gN)Y7r3MKq}Z(K291_TT>7^QNA*)zpRUbhuW0U%vqsDx+odAj|j<29{&tH zW#J^zIrV95-a0<v)7SmE&qHH3AY*Kphz&HW#LQ`In8?sB;fD$g(7w9Bna4=SU}@&I z5-nmdbU2CM>@L=DG3!HjkV$`lwGD`*N*+HXo=$C;P9xZEWs0-<fk=s^&6UN8=XRSl zWQf-t;(RxfOxRNWI9YSyzu59w338!D!EEzcN9a?*=+a`vCTqaUopd%@1Cm~a_0?`2 zx-8JH%3ZFDF1^q&LTlL2Xx+Yk5mjs?r)pF%@6rQgmYW~?-b8Y@j*nI}rHVSA0zX57 z!fFO0rR>Pjl;Ue5p*s2NF&#NpmSQSJw@PtpMBkByJJS&`szW(Ep}BP_MT1>#{B+#k z>uxgj1nM3_Ry!fyhmtsaL=#6!&Gn49xqk}^+(DEZ@vr9^WfWslFo5fa^1F)dMFU%c zF3E@2Dgh%gj85H>mGFkJBI{{V9>8LxV!eo{!Xe&Bn;y@_MxMUT&zv^fV0pYUjN_w# z%t8bWHM)`95B?I65P|U_E(r{NVD15zwkPH~8C-#xME27y^od4W)KUev%HcusA%bQ( z;op*p&%i$03eo#eY<nqC7{=<p`5pOCBWLa?aT_eOQ#YP{`PwYxq#-C{l|&p~1F+GF z<~{?YKKfA5EwT9>^Ksoa3_f!|<YHHKOEbDbzu??FSF>WDxBgA2fO!xV!HMBsOU4bD z+yLpiqnyGi1`Cz3%Jm-U9oXNh3y9(@eH(J$hWpI;&dZQM@M;u&71Bbe#EQQ9{J<US zABeU*XVcPuAAV-}KP<+I!33j2=)?hNvu-6N+}c&&b?@UB?ZsgBa>IBd#jWXk;Ack{ zC97hRH|e)h#Sut_y0~{AR*Ke(<12Gl_7cH}A*vLrnu^(?>W{xeiq`a=u!s_FXdBK$ z>2aR9J=WDlojC;&?c}<@wLH!CGDp(*N~vv2vg$c0kR9brP3HdEE#hOR?T_#Knp_LE zml=d(cKSnzzs3lmFjlwp*)Q8v6Ox|{H^b9*r1>3wf5|%n1NT<r_aho)ektSleMRq0 z-sUdhD{1>GZgopMihEO}d~EilGCTi-K<!Zz3a)GY^}V8nWtv|v1*icM3($WCM-r;M z#mcYsp%>BHcKu^i%>IlJLAuZh+1KzYP=fsur+w{_CJkNp!z5JXTeR25t9T9P)NP}1 z)c6M%%{Pgu<&Dqk?j*bXwmhHPwr=fSTMT9xd;k;}Na9T0Vy)4A`~D^R7W>Tm@!4b! z#*N>Sm|w|cqJ3C;SmRuK#Zi-O9Z0_UpGDwIEPbV4pZzcUyiE6O@#o{OG&D$pN1OJy zo_cyRdn=DbCYsy{rJwA}DbA0#&vov7C7V($yzK)CMUU*>@Exq(>iA(dPNw;)x9YM5 zqey9#wXHU||I<^~<Qr2ZtQNx{S(1;~2<L@~!Rze9c!kUeZ^*`0Gtu?n2f=Qrw*_u} zXSoq*ko1N(q*<#KCz#K68A;=gnuodEx1b2XgrK5n8mbqi(AFzt#W>EbvNl;#wFxVW zWW0CiVEo+Q=NQ#P?JcOwjkRYmDV~F>=eP5g*;OxrlA-wd<~c8oR|BF_*z@ONdwn8n zyz39=j)mo4j$QW6w||5#{K7Pbxm9F+;|Mi^aXhd+Y9L<sL*8PH=_SumScCyAAI9z8 zDiXGOeM#Stpkt^&hDBzSIO{O_LVF1UgB}hD<wceLH6KxuBy8TBA>J<B30XHJ8W|$j zlO9LVg``clq(i$vaGhmRGTj7fi)@r^5MoSBimI|&PZe8HK|@+|!#GtG1XcuE+RY+D zXDR@AKphgC4j0u&5SddiD%z}8CzLh_DbQa4Bu0>P8tiTfMxg@u^Z6s4WV;z6n*&B7 zI3ifBU+l-lZk80QRTwMkBX;29F=F3ufHW2KaJ<uir(s||hVeaAh2cKP4_IO=B~mmj z_XUcVuo1E(4iUScYdTv>#Ke@-9$_Ww@M4g|njxfsjYXhlO6KC&F>edb!!jXg1b}jq zw2p(&fPj{)H6jx!PmWd)$v2r;!qn<QWHOVF%nFtJXh7uj%!(tzP6)w!cs0bpP=W)% z7IK=frcablBhr9KT(~WZzXQ{yoTb=i@n9p=V5^0BtFH^#cCZN8MHLIc^4^FB*7x%f zJxkYAL4lXaNhEm>w`!_{n>f-KhY+M7MlC5AX2RCDu+4*Vf|!e*;>?zK!llJ;!UqXo zi^0C(4ip8BW<^UmDKoX$9wsf`$k1&lO-|4?l{&(5LLLfL1~r}pg%7B)Y7F}@(ppUB z>zLGHc7_M5l;Ay`!shR(5n=s)=-{ouwS49$%+~Bic^)4zgWR}`<j>Vq?==q}QOp_) zwbW7IiWn2;Z6&2FB}b<Xge0M7!yW9s6Z(R$-bej0PD0UzDdBMzlj`sVK;i{N?2=i) zB*miUVK)p120r#TDp-YOR?cctjSm570OYjeei7a%USYHbb2~JyVAvh?U{(<p%4j&b z9N?S+a||rVgjCwcbc8FCA`+HpE{h;lp@Dq-vF8AV25>4Bh(}=H!U#E)^HL*)2>>bm zS;NH%X4Tza7b}<qU>0VZ)bn%Dc(`etht$+{;=TK#eHDPzp;Eq80CVEg92bXfFG$7| zrLME#WI$vJ+JNc4rT&yr!kz(Dot2+>WpPItIW97D-{(-jGGLTL53Bbr@;E4C!6{)l zKQTRk|AWpZWTmR@yPc1+*Mc#9$3r%HVwLavz(M{=)kz4Ak15-^<7^91)hU)0y&0<V zd{C%dL&O%nSo0U3&?6nRRm!^zXpa>^*gamQ80kZdOZi!e-?oY#R3U}mLXVKDNoUWT z-1iw}1uU%)ZzswJEdB(%_Vs>)atCHLB9VqV1bBQF{klz^f+WNITN!x==p1q%Vg0PH ztIYaK)M$rnD_QCkC&a8V>4B?S5Qw6D{!T!_5_MX(zky%80pex=xanE8LSjWz8p0%I z?QBAd1O6q0VvJn#aa#WFpOS?RjBd|joLwlLN0dV?VeMpP4?JN26^PEZ6MY`heE(W) z;)ceo-Q1@vm7@v63Nt4EE!90KO3?NMPu_^pBfpYcM+B@Z%*fC9^q?LhtiCFt3S12h zN2)E7y}ksq#ekK+>O2WmfZkzMz*nJ-%~PCh==z{B!egd__iVZYj7tEY6V%Lwg<3}) zg4H!%sq@Uo+9}pP+1iz8Q&YsEKZ5Bl3cUAIl+ALkl;rdHg^LoA!Lh_VWY78bp(AkY zUXXS7=<IkSR=vrSJK&NJ$n~0*e*NvjQ@C^!9)l&SuoE?+E}(}zPRUun6&AHms}Q1; z4=XoeH9gf)FF8Xthu~c}lo~i#f;1~;WnXS&-&e-zot-iaD|7Ag?LYU94WlClk6c~L zBWbkO@C!vab5(!*GXl`RMOA!dG+H8gb*Cc8SaQTm8J2pV<n80Q-cA1g-ooa2<oPz} z3P2i=SY7YN?S*a$y(!N*F1E-lIhYjw9f>vY^J6RfN*;Lv&stKa8e*{UL5?667;L^9 z-VmxB|J|q2KMsBG@hes+uH)bXz)eUapcp3XZ1l6SBpkf(M6V5yE#kJ1eN`x4NH*!Z z=cDpXWXeXustZ0s-zSkrrK(;RukrK2<QuJlxPSeuC2XQH8lWA08WQ$$e-2`Mp*R9K z4$qpvs!OQ97)*OT2F@rfbd3VTt7vX-Db_x25T>dkQ)C-(OM?cU{IHb=@~8Rx((MHU zw&+G5DHehC0@XtB>m^?6)NNkRrkzQ;CF1@@C=>54?|l{e3ca&=|GLgp#9$;gbF&|e zUG7^Oul5Rj1yJk88o}5#Z<~D9)e{)Obuw$$DSx4RM6trAp_<va+RX{+dgCSnu!4^# z#$lRs=-dyjx%&!q&U%~Xv$OEtIbUKPDEr+(3??Y{bX*+1T%uqCzK{Qr-B+QYitz*? zbbR<`bkMF$!?E%1_*V;}tbJo|RAVHi=Rc7k#<Z&#Zk^_A0vuo0wc@=M)eVx#$Q>ss zsjq_FZ{u5r)suUEKly&wTI(M|ZpH9=u`^Fle@?ki^PnAaLOU4}RX(`)aip<9bNN|( zWUa^|up@Z1fCMC_^6Nev-gHh$<`{Qh===a%<iHVp3<4Z!WJe#h>&C{Q1IzcW5@tv| z4}5rP<PIJ-!T&gT4Tf;gf}boMK3r5YW>-Jjc9eu9l`qtc8}Mun3~7$<>PzfAzce{` z^vcH7i}s@*+uBdxlQ`4Zt>qtu4ou|r<w7t&k=4J&w_fh`Y_g6$3$gPK@d=$T9zkbt z3?|AHSyP-R%Pe9+@5#KdhCx7gYCO3ZByz9IO3(yWwl7qPxVN-YUs7u-vR)%<ycS6a zWDVD%J*L%+?NQTGB|=yu_Ao2;Ak>Bp{FsHWjJ3LLXA-&2nA3l&61Kc81@zl_L#N{A zlZUSn`I+ZWPtYZ!AoK(2;BVsn*Y>>hM@j)8djZRIwe`B=EjJVOB0vm_m4Ie@!CIvx z%*&pd9J%+A0vkqu$kR*mgEH+tYZbvnWKeS~)R>DYC63h$ftL=TSsaaBrjjPU!d3(^ zmG5-lJ`UEIY&Ve~w_u411mR+gli;RCG`*GTY5H7H3>;U1LhMWf0>jLq&`p?52JXsf zbws8Cq#-h4XC@td^44YEwORb!sNE!R`ZC4Of*TCRfMOVA6ehW0`x*ho8Y{4sKt_SK zEh(A?1w>urC3A3(o7f~Q{zx;|pfuy6Kvtr7YAkKgbrs-I4B!C7zJmm@o*QtdzGK-u z%p;lZMJYtJnnhT@2@PfQ$5Rxv(~a&lQ*k)907R;@9*j{czDKZMMUgO*JQ@t=;sYT7 zM`POqNShj=PRxK#XFnb-QE3Mh#^)Ryu%4J^wjd-OiX^Jk0t0FbssMa;00p406wmZ> z+e)Y#IEwYe7-ow>t$2XV?F`x&h0nrv^E+hN@t{23!XpVZnt(wrAIzPiwL+TTjt6=H zwtA%N`eW$_2KH9$^aB{$qZF-jF-cT8u|9Y@4G?G%yhRoMD0v<U!J}fR?lCzxLTz2C zux0sT*hiRyOpd_io=1o_$UL>^V47j!X$**&99hbUMvxl<0gl3WIOtG+cOnQj&C^Ht z;H2<`n$Uo`a0Y@tr5Ggj#E!AQM<IZ~x&m>ZaNncAK!of*^~9nOMNEr@zzCq11$bxL ziE=howQ$wE*6MkPYd}NLf*%aHYaLqlrU(obwy!ZIC55vC@~V&)JlO+n%e+dm(3giC z#fK7ro-OhBKt2Tvf!e!dYXLO0ZPY}TZvg-R3->wUCTym%-=rrBsbXzQ$t>)Gf`+TY zLng3xN0#yKm3xJIV4}r1_!`okwuC8Kq1}ME?j`6v=GHabHFWD2?%whFL~>BnG~yi^ zZfy+3ic)QFIGAS0mP$&$mCqR|>m{OILL7>H=L%^&bHHJCJy|ftnd|X{*cW^*&Vq6T z!`FXYV@!ai$Fhs$r`aj-OTPE3L7^HjV2O(Cv`Nu!-`GC6-<IW}UW~yTYEMb%y5633 zNC9*;z;7%2Fh=O)DJB2p*E}PPBU>yg!2!@yfbw%+-g@5JhGl-;G^tha$E64j3|`mu zH@pHI6aZlF&oN@)QZn>6m(R{P`Y1FVaB+yV!M0mpZWk(gu%=%(y>{fugw!TT7KpK- zjm(0>9@O0b+JI@T{qZkWU+GuuJOy175+6uFNC_&SqV*glI-bpXzx0e<zhH&&nAZY{ z?|pP_*cceaAfPAClE3ZOd;D|9UfB%hd%B*aCW>6ozYKZYnNle1>m3sN4wGKwzfgN~ zFH{S>^T2TXpt!my7RJHhRvC{|cX=onY6uk6-~TZF-n|qU`m4@ecNhn@BBxgnu&8h+ zWo+SXaR1N_Q2+T5H~V{3V#)5Hn|l#uH>5kr1O#JWhzKAhXMdKSJN$Dm$p5^*J%g7v z0=!yF3%$goFH#fdRbwOwH3%M;09lafn|wrSv-Q*kbY(!{PJ1*{FGds)7&hJ;h^?Cx z@XnZ+C95uBL83qYFjGqd4u;%IMv%dfvH=tK#lhA4%IIMXaWxIj30^N&+2rWd`r}p5 zne$5VQY_w)iFWAgt-Igc{Z-jKJ91oTz?_MtbMXANu`ab<h{ZceVL_Yr!ZIFI7a)0D z<HsRhSn(^5o*-<4Zusin|Elp6JZQ_zqf0W1TX)YtZ2BBKT2NOID7Md$I~>=Zf}d28 z`jUh0G{sSP5E==8(}EYNyz~A74W0vI>8n{njdo-A!dS{AZT>5sI);RDNQ3P7r{j~% zj9}G^pzj(+QqC5U{+`f|-5na5JuHsaIh%&W(~5$M=|)qQs*3BW5erC)Ipvzq!D^hp z1>9@1KLBVLhD;9gYmn?E;|U1fV4#pfl$e31`g!Xjh>Q*yV<AS=WN>wS05%QxbTlhh z6)nV|&V-Fp;^G6};#p`I9FnELoM(VxF$U`GnD9VixHwO@XcE`Uj;Q)&7WKGjVdN9- zNF=6mun`hAZ0>i>&;rCN1SptzLM)y&nn+akP#VS(M%4%X@sB)`Z?2Z%v;7t&7r$0n z9P`TOj(YH-2Oz3Nh75byE4UP#=!SqA4+Kov@lvwSYmu;_G3)lXo?N~(PP0}$_fA1e zK4=0Zjt$#}hjJBf%GXMsP0;f*L_6T^%OM^K+V|1nqAw3!@R5zSRHW4xIzAXPcwi*a zwb%BPdgW>OV)jGj+|fnU==H45Px@nG!DP&SyEBtKQ7Np-xC0Mk{KszwJgW0-Nv|lY z9EumLowy!vJb@7j9n^9v`u?Z%K=Q=ZvdpW${TRGvVaG?3DoMp}<YAfrgQatUi@HqP z|EQRvwdA4P3K%yAK~!kbQfYKxvxY(40R&M4sl><*8VV_i3}NM=f*4Mr>kM&55c8CZ zCYcs;$Pq!!643xT8OR_aFf+d2XL>*X&wt;|HJJJRp65PX_jO%2s6R@Azy23<b<6ge zq)Ll(`CTR|DT9uYdMR*S<EE=a@81(GBt;0OW0PxEv>EFJV3l$*zo0YZ<M;Kau9h7T zK+tBHh>ACt$(I&y+dtOytKT+1UlD?1W!m@mZ(bb%+vcI%V7B8XH)On^j2ScZ@GhgX z%sc*%EgIUO$5#isOxKLhzc;rfMI_fAeC2eK#yZ|5qg*_F+%MHK11AOUAg|`%t&^{} zFLW})Hsh%Z@?VW*oaiuPDUG-l88P{#gDHju5ta5^$-TN=%WV$F@?MRYmbsS@af!Q^ z!-ymX4q<EkR7k_&nb-^lXkY8CWZ()WbR=e{=~pjbVue0)Rh<~ebH3*BkNe*03^zVu z#kclPt-s9ifGj^;J~Zi8T>Pu|`If|8@&wtgt8Kvy%L)ija>Gf7ZKLk}cMCW74Pb~l z{NLyi###i<myt74@MNT~*EAYrQ56hDEQgC?H>#W;dzE1jfUPmvecoRhpf1e*V55hd zhl_D25#;a-0%PLaMO{Y4LXL&WetzrJ6zpb#biSr4cqfPH_!&#%XaF*GtN50sjn74W z2<}r-beoCG_})r~AkhtCk{g|CH3a4dq4|m&zJSV*PxgIUXb=wsbpgG5mGqJ1Ic);S z-$})Te10p~T#4x2Gr(8l`)ZQDO2IabqEqxr0wW9aNI_~d<jzbEdSmaPFva5G;P7F0 z^2G@T?<v`Eks`Z0w5nh%Qk;O2X#4wIF*l^6Yn>elB-XJ{EhfTs_K;6nCCcZ-C|Asn z$tIbM<*o}?5K-4qiV#0Mi05TOp(s9qKr6+gjulWv_L#f;S(?F<VI$`rf314Iq_G0) z!*Hx!f?|NrEed@cML1OkFU(2n02@wTqAN1b$w#>+6i~vfM5K)V%ij<ON4~s*%gGN@ z1qvXy!n8x3sOC=s1rbK`;9|lI;Z?PmTr||C*4YULSdK7u9Pt(vq{&<zhjpPCusZk< zB&R|7GkA_mB+)ch2Au7yS}cn?t03^&Y;V)<T4<)Y72hjF)MO%JiGITbu-Ls*<a(gP zEDp4v3~&u<uI&j;DLN$?GU%YKEltSIs@#6k)Y#3Y{Oy^0N#Kl_M?+<<3RJlWLR<j^ zPLVPSq9sG*)XF2Ue`yhV1y7SF1L8MIlWCv+U%!*+VmaLmK?f&ldaEU(s~U<_BB5-; ztWr)dRSw{S=yE}C6^7lRG4d1uttTYn$-zq&G(B$M{wr^*-E+CmgOTv`(wR*a-JI9* ztzxs$f3$TdnhRG1v6-^RwQm7sLq+rm8x6VPj7pq5;^uUecI~6y`{_`nIiL7c)}%aU zL?y!iLxLc^&3pNC?U?SaqVh9eIq3nZfJ7=ha{}*3$_d7TT*xHH7z?W$>VrOO<?&Ue zDds^YnQyE1Ka%J@lL7~mK96<c@*uQomA)&qa<|If8(wU&EK?lKCE1GndFp|{Kr+%) zco}#YN~gc*+F9`+4Yq6P#kN=41gyXT)Wv+|Si;M}uH?lP%}Iw{-3y@*7#7k-t<=67 zQ045oxV_7NPTpP!WAwPnzZ$lcC(L2&zcB!Xy4SD6(a_u18{0=M#yW}PtzEAE<DKCk z-CCO)mq7^WH~DZC{IH7k+T`Q@0r__Vn0hXc)C(J#<YOu@Rf0v#8v2=1!|_;cz=Qpg zdZrrUu=F{VHXT!`9w5igmxPNU<}?gPG)Sw(=l%~VkpTb}q3d_@Jy%+15(P0f*aHVa zhfA<)&gGi=#7w);yk8fGd-hQPwyP0+gIcr`upyM)?Q||7G>g?@c&I5s;40pK16>bY z%^*LsEXG^4h?@#AlOd(|<H<c>Lt2%y8p5^0)CWpTuh8A8@Te`817!0d1VG_EfnYC3 zxMRc^t5d)`k_qr$tbfM*(1}+J`h8OgqZ+BsMi|}N{305x$&v;9rJ1<*D4Gj!VjKw_ zOm8|;$N@)0OMURLRp~R=u3sBqigBqD{zIe3%di3n16;b$K0=Y0M>|GSjPkA!+R>ia zn2-@^Ly?R~<MgMBN5Z~bqRs1bqc8Nf;n%KGEo_}7aTzLKH65@>mPG%WE@Si{YDDje z^x@Iyy}c(k1XRhk5;Yc!azMQI;80tq;dE!EgG!bzyRmlFp@zak`r1THiv^fu)#$`B z;6R0aDWKz}<NjMN!}C&j1SVTn(igyR=+Y00q;esAm6&95xx|CcdN0QLi%L1zzt_#H zFJ6%Q*iRz=UskyLl}xF9d&ODlA66pJW{0gGCFd)*y*K*jym%#7eF?u*k8R*z?(@3c zp?<<zCH#c@JzRcu!Q3C8ep0oe&436um0t<3C6)?$xZiW&m9*cEK@L^eXYBc)tkC{L z%|TIXUx?Xz8{yE|ZPLs)N1G^Al8|YCwJ_f$3;G*;O>kQC>)bzaNE~TxZu+)Rcid5$ zV&uOR9RDKw`Zk5h_h^Y=&1THDLN8oxAp;a&_owi1WkDrX{MRVDk0g2hUaqgv3BoVN zbWnY+&g8+!j4ge0$yyM~N2ynwNv!lUBDG_fBReRqYwLS)mrJTSLL0KJRP9`rE=#R! zHGmGal+8Z(f+kyh!OPH>H5-q~dQ5QKH1L~42Zm}6K4>XBcs@SD=;JbUQcj86+$IWc zYktJoDAv!JPlDD?fr6Lz`+^?&hH}|i*@v<EA$R0V!gX%Ae7^S%Kw8wHpC7ujEd#=7 z>(w+pJpyjnbN0`z8~mEg5-MucfDt^y*^EeO&F&wJeK;G~YSINd7Fv+iqi^rCgo3Sb z#xi2M!)<Y~o@hhwkj$`X%&)o#GFNiHK<vX*s5Yvet8Bf@&y^D*LVUhHbQ*OVrJ5iT zk&FDkqS+hJAbra~T7JZG{nAL};x0qg5f<1E<w+bzif=HVj(v`inRifj!Mm^MPoFjj z8y`-bg$erbNnB%vw1F}%!LA=FUJ0j;B4ve$UGn5c2m&-Oe=2?N3-gbmNQW7eCwLxU zxH;HvZpsWeJ4T2Rb1x7<1W3Gy*R^&+)$&;kmvFG*0O=y(djA2aRV2s3A}}_dbPrh` zOAOMZ2df>RV+!Cs3V{0l#a$d<{5EYKV5KF%sfu*_`eky1`%bL%m<1_1{s%P{8-~lV zpbg2eNq82_E&(?-RV~uSH#3s3gjYSQT9P!6mys_C!S})KytGou5DP?Qr%4oLA>MY{ z`4j2(773!v0yh=KbNpIdW0C0caR~{D{E_AGPBCxJT1Le=yG9s36WfHr;7x{eb*+^) za0dK<AtE>?2{Q~}IH2%_I)wsiGe}pUU_V~6v25<{*yY09;%Gr2vaCxsMxi8E2x|#H z8N_3)pLTJ$VBL7z>~$)lNInB8>wX>qK6+42<-m9Fk?U6Ts|k(m$VW&6)RXc~>nF_B z5Sn3}jrf})xj=A!0+nKj)`5Yl{#2pp;ix?R5G@_A!gM4jR?(&hq$eVg1MVz?Z|)c- znMi#i?e5Tb$%wW!zRkm0R4bVd69`xuryQ?T4Yn~c@*gJ(u1F3gP=5@#m58TmXf9VI zS~aG+PmL56iY{HA4tE7oiv)@oi#za{&Aj6SyuGEl&(ZH7McXR>rMt-8Omdig3-oBI z+xd@<1^SJ1v5W(w2yh&tB2`a+$=1be0$$03@9uYyk#NaJhpO6o_K(+9-W%{c3Rtmm ze8uzgL0`F-1Kr=9UMJ0zi&4_SpnG5S7wo-VV|RGnk*4@&GtM{NhfXhzalU5y@ibSl z^?&+PgERhDpLTC=$upprVQ-s1S9|^t=qs-xRPFMx>WwIjk3=3ytpZ<MqFehxt$m@c zYP3o$B^X{8*04v8vR{8)@!;Zq%~}=gqdo7ZFudX-uL_z-u^Iv8IW+wbrco*}(mI0U zi}ZT^>G)8ZGPG|=2fx{CA2$JRURb#9>ik&|=EnC_YZRu3v6_AupPD0;hkX|s?kwLJ z_si+R@q!x!zlbz}<}Rdv#xqmPwIzd|%YRw!hJ7h1O?|k^S#fvH=$-4FiklBnV+A}| z=|qT$9=+44*iCcz2kDz1k32tFxxD45R{vm1c1~e$!?8ITp0P2Y_X^7IaYus>9u}i~ z-OEx>F9{swm4TYllJGZ6Cj7<|n0YzDRpsCaEOS8d9sewExBN;BK>(%hk6G|~>e42c z8zOzkyn?g>u<aX>g-PPh&g3k6nmuKU%6{F-Lj;b|_CE@{VM2XtKFD@$Za3qfwf?r! zZfsu-IO>pvnMGxf<`n9+B|TIX5-rXLCWiJ^0k9&-EHScV(l?-e3^HiyPkA+PUx)WZ zr7?gkMH!Qn<!y^oMUXDcG18#K@r=w*1$=}7YHbokPw@woGf>ZjXwAV2zGDInC2sFi z4}vt6%bl>QV%CRfzcACs$C{siPq!Cj!Mtc=2Z){sqz3fdg07<2yh!jWn9T9a7NuMo zA^58h9Ue)}{)hR0bd{njPfMYwXN+je+>VZ66qXHru7lj*E0x}lbJejUj*&%6;=6OH z@P&}JSjujV#P_jj7CvfWN;!lA)B40Oq@A6owL!-wYd0|60`}!@zv^)>c*Q5O96v2g zMp4Vnv^g56TpYMU3$&f&m64M@GLPB>7cu8q!9TXoIp{vW8J>Ml<5sz5Vs81dr18-8 z6dv2+25fY%emv!~i0`h>ia45V9u)|zsBbFv_~!l!(^9qoP)8At{?ZL;7i_G9RH9@I z;cKd>u*8)c7reF2?-$MUvAm^WmWn*7My2MbTlUIzk7Hs4>!hJcF{s^7y2@ile|cFA zuP{C|>e>YJp#}Y=DOJvIsxhV$XJTPcWNoz0y|?he`HceCD0y~$zVx>@06%DY?`Yyr z?7U?j$Xa#v@cUY?2*+c8Zn(MPESj`CDu+#VgETV2--AaO^TRgTq<0>O#!?ie5RMK- z(9C#12s&BmbLr{t&xFQ@YBnlF>r^b`y-DwBATT7;L#~4+*r8@Aj&OPtIc+(w+Ec|$ zG6;Pr-7TqhxvAoLwP*GjA%7J4wJYD|Dfw*aQ1VdZ>dJc+HJ0B9PAH`ab+OmJ+_GHl zPG&uQF!Y}2zSk3$Pg}+|YZK(p)e<g+zGso()eH17xP|(X1wMptva%&q+S%^uB1S*3 zJRovZW?5E~lbW(z9!ZWPZN^<sFgOJbkAk8s+J`PiE#|Bv!fR6>NscuD3zO}{EIi<k z2Ho3(R)w5PqMfIgygC(XGdW?Rru`{<A$+u!lCg_rjtsqDS_Y#!wWf&Qvr^D-N%*?T z8pxT3ei~FJyfOByA88QvPptRoQlk%enM;bm8??EQ1cbc>b1-cX!?hh~UoIzrrLT%* z)Llr!cBSD-A2HtWuw1`#TqNTOqEzgUajM7~u5$B|iS;@7$*tbPiO7q-034~O=o5fI z!qW=Ros%r90$_1RS{CJMGEpajKX6ag)*r0zBI*^yP-K$H1T>y4u-bH7ORI@2*S!UX zdvRazX@h&RqE?%@9#g&tmk$h*hvsn%%Ba4uxf&kyS=85v*F$INq`@>XA7w~i|48ym zfpUy6x`cx+D5@9*ME{yBa0O2<{e?agwU{<I7Qx_?u_?knvFm^7&vCwrZk1zIO#i~L zPK>Ks;0)Xhu*Sex(I~t0i8)K_|HM!$e0C&F6-}5Rr;!J&q;!7&_oR$kVan$M4{F2{ zFTn<2ka>YV6*7!cOeSdE>;~V2)uR^H;>%6RH#DXDEn)s+x;f*Uv4QXII5uSnE0I{m zW@jJVH(_~+uE-j*1~H<O;*(JCGAOW60#b-jo+ykCa8;~BvTI_A)v`7{4Lo2KS0KRB zoq>YKd(6H?+5mo>rEDi>w$LEBAXFNSS7NQSiz~aDjhz*6*;*xIEo<!rS<DNnb@q72 zx0DXbm#Hq6y3G}(j`aYCP%fdj<|nbUY!dQTgWvHr@KcAYB}3<K3y-0((VGFTThCg} z5(;9f9`3DtR^0=^=oU^vjR=FVtX21?AGoFPRD3qj`+I!1FUXat0{*i3M!HdVNRcI6 zVY%Wfe%|y{?bbQEe_vk1<F9Yl?leW^RoUx1dNHJk?3r<Ppi0$O>9DT)?X3pWv^{Fm z(S7prV#OCnSF{Ks=`Q7+0GBNF*P9pYSO2qPVWeprg%<WOoR##|c2m~95Z}GH0_9!E zm*Cz_&h|UYHZ^AVj{dyZr5pBBvUS?!clH{y)-kwe48;5zw?OCHlP8XB+40p~qu00= z)fUx!)3*L}vMBt%?#$D_(YLTg8?+}AvB8Ylwfm?1`{09;v7DUGLWYA2sLuAvbm83{ z?*%UPIJQb-7#9Z*np37QI<E!&q6E205vT*mXdubxCL8{G=Os-g8jg!a4dEOEUAp&s znsxDgX80Cqs!~n;*sd9y&2xa`qL{KCn|27^(zo>Z!*8nxZ#zUV;)Cq<o`xG_!Pb@F z9UG`B6J*31ub=x|1qt(XQo@UQS0aUc8dVR9bsWJTicCZ-EY*9?hoZqQgsaKtH*qNq zRwIcJ<paX^DPz~P`Cu2xb*`h{RXj=mvj9`fiSK1XAEHlOqPcIVDG)0JvPZ_622EAs zoYLJ4-~gHI31b=^3bDSH@}b0Wt(Z}m8`Uq^Y!x6J<gg(M&sJ$=5P;R`;&t+J?L6Sc zwj$0pXvv+2oji-uY+FTAp16E-i#b-L^vjoVk4P3%znMrmm^&835GqirwQBc-DFTH0 zYoDjy<zCPx23pYM#;{z$N|;$0cv)qQt5^L;0DeEXn2bAa-S2+MmOYdNl0$OMDFA*9 zs3_G5T<P|VCcV(!!*-d6JcZYiwxIwaE@VaG^HNtJ5m#g-NxQ&M`dmlMtqf#zocyqp zkV`Nr%^nLT;*q5$i3H67+o4J~9nDcx(EI>!2>%ZKSsJj=G<~J_laC}0irPNc&3)6~ z8ClWWAO@9tmbDD09i6msx+wW6JMQ@VD;<YislrMm$^lp5c^JT7yy!QRsOw6Y2%v#< z6D>g98&4ycZRd}i(b1<*UBL`Wo!BWzUX&#c-pQ?(dhYm-*;df?<d*$*ht<P;T_V*$ z*ZAPek@b;cTwdzhW}Mc9PXDj_`!?E5xUO8cZTJ)w#}$KlXpD4A)uH5pNuolnLhzrw zyKBlT+N+C?(tgpp)<5h@6*d5vQb#RrbfRSs7NS4DZ|!5^QAxd;aKFmMc>iT$Bl2Uv zVgdc}w~4-r%^`CRY+71=uQhK{m2A^l(YW+9JX>mUM0E!8+GZL^@=D$4YC1s_F0lGv zLT<7)`X__elpmtn7a9=Qol4mQnj>-JpotGjj@#>Aw|eJL2FNxB)2j)gu61KdO8vqs zyyxzZzcuIE2&`MwMqakF9=@i&!H*7`(GX`R$NV!+%t}HyJvUF6oa-HYGT!KSzv*!z z?4)<-zf!8a9cL)A6u65<;@o!K>e8Gf`sfLj=rROlF$gCMF59W>3z$`qOofB3c0boi zj){?A)tq$ITfuZc$)aMwWJjFZT#xCw%dBE_5i=h#5yv~&$3A8~-Qvnhf4C>sil?m* z?kopx&WN`_Dof2R>2$kf;nqsEPUR$6*~5{GS&qf?f%Cr_K#CTcL2C{VLRheJvcrWG z&YptGOX6UvW)fYElwHgN9+I$t7bWL;MQXeRh~FpW)uL2JF&;J>76Jb8g-N;WN>ZHk zew;a!SDYtvoQb(fyCsM0?O>r&cVMEXlI`u_L!z9BND<{Hw}Cg6;>JVfvV^&TT5^0C z%4gg1c0=r=Rfkdg+*~%5k#OH-w7HxY5jd|@c|R^R<Qo|P7TrY4jZ{tb-s78BM`p=C zMB*MF*$YbIxNYHBih^}ZkPLb0cwA;;A<8>RtYf5AS8ecOOInLC@FjaMMP)1$cml3V zUN|3EH$>S(r6&%t>3)G)nn|sqi_iv9C)Wdi_%;`}q{gv+Qf|OI?Mc|!O#HZE^rB0Q z!UI6eg6C+4|C=yI+zxrNr{78fh!!JaKgl7NZ;<v}Xb~?~u<WlOHeg{84~Z3&I5Ago zV1hQC6>xT{A(7z@RUHSpIY)ES%HpFNr}e{^(3+_yh}H<gds1QASYFslfkn)t6XH1F zE<j{*OW=>|@Pa}cY3j>~r9r=b^;q&}F|$I>4Sam`X|4LrH7=QQUd?F9+hQ)|2gkBc zFbSic4T2`*Kf+R`m$6={wZRf8ipqFAq&0u|#c4KXYdq<5SWH-!;B-Rkm!y(cACfcO zEvXWP#|Y+tGTQdSK1Gy&tY(1%Yk2rfCpsedJh+iJ1)$=`>0kh&7>-k7C{I+K<@TxO z^qx8VmGrj&Y6TJ_{jX{MBZ)R-Gl-BT2i}JODQC1USgvqK|1YvYSEpf=rRR1!8iFMC zVH_~y!|8km)hl+G-FtAB4L88qqb~$XTps;n&uNF-uRDaimc-G!iVUdn+G6Rs#%X-x zSolGrX1KFTk=%WM>pyQH66RrExtgYV%A*;6_6@{1=~<zb8tJ*PX*U;9ED}mA#-c6T zfAo6)<M)k9n0aVy2lRszkHpRBefE(g_{th+q;Ltl%6n~iS#KJw#ddA+p~zp4up80M z?NE&HClBr__+`q=>K!kr7M95Ng6Ac-l^r=BWkE7ECA8w4M`IV<Os~6f0rt8$45=$_ zE`M?Ep}dfP*Eagx@u9hpX}>Ew5CLY6kl|@Xm(`cOAZGQJ`&oGml6<*Rx@cvitVM>` zc^r#1?q5FTYnq>9u+eHh@WD-CsN#9QZAr;FXYI0_;bC1<xt-i~D7DaM!<zTn3{csO zEoEDS%agVenh^O7zO7rk?&01QNkhX($rf3$LDseXd~7=raiw*vo0qmRZIb#y*h>O` z)}Kl`+2H~b68wYTFg(MG{wTVW{Vzs^=H1ZjbAGO+U>QAZnEzKV6BiU&!Be$`=9|?* zbm}4K5*0($AK*qfUPVWuvbvdU_7(?{>NC(E9_`32Z8?5lxh+N4*gAR#*n;BoEGB?r zNrw0rihvrEJyj@EMR8B_=C?|`>_xDNY@Kqf|5bV_hxw!BJ6L~I@U;G-mKdj1=)u;v zx)Kk(pT?S<@hN3VqtX;TVitn!#qeZpVq92*OI6h~J#EBfeb*DJY1A}*ZmT53s{mMZ zf$Sy%P`@;SDG7wFld$U6F7~#4R_W}cZWD7uP}Q_a8wtv4H7Z@F+}izz774U~k-gGE ziZ_<6+~B#}RRE3N6RJoU0gD|b`j22cgcR>b&;93bEEKMVBH6($z_Gp#9Ogu5@*|0N zPI7-*P#VX4W~Ubx3+)nPI}f0z726u4mu&xu@vq8&uwG5T(O8H)1fpe4C>{B}V=&HW zoQ1FhI)@8w(BAO@K}Uh}&~^qm_@-8|>I5zwp=d2QM#rt*xxbf2P)^R5S7`lyq5SVp z51jX4S+h28JOX#eFl>#>gB-WH{C>K;<dgLZTKLxd6^X(@01JXA7K11>HasZLWDMXi zWz^yeMj?MAJOoceCz`+RosTNs>vQw|N!L}Y%@*~<4}Ny;-B^qHGGKt0(6M|>K)wob z4VO2j@!{L^EREtKGX5^*`x+fS+!OPW<(br)^6kjJT^M&LblDAkzbP0bB#B*#tH?4I z3xE})4Wf|GXFGBSfr_rirtR&tRS-)JUgKuQ63^)El6H#R4RWiRE6nl~Bx3WBgw&-J z3+M(rpc}`E3&0{P=s%~6Ct;~7WsL@kbC`Yvw8&)!nHE8oN6mi3%Mzp+>7u#b4BIsL zq|4t9%=>&y(MV-<VG{(MAeRg<TrDE4x9Dc$Uw<SSrneEH$x7&>5QiupRmEa76$mx} z+&UxF9NwBO4w0?<q`2|O%#F5U3h6Fd>ySlzTXK9&h9)8+zC$`C?Pu}@wo35bI`StW zd=uG7V&!Z(_#m$zR8-gl9y?2Ben{U!ctt$5t;CX5UuUY8e8QLIZ3#u^G6Ucb`91_H z7<Ws+D6=^up}H`3bh7WY+fQ;(a8jFkWDw=Crh|_d{g8?RA3jzmFz%<{8FV6skZ4Lp z%o56=EN@E9Qdl)|9)gE?ZAh}9_u-WRiUd5WjTNyYq=_e$>>-MUyhIW{Tm(kCUT<ki zb7JL#JSj3)hf(xN9=t|=c1CmxONvbwM7z}SKV6u#v!0Zik+uP@hb@<HqH<9RL5c_; zP<6+jTT^HCE7!$`O+vKHnJF4^cw2Q>oOAC;^_Yii&OiIsiu~rz6nt96mTb+*3d^3j z^vc*YlA)Ek26Soy^5J!p<zWFEJ5S?-v%^Yc5II-N)Eg75cCE^Fg!l<X9TAYK1bZ?v zxJ|eU0YwZ&`iq4k#ZDHlrM;I%RxUe>lbC%}gTAu`g4tRn1pa!jNK8qjOr^x#ddsfy zR}w6WER2id*Q#l=puax2_{ncWg+G0NCj49$BbX$G6QW0Me~j_5BhOWClOccxN87jU ztJ@E`QlCnfqqKo2XRm+olh?z66@3dEK?p6H!F4O^-QLbfzqQr;7D5?Xi{TSpE-Nmz zU1~G3!#us?%&6X&&yseugf$LQ*$tO%t<)<2e8O-3Ol}@zhTvK!mmj64dSBdOjy|}) zcTCTmtt1AkPr|{e_crh7xpi%-)|cYO+`85Aq}1e#6*&@^?dGth|H*Y+bEl@F-$-!F zb^9Ug2jg&_PLtJls>&p7+ZK4B>Sg`s@ev=x)JZz!F`-J7`mv$PbDF`&;d9Qe^}Boe zm5SO#NGf4b4VHh!RsMUwfzSTz;{E#b8@FX#oj*fo`Hi@sbl$M^$>@JKD*e?oZ%2}j zL|kQ*Ht->)XnTU^_YaD~3qf7l6AJgS{02OEVp5Ayb9S??H0D3C@RZkj9z8VIVQJ2; z={w!FuIM}+b>#$SOS0lyH@6HGguI81-rb7YVka2VyKPobd}&K6oyjXJ-$Fz#LUKi# zR=EVSGN3afujfSrM?9uiW+fD@?J%|YrH)oolT-1XX)Ri~g)TjADg`FFK>^RZFn(fe zBm*^28iR}p|Fwk1Q03Rm$C%O6k5)C|kfm`VIuNJSn%o{vd-k}rhcKX!EPq}~#vL=< zZ}b0Z1i7A{%g9sfFVWw>{MG#c%i+ZL9V4?|saukr<GZlc+4fapnN>%BK_nCHS16Lx zXnR5XvjoXg<nmRh%v`6wv`kjmQ-mo~;?IN%n69ba#EjE9xJlVez$(8suNlsn@U=)> zPg<Mhs`Ua@kaoGcYIi5oBjEl?frMhR$W$(41}9iXD+PGPmch{$FHIFWP+%W^wukJ~ z0t6yg<5e=*<6dBFT5Qa$r>Ff1LMPMEDQOp=J~p$F5ha^BI_LIV8rTe$!&#=u4_k^| zlWPPT9U@G*`ot8-b9aeE{I6&94lmfbC$k|9yI)#-*07n5=I6koIEnTn?MGhv>>B9o ztrJzqXvjYoecSt7`G~YkQB~3&x5iRUMN)R*?~f!0v!7TumFRBIUJqr&o=ghhnSe<8 ztQ7&+)xCaZy!qxy2g%zH_uF{{>k)fxclgLrvE4H5GW!pP(a(zm60-cUzu1|O<oB0+ zzRNy2<LUu@XV=d9_&-A;Zw~^%@PL|=vd^r!7}0b`2}D67lAGL3#AYmzI9_ww%IKrB z?VLZW*}9=1hCOX54SUk)7`g@Pw$!@1Laeh-v2aLUZI~#4?1J>?gbG`9aiOBD*o^XX zyVa4V0FLPa4il$#^*oW2^$R@oATV@t{TJc!>()ML-A)=%m}yUlHTb1a#OtCZt5_KZ zG^|yK;%pOC7R(MC))TR%U4k8XHNY9c8*&bFtK#o?#gL{4zF9%+F8k=gCIPy%ctzml zAQq{NU_6Dz@coM=!Bya>FyxSiWRJn2zW}0@rnAEcV$Y5Vt=&x|SmYyq0TN+17HkL@ z07k*3(I=>5g#A&vb*es0Oyo6|@f<|+S<L!~0X)0~Ylf}?A}@J(u+4!j*Gz8t+9A;S zDpk^^q=cE!$&WyFaYA}=LmMl|J!CHAt&0^1Ouy!XF!>50?~Ik7c)(8?YFmDbxKczE zVF(Y5N?RTmT>;eN>jdwnCH*Z@KVE=KcU#2td1gBak@3t#CGUeZJ_I;Oo0kH_!*zgb zC~VpCplWc8^XPEVB#ZUB0$DX3Ei^C}DGxX@pdbG47rS+DjO8w|Kqu`2Tk)V+@q@Ce zf^6=olta~D)z{?K7Pm^Yi|8j9z^k~Dlog(8^OPVwGjQ|#7U=8mEfs~9ZURiAU#dn_ zMg2?yvV}U9ov-nsH2$qub`f!SmW(=tNlGp#u5gRoB`Z)`lRf8wZaWOJv&Bg5(kgKb z6O+NnfWb7w>^5Fwd}uUs1dN-D2Py+VB19dvG3e{}xl9<$0LT^J|BWU{kn8$y?s(7M z@gFP{K=nCvo>DC`GyJLdq^HW^=Cp;cU-$iy%G<yCUDjY(2?cQwmDE6bZ}?6{Y%$gL z%r37rS*b7xIuy2!^XX;<4R7@ahYOFD>wW<v!j<ge(ah7X!-bbGsn)d?GE(@%ulUdL zU8*_Pn>mSS7%XLHwx+HSXu(2sJ=01yD~76CkdH2p+kVG5qe*k{W9TWZzLtoz_Yc%w zG~6!Ltv)0q3+Kx!f1WV7*U8wG^l<GR&3d%e-KM2tveh9zm#)C{%YB3V+Q0hlMo?W| z8`t0ARjO~FP4~|hnmhGe+>(L|-&DI&^>;0Mp-><o`tD`Zd(Bm@Bd$GZ)<r6R50ge- z819sMz_o(GS(ac^++3hsR%t1{G&1PeQ;QF$*Nnqn#mmh*Zeu_oRJWS!y_gA9xe82E zTDgp0k^M?@s_?e_K(X0>85j1_%b$Xj__JHF&T=^6JArUinX3;;4Z$Wf0c=6c&VgsG z)ic8EW~(QCiLio^C}V&smDJbQ167tosJO2_D@l!uA(1c{>(GT~DVdj07l|7fve@be z)#W;^nQ34i0Vd|zfHMgvU4VyL^IuDY3RsdfuiaG~PCc_0>bwML;A?m&qY*7F8faj` zqFho~CyQSzv3reK)Gk?*_XJ8Fd57jIUu6lLb<dqG*<*Tg=omXv>a4;mpO@^AOd6B> z`FdnopG9dK5D0+Ofzv&bEL<ybT(rxIE_da7>Sb)aMpHqy8~MXiGClyjQ~0yOiY9av zEhITtForWW21N%Y2pJACN)V`w#Px!RsKBDG|FRcdrSMP;@bTtXhzPqVs)480Tr#aC zS~XlQ1HaqsKV=-X@WkCElP5oH7oqla&KESN%+7YA1}Gkx2Xlwlbd`@XU6Z)~mKt73 z+On2{QPX9)|8GK<RyyKN(1XMA7O&3>whyFMI=?VC*WCL4!^qn0D-r<|o63I?V@(L> z-`<Oksw@L;kc%ED%kS38hr6ViMR7(pw)`1aeqX;k<Ive+Kse!UaPjnjwT-CJo-7n| zBUqhrJmZqGBj+f?SyG045_g-=4&qMrH!mt?k6gEi;TnRj$x#z5-Qx~ICx$y^9l3Il zpweLC=kxX8Bx?~+B<piT*PT)&Qa^+YdUXMYNhnq~FWLkZp7ohEOyy8LFbFX1^0pJt zhfrOY#;!e1JLO*}pHq(<X9x<oFI$};dg6|XGXbY8m>0xP1j$;h_RyH;6f)?-)_MX? zs{kVVzhnHE<?#0~hntCK$UIn4gyS&bdQBkq`r3)<tJo(l7E0$psc5twIl;M@C3q4X zhok^YndYWIt?Mvouwz|)I}Io@j9hq9&(R2xZI&~wRWAFRtj~Zn>xh9Oko-3ENaC4G zR~Q>3?-iNYFs~g~V5Z~?)a-?Y8#fkG*vK231AX3;NsSj{1(o-aM9=h@rcyYmx9i~h zzz?Cx1S3Z)BH&r4L|QhQF+dZKnw<HH;V{WWBs10nC|0QPnF^xrCP4!dMvTubU1aQ3 z17y*fSox3mW3-`ZW`Y7(3{r;$xI);)YNqQVsT5c&4QPmym3}}o_>bh-T*w+PP7^yU z-<sE)<QK=lZy?5TDBOL1`$#n1S=eO4dR*^&c^>%7Cc+0I`p8W0rzoP;_U!+tju6M& zYHVlmx0%G0TXdpg!Y&Fx7!Y7%yjs>RQqGH)o4O4|!`qfpVlBAs0PO~~u|Q2@6A+Zu z<oI@Sd@w}lJk30vFZ;db)P6Yj!;!C4WJ1w~K8Y(Y{rzTd9$OVRpDQOSiZo4W_87El z<?ze|0>g$dDE9DlEu~`c|Dw>O3`M^7hXm}mL;qKusAoqQ1@|odtzUd^>A3Szd}Q?l zx4aL79vre*5*F6oQ<#><&1kI{5*`UWz0j_o<Cfmryfirw(E>zzo@a}>@niKT{VVSu ze7w@;<M#(FFhkquPf=IiFMIEN{M1u@Cd1w9=oUHAq1RrNKTv#{A%*RB{E=jwekp}R z*6Vd$nepM7=DjjNg@?XWU4xGq&Oo$G4>eA4d!gd?vJOV7N3~vByHAIf5P~PsD}Jw! zKU(qqi>|jAhrX|iL@mea5}y(x`1$YQXXrCsZWKmk%{EQ1t2hZ~CrAC6*Ah)rvSrLb z*XzR@u|8{gjsbc%A?wq`;aa2REVF>=TU8?*_uhJ9?m4=FL`9Pr6L=nu3zlZd9QgpL z81-H~s+-zyy29fw2&-4yu`s`_9Zr4CNn@Ku|GIM7#-!PysTSuz1}-bF{SQ3vT0!Sw z2v6KU?#y6%+mW+()UVgSJ==9KI=KBVQZK5J)KyvOapkZV8jPz{%1rMk@{AqpZiY!- zVxJ^4wdE7jf83pK8RuH;@Y7D-djK)4*!4-qe7bDBqRnBWcVxEKNt^NuD;bT)ZK8Y> zIw@OV$8xB6H-#m~3O74!q8xqslQ>P+Xm|n<v{gk;Ny(mx>lL`K0B5M&=3z^jqgv=U z&Q?a?YC@53y)fgPtfo7<Xmi?z?7d$m=>@_Zy#fEG$pp!rEroUVj$|KFWN(9*v*7s` znYFBT^kx*pJ=2Yv(mB?`G-&C$ZMI~)<d$sr=LF&h+?5%?SS&jmZCwKeTpr44K{uCZ zh9Z~bB(v%wd*m)ftWqd4RHo=jQSTT#=TCo!StW7DZ`E$U@f<4HQiwInQzN@IKwkTQ z6qhR9o(>Q>m^N?k7)G8dXkmiriF+FV5!Dbq8Rpcg-Sb(9^we^Rb~l$u7ge`$y||L5 zm}i%Dr1|a=dC%FS_wsjqMg5YTFA{j(?zzl9-ECN{BTLhau{0EQddo0=fxwKvVmcW5 z8&8X}VyODyaz{KaENwkh%U1(Fd`8t;=lq<A5)4N5W4c?Cvi=L!y5b)hc494Qdz_Or ztCXxp>lGV%Kjv6A@nDiGR2ASmk8e6HGnKgO4;hBnt^Q#3x4r8XH+}ex$w()@p+o1H zT}k(dt~&%w(FBA;LMdk<o4{kkW~3bx`xnAq+aXxIB4I{Ne4WyDqm@?C)2N<1)B!e~ z&G;C=Gs{LKr|%iH4EJ~*sC22~q}8ZzVK;8MwuqXwwZ7AqPspVKZe%o_M|NP*Cdwgh zUCq4q5fMV2B>J_YHWGGY9o;xrrePSrOkrR<yM(?inLoKAd<{#a>^T<9IZuUdmy@x% z7&3Ac>}9bh66YCrwYiumn+*QlXZZ^+(J8>?1%xXx&rjy>P=vl>;F)#O)lgpquNYGq z7~gHnxi1_{pNhw^X0Q#@ck^s<iP+6;h3xz!Vry;PTp?0w!yDxY1LHK|s}qq7dMo(1 zdY)8kz9%S$_ZR>dyrhLoP_-37CqyvyzNtC1C<;Nr$H6C>#WKNyjs7F-S?tJ~O=DZh z1bmQ0FMFC&!+=s-#hudb64f?|L5yV~F7cFNA4z^8!89^as_}~02)8A!w@Sv`6!JUO zNc+g9OeygvBModMalX9Dtr5L>ig+I)na%9n@_;@X&s?WutlaOwu%w!)5TiP=D#+AV z#D$8gboPI`J5M~piNvFmxOOL_CWpKgX*$xxyDiZc5|rv?f{DcGtoPHir;~t;|5NAR zFS2GHg7OGVu7aYF2Z@2LTLPdejl@l?weg+d165@5AqIE`W2{SP_+m>s-7?ws+77pp z<G|AhlV$JyTIHaAUTLo}ABM+t(uvt%!Xd`$Y#W9YDhkwH@*mRWXWz1$y-hu4XqQNV zAGpGEz_kJudXRtho@ZpA;~_~&r=ycch99HA5y)vf4BL!DAnkvEJA=A%wzBPt<nw#i z_+36dKd<9Z)q^i8fEP*hC1tPwyjq_6my`%4#`X(lRL4zmF{w*6t%W@^BF|Ugz8yYP z-uLcJ&)w>cp(mFXTb>VNHubDeg(a(Df@x8CvSo#G^|o!>5Mu=CSNYwXo9WYc<VwWD zPvrX3!}6FtmKPiHQmmHn*Sz{Jm|n4ux@({(Xv<eQ9uqzdeo<fS9L&0|`tt)n_234v z;ygF`{1kp^m8|TQ;dP3NN0Lz`AHLfmOEKO5q5J&4m;?6*Al_maSxiY~h3qqqd-`C? z$<@<^EkALZv2qUp@iT?)fjJH3-wc(eHd5K6E?nT@hk8Ovi+$w4bOty8sGN+du+Sf$ zT*oHSBWy>|7%wV33%9>=lyNp_k>~%Dulo=7IOS%2GV|lm2^P?e=p?<%=cVg&&A*E( zg{`pt2Zh1uU;EyJk|{9Wv`vdo7XQ=~_ae}OkHUOJd-6cYxw%6~S$ZkU2G^}_bSOoL zfFFgaSbkJHpHK{nPGKAqTB{3+>p6}e(GR~2|M>K?>0hRt9g|5lEw4D~9Q*bUw_pF^ zAGZZ%gsbG+{^iMCEiWJ%ShrZ6<CQb>-}Hb$0F%cO4QSmbeww4Vlzno;wNJQEEH*`t z)p2d6OJTqaox~;sp1%LfPtyO#C@_|Y<o}O6YcD8LX_RkQ>0&fP7p!d_|I0WRBo2!R zlDSL+T{vZcB~(94Ox7gL5Kds-o_gg_weAg>prh++{65d=GnHr0+(xPj;K*Y_AyRd| z+LgH-0097Ke6LecXMzZk<N-lF68!#-eKt2TcDs3i<V?2X2U2PS@g>X<QuA;kXq{MV zYy~=sT9U*<$4MW8&|?!$DX$BS9{qWMsulS4l0WT<3rGf!s>W*-$%XLXI_>No7)LTT zwpRK0NW0r}YhVvcCelNC41k<+{brjPJAks};PBYlkq&1mX008CGkj1SjOBY0oC>S> z7me+GZa=;SlG$2!m`!0R4acUST927ELn1OpMl}D(d}v;$w-8ZHWc|>OV3&BJ=}jAR zc^|GPCK5dO-LrU@U)yOjQd+1u%AHC^6&(}P-2Rv!ZV$?tsp0F=FQCNlql*>w*_`q8 z(Z+oPKkt+!-Lw_9A|ijU_cB7*TV34y(wL;HKdHg|=_QD(`k{5JgF(Ey+$ue`TskHK zMMlh}j_^|goeiP2sPVdUKyyV<KFb~EBEvHs6``d6Vs_-eWO{Si{-r!n5s1aCp-@C~ zt;YH^AO9k%LR@0_GD&&Z*O6^n^TCS?q8jeeI9<OqI=LT|OhMDFp)QA1@ocPS_`kba z%s)#=>PzK67zJCE&0VBm2;4|~lllIp``_YrMQV{al^`!895WaJPAyAmu;m2I5*sN= z4(e`7LIfi{7^Grln3QMb$)y^E*oN)4x(NM4Gki{};yeb?IyJglJjA`kDAZNU47Y_j z9txIyw1xx<;kAK#oLVm4+e#xaMZ(it_&$X_0QTU}o@lHCRZdkF3|hcF$qJW|a5_Tr zolmJHoJqyZQG)Kn;OE=1hDWR)0;vGlw7q3*BUd&^PxW!#9ET!r=qZWo(j@S^A&&|E zua+L1w*|>xgQC^wKMHu0lHXH3XoW$Uj5PM}uE6>EOo-+L9cMNsGjLl7HApDJ)HL9& zdh?MYA=8jBx8M;X0X<b>JAA<^PqonlCvyf0d1lVxeQe5O+ixeHyKS@;!|Rw|#=lDc zMJSHz#m<ar78jeQFjjm$T^PV+?e#?<(}Q~Ya_S)v7VHeot*;YQ9DL+}b3pN|`e}l1 zIG$h3e-SZI%)lH$MnpIqR2W^bA{iwb0s-kjw!z!qx<vjO7x;N-0S+p5z%UN`TcC`J zmqdwqt93#Mu);ZqszUmwAiS!w3JQdIY!BQzPW4I$wd+%St(7bmM~4)%T6oI=0AxGy zI@p;*(e0+b1<y}>F^Lty&D9F{Re!1o2+V&30~z?*V!s7!nD!mm%d{`8!YV=ETCeEP zXTqj1c<ES}ZEUxAy@cOa3BN1ovE!dtw9Ms=hsn!3<gdC6y)qc{>qB*I^6T6AOuF>r zrLo#jUv^=JWbL-d#-`F!ha{<w!{Fg1&MDg)oHU+r7c0$lj;dF-q9|F?RhD+pG2p;| zu-7mcJMH?@(yzSvw7lm5PL1Z)XJZcjQT9D4dyn)VXWzq@;_%_(7bSC!UROjpyi%k( zylHtZkmHr5fuxhJ&pq~hySVW`Di^^{U^Or&eY1n~9Yx>eQ;#7<Dk=Gp6<AD!=5b5% z-^Mp2<}>msl&*tmcK<na<qbY6%5Mq+r?St-njWGt+(@A6^=$(>ShxIcoN_a6U?*FO zTcq>5uO3F$&Y?dj92kcT52abFBePA5l2p0F45j(?tGDNOUEPy8w98a|adk)Gw+Cdl zq;5lh%xgoxjBhucd?abm9AAaVE{-|a81+q+*&sMX$J}lVz0VjG9)SNC?Uv-*7&~a! zRS*ygo@$%B{P62lxZ!0wZ+r0pFfp_B`{d6r{<Ist0&iRcpt@!-(o5s8u2wm{?{r#q zr#$%9)<=@Z1=;6<Y&aETyOXitxc^aBO?yaDCa815hRxrb>zBX3!*W;;mE<V@)8^n7 zZC+Ahm1_>gVp8H*D%V(x5fPd@otO(pbe5|y{a<N4oLFc6;~XpOfm?A;Ctzo2h6Axh zaG+FJ!V)%YegKv^YS<KjcnKFJjH|8Ycj}=wC2N=!o3VNmK+RgxQf`ywXPd{+Mo!mU zsk?)6FN<DdX7aYzcyH6!@gIyDq0}&aGc^8^ZXZ?0@(U-p^zGCW!f;MHRLwOGVZucq zbI)ba08QOB36#ft2_&yuu<pfJJ!(+vzw}%!^S(fh!>rL0DhI5r)rO7RhMb1eo}491 zdnCC<2`zHQ_$ik1Wi3Udz-cX{4vN<kooW~n^6HUiA-m%~l(YZrhq>T5etLFG-pV=q zrX>P&6t85}qO?$-J3!73%2z!r8H>7-fO&QWX{9#Drep=GoJkL%o!%PUMIi`b))W&W zA$3#NX5<u0AlwKwBNSYIuOQKdEXm^uM>B?v73Oy0zbk`3^m;wK|KAYmvK~+e0nZ)& zK+{l(CMGtMoKmAAD1-!#$&d3*w#XhR*y4B4WyK@OmKj&h{7dQbU_l;+3Z@fXHT<=L zbj{np93D{qZZU4a@bXee#c6Ys<(0CJZ55i=uPRPKRHvG}Uo>hbuiqX5K~eMPL~cPR zmscknv|f+z!cBlr#mC+MG7H9{%sB}zT0eLbZVDISU&h>*{~dQNn_fQJJh4bm8+cmG zl?RFOz}9wb?Cij9$UG;x_PP}=O&`@@B-g;A5UnDJUmk58G-lY#E&PKRpm<McWHT|` zJS@L2a}dgdG@Z@R#MlbSk~zsltHMIK9ezxVOBf3%Px<>u^2L5jc#qr15_G)FOvyq* zL1#nyrE*H<^d#8wQBf~SPwh{^Um>gE=!m%_EzA@;Qn`xGxMdYlT#^bAVjR{#N2%LW z>CaC_t2l=C(mIG<=`7*j$fj86Y>rNXIphw92FJ-Ge+x0KI5s37$>DgTnhmzqNO(C~ z;9uBA$`FTcy4&RJbLV~Q2N8HpGdeE;`K@&J1Su}%)e`XV^RW5NL0;};b?g@lJsH~P zY=J-NvuKm0843&;*DL%c5(^;boBn!YN`{d52$VN<+X}Fe&iVB<!yGH!B4GcWNPWJg z!r$zS9_DoMovCp=*Ii<S**Kd8K}tabW-mbJ7k2%|ScV0h0X1oIyJ$6vuu7Dyu%2Au zj97_ZMW#bgpAgyo4kL*00XPjQ-^1$X>GRSPB89dJdN}=SHEc)3B>#bCPMuOrSIO42 zLB?BLjS<W^nWe$8>Qp&3`K$1Dv_xi6qZ_mC1W21;AKm3hNQVvuR0=fyd@3WC84$aR z;Zw0mux!VV3&))5ZQAKn|AE**N2?5@eXBY7?v4lHc4s%2gkdg@8ixy+)4A5!;pgbM z=G$A7T|yK6>U*WT7S?PAtjb!wW9_{hwQb`cP2m(?6JxbZ8e&?`yzq(pv6@pmF@2Jy zBK8eETu>4;@L*EI&ke^mEL1cWX5Lvo#~7P_?6Do2x4Cpr<vX?oyVSKoSG`~=@BDJj z6Fb(-tt~2fW!RlZ$)$Z8SVP{mc=!2_=7z7;*On#PF<2ekxZHjZC!z0R@^=Q_OOoHN zWq~(7dNHE+@!l$ypq4~+8s81?dSa7h5tpl!Jvnpw+_t4Hiax?fu_5Y0|7WsPHXwL8 zok^`Jte)caTrmg4`Arq@yJo%CFKO=n<npJbug<=hQ@TjE?e+SYXYNM!O@+FNf}!=w zxNVZHiUf;n+lk6`#qhM>H{Y;CX0AT4A*v0n7n#YjBi!k%OJ<nnvp9|B_TVk5=f%D) za0TItaC~Dv&8;~UHK5LOV#i`_lYNZ+N9*q3%MUfe;C1%i=C5YPDaTO6Zk7|9WA$gl zAp6{-ZUUcQ9x~^!n`TXAF{-jyVIGeQ)9LNJ<uUQ+>@$a!Y;EQ^vxDe|^2Oo(IxLgL zI$^lJB4CPqMImyfemLZr-eXt3%s4C-LS9H;?c3GyNb*da^PyfjKEGl46o2B!q~AK@ zbZ>S3?JCo$Q!0TyRY`}AAINon-q~^4o?IsG<*RaEwiP+BZ~D7#BU@5HMbf2JflBXC zOtw(1l6Vrg*HGwi4eu;-op!DnqRF~mi!tFl!79sOhHj|I!(q~Y$}?)qI7)F_pH~FB z<Oy|~u}+pVoj88VJhHSWl^Yz?hd<3pJV$f>Tssqc_$w?ELFEz9^DU`x=`Jyn7~IIf z(Vk9FCCyZ32?LC^lP5dU*cusf^w*OY>5^@3tW{Wp+lA)qAgPn3m5ZGf4_$>A3jIy? zSSRKwS+7!16RL;SDYKMJy==epijA?4rXBSfdDdaFa>@Raub^}*U;7-XC*;+g<F<+M zdn?tnAYgoV*E6}fu<q6BXJpX<XSlIHZkt?<InL!1cHC}Ky_oj>=(Yv!9e;m;o0n7m zhrFVUG*v)D3I)bU_<2wr7_8O_;w()o(|5Dg-6r@$>!U;4B7R=ohhF2uAND65E!BL~ z%lm=pxfeI*v0d+8!_xR-p54;k^9v(Cf1hTD19ep;71sgP=YxxQY?;I&N?lB+#m(Hd z{ebxWG=Qhe>~5-p*95E~{v40K&X~$wJv_KVZ~Xl@rH1Grnxj|zV?5v*?hZ$oqhT76 zB+BbqaC`Z~d{v6zjj-PS*`O#6=1hKV5Npw(s$#NODcj4x$4;mnJT-s-G39CkZRdEM ztb&mPp9CPIim!+Wd6#{fI_5}?1xl&6jdnvWGD8m2Rs1ERCHSsnnK&7q<UD0&+a;Ul zI=6sW^nk7|#N>{l)Z<t~;$?vt<3jHZc&VP*A2R@GtV3-temCPH!Q@BsK&rqTDtj#R zzdYJm4Fm>uL>lv$CF6r+ODEM4KwpjXg34<DAcZG7;l~cX<pn-0eM=jID!&K<IvuLw z7JCutO*=a*N}hPfzF?7YYP>XA$T4aANZ+tZaRd(f8upJ^&;zrCue;J&t>FIGdtuFK zbQZS2*ux+cWOxdR5j=8Ek)k6{Ft{ikr9;0`Ua1f<6q$Cpj%es;=HJ>(2drGeOB8@9 zcKAYU1l<X@r_RnTpsSESoWZb|^i52zU}RdLf?c6GElLfEN=~c9Sl?dEdso(z`?Y!! zqS}+8naB+jeO&ZQl9+OV0hAURTnyd<er0<fPlYEFxg?ocdVq{}FkzAgpctD>cqAEG z#)k8o`Eo8S^y$2uyinytqZdIg@BMZ7M8`TsBIc0dZFt*YRU($@d{oh;&=978ODjkW z%r85Z)sC<nM!W{t=F8iUjq$dFq^9*d#L)qt;LjNT(UDA#J1J%7+rs&C>p6w$7bfsg zOP*riXWBz(r3UjeL1PNz?0VA+KQTp(?l<XP&8=)vy9_uTJQla|&!w~fTlW`>m1VI` z!ztI=7L@kb=+<tFyrusqzL>%H{`_V933<(_XXLxMB_YG*ZCReX(@ti6TdX!8f+xyD zj19eV?X&lRf>#M5Q{?LbmfjYj2~)E*F`3p~>@_ub8TL$T`<FEF?o17?+Y~mzZTFJ) zE~w0s!z}mfbieYiTU8Y>7-mcp<6)0lqoPZ1K3W=kyDoE$p4r@{rNqXU$2tknB~Mcs zthoKucj(hEfX54ntYh|uGYmL_O@G9igp$U98J21C4|y+tmbAX>r<d5F?wq%dhudQ8 znrnHo%XTUmNr3Q8)pr$Q&+=b>2iq)tg1GgESA2c#NAsTR+3}L&YB4OTh_R8{eIPgJ z1pHX<b$?%Pm5sj7KzYdsg%Pkr_|d-cj+&ylxkt;P;qYbaz0Q?C49B<qrdR(n9B`c# z&PkVlbS9Kzvfnf6H$%FkkK)|RC!hxjRH`8AYS7ImwAX5qng=$jR^OJQCl(ksuW^5- zzj8sTE`rZmir+!e)y%+?&&LhKtZ^>Y#v4nnm38TCj-E)ZO<bxc!ybGQgTXm}9Q;?; zmS26V16pTC;4)RsM+l+dVkF?m7@U7_;nE)fNW*F@e(h^CIW%aAjR)>$9ASSBQo{!a zN1EQ~d&#Fng<M77Wh%e7KSf$ooECI^=J4`gd_8i-(c?9AIhEWD-FjKIP&2$PeAX7} zp9T51vz!u{DxR}!iA}#Bxjk;}nm=n+bWha@*hr@_*3GbW4}WFF@Gr*&_Zd<)m_f$I z*z{#9?wJdB-i<hl`-9jL^txg#f1l1Z7KfDm$u#m;OvYuS?nrlrkLxx$$y3j|{C<}o znbBK0z%7owpECH=gS?FI!hP71LB&8jruFL8?+Sk`E_wE{x;F&JYsG^@6bt4}2j=f; zm3!rs3@ksq%Ft@C5gq?h+Q$R$tbG%Jd}j-LDS}ci{mTjn2gR=)^<8Y5Qi;IBe{XZK zB9Se>8yVp^+uRVqv%Ye%4?b{uG96TxEC<O#^(-f}nT0eq@Exr#YXHYGYt(;5Fp-`K zI5n8=JbBWG)XMQg$q_<%Tt3bYSJs`}XF)T=&<t~3bL(W4EIJn0&KV@tF-$T!pmk8R zy0(Nq1D*tFhFe%2k7dy)ZFATxsv^+GM0o10!jmI&vCrH|HTlfIsF<00_&@IzIdl>j z*V%Dx@Q?ISY<>;%)MHTskM&5wN*8nQA}X#fkr~3EoHAi`%70^=tbjXSIGDELF)T%P zZxi#dJDT?B&@q+Ho&YCVrkJS;i1lF*A~{E%rK2t5e8HE^jp$+)n<i^1Sm_#emn6V1 z@e6OJ<e`-q2^%GiuJ;U2DIs`;Ey%d9zH9nBf2ZNRCmLT;-={f6aN$kbjE_j)o6o7d zyj_Uf99B3UDjn3{OIQ`F^`RJNfuTpD;$|G5ye<FZwMM1OIT+#Y8V}}s=IXw1f#eZ1 zdKzau`*o!S^~dt=y;i07WzOGxC++v8Ypgf4c+?K^y&pSyIdoKDJ#HBL4M#%q5!a`+ zuCLC4en!dsK4Hdb$56ghmVKST2fL;lnaLax(>0d&Sx2V@;!2sN+dSt9H)G|Q1iRr# zF^b2Ai+i(Az2qy-St-k|$wH?}r1W9B^wkP7CtH|mld?zhuU(Drix4IU^U=lgKc@|f z!=5Gy3sc1)uCP=HwQ`rWQKikk%-|eH{*>RrGi>zuqTdX9>fJ4XBLYlr^npc-^+TIh zxL{o)d5ENH@Izk?I_*Wy${wdxF8`aDA$H=y0S&-?7`T6=AW#gIlM;6lsd9uQ8kz>2 zo;3Pfl2=B$i*+9(5RCZEl(&>54#M*ARG*tI`5O&Hf)o+9n7P8U)MmBBrm$_5zUEzj z8>48*<GX>AoE<~g!F(-HMZx@=h0pI$`9Ub`QFVVWv6$Iui>JUu6*HyWTCLi0eGz}d z08Ao<A^@==0Hb7Dn@XTQVrldU`9_)M@7>iMg?KAlDPn<|(a1<pHL?Q%`y-$!O5=8k zFd7pis&9oF$#Y9f-*lMUm>uLc2|;vp?3@v+eQzea|Gggu2U}&}`$g>V6X1n}88(hO z(AX?%q4eT^$(2;&IQKCPD}+9-AdU7x9P~=_vLA~#ve+8P!NYWf>T09^$Yq+{qR!aa zoc$Qe5HCcW+%$@axpDK?Jm_lYSFqe@>)fBx8*-2JEv!3i+i1GrsOZN~L$Dy6W0jxu zhu>}7h<8j2m1EMGoplE;U%iQ}=9ZX6ha8EoZri)(x1!2#ZX7#)T!+5{RY{??78<Z1 z6X`YvmB*9{nUQsJonoE(-mT#5hq$1RP()5zy+&7Fzea~UR5&D<{S)62SYwi3d%VFu zK0+6n1@^*Wjy;^kdQ!@5&gu1Y-wn2GG``bIs<NJFc<^FZfa2lqj>zp7whzGBhuG|t zR8sXGLn?un7o<B@J-g|DH!}WRX=OTPyx=X+y}$NF&;G4y3<d(o_^%)*I>h;w#T3eX z@1z)1`955-q<Jurx{*Q_$?7$mIgM6jNysbH(jn0EUV@}=re6JD@oUa~7k*B<DmqXd zC$9q1Y(Izc_~~R}-^Rx*iwVCA_5et9b>YwVzuxrB!U&x*O93NvJEnmm%f+u<KRBUE z9AfA!!z_7;<$0GRA4?9{`oov6|G2BN8$0KiZw=d``#@LcnX3CoMLyUmYm#P#Zuqh} zv2tk&@1ra_Ag$Ry%k_ehYk`!_JiD+8PK>^Cb#c|3y_fjXu2%6t;HBr?Cc!>&R{Fg8 z`s$~8V;)I9k8$n(%SAh1ao_9boP>p^9&YUoJoigR${#mW4nMH>>S)<tx09O9;bIw> zf~}DMtlv<0NH-tBN+S(0DfFD;tGcHDW_aCA5xYLR^Th6{8n=yKoPNpUoBpQ5gFq{% zzG_K^(Jn0H4!rle)RT5_b}dOoY4f$}F=SCr_)HCurc3e-EptsrX%9|o_f=<>$J(9W z@W}(6Q=j|YsYyTe@W%v&4HnIV{J39Bx5W1-PZ-^?71s>5$>YP~lauYvmaYPJCwR`E zanYo?_j&!#{_1s_XJgq85!Mi8=~dLGN5vIH?K6BDv3(#qB+vAphpOT&6G2)P3x87g zZw|*+_>OPOflpsiLndwqmqu5xvs1~rT~d6<p|Z+h0{dB$GK$<M>le&g_{jv$B3zxd zsJ{GH0OsaCbfy19ea+E#{WwCq4Dkmp)L;!!RshR^HUSL2o~5roqaM)mW-Us4dSNm) z@b>~y@=9EDc2P!2JoNzr6UIKIQ8F<|gSWPuFQP{BH;ND0-su3DZUpho&T#8Qm|RZt zl96^4h*S(4R|YOUhc^OH4*mMk(K~q~y69>R>wbb)%$!^uN5sf!eO&bVIY<`;=WpP( zYFEGIBNy>Cg`*Aqju<8lMgkrCK5iMOc4v?q9lYYPW$nfe8g9q6o~r5hVbjJ&2ej6` zT6H3DK&#!Y-CmP}zGm&>;5Wv_Z48P+i>w?f|9Wn;zW=df*`@oQGb?*$yn79uD>dvj zztsb8Eb!ZKbIW52gd19~K06OEAom~s`^SJql3H`neUHNZ<I7&J-O0gP2-^0MHN#a4 z)x(i1CmHYrfzk^2dY~ly20`s|dcy69)Qe)N6FxfDDw<UceQry3UE?vxAi-KC_zR#R zE?d`2`!t)D>hF0IynGpM$n2XeAzA<d3K(j!cwfXEC@5y~>T|`7rgF$BBI%-W{HMss z3g(NZT}!BY;9w(K0P!VH5OvJ63H4V4WP95smT^w07gAdQVKk#vlz;&B{HN>4`7*(N zV<aiMO%TdFW~2P$P~@4N?^wyE$y6_b=Fd0F6<1p|M$iY#q9q_N(nk{e9JS>dubOQ> zo(a!DY7sU)s2nSVWlMagVs<S92^=2xz*nir!YK&HozuQ1V((x1aPL!0j7sgn=t_z> z+YDTIxb~@4c-v%;^kqK4D9WX~GY{#={d$VT6;{rc;2G926J;(!$A~SVIqW&{6Jt3k zK<2i%PY<WSFLhqXp(WUn%3?L<vTVyZc!Q{cIQ+u{0ymI~D94(6U<9#(D|wIyEbr*H zgn7=F|6K`*R3Xs_NhuS3`2~4(1b9BPoJwyyTvn~)cIzAMVSUir36=QD`r8m;jm^*y zF(N(A8TMygE(&S2>qKS-!nhiG1DQeAw1_DL)QEYmNn!yy^BR`sTK5$r^N&6go(0r0 z-2zz1eV^qPo3NelKLJt&B_-x;v31oWcrwg*TUCl7aOlvqjh{^G8Cs|Qm~#S<3_#*9 ztP7V~%>`Y1gh&zAtIgI<XZJU7{7+LlID2HOzp)E^=yCg-7sKBDvwMq^c06%I;5G-N z6KT-qbyY322~*ooxu+>f<W$VI><Kxxs?t8Aq5@xQW;>22_s50)^79Wb%}2_+iVu1? z$O!no=u^DRvml^ywiY9*uf2Xp6>6$EaW`mh++W<c(gNf<oJD*J^zxtPD?TFW5*A{l z4?f*U)F4-eI7dEHlwMsu`z*<h0F6&p<)YpyIXpuHRA*We7)l%9?P*mk&V%P}pCa_~ z7O!i%sS%A7D+9W4^QQf&ESicCae5`Q?;jk_ixpbzRw^{l#z~3;B(8p3O|DDYw=TG+ z_po(@DLS4Q%#X>ED=pmzu{^(E&7C1kSSjT`fKfEX?Pnko5B{z!$2TI8rF!$7bo06v zGY+E<23TpBsJ!z!M@Rjjb4~Y`#X<);92TNyQSNd}HNf>@2nS2VV76`FvkT6@Wf%jg z+@rQ{#;<3l4eH+{;hgH5(cqp7GmR^t?i(&A4DOcpwsL+tda5T5B)b_qcD+)!`je_C z%UUMz9cd3a{obKYIlEoQkDgpnsq)^nu9uJp`o*rO{L#2Y9&CQKX-7ojxj@a)b;a}q z@95hG()&F=k6FC*t$DJeX453I!M$RE$>9FO_}hw~pHTn!amz%dOV&Eh{&sl1^5Wum zk9&MGd`f*L)$a$jnBKBfJgnvE?;V|vBFI!IaC*w>Sp9r`+)^3dk0;2oHG|YGgJc8E zKzI2QQh#lI%|1B<_xxw3+xI)U|Lieo%hRf<Iu@!fre<@YzcTLl#gH)jVZ8dU1&`Uf zd}p+5;XLMqv_HKsX5GO*Do3A>s#2KlmwG(4<>|%h*|o>}z&3O-*|`Cgn~a~ow{oH% znLWL~t<vs#0p9Wlw!BLPVmb2*kNW<&!NtLs3+p%J9mO>TE+z&ow+<}*vdJ?`jr0I5 za834OWXLOZ4${Gi2~Jv~!Lq-7VBrhd{I+(XxTUF8+3qvr*Hi&xf3ElOQ8z8&Z1I$< zZ4Wt<ey@3<?+6<`ig=deB`*gGhh~%nth`Mi-q4pYb1A1ikT@mn7L??PO12nTErY-u z%hyUKGwKkYFru9`hm98_WO9oj5&i$q1Y|^@MeOaNAJ?2R5@2g!$GA>S$}g(eyhyi( z-<-YKu0O4q^dk(QfA_})gz$q7lj^;B|93XpWytc>{Ad%sPR{uoPHcCqT9g*BaeFOq ziZ-km2EgnVfdxs2E_8bHvFjc4M5jB_u0Q>GT3fXz|M=a+`EILr&+7mI4ITf~l&nRx z_OJdJ*?T!if1_BjIdHVby%eh)2c@&hAvodpy5_#AA77!EO8+Vsk)?}Zwl^M2TwEmR zk}NZKJj4jkBEhwsh9ag__!$b4X#c@~#HN}S=-?3{*1nE*@-*drECYTBt9dcYU!18j zNrk;{{_6S&b4z?Uqyre|=?X0BK(ISj{l0;fjF>6lzjh-n^dC;<FieDYInH<UO8pm_ zK&Z8|TZ(zHJGnr_2nix$k=+EDC{_-;OXL+Xtc15h>3=HMAU+{z0vaX}K<e)J8dbxU zC63`)V{rIFpS%>5%-c?<@Kn2h!vwU`^dt+M$j}D!KZ+qHw2#nYk%UD>)@#*M+2H8H zGfzRla8dzJwI(TBAlEkR_WW9`ULdz6?c#5Qn1_;-IHZM)#I;6Dc97?rHx-E{6J=cW z*S2uiDjMsYfYsYcW<%$#;;u<mXS`sFu7v9fE+%A|Br*I8#1n7RGt<5)pzr>RyXc0q z$MUr^V&dm_aoATd^d3m5l0k{V^KcRJ$u`TEMa&d4%@;Z>ksu*{+i^H%UxJ8sv32%B zj~T^>YLxiM#M(<DY0@r!pw-h(upyedn|WptV$N!5<(}|!!5_GlV*j(%GVKqfEWx}7 zvAUre@fqLp|BHfME=CJtNAHQgm@uqGTg|)K{;-`QvkYMvMVMeVK%3xJLH6NWfB|*> zs*-E|68I*m8ht=AHXbf$NXWi`fYv&7rL&Slkv&QSjUC03xP)amg8Z(?T#`C)IcRIA zN><$J%086&@{>+U+5B8eu7yedC=b(D`)O5(<*w|WpYZpujE>#wYBdGy2t=c5Zne*T zX)oi-97H&3ynv8Wx%n>CG;*^=E@;hvZ_7(p=bL=qwC9A#baS)`3)*g7O@81oa=xR& z!(eV6)U;W$uH~Qm0M8bfAs34}R>eL2{lZ0KJA{2^$$>3U$LaeRBlJycn{|J#ED`(c zTCw!vzL#$6KV9e`Td~~eEB-Ta&Jpy-<kY_DG#R~jIT?BSzpe)4+eXjG`sPT7zrfM5 z%kPn)dPS>p+$m+DYHlUtk%eZT=+FOqnbSI49)D5)2HmLP_Cr3sUM$OP3hq97o!}e7 zJd;-W|5*C&fTqvyYg8<bZ>8dD6^OqQWGS?0wIUE{p&_7+>>-F1DWbLrLLmyo+FHet zNLV73AbSZ85E+tEM+DT!Rw|-|jWWUv8GX-_zJIkUB%kp-&%O8DbIvW#`b{OI*^b?d z;Wj+DaK;26-ve^NV+A|aEqk=j_bKHT*Gy?`S;^ULh2tfOKiO0Yqh9cO_(Z_PZPD^3 z-2|k3eMIqt#lasnmVR#Xq>k6d?o|G(hVuzCAUrB>RsDuwdE$^#gltoUJqN_(HqGo` zwf|GpJEdp06#H+bm7!#z$zz@FKYFd=ay<zz(;z093Yla8svj)L6zBYVQ#X%)ikSpx zXc4S^_?r323tY32n33|Rb6CE2!$B7Srk5CUF>|_fnLjs;4HGZ8h0FwjU*#Z<itg<? z6rrhrA!xt}(?SgME5hJj<T8rh5T$8TdORJopQQbJzx&?2k2;2Z>_ty@hOL!lqRt5e zoyP=gY&M!)WSDVYV?XgCfZS!til-S4u(%`CBL_4}dSU_rkJqaWTk4E2bssCv*XhiD zjq^g}Aai-A`FN8-cR=nd)JQ@3xpNI(R2kYv&jmDWp0@V0mUK1*wo7G;drn7!$Pn36 z)Vu7b6Ti-#%zPH&Puz5IZlcXH<o!`uP@%ViH`;)wJmMgwy!HFAJV<=x(=DCh@=GUZ zQsh}1`>~tBv$?PQ%rXU_Ss?DUD4}ZP2a7`kmb>2yZs+oU=CQ&j*pK~QwLK7y`F0N8 z5(eD>)e=KWs*$zTnGB8oZ}#erJY`)37MF4K@xR7JM<USQ)&=#hkTmd2zWwysLwWGH z$M3=N&H0QVc92!pI9yQ>t}6yjCMUXQYIO{{w_ek~|612h&K@$&R4$oK?hbsf=w_b1 z)%lv~um3njW7N76h0GMcU#WC^^m@qI`Q`XaamIFI7AVzIi5hd28N&B@(;&X!^ues; zh3c<8-)1;)`w7otrzbVvkTjXsEMdOQ22qC<wo>;;qLWi3Ji*i#p2OmMa{$FB(9x9| zE+y&pCSx4P5xXRV05ax<+KY2s<RT<`&4z|XqsR@=`y>Y?6-NA|X$T)8L~tkc=Oi#$ za0b}z{9+Ftt(T*UVoDh{N>~wMS<lH*9b-5y3wpJXnIdD(>w(<O*ZRUIy1r0lO=Kj` z8s1#q3{tdSzRqu0GeDd1JE;SPs3ro|4HYdQ84r;=b~f6bLdL-c^Eg{+ad`#o$aTRX zAuoUM8tF)+h3}_f@J5Ei0hd9a`4)lW!0pKqzY&B@n9!)`adveTlw?~Jch!hez?%}x z`Iy&I8DL%T_DEz5Q-w1510Z-Eih1X0jW{HbV&BNafeQgEGG=?-@^@ae?z2@`4xn^e z)=wNMdBa4!^!CV!)KuE7LmP|8=o=6=v5!03Q+?S&xGXlq9@n$wmSqwpfE;%X4*cEx zhF4w@j=iuY4QhHUL1o-@A!5OAJZ4%f>Ju1C;!}t_Is7M72}C?e5CM`9(_Jh)A5boF z%4Kq3QcDm@dX2+P1Wodf0IngUx6z^ZGH{4LP1k_03aOs85x0ho;pwANGonT#ye4#z z#rP#`9~V%cD5L9nr;I^=1Hgz18=83nMnkr}Sc^-WVdGJ=zIy^IjyFgoP<L2D4u*)} zm?s815d*^THJG9V<_>$JsR+jYH1N8<q2s(bn!Xs1@=uiB=`c@<)w^yupNSKw&bS)G zpcTIMQ&bp;Lt69#RULV5r0A#OSOsqh5IG11>ly)vBVxcQmxR>WPN4Q^Mx&h@NP4N~ z^>}9qE=h%#wg$3Sa0<zMf&Of3f@R(#xeD~Djbuu&tpsFt5(EKvr_aZnAm+Us8~qg` zZCKS|S&-mKL|9zwuLmH<$%Sc_QbOqjPK|>iA2O>@g0mE+&%-mrYeZ&6sE`<~1rrFp ze0lw8^tHjBBx{nc!~8-Evp8T(2pIyx<!mnq*g(!BT;VG|l8MxWa3>t1(KaGm*oKlq zL%mDheyAG@g>pQCRD=_LaR>ub^0nUJv_}js(O(XoRgntGc+SQ9fiYpCWx5CYs@Og% zxka-DP!YP}a%q^Tn<T}!paE=Q`WG4_Vji|cCXp!PoCrN7kTg{StaPV!>@#h4!9aP{ z(T{ajY|St!pLH~lyC>1`+CixYe(hrRi{)R@j_M)c@oelOc9TWiS!1|sY6GIjA7BOI zL;9O9ZxVbu4aP!8Db-R{`y_2{;(mt3_T5J!-$bewaHe4#<*874A#Z&R7v(D1#u2@B zcCC}kMO2B39Jc}Bjgl?VH;vr%TVgySD)@s1mN9;DVCjLZro`rOs>|Ce>QyRwNDWHf zN4#t&3&kti*8mJGMOd$n*CHq;#^1vUse(FTSc!ClETA@k+I-1#{=&b~KudUnx*V^- zgS1<Fb5ZAc?D5;jzD0z<H6>TA9y+O-QFyOW>=^EsNKX25=LDv?ffH+K<}iZfELyKp zDL~<)2>4p|pu!ozC&+eW<VZo3gcU@^!)XWpX(T3W>l`32v=LVrA&54CI<aoVJd0h8 z!V_-<nVB>gSC1sW3m_H%HD}EFQ>jyPAhIg_{x2772!kZTCM4cv4iK#a=0>*_NAIq* z_9y78fGz0Z`&V5Jgb;&&2FvPu<o=eI4@F?R09^wr^-AQ^9{Yd4zW-SZTM&7HlL<YK zLhB0J=Uc+}GWW<Es?qMcUWZ=HNOe6z0t*k)q}c3Ae*(*4(zTT5-g7p^3Di77hMh13 zs}>mekcFy-1MH896*jiP%G>9GS3S+caqvQ&Kc_<{MIj7^<^`b|HP7VaeH^`Y4tBC} z)K|Uj9qc<@!XSgD4_mslm=tg^nueH)e82w*^^XpAw00JSWQ9g0p7AUn(`27h94Le3 znmBDSVxR#1_7vY`+-{mV?KT4#-EcSMm2jG;d=_bG)%}@emAzQ<0Vz%@4Xk*-egD*H zcfsCq4!0~1Pl$fyb;V(|)so%ItQ^{rj(H(pyT@F0Xv{Cj<HS#L-GeJ?sVlOuz`=RF zaf9ZGE<YZz2aHyS3z|z;jtf(Qv}38`Lc~oIm&Mz3&-RWAnXg37W4<jjb4S_1jeav} zQ54AoKnZ7<2gcY%CGCP0k>=fxx4-2z&rmRHMC#Hlc%K+l%$iZIjeif|ut@elz7R+! z31lT-wti+r(Q?MRu`<aRr~Dpnwxo*@l<&z5vOohALf~4SMaC1oeDqo9$#!Zh>r)0} z5#v@I!$sPLx`GbiK;RNBx)W}J916sIFg;a+a4v~k06rJJrTTb<@4WrEd%NXzwxN6W zIDxR8v7O3+s5szT=7eE-20TvzYa`O@pfd(BK6fgt%wt23Q=N0u=TKv%9ZdW`^7~Hk z#Lx|xcYrpP03e*9^Tj>1-gj{op1C+Ha}UIluFnt=>O(5RakxxD6D5K8O?cUC`^=7} z@LlC$7+?+fB5MKGRE|>(bifc{4Z?LSMsnWh6sXwX#p(Kj#3QtWsu%523FgHFfqT~K zNqz;(-nnI8AiM~Z_-;@;?d-rEwpsl|@aJOG1vkSmmsvmTOJs#Ntz7=XjyY?Fjyvla z(JdpIp$*N_KVk3ymHUI%>Iy0<#hx_ZW8VBx(=15;@9X+I!}eWXu|iqNV!ys&@~Qj@ zdaR1$MHR|O5Ni(&-e$3tlElBnQ127)1PoP$51WLUMD<X(TSO&puuUWMs#b_ON4TbB zU(rFCRf~gByI7W}voRFKpc)mC!n;UlfpiL&1&1H33LcIHEQ3N2YJm?2ASz-2r}8#3 zY8(iJAdwXQISar5`a=U4wT!cEIGd@zGfv8*yFAmF6Q~>{POT>#dv8d`-lCC$hGiz& z%A*jaA`WF_a}{3shvtowDwCM7dPjxQ38QKL*T9zWwS-kT1!Dwa`>;oyEG>{1FgMR2 zg$`t%kcPWRgkJ#quWC?gF#r^ZBTJMWP6l<_L`#MCT`UN3s3=vQL{_>76M?B>y5R{b zB=Aq*=Vy#QMf!ZiPDiGqCj^#;+rgBc|L_wCd>}){Y#SY#s?w5brSo9I@DxnyC(t(F zloweLD2ZQ7>^9ty3t^&cIQ1ClbMjci#tL#qhO8C^7Z0>w5+KMziG$n5#<kMJWm{qq zddTWIpnk$_jA?*Z6yYSS0fK>N4dE2LAMiJ5*dW<3hD{<qA7Q{}2;Bxli2d*`H!GEJ zMx&|tI_^e6dYrrk(JEIDD6KIEg;46<4WYP(Q>Lt5uTVEI*`<CV+niVvWBvEJz%Dt( zbpg4TX23C^q~iQe+rK_;K)IGGn`BJ1s(Iu^ee&XM3kpGNhGoTiC`Wq7F&+8jw)ay< zw68+Miy21((_2>;4A`%Sz>R}Y2%EsPfV~rM)5z8Lfn{O*`+;p3wy2`DCx!dVc06xM zkHZu5fGu=C_DFc$k*M$b9{$qC^Hz>q)*;h%<vZfd6JE*D;oY0WiVm7WmUlO1gw11` zBWr^C(A47WZhGkUi;K7HU}X`kKCGZ2qXJM4DkUku`i6A%7J}gb&mlzKjdGGpHf%RB za>}+&{;DtTS>1IJ1+p&l0v{VomFWP9G+8_|)ApHBS$!SvOVs@&yK<U}O#JX!{N159 zOw!IIo1x1#v=e0Vw*Udi%upL$fU(H1!@1mviRNjO<g4#KQ2bY!?rVcrb`Q3MK$|W9 znP!?2oQHh{F*hr`Ojd#4>E}2c#I?SDMbxd+!KqipGbcX_E`VZXq6s8UM@1nBh9YdT zVt9zGC)5ArrCITe(-De}sDvBtX-{L`(Pa)Gh~PHthv*?d(t5M$y7AB$A>W|&XSjJ; z(hxN87WA!yqD!^2BHrvJ{$Z#kviQ}--wH#dCv>`ymXd7WV!-sh>Dvj*v;V4vGH9*s zOU3zL8E$dB*8`>uylb(Nkf9tMJ{(TjX7WuBeOq+*!_qN%P|bE&<FeZSWXhgNFnJwW z^^z(7RXQ9a$17a$JYmiEv|!Z}F%m(cQ{&EGk;6jpi6yNDb8(zH*vc&!ShIT5N~c|^ z%Ylj_L3Ko2qh{@4>oB!}5$UC;Uj3zfpKW6uW{V|G8@z9p(M9=w-jRL}??{z_@)N#H z5>E!RqaZACZ$B%yiFl`QUn;|DeH#x;H}2D-A^M-0Q@4khpJV?W#98N1e*H~d?qM{Q z@oWb9Bg10aue37Jv`2E*?B5L254ud=@C?sBEl`T~_|Wk1hppX9|M4`NOuaW{f-PPh z>h2Wp+?#SSKkLMgsl_(Y)MLK?s%0ZB-EFe%A?4$PY0R>hfJ7lS8E>Z?p<-qiWn{Q` ztm~oCmXg;@Aitf`P`5uNGt7mvxnpd*@!s6H8#dZ&Br&5O8kHk#RaUKR_tTQ^n_Y1u z>Z_Xg6Rf#|{2{YUyaQE?E>4^i6$Q-&U-&7eQC5mV8Gvrr!#8V~w_khub<iV%pi;lg z(48H&uW@k*r?^Nycl0v_F((UtFfx-5%uAHp8zc5k1*0x1!~$jclP<&uKKi01aZ}u7 zegiX1okv+fvW9WcaSE)*TPcwbP6RNi;p*rJ&chg#xk@TL(oq>#qHPGn1Poe+08N$_ zU^YUGP@4^xYI1=jHTF5tQ+9fSKt5rZVWCcJqP(NfIn0b7ec@T^91KD?{#^rn*Xn$n z)1bBftM<wm!~tN43}Zrx$31)5Aa5AqzCmAF-!1lDz0r8{w&ta05V@BNcV&m3{yh&R zLbiQ^r$(a=T8<Tl`5VMNnNPtzDqISrB5=I9C&$X>+aAD^Ft^hKicz#%C=DanKDKbS zwZ+CYi?ByPJwq2A3Az|NE>T~7xirBQSvt7@_j$HqPC6!Pbe&b3?D||$xBxE$MA1oP zX_=T#F-e=9<(2zm{9f@%I7CIby&yJZ8b$I=lAh*pz<HPoh|eK;;;$`0)TLcBe7W5( zT}#=l05)h$#h4*2ssYRusJy-1SX{)~4fnZ1VyKawLyTVQGgYi9(0lxDr7v3z-q$3t zeuBsil~JG@plQXH!cT%v{6;L4(gIMP;iytd2#pq>0umTO$w&xwrJ$UH&#v0ZT5SRh zRJu?(eDnj!8^CQRsMSHMO3ZurqQ!z#j{taZ2PE7r#3Xb3X&1oQ0L^J_NP}vf5CLhX zoJNSH{2=OvXElm3S3-=KfEJz1Fe3;d78lf_b*N`Cu?h^f16g?OZUvrLc={;hF&nOq z;JFd9N^Ue`i>?o7*dpaC@Z0Ois3>|0;RfJX&<?}ePhUW&)3gyWy0@x9A6`zVv*N&{ za-bsC1@ZeEaz_Ef!;Aum<~e+-4m>Ux5+@8MXW@gNbFsE$;0q(<Lq}c8ONR*+>GtEd zalXNeYc3GFchEKfb}PaNZ7VHNBZUwpB~4kxB14S^JD)tb_6FD|90d`p!NU4P6np3q z0bT&e#~G5q>O@f-hgOV&Rz0Gbng@?`HN0BT)lIQQ90b_$#d4tz1JpM11n2sp2GmoE zam8xzPh|nI%H%jebqmFQ8Us^ac#zsa?MV!;VV#DFK2`a8d;rz;kTBvY5~Y-FJT%^9 zTp9^?KN;a_d5A8pYJlBBou~;YwV|amS-+?sW(~{=+XNJ3-ls@PtWria1B~ov%IKId z5%U3wOQ61*xdRNkvpBg|G>T%pg}v?7O3_`~z_#Nk|B--A0DUz1dw8Ja)LkY0ES0C( zDTQVv&4-Y?BPfbHMS){$K9!_ZXaji#ac(cHP_Vd(s$w_|-x}nG`~%N>7fi*y3wudE zJ2ITaOt?Kdx?X};k%sOAG`E9wEF|5O4!nh8o*Sc>xPaABbpe%gN88r;*7YX;;6FkA z1J`4Y=**)#i3m-c<X0Qz^_(5&aGF37j@ZDYW*~}TsT~P_{o*?7{}g>sFv7XB?U#Ns ziHcX^BO>KC5uOqcNz`KyA<*8q<c>-1+uG<q#M9i4Ye-6^Rgj+n-h>k;3xvTWHbLgt zeQs<pG`^N24*-ba=GWQ#?Jf0q!4)O@U$tBG5wTPZjNv`R_{1P4OX=&8L`wyiqkep7 z4f+-s1_t{;Wih6w0UH5x2K{QR!eC^{{RFk*>Jj<{e6bpGoSY*eOJ~81l3fibU#jSJ z<*R0dqYd!fqKV(Y(VPoHVkxiBw+sQZ01w7N?OAF+UJ9~;s$$xs_B}zBM<vJ+-{O8^ ze8ZFdq?(}b><b(}{B=(w>XsM@S~AVQdwlhK<eS26d_qNOVw&f*o<Gl)pWPSx)Ere9 z+FeNul;04&a$wP)oxaf^nVxK$P-a;hYHZ9fI()j;&d!<OC`lj?gr%F};K#4I7=8j& z66O;q0z{|-@jO5r#k@U0xaK^IrDh$SEG<;4Kh5rtF^&k9_DkNf%LZ?=OUl4FiL?xL z9b<TTS-qg-|Eu<Kjeg|G?zZ^pORMcad}T;$AH2<=TuE%t8Wl8Das3H;DK4q!FOHmW z9^>3vs7#H}Kl7Rr8ae!d_Pd}gDPGL|T=*#Ym&)Cf?4eOX>tk#a^x)cDF8pzA(J|&v znpvec4vadaZBxODgV!P|O>YGi(R(|Ea2!41am}L6A2uk{h$d+;UpYs5fh?pm4k5fG z;g-zfnd2U(eQE3;CTf+pt2MgY|LR=Yy*n#uLa0bB1W9%j7PjnmdlI!yDigbdKWCb< z-_Z4c@;h`Q_}s>*2KX<K^%Wkm(kHV;esQ*ZY>n@%Z+M??t-(ujPDKEkmr3_A^^4-5 zCXnALd1=Ld;8d&g=#ShW?Ib)whPWi&dTUJGm#<lK$-m>Xa_8=wfLt&)h(T|qeHNMe zdfm|p;9i8knEmZR@(G=m%f7W#Edwx>Egq5Do|;FhMIN1=ymKMUN+1s+j*}_|Ei|a; zq!=Z{wUDTS_{akkW=kL$v_<j4!?nXVVaULWACv(UNmDG2!(w=SHR@1?#2FT9-uBAg zO?LWf<WDFSAnro)W-N?DpDkqu$=II>b+`6e_&4`}J2Hti(!AB#kjlxr7e~Fvv$Z|F zof7j9$9w{=9fd<qxW{@LhfvDDo7=c!p|!=2^)UQ&K!H!qgAg_2$|NqxoXl^}ZT0!c zYB7`8K&$~{%n+RXEcJ{OcjKb@tgupau*=p1epTHx2|3_5FOt`zDg#2w#Z%h9?}c1Y z=3%EDf}_RC<mwAtd9<>)(i4Zp2Yz+-eyeZa`OQ^TMW~2UQhv<6OAcR)Yv6iJqH2xF z%~?1_t2%EU$jsPisg76nOr7gdHpMIV0`)`?&1%WFB+#&j$NPgMc(LjbHZf1+xYDaF z@gk35z{f$x+NrHc3OS+z^1>lE5D!Qo9Ki`9CiBJXVU^6?97Q|@hjT|&rkljpm{`vv zxl4Ao0lh40T#DBg0|fy|9FWitqE<&CE@2p<!ob%8(m>htL|%_M&+tJUz!ec<#%1uO zL5RcP=(ou0F14ij#1Knf?tk59HGM%B5A-f8Fe(Tg2%!B0^gQH51=0hdnu=`&j|^Q@ zWYDQf0U7L6=U4I2G^e$pGYWqeXs5}5ERu;vIP23PzxKpng%|2LUjeu?fS!Z>81`K% zcG}JrwUiWF;=Y9mow~CF^ROv$!Zl$CoUQ8<6U8Qn%ZqvHAuSS+23)~;M<^z)BWe%` zjSL!<&Jx3UdWwPaTNvZeOfMy(0q`41IWwh*iz7-0ezdA7ML;YKSnDBC!s6yZ`fKh$ zG^nuHC%D9R086q&8o#%07s4S+CJ^9GdCrZ<H=tgFQ#8JrJU%=R9Pvl75n%U5#w_60 zhkD>9;H1qSHd6hsnzahKx5RqNNz`iz0rZ03#7x{bdlrZZeJKSLbSzKk1rc}+=Zy=I zVvG!M{u6}dgkRP|+XONg_<wTAYu(s$V<$oh6ULTv6~@LtF~876B1WH!1tfry3@D7u zIqxHe#5Dw)Tvll~AMIjiC*)V0b4maf)Zmib7>$1xTbkfX#jto%%t;Hs|4md$-l^Zg z+2izh`j|2mgg}XREkZmxg(0x?*eA|8+EII)B!fLiWpSgJMEmh)+v@sQ@gy}mxQ;?{ zU?L6lcpKjU%{L-*rZoJ~`-E&(RqDjv1J%=Cu(Vh|qT5x?x$|@Nwj<N|qy>Xy7VC-{ zi4RHf)l5cyG-saDD~*8+fv~nue)@|^%AYMtZP~_97ABozf$gri6)BhEvDt&_p4ceV z>_CQ02ytLF#0lbHSwqE)?iv2^r+G=bS}$Xo=myj^$1rXd42&Q=y}`5q((mRTWJ{VX zUezdGlgtsn5Yj>kkf6tjxpC0>1q8j<>%7om{n++uq7bO~048b!WI+6e<GZ<)y_6TM zMaK@Xc4&I=Os>)zBV$)$ey`hqv&a?4dATng3n|;<^<hiiz%W3<pMVqP9L!lj?64<& z9KWk=I42_qWlx6Av?U@N0+)e3H0YfhdLISn(Mwnk7@qoH7meLN;wHLFzS3mt?q#%! zJ`7GG7lhM_Od8m}h4mI`>+bDtN+)ltXGUn(BN2yKORoSadxw<2;R#Ot)^&xx4vX+B z28!dHJN>OwCP>s(PHe`}nKJugdSmj4AQF2ra`f>g52Y3I2rq~d=p{Dy+AXWjiGlUO z9fW1@Xt$ebNhZF#_geT5+0RTqbL_O7hO73;W@-sDp^vglq6fY^ti9xu1ROw`?>0|6 zp_J$RV)yT0i5dlwxilE5t_kC8^is2=#<3OJJQpJzZieZmpgg0|eEQq~CmH)6-CB5- z!lWz7XmAgxQiL#(uo4C0-ZG5LG`>WOW`04jldo0WsCFD1{P5mXtn7Tj?#(Wez*vjq za@V5yWBuLjf7BS-=y#ndft9@C_1sS_F+Q>XstHXbIg1OAd^_%*{jTBM$a}N?n`tnv zz0Bxs(~dn{zSx^SEJy*@A5(d!6AS8cq!6osqo^NcFeaFO+VXz?>E=hDSl>W-&@dU} za~wb?GGYB_o43r1*6YT*MkYJGmsa3q;S+L8Tz@e98VPbxf%lOy>6*}^Jcs^j`dg3E zc+qdFj#tr+lerxG;hd%@H-qFJNJsE)r0my)_n!xu`f@*-Eg7SKGn?vfxdvp=g90r0 zh(;Ce)h#&Rb?1+&w~PBP+vvYZMcEpO8i^d6bBRTVj`{Ab9)A++^L_SpMZx2fj<b4I z<z!?Fc+@#zE(M||pP|PT|Fi(Tm73SHy|VRm{i3<@-^B3Z>X8HqNQ1duIG1zQI(2g` z(6q#?pEjj5QX+*XfHy)OoWQ`GF@}8QZF1CXc!=d2qzs_<zF4yw>pV*`BSji<eu<{J zy~^~DpjQHMjxz=x@T=1oW&r7Qelee+Pq6}gsgdkdr{i``KZD1t0HiA1FG0`1F#Eu1 zOg7l1v^e+@o|)eOMmlxViOI2=tb<lE9Zsjl<b0z8@&^65G8(?6&_54t!OEql^tP-7 zVSq0rBzf4c!z~C?i2yNZoe$8&4>-!h39<S=??fx3apg$*{PWa&X#f85W}2g##7qiT zHDKHDBqeZCo6C+mw_{sMzm`{xnpb{0e6>j+9<mtp@51Q7t~0>~9l1C@;6VsK!6x=2 zIvdQGy8b#;CSm;lWyXJSrf-nK*T%!Ddq6Ju1h7&e5+TX+3v0<tC@mI0=0+`niSf>X z3>NSh+GOOK`&*a`Vq7W6{TiQ9WBh@y5GcVml;NxbgZpzawebm<O{xH*A;OjecLOTx z<ejS#$$*|>O#SZhCc47}6whSJ9?GBX)cl?tI*rgKV4RGX0QD6Nux$Fk8&46U#sH3> zf=Y0Ch&el#!$u9VD)g_bB?H9K)-yqk-bbWQLz-_ONd#g#Xqbx}S&a!hS=xs`anf}* z(|*BE0mv9Nw#CDC%GRP|dNqS0!g~=qDJP!hYn=iOD*{&xsxjseSc*oQ-%3HX%VC$G z%)bP)Ss1{+m@<IFA?#dM^>Cjc*vnS}5+{zxaC}$Q)6cU2o%gvehJuI#R5#GZ?i?Bi zBZFX~hcvyww0X`soOo0)hM|AKonSgB97y3fgfM|5ZbnkTVB#o^=xxMHhE@*7dTwX| zVRjyrN!oEjkmmrBIHPC;I}Hc$Mq<RQqXyPf!c97cXolJB)Bu0=G#>db<yuhTds`^O zw61(>j2Hoire;}5o4#iKH4?R7U@!CsyD$Tp5waR_0^P<2WfG}J9RjTJp<v9T&&Aj^ zQ9#2ohQZfyOdFMgEzo~$A!3LH-f|C!uB$B5m!rGSpEcH$pLM}}ygh68Ej#U4viv2k zZnwCk%s(DvzFr|xLg|`!XYwn@IalNGRyW~H@bcT|{ry1{)NF`AXN%WLd|u}?&g@>a zl72_w$0v{yk16ophxBZ&-}8p$<sC#ESd@QbYVjujSH16Hvsa-l{w%cA?UI?^a~AFb zLytvZwIr~Va8CpJsgxir^yf+^jEhb{7l{HBvc@Nq>?0lci4N6`duVg%cVjItk~uR} zP}fDWpqW9yRCu(+aHlJ5pr4`|F9fe$-^Gv(K$gb4P%Jk2??8`$X;!Q@I|iL50?vE8 z6z6tAc~15xyoaJho$~+Bl`oAR-3i$f>hridS$#e=CNKqkYPc)7BQvDor!W8w3JO(G z4eMQZ!!2Jd!U#{~R=+NL0w}BtkS89*2CyTryCU{5wc!hi+5=A!FD*E~J@x9l{g~)X zh~B=&MBR^ms43GtR(1M%kYJ7q0Z53?K$+z2>96&eo7STn52rwJ!KWDR&a=3#Ujpvh zJ-KLZ&;!7kd}6{l3tW9rp`e@(@}j?4u+EJ%_LFewi2Qmb%V*2|)z`dWg{aadlYdGC zEOj0L1{u+T1lH6X8-LW!??%Y!%|#X!>R#%xrQ(cPSYK8=5Gq|PGNZ(S<JzcPV+}D} zK+)-iuG>h``DnV~2wi`9qdvgJ@NZ183OMI668@LZY{3(?zB0K8Qx<lSoBNe4F)zE7 z$W(WMNQJv|W`*mRF91&5=hWv!lGCgmJUXmIz{)pGIvvY9*8`uEI-6~qYN==|mPc*w z9v)qG*r~IFNhJxCB|ueT1qM`dAtfYgt>Wg<;PjhKQ7*D7JiebH56S`=sV4VU%2%K2 zr9GH|vj+-Uf$sh^`yNgWS8)x}(RJXN+>So|ubRSacf3+*AVtSATx5KB#|p!IO8Sc< zYks+dxD9tl3&-95GsKn#+k{%Y;DNPeV~l=~Q`ca5NGJA(m7a2mfI{4k@w)r7P5zYs z@x1(9(B$akg)pN1>(7on`>5pCO3jBadw7x7wJ7(K`)es^_Qllv0ea{qJ^suZ<j1fS zb?Vk!(sB5fbebPi-1GQ*gP!t7n!m>U-|UfSgMU5%QIiH*Qig^b`cLCy+dPJI&sQ4+ z6?ne(JlwXt>m_66EzfFdyz8;()mqv2X}cZ&4pG!R0B5!&MTR^V#UUHOW6;yE#}4!- zN<Y$BM2&vK$`RbJ_=dFYmi6g_y{)TlK*!-&@POotOaZalCZNUY)JKM$WrFH70MQl? zz9GbyULR9Tv@nPPnc3wp5rCTLwh7M?E-YcE^tov9`&`z8F2{sk2jkE*_5-F9+O0$5 zHthXs1J0F6cH#Abn?BU|ei)!s!rs#;VKIHK(lA{^2$nG7z*HCxRLpw7V)3FwVw)L2 z8Nz&1@T+<O17oS7m9*Uu<sbs30SbVVgM6XGTZqWXT%<6kV_?(+0cFR;8r}rpPsTE% zC6S4hr*FS{vgC~)-FJ5p!cq^9yrC@qF!J-zj^JdS$?z7T+cB%9@1l6@Ae5K@-%0t( zp9}P?F^yLmBm;@P8?&~qcL=GAXo_8{b8z-C&CCaNx**K61*0YI_2hq`wO)m)NJy~F zYfQ*goi&zYM8F8(BB^d*3Kl#C8#B`|zM;zoLeT2`_3=0iJlv?c(#d(j2$X3&7f`kd zz<8JE3e?^LeSFmbxLDwP;Rc8s=TB`E5|%iW)K2fO_jJKL0AUyoV&)jmI7uhyG$zL( znMVPNx_sD}u|B>b4-PF{L@J2k(|p2kcTPe_9NsCY9x+ma__F}ca1)aOyY9NAC53lS zm*HiwX+(9$qh~mjqX`0wpCy87k{mHP7PQm9r_YlUI~7n2&0!4b6C|tT*+U(2`;;bV zM+#q>5^GPidx|uQK$`%&{p1kMjIjGg^l}*R_V-ouz-f(m9wW&G<3JsU`c6%d0CKR? zcMW2x4q%oy%GfFN`hhLtp~N8%hafBtH7^zk>Ud(~xg`(67~Ux=zzwWj3oH;~P!Fag zj|KnsVQV;hxa%>^5u%_HfZ6VWqev}ypn4N&3ucT|6)cTYrFDU}MC1lgg>(9}W>-s^ zA7B<|>{^6>?q(<hu6*RWkC0Cs9MV_s2JZAUmq;Kn2pEB$Af69jLnFV0I}4Mg%8cL8 zlR_-q0@}7NwA^rbi%Nju9_F}Uae!2(2glzec4rg25FMMDT@paKgV(gvPvrh}Y3q)X zPgsCrq|2po?aeRP8Sp1U*znt-d_Kn5a0}Bp`j9B?m4cF+(*A<SG>FrVIY8cfh4JQt zhlN{5@A25}w9ZypI0t<NRAo8*>Z1GG$XIE`!Njtky9Q)i$zh6_?`g(!-~MoXRbbhr zOz<7>x&S`7QeXT8C`Q88`3Z*Dq$?QVmZ~^Fmpx1TGo$=u!hz01A{1*KJp`H}31m*W zfGG`@(D(AbAgCASQ_v<zj9c1APDTu`D~dj|t!m4~-WAub%AA;jAZ)Larx@F&`9b3} zEe&LI0`;`Hcd00*Jr?=YPz)89G%<{#y-Lo!tO=X3+t!+lCQS;mEU7q;R+=uENj)b< z4y3$;z}(<afw9o|uE_&#NA8<9MJoGX`4j&AD*w{hnUfmRzej*U0XJuz_G`%c(Ce8f z*gP<1FJXnCVRW>oV8uYF4TLoh0Z?zrrW{#w^02k%y4$RfIzkJW3vz?x0ig<*WHa-P zyGL^2UMK;|<KVMlw=6qCn?3l81S53nf37<F>ZbJLd~6RA*sz&_AL4gmYe4FEFw)%g z#?^x%{Di#}Z*DQEmaz$&Y33yz-&R-_J!><qM!64VSi?TON{-CEiVwaCHF2^$Hj^{# zP&HvdN_2eY4C!#+M;%Ym@`yG&>7RCeALiVpFiGtU)-(KQL>3>u&;yaA41!@5SCsQG zq#0*GDpNA_kgmVUnpD|yl{;}Ph3nuebQYe`a)R0Qicl*6X@#p+%~#1_F-AGZr6)at z<ZWSPE5oUYmYFx<4&uw$Rq&~++a^2JR?p7MLt1X5j`G;C&&3E%#F)pza%M?jY*I)_ zNM42;r~G~wtPAftGxH`U6;&aR6<>?9DA@03`D#VZ7PAYhZ*}-dPi(zoAis%`AQj~J zj5$Qt4;rj|^d@z~EET%ley{qgCvJS&BQ2-x&xF<t4|RAiy*2POQ#y!6SaQmGQB3Ph zjP}9O@r^vc4&>i(N%Z(<-?DMHvlmM9%qCxft_MzefI<E7d!Ca<dcV1GXLv`k1==l5 ztV-tYVVT?AXi2&Q9DS~G=xF$?X(o*LE0RsDcg>1qTLuK5SU0kN&_40=4NMpK93Eh} z%3Q^klCx3lF@g7(ZZ>soV%B9AIQ@bj%0x>xK&40<ua~eXQQK~fyQf;G<a@J-%CaBl zC_0jK(j>T7<8r7W`MBhSJ)95GZZ64=*&Ndlp<Kn=?P$kgOm+c4>6&|3l4hzJOKU&$ z?BXjU0M_@2P&Ow_WDZ)&PIXWtKo#$W-^)BdVwg=hZos6}m%7d1t+zJ1g}n5e8*~~a zDk~JuD31c2*L)@qbAiAJCK#U}mP6c1_-qRxf{SZJgBgUo0|k%bqzMVPi8*PGdaR1W zj+SLp#nvTToxYpnorQWUBi670aTaxpUd9#t_rRV>42p5Sxp2Ag8<%E9z!w@Mj3;Y{ zx#%YT6-~O9bN4Vr@a96uyX?%yoc3=D5>!=kDxZka&Ff<&J_+g?pH6JAMJ;l92m6m( z|EfI{<H$-Ce@f+I^4NMF=^X|U;#2zrse$t4uj^6T5y^Q=nkDy18_EL}?Wq5ntJ|}p z<9?FIMV?(YIIB{$5x#kg#N-Gm!NA%8jy(pfp@vD>MgNjYR4Hy`AXbd8wLPfZgL@9z z7|h*qB0i`$q_FTB1@{5_Ig}2gXY?lknLvfIb1CCC|D$?85XKe}?g$iNETCUm98H*4 zNt($>2(-|#{mC&^d`?Mphj?iSH6SvA*g=}TPSQ9bnqIw)ut338^uADnt%v3bI?gI% zZ<P%IuFVYIRw($8YogUXG?bg-j)DV*l(6z4gy9@gIi#WIo^l7f+?7Yy#<##M99l*K zF@Rl(;-A>Bpt!bIl^b5Y@Jo;o&dm#T*q;d9fCZEGjEW>3;Yc`QYEcw2v<!2$wV-W@ zMYjw7X8)>v*;sQ52LfTAaG@HXk5#N1yE1}!3tWJSxQy7c5!1>f799JTM)JiZWpJva zNO?u*HxP^%)^l@D@RvJRsZPsX@_JB1amemA6cf!oD{RF9K%Fcd268xv=3P-q$t#z9 zJhh6*Iv|ik3m=6s{PyrM(2Yf4OiV0!Luh`Swuc#Eq90W9P-X7XI*PL^kwRQ@(dI@_ z!T>+wVFSaQH?C!t=_^y=*$c<K&}ayTl^t#{Y#HD=P`juJ32HSY{_na9c%XL!kVTjY z>zn7QjAtQfXt^xxM`5subjx+LtkiJNna0fS94DKt6rAdyT56%}N??l^DsLEvCB&m0 zIw_T?3s&_X?^ch28)p0a{+zl#Kg6MpDhS0x$?nfS87#sR1^|ITvTOL_tiii0lU?&_ zX`skqGIH_rwr*6xSgxTSDcg&WTwA?$ve1ht5KxmCg8>2N1y%r(DNwbFjyTp)B|VO8 z(twFU(K~$;`5guS(|;}C!<uhcjxhW|MF|^NjHf#o%An#!W8`*$^Wh+*z{KqHU?Jr& z#8dV?ukiScj9(=G-Ozi0#6svko@Z7nUPGIWT$a@KLi?F7fl6bw;*VZ<Iz|WMtpl;; zFzmRh@!a+GpQz+|AFkO@nc673Ip@SclNcZgC^~ibVUB=O>Hg;}opW9NaRlRsew4Wh zofjtvmPl2t>a8NA6-uzDsc}*mIuzC+B_J6JREX=2t_I}gCnuU%N<3Zy>8r9RDK2#y zh?_p7JvxEJ6Nla4HLaOHTnVyn2B%dwu;B@`)`X)4VzY=ob_GFm0O%puy3~L4)8ka6 zrYY)V;hNtH4*L|?*`GXM;>AhW+K}GPi8|YUn!!KXgWA$cB<mu%G<@rC$(t8EQ5yRC z23c4?fz@Fe)0BY?<griBGI5x{_A9^5?~`IlrQsmiI_O(^;QG4EB^NP@4}2DaC2g1+ zGQU|56Z~E2rljDaL-MsAlVAaA@4E3#Hw#^$AwYXhFV^ViW#!{BX~Cq+h-<gt9=lK_ zgCmqFPIme&rES_bOw19lCW8qYXcH6Jn8Uu|p{tYKykorWMhSC>ck0B3%TFQC1W`{T z6rEWRR@}tAqCKlA@FqniXk%B!lBa<9Sve*6O+YE*|8e5s@xO2cmEy%G@jN&v3|$&t zYqo0s!7feyT}c&cubyEa6o3aM+tfaS%_)XA9Un^p(VsohBv?1uc_4Z#+j=qhiG$ao ze;6~He%MmVzkR4i|6esG>=z>ZswY<9IAinQxPNb%y4=u+ax$o9eI&L<apHZe8@cB& z=x%dEn#05mGw<dohX2COORrZTH5)5zvq+c=M(T4h{>ucG{a2$O`@R%`d6z;NuS5H) zN=$!Wo;BOC^nzmb*YCdyp2BWnSFvcK6u$#Ol|5^PBc{+{pxOFk#XB9opp+YZ$gt&* z{Fia=sjq@H{H$`af3U>&jJF$DhSL2C|HUW_tpUOE(!q^i6*8<Ndu-EaQ?Y(a<cAcg z;e0h;t4GzLzThOtD#V<UD}xuDhaxdo3Wsj1^g~pvadlkl|NelRd2jY6H9Hj5SRgu% zPV7Qp%TPnR9hgre^0r25;(BvF+*s7iIZaNt!Ouf))a{4Yz|K*pj10W8`@6?gFf?eG zvwF?beB-Z&9NY=s;za;QC`Mh#%x$KmhmUwb=ph)`mH5|>M8k%ILxzC5$;j}YMzU>~ zVDdTdiUwHmQX0$l7$y>hfvVCg+;u|DXdFj5Rz5tjILXxs^N=#l4i}Y^hS-q24lgAw zypD_l=2Xt2$+}aAf66j;>WLl>5W5zoCC`4U4x$WTt_6|Hw$twV<J#7`3C^M9K!o=J z4FsJMZ-)EfP+*k=bG9fyqJepX6YyZ6@4*2R$_oGaF`=Kr%r`~2M}vaduKno4J|xbg z{eKb#)5J{JXIexGfcg+ES1pEiSiM>VnRe%ss1b*uzY|JDqc&o?Dt@8Nlb|J-7O2<^ z4!=25OqLb8P$@e#dFd!Mf%HN%3eh>4lJa7ne3drOSpX7oOX!}3_Xwd|Rv*QF&+cJ% zwk)r629*=U_6|C*UBHkm*k>Ti&y0Y_kk$AL%%$Yo#`r1jWT!96BzYQ&aQNY&BiWB( zAl%KU-gN_^0p6TLka#q#kgUX_vW0~jiGo1x=PGq^9K{5JHMbZq5skrc^>N_Fs>f~_ z3ezeyqA^~LVEs;rqrS$GRPqM#cy-h^&l+1LQZKW@7^GjoB09A?V<NUD&^$us&|*V1 zrEyfqeH4|xp6Gs~hhaf1I6)>Om<9R{Aur~UL%J8D0SC~kaUrF=ObO&{C^e#Br*#GS zMuP*DM^8^Zn^JQgqgt10q%gTE!#{emjjb|}yarznc>KGnl*s+?8C4I)RNqmMpJHG* z1Qd##jkYBF96U4+DMehPHcaYQ?B{`4k5Zl;ngkHvmYDmx;*;1@Dt?*G!8lkg&~>aq zj9h#VG?qlRgG9_nt%eXcc+C~bgWE90>;oB{gQx1S#JasPIJ0qb$5M6f3>mV8FfmYH zg`P4zw~6qe_7?X^^L{*+kleYsj$53s`;kQvAVY^0$2F>`Qa7Vo2fjw5LFl4Lv*L$> zNTa9^(_$<v!dzB`uQii6Vc;pdG(^|+88HHb(Kv&zhHUD4G2IrOTrpl=T4MT|8ECQ` zc&Gszw$nzDko$}z1l0Ud{j`?%98(3`{tKvylxwVDqy|`<cf$o%)k@oVB;ELcxE3;e zBMPJjge?a@x15?)KgbxL#tr3s4Q9T|F4GISXy$GQ9T~hwi$4`_{*Q_2b|~y2sEb)V zq-|%vbL!X?^|n3cAf7H7ZJjtAFJP>UD(Q=!PDQqfH$t-HIbl)VM*d8kFob$i$)Mga zbEYiI>^<u&d;J|cbV%feui01<NWDLIyzQq)mpT#t^@S-qE`LZy-r$KKs1jIvIzG2@ zRp#qA$V2~CTfU1l9gEXQWv+jK{rAo!a~98=xdWq;M?kD#%46NdEgMHhECsYDV4n)i z{|xvne3{3~7koI;%!#0CAM{FYLMVBTu>EZp0D~$e9-NyahN`o{FD)&AQaLL3OjOX- z9hdN$0x3ut+OL#Gd4!Cccq*IP$sB?>S*6&dCFlMF&UHW38B|E`p(Ej)e|g~yWvYoQ z&H<M~UCXIgO4hdppbgiAzl;(HCYq&QwhF1;#vzNPi}f-bk}`63x)>>aSDxL^IdAN( zPQ|&2f&j9!Fbp7Gcosttb+q>EK21a7-wec!4)L$ST;&pzI$JX3!BDMmWxXn)I;A-k z>I#|?$AOFq9vT1~{z6?Du>2W_IqAqgMNH+kow~JSx#IqFF}g#0AjV=$BhTq=W4`%r zYUXV1C^t=a_LjePNcAsk%g1XiiG%bBkKU^cYIs@Z?CDWDUsRfAZvgBI_p~t3IOzBL zA4Khu@+Unq9`pv2&mD#=Y2B!<#qlHT!jiK!i(+0ny%v5H-;I<rFj+SnJEj45;OG5v z=##_KHxXL3$G%TR9|ZEH$)-Eodo?KEz6j@Pb{ttfO4apc)l|H5<+Y7GaK3qZ<Zq_= z;!T0vr<cUVXB}E|n-8ke#8>SM>g6Ms=^)G0=^yf^gw3uKpM9T7l`wBa?t=@k;$YG( z6%FPtwkUrpT=G#x`kO;15~h=bdNAb;&6hXzisbuaPshHKd<Rhjytt2ax1;-%F8{tP zjiD#|C>x7vXpt&<9WMas%_B9R7+3hN8fLGlnLjM}I6U@kS`*_vfbte}^(rM5o1z40 z=;mK{K_>)M4INL(V4|8Gns^N77B`O#Vxvh`LcQr8#1<sb^#G*Ji3GOY;qu3mK;oXC zH!j*qHxPY`%gzJ_O>4;U6q!ShLQv~b0N+?iFgL{~6H2NY!)}!}rg<cQUGy|N<AU1U zkM(dbfv4-+l}^l@c{-b;X|SVWAh<ZnS9upfF`T`B&8!jpa5COfhTs?j&aphqXYq%F zuPnpcVUVoc?h{Z1Pdqe3sxZ#i?$mJ9$Levzca?slL{yV~Nd6tSp_L8%VzZ(*V0QI( zYMTp`M!1^SH`wRi_?$=pMy}emn~a)c%btJp^?yyO+ZN^iqyt%0U>(Ru<AVJU{sJUp z5cb20_0AD*TcuB2?H;=9-T+~yd8}(m(Rdx-kdMlo7?dG?U@{_Vu&<lZi37LoRU;|p zw^Lv3Tv10wPQ5t~h2zB2j3A=nRzb<|a6$PSCXxo(0}{nNZ^5((pPYkPNkV;9PYAsU zm~TPYNz8vY6U(V8$soHoTMgDGm{x(filQx~h4eJzKyR7~14M!5Ei72o;r7YL=u1`$ z5yzobK`h%$NvoIC=N3dT+=e=nNmz~Kbo(=5p6(pS0{RAk-Z=Tmp$5KGpmu_dHW^HU zxd@ong@L|8O+;FvbVtoWd|pz%*|WP2%MXPQ+X`@S9|%@5s2X7-N!QV}^DK{Vkg0gi zr}Qw0*d7E66}%%2a`{hoo34Q{T#$zM6X9+tke_wJAMq1Vicyl0ycwdq<p2U8{q{LA zAoCKeY~VaP;I4xTgHvkPz`VHT9_%&ba?O^{;D!VF5Q$Qtm6<Z9A=5ysSqM6JirjU! zCj(W@E?aO%SE9zqM7&B$)cL#)Qo<Q{7l5ord9YJG*fxRP;{YXRoD`$F8JMmL$6&1X zRsdYKd_nwE9(QxV^7~AqZJK618FWZ=(c{3UUCF>MY+KtgCSTEc_$FOF$dU&(04~ja zDo#6mz;96)>nrA3Pj=|G2@@khpze=f%Y?0~3pHN)<G@1D+J>8O|8PLkkE;ThM)Da_ zco$#r@7qmXF6=>zAHA&$Uq4Ly@rk^FI~SzSqEsL2k8L%f=jX%UA17t2G!Aw;`38Kr zf`Q6{`}5FF<XhDBVJuf%H3_dC4BbKj>Y>)?8;i>iw5Q+!%0<)gO@4w%m+c0hIyBzd zRkBp0v6z3=h`w6#+@U0B*}Hn7q979e+B6u$1_BjB2L)aSlTCki9Fp{4q9bL7nz#Ql zyNDn*!&ENZgd2I6&$YET93n(}*Fb<f2xkaYuQP^NXaqr=2UcVRTA>r<HH3%EL@d?h zU~&_>GhD^80wxG|cm#0d5s=rMG4zTnI*4ryo5CCZWuyt&D}Xpu*>3cm!#C3sbWDnP zDll5+yM|&mhmG9hP~L-~tE4L}tIQAA0Kz_#5S;mPNwWJbXeO(`^obw%1^$7>Wi>D} znE)^J1iq<skmm=*&d4+p2NP3Qzb_kn2PEF~+e-zTAcbi+>$ckKJl1<L{ym3n3Ri#u zk9|Ja++oEFx_{2sy_P8g{13pVY1&Eld0*Vb<HB(243f<eIku>Wn-0(*wmEbT1s-Mf zA>7PaBY)tf&Q{iYK7$1Vzt*w0`AuHx|1!=E@J`)hI3fRIg)OqI^o|&FUAe4QR&R{K zg^8BeLk?wR6nx@Z8rSq<$3i5sfL$RVX4u%+!3IBzJA!CT5jfM`@NE`LkVwN>B%y3& zoHW!`@+*=y-Z^m|=KmC|*W-YNHEdM6XGg65@;XPf6CIX7btxI5$zz?-9vRqB3yMl3 z!aaCPeC-60IcUfZYPZy3COtAdpm~Z`diTayyYuP4M_411DbVPlmEPg;T!~3+_Wdf~ zR<C)okKcBE7F4tCMYD5L;KT=9PFi>~J!E<fPR&HA-<X-W=Ehk3!{wc|RGufZR~T`` zV6L1~122bw@&3QrEB9a8^wrm!%*Y=1$Fi%=n|Vt&8oBy&HtChIRPbP;ZpFJN{haL| z&||1*H-qC>-3lBt#fd))ebO{dw-Yf5MlSuyIimfh?A;a9>yoJ>_9J3Q3cG}UtD_<m zyr16(^4-T;D5U21qJF|IVk)=$WyA?J&f)wIsq2-Gj~1Ww8N+-OB&|u|xnG7P8_m`g z9h!hF866!hwrIPaWO#%9@T5Sj@xCErR`Pgcq)Gi|Th#sWI&Bc*a76B=&Gtr_jIVpQ ztm^H@-X|Sp3>7OcH(6GWYYlgrxzsJ?ZpGVjbYW^F?}49;4PyK6Bp}d$6&C!p9Mdi( zENr?gTm$(}>L;+RjzTFREV${3u#F)Y^_TBKO@7|Eeu**jZQiu=O--H#ATA(dcmk^F z7^W$=uV}Fs(g{}11c}B(O$5U&epQZ>Jj_#r{Erp-(lAi}>wwDu@4SZ^!C5h<Fb?r- zqg(_+>BMu;5tSCE^Ig%j#KGN0V9meKl^jRM*!LO^8k9Am9-nETj4nsqBL0eZvX5Dq zeI#Z70~iXQmXzijEO(gDYZ2g(+hnq|_Kn{(v?ll$uNj(PuRyE%$w(%?G|cX0hmfK% zYIvG#<e*(}f`Hi(e>YKy=IEUvknsRMEha!ynUS*RARt;2&G4DK#P}$X;qDDp)9^Q- z6cfI(Iy^2aFA?b-ZX%0~sY$?2U`(2aVHx<Ltp6WeKqC=g#)YzSk9rI}xz9CLLm|rq z7dDW{zv#dsF`)x798WOlJMh%|GprE5iA6;EM-VX+`OI!(2Lk)!!2rvH*S8+7M%fEE zTov6s=<rnl=w&!hWyVNJp^t*V^E3k=?csK8v1*GLfIXqywhJpG1i0`C*Fj}*mIgTL z;QG|-rExpq3a6uHqY})4yH1Q6;4Cl!CUO5Ye9R{Fs**saNB4pc8`mN(86+)`1v*K? z7=XJ|8bLErWAre<A%UMgj_(v|qQQ6zk0F4_SPssaq6beXmj^~6`ElW%|7>O_nr_rW z@CIdFiFz9N9e`J*gCGyCgQZ4-)Nmd&2CzyakXTv*9meD&inX~QE3*b%ZjfAa>ho+s zzw{J3%W#93Djggngo89+b1dSOW(eGb`9p@zk&+vi2OD}a_#BMDs{DSm(ZMdOSL0-7 zaU4`808pKyw1fImI~bFFl4VbN(ia=@Fv?M)g!vMTE}&q;6Ln?~GmZ2N28h5Su=0JE zDFZgCS<@=qCvO->yN`Um9y31BoNQe?srkEi{Os|Ee*f&F^QS*mMbNw9f8KvNF>jz| zh2mP^A$Ipq!IoMySh&uF4+=h3ei~Gx$r)j-KOOD(G~Qpz4z+kXHu`wm_?ec=bnRm{ z=+OfK44QQj-nAIHrJoBFiLHw4BwEi%YW$YFtT8a$d%W^$?ET=4$!h=_pjD>q{h6eS zGi=4}n^zZoI0(-dFsh3ybqr>X<;o|}n?^cL`p|5X7Z3KiiX$qnebf88QOah+<7KEc z?jJ?`2#%?ou$O(PPul?nsL&B7sq&zvtp1IY^MDPXYR$$Zh;Ok`ko;Zqh!-Kv-wrqk z9$JOBF(m{Q&y;Ayb&cOJNfq&hKEpiM|NC5;;vMa*q;)FzIA324#tr8+N<(4b2JwFz zF)joL0!s5h#g?o*L%HcAxVLn;-?kyPNH9C@E5AmSyxC41Y3n?12X*Jy-G|zOq58AS z;l@|5W8RhNJPfi-X2%c>GoIaO@3$zGU_ylSWH5^_^r9TCDpxM*!GZa+h2ICRbPz=Q zetEd-_zKyf?H?C<BD2^Ic!|u7=0UB7OK(9;Cmne8tJit<6p}y`#=Y5#GufY*eq$GV z*JlOXvb_D?k3eF|?R&73iESkfjhqziV^BDoDN|a(oonD?@RZ8iz4t1cZ(h3G_lEx^ z@)(l%uZh8UQ?)?+RqO9-j~>G}QY83Ag7r=Q<UZWMVNk%PZ(^AAi73M>hW4%Ji@@hX z9`4ZbyO;UQ_us?5En>omKlA7WUH@ShJgouQv`7+=PVdS^<gha0DvR?@L7ia%zc+I9 zI7y*SzBiB_q4FMew3`>Amz@#U^)%gv8om|*0Pgt_OAyGt=Rb6X9LN!ubQ@FSoEk|h z{0GDQL+Kms`rzW7JUeK(RI8bs!d6D5bMxPU7f`P%;Xu7mxk<ywf@85{HJYxPSa2!_ zvz<iMi99>=Y0jSA593E5CB>`{hR!B<gAJ@V<YZ!x!}JtjJNipO9YeRh;SvvfQM#vK zXb3n}&8&g!@DXpF_E(nsCx$D@P|r(x3;;%V0r}LljfrAQ`JV<IJM8_{>xgNftc5%a z`Ol}>ruY5djtW0Syt6Lsf645#L7QZZF{69u*oW)p=i}ybby||lL21KAxn%HY&tZ3? zg%6SPK$KT)_D=J|ym#!2?zghm#JxP+C24vbq3AvFzcDo71m-!4r}}GF6roqX5X`_V zi05M_W`g$xiA4*7tWBHtJ$ShF6JIa|X*e=qx`E@c&bKeQd+~=TBFI#xv?aEzzWNX? z6rB6L*ZjVkSsC3t5r{HBIX`mWn`p-eUE}7>v{7-cLdL22p`|qSzG;wF_Zxd%lvnyO z&xe#cX`-h*`)&W!QLvDb!Y4|=cjMd5{vO}?lKRWqCM2<V<Lg@4=LRmel+(6l!P{S6 zIcbK8FH<G+hMej7-V6<x`Y=b^7f?gpUS`ltx#nC`(8QJt=IRL)es3_5x}2P;Jg)fq zz{YKG;Y4H#_t;ST4Z8?B89?F@yV5hbu$F;o-9e18{~cs=zHJzN*GETlp|D1Lml~?U z6OLh+y?-%Kt(A2Bl|J*&qY^N@xk8AT*Ps2%F?t{TwaBS-5%|-nNjYpDiRpsK;_|jA zz23SaZ?p|b`^>{P@Zn1_EXL7=N+!EggocyH1GeN-WM9P~`&4pcm)B_zLQPx=H>k4u z!y)LsRYJ`SJ<=kmRCJgCf!?d8Id&B;IL$Wa%FohMYGRFio<xx<2QFn0{nR-l)B$J! zC=5wBDoo==GzdTW{RHJ9yp`z_mlul>V1WL=1ye~5y<FxAH9a0Q`P38Wq=w{<kO`dg z_U)EHBZy8m_-<JQqx;XZgylwR=%PYkt-vKZo5(?9I1iN;&Rh#_H8!Yd4v@8Wm>T>> z4u)G|%DAwP-nVDrIXN2fw&(_6XQjQdP}2o{cW#hA3Io<kr*ODaV+@&W$seay%mO}u zKg?l7;hl>S|GE8&er0nWR)fy+7bN|41%89U8*%|M8Q8t#i=q8P%L|&J^p99b%?u~x z^&9|T1TY3baSGv-C9Aw;aD^D2Rcpn7dj3Hv$GFkBCbty0^?0N~U!tBChN_SIIZ9t_ z@;p815J{BO`PIDhV6Z$H(lqN&pU;#?aD1R`gMncQ=vbqf?vGb(KNKmifG&}9YCRr9 zD?IFR27>ynhoB4`I)Sbo<jhhAfci$@aTlZjO1~6+b2fVQDE#WFJO^Hi&DIsfZwP&( zTx4rh=xXI4myH@KEqHioteu`biw`h;w4t2szj=BwRZvOFU9xfh1`dCMUdu*M)*7eq z^XXtTDE?I&VR*F&Hk`|o<py@2EM%Wiu2t4yO2+udlk7oNL!UOtPuaKk-LnHHbq+5T zAZqkXn7DM8$EJ^aoG%&qfa-w<2TPj9faFNp=eKTw5M}^!Rq=_HtzQ}4e-$NsRjJMI zSRL}3j${&(oNt)*z?Q>Wj=s-Kcx_~$sO)r;=4Mp6#o;f6mgq#|cnJkxMmzCYaA3yE z)?)u`IB`HmSA1d!^Lg<7$Xe3E{uz$f6~O|bxu<A&-N5>CT-Ayh)n_&s7w>p@Pk2Q@ zRR&_el@3*3Npm<T@n%3>twQK!^{3ecva`_fw7McaNXKLxCK+u9O)?zwmB<_}wH)69 z3B?GYW@;+jTaj{N@-64?g}#?Ob}7N$o6%94hVrhV;I=Of?W$5@1}x^zs?r5yvoZmS zinhBa{dU4H6xkC#>y0a1cm0z1R<1m(6AZ^d84$*5Vo;LNgy1j*)Ub*@i$j96$5gW5 z*0vwBvsm#@VC;`e-FCx%Bnwdwovc@l)VNWV+ne(C?cSP!|54umBl9z75@A4}3$3)| zgMYlp9yw+bI^uVV|6pa3wgG<e1j7|xQet9MhoL``y+8VWc_ySgZ}nnoyg~~tsn;Rx zzs@#0Id*!X2^yFJuFL&3-NCWxWo0sTU6g1z+Pyt4`Z8)9CJk-=Nx8r4usw%ic-^r0 zK>}(VH~@p5>!5K!_0=KJvSA1~+?=+xOss@2c!op9Q7sUP;O&dn*r|KaeZW}+EQ?IQ zEdlcvgC`uWZ+_}?)x<g$Tw+#Z^fD-Ac=8?u#?pE46m&B%+ZIB;=xqqGx%^Hh5L)z8 z_pDwtfV&MVjT4fQTI6u&;zZDxgO3zMgv>V}aw6GP0>wXpHXWFLS@`jU(iO+DI9w=X z!WKTtk_-lsX5XGt^r!}dU^jD?@aI~UBj<3&D0=6GGEL6|?4J*i0lJN5y^PbBu2CMY zIpH&27i5{l!~18LeDFKXzFX2EE^UhX0rSrQM|U`(h{vYHSQ8^<aglc?AgTP`k7sB< z9u3|Ue$G<1SX_0QITcJ9HEvmxy!wt1cZwI6mMA?l7BQVPZuU1i$4%_AmuL!=Rl-X8 zU$yT%1}K03t9Ef8p#JPy>r}Qz2RbB<e&)0<O}3l57<`)9aWsm)aH{B-uTVR#E%=<} z8Ylp#(R8lEA>3}I9cm+ch`p9rmK_P13?k~(^U}UAZuMEyW&^TjCr~`L|76{+&Yu|v zGc4-M@jKId+oCirlYdG3G5ZHl_u^~8GFdg39G=+`iKYg!XP@sX-qmelM}RA|>bqNf zqghdiKa~PNfuR#~Dk@A7f7H^AGF|>hrlTX?Q=2z37EUA{3SWxrh?9GWne&GBEo(h^ zvn8FU;znvGjJ|x`-NWHdg&zQ0%dLlVd7;)GmCaw>&1VTNfW1j7VUhqbHzw%92!qDC za4Ic;z%LeoV@}5?P=Oid>^|FwsVaSY)+{m10Z8m_7`+k=ai?7x&D&b|La0eGLG&|7 zV~xlhpQjmD)B*ieRe91v)N#Hu=Yo7}$zSXMS>vYbyce@<<u^B@MN^6GQT7wtSm+*a zDW*T5RkZGppTUuZt?|?N=b9V$s*py|z8v;^WjTzq66+V>cD_o`-9Y~MYKS5~i-VBI z_g4{8eE;gEUc!UPiEDw@o)nzB&fzgZwuMGD;_h)$rFp@44sjUcQ!%59+Xq`z$f=-j zQsYJ?pq5EXG#GQmo2^v4h296OJCRy;f>i*3<Qziy@HGZ3v?bv7nUW48+M%Zm;0LBL zcMnWnFO;>i%91{oie8N{DmlD`fCGp_Zl{3#DpOPwQl4;9V8@Zcf{Q&I$6hs3$lT-+ zah|e~c)J2~Ujb`7;<i-}h!h}3KH?c%g3uz)#L-xPOM8{}B%&lK_^fGDKa%N`ufUBq zNU1?Pna83)jy!~eVH3$dI_u~ucNE@EID!h$XGxgnuQ-Un4=vNS#<he{4*DueIU=$J zN}rvF6VCn6{D*v){Q9s9^8rM{Y>=?#D92HNbilgL7d&@>G3cT%c$$sfkI7?%CkHXT zCj5Ya=e*}#Q3j~LMBzFqg_0C+#1M9WG;kQ2shDidUPVVefV1Tk!O$AzTk089=*I(= zgH3x6FV90?T>~kQzU~1y;UV?M;Cf7?C)bvx=v;6Q6d5`w{G4sPUsq#5OpFi7^K!z2 zcee#L74uFqU@J`!be$i8k06jQwZ1s}?fBtn7dP34Z0tGykgCe;!;v~|RPC140sgWj z0At!jpU1;F-E8aBd>c!!9ujYKf9yUYdpco2Qi1+IdG6*}*`^1i-29(wHh4Y@(GC%j z`xZffQOAGeBnnq@iFot_KiSXNroa+WZ6>iL(xdxm8iiv&q9^l%(1@C!xN6h+etKib z@M<1HI8dE_EQDM};r)yJDkMY<ZSciF#U;K*@QYIXQK8Wx=2>k;@C;PUZRtAa>@A!S zX(KOfa(J7x*1U7w$?r}EwNoY2Ol=4liKWoqy)wicX`reU_2ATwf8&@BI;U7NoKZUd zxgWs^sCa3i?3kOLUf=n&-->B62$6_@q(HLOY*|587!ngsh2{rO%%U)5@&V0<y4?$p zeTNxz3|))*eT_#)tUXhmeHl6e(8QEpb$zb<qmKm1dcdW&6g`=`ZZJ3dmS+)XmJVi! zpNRR-vnczhyDwYIFFZw0D0?H6zA!A91J}-V8;!4xcER-XbXgc*al7o2L-aO1p6$dx zLh3jwISJBHx3BzO(~(XPY|5+U_&$cgxEzQ^X9#V1ZraDXu=+5=!XzYck;R)YFW&v( zDT@+Yk|uMj;xUkiB%V<gTbyhL<BGGMga0wa&)O^y^HP|vc3~t1+A(tk*-;i>@jRH| zWSemM-7bt;-1C1p$a3g9R#-}yM~jh0h^o>+N4o`RTMh8Cz=&{?RjR87T`|AJBIo`3 zlG~7-!PlAhL&7YM2_R3nqGpSLg_?0n7M1;mF#{|MN23D>m1=Zn`V0iw!`IYbQdQQ~ z=;#UM6JV}5sOn!b5Eli@f1jX+Jr252iXFmq`maHH0Hsbp%2Gw?J?b#cR1)~o12XTw z`8cBrTX2C(d0?+0qvg&*<2Pz(h%g@&*TmLQ+ep+%n7>EnZNd{WQneR+&CW#m=SR|= zIY1Mucum+p9E)DyZGa_uUuX=J|3&HehXMBW4_ULfN1wE2O5Vy`(|khU@uT?6kMXT` zM5E9WYLH-Ek-3FD;8qKneWu5=N6&e$(C@pbg^C+xC1=g)L4}MBH?AXt=wT>t(T4v_ zw9G0yKKZlIGk!M?JB6(HZ=q*t`zHU>Y{E`HI$RgEMyy!c?S5%mu|&D!9-Mw+0-y7M zf1}&`Q-^3nDwqbuJU?0A)PFHO;SEe;MmA9=-eWRC$(q^gV<&B9e}!^;dU<UK7>yn2 zprHUgAyCiBw$$#D%`-Su$Z@l_|LohEvWd4~bxk}kUAZ?_YBhdx`e<wQJj^)NPX0wV zu!~du-N<8m19%3$j>D;Hp}5c*wPX6+!PEbbr85tRy4?OhDCE|SP}Fb5;*B8?74JoJ zL1ZAcaRzAsQPf0A<q~Qc1mPGkhLuYRF>IH-GK4JRMlO}2K`u1{-cUeM6Hx)#6l77h znd$d>=KlUF6=pum^PK0L_j#Z9`{CcZ%i%;YTjMcU*f{y|zJhJqt7T8CW$(wb1E=to zuy{J~-$p0LUZdjkj^ggv9nZE3^;h-#JTl{{s^rS!TPxXfB^yqJnjEU0iFP5G+%%h6 zVP1^p6oSX?{nqMPbk+SLaa1#6cKE){*4*U!8kAS;cQ@W%Oue+jLG&>HoVwpdAyi|6 zW!<Q-@33;)8z$FJGy~zS$e@w)E7pU@|M*?%c9Ygyd&j=xrMjz{o8V7kHJq`t|E2-2 zX?PlS;objt4hnx~H4s;!;S_;CJ1olH!SE>G!4S<E8S|(9t)3@O08%nUM|g%LfAf|P z#Q`CN4c1aMF2CT+_2i1}GeszhPF5z(!_jIjlT|%`e48YwN+`n#6KOECp$hsr$y^Z& zZ|9U`LEEOQE9)T@SS_?Wj=Z_v3d%Y&(Sx6flvnBQkv)$u0V-x<32G5vTmUgE%Lya1 zSvYH%b<=~W-rWc&Cv>D~e5uk&5LDh4us111bLAois%b#Gv5|tsNL=OYUKfDLJfd)b zWDirxt!Ad#W%{|ho5W^AzJg+gIkGC_#-i~w)-a*f2=c#~T=0&0DB0A*$(49&G%}8@ z&GfcrXOc2QJZH{~pFyQ&s2I%^^9@2GyXTMHP}hu$49%iECt`TN><5}>Ga$rB`zZqv zj0-7y>^}mrNOBM^A!ekp3vv|W%JdQ*1&xm%q8O@SP5g(O#X(P;!r7EgO^5h9ZRX<f zOo_vCNEO1W5Gd&1#{eo7Uo9*_gB^;U{H*}VXYI3<^y(P}nU6dfB%qZ-{<6Myf)40S z&#UGrI4DR6*)ba!HJcHf+J*Wb1X#cd$#@9i_G{S?qlRz^5|5!(JShq!Lx}qh2QmHE zW9M_yLyOX#G&}Jl_alq}4?nXthFDr(2k1%Y6oZoWwPZ3+4qzg7&6`gC5=iFa@Vaqr zmD~<kzug31GU!c4mMA9(L_u}_1R!FtC6J!nk)97e(T&P#5<>1(itP7XRN1m2xa-Fb z5A1xhX6sP08|Uexpb4!#@fnn$vfJuNq)s-bePUh}QMxhndY#{)ZLyWRKtnfNa(Et6 zr){o_&+GW~yS{&30OjX&t8;t(ljIpox9r(&Ycb?^SB-wl;Sa^Q)uZ5JtGVCvy{@kv zdua}n^amWpV=8}k(a~+gf8VRMzo~e9x@`ArQ*N8!nbm84PqrY@z?k}<dD$Vc7Y`Sm zEuNk9u;bz6+xjv`M9@#?);-)RW+tb7skwPjGlqoh=#l3iBwWwFP@sS31bTC(35tT4 zTAxPWF^pJu*ZqMmWl&1JXh3LkgB%@|5sq!OH=iJCG$0uBYm9Yx*QwcwA)Xb3NmhW1 zJldvX(?ab+7a3288R)fv7pCH%b!X5)R_>`juOX>*Mk_$T_$~RWQNQh5DJw}L48+>T zypY~K%`my2lQ9L`qR2Yu;&%7VbE~9W^5K0`e^2Ncqj0~SMQyPiO<(E}nC<B2{9?a6 zqtP+fW9kG$*s4ADSxz>A*t9aTSEKmQ#%y_6B1?IX@%ZO=Jxh|LWmvw3XD*JsHrav1 zs6Y-kh56N&h4A%}{M^rPQN^xNGArT+08B#>B%|oj%TT~PD{#g*Y<E$dgud8PjsuB9 zqa4ZUpeWh$t3t!X?(IFz)i=xtb*p^?%F(R;z`T#yb#f{G&CCj=3TVCv0wVt3TwSdK zO;VU~EOoigM=0Apaf<^MY;O5^gp^pH#nC$EyDaX~BzHU5>oQJ5QAz4t^uf54Ah?xF z%-64Rb<H^ZaKhCheYxWytPEX!7w)`YczLVMw&2U(%5%#-duSh$3M6E1bG{t4ZU3d` zsr7f{@5chIC6!I}vK=t~W%i(J_mmq)9dRsU3?}{A)?ILf_K&l3tyVpj7;m!EQZB#* z2bj>DN^idA)aCGj?lpme9u-x}rnZvH--1!|=Q@u;<wfaFKkxc+^ATU)bMpHd90(X0 zP-_t%@?F!Q`)sqY>&_4y<g;^ivZDW_CzVJ~Zo;CgousAdnfAr<4U$xytpk%hNXj`7 zr*E!IOMp3EfAgzRDcgD<Bz)Oe8G3T_N_!~Ce=PmW>{C<EX`vyfENqN^n&<Y+FCWh= z?z;^O1680N(nP@+$%q+xvnawpgtqqDU+(R1N_f~Q^<t$-)C~n&CvWIJC5+L+sbkp+ zE&oZ+YOZT-&~@EjSEK6*X}@C=dEp39lVd6?y{fb0fpYS;kt?6Z^gYjfp89Jy1jrtb z*xB<)?(VHP>!>CK8%`b8$WDH}LvANvS~qdtv=-4vjHK?UklqX=sJR`rB!#m%K0?=A ztJW!V^MsoxiBPx@Wsi41e4inE(yJoE+GI0X@3hl`547axzsx={ghfUgh8|Oz&UlY8 z2x!ld{eJb+`eXe;hDERk|CyZ~_Dw>Vs&l`?P_zSxU3OS(f@kX0nh#NHgcE&ZfA&^{ zcH9-&b^SDXDY2@6JvY$#Jk!X-Vt7Jv*>+}@t%l8j$K7xV9VkDITpqY_B0^2DQhKFN z^2wA*_^1QSR`u#j5PA?o!)VB*3&)LX=A`+D^bGjo`J6n{xcb^i{<R=_kc7%<j)z$s zi3G?PPM|yyBD1?kc$Shwakn_<xo;AS)r&-)%|l)8StfuXgT4@1L>I)T46_T=6V28o zEhSjA<oi6LgtCoUk9YCLlxyac%o;5~hM=b}8zk<8FV>!e(dGTJ${xBeNA73HYtyCX zFu^4e7Qz`y(j=*|PVD@g(bB!zW<k+!LWj<HTO`(8-b`4}2=;{%s=AtGdhno4NBwpm zq=4PD6meP<w!?ft!GqG2#6L-|D=ZqI9epwsLh@rp;ylc>2vZ4RW=^QE^d!6Q5hXAZ zCmbui%m=1cZfh552IrcX5fM3(3l15;d-XC*W6iXK<CAAzWqQmlkDLXe8--aSqjL%g z`Ns0b247y2%Lor}H_&JnDTDB|kvE!**2<Tc!xKZAMYX?uOuGv8c6-eHiX|~KB<Z$M z{;w;CKR^?5H!ds{Nkm4zfhP<cu-8KP(bF6-nPZ2IJgZ(*v$3=^(Q2^GIWzRVZ4M8V zcOGv@er%6u+aHRjR*Cj@sX^Vdfi<QhRTZAuKkbRs>R$Wyn7&V6-C|ueoa`?D|E=fW zR{E8$`e^lU?G0mQ&zN>~U*G=$ZIWgvp{xtybd#6Mz><Q~#*k#;y?74cvVT46%iQf5 z^6<4)O}(>cO2vl$R%sWdeyWWKO!&)e`RN`}T{O2>D~J2(ubi!$zF}VFcQ1zjUg|io z^+-hTpgMe5X88D+)_h=8;E#!N=bcwTib7YY!v{h`cV4}{DOJZ4oRZqP@}uvc-W-?z zm)T;lcV5@jn?-?M6-$fWa=-huzdHP<&{+)FVPL!OsOsxcdLZY5^v87#FFxDquAD)5 znD$b~g;--~X3;9SJ@SRpnU%#}2fQBZZukAP>*}3?B1z3)Ofq+>(ga_7Rd?~p8_*^j zhhL-yM+ddO&bcV=mF)R{nMHbjGML_H6E<3wKC#^K^WMhn(QQWcZS{@1@c5^@R-Z`j z|CkX#W}c2OUr~Mh@xOWynjkt9q})95UB-p*Ti-t~c30fg+^qi0L0Wk<B>kg>E0sSC zI`sT;^abT+jvZCZTfVDk*F-FTjJoZ~#E*g#QI$CHXgMoKhq3ZFt6bD?C54X<j~j=I z{?&sRoI6eQ%>7$hl^gVnsX#gqih~w>lPAhk_k*O5BOcZ?a=<m`Tf^qCVCFbHQ#Mo* zZ)Q_IwXf<~+9c<vfi&Sws19>b*F8%{qZ8n^o7>9rek|Gu!n6+dibfGOVyp`uypqB$ zazC~!qa;B+8D4TP#l|#XPkQnl1w%PvI!_ExP`v<>or4F0STrKN?BPnq=+SKvMA>T# z_B2y%!$uV+>{!Pl>RH6A&7JJS#>2JG*{?xBQb_%|xNwS%4~mv~TiVc9c1J}@iyf4( za@>vHWHXLDBhNtBxV>cQo=1V#CXM}?Z?%(21ged?O`vRU<_djD#^L74IkkC7YWMlm zZW-;3wO-S4^@xfud-7?Du6b~Bpem*AtKYkID5frTIO<?o_CcssTu}AF<R>4m5#8IH zU<lNrVl<Wi6wBd)ifZF}`ar|?1K<5+wx~3z^I|7VaN`<D`t#&pL;rO1?Q)cN|K}-( zr?K8x9NyW!!9L*4tMQ+2J}!rERz62&tlxU{+f6@FiwgQmLCn=Z%U?KRrF~x#Wg3!| zCTXNzH({v1GyWgVGebY<A*P3@ihm3J;?CB~(wFLQRasb9IS=jm%j~Sv_UFlmbuptd zrLcxpUB8bL5Y<6**GIOx=HTBOZa*J>aG*c)Rrx}K;t|a}WAnDW=YN@nGs>E9aohfj zbL^+ogxADuUh0hI`DZ%Y^zK+JN+)$GG{n%SbzP4o^t4DGXCO6gICX5};E(MePX44x z?qxt-_s1Xiy@aCc(iWJUh=Bc9<DuE@(qOU#H{YYAo>`WgGwS-1i7PSBHtBlrZY?m! zOGZ>#O5|E$)Rbi8@*?xitT{RR8V0(licEy*wI6=EU8zre(v<&k^7*Z83a=Xi<2~19 z>r!(43Bgb<>1i+wJ(!L8S))l0TOj?xA!W%MH49eZ)Oe+lL|jYs@NEBR@aTu1{J~Ed zW*5y+*NKxO(W;Y`2L<~q(Z3*ibnh)THxscKiA!N-mMo_OqYrvzd|Vob(a{3gayXAT zRGiUQ@bkeA`rbo~4R^Le2%~dlgtrw!)^lDE)N!IXDH@+QbWZRo;75v|?{bx!X0~$1 z-k5F;)rOtc2$NS-=^2oXBw`3X1HheWRD;!3rprUjX0;IR*HvhwdQ!e+!Ujy`GiNj- z>3DPqwlun=iZx>=;0;e){Vu?177CiCfhIg(i3A$z=Cd{TagH4$fl=4twX}T<hdDxN zV&o`S9BCAH$cJeMUn=B=Y3+8on3G>P(bnT^WKx5nTbdjtW^}B}j4G@;o6sSX(u`K) z$Ze}GD{|DD9D_!T5yj?L2Yi7aYx<+jsvaCf&tn;R0)%noXq>xTFGrDB)!*2(ig#2H zZN7e9)8QWauYhwmm;$rd4@Iu>V3l|x=HU$HYN)K?NRa{g<!cmf=g)9HiE5%C-ShH` zMNP?97&rwR82&j)@xM6`g&LL3L!XXuq%lzr?-8F!QeMTs0LRVW>-AE=``MeM7;8n_ zn-+6x&X`R<ci*6?MN2&?af^IeAqU1n6c8z2J$W*V9TE;6c^N3d(&3$iil2UvZH|u} zKGTAP?A2aD_aWDq)>>wvv%8spWK$@au*%jxTz?AMr#`B5+rY>T_L&bNx;T!scx6#d z#fC1~_WI36#nW#R;<Rm~K`KWUXLgvXSJRT2qO5n1i|tmv^|Ukp`M7gu8nwfkl?%)E zM%zVMxi1)?lj+Wmz9$Qn#Qm$=cBpvYn=_>bd?~x6PYOFbzWn({_zq*I-0_&>Tkds5 zk=KSx)GxOF{F8C*$IN0fQe;#V{$)0L!yTRTtv9FEh;@csgl$aEq&?lfmp#U+KHgLV zW$+K0odR$!Muqo-C)+DJu4<8d#y5Mp>#XEoe~+Im@sd<Op(nLn3xr~uVi;2EoxVH9 zWW>ExI&<2di|5M}hQiagQw?qxw@Ewl(*JCe+Ih}Eug6e~lF4_n)jj3<$Ps;ac765Z zpyO~zo_%=tAbc68Rmm5<UM=nQ+~ZkBGOBY@7Ib(_1{L{}fty}B+6()?IDMqcvC@9A zw(p{NZr5XMPrN%Z^1IAkj@h~^^ofz~Ik~js_k_Q1TQ9Y`RsP1YQJs=v|Jt}&v7068 zjW-GzPHf5a)Slnot^H=5qjvSvt}ZXNn`%n0qfvTqWm?_)*?)_ds5c?}aA(DKVSh(f z8!jg3ll;<K|8t456817qUKOJq5Irdn<4B*?n8QZ|NI6cnvK*z5gb*KD*3uKhtw~GU zt=uybKcX~6v6It`xJUWbP+<Yu0qRt+yfMe3(Wt7vAo&(&@bczz%J!r^OqQ4_H+x1_ zJz`v#{oa;ZF1A2A$8~4x^f>0EOm@E=`Lp=kp0+d=C)-CLMzSpL&UgB%*gw#tCKC^4 z*!WK#ub{cA@fgtrD3n2!7o_o@%%jUla~w=V+t~UV#jrHY;apPIBjNwknLJ<z8~dOp z@gu^psi7U9TO4hpT&CHJ|1J&DgTm&<&V9#t^m>PcOOuIBGUg1>5)wU*!lZWG*8!M` z!TLBslPVYO5vZZ#mrE1>y(-?VYA6DoGP~FJL{K#ZUdKXOh&ssnsjGRgHq>GjE(e7L z5Z$;aF~!A=t%&+a9O|{}!Y2NG{pFa2$NDl(ssO}!2ZzZGda4tX^GnT)wcmB^h?zFd zcX)7SU+Ap<j8k;xIkBod46pq-{KnY=U2Ftp&z?uY5C6Nb?siL3>CXeo;VtF&e|hQR zrIkNux~_oMO#wq=9?CE|z~#&rzchBXP0{E~2Yg{cgB%5iGULVbIFCPBoul_lzH%;U z;p9N#aV-RBb$`z<2{#|kO^rXtQL}Ka4i%}npUj_T=U4l3=-Wn$mE-SpC^TcJShlYi zcxFNYQRm3F>zj<o<jU)@lEG6C`yaRD>fcW6G%ip(uAyBLP9G61j^Inu2?;NDlv%~h zJk@YVU|U$1;T1Gg6@O4hAAoqM?U?p;ckt(Z4HMUtM;u#)NeM}QlO{bSPS><7<K!Aa z4mxs}pK5Q|Cq4P$UuL^J|LeO%vtU@3+D~y&LldRDWH5s(yvfL`^jVY`h+2QOp)n76 z8{mMUim;{DGP_yKObvy1-&i$D=QOjsMqdV)C$n?^h;TVWIEcmAO|!9~Q3oTl3?Mom zz!QNaQ4Rgu3JHPRt&xbdTaZPbsTzz3`6~I5`d>Q#QA_fQZ#NnKBnk*6ZsTzhd)v3A zC+?eI0m013svA>KmMS%T($i7e{mo}_vo=IJGxlZQPs{Lzt}1Ag>byf)lG2f>qo)Zy zD)wkX_)}GSAc``OL;yhY-%X?kAqQU6dE2wc&*h@ZQ=`CANkf|Kzi}2SsK`{3ho+mF zyFHm~6{wU)M5eR@cyDnOP!zY3CpafrRO4OZ$UaUXJ$wcUXP#KJv<oyE;&O{XKFzkT zfugtFzt7xOLpR_AN8jusPJT`dwfM~|^l-E&i=hJm;DMNi%D6F2NQVQM(e{S8C1BRF z7+ZudhbzLw^PLJfRb~86q!<FvVx+V&Y0m`edo%h1WsHI6Q1{%U)gx-;G4=<0QCN?e zXtsz-R3kkr%X}xtQlm)a%s<p5DzQRn;N%_fD-meT4zE(85|;CVyuWq0n?y&P&VwLQ z?(<sB3<M8YIW@G&nt0`IJ4Tavi*#J>{UXls$?jSwcj3cT#Tb~KjoF|$($dQD?TC?x z&JrWnR@mbVhans<Y~Y2SRf+#d>E46HS8_p<{4DV?FU9i;Ua@Ay_dFOIGxqFm70o$< zQctoY&!RDHA)_clckX!l2DBS#!zF(1YWRjn*500{J_pJXV?XjbK-rXT%lus=TzH37 ztj)VMl=`4kYskF6;5CK=1U71TR5eRqzV5f9A?ghSZ#SYwdSO(i10AQ=<Tc^ipzB*a z&pIbs-BbUNy*6gU^Dl3_S6%vQ`%0i8!{ITA<0M~ga28S`)BZ5N@#t>hrEIrS&G4#h zIli1u@8yTq=JmE{6i3$Wn)>gQ>%G-AjfuRxMD0JsjTCbJEN@#AlzAuZWp$NmTKg@p zms*#%K9zggZ=`!QM}1`bANbjPHu3*@9cJ7fKv2=|jPj(?q|-RVQS*!RLFna~FE?!a z?&75<J#q_h3zBzL=AL64YGS@VGlc}xHoYzM6snB*4~s<&9)K}q#T$k{GvcQeE1imW zb+)iZ7$1V`dHG1_tV_nwe#lbPz}vbFcVyoiQmu_f<?D*>s)<Xt9^2aZEt$QtzRu>u z@yXewrkb215P-!<$wD+1j6J{1`tAaP0BXKN?6`gxYiD$cSg+y87WQ9TAZVb1Q6%d@ znNq?u0JG+yS+cApv;$D;&knICXFZ-LoYz|NWsLj5-S4!=A%NK*h}7H;oI8v{&;{<< zJL1yRh6{dJ_OXD#`|kzym7};3DLk=&7*zp-F;3<mb08vdEf_80j5{qF7MjEn9_VaN z<i+R2j&5fNdRd-k#|d$4CV4oT%r$(M*w`=^0gr%+cUEN%glB3PR{spkFP8+ugT)D6 zT3<7jkFf`_=_MkS_>ZU|G~Zc1wQoWc&l6tqT?$>xmjjfV-K}pxB(n38mId5MuD>?P zk?q!1KSQDkvatbtngJtA4bRaX9Qh-F#98qx5-%tVwia>+;|T>!hXZAE9J2W*ym!PJ zF%@=WnkvmE;#NDIG%!D;qaiG347@VDdegdb*$ezOb;kRmJel0zqtf^QF^YW$>e5vo z_oHpPCq0rb*Q28z&-@}T^80Owqz)&f#@gv2l1c9$D;8tPXkyoqkzbO2J=A~c*vbXJ z%;_Yb!K40O>GOeE!~P$H+PvpGuFFjqs3L<Vj!LN{rg;TKJzsdUPFSd7DqPfgY(ohN z-pZ{h;A}E6Lpblvsq|4(go162BJTGkz8$ap{pZvw-VGS&`Ed_*kN^9i>s3|ecE7ys zVSkyC|45&0r9Uz}=oCM5b4<kHK?V{Hrw_kcyo+(D@v0QzVSDVu4_7v?)oTa7d|Djx z)GPnFpQ1+S)u<lH^n6j3;ywaq?qw_DBJTff^5vT+*C6T1SBi8V$b4F}!`GoF`-bea zfA&Q<GmO{6x6;^$p^>)FvCF|VKKr0%{<O`^+SPy4#mt2ad^+h6q*mfs{>1grOhMro z6*=?bR~%JPY?8h<6XS=$f!wm61OXX@VB40B5h5TV3A-M}f927L;akLmu6q&PwHEP> zpZ-2tU*#^Xuge{%41aD%NB1NP_@;cV<<SJuK06|qzL{vD9Nbo-oOy}aMyw+sI5A3d zN0$kJYzR@p!F4u%bGVec@;FEKe8+6{a6h(pB}aBYpnYd*@>LP`-8^<)En@hfvwhhY z>RDA9rMsMzT+ntL`u<?41LE|evU#X6*=VTkyCQ1A7nqaYt^cJ@W?x~J8qQ8ckp-Lx z_efkDrG&Yb{C9f<+)AQUqxjraJ*z*;e<ay5k6;m353QTky~mM50G1NOYlJs|&~oQX z)ex`FwvPC5x+ru7Szok=7rK}=pq)!`oUI;mJJ^7l84n}CZpDrt7!h<yVeJPq+S}Pa zm(w87;u8`?M^iruD^jM=JVaLpD0FGNU!N?diGYa0Hlmo!okb36*tyc?>_K?J_)rSk zQi?9{hWa61U1ymY!ip2R*E1k1A$nCZ=8U>VIuk$VVF!xxyqxbh80wv-4MtY`j~Gm= zi1B@7vL_UL4Jqh0P8M8eP>-ziU@}UfGB!VgB?nQo96^`-fPIK{SFdBPT&fB(w<Yo` z5QIou`pmXV0;<ki5IMkVXmClpS-7IC&raMz<l_)tn{E-=b;QQTo+PRy44%~AuRB@X zEe^zugP)Bht77{^+t7gGi4<T@5=7_XjVA0qL~E3Ur69f2;Z)MDmW~M!LECwLrPD4o zCY2T%zU!O+I8GX0#DKFcG8gLS;O{HnY&a9R@W_Qv*M;vXM26&JnaMwsOhwq$%`zPK zlsB!qvr3h{fr7+&kdy?t`IoH^z8EjxP!x*3TxKw7`W0hKr@qWk82ZnInmf8b&xd(} zcwl^3H~X~~hjq(;>oZJh3@uHnu9luwGCm?LTUmVG>c}c;p7%XPuG6>mcAX+|ST_}> z)WtDqd&j4|wBN4Qo^BTD^2#4KMOCIdF7J)++r#aww%xO?V|d}f_)Du!)OO8$;yKWi ziu`)<_s^=nD4kTAsB*4;k1(W)>HV<o@}J3Hl};(EiT-!vFj=2zGSv4#ZL;ggyn$aH zgiQW*Xv?b^`29}qt{N`6zeWAQzD)~OKXGdW#bVt71BJ!7hi+=H`#!09v{x01m>NZ| z);`YZ=J`n}Rcg$#orlgkYW}mqvb%G}JFmBQJP8(T{Dt&mDu!l04|_^l9d@n^kx655 ze@fjSN36O!9{*+bxpAWL_ooZ<kSi$nOo;b58L;oGfPsCI{x#|OdD`|GO75idm6yk> zf1~|H?F$9+`)$8BR@Kdfm!}$)IV#J6H<2CF;x)T8$;zrq6pGXJB`s$^^-^am-Bqr0 zi`=9)7s@15tr@Ri@8+0Gt_2JCb<wRrf;v0Q27!d}fzC8`*0|sSOY`P2b>ChW&F7<x ziw}_=9$@S{jiY>2)I6iXK5T}~XpVWpdr9DR@5eR)OGY@L_y(*?(MKiczrZ32$38b9 zc^%+1!a;9?YL{s>{*-3G_m7@I^rS^{S_QBduk!gft|8n3Z~MA3XSyI7u(%Af1kFR1 ziN3teOa$gD^O*(Za21?mhU`kHUZIOrCw>*66c?Cpaf_j3W>D3?y12kc7HvqNE>#U( z;V~yTY@xP&-*B}EFTDWHe)_}c(nckYZeK%VXT{!8QS5aj4l3x#4EM2}rhbsSV>}}R zNqIkm1j&}&US6W20qniX6sCl7`|;@i_KA$5z~4WJxhPVv@het+PB0CVR`yErjbo=T zK*`y<T&Y=@b~*PqE7)DR9@G6U33tYM=nrW2YW8gQ^}7*X6VCdAWTA9Fg;j%D{FhH1 zpI<(At#PNkd$A_u7CXJ25K&$F`!&5!-oQD(q%Oa*MB^AP#3K7&L;8dy6=cqvap~>S zF~$W0yB?(XXVELppqC`y%!uIj?02_}YO4(>-_$@Q75whUn@X8!^Q`Dj{!)E<(wE(H ztX`k*iG>o8$D$jpp0l8?+m)S-sr{mt+oIK<I-Fb*zTTL>*|tZO{TBX3y_Lr1Pwr&y z((8nKvIEVeJE?&h9b#{T;l`82)Gi#ngr2hW6VAJ~ox88zb>447tnqWZU-aFBXsJ6? zQL7hc#YGNFI_}u#w_JE(m~%usD288(ulXK(X+Co>RLF}S+Qe>Oxqp~IM^Fr*u__xF z_eeTDZpDNBWiM?ybq5^?o<V5Wv}{dj$H3XAlhm)aMQyq%?O+mRylhxUbm-@|;y!uU zFtUB!#M<n8MjFP@UYQn&K6dLAU2V8KmD1F%T4U%?#m=ijxwc>=fIdA+RpgCiH@q{e z&x{NCdDjG^Q$YFJ@XQeHuD{Hhte^;=r7^nH&M7$)idTB;x;K)qK5eod)Lx)j)3Q?C zF+nhEDwUnVx!X=vre5T$=xI`hcpN$&vFc7s1{6;*D=YL4-c3}xkw`K0M^(uLRo;nI zGB@q>Kk{VeNN0A5#TJ8^A#xlqEJ8O}nQB;7B&7Pa-Y?4n#k>k(9_V;NWzIN6uuc~Q z$Uy-+4w#XxP~X&>Fvw<^Z5m93oH1>}IrA{H@d8Zoo-`LSff&S1UkAn1R}}8%6wPY% zru!$_QjG?P?pK-_UBV0v7|ddAZ_Pkknz>ZV+?$$SBNI0pqiOCc^)~dvmA3<`#JH~+ z)wKYGbo}=6sZWuD=5Lsr5bd6$2uJ3ULo=Ns$z{oyhIdQ@Spt-29o~dxVeCm3t2#)V zpoYt%?A4W`;>2NVn-E3{Hj9PK5tz*67R`+Tml5-)0IJDo)6aLE&uVcplaDg!zZV~n z0413&uFTFv0wT1@y06>9%*iotU#c%daG^ilzKXxivW2wNO({=J4lGZ7Ls$_W-(0#t z%Fi8Y$`@>3dP`0gx4^z7(Fj^rCd~&@@9`LM!A@pp4gA$x$<L@n6ErbVK^`Kf-_Ecn zp4o#g$t@@!DF<6HV8<d`@Yi_037vTeed*6|Xw#;jjeZ0e%j}$7!#9!TvpKK<Tjilq z1MB9^mhSpV<byr;$!=pq-_XDI^c#D(?);;Zqg0b9zf{vYK7421<1O!1$5pwH!_B*2 zEyTE+51-Ai7#06Ob-yNV#@11cb30zel_Mf_T->@k$2!l5BO#>KuT?p-Li_$GE$e=i zZ`gJJiDD@kay>g}x**C?IXE8mbNUSmJB2i((l!q(n<X_r%KL7gzamL-VBll8WXS4y z{J@vTwk7}Ozb3RjP#(d<JCr)m@#x>2o&_=OTFX+GclGmYk2jr5lsB44dJa$3T0>!Q zK-tN?UVoPU)O$31r$MF_^@0NtBHc4!c;3KQzHOcNlNOY@%OwU~RxfqtXNwGZaWjvu zmDy_K5zrUQ-42RbrLy$;HtEaf7ao^6+<w!=IdwRt&NgI~@Ba0tJv*K!48+IY|K(NH z%$h4_NNi%tjW=FB8nGeb{YMl=0@{7H-?8|h-;MlQuZ<HfNa#!O9+OJF4292Db)MfK zd3j4OUJ(L<Iv$hv+9x+su5Nq2YvXqrMV4g%-=2}i&N83Vc4HSVxb(bx5SkLHu7fUg zvVPq4rke?WZ~KRgJOD;IganeWKf4$GW%jRum5>hZ$(VwuK78)HYW33YX&qf&W89co zs%+yGvm5kf_lsQyj>X%)8p^Am!Gz3qw-e4OO+LWGDeyst+SX0%magc1R+u=KE(F#m zpEZXrstPCY1*j=PGfN3VIl&Q??`aOQfz$f=2fv)@UVCAWj<tH0rrK(oHsmrTOw`>4 z{v#<w4o2e!C4u~mf-wzL+A)Ezo5Vjn%V;<7Ll!sw=H<bnq~dKfGy_BHOOiasIrkha z2*5F_5vX{~G76&Qyz?@F0pSc4=DrjGoM`O@pSiESWAs?#nDc$wP`tIVr|{o93Id$G z=C$uy|LW3q#BRPP`xY+5!D0j;@gw<g$#DWCOsb(4JIit8Qq!3qBDjbKHk=W)li4Cl z=wO);(QA!1BNQenP9TbXW9@zm_>2rD!qK8BTQqLGD#liW#W0Xr5c`Y;$vD!X!*Z`? znVqGjFQ-};C5t!>MD_Q_j!Ap>q82tB$Rxrm!mUWWjaEam4H*ccBxOS-`=<8U{Ijk5 z`Vx2Mtr%yPH&?qT!mz=b73RJLDiCQ7BE&arCQ5Kd$xYuO&~{+`TE2Wx+T(;G@yByd zt6vUji)Gli=iT#^@Dzb$Nh5L4__;Ty#?#j`Qm^ech&20nO!v?Iu6HM|TTIH7`O6uH z<9Ak`E!aHipXCv;c6UW$tSP<_<7r(ubfrPuh9;rAqqpk8%qM?W-?wuer*!ufRL2OX zc=glb#{RF2&Iu3a-`^R?YIwd{QsA~ucXUmM!x^;fsVm{^i#YsCzkV5=ZfiI+`d&>| z%;w=TcPmPYntAPCq?T{yfQhwRkUQN6ruE0F3_<G@T$|_lA8TJOohZaQZ%-!~-^0<A z(XAV<=&PT*0&VH}0Cge+K2mG%7j=3{BjOQ9)}q$E`bOI=w}g-NL5BU$ibsVgo$|(q z-a?ka%cHyUiR)*po5+!pOyM`-<fiXlyYpwgZed>R$KcY?YI+^Ogm=aH8@@X|bFz=; z(6Y!|^<opUUWi>KE8S-J7Cp5>nF+{d`^;pomj-rSh+VEzM>Jn>xJz|hH?Bz)Gxrtc zK*tYHtMuE5dLh!A!3#HUaKd{rvhLJ?!~Lo~F*EGvKbigKS;kRCQQB6BG;7h!w2LQp zR?_b6Ad$uXu3=lEpK&659Q3f;n^M)C9WSU~Y-kIVJ%?H+&;^=VYk~tF&hsoAeFujI zcp8?su)VyhWnDfm>+Xi7e^7fBo<uK5913bFwNGWnbWi+cvsS!szm<^sbD$6E$b$)C zUSm^Vzf47q3?`r*>~r}0=;nzmOsF>>FHl7fH1)Kqdl4MLKAQ1p7#N1TF%pjL9g~=i zEP+~H?x@+rf#v-&#qozTp@NITz(OM%-kXFz66#2d^U-6?83Uea_b%?pM|7h1g#ClF zsL?y7y27yG9iy!+5#Tf}G8#I-62RgFMZj`K7Fih02N2dM)Y$@3ifv|YvGtvNwiTMX zqH14FjVu8g$m6d%@}h#GI32UNYS3@P>cVo!hFmfo&wJ_<Zx8Kjs4M`T-(dwz568NB zmLLq!07;{Wo^>@9@oEp%C&o^Q;KVG2!fX}07dSszjGIOpd-j0jnIV&0;duqFS=-`o z6FPT`Ca2$cSR|VHE?k}(cBvRBM&L6rKswZFk~|kW<Bo?<#SdvA0|bMWqZ_r%=qlL` z60<+G{0-ct+WZAN=n1!`I-zr^5fH{#ZkuL_E2uCCZOIo^&7r0o2xXlI={+Nc*5zWi zGoEbC@lb1n_gan8Fqz+=9|6p1T^l#Q`%T?fak7Y5l##obTre8qV>iSZ9dFKF?U;lQ zAxE^EVjvNLUm=nmx=25>ySd<qU7mWg@xOH&lCKCv{g?MweDdmYuiZDIKk$?lR29_g z9{D(zOQM3)2X;Q+dhIwqEsojqrEUL7r*SmK?bL?hJ<g{~g<Us}h4so&zfFC@apL;} zYo+R*@>SJ-(5ty!3%+Yry>MdqAMFA4>YR`Z5_B~bO>fTp+~`uHRv8$+2p>YEI{lg3 z{_b&0vbQy68%LuFbEBNF(N(|Y&-Rs>*Rfg`e|6)NWwX5|mOM4)7nBdv)jsTW!|;s; zeOEG0KbC8Hf5^>U?;mE|kGma=a4;3S1?m6o(2k0G^YG)|=`c<4C+KW9d~d6(oKrR- zE+F5>Deu)E8FLrI!S}Wh>(%Fv+66O4`de*kLwSqHP%DO{Yk@%i{37LXxCYNOV$jun z&;ma8$b4LPY|(J#XS;EO$Qu6n;GM;5f7!S7_E+tr^&t`sh^(yxwD~no@z&k1UB0gS z{z3#Nvs>P6wq_-=Sj`O<`pL2PTO~<GDP$Crr*YD;fgaV&AKx84MKj-XH#wjXwwvDZ z%H~<`>{|Hnm|_f3GPH-|x>;uz*WW02G~UXdCyM)ZUq0-b?DJs2Gg<nCB|2oOvb<57 zDqv4d$<((l2c-mZ?@R2%Xu^iP@b_g!SU0<WewWiZh;o4az2nRPIWS>#Ces5*2Zf;~ zI`xBbR(PE*Cz){Wt|p<(K{*%l2vQm0Nb_>oq^T|E>>ag!tGma>=>310-70cqtAjCJ zSjJhayuCQ(n&0jQL)e`E0iM=Q3r&;#+N@;)CI_q_yY$)6Mv|BeRn3w^Mrb5g5PL_S zsfZVjkzGvF+bnNNjVBSWg6G9xKg!BfNJ&}VmUIE2Wty*3WZ-<}>pcc}d#GbHrof_r zz@s<>VwdG=z1PC(2CJaKZ3r`u{2)(+6&Y)Wi6$ss0p+EN4B{4+hF1?(YCOiAMe{l6 zwB==fj6jo-t3iD!t?YvLt}bzNAbw}r`Nz{Hf#kIoiOFPZ-LfMIA;CG{a~IsH2pcwL z<&wf06K}>vaYVG@_?^{DXn5);+5yrFwF;+yx)hAmS4<^etMnM3z9SB&u0lf<7=QJ@ zMN2)8Yj%fUdnd?z{rqX~D(c+&K0DNO`kclJggrZC0}<_RwE44!i|Rk81)k7UU%KoS zQeW8F*xNKr2tg^fVyNL_=|8W>sq$s&yehl9;~8|BKdtBO1;uWP&Qg1Q(9Kd*OO*xn z<rcJ(@mT3^pRaf%eW&a6ZBY}P-$|47|2#Rjq4G+Q#F|~~IIw6q<b!)|J&)gPaJ$%r z?;Nc8{&%0e^f!f-my{VgluUK~l4I*1hp)eD?|Ay=j18x?{YFtK-O*Ph4qrkB2S(%U zR8F(^<1_r`D1~(6yFYp8wEvUOYd-MdRllS~YoBg;wfURxKKe1j@-8h?&nu0o@o{b4 z<DScU3pMd$)w4(;Od9<eG0!(*?-mn@3y*PQLdg4}s{|X5&ZxdO$s_c>!#}(0ehs}{ z(Pf-Ka`f|u(reSzDjv@u?~)V$`GNSaV;>A}i~je0-);Kcte0j~Ix^oawLX!wU^P}J zZYoGiDZ1ci(?X%*2(_o9s$idrwYrSW+P}@#PFPcJ@!T5rOI4W4;d1fL3AzHE<*qIo zYT1$HM)lS7zSz_zz4ke#kg2!0fOD{rP#VntWU0RK=4|H^=XyGyH1<Nlb4Fso<9Nos zjn!L|N(Z`S7Y{gJj=ZaSt}VOm+||)C)7JRM&`-M#l}AQ6+<}dX;zDvir*R13;7W}9 zx-NG&_dqYXXaFA-lR#b2BI^_z+5bVe64lSrEz*QoB)+qBMLsDSF@`#u!?hqy{#p$v zfddnPqjbijHLlwlZ_@;dmQxkm(r88ysLDf)Z07i_;D5@NK{(i+YNr6qWI0fY@<GWQ zX3X%|S__`Q(E@pYyIQ}?cg4rkbW$`gTL#m#9j*&gu19TQSTo&IqoTfF+QyF_vEhV^ zE^^_2iB{9w%Q7EP`KMO(3dp_L%%P<-z;e9E4Ymh}Sq3rVTS7L@ugSf~!4xN}=hjyT zCiLuhh2L+RTMoVrR3OoOA<j?6fJDFSu5t0Vx+Yn36@MTykxT@l=(wy<_y=x`yf(5? zki3aOPUDe)(u2_zz{iFl0!Oo*S^!m$-KJG0#67VM;acsi2kCj$DeQ%A`D*%Hlq+dI zxBv^?6W)57xo7&@bBl)MsNtEB&NSuX8c$;$YY|Ip{WDu_ho$@xYKLmKrLBn`>MYyr zuvw@y3BAHuVGh477UBthiHc-gLg>@r%U1SGEe5pVpz-aZbudhWpE>+!`VThJc!y_y zd{G2$c}8XzdZJYG`v)zFei|o#dh7f8U4~{}XqYs+-q$brNq^)8biA5`d1Yvb)xT4# z1b3)=5R+j;eOz%1LW|E!jy{)mw|R;|yk#BIe|`PP>ub&ErZd?T(|1#hogSK-3wA@? zN=4PbH%Za`uEXv-KNb&_>&rp6KH_AXRG4arv*zI}?U=vh*pDx5sQWN3;)u_SB)}m3 zXC1T09b%#*{n&=?4T0Q@I>NRao^uPYtH%K}&#flGCBj{mQuXL<!szLoZu``j;i{i6 zzyR#^GQ9K4-i1-Rhi~rcY&^&O5-)BwE)!dB4P27fmffgF&IV<zv(v6PmQ=@G(GL$y z;bT?CQ=P$!-hBS`<_(Wzu{gR2KuPI#Ds6+?&V_UQR*rtM0Raa?NL+XKG~I+dUdNzj ze^Mnd#O7@H9*+>@d~`mtd%1e(jZ{gB?sZj^(l-6knv4@(`NmSY1G#K=dR|0f=@*a% zCf8Mm_`$aVjwWL$;uvFTa7v`t{>yzY#}C(w843AXPiw;x_oZBacG_r3u1EZ=tGBVm zbznGCNQOPhcevp5KBLAPDQ{<9MH~k{|2x&oJxkP21F!u(4ProT3KE)Lau+@^fM&6! zFrz35M}vk(e=|_n<REF;Jl>xl#_BB%%d?RuP{0Npzcb>YEHFTpC3<J$z#q>er*YlR z#s<MDm|paaqbEd4lQI+l+vsb&FHOu4$sP*M2Q>=EoLohibC$2q+_6iWgjz>I+GuDy zY0IG~e111^Dfb%8b%2@s%Y7NW6L!7h^fm)cM&JP%g7c`OfhlLiII-hNexms)N!o<< z9`L4Wqx~mKlJ<BtBYE8+YVaI42O%Y(p`PFpb>6E0#yZ6}aJG6GW|&8EeGcsnmHBxb z_ah$Gn%u7r|29rPk(XT4w!ihnT&4!I=-cGx8OQoCJrW)8`j*u2e!R9yhg|ns9E^9+ zDK(VqNm+rhnjI4=3%2C$H50Res0}a}(euYH9<Sn8>sk^3G$_-jtP-95Gwqzmohv^7 zXk6PAEs8iXeX<MMJEzt>^?bT2w94sT7LK_Ho3nvVcRYeAn<U7F!HQoKjt-1`Scr@D zD&6x}8iy0A+<jL|cZx>%p^};nKdU4=Sxd*$2j@Rv!gbR++mfWu#+{vEk_E53p|vdA zl6-P-`_``|sjQHU*oKZdLArXkfV0o0PiBxGd<USY*l>8EqRyZ;oK8|C{XXp1ZFe+t z`^J=d9et)Lhdt7dX5bPGg@@Y;9vA!11xFm*ZjQc>u|WSy!noXY7`D+u>PSuwfF2|) z10y0zGP67r{x|kla$;3Y>5oDr<i;Qaz4Vkdr#?Em0UEm@?4v<(%h=Sd@IBP1sk_?K z5xC4n(jyVUra<s(LX?u1LsVKs_J4k3KjyZqK(%Y(?Tw-x%WOdYT781y&)V@I$i#Zs z41av!E<LN{(Jd1q*2s}!M(pr!?fIk}qw4`yc>vXLv>6iwGb<0Z6iw-ARPjx#1F9e# z3vYyIWU-P3Sd2OYuYSUM=}-$0FoeRYdjXt(IXMg`*=o-pv1i5N5IABU+Ywa!AT8AO zunwVX&JsgS%<h20n|fre$t_$eL}%b6AYdW=ApoS+(ms@-99Y=L(`PKfW0u}$uJYM> zQGmL8Bq39|IC3zZQ}+~~M~*dIvD&%td=xG<lpEwQ{Zq9I#Z)z9GqztEyCx6HCZafS zwKit2MI_e)8VfV|yPFaZ-gbJ|q+KGK#q{ULj)t18QHqlKIB-3kXR(!_$rz6(Zcz>= zQ}W7IU?&`ItU)aGJZ~nEmj3u0zNsl^+`U+gpTdz2M8PBZY7wRUAhc`!E;)#5VBjE~ znjNp;+aVMaVw{A?v~?{RX(0~*S->pkr~V@wQ(-czoMsJtfOsX`e4Wo+N|-BD*ILs? zx5dCi!sM3w(k8^UXZ1(R@GHCKGr9Y^9(otuzJ-=w2N1XKEpI$joj4|fUXnmLQm#Aj zm_|iG>*Nd!crIjxjXwxH?1oCJl6JPQ8SC&Ut`A3IA?IgkKwYd}Utt-wtuqhtrZjoH zr-{f1AA~0#OrDfS@!foF+6zNrUchvH)w?-Iy&2kCGgX3z#mTue<PCb1RnsMr3=SuR z*nozT3nLS;#@`~k-1WD`eOQOZ(yk~Rs?dCX*ZvC;{1|<)ya)k95pQGp6(u1_7lLo` zGM&CRXZj4AA?l1iAkx&X>vkh1nO;no%}b3gLfIj*Z5iB;y(1o=mQ3?KgUYK_bm&z} zXn#hROK!_x6g~1^MgEmRDbYfEQ%;fbVxij7-Gcx-8HR}a9;RbLW>{K!?QYFsx-fUC zI@ZB3JNfEx-vl0=cugHHya`IUmj&umGzXaEyMX3v3wC8Sm-`0Dg#3C^;vPwnU@C(_ zmUR$Qg@}v#ycndZB{VYva$36(Hi7r5HP8_d?h!)+E}R)e3+5Rs){OZ<6IjiZ+aVf5 zhEEQkSe#^JYIWk2@yl^al4UmESo?yCOAvPNt+$u$-$mhc5CkmEX<C{C$}$S33378U z-^yfY`4rm*&Tno(z<OG#!jkl8^$%9SqIfa{M15pac7dhZnJ&Fi;}RE*JZhR8W(PYG zev$=&LYdrk&0@HHsWWZHhK55#sTwA~M->cMJ$!!d{<v1ECPv!NGzx~x>bg4hXm!Ms zxxb%OZarRZzh5Mv?E3#w6<8U<65>}3uV(aVCO#o6M?NdP>Fc-hcQ~M^fEpHy!%Ojt zEgHMTRnjum&yRmOu6!u{VrWY$XaSONBmfOPO-%Td^t6chwo-#ZUA_KUz@er^*G@>f zkes<WBo*v%%8yudzAd`Tl|6|1RB8@;wI1E9lR|-=RatmJf-YWJ{Y}5(p_!R>?<QmD z8$Zb8z_3Hdv_K`N*Zx4AEd%IEL71A}@$D@LAc*Oo%vvO-`&ay`Wz4%m8Y{!Wh6C+f z5xV?B!R`*-ZC9OW$cyxa!9n#ok$nQ$094+<(G@Ynysvg}490k-qUggl`pccG-X1c` zMrCX#?1<>CtgbZGXVM$U=y7l)wDM;V)IgC&cqYS7x;C<(YbZ$+v=XEQX7lecqlkDr zUSa!sWGmei(og%C<s5v;BL%3cr%5e*^Mc<BAn!37pU3vX5$@T)^3Z#L4=X%+)Z)dM zTt!;47PnzGKnf#4Ooe>mz>>gn=PZA@CGz_`uUbYUl7;pK1GU#i40b`LZW-*Zjgp=8 z*hq~Fx7-0WfT6Rl^MC`XNute38OqW1pr_SSop)PQ4bqvF_}g2}qyj#K<``#7cJx*R z1ZieDTv#j`;%m&l#-)s4qRHeHuO?v@HHT;$*3CzeB+Y!{B8Q<%fy6U59o3cCkA2mN zA9*1W2>6jZy46Ke5L7K%SBE?Wf9P@F=>VU%e0s|{r-;;fM%OVvw0{LXkdi6=Z<dzM zOx#^*%Fp?{o0QMS$2oJccHzhq4p{+2_JaeEhwu3#8b=T+7s*|cU)n<R_cVSOJSTmD zI<dd0hC;`JkstEnwtQ;_<tCks&)C+anI{tP=KrLLAR9g5W8j{E#o(F#lSeo9dX~G2 zJTo|;3$BGi{nWn?S?{rb>s#(w5eIb(&uM18>F{!D8=7Te#4z!o(PPY+lL5AZ1N@u& zjvowZCYG{zlRPLSJC`;NdRBbRm@k=~$OPT?IQF`{(WHJ>y<eI8xuuO(C$OPW0=t3Q z>D)kZ<1+5WLQ?l6(ol^`0-ubj7?di0AOR2>M<G+8X-|(<MO$7>9hkbYz<<(Mq%#;O zK#}f%>}gQhx!$Ry`C%hop>xCgFm+@5qsyf#pAAzT`D9Bfux4m2HjLwn4Uww=p(k-P z3(rDf{x}B+K217AnZ@QO=m}l%87>4#xEzVQ*)|N}X5{v?>x8yMn2jbV5<Ge#BSC{= zc(JL-F?Ydg&ofQJVrR7wjX-U9_%KVC3z);=Vl$<`#{Ch{S5%B)90LpP+@@QEN}6Wk zIL~vl4<pTzR_5+Fb2)du*LIiND?Uav{d@69m$+k?SO1zzZsL|PvZ0Fcd&gR#m#nsw z34AU?J^T)mr=;aU6W+^BZWNF4h)eiTMXHcPSD0l$MVZB@TH`Q|C&G^uvoV-%7L<F1 zl&DCPpktZoWETHyc=ABcMI{?<{b2Wn*v-NnhWUZw+#gv2YSa4f$WK_dO?|m;yIr03 zea~;%jp*kbPOwS1F}W8N>C4Stbq-lV{cQN;Be#G@UZ<0+URU2+nR$RBn$}Bm)IIC& zufBYENMAW_Kq6YcP@y`!E;Z{;h=qbqC*n7+d;md#GJQ3N3mxmTt|$pwh?p!V8l^j@ zIEx|U)hnW`bj9v`LNiQrQ)7?hiuv)IZ^N$Dx*bezIkGMUSwcZ9VBW1)lF~%C#a%H6 z1=e9?(M0|N1(9J|^2d8>OX=18L5|5bgu)TurI}y|dzl&2Ue|_{ri30A>dh6aUQk<( zUnCfCAp&Ov^i}_<kd$B^GMqj|4lxj)lw7Dg?Ti`)%B7U?IL(Y#agNx@^vpekyhaw< zBnG4<T0uyMWG5~ntyCsb_Kaw=l&*tU1-N?LbaCptx%4?%Z4!eX`4fQ>@}@k$^*1Lt z&tSAX*?0%}M+$fKb5XsS(YXTL6AG^t;!ak4%tr;=Ih+^WBhRX#2$Awcsh@b@<O{#% zz|t{+U8%#*-atDaFY-epLfzyzZ8O)z5MrzYNiHM>0Qu_LhA5^WR&3P5GtC(_m>u%6 z$w!C$Ubu(~I-?m}VTCh7)Xf~&T-J9%>b{z*NJ2js@|1A8#Dw`l8q&-sm=nP7i9^6K zDT~KI>WcVHdGGbb>V?uPAnbM)cf&JrJKvaW;wZP}3nLyI>n_p#TFgA5w!d?a^uCQ5 zih#B$wTQIu7%$b56BF9o+ef>qBt*JcAB4da6PWi9uy>Uk_7Sjrkj|r8i0kwByV6J^ z665@|njtFhRpFTd<s?1q?B-f)vHM3{+)@z4$MOCS$QbrdWO%TAal*Qx)TZ2}m`|Wp zBp_(spfw$>v+K#5RtU=ZY1(8J7EBeZkHRYh7iyipX73k=OtXW&C?!=BSi=eG=SX*D zfvRT?#$6<3mcI#wW2mM>;ofT#hQ@zU;Q#loWuU^((w#>BAneP#%l&16{{Hm1w6^KU zXoE8Z<4lXv9?P<0YDC|J_u;d(H$k>brUaQphE6^Z6e+;;HDkw$em8p~%HLZMR5bA0 zUiGYU+aqc4+2E2(jCkWA>6iE?L$f>gPG&4gtB51(u#rD6V&#<8ivhe9a#s}`B1So= z*BuK2<tx^IB)3~QH7zL3%Vf;6rA>pcoV{??O92x5|6-qJLrDs#r?o`OXca}0u_t54 zSf%@(sUM7x-p?zt2I0#=_n->BG&ww)HOjLm72sN*kC*p@iz7WcUGQnNOIG~qQV_6g zj5JY`)ht)$zxT=#o1u-j!mI?XdWNe<@Hk5wG^69E{19+Q5vO5;tfsK}XZv0U+x=5% z8|J3}Iw#<yb`ha5_wwDag}ffRzo}u95T|4h-r^<Q3|PNK%B>x01wO)dxi+O{s-s5u z0NFXfTB4D+5z-Y(|Jfc-JYVzt^rz+Jlu?3nsB}9MeZ211>x17CE_*ef*DPFgDchy& zT1(PrzGv^JphuD&6949X>75b2b}wBTez#J4b*CXNO7&Ss(`JXkHZaqM5V^$Onjml| zZE)+^!s*JAIO)S<lYhIW`tCy<HU(Dq_R@{}IE92`p1$#E=H*{DUz&R@K5>X*U5#(O zIA!bWYRX<xZ;GG0rf2$_#eK4##(h#%DG%tUn3?sr{s?$<OW(nRLA6Ol&6P!QW%V^L zL$KhcP+$X#p;Q`6hE!t+vHtxT6AAITJ4TDVfd|;5FP}<{q479k?u;RWXNqXu#jX&= zHsgxwp^9(E00rc-AW1y9;2ExRL^P>z%%N^P6KNNVM8?^Pw^%fiR8R_<#2&(9o&nYT znfg<OKnC<f51+BtIS(csmD6`I`Ojh;p`SR#0qG>FZ82t|C2R`s0b`Z7aJOyBwHh8= ztO<CH7C37!lg5igyiU4CXxfOsBwa77Jc5GSan`;n4auTw=914`#p$DDIe{mLv(Teh zyyMg=1UnqMq{Crmz*E~lhtE!bO8Nx#J!jE#f;%P`O(nWi2p%4#l_q+H%p1kSy6DXr zp_<DldHxp&p2`(=b}gQP>ayW-#v>UoC6z-PtVp8SfpH`RQ#wX;9t4N?EQO``O60&` zl(BZbpaS{K9o-6v0Gpl)6n|Yp*`oAeiD>#=%XMf!+0O??P$3W{Yet=AyGb5!jc}dJ zB9#G;<5;ITp9Mjj$RMKg3e^5UX+29&SBsX(QoYxzvzDcH2Jn5s+zylwJ0y2!iFDV= z`bxSzS=lHO6>=k-YYCYWhN<R}>m->nB4oKB)dXDg+Y=!<M5b*sdKIfBp9-8-61Ar* z$CuB>=m1j{^gJH|j~6l~B4O@NBkFkw)5<UH*HXmxwDOJKYh7}AWEp9rsXj^Kh5O_P zk2O;rb7Cbb%6sy<?dl^U2Mr?9gl73H?k2)1>v3uwm9;o}LKNQ%-~-IzzPpudQnxs= zrV$v#4GD{3fW5OWBt<20H1k#P{Y*0Lf98_N_Ct&yaFh8?e#Lk)J8jFsc*_?Fu};#f z2Hj8vi4;REI~>SZ%cpj6GnRy@Fjzr1s@0a}ku(w>1=i?GIIb4uOt*(dELvIR9KbDs zKDMcMWwzE`P#ezxx7}N4z8=Ei;&j4EfX`yG;S5Mc(PpPfTkz0vG84O4k=i7(_d<xL z0p6Bu2p)-duH0n`&<PYN6r_4x>;Qio7);3;K5MU0gfg|bN|OuEqb;yDw8LfGm)7_x z*j#*wJz^;D!H;|A^j|vN`nvHXb4BzyZQQj>Fp>5*r=$sX^2*Z3yhqz`c0%VqPRE_` zO9J`H#Kb+0w~0v99rf3}Exq<S9x~tGT3BO$bfnN<U94{Z4dO@J+7a_T&ra>Dn7V^V zveyJ;AvAef%S@mObGNgI_Ng3(N_JR1(*(!fS4ppL<SUIQ&nz_>ViQIsU;R<bYNMla z_ku{oX7Y!Ogpf~PJ^Hcw;$(|GkAy1KU_vNW;&FhvGt(S6jC7+QBapzvt~sjiR$S1N zfZuERj-SIAuxzFwG}9^KgHMb`vL5D+j#5m_hyR-p_U^TNi%Ut`L<M(*uVK#ga8vdt z!xVpva*!bhWsS;euFY0=x&G)|x?>Eu*LcyNmBt2?(=o3k%TMj!3e%T|DMNF}FHP>W z;#bxN@S`w{#YDQuvz(r46eYN-_H&53x8c~Pm|m*sCTYGJPwtoow#sYqYzNuowxZQE zi{wnSAoI_ok#)l{$_`m-3ZjyOu-eliMY$*ND05G>1O<t(APP8KU9-GLb=kGgXONTc zXMT+VY(ZQN6m~vUiX<{$@;2wp<p!EJ2Ykwa3VlVra2)Hs60#}KTvtd`^V%(hhio%i zpd>K~y)3swB1t8S0Ye3TXAw+q?Uf>4$oj1F5M$rX`S!8@D|maE69T4H3cD{YeGlgD z8NCta?0#bKP7Lm4Zv>ebpZF1pb;ZVXDfp1lW2_^jF90ywfsEiX#X)0~UY!M9aqI*N zsh@Z||E8776Y-ft*Ub7CLc5a;By-0JDNj#LF5)yNkF8>QI%v3&Zl$!dfJ9v_f-^5P zKq6?wcL-Zi;?eR!WY8-5xV(*@czbg1orHAoSRgeRDm2^RTsUX?Y$T5f&B8A<Q+zi9 z?vLavI8lPKSz6r1CGWM;q`YXxd5JTSd<7>MfeJpMgzPWf!T9yT_%Ys(LBD{(M5}hZ z%zM>*vC5@vXOt{?@i~j5D?Yn^l5LT;(1E>@Rja<>Jy!dK1f@{t<UX&>(3JD(D@+c% zqj3POGShqQoaL@6SC6rOhYt*=Xv`Um4*2h4BB#$=(4*b<#xXFIxMh}U{*f|0Da*Mb zhkw=uh!p06uieNW`U(P;SXx96dX{XYYcyf~eAlI|xd7PSyYg++mOi~Oz2veiC$aXB z646tkgB-LAwx&j<2}->-X#!ktTEfV|?+laaW8N4N)UUBt?pYj)Gf>H6H*iK%ra-XD z+5b%;r;s?}>MbpCKsSR!&Y<Gymu&*%PL>)WGtXgXaZ9xD^Ky^+z&_BQDiX~ZaV{3w znS^U&?3g6~VU^q^mvf2Z?-U1Q;ZTL!>mGt!X;aB}Gniryi93xreb0X+9i{MYV~=(* zxu#fw+Rj#UQpmk7+s*9v&b`hw*$#<uEF})i45P<N^KPO6BN#+6mjd%8Hb4XUQCsl% zO!rJ+DvRT?939DY2S(gqG<w8we3MI3Q9Fo{kY5>fnPg66j<p|QXg>Ov8KdiGI({Bd zH|sXXip8B$<IyUu;~PXXeS5I_FqMW)DC?d8^i%rfTl_IZhz3pXICTRtO-Fi5LswX8 za-ScoX5d#1x2%Om^_}*6$)4IxFakh6yLBt1%>{b-8V`G~8<Nk+p4OhemHG#wBgvJy zY7NOW5s6(<r(j7BwHQyHYG`zKWT&X!uGpIa=Js#q0I*KzyR9_TQz7RWJp>tFwHOdH zS>T9J0_v|>VtSYkJWM5r&DUpwu%;q-jUrtEeB<Aoxvmh;l4ACqxocC@3X%sA)Sx&a zIHEsg1Z<J)Cmsab1q(5b4Pqh?YM+|2xFg>kEkyCRf(qDj07%-{nM1U0r%)hVT8Vx~ zLHZ~d3l^N)02|qC$4HZ*==AoZ79S^ciVeq`BPr)t$P-y>Rb>))G67qIwNd`&kK`wn zhU`2xM*vSB3r!utQhHxx@Fi;C7RuKDXrEWpB+~esm+r=b*~H0<WYu(vq_;(D+_g9= z?wN2f1Fl1&5CjYrD4mn@U{6~L2f{OQA^f1Q8!MqC61!U@5n0R7Dk3Lj-l-&!<;S~S z#zR1~hv^HXIDj4bQNca_53CC_I{#^+#N>r>G~|kuyxeCF%#ziMqmAm819a#tt)C;( zr6e|qm^$C(jr(1X0*LUHayBoe)wM}h&&4;;xuF^5d8X}yahA@)Md2p2$<EI$)E$2V ztv<}dI*O>cw4?BD&ZjhDg^or}N_!c}JWpskWvv6j4bLP?^N;y@-vId=LqZuOnvNoz z>1PZm^hb(FCs>zo#CT2zzjxvFvI<<LJ0>?3!TJx1aUQzTIs%d1?^|!v730}TqA?GH z5c|A(S8n1*4j0goHO+Q#2W*cCw1Fw2q63=s#!%y;?_FHj{=`hG)Yw4TtNwnw+tT2k zXadj-60==SN>QnM0NRni2xt1$*PE|-2Z*mysZE8;wN({liKY>7vLBzhuPho&xh@wS z8#frIwBZ@QT_TNlS6IBgNBEk1&Fe@1zgg$~7(p$GY4#JG=vkWD&V0R`!<>{-P%~a5 zmJ|Mc-qK;-!_!ua0a@g3HCmrJqcFta>9V7vtALGcY@}iCQ2OLxXZbn%ElmduvM?4f z-@WEfP4i#y1zoei<t{F4nLri=%#rAqIV}zwMQt&?)$StrtaFz$5+558KXFk}gqXi4 z46SgjA!7cI-4<*&;~zh0;whnuBIuZ$Sp~_%p0Ff(jBCH&G?fQf8yJ-OF|lp$5z9mY z9?@TU6tMoQfYRi~gJF~3U^EH24xH|@7MUu`N-lbdyVhsq_+(dwIukR8abx4h%UdAQ z&?-!J+wp(&d5qziu-mioXT)Y(j<|<xag0DblF}<Ck(O`+I#XaA@&u5S2bxZFVn@pX z%0>kLkC+{=`86sI1g~md(_rKAnem?*k&u`S|K(<oMSRVVKSM8Oe1uTa@$-%IXFXrf zUdyjRR3jCTQYaaNCvJwh489eT@xA0Pv!}atw#f>wzO(y|t5$2~zlP1Jo8s(2og|a# zAF}PB@Lor)@vK;F)z=&wU^|~@TejrS|LmgYpT-hE1JExLJSaHlq1pOx<m7j<zR*mt zX)aeX!w<zrHY(G}``Jg*dLcp;SzXSMHB(3IiXqV?hQ!at;PvAkDF@0INGIEV1|%oV zj+y1n7Ya}Z77h~b9z`74>Z)a&tY(Ukzsw#7FwO49Quns*65Uy-A&R7X^TFTR{*z{w zc7jsUk*u1v;9>?cC&t*H9N-BrYwPBO{t!HEjm-OHG(B`nM9ub3aeQ;WX)-{EQCms~ zF(Vz35CsmZ-4$e6^g5vyEp*?;1<LfNfZ%z6@THjR`o!2Hon_1_8!Ab`*|?ZgO=C6K z;!Rb68!UO42><>F3n1)?h)LUU#T>B~VNMNlFX99<D{4$FPZATJq#i1o`D}YW9A(NJ zf&>B&)Li2En(L#L@OUDYpHEnu5azSc%zmw4WhL!nT-3x1(U23-M-gcyDG4;HT_lzT z%bW7WrCMImmw1-M%q4au3vp@WEg9+@<gK1Ny-$DH(4>(yp`HYl1n(~`*DU}IyxmEJ z7YkMv)b|9T36y~;HZ@ddqe!bKyhp&pRc<*q+K%lconz@UFb{}!K~S|Y=vXjHoTPyw zV;RBH&|Z>dLj4uWin%+^u3Jh%$Hi7Mu#zin%$*M}K$ryV9rMGMBIJCbg~Q*A9u38= zK&`E>O%J`Aa{}5yl0sndE>q&IWE@HqbzTaDwf%T+JdZ<6UxiqX<gEw+#b|%7to4lt zw32d1>nTZjfJ$Ioj}Z^v0!vlU2K86lz19S|Aq^BwV5Po5tO*s)NjpwJhRDxNJsoW` zr=a1j<s43&j_j`wDGN(zln%z&S&SlT)0wajvrJCHoP!vhW>y-SWhbTU0BpjBi6vH= zkXm3L_yBNdIWJq^xYVfGRiH}i%gJd#EL^;y08j0?d{{KC=8$@p5!q0}^0tTqZli4A zjchJhv1-31YLZn>R-)_St^swXGaqfaTl@emu!>Y9fxzdHHuC3;JwAy&u-cbFA=;0V zSVpVuxcU^=#Vo6Uat3glsg;Y6*k&F#%h!9AT8#Oyhoy1Rr)^~DibOF`*Xw%R{1N<u z;j)<mlp()gFU||DI6H0aeiA!r64y4p-9wY802`z-S+Vv7Qa!EH_~majx){e|Fn7ku zW@ze{zXvS3?!9(u&vHl2?xy^xU1S$1YH`|cyyYmcn;AAo119<g2=d!PmmkIlprjeL zRE#REHLVh%enczMR0xihR%Ob-q*r`Ang^_GSk~*p-8uckYSz``4Zo7}1Eca6rUR!S z<}zjoudC7<;uiKaC5quB<N`^8%>P_PELbRw4f)p*Pwmq$F965kjJme|D9$tddN2oV zLrm>v`?zfDopH#jgkrF%JPX9OGpA?I{oW?FbA;$~H|MVWnY&RHQOhRZHI=Q(dn<XG za>4$D^p?<BJfQB6<q$$Xfl;s%qcY0{M+bBFfQ7J8E5XO)DN^D21O*$c0ufN8eO#sb zU5nL*;;TXpl>Umyg8&|(HOGu3$ns}7FSwHU)Sn`fR(KDhr`!Z_fNY-Kdtes5Pj(c2 zJJ|M44jmBjhf34{{=GGP=+SJ^jArmyd(Ke*Pl4kSR0W`3LLvq~24uW_p2?WC(!<1N z@#X@~y7V?uBAV!G+3EHKS!UmxWiVn{MuHTZN5Zv5m>ZV|iZ7LoG7JlrTA(@bPWfME zKf2E2Ok&~{za6Bu9J-+-(MjqS&3GIhXopIoWc`hr+?+9>Wyy^qx)XZBGvBU|u;5u7 zYA(Z)S87XsGpnD2RUjtcu}-G9nv)064rmjBo`7CL?{q{NdFaXsrc*FO3%{k2Y+2Od z|Bt3G0c+~qx<-pdI#IFJYJqr5Fp3ISv{h)})T?a>>Ww&|mcdpmQf(E4LKJd(p{?SO zNP<$dCRR|y0mKmy$+Zq4KurY&p-f63%tL^X@%XQo`~A=NJbt%=$vN+^hqc#U8#N^K zu-Qn94(cV{N*m@Fk@Zw&2vOw!(Onz_5iCe0fM3Ep<4BT1g3T^vY!vY(Xp?Uw_<lxt z7ZU~m^TwI^EVECRyGa^M`aks=l2QQbL`@dd?Z^zZI{_J**Jq56e-dZo!Xqrspx;J} zlNKOEoP^0jw!P=!da-^tpgxD2#OGxO-+c{KH`^lS4OnIr@JS}H<k==KyzT;=`4CsW zb+MGt{E0lB9>tXsk{C8d0q2>Eo*THDqn&R~!lPyPd3Xa<UIV#AAy*w>^Wl3Uh=K!V z^cZwOzBSJL34$J5ljABqykt89_3>mP4xplnXIl)i$zO`@PS;<ASa);O7wB*D`p;Wp z#j4!DHmw;6#;yTjpJPXQrP|2bt@*41;5H036v40d24o@r%+J`B_vR7g8e80@DY!A0 zv$y;B?f+}_edD+a2_)r71!_5t?>a3;$Ls@L8Oh&CV#2#129Rvu`1QC9*JU&+<K34n zL#MQte1xFR&;FWFb_lz-Y0ep#1aZ!IU|ET=!k^j4JON+XS~4fdZX3Rm+<@%?gpj%U zv$t~apioBw`!a6oR`J2^rN~R-Cf%<*dkBLI-ykF2$UmM>W_%#q2!66*s|Wcf7!s0` zH&FmTi>h7Mx1N`N%wzIl)bhUl?9gg`u*ZA!rHe&x;R#V_h8FEyTAcNX``H7(gB?^0 z&6jd~IaMmgMTvWthh+&_m7V-rkvR$mt?Ur^10F2Z=XMCD1lUdY@fBDL9Kyaau!~M1 z*V%Pm#`_%7U<Sx8l2B3}!}F9Kw&Mpsl?vls{|UC7Gzf2FC#ym(vkvl38@5jK!}e@m zeKyB|p0tm3Utt_o!huV9;d?tmvXi`rIk(Aw$F6bM8_iO%Fy9Yd@scrc#Hzcm@i?hx zkWAuH&~@8lYx?@RiVYJ|9jMJe5IW2rJc1Au<(11aIEcUE+*Wd>=$0RWgOKt)b{W4} z+E#{r6_UA4?dKv<IK(|BHM=jHKakiwg%Aakk$5MD8JhFHWDcH^Wf6s;Jb*|5Fb%#o zbz-0nlrZ>s1g}v996&kyf0zEVsrX(JD7a!^3s~oqVa-nA%R1H%Jtd+G=-8=PLW&f_ zRTt1`gHko*MRPMha}rYn#8OJnkOm$ruosB1l8+J;BY01eC1p%-$!JL0Yl=lB0M!kF z7a5ef6hniFs1|-x<F|zmYR-j=`S#ZU{=$J`Jd^5kj2~-yg5C=39G$iLY%7vx&1f7H z@nGxHNylp5#0ZOt&tg^(f!MBd2xGv`uyY1lDs^glx*t<lno(yaY$T9GpjYcly5oew zWOadb!KqVTKh8%_mrFdHh4cW9gNkT+p<OCuA|HymfEEBb5-KjiBT8{fN7Dh2kq<b# zwE0JS5K0i8Nio9vHi!$DXVv5B=$<$BbT{0rwZic#HYow(wnI!m4PE-dC#;q;XCENy zue^vTG*`{BWcUe>hfGMf!SG9L6MrJ?C>)0T<Ff*mc9A3p7e3R~j^JQWYr%)&FWK2u z2$AgG2NHyt%_Ig!WgdA6G9yzIYhZ3P@?V5DKcVD|n-MaGsc+5ee^$F&2z@Tzbs?!g z<v`r$($gEgn~)`7u;n@Yx7UfB$;IR70dqB&2RLM)$!=xvE>g>dCA8Z&2UcSCJrY(! zhui03yA$!Ps64I`=Qxn%IEYt;73IQ^H3PdJk7$rn%n=76=~M6q*LnWyKFrR0{AJ4^ z<+)sNW};+NiW@yYP7U4;?dk*M=kr-tP0(PLAe-(0bqu4I5p$x3v+^^TH*F9Cy)#$O z!ZCaKZMXZ>*u8qxArooo#JJz_!Kg2x5*%<2$!kCkIfo=$0kQ0D`^J-y{C1ZiNYCIe zTaKdQqAE~rt;6TQvT6<nkUHQQWVfA@xe{HXFah!?>o9Rir#F8x4K9)xU%o2}8)>Km zr?JmZpR7H1_RvJ_dQDqi+l9_|ALQ1|$&Gm~Ga@(xo|?C#c*S~jJ{@uwAC_%B4*-z{ zA}@iG#n)s_&O?Cn*OB1Qe>`+f?Dt79A&s{>1!LMyr8o;?9_UFQVlG$DV)~aY{l#Yl zSC-k+^;aR=sTW*3{2%obBH40{hYRHAHSc|L{{!JXyfW427m^w$C_rwZafPT~pg3j6 z`}|AsBii(WtuQ>!l`L1HhS|q~4^{=Wu0cZ-V(jQwc7H6&gX{a}-vyQ-j{xe8?rLtD zn=H8lUX;3q6n)S2-bgh>&cEZmaK#0c^iGdJy($yfKi}a$qj~67sfmI(%A&kC10KDV z{`6)wf3W4jLYvKpUIgmXE4w!a!c)g~Z)Kv)75O`kS3Le+R+WFA`o#=urXLuez{mGY zWTy3mhvEt%DEO{zcurAlW#Pl8H=B5abO;90??eJlVkznm|9^h~Q`Z-%Z$l-7t+0Nd z<GcO&3-<!PQNWyK5Iln3h_93~ur4}q2Sxfj^dzI7;0;^8FGm~)xm<0`6Ys>N++{nV zqeygQX#Hcqh9Q?&-tQ__KLZhz{EL{0%Ox4U@;Lnv0oQ>xSwDbSnPp@qI#b|8kU&>7 zKo(hai5ml5D2#~E_k2Vf%`oQ2s}sGPjK2Y??Lf*2#_FVP58&QNxd;<jtQBq-A5B2) znq|cVBDeCcIYrI`c~%n_4e(xPT2{!n2ZEu4Km%1(pEU3g&|pG}nOah$?g(}fMd3=4 zWEoc))f46optOhBVzA6HB|Aix43JX~>LSob3BqDhw#*s^TlNm-9U|tlM1y7*4`BvV z)Mw6k!d2u{+cJ1A=?Dgqqu>xMpbY2SA~MlL`I`0uxnhL~Uz^mVImvfC+VUn%CVFe} z94WYcZD$;J<k(*FR++jlzlM4}hQtNpK<0wtj`|g1d#X!;Y{(9d4uMTJSeWSR232Mq z^u5XdpKS(_Ob2wZO$_=cY%vPeKtr=-#BKoFCVl}FZM+8liom=`_$LNp=bt^rJEF9P zt~*LYQX8zS9awr5k?AOYVr=6CDG!AwFhvwZRP00?@|?BM#6^i7F)m!|K+_ZeB@D4} zUFUdOrET$<*I@!sqC}m44hhVksgZT6!K`9z&(daHWUwR?p9u6sz#xQ|PHHhTP_oeq zrO341Z=$ao+KFUW{%x6moP8pnv@V`G>xAX%f%_sE1!71(^b7!>$0bWscCF8SmNq{U z-&4a>lF>3SbaV39ag@2F&@f{O!RYbhGn4U|n+cG+PPL6Kr7xWqvW7LN{SnK=+t^k} z*3&D?Fa!8;EVeJSbK)I%_<Z^sO~)?GLI&!Px$c$SS9kzT4(RJ6`p$_*KSvkScQh_N z3V^m#@$J~%RqV64_ci#|n%$V1NMDf3Ppb=$5|+@$5$4U>Y)F^?(Zg8z!OE1;0`u!l z$)r_C>`11L=sQdLgAafH9ly2jTXbRf{#{_wF=vC6I|nNtENPC)Jlnztht0cOdc1DW zQ*GC1weo(8GZtj^Gz$Y~c0rn>c#)a5EwzeySVpkUbQRBUwu<B778VaY?V@!h$9#7- zFrxNcP&|lGqsr<jc#l7mZ##wZ80cF(!N1#Gc$uFkL=0X?T8Y#DwhUtUn^kP+nqT?b z>NFHN$mcxg7PXS4G`_MkwhMe-d#tQoOS|q{OuuFgW@k=OeZ}ghx=LeeW*J#8H@8Xy z`_SBt%4g(|is$p1CJE>vFI)!0LOoC_Z4cZ+Sx{q?=So_g4n{!R7Bk8D9xmlh-gp6@ ztndO>uO(mI&M+!6mk&A5jGizEHgj&m5X7L~ijrJb!fR?P;u?>AD(j;Dn;k-W=S@;Y zN0-synRxF2YNQD4khs0PqS!#a?_A(7)pt{<`j(AyM^@h;{db@?uhk~cMW4NFtvIlS zNnEz_q`#`tOLYhxSn>T^B)tP3S4JE6gaPqGeF4X)JpOyC{yJnJP7dJI>vGe1|CGFr z`d?eY4>ALNGbM4BY@-ZH51UP_SVg?Wzu`V|^#={OfeK81Zx7)HwR1llgC9BACN29( z(fZEM+wAEfe;G6lHa||cO6iu0B>H;oVK5`s%7r8%WUkEJE6Fg`Fk6D#>#AduCJc^B zpyn3_mE}ljn5tv_o}{URb$^%HYEi@X@Y>oQ5C@l=04PaXc0|#t{H0VqwXy`G6}q*U zUOwn|+u;w^+aNIS*KjnLKPb)p%~x=WD?$2SN{Ftg)bp;DAz1r)`HO)?3>S%xxyvJ5 z@`Cz_QFCLu0*LSzy74f#78xJK)bp0cDi)xZ0O%3BAUE5%^TnqTrafq((VaJ;ZL2ne z^@i0S$fbGp5rnJ|FBt=VxFQ?hnxTcJ#aKM6o^C&v98KMicvEdZ$cx@)k(hSdDr7-} z1qX6$)_n_(NYSvZO@R?XP^Dm&@Rk+}(ydvZf{y}wdiJy4=vorKVyN>fj|Qs6sFC;+ z;8c#XbAjrG1u9AUky8;q(5h-`fN`3mn|I9Ev2yc2$T==yr=VtSDY3Y%p82?z_F6p? zzOREm3wxxYhCRYlgAzHmN3w|m%zYMxNo;#9|AS3y*IRf`eVq<v7fLbm9)%_n?D4lz znaXkbAo+2_!_oXJY}g9-8dZnrg}e9>IRUo4mtwlM+)kgQGOQW`;#?)Ireuu6hR1@r zL-sSdV{3UX@A46Ux)WZBfc0~HG~3pEDxPDzDlK~=;nkj(3fw<0ODBPFrh(6HL0XIS zoWJcw#54@fb32u6e~J=26$6UFn2h@w#u93Bcg-%b|0k&6!LL-N1jz*xdX%W2r+rt4 z<6A3wS@z^<>C~6}R_W4_u$5%l((kdc!F2+k+?&STZQee<v;NwhEyL-lsjOf3*djT> zc{pVC9eVpgy2|ZvGP0$wJSgUUI&GVn&wlcKwgj>$?0Ca^+QGV)uw`G&EQ91WJ~s^( z^pEtRUa4SG?t$+y)&XYTkH-Q+7fRw|@8}Mf!T=7A-QJfokUp-K3t{95&{Y|9ll2Gf z45p9=@;%G}@w0r%%s@#(6q$Z6N125R&#*huhI$geo0&178v4_PuBSR71BBNJ*dB3X z`g}oJtC4!Sxl}Vk2)6t9h|f~pJRqcyL!beFZiVFwr+SqN;Nj~307&ye$zv6!T0|QU z=y*)(HY9we^cGTih(Zq2wf~EdqNJUydz7=9WkzEy<SGWbhOATTqD)kb1E?g;{D|mf zmidX*!ZxXJ{<fo3Z4zpY1C^J4pswkTfKV=f`KSgo+=O-&U^sY{x}ea3qAd;&S_aR@ z?{IJNZ@SDHuI96C4eMdMa|+s0tE5b=pT$p5AM%hYm9E}W3qYF#T%J_jl*hS>YmW>3 z3(^y=Y*CTmBY|M?8~PmE(}p$_-22ePw%Ho@hz4M^Vri^*LP(qO9UP*|wc7|NcUeEL z7a8C7JLPS*j+@(DreMiQn`<9xpG(hOc1vzK_#NGzOPVsFmv+bVuK-_3YnpVRim8V+ zhQLY@s_e4XLtE4?vEMdFS&j)IsZ{od!jJ$%9l|;6ZX)Nkzs*E-<)Y_{W1N~Tlm;?$ zVRT__ENz!`U+rMI|2dej8l<Eqpt+_f&QML8G5BnQ#w9jP!&VGyETf~lXon=0y<3!( z9S|u+FM7{3`j;|$abT<Lfe#-ngLJG1GYnm&;K!SX4_G}{&+f*lmnIS=H6e}>v~dML z`7J0gn{=eIyLq-zTaYCCL+P~Da&kmZB<ry>3q0Q}c!z+oVm>B*;MDH5A>P9g@%(<C z8?uBqD*uJh>>2tMkvmEcM;r)nlL{7~ky_ZUVoO6xZJGaF1a!)Wpmir8T&rA!0^$aN z@%E?qS0*%aMvz|S8bJAED4Y&rtiRnad{Jn8?f#P%j8EhiA&|Pe@4V#Yn{Uti<63k; zXv}{Hh0z4r52FU!<JR@C-l01`M6uPTJ%%<TlMUSbM*$Ot-RpD8rTjIE9z+d_4=<Jq z4O5`i6q)|4nCqLPX3M{T0RJ6S9-*Sx;66m(f8J(m{@Ddbpe9JcOym7$!Pa5wg&U}h z<n%l{x1r_hU5UT#bCc<q;ng>#AbmC>(WQ0g1Ut`n6`JUwkHnAwj(K#97hd<u?#=yw z{BT{}Zj2a<1*%HOnVWEn>tA&C(%O)lP)x!A4nX6PxmDA-0!zT-o=SZmmS;1BTVQO- zn(zN|De!^kk?GJF)`*?PIR^;H?p|W1KaxQ@ZNa^DY738NAIo?6r4_LrGhiLRGreV- z-2~gtL)*@@Z}n4oWV*^FrUB3b?nE5_Y|ky~j`;psY@#T#3$p`kaRm_)Lxz5qUOPBi zU|WRn8;?<*fxzwCc?7Q&xfLR^AOYZfVvz)k`sW3xPBa+l2e*UOF8jX2;UbNz*x8IN zMyCf$>Yk`xKSeqsp-+Xj+bDEZ;LU%z{7l*Yi;UDWi;z(01PVh*9olWZ{&?g>ZkyDX zeU#F`GA4ZH_7zT)<dJ?EJH7LE#BNEI?LoBV0lCqly4IGX+SES!xep#Ej9}ijIt<gj zzsY!(UQ|_B2=-r-iiMy(l*F(;P7RkHqFC-xkVO)WCsmf8726~-L(<R)ZsYTS$aD}9 zC^8C#@WUP!^s0v55E|&O)v#9Okg92_TSoO!ZIqn4fw_Iy5;!31fi(h4P~smr?+JOJ z@j|k??OfIUmN{FP3gx>4%Gxbk?jcC2lnay$-F0p!&*E<EU%JgS3m-=$B|0nqlo(Qn z8iBYOp6UUF!b(djY3qStyv8!)<K2riwYlTGGlgw2Zb`h~*z9V*%82I$s_DT4Qdmev zr~+usG1;2F#IpWl=qFMjo%-nq1hLaVsIKS&<Db}%Mgiv!(F_TC#(H|Nxb!Qo{@=_$ zN-SW$A)luf;ZKdgM}E4ZJ*!hMx?iH~*Gj@t{=gM<K^0nGUE1@q?%t=GpO$R=By+5` z<hPSYV)^94ts+6R39$V2{4%e^^F5m3kN?(TZ4z+rGI5xO-Sc-paGRs7rRjti59=`@ zCJXzA`i2&t+SZ<2aSioQ2+^aM%o$knROHn%`+z;bkP+ZNb8ihnVgo)!<)VmHyfnGX z?*CH=7?3$hE6mYblJnOss(6cDi~;EtU8N2j>#BSry_4XACO9;_#^r|xf<1$b1jkg% z_;n^Zak4HFL>xGT^VpBjR!jN{CEZ!b9sOB@Rm?wSOz2j`#3OR$m$PiL2fOD>6A#Vh zh$IH5J0lR*VrKlS^A^JSl^cDj=T~9&kB2|b-TSAx$qTWTi6!$9RWOUdjXHN3xw|ci zlq7C+!7WvWFG?Mg-P;D^NT!4}lF-<U1OC>vuJ4_x_dfEq=qyY3qNs<#bQO+<pXGw7 z-oH}C`2D}<XtN@=WLsOZOunq%-`gA!3jDe&Mrl?epfQw)srraVg!%CXaU3jjsFbcl z&tH@1y0TZ{a*BGHyRgl20#{eOj(Q<QnfG_atrnAm6XUzGzC7S2&!k+W7t!?*4<UE9 zdI`$Lk@6&TWTOLIVhA6Kvf8@BBeIwRjSO00bv^IV*XF;AjBSW7upA(t!RbwlZr|nR z@paOlmXi;nUfF%IPOI2ze#YvcW>YUROE+_}Sk{$j&kl{T6%eG>FOt62a+s~COznlW zuL;!s?}G)_g`)>DuQSfkdqiXAcXhAqK3ePDn{fVyD3tjqy^Ru1E4QQd9xk$87S=-5 z{+{BxQ`!&07|nUS_V6EkEffS@0|fQUA6#ep-?VuOyrFs?s^Boo3!Xi&9qV1%@^WQr z;Xf6frvsFf#`rYV5O{4k=a}*24^lzdqw?{U*9ZRJddQvXIS;N06<y{KSRP%DGzl%U z@1#+YiuZteyPVvGc-NOxPvj3q*A5$&-zu@l7Zlwlq>Zhou*0L@s|>4auDJPn)Sc{K z!T4UrlJ$-%uK)jqVcSk10Te}Loj0Ls!{?f~O55~}vusjik}{P?lVtp~iushWNmQV= za5h!7EIF8OPdAF|qL`-_^&*uy5@*;sl&fg5cmpT7^nYt^)l?{r+u#1yvF(+epe8a! zpac!-l0jL>+%)7!2R2q`-yr@SBJmw`r_!v8xUi5>?OU;*dii@%TY>o_yr<FTZCzM< z`0ocx(uPe(Z#8{E4|OL=$5$OEFqPAr%a$h{+gY+3BENXmfFQNP@MUc&0<-RhT@c+j zLq1O#0upCrn6t;vtZ-#LYsXfxpS$f?(x(>9k}YM5gr=6alGa;%9cuIFB^{#RMp4DS z3<O+TZb~6+i%}kET<tw|Da?e4wOjDP`f9W!R|eTaC5F!iYXMh>MXV8)-jzqjoLxgj zvfj#~gjc?mu*N?59I4}m*s}ZPXKuQ7|AOAbbaJwNOwXDvgjT6Q27pUP-^tV2j*Wgg z16@7KccM~@kt@{#tl<|S-6>3Yfb&$YqG4vPdlY<=@z70&-ptm{7h+%Un|V*BR+`!+ zL@}=+>>%#DPJ2UfZL}rRa`)R>J_eIuVcXArdE1sAKNs=BWngi%#t8!RV|rzX^2M<v zCwG%1;R;vLykrU)B^1em`~2~W?gxJScTGy#t-S|E6gbTV?J?$dpfv|J{Bz~-Eb;1n zlhIKrMyA%W3(tT2d+IqOpemUr!f<F;MMqpz4yr|O4#Zr(Z7YSfdDJO0@CH}tg%Yo; z5lk5_ep`HaMe;#&pEp%xy(lyAQ!Ax>>vCX^*uMFZa99H*lIidHa<xq|qFxXsUi||f zVY!d5`whMIAo=kC?w05beV=WdUWax0FP{9t28nTd#Oo$e#OcdIy3rB@OZ8cH{VF;< zx5=hzFI5yC*{f!!8#BvOpzJ+%LP0tfzukb3`}$YFa)Ni&E~snc=~j?jBp(tXBOO%z zl6!oYypHZ(R&A$fz^0KMx~ja^lG>I$q`CNj?)t4$Y4M0C{F?bIS2srAqr9%r+X7L{ zGG2%T9H3@n7|V6wc``=z!@KD6`(ruxUCg)}@39;q;l|TBh}-E&m*rc(i=b^H#oz^U zOkdee+)}B3n<pur8a{QVZCYmGG3M?&X||R@K~*K|c?+D_=Gk}H$KWM^O=8h*WmpF4 zIiIKYF`wH;(7Y}QSjq$u{pDY_40;-#tz%va)_M0nY<*w6c$%zNa{l`Z1|O#a-dQ@v zlmLTI=cq_4=gx0^1VoGvK9`&+#h_~6t|!dEMvSJ307h(8p|ogOs}w}qPBN}82UcE@ zSRFRVSZ3GNtlojamo<^}H;&iO`s-fVg=bzn#uVMb?y6D^)Zj>rX>SuGu;8o(qYBHv zFD|pNjo<nPJehqiPsjpFTktf(xJL2z<ma{N$`5^?;-tOo3E2G~+VQIg-=Eks>BCQ4 z*GL2gTxi=I!>WMs4}PLB{Od1_Sa(;J0eV5vUlbaR*l6xCQKe{_m_JL(SgKO!7Hqhh zz+*+$5*xR~xMZ+^@%M7pd{D1dU!wHGo*yvpTUmwm={ZjG2i(57M0^{TCf`fbPc8OV zZdW?mE-r18nn|X!*=6q&ELLS}c{62lM47RfjzP4qU{>H~5$7rg@3;2;z-+o*9eI0i z`!43M1i={Ca}k3DqPM<O&;P~sA9f~Iyrnn7n#L>qH93Z!XOaB5+xQLZO%>ZM?A%k- z1vEbW;9`Uz=RU>d7%nug=8TExfdyO3z`e0qaVF!<AC<jle81!0#=mkBOzZ`s0b{ax zw}JZa;SXB(?tEc8%3Qvs)BMRS-akV&TJ*{eU-6hvMM)-|JCbG)NE6!vb<%!by+t|9 zT+2;0#0}C}R3?V3Sv2ycI+>PSX7kMX$|xh$qP`w9Cn@?yEDFnP>W#RggWfA|CcL|& zYc~!7>mJMUAv(@;>&wp_>}c@rr?}f}zgamub@vR8Y?AhG*4dD9BZ8~gUhrRugND^V z@*J|Y!|3kTlTI20vJt;Kz4ZR^uSc^!X;^ulG&=62i<yL{-fe;(_k;=M|CT{N@s*uq zpXl*+OO*A9)g)`>{c_XWD{-VniN1bGC7j(ZZEk~g(x6hovGTv$s(=C>iTBEEWya%{ z07PdyX1<r6``GeQg2fYER1K|bU6RGBAF+8ZvpO&T<`W8<KfLSP_iv`%16Yby%}>^Y z+&`x|dBH};E<+j{z4>;8L(-DnySMFj`}y?|(~^4*FiWcgF!g4_y#69)L6W0|lArWH zv<y?sTXth|Fw?#OD8zrRQYXwCjzn3cn_wX8J(Dxa4FjebLy^dUz1!6tI|^H@^3Zg( z>r|`v;BRg#6wf#QGfYL)uM%9OAq}YpiP4WEsk(L(7rmC}`hW$OL*rV-UT6|kw@l`& zQfDu7|1X#eu)vfFt1YNsS!Ba%9W$0V*%`mDwT#XD{*?Vd2Yo@jxCPV?WIR%O=zWiZ z`z=m9mqEern=~x5Nh?*M>Qh5Tl@q*Z^tfSh%S|UVYMWmJ7l(USx(v}OBm?r2Eg{xL zH&ZBMZdsj+=<6@i8)(I_tM_)V_WgW%uAXE4hsaI3lCQl{DCL7e6m!o7`Moa$dIIV& ztOG-@X3mdAQ+j#Z4Wdi*gf=`bE0!6Q#^eq`NAz5m*d!+M7;l*HEb};h!q!cY)qRq5 z5QP-IHWgT7O=WIxOKfqwHCKJRc|r}>v;eto%2Jf}rGl$WzmU>kS45pPNt`H`z4vS~ z_MR=sBk$R}MZzL*;R6*2x$+PV?;4oYpnhdHYcpDMqS!y+)C{BaJlGIEQ(_B0iVa8C zC$4mzU$~~q|6D|SK&<56^ewyaR}cN;I|xb4HHWa(05~c^x4x7RKB+|9QziLVnN2H- z7+74-hS4XS*0Be+n<I0voi-W3EeHlyS_pD|Nn_a&y%2QuY{&t=va^p-4L|9%R(9k) zA1tzR0?vJ{7@A!Ir0$NyvINteOknvV3IHSh_RiL$8z-~H{+tbBsNGqWS5Z_e_)=kL zu8F)UsT>@I<U2sDbZia{;4iSdRB<bZbw~U*2OkD(t+Rdh=%;RYv^NGG0E*4Zj^MYO zknSwwoH*`3cE7+m`kKIH=IRlWd7s$B=fD>fEQ9xW3O1vlSJ9*f3kJ;mQ4Jnv1Izf` zo5k+8^&`8R(U{Y*+txr6JcQ@jKV6~!&ECy!C{!xUG_M|Oz%uJNClm%Gg0(jb?knDJ zP`OO$yuA)3iBftrCYN|9B|sG6sE?>&dh?3dW#{m47WJ&tj19oqFKR+H{&S`ybUgsS z=`-i=KR#gaMUB*`1j=CK<r5#<UJ6Wxp+~k0IQN~VpS#S2|4gC%zCB!GD66B}%T7TH zAE_|k5|MbIQX06pg(Uj7(V>Z)rK`dJeoOB+z%@?|J!L{=oohkY5k-<go`^&|TdZ?g z@2hvZDC&Kd0soR!$`MMxO~2fPic(=xIbnOXp|_5%p?reGG&1-?(DkDoY;gpE1iY?t zohFHCKp663d18J~l_gw;W?IBCRMk<>{j49$=GnBF`&Px2V`9fQ7>EO4LayitdL%Pk z9Lhwu_5vCdlX4yT23)sgoIc-|U6`+kK~9UtXxp{JJXrYs^{)1;iAfP1!t{n^V8Qik zrL=bxv;1sNtM?(To_i;77793#$HG(yL~sBu=dYz3K2<GLQv(Z<(!h0*qn!rRB9N*B ziU7@a$L<d?YiQDgDVW71ij;H&?--lDVEF}!A$jQMmUP{{Z4TBOvZ_0_mvjrhUbrQO zd0f)_!*!M6@C<+@(Of1>*sEZ1V_4R^Xvq)rJo3uUr8I^uik$uz7>1+!N$n~L->6|u zuD!88^V`#!m8pjKx@~gG=OxNSrKmXu1l@M%9ea6DCu3&+5P&K#By#R5M##KN4JgCm z>sXH@GjUL6UvZHJqBs=_BZi-KR)_^h<crainulsb8_J+cpPbO^{^5dp)mka-<G%%3 zLYOIq2=7E3Lg}b9ZOJfo`;3@Eh))AY_=P$gumCB}%kQ{D<?<CGnmMBH#`8}t{gS&| zyL0XMRI$@%Hsm%M6vn6!uuT5mcnxBmrDW&&6uPRjRDFN*4EFG7r!ECd9uuu&PKF#* z554)&M<^Fvf$bxVZHz6UjwCJTy73G*2q3b6vXv~?CTn6P2GI=(%1F*15MaNb!eaHE za~5ezki@W0_M+pV7OE@-ub+BgzJbETzw=AWVcbp%5cW_)*8pltPk2P8?HpIi$6N#0 zmm0tMcO2aNlPByP{BSvh#}i>%^fg*>KF>mR!Y5SSr-+sZ)LbE%*LQTMZH4)U9)d+^ z{>B<nhHAy@#g|Y>$wluqDsnm`_i~8x{iw|xX05+x`PjIw_nMIThjcROp>|=yD+*b? zO|9MmOZ%<-jxd}x2wtLvs7xSP`!rkN-8UA|gBDyh2{W+%w<9p%MNLzL0>#JQQNxeV zzfgO31l*PwzBAIK9Q*!T&h%xywuOcN9ZIOzJXo+dU$o$#{IRlQ3rbed#c<zen%2Gl z?#899a;6)FSM+}f!2<5jNga#9KrwP=U}nBpuRqg{=iYj6FzQ9*zD(-@nzk1u#i+1a z#M8sAqna+W{=*pTfFZSP9J?FP-n5Pm-H_$PsA1S&LJ$jjDNq_@l}cZt^#*ly2K*Qh zE4{z5D5ATRjsb5*M<`K;1R56de`8}#M{j{HJ^Nku-tH$F7d;r7a@uxXT;?ivqF}sG z=wXHtZ9M~kk>_4AjOagsqd;>Dm;&Y9!Zjw=-u}v?979}TiQM<&qE-OxragjolQUho z@yd7fH!V($!kCu7|2w480m3O#a6tJY-Y$g}>Qt5+kcsf}4d?)Wf@QmbOpa(8#bRy; z@Mjb+VB*lj;*z(^JIbaTQwUWr1@(^}UTItM;o~tqf}9g*OYr!7$x-DuMtAy?4{}l# zb_jP*gDP4?BV$W)MLn%9%bw(HtH|Cs3)raX@(9dmJ=lGtmv=R+r8&8e^^jFxT`TaZ z;SIA>$3zj&o3mwYWB*+miD<>XUr%3-Ljt?p)}Hhs)D$y8FbBZ)zrGh-OTqAXOLcDU zSC;p!nt=cvbtCuQ<ZXd{){ouqr3^8>y9kL$Wfes*zH6zz=t0Hml0$*q*?Rt%miF}T z0;B+rv#rAT2{w<(Uka@wQDi)B2XqwCl+0`{hxggHw&tqs$bRKrMVxove+K2#q@N1x zO(Eb;Z)@OPXDmTtouP4XQqhrRt=slOaqwSBMNdfMUJBm)R{W3)7!<&j(P8IF0m1}7 z2{))QV~hWR-m}Sfm-O9jwFs-1THihP1t6NGR;9UXJ@uk=@vj6LOPwWX18;;iFz=;$ zL6UO33r%qc326@5XkrW{RtVhx<GFu^pdiXtb^zimg9o0&4Rdkxe^Y=uCu5p2!{Zc@ zgU^nTv+g@}OkrMBS#T@|uo>M0HVKBRjc<1?^3R%}jsG$%wy-v6ED1aR5{kY!yp2Oh zG;&NXfLUj@Y*@Y0&^q*<;!et=H!%jd9}^2;NQ}^_)s9bL)e)q3^NM3|{6ukQ0rF<Q zALiAo3P*m!V$`L9NA$x#x$q}i@%1R%b?$eDh-Qz=Qt02}*|M<ZJvya3T6<u2GFfJb zZEn&*tEMZrzq2r@uy=oaU0+Pw&H+<mN)5WxL@Vf0e5%5hkI%Zm-H#IVz8fq<bq)TK z7f!L=;JR3MV3oL?cqk;pZD74R%-`>Jh10jNO_(Fofaj$#MSZB=T$0=8(DwGqN^x@d z%0$AktfUqIMrao{9z&xWdg&0}5CRaR2S>7!8tXc~{dr%TaiGoDD|>kK?+ZFH#1yTX zCMC06FzgXrV!Zuwv->dTS%DI_hzkRHLX19iOsIkMnwKvn<Yd0GyI%9!ImOG6v?xe= zKJd!~1ONIkR)JZ50RaJ37nKqS#(FMZAEFq^WG+EyBi3586g!)ng(GztB37l~Wq~;3 z_2b90haO*wVej_0)uB)Ia=LbS?%|h5zX^=wd+8FbnuQcSekPvPu4kgM+#s$4*{z5y z7DicJ9BXuBKl|P)@p9B*n7S5Qoyjvi0EqP%P52P8M4L4b#j)e-%F)kA=(84M2Dnmr z6IWi!(@Iy~g-aMghnFxuoNg8#6IhH|aO~AkYeGE{MglC)Qh6lkTIdwCpg)J?c1mbI zA@F3MN0>^cICh;2K&1%8U9`5M&jO9VzU~B60NWlxFpOX>bdB*F=u5^zKo*|LWXCXl zY-}qT#Y|aHSjW(1sCUJo;hpE=7GW+zq7f&ADMm!#0flJrhauW&>oBK4)&XJwQP5EU zmZo+&Malp~hG4jQy!^|xDlH~7_@z<09EI7{EfR|kPlecs93zkpK=_9~3K$|SII#0^ zO|9>lh*ln)GP)3AMQvlSv?%rHvN(;<3Y1}*l)epUGWrvaSF}&Jg+gz4tj{wL(o0fo zv5*`PtW&%L3Mi=T;*(IfLSNPxEDTd$!=~yqOg^8q@+JU%5h6s%L<=DALlanie$pj` z1U6np_p>`mH7B712hqj}X|TO06zz_`ODDrx;y#gBi}vE<V^I_#k=NW!`Dm3KhVG)+ z*F7EG(jb(Z5jkR9xAg|&Cn-l<h%LjEJA6Kuw8!akL}5PsY&^CA911>j4Rd$+mLhT< zZP%q)NN=S}8N{_)c<W5y$&p6SEY+HC9X~{<fjWsx1^}9SY&>8UPCTZll%x_<-lZUb zHS}8g+sNm_lXp&}O}p7rcI^0Y$`ha`9UNaKf2<`ML+(H+4{*!*ShS4gVJ|VF0+#La zIJG5X0w>cYU4^RzahFIWB#7ll&I=qAGeP&j+=<MwuFQx#Vrn6Z`sjAX75BW%Tew&h zL9Cn-(=*W_eF(<Y=^juxGO0%Ba(wONSt+Or>YZ1REeI*yMk!vD>ty9Ah`TkE^cJXu zI-51Uj^8SDXP(JyQ3LMS$54=za9qH1WJMW{lPycn0mZ%h4dzMsy!jHtsU(&uO6%cI z?~uGd4_t?5mtNUjt1X{8Trl6(NDK~)&?K;F(8Yrl1LuO1xuxRr*~GGnOuhVfq#09Q zwgw0My|aUk4Gg9X7@hKaY1m>~|8B|>06~s`J3}&6AXC5=(j9(ilqOYGG~Frgd3Z<v z!!nbu*!Ly##LdUm`#YY+>DvsdZ_3M}Hq+<_IK6de0S0t93-=>hVu~SOlI|{s*{Ov? zo8PJX+JFzu7#T3`*!_VArW7osG}ZO2T<gRP(O)9(Z<;@zjP2kuYFA+{sfAbaogwa8 zO0EaQff)xL_s)UBT<fKN|JhW-^hXQqW8dB~9Y*@!Lj+@9X8D)#S;@CCqkq4$b4#mZ zj0KCtJFEwFpdo0PcDEIz1q(-PpHLyn<lf2b&4U~FqZ(d&6x9AGzo5`(+x{J0X_n=Q zf3hl>zc)LKF)9``(Fzvg0&|$dxhP%?plIh^b<rSoih4(tqiA^Z(JunorX#QH3Jr<f zO6%h3M`s_e_20GY=%B85sO~fbD0%4O!5e`viB3i0!O`vCEzAjFQyC+U0o=rA`Lb_{ z<I)wUA;3nN-Z{>EY^)qW&bTao4CI|X)E%6o_Ot8QH_2(wwe8LA<23pPHy5a=8OvR+ zp-l44vGc38@-&u=I%88Cwa}`3H!P{id0FUuDKIJ(263y=n}|Zx(oS7+#qIQ_C66>S z7AMZMb<zU^7pNC;#>&bEa`(IGki=4Kk7>b3R3WZPvD$;xjfGRgpp?j?$L3}9<{1BM zTkz!IXk{b)p)Id_;Sl}s&)qtwson2zR^^)4Srr~Jh4)+we#L+@OpC=y7--@lX++Ig zX^z_P*mAtmO%(+~K<cAl9pkw=*g)4LT!=CjwoPu8F`lj)amx*8xT^Dj4k*aK=!PQd zb$Bi`DMz<g>l85<AhbX;?UkLw!H>PY2TZX7&~aa89?B<v((#>3Xh+mr$MW~Xt6|=% zvYE!*0vAzeEcD)eb&d1IzX%S6&qW!*DMA=S;tP&UcUEvv?t%Gex6a{4Bct%x`vm%f z;E0nmpWupU7No&DVnK1cYF%G$<J(=#M~R35m3=(}rY?pEr%t`H53N3&kY>{4*RHYL zzAU+pjAFq!A@#DXGMhO`PCkNI^u;t(7WGEFvis@IMzn<7-C_o3ZJ(elTlR3vb(1LB z%7lVlR$v)D#b$k*I)-+8Ob^?CMFzeuLC)dh(8D6Qk-4WZmpXiN2Q1$0CUTyNi1^j5 zkG;JFBbH9mO3}d|gI3CV8MIQ>9qX`z%5naI$x~RrVz?)BuSuGmFQoeJu9t=0NwtMF z4iGs4FM$vGAdzv7Xl#-3;e?}dD{k*q$I-b+b@@8!3gQ|<0JGPiXTSzhHUY<whC()) zJ%s8k?3utzvWNr*u*qHLTzY?iMZ0q|b!;jOEO~l@$jIaE_iA>!&|Q1gE@@0bUn~;L zbWfUmb{k|_IUt0zn2X?5xQMNIpT3z6-CQJ*xWUMRPxA}~?!b6uV+;fe9w?NGDybt! zN@B^NJoF_hy2t4}9lUjadbPPr$H_f78oSyqX4VC(Fe?D6X;@Srswp=U;bM2Ad_^oz z&ud4J;3F{Ua7_`oxbhGk=s|#H%LUEC_|V?3*eK0k*J~lfOE=n@BJUx@->Y)SBn%Z? ztV(SE=Gx!rB5->7gdBHS8pJhGx|Xs1AeSDuTQ9Zr>cPJw)(oR~QJWv|EJbT(Xbc42 z2^$Rd+w;MYssp?NOq>!S>%%WV>ZgOx1r^fCYc(2J;FLjfJ$^KhgUJRsoT#{?OaETG z3N617@@Q)riv=Z}j0lkWc}=2y__M%p=yr71gZhS82;uh_FxraSezb*9>rTYmONGby zTIifjMZX{6wFuD@z6UO&81bdea>1QOe+H-w9^f{D-ALjabM)t6(U96O+&MxGN@E=v zo;%@RkQnwN63jKA6cJp21Mx`&e-uL1XQue?SAKwco^&$85{$UScT)s+{KpdlO^i<{ z8Ft5q@W6+zgqHwygHS#}j-g`Ef`DK0Y@A{{fqZ2O;#KmbA!OsI(J5$09sf@}+T)9@ zi*Q}re;XzdZmakbR1RW#CGg(Y@%yfuO2mm)QUgGQ5CthpQab2fjQrbHjz~Zr_aiEH z1d2p%j{=eor247%IO(ulkQ^AWndSu{$oc_$0MSh-ZVzjP)?zl!9DO-=&m6F_ydZ*S z(?PE-Wodwh4L%D(XbnCHt!1?t*b;#^;xJV0Fn9vy1bK<qry1_48q%m+u4p{#3+hE8 zp5uf<-%NdU#U$lBU@EM=6!Hqb0YNE(QD@p7ckJ-NSv8R$2cZXKFLFT~IhD(PR1|YF zujLXejaf!$v#f~3v0`3g@1oF>3R0G>DX>38UMsLft<s}YqlD@oQ*R_=0B~N$4<zWa z3d|%LCgW?+Djyu4sMT{IG9X0tPvf18fd=?WbBRI&{wA4r!UlSv@j8f-0dg$j*g7Zr zE}(TeB$+yaJ}9#J<MFPjJCH4&ybT-R0^qPsoQvcDIE1YcZ-&sRzdL^t0!R}04rpn3 zaJ2sHWGTw<chtxmw>g<sIu_+BjtM_G9v*0wkm+_P@nHbv>q58f4}hA0CGE>C5q~-Z z&2?QwD5X&<ByCc7ueu=g-(ZF4(lf6^$pLL<=BTnj45M)^ApQR#XsT!4xHYWS3MIJA zc&<vnJm@->BACTpfMEVLu(rtWWeIR{HC_bTgA5UX--1kc^*H6q3%KvvWq?Eo^#&}Y zc8HZDQXzrl6Xe8Ew^Na@A&3JZ#EL1pXlaS0A;~@9*`n}(+}AMzg=u4XpS=%m5+cE| zIS5SA1E|2)ZifBtejtY-=!X@I<^bdbtqY;|e$p0<xJd01Qw}>kwi_lD8j3KtLQ63y zAeAIuuN83RsHmFZ;i%F)bWOl)VROp&W2a`NfZ>V^nFTGgKx+}zl@mjzHfEJ&qkM); z5NCDYdd!Z&GZ2y}`Q&GRK~4r39Gao6h}Llzke4^r+`??5Yq$i(D-M%Zt|-{k)dB4j zx|dWE;RS5LxX1?ZXuw~{=D5JxaMu*2^}(=k3;>d11Q|e;T1xCv(5lVqC)pxq55cm) zjgD80;*x*y^-{J~lN289D;zOKV8f!)!;i@~;IZx;MeGlyN)qiVpoE8R8$2B@Bh)R~ zBmu64cf^Cu?-p{)btL`<9)YvH#(oN(4?B88R(Y0cgyF=Z-vXXmvVISe8~AEnu60Cu zndd;fS`FHoCxi>33nL084JX8h0S*8&4i^Kuwrr$Ijc5*xLLVLJgOStSj1UBleRkX~ zwj6#0!4Tv{G@SZvI8hxar62(lu&}k>RY*icQ7so{-$Zv2To5LN{n<&{bElYM$$O@O z%2kVEN-R+$0%V#t>y=#)E<`M8GKHplEJy>9_=D)wkrp51ez2)lC?4U6NXP{BIBXgW zx|!rzr*Y|lYT~Iuk855tDFKcHkA{tdYzeRoA7Zbiyp2>{6VOKmxzHHH$YbHWp#r9r z^rL^(4hD$@K!5W98B1{z>&?ZPaNR@}mjFRHIVa?y@h);K6<VN(lyNGmDNSJgu*C|% zmLQ-YVduLvhmu8C9(UPGdMB>Kux|#^JZFLe37Qy*Ad!lL^dvTuv};f_LgMzE7*jmi zx)#I&wLF^{<JX7>#e@sB4)2n{Qee!%Sib`EhsdVj1<uE_6v!ki;f~M!a|UUMy@bvK zs3buSPwL23qT`Hcxn{$0Bua@=O1GA7Qe%%`Nn`2DEtaA#J<%J5CL4~E-UBcV{3EH~ zgv|{lcMU)~2?5XshI4~33!PS|L}C<2rN!H<W|OKqW(C@`dfc0l$AYFBJJgZsQm8{# z0AE7pcthXDOzvVLCF3A8MoN<fz%6$q`D_%F3E2AGB~sWLo0&>|WrrjrmUKgb?iHF| zef3=cf>MN+=vXDg!PUE&YfC%RffZpn+tG!Vg<2Snb~-U|TM?Y7NuX!efdq6>Q7WHo zg%L%Owi=P29I}9jxzHzVy)FZDWgUv?;~ir7w}0czZ-(j(K{<R;E{ijvS|ts{*I>@f z%b>_p2>0X!T3HLIL@)}YHU)_f-cKHiL!3=~>nQM*?E)8tX{uGV3KJXDI5q&MD{ZPw zD1`|3;sM7aK92yxi6qd{^~wvg#EA>mRYA)eXd_AzFs7J+K0vS?W(At<$dExqkDGDI zfz)$LQY-b5=wrD<8l_<`FnAVURAMLhPsjNkhhLDt5mEGExL#buc1(goV-+z=K*3C1 zLG7_e$PeHQaT{7pqHiidC?KJ1h?ENO#nlc$e1<kse<_a<VF+6elO&4V4+r)jqmZ~Z z998@d6jWNESva1yc9Oxc5P$Y{{&Dg^w$v9$&p5ymgFpq~7y-?<RbrZV7sNtMbM+Vn zK1}LpbwMHXG7!%Iox>ekOJ<@BlX)Q*yf{Dt(-CYzosZ8M+|a2Nqx&sZh;9bkA!+&e zha*HEew;fTfW|~UA}Yv0vLysD^v4|-uib#NhPTBL-#B3#?l4}Lm^3a6^$r1M(9(M$ ztxflQLU)#T;_Zc&+vFTze&&_8(%SSOSR+2%i)l&w`}Dw2^jax&dx?M@7X7;PV&gJa z11#GZgX?dJW@x=DKj-cfHEAH6Pa^nDLlRh=$y&5V(wAgoGE@8;>W&YzKrJG`q!XWd z*=g8;4pm$cR5_bWSlz1l()dN(YfhtXQRd=#7X~RS4XRmXU=Q9Y7~vd5ABFMNMyIjN z8WP6`cFwXqrT}}Og4PRVLtIr-jDR##8>X3Rp*nyWvqUuLe{vh5PHqpO_sF9%2^f`t zC;;<<a0!N47Cj`$aGC&ppu`i*$wGk!SAJbd|8yrG%9huzUO{SZ0D+^Szyy>8a4K%w z2?UPr<jVkLA{-7{4n{fF@fis-YB2o<+5~VT)?AocB86AGUW%ZRXak_PvQ6siF7`)8 zqHc$jEiMIse;AQ+SacYr@z%WgXyykZNObSv;Sqibe9jERcvGeq983g)V}q6iT0Ap5 zcswZnT}NCe#F!<#7aqRv97fuat->s`lL9XU6~qdMu=lD+Fi6rrA{k)TZJu87iC}by z8PMT<U?5gpU=poJcZ!K)&l|_Kbh&1YHEjirMh9}r6r@%8+s~k&g{X@ZA^|gVvI4L1 z(O?TC&y+FHg5iZs6dH80$BE`DXzq9?mVGsduY@l~QN4-ih63I!#a)hQhP>$rz8t$j z?x5lHger<0!~gZ|7PZNcK*3HyUPiZE(_YR*WTGUc^tNOKl6NPkJ;74mIS18u?=fd# zj0sl>q!To*7B4XofJ}GJ8Q?@D))?yrBTbi<;CgDBu~1UpXKzV;11fQ<863eFTLrl3 zXq;7hKpRO5C+7@a6A^(XQ0zlH=Vjozk0DjERUmd1GTR^m0EP?BTDsaL8e7y&LVt`* zOn*B3e(a|g+!M*A!Y)8H+oWI~@`<@)0~&(t%m2_(s5f0;N5-fq*t&6-E%qy54J_Cu z12|3=qjm!pHGukvkI6L=mg6qfm^3`zWCD2VQu};NZAR-fC8Tf!+Mh~!I6x5326YLl zOTGbUULyI4&zZ>t#3#;p<H;pb2jqvu_NZ1OJmFc4I+8H*JCZ93JJ1<KOyo%QZ+Bbg zsT@E9L1Lsv8jGO4Ee_O1T=pp2bu!WidNF9#Mz{*uaETX%ZyK-dwwNnE!;wa$Jx&r0 z1ULJPxEA@=uvUgnNc3BGV@=vmnPOn5zw^xPpC!RphQLeVvB%(>zgY7rnl}{PIE}Z^ zbq`a55EPs5C+Ssgm-@CTU|r7d;juI;P@e$rh8)_yzt#wy5y!xdlVhZ>&ej9YQZ9n+ z$BBNtB9D_=CCABqhVNVjb8H&+ER9j2;t2Uir1p3@#9SeSUphe^fzzqW1h|86u#&>Z zpY4>^^+lADyD8sofdbHY9E3ktb(cz!6ktdi{(%GZnp29?oSzX^DH^s342D5E<9o%z zpcGILvL1o=vx>Ar;~&#=Lm>vB(wRtA0)+>jAz~B-74k;sq&-y-1|{QEE~$wzz;Cme z_Gxx{E<U?fNQgsYo|F3`(Hck&lv#}?xnvM77uh1oH3_s5{|vC8fZfu0jn62nQmfEP z6Gho>oS&%L=~|FEuI05k*ea)q1{MB|OCASmqzI<jxFnY(ku(M~Io%fG?JKc^2}}X% zF>^OLsCT>2MGTshc`j(|I+NHYD~FYhq=z+Q873??me3!rES7d4_qpLXS~y8OIbS<Y zlBo+i25LN6#}KR<{<OXyz7)@j>>6-A4+%o^dMPS}q+SWXu4uWSvo&J8g)dG{md%Jr z{q%+(Wy~fuf(ZPdNFUhk3wt{rP12rDH&Jj}gu99A0A`&d&T}Vu4%GMBpZ<r_kDhQ* z5^V7zO!Lx0F&^<Fd@s_(EFBuSkPe~b3W6B%$bCW5l|c4QI*$zySaKo-nc>GIS!~PT zw`;apit&}V&|!ke4m-mo(Yt0W8Y;|SKVq?XxZ(uaAhxZ-Ya-dxOsq?QRusl*B!^v2 z4_6C{p&WqgipxVXo#HhF{e+GS0(5tA4zL`2(72hFluN2oqevC6&o2d750sC+D~AKH z^r-nE6>544v;q;@WCRL0?NSlOLv0Y>V-J~d4M<eU^AAysVP*ra6rP*vaX*K!Rnt_C z;BO=kOiDspAq><Szm$XQbV^9vC%zqnp-k?29U3-e<->@gV{jor_%>8$VQ96oA6;&0 zD98|FVcknEt^E*5vl_>(tR^Uh@(RSaJrQkp4#j)HQ<x+OQ6yfzK&TKC!+RPuNX{n2 zBwSl+EqABEavFo!C8l$s-2;yGJTNhMb5CDT*^6|fMh3777}NzVNNLt$*rZxoiIQaN z6g1$$9+R~q7yOC83Mm)v8Tkv}xoCn%&;r{@q=kobWKp<HF0mA*IOM#}r?NUkFUhGl zV-gYyi2&^Z1`5XI$Z&rOY>^qT06r)I;XZ5RKh8ksQvnVtNi9SQOe#i>-?S{*L4imS zUY)3Wcm=`8{m;k<^}NrJwvNLqJ#*18KMqjAYILQ80pjC}SAgOG_XijpDu#m8J5`KW z&6Y>>ZkR}*J#bKfqw`1#g1!uV7YJFCczOZc2hw2Z9(UW5!+#={uH$>=+k>5)j#Lak z1PxlMfRO^i5R;2IqP=Do{w<smUXtY9$n$i6lWSfn4LZgd#`GL4&UJheWb*GwtZBh2 zPP#oj1hj87xOH8py$RZ_V%hLJ`G7|e_}+?}KpYlOHZRH&g?_-(u)b2>b!ezshtE=8 z*b3A{^_nsC#HmrOP4PvIRP?3lvx9`TfJ4r$z<mm_XvWiy*kp60qO=50fW-j%!Yt2K z5kmxHt`vp6HXS<sSuCW6sEw`V?{tx(MXDdMzzXRu9F#aHJ&==Ko-yHTLGx$$QZ%=w ztAhy#1c(4AIZ^F4Ggyt_cJIZr;OS4C>W2B>&4Dro9<=?pbQAEBKr-EljRT#5Is)QT z4gsz@B}7IIGiU+#;$nE>58w}Q7U$)m7%oI2b%@bHzyqUiV2|(^o7r(7#;{;#0B(=r zN{&HwsZ0o4WNT@Z3fj(01inR<fOgNWLVhZ=p#Izf0B=2@V5}&?IsfW*3J~-Iszw-^ zZZq4_SuXHwFo~yqgzhPUsI?)_!19gFsmDv=^b-zf<x&zX0s^K#0yhNxl;4a@0M(F8 zCEbjOXV}x1tGtHeO@>S$+rASdrf#Z~SlWRAEv+KQCA%C1L9&lTNs98h_+M}{;t{UI z^y0gS(weyotBTR&P`o4u3bS=VI%%2;jw1vSoPDu)A(lTCaNN;Q$2X5d9wFG~N<Vjr zMk*NBtcLx<WFS6V`Z$yY)*xmLaPjz;hL_+s`ACM@k|fk+&B{?l-&1)MezXdQNe%_O z6*Bd(X-M6Xtnsdto{_A+qi0Z^K|ro#mVD+g;4T~6k8jIQe;Q2<5QNJoSNaf}2a*yp zIhgpSbF8oK$j95I3D`xuV3_IUH^_A%a2zI8E~>)D(g>Z6P2q|l&|PJ{QcyCRo;pWg zSJ_K>;}AaWN@NP{k>b}teTYry3B;(Mh~H*$>xYgN`XGVX_U>1jUcd$0<$;9yf7gp{ zB*&G^!-i?A^!042J>V~~CaYYWu=+Y#<poq0@x1U;Zc(;`GjG6(krbOQ-4}`PCZQU5 zJ$XzebG%)}1?JJ?E)`hDILrzFe}J`Z)+uBgq1%#2#ws9#==x0*3U!(yd?<%#)NF*B zKEk$4Lm__AAL_7@)$-;*?VXfB5HT_)tQ(Jbap#~d*xiO)#}c)XYY|XYQnN3jGwFJ| z6OUvtkwpeA@UC5mtP<V`@@>z6g$qec`K6kJU;>6ej_-dUi%}9W&MBIl2Be`NYhW%F zw}=U{+s9`E*a#*Mi;_GkxSSW{Z2~@VM-KZWG|?t!N#B<^=R_xmYX#1=#$E&;s3wtg z59DjW^Mn1@P+pS0N+&OBgmgd2QA`O{=*HqBEF1qIXfsp}z`vN3hMz$ms^1TeM@|wB z&n309h<lAjwQr;b6M=^8-7v!IC!nL4**amo8xtrmyd%cc0cf&WaD#$XFDEw(jAMv~ zx_*mYN8RQYS5xk!*a86<NU2NF*X;2wR-hj2u%M%(YDDuf_Yn9&M@Q-(E7aoN;W^R( zWuoZVj~rMYWg>c@!49@K6otA!7*)eH;`#6<IP*0@)C>1Jun#o$5iRrX;uCi(I#__8 zKg8ZGpok36CAU!ER2n>94_i`o5!lUCbv%Klu+>n%nJeqQ9m{i(Vz?wZxTO2FCMYs< zE1(m^s!LlzuUBn!PZ44}!7=ne_Vg|M!-(=DAceo7Fo@@Eh|~0KB3DR&oR#u9eyHQ) z?3zfuv!lDBN({dZ<9SYCJH<6z<DtBShHv;!-+3&{7FeJbu!B5!0eR85f8*oEK}Ji7 z>)*XPifV9|uBa#V3g;~dc?dXTbrz<pHpLiIs;N<#$_37!V}bAE41N3)>chy?&_8hI z(%;+8tp0?LcSq6FWk30H)>k-!aM6}%PJhoy6k9LWloOf|ykpxX=fo0{_n@v7u=cU^ z(;02zK&>3`<N)66ghFTAKDFVV3vLlyH0(N{0m;K!G@29xDTf=ok*jX|0L{-hT+-tQ zJN)hzs<Bcz$lf7pr9JN2fW}mLq#K}*(fBI*kL}1llBI~AdU6z^D_td*PhNKBf5dk{ ztnTACajdaMJbBm!KtwUAlPx)%qaXRy$w%Nr6A<nOjruYgr<Xfq#=Gps9=m|mZ0uqd zDk=x9Zjoe@v3YfV4FO%#xwit{hn2#xB|jn_H4k7mE=pCUNc=;*$+-Ytb0a_V9xnMh z+@1NT{xl==mh~5DQ+g1(aN#UA;-z2<TJ8g;m4^=DQ~+@lF!xD<REKIBqSMsJ#iv}* zMx?YJAkXCpuQ^`dK<`JTUp1ClM1!F17Un}aAz1HOfJZ!^uI^YrJn4`lCyNXIQnq+9 zKuz0p+@34DjXWK}Fz7Ko4BupnNfeP~Pl5x2Qv99$tJfOI7z_5<Ha%EF0xSUCP$&2| z<<tm^7f=Tt^OoJ&%oK#wqDU6GAM~A;^^1TQK@S4qvl8R2NEl1v_s2mslKY5CFG~}V z>;_Oy<wzt`Q4ZAv*{M;Mdu3OEtFM7{96`oyGq%u!5;e;35^^M<#;$n28<r8sds*lE zRRsZrI@tsJaU#}#>OIg&#z{x`_qN4X<}4<So5QUD3G|P1$dVA^#kqUL7yc(p6uRf$ z|A6=$EE!aDR^e-FMQyN`CLKak#pv-o&M!yg-&hW!7DDL2sugnAg>ZW-rXV969*f%% zu`rz=knm1~0|kr;upx@7$WT;YMhr?|tO8oa*^>J}L)tYC{g6LJ@w;=@?+Dba*KyK` z+lQDVVWC73m>TO5t@_;rEKY!uJSpsB@q^q45e$g7Tb=2@{od^G;ikDO&|8cEnL$*% zT?NU$C5YXn{4bTyiJ1}iJK}C-1vl;hP_z<5k5Y~le1vlY-k1qpA_zJ%fXU(t30-&6 zU#YmPp)oWnU@D5`9jKHxp+7CkcH_)j(Ev<v7u3*PBq3Kmj@*roC)r@<R~EtC;4*>~ zo5S2s@paetSEmS%@TVf;If^<Teg>IJfYDfeSj*AsTgt1g#QzF#(ZS_{3k7P~){iA` zSFfuGJ`7<UzB?iwTn-E*wv>~E5WqPIFjwliR5WS_nL`9O!2XES7GD6Z97h3FT$}l9 z{?~u9X&P!}!kJVtJ6(m6E)3-8@!PBey;~(r!2hLaOS^p+C%UIlBPN9Oh&Bi!^{{q% z%U%xp!c|DMFN{wJA-ea%ocKGO1ASA+V#CIxNC+$~n|(YQAIk(*!_y<EJ8}Gn&mz@v z$b!hh%Lh%OKS$qc0oH+#2q&ziq=`{o1qSX7_F>cp>S`a}M}a^OEhMc-5|7(O62^W3 zJ_#pp_2@bzKx76R!q)$?^AA{@R%0;|xbp4J(Io<Nv6l`9<G1~vtZ`VPL(7RhYB{La zDVwZ%`qyq>4vNqyY2|>>pkioYn3KW(CsC9+2^V~6+xg@Jd}$)$C=QC?E^+VZK6Men z|C3AtWicH0b?lQcG=$uTqjvd<ruWZ}dYEt>oZ52<!vw#sI7<}0Xpmi^aP2pn;&why z@I?zW3f4f6Ffk~FfLowoHYXc##0K(z@n6D+kCfrl>d_}>!YIx+!<O(<;BBZ%2}%7s zXB;MlcjRK%2{*-rM?qnPi%Tp`zz*w9$5Gp#Y=y&P>!Ie@(%;sy0w<vmCg2<#5U#%a z*{XL0Re;(+0wE3tDp3TjnU8;aiqV&3wLTG5wySiotzb0JXfyN3{~1yGu`qa9G(v5k zwtcV5Q&A)cFKBzgb4ozXz~?CNBqxr$$W$FrO+X-54s~i%RM=awJJ!&ZZ(?dkPCBtI zBG?vYc^;d2D5jel(A!c|g(J}y=diF6jg8F$3P<ZE0(m&z1TB3|4WO3{#fVdW`(zuM zkapw8VP4?chlPk&PxEC<KXrr|xJ`~tXUS{7c4%e2|Ky`gTjXwQ(-1L@fR%Zq=6DZB z%O}Cs6t}2phq6@P%O(z@UDN(3y~gY2f+di4$icx=<FimO(F<T-xm}xl#XGAo$rsSQ zFI!;g&&G7ts4TWKf-{X@XKvXOkd=)YprY}qkq81XK~UgE#0?(vpAPzOzI)3mU-1@4 z1XxflB-s`<06wpY)k6$J5)&5B`g`Us0J-&_l)*j1lreN|uv_t0Ec2hURT%xH=XuO? z`n5v`+<*A-r6%DqjAAqG;R6^#qBq{W-`{gt777iE5Sz>a$?yWW2m;_}5HQ|^49Rzp zPsa}lI(4k;@UI<8;dp73TZ}d=L<rzS5OPRJFy|mTC4BrpQNhIIzwaWSje*$e^Ic^T zW;8Vh-S6=2a+f=KllUJ(JWb2EitS=PM^-K-DmK>Z`DX<mpzx&1aU-F8AXhWY<Y#e? zBo*OVJ}VT1BrV*-b2H67G*GBcJ|XnNGH+(fX|oc^AJM-+pV+4nO(y9w<P1y*xIvDm zAH?$78_-e;L6RwI4$+02>gaB>{$MC1fDd8=memyZ{=g5u^*Yp#0RaJs>P876L!?h^ z!*!4ni1hoC8Qg6Nh!JOrsZkNElztt1=p5oEp##7wg5IjG9sgykdQuC?KuBAfIoeW0 z@=K1mnjb(zsSs!hDE#?{nW>dVuo{qX;O2|7WvWb3=qWFJ6X7rg&Hwb*i0$%fKzc(6 z??JK+dv{Y4IN7@$`mHdQSaV8udM8>viHub>j=I8(j^fC(6stR;H2veb@On7wLIR*2 z>%1EJyWzuP$OTw6pe}qN-|qOr0vljWV}tby5z5iWx$wgblStHZaO=eUIr#6Ae!7`Y zgLnoV+@F@&4$xrzy5{KpMEx)u<S2Ja?wd1U)!2F{KZWkWAgtKL6540AIRgO_@&%4G zN1>XIZoV)pYMi)_n+Z12^4=y#)_uRsEG;iO9yb~}DS{w!+4UY%jJz#K9sc5sPwEDG zki1^@u*NjNPS7JuBD7NF2JO(2EVdkOfY8F|LYSD&t26f+y*Hw+zkn@vB=7yqW~N@u zcy=W+W$8#gw0TGs0<_iwTiDkijq=!oLd8y?=J4f0nCFBQqS@l5ZKxWIm#_&L<MSVz zB=;IJ2e@|}TlECh6Sf1@Akuj)8tZ|T2*$#%fDi#>1?;Xiea~sE7mAMhfV!E&p{LG? zVn>SZfKg&Lm&R?nj)U{l#D1{70$T~VUI{W6=~8frxEHVGxg@ZlL=~f9jl)C7{}kkJ z5kL>toQ9w|gbk8_S1O*gIuOP%M^W1H`H#Kq!7wWp618AJG&<E<L8}n87pA%pBD1`N z&=n&0RNN~$DS0D~J!oBxs0B_^6q>Q=)ag>u6wCZ$0>hn6B+*iPG$LZILXe2tqK|lv zfCYtoxqw-MNrY)!zC9BO(}H;)KsH9<ykHO<<5>E~1hUAFdGeKOj%XS#<IauO1OVEA zu-whyz1SZ?cmTIACusnNpj@;FRcwSzelO8<;R&E-EH;>PD4Q^8giyzxH>th}5`&J| zweH$$K&S=~>-hkss78CIY@?X3O|7!bPgmnswv@co4&`RC#)%|2ESIY2=4I?5cnf%d z(+9TQVg9V%W@|hNKX(bI&A@k;N_v~7`C8Kkw9+Mr1F^MHuEGH;VSVKz{~brJt)}BH z%q+y&+jG(pbucG`zZMVlmdr=NGr11UqQncq+AW|g5&bx&hVOp{kS5c_5P>6D$DYUA zhFlxLwE6+{d_^pJgTYK7#~~3&JSeHiQ!>l491^%_GgZB^W38nteP<zJYH`|x#}u1U z!SyD7{{OXfE^tlP`~TOngXZawc(VWL0PDmIuW$}l-X@Fk*Bol|ju=QKMrLKABvW9f zb<{3Q#!W0Y6BHE{^OAzdGA%%`1t@5#s0<JkkWDUQ+qeJov(BT(BX8ro@AvcleBRgB z>-DbJxDR+@fUL|Pbw8?fbW3Y3ta66>&QyeE;s(V-JlOm8FP-Jpx^+_NU?FSSRACk< zLHW*cgdfvIlhC3g1d}>W4^f02hU+BIH>YvId(|rsy;m(slWuL&^k73H=XoXj_K%}S zaK4wumwlpzU%*@<kT$^?p{6+De2J0+wm4_$2EQvVWZ1S+G`WG0!}Og;_OkWeHx_Pu zI4byriF$QylBIt|i@RU%d}B5-<d2h;t)`qP@83@b2fJf|qr_OQm|IHxNsEG=4;OpC zB3(T}=yCR?!Q9D*K&63ORn`(*L?Y;hX8i|>{_GrQ<!Mo+iJNX(MI*P}1E*}w&+!}a zXlZHJ3&YNhEW7#v>u|ghE8B2U-sKA+s(<96VV=z}cj*TKmS&X~lh^B1@~`PPqA)(0 zW{T2fCf1AJ;rB4*S(AJElS}eGQb~pP(NKS|g9EUNCNx|XG}$)rdKD?l{}_M)jj}qs z2R#tzqM4{CNb8y4=lx3hPZ72-Og^tPn%06lpF+pVK5HuS4wEqAkx{|fw8?z4Z9t=f z3LH;r0!?zm9IsV@+l~O0n+b}nJ6=Pr<e(w(U_ZTrcBg_xjQVCfW%7OpC%bhHeqB5c zC4bQ>zVfTrTb#ayE>nqABdWhgGGh=%3P>FiTF-UB`*uVGTbC#i`P2k=GWJ3BSbm4= zjGCL-2iU|fc4rGdsY6Z3!~i)+bSOI%5ds(XW^Tp`rNpH%>=rdydn-P3=bXP>-gzh< z)%}S$B;(Tl1J4)GsN-Ngx9I%`;CUVbD{)#H_e>&~+oPf{g!b@&8vWuE!p+kh<kYn9 z3VXhY_9Uh#^A(U=H_8UB@Lem4y_6oN3^?U3V7wB^uT}?Ow75RtWEvJPi`qb(gEVqX zehzJh_w|CFgR^O^Q%aLx9!{nPRS#x~d(DBsD{p!T#@L!xQ`eOt;5%7&yjjf@aBbop z_=+;s?xFMEJAmvRMX=MZi?P|&WlGn2rO?=mHKC5L=&P-=3qW-1H>3=%3M<)>&^st- zenk6XaERt+7&mxM)ssO|;Ef_=EUIx6ER0|v*fu6%4r-=M-d6P9)K=aQaAyHg&^yDm zasn*j@g(;`+k9!gdM;TWPe)a|WB<Bfb%MZw;d4B3#bdJfIL485!}&z!qDk!gn|OG1 z@b^pSfquz9LbcuaR+iP+S?<BwbT;`!YXY<F@D`?@6geDdmhPIZ<CDs{2_e6+f01{n z?q-UF(7qu$+L02&L1^Fgs#S~I*zc*;Glp*)r!NbQLx3#yzZ#~6Q)+KC3*gPZv}#as zoop*%`|>hWcmaVF$&`Pj8AO4TPh<|5S_#(Gu))E4#W`&Y5S-8{fAi=)X05K6ubpUv zDn>U?jAN>!@ov8Hvu&Y$pjX-;@NII!+vf(0j;vu}`NQ8aP+%=aZ4Nh4>yV;SNFnw= zVoDp75(W5!^EWNvKxpL(QLYD5Q(#|lELtN9q({k(DJ&=%ojh>f%>T!2Wvj@!Ou~;U z?~T!pdo$7ME_0tKn4cIwGm^&zHUgfxLU#Q?zynuGOt#;Jj3W`FW9}cNb^08Tt-MV6 zlT0Oc{R!b3qw7;W`^Ny2KA6U6!Ro#gBEl+qy{xu$tYF9Fa1lp3%>h-!?=ih&)S*=P zg|Y^3ZdRMsUxtON2*6%22k5p_py}};Akh3~Z{G23&poP|b}UhZv%GCa2je%)A)uAl zQzWY1e7=XSUxlyek<M0Hr0E5^s~-<LCtu;~LkfbG&UYQ(bNk{ls*dOWYP#pi`lkh? z9=>Yvdq@(&Pbq-a*xDL;rh!}aAnz>U#-WROmIwjn^0ekZ7;TtM!DjpzjW1s8?{4aL zoGRzVSTL313P30rnl}kWOIa$w48UXdF^-M4&i>Zu;EjA`0)4j%>MH5(;%4Hj5F$d+ z1K<my13%&4lbK3wQxZYjf7!qJzN~M_qG6J4<~DXVz;(H9_=#)WPNY)$@>*1j=|GqW zmBKy!ZDmd`X>*2l=Lt~MXkvtcwdbcoaw;o_r`)@f`6*?XC^8kiqmn{p((5M#g{;0p zx)Gmcd#{GB{<?i2@P6TRdcr%99Xchec4wh58z7ABzxr;!zgG9)<cS>GDRO~FqM2Ws zi`-_8*EOr1LT8YG_@w}!<9sA+wZ&MxOwEfab#z@!o!q^Gn0>`@qOVCvZ5IjYy41Iv zlX@n8D2-W+so1VjhzNR}>#0E3_@SVOtr#yHYrv89Lpt+Qhtwp$MATtWd36aektH0Z zgBFy;E&D2vdjXKLr)aL(>q7fWGw{cIiFl}~5_9?P59m9-&(Y=BrZh2eWVO5ep8w<* zN7ZO<E^*jYQZDco{bBVKR#C;cF@)a7Xt!EbGoca9s|CaE*C0m8tCn@WQqxwa2^xBr zHWxz)tf@tJ8_|!{1kD~ZiL9hkSto?|hp!5m)Oe;QkLsb;xO_$Yp|2YHmOS%5%H-H0 zP!_f}@4h8j!^*sJ9&6x4PB@gKJYm*0M_(oTTd#8#f7?@VI*^t6V5|iMfWIyq58zru z&B^h%<IS=$Q?^N?7E`{~uA#RSV3=gJ-OS-eU#f+SsxYB^z~dfSukK!TQYB?C>(OHD zb7a!1_R)6L0SexJQYM-O&@IB6SLt1%^QE+noD-k>p62r`0SF#0!h8V8dz4>{5LpN0 z7sj7|v22=ayLh(oFNv;w5dg~8d8&~v;7vQTzUECF!saHK9Dm!`^jfxS{F%YvsE@^H zeL&E0;3G#4bIsYL2}s`i5WeTJBy41eGNki$^cbLHx_x3aAcWT~<Gz5_o;lF`x0ryH z(umLYUO6O1J-u|g>5T3<rGT$H;^vlhy;MzZwvF5c44v)X^K~0g*wlnb^^)6_q06Up z>7Tz$F5>MV4W6H3udbyxV~y9C7dk>mEeRtg*?ZYUtJaw*bB!y<=Si1}9n=k-aX<;< z76ce11}}7v5}@^SBNy1aM|tAv@5(6Mx%74kwM4Hm6Lb5R4DUQMv@;a;fXrcQBc*?e zN@3UdQjwtOvYUQ3_0$}H#~=;i<!#IS@{a-M2&Wu8H+Tk}pfn6GAbiyxr^d=|4_or_ z3)a5O7R<}r76mu2q$HP*>PD|mSkKT_<vkh?i(Wuz9eugOVP1mjt<xcJR^4;p7KrvG zo56gzt$+W^uCLye0<;JZzL5YWPZ|-C?HeDKcSBeILh63i$m<|e7ja|-@1o?OAtnat z^(Fi`67FGw@1lLB@;i_nL-I@?+Lgy*g*_qTlx({>+n*?m)6-ff&I1{1P<D8b;=Q)x zruNmu1qB{(XVwaJg8VC4w*PSfl<PmOxRe=_leGVApgz$3$AFwY6>{A<Hi{^XeV-{e zPCY|cZrTVG$@5Hj_U{vRjlaBoqU*D~R6-&yx}d}%KZO>w90Vtd;~nbhUvDkqL_RRx zU@FS`U}}Zk23@16#r3oL&b^{Wy(B+2qt#O|qd`YWv)6X;+<vfOEOl$(rbNnlqW0C_ zI^7V+^2_Ytz?_!r#J*A09ij6cN{Ta1gswv93UQIzs)JN5=E0xNtDu*bP6k%@fjLL+ zAGPyxcD$~3u!0)s+)K33ZQU!#e4*wjE@7y86LMa=o-*MIzLFKBli8gTy+Hr-&XP6P z!`wOYGy)9Z6_~VH_d*19NxLptuCv#2AohVlgKh<wDrBaEc%F!Aoh;{AK}OVf!RkAQ zm&_~-nl=%s5M~u9Z|zY&mH1yemh$h)#1v_BPUJBWniO0v%m<rHf4F$AGMfn%sT*2b zHgRm4%1ZOz$#%(qJ3&A9D%rCIjM3c97uMr*Y`3if;J^9`BK2<TFiQeNG@!e5<(#kQ z>C4kC`u276z=OD3q*@RD;=@&cUs+qG$lAFohmn|-4Y=7+(v7+j%grz`0_Kq6cu>h! zxy|J)oZybaNTKoB{w67V=oRrY#zFhH&pbV%rT)chG!IdW`Lhc)ZOo7tFTDX&f=kp> zeeYQ~<o1b8lNI`tVjLz5r0l8L(f__|O;s`6kJe+`pU$m+aYaYT*2YbmPKT}}P3c@7 z=AT<2zJkaorQ=}of4xN*_?}UTeVEix#f{EtQyxVw1@<EqfsH}B_g9)}whO@;K3H&& zzT=V%RB$WZcW9`><9;iZx$m12F=1J2D_*!to^r!NUAAsc<cIg>)s>jLyYNBGLP?$3 zKC?Vk8R{KOtBW}=>o+~|lDE<w#W|q+Orxk+1Yq$hxeuM+noW;Pn>mk6NfZ%9kZLV8 z8z;$~F=<|c%pjI%U-XKjIB61a5#Xw!D71#2m*Ltwt;~B?_uT6fr4nBqbEcjDcOB|z z$KYEeUP08<qJ0(%&seqv378Y9U>E;QLVy`iIZxkxL~Z4$nMmWiGh>|Ly8a=rnXp`0 zh6Sd#QYTTRgnri=$ehe_y_86ogpMJkl%WSmxTb;z2b?;cn?Z0<*InD2k(@1**TInV z7mad`BY=$$6A>I#9+{aM<g5}Ak4H9L7GPRu3<8GWG73I=qfBm`zPhYg362{?7bwUR z5D`k!J57?(Dq?4526mVkvPHI;)5(#fxCRSA0Ga`^#)s2?F+h9)F@kt9M~9;00Ly>m zMonLiC|z16NzQ7II*d78x^~&_*iHz{(~BNj93T=pwBHzGxZ__3iyi}HT*2_#ZAhf_ z++g`L?OK7Ch@n&dJ1f#nV*(I-hg2=9UjrgU&}p=hz`3@~N^PqFJ{AP)i+)+chk`C> zKPR`baL;b8+(Txm>`r59CaqHI?#G9_S-P}Fj`hQ6|5yS|;(PGl%DRP)K$c19wF4K9 zNOb~{g_yE}w0P7&gLb$hW%?Q#(IJ}gqr@w^LLW`|hmQG;Y51rNFhCGxq&bi2f@-{P zxQRu;v!yW3iOgF5G3`g{R!c7$CgW>_G_F`7P2(Q5)g&4XEc_&;PNBPt00iAVS<c8O znUFnsoCkWnuIa2sK`4KZFBRb$zf=ow9~-7RW1tscH{EIAk(bl*9)P5eg(U^8QrWu! z8+@8zAjPJHqcKa=JODOSynH_bIAN6l74niZ0NO}LL|4=j{vA00aZjz%xngb^Jrh|r zBHwgK?mnsZwE_Cy$_x*Id9HUG*qtN&$vUaLnff17|I?91knHSzxnr2asB;|^rH9pQ zh(J<M{}@{Jv(Pppx~&uCRsT4YE)?-<S(d2lG1hDl(%3VoPs?~9qp2j{(SX!SWlTSP zqnk=WB31(7-&~2UUPpilan1+`lH65_v@oJfd6G?GrBp#%Ro0NprEY?1!d0YB`OX8# z3z;l%Pr+5TQGTC;o3#Y-3ZN-?K~hxGGlEKT`i}vd$<Cop5#P#~tm1*diuwp9Wz%P( zM3I$_F`VSOnCji%ApvkZAWjIfi}WJJ0Ou@EVM7bZibudgHw_?Kq=e4Q4{6Itc)sp} zDm}dt4^_pJ)U^P*1%*+Z^rSc}1#CRbO>5NS{!wtvDp+>r08?Gl1;H8rP2D?&$g@OC zswebLa^Vw+G>dzP5Y_9`e;4_3Q=X4ns820y;q6x1MAvTbN+dTL(}8<|!_O1K5Ymwy z|0v`X%5vy?#?bRok1|rnZ@8vx&(Dd-B~EL@<&o;aj^wdO#y5@v&=KIiAWD9`EaWgq zlzqIJW>3?2g<2%W_#H6_YZkpASVTZU=_C)J)JcYY0?P`HWFNh;K#S;0pMc7|QbjCL z8Lo#<#3A7o@boYL<Jb~<fgOW|iN}s^^Ps$e#vGTXoaLKcyd+5eA~!Qr^%1Q(xPdmR zB7+s%n%x&tq5%KI<hU;u%7;6s+5;)FALdQ7Wu_?~Mn}M-7O!!Y=LkH-xpJ9r(qEL* zU@TH#+cMwQ-GHc(!}GMNT&KAFJyXuhPlcZ6;kc!U=^qQaXrMzuxSK#`1bU!z%#gqa z6mB3VKBjF?Vj&2c8GNSLD)MC+P4r?AfIv3I;76*U95Rzs|MHWnWvCR;ZMZ0}ou^e; z0JEAME%O~ZsY8^KJ#5O#DFfoJy(uCOU@mw_^{7<Jq<ONQUrZD<sKtu9G-cB{`~fVg zn(Zz%4H)(tZ9LWqQTmw9Q8qd|9;89#l+?CW5Xj;+z9t&Hw)u)aZmOXS)f%m@hX%JC z>{x@WQ!G7`(u<MD@vs13W26!)mHDPj#}`8a+%vO~+Bv<3UmyJ*sQ>X)S|1`yPtCQv z%E|Mr%AnnLa2Pa)sLt(r?=gK4)=Jw{O*xohz)PnVUe_l0u3;yU;5F^ij2c0IM0}|O zXN(;aC3D_y!qdN%Sb|*@a~(B=fU~G*?eg6nwMjF@`=*En<_8vwVz8B1;mWEBqEjnf z-opp)<-6DBW(>98&`MDv_n*b3-`;AqH69#h0U+9@QHtuc-<%POOEz7P**q`#3>soN zkzF?kyQ0-{DM}n)QMye~>|UX@iQr$r#kj$3^Hj<X;WF;+TF&MrB4Eu0gg6zI!#eiz z<c)QNs4zpsCX3glV1%IxU94hVtOdgwxNWTil=l8d9{OMdW3m^?jmMT<&c%qNM6rvp zK16iSa#+CeME?4hQ`t^ax2OFd>E|=s=^(o|iLIoj1t0lc+fkbF0t3rJD(*_x=_01Y zx!3G|Vn=}O7N{FAA|6)}k7ow(C(_Q27J)wP9Q$>86cGVL*wn4v<=Bs`HDo##jZ`20 z(;7b|BhaC>Zr65Q3Pi?4j`9#osO%3ZI?adm<u;F)eKm=RFX?R=HTD}L{<f?T>>%XI z3Pq8aEBBW_1_ZDM5m9+50Y-q@w=gMSfuyVER88MQ0bu1vjtQ_0<J_PO(O%o90x+Z_ z9zy<!e~+ib^0eUJm${jyzT&+_T?l2YrP+MU1E7m+DihH|03WASKr_sF7R{Splfx&x zx%5hbhyEcBzkTc*uNpcMtqdpOBwmdDnksaKKM7DT(3(VeX6Y&rP33qhjQF9{LKRhE zt_cy~;<t_Ea_J%fIbPoX0C`6sJDhw<KaM?DKlj!otD#L&_Q%NtvrbC7*kr!9D<O1% zzUp!z$h#I<$6a~<&BXEe%GESQMd7$HL$&NJ4E=sl=<PN}$GQtZi3=|%uziq2lqX91 zz(t6<l6!i*?(W6%AAioi`T^<>Kw^rp&K<4kt;MVQ9nX4zJy~E;FagwHRR>_aH!D_) z$N-+@MZ-;Jl7Fl}goPT;o-=yj+xFJ)1x`)J*k}K*mkA8%1a!d<8s1y_C(>g=FY+H& zU2rFUh&@~SX45+-vR)dlHJ!%0ch}_jeMR}rMw7|0!Z+cSshtx<Xbm8*sY3O8uIKy; z#wEVt+pDJ(FPYi`2&MqoOr~)8{xX&{M!ee9b+brbhLxuYOoW9y>${;Id07-Fe^HBi zopEkt?|92&pZci0(x4!Vm16hO#Bx`=zkaJlx>Hj(2?Qf7(3^qORSx>Rcc3S_71<|9 zodVeOWHg6TfTg)Q3$sr3@9r0@-yJn51MUk5)i0Fr)~feiRR@}SXdd^sfTB=Z`Y%=) zvA~QN>S!AhT*8Zq6?Ydt`IVpVzx2Hi{oz~Jh^{&o$d+@Z34}~~X@@HESPah}!Y1JC zV`p$57N*a&`(TO1_S<JFQ~mqU8>w|QgL&~kPU2Xn2%<nkw(8p22Bva9OBl_PWWF+c zX0H#@SVU7e|2EwzfJ0mXgO;QE_hPf(Ap+Axkxo|9SX)2W?{GfW_y>~0a*tmdPtP&7 zB0=_BE_$5eV~6%zi^+fSj0pD<9#vnQ`b@)HC)n)kR?s=MV0UI2htj5dNaw=6{GH?i zvQ0tYI^{RPIg{eA3DjY&d%5rV7fa8t2y`9YM6n0$Wqjyt<+|x<zY!^?$?!hVMi;I6 zJ=a(#>WiXiz_CH`GCoEJ<rGvGg}p1@+iNz}ormk=Ni1_{O=ca{qI{_YeU2!EslR2R z{BoX=vO@_5uxh`&6izqQ6o@h13ERIK)&3>|5V4zu%7x+!@LM<Xvqgi-ePeEMDGhlr z$;{6)_VZq0KTIioyJ+^R=W2<lKE<+-G}MIa%QrDv04FGdTS}FgUr)PCAFjejgQI4v z<IF<U!(-9y<PUa60K6Q(bDcj3^T2HQQu|wM%GJ)TyeHB=*Hd62qfCzB?l{zpMRvMq z`(mPW7WEfp2vaD4rcR#yZsQ3o@ra|k`oRII+vJ-jd7^hw19A2)h%HW?)PocTNRflK z7}&6^s}|JjTCdS5XqZsToB`80mcSs!y>`#c{o~&>+|fMe4Xik&<9L!7Vh7EN0$l2p z)X8QY8KDJ#Qq52A1<XLhg~yaSU81wRY3e;PkKsR4PNh;-qy&@Fa~F4O#JJ0{7qZS! z@i3Smi|nJuomHgen-I7rGGm(p&D)n;Ko(w1fzoL<F9<AkD$;&;7~es)j{C(#ghq!Y z2*MM!;g)<V(VYBIkIn?dM;zTi!V~73b{<J35umi@Hyj+^fW8jNCGQRj(YpC5VB>oP zn?;yDg(Ya?3oRy&2ma(ngi%M|BubpXDVOx~QtO<RcGnqFduHZ!1sn)4PTdeg7(>`v zJmBoe%chcab}s{8uF$?=8>I0X1+%UtA8y}}j*>oc#z2JZ$M!*cVRL;gn7z-<nfgpT z;}UyiI>7FkSUx^x;DywO=gOrx_gW5c!cwh7juF~|gNmpcG2YPydL8N`c5{Ug9y825 zK$c1%__eQXhA~MWh;&TQl%#AQT>))An4g1B_3X#92qsQ#mGt-~HI|vg17(YB*^X|Q zH8yyASdO+WIr4N-0~VnV6%s9l+rk|M&&;==34;cFFE>5~>Yf%byWj;cZGau37pYLI zz?1FEK>k_Zq4piZ2_3U-d_^+3+)Z7BxkyT~xVFtvD@2F@8a%jn^%b2GO-A9H_obED z`Ri!^-KlYuAW6${Q6LpI23IHyS}7J+0aAj!RFG>C5GH`-#v~E`LnmTIT*vbaa2f?V z<({cCw23HA(T9oQZZnt8EHocyYgx!Z_RH<ha(SR$V>A;g+zn|Qx>^FnkG(@hH6@Y) zyxW>V+=W3q4PIq}q`fRFAxRPN!N|EFoA`!0^>bRIs+S-}P;rL6J#)Ws*$6<k_!<_l zZMrFxtRS>@WB~g@XVF$u;OIp2$cEN|=m38B$#seg1{s}@3LiRGQlU=R$GJU)H!kBN z+XNTMH-pMTifypRsE%`89HefU+ai|21C+|jsGz|v{6f82QOpQiI$CKJ;C2T1Xj7(l zc>rrI+0)l8)#V6+25l)0HjB=Q+Z*9Y(8du)@I>>pYgp3~;V_M&_Ee#8Py+G9JsGp5 zBh$#H1q-0$BMrboVj~U~1|F`OsQ;`ZjZs`2@*R!fAMuw2w|BX=fL;DRC3X#wpsb@o za##3id_jsG!*d2AT=R02h&I@Eb);z^Si%*Qy=ia>8jcvSE12AM#J+JkBWXqnV0zQ8 zfvbgKApJxX5fT+Sn-I~^1a~YjEf<M!<Xoz9cI9U9MuCi67r_<0<5`A#q;VVxV&<R% zW?7b#$?%rIv|r7|C{yxfJ-)$9Xr0BSZ!P{#sH0AzH@8OzKT$0@J)PBqWVTBzRD{!9 zG<_KD1IR^_+Ww+KB(7;owp@^kzF%PA)W9#LHM(D_6wNl$ce1B>G&l;-MIz}KAPCTG z3sC@+bXP93<Q|z4dg7tykyf$@5z#R-;68|0yLisa4yBeoEn@q<iw!!;{WxmzB^J?5 z$O`e)hfu=_*ep0Z4aGw#BL*|F)ly{$4=8pnzy(ZJieAq@^PJ<1?@(IPyO*o|4uSG2 zhkt@sb=h}6!b<DlpA+nt>}7NYQH+YuV6rN`5&tL1%klfNOX4SJG}dhN=2U|p;b%rm zFu%a#vNz|cmJwA=!iIE?+Qb0SD`lLx)xQq<=zWnVHkGMN7y+LB`viIa!UjZ;lp)HZ z`RDe=cm(KC4)AuYH%|5uz?tWUkWBtD09P9<QlcKX@Q4gx8F=_64VW;uD;-(}sxa8S zV#Bn*Q3re17$bf1@{?>mn7LZe0pY+t*|Axs-j2gy(Iy`dfu%c!(p_s-sV};M_CUQ` zK&Jk6dEh*?qT(esVF)p#bhy=i!y)UZ>T^hSJBOz0O(-fUHs~(@IO7aPUCu%;F7@E8 z2m`?a&Cegj4;{&&i%$Imn6t-TXMQXDZ@!)1&m`g@$4l?c^i3I#w3c1w(FV(0+WFB0 zD@$@yo1vAG7<?zfl$7W<^yfo$t`i1oVi;jA-y9zJpb(BAOnK3&+IMS?ryvA((f-SB zJ04%81xFH2Cfwc;@Mqj+f^h&vvf}n)9v`q~9Q$Hi>nG`$d{L<7a2;|tg|&EG#>xB# z>#i+hz>)4bjbjy`tI172&->(bs6&}R{<We8jIV|45a}9TH2lB+VdVOn-c{!@5mmm; zFK-*swA`7Y&I_CBSbZJo_>U3=P*SQr&^%&alriR-j)t)4!U<T|tkgttisT80z5c5c zazgAf6c=)y??3DHNoPl1>fndJA8?iP-&T2g65DNmTwpUCfwh*CDy0zRC@v3urmaRT z|LEOf@Q+xIx*D9P$vr_Y71g%%#oR%hf5Q3S4wq0twahkEYFt~wZ^ip)24OKtbayTg z?iB!E^g7p=RXz@?ZR6iN#%5m1Ug#>OnDe;mXa6|Y7pEF}sugD+zUSY$#u89U2t-Fr zFymisAR&Y^kQ4n-_lPS_VX_6ssEAB!W=LRlq+^Fv&d|OeHQhV0v39z`;GQID{_`#0 zl%eauyP1Hf$zu^P=!wPvz&JBo=OjJW_31}TRO^^cM9o$ky!$HoqAB6Q(@SdO*g~e+ z7`#)4eoiS!H>~ieQT8{!D7=ACh^g1MJ5}ds^;^HrHR{Z1mqT8^cB-026Mf-e&*`ZQ zFAO}lqw%CO#w9P68Ed5tWd~Al=KpuaKCrnoi9(M#NUyZev7pLPTU9tie|z?)YhXBy ztZoDZgEs?X>e?bD6{l+c`^@aawPniB-(QwGnP7Oh2NhRy=Dye0Zd6LJ0{8NC4f~S! zXo3l3BKDtq&~kohT&F8?r5s3O%?w`1@-W#au3$je?lW>>ZvDPAIp>8Z{h$>(EDG)$ z@3U4b-c-lg=af$*YJg52fY|L=_1G57-gZiynkN!hqW>23;wW*{0Ed(TR>D)v<34sd zY&Z<PV}&2@NFc$%Nc9&#^uC`w)E#Sj51tAG_M%YX&DX0QbRPmYwys_W{K=z~*gl2( zIN>=jio5B_>&Jcc?%Z?D$(z{BRE8;#3e-tURc?7rQW2d~N^x<{{!Q;|J3HljZ65*? zUjMrLc?|o=|2RzDH^Y;5X2JKe2QP7mDh>GN$Mhk#Kw5o4*_B$D-0?i(>-7syPyuj` zD5FjkB_LVu6MHnnDo8P}t|*PA59=Pz*D6tBt+Xo4_w^!>nsGl485r;*OTSirQBq{J zJ-mS&JAIq`ghi5_&zl)8Jbd<&AvpAhi(B+0Ry38suJOB^S*pyiy&4fBE8S}hUqt(N z+=B-g*r`k;$Zc9*l`^URgE+&CPUsr$h8^&8c>D{YgtFBCZ8eivbHavkqUbe1Tki^p zh!4Z4#~CI8`JvgOTC!x-#)Orf6Dn&3R{VRP2sZGLvaNCM>+7#vhW-TNRg?bH&41Y> zi~HmOGB(=dMFIIAdre&Vpni!lF+l%H9Y}<J%TbZ}H9%cEyz;>o#sS7Fw-lOn5cn)! z(w7CNmIl>-xZ9>Yl@QD;?y4BMpt$QXS5|3Mc5m&uK`GpBa-ekCklA?s$h;=~x!@6M zDffIt4C=$;{r882pIZ4K_^0#=ubgi&Vopm#LzoR=)(X?&GqeF`g0|``^G&aqMQAIG zl~7J+c^X8mBy!}SU4NB5+Wl^TL46B7QIqYaq%?_AMDEEx&ANnUwcj5DwggZ)c1wq4 z(sbKBquo^oJ9QQHGoe~$y8oSc!DZB&vjvX9cK6Z4C;Qand^97$03?m|rRwLK*0wa3 z$Wee7JdPo1^X+McJ0#tgim`Ya18l|?VwRp?PQM%b$AB3`3+DBPiEzCuz+fJuNVEKz zfpx0evL|SM=$<^JTjx9tHYfWG<vVH`VuVNmBYlQGV4-|X!}3LLo0lTvtEyL5M6FG~ z&tr;mLFE)t%NJ7rq9VSeXKY5t_@t+AffsJ~|92_rP+Z3g4FRHtUS;?$q0(>YYsN_r z$A{lrL`y3j1sxrOq`CcsOJuFi3L!kC1?Jg%<+SoLg$2^)>!$YVw`VRDQ7<#+IcOl& zG+S>*?Od3b5=YvCYXvC0=(BHZuX$>`Kwq?Vx(f{_RQs+fNX9AzOkf{oHT<_JpI9&1 zCKBizIdi+SA1w%CG*R(1OtJPtizKNdP}MfoN8TEuu$*)-gb`3=Q+06S=9`o{QwQI2 z(!yKKTWRsMk@uNeC{eh-W9ErXQCS24gc`lHKB>D~=L+flL}4D6^lEjA&SYIcVfo;j z?yQohizg4i^RZ#L`!e@rdvDw5nctSRf7@UW)toG)u-7SaeQ;u-s$Az9A$W40GY@Jv zvwMpx#JrK&H^Fz7etkBy|Ft)1p{t<NoFCKo^!+|S6>0lAY`YXys#D5_Yc2QPqc=?c zIQZV*c_>Skyq?@kUoP;nk&cIDb)nT@uHT~Uj^+xm`1+XnTxV>bk6OMxDZE;D>v4v1 z&YmZ(o%m1lg~Ma3t~HgU<qbxUB{chZ_S-4Pp<LNY*0<mxv|gRV0ck&9AeAPz3t7<y zI<vjJQfMbvKv*6#f719B@UqW#?Va(lcGcN88v-R2<1s5j2N`cPesSl+od$B{cNaY& zF76q>c}dyUa`C}R(Yw(LGGcxB_=HFfSQhwb05Z+*7am&X&Q2O?)^9C-$5Qn74e8zB z)f}zknH;Ej^aoSmg~Kmm-Oj!#7I>QfFVUa(|D<f4VD0OUq@?!=;8WQS3L*U=xtpUz zRIMLECw>Cb#hp@4eVtEArT?P_rDOCG<#n56)wxo(it7$6)AtokSxU8X+5aw^{8{(G z=syPhB`N>;y>ereDVBW;X|@Em?_Vqv+>eO-kTk%xC1#=i+L|BCp_Xk+M%kz3ij5%W z{(T<2zWL4~gAr)NuBSpZuARBpEJvl|GtIXw8OrY|utLRQ*BTbcet%MpEC!JYu+K^( z4$?L<8H4%PQ@2*#40MfaAN{E7>zBevI90VVJ&_N_eSuB<@lx%7?iDF4MeM1Q3*#$~ zCckZZm}6V}Od(L0qqq>nB2E59@P@|;2oLfWF_F6S!F`WUPyS<o&)P`kAaS3urelSl z$WLZh_T}s?v*`-ITIQIdtJT>{^SReQuQ=<OmVV1aZ|VvF5KKz<3wCAut{FQo0AZx_ zOPgGtE>dRZ>y>`5?^)Kjp;;SuC+NQ~B}q{$x#bTJWa*B3Z>&KE+~>rBKKsN=e?`pg zj{y)MXBv_>i~U<*dS3S-NV4W7B&PM`Eg8D^HPmoqRBxK{O}%5=uyM<=rg)fiDd^)& zd8)L`V#VQ?wN^SqT%oC}LUdb;ryF^D-D$}dR{DQe&a<R1yP^dAE6Q}BxN;>QFF^&Y zrtU>&6Hcs>GHqc&vpc8MUwus17g_v~z9VV7%hVsrd;IT;zLg`-0gQS*qhm_owNlPw z{{5D#q2JANyrO)PBrjA1FHIG$zw18KkZ<>B##{dwu&N{C$^+?=`H2sf=`XRavpS{2 z*6(Gmls%@NguXZ@JKpF1bgivt{MRl#xvs4!&~wS~+3^~9XWOXPkEeSR%4iSW3JquY zS^ztbi3Dp34<1pnFFwmM>+a0{W<#y6VpX8ViQzX5lAd0C>FMmQzx_5ud9|jQ9jrCe z8BWPHM8Eo{iO4XY5~9>gRHDX3YWi@`v_+y1q@OX7g`6!fJkVJ>$Q5MxwJh+$r>U>k zvf`GrN=)6H(7`Ub{V8kT7w>j`b=T*E@pP6`3a*tG9;%hnLl>vd1M0)1Fage_TspVx zAcXq<trX(A`ui=?-_1WxX7KJ$$+C`q-Gw7M_KNJ_wg)k{l{vnkvySe$heV$`kca5K z5gZqKzW=9C`rM%r5;F~3I_OQb>>5#=iO01)E5J;4u4{3fC_LEQ7x3Wop&Qn+8rxo= zZXB==+}Ij0J87epw`aM04HI>Ji_^83+Ol+I*2L=jSKWD<jJ#4tbht0z$F!yno$1CE z?Tcd_a^$L9LXvHbNHY6>(R^z5`pBTve^|n{(>wij?nl0wdHdA4;D2G|KK-qK2#DEd zUJz%uT&L{6IPIIwzfE_%vY`M|sMsFHDJCc7wMxG&@X_dCTb9Yvz*3lE7VCaI)i<(7 zcQdhUVPYc@?)tGmV-th6Cq8}ao8h5JZycF|MEafi6mIYKtZ8>VWf|V&eKN-3A0x6! zBN7=gRZy2h0Fn~WHdXi~zjJd)-@lswUu|?fc;J>958F-dW8a#7FhAmnpg-MmL8Oz$ zo$u?Iz>M)ZWmUd=MmAQZpy+x;gm4}qJM$*pgvw1+{XW&5Dct{oEAT<+V43th94)oK zh6RoNITb#PH|ff*jB*A4>K$Bpr6k(drnAhPiLF8h*Y3HvfAz<q(awb~@I&%=N|zpD zfsj@wG!t#p3hF_wv)$c)-5LA?!?(3hr%d7ip0V8@AMh20?XcuME-%A0L*SRtrH#6t z5ArQU`ks~WIuWhku?#l?ZbIOE0CIHX8K#;;r$LF9)440nGI)Pdqw(tZ{xYc#C_(!D zEJleGH0XZJEInzHDiKJ~69D`FsC4IRu2r702D1<^RrC~5bP5DtKq+cu*ec|VAQ02v z@050qOnxz8^@A;hE!!iAu9YCfYLmmB&wsE5@ZOe^g;F6+gAL(Je@Qm~YfWzRR;fXW z-Q{Sr4Ty|WTGJ}%zc-3$>P_|4yi(oc;|bByR{gXzY8xW$9ko`WeKh3hAN40Sq^m#8 zL)iDU)hLAA6s_?yPgz%7vL^j*jRvb`B>3XWbjTB13~e(S$v!EB7w+5Lr8+-Y)U0j~ zsh8VY2-e(togC(UxW4_mAK!Y=KU5dwJ)jLZUYqMu98~6tpoZ;5CHh@~n_x`1-=Rp^ zO^UUfd_>M|1M?;{VpM8V{jY|^{Bu6&Q*8_?sZh4PMH5Msv#>*`WuENn-MFk62vx+y zdBlYAn3N%Zm6nhFPjpY{`qZKLBhlsJX@uq)`W4X&;3PoQA|V&BA?(;5<?Vkz2nJUY z!f3w`O+(**JElFXP^`K=xKY=4>OT%b-)8lle^SgB!&8oO-IPuB^BCJRU1vt%!7vE~ z0?!Mzd4A2$9WbXFO`;;3svg^r*VVfj)ersc`(S!p>#L+?73#pByq`FSxbeW1bWM&7 z?jC)MoJ7|@0bQKR=FqsS4@ST6J2E&ZMcGH2t|3P9JY9%C!Cf1wOg`h{ig|O7zH0D> z;;Jq{W90W405j$X^nLs7lItm*w}06}b5jd_=Q#UipF!6?WpdK_oF2u~&X+oSO~CO` zZWZ0tu-t}<mI~iB(w(zC%56O#n@dhS@ZN%$5~ozBLuR6FUr|@^EEBA*+k+oi?S!tf zoVOsGSg25&ZqBW29$Q-Wx%xIzi0Qq<CA%n#73@>pt|Y2&s?jP@e2F-<#I@*q!r1g5 zq`#rL(UR@|wbShEZC;3TOXD8BHo5|QeQ?g}S2cKyc6<1u<oa&g(9*Imi7F-@P!BSl z_K1~)E01>G0<+J2C+rQ?M;0yfetgn`m0HD#2ic$LRwL@Px>b#_6LYuQcZJs9=_yzV zu5V9b{50xM)5h{(zX8PnY_l*v^j;T(NYC6){Bq~C>#NIpwz~8zCtAY(!?0@IJ{U?V zx5{ZcQy6=)@8pqJ@uzuxYd{5c+^R9dn?fYl+E;y8q8>I|)P%KG^}Crb#Z;MPwxN~Z zH5wA*u@7n1O_(J5&^K}4pT5%prYfK}^S&+V&91dQ6Uti7c~wZqrp{1WdPk?ZV!IY_ z-YqL3V)vVm$v3px9H}*m50!)4=AlG`C+9@?5r_;<a53#gRJY%6Og;OW=1cz&_{%RA zo}|c?!%&y)Nd$&Up>#uJkuYBxaq25DO2&T~1+@~*jA7i-q_$UT6ur`u)0Pl^tb2>& zhG2%Uzz&~0{q0{)PP?4uMmEozor$=ZP%z8NygM&xURP4Qu6#Ym;9lMene@d$Thfd! z5QgB#pQ!(n@!y!=(K~cTV?bZT5##|bd@rsKhnsIGV^+&z{q2~ov2gC+$8A3p$GkD& zvbrnar_$+E+&;X)Nd<sPqYYGJ`p+q&(|dgqbLR;doVLj!MP;~e-iD(+D)gy)rE#v! zFOGf|+Bs5_tjf=AF5O_)s|kwLrRfO(xbzmMkoRg=-duFS7~Cb#Dy7s^T;@@{o7y^N zsLp3)Xwr5Df*+ubgeZvBp>#%14Qg7vS9VS}3{%tdLA~4QzOi`oE%P>3w6Dvqz?gxg zeR0|%ZM)pG<Vq~%T6tP<p52Gm3M2(Ao@h^9*jcyN1KgfAlWLlyGtgmcjW0XB^7`k> zjW@@q>H_YE069dOURQG9R-f0MNVz@qyj=Lk2v}W&!Qr`z|86Mkwo_-BZrtGFDJ)Y` zr#_WhH**FRXA`;tO;S6aE-!Q9#`b`9(%+xnwk%ciQ1dU4ayd=J4i2B)1R{^!8O85! z2t2K2au79Msi;hzxv?iS7P6#}XYFf*e}M=V*-WZXBna-%8j^u#y?nA`?YyL?>kK+a z0x`C({iEkE8kL)#IfgWH#WHNYt;OgW=@>B{tphNY3dlfK(fq0pH_QkqHUJScOoEh5 zxU_d*;hO#WTggbZnO4;%VHvJCvR9YQ;{K)%l9JZ+ZBZQstWgnAd?j}_Px`ykxgx5U z96MM*JSiO%Bc?5>+-uk=Ya>5?V#BUaWnMLthqtGUeqaT=SMEAH6F`#NnVO$|J0;WC zkX-n)(Kpq*+ZflAP2c$ld~3um?H&c*_I%ev&cs@pv!V&A05O>3n-V=DtZ>bV(!Mux z!@zAdp8XpzX=nLO&3I1($<stM3P4l&+OP+m=RanU+`7iIG6tTfF^&3pp~GpRnoB9N z@z!SgBrx>HOsbhAH_T987Uku;+;f?0ESZ~7Vow-EW4GUY{~F+WQUK{1Vd{;`X?=k| zC{r{t`3O(vMXE5;2BM!bb~Ej5i~`jWY_2d5ux6;G6pFLD_Jm(*y);a=rP?CPX*B;Q z5E;p(pD8f`<3tz)KBl8Y`JiKHp~II^K$SM7^$BQ)g$gE(G@|yzlgFkxjL}c~5DSU@ zD6MBtSo&LEufG3G@3b*bjJ<98EuY#?hnWeBQtti#R8WKP$TSkM=fmd3gZIcj+YUUg zAhB47`bdR!Ns<Ue&6zF3ZfMyT<<*FL7LBGOc5aYi39_B{$bJl~fL<(Uz4~Iu`obRl zxw{I>^~5`!m3k0IftH20O8aK|9qKAu)~KHVy`;N`P0@guNl;0%I@D6C44G|E&n;Ui zHgGd__F$n3pn1LFizhZ1^`Yhm-~T)qPyFes3v8I*9}eS&i-@1r>rCLSjnDPH;j9?` zL+SH$^DEuWMc7%V!;@`H2CGlx;webgY1cXwG$n+)BZvy_yt2amQqcTgtzD<i9~id` zf%y*(Xa+%9`D4K6i~%XeR=AEIOz%s-edS>aw(YO^pkP(9&pXXm>W9ch_sYW?%rdB( z7kor#PNYxwO#K(b;;ug&qWIvJKDhE|UyOi&lv~p;WK+z=YiCZ&zo7BDN)nnBQoD?^ zS!M5NAwqjicemKCA*TVp3&NDKBYa~UI8Bdc!n%>;r~dWfBx(Fzj%94$2e;@Jx~;=o zOJjAt4Qz}PZOXnks>7@**~TRAK{C6=`A_j>6cGgihMbNwZ2pGglGI#IKn~TBT{7KN z!n8w7bp$C5{}*`T+M|}&HaDIqjxhCjd-YA7%^(js!>&77>m@0+ZJ|?Fu0Cf~?e2TW z+tDgtPsG<BQc{;_^{9MnF-Wy=Q;{&!W+Y`__wQWx>*16sOirIro*u4`HQjr*c0P8= zy<4$n<w`#M<EtL@V3XT0n2n8JE1WDUfi64cl7@W*d`?TKT3JN9OYz<Pb%vzGu7^@w z4)Y-ej&wgc?N@c<bR&{hO*>pNyl<Zq?8~9Ac)D_9Om<W!+e_gA{vF!ixJk`Z8fiXY zrfh!C9XjL3pGPQGBq-7=?nH+RlIUu3q@G`<R9!Ba&EJ5odh(uVhzC8fBoV~yGQwlT zAhqOyLY)^2&pA!V|MxSeZU)t(w0~*cLhjtx)YTh^CaOCs^Hs?w`Srof${I}~u`{|N zAm4rBV2z4cQqWw?H0i75GBX!3=<a6}?Y;h(^y?YsOSjh&0G+T00q2w!CN>kwnk)@K zTrB|CMKB_81p<7Kw7}q*-Xfe!q`l_MBSV;tlwL&>67-jUY}Qc~q(0#P@hNu*O%UXy zG#}T|YWtH$)Jo|;CI^_T`*%mi#zLhCp&QsI>twJr_u@n3PDK$glKwa$p_MvG0epan z8i^rf5vLtWiRl$#*nlue=w7p7={1ik1{Ce7WU{xyfqQoepcW{cssfpikn6lLU_rV& ziQ1UJA7T<jBhj2m?$S`1-r@v9kg^n_{4AizH0S$UUuIU7Qkp1-ST0hPacwJ<T0x(q z`#BwyBlHzDPdYa9BI};DjSmR1K*Kzm#-bAUy)jzM%uS;m15l+K=hvOGJc4VN--7M{ z#cM*ZEt%MRR+<z?yHKQ!01l+b<$94g;9h36CV{S|&TY3alXnj{ML%>RDIsmFL2H<h z#RwPZd90D0eQa{H5~xICa02$IK~M`D<I-I}0OzjP@LHFr=eU31*W6gvDpu5WkxWAP z%gjK;PP#qAh#I?nKSFYssxQZuS&XRr0*9cKv`5*!f?Y#qCUx;DTEqvkz>?booEcyp znM`j${RS@8uLD7k3SNU)3_g>IQmF~a<syuUGjk=dBA|b5jSZwsVvb9127AiRBSMxQ zWxhwbl?}io9V&fuA;lJ?LPB5<?!P70bFoS6v*rb)I-*GsKlh`i5lS({*1--D*%AAv z-;8U9+atPoMIbfx?&!r%>K}CZ>`D~k;7`tl{7X4c*vXb}P&d|>8@wGYUfI&Id~P@% zhTxTo>A+8tx*Q1+f1BHdntq$>^ev!RG2~NusGM;Gw0^G&-A`Edz;PbtmnrEe&Twrb zp=3?h{om#tGk9Qfv~WI7c)3pKmRqJEp0rx%D2n;@N?>%B8x`*UalYppPo+`?h&3*M zgGwDyG>?9WM_pJW;-HgPwvA8X^sr&N(=KNLRu=rX&IU&8ByCVQI9NIkmNqcw7-3li z&3JGML<V??g?%ijM`Vn_zylY}#s^dkr^exKigUeUsyulD9FBv2#4xEdc}1BQpLC?v zX)dg=f|Hzv7YR6=8#F(lN|O^%5xwesj-n_Sw2`NMbL4d@GoCPD!janBfFgglUIPIS zI+ruKH|p#i?;<%!dmFSu?o~9ZnX*M)fp!zL5E`r@pi~(%qjYVXe<|7W?|}5>urq{- zakNffT_&SW2}Wg^$Q2ppkgfXnpzL|jFvo*vyQptp3g<%DoPBARLBeC8*)Jeq=YpB@ zu;^f8MP44rKLF|nHZN(bS#!_TgHeIS*|9ci46}=|WQ`PrP@3fZsNWbNs0^!+X@(<Z zjKMiOR)GFwN@7qQR!BOchuvE)kg9X5UjDO31>oC#G5M#5^w-3M%zL{+gb(?Ko?jmK zP$5rPUUmbZ0cx>({)_;`pn`bacLFSgRE@5un1jTT9VdP&)Axt4K~i#|$UP(Gx(@{9 zrB|+H|4cb0gh0mK6*|Dqi%0+Acex8O7$j3MAVh9esd?BGq_>Gz9C5CvIB{z#j=N*I zT=34=R1L$T=wP(9O<Wcrra<Gcd=KR5Eqw1>#}Hv=_E-%EJBy;e6%CXkIktm|c#MB3 zq!k3V>700{^r`N8AnXuQ!AY?QKxBlC(9-R-NN&by0j{aq?_&202b_|><1boUm{*5T zW8}`@+t`q=6>B%&0a*=F0cCnl{vPlEuJ|b%pEc-0pncE<B{&b!pM>P<tQgfGK<zEG zhjoq?znIan4BLsKoJo%jG+d=)l-<fox%*8{?&239w?l*-Xy5C*JFJEIfE-Y!V^bCu zo)Yw#h{pwHFb}zV07eXKK9QO$B>mAPGWW;L894Hx@M^Om@d8J^ZwKlXLL?_57~3!E z(Kc~UOk&}A<_AKkVAt@Zl`j|ycRWr&AXL7?R-@h(us;CEFKr`AcbTh%a3;thpc1*_ zbmmw+L-y(xjtG;vk_C(l2tu3Ggc>rCQJKI;q*Vk`KiS8?5nq83$4Bxt?Nju<m}U_{ zMDWL2rTZWAs~#nl#hgO<qS0SAmynd77F&g#xK|@&IA;KB5>J3D0tJ8{;dVN9KMvMF z1C|d1ZQg)!np-BY>WA!&LTcUK$19u<l?|LWil3tmG!X|e<A^G<t_53sZQUdJ&=X&9 zUqD+8lpS3AGKkNV=`hL*x+>UyX~OH$#XNRU?d9NEW{-KiDZnJG667HE-5l5;EC`ra zbOFX(7cqSnPC>ks9j(%`gK6jF@nK{#1d`c-CdzcJyB<p`E9DpogzK)b1QJ=v#*h?0 zjiT$fFe<!Gh;aEBnKli60guq_AIm-sA8>#T1mKPxj0EJI<N|PS<t{y5G~7I~^I3Pl zidu2Q!WQGyNP+ytPj{PAHa;t`@<%A)iM@<uxdI_aIb(#RB`Sfo&H7)d_rpX4w|L7% zjtn9b(QtDwhXYBMD46d9gZ0w_)E@;T*S+@eWO|7_xgdizRm;=P0Zj0ebwtCtVE12f zmrZ&2CDxd6Hyo<%ckNh6U~itF>o6e{W=yif*{|k>Q70sN;_oWaInJ{|e^CuGPKOL` z57pV77gKctz$W&b#?cbd=)T||gY0ykVWAdYttUukX!G4i1{36n<2QY+)?Xk5%sh7! z;@&2hAA&9z50H`En>a$`NO%3JDgr%~`7RM{rD~ij<{?GyWs>&1V3#2TdTo)bNX*70 zc!9q%MV{6oIv5t5nJR3$f0UF2sI*9KA5-$A7IC7SCP8>FD6p3`19lb0+1z_Ky|>FD z#bA=y!F4KnH=`c;?6OZ7h6$8CI~4V+i7eH2N)8Ojw5IoxoKXFDU-#E_NgWL2^*BFh zKqpM@<zYl;2~7w;vlU@@`P!+!8C4)$8$40pS`ASU-$Qko$)ZG-S5CQIf=NZ}MG#{1 z8)jj01v#RlC9rqY^G%xPK<M|zFCf7dKabH?v|UdxTh`2@fUaa;(;f}ccT=GEWY^<; zGB1vqA-d}f6-{Aaiv>)inv=vFu2|Fc)O=@zi887XyhJZ3J}_sl824-le-mXU-2V)! z={L&!o?L>6H&uH*31-5FGa9NGDxnV0gUi*m36U<=h<!z@HYlwuK=4{TwQFhmo*CkI z+T%3HS6?PI1lcVYbR%G;DO3&-3S{=k3S#NqgRP%1OhU|K0NsSKq4+z>Sl=FV#xO+L z&R;;}nq*}Oc?n1&-&`Qx1AQ5#QmFf74u~*%L6H$K)7mKlgUn5JSP2(->|`QVGzgnj z|HNR08>Tm~Z4Ao3#};l(ow}HW1YRrT@R;jtUpT|~T7+PfJ$v7v=!TaBe4z>2Z5Vvh zI|v~*8F0Yhs(k|m-5t<C6&o=l>^-B7hyjBswIJC<5G%qfO7X7Z*t9(E6XbU>yJ)tE z(LY%_7{OT+C#Ug1Xyr2+0q?faC&x%?*aRvQ>g`TJ?IEJiy$raXqBDUAb%@@KsKKOQ ziC6<nQTtxtd+BAksf)zjEDP~1Y7`=P64|Nl(1C&5p?X`d$=Hi9M64<W0m^AituaFc zb;dNrkNHBrG&>S>1Q<t-cI1_f75pJcWHKb4P5w|PO(p4I+t2!_DMmBM%FHeS#I=o@ zBx-xq2M7R*H+oY{VwYklnzd`SI&(U3e@;8WCwute<GP$?ja)P>IBS+E1p~_4lSKL? zgs}*#rekc_J=K}MCWWa4_16VZ<oE@zv-XG0p!hIXt#tDosVFC`hLp?}$<LV%Bd4Mn zRI|=kmy)BbASAfQRfyAa!haBa*9pwVjl)HlWNCEXMA#>oFkU$-22{lnTLn5eD=I7- zAH<s?Z!&LSps1X36x?g}p}{2*lR6}u!NLMvR1wcO9S|dRXVUw|%wX|AlatTR8MH>A ziHHDowG5pR&rC!K!k?am=H^_yXFO5fv;b@w+9d19*j5R`Imab4VxS0$c=tfn=OH0* zMhv_%4i@zctb+kUhmu<!XBCen+@?ED`trco9h-$Zi1YPrD9|V>KQ{_E$03?@>HHMW zq%7Ib5sD{v^5izv89pjs<8mne**JYo(3H*YxQ<4V&5?_YY49+HD8kY?<#iI~aPnr$ z4TspKW&K28XdJ=VxMj2M!orEy^x-}VTWEGj$8rq-6d;g`C9}0g9hrL!4i)DU>65(G zmwli~)@lO|2w;(sC{To3cP6oFVlDQm2YqaI#S?`K=f*L^NwD<=d>(aQVgu}pXqHCe zIE6NA#LL4fo)N1^Zh*1nWc`W2=X6;nwI#aD&ylcjt(N@kS5i7%NFvNr645ZLn3$J- z2zpGUULJEfUYTloM)$i0-;{3M$D&iM8#w?WJV7rx)PP6i>t@kHBv==6GZ4@Sjzn<q zy-?+G$!x!D3@9$9H7@9#${<1@PIH_0(K6055eIEe7`r889jy%Bq==cSCX;)4h)1)8 zM>%3@N9_$v6F~<u)o24JV-DWaCU|8B?qVqq5vhzHH2}P%v;$qe4lF&-tuO<`xpLX_ z)RA-P=YuxmVPE!{E#=a~BBG6(d!6ZDtZx$?i3aX65B$5xBp7*BTe%-~27D{E*d=ow z4WL6B_l$^~Q?`k1DO4J4HCu&cIn5oG)5>J^g;-MSH)+2<;?SLwj#HS$(PL~ezg+kx z!(nmCBz<D8BV`r%cYOJkUk3^+%i>z6z&HgfDPpkh3?XXF)`AU%rm&77R0J%MaHAOr ztw)2K=00(zNCKdXck8b2QHH3Y(ZKRMq8=q;0Pzx!n95!r<R3*Sem!0|cF)_KEocMJ zy00T>kPfg|ya~(~6m(zN!<vl*K|s+cA2j9R%haPp8oJJxx5TtZ4daG*(=v$flSltC z0MM4W+1hXhssLt!yd6hF3Z?<14F-|KH0&d$mglwz#|8krhH(epMSPugk7v!v<$)ZD z(XX_8>?}GJ?5mzTydaiBI9H4{i(Sq!LfUMcP!eUmsy!fV1fH7qPN{?WL!y^rCuQqx z!@VXE^a>zei{Nq?-)tJp+f{bafS5w>h*GxpO5!cgfgK0wrb5|w;|&|XtdsR$+%*+? zg503HnPel#Oo~_e)x*W0`YJM$7V_YIOUmGqke7-AHZSA11zlyVC@51lKxFg$(>^I3 zY9a7P(d6`K{>>1Lu@)tRJwxRBj`<4exp)zxjO|0Y<4Qw5<DT^-G*|G9%&%Dff8v{( zj0is+zRFK)FnI)LHYFJgWy3|;0U23?a2Is)Xa-Ou89VgOD%bko#0`o{QNkILW&n`r zN{KQ=fhOp?6uJ;)5FMRGFNs`6Dqi%>&#E1OhTRj6G~UL_JqECY)J-5BF5Zr1G`tAm fwoC4HF;D0&M>Bz_3ER<KO9E1IFuTO-k8A%QEiVk^ literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/30kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/30kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..4bf34b19d21338f6e3c86852307b40cc9227f5a6 GIT binary patch literal 158002 zcmeFZeOOfG`Zl~!49$wf%3p<yyBQipg&kA^jV#?+!;tO~6;T3dC&nf#1tA>6S*Eqq zK4xSMNRv530s?}#{U{aLk~??fFyzRGnje7148uo)%z)#3ti^lY)AM_t<9Ppi-{-IA zI3C^YLc}#|UH5fg*Lj`id9U$b$8S-OC%!Iwo$~YZqu#>*sPWr>Zhmb`_B#}{bSV{1 zQPgD0-|q!#0=}9`;fFuVru^}>AHH6-EA+p=o^@a#m<qu69>Jf*<Ns9f0RHtj`Rc*1 z2N8G>fd>(I5P=5~co2aH5qJ=R2N8G>fd>(I5P=5~co2dA8zPXB{Xyo&g3YsD_%oh% z;+}~<HsJ}1n)M}H<onwHrI%l%{uhJr_;wPN2Mhv<!h>HABJdyr4<hg&0uLhaAOa5} z@E`&YBJdyr4<hg&0uLhae@_IW{u~t*_vhHSKff^Rh52##=g-mP;U~d|K%5B^{z`r~ z0lx>oKv93L#=m{ve~o<K|9^ge&mSB^U>&#z3;Cl590Q5MgI^CK@E`&YBJdyr4<hg& z0uLhaAOa5}@E`&YBJdyr4<hh?R0O`n-QeT_^$_{*s&3b#lg4h78x)e?<Nu-LzmD3! zkN)xf@f*~u)WiuB$UpeykAEgjo;1ndf6~JN0S`@n<l#pinfmb5sgFJu^!THXO?zzW z)W@HCeA@IUo_zAjM*?U3*HcgYSI`qrK0z+xHxYlwf6|mmlcqfJ=+sA_`2YQD{6}iq z<cU8{q9*!1M@^XKH*uQZ_<2fzyPbrS7v%88|M=xM0r&V&z~m_pPsI;>|2Q?lZ{oxW z{u9Yv<EOXb&nf?DlY;*A!lH+!C;ctpxtu4WJ}&xhvhXiQ&po-k^{y!T?c5zx9)4=Z ze?9$7==0*R+2Jp~^z!_e*tl00zxKK`L6*2;W%8<&)oW7MWv+iG>+jj`ZqCd9uwaW~ z>&{O;{l{m!c7M)lic9vEey#oHKzT*w!K&(-L&uJv`2L5Jr%pHg`=|5&`Pp#6*xc6M zarw&CU$0%i{acU4+H33U9~iMaM#t_s@4MXOx%}{)|NZNa2m60L*EBrW1b_dD{sH8< z{3aCO{}ZSAPx{jf4+Sks3iw;j^yi{Jp8UjLioQE~Zi+B^`Q0bq&TW18Dbb6!Lr2J? z`JU|m+k@@+-+HqD`C$L+xvo=>Oa$FDZQ?YFro0}zcQ<`SIy1#SPASHzxjnVhjGhK{ zi+Z@@DVao<smt&lueRw;T<5f3#;K*@u`kQS+Hq=6-vpV+F>9Q<o-g2Et)UeH?{Rjw zkn7eioOaG?6qKgmaw2AsR*2orHNCj9y`9VOo?xrkE#s6`@4nDSbqD7v9bCF#13N`z zx7aNXx<HhduE=raj8mq>9h1EmaE*llr6J>#%SJw%?lg+sr^cx}l_8lqM*aww9))l9 zGIeEBm6^;ypK7s8(&Wk>rzCycO~DyF(Vfcpm~pCqKNTe(V;NJTy2T-?v9L7V;+U-; zz~y@xOB|(&k(i@o^l;}QL8(8}Smn}Xj)h)6G9=XSYsRTsN7w{hMB%|FE3AfI8Gk;H zsdY%2x>g3sJmzSVL%?f0_>9tViV5>8GI*MzTdKyXIu#x5ELJEpxD(^l-aK<u0<8!x z_FF6ON>)cYmFcvJ>vo&FR))M|9?SES;F-;GSC;fT-Ty6qI951L>GId&bFV0h{oan1 zTo_>7{oW^+<2wcX@s^rf+)d_QJD<ADU;nPgS>)1XXp_uMT)JFP8m!CGCTFtpG5s0b zdMtfKHclNFh!vLesVmt<HW%Y)+dkRC-7NBbWd90-U?@DW(;&j{>uP#910G~v7`2bf zC|#z|JBJcAPK_~nC~U%crcrG|P_6p~XH?}fdMB5uceGVFaH~HQUGfX|Jwg{_j*~P+ z@~2w`LzZ!>HBZ4f%+6v;W<@0J12H|U+-;jF3(j%r8@WztzDRGsxIHl1q_JsQwz9Ew z!8o<VYaYvA%XIQ~+STt2Pp~*d_C8AE9H#~b=*V&EPaV6(!;(`2vL3tF9Lc3qE7eYN z?-jK{${{+kr5dZbecm|<EALh4GO_IPv69MQlE`(dg)Xl-+NmEH++ZqubmJq&acX+l zICUA}b2q!+{Bim@`m-#Dh#RNweNgGapI$~P(k`3F?8-vY5BAOz@N`pumG?Mj{itB) zkw#-g4|kK5WlNZ*acb2#<+w<@ZK-Xgv*)Eb*SxqT;`=$Ly{EbY<EM!9T!xz@w1D#< zEc(%lKhVeK&3kb$!Q1p)tVQ3FFixrY>r8iZ!9UjROm3?>rIL3W?#V=I9@|YHRXdn* z=BXgXG=sI%Xmu6wcj&>&f|d6bss)PEA1Ij54>P~jUv4x?PKnhf%>^~zz?kT$M%UrD zJSqRULtjyBHi%38^`mWc=Qw4F8y%+}my4V!{Nic2njZJQccZ7-{_HC?qLB~x1@Dms z3}Z9u4fvkOrB2jlELUIHnaZ6HV*1QuCI9YPZFrPx()KEHrM=9JxY3Nx>wWHy92dJt zl;cunxzDRxRHwdL6)W*zLw35DLD7Nu{#7xaYSE5Zq21fmrL-UWpq#UmoY@wfD?{GQ zqZOX!UmA9r9CJ4O*Vie`;3WCM3nS-37v&2|S6pLi4ley7kC_ytV91^wr{3$U4jT>p zl(t7N5|3Q1-LOaMxsRQKNAA43r!YzvBUu{YbzldT{O&${q|{oWOk+HuLC&w1%+wWz zFxs;(vUCJ?(&+jih2Gv4cNBMk{VYf27-$;CM~J;-({5bz)Eg&wN6R>cGO(n7#3(MZ zD;@k+1=Cn<X<%g}Sr^b(nA&P&dIr9hm`U}S7j$6w)FT=vt6-&8<WM@T;F&8cdOjBF zq#BMXMe;UrHRF_WAfbnip)b3N7fEs#VSiNHk<m?&rg17IdDAR5#-cWHHg|*A&YL7f z#^BOt>4ILVr$I+|<El%>DO=?<qgd-{8q+(>e1mf63qRDaAeq&rOw%`NoQP|8b0*^) zqTSf!k{pBQ0$m{XI%<0CBE89OlSlJw46prIBhUux2W=Wo?aEr>5UY@gmkokak1_ma ze?Y0YRHPqkt3~!?+l&IFB9=;gvxd^}-ze|_?Q~Ry{bgyeG7W_;y4<KSk>yqF6QP(N zQ@>(TI~n^$IvS7UEJ>L_N5l%T#}&avE@g&uKputt&L8K$S()PsQaYTvOokL~Qm@_* zQ*#+w4>n9UTQSkZS(KT2d%IJ)KH6lL7$w-CzcaZ9?G`nE8aEL~Up0HoktP-u)H|)U zB_+(f098KP#7+^SaT!QWK~4H5N$fVC7HdU_4$pP4%HLw?!74XO_@SesP0Up~O76~H z!pfu3B{WVXhAezbj{}>hL{KUyMI(#wpXOp2a}1U{WtC){ifnPw_Rtje=h(xUYA!8^ zF~wLsBPgqJx&-fO`byHKDMHm`iw2!<l$A*uvb5qNtg|VWw(Vaq&5Ndk7Nd13*P8j* zC7Kp?vc>LgnClm;Z*)k^V?{2;hTCKY@ilgCB5m#A8%Q0k^OT6SlFht5@vR`aC?qYH zxf&bBS+bvz3AE($G2UjT)MK89)NDr|6|1>*E*6RY?~?7T=Y9_|y9m3U8JrWfrH7?& zBJ#|+Rd}YoEVBDr$BgCJNZ#F6t~nyW%txqAm$T}2&H3o(BG=aQ<J4H&Kg-n4lGe@N zw(X!h5!$7+b$^B`R)kxxdGyWiRWceyv#w_1@w<nc^y_-10<9?jvWs7<&bCN`WWi{Z z!TK}f)WQ7bzZbME+CZL1MZ2?72lFL+XZvrGc}|PiqwjQB-rF!^?K_pUR-!@7>)5z$ zhp%cElq0w?lFxr)U-9&dG$wRDJg>a-@+sk&ohG!j3TE_TRdM^*gR|_nut?8HaW#jq z?#NS%M9;i`es7Us(#<_mQ7&^sCOJ)yu20?JPPns9B}c7TK#!*7@2h`z?Y1ugRxZkg znYl@VJWWeuc7gcb;hQ0uy2Tn7pT-P$&945mj?FH{Zg!S@|66wa<$O`ePP2Eke&@G) zHR!R-xmPbuQb$@G;f*=1=sO-}?BZ^bD~z&xn=`l?RGEYM0(S$&#_8mdCQT*-Xq1JW zHMhUW(7Q5Mmi(5`A!*RG*n2dlY71wLim}v8V4~D)IUARmtF*^aI(e7u4eXNgFjgM1 z9sM_Dajwi?mzkGj<?Y+&T^}sHD+?~_GzXOOM@*Wb<Szzm##Vcc5jGtXJXBt8_*=f9 zsK9fYw*5=C?Y3*Q8lN;yHRbs|RB~&dX}Al2`Rc3d?&^LUpu6Z&Pg7K!wdq9Fwcs2h zR;v~tmxLOej<ugBI$$44IrHoFj<YicR?&@i5lfHl>$}7UyIAS-mCPipN1ME9_3^>d z%~)qv9#y7ZeMaueZsHq~3U2Oy<(cdC`~J3pF7@XNQ796BVPm{aV<mr)SpZ*(Pf#uq zvNFe*<jNQ2@I&gc{1i%!BCu8dlUDLe;418XqxGs5z;0CkkJfSO{K-|MyjYm-Y3P{| z6_0M%Ep)`&_*d)p=Xy--nTKyw1HM$~&v4zOz#jw-(2Q*K?tEAA*PZ6?=e==fg>hw1 zgNEO_-0ZJgzbN(FlP|x&u|id)V&dgdN6XnGsVkrOkQba)F_A6mmTT!Nq$0bhh#z+5 z+uQ<opSNMuv_<m8e|gQF26R<>TX}JtHZ_6Z*egnVE%soLLYc+A$R3sk=X6R5WY$`F zY&p`B3lHuvicuyOjF8=9(Z%-Iu~UCwWyzxNRWX3aD6Fn5u{JbtBfwLRD_1&mVIXJ8 zRSx-zh%s5Dz9T??cV(~Y8epQGMMg1~ry1@DNki+uE5$wyn?Ogsp^#kQZ3Kwe4kYig zIA#$%rw5$rTxPfE5)k%I-r>yYz)c)QMq0|I=A5%Aaty(w^9~+#pR}4qIk-X2y7GHR z#4NTh)#x#gDS_-AVH2k&1H(MsqvjRZlyTpEXFU5enykWl<%gsGIW8VQRHuK$=uvYu zse85_`L{WO4oa1x)oQr)+cJ985zJ#!Pg8`fP44c`5Eae`;QC!K+U{fq<GF1cf14s~ zxZ9G8-fNdMp$nj19n3=)ef;8gu50`egleVcoJDr5e8*%`%5>@S&?BY2%Av1!iBxo# zlt1Fke?~css(!J;?lnq)0?Bi*UyV~|R55)M=;#(*1q!vhVW+dmJWhQdep8v5<6_Pr z8<zP67a0Tah_gqoBl5UJ92<khNm;x{QG|<-g{se+(Yz=)$BZr!kDYnhz#l;=*puBf zi0!!-<(qwDjc_OGH-D_Ect>C)K*io-SwIoi-=yIcu6(h(LA3=<!&<p4NGic)&GLD` z`eJloPlHM(V&&Y7W!q|<`oVa)%eDd$rpK7ZvdI>Q5NoKAqJX?VyA*hat5?U<U3k=D z3LVOsyC9lND;}q!&0II%eh~A4V5pBmZQ(NWm2~6<Ho=FS;;K+OXjj&9S+EjNCb(?! zEv|>R$B7+c9(~c(zg)qLnQ_;;5+Og_f?K{cNhacKrF?z4E-*qSF-JO?Gu#bViP&wF z7=_g+lUWG=_E`yqMoBXU$Z=|zzTDcYKurW%$Qm&&^w*Ce($B5jquA4aYe&rV7LCa< zo0WMkc$+C)Vjr()#lxd<2P`gKuF$11XB^@4xo*zmu`lx<ArWx(ON)9jgmt$1>-+48 z`#k!z6!0p#g}YhoxBQhgLeJRSWMm@sy}wd0XyGiyQjxAuxmcG`iVp%h&GQSkD_EvI zZf6T;8$u|9^J#a(4tb|>;q-GNpeFNJu>w&ar?}14w>S%WCqEQ-QZOv$Iw|0B1c|<k z?+rUk{M!^*X^eOJ0X%}*xo<!ov5O3B#}b9C%!c3<qq#ef;I<{4P0JrQ0gGACO=--- z6DpfZJ<TlR>#1Ryw`Itn>nmAVFpK8`*s$ug3!e~TwFhqgcOCwrSjr!hcO^;q_0*zX zrTzQES=@gzfz_~e2Rgsht*1WdKbf(<LA4mIlHZCVFn91*?+i)Kg}YMmwfW~Ho8Chi z^E6>5=xZK%mT3}jc}G^?^~X%w#nb}P<oS&{KW)s|@Lhk(^v*_BF>+2k)JE$~YErYb za{^Z1-@UOQw6ZZ*>e($~V^OVtAeiOK#!m`E4|dCWeSv72i)qAG332ydmEK=}dz|We zcg4Bq7*p&lO$)MoxHIDije5>I5wqXexB07%!li$+ngzqS(3*!Z_Gh8bj8pfmionnF zcm2MxE~34K^!2@b2KOR<WbHV0$eVg!cCi0QcBtVxw)F+EY6{?zGNW{DbdP+OZc;<X zI=;oTavHWN?!q~!@BBUQHT%$}qQM~PhJs+shluV1p?xsQv%K5Fw9{i~eY9G#KonG{ zciN9Lx5L{qG3-YG)?i93UFa&mX|W-hy$;MT`)V*<BKezK{US!$U>rVijs8%VVO~?3 z`d*-j6)Ds5YXY9m7idFe2MuC#YU<v77Fp=B9hg$f_C1BlusZBoXh_!3z!s5xmc1`* zFn;<tb)n~PKn)}Yd(oh-OERnmv_Av>!TNa{M(BSuof%2~3`N_9g?=CK>!X6*<>OQ$ z0gc6#!%se)`>nG`=)%Ylgt`Z8(Zt~+WV61a@8~htEtmC5f%wVwS((7yOkd{hF@tmV zJ(AF*5Euo+LZs&FzhWbx09z{XQ;fZ>!fs&;&^3=c=zCS}hDAS|S2D)nJVi(viv}dp zc<jnyE<I$e(Kj;J%Ey#he8&O03rNzFg=o3@6DHqs2-!L*jeA}~I2kFB{~EH1qssM8 z&^h%OQ<684l@|}U#ZGtTVtA64Vptv{c#Iy)F%WEv-T>SajyVEVX)OPPKL*T3wHGPe zuxA$6jU7B}LBxYKgkeCRuL+9j#vGD^ib_Y`2M?m!Vo@=jE&@W8+eJG8B9&R*69+K3 zW7sJ^HaEu@%)W`W9>)4KA)Wc8lcsMHEa0|0sALoW`kUNee+Env5abmFz?;{wY#SQt zhpaT1RREcbf<O-mGWCt!ay7REum+%OmESm36sDphO<1I;*l_gh76+~9O)mJ@qLO3( z-AG(TaTdmL5#`ucrIij5aw8gzA$JAHHGHy=biBRHU^pFxx_eW9Mn!vuG19y>&%iU* ziek)QS=|`F5G*nGVs($&X-6@-7<W{p%qr#X4=hxXk)(i(RMu|+ZHGlFc~rTk#n&8< z^V(LMt27D4E()}Rpwx4cRC<E87)QHFgI&9Fx&eFKHwt4`9tOSw>b8-aO7S!xQfq>9 z&Uu<#wqQp2^&>j0d^>oPP;n{fIgN=`kFlgxn&o2~y-z4~QmqvW9=HAJ;3D3^eMV-+ zmB=!AH0g!oQ~<xYrspdxDd9R8dl!v8UtfH|dx5lV{b)P4e)TkS09Kkz8hC`b8d?i* z3c3eFXe~*_G=|&1Qa7KaBRQ0c%1x5_hR2!nSD1*S@4sKzJW!Y;@UENzdh*K3tuw#+ zs!g%kD9Tk}x2=m<UisCRAS@8a!Tou0Dc9y@+HE95v{qNiLzU|!j~lIc&N1D#cUJ#u zSkSiZNQ-Y_iXY#aeB{f*1sgVC1~c%-Er@IKDL!(`yOVoV^!K=>j3Gp+r{sM4mQ`(A z#;Hq)e>9&e6PLbr<lKT(x4hHrpVQ=Sijqfe%NlaNc=c#UM&X;SS!(Adc`!mpVE6Ox z8u~wPU_Mm^M#K^lp_jQ6*L`W6%Hp2?nT}pH^87v<s=w%QIq8JMo$qYfc`iQi`yKM< zh7^Q|!GJv&e){d`_`uz%?>Ru%AXAW3`v%?^o_4N2Rrwph)&Ov4ebCU=rAN7&L8y)C z;aw%a(f>49jS@S`#sIyO|7N*W_;pRaa%f{D$v0a??y4DXEPZNfZw*(wE%ZDZwa5{_ z^%wkM!77v(kh06^;rOjP5(_seKotV>;g779WHNt09BHWL-YT1d@a$z*Dl@dprTjlT za%EPd_0ptWp!`fV^ylR|U=U9OmHN3l+L<SN-c4y*4mp^*nwM9;==ZLV%~32vs)35l z0Y?jbR0|Sp*+fZGlzJ>1=y&$0G0cz80{R)OyE{(p<}Yu!_vjnG`H_s{xgi-t-sVE) zOxa^q8FxMBdgX-Ayb)(Xdq!T=-956a2k3SxcEUnCQ^#BB^U5dL$=*@IL2Q*S4AvL* zu8^oB4uks!loP2A-CD-RVH#pQf3339iX`LArzXfFo%tB<YsixpGp4w?{(>`(rh>I! z+&$8w_atIbh3vzQ?nq}zr&q-F9+e2ra2A2R?cmzG($2VNtEb@>_L4TRWN=2>_nzcB zyEHx2={5>EYv#`=R!9;4812bk(VQ2uM#41W+nsN^a#Obb7Wfz_y&jaTIqI|DACB0p zO|Co${@}Y~M}9Skxf2KH%pBf%qWfg}BL7X>4#;ThxB2~Rg*$&g?#ej_%IQ=Omh1B6 zz)zKeaq1H$k-x$Y|6XdB5lY-zRl20(`>=>AJ)oS_dL_*u+b3bMmwIY?zQ+w&UAio< zL#2-I!mz87#mjXueLkuKj{?>eS14HKKmDAz$kVI>pJ0)KAgzh0AnbX+KPk*S3NvU* zp-b<$xLr(okecVgxk+}RKsZTJECxoB3yQ>A($!RnDzHid?!~gnLx-9EilTPOX)s0@ z8EUUCm!gS^-A#aBpxW?LLnNTZ1Un7;`V9~n*D1HTrbu#lyG#g<z0oxgW6=yLz#xuZ zJbdF^=v6J|Hq0K3Vd2yByV9^T1>A|c$cK%+Qt>#|SpN^V{5g4-(t&|`Z*Izh?+nK_ zkSJAbhOE-Dv(-B_SbyVX3>|+|(m8{j>$o{T-j#|%3UeWS1W9{0f;!6(Y<Vt5c$v*3 z<gx&OwkhLn17C8>pPhpFm;kCZiS+sQSK~gjeUhul8>e2d;ahxtV$s}n_(C*d6mZc@ zR5^Ej#p6w9Fwvk+R^MXf@#U)do)m2o$bQ#u^xuYMlhk9N6zDGO^m*avz}|e?-0Qph zgSzyUOqWb(>`egN#v-2J16}>AZi70l#@>YNQ#+0SE#{td;Zr>tGF&WHm9w#8jgx6) z)e(T^qTH36QjHRx@lmnGGg=k}>(V=vnYl7ZBwV^ISXVg0+jq}m6IBTkbreeVdVl{B zqlkrM(9W-E?JX?9*WfY-!&C_twGGJs#j=N?0-zfl^nqd!CJ<f1Wi<2Om;&R)B|obx zSGJh&{scdQw>=j;PK62vycc>n+i;j4<Piag5&oMMxKIi}MPD;kTA2YI3mY?~7b9lb zWRlpJ)U_gAW*cUMLZTL3?wCdp2>0~D=`N6S_I8kE(_Dz{)kFlP9Hb3Jt6Nxg6neO# zccn7Rr7CmGH{u@pCLoex?JA*4HlOg7NBl{dQ}Ag|PzpTm0B($nuJ$%-oJ7Yl2;8T` zCK$A5X?J#VC%y}z<xKS~c~l~$qoL~fQfFzHN+#?M1(SfCKiXD7_-0HOtkPcQ1LE}< zDvUrJo~(sI_ylh=y%Upk_!iuPhy^FnuffK2LfYy!Il_>uFZqKN<<`^unoEAYfakQW zGE(a?M?gPXnPZRx52P=Aini*9EH&}10u6tR@EQ3So$~z1yfF_jGzFJIbt}98Y7P@3 zv?&cg6f5MpMK<Fz(wTCMgXJtOG&zK256MM22#f^4_nIWf*WLE!t`MqQP#Wm_lQ5z! z9>HXGm|WPlKR+aRB<0?F`X<gofa2*77~B52%wX8Ww)~9U$E19@^Da||ZNKA`>CU>; zk>EC2uSA#SzA*T_Z1zZ}JXo0tHLwRV64vn2q%#7)!PH{F2)<#}w|al?8@QF=5W>Jo zEQj{SN1SPAE*sx`nSS!6zauZmxM!!MIiyF~!*TSFO-~QbX#I6j1>rrA$qi#m1@}@u z5=465ScP(@W2L_7B?b8fAaf(}_FUzQ_xE1q)>ev#=`FgnyhS5Fo&VuvYbSS>Xgh0+ z!OAyV?Gwf+Rs7T0@xgj-y4gV}a8I+X>~70lnSbesandKK7mk60wLQ;rZ!5%2SYJI> zJO7L4D<$|mtr$qCzv^b$qlY*D{?rf0q``b9b_ujGXZ|mYneIvgucUDn%lP{3fn&g< z+Fs^r43Q5)pY5Aic{fi#5_1B#PD1;y8_DC;Uw2~82lHgT`j7kA=1&3GGJ`!DXUVYJ zIXv%<1sJU(QSx)~#m%Jsd(t5SnFGN%5I8?mhDjI=5tWox(`G%MP&_Qc){U<FYBE5P zFMWR~22yjA+`?$Qi|m}H2zfj`rpwG_`tksYF!Xa-!(kKTW4Q{YR7=XU{#=sz8HElF z90~?zO$$OGMS4I8M5|yt%cX}-1%fDJ0Xs=RZdUF9$1C#f6$v1ij;PbPu-nFiBl6L| z5EvTvh*)T!y(nl{{vK4ZSMlh1+e%Fu#9%M>c6UQzNalw}4IZP2$TMb_4f1O>kiRZt zsHbd-$mIoOBWM?TW%<q)>{T#t?h8G<6<UGPF7JdOHXNQnN{!fkT1e!CJc_B)(GWj! zAX>B>h@pu<wTG#52&;_GyTGJy8N(8vzSJx0m5Dj;p;M1bdr_h1`k0I*{fMW#$&=l? zvIyfEjXYDL;4G61+z?J@;pgUwFuQ|ipvUqQWScD|O4YpCB>(%XK)*Z8E#3UFuZs); z`eT!Oa7(h_JZcdJ2*hnPgYT%Z>_q#jS7x}4vk~!NkQzi+wGnj+<0OBK<k6@ZN*I_C zXenD)7V-QRi^k+4I-VNJF~r|LI94cGLVJ%&9uL$?itEM$bi@`Lpf5f^$8^_*;PUt! z(h#KN{u%Dm89uESm%rALQ&l=s=FgCd2kB;vO}fXpY`*=7iyh3LB_+-RL>p2{9Em#$ z(Ol4^*)!u4M1;W+?<MR3R5G)b!!)&(F#{PFB)|1^0Ju?di98o{PUZ}V>0RicdpF|m z_h)_uXg-!JeeFl}P^zn_3Q03obXgt&{K8q++9kUsXu$~X(8}pXkpr?38nUPOM>`!N zwGJFp4r9WqFEN4FUE?bGweT-${`s?6T(o^q!#~_%6L6IU7KLDg-o(RofWfaDsu1L5 zTN28#7F5LSzfahBQXVkmHI(0J$J&v?x`?koP&RdXCzf`B=%50eP|1_?x%E`sJ`tAY zb70)<LWiUoK91#(fKYbAWB<fNd;Vw#YT9&Q7xH6a0HWMd1Az}@GKN7slu>XI(w3)L z7vpW9vP!L&6-`%?jk6p=NB9)qzw0Mr+vfm_d(3VdhVceyE(d;G1OcsP7H1U<hSgAx zFbHyCJDs^J0gIoYu!3h)(7G=4VYL_MCa3Ltgu%R`D`sZGSklaX+^-)D$8%g+&eW>5 zPj(u_UPt}$pL7xI75Z4ZD>s$td(wzOMVTIg0x<F9h~U#gh&v}Z3)HoQK@FxoS$tyG z-6Nk@v@@*{X#d&bA&V;UU%v$g8brEnpC~h*@H63)b}YtrYE(+y=BPSQY0f;qwUZGA zYdeN#XbJk@e1GhlL${=2_fP3rKi#k$y((l+gFg2(w6_kOHEqK-xmXdntYJs2_ksmf zi>J99lf5bKBwZR>_e}9Len>u6WSE)4y4w;+zgLiv9Hl_)vJWVh4n>=>+n}LCwbW&d zTvmALvVkNcTA&OyDMN4<y7^HF8GsfD5AkV#@Z8}KCGWe<eAa_jcCyL^2=eW{ee?*p zTh4v0y)gRr;m3Z)j1UnC)VfAgvK-<ffSXtgL>uY+C=BWR5n1PFQuiK}+?5c<-uf*V zsD0>2nij6}P4xxblC47TXm6>ZTO}6=EM=t&pTt;dz>tHh?q!pZi~XPjE+bK5yg;sm zd@x68H<F8(9JH+>uRdkAw1u4_F#;JdjXENi(wG7SLj&hWxC00ZKU53-1Y$1PV8+1j z6-6-V0FBvJ-B|~43r$MxDe>RL)B*JzujxU>&hnT!-S$~JIszy#3%gj-2XupZz@=O- z6O8~6HNjYt_$PHs831s+&%}^0kU$p%kNj+xic6D4`U|Lu%{rnllLsRTKFlwbqxvRb z3QQ)eo>KQRfA98jNQs^LEH1Bp>lK;sY9vw-qKw-}5AJ_=QD4Xmjp;1fGH_m;M~GgK zcsD}}pVCm^>6wM=%Z%3UbHPOh5qO$J&$H)pW%;*;$MkkH`3s=cJ!wDZ2b%kQReBy6 zo@y`p8pxlB#tTkY?nX5#&YGDkeaw~q-o=ln8;|2VJ^B8qT*DHhh&*oz=0iO;6Z?A6 zxls9^p_^cqI>U8_WN5`GyyXtEdEvRS(^rxy=_9$yJHAg_8omVsKBOCFw5@!nPue(0 znh#j%V!sa(dOZ43von8ftObn$u7q~1B@+pI5{AaIfKKcWNbJRc-oJs!?`(xWuOF10 z4v!TP)f(j(+)O!iaSy@UlAda`Qvf3E5>=o(dm(O7&mG$ZvDq9~xJLmoIx%yPA_ztW zO5buV2|}P)yG#bnm#sjb@4Ph8*5D8wfK2CU*ul87#;I+F#e3dU^WQ9+bQ<`~$RC3$ zzkeA*MFWxJb~-i!I$gfx4~`z0vbe|<lDXL+%9V-<L6@>vnFiUq#Xc})7U+8b?I=KT zT~~}3@N9*!dnRqhl@<ng|5-C@M*<Q96}}Gz9?)a?A~4?us1S{iuGO3r6e$D^v_NZR z3KUj62X!>`$~c9bBwnox1C3}DGD70<sYyQOBxPZc6w(mN+7_>iwtb7VI3$y>Nx^mq zS+1;w)6IlLsAVg-oB07maonq0FD3X0>GEUPgi%ah>M_t&&XVPm0rSoFFbbp~CK5}c z5H=p{Nn|HLv(ym|^A+TVl$}n%vJPF=Fi<-L4R}2;>S$bc<&Zp*zjkSoLPXdo>^e{a z@yr;k8(QxZl<SrqRZq7KP4<nYY#=x^n65-nSQP?CTR8}h#@ZQ4E@h_j?PdPC%3-wT z)?%z0N*Wk4MKK^I=Kg1^Ef}a4KC?+`yKa#0kRLM!7n`0v0?q=ub|K~#{y2)PKWQip zth}jrB?vhbdWofMqR9nO5Y0C+_4}E1n0x?^wU<xLeM=26vG8enz`}JBbZ{`gO}Z{y zM99^{uVg%OU1o)hTI_dThLMaw06Fxz;W?MzEA%^fQ#q6%F?+I|0}Iyu_{@8c6LPVy znX>oK);l{lyqhZdkVfGx(eU*$+NS5C%O*nHDV1tb^83)i!4e1^FBgvbUAiB~M7RUg zTqfvdGRV27uO6q81f^DEM%<QHcpBK$+-XGi9yu^Jr+RGO%WW|2V7Tp-u9%%$+VU1Z z1U?o3ZlC2K%vquj3Gi+ZWBh5+ICFs!QOlNq_XM>XKr*WWu7Q@irGKHjU`+#EfCR?J z-icFP?qLJFWHumCfu0o0F=hJdeNGtddWNKczg&6>OE^^-eQ!UtS_Kwd1V_x>hi4%y zfR$t}>vv#NphuGR2e}kTb6MPG7&MD1BXQh7X9Usg%3a21`5@z-zEcf8j|5o^^5liN zSgpB$z}#jahvoE`T`E$hqBaiG>TxQ&19m#(t{r>m3Q2khg=7+K!kpDiYBfXvlGf%p ziZG2#;}!rwBKV0=E^{$*Du6moc9eBe=14zSYFF$FV=;$ZHe$9Es<sExW_1fVaMxpp z4Z#`%f9w!?8$JY0%L?7%3be4^_Xui)4p|m}3cUr58MpSFw0Gq+c#{ZiQR8%BgYb^~ zWV}hjB&86P9(RHZkkMwZqiiZTmc|^H8iatoEmr6mr|!bQM2Z0>0DgF!dN(-+ikyR> zddQba!91o&3;w)ck7)!?=|i!5^Q2_>W9qPaqLN^=ms&MgU<YJCDfAUmVPKZr%q#E= z<$#ht0SvW<A4-JW6s!Z*zX70;WZo8xe7V;~Y8AL>J0_d50DkDBBe4EpK5B~EC34&% zdxQvuxVRHa02<-S5Zn}+b(8)k9tf64Lb``SE%_f7D4VBQSmXse44MZDHh2%x_46p~ z=wQ;T8j=txV0Ua8Q{w6#y&0pr(!Pu6Cir87)>U+qXsSdH&W3Ce9;oNPks_9+L>8-m zr&3&MJ=Y8PcIZ|#$M}Z3ylR`86r}xf>|XW|Sta5J+k#wSZY1uJI1P_Wxk~g=yF9X` ze(i#nX^%5KMICYWr+jEBz;vhjU)nvVZ1+c%eWSkuAMGXS(w1m!P+!pC`4@jv%qGie zXYtcPGO$)#VQW$)O5kk^rKYu`8M*qG*m=;%@DJiI8^}t5fDVTNtend%Nyl9f0t;FG zKB?Z$yw~^95X{N&1=d*&I$3~ix-?9~y;WJ}kAEZBV3Cg{vM>g0fu)5EE12F8$EIa6 zxkGZQpItzupe>#`fc&*p24Q@Z>LI{F(13p!k)p>+o(1Pt$-uJm{B3`9d+h33woFxl z4eM!`yG)kkVho;NN_-ya#Sm&LCg_8e>EO1B?1>5M>0Sl90{JV-lL|^-cT+-pAIv^< z1l((94koXjQm(nc+4wK(OaFZ~LX)VA8S3$*S0MPYbG}Jj|J20R!bP_)MARv}{|48e zt;#uPj{_WAY`F82!t{dMo+FWrmH_9Sp0P{!cm7l~@I%zQR|F&dxczbJ?TW{u0y{78 zX+S2#?-mC`<!;!h4rh-tQ5fQ5@io>c&(EyLmmtF$YlBi@CkwOjipyz_X?}{2(7dWj z5UI^4^jv08%B#=U-X821vagWo*H(2mWgl{<ygT%%$gjuN+-l8)Srifb3Z!!p=l)K7 zZzH5B9_?&v%KpMpz*74_?8L8!Zt=gM6rVJJeXS8Sv}4v`(4WvC3)XJ7wTg7<!8>iQ z^bOSsHO|rzbVb2klo$Q-6PR?)obon1vWF_FMGb8Id53O)NL8@F-WBM{3Kd)*F-UTy zl6-5^yQrHb;v0uz1MaLD2+EKWKXfI*i)K1%*Vt^yX(1*j%*rXHhHakae@(iItsW{5 z+Z<A|AwL+xIO%`7ci?(hbxYkMqZL5*v|?t?)>TJs5Ks7H4f{g|z`MbLK)B0!v+c!e zi$v_By7db+Jdy}4NSQGl-oczwqh1Ag9iGwjMFNs@1wbg}#m6v#liX<np1hNFV#lBp zROu52(h6qE4_-Iq=Mz<mu(S`Cg?G#R^-aJV7xG(fpt?@){{#4Vn+M0Ly+8Z*8#c=4 zKIO4aRh;+S+Wwn=rw7k70~T!Ek}>B`8KXxg!|Q?pJVVgO!$U;E(Jpt+85sVgp;UYO z#;zW9i{4qp+tscuOJ5su2p*D&$Z}ZsgS^Wuauv&obp?$4Y?wV6?}@5`h4=3is>i0e z^5o)cg{OKPLKuZQfS!o`0HyR`iN75@1_Pcg00Ur<q6jVLUX4iK;;=Y?j#+uv%1w<d z3^a8hg@X{oxqT3Hv|=tAou~CV&|9>3_cCOrDQ4h2A&M~X@>*abq1}ed>(T}5?LK0X zYxNjIWcb0R5-7I0pm(Wwl&bqy8N@r9Z&#H&L`WNuDR0MmPi1NVnMntx;xQ0;Plu^Z zJGA~V_sWtCSYt^u713x$<V$(06kN>#*?d<XiZKvVFuNVx(oCoe;}mpO4Brt==nnH{ z6Dt(E9le_lod!h#z~Bl%zI}j!LPB#j%kXRrZchhm3M0V;1c(jl7NtfZ7!EhM39EGw ze}>whxC4w=6@+zA#YyJ`$U&Z8=8p+15FI5vrblf$$Q(hT!md7u%5s_rhSbqOEyNb4 z(+Fvp^APhNPJ0xY1-OrUl@yjQ3zUZ^d+}y$ep4K{Ht|6z-vo1dEor+-@XO(t>9Ln9 z;j<x4{?a6buV588uDzgzFjlarsEen$a*QAy;7LHC<vQcBI?__n6BJ=cYePWw5rRIs z2T6^)<~o2NJ<XKxK!qw!g*G$XNdXRthln%`I|ms{7uyjS=!KEsh}~HWrx~EURNGiG zP#?^HdkT<qyH_0rM`RepeS(93$a9gd+`&ruV`amk6b47bVm*mPPAiDB%LJS6>fz&R zKYm-_1NFn<^qAltIn$u3nB1ekKsX{pA7)k$Ncc1YOsfeRfYUsY(wH5hDnmXh=AkI& z$W|a=0`T@z8<_0Zck}fXJ6Dq>$F?r{6eatBf_$7gks7>HxHQ{eKLD?ImZ!O0W4H@@ z-J~kgfaY9W$5yy3?Dhpu$v>ZdE;#4LIXF00UoTZf4mDYuI8S}N%zHXK!KQ9Wq)x_H zir`yH13#EoZPED(&imnkku56qb8=6Xz<Z)Bz(7M}7$H;PATfEAkpUE}9?TBD(f+=b z%F{iqH|b!iLUUX?r~j22$yXu3ndL4}Bxm2ds~&>tGUUB5*gt$n+;A80753V%>({9v z>EnEf>#<#cZ$9`_I}Mu{#t~94W5Z+aFgW-_7&k@!{$F;1dBt6rh<hp*j3%L|<|5bj z%dN&>-TIJ>yHKD!*{}VWbscNdB@-2)>W#MJW@*fw#MJ_iC4ADlEEjjPWFvnAi3JP- zhK(b-mM^ei7kXEIEYRA{0h)~%90mfS-Ege|CO5k1JNx6wa5wyiO|1q^B9{gLz{#5c z5X#31;=q~$-ra!*V%IIZ_cT5g)f9hny+kx@LqWpR>frhBM%lpaY)k$zYgo7gd-96h zirc_hADOraR5#G70)8*1w3i0mi%qO=^o$<+W10dS%b%439Rk>xJ8mD4iSae~<H-b| z5j`n231sN7u-ZbnBLqi3c2VAW$=~-!@ThqjjskhpgbV?oy;CV5^;XZl=$g%Ec~64y zMDP>(CQN}#3@5mpWQODG5gBwQNNG}QE73jyE^y>Y9tGNR5WJ1oQQkuK8|=W4NzIXb z!%DCtK!O(ut?p=r{!Wa2mQkv@=8=%J90T+QI2@9GhQ)sid{}vWoSs9VaQ6x*QT8^y zKfKauyV0onoqgS#!r-Aqc!|#=vxLUaflK4^%CmrW-~#lHs_0wgfNe0Sk!B)~h@(XN zNwtTu2RB|{u1c`6^r#vr9h^g2E^y(+-Lv3-A;*Ryow{^9qvsTFfviy{16)B(jHO2( z#z7?_Q;;3^Pb@+T%^mk39Ndc<a-@Q=*xZY?A>gTrw$NhlgT1yZMgps$*02n!a}l_S z1g{Yc6izas<mtf?lR3mzH7rq&;n}>OEz!wuLin&GzNP3se+m=x9dxK@ld7>zK@Z!U zgYCSKw_k+Dl%fSe&^c|{jyRDfQ-200tZss&DMLG3mMH^BG$(?8PclB2B)G|L7qPXZ zDAh5KO0i(*6=68QRq(t!<2i^vDxgzcc{fz-+$0Rf6tPL@4LlAwfOK!+tdv|Z<ZY0U za|vW-s$Aq~4RI66@SQTkIpL^OkZcJE2B6D1Ml!-l7w0PZgnqCG+l72wMx^<G9OO?i zrCT}|&Ei%yRH^NvgAjHU?M}EhvtS%m#qCJ2)G`B5#jhoAdU`P!2L0k3qe!<t;gNDv zmC<T|t^CRgutrNkP47*>{XoxHk8=v>n1KIKG&co~<)*xPJ7Y%r{msi&TSWCAahb&{ zKkjenEq&<p#DVMY5gDis6yYz~4d=f}(SnV_P8>ZHA{YsF&m7H#Yvs6xOaE|2sw8Aq zduG!=$!6h?O@;`t!}aC9!Gz&*4-$o-tOaw#z8apAWE9<tf)k}7b89h9X|=bMeLPNO z9#p(2%NGxWNJ(J_NfLuyY}m0i>w1N%)|e0H(xFoUXiAx|bp>k*i!t>PdN}i@Dq*0a z=nAx7Hu=6JcEMHmDGa}<XpeJqbEQ%^8GaYu{S^IY;EtE@=HBO=MF!$2%OR^hvE<vr zJ#k=1METdcx4b^|ibAwSq{f7?rdOIa>Xra!nc^m#JJ^Y$=;~iv@|}F<XgtngY6IXG zZ#?rmyU1!>TXJ_OR&<IXx3i;ve}I<%0$xL(exq2X(3rt~Lav(+QW1_RBGOqa^5p)x zNT?!FjdlLB=$MW6cuOv@{Yjh{k|-CGtq4aAVYOZTKG)CwZIT&l3vrux4&aDt>MSOR z(a$ZzO$EO}vZ@*yJbneI>muYr+`CSHrvBArNF6`;=Jf*Wm5P~JpIOv*&=xjhQ)MhI zoNBjRvH*HQCju997n~zlg{vm_o33>x)Kv`XqN1zq^zl1aZ=8TkXgA*%dH(Q8EPSIg zKAd0+bOU&|dq_|HfPu+Vn+yz<;%R;al1!AGl}BcI9krWMv7^!TNf^I_4pqyX0isUO zrQxq9QWA3)^nH6DE(ak(A!HNygzzZ>*qQzJf--_Bz=l$UQ%ue15dxgU!4!^`5BqMI zA1gaccXkv6DKr3nb0G#2<T^759gWB^<thfY52!L}c0`ANl}-G7kVHn8Rw9DJ1+pqx zq%k)Dd??pb_&XBNx>l5+U`U)9r2Wn=y&5%ui{FIHJ6rIzeWOR83oSe(O`k>38=S+9 zEEoYHHYsX^3cMY=%)cMoO@R{FkjVmNLL~()<7g|z38u0sZK&WZ)7?;mL65EahK^&R z|FGs~w#iT_i24M&<_KZw(g4Hu=D5(qa3}M^$!Xcza+FFqE+$|x8vp1K{gpu|x5<6* zCZNyX0Qe;6O_Ys%nQbrR)A9fpF{mQls)p&oeXUkB>d@8pbvWpWpRX%>SP!<^lBnSd z^N6DBxVQ`J=ggz-dz&SvEH%Odfn&NffW}FOFjyA(&H*oA$tl}rv2HtxvBw3~sM`B4 zoR11m5V;71Agl%)w52mw>jqmu2L0(WdRY#kU2!Y_66G0Z0pB8De0ESM0tOfbT_qXt zq#VRNUPb5t#uWtljCA}6E#L@FnmA0AJF$>*A55`TE)w~M`Z^8g&a`8#&y-C82N;R! zm=wIP4+oXaT{6&NIYf*l_+El}llrQMP1NuW$%=!7BOv5Bby5-(+K9tIU-N_(Tp+44 z1B0L;TRQ}eMPU=FiloEnA%t^Tip(TctyfV3qMHy~m<uLspT)wxDvv~GgFA*)Bb(gb z^9}Y+FbXDq{`6uGKD&Y133L`|Iv|s%fq+0bk@PAGZ`2R`he9?1->Meqy&u4*UerNq ze_%u++^9qzhl7rocF}`CnU{(=PZiW_Xfz_wa)aTMaTtlpi+_^)&sA-P)F9ITx=BXL z4rF4{k$sYA5t{)vilBzJICuOM3nZ%mRBwJ5=8461pS*3}W;KJ#($z^NxiTmo7cBMk z@)7^sbR*eL$Z>qeN9ifReQOd8i#oil42cWG$|k|n=u7V)7*m9Gf;(YD<@oUu(bkGw zVlQ-Oi?Eqr|G)*~kk8Dks^*6;AO=o?kP5s{YG*pN&*D>vFup$M-J|f50j^vUW(@h7 z652k=7X%V>9a5*3yO}F<4nF_NFd@Ol@?@}iFZHpt2aA87vu`<I9ve%DOV243l2%mg zcAA@!=DcU~&Fh%naEwD1a@v0cCTvW@<hJsDpD{nvevb@P02_bI<M=lqN&QEjb$I3< z@|br~DEJOOZqMnqbHR^;)8}K4p)_8>!~_;wo95kWE5%U((B&zb)egE9PzpD$S{D5s zLgq`>{wmnF!QfU$RP1O=5aQfqAqw9a%{l<+ttkt}sVPv?iTvBmWk4H0gY&+EB8QLF zMT>Z(56BPWI_U-{YQV(8N#R?U#`?8OH=9w+a<M0reVSyPPD8uh9w)#Mi4SlE?VhEI zZG*DhgA~=#k;4c!j>CGg(yrb!c#or?_GwlV_7Fm0@>_AcMPGrStU}%C*D3E~^tQPh zY-Jsd;96y56jvmVQzwZzBnFy8zc+97W5@3#k;7-E1ad#c=94&{0RKlY%9PrfZ<5zD z?U3vhdB-;R9@m-E`c~XWYskh#NWCXq@#7Q}j6=uLrT#$*R_;6N&UJU!E5<USusv}E z%2D0ZQBF`)!py~`K~gJpH{ap$IQEqzQFN37CpEuO4xIx3sV1II^_?{$SW>e>sSgDo zs9?s0JJlRj?#Y`5;~<(Y$ltW4d!<^SCNe~%SUZ>-A!#^4&!xXIee*v(c|QG0%{4_; z%WI$(old*?P031j&<qP$CM)$m@%xNtN2c?V=~%X6S4m&j%V$;FLP!8Ba#Oy+V16U+ z*U!IXX<fMr$Cik3<8rIdj#+{HZI^}3A{}w8m@btPi)DW$d7x$fg#>`izf`=8Dwzkv zb57f(rRV?1MM<B1V8PfrlPfF?GjJYk9RS6I+oW(95QFxM)m{U%-F*LIKbnm6D4yk* zi<kR6p#6k3$a}B+ei+at1hv6OgOo!R=qM$EyUQjDRq6;m_8#bAAo$|xId`QVBTiG~ zpo`86ON9118`goBR!#kMt{@ks4f87AfKYK@i;cMAkaYPW?ksKZiatLUgogmbKkVdr z%ltw~>7R$3zI=JRbTKd*JdZWul-hJyA9!E2?J-#W!F<?T=ZNq3v&#Z12L8Ev%QuEQ z_XLB8&6dGky4bl{_JO5>G|j6xdeuX;?c9{C{7F@x*D0@N<1Cledp9}lvFBtGbSG~! zJ8=2;EL8L)AZK`ar^F}Lgucl>d_=^ACOr90&7HTfE7=ow3Y(4*>&NBoo{UcO%x#-J z;a+r#PukBv^#WHPGf%8B=>|>R$3U%<bf)oqs+0>Ko=kGVa6aev$ZMbdHp4sX-Zx8N z>IPH-H~tlD$Hc^5H}K?A{qjN?SM;XL9{+Qxaoure;5G?4Xi+bha>Xyrd^17iT)Jam z+bef6)_({zlEAM8nT&Q)KBxVxuyAQx;i3)M0rw(z*AIEsIONH%ui}n#+$MHQk7xeB z8%n->>Y4xCBploY*3Ae(U1SZxxNHtNzxJc<6=tu(^OE^C_wvvyXQuovCe8y9q$COY z7qSC?C+F(U?4}8sBlCBcx4)(5o`cX6W5cZDfL;G1zV;!_wrxy-_@_C8IO7*{ODDsY z<X*%IZ$_G-Jtp?_u;bLLS7x12|CH4CgN}g&=c5K|RkhlEAq6A!y_c>u#(vkGk;+sW z{LyT=&5k)g^D}>y^=3hz9VUzIxY+c1=KZEgS3k>Qe@not5U}%lx4G{}p1b?zuY;-I zSA?V=SX2NLFk~g{CB@?P=BLG%QpaA)CZe8AFg*LPcn{=c%mSk|M=FS@1s@t5IPY}A z=R-8gy?K=p>lW@<ikc}4-!?y)|3wc+3XaTpPr$~(Vj@KI1m-JtVTk2!=D8N$xEfh? zb|<nH43lyw&e6HKg&p`QYshOvlgNjrwFqaVVMoHebAN|C@^`?UQ(pIhNB2iuHL<a_ zA{!hHs3)nR+upeQ(BwOLhcQcRf>-L41RJ{`<Av4UyLi#SICbr6d((vYEtzU!xr3Ko z_g4HI&Z0|0t2Hj>)A)3G@IIUh$&~^u;Ee@pvnuYeGwNy71q5FgEBYRvV+4_iQyVJ@ z?^T~K5iksBq^Tk3Ap{gv83Rg}$!XFyAdy{LNRAoIMT6d3)Cw4oFVba{f@vVH?l3G2 z&{}|r;0c+G=fuP*kJ4j~%aty~bX`gg-@&LpmPdy7CLplUi&_bczN2m1g-lc;%-T3R z30@46G&9z=t8YSJG?$qtJ(fsLvge0VIEO%^;whm0=dR4%<_cd7(r+$NP2m;B{eV3( z<E;WpNSfrPK=Pu5-A#g<ZkZn@eh|K5kOLjMOw>voWld2*)5T=EFo@Q|P|GydV8??C zXpk<P1}2e(84w2(3F`-0=j|yFFuRE5F^;PF7tYc)tD&FQ^ms;ntFXjU_7L>)nc#{~ zho9dBxoVtxJ*ih=2ZOvGH(nBq1<+-6v+85yKwup+h8Nf1)WRh{QPFTYV7r=6mA-)! zB*)M*QSJ9r(^1c3yhc1%3X%)oBZnv<C~3PADH)DSuE0@KZhf@g)xXdmXh<u!d&j9L zS$G_qfUymT4eqf-99I-o6Hfq5W(O$puzOtSsj+CBI9i6L5GyQuc-V<X+)3J@0;c`- zYxT|$f>X=GCqsn90YhA7zESSNRYLI275hMfFNhjE#DQ1|49f}-Ce>bmXqz!q1d3xj zULa%?qRF?%iSRxIr2Dt}#%iG>M2^?95FMvlv=gU!+VohT_&>Vj%<0h6-Te!vT4b=C z3aeoCK+D9T3Ai6@J}8ne(ilZSNO!z}sIf#u$lN={$T0f~RFOp>kjdFvoXmTrsT6N= za3RD@_<~VC5KjjZyr+nMgN4h~r3Ya>FumSLq^{llo!xc__-*aE{5l!^kN0OGx2;!I ze-Fg?85KA7Xo$h{Mj|Fwe5i!CQn?PZXLt;luZ}c0<<!0&?mD2_Ef}oMwr8FMJoyOP z#-Y-u_A%CP*+LLiRmEpFHWn6i55RMm!w;KO6?_}$WQ^9N1)|cMy(g;qpMt?*$=z9^ zqK=|py(}Ct*JXm6)iYl3|E5mIXhpf?)ek0_sLFT<mSm{DFimxKu&XgqVaaS&-8G^e zF~EwDHMw-ZmX)kq-nEUmSI}u%pRW`#T>TLl@OVgivSukaP7$bTt0=k@jH7%*guh6- z2VN9bbEo|<_YcxLiN>-Z3==n$np82^huY%8|H$yB5R^n)1z3JXiDd8DEMn)l4tsZ~ z8Z#w&U2x5e7xo2rHv)WSIl=!lMbRLFQDoY1aytq{Z|@4x_ZXg|2~<Chs(q$x$0vLt zpY^p}2F``0JBMp9Z$FPzw^f0rYm-_OdUupMlEV~@^fkv#?F}>F<ughLh;3w^T?~$x z(;dc1mS{Ahy!%-6d;l-EIT99{zQ^AFY?z!zCTAs~1&~6{pY9lb2D)l6sr4CJ!EjK8 zuFLmsAq1u?+0MRW@ZUo!d28{uy{HU0Gz~{?6KaQ)9H1)*r3o$A*StMCQ;pG#*nhiL z>N8O^^#cRlr2rx-;8ttvadPm`rFR8={AB!3C_hQ}GEmwOR>{C9zTfx<O+l06F77P2 zTpSla);9fZ3t>3)XUc!4k=@tx4`agNuO$yvfw??Q229C-YkSQ-K|HEr`m|q>LUWP( zihRb&xT8(jfnzxpMetRQI>I0B4VP}P$RGwFnEm^sVlZ>zy)t(60U+nvRwE(n5RiyN zaM+M?102jADb|#Ze5pTG{~Rd=>7RWL`;rpErp?pP1IpvFUuekUBG8V~nRpO<H2gI$ zmIWC3x)rdY07v68Rb2D|S=fXZYlL``;za@+>6%GJ;pGm-aCx-NM{f^ebob_?{x^Ts z2cy-@MS#ylBgaUSgvg*oIl|aDpy8~$III{pVF4f~;#)$>)r~}vYJS<|9=3vrf*~12 z@<d9+{Rb@uZ@c-bn8GQ+VwueQ1T&MG7qVW6ty;-~SN0k5Jgzt70Imxs3Gfmh&KiUn zv+wzHqGG1*yXh_Em{Y=LdK-K{8CA}Vm8_az7y{RcAB0y6$Ji#cDT-xM?ZT<4aUrL3 z%DbhKAf~qN8vF#Ms{*Rc8?t-85PW}K8ax9m<4-M~v43Z*Hm;*fmu08^=jRg1=5ylG z(1KP&cF$KY%TO`AC~`O+QD~Tm!!B!O;e6#m;|8(T`{Z9RLy$8$<zcgGLbF}E*VI@} z;h`YRMPqvy<)I(nNi}1bhF|~o#mbpSK7HTDE-gBT+*ly_7bw}r=O<$itUZ34j=Cyk zuyLRR;1F5Aeo=pF@2BI`Wa~lm;{!?N=cJ;MbL+@U&4N*0fLph2ByV;&d#RlLNPefb z51ck&+){B%w-}OO7eq>cLLk*OU)`b~fA>nmlG2>}8Pdyjuz0f{4L&WthSy#oXEBQ| zo%7Dplyvn4J^%PuAu(`vMw?EMmwUKTwZ=-m`o%O{w>ll&s%P8VxK-P?IA%dMl&w*I z@cvf$33>M6cT=1r=v9t+5;Zvz|NfkU#F0szUk>T-ev(bt7Jev(yrl<bpgMg>`n##c z)6C56!!H}0VACd5pg#8*MF$_6`;BG9U^UPn7YW?Hb>zjnV;!6Bw|U^s1|uyMk6fv9 z8}O2&Ga6I9JW<cjA%|RbB^4=Q6)qJ!fXNS2HcZ5aTp<jkq7$g^IhPN=;Vf-~bC{Tf zl=f;P>H}&Yyq;NWzEs8ZU{r*A(0Ab0s^>eZTy|`25QHF`;Qv7aL!ovpJbf0_X<Z~N zEnfscj5LFtzM`@1gnJ&_3J3hu+(VfC@s2J0c3{`bzb_&$X<6gJd&+LTN=PbheW9@& zhh71k&?8Gmvwl3uP91&@uON~Thks@Bc2@{_N7^YAES#esz}r2#Xt>yUt`%M<ylg=Q z5+#G2&ag($(r|ewm^gIc(>zjF!VYIVCJWP>u0buB1vREwCz}bZw+3Cc6Se>-uRtOO zF&M9fGkR1pXqq@Zl%mNjx}0FE#c_pYeij@%>LaQRY8j%I=khUw(2OzTU7F}UEyVjq z$iXgR8>>BlEC3l2UEQAvdnh`q@7)%lr6dhP(#KzG+=uU`1Q*NbQtViaM45y?6gnd4 ze)#*!TMonmg!5mNO}v2jpp0Go;s})YXS+Qm>u}tN?Dr?fsU2!~f1r_&d02omS5^w4 zT{?T626Eg`|J_A`J$A6C_u%35T)?Bk;PL^Db2H4$MFRfIDwG|f#TETR&X6qL%o7R< zh|CPUBE5bVVZ~$Al}*8!6STBJpd=tkpftQ<09p!~wa*X=-BN(J{sDv327iRls4oG} zS>!Du?+L=3QAy!EnGt72qfK0w8zuy>9k2^gg;4ZSeWYO1T7h}sT2jRfAYv`~Ft1>W z#!K=N$n&JA;xhHXP2LeBEbnM1fDJIo^ufZbOvm9z>`rW%o3%crfDoHHv~v4Q2;(>b z@kI^s<f4Wn{}#+<H^Pw@ff96|fJX9~3$4R2Qv~l>Gj(b=&_K0CbAgc1h^RJ{if&OQ z>dK&-Vq&avyTNr9xk`XXMbP|CsMKSle!+Vb%)Pd+_kf*;dV@n*>!-sNvt6i$@5Otf zoLe8|d!ZVf-|~n=O!2;B)#UU_S|8M_xCoI-hR4K1$^zWGyr9z^ZG=@e%ez*H8o17& zG=+WvMYmL~jDkM4LZq>kO%d;FLE^FKAH)mB?#9%DMzuswgfIxm9YJt_p1G}+oW}XP z(zW|;oBD<A>&U9YWYTE*2^FJ~Y(A1NA1Vd<7IG?PZ_cHFH-eSGb>=@*Hsa0*!8nKW z6#URJ<_CbKtq9wD{q${o`OT`=a=+oFoHNN4gjY0WxSMbSs_vQu*OmD8<-G7JuLx5P za(vPAzvJap`o=9Nli8s%(MNDgaVR(!O3c#VFa*MK*xjt=gR*@n&z;@7EM<0^d4mO* zDW<2|@)@aofF5;WUPK^Sem}v6T7(2zn7jXxBJw^WGDa~rFY>g?xB;0#Ug!w50~)26 z{-SCJkRtE^(gHN$mt>groDM(z>es&$7dxEz8J;ID+$nV7!_zXn&z~d*fVg)0_6vI8 zI85L0?az!~{?}h-!A=6u17u~Yi8p%y#;n8`eM)_Q$wm?+16Fi^zW+vjkE(Qbnqead zIiNUWn4QkSyAyIMK}Q@Kc9Qogu34fvU%)uJ68H4J(m&cQ<oUu9RA3mW5WO_;C6$|^ zHXvCYU0W~(RFx(f>(Y@Bity921<(EtU@Fjptt3NK5Mg!eRM3pFhDAqW@eV57q#2xR zvH8wy2>PH{+N~4Y)}2H>;(G7*;XhbuC^x-r8FGkeY`Kb<!!2x5bHKs(RrI|1KeJ45 z?(!Qjnpq7Z;8=&+bR^1?M_dG=vt)c;^G5O9y%$Ec5oLBEQVL4^F-%F}2}5<{d;&vs z{yC;bf@j;~G#Alw0B7+!hvtkI`soi&*zbw>jIVWB+RztXN}mr4q(Hm&eH%Z-#x@mr z8e(7ldbH-HF9KbEAAxf>PPH`mClg$GM`9fnfL+$d)?F&UI+wiAFn~Kw!l+;VPYno& zt`t8~jf}&MyT~CaY1rxAUXYLZIaY&M8=U`XZ<2V}0$PvM>Hhs|{$%aI4lu{9kN3S| z498X1KMBBW-yR4YBoz-0&|^g%<CG|S(fp_JGKV8XI%2|!^D4P7EDX==X{L94g8we` zhv<O=s<|tn8yiN5z&?b=(3J#T1;+XYp(7{`1w9R~4#Kn$P2Rk>cl&dE94M2PYVczf zt}wix$ypp4xES>d?6?2T%%TpstJf0(!Ut^8c^576G%#9gyQHBohqn`V)f)a-g}slB z>8DlOXP6w}c<lzbcU<wZabXZnjl3ombOQrgiv4`z^bmP_8-(>d<I!MpD?-(7NNZel zRqm%1r&z5wuVfaS=&+I5FP7K%Jkjm5a0-K)vs}NlVFyyMK$QO~pQ^}*A$#^yTbC%M zs=1kVk$t!aq&gDu)K_o(KP;VlT-0^`{RhKL+g%d1ww8+<Lm(<{Sf+%GY}7cYJKPjC zku7mq%rp>I#|vY)t(R&h29VIN3~|2+c}qo;>>_eW6j0IxOzw~%!*yVoe$V&xd+a~E zuENac^M1cB=XK6`DfX-*sFU@&pSJhg=hnUC0YjIKAGNRF)v{{hzQe|BlEZ@0&IO+v z;7fYyF}o=|raA6hl(r$^wralV`ta(t2VQDYc~uV8*lY>gR%<%c!n@kJQ3<LbOKEG! z8GTDOxc2wB0{L*cyzzDQ<gU_{V?`f?bq95QiIaq}-@+|6b}+P?TXM$>aaH1~JH^Ft z>@M`S3_NId<VLNU`}Fvt6>B-TY23}y**H_dIT7*;!<x4m=HF`$?eaIOe_ns`zfe=E zuIN0q-|sFumeSi%miC(jlPjsdV<I&83a?<i>JT7<{*rm(*}wVhGoRk|NFW>lL!GYG z`hOrxXco>98=ghU_V`!@t_v`K4d2S#JqP!_Q5_HGVX^r)Ns7JdqfgQzK9%Yb0CXoQ zj=x^^jQqtg<OzJjoTxinL6%leL@#M61;Z+9S|dlJe|Esl&qdeFO$-s*&JEqjErst5 zpEpPGTAyq%3~Wl;%>UC9u;KiavGbZ!u{BMRC7dYJ#kpISczsVqn>bSx>Zg#MiO`1A zxSQA24@|pOoZ|RnWSGz18EMO3UBJviy#oq*$c-`C*dZJR_tadyo2d;1eN~A^qg)t) z94x!<DdT%g1jL+{PfVe(vYXMftnsqQzjx?^f;!T#U!(>X^~g9@FH|hPw#zv+*bAY& z@m3DO-=+=H3qQ>)gO?UCQKcVk^H9%kCMkt1o7HlTUkRkZ3~f2>V4T4Z{Z<WAK!m2Q zlT05l08o#4P}<-%30E1$2?7tn26TeUl`cjZ=F{{~<!gYq+{JCP3PYn$iyVz;(ikC) z<>)ZVGv5m)FO->IgMNn|fI(XAVc7FqGx-#0X%W3$^p%WRxea~yDbNnPz!O6eh`Cl` zO$Hz2KJ^HtlYS%_YTFbd#(Y<lixS;p4lN_W3*9zDg7(bFD<x1qCB<1nGMZneQfl}M zs+EZo`w$&UP}>WF6|q+KV5Z3AJSPZw;v?Yv6NrL^YX!__c?2H&pF;UB##NqD0k1*F zxyXQ9ZF<x3>au4zZ8b=6nRP|{COO+>4oh(+xgfgCsg#6Iujjj7Z{Y*(bsVah*v#u; zPCJ!G(&(x+m7_<o3|{KsW>0Dsy4u>@MDZtW{}+X>YbeZOI<zX8naR5fTjk5N+I4=~ z8Ux)DfSP>D82HlR*+hsI-XPb})#|f45twNyvN+c?Tez8!(_K;-#<r_a9ayNc_&5tA z)1kQVBp5%bE=QB(lN};b+7)X+*x(k3w<3xY<{!8=6`?qUzgSAxL6t)v<&-|jQ>QS| zRDs)Etlt@ifR_{bGvU@<*`$C{k7(a5i()1>4Jfwp=45Ky_3FtA7xTxtjc>G-Q=FpU zpVklSNVmLO?L_TU8Lu4r*M3M`7DjO)xieZ3@N53>lg^G4$aJIqf$ZC$9N}b?*Q)V! z((Rw85+%gFVBqLi)J2)x)UT4Pz&aLI<p5%N=rP<O3QO)iuIU~6vzUKUmd-tM>w(V3 zgGP!8E)Cmv-r*@XLjsl#MwNTvI^$J&{rD${0KsdS*R5YIE{@tzQ&sTX`XVk<k(faC zWQW%j@Pz8j6St$2ViG9>wsz_84`DQ2yk*r2lJIaRAWHJ=7}*x)-j|_`V~UM(^HkZ{ z%mTxfu*)Zx-NQwLV=~78NFDo;{UEna^{OkdO0xda{i*J`11`M4SZkf!**`IGz-@6~ z;orAKZqJjZ<xP}o&-(}LVbDmF#9%D0QT}t@OKp7%t97FD{3`kQaG!_vtDDcgav8`4 z9;u)R))<Bohr7Hg6CcIQj8y3_BcI#3PQOK$#m89ooB&)v#_IK#iz*h7XOqgdal+7J z+{V0Ev!5T-1c8anU9hh};U>dBFw$l0ER}Q^k$LdOk$n4lokFg6mb`5-z~Fm174#D` zSGg%$(kE#>(n~FDgtimGFtJ^qSg-Ip)Z@WjQ2FXO(4rx5TOw2W4hm~hN_#PLXW(e3 z3r^d>%rPz^)i>%|vh)M~#a7CyvRD_hZ@M*~Z;o!?n3JF>j&xe_UcewZhxqVukNGc4 zxugR4<x<0a;nQbnRDu98;6!k_U4hX+{f-JpkeC3a^V+kYdf##cNER-5uk6$G^J`X9 zC`hJP1k#Cr>PpAN9g~YAB<pK?YjAt|B!w%Ga@Qu2qbgS=N!0c;x92FvF$pp#RuXOr zkR+)|erl1Q#1TQn3Is&G_A^}T)$eYd34|Ic=yb~6y8m%drJ6&c6cL@TG^!rfw#)qt zS>w%B-}>oN`RemsU4`n5`iu{P&zUaM(21QPzy8hrj7^dG(VZq!Yi2xf*bKFNq*Ir5 zd<s5UYku9Hdn#?oY@Mh{(~<)*iF6{U^C5iXSy#OrUO5M!pyhU1hkm5zvn%HkSCIr~ z@Cb8aQ{US=d|DW6o_w@vt#(8FR0dLzxmpv)2dz@ya~z8i;{tH@x%ba5b^D{=wIz?{ zOEpuO)|6OUa<IqfkWV@ds+5~@nV<_b)HytN%3L`b^$wTiG;*y0SGSkjUwyPST>qW! zAIG*n7riWPLrS2!NV(8_Z_PgrIwoK<`_6lKShkf<ZWudXl=}Z=6tr8WGiDpp!PT=r zZRM?B=8TZB;rnuQ49?+O-`}ONd9i!B^yb;0pE79|PCU8XgoBuv%aOCH{2pvCxl-kl zV$Q_oQ73;J8y*Hl7REOM%gwL#xue->QukLzjU2wHURyu=+$r4(C{1`MIIA4~*A#b3 zYLK_f+e2a>PQ45eXJOxM8c!}C{Z~VET{wAEi`b{z=&$v;y$L{=94O3M2j)&&K1{`V zwkNwEdGiMXtR{{}0|h8OJU44kn6wM31jRZ{7vKV-4(ELZVlTDPW@60p$G8*aw@Uyx ziQ{*+T`=tX-$SyRh}m1PmyoH}z1DnL!{P4Irv}e``WIuX;r+Qyaet_>d*Lh-OS<HN zk|!UxsxQTVUG>Wbt;0pT?c>k|qUAm=KT;R-i^&9tK$3jK4`cWy(D42K;nRiM4&qwB zfY^x5!?47~3!aPzi&5OK5GHEvZ*jx?!kLpnAZd-YYwmFsSP*RD#T+|qT{z2x1g~xd zP3=128I=#wgz2F5UA6=;|Kc^)vPl52EQR48VBuTIc2H(?fHx6=+*5w{BjtniNidiW zwZh+Jg@EP`77cP{hSj?LQ$+&_J$tMx02VMhXy+meJ$WJ~WBX8&m7N2Y7=Uol4vN%; z83G;kx85!jHW^EZniwT^#sdce3UPuE9l}W}m83z0c6<F|8I(xA+#zx52Dul}{!dVy zw4q&Sn{Ig^X~{GqU@;g$Nf{4#LImSYp8tXt0>e)9n1q_gaRa|e4hdVmw9t9eVP<!C zS`F+QquI?DgF&T7A$B#8l;AG#I1*grmG0bv_3}W5fryjf>Yl06c%CxFDC|B6a1o}Z zm68&SXI7pU&)=K8M2<c%N`VB)p@1yuYW76#Y8p&Gt`#OwVi-Oo99p#Q|5bVvt$MF@ z72039&zou?PFv@!82P>Gcl8y0?Y(3tW7JJ+7#^a6L_k3oY>Zd|3YvtYQbek~L;xUI znt)U)e0P`_>E=NF6VTXBObg+u5HM+sXs7Eedisv6*eSRswIQ3J*dbb9hK7u493zw< z5tbP0E+gCVlIxHZ;x5Y&+E?9eRuA#fYZV-Lq2DgzlePzR7)1w#=Of~D0n|V=2%9kF zw}~E4pvTuyywwCTc;&tFFb8ksJqbu}$tf;lXT(t1@>S;v*f=%}M570I&sN@69}Ve5 zW5Zew`7#^2nQk7c%3pvOYH+_99}GA(`wCpbkV(&UXZ5AEw5#n3ANiNNp70~~{5S6D zGAEuLLZNp@uQfm)Bi0vThx+O5|0VzOm#5~xa<{kDz#)`1ZJ%h|(d2X`F;F{lY$jzf zr-(tsn%CwgJ^s089k!0@qN2O=)vAq|UP1#rynwv(zFXF?$5!T+D|sgkOXmLLpKV?p z*G1`<!}rA@?b5|pR2;9}O2$X8=nC(30`>n<)WuXj@|RuyIvnO95M=YQkcgL(9&;CG zH)H&d@e`o+hh;|FygzxrB9PON@zOGeLwEe{Aq%t_`p;Bzabb-tW&GmoaT%k!s-h!p zi?uJxyqCAC1=;`A%z}Fr_VvkctyniV==E8k#QEM;ZFQ}ubo)<DNtLGtffR|*;3WRw zkKVcCe@M7xUz9ZYkdfCOvs(LQh0^?^F8)aJ{8htYJh4Z9y4RnF{+(|>fBpC$uwiyM zE@lU&!^>uF%B(WFjr^o;&UpQK8RbWS*^P#7Vn<<A7fB=kH_4fQPx>TUmAuWd33NgI zYd%Ha#F>nxi!4sa&JuqbO6{(0Em*~#wE%=I1uvKLsHtb2jIQFH2LIa}Dp8nL+kda8 zOTvA@LrnFp)x?D16L>Y1n2WR1r{H00sq<0SeHSP|L&!?--aCxcNCAQ&fW?(pS@SK& ziU3Prfm>FE*V#PN`Fy9{Vt~ny<O0BLqMJjUmd=A<2LudhQ7l`>ZAkmq7)_5TUGia$ zSpP(QT<T}5ZAs5Sxdatfnk?-%3Lij?5P8xiB7TYlALw4*sf*txqt>qTgcRkPdsS5V zpuOq%zBAOx6;h@d7#4tiVDutv#nPV)g5wrU_32kA37SI@<wny-*w+Ln{!_^2$`-bY zcEMbH*saL_+)N#gYrR^J!vY(yRmIx7sSC5XldIp|HZwRuXdR2b5UuB%M+lrqouSSm z=1N*S6%BlCeXzp**_VE4UwufLWBKiT?SOYR2jvE@QCf?}@{Q%cNuHkj=#DHLr!g3h z$pa=2Rcz<R=hMDhdv4q%b$HbZEc)R-<S+PqaIMM5x}QjoYr*Y{uU4(d7m8i*&eV+y z3mUhqS!j$_B^YBA50`Kyc2u+n8<KW6Wf$D@nZhXM;x1EU<mCDk^`&w7W0n5u2Kn$0 zje{_!@62lGn`4+!9h3HQzjpZhsH+&Mxm`;xC~sX)8|fvQK%#i)+(Yp;O>52-8GPF6 z{<P`NWw|-o8fGc#T91ntKr5mN)(or*PySre+_i?=T?eONVD3w3X0VHXA@SZdX2U{t zZ12OZ64{4NjqC@Tm#s7p3=crt!$k`QyTa?6U@;1&{*!V-RjW||+QE7F%4uLWA<A@t z!E|JB>;kHPL|bjQr(N5AP_3F`I$N@7bcZym=O}2JR7`XDEpg$otq!xa0_Ejk7$Y`b zd_1g}-T!J<6uAK@%m#igWlyW$RPQ*QNI(3ekTnDwlL1pWdKl#2af06Cpca(Gb<R)v z^3%lzBa!=f+yrFqV8&D+6vi6H2umjB3V2HJCXhSZ@}o62jTJ;-;7Bo0QNcsVqUD1^ zRFu~;(WtPOC{h0~)fEG#iN<G;wh7M?$ld8r;vZhitYo~DbxCzCiPicl%*cNyOf&dc zu;)u_%S5)hw<UwcARxs_Ldv6Z{@YV7g2p7$K^k{Xu+>*~8casnXxm!oWf-)t$Mv9d zQkM8ThSvNRPT$~-^mrTWP$n!0;mA#E$_)|DThZFk-k)=OO-vWWk87(~_J<STvN8`p zJU@_J&w%PO-AuJ07`cGE0;^f>GQLzIWov{d7h5c80Kja~9fD~co?zU;6Xq;9%gbP8 zBg?UT>SZ&2lSHS2<qJa0r-N3~SGNiAXk`hLzP?5gLl}Ly=+t8o;xwcS{z7gL$;Zo7 z<^=cY|2O@q&M;58e4+ta$|e)#i_81TH4|+<vWb}VsgE{MY`LH`ILO-!xGMcj1v`n_ z3Vj1v;{;!$k0X$lWR&ehtwavAXktQLK}rlQd9_QN3U{EE69mEcaaRyXc3b(fnR}tK zDkqvM6MsET-loy+!3V}-orZS{A+AE;B$VlOczA$bJYdEFskuZvDb_|&tHeD7+O+_) z=zuQ3^WY1KIS#G}KfcMhk&Guk5|V|_M0VfrXa|9(uT9xzZV^Joo@^h%v4BS^iZV<; zV1o*9=A7FSN)L%{H)mU&cGzjamD!U7-a>&PuD3{Om%MR#EBcN~X@)21hpIx<MZQ{l zIViAsnq+;9uwa>J4ExZD;~rx*bnshMtM=Q!DKSbyuq_<w#EGaFJzjont3fF}mi!4b zlM5OfzF_H^^WWW-J-jQ%V12)OfKH4-hA=9>pHcBrwxGj;Sf4u5{=~h^{%arG>3K)i zYT?6k?HKmY!)Xyr{NfCkZK`#86rXpmw6rfBmf1y$7TPhYe6{=KO<CgMwFm=+UEBLy zC)(^XmKMwY+<EG|@e1*$*}>Xto?AaqMTe4W2J5Oy>=LUpt92=^#+q#hzJK<G^4<pw z*v+bnb>1&&t1caYGrZvOuyRn`k=Qt<w~Ihvc+^Q>-(4$T8f%|}?U<#$N{bCto~F2h zNl{-`4;yb?S&vh}k+vsR)Ck6iaOP0EE$%%D0r9#nFX*+~R@u(Cb5qS3hZpc?L$i*f zbX*i{_%M68Q`Yg(^ln~zkxphhyv_rTgs9V0!K;4!H@in_hNj<gDC9U*X-=O9G*Egh zZZUSc-bvihY==IlI&*vz7c#^?+;~|2d9qjf`|@H~D`yUn8l&G!<fn>4sVp|JJ;<vv z{k8BrE(3t*(5ys>s3=x~Z4w^JVn1$ob_kEU`DEE}>!AMU#0r-b%K&KSx{WdFfm(4U zz%Sk&k5+rg;q9c1NAJ_)yJ7z?m42i*GfmA2ICs-JCCG?3a_}>81_*R?6ownxh0Glt zHbl!Q+Qkh33!;xI%BL8_eV;m9g&41FVzZ;6R*T)Rjv9hW`>Y_nD6C1&OF9Mw${Ft` zQNwp3U<Fgxq9TbzDac%b5x+hEbidQxHMYcO6sQ-OR8SzvJ8Ek=Br8Rx6%}w#w#2c! zE0X310I*bo$P)(4ayoPKBR2?a;_34ceO{XfZYv_CU}J_-M;=8=&mZ~t!W#HZ^64$1 z*GVIbh%}HU#6A2jTZQxVTS_La@mqmdKgG@_MyOgLXQlVqBe{DezZpv9E0WQcJbKn_ zz^lvr7mPJ@!8>h(VOfHgFbBqqg=&!kLq4%EXVvvil=~Qkshnvyeh&$liBf0$?3ezf z!dHE%aMs53bnfY!GqJS5Ed~I31>M$uMw&-6G=5?UPQitz743nwiZ}N=>2l+V#RN-t z{takOTip{^ZVk;<&RT1nQDL{U-%^LS6wP0u(636vfMVjWSTwvNj~!lTy572r1NQEv zM~>e=v#Y@RY?;B_Kv3<Ld|OvmuWVnlYJ_VX9kTAFWam#(D3U-J6VM=RIMF<I6>uG= zez!69$wl2>-ctC%>JPh4Z%{n>>Awwh7o5R$!N=%i>3O&Etdldd-+T6jl!K4vySHkl zKH&eg1Lt~m?xW|bwZEo?s|`1nON&&i-o3a|kIIS{R+eOR6ht-{r>c6}(6v&%n!P`z zXITZosD_x;<{kK{YpZ637HC*BT?Kqu^9C`4=ZCM<bw5SSCm`R*tJnw4lT|J=Mk81W zD9T<H554EM*K=M8-CtrBmE3B!Q@+?B=+bj*FFU!6#Z0HV0UGgFJk+VPflSV~mD>@! z4z)0)fhO!iqILCfnYhn{g(x4tlP?&HDkra<|H4;cYQ4;sv$%)U0d(6GG(Up4vD4Wb z7kMca1-=C`KEo=p7!iI8r0!eh;$5Z-^y19}u7X6q>{)@yqojPg1cav#)5n3DwjY^8 z->#E_4O-bbUeft7_z}2z58e{$vW(^Y25urrNl-%9`SPN~lD?IO5#p7X_-iuD8Zv(? zf!H}!gH+s4w&QQrksm~U-L6YT(Y;w1!_xWYb)YPxO?a+}8~#Fo9aC52M03dV>cTH9 zN8Btdt43nOs<H>TY~_fq4AKGgfb{mFJdm|yP`cX)#7V+pwH8BXjG^;DRWnqXCVwk0 z{csJb=qOBOT5KBo=D_ve**Bz06U)(_gRAi!gt~8fg_IJUQmW2V*TkgWQt_<&ySgy{ z0sXYa3#{Y+V#GcST+)&JBElH$;4PtWSKk-tIY!ok3$)Z>XCHtfLYtMOPAe~1PQiQB zKjp|@s?=9EPobjZL&Ki6!A^4u-^()dj1EAC*k3_00YPG<Q{yS92MaS+<V&@^=vuKE z>cgCgkel&5<p{<F`Je^-oO2Ac%M2E01w^`ib0W0WxI{<F^(1dyW+G-3tKtPYSXkR7 zss2JTdvrp9Vq)^F-_hPyKdpJAn`*WOf)TZp1wmjV=UxHB#9N>Zz?s`8ryP8BZr>kk zipnF~*RHQ=ReFz_g)!Y1;G>kRUoo4)NaVE4Jzb}Q;UNmLGC2$tuZuEOkOkt&iGdVo z-VGCk?wm0<p~i*?s!<RWM!@M6ZMV^@ujYRhLjc<UR4av~m^KPokd}4|bQToKC8br4 zB%R*KxQUb2%J8^Z6k=lSM7L?r>_obTI=||8f+Ln1w+}H^7Qk-&wtY(<JY}l+Xv844 zG~6X~s)y>TOOnnhN6iAa!*S){{!J^wBw^G6D`DU~juT%iq;hwbV^;$#?6#}KDo2ws z`GiMX?}>&3m!00pkM#e?V|?(tHa&LuxLsYI%l#1T)8_15%$593X`X_%;aPj&;SXY0 z2^sci=#loro$ALWF?q5BRRs>SAJ6~f*@YFYs=tUE`dN?5w`I25heF?7%mA<nX!NPy zBoCEp;zz3vrvApwj*FBdUAo{Ab$`FJkNuV%Cvv~b+xw%RU$<#x+2v2E=V}@!D%;G@ z%iG_>(Loh^cl6le*0iS6dCjlAT(qe=dSuO&@Ys*A6k={j1Su}^dghflc+G0TRnz_P z*>2^+8Xdp1BR8cz_*>uq^G)05y}0R;&8U3vc*)T2U#A-_p;ME4>ek@f>%1ylG|G{l zfBf_1lkaajbxOxq0EYAII5)S?TVRwBrAZO(Yf=sk)tnDiMLPBpr$eYUiawtWW^d88 z9o4P2vg;du`*{m+cuDhR7Guz^HA8dzJk{8qmP2aD{Kwp+<Jy5NnE5m*f?#@CllN9~ ziD}Pmtw({ga{O!jduEisRLO5!yX6IS%6R3JXqkr=sw6h2PMO%rTYW$qU9Dm3R3$xS z`aCFRlyI2>fi2Rc=eKC$(V9Xynx?J#qPaR9y~Jy*CbY22F!F+zwV(B;oJ(j0mD;m_ zj8T}TJLQ(kQ`-F}D?L^X&6klb_;Nwj*0hLHHC%U~55XyRhgIzC55LA44Jq{1h=7~c z$3<&EAZi1Gh-UjOtUc?WVChwJsuxsejz%WUd=oen1cZUVpLQP#icstOFu1TxK@{U6 z2KFBDtp0<h1`3?XUW-o1wYtT%EO+BmID4mhCCzwuiT4DR%Y2@IB~jF-F593sAEW^3 z&D0!?KYY2yLxYL;Tg2JDHQ2>nD){mbx!lxDs9C}L>3{fDv>gQ({y^yVVyrD_L-Q@K zl=6U|a@h6aBByM#C%Hi7o3vq`V*JM>{z^z-@ah+*Nd@ro7Ky-h-q8$5yo^BL27cHc zczeTBWw-0kJtvYX_&6TG8Q=c|rlSQ`3#{KLn3pR>bpt}uc49sQ^1ymYpo%>isrK`w zF;?|!M~~OkZG$Ws!9=KNJ4Q4G@<7#~)t2SM@|8NZv19d!fQ-Vt_s{q78hZE65@}+D z>1;tl_r|c^TF<nGzyZF}3mf@%iBz`wEn16ESL69btn+*SeylP_OuUluU`JgeeJJoN z47%;B&lz}=g|yM1+q)-2U{H7WTzYJZUKL9xi5-wv<%4;9uQN67a^7j4l~{d@Ax|?K zD6VrKf?r76LA>d0$q7aD6Z`>|5&~|TID#>X`SgJod3HNj>Ji^dHF|S#f!ChaL;z?7 zIE;$Xu596Ehj78PLa5A_;#_*~>cs9>j50#R6c^+c6^#*vvPzAvyMeGhTqYy5@*cdp z7_h>h*pc7C-xh8DYS&52TMF<fjNPVkg8i@aJRnpr+(<@-gg8e*`!1uThHXS`4&Z<% z?4PuazlwIT0_L8<+{P=2zSF}B9cX0YIp@pZD^Y?37}G+<XSIlOgu{pF3^%W74A|<H z9fkH2BT-*F4%QwP@`kkVB%?PZLUB0xpUF?41v49RMb+ZV#v}pa%c(g;KUkoJ5+U6) ztgy$&r#gMo;yL|B`gYIol#Q0f6@6{qOU$>H!65(!p%wp4a;<AXu!7y8TdSMsr<YB& zXPuDJBIOy*{!1&+IfiB&a{PYxF+bzl-b=!QhVBf_wBScK3FSMiE0ji4fK3tgJlpa+ zs#`f*uqy{cLo7UpB$Zx90I*K1c!A$TQi@l*dqyOj0r7YbKDR1H2%Ul*%LA1zsTRD` z;>-gHUg_;gIn-|ygOavvM?=j7rgMyGEz_Yoi)w*yz!;{&F$E4HHA|njp9B#i&f#)Y z{U_x7DbIAj&huBVx&70W(?;drdnyy`n}>^{${jgKHe-<jWcvglu}uVtRQt)=cs3}) zU4aHB*q!mR`zmbSF@q6N8~ZIiG=K5VP+>)2=2+7noLB=Ai@e%mkb~<hXsK+7OuVxD zvH^~QEg(NOqp8bml<v9A4_KbJG<m-D{Ud(skdAnj0)FMFl4eo|c7IO+DVxX*C~xbd z9vX!c!2}L~Z{5u)x4mZ>9*pi-ib%0b)Q8QbMki?3o@)Gc@b{H#mYAlf*&wQA7~oEy zH56q`XejqAQVYCVcP7Vn<m0iB4~OQzd+qfLvj=9AGiVutU;Xh<ecufjci{TAG4X+V z*4oI@7kr?@_BSkTsc7kcGP`}PI!la7syvJT=@I8p(>AK9{rb{|iS~m#`O}&ubIbQS ze$iO|@M-1!kTdV4g&(u)XOPdcYRg{r_lwHoV2EDH*2&w9b!sezE(}PU#?8usk?tuc zt2N*KQeyfaaWW^N;e9xx7wJFf@QR&&NiqFT#w!fXJzRE2ghpOY!+hWEE8B+N*19il zEjqm5^7ZcWL+(=cCmPIt?PcdSF~qrDxA3)1rBs>n_8=F5z{RFcoQfm}wdx916)RZB zZYnMIe?=7Ztp-(WVqW(ZcIz>s%u{$JlHhcyA+su1eXDgR&CK_Y&xxlv^q1Set=T^h zQC#e-6{zFMpf&<-uFA93n@@lE(<w|9z>{w?3Edf}N_t8!Qe_=fl%^mjo&HMvx5TZE z6VuBXMvYw!gv6Tu6ct)_mY@qVNEfCyz5AzLX%jL$PA{N}{4_a~M1f)ct<%df6vX7S zbCLprfSegW=cUFy(+qcEL>JIjuYUxJCzwv_Zcg6K6z-J0^-rHVR%NKc4}bPc>}7sL z)8Ras5*&<jd&ZHeEUev*z8wd9yW?{ZGTihZ%$JHFlvgVX0UCX;GWSfOgmK3GtUW-Q zL^56oc;$@N5peHKLAl|VJ5w4MYH6aU6G4}{@(f710~vl2#;}&RuMl8X{5G%^faawP z5lG`VpR-}sV4;PxKxEQG97(+W)*o5kUF@%Lo*BRz=Vh*tt5+<WETfz~t1GO4K2N{T z@4B2RJa2Mn-<T*O32a*tpjhg_ba1ZZv?}=pD(Bl3QXVF(g;ug;)7FgaJVD2#DKgwR z)T!|!FsS=$jWJvX+%Nm+*8V7)zz@PSn4$F$q*2-B!vDy6+@`v%P!ILre6mQ4_i~bN zj><=l9j$3%994X(43G4|8|U}hyQCD!4FaX|E3`^{*lGHDjo<gh<>g$<?<@UUhq;me z+;$IIdzJ2z&7aie^^Rli7d~CI#Os2%7ylW9IQUov$dg__pkFAq%Oq65C#&%|{ttYy zu)Pg`o2*T@WjYv8{+=DV0&9&O<#w~22Oo0?T39|N2-TDK@D0Ug+#Y=@+zvoW;WF$@ z)i0obD{H|)fH-&`JlV5^VsKziy`&FgKf#)(E`j0nMh)4oQxeY{25=}?EA&dx0GYD} zTr&u6T$)Ue&#b>SAoH%4+zMb&OA3?;x0M~~lay>$s54)z<H+bS2EnI-{i9NWk$r*d zp2f*8#M!4!v5d0rQnN2DGhdc!#JsC}f&2bvm#{8H2K4SDHk$ZGE0#U?Xv-359zskZ zk<OxuJt3J#D=!;L5_-Z0Kjvs;p)~cSOtksHslzvNAr3PCrU6N!#}tGuQTs~%VNd~A zaAhdo*{)e3+qtGiTa!MG=gc4syH)jzLiw^@;V;Z%@omPuvitrsK)(Pr0+~^8AaeK> z92eGNJ|K%vJilhPfN4W0B-5t}1;l70!dXZFun-0B046?F0sS*&@kOpmmw2|iCHMtY zc^*ZD3$g%tFrQBZ7Ceq^E6NrDKJoj=DwO%;<oRxLK~%_NDlJMDz1V46;fTKl0`0`A z0)xD*e5Eij-tXuI)b}|GVj+%e@PzJ-Ny>hw-SB`JCM&tHGot2%CswCXAyFd<(=KOQ zlJA*njdI~c#Q4mah$Dpfl0R!*t@eP4m2gvH*edj^QFz9~1KA9;rrpfI(Lkb=r@#hH ztje}@?xMa`yRBCW8fH4!f;lW@rM5%VvC#RV#W<#eIJ7tF_9bk(koC5*pBM}1*zK!y zi#wDP&-=(5b}ubZe>+7@@G^d;a5TSB^6|NvrZCRN(z%c99c#4TdM5D!u_5j=Un~!M zVN~O|V6|R6{q{96-)`*s)GoP8HdU%waR~+<f4Xr~$n4Uz@(EuH+rCG!=bL@6+TYGn z%isa<8d~Wfuf(r%>w{Qsj0}^N7l#S%JwU#X^U!_0p~<i2vn%g@Ju)^@Ff<SP$l{(I zGfGC^b4e&-jPhtN_w!dnk7jhUV`{Owkl491jpzQ1XyNkvkJowiZO}eizm>}$eIcYo zQBTPA(ZjMIn0q64e6TCEs&RJ45wFtw`*XQnGJS8*oc;-@TMg4y9-e!T*Ntnhe8Dn? zth<3XC&`tX<3XI1`L0%O>$L(5YK?v30?m{wUs9>@n{@R}SYjfL%;QS>Ar1-Fnkv?~ zy6%nMnz?UbRc;@)Y`AF&0XZU8CMAabasy=jySERKQ|v?hbhKH)*7_gN6{;Ll{Dm!B z8l|r|+3-gMbuClpi*Y|YB9lRuCX1C5%WV0o0{<E>-E6B^W|M&tUGEXeUY!4fk;Nl; zEdQKu&sYuEB{P$WUHYWuLKm{q&^6@Pj}FO#YlH;K9pIsHFIGwOMqp>Sva(U=p`De| zScggp>fN&O$hRsT_9OI<5#cv2=}JVZJf)2-PeH9ZPkuSOUsQ3Sh%X_o<e_7q@h;c1 zwb?hp3{!&k6xoc}gGBqyOgC`3sqz#_JE>A~<OnoNSH?{}1c;sDq7_Z5_2hc<#Xg_H zMg<{MPm%}1*@@rg2t+l}=-A_w=lZlZf6LcksTgL`rpm^9lNmRo^(5kH!Dxc_UvK5z zmU$E%kB1e|LRH}RgDo6E!Re~;bJ87lz3|LZZ>=!5*SdfHtdn-LZ7>~SmM;05&9k1P z>g5W5X`Q^ZWNhqzIp>hLz4^^Oh?%vcp2`Iq;tBI>KU>rH-+vCgdfmxLEjU&>Z_A4Q z7i>n4RcwgBvUcM~{ecbFOD%6N_8W?bwu+V4@0{YWIF9rb-C{n>aGQA%drSUtO}U^7 z8aKvIPDDQESkI87;<k9TaHkXMU-&;Mg%W3bYP%v(F4H?tCpWC@9Q1IMI$qKga5Dib z+fJ-SDrPR;jXt&NKviB#0+|*E04xxx-APP9rC>}?0LRvNg7}N!l~4i|iuvSdt%8s# zaRAG2rgd^>@CJK9pu&1$7$K0oHZ9rlQwHV;!rQXx71lbX{n`W72XI;G)yf2!TsB7g zB(`{w1T8v+pOME4u(j>Pbg1`iTbEVomeaSe3P2$@eM$dcDb<>cNo*GuG=3rxC>iG} z8G=u9>3M6W)r?Sm?6#i~yBN*A&{O#6G7pBF6;A0>WnEc1RScQ>h92K8&beoJ6qR>n znyAa3BKdMNSsXzx1Rs*k57_NmQ0^&6fj7%Xq`D;{g((>&0p}qw6F4Zlq0=H*Tg2mZ zXG$O_mg~rj1lb6|{9i6aC0s-?BT9>b&n@dp8#^z^Z&=dj3BDaPt4S&^ZDTz=CSQj8 zw9xho`lRXB7y(m-iQP{E2sQ}UGMFWr-QXRjQXJ1v@ytQ7FjQy07a+uJV%$*~znr)b z1Y_^-!8@t!xa2R@7$YVs@#UImQv&*qRYowoXl3n$BwpEEPfIw_=%GJT1>gvcDq0mC z#H-M8kHQ6pA@Xxe5)XS~TvSg;MBIULMAMgrgR&TEOO)<dax!CqiLFt%V$!G~P6fz# zi#vT@vptS;!yHlaw`EVZP5^+%MH~jfSVU0ycxjry)5Jr1DU$Q`<oQ_aw%wLc@<l)p z?il-VkZj*YG?6Hz$6NB}hvS6zyJlVC_7s&#@bD?KdB1n%V{6BIS7uE>m29gK^E~rK z7&n#uHMV=7|5B%F)u<r$MLO?RemHb^u=!6uZC$U0#HmwUQUR>+j=EU#%r1@j^%CQg zT!~fEfw})zKhSBm?J64-+J>@ZFZHyTW+vum%;P8P8y1K_`tWTg;FwoUHt7w&(62%m z+*|#JNV9Ec(+1)ZmvQf){PA~w2B*aE{&I6O6WBGC?;T5-c!Ec|E}){II}j-4uE$o$ zZd3zg;w4$H&y@WV80o<j6wp)LU|o>-18;sHR#c5!ev^DF&j&#Hqv*$rMWya|=v7y* z3$intuo@GDk-SUY-zzpf*kfa3OuQ$T?f}=)`TfxU3jL6R9TDsiU9Ws5>>iODzS&pI zg-bh1&duq~)iUNH7pRM}_w>GQr#|Fl_%#9mV!UKg;>0^80e8I0UgY1OP!;u?4d-$; z`xpAgZh76&L;KSCg|qKsaT_Z8^)%7J>oDlLWYLjW{5ck~T0F0%aH`(}h;h(7-UJGG zeM)M3z~2LwZP<$~A5>?z#jTV~qPMc1zXT#53<EOYhd-gZbyK@9W^0#_pq~zQ2=&;1 z!N^#eFqJhx{MJrD`o@?Hba-WVDIc4re*Z-;vF4{J!;gfeU?(Gce%LShoQ+2&$R~(- zL{Rl}v$1-mACvJ~k3x`{2>pv&{CDEy#Y_yAT{3hz#QzV0l}mqZd7#Pxc>_U5U=-vX zDJx}!CeTZ8voMJ*Av6NYx{BPpGJQ(+iU3s{^Vd4o$XGMlw6`S-IB~ZrTpc#QH6%^8 z=aF!5Zr`FBy(PLRm&bt>4r6NWBHI?9PB6ww_gMbH2}i??c%Y)a$X7DOr*+tDyL#>M z|Hdes<$-a%5b~IQ`n1*72bhIS<7mu`e;PVj`k1MUKg^N_-zZBP;G0x&N}4>``w*c( zN|^od56#LPI;uN?^F)hE?m80De|zomgZ;NmGXsS9<J221`Cg?Q0|uzQSx<E<TnF5! zVQ=5E2Zaf|`9#-mlB@o8D7Y7!JNmeVcUG^R#PnocZT-fG)IjUAqcf@?nr~k-CBT|# zcIkp?Jl5#i<vk||_Cm(j^thvU=wo<Vl#OabZTgi>xud5X$Cyfyx?4&X@o*lU*nRMa z3r?DD!Iodw#_}aq63k-W7TXU>Pk;Qky`1{eA01S)k1gSEgaJQZ=s9|hvZp=djZ7ov zbsuA6B#DA}B31@z(UVe37P9g)&X5YvqIF;f@v}yNY1fIX75-FRVgb??1jdx9a{ze= zoqcUIz;Ypc4dHBa``lzL=}(Q25LF2x%~J{o65HK*Igfa|>OQwAd|D;5eK)0(`EL2L z>FliiO;YaGN?_IH6XQS-%9lOe!GzWW-l^KO4ai7jog!L)?8Pa8#CBH60Zb5i3I=EI zU8XXzzbSLVH>L(!5X2{m`ffP?9|GwJQI|FNc^QRC5O-GOVTs&fY;P31y1hW`a2c}J z$va5-!jKImR%X0%0XK#m0GuJ}!GY=wBBF3v8zcdBT7`qO)MHDzi7~L7ENzLagvFj` zpb409!eyNjI+6W!3gS1Z?H%Yp_w4EfO-1A(T#j~%wn-s%<Wa5*sBx^}oAA9VTy;D1 z5fPRE&n6Mk2``XTnUZRS&$8YN^-u+IjG>{R2E#|Luw>d0sd~6JbxNO9cmu_4wjEg} zXx@XmTrJdgIBFyQEPoLpLx&1cBDSDcauSZlS|2Ce(1clenKy9U;TG`z(qfEQ19XDV zK@@+IQdc`FGGk3UhF1%7WMTkEi%fhjhMLwh2lA%vzRGY9DpDdAdb1cl`4wDV>F&}t zpdA(Yh5gp;s|A@!BIPg=cU8Br$aJQ%#7~?2TRQdBM$va$e;`=dnL1D1u1?njluc>L zGD{!Ir%lE^0<=N_QC(DK;}^sz8Bi(P@e(7w`yjFe+FY7KvD{f)p5<K-Stm>6_9Y+) zY<NIj!;j%P@b=fOY!=%7)xd+Wir)ILf6KS!-;KTh-)B?<_+^2fcJ%h>`nPMPdrB^H z9ma=Rudq<X<&HO^Y0+4}KbmWn5lF5lcdUuK5pbk?Me?VIy<b#9TP2UB-u4|$h-H*c zi37^{ptmIR?C~m{U;5ZR#xu3^tHQniv-`Yh-qdz=V-`oc!Slz&YwMFJ9u~KjP!Ik0 ze~TY*V<H08+vUz-SDuqcymmNtjtovBe(6y?4g3?36L1s1))^t%>W4W8*J{w0t75Wu z4L+Ou-uwHOHcTw^%Pmkyd7hpno1$Fqv(YB`t@ejX*~I3}&+kx1k3BzDG=Re^?Emg7 z$Fo(@DucKcN8>^x_YN`Zjosj553QGr&x!8ud@N8y)HLIj=id{~RexKszUxcw>pY5; zw%giK`F!_u%(z=}uUdB1=T5|&+!KmT8pmf^`{GL_2mdBZZB^3Y*DP)=esAsLP&2Tw z7*dW!Y^<4Fl433vF{Gm+NYKpruRpP_!1z<N-U}z6p`?&2p}XFy3yfc(JdHw0Kp=H~ zhO!yE-22{011EZ{#z6g(i}3+%OLjvWugXzR4v?zL-?%yG{{+p-kvYjBR)eY}Y}#@4 zeHN1kTeaT($X*-|C$su2u)e-VoJ@IppnCFx)Hfv_xdUF;yJf=uFcWTEo5KFBWX><% z7(@lurPMR=ual{ySZ;^)b|sDE_&?F2-S@VZX@6_pmIbn^^rykOae@h`usooS6Sg8+ zy9#7YKt<T-auDya?#UCUZdxb~=ZXOTRTYfyQ&zAMBQsrCILzx5!2>eA7}5Xx>EzB_ zN{}2%XRNl?(l#8~{Q9V?>w2kZ(FCG_pj+V#@)9$1I**y75>S7Zpb@`q`YnThAD>tg z|6g{AyJl7~{!8^)G}TqZ9B~6PjHB^~vUI7+9Ou>h$*f@ya?O3rwDL@)^Q`PWmUo#$ z9X3B_MHJT#B|&eG`99-;_Y${qocNJc;Ri74woE-%3gL~SC82!v2TyfH!e^07lh#hk zq6=opQpPumGQsaW$^sd0zj;=WZkXyfqX@x40Cn00`}rlNGsOp4s`Anr>T-Cywha@$ z9Po2z@5<^<n$8R2E`hJR^VHtlo&E31JYQ!StdmykMr@{T3`vF;UOA*a;t+mxkt2js z<c2(fjnKSwL3Ur)HkQEEFGZ8DHrEyZt9&9frZj}uF&;Yi53K@ET8M0nlPpG28Wq=i z9o?0e7<^nmZ`UOHDlr~g3A;dqkPvw8v_tTqK8Q0+L)VHXK5he}Dm`N>5kKKd4BfJX zX@NaHL=Vk02XcZ&PyHhXeL^>7o)(WD5D*>J51O8GM{}KECZzc8AV6_~F!v!=I0<~Q z0KN;wYZ9xcaW~;;?1aKw;Hipr`cWuM#v=mowB<A2wBj0dQK8m&6jrpu)FSo@FHk(J z<ZD`tG9)#a&QLqop++y2xKR4{fr(K}R{4eN2;jd9I@1zvTETCljANomvI-c735<T$ zd@oR#+_eXC?^%xhy)6PA>>xv7Y0q!XP?`=aiM%6hF5?6Kt|PTrDmZ(y?F18+CzvtX z%c`kBg(J1_L1s&A8XlP<Lt5Dh^Ajc(D-pCpv{fGOyV=h%_LDdXv@1u)9x?jz?vv|3 zG+plm^iSyHZX^d?A8>2dGs6ID<tVTSC7Aca-RW{un11BEbWv7XbR|3<xGp?)i-ZW_ ziTL5Od8%;bjwjGdlPj2ziC*oATaKwdZzA(uOsd8L4Vo;jLnK}twKmJD)1SbDF35$e z69XZZM`5ZATOd$sz!j**jSM14!8|^?WUorN$7!KHpn<}I0jUg2zkxNv%x`C}O#_EW zf2tWCfdw&uc|!y-19iM{lQd!x!pP0OU&!wGTe*lGCp-hM*eNN?Z19VTD(~PiC$N+z z#r~Onm6F8GV*Id`5sZi5`m}%ADjVz7J<>wx7Za!bN`TEJ@9he!GXG3|&(T3IKa{C` zq*KLy_{%QZvYnAI1y4>yFY&%5<#}ybTk>#OrCk4BK*ex(wzU6O@lft`2i#L)v>g=^ zV4M*WI;Y7i)5bHkqdxf3+`MqJIyKOTuD`A*t}*sZb#a>glTWYnDmV7bsSh4`LcR(n zh37$k9jv1}s^oXPw_~W+Ti9GaaBb-7l<}I`AGbd*P1R@;(9=otT+)`f@D2q<=xEd} zUWumkQA7UbLt^MyRQN%t+y>R`?WtU^uaZB?S4vZCgPyo~wsDQkP~6_Q&}~<}c0d6u z(p+A%gfd|L>Pw;T?s;CeQ;cVS_Pg@-)>SpJFnu^H9Va41!pn(mi*p?PlxoBtj)bu* zbXfba=a26SX5e)Jr@Waee^Y8!<3t6|2~Te`(q|uQE@ax`)&mrBkL6y8<p}Qa$)S`( zOm7^3oBDQIIrTDi&4Hlm%ksySujjSu@rs~`<cA)OZM%0g+55OG#futf->c4_@ZqZb zGK+Stv6+5VI-^{0wC1%IeB9=gWX$+H`RCC~zi^fhy6BeID#U1zzdkuC8oL<O4qs0d zY!kRXX9L7QZhZ-y5q-PA&!(!3LZ<uxq^JFyvdE#Q<yR<2IbmJ2BrBvk*d#8^!sVQ8 zB4>Eu?f$FE>wXu86(|4E>YYAwaT<RaO!Sr9U(?f3ju8whHQI$$V4B@Zz$|P1(2Y#S z;=l|;8@DhkT*yui$-tbhmHEReeRTXb`4z3;ooceu(|O=sxu6%3fjAqr2&Rj62z5Dp z17Q}jQ<@a45qdjm+-93VL=8-%IH_r3uPXb7DL?JS&<)3L0Zz_%7oKOVvu(g>8iB@} z{sNQ4jdOQE+pT3&O*2oKds7v_?oQdc>d9}IX3lghSL!^eSp(YYW*^PqtIAX5W0e`- z9%^OL969F5n%Q2Zv}`ElL}9V{*?H<zU#2L!fR$5Q2IlC?14z7?`{r7CMF&US`a9k7 zH%tTs|90VM_p-f2O2Z8SeG;p1`M)K{EBmQ#rTftnrkUTY6|u0~p1Iv6U8=tov0Kyu z0Klt1@cc{I(93teq7HKOr|NB5Gavgt&AFm*h+qfQeNN4RQ*!qDX=J}1UuCv17gY8t zU-f03V(x8|+Qk$!41{+UDXVHHE&}aAr;5J*<$ZNmR_x8LGQ*9FolX<u4J&d;4`Y!o z<|WJj^dzr(XMoX`l$dY}>o`$87Ct}27`GwGg?&;~o$iNZYOsQ*f#)i{E<)GPU&=!_ zdN0@<k;1lHdxVy1!GqW^lVv|V5=`g$KCnawDz11U&JiuJp9OPsmdHp8s0Q*|X&5Rk zZWVfIR39)T;~)lMW=5%SGakyuN5J|_G|-K=57UyQsW0bs0Jt@BrszcrSEs_LmXDuD z@#t@54VrzqS*c6E3&|vRjnuM?>uAy_SSx-U0Vc#-INgO!jFYS=#<1{=R~jSyF{OZ% zuK6$a2UEo!sGe*OrO@E%!6Av>U3v%~9ThGl`L+|hrygFo@;s2ICQG<PHr`eXQj2>L z*G*ut`~_D=ZIz<08tYgiijZD(p37ztw5S@$B3_twAqGsJ>b+Y)T0x|ZWG_T6sPdP? z1?gZEQqv^2_onZ`w#ioRESZ5dDB<o!d4PE!0y}?p&x$-M93YWN82o7X8AS_;6E@wK zIC%F(Z;_NFCXAx`ldk|BG`7RQcf6d2Ac}8yLocdyA2G)iI|lmNJm|hydNoN!X%@o5 zS)7p=t--aiBw0P`QF7nWSVxN9r94bB(%sXCTBuK%_%#I|hIr<f(jL^3-){98Z1IHh z(_;BLBWnLy+@cK#=iw=H$a!-Po2S>XekF;;Jqy#HRvT_`hF_-7<oN`us2^)4#?t&r zg)wko)6jqm5{af%c`)q>eR<Pt?J67xsg+pEGwP(d@?o7iTz&fA(V^W9I?5lN+}e>m z=LKWuLdkt&*|$4Xo<MY<6NPEg26NRuuQ*Wk)Q!jAdmJx&S~1ytvR(C=!fu@L5sC1! z_6J;s@4fItW8>v$6)QkclS{j<Wv^QEp)~vAf&48^d)3jWa$!hyoXi`1{ZhVcr?qai zVo*hw7<>EAdA~lpu;7K8iE=$XKvdV63Zit+iX-3u=e4lS`s(6%8(TE<U%&I4<X<&> z#O@{YBj`ixgL4YDIsHpHT`AxVukQPv=YKA{6SC+rD-f=?YP3zk<I*WBK;eiC>}t@R z+FM~N^=`xnw4l}g#{X2N3v-{vEX})7s#~r0EVvpqh?ru|PrhlJ-#&FE?T*?5x`?bJ zhufPM)cK{ur3cC*Ps#>Yt!M1CU}Q%_(fUT8ee9$<EREg=$Zhmq;#Jz|wd7$>*`E~S zhcWLOyDn=xe#hPZ>?<AK8S$@(rF+GqZY(3(|9a{wcbGp&uH3cY;i{Z6IG`!p|09S5 zmx$W?2$v#NdG$DK-;;do8AXoqH^~KzX~24%RXerbe<<H)mom110ic(b^WES%H2O$Q z#gyrVqo}(=ia#Yp(pt|MU)}q#|KxD;(oettOlfzhpEIlR%WrFFaCm8SPu6I`oyG1g z<IeZ>-Eh7yZnSDq{_mLnqj0syR2PvXy13oE)!19l&zVvAK|M}RDZCi^x4g<<<g8Ll zwzrBdXR00yDh2nQbtH1g9x5bX2f;XLq~f>AxG91?S-Dy1x?!Jps{M4cA@2)=oDLFS zZ+r`@zku0Ja_qFC8N)YYr<hksp{q61NLl7P>ztLRQ-i>c)7{BpRJHi#kQ*mIIfgAM z*Q~CNL<v<xv=N!3Zp$fW_EMjc7EeIbWE4P3@+zGM9wMec8GchQsFDVA0({<}aIFaV zG0@poZt!1qD6+q9j%?7=numuLpDRT!OZ5qlmY+`M6AF}*$#YW0m-*&m9S!0~2P>RC zj>!I#w054tG|S!_hCtTroFHmWTe<z~n(xS;w+L=WX#3p#1LS?K8Q;td0uNR4lUF_& z++QP*8(K;-weaW;aWvP{T+4u(CA87gZ?y;UE8(}-VAxW76vo!`%w#VKYR{d(x|WRn zuWjA*n}kw24Ti|sqCnX>a<#dxsBw|Z<Efr44HJ9$%Qh?evm7G+`#uX%pepFp6VDUw z2HF}@C<j}0Ux$5v^Eb&4Q{FkP#FB_H9u0Uya^6H+*xmNGvS>=x<FNa_I-8425Y)x- zVzqg_7skV~i*J{P7!6$;{)D0RZxX^>5r)@?L>a=nvB6eIlXZRb`gnF-k>l3!e-F5V z=L3netYt{>>{Nm5EdlBQX#&2kF}4p{*(Je8M`4i*OJxqY8r6ptV^ui0zzB7j<el*$ zYyIVX)Aw{MhA!|#^MF`Vr0$tx2o#x?Cm|R%Xiu|se*E6`_~^juh>?t~6-AMUACxsf zeMWMeIbk*<ipq7XMUggQOH$wgk;EqM!&6=|M@{86Xki24pD7eYLs2*pc^u}(9_6eL z*QQf~3d5?Klc8SLCtMY3zj-aV#F!kxc}E4fKG7;1KH*d;;G7~CnoZ)oEJRGGW-3UX zf{4Z9jrypYRwV5#pf5diq{HyggczC*ahdH~Y2iA=%&e6V+AGm3z~T|VYLzP}<<Vr( zQaCSUnHJei02)y@tyvuiP|j<?JY@<z6m@D)r4^QZ<SpJ%l)3njsmyd3)=-W*k5e~Z znJ&dhB@q=A&Prp~%@Y{G;VDw%rxqMxGB>`&ju;7D;H}9M=!t6}VWrsHf<&sKOlCkh zkV{LtNusB=EC`@#<tlPcp)E766s*@g$Upm~$5}gN4)tMC0S>SMu!Y1N&q^?=WDB5z zh`@*9NiVz>ev_<$F0NS&Wd(2T6PBhnLNvCk^Q_c&{P8%vamdX#eR5tF-sYRcAmdK3 zrBB^SAt6}6)L0P2ue-TP!szbKZB)oekX|fi7vv&hkwfO==YBY9w&`!o!g%4KdQj0Z zAgd>jES*bJ_QGh&s=BRPrDq4+r6>ujdA1B_%RJK)fIGXe5Ahu9yV~TDcr8s*yD81a zqqm{@!w$1-z+8Mr*Y;9CptSz0_e2NJiLO%2P1AqtxfP3uaiW*$jLPZcU8i`NhbS6B z82&wI@nWQ*`7U+mYa^HJB20h1^XwV(LmR~Lt&r~3$Q||HmTpZnCSG++4L#9N;aDR; z=`-QFl(QQy|L_yJ;+I)xnVJ0x+*@Ys2zGgV<9JlNkewm~Zqayli^{PK3}9XP%7NMA za?t>k#oATHW!ATJJT5-=SDjK=Tesz=PE_V&hJ5mq&y4DDjdDC9G`vrk#ql!x+DPj7 zy9mS}c0<p${i?w<tGbOsL|n+#JKnw6+i^Wio5St$&_R6<Xukeeb+i_9-MV4z1&2NP zdtcRbFE$-U)ipj;v+D7+J`9I#)fhkAVYVxvT*wn{ErBcEU*3B7p~tRC=Bcbip$#ff z{u1^g>g~pgjXk20+!?%maMyyemX<2!5kGrx{FmJ!<5+jO5a(7Ns47|AKjphH{fMn< zyNg&4*FJV_)uQb$;t@1=SN$iSv^_V&`=}sNl_d)f+gBG8fKd3EEAJ{bSv%+X#5xx- zVu&+*t^7v+Ty9;arY>+|j94|d!p&Fho)Zx0IzHF$_WQ4XytehMzWTiGt4#-lEbaum z;SXH->z0kvkMo<4>Ic5X?_lu!e)C_~?z)CzxkZELv~S;9Mf9=qCQnCW7doReICj+* zghsC4R%m@RQD{Ke4?6Moo%8&>`7Lb5zKv2C@l@6n8q^uy(-prUb^ZFa>a_AvI_!*) zqlzgBE-7K#AoX2mQk5lImJ*lIPak_PU1RfT{<DkC%~Jj4cv;IyC)v*AONo_x`vcZ| zb?S@8&XGW$ossmyq7&9u6*UhfpR$gsKV-(Js*{lDGpQDiiZIBD+dTPTjc?4^z6a@( z2j&bSj3+T+B{^fX>)#nrSh~B$yL3#R7-dht$(?Mh69uilql%Tal0^Y;a5TPfwMq)4 zPkG<^zB*Nj4{DuPX<X&BX|BW`bMX=M;<u#uhl?pcDkN#fp-xE#<k+)GlG6%=@@}3- z<F|P$<|GBuNRj^8&=_-erc_XB)*s<Y1GUmqyiwO(<X_X0%S=F&$uAQOf?9L1g+Q4% z92^~ZVY01!rN(dH-=62uGB;)%HxcUX7tVg9Vk_lD+sm#k=G{RreaF9}(Y1HjJa^{I z?|Bl+Z1c3wY*X}%u&DDGkq8U13TGAu;7}zc#RS;J@ZH?$wQCQ1Rl;kNs^dQX&;_3Q zP)xwej0Z6<Y}H}fxBgBU;oLdAE36wHC3p}=PK8NoA7QR6dG_wFF4Cba&EnQzc4rs& zuS&xO{(|Th9%b*&DIBjk=q(o`eLew^Xx+xmd<`;DPV&DpD%vr~rS9JldnU)+Pt5@< z>Bg5Gq?$ni@OoXStIqyl@kIfq{S2QBRV5yEFzZMF0_Cwb1gF~QmX1p`qD9Q%^N;i% zhI}FM@e)l-P7=&$sLezIro`nq%CH@}!B3LVsv$poNeeroH$_|EgNvkVguA>LoQA31 zm|2qe4c)s;mGMGMgH?w?_@TwVR)c4mWxsCdoCIFPW^bkOU;Q_&6C3vxbgwuJsfH~^ zT!!l;UD4shE3kRHZsd|;`ezr5$w=k-*eNijjO-88UgyiOZOO5R=aGgz9uID(FH9e_ z&~sp?P$5kAJmZ+^i?W^xf(afb>-21uuk-V|TQuyoX0!1j5#6R6waEU_Wbot}#G${d zSx}YFPi5?zj25v2A8LBhXQ?#>evI%{*~9`_athay)p&NzFojc`9l|gI2U%v6CuotR z_~&Ngje+G+#29&Z*|V)=wxNwGuL~_2?O2z;x`ZbM_ls#ls+|Gmf-O@B!P40ZBl|An zvCY=^LD9v3fb=gqF;g_(1*y@CnY`&bkW~(EI@Nr|v&4CM5=B8%Ah#|ToXeh^iELrn z(}JD20coCkh^>8q@!bU0V-lp8%%Jf$3L{ziNe)u~h<_&Vcmd~u#tZ%wyaG#|#Hb_& za+3f~E&K?HEIyOtzRAMT71h;ges!_fmS}Gyr|Mu#Pk31>R&=9GB`O52Nq-G|dX709 zN;y3B|L<@~2oe>BpwQB7w<f7Xy_+QH(~iAeY5%H}ba~C)G+fwsktNA}bMKj-U)y-E zvmbW^C-_`wU#TE+)W$zu*8fs`a@c;&a>#+YZrO{Adph^IUwi#8kT$3Uxn0eb*RuB4 zojRrA3v`@Nz9hEJNTWe&$^#?6@&@v?OP2k#w@f7ZbzCm5($?YSo$W7&-)bRqs$@b| z3oG=MF)E9)CXomE<9NRw)^>0?JfMsPcbpTi!ZH<*pE>x>!16ZPsTQ3~hONAK)V+l@ znb(BooB;(OYr{HcE&iB2utS4&4K)Zb+A7TI(YA<Rzqs|>k4{I;71$S3bXd3ub99kT z44WC$_pTWn_TUzk3_lOvXoerG5?#dlJ&O}|q>bB%{qknfq_5ob`hU$p{cn3j!h?~G zNBS$?V;;_jew4lV*7D*_i<YAn#3!drxTjz}=Xs~}oEV8+SNC{NI7a+zy~mL&+jb)2 z*X&!`&wof9?-$vkGi{ft0{E&1V^xG5>uY_`27{lZzH}Uobd$pEYeUT6ipx_cYCJA? zJbd=JbA3PTC&*lFyZ8KDE(OE7sGQ}4z7Qjx(t;hIXaD(nzkVn>fYWZO+}Dh;%cY#H zB`aGmjEVlQapvUsEC#;yG5-E*(hfd+`fG>or!Og5g|qPOiglco89TbSAC$c?|JBj? zzrMP}yG9MFGoJAE?(Ew|$P%C8>`}V(JQ#mHbv~5M#Lasmz6;Yt|NF80os)5fTe7yE ziSWZ4nr{5;w6^N=k<@wN8eiUF0{2IEHocak#f5=6_H^FRpIbn8nV1!Y3m-{?={m)d zex&oF{P<qK(Kp_CSQvKS$NnRDr!}&waSrs{_62|51rPP=y`-ZlV&~CFv^uWr&66=d zy;=pVAU687orrRHWps07vCq<+Z0l&bi}{nnkJ}b@$h=z*jKnDHcSG}U{&2)>GtkQ= zUs1>I96ni5i4!JnkZ*JUb|`XC@uvS2!I|b$C+V-Q@LBY{QXE$SmCd(`8nR2G&KruE ze8^OpSe+BplI|{u@P9$V0iqiJ5kaa_E-)^S{f;=KUi!kdnItI@^F~c(v;BMlG)_ln zBX|j1XQHos3_K)z`YmV4O!>-;{kDQr*UsCU@A}gBX>u&AJvE9>PHoIg$Kg7&8SO}{ zG&W@R`Z=_EVlif{b3(bV7zC|bp>RfIsT9F#vNwS=Ky>%>JZP3nNdP`?$TXi0swX>k zcNYm>FN?_a!f*f0Z}vHaLgNoqI4_@mi?X-MPuNHlCcbkVKIfYYM>{Y2>dO^U9qi{i ziDp$&KwB*{wF^^`e-T>gO296L5^jAk&6P$p3F=zy=g*4ouzFXAK{#KA5V<;EDQQ}N z=XObN&vWttY5Z5|U@l$$Qwr&P4!+E2$b3d@?<{fWN#9Ya)y#W0=Dy!n@p!mJ1P|7b z^;F(dy6-MKvm+qlQ*v0`=J!G7(V=$}`q$aNQv-pP7peOyrn#4F8S=y-ol=Gg?@ICN zNGC0sze$#5(LqD(>^WfzHztQ|T>{$x_OKGFaMO?rHTiru*#o*_OC6;hie<(L5zHbo z0f^%nhlp>>EFnmgk=TKmNR9mbxK1kph^bu%9Dw+F2yvm)`QKadHRQfHTOh!06@-4q z;Y<S=*LTAEu>2N36aX=7l%+$x`NV4#mNp_ybbaJIk_h%2=82o)_0pI|(VeFX13KuZ z%I4oB{gr6`x@AtZ!w%46aT{Ia&*YzJb)di13gT8m1&rJPY1#%5bmn;wb!LlTeMb>g zF+M6b*#7>5`6m}Zd)3T^9egRfgeM?23#!<#>h#I<<3O$oH$8u{`Y?(kIMSYMIOg#R zh7!aRaqpgC;evon*I0UJF%7hIg=8Nvc1gHJa{mbCfQQXk2Ml&fgNhfx2A-5#>#%Q9 z4qU##i#!^09V9ikeB8)Ol1!&4L?$HC$5%Wd?0Bm%w&ZWAWz9Kqs+nF4no85z$hKIR zBP@|3^)$wcpE{MUzt5G&YtK+$98ku=(1wK8QS2T`LrTz&yoohSl@b@&trfm%HdZ7V zQP`)h7{5S^grsG<xmVG>*eN?}K=^6yK2V+Cs!K1hGH>S6MX*A|t4z?yp*7ipz#PK5 zMUW=Ex)N?$gEtCQDq;`>@w_0BK+|o)M(2M~?vkpO!XFH`4LMi7z1@dyN}!eB?zP`% z{uAz_3$8PM#X$S(MNcr?vCKj?1Z~g%GV&C*CoZD0O|w+R6}X-3#HHg5*`+LYoA@^* zjpjVv!zL6Y^otPbZUhE&TYHD6sd+z-vVDZSIV}t$E*f{bF;F*=SMLOF*kGwfGx*!j zx;6?0w{U&!FvT9Hy5bGbcQXGbNp0VL5(5k6LSelO_-`m|R<x=hwp76Tir#yCq`tZO z%nRFJ78UVUfLtVfQ(F_VIOq7pi3}Kf(tMi7b4S6?XE2~s?Xe&SEoRTJlaD_1pe=qG zf{M7$Ej0YX`zc(kdWjJB+lsk<>_!rWz;JDWa*9||YdSO0xOhB0_}DJOIJG2Ha{kJ| zZ1I<dZj>-~0UE<nvdb*Dd<Egh?Yr-$D|{@<1!g*t?OO{5An=*@me%QN*|8}oR|~5( zC8<`4QapInkNgHo4o|Oe&=XebluaQy%JB;w(6MW<ZzBx{tNWF_9vqLK87*G4t0QHl z*>ev8C?`Z!5oLz|qK?nZEngOY#5H}=k<H#8-iIEvoHOEqUu)ZBhs4Jn4{tZew?lLu z56xwDiQm}I-=w+K?OiwJ-eA?C-UrN1RO<1id#&0-A|6*goJC<|@|k?!79G}xgbMS? zp63Gt8}c0E?pAmo&$A4-uncQZ<y1sIEL<xxsS2|qL+xetclu|}>i=BPb}zJi7=Zm~ zS+ih+{b%>~)J?I&Wo6X%t=K(=$Npc~%d=*0Z18fldyQWE_@h?yAN7|?lFW<ZYT`C* zFWj}ecDbpnY?EE=$by4I%U`{2`?L@p8fx=KKmNw!ZDV2<^h=lr^@n~e-(gtaeQkL- z5I4)FWU8?3rtpblTfJ6AMioZBY<%H-%J_BJ?Q0M*PG4EnKjmQW;OkwF+#l$swjlq2 zBpvcxb>xm|e(U!pfSsiT`=4b|hSq&~=S#l`&-8hMu?i`Owrh{uauN^m&S%lI-NCPn zO`DcTsK|-6pI*Lf^7J}WUT1Sq^{Q(mT3-$cTq%z{G=)7*IYA@0mi>X~@Fv1tD0dQv z&=-+_h|3kTl$l|yGu_{11d*>*v_tw4rYB`o&*_ttWxnb-tub=NGMhZ}?)4v!=&%zS zSFB9zqj!i=1g_$=H`aq5au{^+hsy4dh^r_V1L&j?K5+a4-kg5xgQ;#X<=X1Yt}0ee zHc#`z#0X|mQ?LZWmoy1C8R4+l-H9o|7jA$6(5pVT20Td_MNgV*OqM_p_JwSziVd++ zYxJz9MaZ5%sSG1~NAf&1!Lq-2u8cCyIynWG9;%URw=l7?WT|;QUz|Iq>#=Bj^)w4Z z`y9HLn;mK#^#YtM6s4&O=hmHp>Nvkat&PIDVZTtWlr@E<Zj9^QKH}EWC;z;DD`-Fm z)%KmQjzcIG*LXwEOK`aD-y=#nFSC=69mWvMW6A(K1O+8w_{74?u^}F|ei6b7*3gBN zle2<gHQ&l03{MzPK(Jx>iW7HSsKil3;?cMX4+4#ly7x1|#J+7R0f0HUR3Prc<U(7; z3JDRujjcI!F#@4m(-Kd%y`xy&fu`<K`jhI(coGM14}jq{k7`k*E7<E=cUFx|Wx!!f zp6z&f7r85YI_NJ#i8Qn$W0C~adte>{UY(uKN{=a=9hO~|N?FqvQ^6yWcyGTb?`_Rl z1@8@bznj^FMA0@;W7#>g)D1|QgpQzx*q;6rNj5Dx4nx9qR4RqjE3o5Zlk4tJ>#70w z3B^Iu=Jvf1X9uct%bBBUaz8Yc;W=!p7~mXnV!BRvD~YB=7I8Z1VNEe)zzN-<)(qJ~ z>^;^84_Hb2(b^pgo`Hvt5PQTcoAxHN1C$Xb;3Ul5uoT}!V{D$S7|*ginFI>;D^mmU zMuJJ=tyVg(xI-L}AY+WA0s!XN>Mduadt42*i@R0(iK4L7ahha_N^9I^dAl=K9by>c zKOHFugAb0kF$Tf#{sr_*Otyp~ne8qzHJvJNCBhk!g+LQ*%*DA$))a)gLL(Cgr^Jqe zNeURTW2Gfa6&>hHJU=yk&6q&7%rDGC>w%VaJu2AE4iUYbZTP*f%@K<!#JgyAwo6}2 zftq&B#+xg_jA6ABnrX=P$BBMtZ|~g{X$L5bu9MP;%$4Fl<!jUbW9dxbqAb_<kBOPp ziQ|&C0An$TqQD6?6T#7vGY;q(0TnQiN{vv<KnO>HF|6E@kpUz$L0JVATrdR}(kx_2 zViPyOVo^XrHrZyz|M%hd|MY27gm>QedGF=Auj{&H<$oMHdJprcP1t##w#d$$jJp@c zBMvh@=@J8k3&+a~&p7eNvgg{W?S8#G|549b6;g^o@&49Ug|3n(SjC$aib5x&%<K!f zBsze-5B!0PQ3;Le)bPPSmj7-0{r&5Q7E)fKH1586%=e4=Y@emfR?DhuRse0(KZ7MG zJ(fM`iR7ZbZoSiw5!b5bCKQz=4{yCf-9>Dp1*=xg8tR{{0nU-)jnNlaWEOmOX)~ns zLl%q^qE<}f14pbyRMdtJgVL~apY2!QZcfzJb(9W_7nDVp9O?KX(tjNrAD*eYI0MA5 z#JE+?9Cac5ubJyu{MAm|(wr}TR7n%(5*wr<JfJLIVVh$M?ve-eRpIbR-9RZJOfWDY zT}~zjD&uZAm`yAEeEym#PHX;e2}6Cc`dKW*Ep#NaPEMW74Cp@a((V~wB1rQIcA2?r zwbPHcd%dhM#WUnVZ8UFNyAAkeb<EOS!c7Kuv~zIn-Hl_xNC-9j-Lz!g{QS5t-khll z+Jw~JkkAozK_j_am>J+<=!R3yk@)6r)FDYiA78J_&Hm{6-H_kB%7&BC&0l`}Il^M* zuNjc5sldIGxa$0MTX&ijKQ}5=ChvLSDpK_YJ}4dlvZN5}prb0J$u3im9NLMX53E-1 zj>wB(i+jY&bHe8RbNso{zgn01dHEI@cZ%pSWbt6rA0;Mcg)bfomrgvG%K@qRfW!MF z?rH58E%`qVZtN^G)-I$dioT&;xj8+3bgRwJTCe*HP1W#{36-O^?))Ka>8R?QJGO2A z6nvYM+mxQSDd6Z9t<u8dxsjWBnoM^-C+%c}+U7x5Bgu0pZ~BD#<!jun{QueXlA)vQ z6su?QpDOnjj0mpZy;9P$t>+#gM)i#KumtLX0JHE>f0w<k8mF2R;j^2G)^z`sPfw;F zUlXVvg)o~JF;G8vZ}Zz-lKryr5tCZ$Ukll7WA|WqqlS=FsacZqQB7;o^|J2<mHTGB z`FQp*frG20<b=`sSvfz>w=ooN?bwl8b#C5E^J|jt7FyOPNS?}9yt&ydFs!ib|FCXO zUt;T+cYxPGV3&`JXg{{U>rvOE<jCJj1OmZ`zy+-)$=t@;g>b`UnsR@{*W%?iyex}M zSh!G`E?=Y-2I^6JkdY>UW2;YObfiOB6U?v?mbg&Dk#bpQG#1rSf*H0EQ|rH$%t~Bm zkH(?mFJnLY4;Y@pVExFU?~+K`{-o~RQ>Q`)>x;8-#%GP7+fkCPO2mF9mgeHbp;zfU z@*Rt<Uw%^>+rzauk1bsB*$Y4Q3`{#@?JAMSFL9Yuy`7ugWrm2=ZP`ePejPRh9JF=j zejV1?*mj9hQ7A`;3)FOv7nH0^(>IO5-o@p?gov&^jL0Sp8{MaeSn0ZvK~=^2yrj!t z6{h7kZAVUXEM67*)a{d5J!(7xKSJF>h7;P4>}_(<#_p;8fr*X1!+xjGYwrytzH&u` zS~`~10U?GfkW@3`SMPpcquoM1UrJ2}bFLw0Zk1z^ZBk$GKY43PzYOZ_yCXaM3EwN! zQC**LoA78*8M@AVb?FA3TRJ1rTPuG#1g@gKm}>E@fyjqYL@^!$fgD(#w))jweBH`n zgMd~LXu<|4W3$3+#dcA7q3%D{0LiFDFz<*MNap}VYYkm^;x~akUtpcyfS7@h(Ec*+ zQZ@+(%9n)fw|=mAn6k=T4h|1MxfhcjM`q<&Rpq*;lwL1u<uu0K79>1XV8wt*GYodT zGS>pwI-q6`pkctX6<ZhN#2tF{o=GLNu=k%EeZ>Sg6#OB_eDJhsFPvR7b00diP7wZO z8~MyyH^OcMxs>Ziq#_m@Abl(n#+dc-?hD{AGg%(q#(PV?gekgEoOFvc1i6g!JFP>` zHcRfqlO*t9r>QTn{%H{`$CPyn)~LZ`FNo)@(l?R(b_-OIDunR{+$sTYk20o`suvak zH*_M6k^u<6bWpxi#p8nsIYLxdGg`U}o83ri1Ft1W4RlCkWoi_0BAVS5ebTgUM_e+L zES?}I7d0<5qqSpr+ub^c%Vcf~&9$4+dz!3&>J+T1PYcicW2AJk7AK*cGJ!G)6j89Y zM1$$MB$a=FN~^ZBWHM@(?$2082eQ791@?;{p>}sUTwj`naK=*kpK-7NYca_}YSvWQ za){c~^ayF&T@~Uq9lS3k_GK!Q;TtP-#E_{VnhoVO9vhM9E9Qf$Vbm%+_(t71qnM7$ z%&>fmJKm7LRdH?4jf{HgWnLE{#&=JSV(WyyY1^j9-BumFc6KE^sR)0=qO>{fBii>v zbz?;lYT%*XO>6|@BskIhCoJ8!CPx36!b%vsfA|3dIetEwP}9#RobMahojl-5K+mMM zS_Sv^yXYs4UFBjegjIqviWQxtd%;92QP6k&q%CA^X2Q^oR+aY7!O=Wt8^*01#1Ico znlSD#jdSeM*b5RE$dH?KCjtU}qrp$#=~9w%VM5rhhOTE~`>{hLBuiOufaPlXNEVzo z(#YlTm|ZgGu=hvYs9!?X`5dYH+}6VIa#ZsNeQ<oheG)@HTWqnjG*LO=Pd&G4x%raa zh&!0Vctc7&7w8p<L`zrDYwllUn&`Vc>Xxj|fx$-yma><Q*Q_kKBo;0aF9$&Mv+#fw zCi!L~Pbo%I4lm_a4Yws``2zOmNU?CcjMo$I*(ZR1T%MLN?Zo!r6&GKPT+F*F*j5lV zfGN0oYU(P3f6~wm3$Z}}4Vv&qWX7YF*{9=Z7i+gutis5SD_eg?-l*`U4ZFl^Nduo2 zG}xp`GVUY-P>`p;*YwD(`-ik9eU{QTOX2IU<HtNYJHYrR4;Qb-9M_+kCetYqKh1sJ zjDweBF~4lyILQA9*|jGaI9z0XI7CGbt;_VHMJ$_#{|-o#o0j#0HEl(3?)a~<gsO9| z!1wC+i4SliyK+sRWRNLST22LAvAh_y&1Aqom~b}kihcKVm%<f^FX=ASDQ(aGyg<LM zqT`dQjh|f1-9oK|!>gvh;bg7dYD!BLJxO+eW!TuE_YHql_RE*=`0!T7bEDl8y3{!_ z2H&+jI|g}I>P}yXdiF-0%!U>k2HjDGNBs29$ERzY4aK=tC)C`w3uWU2Ry&{A?|XG9 zj|d=D*JsWM39wm%8C77BZ_du#d&<`rKhydSPm)3(R=?p|EBoNeJVUAHR-c%*)#jQf z-!Q9-l=Zey=uB@ubaINTXS6x{d9($eg?T*q_@ZB~>T7`#j0&sn-0;l1B24wLzNMgZ zMs-0Kr09y=y-f}&ZmydFUhwHE$*wPaZuIK8dZYDcyw=|uN1$_Tj6v$aNtnJ@JI4CY zmn^iYsB%iMJPR%kA4}hmbaiPeZ7{vyqbb*8i$R>%y)YgZjC6N2|I*-}p}u&5Qcjp? z?mGe5d94w%V`Q~1j$(W_7FnbP)Jz-WF=ADs*5&k)BgRo8X9rfrPP9)JiW60A?)ad~ z6JX#FK?PqeI4f_V^Lx__>)!oJgbe1(=IiE7V4s(v>pNa{*lGLUJOgK&QzDi{H69-! zy6R+2Z=4aF3wmwKnc>KXM9A|N3)cv3WY=Eiej4m(oVQD9&`=*wTfe~C+OL7fdK`;j zXJ_RO{4pob00)>^noQu|hkBMIR~1{#|EN}cJv&#t2`e85c{&{}0>`|c{ewwCQ`NVv z23GR?u&H6#!@{TS<~eU^lu8!5`unHN%KkV%VhzNu2ea*Lx3x$`fD>=;Y-=U7Rzc7I zGJuMoc)cp3>vZ;|f_DMWSKZx+u9LEQtNR60{{sfUc0pag#XD=b>w!N23_daIWp&35 zf7EKn>2bvj)SVFEj<_k<NIh!4NiRgNq(blqcCXekCZsFp1x3KqZt(TuG^pf*18@z< z#B+tmN1X_$nO3xe=p=`+Z58@%Zks5tKok3$=8J>?fomim0@yyEiKp1!8|T=`FWYZ_ z6HAILUNZ*%f{;ijAUekx!>jZLi`Pjbe4Q6eTtf{vK=fs|wc-()OnSh0L|PBK>cG&r zCQHw#6I2oOmCu%Mhbh1}YbrOzooax{gaub4_fO0)vx7HkH8V?+7YRRZT1Y=aw-{BR zZk@mVjUKs~lCQ+UlS%7<|AJQ#C_>0)4<)=lVn-)ykTI-7I#+<8fX5Hui|fuf1|it? z7{xHj3pJAyx#b6Gbwb`Q!uiCAtI>WSK02IHS=4cKHSC8U0k1eJ1(#Ykz|SKTM#xmh zGzh31<_0C>Tx%5aB;>%qmPRUc`FvvFW$kW@lu~wiJV>4^Ye{N<w4+bE9Pz<A{5!Z7 zebbDX0fB5&!#p|6i#cO>U~e;lkcoW<6N3?^VqDOkaz_k~6F(Wl!sLPAIDhu_ZRcCb z-3m!#vfCM8!n`*|Gh$$M6ajNwAnglofEr@LB5;=ktNU3~uKFp$Mm>FaJJ{|#^ZJK? z5t^YS{<Yro=ETz-iC50{f3(3&^Zkr9+<1{MY-o9%K8!L5m|bLkk-;V>svK`H<EY+3 zZUnB?mF2lFH16_MSS1YYOX|Cx^sq1F&o$dLNsGs^?m|jZ!(A#QRrzc;-WYX?kL%<l zs{Z>SzVMm^aLvHH%%Sj3@<2jyk-r)@{7w`i+=oX|4IW(<`oduvu)41+f7&E*lOGkY z-6IwL3Hd7{3QK)To7Pm@+C1ANI^UMV9}Y&VZ2%v-D`d9$u8-8n>W;@4@@_encOcc) z6<ho-rC&P#3w^3*)PPjeF`yoD*PI`=sluKmQ+h6nSH7CJt2e~s@hK4Qf9O#L*7vSk zJ@U_o2MqoR&X=MSF2QhHrdR`}pVvBORwfDCuvXpL(!IR7`3oEKrpFzc(gE1_s&cd6 zFJBKVf{V~o;ZWRVi}sjzJb!s$y&uV8GUT*v!LRw*>p1M(1(m2lZCThO#Dm_aThAyA zXXZ{$SDe6hqP0P+UGjXAtd#Dyg;|N<goFDqq~zG+jbDjPltaaLwvo>I%wbnh^7$10 zxK``*8uyhtpxV&It*Ng5!{^?J5|);Sa8jrd`L&KcT~42wygNv%*u1hsC#}5O;`hmp zK1p{4zZsR6X{A+7|K+`=xSJ~1pMKD~X!qRLet>J8UxM4P9|F9Ml#=A_c~<eRZf<5T zSSH7mrX4wBEkzQFGtt`H7Jy_;)mtr6E&hiGCpxSvDf$D3`O5UR_sz#wrzW;vQ`g=_ z71$*k@(nv=77&nsV(`nVO*BhrJ?iGlRNlo0qy5`bBm6Ny$-^sIRejlf=y87R=BrJB z%Z4*o#`TXM@>(A;T3f%gChX4*&YX%ctt#fK*iX@v7Jl;RhPV9p2IoAnGx5C|{wa+b zz+Xsd(%Jaw@5R35G~K1sbUftKVO?V4I>m`FdyQAOEqkL&vtN8uY_%)V=4)QtV(5@- z7e5s6NkH?;zW20Ej!FOc|Muma>vw|>DtB$1&rHR1GjDP<(IP#_^AE`z1)n>8eAS~U zJbj_%vlzo^DIN`SzhgB?pL7Pxh-Mmqn5LRh*;`h+D(%Ni?tZ`!zxv53kF2u7d&eaf z`n70<M<W;1hj(_yKXa`NQ*H=7zU3>~srBv=U9R4`vUjNNGW45sesuiwfz8KPw;sQ} zex-JyBal(f{~r3Riucf_ugIfhU?!V4^-W{;B@)?_3}?l*f{}pK@%)v5>43VmF>|~y z(1l_v(a##NUfdEpXe4F(1+-eRuq@V1Aq_Ul9gI@QLg9M9Z!!?D2%ZZ#G75{$22lDV z0__#vy->MRh?eldg(YIo%@lY$Gs8_5sV`>WTJdU1e@jo1^p5kjMz!VQxYtpQ?42-w z5BPt+_Nxg1!SK$rnnq1fI8QXv{`CJdx8)=wXov8b)J(SFN1c0}rihkE{nX(TD#c4^ zQ6#u>!KHH)N^5oG5#wYRxYbeE>QE|%P)K;abyqT2coId@!vvpaJDU|Dz%WNqE=~Wo zRsG7tuAY0S7i9LF_lMsl`V9#9=i2&Z;Ro7oXxbrPKgfnU8a7V-d3{lVVJq#U&y>^6 z@^BvcFv%s#;q&z17?I%09B!Sa592-Vvh>gh8A5<3`{)i&A90NZd3;DQd98H8Sx}S* zjmak1t=LN`b=mL8LP%ayP`f3dWYGGtwtJ~jd$Lf1^SbVAmS)jrTI_`q9$HhSRL^TW zY{B9nsvY1Lrk=u}Vi(1xB!P7d*z|!kEE|dR2m2$TWXcd7y?66+s%&Dzf^jNVdgBAW zP8$7~TSv<MsN9N(+?ECpJFLE^0z2Klz^bHy*HTDuY-cP%YsC(!0W`@e^_-jK8cFn& zBBY_ln}7#yw1SgzaS2$0a}5h#Q8)qO!-v41_cGXZoDF&s?Y<tGZ)xzROh)7eFweju z0(=7y5foMyS&T1DXK8S4_aX_ehxbRMB?L=-Y^{RoJ%wSOfHb-)IA5MPFf<i@NDaDH zebo|P7_2P*#DbAkE9}}u>+Oz_-J&ChUOgrbqr0W^!bPWfH928eO)z8?ZE}(mst1?x zCBqJ&!XfNsc+{;*3)af{^Erl!fottbhP8j9gBOKLsM*Tnva1V5irS$uYG>x;q*Aed z&UP`W)3fQatTbKWMET<~7xbj76|gr}A@=lnFCRIq^3d)vqGV>O3@VjxAzlmsC#b9G z3T3x$H%1*%;2oAmbmb{Bq}&+0ZJ*(FwHbR*!ABgDUE8|xfI~>?+c43gx8*y9#XPv^ z_e3&2;1tY<W|ksJb8>R;sVvS#8mlZw(uux7|Eu+SI}n&$68{#%qypQFT*kcy(9o<^ z?4<bz;6`;TmV;ZOfbw6anEv*?H9^&dCDKErv!phu!6D=AH)+Fos!p<JY2F9Bfo}ns zhF&+0H?d;GbPv&B(AP-`rm2di5-{;Yec0*g?*gm1zPS$xT!`8A0MkRFk<%4fhuvz5 zvrWhK!uD)Ipp{r`FI?_Vma*&-m)jzi2xJ-LL!!`2jLY@2{ndU;Ln2DD*49hU=KH91 zK^a}o3d)4}fLpEOW`R_2-O9v_t`Xp~fQEFQFoOpL?<usY49SFs-kO0FLnyqOnt}B& z)}-}0$Ib7UxSX*{Z3ef5rBT>4!gt|w4P#;jQuS4Uzw^z@p)WEwGAz>9{%0yq*dXtM z-gK-sV5RT@9j-{#>b|&>++Y3KtiG{^_QefUsS&<wHcg&;@rgMDp?BxX?srfBzCSv> zRsO%O$y&t&dY_^E-gzfMIPl|m5Egi1%AqvH6cEdw1G-8M{=Qk_RA#!LnIJFBbEChk zS-@H5sO5ZS7KpJ?i9_$r_hJVLb<hW-govS@T&??GOTX)CBn`XBs{eXdW}C`+6lG%6 zx3>@M*;|^-xausXN|Uvk-r#~lx4-6@z>=hQ5Yq#OXWR3nLCd3yR<KEK>Uma##I+Q> zVt9Xp->c`QKCJL(^3v6iXwrc@bfT}yS81lS=^NS8_qSi6-M@6JPe+=}cbaou)>Tn6 z1dZzE#V0q<kG&d79@*CzRbZ8?9`F08&#f%Lala3W3DfABngZUR4HtTgCYN6daipSM z{GfV`fr6{$a!^<CTQ<v}yA75s%}@M;-VL-QJ*4)F`I95tN}}2?4c=PZczVb;wX^;< z>8IbiDZkKk+XKSptrdSLey+&aoZTtevF2iw>*YCm=rcL*_J9AhY-#5Yhn#*m`RNqY zDL0ea#$A@Vbj~_(CZgM*FZ6Y;dTZ036Y9_=_CR-6WH&lr=#|+-%#0{;sQEUcJkx98 zGyN3Vz^2j9jmG-Pe7%b{Sft|i9XIs$$^Mn$4l0W+jyEI*@0wEeTe5Y&R)5%s7yMR! zHMN#|b)cXNMtWP4uKRew=JeSU&dX$tQ8?E+Jk|v~m`CT{HvabdWePEdfH)tcefjK% zCK$@I^B(poLPzWo9P^0}f-6&uAzy0p7OB_{D&|Ty78pkXf|VZG&XX4S9#~xLL~|m2 za4ygmUomyWdTZKP;khwpnyk8_LKQqwg8gnw025E+`>TL^#6YqI+kOyF#~Tf><vv^N zxC_qVW%_E~A=Zb(Qn-bBv@v#o@IZtu2>vt9bMpHh5AR4j-u>@>rs}Pg`c-aA`1zDo z$qlDGTH>spE{|m;(4tr)H%t4unDeaIeZh?!JhnV2(q%c9t7xi3>iqS~VZp_+$h}5` z7B~qPhfl(oD2>`NbHw^-7I*kGzzn8=NSQ?oAljH;3yy+?R0p4;De!4KSdJ*BmHcWM zd`hfgEOdFWHR(6I`m1UfED^qeZ^Z@{X0m3Xi>M~M<>~wM7iG_0_&tE$AGF1Fj!rN? z?g+iX<=yNrgMRD=_=3R_q|y?-bMTL=IEIEyINTn8X4}dA&eau1n_^8V$_cR>uu#^0 zbH_W~;Wt<S&Xk~%x8A#{oM|b1W;jbMkFJyrJX{pmk-UZJp_mk{q8Fzf;AwKFdb$uL zV<$FLl#079^<rXR<pYMXYm>x21HzU^V^Sa1ny_}<3VEvrAG#ZBWeEs^QidJhW*YQ@ z)_2c=j77_^z!(@7YOt^<)hgUbn*zK;l-gafU1F&)qiDF23cGe0a$}s;Vb(#;^Oew_ z3HmrXFHnf~RM=-ivUoz^ueePigBDGL05NaScs@?%Ti#ME7zdO}B?h$^|3XZDktQDU zPgs%VCukeS@ot4s)5y^-M$F8$9<`47{<!(FV~To%5}y@)h|BtGErm(qNKjP{ooRGO zx&mY6l_^kUmW_IId}&nDC|6k2;**W;tOCH`hD>V#Rxq&;s}bSA0itB;I_f+e2N0K` zi2~*)no-x6xrn<NyAfeHZj4Pv<5Yp=D5F$v1$ay2k3|5CvkIU+?}GbO3m(~BvegK5 zf_G3h#M~Q}2&EG@fSG*nu)k4)<bJx_g7J+1DOiOe3O4wS$bC!5{G3D;#wYpWqLTVL zN>hFs1GuT>C640_hA%n7s<YgX!tWxX7@j#)gQE;s%WM@EnY#RS#;;}uobhPb*YfS% zFe{LPfb>FBVG>F}Ydak7pOO1b=O3WXxlxxS5A42Md*#A~Y6Ru);(7)RHs?rgKg$i& zwf~19t`7gaD$k8w1>I|T$0R?AjB(Iuemmq{5tbpSc=p^2RxqLkt<89D^!9O(<1&U4 zgxCWiMUM~FfAa9X#JcVqH1j^uBF~iO$9r%kp`*o!Bs=RRpk?&J$HW{3pjnzcEAN}= z(7A_vSAMLJRpIagPUmo{uY7=7j79;uVB1zGtENFvA-E#5wY6S_kgMrz71nFsiXQst z(zZ8)e4Xiw+n^|HT^@a-zO|C~BRja{;=Dy{7J<th)3*&qex=1ZO<(9Z%Ag)(8g^g) z`>)eZLj%}<o#FkL^jSNVBV{v=Shp-c>dBEEFo!X8N3C-ApE_A@gnxqaZpo8h!;a^D zwMCesHV)UEEs3jdH)zxy)9syB{qwfwKZVlZ8?%p@v>VEr3ff!#$X%D3>l`FIvq2%< zkKmZp4`PauY%M<%8f3<%V{%HQ(#M$-+hsDMEt13@0F=JiCU^UNm9GKEsl@pW6>B@W zEsI;X3=b@_)$D9cVmR0>KBu}~n^U#pec=$z^y8x(i~ipw@f!lHMDzx4$rcvOHWc9@ zfBQ{5r;)i25n@jsm4wL;7A^CrORx;>`uR7^Wjdx2u3O?3jV*F@c3$up7r71=O|D~b zJJx2x@=b<p2*`NGB!7E*-B?irQ)ukAIC3O;k6*))Lt~unIx7gj#$Hh_XpiU1>Xv!w zdp{ea%g;2N!HeCg@In2Png3|M>l<U1`rK$!g}Ny{F2ryW<YxEuC$b+3az}q}n3fuN z+qW>awF0DQa?3+asd~`=ZBCGj?n>0w%F{Jgm1_}!E*ABe+;WYzqBVC-OtZ`{H3pHo z8gj~znTx9gX>C-&yepFox9Z+`8vD(GgFh$Ty}JYzBCE<<42@dPYPE^_3(dc_47o>L ztLV@>D0{zFV7UI|uyfLyDJR0Gr)`P)my7I-FF%-4{niS}*nV@FU6}wvEQ7wG=^ZL= znUynMxq(+x@h<Wl|Jj;poqfNB&n!F`eDL#g0q`>iA|lG_tn|4#dkyx6lD9g()eV&x z$GBI9mGwTA_len^&Geo^_j5Z|P~331eb(I)YfOTelOQ->@#h-1>pE59AFe>bT!U%_ zOk)@Q$o@M+(v~alX}5L!OZCm9A*t4Nl2EsF+U>bya(v6mLDzq|T-zq_LvPck3iIL$ zyPxXpero!K3gB=hCEZcpMl<}R`CxOc-x_nFpLHPQftJ`&-)VPJ7cf)6$<}uiEfHN* znYuno78A}$ewU7zNH>B6cj}a;JwnY(6PC+bV2ntvC~bG6yJ^dy3{PRA9>N5QQ)9kv z6xG>@<ajzHUC7E2(?BkBlQj=Ar~KM8NKcRbjNaGFYpO8bVAz)y^ez5B2}`ts;{J&V zK<x31O7p!&mP+cssFbMP(&Puo-(veH<FK{Zz2t>N{uR4y>CSQ?4rS<xQm!IzA$p($ zXV)b!>=AcOct0M~6|aO;4a?ola_s*fIePueNm3fshK=&g{5Pg2Rurhh&4S-6q&J+r z)&JUnRNLB4lw)+1z3q3B;PoywDleJ|PknJszn?_6BpX%PVA1r%PR|ZUInAmtNI#*` z`>y!YMbgDtT)*O?U!7QsW~J9<1<A<fH$*?|cbZ^?2h}GZBv@ddIV?1GE41{|k};fr z<SsvJ%$z*H<HIb5d3Uyp$nuFHlWE8-j#25D9-5lyVgzK}Vps>n4Y<Hq%i8EP`Ig9$ zKDhRECh3n@HLB@nr-U>Ge4G|hXp%+`UZAZ87(G$%UgcKpGg9wsX(uj<H5OId88BvI ziIrElh&lhm!{haX7=ejlD!bCzP!}fw!Al`#{e|wX68+c_0)72OiiCO*Vc_EWB;C(C zHJ<O@)jIdt^8FFQ>+w->q+$-2=&=8#2h8LB*vsM&J_Ajc=oC<dlfq?n9+Z&MAUvT4 zPp?E_r0%K&&x}|eXNpQW2CGd<Rw|j!>Rk|r@s|R&RB;zDLs#p+A1l^4);O#(T6D}B zCy@JrRqEb~?Itqn9bRYJAV_g`gnq#pCto{77s`jtf!r`!jW!@aTxJ}I3RGyjqvoWE z*{=gx0I*-M4sR_Viw<=#-ye%APLF>l=E_{n0hS7&%E(VD>9&BtQEOzsh;FI>3vkRk z!%qRt9Nq^7_A*wbi?5%B39IB%D(X@f?VQwQ9C{#_l>YVnBzJWl3$t2C`*~A2TT2Yq zM<k5gy`p5Yk}OC7nA3iIPE)$2RkdI+{=tmE!l%zF7E@fu6g8_K<@cOKnaaC^h;_i< z=lpMnB#)mPy&UjMmsR|`@}?WReM6JZml7(qms+($`$|?`@zIJ#cK{mQeMn-&Z_V(o z`vW0y{+ZDHN>F|em9bjh$#2N>uIz%rj|EuI_CM;iIN-Z?J`}H9RfJmCz0Z1@xgC*0 zIa|jUClV5Bky!o2pfL8NZT`dsmpRy>D>kK|{$a`thXIMym6JurF|g7E$LQhVl^4zu z@1UGh;)XWfTQ*HOdRThMHX&wh)+QD=1boqL2rEA4m^@efiG}Y7;$hqUQ0KQhP{iI> zUot%GYt0Z%ZFxwVR9JX0@rgPDe;<Jb!2bRT;z!-W?t*{1%|FBy>Nj(m-SLL!7qNj6 z4L<CmqG=&hOAj#w5;uzS&!263?LDp+RgSsCtEHYB1)X~^Tmt`$N6npyY)}@Scaq`1 z&g7;2_ioxZp7Z7wSrzPH-Val0xuH&WamX24hOWl!<W_;bw|Jk&5{c*iVfwAo?6rNY zzs)Li42l3FxKp%xRKw7tUb}xQL8$qtY1?j|PPrPsVVLdFb~x<se?G7{SM48VB4)j} zH@~d4UoC9AwMTOnH1pYd<Cx?Gp#z5Z5&7FRDJ$KowDRQ>r&kf^DPWnxQiQ56CR0Ze zD*td|;)Lg@52h=-l~LO-xRJB}0{d;PN1q{xaUu9XvT{-)X6NGc1}*b~1*H&e;elWy z?zf;yf22%b_?4`{Gxy}m4wt0TNEMYc6NdNj(>z^Jg4<zPPQ=R*x5wYs$0#~yM1*I= zH|dY#Am%bO>9@g?8GBBwDL9o>_J80?P2<Z7tEZl)!^Z2Ady~G)aad@GUnA>~p3|x< z<T1~U0;(7T8>QxHDmvzGlMscU-OTr$vm&>uAW#<H>=_^C*nc`z=ULux@f7==?C?~X z*%xwgczd&Hkb7Rqjlsj8=RN4_(v>KCH?6ko{OIqm_IAEj`1q~fogIYC?|UR|6_?|G zGrWgHHnIbCM94O;@+Y%z^j#f(n{TOtR!08#v$90_WBu8PlTV+qTs>0JlQa`Inq6fZ znAqHCduFoy>Er#X=pv!n7`)NeRJKoYX7-h{8|I(;`-?_b(63MR^(ch;y0ZH2xBM8Z z`Ch77XYbPDDF6H8=SC*=$^f<T{{PV-Tw?tn?_^iSi8Cg4rO6+#BWElydi$ef7iGhd z7c1bQPm3KN*o7QX(|3rL3Y8_Y**Vp_8aeGatB);$;?%zTir(BGX#Gvy>!v}dvgKwk zyc|B^&z@hy?f3OWbRGL<4A8qi7~d8dmf22lsmsso<jJ~R{fvDTn1-Yblc?93@M~uF z8fzC>WZVtOk{G>rMj?D5b#JWKsdT3a1C9j`h+59uKXW5dS+E)$AIH7lqWle3jf?2i z;kh-?0{G5%kq=@GAt(m-xbR?~F#(SG;G?iBAJ{m%56|EiPwdIG7z&Q?AIxvH2`j*4 zF<M6qWkh{5Z`+%)%9QK_w$+|54HYJbO^;Ia?i&8^kkVDU*Y`ENp)32h(hAUy)U_cD zmfw^!2t%ZF^4^K>X-aCWxCEwl`r1kFpWdf?{i{C&(<Z5}{cH-?PsMt9gG{i@Cyl)Z z!87hNS>3{d@c$ZCQ{6Hlrn(N9vap%LjK0?JJD{HpTs$K{`=)Z-QX>2kOo^ogR!p>U zBZgr}Z7o#H1qi1Xj2{R-1K}-7Hf*tf<fVsV%&01q)5!uBT5w^E<h{#>&l;j?bH8@6 zWyq1arbCWM|NX<AD_hFIEf_@q7jcT5np4<vfTM!zK(3)&NT;nHh^`Js!m4lb(k^CJ ziJl8?PaWnfID}{c2NK*D4r%ZW5HhvwIKs{EGf|dRHZmRvJ~BquWhtle?Ak4jxq%@b zX_HpiTnz#~;LrZ^=&Et}p<;mx-)<!L<VKt%n&f-@IKVq1b)H+X(J^dUS&MU=+YlxR z(tx&NyDX1iv<=pW28E;#_o)(|4j?qVvT<^3qKi?kCo6kDNAV|CJsO>MgJd9*EJ8u5 zsCRImgo|(jPHrP)FWJMNiABb+9h~H}Lc)8-+j1NW5kmN{6S&p=WgJ*ejn}2!J`oRd z?27s7U=&%yO}!W<p_j&{SxC0D3A*J2@2lvdG`+CbT-E_IFBq#flU#!RJ<!6kXH54P z`Hig#EOf7Y#UxYIDS*G?BaGD*N4f7H(4Bbt;!g9^|7>^#1k{$lL6Iw2Tx$2?jf%@} zKUf_%C9PpG7mXQHeE#UFU;ZOE{kI%hmWH9N>ela>nj4TC8GF#2&1jppR{K)DAcrxn zQDE!lN2f#QE96L~aaTLPJen8uPlbs%Jfh+{W>pa;<Zvtjp6>EN18%GsjbZ~t_z?UF zui_u2%9(R7o-2stL|hlOM9EOES$ZB8U<*aLTG-49eTZ``+YkY!{q#ecj;itOA;dMo z&Dtq#jcfg8>l*h+buAE>KY7{4JnbifQl!$J!g$HW(~%7w%wxPmx5^08=JA3D<kNWK zxly=eulwa|4J9J;h7NB&zvTf9Za^CM)6-h7qA7@=XSOdt&{s3|xlvB8cB!zH`FVqj z>@BnSph5&_Ou-bAqUIF}$f9<A;E&#cZ4*P?pm(e9^ON@7`fh73GrLV<eseM7t-lVm zU+=n-wtG0;(>mediwaALc%2N|(t!!n@PWz>E)cgxqU%=Hg%7s;nD@&IQ0PD479_D^ zSVbKxT5R4dz&8DxOW2>R1G#Jy2h40q@V#XgYy+Xf5Tx=uZbeO35ldiX-s0{k1|ke0 zjx81QuBJ54sir$Mv!~4n-Zo${U=?LjTT^<zvdD=S$8hFycf;#7IuCm;-5bNZz?!ly z;Ee42S8DU(mfmP&d22vyp9mbDyjV{hTJ0x`=sE$DjA;fRMsQGBs)D}10W^=@-BbcT zw|8UfcVeJr=IU(ZOb-Q_X~M*r>t1(cfzSA_#Xg^|B+C(>t+Jj<wAr2~K?daNJR;CB zA5jqQj&+KK3(XYE)Mms^23_E4|JQ+bgQTf1r5zaqjK+qtfuI%GZCe_BQ)k@2_vDuG z%Qfy5n;Ik4gDrUJ1o&+XGtr;i==f<<%N5J6o?32v=%^YIjN3AF-P!^t7WXhlK6$TJ zF&aW-Z^+M?nH#E1Zhv7rx$21iI&yU^n(oJ?rL=lnHJk<BIS{0Z8z_2e_iTT`Q)7d( zzP8!`?HEbF{UQ;I`{cj*?asHm{-w3+<td1Wc@i=_3kTwUzFawasYUhVAqJ`osUWmx zL&`?;GeJW`+{Z{+<t#Y%C5zjRp6+Dl_4%y4xU$3uo3Jr|MOb+iS>Bg?Qk9}H%uk8= zTx>J)dnL@Xe|%2Z?CRBXpEwT5sTd!`gl#g5$XmT7!fE9kZDmQ$`<<bY53ZckR=Vf9 zUgUG57rzxhD`Q2{{xb`ks>9=+&H2Ob&crPbFIHWeGgLz0cUsG{_nX$5Z&s%Xk&eGA z1p{2%dik{-qePjid;PO5qPR4ZFL?DBnxagp5+uM#PR>Qg;!gTUe4N$8$j?G(5|-2} zQ`#YI7~5+aGAWZ2gBfpS&wE8Uqa|EPwZ+wwZu|Hvqh5b~MsW7TacM^h&h<E>v2{hs z(K55&^T~XnOLti}KW_WF34?wO=}Uhz9K_SK`(}bJnCdckg84cc0>y{0^6p0u1fLio z1xx1w$TEx3%N8F<hNqV$`0KkKB|rGMQXLv@76NL^x=YlLMJ;C(W<3%S(BrBKowv6e z-ZFHo!k1(qu-fh|^^Kqo2Bbc5oBl3M>imG9hz3_9YkZG}Mo`ZRKicqyUz>$CX-znW zlAzvkuc|NZYv7yVpU~ZH{lTo;b`Yn$D=tK>-a?urk={WRn1G-4^`uJ~10)72@|MGj zXk(0s)u8QM@M)`rQH-z&hXfGl+X$|qQycQC_LEcVXz?fvSms!fK*Y0FTi`6WaJZHP zTI_E!LT@DAayhxT!~u`8JgNpTy#?Tjf@WMnl?|jUQUu+o7_=G*8z`|q?NW5P`Cv@R zfM66E*?3a8SSnd|%jj&EXlaX@#V&J+zH`CYf!*#(Q~KBx8f2=RLU*~~e8W)l(Jtp( zmpRb=bIoE~eCGg*K5!mT;A%${vfn;qVY5tk7UwV>1V8JkjT*gwCzmQpEpA&dO*T92 z2Lv-P8Qz5@NChI8Vumsd6s$mS4)d_lPD|CS-NGzWq*u8V%MroseZu`4wp?QmQ`gO; zVR86f@^p74-U&<$*k(!eb;le!Vx4CcSQ3AFh)oDEgGkWClg#(AhdVxDf?_Ba+M3Gn zI|CB#6MTNHOV}pU5D)xzIp^{P6Ukyi94gG&GNsxh!Uc6EyYU!eL+1?wjyg{32L%6u z^1(6AgSSWF5>d#pLFpyNV(b*-*I<e8&jn+aY8@=l48jM=h&}Wj`!SXWEl>Jw5q#%k zGvI?(;s42->tsFGeEX?lB|Z6af>q>hzO5&by_m9=S{n8k15$2bY>_$UNTm2n5jP!V z9aa}(+Et12_|+yGBni@x-o9&^SBsA7WT!49&Yi4P*Ix?a3?>-XWN%zF@agf{KdPb% z%er}}m~54moc!|rTht6Qv0i0(|M|j@Q3W~>#&qD8h+BgnG<5SZZp8g=T^^k?eYP%- zLXUh;Hy42yLRU+)lJkP^NVDR9QR<n)I~lXJ9zW*oYO=Uzn)o@b`9O=I);X`^ohUg! zW$+8=)yM5Yiy^JGnvlxs#UqPdetzo4@`0U{BcUXDZe!bFzoe2bP6_^C1@>pvq0rmK zWqEr@f?rBM|J-OXssuiRC(Zkgjhl3&@zX11s#oj$6C@nZ8EnuZ7Tr>bx;Uw;9<6uK zy-(w$=c#3WCKpq5x6gV*LN-MyE=*!7_q;}xWv{e<pSp`JW`hNG?JMomGt57CD^sR0 zooIh3Qr%F&v(}`0vp2Bt=gdE>S@4~ieghTR>f#(}aFdJeoNs-)>}|ppT=DN1u7w63 zdOo-{k*H9EDZ)Vy>6s{c)J1#>K4WX@pv@(*$3?`Hz@omkq&{-}xXagcm<@=FIxZl$ z|EhFF%o08Z6AZlNf4k!`uYk93DTfxHwj#-QaabOvvV3)k8g|3<<ir1KTh{2PY4~57 z<G~aERtet%>i4eZ7GL%CFV#b8pHNN7kfWFcW;?w$y&~i3`oQIrO4!=t5~F6Dh`KlK zug~rGgxhEQ6#6p3BNp4-B-)F(4<~C6XkDa7LdQstwXRZ3{Wl9(-OCp|_DoLXVNHu2 zwIdv^2!sSW`<G-<Fg?0bz~>KW7q<jB78}du%m(H03qPeaH~1x(nX^b8AaoIBd-;Oh z0iB5Tt7)bvB^)2kQ0sExjg_0?3kg~<>Vg&Q`Vad(JL7%(*JaB?(`$<w)g`W;JbX*l z9_-7<7I~C}|Eibvdk=lG<>SIhZns<Aijr%K4B5O=s<(xyQD4DKb-d#^LP~E%!CMcm zXm2TNYs%FlK}i4HaCP(Tfc)5`O_Z_?dR<bG!%erQ+q>mI>E8h8KPOoGT-Va+Y27xC z3)e942T{j<UM2fJOm%ci_tL2FDTY_D-x8v{&gn-Z|DjQAOX{%DrrW#Q$EsZMbNR0E zG?orB%Pm&Fcid@E^y9uop*rr*4OmGg8N3Vh!6*-FDh|r_u#_h>!YB4m&ugb^Bf75P z;dkPueW2{!`BQZ7)I_}1>b`3IN^`lc8)~nGdJsq0(x)|T1wT5z67bKL*5Px!bGx4q zAiSG__S=4r>zq@#>5e;YG!=@>{%xgIxk+}Sujd42$03DVvNkpBtS<O&d4A>EbBUr6 zjFx@VS*@_>YRH=L!ydxWBF3h%NEzZhr(A6+cM)S5>kqFQ&g_=fyGr7Tw~t==enN4W z`jVzJ{T*iSk6hkg7TZ4WdxB%?(Uw>!B_UG=_Z)EHk2eFR@;~cF59ZGie&0t%7ee|| zS^OU_)J(o4O`z>!ltaYr6ZvhNhfy+S|Gr5*6>+~RrX6Zk36p5Ld7j3!?dMi)je*{u z_VpXFn=)mgmZ1F#=U>mSd2S?e6Yt0L6OpnyV!jr|f1`~$)G?$6w}CQ96lc3y7d)PC zZs_*eLHaESnRERO-M&u&5far%wfwg`mOZ(lyHH6BW3Arh2JBwLmmMJfoXvQ>czuwX zs+mq@7Uyr}6PhD@-DVz>pn?@>C|g2(LKXyG@z<ZtD3r2z3rVnkbFz%@ejwz<MF#%_ zD??=#TpQ&g?MAJVW!(7R2tpgi)bWxIYc+taOQtc7IZ~*LhMb36;V}#cjO0gr3t=N_ zv*K4Vi;O4AJrWMUB`$NyrE!yOoXHKz*k@Y~J8|FK4t<X3H&mQt$Sa^;XaS-(8Ss~? z2W@v-VcY$}9Ae?&apC=dgNu2GGlnKCGz9_Yk=ek2$GCN>5vVFZ8!lWPKCtWLLSh8D zlK6W3bqS>jEC$iKbP$Tnoza&IV1-ONmNmD0nU)O8h7o@^6hypdY}aaD4ypRl3z%Yc z1D_LP2mM8RB<KiEvX0uZg$v(*iOQ1=bsmnC^rGO<O6;IKLFAuGg{ZI|_K$0J_gK3X ztK3Fh%9Ca6wcplo1VQ;QU))E>atKIKjADihm!`v`cD9qjJUR0hk>QAbuq8FlPdw3B zqq2W8xHup#-Gvsd3MM^TLg65LFrt0egChv#RLbsY%p)n^=0iAIFvh(jrJv{EDa4*- zQ2$Y_;o&<X7Oo}xmAIcq<J8AN%miA__Q7<Imf^8`h(vcblZ$74>b^&Ub`Xkre&S~v zgXfPt9ocsM?#57a|7d9^AtYj5c%FG)v;3KWK9Crwull{Kn{+Np`Q|DBgtdV+)e{Sl znu$i6!H`y+G#KD>F1#h^(0?7%ZrdD5>gVmx4mqknG?KO$P63b4Y~{K0!+x&NCoX9W zt5!a_w5zkwA~moG2|<F-{j7PT-#h&5jcitzDa<@-RRPe0V@mKYpp_O?<3_%Yi9MQF zs{<V9?&*okKedV5`|QU;LrqsBV_+C$HyzHJA2(&*!bxgLTea<_huyMo5`Fl2eIffo zQn56N@S#K-uHb&*1SY?iX_k<Ec;6cjO-!{CvAuXktL7*1h-4Vwv@Daq`qa=~(Eu>L zBIWXhNSP4(M6_&ki8V~!d%*7R&wq^YOEj<#t@RRO0;O)}P=5MB9^l59Qj%>bPPJ8g z1BF-nm!{6sT;nc|mR=lJ1hM+8!JrPxqO})Vk|D_Dxwa@T!C5$lq>5$SVov1SCj-vi zU)U_lYhV=BHtR96vSC@jpuGr+x>#ERX!5YVLBr0djM9;!!WC1110kbzJ=BRvV!>c) zWQIFRdiVzIV)m^tD!QnlYmRxcnmUqJ(`eZRO{s(;xT{UmnfvdBM}3QAEV0kN_Jxqo z`>Oo@*wFGMxZV~n9|t&{o1Fb#Q2c+)O+xz`vkbn9B{|BUn#Qpw$8y~AkVUtraR}jE zb{o2W+QAIc+)sa&k)s$#zI!c&BkQi1Qq0bh*ncaU>EUV|AksPJizMpqwqQ@sAPmCv z5sQMC1KjR^#ZBSt>QU^)+uG`&Rpz-BE+4_{+%`4p!1nRO5)~)j2y<Uq|FpG74!z!( zj1ENaJ0ggLA!wy8>n2P9qYAN{uxvyVtSMG%vduSaxP@On;knUFJkdmP6FlOP`H23* z$G41M5!rstuuY8ykcmryUvStM{jr{;UFAh<PAXnZ$b<=0U#cldVhHEid?{#UBEoii z6=CRvrhVnaG28AXo$|ZLxW`K1yBCl4N4dVq4C#hAieV$^;4c?EeHfkEzf*6w6asJ= zJ=HjwKGV;?|Ksa-H$~05FxzHI`#kaHh&^UC4zF6i=26`-W1}NX578Vv2=V(@*&5W0 zVorO)tJOW=EG2oX#g!diJ4#sTy5gtbgObd2U+WJ%c3k&r-{9+)zB!mHf@DnNK1j{A zVTuOL&V%P8XL~=HJzX_fYtkDx^k&u;+1kLOO{)VMI=;_0iL!|(I_b3ufU_{9$zU)U z3^4P2@6wdShmAi*KR$*5c282F$(>EBo~}-Fs*5o`c;JxGP-sf;FqF<oe0WYf28YP3 zp7*C#t@fkujP6K|+~}E{sud3&GXZpK_F4a!%w*8Uf13LxD3gExF?nC?rgU}^sm&$` zqcrqQ-J(r=c-Wq}=kA2zIy&B#Z{Kx0lbor>l3G1V7%xR3jGO?NE~FV~%h%B}7~h^M z!i<T$Q>+bHHy=Tpn-t3$yQl7QCQdFC@-04Nm}EjK*faGM1%O2+4F~8>tk)|O3)&j8 zuV91J_9H%oAVS$UWqGDrRovtd!$^(68jenekbdE2Yq!g<Q$GxFWwf_RuBtEHvcaYw zzwYjnn|7a(o7JF*m2|wXJ~7m#qBqQH&alFitwA#cAhFHcI>SH?$PW3cQ26$q0N<RM zIdT{GhelmZ!)y$1Qv+|s_eFuSlRpqU!EhH_ot?z`-x4imd04Ojhk1hoL53b^8M^re z-+<=*1r_f5DAjszvM$<vILin-YKr!%AoV@jP~Q^#P_4A&5HlkH>_q<rk%&}a-GN0` z9e~~n$3T7rz2sbJH!us_LcvW%f|PGjPhW5OZ#THmT*@UarYLpG*h%H$H{h=jDD!s9 zW2yCcLSW}vHuTS~h9hIJ3jw&8wiZS;g*R^>TS%GvVTF=#Wna$-$$`#7cjDU+&wyJ| z>0r)n2puXSjT<QqCs|{Nu?GhGb6_;o7aJw90Z2IcW1<gv94w9n$wOlcT^m)w{RE~& zcBui;Q~NzJb9Sfyhid1bIE(9tFdtJH+CdgXDnsW5Apo?Z7=8k4#zj=fu_Rr-&I91Y zAwa`v4e`1@n529L=0}j5q1MQ$v73^@+>iBv(?Igs2j5xA+_czYt8|FsR2aX)bY`ci z7qR#qeCN6t9f|G53EZ}>Wd^|zs*&06VbI?_6*}H>t$fLmLne%u7?oK4|CXBQ#h0<( z&40m;eqtDU<UF?G0`wj~{xrZ-RA|`2G`D-VNzP_RTmF%$4mF&4siCXw(X@9oPuvxw z^}(D9ANkdSG4hlxFJ4oPTWs5r+N}fPBD1v>XqFDm*v8;MWjI?FQ=0SEij0-1C!RU% zJt%9ppiF6uk`sG4^I!!|l(L`6-_dZ(SfhLV>H3eu^33pN)7Q>kHNByHPkpgZWc?FS zHFks1<IwO>{OkiE?y%;DJLiWPy4>_!8q0wQKVh!aF~4bE>9}F4UYFSi=WLVTNtC?{ zz;_>V@ZRHZG@ztIV1=D)yb@1b{y=*pLx1i-Oz95Hd?y-3f7eBAicGYl>2u{*j(L*_ zYAQqaTxrxVq8Jx-H&c7rd#&H?kLVz0-q`f<s&{9KRluM)q+IVCaqeyMy`qw&d5X)B zYE`_S119}|IZ67Vl+qzjkT%Xb-`3kDZf^UY<_&8OZ~5v;L)U|2Yi?OZD(g8_gM4S3 z>8skHq<0UK8(ngky~ylMYWe@sUPG2<7Rj@kC+}Dhsb<$|@nPFJg@(0RGy8+afLTO+ z09_&O!==`SF@1Lha5*h!w@+qJkN-!_U#YR)t_qreo5C~UEX{-9Uwm>kd;LUv`Lhdi z{(xvg0UF&3Ks=navg6#2zxl;47IE=b-RA0Uvn|TPe|bFdT=p?f1lm$`&AD2IB-(0t zza}86pFJP*di}kF@o;Z;$*Lb`=esxG-n}hDf-}=r6zU<Pwpv;8<VH=fqA|MVY^=V7 z{~~INaKCAD-ZY!QA6G5W9$O?#vZr>nd|`HN&(zGOSE708;KOA~v;Hl2Rd8#FQ*n+d z7jlKkE-zH%wF*TagH;$&BCj#7-hM&BxbKlxyz2sQr+=5zCQY5v7-y=bhLGcN>}8Sc z;NMvlJ7N9@c%caI5~)~?lSVd~KX+OzWS;G(up3<ztD@nD&tmzJ$1*ppe9X2!ye84S z)p1R~vi|X;pm5gFsf=kBb@`nl-IMt-$hxS_h#N83@HFY4U-ovcaUF_?!G{;hJ0zO@ zo*U20V079ROt~^a=T&{>&HjUxD=Yo*(rI7ZX!xM5z2kdS4w~<DD$BI=G}$xTG+DbY z&%pWu#F9ZisV)Z(6jr{qX_sSx9p{XN$~QBrgO4wDd8rXTgnnlB{JH2Zz@h>mK(+p! zeOx*&0;8Uc`l!7>1x*MEANAycc5XvA5a?FVVu|T<qqP@i4_H-Snh|}~F>!6oZQ?*Z z@kszO&z}5v>tLZ^EP?cvX05_}p)ty-b3iL!<y`;wOI3mQb)R?6*^#506Vg<BS1FpM z6H!~F8h?Fo_WH#J7yZZm2~Yi;`}bxrZx1jH4U!LCywEVv_8@6*!P&B15oUg}LE{*- z00|EZ#dsAfgov#9eVLUL)2cdMtgD{clZ87<vJ!nqTBI|H*O3~@T4>FY2-mIfImGO- zsocF{?4*Px8E8s_3o|~wKaCff6(eJdoFo5sHuvwCn$BJlU}&TjORs?+b3_ukQ1TCd z<ha(wKhARD!YjL(83ucR6IT1YC=^!SO8#E5)k6EzIJKGlzk>iqa!gL%_kg>{{yslZ zBOg!?{cn#ovNiiX2a>fer=&adYeQ~-Ofn-kUg($A;9v9j!5!*tG)?}^%STjgnb#LF z`4pKMU_zNUlwaEqO(qj^vMFu0kB}K>Z@M<KNPl`XMluh%=#~h}2wGWNH6=DzJSXq> zy92`KfhpZ!{`ocN?gxugFaqkf$b77Zn}C-~NmicKn{chVA>|6uWx^r|H7tH-+T^~L z9YR(V{h7cH`dL{|+1|?Np|5?r6|Zko6-m5E<TSB*a4VWJ;S>X>s1(|QLdvk9L<Kyz zifAidF~AJe>-fGC^?A(}Z63z)gxEU~=(+WGBgvrH0iFlxp3O;`UhX**w5Shihra@D zPznfYw>6^<-e?Q%N%UVMc<r@w$L*dLu@yF50PoXr7vK7xifFvUvQCXoSjpyxGJVDh z$VX!B&k1Ogi%kRx$QoINp;plD^ciyI=d9#4PW0h2m<OOTmWg#soJ~gVx7^6?Vs|R~ zoZL+0Z=<M(Vi5|(#&!$@ESxircDlwzyO>YZEIjH|@F=B8m!cv8Sk$89ZxkwTU)hiY zi=PuATam{Fen~N@BB7CW<0S2Msc7zK{%NQ{@Le5~o>lh6Mn7hhB#ISl>jR4)iORw_ zu#$!{y8K}|EZ;Fy1p?&#Dm79D0o^#Z)hM2dvrql3;t&(t1G^WPK-IelkeqlzY3Zra ze|qEv2gm$X3fY!K07e8w5GUZS)9k0S7}n)wiD}|G8@Z(r{ZZ`Ml_blLF{1cu>260{ z-KIS|T?Cn@snYS!-l{Do3k<ib!|(!pa86UEbxClIO{q7$5%yyF&Yh2E+qksL&Xt*N z)*n#X@#yHHqNiUv^lQF-+kU?y({XrU#7nhP^gOKioPR&{d)8j?&oqljg+=6Cnc7j^ zT9L21@*gknEm89p#pqv<)#|e`@4UI@ot3Fi#`xW6)8ub^|EMf}7N&UI#uHsFmC9#1 zcEhz+NW$#WNky9+HbN4kB-rq%a~E%KOgmQJ4acr}#0IpkP`v%0yP9`p`V2GwvNdej z?l9b4vAbFS+^C&am;Oj{cWso)Q2^mdgT*~flWcds^WXM5SMNk7Os$u;ekZ#aXkKP3 zvpwlc3>tn<Yw31!90Lb<bGkr1n&Nm}Y-{&*gqM`(PLljVV>(xs=T>W5X1A78aXR&E zu)gWCvpy|QasX#v=p3MGC5gH7XCF;Vxqm-Dp9706C$&y?NZbtV;xk~(W5nRR>F|uL zspH?MSQJyL0{LfD<3F)UsvS*34aYU*?jKu2EVLBo(M7}16S%v72Z$vyo?}+SM)`dq zj$3o?e9}ct#S@PUeSME+w4jHSeIVd3RxVKn6*(43c^%`V@f8Xx?^`T1mx{SkqId-o z<I?WczM4t>FK<S+X|J&m!>=CS`8ZeooFvohlGX6os|=qk*YcS$f$ph9f^VCaD%cCc zs(EAERxAV<JRtVa<)@&*qS}dAr?ehfXt4BKUnkj7lB-?(M4Iy&jAhRp-DjP%B0_Il zkj2zb96HMyv=@&#cWqp^j1u;*SXdxeeLtV{^83{OgjP?p_l%<-r>p4mdt-~HO_Y_v z1pujmk8;=^m7K6iGQO>RkS=#ew9afrpii$|llML9o)#e0erp_C){v^z*nWF^YNjIv z#tYZgZBx4*@r~X8ntbe7<`-tW*eje#bbzb}<)}1s94XTtDz!0IU}uT_LLrUh_hpmb z=!%L>AR9chq`@-V1KVH5O+eAtDni6ChF2>Q{9HLihh&$R1<#A!k8%{WrcA&{F=j?K zV+$3!;M3?U#$3?%el@R!%q_~gGKUnFgS<RHzTa-><1IUX9cP(-QugeZnC9@JM*Tm) z7DEMp_g&v)61KFWf+bi5k?^bP7D|%}u=FyEm@k*bTe3>cBw|Y2YNMLTRk`;D$n1>% zgCd@^&Hd=7pgv8_n8rlVf035+&8Giep)meh$;?(&<Tpq6iau+W-=2y8@!C)!Pj5R- z0<Kei!JFgxi_fZooqbH}(jPh=U30cNciz&V`ZCre#ha-*cIjr0x^>9%hm!$jwW;7y zV=VOdZnYmep<FX;`2Ue*)mzskuqs6`loc!~?YC&CdAxU%<D{)M-#5gR-jQ~#DjfO~ z2-dN<|Dn&*Cd1Bf>7;Lj?7ht*5%SbfpWoTR`tRER*6SjC4mA+?;{K6Lykh)FHo-<+ zVKMY#8t+5<ktl~NYrK|94piW&9`g9P(HmEc+6rDhH_frXA@Q1W=8Z&?frqPQ(s4i< z$8PT^NlVqTt_ynBPd!erue~oYf^lp&cr<mY%lk0twwp8@<<NP9>*|7IJs?4={zCIB z03)~Z1t#epkB*HvB<hN&J%Z~sY8)~m>Qk?gr5MXMnXj9`e~A*3!S1wgznbe<#5;B% z?#{i!DP=?cK8xtnF3$5qOA~xzwCmsAj+a-y1oV&^SD{<l)sRmmCbn{kqM)ZD59MaZ zDtNGhgWcMe)qlt|iG_Ilrus?w>zh3ycVOJW9cbO=S6g`H$d0}s#*1B|<6rPMOQQQ^ zp~H2H+J48oTR5Lq&_k^bOW}XnOA3@Qmsj|_Fn7MX&f~$I73w`1!zu^5a=|HaA0ZRK zdD>V*yMvekjXcWMI_jM9rO67Z*zmzy4n-%Qx3!RNUmlO=Z3r*CcG(ECf&^2h(ibxu zc97EbwKG{%C+^)6mS0wNAUMmj{-6Q97;%bhwhPq={bt|*A}irFqe48VDPfyP6T~s2 z{>H?)B4&X)Y8}ElnKK9}9!d;$I^zjLsW6QpL27c=1KZ)9Y$XoDC5^rI{+6DQ?{--$ zE&v_Vz)CeGN5v9$>>eoFBbZSj+49$KMyKZ&uT<tCMw~iAD>!YMnNZHft!PPws%A8{ zsJo(qQg@gEM@u>Ng-c@fYV(RbSk~25;|=ZGC08_ci#x@@p6)y8;#Q-`EsyxTmP#DK zj}6DyLHq3{eN#2<9=iO=jKZ-JR#;)`D<AAjUi|2VF>EXsrgegI$3k}jL8;j39zK6A z;myb%1AyI(RK;Bw|A{ypl@8LaQr5UkeFX{NFer3bykpgWK^+TqUEs60?U#P<zYp;m zv=yb^R!S$0rx-362=G}Fa_;Z4@qYcD?os%3h$B&5<T15d9-DIK%9JgUCOdz5uYbdD z^%tTRH)sce7GjE4Pk+@A%ty=UoU=Daw=~?TRu?Vw%O{STzw&gbUvqup0g!J6kI380 zBQo;5dz$T<woN;~R)qY$VT^1`(gh8G=ZPHWy*IotaB=#2_1JS7`8kRw)qYVYofslP z=3l>}HDO5P4b*j^F;5l$-;Fiz9aqiTd;|VFu{Tj&=)Jj6l%jPWYpYUe!Ee!X&(sfQ zN)Cq);pr?EezjSx8rSw&_#rdX=t~Aaj_#A6lP-}P^?q2{F#3smxyY*ijxgOWD@oVq zgdLK0^$C`UMS%QZ(`~6(oy|PH_2+LJyXUK9=)Ld}n-=fE6faTu5+P5(!B4R&p!(I2 z>Yq20g_p{1ZOR(=%3ewDCM#4oC-hlDEza%|cq-3srd$B?Zo}q@sw2)N_}3%(y}zH( zD&YOWk?6MW*?Pv;&}k*4hZPP#e9^E4W8gCOsWertxgd-}2Ossm_VeEz>7KLu-q-bu zc0qv4t|x=G<=EYThRO=w0h;x7o9&FBreEt4<0s=dv+T?ILuclSt5CP0q;jC%S^3)P zLb-TeOJlXvG^S&@=KxXz2s++(XiBSrjY4R4Y*o)I1w;C;V#S+(d^~!(G)ccGajkac z=V^`+K8b60Q#<hr*=1-y5TQVAk@J54`G&VIzxKzx#j?<Ov>7h9-fNDZW)-7bT6J=^ z-FT(tcS#p%4b%}A&LkPyPb{@clIgm$x?s@tT9|uvr5srO)Xn+zMYpGFmAFW#M~(Q5 zH@2y2LeJ4hQ`ZK&nT=B{9HG?cI*tXfV^?>9H&xdirLim3?&Q59+$<7WR}Ltm;y9`B z3&FEw6bat`K;(@qgywD54qAsXr+A&78-2#`ewFcji~}7QTFqFs2Pi*s;{*gI|M$uz ziQ*@C)c2_(NYf1nC747XoW5)s${jZm5PE~hfBJ>^?O^%Bg-sRZRQxj@O}SP<A$N?! z$nx3+-^0t+olSP2tMpO@Cl$I5yHY@%9UmCmue;96O5YPZYVX}Idk&oaqqC^#vA!`# z?zdd`s{T~(rkAh281s)rw(2wxJ=O*>8M@aL(;N33mLN-225D|5z1)9Z(U~4+X4tDH z&r)eFZreH!!wSgxHI04OAZ1>8r{6C#Jja<SlD#sK?%{2LZVq)nNP1%PcgNm||5+%F zZaH{<u;5IYW5gQKd);)6O<Y}Ap6|K$5{q%MQ$8%myryDst~B=o2lG-_+d-`?i3yGC z(oWO;MW#WN(+RhJE|k4fxaH7qU$0+z_V)T)iQ(U|qE$P0dIMhPXJ$OR5^?hHFB&e0 zHPShxAN2A)IptfPFi!xj=RU{X*kJzJ#natZ+|7_r--@zon14K_EWNC$3>~mHFyP>) zojacelt)Pa*BAK5fw#_sJxL<2Oze+)>c6@_JX5hr9e@`^m#&}KRj$6&s=1`n3>J%F zw)aY)Jlt_c%`=j_>VkP~KjN@wj@bPX&NXa)_8Jq$aJ3;FVU%4-28wmZ{LcpoTq^@& zJ~gbfPg;`pS!5C&Ct1pX-77G2ieUd(5(0wUKKn{xHleJ6x&8zX@sl|qM_xewp9ECv zF?9qUsM&QjrP`P3E-(S`4D>go%LW6MjqQty`HecE`b&6(EgXqep5C3)`?PQ)DGIu$ z?|)jL`|gNH^<5Pg?RKs9i<anmRMyGa>%aatZ>vE5hKjW&?29h2KMLtg#=zNnn?#fY zcVm5C8;_h&s}>Wy{f|Itdv2!Q*e5|nrhiCJpLXn`*j@wR$5gq1ywoN=)_7!O89{$& z-B<#c6Q-kwk-Psj3Kg}nVJ*`OZj8t>Jgb>UUNX_;W?YqE`cjoB?_e1x-~j0sLLGLZ zaNRCYv#{T$vxpggmLV(%;LhkY%IHKacV}a#T;U+y(#X)49YU?hlrn_#InBLW8SlxF zF^-y<EJ_f^aJ+C$(HCOp?nnmzON`D37qcZE(-x9FPB_pM;@-}n*^k_v(v7Q>(ejv% zfnc70sM$DCC#55o^nqB%HKKX+9jBBss$T?_F!hD&!tx_nwc8Y!n8{m2dzLD8#2Qc; zQ}B>JE&9jyUDT!vu(zg)^1*B$UWu8B+p<yoZ#8UwVKa+2&QPmKFLuWdhGJt+7ouCf zxtk1uIlvr-yTN7lyBc_e0rE~vZ$Yjj+6Av2m?UlB(FlldaTWv7Rg5$|8jl>>uV^Zi z$7AHq)2D_SHM$*N8Ol)+TSizV2*rA)#j#plvC*o<4XnWqu}TmZC!`TJ3<CSq$QFv& zJCvk`!cP=}qKX3z&N6vs!Si45oL&F@rj&x*7-3b^;^o&i72d7m)y-|n?_}c&{<e)& zSluzZFJa+cZ%C`;EBt!JKEJJ=*CSr(G&V@`wOi=x;7xe;`t4rzI7XGICiD5UO>#YZ zI_JG!ecj1TA-X`sYuFGk+PdSe0qPG1;5DUpH~kLWh-G(oJtsW<(bj*~ul$el;jbD; z+UDl)!RE}J%HV)Ezxk`DXm*)B{`3NlY%!BPN!rjQJ)bC#T5J#}Hv7ez-@&~Wb%jS8 zK=x103;z&!kH+KDK>2aWx3}wNHupzmyB;0Q!{My7WEd)s+2&j-KwQNsh`zOC>y_t5 z+76ZgmI0VnYtF5b8}sss2}}ZyJ7iXyde%q#6BVfpBRE=0d)7Kw=(oz@wD6&qMAu1% zU2jS47BM>7F_&XCpEB|CY^vF~{=<*$Rjy@LgL0w#DCXhv>qEsyO%47!VjXp4CSDsm z=txEL?S^($ktRx2C`ar>2|qv^))=&W;%Sx{wtv9MrP4WBbY?E6BM2iO^4qR7+wE)1 z{=OkR@Jgc8c(<)Ep`u+%v5z(TP;Z6fEhZ5}4JyJFiC_Fbp3Xcj>U#hFqhgA7Ly`1m z0u_TSD&DYM5E&?J7}SPMQ39!y5VZ_~5EsVKdlOBNVY}oNh*ey`^`>ZYHERSdWKq*X zRCZ8Sk!6;C&o_M^zklvEwwd{SKJV9ZUgw;bRI83ThzZ^e^_j+&*5EfYwmkl{S3aW+ z!DYY7I!6AJ(#-8Gi@*rE^A}|2C6t0s837iv58eJuxBeRtpk)_`3%X}4uvj~)C`hqW zmSG+FsO`qndDGS3UzJ<CDeo;$_~9kr6uT~bK#z|0u!nmO?Y%AKe}{IOd3&5v(<kkN z&+j&BIolXQCf7(Hzo7ikc;8$+mNqM|VC7g+ga0yNB#`KU68#O2)*}rGI9Jr&S`&Pu zXhY$xQSMxh428J_bqoVP3^`<u@wN%<*kt$fKD^&)0!#$?f#Q5Q6BTwT*g!838w~^q zmviJ0<;)FSmRPK1*<ovo({!kN>Ws)K5#nF;-H~Q;^JU(`^lawiYQ~xg`PttY#O#24 zOdtaZs7Mx*Ga-3pl_L|i3~x>t(6ieDX@Y0nEuC9*Zk;?DyPNk%lI}!0yzJag**)#^ z>mIM|UfT1Y%#U%+=(i(}RHgPmPgI4Kgn0$sSDN2fAnSN}@JE3F{ZR7o`=_rzw%nt3 zGv}yps$NI7DkvY|0H9M+H~p63u&#gf#I|SkLoH33pxDI68yrsTh$k{JIVdq14DC7e zWBs(VMK;x+$yDR&&*7ZxAE8#P3;#hD?S1p6^)&Ne&s>Wgr}gi8N*0gtPjnvl7bPy> zY{GV>*u78~c6p}ITEvKMp)G&Irhrc|otJh)nhx6X$`=z{+J+AG{P^7SQg=y4(T24l z`aNpZ5#`WF!Hyf9oS)CTMEN}wrL{gX7~wJSmwsFA|4-e=`fnqH_g3#LUf6K*_NB79 zm5GCGih<huj?J=pjS0CWE6LijYc7)7yg0*E<y=)K(m=q6`l#kJ_sfkS$Z%SUQ#v=S zthcrtdI=_QBw)L_>;~=l+-|>JYF`Y;ME@$JTL1fGctO?aeXAtfY`>%C@*UM9<lY6F zbD>F&l6STiqEb3F6lGCi_e=tdYbp0q|JD%+za8{n$|Q@PAsm{p_L*W?UtGB&QU8Lm zeevXh6;DkJ@37ZH5U;;1o0OZdc(L%>s={)nl&U$*jnEs7PiL>wQ<v9c4L_T(aY3ql zSd>`0F=kkGoaP^cIQ7cl5j2|uPa8Z>w6)>417DhFxPWvDs2i0^=yLFM!O2k^#LXH+ z*MWP{lF!Br*=@o71gY<-kc_n7Bg7-t&6Ur<tnU&GBP{w?ZY5+`OIG(b5V^c5YSf7j zb9tRigjr(+9b4qCLTE}&N^QllU8F<CS_;yGs8l#8Mda|WpkdKjh~4D(_!<$D?UsL` ziKCT*4usFM$c2>NP1Fq;Ghmdnk(9}M5f{W?bU>q({o$fzI^lE0+{H-}YRNWg7rl!U zE6>l9u}<-@=5l$&`+~tf<4_}xEpCv93$OU7%<<~+8ZEZ?h%U=S7tek5=OYQBawBhl zV*qX4ZF*@_rGA<KG_J*lcFCSY+aF4*5=cYqXuRCSo32nX!)W#pZ#{?w>)GSEHkhPx zsL_8Xm@vkE5myjcKAxv2SLXXo;d;Svmz%#&R{(lf%WO^*?R|)B6SCD=h!3R+%DE8S z&n6^%IG&B1G~-w`c};mj?iX)`dv*I;u$=k)%}g)j*N#*<S7fPl&jjVydjT5j&~)z~ z@DF(47vbgoYL!o|lIVf-Kk-H`)3n@?l8RO#d$t8dO}bzp9cPxP@BwE%cH+}nKc;Wf zWSHl}hlXO4W$`t5MFay$!|5|M=U0b*{kHA1-=Fr<h3e-W&zf8hsBB&av!l1+nCc#S z@)%&Dc`HvbysjTEE%xcuCbxZgrhV$^m~can{ruXJCwaXC(7(u-jrW40cRlM+o>ue? z5%nsa_WN~r4oUl5wl!qhs7tJVyD1$!pwDkAcLt~LkS3gcRv&-neqs8I)ayZ8mtwW@ za;i&Kc*sD*iCp`L-y?p=?cDzJ?uL&2_oQ0E?bMdfI%fFe`%IN!f_QYa{LSRr7i~WN zTh=w~f#WHn*{AlQiZ8yH-j`YS!YOA!NoIC2homPqyxkGw%nHc_#jI=J4dOav*&%!G z+3{A_w18lm=^k$Ml3BkV+jIH8x%aUfwa*lzQKw0_sx!?0h_|d1!<U%AXVc<5?<M;v z=5K*(%niv194NBf@BQub%nt+|h7)LDM7(=Tmo(v2jC$dq$lnF=-kQ&|+Is{;bH<6H zikIKoKH0h=>=HTUIDbNS_IO={>NFrW&xy=2BOCzYn!espTjDTy?zqzY_#}DsOq7Fe z&HhWBVrxDzO}A^gY+qY=JIc-`Qwh7j5e^ZY+mH{ta^&g*sqO#y$a46~yH(8!<~lh_ zL1N~-+KsU#L@k}H@iW32zzG1UYN^t8T*gwzec4kOzNb{|h?EGop$g<GE-d`<JPC6J zT#7?^JYRi$)p*Q3LtZz@y_qxe{2^6tCmf8Jh^0kNolN8!Awu~uRCFDSE;qoB>KKVj z*2NsBWH=6DOW$i&to?vBmu^014AV%*c>6_CGUYSX@gu_eaxz0AX@Sq;p%gJt@tS5L z0!8$)rDMkuN06`~bo)5Kj==_@Dadx>L~k@~Nwtx}gq(NcUDfQhSgnFvFij3$#px7+ zJ+b)^OFt2A#!eoheg}>_(wco}tXbI=dAAp0`hFpUW4)oU&yZ|OzcQqIH|lYR$6IzS z33#A~iY#_G_CLDCci;Z>iyzZezn{AD!U@P@3z=t>lxK|}EEQ`=k8evm6m6aVhiFEI zW$)_GMSZ&9y~N6z*DltUwUh~(LPM%!;y;!>kh!i)C|TWpI>6BBIhc4w_5I4apO1a? z!il{5S7tye+-j5DDAwad^*{gm@tg&Lr_N?x?S#=vHV{aoSBSLXR@aB6al<AKn1r{S zOMKDLcXKzQ682q~#!S9_zQ1xP)JA^>ETY)4`OSrMwp>k{{?j*U-=^k$aRnfwu_V>S zDOQ73$(HW*rZKAC2Y2=BQwM_jzu8vOWmUYbV@2``eS?NdsQtgcRnI#$`1J9XalwNh z4=-Cb2=`6Uxr(=Wu$@}}?%*Ts;?}aMPu5>No3MDrM)aH9!C#oL$Cr)Kz1!WgGV_5* z#rn`JTD2(uxA$LYjxvk-j2%PSOf>FzfBY}maH-M}{ErIV8t2ydlNGjwRUiM$TbYwL z8kw4>eeswDHR4B`7($p&8|7STFG|+jzkYo){=o&<#_)6&cuS-1hg}X%-l8pgSnS~R z<XOps)mQ#1-4DAqbRK>oReR$IEiFNI&a8_)IPO}1W6Iijfk*|-`d4+$jq^-4f?5*G zq6_ZJExG66D_{P_!S{pAFn)vfNx5kNg@|CG>z?tXig^s%Sc;ymgNza`lr6KZDlb)@ zWpbh#t`IVDUna9fj^l~v`%IM%5W{e+P}uQ=ebA>n|5s`~A}u1eChRg6qpWCN2Y30o zq|7G4NM|yf)p9e(GgSMG$^tk_(EY%=3GSm6{P^;OJ)mBGJy)0&pJpQNDHZNvDcH1; z{DZZud7ek5tlJmb<2AOmF@eOwVl@muuqmN<kiZy%FOnqQ`G_LfxqXpzsC6_1!FGi~ zZyMX1lRZ{T`f8xX|AQPW8o$4i^Bh@>JJ?nGQub*|%I$jC+h74DJ8PhQ1w=6zeLSW< z$mCd$O*sxq&G>6HL8|B>qCx{MVJ*XzoxX7AcyT-{Xqf~^9gFPfXs_xxIxhku*B{D+ zm>{l!N=xpu?3ki2Rb{ZZ_O^zhM&}+lw|Le(Q1n#+bzG=jIa@e&A}GxsPpJ2v$%g{E z4jvh+FKkn*#!e~Auy%18-2mZ^LXf7smKQrBd=S6eQK`<(EQHokcMHEeZ7GBbC#Lg@ zr}BCKOM=Nw5OzbLyJWWI4M&)nq>L?h#%0pPWov^$?}vP?HF*4vX*T;VtuTUUmpITx zvmd|xyLG=`o~WC3`0OEtOSv?;(x$TxBlB&SFLZx-b)i+3PxZP?Wfx6_)9qVNx4acy z9r?@5$BPy0>4N1TAk8)0oJxJs2LYOW=MLLHP|SUnbq-AV!FX7bU9&1uo6gMl-L$Sb zYj3b|<lW?*->BA$a`5h+t;gOit11hR7W4>u*XV(cr)@g<qdz566ixM-8B=&oe_5xr zIQm-sgvk0yZic-g?=80hHTidKszdth!Q>yksGT><n{=t|5dq~k=`BOCA=}<=xq5!b zyeMnU^X15UoHVs(SptIi5X5-(V|%B1<4W6k`!>nAP~y*Z9J>43?v|v+;!f?-^9jb% zuLd-XDNF2nrUYrCoCR1~7L{h<;B#hPW5}yrZ<sh1u?kRi@o2ga7B>}lYC;pATn<iO z`|P6%?+l)*-<{M;6c3XJwglV~0~}FuZf;-nP$-!0>^@bPt8*_qt^Wf$-rcBNoj+yb zg@z$f_r?T%E94a8M$B5&cRXg<`Rw`ry-QDqW%8bLhx;$1oSSF3zv@Ks`A_t}WfBj9 z=UypNZbIRxc52ftZfJY@8PdEy)AL6kCJ+8?XGv05O}*S`3fl5BC5Lq@k1LLEno>!; zEl&O^^Q}bhGg{n#;AdNZ?x^_SqlZJE-E3F9m=iB1vrTuy4rr>Dqj_Xuu*1PX7`2^k zOo7UkXdNb@#Bj)3&hzd%nE{F!q%uU<mLO)MYs4-GRykq}B1uSe+}kQJJj4*lmK`&e zS_DbVRFxh&#%S*naj<o%8*_@*SX;5p`|_^y6+A}B(U)h>HUsxdOV)>s`q<MpmyzMb zMDXwoYpBJJyUzQCYow{xYz3NlP+>j?g_)OElEw#DFV=80RW;Qn@%PwMnEj<y5&1h; zrR&RfFjdeB6Dk|nOyH1*flL~9aRK`Xqr&KW0zb!J8BWXLX_FInH@D7gK(OW`Dv!80 zaBey$iCh;M4_9QFH+&aCaK^;bD)Sfty~rvdZhv?k1Oc`u%(~be{8QJY!MQ8XmYu9E zJn)b|`6?qC+!5FnsDLmT^D9hgUU%h(vK0oS*xLJZug&^k=YoKX+L`Bsh4CAz67>(& zhWg0u!lo!{@RtG-uz-P^?%tM-Qf*$b?CNQ^g26P!+nbCDI>F9a?HvBJEUmA>uxiJD zf6G|vp*{UK&+V&gL|;ITFP*j1?d@4xtKI7Z({>*Zb9uAo>D!;q-|FzxCh;aK6TbCe zYk^Q~Xsstj|Dj2_UwW&hPl^h1NYzJ~7QWWG`{l0>ymjHN!vW)4b{p0RSH|LjckdvW zhe-ktqvHFcVJCx$qP;6C?A>n0ZqUW*(?8Qq;}9>IR(Y{{N0}p^y(x!duwqto-Le(x z>Jfgaq16A$m#1<x;YKWwY589d><)v|(7J}KC#hj2L&M*Hou^)0)~{y9h-+o&`^`NY zgOp#bPYijvcJR=ZZR!7d+m01*tY76*M#uwelWJZupC>?5(GA5!N-B1mdV4-(>RhpN z>S*MNWF3gCZC}v>T3fJLrS$-A8ZAt4k4TD~0fL#*u3SA@Ru+_*NMBqec6WaxP^){b zy)je&fzyX`>FjZC1%^(Td)of`!LAzyO&mj46yW-x&!_tjx5|jF^@F{t!Bk>%Gcrq( z5`?0k?>bkq8v~6Qhy1W|9jm06kcxyNHtQ<aH7lHxAU1zwu~X!7wyHMOz`wGo$1`1M z$OV=gvFCe1c{Y`={1E#U8(PV~=oiHpx%7#F#z7Nywq-)3MzM>X5r!i?m}rj0oDY8% z!0tLBWD%yAoQLs6>&V9nv4}i#J?m;|;v@nFQNcM^VMML!V8X&f<u9`JUtW?+*gc5$ z)7k<`pG4LFOfds5J<AM%Ziiwq7s<^{vR`Cpe|$8d>{8AmdlM8_e%(UUaXs}l!X)sN zxf`S3A+bD%cUS2tp&a>y)3$`C_<EE~2sOs>Mr2Jn)FWMuV8OlI+f4eDEXXc1ufVMY z0l|Bm>Vsd&R6VPXi-%R{#9FGd{-mMQ8Kx>0xY4JMUc`k3Y!h1P>nZ&F3R`w}Szclh zT9-ZJmI6wfWl$zj_{$(kHV9{?Q~~be2)UlcttkpADi6vUl0!68G>L+xCcUkFP|YQ! znaheqbp?Qr26kk9dwuB|Df(v>lXvPg&m96qC{8s3T<0rBNkahYY{;#w>%!axjWa<p zEjGkV;fI;0xSRqAS>|diYAOgs)74H;{40!44tBJg-1A?Nu=s-xP66KM)a8}3{;U?m zy}LK>yg4-BtqI<!ThjffME8cvxU+E!br(9z!kgtfQ^jik!Oej?8}96QA!{RATp!vS zMWdK2S33RN6aCYiiSOT$R)5yn5Z7t)oKG0^V!Gmy%vf%%;Y%hDaIA<LYT(jMQIu@m z*V(CX{-tjy^_Ta*9UArg+MVHP`;NypPJ5LTowsF8_10CLxK-D@Z8yUFVYYmrqruW- z@J~rVw=SzSy-&maWukM(d6xG5;CBway`cf4+ih>eMCFAo)Q$bZqQPeGxmlJDFni&o zaA6L{_6WZpeexsO%Wj68g^k?kWX%9^)4MzI=bhtzT1)LTLu?9-r`Yy?cjqJhf@_md zS2Sc9w$nff+FhD=^I+<MmsWK=lHF4^T;1A9>aTS0e0XWa!$T-8{-#`kJB@h%s!Ju1 zB=>}_y2VS!qmS-ZRZc|LpR1g_`RnU<5nAE9wq7XY4Bj`M7$h!h@4CE1=d1Y08Ad68 z^6KTmO~=B#VzSnA6T`Hn+NrXaw#oyOZ=OXG4?RXuMnWw!R=!<1;l?_ng8}3S!<kUL zWW;dl+$_~*?Uag(mXnk-4zBbZsGq*oqWZA{i2a$Ofi1V)WXObekA~vXFIwiQo90Kx zG{pU^5<<x}ca--p5q|vurD~%Bb4)l-HJ(L{3K~zaw|k-vO?5W`MDnH=QGisNYpSG? zm8^G>Mf+B~&J2(Nm!UU{pHE;<rQhO2wI|>`V`Y8aXzUhZmQyUj)L|k*<$FvWca;$n zt2EprCn-pe0}QA<@j8{(3qAnkPlkbBV=u00h-0+1u!RE_;Wq`I<d$u0cf?YVBWeCM z0f_@2S%EP8Y8IMrB;ZOk9nuuWTeTGNp5s0w;w)2`n|e)~x(^oo8>(a3vpKwTY<Vu2 zHyTdI?PiG<LU9j}>rt>T*nh#EP3GQEXPi!1%VDL|W(MJ%z<cI*FeK|KUyhK&)QjbX z5xK`$XPDbdWrE+y8o~u$&fd3N(X1~W8!uI9ylc-Q_k<i><pu&@<;jc8X3^}q5wcj4 zzTE0)Kh>Vl*#A%9=-y?+750jgd?^^BO<ep&0d^Opc)LL)?SpvS*$Qiy85mbm)I?)W zeVjE`c;DgnMx4X#LO_rO)0P~2sM0Li{wOj2gw3go=*g+1*(^{VCB|46Xan_;CAH?3 zJ|}xtC64{W;sZ_8j4e&&0=G&i8`%iwG;H-q_4KR9!IITiKC(=T4l@$%1-fDBg|Cif z<zahK331Ws`*lSM=+kNf)X=g=CQtJ}dK}YuvS<B4H)plHQE6n#m0ltwSQtPciTvGj zc=58^PolJzvgH>OI`LQPYdG?TcX;cUr(>dTVHFt?albf`l){Nq*(<+~F;#s5vEi;~ z*$c;73|%+Kp$G2h$~&zzF19;fuev<5&G&xr{g`R=92l$_6tf;Bev@@3^F()rQZ^8= z8bFI~%v1kfY0Ww?3V$fcvyyAiF6=Cej-K&_hL4N1XLYq>lgzUC_-C_2)y7t8V>TT} ztel|DZTR}hffr6#KREGdYr}3;hBWQ+C&Pn%*DPMDJv*^&PUlnV8&O`%-bn}(4Z7j< ziMoJtQcaQPLkigX3WCEv26Dcm458^v$kkkl6|$%K!r-pUK43pq2;}}%qt^3CMM94d zinykH1}n_S3Goj5r+i*q|07U!!`N^N*NaO`2DWY9UW4UJ%9b|P3{rmcn-TumTl)-d z>{LKH3!}^F;gf+O#(J1j==zHLG?RxiE#nrE8Z~@>p#4$L;c*#aK|_7z0}Na1*c;(4 z+PSR08pC}*tU;7qdy?lI=hC>BMtiaf<zr?yW%FRUiFJqB*CD(LT}O;LJLHm~MOK~O z^*4%i?RC23zL9wu1N<)xU7Y}d)q+-yZmg4(t)|kU%NABE95VaW{0U5TDE6^Z3ucjo z@Lnm7R5Y<Vo@SY^^PIMhW?BnN+;8PvU7vuYMLgn~14T%Md5YKz;<!tyhPPG73998W zN!*EfkTe_Nw>OG7F%jthl^NJj3v*qT(nC8xLsd3!0Iyx~dcqE8q&8{>wOGfKk|4|6 zWwQ;Bo=8T|D9bHE^|~V2zv5jySxXMmA0@Ty9*?W`JyFlkZk6<oAP48D0z)(UYA9vc z8O~H!6c_k|GpW=vK8fzDv7Py-d2`{AFh_5nV4dJ8czkjiZN_5jg;iF(IOYE4^LNcm z)UTl^Xv++md}~b6X}MLEZ#f`ij962qdR}gups=DPrv?B^Q6D*UknoqogGGR|9RATY z5F8wts4t5H1im;5d&4xcG|y(--Uo?R?D}0nbzt<{6PGE2Ul>eHrmc1(Vr!r(S7_({ z*uC@OwW*Wjm&ZR*#Yn>m26NEj2gQUw`BU<6p>7eM<kKLHR$DUE*1I|3hnoLQeN$6V zSwyurP|cLK@92$h1M_pg(HA;z`cpFgPs#3<lUT+%l!fz$W<A=}=3L&WR+d?B*F2Rq zjPI|Uwi86}`Z+O`;${OYuQi4aRQ#>Wlh3Y^&h#OZ6iqB%P+dB4Vb}N1+vp2=6+vI` ziJiUa^2_?V{6ExS^V$obBzKL;Ip;3P9%+AwP`*(OA!n$?w|(5@!O-X5qCLBR2cbZ3 z4XWs<_Du7^)bF;I-ciiK!5*607eh&Re-0?#t@^G~J1G60M<S_a&fBlNo_rJ4-kHWd zhN+u({vP${#>BQ3^+M;bDH^){ZH~=9^XNC1suoRj*tjk!b@Cm5o9=O|@0^=6zjOP= z3l2{xF!fDQS*FE#y|10bM#~{j%nNj9io+a&ERLM{DR$x3quX1B>cSfrB%5@bj50&a z-M!`3+ot^#@BGUu=z2V9EwT=2@qN{(N-t-acn}Z3`cAy4$)_1H)2B!_=Z3u6M!_iq zI%g^;o;u-EH4zH5;AJSdmXx(dM4}r`v?(G#<t1SHSLxcRV3y1iYb3Y%BgZLVC!EX6 z$WbF>ScEV`pb`ZslCw;2&}5knii$=I!H#ik9KZTaYzKVc*JJ49S|In0ll7~2fDl7Z zMFVu}jYW1FuwsF_$8Y?VUv0335VUM-Ghf@8R{_@5`w~1yU!xz-OJvm<PU;?wJkU@r z84=@$QzecSRLec8h&*1x8`Q<r%j>Mr#$BkcW+rbdX3M;rN(bQk2YhQdLD0Yif2c^j zJI7rUf*(RSw#xoWm5`T*l+;lM5k0{(K#4Q<f||)TJv^<Ywnxq55*;(%8#a2Gog0zE zt40%8*hheoftcF~&&H*i506=_PrAJozI47t$h3)5A7*+qmTVeato7LX^`o7&;a6n$ z86t<RbI!71&Rk-QYhz1qyQeJh@+&(&?!NoeiusFJNG=+v^4aUvvNvG~ewlQIJA-e; za7*w(I3x-AkAgfWYA0TJ>VR!qgxq@P1!UycPxja#BR}o&bS@9x!%SH})Lr(%nx$4A z{d9|9RL~_66KQCgf-}c==JI4l?KkS)IR7$;HWH;`k9L!D?AL>d;B@}-$FryZHxW|P zr5leIT&XwNYPh31cV9mC4^?|hf>XbK!D@`bqg4ogZ|_(<ZumO8sD{+VcYbq-4b-h3 zoc!2wOueGziu5^AZL6R+mG;IwyH`W46E$4U9`-9mtIIzs3XrS9&~f)%&s@JHc>a!$ z_30;O)~vtS{Y>-%^9a_JqVxYXy>Y`1s7>;uW`FO;CZpN|%xj<b-B&idQT#;@%*spv z)Nf7O1@Eu6MnisX#{d$JPb%<kyy?PrP)Ygnu?8o#+9?2$w4t|D|B`YrO%wR(mus1M z9NZi^>ehXH7OBOkmD1P7H;lJR{_%Mhq6tKk3p;*&5^T69%FJhTr^%(mOA0&5S{Qfs zSMSvp6lMs)8~v9sU@<tI+JqgEC|lOt-YSdXoL4FztlS^`KuI2#X1_Fgq2Q3pI~xkN za37*6U}sk!{n;JIQ2xort41}OEP1A=e{59_P6v4*T2Z6$S{^5kegmttj(d%9*{0(B zqng4&8&|elMoCwiMJZ0EQ`m}fB$25{ytGeOaqO$Lh@hyrxT)I6>kTYqW&g;*afDCz zEM~0H&^x+>eH+grhHeiNZx&e!`7=A8LfzF{vM02a5o-OLeSFHz1(ZF$P1Tf7tvFKV zAI~->lesf|E7W)?PVX|N6D?rn-A=~AbmqJU?614x>VqQ)n<J{-x-#4qMNM<NmYz9Y zq&=(=o;gX@C)Mz|K~2`D4D!CjQZ6Xh>MSdfQfzrt(edyKVvm`srR9ioWo98(=2)55 zGQqofgkPbtMH9yU)ebwLp_&F>-&fNF7mPkc;)i#9=rVI9n$CB;jQsBJNFoU`Qmfa0 zfhdbbwYJejyWTdnH=hm?o-w8d=<p(VdpXR`TSt5Dh(bn<{rgQpe(4Z`b$taV-g2Nb z?qB|jhd)?qzqmGaDnz;=<j_dl{g;gE>}V~yr+IX9+ciG@_n*fkUC~}ACB=@Iaa@m@ zk}i$e^*rl|>SWuhZ$HhOe5IwlQ7-1dvpY(AT#i}p*<lsUE}M&S;1_jw=6|(i=Bb8w z3xzCv-MHbhu5xY}o$vkBtA^T4`$T2;a9EK|7hg=nQ%lvB|GE6ZjvqW-R`jG5&Ajk< z;>8Qj8nIXUf!~y^bA1zjo>+ET(Nu|-ifB$Yd?~wM`ct0e#Syl%r}o&@%P*hY{p0gA zHRusFAjAERqY=-yPq)nMyI(#|cjnmiRflHgN6nb5VH@P5p3o=yM^Crm1maQ-cRKD; zu-{-*p3bi4z@FjM`iwA}uK6)hZyw1i`p>#Arupgr6Se7sV3+y<98xY7fBjJP^;2ir z5?y+)e5?+&9Fd&|Ikuzrcg_9T_m|ZD^iSQCyvZb!67>$n(fZ2bz@YNQLrk-qw-oLF zPwtI*@BUu4VUFijR^3)F)D3m!^(`36{G?*2dc1B3!1zRafZlMSNq@OBMz<Fd1XW9` z%gciyx}}egc}&p<D4Lgq{arifdb3OB;Jc4j>tqjq(_L?%ViI0x7rOqwvFyH6{_mn; zygM*SZrRP0KV$8IqjmD{TED0S;n#r80Bm0R7?XhT8OdlMVtWbxO<5U%cROltamx2k z9{S=w$9suY$=lmH4Yt8@ms5>$<kXKWE{5q|c$=yxA^k=n6hh(UGwU4(GX>GYpA`?I zugd7?9Fhmy0Iny~gXV%d1(`_{OJAO$irppUslVd~w}t}Pw@vLO=_$A7Y>^6`E7YD6 zyn3}20ZOW5nm^swKIqWI@COBA0)xmzhFNEQ#UG$_Hjl>yL0@OG9Py{EiYoCd6S0cY z_qlf^5Z!4P7;Qx3c2C>a5}d^J$UVHK)%<6mb#7LsXfG2ycO+@Z-(yFGuUF?XbHi!* z)*A~O3TaGNw{m1zynLZ*Lz?40+|#(h+EPG2uhG@4q-K~Mx7m@VAp-H9RQn9=c04&9 z!dG=3AB2gLSA}h!5MP>e5$Av-XjVb5j18JRQs`xWw;^Yr@%f}GX_Psc-oBV+Y*@jl zspzm-z}wiPb28GvE@!mm89KA!34e#nz67BxZKGNF$%+M4y2#<|lM3v(BP%9YHdSF5 z+Gn?#t=z&Xi5m$>S>#;dF#7hf587UX=r<6xYTrSZgh3nas!e4kp=WD8Ycy0>uLop_ zi*ezD{(8BkJNnv*iH}#MwzMti5t0ZpM9-|=`E*nd{6im_?7jc}SN*n~&wjr!$GHrf zq*Ukc=5E!0s5YJxs%PgwY)F{fG5=p>FO+RuV)OGsw}SQufz#7jiNjMd`vDz$=fU6) z>fh@PP`s*PbIP%@h!6|kwOg%9>1lv+?|S}JdW#4BdV{b6ii%xa^e_wb9fO|g6Z)fz z_zq@s!xv_~A2wy(%}Xn~TNFL!-y973&20ul6^(W;DNA>@<gnrO*z3x%wdv2N40S75 zodqK9sf~F2voXpY*09L0ZCdlJ&VJDxZWX_=NLD$NkasNW-xdqI&FlXewf~|*jA)e( zP7PoKZn0Lel_z(&RyAgt%w2K2><*=>s!RZrJtc{Tmpj&u5%jZa4{^0K&<17aRvszJ zJBNLvey|-$6S83JH49em@(+1bIrPGnKP5kR984(Hn+$xrS=C`LX*<4v0tph|n4jt| zb)P82Nr_EjB`$1{abfup7rABafyaWp{Nfexu25~cl@K0j3+_69&l6l0^~o#FS}eT> z)LV|$_txBGJWa=19I&_VLPLQ#BXT9H$=X(5pE8iO1lR+@U^QsF59}+`n5fqn=Co^u zD_}?Aa|+rnzYLYq$PmQXc&M#;<zCDlL1Ak!8<)aTNrVf_)JMpWG_FXKoYt#J&?lBk z*7R}sz;gA$hD9p@jV*x42l4%k!(aj>JIm7GZL_V0{h<gDQbs|sitYVc<q!{0=18&E z|LZQx7ABxV^*32V8Pt|kwFT7N#xP;uaVnW3En;Up`&;39vw4fr6m(AKQnd-I#v26# zWsNySzS1#m*Ax`abQl;uh(<tcWy^j+J}yJdphk{wL8QVEeQU*D2uCp2EaF`-e9IHF zO(AS8OEI%pYDye(=AxizLYxct%jh?#U(APZ!`-ZyU=^3wiyKU+eE0&QolNrjR^4@h zi&)?yN)K|KV%0~AW&=g(k>|dR`K-E-=?g*Enrcn``pV7S_*^CqP*JT4hr|fHK=_bT zAo+`?FfP$Sd>V$SAeMbnF~g4mU1an|p_Zk6KerwR-7?qJJF+778n)s4o}j!yrWdzi zbaUpRb=Lj0U-qz8jgqdjq2%1<=^J_mEw6mpQ+EYy%3{4Cbhu(@|HJ&-|4cmaB(#h{ zJUd#1RYrg24@Emmch3J2p48m3JA$ImTCV4ZzgW5B!K2V+4-XYR+2Jw}p_q}mL#-5s zuezbA-nmbW8<c~dm%^eUFYP6TMD;7bc{}(?$plK@-d|0`^1<0159=o>qFwUCozYt0 zvN}BMclU>z{&w%ZqT8SNrtFUYnH}bXhaSi4R(w>TQ8{-jnQ@c}0D6wB*HW)7F)i^J zv}rK6x$?k1(dTw<@^xVZVE*act+}1ooy%Vr)B=ag@9J}9XV1-@#s)4BdJzbsgO_g& zeLVl4kGD81dv#E7K4v597ZZ{bQQx(>uq3Q9Zt+=$59>6|{zjiPIIP+mVEK35wC>{u ztDcmp$r^29f3n7UTiH*EyIrQ&?2x(S&#-Xs;n|!`3;x4)n}5YlZ@v6dY37RgCNNXc zNv>U{_1=1PS&-A;W)dxB16`y|P|mPlDrcqM+>sGAE?rh0tT0p<Uef>c;GF1!ZIWh0 z^)(+}H?ycnjz1o}2z}Gep6-sT2e*E3byeCyYQoRK^X`I)2i#7d9kVSZ!g5MzuS<CW zEcr%3uFtsppL*xya_1gBoF=vE`=BgjmL01vQggQz-g}KO71jK}rS`*`$RhR<I5dQI zHYA)n&~)od=LJ9At*YNNP0VLdyMIxySw+`wp|CGQ4}LM_fAhhHpkMpIsDMK{>Ah!_ zh+3#5)G#;kt$fBax{QH&f!E^1oD5~Qn;daJXJlN&bRH&YWQEb<LA#N8P1eQU)=^>o zf@BdeamtM%gsdr3KH|TZDSKNduRShYl-N${I>py2S4X8(m_Oz`7|0O{3lgC^n{(mj z{*0B!PPVUE<;2@&8!7u!$~x@YmP#x!M-?@$)5KR4kVA{4xC2TOXt#0iH@+Zc%U*2S zz6qw-q(U-fy>A}nVk(n2dJj7Ew!>yDI*~XovR`B$pzLR3_1?^od4nL0BLwaFCK$ZH zY`u+I&t`<1GSwQ_jl>(-4$GF#6p4c?({y-L_{O;`vNBQ;CI2hrT}RKaMoBgh>FqP^ z6)vr)P=`5m!U1;mYz{GB@gI4*t#T3__Bl*5rha$6fd5iMA#iU_lTnI%x!TEezhnr_ zW&-iCY3j^JKDBE@EU<Vu<$g93lIPIKRBr#2F9I|xGk^9Vd1EUDG`MJ1YvNZ7L|)2& zwC3qsbsH59PY7BwSyCpf9{wBE_x1`xyF%U}-?KyY-PVQ`30*5{voDHn4(Y#6y{dEQ zwF9Eggz}Ug{B7_{u}&KwjEWooR7#hsBpLnC>&!6wX324vNrpSq=kC9B(LAc5W(&~| z6y;(<`VYVP1paR6?sh!(F-Rs}9tg;)Y=-@j+WgM$g1BX?p=etXlVL9geG(LN5Ncj$ zd(P0_Qy>4$^5(g|*NE3Ll>LEOdv&jdJ>Fn*^7aX5S}Fl|c07$rJT25APY(wt{Cu_D zL@eJLVL%4OwOp0GEDKqD@fGRCTX{P@p>#CL$8}AC+Z@|_`HMTwi=f$;8+DJ2jcyty z=r`1!l|4DKqtZe4hG(yAZ~fS_!F#=84dZ9e%}pHmLSsJlE!l!Ep=VI9$joG)=<%_w zY;;?qFGO5y6?Z9O=lo@Bkmz*TZyviM^|!5|1K;|E^FVlBt&WW8Uv}hS9IFR_+swDO z>`{fP%vL<gI;RP16b&38yic&*HTEfstUA>8>fP+Y1m$4fhh)BH!K@HR_Rvw?lG?K- z4}xd`n-vzczhNJ&otfaFTNE}UbA5!{40H`>KT@V=DhEW))oY7By>uND3XF7;TeSVc z-etY2z3utwm~<|}F>&vGqF?JPaVYdm@Nm9ht9-Ddf2Mo9Tt6>&AWMH5_26+MdIQ#d z16b`~{Uq?_>``Yh0LjZ|`sD-Hy=e4XP(ILxK4AARgAh*~TIfwlT5FaFJhu(7WS6B> zb-qv5Ywjjh4fGO(V=Ob|B9h}QM(n^%SU?5K8I1E?`cxa>D+ed%N=O}5P36`SQz-AC zEj;tgv1G$7IDD&t)bBtM^AO07sW--(T_RPwz6i`{X9%&LP0O+iq9nfp<bLd}O168M zK)Mh!TD113o%ZcA=MC6t;kxmh<I1WS=^NL$zKEG=mf`e5taR~bYh%l8=As3)5s>NJ zN8D_@VXk5qmsGw=nv6dy%WcZR#~IYHR1NpFZ~efolz5dM=ZHs660U1a<>vmq_9}<C zpOSRf`DEf<-0&=+DQ8q*>V)^H*Qhci>jg~Fp8d+cL`!L^k=jp86H1Lwo<;VJt1dgU z#kST;=7>9}MgrBK5FiH>!NfC!CRd~s!?_77Qb@%?M8LiGtGX`j7ZhiNfxoStamVV= z>IC8yc|8swO*Pa)my6NY8y=0G19SJtCSSfi<J+kxw1bVw11}%;`1a?(!rN8Hanl)s z0v=hcyrweNEqOfGaoK^H<8{}uPeWw?y!!laQtjL<X+)440|o7i9Ck?k{?F?7`VW74 z+;UUGM8VJi-ql{P#8@=&KgXV!q&(cQQu`0?_{>A-k%mHzQk&MkHW*wy_=&<<i|CdB zzfe~(tX(m<JFi|j!*UY~JPm8gwWaqGeytuR$2(j0Rm&O*UwQxan>$Q4?TpS>g2^4^ z_T5bQ;nl0Mv+{k;i)MuDOP-3Ocb9eMTYDB<F`sxXxMPk>xlDJqSC()o_gej#IXcTr z)mt9II1QTt6h-_9+!!47aiyaB`={%2Dse>mT_1-*J8@qdw)W+oLQT(L!?g&dks%}x z0ONve(pF2R@V#!)VbB>cK)qwe=sY#>pilGigmtwBqrp#<leYF@Kj5(SVREHVpW#N> z61-t+fmUnz<AN<1V>Q6_x89-EzPUz`-*%?mmxj5q<h{XvHmr6iIq_Eg1BGS!^9!8) zG%8`wikyLGmUb<r*9`7S_hWk(A?b(q@~mX?;CGLW=bl?b-{Lr4Xv|_g`<0XHV|rzk z23>03<x^45Pk8bmK;Uls=erBw_>N>nA>}Ab{p}N!U{`#Y@N*IhFdhIFF2^|p+7`f> z=%ruE3>q!X$pt{3I}jT(hRu;ILlJo+7Cq<kge+a;_ysk<@|GP^I(Z3J=4O&C_|(31 z>{$255O6YsY`XC&yxuyhO*mv7Cn1~vOX017Ru+T?dmfV+Jfw&Svvm~<hTwGWZRr)m zI3#~w(=47{=WWEK_|ZM@Iwk9=v6EqndJ?fS%{j{$oQ%wTTf5B1e#5KFb~+0EbxMUo zT4X!%<#vKCYfnBRA<tQSHl-3>+{J8na!Xr^un+!I^3|=yYSL73WQ=fRLv=#$4~F;E zMATcXxo$O&Q{bhPRMk{{%X?b7d)6g&ejWojCt<WDsxqT-;1LjB)5Tk%{b7OTeuecM zn{+|~^F8c9<35wq9f(HZ=#`I6`q|2r3mm90fBnV68fouyZ@<O6tCo_(+udaV$+1Bw zkQh8JU7YqRiyq&!H8_3fqO7Y1g^(-h)((A*_&0IHK)<yj#CW-b>}Ju%i#71>G+9mM ztDb&#DG@hnZz>vpb63mvcG&8Vy<IX!Gxnc4b#U7$8m9V@I<@8S&fM<4$9KQJY!l{P z*OqKB5Jzj3B(ai;e>a}!dTHx1pY9XSqMy$jnxX-6DIIsYrM>BSx;EY!9nYGw`^jzJ zdmFmM#^=kQ55BDp`E0j#!Os?GMJ^kF3u+K|)~3lmWTbAc-;-1shRLq!e?o3ta16}9 zVL3%!jLU0G1ld70Z%|g5;oZJ=M%*ysq=tk=1aX?26|-J`Ry2D(L#v^eO4<S%8R{~= z=4J+H>ZIT8d_=G7A-G)TTT8BOxwqw=9zR3up{C!0=qqT5Z<p~sKBCP_$4(nJ!ZfY~ zuZZnE{n?3i%%2*Czgf=OZh4(c$lw(1KLWRI(InS(c<YNFX!P$W3?~`|F#Ei6AhmyH ze!<Ye%}NKEb|}E`%I+JdL^R+jb#CAO^li#NSO#|#Yu<ZvUCM<-m&@Hh6kM3m9rU{f z(|el?!kTJI?D#8D1(nZD>O@*UrvBmavNe1_*4%{OR$5gaCd09uSeO{indNgKFLwLZ z#Q!ZAe!Dhn(@8)X)_%A_w=q5S;kn+<ypmgWUtGDrW$%;qafa~>?fN4;GDEfofAgp0 zlX9!jWCf$PdY;AI9yk6y7_g1W8;mK>^%Pne_Alb&)5OlQ77VzCTU?E@E*8kO{}!FS zsT=||^g0RYm$lvVD2#lGHU+6fbN(-Klpr8bd=%;6#yT9u>c<y;M7W{PaPQWrD87L) ziG5)@e_CWF2GC5L7lOuDtk1GmYOmJ|QYILtLKcmCcPx$1xf;M`&gmG#8mw(fPf=bD zjWFWC?c4H|u4E8@_waJIUW)@6lSTh;EF?x^L+>QM$ib0dJ<@LMqL<ys@pvwGHC_f% z7~4nsERw~T|Fx&3?XVm;qY@Q|n7_>i91=FdV1@u~f*3BeQE90ktKRSs9r_(PKhrvz zLOshdoAJIuZxLMSY62)WSFgp{G&6BHYz7>9wo8JqDgTsY`)yGIz(78Gahuqz3}PxC zyuW<MlWMA!%n+}M4<ZD<=?F^1nxhnnQd?R?ZdT&>cEq`iz#tI!xo~n*Wa(~hhT_BM zPXu`dj6wn%Lv9YA<O$DWikdgL!uGY$jMGG{v{YxcC<bcZnkpsl<1-}~+s;(ZDz4#g z*@qxHgaYq9iF##rD4-}#rwslctmJ@46Nn}(`Q3H!-q_nENyn&5Y=+BgAd=kmH;I4i zmyhr2O}Ew?E|dqqDYyRMTy5bwl_M<(=EI@(8{ci-S()2-u5ZqI;8d|D%{nYB;OG2D z*L63RQPK1#X=Giqemtv+FFl;t*^>P9bHY9csUfv4EZFR=!=A_<z|r+@9Uoc~s5u=b zn=0Ks5dFLt9>O!cgwO~VYkr<Ty;0444I^(*g6d2DPj79STGpzT`~EmaaI6zU)>V|I zZC{(4``f0p%R$#BSI)pUVb-tC%I=9v??|(*Cu}zso-52H>`MLjzI~*z&w0p3ILr5z z?pOX@X{l3PY2pv{>6>Pio&4XScWa*N=H>5H*Be&j<yQBkWWimB+}rCf))oSP(6>vo zB4mBmQ5J9Z=<~kyJBWD#A1E!VPnme>1DE`$=gVSrH#`J7`Mv+&e+`~AJ@(C>YnJOX zt2H<A;*6FWLJj*%-o|r`;SC(bd4|%J(Zxr8lCOJZ`xRXz$&qY*WS4rMvZ2Ug*XxBf z4GG*`jvPl11>a7`uSGdKS>uCy*OLOTF@!ZjNKOW`y*9?qaaSQuEEj|h6w{(nbDM80 ztooaj%d;U@HC5p}Y;eyWoh4-=4ztYl$r9U~Me}`mQBNZ?3V9qS`fO*1*rYF0NMW6s zv+YOL&2$|FeD({zWpRgC0lxU_;R>sSJhaE(VMN;7%9P0EyTU4IikV{;rD`PwL;(!h zW`HN-kpR*k;g`wwXNd*>Ge?R(%hMJ!GOIr&w`}<|aKw#%3$ULHTnHXcPM*vs;=T8p zTjGjFRRKekzCJBQA<yukfzLjasw=e**cTUXmE)PPxAnE)hC-3?S?J8QIG%ly^Sq1? zVz*)DRfV@8sRh^<d#U-SkAicL2gf1X!Wz3|u{IOOEgJmxxJM#UW30$STt<vF1Q4p1 zy17l?0<FMixWeN2m=KqLKl3?17R3s8RtXHbUozOH>NqUFoM)Kup%jfT$7t1PO@^Yy zm(O6?-g<KC)2_qPk~M=$tt<2JU-P$^=R;h2kwLOCy&|14{GhuBG}ek4saE^LW$zna ziLH)(aqyorrY6^2`KSoSN_=B)M^*9Wb%)nMxCZkUMO>M5c9eo`7gjM=B{_x{4R`LR zf4$|z?6>c^)EE3IIU;aMPpi%w|CZlB9rL`5@odKJvU75086b3K*2Uvl<8<$J-@Uf! z@14&Moo~V3UdTIZ2kyAg-6h^U_DxEBO5ppQcQ%Z$fD7=kJW(Dc+Axi@*l`)0d&n0N z7-9U7AM7C(l#*YF^$lIG9ICm3d#7Q4-z>+iE;pp0-YgDmy7Qm(dV2jeBkDTua_3n0 z#Fei^e6`;ugW8(FbQ^;zp*<9I<<B}+Kx!OP`&r(55Z&3@G^U4j+}#u6ln$N%GI1Av zagh6xH=N>}PPx59VU0~lIAN;eKdCl7BF{)<&qCzZ;$7*BS>BQ)dOFE^K0%>CpjXb0 zARS<sjb(yQHNz(7vOaSOgI>>l$73Q-(-vBd7=nmkJJhy{>_YyM{wZl@G4&0e#yjYr zM~Kl;0``8dLIN>-MDye%)h02PrV|lgF&AV|+{74W<J*!8ww{-OvQf~yqg`KafR|AR z>ncKZY{WrJ^#?6&ogim$Z{0<teh$Np{w;Zc>B=rEgGpUgBaeqPcAZAfhwLfk&9JzD zk$XHc4#;AC)w{-jn25xbRjYfxv%M#}=h4i(AfAYVQCq2><_!uWG{h9Z$Qb?1@Z$E~ zQYn%ig&+6EdniTjYIMj})t}W@9dFx98^>2g&Rrv?E~E%nS)1+@{sfd4ad~{%oH3TH zQkX|7ye|&H=j`>?y*2j7k^9K7-P-@yWDU`PY<p37+p&}s6DtgT0P!i4nb(Q`n6aJC z;YN;=Bzdq12H<inqxQJZKG?nbVhst(hS@%`q3MS&r^=@G{{|htN5I2M@1fKyl%C6) z{d(&^zwk8Ha&QPLmPP&+OAP0&)Z=xf-#wNk++_vDmuWrZ49u6LC6<I+AP9Bty?3z= z*(LzbLUjys3zQzI?<w%u+BQW@HZuYax(K5jkfJE-rI+JAvk=Y43cHjcs{*K!k!DNm zm8fe(@xDA^-!`<T{gHmm9gg3cHmgdxO)Lz<!~t=cYoJO$?>jq|&QYO{o)F>^PpR`F z03FxDR?^#Agk?}^9CRVU_F<+m>T{7opqf>Q<qlu{rH2jJIp(|^o2U?*o?BDLaoJZC zmM_nCQ|1|*0>*vR<y9S%YLkI~G@99V!Fnr;RGyCe%rP0V{*1_q(T`&y4Gc5q4nv}& z6|&<RyLQTXKJ2md6ug%Z69(RNHM>rVuy{k(k5L$iO{If^g9~Exz}I$SJpWMYU*Y@5 zisrM}%RR+xydel3ujeO2_MXP)eK9%8fdN_WvTefDeF}RxMBKHJhma@Gr&{4IEaaTb z>G>A6GZiu!ZgW>LiqI1uCCQyQWLwKuq34BsW^ShNY<h8<y>ezQ6Hwff)!y&kO1a7e zY!14N_bOmkX3yr=xDeJROGkak|GziPkz4AzIz7bl*{^$YupbPhfpf(FOwbX%&CTSl zrnP?Fp8w<Kajp0i$8#W>BoxYfg<F@`INwLX(>Jc2d>Q|_&Sm7PJ1ha~ynJNvUF`=k zy^3-BWOunRi;r|XZvTGMUo(anSIgor=V?mXPE}Gc3u_yP6Pj^Ju(L&P5##@4|IsVQ zcSz4-G1~{60;KbM3{m8MYI|v(Ay^EN%ff4RzY$=f?ht+K)2s|%eW@tI@M(Kieda@g zp-T+KFqMHeRhA?o@0?lQt7~8&^=MW->=i)B1y&ARP1LVP(arhIjLN6t9s(8}km@2x zT|V3$wMWBNHnI%8eBhTj&-JR<#JM-s@m9SXU9*^dgC1DYFXob_Q_ixW_zX5*BN&oE zSlF_RxCYW`7m^9dJ*uwTd#w@@>BVDG+%P7eOe(mP^;`tiewCo3&^o19<Cy{_&(gB* zS5`#}o|Y?nJ#c^!YY?NP+Z!2O@%RB6;^S<o^~utf3OYWc!wC8EBEe-Bgy4O<rU_zC zYuR&qu1Jifp{4-BU2iq(9|*9F4^`=C<5U-OL_eW?v$05;sKPf^5MrTwFzRpk7h(3x zOkQcS5Zo2Sqzv(QY&u!dE=m$`PW+Z`sy*zN^!nO|5riawR1gsmn8UwGbl5eXDG67U z*qbN3&)j*?<EiM|#HT*S4r~BE24yTIWSQ!{5!;uG>b>04HBCc=JMpC6zMc4xv&_ar zf^wJ3wq%hz*yb>2skH*~6d7OeTEVxhF{2n5(X*H7&gQV$<w_q3i}%mcXKK>3>Ui00 ze*C|Y<+cZ$%WWlMYU!^n&GcZzYT~fVDpCKTNE2+|1d|!x?$N%G!`G7S;Nl64(F=ob zeX4W*i#hvL8Gf$3vnApT4cURhW=FpwO*OZKFu2XzH4gh5`l$|E{4{g+a<P_<Rm;Iq za~6sg2%9G(W1HbC?xu31o^omIj&P2{B3pH?!D-?+-p|roY!8ncn?TG|2+qa8t;I$# z-JQfVD8xmv;MQyP6h#MMD95|L*xN?Nhjhe-0;h2w31sbd72oA%F`exHm9aZ#w=T!m z*4D09zI2`r2NlLf{_+v$WeTV3k({#QW|9h95dloS+_*?ZR_M}Z0OV$$7Eg?KImWjv z_Q^i<O(F8CbRT7NjCy2y3T@s=1cZVmAa>rGn~k?+ikosdXv|4wEd;5YxVQ{@xU?*d z@}AoQV-X>1JlChnxK|HWM)Qhp?`|j*@nhGN!M63<ULsf1tufDir7Y~MkoLC1Uq&Ix zmCJ?fF%>(^<eNo;IOV$9xzq)2W!)1YhiodxfCw0EEUc|+K?=6Yo~^Lv6Zokatlh}Y z=25Q=uZ=enr4=$zxWjxy^)w$9hSPWxvDC-8ZKM6#Uf)q5YYNcer?skKb5q~*PbRa} z&po^==O-hzuN_yqRh=|O7PlwoK<c~aDVy&2f*DOPnTuPx?Y8+|qfQ@4u{M)<afR#3 z&7rTiVZCabgR#OWceVHBEG$=+I%Yw70kdC5^o&CO;W~AMFXyeXp0j$2AKqc*UJ#6V zuJDe3-tuH!&$<=os{WKbnqFJnaQ3i`+5^m`e@n1WJ)YSPNcxqIqIC5?m#LT|_OCFT z2uyvZx{`I@DyaH+Y`IGI`xC3IPGKuW5AD9Qy6M%d%`6Y?-3gVojAMz-pss8#gzK&! z>%R$@_RYG4MK)S%9Y$2?(#%hWpIti_^E!*I1bTVmuCK9!_l`10&QlXsG&wAnbnjL) zm398*eyeI9s7<;;Zet8K+~#>LE71k?Ctocvi5Q>vGD9=g9D)$fs`Su|RXWfuT#NA4 zld6{$$zr4s(o294#2iF}jDUSyY?8q%P0Wjn;osP8$P=xX>kDExj}KrC6hMu4zVft( z6%RDy{8#9T25KIdJX1MlBV`9j9&!iEN*N`cdO45=%CM%YF@~WzAON5Tl}mDE@{MdG z^}h}4SzeC2%oSH?sJaS^z0BTjYnuHS`Z`IhM!4?<Q8t2sSmT7Xjxg3_nL6jDlI!g{ zuFJy78JDao<j#T%xKLMauduo&XUXG@BQ0u$?P!H~?vEYiaKg{57X*BK_BGUrEFl@0 z&hxR{)ieOdL}X$bM{71()}I3MuuTLR=h9P@b(ch1N{f^zjHoCI)!F2-8-^zOEHRnm zg&|K;?OI;Mj80lFh1DXH5!LyNDVWaT5Gd~8S||2p)$97QM~{Fp=$ZO*Je*5yL`3L< zc8^`A<eo4Zt?^7#SgD;(xSAqEbI<Cn#<)q$O|xH6^wn-)d^wI~9j&7<;DAaaB6sDy zmcsI8B%K_FUeUcWngIJv_gV4tUvhs=u+J@T)0KOrLMpA$y*1_Yr1pjFO4gg)$(3Wv zJmSCa%{I?GDmr${CEya~B+Wj=K4gWpqDc^<W2CgQ8-Gw5ie(PD$++RqHuFn*k_)`$ zCAYQ+p=m@pU^LO2Sy*vA6E^d`?E(AOixoPo*Q-d#KMKFi$OPPdNn1RfG-Gv%owhBj zoprAd2pbYv%u>q^rckC{i%oJCK^t&%Vi71u)=>Nv#d3Xyl0->%=7CJPj!PsOZX~&0 zD}JOxBD4_6j^*q+iNo1Y7;@AQ$FEG(`$Ameu0e$ZF{5{>4c8BkpN*|L**E^ZVeo;k zehV?fjl<SfOe*J484Hub*`k^Us<2D(8lxMsA_e1uZY6pf+4Ens`|M+^?y=+N#X{9s z>d=r;;m`g9^JF!wJw7K7=(jvHfsoYz6-Ln<>_s!nBWe2@*69j&L~<bQKjjEOea={8 zz&|#b7Kud}KOMPLA=-)wL_|5Z#rUL;Zx7(l`4X>;{*Y=@#ZncwcLY2x&01nMd~C|+ zumHnrEcWCyne^GEY{o-mG_yf;AZCHlugH69bfvcE136er0ng36rI{Q`mOmHAea#U< zC*Zh8fH23|(Z#PW-DN9g_9+z~x+swJ#4Kee_AW~wf~05?ivLfJe|XN+Q9ZTXGEpAX znsqf4P{Z_IRE-%*LTE<6)_b0W8*Tk%=EOfGi64}S^Yv5hsQNJf>VV2-xpPt_p+(%q zUoY?N4%Te{Q!=6Txr-`kN#XDXoP2*sy88<beyjl$UFn*jU!G+3ymvn)o+1N~%6(^p z?^D$no!_m?uLo$B<p1%x5(E5$pdzNF<y4Vnb8qx^^v#v`e3}2<FEgH}N4PmtXgLkf zePr`g5j`U<ZF*P6h&zO3Fb7j+=-j>Not7UhY30#!c%wcE7KWG#LYuuiUvu3H&uU1- z3jnQ*+EYAUf0a?YW(}o8Q#f%V-23q5r<~M~!!Yk2NI7RYG8px-8NP-CCv05~p|B1s z%V_qdGv_g1hjC3I>Kl8d6~4_k=*0CwR8gIK#k>^SWQSB-ThV+s%Y`C_EJ>qxjAO<d zpf)gU^D+t-1KFDixzN#^k_T-^FQin)Icx~dqZ+yz%)vFc0HHh6a*`R+iYilrb|O)< z&pQ&OQBu>G2&z;Zrl)A&g5bX<uY}TK0Zcb<APO{ZWZMgLH=sdwmQZ-HQGB>eU$hbe zs#uuj1C@<Zq}gxfY|MOjjpH4^gZ3(OeToex!c?3*SWHa!K)t>|?+vaXK2z1Jni-Bl zuQjm6S|Qyou9qQ%c|Vak-x8PrIUPKlCb6oNs#aK<0<~(d9g#hou%lNjb%GkF>r1>* z5W{vVlqtJR=H6gI4eiLWBhubR0o;qL8LB&zj}t670b@QvWA|T<M!p6ob>U;p;dE}u z|K0Etc4bq<ts}dykX?|AE~bFUKpSk%w9Z<%%ba9zCUXEMSGed|IqNz4aZQ5&tIf=~ zk#wL;L{<_YggBSS8pIF^PG9xjMo*YJ6HJ5-e7IDW0J{}0?U6=QG{lhfPO~ft&f$`0 zM6Cj^H&nPmy(Mx$MiV1CUML=ReVBXFt*H}CDM$+<FH@dRG%1LQq_#~SwA;XLMZ$k? zD|Tl=G>-(m3W38bus>(MK5cv(Z9u-lHIS>G$ufD_ot?Py+V#@<niQ5>yEXgVn#O)8 zQ5vpUid@VgPe|KE&HXOxh7#wZP?iI-IPQ8yNkLu^lSmuK?P+5%pF*C#)P=oUZu4J( zm!Fe$nqD1_z{qowvloKVKP^Htlm%YXCJ0POnl;cXI)Cxt+RGf$MpQyxJp$Jfy)zma z<noRH$TPxkug(!+o6DMbV<c36Wl0&`?Uy=jnC<G|#8f-*h1pu~VA)r569gt5^KaXU zNq%P;5e$s1UzwUzbMpvF*<yNc;4QjgEZ{ra)<JwW^|V)DJ_I%d;43!4tXzG_Xk=UA z<Z>wog>`L|XDQb#FXf~Uw%G-qRHq|7`oG0B5#FDhIPj_bc8PI}ecFN456z%s?2}lq zo1l@}+ikwobLZqL&nus+d012q|9)0sBCz=twiKq>hZ08uD+}rDR%ibuSIRFKwREZZ z>H|=gfF;VO^SKO8{*t~~-*;Pf&E_{Vqpoh&w`2s>@1pTqnyKW{j0+KBPwElwYC%+8 z``Uo54lo4BuCMV}37CyKL|gpEUB*KK+VhXvNv$?6fNce$a4{d3ilL2la8)Dq9sxe? zRN0-sXduO@`MKpyb)xQIG;nKH=BJ4Ekwoz_SP-%4N7j)2KMP>3B5Ge)CUySmM8268 zE^tf9DKra5I6G<ayfwPD0j>wP3$zehRpx!dBJ$|QNQCH>Bf;eS-|}GVKuzV`&E{?5 zaC2~c1BnmiWC*@(XHks$#Rd|eK>B=QFe?z?r31q}f=-Y`r0C%akU+{=cYcD#-Cp?+ z<%?kD#H0+i?EtCLiKPZ`Iujk0Km?wI?KvPt8PxyHasYF|t7#Jhs}Ss<PN$<a`D@_t zUF(P*3@s^To7%fYOlEMUV4{{H84jK+_6R8*ol2PA4_^>B0c%Jx!-D6^Fqx8<hZOjr zLvU<b4h!Q+T4a+E7Aq;yQjE=o+1u@MS5r!#9g&qXgT5Ay((_;AJ~JH|b8T<P;V^)% z*s7f-h<dsW(+ldgCZdI?y(d>%(lHcZlA{_5GZd%odV{E8?nt{In5Fe`Vj^Pn$8MNq zMONEXNrE0sOAcx`QaYnmr5vZKmb<wd)^qjPukEE-CGY}yvjT(ZTo$?r&fs)Pb6AhG zf&#t(#~VA24~CizjiEOVJ3Q>-dAlTt)lG%0)=Qnyi^@LvdhX34L16$_$&?qd8N=-z zvXOwjmf!+GH%^wq+pnf*qx6_%djpkaxi{Q>xuxOVY}XVf7G1X4C;9wcb+7XAjZZ4f zasBXxPBBXK)zaLZ^Zt~$=6q%Hot==$F6P3nfh2g!TZQ6Pu5`#Q{K4{y+q?D)+i@Cj zhyybXPys!<j%5&__HF3H^<m6~ak{hlg+q*Sv=yVT@#v5k@JMk7*$Ld~m<eZsEu7~$ z+Mc%A4qU6Y<tQ#jHwtCb?HZ`v>NqG8Ie7R?L1UYjfF56V$M?amld+wN4Y_2l$)cAx z<CEB_xj0A-`4|-mp2_$MO`Sk5-;_VcW!HH&+|7vecH>oH3=4B<C=_lBrUH`La$!Xz zGh(bmZ)&=8`2Tzi;KP&uZwG$2(O#O9cW9!{Of}ZpbY<Y|m-$_68?48&3>ASS06+Qq zB>J!GB3?UYxu*n<_OwGyWc`l`AvpEUA{~+`yqDvOtYADyq>1q5Yis0PwmDS&zz3@1 zxsY1ua>Hw+2Lv(Y%2KoAMp;)B&A!y&`gw&leAD0jWgCv62V7J1X|emj_7pgoU>Alx zh<CZ?{~WXU0A_*48*-8xa~{s&hvAp9Mf}SL;}Vol?qO)Lri^F$_u`osOVC)mj|@)k z;M^d20&_v8ulsU1C8_e^d8%)od_KQn!s8PS2^Uwqqa4ijHC!O2z!dX-e&PMyHwa6P z0xSM+)OLBFOC6YlzRoABaR|$Ur}=BE8j_z@#}GQ32yNTxbC+kzAg>6owdeWBc<9UB zNH*oR_eN-XGA3{$@<~+Y3Z`tA*s;Pbl91V{6W3s^o&hkKkSEgh*4EK^s@N06C(C~P zhV<`=7E?Blz?W@okth0v|1!#;4P{urGX9iJPc4r;u|n*<Q`r0){b61X^J;dtSoT&j zom)v%U9*b9W&yVaAsiJHl|VkI)<9CV!gZ43bUc4a5ryJ164ox02$rU5sKP#{s8M06 zlRci2Ddp@S@+XpASN0e#1Upl0x){KgIWnP$!E_dios&pA%a2?VUn73Q`UxlYFS6w{ zj3j}f7GX#sSpaH7Y}-e#0vPburmX}0mPvAk_NTB=jZCSW$0$g}iU`n(ELJiFF(M&e zW7<m<O?1Cq`{h|N<P`&#Lud>lEAf%T>R`htewuY!$TM@r$@IWMFX?*9W_`T~njZZ# zCJ%{s<Y|1eoS^oyGrUa77U8@xWSU2-qn2}E=-#U+LO3%xRg?arU01{6f&)ms>v_QP z2BTaDMzby~55vO3c9Pt1k|`BTNA}}A&i?XpW4Put#3uH??d7l>Hfg%`T2lKD%e=kT z@Q#nPulQ5K<jAU?Ic_4E$=X5`@<F!s0^yxHm2+{45{woA;^fo3|4VxANo<JibmAQQ zyRA>^A|}*9e0VGS(7%S6iol;p8T(_1se&lJd89PH=Nh=4`;j#x{8m4Lt7%pOT6Df3 zG)+iY>HEw`KhV0yN_e(Fznpe5NYgisIq54+$Ql_xE*%w~LYZ=r7TRm-_>ni{&Qg@J zp*DriY<wtaqVq^aRZ0U;S7mJ$!-LH%u!Z78FxX@_`|Of6uALS^7C~5_lH{{<OdPW4 z<Am*^j$t`=V=OK4+ak|uma~C*wa^%q3q(c0y3v@{;R`7(q$!nHYT%4feh-)0(G%{n zT&_;kea-9Gkv;ixhL4=CIgv|48z12-1<?c<1UkjJcs7F#S}#Z;g53!!g=@lih5;#L zkde)RjHKx-vZIY{6ZWVa(&FOwL4xPbN6Ot(t;yoW!s1N?-sJF&_W08tX)OHc#lkB7 zCP!m=>&ec!J?K@5<FD7W=KS;`Z{odSTh9;Sj&f$%O%*gNnQ4_j7rSk#<AIdb+2SWE z=KFGn3nI%;RzA$hk{)VJ=J%`52Yw7q0c5NmS9T<4Xh<na%qQ1Mh@2o1l?_F<qegmz zWlJT}NZjH^%<L!^sqSW|TF)4IJ)my11j>5uhCdvS6LzQoG^X8*o)7K*yn$wOn}1jl z%gtW@e8j1uBQG-~JgtbbgXP8A;vaof^RE7bl2wpR(*!9pySgQ{TwAV#L#)4(hL6-v z;e-82C9%$lx}sF!e@P|{ua6ORE;Qp?iWYAusmz*bR=Cw&Aabydi8-m#S0C(tW06%o zR<;04I@raOTd+t;U56?C{*(+vMki$9Tiq;DdT-?bR3WiLfj<Nwv>rz9Ui<?kVjVyL z>$p3`$OaGIKbQh>&Q%1L)(S~kbIkNDMBk=MS(lD-vbnK^hQ1p@=8%R6`)tClsae$7 z_!Am@L<u5!pNSt$liF#GEXLKisk*R}PEQb*i!-FuaP(pj4}{D&-eM8YB&R{RtROw7 zxB$x=LuR&~FE-UP(CHb<qT@yIDC`ftk@Hp<pIWQbeZ9&GQB5w3fw;zRp++dT%Ffwp zXma!*o}`GJiF8FOBwFKbdU4MbTa|f4tUY?=*6%%oFfKuSP*zv%16!RfETU$USh8@m z4#O_X;ZuMJn2GT<Mn_O(ie!~yR6o~H>MQ(JF#SgCF=FB~WXe!Ve`^#zyT~3|a7`{6 z;HWtjIjg<Ipo#YmW=P^AYD?~UmotCa%uokJb)>jeyf4ngeaU7HV4?#T2s)SRiwRCU z7(<URvBk)ENs2;yaVs0|cc>MXN!rRc#c9schPqB7O@07xZYa!`7!Jav&QK<IRp~^G z^(VM;|Nkq1Hu^J%_#+c1kAN5~PJyB#7GpE14AtYb0xii~_Y4E2Ic9@YNYRGV*doKd zQ3{B$<1k<``3J5Q-`Lx>;Wdv2nmM=(kyAy^K<povfpjZ!lChyUGvzw>Q)zIL;2m%J z|5tBkQO|R+Z>^cL)JIkSvZY~v_938SVzKzZE$`kEVPw)0<K<{_1=#=pXgc?}rt9|q zquH%yMIO?-Lf0MB;R)`rR18_(Svb_@88wwkjL1qw2&TACx7KZ@vKT0#xtW4^Hcu&t zE=`*QbqOkJDk>*A$YC7EwvWH(o4&t)vIpY!`MeL;;dQ;P*Y(sd9UueI1^Lpu!c0{^ z*Xg6LG-9kYy0BqVdyb*)QI9pebS9-w-k-2c*y?i-mNGm3$9(2Ho&@nLKR;HObB-KC zJXhe<?nj-}t2d9K)F$d@AGxZu{yW1){n;1B{>#E|hKhm!747jWnYSWpVjTe7=h$68 z`593}g5S;+rjz|He!<-+Tt=5WgAMY*?<$*~Ueh*M96tUs@atd1GzbJd2(Ko-FF)fI zl^%)+h^WNH6A<8a^Mf#EXUBaEgft`!P|0h!DqRcqnf&MEHJm*SjXAq0;wL8834X>k z)1pAkXksdov;a`#d&Ih8GRFTIm8@lV7QH)g;?$`hul{}!%9u}~Pdn%5N5x_1Z~8s% z-)BZD)1Kg8ESmY7-;VDiZ~Cq9L(O_RN|(4;uTb<kU-Tk4O$XQJ2`jhF?(uG)8D7j> zJ4R;qcR7C6Q-hoGR=w>lkVv&F8VG(<cxP>+E9dc<0XCnd^tNAOifHE2!$qs=TeNrP z1K11VU)9@nUr4k=2y>lR{boeUxqpl3Zr;ZI%%f53=8rt2N_(IH6gosSg=OFZCfu$_ z$6$-4l8?3#Dy*&bO{xOG2TwZ2*}Jh=%tDS*xZ(~xa0aj6BYy7)XJzKH0b0@bRGq20 zJ!WpAf=ieE1H~n|k(nb`48C*@iu;Dvyg?o{tqY}ZR1rime{-DArtnUYOj&>8_1P42 zRi(HT6Mf=d^_Gw96h9-C9j*lQ=<#Mh(NBFa6(XcaYUfYreYPvu%iTg?HuM3qtdqof zW5OS7&vcqH9Gp%PZ9h{O4t)gZpm@H@ZIG(PWAZzqAV6W@RAzChxKCKAgGiZ&$D(AY z9dT&~G@$<7p|CM2liW2nl=7iY1j8Mp8hK^f!4M~v`g`?6Vsy;h@4=|RT)Icg?_84@ zTx?p%B@r8%iPJqqNe7d@Z--7y(_1H8EunZtrdNmT5}!|~_cZ|b6E8fBM8HQ<PjR?_ zj@cPYCcfQMm=fQVHbHD-wrEGHOb1PYxtw5Itl}=RR9Jy@38qcEF5O##<RZ?lyE;kK zr*@aDi1QjoT1kHxx1eNu=dd+mx+ux&_Ri}DSBgcVf_a|!OFN=;C*x^qzo+9(*Pq;T z*EG2Q8bf>3q#bx~7<|KD6N4r~&#YT{{%JhT&Yg*=efbk~or<d<q6liEh{%bv1Uk=K z)A@EI^zE)Z2o`4IREh{*BO&d^PM!HNLR5N(h#&^O-;|epQ{T?aj)g|^xVLeGhI?dD zWolezE=CK~`QUe?j>53^>65oAP~+FBl55`U8)4BzZrJ^uKl{C;jP;}nsV@QFzdgIx z#?(B0d*|N~tdpqIm33TW(>x=f0v4tNm(ZoQN9rRy$FlyM{QD|)JxuE0IHx}S$MjNa z@J)-zQpGR4!7TW^!4A#1QQefuf-;QS69#ThsCcl|-$Kl&?6vl1Kd%*{U`9%i{HPO0 zka-ToNfXi9!eJ1+_-yag@sH{TeD6g#o6;&|rj25dY=F2Qap9d{VFT^aE1a>lSLnNB z<h1$$<T;=J-j|HOY}?b+54bsk^7!-!a`3)8_Rv8E$~Z7XTrk#sH#TGSdT;sQKA>5l z-?z8)=H~C$U)u9&_V{U(Uj|EpQX2m5*CS^%T#KE-vD3v`cM$H(A;}Ee*ZV`>s(&9* z+soWFg_p+WM}h474Z7ciPC$?!qC`7(Fc~v;`Y6%Y-JSR+lf))<f0rbAQ7=#<P%X4c zWB4lH;_}b=v`O8SnLBo5eu%_N&fN8$MH39=(>qTf@W>HOVZ)hWI!z~%`CpU=T@Of) z7mM&`KLitfL~XS_F|TRKw+-^cItqfGH{`On`(NJQOGj2D>rgz&HRfCnZ#DIV`vZ$0 zJ3pcs9y$Z%+wB3D4jL9DX@Uo11%?aW3<509=f86y47+0jS)eLSK6pGg$YtZ=Z<bE& zCnls|>L~a%acG%!6|4~(xk1#xP7Cu8s{kLN{3O6UQ|doctm?G>BkZ^=Hyzw|-tg_- z(5pQob`SWjl;8!?*SPS`qxoE{D!pGQR_JRtHqGu1Yh#fz^-NTnmgHZz>D3W!RXQRz zid674Z(Ri*_DZ?bL3s3(q8n-C8`Yc(;4@M&>Vn$9jMb8V0?iAic~nc3`cK+7BD)&m z7ThsgXu~zkhLLbp4kCHJSUEV+5&$3<I_>kH{X|+p;3G5)t>OsMpK?R<UK`D}9i4eZ zC?X&Bnnu;xa}}VHsv>hO!@OvF(+tM$P^=M?j+(rz9o_`0*Zs`xUET7$xCP|#`>?7l zGYI2ElNvZ{RjyGg&V!yJMkGOr0}Esb6XTuU?m6QKZka%b8ahu~34EgwVoewa>b|L7 z7w=_-t^N)};YDZnQ8YdWiWNX2gtom>4*kAeqB@7=>MEozlw48Wq>YsgHmFI@I%MhI z)Y7Y>LS99NO`E(cHBWNIlAk8~`7Huj@dX>Qz76P;Gn=iPgW2bN>i#pO)0wq<-V%Ie zp^7I;Xp0o>L^sTIeHV8_=k%5-<N61PjN6xlvoE=39<a>SfnDwp4((h;{c<X51tFkt z!Nj-fcCNaiV8$}rnX&SGDxcjHB&$k_O=MnCb$<O<3s3=5(=JMwQT+qQNcB@GNq_uh zA3Kx(8i$0D5h8^W2})rJ%n;6qSa<G}$=1w3!-!T2J^(DcVs+>Q?R~J69r_-H0Vi;6 zKNSA&&7hr!`}FjAz~d)gJyG1PWswB1+aMfO=Mta`Xm=<b2j_Ku0QOp)34L3HvBN^v z?&|Q8=pfhm`K{_{6GEY(bV!Ez-6EpvtfN@Kspk_#MI_vZv*kMZhzSeu2~(#`KKC8c zf5r^tLkIS}ibs9qxp!VP)}*^Gwj`P&oW(Pj{&LKyAsEZt(_>xB_e5gX3n6~5UjHHo zV5gijwS3Ct?>eem2Q%R4joFvl2d3<!9qa$g-U;&L=Jb)TC51(lpodNsphwq+YfHp~ zgr-fK!jy1l^dxx<i@In|r!zbDBwGA8rhb2N$!?L7Y0C<gNk8uIGu0>V#;3*4#ywvC z&Z+C$j~Qyv^V87jpBa-hCKC}4GXbKQCh+f}*DQ@!!X&a0rC||CP4ZQ(LtUMfHf>cJ z-C{&fB#t>=tIg9r|C1OWOCgR9l6{Js@ebghXtkKHG%xkw)82vK-$3g&e3s`gT5<@7 z<R7QMT7Tt0uxW1ei3L$;lqvV*)b{=4{r1GT<H!Og9iX?S<%=Run=#Aqpq6xE_#3x4 zst1#=&l~3QX&!)t;rwv-Q0)s&W2k4Vy0!$xo3`-V*XW#@iyEk9QsR-C<wUHphux#E zm#(>F99<~V+LE^E`#$IWy0I8p?Rnvfp`-KG=N}~A=p!GX^Sy{mb})5Zy%bK!q8oe2 z^TaE2X<6FBZ<4~A>b@xs9#t&RBMJfYXQVtB?he#D+DV0~&FS+k|8>8jTDx$YYMV-s z=P0jKu6X|SvXPG$3c!fK#NBw{&<mkYy!sqU7Zc+>?fZNN0Oc2op*H*UgADogr4)BZ z^OCcYJ@!Ud-gExC87#5VQN8%wFS_<rISRI7kos{}`s|~&GP_DHJZON;;plaek{EZp z>B>)Lzx@eWPC+rVjz{{R{z2bf9R(J_&gn@}ck|xg#*9h1;<-D{huS^@Ib(ic8ZV&* zr)MVf3<>#L?84Nh0vAHm5(OJ>t6=*V(iA)lr`BJg0@j-B$JpLY5&0=~q!Hxrmqfcj zI+GW%8@%Ljig$231ccg2J`#kCAiPyh_7u_ghbEZ#N9r5;+KgK>m%b$Kq<DOeeEj&O zxU?(lzgD;Bsdi`u8Q|C>N5-Dc>THsJF?R;sVUO>c);?YxO5B8zpYL{`NDA{xuA*CL zF6?v?Be?&Vj67d6y-a`!rSN=4Pz$BR(-@rBF(z<xtUaItHYUAYXPEPmg76$pPOvao z2ytaQQ}CI_t(LXTsWjtF?eODXzH0@e{XPQY?-xu(ogBJk#w}Irkf2vPyi@97&dWWW z@jd7WvPT2pxrr|2JT%Hf>uAwZqvd)FnKLT8uJ_G|%=$TqWCl<>2MquECD&#2$I53I z$Au=V(%ybH0~~9#GRw0WJtsb%m}Zme7Kd{DSC*zLt3MYk^3CQ_k=0yHUA1`vUDqNx zY21D9;Hu49nM}V+>N6K&cZw3)zMi*p!Co$9FxH`Dd!!mMf{Ya@HD>_c%r$|`X%?__ zO93`D?#s9405+#;7As*lZSN*b{*0AX=QkhGNsa=cBtZLO_Mbyv1W(D_V>yzQBG1Nq z=&R1Jm|5Ize@*LZeLD}d1ZgbY2NCs2pDl=RC)|~a(U^LsDx&GRoRn65RQozV?)s_? z^EqTo&{6w}+o;=BELb)LVM*$ztEW5l3sP38Jj+*y&AVFrkKr$##w08_-oGf>ld=jT z82SUJce#f)yqD=?TCjePB;`Ys-&>d+yuWmCbAh$K;(Q?1XGgK%V~qouIJd81e1lx~ z?in%sr~k|Gex>))=S%J(mOj#-eXGPyYwA-j42VegtdHZp?PC%zK0hLV$LQ))h6k#3 zk&Wty9|W@;0>GIw{V%t71Es(xULQJ2pjN=J39RjEy1HOJ%#?r&y^v~ADuj_RFE-Gu zJ>9oW^$<+{CYM4g$+Ew2G`O*?3SGgrY5IR9jV?8I^Tpz%SZDdR^>{c3M_}zrURIGo zC)~dm-)sz^IyiV!RkHi325<Arnt=wh%Kb}{gf3*|tWuBZ%}2%g#)mg>v;;e&wCVlw zbhJ%BGM-*2_j&%fQl1z8m0HYs)nJiI;(Vk|anbyr;UrZKpR2X+rkC|``ih>6>dX~) zq@%T&NG-HbKtZywwaP6W&26x`E{BP((_JKYEqRHLy!ms^#07<MuD9%68m$8|<(-}= zbJw)+`<|^zj%&)Sq_LPJdw%AXkay1IQduPe4#&Fu9&~$L@DJL3+OF_1m~10&$g;V{ z&V|^x;;3jq4J{2VAL##aw)UwGj66Q#ZB2dGcLjj7?ijU7fWsJADfYSAy5LjU6&+0J zn52(l%x{rm#x+GsotpeYu68lRDH~vD1WpiT;^LfF+k78bm;_@<3Q|{E?qpu_pYv77 zaz~{+-ZXzz55-x@`>g6#MWb7c#26Sou0G=TCti2V@~Jx4CeB^>;KryFx?D(0M_|dO z))>#Eq&#^3+h<KtEuW{H6(!VMdV~3%g5zxw4|I<s4X%-)t69z)p<M)WRaF)Ad#ZEs zqF07i`N{p--oN1;P%|KrXcnCd&CoFQH}cCl%!vE*0I9}ieWGL)nRvzX(@V2`ciN0+ z2-Uw`{9xY)bA}IZx~X)ib*_`@1XL}i6Cy8uVD=uTG&c+^*eM)Ug(!afH73ZKmzdTv zCpbsBI;{O((QoYmwYB&EJdj9f&dlhku|N<9th*}DM5K9Ax~7x&t}al&{sgl~MImWv zX-JUqnUss-JXCI5wQ<naXylr&eh4-W9c`FIrZ<oCdENEO?240)$8Y?IOmFj2ogz2$ zard&2A+BNM3{>{=$M_aTne!dKXbfXZnVr-U+me&!K6W+gm`MW;*yAPI=okfI_P7rW zZhFi4s^L<7Gm?(Q=vEsA*|V_X`5B3!9)mi)MS87c>G3`cHqiTA%W4chg+xAZP{2iO zcJ<@@h-a%Ka*bpAwg>TSwl15ElBhDc<_B8Oo%uI}r?G?D5pyJt-e7irnY6Sl#6RU+ z&hgv<iJSXP#d(f(TZ~yLzqQv$jnCzXNzQ2zpG)U@JgjtE+Oo0$ld|qO2@J<Y*Vp|K z9+A7|_o6~4#80s7mFl_*V)`I!{!=9{g$!sDoO|7l;&D`bUNw$MkzX{g6HC@>jys!h zdDSNMS&NUgJXHPdaX(bj0`d(}aPyZZ(NzKlQg!#xS?zZtV1_-|_lOY`tM>A9W$a4r z>oL~s2I3s^3s!aVpsi|v%wTtpQT?s#XOse5eK`-hGN)16cj$Ozn|H~N?zWOYqs*|2 zI@lOAlX>52v<A-CNjHy#GN59AvR{koqx{|vAB8;Iws{rcx_LS5!)emF<c47wW&}v& zGv`uTmb87VG9L{)yc*Ul-S5OCSM^YUOFTa&t`g<C9XDlJP3gO?HCl|hZZR!v_1<84 z5Z0D<k>IL`Tf5n8aiz|6``kE~u~E(8l!iXO_{3{bMBm$Yb*4odxI5LOt}b>BOZYwC z<KFzb4R4513i#AotLTftUVmd}Qukn21f$z7mWuh(vs3QRf8s@gH0eO1eFQJ)p!?1> zNPR2n!V4P3?dG=>0r^aOx<m40ZYkJ5&NZy+UPM~_fw@);qWil?6{~Em-s=zOyUx?~ zw1s3Y7U<o}8eIK@aarj;%d209=A5s6?aXOIOGJ+6&hqLThbaN7m!Ye<ZJ2a)W^PQV z(lih?ezFE@Sz(3ZWa47Q*=YZRxy1ZSoYCY0h535|&U8P!P|52?2eV3cZjLA!uL9RN zdivY_MxAL`QV>ogTv6+`G|ESI&rj@K-`Z|(oA@f^V4CO4r(X6iDGRm5M|6w5$z74F zG~!IQR&KU*Z@MW6XA{|Wp&xMA-M>EZ1)gb`QAb^%6%yD{+|8`Xt-nY7W3F?V?csdB zj?v}qR%7z4kd-M92BiekKWs<VkNJmCBXOy*A84B$T5i{2ReJwb-l}gBJ9TY8{TZg~ zab~0~GjS{xnD}6@J~9L2SjcoFF*v?C{W~rEJ+f`lgGb_Bf`8DNtKkZUEjsl3{2rG8 zg?OI)#^CnW^kMn|XUU;cYDFJ=<CX16(*ORX7hyo6iSmXmqypFy<lNp!I61_*cHxD8 z)hoVzEa`#=L@u+qn~bN2hF$;sjYH4aGR}5c8mgpN$7z?3<h*iV;e$G}qP+{+n=JD_ zLkDETh|*bX=b-v$6^-3HjMz^gh;Gs1Wm<app}KzUr)MPh8s7xu*Y)#Bm%3d^Q942g zq<4WEsJ>qGtEMEt>#Vx=jR16LnQT<%vAfqzwKnwrE%~e>`N1RMm3!Wm%y$c}MXj^` zT>0<NvDTZz6HgW*Gtw?Vv`t?YO)g0MPHC7d8q3`V#&@h*8LRkbZh#1;&IN!vP{^a- zk~{q9c-w;q)wAy>dG|Q0@cbJhaKRX_27Aq4I=7_>aucK;Me?kY!pP&RgL+RE)Yfo8 z(1<S&KXTihSh&!fpK`9{Fw%zi-jgHE<mhdmE}j6F<D2`OH~^kgNt=I;y6O0Fc+_E| zI^bP~8vOc|m;?s0%6#|`!$Dh_b->nDl;E$Z16ZTNux5K(boB5qb1iM}?oYHhqg51w zOFX-4DM9N8945;LXQ(X{<<Qsa4wp8xEx*vyRw{i$xkBdLhL&?^ny+YG&gs&*;|-C^ zb&iA;qBt!2N2wR)Xv&KAO25w_9!&qo`h`9Y2?5D6Zq{+>yTojktZ+N8h|H7gGDUPk zOl-KNdDAk(;HV$R)t|VKwje5PhZs_iT8@gOV4mB;YRsMLey-sss9y=6AtoMd`k2Y3 zjYD&DJO>kJ1}}H^9T}3ijOK<%hL((m*tDtk^0`(>P!nXtj?p}*LT$M9)VJxj(0Xrc zL8!|7pi)%9<wKHZ`4g|#uc94!x1p~#1uMgqllE=IK*jZzuPyjD3TqF$DG@N$M=*=e zs4qA(!fbam;{nRDsQD57F*nbCa`DYQiki%lQ+0Q3(NAZ@=<5=t+!V-pH?|$BS=aDP zJHLOm=0g(;k!zOZ+cW2=KefL?h3G~G^8(<@Vn>R_<@jRAH|7DkOH}DkD3COn`S>~V zLGG_5)|nP_V8p)To^|eMg*$f~H+dfi(cB(*Xq>Be+wYGHooOvcZ&K_YO>=`R>&QD! z9%_pi@KzFM;o;AmB0>GDOpACW_ak+BdBSE_D<>j|8ELH(-v^4%j#yrh*3!Qy677nH z=Qb>(pt72crVXL#(3rNf^`A(qZ*NZNlD2fdmC~Rqy97X3DY;p`ySVI0jSXx5=%;Ax ze+HIDaJH&(=(Yycx;KY^JmFq@?MgwK3CHM;+5Oj+$KOv~RyB3C_Be%ErlM_#eB$+e zO!r_L0CS}|{m5QbJ00Vd+?&#UdVf%?Pl(y&Bi_xMKGX#}5}W^Q^Y*N|V?vJGQQA1v zY*Gi**?d-3NByRcxSe5QXrzEW$<z035AO#2VDC#E;h2Fm*Q8Hml+}oU4P1+Y?!wfn zix1r>Zd=sNQf4~sqjD85EOwXfd8K9ga|-u{JfoC2Tg1T!HKvH7!SQapEuifa^*=R> z%U2osU^d_PYS$V|Nq2SGw};rR;8Js|)b4MYM^Kiq^Oj=WpXR!dpGGjK4VKW6*`7a` za`dyq^Tq@6^&z?;EpN1!DazG;zMfR~N5ROT+!Vqnc1<aXMD$ffP1ZwOMH1h0G*ZZ< zRnQXiD95w#iP!(88uZcw<!o!~!o!%mO$vA5qyZBzJn`xtbo0I9wg!be=8$pzy7ude zavqu6v&hni$+JG~GpPDB2A?-+<xx{_%a_g!gXd&tejfFE;cH6b+U<&(^@}@~tNY}a zfBr}75k6^$bgOfB-z6h1d>N_!<JW;w%W>_|A69*4Xw*lQ*0Ge|tElDIghWAjH0gXd zc65-@bu%fY<%5Q(I(6wQ%48cINAL=`2}RX`vURhsqG38+X}Tv~|51#R$5UZ=<)%%s zIavFe_2?&Ovs4VJotfwAdSf@Y(m9iBnf1^<qOQ`?D)Zpur6X&<56FNz8iu&@yp+2h zOh;>f{eGKEaobjAXbU^|Z1jN38za5tYkM+0$&VwQc!|N;y`FfjIxtFl9A@~$+MFX@ z(ud!aZ6O2Eq3Ypb5>{n~Lu$y`)3s)6Nq1k9Mp>B15sG(ZLuwR5g$`Y}v_-C*lFY{s z8mQj5|Ai-BHO-$Dw`dC<oJo4noRz9v*=5PcTh+sx=cUvH9GEIEx#TvjX_?Xx34Ot{ zjha3qA>1~<lon0Hc*#*5#%*@!#95hjP#w8`@L%eB<7I{G*KX>T6&smX{oL!tmqL{I zsWUhBN-ZnQQ6XoW_o^>D&70Kqww#&)kq8(afgvwkgj9?I-+@g1#kreu8$6cz1-VS4 zb@wDnEXKS=><-jhx4iXh=yyxJYg_b=8>4o;>+<<D`DpKlul$y^A$0M}iDyzz|MdTt zd!4#wYlpPQH~;%XeV2CV*R;f-ug&`WiPw>P2l^M)zUik#S~R+>s47E!<oR{|PZ0rk ze~ti9=lpO(;=SX~st=!8yTm8jV@Y_Z&Mu$(N85p*fj2{rhdM1I9N%kit(>b-*st&Z zP()VpkqL$JikWQCqUYvTRgHf9=Hiz`2&Lo9^w;l`et)$s&TSttGk0l2&FjwBYutOD zc-33wz5%C?PoBrQo-ZP9y<AZ_JwN2U=gTz7?l$Bd7}cV&kok|8yP8solW2v;+c=l9 zYSvK_uHO6R;A+#AFKARECjkgQbY1C5%2l;Y?XqRp{znmsKV85Cmu!;cmqwjaH}$$9 z)tyA7H(a^4IcKchrc*CEWx?2;ukr?d(v;5FtUfZ?(`1y+SB=8H#OMY@Fr51OBZ+(3 z<*%&Tx;GCv@1D_=NS>@|hicZ}|Cy54mLkq9cYNbDNB&`HUWQ(4bt&&!gO}M3@`Rt) z2%VzOW*XWe2m6{^<$ta22Bc-?IPTii4p#c?`uoxd>GqpHfz_Rt++P|aZoTqb<LAXA zfB7ob)1-EPnRe8?FyP=c^-$@7QPP!b9?o{dU?lG9NIk0OT3h~8@TITC(R{1aEN_{s zf6NFp{WkNherG3dxLYj^ty5GEE`oTx-ZiN0&7LFgEbduTS#}2^am}VfM?Y%59U{fM zdpCCWzWE1g)YWIAs5!1mxrh%0G0M{3+~qwYKV`lV>zb8Z9vZQ$K(?Lf!P9>*^03Nw zbnDNBa$DA4a^3>(6P57?8Hjh9!*gWTg1nF0J!<tSxw~_%qGllhv*)u3#UNa1bg4MZ z>Y61V^`{E`-Ir%b9jwu!Im}WXUU|oS#QfikFV(-|Tt0d0p`{=r;#S0OKm5^i=e1{4 zcZ$E#YYX<>yclx&`81c|(t5?sCte!kgi`ZdbEKY|nJoJK+oQ{8v}e_9+`-`LfV%A{ zCK8<cYkCu1hgY6(2NwSq%<D5>x!AN5(;Ly2xUpaRz<X2bv`rOHyj~u=VQuqGr^i~} z&;7dmZI|9>2g>`D+<6~)o}~7SxFt(Brgp87GMpg5$5#>4Qn2!of*GvjnXlh2{XWvI zcC?JSI{}<+y40{|p~tN6|G|+@{*f13yoVEh;c88!`k=qPR{iftkD+O(B2d#jbdTC1 z*xrw`(xzzHqtCqkrN=`bG5QO>&}~w~!n5_>54M!6{nc+4=8><hD?aKnOPPLciuzv+ zszs+Ze16NbTWZT$aCvP}zo=HlkJI!QbF_6z*ZfwwP%xb^n48@JJ`G&VFE{$q%U!}$ zGTqRoJnb4w_XD?k%;~Mw2GstiJzf5w^3TMfZSRz&{`ZXyqi?xR6K4N9wPshq0jrau zVw`Ju+kzg4M%Z&q5C<Bq{T20>&UhzL*trG-3$4N)k@;M`^?vEbfhX67-c?<Bv}J8E zzVQ*IgSYNq&Ir`)`T0ResO}K1;?Jtn-`Lu(Nt;+}i#xFO8=~02Zup8_%WUyXdaNnF z@0$2XnWAa*Wg&bY7tj!dL>1!;A62-0)lXq5Rkz+ypK^?BsdQeSX!mwMopfXN!JU6@ z?k2bA)_vpoY}JOm_B+xh^G`AQD|+un)#|spll;kbk7I(@kqW0Ls=DYCm%<6M2QiAg z<2w4?mVR4*;_I#RySEZ;d|~)??`73*Jw8}fbH?XZzGr8Q^xK)lf|lt+tNZV;+vli1 z!BkqirVZHGKi5RVVN$y!2LU>dO<0hiOd2~<qm;V?G0qWSxvN~;Q*VF4Y8mqikVHl! ze&OS`k`}30*||uQB7fkNqFAY?ZiOEG!INuAHk%9G-t~!Cu8SkPVW985m&`G1E|}oX zJF&1{{rj|WDz^q`2RYW{V5+iVt{cS<!)q8%Gw9;01v?WIr0@m`NgWZlK0UtSo%=8D z)ur65oJ#3t)yO51$7DY8!^(K~{x(VOWB;b)L{iWjcSovUqm$UbTgm=gAw3d48$I0D z@cRu5<$dG0Xdfeo+>XXs(Oq->$ur&NPVik5R+xKImW+QUZknb|Dt@Y0(Iwe>#5G7N zIxXg&7w>7A_PEVZ-HXApn#J|&&&E#~r`$4mf1_1tu13I3)6u1io!O)`Ka;5F(v$nq zt!1kZt@oN&lfqn|Xm7uBza~bN_H$@32#KR+;ckD+XNGV3o{4f##1PU|{uOaI%llWD zA?mf$xlg=O+x8ayrtb%(>$y>3<JYuCJ3^I;X8R)T;`?Kt@jh-Hl(G<4)T%t3#CtYN z<zw1q@7wtg<_YohUg^U~37pZ<ttjK;|5EL3pV_}{`PK5MeOOP}iVm6Q8?Ju*Q*6wH zu^E<B=krAm4t}e+>AU9LHFUiwzxwsxp@hR~{|OvTL4q~ce?5Dy)u;Z`J*spt%^v?O zWrv63q?pNfAfn}beb?JNSC8%C89?sCxYr}v_KKP62Zw{b`!|_B`4;jgOr_C605(MX zdgBavdfBPE&Nnsc<mjDqZSmCQ`g-3}qlx_TlCKvUz5U0ItWpnGUkhF6T1(x=v)mwZ zu>FVjDq618uT3tOK0(o^@%N6I<n0x6UYGAIc*QJ#I31}aMC^O1&2l>aC+tw9Yt!Q) z(%{AmhrYSj-Yxj_%Q|1SU-!c*GJOK#Dvi7M*z^6!Y!*gniGtF7HmjF2VZjuE0V~VG zRVL(kPQ?E6aj8-5tyPiV*CdJ0hAnve_Aql*Q#u_X?qh4@oM|okk6SiLsrBHO?^GDO z-Ivdup|YHxVlRy3@YEHji6+V>eeY`rJ~Vb~+P3hbr?}Slm@%PH-V%PGSpQf1q~*4! zcdZ|IM=-&c!OU~^V&xI51gv81Z;v#Fs*|bd63)W7;O+jX(gmMumQovR!9Did73u%j zxYwC{R+Z)h=vWwbBJRGT*Ib)&^OljB0s+b&Jv_v-Vwm~Y+^waKrb8phHp0105;CV@ zdsL72Q~)aMqIgNKrZWl~GA1Z|*}bfV-yLpS_%K_oi)Ze#Mr?O{tGdOERPpe{t|f#2 zMeehrJpryM(59NO<1eD7`J{rso_3R8{)g@oPJ+64Z(78!|2sfD-I~?~FC6N5D4E+U zwVTK0wYvT()$enM`}`0(Xd@bhZj1jYN`vl!4H0STw4djPDjm9&Vq!#q+cxl1yX&Kb zwHH(J3m1}8p?x>g-?F%_mn^?Ec_b$*p7vbA7KBwvggNrz?_aGAxcAk+%=axDu*SuY zraNQkQ++Jvi#rBtRA&|aY(9#H;lu)jAwGhtx!BOhwpfw=(PGgOWea9TSeAeb<f*F1 z^B<-|6`;AREQ8cCXZV0Jx$&1rAzj)IYE+GH+!FnIoH)5QBjtX;dZ?9^hxt7a-4cFW zy=|e^HM=b*h-MI9q08Yq!RMIUEpP>sw6~XESWaqiwhIj{wI#&_%z3j6OOIV98i;!0 z^%5EQYHzeq9mN>I+p${L*tRp8R~>SG7q+!fGZZxMf5wIr?Kb6MQQ9@>1(NIDp}jry zj{@v~qOXN}8V)H~q~aBbG=JLKV^VdgXPbL!Fjjc8x~V{;a#T9>cKxfy8wpC+FjFF% zM31<Nn?1%{QnAr;)pyPG)nam!&EKLsqjs+?yVleFWkae#m97JDaUV5y$*gUCevT=< zYfURyM5F2?qc5Bfd_a7^*83et*6CDXB>cdhb&Nr(V>cRd8Xn32PC(*#jXdaAOH*O~ zv6Kp!M6u9F6X!N$(CPKrJ?f-MW4<yhb6jjuv_+ksHCjpi<@yHRd%xk*8jjg?m1kS? zV5Mn7^CO{lF2=}OecMiu@x~82pmsk$T3+#S;^c;BxjQW>NYyrS>;Ws%PTdKLT*-nQ z-LRar^$TR>v^gF#&h3+by4Q)3ukw-HF<M2!PU^@-Q7Q5k^e+Y*6H3kl*?pVQ7<}0@ z4+yb>?<-IYtz9`u0IEMF<K2Ge;v%)jiYJpytt^N#v~Fo_M<cNT#U^&U;U)LvhjS_n zmjI$WVuLBxhvXIyHNF<}C7>}{^wja=PZwk>mKWFPyHrk_K(KudTUP~|+;HP3g;%0l zsjxJFHPZ1zEx!C#aOgpM9Cfj3PXwq233{4l@&3=IXv)V)!MNBJE4upDu9}#szZ}vN zI;Y%gPVjf7hWs_H%l_a=TjTWJx3-?mS(4sj=|z9Li}69)fJpIb?}givt6xq_E?;#< zP}%3A?<xG{)d88()5QoKi#`?BK;AMdad*%nxAjJh{_=pQa}2Em1{w=+Jf$R3!ge*d zpKkl2OFR&8AEP&)Gann>fgp<ADxF=MVH$nkq;unW{Xu#Jn`ybthf1GIYG0x%Hhx{2 z)~JZQ>3*qg&f?%+a}(C$oap4~2mD7SCgA>@wut&28gSl;E+?$#WV^tf#8n9AZ>vl8 z3?Ic1O_=Z6TA{*ioXBn%rN1=r^Rz>r5542+Tl^sYw`^aB>iU7i^@jr00UVMDZtl>q zqTi&WhT0nc=Akc%-uBld(PYadtbVAyr|C@L*I6-ecGCEid@QvN$&BD^=I`WYMfw=B zTYG(KIXW!mEGgZ}iI&$Ulx}3eY365dNJl@HPMxwGOIA)OA<b&Ax)t@$v;_u<3L(xG z!F_x+*AH1Jq4g7wO&#nwKP~HWi}~KFy6A_BTS&By9;UT5mXG$8-1>cY6H;2fpvp0M z$UV)gQb7JnZMJ+N@fGDVF)wu=)OxFECo6UzP1;Fs0Hw|8g@?`8iyGCruDm51BaX&x zJh^Ru$-7UyrcC<kiX3Hc4SA>Wx}hyX>U3bX^W_k7n{<PvRW0DDU7PABL1C^)N5YlI zd>jkwUY^}SqqX8p1(rKGdBFu~gv*{Cr?~yW{cn~zdnLSEd!LY69@{EAOw!_rZ*CkN zH_-CUE;wDL#N^N?Ubl+Q^<+YZ`IK3_x_%z)!beOZiZqD3P?i}oTN=C|Z*1|sRaAKw zCJu#EFf~StQlZpP>4P@*uUTI&bW|A5Dk@3Dz^NTf>uvjNbg3(xQYo|V=usqTt<vy# zBU&3U(b^Gh$~|S@dCci8xrj#gTT`+{S5p76ZXKk+$Y@!*etqSkze@h&@O1<aKvU*u zt7$=ATUx%Eu)utZmL4JS`a_kDrVs^n24d3mnTu|k7d~&jIjZ=?@l(?7`fvAPRQ7Xm z-;>gZj@15joBNYrZ`wlMMN|5jcNq<Z7_MOUSEP4TF=?`@Drp>LD<|oXe>d$Tm*4Q@ z=0xelu2X{B(x=%V^t56mbKvf(h!dZjf|37K-(RFc+)I2!0Q3sVocO<rpO9X3c8KPp zE;;9`p~;GO?XJ%f&S;dL^8#<#m*jnK;5hZ;ttE?h2V0tEi}J<Md>3{rJ7TPmmecqc zI5hS#RNPN?;Px$4&K*NHk2S>Pcn;)#5mzo{u-&a<lbrO@#PN>LO)PmtKgqT2Nga<6 z6P|2eLP_fH17Vqh;S`Wbym*nZ!Fd6t{xepbHy^VnsZv_Eq_ta`MKT(<H4ZV(f-33W zVg&e|dI2>z<lXl@?kF`TAc;EyDRbuM`O|b!A`W7>D`$Jzx<~yYd~%o2-Zje%i=$4t z7xX1Ncn%wV>PA))0RlSomPYXEq3csxds>khA}g9xE@;tr#&y|R!f7)*7?nf7LyJ{q zzeP7IceWjPIGb$p&8>UXWj~oBfp7NCPiQ?q;;yEm>cj%d6;79N%x?l+g>)w5(tIGH zDwkPjUiz(otZ=W4F1u0IfLzSg2!K3!$myc*nuk`;DM^{ecr4}<CTS4mh@KgY`n$OE z`*)KL(LEy${~Q*-A?NLgl-Z}?B$PHXme~@h%@*Z_yhHu3rC5EC3Sk|Gv2o=~cH;~; zGmr@;jJ<WMuP_^O?bpMlXicfkln4)%1*fJlBj@;<X@?yZp3(s@UDQqU1JVYd5J?j! zm*L(NDxW9mL**z9D=}{RzWh~2cOV?j_E-EA=kvpR^`s>n5KL3h5clRYq10AfIdqVV z?(>enm_Xb5bY&DmVLXSp!KOum6^lJ(<L-qH<dd0_%YS@#w#JAaIAhQ#M8tUN!hGf) zvv$mbVtSFYB9!%-55s2;HPSp2SvY}iX;020LFL;ogq8}CVze$9kTb2LoxF_9V+WKK zd<{39)2GuW>EN`}cP|PvAAjA8egr~#m>PT{1y=qO__Lz~V_nI+u^jdhQY-D+Ltnh~ z0gPnImZk`XIy20ju6rUWYJ_7*IvIO1<}fEjsL)a$wD_-II~W1HD=46=J$+NhQJ2+; zz5cxN!!<lJAAbWR99AMfV+YK1K`{U2`45ewfE2i90i4#_s)S%XsITV()^<XrufcB4 zU)`|{!~Mi{p+m8*tl#rfXf)J2a5_G5Uus|m3&I_RgTr|D4{Sc7*NIMGNu2^q7)IaG zJ;P358x(YrJl@tzNL5`DiD4j<=(q-xY4Cy3C&Ki7;;hloa0S(fW>%Gsx5J=9u=0xU zz#+q4K!~B8pgdH$6`qF$HY2}zM*|+U>FW~%_c6gCIN7-jdL7=*>a(04p$Nvqtpf7s zFawolz{_odT{w?(w5^{P)Fc*^>sIJ$?thKAL-t$;kcT;+g)HP=%sEFtf5nHx_v;hQ zxlm_W3PoD$U=uXG`m&5<xZ@ZFVN)t^9JY3CKPHULb?36{hJHG8{f4tjVU#~Fl;;$U z+h`cHB=FvnKyTjjFRg!$`YD^LWxoSFm7_IR(^|ca2Qf-D%>@bGvN}tYf;jB)1ADc8 zyRezl_UV#7&&qOfS+(n%-GwdxYlw_VZ0&o<5w-AxR}T$yVuwY+>mWflA-PbxF`4Fn z@%W_@*AOZ1Oi5v>XGicXqh!4k65;wPPu&u>$ojbF!?ur7M%}1<O)A_G{$nVYIspF8 z6R$-29Vpt-5DVJADWqV&t%Z;@wJBTusTR_K-IFWj-g2Fqv0}aaa*sbkBHZ7+8X#Xd zA~n2New5g)kim|-U}M9mPm$BDp~upext<XZaSeQId+z+h>W9$^xw8tgF-3|8JAyxZ zuW|PW+qLbnT2t;lPH8-AzMnavGkS5vMvzoO_Pssf&_b<KJDr^3e+_BdPPqOvY>Cya zvqD_|PeT6Zi<-xsXanrRc0L?>sl<?PWPlG?QT5<RS_<=Jc7?f<p~0ut9?o=UW!hZt zBwXIs=|*SomSOyplDL;VKj(gVZbHiJrwiL;dslA8p|>1V>2&aWMMb_bczr}56h}|S z_bp3nR($N%H|!kwkCRWekEM;B4*<l7kl)b#<IS~=3V9ndK`&=;TPiY;X;~)*JCNm& zR#z@R;#_#MX->%4gew#5?)S?Y`&C5vk9O{68CE0|{xfCX7hH!;6$L^v4Wh0;1hWoK z+OF8;zmypko;H-kuRn3h@?D)&ZEBx$W@OuihfCkAzIZn$MBa3cgF4xqD~xvCHKzCo zuBu6hm*~O*7w?{3t9}rdkT=1eerQ3Rdilbf>Ag!rH?;f_+0egM%0{v80_wonYmB7Q ze3Fh+BJ{9>(XIV=-h9l{ElapulE9z7rzK}}h4n46))(g`e%z4q`40(OXC$dx%2$+@ zZd4`((O5G;TL(kdKmN{{8F6bL7OlViM)!vsrx@xo3$Kp4Q1{P}%ksajN3;cBR2j2J z-(T~1L1Z#11P0n<L_(v>QalOK2IK4vi$lu#e{Oy;aZXtcE^Mt3pRX|AF5T_hmih47 z>d~bQ&qKuHZWr6;)zHGjWGNIb$$|6M&@d~6v<}A1bZJ_j`q}U>{QHHg)ot4%gwa=} z$hT+oN*v!X$$Uz_cP(S1I2-1HAKP9I4ZX#lU*nf1xpNF(gxvqkR&sj91f{{Xpq)&^ zRJyyO;mm3IsOx=ln&SVK?qBj6^QMFaF)gEElw_-*#aQb<yX6hbgONqB@BULHGTq^L zyK$-wZ!)!Q#qn0p8;vT-bTrCiMY%9=XG*?+3~pV09Chd5v{KW*uED*{cM0y6B~bIo zaDI%)9u>Wxcr9-=%n(OvWpEC3N>ogPa~2fL&r=LK5MO3frcEcO8CK$`pjJ*Oe0N;` zCZoou=Q=lZU4}6Rbj&sCN^n{oY%%UMY5k#~{We6Gd55#Uc-}Zgx|k+BuSK`1%a-G% zDOLs1wSw-C@)=N22&|;q8NEq<oGi1&U)$<ep0?CiE+AeUWz?W#VVY-(u#az@Mz>ic zajwSCq=AY%hcE+D*bJkV&S%<&VF#>gPpsK)sunQ?Ds^c7elF@CLIyUW!l*;@hiX0) z;;v2+dAeyd7Ohm+#aNr~nu?TsME-@chWgabZ5!6ujiY_R*ToPE(c*E8&y*7_o|mTE zROzeAHL7I9NSwo^cq~yf{bB3e=$GfO#%IYFX7I=hE_T$q4>g9AMJ*j_jZ@JbhhKrc zb4M_OaN*t6R~OPJ6r)Oi4UqsEh~~~*r~V4QqT5DP^Xn#`)~RQG^z%&fVu)I>mAg`% zKfb6kw;F|bn$S3q@T$BS!9gI2#tMz9;rcojf)GRulVGkmg7D!?7LjYQPw_Zqzo9>_ zM!AU|n&6YzrOlFS+Rn!NtJSYPCnAN5zWbo<v&Iqab}GfLaI+#^;c+z%o_8cG&C<%Q z)uK&ZA)2H?C7tHhy4JWQV*YldIrkQ08d|H~vIOF%p>XXJwMaoK@PB%~yl6jDwxxXx zp3LTM<Y?tXl$@^{0w*52$81aC0M*SaAHgV5!V=Mr;5d59UiF*YwKn*2vXlAfx%vpw zgQ@Hl(~wJu(V_I*XJ7S;K7jg&*EY9YmOX)*+-yME^a;;6gc`f?JtJ8Vn;BfSq0vqk zLt1bzxEu)2xrODTGZO>q7#OWHTSQO*qD22Mp&P=I4E!Wq@bsJc;j2dVF$hl|0ENvV zw14HA6ueX~7E?E?WLpW*H!(a7aY@@5h%JJG<}2&}>$A)W?VO+;&K`MUWBGKYN$?Db z>6rL-mco<tD9=P^A_-j+4?^xD+!2E}E3>dMIUj}#5<h$$hDqECO;;`@=aigL@*%gN z2c6&m(E%@HKT3?qXT?aRV<_h{RF?=WGv<5aT<CJNSUY*F9p3jSFB}zNRk?-%+{SUf za-GEA`fJ_m#*24EX;siQ`w#v8{0rka<d}k;!L+jyse!53+oPu2I-(oGX7uB0x8wCR z!C;A)qG1Bt#gAq5^F9KptUxmg&mG2Xp$l+Asd$0(frK(XF`7_hqnT*YZom8I)CCht zw`lz*l+cq@DUyWlEL1=#+0G&7GAAb=?I*Dt*L9=|sI$!lY6$$AUlQlnby9>r$ys-H z>3X5DAlA;{6YEs{x5Nd=UWb|J1<{<?lPGU9?WH-qn+|4`T|hXfhY>roFt+}orD#)# zXs}Qnm<3UV$QiMLU7tJ3S#+k@xsTDbU?#Q1B&T2X86Z*9+y|j%ns$JFME(grT)-4= ztnD(^+OKoaaESo*2yZmCLwXymn5#BKJ7yx=)`fk*e8=h?ql0a<{ZTe2cElxAZ=3nG za%~ikJ6ZiWOCG<wbPcTk8(@vWmSUTWU#u%c%n5Glp3Z9jH^jP_5Nn`c-PcTl$5R$h z({@>IJDQ)8j~#FjuXoH$ceG&l82ZxF*^?l-nR8NzU(-#s`shQ!Lh#<p^Y`_(wHyMB zg^ybyI94rHLF@wq;3<F7P~{bRBnZKKF`F;Fkp>p4*zZ58&L=w^`p49jG@Mk=v7Hy8 z3RGmEAXDqRni!qlQ2ltU2ge_^Kj!kL5u94YLH%nqmpdGrC1ksxWg#um(RmW2j;F&Q zk_d>vy~6Bn+JU^rJ>4?0R|so&smTT}VJt2rMy%ac$@%=(FDVB^g0Ewxn|6#Q`LLlN zP^@(Yi{UcE1yrCB2r$xxf-T2PAaWp`xxyoqCInjBltRm^_-lN3I9I+XjMxB+BSOHY zEDnxHwdpfN94+M%!{qs55jv}c&Xfu@HGfSZsw)c(`DQssDrxGZHq-BIC08yb1y}a8 z33$j^nnb^d+XADju|ONp8Vk>rx{)3E23mwuoF)k(o<mrf=~PL8Rxn1pI>zKN?!!j% z9jhUalM9VscjLk{``dl7@(0#mBvi5*G9D5-72GBZ2iUH?k9^|&HRu*4u^i<Zw*viq zLHrCHPmWP360u3pa8LpGI}r(23+!-;uBR299{qUsM&Kv(HyW;ZO2veyr^M-Ihyx?Q z&=xD#nb0+<8YOUG><(VV71e(>?FEJoh-zEMsM-ohXe{U3UChme@-0+)Amk?tV|dDQ zx3?3?KMx|CQ{~zO1uD4=c}zn@@udpq5;8q10W^``wJFl4@m*8_>KKHhlk12P>6+3| zmG{IN>aKrHq|MAaw(^t^2h0Gv)&e&Zdft!<g}*p{O~$-~a<}r&LV4rxGP&fExc=qS zPO|*wuC*1MZ&(Xxm6FO%lXl}cVyG4|5Q7$R^hXe{9V<9<D1V5-$sYz*<KZBr2Is66 zEL2p}_>U<v?n_;;Wdz&CFYdFVcA<|zN1o1U5pfXURHE<wgGNlb9`E#}3wfL>y{p*= zjt6kuHG$rhhIZ*$Bf=1eF7;q1aanR#<0=TEu%$aM;oLYW#W{ktZ@vV}0x1PNT`a7~ zu5_JoY!qqkKC?R`<R}2TC?Q!o=NfbU2sY~O#LP4xr-exq8#S|}kr;_*X0nSb^*0b0 zVM8pa+@LX4kp&`px6u6^KML=%OuPwcF#Cv<8mw-)j&I$})lOI9ca1=a?w*_uiELQs z%XtN8IEFwyhNbOpFGgsw(!6|W68frKvqosVP&*qv?ZzPNHl*7kjjvqx9&?mD?AB&I zs;L@vngW1e9?Dmsq~zi}h-n$3ddsNj5n4ez-U&IOQkCYh-@OLqxWs&k0U6@lfddpm zGG;<Gr_Ag*n4ue>;oi_V#W}`g$p=MqlQ`&a_n`I5O#U>-2Y+B_<@z56pyUza#H2RN zml;7Cv?j}(3c@c)N#ZXrrh0iC)2xaVAMVHg3=DpFx#l$uL|hP;%Fwid`-$F0U>HIN z4&9VDOh3PfwQP^V+G+XXNC#1#3^fq_U>*V1b{%WLskb_fT*m<-(4!i`dg;?KYeHSy z$^cUTodz^B&>Cbkgu)ZcW>tYkFc*znr8*<E(;Ms~1$^nOPwElw3aJ#S@054cd}Odd zf};BOBuGieAgaSIEbqIMcf^h&_k=1;^H!1A5Lj=YfJq4`rI8)f(6uQT9w{@|S@`5@ zn>9q=M4F*zu)%kvr(e+cY!1{2^X9TMN|?KZvu7ln`Bav@%Q_`m0-_tigkSCO6KSo4 zedEy$>dtY9_OvULw7#`i4?=tuGE;;~#6+eb<_wwUAt#pUrK$M)j4|8bfZT}Zq5Ojv zua{got9zherQ>4Z8ixq1DUfrf8|X!ynmDi`tF~m{3mO>XDtW_R%PIB&Ry$t4tx9rM zg00i{E_h<Ie1DYiUaDGZK6{VoSf^dWKy8_E754(i-?Q9P-fm3jIJsk$88c2l#1bx3 z;2?Hhm?m9NcSJbXMJOjiai%1RsX$bY8<C6jj4&Ghi9730q?C^(=>Uay#T|NmqurmO z<}6mcE3Y!qyL?rSjxN5qE8Lyi>_KMSfTuinn~U*Q^M|ZmSi8g-rA9Rg2#`rddq@+1 z;&|Uc#ZjO<mF9MocBbCdHDaZ;uc_}kV?q^d!W`iX9&hWK9&=t~-;ROr$@7-mD8h(~ zkqtsfdo$X-5bZc2*xKy=3V<d5F|-b_{;;YvGfO>gIV#<a0PR2Z4gz%%gT#*)S4A%C z)j{RwYeMVpF%i&*MMEn}M=PweQovA<RB(|@2e}fKSO*w~HjOZ}{b@D?K*bV(gCKaP zT<#QOe91vT?sU_*?n<MyUo^;?7ER_75Q451BlM7=5PRC{7m)fto`f<DeWwKm0?>IK zCt$exuPnr;32z15DS#VvKL{r~wx=wsPPsj3LZaxa`Wu5y)g@cSwS9#AB~20{X)~GT z32FHBah(~U%s-=}NI{_mh;*LRB>efHVpsO?zwK1MHf50l#&1U?{5h``x@UK>t5xCZ z6Y6r}u0+RuhyZA*O4~2Fm|}};zZE4Grnjxubx6a<<C+Qa=<Pt^WplmoYm7i=UY_R! zUK-~Tn$}9p$^9qpGm{+eDfh!)a|ZCRK#vvlH34Aq1sJ6322LuI)`YppA9IMUwOeL% zQkrvjtCF}BL@Hq?ROul5N1-7&quntxdeJ?@NGxKcsCo@=`^bykNoe3hdxc{0Q5eGL zd0fE9#Jz;eoTkGHgzB3LwD+dWJa4U~(U$c)JSj<)G+It*MH*o<>EbAH!#wjt<)7Ub zx%YE;<s8ZEzw>TQ-)>~9!m;wX@;jV!G1nv+pMilZ*~2sPaH98hH@Xhw=*_Xt_d-P! z(iG)NwW*8f5)^^Vgep#Wh=waBBy;FhD3A&P*aKjkc-hJBJC41+Dt9T7IET1$76BfG zGvVXoed4BR+y>%C0y<_0j3SQPcck_y<|J4G33nR{(iL^;zxd6v48&<nw8s-)jTb2I zdzdi>w{WjJo?_qb&g$2Mt)W=OAA&t}FcnuW1qR`H%%>(4n1jW(tdREa8YdEkMjoQ7 zbXU_br3cnKOOQR&ovjo*Q)Y%5Knh7!=PVQ-4q_6q2Je4QC!KZWydC%u%K?Fp-^_A1 z?rl7)GSiDFC>JYcu50Nys5@~1xdJU93L3%405FhHW*BQlDm&HMCHb;X&kTWP=p&6f zv*$>LxF5na+?cUkt{rQN5*e2mDS&vZ14m;bOZOZJ+oMG25j=tXBEXJW$T)85E|`R( z4@!ExP0Y=~$P=_hwfYTB6(cS>Y_aDJ@u)y8MXknQ;0rQ-hDNbe%9IQ|>1f7BQN=E0 zm0GTZ_2~X8qWc{TZJIs0K&aCOjuyhS*NpS&xbGO=oJ`PH9y&#`?(a8%+KRrzorH5K zgxD+}Ec{h~C+f~ltX4<yh+zw>Csz7$b9^XiVSGQaV;Cn@5o(Ls9fH64cHiLdP^9Mh zbN4#N`K$w@NfYRTw<l`~BIGbDkWI#I(@U0#Yom%!Lbd7Zq*c5Qeh|gmi%H#8Of(%3 zX_{wf9fBqIHC!|?!jLQkz+u-WAL9fpiD;~!$N8x9`=x7|Vp|y{3knBB<XKGrMjRX1 zD#&eb>stE=kB%|6VApa`BiP72;pA6ro6r@RbQVAq3x6&oE)$uCIE5!mjRwp%e&1Q% z9P#)A@CQm{+y@m?68|xQizR%)JyDM^yF~0Z2Zd03V1^O<fZxDt=v;Y8>O1T&|Ep-v zW`;(IIFC@PfvLz$r%)s_3k`Nse|L_`G+I=JM3!9GD#h$<gaQ(elwyTjzi8&#m<evf zT?n!)TKY8vKf7^j7mX{|@bt@QnP|QT)}=Lj5^2PI53!q!Mc<XuRwoV<mtb_M*n=NH zOSs0KdGvGZdZA+2UOAAiGVvB8FmYGZmi{yUK;uKG$`aNE4K|<B2uSho1!ll|#}K#8 z%dM*R%MH%0RUK!1GNy!^*Xmf``(tbq$AgQ74;9LM&M5KfV3oPM#R?EUDN~^Sz-VWM z^jxnQsYKQU8-G_`!r%#H5u~v4jlKq1o}m}i8_F;pbOghAFr*-28E1u$q$jab8kexG zVhelQzzhtL`b7%-E-0J;a}Wf4%I+zy50&rsya*^s41*}PA2!VhN+aNm(6Wo%txLpA zp7UG;o;176HkD(@1HU)598E$hh{$P2q)ozAqECaT>MS*P|2r5VdOxyLY#mXiD5;;U zgxW)_iE!u17Sy^NYK$Ox5m(;bCJZAX{n3rSBG;zlAPPzDP^ea_G@$!i49SBp@V8x^ z%-ORd8cFvzF+Peh5_zpi011%?C)%5&0Aj>njR?6Ud6STqpc)jS1BqkB_={bL>J*D= z64r)Sjnx@R%J|BBP>3ly^GO63S+J}$m0i2Ks=I%NsP_3NEFxnfo|N26<lCqOsnZ2< z&LfV77#=TowII$ZCCia$O(c?fmcUJ%*Wirp<YTtPc6fuagcWqpD3^ljakWJ$N4Uv` zJdm~uXX6kyT*nHqTaQIpRSjgZy_;aOa2u(Kj$c;8S%=FeyY_JBBSke3@65CoA}HKC zxx9eGj#Gl|jg9SvW^eNqH6~|Al{OHRhRa7Z*tAzBHN|eX0$!B>;ccVd#x+mJ_@W7i zY$f#qyJye9a2SycqIPT!x^FDH1oQ4O(gHotQj8Vei99yUD=|iA1Z#K&YqO4L?;>DW zj)K6ae~t4=5i9DfZ~@9qGHQk=@*?dO3be~kbgjj$uvx%f;pH<mYz#}zYgW)Qhl;y6 zu0Ih2snfeegXfCMI#3=^3aP5_wG^;pq(>H)^IaUxa>9tH{^1_Cc<heZ7(|@^`m+-> zL6NHnSW<PTV`Lla1A}b~0-C;!Zl_%2Lp_^{dPmt6!;Sb9we5TSQcC{bU%;t|`Jh+v zeON`PfF!&!15jxI%uf;SQTUQ~uOGs)I1K`bR0;S~lm}l0mjob6;cU^&_xk_!^?~n+ zaMz3&;yi&-;KL7Y@=4A$eZXF^+g!=LzlDnElGlqRw;^zpz3)x+>7|7T*#XSk$MpK+ zp^y@UeO-|uS>OFFlD52^l&U#`i0zfnTsQ0>1_h@Y%uj^&=iypqO1_IJ8|dUbDt~*C zRqXD?0<8<#2ik};M4>|9IlvFK2W&svk!oGXSzaMJxpqAFd<nRLf{?w^TwD3yP|PGK zJ05SaV;(#_t|fH}bs+z)7%biZVoVLlbN7Yl6F4-6m$Dw)pDm`t82gP$d*T(dbE`nt z_IJqKAaSCfJS5ia8BcD0v{AV$l>TS85z~qX7da=bfPX&Coe+kPpbMb|@tuM{Kv|1| z&&+kNCXH4X!P}C^1vdXeAl-6O-ID1wqr)_d+l*xM?h*$}QYjqQuu|8iB^Or*k!;oe zjTMeJM{1kXmWr|IjB%av^n{U8k(y~nV)w+v-aVyB=ZKN(b^@!ln&yvdIWP+GC^?E8 zJm8`*9i4oPdL)2uqeqi8;l8M~br?R>>szY5sVHfDNIS+PO`bTJ<8lM(`=i_c!9tMW zA2jN@n$f)Fbwavk>CUduy_F$RZs?|!8L^tZH(}Q-vyn@adiEqv)F^ku-C2VT3NN4P zIsB0_M*mpEGlGAh3vIcu3uL3!h{cByc`%F|Q`+a^i*}5iOJsBlWV~Wv&$iV>DkZBy zY=klzqf^A?09|L|U<HLRXD=w^Rim5jf!=LR2D>nVnTo#@md4=kFuNuIiO%AvVT4l> zi9?wfsCly^(O%XSSE9CimhUdPp-KWmB$;5jz#0fTW;-A^c#4bVvYs3-&Xs{MGD%F% zZqCo<b2k%>5wJ|t?niZ#R{kvav0a)a`67-uW!yOdoFqp2OC7k~Jns}wbX|-j1t&O7 zufBOeHhGq#j!$#Pd>s(lg~}YuQU}V!o9~hHmB}z)L=HXYM(m37rieO!fntvvWML$% z02FvB<Fv!`{y1?f3h>@BB%vlU35d50-+i(AnaMGPCD0oIKed78L5HIuIH%zGt^gfN z`*vxL_unr^-7(_xm|>y(Duh!ZN>rBU+2+5{N>0Q6fO%wJQ`D!-7SPQN#&gDOQ*It% zg-H`EdJg87><KyN07NX|Yj0qOl`G0ADG&K2NfRQC;GdfLr{kzl5)ouy{jhwDW_TnA z(@oVzqlQ8Q_I^?cC5Wn3nQw#0q`E5;!~jP|Mw*6TvSNj9hR`cMdnq<B)Q8Ju;xdvD z%(=GQ3ZP_{NaB*&(lO$DM>pai;pLS5WL6g+7~22iu@g}TP%40bQt-}pc(u_Od>>KI z@i)9IUCe$8WP%g1-*ac{;AC3`{KZxx1J8VIi6X!?z&lWj3I}k5|Dhje1)H?ZW+k`( zuQ8R0T~+Nf@9@2p(UOba5{KOEIeKvGZ>LIg#nk{?+nbitH>3hs`eG^8HeKX}w7L_m zi34)<z>>DmT0y$hburi3h?pOb@vZmVksSBBxh?mTvVLszkF+U4V5O?!HrPyhDk6kZ zTcoa@*aPaCpprHD(7TBQjGFR+V}sRda-U~@PJdl=&F&K;jdW+nFOy}BuK@&>RE$g4 zf3b8<9SolHsyKzRgGcJd=se{Q+QlMBr}KOJ>b0U2j3O~=94_q5!8po>-Q03Sdz){g zGQ;qDBSaiWH!S}yLY^Vz(*lE&-SVOlgUjj~#mmsS9aUQ$F88$2ssIAa_goEGONr4@ z+l_;pu_<`xUke9``mTFzxsbeUj?40_!6>$mS2QDv{reFBr$y(PN*f+`=UFp3AYq3O zpIMsXB8a1eSy-CHrcmc2dp`ce>lZA0?kht^yMxNkzNV{Z6$E57yQx$9E226FGWibJ z1jQ5|5RT)ee=_23)Lmh3QA`Uhb*c-5W<XiyYt9XX|4ZOnR&qOF#&*O~o_=$$w&^E` zsIGxsSKr^w5mT^|a$1*OC_^{(S%k9_ct<z^VGbdz)}NxddJT}_2kM&~&O5yTZKzwR zA+qJ41SwtA#gRVp2pL~Q8dks*)yg2xgjx&iA_9V<@q7|rG&J7z6c*q%R}lxhWq{qe za<$<<8;S*GS%}z*^PaCRwuw*i*|cZSS_M;H5|`P)@>ucJ-?`O36m{zmC7bi7_Vu(b z$$zKA80%l-x=<VtVSm0xdEnL?ggNF%EI`Jl1(OGKrwC@Hka@8**)PX0&wwTe6&_+# zum+mBYk%GO=VSIG?W8-qWAefN;_)kRPmKYhWuiIu#pPWE=MF{9b;7FOkV+?1f41uR zZY2)6m<YqXoH9bt8@sX469wQ@RbmiI`HfFs8tl%dng_Hv9y-2m3EdEM+t^zb#E;v) z&}3pgSbZEd$_Uq%-#p7_r3rY)fBPrH8f-3m0JAxGPM$2BIUOYGWoNMqf2o@{oeEhS zEgyNStt3T4&18yZ*KIK#CkvfOejlLX(2vi~DNX85^}fUE#re>yBT%4II28hr>J^iR zpwM#n4nL@<Wi!;}VTVGtegrrxG<xM)g!7+z#V!(U+&O@H+_Wk+{5S7FEEw(d1o*)@ zm4B??h4x5Gw)he0YG&Z%w=|A>8vhDG8l4;J6Bl1Q^U9YDpeD(d2>eWO3xZ0IGx$@3 zVUmSD)Bb~-C#xp&H50QtQeJ<xX?x1#0!inSw!8yOPExyCrwsiukjqy`#}NpibrPL_ zc=%RF2YLD`st7rXUn)-!Rj(?d?V;E<v$Wutz``Sf(O_fh`}U}@gnz<HaU6bH#sL`v z216bxVzGJE(M@+%tr9OXFm!Cv`e4wG1hNC1WCi~)ZjeoVjTFQ_Mn&pAn#>yTtmvJm zcYWKn{bU6OPp4|P5aU@}hj<74ew8G=<p9@gb#~GUow}%_TfrT(&lXI|A&XLnn3c5e z;QvOyF`Hu)8f+$fE6eO9eMDYJ@l>ce%$?$64d?>u4=O2o-qd&998f^Hg{m~Dn<UmE zAsQji4cBzpG7M0&iwvKjb@{az%?`lv6&jTYbR*vV(U}x+iJjw{MZ|6%t5Mf-ww>nY z-%D@Jf7bXZSa*#8@tjd(!;PzYTr{eG(I_QcCi_Wb5dU^|(n^d>hnCApGRt@Fs)<ue zI8km3CuY~CKdq}WYy)h=lu6=HY%9J)ts_>7{`3gINQM<_3?)&cZkiX{_4Uga8_102 z*rrmu1a>Dj1)GdLGC%rtyQ&>TN1PCRU(=PHhG_*fy!=Cil+iwp&~Z_3zQS8If<{$N zLGS`t4{Wy3<p`fTXx}cNC+QQbiZ(XnbOQuW+%mqsY^_=04*McfG);kU{2BWCWm^TS z&P7KcZ#ORa2nr|rVO71i>6&zI+(%3k+B!#6d`^mX&x7bJC^wS<N}rq!yYN#k3?$Mf zOrcB{(}*lvS2U-aI+~QO7fqzm^TltB(#4TQb`YD3LKP^KpT%f`O^d!YBqPwliP`ac z(8@ikWH*R6d&40X9&@Z8W5uyY5FFUbsfu-QK6>7qD|}o&BrTpJR#T#A|KCmFz$;L2 zs*vYS?`iv+ENsVc-=OuYVp>O)6Sy#i7sQ{;e^&px<KAf5worgdlYk)js>fkT>VMiP zl#6O0CS@*@mhd;~+{_PyPTnUM7M*;ANzy68=qMm$5l%V^%unyfulaI%1iKxJ_L^q? zv-0RuMC^CqQ8f3l1xHJScrx@6*e|}$(jDg;eVX_8w#Csj5lk%;*h^XtTGBG71NMs% z*Z#(3iy?rU-(1gGhWg9LS7*tEJEQ@hMG#%Eq84iC>G6Sy>oCp&5HLx#F!l{KykE0v zyo;2{b0_Y=6R#f6$P-kKI#j?oj9jZCwKKYZuY`wnHHV#`5q6Hge*1gcmM@Ca<sC41 z_Y)#WZ^Y;yO0RcxVW^pTp-Kwqz_X5LBy~JWku%ob_Wqjz*)0}PjU<xT`+IhT>v_3~ zpqmmn(w5%-kWIa-B0e()4TIq$JWRdDX9-$c3*$kAmzXq45Od?q_=XK^^w>KNvMn%{ ziXG<yY!BvtV0Xx8<G`|qc(=WCJeqrC=#HtHWv;5qko`}=Bf0B@ie<lqA<)IWFTDu( zsKY5$W~9!3P8ZyNA86Af5hdCwi0@H9c>a2ZAwTJyP80wpiCeflCvClv`C6s?5@qBR zaRBJAiGHVTOAxIB4s@CzYkKbXeJWFQU(W*giUeRJ5`=_DK$LU<29k1(e9ErCl_V== z&xbTlP41!}FD+&aIoZBHeRraBqsO8DSJb=5MO~(U+*X*m)tXwi6*4AcV;-QyN^Int zyA}@Wjwp%;kS%eEvNcgs6d2RmVl9XPBr<3G35tq`6ir2R@=)W5H3=w6Dk_5`pd4m6 z4KwrYdEevnyq^C$3^U)ueP8!=eXh^va}A#C&f=)nr`KQL!d*JIR$dVK?v<v%wn-ib z3>8n7tC5{oB@s<##jFmJwL$$kj~Fr}%M*EPw*nayQ2^cQw?eMvyC+{)fP_5A(%)Wh ze^;?#e?1V{w0Y3OQeYst2H;jO;AW%U8R(AP-;05mx~HC?>D;$KI~W;Aw@cSq)gxK4 zGHuJ7OtGHofEhgZ@hzXF4{(QjOttrNdend?v%+s)X^}qZ&D+m8Hr<|M-#1)4ctMIB zF3>$_W4IngvWdqphb;#%)_Z<$_v1s$1D-qL80PF838@|S)IKticl+)y@b3Lkcz{Q` ztp?D`m>5G)W`EJGCKR-mNw<PHZf(GD;t=;<AN|;UTidT+WGl0qW(qJN-VpoL`@LFN zB_G5I{%4%;h@$UNz3*9h(EH-F3W!;LQOYQCaCA%&DYVtyG4GQ%ca2~BH?eaLmGd;^ z)f#72*qI%tIKo!lVF+Wr<EFy~GD?sc{TUDTIHZIyi)igmqD*Zc{|(9D6oK_J&F$3U z-?tvVD13lSMsPpNFn7n~?eEVfjZ`qwhc-US9pLShR*$j<LF6O!bOj*ty3R<reNmJ^ zaTfn<Gcs`0*~)FFR-9b_<g-8#tQ|3{%OUG<Eyl->gg`3d_#>_BZvHF_sW4^SaM5Ea z$t;xXOrk@15iXE6#ELKNkjIC5t82#$Ihl~3Jc7Hf<ea?|sp=vrYN(AhizH`Tvo+!J zYl(!u{?L0695Ae9QuHies=?;SomY5qv21~Ln|T_|67VBHP0Lni$JJp*?;r{rewZx= ziAFR?sb)KVJNmcIvD2XEkU@{syXQiq(2&fx;1WKjU-HndjUQ4NzDx5Zu0U!HC^E+U zkQwgixKf9M7Eg&aP@DXdW!DFb5}5Ivxpwa~xFhXU6wV9Vep>UaM>!-Qp>+%yjInuC zf6wH^q5E6LZ;l(sUHj(Hrq}O#<U)11MO|?ez}yNd+SI?^BnTGMsOF?#Z||6XY2IUq z`i=iO%x-{vwdj0M`3wjqw?6b2H<LL{dn0;_X6Utc%bi#Y^R-!XOW|P|E2hdd9OyT` z4ftHjD7Q$<`|hXd+^t|Y$#XR7#jE^js0c3sbRES0eMsya5<gra`qZ-?1Amz25-sS4 z?S5BU_mwZ!`457T;3u$PN29SVFHY;D+0>>apVstaGdBXla*jKOmFXwQHImo8wUD^} zS=L;Vwy>$p8-a4-Ht!y^dN-O?y>x`0Er*TvSj=bHr=aPqu(BtaK(dkW3(EV}P@_k= zDoM+FOiD3!R_@l^eiPdpNSA!+j=T!F9=-$q@|A`9319<PKmc8A96M&V{Wwed_dTmm z(S7KH#^xw%l$ldj!uz0_7i?a+W_}0^J5_$7nvKPOw$fJg9KETRhM(cIoB8OW^kM5) z+w^Z96+)Lr_pkcds&>DRdEM<)GMX^&5&?-^6bneBKG9(fBnP;v79ZXcH}ZL1?Exwu zyvuau5Zl&om9Gi5xt)*`(^L#lR&ppyuGP%pbR{BB7UllLb>oXJ56gj<;w3M4G)ec* z!2r$-6*Mkmew2<7KgPq?U(<hSd(f(Exa53jv3u?S=xsK{AQgq~6&G^4X_7?j7aTiL zIGFPKwK6(g-9tdS{?-s%wK%d?VboSNp?;^b+SK@c-Xg6eFVIeZz%;1jf`A4cO~>9& zy7t{3V-sAaRYZ<a<@uEehrl{&XG@I+*C<g9Hr$@t^v?U{<W<Vefp~Ef7^i3U*0XY= zc@6eC2xQsvB-V`AJ*GYiA)0?(>nW>#T=4;z<NOD}nS4p=J;4&L(%y&~TuYWki%tyD z<QZW)dRU|Ykz_@GL>MAt3@Jez2J<c9wN!&AbI*-kOyvj6&{bLJmIP7b$Mhxsr{24^ z;=0^gah&uVB=$I_?X-2m*abQ!hS+%bJ9pKuXMJ5dHT11>_0$5|pw{jr-5$qXZlO_k z2cKu<t}rX^5<7PV9ySO>j@J{>XFn)B6&@Y6YVt#vz6QRep}3`~?#h22bew7;^lP6J zIEd)ek=~KqZ0|Fd+#<)D$}QGJgq`uDDPvKVyxMpKj$gKw{;8lrv^PeJQcs~{SsUO) z?Em&J*;i^O!*(F@??az+kdUl~&Q_+uwxu)yh)%1@FD3Zo`S(&?qy*6xBMsa6@Pv*l zB$YvxDdg$rIXu-_*YOh+NA{#qfAl0&7zN}bj0}%S>m#IF3Q@xV+_Rf<AL@5?F<B|V zt=M}7v(0REc^d{u{E9N&f4v}T7!qK87PFy~1VAZDje6qqx>34q1e~y!Mf$2y?!q(J zPB}dfwoR}%Hu1=RKMFx+4fwhLg7<dRfu5u)-l`!_{qx%^o||2V@=K|IjF^M4sj|Sk zJ@HP8pl!iIaHvlhJxM<<M!U4a#ZgRAFk)WLnN33u(xu@bDt9V(D}T<KhcjcQ#z*$u zk*u4c4;?1n446z|z~)4MJaX4-=(sb${>s0wA3X=?d`>_*&BaK)?u?q2d;CM*>;pPT zW`ufizx-QbUe)DPI-8>&*TGu_LFI5NZa=GNSAmHbL?>>qMSW1CJ_fBd#@O2zDo)n9 zG83yBP=<=7bf4B6({84r<bb`-1I6%8oLW2EAUyAir3vbdS@~4j=j5^D&HxB-H5h_6 zg@&mp0@T^31T&!Gu+}s$lAx^f|1R2F%Cu}j-wiCQE^>G>#_zw8W*sN0p0~~J^Q&Sb zD=G$W&AFYv8OW(XO?W=!Xqq68o<~wQR_Oqpc7Rr_Ib)a<!D)B(pza93o@3}>zMZr@ zWCl8*1>unw{J*)k^w;);8QgBieqr}X!60T3d`^%Am0rz;j;46q(_eX+vqZO@`h$_T zMj92lY9T`ni4cd@rj;xDjrpfu`rq@*0NqxLmRT+)YzsvDpogyzEBshd&Me?e-41|s zJlm?j(Uj1KcFq9QtIJnz?xMxHZO_*=J-c?$zHrq;s^pE?w<{Hc@3FxG5ntHpoGS__ zRsT3VnxnL3d>zx#S&v}Km^wx2QE<{F-n8FO*r<R2$W=S<v<!LYEK1-*R{$kMs1uk@ z5x2J`kqEq>wxehRRZKjyK5YS+LE=H7GWtzArowz5&oy0va+Ar4+HX%xHkz6D6Jg)V zd2G!3EE=>oKxW(tq{iYp2c^y`&0H<5O7?Z^ULF0o{L&3pZ0}OAgsJszrlMV=&Pf|> z72!-iz;Xj+b??067@dFauI|?R3(|H^@El{4rjU=5!t<UA<soyp)^djmJe-G|?d`Rf zpIC@8ebr*bzUXK9u~-70!7Lv$|JkRd=}g`Wvpw@*gmn%UQ)56}lf=#b-@8DDovf4m z03H`rd)}{F@7}KYQdP$ls?>x#8qv(v73|Uty+Jh$^TbKltKX>C3wsLQhmmmeBo}Q~ zxrj`;y3@b<_`*#sM1S|u=4bCmJ6JC-j(weIk?yo#<>}njH_tLiL2tUB6SQvn)F^io z6y6ov?k_!)_k3O3p<xcGIyPK<;SScxOQ#?vW$<!1@9HRX_MEes4rfXoZiQSkGv&K{ z@1uJb!#SlBAeVY%$GV1h?irsBba{>j6@tXO)+%>OxBfjDXkcqBfQBI4Z8F5hgRBwx z6DKP;fz^V^YDBD(Ib#9!%>9wRsw3J4w+J3mSDE2o4exXq2OY7f^53Oc8yiS#x@As^ zJaV$1vHXYXau~?+zJm#62HiN#Yah<z+x7`U@5PnYpcYuyue~o?wzS2{LjPBFfDrlk z=yQ&Gw_iK#T=B!r(gl5_>g-Md=$~%!VP$>eEtBfD4A=dq@c;tziU}jv6V4C^e&lah z5|wtd>cD>K?6Pq>m!IV%)n(p4r3};29C<{D*<azP)Qo;f3OSc0zjX1W1*rsoXZ3Ut zC-f<j?M+3tzfs4*8@41qdem!0J)cVjrS8{ZxEfhfJgLR87@~E|7l-^9o1U=QwIzyJ zN~36j_Zm@2$$w(NU7jKv=tlPk#D91e6GqQkc`q)<><CvTO)mOPbaBe&tlb|FdrE2@ zzi_``z;i%1Zi&p)*!8EUcJ5NsU7qr+hU4K}gtm?goPfwI;gh&g;|tr*0@NoZmbx}8 zWl2B-wu!r>%wW%PQ?N$ATDmOgMJTHbkl1${bl+yXp0^hGahO(2P@ij>`ch_1_ll+( zENQ^2LHQQ+8#UHizp;nzM8{R7$PxY1Csdao<ykHio=-jeH&b$s-PLZkeIPJKD~Mh} zb$V*{bq=t>qxaJzNNn()&-}Ol&Z->q^SMbW*?0G=AVJonyy7GMGq;P}Y7p|U+O*#P z>jFu%xzlR6-G-uEuJcvbcex-HKvYq=aaliqXQD^mkM4c;JzQDby#AHC)ART0O0q=L z5q*&-xq#Ec(fKlXWTQ|8T!Sz$;<~T*hqxm>_Th$izVM8Az8Y8LO<_~8q1dOr-nvcq z^y>dXBfIzN4vS=JxD3=nwNZCnpui=on<mt+mpWIis`QbQk$L^9Y=87Hvb#-+7DzKW z9#@{9A@EW$y3;B#;p4$WAOCU6S`T{=mMS!{JpXSN#3HoAd7rRcQPel%@Yf5pbzU+v zK2w|Lzvh?2?z2L{-)b|Cm^|XE7tm5x3n+WdoYnUhqeZx|g=b=f8Jzul-!D7A{(v$p z=rJ3Q;M%t4IhV_`g3o19Op!;W?@aseV{ag3@G^rhm?D2UP&oD@Ruu?hsLGv}`qM)B z(&ci%hd|tlSPj*>|6D3WyT#gU_&(b_C*c6Xw{JAy>+->g*!9ElvSp^&IB96G+`aR# zC%-nIW6@t1pA8nnB`~H`-#piQmfs9PsvtWiuAek&Kqn2gq;N>1Q7dX`7YtiZy@E9f zjE&yhHrb&g6RI8*8z;AVF&OdEx+%Q(3UI#-`4R4d1F!r<Q}GO#%lu2uzy5qItd2<6 zL-Lp&SI|AGd{wj~MP71EsISL(j)i&0&3L`Pba^rl7jmj`1+&t+et=f?4aj4aD8RyE z-^x%LXme#w>j4`^b6?`!odOtt_>@xD<nvFr_LfPd|H1&p%n>?6NwT^gG6`J9B)YmF ze4Ul+9^=4u*i2}=PzEwDUK+P5=Ynw->yWELZsZ;_D7?Wd;8jEgQMx5rtcUf`a>NG` ztZzL&qB{EzmvNbXfB?&v0y{=6=e2Oo2p#K47;f6mfi6gqQvEK~dXT_xCX-jdu8z`A zLlh`}T%^doWok?kbmqDO0<yXcCVm3%%AXKiL>H0H;e@*nmnTieN6BvC)7GE@KZZFZ z{87vXHpDK>sW{BS5Y+=X87fSnpQ1P%+Gi$E7e7#G7r$a;x;1&E_`UqOfkpyi0V(&y zK=OM*C5l!EsmLhSziSx;HEV@zgS$1bSTNpTBh0;@YCUMSTm8@_7AU{Lok5r>V@Mzj z8LBEW*Pnav-QNo|Cx)8r{`Nr{Ke`1_RNUROEo%BeCQ<nau}~f=4Z{+@fo2<HBkK)( zy)r4%ouP87Gl)MZ78U}dLy@BjS`f9u>h6IA#nhHQ>!sjx&M*rpqKL-ZM7iu@To0sq zl>Fr0>^xH*OdAPu=%tH(GzLDsf)}<!x<;FxX>OC{gKLi}fAHD{`O3~fVPF6?-l0)j zq-JBm6n%=Ez{r|nzGvUczRV%JW{Af?T&XMHCJ7%61Y#nPZ6C;cAkLuEI|`)*GH@sK zxOE4R+fjHd5Nf$?$c*J!e7Jn4gAqThYJgh)MaB7A3fNz8QSIwC3F_C(Ap<0e2wwfK zqHcfnqTdRaKK(Z8KW>v;?F*j~+ZdlZY6_IOmB5z24>z~o%<{$ztX>YQAV><lfXaI% zk=5y;i^fLZHxc+8#2Ug5RF+5Kyl}eg^es0Qc7WsrA8Ty4A~H3sod=ba<DvVmgRvCZ z5*aBu6_19Zh*HfW*|$G(04^I<0IyK(F&)#AV(G;}^+&`3cUGq%92Qm`|5xih%if}o zwslODlOoD=7<@j57r8^n=5Ifbr=15&0WZW&386HEuiu9ZE6eE)i0MWPOO2n^joc`u zJFe4OQ6k4IcV+*QO}GV(!%any1n2v~<P<RErrdpzi>B>T8fllQSjbE7;>5!`SWWju zf5@IWp+(6dTMr?{DB85$oO4j-Y4kX%1e?crBl6>skZzo~K*22L`&Md5W!Sd-&l#go zg7}l!GWjRlLY=L3z2EVZ1x-_T`V?7IJ4#OMaS&Fy5QAY!A~ai+mxAU4Is@6AwHTx8 zs$4g2vGADa(2yW;>CDCh4W<%AP$D}H7YTsvZrOez`||SUq9bnp`y7kSc(+|{r#e2` z6k6z|O7wp!h3*i%t@og<)fi|s3)2eHF3$H*PdBxT;3dJ)Sfyg!{+Ju{mw*`Rn>8ZR zSedM67mM)nf|Mi`n$XMNX9=vK9>E=pG14W2;L<$vJpx1SPrvGK;4kS~%jHH79Srk` z<B~lEVzt+Wp&$MQQwTZ6qzoH3u7mpc*`^R$C#K9wFm%RUzrgDjVF<^sJoO6P_U}v< zZQ2a)d3_@bhH;;idJV<h{9zlTbV+o(r+g#fFt$s)EsqtUY(Shi@c9)6MLjGXw5sym zkf}HoW{fJ@bdn%#xA2fXWk=u}Q{fOWNBZ=t*iUgy%gHMHtba4EciD*WfX$F^Awvn& zVy=4UU36MRc^^lSv8+-0Ur?OZiq_?)<fGyz2~NT(WHwKQC%VV^db%?Wg*7W;`rU_3 zS5wJxM7GQ{R^{PL#-v>Ov(L9pMb9pzjcieBy}RD>`{ajkiOU!3Dena@MLWtOl0*iK zxd|qsX7$?g6t$)r^8-On^jm|{J`Z%(ql6SAUxafIbIJ4jF+r2|I;D74&&vk#wr|N> zgnUk*J@cVn4^D5T&9j^l+9BHjKwa;W6V1_UXkZFLNmaxK9H~UMKHrs``jgiFOS_5M zGgWuI5KTl7?O3RkIcy1<FP*;?a<wV=G2Vzg-}e|m=M9LVaiB~0BdCk%eTgK=kUT5J zck9H3=Ix3PoGKm)3P^#PtjoXuI{`=3(XRSpD#@21R3t`$D#7g;U-+9yGSypSoF@Kc zhIDyZAtS-Tq3_I*4liR%F<snWkd3^oMCLo^J~^c<>zrtU3*KBv&#3YotNUnII$YxP zmfb1rK3)_-K1b966ennA^l9hU1(UF<T5g~U=Itfm_mnhuX?`WwC#*+v!;=y7x&G}F zp<nv_(Oh(!+B$-;w^~n^TuAkN6u-XzPCE{1FkjK_D9Y?*r9yi1IJZ8zkt+uWhB?%m zFw3m+hU^KxKa%@*pEpdJD>9v4%ggijEnX<}gy;Au8467>WM94Kf6kh<o{U2<M6X{A zC?N=u(GgiD#&7X^Ds2;v85J8UKrv}a)kcy_D(Oo#H9tQoS}x<3Q>yWr`X(HG+yBRN z+**B|{?MhYAQnszS4i*CTgEHD#Tqn?>n}AIt(<&2l;bi6T?^hBB?B)c599!3RJnkU z!7EL??mtH7W}O{OnK58oF)mPI!q*hh|E=m7`NN8#V|3!6hV-v<BJ-k>R2n7kN{4OV z2a~4FqV*q7$Pvet161*oy{y#u4PsgP8)Anjo5%9r#r!%Q#zNx;_%1QVSWvQzg`LDf z>in%t@z=C{x1|m?HLuVr9h?3n^`Hk<Kw*24?%j*`VLaM#tx4gtMS?oOD(Dui?{?du z@WNU;{&3bjG{s7CH=HLkQVOfg<m%K(Sr<<F*c#$)#$j%0lP_{u)$zBL6Yqtw#>`#Y zMbs2R2anU+Fi$bxvZL`}xV$Y?$@5AVkWi!X-9wHW(hboK(v1!QR@k)Mdp_s>MV7Ul zC9W0?wL`n^gt}(DJZ7od6-eL{cRS{8<}arQ1Wo02iXe1(dj3TVqrF4}XAj%hQ+6O= zJADfRehqoZ%+Z6*i&2Kr@3jc|RF#&Tt*cC*rkYVkxT2k7FA@z3l0vIIW%uBwMGG;5 zxM`rYg>+Q9(|!_P2iErVyQ6+FUR??rJcVzmfJ;}h({@0Rd#k|_IJY7S14<M|#PT<E z^^Pc6moN3wi0cG*k4a8F^<MRwWD}(4?%WZdZwpr@V)VqrzM->46uz{bgK7`xq>xo- z-4DK|<2HCN^1;l1H7rX?d&fM(5$GHfXy8a(?g~I0awiHvRtqO105);2C2;qk58@EQ z-O$)X6A6LNp<RL1g~FAZ9del^U9np+daR}I7cKSJ@UpRn4!&|l>$bi~&;cqi%8s3u zG)gj#dm)saAL%VQ$0l{H?7Ok5@y9{1H88Uh!BB4Xa7b;t{W!wFDfDU(R0fqUE~9oM z9CA7glt6_!IRh`HUlgyPz?H7MMs}0iZ}j*bM-I_)z|D^Jm36RohC`DG<U@gLZn(Ux zD_74m9zy}=I~)voh;xx4tjIKM`T4`8iJHZUf-~S7U_>L7#?^p>SHjiHY4#c7jjlmE zV?KB#{1NXqZK)ZgR$t&flmk86dz)%KC?fMe4UXqc@BSbFh2`R^xUqBhKN?0i>oE>l z_T12!`rc{tZo)7UtVm>TWtr0&)yH5&ik9n%H?!aKeDZoW2uvdSb<d%%M`k{*sizg7 zau1|~G-9SZYPnE3(Sf;S9Wk&e(kw9$ih_B$D=*_6W3L}np;LZ_g_J1@&wmOtf2mxp z)C%%Q`b10F(M(-udN^6)Fnxr6Mnr#F(nimJ)*qV@e6Tj%Awgh?8kDA=+NDYKdB|{B z<;|*};{fo6kIVJ7LS&BC_f8<wZ#TnTB#RN{(KgTdM{+NF&&n}Lpsq{FTXe2L1%AZ0 zgMd6KRFtE~@x(9v;snd~uG}$sJR_6har(e<l(se1Nkj1DuE()45n)u7FOg4Md(Z2q z-sG`OC4^tSJmd0q1((x~eh!6EMoS?{F;&3+Z&SB-=|cy!j^z;haitcbty8GMi0cRx zJCi}7p;4o05aXj6L_4BJ^Z=JvSKJs`RX22xj#E#xLF>1L2CkPx?}WIZ*9@OKebpj5 zz-&aZQNP;lwEF9{O!HyqQjxX}?q0dBmVT8uJkoj6_y_DBXzhpG!4;6oI1n>37%t*M zc9p7(fs?eHY`cM3*gZrvHgt)*W8nG3SgoRf=o!m<Bx7$X$~o09+ZP(_-$V7=sZlS# zmVR4!8Q8z45bHL&XBCXNmM-|b;)F7}yQ446-`=%92&WiPsa?ow6$tM7P}@~y_9>>R z%w2N%K;nn;$tm!wonhpg2Pt;L3kbn`d{`MRqVkA!<8215n|C<9sXX6$htfr4BDAr3 z?ei)>d?oQ9Yyv=QSPn*7Z0Hd@`eGIUuNcUHdelMR3e)XAahc5*vcYXlzKS!_g0T-w z@l$}PJkiaPwIB)|KKyUKilyqcik}?QG{K%ZZNB>0Al-0ee0&h99!v_w>Q92gCGU7n z<wO%Ppo*^E)NK0Z79}wl67}vJ#x&_j5~BuR4{xAs6(S1n^@rZOmLKP=Waq8ocYWQj z&_InctLM)?S9Yq;$)ewdIV-J`91%lBcRYQ`!@+1e+2hg?iUy?!lsw+cb2Nf6&P+Zm z2+86LW`?h7;PK8!@&m{~f3Dwq9jj&`@cWGe_|9yS9=KmZ%2>Kv@jjX@z<irPMt>wj z;g}Qs1Xto)^Ym+5dkHSMgMi~wSD8E+qNLQ2Cf?9MR6bZ@P8OUatW9LjPp7EyS25w~ z?#L5Lhem-(3GZgQU;%pL7)z02q&YT8xqF}>%<cKJ&!^^ak`O>0G^jHwR$SNgqsH$P zYh$O<pu27s|LRKcX{cMTN5g)R#!aw`NOhS}@d%w^L3vk}Gz?tkOGgcP{z>n!B9T$Q zAwF~orMb6ZFp*pA1IWPn-rmr+0-AkfWEew5dY#Y$qrBEMT=I1-0MxL!;>3ba@i8YH z^1eFxtDO&@g>uX;@LtRCEfk@o0Qp9-)oHYM=P9^K04D)qz_6pB$((w3=!W}oG|Szt zp@WE1y~57q22b6|j%88yo`;u4?c-~q$otkE5IYSJUM{GzodnqF<}NC@+pyjA?^6x< zy9j=Q+z=3xeXdbJBHlQ{mUDC@kPvw4gFSG6WlHuRW*bB=$CtFmxi!HV6-E*}Z9bJD zJt=*}xr4w29BXK&BI$T2^{IFtIPQ8q!V>^CK;=}Mi|GBM?$l(&KO!nwMYX$cGs1F& zX^r98CkJ!_j0=ff!E|IlbTfH`K&pMhB~jl-li9osCpL@Zh+<Lx%Z3Y%F11gA#woRJ zDr6wYbi%4d9IuAlzn;}oLXeu1f=$FsfXbQi*Fv?SC{W}d+&!6dkR=^gFtqOwQ2@<A zYZZWE9i=JB`Uv(F%XYp3;5HeLrdAkoysDas{eQp%!9wA23=UVJ!2iWzPbp2BBr^{! zDjNrKegg5eNUf@q{$Wo+I4WdT?y|oSDO`3042aVrIrs(oAR=_Vz7WQY(g8n9{MnB5 zC7Ka?=x@g0l))Pl8~Lrl?0b{IOQtuW2z|e*!UdUx<B_57#5MkCxtUYSCs4IcwQqd{ zj+Mh#*~N~!w!()Bi!h>SzoZ%aAIbg&BKe}cz*EW`)?ZGA$S`yJxX3gSbC35n45IQB zzpVACAeZb302Ih?utI0#1H$X<YN^l^QT}KN{xNqSYG<!qujFcgrO+8vIA4}Zbpn~C zmeB7>`>!t8`;LfOn{pq5lnU4T!5}(Zfp}f`@KM0Z`wDZyg_1N#a(CaE1K;nMika+h z#*NcXvNIb8qcO%-A_<^<t}bJV0ss1NJp-H~t!$?C`Yn%VMxgilJo$|2FzwEI(X_?! zA#dG&rO|t^z>d68DNbG<m(fuPhwyahE;yoiYJ)WIlWuO423!aE@^6PwyLQxD`-j$0 zfREs5<U>P;wAxV#i7*s@d^E?If|z@}_|z>6M`10;(<Rh|;WR$*r||UHT>{)kuBk4& zOtXBh4rZGxjI1L@=RLSJ>vUK`tJ)$0Z)~5L>$QO_)VL}6i&hF)OWT_`VqwndaYSRf zwl3*%8f^~GXbRXcRs!oKl?1lrp#nd*nsf($8seZUf!9?fwah(acqWT%0!6DM3|*cR zcrj^pc=z&i22p(;%G~&Aj;ULx>OHhmzOKs0<P;)qT^*yy<$-bIB-b**_9dI?O_+aV zf%^HVB+V)%0xb9t?EKuHK%>~AJ`NN{me$T?ihPsY!?@S+Y~^%9F{@$e-Lf{@cS{Fa zRw)oR!MjrBzrfDHcWYdNVQRNo`Heu#F)w2#!9_p-l0O>tz-W(wNwIZW0}WExfZ*=U z^#Y9%DBhT+sp<i{VqwYbxUS_qH8a(T5*!!!=z-R7b$U4Va`rn>0jY@qK*5ZGNRZBq z{bay!>E76BOu`cgrw<(^;5SJ<QSu1zk|Bpj`lKt1C46$W)laY<4hR1h%%!Y}uur;W zVYqVqF?q=99nBY}=>~jo&{yiXpCE+ZJ)a{#o%IzmcjMnr@}3)tKAw|!ZS(i)e83s; zCE#jDK=HetsWZ0){xbO2Kl=<@xKmoi8w^HNW|@78Q7~3{U34VRMI*EVAIy5(uw(>A zvVs=z<ML{bb5d$!xAD}S=pu95vuF1?U7NlMR~Q@2k6b^+e7N%l-MWc~k~DJu_LPi% zMpf@hk-}l46~fZa?Q0$9jzUL(I=|hbY8{4HE+q3rwEXn<avX!I{#tc`QJLx6VO;0U zmY)%xHtjQe(%;m&S_3E`f2rSE_*>W|FtZk@O%)MJy1glK%ZY$xpY?w9Rgy;a)%fuU z{4_KSaf&o@)VF&k{aysu^ylZ78Ht!dp~A-}?v;QQg8Q&d<7<!b8k?(iw;pM$={=^7 z^h*MA&bg<j)ip=SbWqSh(^Ie}4moX%FDU$W!0XtF-q4u5G1=xtn^m8u27^xE&yXd5 ztLr+S;0X+S9<}YHZov_nI;xMeKt-NG==?EHoFDG8j%7XJ9yQp<eJc@@NU)RPQ{|Hs zM&-wG5CI(%;EHS=Fo}%*+DgQ(piKKU?x2l|-d|tG{LCp*T6e6X{bh~-??!0vSr?em z#to-8xjtX~>tc!`=whu68immpDC^2PDi-d2eTH81f0OBNpYt4V1k0AAvYX}(G%J|M zBMLi0R>th#qF-*fF~v#dFm{yrYCNqX%cAT@i~T-M(Z652G>1WqxZMd3gLs|Bg4wuk z!xPQETZ`KuhxI)wuWm5_!SeF;u7M4vcMTCa?ts;7l>XxKrZ-nB+sD(eGrzmtC#C6| zRS<Y7L%qC&fG%%Tc+0}MGuy;()IUyoJ%wkGC3G;8MosP5W#c^MoWbx$)OIH(t5a_O zO}bP^amrlp%t=NZ%nRkgfA)C_ZOCi8AYm<_vGFw*Sp>pnd^M)nF!`pN&5+VXRVvQ3 z2&QN2_F~ScDbtg1Go{!XaWBqnc(E+Yc6py^wb5A_k*$v1LnZUPprIK*%#pp7cUsQm zHvFq+**>@m?Jr)62S;-s*GN5eVr8GpD^{E~J|$>%0hbnoYI!VBTbgGz|6F_N>|pat z#k(|q*~Iv+V^UAU<VQ^<02FHucOV|sl^oaSWgO=O`doDzW>#QZb*mo-`X1*^w%<D% zCXV)Pr-z!9_-ZkVhmiZfFV%W7<{fB?Uj9plog!3ZQV*QT&Lz*9I?SNCF?E<IjA|^( zfiAux_T^72HEjzQ9AKFghbwwbb#>uR%UoN}Slwb(YiIC)+VJ5ihWOrGe$+bg4zx^f zJ^8|XS1wqN1~qwa+1%0J-Ua81ZW>bR)oTa!Ozh9)M*H_x6!HD^B(4*AOyl;N&W!wM zF?Q6;Zhb2f)(pR_Fv6d^tO2*DmYe(qGQVV~z~e=^;&#3B>G@B7SpCSEO3fYJY0K{r zvO48O%yg&62w%)D;ExRTv$s-S)JV794ez4M=CHMS+V3$|G+gkNzMxd@7Wtr{NR}+O zLT>UgT6z;_`4`82c+2$Y<TuT#uUm^?fLj{wR`N$50T%Bu4s2W#w3)~kyTCp7ki+JV zy}aH3<EhNP5J_3`2ADYr-2uo-xMXcscUubiC(ncDV+`6?abU!*u(k6=GC&^K)HFcB zju~`?10C@ReifHChbsRdekCuw{YF7R-n#%zbeBfYbN`eQ&ICrnlDqSAYG}>{Ln~0P zU}Ds>M^YeaY|5@lXtQ_cN9$0|;(qtk+T7m#o<r__BFO~7b3|p=Nk%%N2%jXoNuIL5 zB+#4Z>BlSma*g(yTmQ7qTP6nE$$dVv*i!#dsk@e~pJ8;pHro<pe&h0sb<VJvIrE&V zoC}B2;Ocm7bO^J0rgGSuen?pceI!#ey2;eDB<>;0aytpg&z0A7C4c-V=}6{3iE_#n z>3&D0<2|1j(Ye_i7|(9qT{7*5wD*i11&--!_Ox4+#&{GEqGg@YxlH8HQ)snAD<0iE zI_~PSQ(^H*12QH~!Qb|x<QnyVVv1<ny!fl_@BA_ePHXB9y7t~hzojuWG^9c5nHoqB z>po|@D^cl`2@P*o=Ra?Tvelp9mKLqJS8{W8OJTM=GO;q;sDHv-sv|cj{<F`Su{{Id zFnPv|eYV?pkAEK#dCz_&taQ5Tr5O<<cO9BxqFENwg7aLCJSdbJG6;(bJ91{(-YQ)% z#HKA_z+vglxDYuaXrp|GxT4>syOpQz2OFU6z@eIK>EvRfV8`0fF2&_tt31y+v|V<i z+jNjEr<3667F!t71mam-AQXdp^bx(gm@cX7WBIesYYL6)jp8Wr<g%qDx`$GROFi>y z|M{lJ!VTIk1^kxwdFOWt=U;6)0H@?Cyg<0NcDKAFJfMVD&OJPEFc3?C9J9Y<t2f8< z@V4=BUzSb1(yD5?I+$+$&9bMn<?{iLU^FTZnVX}`_H6E&d_r<e3ivJdf4x6TjUf%e z_p@$@x#9HYwrj$+-+_y?0FZ;^)R(`RM>hxeEHOR2H0MIk=i6>;jdtI~CV0k~)~$BP zFTQWOr~Z_^|Htl0VqWLV3^O#2)ZFf`HubbQ1nL1poLiYRs{d<dQEF9E5CH60;^v#( zFZT?^=;7y~6M!8OC;rW2^(rDYjAQRdVxiC3R-AueqN<yGvA6K5_5WQ}U#+oytZ^SF z1y{g-W|9Y5&e-At3Orp%#Z^%m*|(&{^CbHe$7M`>i~Li?8=pP6E2>R()$^r1vT^5f zZ>upu?(16x2eiG@U4Ks_PuOq)inGicQ{R;@F|x)xSpF_WuN{#VtGIW(?auY#4tYdl z|KZ6wmKSKWzBEcB{X6c9dF+}&D`Sm1mR0iq|Ai`d($xDrJ-<X1VlW-Moe5D{bMz@H z)-RJ|I7j2=9l3Y4t=5^UV+EOYQJ){-bb9*@`MKg-7e3ZmG*#(ZS7O&Pxh}la_^;ld zLu}TbsYOnyzS3t1M*(!Mv*P&9K<`-^Q>ejMR#g*w&GK_Kw=V59SbOI8M!m0Jth-|N zw#z3oqy)tmZ^r*OIAaZC-?*-^TdZ={gJ)Xc_{uQMu$mY6R;Jb<bppE;c+tY2Qe076 z1>>Ktn*02NZ~osBWlu)DyN<V$m1uGe-@5Upbo%PEAEZwC{DSc%Th$Jpf8ofk755bL zioJmie|v2{Coe5)U(41$OZTCcrwa-x((<@Dgp=%^h0p({?Afq%akl!{z>Z_4o`$!B zPsM%qzg_)2V;-OLYH_RI#MDYn_axgI!oY^+r~m9zWX&@j+K<#B=rJ`Qmc8L(z}^&9 zD?p$ebaHoD&&zF@x1W{Tet5e~Q~KpfOMT8CJ>Au>dS2*xn|SdAuXn6u8%P@ctaelJ zdnXP}lrFdyOlt)C(LV-@tT*9K<j_mkjOA`3zHmY#)!MzdM{4_IoOIiiIDCeC;P{PS z8+(UN)P5#CYRk&{a&RgPp^J81{dR)N{=~rziX*XB{`e`THXuax|89>w<*D#~4CHQB zyQI}*CbGBYl0Nm7p4a?0{kY-wGu65dtNW!ihptZN{^#CnsUiH2kHcYZ{ak|r^3LRK zaNNq$e@pwHJ;R|~RnvYQGFCU;ajCZ4G+dI{wm>{Sh47)~rmUX13cq3hxU;%0%B_Ci zUHRk-@2TW}kS2e=qAjRjmON_9yOrUTqLWnrwtBu`X)QaKUa2~-`v7}W^lP%$mA5FA zZoNmqGC3$?Ou=+G_LoSv`u8Z@mSOEdCiqO{x~s3Eg5zYwmNu*BA98>1CT-xN_7}_^ zUHjOq3tT<jXz)9h*b!R*KhS<X&TAA+s!l752hn10T)vo~K8D4p%8#3=xmow=CqLAg zy?bvb(vz?ZcE2PUTVa^zyU)*8ztI*guTMvvB$x(oaq`u#TpRj{=kxo|F1|C;ZUU8S zFcPn(t3l?7xTE?jO%CQR(LD*4*HD{KWL252NDtw7a8CP-uM|*a&G=NQyG}6nfi+7T zvl|r;-!#f$>O>S`&I=BqMyO3*^h=s)Sl7k_&L<pkvW$7SFI|ketAF#@FoE1e6L3a1 z?i!ESJF-<jP5U<y<}0)Z=cO2XgBi!8;bPZUnMeF_rKgG+Lg|jm(-3eNV&}>W`z_7% zqWkSDu7ja=QT<a6pc#Eaj!z^b=g&^o@890KKkTV+KYdK%jaT(r(;eNm6r*cEw+<?( zTX$-6T(I?G`C<vlxg~Ht!MeL8D<Qb)%$>BX@1)8~+Px$zn^s!K5`tB=5JFm-8&|iS z9K>U}7yOJE1*02rZ6Gfpmdqk~k#=C}EBe)>WS_;Ity%7pW6);--je`MaRzR;1l4_W zEZZ5s=?G*la;k|?<}-;7cp*A|i|7rL{+9ZBW{TSM@apv~1E5Q-ITY|7P+pnNCXFkQ zz6yH*99{LP2ngQz70sXpoxc@t`UjV~x&8ne#GDH`3HXS*5>E;i%8O9y>L>+43~-G* z$Mwhk-BLf`Ve|8verM)~T~r!7Ua>e>Ws{^!)$Ki1Kb@o|{3wA_{Frp>MT2x>cEev2 zuDGn{jvM7Qkt4naAux>#2XZWEsQLYX=kIMR^B1KWpDYqqJS>6JS_yy<R?JRid-10y zEBu#xCQ@tFyD&Ks-K=l#HaHa_a<n(qYCKt?Q{>x4^Pm#}&{}$ZaRplaFRk~0+!N@D zoM@`K{p@E@@sw>abXa=-2(i3?@a#b98_QI^(wWWA1qrt8OQmWCJKexUaO0|%S`XX| zxnlKK9M9ARvO9cRCxr)(Vs^T0MrGMa#)0Z9xx<gs=Ft40lQpXKW8zsf?4C5KSG17F zj@sUR_M;&TWmG>>2nD3vVLNV^(Qf%?#Zi}W@oCe6R?m_36F_pkrFA0|S85#O$b((R zd*KZ=Wjukil~v?s|9kfIL1-%KjInA<fY$e|{bf~R+dR4Tr?BS)UoP9c!<B9FmTo`q z{$J~XTL&5$2hf6CB!M<XXKr}m_44Jek7IQu@&ub0kNbJ~u(D6768g1WFwnqixfjnR zUk0Ddn<Z_m!X45usLfiS)O9?W^FVGR`s!h^qr;keU482o|Gc=(>!IazO3=KB6C~@S zLOa$TwS5h6%7Zd2S)1Jbb7QentlCwlUr{ri#{AOPLQMP-WU|IBininG$$j^*C*xNq ztu+k?fn$U^&TWanK`ZC$#(8w-qSLaT*>EOb*7arxXPZd#t<6Vo(k@5?4NB3CSgTe% z``W^|>*gIjI`MMa8zruheIGk2G;I88V}(Hq3^#DDTylN4te{jlRuwO~HmSw@jrLY- z#A?)yd|Fr=md!~i9}O61r`}cZ7F1rA){f+RZ^S)U9xLTH)YV?WEL&+@a!4zj$iQ0t zbHm#={xS>XY0bU#nB~yL+_>?J_!8oc9TI!~P}cAbXWkIzD|~*bEpsm~a<tCBy%si| zSVqU4qpSCw3|@UcQA*hhSY*AI!K%7jwkx@P?Jq>{lJ+My@n~>dc}i2tuDiJ8+StGg z@ohoH5cD%}TI_`a7`EoX8)woM^*-jQ&>*g|Z@?bIHnAhPXTD*=0kFJ5v9TZ_KV%Pc z3H}X+Cz*wUvtK`8xF)du$qq-Fa3nDH1{p8Bc5ivRC%F9yO7?#N7CC<#U_yOx_lsL$ z$NjU-FKx#4LFXsTzGsZydAR5E+db0d50BI&adz4X0p&V(0=7aVWw1Fm$b(v+#z~}o z5`{I87IRB>b+7&JiOe<ix1P;NwMe&T>;izGnI|Y=^~vvs4d~fKOVa&%bG&F02SwCm zos~!AwD#o8!-AVf>VXqD|Dv~aFVKUxG!2(4XjnRNM8!1LPWrRY!-rdz@OU@3KP~F$ zK?S~m4F%sPrQX~=o&Ig(8^~e>!OUAcH@-dWgx##_+S@_pGb0OYZKoA*Q&(GS<gLeo z-nkN1jTn-p`{}h7Nq#!~OIwbtW_NlHxx&_f*A4j6W9(_m!9<w#BnURMrfn?QCFyi( z>P}jAmVk*HmO8?1XkMoP;L)Jw_#;k+k7{{-^FY}uznsHjoy>0IWK_0a{IkzrUO0O) z)v%=KDcWC^tAV^4-aFOLD7wK=urRBrAeSy(OdW};Rd~eFzg-jc-xI$!hCSNU7A{#3 zf^l5SH6UjAu!%;EV~?iopK?|A3dX8o#CLGo(LnOQ?9m08kKIpTdI+)Ah3E;K>s+4S z^B)y0H+QX_78gR7>?)NDkKu0FBa7_w6{iUlT>jvXMpY4C-0r&qc#dPU&lu%VJh~WM zwP)%|j+*8j+lMZfnK?mAN&<oDsEknKU-EIfBV6_liQTZszEE*`q$*Pv@^jd8KN!97 zpOiM4%DL4>G;g||sLKcc0jQ98D@vGFN%xZkf6~<$6C?U1*dlRO=8f2&4_~Z>?6MOc z+rcN-Zt>{;(jloTa(<B&uqV<TZ?=wmgQp5u-XRWGOW1R(lj^KF^5E71pzucLjVS^W zwG93EBE1{ImcWmwD49lwnbeoR`+nux6JP9KQF^#dT942%$dmS=dLRQjmh3HR2mj_# z+%1cj|JpX?DUCWkEE8l|AO6zkWYBe{aYs#Ip%AHs&Y`QyzHPO~MQfyhw{rKHEDD{^ z!f$m5_M{50E2_Q8A&4)8teT@?-xoJu#%R1}y8Sp3^-%SR{&=K!--#aDr3)f?`u@*8 zNfEpJ+pVe=yAy|B!R^`@bf)H5<L`-aPu6FywzUuV680Npn`sof^Wk6wZqtN4P2)aX z`YIJ7%Fyk_Vx8j4;{4L)9;0I;^y4@_ukI0^HTDO@&wM%c{FXN#Jz@Rl$rC-(`~qSU z%!4K?JckZv&2aIR4dMQEkEOQWSkU8WnMz~kh1&2%AJRs`Ukr=v<<*0j3aquG&4gK* ztr9KjdSkiXu*Edw`R++!x`C;|nZ268w&IP2yr4_v`IklSgw;braU*Kb>XKVEUAd56 z|K2>f7*0Y?vms9Y2f$$T7K^_eo=s$|&<Z_N43Df?f|)*Xue9T*j>kMHZSH%oo>HCJ z8v)3o@^VbJ$Pt;+GpTQ!G-&KSvFdc@A=S6PT_<nk-6z|PO!Y$)Yg2SGuOc%vxV-27 zFsJ&2gSf$vVuFp)oiMXsVeIOvpAIf4TJ9OQesy3L94O_p_-VHNP#*lD{As^4TLLD) z_H$a*-7Bm#s6{^%q!XBL(F)X4@i4x{n4C>n;WY0$P%)%C^77xE*Ktf9{eGz+9iINN zZ4ZJ&^)U{@9!4w2!+X<fzgX0-PAwK@<Ev&;EjD4-c}LwiNIF8Yf@hPu49cbOi0RCg z|50_|Zd}{3ePNf})_y&Rf<%<THAw4Kyj^4ddeH>i`X~FH*%W|v#){fTR9LnMr!lA% z(^5fS7R0FaLc0l_j_>y|1(J0mx*un*<dhBd#b3pf=a1jTMY$4o6bp`K^oVg%R^3w+ zh-;cA^CHG_rZ|SCbTdIkRFIyG>6!hNnKQCEB%4P?99lc{nognC(fegOEHO;!Rw}xk z-q@&|dR3-SI-Uifc2rKvt{F<xK+#M<>NLdbAPtC3rG$M5k%sfHLUIlr{Y7c`Y}L=L zLt=D$+Jm-JM5s@6ZceV}e(NSHS3TcSdWV^7mS9^JRU};V1BJX0GNw%kwy5T-$^D*K z6_CKUja47REotTpD|-HjHH1pH*Y094gRZ?>4HIN{`0b$!Gy&6&H`<H|t%3R!V0Z7O zU~$}!9o3&7Gi>Ia?l3HQ^M|q8U3D7d=_{<bDN11}%H4zamOHp=yqJuwgNe;1=!v8W z<jA7mkr61m+vm8uW8XfdQPq|cC+tFxGAKg{YY)|i!04N|W4ft;_DavafgY`ZsrTul z9vWJ0WFAzAmmRUwhE+Nk0htOB%T@xI3ZM+U;y~0Wdk6S2NQDsxmuL3X(Z<7O`5cTL z==KFCi5mo?BeJe}yHL*iCLn3$nknBP6A7Sm$J4?S6v{8n%q$6`J?6GVq|!=&c`VK; zTq5CXvQq4P(s(VR4+H64sNhoRaQ{}AgQXQlU4qJ-{N7YV7{H2lK@pT^^oc?*f=<|l z$JF?3;~BQe^>@Vj_M3@|6e#Th+)|Cgk4j6t^q5+I@0(&;rC>WB%FGISjN4W89wj^% z<)Ic?ZYhOq1SG^!Aad-+;<lN70lIuB6n9eEMd#8`%xd+XWih<9OK>$1-lE|_t3%cR zQL=K~bN*;8eSLP9y&E14zZ%W|!6w*2$q;Yss&d2A5Oztt!|C-~`?->Y!M|t?PQjPG zTjbdKO<0nI$ON1!>~mpx2s-k64D0NNPXybg(U>jkTCXMh>sD~q&lglx{!#~}!{O=a zV#9bJE}}hyd}^iTF&=BTu2;-i5X&}NC2aEKjj(Md3<Fe!f46-hrHs#sv~f$HkW@V> z3MQNo39`C*F54ju5M|_aN3p9L>P`BR5b-{Q)&9fPVs??Easun`N8<=ZIn80tJBw0x z+|dYKpXI+&({PGT7c5UZ^E>uLzp82x4s7&BS%H~YNaHCGK1*;U(;eDim?2iY!~Kh9 zGHL>Iwh;Nd*|tp@^=H0<Ti(B9BGX=grgP-l*{lLF>zMtjblg4a`sjzNSYY!Y@YOA2 z!VDuJ#M(lKn=MY~G@ym^aJwhieaL*LLw8>b3i8UacfwKIloDVEFPXRD!c`kDrZd|d z$>Bsq6d}8$M9}zrZcwc8vC7>?lQtFlfGnZ^>C`c0=ii=pNN491i#@d|Y3|`Y$vN$h zSKw8FVhx`TdEbvpM-P;D678D#ZC%p1wWveL4$(JvRUU&v!bwbgogt;fesRVaqzPtG zg0+ZdbkO<%&}?pKXc)r=zp!hVVEu><wIfg5-mwur;stFh5l2$8UQw1o>RDl-C}<Mw zQhFimmHcquvt&6Pneq+QADhA!5xVXTI#52YKA=niWTw&!l*{&Fu{JWb40$3xM&z*0 zAzN&jH;{fC9uZJ4XVLFhA~76jzN3Xjl>(D#CxaDq-hGANmIy=cCaS_X;bOT{b(E~q zG!D}19}~r<m8TSC3pRl#WA0Rq#GGKxIUYgQVY=n+qhiAePnlg%--AR{+i;G!Xe@V* z9QviLj3Fotv3Lqv1?93X5S0q<O=iK87+*~5@{q6xm^|gF8Dbm}T_tESd>v1<rHR={ z_5zmjswpf57;%TT>8=yV!wG;muRicc7g9D*o9d(og7+kxSoQFHPLZ(-2jvh{CP7-C zwunO&bF!6sroY(SG^R22VuwIULNrZM2#zSy*U&E%E7uafiFwJ3Gz9wvnpv1o>-J;` zw$Q3@Ca>BHPG&BC%PG1y+b82Os@L7MG$EUla6;P&`bKQ$_$Xf!`t1`KArR&Od$$bI z;)t<_3`5)<MU-0H7Gxl)>-&|Oe%=sL_jJe3$LjT=VHzd61S&_?B#dh3wiLmL$Kqd* zVcf1M94D8>yTi9TQY}_geeN^wk>((^fE-;Rxf7=!b-tbgzmqWKIiG4|t7VVm%Vf^? z%!!7`uYmML@={6!8p`;FfkZ3r-d!fHfi2fNG@8{jT=3i&G`aI3Rt*$1NLV{<M}?Jz zgb#Wpq9tEPOlrNZY{Vqe&DvP_(5%n^)=db^d&gFNnz3BVU@(9xD82Ccgz{rwZn)nk zrp`)jaQAXRg?F!Df&;qNYacrKLuF1aUXyMiRiO+-Uu<*O)@wN<?BqsW=aKR^8@-2$ ze>+e3%hc8JlJMFzyU$7Yjo$9LO0fvPXX<1$|B&K7A-Hooeo<;3wJx4hU>Wa?a0bQo zk`5_zH+^*<mTC2tmMn+*bd2IXo5nmVH!o6vWYEyM>s<V6^7m=K2d*ZNGoXemDFI>a zwa<ins)FrhfUE89{7?+u>JCT{m<R3o^9kAh`HPUt^ZrVUqF*jZhWKn26Gn&~K~uRq zzIR8msumF`e~8yG{lU(O5EBKzQfP55Yq~{rWE3J~FMhOwbj&H%r)%S=6eh{QV-cp) zcP4{DpI@)33{`@D3Cv6oxNyy9G{W|Uf}Z3GV<**<wQz(OD41&_<$VK)P$U6OeRi=C z3DyWytf8ZdYYRy+?6jd*`J-b%!J9snGrnj!*Ni|f1NzZ2uB3*m>sSJ(Xg~=00Ou&H zWCWvfzZ6<EGSay2QD=<_>!)%|u|t^S7mgbhs~}jO&$HY57nYV-Sctt;UiS7kP5oce zD>^^cNW2bp^E8^nJP`rOkdQK;`Y3{-tRAjoJ5o&W(LbPx=4w?&M3BP&evPhVjY&B4 zy6o6pEr~K{!YaU4Y*0*TFfbWzvKo_e2oA!T4-Ow0QK%Xw6^o;A)LH@-g_VA4Cz%AU z1D<o_u~1~v`oN_+N{z+q!!I3&Y~PZCxa3J*hA7vAzlR989_J2tx%J|GH5O%ackJxk zzcxS|W98-~^qNGnUiXYYL`5+?vG-`b?2R)><G@algqOi56067Oe+UTzT5VGKHz}2< z%y<+_WiJOD=?tnPoL$V!+X37*-g(o3QVvNNhf62-^nk=kU%c|z+u+<brWfFi3A>ZT zfc<S+ncgx<7OF|8&9uPg&kfAE7h;jnxRYiRoQNlb!1SP}F|vaatm@(7Y%#Ax9Q~yr z=jhu8o0T6=_SYl35N&bv8X6OfPx=f;eT}A?h(Li`L<-r1(Odl1)4aXF?&YVzQE~aq z8m^&NFY??SdH>-!f$*33_E$nPN&MpwN|%NG%#PeWeNjWcA$)kC1}79u_uATtfCg5* zFvgMG33E;M^5quWWFG{_Ofcz!umcjqQncRUx7THP7s@iq?%I@<T0g@YekZ6{KcG%P z`+KrbmkJ+xela{>tQ@wNF1_fnunO7+t=+i`SPWzAPG8@X$33nH9gi@u7Q2~qXu4qP zkV+KXc}K=opIX*5w{OZY(P<HgCiBX0^Cbc2@$(Qlv;~v;{zN@;SDN2fMNW>krN8tE z*TN`_6#cBD{jTa#1YEevKhJN-0iQZ^(;%^wcKOsV^Hup%+Rc8V9drNtl|LyDJL*7d z;iZv$$CH|af*d6r?J$<FF-#304Z$AYN5$hy8Q&R+ZGL{g7DlD9nmep=+02JNd}7l9 zejN}60Zo+d-JJW8a9k)(i+nzls}!vw`HvK<K)fpfF&gF2nGcQF10@@6L2p9j34yb4 zICJpZsetw~<`?f+nMHQJYFHKn2EP*zeRo6BSL+9a5rk48G+ra%8<tSNto6W72qEeq zwWD?vz8c*iEOy>bjyFbEp8c|ZP|C+FhgM<=+DzDkOqT>I2n`g|Od7mBO?6&QhJCtg z6gxBpeCCt&@?WAK?g!D2QOC9{5nuXhn0L>n5~@X}g`j=-m^{`l9#0j?eg*<BHfw{i z#Z&gp<2)bU8cmkgk$Nx{^=Ag+9sP8CSD|u<E`v1!y05QDfQ`n=+xn>HiKLWtC}Rpp z^F|1rVOTR5;&Uxzj9<e-3--n=H){!mLEHtdyOq0t8Yi@ZI5e1g6P!F%S3<aO!=10l z*D_uQrZ1b^+s+yjzO7a*hMNyjv-ndRtHjz`cu{0(Kx^*vNV}~<$_3JQUe_9C_2U#? z_Z(@v%Mk8)#O)(=8~y2QicmlQc@!qp78Q=WFkms?Ba5r^9N`H9;_ki~uFha^8>7=i zfEVkmd5Z#@P9Fm;b|k@zYLlO5I2FeaC%7n?TQ7bbXu$1G*UM`gV{>%P7Hysfc?qIH zIer_xHlFTfHK9d3y^><rtH>l726dG`b=Wra_yR^%1oYf5VYP!`$|>I7O^DqDRzN>% zHPmu}gMCL9x9{B?4jvavnXiy1rlJQR%<Rx5P0Z<DA!v>C3Pcz*u?OG2Bx;|7Ub=J( zgud%g;e{M4TM{|O>){Qif|C-vLM;^GEulR8O?oJ!2PXy<qA+3lTLQ9}VT@!UNEQJq zihCeX+~G{K4hIhvENTpQtR81cDGm)G)O0y50NP8=z+lIikMIfXZc(3)9-aGtg2jc+ z4oiJgvbx=+fQMSwtuEu7=@P031bGobMNqS@t>s7PHebKIBrjnD9tR=Z+&+ran8qBA zCdzjNdd{luybt;Bh=Hr*`Bg&aWWozUXd!wN7sO=Fo=Bu`7TIBDAv2n>^EL67TWsFz z3&oj4>>5LuFz9FV_T~Oz_7;Xc-bv#a!+C)7S%9LKQ-B}L=#(U4$5`qG!Vo_QuGF#h zFC?tu;1d_6r>`yu%*<3+rX?w+=(|B}AEc$^8IC^Swf$nAHak$v?@IMqn_edHO_J7A za_Qd@5CEKWv&Tt-+_}7!r;ROkE=jzu9Wh~SK)6r~iCUYCc{Tfz%T5YsfU*D{I5JMI zd-g((<tkZ(cL_n;K_CM;*zaZ#qM6s^+p0_gLYrRB)h7<^6A(__MHE`v^jH;7kj9Gd zjj(aWb>cYQZ8ZBt0Pww)D<4`E3inQ)0x%#7GTq2b?eI_%dchgbzy?SJ?wea5sc_VL zuL<QwmVFz~m)=R;d5%LsDj+lBm?4gUS4&(&pT^1+W3()9(I3*o05`h+TA)I2g`OvA zwy56iMig1CBQpo!+`!ha(lEv*b1Df_iazpA$~R_`J?3dmWh@oDp5xa#k;01P<pC<U zvX4j&=(UPqI7{Qp<8DO4VfeGp3XXo~PLV=V=y2=l@%pshK1WbWA+Zq!JK1BTi&<ae zcfc-%YUdE&O_$LJyrzv_hZl$^J%&aa_OA^4I^+Y*Xc-q~rE)a;6J8kv#rCGGvXf2o zfCTRF;Hh$2d9NkWJQ`<oTSNp~#^*hc$SGCA1%XGu10#slU5J0^rm*4yxAr5Rirq_< zmd-KjFXmCgmW5*v+Qily8@N+!*=!FXky<Wd!z^vkBzjBWS&=-WK<68kqL?IAVwx<G z$H=f`?wS*<Dk6019R-OZ6KT13($ylG1Ofu7<9bjOgZ{X?XVG}&z;7P4$Nwy9u&JIe zN$>aqqxazcKX8Rl5V4!KBA++{8MuT_l;rN7JM6I2?jY3~&dM<|^+fwh(x&?fpK^s% zNc_k=)4+1m52yIsAd+Oq#nJzH%;p>vuGer5R%9LsdvS8tw7>C2#RgO5kND`h6&Pyt za=#3fOlWC7)U!g>8eA{nlOOfb1F4?K9|dT?D(=bnoC_zNDxaan*f6_GP%BnErTg>h F{{t0QkTL)O literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/40kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/40kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..bf2e737740b6eaa0cbd0d7e69ef36c0b5f79d9fb GIT binary patch literal 159519 zcmeFZdstIv`Yyas9Mm4D*y^+m#A!l<sMtbVg+`Xn&uIwi1n__dkeP~QsGV96im{kw zac0z+Hjx#OrX3T?K|m1dfmV=;w$>0}Oa+8iMQllkKqZm@F{j0Mzx22FzOL`D@7sUv z>)JYYR0wOW_kEwk{oK#}tjQlH?@~|2z9D^s^6~MZ{)GQglRv%G`iH&gZ&B2`byO%t zQ8OuDpO>j=_}gO?K71&h^2OhM@b^uJga60h7nBU~C_jAdaeOZt|53al{NGdLZ;yUG z+JQ$q@Ms4f?ZBfQc(enLcHq$tJlcUrJMd@+9__%R9eA_@|2OPFV*0zOyL0v|c=;u) zcKXrjQ*6T16t&<ZHh=2xzAwM_D)qk@gr^RWU3tVHkX?B6>(LH8+JQ$q@Ms4f?ZBfQ zc(enLcHq$tJlcUrJMd@+9__&YJv$KoQh0dOOOa78y}aP%Wl{M3(yL_gGoV8t%7kfu zB>$R*e}iA3sFy17|5IQ81Npk||NQ#VUpWT<8gLIL@~uZ41KEW~zaH(tqaAp(1CMs# z(GEP?fk!*=Xa^qcz@r^_v;&WJ;L#5JAGHG?;b|~=K>ddNxv9_j#EkKu$O8(<zwuu% z`O{wgm$6^JK6#7!FKYU<Y2-J4`QrDCnKNei`p%f`=l7eLkI#Pm@yBLA_Sh3o20Zn| zlXISY?6IfjJvC?U)6YEf%;Wy^e>?B#-v&JW%+ur|KGX3tzB6Xcm@(_=Cmws^>Hpuq zCNEKQW=_8}gPQL10yS-p&-6JylUFD{o^}Q%FUau4fB*8ChG+bZ-^^LFAHxUgpQ5Ju zOrJi@cRG1$e0o2=Px;Q75%9a0SN&#g{Ga_^$ap&Z!~D-@3Vwh3@-qq79|$Af%*>lL zd*1xtKKoqoi=vQ)p|8C9+Op-5QUA624{u0fq_OKaY}}N%dCS%vsXO0F`%C)Ud$O|M z&)F;Ackpk2|Hq-jNB+sG3kr`FeWLlaq_nL3L`7xQ$unoq)qnZb`G&@CzP<9@Reg)0 zwWG7^Mt9E-Ki>T5=YErUz;bVJXw+sO8=r7Ibh^m8e6Y^{@$1)x{lC^V2kV;V>pR`o zkF3jQS`Pl3KF4>)?_T~*z^Zt^KWEH+A^gLcPyasu^V64S2_h06Jo9Ge_1W`;uly7| zN|rXYvj1-j%lqG2+5cSF|612g>hbBIo90ZPL(!CnQ_8|*y_}79T7oxBQpdC@-dCy? zu*>Q0_>1&7yJ4P`<{~$m8f_+gGh4XFsk`9qUFANHe`<A2#ePoh&H(8Eb1O>C$+?j- zn}f5r7tiFbyPL-gceknAKBjX9Hp;@KCUu*)f08mvLm8UeGD+1GPj_S(_?opW6Gn&W z#Q9FX{hG{aS*vQZ-J5o?#ba!CH`10830HgALT;YOFIvOzV-JXwdp#}v>Pd=Mp|?pV zsTK5K`6~X%By~g2*WjO_d&!gPhVJ>WihggJt5N0Ht8x^ISz%64+Q^_b%_=rFh&*Gq zdrJ#cznsRCR0?bzQ389=K6Y<Ei$_@H<2D3I1$Lorl9G!?hUoDOXNJMuG8E})9?#dW z*9TH_^k&Y^$*=oqg!z+Hn=Cvwtw@*|FB+lcJZ&;1F*|j(YexjQKn{1Nf|UxDQE57J z%Oqtta&p7UX-sD<qg!hiw+uBgwvGd$>Y!9@imS1Tr@)_@_4)w`FN3p1hD`hJlwI#W zKS`M@MuxubVwtws(*qJ;ZJOuY$pCRa9tw}h_na-BX>yN?G-muDccv7JNat!}Pn+cV z`m^4hl!X6DepkNU-5e$x-yN?v>qRbde#f%KnGzljafZ&3!HrZKgt`m1duoSm!yd!M zDC#tiv0Xb%XADRN6eChv9w^x*((qv&^l&*9y}Vz|X}ad<FD@U7F?lWCh)HUT`8sb7 zb|Z?SZ#c0n_ZsVXiWKjj>Hwxjg%9uX=q^lBEd`W3-^nz2O)O)KQnzD|hL0y|WiQ0^ zwN(jp?cUo36mv`FITY_y?A)xR!x>ll>QNj3cjiE-goo|nPA}xrip*Ww+zie-N&TTK zC{43+-u+a&kd=kwD8A+us{O3=;PG9O7hTlN2OefLTuDc84LzMH{_mE`{0+VtlT?`` zy-FS+XU4C|mf~A&H)+p)re=~lQTWT9XByS+*SO^){VMNo7}tPJ&fvjM6lOT2Y=d># zP2OCCaMa*eWVy`8ZORyXC-<pbXK6oGnYBM$zvf(L?)iRqmfc{IE8coINm={6d#c2* zKfbU2Bb!{iLq7p?Sng?dr8y?4`~TKCMoKkJ=f{2&*i7yvxAQB!dnT!yg}txa?62+l zpy~EkV%2vy-(emU?b@DJWRi(ALb#|~&3T=SW90niC4b_6crZ3c&wC&ddF*&fowxSu zWhu&-R~KD4FPPfi93d+)!_Mmj^<7QI`RUPVnsk%Y?94Yf;E~$=o}zg7ZT(+g9kFT7 z8YZfrcitCFQmfV86f14kdCt~G5BW#CW^zo}1>#z(dU6e7Bi&~6G&?N=lBA2}{zWUw zMma0j$n>?U*YNg_1*H&26sWyPh3ag+Rako{fumi6o4@*g(}@?K9^bvrE^ZLmX}Csl zqsqHewnH?63-@PldePh*rs^;G8*GWhkKjPZH%tT<@E0*|CDLrKKPlxs!7mz+Gh>|( zhg+hbHJFFLXBY>3?dzh=HWFg`T+PnG*sag$dtch|BQH8NQ!yfQrtypH#2_bHRqb{m z0+oJE7Ryw7Emon5^I5G;DVn5~(8FaJ)|xgxU&CW1_$~5A?8Ek%l(OC~MQSF~M!TI7 zmjOqnL$HxM7A8%@mEovx>JDjWOuyaJd`G@}l1jR#;`T8$>UMZoAzu^RW2NQT1XUZ3 zwcrwM{<qH7A#)A}hs#Au|L|D?si(OYW~?ocXUdr-75AxPMCUt6T~K**^9`|=5aO1Q zV`3~09DG(~f1Yey*EC6e$?k7uBPXeDsZf#TjZn3fwjaD7@6@L5=DV7Eum4G)lpqf5 z7LmJa)_!HXt8!#2?A%r<J=!%%y=(Uv!y@}hfN~p`S}L(3cZ;Xl?Q}Q(DLhh)6OL&A z5k}J!%Z&7UZ^P@bu%Q^bTOuUSsJSl8H}Z>w#4omxAY}B|5rgc4^Qt!QZDv@AhyXLb zUm)dsv+M|^c3hD2Uf)F*(XQsOQf16Y^9>`MdBkH}+Ft%Ap;9)Ee+;s#1|&j7iiQvO z9-XABl~N&Yu==P0F%Hi<SeD;8EmFuX$Fhm99xLRHR(Q_g)Ek60Y*KBusK{+}r@M_4 zLoxmMvN62yl29oXpZ6G@>BI++yU1DRAV80G=mzA9q)aJKkv7t=l!n;)VX-XJ6MJ;Q z!FIdA)~{-3Wf9z`V%<QLmJXMVG2=R$vF(I(SK!#5%WfngN2b)*CYhv41}CW@WFX`O z&5aL{6f&Gzc#q}ZyA$x;#kg*YRg6S*thvcf_8ifi*b&Tb9qryJ6^&R_4n#v5c{nPO zQZ6UnP%uVJwE>$zV&@$FfMQgPL~#GOl$R+LS;fu02(>Y|DOPoY;@+C1!eTldh^!MG zsxX9WcMD86!ogVZ)9>wO{Sg@>L#1?%+kh?ol9e;=gyNawi&DZ7zxSGyk=P~@eJwcX z#gmk!0?uC^*9eCZH!ndvs4Zl?smN7yIPFZ|7*>jFFc+$)TPCUb+nmo8<m<OQwP}+2 zsMI!|j)eTCB=GG$ZM{qMfhmZ*u>2E+3ElWh^#hS6n9A1j>k+pPa+)4#;1%`Y*4<XY z)S{1N8~>7%a-OA^IuN02PAxZSKiGU%IZJ3W+36eIZ=ASxTBv)QC95;`8a6F?SAG9` zshP9Muou;n6g}4QMOl4wqpn@siT&&^Ecc!J3zk*>=CzVY&qEqph0T0e(}!^R{<6%i za%L9`qon}{&f00C=UmAXu>d|2_>8&2i4|tAzw%too*#@J#hZ$ePlA&BpRY3A*xk>{ zg?UoXB(;>=;w&^G$s#MB+C9fOQ9UU1n%^|oXwMi~a@92{cLo-;bwj4q-AXG}uJn}w zOtrF986{xL*jS2$qY|mOdAxv`F^j7`Fw@g|nwRg)l;?A{!~J$Vg(e<(Pv%Nn`M6zt ze$Xa$|1&RkAJZ9CO>L-uI=@rk9_{*&cC{+Ylt+ZXO*7%oGNtSVS$LGdYsQ`5DSoWG z(R@2VF*33j4stC2Dwn+N;zeD;K`z?D%3SHe($6QUw|be9<jZCRx5XA^&D$4wYUz)# z;e5l&XI^2ZZ-4u&o^KT!=p25LCv($%)i)m;>9-5X^=b?M!=xw4GxP&eei8pzfuuIs zsT($_xtsCwoJD`Uda?RJMdIlxB$dN=wZ1|hdP^#HyN9>II}v?ro*i$4g`3NC7Z8EI z6mj19MejL2c<$!a&vxvfi_&Rb;9CY@2v=*dBS9J*l;Sy8d{pgV;{yXEGH!PD+&}N| z-Yy($elpGe%8IR#0^~n)S%x84o}+QMj@A8xl?G~02?1kf39E{lk|W-5#c;Aaa&7Wk z!$o~N>(vh3g;U#bXE{QHpLb8~2j5+vq^^AB$QGZl93R?Rq{|52pp=J3-aR34H!NCz z^hSN-B<0B5c;3Rw#fT`IuNx9iG4j~&j-NP`9oUrtVAX=ql(_Y}6Va>2YnBhFM2PLf z<@=JGc29i3L^u>XcebXlEf-ngg~zmME<*@*F%v=louQb!lT?hlP328OY&wjmq7fy` zIv}oB1ngdq6Y&I@j=o!MlV?i!Q#s3Ao@hs&O(k(yn<<S`j6}j$)VZ1ROy=~;c_!uZ zyIR?}BE`DsHCY5)*|-$Gm?+Y0>c7a+uJkt^npBLdk*YI06=_B8#?yWyck}5S9y4|g zUcN!V;<<YC*qqKNmcAoL{%|m39S4?N_M5tUH&cyZrmT}$oPc;FB4k$H)C(t??M6rb zBz1|FCl;##Ep0KLM(UfcV!J>aNq5TwaMh#3%f4l$6Pp1d(zZp_xf)>WBg2n<bJ}@S z!gm>6gIka8Gk&A79Nc=aMd=?62yPU4&SA^4#~D@GB=ygCBZaDVTfbf0>YV@6FQebq zUUoM-)5(vfxm#WCD}BumvX~|UShPBao!b}Be?RGJw*R%m{Wh3h(dq~COex=Uu1ee- zt(*8Qz@xa?mF{lzU4_*GC$wQ<@<~cOq}L2cgCzrUM1F2-oUbC4l_kh^7gP>rXvp80 ze)i$e?KuFaE9d9|zue<OK+<-$A}_|ILV08EQb=%yIqpVEVDlJVmbD)Xv~;g`l5(c6 z*O#L{$<^+Zm<+x_DXy>B1J9bL5OQ-iKi};9fQ0F6+NDBlGsfoa#q+ETSS2bF>Y7*t z;V`LyEzS2BLjA*~!fFKr+>^d?j=`<EBi9WB`x0P}?J77U;{ocF+544I6ba)~-;8Lt z-E$)-ok7*NI$zIY>>UUE1rBYhHhCK>6(0du0d`0mkeYAE!VsVCY-~n)_C_cVEYfpd zTo?13*qT-DW-e0VIR`j}2aKZX0OD+(*3^9Ge8f04N<Ua;yYg^<pOD?iIMXMowf86_ z^I$2DX|kEB#K_age=z?<{2^|oL@Gzt!)5xwIhT1ssjOVF6GfwxzQK*eQo?-XZ%e!Z z2hz_)iL_GkQ*PsUfzJy}Woe6=+hQ<x-eu`992U$3XJ<K1Nq9jix0Piv{VcFQ7pKKF zGo`D8Qgh<<Jl$9)C;#3@sIwcrDW0*DI)^ol`>2YfaBEwoP~C<)6BZFxrfP%JIMX)v z!>hc>o0YOV(v^Ni?$%tL@H2t3SS!V6v8V(&!Dj3M0X_hvs4cVg0sd+8^{cV9vb&WY zBaN!K&w;bkaAzI5q5i6VWh5;Z6$R35Q^+vO$Cp8IxOD?7H312P$A;t!aP?nzCuG`_ zqn*eH7M&(Rj!Nh(aj(u;rS#%HDi!E&4{EXQ!aC~$uQ~4HDZ^bC`rSv9R5NzsemRvD zwQ=ld$||5WHd5STs@w6vcT}IvD?-s1V{+0B?#2f{2<<N-@MI4M`Q?$)7as)J$l(F2 zp1iw%$xpI*gN-ZTcYm3r;seVRs}(6lTpgB(vpb3kr}wS5C#gB7mR>Zt4a@XmQm3{) zs5|t^t$Y1>BO@`m5^!C1=eHG}S0A)%73KS9=#g^8EqCy(_QK3sbJyk0_@bAu4s92l zvzb`g9SLvGRhvWv=P|lkNBaVXwA<_doa3uV`;oC!jP`sVRrj6$-;RA5zDl5HM4Cy8 zAGeD9ku-eOvwQUUOJDW$jV@$|W+Fu;x*NaMJiqFq-si>B+`kwUCL;KSZldF)Z2!PE z6xSZIP_uqp;&$<aF5QrT#WPvTMsG;P8%vC+H7=C5ro5~-64+=pzcsWyMI$Ogx+9Rm zay)x(U;0_2P&a05J304<o5>7d$QBYe49nY2F5aQy8aI7eUM`=5@`&5`*k+F^{G{mz z-OhliFw?l~#$l6Jk62oAuR#+3z|y9=(ydJ`ysrpl*96AK0Hz{~$i}mO);*Din0K-h ze1^+G&ynZ%%I6wH8j;H&s3~h$C$RF)F+=?%<lwoKI$qFLsZg7S3$F{k!ZaUjhcnVQ z^t_Dgyi5W!fgB@4*Ujdz6qE-ENG3v^^U2b@7?dIg1P-t1X#B*pxV?UWX_NJKeBn!M zNdQM`L)s3#5+D&qOTeSt$(^KJOM!%7i^~@PPNd<1jk4bBJm!K5)^QA%vbb80BJdnT z7C(<C%)fDjW<Z{JQ*}Vh$X`HUS~^S?hFv#TIAHK6vWzRlhhfETm2(i(!^ume=w&6( zNy%=g+Nw}2pz>slu__XJdT4wqUdRlglE5Kpvo_E4sCu2`>T>t_{!%0f;9xkZR<}Yb z3`*ipfM!a=kJH?b@dm!jAO?`<K9xA=zA8!?(?JUySxk+$k7S$LLg8*c&^+#|q@8KO z5_1_0-|WN}+F~ghcTc7#_NDS|ooxplL0FN=&84|obK#veSP0Wpg0jIm2z&6f4AuG! z04iFX*obBz$Ib;G3Yk8mP@787lZUaiS4{oXu}mpSEH${0dSHQel{Zx((IDvC>Gpz4 zFx?ZRO8nde&z`8zNQwp&c5f16zg8*dl2Ei3f!rzLyYYY;+7`Iz!`(RggZMz76QP+< zO7vdc_%)rMXBwQD7%JIt=5`f@fbBq$8{=sZuqxW<H6a<KGEJ<kzp}3lxN0oT8tPv! zx^>YopztE?k|j6`|Flgz(}XMJcg;_b3Nw)>Nf{H-W<x44-eGjk^iBPFQn4|N*c^&4 z30&0EytLg;KQu4$@#WGq?&k0);lXy)A6RL@Bo$#%bDTWOKwByv#J@L7+#HS^;LPT+ zQVVBq+l$BD;t2=_U6zK}&@JU^Wg{D~-Jh6F_%cX%TQ-WkrhttNWEu3GDSVO>mm=Zk zTMTYgNKuK?zs=3?Wp@Q^dS%|LU3-6C;kp9f1$|S<KlIBxVWsMJHpT+G(mRGr29nCx zBrj`IHU=*HW!@PD7t@dDlrG?qy$M4TbgEp&%aqT<HrYFt!`imI*7(kzUdcpruReiS zabob|D-Ujbl!4DWpPap!TfBE)x2zZBo7)&3a~F2vg@K)56N4wInIFy1aK0a~3e1k@ z9Q%3w!-c1I`Ey4=9|0eVlu^b%)|A%ie(wI5E;8RjNYcSPl$DdzH^zDbQ+AuXt%o?D z!A&n+b@d#1N72L6CQZB~bGQCylz-4OcNc$T1VxUVr`X|jhJJl1WUD9UbR!!nlnMxi z=eQHH?#-UIyjh_2-kaY&G4BjhBE5KOaQg!8Kgi%lq^a&z1Jb~-gh-7f$u71o{e??@ z(~vm+pEd4SmxRO|WP+1?+qD|hZEb8B5c%`hd0CVkR(UK^+<@ywqwb8?b7x{HwW-q6 zAgmI2djoKGQPuE);BcL&uX04^C|nS*Axn<KG)4*81LUN++LJO7qS%s9xzM>#w})$t zgUu9iAT_~r#uEE1<NSNS_syJQ?y_J$Z70@G#Q9(c6g#t{_=h`&X5L@gZ$}=0UwNJ} zII|woIV%H~9u`MVq}<u6u=zXFgxPIC7V8AH&EINY^!ELT&jX1cW132@1U<tp_dG;O zpe<$DiPO~pIInGNUJ8z*z_0*&-z^EAKkZPF*|5IC)u?Xqnk5OoAX*y<X*8;zr2e{) zmAD(L)o=RuTD^Cih=V5z@1@MPcn8Y;V84u?=Uknb887Vfh;X$pMR~}4;s8nPnommK zAD*g#3A{+;YR_h`Nuk%N9on6LmAP98I|IffbK_%M1S)O|(l~N(<CS~j#vy<BC1*Qb zd&<+W==-MlpEOHkHy3zK+28eT?RG?(M>HGDPrwyVJ|D_`#zPkTq$X$klc$xgp_zof zB23z%EAyInHs;O5>g0$cNN9<Gfq&<ClhogsSapJSlKN%7jj2A!Z53y|-B^>;NuarX zQP_@>tGPCypQVmMevya}aU>C@M894)4kX@R!C70Bi1h9>&(nJzuMTe33`qV^lPMFv zN3g28&DLKs+=e70o$F0Q2+NZ2!DkB#si555CLlp!CSmMG?nH?XBjJQ&#W^zVtObCd zhznjb5VV1?P7%ekSwxw2^!@TxJcR_6{J#qoOc>}n0l`_?LcR<6{&w-K1(Q@9z;O4k z`A|2`IBej9fY~RhK11kCdJretQGeRKff)w<n6~oSr~;5CB*b886T^>vi~I_XkZnwU zlfEP26Yf<D`hpp@C{b36MurpofB#^yc6-g#O={}Cs88v8_{K7Cp9XNd)7qoo?yqj? z0?f8>XXvnt-?1|-55%~=(Jy~MVLR;ZFh^7>_JSMo;IJz=+g^COXynenwrvL84uTA| zI@%FgOeG+ypqO-IRNgf2*-ETSs~Zkcc^NAo3qDcE!-KAzCsF|>?*jq2rHesD+J^hC z2M%t+wva4ZbCQ(=IZ=dx$D1Y4#yH@G^mz8Wpa?yUpJPwjqE7oF_pO{?rp3pH%QxuS zS$U{lZDVRqj@~rTZk??Y5SPATK)q3e8eO_xpJBPC8yZw!7P3eSx1^!V?~+DNZ2=|o z)#kE{pEsfe5u=K}aaEh<b(gm1#URu(?iFZQjNHZ3ZkU4yL-S;cloF#ef&36oi~hSd zTM;tNe_XLsDj>ZU9pBpjBN`kUuGGN{)AE&mur54ybqRnhT2Rcbn862x3mycbK`}f2 z88#11B65i|&$&|M9xOSL7_1+T7=MyQQnJ@!1<0QTFsT)^4S6Tu$;SBz3&Fwhts$TX zE&IR~3X2~LN>y{V3RSxn>5A0Lb$+hq@G?6m3p?N+;m8K=Qj~GCmB<sg>}G<8k`wJ7 zgSZj32H=U;l!0)OyJ6lLx!RfKLu;lwNU|{1cmTpZ&{rWK6<fxjx`?8bvOdGWh5*S_ zB>`6SxC|jOM0r4{q<g#2!vTKPd9zAzuN)wh&`8j^4I$HFLTMBt%@OT{nNE}-^TMh@ zE46q?h^D!1oYj#9HkQ@#m<eNB@nd{2q!zu9KTP8?OG0OwDlO`^Vx(kJ%q<?GmlB%0 zBvzyzQH&gz6)o#^DpIprEb8_u5*UH4e)Kei_^<@F^~7p>yjjQ*k)bm|wSr5+CK;nd zwtg+bMV8OmscKc5-L*II%JqAWc$~WykAFiSoEfm;D2LvIY@D%m;*<9p^;dpe@~*%w zRHVW@+9HP!H{QtJ{gh0|<>FT8KAxnT)QF|)e>#4bmBJg2fsU>+PrDuDccZTPeg&wy zNN(1{V=?F=svKZiPHuhJIMOY<Ej1%U)t^#?zTJHq_s1>{mT&yw*-z=q^s_^asvj0~ zqyhZWa<2C4J^$rB)_k^9xo#`yAe2b2u;<sLd>nQEU);}DAZ>6quxuswQoXuem0%aa zBiU7afYW4gW8x>zDZ~#yDBb&3O#eAM*Mo%vAxs?K^ZnlKw(d33rIS>~?rbo^ocFC= zK`%FVi`Wku#0C?9$?39-I&R-PrFTXWU%pT)IiW|Y5!!I}NL?w!DabJ`w4;qT9OAv5 zPf&U4Arvc9c-4pvY&s!z8@ZmCv3H7}thf{)<sV+0sxq;Wi*DC%5jN(5SYH8ZNnvYR zcF88+R|5k(6G`9bx%e<|ISArk+2;Vqzs!+1;4Y>IjL?{bmq}YuC>RFh*&>$_8KkLX zxrtq;BZQP<XX@LDFfe4_H)B!M5yFL>$Aywv3$)7-uU?oXunW9>BU6E_MrAd``R0>G zO{Wy$*BaXFY7iR%9DCMr$x<E)cz9txoX$Du%Zzsr@Iahqg-``(XX^kBmMK4q$8rsF zxvi;Sq*Rks{q^S!=n0^)k>DfLuGU?Ev%#IE!2KQrZe1jCp*Jv&kX6~wN<D^X4>R`d z!+X=d>ry1?hLNvp^Kpy6B6MLL2wunVbbU|DS?R!r_g^*$ZD8WTLrsNH6co!=&RYN& z%QAf}gAV|PQJSAC0rmmANBSJf*wpvXN)?cPN|7+%nMFC#2*XBccSd-be3Wh#dOjK$ zo+IY2xrV@+O!<3Kq?k$Sy3U<YGu^==KO4CpyN+F4t)1#fg+(c2`jrg&)A=0fa|MHi z6$UUpSYw)%@8L!Y4=866e??pPY<o#eKe{s(BbVEJCmvhJ)zWvQFd6VW8;%+Vq;A7p zB#ir{fNH*ji+D22)a|74afj)Yg;#@MTl$cMug!MSQfXZ5`ySx~kwLt-S$Q^3!Q>A} z=zMs)k-l59e21OR;AMafrgI!aR}`s1NpO@%aqH1gsrv|M9h;QCk8D%2oY)oV-6Js% zG2wv7=&Yc62qz`Ottb_@&45KIk~dxgD@DMlTxaj}?hFv-Uq-q%f_ewh?M=$Zrw}un zNNq@>)!w__+Zk|U;<69T^AYDWr|5(na&@FqkU#(w;B-J<+7u&L<v4Rec?66ps=+M= zH$eO!4y5KAK$?JOBtbTj1zWaBsCMLYc61j;8|#ENiAf5Sf;3|r{Lr*LoQ-^yAHnUD zxY6v|ml)~iGCD1R@AIERS0u#^Ub6pA{mTUnN5oE)CsU+2>dBoFo(+_pxN)n@ncj?2 zZR}c}l<TF7xHB>LSeG33u|?$dR4(h<;Ird?2RShM{_zMSi?+L2B678+GWwPN=%%g( zA5qR94#DSF&d~>>^>73?@mjdml_uo@0YMt8_k2Ib^h8l=ZmYbImv8W8(QQl0|DMp6 zBL{?T-EipNze{1GY9GjTD=4^JN>RMiiX4F418>j2&Ql~6>^|AB3}H1fK_b!w;(p*K zg8dK|kuwK5i3Z_l;Zb}mcysaW(N2?kKcCe3$LAQ}sUbcEV<!kyuLV@^H3U=st6{ob z>MrIoX^gOqDNpXL{^hinwK|Ssp~}Q1D0UD@zRWU4I0}6F_Nu<Qn8fTpXBUEY+$zu3 z8wSv<5!4>~Ci-ReYUGkIK<ad8JGj|j{p|nbZl&}-E%)<`6<=J>o-oXaUd{TWYa|5E z_|z)@zREr?v;^CA=u6}c)yxKRjT%-2^+|WsN`#q-h{H?7tsU1#E`Gb;7ws5iBOpm? z-#hlJ=)xEqg5y|!0Zz+dt4~w4pH?O0(R8~CEn1+AlhXY&y5Jae&idA@r}WWCzoL_l ztwH~)1+AqQBd_{%FO;#%g=!$(cqB2X0U|h!K5oV$>py~m&<ay+y@3Au9mxc20&80I z`RNBe|2X&hX3u%yg$pW+UC21ow*V{}gdcbewE4JHh$fWB4$K54&Z?b1bTr;bWBtSM zDP-#Yn!X65xBr)FyFQ)PxQ+PoAm4Sa5}5{p(>VzHZHxUAG%NfjWz>RvL^-q)NL*!W zk`Yh<!nMRItHEJy0lV$(MU@3Q6kdWOH&t>sM7jYfR|lyLU>_)sV9AP)6f)chJ_Q%- zgdU_@;zs2EvQWq;&0~Tl|GC`rmA7{@cosVVEIoWYCFF60*G#Dwj|8TL2aYif^pwyx zBnw|IV0xW4l0NLA2rMXn9NE-1HfE|6;C>iG*x_aFMmK<1;Z=|o$s1T^9F4S%=TSx` z0s(u^70)i}oTSQ`8X{a6+`M(S=kImEDNNm|TUE$H>UKyfx}Oe8nZS0CG<71o$}i`q zbo%FPzantg2pK7FK1ApB!4!S1gf@y9ZGC9@RyR8Ci=@yd0g>m)9`8Gt+x&19a$Blm zweCTbc1P5q%i9t9I?-B|XCqA`fM|DaZgdKf1yXT5q`A6jJf+Q!C*2|m$z#Hv{Z+Ox zd^`eQw1<G!W~|o{tix#ZWPC_$(dgZ+BB%_4B^EL0hly(y$`}r@J2`{`1jMl{9$J$U z29qW7rI}N$@nhM6R0<(^NKiaE+9%`bKsR7zO9Us-HS(Mv6dU`nj1^<^+m`@DqQUVX zN^A^|Mc@cWbo3mFH@=9LXB%n0-#_jf0Io>{j7{>@op@kvsCCdJ3!Qm)Y9XQ`(Bwi; zO@|?CsWAE#iBPq34cE<J+|b=w=^GG_1~vKUmx^Riw?f2k6vTP5@G`V_b5{DZQ?|P# z#P0dpO^URrRHPnpt5_B0@4~JD{NtzrB5O_tfYwitqc$7AhQ>v^o9M5=puvi>;T5|? zMKm50QKHnFrip{bq5$ZcU$hq63QA8{_;j|QS+mm5b;ULm^Cxw?TXzAWCEibCMh<YN zuMU@I`5;vnJ`c-R#<FtYzdG3KUTt!s4oNm-nyen&e-Yn%uCgBoIItn#sZ9o70(5Oz zIalwe0X#C72PkZ^uws^pK1_(aoRxEp;9>_hOqH~nf%O6)l^381qrSrKgzNCQQ(CYz zZ$uU9kQWa46F*KGqF<oH593f_j;1P@%?UIO_`{*h_?|92f{2u$wS_#O1hCOiW8kzo zd8ZIm-p&BDQ=+3NbP-icz1wii;3onUR_^Bd{*n(;pcXqjNu{DDRvrP1duIcP!is%V z8sRC?B!@Z<=+8iiVy=$+bOSUs2bNxTKNM8`lrLbT@~#fI<i!v_<IbGwMJgo}^4PT~ zstP3ld|iAGmxSbN3KC|mvKvTkCIylcltg_MSOc|3;@#8d>><<VPf{z%qR^zQ{l|*X zI{-AWppN>Q+(_Oeb(ybO_1bcxP-%9iuT}wt$M#(Ma@qEj5!_n)87+UK`hjDevePk3 znE4LLdzw`W>z+1+N9W1ZAd^`aZQFRg|1^Q2!EfH!yc)p7T>e7*8?8s9md=uzk^x)5 zU#I+j7xoHFDtu^o!07)Uk;eUXKJh3M8|&J(S!X=0lr2Sb3sl6trJoD{EZoFeR)pxh zjO#Eescsx<4QL#+$Cje(3xdK0P=c%Tri^qt3P1i>DqvUG_00}#nkM)u=|m+^rE+9B z$WkeHif%`-4)kcu`j|#f+}2U1YXP_fGcv_U3RK<{uCr=djF6D467yxG+EDrq18A>J z&F^Bt6+pijPLG2+aV<ssy`!+5yvx6E5IwAB@BGz@B)~Cyr)QGVxh$)v>M|pWI5}s{ zEdaB@E(c3ETpr_R<$8qy5;MM>(L9QuFe0)X%jUf&74m_F@>GI0kbdY47-Na72e1hy zop<uCbU^B-fsz7*lpabzn^X)TA>n2$8r0m738LNQv4dlmP6;a^+fcoLno*m?GN#zq z5~Oqyi2%boD{977XaU-U`Pb<Y6Ci6J&;?{)H1|;{2w3pPgx6r>&D;oL5y17@ekFK> z;%SjnWEgJTK<6aLb>~@7WWeCSFgVdEE_m?x9Dp~3z&2^fG-A`;@4#s{!Iu(AE<?uN zh=vRlMHU$D;(H)8k)eqRPm}dt9*{<pQsx*d4d#>3C-S~xr<*~}Lq*95p%6Vk6iH}2 zxo{MWKGFo-5y2<`ilbz-?xtG(TcB&pWIAJpK=gsyX%JKf$-*Lu1*7}tC`|MLy$Q5s zNByH&t!vV?6Br<8A;GjA!CLuNk=lVmxc!6_0A9!ffP?&qIx2!e-iApHAid!*it~UQ z+zrGh2iBYHP~)B_px07Xz*G~INcoF&NbG1NdJ%l{c|mCYx4=%nmbsgw;lESt(p~SJ zR_I*%0anoh9bEYoQwdtrAhL$2z1XmiQ7u=na-xrOvU1#eLmDfq2S<m_2}n;s$xHUW z-`>0&>~MXpgIUym;C?L<E|;Yh>sr_+MxnTX>gT-iehQ)KhZ7!~q<-84_~7JHJocK; zDm_OK%t<Y+S^a5&HWkaP_ExtSx2VDWqHlXm1wW4Px+pqlb%tK1_HM3RfTk<aohc89 zz|($+?Xty-T$kgR8ukERXxk0exer)xIW3n#d&4dtqWi1BzqGSpR8W-l6|FCkBiWk` z39I-T#BKph1=+y669-tl9(uW`G>t88hMe5dnSWi#CC^&<c!d*UM8tsjW>@PLVezzC z*z{WFLPgh{uKe$P(7r02q@s5MjK_X31%-Cf-el5#_nN6_I$}S6cwv4g5t4zk&N2u~ z+e;wJSm~c9Q9?n0(66vH@*jVAa@|7Dh4UUaGNaj$G)4;fl|g?8#9fuW%S-rNeFgVn zQjuq$0k+7Use357TBHcnf+OwTid*|zd)C+PeQU*=SJ$msXEU8sLp)vlWI&`C32q~f zBqfi2fiwfQ+!!2V!e?3z5*b-j@#9OwDnQsqofZb6xs6UfN){7LYU7`xRI?xcyzWW* zjMVK$^ve-~G-&*-wQ0qElmvZ1LrcUBi`tus-l}xJG*@3~2>O@VD4Hn1w~PS0;gwSF zX9Egr0<I?Nt6QOJ?~6CAZ;jq_;h_69|2s0YbP+1NX6cIYLsl^gfUu?s37Y6(^myU> z^IyJ~ki1nYDhl>YmH(l$tfzno?`If<*_QC+4FM_AKVEL%cW9!pqKNNG!e%jVqr4Q| zyo-~`WCG<mH=E%2@@!#F*XBr-Or4Oo*JG?F0d0Aoqfof72Kxg^chi~IhrXUM2J9ah z^2OJm55}d)wMn`r;zzooO?QD>(PDC@K~Kj4k|b>}tdT-~2t1~<cf<~keO4P32@Mw1 zKJ(j?SyIdzW#Oer9_`9964c@H(B*)d+^~n~i4<0as2#hB;#%f?G77wQ9&<-x(Myg2 z7l8&xp8y<6Mg3`|)TDxuqo$etX_1xg0`4mOa5pdi;XfH?8nVpJELTmY1cWPtstXi$ zs|i3obm>w8x~os^7&-br$G0H^jO!e>D3|-EI;%L4gk8D0N579Q`kHVRi-(7-fBV$5 z=i$3+;M@6#Wu#l`N{??{7o(eP$N|j?YIwU;U=PtsN$3oYcsSI;7eZABT@r{#IU2CI z-M(K%1eW9B`?)kLaG>(QTn1%+BP$g<<U%6Xz9SW~`(4VJC}QNn+t@qHk@r3z0V<p% zCZM|t9K~|d*v9rneaJ^@Nr<sYR^?tcDeP^P{U4%TAY>1NEs%wkPKgAah2k=#p`z7K zDJChdF&+)Vab}|9lwJt7g4?%|`a;p)UIujAWE%oRYOfM7kdXxHp`nAjAnGQ_0CMDA z?@0$_2>kuUvjUc*W5uFvu@QaDA^$KM=J8)uVa?d7tAnHZGo&)qxu5p&wMmio0+JP0 zZyK8Lw6%*%%IM-d13(*~Acs?g;tqryj)hk-y@mm%bNP^L{ADbW21~ru@j+-4+Q8L8 z4EnS7%DacSebSWyD8BejrK#EAQdoIL1<rA8KPYqZL%`7itDZN415oZBFF^W-zsK|P zIXr-yxllY4Jv9(Vnm|4Br${3M_0@hth&DAOT>P``Y%EktRoDX5!)P&lRSagf3{RM2 z?nH}|Xoz`m>sU(QHK7&OW)Hyu#)^+XsRNZubgbHuMesgN8uvFKQape%gJ}9u-5<*) zxQ~H60{Z=kHg2{GjqEA7D$Yq6LI}}j`(lg)R$MZraCwfYCORw_8+zOJYX^|V_c7I# z_}~_3(gxsm%+N$UHlV;Kg~+30I=L+fzbPX_Qi6%R=j;p5`8>^B@S3AxQDDWhh!);P zblCe{m}7wP{I^oJE#@9B3O$#ER{*3so<&LMqJa(C{XxV);ReA$N$^Un5#omRceTs= zPtJw9YYp-jmIa<Va4eHF#coBhPi$IFzyJt<FTUdX0gIU?sQMeJU+(9wO5X)9@))^g zTbT!6G+*CgyT1TL9q!B@?a|^GKe%@g3=#_Cu@LUX-U?Uq3$qPfO>$<xP)8&?!^bl* z2a@Kom)S$6nH=j4FFN5Z_RvTnku<y0;^esN$86m6ezwd$NwrGj5QG(2S)$tzGQI3U zmTvGmNj9!O4$TsDoHFH+ln$j<TivI*k^E04sq@}G?<;kcX^l$8|E6?87KWo=PPP(F zyEL3!$aEDsOvn=((+GZrGpo3*jH1G}3_KyZm$JtJlp+L}_;>cTcQ;^6BL@(~q`OcB zbp~n9-7t_Q+;F*c8Xk5;-Ga|9a~3B4wgpmWP=VlKor9obA;klFrgMl4irXr=2wz!E z;I^0?J^)_XG}I0{$PkFsK5!M9AgEv=u6Cgc-ilfak_9k^Kmhm=9N$z&<Q{;a+M!5d zGLd^>HU@C0Uh`%g*00gKe2x=c9HOB_81*xNjm(LQLE8l2c_~tEuvCmeArtTeF4yiZ zh#}ewSa=<3Do6)i&Epx@gUZQl4T?4AU_3Y4&n}0@6eR#_T0wQdL+?#n-Va_I+d%vt zG4eW61F0y<_AVhXwd<(Fjan?l3fVbXDz+H%F-YaXcq0{k<uFwNe1Rk&_2?F(`+UdY zewIPy;mAk$#tc@FBp(Dbso=%1x;o(;Crbhrf>HTq7MK!`j5AlYS0X47wGsT19s;5z zPw-c9<E$@Gwt{;B%eH}NWe`w|$XC5VDVl7zF<KU3ML|EuN!ZWgk_ru13pEnf3sVS; z?jeMze5$Qbt!}rIum))`{1anQWoQGaaAde-ciapnT-vXjB8pZB)$M%}Jna(D#lH$B zthWnywET*+QQ>z+DPK=klV>iT={au#93w$w@jVc-1l<$XCJmte0%{pNM4N0PR0hxj zn<cqWt#=!+%Uk$PkQ3QrwLyrA$g9Osd|3$kAAO0>U{Lx{G@EqJfCCGltb@AVf^TQ@ z^7Z6kaLrB>#Ws{x5EiE6Ik8^PS!e;<ov6{)p&E;={t!PAAa3Z-!&Hjj_VnO=sw*hq z(5l=DR@KfQ&*;AH_~>Lz9zCv2eo~t(<7H2ur0R<EVk}Bf?W<J-QncM#NQfo26BfIZ zik6TtcOn~{86{a`N<d^vkQY$Wz@RtD;U=JshL%m_O5bb|cWCvid{oXW=feJr*5(f_ zgLs@IAG9fXx(g?D!$J~Smxy%kR;ua+>43aYoQW|XOgG>b#|VY`*+S%~@2A763P1=1 zBrr3m#qY^c?d$m7J*E4@5BQ^Y1cX}wdw_<^cJ07SM5BLat`{EkreGVxD^%WOgi1c# zM7nYg>FcH42C6D>r4<dtVXb+kToh3(G#8+VKlz0pX|LQvRfQr6@h<l0?A`~KBbM(+ znnA<kX}9nl!&*pqi9BuaxbN+;<2(NATz6LA{UytY!qMpOv?Pryt6%&~sAa4OCUFlY zsl)j3rWQm(&pBo6aM-yY#=Wntar=YDG)!Y^O1pYK`Ok&=y!7ZEUsU*cXHx6gVph61 z*GTMs@!;stdV{-hrvDcPejhX_lGTm`#Iq%#Wkm@LRJx~y*(gNilAA+KYD4hGOLz!N zIdnNFISN*}TT^c<_YRdI9DP-+GFEkdYm-64k{Dw4G|FC#y`TEvj};IG{wTB)Q*<{9 z9(?R!hL>QSwVy3iw_Xd1F)3ByF~euOnil0it%USTKw$Eo&U-e(_)Poum0Q+6J>ub_ zj;0m#L}48oYLe}{Cbld<kM4Rj|69v{Xzw2T!p)6oe-LL}<~_hD2-7($v<!MufRZ;h za4A*{AVlw_GoTnTFMB?C%qBBKCy4qx_NyJcFg0@6L&iU}%y8)6G7v|I{-I4aUifbJ z(3)+Prmp}m5s}UMIG-x{=uOl=U}xNoCQ`)wGp`c_nlLE&{ZCEsuRR9z4+1mxRTOzo z{~078Sm?6CD!=4%gYby~2~tFVT?IG8&@9mcb&w6wBB71d6`lK0K!BE|eE+Kt=D8xr zBH`VjlZPVnwvUc(U}(4;;R!(WdZuQ|Hm+eHB1;VdRPNp|@r7JBVMIYjbY`QCxeQ8! zEwEQgww4UbY?bn|Y0{5FCJaQ;wnB`U;mMlcD%}AkBbsL&I$FcSCJ~x=@nAld(1}*l zIXm4Qw-OLY1p!6GN$e!lepAdf3Pc<cW?~Hk@hDe_d>6H4KMoYUR57WqhL6j5%#ex9 zLR=gwW93CDkj?{E$hEl$RfOm;|C?#5BK;B!Pm*9g^m^S`9h&e)i7L$~(yUoI2VE;{ z4=6Jn4x&G(-Y7DF1=Q#Z7i&YP0>kf5TZ5qFPnJvv>mMuw%ti${2bDU|dG45Am8!c? zVc_e6!!gT)hFwoARX4y?ySWrsOTT>~)N@^c!?weSJ;4+o{DP&z8&PUx!eWuHNj#03 zk}>$9St=SCoJ!AcjW2l}=YJdb0jhtc+=i_(ECjW&L6JftN+J?6wTiI1@Km&S`@ZGs z$ap}h4#&A>Gm=s+s6$kZAor1RA^AiTcalnjjKhaF2iavap<p4E0eod{Gxu5{rAD6$ zTXw&!Pz3%J^BzS5@qQ@cS}CFGn$1*+^gBuIs-B;?Jynq$N7f19c{9Q^q|2;gM70!; z1;GnxT$83{loAEA+X!L&Jd|oKi!ggTZ3o*5qcL|qSY`ema(+A)Cg)C&iCue#j`X*D zpftJ_i}c^Uei9Qp7#KPs*QOTuh!Ky2r-l>KR%ameMX?YB0<#2D0g?e3e}s!gX41z= zq21{0N0TH;i-8oVZV7XXsSH$~TVyN~j*UiA#~fMl?9TwH<#5Mig)6Q=<cZW*3gIQ3 z8Cm&v<(MMwAYx9g6J23QeOrk&5!@e30X@c}(qE0PZ`4-mpD`e=<Uk)OMJPZr5%yX6 z)0FX!5J0~IcjW`Zxhxw2hc(|%Lt#&rk0-QX-U--=R599A#ZD?K`Wa=6wW$Hwp>Qm@ zX3u|0Z-N!f11c}HSNtQl`77imuJ+=g`bM_r+vqf_c#2aRJWjo(-_I4I42J%95b;z7 z8j_TS$5^oLbGaX(=t*dJ{eI?SRj8xvuaR(z3Qzi*Y9VP_k26EV&p&@W4d;z^X*k`F z#ZJ|um>+KT97*!lmXo=pB?$N<gQLT9h&~JAr9oJvJ@k!tkhRy18OM)KwF#jtP@ZAx z8BF)3<737s<+@EWu>2NOC$C}<Kp9Dn9v2gEUU(L$Frs&=`OEkgWT$W$<^~(tb#D?f z7Sy=r``@%9`VsEVTu~$`y7&s}OQ9P&|8qE=FB4Y;ohG1-WIHXmzpuw6wTKX)O`fpc z#u^vntdLhNPA*lOg2u|RLL;;LGUmHU%+fN=Kx6ifQgxEr2!d(jfqS{<&|&>`Xrnpn zG?ZBvl<*CAqowplZi~qac=>A$QlK7chWo+}s#Wb()AwN}eQ7(A;TT)W4lVZ_h7;LM zEbUI`7~{yWw!T|n6WD0br{JTJ!`B;Xkr6OGM|Sbf`qRszwwRQ!*WHmTcIa&i6cb-= z2#~)gLE{8wi{PboF4A&8ppb6{%Lm5y<8h<s5CHDr52fXeKLW;JgVq5bxeMgB{U;;E z=)Hm2d_e*kMJLAlUJW|ULw|-Sv3@D!Ph82A0EG!kE@cDg=^z`0Md!G2s}ouB2TWU} zpmzI;H6Z=awgSN9W%DQWMSS=_7=MxG4+n-)@m>OR8RJ0dZ^CFIv~<Clwp{^=pQWI3 zb1=D!d+5oJf{hKFH@(umI{%tY@$*z^L&ChJ!et!Kl2%FlK-xm7=uA)Qo6vj4h$5;s zd;7XX<F9$j4$CN?_o8L}L|u3!(mC+@^}rsD==M~D@tux_y8DL_@lOE9N<$;9Xyt;y z$N~M*x_Ew6ixqQaV??5mf~>A5uAt3sk)A|anVJbMVBV1v2?NSZln;N%v!n%&W$1ko z61+R(SQiKegf76vq}!kB30?*#E$nK74-Eesij<PenKYlX$D(P-=0Z5s(Nx!7_lMDJ zhvsv1fX^wLZnb;O8zZ7VVoMRCgNc5m1Pu#h^}xTxFwZ=VhTZOFluntFRm+}*Txybf zJAtWDA~9Hw&sqh^WU^FPAPMH%I*F<aN|5l_tqaA?Fj9(-R~m#c5sa%9c@@;dl+T?g z0M;M+IzYN|UNl&PR#GRnA@GI}L1*zaR1G9pw#5dJS~gNxN_0x@WWHWP>Po}P$Gzq` zoiGA$Au#u~_@;cNziLXN2KjuIppvLDt`EpF<JNrxV1^#X2SfPay5f@EWS;oq-%1WV zi&q^Wh-wSsNz{+?fegu&7H{Ac3JYjg<IHDe@cDR55#bz;X_IH55pZhvlY6!MpBzTQ zPa!C>g#)u2NbP&Ke8!=}V}12MFvb-&$-sWYqQlx*OH$b=m83^_-CC+8&6XHb?VX{S z;^ZBHy?-O(Zd-?cxGHYBMg%Lkck#4(-Ffhq1RGHs&>M^WS_~}){zg^5D%;^VLae4R zet1(4x8m(f^?&s%3Qz1#Iive_k?gs>%9$e~w=e)2)EEDQ(<akXSSkelUQb>Af<`5x z%2@LLL+%LA8|NM*E7du))pNu|`mx>2E!z9+mabP-P5Y&z&ritMt1(>5r-kJeu7}Y# z#2@q_exQ|?$S+qI8jB8lUQe$a{PL^B_oJB~w_}#<WsLk44$)6t{M}zJE;)@eIFq~9 zRa69wCuF5~lf(+JIv{~O@1EyB+#I*+r#A0vE9P(1E*IJnI~o>zOh`lVP~_KlcFnOm zmaC4WoLzTEwM(cTJpF_0j4WJM@6@^fcu{ek^VR=+f6p(v-8v(x_{%FQVBUz6w!r<f zPF^k<iZ|jI{ok##T5KJUff4!-8Qg1txitPPQYBm;-#lV@Ft%^)90N~{;J%E6QCmm# zCujfhFyH;$(4D{sy<TsHhR#PEm{KNLFk{^FPtUTm_Bp1#oQ!P1y_&xHi?jLuLsH?y zvJ5@%sMODMmO(JAW}_Y^e)HPtTMrK=e1XKyKGuLJWTn04<!zseYqpNRk#tOjD$$8s zg8F)ImB`iHkdO?`6w=-}(?{g^)oi4|=4m02ub|=MnRh>H*C9D1lKj74l%QJ&vJ}04 zaDykK(-5RkUc&pftOvnMG9LDDZGYwT-CG-V3H3_(lu(mMxtr`)FwuJBpp%s(|4S-- zKivX)0PhoUkGBu&F1SgRBi}0Nec`QZpY3uV5u&mM&vQ~S?K1DV4O-HDbfu?+ZE<F9 z0c%Cy*$q_gyUMNVLp;IO<4M2SJ~)~))sS6#PY3-5h|&Hkq1S_97FC-XBVoLJD*?Rd z=sx}r3135F9<`s15fR}Yx<)4DNh!hmNEU<T+rGkr5Ewcj8{x6wSL_wQ*m!ab<)_6# z%1?wuQFuhwe;gvkDN&Y?85UFyfRMFy)F`aju=|DEe+K*8@V(D;C&?G}p|bI#P@p-} z<8XU(C(<*6x5ps*1HnRj3&hlf+e*9<CuDpp>95OIk}jXlMVjRVe=Q!`OGIYF1oA?o zEYxwI0^uz{ch3POpax?-1T0WEJ`7pkQ#tk!@(dL(QFgV(>QL;)`J$_CL%zlU7Mdmr zDDCkokEHi@tG%lc7OVAKJ_HWnKvCyI90<MNJ#zNPGP;fc!5M=wrHhFMwBx%F3~M0M z*?2_6`4fmr+M6Tye1Nzkfr`k>53E7}d8E~wL*LcdAc{gc;j=vwiW0;swEX}@ozY%? z(?KB9txRWRh)=%$qK>ceE&THWQb)^C8kC|L-3aUob!ve`luvucD*NlnW8K%e8dLL~ z;c?R~Y$W=4D9LQ3%L$4GJuP_nfmvuVT}QnL$`GsXj6y~aM|31dyhKp!i%F^VLe>7w zcp4+1KUh!OwODF@9rVb=5aU+axe=YHh^PA{&Nt)6VS%ch;UeSY3NqT$t6%8{&s`F- z+BSr|)MpKi0pUbRJb1khyr+`x#=I%~J%haPrh6kJK-S_`7ypK=0J%~?dKkPc=HAmz z@p*!H&DXIR@Fx&P2pq8QwRn{Q2B$=5>6L=i_IY<|?&~HCJ;O+`9S}htjQ7@{Y>1m4 zBo(*j=7ZD&((V*$K{8^VmmY^!;J^|+cNS;&WuY%xKhQ#7=o5L*vKo|c))0#9RpW-y z%LA)K+()QKrZ`eWNk~@wKy|1cV^aPI+OteGm=X#F4B(NV1V?*3V7Iq-4hKFR!`a|o zBvZ3>v1zU&wB-bF0Ju=B0YxUaFYY(SLl#7ASM#03+T>lV<fl&-Ab+E}Vv$;H{{BY3 z4)OZaK-I)CHH7GBGFB8kxm`X<bu?QlFw=ZL4ILHePu$JTn?}x6L2KKGzB!aDr5twY zR&3t7*FZ%~5z=vqFG;K9M<IDYOBKowzyY8tzSmvZaaAe;Z;6vpl!5If)*~KjkhISk zLh(g-&JCGwr`Q0PUf7U7c)<k2C)|}}2PP(+0cA<wG4~e|eVf;PLV6N!62QqW&TVeM z7-#{r6EkZVRVcas3$MLu!T|j#bmXraknrF#%($_=n%M~!S>{eNcV%ux_~63~A~n7_ z>z!~y1cG=c)Os|+wlVgrz>`wE&gj?pIV2O183#v!-^=SU_y%r~N4yr?fP+L5@XQ1I zU7czMhsm9()?-QtM~t)2gjP2@sjM)psjbQcLjn0OHDh{v^s0@~HEc4~6UqYbG(wvL zih$(j#VRBM_aAj3&j^&5Eg?}xWDP2|iFDjnGGc)lxsg*49UMhKQ*jMl9O=xrNlCde zRyqAO**Ws|9esj)56HROc*zGhQU^>9fi}#pfW=T!#MDr*7EPSl(Mehm7Wm0?rN1;^ zsAh)Xpg6?k{pcb0d9%QJK+&|m1#h2;Xgi1v{4#5QQ9F6w`^UGFkxeI=$?S~Ho6^~K zBQTS4@NV_MH2*VLkh?MZTQ~OqR&0m&CML4z2#9d1=vz|*d`?T;Z)88D;+ly5vAM^h zQ#mLm(NNR%RgXIH;*?B8Pn0FfQg$yXZ?Px@Ogg--V7BhZ(=ZJpQ>rJH=Wal@@Mcw+ zQ2LU$CB+j#3}N(EJ|#T?c_|T}AfKZ<y9zY2A{RLWyp+?DSOzg9$p1h8nyrp+(2Yn2 zq!uSA7dEfqk11Ef<?lC7be#Wm*pn>Mfm1`KD%2ae+IpmAA`{uNI-?0D+!KqrQGuHf ztKnd*@zM>1O%mJ}RNTUN3JNzC`Wr#XibC-v{;=@#x#$a`r%~#?ow?BmwHS25Wd0B% zDPU9$WT+dV{s>;;0XEuYiN{OOC~yu(X!$1E+ABezn6{z-l1Oxuv9waiA~$aSY+AgB zNSi9U3ZT4#exg$Vr<N&Kj7bAG9!O>5C9c-cm4Z@7!ST{^JUCQRs|&!;ZZw>4L6@+g z^`B)Wpwgxk0%-}-KnnVi!E`aoAWUiy3C;~PLogFd2wIZ3Q2ic&dJrB}0N2eAv157} z*Q)<O(k;3^QmUOLZu}ft4geIcwyd-(_h0_M9o)XZVq|Hl*Yto<oPYk*YipiG$4?d8 zE$XN(WoL=MQeL=s_uS}rDor}Sh=INZ{k6E1mn|2w3WHqDRq1CoLw>OFiLs|P=)61A z^`iV8P{^E||I7!DOwxeBOG|tTeeWcVdJ0FPsf$Ye<qjDni1|6twyeWpRKoyt6W5yF zn28P)Ut{m7dAMDAKWjet620akT9rjjQEAur?LIsfGWLP&VRcxObAhV8KJRLb0G?H* zNJRp&p#(a~zWwRi33fB{Zr`eOo;J-o_5((!yhjjTYCpL2+(5nP5S;^a^&jfacV-w@ zjDLi}79(4H>!PhI)+E>0v$BV)$Ev_M+}7sKZ9%_a-_?PE0>y&Pcbgf}zs3)fiJ2uL zrA$k^okE5iX{dW<>%)C}1sA^PuB~6Ptpx#O0nwt85e9GF;qgk(B=xZ5mDimR9qjSe zk=%mi>cVyX-W{86?68k`mhLEn6AYtC2#CLPx%<+dlv}JkC`s+a$>K`Nrv7hxwo5)< zS_Zh_0f$d4`i6QVx=}>rb3)fwOG_@=JQ-r`&h%$m7e?<WztA^;iwzAmX}3Xr23`*C zsN6VQ*V`)tM?KXM08{jP<_@V(Z{e+JNu|God^wfq2F%CdWC)HJ-r}-|_e6;g0UAmr zApv^P2;m-X#eO&HtKC@>z!)Pjdic*DVX(U}gFWn*q@=&VPecmX%1y7`Pep|Q&BmDS zk_x(h1M)TuHAh57Uyl{q!#?F8TO?(0T8hLo!+RUy1<DVXL0GId$wl@BfJUa0$mlk= z(Oa<^%|0MaA%DC>wG=uaFl(T6A>xBT2#s+P;{dgzlY;@5eZkT|2DAV|gI29<ta1>X z8ftWXCEx*GI7V$#F7E*Ps;M;D0CMpx*$EJXg<g3XE{@kinAYRfPg6Y-KrV>vFT&Ze zAnd1{hm))6^E|zZZ>4Ws2LkeTiY~IC(L7lcU@cTB@lJ%2+QU=h*{d-LLTJ!oVWmLj z;7~4LCM<9D)LX5ZLAgl+>olT~ds;v|>FeO>%{Q8tUL!N05L`r2pYuohs}|%*$xMP> zgq|L-3yRGCN>t8HEr$A@f@2>Y+WX&2;Jx2`9zaA6y%SK?Hf%JO3S}2M3(A>zbT{a< zKNim_MZ>?XvO_kW-^C|qT}~TOxK5Lbudt;!D>4m@f_pdkg@Pd}3t|E?&FO9>Lu&RA zyetxIJ&Qh3rZnE*3puoAEjJq`2<_(qKEjDo18>%XNdo!-8}AFoT!;9Hk{A^MX$k_H z6H>FtaZiWW*5C`)-WV1iPw{$AK*);%0m{{UJYH6=mO=mH9b9`oiioaEAqMaGeX(ST z<PC;k8Z?;2X%35m;O5!^KKSA}+z8TB)Lh7`rtOCg=R!%2t-tcFx&_x*t9Af;*5HMe z2owO@p@0#dXM8h$QMZ?1Dq!VYZiG~C4dT`hX+r#(E1**W1|d@+2Ly<gNYA!w8WWn) zRV39`q0&N5BQMVZX{>8f<z_K;Q|jtYyoN*w0X1l4645YYh+K{AhAk>%#<O{90GfnV zD<J<G2lYSEffsfRqoMXjJhpM7Lt_EP!E!Lp20^nbf~a7sD}~BfKI}FC2maTorr-VJ zhzx^v^0EdS-gJra8#wz!JZa7^9#kU%9$1zeAu4(g6`;vB+?h-7pGaPY=h-rlsM)Ka z`!M`-fqqgpu-QPG5{PwXD(ee{y&Z2Vo1~tvivAX7L>L<92M7;ZyiXBO-T`gK5wQg0 zs~u;;UN*l{s(b|j2+)hX_Y9d)0&OGs|4Iy|uO&xqJ`OnfH@tQZrBUsNd!GM7;y!{c z!>O$hH;Pr{jWT$3n|0A+TmW86z(Jzf2{ug(?Z!F0ZDDX_=4Th-^w?VN$LnH$PVYTi zvk>1U!9!cf<6fNF?HY8Gk@XXUeOj~Vopw~A|IR?!2zpqlK_h_ZFfX{ZX-@F1O|@H@ z`BLBP_1xSw5a(u)_l7yM0^Zk3yl2%@Ep759H^CVI7EJJE)rQm0CF{|UQby4~y`+^c zKsyKY%`uFYrxqri`DLDL&lhY@JL)#`zq3U@<~D#r14>h#S3O)?OFCQ<(Ld|R4;23C zeQq0iw&YzopT?VZPbtS@NWJ`C_}-J8Y#fFOwaaKA5K^W2Xwct-RU>!t)(ScTYylqp z%R=5!#t2m_<Yf4XJW?b>!{Tko!A_b=3u<><FU<p&DZ<XK9g>Clhtp90HubpQB%e$X zG9&Bha}}T|*!5=N*e57}oaub;IW7vaDnbDM&RJ+_z6qN*N*C(hl|$5P2r*B;o(our z$&^;XdAvV^C<4c>;i0X)a^uZ1&MTQ1M7<i8(4hJwJJdP#!Uw#=>EEnm^`4v3AY*ux zeQ7<6afJ|7PcNC=sA!cAHoyCYo$i^MA=#kXj6AUg<^3XKF43bk5q)3L!X$ku^Uh|- zR8bo8Z_S%iK^Tm*?b#N&ZXAqqr{_NfPU(ur+;4t^MfO9xl(}K<@H}*U&Ju59h1r*2 zKVv6k`-5wsUQ)&_dHC7JyrE%8pj$0vVAKd0lLkZBFy2u)y-nSYsQ{2K=Ht-OV|BJ* z;JDf{2-D)@odwi67b$BJ<QZkK>jSd{C#_s<4NCB2WST93)GP_!nFYaz#3}^V$~!`L z&;EZ{I`_CJ>-7B(ic3@*iCS9$)5ahN6~CdSA~I0gFsM6n5R^nJB_b^oAsj=-)mkMt zhyf&YWr%}-Amph8Q8F#$kSGUD6Ay6)1pyI(nd$fbOus+&)s`|m^E}VzK3w;8UAH}Q zUhz-KLZx4o-Iyt7_*Hc%yv#v9as?)PD3xn9?q6Z%uXrVJb2T5%oox{MtXoQj5X~>+ zm4QG?I-pA_MeE`9wAP)bRS8a;16rVeSR_eY{!n-w@UJ()O}?VZN&9h^ale0K*N}@B z@0XK!?PS`G1su-H=5$|8f;5~hN5xScWG;F+K^NMWdScW*FKQ#-CRjnZbGOykxUPUU zqch<mOP-e$LV3&K76E7!PEfg(c9*B_-#Ab`ag_0!z`upsY+tHb_t9#LuV${-T0JJ| z7*}7LToify2CgkDB12Ng7Gahske|VZ)7_3I1`Zt{6MXU^H-)!iB<t+Dy4)cbwd0@| zkp>OVa#^}smWW?iAw;!l>tFak)%3C9daK)-$jB?Aw*VYh>#EiU!!%s9E$Q=F>&Iu( zPKW7_8(N$fCVCFs*lKsFVPV((*~5i%zY#UsUt}aAYt4NR@2Ssv%YS?AI-ED2pHydo zMPqKvC53tNjdS>NoM8;M9?zC1xBy;>|KYw-bN-{Re*MSn();g_Y5VdlIAI>HokZ;Z zcE5p157TcCy;y!VH^rFQmN}Q!BMNJ|mF0;(^p65ls{IT5UvwntM$Xo@%qQTbx99iI zYaTL7+MNG;)n=rrn2mDCdOvT>OEFHVpRE}nM<p&w>)NmNprnCyRjybYwoazq`U|)o zx|FG{P5yCJpOq+#X>zjYOZ=U~)^xmNJEGvB7|jJc&F}f9`B0;8btbc{QO2HcI*JJn zL!R|~C{+Ahx)^*&%9eJ#EpF-@adb#x`j2x=#%G<mIvN~@<0-YXJ2Yh2W5Y>q%U>73 zB1HwkE+52l3_WY{!KFrT;zpxSS5o<mbo?;|?wa;cac*JhY=1*1TAwnH>KUEe?H0%q z8vtMp*DCbSl_!nAH(%5v7exp(*UjcVcqohjL?JuWkiaWjEsD>FjpM^>efR>ALsz=i zzl~QaKgHnCMsteU<#F+CZLF1olLQX5ooXX~J)E!M#@YhBMMrVowE2V{^47}F3QfSm zjc7^zv1-wGgHXi#h_Xr8B^kC9@W=dLYKiiff$3B&mnV@CJ<e#wBW(2jb|JUO9mHCA z!DhkH62bR*>p<bB?3N(rVyR{p<k0vY&8vbY!#gElyf`rc3klT5_k%dLYLkZLWW?qx zczYqG;)t(?VD6xh^*a)Mnn$DSTeBA?&F;*4YBTaea=5-6@P+8;K_8zNoY=!x@6NMU zc2=F;0SWD9DtE<JF5ImJ$^kAVE_^l!;ll#`sn$b)xP}&(1s)oGRFZw2R_AEgLJ7tf zr?h}*8e@U7sLjwO?X^$zO_Wx8nI8~i#GG2KkG@8h^qAPNnz?h<-_*=-nZe_biZ&TQ zBQu<Nn0Ch#9M*k|pkZV_hA^Uk2#;Q}bJK7%Wf>ZyG8d<=37t$F$0Gby(8M65h6W4S z4DaQrNuadw@}x?)MF^!J(IX+p?|Cd@@gro-DCO#*i)8)n?P`))H_BYtDUKQF6c{Fp zI&<i<8IPsj*Zw+h4M#3oA%ki$*pNVhMteU*s7t<4ElZR3GmbJYE`qCIpKNRcB0)@- z?W0c`j(HCN<22lZB1G%-TbFjs6nDHUQ)Lg`p|5Ab>j<bWiB79ULPhCb$fP}}4eYjB zRMJF-Sg&WXSNz@GqY^(@0cOk_`=;S@uFdq{>wPu-CR*C@BHCWC#E~?MjE)t{FJg&Q zE$`Hgv=#8gtAelur^#raWRcO{gjiyMM>+R6%TjpgC2pf0ql>4<H_gILV=;%xRp{?- z1qxQob@58#Y+XFLdb>G62a-<xY(sc#$fDA8lNfQai2oP1zJE*ggEvih$+6E$j{#9p zLI_0PE#2v9-N+WI#KU}@;Y-I|Plnl##2hdjHMZE~bh^LLX)1K00yl$YnC$d=^R_gE z!MQ0uq$sE&t2?#7()s2iL0#LY8|f>m7#P*`&UkTYmvKxOpkaIbD3vO)AZNpUzj|Yd z(rMIwu=lw|zV6!PzVq7-Ew8%mlL^L?8SdS=(sFj8?qmE0li%7WQW{mjY)o{eKlpDi zcb7CWvpr}R2P|+rzD4nS!Gw_v1$20+VNUVw@2}W4OCq;t=fW>D!9%eQ?;A>zPF`OA z>ul7*Ty3pNzkBuBxP;?af;fFvD9g%O3R*^aojH8KVTAO`H^JxrQ8#D$MygrfQdwHY zqtfva#f^NSF$GxpQ$kezK6Ry)r_yElL$gh!Uts<{L@&pFmnR$xyCmWc3|(>;G|0S> z40FOrqi<p78Oa89@;L_AuD*3z4Fo7>?Q&TvK%GrAPOvg<l4zo2N#a#d^KMTD4=TZR zENhZDWYG%3A19&LnTONZ2>=eyn*LLXv96L2koI>;aIPSp@V%Gy$X#;>d+6Yh#=odt z(00<)YtW0gCFX)1KpN%};W_gl`4^s8X3Tpn)(iLOAKx<Nsh94>CK<*`$4_;kg5eOQ zISv>HbGA86;7B5BDYr}FM*L0OHJu}Zopj>OSUItL+lq-~v%c<baH|N~<Q54oPyH=( z>avq?^x(eS;j~p67udQj;Cu8kdr#-YW=()k2J{Z4yCTcX#ZnYq#7pB*LAkDcL|;(j zxh(`^R|fF29H9@EyZWIG^&>6j7{X`ySfQk7-llaY1z%mc%92bCD@brK_C+fer>?R@ z#gfsK>gV7ynIqy`xvo&PPM%@T%^YfQ|F->#w6AMo<3|y@s=kgNu-}DYaWLm|)0*%{ z`^Pp83N1W;@A%8*+N<E><+khA>{_$af=IEITP;h5`YKtss>*oKMvEOComb+Ss`FzT zx9v-t)RH^poCUfkIbN&OBAtfgr8W%}Wv)5An_<fyudN!N@#Bq;DwAQUCaM;hj?K`e z`CTqEzWIIpY3mQ-*S|RP`FO<`7^UHlAlKa+q>oB7Y;&K-Hu%&XT`k^i)n}XX5p<gd zj0A38vtpj4cn5m(yty8RXd*Z3^v8?8`l^0%_q<Q#r*&^M6x(acU{B)pa2)bShekIR zvF7hr^BhY1?x3Eoho-vW!xd^Ks{E$<(GO@hhGtCn(U0<dDNO3!o1S`cU*3z6$Dln? znXXlRTWvGeHfS2gg&NDo&$uWu<*%q*PgOpBgCPRUIw1dWbGu!CJfX+e=c?w%-b`pM zgxBRW@&*`?z!VvJU2}U{Ex|~pb$`mTa}X}5;Ml~f20ap7ey+$|Bm66FDHL$4Bgw;9 z`AnA1i6z12%$U70srIDKSavlPBuLX${wr?0zDOeljVN{U?5!Sh$G$r})3v=1-d|up z02N9o2lQolnC#jbB|oXKfV9M20);RA^s!2=SBX5vy@X?zWp#k*U!`F}5?v2$a}nfr z;r~6nxry;5naulZ274ofZU&I9Oo5Dkm5lQUiJ}gsT!PjdWg7iypg!=}F<sZ0!bJ&y zs=#_68uJvwrC5NA^okS`nHr2SK~Qs0TBO^;BLn$#sr*a1c?683((nQ-Z*K?59OEi3 z;+CI>UHCIN$ITJp0=Btf4n&pQR5K}T2l?1VW-^n{i+gs}PuK^ErougD`35P{>$-wY zLYm=uugT~53oaI1fj=ytE5@@bTuUYkyJBpSOtFH1zUO5D+N;VLjYOL{<kQ|ze{k4) z78Vh)>SCbJV7x@ZMP~t;L-cLSnxGU{J_cPwq-V@nqRni!0EscON&&&`$L%AX8Dlhx z$T|0=B-oQlxWi5v$qe;GV8eO|$rN7d!LCG~5!B4csS!S|KtN|?bb{PMJ{xQz+;agh zZL}GH6j>r<Wr94`L4orXwGADHAnC0|3mXoLWpR|IxDcrn{h>OI;VlpOzPn`^P`}`^ z3c5Y<gh)GH{v=PKS{@5&jdww-v9$|-A~RgMsF+x-8-~6JLFE_ia?^ktJ&Ue3ak-I) z2@WGy`&G;Pr;J3)^>G1$n->eUx=jlz)G<oTrO$J4V=ibc(ShUfJH7rk3dYD!W+pe; z!C#d3^FGvO{Y^O5YV&s?H7r1HFSvYyi|-yMP%%0X%cI=GVj{UyqSYu8FEMZfx)66* ztLRv<0$c3$o13;6|L|SU<Y?!|*1~-YelG%qwzP#X+rbw34UloZ)vDU7{7jJpqkPO- z7z@Z?+ln&RU2@RlR8NKO6myRpk(%N!Iqk0P7p<%R<+pyflpzE@{VjeXi8&a8{jg5T zoYG?5Z$@d?BkQg4PgNdM*z>_d0zdm{;OG1lM!*7=$;=Ghmb9z%i2Uy4@5ZMeSfnQ@ z3RnrB`*Q;^*B+(n2F*CI<7afIM`!4^|GGf+OlB4OHl8nD2LQh{!!Izm?U*uN{;k8_ zQO)3_LAXbqbm0qBi?mj^{7k<EWbL$i?sfa!MsH7m-))JD=8+M;*~r@|-o>-;v@fta zCSGtlv+{ebjqA}*-@DED@S3muST3I^XvGa#Yj*z=Lg)dH@`lg;q36{KxqY23qdq$@ zYI%EA8z)rIsDq`>KUG7&5Dqw{A={4pH@QWGH<!v}<GMo;?^(HFE$gfKZT*oqF1$AF zZS7V5n&)|0^rSr;&g7;)CGT!ax#zaR&tDhhdA<XaRi_DOUXm5*t{+oJ!@E&>O~Z9~ zU#Vi9EEUS!b*G81Ljm$%*?AN-({j<LM4KsU(VSLLW?kR%rz9%hC{+HJ{}vOHc;rt> zc(uRcP<=Z9m@L{XV|)834H*DWv(&A01C-k}F>lT9lI--w3xTpb)y#412kyQfG-Q7k zHOwt&%Q|4eqJ<vtY+L?Z;k8C<>BQd<wAb_g%8?%RmzH4o+OGx!aeFvh@YH0(82pQe zie*{m#Cc6oPHmw_4{T~PKRT@#8FF4x4~dDp`De16zs6xyC7cFF!+6${hBmN;u^ONr znib{v#Ycb&Jw1Sc;s_K`b%-iR#sn2kw6Cf)Z?J3nT@l}673s3nG5eJ8Nl$a`)QiRJ z95ZzWjKpUUO$UXC$Pm2M5$TKRC}^BP5;tEqvq@FM<tK2ZIY_3#Od&|-;->8$zVb(v zTM{<>wOlOAGaQXi?j!>GE0$@7qgPqrKT46up9c`-&_04v^A(V0)C5n*U18P|f1-_( zjM~-hOPAv1yA0t<bK{!S6BJE*Q$OzZJ7+UcEyu(N@<{)+?|+MXE3v2k;t5uAP)z9` zZW|r6<f-$Kmi6x*zQN4rL{nw^0bba7g)RpcJ!$o<H`7c`lqn7rMQwO4MYu?rfXC!( zNj>v|AI%w!3Y0!bu17ItGNuox*|6nW-^sm815;}G53_;%Oa5hL<Gn7XlaD2-RXJ?d zet5hk#3bihPA~Fvc?u3FA^z=iI^3oIc-%N1BtK>{^?1ACWc|aXOOe{tqQfzSeo{yl zt+|dl?be?2-wdm!sH5JDq;jH{9y_CpD(iRkxlPcG5_Ha#+Uudu<k?pr`b|v5d8Eaw zp+Jd24)L@tt7+CdJic9w$kn-mh(oL*PUAJdfPp=&D%LznjIVjy4V{!EnbBtO=0a93 zJVIzRrB+JkHAuX8B|I*`hEc8vRp7CEd3lZ9G~QZML3S(nxPG?bm$Jxlis`i0wa*P2 zY20stQ^fSHov5AvTCEatMZY~PqETyihrT@zHpwA%!={cyIKu-is&-5kg?zCnCU{1b zsV`WOw_CaL?t|6{=Eou!_s|Ot#t+IzJK(pjggG`w*fm>69dI8ofFFF=kjuJ(G>S&l zO*J%Onu_sZ8!4|J!yszb%acy85;lchHA(dVzoMXxp=`6kI1oK4=`ibW8|g7%q8k0U z*@Aq4RfI9rdmiL?%FdnOn&94kc$^_@TtL-iE<MeCZL-FeLGZAM&f35DRT!Hhn8G=U z+nwey8DN?T9CL;yUbD@ha$<%s%cJ}Us{J86geB6`6a(El!(4h398~CE5*I-3U;lvl z*?n|c`iF^pI)JpTWTvJ<yXS+H5o#Qd^0+94#aN}=j(;#l90W#kqh=qvl#?|{99h3n z@EyJjGG1T@0bxvFIRe#ph7h%7tfa=uP4tyynp`I{9D)-MdOee=rZdNkv!!WreTOpO zqV6=!Lo9`wN6k(jT3fVyqRhqbO7ywFHT<HhBvCx=<!)BO7HqkT)txNMJ9u{p&g3<B zM?sMa$_#b0yk#lNKgaxPf++QwA(2a=kq9ksSh}KLerKvgo^BhwbAb#8Yk?G%dAub0 zDif=Oa21Qef_8@st(i03lY7cV1TFC6Mb>|sS`h6Z*V241pJK^jmG%jJIU5%!grujL zP*T>}N*^-uO1((+;AA$aSS<P_wJ3W`6Ni%2dRHaRJ}NLDPYnlxugO9Ka4@QjG@De2 zrb^q%;#|9BcxX<84w>1FrD%j?oK8IXC02h4YeRR-qts315Cm3f-FICa?0PDpLyaLs z;vV{u@1xbxllD@UgpJjF)iYnn@4&%D8OyDT_4aO8`iG#DpdF`KL-NslIt(X#X;2)X z;DbfEgUSx{)q}W&@>#)abO{xkb4OD~(?30{$Qbmti8*q|Qnu?ZDGep(D~%&K5km*N zRzokb{jh2dx}x!#UuJw$wlwvT+9NbKSF4VFpt%hYo%BmcFn#)F(~xS$xr%CMKBB1o z`8kU^<p1cF4~^IW)f^7pTBY1Il7I$LAnU<<jDx7`ddeo%eHN^DxS>LvbjNgBy*ISl zPQQ9<ewz>xGA|jpmZ;VSe%6-rwW7T0kEi|~B)`enn+C3U_Opud$NHKM{lt0c8X1{I zUy`#%XyC-#iE=M{ZFk|W?GCw_$WDgp5)W&#Kygj5GL*mlP-lTd+z#(|n?3p{!4Znr zov1+Fhs--NrH>8ks~u*oc=6Si5KaA)o-L6bnu6k%)QvnV5Qs-za0I4mKBz+UycPyn zr^EZyT?P7@S<k+P5C9{NSKL#^*Ae`ZZQmOefWk>b86dzEqoGOjyA&VlUdOuJtiM;@ z7cwudC2A{10)V{$_^rh~d+W0PzUh8ss}7$s6Y2D-pP|enCZ)q+_CZ_8hYaq#Js1>> zq-s7^Q8N~2I5LQfRD6?ac7$mY2ts16@useJe0VSMyQ^GhTz%O*rM{EX2!F~1j(3qh z^$#CoG&qEf3naJkno?Ao71?Z`NQ5=TC5zQqSqFAwhhkjd6ivbJ{^S$(FakT7w2R)v z(g_n3_8d@Q@RO&rESdBZ;)`=e5^QIg|Mq1u6n0}tPLknW5S?tfXA&isqd^bKihd}; zWzn#VADV#CFzLKVn`H7gD=O%kaA9Ed6SeL(Itf7+-^Va>x5n*B$xixH2ofgyS4^SY z<{P2f9s5!uO9==4(;b5;1|+<EH*}qLNA56(qVwRSr$=#ghuPqv4dm?ZkR9?@_!Ai= z9yJ8ZGA=$81D(OcKMLcPB!OUd1jrNjN>T%pC`oJGUk4U0oZc2)NO$0PQ_vE!ASl+z zve^gFva<RpVqq+_6$<_FLMIQL0p0dsAK%{4AimIW+RMt0fIH<{OZ`Q0+Ey@hfPQb= zl6chO%Oi1n&*(OZ6*3j0z0a>~$Zw3$E|@Zs_Jz4|u@QgF_|VvGo@J4LEDSu+^t~dM zdO_p5bM(KVE^;@^-swHQy?;u+GuArXB<s{BmOWKDymKdbbIaR1l{}){n2)V0gDegy z<a*_OOo)g-u`5BSUFEJP<}O;dym{{YmrrBt34=lN14-xbSnAl+DD|g<2x0%$K3`B0 zrN;keFOX%@PF{U$kfEk$`<o8UpKsxvAmts34h>xu3dzIf6Y(ZMt?C9Pmz#pxA4)i6 z93aknmUb&5a)@w9GanVH<h4M{BbrB-u-y|5ki2>fB6aaQ6_0}ri%A%#xJ&z@f=jl# zsvc)R+~%@-^KX_qKG4TQ-mM?e_0G6bF~cJ&44U!@-UY1NB1RdAZ@rLA)xmL)4ql>Y zO|-hDR0&(`_B?M7NCXcr?Ro{Qn~T~<hspiQ78P)zqiRkcM1`@Wu}GCxev>y?Oe>7- zZq#^8ITLj<tx{Bz)b+O5T!1$C#%-oF65p+t9uL9+ysG%Y+^-nJN{Cy4IwuMo1-c+4 zevZi=nu-Ep{)Sg7%H_Wd63OYjL@+f5M4!vdRbs7#n!&77VLQ31Q>mh2;bu}14R#H} zU#bzR0X5@=uE91?IyYo@`Y&ZVtVuB9FJLl~D!JHKAynA?PEdG<Q@w3HRh6cn*W;jL z`q__MRC0`|`}iVWPa}C5zLb+f7$P7V%U7yjM(%MlT4h)5!QKI~kB&13O7a5g48+`R zkT;su^MF>`oAw>8T3Fp7<^-3`g^pk2{J^`zU*MpR<^65ZW{&BC@m}vPer;!-s`DO) zRPc2NFXiy|V>8!&rPDZ0A`ey==Az^npbJki-cUy?Z0CrnJ{5uxoT>i*ozjgyvtvf} zQo*neb%OGpJ)hb;W1f_Qn#&^=<Qa-cQK5Qt4T+^MuOuLmboJr(is2GmUPJp^e@f`R z5(B?hi3SrtO`H?zZ+Y-kb7+GotXy*`)u8MCKEH=vM$A8io8}sU8a`^s5f2p%D(50( zi19LvU-;(MnhZR<w|n{k=z#p{hU<B2OQNT29we;1KkBlef=S-nL1%3$o8#oMg(2RZ zH&#{K#PU)^?fh~wB`pJ#uZ2S=^n@^x`ZLokbh5#?hmyyToQCYjA98Dh{m%RgZ`mOL zl%>22;K9HOA{O@a?2zq8RkuQ(5!7*5D<WCESSSbAo)H#xZ3GDfq#4VR#r#UB`%H5H z3TU2MnurwwV4r~2C%Bb|b8OwVGaKxy;B1#m#=?Ho3@+^#Wun-L_;^P9M_Y`ZnP*Qt zz?}X3fycZRnJ)<mNSv-%@n~;RW!Yd{|Cv@woz;ytXBtmG2>W8=YqRVuI|WVaW8dzV zAK0ZBkKZFBZz*-Vtk-D1y)pW%IzD9OW1~x$z!o^%*z@S8j)uKgmh{H1yL~BQ>xN_c zN)PWli(bF&o9TlI`CzZ(Px5C=heLxF0@vK+xt%V3)?50>_NLIi%@i!L$1c8}pOh!9 z*RJ&aA!fX+t-!uym;H&yu@)Ic)MdRMV2MDDnVO1{rFTm>bgNOherlX<Di4c`U0$rZ zwcxY8VV+j5;;^g=4my6$Hs-lwA%veb44EO)U?(kfCR>Rgm1%2!+^p-K`j}zqiCu4A z&ZllHse)&735kvKBln=aFs&Y$xO1I(Hov^}`T?6yU-yh-3eC^1a!(u4dGOTN@b^#X z6~)`jdm*_k=6tySd~z2`8^~{>KDWu5qI?wkx>5>9xzD{bH<Rbhz<ud`e|%`DPMcqF z`J+t9{d4!7SG_F1%67$93-NaKNNM(w73ynPyi1r(Rod0;0#Rs6edfILz!h1v!h!;^ zJ8y!OYmQ<Fr3QKficE{Bt%B-Xkpo$Nng?*z&Rwv|r2Y1VJaB4O4B;6cs4*uK&$R?o z{&HsKizI^CSnHk?4yY9_!MQ5IKKn%`2gbcwPcjOmBk(AvB+eoTU-er8WIZ0?Wi2L7 zhxmkQ=MP;ZDfQVv_r6+rB{Jm*;p+(IN6M55s2s}riiunR+Wf^#6A-$gl2u3RDge{M z-2i>PENRfhC9W2OmAQorm0sqXe<5Aa^hfzEgU-$b;|T#bGIqY@2dko|3&TWMPmOg2 zt=V$7+^nO*oa46s#JAkhrnzFGm3831bWWjmVPoYo?arOMIfjeV)`ASSH?KON#kx|% zr9oyC6rb`^+oel>x)A8ktij<qr+wL4zH?Gt_6753X1ayX;~TQccx>;!rAo)!c?A{a zGnela{}3#10a%xL+eDx6S4Ro^8*y7-p0$K3<V)CY#S<D79$zcR%R_v+PT4NDn?4?t z=8(&^ibN2*>I!||cuk?rXU;~A=#AorU#4jSVh!-9DeUl9HwR77Z<3|G_sas#hDdm8 zU+NchMD|o^uR%iv?R(Ua`}f)Q5kg>jbTmo^>Qa072itj95A8OO^+ym#1xM8!m%nJy zqfwsWA&SDp(hq~qE@?{h=NdZmZyr8su{2NF=8cIRPc-KD$MN$r|7fIC?H8<?Q%j}D za?vLQ$KI_io!(=~W7-!pJwNlD6v2tD!b60;LpW~=Ad9bH0=_P<U*w{ET~iFE+Q>n> zh?oiTs_=XBsJ1Vp@n>GGoYyFltYI!2eMCV-04HNOVNc~QR@cnoo+q?dVcBWU)Oaxq zMB7KT0ev#TDue(d(;g;+OGHJ}p69le>ANtQgBv)Aihjs?$Bc6}kW{fFgq;vRx!z`r zaS*(TDj$~UaYH5VvWID$KsTW3=R%s<9<rV{uCnu>w94zbJKDp7V-F`!EHWzKARi)G zWQH*-6^$O-sQ_&P<HbYk&hrsuLwU>Z)q<``hOA%$R}K0zqPdNvsE<01EVNlPinn0v zQK0dn`z!6n9QlJO6`S+<kl2-aXpgtN1xgDQi3r8t@iPBJP4DI^AJ+6b<AlY~LN(Ni zhaQEV@~>yxRUY?%G_V<0(LU44I8nOso8-3wXxJMmF&KG*b&r?HJ9Dle8)M=cEl~Md zUV4qLQ^0*sn50}hm7CF{p6zaoG&LMtC~AiAV4gKqF6x+&z`=jZ2C;GFXF2%n^Uw(+ zOhnoTpC`W7%VMGbc02BS0O9nNz<sAZYO-MRdkWSnL{adYL#ZmcAl;fQ+4zL-QT8We zLLI+8b3HS6(JIYsMW$-XjQ_rD{xuaryS3<K%4M))#Qjk8J59eZ1^pAi%$9tv58*xc zw~KMqJ`H*kk>3xRMV;pgOLBfXD^K}p?X&^c6x*Gl<S=hYD?}qXFDNp!;u1NP%f9Gp zvV>@I7dbgm*N;Mp?xq0Yf42*`AF1TKIa!wLiRGtrAgvYX$Fxh)IZ<?B<%JFa`j2qG z745nA+`+)X9Vz@IyZEm7A)~L!0^iG&55LFWQR*3ql~@t(?oks#2^8NYO3coKZzoae zL?HWV-P-fnDpP&8$Z29v*wa<ErRRSaQ>witGv{k^x3fOi?EjP`qz+K}ESPa`lhwJ7 zt#*AvCe0@`SLwlv*k`ifs%&U>E=o5giM)0!_}{~`f__<e>Sf$DA8L=s{QAuHXEd&q z&odh0CjYVF@A5Z&I&t9}?Oe4M-bTWsBR2aoIR?X*4)^cBdbuRv`5&z{KPw_}eXUxP zRCihM*HPUQ+$wgRi?=~d|M|{F_J_2>U6hrEnJ$pVgnqc^!zW+uAd?%~29+y&+DFny zJbn-gpQ_tPdnyBaH@xuMeX&To=NNd<eZ69OH8a60X}`q12IH$#(2T@%!D@<P{6ex! zr0QQC>NZKE+fO=soa%KhtvC-@q}c;~4M@SQtpEN8Jp0_Jpc7YYsvt;+TkB00z_00j z&Bq}GmYHqZ!@rhZ)U@7|O)XpPKosR>lfGjP6n<Fwp@C(RpRBZW&4nDDT66WnO{eSx z=RGc;t?H@R+<dAPr3YYk#ub~iX-hF0%nYCS-55{QTRL`BrOk3(MGNUtf&41T?cdL} z!fm9`W^-wcj=f0>lkbUt)h6+74>>uZwezQ$%+W63>#klR;n=zZ&89A5g$A;3re1cT zC|!7|lNbto&XTgGIAQoI7>w9xWo1{5N1LD{o;fyI80`tlc(B(rXZ9XYJBK<IO`Y<d z+%01f7CB-7pfr~3#0$heXZuv8gM@>|t<cv<4IJve3~cO1oH_l`7hCg%+(2@)U7r@l z7d=b&?JGIz=XW;4%L>BGW9P_J$>UajDZ57t+6r5TUPq3IZz>$?LL`MmFkyT3kX0+I z?F%Q!XA@Y06?pqV^%tbSOlY4wr246q+{XQ|FUb`-LNC8VE5=&3`tn5Inah7Ry2t6_ zGi*c;u(5kEz$ww!DG&be>AZKQ)E?4cRrZ(VmH&hWWQ=pQIYZ8AK@&7%kuV{!EOmh` z8@*~G<jewYx7*$+pI~`UIl%m9G<DUt9_20}Fs#0_#@nfh`Gfn+<q$^w6d1Xv1nS+8 zn{6fhv&5a4G|MgmOj7Q4<hSbfOURJw3P@3n_vP2Byj}`04lcqg{qMcsK1k}HU2zJ? z^t(#tCdEm{8$tcMaydp9K65Gg+oruo;?DSP>n!?ipv`mbQTf=Z-hC7dkwO&o-Am=0 znCwRkU5mV%p)V82s1Pu#*SvKA2-~&X@Qi6OpIXq)K}yp|w{)D$O*EK=?un~^Rb&j# zqFdnC@q_M9?;R9AD#GFKP;#?IXz>Q&Q4xH`K4?uEAp=H;1GO6Af`Ap<4|?D7<*CPn zfg>^LMeN;_`98nCHxH8eU?XMb6^7=(wzL~^%~<&qm@-fm{A3jDJD#AyVhHUac#o?) zR(__ILDb021m_hBgA51moO5PaI-PHQ3!E`yzee=K(WB0UM(PXRgiAXt+lE}q9n*tY z%^I<i4mr}xdX&6UoULTpvPZerr^_rEWh<=T!}QU@<Z!n4_yu97L!C<Q2wtIdWW7WS zesQp8NVyE<*YiK7R`#5I9tNJ?b~>s4xUi5h)p<<`d<vyBEv!;;bI7BNF*2WJ3c?h; zSg3eC3)M~DOV^J*OVgm&*WRQB7fYUsgJd%ESkow49l-V%(;Q`%yt!#}^|IT7-G$l0 z_B&_^mSZfV-6JG-bBjPSYb5!w;;K7v1v=^|)<ICi8pU9bBm2+4C=9FNAsb=wub70i zBXGpp?-lw#4$Q^qYKFd97VML7WVzHGbb5zC7UX?B>K$>`Xc~Fj`D?3%_c5IHA!mM# zB5-+CH3TGr$Q+@Eq;I~ohs%e~gU;N0F}!R+_uC8=P<Og$G9zl!Gb5dbN_#u0J`i+P z%d+8Mqenz14jX^ONuuFLfJXRbfZCL8%oLaZgcq+L`$F_JoFKc4ty!+(7LInaK7f*3 zXrCc3(it#eF<eH4EcE&=o|?`)Hwrt~{8Wo7TQ_$?EoI?oj2CL%p!=HE`z}^^v>y2l z-$%PK$ylQz(Nb?!6pyd@IX*jrxCN1-Fzm%%H+8yy@C|nxUHF4`{T5+<I;j4H5@q$Z zpKr8nuG;Rg8Qk4AVwpo<#@UE|47{wXZPJ5zgFhn}1Rr3mRrDY%^v0i(0+W-}|I&(c zezjZSxi9IWN(?JPWyLK~V~yjl_s0npN2#vzhuP$lioc4O>e=~Jev96H@za*{y5OeD zYt<tzPvD2C^|endUsfFRr{oz;Y>A+-7MC<$xKcg-Wvl0loTVvAEWGOLJv%V>Gmj)) zZOOL(G}SM<`p@y810E&^>Yo;E`&Zuh=@+PT4#jkE28)k4C%>xoTQcq2Zvr^8y8034 z)W;AiCB1v%>*wU$cTGCpwte_{9CB3G>6V%X8twC|ysQ=efh%2WzBbQqbjqFBn!N{I z!j30ow;fb$BzO@Ek*B19EP=_@4zw(A#j+;imlEH%rw!ExJPwIyobYT!ktS+CmIgC` zrq!Ef_kIma064C^)TJJ&@%{CXZG=CIctOX``BfXgyKH{aTGJ>WW@_@K<tZqWyhf;! z`o5gdHh_<p7|o@<h@IEq&IC{2#Q9wuz1X+LB(kLNIkov`q&;o$(iUUY%kYD|0jz9j z7l&1K{msi0>itHek@3BVdmz*4Xc1<@r<ytH*uMdXclLVHOA^tB6I~4biC3S(O>`r8 z^kMy{63J4mBhNAkjU<eTL?XK_*nLJ&yEZIKrbL~Y#@x^pK7jtkWM<NNm@0HoqtWyT zqmfI!7l&0qvuQf{{8$a|z{)iT%r&rPiD@F8c+?>Ka@#xAQ_%1(ipQ8H&*<=b$3AhN z$`y9=75+b#DZ8_ihP8h0Jef@Rh*T9$xWKGH0k^Vxsn;~o;OeKQDub5S0)Y#~grBWS z7G2_ph=Jb%n(YU39rkkc8cUfr|K#`p-?u=lA=$tt-l=Pz*)1lPM{ZjXtESYd<`}mH z&6Ex|j-;Kr`wwG%aR^wc*!++gGyS|?W23uq>@QdH&BI-qsk7ov_m6e1v3Q`l?|yvB zzpfb+g1Q{D-$NJ9{1e7u#+s8!q_Dy(orX4RwU%}RKJ(x5Co>L1C>&`U46Bx*dLgut z_B^HeAcL7MH%m|+NLtKtDJY83j=Sa%K#+PskrLX|T3;&vM%XLjheU8N_0xis1iJ68 zN$*fB0|Uf=ElkwR-GhP(n>ArRrwtlTDgy~ytbXd}Jcfu3#TN;_%M+-3`(4zm-4t{s z%mYxSVL}X(H47DrJLNm@b|;yTQ4v$tB@S*2C|$)~Q5i=2$yHwFQ5c#Hb8U@Sv?a*0 zEbYJGMQv{YnzYCuof$&k463Miy(MSBaoJqTAcA_hTHqE+mLEWLqxcxsu9%=)woSVg zpJE~bed>Qw!d37oZM~_=B$>=8ZvpCM0^8JM#0JM3=LyHLnq9RbOHUD8YN50fJ4K}E z&+l`oj}Dr2jy9Vc8C-%HKvM$!gCK(QV5i6mf?)?|s!9*Vh#_ah*u}0^qq<oFfkEiN ze8F&%giH)tX$n9&<Z_Y0GnvD2O#YW9+j4nQl3<F%7o`n%9)dnTh@OrtkdH?tJ<6QI zjtTNPby}s1r6B%>x&YeQOvBbMoog_m6ER+aCcHbKN)}14Gvpk1v1`Hta=nij2_qQw z%f|`CAgtc3)z$$<li3?)DgE+Cd64ir6n@6RT=9kmgG)h9d4BtksP7ce-D6}2kYC~i zFL^nM?GD;S%CodmSR}Vku3jbzYcqy+u42bL11;e)xQtmUzq30}GMgfxVMsJ};=ANY z<e1Juy2aKz>28*#436CGjDQ>1V$qi~JukGGwg~@6NJ_<p?Gx{9+I`e;`X@Ja%DHyv zJ-D=R5QA;i7JJS<{hNAFO|c^@UGl*0==9xpUs~!j(@{4vnY?1kmc*N~{>k{-uvr`q zk+H0L)%~M|omcb@M~6JsvLelcg6Q8Mi)nGCsvl3g9P)T)|497%Q2YQ?hFq-f*N%3k z)P5)KY;bVhkG~|{bp=in#P`5ty>sLG(KaQdRu0q88>yGWuy1>KT_%i*-E@YsB37|< zNpZu9xLHtf`rm1PN}f!Ai>`2El5zj`u_WU(*EB;lq}~0>klVlS|DWcxv0D3tXd@SI zYuD>~XVMIcix~Z8a`)Pa-(7AS0(1?dz%SNKd($Wcmix3pCo*4dB3fVJ#DU5M&)Z(8 z-0t|z0GK$7&w^sl-iccKa?-`dh(t86*A6I+-(4%{wF^sTz&T`Zd~zs*jWtKQkGp^I zqRWUdJIIWYri3KFm%F*?fXnUQ))Q$*Q<WQd_`1PM|9<w$zXrREE|QOy+bV2V`I`C; zy5S(F?A%YSnDe3F>o$f@;47%b1}-j3O`nC2$(vcRR!|x;pa?iUh4cd{FdS;N?s5Cd zTmb+~rM{Yz?M`G+I!$kF9UKw80aYhsi>MWTTq`GXF-}`7>5vsdkBJXe{omv(9O~OO zl*M!^Gkfy-{%wIbSDEuerGxoz>o=3UyAMvSciXwk5X#npsZ3Pq^9J4JiMh-@L>(nV z-ph$Pp7kUpE&=e7pVx%I%!s}o_t(XA3B-fNm@$q6E0*sOIZPotAl_;}>eZ|)F>QL_ zf5mug=f_hu#WY-D!(6D43a8X&gIOAG3+G78Nd_6XhJ5L3d6f8)?YoX2hQCIT_;|-D z0<l|yb0oEx`-F3_*2v0z3Fz)M4=+JNJjFDPlO>qeOkLFcrUYB49=gRuVH`n<rk|H5 z>e?HvzudX|3O7Fco8h48cU9nSJzd%7HV=r%DfD--epmd_L~|gWKa{r~K4s~E)=xFN zE?aco{${qYBOi*awwC7*+-|79<(M(3^s)vaqw5hD2QF-`iOSt6clGH`{n{{A^zSC` zP^&NaCJ7g$!wqHQn&E`E&%U7b88!*N_HC(pMIG~UwB|YPG4$kZn%gx)1zgA4jDfce z(bi}>U_e&es!;>ikHm!61kDb?o~%2Xpe8Em@{S|xhU{;T*K|i0%7`7rxHwIGRt}F~ zpQdUtF*r7$dM;AwOxQT2<rmC#rvL#IdPqUJ2$`-RMW+pmQsA$bEvU6u10DtN#y}IM z{2oGV!o-QvxDOH!tL=I$3PscGua-Jycul54T-I|TGc1{RH_1RNaZ*?!^Iz$~tOWH0 z9^JH$O;e3_9m~16g)8w>5~eHBW?_T~XiMEd2nhlVqW<rM#1ltCiwY2wK1QACQsxp# zK!GMK54s=y1X}tsN)LbstCnA>4>cf`Jz{T_Xa!aD1rfsIr_Ioo3LhR4!aiPi;b?e< z^B^}o0|LgTBGJmw9`Sx3UzsBoU8Mz?eULAJJ!+A{3Cjnn;e^Z;0!pG(5eq!{QZr3H z-7R(+c0>h%->8Pu)^4T7{vVk^O9Nzx=yzGTw~%=%mFWK;t3?HVCYm<1K78;TzA#f+ zJ}T5@=@DaiAj5!EGr1x9&_)xD7djzn-9_!$E?Fh`bEA<mZ2;LJsZN{4oFak6q!K_I zT)O2=frviBFwB_1hMVz72MP*+QyhbblP^#FivnT03TGoZ*sZd|+iP-l$4UT|DKyP~ zP0b!zO8}x07m(t_YeIHdtpIj9ETMQ41ConrYiTWm^g75>bR`a||1*~|u;q>S$K#*d zRh#q8laN9j<h4wQAw)lJSIT0%yd7`m`(py0?d#Alsg|-%ias7M3FO{%Otf!C!Q6Ur zzokb4Rx_^f#B$@qg-(zDlpQMO&mxn9h7WRqAcrod=ZVfNs{)VN1M7TGJ}@45*8&xQ zl~Dd=N*`V-lRv+8OznEs2f%hXtv!B9rs{sL)mZo2@w33<P8_4JX2f;MrS^KwtJ`j- z&v?l?ZgD26zy|rNt$g1ViUI51ktijGlcc<gv9YlyA`nyM8A@$payPktvBk5qNICFi zU$0@!W&tvNEC1@X*}_P4OX>WiwfM|1F+qr>y5H57AMso8!r70NuW=;tkYqN4S7i6H zq)>pyeX-V>+c7-xk7Q|!N=mfy^t0LZM?LE9eYDB(>?z@P)e|r}?X9alK0Id<TVU|K zwP;Y@NZHr^bB23r`W8a&n&@9=_zu!UaM`?tZAA^<6s9G)No_~^%*>yqEoV>A7z>*7 zLIm}@p!FN52`sP-zVj|v0IROf?5Nzd&cd*TqkHteBkC#o<i`fLt3VK<x;VHYM3|aa zi~0x!#gZ>O7HlZp{ePiY&cDj<yckoz!A?@yNSH~gXA*y{#M=U?F;rYOfl?_}4^`pv zGuj!l#Vz_?+{pBU9-CpS%?aOb8Iu>X;kkLAC=s18-I!6U54iKx8N0h}yXrC<p`^XA z#p>%nx(e}@>T%DW`Dz!Zt$pgG^Md@=d(iVsCnskvsGep@>96n>k+)wy9xCl&8In5n zxnMBqa$Wcw?#{E8q$3XbEEivkD7jnyA$7Fj;ndmbgdyjFrpU!G7%g$W!T+oXvhr+z zHjKE!B~$B%Q^z36EgIfrSfBRyC7l;j&E8W1a>~(kp*sqZXdVy_`np7z!b;8r&m5Ht zHW7OTd1<NPTdsIbn&v3}40JTb@NU+`?N<H(G9qT0SyYS35Z?v@@_3Ev4x>F_-xk*8 zF-mvwVZbtpAyKv%2x8qJ)Ow^`X-{{gM;W&rlT$AI0EPWfT>+LpLh$9yygtU(TDfH6 zcM1n<I#tFbIQo1WW(YN@pQt{X*X(o;_w=<tv~V|QhJ%2f>WQEQPyII^)3z(JwBV<n zh8IpPu1R02pStE-`$A@^fq)Ne*lOVzF8Og^N-YTp0Malv(~Pxq%mL{HtLftUUA$a) zSPbu>V#5hfBWK;NDcTX2su;nwm|6qoz>ht%){~TnFa1!lphNTFIo?5!nsY~?Te;t8 zSf6O?3$;Z+mio#{{D4~G0uxoQoEQBlR!ZFJwD#d1%~boOd*3tm<*A0wr~&DZY;R6| z8&2%zYfJNJ2${fc3BsZw-B-jfmda*5gL*<}6Y3dmu5{cFWF-E@w}_7%YGCaPk3qcx zT`(KZ`d~n|LzWHTmj;j5WL|^Q<22zy6fzhnU)X*N0&fDFy^MRcJ6?u;BAnEGSvJT+ zZ*IJ$a+QlZn_fBql^u5=(*!__(CFd<h7rDC<X~T)Xo&((vTEpc6|^Gx)s<U~24=`+ zjyH1owSK%C%K_jx8TzOkt(qhux(S@VG$VbyUoUXEszkgtaZI+;^t))#pNgt&wIe@_ zd49)unuW0u<gq3NOv6VQ0rArvs_`1(M+VD+mBY!nW`mulFP089!gy*(sm<f7kn$v% zFVMQG9lRa;9q}I+6k(h~kx%wQ=^2f0qEH>m-E=s<3gzAc@f~?THAUGz!T=l+u)q@b zD@ZF;eY>zrU|7w5H-6|AJ5)R#^UnJ-w;F0V487RpW)vK=uxhW#^)GSbG~B&f_&Iu_ z;-NH6ouMt6;KR(^nvsD7+N5Ewz%i1W6W~*`2a%{O(J*OSW-{^9Pv!F9g+Yvl=W2g_ z1f|3vuZhN4yPaPv%!uGQ#;ax<Z@>a7ZEy6zT_TP}Im7^JGa%SLVVJ$7v5lsuno9W) zOk`<~i3yVD=^KHTWLPU0Pzg-OB&Hfmxs-3xNCUU|9`wS85&EHT`K6m7!}~KeLL<#6 zL>s6ZJYSnAAOpZnf{ZCvf8C>A@}3wb<|a`bz}Q)pJ-_Ea($Qyfv^pU;h=4nopE`l} zDpr)KsMeeW!!i3~<*_}jLcyqVenVpmEE?Esp1Q^C$lVP2AKN351=71*?9CaNn;ClH zsEA9Q9=sR-+~Y}0GaC7JIlS3Vj1m33f9l^#|L{t%-*Gi3<$m+h`cb($^k0QGQxrpa zo3AO4MM6&e^xgJf?Siw;$3@r6DbmMktjj-Fz0}0?|01<b-itA%zn6TkDJsd7K67pZ zKFGzz5wEE}nHzoe!sO-+x3wRhwh>6+=H}&Z{51-n@gKL2gXQMiTRsN^ao3Dh3o4*i zA=6Q1RK~Dw0`5`h>5Z$Yq3qAH`-1Kia}5$i@r-V|N@ug%t9rg?WdQd#_|0`Oldf?X zRjw7mEMCjJwlec7kw_M^CZ}^zM+3|*mgWRi!XIaBtqs<0)%-D)H3#sVzE*^e?AEV~ zEM|s`!aTe$>6`AjQ+*Y?nfmbJP~AXG-`bjZ4cAqK3Uw(W76dcVz&O$5TX0ads5C>i zxuGm#;vZK33EH0;rHmX;;Eo`gEOor<A&<?eZ)a0!m~wl1#8??E`1WsaY~8=$ejhpw zVKDC(wLq1z{*c4A*?Z4UYw7k^?~`_a0@8S=bdh#Z+7I9U6NcF!Dv{_KCxERQdu@h3 z`f=A&BGd?)l(b6qLzV~}?RkKV+47bv?W3vBam48l+rilqIIxJks1b#jJ1oO{p7hN| zj<9K^r*_5jfY{{$t=bF`%XICd(Npc>M5`9^Ws)1~qb%(U<w-aXG9Bn~7wF)SMCky) z<;$=_43?L>>>#qR5<DkS=Vh+-gB_TU9wr7XugdrxiO1LSyN%ftq{wa51d07Co);xN z+8RN5WqDVDENkXuL0(93O5DRAi0b*NFG$o0^k^>;ePX@Vh`b}FX1LI>NJOZfMB8W= z&Jk_Pc7IZQU}v6nApR*?6L7L>D<CQPwKu1{7qXYp&K0jUcxu^BuFSB3BwX;61<(;o zyql5@HHnAMy~8G4Uw%P=^A}YBquCj%0w<@$FYP(NR|BKj1qf8Ua>sV?SS}#Ddxxet zk2xMWwg5~n78Ei2uWnG94k-vGW>kifr4B1sO(1QzQwt}}A}Mt*j$ZT3zF$-~6>qzH zXa?K_fRdT^#X846`y)qQ$4Lwns^955yM%!kZ`WP9$I~$_bPP_<PY2p-IJ1rjIOw`6 zPD^tDBEu0z=(L5;i2hZ1Z=In%x;$8nt}mw5o@2eYzPu~?x{N^DFWVM8@e5H`_~k|s z<QQr4U}T${5R^AIkl@B533C~XHI-SGa5sI76lZAQF%{!MLl6W?2w7oH2`#_HgOx?Y z*qZ}qo!hIHF|4)J8;qfD!lN7y3B|EYBNX?nC%V@g+Nb0L<BC_N#5|L5#^nlW<v0eL z$R<Gt26KfVqIuLbx*|!WuN2r!&~zG>M=Q)^6j9?fM+FVbZ<LY;fL};Xz(#p%W7dk< z4dWpg2U0dP>4$}ax>iI+KfD2Xi;;JFL~%GW<*ZGBal(x`6n(;ME{)d10!&;B@9gg9 z)OaDv6YQ<_Je5U#N8l8kG6l~Tb8$Iw6!P=i(DmvD<^7%MP@&Ou%GjmQfe-jM1Eg+j zg=$d66AMHa`;pTG%<h>Kl<&k4g|1m8XAs$&=LWT<V#rC7QkM^82~sBr$@$cPd=X(9 z$=JPZeAw}(0Kqa-mFAg>bdgE-uYi~bGNc(9%orNwx{v3;I0nwFOl1dO!1T7idPZsk zP-h;XE!)O8H#`=ftW1?_(j4{$fYvL8GOR{3RwnNz7NPgY_NSa2h}&Iq70`utw@BpX zpxvfjJss+4%>KBUTwNvcodn@MZzd-0VA?HL$c6>>+nz+hM%5s=Ghzl*@6NQ8o?5+w z(7;pu5APmbgRgagrG3(N=%ZrMv-onWMc#EXBcCo~cbK8Y)2CY-mnu;o=urvVRn8?F zPzZ*p0{_RVGi_Zxq!?I7fc$>4n5MV|5B`4pg8W&{`!|#}$XjByz9U~rA1N|#dnNuU zVXL_-U*7ThJIJJ5!W|}uO6NcJ-Q>82-DD<XuvspEDizAMu<F0n&tXi}I5Xbr#@6?j zE<NM>hXTPH&Tr%8gI3S2u8JuMt&fzli`7_C7CtFtbEVhj$~T|)zgj`b@M+pt3rDp< zO)uJvg!SCfs>a?=dt<qa8Vn?+`5y%vpK}g;O*8JI8SPw_v|NX;M~GIjPJZ2SXhzl# z15d}Z<>Ot$e>h=&)mR!1UOJW<I5P2l)wA`qyF7=W*5<P<xCX@hYS_264Im94*0vbW zU(Fh*6r`-Ld0FfGGge_;<ADRsgU@u_1Hrz!j3O;-JfPa|m*JqNk`DQ?vL)cV-A&)A z*qqsqg;k*6CySQ;$h2hrPL;jCZp0c5`fytBm}gPscIJw*Sc>nn0Xu!KKj8k%W@(Pr zvQ022_r?4#r*8G|Y*=@YtdFySElu{E=Xyjk%zn3&OgX2SHtV&dhf7bj?%eheSrm0T zoh18+TejRTD}3XZtE$`8avb7#C{W4Y!ZKv&?%xj;*`)jy|A%S*3j+Q_sS^KRA=la# z_;uv1u(4C3w7RNh>uSco2l|d<2megZR@XaP%oiY8k=4hoF4#?Oh*Ow<9mdjJ<Z4k0 z{j@vrb05E1v~}$QG$ki*IO>0Z5qkCL!I8_E0he4t;*uL@yg4J8zEHtRoHdIzZn+d2 zIUpruLcqO3`z%*$KhgYlBS0!ia@$dc)gq{s?)0G*D;{^VA9`7~d*%wM9<_7z5-Vd# z!GZtsv~1-%@t8+af%t;G)`YX&3QV7Nh-H-DDWn6<H3?2xS%W#*^j(bGFPojsP0aZg zw&3);9AwVsQa?r;)a<Y9^m!Cu&rn*q7$6N@hQ5BzNb1Edt-IwZu^vXDNMAC^QXhRR zpwSTO=EI3_%_aU;DuAx2Q(GFHNxyXv?Sdhi?8`3nC}01ZkW}Vq_jIS;d+zTK@qazl z{l)Il)Qf@+?K!_Ig$;XopL`d<Xj=>pW5>(G;Z5|rD6+HjKH<0zb{$gMGN-FPl^QUw zv3u3G$<+Z>n?+0UWL)%*VlD+mrY9swlFNGn{}eAs!<@vuJD~0Cqt#*STaOp^W`P6} z!UF)V<knF`+vKY!i!~L+A1yR2jyWF5IB#<EDyx8jwpZ)#hQ3Y=FohdiHMm5n|A1mF zc;|ik2SF!sG>n(dN-}y<-axvV$%W*?H|UDKEi|3Qf|<6ZL19BK6h6qgy3<E~myUMQ z91S&OJ@b60*4MNtr-}jq3_Fg@gNCFy>*6l4OA|ir!$PPBVE>0w-=fCKy>2U+%(P1+ zz8gX%Bcd`Oa-3EHWVsQnkTMBXqoFWhbYN5~az;6Vp6yao8d1=3v|pZ7$=+r0;=_0p zRH<?D;7eJI?b_1heUAb-DIjAzo+DqW#|6{?!WrXXw?4|}VKx8hMNLuG1TjoiNBM80 z#&npe6F!kcat#mMl*foeVjUr(V-Gt9DcL?`&MSjz-NS|i02;|;Y?tRC-7XJk`(eob zE9`mIlrU6>>f@x9iLEL11Z>2PcZ%#(eGEvhH#5A#9EbvlYL}4{?=+RLi;w7m{GlPy zK7mARCdqBYzaOShD-&us!}@yBx<Iy!UlW5L7s#cxU_ppE!gW!@4ao!%d?{U*gT%3( zav_^`7%o$KTL7p9i6C*s#5)EO=(vCGcwkBuX#8N0T+R~57*b8v6JYRyra@*9xzbdN zP#ZS-X0EV=h;6^SQ-qxwT^+e4(Bv4yeNkN}7c%fHbH=afG71l&?}(s;8os36r=*23 zaTLYF!2kw0WFmnrX<7cLaZNO*10IZuSe)NP@5!mK2WB(%`&d8lvM}73e`i;nW>|-= zO2kNZ{?;#`8BLYoG7h8wi$t`kuTUY}PRuTHQ=nBB{cGksK$wuat4Fwzd;_?W;d9y! zPXLQ_50w6_x{mIW-p<PJ@l$^ksVukNvZQoqQc05m;?s}Ul^)lJ{;~A$?!Q<aBTwVf zRA+or-*++-nAfMbr{3~$p?>9q{<jiYgD&<o49$2Ur6#lebhkYldfJTg7X5I2=+=eH zVGe5>7Rc`(jCP}jL~qCe`JC7#?7<&iI@U37{vN&6yBjdIp~93mH!JnF@5=s^40PL& z3Xh%M`^94DaBrx|l$?&y&JI6k=Z&kYs_(vJHK#7I0U&Ip>_N!^rqO#CAB29MKyXu| z(UYgk1(<y(xuNro_61LsKG~i5Hf1y^9*+U{!g;&yy`SiF%gWWgm&La-0jUcvaxkKu zrlHr42F-t|boVFfWaA%MNq3t7C|-&0JM)~+BUZJVV1IYvc}qtp4s)XWS#|8>j*$HG zIyd=4fwp{~wo8r_L|^|ZMlDBK>JI)LA!VJW=20WW!u$Uyn|wET?NgN}HMhJGa>(yW zMK^}RywP{0zNH>j0Y?Qw-;JP;^X}Fz?b4Uw3r$2wZhq@TuIu8h)0&g6L!C`qdqx`i zIQA9KapgQ7?}8bhmmk&sqCw<R-u2(6@8_hdeRUXqP$jqP#_AurC`}xU>X4h4E+k;x zD)2g6$8`VaWQppRH7(U^58RROy|&F`;P>0rvPZxP@CeoEOv&pC+m}egw`wkYy1)Iu z)*&jJ2O21O+k)!YkEw^WNp)*<e?0P&=iIXo(nfCF6G5mmm&bfI<*{bq&E*4uc)%$( z6*4;eL)BU=E8G6mf6Eeo;{LT%AM@#1@Xwt+^AfjuTofL~o%$0+jpsz2$Qw+AQ9EXg zxa1nwCmZhz>=&3$_XfMV4?Kvyn7DlD64sn^3>}I!KzM6<e{nss9$lYyfwhVqAscbg z5jYMOMxpBdB;zx`ZB4W~c|(&G#(z|`81MJ4I=eb5#c4?Te}77TbaB5mV6l6)e!+Ix z^N+N`V=VC)nB~Us_XwE1d6V%-Kds$^LgjXb*G_R^OH~x&7Vl{HQP(>?^@aSgGqUj1 zNxQGeQgu~Jz26kk(T4C*EpNV@D%nH<PWcUYgjL4YD?|xSN>AYM5>K)1#i0d)Uxv3? zhdP=-8|!xuvnzdhrvLfvQ*og{pDd|&O>kyvKZ`^mXlK|m2Qo-;e&{FIr+r<C+e-bF zw&vC}$sK+oY0mE{UiigQh>6`Fe7D9aJ6kiHy7MPw7z(|n0@+>ql7(M<IlK;4IliO< z*31+bugP4$)_vwHe8t!|Neqje47X~ii226;tAHP)YqqbR_X0Z)iVCHMP{0=9YR_MD zdD6=5OK19{l8Ieddk7Z{kD9Nabk^)7>VRH#4LNbVkbrtk;y5j_W;Wk&_(!FHpGQT1 zZ{|-A(uX1|liTh5!Ngc*I46&62pb+Cn=5BH`WkLd%QH`|7KnDWcU*o^FLrAaQ6LA8 zp8&ER)^r-e)nQ}R`g+3)Yx57!(>>^*N;z(96$dA+y<v8S<4r?L*td(1DP>!(UOgZz z#CwrAtt02~Rc$wPS5}DO>cj9E|2|(ma*L{pD4&VmfNw7FhL2np+!mG(xc|J&?mf7% z<u3~byD(4{A0|kmD4zYd+7CkYz|{?9b(|I@5($Z`6i;LUA4T5A^`wq>p*S%M`g*;% zD_Ytv#bVuQx@3_ua!7?{Hkw|So0`)F_9k;}ETidQx+MG#_MToupO>Ma>DLCd3Hym? zGuhDSpgIYz;4ot>bCGpHJsGa;feRqSlM0a;NgbNgg`K+yE{%1EnTdKm&F7_gkm-}C zcc_Ew!B!!uCtsfAP6;wopcyDbg_ZyUkF`qBIP(-|_kab7QTSg(7f6r2qK9W$TQzS2 zR9s>E*D9v^rg_my)h&B5*Z-z#0vf8$en#-j86gvYU<U0-Nv%bWqSx&AsAOT57FW8D zv1`G9prBJ!j0^@ui%!>=xWiGa8SQ4CYUOEyFEi6*Lwo|atZ{@<1Vpz3=34b8fefqM z++P;R6DOfGD_i3>*U+Y`DDbG9W6WsarJLEU*~xzIHmbCy08Gds_{*_$nM@0uA#y#S z>1_DUT8Q364~b`nEcJ1B97~3Hd?f=w=<UoL8L+y#qs)zuFpNXtsUT$4yK4y-AiNIG z#w9mX2MD(!<dal1@qNAsd0o_AL@ZWk+ET(%-fU-~1W(;daB+AaL5u7{?P%B}cI&Dg z9A>AZrbK_v^p=5DL^|K52-!?q4x5{q?sC}_Pvry{i#PB7I<J06^gT_Aj^MI5w}z6r zx2<k$N~zn~TZai|CCm|y>JZ)VjJmVW*V_!W{I)%%emu6XjhC3m7CPhB+^zPF8yn_R zexQV=E(>1t#^~OC-^)MXQ)5NXEq6PV<RjK38OF6GZ~y*>(gR8!)oU^8l|eC-Er}1` z{FXNT!iKsnZjn|V@$Z{TwL_Yyg6f>=&MFz}HN-yYP{sAQYMDVWVYnA7*W;T70?n)8 z^hnv~`F>Q?2ZP}3rG^93$9iR~`4PEa0DhMDL+$hK`NiF9>uji~q_})oj|0g*PX!PU z>L9iVCjOAysJRN$F8{S6L#BcYZ_gh))nnK{`ofUSy-(fFNvX^l8EGpg)!D&8WkTTi zAgJm(FTP=2)2GCm-`#Z)ompF6SXd(KwGmGgh;Do&#9zVMSy*#ihCMRZHmctI>$SOi zJLbe+(c7&*z%Tk=RNyD-Pt@@WgI;^`>^UJ9*IgHsW*&cc$I7<?5~hFj6N|$ZsWlgt zhPnN5%cqsof^$z#eSW`Ib$gW0EK8aaQf>QRpeq3_US0Xt7XJ?I#GfN^cj&ZT8e^;+ ziLu=l;jpWAu$#R+6yZBg`S~~buXx^S&PduO-=>J8rxHy)JfEE0?Caz-7Is%t^~7sZ z`(@YGCoW7H9ZPxK`<qc^Z&)v6-2F4|{I-6ux7j#Nzy9=tAJPxqRyy1|AndtBfLU|t z8MlrlL(;dD>ts<F`|2KE`o1{2^dxmu(GZAUX6XALj2+p%=g#={oKfR@@qLR^^rFmc zIXN^7Zqit!IA=?SrbbDhJ^Osf*8No%D|h;^_G$6BzI^oUDhR!s^cKb2wf(i)1)go( z>snvK(~Tc}goBOno(o>|N9pd@_orHigq`a=2jB|B=EUCi|0^54j54e4P;iBQ`QwSP z-&Q-^+S}Q3LsRQRoL!Z6_xO!!0#oAmPDM*ReYysjZ@ioOxHa3?<v-T+v_L)#UmV<Y zOT;ePVyXv!;h^M*)BnGJ)6vh;**m;S#JRlUaVu0@F($=}&DL#)r4vI*!$SpBB&S2_ z)D<hn2!hgc%f#t`Cu|(#8(j6j;$VJLmYu`>CnBBB%F^Zv6D6G<;q$s(46e}iLH6I% z2D4i*%7;9;Pb+bk$j(jthUKgNjiy%?&)Sjb-BBhkZ)e_Q>WRf+y-q^n3901pg_}Ed z9ezuE){taHR()gTnwgeMJoj{+S_5=UJvJnMr^+?2(CJG-V;GBYunT?FNn(6*yB$;S zRaRiliS9upli(#&xytMxr(*YnOde*SNuYmls$$7=6L4ur!oCe1=$&YHX@-pX-1j+O zF&^ers4{(jzS3s+d4o5tm)CGn{jIn~O4Cw#At6IPoYwy9c-f4mk6MR}HlvVJM0EST z)NK>ip>_*i*R;7;e)r*<7|p>7scC6kH%L^>j1ON2yY7@I16f`23oDC3ZK+BQ-Px>F zZ)sx4kR!GSP(%sxg%BMd{BMHC#ct0l%P>uH92X<-rhh|p=?8`oj|B>~z<~FC1}z5e z*#E>Tccu|FuPaqNc#|%{zR)B9rKhR|rLNP?W&UoD3pr*sfr-9?p&Khk9L=Mt%;V{a z`8nLLAeNZYBPx6f5;p*y<5?3a?K`W@bu!2ypxCfoF?1LDK6-fShvm%ieR(_-_R!nV z;&@H2wi|_#&7Usj?P1I!W)Kx3+i}2zM34VGWcX4-R=}-B=q<xc+fgzpzOZe+?$0S; zGTDT55Cfe$Rsdlyq<x|-ajR&mVG~PFGq~@ya|eq=D7o22t60e)I@?w#dYIqYX-WHC zE^(yUc-U}QQ&c4MEMqn6DZrS0z=%jA!VI#4>@V6!q!&fo>FXqd-ys2kAgL&OGQ;h{ zz-v3bp4Q;=Aa0KEvMp@Ums8J+Lm&~WN$L9p44Z^Gh=(x@)|?fbCC*-OK+Qw}CGoam zP=pL!zO%q$G;@7)z1U^(5`PDYSJwm_{7qNP=u>>mKs_giW1_oVz+1CgY^l>?Jxto- zH?oyGV{z0*R-wbeh6TWx6dM)_9tj#?7nLFhxs~B)0HuhS3`8i>Z9eNxiL#nqtA%~U z05rnbm{-v5q?BFv8>K9lQG>Z8P-wd4LQ3JCgFc>`=JE4W9l{~Qogvn05xLfHt`0Qs zHa)TM$yLYlF@xON`|_gNJ3stq-N}aB(~yaHy3PGuVNB1lkWuDryps11zVldmG3ER| zYj0_~G<p2gqwV+zVeVdj@4lu<&D8nVwE6{e-reWMF@>>3yIH93mfzPw@leV?O|#ho zgaEIRO$wddb`x7TGk#4x>WqbnKU=mYiah~kv}6C%DwbiW4d-jDQXh5Xl5q{UgVcXZ z&HKaK$kY!iSL&LX?~C&#5U$^SOXcwThK`-k|FE_7780q!hWWR*D`KoNY&17Tc3N>? zn()jo)0#};AuLYg`-<2Ef_Ba@nwH;QC7wF}vbx$ffZ+tOSxlCY_tqY6JoV*KDlK)D zLojG)I=xoW&<!}iQ2+#DQgYHz1rnh))RcUD?!8=uSl~HgrXzP_!6BDMrIDGI*CzJF zsdUDSM$hv^CulHjqb!S=WOb~njXXU|ChEUs=%*sV7#|WY#BO-F7u|mKFPY{)_wy#c zn#(&%-aVz-)1b85EzogA>01=&l;wx0q<@O@+EsUj+b|j-H8$lh+xXx*;0BU8PnDa} zIqg=|Dh<Xy7#cYbTwbAA99>zZ^qNF4r9eBNRX7N;Xa>smEZ11FUA)VOYb}^kq|}`N z%;fznEs3|?N@N(w-CX?+N1p>B3Y|qW?r7Y~rIQ|)_n&ufd;SxZOj^M?zZ&($qsuuD zXRX)yo*BAB#bhj3$8^2unHO2I%0LnoKh3=<wR)iW`MzV-^YxSR`?zvO`@a1fHJjx+ zi?Nzt40ZWaK3nr3?rWtz3#P=q9PI7r|F7<N#kLDudP1JI3#BTfi;5ZU+&x?{{DeM% zGxfbTFw_3QGxp=5`TGXAz*+W*#eM~?Wuwx=U0b^6`Fnd<D?GS$95!_z(BA56T^2w0 z?+8&P&WyjBY)A=OEI7^s*Djo$``{y#ttS)ix!#vi3vlz3uO3Z*H9PKin-i%u`+d68 zmQ0!&!2Xv2mq?FOf@bapRUa0o@cV*ntP+Na#$&n_ja?`{p(iky+}w!JBznd2oiwim zm}5c<?Zjv#TI>^(?@X`FvOsu93ZA-Rq6^fU0KRl0!)SCcEsg^XRj7Pc?Nn9z`%z+` zBy+XH(N+w+gvlrun0jLBRA@#ansi}r@OhdIz+;4A?jg;6-<f_MQ05V<qXS!#0BRm8 zYBG^~F=%k$b~{mNqGs8BlhT;WNw*c*w$RC$7^TWHK3TLQZ5D4TZB}<4zYL1Nc;u2D zD9!?CTvs<qd!2U>b~3nNoIcZjjCc?Lt6jWf#*%L)DQ(gw1hnS8BV#H*6?pl}nPv); ze1^ZiGxrI5(N{#{aOu-i{I^SNJhDkUvSGaDr-sUA1Z|=X$UAx4BmO-`bB6HeCN`b; zhrUumsmj<ZIAf_}dQ8V(Sqt=g+omt{KRlRpAzssOU+TtFN$M2GR%Hy`{}mpK;>GI- zI#`@ZA`q;F)hWs$hFVvTVg}jnWiyjym{-ho6+_O5+!>BicqY0({kb;d7{*im?Q(uR z6N0mu?%d)iX6>xq>}kz1zb+1N9#N(~!*5jZqjE9E&a$YNUq>3QRT+=5jc|QT*hLZp z^Hjb*Yx{;oZ2fRPFw&5W{turp1)D~E<*{Vs!-K3SqJ1Ut-L8>j(o*~>InfP)lNKN( zz!@DC*uDg~n`%q!RA_7~7r=-&Y$$mKcsx55#4O4&gDxDh&;O(8%;Tag+qaL~qv+4b zC2aw*7z9zE#9R;=DGUds5d;wesnm$H3<MDc#<X%vhyf%t8DbF-6c<cElq?fj3<ZQV z1(h8XWZ#DA{a*BW|9c)&n7QxkI+x=-j^hlWBxpRrm@&T^CUOZ+0I6$$mduDZ9q$Lz z{V&K^Okksgxvl^I7gw$rQvi)wQOEA+eg7??(&EQvble__FxLcE@?`ihuHSZ%)v$(? zveKI&8*x*-uOFM?`vP`T>A3N1K)t6F%qohP3U^>$E*U&kkXf|$%B*+M@9~y`<SIzR z#J!%skeghgK5@tXD<7i$R68*`wrUCo)0VJCjAI@jGY+{Fd7#vuhlA)|b6#qeHi2h3 zQY^r#f}*mt@js6N!BDWXgP_jfBjtk_s{}EI2&M}Yuz;Lf{g3_9J>Y`$dTZwzrPELX z;jZ93LC&#*8pPPBE<j+{Rz=~&j3B+SVj+9()FWK3>E4%A?21f7Co#M|IgwBJ+7Mr+ z73CA#75L_J`RB^CN&2lOdAyDx1kSe*t_@HI#(y@b>Yuk}c2r&Jb<C<$2ciqleG1A5 zrd3(`-Bv~R#lx!%#Nh}(o6KO3>>%3SD(i9m{*&zo+uAr3Bw<R7)vZ$_0`5L{u42g~ zMMd}$@i=qbetqb8o<0@m)8(uUCe47h1khspd_f3?D=4;{$6x-!IrMhX-GA6@F^eWw zum$X_<NRJHud5Gw0CCl()rUJ4GM!lWuJLa{Z>OHi@08phDm6<h-4@1A$&t1u$9n}L zQxcR-z{?o+wAYv7z_f$`T}kHfu?K@QOZ>VD6}p&s@C7iPaSdkTiE-CR{d1gwV&DQa z>#jzEmfhJWUbQs1>)!5}>XM9~FIL>7eBLSQrZdMI?MR`&E<%G_N~Wlmxz_D3j_4B* z`n~camgnwA-kx<c=m989OJjIKe9Hu0?MWp$v?u2DyP4Z5&-RjqcDb@yQQJr<o82Yt z-F3yaO&WA=`pjDX{6HK2mU(!pBv|VD+uTqpext{@D?qSILdmO{nEqj6f6VW9+u%G3 z{HZA2sI83qD-LQ>ls(34!*#Lx-G5<}tE_BWLK&0F{j;h|dA{`0`}K26#d3m-a7F-q z^A2>>{}9#GHK5-*FEdx!rd@ZWHj<{f*|Rz)RF@1oLg9#y$+Bo!88KQ=&cnRc=SK8( zx<bv5Y5Mu-#G{Gi?D^AWdehg;oM>>2V|kBB4y?=chL_iH{)`jTMq4t3YLQ!D&xUf2 z|1>{8WlQX?FDtfRw~8zTFEq$H8#Z2Zr#IfDbD`?x!f_{4ux}S+5GgaPti!b#J1#kU zu=<TbpWY|N=@T1UHlNNHP8*u{vus~v9X1G`@c7CABLcTSyhr8x{!}|;{oT`pb>TGk zL1nT&5xjbf2CIKxW%f%K5nvm=;Hnk_Gk5<BbIU(E(SAT}Fs?f+bU)7IDLZ{`l<u>X zM?AAGOt+CtgZ|viE`!~6--oywW@>CZ>9Zc5iCS}~`-GeQHQXZ)qfhOd<=s(vDJNp_ zn*(ojY=7K#`o%x%l>m7xQ>&YX{H@`<-T8cvJl_{>fBfmOwfFUy<e(i>?eH_`A9`B# zY<K$3u*q`gyPJl*zMX<OaJ{C39T^{P3b<)+SEOiZ%BZSbfSZZG>v+!I>K!vl4v0D^ zDy6KSCK&8JaF>B{UnE{CO~7}148qCSn5IHv=@e-k|8>N5!O_^D*~P6Gx11ML0TBzg zP&=AAQTm{HjI|BWa#}eB@x91`K(I^*i*QL76qa8DNzN<`zN<HGJS_;@qBX&I5>ESC zdGwGRNeng|iOGC6r+e!Y2CQ<7`Jt=rqxzd)=3qjsvFLAV*L&-a{$>L~!}7Z``d(0K z{$LSC%TfJv*>%!UUYo9ku&|t<$3T;T{;LAX?hfk`gX_#wm&db(I6E<7&_}=`l;h*e zjqO9{X<?(N;u+#!vGO;F&bfe*$zuc%0E|8=x{X-8fKl?j^^;HNw=MtDgC$g`FNXs% zO?A+mo=zit8c{5>g3==Kw_SbTZVZ=?qq(9-<{P`k;UDbfmfAl<CVlc!1x`Nv)p`{P zRoXhQB+DS`Io>xS44Tdzj^F6q-Tuj}nDOd9kp-oWc+KPIQf^s7Tjw;+*Ee6ZwIY44 z8?zU!sbF;pp9H1NNX=>@g|a1c-lX3qI(AwmI9H-8O)8~TMaSA`2mK48P6VjkU;7il z<`-CoFF`0e%QF(1s;%DuAh;4=a_GrWGpGtM(c-pK9PLGGiaPot!n+R9Cx7iS3mMDK za!i@|H~Lq22Exi8*5y#HPbAFaT494k5<Tg6S99iDA)Qf?pcumP?|AFGoTRbDJt_*( z#Ehd`9`My$zt?^w7dfn$795$U-(4m;3fz7Lcp|{r7+u(&!hri6@}13Y1T}krNfg3k z35fVFk-u>NLwdqxi5^82O|QWS1FnuwgA-tOx;1}0nSjNQ2v>CD$I!Hw(u4*fqE_?@ zq7|ivV1}dw(iTj2kbK49g4E~)9A<&YuMy{X98H{B(HHldh;5))HCQVK8-?u+U3^|= zbFABjO)4=EYB$F2O03R}wDn&zR?$*EoEyHdOFBeDOFaT+5P4^msIijM72#k+dnO>8 z*1*1;K)25Wtz1LNrWA+hO|i@;j|U(bF&u~DX{X6#fzl?{u?d80LNCU>`RR<TnfRRw zX5TPuG(qo1DI;he^(kv!7I#yK3FP(VAPYj16=}>((;I<<T^Mu(uMpdUSWP<BNpHnC zYvcjaN0kZssJ{ojADbQ5o%Kq1s47pCZS_^Rk!qG?rH5%ljefIo)+UI%ul!Kwvaw{> zVg$2dZImb}w-FGk?6E@7cxw(PU;KWFL6<&Qb!l;p?Ux`F3>v$z#Ze849bUR8lfPIG zX&lyA52dJp%f-%&9NoZ;C1j@N`eB&mcCICUe@So+7vil{qoOxaYAY;&s=)a1)D|8w zo*c3ic_Z@_V0RhPp=i0T;4e_K)t_+usR$rUy#EY8ohY2K>z10lI3&MVs)?lhBkd}P zQSPo^B}J8T|5R{dPtH63bn|u#i)Zf?j+8*ExN8TWg+O5_;ewyX#;}bnBq}e#+K=C; zR>~UI#m@Ot`!t<zdtRX3v-9(z%8qbJ0(Wr(u^wrVtr1B5eev_yVQoFUq&am(4*hYk zI)~eQQb9N#@Ueqyf`6uP0(F=8LBQio3&bVp!wqeJzRbXk{~)?%kdRK;UV&dJF65(y z7EUSrrTTl|3^W6`cp6C+(?4tR=8K(Fx-CEB>(sI?pTV`?e?4Swag!vRN`$q-(tGV^ zb`1>+IaKWY-4g~bc<#GZkt$-qan1RQ7Yik9i&61fkH*Ao_;z!Vf23@sgHv$eriUgT zCUcFa7zyf(_)6kL!xJQkb`tF1Ux>#ul%E6E#=H)eRCD-~`n%2$hz(6=pLPDIg0n{y z2!f#87ck+{*de3vYe~Z@&0^W(-RtMSyQROa+nwoo?9i=w^{>{6{4E&Bhaww~9J<>U zQR$_#KD%n+-{#L}Ej4XqiouU+Jn>c2VD?ezWmTJ7W9hSwj=}cdcHMaWs}xC8(*^Q1 zg`^l&x80uS%r2fu{gUwAoa(V1RnkAq+|s8VTE1w~8<SeSp?v2^r!=qqyWl(nMRu8K z;_?yUdDP$=QEE|qrug?xU+dW?9_L>fB2K9<4aNL&+o&jHaz}aZM_rFq9xw9zDSE;> z3yLEs+Rg-ahMjxDcAJ(}X0@Go&HCGUpNltnG5<wy)IYR?eEni&-uS2cpA96a-yiaf zeK|DBqf1&VwzQ#AUnu&6EDK8mr&a3ev|hUnCpy+X{`KOEQs+){*6t7mtJD{Eb-B-0 zS|&N;*?~eppsxb+oC7UbbnOYhNcX~mmf6K3L}gO<UsrK*jpMiQgygiz4-~NtYp5XG zAI<VIdf{>qccq);@O$MF<$<PA8t=Ad<=Pf06d(rAbpCiH(L)H>e$Es9niTT3o6{Yr z!nA6MeCS|XC6y<p%osbM-vz~GA*SKm=f)uKwO7R2b_@jCe4TipscY`~`4FtF=rI4H zTENYyy8y!MrfAvf<3I2ng5QHkerTe;gE}CxaOJ$HPvz+JlSG|;22%W4&>uoZAO;7l zWyK<g1M2U>_)Z>vcslT{KPE`dqYS4zt(Xe60}%_wQnGxgZ=G1%Ab3gDE`eIa4b!=> z{U|cWS&uM`f2#ypuZ#EkN{syUwm-0j%UUhGDuGyH_Vi@!zviPhu#Dxt3B>h5OruAv zO1Bg18u0h}f(`p$G$<_I&mV3q_55E(Luf9}JPRBJrklU=wtbYQvyxxZU6#!f@qDqd z_JZ<4dw$S(b=T>6`WAGuX8@>+6Myr&hPYAM(?KPk0tP-(UPZmhd#Fw0*Vy8pMIxY- z)m06BxMu=(sBJAf4F*KlrcPTX<IQCz{7)v0)yK9@v|>~ou~60%Ch$rj_h3R$1C(hH zj_2McCf>;cz7=2#x<uOMq>+TpU&L()>74>m45mK}<1YgZfvbzr((0DH7~v~&3L=-G z)_SyC{P7x4e7vP=F_#!7E9!!Y6T?PCXbIY;jmo9`dIGX1*^;3TZ-f6TRE2Q1)B)%@ z)!Bed@H+$7X$ec;V=gpov}8e=VMq&lQ%CGdoZ)K-ywU587VOz13CI6$gsFjBdV9rG zy9=y7_>Z+cl(Psm(ugE0m{0KNKT?*Ka>Crsur}KITPWN}`hva28QP%e8p>sj0>ppe z*dVNZ@Wcp(TzRWDeVNQ=k^X8WBJ`8wCCy@+m0|<9n!N?aJa~3pGvl`-pOp)uy`sHr z&De8vMnqkfP_Vx7#1st{{=<9&x$)SM=jY>8Xcg<i(OX@cE?z~~snJW(6vT;fwIF{o zY@n^zW;P*!Sm=UG5CqAjUJLXmVzAK(^d-iqqk?SNFghQ`6>V8FC|QWonK9;HX`_SL zArNjKa@?2+!=}F}Ze@<56p}Mn9L!xgqx&CsvolHINNYl3dKd5MUeYbqc|dn>#UXI_ zo~K?=mVYtC>!hY#^HG6eXw*qKR4lU^*+0Oj<;<>Y9hsqJpBpT8=HjtEuU#@=T}Sz0 zA2l@DXt*91djyP<&X!ke!*Qgw1@#vm#ul69zYL!tX9FdXVpGA;bC%BZdwAOLL}Q$8 zBu@-9Yj`lpFErT40y(u2Pyp+GYpWcQi>mVe?u6&T1vwhS@)L0%Alwf$s{{9+bNI~b zuTPiz<EUJ^R}6LI<Gtj==f<*Mi(VO6-2QLnUs4w5MajVUa;8dQ`}06+D|ci(T=>l5 z`HUZBnscUgqF(c<Id$QdW|NX(CMUJfspj)vp`?^qrb`wpu26-<=`HyyJ80#D<;8u| z3MnS$_YEjX=dSAh8>$w{L$-S!=1gNq`$Gp;@Djx?s^<;&+l^by?Cu_$x%Qt&1RfBO zQ?hMCRPRfPi!MX{ip(2<k|3vnj$51#%gT3WYi532AN#3Dpp3o>`PymX;=tlRCe!>W z31ZK%NXGE*y)9Vb<455%(CqeC?zB(y?iTXUz+9SLCGxkZPp)K4^}@=OZ~>PwJNzJ^ z1O@ppz#B#(Cu%;KZk9Bx9w`W<LF+Hw9iSOtJK(%sJ1OF0|MT`_#oMI==E>*EzcNxT zsYUe1Rs$qj&91w*THG?aqdu~(P5Pg&%oFp3P9x>jD4Se|=hjcjtCXlpx7eK##hQD< z(DYuF<I*h~we6z+<d`{#w$U~w=L9-7VTo~ZX6%Z+hd3&tva%olF<&qc^IEy_0Vt!% zspTez-|8|>q!-h)1NFHaVA1DFE$_X)xR2)!F6;H~9|(G4KJD+%Jz{P|HC<wG+4DOk zzX*NL1G^RmhTR-=c&(OAFrrGRPYzsg=;+g&!DkZk-}v^sEe$b&bzfWy@fXcprJZ-Y zbnL%czPEjz{9NO6Md|1uQ_A0Y94{Z9>Ahp8^yV@18(*4C{^-5@a7FudS_o}0pY2}1 zTU~l5`t{{Tb{zqeLiIa{bB^<ZoL?;8fAGtYA?+y=zVikj-D;}TJYGS`>F4@?R_)U5 z48?P=(ZlnP*sQe&I{Ln;J$7@q-WR`X3mP=#Z9`Fi`_sN>DM85vLFqfcki9#Pm%2Gz zT9XPrx-4V&Kk^wK1KSbh0$`u9aDNf{=y;*T_Zkq<?vOc=3<>(52d2oj7{#%)mtUH7 zSH-Zw`f$f&qx|fMAtNs)AqVx_8l#4D`(q1gCRn}ySkHcUsQt~|ih)LY+S3N@dhaNY z7Q`=KV1Ehp&?wdrS@r*HBmox}6>U;AGG`eFP9EL<IAK2G8JFl_KPYMwr&^Np4Nk7T zBC}ci2C^tanclc@cB1k2m53a~A|yS*ACFxz7Uh+tMBYO~M1NOHr=B3t&DF`u{Q`tg z#`ZV!qF0QMTP=o$EtzACHI`HNCp-Spj|x&qT_EPqm(pl$wg|P3+4}?&=N$OKrH|8E z>}RS5nyGkJ!U#A?K%Z`B`1aYb&LiF15|^4BqNbS6W}8*a{^``CGsi}jg9PvqTNrW$ z&YtCkg6@#O@U`q#>JN^S<uj#4$H|9HJoVd_&lP#`_SJi(=01Z(zu);+tG1m(>Si;Z zm6ST*li#%HPpXX?nukRWMM=J*QM1d=b54fQV1Q~!t_iLRdQnw8WU6M|i=?LQvZKA! ztd(B%zY%VO>#-Q0D0beQUiNA&%2^TJ=eIIP;-#jh+Uc#(wPKYIyK`8Zv`_OOINI=k zw$v8}Cke(BGf*@IU9dUDg_MJj1wI-^KdFY#t1cj>fSw7!0fv?^{-MoKem<>{8*0?x zzCwwh`zGO9pcJ0^G+=d>R{8iQ&DB7MqNdW*n&k~5P7A)5{%k=ir&-tEWuevp7qUx$ z3W(cTLWIw!H>j`#M~*Q<r<+EciB}Z}vK)cWq=4Ni#)1qGTu-;&W|;*vl+JQMS|)Z0 zj*UzX*p`IjrR*_rg#Dw)hrxIRUI>lna&1b&SiV!caXeoE_(EnpdZaWSftQX3WRpS| zA^;6ovcQAbiElOn1?8TZrGUt^@FJZgYO`C1e6Jg+?$(my^ha*(Y*y5#SR>XL>sM$S z0ANI<Ois`~WiGf1BSYu1qkE=MjX@>5%t!wK1CBkB&`}~QT<0sUD8nIo$E__iAjA%q z4l>c^7sPLNT5JHnkP3+>MY>}5j(|Rh0u+sIHt#WX?}3A9pCzUXVJ!tH%!EUi4qPQc zA?e2JGdX-4_`?J>$C;gbb8wc<LmBI;#(!7nKm7`a2Hoq@o)fSz=<OFKYm(!0c?iY! zxX~m<k6sqRjM7;hqZ@g*ULC!i+QGbp)}T3>YVa1}ePn&JeZth^E3Ku~!GTu4?H>PZ zD8<g`fFvG_n)81xX1)5d0mwq5`d_U&ds5n-2iqc_lx7DjT6wS1ysXbIy@B4)XE>ls zGBEG^i}hwMN2VYAbog->X_x^nGYAv38LZo)r8W6s%D|L@I)==|l_lggUCit(II8z5 z>>laAZKa%xH?^4X%&%3B&B$+IG~_O38Jt;iK^Qm{r+aGZ@l+fC7#^cHT4-tv{6uS& zsk`0VlUTMuO1atc-Mwq%KQU0sxc0;Ol<qLN-Drn@dMr|AAIuVO_+#)Ic@5ygP2qN@ z%Fn)b-lkUp2ayZpWsvmjT)~KfntH5vo^63{ZC{M@=ZhRcg@pH<ox^kgZ|ohsrL=K+ z&QUTrihj2YPUnanmyJIQ;&`qLTSj69N72c6?u?Hi-|4EZ#0w5RV|Vw8-P;nl6#mq| zmJe2`RRWRBrXn6W8TpZwvwr{Qt(^ORT}usuM}??~7i#JK{D2<sd5*{xhF{76P<ffI zMrEgAkASLZg3Er`JnNU#jf))8;FmHFxiVbur?I{)@3$i|!QaCb&MLQQ+d}W^koZp( z|JZjb4$XW$I?O9M-Un-*+~%U73vYSoO5$f<2`_jy1$W0nrDKmo2{;5vcb9JJ+eLGG z-k_v8HK$fG)Sa#5Law0b7q-5puUK9G)VwFgR1%}N#`9=mA|9TPcvqsBJQHJ;Xpnfw zWREe#QWS~o7Q@$~<*H2Yorm#DAwWE;`Xyv}|E1F*%PS4?%f6~(G!LOd?I&uf5tE~} z1%{tG4a#18)Ej;0n#uYHzPas@Njvvb!EkU&{{wwgSgw53S$9rV%s>uEJKv!D(WegX zWP3(RR6W;H`}K#s3ODvno_TYsJm@6s)}Gh&OCqH;4E*fY`&;g^`^5g8$lh-!8%Bt! zAFLrj#pihzPk*9T$Ws`8?O}a-;~C#YgTEeD{O|P1QjCvQXg({tijp*J6A{4v@?XOr z?)uR#G^^kFkM%WvzHq#UAI8*OTihSC@#&W)p+;WiVKtvf+p48zSLW%zEKfl@PsIti zxx=r<_u8E7&bn2#*dDn)EV6DZXehm@x<BJzEjwlVx))W0VaI{{j-JzW?)+D)zdqz@ zXo`HJgo#J2_xWRud)vDI*?&2rk0Lg!I7_Sl?vPbe{<JrhyA|fLd-?Ur9oL6)$POvK zB>^`RcQ=J?4Sq#$m;A=IZ!O#ZIAQPL=<)k1X>*>R<_Ul4=a}CL$G5dyos7%W83<7W z1{kGG`<R%aE@B7-^m)gL{c%9ID3w@JS4TtSNC=H8KDkz1^xi~);n^ykH0Qthn=6aY zb(}iT(1^L@M4k8p&Av=4$39dhg&&;z`J{t}rkJwM{o;(1{tGAd^q6hW&Ry5X0iC-O z<)0i-h<eGILaq6P#b(!{$<Yi1AQhV}As8LUW9_pdwCTZj{kKjjke`HuT^#=7_uEnn zR^KN89QD(*ohXKY0O5F+N;kS7eN;Ci1e~l3&pL``SRBpf$O8L%9U`+xfGeeBt|7y> zCq`+;uUXsdsSSq$JzA1N*duVhS7~FOB*;s*TI9-8k1hJ=8l-<=ZeE=D*juFjr@2Bi z<*TXRzDwHHo{_>sfE{GAqWfR1?+BR%4>8b|KR#pO+$GH>ZMqqaEDa74<>BdmZ%J5a z4Xd+y-7KCOtFM0A4n;_e{|-02YdiqsFU$8_q2xzWgri9WNGG$@d#(BwqWX_n5!^Re zDB!ck6QWgeG`Rsssf32L<^R6tFo<LWm8+lYkMdWB3d{+@Smd3t|KYzhhNLzXQUv}~ zP>_H#&GzU}F64KYLHck4td!7M6vD6;KLj-3ITL!2$Qm*<eTzAU8%CP)QyQ@qLv*g( z*{UVX=lXUVlWoO(0v^4V4Q^<Ov;y?HO%SjdIU{)#b5op8WL*O)spkFEqycuz43Rp4 zjr@hh2Sqyhg*HmqMUwo&I)hF487p26>r7<@;t4y+Zb7gpp+Zg=Q_|He3|t*FiLmV< z$ZN^Aa6g^!#e+zM=QjhskvbD%$dIqVyh+3!E{ZGR@?PPB$?1mq-snVd6KD2}u*MX& z0BF6G2{m$v_U7#n6X?Q4=g@k>qA{Jo<|GydbFr|%Ot<ov*#@*6WdwnWt`Q&31@;k} zUxrQvWs#-EK1j}BSEE0o@=q%5q&DK<jll3$O&V4=5M+%<%dGM(u&hN_LbFzJ5K9H& zA0k9>Zq6Y3g(f-+_HLE3cT+eavcgsLk-}rBa;??v9;-jc$FbheJ_NFyFIVr^m=$u} zuuy)vXAE**tfm>@Ff;=C<4tmC#qv=>*rsy$2E0Y-qz*)=pUX#0&_||)3B=Mx0BB)i z(a-`Mj|N)EUV>`N6vs~QqkXuU_~WwT<@1MXV&T(mQyy?%B8E3b3Jhf2#-{vlf6e!K z@#X%(%NqHDtK*-)3>nbsQf9kOv*P}m0(kyU`Q(i!0@nR{9>i&|aj2-XKJ2Sa&jO|^ zvhzx-`N^UXzY(OglLExU8KcR%_=Aofr368<(e*z;9e~FABGZr$>vmuLp|WD5fV5y0 zG_U!m<wr-Oqe_~Ub?up7nkNsGmk!r&E`4$ts>l&!inPD{{M9YqRw1_oo_&ReULyXo zgmPr))U-!3*c^YQ$$W!+rLnplc?v-asB{gM<gi=ume}soI(xX@A+5IKtsI#TKq0*~ zIum<|&~=oSh@9tm@qlTW&O7S;ge<8=9pi%46nMf>6bekYW!byGm_FL4d>`DIJCo6g zhJ;ZL9zW0l<B{m0iBH~3Kfp8k8y~2~;TsTI__7~u4~{GXn_@SQppK1ipKEo4@A9wK zC5MHP52!c*#cb*ddk+FREjOyX{;9%@IU!@&NX=o1V#ryg-)<zTamG6Dh#jJxWhb3} zeGqNqH&T|27`j?!8Qoqe$Tg{LwHZ;+f0jzy51J%%aEBj?`pe5C=<c)sZLSCtjMD7Z zVvX?^cRZTUfz`0IFW9dt%}bnE)?OD|4wOH=(N*x2U<z4j=yK~9bL~B=w0EaYvBE<^ zwBSH(3+%f;TqeRWbz5`1mwpRCb+pq;Eu*;i^Wz+x6d5NG=sD0p>PD80UOE>uF1_!U z)9p=PGn;?3a!MI`sxfDy?HD;bnOY}dG88Eyjj2hn?6ONo;TlHOE>10~Ntz`)qn@1T zd$91MX2C$2RVnY8MzmVh`ivNjCt=Wc>QMd2jNq_0?&aMoXR7i92X|l2AVDuB%&%bi zN4T9<$``P%Q`nsrDR-TIwLP@-Z{tQBVrqzkkUyVqOWvyh(IK#}ZtZe-lJ)$}r=_E% zM`Js^o6jpUFUHFk(5;+|>52WL=E43ysu$%B8L8$R_cK!WDKA_y`X%Dcp0NE-H$@d^ ziw1$HIsEAL#(fDmkv^OE-LI-r?*&V(N~08UdSCf&Fi_s4#2<NX^J_ESR@N`6d1dE< z^7ZH9|5%qD-c}~hZ?L&`&9eXMkbzgzj!U~P?LWiodd|>y6+u~~ldVJ!x27*Eb{xC0 ztX6?E`pk!|w(-?6$pEl);N}mK!W(NVQ&Qw73nkmHi?&bxIP-SQpuA&uukVY#8wcu? zWlI(^4zHG3eH}V5?}_4o_r#F*AHUI<eJ@jj`$E?uf;{T$dmp&<Sbka&K6({wuh?~U z;Yk9z`ZebL*~$nr6=UEyNz6MDZ;wNbhjP6I(qi>CB50Q(XJO70mI#$r1CZnkEOr6l zO-e!nhw*5%tgrcVEESW|zmPr_{K9g34_5!#F}f~`TdZwNhLR+n_|}1-J`Oz|OF6@T zziSlt!5~^4pzK^@#>9`{;mg@3!`>zPy1$Jfl|(#Fj9bz3mLek=BSrGcaQ!>Y+}YJB zA5WBqA3`?&u|Bdg+53eJ(!tW90VZ0QpD}~Q(^RkmSMI?*0#BLnpD=tA3<s9-L}!k> zs#AB3ZyZ>GC7<WDn4v3attp&AY5$=gmm57<UKJZ?sVH6^b9?7;&HKWOq$lQ1h&hC_ zDB5Z+?b$rX2F34oiV=WRdFtlLZR!hMCXaqlAP^0=zdii$YY<qsXCarHF6#o8=Px)w z<~*tZ4zR&Y8Os4NLXI2HQU>1!mmfn2{pCoxMgIZLCc?WMr40WU)!LQBr4oohwoLWI zyj7gQRIITWVzU)~9IH0<JIh1u8Wc5`sf2O`=`KG&iybGl;t@U3*;?_!tA<HVuq{o> zOUXy1m7zshED1^&o4%2UvZ}A3LAU~GSwSihHdj)!{UQyHC+#T5axntEMc<vs(xgg` z4vs$-n&ApSju8jSTPhYNY1%crp!<cQ?P84Q)Q(}c8l^@_{6UC}vbV%;@Y1EmqjAt+ z_(+6TAc99da3wqm)6iw;#ro39uz{UVUbd4kMn7XOY;U#nuRGDH0c2PBL6E?<K*Sb~ zBe&2HaT~W$P$3xGCX7+Af)2zi2F7E1Nos+<is^wKz`Ph?=1TTPjLeAkZhgaq?IGCC z3fc>D1^wY69&q$@{$evI7tZg%r@pJBAXKt`akY?@h#^$er%Ul%sy|`9M03}vus%6P zHwAwNs^_Tw&p}=7P4-9+spbqAq>0bq8EAFmVaRmm$*}NT*h!EJg|8HsXfS=32&ysK zd234{T^JzFE7Qi|!8xx+>f`XLx^+ODkjQ~qn_?bUw(`BJ?&XgTkq#e!@>4Yx4$EVF zM0ykndV58G@Q=0avyN|}AMTpxQ7-7;#WM0}R7ocI^}AFAt*OI(>*lv7h^ofnNTaBs zE(~vq_wu`$7@gy|)k{3g^Sn$C$UtZe2bux34KgMXQ}_u-W8TOgVFE-a=lp765HBTw z_MWh*qiFyz>MGyt@uL+u2mW3l+7F33LQ_VBcZ4o+zsKyxG|aWdJa<tue=Ppmpsz<6 z%e?tp#9^3IP)H*OVmwQdX7>5p(AsIF>~O3LPcKaU2mHZ1ma(Dq;pw>9j|A}WBM-*S zmF~tIUV&I+VmQ&{qi4&0l776C9)mHMI?(&M+uKZMxL=*E8|2VNIg}pG4kPlYc*f^v zPfWiy^V5Nnk3zSU(1Kh!J)wOh;<@3HA}|z(!x$xSOH?pZU1yYUL{tO3MTi^nb$!Lj zA?DoYzQM<*q3tq%kcX&Wa$i>f3Lb)S<bC$hgJ9(coiazqPd{3}NH+fHL9sc@$>hBE z>+@m<97`XOh8qOmi9#meRIE1@F2A$NF-G_GI?^3VVIR$zgk!aJ5q-Ps82-e2d2ZI$ zi7vV4(>WW&htW{cKx)C@rQU)AjhA_C0(N{9qBu1i>xgV1obewEVx!ut{+fxCg?(GX z_6n2b3szxxy4iHct4N=m!1joo@J!zR-btQR%uvgCBv^AdM1-+Q%F&w&TZJ`Zy{_ZF zC#}m*E+6%=m_T<4=`zCkiBn_y=NbblgFdmF58l`48Oo)`T_#cs()1noPa_s^FTwgo zEri`$oCuJD>$LwG$Agc%OomT)A3aYcRuUe}HCo?Q20PNjr87Eo-V1r}>HHTiJ6`|r zv~KJJdxSgu(y@M34>wHeSah5X9m}52Xj^t!qFFMp^DUBmUrdYs_^_p0q?6t?t~;w5 zo+^_n#;RJXEsOlNe7gD7Tf?@>Wmiq$bcnMTWLISnFMq3D9J<Doou$9)M|hb3`J8oj zm&2EPOdt+zq5tfj`({yCyT*OE=y>1VpNgzf-Lv}T&)0;WDesG^k6-e_G4<ecpYp)g z32o2y!I=8y-B~D|>HXkQ7!|Zm&PSJiT)%T~wT#dfHGHU|H10QbWq<k5oSOc1OW!q} zRFYpFQre^FygRRP((^?Q?(ELW`g{4tKhCcg!y|+kjnulEhmUsazkWR^<MVXG@2{Yz zjAT8kUWKZ+eArW^-rg7ES+IIja@a1Jo{fZMd0kJ=TztIT-eIyw*($Lf)=eMK8IPC4 zv(swRrGjqE9vsJg!{~`<!Ql_mSzuqn2-zOns5|JF{7JuTlYz6A8!j`sF_kE{+$7WS zdl$uZxiZ3{FYwJzC(^7CW!0~|?s|Z(x9%k1LCoQa5@m8bv@id)vn3;2fg4k%ySThm z4{*uGQQ~!>Ce!(x4NU=e)eQDdQXl46e>6uMzF}+}l^3IDjZ@yVPeuSIcPo^tqU~u; znTM&)U@m}mThrySes^vC3XMwf;}o{!Cr7cO8L@nV_FPa3(^uAw;uzb(i&XN{6MvI$ z#JI+(YAp_O>O#q?)}!Z!A5{ca6fnWovF&#=icQDO1*&&T>l=SM+gaxXY0ld*^&C$1 zsG0m(_;LsO-olZ#&&@sloi2ka7Ua3!&fHWWrcJG>n9*bo7ItFTzWo#gZPA%!?2ukj zT1wgsz7eV+)+G1$(6=-~qo=hMVnL#PE<$)#;~9rjzGb8_r}XZ)3$4jsOI4BrgA+oa zhUo{(2ZU<cr+rayfUq-3XW?&zIJjG>pfpU}M{X!d40<H>=^bvY8+08qRHLnO8wfU< z%vl0#gE&TO8ZfeHsS^G!Z!;229V>;<Q6>@mYXhQ30f+NH0wo<RqY<&RHas&-_-_am zx1D7e^aStN^E5gZzzm&br|ooov9zIR+hZb@d?#(z?=GbzS*1a1J%IQN5_W-}U0qnC zK>bJGUZz>E$T$^&eJ-CT7||yQ-#+3Np{kx`X7I#wkJJ<=OjOFCp)f??Kvqme6{2M= z*32sMPGT{o$N%<OF%{aM1prZaG8SGNg!Ejn<%12e<KbVi?TG&57zY_>7dzH=qL=#z zgMxENi%*Av$KiFn8R1Q^f=tvwqePmX)~7IJO%20kz5*r?f}$XjC<BodlW5j7fZ<}? zM2HL*eojE{ub5*aaI0z5-27HaDv2<u@9R5`--{<ZH(HPxM{4B}*TZ`iSnp67*+$-( zDejCjgbWs-5BRK}FKbYovxN@Q&(DTUQ2(h@WyqpCkE^U)Kk;SqJC$B+Xp-H<2>Wy4 zxDh>s#d2-uunKqh^(toy34O6ox*IfqaKSaUK#thj&8IsEj=8;bOYxn*FKrpS9c-kt zHe-8}U%^;9W$G+P9*LW)=|-mf+$@zk`?TWx2!O&?McZFqjVd*GX~&g|DyU`>#o#!* zZKuVOOW+8=Qnp0l8hP>L5jgX=T29>iVLJ<#%4GA7x#U>Sa9iH@-h)R%sm|6OfAN+A zP?-x1Ts1V{UiG@$eMPXY@&i>%U3f<5sm`09tNY2Hyn|2A1#Z^ctmnA=*wFuO3|U=f zcI0Z7Oc~ffXAiwUz2MY8f>ihx6@nh)ru^Qr+`0F@9c)=0opfiDU@LLa6oPEhsb|NR z%LC#{k%|Ao{Rm_*rSV2*+3fL+kSGuc1umZABJC;#I_&<-GX8V#TMTtKK~sIkVd-4{ zM#yNBfiN$joYF;6!|2Ba{f)5B%Q&T^Xwe@mT_6)HNU~D{AMP;fOcICqnIO)FJG>*2 z=7|mgV??XVy^vmpeCs*L0vHU2JDGX)nDL+2$_%6}WefQSH!?rE68ub2AsZRzT+xQa z6$BOVO6DW`Dki?2t(MVG`^=Bo?NP7kaC~&H;Qpc!13!6tRb1iiUE6M+u%C3e$rPC~ zwL+<7XG?dJVd1%Ar!f_Z0_Uw*m{r+~;nYM6-yoP|>Y@ocW`z1++&<l*QK6^8hh)Lt z(SpP6u(oKdi%jrnyzE@YEOJ^~xMn$CjdEdJIym0n!^9ZZKOY+#1}O)c_`<Nov)NjA z$MK*fB`q0B_@o(BtSs7v0TVr4t{Y>dsxNdkNH-pn_9E+tK=X+;c0ng=N`0m3?!ERy zGat*J?;qC}ncV+-o77rrwxm5jAB1Awll65OUwc`J3IF4;>%JRimxtJF(e0i2wbylN zyFvWYd2+{iR!c)pABcM4UE6#5#kHZn?S+QP06XGk_eK2fedP6-H*Q->&w5|)6;rd_ z-WGiaHCbZDYnAi#(<dAM*&1kU&bYxc{mjm#&@*Rwf~uVRxNEkU>o2|mJfa(uQnEEz z=f<}0UpGH8e^YklX#?7<dj-;mkwOx4?b>Vo#Y2l)YIHU!+iHf*x%2M5xx=o<?XoLz zrw@XI@m<IG?>6m&EyHIvIWqU2Pi=JX`Hu?M1PAtc-!#8JM`udm@_)6yPj;Au5s62k zpb8Cng?#x`HLhjD<ZJQeYqR6ac4D&8ReRsV_hC~+o_~c)*B?VgZ0{KRH|cFbR56{l zK-X4yVys0dpi_Y31POkkwh4j1v&AywWqp)msscG(UYzr?{e(HTfgrnb^|TSIufSbb zr<Ut|@AUp%8=GrMolW={({PrZ9S_~J-()%a9~bK|ywqgg>2~$}rMt*D@i!?pSpCf% zcUO;r-(GBQpp28ln(8f!*|V{{mfct?Q6WB_>LgKgmofgAB>wga0r#%qOf3dUD=wuf z3PkGVPUkFpO<I<8=Dg0MLP~)>%T(W=58l-XB@hdye6zIvvZV%9W_>V;8p2>xWLv); ztonz^UQtTzD)rTMtBB32wpyjUYpCdQ%NL)(p%^#Aq5vKRmnxTc0RN|8<5==)DMYkU z#f5ry=j|_P&cS}HDe{S|zq82=w9#iI)!g`xh)2HQ5{-{tF`7QPH`gk{jQRv@h4!Dk z$q3y}!!uIno~tKFU`n3IXSk>7q;W(405j|<14s;r#HI#tc#vwu*%a`W5h1V;W|a;$ zJKK%jEoJcy?ISHmE!R>j?0G)9frU7pffBJ9yQ_pB9WZLFFy}y!?<}wHO&YcXty2ii z+Q30)*-+8m37jz2JE&-d7}N7FnXZcN_XtiWg4mYTIDmCk3VpgQ`i}obdAEe)Tl9!@ z&6EsuCeTQz0ys5HvC(n~?f=&pSFqB7<auI&%y?9%G!EN+xXcv)G2RdvSc<&8%fuEh zcDU~>&nAbRlL*zjrW|MgYKAE63L_&+Mqp}8UIcKR%W~ye$w<;buk262Hyz;*4zEu; z<!y1RvyN{|{jm2y-7vsy*rxbRkzz6PQ3#&hf3c9SlqfEslYcDt(Q#2Z#MR>q^WQsW zUK{KzXVnzm3a}`}fQf;9MDeK(QP^>g-&*5{X9T8q)R!#JGA~X@TxxKi7&BM(r(Dq! zAzNEAMuBjIPgxqTV$5DLh6^S5wq3#<Iih%1yfDc{Hih^bcUsM#vpgZCimg`2Sw-jQ zdRV`w+3Ds`U1SaJ)Il#)zs1g4)?qaxvS8={LDow3Fnqt6*YDOH-Q%xsdr8K3pLksY z_hdx>(VieCh+LDu5~Jkkdcz>;fqb;pMo{NveC=647hjuYenM|t#;Zc=(1oK}G@cG* z6m$IN$JuOwAd1C}Nke~L_7N6;+*_IR>OsyG^O0bTl}=fgTF~j51RF4Qc*rnd1b!KT z04PdhEKPqpKpXoe+`Kfi{CjvsppVbaa9*X^q>w0qL{IfiX71D{GU8FCbN8aR1NE#Z zxQz;F3#^J#439kY5B^$CuIjqIxDuy9L0`FOvMlRiaQsH{WO~f2a{pSRX|I?c)3JCi z3WqZgX^y%0wM@y|{ipW>t3vBt>DIB^0(G~&71k;3VP<(QW~Tl($F_SvT_?E^FMH1A z7D-KRCbxi6EZNDTG->a=8Lg`?pO5I9DzoBTWQ1F8iVdpN_&ngrF+WgQAKhZ(9`M<v z8VVe`Zu~SC(<%o#PxdcUFi#rZ>>1tz{!t@@il*~EuV}b`IHuPCwJBs_h#cbV&)O8` z-3Gs5EkWv0!7TRY`NRRkw6t8UuKR&9qlB8N6JjxEx9I{$XRujsYoR2vpuXz0+K89! zlKTDIf>F&zA{RBk`my!aj(4jbTs(}&Kuw$#gM!|&^I!Z~5g!tx8`$!5kPaqGS5Z%x zmq5v`hb?EEde`plXE=tkD>eeUbefIf0u|26xI&GV=Mb)7+m+oJ>+IxQh6l#o)w>qo zS#M{^_OP`8t|MkFf^t1ScxtGs6oW{Bk1pvxwWc$PPaW*Qeu8QK^a<{^G3<iBGh^ar z>qDb!=dz_tZ<g2eaY$JlV_-aH+O6<J)w{aOI3Y1WVU}AuM*Uu8p3WJYbl*$<HdcW* z8Dhj(`7?d$OTAw6kN@OPTWTCTHmBa#tL@Z08Vfijo+da+y-H)7m1Y_^Z?bdw^Boo` z4|R+NZ;AG{z}P&QOtxG9dd&li8`75ojSVzqN=GA5+e|w33%xt;N8&A)He)av_lB5? zzguS<tD9xp^K^q&|CJ~C2ao1=nC3@3r-jJm<;7He*r(03QJ*D72a12X>EyRK&+dsa z{NijTo}J~zS+Do2UiirRk0i-YwycXRu%dZD0(B6SG;3>F$VMV)5JG_NsFIAqg8h%H zW-A?JAZG8qH6Sl+KdiV=bs$Xlk=*L&RQbtvddI2I-8L)@+=AmlX>r!yU+(_>j+e*7 z_1+Ic&y>j@-HM_o9hg*m=~;w+q+iC)<&t>u$l)y%a!V_(rLNxmn*J*TjL$Mq6}+T) zt4+s@R8qNaQ=~fD;n95L^bRW}jC!}x)e4e^7+-5CEsbG1h3_59ST;*@MtRU!D^cvR z{5D~Swm}l^DJxwM>7!}PsK{?&E@|d?;FQOqqpO;~+Xo}d7W$o&{q?VZncH1jd(z2B zXyMiI!b;Zy9$raONy^s~H<ojv1=p#VKIvnN&DNF@RQ7J8B$(ksdx7kpop|FR8a*T} zVgW*U!miEZmh*G<pb&aanz3MOZUo}X4Uw8o5{jlE&hxuWMZWkWZ}$2ih>-}Gc=is( zONe)Lks)c^%hieo#a9GBK{jz)(?5nj^xM4?gqT)y=8W2gGy5x?0TgY00Z#{xe7KGu z+%*umoQ;p1t)Iyer|fjW!O`-;HW~>0s;citWW-{??!M|Ju}b|U=~y6??)5A>0+fug z(zjwoR@f$`i;ft&%W8_18Q>AF>$SP^&g?Q~3j`EZmN>>ak3~vWfdC)k&;o$5Mlq5G zu~=0nHy`RI)rub3i4#b{Jf&3h2ER0Ei9aeFDx@Z8w8ix!@1!(t#kAi##8Xu<s7LL@ ztL{Cqf=DoogW)|4iGI_^1eV(=@plPBgNaydw!To_IF||H1LJ5d;?_$VFVQ0OlqE6t zT{GIrnZqs$O|q_2p`O+hO{aYbbH>;aB><3ZvXCKa(J6x-eNfu17*2PElGbH#f5lWr z+W|$#mj0{dXG>SG=e2*e%>LDSn1oxCQW(K-62m(8ZpEm1v)eIL0nTAvKAOTctGcIS zbch8w@-jx7L15>a%nB}G#=8a;yZHk=*6|HLC=D`PPY)xS%;AQ?EJ=V?>C;s7MYtMn zULgCAKWYfFL7E*E?^7zU!#_CzZiXy}gSA2LL4R>@-s};;<tRE~%r)sLL_k6K8Pby` z2oR1YL`?qCP!Xl?Nk?c_0|9KSp|gvG*%E1^N6bVbvV@qZcBO-30YQu|iz8@%N4V<6 zOXq%f@EQGYR@ybK{xHS=_4~Cq?p@V*ZMcqaRBkzt1aFPq2umTZ3_sj9Tr}incTrho zpFMmdG8J&!OqwI+gxa^tj#<i=J>LcigGZ@)Dav<o+aomPVV$<&hu0f;Gk&?jDg8Bb z$3oDhLoOAU9-i4aXW46}*Xs2jm~U$cP1FI%==|%V)#c}PVqz>_sLyI<uA=PvHQwvv zCxw|o=J7*6K4{UlqD~x&ZfB5~-y?vI`RdZgnXS+DONJj?+p0QCH{R1WH=jSP<bH!u z?D{VI_}2H5qjOJ8lGW*xM(gZT0!fI}24FC<Ov8HxsNQQC>u1cI>0V>h)*Bp{VtKeh zH#37lx&RdN12FDd=#Npy>(b-G*RPbpftW`52k#by837KqrUVpJOJMlHMe)0-@tWmL zMPUm6Ca3WIq-4c2N{T{&K;ZT$o=<5>(w+a|wnU9udn#&xZ=<=d;ch;<hm-~`p;#EY zltr3?>lW{vxzVfXXwWoGo74b#pZ_|={Xo-qB|B?M!!27j?L`<;D~j`CYT;m4cI$RZ zYYNu8q`uaYy}4`EZ~HfdFYK(AzS-)O<%}z)bf~>J-Tb+MQm5Kuo1k<aRrLOK&Zx{M z+)i1>XkK#xvQVi|e%sA|V)oTHZM_SPj!CQS&eK2d3)xzcJQOm6x5T`v`_aamsu$tc z8@_NFm_<Y!t`F&`HJ>7TYU(d65Rg`#8N_d<@jb(~pUw-IO^^E9Yu??ZW&&DD6Tl2V zD9)*f_0yiwm_-Jxl?>P0j8^F3R*1JTEKs)+Y)N@ZJ@210UFj@yx-(PT7<;j%my5{L zjMzsXs7?REgwoy1bUF$WJ^Un1WG0rQAy4a>j-JX!4q9&IH-Bf5HGbh2I_Zu2ngD1h zS5JQcDf^t!U@k=biTapn5M`<HBg`O+X?3R?sQO~O_y??EUZE%dK4hcf$?>$t?07MB zhOhR*?STp~yx4JjaaqVGk{x|hgZ-|D>Z%48NQe5oM;Urw%vDZ|Te(Vyx%%EgskJs% zvh2H!tgPIBhCwuCx>AA7ZrAq5is#Ethb#>^J3`IJx8<#1b|Zz>JXYy_o<A*MNqhH} zd}|#Fx`&zGS8}2gD~lS>4fM`}%}vJQ?$7(7WBm7<&It-E4|loA1gm}{CGrtXPL=z{ zQw5>=m>2iCZlBhmbGYV0*x?QnZ9L}Beo@oaqpMH|djQpR>q%Sk|1T>w!Z};HL>vby zy4$TiHS1nvsr2K<Q#`tNx=p4P|9i`fZJ%VU4}QUQTTRM=hqpyrKVtj!`oc9~olEDn z=7+1!X;M?aSlhB;=3a-ZM#Dal<4fOC{5G%t%e5a|E^ABPyAvg-GVPx`_&@I}&hWQe za|e*c8F*&Jl=3Dep0$80pA{jAU-p0OVD@)%{rIfYN}bieXpr>T(F_B*(0;`8ih_4b zI-5O5V+B9#&Pf7lar#)2)ZdgoZP@GWsd4hem_2~-QxAo{{hFMoY8J=vH05jkm150P z+hMKX=qr+BX1`WNA5Ra)I)}ZGL+(<A-j3eksh5l0CE;8YnZcQB+^8V?$2-Et3>O?Q zMTW}+_O$u~#%o!kro+G~Q#G!jVW;RqyEkwB@4pNO5R7$|il*H8U-_M*73gBZn*K}? zWHeZyOxg=|srNj}Gn(n}!&Cj{Vw}wob-}4%p&4Uns)B&AK>S`wpi%6Ff3<u%n@HW! z{rm<mi0iSlm`VF!+mGe47-7@5_C=7^Ysj?un)|k|AXL#8?)+Nllt|A>{g|a?^+hAn zW(k65UnR`;Z~z&RUiko?i)2TtcDGerPFzxp+Cd*;R$FZntHvqq$arEdl2#jTrvQ2u zo-@KmPWL#5|3d?|ik912hVxN$t2LY1FcnMY$I&_X&RBYYyR^5>BZba<1n5W(=E2>9 z#>VF428ykuJ~nn?hN<5^_v7J5mb_aBedvRDyQ(kO(w$<FL7#j;Oro?%ik__5K@blg zIH`mOHZ%YP5TQ$L(hh%4n6yE*g8(m7XpQPF)NS@CUzgNsa7*b*&=$*SO!9eYj#fpX zVi`4N8fAB7Y@kL;Dr&eMe;5BSN|PY6^C(Pvcp!GMEYvE}zC0k{bfg2Y$0ATb?%nTP zs5vjp*n`+n?Hqg@!-5eW!g}L5b&+?$*wYE|VP3CT{W(^&dTzE1=y{Rh7_24$%dxTD zs0KI4_VU_&<n5zjKByU4eaDbV;x9Mc9s3<GecrI!`<gPo0i`!R>*?DYdxM8o_9VZ) zX*(!vtF=7G)8a<iw>iN_hU2b>yz#>GSi`wqEQ`;3XgUc5aC5AJUUvLH!tX;-mhfu= zqaLe9ebhhGHe%(G+W0ob0@*BqHvfvL&!yxt#f8rz8ledMtM!4~*o@s@DC_ROzW&md z37s&H4Z^c)*EfdCO%38#3EYoHA+xE9<sC%t)6IR@1Uw&zamolPdK72<-Q`-W0laJ= zWf9QJQgWhhp=QqD5z~Oco&U(*WRC6Kf`;J80$wTk%FszQBGC*MXZe!mj7aF9AW0yS zIz5yq>h7fIzYC)5WSfFUHYliK-7lCv`u3m@;RQs7J>$oS-s<O=SffFqt*7lFPMB+s zxml%~<UT9<;b;4)Tiy<iJUJZiGtk-G^_LE==p0J-2A50gq@NE7eB9)_>f@Hdk=Ko4 z*BW{pJKq=S_H8j%T%yQ|x-M#2b_)#nKzz?Ez4*|*;LQ<V$-!GKt9r&>h94^M8T+(* zhig92{Vqr9$Htmrb$9}t3BmjKz!tA&>wN-iIe7gV=GyRLNcSaY4ipxD3geUGDn3uV zq9(P};vw?d<yN`hJXjoctFtBGh*1RQi$c@(rHSIkg1n<o0b%%2?uIV$?|=lE)KT!W zPMGSqKIO9-AsEWH5Id97>sRcAw4^;d!hvl*rBeP5Nu367A}1lH$$RF-!gtN56hd~r zj3zv{>;Am*#2nwB?~N%Do?}P4i^`)*!iwg`ds&A&-;}-2BM=0dYL{srhg%vau4;7# zq^h6lT*j(O39C5RTHH5+`*SBjyjc&&CI|K_U7>((J@NL8LlONg_U~WjkCT+ie0+x$ z--;@CYAC=`C)+$?tdcGVN834Q6hQ!}f$vSIO&VDP8U0dSjIPp&eA5COZH1>&$}}*- zEQxBzC3}KGoy~KLUTd5Xq)%16*>w7Z5Pw`T%YfJb;p)eIHyv(z6ZEIl0>cHCWPv?K zc<mRpX<k=5R$SBV51;HHyMiwbX0P!+ZPk~xc@J*9?|<agtXuBfBVA`bLH%`E*gL+~ zoAYCR6{ySLz75aZplTF^=KR?qGi#5?uWM#!S9JfAGdo_}>Q)^+(Y5M+x1rCQJlbQ& zA9M~~RLe(U<aGoB-p{NL**tUBxAs>5=x_MDfA1=*9BH#^Ft@xS;cV6HF01Tt1x7>v zJD$FN=RU{1gEya>JvU40GKkly7U#!4e_VGjEK|AJ;h+3ps$BS*X;__KJJo4SSH#VT z`>`uKhBNziZSqZSsbPEaHfk+{tjw)}>)$nh^r%2z#6FYdKG&-^&Dx~jg1jRz_3aOm z4)#Ci>wh~~wWm=z*<Q!Y{xKU4v#L~jAxq0b{8Bu9bDw{^9m`zsrv;1UgN=qEHXSv+ zYwqREl*A6s_y58}uFgiO@S~z?Rm;<X@B>#=@5o$RKWue`V<^@K{303{Yv%(^0-qnj zT~;0cA$1_YsR3Ap3=R23b=~QzYth76sM$_B{y{S0CD;MTVui20a(d=WeE<nn-T-{X zU1FKbapN4DYbpv5H_<7ro<K2<FFl9qy)|Q+aHgkxXixaxR<U?EtVwxj9ZQ6BM)s02 zh9lO+k^^r=56oryWf#i~9Sg8M6Bx01{VW<%wnCwE_54%--SL6<3tnf(c-W>Xbgb07 zZeucDc*o5;Hy*i>s-^X#r{DVhaSF%}%(%H>oqS(@@EH%R{<=?R9k~0iR*H@23hIx^ z3@z3kM95;d?%77vqYydVpPf1gm%5#`T!Sp+WLTm07b`u9eAt!x*lIih*p|*Z)nMDf z$ML|-RM^Qgh|jpr$Sw}#mofWjq&nc-P)iDpF~#xK(|QAK1D!UH4!V!6KUrWt@pXhB zS)ZcyGOc8r7{Z>6z80bsYqahUM1P=Rpi7d%SRX_{Y&K?^R}?w2`ng^Pky@QSa$m(1 zz0?9coR_HLZ*aGxwQeh2;2#KMhoJfbn0BKCZ5t3>36pDx^ZG#P%Kda-p%c!sRI4Ij z<E{9lMDvMSYK5;q+=bEFR+q^rf>wcetbtXf4RT2|4b_UNYx(SAbwj!3RC)hcLEC2+ zht}Rznq90wUXa93gDF;|eNKX<{O0vc`-u?2Ha1X-y<|X9Wf6~4|Co#u756lvN04|S z{gi5|<O%;%=;`P2h3x<!<GrTbar}Mc;a=zyiwHOfwh`cqe9(aDHbyn6pjSR|*U(<z z$QNfT4uV{L&^Ef%yaW$<m^XI%!p0TdT_iiSvA~TF!eZmmK;T;Or1{;cVuOt4d;$?` z%~)S&n0m?Zpn(p?jt9OJOUQF2z({x8C5q**-~cIT3<<{%*SDYf=ep*V@a6CJWaRg} ztVqK=W}D&H*KlL~Cv2t~n83rWH>T%bt@{f<XHM?pd?(`FXHFF%i#qxa_Z&`pd`W31 zdPjqynC2bUZ#jO@wsW?sRH;o1;_tSnzxHYLj9hQELG{cd&ldhvdmlgdpntVOYlb)b zguGGNuDaP9d0nDvUOT`-X5it$Qq9s0rdtheeBj)_HSlIgYDLvzY4iJiVIMPszoG#a z@%S+~woEo>V4n5uP0WWCRZ_EG1Nzlh@hn&5JMBw)mj0bAw)Vn^F#~e{_gXBd+BgBY zsctW1(OqV^&Y<sy-#7L#g~rU)%QYe8Ty$u;X^;5@%~P55VM+<@Syp3sQf}1q4VxnR zYWh^|_ug>NG7ZVE4n9cAoOL<nwu9r{%+T6(()@<tP66<<=C?N^s~VdVsAaIlF5dfC zb&G4Qbd8JGo-?9c&}4;vshwUNef*tElior!Dt${j@Co>KBjb#17j8rr7-*1C#=gbD zHj7^g(2gcJve4D^tGu7A@(SzlA#AYI`|_3IYne(}WB8H~NXbOglS*=#RnQtSoMsgj zuU>4PZu~j2LjMaABFDX0TD|U%xsMhKrAoYgQ7+-45=1NTv=u<odAa%UftLJI>9CqP z!ETeK2ByV_{aQY;2?{>>NKudv(Ah4ax6^;OtdYMCLr?{fs*0rJD3uSVy9Yg(eD$GV zCorT+4m|wrFJ}j`a(;R3zV26@*cV?Iidoe31dCtw8SfpbDa+KIp29TuXzrg^yCMH? zrFPCv`=R36^4}jFnLCH&mbIDNUfwdLY0#x_yNH4m8p$!I7eCB0=)e7RnZq0I^CewI zqAUy=Dr)*6IHgGT)Oz+cO<6@M1-5V$(9~~U+gH$dZx{6VedToRt;Y6$zi(AIw;NB} zV82R(bGnhwPOfc^NoNY{M4^#xJX`+wq@4p+E&((CTR_t6+x;?yUGwME4lJ2SI(zYz z>8=xu6H^j)yw%y1?rW7hx{gq2X-v3rzVntzR0-nx`V-^!Gsp`F4m2G*#YLD0Vzf8c zx1CXB?)Z<>1OUj*V;L$p)xEylcv3_fZ^5|?a;y!v6m996^#dj&J3TRMx9e>7rRv|i z)pW{TN`pfaCte!YO?b*UwXnY~LFcpnWkYs5W1nnD(f!e@P=Vb<Nx2U&tf)>~yC*%7 z7i3LRdtBW2EcV5m(?&Jtn9mW_2vhlUl9ZS7ENb-}{#bms^phaN<PIM5s+P^Ky!r0- z-WfaVKzF1=10Q)ve+bDptCrP@1H`K1kndj1>@D1P<8DE6|FtEifR^{Jr(GYxp;F_# z*KFJ8da-6~WGPI)x`_T({fkAnqCI!%Ri>nR?A%)kMzy3)aDi`ZIi}ltF3;cQ4gM(* zTD9wyH=3VqV(8Y*Le4c`IMrauw(jGQ(2k^Dr@JAWCs(H=J}ZCMygIB_<DM7uqWy@q z?v@SXt|`mcomEy-9(Z4X=wBCJ^&B4?;mLO;JTLa?%-@G+792gle#^R9K7IO#A`3q{ zZEfoK$-*#u*?5)$Cv>(pm4@q|ufF>DHM5?1wnG~Z>#MIS{IBhbue2q$68cwOdE*t~ zr;rV2xGwzgG=I3kOx5!ef9n30M8`68uy>bb-)X<+#5Ec>zT+-+2XWuY^=qBlRAK7w zZa8yPcTwnqpLBp#^;<FH$KMZT7UpBonWJ#sg{6OXY&83+0)%6|d;t=SqRldOz;7Xn zuq#VI2L)#D?kT7|S9W{%OsN=E*1x!K*S%C4j%r2K@}9fu4@5{q(A=XMcqvEzlH%4n zogRN?mG`T>Iu^*ykmGA|fibGr?t6F1GQn&lVY5c0{5jVQS{?FK0f-A}?GPDjsmX5g zS`axndHfhDYk4d|LBL+Dnw1Q`GhUm9SvREct^zUV&M`<c7%&Nz2G3!Qxh^${YAAO< zezZul4~h;Z9hg99zJ;AqV+u9MoiTkJG)op}-{MZ65WBcrNlcxrEfap`tCf}^{=tEg z9ycwf7Eb4rNm80lrTveu@#)wO%^;}{Bq5JsHu>((81Za|E;o13oDQFlFq3NTzfY^P zVrs=5P-Z@7Wk?K+!`k%6SmCf;tgTKN*GT72h>9Li-)iJvg9UA%CJJ^S3~Pk?(angh zbL=VOv$B|7NOqP}E&3C5M^J}Zn9q*1^XKaG`{0WEuNj3fduNNzVB=bRT#QF4!4{yd z_2_b=%As*~k3t!!NfyVcVXbM{uzd2^hgpWRHlzLR!h_x|H%bv}V|%<wsm)MSnZyUs zoJmQT*tr(ZS?vDlex^?o;GwWNhWIhd>t)P6Mqd{XZY~Tr;m;}^4#W}n&YHqmtVIxr zc@eg}%!@jNwMHD-0&S`GS(@QycE~q_3-K`4ls-+gOB5@Obyaz1S_+;voKB^Gm{?OB zt|QFKP3L{XNOXh-?y%N4{qtVEVrNg;@;`SK{N|-!Qe|CZg=;^-uQPPfgvQ+PrPgu_ zjfY#6X3~q{?_*B>c5ItqU?^?WfhT0U^HSC>mpX<oQ}l@PFs#*aPUoh9GLf^~joMl# z-q7YCD&<2y>o!%ate8?bmZGNAY$>%IUVu4CDcOt6AG#mkslHWH3@kWbom;{d9Uo34 z!6ZKV(u2IHf!*p`>dQP~^^{7*KY9GGAaVK__v)=q(cUVbyZgB_M|inJnBhrcoGJ0Z ziL0a*{U*|jVQmv&;H9=pH1#$k10{F*Ub?o-vKwwrHw({~ms}DYjpeT4gS%zZaQ=N| zTM7J2CfO|BY@xXM?}XSNI(pUNha88qUrc!<8@fb3j`s{`+%JYXq~0p~-!31LTd+cK zTZ7A#)~=f!*R8gb)H!u#_C?Moq!Aw<YFM0nnU|M8fQ3EdwwQG7?2ovL!EfaEQ9~~F z9KQC8u5w#VKJ@pZ*#ErRe&!YY+R)gt@}Ri?VLmTpVEw)<Bibw*-(H7~mYSVjw*@2G zn%FuybY(EV+|f6}LI4^djzYq#PttV8-|e9KO!<T1vmH}HY5O5F$?$`)HamzsrDm2z zK@AO`Z}$Dgc7SO%xlkoWW9tXcM2!_-3j;yDuSzBH-ffajgHy2zMf*U6p^x$Qfp0_0 zi}T!Tcju3@t1s1HCy@v2(Wr^5+P5>xGs^Rx5e>j528$(G?){I_Jm8kr55zLV$un%t z*O5QG_nHe2*Kj(N7`7-S%6q=Q@}Xb+X6fbyOXmWgq}79$RUbi_oSXQECZ}8?iso5+ zw_-PLxZs;{VnEh<0{d$yGFoKJdv|T4*DRY-=<uOt;wH?bZ388k<E$7*c^!~FL->y; zr5g-&Py1S2REL$*CqQF9G3Bn|xWfWON=e)^(Ksz_w8x=LMxC5nj@Ps9BCW$Ef>LS+ zsmnu4ZYC&sN8#RFNjN@5L^(;g&@)Y9plPIji60-n_q$Z~F5hKLSAQ2eEl~!2FOZ?~ zkn!k8r`ZP&R+<&sZ#v{cQZIR7LwI}ez=Cq_A_$ppq4%;K;hC^UZLdC-dWL9sNdKsr zni+C?PTSI&;Y~j(ifzvn{}q6|pw4cu#$d~aNtLGWnl5PDEqlzzimZC182zu-meWQB zQwlzLs&636=bP5Hu!MoKb;P?7OV!uR)-JVKHF(Ls!{tXIXQurutH@q9*`Ha0)j{ds zXUwE#a(4c)gCQ*CT$NF|qN<dhQr&$jB5$){kyEAG61v~#dv_Wrs}+wZ!}UVaJ1+D( zWLM=4JN#aA1zgg5c_zYJl1}KoE$^PpXHuZ<>THeg7{AYGuMWV+NM7*0^!t*+f~V5g zLcAXHZzi^^{oDJxWLh%y)T-9_sDHIqR<#uTX}<S?`HhS>4m<Q)9nLo|*{f)ic~4Y- zJ^XXew(oOe9!6eoY_|4kYZNU}ciGS0?__(GPE;n{uOEo{YPY+AGNH5O&}-@dLBr5= z#vHs{gg;KRs$gZ&M8zQO*T`^JP?b7F4wxJDvFLYKqczg8d0)-WkEyDLwZ>XC$TWr@ zP1nLHEn-2OuHZ^DCn#EcXOukgke1}6)A>VyzWH8{GF44y2{`~QbiQYv{w43`ZnvIT zVOMP_eJR-gi?d{G4?8dO8{5nj27P{-S~&M8;%B`PrI}ONsmL7Q?wr_>Ka~vO1ijfH zBm89QagrT;tb(<F<7HA$RiWZxxvzaN5ax++J#+jdL6fTu2nCw7AaC;YjwaudQ=g!s ztxrML7l4I^kgS8v9}rI-mvS{UZ;qsvLKq_P(<oLvK^jqJL0|Jm7ISt6B@xloswIz9 z-14XXm0ds599xt``9M#Y!1aOkDm6n#rod}PIL`}EgZ*w{-kOS2{0`bs*WYk$zcj)S z=54(GA0J<w_L$jHpcvd{5+IJtCC80NGi4qiQ@H5~^&D^k6FSk*os1sE&&{L^7-$CG zhjS^Ieqse|&u1_Mi_UQ@hqtHk@*$U_HtRgl3}$5o;?BN8b}~xRApbGij;y08$AlTT z`k_Oxj0E7tkAiFjiLU{A%|;ApxTuXNA`KEnP)S)cWgu`Po%{&W0g->R*7{?oWPK(I zjM)<KIA|L60t&C5Iv3Pk;Ckrz6UK?ipdZJ2m9~iLHDlBVCBfpcC>TUC1SHo3NUFeu zUei_Or}Nv=$o|o!*nm-!rNsktJ6V3RM~9WgVg?dD?dz^t5%I~I*IC4BW;&f9>~~k~ z!V291MIN9it}$MGI8){V8lhy`p0&Pz%G2hBiYWzSqY8DW5t^V~vf$OelbQUTet+%9 zN{7pk$-$x8*o1xLP(*HM(w3*K+Ssp0&PHA3`u|uu^SCI>_5Y8GU$=@-)02tgi6Iab zPpD})GEmwusEvcDh#-|3p%sZBqR1FlZbyh=i%bStMG;&u6;U!x1StemazRu;Hf0$^ z_UZS&Iln)8RWQuV^E~%`-PiJ2?#|xM6R&=VbXH?^_TCwJO6}TB(jHXmxI{0X-A0=Y zE8Z=5O4|xhNpH*z8yjr5J}x|>MmNjo-5H?UI4P(nANnaTw+wzTfxB`yw1OMR;Hfw8 z{A<Vkf~4^i^_?wUQ;QNN-Mg~+*iVh2cew@&t*yGZb5Wq8F9$UN(W?slc4MfrxlV*> zk%2#o|99kjs;8WD?NdIwsGrs;wZNDP$$)bt0T2`;O2n`^Ey0@{&&{Di8dsZ7I!jK( zKkz0OMa(na<I<*2y%6trvp63TJ5zF_$BG>_W`(%uB7UrLy-XfPbBiy1!`_1Rmzi>Y zXMygo?Qbf!gp|xMuDX4H$J*`Pn;A3xY-e$<+gR5>OSk{V@EUc;R^9o2U9V;P_~#w* zqy22@iGw?xX!O)KA)D54$UmsG^6$c4#yfOt{#a8UvT*2C-HxpHNB??2`7gtD&x_$d zypIi$=)*n#1((Ftg)earrqv!Vmh$krcKIIU<XHDNoU2o;#EhP~lp@%}rL<A?nY!{a z9TwVCyjGBR)-|3Ajy;8*ZhN~$yUhb8xnRQuc!lda20H6P+dFeVjaqU-Pi5}`SpBb~ zX3H&$cDA)l*l@aW&EyNZV6t{F!}UTZ3G~(xS@=bVWjggwA^u;csniIa`0LEdL6MS? zPQu;My4isb2f)TNU%1pWw1;h`C0Yq%sh#K0sn<CEu&g>Ms>^y%NUpW8CJl0Y_J(Nl z)gEGqE`Wz@#atxC8O;Ea8P2Fy%}{;4)c^wTR)W{iSJLVGhpr#(26+QAGaPFu0gy{* zM&^dA^9RuJ#4>r&@Db>a>5_H!qeeK?N}Fs{-2Pg9+~UN8d+9ShWV?dj@*u8GtGD)0 zA7YjRQ#wW6HB>Tvtj6iRw~_pcO-fvl<F-b`ig5yC47Hvz2Zc3Cbi*?1K}Hb}rce1I zaae)nnv=P@J6kasS+8lgZnqxNq}Z8%hPGMQi~CDPt!bY<6_2aA%{1x6#MNLG@BP)* zMb~;}gumF@^5S3@#_ftndQ51lGnvk<ObwaQb@z$%2an94ZA<zXVg~D+n6~-}P=mvw zFAJmHB5wcGoN|VNopF^=<_}DewnfBG+;n|F4=F9Cz2dUpJ@p4&CpVg>7?htLW4W{M z4i*ad%$*93{)pm~_11qkhd4ccYl&-BNe+7}s89OhuRQ(LP_yvnYuiV4S!@LiWT<g@ z{w&0?P4sMoR-e7;v2g+_AQ2_uXJ#rKF3k-se79ui!{d+VBK1)yJK3&y;Y}$efX)Wx z-aPY+t)Dk;=cqnU;Ek+!wkGv)DeXAG$~FH;Km*h(MrVc=YKKMA6P!<gU$uO5a=bL! z=*8T-Y3jpE?}q-FTXE%X-34c3MGBF>R|t^gx%MtexTdz<$^ZmiC&dRvlh(gsg$+G~ zbUCCnH~r<shplxnirZy$`(l3kOmpc#^fJl+6l{>n)9sX+&*Z=vnA?{cPa$M)Z%sYU ztqWf0uzx3|XdohOIqoLJ@0h!P7t}Zn>))JZXaDTky7uXxB>fh!W>UnBOJ^CpdeR7U zZaUL-KpJlX)x=YXuXp=+uGj^)jg_&O@)j|ldwnkLvNJgVr-Mj3T)vqte+l@$_j>35 zuw>G>ODSi>AejkibjeE;chzgLk+zDrlzeka{S@_)MwTv%7jn@=y}$iRyV0p4y)l%< zx8G`G6mOd{9Ia&lJ=|LvJBOa|8nkGPS&+5`p{yFeA3QT!iunM>=cEl2F(4YK2u=KP zuAvtNM#jQ8!bV6M9EF8|iR^%Z>(2Qw+@RAmIwCoTIF?z#Q`buP?>;@b>dJ25_2A;q z56A*Y%nDCa^>30L<S{11Fk;rZwNWZcz;T6&CJ0BH;DVD!Ul-UwWORvK^i3VdkZS~7 z=dY-pNZE7<E)SgDdJ|F`!QN79kPPN85hq|WM}LJAw2ajd8!hR!g5!z`H2m|3JQVv- zy&)CvG!Vks*F#^YH%kkkhI>goENAjS)DvsdN*o38=8Eg#_L5yN)8C*Iut#WjI{qKX zHXuIA`4T((5OMPo0<N>;(}`z}CiIv%>k;u(^S`}Cs8~gc^y8o@a$+z4im=libOI3e z*TF?JQlMn)9Kkp}&5hkI%yD%~m$1Sb4t><Iw(IEo7A_;<j(kdk2&}jMLWW{r*q2JQ zgF?O3H4KM(e7xrD>XRz=cDN(LR|%kz@Q@wg{q3(kX$MRw{0k>)F9`d=SpD-m%Z?;& zEDE{Nd%a2hVTG&|DC|IyIVan>ZO(7~tFQbD{%_L*C%zQHDLC)trN!7Eu$%fTtqT`@ zJ~4fE#>O#K-hRgqo!!#&WzYzzP&rKq{HWsNUA=2>z((tiX*}CAH2<Y(oS#*H?>~|i z9kFj8P5NMC#*MAYCrgYmN7MD26n7`hPw>F*gW1uA9nwFl?#?VQ|1Prd(~0mLv#syQ z9a=-%u#a&Iiu#)%G~L3`m~6fL?sprk^{&1~+nih6A%l{03aiiL@-u8~K1dvq-cuUZ zK;;1w5@j^5Jh9csQ|HVan+H07YV4&6GXesxrNlQeddkV&!MLX}*DFt9D0_b(Q<x^& zP5xVYP8h1SoGc|vI<!kFsE|>wp9oAu(Yn&KC8HsCcG-@PV;9x)Vm%Y{ZeQg9Rxz_1 zB&W}{lRrV<7AdiE7IHA%qjL{y)Svnvd{>C+W+IiClivNi$|hZ3H=u?9TnBw+@mLIH zR1V9FbA@zbT`)|EV~uO1kWN7pvD5><sypD*F25L~i2s)m{XD=&q{S$HoOq!>|4KWp z|DbXDjuKc=Q$53aiPjjCeqm58t8{w0x<n7kH@i4%k@wlNXTr7vL~yE6K3$<nt8R@e z{$lI3o_VX^q{X*a7RFRmY;FC+m4(L12dZzSGm*w7<IYN-C)xYPZ#$lSSC|?Jz1%u5 zT)&jab*eRotmpo6M#ehy+{DuEWma8tgg05nmre-ik11PETPiEMa0=pB+5v+4DrQmV znK<lSR=l)GXsFj9c8BaaAe3aIy~#8>Mx~nWfE)=2=YYS$&3U^?!k8pE#Mj=O4EU8j zbjP*Oai|zr(FzA2WEYP<gqOsupudM--UeEl%oA|>temH+Y_5msZb#5YKVvA^fJ(E0 zO}z@m2bv!5TU%S8krE;N032aMiJAV>rArFw*)C4M3<XQ&1Wy~tYK$1^oy&<dHUrKo zT0iKU6rGC<bM%oik-V%@#;c7ZhfhvQ(IqEtkwrAS-f~kpdcy8%*Z>{RHVpKi80@*; zT(aj#(w=`LEw#&kzY2s&AoSN@|8i298Zx20V}@B*(Y5l$hbA*32?9dhv$6GIi|cO3 z6DKOZuD)<7+|-sfdv%q!?w)jyRcrr?pe<txP1?91o&C$_Ltf^#eH4-E<lDRdJnRyO z^vv~dUbk$Krk()MCof94)97r)vHemX@2w9t?>{SFwD#!bm;1M`LeMK%`hZ9q^K$oh zm!@vrcrErlo%@Crr%UAQMqT9S{d*hl*hg<Js4Wp$@ErHn5`FJ=gi9f_fZ`T|8E!%E z+4Rd<7`BC6^Gu(4q`_ga-$bIQwm{lBwXTXD`VUdndt~{oFU;<3&_G6oO9fH+)TJE# z^*aQngzey<;@v%BW8OJvCHmH(hGSoS|E9nG#{_xT#$#KDc<PtjIxY*_Dw@QbbWYxx z|481r^h($ECuh>*aQ_)E!e%q#t*sG%sP6_{%{N`EYj&3R{)^S39@dkaU;NOvZWmV6 z$I9=iOsH}fh$+JdtoY!iOI->6(#tAGpna94D~8kyDE&59&iJAoV}Dye7T}*`2N^42 zd|D$=`xk=YZhc}j5+_@>C=9QLoxArer|O~mJ%n0*oRh;>EKlTy5ZPMxly-0V4@DRI zg9G$##h}z~?bkT4qOaxkkL0RfR~s@u-4x5gY^tA^ZV1i+wcF#n>|Q}{H@ICVt2j(l zIsPD>Y+zDXn?mo)Uh-%i$fOs4>CMeV$J?ssytUoi8Eds*y?P55Xwf+<z=uZIJ}}O$ zC6)86r^n7I$hHu4n~V)sAWYwU`ek|xH$IvdEN%cO#hJ8IdWp(bKuntVT7&z>1iWvS zQrh2_L7A60yjo18Vxyx^2@pbB0BU56DoRjneX6uHD-ag4Sk2Uvw~AT<C7!3)H;KSk zV!v+mva+2rqrGYhlSmgKDvN+jqcTbTZZ&p<L-gHsuJrlGD&HxoEEN^K%_??0iUkv+ zgzS?jjju-wbRk<iob7{7oWwgp56_P%oH~QS^axH}7nIqe`nAM>B~v0V3l-VAR4UnH zEKq1Uv{g{fcTr72S2hj~Rg$`I_X1K=$WCMqFaJ6+Tnyd>p$zlOIlSdCA~ugv!@rV? zGgzZ5d1LFr3fsM+5I_RM8#I83CdtM8P7MsjWu4Z4r<5Y&m~nXH2%BJ{AWrrO{?T3g zTErw*jSL!lPi|T1i;UT;>mMQUrdoB$YkR@7lE-iDSm}Nt|H7`~0cOPtfBm$thaK<x zch_d$NB!o_f<++G5Q9JhHXPcX7PsTDx5qsXPmdkCC*1EK6H?$Yecgcv4&O`5$OOOr z)We<9ZH94s#j+>I=PbE>Sob~;k>}>mU1+cAKC?agn@R7s79;=m^2;_9$)5&`UR-{g z#p8|#{_`K075K@um(6#W1*UI!_-2CYnU${jiqXTP#47%@@qDS}%lPW42y*;y_*&Ed zVDB=YKmYtc&*c$2JNB<WKO;e95h(@hmbP`poyLj}!`}xUrtNN6Q~Jd3yO*(weBJN! z;E(%-pZ{vn;<LcJPp98Si7m6~PIQC8KYs3m_G8D80=Rl-)?AQgBuwpP7v6gA;H(HX zo;q)?UDZ1a@td+}{pIuD1t)C^nh+9uR(j!hzv<QTzY7_rkjSm@dU=H5N5<;>`^W01 z6n!l}J$p?<!;1XTlc6FVY|6YTcl%ife?(wITBq(IVGeTjXguAJk64VoYw|e1=Wljc z{(AUV=}e;Dul_5JUwr&Coy`t?f%#VL_o0^bqK7`9mC?U`+t&xOJT{PqfdcjwUQ=t< zyWlDw{@;goPwmf~b7mQ&>D&Lxd3-UPcyqfzfJcr+HjR|p&Zulb>+Bzie|qmn6=W&w zl?sL3ssBDZZ*{JFNlUj6<0#r;pN5Ti*wVS_dYjR}8!+`+E<GE}Q6w~b6X;vnhc6Kg z-0GN|9gqE^nkK}(bXCa>0?7+*@<MikT-#>Ta&>cwiN7|H-9D{p<CBQ1Q_rVIsSMTJ z_32`rMyy!^J~XRmR(FukY?X=5?+8~meUew;o1WmCJT%CCIJ#^5Hz#*B@QGlR4L|Mb zs@K|*V=t5zIB$71x@dbjn|9D9Oi(P@%+V_IL7Sqx>S3z@GaD=mhbh+)uymg35zhKp z#?%&UUUZFS9p;|g+H@1q1J3#IJq-qoAl}pzx~di@9=1qL0;tG=JcVvB(<5*=j_x74 zkmy46Y}iniG+NPt(mB(#6F}r3bBWVH_aHMknt2w@yYSdZ^1q&<k;AKxH2$Hqlt>#J zookM^7*EBCO>95nq~%yQ@5XxTs2iy%;q(C{(B$(_GL@iIqT462PE%Ty2ul7jiN+PM z4)PC@WPuNXof(}oXnaqRcXfu1&4}}~EkrlMf%JufVX>`xV#m#{&DVa8+dU&W;ddj& zai=fQ@L85OoAB2_S-`XL3P*>*#=Bc4WN!I+#(oQfExRbF3W$57bNa63Ve>AisuM;C zY<{8lfA5?vb7C<NXx20_Uyr?gX?){SC%Mk6KHpGQ!8?}HjX7QWe_5eF7HpC`cxrph z{XCk&dWJvJol{8qoLf8pc-89pw&{Hk=$LjIM?UB^jkLmajG+#P%bfN%Z&cckc)_U4 zKnCiWzo&2Jq?2nM4r+(#ed*xVv`;;Jv%~vs67AJ<ZYqx=o%4D3&OT1?!};r%{HQ#( zbxoQ26eaD;lW?;;r`Ei>`AX*muUnCM$T1W$nC)L5dcARi^hfROZn64NbX>o61_b-` zg<aoIjN1}f;G045sqgKuyykgd|MSPRC)XTkoBH^*Gml<f@kCe%k!gTI{Ji70l3^%3 z+7x_t(N2$0$I`3GJI3~`kR-ukw>~!%Z!Kw$`G2@=Ol_j6&5_fAStzp5OcP8?ABbhm z9+*C5=b5`-(ET_We(rj8R*5p|^Mk|sa@t47{8k_EcVFQnsv<-u3%xoc`p(Zf!syIa zZF|mqj!=6?1E}mmzLW@CfB?2LFoyd5C(o436|N04`q%l>H9fiZABoia*>d-4n#&y3 z$L|>p!Vc|R_>jK-9)QdAVZ_O%6N$pd8Fu4T3LH$hF|+8lr?^PobAxD`3@Z|u*q(-u zy6T0JNwmtMRK`h_!q5_2ed2IN=$lGK3DSvL+&LQB^z1`PgvxfZ<l}gWnDA~Ag-5OG zRI<+H7?9XJUCPhYz(?C|NAxsU#kmgM;EpB~MXFNh3^;NRq7bnqNZ@YH33>-Pxt*rA zbHx~YM-NK-l(aOm)<xoAXKao~l~ujVn2W0&;SW<A;!%uA40@t;$Mcf8?eC)Z&Sen+ z1zEi01|-KLFIB>LT}Rd>{YPR(sMu6Wqe>wCSCXdByrJ7m95K6T0*}O%<YT7FW^N4| zd?u?rD`3zXpaf7YX7U*4RHcCPf`>HXTu}&EEj}d>wOktG#r+R-OR-8KwISKAr204} zN`F#t`knaO^%mL?xC9YS#J<3Z`tH#?Wp@{I!=IN0zX+y%o}hY12(U%*p{rylWvIBf z3~8%!S0SJ!M!Y&V9Xv$Z95sPl4G#)2ztiD6fr~9R+Jxw6dlVtsYf8ZcTEEQgq|vZ* zdi}P5pN|W~P`m|_NZuQ_4!d01HRQ?(cMmK54!KD1M9U2@LB#>%U$|+njVf+?^+Bko z**}sa?Fxe|=0$$k^L4k*OquPgs4kn^w?}?mVX!iOnB{Wn=>+@L3X9*2<}eC>nY7LT zhvw&%1)+2MlV<z&ZJOVY;c5!S)o;4c=hf{~%M=^@_U7OHHRCZIeC~Vib!xzp-fnO6 zLPg7z@-@$|?$EY&zWla4WQobR3BM#PyvGeB@5(pcTX}ec$5&~`Hr6p%Qh+j(Lr$3b z=wI(-yR=FRUfuY+gXbiz-WRa@?xTms{yO8Qo-Oa6nej@A)xB!0wR`f<&{#PAkHlfU zC90q={2+z6t84T0c~RG+psn5Z9@4iOc<)+iOEtUQccY@G=-#E9)w%lT+rBh-cwH7# ze+R<O=`2-2_YHaWs@9KFlM9Wp`g4dP7!7&J*Sue;yQo`Kj}AON@3~ElTji?x|JARn z_(b69Vo84HWcrzP&FEdBvV9Rh(D|0>PX9O9vc&w4>k;42$n-g*bFO2MV1G8bq^3LO zh1GtC@t0C}NbhH^#hl(Vsz5xTrbFK(Ozu(zJ?=uSHkdn@5Lw{WmYI59o^EEIEjU!i zj@afLvFfk!XT_D+>w1fKbxIpS9RmW&o-$PR+=m`soQH>EZ#I-JfE~w=+x)9J=Pn_& z*T?<ry)V%*9FYAv<UZ-(<A{Be0*sz5!V6bmp;jjQu6YOBdk)a&heEOz|5)hdy*p&} z{QZIpFAkyF<Ga86b@l<(f}S;_Qv7Dn7!zBgpzou$^gfIC96UD_SYD+PELp#9L&B__ z@&Ij)GKd}`;^yE>@`9G%vAX@Wyt_^Zug3Dz-DxkkPjHK$l$xQ=@KS+I)v1=VL1zlW zeK{ooH@+gt-_u4>oq_3hi}k2s=yxuNY+(#Kzy9@-8Tja=cZMStjca9%Zck0S%?ROl zHke9-QSn|9gBiwcOWljCF*APMjP<{`uV^xKHuwh*B8eSHbWvzaKwP1Z0#tSe_NH>3 z+Uh3}>FDEw*M8=}%nl`>naur?5bdJu89b7##SQ%oEFZ`-rs!0s_C*lAi-vvrMUoD5 zj3uJuisHm+LM7;-#;S_>{R!GINT>^&``#iMO}t}i!N6<9JdwsCQW_Yl*YM*C7oYe= z<RJkB$Gz5OXj0VPieXtN1`TgS+~P=eqLaBeV}vmjVpj6p@KiLg0$yV=EZ!DE@fm+= z=Lt)Pxedq}5T!+M>>>d{C?v_=LruLfvoqk#SbEQi-)d{qdvX=wx_!ewbEZ9vWraXe zFT$Oxb-DXAhG}rK5F0>h8~5Jdr)efW^io<?9jQO*lN$1$uEWQW{7=k3alufttMed3 zlhET`AO7Lt7a>>pW_YNKm*&<)+{nIWZDo*UuWcRneEO4;-ML?Gi5*iQBjl7g_Z9u6 zc{*ZyL8Dvjr4P9s-PJn%+Ih4W#a_bh@DJ}1imx}Gw@p6L_T8pJKUSwL5|w0Z!3jQ` zt=Y%qGppy1FPIQ?|HWQoDb#;ig4gJfv=u&y{U<S1==gp|O0Ygp-Jz{AG>*^PDztUH z&)n7`jNIg0xXAzgkB41L7<Qs<MTEn_3=gG@Mkc3u*`=vnb-mV=UCW+ti~ZghmsZe8 zN%RX5IDbL<$*?8?r)jC(d@t+Z+e*6T><9acD~ii(3#u=^jB$vO|EMOT;^}~YGHTm$ z4_k)r@B0kdz8U}WsH$psw||!_rs^ir#)mFlQ3cYG9eR_-Y+tRfOaPM>H)>}(_ZH~! zVkZO6$vz&kF9X2(JvUL+tu04>myjRs;$6+q`Qft0-(sVRQ;%eL4p!NaxZ{Uej)a95 z#WLvlABQ)cy;);;_KBhCzbwoaiz=@lc1z>a3W!@(xsuAV<cN}8bW=muZ<`Z7x&6g4 z=JS-R#e#hr+>B);OgUP6r!HE6*7!#<yoS634lVoN+->=v>KVwY=?C2UXfau4_s~vY zCGAtcO;I35mA;%-$F?Ae#-R#7^~9tdmUfEs>UPxA+AT8dEI1Sv@jM&A)w@JRAYU{r zt`<dV@?K$`dRrK)dNw-ClKJKWD#urG9KlVMBbHwy%3iYO1%RxX<Gm`hj5=7Kyd{Yn z13$c5LvU7AGKFFB%aQHo1*qzPZT1|(MW$16O%pDyH5rq*YJFF~v#HJ$Qww_^JzR29 zeYy_1WelUsi198Vx}_$Y7-%DB<^yf0I!W=aMe+bR({V7MOP%o7Km@E;jOK%A%Y#(t zU^bW9O))=n$5`47+>jn$dJ1YJ^kCkV=pu*=COQQveh~U^EKC#%2Bi3+`qxXFEK<2b zRLDU80ZW+7(2!CUVS<6-gudmLKcY=1X(+xz_^M5v^m$LnK^s#<?$BH2s7Q-enoIw1 zdXMA>jhm(^MrZ+{o`Cw*1WCcz((~7juNaKm<V6;}(aL4TgP!_jFYKDv`cge{E9ODr z>QhRlXIbN}-C5LtVVq8-IB&iquJ!Ei@99lL#+z4GHCyQv4qGu9XGkkPGB)PW%A#SK zjfV@2dmkS&trT$FzKBP=C`5t-?`%Ejd7@RiEBykbzIpBpJ=<=DnwDNFdFAJv*5IHZ z@4T%%(S*SEpyy6)A1qnxZu~t*=lp!SHb~KI?29S<*ZD=Ue@wFEW8P3d`O3e!hXhTY zu--q^YqjouE9_>>w~U#w)kBR!6)s3>+cSe79?DR!wfA(|#EuplQFrm|<Cf>+gHpT4 z{ag_*mm2=!j)&z<Vug1ErUs>YHJnV*Dc=sJ32?efc|yABi_j^hA%1J0I@MOf0AiX| ze9Wxt^BuM-tFo`<IV6YA7>LCU5KQV0h0J?gHQK8yX!+TEnr$?EJe1zbzS;eWV_bh8 zwPbY-K*5RHy!M)`Rhms@Z@uODqNK|?=TFx!9^KBAU#M3EN%g}Xuu1$^DEH@_%{}># zWP#SM%IM)FXwBNGNfop1t6#@JLeS^B{nl*H*f>6P;;pRdvJ35x!cFbeGrOi*O}aO< z#H{Q4$N#c8d*N2zb-J@#wV`>L`x@nbPZ~P@1Z>E3(5EN2rnBO!xew=jZr6EW?(Dr5 zXLP3BKFb|$3x9~zl?d3AGS|5LeJ~3AMxZMZC0OhpAeiAvM*ESnDx}_NN5j|*aMhZV zu*wn>8M)(nP7=FP(?;R~-b2_G79rupHe=5W72Z$Yw)?CnN7N)2A1=R<%5WMGN<b0P zQlLnI8v1IwV=N^~@Te-trh=7|M+6vP1A}@+b8`CFuD$|sLS1wRk4hi}^?o%*;3q`D z3`k>;2YpwReDLgRZ_&8Gb1asfG~MLy0l`LvT}t~Tm9;g<6<Bd;O9u;a{_tehtzf{` zqxXio3JZm)Ad>-&>Z$9^!I-4Ow-qWo^Gr$Y=`A3NYCrf%8P0lgjz}e7#l*y<eJUB- z1A@+o^OkQg(n?J{47P|tWT(yC`pNQKw93g2tP=;n|DIa{W@*j%XC$6LTgn>oA#hDz z_?j_`Bn_Psvr=R>%WyUMsK@r-FO-YZOZ~-zVfajX6&qvKlN;_bZAn;WaDtbU*xNQP z(+lL0g*1Av%-Dag;)<95{6&cT8h=Jq^*N=L_P&B%(Po)IdJ7m&&-X~^{wNH13QQQn zA7`%9%JqX@_c3Z~Q@8cS-f6oGLMzG`U*H`+Va3V$|7|NYNmzg`TIBVZj;i0_2ii8@ zQJ>g)NuA??SSkrpsiIEbtxJ!+KgM$N^Zl!{-}VzuNK2-E4Cvbw-HXj0D^k<C4lZeb zW);4bvmmzZmQHP%DSCuucK+{N?Y!rPMu(xCkMuO%pJ$rXRaS80cFy0l=uwdTab;42 zN5MT=KPRru!(+)p`;R5CVwC=1)%g7N&sSfGTUN=Dn!N-nsl0?vm)F#~3(qHQmv%%J znung>a8C|~aBj^xj%@6pi(38m=}+H@f3k7)h5e(PAKem==-UOgElGcP_VrSNCogE9 zTH3d~)z6FJM=J(Bq249ECB(UHE6pr_d3j2S&>3}L`;_rFY_EkxpON!yZSo?^PK4RZ zb3OL`G=y51Y#W@Vp}~DH$3d`{em8;3i6(%te@iGK`NuE)-M%edRZ{z4bvMAMnTG0Y z$F=}{+s95QZhJR3g`Mo~JIC@*2S3u%$FqIAM%rE?N{blHmf7+vqFxlrspK$?wGmai zqlKiP^dpUKFZ1)FiWyVBDBJ(-Z<K(RLaojTR%zs|coQAuNe*Us_M?;OL@E{Sf9+(7 zA0bRB8&YD{cG<w;>8^7$69$#>xAZT{BKpU>21}bL#yu%NS%LY{g_DtSj^HaH#G(h~ zbNi-=RvhqYfuEtps3{=R?e=liGRc)-zp7dQqd+v(dy9O2{NEZDME}I$kI==$zhgb= zRsr@T|459%w;})mP8ElBJ)wlj8!ZfRD8i-SsHQt%o3bsU6WyCVfbD$A6`q1q6&`ak z)UB|D>2y^B%>OIdK;vIVM=fsIMe^=^TlC=U<@vqcbk+p@us~DzP7&sEm5}=lijHVi zZ%I`?Og~6<pvpLf(gGwZb159s0r-Wb+L#4}De|VtTe2jz4&8S0k@b?9QdH@vN^VU; zxJDSA_xL)!XUeD_kF?r_i%8tU!XVqacz49Ch4KiHUZz`Sfi7JLuCPvyBbE>#^*J%a z;tWfd?C$0!kyv=g<8%ylJYeh$;EH^cEaDG09T_3!hUTxU;9zI<K342hJeIf38iyp& zJ#+|N<~w$1?`A&^8UN6Gj~~_$w!nF+SgrYgr2QlL-6^Z!(~15&!W09ZYE5%KEI;lr zv1{|Q*dGBjUk@|IIY^f~-R9lLhbAmKU+2u7EUe=rdy5_!Wm!Kg?JBI^+Bf3yn=iH5 z?2X|~k9KU<M0wsy2#Tr$HstccFI+!nU0d3DV}w=nWEv%Ty&bh%49cNb=>v!^T)BNi z>ezh@R=ZTKAD8w1?htw$t(#ncN9yL_$cia#Z@v5`zigduhgESxIS<EpYC+cS$EF2M z-&&?cX?^P;7=(uStDdq8(GN@eB;xrBPRC5XA(Xv}dC`Y!R&}2ZO7e8CRQbvMKWbog zX9u*lJZqVB^6|f{^u=M+@jmgEfl~7`Qq!$k_wse&Ws0+~GOXgH&5Z@SF3tC~|1&eT z^Bd)-L8uOHqWk@jJ^TES@05=<=O(FAL#&K9+WONDW~e4^N+I{N+@5_vKId@_Lk;x= zB{`w?0(env9R=#2ljLm&jOU-cKVtwYce`8LQ9^TULiW|ljmtR#PJdn3{>adnI_ayc zn>{i&73{EzWTUOB(6;(q*0#oM4L4O3_tHJ1qb76?AAR{%%B9@!S&Z@!pZQxcJkLz} zUC7K~Kj|9`!bd6Ha`=PS(w8SFUfUX~vgii;3N175t!r`1{;u!zS6lS}zSU8DyzrBD zh0R~N9Kdm;aCo6{mKRg4ADxx|L``=V&zzOB0^Y3d)O1JPR#{}2_Z3B~5Bll9Q1?g@ zuPB*GpIFA4M|iI{*JNyPfJSg&0NN~w?vKV~*>10O+R`D_n1CmqAcbQHu}>Dhr-q66 zSo-58I1(xsj@EF*;smWrj%wxz98E4Ql4_6tao4p%E1F7q&?XCAN}9&eeTULqH1~-( ziPOvq>A?$aE%RwWZ)&Zzt;=NTr33_`_U$qLq`YKd<|-`896g=uBU;Mo{HG))QXl#W zqvXZmOx|q)vXE9ZH~2!?tsezT-&3fYTV#wWZnw5ZH!5RFv^etll<C%k?N0(^(IVg} zYMpo$wSB^R(EqqZ6gtiMH>bU|nY5?KIy`f^=N3$-!c)ZeqZOH9Ezk97yA`cl?mm=K z9I2_fjn4AiA2|ou+G?VP$pbNuXh;db31W)8=vcI!-cnfK3>`l?{J;yux9Gzz77fUP zPmMlt3rCY1(M(t|D#B2oMm9c$H)n#Tb3^t+G*TCuJcvyT)7rXZxRU-P|7{#?y!r6o zT|PUEdlmXGV7T0A#6q*T{jqn!SHqtCk*QsGXnG4Zqer1-D5wChue&z?v64J8F&||g zt6fmj%A&u1t2y+7N?0xvbi<cl@N!XGFp03pj&c}btXS%8<9o?6VL(<bBBO?j3G!a_ zh0!9XZPG#W%I_je{1_C2rSn@HuZ*r=7g54X``5c&;(0;z2O_<^hNcVRs>bG=N0-{+ z9dH_O;a_JKS9f^7rp$0`^|}`vNn3z?YK>{zsF$v-FAT~IkKov-!rt@9q|c<DuFCEC zYwIJe?YaCt9*d*?#^%b2-YaLK@uYP`WXk7HLf3_S)U`S2vH54suL6)__Y9JAGUP7` zS=+jMN!!zi+D1*m&?*!&IhR*?Pv~>+*W-CJFZ-c~>?Nn<qE!s2mujl*m=>+~NVw+Q znBR7Dh_AdTN?dY7Dz|33wIrfAtK<sb_3BY!5Tnypy>We|&*Pu|kvv&#?r1(VyG7B2 znoagcZU5D`DLuft;b!uH%t4peSU^kyOc(Uf)=<-WJUzaa8^>UP<L=j(m9ypdG4&J; z%wGfLQalNF;TQ}392Rf-nY(qg732?Hew4p-7S$_R!XY&}UC8FZr(;MDv3OMm=_GVF zhWxIg-<CKMgYhO5Yr1_oL3H-vis`}{?OgQ{%J6pJc_lNbu&t}8)=4n}B*F=Y^B+}x zfN#-*{GF?D1Otw*v|K6Fc(N#kBLR3WBX{Y^&4Am5$<8Po-SE~Jc%CV`#Bi5Y7LgEy zN_u@9P1^;eKUgD_-#Dq+w;&uLeVZg`i9U>vu^r7hl5tA8Kx-*cPt=n65dXex0Jf%| zNXI1}_TM0bO0-&+w296m<fM`g06(ol^hT%Rpp1oHR}=ymVaW@cB<F3E$+R#CM*nLW zP<b6LFHQou@fk<FF#ipw(NAks!@cxmsyE<gLcx!y-d}sUBUK_*5KR=|#fhkh+=%Ek zFjdzc3r{grb8t(-NUGK0iiGbV;|oKJf0qI%kVGLLqv?&HJ5mA}lx!s89g+HI5H5C_ zL-nP9S(a=-sa8ds2Va<HiHWE=B}a8emdXHC7Yda=X=6>2bAyo-DK)`<#JNa#Qo_6T zMb*x;W$s;1%ADD8R2V#jz}mJ7zt(K`2xZ&+lqf-txX@qFKZ^*75R6i%HS3BeL#+M1 zqH{|`ZGVr$j13;qp|4$tS^|m^h`pVHVQyMXWO7%S`ZbTs(#WU2iuQ+!j=f&jqB7kZ zf4vm4`Ld$#bk>yZiJ{t!ud9dNLdG2i^{k_;cyauC`*!s{y0rgE)5^%n;blgZqN2b& z<j-p9uH2R%)`maXiWmqgZcSVN{Leha-DAJMH=%Ctr3!6r_ZEF)wRT3G?$YJ(S?7M3 zTWzQT0T}B4MbB;Hw*gW2)KGxI3Dj1UdcUgmJyLCWKKt()ok|8_$9##)qJ#0{*UqWd z{;q$$(%Y-ayRFlA09$_hj`X*x@1vS>QG&WpJn#^Y0HB`x7d=l8KG`UBD07A*%J5tI zApLTx`xmX+B&UhrpbyyrGV}BS)iwE9^OA&1^FpTH%sKwf5|>wF$M6n}!$MIs&i?7? z&W}2pr8&E=PMKZux>x<l664;rR*_cpRdceZwWjS->^pOP`eZn)Vs!_Zf2FMK`eB>j zv(DDK-k{~iI~R8Kj|KsWz1zUCRRR+tv2SgL_IE{c_cz*t2YNbg;^cf$b~a?pqx!z_ zk9)V1Q9iJ0nOdB;BtxCGHLST=G4p!Z`;)^IEftD6IWc#YRvAhecHu2VQv@E$T@0rC zCe+<K<Ndbc{4fe9yNk=NPKe&NB1TR#lY}PNdw%2Ds;_f(Ph9T({Eo+)m#9OrEGXjU z2fjH3lrBgh(+`$9YA)?VYUbHnLNg?Iz}$O~zx{eeUUbpm$Glu!ou=xnH?x#t72bov zlSX~Gez2)+tX@M85syS+QB39R?yBsx!5?;@`n`h<a=hk3cYwgF6NWhoaT_-)6o>X+ z*<pw(ulKB<gnpLO+Ol}#DVLDQa#=s_zLNP3I;A-L&6Ry)$82IUf_>yZ>rwyBIFiJp z2^c%Jh#r46DtHZwaJqZFzK)}n3xVuWrjPMwhaXXd>nS5p$EY6_LsKXvZRyekI012R z?={Pcm+UG|TUITouB+U}nX=7teOmE9Au^4}7Icb@$Kc=JW+n%oINw;YoG62r6oi3= zi!@8eu^#VE@ujNhT;%kD@Xm^W4bhVu8}{`=OFOYi)yc()A1YcN=%1H2M02tqy>jAI zXbVTGQnhfbXCk1&`KF79bw?M`j{qdD#m*$UXWCMdBP7*PN>|lFuu(2H+D{u=k3KG{ zdoqI4#fV2G&xd66$uEV?+go$tB&)_hq*oE#Ua_apm5OKKZ~dCC&24@Ryi=9zq-!+D z`|lTaGWgx%JMl*)WF#cA4Rn@x5G4bH$E=v{jgPAK{amptIegxz{I?-cA<CN(`ik+c zS(TUa(<j#{eS@pCZAAw!Ro6J2*zFF(lcuW@2B*3@`MIW2X+@q`LRZr*tntd#ZC`Hw zTW!*+miAniRV|;9m{1{njr##@9z7qkztuPYo`)ZSiR3sh+@<b}x9Q~_zVp*kCyu#n z%yO;?KXW{Ah6R+f>f=XhP9#(qx2c7^_O|8jwjq1lyk9QMsc@*!9#+XVvp+{z^mbr> zoHtDS*vn-*)S>XLO&yz;x7J0<H{auoUR-Tx`nD~7=d7xK{oOqwCQS79oQ*XBHRoN< zcL&!5Z@RU8YD3jN{i%z_h`P!KhxL85T@BT}jK42!za64*h*8AJ2ZCOB(zRdG=CoCO z`naUBL4$ctU(uhfb>I8-Ey+-R>MLzwajf)q?OOQ~{9uS;Vw}Iygsy-vtcf(XP`AT7 zOR!oCk7t0=EH7%o3r_X8SEab6u7Q@$pQmlQqu+aJ)P{#|5bSpCNaBo84YcH(o_ryT z`27SGixlC+-u&~%tjv3L1mPRXV_OtWAfAx3*qpQ#fiaN`kY(8&m;<G|?iYIXvnWjh zvc}1||5W{=SF4e2O7GvCL8-=4aQ#fxUSO%bhkO7w&<MW^fQ+cNm)Mxjs7o(Uv@pMh zKTXpL0v9BT#1R{2AQcA$w;oIzeRnQ%6)pI{x3!r`SfL0`(*k{{J^d#)w?Q)^iLv+9 z=a(*{5fvN_NX^`}<w$P<mZx+xbUQ}~Hn7InOn3@%-9gGx$`#*PDqKpciYy`+!GW7n z*zWm9vYGZ!*-j}bK)DOB0843J6pYmpJ9RJLO5R}nOjAP^A~ZLVyTS~RreJ|Jm|J1< zNG?(Ca_n0Hh$^=SN#7YGjWwuTO{jm_wVn8uA%p}XM;8HaE`EVlTbwweI%)@6rR|X7 z06v9)@R3BIt)+w2OfHec{uXLH<hi0gkNQWlK?5|A6f`l6Uja8dO|CBh@vdBnynY&l zdP8I0L7M`RU#(m&NbvL(Q_`q#xU8_<g)riE^Qo-JT~K*wCAV5yUX8Bsi<aNjZ>XM_ zj=T&;QTFl_a=kHSi{vkJck4e@+_fD@%Nm=wE2dpXTdvGmv*SCFPDk{1G#TIMI_aCK zo;Y4xABP1C)Y#M7E~bZ>8x~l!OuCWW_i==A{%k+H_r*>$XpaR?J#pyx>;qH#eeOMn z=fu6582ETo;m{WeIOUO$wcNiGw|n-1MOW;!EKLC=A5qi(-b#7!`kR+rORh%THNLw2 z`S@*LYS&$0y6ar6yX4<C=i3gykyR>_mpY}$-B1QADeVjX^e9XKt4P?k`mUx$o;Rn- zoi@tGf1{Lh!;H<ptgBA{z;s{8__nt^TFoosKMj)8jXE_PO!am*MCIKk#Qor-KBfA< z<1_@|$WeRaQdfLbYL@S_(ph$)wKEpgs7_OW6us+1x{uZeZJU4VM>Y8>7k~V#kq5v1 z+z>o_Y6BJlFc8|OHW0_Pze(4ZudDE39<Qyu?ClUTyS2t>(Pkn<R|Y!DJ1SGvzK{Pj zWitPb6F-aS_gb=YtKp!9>65fyr@yFrc2M2X=`GaWgn>@>^h>uA+j)`aH;fXuH!b=j zx8UW~vJL8|N{nM;k<>k%Eo<BT-!Y5I*UVE@la3AW5m&AHXinFx;l1gz+mwH3D%CHC zGbCvdl7zk$@t}ZJ^DFLw2hZ*cy#Fu5Phu%D<)6M#u!HX`AM;IAr~lGuOEb8CgC7eV zdLZzC5_?cX)`aUH_JY!7%>24lTN%wS`e7DPHxdWCFmi5$h$fLjUOCd2i@<oLkdGeN zKcNi`i^KJfL&{|-)wt5%95O|o3sg=0h$*#lv6h^fS@ej$>(zAsS<Q!O1kU@O{7{g6 zN~O*9*6T1VcB4Zt+TyYS&Mt7+%F?=Li1(0&H(8G|(IH}00^&|%uCyHFuSJf0fk@9! zAXEa|GdN)AZffHhaq4ZnxklPn#&kFxG)x+94jkPzx_yKH(AuS@FzB~th{Z`w7UGG| z6PN+MEmLu!oNt#*Z(WizU`DGHK(y&7-+vQsPgi}k=BdhYPd&)nFC;0@VYHcP+M%@A zhkZt=v>-ZXsb+kSnDY}(VAQ=+<EG6#Hp$DWFJS0()S^&F!BU2B61RAoS-CY;2*pao zqodY}aK87dg(Dch8AFQJmiHB{pZfjpP^|>ESKtIk?^|yQA#ch-8}*~agCoqx7TJuH zKGiII;}bHZz^_LjdsA8HW+OPl!%l?E>`&}l)cUl+BIkl`(QqEO2ShEzp1;%Q#O=Oh zalgPXsJ7uOu4BzIUH&Zkg|_x(<$?Pz+BCoaNarkol}gQwtyvqJL(f+FdT$6*ynVhw zmS2{a-ytAHe_dM8W!1Z;@u8V+-m6<w9UDz&cKQ>>@-QpnvZp?)dZp_E1phq6%l>gj z#B&UNz1}m6b*5O}+pe8A!DHo~np{2xH}CYGqVj}mueuP=>(cvPWNm2rP<KaRXZk2( zdf*fWEP70@#kX0#@cvf|)Qa7*GYDw-O3`JsZ7X1~V7k?yesNB|x0+c@0qeS?r|9K& zuhpG1f%a+Ro-Q9%KY17Aka!ed=#QmMO|WeBe)-j|-yCM$%C770Pw&fBy}hHS^MK3k zr-;iCq@^uWS6_+j9_QdKL|E!lS6@0w<%c$wf6SEg6Blfo6{P9jOyDk2*yY`SGX8Sq z9M96e{llwIKxP#q^7`D4-sA59!t{p*lylTU*@6sCH<KS<4?|RO$#;2Pt==B3eeC-! z4%)tUxa1`mlYgVX>+iIq_bOfevQf_`l=a*JzK4PN&)T8E<HPem?_IKDPSg^^qXgB| zsTNyr{M6T$Ab@wIZ!Aw1&f>@h&oJ$yG*;cT2D84R$eJo+*8Xoz+Pb01ixgsk-hWS{ zqjeSN4w0nKC+}w4*z5b(1-ia3a*04I^lu~~ZQYx0OFQ_Vr>-ix4a;|0?4r(Cso_k6 zPe%T4?)*xx67^R_@sWC?jU+@IkuE0z<{v8%lg%ZR(;!pM)zd7;5D=zc;~&d+3bfk0 zx4uEFK{UJ3c}W>z)&C&IWN&TZ$EkdM$6?IJh0spW;&hQFf=wy0Jz&t_DJgzy5}j|! z7!$vkA5|uy-tlj-sSQwhC2q_fIg-@^C77$_6+Usm98&ljrEx*BDAxs|Z{U;=KNM5` z|1~cttj;?U`OejIaWoEFkbl1AC!AT$B_uWE&1HMUT?y!N*xJbcY0#t0vt+r&wnOYC zw@Kb5j>BLSRmyXtitqB#5_!>_LX9}EIzrd0q*a2-4<mwyn;S)23Y#Ca`l*2v558iY z5VE<OmOTkBJpe?s4(Wdgwe;@N_K)e`k=`lG_H6w}a$we>&rI#!e<X0(TiXiz-e})V z8fTod>~e-`qs-3)7A>i;b4^C=!ghzcTXRYaCT{B9jz(1{0FH;P+2OON+o;gFiDOQO zB~r)U-u!kk6s~I-6|yp+Xzugb*2W6Nw9468YyNnA$o0xqO?T{={v;)LX`=qJyNj*; z{SVGZc;D>PY<x0ml@%Jy+8fR??ZXu_4miBou;$$}hMF8hop?11AT#Upg5S@Et`T-@ zGy7Mw5WFlS_GCZzF@Tm^1T^ZQQz!XA<=UeBpWa`bEeV;b9#R-&)m+C2G)S(!0F?ao zJg51U1uwr!$0EW`3t-*HYuKK=Plx{S?aQuzBxST8VEGS>x7Lh+_N8b&(EX!QdaotD zyH0QH?+)Bxh?}`^+o7Qyx1zcY>WP~Qq-}+3%&WDpYro!5B~E<KVE#TlxoueZY`@o4 zR`;4~#1wm2-)Wb+rlkMW#=R@Qy4)&mfxZgX(Fei06+f&PmsDlxE~FC!4E5IGdsv+d z$By|Xx!*I|FOAc6@CXG&Tlf`~g&(pY6aP<pOt+W0F;Yc9MzNC?bttvzuuaiIBtf*v zO6<Nhty=h2JzOk)w{%&9F0`4M534f6I^2H5i6V91UY3*2e&oo3+>)U}w7$S`w5937 znZ=0*zXRQh5(BjU(B^MnNzyA>@uN&_lXdAXVbskYL9MQZixanuDb|7d5cBMa%A4b8 z5Pn-~KFJH-mn_MJlO6hdy|p##0kb=j(*WvTs4oI$mOw$hNL70im<VW=hi=dq9A8Zm zzSd!bT|AIuy<HXzgIrA3P!M9b|5zW@tO5J<@~^NjM{AhG6Cj)x1WtcrJlh2%%aNmM z>grFpbbUuzN;jENAR?miyg_5uxN!s&PE)r5ixHyB`sweEupH32Z`}VT44Cx7#i`$j zUcEW+l*9G#d7;`9^@PYlaG^Tsx0&mi+V6$=yzsa64)My?Ws<vUt`E$_lxUvMR7tm@ zA$8LFncBY7>7}2Darv1w=?pO!5|21a<+<yv;ur4JmqboI(dvEm(8kNT(Lvk30!|~J zv<?Jq-U0ED1pDNM%M+Tr)Y;>Pys&uG`8+tK>*(<3@<kK3eO1*56>-bJlv2?>`eH@@ z7|%0j6UwMc*)f^f*MF+hU5t2a`rPb^_YY@FVP<T;2LNJnE_Y(ym!mr)Zh}ACD2Qbo z0;>MhQ+Ei@xYNZHhRC}*9{cSZr>Kt$T}a!x%gQ*i!KXa5Ql?#}dtch=j~;YqWA)UQ z!}84Mk8ULjVUdJT)I}d`?$#mnll6giX1`!R-k)2O@#201Cs4yg|K$Y_XWH+j?qlZ; z0DA9yRe4nS3b93E1HYcf%VvsxY&&|u&zGvC{W*6h>XvUF^t~)}0iZyX*TcUME!r8z zyM<4eGe2s)LqwII2Wk~Kaho5cmHONt6%z@P%B8CI@{B4=pS7QH%6NvZcUsnxA)yZ| zpskCcf+wl5L)pprbE3XUUW67N8D1dSE{8ZxO|x4dw{sa!-5_@qRSv67OTUS_1kW)f zU5xmf_T(Phc?K7QKiq}#Q?Rn9kj}_A47HHBMBbRDjXTgGb-t!hf&Qz+2q}_O<hm#w zY1WF0??>?C=)4aU1#Hi5Uos+b3ekA&pm?P9ok2=Xt<2#L^b*qW7m@>gOsh4029952 z=IsbuDwmx$1WwNeME5BoZQw%IM1oHvA)E+56G~XO53{MrTYHs6aby>$?daF`&q@Q1 z5l&?s2aE*}o2S0xuPlb|qQOkN8ppB0!v|WTxVjX6prPLuOk*4@D=7OHLKU8J9CUnT zful*xJ3adjnwva0TSw<3{?_(}1o2g-HP9Dj#=q*O27wZ&b5Kj`4c3E@xzqGf=L0Yb zDB=2tfLKFUxR4RNpq=@LuxAI{>~6Sl$spuI1*KgCK=Z+-Gi#Du!k2W&HWeCAeft2^ zUnR^Hwe3C=Gm@GM>6Zg#G^Ep*!{ISxUb3(?;@Ve>uDo}e8KO4cm|ddF+~95AaeNU5 z+2jKlt{F!fvMD_%Q{_jJQ*+zWj?0bOdo?<j%L$E(&ZF@cyqL&SoBD>MlH4IRz1;ep ztFFO9z6U1*AD&jQhJY214;C*AVr}u_pWXaW2n!hV85fxr{Usqgz%Nmd#qYcL#1SKO zf)i6!B%wf005?aNfXm;W7&I(RsorL7jZS99(|4}AK_L{`dVr!QH}OQ_ln%sx$W~T5 zx^KT3Lk^Oe3U+Mx4m;|tY4kV+POqn7kuq-KkaHR!{Ce0n8MULn)46Jg+PUcL55JPG z9Xfq1T7&+3YEsjAY6I_%7GAW{vDvDv+}EmGmYO(iY|jAvXK5#THoydV7HMuJnm--g zzd}P#X+C=CI8$ui6Fyir<;8GoVaI&?CeFA?E;7`dsu+S$9rTT*#Zx6{Ill^#0Jlv* zn@+IFkMN-OBKo^Pn7Jgg3cq;gu{x?Vph(+OH2A7N<5_`W8aIYzqKn;ULhg`D<wi?a zEbn^r?~`!d#u3QrLu@}4H-y^`@C)i<(kVtPf}-h~&!&v}Y!1J3z%#rd`uEFpN@Njr z!e(OX_w2pfrOH;#!~l2ONj`BOXfD}XpLD{g%6i);iW}TqEPJL{MA6!naQ}F?4Tm7| z);bJ8kAWxln1d`q%50zaqa%apK#A7pl(yTRBLIGX9Dz%dv6<80&dEErFOD6l3k#l% zwl3*p&&)?>pKF317gpy~pfDgt1FKj}>K@9Kdrh@>EkK-J04#|_@@L%<ck*A`aANDh z55tV651qh`U2j@_!%zovLohj3)>gzA3v+8G#Qkpm4lzV#CPWz<e$lNwy5TfMM~J?q zo2Xk=qzSp^@0ld9I<vy<L&ldWji-(Gf+JS_N5$mEkJ_T)khei}tnU0$ynlkGGFZ3# zoGq)F5L)y{7{Zqxsuck8jM@^_)I~34eOoAl1b<zCW-zbm&|kn1y0+ro6VWFb?Tjrz zdI~jVeHXJSZ67Ud#$~jF5n=9YKSDeXZBD_){Qy5eogl+v7x_q5bo5EVfWr6U3^!yM z3`%}?L@J=9)`NptJqcPvSt6(#c@d%4Oi*U;yGW4F7UsRqd{-rNBcv>A^u=h!#vm;5 z|LLe+$Y3!gkg#Jf9KnvqnXw@vP!F}gSuk>BgsX2I$=^ef<q?C~MeK-1LRC*uHl!PJ zsSG}2FqM&ACJjwat~yM=vlPfkCwSt|P=%z(nC?(+>=9Y_ly*W~d%t)8<}^7eci7h- z>l*=-E8ppHi6cjml5Bis!PHD8C%M-!o~$igAld;#xF;L{i-jpIE|4gWaNT%xW@82= ztb3_rZI(pdB2DiEY4f_WMw}<EY91o*Sni_OlHXWAjmo3W^~)or)B%JTiBhUZ#|oX# zP0x~GCOr%u%^aYo4#;Cau`w+YmOT$p*i*hN+dF9wo<Y{Hchv}}G9jS-rn{g69WidB z7lypSGV8(Ce8-WoQ8(DBAR!uExXC}Hh&_TzUj&LmQ8gl5k6t={95|$~SiJbE!}m1K zVmxbwmcJSG2<@8wTH^6xrYa@2d-yCbJLk@u^CGYWf{hfuS4L`U5mA%DWEU(X6}qn| zXJknuD5-VMW$GEmRfP+v;+kGH87j?7TgF3oY@S4ITr>$fVhNriKd3Af{a#~>hHdKo zUj-MQ5IvSnTRD~_m^>L(xqXT-L=+^e1i~`}?c$|Ne%H&imePWSgEmD{S#nnD4dit~ zPz>hWGN8xc7|=u1FHRvFcXVg|EL`mdeTx1)2;5i~(Tjs>MTfe|agQhq1R@~KUo#Q@ zA~4ON(?@G+vBXK?rYVA)obU@{fq!@thfZJw$x+1_FPB-rbHy5k14I2Nor<>1B`+yt z%YivkCCgv8b4=Hi$g=WsVdqV2N|z#(P)1H6g{Igu>&u02X->BY_%PZGZjt?>L7U*E zS`3OK)N7~-Ke`!vfqiO6j9}knMz8|zyJT~6x7%bQf<*7xp_W}5VV81pUAr|WiNLrF zS~$sT64*|8iCtXR6rTUe<^Dfdj->=@shrWO`NSe=AItPV!>b2&`<znbmB-FEEBvTu z<l7m(nDZr?uslM&Y>TYX^%uf^2VM-=vfdm7@)l-^<c;YIiN`Aj|Dj}5#8LH|eur7f zV$z$^Zye6{M}@xk#U-<o#=<)(28FhFFW7w1UMLOh=-XDCb`s8|e6tvn+N#fc>mn<I z{l$3d?UiRj{@r!*_*Val8{y6Bx8GOXQZYiiwCsi1<aSx47%?=Z_-m_>6j~|9viLd$ zt(n<c^>R;Hi1O9cwBypdwsk1V%6cQLy2CGCtGIsqllJGpK1l?VmbbrI=uag>JS1-{ z8Q|s+`ou8X?>YksExM3t%8k7d9r}*)V%@Qy7r6Ir+jXO50S#(yg;==+S{jt6W{p0G zMCCDmC&5;dqmWno%uqjA)tr(`6G0_Q@D_6jg3tYd9MuxYa5Pyb1b|54!VCCjN{+<U zQVK-<E1Ro7sx}UzOK?HAbKF5d@_{B=MDyp}h(g^Fi~?^J@{feZCMG+$fc4aAXmc^l z2b(kkfj(B?HhBq^p2$LA{aFA!VwOUOBmW_QhQ>cff7G!;60w5=($X0aE%`VPAz@R2 z>wq#le*=`j)x<xPowJX<gZv?}8VI5jP5b^?yfm6D60me+Uk3{fR5L70;w<WA1{W^m zi@|ePSiQMm<V<wIn>hl!2LeBJx>8waC1y55VA7+ABG4epi8`WEU%st9Jz2^k6v!wk z6R1OFhG5D$1b|tmSurFFMA+plb6^?=>jj#`oDfuB#EpOhA|yrCw!3M{RGK_cgfVYb zVPw>olQxi_E@g!q1pQ<r@*QM3gh@k*kX)7>=_I5588Ks8Oc67fc}k|#CwR^5%HV@a zfIH-O{-Lbxi|(pPQg?h7_Cs(WiCGE5B#+SMWL?<Te1pu{D5V5i^_;7>w$jmh!s_+K z5pD;_Ea(Wf!lSsq7BYlIqAeJyD+}1VrLsWz?-nBJbo`J>;BS!~HD{)|L*ycGn*ybR ziuDe2*jqU|$XDa2CvEIUe>=KVMS6x(tMLTTy~cWxnoZ_6vB$LLL#b!ZAt>_@&n|Pt z4!b?|=DU~$MgIaI1zT9-J<_^I8E8@`!2y$rtaM5={1-D>K$mEIpj$C9I_I@3`C$V( zFJ?C<)4kU$94lEih3y3t4KzLFG#A}Y4>%Ha8cKsAITcjC<6iJv=wq=)Vgo1jK>lnV zjT%>jfoGx!|8`ibYdLJIh~hL_@`)!h`ijE9=vq&fcZ<Rf11ai~=eI_?wJasW9k$7r z!&TAMkTcc+TbrFyrcX2!SPua(SIJ%vMrw}<6X#7vL#*D>6IPAEl5Z6o7M3K040sC} zeXB^G?<z+#`tlj_qVUwj;ThWSloWxIu}D%)*)T<xcyM$XUoU*$v7v=Bveu3ma}_rL z44jR<Bt!?l&3^re6-x>VEoXMs^LN@fmp_KZE2()x>xq0KVxM@074f;gw%q#U9MeY_ zs6frp^aWa)x#iFlvucsn9jQ4s*ky;^z7>OBP_EoXZB6tTLN=Ak0!n7yNcwGl4MK;a zfxwy_>p21dj6Dh)Oc>pE(h|T8aQQaY*-{g3EdhLnfJBRfD8nXmNYlAib>FspAyxWK zo3Z(VdT60>zmPbYxTF01$y@^!GvVyZ>g=!4g?YaE@<VC)y7n3!g2X=Z1RvvnvqzpZ zyhK%X6?xBG-uBRz&N9`o?>^ZD?rC%4gPyv_Ed_^0U1K^Q1t^U+@<j_e0{%``@%jDx z`p%!cV|4~3G`4o2<<<o@SB*s3_RrN<bjqP@8$X1k06#yXF?4gSb%t~jtvwdUsue&e z0=-${?o{UX$8_v`CbJhHE|SE!!da`y7z`s;7gv{}OG)7P^#-813-gN1!!`r(KEcca z4C!YVtFF8qEIT~lA*w>Us20U_igs2?hHMwg&CEtcKP;40Zo}o>{#g;6&rOzy{<0Zl z(TCtgn^OQw5xOSLZM;eli<r^>zc7dcNg<_HxT0@2EbL~HbJYG4z<+@q5~<5TXmdvK zU38hCcU0mG3UcAE6j3cQJtiGL)}654Sr0^AZzv;UgE0-SQp@04Fi{4Z&OkcI_~BvB z4UxDV0R=>{eUrzGsbKtaqNH2Gj+s38!8H6bfzf1}t0o?-mu#c&;Fh!3aj=_!VA;iM zXrIhVL>iqX147#$(LX@p0#C*P;WWo0EcqYFGO{gcr`~cXqCMXIIU>6sX1tZ8Y?mb) zfBq7+I0FLl!cYY`J`*V7Y=D^SiM-Wj<jAiafbR-0K8YcxRA_|l&fyNV0!tFC9B?=E ztmm=vQD{IasL@L78T|L11_{GE<WwixPV!Qs<HK=?mU6HqMc#C4YgvZkhlm-)$v3)r z8^%$@-T0>=AZE#XziiCczb#%*%sDj3|LSI*m7O>aehuXQAED|0aOuCbK~G(|E7n!O z?ZGJ!1aA=!ZmyEH3X7-|o&ACOcdj1fa6d$g5IdKW^FjpIP;WMUp-2jwY&;~{YEjAN zrE+dH+DojXjQynxC1aJ7iip%>U%OJT;{aStxx*-I+Vrs^KwG1IIkPiBwa96ZO88zR zo+JU_qKz$eEC@|ET|`(tA=<q3LMwpsh$`M3CtWyp>3HORT<E=yob-aa>pcPsX{XDW z8|_mXKuFT!5a^<jBjveM-s74i9?(bvl*)Lg_eO^JqcV*g6j8_NLm0E9<DJn(lJ$z> zWaNhFSjE?3muD%NZWXsk9S-3P%TbaagsCwMV9lngG@MO_hF*)r{|nI@%9#d~l>*OI zIn)jpUZ^F;Q?WbG0hdHnRNp^KWZN(pJZYNpj!(hXc#IrrGsAA5M4TRsr$ptg+d0}L zJO#Y;CKiokE$=Uy#I?8G4}KTT0tbBn<*?z9^g`0(PtZNt_c`#P9&5l4n$HIF{gEP9 zgr}Sk9q##Wtdt}d>rkAWY@<jZsg1TAa?TAo0{XOLGnazWre)yMRw^2_nuX3L{vj`r zqf&%tj-Y07y`{OOb3HK%|6|$@(m1OY`B{OeIx$*lxy3j#s(+kzW~V+cYuttGK{U)V z4J@hoHXk^&-6gx4R?V8VLaDOK9iXcx-CoK#0qF72W@f#1XAb)vhLTHjM~SU^$Yn<Q zh=nlXIH)LTuAg(V*67nBW9}n%h!GIuF=W~=gr6o38d%;-6nB>Q&*==hFTjl5b&l@s zqQQuT156za=}UvaUSO0Y#EgQSzLnCjVnX5?Y$WO)sWH@7!P3kFkUr4-o^Mmo>L!dh z$%)8X7;(k=t8haRsunUalSZ7H?g449vK1UiErw#2l9j?yyhPajQrX-twB(g2H3W!^ zHWm+zoge~B*r_+{@f%@*^RU!Uzl@+JjUL3=#0Z|f7Cm1fisf7h=*k*y-L!{dzLpkn z5`x@^Jo7|AG7mOUMhh}LEt>3s!5!l+t9Vzx)D*oaX~d*XY#74E4VQIdI0`AJtqe?P z%o@=5y%e-w67k-hrKGv(1Bj%oXmma3Bw4sf=`o4`yF{i-HgNb!bc%$C4n7i*;RuEZ zj%Le$>MN9qCVQcSmO&szi0C3nR2--?h21iJ*1r6{-I_uHMrgol+Kq2=jF;?76~M-o zj#MQ&JpzGAq|adVY6~=6**_Bhy>j7wfnGv|J#lBn7lR0<R&A($z)xi{^tFe_I}XzW z9>A6&nUw@Q82CF6rLKQ-3gnhI90-p=P+;qg6T)W!?{sy3F~)x`NB#3u3S~p1%Hlwy z1K_to-+<YWc2<s7xr)1GjSA;_`UE!od6PhMFRq^^`rxbJ*hgNR<Sk67%%~J_+ao!5 z^ItldZyEDe>7_j^B|4>lzemmxo0K8WCr5YcJAwZzMzM!K#64#>KL(2+N{wNkM)$w? zGKtS&WLRQ97$zxsBjaG9Tf*O3kcW!J7646U{Nlt9v_n;k2_yC94CyqSClvamkgx!q z7D%g->=RT|qF=WYB}VkXbw~tiqd3Wa*eCE1>}?bs0YmpT#0Zl#%R!&^HgGJah+}5# zG!ZL}C(5l8O^o*L4cMVN*%Kb)iKVYy)u}W<vcQYyjwDOWuPj9hoslH>Ta6qjJPwg5 zkL`~h3)2H_L~;ezoaJ-}^+V)_1<b-@hs3JYm3tTJW%4(TDf{(crEj<ZM9GTXN8{Yl z6Nx2uB07h{^iY)CSeMa@g8|81SkxD|^7Uv<EpHHhH4=*xSFPR_&_=+}AJEMmIIBWA z)4)~b96kRb<wkW%l8fyi%Neb10o}5cC1LiT_W;t6qS2Cg9=)3?4FP7D7}zbQBp4`g zXh(cI^eyY;9Yc4O_KoFm;2axd)v6&4ibBv%wQ$vY!^Nn=VL)yFcDa!-j5mp9kyV_k zw(Oi>tK4_7;R+ynl5h6C&?PgnDsG37p<9My@%TY)Wu*u><=PIhP6=wa4roWcH|Bnq zv@>=l3N!>jXb@YBB=!-j^O<_(WyIwU`_v@VGqRg{_`+8!lu?)Ipc{=!&mEbe>%>nD z$SFQ+NsKVQUN6kEjLnc)oGwO8i|AwyfQ22+&c=rkwFP)OP*7$CvfS=0e=hBeE2B3| zkhyMHs`~98N%j#IX+Fz~_`rBTVBlWahf*dlpN@SFp9A<$x%?AZl`{UR+ZS{_&;}YY z*-&$YJA+MYr$0xfHqP;Ncng`}nWRLQ=QI+Ilr!U7{+r68U2z|2h+szLohX*9WT@x% zEjHhzi>kM}Hx-C{gu{%2nQ|5dT8VpmU$>ke=QGx0zZ~hjrSJV1^&fk&nM4ik5<&gg zRmqlVtRD<J-hUZYii4Kj2~MuwIP%!H6NNR8@N{o<Hqtxou}k6M-7a_7b_R4FGD>r6 zkS)q}i6z$^X!?`h4H4dNf>=^j#C9eB6y0tYi4gCCCFCm>3r|&~pQ(;7Bz{MDzgxUI zW2_4J(g{l$z0>%1Tuj<i5|c_uXR<g9&h-()>(Xxyd2eZqRjb=KR^7UtQX&20-QB>2 z)X*RjEFC!dqqx~q1~SqyLa;~F*2@YYS3tFZKh};412${mmLCe$hIUScrPRvR88w{L zCAMK-f7DQW3&<r4RNrEwsHD}Q+j)-E(d;q}2LAg5xn_3*!e%-b`pQcu>tgj!-Tbwg zW5-Q*NZ!@|d65T9g4+=Z$;b@&k`(Q!(Zw=Vu03QjtWa~2gMGX8U_j(c`Iu06Anl5l z%AuIJ{Xdq@1T4yW?f>Y}(CkEN*{P5*8N(F{EtN(_Pj<$^JR|NJL?ymNn}HgP!aSvw znaRWe5_+65L2)Nhb9Zvdalo7uH&jGr6I51NhM9T%e}2>dy3X~U^CHYV&u_Vx@BO{M zH+!mRzKCPtT@U+kPwvsah(TKZDdc3H*82}<A()LFDoO;sZR3f27i;^6$P+hqE1hVF z?gLKL8Ar0=z3uqF%>hyPPWBjtEGg})gM(P!!+n;2r=6I|@BmX};quQFb=1+DEr5yU z1)&f$rVNp;Fe{TxI?%|lGOs!75u1+cdH{i9^S%D31i=$$!kl4?ZF2S0sbYA^Ceo8f z7m;{^&t?;uq^dIC7SIVUUDoZ|3h#K-@JVfv6DFE8k;nSzl<6GEcf5n8d{U^79nBSP z3!mkF78Lo{85UJK?l`i987t%cI2+4(4B&K!yly(h6O7+<b<%Nid8Vzd?`@l=sk-oX zcRwg{zB#%IdFk|zcaLZIaUe9a{@+d08=^-jEr~zFRwdT$ESjfP=F{TcP!{@wE;O&J z?$)%6EXusXPnB8yp;`y$M4U(vR5ey{-q3&F)ka>j48pp9vFQhbi_3E+aE0rC7<_2H z;G`6XNjdLq%6UTpZ#+e)Pkgxi`&!QC^sb{ekvyx@mVf^23@$&|bO|9-<X`=sR29W0 zl(-KsUjfodZj~sq@xUEjDdAJkrw4B*LEQ+Vi@!%g^&jy(79aT-_(wcH!zaZbEt%b= z^?GvOb7@!VC*A*k_x;}$b#d@2hmL=^E5!i^mjj)3{S$??aZNsBiUr$wEui_qjzBmo zb6NSQ`@dd}ZFcvEe9Sh8Xzee3RI`DLu;#MW&t6lWLc+Nfsx3hAzDHv!%$=zworpCM z*D^2ndxPu9AcK6u4_<_tG!~5DW5)~h`7L-!NMF#;x6Oyf)^I9@RhQ&wsFN1==M1^< zo<>KQ`caryB5}tyC4f>3k#~-0`ki5-vMfM!J2ln6x*t*}ZLx_MmGzrRJm?LyE_uN% zfP2mOJ_J#Qd$>)x5QMzXSO07kvCLwj?%tD(4B|t+ZK}61T5CPGf~ZTvmR`|_%2?F~ zMay}1WIC%cj(7z%1>^zLdaU#g6S*3RxKsgL;gp2px!erIOBR|*`SA#{@?^IBu%7Y0 zx`vV<s{LZ#@lfCg*p1!#%CdT74HSMJF5jeMJ{DDk@vV&hp3naXAngar<1Hhpi358x zxnrwUUp)g*>?}Jmh^SgmqwG=oWb$y~Q@eUQlIJpkJwa6Ui|EBVg!L#p`$(i}Z1tAK zcE*h4VM_IpT$*Y4OZg9<fSBxwB>t<ETl-L>q4JIIS*+1c82u9FU<ZdS;5{rrmPqHk zBc3ZVpA8>_59vddmJ!gR^0v3RR-II-3Hq6?Rv=NA<2AKIF4@TRTH(uv#1qN^H9fTz zaDNWECJVZJ5SV6!o+)JbX@#r7hzKjigmU%64PD-MRxS<vMNuq<l`rnWEQft?wt1gk zFThHOT`W<2Ffn?z#|v7ktiK@cKp28~`}<<}zP`406XxOHk>jHlgpVDPet|@e9*6Vk zwBPYwZ+A%)HB?8Kphrvtt+<%Gad;o_UEY$-79Q-`m+oy59+ON6dhex-4^-CBZ#MnV z^~7FzZb@INtu&{D_;o!^jg;WJmNRxSA}9^&-}pJAzBFB&o2tK__d|1fcNldPinTzF zeCv$}m0&i^uDURO4pd#D>fKAaWetRy{!8uKp<#wjA7DTe=p3XzG(Ci!vqBp33nhN# zT8aX*25Ic>wuamVp+7tsL<?74n9^*#y|D}Zc#ihWN59<bf@JYakVLX(4@iR!5<Nkz zj&`UfQ8d#}=6Nf&ADp8qnkQ0OL;WOix_f(ye)^T6mIUS-U>NLv{)I^1{KLGwjD|~@ z3LzgrhXh<ENblSuW)A<&VNqn$D!?>!ka^<BxXI&tih&pCV~VXh#=qorVR-#$uAD&A zQO5YP|91=XZSU}(UtnUuBI4qf1mIO{Z()+Vs~`J}r_RspfoZ=Y#{72Ach>uM7Nv?( zu`&~lo@b^0Ff8*p#F@LhiX5E07`crua^Ys^45h*weLd(|Vg^<?;`b5Hnu(SQxJ9o% zNni}Hamh!cBTE{RiNp{;PLiIkEPYC};MC+q1<7AWx1&iii8alhHpZ3z*%P4aHbno4 z4o}TAC%gN{`)4?zsvLTA4*RPYO(yqWH{MDPLlap(tSwxzNYowViFggfeJj%5+y-<* zY+ml(YuY<s54$2ssc5|zQQBC^^jaG+%lYMg!+05#KY$-|h^%#KD+Uto03*<X8Numb zU;%xih%vLOC`6Npc~x6XU-dvIYXJr{&cO)i1)AgESBPY_izs;!JI8D4Z_#Y+1u%Oh z!lCr+-J~6T;RzzQ`x|_io@IyW;S>jv<wWA$t~yK$DfMa>k+*#!t%Q*^(DVV8x8DXQ z6bFd@whY0b5h3GsKw=A=^q%UZK@?7?^NPUDD3?-gN&8B<G~k=u;<N~AEnHu^<8#y0 zgk&XQq8LSwz+j(dvKVJ3n30y9S}WDn`H_V9QEzhAMq)fivKC-`92;_C@+Kt&IND<d zz%Q8E%@C9QZ!&zUx9CALbOT6#M;ESzR+CdGZp``Ij=J%HtJD=TiP+c8kd8{B5kAV6 zA#C)Pi*yWn7H{k>Y^byYBls{shuezo#>}NYYsZR%GgU(doo^q+V%US#9c8FbE)r{d zR`%f3?scV^7^cW#p>4qvYB~>c7^Zfqa;{fd#T^BlSDb^_js}=Kl*%&yI$bH^-Hdu^ zN3O>Rok;}IJw#PCjFNh$Nnl;1_V-$beANFN5;$XPR!j$#Qjw*@^w7}wf}F}=N;;t& z{n@B-)UOgti=KD-h3kSfgwoaoR6d|ck{#qO^?hG{vQL^+vpMvuU!6*kZ2yOSAMz39 z=cTCKE(p(+pQOGdwO;&Y)1+Gwv4$wlU;C2Ty^O-_Cq{D5uHs$4UD3YSKEwqFDtr7K zR?qe}U_;d4rMy3uRZSu5KSi<We?718cJ#r)nfc*&R6Z31SV(J*U%>I*xsA@hYQWq6 z+IRB*nzEv!))c8T7Gr-Fs8js}s`wL6m^KDjBH!IYrvgrf#9{ezFM_Ie#rOAv2Ku4; z_BP3pBkuo>jT_}BA)dX3SK8Qv90!75U~W5%DcBZNCfGXa2ipEVp;D_!58W*>&jjk+ zJTvMEK`42+IC4;E-g-aqxLk3$+S$SJbLOeYdD#zV+=RDoZDfhxvLb%e#XoDrbI<t@ zOLNAtvS5FRzMe-y)ucQ0j>vNcJ@-7M9YDJ0Upc*43uiCq?U%c23GJt=(>4?<B0Y8> zrC}H3*ez42!BJomQR$KDAG-ejNKl;w!sE1bcwV9uo_SUjp7acqpK_{W@YYI`>F20D ze}A)pY(le&kjl&4|2)t2yOQR|z-y#myw8SbIs2Nw2OT9&`_(sRvM`dO+w1o^I81aJ z`cLv>)Y3U50|n6Ey#06WATHrQD_i>2Yl)Zf=xImWj`h0psb$1XmN9R!WBhV-UJcDU zXS_1OR=p4dWr$w#;%VBb8Xea;<Ybdsj`-sontC<XDlXcOqNsaVe6>NIRFP3^0w})O zoFn4hro)%9bxol_p|lvrW~HOt`P<R4{-zi$QKfJ^UH1?farU6~+}}W44Yt>wHTzX% z+Ty&HA(kV6TD;`uS4Y^U>i*`Z69{;-yCz2Q{odEJK-ZskkA>Taf{$*>Mm&*i{f|_F zXrWI^f&jTFpl-z~3(RjeX+}l9olfvBA~d`*9pnx|7zCj~LF9l!scM9B>#aQEEpLei z8I5AD7^aQNUh9Wn`Epp`#uVn6)D}^Hx_o(#C^)Q(1dbOjY2hz~++Rt83sQa<nm8mk z0x!89QVDJvsM8FyN{9^5;Sz6cN3P?L0P}*;*Meh4^c7}I<+wR%3?i9IC1T{P`Ha4l zDD8L-*#;!5-X7o2pg+2g@76OqmV%KeiYwO>HSxO?5Ge!rHP;#=XY8?!e<}tdBnokP zTQJx^-Rqjna_8qv)q$!>;IVP<EX3yawoRuahvs}{<Jtwx#sfR0&ftwwXub)OnNM6} ziAdeajY<g$fg3W(&Rgk9S^jw+IB}w5bNTlbP@Pv*P~ca$CU}a3K1nK}z##g?TEqnv zRr0x$LGf323`KuwRUk|l!9OCi%6rq-F_~H|?qLm;z-O7zMVQO2p*QErp}OGQ^6_)H zUm8(TK3j*GXdcv^QA0v8ui>4IzMEefoTj7c3AusA<NCTqI^c@?4>8o)T66TXq6=x0 z<?Zg>&{SCS$kCcPb;@ZuEWK9nmAiN6j!^PAOf=`C1x@qHhm90P;=W&)BDjGY|6Kyc zLYHt7do05aoVfT|P&6kRpZoafdXok%D6H69x{bl%D{0<Bsq>cxAi+3!C9z@8Ur|fS zK9_$ibnM{4DHhRumh@K1kOt8skw82cY`i7pOTOV)P8j{95Ja4&ogn5mq!}4Wz=%_f zC-tM2EmKa0DP&&;0yeJ-%>QDKlG!9P5>uJAG`ggh>7vLwwe&pHZ`>3n(9$Gfn4n@( zf{lD<qv?BoqJacHb;|OwgEvJCE$TVMI8CYy6Z2-a7#0lcn;=v$KZ9^ad5CQaDc&-@ zSNe=?|0z<YeSH%{FB-!ZyfpX)B0bSUIeTud`}L~~0CTqPn5-K)Wj|aFz0zfl9`?1} zuE>6oe#sI6fD7KI;Bq3O0U#_c){w7pP(yiCCy}_N>Y{U$5P}fh8pd1GZ}~C%A$9Gf z+NdX&%%{k<Ls7cdX##JrW|7;Me6D`_<M(26+NcVH+}Phf>DYsvTe4ZP^7SFyJY%nI z>ihreGrgj5_b!z=YUyWJ`O-xC|9{S0G+^(8So@&R-=sUwUAF2KZJ%8g5coG)AF8|D zFO<%`Aqkf~d(iW}!q5Cu+kf%26!leW&B+MKJ?z+0b%^6vlOL7W9M`c&i!_I#c2?K2 zQcGTQzkWpoO$TwR7E6Df;$+!-_zw8nrqwHljeSz9P6FlJeOLX>b*p=Cvy$MUHOM`5 z+$Y7JitD5RW8FnRRmJ)CUz&9Cqsr#bMJ!4GXUld=V}8SJllsv?QLa|q-`l8O5&PHe zBWX!#RB%WvZxwZYEpzEhKOvrQLt+d@)u$cn)E%4O_t?D5yWs@q*B;JKqsS)`jWB7o zHQ~-Rq~8b$2fu!Zg{lLvA`!<6G0pKm>XEa|l=hTMz7^yBLJ!AuInnlTR<c?zdU?Zo zs%G(zI++?n4ZwNM%tZqk4qQewOa=&QG-%MIe$wR&FrM)XGZO67K(*e?K!~sH*e=JB z>t~<>TZ(i+AmLBZ9tL?NT!J)zud6K^O)*oXGI4_IP#_1<G*dsC&So7M-Br4HRE`lW zvxp%CdReu>hn8o)hao30;og`bIDbfi2%$cQHyKz9*LG{yk7)xyo<~%bxofo>fU+<L z!KC&{RTqNXEf5qaTdWE!AKxpID9N;$IbMAEtRd^IwVTz%iG~=DTU3w%{)szB43?iv z8&jvDUwI8R!R$!epkZL<#*VFBIWwELH;HO2@+U%~4XiFn!?YEVRK77)aD}uiJBlwf zJd<Xk3u+Qqv;WNB5$??3z-^(h3_b=oRJCg8csQSf`Oaxxb%tX;BRk@oyqDjz50Y^i zJTf789Q=c2fd)i0Rx*g&!*ykF5e)<|S8-n5ECvymumr}vM6UlaRzaLtugrHUM6HWa zXf&&Cptz#<`#0i3f@D`4|JY{%`e+xB-yDy}^0Looa|wkwtzrSeP%Sf%e#jI7SzX=f zFAKpHavu~Tvy2;^t!bROYIrOGQR4K<J$%Yv{e}v;M(8kwI88ZBS7;wUC)Nb>rOs9w z%T$WY)bF$e<%!zyMXgL*tIwBhN2p~C6pnWH66K4aUdn_#lh(KMv|QyggLezuRnYOD zB_Ynn!!Aq9$%r)FQ+4rVWDjoCiX-!-Y25SCr>4I$hV<aN<;2oUy=}^MQyz(Vo|XGD zYBu@#egcA<omWl@utB-`&w$$>qE!E`wQ=Rgw=|aiYXo>)GNw*m-)KF3I5ScE#OhQ? z_Dm@_G3d?RcedF}E*_p69?-GU(X8IH@aS0%)VDh33tLa`#hVUzw*Z1fPSu6v_Moi) zSvrdre3{@@Hchm&^t8w_^ofoc;gE7OT>WUSYE7KE=;h|UKW++pSka-q8xySSSPP38 zDp|y_`Hkv7KtF=6F`tut%7CLqykpJszfk{XxNSpZ^d*aL%H(Q|;+h(Hrn7Z6HwWce zn67P;h#BY`C#A_<Hx7FUfK-@WT<|t}>OprEWxU6Wl0z51%hvcjk6f+k29P8Ifb8RG zvA)^1cM8Z$zWvADe^q+iYhOD-P}L$=&9Ss4U45VDXtNR?T^2z1nhSphR8(cpx8Fm^ zrfun!JWH`FI!|IU6?j>r<M07eL&cXz$S`<h-7uBuhqgDR((>t+c2mrWZi<$YVpINp zkGVe3=n0kyIv)E3>~Ur;8tBwLOLN5i>$|OSwIe>yH@YGO%{qjxRk?KDm)5;;kW)La z)+0O`CnCdqc{Q(j&N=t?d(qmetA`z~@ayyB23G`{sh%jZ`~=sydGu#`c40z_b!8W; z2RAMZHnuK#G*Q|suZOAE_CHaQRxy_7p0RD&#axT5t`WqBs-ugYxi^nbui=o+ol=l% zz4PyTQyD|9M9+x0w8@z{&)v7N-6H%Lb`9;u%tI?Oo#j;R^@*Pr<SIKx+@YpT*W6Lj zmxB!c&}8|Uj*qWgksb*GLhB-jN>r@NY?@aSEn`wG?E!JzZajZ(>7djgj?~IiR|++4 ztBJed6j7lb7q4l|IN7XGyC+LY-TDAUQUQnESfv}2Xc+<i7oj>d`s$@fcWC3Wor+lb zPYB*ek!o~5_Q@F*VY?%JxBEAZCu4pU<^9jzkc7Ob$f9eWo?dAks8tn(+Xtm41f44P zo8Vg-c=3IadtJ6G6P$}XRQ)%dsImuq`-w2NGU;^M2Z@$}scX@#zHK_buOwyUFSKhu zv3h=>-DMAK4rG8;{Pg3-JSK!S4Ot<t({|5GoYwYjqGEtP0Dy=}J3x^+YDwD+v;V$~ zbIYgnqBSYXr1AAE<_42}?y}u^?DMO=Tf)6PHu|CxZ2j{&Plk&8bM~t6p)Ns!iN<J1 z4=<(H7V6}Jc1!*28;S*&3-U}-hi3QDLzu-e4`MUG=pOr6f_KilR(Ew)c<hT)9wnT> zo~#Y`o_Y8jxj8F`G%4Epm*-S@Oj2hJ+E}(b8zR)LYez?7`l!JVO5L>X^UX{Ao9D%k z#u@K3KCmpJr4@SSwgHVvKN95(Xl&aYl#P3NAl!5M;5PFIMJdr}ZtvbDx`_JRD7Yo< z@SM(4y9XFv<`S(N@rYNvIO+bwA*x<??aDND$A4Pq1c}zMxeAXv?R(WfDlmy>zTL)< z+#{Zw^z)UR8~b6(eBV>$&j31PZz|W4B;7Vy6sKaIaRx|emn3j<kZHJZykkm*C0MJz z^WqUx53cq9mZ=-cvlX58p{EtyQa)>&t2*|?eSoKI<tl>uy43ui6Hj-f`K=6p**qn^ zb|m?U)jB)3Lw8rv`Gh?tPTTm>-KSuiUK?o-l2?kqkUFMHy~#LV^b=#(4_k_jFlL-t z@9~85Z+0B^TM<6^a7JZ`l*D={&1!k<G)?2XfAqC0rT3>;T1p&g5iX7Vg6&MngO*W_ z5QnD{)y?aXiU*DgI@$scAeZBmj+(vdAi2ui>-v?$b!%cf`rn;%yCvMw4cqLPRI_=1 zM_>W9fy8k;1#&-5$v&^SdcB{u@W7hNW|ebP9)S#UDD?cdSqmLM4)9cFzxZh%4X3?A z8kx#!8tycWvUF{|b~{Z9y~+dvb|p*s*r#i2h%-)_PlR2fV=dNPExjPyj}H<N`nGE) zXpv3h>-1t%B?8t3$39ly)D_IJ5%&`i=*ttX`<{8j+7-It@y*?&)<0E6R>kkh>Z&b! zF;$oC{?E0#r9zK8;Y7{-E3Y}F`>OAmvXGy{K|3|-#QdicqdN*A!gz3eN4D2|@R4GG zbTZ2{xnQI#0%C;fbn|T<q@ipArs4m3)K{iWnOsa<6Xz;&y{Id_duELLkZSG|l*QrW zw`^@V-m~L#zfiq<E_XII@xRzB=kmY8-#Ogz+Gc&i+3c$^t>+^Od{2&hrDvdt1}`gm zDy{D@oyYz1eA#+>j}xI6NiNx*9rKjC?-sY^#w`K%4X>0!)84O&Hs%C&=(dzcLnw*G z2TyYE+aWb>S-gI3g)54Hh&~RlmaX&YW1aU;%3b!D)E#KundmfYQEsiip!x^tK3fUm zsyf!JEwqHba68iddgCJ|3pAB!eX;SDy7mjcr$YRIA@&gnq}yGG+uz+4a_3xcn?KVX z-20j_Ylk8oic<^K?LX-$vQ}^k-nMf_SwAsQEB}8x0s<AMKs4CdI`T@-C|7G;Soop% z&B<}DSGpO`0yYLGyNk*%?N_fHeZeVxAcC=~yf0MZm{HSl6`8M|Hh0-i|D)D;78;w# zy^29USP0I+e;a<?nXGXKh7HfYsO|nuA2x;o2PO?Et2FeqtoRFoxTT-Iq^>!de)Z6) z3O}C-ORA-l;}q__<xnBVX-A(n`d$On^b_K2Jbc-eD94`sA$Km^>l`jM-<hwb+<c2u zToPuTzomB13Brpx;`ntM2abJXcA>2)<0PcuCLO>4IGs)bueGM5Dp%9(r#Z<>djgGm zahQ?v;aNvdm$s??edSEa%*Q^F@!iYQ)!9`id>Pc1bNR@-a{?J$c5zIFNf*c*wUT1* zOj_}xVQmc^G1qk#m(@@6A}utbtWI*K#x-#Qo$tQiZ4?cji3ERuU!J|P2itLIud?~z zC_N1<9hqhS<&}!nzdF+|FWaS<hARDpcvXgtHBwm*Dd;fxPJLa&#miYXrCF&BG>!9i z@6HvXMM%T%_iSyrZERon+>eX+6P1FW4Ku!H%eZzge9#8fHzmPts9tG3`w9&G(PJNV z%lTER?$}b#tre-5o)M~pw>=edgGbXa?6T6ceg8)yC)=}As?B#)JrMBlLixp0(JP3! zSH1ot_j*!gIY2sH%XPIaud!G=rgUg4mNf)R58mBMn&4!b(XJDXNoVBPblaW#1)*eh zUZTwfGKXXTkYBX@VUQX|j4BT)Zoa4vtjA19<n0>Q>|`s{wfRbsOshDD7Yqw#9zA)k z(t5|DN~*H?uN!V&@Qi`ScqZ>~+L%!>3{1PC!|IDz?~=|nJ^6gHYTv;<Uwb38?lTX2 zHmep=rm>1?y=IQ-&TZAH1bI67g+;cDTL0dqlsTg)x-Ix*f-9h-ev<l&wpY=ZxE~~k zozH0dvB_!)O5dgPg{lWDqa?_)NtL8-P~Ul(e6NOP1-x2rR?@KYus0Rg3eGITn?Ib7 zZKO^qulC%u+#fbieJ%U+URu<W=(Q-34>_|=>0A?%Z|Rl#*KZUI)U|%0p}bR9cNEoE z6$$Kp_gksHOsUk7OmL>|ksq=Ub;m!5H?NF$J>8Lc-TA!X<&yWUn6|4n1y|=c$y0c6 z;p&*~!QoGp#iy6o{q?c*Ih6|}6>OHf**`29qLvCio}S0haZgx8b!+sy(=X3Yo9sGN z!$(}UtD3d4blDc6+L4fW{H~4$KRrHmt13F^x=PIx2xR|?cIGb`?MBh*0m);PT7Tzf zf@aRX>#<ME#eJ@*O{%?AEy*zRvPzO)(S^!l+!ws(-Q4_&yN6@C+x$B-#U^dRKbQ4s z|2EO;9x1Ix`9Ze(V*c|j?Smite7B(K8;jwh9|EAx*3Rn3K83~xS{-_CQsLv8@b))` z?2(HS(NB_2PO~22-GjreG_b^l+p=1V2p~o_&z4_E`a_Os81XO#fW!aM1Xpm!E@&{f zdho8o7PV$|@={L~hM%7<_eu2s^jg!k2WJSn-x~eET==j4s>lJ!f*rM7EjuQcI(|(} zG%o3|n408b!|;PBdh)TI4M8H7QQygO&sE8qPCrqy+0i27YDiVHV|FGQ><N04-k`jO ztN*XsQ)tqazB0Bq&;L!Hb6RSve4b>ZGGceciq5Lwn#u>3!uHickfE2oKrQKt7Q_Qf zJzL`rZU2Gxww6Z)YB@P|x6b91cUzg`nSOiCPnPE<U282=xD(UWv6FS{rB!(~No9rq zC}1A4J^YW<kBu#gj6Q~9`BmM>SlZhao^f2KGxu2H_nLsXEmOc+_00$-dt&)n_#WV~ z8O<qZsozz1RK2Zt`CotU-S5?RhMLO!IvuZ^{U@ZGK55#OSGJ;u;*1P>aP02)O1Qxn zkJ<xWmQS!-Yf2vb+{skU<;LEBq!)*yHc@<hOh(&Vdlnfxv<o;!huV4@JugfSda!!I zC_5@~8yxO^fBxhYP^7LfU5eW5F3)k!{KTc~*aR?e<l;vDrYbK(JbGPEb*$xIqFP$& zaGk}d_b)T-)VT)C)eW4KGDYkeyL<XjxXx|Zb=_dUzT{ZDCHUyo$!m^BUFo5bSI)GD zpBBqvh^stpDYX6oj%|uRPAM$ooGEM%2V(u*xq&T#M@poJM+G%wUuD5%yE?Xb^t!RW ztKz=OZ3uY#halN8)l%v^*%X_8RQpBL7t)2kH8DD?X1L2&EX?R?!!(;~aL0FJdAy{} zlp*yFaZ<25OZIOzoSm0Rek$#Xx5kQ&-9VJCU2!p6d%6PdHF3J9-bz`uR~~ouvCj`% zjSu2By?!&>_w@5=4tIdY?p&B_N?mb(hP1v#{hIntMw}^LA@}M3=KtB%3I5Oqu$=_| z+xyDJ*E1QSc7Imr1R>n7@wXf;xXjYTPU$(~ZEIWE-SO#X((`6DZTWM<&~2VIDd8nY zHY}UExMlRFQ6DAfOws@UD~8l~*0z2!H!v-A-epiDz48m~tlOT9CGnM>Tl?pe%gJ-J z9K~7F+a@%&Z}2zn{MeTOYE2&t%lPe`h3a#1$>rBP<z*Pc@%i?bQ$IH@YBt;2wASM- zff;l6?<3D#hFTMCmI%yArEkb*uIPhXZ~Uu5v;)|LP&np&Zp`+0SO4Ux|Guz6GaXNE zUe>pB<|$WT$6M!Gy4UYC)@|v+F4c_)_MUdOwd(4F1FF|-ingnWeltsuAn~d7+oGkd zmvbd&4Wmt{enfb9rtc;+PIVnvch&u5GNg)a^F8TD{dyZeJ-qwU14qv?0RHV`mAWgn zij49``{*yE9aoU9<;Ock>+$u>39f;4k!6OKY0JlOq30?Q1nfMCr3zWm|BKIC9qwM- z`8Ah5!<Y0bZocZ887SB30@RP9Ke30O?5qk=A9U}^Xw%|^e|!~Gfx#+zsm;-zwQIA% z*4Af^!@sk^k_5M!sVL1AD`-+QG+TAL2P<!Xe({qY>ca;n`O05Ud&@PbW9YvwzHW)S zwqaz7x&u5b)Nn-Opxe-TXLX9>&~C^x8J<{$r*N0e^{*2(`0p<PzB=QYseOCKstb+F zuTQD|Y`(hn5r4f_T^e^{kNu^*bz5KC^2cK)0;n5)D40J${wu$xT{^)m0?(S;(k<!a zTNJTa#^N58>9j{_)en;5{c)+M>ymF%mZ}@}$RjO?c_P2;vk$_hk*oj2rIn9@-?+fo z?bGJAj}M;be|yw-G<!bmYz^jNUmI0^%{Il9tdz@+o5!KAG$s%;diHog+A?eCvdT0G zi3(5o&wPU=)H?ayws#wcbIp!iG8hWlDyE4XAo=;Kq8P=L>#JGwkog0T9}8IJu~l7C z?2%V5Oi){Pd|b##!E~E~k2q7ufr}mSie70N_wF?Ko+8|X_7dTlu%hjw4oQ(!bz(_X z{!Qb<hP_T`X<;d&(-wwL`oCH99nH*uoDxtpq4nUGQi2n?29EjGK-1XPVGSciCM4<? z@>0DadV=qR^>?<?FVVWA!AWY&VqpU(WZw=s^>*-}AN2*7j_-H{`t#H4%Ku^L_tu`u zwDR^;)t_@&n5vKk9OVS@1$qo*UY;T9#osoo-Fv+~kR4@nR<zA--1m(B`NSCXF@cH% z(<j)fQ+B-7xIg7!RB7(mTU(d>yO;cubNhvqAsypBsSf++s82JNu|K8wCXYM!+PRo_ zSH`s~a@xxa%fGW;zOG9pBQ@zosN`|&P&EE&_A~cT9i&z!-BPAIWT|$uAwxR3v*XQ| zD(8K4<d5S?sas=h9@(nCAE~`9E!UehVZ&F*^Q6;%mS2_ENyjvMa@0}AX6r%sEva<% zN$lD|Gx+WQGMvOdg6mV7d$R37q_eG$&L3#kZ@-5iUSz2Fj1)!VaGUby#{0RRb{F<6 zZmK=c-E)6j)}6m{TYfwAS;KEJ|Lu^j80Wv{S!DOvYPw&2;JPiizF+nhJ(goC%>r%( zS$wMac1Oi>rl+>xmNU+pFn|y9u!MhAmq>B<`a#?EJ7bP>ywYBJOnt+#aM$?5D<8<; zmc?G2zgV|VvYpCTl)D}s%e48=l#A8s3eW#i6cn1)y#pX>9qF)Ca+xSxjRf@Dee`T# zNs2X?lXcnNe*clewd}U<&lhY@uYR*(&5dHC;jvHsOsQka@veimonOC2H7(^%cVoHp zDT_NgBrf=mWl5zLA4g-zNjWY%Aj2QwwQSKLV{yh!XPAYt@e<*m<=U_MpCrdvFZCex zR`|;XN1Nfj;?Md$lWq%V%z~|5y<F#B+0Lxz{OFXa9le|NonLMUY7p8!@1x}XpfccA z%vr~GaUCzSDrsX!t)IgSm|=d*%`Wfm9z^=v*t+W|*&?X`2JNaEj9Os+sbveB*57{X zclqt_GCvD+x=*K#TQyDFRDL`4hw+9}^Znyn&d8eV$)(|US~-ow!uz8Z^eqpRVtl|? zG>aT`B40$h<9vE`!#Cki9caEC5U}S!IqBk2h9rr?N^yj1+SRrnJ4OuJnbdFHs6LwZ z3l+>&_-m+NN4##u9!7fRT^B@T(?#0!a!bQ2+D!8FyZ2=Oj*lnRG(Xx9a1p(_=G5=} zMi4^u@2B=l37Y@p1kalMPc8De0WNR8k$4=l^WC}*-79D16Q2kqZ-nam$~Efd{<Hb{ z){Z#;fY_y@B+@vSH*vNuJ`@}Co2A+EFZSR-<Nh@}7d`fwAHU}WV~`F$41~G?wlTZ1 zBQ-AuURJ-cw1Wh;e~HW|JGX<dP2PQcPe$A6j?eH6OLZ13zz)+Gm4mbR+0Zu&uDgDJ zHCivdzv3(sjD`v^T91m!f&pX()2lw4e1buV)(1ZamWrojAPq`FS5LmG?UopQ@4bml zwi>(tPn3xrqF;O9>`Ru$(tuw0rrJ;lRP5bE&kaK4h+jzHv+op;<aJ~i>c^@RXl7f( zKbx8Flzq-{F@Ju|yNX^%*M`R~ef_5RyjqB!@>`pvUS&E}f^AE=E)1gU^Iw`{SK$or z-y?+o)boTcbQ0q|lf?V1z@J=S(#`VQ+SM-ONG%+6;`#(kUC}tp&&wjLMahc;{&8tx zeskbo1+>}lj!E;;cK4oYzwLQ_CcKidO}kKOsgqeXa7oqSR=fJMKi^1JHoM2EOo#+S zeb6cdT`<vbeeE+E*P2(ntqruyOt)9Rd0C!*wxVO%PDfDsD;cTegp3tTM{gu&cKvZh z$6?^&DQ~z~-g>ZBL4J7{_Gk#pzqP{5MctE!aQ{3=m9$7LovG#Lq$)op8?b`4X6A0? z7ajSw#+~2mlSb<weYDll_e4lV7bJB>Cm*%s^Q(6nR#)tAQ8t!6LhzVkqVxVQ#<o9? z!wx;xPYo%7M4LL^%okX;hqKRS6#pejR=h+EM<+0U!Oa56`QI;f--Zu1O;S1hVwf9L zsI#=k!%+)4{zAv~DR1ZpT-ZOj2KtZ^y$Tx2h%x|4hsDV+1<h+_saGvTfg1MAD)lF8 zK8B{XhxR<<Ij4egLFZQo-)U$I{Ve?Hjv~Yk9t;_<LIk1Z?3X!uj<=w3e@9G+>y=~< z@>=Ac;oR`!Ps(8f8MVtrnB%x<VF2!Sli{*?xTUx>-d_RwY>3MlXsFL$JFaNok$$-y zFWp5La-<gAqqPr9O0aSvOR4UX64|ZK_|8ws>(zQb|0)#vQwKdeR544c<hyV7;MC0S z24*3uc5ru0Cf)T#e=Ph&;ZAl6^P@T>n(fYJ%`(mkp7-5V_h5BDK>YpymQY8Fr7|bY z54)_t`~6D?X|>-TyTUWtbkNZe@Apz!%!D9Ix1Tgh%fYm<v~95~<~X^8Z&@<U@A}9y zEhqft)Pe@_$`beAKto)WG102O`LKdn7?E65lNXX~zNO=uZmKIQc;MQ7LXq9JItF6F z=z_79wy&EkIYH@3-Kbl5KwyFh>$g^Rv{v-2@l?uQoUdZ@NA1ryylKwZBA-7#U`2ak z^mST76xj?^d3S$@?_EE&<A`<7a$peuMfSb&VJ3Stm3KrNUPV^MvA>k2O$3<v`hhTa zGUVqqR7$t(avj4pR9*O}ec0N#T^iS$bxn5Hv4}HcsiN9p|EX*8(UMW$+0d#E*D9O5 zMWRwZgPHe7zm$G3k2al|RB<I&PZuEtF7rGp7@@1=S2{LP5|poyg+MIGJa+zWRnGm3 zhVvlS*+JjGpQcsoDU+2$qrSXK9d|^%m+0ZW<&(T(4QrR&dF<2pYs%beox1IurQJqK zQ&I4&R<=&dkZ;&s2RvoNG>1|O4n5o}pKt5SLk2!Y2+htzpY|)guT8t68+p1gT5dVp z0?F6niOZqWu(S5Pz@Q(O)Vhr!v&0>}qHd^k)><0V@2i8dw>hvmsFtn{K5^D%Ch+-v zL%%U<>8?G{BGLpA+u>&~Up}ag^Ypt*#l9axMSSr){FS?<VEy}7U*8&>XAuQ1v`4j^ z!iVZk{_m!`Nv+Wz_o!GtZeHCOn9-a9$ud%2H|^KN<29H2S@*_#%aB*|pk~!sw*yJK zRZwDwKK22&_=X9Bj%Trv=D744+n|)yuQ1BD+ZVbW(F`K8GZ~>pK@Gg6Zr*-qsDs?J z!v0AKCF|wlkm~RPoX(=gkQ{$gvgo1POOTt#kMtd%`DfVGKX^q(sC896C@?9_3_>_( z*3+|ub2dc;nK9-}f{YWq)V9rU`VP1L?CN**w&T=4pB@uZd1a%y2Rrv)dBN<%9iKFQ z;%EtWPxj66=j)07@-cM7Dno*`KnvyM-Z2d-r|i)nI4LwI>oI;7%-fd5i5n|Z9fj|A zENcw6wYS{=6}CY0Soum5j)jfU%e(jGHYPo2VN#s*{ru%)0RaMA!rjo5NoKLAIag0x zjxN{1I&~&$5ut<w;E9C_r`cBcwC1MkxBk7_mU*tfTlbSb-6j|M1y6zGBI`?Dl3!Ri zrm}q7^|40J|Jht1DFg>$9Uopvt}wQf^FKPTzP&|LJpoH!trr4rV`>wBiLi{G-EK)a zwaak+jS$!m0Za9@g`=mmMkU{9``mQ7cb{9yfb<XKn9hBk@<z!QE$VM1eRYZqS)hga z#UwMrD^=O5m^Nb>8gy-ULqj+#@$C-R==j;Q`%KvMcAK?zVcRnGEw#tBb$&;?Yut&1 z>UqhDlc7F@cZ?7UABYGPeB*{uj-ocwKCOuwT(>gc_Q`QI^=bu@j@QSnxK>at>DxEh z9=_K2@28xG7t<?#ayF~4m8p#l$0qnalp41MkGOrHvG~R+b#nUITN+O9xHlw4<Ls00 z{|Rkbcz=ngjGFUQL$kWG`ceEf!<ljAw^GZ49;P=Qd9de%VntkYrPPW<tMt$t0qni~ z6xMV_wNBw^OLkj3K-n%|JstC?1m#(WuyclcoOzL<?8HGk<R3Q`|LV!q9oTLCJmd+L zAvJ$_--ijdW@VH2bkvwTe+hb6mN&sK$9MS%!__LRU`RckHKE6c!10EoBm9XLX~br^ zl6Dq0o$Sw?Id52OKv7Vsy75-JGr?(i22J8JXZi^@YFIUmvtDn1Sex2*FL1@lb)P<? zW#MY1TS4;Jn1MRQhHfAM4FRy=?6cm`)|~NDH1(*;&3*2{ook)DbvH_)J(cPA4l~%h zA-vKgRq8z3c$phvxv8!t$)?HDqh-AmY=~h&%6?@ZG41Ai;t-`F`o%Awo|uYr{^zc{ zhgi~Y^9->J3=)0&{@X`FyAElV9g0%0FlUWYfot2nq@|fnRl(Fj&P#;oNP0Qr{wu## zrP&{CxMF_euz9TV((MDnug&H*y+pn$Djxgl*0eulh<8PE#U+_!4Q!+RzTL~}L`lK3 zcq?8zgXsmxW<s-93||(It9aPI;>eC2y_OwAXYd@QJ`vW1M^Cl1ebuzN>}rl@Z&13z z{i}D5cT>@A)j@X$zhF+B0cnxK)}X0}K1>Qt`J(9??#zusVC*`tT!z&U9jaRsK77Tw z4A;j}NSu&%=2@w+C2<b!e~TzP95Xs?Ek`*E0BJY0L!GO`CKvn=F!(r4u(J-+GGw1y zm|QY1Sp*<imn>~1^>{El@fF>g?SU<W&B<+yv{%>W0TEnD>gqO!TH$pSJK^)s({frm zQJJLmr!ni}@{df?!%u1hC<|eRDI3KL10P`rJ+^dG%vewF(2GLf!Qaw)@#j9#A0K#r zx)TSMq$dB8=Z({hdt^eK!_bUDLbrrO!<v~w`3hr+KbWdjCjN&iJ`HMJd)B1U7R|lX z26`$N>O=_u0uLPuLQ07?_y&4_9icr*P_q>EHEGPvVOe1Q`vanJ`rZ&tlsnOT_D#o7 z)XL@Ub$Uk2!@J|>S9LTovsx(LA@r^Ps|!Ii#-l19GpcSopPN=LjstI2q8<8CrD;rH z8c!mgIBzi;hn0p{!BaDhsg2qlnf^QQHjjnxu(lfCMo_bvx*z|)wO%t(WMiPpkOsN7 zaD<eqg9Db2p-J6B-P0ubTUf)75h}qO5iN?=o*1}*SHOAbAQG)_lskO_jhr*~bti{q zvB;Sv(TQc{>H3eP;-l6J#iL@pi_(<xh%Sj$tOH0rf5Sj}2mj@@6KSx&d2@%_<(x)i z9ZRTYK+~hmiHF{j5l^N8G#*vq0~4z3stj9@XWynCLPNw(Qw6m~S9%HaMnGNlU(k-K ztDmtpB-{TBJ;ll1{OQ387hH9%Y85j&Y1&Z2Hy@RN8I;1^<O2tIsq7YT$8|Jq>_{&n zdatt6nFb1J=}s!y+S@kOUJ2DiRHV#mDE>qM;sM`by*KoGnhA51KRMa9iHJ?>T<xyI zQVw#_Xe$drLf5qKp{fZMB8Ph}4ZVX8CIa8b3P;0-B?>D2$a9AY@U0;P@@8S$)c1#W z!!}557xUpbk8vOLa?Z)SFJD@#RV`C>h)*2LGR_XV>7`{g!vZI~z7d8m*pY@whtC#~ z0U-rc0e+ZJZlLu+c`KGUL|enF59eX#wEnYlVNRfhvE{VRZZW}9ql{+2feDTZIzu11 zt%L~Td(4&^xwPcjW4A?-QQ(KaC3rdyRG{PLN6b4M#l597|Ml1>fpm%5r--RLxDMj4 zmd=oe8s#Bp8QdICKPm6_==_0^s@=MB@2=B;v^cz1M)46ob1i95OlMIwXKpTMjT@Vv z9qsoOHfYt(X0{c)uBz*y&b8`~EPcOTd1!yRRiW%TGox)~lM%Ye7GYVMr$6@jzTnj~ z?^Pg{*~^nM#GXjRNu=VSWnoupp0V#W65<lu!{_fZqwdj>XpUXUvrL;CBHj7rXiPv- z-5c{4Mz__z7sC<Pb@cCh!k<=8A{BANGd+1L`12V{SGq@yUVXf#?OUF_L{|vQ>O#PX zH(YY*i)zmoI(gvH<IBExA8dDE2OZfH)18!!IIuaG#Qf`%3Kr;`y8mXhEpJ+`muefO z1M-g+_uHW%*I)W$7rw8Scxw0sbz4MBkCI|y98)AN!fQLZ9`Txe*<ZAcdhC;xYRd<w zoRD0w^2L20zSiD;%J;EP@2NJ|zmrc?I@<oHUlV%2ZDQ$TpN+HE3mAVbll6*Xf6@$u ztxNAcca-5Ph6_esXJ&f<x$-}|S0u|xSDsfal2sMk`to$vwbI=$tU*nlG_^eXJ)#*d z4FtvKkq9`XvQy^BQZ)}NJ+-Gc)bQ7Pucxcdwti=n55IeYb$|QPWY_qPTOXZyeg6-m zYX=+v*lgRNw^4kAPOql$JE)Hs`iU`RpBsj>tlYbD{)Jf2M%8Ej+lF^uyKWg9v)A_G zjDI#&oGHRh?Rk~0T=Kg!f%En$Qa85*_>eS69Y63;<SlJe@tOBx!3d`6s@0y6Fp=8p z)8*00w&EoD27Y+9@i^;#&@Tk0P>yD;*l)EE+{ipsIx9M@Ed2H412uZp+gs<?xH2Mx z&gl9%yH_?nR~J{%Iekmf-QR3nAd(uY(hNN)-d3}9_K;HPWK~mULVnKOaT?05M3lLM zGb%!UTwmPtZfazIj^geJ4q=jjAaaL}&4os9M=(hb?W5-A*#BDP=R;QC5=Q)+jL7E7 zcbt}wCDSiNhX*Qp{_j8X;N!iG#~UyV;}TJGviQUEg^Zu3Zy#Q#xNG}Sm6;*;`R9kD z<Q^&Q&Y`^uR^1xW+%6{6Za>OJH$0T3_WNcr197)uK_8f4;vqg8I&P=y+w{N6QvTbt zkW={bjfT)s%@wA}2QmbnFuCCSfPv<*sz2YIhSwVDNy%E{ou-6Td#<IJu>v;!=F@v^ zd+YnXZoM<6=_$+o*KgE9^NtU^5cK2g3vcPy?Qi!iZo#ZnWMzyyO8YzC|C@AktJ_G~ zY?UDCM3E^}1ze1_&DY6&9>RvN9JHiLuye<v$fo<({b|_Lmp`#OYvjVc;GR_folobs zu<Y&*w$|Z_6D?_NKhiSlR<8SBhE29C5x!lFD84)8J-k*!gH<Ag%2AnS0%`L7X3GQm ziE+5*iBjA7u=g%T|GwUp$YVq$O&8{;L<%M9(W?~WE{U?-@LKac0qJ8OM+73HC|qvM z1{xW)>b4ER`XnFul35r5oq0?R*C~OFbi3vABVaN}c#yHNl8iNpB0Lgvx}b}UOl1!I zU-YV?EpDVmC6PwhvDY5-E&p!|53W_;z#v>ojQNy-6J|*imZqsihstc)tcl#@-P^VP z=|n)p{c?fp(V}1XDBGuLU5;=Tsy5%^vTaXynxj^s{~?m6g5q*lk>y-Drqfe4p~kMH z9Mh9u{2%&a)eD}hgd0{YSUQ~z@~(R=f$Ly#3Z~WWET!dMp`pH~x4Y|0T1@Pf&>{bh zH!PmTdEJvMf1>}`^=A{j7Nct)LRn%-vqd|Q7q*%`i<$(DMYPkgDwa+Fs`yL2t?5c~ z0WChIW-s6RFd}K;m)$23s~`(ZJcafwK?~t2>pnt3_xkiQI4!Vs(M5u!ZK>oPF?k(j z0}n-{BWM&QAPk$gQH8%yxexNn-rqPhD~S5CU<Yhqp)0);tUKceb<Y~jECggM($v9| zE>7a4#zjJ4{F{#<#{v%$gO|^$$!Ld7?6f%hriS97szFGdHGsmKzZhosPZ!@uM#ET* zEgDsPPy_R^DK8pg2<KnB1S(tt9_K*q3WvLVRgmYp)XijQX-_90MeU|Lg0*eD#R${_ zv$`3`i4VFRAz~@Q4#-=O{RK$T4yHmZ1tY@?&4xDgX~}To(drk;vaZV6+vZCw0@Y_s z#STdg7~EM?t(jS|UMMvXP$eml6VZ0dur+H`!fhKH<Yw~p8n4S<n;_TsV3CfCbS!s> zOgkzFCozmRQ1%PXGpobB{!Ba<c_`7$y{>t^xe|V57_+(k``Uzq5Qywm_3a%A4rP3m zodw{*#MANp*X#U3JSaR+Y}`k;!jbI<dwa5KD0>OX(Jgw@gdn<U!IJV4_3LR?)&<%K zO)RpW&|on3M5J|#X;XMx7veBh5_1xJC>q|F@r*vHytzTeen**8M7|rX_Efz`%M>F@ zFsRFQp}FR(XN?YHG5H4Zo@Cf*>b75ih`9FzyOLO2E*8K8F>mFP&qZlN08WepV=IQE zOaZN?p;AcwuN6IlslONa_qF@4666zFEJ#sm(@(g(J-UWi)64?kJ`y;!{*}%+fol+j z*0`UWHmm>lLHje#NufLuvVXKV^cm0K_2&F#Ta{YX_v$O;(ayNST)^w(3d~?Sl2#J~ zC<yLo7AIny=$GILSj8y!;R7{}YOMzociEZM4a5RlD~JOd*Jsu2XL@6b;)sZIX}pi0 zM*DFCicwrC9ae%uE@7v>Ma)s5GbL(qeZQd^UxdDHn%NhAK~w5J$QK!fzFE?2kRI-b z@L=RymuPOXbF0vR!b}>X-~7Hn*;{TNQ<J70l1?wR3(9V1?JOpApikgcpGIXWmm8;N z+qMmkOD9O?3`R_PnBpZXre8|`6IIwmib<*>lN3tJy51=zPP+Gke}XqNnElx24_l=3 zi+OhPMwG>JJVmrF{2da`brr?7ZCldqCoR4%9l;)wpv68;@1U0?m9UI0L0}{Rjbzh= zTl66`gUX#-qp}Af=*}MG=ZJja;buNS2_l$AcNw}2F~!T_LX3<P|0s08_jKz+$A>pj zLJ$F}TzYx25ksw%62Bse0Y&#WiAp}1rbuV_!n0{(*gvGD>1am4kkrES!bHna)Ecc8 z&xaZ&TJuls=BR~1?nb5;OiaXmh{bLfa~IBX;W1NH`StX{&>EvOX%sn}%QS5`1_DKu z&>kRz9906<NBJaa&OT#B2ekuf!)$U4>^jZ>?f1b(y!%lR@}sRBw7e&ML$)eA$N82; z3>}w>5p=BKEzk{Jr83^a1kpT%AR8o*P&IUQ@)}ya+sQgPSjD=K8fIW0!pn<;;56!7 z!}$nN0@-4Y?)zXr^6S`j;j*|o<9)MnbvMYGrU6b@V%{*-%1q5Ci0+6yw%u(dAZ3B0 zRlF)AD*EUbIR=7VdiMRIPM{~B-9a(35*_P{wA2)r3rVTDFzAWF;P=tH+fa4Fbx=jn z3r1?W-v<SOZssUswVHroICP)QlquMfa;qzDs;<hW&aMIb<0hg&_*IaJflFeAS}$&7 zK>esRwVNs;l5&_rIstJP>>`7iv9753bmQ<G#aDOoLgNOv3@8;|p2JUr50fP5PUb?& z(xYfB1fKg`srX~=SJL?BYRnV_$)NNCCX*DNQJcncTX78ucJX!M=+#&{fib`(@$f#e zvgp&s)YV7O<aN+}C;&$%&Xucm(4|#u7`ku7NlV_N3zzzKG0H%^!dHHwW8Bu3{(W>T z8#x$6MNNYk+d*Td%a|IfR}~j9Xe>c)IVXGObW7w!3F}zJlm-a8ltSqVZebyvaXjSE zv6Y+_M+noKH^1Lg$xTsL{V%Iqy2D?bE7-;6SW9Pj9dF$dK8e7T$z~$=Ze9Gln8=J> zs%S<79+#&gwh$&RYxwHp<(~g@v{j_#meK1+6V^!Wkj}6BG46y3&&;K@`<o`2Nifsx z$1#i6Y4jOUB?{rZ$mPguG85cT!TfEsIaNjDCosd0x)1O9H)E70TM?&HsAw3{Y^VoQ zgaGJpi<CA{-xmWmfSnRK`xGIcimR>_8F*A}6Wxb|0U|%H+Q3LbF3fB)3=u<2%n&a! zLWM@uc;8N7c9fmaeL&N9(<J<lXfzAtS*%oHfDMiPeL#i8u3d!j&Ld8u{J%EchE56y zhFhvZMpKba$6X1c#9aUf3V`&`h}4RG-Gndp=jM~bO%kH5WZv{%TaJ+alQ;j>MU~)G zv^sE&ox$IW+}xK7!{MgmlXhWxkx7XhA!stTTnzI8v_phMpGkqSvLyh4Ak<mq66EmR zkJ2bqO9(;JXQ#&?ATz*-BshIyDSoOG*NZDZwnm(3RQdJmD_ST-`@DG;u&><R;%b(5 zZsQ!FACW~9fr+u2=<*{F*v$}!ScyP4f(w4`I#x;Dq!ayYT5$Mn3}LYbEnzje;)qHt zLbn8pW1}(%5=tVzVqO{WCYOpqFo#nh*{E;nU`YcoZO79#2t%dlbOi761{3-qch|5L zk-s94-mJbwY8`4(J_B1CQ?P?=tDZ)<*5*Jzmq{_qRjtHvRO*7aS0?^QFw7-WZVSI4 zuXcS;6m^d1JZc#$$OaE#3+Z64A5(V|V|=a@BkinhSHr&Abf>5{wGBg4Z*jM)F1Q?= z`xuYQbA3i{+|Yfs#046fjEfY20W(ht)CPGy;#zSM=4tV=YgtP0FKlWSJPnf=F(wcz zMQ2flhf*Z^kn9Aj&~|?HTyRd&*GRxu7TTl2f`B?9kH;;1u@H_6@o0#@b|RlN*k^J9 zT_F<Vxt#*?*p<MURkD)&;`%x?SAUfp*z~H|rmN%(#ah99ofr{yqSA1exmtpum_!Hu zeCm0Xf?HrRiElGUakX<~t9&@}?!DW48lmRLD_rCczYVml)%0I{{2$Jc-IW=#-o`B& zwoU*}&}flH-<|t=f~}1QugM2}UamV#zaRs<V_6AL6|r!O+O=Q~8x+*2c`=e<4z%lW z=!<dmeqmKo>v{n@V!sf-kZ{h{CG(4ceAC~Mc5dgy;m^cjuQ2^==k0!zxIgnEg=yuK zGN`h3_yrsScct~bkiv#^gie867&fi_?GOD%A`zgMq=pM9C5uqS%0G)yRkTouwtnuw za3Tr)=6}3^FOt0IvfOL|so_4O&<wg}j=M?lR1&yCmi3EiALot=+|e5`iNfK7A&-6D zbY=?U5MPaVY_61_1by4AV3U&u>dCuyhlzMfyu)XKxtK5TWIJ2TqZavq2ha&ZAV-!w z>7KZq0#>a^i<m<^M!5Z<Fiq6Ks;t@W0K`%^9{+$fm`%N%J8zCMah9-KHTf=yI~$MP zp(mTyERHDfCv_UD+Q%AY`o4N!;(U`Q1GYLsBVt;cmFY5Q<qWeX2lvl0z9Jo%S>vfH zsCV;dRe1>~+>143gXdJ5h!lcF3k#QYu(8+zOv{?7+>9QnBq`9NR|9%Vk(Eq`YYI2V zeYj^;;BpPt%g{mx9p`_95^eZOsm_aDlkyIlpvX}rfL~L%gqw74Fp5hgd7y$vORGGH z(#Wj7ePWXsSV+pQVX}y5zt_D=$;Dr4b;wJROr%K<d=hkAi-ozOsiysu?gEPl?J^II z2U@a*s!4UU{U`V@a(+P;sn+YL#~{M!eFIGAqv+w-R4&#9sfK8lHu2U)B9D7?ehk_- z@IpiyMPUy!6M^eMNleQ=t+ntM53$0=z~bdx`9}+4UZq2al_8`1wDu=n+I!>Cun`#w z&2t1rS=~(fzH&X6&{AKq)kj>kg#uBD;ug+S8N;to=LWf?n>sP#0K5~iuq2T)E1RL5 zT0~3W#($iZ!tn)<9Ot$wmrqjJSxlk)YUF^weMu%*7Z{kVo{FTdNU`RUjS+k?wbLiu zp=6qX0G#zyp~6h!EzFo!+SMythWe3-b1^t(;{rLb6DAroomNl&RHzLiI54=ax3`g? z3I~UcP20EvB!@_r3R?6(s5PjpOyjDVDQXknQ#taUWHEw~Zt!)0`|g#4=9pN{nmlrE z?phrkH=vnU_~a34t1Pu`9_FL%2CgdX5kDJ(b<D64iWpiLl_YB3P*|v8I;h?X2Q@k) zjvB&VKxrmy0Ee7~TC!DTq5BU0Uh%fzAl_WbMSgVNII?(>n}{Xfy-$8}cy}p;Cz@*$ zUwdUnpLzB+LQP4;T|yOET_aqhkSoTb9m9^~wp4Jqse2g^nA0!*lZMqE+yl{~4laTz zX|mUd_h2aSX!O(t&jg8Eafx?Z23^G)&Zk!ISn3mZO}Zq?@G%X6;+7JKvgw~8s9cw8 z^KYWAi-@zkUFh<fE$s~+G@cR>)#Yk<<uCOSzY|?4c||WoP_HZ7EWX=vG=q6Zna&D5 z8#x=VPZFCrokRf-8pQ3zQ0h!SKchEH?8EajHTk9??q<G7%rZPFKjHTiMCRs9<fFy# zM^jEU{ilE*_cxF4Ygf=4Br>m@OGyDyfEV~UDxvjte(H8eq`QT|xA)i9z*$A4qhkB7 zy&Vh|vMJGyhc<<}+-@}*3Z19{G;<pb6G3Udhk>#TS^$>8+L{^F1BHB}n`C(!*PU!Y zODGvqyqz*jK-3pJmgUIT>dOyAg2oNk1&UCgK{n~v(zFA-g@e|MI=OWEd8T)yyUj7~ z7S=UsD#M(kOa>X3V>v4Ov32_gGdW2gNC$vZ>8WYI*UMKR5nkT5*>Y0=jQ(O%NNcg> z$V#g@oKbG$t;m-gN)e$a1rff4b?Xgi#k);to5SYL1@acfJo93BioFWJ8gd9?7w_Q^ zkx5?WSI7GSLab6++7mTm8`8cHYys?vxrxO=8jbnP1V02rS9Q0cdQr^sPjGM`Ri`&@ zf+lE=O0W|^2}H%5CGs}7=s;N$4JkiqmCxwGDhmMwCNgh{n1H}=`@xgiN`WwT;&>FD z%oEcgLuigejPDi{&Dx1F-k0*)2d=}gMB+GsoP;F<gS1Djf)hNuoiEx=xR}dSq~#hh z9262d*a@TqJ9Re9b&;jm^pP7CUkF9jS`}N~Fyz|op22x5&NW{gt2)hxC^H@V@J-$k zpfz~}3YMS-0y>I^F^paWhLs*Ic>cW@jx*QHy7<BKJwVsEWCz0|ViU=QL~?sgTy(>H zc9|kzNS^pMt_9}Z(pftV@)Mv5CN1A-P63C-jS3uCRo8O>v8yB$*El~Sk_;nL#U4|l zbucHTQS0gu2&X(Yl4Qr?(WJ}es4J4ow<=oC=ise~V9?D@G0?T#+sU0OPBV&t(z`YT zr<2P!yN`LPV{1k2mH7AOB4Gfj)K;OkEfUI|0+Cl=%lB;Od#{jLQeoum{ZuQW(TsCQ zq}e7)k4msDEgO4Qifhcx3}p(=XeY0Mr$I=NWJ2T}`2ch6l!7xj5VJW?_qzJ2{|@5$ zEP}VB>CSW@9?(tUR%Llcf*>93WCy97_ke`n$)*>NMVV5~N!`sD>=!2>mnLFjqCC66 z2=MoFMc6S!6gZUt5qk;a+V6Fhkfw}u9l>4#0C>|{)gfG8C>NP-dlDLrTI97~6IuxQ z3l{wrk`nif?FuizT!?kA+9X7x)BFlC3yKB--rORgRN_g$3Is^>7Bq?In^z%gM!8bM z<!VRRKbs{G@Ds`+Xnpw-lvaq_j079_@Io*VI0&1xm0$~+CrA-d#vCamHL))TIZbA% z`65#+l%io)+_nq`w2{mlz|0H$L?j(yAm-i-%-;|r1GYYt+M8Dj7qvUV+KEyokDgGi zUyp_8WUHNhu^Sfvy#>NcQy^<0h6zpOau**l)r%4;VO(6!adOoKI@GE?mC!DycJXJ6 z9Ha07Wwt?@C89m8TKf(_P*)0mO&kn8b5F#vr9+R&rKat-dpoLOmxFvLWObxBAi4a2 zwHGPa@H#E+&RAeU6)<P{|3q#>j7Blk6Vou{YhOsABL5X{wb-dn;19epScvB^oC#~I zMEFD7bH5Okh$cuh+a=r7?r;KNVY0M(E)ENfRVD*Pwz>0DlLlcHFHS`BWw~y}lp|)Q zZW4uNU>SFG&67#SE$uDmOga7uCxp9XF{(DdE1xpMMHoSWgkzpUUBu!ss@;tQB=l9t zOJ{UhuOKhqXLJw+k}(oL=o4_nJlv8Gr#!8{g9`{BOBXG3>jT?cU^lT70B}sHnDZ=q zMzx5|+AP)sr`F)gGNisy4|(b41YdmaQ8cS^jZ=`2Xm1o4kb`5t(hLV(gjZr56ucDF z_CKHU#u&Cb<`d9H3u(jjK)QZM79U~K3ly0_J~ITpkTjElOoaZhn0O#d1F#xQ<1quo zY9;w{A5;~hlASYDAGi-jbj%5P_g4c<+;=_NT{ERtS~Izaa@c{YYg)Nb9>eY1l76Yr z$Mbac73O+xs72`^vx|b!KPpG?-M{V2@wH<E$+QIq?@%|CR3878IUO}73Ex>?r+)Zu zPu^0F<!p&^MFadZBBuU*>*g&4veLp>i_7s}^4_>vr-+XdrQf;r(7QM=wpwL|!<$Hk zCACrc4(bFbx}gi+Vc$6qV=E%}=pl1<zmG4Ycnk9mPrau`t`H21+6}Yi%lk|{1L3kW zrhs&&>_Py8$ymZzu3WvlD0b~pI~avXW=VmzywxrJL=g384^wrv=<fQpn%@SeNAO8I z*ce6RTS>tQ6Lxsku%FjK$UspZD{U6hvzbiq7x|i5=llTYkCB%?*HueG*PV=Y(}{E8 zkg7OpBT(u)M9d&^U-M$eLpxUKmWEpiF0+(%J|eXWxNnGQ-g3dOr`83rz$A4Kh_L|0 zpA{w|Yu30A^=^mo3luu4r&nGf<iVkp4SVj~oaI+0-8L2zxLV<0sf&+bo6yi4B@St~ zrIkdU9%P4!{nMt*2hE7N$<AilU!T9{;C`kwDoy<2+`nCs?OGgM(TPOA!=4=XA%SA( zV;=;GiEV%trmKG&AfSPZpoafPViv}F+zUS?SmcMiL1DgdXSE3QnAEN~BH|5;E_5uv zD4saUd;VLIHC%Ce>8A-!Nsz6m$Ic$G=%tv_LU!{ggcW(+I9=P^AP($h0aljia6zj3 zmi<lRzUj@;6e_P8#j0Ic2NP8Ki+;}9>F-yEtr{UE{7shO9or5|=|E=<;=?q97AYFD z8JsYNA>!n%T#Q^w%-ehN-9}s(Cm(FFVeqeu`bU{#uIHwW<)k>xUOL@c3&kVLS*GCf zP3OgfL=RhUITMPhYtvG;t5~CytKQvzRlP6IG#Wl4w_fj0mVM$}yz?1t0MU9LsI%+` zreDCN+mYXKM%|HrTa;meuvO?AixsQ2xDuS1KxZsKqwxd=GLF(rcu`4aM)5D6Q>5;} zV)d$LPq{4xzj@!<il_0HoP7>SBiqxhB$Gt`Z_JLoZ4G_1mh<ejndz4&-x}aTf~lqx zlRr%l-<$kV!~$!VZ1${F;i`ME0Bac*puXcTs@Y6*q{wXCU!?y|Cw7omA!e$`ZT|v6 z71&Ge!xv?nS*yM>K|n@}9UYo_;L|3~H72`ebN3vcig>}RiR>SMFQj5pEs#L}EQ8LE zuQ&VQEgt)Pj_vB<mg71*xQScR?bFXa@#)_rQ?mJZKAVE~rA4?X-7QW3c>5hEHv>^0 z*EC~?hT(rk#|qDasn3ceLclgt^{axI%SI&P?b>SY|B2=oJM9c+zfkTd$_Fj*^un(o zeesn&jgvtDv4xRob@%^I{WRuyoY1Qv&t044+r}F=pHJqYezPQQeX5kyNEAFcpi8_E z>REI2C(;MJ$E^v1<!22wKG0X_!T!KxNhQQ<m<Z>vWI(OiC>@B}3}8lupdNuU?^3LE zAFKfRYH@ht%D2`u)`%!%GP=ugGrIc`3SjTH0BnT?I_q<dz*sXM{iVR(oF&fXA(IC6 z`A9*OdfQ16T-fxD$LEg(ac&S!bHrfcA_`eXj{7{zH3A#0F!)!r%EW2Xe3H***)Q~~ z>XF_u4@@->8&9X;R;B4&?TW^k)Rg~|Vhz;?Kb#Lf?R^w=%SB7TO2C!L2h|NXGoOuh z05_$R98uk@@r)$E7u9?k9Od2n^O#|GnG94#C6G|TcuMGt9T3?dNyk^ADb_MiM?1%V zleizEjv%o0c^5wlAc(jQq}L}okp&2?CmHLEn_l$9a6r>Z-W)xGCT+IqVSY~4mG(B3 zqNQCdERD~K<+|4FcoET9gSYPZxlnH=@NMEIyyHH+;53lC2r#_0qPg!De)Pp#a$&vN z)jn1F;6$4g@-TsZfTalk{~^LDOgJjtIt)aGpnG9EKhtbE!I`>r^dM_!Xf{3=!!#_! z@2*HCPo52apED5Rvb54e+D$t0ojMpZ*MISA9fnh=GUHiES`s5YSsy?lKO(XOBHB+! z_F{KuD@Y+m)@)C=cOx%GIFfUbmvu2b<Adr?T{K3sW0x=W`RL2O8dvclQS=hH1rbW! z*dt$q7oeeenn0%*f1jhFpbKzE1}k_3<%jRZUU*dQj878$1}(+Stbf%0)<;{Nx?7a6 z%*O8H>leKjo8Sn__NBzU$XJu%wnzTIqRu@o>N0)*R+d_AByPDCI(}sg^8lMv3L%rN zH4aJ>iXsM5iLq#9paf&cr?8W2F*1mRhZ$Eu@Pv6PLD$K{1_(6?9!WsuBp|051%{dV z^m{+kzFxn-+69^U9G>TX?)$p0>$>Gmr@3DJXLTqJp+A|OyAvZcu5G)Kc9=8Sc@fQ* zG*j+Uk{h~s<HEj~!30Yn1@}Gjovi|^DUKClG}efuLq)A31*xMxA^THwd;YkrW=(^C ze^wpg2cDY)aEWOYq1CAv3hC(B#yiZeJzQFKw3-o{jTyH{iF|YWzNVzI(Y>=9evGR= zN=nh(HCLl*Gv(08zPjd`vxI?z+*M*)*Jt0&*S50O>ZLo`Lz!l;p?)Q1afrmZ))X7& zMvv~7dhf9c?<IyMJ@my;s3GuHYx<4LpL{z}rce^tCy%{3pGmu{0usL&9m$oy9f&<@ z^Cs3^vRkE2t@EolwYvw_j$lGj9gQ@6NmSrh#mgR{g^;U||Do@`B(aqOyxFzi7k{a} z<EO&+L%^pBVqMv!;nMeUr8c<&zvr~>RD*iVeO2#>vyKegS7mQy|4A?Ro9_0uNNJ^u zy?+C!6CkDdYf8p@YqY@|y;gaBJc@Yg1Ca+Pg+L+QtKRtcmH^3D`@A?BM2q!gK4p0j zD1fRtuS}M%7jIcN_qFv^880j7c+uej(37Q(9n;p$eU;(%cS!F=`PT)j_LbFM{auYF z>I}N^dWRJ^K|$1EZxm<$Ru;Sw{Oi%Ie(+!A32rDO&HD8{o@}D@9{Ccjrw6y2IcvSi zvMKM~?YDd$WF9qeoSW}F#W~pSeeq~6=U(;OLI-T%h#hQezLN#iSEKrI%BcR#+swp` z1Gs5<Q~mre>u7It64Zw$&QgIV-38Asi=Maj(l`G0P4VAjl_v00k%<4>x$qr;Z_Oc| z2)_EGZzm?|m}mdz;~=WL`xgCF9ci~_H0mu-;e`w6A45jGsHf`QU0Z>GVsTnGTWJ3- z?WkG!Z*C3!MnL>c3cKgVzXzm<&2`!hJbM#$Bp{+D(WW%=_)9kgEmY+GF=Xu1t6ctB z<pK>b_k3qhi_3Xur2radj>`xc-ZI1PlXd5m)FmKBk%YoLb+_nbdhSp)#DYy*I@q?X zca4>R;B6q~-~N%>ilL6Ox8QdgI8#$8WNgZ#Y@U-li{q}g7%pp6AG7B;$uQz~lv4}& zqI?jWX^?=pN$`W#OiSs~-Efs%lSoJ0Ml2ULS2*J(9*kvZq6We(^L7i~*?u>(&O#qf zI2Z6MoRygMUT*MUY%Zz%<-2JwnQhLBu`_C@Fb?CF))J1!_3@;5?{tk%2JJlzP7ex@ z{x6^W?eJo30WmNV5zZAAKl|h9$%}gHaBvg_Q`!&ty>fxWeD}DwJQJqchk4t|M#B_4 zVTUid_kpKF$KIl(d%>W?X%E3633^P0QUb-Nz?dUDIbdmeENpX1l6=Gw;`T1R)V()n z>GNPt$@@sPG2CJ;#b4~Wo;*Cre~(l-S0m<D+TUSR)EWPMltM3DWAX#-Gd4zR{+gJS zQVttS=W|UB!@5URF+kIrm-XKoJI~ncX0z?Krry0X{+#iti-meQ$j8Qu;ac*tPS@sS zIyP#^E7yW2E9|c3aMD5GgKqb_*lh?;OxaguQ^4S6htHh&{b<gr$1W8*qNG?Or{5*J zVHT8-B;{CsXjT2@d&=TPU3;%aOwcg7_C#h4>?O&*TS6K_Ze}Q|xU~|5VRf08fh>$o z-s)QZ<O3|l&(-tw{h77yzC3fKjgMVC3D_V4Hkcq_M@gG=AsD?On$`mXI8$P-;$L~l zge+uG6hF7W?@Agupg@&x_vT(St!0Pv_)uS&gczSC*mW!t6%b=bL1OO!Wv0l0+uO1R zGHS{pS&MqHE#FOaGj3k2jv=EX^XY2jXreox((W-ZI~E9Mou2&>)MV=4FedTBz*diX zdI`)cpNS?xNv5NrD>UWh9dXX_hn0$x=9*<#cc-npZj9kQ6lcHd@gRnNEh`p1Pr>*J zJG9uBEh-x1tsst&sCM|vo}wF@tRm=4Aqu|sua~8Pf9&MRZOw)p-J%n{5J7~{54?_5 zpi;iPzS2k=j7RB;PM|1Id-Z@SB)GG@2(2gzRL?8Qvtko~eOwh2554sAai=PtIWDea zqH>Pn@kWwtL3~t?&E8F8(N!R@61sk7bJT3(Bt3C9U6_JKkRdb`DSIPmhT0{;^4N7| z=EHxP9-4uZ+oB8&|6~hfFnH*3G)>b(r@xj(u-&j(hCr~s`^pH_hJ1sz?(~F_1A8SH z0%XJ&-u-oO?wE%??&Yk;cZ`K}p>NES)ZU`Rrdp7%EnVmHHJDpnEho1arD1>3onM#; z*r8a?zx#f2+UsAy+VmCcgoJ&Ewkc)pj6PjXm_4ag)w3xEYX9(d?ZBLS&*2etBO`E% z_o<ATqrpv9gG}>?zz?y|o%YB9AK-{lr-P*S8Vf*r$ER86p5ENUxj|fvWE`<y-<AUT zV7YtEguQe1?%%pzSnMp9D}tz?G(L{a>rT989PT{fQ72nf(*jsW1-gqlwLc0lC9*}Q zC%^k+$h3vJ7pI0`+6DYmES0^M&b+U6`NV|VnPn<O93cl?1@EkaA(jR1hZRA9l0Rm8 zVH_(bBFf|UWB+tk1c{L^Lk%nHfuR$CS#*Dj6AGT3csHhV<M1ZKoIBn;h_>y9u;4?h z5Z%^%fPqn~i%8zxYPU`PCEqlkG=_T0{+Rym@lHu63EEbT21JGY_ouaEuKeq5u@}zJ z?BeK5dvEZd&&Eebxr}o^aii;s++jHrbayiGB=7Balqevrmu95+I8-@(Vm1d0$=i@K z>48(MyHZV~s|lA{POqp<jEnZ}UFiJyFuY58S*G?5OKORzQ)}=x10^6m5Zo4xoFgAD zdaPR>^_1v{s58-YIFDni8=4H(3{ldAz$M3aWrR|o!Dfo3iz81%WK|M0TerK5#5JQ< zm-6i==A!{D_+OW<biM4k$64NJkTpJ7@)~$$VpSGTn=_7XTCz`9LqA}?==h7yKAh4q zC)1uaBdP7Ql>^UfCco&M1-_ag5CdL#Q}L1j`W*L2M(J+G3e3$XQz^I|4AmT?b}IRW zE+^5=xXYd&x~zW{2OaO7=<Uz4zdSk<4ha@=(6}&W@+J?Y%Rl5&Rur)!5j|9T=({tT ztnw8vJuHI#S8tG!^=Sk#60(`=1)v{0(PG~12SU~*diYn8VfxV-9oex#HAsd{Cq^#P zNvD+~dAK30STJ#3@&28USXUy`@1Wn<R-kqrCpD}BJ0O>9&xgp|;hh24M6EmiQ(&6+ z)g=9u)KOul4pF_jK>$IUXuKrVYY<tJ<+pA7V+hmBdhI4Nd?>l=;O0k0b&M4BDnp3g zF_#u}f|w)Z1^t8tOweK@Fh)kh2|}WTP(9<#(T=%QdY3vEls1neP}Teuj$tHxt!9@a zW6K<_&1j?gnd!ze!Y6yk)jL`ZGdc+r?o8psuTGgj)bz~B;M+hYPV5rw(s-c6oxV#l z+PmNdj4aHZogA@>ljatc`aZ*6!A5c(HRL-U9q9rbZYAlBwMIvmjRhZBqhm5@{fs6< zp5Zb%|8)jSik#e&YYtWJ9A<}=n5gT$Xj);SnMYwwk9)y5T$F9W70hw?daBfRmJj$f z#Q3(tyTT`@C0bN5-lfodd?7KC&aF9AOMjOh5_QF%#`G?bGLQ{J#@jS9vZ@+L#RSPN zM`4mr=~S?%J0@xGY@?#ZPn;LtUe@=)bt}V9{9R3(SKs&Qj8R;M)!ia)*Nz{`(P@zn z9{{6@rpeEa?<@!oozw+$DTwoh)1-aKo-yByvP;xc7%i9ey{~}JVtkj%d0M_)ZsH0~ zh%>Nt$6VKX+IpCvHZWN8KR+E9yKShVgIO=Nngyp<iXPpCpb{F9T1siVw?PM4nyn(r zqxtHa1Dsi2Ii48vGQ9b|VVQI$nrq1%KX|V9bUdn|o>}Y}&7^Z_Pr1svl?KXj$hg)T z+4bAdvC9ENoofZa*sf6`@xHg^Fj<JR1T(RJmfb8D3^j(5Fm|TLRmfE&V|EZRdGjxh z@R1Y>>qRG~?n3KT&fpvH+Nq?DeXwR9iIsB$Wq}3WgP@7cYd@Ffb<}_k9iJ{*vUorq z5ovBzz`Tj~7DM<+7%$+_qj#^#m%K<7*igDl2k-3j2-Yw-ht-h%T>9`wO>u6%=<YQ` zbDmq_K_m8#=q&s(WN5a}x6j&wRKr9)6G>9EW{WY(RzcdYX2IzC(RGQ8X;TnyozgS< z{nzvpK_r8IAq0}LL}+e!)JL;yELy*+;-$34y&;~EKVQlh_^QfUU8=udEoV#MacEyo z?993oGq7aQ<AB-{&3|5An@LEa%w&kys#5_I)u2{1>iUC9Ta;Pz8+>w~MFn8}H2{|u zp^G5jE>BWQwe>MwO*P9n3+o4H$HPZ3F3T~D$;i-dxIFg9g<jH=Yp%9XzdCsX&D$wB zV_d8EkMOy;Q*484VYQ-nuGF{k)TLH=>%tV(4|((l911bbswisXp-YzDkZQ1JE(LPD z;B92xO8T6DS&4mrVb7vrgQ>#mdl?CoiOEVatlwXz6I5*7HHz`m8wU=&(}btGiUws9 z8^wJhnz?MxJ1|H}eBhe%!~$Eq*Drztst94D5%AJNf_|A>Nfce?C9AtRIHCEKlQ$J^ z4|sRYN2zm;X3#^qr30>Rz!(C63{Li652$oavyy_y<3d^+I^~$bUnchhGzCD-V+Ud} za_EmCqgL75b`zGSG}=^mmp|{AvCZEZ&R7B{n+W3Uo)ZWckGw>?uW59cELhy7XAGes zD*LKs!aho+nlG?3X}7R87h$9DyN}hg_={=Pmmx4ba?qc;kS)H;W5dT;_#2dRMqcXX z<Zz9SYA_w3CN{(`olTU{%2(!VCO9E<ojCCn=RpMebFOZn&g)Fmh7&&LejiR|Q*cqn z_Mf+wJX`VvU9S5x6z`T2OKy+5nAM+?yml383op<e>2}F;rZy`CBxd%BwyW7STK#-f z(RI_UV_!iVT*ag_how#c;dv7gF#UTK;KziEoQEvCOP9T*+6z?L@$rYcfgE_pKS+Zd zcCRl$ZnvD{ZtIq9TqIt}AqW1E{q$w?6H_^fog2ITC^{em3e|AWv8mprq-kP@v=zK- zaTPRa`aW^|jgGwQk0FA&7@iotVgc-;RW&@zEoreMSi&`04&B7OPvj>*_oRxBXI)@z z<Ek62@Z1SFx+I!TZ0?nrLH#y+;=1CWL2}?Ern2Ais>}d3t|k1)z5(6fC&CAVJgsx{ zut`XtR;Y*3fUeUv!9g>q%nMHUPA@lTk1mc;(=!t-HMW`5Z<AeDX11(|h&hoJc?ix8 z3n_yAecRTh)LZ20qZuQ-ZH@F$#3injpQMeKwmjbo$<Xk+$??Y5@`Ts>=j*n9a8Wwp zYH&!cRr|j~@tw~QiQFZ)OLesmZ@hTYY=7)3>+O9KY?ZZ!_UA?06NSs(Q*AgEm(#L1 zW)|gkBHaPi&E@JKIj--0j)bm8V4EKn{nZKr7`mc*hN|PM>w<r~M`@H$a2-`xe^t5r zEh3TbZuY8r;ZD4|_a%NNpQS6A$>FaeoIxQM-oCFLJh!LSq0Y@`y$VHfx7gTFJ}zr( zk4?Oh5pZu`%rrIY^dc*NS6ik<;_O>d;RBNDk7>7%LRvz0>B0*3q`r!kgJIp1b4ats zLs_p^K?ArjOy88@VSk8QMD5ct?ebvCOPaAqH?5-W!%9e=C%Dez=iF<c_kEp)O!@5> zn_sUojV#nl&be^{q}XC=b<)!y>$B>7^Qbvq=oOk<mCUjM>Dmx^q)s!m7YDNr_b0Y) zPv}NyxLmEws=W&Ayu>EJGGlaM1K~Z5y6>4i&7+??pwPFL+8WnQQzOY2$20HSBxJ6N zo*mJJU5(Xo2Dh#z=~bQJdA(TVgnHzYE=FlvIBMd;1dM3v4HS%AgNO60mWArN$HL<) z8Y_<rj`@*T0iJjnX(bjqeYPGs?c)sjn3j#Ibw{{OX>ZieN2F&4e7a7xko0Jx+FO+? zCAmer?i&_Q6&q5)_d6LJz9KrMaejlBbS)S`0gIuW4}Es)QR#$ZsPMf+aF`a7KBsYg zziCw|oMnpcB*81!Wj55&R~A{jBYRWHTvN}smGdD8?N<M<{De6;*rs+)c=}4NGPBKe z(u9D1Oq>PT&C~0OJH(@Bsc?vx8Ql5|QA4pB!8D|}I7jK_?vnR%oD-HDJC_!7l{9M0 zCzx;~J$MBTp|2*m;+g*)KU-L+xCV1LhSTA%@Dlbz<hNmED;1e7y8a7%JUv(zz@k^; zQ9dp_pkd79;`iNZkl**xTgqB_sH|n(`u>DVPtgeLwdcg#gZ9EDgjF!DMrY8nJrXLg zipZ+m`H0lBY30&b41P2snMjytin>&6zKm*^>N{k24?`K^as@&_YLPo(|EPRp3>{(8 zgf;iAa;#n?(ghr!idFZFOTrV{ORw+_rie2)2dU7@i&>`jRfwnPyk-x(_BODw_L!&v zB3j;ju)8ywaVWg^)<W1Q%z+Dypk!7tD3tYbd7<WRk@q&(w4l5q#TavW+t4i-m(?ld zC=;B)z8yo}GCCI7UeYLm;zVj5n9=T70$%{+kvxV3tbO>MWjdOq(1e*jz!3;hd0)lu zGMHiOF|o4F;e$JwVA@%`8KO?38}Kuoo}E*h(;ajIdf+L+Ltt#7YwIRVXFZvOR3DbK zY*<dyI&s(3AvW)w52icjgMdWQKt2tZDfm*dGEtY)YlpD0%lI=V-gQroX#o+zQ(oV{ zNlm)dBpUOk`bBx)AE^TXW4XkuMd@8Lr`;nsg}k_NkmocQujyON99D-?IxgarSmM@d z{r6?;p^x~O(CM_)#u;=@yQ+p|L@y|J!o^-ob44<}Y3BwYWe0I|Bm^Cy=mN1y5Ik33 zKtEuG%SbgCBPnVf4ljs!P;A1=6mb40I0?h;PR4j-dZ8u~jg#F;u#N=D9A=lRflA^5 zOS(>gY!*S4;9hD1*+?wO&a~7_`!=N^kUpa~2n>b1_18dmT4;P+wB$}ryw4bS4IS2x z(DP{Nl7Dn&i*y+Jp76M-81oi*JTwu6)R6Y_j5GRCK~NIB^0-zhHm6m(GN*mGa|2Bb zVT=;7WNE7OPoY+6IG^s}D{iNlX7Ro1&#oS91yvF))68JktW&TS`V9*Qnv5xpHe_D1 z6Js-acdJDS7M`ees{u~Zt$K63$92RQ4!Zz7VaZRLfm2ahl!VX;?b3m=BvGpLBJ+4t zy^b<YG01QzJGK_9`8dZ0r@2Itqs|<faK}(hjUn=(JvU5lZtoVDJy-KA@ZVKt*wg7V zmZfV{2}=4b?Ts0FKgPf8X)<b*yBNDPWRF)`s_6tC0Pu@+p4y>(o-prE{LgUhN2M%^ zHMm1_`}CYgCeG23v_^abL?;jydzj$e$a*!44&Z^YtABQbSv#M4r;n)Dc+V02&V6~6 zl07b-aZvKZhkyiN2%(|LGYMjb`mhiuK_JYDF@yBMbZA{97&HAJQK(b~FcbJ4A8;0B z5`wdj4<q3jB#r5wIE58J<(X;UAijBzv&5;dvyT+-Z`w|MrBT-?dVNgtmJW)Y1}RZ4 z4jDe8kyJhziB!i+ILXwI2Zwn%#KXsHeom8K8Z6Ctd9gC9$_VrgTrH0f7vC9ToS|wp z5tL}?JUKSjs+P@w2-S63rRjtrrG}4>Xi+by7`lq;(NECj31&p4=0Zl0uZP>S)~z3! z8dM5GV!*B5VVi{N#&<^0*PM4N!sK0U&M-TUskS4CNVzkwXH~#8wQ@9ye2A*!YaiDw zh?{;Q(M~M1HHt;Z;ghzM$S<ds5+QWhf>-UF5@FEZjR|Hk=tNQyCZd}#NAat)d4~Kr zEHfy<;?}>gQ}WaQNw(w;cP6R(x3E{iqVEYp*Sw4wH?pK$G6OvLbzk2r@G{0yvJ(;_ zn^9rWvo|~9THbsJ>JF_BaokwyHEtPRiPAO>7F&Eoz8=*R)cO8Z%}iW|b!v=VMa9G| zN;4;awr#@xv9X-?#DbYHb{5h@VKE_L^Ah)SFOfdj0iNPz$#Fh?gg7R6_=Gk=ZFu`V zX0Nb1(nW@9A|1AgR@j^yE~n`@QbAB=xjBY4=mIAoSBQkCMix{;_{b~^x$&Mr*9Sjm z(zGgh4E82UgQod3J)g+3F(05<I1MtU%l3jdICB#>g|gxL?uXw0NK0={tgM<qpA1c- zel6)96=@r16nK>#e+7B=-ot9IEKc8<-a8+*U9I5J`35M98q;Z-y2j6;h~1w3p+;o4 zt9NTf>?Jr|*nHp86s*(k8Do(T2gYtWObsa(oo!MBL^dm|f-51^^bK;2;nPVBf)n2d zjI-<InCDf=K?XKL{X%oyNg=!b(^`JS?fXxh#-3=iW*KO`022Dv9wHH>9Ov|}#q0El z0Oc8tHPR(GCCRkmb6wjwPf-mZtDl9vl1W_p2ENC<c}V%xW$dpCo-n&GKsXS>ja(9L zlz=~))k@=R`Z?moH5c~ZzR$V@rx*g<mTm1IbF2Zmc#Cd2cgp{c3p=f%1a^~2XHwNX zCA!O%A*bF}I;M!MK%6!0?EyE^J#g`&&AVGYQ?0B|g^RND{u%82L^XG{M$5^2U9b{& zXaALkB8D$(%3+IolVS>lqK$_u?lN`fV#t@Y<TxMsErF!6sL@nun`Ev%sTcS|s4{Q! zBUZ9!T}2pHA%i0G;h5}r*@8ye%LEa1`J2T{x$8C)L2Vx64sDb4^h}YecJ3IVa;?Eh z;PO9SNEIrhw=NpAZc>YN!h7rX^-Ha-c@`02SRrc{?ToT<6rz1*_wru@OA2uD&*4LP zTn_9Ku?%=2sJ!+xKQNb3omsI0W-u~qg3IbKiP2XP&6n3CY7Xz$On0pYnJe)6X$g=i zr67&DMb&sB!CMs>>bG8U>^;@*dBO<?WYJak%4m??O*+mS)~;rf1YHQdR%_&;_Amj9 z8A2D$Xkt%$8Qy$obMn$S!P1sG1kz_gBMV;1td2xFh80<1LYhoAlP_P@P8EpvR8@EB zkZVkBxT<RY{BgIA*HxzlF@J$;S6t7)`}M~^>5=laYUxAzGuK!g1@D$*Y!rrKA|UUU zs2I9TNC%>bmX%s=v~04G0z%|Uw^E#zd)dmgaiWj~EiKH&!g$BDH+H}+#s7eAr<Vbb zD{=7&^et+tis%0&F{NHL9w4YT+^{l-K9g`S31zPJ;^Jld?SPVPULrbhb9MvJ2!G0L zC`4WA+9$z{ih;S8F>~%B1Ee}Ok-c?ZR)JwgSDxF6#E<@=<Gdk&Op&vKRylce<*cNA zNI%5xVUxU7t1u-f24h6sf$iqbzeFk#(oYv!QARs9n(g=15|hy~(QOx^R@j@IUYvIB z=q8ej@}vc2(uoV55YWJ_U3Dvledq1&DG8W7@264a{Z}N0X8HcPacy#OiH@w3b;UHP zi>WVWXkMIbW_GUN;~tx&du?@xboi>8bBKQgbkcmG@2%N-cS4xf;qM52){xSt%RHGD zLo%H^=8D(^g23ZT_?%T1cj=k=@jsZ#hS7W#o*?Jfmmd}RI#3v~czaUr*n(k<_M?He z7IrKO1%%{Ux(_<iCrj><?DNs`d5l#JDNP2LpK*hw>+k#!CNvUs#mZXLV>#7EzeyUZ z>xI&q(#o2F*>XtGX3JFRft7EZJ<=5;pRb9fB_T+b1j9h(q4WUNMFgUgpM9jw$GFac z@V^_si2YXL@CqF#f(eQS%R|Hxu`rf=@vZ7`E$7$ALSx^eQLfP}%ctdJi63)4QL+Hm z)dT<@y=id3rgGPj#<b;%+EX#Ps$A??geBL|q@dI9UjO)|krl1jL%6s3?|Xv2MhTDE z0J=TU_~!Sdc%9-n|3|#tiRm5WBNWIb;Gh-Fmmb{Mv*fC@KZRa8Bsi&chvyQ2y4WqG zJ~I$3WjXEHuhOkl`NG#D6d0KdINUE!us6{m8G#l^s_p8Xi>s|umEUqeiXsX2ZhF4q z=d+d8`f9fZf;@HA{%d|G%c)iSS!^OJEzef;<)96q6+kzFAbf4X`In!*aJ3eg3tB`P zL61#DEbMBZap!%g;<FQV*{{#-9<R<q9{sB(=oeETfbgZ1u9M|pKW-3!`x8Vg_22ie z)GWijLvc;qR@^XwcJ?O?ee#ECAnCCTskYNkCg<<io-{OhX_PVMJHtZlF?cW#8R4>U z-5Ft5uQ~qmc>+=!aTW6nm(K*K8f$<Rp(gn`i3Wicrf{pb6*muh*p<6xzWy@(RpH_# zNJt6)@%s0&B{KuhD8{SCtFCjpAsb;-sCCIzope0i!x6Xe)U`1ObG*_R5Zhh3>t$&D z$RETWdv~L6vvuq9wbV{0I39Iysj@2bts<3ebZh2WJ=-Qv?u>D_p-6Z4F}RsnwRzp% zIgpU*;V2q4lScSy#uU;rp`a1YF<;+#e_WR9Rh0j399(Qcg*gA26`=UgMn%k9+s_9l z6;AnN^!XTL{qUx5onM1hsGy@~sKyU>TE@>Hf=4Qo7IZF+Goj_{4=Yo_)zqO3I5PUV zG!KE)jE7lZZ&P&DZwQ88QjYsa;v#Kr9?QlU#n@ys<p><p<Dxc`z+ygaez6eQ*PKqW zaxEcEKDcg{vKKR4rQ$fZtK&@IqRdITUOm!5hENI#xtl`Vzoxu9Pn^lcf+)dA)zs1l zHdhm_z<!?L2d({+0(>}?*d!?|+AZ1YP6{{igh|rFDw1fl2^syGokv3OQxi1;rzmO) z&8k-PPf?<u&x<J1$v6Q}$otbc>NEic76tK#q8THe_kC*v#&Kup5mom#SNP>I5t?r3 z!2WC99=R>+c4=)2ySVr<m(I|Q&yq_u&13<#3997dPgiSjy@RTSDkG-9{bWweaWvEZ zm9onDRix@e8^dTK;g8DJwQ(jdzScNHX>A~Y%f*{U=NmMj+fXOlh!~7}w;^IL1@MN1 z!N+BavacYa=oNjRR#geH-{QwPwk65yeIpf{wO$3*FE;tg+Yjk~KUtzmz*I;OsKiW9 zdz&&_ZQ+yIbCQZz)G;YQX}!S|FjYgw;rp+<b4Sn@L?Ib-_W<)-#84iPze`VbnY$a% zzQGF266PRoKLcY@>VFsihmF2mEE~5TDp21UX3xCCb&6h&j!JFX9t$;u2xM2Z<~P^v zqgYB@#RW?z<%j>h_%{b88#WL!W|QviWzVS^Dxep@9qI=b&@ht^rCWZ&C9Qwg`}`3a z8EeP5Lj_~5n2<enZkNPNWB)4Q$=|V^+WH84jDME44Elmd`I|5na5Ec2?muU<sA|p4 zX5o@ZuT?8_+q`Q>>>91mTS8VkD5NO1UyJNLvnVb|(pa3m=e<o9(b7UJn`z%X{Kvk7 zLhT{G#R%jEPm_}$`;S)YkA(z^MBQo#N1SI1opi+DF0p$#&px|qCN0|5*x<%b7+*`A zmLMvrD32WXh6;B<M+xZpMbzsbsnH%lBek~MKYxppp37wToQ3q2KtOK|VChc)!sNSG zoG9@@@Nk7#Z6avu2s+5en~LsF5hqYuT<$z*M<6x-fkfkGjlyuO4q@hA1Kr^+wnca8 zsdx8lTJNwH=wj;1)Cjo%Hs(gcKVFM$Nl4VKjWQlm=ReD`>v3TeukLytg$>_LPOq(} z>1GuVOr(EX;z0z?W1b=MMZrH4E5IHXQ5E{7jsuCD0{OAazYrxQGb3?9VQg7=mhe>S zLZTX%qrMiGK}5V{ABnx|SV5IBCfz?mC9!qA>FjRLr0{d-1(jPkh&}Sw25*<sEn6o} zZ04hd<I*q2nB0h}q106P4_N|emFIe8Nj%*t?EzDp($S%i`q8k3rOCrGV=Ko!48fAI z()JQjJjfzwsYh?qV`qs`cUwXb(W2QR!>V#Q;r5Vj0ex^YncX|@*Iw7kd4Qq3SO-g< zMu%oL-C^heRR0=cvj|=-+!N_{qgXbP097cG9ysKa>z*EfLnS}dl41_}GLqh!t4!3Y z1_wk;1E45!Zs5kDwxN+t=WeeH`Tj0VWBQyM)@rS)Uz#Zz^w?F2VA>K+G1TEL;pSeg zs=LF*)xj=c^p|+_zIxnWAV=|*BF2oW)up{lRNy*i$S%clphux({VjC8C1W;w3KKa8 zPz-BtUgNGgK|(x5r5Au6AXqFKkZis$c^38?LXOXiCXM8(s0&OvV=!5#d?cn^)~(T@ zf`7q)84cn@${_*HiDB1n_Bo3=XZDt9Vig7O3?k(Js_q=2PWJMIEy>EjRwWT&oTvsc z7UniQam+V0fkh!@aUCu4K4hFD<I{;;EXRu|o?5!-{&SS3TpGa0%%Jmni-8Otb{9l4 z(RdbPm7({f#c=uUnkjKSVm4bY3Hrq2k88Zk7_~}t?c-5BFY-86KAp3-j$Ob*iIkMP zYZE6#o`YUGk{2#v_t1|t%2iykKpD;U+x%AO(_M%24JlB3`PW34yUXd1?}1>3zYelR zm5mNg`<$SFJ<&MNM<tM`k%{_#I@z9?&kN6>G-4BSG?1Rg01@}?SS+6vjFD;L<fV2p zt-8tK<}W7BK!|sgM%<sD9Oka|@uHZ=Q`UHr5QyH?q`StaP>3}d-AQ7dzx;Sd3EjwE z$_(cbedX>4=Qxjx<AbH{lQRads4g>g1*JrB@`2}qCaW-JqpUVz5`W&i=NrM_;APmV zvp=ms|HS<f6VsN}a0;s-+JwnR27m&W#Ps}&{1&z{H;?L_EzF2+Q4DCDlZS$Pm=GFT z*as@xulbMS7D7d<Z-st=f3YaYBG~GaL#~|d(RvwYXIcp3;F)08dz3v@K;96yufbC0 z0g0zr{LmE9YXw|@7Y1|xx^Ooh>juV~0wy`rywYzC=ZQ`WVB?q?_W1Nzt`Q;;IeH6W z`rwbdZp2muA+;2ujIpVJOF~y&*gbiX>M<S3&!14KLYT0Qy4^DiE@>u|X%_3QTN7Ev zyp(crcLFM$Csx`$#IKx4l?UQqz!jxM-J}~Sd_>%S7&9l;9sK;m?mX9jKkxrY)zxT# zqa~KY@6Ub1v^t>Q$O<Jb)R3S7nie9Irj=F%Ki#o3wzurxD<as?+VMX_j4`?V^>BPV zQ~i1$g~ZdNU#XxPn>O<$9SddX^`@p$!BQ<@A7an54iS~KU$VDGpOYSPMkdJz&(<Ck z*|=fu2)<$WX6ekP-c?=BUmkYIr8>`W+qf3>UnX2Z7S4jH3GqIKo`u<pfA#yu$ELa! znnaKX!L!1ndoyk7x5_NX(>m3S1gFXFd9>xRSe^cNGkOAT-G#m)P>aGG`Fc{@{M6yS z9)lH~<Ag6)y=L7|db0A?Fx5}dD*|wXECBv=DJtfNwHRU~;m}#TAovRYcjX;5`2#*m zn4yDRUkx=-KaFZoFNAFxs($d|N7`Fs9sog7{B9QcV?*hww}Y-YLfmBtsmZ>qs*F5G z@}J&;P$~9EXY#(!=#XEJeu>yc9tb=t9FwMyGZcjDZ+2}2fs-d3vU!6R&R$({m?+f} zRyAz9c*T$_I$#uSu3(i5W0<9Rs!xOb*tf<Bl%iC+wHj-<XNt$!3zVUrk@!>9OJ(1P zW<z(YJUj0@j~5Aqgh~alErtTI20GJxbw_o6kNykix4m^1Lc6tEfVZ{T^CgdgwKMpp zxup~#q#%q_Sbbk>FfLXSCxafw6@>~4_hf7QQi8@7X@!xK1wViIC0Ls<IGW!4n0_}z zOz6b+BIBLKwj%d>Vq-~o0utaD6IN9$|7H5w-*nRLQKEBV@nxgOi^S6SO!SjHrQ}@z zzqTw(R%_mOQ*=iYPV#4CH2+iSwLNdyjr_&6k)lh44n$Ce73+4FwdmGPVKrLF$1>hN z)Dl)(5rl$=g|=mlW~guqBBv3IuciNX9g1JoYG3=tj-gV=beLgmW@%E&ixoi|#>v0b zq+)2+$j*Z7D+`C_Uz-!hMvmF92hac-dp0|0m6*3myQcKsh#)nxnZMLXI?)iFyNo;u z$${(W9%XOFfie3rbApguSJ5}e$-z(ziT<1}>gjL;sM}hgyTBiz_PU&k4sVlOtL~qC zNp&-*cM998_QGi|4)gMKm8&p}X5-J7^Nyxh&s>tCTrV#s4C=*^@xU)roiioQ);^u8 zTVJx|!ocWgf#__Qde<0B4&vp>ZDC#7SMc$XftqvvFuqnsH1tu{T72~bZ@hSwqbd5L znLeQXIosa@ECY+SwyU4v+h*=1dp)f69nr+1NJ=ZanQ?69#ZBs)oe@G>q+O<z?4w-K zk@|DBM@=WQ7M;qHOK^EuoONz(_LXiQv&lULs8If9&-c+;e4M^FPMBnUzJfp?pHj&I zi`Yl64jidsdee6zIjr!bxWvQtp?%2@-d$am>_hE$FUv*O;!Qw7x~!x;K_a3HT8V|l z)m``Z>B|QE_X&H8kH5#<z}0-0*^z}=H;&Rd&1$b5Q|MY3qaHihva{v`Y@MFm^a{r^ zVy8e83~h2ctg!}gDqpaB{mmfb8q><lC%qrcm#htrx2mp*W5Yt$d?myrKk*AbWFMti z&Q1e;u~l)DvAwRS23w;{JCtd$REDB*7AGZX=?^H`Sh+r#K;Q&EjdLWqr=RSqQFi6^ zsJ^(7u2bC%u9@#quN(2uwjgT|{biCvj*;70r%ye4Oppt{u3-^p{=6yW!>&+(#^ZKA z-JN>R*U6}Z4DO_fCNurrHrOxTMK1<kb$Z{J8;K!S@_vv<TmRPS%)iMvlJwS?(IKYF z>ZFwiLIOz5TI<xp-!x4WBMs-vu@>;~7pI-W(%;rw(ZYg^yilc{*q7DsfuAkf<GPB4 z!T+Z-UHiL6IkG}Q9+2G6%|#q&q6X*GrK$)i=zUn_9dcCfiUVuX`gJY3D^E7)aQCbb z;C8g>Q{^8+LQVjgiq@wtsa$9JC+9R(fzwu8c=Jx$I+9yF{X~m$%jW;Cu3vUZLY|Q( z%7Rviq5DV$a)+iNmN|z`uRd__SM9a9pN`B)HE&q^{<||BH?9q%&rhhonVmYqD_uJf z85ors*Hy+M`5hs5*q!F9O@rq~v+?|!wVf4DDbweo3US45V@^Sc_hsec)Z?A>A_hx1 zLkreLsg|3E+Fu)W>y6A4UBk|-(w23G?{iE_89T4_*4XS9&&4;}GY)lYiBpwp55`SB zuyftJrn|Y;uln|bJZb2*12YW{X3Tt7<FqRQehGI$O$YZjxw2D7zWkK;z@BAZ2Y>Tc zA5vY{1{W|PWpU5w9Miz!T9v~=glfF&%6{W#X>mbAPh3TB2T{6vDm@eWO{RIKb0aNY za27?0M-^p^V%eG9#M_RJSU!H(vpkW&WY*sCWp<Ty=Hv4DQ^V}jotl~tk=OTcWJ`Ch zow?cZ#J#<7=O15jSnHG1HzKG6-vQ7l>+SVXHXm#2`dE=Nmo(`~m#rP`Jk{mW5M9F0 zY2NV*Hf#M_G9NL^q4V+no;cvKtSq7TnKyR8S?#WpR<ru6`x5V{4$SW!@NXXRqNzUZ zR<$%uYmaL!lT*)Ugubgirj|cbCa`xIud$zdU(iD$Ha<1vLY^%cUt4OEg>ShZ$@nz` zU*s1$_OIvQFA^WRe}SA8JWsv~9R0BZ`#E8IJ*9p4y$T<zvl0Y+Fg}R(mK<?8rsur; zAYNI|1*%<Z&PdjU>XnQx^?Y(uW$*NmQgYg9r>#=Ms7r~J-=8|B9W1ft%d}_iZ5a!! zoUvcKm;S5#85uR)QpUUv8XK8TIOWQ4XdQ>we6G0u$~M*Ay<4=`KKaS|dL}XL*9+3e z#-%QnnsuS}i0K`ddof6T=lJFRqqGD0PlndHfvasZtP~>&d)cs=liTgma{U9t8_WJX zX6j3Gc$^B0TsAo9t6FaPN<V(pK-R9mW++_^S-i8K2tgO_v|bH9q#c}R_m(|JP{TM7 z+0mLIhOxecaZ`D=PhS(H$0^?F@Wr1!KUgC_rT!@l3+D|>!VT*z^~z7E0M<>@UXy+b z`_&;UZ_`<{RBGjrJTVQ}ec7A0w&qX)@F~J_FJs+Y`o7myE~kBR#|YK(KZXo(moJZ~ zAx5_rW{oA<DdtGaEkh=?%1^$x<2ilP^}kAYvi|?Iz8boSOp)2pa6Z!X19Ox{=7M?( z0?L-eh|3>1{8R2*9Wanp@O58;BhxB1t<?^^cks(2(?$=h&nq{n8h&8G-u)z?&%^!p zHTuOT98(fC42|QUhZ6BKbcDdzt>-dN5B+GCo8M|A13Xo%?@Jn3uJrq3$Y`H8QfiuB zo=W+n|IK_ve>URB##`@gPbOMi6F>X&O6S?tvS&b(QFWL1fI9O?R^{4^&_&%9=`%W! zJ40F3#6*TVf}PKQ<&w^Ys;V50Up6;5)AAG#rj1@w<>8z%XEDzv+BaFAALf2f^X!X0 zX(Lnp4fF)5POwWowjkL{j=4rkB8C%0#w?J|Y#dl*C|3@A`$(xz_h`rXRdPUxd1%_G zrW4Lt>2q48zk9chA{>}zj{TJhxqtm*NPcR`gu60K7X@S1+5PYF{<6Kc9-t7vc4IxM zy{I2+JK9U+hf*hG1UzaQxrq4rjkNrf#k{cW^uf=k`QwB8bA4KJS>M72o?rpjT6FpI zQqvUmx@4~e`4(MbHUW2x?!3b9Ahz1ac>yNZk%Rj`JT=n!fA+@X179Apx1B8Po84yS zA@0`n=x_XI_c?{<7-g~p-fgw?Q=8+Zm>)J+-%q~6MiNTow(Xf0r4{D%8Qu<Mn%eb( zo}Fv*J#{eaX58ug1~22xZCz4j=wl%%1FL#IeEF~63|Q~dX4|h<XDT?P3jE@N&-7&m zhZ)+tshCG1x6oG=H5plZLY;5>^%RH37s)*fsv3V@`}w;X)p|8-T*m<3dTr*OgK5J= z$MDR8{hDF9<hR#U5@+2HYh2q;jP4wtdcf-nv=TAw-mOk82v2X<jl;q#IE919lyd|H zuv_?B6Eb*4dta)DNq#Rn4V{=|9pPYqBa6@uaeBZG3O~j0Q=?wd_dXd>{~DI8bA7FE zS>@7?3n2IBkXHiP=$-Z?FViaU8<8HMU7$iwy4!g$U4CduS;Dx>Cqr9QIW6y3zm43- z{d-rlpVQks^pwSCFz%aJ5?rO}+V`m(`HwLeykXNPb4-3Zm{8<CBZ09%O+ZmlY%zPf z$XR(DX^#5^uCF{;_~B7g`kPU@_&o!+@N|`nf3At+D}E>DhYmb}orCFVx(S>DZ?A79 zl1L{D?==5z_1W=paJ<d;2CT6e^)uS@O)Cu)gn}3c&4p(2;Foi?pIu<gR_(yg0SY>T zV+!7@_+!Y!5r~<_&M?VKa0|N1;rqK)aWq=LEfq8s;Rk2d@phFjQ+-x>p~FE0_Q~Y7 zRRc$epq2V>mSte{HZ<X?)ESt%R(}Sd#{c!+r0cz+RyZv6o;PYfc7D}4dRfcLJyba3 zrNMa8<6n1XT!ySdf&?8%{7ZpDN5XmSXq$0Q|M~aYc$L$8>?F`uSJUIsG&4mw-qk+* zMa$<u_-kesenIZ;iFc^)ARUOfZdC`dVP&2n+DsMti&aglo;2v5spnzeod%VVUb}%D zm-ApgDaVun!31~y-&pVTIW&LQZkB?C3we?ISF04=<9Z$|APG$CcFYx>r<%Zk<-c1W zIaT(nCyYk?BHa*pP-9WkAtTfWz8%=K<95Z#up57Cw0ieETYxloa6`~Pd@KM*lk$y$ zJ@ZT*!J`?-#*0Y4wZTc9F?X}CL!r`+X`o$10ly@yNvjln&zY)AWihW>8oTeWJso7~ z`IHsn*5RF*mD~#a>?S{+^LwOXD2w^bG3X-gjiz%slJmoiH&5J2bv=0CI%s&S9+25E zoKxod8qLZe;gRi4OAhR@fAZ}}d0fgrsxq_#uf)>XY3+V7Qs%G=Zyeb1?^&1^o&De? zhzDMY()$*#4K(##b-{18Sc9H%yd;ANjsmMX4qmL6T+UsgljN5rf4V9h4zvg+*T)WI zi`wt&z;L30OPEI9woKbs*89w>$4ay0iDMq~K=E|~4xJb-;9}jrFPi9mzeFbUbia_6 zub5AL<SAwgCHeHtth>@3R6;{2$TBUkKR4K?4cIK_M$BXQO<}0}8So;x@j~BIKJon# zP`DoKY3fmPX15+S=oGT7QTu%t-4`_7F-aP)QKpOWYb3LM(8PZ&%sQK6``IzhNK4Zz zyYr*e@E_7UEbD(tdjhbQ^W;ip1O0LLh=8Qt_~QJm%AVvemVtkEPZ3)=&TY|ZG-yI9 z?KzF|t0(THAVe{X2?f<U&K}c=-BBqL`Id2%`-LVi{l(|M_jx5JYH#{I>?(#f<?nb( z6c5o#FwgC4DuO4+M9=b)dNKwQ=L(COtvLKHJa5iT`@iI?y>p!Yd-%8Q_-Qf4`C?A} z6DKl;%U1-SN4jfC&AwwzjlB}|H3a#$Zn_P?jZ3$=OGh0DlvvV<DH$3c+l^{-Yks2o zZR5N1n{AV~Mw>^KdG{0-2+=<Gidc_hW3%QaIw2SwqA5CIt;IRDdsL{R%P()en=`#^ z80&dcM~KHa#z|P~5M{^{eKOtQIzpCoJn$vzf6co2ZOEJ(hHA0nUhh4L7Q+sK?ab&s zl0|gU=D9tVEFt%v>E5{X@5Y~JG+s`t!1~CZDH^*!-(G*~%C|w~L9UNQQ`vq~d}SyG zxlcx)t-qt&FAuwPfbwPTQLBh)m(hi{&y5+fqJ}_(>~%X3sGZX*Kk4=&^XQ-$h!tCp zCTjT)(4)1QZ+~R^e;MUvNcpl|D;n0~utd=)K0b13|FX~ZH^2N3#lSUXy5vVcO|()3 zEotVY>(axiuX**_w@i;YiPvGQXG9nu=KbGOQm*Sn5~w4#$}GJmkjX(`l*zxW9geKs zGc<y&5s5wpMMd+I`owj%(ee|%{|RF6p8G*!p%7c0AL<9fPfew$oB4EyU;`LN1Z$mN zEotc4lJYMVhyJP+r{bJ<je{DMRgpW}sJv2$aBS(tJhqNvWmcucE;}~y=qLK6%^m~c zOUFCHrQWHhXdbre?-*FFebxE;8x0#``AH}hT%<t!9odOx=K?olz&ZHCKAaPr%vl$q z2ma9-L+;oUd!lFgI71KS1J7fOM8kXvAK&zn=>g~5B!}hB??pE-ydx)|$pExmsK4R& zFIqmc4okmlNR=A1mwdAAL|aov*Pu?GQ&Wkyi`$sjl#vHW-EYtaS>ZxWqvJidu4{5| z%Vz1m)CDM3C%}*?R@GG~$a8k7J`0{e2W;-*Ms5?nVFj_mdA`c1^D`$4NdU1-1N|S? znj!vsZR=@#w@nNoIOh<@PT)VTlvG=Kd=}`-4VtOTIGY<CQPNC}>U8MJa@d^gQDan2 z0(T9bC`b4Y>+&(EQ3YshPMH+Vk3LLz=4r1{I=o19qW5|J#jdCO11HC%=U`AWs-f+W z#m9NXu|_m%{<E@YgAYEy^*wm@l7sJohS{W=c6{K5zT6u0H6%Z$c|2X|{;mz<^iT=y zw915_<+ru{fw{pWXSHzBZ4B~%&<V?a%GT~2A9<r~l2dwQO_2|%aNNzOXoo}ExoB=S zp}hU-*fFc{k}QL71+7J8EOc8H?x$&y9r(!7)_9*Y|M4r&vh@D=6>D*eK|AJmJ9r6a zYXn57h5CVogTr!^3C>x+-7w6Nwf?EB#7-6RlaJD3@&BNUS8^dpu>t^57@p=Tt{c7` zc5wCate;LjevHOk?{!7rS&fOn-3a{q2*+Ip6UCu{a=d8n#tWRxESM{e*=IQH%+HH0 zN+~TeQu*Q@aYZ29co^)S9NfAJ_)Py<@L3;cM52Z!FUw!|63nt`U%w!I^?U<@#Aip( zhvcfd^;%G-c@Sfz?4J-q@ma>`;DAOHn`FML<-iy2ygbHLZ0b2bLTPjUqd3~Wp+)y( z;JlCC7vI*Q+~fPqO(lAQ6=~0#P~P~aj60f6Xv(#l9P>|Fg%>X?NhGDYqR+OH1C<Rf zddx;1P4D^4$o`o=js-X8N#+cXu^JdHT|p;2ve<IfXV>-YetEI;m+3$Mm^h1`qR&xc zPiMa5Dn5Bj<180^>lZjp@Hhls#biP>^zR7rfb*{S`<j{`Z<QTfeIfsf{5Lhk=$q1L zy2w?IMFpZLc%K_AYPxdjnKC)=^wUkaZK`}b&UuW5y}}0mJ;c@^8gfx0V~C!}+YRD2 z=n^3iUDF&dojsJ8SKZQEc(&vw$L9k{FfA>rziNkW07Poc*hA*9u&299>v!|04W0}8 zU^LI$b+nkCAJY)%-L>Wm4ud&~F-ZeTE4^spW9=xNI`-_9k~XPld&<Le7vETabIsVe zL32aLkCMv0XE&VsTY87A`SB~3MO|5|g%{6a_`$?S{gB<FLNtuA63iX$Z=NXI<c)=8 zf~VBrI%?Rc{(j~4yK@h2e0m+S1*xYvbxg9#M6<MSn&y7BaBL-=a~=L#p4w(zXHX49 zoO&c(L~#4vRU9-C+o28<WTuelZeJtv993t2=7qv{jM)jjKM&4vp3pux;5&j6*>dM# ziEz}m<i4rtZH&t3=zm)M#Ru*-_cJ)nV1N_Hd7wKdh`;1kXk^7Kw;6)$ebNvZJh$sF z=*mZ1zF}+sF=Q6BjQS<6FGWM780}#h?`D|Gfp6HqgQ!@i+-vX~a9R#8Nj2FYI|-;* zLNtTBpvR&dSk5l4@i+C9H*RS&mIj+x+W-0zMh5<gr-xC~Z))6|qj=i63Px+%|Cu;Q zAjzb~$s75q><Yjn=zNxYNnTs5>S0~9Sg|oHd2aObtF`)D)4%a1(r4yH*_&)l%tC2k zVeU?PRr|MrEuR#1HJsaeww#7n{ehqa3Zmnp``f(ZJzo4>fk1Cb)G=Ja^@8YVKw9|e zO4fe|J1>sp#QJ?9TLQ!GE{$?;=0M(}43(c_kpo7pwJW5s8GCJ^;Dx;5xsFvDcG6Q9 zFB+-X;+?qfNWC_x*`6~xOppobD&Dq@)dbn;UegCD@sU05ZNA-^O2Zs>f(==xEMsM8 zURd>$#z&Ar?ppc@VqIbAMBGhMF40I^qX0KslTa{S(M%NX)MAzZb5iMg%*Wmj44vDv z1bFY((Z;4R>65ca*wI#ubK9X^vZFX*VHU5^ac?kjDO<Sv)%{6BA~=gB0kH0dp23!~ zbWa-I!2jiIfqf5D@M7^e6Ny?{v?qocs8($g@As&y@R4WpmXZ{?V>G}VAkA9gGR@jB zl6b!PAPnzT=Uu)s5fm3UI>1wM%!0*PvF<Gq)qWC1><bxmuKP}5&hK7Ledkl@`)G*x z!ceS#QVMi+dz%nxOlc|-84}M}EczWW6CX`i`Fh~%t8xFtI$@NZU?uV!=aGG$cx*$z zSt@*q#aSSlJ_@k6@FC@Xc>*t?0dg1qli;cm4)zt&SK;co^evfp_K<*+dlJaoXNV$q zKR<;LX*R#Y$^=JO3T_=e!+DudLovZ;@yLOxJgh`v__2l9itq3ZIylgzx|`x(d6X<f zxEf~!O7z)?zP&`TP>75gTECF?s*30=<Nx$LD^NPF?|SpTCbe6_A+B6X%(r54#g+E` zx<QaV2+S0ZHikqAsoOm~3|03`{av5pVr@DJv$|mr=6oF%13a^tlXz=>Zo}@7pbbHc zVit55u5t4a#K)`<_AhfL^2D`TVWF8Q_rguqGb)FDfmmklCUYdCKbp&e#Nvrmpd(;* z7bztnig4Fl*gY}b<2p&4%Kp!6C;^i7EMesK{X#JM=SbJxNy?9VPm?l&p1NLeY{rC{ ze@Bf6kdM(i0&$EQXrl55*`I5Nrm^Soz!e-FCKO;)j92x(=8C=&F{C93Dy@>7lT}G+ zL@G|$aL+o!)x@42pv-7+#lpX%Zp&8nk|WP)6QP`G7njOfn0JE&hG)fCvTI=<HPh=x zIZSttt)TMVf7S=*xJ3A=3HGEVI9-dhIy=p+qHW+?J_vR_IJf>u)jdz$M@VCr=-6vD zAyotH#<Ab)L{BcNV~K|!nz<vSJB(s!d4Ip@>#?y<z9iUWAO@GejLQMOFz_8+fgQ3} zMXN>fa*Kv+HLb<r!ki!Z57L6{E2#ncDgy*fQWUr`y``6zwhgNr%g|I~9ISJH*`?`Y ziQd~BG&ag)tq#l>?wv7{w~73!@H^Y^Cdrp6X&P^F6bl@C%wjhU3Jq$1TC{=)-$2&J z>zD+J!Rxn#1bhnn<dR@hw+B$5@w-j9HH*-YN&c~RoI6Nn+OywQkGYabXQ`V9%bPLi zkHU4V1Ne_({0(R{@k2UMBt*w_Iz=HdD`E<2EF1>WC9cDH7zYe`$(UP+%|~P0&snzk z8@ObAIqcd%Na8ple+}IX0W$t4V!=faV5nI{8|Ek!uP@%VDIhI!@D*>i1Z(|iOxD0I zscAwq#T9=hckN{T)5GM+60N(!9}TiJSUBOuPaE-DCLvP!b0WJr`tt$YcyB<?fx#U3 zz(uFt#_CN>hL%h5`V;Z-hlGpu!n_<1qz=;*y1$ON<_lFZ6A!N=NDwAywHVRF%2A#g zFOfz?HkU0Z6J)i{?c!MR&-*T54owz41hM1@Nh#A3d4jH+NMDRxMh1m!0vu~O*1($% z_?NJn>nIp$L5>Q!6PdR(W~7)CfL6$$(>GsG!UHCoXADr{rx0Asq~Nrl{DIK@@sx(q z#bd29;)BB57Xl2Of~N=*uqotwZx~!Y+%Rf@FtK}_cSU&K=ZOur^pkr$V6FmihJ<kE z@TO9l7$&pGV}@FFa76_d7xU7%1$aidM@OdN9Ay;Ko80t(nW~K3<zm0n0CX#)VccKe zC2RulSdy4lP(per|6`v5x>O878ZVWk7LK<}ix2-VnRU3osQG@6V}j&~uPBI!dA3c| zqZLZqbFx$mMTa3z1CvHTZHHo)&T|)NC5M!e<8P=Ohe;i(Ug*1?8d42G36!^ncZuBm z2eO(X+7yFk+l0j<#h?mSI7bNM<h-(613)T^sO10x6Wmcb8RA58v(q5d+!ozr&z~`} zahp`&hQ})1J1dDnaBNP4hHv5SnF3dza>K5~XbVdZ{#KSs!pcBYp&g=DeB}wHU3{1D zBzMI$6x}drMv-!H)4c=jWz1s~B{@fowP~*$yGkK=w&qMGBK2}k(9y45cOH!{fHM3c z^F2wBgbT5QVl07plVo+>6O9PJaJ-f}CO$B|Gv<UmoPNM@*1F&UhT@`zTQrHj4&E5Z z;qqBcIu0@NXd-!un=W~K@^=S=0Dyg<b@CfSxTh#WE?tzx`Jl)>0s#e;6)U4&C610C z);t+bk%?r?oA$H-;=37VLb`rL?xlosC?Frf>=ZO3EC8&HMP1-9gdN7EDL82vwYL8) z4yr8qnte@o{af~J<g_I;`2%qygYm%W!X9hfrM*YD3i6A3;pDk*t$1(*F(R`}IW{K8 z3QaD{z8Za{phgL&HyfQBYqcbxEhTk>ur4tR^B<D#_E&xZ`TibrYiWOBMG!d#wFF?> zyPBW@<_IE|!?;Z>5xeJxpyM}O=RAo!EF*H+=!y5|i;RiGmNX#|Gu8}^@{=N-WIwXD zq@dMzgjj1m8?<sdv$JVI^SUC-Ub!>N{a-KXZuL$WaZM)KdH}^O-kRhF#Vo1@vrXVW zSpv{+6rx&1|LuwYR+#$Q@G638`6u0i3M!GB9JU-$;z%Z%m~OAt6^a~;HthyNBiz_Z zt?Q{pPI}!oED-yR(L>&=@UjY}pM|3|P^teFTnjAGkIb;&EhIW30w1qX)fJvaw#B$E zs#AW}J@(T{QUB;G;=aTlfKh;hAY8hFSwpAs4q1`JwWICV0p$>A!tA?@iKm#iLocU2 zpq2Q-c`m_k!yfC?ajv?H^uL%@h#;<ueL4ndDzj}!obV!}2rVQ!;gF1`h{%MZ2w!T} z#qP}@p&(FQd|ZUr=KF>TmfC6<@cokOa2^?u>SGv4I9zj7l`UfaMxrk5EjzO9fr;xO zNkcy*^g1kXGqy;MH?luXAHkM)I}oz6<=I88>(TF%dGG@E8Rj^DF-W<}eXEhckV;Y0 z5TfuH5iXTM7NHTTKmYc$mldl1cx3`qi)y!#8{&HTu*$V({`)BIA#u8{Z^p8U_k+-> zdB+fl$RHK4h*`hB`34Uf2~F(VCa{0xCjzYNw=zcnPQ0L;@CPGn34Sb!2o|M4^9pde z;9Vnrb477(H)$s6RE;77ZQV{Dpo8%Wr4^O8n@E@Z%FvJf#Yu|)7n2Oed}BI64B~ME z+9fHsoI<h1ECzBE{{GU%OoYxp^od;2Ln82!;8Brq-7|z|-r?(^xwsxf)CG9J{u_*+ z=eqtlZXGs#WlE!M;t(!Y=L4mpHQ&SvFehO!pe7%3v+LaPJT5nkj80?{Lj((eEA6*# zn3`%X;l6$nbMo+JVY$HfQ*-DX!A61OOz$XNG{h<x4jb6Lmi{EK$8pH=u`=|4+XpjZ z*)>WnfyS4MI8}sNK$$&MlnaoeeDm+0(U{dOcd-GPGo=*x?KF@L340DfH6gg8hTGHl zrBD*ul#=Uyy*EdBBt$gv`ne(NgoQt)52F_5vKh0;Yq|yD9(%1~ts{Q^EO|X-I>8=u zLm8@*449!ue9{W2@Tb%zU08AWa#9!OIQ}DCEH^S8PrQo?FH@gIE)6%#B83-%Ht~HT zvF^8;h9+RT>t&#Alzs&#J>i&HdCjL+#KgBXO~{RfmhZ$~dA3lB+seSZY?Cm)hFT1g z!gM-#o$l<4vjh7%o~W<ZJYn*E%1s#ep0EiK`AJs)24S-fAix3K)s(`!!)5JyA)n~x z)94(fTsuN{qKB~jTD|KhT5aMv`s9Z3ECj~LW)R8ve%Og(;-bnGjrD-VaokxtWhiH9 z)&PUo*E2}3$u^ZkeXyJ;*e`J|SvfyMeM>}Yu9z@3YPBdp*p^%9lJ9;1i}Y539tc?| z&SMByD7{>;dJ`!o$f&n!TEaK@2t6L@8&b@Yi}x+nLF9)cFGOZ&j^UusaF&C_GJJ{f zR(TA?g0=A)xM<=!E~2}6Y+NpSWw55#(T(r@3AHO}6)1(+^4hMjCSWfJcd#AyS(%WI z6Rs;(?=wiI-)iCzxRA}h;GE@LeD1TQnz8PZNVIxRv7EYa@gSEGQVu`@lfVx0?i}Hh zSguuB-P~z3M`j{gBk}P%GME}@+=AcOr1cwUM;+$%35l)P>`VeQNl3-S49r$T2z*JL zNV#90ejvVF>njcQ9@F6dumQHPeD;T|7d1_dT)J=%>wrPycn_32OM+cU`oWS~MZBSa zDf})V<S=S;e<GvlL=nZhC`y>}F>OCIVmFVH(?)l36?@qS={YaiuRkf4Swm@Y{bU`H z@D+EdgpYoQs$&Nv3JwRsJdT*49(#^&VOxoHe6j(W%#ie#7ZbDb=Ce(7HEkep)A%}{ zRYg8ruXJOH9LOdtjtQ@=92d-wokVxJf3<*@t<@Cq^F`V0)`wG#?Sh3Zu7GpVg509+ zXKeoBT&oSAJ|zwr<z~BrXJJGV6R1MH-N9@6bb+@aV4OaVQiK7@aAECjuYg@sy(PX( z%v05M?_%%|q3<%VD)v`<gdCM|WmY5tdM=V|9#4cvv7LajO7wx%EJs$mD~>Hd9{KK( zGW~ji!kve_1I5w`Vda&PY;P!H=poa(80aCk8w_tU2euhdJ{u}`Hp^+s?fc{y@q3;Z z0usndMy59i#)>0a1%JHFgzt8DO^`WQ6C5%`rK9yKHI(Bg7>%NZ<$jR|F-)8cwX0?` zT$t?7rrbH4UO6HG^yP**u>k9MQ;4&o$oVzV52QgM=BaA=%b%$La2^yD0A6^la_O7* zt2xcVD+HT_97qHj=q@3fcs)!@wA@R$XhPEfREXX-q54qNIaa0|DUbo*JRvD+%jYij zh(ek87IfYnJOWhRb<<uAaJwsBrVRWwPmGwxGm8hBDdy<z@iw_gHbmKDluRP`bsk}) zFI$v2gkKifCjXBA6Z#yxBGQLklmAV97(biEw4W2bMeGKm5ieC77;C^Fz_bR<{z5e} z4~HlR^UGM`p(+cksC;g>)kLA!tev>pQ!|Xu<IcEbtw2jSG}xDwp_?(Y6mlCf1$(?! zOb7#1ciLQak=`)$(Ngi@<KgC$2;^9${YA@McbOtXtQEaf`(w1Jw6u^pgR}k^^6kaM z>?&$L)I1!qEL{S|zQ?s>ENL;^3vktew;fZ+uH4ImBg{q%xe#%qsHY=Dg8A5d0&i<R z_KuA95E($e$yQyEF{4J_3fWCyT?;C_j1mTuoVVV4zhC`09mBLH(CQs;9dbj79IBjC z)VU*xIwH8(r2%Jl@V1pqh332wQsg)RHbrrHG$h8E6+!~sHIs%EZ>o89gXhWPogXkt zOlW(q>k{r18;Ct_o15Kf(W|AA=B6j!K~!SE>!*TeU%$|x+mC`tKw=C!FRr<{UphgR gSPXiMEPG@#)~@0(uS@m&(b~u_(C4lg_Q$pV2MQq(hX4Qo literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/50kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/50kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..9da7369be729d157d851066e3d8ccfdd9a212364 GIT binary patch literal 159632 zcmeFZdstIv7CyRBEZQ3dYiDeMI1(C)6{lzwXk^2bHiXJV5JW7LPK7emwhjSCV=>#} z%v5_xBmpzjnot1&L9Dk{E;VDd4H3pvuGI=?Nw`*!1PHlp&im2d<$2Cu=bXRJ^Zc|I z6+*K2`qt%L?|Rps`)TeD^+fEe!dEFbH#h1{{6o#%{o}P)_GG_JQE_op5JgdoDR;LQ zs0H}bBNSfzQ8wj{KfB@2TMq{O&p)p?KI%hx;A@ZKdlC4L@)^bdo*;jE@ausE9$4Uk z1s+)7fdw8|;DH4mSm1#L9$4Uk1s+)7fdw8|;Qs^*Bxk>$v1@nkiWmNfyIpvA;XIr0 zBt@<GR8chlXZIIFHc<bYL3m<6vC0Dmfmq?euLl-*V1Wk~cwm7C7I<KR2Nrl>fd>|N zV1Wk~cwm7C7WhBM0wI442?_sWSoj}bSn<M!aQyqn_2lLkL5Dz;2@C#A{<Z*r2fsj3 zf2_v;=fD06`MUf6`ugGDI0nx;a1TcEtp^+fvBHC24=nJ&0uL<kzyc2}@W28OEbzbr z4=nJ&0uL<kzyc2}@c%0de2S~V<^lB(`F(4@?XgAEcgY3%lfUD?0P?$~_ODaFeSPj{ z>Sb!-f(7JX{Bp;?ixw|h<nF%cVGoao7C-v%qmMrF@FR~r_PF;Gk3H`7_#=-z@zfJu zOP^e}Y}uopzx(}DPyXKf$z@NHH*s5tpK)KbWYMA}Pd@g@V^99S{x$a>%4_k$|16>w zx~-%Zc)2a~a+|wKad5SZuz5k2FaF0bw*|PyhddT9dH4~$;KCEs0=I<=7q~AZSB+Qi z!}lq7uSMQ}cp>VcrSX69Sef%=$cIH=F82S^naj%(ZrtateM?-p<l(1&_xt5f2RzFQ zd@g9+i|aRphK0Wz{mQF?7-8&|#H6js+fugg$jE#<>#y1G<mTo7efJ*8-UI*m=f6HW zc<5t=vbf}k>ffcGA1|+{JW*9$bMoxD^B2DU=3+zRcUP`{|AVeYf33Zvv#Y!3r<=F# z{xV=R4Gs;Dj82*@Q`0lnS(}~QmmBW$fByRI#{O^j<%RoN;O@TA-Gkhh+k)NrZ=sj_ zqCdRwkatwP$6s=mt_=Bb@socl`tr=>CH`v@?k{^weB<G#xa;l)Op;rhzq9{mH&*!n z>CXPwjs5TYx<x&@5OkB*LNAJ@oYpxinKy1!T1$L#^xQeh`O3CJCU~*aFs-q)mn&Q6 zC~e6ig^)ehDz_HRQHJP~=2U@?W~#lSkg;WPRPj2KP19etu+73PZ?goNjdCkvd%VKz zY;j(r{EN6QBV%blr61CpYzpCEqL-d4=atS;47W<pbDb|+KnI8M8|dBUE&P@NT#9Lq z>WM8dNAXmH%+E2Si}_kdcBGfhOFzgM!uf_iNuH3;OkXeMj2j*5OiDDkOA)S|qcW<U zhF~GRo8z?LO}1Q~qf(uXRE9dkTj<dCB{EGGdhD2x%QU-gtFy*O$Qx-Kf8M{s?C&ya z?7_4)I@k6Db1$4L6T$|!iqGjB2HQ~N5{KSsX6Gmsdsg1Z7=%GfjB?i1b@1*Sl@jTt z!&`5eqfAw$o6JU+$y+*3_v$0P{wq*%b8Pv1x#Qp*HB`CQ@Y`(}W2pjWs>7A$SCBJD z)w=q}M?KeC8K)T5Sd9<88R#}?QwTT{LH!z@%EXSJ<Vv%g=WD%S;2c{XH9MqiH9HM! z+F}ctkeE4Yr1EuH%pIFiQ7zFlTj;4wN&w@v(%J;3b>r0h*G!e(f<dMymcq+TmD>)u zQZ-|=WRu*QH)}K-%N7Xv7lW42681F9#`8+)Qs1Z-sn^X;+Z@$p%h4wYp6250YA@5{ zba$f0Y-n>CcSU;2=(Sdb&}7RqtPI78sf#*u^n*gK#yZhj<J8)+=cwn0-85tTYqC&! zqF2b)$2hOagn^WWukB;%=BWDol`vGFbfWd7#dcUCW;$Y(1`EBL{2ZmUvRNueBfo(w zXC<~gfkPi8TwxAeP{B+YTxmRe17AB`@|G|NmMeC9e+gfYlayN6y-BmiIqFD$(N3Q8 z{Ha}Q+T?BcYq8t6cT2g24)$hGNBZOWfxqUxba6oL3hr)qSaaD4#@;~BXjJLJ!(z#9 z{Tsb^9;tTDQ7a|>W^UmgXUiN#E@_UMFr|fwmj>kCK5^ro$>sEdb+qRdVK}iAlP&+u z<0XHonw5Tc<=08uF8&<VbYjoO@~*t5PiCE06`uZC<1kSRW4?Z5y5P{dpZq^tzpq}T zY;z5{&d*T;CB5+<H0z$WR<?Z2*ZgpVp4>JTuQ$0Ad+4F6iKT2K(?L(?56$$Y&*(lX zi-GIy6>uh5^S7^UvqW_9C*h;PLcYP41#chI9lzMrIQe#|$HWRnm_NdBc8-$FQ9rNx zud3N5k1c&|+XeMYX}eo2Lo$&qn_py8r<Xb!a2F>^u8wZKl-cQ*K8{;{<G{>_|Ap=f z#hw8LGcC<><ylr8?$qwySZ?!6pX}Zd>KHCKXp{+Q$>7$wDQ0Zdmz`S4Ak#|sZC#DO z(x%E?x&9CD8SOjD9w%O>DczjbY2W3<?W&7gR_h&x28Xuyh7U8<{_#>*W>nU``%0_y zSs881;yKTqj_)jwGc$E^tH#{HmfAE!?5*Tt=bA>xnvdV}SI{B!v;uix#&>I|)6i>U zM&YS9*5q}5@48*otVXmbM7EJRDvf(0ZF`GZYH4*Db6_QhRiutV_#k#WcnUgLbXz!| zAX?7u;p3dUg(U0H7Pg?#-?GBxgk{*%Z5G;KQ<Pf<4&byjbJV%^U(EyNfg*o7oATpA z+}Rg%)L0O`rT`&zuTsdBW=JzM%}REAypJ^1EF2VYR9tmx35DE+SmKqslb}Z?h_|sB zewh`MdfNGwvdu<!vE%YS0bjwiitO3Z;utnnouwH}+ArjiACR}j449pIy6Xn7lviZ3 zF-@>z$$R`3X9NGDv$3!*l-@m<@Re5u(`3eZv*%cxc~7jrywyS@FKy*2mJED0;ObYI z1zgQ^do3=6r$W97yy$Kg3<}vIE;2c78;Q<g%_0&>+Xc_C7WP)6LV~PX=Q18<`WyX5 z!?<voEcR?@U-+ATSw(qsl({{Iga|%OIvP5JB&t;+<Wi7IN;~|OR;C$0FvL-9(Q{Nh zyEZt6b>_KoCN^~NTa2<We}s^x|9EJhr)|Wi2uW{?9>vF@o#t5DWA~GD7Oi!qyVhAE zT%1uS(nbdzT<U-o*a@~V(LtLu6LhzvBzeK&JMuPp);P{Ya)VQPiMAsY;%I|wUCn^Y zC}!#`_$1nqP%eY#z<2VtJruQ23pej(I>HMO^_(VUtAe(@t=Pi7U>QJAD?*K^5UJ`^ zd34c)oUt2_^~2xvs?zvKGjeo1RlI(XWLZP3yj2}WK4boGo@=sPYjO7pq{86p5tM6M z%_G~Ea9y`GO&Yk8B!D+QUWU>*YP9h6ba#RQ-Y#cv3FGy=qCu${SJ%r<^8Z`>A4M3F zTEkM3znEtBVRF(4(j&|mSKfM@xh*w|G{n%n(s&(Lok1!xPA1Z;Uof-WC=>Nb#1hU$ zW!q=STfK>wT)zl?v-LP{*x?A%<hot*r!iOhbvDc4mqzXR-KRUuFTQ>dMe2)^PdxhT zKluS~clDROLrPa>p3h)0Ek1=p`uyl(+H~yo3vj4ok-l$#w39vHE`8mmhPTgAU*~s< zhV*wGp3~33OS`2Ot2!M?uzsgN9doZh8+@U;^_z|z=glZGTJ~nA`DkiK56?VaArtl5 z#7t|rb_ZXY`H}NHoOidW=Oy0H6IFART<EV5tzlDa`Bm;qFLT8bX*%&)|LVX|zKyS4 z)9UJXPO+wp*#oVGKa9ut%kSmrI0jPu5JCx2)ju3LbJ=7QOHi^{NmrcM(b|z=9x@vh zo@-hy&u#Mzp1f)n)~DMP(s7(rFg;E3$nJpL7B=m@J+eJRmx=}ur~z;4ec#Om^7$$r z2PB^^;n*7j7r^U{u3o>_JEd8;rno>w+!V#s)$kNTF4DRY5Jwo`)!}c3*CuUqk39qX zWguiV=IgQiMp^h_e^ffhHKoCPZ;tv2#ju1^I+&ni&sp=RqoXm#YNxiBHRDLSAEs~$ zewki2Y3e)>!wV!xOoCFbx1{KX&j%xNE;Dm||GF<HeVw^FR>Nn;g$eH@ZyEi{runNv zLXT9G&>szSyx-gsJYY5|U8y4hqLZ`YxK-97){KacT(<7ChiD(ClvfJS<m&G~HJ1L* zT!V*(uNJu0DjH7Td;OwQyV|J@4n_VLAD*NBQOMG^T|Aew#@ZzB{dMO~&Lh*SH?%2# zWi#^q<oB&@%C@Ga!o^67&H1144h9?Hrd&-^HN1ppp}UjPtWO>L?9`6f^Bq~{J59i8 zBb9FpO-RpcTkCon6~aLHs5&!gze2({*oWd#{e1y5ayp*9>$^AkiiFEv?JT$OFXE^i z+Ti9NXzd%y`$N{x->*b2M;Nf5RtHCnoXYoM#z@^!vGr&3KbcsmYm>LayG+Njd*PjM z3d{9|)5`?BnO$~0|C)Ns&MzLXtP$q(OWp`Go)A42wf&2p7vFooxgqFwuFbr4oj7SM zh29<ey|4D8akk3`Ik`0kX)o=QsKH32dy?o-y587Xu6Ll|j#Ta~`NA(vGl2qJgf!)} z)HTFCSIVY}B?^gx`8oD9tF>x$TPu(kMxBPW?9FzYIEt@nQfQw0(jCqt7?eoUUPmg5 zacb89IG!lssC<g_1PvR)Gww^gIw`!!2c8XJu2v-Nxrd|88t=n3Y>nueqc-A0?JdKy z7?kJ@NaT`lsbo?ZkXxBiXX6<kd=$MFg>Y|D2C~v1(+_)2WeSJbAskbZ`NOw7d-bdq zZ~k@3TQR{#1>I`{3Oy&IweeAdLJuVKYw9qV^SF@boN}3b%5v=|rN0o9@WzAWAK~|% z>^UT;uk%lxWH_$ey7Y$)gWGk31o{0KbZ}$V-HamLFLCQbjmlOFA8>BqbgeUotGWLv z)35E5NHYtH?i*U=-#_Io<Q4hk+B8k4Pdnq-lDoe*q7L#8;`G_mbJVNxoWH03knedt zrlVDM=#H7d$M=Fn!C~Ag-A>=r6Z}T?U!IWU*u(<1UWCw9&1Z*@3gVIkK_DNh8O!zR z#ZEm>$(D91Xx02{YO7Ja*ff!k8b^k3i}XMV;7aiYQr{I!Z4FKq$-$SCsfeWxw8}&p zQgK_u3F2y#g~4-2tj|r3q)&BNi-kJ_>coP<f+-59UGB;hm~7H?=Tr@<0#eT>)#!o% zSCItrC;|U4V?Y6(u;xkB8H%Jhz+evha;=yFW;lV;X~#KrOU>mLu7w^t<}D)m(89mw zucm`xe6ueV5{k@J-WG#9OA*N!bQV+BOHDc-X(mOtkZb-r|9yIPS|JKXl^jg^{eXf- zjT%7Z)NO@P`BL2MGN+zov7u6AHsEdxm$8i`MA0gO*mx=)P!NB3L6ydIgX=BeYo?H0 zzxA?-h49T-oXKhun_WM;0Se*vDrCS}eTnKU)RffG(0;a*HOErq<EI&2^sWHmqSGoL zbr$*0-Y63yts}#UcoW1~8@ad%G*|HfJ*7h0wYF@L+?B2}-M}HjjgI8a;?=H3e+5t| zSDo%USN3qx6-(Dev^ED^D@A?roKl}jn>XnTHoJ=f_1+6wf_JRXr->C2B|pcKR;a1W z<1#CE7<xO4^z6CWpio-k(0kWOiu3`L7tS>7Idee~JJD(hT7vvFRw?9^p55;cFep&* zN(IhyidY5RCn<JIBbTgyPMtmx#H=I$)flcunLz(p!?EMtmFzFHJzFpi^oURdlAGXK za5-AV=0&1DVS>P+wPlIqRz*CY%>p(Vs-yr_)M?q<4LnsM+)*>tfpGm~IX=c@E7C<i z)0otGI8DG63*XS*A7swL$&okEF$0T@eg7sC96K#{({UA1juryZChe5{_3tjNYcF`| zgu(Z=(&ioIUS#7mD_v=C_ZR%>n?@98AL%Q%)o&5_hj!UjlM>-|e_Xj?e0r5O*mI3l zEacs;FO2iJt2*%B4&_#J`(oV2<()j&x;bi_I^BlDO1}4P-|MBZ&%O5VLEfZqm68;d zbA&udc_ZwXxUHctt`eOU8224P+0W@|>Mcl^ed)wcy}C<bKn*$EzX>^blZZ@-r;Po> zo@d8LL#KY4iJDLAv!>kP_m+p{g{Dj!B7R^IVEs56+L4{|O-~<MMeVeB>%ATse<NSa z3}0(&oZR{eUz&<E-6QJ#F=B^GO|axV7*-8#eZLkYgoJ5E`V*!_tG35=qAsIjNICb@ zW!`NxsJ5Z)iX2qavlV9$1>3hDDKT}uzRjt%XC?iOW9n3=9v$(nD8x<VugKRtzGII1 z_~aF~@m=5%%W3gs{^^^$nlBm^qP}-srail^Xo5w{wh0j8if_NU+I@C=pSF~z;WDEG zvIE;3I@)A2lju%C<OG_XhxppwIjTbxQYX<|WQRy{O;%cw!6dkz(^gGW|F+v_-n>9O z=Y%wa8G8=M1%wCBm3v$i5{l#?;JMD-^yOHt(`(z%qf`{#_#1Ks3gMtcEOcD+m$xbK zLPR(sC?8kh1P6lHY>g$Tk+dIc*;&$Dtnd~Z;ZQzEooB-WKNkfr9#Xa`@Chg)Yun1% z?TKQrK@M1s9v4P>6q)os3Z@73>JCY4^9_nLRh{m%9LLX$Rh1@4e-R-QAe*}KPF`Gw zw#0c}rttxzBQ=v(RNxzq8veIMtOY?nC;<;;%h7@RQ2C%Kp>0F2{0EnuGAL09P~ZGz zbnlHpfn$!EKUIw?I>)8PH5z5~8f%U&06~f@(F08U%6|%x8FRRdxq|?J?!-yG51?df z5ztnv9F2ZFlDwwbH3WA<Yki9`gauxF#2qhZSw1mLI8!=L0PK#};luI9gQ$7u*oVOp zt!5-#Y3d}2ynXh=$eD6$G1CJGj|hq%M8@F{d<OC(%H3On{!`nl!!;R%9Bav&B5sk6 z2Y7%8(xFFmt*b^_AmEYR3uxaL&lL+erSt?nQdMd~x3f1<oo+Ww7gHj70#-=os0O9u z<!Dqad_%APRan8AN825HoDE1`SApWlol4Cm|51o~!MGuHpug!$^h+;77v{)v+0~x6 z1(#?v_VyN|d7#?A@TGKnmJe>)F}2MDKatHV9Tc#qT{ypLe?{0G!k0NM<Z`v>s`z@Y zYX~PxhlC9%SqYLONypn3gwb6#&FHYQO(sE;W&uy7Wy6pri;S?vYSczqEN%J%S7Xg# zE#rwF`V_HtA?|T};N<T%3x^07fsz9o*<7Y<n^{8oGSa}Z9Vg8=GIjd6(_qW?$$xWC zvTU_cxeb_Sf*z{e5w#;N{WE{di-+iu%BZ`JXI?u!t&kAVAa_iEdtF?4>Qlzt-stQ1 z+G4&Tf(Zt;F-kPjd5)k6=G2yKNjjs3?}YmAA=c$HmlN0h{Cgwn5x(ZUc6j54xJmiH z>UPKkW_IYlAc6Vrr~A{N=GgoSG?or4$94AN&!-=`%w>j^Xq3`$h$)?a*FH48b7F1F z2kC3r&qb!ro4a2O*GB|ri@3~1C3{nsG&Fl`M-B>2jM3G16`#`Bdw-7lb^7?_9X@u| zq4zRCA#A^;cj!>CK%|~4h`Xb8-+tM2D-9HAPwc6eN-Z&M2Yz|)BNcm`nFbKF9v%Im z@|VBzqjvfnjxyoLQpff;Ug&r?!*x|5OrAQuR0wtgDO}~F8AV@nB;TieaBaR}ntj7C z4PxpHx-_82If|;a4_3~M)qr{1j)MLr7|6QAFp8kmLHIkk!0t#7Nub>IW=(`>T4Q^> z98OQ2L9$dJtKc+*z93t{MkOKdfG-FxH;;;@b2@W{CVhe%ibZvM1)3i;yiQBm60V|5 z!|vT;#0NMU542hQ%a)Lk*klG-NcRc1*nrOVFBjMWk4_ZNQFp!^UJwI^MVKVV-<2;F ztQ0&{=|FWeeNpm*B%e>x&WZf33u`7l{#9_$IZI18&M8^Lt~I0t`Q}F~pIqO<US>F@ z+2~(nnqNF0wQ;m^D?nGw=xe4h(Mnuwzv>)1t~B>2L1O(`Gde0<QH@LLN?qdbx-CxJ zwRMHao)zCL79_ZPGj%q!`0VG&Uls&uTr2JEp#$o$I|Q2@z!%lD{n`}$5B2L~o}3B3 z-XFZ}u+P2@@gC4J3c#PK>*4yY_oQ7ro&|Y1!EWD*4odnzlFiVucv4@)gp%rr8Q#D@ zKI)04e(NSAo8&L|lwVOqp|TGOaeL;mPcB_>^(I}Hd~hNuJ6k&z^sj5$9X=Y1!CL(N zj!XC7I65;{eFu~=Vj`#K%RPlXzpCOdqXUqgELe5lsrKo}=&ovV1b`~wA4E0aOVge{ zat0oNLqSnW9Sh!Z{QGBWxUvBf&wUA?76|1X5;`ghd8r0%EE;|xQV=Oyu^*NM`xCb1 zM6o279mn_}L`Zl2Y6<$FwtApY6tZW4Ks@ljdowU)$gwf(_f*8<fdj3I&;e3gOkWfm z)>r`r8v+sADqqwdl(Dh}d-~bE67c;e(R$FO9J|)_`1uO6@#Y{?dxG%*TI%}I{cmU@ z2T4`8N;6+C6s>79I|)sUA}IyqqRyJ&qkeC_b4D@NMhdEC)<q>E!u>7W`q!@%*$xXm z?3h)I<Zp8}fWOW{@=N>6o_$<LB08h%LjO}S8y~s*tNPVOMbxD*RJf9vWj*%f1E;tO zP>KK&>6|@0X2zsdaY`Kq=b`jBbv(@-^vuQ_8;9_dbCd>%^zUCDd)acX4N)|Nk|<F# zxOS7qwGQnH(3k>gQi=+jAauxk_2>(NB>#xws5~Zuh;1s0(G!4Gfjde#rM{b=g6*|y zt>|hTaG>!jIU$%fr%72M@-qR&k?y(rK?w#O#D6b38~jiDrM>=*O9x9#7rX6h!)rhe z`X(N2W9%adaU27Zw0ErRCCRg>WQ2GtTTFL~Q1F;q*O1Cr<ilomA|Ast4wE*Pw9vJB z4^^ahT9jjg&=t;x6$Cku24OXV$1lShr8+KfLG#~mEcg!2wpD?Pqq~_}(2BAxMrDEK zwoEk(=9EfC3K&dOBD=MQ7l30UhB@ZNPFR_-KsPl5nhfI#f-J@mNXTEsFbuDhJqwC3 zO-Nh-sF+Ym)B(Vr#x1CSn0*i^lAl1^vH=i_-RNT+)k?u;0Z$d+Wy=GQh;&DR@1Pyl zcs;tCYrr>X64Tqt9sw*Ks^M#2LI<lxa;!x<-82dSdBBQ70%lTz&SQ?sz5!^hjR;4+ z*T?JJ)mf!z5h-CjnisHaH5+g}$SaF!2~WjwIm?y|kPA;{&mKfS-NzVX=`NfxxFb3w zmXf32vR_2V)fZ#r2JmsSV@L@WZG5EDErh9+g~t`2(fJ(4X}Zo;fRbmL${u=^6}Z+N z7omzf&s96Mv{hpoA#DfcPp(LWt5ByhO(z5#d*fb#gTMzDXx=)Mfhf{!Y?dez-)GaP zZOF8{5bLI{J$G%xmOu&m@kR=k%WENxe<#41zpOmZJnW{_ssbWBr*9BcwBkV9MVIM! z>D<X5ANqm=EG_AYziaTiyknn_Qir($%5|zbO$>UOnQ8P_wkb2Iy}@TD*Y9y&yvJ1{ zWh1xnacZgm?5?e!EfjKP5;A1T0LkHK@UObeB~vgbr&+Q8`Iql}`;J}Y$Tp#MY}ec| z9Lo5RC+lbfd8jk#H*cRkIqnJg-^N+?;$MwOtprUT6a8^{_=d~7p4$2J>6v%;zB>uO zB0XdN*wgf{-x!&e*Aou3In=2f_+>rD3ysNMJ148Iu3u|AoUZ4%)}qoK82ISp6`zL< zbXHh!`8YV=q@RB0%(*}G%6(Ulop%dAxt857;;6Qz-#^%YYoFqSS?4E0BSA_NtJZFt z%<nt1@v6lp7V&Xr=j&?LR1s#d*sb;#&#$69kS2ym2NM!LhzUoB^S>Cmisd2umlMi? zF`!fQ^#Ty0Lqdm<EF{86U(tRvlTm-+0RyeY^)|c{UvWc+2snps?TzJk<|x}@^h(bo z=^0idxW09y%B>i)=FCw>;RZ4d2pIqTi%uYb2^yAu9>w%Y^x35HBIIJZ^Zf+;Z8Xj- zVSu{;i}H&y#JkK~j16EBmkC)PWqnY@>pzZpY=~%j5@E5L>oWOeAr4~zD(b}vUxBbu zfh`HCMUzgh90lxGWV<#Q8XC)W^ap*w`)H-I=O`3)bAVq4(}XshBoqcc9ccQBg{?LO ze<kj})@78YJ0@NBrEMB3S^;u@+VS{73BFf{cI&)(;N(S*iHKImMSOgU-|WEg7_>IB z7^`kjYH_6&;eL%^ROXw-U`(T7r4f@&oux`}C&S>~ASsYvNHrdXC5~v2sqw++H`W5f zO|k<hLWDP{cZVa=YgpGD_01NYJLw((^!V4Zia@?&B!G8BQVrIiq~#)`gkf-3n&8eE z<El{t*R-LfL`+|ouWdnsK^cqv#-!uf4YrX%iDqnlqL*P1^&jzI2&XU@fz`TEWQ*`d z>yUr)nA*>U^gRujejxc~Wh)SOr!?bl0=`9$O4ujjAo;cBZ(Sf-8Dms1_%za1IMPr{ zHaSU}%BnUVu)?d}1*8;$R4L*g;)4ByORF`wjps)r=VAK*a1Dq32q^`YJS$&=@27C? zBZ-!`%3CE!ViOp$k}0wb0oJAGVq|@Az{0)hKw0(OW-*%m(Z9gZn}(G`3gpztWf4QJ zbLJ5iMk?w;alpif?&^|om6#jDld>I+R2CEmC^XLFqT2$tSH#scvqKXYFbGHm*=>}d zAtCMR{^jVEn6<bwoDpU%ojL3{&`}9(Hw25w5F8V3A%LpLJ_1325~o~u@~cP9&Wi&w zdOD{{g(fx$FX|z6L!I_Ic@w5p81xxZ8<YTKq<#E95?W3hSMf?sKTI10+#)@C6VleG z^ScZFBxj%1PPd1{LkhnRF>z)_24tdsy-Djl2N&9eDd_IOjeZ#*=?Jj14aI-!zSMQ{ zgLDj=ME0TR&x_3%U~^@(J&V*Hr(dSGL<7#At4wIJz-UIoDhW`reFeyHsJ8u$6y1%4 z?Z^_?5hw!o!|3cmVWgL>gjX6(#w|xQ*4|`AIHeE<ZJgRDBn~iij1u@@OkaViud;QX zyW@|B`PX{==>7p;tKIx(hy#Ld9|rea7=vNbHL5_22Hs&%Ag@M4SCF*r=wYEXD8`5@ zl1~>)@&gumT^Wpb2g5MQn)fd!gOq$e;4tl4{;HkIjG+6r&{Gc=Fi6l#a4hOPWDQrZ zC)$KYY6S_+`g2zzUQql%pA|V;g{z7|he$wbrXuzRH+$s&LO*Idyzf$n^@tp@6Iu9x zQQo3#JvH&@Y|TC91{mkpmLm)VJ|MvM$gdn0a;<ycJ^Cw*<S%y={pi67cmV-_q}b-K zSi)~S!<D8Z637s)uI%CaiQbSK#Hyjf2#A79)h>8=jP>i?r%DCklgxv^4sE~X+jDal zS`SI5+i(X|DO|=njvlP=gLHo@GG=Y9SirTv`*cYa!~wVp#vW4ZI{C<Hq9{Q4;RSV{ zwM2B8^rq``l+|3;c%S{GMmoO7DYuRA#ffHt57K}kToyARgLe)cTewPe-*81_vhDq^ zbpo>=N%resNBr*oOvwqIQ4rAUWST9QOW#akGk`DPGmt(QkUK@6r~Rk<Qdfosumdb> z_a?DKsb}lar#+){=1W8G@#X~%ibQ5ugP&X5TH&5^3kL;m<1C0I3@y>)ZXME)cAIUK zj-SLR)Nen80V@d90XJ;EUM}nt;`jziNO+^3CFVwf$vH|m+@UW(Nb@v6e_)LjNe9V! zV32c?jfRCfFk{;aGD!wG3!4QHSty*R#E%qp9Wt6xfFui$fYO3O{VfCFE=PwK+$L-e zSbr2SZE(c_t6!G=TFr)19|aOM089-g`8rT5rN~Gm6(5Rx;vHIxJBPo2tr0ie3lhzK zk&X{WiS2#g03M?c-Ou^DKwSMHlT(`cPE_BXbe29v2>2Mh1Cm$rPZ2)Kw)-?0T-dTm z&eejmn>2jH>}EiwiSfyq`~G=H!fm{tJPzI*Xa|jv&0Bt<Eo<}a!*qxz(sny;d^Z=v zw^+p<&`ZB%A$3s~@{y(${X<!_0xTJTnF<~4Nd*aH@I$zR5-zx`IqIEwzBJk|lZpr< zb$25=WKdRU5zV~PB({rJ#A7=#O<<90_z250q~Q|<YkZ1yCe~ujPgt@ZnV>HbiJxuw zaZ$s1NNi|V?n%6_dI`5MjEfTvKrP1038BrOqk_TKM|z@MrmH|lE2L&5(<3DE5F?E; zNg#!a?|{@waHL4b6*K(}K{P2&r4TA;#sU{0xl6c;cu-P!-Im@co(2;hfP*}VG#co3 z2@g5591I<AB4`O8P&F506HKN`BR$njh{#oCx-p0r#tKRd!}ScbD@aJkp<Y0vY=!h- z|7wFt?}0-;KL#`Kfw`f_K&gQsLenhUkHQopni*EmXZ75rxI98W(!0+d9FQSzfnL}h zxfHaHtM}CrQ-{ASX2d*CHK1z(%?>Jz9j_?Fydk7Q-gc8m2t8mI(~s^jLb=lFE%X%v z6%ZD1?2G&akQdEmk1+3`BufE%nwchbg?R=a82%v+9M&|14liKPu>cEfPgFt}v4&0Q z5`xqyM{FL+bK_4|kclyAbPy0AP|@11aZI~2c-xr?ALtG$;Dw}-*}WNTUVw0LpNhS; z8TQA(P`rhIaRj(hQ9&5XJU3sheU#Ma1c?+W6jBhlN)SyOkZtslk78azbQB=tSP8ev z0L-^{3%Z8@Dq;^`Zp$9TUv79z_`6JWtHs|ENCD9&7#4Qi0engma{W?)aTY)g1bWa^ zDIkNy3A(=q(OYel?O%7tWvWAK1)$fvHcr!efK*9oX2e*l8~{p7MtxKUNiXOanAXq{ zt^yhiE=~+iHb?z|fY>#&Bky!R^+MOhU*7}>RBV1IiOV!88Us4Y4EDyZGxysN9vM%% zf7@{owx2b5GqtDVFWiqfifI!O>Zvh~ZLXd+eAM{v-|#04i8lvc+R;`~jZaCLql#AT zO!~3C$Cb)v!k=2<@R3($N4yEa+kcHVsqNHAfiJEkZ~#Ba43tbg+rZUi!f+T_+O=Ai z*_|FXn`>3YSCOOOB9~wKwCnxy#`aU(16CAzW-LhZ@nG2LwWQojGnXP)e$MnjWk{+w zq7rTd??wJVGn)U<<w2&Bsa4=x2?CP=aKi%aAnXgHk*0^Ft0Q^fx_GJ~$lCA)j242+ z7K9lKAu<5dHb1c~LAwc@-mqCB761sYK@1(1j`uP4EQcXvKVjNosNKlCW@v6KaCEp? z1xAl)n1lnm&<*U_*cIkJ`1cU-=|*nZV!(czKbm&uIf;Lb6Dq}8CELghH)c&BVB;~} z0<E6urQ;y-HjUQ1BNux^qrg>X3av(xD<=pBac48U2&S|R`3lj897cX@JiLV8z*8`` zETsM_aJmX1I3nR@w4`(}A<RE#?$J0y{-|gT5$*W^R`aha_AdtX3K7UK-vxwr=3(YZ zvW;{+R^EmwEfR6aAwM+1bx>Ji-iM>CMOEaCI~xIB+JL81Il0IRNAkCT)BqOJ&L2+k ztP_0)1Yh=GpeK~C4pa^#ryIrZ0z+wBYmbu|2I>w7%kD(6h|6Kv20eke^=>4f>D~%b zUono%P)GZv_aoVmN^v8fQ{*@VRMZ&Ji<yT+9gVRFaq+M7wk^bP6!mK?hy?x|wG}e2 zu1;nY>2tzg5o)#Jod{`td?fX#H_*zykPQ%Bm@2>vw<*d2gR{VR%3uRW4zA<9=bjXT zo`v7=m3jvfBHY2LkDi3I6x^B~z`#^V6hPyc&Ew`Zzs6(W>(rv;plVQbn-UXmrmmW+ zVPDrdKs}<Bs=&k$<6>sI{gA&Ikm#0J7`Y7IqA7)7#%n%Y-kzgot{-x?;64~AIj@JG z;hPCs4)aH2KvG!|F%1}`I?u4l@9V_rP=xtt0&;Uk;_=<ptEwlRb5y1}j9>yuYQ|oj z3U7_!4BkAvv#@{Wy($!gv1dn-cwIHV5wDE|RcQu=QHQnWc7^acrW@xG7et5b_Y9$f z56&R5#m%$GWLzxk2UN8Kccj?z+_;*J0&X!=r+__I^RH2SJEWOGo@=ZnTm@5G=Ak3i zb9X#~tOS*6(Q4`ygidfBQ(Nt9RD=$@O(Lzqgm5my3~8Dtdc6!L-6o56!bAZr`^!pk zfX!7lb!N)?<(vr&+i*kOK*SIy7o#yM{D%xatQj@d_?7y4=_41-L+}6*dv;zd2RSQU zScxARMN>XdPWrVv=$47}cZ~F^{ns#xD|~;60Fx6_2mhKZEHF?V#+6%3+Gmr$Z_nPM z^I<b)kVxr}1|~!~8@TXBv*7N($4@cm>$sNHTxEusXep3!o>4R`;kTyn8-lF=EXdw{ zcaFL(92EV9XK$gkX@5R*_xIDS%U^u&SvsU0mHXGt=`Z|8;AjYX`dc4PrkeQkk^IVt zqeHr(%Ovd0g^zy#XVT_}^Hf_S4A9KPjBYG>Ge2V4WQCnG&ULvea04q8jWN^dp6LP~ zmMP+D%-@OboL+AM6N(By-Co|04;c+%zT1eC->aGk`loK@U8bqfj&61g_$wI&>GR|- zpyYNO7d|KU{9@wHzV(1R3=Z-+v+ys7z-c7NiC)P!rO}G`7N4PgzSC9X)_yYDiVx_j zf{MFf7mk<TXxaJ6XdztaS5ep~=N9UwYG!ss@lHIP?WK#D%w~hwzTVt=uN^N>5&V2I zY|-_-|M<MvTO!_9AI3etaXX-p-d9qvyKC<wBXnVG*u#SxpMIozNEU{}KT^bwpC(nI z0V;D>e`)HgM^9qRgi2js9(PF*=KKbUR`ObL`=H9+VkN-?8YaqDr=ll<L~B4Bi_xd= zO+*I@UKJ&4IUkORw?!E{U-JibC{HFFunfTUx^w|vaM$OZ21mB9$nPk@c3O-}#KHh7 zYM)6@#(OA6rZ3c4x9i{V?46Y{(@+9k8+-8}(hP7wG7m60YL0rB;EQ*nejWy~@H3E) z>{8Qg?x5(-9(W2gt!SO_@g<XeD(>Gll)^#q@+$i^d(YixE9WThB`Yw0nP5Lp6e|;W z-$i7Vg2y3~w2V9vt-{Z`dS6%yhsRJY%hWNrLPHARd{}cE9nWLbjF(prDBG%0k0e}@ zT~ZR=kpNAQ(6^@xhYW*4K6o1-(&oLg9;+frdzKv+2D%kN2u>P&5#iZ$IzbQ3(=*x< zu9*gV6&wbXc?Z@u^a;3m0nN-90td};v~&lqAMzybe9P}J-~(HV1-tN8BLHpymCWd9 zzs6_2#KH^qyW>n;Ch)%kcZH;wF$l^QV}SvojL${`gac0|xu1xjkWS>73vU+E69aqN zD;gnXBji&=C^;?YpMDMl$Kwf;C_dRUgc<}o6D0}#Vxj^rh}zK_E<?#jaDv?F>ip0r zM;8u#a%;^Bh(8n2Ub(Vd4rug^QP>CIU@d`odlZ1XM4UK{Np_Jw(wjGq(NH;XIoPr? z*fKz5!u?LQ@8=dmD@vLJ>1Y@-k|YNO2EPlTG$<fVH5J7#1`5M`S#fZ{HN<w5Epavk zEm=WQSqR`Us9i{dRD>O}aBKchg~TLp1v!fTE3lAW({}PJcMV`kiU1rpq7{j2H5m6b zD$;ql`5&;7Z$f2S>ph>To8bX<<)~H=&U2YDdMeFZxDr?)n$rwhO=WsxKyA+g4j+Mf zV2-+1nP?u6RiK?52Qj07WMDpysTiQKpR0K`V~xMkTGXk@ZNrTu;vIHlrbKW%nn3kB z3s>a&9fG?Kh{0G+c)wYbmrW5*1RBL|Z=wGp+b329dI_a9o7@m40Azmo;g9Y)dXrvo zOMCBF#J}g6NWexnqK|_j_kcD3RUyCOIRFy_J)Ir-bpNe0IuE;cI-mP=9cDjGb!&Qc zzT|%S!wb(HxcU?b2Gnr}M5VCL_VoK-mC3q82hIaty^-%TH4Byo(VOQsoa0PvD&(wQ zL0T4d$tN{?eql$2G|DPSy#Y8hkOgWw2(HNARdrUVMIl1yKwzm7k9nVvYzA2~N(TUT zueL$+3HKa9;~3zV4n8>2m-mk>^F%quj8Y3yK)dyZ!B3uz#=K$0yx?)DvY_?uL1$|< zE9&j(`0AarX@C8jz{gu)MEd8-+iI!{BPR8F54;`*sxOuRXX7e?cq(M5qBvGKbc(G6 z%og4N2mIcurDa6B=Ex$T5G<CDoO_6aB^PKxdZEi0hdz{3x|J`7LWGoigJ@>{_{N7( z_OQ4i$G!$w^eG#^0Vw#lXaf#y8I}`N0TLNwv1l{omP8VduP8Pz{DVSxXPz$uR!X-5 zMLEAwgtB|!)%HdJT@AY(!bfmRgn~xD>&~Hz=BV;O43cA@6qGH-3t==OZzMFKFyGNa z0(eX_K764cN->Bc9W6s;3q&EJH3oUxhyE<u+1(<rMlh-n8gqb9rl}fArx2+HN0<Vl zMN0_8F%41Rsp0W(wa|g%A5;(g3xj6h>+vB)Ij&AS4Fj}>ZMebpgLcnlBusg|+gVKS zhrnk{7uhsoxy9EH^wtqJwa8Y&FVb1qi8fiqV$8rJHsCzafTtlgz{&Pu!{`jMQxk9@ ztPQz`2{N^bA>2uq4c+5nqo$R7E1EDlpp>)Eu_>(i5R&<AAbNk-RnlfCXbpB>+$SL) z0apM$zw=xb0gh}6bV99Y?yL&JhxIq|FQO)afu>zp4RTzaKPEoz_!tDlND*;3INj(~ zO_LItiPWUZr8*?gp~z(e<{`*Sz>JTeu|cCo?$prRapwZalo6i~(0{ULPw72e>xd2; z+B=pdXlMSUHJ1U80n~GJzT3<=EEE6)N4ybz5$M6w9^)%O%whmeI}arY2<5XHqD>qF zQrTKGywPY+2;+4tDfMAF7!uGn@V?m7G}s~`?hfPJ4CE`bz$l!bO#*Qxf>G&)dMUW# zan3KPpvUK#q)jN|22ek5{3VC2|8~PK^hCGk8jO<j2hXC>Z+!G*$YSGh;d&u396|*W z1k9l<^h~9@cN7_u0LlsDXJi=5aFs*VI2}?4Kr`S?!({@+{>P>S9?tWS!Gw}5NBk)g zBttU$u(IvA2n;yBSraHLM`shc6rUhFA{>SGs}x%n6K#t9Tnm^N1riqj8m50HDhgWz zHAM0bR*7iP1f?P(@^rtQr4pzH<9Xx57H(OYnGX*zMU=DQlrl3!!<A-opupU|nZk6n zt#;Xy;&;p30?TJd)PmB0r2Vi-Pk7+*n9)dnBkI>{2x|F-7_$V7NGwHn^}KvHeVOR) z{P=bW`Yhz5zJ_5evGF*T_7791?(KN_eD}Kkd#g8)rN7pgr5M#7%iaEd<+I=mQ8>X! zob-EUa-H3`Q;f)i_f&`(-+a|}zI4SIWx~9kAB4(dZAYtDTsmNw-#qhI&aPVjT1wE8 z3QZgtGwFuq2^wtZ6#riS0S6sTsj*WmA}bd8JXO-0&r3Mg@sn}UDshs8r-%)92jZ&c zp|#q(!ex5uS)=&n!6e~|Q^T-{i1X19=~9elh;CEMRpt?X>8h`k-+hDfjL-QxpXXe; z0bt`0J%W63u_5KE&>a%`qpQw!Hm}0U;8*jML0WG6UkPRQ{P4wXY3m)<$)1YY_eJ*t z3jiv7CB;WB2~+`l*IfC@X&XXNGfl^@$QyStwS~lc;Vt^XMDTwT1B!BWHz8J&xB0qp z&6tTHYX$YzAthtPoB&}bG6jjY<ILo>Z+6y*cF?6BrCPGtRf;VRiSn|^05#`6`{0Cj zcYPGb61JkAwED~ZcNL<Am!Ty@hVJn{dD%4jHPjN<IuCtNl~y6N@Jf9UsZ;&dRU_ID zF^T)<`$ml`3oZxHbd%j-9y6U<FY3p%3OVb}=_+m3O}6Vx15&ZZ2e{4v32ndxXBlW? z^bH8|P3C?`+DbO+?2Uz<y*Gw4p1pR)9q<{bHVNUs_0AlX4h~j^)()d5l4_%+SpcmV zofBMQA~ZCOpfLzZ{~DpQ=I96GxkoWkEH!nKDO*StW~(HPVf<zuUE*H^bvH83RL6vF zFp<RvP3IBeBmlr>_jy9pmATZGH%CFTjC?`{im^3AHjM94xk(R6NzD@EI|-5Lx&u0( zKLSLNY-*gNV(}&t<XqGtlA`MK=96C_r37=-;jbZr2bBot#kpOLghjMTD+ui(!5Mah zGtTqXD?k*MAj^WZq?jT|dR@QUEH%>_3<|;btJ6Zj4r3k7fi0YQR$zjUijoYS(?k&7 z2Xe=A=3!(AB(uKFZUll!I4+Fs4Z#)1`1+v78BB0Q03k%1JXRUS&Cv_k=qelLli<!{ zz}#We2}+NKAYIWQIuIl_&?UnQ%5Pv=?lR`%GHZ`_V<fbZO)c^Ho1}OeH=4gvXoNEY zZiAawoB~^gBO=Lm37tcDNlCQwM@)E7icTmJ=SzG?tSnpss{vgTa+0=>2$1+qF%~^W zEY5Q$0ahZPPQZNHmc0q=H^$T;TSlA3yJVv2VsNV@1wMu53i8ZODZ{>84QL;$CY}-L zg;h6LBqd-mn~Bu}K!lb&!Yv*-js*aJMYzV5Q9`;4P`o5p9whM;@8gBEg9crP0t|+r z$aWNXl!G1`Qrtdftt&Hxc76n`g+2!ZkF%&;eE@Z<30t!Q<+K~wwT4%^k%}UihJb9M z%8Uz=Kq1kHS>_5{4?=xFwtqQ(BSq1Vah)S<_Z-E$hcVsgXxPl=h3i4T%Lu<BD_6Qw z%8o)PezxK!(SQ4jc;kVA7_|WSAp=6f<{GpYFmNyw6AHrQYYeN8)-;<()cI6i#PXXn z!_I5=HF1vA&o@?JR`7Qgy3Vyor5)k6D_1NwReH1RlKeuW!t+rbj+88!bZ>rWlj??! zPrMcvi_%?KVS)G0>lv~K1*yko&iJU>rDiPH7VJGub{2`G@w3nB^AEDAgm18oI2yCY zvCc&@&PdgLl!VLjr1|EmZWmO0Ed>9#&etrzfVGo!vOP(J6(C*%A*n@Z6Yo`-bk1eU z0IM2$f3h0jEAXo&glLXUnzryoZKsfAe~IY^dlp!$Uj=O~{I5h|uPQ<z9jk&)B`z7< zAr~7+SVhRTF<P=EL1^xGkss`hh%jIW5PE5U5uDU>a1pVJeLJjv=|t~ZFW&r+VZPM` zf<v=lf&7$>K28I60j|*@UuiECTr}PU)#mD-yy0pfBq{jBE}J~^nM<j}T>vOYjg_)c zC<nJoG*I4MK9Gu`!~mw(wk+4R!hNqnE(RVJ&|vGr3RnLGykAakf#AF)!R4|&_yRZt ztZWcaU7v3d{1Q53;hrZi!~OF5Yv^x4J*jBdx|=Th;c%D`g6myMg4_=NMl|&|4$e_` zS77s&Y(AclX4xQjXga=cN1J*NgmQaezsP5_WP!6Abh*Z=n}8b=dW>wi`pe-Y_+)yf zy<z0VUA_9v!jt#{DE+{N)fRtj1vB7YkvKcx8q#r*^P^PF%xNrhgQ!45Qo@@VQhBhS zRK4|n-q|$psq<Roo>*QZCR%gUD?O`SwTK<2|61Y3TqtY$3P1}qM&(u)3c-X*{Lw(n ztN$d$`%Z>|-^94Iq2a}J8fzn5;J9+Oi|m%9_$GZEUdl5=7J&G|4*PQ~gOtT35WP~& z{Hy>?EAbUPdj@()ZSW^<-2$v>ksH2O$$1|uoURN7Q|B^?y?55Yi!mC40LnV7+!6x% z7{1YlT}pMv-<kIj?YM|4lED&rjR*FL&F^TC*i#%t-mzJ@k838u0roaHarQ&Y2uKCu z!kDa!n_JsX|7kLRYWH?Np=eKsDP3=#8kktViJ-S5dDnKUIL>ouF{j#9gy17O9B%Pq zl0D^XjCia8|00I!z-q4+17G@LVvoB63E10-Dr_K&yYV1HT(>bO^TN9CAY+7l$7ulY z65%dKs#K9405<XLB-e}?SKnrLq6&#PI7$zcEdk_1vORxX7_<S|1JX2Su>dqAM1sKW z++y;^<)nw^G@lTNpaLNpe2Fw`e6-HZ2MgLHYn7n6!EgCK;`mDy3q;fZI_PYC4sG=D z{!OS_L3Ill-{&DBO!Lcvvi#UnZZs&-JPGEMSY+_RLdtW+NEiDNaLKPjD(hqStHi7b z5t8jw@`*DK04UP$Xzli&_Q-Vi_U?jyC414|R9nw(Z<*9@YQLbLdZ~J-P{dwu8moO> z^!r<``tNASL0V(zhNuGFk|B0nWvuGorr*J{H?Fw3ax>OXbYyN&p-xvNR~=|Q86t>W zW~}}DSKyXQUKxA4TQrr3n_<lDbw?L{3YmRRkLIlAyIE)UFE1?~YGVIeD6;L9d4@!j za5OJEWtOn%rRjfRTUoyRa(8&rRi;^ak7@4bjrRi@Nay!cQaab2kk>>!E7j*_i@8T8 zYNB@W4DPBoP-=<!z8}$^m45k4TyRH9$9uesq6^I12GTLr<8-xajd(c2Sa$(4x#5+` zMHSDiOZU<<D=|^$x6t=A6RQk6CXIWy%4@Q}$`02#_p#%lJR)-=kFuym`{k-Z?>82~ zys$lM;p8JTSr_k*f5d9CH&#Gmqg6~`(02>++yle?3kD{6AD49`jC+QlfAmDN@pG*G znIvT#*aYUI@RHu!MLM6Sp(!yZFQ<Q=VxADtGoqPyz4RmlleuMoWBuEIZJy?j{j&Sl zUA23dD=O=ZX2dUA40yu_?ddvydfDvmoxCGJLm2TLa$IvQKRU1=?XT8s$00fgZM1}O z{P~jCedl4pFL7_*Kwq#s!r(lFf)G?5{MVnhPrq8Afy`FSbcohYbe<K>qyvhfA#L!D z%ZIw0P*-Tn>TV9;?$O6}VEXZ7rQcgWK(Z`EnH}BdnWTxkWbwa<n2^j-`?|u&`n{=w zj7Yxhk^>uq=#<4D{k*Hwej4lZr~&gkQ@h{TT`%OSwtAy#Y^1xBvBS6T2((tmavOWb zzyAn<JLEiHwdv3YKb$za0}5r~5FncZldQCT@%JC1{o@EkB|Ti&(%Dsmt2Y4g;c~`C z`ak51l64(qnY{nZHUc|9uSK3Nf|mdJ(c5J6fe`3##9&#j*Os@p6w)G$qS>=mSOLi* zD6yM4lf;F-8*96rGg>_Kf;uw;?P)&-2WVHTu>B6yfsji?L9G+=Zmp2Bv&dJ#M5qKE z#Dm3&N*zS11UZ}lL!)Es0ifeCzrgC@=a`Cvea5cJ7P8__5K#dpRH$5$9vTEMG8wyl z3+9!vm^Y9-^Esw-Woo(~;I5fahP}{;;nHlyk|{TLC7vE|+!ISf61E;^D&doPI%j?- z4*P>%Ak`d=xGH47)KSmryxBXl{m(PLfZ@n6N1z`)H1rva6->nbyM35Zs28yW4UCDq zNFhvQnsfq+T%SoDW{L!VoyN=^5T6SbWM1_E){npy0#@SDCeXZZcF(zuc_w*W$VM_1 z>c%W955y|FJ?S6}>LA{P)*)Gj(deKMidDfNk^+{zCP5c@V<e5;(lWQDNZu*X)nbRN z<gLa0i&!basGPjp_{MoC3o-;dn=7!^Pt41?nc)zCPen2%Lr^4LLj8b)whfs&AWqrO zl|U@*>boWrtz{eIeZYExiy*&4ij2-V9GXXw#{`jI<Ej!lnD7!kuE%8_+H^<5b4Adp z77#)OdWvU_UcgdYJFxbNAqk`spn^?5Zr-Otd8_uv$#Ca;k`pEPSqWrq`&a2vHt}E; zy-Al`ugx*(lE}7ew~&YcR*KjS0z&e4qsc_ETZ`UBC*+X<8Z7A<4gP?KL&~{92B{QC zBrqlU9FpVFOI-s8R!r$JUy!5VcNnphK|CqLf|gafqZyeW(~iie5VY!i57nShWG1V& z0CV<>eg8%Y#efY@KJdZj_j&Ypy`+DGCSi*n@u`YL%Y&t@c$5$r8niif<;O7t#(P2f zgQ5@FAsQt-<6;1FJWO-hh8ye&XlZOCa!|eS5<GGNw*{E@(SSlYU>@sPbK%g?eW#ah z-tXw9(<|;fi}ZX<)4$#F@&&fNy&2+ufEd6}N{s&c-wI6Yf~zi&8ODi{ja_mT4<2Sl zQ1e`CN&2mdK5`aHXdrd5s?B?+ALQ+FSC&3uA1WrEL?g%k<ZnaG4iKTyf7hDZW5a}> z)-N5^A|#W^P&_+cUw~1n0rM0MMp`MT?y(V9kS_7bwk%)l(_mE=8HZ`Ad@puhmUypf zd^CIY4qTBUe&+W^@Cy**ZY+5rK5b#?VZlB;7zAjxzma>15RLtcQ+js{2ci#SvD;#3 zD+~KrT>zcnK`6t3NUZ&nUD}mGFwcZ)Z9$KRI3q&`)60WFQ6#$H4JX8j>K%r8?T)%+ zR|{6kAcE7n(&%5w5<^+)5AU*>Q}b(P7IeeneRgG=I{aIc?zjBZWg|flg5C-}tL;#b z)EvgWNtlb(L3BSkB~kEcJ*S9PX%TNNL{fxiz-h~;5~1-y4#TAI&>bbFJy24eMl$tF zWyoG4vz7p9qJ(IVrOJU#W>WYUQK~qq<mMJD!2lq(;3?A7{DS|)JDyi(3TC#U9(;ix zI9~zG4i=u2k+u`y>;T%GV0e(XHv6=XC(4MXGdcS2v;|ehX|b$|#e<~$5w}n#z}Wqb z5WQf6KFwIJf0!~8xbI_}Ge%ZY^M$ABHRy+o)y;<99}~;3VMzYAZ5IX%&yDObb<N`a zp+kqCex8UCNEcy5vm!r^h!#WJMOdwFh%}iZBM=^Gg}1H;s7l5T_MQPeWdI~;m-)li z*>=%wQ0SN_H@kXs)TxT(^noSxkOs=gKZzO=-4O0@UWlq;3)8U>jmcR|k$oP=6!VxD znjDu2sE>-W4$H6{D60dShK45)s)|_UY&AGyM6+Z{7_WoAsYn+MM>51J$ZQI#P7J$T znajAECQDH0K-q$i6`t^VjBVDmmbnFqY}u}B2k=~yDN5*Q2)r4cbK~s(<%977M8;h& zpT+|w@=(qpr4YVC2*h}ST_0FO0sM~A)5St;W^Sbv2SIqcOwZtHS~0lR+VZyJvD<6+ z1Ab?*^&ca@M8X&IAS-{~4Ud9pjK}{{ZUn4;iaO=%xlJQzw5(9X{#QAk(D~tL?&TA+ z196IR&)`R}Lj=hTp2Ky~_q90XpB1qO;<_^0t7Ln)q`6R+^b36aLOTjthM@RU5ejTt z4rHmu6imP;+w!j0;uPJnWn`vy^6E0KJTqJ8_+&Ynb4kgch<L0UJ#VibhfJM#C}XK4 z7Z-kd@9fSR;m*7NHY%cJp}_=&XmXvuo_2$BrBU{6)^}`Xy=>Bn*$_sWAnt3ceb){* zr6qr7nU%JGAbMhSbGknJ(rer9an0a|$a+7ZwPbVl_9LI|TGU(R<bIO?+%9iB1K4#= zIUl<8OvjP?9)~XcG!@2PzPoYN)~_(w5Ux3YGZ^Xe2+CE=*q8F8o&s%zr^hhnJL>c! zM?y%`d4g%Kd;k6P#_s322U_Jn>@BI%uxB5s6%NU<Pl$c4`t++m?%Df6O2m~@>1hTJ z=U0uyQ_Wn(*72kD>9;URnDzg2QxhgBax3oLfGSMLn=09h|9x%S8Tmb_--V7hiEjg$ z&r!qIf<5@^73!DLgC+jpp}&=U^RM@t<v#DckpWO43OTR+dc8!$ML~vQBiuN(v&Mf? z2SHeQknNS+DqvL!A{7<`0W&DzdXuWqnAG6B7+m3k5|qS^Jv%Xjv|Y)dCvn?#cwc2J zgQYi&Lx3pI{F(t>FyN9%3s6;HoIJO;!uYMr$u={Rl7HP}A6Sq4-3<Idx1Ksg4|GGm zAw^!VOM8o+;@lzG58AkRPTqm--Sf-Q=mAYV9q9|kn;U?B&S8t9ZF@3WQQI);oAGqT zr3LJ`U1S^L=DC@pLHWdBV@Gk2hprF)cLPHF6HFbddQ({oJ_#y1J04f!Po$-TiQZ^j zF~cgD*J0L`Ee=LTyH^6CO~6{*;*lKIT&s`#-9TX|Mv17=U*|87h?DjVDfWzhU+0$r zN`w@oDxJqX%K;0Ja6Zshwgd@9fdO`mlkCudBnJ+&;Qg@HBg)5vm<Esq+#sPf3j;x) z{MJf8LFTt@^Zj_FH`B`4Mv?%#G{zb(QWKCuV$pwnyrFlYWG|)n-@uyu{Apun%w>Ar zL4#BLh-{`|P5XEryrJs`7)uDkFgt?LpbG<K&J069M6zoQ7mr^9CRW7b`5I)cuP_WK zH-bjf(t{~K9)E!3?aGr?{A+&T_&l)bv1FXTK023VEi!D284X3$l@lm}$%@O+dt;u7 z+a387$QH)=eywfS5Jt5S&SOzr6f6fu@s{lJMDO1~&^eMlhWjAe8WHahlIg&~HRlPR zwHGJ^zLXGjcqvh55qcn5=raOd3L_Q(y}`}yz!Hc2%kcz=(P4#W2-0Ez)~M0%8bai2 z+CZCQwfL9_I;mJBQ|bk90P^uINIjStVu=|$SLfwzCm^%4=KSae{cj#>#%>=?^9iP! zNU}is=&{T?@KM`w;0Zh-?rB=JNn<r{c7w<O2S|2Rm95oS1qJ_2Xiz*WqJcbGNi+5w zg0{T^Lvx@(Xtn*zvGH*exHJT$PC}Z<>b!=@4cdm-Lg9uE2p+sTK(g+KAFc#lbUU9* zgd~13#^az!NSwSoP&4RuUtp!p0h}g0UdNFPS{AIkLUMF;zs8lxF}IfinRF^3?i{8N z*-VJ2FF~-$)w@&=x&niLg#>#vF;hD1?vX%17&hHina9gd3-1qB`kp!sP8{BTg0Xow zw_edS5xUm|#;?Br<woVNXQQ6QU<#B;-V3%|JYd7hVlhmdsJVFtMU}*>UBALSwti#o zuV-v%I}bXs*N0|c)k-`u2jU8>8Iq$j>Eq{DnOd=qUCui=pDCe;{ya&@huq^g#=0=> z-**&b4e16@(5CssgsLINPT-K{`*chDl0ZDX2*c+t(wU4LTO>YuDV3Qv;6XeI68M)Z zw|*Dvy$j2|bJTYjN+P-!7LOD(Kv*~rfkN-#?2&f(4g7{x^2W(LHtTjdyYv}MBS2Is zgi*XKF0?98)lap{SCYElWLX91{*QJh1Sx`38ZBL?xsFL6CeaQ(CM412n_m*%QG{}p zv&QoI&7h{6sRHM-Dl^J2!e*_!6%^n7k~BT96uw_uT)(3U6eQ9>f2os@&6s3K;CYaZ zos(T$&X3!TNA8fx<I*(jGiZ^0Z9}4B<t4Sw3N>!%C;(479w&ISXQ8VBl6Z9tiAKS* zwYzasJcVrY#-~Hcp3)fdVOGFW9eN0ZZOC!Wvg;n&#G$6noPH6M)U3#n9T1#glM6|H zoks5XIW|3H9nJ`Ev+BCEm$r`5-(Zzzj9XqDCWoLHJvdVI8ulh0*Z@#PrZ;e+lEJg- zLL4+ar@mMpTmc!a$>+<qz3ar=g_v_3@>ggAy8c0g!yvcTLX6f|ZqbfZ`WzqJ82-Vj z_4ITuwxb<a0ZQ(D;<?sUAkCB*G>BGt1a?^X*TRGwpK*w<APp+QKb!u<b0y}>NTUR5 zNhYw<&=U?%7^#fdym6J|tt&{;DVXR?=l^M6LPv`tX6zroJz;8-+R-9!t-O~0!mjV1 z{xtWt(8n)hp0yfN<0mk7vO_ic-;#{i`XI0<hDc>QbN|P<7JN#j-;Per6-<A|hXeVI z%Gq}i6v&=D@*v0)#T10W`EQ7NI~4$qg27#o(L%cdCXP&otMTI+*Sc~mTAD_xh|_vp zgeN5ypQk_;LMz~bM=IF$aA1f=BE9A)UvIKXiibCGCZGdu2jz!ZI?Vm~X7^pu;)3FL z%Uv1h`(R!HSn9q~aD=X2_uF7~ME!VRsVtm<dozKL5RrMT|M6G`SB$}OfB@$iR2N5V zqs<GK<e`6sZ}lY>W3E^lod=Le778d?ES@040rJO&7}RAA8$4YL%F*M;%1WaWfR~Jl zgShj6Rc_o8Cax<BaP9-4u~0Noxfw1KfaFtg)UVwAh<aT|79Pp?*lX-|$fh)q6S|!o zN!Sk8cQn3zbYDbCzRzJa#TX3KI}GP1PaNeI>5T6nRO{rfH|&o|<ROYG856uDsIT&b zo;=r5OjNPWCou;1$>}=$_GNTPME^79$LYM(djjQk!_B7|tx5MrGPc8L)f->lndtqA zHPh4LM18LNzK#p`)4r|xxx8?k-M4-Ts@S+O&w}Ci-=+S4^}nEO>3;t--0Y&!^$TMR zgPJOrzPaU=4l_psX1I=Pip4{y*@oaVKkq2h?yPyI`vo1x$qg@l2GqED+z5pHPNLMm zE32_E^#5Y%Ou(Wp*Y`gv9<}9=Tm3W^e=!J>;y)-CLPt*8IH(P)xPVm3;gFVr5RD;Y z+DXxzi2)=u0of6R+)~jbTf_kh1zZ!C*g-`GkZorAf8ObLo$ESzA<lf4_kEw|xu5&K zpT~VgN4aa&mKtfw!ENAYjp++S1mG2}t{?iaIM&x}`1BE*vK{Zl#MnHufi4QQ<kp}u zlM*jB%7w)3#^HMv)4@wDyKn`4{cl$3n+N_BD?DOy<?>s1JICv7>)ETtbY0FE%YK8{ zF&i@R%KgV|5*vt`HtMIf$2SOlq?=6WiF@<hRMXg!4PLE-@oR(@k>XG5Di(3eQUgn4 zW(S@AI*)$@YfX#!Tfxd-RaPBI6;;Egb~yUsUy{DM>f(mC6$^j%gs~+ui7Q^}6*^_F zf-S#aO~DqjZN!s>9rNCp@i(efEbgghtEV|MaozBfg_~#pV*kXNcB=g>rLcpcbI&vA zr+3Gm#(4y5yBI(3=k`Wcl$#IGD6D|qlkv26H?Yox6*f9mw8RT3{+YIPgdXP%ZG=Z! zlvSm7g^<oowfPlcZ?Yk=o*dY-!y2jz|BGG=`bCzejYA&NFi1z#;^g93L1U>Yg_FK0 zbF82ZP6QOEGi`4=Q7C#_-C`RSpyXIerHOz5uz9FVTQw-d1&dAOoYW7Mf&OXN!cWEd zBNr8$fYrl&2Ms9I(u~nw9;zsx(P!`xt<D<fxm%F_1)Gf=3v4WWIpM`$RHR)FJh^1{ z-QzZVbk71(i7to22KF~u&Meteh?#Vb&S_+#3#~VA5HujVT>x&hCRDtgqD*KW2><+G zbkQxc9K>(~X!yh%w!hR5k*I41uDcp-U*uI=iF@@eLFdaBRVT|LjPn{<rf&r&0r6=I zLX#cj+{jxiQBouiG!;6Jv>pmSo-I7T+;Z5?-f{M{ktC;~GEloGI8e;95MrC_?a$G# zLO5l~^)PQp59bDgxo<$H#sbdBbaj+vxwYm$ZX2=Rz*1AElK2)EPT<}IU5x;%V~dNU zG;C~o2=F&FQJ}ocgI0-yNzhKehCT~$ad&f%ONGEL^P(ron_zou^`_=k<n>CHP*;PX z^77$GDd}40v;P|^hARb`LuH?ez=KYHvSh$`hS;B%@;0w87C9aJGCnw7wBXwhNdh$1 z_{!3&f~2n^{_Ot`2;y!`Fm5>lTY89Is&GG*T6){OQyaC}kgY4Wh&IKW5RKO5ZPR~& z+bX`*S5ME!Ye~W!{C&=_oq><VJEx`x-`ze9606?PE|?m^<PJH2mOOR%J#l+Mi>BV4 zf>8A}A_y1D2jAG7yM{svcL>tm_{V(OGZjvMWb<(`^)=gUi?;y#i0<I;-f3@+u&uY_ z!!+JP5Rjf8vZ011Y`4B8aNHZA$Pd`DtL4svzuh~<u}@(GjOEdq1B727J4r2d-M4bd z@B5b(G?6I>=y*!VpI4O@LaeT%0`sjXlso#q-G4h<G+(29Jt@%H{O|u<DECto%59ae z&2_qv)Zgd-`;iG$mn6W6_f$Idqoo~tUI%+~)4H9AZ)mQN|4}fqH_De3`-to#s8iox z`A4$Ox0T1Y02t!mrth_<6)iq1e%t(iBAb#Jdk71%kFp=F3mg5?d6Z_w_fBy^u3C@n zua|Qd3mgm`@2FdGpWNo4hx1<Ro%HA)$>voWZtLzX69kEYhJSB6qCLga9?pE$9FFZ~ z^ELZZ3gx{;FB&TaJ0ei9B=UJW)Dx^>$LT{wG1D(M9zj;N{SD6l6HXZ-w^*)IiAOkG zx$rNEh?ySHH8ly+Tdesu5e6j++qcadqAl`=%u&LAMnPhy26o0800VRKw`|=41129R zyZk-NGpaI20le98^8VqGVLn^u03A$_HswPHbVX#@ME?~DBIE;zUv-FZK)R>{GHR)~ zX$~FkBlD>EOLEHDc|wjZJCS2Gf*ZTCLQlca1t%@?s`MbBZ7eu-ja!Cs5@gJt8SBL| zl+cTDHhai4hcgdaXJNs$m?CAz7v^W!O%zpT6V70k)sh!^ZPgeN7W(2tCh;NC&s-Mm z!|#@z;ONv{2NV-L%CrGgPV43kWuNxrV9G1%qHG8q+sD^c=R$2p?SyONc54iTSWt)9 zvTQH`Sj<&Y?HHhS3#5%g(?jF2|H%DG10C}^6fR2v|Lz8!v-SRLit#e1iPjVnkS@yz z8-HbW`<xTEKdtblUf(M?sp0oZ-Wj^I>}A1Ej#{~CqJASd#KBi%gKs#{-UD<9?&iGt zOY+h7*D?*}23#%7TKl2Or;lFsUe@_PuJ<)dIel?D?&49-WJ!m7YEBuhDrgiiP-%|w zCHtqc?XTZNTVn8n0M;TGE<eD5Rhbw34-e0bU1Ot@=Uj|z;*_!vHPm|i`owg!{AuYo z2R=M{2a;n+7rJ=&;)6%MmlY)lury78!d&&Bp(7u%XTP?(c;AYymsC#_(%5*rx=mcn z{-{-YgZi{Mqzz7~!H(C9kp7Lw*@lu+BWpamvD6h|kro;~A80=M>N6_{KPSX#0f-*4 zacc1ktMpa`i7J43vhtLsvPtRxKFxMD)Nv~8PrQ-2QKy=^$<oAY<OeCg4E*~>_0C6d z1))Y2Z>zOlbe)2=k)<P6W)W(nl;3K`q;Xd1%Cs-g6S}PgE!x>s@{aN~!PfM6)+wof zONGIIVa?Ok#@`a0(wg;V(^}jL!cz?(M^JVexsvpZzTdZx1)$)CyB?1Tb$`ftcdzn> zIFplN>>oRc&fDd-$$HQEvd6PH5C4+9w65pLCn|><&?)aCaxLz8^~dw><`R#mUH|Pd zr3PAHx@%VyJzqfEiGRFX0LtQercs>;M*wv6=}>8JUD;q4r=vwg+F9607>Dm@XakAn z#an_n35FgbzTj*2VceKF_=Mn`>U&=Iw`c&be;TYASXz*0Z{_mO;5#1<7iJu9D@eSj z=0g%Z!$U2^D9}mKFFR&qS^74g3HR4B2{jf)L4UFm{5OLD&7sB<p+_d(2um--Sz@89 zRAtF#hY7GOS!K_uDXwn|4k|5}UHSQr;X9*Y?JOF9(MDZ<gk6l%Y!%ml;;4YH#lY{7 z?LrW_W!NamP=cdwRE`l6k<2lF;FlNhlK-GC0QL4&T+M||ra28k1Eo3qwY&6s9ys4x zWEDkvu&G1&nu8{TgfjXvrlPlnAx|mESjzi#l*k}4ZIC<?>)1R^nIi=8D0Z=(Xbb>% zZ~$i;xM8l$-Gp__!ue!4mAcpIuQz6n1;G-kjMeq@nVhholf~MSQ%LDYLR14{&yx!r zoq~=a8VipXF+2|_dE)z@HnB{S`6iW9+VcF07WUhR&d%U;z~h#eFtd$cjDcpItbjUy zhVLT4<wVQ<c!!>J)TBVc_>w&X$!`J%(C*b{Yq(}~pM=Y}XWKz@+LaLqVQ@P|2!l#| zR#To#@R`2L98KTJP1#V_$`{1L_e8dhPl)iyNOVCS;lSht7xiHH@l4X$t!mL>T4ZJE z27a%@?@!2=!Cf;<(b?5F{b>OMi6QCq6jfpxhHs72t+v=6=aJ&4t9fR$ObeyMoLQq; zxD{rTWMa*58PB<p+zg8nQk%O0k*o-)G>%p`MMoJC3=bzg#ZO7?BumfMc|2o%_w5Yh zN4wjxPO9CG-zlG6k}S8c@vX3liN7Sf2XI@IX}$J|^)51^FaG`P*;z7rJnqGtUwUh} z94Z-{5Sy5e^ndE^t$6ZV&L;;p^{da&@|`EzJnC0p{xv9eYw6H$&nO35ZP?Vu&K5qH zyYe{Ptj@U)W#>y*aGy!$MaNY!ejS&V&ecy(BF|?3`8y={+?qz$k$wzwA|C!FIVQ;R zO%u77p4#2LrG$aYb9nRZheH3~*?+n%b(uenM6&Zl5}zn*dRhJy8ILq7qWoO;H+yZq zweO^`3DsSiKaB;jrgqh3ow{O|X_yd8Tf32Q4eakApNPtjX&9y<zbGGS_vJV%8cHcm zjd2VDEIj3Y%rB?MMg5&#eoLB(x_`X+alV0TUt^J6ByZclw9R(+e+n=BECuQc+xpD3 z{A=3dkY7y)$qLOLF86M3Ad>sqew7{~c}rm%YW@ufuCDQzZoBg!ICGKu)^Q-R6DU=v z)F838jZB&SX$Q9Ea#4CIAKu~sDFHO!?!pg3T%x&Pe?8W;Kyfa=Y~7SDDs%k>%ld|4 z0|>fiO$7kj^-U~uiF}EDM+aCRk5Khid72#X)Kl!cL(n$9p~(}iV&5zk+WEy9=V<kq znyp)WeDLQn{GR&A{``?)oZl3nyN!mXEakvJHUcdBp`RB44q;e;kG-!=ug?e$Td`ev zdvaf6@5J}5UGwogaGWKhIh2`op%T+LKe^)sxquky8^hS05U_dCa~h=sDtLQDv)Sfm z#bRpyD=T(ZS%mG*hn=7OO6TE3(;V{#lye16njJf<vb>#jJ3eyDSdRR`<C(FI1;%p0 zO64T#ORRIA4wQ!tG}*a}>~TQ!q*Y1u%pok)m`k!jGvpBV#TlwgaFNmX2Tj5|pg+cj zp#m%?mF=u0=91jP5o`m@$zo<r4jMrko^zV=A-l(!Z5<u_&s}nZL;5&$&cP{<=KLj@ zxW2yl(fu9s8Z|Ow)P=YmifJWXKb^ilHRY@QaMxa<^&yv$wY#`AFPJWyh!L0DQc;Gb zN1BF?IqgP+M<r5@TDw~NI7r)Z`o>fD!3hc<#h>Gh+CGC{)2rY14IlNcy?z7c9fd<< z$+{aAFYf2)5rOL-Z}LysX{R!UOvMp>eO7OJ*lSyCt@oafFdfkWtPWQm%j@`V+x}W> z^0LVB2t@l*j&78tHeXvcU%RGzOzMJtIfC3OI~&}Kp^Y4@NXY*7$6V>~Qw;?YEr~_u zvk!}BNR!lr_*r5W!$8Lh1&%K@6h9eKHCJIWf-l!tpx6o*wd=h5TJjd*WGnGPcn$=d z@-Heqj=^k)qV7Sw-Fi8}*eEYu1=0h)ZZh*OoCnsM7F$FhL8Zp|8rh?@Vt)fVG<h4W zpVPN^iM1{*4Sr&!^D0?`V40v7WNT$Ny48Y4wE7Rm$Hi~hEcm|h9peB6?9?Rm*RE^; zFXqiE@wpibVOvCt^8PmJD*D2JAerPGG{6^4psA0RMl?T+yL>DB6d0lSj8?mOW11K1 zd#Ss^k5&*zztt1Sly0Dx;;6(_(=Pa95t_@Bffq=^N4=?EOr>qWOxB<6asU?#zMM~| z!;V~4>2`N3JDI{jGX5^-Gi{m6Pz-X>>aZ7!Fjv_ja7#SJ!qyTbkTsFP0W52d5S+{> z2&LSt$LUCDMkN>>TXD*x&AX5TG@HQp_zrTsczOQa0}*Z*cd$&-yHKN3afrfmW*dhy z8=e(#m43{kacn$}SvRaMw)z4kpcLIiz8v9{hHh1AU;ck>B~FYQcT<S9U}}pzB)KEE zMHM5Skk!}M+Q`jw>;-S<TMXnxZ05zkV?Z1zXoo5#&1kX$y0S1tMC{6ou5lF)<wSps zXCkYsEMP+XV-HFCC7I0P!vGtLbj0_f=huprg!*I&O<WO%(3TU-sMc}i9)5=G5R@dK zM?#L>7X##Xwz0s8=Y|{i_CnIPeDG}EwV!;<P)%2z*w4Zv^+Olcb~3amzd-#oEl6(x zzXDd_TWMuq;a|by3kJ+j0~sD{4HzXjpysXk>q+xCXnP^DKvK<8VZFgwC&)zfZd_Dc zO?yr<cc`r*0RS<yi?M^$q3)~W;JGrQ8Cw@aQD7Poh)9gs>mU@DG)MZQlQ_xa+YD{a z$5?ZHDfE4LshNdFi?e2t(6r@znf=IiEn-o^=OX)6aZVX#=YpnmQXPC?bV{0~k>+XL znj|S_+%LB;Ev289qrM2x)K2^0^!X7j@+TLVlL2fAQWTd_q7>dPCoI*~`pMNnuRW~& zv|<I;y|wpo>T1n(Q%;RIHki?lO=oYd_mj<c74oiE-|?HD^I22;>sQw+rVX!wsnY47 zE2wF-b-LWM@P<`X&~8pHR!O^I@V_-5kRntl=tG>k2v%}E;Nws0R&X%tx~fa3h%sS0 z@8H}m>COK*o7Xu(VVeWbj)R~iX78V~8}wt4!Ivl>JnXXVWsTRcK(5^g`qR4a>y=T# zd5QgBz1rnat-*@I?TGv-(o=zl6uOqHtkYJf#N}*x$vCWJ4#t9OyNpjP+e?3M*-AzB z(;^%%zu;9=XD#rqGjAgv{d+Jzj36}CFO&o2yFBm+{v-G`X=EK#_z_-n=d8a5qSZJ4 zs!5phRL$$0u5j*|uw!58qZ&8a?8{X0+2)%`B4@DuH|#FUsYrx*+%{@;Unt}t^3vGh z%WdX+(3yiHuPZ?jgc;+AqtlB#X<?v@>x=UJOES)?+wymI;_ptG&c>S8vm8%5F(`%| zc|5LbDB>->P4tLUf6vs|4>d^ps0!C!x4(1Um?WDNn;t;R=n;<f<~Z|)^e``0E;iY5 zusL8Di-?9qDX^nrs1kym3UbLZ-_5xkcuGhg;I%r%GNC!9tzb2NFj=_(u3Z%Ixw}5G zqD3|wBY>&7Qe8G3&w8Sb#^b}$<JHAQ;6^=1x;Y3YuP0A+9w{Tj|1Ty$j}v6qpAj2v zkrjkP8V72y@zwPwCq~UmA@{~*j8Q6RVSL}m5)xki)<A)glqV}31&A39sd)q0y*K?X z4Rt|HpV$v4`je0Q(2@Yo-NQrK0R^~S3H%5GC4yn*KWI|Gv~xsA6Pz-Ja7X#nP&Y$5 z+{<xCs23K-va@*X2qoq$=MfP^bM7a(y!ZF*6Y%4t30mi&IdWg&2sC92crtBiLQ8=9 ze3rK18U`OUK^6n$`eDnVcP0bCE=>?a-yL7EOt>C<H?a%~r<GwzR^wh}=y*oymL}hp z)8X^!ksA+_^fs}P6?jmw6*_ab+%7q|kRFCW24nV(uK#)|&7ShvcxgXAcho+3=P&zT zyB#Y21$n0~^SN1e3!W$ei#q3Y_NQEzAFkQB;12$}ywL7}&Lq@L)N(z)AGsgoecIN` zD&`~WhPqL8Vi3rL&nV~ar1-H@1luFT<x)z?st?xL?5Ks}cpsY?Vr^f{df%jfozcyE zL^G?Vp~5D?=c9ikA%HufQsdU6Y^|`<d!8moi5Zjeo{)q;IwY6wpI8InZmB?BREtjA zWL%)W6b(KOE?VO>l&O}0LiiKZu_Ay)QNbbdi4O_T4b4OQA$X#`Qu7qkUlNE%GRz>V z&Cm2HN9j-a?SNANaw#OrmB#tagZ5A1>c9QutMqlb)M$c-lWF}w+Uj(f2qi*?G}sCe zG!GvxB%l-nIE$$7>05j@C{afdVloDr#dsA$8|04UL81*i<F3yrVclb>%^(oAf30V8 zL%M<mC5U|zL2=ADN2}GA(vVC@5KFSKq!wuH$X~j#PvJTOmle|X`Wsyy#JW+7DQvya z&m!?+jX)rvL_N>f3jP)0&K@+rmU53#R^H%Q1Pz%OBPOF_#yDL7z_GG4s!D=quC?fc z&qBL}dp%`3xSH^wKvzgd0B2vG4*^XD=Mz@QWva3LiC4Kc>TxgxxSvOmZVP4Yrgo$x zypo=Lm}V?jKs?S9chX1St}L~i!hxOVYolI3LNFLT=%ATD!_weve{2quxM5k;fMa8i z%bIP)_8)K(iB3(Iz#3(^XB9S{qDAya9V7-#4lPVn>uFa;86g^T^w`A6#B(J9pu=f@ zhiZ3}aNbfa*QhCW4{@pOVxfqN{}8k2#H1fcErL$h?oZc`wJL*->?KV`e9v=f$2Cn* zT7r~2V2ihngzC_Wg^MLMIG?@&XcQz-A|xZgWL5dOfz;mgH1c<Bl^{jo%FbS+p@lv< zK4g{V&#@3;IIvMl&@<}$J^ve+b(T?;Ntb2Ajs)h&Ya^`S2?hxEdYIDF9#bj}8cY=I zblyyLeEBd0@$97PqXnMsg&(Z5&scN%q;A=>t34B1&6vFY3(qLHDTO@0!5FI~oKa3> zTIE6xrE3~udFQOJtIx|l5zh#g(xPXj2KX5BJ@qpTEa~uX=xZca!1Zm+Q&HSCoKNx0 zoQ(#n1-Z0&aUlm~5XHT+;o1nPJ?-4k9$^D!yMb9?V%N-~@3;1}(C_g~hBiKUxCKf> zY5jR3(RHukvv#s_X^P?d!r`hyioR{D?_2kVe(A4AT^&!xUDuyLA_4|-D6X{FLBEYb zJ2X;FjSpEn8G{o}<c*2BUq1F`$8FCoHDEp=O5?Pt%c-FAO<PP2s!w(`4x9dY<1z$8 zURoBI*1(zrsm2~n#>{h*t7EU1TStG>s!>c6oZ!nH`MW)>b1L#`JR=7;qj1&Rq$E8E z-5tC2Qm$=IcLj9k6ICU{zu2FD(q!OxWF%2Z&V22+Ai_;Y`l33`3t5>t<h*6iJ^V!d z{JUZRK<A-P?53l*x5l|8O8s0mRKcGC34T8pN=APfUshvpu}j>_*S}I}RxS%YMFP1h z==yOwg&`ZF;Jy8TGL_?FUi-eySq!bb@ToXG60h2SI{zK}4F*+=^fMri_K<J4+U=Ef z$-XBqV4}qa()l$1_A<M@R`GGELd6gwQw3HllJYK&KKfNsjlJmGRdgQ2bS(W(g@XxH zY+mQuUk+6KQNjld^in5RtoqJN@S7ScL}+P|q$`iF!XY2!Yvhdu$eC)qPanCr?T9kT z1j2B{ZRP%H>O&AVO|R$qH!_g5Zqz$;RFo}&pElj{llxe4JY}o<l5acP?${G22wUee zXA<#dwh`<-l1yRa%q5>&Yt+Nxe%H1Nx{k{0Jz{PQ1~MI(A1FAtphBgGDV_AZz-xMX zhsh(HQkM~eRxc;-?Qc`#P#9e^8)8(DK#HYA0-<x$x2YS9fCnBV0)l@ML0BF=`bF87 zyoc3J#-8lz0zokv4EJNo=&XfY5+);D9ZOX^7%oS_(M*u0L4tNEN9O_8Sy~9G;T{Zw zj>bX(y14<;;1$9`eg*}Y$^Ebh+CD3O8r#?-rh#U3v=76c7Z~5Oi6m=q$_NphwFRQ~ zdy##!pJY~x&LYph%^6g{p`b0xTM{ON8sp3#oOOHl-NSHRSx%)OmI9*}34C;uE0wNC z?t`3kIv0-Q27L8?^?p7hAg1}j(%8rK1O^lKT`9$d6WMU~!`>h1JrGTnDDZz_TUF<N zJhsiy{(;Q6Ysq$976+e;!ex;rN28vuY^c4ua!io@o(tFV^fu<;%|aE|SUel+779&O zAHv{x&Pw4sm>v^UgZz`8>dSh^RbLWO)WDdl%_T>?3M~!Z!iO=l@1i8=qWb(tYGRYD zYernJfg8_@dFM~>>sKDd(NdegP>svjk^Ao{V?>%O<lgy=BB+X$#;gMv%p0>TcQf;V zLds#|cMOfKRWyoiFc|Yo#Bt8APs~#QK<10j6s?5bFt5Va|A%RqcwAXSvR76JxD~;3 zZ?*}zQ<tB7S@6}Kmc=o$@sN;{wq~TVuEgs*GLkj0nxqP)4Dko!-HJsM(HhH5TMF>b z$2LWPrHlC{{1$nkO&&YVWxQVDAcL#A#XT^^AA-vW&qxvWcc?LQH1-y4sljqc2sl5l zx3(e4E|dIiqL&Yo9PEoy$u2xqstZ7GeBH-toYP|=_-N&d)#4*B3w57Us+^Hi&qmUz zH_s0wQABPWPA4O&Iu8f|H8SmZ9Mw8m=!lLLEq;SK@$+Pfy5c;iuo8O?9Nn02%)aA& zG2s9QqZpdgLep|RuzWV5NTe0ex)m5l@*a<54B3KBLOT^o@gVc@?e_4EqUD$kA<C&4 z3SZu1<Or|PE9r5e_wWNawLHcx`8D=wSn{FpO<gpRvJ^tZ-z$a}ASNlmFU0g}2B@=^ zE?R5GkO0KQ`-`3!Mcvg!BV0i;?v?>GMHU4Vzhkf9y+eOE;ETuMAV-8x-3BoLaHOJ@ zH)eyZ1b<Rf7_c*8^2sJ_p^3{)rUr@$7zYVWLISF)Gw$nVQ3!FPn}DB5S&6*7mORdy zGhD!GUu3e_%#zu|w=GuKiBf+sJ~Y+VZY}nfG(>BJ^Q9#<A)uhS(z^G5HV3j4ro13N zt3#CkjZ^(48C&{g+_F5A?#;7rtW~};UutGAQZblL>dwxW7BHAp-SJdK3{{M-0MVU+ zqxg<_m}B=xBag?FdSaA{JnnJ3g)~S{0}V%^v`pk3bPfC~p(<f?M$5sy8Y<>haa68T z*cFUaOcbi&;fUq9!3{F`M>#Os>W+g32O=<#c~1iqWQZKR-g24Y(BqH=c~Yb?5Gi;* z`N?A{R{k&7PaZlj8ZgKICbm%mRSC2Cahw1Bvkp6doT!(fwIHN`f>nd)T=2T?VCc#r z%?^F<Q+2iW$5^u(&q=#bBK{_tbhdGy7sneqybpwVd*<!e-e1A2-yX0xa$;}&_19Is zr2IybB0$>qb&~D{|J7)1Na7)ncwFpmN*vhfr}@nK9yAzMV#|ha?v66uOE?O@#dxwb z^14iQxJHN|*1dVZMraa0x~*_LpLh{$wX)CjzHIi-Js0t!FU8KUyT0D_wdRFeK%dw3 ztt$!jB#}R^l*OfQIQW<36PCkh|D(m>TTTsZb~3KW0e_;mK`Xd(!nw^Dp)+zXl!bUk z`{i-f)?YtKcYz1Xw)eht_~f?6{nuU3m;I{i{7Z5-P&>XsF}gG@xc})-Y9W*FYFOwu zf8V`RK+)J+?^sso^2LE)^Px0wz?7u;sbApKK<Mvre8qeR@m@U>D{MD(tSQYHKI34x zuPIOnOGf>Sl$FyTESZ$faPZx0(yx=51vYAqRxEmvjB32zmkL3bAkBU6W=3_P=j9Ho ze7&FV`s%DA<iDw2R=u0@AdQkb4TgKYKRAiE>I5p`!ZFTn_L?KrtS~@rkA~hzisk~4 z7kR};>F74!MFr&sJV^SP0M#us=9-PYa3)=~w2MbJg0E9u`eN^u`K(<qAQSW&tSHiq z0v=WAea{Uhj|d&;Sju==Xy|Xek8ka~rmU?5N)dMbE3G0es(IAI&C3EA6h4mgN7N%8 zGw22Qb5ELV?+J+fj&Ue!_K3qG4jprHW&Dt2j_>hr;Kl=s@7Sb-ssv-Zh!`4K2Q%Kl zu!$QUBby>kgK+f)6A8E=FluL2ZoYanq!E`zRMs>N<BtdMcxVr7Drmw>CtK%Tv^^j_ zn7N(=&lS4~%va^9%XmBd=~{56`5A8qO>W`zKUFEy2W71}DeFM9myDi3WhaQ)>`o^2 znJSAUENg;)eAwh^v!8&*X6+WU0B9!Q{k<Q1oS9Za&Afll*Y>b@f<@jvzQRGT+{#IK zxs4ZMD-)4jjeNb9zNiI9-Do%H0u?NJ*uJlQ(aW$GIjC@NoMY`CC|p1h{o4&SJPA#+ zJ8MBMLSIYzbK|P}7ZMQ}QCJ!$?`=|qglnf6`c^}p;1iX1gJwGo>PptU@X^h3Ks{Q3 zub0&Q-0$b*35O@n94Z_LhtG&9EFtk<nuDJpvEtN9>+g78xj>}b7h3{Js=zjpcwAF? zR$?b0h~Llc-BQtf*&HgQ3lXDH#cTjH=LHD;H+w00xDa5BB!#k32ZbCB7*S6EvdO=h z;a+b+fycx`L7srnM)V3WkfV?>tO<y`Xgk4Ybb=FRTCNOsiWCuj9Fz)N=+jP^LL@K9 zh1eiRrxyBA=0+eA>hCzu_lsVtA1hmg@#GO`4p}H!3TJ*QjRaBxKMpE{c}+v9fTi*% zW#tIC2c`WnW71agWN8+&QvIkM-PjfYMesm?>N2QWaX`V@NU+$TxUcB@2$=yk`$rNl zwqWOMLH*OIskhGp-)(|y%GMqZd%FvU8POq~^(})yO0(0vMyv~VnM8g(U!46yv@w1# zsY1}s_(v)<ADAUz;Dh-x^*`cWf@GCuY1_!0sLh4gi4+=l)6qTvI^9#nQxld{%n<lg zh|Pqu@e5RXBozWGcC@+^Gl#7D(V_9U1^?llNNSPlwKyK<pz+r%thVNFV?xP2`E*9z z121{&auPj%;Sq3>qrc$1918bS%r*Ar>tSa8o*;-X!EF*vPKIEY^J1d)O`;LuUu`8A z2bTEFa60M=z@<Y$0`wv`iQXa^Y{FK7dlyIoAMa$Y%YzNlv0bCSOHu>~J%KJ99OV(7 zWufjhJx&6~EJ=C!YKx)?1c-v`m^1l0xuQ@J6YKq(Oij^}%>}gMh5F&xVzr}$Dviey zMH=iN1n=oM44|nHw{LY5n}^(-o`tL*tQUvMO;fzy;>lg@XSJg2{~eQsS~jKxzKeHy zT@`AWaa_~dy7T4CJsH)h{O6iM^LR1tm#7a7{5#EsH@e3d)#51cd}M1~o%B;#G75p7 zx*AIdY`@xc+<TyEmDc3p{rfjlUeh<<$T2!4O3N7a(RxUAGO_;Y={iWh<C+9;Xp@rj z!~KN^h68g;$x=OjyYa@WOCN@FV~=?>gTup7e@V=rm79!!!VF!DHw!zbyp+@vJ@&7y z8$#a%QGqp0OEY@PA@$Fp4V@e!H#{C011*I^mB*j)Q!B9D0HtX?6nocE+k9F)+bX|x z{WFT!SARUU$u9mN0itAdXYHxkvmYk00axERP-8xRDo;OU$s|)s;V73C-)LL!P2D!o z;Sr~f@|LXKZA`OWs7!4dwBIJTwF_C`EMd+;dRlWG9zh-6dve7t8esz!6J1O4<))lb zjk#uzIQvej?MlzGF&~pS1^_e>*Zkxyp2?#tDyBn>JCYuv^jfS7z;CYpAoNQbHYnmn z^I{br7-+$zpnC`iEZ;;f6j>+5d_v$%rJfKZ%MEpwX-*=95u?W8XJ+C=$Wttl$ohrf zggd?!pn==LvMZ$p{eZ&;;WAN@Vrze1Xu&_FDD(&)D*LQnT|sZmUJv&o4QiVd_tB<Y ztw>@=(ClgXdmbD-1&JNm=i>~gp`RCXrk=?BhYCWBjzt13T{6f=3k&XtsB`#JGP2Yi zn`T4)_(X^N_;4Jfps3e{V5pz0>37zqZv|2z5@sQ-?rIjcd7Q&!sFn5{d0xh7#My{` zt_>2#0zZB+i=7p4GI(sZC=GGe&p4NrBM$4Hny{r-kZK`xQ9{T1>K)yV{BkpnOR5yJ z-!a^PN86xZW}J*zFMlxkN7=PH=X*;e<CGfj_X9F6`ivqj`!deER<ztFkl-sd`!Tf3 zJgD7CqUxJ1Tm_BElis37%8{`~qHy_)Aw2a&(KS%S+eRIxbA4sNL*Z}(V#EHJouHvN zJnlZx@+ilR&Zl%CZy1j7ipw@TF!;I@eG|47U*q8gZ>7$B_C{7*z$wjwAoyX%vYs~1 zMBBCf|8+JTxc(YOes~EJ3`+9lraPiTeD>8);ZrBh=#wR<-(s2Ao9i{1C%)js2ip_7 z-|`MU;pz1>7EYtW-zglKC<HO`LmeVaWO{3PaNpC&*k=}GyE@U=g2;P@q9)f)09iBJ zAXQY0K7I2;p@;$K?j2#f%)U!D0JV`y@5C(uBy#AXwVEL8(6NyO(Bz$nS0l%^U`Q{` z90hrumL|$KF$ZY}hh(hd3Se8-%>;${c(J8NgEbU~f4Qqx_V>JCQT8nth@E^G0FKRh z+mFR{j>wuplOc2n(V2+x-fD0`;tYAKX^Yv!$I(6xoD=Yr@s-4^DPkdS>HsDpVY48+ zu|#D}Hc#E61p)uC(7IPs^@J%YzYas$hOovtnuz@+!d@cOf*H(_k~`_Cg=ehaS(Su( zz{l!Ii0TDJ1eZ{(!%0a*Yw^0JJE2ctH`;AxyFthyLEs6sQJe{S^f03&weD<Aj^|E6 zJ<|p7W-AFLk1|Aqek`KKE`hs}G>^*SIX!|=9*_7HOj5RE`#30<w5weASmutb7C_@Q z(baVxVXz3^#Q1HEuN3+s_Vi`E?dDv`T0sWyONQjr>2jX-ehS+v{avCHe6rBgl}-CV zk4ZEteDJ7X{ad64^PO8pGI_=2(<V5h{<7GYuR2r=mt~HlsN}VZ_ySZ+dIpk(#P6W9 zC~DgeO*9+G4>QN!-H$9)6%Eb-ZDu|pf62;FQwXbawIH+4<fJ6WzFE*zNY_X-&hwMU z^2PqLd)e&g)pC-60O8A{d;OOE<2J67mJo0jR)eBP3+h9!@kHiK&ND1s8?&o#(couY z)p?Knxe0AngTgAExl`k5Q5P3JS}(46wU_+XI!V%_yOVi*Y=Ob}^&(Pq*NivX*2On? zMlyX4D8ua08!GuAXshgt4`(gB7!y0p%p?fk5l*SLQD!))#`y3dl4zblO3n9|@}IT; zY3=_s@##`FP`>to>p_u^4L?5p?)5ij&+b34S&#~u#`pAB!6)76Wa<y9{_#@MgBMeT z7fDx{bYN|s-Z+sfQP@}OzF&X+jR;w+-9Zw!8V}j&K1|KrSAeIR4{RHn|IHM)I7jAo zE~J}OrZrD?O>xLK*Xz7*o9~n}*idPVPcV8F#&<W?t*0O!WJAtuYk60`{{FMi+bI|F zc-8idYRPy>ZqA~mx;AJ{ORiOX=+n)nXxyG|+^FmDzi5N2jqp(plNZ>icgvcl_O<%6 zwo83)NVS)Ft~~xa@1C^#Jx)hwq}4lL4JtpefpoZTVHH*x*KfS?D??L`mzuuhNIE2U z{3@|x_;UO1FDW^pOS$fmI21Y*FsGUGX7wT~0Y0>4WyX$^3USi4J#(*my+zPt*=GM8 zAR9AB=V-DE#~Ulh5+zb(j~ijll2G1qv3Aw=MZY*nPBqs5m`@Axnrm-AbkPsVUID~M zz>G->k!&SVw9#C^x*nt4!j_Q>df^P5EQ~;Q6<{^lCQ<KyrB`y9Gge?(z2YoOT_PE; zKfW8?=9~aw-pTA8=n|YcP#tpUVfc(@^#(1b8!)>X%9Vrz(yxB43wbyeF_mi|94g%e zRa(Un3N)PN2bV;Uxh8%LkUG#FCj<oEBOfeI9s&w-es<STWtcSi<mfLz;_+lh|37*R zooR4QA=O@^f&oPZaUokLYs^#I(z2+VW-A)4>;}sd_IgkL7&v)09GSp(#Ui)$x{!hX zLR+16pLpNAFwG{}e?+ga7$D`W@tQk^-&r#5?aGzTA|%TFR4LQk2iiF}w8Aui_rQf; z^{Z83^A~xQnwBOp<t<GmQ&`}SVUyUAS`zK6?^?U<<{`?_Km2SyzIR0J#SrWN#;=I_ zi8OpokZg>x_h`eYYV$QZORy-WMXM(h484(Ewmvp9V~;)YeM)O+=d1M#XI(U>j4^HD zp(5ldovA6VUDsZ;k&UP;Td?q*I4Zi}-?Rd{FNwL*9*Plm*o-&7YV<6BMT8^HVn$v7 zIMY6qvi*zI!m2t`C~f>UOc3VCVv=(vo0T8uldylna2t64d|UGsGO+owZBi0nxu*cD z36~gFTH?WKKj_AeEFD4%GZUsTqXY3RWTb}Lz?$O%36bm=+f+yzPP$TwJrwxxXIx_* zI6C~?K~7n6517~OPv~v1<aBA$?h0hue((fD$>I@5IJ<ULW(l*`{T+nRXcXMCjPuIj za4v*%k|U=1kX>9l4fo?(gzi^H5OAT^&NH6nEiD&gWZFf1#-q%lv@u%{C^065zkVn4 zAK)m?2bt1GGY{)JrUivape}tO(xvZ3GmF;cP>mb38ol!fhdg#pp|SGI?Gu!J|K6W8 z;Bp5g7G3p4;{n9@e%Xe5#PT3qsCmCmB19mC)r)+M%u^8~I6R^Y9~20*g}R1d1%1X% zY-@2QyJi<ib=zkdc}>}d#y*XpcPU--)qRnJF`$7QI$R|Nm9X{PybB@Z2(LV%N6I43 zcMpP!m-xzSb;bk-ZcgB#sw*Qnty7!pqu`XHN&zrkafup+&ACEaNGB7HkeuhZ+9rAr zy;c0SWyT)<Td|xdD4-#*=x`=|7Tl-0q-)9nP~**lW)lOiLDp%trGA4P#h?Nlqk|Z` z$s86qUw|h#Cm|Vq3nH4bk(C8s3R<pU_34&MGY@_pZ^-yN!f~mw_!nem_AsXzla}9e zv{ko6ax>iTHD^kTe_cN;Zq}?=HZ{|8c2?!R1k%iT;?+FZtKwkGzPB{HJ>&VfHOK1W zWO+BG@p0+FAInmm?v%)WT{tJ>k*_fUH-P4h?i*<X3pWpBtlCV4OHN&RtJ{qa1wFrT zzT^1Q7>8{iJ%8rmzKDg>lw*cY?&}!4@D)Z(fVrG2d1h#6p7e;@#&K)jekWvfjcaS6 zvazZVb4%G!D<YeL6{lv4X*fgS!B$)QQz6BWEovXN@v8Ty#Fc(Gc<ZL(&k%2<kTr=c z{~+JIA7Wd!iPXO&MX%nNpXPtDD2EXS%hvtU(EsMMYZJP}!!tiVeC;DU@|sV??H{=w ztD`A?_ejGB6HaEFFJA8&>Q_HlmbRuisUiNc$P$;=VOd2GG;N6a3{xvO1|{cq$9=L8 z(Lj%AaKe79E}RuzAo6VyA9$QHURBX2$5qKc)}A_rug@L8kKwY@(^G7^A5xdszj&PX zvQEDC{{eqg=SH1<XRBJWN)TFOe(SXV=SL6M_e|41qPP6RdYsw8p+&dMRH;q`e2o|` zi>v*of9v4upPiwzK-WF<R_I$bxobPVQ%(GvSGvz^QspOHu)P!EJGeiieH@|a)px?` zgLjQtqLf-pt*`rCo08IYSd<z|zoQAYZFYAp{j&tz9}xPS&qUD!zJtoh1=Y}e>PFi6 z$uD{}UxgVIVi#g{(;+KclOw`taG0#R$2lLkIMWsWGXWDRaM<Ya578?N7LlXq4J1#D zlxotH*#m9P!r@8fUx8v`>fRayBnm{j=sI~5lxgWPHoDD);^dmyp;{#L(f|(j%%|hs z2EZ(S3>YeofBwGxKO<dScr+bUNuuEVJH?u7jm9yt{v;F(&o<{ByZCp?Jai3d#3b`G z8t=H*B^Th-L!Piz8Yk7b_ebG9hF$6YB(zj)64QTYO=1Y*cvZ@*B}8#m@~WBRg>!2b zPo_cP<>)rAT_lv^r1{voFS;^mV21OtQFHvoq?uTG>hkaMHsx2?PMY{Gzp*@fz&ZE* zghra0qPA4D_`Ykc+n=SS7>*BnaU@|QTG2n_gBi|eL@H9L+1*5f`5n@YlNk#p_`dt1 z&V#BaX*l`hkL{1tDw~*7hs|AnsA8xviuWq}#;slBnI6(>zlEx@Irr76hcbRWBQ;<_ z!<8^%FG{{Hgto#^MDvX!Mjx%|AGLsr;qd87T_4&0znOo4{t*b8WcN#wyn7r<J^<xz z4{_C6%8+#094enN|Ld92TPM)J(f(z$pa*08h*IPt>F<*qKDVo4Ix;qfe!`bu+IU2# zD2KXf?@8chTbPLvRUYYdvWLq}Fa3+(m!=En0n^FMvEX1smCW4wKR<3y7`GH6h+e$4 zKxhU=KoF(zq8D*LPz4h7q5)YQUhYiP-sMMjD@Yrh^k8hT1+KQ5yC?uw^>EwG*HkhB zLyn*olxfrrSKyy76$dwMpcM2cs3xeri3m(st#QjIIBy$bz<RwwDXvn;F3Pc#eJf9v zMz}@F!A>ajv@kF0yd|Q$8$c#Wx$H6*ffsRkrb323gJ%NLsqQyuhuT~GIg;s8zHg1N zq6uo7-ZJV;6<LAEp6w!1VxY7>#*c|Ctu>d+>vX1>Lp+G%I3|*ugjbqMHXzRS$ok$9 zD87ED15oIcPDeghjxI-pxRwCeHRckaN11B0ND^Jfavi+AdqGVZ0w1ozuw=1;I{>Zp zv9b$Il&TqGSjR91Wl~q2y_iPpy4@boucy5E5Ud(%7#e%%UYasUb<Mk$r!Us>zJ`yO z!_!3VI7-P4F>)*OmbqCDug^nGOKgN`XoE;?^Yt=rG{o7^lmsI5hj*p}QHpTNznlfd z-%$o@r^k5&uQZIDw7CwmBL1q$djo1~k^I6;6#cL?C4X*aYV+hK^6m8|;cS}b`-2^g zKp#pep{SSL-6q7K#)QQft{9={zpn%q#_Oc;1jo?yMxI(p^5sS?P4W^nqz3TFX_;Ag zUS)4!);Eyen#-i1SaFtxO|R5=UwC&;oV!&0$0wl2-VNQ8)a}+5G&wJ(W+2G?uj?6I z*YBQnN>e$iZkGPJD8aqvR6)~l%*q~GNF8sCg*rF9B(mT4VOr<$<Ssj3r^q<EPTCqn zQ^8$b*_W$&=GK3$7#<Msd1_4QA9;rU8!N`_diR*%`mFjrC*tux_NNSAcF60PpxRQ; zp;kwx6yxs$mE%T+a$x5>KbJRW43TZieUySDDmH8#bO=M|_rIb%J@$`WoAHBDfz~qY zl0WcMC7Fhf_Kzw%hHg>E2@_rRVed=6f=-k1wDx?^wuR5OPebD<!q<`J>8%%_{SQV! zIP0xF`9R1^(!={ZFZIgo8*b`tm>BOEJ7lkY_(nt{vbM9}rs1Vq)`i{al-;1o3|%pv zcJZU!mp#ue6woF_qf<RjAWI-ye12imDe(e=$ic)6p1sMD2U>srV?~tA?R8BpJ=T_> zqyg<ubK`9?s?zxvmQC86yX_@gEn#4R^hi>>&j;U^j=rNlXKw0UVo0ov``OX$hww|G z<2LM2I9*k%#~6o*+*=K|9<9S)A9oxI)Ri|vF6)}1F}R7CO$un1Esm~qp1f-?Wmb^) zwh`~k@h<3#6r9|SrESmBBg^s#V^X5CGwA{phBl30nF^y!*gt{>Sj2kzxm`zsC(Od< zJHNm}7Y0zhd7DMss~gX?RdO*q&#n?D{W5W$GrbI0)#7X-D8Rw(aW!rpD|$zWq-clt zHhzPxiiHs{5)Jh>v_lSzfPjl#No#!1jIYPz_=)8}47q2d7;jA8oxE4*QQ-IPA=Hc9 z0(&@^;*eOO#4f#?ec&F(KwDAe)Otv?12Z;QEYlZ9Z5ICIAdH20dC;6-R@wiZKF@x^ z$X_|-UDmudPQ&tL3QzUI$~EJ@OGM=Ws>KP_#Ap=T(WA+Iy=f-0`xZ^`z;>Q$8JiDE z&=r^4;2}~oG#{EY`qHL+9+gJRz18$3UJE|l>kr#TctCzGOIvRC(Ck?`qWda6)#QP; z?<Od0srFcG(KU^QI7wa*xbIMzGqZ`J%PW*b?N<V#0zRjIx<;5hwb}-5ci^5;K50BC z!#yiqM+kHA-Ho}0qjEln5@}CBJ9_9<vy2)mJ;8DPDl8bZ)kin3mZn3atATf24*9KD zx%-OTZr6KFa>TojG5m(2CVa;FQ#$U>VKi(rnanv(Hwz5BF8Cff+@l!vzgv#?@A9&E zn6D0T1uqF^U5Qlcz|Q_HgH(eTHVB?vde|bHnY^oP$}pJ2MM#W1U<tJ>Ik2m`V6Fwk z9xnUZNvC$FTZ~zyZ-qGCLnzR$0p|&2$^z$+^Cv=zj^fXc+c(^^rLaVrA?5V$XoKjV zfM(>Dk^?PTQe#<L8T|&GH{CaC3GAgtQPol-WdIbkqZ2G3KFI$bxI=L^!2+l;MDkv_ zYY{>a;!W@G`+yriWe5pfye?6WiGc<JH1*tVIX)$#l>Nio0*k~l<{5AEChU<=_1xkY z2}_tw;I?PRTdF;m>m=+`#d=XcXU&&pK0Cnz`Lbi2dS*Of@2FioBmq76fpa1ZSH=Nr zLW%Mcc5giAApbv@%qo{csK!PXgj8_1Lzq9wGdkrwQr<I%<nZGPNbO1bmE;1FAhc1c z8R<}Kl2~zr;UYFk?m5c9b?wjVSc^fpeMmSGxUXax6YCo=E2O-y@peTM%o=70C$W2+ zbJAmfjIyXFb`v;3OKf!Nnt6@57l`a)r4S}7U9)x8uJryeq-ZQeOvT@%3znM>W2}QZ zn1n(fznlj`&kZ~z!`PGK0}&8l^1KcZD8}k*Zl45#B9!E&pOMg?d!|_F7ErYY)AKY0 z(rj$5pd_>KP**E}w7Kk{MH4m`^52!|P-eTFcWeiIA_JxFb{0vF(868jN6}0HLK}P; z5fxVu^IGa_Z#is@ivo~rQ6H111z2_KL0vT7(+Z^-%x)KtzXTzW{6d1mU}w(2mix=f zcdu!^IZH}Pgw8&tYwG5QTIp1q*sZ6Y>Pf*8r@}oDxbcUt&i&8hU!&vNAAE1<t5RUA zORahKPxT9?{T)lGw}Xm)ezN1|pHKTXG}H_;xlR__Q?c%i#-$ErH(XnHR*R{r5y7?j z&s=+B&8YfcE?i4jyEhd_fHs~gKTeI|jzR4aUBq$v8RtsQ{3?I<n7q26=&fPF`0@SQ zNyf8t*`AB*V^D`z-r4yJJ}#tE<+_#jPdAYpWe?BnCf%9u;y8NNFPrp#Vgz^E?z{d| zzv-=5#>J%7i7wl8Ye&?c=hy!5#ybnJW93U}3+z7<aX9eun}?q3d8mbl^&S<gqy0xo zwVC%ELv}RvO?F4;n6-DTwCF{H!q?aDO}kz9)d_Q_${x>dQr+jFtIrRoJSvm#p7q9F zwOj3{O(16Rh6@4SwO9KRde5D~2i<jP=lr+6$?mjv=%=k_AwIczV8M%JDzc`cQnx3v zUq4$`>iX<}F#)M%hH0p8w^TDUuSv|L70FZkq44ipaz4(-MLE8kR$P?b>jOb~1AFE> zX=KMkSXWCs&uMO$Z`D6pWuoG$;Fb4ujJa%{{$yS5gM+27JRSor9tyyTt*tql3%_6Y zbkFPj+Jw>OLZxwc%7eS}24=@*do3`1m9Y^}Y&A;Tgf*8wSZqjNB3!gwi<MS56>}vs zJAPQ5@>7n++aWj8)hP|pCgv?vcA(CCp0Re@W8q*}O;C}MIRPIIS3WD%R_E8_TrXc_ zP1Z)=-NPAWhEgPmbv%Mr(gZf-V@yvbRUS~{X8{}u+S6Sx_<=KVy`Y1}xg4}8m`v4s z?$ssA8D8aLHZmIC0BdteI-z#^e%f$6R-hAK8%{?|D};<xn&mz2I~?=v!g11{_mrVY z#xg5=F=)&D7SMC+5~uDfZ|?QI6Y!Vh;&SxPQ}AJ-R~lk3eD7JmEW2V&4n%hsnn`d4 zpzHXFo)PEm2tZ?YT$a}K&mEhH!ewC#(^mS3=6Sy0^q}dSHY0(v8e+C*+2K23lNO9; z_-2A^ho!Yini3$<f@irhkpUbC>X{@UQSW<o(S*2Ub%q;a5;#38B^oU}*tBJSBT@hD z0;xlc-QoS+6eUQ}8m^?MVALlS=puo{%2ST6x2PMgyy~<<GmlkSl5%Rj`2wya98aU_ zJ=IoGpRWAb6m0Nf5{2AIXVNH6BSSQz@X~<pfJjK;FTE$0T4%obty0&&Bn!g=_bt(y z5M-9@@@7ql-qqKg2PpH@OoAg)G(?we78OdzqWf_*9K575Bu)2l0@2G8hby1MNP+f{ zY<SQgrHk!&@qa>A0L;mkRgvjqtYCho1lTI^YI&6omBnR#pQ7lY_@tzM)>Hzf9eKeD zjL)rfn{yaYpgzYli4b;4FhiU5%Q4hYMWYovSqL62`7#44j;Q<x!3gHhpr!&3$Df@< zLv@g~K_N^5h+>j)SteA`6ERnTa!K-ucBafy+WAU9YyVH?m~!%MtN{gUHJIzv_9b4O z9X$$C2brR0ne3(}lUT@z@>#4-x<-N!;WdV2bau5S!+g|}`Qu1=5k$ir7Tn0kU~Y({ zVLe(}L97drORAVf$<CGwr89`*Apx1jS}04*v`|nkd`no`J`SOUhy$y|qn_8;V<(U+ zXeq)eem_ssPk9_kR9W~FAFHRwRY?#M!@P`>24I;wP=|p@*YIkDl9a5#9RW9Mhn!cC z%Z0)&9Tfw72Q_DTcoOgfkwf5%G((~JH^?5EgGG2QN4#lh%D<za)}u>yT;}S5bvWl{ zD`77$nLrleV|9?Ure083xq2{m+z7ab>y~L(n^2gmnr<!M=c#ud`Kc5Z2my0vm1T@? z2o81grit{90vE430(OA?0;Tiwxm+x5IaSP}2`U=<?)bsLOsdDassgGD`9sz`3&jVc ztKriH7%dg>f|_waKjG`Y9(Akdk6ZJ9R8ID~-!)a58XtPgHG3HHe3Y!G`NmB<&u-f< zrhb@nfDu|!APA%)@gec?H)|L)|BAdN=$iSZ?ws^_Pu|&U)2(;BGyb74NK`pocb^#K z8lu`-j7wZv@DKev9zn;_!T-TkjQ#Mnd@7j~3Guh;M|GYVuZ(R}-o-j5KG^<T@mbx? zJAX3rWz5MP>V}KW6+Y^pZ1XB)L)zi+kZ*<KEbjv6neM@;IMI-0po#If<SoxNH9q;| z;BZZ^@Rz}v1@h?^;VY=cn55C3|G4vH`n`UVRuKvFq5>5R{SG&ORWK?k<EJ@*fZLF# z<li|map27r+@IVuT=LU@j0rMkMTuICjNa)liOrFgDL;n9y>Sdg^kVb1v1Yq97!8Q- zK#k(n+MFFYpRC4QX#Z;*hL&|3+`ca4a<g`QRp0C{fni__LtELZ-qqg@-Rs6F*-&K? zEjn@Z0bj3qJ16_h;47a_GLJuZiZwjuafkK8c~VxcIXI=4#0arRVvf4!_p^_dU0jJ+ z>I_xNV7u+csU?dIc9Ub)KV6M>#-+>Xb^qCOp>9iM@vM?F`unKr&a%9ZI=HT%|5>h* zzPxBK2=E|>1{ZtQ_|eI;bIEDaGblCKN{3`sh0clgRV9B(engl5k<r~LQI-}PK}an1 zEcC2Q_gQ%9NzGTAJe3=5p3rp(dG6y1!W|2k?Aus5aN4W;4fD<zo2N;Ze4=LltL@gi zWG@wau4ukV{LT8nPiVYXmjlX4zuo$u;IQi0tD+NpL-ZrkGveXEu^Yta$y-(?UoZd9 zDW<lFk}YsqfmAc!#li8Fn*SL{dGg7EWhU7Y?PUu-x)JI>+acyb(Ctn8-Ssw!mqih} zz@hZyyKHP`FY(ba`hms=A^H2>1&nxe8S-9A*0##qvr{9N-CYRjvn2o5b<ftHcZg{U zy{#C7QMSUt&|eYUn|S@wi&K>M#DIseNs}fGiJ{yt;+t?~#FDqQ&Gm^_m=B}4AiPF* zH)Vd_ZGOD3m-IA0cl3WzJ#^Vll3*nn9KAqpoFq9}xy@oozO*SH2GIsIR2kIWrf5nM zq3q=%X<Ld$k!p#=jpesEoe)dnLx+Zh78lFqnFpD9oLt`Ntn;7)<pW~_WNp7rd3MpL za^X9X1>BKIsx41zzG^#b^f<;v@Ui=&Pl_juc_&H3^ox$7gQ$=XRX)RnR6TrwJm3#m zHKQAlf*IOa-$IC*tvmALB!#Wp{23rxOFz%3SR$*+<+Dg5_D)D!GO2ikGH<gW<Tyi5 z-Gk%Q?l#skRD72oo$0fMOi~w_nqU3g2?a)V0p1sBbEP>X1ckVzoBo-Z9qWw;@AZ@P zPyUje>~vc8mqfexs54;<r>AR15b7uYy{-NOnPoGK&CdFm-Azdksv}9!1tDA|Rc|q? zZct+u>y+*&XJNpS+Y?quv0~1xCj}Uc=qE4Qpy+Qr`r)gPJnCfT8%wtTxna2Xm@#oM zS@5E$HQJMahy?!Ow_)MZHtezZZ1(CD=aJ`8)eC->=Pv{sm6Xtl4#zUx0ucd&G&^{N zqHk2;G8QP1Kq=LlP4)1Di<J;?&r<yYY*cHpi}aDCc;Yupp<#tFD}|VW2<!mpk1MKP zjy#R!-bSzMidE{3&=1OVV6q~yrn`-kfS}~0s~t&3bO5ys?jatD4kGx4wvY620j7Yk zYz5MhVwFLPxfQ2Iy$~__(Owe?9X?0IPFX)R={&v5FY#g4H0%YlPr|oYcG|W22&q6m z&}1v{Iiwh4xU#ahRE#IY7OlLx2wod!(&9+Hg9SXsRmp+Ch;vAxl(mN2F@udk&2~fc z(YhYa9GAmyGqVs9DhXK{rx<r3yp`}Xs4xw&49_?~{;y;7mk^G8pNwpe0Ume)w2<_7 z{SC+3n|X^RFp$F}6BNw?Y{6u>!oFs>Qov5zo$!qWXUnDemL8nEz#ax2PJ-lmS@VFJ zM1H2C7!*QDF>nPDbs4SIKWGar=TeYkv2>8ung<F9{n$!JC16&Rj)9ywNJu(9oDo5? z%V;HZEzyMdETuah*p~WtyI@<6^NY*i6;O<^-^N?gG*l6fElwz=RfWyY)XJ0TEz`*D z(({#9oLeTJ+m$9Y_&4cvdk*il7xO0a)RSe^Nood_`d5!aZY}TcP~V5DElRn7G0PtO zHn;lJIi~wE_Pq0+(K?^%u5D<O-G=z!udy2Mr!F@ptb6ZC_T{o2%kbanAx)B^AE{W^ zyng*tpdDNp1THYM^FU6TulBVM7QE4f^}715`ZR;+_Ar>lGL=E)7<y`l(71@KO89>K z^2vo@fEk^~gQx$w+xmv-peF<;#yk&(uXb;rJI*Ps{BKd|D?#shPT+|d>ddRzdlv(x zrx54f$za&W>e{Cfk1Jc)Sr0#ho$RV~H>c5=_EF^NIhPyZi(oPy7Nc7Oj6j!axIggm z(Kt4?m{3eFA}T9q_J6jhZ>5gc_cv<1cWhhur}bT2*Gyp_HLQW|BDhudsr?=Qt>?=L z58}$32UBt)X2kq+%ali;;gLTkIAGocz<PBUGl$vc+j3(}ZWBm+4+rA+(Q^Ali*JTX zZ&r6TE5F+qcxJFVR93~Xo6|J#uGJfY#Sz1LI!Y>uAeHq}AUzGd0!OB-WOZ-7?u*1h zK{Hz}w#ErkM;0H>eJLNUcuiU$t=rHe`vmN$_C!m@`-8s!VqsvCxh|x8>aWvu<Dl`S zbfo$ySpGWiCS%~nRwkE@-Z=H!<IUflRZhtcQzC%@;_*@2Zk122s92mFaB}qS0$pxF zfwRl6N9*Y}7F`9`s5u-z#kj>_Joo$u7MjBRrqalrm&;D=ybQL?S=PMkPU#o#>VA0n zLFum>YsQ7ht;}H!Uu4A3mkxttpY8A}+_LDlTg$?N^c$B=O_7$&Wq(R;-pxU_>@CaT z&{g)+lhWM}JwrCO-c+`DIYxi~9p@g~1a{FqhGyI4gumIS{PKFbwDy92+ZgPx1)F?l zb!n<`+Y=4N(iXjEq^W!bkpt^Y^H-%moK!t}W0hwDK8qU$cK#@~$j+J_YGlVUx4EJm z%L$#a>y3WdJSXNgAk^>)sttWn7OtAL{#^Y@XIjHiis=W%{zhusT^Mn~l8Q<pdr<Y> z%-T0;$g^zRF-TFA68&PhX4dCciL_zk!)A@<G!Alf+q2E;&J0Q(Kry&D+wrZqPv?=p zS~7YJ?l_)h&UBAkm!rI9fcERWT+tg9_)(EA!zOv+yWU*6do}0Z6`vupZYVaQ+|p&B z#y8Jj^jy~NHsX0!nwVV|i<g2%!Dp{trpz2OXnzK<(KSc6BE^P2D*q5k`@Kqy2eq?U z^%C-Z9#b-eNx3hDRZ>+hXNzL_)@>8ywxgdT)-p|ifg&X<E^W@<Hp%z>&$*3`wk&p; zYRQkB+@uS=zwgf(TX=AW#Y;-t2f;UQQ;~#!T0`6CTz-Z3k94km7f05OT(h^jP^!t! zeRql_47B$K==>#`-EDG2Sna}~NvD{#-m<Z-pE@6@cihm{P5LI%h}%0+9-YtnaqCxK zvq7F;FEsgd-O0xVrFoxz-9|B;s7Uw2zph)$9#mt0B)BO>y7OfU8t~X(UCQFL$L-k3 z6e?IAstTuj#Syp)L<#EgtykBsfH&4t7d||BT4a<E&OI#)@4iaK+5j1Y+o0_2a?tJk z-|nkY(pM5j`Qj+Lp%U#j#C`NEEt+(RY=^Mp#Q<4I4To{|1+=5_#qbHwGwlX>3rui% zDu)nMWzn`o`hh`R+0wQV5LEE$WB6lQi<16CyA%bwn}@`ERjbb49rg^YgJe|%@Cl_q z%;4pqquRb?HRCIc<--yF6^lRSjL~Ihj>bhXK#i)8iliJ?t;C*k1!$9r)(oHyHJ<Fj z%!s8C_^~kIp$EMBDqaIL^5`5ulA@WorEuhYQI1lz&swjuBx0iAuhJB6>Y1k5?vO47 zMCmd1iA`7&i$t=Z-`rJ|IS!&JUCcmh)Eab>j|q)KF*I|0`9NnlMn&bw8@YjPmqz(Y zHik*0AA|8En{`zNmbxHir2ik>f{F%D=IaW98@HNOSDgqbp6w82Eih`d<Z>fCSRhV8 zPR6@PVb124q~vVa?S&(O=6#HyVR`FqL19X+aW_^lpF4KZbHs_h+Ar93isgw8TtPZL zN5N_$k%6ij%FC{YWUB|4m>}FmNPFP%Is@V-&}@+?8Quuxs=!zlN+X3dSce<I(l*jr zaKFb1C<oy|bbx073}}4td9?^hOVA^`(=!RgW&+#~o*+dS{lN~^c5dMbohuxY3M_0r zwaHymFv?u!=cnh8&Xf0GRhRtiq=9LJ!b3Uc=!3oXr#HU%g4!yn!X|mkh~6<jmH*Q# zZy<g?1^Q}6Nh)ko8W`n-=`>{GR$KYun-!a_?1C*a_g6Pw)+`lojzj9qVCmUH+ft^> z5+v{XN)ykM^FgOd-;j7M!4i){xD`3o7mibjqUCvZ*^=)n?LUB<*I3b9$HxSrpN;tp zQxdI6oK7<(?J~`3{Ct1^dJnw?fOR$_za|zc-Usc78xyZhnYA8Z#!ySw<f)h*R}wnI zKQ3x%`i2M*&--KEQXjJG*PsAOW5E`6o6XF$rf(w5jt{?4EE3Jzfp6DdAKLTFmcfrL z3YtfU0zR!(aXqWeCk7mfw%pc_8Pa=}VM;=iF5`{<$-9laiAdi@%SnTwp=izK%|-US z@BRc|)BZO<o#Xpa^9u@#_1N-`Hw!#3n~gLEIvR^O6+|ab6dv;%Ign65pER^b+<7hn zh#tT#C|Ip=J^zD?dbZgt4{5l8LOIB(ajEBT|LmgS^!wM^kq5i#Uv4MStoU_uo6TXm zoN-WgzROA-Xm_3_4t}|X^qVZ~_j2xu<^7+`SdXqz#wFLzzqF08*9@&1qFsE*w#`pU z|2(v7pTk$T6|aO)TkQ~GcervOy!vSAGXt8gpND?UHBQu9Q5nD8eLX5Kx71I2b%ulP z<ww{;tE=XFmUTrx|G~YL+RHG2Lj}B`3SBrbrtwlz<Fc;fKtLp5Gi8668n#|IWPfYD zWlAm=)H!u?*W{)7XRmC$J63ad{=yp0AYIVs#(xh?wBLKwDg7tw6CGDrBRr+P-kLAt zylfILM#MH>Kb>%Xj45}_?ME_oz<X0(kCzYZ{JEzsw(hnPm(B^`o2!nqv1fMnhX0v* zaluO!PiHfM@E^JMX-%PWaZEJa__=(-g()B0m0XwZFxLqyQN8`p>7!YL`~Do%yr`Iw z@_J$&xa}(EERXogXQqhp2QvkTz$kigb3&}1M+a9N9wTMC-R%)(xKPT*T=5$Jc6o8o z;e_l#5^R%9=iX<8<9Lj1W(?0r50gxiD+{2uZFj`XRETdJ7qWmL;1hhkj|Jky*e=uL zWYKT3rtN!@IDupI4!V2Ibg<M<YqOE#J#FKsUhj!c?QUcSf<#KQD{YB1d14f~8g9bE zg)GT@)?z*7j8+gTweT`SMsAJT&v!|n{tTA&!$kG02k+{<sgt!;dH&AZCKK~f&ZX$j zsE`a53P{pawsXMwyI`aZb(AQD0>hr^Q%U)pN_w*7rRfjAu*)la>sYpzlfR%o&can9 z<dsWmTgPQeQr0V@w+b{vLm1-cf%>y2a-n0~1`f(g*?U-TK7P7*(}prg`@6cNg>x4u z>CJeKk?OqcGn~=@Pel=eXL(R+h`OSp=0sI#;FG5K@SXWAa8C%H&@`h+!`B3*^73V= zD@S-n3C&KGz;ug_emEz>lH`I7#q7fgj$U|2=bB6NnrMf#3zC5@<;MqVq=@$C`9M07 zVeZxV(igfpY<1AK0>isA^PV8c<Hnnk4R7D&GENM;v_+*RCgga;ah#t;CE;G3h&;h~ zS$L6R<U2tq=FEl!C&GworI2w1E^WNG$eM^$$8e&xe2HZ;P!W1viA4op!gTv@$WM<L z<a9XiWSEZQLbd8XYd<~AesIEWlq=#Ov;|tQPgUyFK+h=PGlivix=_uD!hdFacl`_M z8inlB<RSP)cfmPOeGEk?A==bA4T@9D;;0ZTDn}L60>gZyR6MR?46OdHorlVWB>#J& zb)|*zhnPeRIHj((6ZD31;Bx_}$0VWB`yOi4upiPAZz?pM%#=@HL=HcuYdrEq5lHi* zhc*D&AH8UwYM<8MX3=q|$Q$<4tYJBX3%(QT4>bxX0Muso2q!utE61?OV8KqX7~_|t z2B9n5^LxH76WHq<ObHGdThXkcO}imIWP-9u6)D=s!n|MU_D!!K%QGmH{X#lW=Zzx7 zWhqAz?e-ZK9mqIYXHN3Tq>8EPI)yVPblQGsuG^pQzR23KNOqQs^0+^{O4#x;dR6r1 z`IPJ`ivvWNeVhSpF4SJ!GDMxcSIoOoAlxcFN8Oy;<Dec4_y6sV>q6xqN=L!aFtn2u zYkbbW#0nR1fG@y=F7t5mKx3XNd7#s0CUS<Z_!r>2+?~FY7fMS}bAFio6R<w$3i6vc zm#-trZ~HMTh}A`zaKroe{3k#5t%CbtMTR7N`!x9*3#T7g@ip@?2!P6=2v!{c;~Jc` z!q$YskQ5A6gZKS{kM^j;&jS?mj2S}v+b>b7T_z$@lSVl_xVBccZ@7j}!_0Z#cOZ`C zLp8&Ho_M-qQ?JvvEv@G>PNM2=y8awae-_Z7>?WcXF&p$uQ_rh&hQ>PKw!>a;%|RAc zl6|WxXWvKX{zqFRe_GHanpDqUYuW;Q5874ZdP;p_77GcP2bprfM<;K34p{QYVvVxD zqi}f1iBWT`8-9k_VN>8*E)W&<Q25H$+U#_tdrcD4dKsg&ZpCcwaG_Y%R8B5U9g7$I zq;SpX-;4;g%;`=62`Cn$$H6!X9-q`V!rT?O)Auoce_rZhLL`wOFXdoCWB30WQXd?! zcA);ILzMBCg!5R|(H0AEv|yOji}#=X>Kxgri;jxvdFyxfCt#;~ZFuRHEw3;1>rZ{T z!YLIW;Oi)(Ij0aiectB`9^v$V7qzritEWJFMbT^;^3K}-bF;hCso}+7q-WKW70vBI z@mOXE6s=6}#5!Gw%v8T>O>Xf^J~cK768}F-*B#g7*>=HVU2UnTwOWQPL6$(p2?io9 z8UoT7rXonIQp8yh3Q-`4wu;t7!g|q~AR9px#VSLnb%bG!G93sgggp~>hTpl<?~nJ_ zx0I3Ox$kS7>zs4d<1p;>(|!9YUbYYACN7%o-8_d*KPF%n2sOk1#7IGp63UX)ufQ-% zhrVU;nIAKrX4Gb>=Fd0i@(5))tk<q2jgXz0&$&$WGc=qC)b#0Zxmk99jEZq-2qDmR zCZYZ4puthfNRYh=Y}w*Pv&T@Cy+QG&vN4Lhs>eLI;o_(QuOKhcBSy)(E$^j<fWEY| znf=axN!0JmTTBU|87U=^^G38Mk`w+}{idh&Yd&MFZ9MobaHiM_@r&W>>;7H8K+fm@ zP{7uWZ{BpoTC)FHu$}RakpcY`clht?;SQJ7x!WFEq=+)-1lPvv)TvHoD?rcvNj(C+ z(Y2Qj2}59^TiW&Mf*o~*-FzGSX6PjNHs<ca)V~#(Q}0IRxM77OJN|)D>t)(ZTnE7^ zakWNE4EeUo$k7d_2iKYJI`2~EWHmsZkJjigx59NQPyR)z1BdhOAVS}%r}9sbjrEzb zE>D@>YJU7^%1kLX6byR13ZAeD$1H-xcNTz%+?#w`wRsxh6QI#bm@?6f#P`w(h_0K+ z*h1ISYT=Bq6pJg+krVzsFg#jp>=6r^lJGv<=qqRD&+Q#0B(r*FEG778!req>!jI9m z&O``+iU3y#uafvIg1Oa8I+t2*25gQ2sR2V@2*idESe+4HI<nmu4q$^u6CIGpXYZgk z3Sn(SD?khpwe<b;cVh-xDWXU86>f?j1~(aB@=ta90-jkm0NsDCnbpyT9*JukIQl%v z+e8Swl?5%}PGHSj(duB46KavEo@`7rjlR7H>g73_L{MYudzHh@xQe{jx7jpthAOsq zzIBKJd=jr3c(~=+-W_Rb@Hrf)e85soS|g?nWHyw{nbygW_U^y;l`W)_sk^>KVTGVj z`p*j_HQl5;2Vo@wx(JS~VS4-V=Gbniwe*Kkssr0pMkaM{@bB-hFP|g-pfSgvz*B(X znp6GRSdoiXkMsl$MNt#lHy?b%fGz4R^s6(6LU3TE>SU-JM)m}tT0w__3Ds*4VY#$V z12gPa56{4A3=&(n?<2LHtJx#Wldd7pkTEt)@S!b-7Xk7h_DOfd_dQaFRK*xfLW{v* z2cg6;Zv|PIlANSpLqmIe8zMy{Hy|<`a3$fNN!B!5)#kS2nP}Waw(e0&0K2a^AZiG- zkn_pHsO_^ESVV~FG#a*i*jy3qz6OrU1~|*|h#DIjOAsAlVSr}ds2MMG6|r5iqcD*c zgPzZ3wqvCYHv&m5X*aT7BWQ$Z$jGF6wg(s(k$~#)-b{`g$~HXL5+W<G;S|<Ec=O(F zOcdp0SU><Cc-03<!TrNtEBM{x{}ip9HUp^<MUgy6y-*;&TCtd<+D2rkev>w}*${k= z6eYd*cj%e%%2AjA<*ue<_Y%oA2H?8@QN+uci@(dnfR`lN>TabH-v*l}n8iXyMo<k9 z_;A$G*;zxu<V9;n-n(PA0kmYP0+V^b<~0-u>6|*-h+{$DM&c<|Z+pSu={3L?Wb-%x z3T(+m;9Er++fX>GLP-G6uu`4Vpx?;@>EAAdRsn3PYS`bRP>63l5M%Vp5osDc$xJEu zqm@1<=P0mp*tW<R{!^{DW&sbG>7DFzBBtWjHxl7s*ohUOd=TzTp~OC>!O73bn1+M_ zVl_@#M&g1mil${E<Ryv>JGfp}d{V@79Z_a3REn(#zrAA1^LE+z4zTnHMAH1K6wUQP zUDPWD01LzZsFAGu@l34{s}=A_(6~|$6W6D4&g9VLg9qWr8eFL?=APft84qNIPg49( zR-uKvhIYviq{k7bF@zSTvY@FTz<(9bU3q5pv>@;qxD41N8iB))4{5r4r)taTg(6)t znzW!?<5PLqaty}6zm&XAUM&iAZvseS`4M~?2~c5Sh{_<G!V!7?SmHiVi5cE&uYd-9 zUj!R<E3S7K<&zVz%&-IsKUxaZ9*ngQ8X*^JbO1gf%yl~Ff#7F=g@&p>uIKMS=w5{8 z3w{yCsh|?4qBzIz_i%kGwBEQE_lWOF)&*j^(L34ibJXgooJ>FtoBeTd`wB>_U;=@Y zOs%g44}g&D69B7(7pZx>7+#|QQgIp^RK91&TwL$0HDm16<;mfo$jE$invUuRKWahA zcf;%I0>+don+`368`q5GZAt&ST-|3^b0S+&R~0fJ>oBu>ZvinY!`2ksskT0_OYo@{ zSUArGF_5q`@S)(AS)W;3xTb5@@YD<``Q<fvMxpj=V>kIPd@It520|ifrtQvIU27G3 z&Z*DG%#QEr(z=3aea<AWiyT=uPEVK~12=UT@k_udml<Xxh8yzF5=9Byt#K~Hbborz z|8AK9E(?N3l_pi^Fu#H~wP^IVYDr_kud=tw8?K;KA5_*%=RD01e%8CQ;Y{&`|8)!r z^DCB(uD{%&r~j!7Lnw|#`ubJnuc|Lh_@S}w2R<23d;4E*n-#sGEppxHa(2S>rGOUr zJXb*{%u!0BW2cTjO4c{6L*|^<QFc=}#MJw-GThQDz>Oc6>(jEcjo3nyxOi;0;fvNM zb|@VM_2{Sd+<s?R?8AGBZw_cj_H4M3amr0*80$!)zpSp<rt{C^!o`Y1%9M=JaAAJL z@r{G)Ocy;BG%?j<zd~Wz4PK<@J3W_&ml7vZCio8O#@@eZ_ctS}!h<HxyPQQ*NEY}- zG(WOBHDkqHb!2eeb?c4YXfYc&{q?|czS??#E_oW?a02wy6aJ5fU$yy79W)k7l$AK{ z$>GmA1H>n{Jmla`9p{FZd3p>ZeZR#T?xt-IT+nUQrOqP8MWFDwI2Day!fo7^c6k8< z6YE@X?!jZ4{Sf9l&<4StSUI+sV5RP00corONr(`_IBHLT=UU+I;uc`5?Aad8Ad<-A zsP}sCz&(GN+nIruLJIo#W&&Cxlb_*O#~31}<W%c{oZ+xxZcqBz&R3g#P4J8y6SAyr zDE!znFO0#k0h103YNvYA&*dlVVRmFp^-|z?f#_KT=SUgwJpyRsiX_%peuM)A8!Y4+ zta8Jon)K(Zw2%c{SPY|uA~)BEwRs0<9hop2Pv|Ct_B=!GwZGMGv=cg|^uG}u`5y6& z#}haTS>8wf-^-<5ohbflv0(t?;C{h#a{KOU#b+XT#@HQvH#|(W;h+gAg9AmE4@S~d zq`fBZ>`0p(9nXgq4*}jH#q?fbH;xNuJmQ~lz(<)BdEVITmdKCpKy~1~%jYPuhmqGj zEtPi0qEq)depEeB2G{I;haCMlLd?fALZxr;^L^-Wr%1*U!&Zh3Tom;?5+bGs1Z+hi z7GEAZ)gdDvE5TqLCPB^ul%bMMq8<Q?3r_X0#sJA**@BT>jQO;{U%7^G+IOfOkDyrM z5~N!Y3UF0ynaRWJOAbY!30659ml|n@iHCLx+5=1vCWmtH^0DrQeCDa(p@C_uLnqwl z@}#}s%HuzJb^^#I2;^~(Xg@2(ZPa3*^25WT6F!4*7IEsmjOLj`#$4T3@E<5RE88;h zgGkAd!f0oIS|GZV8ZL|_fa>Dw_$wjwuI-u>xc2~nMEt{Jx%%S287Y-~&^nkwjbo0D z<v8kBPuTFuU_nBK1xNuPg<+n82e1O4%CPDZ9$ea7tQ+c3i*f3lpqOV`k)H$Tn1L4q zN;=k6ySEZCLK<;-0i*?q3tIQw?z~0tRshig%{WdCb_5bvdx#~3A}Dg#VD<o#ngH9p z%Y~Cfo)x}rx<|8j>kQ5uPCuA#_mgxvBlG>I12K!k{s3WLM@AHw7x*mLMjBYz10dW4 z>5(%Dd(lVGPy@MtF2IhZ91wQ<DR~l&Hg`g60~rr}0j6IP5?bjHqmqgTpOqT~OExh# zRJT$M+H$J5$;@K-Y%|*v)7Z<Rwug|Ja8t1t6;N`bW}D)xk>QE%^LWqRa9<F&dN=z- zRlfRBt<tTvm1@US=<-Dm<6)8~GHO7}O@krclgs!<3<uEPI=|1e3M#qD%$`>5L&`wR zS*3s#-OhLLhI%6+#oOAMtcs*LLX3EWF|M7s67>3JDb|~G5;|0g|4;wB9vO$yvJJ0Y zKlRh`az6V+2cQ^ppP?tPP+WsZ=bx(L3}*c#PEX<G#G^yzI@h+HW_x7?y)2mkLs0Cz z(>OwLU*(Utzpa1e;gv($Rs*CYIcz4J2`Ioim0`623#W+IZ%#XG#?djq*nH^+13c{) zVOxjhVV4y)YU2a~kI3z6GURWpqmwPn@C59QH0=NH{Q1;h|E%zz#N`zJ1}Md5O0n}m zk~0kCf-Tx6;9%yDa|)P6hPqk}#~><&)rYLwj#f%$24QD6j_WG)RGESRe;H0FN#(C1 zKWMDMFYq}wzr()KAl?9v5PuCW%A}Yg`@S&H20sK`yZ$Q%<tSeb3kI8Whjj4LaICPY z@S_&?SN|<*#@kYpqQv0hB>}sqh2w0H3ti&PYRQYz6$F0JI9TB4OwKd2)oToVdB`is zr~&hZf?Z%|p$nerMtf3)FoS}FT&Yc5(KCHZfy?!fA=IaG)ByeSaZ1De?l+(Lpz%JK zCM2akz#9XMvBD_O`IUWQ<6P_xmSP6~4#mgJ%#a&1KRI3616mVaG?+wyZ9`{Q?@vEB z{~H|IEjsjD7?Z}M1%N9pH}*U@LN$}TSC>1se9(AUxopSF?!o2j#srQNw-`l>RF{B~ zbIWJZD!tl;wE%kq%?|83In%v2&*9obJ>_Y<!&4|FeU?Y6wq_<E#KAoub;eHr%l;pK z(AfX!!FK_ZGnC5%#!|%;MP)0m#bBNDsp7}_isq|+0~I`F)F1GQGunGJu;R(DhsN(4 zJZ{}GIRp9usDX|DzPqyFN%Ad-K^#ZPqmh=-f;S99tbz|&5D?TGZCLgKH6c(ARENbS zwKYFZwf(*3wU0O`9G>=-sj4D$=hK@y=mSF4`SAP*S4vcTHRV6clD|09z%`<jdkcIb zVntO#1g+4*6P_cWZggRNBqt>Q@C8HGBgK)%NLu(+F=gopBZxesZd7Vl{Bwj$Dzv6f zykE;1T@&l#$}p66lmQaB(EPA%F%6GhM`3fNv#gkZLVJzMp5y{n%If+rG9%>ml>B3F zrb+4iI&8O7k7SuvV)0Z*x>H}=O_t;ZB^1h}`3UC8Nk)rn=G~kk`VW?95^S)O7-vHh zV}vE7AC(v_7K*m<V{R75V<iBVCK2xrtS?aGa8M-;ab{a+wO}z(!%@|(Oc~<SP6x-3 zXwdC5rM*`=)3l&}#aYWjX@S}p6$Sp6|M?nafI(mHm?*uSZse3i_POm5p)-V2<GtP( z521*G*4{kE9WL^Yp*v<V<&)d4_OxyJo0GD|TG++fbHo6X^*FSuh-wDP(DcVTbQcyv ze)`6~%_iw6Vl=Ra2_2gBY~SA|APo?g5A4xAtUY-Qok(&2abyx@VaZ!<l|596iqA^% zvcq*RBS!2*L2bGtqfxaS->8#6g~yLCQ5B`{))}<DWuQ-lIeu|r$2+RZcd06HsQ+X| zLM`$;z71@0oLR>G8jK@t>+3oFIjJ7hk`;tCaYRHcKlAaS4Q6Tm>1Z%IDz6c2L_UC{ z&Na+`^U*QolEl6YmI?5z5IA#Ez~v{m6bsL}HXt=P7-M<shE(Ve<|;}dNF}q<t%TMh z-q@p=fN*F*8}p-tQQ{DXP$dB_->gNTEC<CB8bo?hfX;j*d`#Zs@HXM`6&(N)8<x_+ zC10dxfwO>MB#1GL%_N_x>icVi%_}8~HS#r}*0e<Qjqat25ziV@wpU}pk~)TT|CzJ` z!(;T#@DLh8y+N3i96cS9)3cLkR|q3eQHntvcyTxsaU|@GmY&NZ%Lpt%u&8yW#bzc< zN{JXAxTCHxglDA;fXSZt?La!s5(&#nNhI!8NRitifI`!1NgGf4hPa)9^2FM%Rf+71 z-U}@UMzeLc0Inckm<6vhoQu35;*N;aYX(<7l@yd(xGGcdS+@~bq8`f+h~$deg9MQ_ z3({$5wir|qKNHWXJ4>sDyHRnkM@j-F=(AW&vSu=o0i%qej=U}t!vr|ZH;T5At)5^p zbYV_`p0l5V696o7>>2MZbOKs(oQsg$xgEg6@au_Z{xO+ZCHQ}vb%>RK8&l0C*Hpo8 z3W@~h9Y`Qqu=m0WAN+o}ggFN)#*TAfVU9T$ZkO8sMT-ME3-LuF7MKwEb>vD+@L?iD zVdmb?q!%T)HKfIAWA%xoX&any?{8=qo&jD=^(3<e`a$_jjD7M5m#5ErHwDl7|M+)1 zn_aXxQZeCbsS{JiUV|Y+?q3;XdmI5(FyHMgbm}!vdFt>9ZNCs}FJM5a^i7K1z-)~Y zY=jb<bJwGz2(c0mf-tk{ZSUeBc5;($lu(YTq-g4-ByaxRmqTnHdT_XK`n}Yth;X!$ zv7H(yIF7X2vc<hhxZ%>(=c{sC1z3}GxhM~OI<PLtAPoz@&9cTD^g&O_s_4pII|4_v zsg7$QL8DkwiLx9Y47f1;yPYiY!m~LKj2wvO$BqC|S!Th)RNsFO{isZi=xoy!MB*iN zjO#V<cU2b+s_+r|MDMP>fh{3KFGmVy;0tR&cd5HIv6}bbs_)>?K2ek!k5RvJJF^om znQ&jR&N;E)5^H#10#lP0oFO9b9G_%=&ag>z)9SAKqM<J!Tf=Xg1IJX*L(xZpj$)<U zhd*CS3WzfaoP(4QY>BsImTYHS6KioQQ6a!nfSdEis<^=0YA+Mr!Qd5pWPdy+&_^5_ zbb>IM>17HaGvstKt)}|-*I2J)1^2KjaDhn~RWitNb6xqw1rH)QxM`rR3@i@RM1@J+ zv?W&M_djzY6Al6uy|xhLrC!Mq1?BlvheL1#LZo?3Id-e%F@5|;QW&#&uU3#Dzktt) zF6r&&_hH9|dHU+$l+}M^J$2Y(p9;r{>(y8-)aq8ppsP+gY?x<?n<uf*++&7DR>vcB zHZFbxd?8A~OrYy&{+RA;nz-1WXPwGSi^UQsjB0t-CtnI|)_ec-&fu)i-QU7YEXUrI zSYQydW-{!Fd%e<cwn5ql4K3P%C}YtVzwF=rEq{UQE~Sq@*q7aSPvFzvS23+c$S_rS z{oY2=jy`?2e4xBU=&Cp~Wi0nT(7NDWQGM7AE4SxAPE+G(P0)BEhIWM2njN8O2+N~- zKMC1Y9)gDsBzBS`^5gv;$(rC;i6JQ@A|n}d_Ehth(TODe>+ep0%CQ69TFpw|i=1Ys z{`4~_SNzEwyMg&b&f2`};~y8Lzl^wKWBh|Lzr5q|?%DFNf{Eo<PKW=x2)em$ruAPI zVc|u>r)}8S?i=>%Wq(ujH>U;?;0%j7#+}kN=l^8JRIHA!3T~l?=SA2fPIWQ%8qYk! zfyS8;J5Mk59r?HQe0XqBxK^?Zvl|StZwEw+`lDw{skP@B)JL3F?+cOJr>xQyTZ^UR zo0zxTAWIlZQ)$Zsy`Rop*`6QuYWgq*F16S=cVwzaZWnRp-CzTsIp_5N`2fRkROLaq zgZ&~3B>qr_@N=KvP%N&Aj30mp$!t221Lcw;Qme%WjE$UX>{cD7g;PSs)*Cx96hz@j zOrFs|;fN7+87>99yD<8XGeKiA`yn*KVW{`O5}Ngh^zj(`FSf7;+mwYT00Am~v6^zX z6IA(yZoqvF%D6ew^@t0uCbKG4C%54~88MOLv3y2wt@9;?E5yejg}4Uy&tg3ik-KT) z!fGZw%yIxe7ibdn-ad1dGsyhuG4uDhccfqIY{4;IZ8}zCxqW62YirGq_TVLk&9+a9 z0fk?ZWnr8uX^2rXvA6ZvV(4AhxMOY}hYJLiVf5|VF&kQ4er7BUmdIDZUug_2f;vp? zoP}`9_t5O)EWjEllwSfovu38?-i5ujJkK&^3ko69IW;M)WYlRy5;>l$cbB(SA-(Is z28{i%d0i>-{MXq)`i~85FlVSw$wP$090a8YPCytg9C+pY;=z3oOCut7+Fsm<fKLo2 z^qf%RLFGh#;r4y%g*%5)0af)P94)HN`j3qZ=VG#57~cblWEd5%uHJSh0IRe)hw$qY z6JO#`U}g&)Fkd|n?A`o1-B_u>cpE7KsDA1;;t-tr9J^ACQyddAgJ7gXM?tWyck~HL zTDY|J%$nPYcg9wece2C4s7s{~P#Ih7$^Duj%<sl(ca@YefxiNO7uGPAd8v+rH(sSE zL9h_Q5_}D4_nNw4XqxDf=YpT1dc)qLcx*~_SWg<dbcSIp4OJ$}p^cb|2F%vM&J$?E zQR}g&2&N_IkwB~<WiFtIx79c*C}J#3NnwL$0z)E@p78(Ra6&OaI+A3DVp&ic0{0u# zSI!!Ei&*v<MNCzykw5Tr<!Q6A=cNtKW%$CXJ{!D2J-C+x1whX@Y_jq(1IunkG0*~R zjcQF^Gau8`R?oBGDBpv&8K=KI-9|mr2Q(+f^?)><IdN`Z0$O)z43e`HuO7yBpj&oh zGO7We+a#?-ocO~gnkIRi#_6Ovsc@tKSrwIC8>kHoXgaf<#x$Z}UegPf3JRFzpxmI7 zgyxKlE<gnZLc!h%FNgBnw+cAE5>>yn-|Y~TobVba?Du3y58>q;M+egMLKk9g1DK(F zgpwiy_YI{adQFdy47n9&l!D@@iM!#^zGMTcff&B|mGfF6a(rW-)MJB%MC9)m5%}=i zh+j9ZC_eRbm7=seZ=K94v2RuIg6Yt4fhnjcB#U^vIi!oifN~GN4PvA}fOI~2yt_tf zb;+(~J45#vEEAvL8N-G<TJ}L>OM}#pm`u>rOZ^%f+<Jdu;xtT$rG{mRv3R|lPene( z6-$Q8k5b~8*<rcsv;LA07c8!V8ZKBQgY}biFWGuWV%f(o{r@w@Bg9o!Non}~uIA37 z?TpThH<qU)QE}A&5mU4df=Wrf!de7sI~a06dNcVp?NVxSEOI7WE=D_Yk3)#_t#qZ> z^6qJ&>!a^+vO36Ay4IF3KVf8rS(}kjL$dz9U@?|0DO-Y3{mBU=p*1?a2!R540y=<x zVXBYL4k_dv90D=a+U6O-x>+e9?-Dz*353qw*q4LV9bKG3Y@~3N;?SV<?d|f=_aDX< zXLW-bVzi6TX+fEeRSY2>zhJ!vyzuZo<Q@3Hlf!f-U6x^LfPjhFD(JWqRekJL;gw+E ze1&8}lc^;7yE&lYWaHg!b)DcLl&k4#m=Ek4TshRF4Zs&~$M5J2+3bg@|1~D5!!VKw zOU%voUoCojaM4SVd<qWZ!{(2ozm9mku6Ec`drcK;x9Fk!-H(<ZI-bOfhjJOaqXYqw zuR090K|ZJDu|dTIl4f3b+WqbS8sdL5+B)V=DU_igPTdwkj9!_l`KQ25LF3BWd|GA# z_x(Fdah;RNz(Mb9CN|zk`(huO<e;0KyN9)fp$Pr#onnd6mhZq0ShYiDlI@Pbz%+GC zq8w|`VRd<EzKJk+f8<X46}JV-m8uh1^4e9^DIcF;{xke$&BNA}+`5O4=h<J*V+;Hz z5`T$)hXj`i2)1<UGhFs?FT+x#!q6;+%kGT(le8ZT!p^%oH`%mfK|GY(VqL+$qds4R zyQvNK!u^wXYfkmP7oWK;QeMtyY8lA-jfc?<R)%;t3g-jM_;<sj=I1^KUMNp?N>#YQ zz<eZGfi>-PiwS$t2(~<JxiN$_A7NRA5l0?A`kXz%6$ApjE$?@2{ISVmub?heU}GQA z$^EM!Z0D+dyxMpj+uI3Ax~j@{Od09nKXHO)zs*G6p4ZX#mB`;p;iKdYuCoF+<DU~N z2rC?EUAff%NOe?Dfdg&={`j%*-OB_RPQp}#ocbZ(18bx0`vtmXBg%%0{x6wW!Zciq zO(5~+OQBJX&Q$nJnWiaNMS@NDI&M~=O^ubyh2v-jydToOtPC6se|LRM5E&hC8X{vv zzoS0Kz(q)Lf3n^k14GY}75w=itX^c$K?HLS&}yNHQ|R!t;HNr#2LW6u#K+G37z3me zF}WHA2+Z76Bdn~bp6prqPkkjfnS3M3xB1|GVPAt9GmbYEK5)=VTB0AY_zN8tJyoqH zg4hkbFR0=JtP3vxW*{O8yo#iA2HP+?tuZOuFy91m$!M`}nloyFRhsUiNmHD1Ou)jo z#9;iFD8ekmI&;p8F82*DQ1}$gc@8=OF~;oTG$V>OXjB5RSX?Rc`bbfV5eD42<)vO& zz=j*=*1#fqFuO6|PwhUVLAO=<rJAt)$a`I;NR^})dK2#t?QO%!Ug7-igh6j4$O3R^ z3}uwUgO6T((0C+OhXM2OcfP8C2Izu@kh7BGt9?IcoG-5$uPveQsvz2`>ic)w%Wll% z?;ZrF?L21IJBsk<VKWw|XRi53U0K#Y%_W&H6yOM(>=eqg#w-QAx;xW&-U2>k-3Hji zhHvpUPT8#e3WvgM83iA^B+Gtor%X)%7)EMJ-MnxhkAf(t2I8?(j!jnQG^l;Tw{D-! z8wUZM37fbq6o0`l6pP`tNrmrtfW=~z*(6;PS0FnFL?rM47OI8_MIYD=q#G?*HI$#3 zzq%Tu1lYVZgONvLs|sW0P9O<lhD)+8w!IP*p@5$+($itXQ5rMaqgLQ1!IdEu;(kz3 zh?cAai$wyFrY)#sL1rV_?m@PS5d;HOMQ5~(H0q#pBX?lS1AZ}(U6@Vd(7}2L>KUvL z1_k6e*G3<^GeJEDluEY!$Y6&|h6PSKcrid4NM9c;BGE7p3o@S1s@tl9IbtOmi+xw& znCq{`B0yolxd4d*evg(h+G{{mlRX3Mfsr>BbHk~eB)WJ}x5xnu6%w(9<r!0E1oZ)^ z(vg-9ts?g<Oj{ZoF2XKlvVr98_)19@of5hjep%nU1I)pwjhF<K8lr%u{=!ZKT?y2J zdG^k*4cjJL&w5JgU)s4iTEqPGBlflig!d=lS;wA2WBC$WAb~HOGno|%IV`3ZW!&Pi zD6=T9nT;!A8LfC+!O!QEME_fAkUF9K0i*Hm6s-_Ek$Cf-O<$ruU{k_s6*eO`6o&R+ z78fzq$d+H?r@97xts6TDxXqU3mXxHH9C>tz*R5=uG;2sXp}0S;yXXPDp~w@c3WIGa zZMa=6ukC^uOh>r)t53)QG~_$-;1W1m$JB){4PyfY<znnJ$Fsyp-5En9m<2HjM%3#g z|Kq9ztaQ|0#JkC~cvpm?WDy8*W7p%LWrwMvnav963e1YJ&ihzajX<*1H)mb=r;iH+ zzHlN}$Yf?o4c)5U?Fnl9f+myKyy1V{4g1;ko{VoGvgF{Q1{N$?MxQ$JMA6)G-Kcwp zDlF&i6Utg$<Ewv=d&HMt29E(!i*V1(qPzZUbQoH~Hty}qgUQ1cG%#1x$G7C#cV7I` zZ&sgr^Sux12lxaLu*m^O5ijHan-_}A+~SUJGy(X(@f6-+$AQjCBm>TMORn0N@?KR5 ziHT7;`rcr8vZ0j#d2%flSWE_y`61xm9(a-9@1Y^<y<*QITynx(k?My2pn{Gcau#f? z&!gaX;Exaf3H((z1n@l^4^pgJwlhgQI_`C-)tCGUz?x(Eb(}Z08MIVX1>}>5y0Ncg zSo7Zq?u^|AS3aA14_iczdq1sM*|@KHovAS>yWS;{yM!v!o#e`*r>OL|!&S7S*7T;A z{BdAOo6^r3=&fl|!(K$Ye$&KwEW9IRYzQ)H%-Cna7(lkg@}<H!GX`Mw^cq5V#q61% zx_;Rf`#2igiL4eR_yPCiOaG3{^kiT+n@^J<4*4|XRj_oS>n;8Q6+kZF!JW@tt5+x` zw5acyX_ibq=In;}YESTblJ<b}Ki{soeR9yMP+@n%h0!hFoq*wZEZe>lAYO%R%74^w z%T(4?Oxw#YOhgYwe9$N{ie`u?0zy1(Yz`mke$Tx#GU>tnpus?@H6)FNXh*3_SjOV? z%;-Y#Ui-^9T6j_+UQN9B8x>XUAReRX!k7NWgK}X^W$m5#s$|8@CIYFy@W*ZJzjFM8 zMgoa`=O<gb64^hrd5#n;m)uAV0wI*$oEmZYq5Zx^FAsRdzkP{iuqy<R<`pK;o2|z3 zZ_EUeGB=MqQ~&65WX#U|k`4BnQ~$~-)5*6Ev@VrdQgCs6)Z@&ZA2gnTa^)A9axEgd z!=+R(Z?F@UaV<E8zco@VjQ-$9T>(QpqV0)Q%yFy7UvaFNQ^^OAkZL1P$rBtYXZ4Ha z=XMEGKZCc^?u=3Qc0t)lx0lqa9aSkP<Z%7D&n_M%tQx$v-YcxD?zQQ>RuXF=!c+P! zW<d;%Ua1Mv9<1^ZTgDiMqr}4wZ8UdzhUmcH>XJt-rH~0yC9tC?dxlAxB}&{qpu?qZ z@vNCo6^|#*1T0-aK?q4?vE22l_Y0iYvz#CN(gqTDC~Mo*F)#)>dIo)c^X|>;t?x*8 z&QH`qLtn`uFjsP74gLv3MOY5S)Q~{|Cxz4#qcu0@s)5jEXA>!i!N6kSTx<0di$}aQ zX-#g`P<VtQSvarKgqb-z@y-e~<hkfv)d~gAU#xmLqe^7<Xem>*!64Q54o|^(;I}OV z9#rjM0$TkuP2qVFA>6;fM!-W;-MU%sXPokW0ccc1#j53W%B8z#qoqKYZY%cANhxHi z!vywqd9Pa?NtAYC%j++(?QlS5$iMztL?QtEE2KU5bPX$0yl@D;vGCXS0;Z+`7@KES zp%bcx)0`R?$R@KOXu3+e=&Wjhj<6k71LEOEC|WcwfFp0@g60E_0q}Apl`lY@Lp2Cf z<}Q}*WoX}OxiRx_N(Jat&CnX_VcuVfZQE5H3=_UKbm!zCv%P4Q@O0)_0X#*fBj6$E z2F@GtPt0aOV`CV;LbL9P`^3g_Y@wY7S|WU`_{MBl`jLe$5vTyz@zZgemq3sUg&u>r zk|xI(K*?#DfjWoJrbwxn0U!;L0W8{K7^SI~R1G?-%}08(9FWNfF^dn=+!Q!&R$(j> zh;mH!?7B#f5c4M207l;4{8W<uYa%cA@MDiGtnQ+_;NN=<<$Tth)UNF;L&#53Fy6ql z5j6vff|Z@HHiZcyh5Voe_IV{D3kT>hVC6@048k3mGE8F|1UQcPx1>FD$p!)9l}Cma zn=!sML&60Q9{o7DHJJHB>j@(-7F5Hra~1!N<0Gw!2g62|LDVm@#qdKQjXFRzT5WE} zHBFAx2>IGMG7()j%A;k*)!TBa#<r8qW0EX9aac$(+!%VZm!M=WpcB8|&5O`!`+pxT zwqGb62y7@EG;E^{wX6MLRGcR7^HWw2`4Ojf#Ma>vHE{|O<nhg~1q+|IzZiRIv4XMU z0w@t7jgdt~k=cLh(DzbKAlZ<_{Z~?sGD&v?aQPZg@%u7=q2pRX+GlP1s^|`guC;tz zu1nq<|6mv7+=K}3DONrAdR=W`{l(^~2`dzSabaaRf>uXC{(Vau3y$PZq#_s~7X~?q zoDKyoGmV5>IuSG1!~*<=Uk;pAf|OXeF(GrlfEYeX;Ly7tXB`bE%$D>ulD4h7yn*Ds zWI}<7%tZYpS|Z3dfP&ymw}sIJMfeFD%C*rJE0WOAABM`lP6{Lmm77K^@`!|B(*4;D z+-a^2tv9<SkMa=vCM##UJ%@jtb>We|FGdfyamTQs6lV$rjwI`#ACxNwVEGqRBl_{3 zFn160T2iyL>91yg**{p|@Mls|SVnahJ6SeBLT4F8z1almRnp{^wd_!V$ItKgtQ(i` z;J(z>SgYq{)4^vd&KQq)-XrAfQmE6+t~8y}69J=XqTVr8SazlG_9#Bp#oZMH1iRoU zoUtw`v2V*lNg0B>&)5DOHHGi!G^z8m2A96}GEca@ArLK1e~vP=U>B-YHBV8JwW|~u zgNz2*@KH)q?Nr$gxy2t+HlMC9o(|f@S+sXem1=dwrA>JqH&I5T&Lx_o-9IqJ-s9(o z@A^R{KZb2fUzykO%Je-#YFp>z;>^Lm2IVgFl^-;Q-yYa39uHv=^_hj4Qy-fioH&D{ z?!nSc1l&PZjDaDZlNf^!ben2ECzYNojD{7?u`lRbtdz$xudN7JJY%v7NgjPzjme54 z1VxBqlTWssug%+^9(x*e3aA2{=aqo0DVq#MP$TSYY0m;air}Q(=jK~X1Gxhyw=*|r zY|*h@&dru%sT~o<;O}>59+fmV3U3b&o(Rtn>nC(9D6txQMQiY5s&37rO|>aQZ(Q8a zc(xmp4UZb?V}t7|-O;Y|9WGAYbw}G#F112DP}1zOR~|>f%131zTzG2Qe*d7c^v=;U zcU4iRLB$-aCsN@X_f>OM&r6w)T_~|^!<&tjl1v@OBtd_$yO~nrl*neLt&Q@6H6tbe zxahYZE0mH-6r|=Uv396ifs`HSEmb7nVk2^;*6uwynsah+ozg67gIBSv9lQ|5lF_3g z?N|204@ax>BiP23#o)I%NK~V=VT47cnRL~<DnuYuhOXwkW~!cDfs_HFt`?RZI@cdQ ze}TSev_kHpRt7*2z>fBd{zI`xc{x;Quz7NXlh*IwPllk4Vn~n7-&+|(8jWf{l=oVU zAJqN^>3~e(G0B^#E9RAlKF-r;Q!p^&SzZ^DiGW!qXhfwS>wu6ba=}8n-I-h`G6kn^ z(P~LfCoN6r;>9&O(C5b<0_jj<AY#J1&hwuKxP95~y&UfO*;TFQ^w0hD%kgvP{ILt? zs@db!CO9jbXF-y{SXmPprq%NE3}>chFV1HAwa41&wkF^r24b&Qy}q!^Ge(3<_MLkV z$g;|{X|q5CNBPBPZ9x<+A(#RDpIMt{8<c}J5Z`!muPdx>Itwch1sj{c1|BAAzzDSz z?>-!l3pV0WBh9Ms7h*C8u1?#R)m;Y{O#^^LoeY}q@EIJmCPP^6B7gK%a%tfO=z#I_ z*Pi6q!6g$M@@edA+wh_ql1EJW5jfD6ARL70{<>OBiaXWN|8z648v*Q&7wUZ+gaU|T zQVG{@jCdyqo6aGg5aQv_?qz(cN)35%40Ah~hNw^!XTZlKsjw6{e`hAHA!g+(97JIH zBZYgJiQ*;78tOg#v;@w^ayi**h_qNu!7XeFLr8*DhFCv%gExmy4GElhsCv_fI=Rl| zv2|Yonkgc?p%Cz`$rTTQhXW=B?qAEt;ei!O^y~i-nq9$;>o<FZ4+JS6c4v%Euo}ga zxDj?5#Bm!Df~yTO0g|w7a*Phz8*I*Ej&nG*{0y?h3>z#-oj41r!Q0btx{r;zWMMTd z^k!EA8c^@)MN3A?3Aok(kcaPxZzy|=<lSRx{oP*}L`T_?bIS&()C-V+HV%#-O^if< zT)GpErsQ+P3pmt+-X6h4(>Q(`f4%^j8AAlDQd5XfpJIRbf0dvuI)ZWHU5?Y6$c`TX zu|PjC)sYOF?9A{^cGlxrfqF?fPFB_>1BnL|3zsDT`7pm}1hBp@iOe#fIp9YR33Zda z(cHNiVzVSAUZDaOfgK&d7o?y%ye9O*6qp9=3-ifBrRD=x6@{F!oh*WN5#gY>5&7d- z7g9wGfF)!rp&-sgW)HFel)jP|Tl538W&;v%!$^dtss~-9b^E4IxH+-f_Rv(ocoM}( zs?qW82S<PVpfQqg;HG~ce)prlnw(H0s%$WQ+m=<sdaDvwe8g{RmODpKWSt1;feP7; zu%bJF$k(c+pV7X6Z*l~4?Q7*{p@jE3<Hns8FP4{>Kg(lXzT~z37P6wT>ig?f_H;<i z0n}eh-oO%R3H;HRW`-RFkO1TD%*2wiR4rj8DvG|ox$RsUh(alJ0yGgLBg{-NFbi<J z-@ZaHw+$}Qa0JouT0G-<r-9F21le6GScjmYJVzCYf+YDEkS-*}V?flxUsUTFpmsoS zocCqJRD5v4@1k!n{V@~uFslVhLHYQegTlLvineZivREV%=vA2Rf|Vp{bCyONGckg* zP4WHu;o^jWVLZREl-pN~Bkq5iVSjjRt%3(oh7>pKc=*Q00~kUN65{2Na`$sF@hN<n zuOAwW*=IezE;#C~OJ5^7zB<Hi@am_{saRdw!I1~bi__Vem_QR#foGYx^i5={ngFvG z^y`&tu%V+lWR)i=V=zAJ0zwR%ed1zatQ_@1)j{|HxyTsk^*htw7x@F%5Hor9fvI2e zR8!L4z0wYpl!OlPg0SSgRkxCwgX5Kd!gYvjMx8Rt&d=WUmQ!$7Mgbv}T7&buQ#}y} z9o-uk9WVgoo4T8lEr0%|{By#7@86@<x}0(;<;LRCNnYXjuDC%o{{QJbMgE)L;`dVi z`xv|>&HoCQz@<uusS903Fli-vueu&Pw#fKtFj(a^BrsW@?SEl&h<@t~whrS2LxDrd z++Gu9ok{kdF-<qD$f@JZw!-GJE(ZPE9Td>jF<n7|$Fmi0#N7&Roc&w+IWzWYN+PbH zH_Bc5w*#moQnxH|_{AC5Ai(~lRxk!@ca|9Ro9I;=LQa?-Q?g_+;O5P-P804rLP@=e z=2+ze>~wTta`UH?_Si0%9~nX%zuh=`U;|T2-;Ufke?wt@O~lE5TOC9Nj%#CnnJdJ0 zEcco@ul(n54*%=?<lQRjPMGm+g1BU&r-N&Q1A2lMZWI-Fbt?AZqnXg9GlyG_Js`tz zf8Of1)DZ7Xh1FDjp<-R*3c)`^PN)}UgOTF5<zbioPB)4hkKSb*q;UGpbL-0Kv&W(x zfw`+ny`QyVWDunNsbU*<6KBo9r9@1CjY-z=&SM`%q+Abf7vO>?9xXp)>>epTmXjJN zuaUOtDK^zp{j#gG`<oULQ!5pUo~+{^^WNtT1S&B!1Wn9u@x)&O%%4snfj~&M?8y(t zUCbxqSN?7z;i-B1Z!$PPfs9|Pnm_$d-xHUeK#bou4-}T9G56xa$<Xa&C&}iBtX_G$ zj)v;^PX(>04?DU>=_u@L1)&Rn@_MLzTdQ>!&0bMzUNGu?a@=bETlVs#)5!@U)h!!Z zY)KGCZb*WO%RjF}LCAL^3rz?zfbE`0V|}zWwfxvaU<>Xe*R&KHldZ2kUZ4m?L_Z5r zLKvmR1kZn44${B0^V&UM+L-MgI0T$qwcP_j7;Zko@@&^f>B&gxY{$ger<7oBJ3-@s z^pSy$&fmRL6<!#d31EHSgQAJJ31D9|&}@yF0DI0`GPj=&+Lpia9n45OFm5tYiwVb# zm1{CV4=eT706XLbBp24_V>kswL#Ses<P0jvdCenFm}9y9*SWN@3-Qec2VokemDKzI zQ2D?GO8NtX&;gbHbbS9P_&{jeuFyoI)5kk;ybH+N8PVd5Zbbi0U^7ZSXJKXMYKpMC zHvLJn4Xo8ruQz#26p_xo61`KO5ZjmX@$U)Kp*!dcF-CMwK(UsLRZxs=ke@k6>O{-- zA?liKLz$lhj-fStj=<(YhwlqkZ_Hf0W=PPW?h6(<0_28%?;}M`VCr%#`~xtPkJ06t zv;{g0BMgcxOh>ET7%OMson$sojqmkJp*%3<Z-+@YEEj>ki-BpdFsL9Ajqm~uuicz0 zWebthshn~Kglm(mX@MgM#pNKlt^i@LGmnBdEw8~e6Vns^_E~lKDR|w4Fj(6)f51Bl z1)T&ACn>04O$bN~UHs<&0I>-J<@K5jAn8(P4Z==m(?>i(HiNG+!p<8w<N~@uopr^4 zrgnuLI*Umif4ipqK6y2|A#_JnTazIy;~D5B!BCWDNc%vO)`bH+F_{=ooa(*E&||_+ z2+cY&69OXo5H&fWHccxF1(0VP0x)V73;hfbHcw6ENsn@E4PQC(?KB)@RpS)$${~<R z`xp@pZWBYjiBl8Xwc@KC$yNkTKP-|#KhXCFB(MP`+87q4sczY71mIb)qx}g;B?zsi zg}ZS+)vy-oLIcu<712Pj2ni8Ryo_ylJD$C3Uv=O~CTaazu`m9`(~l=l6-SKoKHuR( zQ{3fm>>vD8+c~z`HMXvf20EX#<AV9aidhO9?ui?N`BPx1e9&MSOm^N#ANUbXa9bgx zTDIfmC8)nQ3qZ}kWqU`-(?t!6@=vI^o#~2Pg&YiPt#bYixcf!>!UX|=L$TzK`yFe{ zI$YPQ0^_Lykn?0T@if1{=fGE!Zy+up>IDm(!fKDB#V?04L6HZDjSG!0nhR4>+MieK zX%j+4tNP<Am~ndn8a6vWOmI_Gt10sM6kzupcD&h3X2=HZ5=cx{@7DC*4Be}Hf-r_s z(^~q4@$gcv5TfyyPfF?)D2-6MHGb7gKE$xQtN$l(<YV0gbS!AtiHMY}NrTNZL>e&R zske>YAX9zNz=d-)m0n7ftqM1gi6@hiqOz+gf~ayVfF7^=E9Wli9vsy!JN!_vLKQd- zoz&?-eJ_uF?~iTobKAi*evR@hJ1OH}9zA?ciY|^>L7R^V=ox4zk4m5K<8rK98Tgiy zs-cp=W%XX%+%oz1{>pvP-)Ew}OlDeh{-bi*nP0loOt~YhD&vx3JUImWwRU6nPl&I| zS%2kty1bu9PfXZHEDFxHbJ?WQZ4ZKGGq3%WI6+nF4%`wx@R01GBoE73{WXF(8Iwr; zfZ&qla5LQ~gS{2{Xp0D7=V4jdjOvm=bvp?UAy-}zi;x-T(><}_%(yA84RkE<UhDO@ z@?&&2-%x}@N#WuG0FV;BcRIfL+}g{JlIj^DPkNrERrZ0xf{PsXqGli6ksq1JCbomA z^(GQc8aGAhKU2dQt;hHw@z|mtQI0#}1Yv;doOaIxH*pAy1lgOx&qEOBf#Umo2V=`( zIHkFwQmsmif3ao7O%`Zn9-)g}Sg;K+h7}u1|3$$E%>3Ik(^f6^h_8G8#UlI>uvsMF z5gDdC&o{?A19;0Y;l?bT>Wd&5#$~fM-oBa>7JG;WPSX}3p$JK3X;<ZaOu%f^8jhND z0!<dId^Ha5SFI32q|SAodD!khn1bzR%a5L?%H?Rd-onl~0UdD7RMYhbv=r#yHD{(X zAoh$aemOk$=HAdC1yj>G!{*`6jW8c13;RfQl{9^HB%`DGZ1h)s@zp`$T{}3nE<2&J zZR5<dw~aXQ{x7%;QKakeLBTec9NahNrY9<X_l>uYxzlWcmcEP(UM?|wn@ZlHHRh{l zhj3B(`N5o5`v@S~yY}rK#tKrAbYHRGw<kgfkzus{)S11V7#>VxPD-Z{LYX&!F=D>y z|C!=v<)yG2XEwNtwL<)QY0_sLD~KaFDru!>&WI#CYYyBX1452JIYZIkx9CBagStDC zTyFaF>Ai-cDUlu2IG&v(P1nfZbetKuaP<9kx2RnY-F#k?aM4WY#e<pAev#hqkIrqI z3UuSw4b??J&s^C`iEp$zu{W*zS|!wDcY$2N6Hldl?g}GJkT)RrOS6O{K{cd)p22fq zvxWyo_-2V8G%Rfm(;xqlevZ~yxAKut#JX?LZ;G}vC*+ixr3}n4TI!^zx#89jLZ~z1 zxAmH4-k1sDNMJvlrtyde09cs`S?Or+3<G@B$$w*KBanKb+egF<M+_YeEjCpVI&D^{ z*~RKYfhZ4T=FRds2T6W02GG&|DUKnB@(x&87A*MUR<z2t9~nw=CHNxdMg8|~_e&bI zqB?S*_IOZ;{Fz}WAI}*zV@{>A!J~p<9cFDuV>#i4ZxDKbCTAUrWN>MNrcgI1B_5vt z{$LC)k*e8iAQFwc+|T<IP*lVN)S}nHx#3Or+|*?f+8bsU#I5#8pSI;%JkzZ+2`kVy z!p&MO?u)}Ow%>qWXieIzjR0@agQn`D=SH@5SMNH`z|Vj+lg@^+kQS~*b}#~~b_}Ig zT>IO=a2iz2Vz@hc1R10P)M4~(2KvQ92&^YWdRtBk2m=s_BHq5x4Y7kgJi{@>(^rdF zNrgKS^En{+u$aG<d70mULIaWw!U3R$E+)%nc%VPjv9TwJL2!}j&7WXKi|IZQLVIBz zpV0=s0YCE;*!N(607Keiql1E_H;bZn?A^{O$gRhiw>WJ9lx2M=Nzm{2!8)yHR;6ML zem4V^>iUX7sDYG(ZVZ#s*=WR#fr=<dg^AmdH5;bgkSV|l6}vLkB*QnhJeVY4eotl} z#v|Cspy^K_2C@$&?|><G329g(|DxLSHg1Cewl`5@+5nh1-WVa(dDGFlY&+R7JV7lz zyq+nDC&b<ykhyG6A;Kmn7Hg1-CYOj#DVz|YK2H0k?X#6joy(dmGh*v(AhrtJ{a~cc zb)@<CFn_B@-$oV6$&!szz}&spjST-&VN!YlRLH~F770}n-7i#Mvp&>@`axrH#P4&_ z83=bEnc<GW6tY{WR215de|_}lR|Vdt13oFS3R;x$>%kSSL|tn2w9PmBf}Gl`<45Ok z!l7&z1jZYT5>Du;e=4Xi#;<%YH)gOcEO2U~_a*gQ52Bt2zYJ*-wtUz!dnM1dLGopN z->+M??z%P8BVC2AJ2-P8A+Hg8rlvcUL$6WVBp)S-b@VNRV(%C#-^IE8fMD0Cbp=Vi z(sgt1l-k$~mvEFgNi!ulQw4d*N$7@|mbW9tx2J<tg>d%xpwV)D-8K<+8TM8)8&WM< ztPIp-!8vd?*mnl5d=O{hF#fEw5m*JvKP)SV=PB0`QX1Q)Dt1AZ3-7I%Ku4wjT$;Bk zQ#MGES&-Bk_PmOMGM->B=&>4UmNpwyGNe14UEfC2w$Pwu_Yw=j_ID$&8IuYWa9N&V zshpld39k0M^OdejIu{qd7n|p8Tc^jSsb##kO~Hx1id|nt{`}`cQ2iiNBU%!?syI*_ z@wNwT&u!whvM=MlRJ$CcasXTuCcRo_dgx~zKcY76UxYy<pYEw<*mxV@k6M_uJO^8r z+_sIKxf{0PN8iXt>&Ir5zX8Im7|W$x9$Y8_Y5)piLH;k$(?DFKo|FW}<Eu}v-I-jN z617*alTS>X71K$)^-1B`m8tusY)(J51UP6I%1tuKe~Q<K6LULvA+?yV4YVOe?^um+ z{q<Lup7>^e$}PvcPngs}?er?vqx2OeWUCtEOAhhe_3sy(s;JeAY7^w6O=~#^Uj)Lr zNsI&gJ-4X5x2E=|H?Q?RVpfvKTaSP&QT+6NBbAme4yTfjT5{#cn?6<xXuF1}O@emM z8GZQpMV}iz`vFbZ89j;uH0vnC)P7%eN-6v9+3~#bLFW@CDmJCSCpn?>#_sAv!7aQf zfMVan@-6^NTKMM-d9am6VULxF7x5qHBksUZ0W{}^FVhXBgDsm_jU_GBbgVgnQ3g1j zY2Tr7q5vmILwMoxGjWTJbkK`n4@{Va1~yBh^i7VLe*&2!w<Dba6|Y`Zn=$|u$MfxU zH_zkPc)0>hG!vW?7B<}`egSYSQwrkv)3g|P;iYaKLV_`dp|pczJcblz=pQlUCh9c8 zh}VFJR%bS1YN#ePtZs__Bt^Bb@yE)W0w-f=By1(QsFctQntU|&u-#zLAyctkV7GGk zX>ntDC5EmDUGg9z0BWUnOvD+s!8uQH`1yGCSd{YuY|@015GLLu-Y@;<a}HMx9{RCp zG$1pj&UmJ*$57ePWc^2m<(_~ghC_BVU;cC0)|41tpSDVCS^*4>a%1&~@Q+Y`-5}a) zAB(ovgD9tyaYhQR-|LKkDZ$d!x#w+f{N4$B=~F7zp&N^*iblTrZtC(uN!#nFSlmM8 z+r}G&v-TH=()T}T(3>Id5)%t{Rnfa$C;I*EwXKxsxTnJ$WiBPt2BSwOqMD<1-!i%! zC=*BtDb(QV+luM1&PA`Q4bW0HHV^R5mam!Ju;JH~5%vVsb6lr>Tw^Zhmi7>(vD^X| zM|JDOPV7axJ9KoJsllRp^J7p;sLq5@mj23jFjlTDIBFRmz%b0gqG|XOdH%AD$+b0e zB0aEHh`XuOT|ae$fu0WXyd`0&yi7~yb)Y<0ssSrC6P2xLLa<aVDWaml4*hrRP)2}* z18iTgGsn~SV>$_pqctX1O>Sy)o%it%WuWjy=mg}K{gH`t)WYYQ*j>X?!DFcre;<%E zeGAc5YAy#$$M5tB#l3zWa;rDO<tkjnKQZ!gj<NOELh<`+J@U(SUflLW6>!;+!mZ+` zsZFZyFRDj=wa&fKD@Cd+y1?LI8?ohO!#gxmB-ca-Fb`reFW32Z7zZIfcuZ7aeyM!B z^rN#x@i`6919>7IOdFC4uQ(VnE<(2~MnN0Y7zYN3H;^G)0qI$Y_5{mA{jpwgre+a_ z;dqKYd{>ME@(F;$CL#|Dd|xH%HS8ULtG3ls{LbD?SpSesXxLFe2z`*`ob3dRt+E9H zoj&>k4GIUQ3%GPR;35-*%4%|l053^<@XyT)aoFG_35_XvYh)!-+Q%LkGq>kXBYh-d z=W3`X95F-$iFYDzqW_9F?k+ySNs$-%cQ_dmPuiK9!<&dJTsVgJ_s2AMGiL(H25Ytu z7z&p4LRS}Kl!L!TX70i2DI$;qAsBq{-butN9$Gk>_9S2;u;hiEVl#dgr~*QAEwBe# z>vsHM6P`jP6=Lyps*#34*(;LrP~<Vy&$4}q0Vw+iG=OuHp$HV1ctxPP5WsUGrUEF{ zpg;r^0>`#E%B#(v;MrkB>dY)gJBCl4lqL(O!ArH}I`yJ8-@K@Drbfq!bY|0^rAo0G z0n^pZd^Qa8$Vjdb$sP7ByGWZ|nB<Nn7S}X`;K>vK?k7Z_%R$Zj3ietO#Ta9=el3{J z-1@0wf5-QDU1Vs1Lsxqpg3t12{hmTM0UNT$eS(0!UeA)Un0ZWHO!>*h+!2y>QxDei zcArJLJZ|D+wxRX}_IKNbw<1EhRZT7Jv|kWm`KdPjl$cjbc2<dZ!~R<Y<7XXmpprwp zmpGkpzI0`t^hs6hW2#Usu7BfP58{BfHPe#L9OrxJ_^949a2IU>q(zXGxGAP_x;#pe zlK8&YGE6TV-$RH(ou%BlxMxDS+wI}<YBXiX8Zt{thV!mlPau2P;TL4cw4(R%C?THa zQBGi;TB5y`2*j3!PhhZ**8&wwectjb>&*UPP;tAkn&g@7j!5KA_35x!&Y*-)F###g zsip*}%SS?gcr|i3@0ok)mCjOSXM83kt_bR4{#y#O1pI#6=TgvkF`zY=DZK&j<(<QL z6rl`LQPSlvX?ujODBvX7VnuZ3-3IC_>U}9ZrU)K#u$JrMH-3tfO=xDMLE8a_ZLL}4 zjh5rfTjj|e_i%~2v#c4&TGQRcykvpgMZWUrH^V3dZu9TBNo^1%k)+gH_k7Kc9T|9R zBIU#HCs?E&BUPd97wSqmbCkEGy?j49eg}~vfM}b+-PlfU9^e{6K1>d)-@AzqxrMMC z4HxR=ZX8#%RoGG{MZ%fsb%Q@Bp`2NmfLJiq!uOa-Cbk@yVU;w_YiD#qMkGdu>Lmo9 z<!M6>cOx!Kr?YRB_QI)GVc}P&^&R<JLF;tFo!tFZSeQ`*+?G(rd9z13kE(A>;kiIL zLkpiYKUr9_w!yHr=r_hf^{!E@2nqm=HtBgl@bI>D;pQC(7}=plU-c}|ik}XyH<d<9 z|3^533qc~hU7OpPj%iI=_@XJ(cx4TRn@Rj!zc2)e$R~<UUj66T$>PGGB*JIq1sy{@ ztdC(x>Yi_!y#<QK&A!}o$r&o!S)ECX(Mx9Xv5mq~9}~OFeLm-6O0ey52Ax@d7F|zg z`xn~Q$q?sefbxynx8B4AoG54Po`fRVs+ROTpfG3>0h%+lbnZM#x-AMXhQl6?9+`dX zcnEy?+g%?%&HshzK~{7FJx|McUZJbl(Nv+|fAN6N;kFbY6w?0Twv(JYKmRtme&fKp zqgITj%I-gfea1Lk9ObRbZ_xx;-YLHExnIxZc4iRuA~Y6ISQ%~0csgewa|9ey46E`> zt>TP}_e0Ks1XHnOYLPt1uXp#>^Bwc-+kV2(`UrGCb++;~^yXsW7q68!7-g|TwCSFt zL~ql?1V3#@*#Ol6v~Ij{4DxFGDs%;qdq_LEX|ZhV`O5@(^6sH9|6<Z{S9M-nZ67xE zKyKILzsO=A-)Th=sadePOZ7d!;tP}uhOjicR;|}!fV~AU)PQ3^|M)O##CNHeeI!6Q zVAN&Y^0vnU?c!#O!1}QKx!uJGNEnipHkl_jEuwd{jG&4&%SrM7De{o=VoqH~S!4M+ z%H*%B5g^bIegi%@#%p)XC3fE5m%SLu#CrkC*6mP~AgQZ||0*~3&}I_7`846voO%lX z8ZmLLb>^Q=KYvks%VJDpjjUl_?oR8^f<sGAwc4nk7!X(AV{NfMzt}$2jWe6R?V|vD zo^_mwMjj;_mmj4amb_BM*5}m!$0Qd5H|4LtRuWc`BnJ!WthL95<%Q3hV8V?TXYx_j z$REPdjkxbS(PS%b7Yg6gTY=s)txGtcR7?85fV2XeFIDsV?N^fJi}yN6ZoRUx(EXt9 zQt<W%IpN4NeG51wJrll1pb>NLq+zDvNisqV#nqQ$Ee@Ro6hV@=^;}#!kazNo`DvIN zUjd}+5rd*5ISJqk3f+8kEwIw>1ttr}V2rhiRcculDT*<{fG!XI%+wH1K=4rSlC3K( z$l;hzqMAi47|ha`#}dh_`dWgKMp8d$q=5`r0$~CYDgZmecSjPk2GS>GDLiQ@FxLa% zO=jW94Q10kvD#3d(X4YI{+T^ZGMuyyM?<?6tB1<d$ueB{H~faRtK{;|vcqfv1RvNw zrr@xpGl^(~Q%{p)$pm!iwYI!kXG3hw!KXF+_A4`HE0r^2Nwd!1K3fP+J=~Qv?DK|E zW4AkGbr(!D`Se>nyt4lyXm%pgfVeoZu*6oMgZLdz{0m9?b^tyBZzJ%KW6WU<NHhe| zee>`Q@Fup?0b`F$K;WN%%{ZHvbYmt!(lEN~_=d$A_}*<jTnr!$QAjKbhGYP5#1y5h z%y8Ni2a%GFkjQrU9{pb~tav<xkLjb^H)B9UkC&2Fi*H3_se<hSZ9G@;dzdeQJ&Ax1 zXa~+ZJ=!rh_uuYm4xavnkq>%3DF(8`WQwrYk>*W?b&-BQA+2E4Q$u|r`DpNhS@XcR zbUbCe1dh22GodyJe11Wo%0`amA^?D|uQT7#AtR&#sI_)&%7~o@ZRo4%u&##6y`lSq z?s_G!uBIT~(k9F<G>WctLM-9@PZT|r2M!hbNt|ZqNiHVzr0Ai6q}JOobZ6<;*C)>K znS#`B25{mCW8R~#2a(th{RD&Z9&f()%EA1Wec>0UUjPt1qf&tQmsuYc_qEJW2x<#n zjE6<Au%ium7+yGHh$WBzR_bSfH7>+5tSg^+c`~lgb0*Z*<VJ=NbNV&4*ESqG6oGtu zi4#&ZIBsguTy+oBzo2O$93Hgs;We+lmg8gLyy&e~MvaSJbBb;dYGP9?5I{F^8zq1@ z%c;VbSn^(C^W8*USVj~K-ib9Gl{m2N*WSKIEl*$IGH-D*0MSbt59T5BliPHpugMA9 zGYB^UJ~9|Ppd`i~&aZ|RPC6$%&}$y1@IWrCCSs@VBP-xBBWouHx6^@op<?|iBytcu zGoWAWHo&OC@oLD^+Nd8k^-K!~q*&E9nUn)l2MOxHs><i8whgI2t*kvuig=HrCV@?7 zaapV*UPHVXaiM>1<E39OnWq%hV_O~hLI*!57H}6RCmYFmCUw)`n@Aih8`|hh(K6f? z_H6*4@Bpk+RuvgF<LnQ&f#GH~Rg}lsI~A>RLZeQb44yWS)#Gd=^(@bl?sVwJQx3cf zjle$P1Aog%kEtZ%^GD0i(mMXZ@NBTz(Zc=kZ^upwIM$q2hOzSYwWDqfR&#m?c8dZJ z1HuPzk^S96bcipQFseBX+g6aY+O|$(_pgA}!hua^gLU+fAdxArx%vtB+;I<%X!C+D z>>PoJK(twh^&eJZgRxp7Oz?1(3<2_iNZ#kvXJeRdV=_yWN{L5}pUq+zx1<$8X)B?- z(H%5NAmPTD?$?VI(o<NlGhb}6#mEI*!`MThD@hUdu=)iuCkICu<8(pN3v6RD9&!6N z0-4rJOq9SfAb^2|=1&ypnCLDHgO;@KUTmT8x9{NOlSwnUSd>tW;wkcc2%TA2o_2Xo z3Jdo(55mUK#dISYR-TjZEOf1IPwj8C*NHq1rk#b)yaCHjK^<*8`4%VtI4Um;%C<1* zeY^*4uNOV^Ut$q?w%g@XrYb5h0S~F!cAWhU1g^~;+%xa<?|(M4scc>+F-&a4c7PhW zdAo4%dKcs4%kQfcI9@O>dV#Mal;zA+s%&=FP%~@H=x=Pj&*t1o2u!8K5k0}x(pb?W zR1JWA3b@X)%X-fBJMPH+GDnyOC^&8GmHwyP5?n#`os7o|@OEEXv$w{w=-sPT9Eo76 z6NiiM9TOR#{Bx~U9P9qu%+G^L#h?bFPvK(NihK4N+7zQGzpR57{pplNN@!R-*YQ45 zUTYQ?GodqY>U@$BH`PCC-ab?|GU>+OBxhRUf*7axesb{;VY?~AMw=gAFn;`(^^SvH z`aoKrVd0JUW1%ioSZ_XPd}7pkJ-u2N?zup3A&5LbY5UDkWELe1WqEx?T}}}n_STb0 z-#MASL_r3{0k1Z5^S?lw@kp;}aGj$Fi3m$npXTYEf(bgNRfyaa=&ZJA%S;nlo3+!= zcBCg&->e*~LmSB0vIbaz33A-mb?%!OTb62$)g(-rjw)+@q<6W42?qatVC7}}va&A~ zwL8Gt0U0XmmpIj}vJ=Z_!Lv8((SP5^lY42C*`y!+Q7$f`mH_Ug!OdS^6&p+><v<Kf z1{taiemRf!1Lg7|Y<>8_C}C*ty}qP-R9*Xft8OcZl%eDxY481zt5|50$b2t5$*v%H zI?<Ot&$tav@8EU$r!eu?U=RTtQl{dJ+djYqZVV$B`;mhm|6CKrLpsgcHesp<@!UAY zU>L4sqt8F0PRdMC%P7~tjdnG3UT76UHTS}H4B1o<7J9^QL=cAWPccrVqX)>>gplFi z&k^Z~TM-!j<z%A`Vtd{!+;SGK6P0x9u;C|WF_8GdT?a)$@Bn^4+F!Jd6o_P!C<)Is z$rdBAZ6rPxf>iGdhOT%KWa$Kv(BNv%1VLl45ls4Turo$6qk%*U*DBQCA)ZlcyfQm% zFO+;5bQ*Le%77j4<Hc`&4imIejT`DWyQVgsK`u1huM;MD5)sC?5MnbRZki6F8_1r; z6hTS*7Hg70?17C6oHof?#x@7_w1X(~ka^)&WR2a6_zZWF_(Gru%rsFC=rB<L^ksr^ zo<lMV9wx$-!z7{>V2D0NrR8}5FQn?i-b9$`rQ4DDG<MLDp#doMuqPRNmTKIV14RLh zys$52mJN*q!ap6ZwCPT*G0RxfAq+1n&+-g@J>HVNGxsb4fJ%D(<;!Y34}c-C5txq- zsYBV_l7TZJNa|NDn%WQ^r4@n&g7_?wIW2{2p6Ji592v?t%6g<jHy(k2qxQAsk?l4x zRxDK-IP;t4T6Tam!^tl^vS}F_Y++smcj(EJO-$u7@0vNgav~iY#%!Pj;**Rnxm>-w zqrLKcaGQhfF_I(Eg~-RHyOY9<#v6zTym;isxwIFsorfc4n2xjG{4V>OcbW|wDv+Mq zY6NvNn>dveh$U62_t{CjbM963R)f&K3JE2w$gkM;%$qcf%-$1{bosTh*8XGHbR@P_ zg_TXfw<Ha>+d%X{r7>pv_nnGGD5d0(BFRhncDt~S2~0QGawJ_?evTzM{w-g!E-e** z^aZ#q?i6ppG1nkYL3w1~Jq%SQ$`4HBR@1@>8p-x6{dJARxDww4Y6UJcrWfHj=$~C* z2|JQ+oFF~uM~3&?&4wF=^4PWIeC*scR>)NI%;(?iyKB-YM;}u;+*mc7iMrfdeix@P z`13yPpMt52AP7}(2D}|~!7!GJpUQD?`AN13U3Xl+l<2#E*S~|`3-D<0&k&B@BC+Rs z27oY5d49CxFF1O@d(}u5yV>*UfVb3;JWw#nfxY34t*%2?2H!#aK_<U_`u}J;6R@bu zwg2NnxKt!s9t#{#41pV-gXV(BNMbN3X9O3NKq@6dD*_=zfl;g!t3ihCkjEKh6*pWk z1r;(E1Uw;&k|tuZLxOCw4b%VgaNhs*Ue|dqD`DpMdzSnD-rq&@32w_U)j7Mh*6IZ| zUlAq5he-@Ma_BW807o*KHG%i$u9B+;r`g>AH0+Y|G-UlX+g$s&Vzur1dT3UF`1g29 z7iKR3(EM{#>9wZ*PlT>CT9l@It<NJa_eF*WIpGG$nKyIZDP8IA1NEv!z_*P72R1LL z`s1G8nTzV(t9CX)@tI}5vc&6H!Iu2~tDT;;a`}Saou6nrhCjGMZ&I)`KVOX!2_Eap zdsTgv1Kq{&Okp*h=*ao_$h(RyD#gDk?!?8-v9tcpCqjr^6)Y-@;Iesl(*6w+&?*OP zU-$P;cxKE7*hZ_3I*tK?fenCOst>)a#vEP?w+P%|nu2uEnkj}w18$Y(Dh=DFC4L;D zqf{491FQ6yjw+28=jkZZz;cU8C>b|xX2*LtGAG0yahiyl3zO@n;E4j($I0j~rKsWl za*TIEmIUbuV5s8mXk1b`ZxT7_Nf2xw;ai6-H?Bjc>)%tN`S`Q9-)ED+l@ve+lZcAM zV{@j&mP-@N3{A>c3Xc<W0ti#0JeA4oTb-Nd2>OL-@KU(iVZp+Iy~NkRa<IhnAf-{E z{!}v>CdgXPz2$-iU)Wh`S2AH)-xI%Q%brTU2`zsp54F&LV>wtlt$ql=v0w-tq~G=0 z*B5-+-t+sFvWB9jhjRVd*<G|zME`g@eG?vdV(0sVORrkG=bsU4uXt>N-LYir&&#Tt z80HG1d&t$J{g-cxQKf*BauV&w>hJ&Pr_x=uykYO1@s|P4`SqfFc~LU>w*!x5_VjoI zO$}8=HIGWx1TLGpzT%{v!*;R_1Izl_?p%nOP|P2g)IyZpR^+9=k7b9bRF1{D@7s7* z9JCx^G_n7_(_dXT_0Nmx{ZE&)_xxLbEn8V8dn_1}pS3+LJm51vq{F~l{?e(Bq?3xo zrPOdF^6IwDuT$JXYe#kC(p~#z__E4y?=2SJp85!`e3=-l5jM3hqB3Ax+3n~jU9DGQ ztE(k{E8G&X%0<I$=oP2o41Wy7Iq_0G{yW|Lxhmt2Jl%Igaxpm3>>w7baLZbaiUVFa z)VRwj0gKIM{H<qgv-;#{TfgVHYu1!QKKmPo6_8xa{JwaU4xIcp$?rjlaoO-rU1gtE z=S{D3H{R{zs2C)WK6R--Teee~bZJ*kHGsl~9b=^Ls?}p-I;sP<NCxMCT5vR7YCFIR zOL)*yc;&*r;Y+OsEen>&p86Vbj)|o1l0Wr-m+KE6;uK;1HWYbn-q%o+&HDm($7-Bv zW1hWio<L*xDM9k}uZM0)>1L^C!rR_WdNE!9ilN&r&!I+vpWaEWH^tco!;UZ^gcl-M zO~N~lvDl92dQunjirff3_{-p}6O%;IY9I>g_}j9uwa~=bhz(gu%S|}BX$U|G&<Mhg z5=;QNhk}XscwO{J5tW7wfiPm=<u~)Guz1FnpVQ96a1!+BRLEisqM7z%3?S-m11C|j zj~G2lNh;EHgUMk{2p|w+!?l_)R=Lc6u@1PdR(B?DNbkEg+x-A@bV3lu_=;(s$~Fgl zf?pIr>I+#O+{zJj7*?Q5jF@YdIXBlXe+_8dGFidU4sykaL!*lUuYQvtSeiiqQO?wR z8z`Dagj={WhDf!o|Aib#Ih=C%YeEoN_s|~14=#^oAW)Z$7a(yN>>X`S8K;^l3<XZq zIO;wHBnRX9<Qekg^$l{04r&1`{aY8e7PZ&y%8_9uQ!@gyC}3ON))fO_ZA=+EG99m{ z*m&L5jhBTVodHc~a^t$gJoh6jS5Yp~D3Kb-Baa#0m^!YHX^7_5tyL|$O9ChA+PmYr z-t2O9j=G{^JlRlog*8P!?%}ihB`@terynNZPhlfxI2N+#XP<9<o*!rl+UA)XSVV1i zrK`4IR@O25QTV*0WltAe)O6h0=L#QcF+CF%bESN?D*aLIy!Qs8b+V)VyVqY(k7J<- zY2SdKm*tHB!-q~y*CPB)!TT=9mFE1bQ+3#2Us<m9&m=|`dFDCxF*n_J#y#`=;#5PC z9nX%%DLCx$URPI|DZbY!|ET>l!c$>B?8JhY)3&$MEN5^Xq=w$9H<kM@MKPN~<$2m= zVBd`m7nKifoa}-E_!i|ZISYSiU6;0_;Cal~A6_W8uPy+=OJ{tO|3tSc>q_Wm<paic zcdtxH`YL~2Vv>@Z@IE+ro?Dxz^7k|>S}vJ;SLQ6NDKEX#Q4&-j>5NH2TJ#A)ameOR z?_7Fo+@T1y6NyW7Em7OwTzTsVFL-t9uSq8r6SF#ISLM!fN`C8>SJwTn@?&5RbG$tX zIdA$nbeLOulV#uRTe?XnBAf0o`cYjSUA=B(P`sLUJ->U~9|OMsHT(5~c?P;Ojl$Yh z+gsK@i?F0XN=NuVzb@!%vsoH*p{QUH)V7l!)ZQ+B6Po)7r64=&-G6o^r7^YP?7{K9 zDeks#3t2-PbVCuXlM>Rg*m8mi$-VE@cI?-BwWrfpL-ldcKD^%UkgH__0cM{uU*i+E zQ0;chy4c8XJ%Qyb#$NZGyzb37zO8SX+36Dul*ry;kLMKGsYU35Ku<IYw;qKJe*T!2 zxvqBDOXC~t`LCRpGK>aq*Fi)qII`sQ7aLyssrE5E44zkg_pFsZ%*qsV1$^Yutqet% ztbLSqtB~VtQ=vZW-e&#QM0*_CZezGb49c%E>y#rba8GGqA;7{tt<4gktxfko@97dw zV&QtcBQml+{D<9^rzaG~EjHdYW#{{X7~8eC)tCKk=V86c+>cikLaF5`1XlZv5EeGi zU{5&fIA<Gv^oT2dXRznfN;j|J)yJJd`fXey=naFXd1;&l8u?5M*(`<TF=Yh`2w2)` z*pD!Rf?vIEo=Wb_qPu_ZSWQIFL5ZL@;R~+9HWBs)`+I+&f9*BbERF$43x;zDvhL%k zxw|x47krNMk>)gBzC0@0>R5fs84^v+=tm|8xuACD{F~Fl%+BGxB1wBQqPKX1bug3C zRR;}xnPen2RLBNP#$S3klRZtR8Wj!vxEA#V_g<NcCn9>Gm?J4TTg*VjPg^aH-T2%o zQ;17Xc8tXVW$8dLpsS~WGj)$+d@c^NPAj1`qiz1>U}CDWH-5@0xfqQ4ccVcX$}<ru zjVB3ARYyyYjTlKM@X1DEVy&z;cUI~BlGe9+8uXBlus-X6&fD-Cea7^-v9ZOL4_VL) z#1L-K_j#>e8Ywwb=~t+3UyQW1%cK7LshfScU2<IS>Sa66uei&>Klk04U{*p0Id_)t z^beD+PG8%*ZOM#o=>sfV;riN5b$5`p*AL9@Hoq>r;P*q%<u>E~!_F@b!P7JCeR1)6 z?L&`i+Skm_oQ>I_e#He$C2YIYgrb0CKWfJFXH9<isj6>y(MDnM*I|CFckZjNtP+KI zy=}=w&5}P<I~jOOk|jy5`rp)#+d$1i(tYpvmiV=LIwsoiFzuMfB-Cs1PKucN^k$(( z@12>!eUmR7oIA>E93p6>8Je66$PJsT3^N+cKlA;66eR)Q)sF7X`PTEsi=;2*cHE|= zIK;GH(d?W)e)fyWx9nf72=~vBXSQvaR3=PRoZFsus3hmuCHtk9@8!<4ulA>Py)WyH zX8JCBc4X<{o81y=ScutnAODMA%`YCqiUaGqA2667ON9~h*lp#eh11@1<MOeBydv`N zO2P%Y`%|z1qviR-zHiO!tT^*>R{6?*OxVihW)FALV9+Xin}M@9FcN<AukEZe<cMo+ zJ6~B4vCw$1iF#*IuEcs(|Lm*%-;51%7>h5=6_|8fPEEtUU;bzpi|;D56flNRy(~s= zafT%{M~AoYrRHs6@e;Aa1^zB*A7R|)X)4KM5tZ;$r0>QH428SP{B-9tK6><IEB~Rp zlZC^Zq(O)QVcr3V=0dXRMu4-sAr=XB>a@7Ngx6Q;Ps@4{E1EE{+&Ap4U{r#*-@L1N z6frsQBN*ZfkUkVBBn*!!RA(Ar6Y;Zv^7!oRVuLWIx97!UDVwj?6K?hd?MZv9;E?Li zQT|z&AP=n7%iPDBz)aLgdO4AB5SY1N@43dXd4!jrncz+)A6S2-%UQHnsy*YlS>%mw z9MNUM@d)C27?^3Yj6mEy=0o$696Nyn`r6ZgUic}au!Cu0M!Q(R>cZL2^e_PrFiwDJ z3cD(_Og3!Ny6d`{sV*_l8<EAVbQgFE!H2V)ExXu;`TLMv5xhk14zz9Z>cDI!6Rbt; zBh(PlwL&Yx33z(sql)u@dVrY+IEa-PdNT7LJ`XiUG%ke+mSvzC=DUE&oZL9P1Y2sf zI46Kbp!-r1xsdov#e>d`?rzN}JR76UL7pyLS@K6|;cMH@czQZDD(pB@)|@@7;l5+w zA<fB*d?j2GbNz+v_x!S0=s)D74wXG}(vwE;dHB2i^FMl0s(dzgdtXvHg=|?(_3?h? zip!m^_e>?^#_(%p>kPdP0LSHNf=A`Y1FH%oj6HNx_hmITg*ulHQAdo8rp;~PwB3GO z_J)3;zxL%n!((~}4;NvBm@F9}B{#(9>BXDR7X6VJ!?LVLO&WL&qeijV;Z9u%%-(s~ zUEQv4m)9T9c=dBzlZZ)Aln*!5dEPV6t@arX*IovFOZ7O>_Ty)fZ|{Weg;(osAjwFt zgy&PH3cl<D)z$7N+FN;Zzc8-|K`@0AJwm#|p@H?bU)`VRo)@#@Y*k9Nd7S)S8eA_9 zme}IWesz-l3*TH{ogDgU(wBH{)OWSr>-}N+vY=Z_FEw?E`Mw9k<deO5F*mfIR)lO< zysdl;EK>5vDWka;7ub1tU0kKCxz_bTkypl0hoYts8T<Oqq;J0HLC!jm$bDT@&jhyH zc*@3zMC05K24YOLJ4#PaRSdZO*ZpvF(8F&|2EEsE{?6$)8gDt1edsxV=l;H~@ZR@7 zU#mCTd}>_Px6R)ieb~SBrjK9LVnD>f{GQKeuaon!HVI&*v*h_qDHA`34L!B5dp{KB zdTNiYNACno3(~s!_g%JE_WJkf@@5|$T1M-FCyHhAW~V<SuPe7b9N_S!cTe_yaU`tk zv+hMj+%~g|PAMMPe|q8wuEkdaLeJ_7fzi0@6NLMd96uGV1=EmyO;E>9`=66vEw7KE zjM;R*Jo~@XKRC2KOb>8;qWZN<L)cE)p4e{G&cG9qOV5eOt%sZhl*I3_ce!}_;VAEC zk>y6@Smd6Zc*>^kUj^j!0q6-F8+b*(#5;aR5l{J&j!y+wf2GCoF!jfrGy^7QvyB@^ zn@QYb+&A(UmL3pAWaEZYMM>ut>)6Mp3Aem|FVM;!KH)EFyzs;lZBym>&d(-adxtf+ zGgfRUh4s0tnLC2cHN2ISbK&1Tmp4f@&UI{6#9jr;{%<-fRyA9msoXMrBf4Rr3k#cv z{a2q7EBWA0B%nYe;1hT?{i@%Z(DL4*M@?}J<{&L$cEz%=HESOyd+%RNae<OD6;$(} za*(4R@LSd!mBLH2P@LN{UUvUYPGDtcKFw4xv0{5(i5GW6rql92C4+`GTD0SGv(eM! zW=uy(QY94Jie<>d^G2e%aGgoSU>v!R-Bz!K1rrD6qjwbjnOo8Fc6u8pGkb7d=%&a6 zzYPm636C!^`Z9|Ssad@jZ$~tnbH`j7kPgg@m&+g8PMFr{)=(_S88Fqn$G&{*coANJ zXX)_gP60jP3q)I~Vqk@gYrSa$Lvzd>G24c?sqr3b5*A{?NOUXTKo#|iizkq;8{&4@ z@duhy#(#QzsFf;al-cWZS1vc4?kj*B_3<YZIc82Pqx0yRD(|G-ImYYbC^dUy;^d-b z{{Hzl20yRbagD?W;4jtL@DehJt%lxu5ixw$S~vfND=3KL3&gV1l}ST4axT~{efopt ztwFC{iE*K3HGHtZx}00L(Pk4qopVjAdb9eMh@hpHS4E?;?R^eu#w)?@r{9uiYqRG{ z6aNXo(p7gVV$ltWknGe{$LZea?@QHvQn^JXv##7k_q>rqUID{AI&4e5ywUypJh}R8 z!QlGLvt!lEk@?a@D?0AKaROFYO)-p`L!32_nLS-hYxQ`e5G(<J@KlqA;zpFiIIMl) zcPCug+4f@dna<B+9`?+3em0Mi(P8ZFMb+1*FL*vZ;|X-#RRRM+SX`=EmN4|niGF3N z4ZUYualx$cX?F|EHx`=>rw39Do``B)tXFn3Yt^rP_xrq<5<g+ao)gl4b7<lA%?1VP zopUWOpP_&b#d9Fx>HLSqVhCDs)|Vfhxy&9)Lh8@NL_~HS^y{n~)mct$mP&{ti*sGb zTtQ7+J&r5K!o&%o0OJSI2#}WWa#wnGohpsxXn|2f#U&GZ>C?4N>cu_3$$sOXHhN5I zsP^OE-(Dyip5|_}BD1LBzX<h7gBW5jcTG^ylbD7y4X%=#-PmoezFcO?x;8<XKOgiX z_k`+l^XEH$Rf22u)t&fCc7+!saP16wTS}F#*4`KayPwt;xjeNSV*G*y>F|Oy!d|ar zh6Uf*PkACPNuiNfSTBn|Ee0U#)Fc5xBLxsqSYuUl#Cf6{aL5`kS;jrn{e)wY0Q$!$ zG4od^j_^$I`8*;_TT*xi_dpuEC@|c>W=KIm=+RXPb1T}Mue)9x#6rRu=3ccI&s7Gc zOheJ;`%dC=9c&U*WCPxTlIgf`(DIZ!#!~pBsiC|mGG&g8C6Kq|3M?@T01?Cx$TvxU zV(LqAtUI47NF2e%GhgVb4^qbS)gf%U&KhsOON;sS^pyrqX7f>e_Q@JDOD-}l!{(qq z!H1(^6nc9lS(O+%rj@G2(dh3q96Z!B3Ji2a851nW+F%6Evl>lDFC;O}Tf6i+0xwLX zNxUw^x!N#{UziwNhWe!*$d>^Kh>lT`Q*uM`+N%!2NeIIP*JvDlcR5*r9@COk(>z%i zzG0V#lO@iP-X=o2lYCdd6@(T4bH?--<E&P>_Ez-!U3-`mor8>{f|ytZJ!r~=AC0~Z znfLm(%_~#oc3rd+&=zL5m3^a~xS-acSs5TY<XomjPF?z@f#HULol}3dRqPGk`50%b z`Vn#2GueC{TjTWpmE}#H?^bN{=q#Ro*c9CuOORU7mG7eox#{lypS)c!=cIkwwew)d zv%w_YzAbTga-$f?Sgh|q+qqlbADSUI;wG9rZ(gaYx-{)+(aoib{rT&@T{0sK#O6yD z8A*G7-&yNij~Cl@7sEpm4^<PKUAa5rkhHVthXCD{lZuE4ySOsDgyLdP56@+fzB*e* z8^i>lwsffXFuUX*`}jLQg-9nCBPP*xA0L{fus&vd)PB6qSA9$Qr?)3)A<M6fnNqdO z;F$Gi|1$V`pNo38q8BO*TonEHIb}neq@26bkRHi3*$<MBHLqB1i0d<EX>~dAbs4yC zabMU!v2oe&tM0FLmoGT7ZHaxg$e`lp71iwJ99d^m)U)6RcHiN>E#(x<*!ITwoQ>&+ z<dTQ1Z4b*n>2cfeFLy@C{ygHj#IE05#AWuXvGm#HF*a@H`;Gf=*1mSdY&a%VdWa#0 z*UFR17B_u+!7rUn*Og};g_$^*zECqz*7(&zZ0V`E;&)Rv{x5?+%zkLEQ^_aeuz31- z$kn!KC3e4?TJ$AZoSbyc?2}sm0<Xxef%iL-$AVAN)^{J1{bV;F6~5<fC-+&dxG$~z zA}wy%dp9DTk6yYU`4!9zOrrWgt7m}jB8`Ys#<ue<Ym20qI&KJ=dHiq!^^m9eK<$n@ zCpIL#$~lNI1iz__FrU4;km(tA;zHqpcnJT9A-~PXG+w{U!a#32TPuToBlmmx-uZkZ zq8w4*@S20<p32^`K7hZx-<38Cl>`2g_SWCYwbj@5wQbs6-Z-OjXkLeis=JTZ!by3y zAdi+Z89q9E*6e#FMC!tX#?4FnFKpSeUAoJ+_F+5K=%(Vn+0KtYm|=@E(#~$zyLFe< zVLT#pfYlC({z3Jx)6F}Je!t?d?D1iv2aD)7PtNt&q}^Dc4ue3-4&1OBMCkGsx%sOf zui_fXUQ}imLrHvG<GZXy?exJkFQGNnwl;&t!Z9DA*Npm*`&SiHmytq#IRJ(@STDnU zwkOqXMi-Z+H4wRg9bBYCv6bW%n-vY9-C8nhywyPSBv~@^eL&Y}#2~P<nF29j#U8N4 zR~r244Yb>MC&jX~z4#HO&dp>N_7QRMY^!R#NSqUd>qKU9PIg_4xYcXT86nM)-4XOT zW(sQsCD58{Br(|V=KrZf1SnDrD-@W8c`*hD2l(J)`BL$6ivRZJcWwaD!~jtzMn$P* zc~Irn9dcT349G*tMgooZd_1yIvJCIY9`P1l24o((e51KKJrjRI!{`>Z8{AYksAnM` z^P5i#-=CGv(P(HVe<_9q!HkHiT_%_#8+L<6?xKqN!elLhV}5Jatg%qkM|QBA6NSew zOV%si$ziMpnHE>WeRiT<tIS$dPKoiaUPE-^8O=X-b68II2MoD7>)yu0w7C#)lUJ|c z!p28{VDCGbYc|Qqfx@P%B|*|zadr_)V@!Vq*3`D?Zzdj=#fFZBvg*;=^h@D^hXFT? z4O=eiKemfQGIm9KxfWP2p}&vEpYWi6$J49>;j@imKf+-<NLjkL{$#`Sk56ivha>U{ z2Y?0wY&G|bD|zOEH!yJTdCZGjo%6n~`?kovt9SdjTV>W^k~?ww9|I_$F=XN5w7=WG zz4Ne`b>+-=EsWu4^^gWdwmW8gQ6HqaXxNu*Dmr~OvRjRksit3hy;}C<_-MI#fUsrk zrHfu==D`a1Nf{}Zo_c%Wz><zh{XwtnaJ_t{>g0^VTn+XzmN9pJXluy%zVO_XH<Pr= zKgd&&HC5kH6;uu1%8=-~Y2Y@z`}i<7yi=pI8W!Qf@6PrQKb0A6+dQp6Q=zZeX-Sk( zkl5>$E=}n}y@N5GE1syn>3sW^%wBfRTMQ!VcqL523ncwVhL-m4|9LQ8<NLMRlhLqn zIC47Oxc?y5l_6Q#o&%HE2*;=UB)j~~o`%AiHwz|DJeOJ~P=$px7pz>2a5Fx%fcrel zcFt&#)*i$yOWU+$M5ldl&L~qln9HuO%4}{K5Bf1C^N?_h+Boyhy*2wKI+wKJ8fUY2 z5*p=pI7mSyqPMN-e=3{D-~@c(((GyGau{<w(7}=(*;@_`{gJhIb}~;VQrCBJ!Itfs zk0kB&4@76!c4XrP`~yf_K!Essy*Q(wvCdWA7oV~=|GmY|edUrzYIO$tW7;HLCj$6k z=z8LO+eFtvUa7d7JVv`FP>Of8QX)vTL;p(S2!=m1V>(0DlDKe@h>GAp?MIoli-Akh z9jdi*X%Iv%{;~#s_{iv}_mdc##jJPy_Q)3-8!1eiV(};6Fc~p1ukD6F#WF+IawKKj zl>v+)DD4n7qcL|#gc3hlsAy3+Cc$UyqM0_xG2^`E>vV&~JaFnT=ilR(V_=d96NYY+ zz^bO@#sH;Vm7q+KK7%FTYdqrRW8>G>^Yt9#4HEqHyJX2`8#07#9KTN}Y8`{taxQ?^ z&7hi8W1ea&MPQM<{Li=Qvj*aeF@F(5Wk>+QQ+Q4?29gCC$F7vs+#QYJ=0TOReQkZF zy!-C#sVBFP7IW#!n4`^rB#x7d#(wEwI;pIwc<7?C+alcmiTCtnTW;?9JYCz`q#@3j zg0FDE-)C#TpR2gwu_>2ERoqh6JcQT4+rV65{T=_3;QI@0b{06d^J+ssG8+6&KDncq z>QZ{L<3Q~j!L<hd9)ZKD<L6NwP4wwt9dgHnTs@_*k4Y_C_O*$3+33i2YFSmm>z#iY z9O(VrW245^MP9GfA7)vfG&h`k+iGXgtsj#P=3E)d(+x1VQOiFlGzy<;^nJLi=~MzI zCQ$^>?{C{12c~x_;MHv&yS~T>ut>*Bnz2`FLtohPAt#@Hk93^yV_b(u*#5*vx6Q6s z9PoKHKxdYXU`AN6h(K6X!K41&+1osGzWLm;sxUBAx?8UlzT&_1U;X31M()pbUE9i$ zY1%mA25u4PeLef^^9<Et`;3r!2Lh~7U8qj|f5Uz6YtkJ>ysJUWCjsAtFKhJjDY6R< z)%!7a>3ZShS!ilE`>4~=;nU7DqJq1gsGMh@n{4v7$u712U{Xo=<qUt1T_^QklWzAE zn`>RQFfvUzu9wYjEsWAnyPI3{>e9lRM+#YTqvCCkWc}SYzxrnTNo9(Y+0{qdE1Jcv zTi%@+w14KQ=ZZS%kKunAJjl=OQc&Sp@;&cWSJ);Ve(CBK)5N~%UV0L*JFA=SYo)Qp z#Jv?h_PFPBzV_gS6Q?Y17j(DJAv!85Otz2W^_lIDXPJepi0?V!^O}>X+TS)FskOd+ ziCtl#m(%xKy8qm&GJfo-kU-Ha0!M4h?!0*_<6h1~UD?|^WnqmT|L%_|>TKCOO}(1} zBur0YwjSg}_r;lmjSK7~PmT6VD|%;29fxmdTkBPM($iVD>=$cqJoaMTb&X^7v`_!` zpKQZFG3isqIi2lV@W4_#?3nP)@s=}TF;Yn%bn*4tKMN3t<>!pm3rChb`KA9Za@X94 za9%9@HJUPZE24D%)6*G<muj(?DCrE~1f-?&$X({*I%|-gMnw0xx@^mAxY?!Mu(2ld zc70qE{0B{0o<6+fZZcTRfS+k#b*%E2Un_#2E$Ra#%wU>!u>0!Tr->IL8lB8^;>+9B zsju|ACEad$5xdN&Nb<%ryXd(KY9EIo<^aN%J@z>0<+YTCEJdTR`8wzQf3EqhG5$Y5 zH3`!PMJ(Nkx39Anqq%`o_ngsQTjj_|hSKMa>G5t-!U>AeSR~>3lHzbK=J7HyYR-(L zauTy*h$k(~0ah_gdO4j`g;_G|y(VGUYC?50qkF@^W?<IhW&?GimI!B{<8G^N35Q}P zmkH-74vU^_gD`jb@;_}5#BzPUN8DYs9Y`}hPT1NE8^|d?Oh!RXZZtNXqoI$Iv$V=# z(PShrbM2uRPW*1Ay+D+f?;}o8urlti3oNG$nj@YqYnUJa$Kc$_fmBQx>Bx)LtO<)} z;)LRGk2I#87ywZ|8C3-WV&E`XQO=L%yzOf7M~kuN48<^Hr;0RDvgA&AeKX-uu~ig8 zsX+3MLIZe~4uVo~u4VfR^gPxso^r~^O>TGB6c(-E_+eB=BI0W1;#rkMM@R&B$TZ&V z!#t2CDX_mF9F|}{bwMKQMzoOq&P|32^{3OWMcP$eF+2G|tLNvB4k?T}%++}ukqy&* z4JAh<V<4nlU36no(MNUT&2u>$wK-2XH_B`WKY8pt@6_gY!aj_K>jNYmi>m8fPxU0` zG{PqEaSS&eKJjjVf!y%hjK*!A|Kh9dC~kC4uuH$Nqeu44-IIfKb=#^TmnCr1_!4}x z)3TrcGMKbLa^T_W(7`#xrba1rLAgu}?lb)C3yK)PQ<(+uS?kk*1Lqgy<SIuv^(Xnu zXh=`{Y^X@n+;_HqqH5>ncanx&$l7kQ@h^j%SaX&DQjrfXmR}<w4`{k?ozZp4v_jv- z?P-^)t}KJ>5@z{eOH7Bpt6*)XQB;RcW)~d_w!{#@cG#~fH|Mc@>~t@6WcMA_mC~n+ zez|H{lz9H3_caOZU_oELZ(;aIcZ2DQ)8^s2m<N8|ceiSu%B)v83LaZ#wAs#6ef!)0 z#MTvbT=m25PyI`_6q67%*EPiS5Ec<qRYLK&`cxOJW4{~qIwE_D-mu`G@qeg4UA7{o zwDQBQwgc+R%2(x${%f3u@@5%4KF=JeS+iicY5$CF?nstzb@Ari+mV#zu;BN2r0qO$ z$91$Zp4|&l?OX1K1qbT&PLK&%i<+XoE;&Esq<^Cqi4bB?pBb|3WGsrlt%97Vy>dLy zXyUmg&@(2{v#wFTA_J*eka}x{>|oXi5!RJDp>V*Dp;q%569sHmS+8cKiiv|S`@5~E zf7<K#NE|-8kQtJ$UzZ?F_H>OOMSaDs+eD8%Q;kg7Y*O*LG+Gyo${s@rEd+F`w1vqk zHmR8bUMVbY0=fiep^d#M{)CekHeejg2l#KK3FL1nSVmYHri`mdi_zzmzXM9k&YhJc z_9N_G&><0-!5oknOaX;oASgKx9Qb$JIF?<aNOutG9&vPy=wRTfT+aT~;8?nFC54rX z<i`qcj6LQmPEbg?>!LaS`$R`3#|0cUW~JVf+4%n$JRre>L<4lSi?Ip3J9;r`Jk}4T zF5%JAc=R+CeBNa<`9iaddxOHU0Lp@C)L~_Xcz{ll3Rfsc>s>Hu7Q*CnRA26h0K^w5 ze9WlL0FZLPAC+>NYFTF$71IH$F(3SLvGzfJ!#7YTu;c?Ft^UpPi?fywK7V)iG$0}U zMrLX|s&AH$^Z=K0vaT3CJ@)RrSN+d9g*J+H&9!+FuFrpdeo<q&Ik)-`wX?L_vKyT} z6`nMK!u8F_iA7JX*auarrI#3L@z{3PjVNXkt2b)y{{h#v3;JLlFaCq-jGduA`)+s! zL2;oha<11;XiBI%_g3Fm_J;Qsg!P;#d;6*EZRfVT1*3|OIy|k9@T9gKfWF56dF1In z>Ype1?(?mMXJUp~bwhs{44*4lceU~h9W?F$Q{=x18B2B)C1raRHGh6G`i0LUkN^7Q zo~ho-7#fVuMB5u%{HC(GB=7muy7cZc|D)R~86}jC=Ob^@EALeoY}ZI~JJ)~zTp<mT z66@|^f2PJOJnNT2<A4jN7Tx$#o<5*avWGC<mi?{p4-3uUl6Q|W$}OxJkhHe7)V`#% zC=Ztm^~;p}#4FuxQNw9=uBq2D-Z?CtR2C{5yhH{Am%wc2dyNmKgg^MhXZp6sud0=2 z6#BxxAgAHM;(H;{z2CK1H^KQ<^v0|KpO=Mh{_c4knY~M^($t(KPd_k4(mK?er?m>V z?DvrUFfUE5toe<(?XJOJs-4a}*TkJ0r@J(F3vVH4-H%`F&+MPKqHBg~@!T2WpUC@W z{~GT4G}{jPcwx^tDxxAj(DXdt4*$D%v!BW)6+fMrZC$T+{*zPD!$=GdGpM0D-?~w; z{muA5phDxC>h%7~8<Sh|KkFjHfj%c`_;%aR9a(DH5zk6TmkqP4MADV)zK2^hT<LO% z&t>}Ia%LI>G}>H-!t^XnNlSn(ReR;Z`p41ITBpJM(HIrdNch@EMagGseEIz+GpPHy zs8u3*2Cm>jw}L&>0KZoXdhFgun#Fnqs>!DDN77RqbW?JXZQ-qLC3^I~<Gq9jdR(qR z2Q(i}g?Zi^ti49yJRj0*&7UBCbot_nU$uNcVz(Bw5bb=}D)J!s)2FYw^GVRY&LP4> zi8#EWN{I)wki8fmld7{Ydwx-NC&h7r#+O2d-B@#XlOzdSz`#m60W$*=CP0Fjth}7* zL`0ObH+b^L#x~LB8CiFc`K(%LFSA)<H7cG{k$^mm48USs#-ACX#%deaOr2e&@oAU+ zo<Sz{#2EbqzhZZ$IR__z6~O|QJ8FYa_8@gkkcOb>KQU#BlVxqHEmmS`5Cg)f<TL%z zYLH1e33D>+N@IEhs{pu1y;PzcEV1G+UGKF=;KrGRL-ASyANh)T0wzo=f2p&|8VKa@ z5`JaHlwe1pu&j0o=fFyKUyj}|nV@TvBc&3j!MvH_g}VKG{<*Rj8S;hFfmUbf@ve0j ze9fx&*uT@Z+2G!m!iq2IbG5+G)P$V&=^=fxYXJ{SS9Vg9FR0mGdZr2^O3rEh=`c{g z$S;d5Hlvg4`TbaZ6asOM(|^t~7~ZRq_3mJe9%_9wwE_xa$LuFULF`-m?dD~RJY$<G zm7%6E&3}tD>i;3V|1SfVq0NUw$MP#G$6H-)cU2L<e8(j_B(o@lq0A;a9osZJgoThR zyDp?u6*i?Oc)U~eZpa^fs_`?_vI|+m3vz7u+t&hK*>-j~=TFI2o`r@BrC<+&28?e) zZnFumgH*op&ujjH!th4m^i(5l85@q=iVO<(@At9X|88mCjD4k1U}(#rYGB)~)dgJ% z+G&?R>{NAS6z!N~=%uW&K_Ux!fP!|gO#i^gLifRNQjTtkJ}Gse@5M+ZEgsI+^iAD! z2$#0GaAEHB-P7t-&M>|5Em&SB9zcHCV@}=32WWNioxLZv+V78I+0*rAK_S2G+@W{K z=JiNbE{AM!^@s4hgi|Rqq<Ql!wXEL>gA~LqjZT|C-_FerKEUz7=sn?SfQ@XzH6zqf z3@9G23D{9u7+Tn;Y-2wbwYn};)ItLi-hjvD9KXmpuAJB)YpYL*D<e+Wmdv9pmXGQ{ zeada*J-gg6x(Zr%NLb8OG701RNc7*O;5%0<C<a1b!-Q+N#@G=_tz4*@ilteVmV$UP ziq95NhM)&FA~{upJCEl;cf}saKYY~8;M?`0oAyl7hjEW?0jEf1F+R)iz*TasEUe)8 z6NS+r>!Ia{94#P;oTW$WAav+gWOLEW_!rM`1lKA-2Tau%?=LqdX;c6-<5{d&R3tf~ zGts5+r-uDtmU!__(Oym&&!8C`+cX}*h)}qXXI<A|g((%_W#ck{C^K&5(=HU#5EL;5 zPeA2T?67dG!kW<@V<>>7ffjdgkqPE1Hf9~8B>K+bX^yc14>O3lt&TQFJzs<?l8%bR zn9IJ5<HdSp3l~wOz~Q~ZFQZd%0gGi6EW9WLiy5^IG~_!hY^+(LO+iyI;<>pNr@C$i zId4NqGU{v7#I?HvQghp30$h>r^Ib~kONT9EA)~|CZc5$o)8TCI=Fkm&Un&X&HkHKj zUzY5%xZmSeT>mG7OP=t=19TxB8q?~zb`BYy3gjJFFYyT;hM0JrYaH|F%94|wI}f`K zc@g*nEtjOt9i3T!ygYqY<<`r&s>QulI2RxpF`MnKT@m-}EA1uRj-2_ao3n8ouJpP9 z&FntKr@6jitI;*v%$SHjj=aBH{zPNM)Wz<0TeI=rLeujB!{42z@M^7#YIXTjZ=<s~ z-<gr~dy2wZZw$AoHb))ugY{nqj#cSV@K=N5N*{nqomv;4R?;`-PY7p!J7qUNt=QB= znN=o%e(~6&$bLq(wazI*+P9<Fjyg|1>xY{?eeW->$6CpM<o30wjd_>L;(mk>$w`Cr z!d_YNhtn?;|1ywlbGzNr@Eetw%V2BK^%t6n6`G}vLqPm-eS)g3QLi7CI8}yE{iEzr z*jH~bjX9^VmJJPf8Gj$XT5qjsm(9Oj`Jo#94flq$_iOEi%B{=3*G}rcC41dF?77_X z#b?Z1SR1?Q-u)oQT5c&saHk`E9-aF9{lNvfsCk?%yBCTrB2Ko>m}vXO`ihu857B4$ zs@)GZ{^qo-F6NEm(>`*<S-d9?ufy_!bhb!j*NN)jh??*BHtQ#Bjqgd>lf7-$qPt7g z1dSgnL_c2XlDOv*BCoV;GhK-)>RUN!q#8V9@~z&vc8+zMOi?_J>tx|NR&JRLVcB4w zmDvIIWFmZ|<VJz%ZS-eVH5?f|er7z(27^H%BgI>$jm*n)dmnuZF3Gi&AQ>#73}_Pp znI#MyFQ>d$5k~dw+#DrS?|o#K@2O0pB%VdDJ?dkHP4ddO>B$f1^3Nj7r>?F`-6J8| zd1ecQ&s$E;LUW4_or%gj*B_@TF%e9Dr^F9mM)sR6sq{dh4x{OIllmfknGcFPaLv+h zZ0PYh$p%agG*6tw@scXbbB7VZsY(=wn>55Uo=i?hbV8AdWV1l4;9I?_@s$X&G$vbA z?_wMvi`w%>3<C*l{Rg0|E+*XLMm*omjj8l8nTm_ujS2$ayc!cHM?~vL|6f!@eI{v} zWvf;cIwfJ&;SyJR6bia<{hd4N%VS{wfUhj|0h1UTh8%*_c8Oq#xYFZi$H2$5M6uP9 zVV`UY_5VB7F9c0v=Zx`R%K-+xq=|J!w#N*=no#s*rt)MOW>%8c<}>??9Wk@Qa<X`3 z>4d~op$_`T)czK|?|gk;h5MN|>f(GuQG!IyZRHC8@NzBzp^)62rFz@$<KaPJAu}TX ztuq@wx}f%e=VyZPkfNZa)ax|fyB<Y`KgU#s_Ct&;G$8}i()y2cArC)dma6P7yOVR& z{*}mT&!n%n<es@-_|!L3po!FDBiCoya4wx_P?X=J&KkvbqgWYItEOaevE2wI?1|nJ z*C>XL-Ls9ZPq)8&B{Yqk&``r0WON*;7a@>81>XPWUT$o0f$`(D-!<Aav~Rv}R$p;J z+o#7`hF<hsh}k>NkqYxN?1tm}duPs2aw2o{&MQ52!tCRT$IP8^r-c1hJX})gls~Dv z=|;eV%IlBqRAJ9%sIHR|lBw}yC34fFt=f?jtC#AGI*s>QXLZlDE5*`6Ocw76rdegg zmg}804yNqhA#Sa_Wjj`=g1hEDn{k=ntO;i~pGbY&@lTI}rUujd=a5g#T9)u4=|;x` z_sR{IG#%G#rJO<IvB?R){xsm*{OYg2NWXYFH<r%MTJSDPU9=AW*<3vP%=3C1<tIg4 zLu_kzrtYDU3p&TX`FUzsT$v?NgM&>zTXqJ#aH|ZiHO_jGlx$IpiREI!=NisltK1#G zO!4nIAA*U$*SWw%`OEB&xOKO8wf)o?`sYAs=IyRe&qd^jWcbc%%csv|L$h6?DwH+F z^<j8Di5WK9`Z@n?-`UeSl34-gk%S89s>5$9tesnY_mv&~Uqzvbhtd<o;nUYHpSh|= z+P&>Z88c1Q;`(e-?OuXBUSpP?MnAygO@Mh(Dr~R0t*z6e6xMPoOW~RUQYYNB5>b~S z{EGC`JEn}rY@J75g4XHI|7g*!OeJjg%%*8jCm~9c3oMkMCAbzSvsxGZWnho)2<|5K zcJ#%2q$hY0Cs_dbIXHidGi=CzxnVU{9^wTZ%ib#f-X?ctP72TqnjL|=#f+E-8jMiX z&F1NH)A=vNSO=4?`F92w$21%PNk%D+twFv4-Mf|W%f-ug07{rX@2;Vsr)Z#pa4<=G z;TJ$3A(YKxBlE`f^=W?@yuZfvmb_0#oqk)?An-q$RWwOM*oXi`Top5^FkJRnX$|S| zhQG*I4#MT!My6l18k14A$nEA11X3j7ba-og@#H%yE$wQ___Is`J8<FR%eT!cjCE)3 zGeH{Hr}2iACY-zj?<wu~jBDzuJDqgxv9<PkQu(jgEs7a&J=pW7KQxbNjd^wFkJoQJ z^hgHz>eP23$Zp?IkPu>@upl(>5tWT-{52t69p8q#hW=67jB_v|iWW&<TXV;l{;buV zC&!zbIJ}f)Ie1$-{CMz|Ti}=nxjvJwo!(ePD>@$~_h3nP?f2SoA9jYEO!_Le$P8tj z7~T!_9^HPlwxx3T^mrjcv{AfhyHs&u<GTlVn2D0^3K2H?QEA7HQC-IS^v10Zn+~L3 z)X3hRxJjmLw21J1a&^}Ap9f99Is~^zGCZH6wHse+C;!ZA(k>^l<U|Ii{=1yTouLPs zI`LJPv@iHKw=qN`&50vbj~L+H(kzJcQsIShGd&2}7lg&$ri-390}gq`BCjRj7m<DU z@uUicRMran8K9{;wtwj6W;*AsxtMr}%lP}SgA1+%cG@UwANt1$(yndSKvVZj<lSQJ z8x5AUem`Y(G|%uhMI+7UV)$JNj=!nK@y;Dt`hqPu(QrzEA9H8~`gi{>QyrubT;6WH zx_f5NnyKSO%ajLs6jR7;vv@Wet*n5qqs>+O)A$vI@sq!#F0Fa1Ic0@Z+=If(u6Yj5 zK(hj#9FwL*3GDpZ8r&V2&JX+53Uxa>;hF7L5U(q|*?0r_N)r|sx4bUjGxYh|PhVpl z0%w;*j5#yhgI|!9)vo`WG6sKk4CHf<5&L7cDp9P&$se=EDzWv$lsOXrEAL52F-6_U zkER%1Ga$|6zV$}+ar~Vdw3{vwHU~%7&Fn=n7Hs&-K_wN1m6a7IouYO%gvVn*E|nNq z&K>((PUAXtM2R$2R=C^?W-G+U>{*Kx)_cz2V}TLYn!%Vm*@6+l?nQ(K<nDT1zX^Q^ zq=eph!|S4PzzjJAsBjJ7X});|<x$WY*Kdv;LwP!3oW5c1N_PN2Gdc2wjAQ8#45m<@ zWc!<^I5Ib|OmeF<`xf*?<aiSR{Km9`n87BufsnV?fAfpnDiwZ3$ln9I_`#nHF1p*h z(&)Jx|3S-21N(y?L&{{3I{p%mk=TV1F@lVs)01oZaneJGM5rK9FoZXx-uMkPo|}1H zw)ln{)AF7xZ=BkG&Et%B%f)V-(RwNhe(qm7^s#@zjIN&ADPdntr8=f@O$_ic6yXI~ zQDHL>No8*C3@>V{`f}sWD2UXSs-3VQiLbeQdbiuz%ax%tc7hd-$hEJ#G-qGrl*o$d z7X6=xnEHoW)O`Dw!DG)~yX?qooiFxzpV2RcKWN_SKbsa7TNs-S>^wu;x0`PwuIx0+ z$@ZIz+%mSuq1BRciz{cRt9QGuC4W`i#fc$hilb$Akz02#r2V(3vsx1SrtaF#PO8nn zzc9(&b*659qr&n5%?y3Sfwq`VNmP$^Qb&wuZq!qSh*Nm(v1vHZ^fkG3gi1h$pFX)N zX)RX$`1@j%J<zk~N#yIgiJ);$Ck}sg&92N|_O|Q=m+G#6Wo$v;CUR~Xe%z3>zmCi} ze?9>yqrZiZ#@K#5zL8dc-?1pKsA!8MiN^swTYoyw*ff0Ena+iWm!&6)xMLntPsP<Y zB4)#~>GA%g$VlMir-Rl`)V{g1`^B!p@;Y_<FUA*yU7&ePU$jM-YtjDpo)c{cnsU3? z<B1Fpf(o6tUck<4-pEr?U+KH$Gdg_PQ>!NRQs+7itSVieeN%huJKKMaxf6=AU<OU| zd7^UJ%mgbmbxV)I_8H1Qm{it{C~e`0C3i#7IhHTR-aCk1@m$L(;PI9y8N$U4=i*1u zWVmo$8VH~fttn!rk}XwQ|4)DnrJ3za_gk06t)j3_f$oZFXEuoQ-7%K?`a;}g>hx}1 ziGs`xf?qhaf{V?&S~`V9h;xM-kmLw*>tJ8JsIWCq!kZLz`wiuleFQ%;GbSZV{I$ej z2p5+HQyOSrjJ4>o!?5H+fzFkhVpKMC5kCV-hk1HNx7`gmnUX<kb)rkG9V&FXczysG zR>go3R%$20DaOFm6xf7^dl*b37f4LP4unG)*DfJT;oZeNO)DLk+$2zi$scuAQX2WW zFh7&-C^pr0mD?4L_~1bmaT8NFtV2baAp*4iceRgq4~vX=zh@M}m5Ku#iifaL`w!ly zCZCC(jg?b(9FWXiOg5R-92=FZd|h(gX|S;0%)s`v|3wB_B3)>JuYVo}?O?uoQOaS7 zL%+uh^~H+ZW6yeLuR4*3B@eWaj(Y>LPhYVaZ?35rKZ7!eb#gkPJBx{w(4>fFV?*SB zr$kJ8YOG4s%(&2Psr^$Rb#9WuqMRl7A{VrsQ#AZ0H~U(0&2&<=rWmsZ9#iZrW1ABR z#>suQt{z2$?I%pN+Y2>9%(O{gvttKqsjDK5POQA~GoE4N`f;M)h(vwn=hl(UWkL-y zr`2{Gl1G73R@<6nq=cG`5O-lRSvXmYHjfi(o)zWGIoSva8=)lw^CGHj9Z!u_g+a^m zjWI%j{6m72?#@wJv~vEPR64sd8;)RW!K*j?7Mip0SL?7!S;5JUuljt#0aluz^=w=- z#tJr!8~?wr+^s{Eo^pncRr}&sttF)RJ>qi>gjirgij6^7aBhFISyZ$XrfNxe?A@so z#En5%U6_M|G`K{W>=^%=%|YkpxQ@F^P1Xgi<&H|W81=Dpvv`xML0btPW~v2%Lc>S% zX{9=7HBsmi!-BO%t1Jx1B39&yd8|%X0oPt&W-Qhn|Miqf&@JprJe})O4%0Al5v00| zzCP28?$yd_CNT~%u-r_le43aYkGQ~a@x4G0ZTNC}T)P`!cC<7OZIgRgf*H2{y4+Mn zo?BI}L2Nlszd4w;?=OQptX+SwM64f{dlCLu<7BbQ&1v~YY}V>k(WJHnb{x-JVf8?f z=@#_a6uG3m<u8NFnM%WdTyk?{k^woUZ8BHNN<+gbYg-MXgbMw=wYvNhabIGj31)>a z(Dd)(W$?YvrwS*)OJhUkdhqo&%-l0_KP6k(uuQ5(+3gqzxd6HTb)SBvyK48Uyt#01 z!4FZp!S#H%ab0Zj2BU|v@v_g0E~u9pzX4xX(miY>2;zn8pn{C&P2c7EO!q%q^PBgz zz_Hq{>%(3N12e~JyubR(z&LVlTj8q#X<B)q+PI_0Y`G*;?SKASpWP)GIlA0#^K99L zE0+~-3zq24qF)Lh{(k-OKUEW5LrW_Is4ec`R<cVM<hkwa01-{nNI%Nx+PsBJ$Gv-i z7i{r?>X~&quAH?TBAME*io7KfnnB2DmU@{-Pmay~oqrkh*KGgk#-kPrC)>0LQw+1- zIg7snFl}LP5W2h08f+m+131sgc)U?stRBx)Wz$e$pOq?19El01aG+)qcOuhaOCvI) z5q$VwWqjBkUBDg2#VK)3S@;DG<u@*z)=<@{Z?}z-6|ODPZ%G+7%XnT>HdA%u<wlb3 zUsKew-Vi&K;^I8wniLN5q03*+t{0tv(oQ+_uXIEZ%O^2|{uTXMSXGRp@Y3N8t>1C` zK|>X;3Batl-IbG(cw#b;1SCk#V=Du6andN~CnCs9m^DDW;ixl2P{hHg+wX?GO6$o{ zrW$Wtz?dqQK><(epS3*ZPR2+(zPg2Z=?O4~k*>#sp40^lRA8EnGWDnFp&4WmOu@B0 zpnQ}v2HzTC9@GK!*<p{$U<Dhsuw9qW!`fuo0X^bS*pXx4vfNB6asNQSTWd}{QxBtN zUXvza41SHu%Ojx|WiCJ9JW=>~9pFjhnz7MRnic>*>`F&DB@6yLr?yeD`#sq|aS<6^ zt?hz@;Md+l4=&__gcX?{wo-FF0@-(&@%iZIm%l87o@x_QQ?6Su`6G~m+)U+(tPTdc z$+`to?3awth1Uvh1W^+rb%bgFV4}t(EcPDO!g@V+YHDZwE=&l#=SpL<21))JH%@$y zORdH>rv^eyg@;-xCQmvI{^<>ODTF=cvilR%f_tOuPV1NbPCSU^;5D~Dvyqrf25q7a zpx*j%T`tWW*^pg{QC~pVdWDch0d~1e;D_ITGp64vEn@7Wtz0WFD#(2jYmb_MA28~p z7ETdxO|EzMyHnrZwKb4R;75)+)z>N3Q`|VL#zh^BfXQMO#k%nn_H#qcuL(oD)Wt2p zWkLpNc7thINra8d*eOKOhXv!qBJey-aGA~C-=xRHtCt|W=0BR^MDtv<(uN!wF<g0O z8-r&)Q?3~*7r4VvQ4GJa(V|PvT;odGEzYr4uetHAc-!Xun0r-SBW}c*iiRQwK4@2Z zDzRQP3ttj4R4)8Yc{XO4+aj2nLYX+%u0$O@v&*TT@m+VNSX%GYn?#gwaq!&pkay!? zw-Czju~t+a`ZX=0qHpAEi|I`;lS^u`m%t%S1=dELF@{V%5;Y7{!OX2#jCf@Fnyia0 zax0efS&e4%0S^jtuqIH9c$$ukodj^kZTnLKudyol4LO(Dv1YOP^QD=tw*t~4-ZD=; zmZEl<9&LWq%7Alt8NqK}d(wQTtTo#gG3B#k$0i|m&no9+24!7va-)cdP0KW(|DM?c zsUS6B4^z8FH^+n-(|uR1WO476qMOyOj_C^?+%UT4RMjCQ%DXLpkvyE}*}q#B+cfYZ zPFU0qH-hzServ-MI3F`2&-ahHad&6kFF*a5JALaRZ;$|U+HimGmt%{@3bY=5g6Z%f zonu`1-_KBJ1vxZ2(1?Y!{dkfCny(`UdiToTDoshxa}p&4KyP4?6ND)?LBjhJK^q>+ z8}2pHBI3I8+wHS2gYh=8k~s-Z5g>%IW2E2n^}-h)u~>SPvX{O-|MVAwd;7b&FEiz4 z8@uX`cR4lOU%1fZFdivo4dwcp>BM~+9`_Sosv^}j-#jkDzywP)PTfF((txI6UC>&a z3?5Jo1w@=;WMs8EgCEha*Ja_P*dTzNwwWEWWSx?_xMVLI1-0@XOSQ{hUNF|LZbb!q zXtz^2^4v+k=7Pk!T_{3BUa|k1a1;#VR48JC^A34=>$-~??dZh0fm!c(!qS~$L<3zH zOUw{}gtU6-zr>+&hC@qUCsaGjtZJ8=plhb=#Nq@Qku@Hl=N&tXVDRw?_%P#j1@~wv z$}Kx2cQWOKRVm1l@fgi97F?zw{A<7+4^rDh#upUQNDd=J#!Q@sdgPcarx?K?)r8Dl z31FVM=WXg>p{K$UiU*wyYnM*Afy^i?4c%;Dv4exyE``?V`U#BT<nCC#z7dCtNaTz( z=VNTd&(ij_@0o#BjQ1p9HPD59&~wU!p3KAv3@TjP+DGd^NJ;rSC0mt|JSjqAU1GST zi07O&P8hFzB+Q^a4V2HzP1SB=k(DojDW&U9IUIu#JyzChW#2{}z^#jeK+;pz53fGd zVUd&@$k$$`iLM*zBI2juwg(aEpcr#O-hK@lGnSbE)GO|81h?)N<)7SQ>?5_{-)#Jp zxD!5>!X{m{cTyoFg7J1}ol1GWE&qup!<R-s<xE<Hq|FLQqpsVI*K#{V@_e1PwPjn_ z{-7&htG3GLZVb_FkG@2j_c{!Z(rb~>VQMSYc;lWMiZJw`mBB8?20Vnzs$?_6Z%o#{ zSS!Wza<C+VUCmRTxSyC#88tdK71px;mRvjsM@t11=~m1Uif5<HI_hRtxrGQ>j)h$+ zYx+<8YmzQB=V8kJVR0W*CZaMOZ>5g5N;w-p;_&5UF~xw>JBj1^WEusbZVGhA2E{oh z8Sw@Wt<s@G@Lb$k)<8FK2)T$NyJ0nnjKi^%#bW5lLL&>Yc=_01`Kpx$oMNJ~=Dhwj z>I>wf%S_PSjix-G)7;gpPD`P$5Hxb~sfI4qiDqijK(yJUYl5@UrxwoCI5{qFHvvv{ zD`$#=w~1OLo0U5(oPfe4t@QY%eRne5&S~8@3d_>gmV~Xp$pm?GrSWnvF;odw8ctcW z=CiEIMdiy4P2|FB+NJ(CI2v8ee5Vq|3N9!eTMa%LjF_^1FL!IIqR_3}ba#uFNFJ8J zYw(;i_MS9o9c#2)q)&WluO9wU`Kgutn*%?7u2Xi-g+(eC?5c<~s?r0VQ&n@fQa(m? z^l3J8Ha0}M70Hq;cE$WsJJqLoTi+XTBf74h>~TXyEpxsUlsy@X?^H1<4Di&U+xXaq z&mT@tSKS}?Zml&x^4<W*VRiYgm-5p458gt!dg(C^%f<g1zG+dS5H1FsP_-p$*>G0F zy~4MhS))Av=}r_#_Xbd3F!OTUsM`f3SiTf6Q<X+H;ttBv2t~x(;i&21Iu$<eB1Pg9 z&MqVd*K9~JREJptnyHcL^@;07jN_n}v4%1ftW+vN5mY(g=gt?O(;Ope!xtGQBw1RG zUWBGuIpltzE?bv3V}$q@D$b=*pcT=wrp&UTKH9hw>KGZIgIK7|qv`V56E3joh0Cn{ zF0~wDEWbi1Gas)*U|u}SnVFRV=65|Ky-Noa9%@f6O6((#kS-}yK?mv}#Uo!F6x|y~ zMVQ$n2;d?r8?Udi{^&u3-?j=bdQM<8liW#7>+5lL5>^+9+AG=r<8H=s^@>Gvf<8V@ zpDd{9rXsj1J`73eeEQ)L)>}H`b$m7{;W3?<1?<m{vvv`*2m;ZBG1<^1QOO(7L^_?L z_B+d|n${Px84q1Lr`q;rJ`{~9VXA_?w0vxA2Ps&5flZFF<$S3&Ek_uB)P*(-vm80q zxI%5QH1I)sI)1YLM?B5AbXwFreQ!)h3@|wm;1BZ)tomrPP;%YwmOYs=IgnkAP}F{y z!JC!PR^3i8<r~#<zYUl8panO24)vgq+bNNW=N|K@^qBT_EGO*SW$LJL_3Dv%YREhA zEQBcg9?kGlwY+Z@lorv4Qi>3n%~TMzKUElo2xjm$sk_cLR0S5%bOW)lG7!P~@TY}t z+<A~I!4y5+Fi%LqSZ$W9F7@k_IVd`>u`0~uW)d;4HJnuL$oFWiqr0AEo0!TnSTn{h zUz&B*#@0YlcVfD)gDBuAx26aI$lgb!s;;!zb4iSd52_S-PRYx?=q)(Hve<gS==4P) zoSbS~W)pX^iY#nwt!60d()wFIRoNN|wHp>6xMd_S-(L(2su=WN#Z75!6W8CO@dh_= zG0^t6Dwy1Kq=7V-%vyr2a*8zvyjt6!?||&J=13YJ%0mwYYHK`@U>EeTZel6D65L%h z&b%imqRq^vRWb8RGqRM1qXM_6ZLLzH_TwW&kpR_mYk~x9z#xo>9Rgj&_$g&{nwk#D zI(fO_N(*r(tB%({g2Y`jmoQHY=L5&Y=E&8yHqU`$9p{VV^4Q;a4HZ?JeM!WbiXJVj za@I{JUGNlX&|0Rk+#0<fPAYB`k3Kb-OHe;SMJOt@mCLm+yJyBIU>3NoESa{_{@|g% zQ4(6EetrCsp}mW&EsKlh?Jw+?SgDf>4yK$DB&>7jU@)ecVh_a>5IVS6n(-x+tdgyq zH-Oq3jjD3pfgqlM)}J*R%=ewL(Fhux54}>`ti}3ax!FIaC;Z+&U15DoutzjBNSA)- zeYn$FVRK6fNr>@t#&WZaD=}|g!`lsBS&+x+mV(7lz|(&7ekecZOhJ^TugsYd#U9~3 z|E{pPyv#%Ico`X#EOdIYm_lR?s16KeIrJ>LE_tZBz9x1~$T3}>Si*LJ)dda_{wF;L zo;$}-M&*?Dw-<(4gx0=XFb6W^Jxr+DN5-6-0|64EiMD^{TN3l1Ew$2wj}<i5Oq8M2 z{<!{Y&e?y}kH_V7q-gbOhWP5|4tcLWdvsRkT3sF^%KX??Vb;~c7DfLtqMq6`ay_>Q z0MXTIbTEI{9f`MvhuQ_6F_4st>{(V4tu!y+xaRICQHqvg07~E2z!*>4^Xu^^@Ka>{ z4gXVG_Xe-)EOG}IQk}$!Lto7{DqS#g1JGQq|B{>_9v`buoKFn(>Q!>P{6jP1hBu|k z=Ha<>l2QnNe`EW_qNn1|ybYEjuk95BQNYa#Gf(AdhdFf+ZHUT?W9`L}@$QO7=U#|K z)WXF1412x4nH$_a0PJy#fFSsvzu(*0dV`2!v|Q|kb|GJAV2=%e&(cPTL)PXbchFGT zd^A#c81sqWXGaTSCeRtbr6mi~=+Yq?mDHWO63rSyOPD(yolIyk>hZ?)qu@&N>zVI0 zR0RQFQT7RP>$4*a9~t!w_{oXc3`B|AM>1GSDxVKZjL?W?9AgzQOF9=uUxmm(DU@N4 zx#;dF2AW7Oas77W1FCIhVJik`FS}^T9647h<K{xxG*C0f0Y{8X6FBf|6f-WAg$iEV zy<&%t8r{qX0>$US%y_IO95cAS;BYZbE0L-8vOPW5?Y2tYI}-LNc0G7jk=wlk`UXn# z35(!d0<T+*R@y|<M^kzQ@GF8}t=G_afYEacjd0;Nfir_*?rtW&`4KHsg5>#{jpyWU z|Kn(mzf=+)?6h*!m+)6ag%dnwid*A4VYBY3u;D1(i{a_(8%9B}zeJj`*n7abVZym% z?&~vLxnbeLAqjDE*cwlf=c1@f*~=}Lp1Syj+wwo{;oU553Fib5T#%L)Mz@ctB7Et- zr~AS^lXEhS3e<SR0r57W;J>6T0+wDflX8`CS@OE3`%am{zmQqS^;_vDY%)(7rz^9D z($dxP=_u;>5mcCArttsoLhS=L;~wqM2<``}f0_8nLfxy0qMY|0^`Y8D+@czRzNe(% zi09VGzzrx9D~8r)0qqx#kb<~Sobd@QTIt-;xPIf|uVa}A@h)d-ugQTllH8}7i+MdY zN%pLH)=}Rsvp;CAP99}plMdW8R9NVC@73!hm~D**y>)nxOA5xI+Y0U$8u-+MeuE_* z2D_}%h?gw2{cwt?HC^{MyND()DoP96ex<?u2uW`RgHkyaD@m!ohD4i@YD0lzHs$0f zKEm+)V|Cfm)Su_RK7!|FCIIwTilCtK4~=auE5{T!ZY<;U(3Skbu^1X@ID9kV5tld# zg?{dn`cwtgqH9{DLVwT7UCj|!9U5V`qu-WGn%zhhlp{Pe#7epG@TC7x{<Gd`-`h{z zYhO>vr|6B}^`_<{rt)2sV1-AE5Yi15<1Udv<Je)t@yZMK^{&vBT_~0Yc5tcuWe{}S z<$7LYVXNrisP`d4@H@*{I>)GX<p9Y8d>$96_D)ypg;j;Zi3)q+ULsGRAZ)q^u>O#g z@jLMbXCLv*kSL(=6Vss+$VuzF8EpWQ(bGngY@Ze}(xGxj5ET0X&s=W|&=+=?cTInQ zs+(?S`Rh6kk-VzIR-7RqRNw=!5=mB}CmX3InTkBalM6Ki%NoOt?*CKhwuxg|R!T>G zK9hOs@y_CU`Kl&7e?_q)TtPkf9lxfd!=jeBYtU=T-ImTsx{?KDU@x)e(6CUvIEaVL zC((#$JFG_ki#(Po6x>uzc%mDCM7_Tb5baVu*4j<F^GM=Fkw$V)$~fNs$Z#ivgQwnw z0i6<LXOkm&XF@|^0<sk^r)!uFtgXGw2x>BsV3oEx=wgZEz|m3Y$yRRo=(rwP%WkXD zO9agnpGg-D2&c%rAhAU!WH0gIom@0?cvYFP6|5QCaoB_9&w%8~KZzfZcGahx)oc}) z(cGEl_}Q!Y-ih&(gLX2|lMQjwGLCDB<zz}0@eN-Hz`})q74EvnYaC1^b~L<a+}<f+ zC>;L=p%BN!_Y(I)y$j!UBd=tW!$N81+Dh7sifF5eV%gdPZ3FzWQ8QEKtZ2l4XG<}@ zKNT(j!qL){6iWP%w>U+CzRyL0gGFT=<1TbDBJDbq3hYkz%q>E<_IJ^(KgnkOtlNPZ z0!}m)QNM^Mtl_rfI|{!2<RIIv@dIQ{K3MMMmppQS%R*O9y8Fh2@SwGD<}27RbFC&> zygmYO!e~Xkl5DYzINB2DR+ku5LV%Q<?{@j-nKL*`K>?l2{{CAGMO>xTq(!9EI;z(x zudQ0%KAl#aFDn#-OkbQ<j^_D#xbx$eS#{46QnfK>ZQWKQT;9v8Z<`rQb=%BH=A6ui zbPaL84i?X3qUf-Ye|>*~RV~|ilZBx%%V;ZHA+7#&G^*p2ane*55hLza?6ByKI6j3q zhK|N}JVB<Q<_xBx5UN46c`z1e9acFwIJdw~AR7mmfL=%7njWk56Vz%&p2K@p?j#zW zA8vSkt5LF3nQ*Wq!pmZL`&`Sx5-!_x8b#{hGi7z42*TZF*Lp99mGe3)>r?B_vYX-X z-4Bb;(VzY<UQ#4qP27{LjBaMAjA=l5<JyI8(tv=aS;bxUWwCu#iT25)6&9QvBODH~ zt<hz=Um6=IGCp+&U3~vBdDtt`SI)O)3%B$b&~jEz*IIC;EPwfdA{+f`n1(<Nz6glH z;jeKUgdIr|sJ=b%Adj!<$m~5%eKS8zO&@(ZV2r-~R=Z+&nwNl2p6QJAsmcL>SR>!< z+bxsc1fbD-dITIVOn!p32_2Sf=;@`Qzd;{kPJa5jd(7?UUc&tt=RW00%t^ehY>j7k z+Z97p7|uO4_f@%hK^$iWK9mjjgAv@pcvibyJ<7YQ?vQoVhj`3*5?*Le3$eaF+gv#h z7NmX`N5bQE$*<E*kr;qIC-0k)t{)DR<LX(!*kuKU1ut7};=nxO#SsW+fGBF&+rqIK zkY)rv=Pr(^W4eNaHWW>Ef@ADG9B<c*6~t?HcVP&TIuydQWJ?K+<B+B>I}0|zECI(f zG#;~Z0O{&ElKy^ol)&-1JOm9>y=NMbhxkT=h)j9>W*fDodShL*s3T=!Vxhbwh5^x{ zTBRxM#W=!)O&KV1niE6pfXo#(X}b=YKOpdfhKwm60K#-s!$AQl0@-9HgM>~d=p|f% z0DJ#yRfCn<$6!qVkEJt#i?UqbKb3~I9MUXLg^VZ0aK&F}DmL=wNzXVgXWUT(sl<r1 z48(L4=Pm7I<cX01B=X3Zpt$3jYfdgX;5NA;Zm4Xs2r?`)!_2(?zYqOC=kqzIV=~P9 zyw7t#*L~gBecgu%FE#!fI)ibA3Mpq%j2M}Y_d6n!`C>3b_5YF%yg1IgDALcNIV)$4 z=UO-G`o7074k3vXK6)64#!otdADT{M^W6#CnC?s1NW6YZw5Nn*1)XKy9}0Y2h^9X+ zKom#P_|Uv*>(f@QalM&QlUkvky2I2-#BSB`>TP?NG0HJ#_V876a%RtNg20BG_-i&T zR&2F>;v2m!fy}Kn&^|M*j41-^VF#a|V#p{|DpaRLFhFHZ4VbU->WdUXSt&r8D5xAC z+kv0|Y~Y~w_TBz}Wye5!!Vu)a;j2{8)^!y%SZ21P(Dm*Y9XN!79vz9C9p8AkQH=L| zDnks<5Gt@on*u~Buk#_g0Roe_xLI&+<Zodoj+$4jM3}(uwk83z#YR?!`w`+rt8R}j zii18Tggx{TwOn5D#Xv}J0Hm?uT;7I_ucLJm*4qMLXtOFOPB=*-oNT>o04|&E{Mr3A zJ>sWOs6Z;y-S$%#@7`HzDD@5AJoQ#}y6wHF_O!odNm(hIJo@Q=K&FA5L>X><l%@8? zj%LJ|42<{-cm5WXY{CJQJu0SA!46>E6$^c|!3;2c=vM-7QsDcfZRPom2s$25eP^hI zpn@n_E}%S-nV=Y|3rupAbErJnr$%?{xQeL+-&saKm5|ZURy~2S_Z>S5-XVURe#5#B z!nT6-)Mkx7ozamIn^cKBM9XiRdZ(sDRKQXGG-FmDkm%y)+3^GV#1r{b^M3iC(5{SS z7~zIaWYQ5o#N69<sI!PZS;`UWSyAg=;N<k`hMa13hSc6JEw2DWV!+D!6K`?2m^5-u znP89X5X|%Q|D14U#48%~*G#2j+cQX4owRG>+2lly_a`is=g5aTuI=j2`l2b#{5>_# z&0U^2sYmyx^*N+Ey#{pqeN1({5|hQTn*LNq8wLLU&)hw#e@dzEOmq<r{i}DCf`dcM zd4IcXbEXp;2J|bqO0<2IK-xap+)h99zl#ZT=Z4q5Gc)4Uy;=lvq(pYFC~>@~fBT7_ zX{PruBRH$n=4q71Z58$kpGAyM*_X#G0%9N0e%9<j{vH?6S_*;N?imiYfyVGNgSHmo z1O^TTYF;6GVh8|c$W+=<mjk+>#?U?^u`%!9L~3eiM#BRcHTiYeXNKH~hGAe<*T0-j z^B^_^1<7b}W#*q9533!6Z;;~~r0mLR0oah0Z4xn+(yOx9yjF-{VYd^+50FsPFvWG2 zI!sxboEho2iSI;CPx8w!T-IdB)UN?p0t?Aos7Y|n>54^f$RFh-;gmWE5X%gPzJx-9 zdD@K5BA+w}ojz^!R5DQfT+Dlxq(5tvNzEL+<$ikA?JdOPwHe3bvW2G#<85OXx)<7x zOTz7>;(r#K-W@`1;%Wfcpf7iqftc970&1cjr-%dp6h76&LBbalC|^97GGS*>lSR;H z#5<hQ;A)8CTnI#J4i6N9Z(qAIgtD|u|M69av7yRzZd*Df@vi|zn=`mD+cgmME1M0} znfH-QP2JlL0PbjebbOxeRx_;HAtVC=qzQ7c3qr{t{$@VAC#`R|+EJbU@t88C{Jd^1 z2cewI5d_j_W<#T>WtT%{>sy3YlT*4TY6b1gus{MzuZ1WqeAt_1%+LXKdiU(2Im@Wt ztze<`BYSoHR%OiN#qdJTNuener#m0wEK$n&r<64+spBahiK8wsaSU}V0RpyfDci82 zU6WD;e%_m+Ii%=GLBlqdY8x3L@}_j}7rYk+Z`eD_<aK9QPQa#cmqd&mdX-X3*7*%9 zWUkTSKv>S0MvOu^Lc-2%1(d}7wC@DE^ZE|u`;7bub;4bYf|C|(L8-Ii3!M-QObX0Y zeOfb0(3gGEu29xCaSzkE7dmz>Wta><Dh#^u=Hbu3rr-EIuXp5A%3jNH)B*3+1;u&y zHTBMKAm8;C4M7_)w_}GSUke18`D@j2)4k1Fy@>T4ZqWU`W9w(V>*-jgQxOVj?9->= z!5Ov!k#HTa@>f-KBZCQYY48f+ILp0zbNLRW`yqX~>I8`<ZslFv>lnc&_<2OTvOgeT z@1$uTuVgLbvP3J%(XDSixXhd`b}$%{SRDnSjYMbZ)D&7-=7(7bl7vnUiP)wMw?*jm zRdl!^jub<ad0{hqMWRscprbSjapA?1O58SQpMROk_79zRTSkzL*XO1JSqBp3BB|uc zJGSkn$%KMSd1~&)iWijO$w@>tQm)AHrQF7opCT<V-Gh2OJhW5!FE#pmdHgNv&m2;+ zj<FwhW6}rL>Vy@;`=sE>^Lz*Hq&)NYH88uOo3?D573r7P)aTQ!Z=Doo8}W^{y(UjQ z`}qo%rg}$phO1`RGbF2GgU5m1wYa$d9yE7xX@FdIy`GZ&ENzs3WATP$$>bbLoEuZ~ z&xppGvkLH0;ux@v7hRwCd<B_xSlKxf!vEzh7j7sG+{VRIwkb^~zLalqWsb}2;hzaC zy5n9)AjmOKx2!5_dS?J93$D1SUl=V$IE->6&BpoymoZ#@l_^V*;xn)GZ0ZBj6@8Gu zCJB~Rl<2rBtJ==K&_81MqM_$XLzF9^3I^=y{yHnB9IE3<eu%9o!icO4R3|ELLfB6o zMx4;Ki-OJur$QPMpL};B`0bv_0J4hp{S&T!?ZUr(v)n_XRw~e$KaxpZum0Fvp~w?$ z8pI}bqWrr+*l;~Z)1Ah4V<(eS1^U1c0H*nwGEd`WLeNm`=tT*IVV_!p5dR8OOEh=Q zbPnT9fCu+0vxSR7u&{gOmDtI8&!y&xz+E|2h&lY9_&q!V0V?wC5SR4me_RA8KRa-K z6Rw(J6wrP4bks~}){g@BrrD08Y|b!HLN>YMAyECuP?mRv1{3|=PV+>L9e(2H#5h4} zLhkB+ia*)7T{<T8L7W(D-rAFPiDX{{pNU2X<yR7p4$ybzb>eqlRboUB2N*$gBNMm| zJ$#EEryYD}x^`n=^UQiG=)=*4=M$L(6zc@FiWXDrfQ(X+^5ft+nr3XraOt*y9gS0Z z_gKXza9D!PR7E#E{i<2ln>j^OlU{v=1_?(lnZ&g}Clt|VAc|VUSr1BBoPMK&V8Z-v zuqY1I)Tg+J0EzwE#{-NUN#ILniOkzh-=^AN#xlxrd4t(9e&hX*IlPNO?|p~&L0&(( z`*VGAq9e$vx1FR<BT38HXJ85Cul`c=T&?$&;48g*E}g^*Q?L8x2E%7QA`Uxxb?c_G z{p)P+4PSE>rwGfxRag2n+JwNC(T~GBpr^Ei_&gg|oS6zqIk;Vx!gV|<0|JoJ4U#J4 zKvxJ+LD7B@g7W{BvRkg};f9VR*;Lr_mP#vl2`F<pp7?|zQfadj(z}viCsTTx8^ATT zyAVsm{32!d<@OHJ%^4=PQ7a1hGPXKNKmWZ#q%%zr{e5-4S#J^i{I-a*mb8E31e*=C z)b3(9aS}77Ah1X!MOQ-&U40|}X~@_=b@H?sD{w51BP|w2G&4im{}=Q@AN$6810PS# zeC3s%6rC>hnwG-!;z6#5hi1rhqNf!#U3y=HnUB6K6){|uO_EJr?D>un!w}n)4=2~( z2&V&^O<<ffx?8u16n;p*;b|Iz#(BHt%zay!poy{zTam&hRja10820-O7_EkFPR!l( zA$5esz$$<*R}v$-Uj|sKY!mXY`swiBXN?BT08{+g@3?EB+BmvY=;JmS8nS60y{-?v zPBof7*)7i;Ux7H8CMwwH>USW}{6{JUg?wYrAxIS5Qy0=M#Yqws-HLqXrR>T&jW+As z<iq8q8g5>Y%bzr4$F8)S*@;3@ec+fxQrU-h3=@nJWQXKlATrMWY`b3bU5Ue#JK~1Y z@Oc(DJy3I}0lTvizc@tU<dT?bWcL(4glizA5&AZBrjHpUw(RGE3MXfyX4JW?1fw7` z5e2H~=!Q<)%H_ljrCPE#QMV(b!G{^u{oRRA1$KpHG;ne`e7WXPVo%B234c&doV)y@ z9$Na<wra@yX%jpW`i#aDHoSoB@MEgm!D*rw`Y!x*Sg!J1XoqS21rFStG-CAV-`9$; zojbRS;3*%%O^;m@a4%OpuS0xw(j>VR0U=G!fI+N>&yp`n0@{Vx$LaP`_T#m_*HxGv z#wMMG9Z>l^xyY8=qtq-J+XvJ|51*DoO<^1Z0fdSv6`uxE0akei5enO?I15U&SlbD` zpNb(5;SR&xBI7C4j?6TmM%0eBLutszi?UK|5(M{$kqz2})KK`{9X034ctYeQ0Wzsa zA*~PH(9}o4vLW5o_c^|YZ4~4Kl+U2{-cnw|h~6fQf1c|xflfS*B+k(Fu$%2c>O0Os zh+XUH)=f)y<wYi?bWO$`6HBLF+T)uxblSof$7Y!s5UInQe@-|h23K1g7wJwJWvN6* zSSIA%)E3pu$fWNAjrq7qppcyCfN38-H-rZB;k^%cIPh}&&$#2pd_{YaI2}}x&!(<l zajzLF$C<d`iQg9~9F(xU{t@4o{Q^sdMc|N$6Ll308&kXtLdd>!e8v23wCAiqb=dj6 z7nmQf>mxd4*)^l7;l2e8e%azpIzG1xtvUcrieRKC{2P837@ukw#ZnUQvjkoYz`C*H zP=_NmAfNp2#<6qBE}m0w%+?cjzgCUzW^chnr&)M8<AnXh@8I~<uXiI}sl)<ajD(>p zF1i;5o>~j`?_*6SchxvgVXH2rk<zsvft9d6aY7-Jz>g3u0pO$LT8({>GtIqd`b%=6 zY0&vp)4=naHr{)eaknh+HG2R1{0)-}M5NsP8668r>BI6x?lp62_tz?QdWPX-p6xEm zEo1wne+UElL-3|A4;6Ac-@gisGt*=~_URK?5O79Iu~;Po6X4^g=94G>Iccvc*qPL6 z$i(LPxpSXE$DL3-DcAeX^#d1z8m6!4q@3_?D`G0@ro`0QKgen9#Y7eXt|jAl=(DNo znAJ5f{k<+e4t!9)L#E0UF!lj-;xBz~FP%yk+)2I1ImPx%DOdI*krUZ^b?=e=&mXSn zU#Ph(Z@=;dN8#75oP|!ic4E@LbnbN`R6L=vNE`Ni#F<$0f{nlCKK^QFg6B|k36fQV zdy&TISDcLh#0L_lEKyNADuL&gz-6_Y((gBXPeY}0Azitt>!DYjy6_nzfw`-a%&SxF zd(KbRMvqs$xQK+r(7MEHZHw0|8eu(o=QEscPqfRH)mv5l!k_DRaMk@G2h?d#{I;0d z6UgT*k*VS8(s^Xu<>^oSe*80HW}s$Kbxh|cepgEc%-KN#zfJczRUw;MJP&mk%tzu; z>ocx@mYo{1&!%p?LkF51`t^UKmcH@o9_F%^>%)$yUN$zId>gAz#5<H8X@_!bn|0GR z&%f<Zu-t+w>gaZ3Uz5^@2A#iDEA<bDXhgd8!QEF<b?>}36o5;%`Dp!|+uF(rBrVnJ zlZ^f=bno=>T1ypVKV6+;H1xwU(27np|7>uNcR#nLsF{VD-hXpUIW}7Kmy-F39#&se zlHrNpA*yX$gC-G=b-`4>FeiwE7q~u&QQpG^(z3LLF^R~a-WsoHDOsWp?`pt&?l1X} zki7`TO50wzWlD;=efX$979gHOAhrY|E4-2?Ua-C*#QCLrg&30xN|Ts(--)uKU@j)~ z)%P8X-PNneW<jwKU>rcdAyi((z&2=1cNLXnO4VQhaf@&dT@w}Au{@gS?G>@>Du5D^ z=MP`^N-NufU_1d~SEhKYWb4SBc>SXmkXHt8<|@GE%EiQx%mI-k-N`MQggW|h&3V3? zlf<>w|Dg!%U5<(Qpw}Tc><mAIX|M7&n^SuF?o9iAMwtPxk@i`@ky@<L^MsciC5jph z`eHMtDlsfn=$MC3$&Oxc$~#PCP?5xKUfyELyiFH#nVG};Zn{j7SX3AywQ0=3wuhlj z$UxeYW)o6BT~9%T$?z_q0KfMsYiiQ21Ro%ZiTSI7#-FV10G`WpsQ-%GKLAge%Wb|^ zZr<pK6<K`8Rg?6dfeg^Pqnay}BhSOz?w-2n<8iO`7S35mMt=O;D<8i*6U5qemOH^V za`aLpliJD4*9xP0sV<CU)^7``=oH^~qKy6}iXNH}m`n%>iT-(K(L7S9Y|o);^9*}C z7;yCPi!2=-l|CVd8$MCkDM_t0vP;_lwx-X!oeB85w}Is4X8Nh0@qIdevPKGHa%@7c zE?9~XMgLRmb5Zp8*w*8XeoH0)d6VVyLuy%~oE);-oae6}L$~^tM>(?GJa%#P*|+5t zKitJgRTYi@N8P%HLB7>GHKPPxI5uuM!Ea*?k~n8i^N;VQ&spoMc%vT?!~T7;_=sA? zcXds2SmS_V_V3;WWJd1l4r!P26H{kaXO`F=7o6T}$eF!*k>`j>c}4m`of<Cf-u0_a z*-0`yx;W7=vrs$wD@Ss0V}CiMH5OT;FLu!vsudA^%mIVyf}+^>c3tqMCC-7F|LYj` z+jIJFl>St|n@ig}&C-q;qq}$m8vE0XEkYlc|A6X+{|H*fCA(Db<&JvEh9l()HcWM1 zrbgwL{JxZ}PB>9vqta<k{WN{fIZ+I2Ns;0TUZNo-c5NRul`^_C7RT(nesrFcRXMAO z4#%jBg>RbrIcmby1s|ANmlwy;uR1P9FeCNZs^6nONVZgeWd#h)1W7~(UaAkBZW#Sa z?RD$E>$s%H-MY5|Oj9}SkQBH5P}Pd?cRp<|d6rP3kGfPJ*{^O%L6$aac5z5uV?syK z>mF~bVCRlNS_=CAE+Ne5nD7BZLzim(DY@iixYr~Gy{LE8-ih_)>>LoA8vf4K2pPG; z)+*n+N5N(u_Sbw!1*heZqg6NVr{w%^E_u$jJ)?B{+v>nB?xp*cSW9iN<s6Bd?|*e6 zso_eg<XhN8JyS2OIUHc=6S1^ygwo;D>3fZe4qi>1HmRZa0hj82!vWao&v=E`kg8Z( zulS-P-;T<^nBgijAOGHT@8GIj0~|Uj7SlwkNa=Ph`XXTE@z)upbSMOIRyi#?lg<a` zUqpUMy-oP{JH+`eFUT!->3)GL^R27YR*7qY>6+L7r}9r8xQOekRD6ePzO}jt*w#wf z;*OtkF);t!aU73JVkV4yY&rSZV4R&Eh^HIt<4Cr+yB^r!in;%=%vZU34#Z6Q`K95u z!eom&aZ)**U~Of}D+S->`fk5IUu5dnb%Bd!Oa89UuFH3q%$v}pF-3$&6anQ@zbucK z;^|LpFugUl?XEt+WuS{mcO}_Qq35eLhIqD{)S8#{)~d~=`j1qt<Aat`F0q-E)lilD zsk&w?T=fr!wq$lLp{15d;}V2S$JB6Y@9DmmIgGz%E|~CVt4>MDb0fn)6j9`qsx0*n ztGf4Toch)A<Q$x0(IqbmX$5l};|4j3#=mvPSHrWi)s3z%mJqY0JJowB`$_IN&yfRf zWp2F#BN2ZvhP@c0tgHmJoGH)!UsV2S$ES-Eik|odrK6F$EP&#-L<wiwjc9}1a&oL^ z`jxTQj#>B1AD517MVT6`T)@_glYr80<;mk*5^G-{aJ7+pJ^kFu^CjA0iKkshq~~fb z2_E?qey64RB*pcoT&qxAUs?dX+O<X(Ggp6K>M|xL));g(kETz4nsk8)YCCUw2Q}uk zN;fBdIx8!SHn40>P?SkvgsoM}Ppu94W0F@Yjw71q-H}UwIQYcxIs0krp{BtfY`IKP zkL!J@=k?<IlBqx#YrnIcJ}w$VL!~AHsqOIxw!2ZrfBk1Gq!0Mkg+fMeIUhc$F{<=$ z$?yAT1^zsq?VmW*cSllQiAhPe4)VN39a1nEo=*ZwC{zmiqi4SY2Ck4=(3bN10u|cp z=J<9Rl`6My0}p?u_?|uGi(^H>yG6?ZV%UxP6?c1aeUx49EQ~<LcwNd^&v3cqpsfk^ zXY&bs3)n0naKFtLzn4B)&;x7E9veqS*xhl9D{PgFH5ws4w^IMj-8Y5l+G2lV*@)nr z+?Dsv9CILN6^u{oAJ)2qWhrlssWSgT7Gtndv>YJMwf@~;)-R4&2S0^CxqT?rh~BOL z-Tof$=$l!WwH|lfhwL@8jzJ(bOO$6z-CYe?*Y~*PmMc{Sd-8ml$sf#93a0E4q!v;y z+3p*>y^C^gY4ex5z_#n_l+$T8XHDqIOA(<f@BLU+U!K#(ly<4DI`W?DRSI99T{>}G zWX;R%ZPmn?HmPKR=sR1!Yy!RtIk5>vO$Z)f%l@^_^R^{af57!!vCleC=<FSrw`c!n zL-I1!@6{TY_rfRPQgz;!F!3QLrl!^mgZX=8N%Pn}&X_s!sdsOjSQL`|;3xX4ONn9> z88#eo1^+V3rp_|<SqZwO`u)W3W6Q8*tBMxKJeyP+CcRlN6Lz(eY>zDyR($%z?=sHa zGpPcPZTm%e!4)y4^nBwB^rSRj-f|~7{P8GN)9dEt;+&OdMxBcIJe_eH*NV~L(N9Cc zVd<oh6TZIJbrIK{lWeNn#4>WLT{Qf7jn6#pwOwhN+!O-Kt-~69WXLMbGyZKJce#b* z;Paa0R%=-P`c?h)&pz?{&pb5iVLEkc?K$RD2(g^}qDEp!MuHtYyq!B_cCA_!5N9Eb zf`v9O^PXL?M0ssi^uLu+3vU~YF^no4LQ??`a%F6|?X2l#{VL`46=mnlsCqc3oTlTy zMZSN1@ST3Aq>>?Pj1R`BS31)G4!bfBjBuX%>E6n7yUnstJI@TsrY36brFxvc<XNfN zFn9*4%<Cf=%8W_y-DwNEEh+H6Ieg%)+@`vod~$q<ClM0O8nS9|%pjj?!b;_cuE(+$ z3sy%2o#?=ioE$n26D#i_{;pN766zjD^7zNe;Qqpcm3;B6N~xav>({BD`KR!=B`p6c z<=7KSIqk304h`PkiO$7Klc_fd#{sz?XYv00C7%Vjnjg39pl69^zB%ovDm5s`BT&J~ zcPdU$DJ4o!u6y{*>DViutFa~AZQ{W;f5p|ZfBT=GI<z5aLFpBCVXR}a((?>cU!|-r zh+EnE{gn?9!ML<L7Z(L499u&aQdVy*^W_cTofuzVL7PpLSciv4{2YI8hKtZ?F1#h* zp`P9>)UQ{DOS>19cu()%ef%ieDdQ~TBT4Y)V_O4U@hO_4vMYao=^&K3s1gxAltLXv z1l%-DrZS)Y&pjNTPns7-+%K3@RQ9+bWqzDFym_7I!Oux%A8`FSYEB1rY#iNkb&Y&- z#8&jtM^lGg{_W#{o4+dhL4}ug&RIzTY=QHkrFCcHiv`|8H`=RG+T83P?0YJ%Tc1mg z-wMIJ;f|r2^x?FlRc<|Eo%2|G=JCkD1lKHsAZWV^dq7U+=lw3t@$Jxz3(0<c)<^+< zhHu4QYFZfynd-(A<p#t}xFw<X#)F=&fX3(AI(bb2x_CwtHiWEH4htO0XN<4?cR-2h z!7H|gzt%tJ3yV^JP`<y#yBJ)1^U)kp`k2{@>I50wM(O6lGjj9G*!osAXiQe^p!(Na z2bK9UjXg_w@j)*c>p2(a*Hi9$%xo~<)>)U7LgNUry;q(W831`HP}9*XPUjipYH(T_ zhxl$4d8}`uWNST}Dw!hC;A`wJ*~R5dY*qH=&n~~I9U1TG=DJ(!OtW{)Q)1c<Q_N&9 z=0wLA@#n|q#iUO@kSc1q;+8y9n__DHy78DXR=#!cvRsTaqB3;J#U-S_55{d#gE4R* zXvqK68MOVArM>d&20WPBq_&(MLTpF-!TaNrMceD);^!Nu+*@xuv9*8C<JQ#r3I7TY z@!5QXxF?wWGI&S0(rd}unt;&dpR^%IQd>TCl*?3)s+8>O-M`o9w!2mqF7u6D{_iCS zKC&)Pvt@1ns30+4lv*Oa%wJQ6YvyoQaa)K6zil}}0z`7uI?dEwE<Eg?%>@!sF~i>5 z;!H%k;45v=6!rV%F^0*@1qfEkd~*|vCywNwbE43#Ty_oDH`6;t;~ov;b342spl4%T zR^^CIyX<A=aD^RQl6B@~rK#`$Z&TT4FOAvN$I}ODzi07-K}=k`9?qFf>ti;ay)s7V z>N*e4`~IiWR!O;Niknn#l4`FWRpfHxSo}E$F1bkh*|C62F1m(woojtnzG9-$#wWK| zk|-QoXXW|U-l}u-U9x_Z=~kT-qWpK;6TinrJ00>LQ>~Al_?<qqP-vxF7uIR7S1*=& z<@(lo<1}gRFK18(Uv{S`$nIS=<%DN|>v*k5Yxl*HntVj_L5Q+?sV^?Qb;|AP3Rm_d z{{?9FTcNLB3%Wa|L!!%)Al1H>bf0ZqKGt|~wC^)hlQFKML+Re))xi#pd+?3&9Kc5N zVX$btD3D4nzC0WEy;2TTh!_iey|Wbi#)LyFPdl`p-z<&gsL{J9g}Y&pFEr}boo~6a z3Qj-2=>OWTsVcp87RoiZ;qN+48t4}Wq)9EB%73J({M_AMp2)1g)-btP>!@upDSuar z&yE7RZ5yAu)0Y#*J)Rv>mk_UB=Kn+af8{-!^O=G)uB0&HfYxm~%PIe4U{@Olb&p2^ zqsVviK#{JwQa8Pn)#J>%a+Et>H=FraOHFOdS5nEdMIQ`&5Fex5=3xRiE+~2S44o57 zSHtODL+U**0c|pth5KIz!ws!8P8sP@yY>oc)woNdGqb{C3E{wft|6wDbU)L@ZK+;L zv*|7dXNCO4^4iZ8TpQwBGd~$l{bl`YrPjn5;>$)plIMQ#?g#e$^2zsuA^TdpmADt= z7e$=*C1%Ozz3bV6QySG4$ucL99ia=-zx|Lun$S3q03dG`l(tdPD??+pCmM@}FSEa4 zdg<)<>w`T{%Z-cPPzqm<KK*%>>$?ZKfX3C)7SH5-^VXPIx!%%jx9*AG3+o=JBBaoU zu|y%Y4?U;wwz;{o^`BQaILgzb>7I61g=9A=4PMa@<cr|<MqC+M;GKGKuD^HRyit;8 z#51i!|NOOXxbGg2WbeB(E*F?bwrrCwxY?ENl~P^4l&x7a@5p@EqkTdiXF9*5Q2OKz zx5nyPH^Zh*;ZBUQv|hGOm+q$xmIubQwp2<t4^CmHUY(?zX`?A?*HJ?^SdKSlT$1{p zGcR9RJ5^rSB=wE+WgX}(8Q$7C2eO_<bw>~VJWrpRSs7{WrJ1HQL93b0%V5YDV4UrE z;CFJwh=o&i@*PUJu0KM&Z(F}DUr<`}b4KImHuG2Wm1$A?>ZF~M>W!0UC`H3Fo7sp* zH~(&?txFjttS5GSX5EV`Po?gyqjN}}D|O`~)$62c3jwCSw#8W5I_hy!*uNebwvXHA zaj<z#PrYm`y4xlF8&nGZcfU9P^J%%f?^jtLE&sx_&@rpFHPQ-;^y94SG9XaPOkqdf z%2u8AxaHi+>G-GLmA5oWt(%Mmgo%GF8FbEmYmw#M3SX5)wZIcM*~Y#L3;+53#XH{J z=e7)9WASa8RP?6t;23X~rB!!z1M<9^-_TlO59{3bw!C*hX-Qn_gs%eL4kl!&gQDcN zFzfUWTBXPD8Z6bXS2aX9+a?o5)>J!`LdAcb(Y?r&qyN7L58iSACSSYe>EmDA+wHSe zOttJCkL*G7KJ%3Ax}Hr#K>$)q+Vz}FPmi0rIU(7*ih42Fcc0^);~tt5A-ap%Vtrh6 zyi-$I`tV&Z=NXfiNdrT_$8M~&gU#yv`AS3W@n*TP+iw{~ZI4vaA@A{(t?vlDx2Aa= z8Q&UkC?8|>rc5dFymHf>W>claL9pv8XRyAue$9>rB~wnA{~cmziLO}}7TSdndc1c` ziT*_Hca|Ax(h=u3tCW@6y<1c_yLpucS4f3dwdc3IMjD;fVJvyA8hTn*hECRd-nc<K zbxTRvN_z2n7&i>9%fDCjTIc04<<*GxPnw7q&wNq6El#oOUDG_>Z_Be+#X02@QrLd^ zM(Jp?9M&-Xhy`XXNSk%svP~&GGB8^Xe0}|8aBxqPFD}hvRl;L76SvP9JDy7kzM5C+ z4U740xW2^nyBy&fXf+i3!nts>_N-aHG(tvT<zKh>7j1{MqV1pU)rYjv0gsi&>X?$} zbvbv#gRkZv6)qHu-!vpN6kNID8R{J#KlEc_!am>55aJ2NkKx{7KRSO3S*YCI-UoF^ z^|C&%v=s6VE61z$zPj4K?VN|gVP3-3myAUbukTsq%xcR(aDXemfEJe)wHZ{utG>(D z-$|J{-0<^`ANlAj()}^Xy;BG4dhT(g=PlT>-m<oB#Q%=2uAQVrI#oZ#JT5xY?Mt;~ z-f?CSvCC8qL#Sw)i(4ZfUwz52@J^`?jereCRp5$d_wkp!{l2@aE%|th#ZWqFz`mxX zE9C#k{sU%?zWHfw=*1V>a*Ay}Z#Un6Pt~s8=P{i>+E9{pqIIvfT&HPN8k}Z52E%+& z!Xdlq6IJJ%yi++EgiG=U!W~~mK+kOZD1=J<$~7PSp>C`;&Px8?@!10QP4D#IrDx05 z#jc5$ZaeO_w8{^Ye)~~ho!)ZjiC;gD=>l)!6HDi!a&3o&IC{p_mmf9L%qM*k<8Rw# zU@-?3b&wrpJ#MGv<5F-r<C5|D0oF`Qz~9r$Zx+A*#P5e~{eJQKuYE0eTui`)*O#|w z<7~CsJwGW2RTaG1!^=HGU2ndN8%}u7{SKu(OZF!2kWUSE&F-Y}EDJbLB=mqedaU!? z-e}dA+<nR#)E%a2VP!w>kB_X<^&NNKf84#U$(^$Cr^W8X<OXljZy9IyeD2F~s&cw0 z7mY8Qhn1y|W<+&)Q(2BUglEmtH$g8uG~YMhD93saCS{ZH>mk<1&(!HOzaHuHW4Z6H zYbepZZt6>}EB89)*#p0PxLNn|`5S4u4R1&%v-bVu+t1@!N+17{Jg~I^u5(xw6U@Aa zIHqN={9_`XUou-)<!GM4hq%#B=|#v*9(vmH_0RJYZmWmuQuU>IjknHtst?9=k9bz6 z%1(%%6O#51U)2qNA3u}OI;pNQ@>jXg{#~$Z!2NKq)n&e^Jdg(PuPW+zkG$k<G0B}C zJJSMRcFjK1iFcdR1-xJ*<S#!T5tjViI%jom^+A>Fi%PJ%l>m=hACszj<_+hX_@zl( z!GHhQA24q1`>l5OO!(E#-Vni%cI{1~8YTtTS=<3&V5zo`bbpF#>GkWnvd7n$BT_li zQ&?spe~Y|X`uNY%XXljc(~&{C<;H3l{hIZ~k48NHYFy0S_}vCo)8%C%9Rl#?WX`^@ z`lj6-@ZY3TKi4dM>50wNQ{1YfP51UAVra9%v9ujYExzyk&+&61mfZNsbY?3IxJGck zl)LxgS<e9Jvw`0-|3WU=O^Bjjt^7yHo;}I#iB2Ap8UWALE*KnkPek8hTAMt5x<AVI z=G)S|(&M_;J@$_O+3}@lC1olU7fAkJWZ)uAPRA=6>zfn&&kJS9+IP!jPaHQSvq86c zT2Hv37w=u#kn><nIWsytmC2N`)3L09qnTImwA-N#N)J?_bn4yuW~*75QeGXQihp&l zK0f}J87D9r%5MFjli&|g;YP`|y-g>tzuGD-u;`8m#O3M0j6G4fji*-Iwo89&&<W-< zq~zHaBSu%}j8bv&{5lOIrUlO%5_P_HVhD+$!sbuccD`?aZizeVQQxm3z5wsNISkso zxnDtBT-6QH9uJm4bncw}^3f)5;oy11zv}$f`Ao@z*7ij&50D;hx?h5R=u#{VL;slw zbh-X#Y^r|H=p&+Mn*`<7aHIYFh)w^ttqxhy5>G2--THCoQ}K@-kw@9E`1hfAN9D}^ z5z|2EsSa4Vuuaxx*0$Lm{kHigGjle4I;Cc^j?M6Bj)<C8Y=;9?zs7b29OUvYw^K5* z_0acUmT8}|r+lF|yqMS=iTsd8r-60UYuX0VAZm3*9uH=4+bP}EV~5IoCrA1-(ygs3 zgkkM{q|Xal<i<WkQ&dw={O++!J^$VoZ7iV^e#Bea5|P?npIi}LbnJ;=#=Xy#*Igvm zp4sVJQMOtfCw0MkUw-5xV~`6cHHT(|#L8A%vaA?PUSTxI9_8lG8Dww|k4LSc@!Zog zS-$n|G$A@m>Hno%ECe_+1+xF`=XyzY|NFDj``v#CJ!W-nYRDDYXOxJ;LOV7S<TllH zaokL$=>AdSn*I)*5v8QKJLB={^?gD_-YpzVcQi%FO+q7@XZh9td&aU19FOcCvyKMF z*$6dp|D&c-WwO=V$J&Ec{lEB^m1Sp|Y!h{lwSPD#xh*#)k0d#u45LXXV(T7cHX_}u z(M#6q)TX*F^y|?D%mHNAZqs`rUHhClqrb(@!<iF@9`4-X>1m%yD}ws_2wNp#dITb= zl60;_*_CIyr(Yd$DkOWetrc~F#yD&GRLg<L6t(X(_J=fJSS7_L7?9L}n+yL)G;}#4 z{9eopNOP*F?tbd*KH&Y&q_36#OMTEe;uMLT=CD$sm+CwZQbJO7T|1Tih=2j^-DmQq zL?y#Ln*O`%n6>$PA<+_CUEv~s@8HP)=ApSPK+Km&w**c|NW7<;5)|j*;v&xo*RHm3 z-v4gF#NZ+6<PsZSbDKN)?opMcJZgp=ohNq6^vR+!6!c5e_JY*eVMo%P-MiShjE_2; z0;yq$QPg<u5A0vf(KcA1hx?cPXY*n}$%UL=sdCsjkBS+uYF}kx?W};WBmVKDx2R>_ z-^)r^)>OU6t?WG(r*scV4bIUwH;8()&z3dCddBp+E~LI?;2|su=_bF)oge;T#LS$7 zs=B7F2D8?eKgS=zHl)xMs8XyH)-M_urjzc!c_4LI8T{H(M<1oX>*A8~gXuG=)LOEi z#`&ext_<a?j{9SfAav&G)ELE&;UZU#@bLqJDwg@|(dn(9(>qvR{Gl*)Hpbw(Ce?2G zKrT^A&ru0_sIf}t%@hq6fF4)Pel5gwY?7uCOn!3-zjbqxd~(?X)gb5642Q9yp4z!F zdf?(iZq>q@YTx>1WIry8wu1^150_jT4kMnb&Jl#v=M;PF&dhuA<E(l6l=|hL;q1ea zW^Y@<zE9TfI-xPk^P=gn9z+|mCoj-+xOu3z_vaz@Qdj^nJHbAt+`QA~ksdO5UEfVl zTIGxnOb~kY;tQp>e%_yGNUJHH9c7`jvuWt1pu<~f;(n*!R*_h8cENinIL1zI>fWz@ zxo#dfVnMPoE+v*)<(r)-l=BVYD_x)$)3YN(vZyjz1UH%d%d^|J8dR~K<;~(N=<2-} zxTw3D4#wbZ+j_Ks8LkO7sdUpvj&p7k8}k0oit2>M7)N1~Mt08!Y?b-^a)^igqQ`IC z&+BSfZ0yz4(;Ti&?HuB}iN!|?6OFy@MUMVmb(^XCs#ADt+i8gNSVM=ATMLSbdUbu) z`S7`3+l?XCXN|AUDC%|F_z%;0gl0umZcp%5wM+N-yUv9Eok9?C4qpxDqQ--5E+DDc z7xdu>whePpjO#+Bf#sWGSzaooe=~O0s#OcFZ7|h|3Xq5}YiegT+?VT`RBh3%n>yxo z##$~FDXyZ(x5m1@8dkm%SuP?~n%7E3|M=gR6i26EJa}kRP&ITNo;Y@7p~tfL!Y1Y7 zkUe=X*L>xShZsWfEj{{Kw&aLLgcojYN-5wV4=BUAN1Zd2nW+jIlF;KX5zhdK1A+xL zb}6KddTcvO<vEfwRliqh^4O34a!vZ=r-oc}uY(>-toFO1Zo&Xj_Ascp=B-9sojoAy z%k7^ia?$r??$YzB+xk`kqg~_9`A!?7x?qsVb>saFe$sST7m|(O%N>u&%JAgvU#w{D zQ(t;_dBeO$Q|q!lCg<x(Ia*Iboe2apWrOb*V@F#;hp&Dfbz`M--GzM{c?^;(i~0Do z43CsVi!2{ZXuO%E#e%Wi(XQTdC;051c>TXmw)Q*fu^+kBn(KO9iH$q8Z;W}lcV<H= z7a4aFU;oAw>Hf~+0b2iT|L+i^>Pu}stitepAs0l!f1GX+R&ERRQK>h>{SWUZPj9De za1L-j`sQ)^1c!R%3CDa6t1=>(Lu{$932=R`U$xb9PXBbf-W;%>P{)#*BTo;qAsu?+ zm)qC+lc3fJinZ%QXUM&m^|maCHr}}#@Qrjy^D+*1_HuQXGh~m1$~WcKMIpYU`#*?@ z7^8WnL!%AuD?4ymSyR6UMG*!R&Fr@w^mr9eHxla`jd*_UjS(68J(a%012$fb^+?|i z{;iQMeLQW*0)}_gPn%b8>ui;s;T?~E+mRE+tV-y*0u$JRgT7;hJn%eXh!x`ugx(w@ zhA_g*WpCZo_>=Dj*Tzc=ejHZ_5w~|fmqD0xSTtTY^c$kTweOFvBR#)`+0K*whe>6E zEMCijJtz6L#=MQRUF4Sty~{KG+sJtgeCyJ)+jpHPG;J=hes1qdsuG<?Kbjbf)O308 z0_*1sUey7y0=wV^c+jC#BsY{B616n)p{G`JqrppIa{sqc%QA}}$z{)P0l{HM5Z87g zb2ZfW$TDlFKC}&=srF_5N`#KF4rJwK06hPxujz!VMiI(pU2j!?{iGwlykqjB4mq=T zjyQ%Xi-RczV}Frs_CReyCA5}?qV4UjTGd*po?!xpxOuu{+)!mI&&b*BdgN}<<RVqZ z{bldh6)89GB!AHuS6^nD1#`<UrD&l!yLEZv!aur4PL9%TXJ&eZ@?dBa4V20e`HKE- zWDndNjDi)vjc>2opf>B<sw$Mm>h5!I)P^4K?b;~6EgjfpHINagx21dEYkaXdyK>$X z9%6^do{kDEas;QK%*22}f?ASJoxozIaUIWeXZ&te{cvF5n`5N?c@EY2CM5B0rWw<b zoST07CX`cRv|XLREhhrdh`y_!^ar|_deJ}4=3nnE(%2hlDg0XX)*d61dntUx(*nsR zc(i_Gk1IFPIfP`9Q=Y=!2SWzopMm;FabOwLnUBmBngLp_8XC3?+>l!9WS}m)@d}O? zKaU}elw5aofn96@8#UU|BBQy1!#h6lHQ_KL??7s<@Ioc0V?&b{Nus6s0vOF5r%!iM zBF3T;xiLLWKKi?b6=>yDKO4=OIZ~KR|0bsa_aVNhf%Xl>KFLikhUX1Xf^JlVr$U02 z4!CH(m;&2W$QEKe9KVsGvnL);9i+>lhTxTqfaD5Lo0r>t-A5%7c*FqAD8&~s4kC0Q z*MoHtkAFE_jqF~Cgw}~cPQG#hxslI``A-Jwlc?U;%55rk&hZ*pXQs(q-V=42rP$7u zZr1I?a`a_t!ThGZDc(Y27*Le+$nYW-6r9QCm7DG7w)W4VszZO1D4T80AkE`;!%vA> z5m-@~^<h#A<x-9p-c|8HRH_a+G3>q(>eR18bcCExMpQ}naFNQQ&4~WT>hb6!#dmXD z9>YqFTF5u#qw!ls`u1`7>dA(LB9YZxE3%$5=P{WYn-M;5Lf^lOpW<NM(xc%&<V6d` zwll_M9bfJL_F!XFI-NG6$wx1?RBtGtS~UZRt3!N1&r2DEf9yzjSTtyo%w15Ajhwy3 z7_IxrbDDBI>o7AAx7(Z3QV?WCI_@1wUBWUL((2m3?Inx5YaSw%PV_g!`p_}gfm9KD zShHT@cBB@<01J_Pw_$fzNO!NWVYo_BN^_{pRAnBUUgZ!TG}t0P)oq^WP1OK}a?Ddg zzXy&CY5+7a5+%(|`$~HV>Cc4U!|L=xd~M4&5BN2hM{3~xUL3yXLACV2vXXTt8`4eN z$%XPO2pF}vEfCIY*OI-2i~Dcv$IWp6^6JFwoPWhmxQk;hOE)tx^O7q_|7Oi2-rXT# z#P!?4(pvSdRlhsr{OF<(0^IOK=l9a2JYSwBvd7ir8+EcZAnokbMB|@#L%ID{QwjLB zOL3N4K3dXiP+@9#KYe`Ye;b$o7-8EYpBnAj{Qgh%k6Pv8ZBxp9zj!Bp8*=lJ@`ZVM zX1}w+mSkfrJ*X|0cOXRfIHoO|`AS`%Cw_fBCatCQyT*c&@+A!)X_bKH*b)-O$p;^G zF8jw5zqkJ`-FtN_Ff=mTh7<yq);3ZOEvuMTB(Wu;$SKwbU4OrIDhXZlY2Po&bIU7Q z-bfhe4E{z1Yr0W&v-=+x&eiNeX!&^;sdcQw*$yABj1^L&Qa)jR*`^DjWvzq7&zHJB zHT_-OZl^C^mKxk&0!!*L<Wr-TocvTS?>C>Ec;lFs$|*$@M~U@}L8ofbVyUOa<v`l( zvld6ep=PV=Q|UE#wsKWfzdVQW9h0n&UMw4$uKY92u&&W_bV+OE&&CF4f}7hEGo=P~ zZXv;w2EV4h;pIUWdzi*7xcU5<d9Tlz@gcG97MtQswdJw(*e7)-M<ndNqpE8xUeCEy z!qpjt!jc!R9VovqH#_s(D|<)0!tC6Ee=nS(gqU6@W{8qv<B@_zP)SWarCXmbSan;o z$7$R2<zyhsG1GaIaCcxD9BS7VBtx{5w5Hcb9=%at?z&bM(30}t-O{!yE4k*?#N_#n z`9CS2SQj=WxxL3Cy9iaM9g|9SaMH+%cA^<Ds1^-93-@@2wZ8kR>wa0k<?Fm7la;vJ z?rKN!XN})IYIrd3#>t4f1&^wuqRiSC7NW6Z5lC2ao$(T(QFLq1np|Z`a0Kr(l?`0| zb7$$n=Bv@=ZmF!HezLAH_e_|<(m3U_&b*>TxwT)qL*o<ZW`5Zg1x(!*mTGYRZOX6G z-!-xO{F1dxW$Ru;Uz2x0L-z|!*6$bfk#03HgnQV%)bMig*t}k5&zMy8FwQaFW`cHe zbkODHXDdu|HX*nuc;Hs+UEAInm|m}~Dk8m_@<$gE$6YlMb7(p9L^1mBu>7_LNlNw= z@Aq8Mc^SUEqbBoP&6cjmuspHcx|zj8MRV{jWp-e~v1YWCRZ%-DLnL20h6rvQ`|#7Z z0s%aOw>UdhFN?hWqRI8|0}Ww%*ZR+5j<L22izcC1n7i|@J&BA!tP$?S(?^N7PH15J zZ|aI~uHZmZE&H>+99-47_5h9(OAk1+m=;u6T0c#vnYmLRxJJJ-224P1nnTQO&2Q*? z49X5ceH9kUa?8aHW-L(9BxhO<SQ2-9kbZh;2CTuIJ8(G|3F-(xG#pHjCtIB6m^)e? zOTC4_hMACrJC^c@wcMQaTi($h{zz%r?le=sliI7YSVFIuFpG0!*7i7!N27dn<$21n zN89l-1Q?<CI#5l}K{I<v@u3x6PHc0B8Pe|9Iq3tPIkL~QS+`Y0QCGRy5V15FSVYl{ z)Ur>S4J8L#9NGxsui?f^x?MVTT2U`snz|9qm|6d}%DL#@$XhA9ik{Q~z?-`?=p5uP z371AKD#G#-WzJ@Or7lP?v7<JZj9#Ml^rva048;#YZi~99C+RYmB5;e_Femy0o;W;c znC1{<o10*`C~&R75Y2cvBrV*N$z>PP-V%h+6M&{}YG-|OEQ#T?#nF2tq|}F45;Wfq z;S^1GUqpre9p}@;?8Q~?ly*Z|>F5@s!(wJ*kq+&*I4xDaxii?EGPfE%8Ifq>iuU=E z#iL_5GNx0AgSoEY8es@rMcTN5mvyb3t^<j*PCG2g8u<_eH@O8=Z@hviI#Niw)2rw{ zaX#$#(~2>)^jXTq7}~{w=%LskRqID;WQ@ij^F=P&jzFfDE9K(PV%pA%_r+{&-+oWC zf1laRW`M&&e$k|chKIgXcfml+rY1Y5W3x%wyF=fh5x9+08kzb3EXT$so8{6%^xupI zmn|(BuTD)rXV#(OvN&z^)r_QGLmNEOZ_%_V=Fa6a>oA-qaUNNiN+1c+Rd`8d=$(#w zuIorO4$4t->t)lMa6Oh|_<voypu`|;Xfn_RWgS3qkf3>Z^wDo-FYz8$uLSD~7*JJT zEgPzE=LExZk_-YUIg{MDOqm32EpWCX3)e|&D5<;t?t;`YWsZl3UO^WX6lIJ}qyq|E zH_-r$;q}%2ti`JNJoR$s-=O?MY7(Mc-BNyp0IwDM6x@I4C8L7@AVRPoiD!wT2l=&~ z-Lr`99&TSUHFcWXaw4RmPouqx_2O4B@M&|0AZ@ma<f%W~5Id;g)G-25h&RB%Kzi#7 z3^~ahsT}<v7kDtK2rY)y9j7L#NF6)<>HIWYAjHr$(XP*;;XdUS(;CCrG6h9|V9#L$ zkF+^)s})i0xIXF2zJ{)xNp{>~Z9|y}C7uw3jt8OQOsYazcefqvN!}E_IUrPOp_}H! z<aaZBuF$a$>3yO{H;IOsa)r()-XGO!$K{>KJ@^csJil~fc-MfIuFzJD)|hgr8-gLx z(#bcLk8MnHJeuP}*=5GbMR^|--g3FXu7RIlh~F-w;QLy^h1a?ElD-|;`kJ&jgic+V zv9B1>v&rd*-pX{xK|;6jC@+(p*naG>vzz|zOMD_zWCSHh`k&xdqWGunX5QT5DGbkc zqd2q?b3${?!|s{NSA>@fy0O&GS^B(B)W(2dE?cY#CXw}qc$;Vio0gJ`N6G&%VOxwO znaSr0L(e0r20)^Tb8F7-aV+5iYoFEbHDka@<E(`bVQ;`eFa<p*HYcjR_fMH}cnCih z22|zi!tAUNUyAm6;hW&3rxjq&X1r$m_o?92&cR~xE=0mz4AODU7t!1i)V4<wHmWnd z#<`I>9T+%o9#$nPo|p=U>3X);J}22cg_5C4=ot5459JVsWVnxHs?s!R$e;!hM9a4A z_D>hHKjXwA<6>A74wLDwhQ8&75J0@lEb$lre+bT{VFk$)JH5D$Y4pC?PyE{ACwG+h zx?kO6t71cwhREl51)DQN(kd4SqTITO3rH^_GMdjL$;RaNcR<$p-b*@v%*Hw7o)$GZ zco295gR(1S2iZY9p`9+V3a*bD)G&A+Je8vt{V%1~u(8Pum$$dRj3toM@|h`CtP~FX z`?o5m)Q)x)-R%vX1OwJC{Kx%-xGc2<#UcdF|E~BE88%Z~is%UsOsSLuQEnY&Lf2Di z9JdiD`eb5Hs>BzeO;S((uuCXY6PbRi<$BwTI{&>c@ONTD0eIeP_vKHgy;v8__PbUz zt;|%2sSvGcQMh_I7s2w;6Cj#9zkaQ%h;J`Co)>$V&#deXC)U}AN1SWjsx}qsBzi0Z z?uZHIdavwd!m~R4m{~{mF363$+EIxHl6K(x&zcNWt{&Vh%2GSs^W7#09;H1cLZ>OB z@oOpPs~&fdU^;@BCt&x{9L?xokx4S=Z=#-JZ9ASOHN}zxSN6a}Zb@!1;aeD&)qb*Q zS>=7KBS9hDL}FW<VSJzqL7aL!(LitT)8WWeMP2#V#Hm5aBKz$xq@YGezGxV<3C^(X z?26|L-VE0iR+-t4=<3+wz5Ni{-6^7^z?NdDOX+!&7&gO(@ePLhA-9f>Ocxo^fWC~Z za2UE2wI^<CVHQYpipHDeP;w+H&AjHS6?ggYGL{l9JaAE9x|_4;wIdPHjqjx9)_@#> zu+3n*gDy*0^{rj`)>Q(T30o)?LqC{I=!Y?LjEIw4LZ|{HobZRT5srQCI6P+w1eQ=* zBiwOZ!sMNHPuxUxnlDS(sfhQsyEDIqO9BN(qK+mOj+cB)l$H6xTVs<QENlNVx3Kl% zE)gFxzIw*96h%Ve5mDm9W=?wISC9sj6w}4;ToP=>4qv%3mV6J>N-9H}pJ7!Slv#9n zxs%e1MDi*wwI*R-`3X5Jr^N~7zD9VM)>_)EL@idC)+*>L{&_9#nZ(DYi-_&RI%|s5 z_>~*3h*8BPkxPm7=C6Z2jlA`2l`kpR7o}>xq9{|%sQ(=GR0%}5p@30Ke<v5`+C?$c z{M^+vR?)1nm1~(pd=7?YlG}*KQTtT6wY1MRNY}jZ0M5Pv?l{V8N4W>5SPg+B&3^&c z^@GS?Lo8}q+(qb8<c2#jy}Qnb_v8rEdWtS{d+vF;g(h4YZwaIPq@!$$Upia|FR-+! z&tqNrEPSnmMA_dtL^~O92rZ=?wt2hx=_}kSavWhrABoQ!i_h6+PMqOtJbQ$t<;Nnc z@*huKBW(SN33whN^G_4F$v!+}WuX95P~*ZF1I@iCG3rxwLt$nKV{18o4{_L5W{G6( ziQi8(!^+t|qMU|%zfzT@2fR?-#Zy`(ToMA)yv+qSc1=o#3!y{Bt*X_ur5C1()^#LT zkO#4{<BF?>*JXvz`JG)gMQ!e^5#<CPF2g0RJbulNO<P3Q+kV=N9r_OG*c^MCR}f9Z zq;#iPG)E6z2ZeTH?lrL=$5e-K47;Kkha`!WPfXzzY5*Vix?DaSl}FFFn57eICP*^* z0<f<%K^+nI`s^JEF9<@jA0B0l`qGe~Ji-t>bYkT|Vo*rEV7It<!iJlwQbq3~$XB>A zir@}7z@?1<D6HJtPN$~L{q}fjO{em7XM5M~l@SnBUYNM>zDsCj5+cHxsw|A!czWTk zX2;P<FFLF^Y43G~uc=H{VyPrB6)6&=1b|5EJ5ysHNQ3x3I4x4<Ceil-TFrkfTYOvL zj=nn;m=lHDx-c0nE1lxXg)93uL1TY2oVvkM0o8svV5(~ru|@oL&yhW4f>ip}D0-8C z0B+g#!SY=n>(%WQKzt^8B^~$2iix0U*gGQg!bm}SPP!Km_U?A8J089>Co1Em<t4(h zLDP=)H)j~@hl!7#Ovf&H$*?lmZ4U+Ha~qmE5v1|}#qHSgny-z&7Rg_Nv(onBX$9rA z7(dJgoQb1@VuTr<O<cW4JsGbGr^;f;hNET}NunwcVlvmmK*I8`i(+Vx<fF*$#JbFU zed1Fho7Qj%U21O&WfNhG;@~H9#3&5`JI>KsB`&GJq~DV*R<ai`@DYq~XoaSxk%0<a z#kX+;VpSBC2J7-0Rbo)diZub?^y?573~#UxYLDC6UV6?6$e?9Wpb)!R#h1#lly2z2 z|A1%3-K`yEj5W?K0;aw1IXY96jzmZ#)?bzgPy1`+P;r<<!-OxUbi?tF*r<FuTZ%q$ zD-P|x!Kq_^W>$EgoDXao;*xR%!-1p?;mG1yEI~Gof9NZxKa$TimU)_w$39^k=on!~ zpvc#!E<6#4K;*HOkyRH*rEa@_o^L!*<&D+`iv1;~lrj=~Z8!;HI%lmpnwEc^R7{z1 z*3?!12V@rQm|bjvEQHTPyS%v5<Ju29tuO$Sa-Ap?5c4-M-bqA~5Z^-jeuK?J#Xiug zQ$+k^+YetUa>Ec_8TadZ0bD|acHRxw0%04_lIyf2LS!&gd9%o9kdz?J*qi^;Gv}DB zD=aGLm5IZNg$-H2Z)vlKrl{T05(R((_dS+2VVT>Uf`f12W^A;~Q>xIG@s-*cX-3Nm zJR|~QNJGELXY_2fCe}FSiC;2vox}@a!39l9m+k~op*wGt0RQ^C1&Z#E{>44zt+GEm z#WvAK;%p?A1T*ecMjS5Ob<V*`Qzr4cIM+=*1^a$^=oV;vC|VSc#@I~1k?nAdz8Gre zHE5Q^w8yM{Koihrbu!~jbs8rr3@_73V>Jb*bQ`LaxzFsj!vh-B77DDS38n#8m{BA2 zujmb`XmhLn9}GJUUFAobq$Li)2WKY#@^Sdfa2CYD;^A>6G9K1qC`>JxL0g=%E1R|m zLYP5}n8b?fy{LlLnZfB#{6510OD%ZSFbXw;#Qd=KGgPrjPq5=MXzv>NBD+erphFj~ zYc{u83k%+Gr(+lUymk!@n8)s2rR>_^Pz&nVfWiX)!$Rb$_&q0<6BLeB7vIbM1xM@R z*RNG@5u=k8zK@m0Mvmjv#F3gDc9!6!xr~M6z(TrR$cy=vlc4NE{4S!qITP=nVKQd7 z{F_K7a8-=d7^BSdX@U`BSZ8nz365k!UkhDV!^*`yFB;&gyteVXKJ>hR5@;bm$6Kw* zPpi}in(6Bo-2U1{A!!}0+2Am6mI0lTNd6=6>VF`IGRnTJ9bqn1N-iJ%h?%<$peq_K z09EeH4r{}7fnBMcP;wJDQPrlPWTOne<WO*-SAjOXML|3~QNHQ&PcJP;g961t6vocQ zA>KWBP+SA9-fqodDDRbQOro>NH+Kh6iUclDKJlJ^iCmSJW(&!NSs+X*$`sxgJnn74 zJZ7%oO9K}gy+lW15h8LTkzir*c8Dvdz3_%Kds5MyN`o^IEKkTNJy(h-uCM5m6PM-= z!8q85!@39*V`V)S)_Gc{KYe@6NGYpQFS@yi4w7f`w&<cjQ6v|LmJqtA$LTa)ia1x8 zpbX4AL{X%(w3wTpl#c$&H32QW+#O8U5pz!q@V*NV{-!+LPGSJ<dPKt$i-r?0QZ2;< zl8vhinSR6t7B&p4Sn7_`KBN#JCSIqD$jW(P)SKfTIVdWRng9Z)IG}=AkrOR}@HY<b zMJ^h^CbG1xPnos;fZTeWvu4<R)~n3j&V56qb12f(TY-bV+dP*jZw_j>O2w0>880A* zF?!n9<|X&Q5*YSTq1;ktzRT4N-9@=J{k%bhL2e1ODm&bLk6EfOYt?H+y$8vCa1$PY z#xej!r4A&xc-%g)k|TFrdrOIUjJ5QVwZ%<AG>Slps++($e>>d;6w)A|R~!sa(O#*k zQvRu0Ax|VNgIZ|G^v|x;iD;t~W6sCHz-hUE5KjEiI;jCoo+BabNup2d#jyoyGan7W zY*%B5L3P<GR7FnNRq>2Jq*{$ob>N9g;|kX<N0n$Q-sd%grV!+%?EqTDTLrH4h>+Q^ zk%`o-%)=ucza$!qUZJq?GR(I0cj{O@j!z*>m1#JoGEWLF$O_&Fg@PA0uwI+tn7mCQ zU}?@i`?6hG&DQTPfK<i$i11)hJp#hx_iSTZiZGmmhp%an-Q1Zg$%CWLv+q6%0<w-N zlN&&N4_AEZ#gtUg6?d-Aj>~2cTRJylub1Fcc?3Q?s(jm(-2udQdOHP7Z|DQCErO3? zq@*Y<&J@hApm7JNn<6+C6-ARfICKe|s{}6Wiz&j%C#Msf_NK6aJJdUl>*&wMdqqnn z4IPDVf9kg1wXIu8!a!6KHc`y*A|JjBR%|%$E44G94Wu-H?Mny;$^dS%M8b7lH~E=z zL+A#IFh#h|TA@@SvVE8^h~njC;ajd164qUm!5FG_!C^=%;*M-0b@N>kYDq>IJ2N|w z@`I$uQ2N@ODWCH_(5Y?{d8o(u6||a&bu9Ki!qwfj83YqZjvTJ3BV)?b_<^-71OJDq z$#5WoRTQB$^66oaZ`g^862@8-9Y!sAPd>Ki1Q)J`D=g78nQD7fntP3$$p4$%q4g;K z0A(c{m9pISa(hUr*@O`siI!l4s9BC*c|Pa=r<&tyc07ZOhUVz5?Lgk-T&Fq9ELb=1 zdZwx!N{|ZhyMa0j`8ZNCLCoK|^krunBQZKJC+A6z^LcZT<$M5A<`{ZlVc9{omaOsA z0?&&hrG;Hd&GQ#@7LGrE)iex~5jAi^#YIt?n!7?PqEPz*H#qqq<q9M>Ptr403hg8? zArbn_!>8p4DFQN;dL3{^TVKYbw%-^s8;Sl7q(E-TPIn@Y!!;qEmRinAuRGz|3~o<i zM147zm=lUSYm!|9djx|DLWwmdV^k}?T|2*6wLW4@RjS<bDe<v<?1#*f6#0p`;;0hG zPb3#0!4>?h;73K?lS7K60_N`b5f(u?j)zYVgQzng6;k5((JD+3&=F0|iA^CnLJ6gI zJS0IH<WXX>dqETv+yws0$z<#ik;^a&;53GOZM>r@2P=CW*C3Z%3<T`WJ8r6H)Q*#& z5*JN>x)Y}c4X1e$2UL+kb9N~#&(q%l%I|6j;?7PTp8V=iV=N}kBIkBge=|iEgpFPA zagK-0;rj#iauTN<9(>D6%6554`|;0X9$_$O${5>KzBSCtEM!Z46|fI2gF9|~DbI7R z9Z?2melcN4y?6<ua&+(v1foW3*y`m$^<%D_Uoi~Iw|zXzCcmjURJO=v5|NMgh3*Ms zvyv8=$6DVqX}WM{{Y$u;Xm}c_a;&K?jIhY0KxQEZ=M4AD1v9AGQ`hkKtR+xTQ{XHv zTHpy9c2|Fw6Ft9tvwn`)PPW@ZP(C2INwWI}ZThe;gD*nFs+1l{)kR$5V~DG4gQjat ztK!-^YN|><SISkuqCUznyxOHGBztiOBno4yznMI&e1)Kq<>o6+G0xzDo)<IS>v_>~ z)GE?<W+-_wit6{@@Y+kMkZ_sw@Y5a_-)yEDTI)Owu!zm7EDeAWPxJC4rwW<5ERF+Y zpV>3P6qhvur+thgN=0@Q5$zX7jI7E>7B{FKyHA0FQDL`Sq$P+j9h)N)siK%a)%l%% zxZrAovC-nn+3qOY%<KS<{kB%{XReBf2_Ijv`^sM?IkL8-T}_;~mY<CR194g_{JQF4 z6*&^5r!}X$K)Onyxyo%Zxo!XlVUVExgNuWaPTv$Cr#6d$FLGA9vVwU}CLTd3I|QCG zI=0&$1i0gS<Y%eTkXEQ3r@2|a5(fCN>o#<zsi5{8<}z%xG3EK-5Q9{05n=|Z%9&B} z4q3i4M=L}tj+$Zb6op`216!E+L!}C+w2Zg0UKjXsQ37~QV9A--OXl=!r~cWyG_aZ; z6%hhO2B4wyb+b<Ws)OfcM1}#|wbX6$7y3YWA#&N|rR5+G3*^gt-H)Y+Fe=!@5q<S< z;%HN0cY-<CSk2LMwL5hFbchgk6N>cdr&TrHA~vJdlE`-&{Ahlh<6i2!I=;$U_;22# zH3J=Qk;bTnMi((4y?*-OrR6W-x(lno<zssEJ&0rABlhGiBuGU=jbP4N&@mqx3B{IY z8k-}zD-{yoelIIs-=*pyMMy0c=N~*%=U2XUV5DgvFYT9kHfhKnJLMp<0=8nq)ipER zFP$M*Cn5mefw09xLsE7?nziS*m_?}`XU^intJm?gyOL&v|7d?xLci&mDJb7|_?{MA zI>p@uiX^O)U?>gbT|CaW+pfT&i(_nYK1@HehI17v;Q9#7p@+K{_K58Q5!V0`WbSd{ zwsce-$9^o!Ib3~gj+!_jK3LUOSaUaX*YfS>&Exc;!vyk6^R>mUds|UVf45b+jQml1 zjAvNI&Yi^;Roh`M&{?|a-uRI0`<_t%W&q#K%q_bN6r6JAE;2q3RFIfbQ`!(j^#(JD zejI|Cl|-`ryRv?7bT7WbHM~ES&s{t+<ZhR(Ff{RMx#_a5x0!O;PF3BzCU>>J&%4R= zevaP#DV4#bP3H}3Q?gZQ+-_X-uy~g-PT?(W7u4_}XHmuV{XYj%eJT>!PH4(tYV!K9 zCA^8yk9SRyiP;RmHj%}tvIzLu#NnNNG~pU9<ARmvx2PYNH$mDz<{gf}u4>|0Z1-5; z>tdK)Dvg+CP*|lPT8^e3kat(n!(d-Yx**+ujf+1VsTpK1FmkxxFM|CYVsuc5#o7jp zQ;M!>)+LwGKr}InpuahB5?*QTVplPVRrC8N;0*3R!b$T^i%VNYL%NrG84S-BX?HoZ zvx@GSaN(}6`MT&}dLhRcKoHA4Gd851H7A>4p#08wO}OOUm(y9)3aU1#ZisAi0Qkfz zeuG|2H&Kr%Gr@E<;c$s<6sccDo_u1K>amI9qEf69c&e|VSpb-|YlNC_TKDs@?dQ}i zMSztVtj0}EEj5ihM2F^Wo_tc`cW7J$Ad1~al{wsNj|dQ=g8nSs#7XHP^*!+!V|N^5 z7EpTx6~|Pz&6@OZA^P>BA|%nckL>Glc^cLv(Ka!!_x!d)-I7V);0AsBw>41>*(Vgb zj6elAjlFI<)rbVLl>($NOw+x!igo9TMIAtCq31_BkE<PX3=pBRT7cSyp<G_ucNVy` zL;=eo&UHHRfAA7=B$!w>Q0m|ndh^#|OtOLeamt=v1KUgk#jm_I{CfKPsl58d{#@=A z`EAr*yMScx3ibYc5%k-R<a`(=FBSt9@DHM8U1;6NmTE1Gp(v;WOE|NDuw+y{v_Y%5 z8kg^sh^*tQ6Tex_*xJ*)SZ<Lmg7eO&LV!O+?Jw!4*62dK%Z2iO`<C)c_W-Mp+FO^m z_pOpRvT49EdnIZ+`2@7^VyGUrrZH;K;fR&~yc-qewYHD=@_joG{s0y%;{WyZ?r~9< z>Hj~KrLGmJpK{wq#+6Y#;wn~(1CyKEIH)@w^AJdRh(#+xBpd_Yg|+Ecj0`A|D`O%e zYLcf_kt7d=Bjg0Acmh-gMnphn6c}da-S2r%-^cHt-Bg%)AMX3Quj_TaUa!l8@~81q zZD+r4YUa2SPV=!h^tEhnDi*6?9q)Lv;#&p0&6U6Vc|Gab?onq%0Mh%8fPH&j+~7XW zddCicDOrgM$5e&XZV{<CDfgAG&cUBysFBn}qNAZbx8Qc=ea`3fHW7=!091*|JKllC zNlM4@n#+i;2U<ItBVU#0LoJy|aQORc6Q}%{cM~1NQ?`FQPjmP^H7}7*R8c$p>C>C` z0zd~BYl^v%jLV_Pp&u*SCRms0G=``#-+r)-Ol)v%jYzKO?_b=j+ueNXU01N3<(9#$ z13R@=NGn;s;OOLLcrS26S~>tCug9#V_@(b(ot36}gu|Jy%Z;(9c~<3eLL7H}aT3t? zCnv0wonmi^WU^ZHSj=_vf-pz%Q6$>CB-gXW{y*G3*q%N^w7)4oconUoF`XY|stHx3 z?Kgo0i@wRrJw?=_zsIL}8!U>CNBK{w5N)&&_O)n>myO=zn7ByLLGd7yvS;g_`kZ#4 zw^%O_P4ZH?c>ZHnF3akT+$0D&zx%D*GFRt0xtNUE%Bn4EtkDfS@a0PoS`)?RkvK8# z;k!sC-nHj3brI2y-aBY&WZBEKY<rXV3h49+Z=+V#?&Bqh{H)62{hY+9O?qVZF)FdI z>=>Gh$swQj{@rJnZ*vB5eLjRoYQ2=;qt;jj|Ew$Uz|N1qA5QvsKZuTw^1AGuFs1c{ z$>bDgs4!SIBc8>$&6DAA2*+wdH&yPI-q&|HgV=f%Xn#{ggZxO#59#iyG)k_gwgF$3 z5~O1<Pj5eBKBR4I4slW1T7qpZF63K6Jn%7`qDN~$1FoqY^iL8mSyFacz%AY_6N&vf zbIBgtsp^>YN#Uod2P}vtSl(S(y~qEWDr?4z^t3tm!t%1f)56^j@MGcYK^rG7x|Jyp z`yqw6U-SRgE5j$l5AMcH*_*kVgq-Rl?cyrKAE=WwY8Rb%47)@sNSr7;aA?-DGX%~1 zH==<jJ;g=j27|vc88VttVu6;^Vqq!$;~PbNhH9Wo%+V!T%`zkip`t21^q#7tmy%ey zY1V$YMTU5*vYzT%x$%~empxfTw~iP$*l!J0NDybSI7eIaVIZ@fABs#TsI6sB=DAp? z=vSAZ%Od(4+c>O(eYgJFQNDsA<`8z~9?Mik+1SDRsq}IboGMTf%q70IW_|J6L%OG| z6WDE#`B)<}Tk_0h16W35$4D@Z8yxB%$-k@>JN19j+bzm#W0!NbnWoBzGUB`b8GYVd zp}#5Buy;<#$ro}b1(4-zfR$e=nqad=$9m$`LcrvfBiBsllDlV(BUEmq%lz%se|%!M zrBO^1b;b$e1ugCL>8f;TsQ&~|15QFB!GXk+ny-WC%BaOE+|8^^jj|qY5C_#J0<ick znP)z9&N9PSi&|qK+VHbt#j*XRrU=cUB3mv$3g65XYtt>MS|`iWxQdgeXMhu}<>@)R zuEv|W(K)FODrY8?{rqCa-J}F);tCn691i0f&Jrw!8j?iQ1X#_QjRtRgDc@@wrY6T| z50`>9%+R$qeCZmy-0>*Z)7=2;m*(_O+TmYFiOM#3cRUU}PDD@d^F%B^gR9n|Irw81 zFLuehj(6<paK-P=Cr%MTXdTU#&cv%TUFPfaMDd69_?Rb;t4CwYvpL1Ij>m`a2QomO z@hrY<7}$svIqD0~@CjORWXGb40vE=W)iZ1<l>s>-bc3LJ_Ev4>+Y@aMmL3ht>9tkR zoXA-Q7`tCT8jIB!i2}V8rz~B*GDaRHru`k28*pp9pt%i}KcNp1NYl7;&O0}2ji=XN zN?l=Ek^-LuF3w$k;@L}iplrrEt$dKK0XBu&$cOUyBgU>I!PDAL-9rC@0lDkG?R~8Y zMIdbCF@fKiPp^m0ZxYoZX^BOaTJrV1(|o)!6=U)aGbY8cFeqr#4j{7=HcUK^6$Y0q z0GeyGib^W!AD=W!xBCf{ycbk%_c2HTyUb@wTU73puK>o;#Hl5K)dSJ;fL$yH-mvrH z4&%>rz%;y#FATnTQPW$ekhSJslH(#I{1DEN`5E0>YNEei880wwW5t1B{qtPkEJ62< zp~tW4SQ~FS%v4M^U+T*7gG)Vu8K+k_=?*j>#1hUG=gWv%^2y2j{93@?z4QKRak}%< z_*xt~eq6mk;E*EZ<|x11L7N?j!kx8$%Jzq;$|Ec)Lm_f9Q7R7Wf44_el>4+|=zZ`c zm2328nLk$|V;ev(^5P`Oz1b9(dv=~)e#-r9W>C+sZ^_=%D985LtBzcS=_Qc8Yu*dD zS9E}BWO&m+1E-}9=Pey?6>Z(z<g7*7xZ%c~<QNt;!N6hVgt?y8-MTi~)vobQbZWY7 ziT2V5nR>>|T-DNVfa)WbkO*)$q4cjH-MeSY?7sWM{Uk?h@t6SylP=|t=AoC()wDo5 zboZbuPE7*nWH_lvJ0*>q^7RfYs?;G@+R#7%RZqXCQ!kJ>u#bp6O1YUa;)lrgJmcSK zKTQr2+qh-qW@#DgvtJQh0!JN1@X8NO>o&}VyGWu9DE{);2&vZEYmHPh{q8~ScT*F; z)2&7t916P?0*$C}_wN}}TqPOg4e|keDhIl@0e|IxIAK-s(Q|CMX{Jptk6j`{hbU!t zuU)ila98L5GJD07Giig|oZ^ICy|b}0VBc;*1KYup7-M5NYS$*#Zp+2g+Ctxov=?L# zQ?9yHazbqh+<7|Tx6=QOK}L5qFq6|7!s^SQx;Epi4J@7miA{6$g&<T(bYCPzA_vuK zUVlTIz+f8xo3$u-eOS%Lw`nTP__IK^K*Lm9=FVC*33}KsHDuTe-RIRO272VS5@$IC ziMJ^BTKJF;^3q<E`TW0*8>_i|-#PNyM<X7NRL>H+x_|7KI-3V;gZ@+CUfAA{HW?H{ zXcDaMw&Tirm$?H1syJ*Gh=MQWfXEENPj)=(mIt)XD5qZ!vyPILQ({6+(3eFvVuD20 zU@bq;zg3bNEfDIE)S}D&kcXpL1AWM^)!wlH1VCeE#lwE^*3K6ttoVr5k)&tXYURk1 zeS3WW>!+y^eJwoq^T=~}AX$%Hk<Mt7l%7&(n5>HV3EkgHby5L+)DTldBe+kURD{RP z;XMsU)95jAh!<-I`>oZ0acovgaZaLSYK(a%Uzj$@?rp4x3Q*r>b3fWZjw&A@$l9l6 zlqq{o_66w^1?%jmYC6&VNzIaLVAq!3o%;zurLtFUJGg>CZFBfqPHM|2(n+`VkQSHs z^<m2<*)jx2$Q3&*#Jy}1T`m(-mA_+cK;WWk#A$t?6;|K*v{1hvhaXe`4^qe|Z#>5t zObS;{JEbM0!Ys%qDFaxfj*HV7x0$$SfOS8O4JJxR5{dY?=ir=(CI%-e>(I=2H6i8~ zR0W#be<UI$ltoR3xWW1n{+W^WY8nvU6-?~DzSKv85T)pX#mH8PlH_%Pdt@o3D_dgO zEOxC;cx>6MHzA&R{*yi{f)f5i6ipjAy0<0>B(YhUGsl}PuaB|<Nu{UHi99;&p&Zk* zkuoKJz^Zv*KexzMIfMo;_!`brtZJ=b%ZQa&nw9YMkDdEY2!a!)i1SlZJfzqnpN626 z_$I1T91d+-@vzA4;0iV^_*3Jax^`b<D2eKPgz26^yqdxD-DB8@`!+zeKU_%W1yVkH zf)w7)GB;A>wdMz`;4n)mo9Xajz`dj{$HpNJO=Fc$jYJprZ~o~z8?Y}u59;B=UTS#H zk=?rG@MKe`J+H}-pmG&eP@y#{euADC)UGO}niUnb;yEy#_*%-Ks8Q!W$`&oj#O3!x zfHdHp(jqgZzdb^`T49tA8Q@pz6pUu@9OJz)%QSz<hFK?zMb$7&@7<=(klQ4P;FTAi zTy+0!cKT&&)11yfgB;{mkw3ewxAw(1&lB}FYMol$aAPQd;v>KL>A(299%fd+N#u}f z=H-pLnXAa8OK5k%UONGlx3d3TktPeu^Nv2J%3)4U&$xWNH7{K={+5x*k-JTfcrQRH z^s=He_Gal1x5NPK(a%?0IHc|MK}Xr({WN$f`L>Nn`*=E$24!QHKo(-Px4)s4!HA<F z54^jGtr07-!fSi2!N7p{^V`Vfm&Ey{=jdhV!sxkS&-!ab64zV+FWLJ=EIP6kKEuB1 z(A;GwX2!KHqVpsPb=k!uN3J!PF$<tg!F%1O%U@#H1QVOUS`%Tq;y=ziP2_qXY(JZo zd+C==p8f?i*a|xKFa75i|AO!2tlGDPI26()`fB4V8=@!7dbV0{7TF<nZ{BE&NvJ5j zYzd^<E9AP(>OqQ(+9=lYxbpN9)ox44agQZPf(+r}*=(s?=P!pJ04|BnRx;8dcFwR1 zgTisL`P}>tHH?SciAJm_PL175zI`v_emdK<`M*N{P+#hHMc$O+GOZ3(<t?A01{O@I zw}9Upr3-GO>z(NyB`T1u2`)*^Z69sQylJz2u{_Us=UvX9FmbklKJ7tt6|+PgZ#iTT z{XA{<q5)cov~bFce3iLt6e<7FUB+_5#QGjP>KmxT`9m5v{if?!a+Zb0p^7@MOzRor zrt4zTGx?!P>#cpqyKgS774J5-EzEq*WoP511d>Bo17V{kVYs&j2iWwt8#h&2I^LS) zwObN>a1Uwxcmfd)orjOq*BRcGgr92J;J3A59uPOTQe=2GhV#vE1!yLuyb2l#|9*e! z#lh(&{idzb!$(vg-d`>l<rh|d0jzE%M`&T09!S+61AMYqml$1kvIAi{FuVX^qiK<R zo7@<#aIBz9uUa@Nw68pJ5xE9a2t+faxg+#!D*<odX}sOw4bYTZI9c)SmYO!Xem95_ z@q-hyb9;YpDe)jWAIh{-v}lW$bOv2JcUQW-a*2-a+n~A__DIrfUB}$hf%T2G<c4<W zDZ<g8GjGv^lvDkr@j=zgp`Q_B%Oh6c+n~${&)*Ft9}tSB6lb>JCnU}I=D_^5gQB1R zKJZv(#j)Z{%J+LJ*WJuJZ{$#h4=WLzO|?zODO${yvD?gZ;p3e=$+>~9K`ObX&5@uf z+pqc>Ym1Q$dde0!o}IsTLh_;?(hcD=3K0oFQD~dLCV4&?(b!wLx*$P^?I>F`$5N<P zp1g$5r{IeK0aONcX3^i4YwQAPAN<&bufLH;ETO%9vIyf)i`vRdH$OQ1evrfN2rjX( z7UwixnQ2-zSKqihe>p?}Yn_&1PpdBFIn*cJ%5jjHL~@dA_8zX-*?xRY-beaPKOm?8 z1r<q@#C)QTSNtbTZ#Y7sMvT}crT*}Cv5yn8Z;?gt^aVAGGv-KhhE*C|<oSI63JxEL z7o<m#cb}dAo~2{Lt29sh6@`#I@v5YD@Wm0`-^D0<$_GbC;8(1UTCP#A?3uPcD<G0r zS^CJ>v_O9}3ea|V{&I5X1{mk{pa^@K9DRPCR-1X}HK)xK_DYZ7f&fAL+SC2Q8R{wj zdP+1edyJ2yuC_y|H7T5H=OfC>Wzk2Gzuakn3p;eyk}IO~59G`E?Gx_e(u_A9FPGk4 zE(+yuXF5sT=%byOX6|27>iV}8N`hgyH3ZJvFU}yhHplxt)HS|@4V(A7-*orFp78ut z0+S!BBIR~XP2N*QG}%VU-O-G*C!QkZnLcvB{zA>|<tPh0Gd?&5ghT5=;~4g?B~hKh znjW~v1}n~FNL*@wr<R_wiXdPwXj7Ns&sL$>gCox8S@a*ORyYH9OJ|5zbCjL>Htr%Z z$IkQ~3Yk3EcFmvB|C|=E0<1*%-1WROZ1$SG8S)GN2bpW)HIacq4RBWNjY|IeNr&1p zaa)m4V3_MUbmaqw-_BhZ%!=7`pLU8j`dYZ%yB6?h*h7<6Wm;87H-WZQK(yCQw&$oS z_~z>=f5G3xY(?$+?M!a5d=k0_vwJSdT(m`z`tIkx_%a>Pn|F|y3CBWZ?g)c^3S_*Y ze7DwpQVMi0nSP5S#QsG)!>^`B?)g#qbufkKxLN!qpckaqGx3FLDLhl)U7I}@^60&* zGs+6}0w!tv@AH4r`{+2UqiFsMYQ0F8_|1hC;q#--zkGWbTf5ynT{XaHM7s3nd$ZNT z#GM_qN2fqh;60TD7Rn0R!+paql@fpV^V>6MWPZ?>M@QJmHo)8)m~;>#5BPpbjT{O7 zAhOs<bJ)AOiK#I;oi1?>q%ggHS1$CN6&WsgBBqbqp(}?ynO%B&)RjEA1J%m~fW}@? z-!=ZcgqgOTN?}5xF3uw^;4D!4Py!m~QFks96WKm)=a8&k?^mkabTn=PyeW|ekyNHE zG)7)7A^(Yo?deK<V={f8I!cNGhSX@EC>k#2V0x7&f=kJ!qDDM!c=_v9{T2zQFT5>C z)&Z;6>*hwTDy|V27yPfweQD)CGOb!LcgkBJTH{)mYI{oSbX_C?-ibS&8R5}>Keb7d z&3fOh+uL#~8cmFN!Zq}%p#uf(9k8S<vC$PEd7O;RnPt3x5cb#2R3|64pzgLt_#F%1 zw@*NUzz#g%5BBN`SN*1QZ_>2>7xA>=(tx)_C5>Jup4wkDWdA+sme-cxGKoQ4*RLNI zopU0efYqZ$xIfBQ_E@OcJkE9ZcCCL8{*NmGMj*}Eo@NFy=KcZ*qu#^|Isjnox5zyA za*1&Q2*0@Eh`?OAug0Lp<%5Gj0rt7i0^ldcX~7ITimNkVVwdBSAm^iTweYCAAXVH< zT>5bfCvB&ogn<n>M@G*|qt|mjT`OYYmHA0a-W$NO3?PlE)|-m5`pB1)V1unT`HM+h z@J3E%+Kyk!qfn8a)Oxq|+KlaFLp>q^_^`oMEfwB#YdD<sog`<99WxXTI_^@eRzWV` zeXk^YE?tsgzx%Ol#;P$R;AM;9uwwfALF0L0?h>5+x2H{phI9m!bIP#SpjMjp(LuI> z;zM?t^Wv^QFbk+11r<*kR63it(PMs8r5m{!jijbpaGD&|?nmm)+TK05WAR*fYJ$ar z2U3IHrfrJL`=-wjQ@_Q;jTwL7kW*>M=z;{)7u$FxYqJ)W$^i~?ULM<Giy{tL2v2(- zC%_iJ`LsVgPzHebX6&JHcY<sX7a@Wh*pAQ1nn|YGBt-(R#N2uD)2oGpFAY51<U_P- zG$B~4%u#IC^4)aF`E-U!lQA`x4ZhhSjuw)wJ*=@h{Y!MM%3k|7!d9Pfj<AXM8P$oH zfQ@+wb6y=$U>((LBB!xkZrhRDQXx9#q-ZTRZ<8R~Vu}!G(u`Lhx0~_|L*Tp!48O;s zDugFSZUoOr1=r?qfw&ZCNyFf$_CKx6?gYc+!Z4%BAS!hVPp_@g$-;(W(-cwv%p<o8 zc<Xn+1P-3+9eo<S9!KgO2@<>yEl))T;GSl7JY%YZam%B*LQj=bg`9}Q{zk+x1r>gi z7X3;s{RDx77x(_q!TX~`-xGM0wx#}%0a@4z0zR}~+N49MOkuUDimB5l`4nCDos!af zc*oQL^xftaV$Cw4WT{T|HCH+fi6`@DjNWOSw=ji0INvM8Yq*KXzzdU~!HVyBIT%)R zxYG3(2mRL~<ZfAR)e94z-C*wxMCl~oCR%KHZIjxiqHu2g7pC$Ms>-~Fjl$c5atePZ z+SJgjnh8@RyfN8>pZGzC_qnBMYEz0uecqO5UB^S{_UWuo-4jRB8bHx$kP)Cx5}En- zyZtt^b2T~kGC^5OHxHw-3(C=ufJ3-mBq)cZF%FjJC?v1Gh))oldADExS`;=8jH|%9 zBiAxHmBo<{cU<(T(!U2?V^N7FK75ij%&9!@v3k~|ZG>~&l`3U}^)&44O9!VS7Zg^` zxnw?B-(>jMmTv56ZUpC4#Q)Yyxe8jT%^_8zRMj@29Rh~Su`I+S!^ylfnq?61W9FO| zIijyeyW>xpgkz@#Znjh4Pj;tjpDdWDrNP?tjiSSio8O@=KYiEvwM>oAFuS#TRHjJ~ zrK#FPnHdXpox+ZWH4Dz%6THjBn}t|;BlK+~LHk)my#?)Jjw}AAw0}c#YSe04h@y1b zN?h)~*H=Ir;y69h9Qm|$Y=avoHcANN(CIes&Hg;y!&i>1A%pfQGILR{G$)@3BnGpw zt(v-d!+%+^^$==>Aq4m>y*BHEFuG#Vj(!X44Vr~b3k+DW5UJonIK(Mnp0MS@2;sKM zJJfU+$Fx@=dPIMJWEYvhql+8uT(62+Sp$dZ>Ft>i2o<QcefPm`a@@_G0z9^hnCO$O zv~FidE$*FdL&?ee&hRjrksRF}<u^OMFSb@|Qrk3)xlEf;<cd>>t--twjCwUN1jJh; zRi(x-eKN%K3lD(Vc=6Y{t}vF^0g$c&uE=5aNt8m<@3fR3HM74LQ%@NX30V)hgdB;N zd*V|3b-CRq48Fc)8T3`SiDmN70b;p?1@7o`tLl4F5d5?<eOh5OQJoyZpk=~+N1J2U zp5lEafjR7^A;V2DJ$7|(VTr&OT!z>?N^|J6AOshP8c8Y8behQJxim;b1%1KKcz--W z#20%~(PW$cT#e%*XHZQj_pwa4rsb~HYPe0!BeMoxUF&u~UD*EqXWi$4@TfAh$mHTr z3kEfMh?P^tv))Ou0-F+sW%g^m;`!FLYKa=ZA+J1bdX<Jh_go-qlX_S!Gm(Yy!7U>m zudSzvd(WpX-Wq>d;;4n0toj&+283F!N4Vo45wr5p-B{*~(W&BwcM&o0vKS$%86x}w zy+()}VHcFv&AITT^{7rEKrvQGR!Uw4{9L#>qEesVAZj8x2iZ|nf2)nt74)A>MLS{; zZ6mk&fo6hONT|kx3%&b9f1lyD#iX5U*L<2Fa2~sd)&wCAUg!!g%^D$kk@WaW;T6+L z<PTf<(WDCg1ExH$kH6*rk{Yk9$b{SJ+dEa}!8MSI1mt1gm9^&6@9ct+%5UUmT=Er) zi?JY>=+fA?>pJfOFsyv-FTX_@;uI`y7%Ikc=8>AIV~8V$EAJ&$0&H8cgRlu}N*tZ! zYrj2J(KUySAo363<7oqRHsQJ84cTAcx(Ee>nae-)#g&0#Q6gO-d>wt_-M&zZC;dU7 zQzQ<Dv!)rUCu&z~N(D}Bmap<{DAMYr6Z0&0`hWt6E4`u(>Kgshpo$N;0dEKzi9|Io z5&~IRg7U#;U4Zo_yxoLCV2UA7i^{>_yhnDPX$n1#eE`RUd;);KY9o(FC270~5KdhK zWqIL9`UJh?m>h+&3sL7HQ6x50g`vTH@`Y!Y?_ryRRLx-u3C(Z={d#NN!f{XK7aD%| zyBBzkZmx5LTy?3`Zq8P%U6folPk}EXD+=`2byrjnxn$iaeR^UeFAZ991ZF5wZjPaa zOX`&FNEACAob@@?L$1>S6)T4RKRA}LtiS6o3P|52av$EhcWoiR!UQc4%ZF7FMGe;4 zyAN3S;#E6_t(w}{@eA`H&=l~7x34w(FaO;yqEr-$0LN@@ni)|E6H+@$lYo??7M?w? zlB-HHE2aYjubol*M2lhU+tg*M{%qOuNzEC}|DywRKqGu4Ea}3c2bQF83ov)Jd!yyo zceX4rGqNwkWpp2}(y2>XNMY<%{rF#(FPZTYBrqBFF{k43yYAp^K{@IV1;ffYYFBm@ zY&w0QppEtX`bc?WS8gAY0fy=vh5<Eu!Pg_lyiY$tXy&bxRW4F2Od_p;-k$FQ@_njg zH%^s>!1E_Fk&9UC7C8H5RcFq^;<4cj$y1|mweRLY$a6ol6MdOUu$u&8t|{5uzn;#X zpiK7^XSx@b!-zI%yn|+kzZq@%rP^x5>cGrsoA}BA<^%<`1&Y0HZflv)66wJ1A-7MU zcwvjV3($=y-LOltl-;CtNc9&^y?yY5lu>7-ab3^p=>>p;!=YO;NBx3ns=`4ln^qzk z<M~4_s~l>PjMFe<ew4V{?K*EhX2Jwk`B3QOw4XOVtbIk}`Y=s1t~)Tjz&%Ff`xIM( z@O{CO)&py{VVzI~MuUX7WB>7US3A#&T)#d?2nN%BzB}XyL`#x8Kw}?W;cjj}{|TB2 z{!~jAWk#3BT6=lWsjnNj4}3w0E9ht4#o;88vk*%rs_WM+s&b5_EdNk|o1DdqXKSDQ zY_lK`_|()#ReQ}JAbS$H#TG?U-HOx|LZJ=i-P`lY!TiMKH1<=q8A@-+Zr$qTVdrvJ z^u-*^+ciJDmIgI#10U}Um*XjS8|q)8%7*>-H4$gk>I<=_m&a<_8jfIDF-kME8nop( zntG0V1=mXrETnW`%{jn<1_wrbR4EkU(g|v6fo^6!7wi4^S#RW4QbK{Z%^CLnt`0F_ zQz#ZJK@TKz-J3I$qGRZ=M7PsENuNZaPrUudrTBXXy?Y@?ak98#1mAXEMfmHh*4-a+ zbbDR3HI0MLp!m?Rja<P@FSTvQ1_~>(pllYqHR8MB`EHje?#2+3=7nD_h1?uZazB&Z zIQX?M>!$TDb04Rbwm!8jbVK<OXRv7gLx_TQSqAf*E6<<rUPyP9oPjloTCAin{4y)1 zNrDD-IU@4sHQBq;`ohoY52z;qihH}Z{t(65UjfI(B(+ildoSx-$A#)tB0Dw!^2?zc zT199+gAO+GWByJ6j$;8Q6lWV>&U0(7WAh?vp)1rrA|f<y510m3I(OOtji7jmCHZby z3e_S-6wrWH!FcOcN1#Upi`d%~ntb{~Y*2<c6U5J&+eVls(K<}`?}=rB%2fhwz9Oo( zO1^p~H%CTFT7%L8ItFFwmd6`kmdG81{`&&G4BRd<%7*ebz4bTuf77<(TRxRku$q=< zR!Z??LNxe0J&d)zN9F^#SBg9Vda{pjJzJ+H#ibuBZf8N?;F50f<APXUieuxYj9U2a z4e9%`4tYAt<iqC)^JuEQb=cp;$WrTeZP+ESyI(oQD)w98$`}-;slc6Z;$vLA@3ofT z(kn=>oW2pwbtJ;u!`}|dH3SjSsvt$xX%$=4U2}D-6|ucYYa8?DuqFW7ATqcw6b-A% z5q0l*Tte7u%k;rJ`Z=N{>m+p<Wia>fq*eu_#eE!O>ngTr-4T84>HZ<*x%zt70O3GX z6G1*mFD90qN$}cD;rq!r7dpX1lQ`&dEDLOx@`@SugY4cq-Sgw`eoYaDVKw5&S2DPU zl0_<W7pED>;Zd7#d1f!U?Dee2KA6!y6ltJP8=Hp-Y)r>V)7J88YqU65-{@eKu@j~x zEloLR<_O+xZVC5B|Lp}kbkTDne?$h8y0p74PbVZ=LY;fO-WxT?J<lRo0#py@ZF}Wp zNOgj|wsmd7v%i>WveE<K<csMVRg%3_D}TiyFwkXwL`iFr4+0*{ceFN$Vc_M`BW0&m z;I_7i$<tP&Ur>oa!&XbmEZ4hZW~Qfbh?anTA&~ro@g~k3chpq73zzD{jA!7XkLtbb zVHdEPNM?y&!aN=7yl2x)Qwv#1P_`m5x^=0PL;sf4f*1$YoeBrx(W!R^?aGC80Lp-| zbP$SUwyH11ErrIm%Qv}<wOJmThB>qdpkV&Bj21W|GI8l{@uydhDRPq~o@2}Q{<Yq{ zbS6UN91#D(3(;<WOD<H;1Z^OEj$?6EvtJl%r7-tBDNzknZb7ZDEJ>Hdr*8#_+)EWB z%Dl@089&a)7PQ?pclGxH6s7U5tUlXCXM*;!kfn1{*9z6%-t4)l?T|Xbh^oEsUf|8Q z`PNaB_O%y;$Ag{JUoc(mU8pSi^$@~S>plOWI+o6GtKfStRAm_?9~W~{%WS1ujzKic zZ_Gm|b-s)H$G{^jfL=5$dNY@OfT6v4KJ~=n#$R$*u9z}_Dp%BJl32G=nbu5UDp<`4 z#PvgvH^j{^rh;8w*=VIW;N_FSfvoe@rCEIfSqZs%0I064*E-OO5;Umq?%6oNA2Q4~ zV7h=}h~R=C>Sj?*WBIbh7>L{895E)dD;99^H2TbP|8Z^erBz6MKn5rHoQSR#s*WO8 z6&)_<@{hLAo61CeU_j&xFKF$+cZ5R5hY83<<qq6axQdE2tV%TI$Au6~lvh=of-)@* zHKE47i>Q|R$qz!gu$ax|toE+dBvXS6aUnJk)#2sr2GRWTNy)-_z*oo}xDR}OzWJ!1 zu@=G}(am{LQx}&fUnBopFQxi?ohXz$FXp*HG_YD+!J)PTVof_TaZ~_S?|;%a-eTLP ziw~qFmU;ga`JtGmx#RK4AXL10VZTj%?2~s7F3J|zADK>VY0m}IlxU<s480e<DY42Z zqMRc{<Pt<2)rM9j%xAu^fN25(<7a~x`>juHkI4a2q8Nf$08u^Fv5|pg;s`=-=VEPS zX;%}^SgM9$ev8t1;2NJ$b5^(=<agr=A;ZwrLiix%-6O~zLicxm?bPL{JbV*{n+w`U zF6v8dit9N6G7I$yz#QkH<F0#5?z?o3u2nW#dYS2Jk-w#`e8JCTpiYB~#3lH$>$Mgn zlSDlhWbWE-rg^ibOi<(x@9W>Za7{A)h`hafcYk=^(+%^S5r8}(b;Hidf~5*~H~Y=N z>JQ+@&>v>yh6U~cM)&|7kZ&39yhTc^gL3rYRFMx0`ErtsvzShpmy}NwW<TOPr~K|0 zNP6Id5j<<)Wxb1t>6)(^!-3K{;`sA{xu{&J$6E>>kW?S+#OK|+f>u$XdU6sLBk3A9 z;eI9-$J$^P4&~kPhIO2>`O}{kZ%95I({@jDOxw!=V?hXTpvc6u!|z)X{op^fF0wEM zyxfXBxjzp9*w^LjxLIC%@vvCd+zTBW^@Z@u!oXoHfT1Xhi#a*^d|lr|;iXg4Zq#~) z9)jTY&BH$Vs(R<I;DVYPd+OrqB&bT&5tYU>rOY-GnM2q})4Df=1ccY$YJRZb+46&# znrzh?LkAPSO$I?enKe2|?!O3zJ1lErmeVHp!54Utd`b$If(12J#ON`1kAD>%BBD-E zHUrzpiM9`jN_D*I9KA$(8q^IH=?N+i;C}Au%KKN0y)s<^D^jH%%Meq<@*&vc_zMj^ z$7!TVFb_GVqvf+{22DI<Ed&&t`Y;cxWv^v{d^Wa8uQV%j$ny-MWNL5po2qFOEZcbY zA;@%^j!;=^rN?@t^oIt#=gMfx)AM(26A&W>scm1vI_12B8!F7RifMJ$%5vYpuSZ5| z!{AZLhky6mxQAD4V{_u-8{@suLIpan``=U6*<tmpo}1QJSOFYlwV1ilc6-j?2{pH~ zH+^s*@N0G0UeG|^%fxFiPHP9fSY}C7^mmzE&*r%oe&bWjkg6q(_b5B2b-2tA((fI_ zX2#q2mB6Jk0t@+~i0(u5z5`DAOn@f%_t+N{#3uw=RmISVh*tT721U~rTfu?DVp<qQ z#CkmWo!<P@4<GE}5hRHs`$mN3_SEh(I?suTFR=xn3!i6rui0La_s`oEMztI8MLrY( z9_~Tc=h-xD{e0=MWGtd|VY^;XQaY`Pp4vp1pcTYKTIHL3kG=VzFr6+rCEB!_u)pTM zKkOz!tYVLR83z?S^joTI-Jyr3DzooIKTCpCHEW5+TQE3WllEI#iekXJ?6Xwl5X0S+ z?OxZ~sK=U2(W$Z~n0(AEKplbED99yn$<Nn5_~<OKR!6Xr9s)cCliph}TmPU-caU7= z-2XH!YG{ePiiX7GpA5%{r@(x0tBSlBi6!}-QfvPDuTuRUR6z{9Q@)s>H9<eLulfiO za!{J*<tIzq)vwcpXQ%$6A4?M`E8$ONIlOGGSm66P?J_EtZVUQ6d7RxP!Gxs>A_ljT z`a<`eKd@Um^B}ct#>r;Rvc-z{>jKHWp|6|&w9`V706YFZqI1dDx2}nJIC-MvZ}{C$ zHK@vWl$WO)?-xBo89(^POD3s$a^SwEC#*2Wog=V<FVd!${hg?`bpTsi&B;p>y<_Nx zF6k;rXG@?n$f*%bA;URHw%K!B1HntH%Zs$miRPZi%am5q9AHqlmFd6*Y3^Bq2J*rc zJuLv8EH&oydqvs8yy1{>DD7_H=r(Nq+P`f1s=vkduQy*Y2}7Lp(4Z@73vqDMKes_J z)&)Y6W_@V?7O=AOMN+sjDuSwA<_MCQt+^}Lzn44Q{j{><cHU{6F9KmFk`f4pQ(<ee zL89@jTxn#rENr~4b<BUP>ABc7QKVz2rwYn$-ynT|DELY$(~m<ne{Pw(#G?2%+pKU% z`%HZT**vKY`!c(o=f-24%>WjGo$~EjY2^p)<GWdqUFN$`-t@r{#|V5M?e92kiw(_^ zCC`zxDxTfL$i!=w2K{qZb;hZa$>!lmeHt%0);XgxyG*MW`s9xfe`>nbz3|S9LsH~` zOQraK=@04Nd|3Z^>R%b8BDVPgHlQmG$ru>1uY>BX?`(YtK5h+eBbs*>(5DJpK3B*# z^`x6|LDq<$W++c9|Bn_h*L0cJyANK7lAN;sLKS^;{|5i?Nw(jTkMr?c9nn*Lx%Gi9 zM(<$>Krf}%@BlC!2ZVEZt#y$J9tW>HK*!-;nf2x2w$+%bepj<R&3{5Q(`Xl4n%JQ} zcO4>7YXS7M*3@TfUEwR`?{B;PNwv#UBB&~hc@|>?rj#&8R9t%m`KDT5TPh+H)|FY^ zL9n{b6}lmr-f0=oS5l*<e3{h}96r#Z*qmZM7yc}?7i+lg(YWA=Bz5uJ*O7ZGx)WB% zLE&i7{HZKH$ZFFjsodg(!g-Lc;E5MizQh7>7Nb5@_M9>@G;Zog)7;<Ie0{N8eoo_G zrpT3yM`&d5=;p+-&Jm7N|DnJZ#SQ(t)aM@<b5#93e}|q=?b`eEV6Yl~_yBSAgwGhp zK=%@KZLSv5LZge&^4f{$1UBhs38(v?-=zHN(MaD`{7&bjGwXHlAG@qfm)25I8F!%Q z7I5(O9qE7i+2~CsLF4%)u_Xen0_6@RsW;!;tE%z=BRJ&<ni1F38v0$wOI_d6>&3`} zBRjf>^VVLmZ|f<MEL|pYfj@iS;;~13*U_)S{mf_d4txo^rYZE)+v=b5T)V_^@#tc4 z(HDobo!>|3>yV|@NoG(RTgmwbC&jmsFLGaKkrib@W)Tfd)1k=C|MAXyADcVBN;s{C z_k4$CS}%r7?<*W~d3m~2w?qfxfUAk*Er?!JaR0|!zBBl9WB&ATskT_lQKr4b)HeCC z^eLYi?*we=W%R`Fl7eJy{{6<Qx3~ODThx?n_U=PUo6!qBF=1Ffv`fB9cIbUVxP(=& z?>Q^KIPa$qNv%3wib&HpTs_ETx&oNS`TZ?voE#CnMVbAVH&$Gbh#Jk2m3(aKb+dHZ z9Hc*>cUv{HzE+n$if?C1mD!uHbJp_K=n{8OyAK>FtIrvnve5s2(XHsv$;vzb#PoCf ze}g>!^3uKf?v>Gg2FE|c|N5`!68TQS?|#GP@X6ewH?VQ~qjM%r_d`b=xd-d}sJhf0 ztL?P6s~oK=W4X)b9DR>je#$4ve>`J;98E7Oqzz_p*}WvjfA>bk^}AocK@r{tm-!=& ztkE7eFO!eXD7^(=_87JTv?R&FLrlij=wO{1FH;Z&(fpcNv_H?AmE7;?cSAaYW_~2U z`VmN*`Fde==Yj{SZB_bBp>K7Vw=Zv@6npgW<H?<auEd&0==O=$^d{VUSl4S(E~L*& z;DC5XwM}3yY{K_Pw?ucZG(T?mSabWGf1T9S>Z2$?9?jBUoA*<|GPSw?k-`8?`+muj zYK#d#+jBXX0XgBb<jW3xTpreobZc=?j@}%JKJ@r~^?5Fzfu8MU@(LjuPg$(Izwd#p zj=A#+q|P{Hc4*l_VnLW%z99D|w~5<S97|9*{=+k7R{)=Xrsr~q?VCrNDBFUmCaBp< z!_DCb(WH6_)DJJN@A;qpTJ%rS!+A%(@f>pwY~)~a1#Hx;)PL~+?&`VkN3E4yclnBr zp0NMApMUfpsVe5eoR$Go8_R|j@XGDG*36e~3>pag?H#2^UKU5c#gO+~iy9o(bK75d zl?{?U@OM8`q4~iDxz{zazB83o$v?ISW&h7#yr=B9dw$k5huF;B(`RN{<qZ@aUK>x+ zKu613TRHqB?MUr%Wk&BDm_VcwbmbRbiGFaQ)PL|mIrxJur^dTayi(=};ti1#-QMc) z%P@xA`FFZoW3(9I*i<(bUJXB}?>XTp=sX8J2)V(R&JvaOa>Dzgbih5ugx?crl{JKs z$5&RnCwRiF)()+19NpkNQj$kX&xF#mcre({)rM4D^E|-;cw=v_uG4@2Jo!NKHt#;s z-+nuN64#AZ)9^71E;muV-hM6F`jEbeT)gn|ukKeolix7Lo%>a#iffYga&by7+I4M4 z(Ea8I_GNM1-{q4Wc&GDy5550&_r5ancR!tZxNff%UO82pXnU@lI{YB*fu<!|(O9D~ ztc`x_b@wFC%f_zdciz}O&OP9*DFn9l8|919&umpqNS;ysO~d)R|9xQo!ZIoEn)Qd2 zWjT)hJ^QgWzMmVD0nb<^rqP*eg<-;qZ})G8H#J?9HO=`cZ!s?i3f8H~`I|kjRVSCZ z9bp^V38$17a^ow?Pc=_#F~AtJZ2`tD+h(j402Vt$Jdw=sg~quj0r1^4SRfPZkgHAt z3;Mjd6CbJTAD5qxeCxB!JHv|T4zHUP92X+HnVLja`s!`<*n_facvMfYSwk5X!J6Yi zn8!%5m|t;~`}PE0j$_qT`D?mN)R*QSd-P(~RCf34onMq0$9iP<L<32B@%Ql$q+4!I zm+sHwhLvR8UuUZfTAQJ1FXj{dZ=5Y{N<J8#pQLF+Lb0Jjv>l=*%!&|(cLPM-R2qKj zQ0A?o(|0|`8@fNW#YwdVo$5!u%)R92uzk~<`?6?)K6moK2(zuQF(b7q=mOK9I!-IM zBC(Y^t59!#ZqHF#dS%pHc6x%k$F6RQ>$v3BH0ORD_KN=BrBB5i**d=AtxV4AUidmn zUsxBG|E)74d{%moJneVC*_%Y2sk7(43d+tDh5@JYjklvugO$|(@~v?FeOOuQjvD9* z>mIwzL9FZ>xA7HLjl;@+x32wh`#*nnPdAS&i<i*DY^0@6OBUly2mowOxK3o7DRUBU zm8SK-8I*Hpd&;?3XF+G2Wk%vH<EOH=UHy+c(3<2T_bXyGld|1qKy?7OILDHt$*`ZM zLSqUZ{XyMK)5pg>z)pf<p7MGemHVe1`Db?@y%Prm{m0>bx&%}#EZ5%mjC~NnGTU7G zRSY51+|m3mv$I;z{LQtM_w6?v{;>la<0iC;6b<u0zzla{?;OF55s8^k%h$qb@lsLY z2S=jQmQItJ<w;m;lzZ#8!43jtUq>SIspECP<=8({IzK$(;&CWlxPr3gkJ$n$KMG%F z66NDK$YKCy@(ETFkN>Zi61=C_0_qc-bGsoxJ*qmDnW^tq?q-s}=?07syf;7k-&V6H zPA*1$G48wWVT#n{SG&tZ0<3s$$)aR)SDU6Mc38m0l+vMwN~a#qh!U<gN8zQ^sGEEu zI+gmK^DWKa)ZenbFrJAH$9}F~VeE=i_K1oS0PP9`<4n)YyLCUq6@ParN;#fToDEfo zs~OX8cX8^)sM5c>|8dpz<^98eGyqbyWhhB51w<mL9w^+~lQcP=#E0429(>gA&;0gh zAOAcTVAQ0c&k9w;4p!riooQUsy|~u^>F2-Rfuccnq|W|LJ5;Kf99Y<x{SVjk6>jAu zohC<-U{U)}O`MA#?vX7Ta8_V3!Xx>CxwfYA%BfM^E7h-lxGMFzj$U{`tO$4`zljZr zl9EpaTJ7F<yT;t4y)`zX?+}!Ql;v_O|A3)-J0G#XC?>c*L(y{3$$W4@sn_-5j!01E zSSb>$5j{_7{<3cP6~T7;{Nog;1Q}(e=O!eRO!{OsVw~eVOGDA)mfoJs(S;a-9rswD z(>G~&lwqTW4H|I3t(@W-v_{zIgSQHeybxx<<6)87ccsR3jlR3d^Zu<xcIVh|g;li% zla!aQHCz)dzB!hL_NP*v*6!7U;bqmgUSl<Cya&>w|90|zvUk|`Hvut3W1z>vSR8?d zTJK-Oc=VA&5V%Ns`f7|N!5Nmp1!u3?AO+k^XgOS_lwaSwIr$&I?eN-^&#YbNIiXtD zV0;q=sns1LT;6lnuKB!v`I!|}2W*%l!`fltSY~F<0^DD0)1yjmn;evW>XYK`4CY~i zB@CLytEl)|b<!-$<oxh(h<z8Un{xHzehOF8h5MHSx?7d+n%61T&v!z3L*tL|^j=9% zKt3iL{fSE4-gK4e)TfzuF8>#j!R%8?zRrElG<j6t@Ue?A)KmAneI7I<CI|f-4o}Tu zZr2HAd{n1;IOac-VNzux+Xg%RR}%V-19}287NA{;ZF7^C{^u8c$gBsNf4>i>u-?-7 z;*fgYjTkp@Azk{<M^%XQZb^S~_5a<kS5I8d(D{p{2_ETuQi@T5{PYMy#xoKGEj)jy z_g2o&e7!WiuLhe0LP<pDU3uIrI=>H&eZHL5p-Xu!I#uK5DMpRjrF`LN^ds}t@aGNe zfQ8J6jq7RVwZLr?ZdR39e|$}_J7B8U7?gwl9d~Hh(l<$|R)*`Jt}ml8gC<4Ow(tji zM_#1aYMK!iK;L}adHGjwJ>OB97%jih1%s+`Xyq-=i~gr~do3dl$t$~wYX{r`#NIx? zA_{V2al!c0kUb3#ex?16mAh~=;RALj-hYrB)1h9EX1epwwB1r8KgzhgE<AYMjV^OX zIE9Km=<3@pCgTq2IvFro`R@;qF^C6?G{qrxTsSDOK##KwmMoo|(xLu!aYc*G4THYg zZJHE#d55UF)t@;<N>O`hK=PsvSPU<<9MT3_038Ohl+RQ0?iIr{n@sDTnCrZidEcb> ztdY##!nxW9HBn}7)Gox_c&miDDUoBMJm&u^dB<JaT?hq?lOVkhr)oWRqPFgwhQ3VC ztN9?${D-&-W79b+Z@zp#esl7xR|>qgtpm#%z1_C-h-6K_#Af>jdDyYpw2Rc>EF4pv z+t(iU{G;PD2OR0Yp2E%x`W)zQ2|#tCN)GQBdr8n<`##epd{HKI1Zhv)40CQJAn5PB z$RoMG?JlJ0=$u&KOro!O^@A_Y9gDvAa9cC*`YyBQgJVG**&A{1$vhWY<V|o#Zkkhe z=f{uWGtc^%x?WVA#uMRm+5TC6{JuM@p<8oj1lYE!Ci*11pouOcSpSmw@t#2)W7sKW zUzxa^NEQF~W<$-<f6>be+iwVn&UXJ8p?@TG(*0*62JgsRddcImWxja|hDevW83HIZ zXro!4wx>&5wC0@haStvH%Fg$;C_N)J11<95S!Vf~;Hkjj_k1y1id{7ju1H~29J0FP zIC>{+I!R+~A2p-!gW!_$)br51|0^C7t2=5$*ZLnW{iysYdLZdY3Kj_PaE2NZRgzya z2*SQJps`1}%h>o{&;IGH@7o+*W$<=`+HR$3PKbepnxT^@fzU%f{A2#f+-LszrTl;Y zJPI^+oX?__$({2&^}SEe(nCbZ5RKkzNu2zy=E(nUp337W;Wrz^DJ(pKr%5Y?o6J7n zETfq(w<VG|<`+SuHMIk5<XDmviDRVR0?d!!f0sKO<Jt6R1UvPATP#yiqE(}jzE;^8 zEn>E)%-t8haUA%xDB+0l_SpT>@sk}fUyNm7r9pW;8kr&hF>Rbf1?JnqTY9Cgtp7?K zLYKG1WO#Xmu%#e|Hkw_|(Hqm1!5ZwAz4jdUapGz<J@VX`n?$1G>ZyynrfiZ2-Th5_ zN;9~74Jo=e8B~DbA&$Haw@W|2RqV8N$VSRa!3HE*!6(bgW;DBEA|-;#RJG`SwZpm+ z-4o6)BIuxbE5bhB&g8<;?d+9(nPpcrCy~}oza@<&FUwzOJ`?a%`gEfBXFdINL7ei^ zwZkrwkQ#xhoSWLa$BG-<M$rlakKn_-J!3Z1wS5%Q9ew&0PX62}nfEzJ)yLIgNkQ^7 z=O~Fkei6+u+!t0wcMmmt%4DfI|3luJ=m4a!i^QQPEH1`X?0C6t{rr#W|AdZP)#1OX zl*x&%zq}W3rHHt}mNfYAr1r*W_p4`S%s0xz>w-_>RTbCkIqge6=rlK@X3LVZ@^*T@ z4i2i#xRv3WbB&b-q|*M|3n|u!+=kmv50LhE*ywV|YVL9?xm)pyLG}HH95iX}*9Yi@ zOU8s5eFW2${$iBDLmLq4q)}ccl~08BC8i=8&zpL|3Cb*I=QZY!HZHY)XWgGX##B>b zJR^_K6&b0#rEuy~Ftyypg+Uun4L%*)E2DeRxd5php4Y~J$pc8o8fz%)aC%|~VrU&w zL3{8fUG5Rp$L^fv6Loj=46x6p+~}HnT%-scQ8y*m0Q^=*cZ&%qo^ev0WUcuRY94Rl zQb{R}3-)RCblIzP)bV;?l(xfTUODSRV~X`P?9crVe4lC!I&+uj3+VIXN3C5x{wzZ# zJY(wr^t!^NeNgmzx^Body9Hd0RK(2G$w>}7qjYKh`TW33)~6w6>82wLD&~!LksD-r z>&~^@e7G)rWbDDyiX`col0m9ms??MIVkL$Uq@)Kzn1e0A=MU5$6SY50?LhUz>&(Xg z6xfl-B@Ff&5_@HotkJqph{n$t8m>p096?)y@}oSf2I$?!r`Cm5`3qy!$~?Z-p3iUf zYhQ3Qea5<n=4Y{>T(MdARHh>SG=10f68j%7ioWMXx+qOr&+~(jo2~ypb3jR~-O{PM z|Go;*OY>~5ihz&Ke6HU8dN+<R>yL?mK52-c?Oc&+LY<q~#%;H}M1k_@%{1OQ;w9Mr z2fkTzuC@Ktl;qcoGi@D$>RB^oI*lX1o_>eRK2{rBZxq#WbbrIYbd=WC_#YDF1PVO} zx$X-<o9y)@&awI+-tgwT&o0`o@r<=TZ%t7+yZ_yzA15z99fV_J$ld|#x_%x2^fusL zX$gP*_qkGs)w5~Qb4yN>*v5PK_<iZ2VC8%|epz%s?zwVSatP{<7DBy#xptZG{7#?V zUO*U=N|>9bo?19dVeXg!HFUSh;2<l8n(+U&7k9~^!#Q+GvF9R&&wgy!C9vQU!Y9_+ zwEEKT#Rdsu4~|~II`=rDSQ19~q_8>KY()~nuEVq;EFQsHeq3`D3I*#DN|f9<L38sD zOqwOXmWevJi5kVw<>u`n=S4%94DTTd0W*O*MnJI(8|l{a(X{!|iuh<Dcp`Fr8TWT< zZTPN|&GIt#rDN?pnT@=dKhXEB6};*4h*YJ=GFN2n)q<+(n;hAgKUJuI*udq}@A@$n zi>|Neh4WoELW}T&2CVH+ZCQr<5<?`(iNy4bp|g9fF=P^{#?aZM+Bl5Knw2NUTU54> zDkEg`$T;dEg`kyD+M@Wc3H94>-f`=iGDi`sB-A%*&SUl>c$_)pm_jk#xrl-k{RjI~ zZq&jV@<CG9M)+|X!yu-JuCo{|A=Os8$#D5h5rRw`*(7sFaz{L_3IC(>?#l(FCj)qP z+-CFk{v3%)!Lg3<LFzQwBm7oyxr}5JC9<!}Z9eI^7gt-xEj5^U{*C!cQ4@97;^+sd zSt2eP5Y`?MT7uFocm^XV@-at}=Ae7G?Ve7P1j!*b`{{ZoH-0aP-%j$4WG-jSB-|8b z_DiTD8*xt9LbtfLH(^H~!~q(HNx)6m1o?+G`-c_(?zL#x=#cBk-*xH>EG*GTHSnv@ zVo>3W`BzqtbI0TKL%|h5sII5<B=hSxuw&?zVO0!(0?+9!8oOUtH>6Psqh-<s)#Exd zyVvITL=}GzBTKxft|RdG(UuXRK><A!sur%F8IX9b?njVIfU8*Eej<mo`|_6qTS#F; zRUJOoD+ZReI^RpmHJ9v^_(I&+>8v}$y?&uI5?|%byJMOb7{`@oa?Oh&{#@#B6<&GB zgapB+ZvN&}F>_Ch*L^a<KTSGHO>Grpy10%~J$L8-2<6E}O;T@B4B!EuxV#*QdkN`2 zJle=Zr8t|2X-M})ga1vT7res0gu@oXp3pci<{&Gk5kS*IEO;nJH$syK000XrrI>Eo z6TJC_Woa`ZkFPL?#d!Yi)EuVtp`U>W5611Pv*dWGj!;W?hSD?ReI7yq`a1K?1K&!6 zMrJe~q>Bzelawy-z~S5N?ZF2qu6VksF)V2UXhovMsz~ZDdV=i!DCz7~wTs<ziKEl= z#p29_wrfoqu~wn6O84ieej$)8VMUH<KtPRGxyTo{#*5;KGlkZ)_~Vv>@r`TF87s^< z55s{I>q09wJY(MNa}6EhnZB2anF8`bv8xO-zFD~rf+xQ1@TyCLHMN%zFe5M(Q=v9- ztqT>gf(DnazqQ9>6fRAvG}HD!(K=VSggHDHVy=@BljE`a=TU--87sR}qxw_DaEHy> z*Tk?k2C#@R<E={}%lH&|WA075mA;M;uvkIp)zscEAP8l8Eu#!yzDV*{WGk>Bj}}l1 z>mWwybr;e;&f{WG{1HO<<c7Sgr-X~@3iyBaT|!SJI3`rJf>-t=ChATAM3_8WGU*o5 z{>h)e!;m(}G2hZc4mDbxLFu}I9P_9mSl@s_<iVaJ1tlMAE?<87i;Ku>>T`yQ^7!3{ z)>ow*CoIZ~5lPt!L@n%F`M}05cB3zVf-4gXYeL`o-&yhga~gjkMCMsdkW=``hd9ot zI729Uoq>7hi5y9AagaAvz1$b6HnJbX7De_PLK-g*>U2I2g*S|MyNDy|bI!g#l?p}) z#VWI~^I<)(e!51Gk)zFFCpxMGW>-g>*V<)1Js)Z&m7bXLy%nM4xAWuRf5Q`wfph2m zkC{@8R*8F$dZS&aQ-vl(wVl*Co@Ix{ig#jOYqT#q&NnJqqq9bd44VW=5IrxK4bzY4 zZ_x-+nXf&PE0yfV2ut|c?=Nui&Y4L9L())9|7ZZDK!{vTqt3ziQAzH3Jfmt|ps>E( z7RYjCt|T}lLo?)<t@HwUVa$dT?5$X;l$H^VFZPCe%rjt>ab;rQ(uXvM+9=58%P_jd z{Vi<LYO!4sbIKUP_c)~-D;?rHps2<h0~J+J0E1x5>q*fmD)^~PH?OFou<7x>DpMa` zh2Wl4g{Hxn7g!V7L)kpJoqiWG0B;C~z6uQkWF~l?cN@o~O=%YD#U?{;v<q&u*(SgT zURGG3>($HcAzd9rGrUP+hE0IIhH(v#tR?@o|HCWZhQkc2n@sf_1Zq0tkG9b7NagtP zJ#`oNvVfvn1akgDYzbHF!ivYRIv*#zx0?mxz`TnMu%CT#<7#1pw}RzPM*{(W4#v*{ z#Tg?;Vx=#0{fDw+zjKIbx~w0^Q@63&)Ai#$Ke8c2&Yap-Kn>f%xr&LYenL(ngnP_S z30qF9P~GeqG#<tvmQDu9tgxIYeumCRcg9s=Yn4NFQYa(bQsutUjX|Xe#v{+*hB(yT zyT_(af-V5}7STMzi^dcRhP4PZm&+EYyBP^c@ruQ00c(p?mEVy@VGq^cdtf@0kq~br z{aY@%zL=n~9qkqd)e(M$P|t|zGLa7~h~6nx67LpXK4%8L<V_1`7nbLVG3-PDC=!S) z59u%$gA_x*-Sfqq`jKh=jM{(<^I-Bw6igOK?5<~b@z{HNClX2JL*|gjzbZY>x<tiS zIzbnX^rW<Ie!O)UvOT<vIpA9_Bf<~?2G*~>p#b$Nd-<}3fY=Z*x9gKUHiaP7M+#D* z_eJszX5Vm?7!5_^uENwy;q=Bg26bGP+VG6cje3$wTaL!~LWpA4<Y8!Khcf|3`En`b zI^waCP(x}AQ0lg&_f?nn*r&cS>J0%?Mml&HWBAwqqNZXlU}U;1a+wCly)x14Uh{@g zI6TRMp;~a7Zs2KZJLs6Y5hDsuX^CtESHXQ<2+0Ho7DlIq_wjUxQ@%*TQZ9xEJ$i=K z>n-^Zx*MuzRy;YZCS(PyO{7)mhIlKzv(?Xu!<{_m|8Fya_^W*}KB#?EeYPe;C=E$W z+vK&onUTq&F_#ef%7%^pbm=5j@own&>eLk-E~Iz*5JsacAiHOMGHHzsE8AVpQ6+0q z?@R`1K$$?F)NS@2`0~@aec+%1_&8u&sP?@?(P|XuX(Yc(G!gOQd~Q^L&=5kM*zXG5 z`P0-eEZ#6D6p38fy~#tEYH?m<{h0I>h^FZ#(KxLGj;5z#5p#EZsd}@*H1F|U{ap{l zezc31fs6I(UYp^^5=HIe9GI);;WA9yi9E1PwzEy~V#F5Q%;|uwQk37oG6D2F{8Rdj z#aNSa9yf>+S&3V>`8el}9g?5@b7c!>s7L@0m#682KVdE={nth?e&Ir*H$kr#q(Zl~ zEjf4PBKD=ADHuT*w=Bg{vq6MkQpg>TuT%N5Wv<JBM;LN$0-nhn%6W%NXbAcX&*9x# zLBfb33ZC5exc(4)D#3zUgZ329H4?<AfL#uT(TnkSgM}<Q<8)(LsW%dcnZ@^7zdyNB zmv-1d#3tl)l9(TAU?_{^Eh3fLniwO72jybW*i8DYp>|?lHCCRwr5(IKqgGHJm_l?+ z_V&My@}7<8{^u?qmDeE3Z_F_79>L()MqSaxic4+V@=5w6b&f_1M_O;ldfjcD5GF^O zuz%-NoJ*9667oJr9r1CGAOtg1E9!4bMSsrW>FheunK1W=F`{h}d>2TCgk@Uyqp+KF z4&?9=X@BQ-J;{W3Ej1MOSAK>M4KHb0%>=8lBgMN=bpYeRe~z~}%chAPAQ<t#cDU9e z5n<ibgL|QOM6YGjaL%~0bfSyx{?SZ`O`0|U_A<+o<(A9TrSrn(wFUYq(SrormqIX( z_+ix~^vYyib#ow@pAb&aA`hcwvdO3Nq1%XO?X3Y~+7KKd-H7x_!n2=DMCdA~Ra)$) z-6wpxg<a06v}t=m^zsh|3KjlU;Zf83w{ygcM<M3e^Fn$%Rk}by&&hJBkJHcFYSJT0 zYOhqqD)>mES(04lV(1&|0B-|mDg^%#KA{}3&9}dR4C6^BIMJ2Js5Dp8_f8F>NU-zJ zq)|T&M`=p?iu=L3I$cM!JYO}5J%^vAXgTYcX{yZm5m|&&Qz{q15Elg$gYQKOv*jl? zow*$T77{T&E^lORazdF(EG1X-uy7V|uqIrCC^cthW>+TJ9rRR6otb@Z@kQx(bOA8q zIdi=Qyee2xoMRIURSu4laTQ{V!51gTrrNpu@t(R#4OAj^lmY2tLT0Z3>5m4IIh&^M z*oHsS?KRqIPGT3KlJ$x4ekHMs`jQaA0X*Wd%_(^z!#K|gT)qcJIA^6VF-sK9B8><^ zyUjO=uRQxvlVNR%f81>@d+j+bv~u1*g&;4BqE5+7XMlP$`q>o&Sl7}B!9SxE1+lsN zxWC9sy@ySCye!Csd`51Rpw?FNvS9wsQJG5}1Y-#K<H~nDQEs&Iut)XbQ$(DtKz}6| zgL=`Tq+_bcS|s-v0-fU2;xp=xdoK8;q0H4>g}LubGBHQv>Tv<_DL+oUnTLX<tUYk2 za>8V`%QnXO<u4W>(-F^w@QY*%h$eZlW-)h0EReC{-@;S~fb=jag@?8+)HGv}7+ENc z)pxG*9GBskVNB=A0{mww*1h*fw#$_mOVC7!oS(Yc8vH%ys@em;ioKa}sXvE4vUPU7 zm|!4y81dWywY?8X`yW$)X$v=Vrnd+-?j@aAlQ*RjFg&fmQZ@E`zn28WK9(fU0)Qg> z*UhK)KfI6eO(tm%A!V)A-St}kGMZgDS~F+>6A17H(P0%d^s%E1a9yjZ`(W$v$t`Lo zz`)P<V74aSYif?F(k1)E7K9A5#IkD*-G*aPn`rUW=tdcMN#JP_jcc|n2SMQg5!Dy= zM~$%Ud$+50@>;~)PJ#4PO83Ca=+gNP3!Ar=px0*R_ydS;{|`^Zd@?;x$R`<MD>ire zt3v<VE0<Ml1nkf-)94Sk<a?8S6IjOFV<#dr<>)3#P%|P0kLI`x8}T@T3$TIpq9FF^ z74YB|$Gs>6Xdg@?6p;;p+LJ8?6qx#km(y$nhJ(BHT7Q=uRhrEd9P)73lKTtFdgF4( z?kBI<UDiwBld$}%J*7tsN}t$vYu5gSf9nQ{GKxG6C&-<wVMAkyAc$Y9=KP}ob#VZ@ z%=f9*kZ;q>A+v9+e7nhCn5uPN3>AOlWl6U~%iTuL(d)^y6`;3dyWmA2&hwgxU`0N= z>MyL7F`f$|?H9{ZoR5sCjleYjIPr4vumDCm5qe1L#sA(29iuph%P~0-8}~pWQz?<{ zk|QR*u#LWoF!n@v)3_@aS{fii10Xq;+YBJGt&N=ghJj-mnmld6?77hMp*6%d{$jRc z$PEH-QGJMit0*#jsrddvmJeH#0Yl7=_)@s1jEOJE1~CB;BR~88ESJj~<0{tTCMO~X z-HCGdmf_oaIrQp;GV;q@POq;4L4NmB>}+&w9YQ|EpERD-L#e}b@|UqqZ{AO!n8Sa} zb7J)NZhV4c-l3BA)<!O`h)MW$AxdACwJR310ZA*#Ld!0xW%QSsT~(kC?yjiPv$U6v U-C!>eQh7F$f2^CM{QcVh2NG_rtpET3 literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/60kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/60kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..cbc6aa8c29bfa22dbce678dfb94a4cfb5b70dfde GIT binary patch literal 160243 zcmeFZdstIv-Zr{WEFRigw1=4%h;OqHMa3y}sxXlytu+L7B6z?9$h6`x^khLO#A+7B znW;{vi6k6~)`ZGQgi1YCL2Aa<HUy|qKxwUjN<uhPkOT}lti`^c^nJhYy7pgt@4xnS zec09_hGebh`5o@xec#WT_-W!U^;FDi$!f~W%ZvI8{-GxB{h{gg?9{(f)Vg(4Fhx<* zDQ~Zrs44hr7KImooJx7)YcG7g`C#Dxd_C{@fFI?9?>&yci^PAF-vEAlihMQsYjOo9 zS734lCRbo`1twQuas?(=U~&Z}S734lCRbo`1twSE|AZBYPkk?Wch;VHFZ}^`JN58X z51a5bMa}!SD$nz^ci1c8)c<A>p2{JsGRYv2RhaxWxdM|bFu4MgD=@hNlPfT}0+TB+ zxdM|bFu4MgD=@hN|L3eg=pRBuBmNK`@rRe@y|gR>|Ndb)x%p}EArNQ6ls}U{O~IeR zFHqDUPT+UX_g^R9_x@ksKl~fVFuMlagNgjrB*#EjVe;4H3QVrR<O)o#z~l-{uE699 zOs>G>3QVrR<O)o#z~l=2|7r#PjjO@Q1L`sI|IOWwC#H?vBNr$nf5v}-<o~wnzm5L( z{fS?w*QlverjUQ}%Nzern?7xtxA(M}K0c34e|+ZSkI$MpYt|D_&UxyICw-rsHS4Ko zpYomi^fS*q^Z4xNe)sItznk;)Gf$H@@tTUC@t!tg+O!!@KQZfxr~hC7n)napJALYZ zrcqP9UZke@dQJ89nz%{{aJAEL@`4<``0rm{Q*e!s`AnZNa~583{wZpT*VL&~yr+_@ z#;f<^?<sHJX><PTrKrc|#=hb6V%pQ8ALV^9UHIzhE6>E;cu0r6nVvgi=CjZJ?)T3J z&JS9!F!<#^zOrn2c*JX~USBPamc(q>xM_3zmaW@%Chz)d%HLAo+LMv_K~}bG?}5Mn z<DVZNJoGP>I=`T>=(FM@$4kq~D=JS^ojh~)-1)CBT&%1A_PeX!|DbO)G_|(1-@MiF z)6ci>-S07(do6wa10z=3=-4CsxWh^A%M17UKfivvvH#nB`QpB&czaLv_96G>H6;uG zP4)Gj_FpeOHYY09=Z&<vFNS_J{pnZpzBqklhA=Gd;WKZh-<bI<{qnuQ5prvuJNtij zW4ZsI?(Bcv*#Ew-+tlMzK{xqM^`#if?NX1M6x9<{%>;ESlTLH^-sokG($4m0B|$?I z)S%Wqdcy4xPEZ={P^|w=aj&?SeGo%2{guPZZqS-!cFf4j+O-WfVQHh1+eP{ER;Fu{ zu1n&VHbFH@7)#~Q!0bp#k1CvznI|Y?%!h_vF@Ls2l{33j&!1kHXD~Z7Nkb-lK)$0) z*`l1FUT>SrB@Hi_63(!+N~THSGEPiTx8%e8R=i`3Xo3onj<JEEOcz^IGQ(}`5)0h6 zs=HiwkpLI`pgc-2WO4|t6I9lQEBvXP*<CX2C1uMA=3kX6X-Kw7AzjLE+sKZ#afwuD zG?UfKnj&(UPJK`@e<~(YX5r1!6*cT7HTkq^+kz>x$Fu_zl+2H1xU-e|puC`BKdpV} zq?DE?%M&u+TaJ%BMukon)w4x@+6JyOKs-!WNP5M%ijwITWlL$ZwXNC4$Tr(~OEa!Y z#-Ay%2^G>#N8a_RJxY6qY^06W@<(KuJD9paYRd$*)ukKD6saT=)RN$`G=8XZf{OPn z9i<8{Q-lj`B3+n0)4yYw8UNR5KR&70Wekn^BFJgvm#y^HUQ&}!d2mb|R3sP{>AKjy zr^SA%jT&*WpFENBHJIB+^ezMQ%L(SDVS-v0oS|B7Qu4)QX(`$^??AI{*#y-QbD%|S zXRX)D)W7||+8E@vmCW+h(|P1?nfBPXgN7cl%`yAZW$7}dKjo_zIE|sjxX!j1p%uF# z(~e$?peLw8)%q##oDgyr?&a!$lwr4l>9)G-71FR4Yfs5^chhP9l+=;BDTwPH4$ijN zm@EWG$rK5;xoe|5saU{;DasCTSw(Tu-XL71sBg;WnL)+9Vn5c_TE^WL2S)YEv<)S* z-jB9*%2X?MDD8Q-*3}l{-i=+GKhN+we^2L_A)cU07xgE7+_72vQ0aJI#@<f)xxQ#v zh#S}QXD+8+pP<q*ds(DGMZp8PPrXfukWqz48knLWyNSfopO4O8bL5p3xAs3dtGbHL zmEPHXU|2svtsRssdFSOXUukV?%nc8z)VAP;H7U;e)AwF@Va=CM-X97#*@P~k!B6eb zTKH{oZ%t4QidF_OdmF2MB))XRz25Mp!|9r+`+vJTLH+$C_Camm!`tkv-qm!s<^g;E z?Ry_an_LOnOA2WSqjNQlJ+a5`EV!c)I~z?{=pN22d*Yi>?L&2HWXh08R~J-dN0jYY zTi)VOt}fP|yv+}9o}gAKqTR;Ob=pDZmMrs!x1Nnm<SN}Z1Y2Ue+TgD^@0y@OC2pOT zzb#JasumPJl(BYe{{9=E?<jwp_B9~I)Li15o!_~d1~RwOsu@BxZgs1!x#oov%&pB8 ztDouUuHL(Q=q}dEd@L$UdYX@@R=;^CudV8gc$GZG*`!iTQ1@tdWP@1XY{ZMo_g<^? zPBYSJZtbIM4IkdiKQuwj@RO$$O;A_kFTT|uK%!`j9Wa$I&2BAj!CJ2qDqC!fr94us zLIJS0*->FGh}~xu%vhSi)s&pa+xTs=Gzad{$Ys==`rET-WP1$!neZO`oTz>uI~XaW z)y>$UbcuZ+nwN=mV<gKK_ux)erOSJoZ2`+shziqmLtUSIBtW#SouD2a3rNT#!R<(y zp!6bR2vS1JrFc@SEk?m;n9y)q+05O^(+&0KG@6vZo)PnBq|Sb%FJmr$F4pj9tNV~p zHQa0y+ImX)t$LTT3-PGfIHET@v;(B_X&<y+^d50&t*z2deu(LkTT9jaURl9T<cQUT z;$_0`cC1a1^Bk^qf*M|M@hMqA66&4I&)30TQZ_pl@@x@*CK~rrC{NbfT5F^xiR+^0 zek%%mhEaX_;g+f?%X@4{N{uGPZL2i6>S(1so&B|d4oE5LW&bll-Mry9K_T`@2`S(7 z9|aTI&2Qz0`Mt40MZJ=sBK|CYB=!ZzQIV1FSe0ksYx%wM;g;k75uir)YmuvmM8<Ps zRDoY&R49$NWGENa)*i+3fpF%g-Y-94%5sy9xk;*xkh`NvD(25}iHqea#RC4dGA);& zNg3)<qZnpvc}ym_%$eA+wiZRHLL%f$dnTyv`U|c`lZFZ7>o=x-XF)q*P(~ey1EVzb zlbl9I=9i}Ll_A`8Lnt0Ytjuf(a*rZkmnpKb6y2^mQ5|DG7P;JXpam7_9B=-^yj-Sh z|EX}=+8QoYFpj_SDMJGia)s44rvK;!)mKm3=z6TWz^Myswz_pln#I@wv#;J<roA*l zeXWuY<p`zdW@q`^8?`}2CK)?+?GUYE9I0rfOlSKZy?>3sdTsiHou2HVBEuQ8)@dM3 zHA6SZSjrIkYX`!EJUf$)?mNV4xym^7wR6@Um4xX(wkRi2OtXWcizEz^99-x6%lKiH zES+tZjv?L$%eU9tL<XTvXdNhTmnRDvJYlj<SmE<g_7BX`EgHs|y5+0=&aRPv%Xgd> z$rH4XT2FuR<)70>eNnNcu9VHFKJnPj;+xSz&YX0Bw7;5?Cw1R_eR)^S92u*#F}LDh zdo;|vh6pT_uR<MDF<6Qfi!|3Q)(87^V|n_(RD($SM(*@^>K4*IGV{*=m?&pLoYK(c zr2pSy(`$b+1{J0HsYoQ9VnR<>y5!}w+Tc?}7l@up)SF~^Mga=Il7(AJPuOVH?4?}F zkXvUDR{pC@vEmh(@Mr(-yj~>Fl4TCudUXGz`r0DzG{e^V@7tf-_HK7E5<sNHRpl-C zD&XB7iHX0dnZew2Xp-~v{HeOyFeHCP!TI}tIx%#rOvP}|ZTaKrYZCrUjFL+f3^F%w zm>n5jK}F^p=5NHkvh-M58%PNT=_*>y-`>EOD~qJ)*OVAFM^&bXP@c>85<J|fNh$Id zuSKTh1lbnYf|;ew72=@b1@n>EgTWChrqi$rwLABq+Zdt@U9*+3e4fv6FPC!3`Cjsl z1YK@4HoyW<A~VD#Nh44D6k80)(9zZyt(gC@-r9rYR`Va~1EnX&ca5@LVq`$c%=+C2 z-U}(U1+gI!eecTWCP<%`DM>ZyQI8K6@~xMYT!NLPp)rEF5Q1u3Mhe}#3mPsJRPIdL zG`^wwC%uK!NU^@ftCbHQ&>UaBf7;&#qpjJ4bJnHv(lNDRJ^PNam#wkkhd#da)9sFz zFU|V>1a%|CJw6!9E=76DJW5+7flD?W63}_=$hHCLQhSE>%Ik*H2vxdPJieP|e>&2V zE+0bU3L!}w|CvMEP%9bV6*RQ8$KkFMR)s|Nf0^l*F1OjW4K<zV?28@P@z!(i>0~Zl z7|(UAxZgKH-QSM9H9G%VAgZt&8>lZj#&BUL`!neb!#q{Vmw(=V<kp3xhU!?O#jvH3 zPuy`{Rq(Gr?SInwrxSP4^y-AC&Ngy)Sl7D2Yv-2Pf|R5I6bx)0nV?Fp^vZ`K4n=O* z;`$*euUCRv<YZ()!!+yc@7;*XRf}+8ZP&DZ0SPJ@dr1+~a%P5weF=^9OTB2W-lcP; z`iuS23_-<fj|p>^yLC&OOMDC{K*?#2O!2R$jle6Yi{;xj=rs;YEI*9ScPih@Pm@yY zr(qG=W0`L<omb3;2`Z84FW-nuOP3M6X*m{<RP5tEtLBRhE1zF4HXC}efu)h0l%8u4 zI4`zJ$MTS=ws}_5fo4>i{>{SrZklyGne)=_FL%07paw;{kQl>5w|v*XQ6HNb`=YEk zyuBu=2ypSMhVX#qZS4oz<<A-Xp8qu<8SS)%yQ)c0CT$<@Y0-X{=SY_oSeJfR*K>Mg zTA7t?mY}gTW{%kpniQ@pH;jC3v(m1T2;67OrQ`q1oPAB%CBw(`UF<{B+B1WS{8T7? z4vREbAhZMDqZMrM-GE}1A$eXR7>+b=;qKT_o6jn$J-;)dF;ude1pXziGg3MxPjVWa zDXa1vdu|>?lUw-=J|5+X+qFFxWfjXh5beH*xYiCYP|cu~yiAW0+Bao(r-5-c&9en{ z14EO0s=C{@uNhsx#YU=arr_t~TmWe1)_U)Nggx!MffDg9x7eEMfTW+3RZK`kkn}}q zm|eBr%TE;*<TPO0Qq6|f43;|*G!nc;K^$pho)%y^2C(_Thyi`p=ty1pOwgyKS=({r z5y|P2-VJU{Dlww*9);A=zw&XbyAc(kF$1_fFkl~&A_Ax(H)nc}B3xu#+Cp&2<>2mO z^A%b<NT1{paM*!2qkB+5u20J*7ug&WQo@-KmZq4~ei{@NPmN!(Kt0?zf_8;i&G*`1 z<ji6^J&Fdf$Ts~P1Wf%K`l;s6NapfeuTPN$B#*s`)+{4f8pDu1?FK2ih?raJy+m3p z|5FkVir-(8>L*WD$ubN<oSBLgt6MlTmc$qmp;}YL+#zeRLjsU3b~RC7YX?O2$?waw zn02b|YVDccXz4U6qi0tbVY7OIdW&RKchfx1t-=ghtvKj5(8@-x+kMV8iq)16mEe95 zS6rvGSC&>LPZ}1Upt(EROC>&f^A*2zwz_*WvT4lIbJK2SGcx`(b2sx%43=az@o})$ zR>Vq{pvby$jwGnq9grw7J6Ky=OUZQH9MWe6Vuitd1Jz}rhIhw_Y4vsQIr~N&1%hF; zCsTw53zJ2wBpV!Q4tWy)TFJ~jha3Yai5*&dk<<=N-i=;baLL+JYENH34c*rnTB&S7 zbgs&zZH7Q93iX-m9x{EofRXudFW3Ac6V=hxAB3{a5maABmHSYSnoA%lp0(rjT^Tw$ zMxNfNpdvb5hG7?zFec#t>iG9IJrMa)E^%*V4mxwJpxEq?Cmiximu1F&FtvZ!C%bap z>9!Qrkj$d|^)T*jtsAAqd|Ynh>u#<7a^%HtM;?&s*Jx6)NQ7&r8y0=hzwCyAtIRU% zfh$xjSC#lG66wi(VKjR?{(ZLE!La<k`oQ?3Yx;IA_}(vBGw&-+2LPxRkd<aRfSY(l z_JKI%I_)|ul1aJ6t?LTv22N#viLrAV?q_{FYeBMPo??g%mGo$qlZ8$|19IDHpC8$M zb+@-9)92B<AODPuN_lZ}yz<TaLuuBx1LQ|pB%uMN(^T_Ib!{j%pkM2@eVOXsd9NRt znia(DQJhT~`QVc@TzHWgMR$yqD>m%ddE_G3U5xLbeMbD)-k^(Qm)a3w#&z0;Q^!Ai z0JMOrj~vmYOSWFP{chPqSsoBD*~u@z%fCNV%9$k<`fc&IcNcA1vXe9ACp2AE#rkEU z{7+EtX}vWG@`U^?r8VR6e(b}~`gPW84C;b-N5}mWk<I%9%Mcb}2VCgv4dQz(>Fl@b z-Y_HK8)`oop*1_o>D_d?ls{`{8%`9}Z`|3k=d>{>&&=D<Z_S2Sw1_#f4~6O>nP!({ z+0b2O^Uuh}M;leLfQ0nTkCmnA{V?}4p-KW+;>E@E4g4f}iuMve6Ib^&d#NNj9YCN* z$)&i@RnZD&DVJ0nRJ=;FYJ|6<4~?bE@@4O1(z@8A<m+y3nQl=qAsD&I&{mkvYHhu- z{`%r&2sZqjz&%?1oUbDwrMMSMG*oIcX~GecGPXf&2ViHqz-C}C-AyELfs)WoqWi4w zaZHkF2CJCP^vlyDdh<Y`0C@$kRG_BKM%e^WAnl6vOLMS;OjevsldK&i+{KuDm-yv5 zVn0m+U^3%M!Bn+iibSYb&YRc<a(Uudha9}pwHk@5&SdSe3A=%;i`!9A7;aC=R4(BV z-nvG~|J?o*ny(`b(b=GqcClJ#e_-V7u0$Eo2Z9!_!K$uXU`4_ym-5--O@DdLsE~%v zcJ$-h3u!gCFO9dgkQJ~m@RZVDf~8$zzjTQJAU>$bJ6%4~cX5uyhPlkh-$wo_miH(v z*bth872|kPIfkO7ZpN}8?ofYqnLb59D0@jm?nbxHiR@a(ApR?+n*O{0WHioGM5FZf zlGzO%?dyyvOuX(7JwF|9ZbMNZ<EV`>m!-#DMEgfgmnU@}4<`r?>qVAFwcmlUQWC_4 zfuI>{Es^yovhON6);Vs%M6;*D+bUDBHEO<IhN~g{)Uy=TT(`4c!#YxeFt~=6Dv)Nk zaP53u>sODHsuqvxD74MN#odY(crHyl&~F6@#-K<5e@3H45p6=NG6>bpV2oU<jX7-f zaVFF=Fyr={mm?$$BE%aS;4cwE%zVqRA_ehN!rjKO78OXrHC3W-tYSayz(D6!Z3AYl z)Ic!<WMKXrS@c=JGd<B=>o!ZnxRjAwFF$)ZIkP>xl?hA093l94^p{zE6I81SQ-oPt zBq-iioL;cx9X3l)yuE(+&r4{|o#zmM`LZ#OwA{Ihx4sU$;;mT~kc_E|b);^6<?F8` z8Jc})sT-|__r6!qBYh(Ev>uHXFzJ|df||Aa)${7++;Ez+fCa3ZAzJu0<Icty*BYbf zxclDuDv9gk1KeMYU6PpQx{7ZUrE%lmlsVYGLTv*kx-8BZTB5yQ{&5klN#K*5C~({N z3VyYfO;EdbUm6Ll0g=`^>-R#?k7q?u_hx&iekCz?q8HXha+^v*Hbi#ZfA(l#yB2|i zOnkoR;N6ZT`x@sFL=fK_@0I!X8#{xXXr{&6_A&>DMr%W7hi1F$M230bC=DB$LUsnB z&L)`+0ft5MqX!<<Rk5i_5(YIs=0`AXX9xtYdMlWW<5|7y*B!+EYYKq8PV{gV_t}$m ztF-z+fK4$9Q*SKpK$8Fr|DSErvCKfRs9>I8V1RM<i;H_>FXz4^>D?p&21PY6p*NeS zJ&Va6aa>X0A0-$LMgc};dMp;D!+K2%Y*^ZmPsxr7ZHsCi)*dR=a#MjoV-evd-kgq) zB!k|F;Y?11c5Ze`BZmD3K&4dw^j5%KSL0ySL*qeIxH%J){V=Eu{E+m1?M#P2hgoX| zldX!qd^bJdbvp0Y>U1$ZN0u%=ixtxpc<0^xC=N9cZJA5r!m32dkirsg1)yQ9-e2N} zGWS|#(PnP}2qd<_!@=#FuaeN04>XeqZ?H6T=Dp8-8!gl(04*R9!8CTOj_>FbcP{(m z0uY;QGiK?n5nuj$PyZP--ot}mXlCDe2h@!NwIMP1?`#8d?V_oqPjq}>HmIBkL%p(D zg^DpJ`>)Y!)!?KrUaC&&bQHvgn}>=wl~;hf`ohdxYk$(CjrXhf)IZErYBRl2*Q{)f z74WTgO-G6Ky@pTNE)4v}n97H>-&wQ&+TnU@%>;EO2~dh;vn<p9QMI>KLTG{}OT>$H zG0(+GkZkVylp;C}6^1i!S49(o)zu^dt|c5)B9j&Mx<shLYLR4|?LJFt0r=;T%6iqG zHaaY;I1_%<xWXz~YmL0=<35LWzkVtTyTNY+Z+TqWC3P8SYrh(ozSwQ-yy2%w)+DRs z)*PXhOCpU`g-+0mg3zh~wPjV32tio;Q&HXsXu>7|Eno2KZeU5d6q#HF-g6{=8gY@U z{(`@<IL*wD(4=Q%cpc3Q;?Q8PFM96V)4zgG7l4oA&s@k{dM6QEKS7;eq`|P0I66Xb z;Q4u@yC0L%&!1t9;e;*MB<}x5rpq`@f0<-~OV`<<zdT*tc(WuMC1n{u++6!r2{%D~ z1n^N=#Mc7p`r3E3q^x&8bcvnDrTo?#xJ^anfpxZd3JDF=8`i9f$d!n2KT1GH%dsi5 zmo^e^9ys^K4fAZYrj(F5_Pp!fs&_u^u>~Wp$pE)x0hyX~cDDP31q%(Vp^_}16f#ge z+jFIn(I)auXFZVcfV+;#+ALHzT1^TD#ljdveFLH!BaP}L)?8$Cq@r(E1$n4C+1lJ0 z;3)RW(s*mG15Cq<8F?semCkx0$F-+JI=Q_8G$NuLYtNr5!HfnVa6A90xmU>cxsA?L ze_w|@Q3Bw7LqKo}Fz9t}Z2bvfp%NwD86@o?aAz_xSpRA?;iTeK*4+v%uY-Vr_RE0& zS^2n4)JR6x$l09$t6H!e$AOu^YGQi|GYLc(M!CF&9j6X(3HcLL*gk{`5edje;nsWC zdk+T<^(ab!R$_!$PGnLOxz&~4sNJY5X%5XUF`{NKrV_fu$8D8cYoh$r7{K{crFcC7 z;)NM99?+sS2VmnOa3yY~6%rE&+*Iiaw=z^3MzBF!1a-O>oZ6+6d`hva9{C_KgF0l# z&7re3Y)DR!lHVqNRbrC#Zj>jaK{Ww*A>$jFRBSC35<#&T>>Tc9Lr=+!dCF$xF8sXt zSG*)&>@vDiL5{A3CQ?M_v(2-^fK}wHNM8&fds$;+2B8^21=!$FL7h_DF%DvtWo>tr zcCGDN4qatZ0n+V?dVwIJL1BfI@MSpyfQ4aPMPa6o(?Hu6S|#G*m2+hB1kVm{^fkDQ zW0||Tgv=e$Zsk}$1(t1sdZ+Ka+Kyy3fp9hDIr61uJu}odHKtzsWcE?lE7>M3LCwGi zLxV*g(W_33i}vcP*I)hl0kBFcMlx)WtEngC{Eu&6&5Dy)97?ngFzP?5Fg|9;Y*$_| z_za;^Cu@?pmrG`SaCzp<TAhqYE}Nyf@<7$}uH~4n+G5JzzW+&c($Z#C%<XgI$EtqP zn}0Y=v!mCTx|Lj4FL<b|?~fE#b4LS?isl-SESUZ>2lq0+eiLxaFa53C=K@lkbx_X6 zGOtFBR9=1Ma!Ov7Nv5?K?HS^cvsb^8_KI28I5=!bW=Eoi>`TUb?w$JN-V3#NB$@Of zOs-)qpAODs9`C%ZPhBxV4K1OewCLTLuWcDA=j%kaP9p}mAi(ILJ2kt{OK8<TE8hKD zc<`yK@4lV)Q<R`kB?;7XFDvS530o&s+f{Mby|?#OF^~3oP*O#P*NyR|E&NaCFqycT z>?_`6!Z>yqnYj(|a=BsIe<mpFGv_$V5a`fFeg1ozLGLaX89UwJ{vC4)UUew;$}mx5 z5L9`zuOg&4bj=OFB0@wELc>mo4!V^g%pE|yW)O>8w_I0bgI8SUsRH09!CEz1k;QrX zUb&4+l+Xc59)@GE478Gk+l9d!9R=ID_6_<&LJTm2TKhmaiW(z(UeX)ntXrU(O(Ikg z&J0%GsTMR?Ul9wqb2cV>jGFU~($2az48;n7z_2}p#BM_MxCk)Ph?frshYMXRYPHDV z-voqXn{rf4Xf*PBD}Q#_5X)OJR|L7SI<BV?_9X3Vx#SGC2IWJO7(LZUcF$aiE`x~M zoG<a-qle0xzPjH`DE?n!Xmlg8K}B&Z`2@j$PzAVZDa(wfNa>K!@}%NGUp=S=+roYV zmpm}NFvIvF1Fdm_V)4oN$lpd3361X%LAov4U9W-|iw|fH$CYaGA%{-~<*x`InC`yV zLuN=M<>-%n6leKO1OnPJaxYim#f2CkOr@Y_xAPB>mlZ6_?ef+8u>-$}EZXjq7oRcZ zE;p&NvE~)&k~rzxWZh(e5)_6^vWSUf9PW*MfA$zYhUX<1eG<?@6TohV2TMbcU)oDm zH1dp>k-ipl7;^NWP|fojF(68XD0jee5P+99;_7sew@+H70<8!$4CLMvq(644a)Nq6 z&2u*srZ#gXr0AZ~78M{2oz8YYL+3eEXb(L5i-Z|B<%79QCoR+1X>cPkKl63)5Qb2` z6Z(`M8MGHK#=svD8I9K<P9O?~wIJFthe7uAblR0ZMX00Bun8))J)Nz^DzOb!K-R-T ze5%ENE<bDsDZ_7L<)omYVvv!1wG{7GZ3{+PLjT#zwn>7IbrhQ<e(WU;VKHosD{)JJ zqzC=wei|r&Q+sCv17-nr41P8K4?)pM>?C?@!mhXWsQ1?oEvJ=63}*aRN4}8(wM>Qx zXOkj^I{l~);~+3f1_Z7}(1IEYe4O>KtoPR54#S)ZOe?0X>!1iIVp57%P7{15F21Z> z3I++&uZKgdz#2i5FuEM;B?9i{lNYCtUfwUfai(l4v`5uORTMqf0XUit4G@Y)pcufe z4C=zB|B$)4=A>G0<A-YRM1jT74&P*jElOx|ualBa`ich}Rpg5WMXOZ1PhNaV5+@cH z`Q^*lN7u@xD20fH<G(Z6f-%x;N`EKHkDzQ^U9(CV$}F`P1U_C_j#Xb-Sx!AI_J5%d z6`E4FSWTx&zl#iZJ)XWLk>`O@``ynN47AE4(nV~6vWTSUUGKC1{_dHMJnr(hD;~`u zS8^pm>_o?3RQ9m;ld{tgkaa5AVu2lSxPZO7*L#kv=mWt>f6$$h%R80GKmSl9qia`W zv>QJZeDyHWNjjGQRQv%9*ojdLhtxY&@TNew$<pno9c?{%SL}YKeSCHt|KqK{pgzVg zA@!a_LS<>^{(m}Whz#Hie5wo#r2bx_av?#D5kJ<S23WmFKtyvy-G0A4w=2q1JvAS_ zZz+go^t+S%zPSc^wqSU{vbqfqe6IvKC#X&biNS|MpPtmyS!o84(>0pe{IXS=*9-s- z+?{l`rskg;bmK|)P9#g_ZmlQ9fv<1l#~tpbzKrfC#<#zAUfFm-H8g}xm2T}OwTss5 z@-+&aP$ojFi~muybIqn(G|1Lwg2pYMXR0l*C3qTYbIdK}uXFXZimheGR2zh<E(vit z@JBX&lmza+YjwT^D2%g^Yz_XteFRI#ECIPD=D&}}g=7(R;4rxDutw5v^APDVgfs5i z4F)S{m~rhAuc!e_IzxoYCG9j|wHQs=`2)nhQLQH|OvD9TCMj3>6o9K@Ip_$yfi5Hh zObx(aC-mK7u1O{7$t6lU4G!2W_LgU$$6(wp%ey}9Vvl5=jl>D&Co6=Ild3;Myw-2H zZ6Ge68qmX0`x)Z>s0OD2A;*6{GyZv!9&kiE*826SG9Y-aa?9q(lt<<}X&~VcmF}kY z0}T&#!++d@l7DRffl}P$vlCPcVWj0L#b9(vFpPA6yi@h3GS%h(JQVS4E->wJpiQFO zmOj`sH&)<<R9S09$f37aRl-)obP>hb7?T^$0D$P}l3a<9G@#p=Qz7=)czm-t27gZC z&m4+G#Afklas+T0X~&Fq%`OtdvRESxyG$~>3k#;%MFk|Fj?$XM$k`#wF){P6op_LJ zCH5jq847aYa?=s%(0a^W$X~)PzIkv6w|f!z&C%~_!lx70##sLTQaj;%Wh=o<yKN`j zbs>PYDRH|`+H{<&WD5FU0^nhcCxF0tKf0#uG_1Aq>=-1*;rY0d3^D)JM)egF;pS^5 zsC2k|!1ol<$fX>bxQWnCUX;L_6#*}TDLu}if{q*#-8V%R1iWG5Oa*=@OmfuTD{HkR zG)kd%pbM;g)?$4mD|n4dhTA}eX86yX7r>{%7}HK{Q#PzDfbc4IFrWmXDj$lWv<QU4 zOaWvhNB`Pkf2IZ8DW$vQ0^F~>;sa#}a17$9e5mZ7<kmCLoxx55zn0iUbqj40Y;5%j zY{6DS&P}<hcH|+H1kU<ev@Fn}eh`}ngJ%F&Krvf6SC8=uo3<oaN=BAbX*VVF(Q=JY zMan6uC`}&(DHSC335Y2QC1LiK1lLTvlm+|(WX`z@Ruh|8mD?!fx3=d%c|yOn#OnRz z>@eyJbXsO~moKR-)JM#%jV_=B%-{pk7o%xMpNfslS!6(>%JjV(&>13Sk$Y3%fM_Y1 zVYy%x!f0ez@3BN+q?7(PiMDt^au>oi;>hYxiG2u{yw!@XK&a8R1It0NpS5Sc`62Yv zZRn)M*Qd#tEbM3-<49darr0H<r>zT)p4Sbz7K)%4s0L{L&)xRI%ex|HL_&)>SCM*Q zN5br>ZJrq+iC<Onn1s>N1v_GB)j@<<FFVo%Cl?9P{z~^~DX`Sn@PkAT+<A5(L?8@t zme12T=Y?sXR^omUKB37I)Ru*wwCQKgl&E5Eoqt#}SKlk~MjU>WaDN}j0aw#L%%0$X z$F6;|TK}I%swfkI7_iZ`oES^`_-kK1u~vA<-KnBl;y|-#hvBpce0!jN;|FJC@?CEl z{3*m|chkC2<5FDHsRHm_Tv*AIAAcJv%esztgAps|CM*oNbPw=?7i7@FK8`dVO=r`i z2m5}E$sVeC7fTxNLJI&9c=^CijdI^%lJY1*0Vo^A9`dpxuRV;d#RMnu{1MaTF{rfW zO2`G!K5UCLJNltyUEoXvgcj!A@CG;CU`1$nNb48{8f@==VtR}hfS=5YV~wckgIZ@j z1+mfN(#Y_PZDc406M@q8P9M9p5w9l`mk9cB3<Zt_-?-_S$pk|dvLcnl_>>hF)f+{p z=?T$`;8<07Ia!lJ>^b^gF>zdGVQhqJ1rXbH(GGsvfh~<gI$2S%NeXDRa-|DH8NYWU zKo&qpK|BT19<2m9(i{<avo{LfI25!|WAh2%a3uf0RiHY|6aaLe<e=4Hm+)n!3bQ%b z^D=;olPIG=6K!0Qvk97u46qCkhg_>S@E^agDP_oln<J@!(gRgOA-#)*EAUh6cS9pQ zgvIR*q$K=l6TXZ0F3pYZ(E_ayNIYOVfp#r{e8kpNMD<FTp&qP-xeR8+?OHpbm<jTg zwF64q0ou(su)kw%JO{pCOXp!}MR@h+cy$0cNC|%m2?JI-agO*AOjVHIY{nK<p-iOI zxpV-_g9}3{tq|PEbzB0YXlX`q4GG89Z}rm-w*y)y6=8UVDU$|}s1u>glD38NfmsMQ z_pYdk`i(I6+;6jTNNznS0!PwAkQBb>AN8_4fn3%S#_Asl!iNMI>D*9r)_beF#b8j` zu^V)Z0<tvLsS9boO>V`|Hijte2p2Uaqcqk`#ZDG#-ju;zpbX=SVd27i!+mfQtAMD| zdJ8VvXmv6>Kx92@;35jq)WZVmp~F_IB(KQQH^D`QOE*f0NVaLHjNI{nyD7v+Gk$-% zsl5~;w**zS7ZhPBh{J;ReXm|r{4g*Z2D6KY#*#w5rghv==oPTud?E^1rAaF8#fYw1 z(~p5+Xh3-^>Ja9oGQ9UHz?kL=_8H3e8xR`BQtVz<??zuJr1@TS9&d$!Ulb@Y8|Z=! z;LRwh1&9|n1L=8sPbCsll|y!;Krqs-9ldrCvG6>FZ&YN`sb+mF!DT`vxAXecyPowI znJOeweCXP|z9|hr>0-Zp1O2nKdnJmr|6;6Q8%CicajgGh)ux1_-k5WW0-61x;R}(h zh4~2~iwgt}+d`C#H4sRu7NDkM!vXOC4GzMISu!PjA)kU;ytuDImQRi1H(7xnCXpam z%v9iycs_p3y`<k6$|WYL%Y_Mp&irvV0$7o=;)SaLzgIXrTx-^GTp66c-4EmcD`<$x z3f%rs`N?~3hAHAN!<KPa;?BJFwnlIup{=a_+!l8;#u6f~l>BsWo`UqyO&9OF7PpE6 zQzhm5Pj-bPk-pCV-RGmA?!LU@s#ir5i&vuH%1ZyG|Jb)X=wmojY5D##Eqz#;xa4x> z7fG_+e%fSfj|&*K_9dI>U(0TM{r#SRQhM)V`0=!!kYFB^uUD;@&y4LYDkcR_SPQ;m zD`ZD;Y*XY;-FfXg1>2QK^tli%?R-ZqN8M>rGz=Q8aG`OXTlV;m7Hxh?%<K5#Hv00p zPf@6(1Y>B3uf?+LxtrcaU5O#D%8aopz5{~&9hPz1_?gUk)iOo&&|Qr41ZfnQliu^V zMB~_03Fi#=X)&%-IcJBpxDo`mR^<g4T>w}e{X5?FAKQK)7XE@e`RTJi8-4qQ6Ba8n zRs%7z7NVlxh#sIK&ycXX;H1L}3cTi2^*T*-H;l6I09WQ;yu9<(Rkjj>yOF{0OwZMe z<l8wr$@%pCO>k79>3Zg!ju=IDPj0peu>#_;>^P)(H-TYMqNk!Y`{Zwm<7fdaR2*~| z)hGV1JP{*<%@tN<w5zQveFt_V5U}F$fuz?R&BiEtob(Tna*IyhOlHGi0xd9fN_w;5 zQAu$j)bD22>~DRt=k+7Zc|ES|mH3XN$91y1I^ZELgP%D*_`149Lj)8MAt;wWCvD%i z2*$pD?P*j2YeL<|WDmH+GNXyF7L>OfJfS?0avA6neFg6)>N#OiCu8c0JA^4t4NGbh z$U^*`qaYd99B17;1^xor%AZn&lcDL+u{jdLLMQZ1LE(hCTO(UqsgeQy($MUKaFe~8 zKFo$gTeg{RHecxlqq))t^B0M!7?nh%L+v;TD1#`K(Of4be#C~bgaxRA`3aN<^tT0g znIo8iMJgl*o^RAzTh%-z@sKy1FhMzFI&UgNVQN8AtemZwF^~AbJ-6RnAs>Q8Y#Ry- zp|JQfT0hJo7Vd17nbLA8PUBd{K4@#ku>vxIj2c^xV+3;alM#GMH0}{h86qa_rj)TG zO7-S;`;O$ugbWDktn1G?^FZ;C_9)Di&@h@41cb}3o&!Qzo)}NwUl*D)9W`Vtq%Z>7 zDl+{*#H8?_RKe}D>3wg~^yAlq3VXQ<Yy=T;!Bas(Q?@9|X5i=I2?;|u{#ZTevI?=F znDp}DPG*7<C~_7@VORv%1mRc!O&+LgmxP7{8bjs6YU)7hN6b@$r*6Y!M#_P)2X+?H z5FuuPdIqD%f}rKjR^Utqz(o!KQeAMgsf<X@G$DdIuX~|6Z-swRwXYyh{5;`JN*;qI zHvlIJLR8yua>OCu1<eaE4g&+YTEMyHQhb_DwJ{IITuck0If6%JXnqdR%Ln@)LTiiS z0Lu^;FO*F8K#8JQgP)SeJcm+R1#+EGK&BX~GEM?4Hv}Rrx(8-mCR7@dGkrih2FQUq z;{eO;InKaojZuqMME6uNx8MjI10ka%x*~BpM0j|LQX|Yjw$kxFHTpPIk?j5vqaR_0 z3~>^djt^h?yzcf(VDgLOwhf#no=$Lr5#J&m1|$eA#AD{8%k$42;9$NIaQ1lE%^AgV zTJa|mZk-NockK$&&4`G;HIUl7)V*ZZI4mNmp6<Qqg}9OLx%O5`uiT2*OeiW|)5{hw znE(By>V6D#Fpwc83X%x%@2m%EAZ%CtOhK<KUyMd$TX+;*lmFy6<8rL@5Bhtubx4QR z>y;IZ?r)zvLA`N>KLe>8^@(e8eD~c;R|4D993K*O!|3c!S_5wscj>!A%v<)uVBj*m z^ah+BQ8y}<TR_;QkjO@nnV|ftK;gqY1@^a1I#wX^MTDfHJ|dM%Ars9Gkq{9`a(1{Q zyw1n@%?N5lDZ)h60hO&y>g->IkZJ}UvjTH0R4&xd{Kr2cvNW8}%Nc;Iq@k`d9QXid zjgT&s?}AU-W<qBq(-hH4;CdK<*5~>R>gsY5SE!;nGvIR?b~koO!Qrkh)Lp{h20E%m z5rbsc`{g;<-Wbn}Qw<-h1*-@NCC`C&-Yj*dxGwgfxw3wTA!338#nxzWGZ7a=U7+aT z0D~^(SvC|RZ|xpb2XHq}$<nT%B6ZBZTRkTVUyPuFZ-Q_F(iCn5?q$~~1w$U*tcun) z!UBb>3FF7f#~?@HK7qik+L#7^Bd9ExFGiL2g3a@xgP{y>CGQ(?+D{9&^G(C5G(ENf zlS&4BE*KF&OT?|;4QDN2YlI>i)_DvCz=k$D27|M1DclF36SRJsZ3y)ks)}GlkGFfV ziPf#L%K7PT82t#)%;H%~`4$y?aS*y7zB(<gdinr(N-GizQ!-eW46h`+8nt?HA4u;T z{ADmPC^)bw5_3ic(Ris^Y&|n-<Py>){FlGY$0$P>%<C3Fp+t`<hK!2KgM|>4X}wpF zQ%B@z(kEGxbsi3!*a}bkfo_KDQG3Zc03s2HiH7|q2W(2{V2cbZpn*HD5LSB@n_I6% zH@s1R@`w_OpW?Tz_m+!`1x};O9w@P*XV7G+V1dCH9Zup1@Mj(H^>Ms`JQ;tG_f09& zUL=D_1CAo;P(wN-q9&bLF9PEPc(-@sTx59>F#vD9?&CGGh+8!W?xA!s85WK%YVL(g zV@LVOi%cl~8H3rsj>&EKI(qPUWdFZQo5*P}D@q9aaHdDf=!mJMwK{?(NEe&2IBJ=D z6uPw}79Y!W-hcv;NTC>CLV&<l1M(~aVhDyXD04?)X=(DP3^&{JkZT~!F<GMs!%7n_ zJZTjZOW_oh3vr>AJ9SWaTsoEu6F8VPn1GV;mi%5J*ceN934kO%4~N&9=%aS@uK_H< z2#%}NwdVmn!?=yq(!d%z40Jjid}`efY_$rsbL9;}+*K`58mi_TG&vTKyKsQS8_SRn zX_4GelR^A>EmVnJ^_t~4RW)OQSH47AAqj9&(z{;({Q@Ks)e;kT$&}@NstB<5*KNaU za{O*A^U^)-T<JYmZ5UWxGQp_6Dg&28exf3C^VHVNPlLZpXa$J<`L4BxGaUw>Dec<) z?9r2kQUeHX0ZyYd4u-up^2e@^Gm*ir%%2id*Jmr&slYPZdw6s7?=HL_l_}7Ag9MED zQFRLjiS^RnZSea7(`eE+^jya9v}w!KUm08LAt3=OYgGd>n497?{iZ5d!XRlh<;Fzb z3_{<@A_vcEPG0nFqfeMr!18p3H!N`VxzU4f{jLX2_FdbR->Hr8#6huXuq~LXRz*nX z$Nb9Ndq&GT>(#vPcJy8I-|;RT(ftVtHTUV<XcLr>@I_x;erSRKXKTfX=Eyt{siZT$ zf8)rz_Tfcs`xyGUTeU%jfE2v7;nJ_FD6?UQ`r#uc5;2109GIo7-z_#@c^d=083Xe= zp&G}!&_R>1F~IRVpm8@>g_J`5!1T@^5ywdd$PA=#{MHxpjG6QVg{vw|-*jn9kb^W- zguKE1OdMDSk6k!^!<8z@+f~pL<P+3*A9dN4Fal|Bn0!QYC)@bu3{)8Tt`GK_Y(`9A zq<|I{{O}fH?dmO<ARc7s?yLhc0*lw#(I%KG()}7v!@vNyoGd-Q<@wj!-w#E~ahl7Y zbJ`Te{(uaYm{_1tVQTnd<`*N&ApWcc(b$b4B3Rag(@21q?N3RfJ`)RwWA>K_&7TCQ zujr0nXT~zOHX&!Xff|8hV7*r_dm6JNLKF^JXr=O@*-PQA2?dTMWd1Lb1zwL%>)~kC zI-ZP33T2pPC4YNUHYy;AKSt|^tujI}f~^3jS{m{UgqZH;&bh{5Zbq=gI<%v0_I$55 zAqW7oW{*k<PL+m~Sv@BkR|J0!EQ%3TCFd~=_iOo8!26D69+%=ekoHPw*Ay5*xHm#) zEQI3%&6T}`vm2k0-cHSfHd;Oh=O36lq<QdiMo}Xs+GFqfDR2Z0V&~%5W9>TIVX=b) z@Mv&2>MUT!rIP6)18U}08hwBeLmHOQ%An%TR>|2q2{D0!Qg${`=&BZorZI}>eyx7x zTmvDsEahUe9<ty9EVL|+97rrgzhp;S%g9MEmG%r_*$LsksSGF1Fb+rHx0^S-*#@|z zv2zP?&T|7sWnUdcd@2euBZlr8&|m<1G{o#GocSX2gDeirr9ZVA7mrJI!2l8mQVO|& zqcD(+n}|cCWJ)yQZp`Id>a{J7;J>F!RzB~!q^)Z;Xz(W=0+d>cvBkMLi{V@z4%T6? zUdP;QBNBF|2)@rzBVTvjJAf_1_u=$f%iY<%3Y~YoH;l5lL2F<X4B8D<&^k5(CDq^- z><~Q<wgJSf(q2^M%sPlj1g>N(TIlHt392#BJERiuhO^RFTE#d!>awrW4hRWT-4s%3 z0}+f}H!!(5^I*6iV1zAI7G-ml5RlS(Z8>g6TjYM)%g1@qUC$Qd_#3G@Snh>+dJEF` zT)%xs0+91`>@IjLEV}z&v~pJzX~XmHi$VQX!6*Wn1e8T0uy{{N2{v)CtbnLg>&5dO zgmkvSwt)ATW)(npYTXB{#&DW4HH&l5XjnNBg2(wG7nHu*<BRt-fB7UlX4)d0&2y8@ zbQr(mlZ$TXU5$vC^8L?E>-cHkBG_wjSc(jx6$PUIBzJb>RHKJa_RPC^bagsB9WX*0 z!2H(Vd+$6>$VCHbxHO5|`JX-o83u0$d~2KMcSPWAaj*uq)iw#-BXEa-UBJ(I2-H)1 zSL_4>=d7o1?t{N53}@Z&^6rw-5Al^j=)!)r*$e)hL0nF#ZjiS0JZmnGRc_3{*9L+$ zXZ&$1tyq4SprH_t9S)Ub<qMZFy@g7hsX?6U1U3q~L-Zrm2<u>wYcpWYu{m!CV0K06 ztKaXW`jSyLlW_2bpdsYLF%W8E;+J3^RCb?YUGLyj4niKAwhmJ<<4ORSA&6!5H#wb} z=$`ZHmY-d^P|$iVBLEHTQalq{*Z)T)Y^CnAyt}~fh`t!dpVI(_a870O)GrQ@IRaeq zZE_}*=1@Y&+KSqmt%J|%6J+x+S7V1z>^4as9P)s(!SZPT$LGijF^ePsu}FfM$mKx? z>?&*vl1taA^B9AMJNJwX{(#wInN5iLpxHI&?UWYPryqJ<hui^wG5<-W1Mmk?CrfD9 zYr=ZK=}hM0IQAVBdoBe*Va<v7eUK`gP(W}2Atr%54>4JYHk@pLoyx(=>rRYqrD5T5 z>;^AU>e>t?DFw++CRC5$Y<@Fhi-pt<GQph6muY)rETy;DtOya=d{E-%cEK+U&X}oI zpaWLgW*u9l_PC|$R_)<=g5XiOW6Wh8gm%@Uzu++GqpMi58r0&j$~O`QMd)$({Ip8X z`Fk8z?WxD7dBk@(@jrC!gns0SPu^O>|KuRr?Jp6pMH~u3;Rz~+vVy~vIFHJ?IdgjV zFTMl~LTr)DuS2D4&UWj@@~00*-h?OHeGW$<%kuZv1NJTD$Z6Mz9?PwOY!Dmeq5I>B z$HP(yKH#f_U+>o2&||lHv%g9h6ra-IzuRL$oZ1k6SVhgQJ$nXf3D%c7Qv5e6oWvJb zk@0O$<UF}81|}DBD0l0QO}+77WdGm@Iall4?JqOB&z=1DdnvJig#*kOIf4$t0{HP1 zxSq|?aIB*H9><U+#_<yfg9JT?#4x!K|5E^8NJ*z+)Du+7apHk-)-%H<oFoKP2Mv#^ z;z<y35x9ShE*X+lM|)JtF?MhPN-)GNcayS7afktPs^(I-uu>l8iPG*kVAbl6NSnlA zS|WJ98hg2HiiDA^tpuoylMgqSOkY?a(!v}M%?qzuR}eqH=dRKSgz88UJL|y~L1F@w z88%CzR$<&)n6D&5I*bFfwU3`k+Mu+jTy5dZPiys2uRMo?$e5M_=Ky!j{Jm5aLsoOE z7^RsKep&lu_L1T5>^BTPFhHkb#4AvfB|mvF;ONOK72_vogp78FK*I=KlQb0XyP~G> z4BXgz-#Z<N;wj)<r-lY*&3<kRcdGSe1-o?LVR2m2OW&eLVK7oaL`>Xb*a;403(PdI z?5>ZBiykN|*qiOHuc9+IPx<8Lr7a-AO^S05SlQcH!L&ADiwUY+oU~2eob<%bk*tG@ z8TL^$V;&lWR)SI4V<`9~!VxkHyp%n2Y=ZjryPk3Pb2}?Kht<ul1nnhQm!OcaRwF8N zP0d@;C-k2=kKW(?tD-*R@cx|cEk8+Z`bV|G7KlY?^PXJ7E-zBG>XKdDp4XMJr_Uex zaD%Au?1f_2kC+ta#EfbW>3m;KdTxu}`^eHmWje4p7#~&WhNl2oX~o4u?st}CtcYoS z!e^688fLT#br2~GIA;OY5n=r9!abM2?JfRp->cl`?~OhYGHh(y_sKaNX^{PfDH~ZL zG4GgGwr?gLB~bf)>`#*YbWu9SYoZ!=fO8pk)*N}q-YQ|fJ6cUdlK4!Kb`ON_^tlH1 z9{1N-7f18k{sOcJ>SnjAvETM#L&eb{S;tl5Pu<%d_A0ZoQvHf}pqC+{l`J0oLGIsw zRuAr%IHzN{-|hb7sl;q~29QZZKvEIotRG+W?TcOhdp4i@NThtxNw~uFh_s@YWqUu_ zapDUR_=bUKi<TUq@c8UfO;*uW4Nh`2$CSeOrM=|oInAZ{*Z&J4oZ<pZa7I=IetHKS z2ufrNprzhF1<DqwOE(Zlpf-{Ay8Jy}*9VW}+i&Q5VOc{<!%0Znu{|xS5AiPinff~P zjJNsPaqQW#Jzev%-Iws3lF#|1;*IM*{bbe_3l@~tfFXqnzAe6;IqR0M&ZBXf#^Z!q zODI)y`M&SU{|u!E9G>&zyG!9UgU5)q8Jk^We#c#+%I~{UikU*7tBQ3&T9CVGfQf^s zD)E4SP@+LS<mopjNBMmid`G^kCXetv(35{X5oDXAg=%c0OJ)h)B7Kx-ZDV<DIOPef zwF&QqoBSo>LXdkeMC_EIJ}(X23F#X_eY`HPUXv1pjYAdiq>6sbhbRN|)Px`H=3Z85 zUEgRh>I$4Xt}0d!<@;7_Z#18rVE`Kh+vXIIM_eKyE=gh4Fn8D*jLB>V;V5CS(1n(r z$K@lpK-?Jy!bN!agr^NB;Io8~HN<2XhT^ps020^uL*J)D<plNV^=Zm53jy?)WI=U; zus?*j+lqM!2W>$A!01;XD2DMj56`;@DRVGcFz%27m5OV``@kZA`)`M@4~O!!wl)^u z!{^wa_QFwrVnJAAcDygP!rp9W_t*>QbPy08AbpJ5h(VrM6qgwYA{K*iB|We)gTjo6 z1*rsPS|PzXfL3J~`~={uiS4iga%fp@_Fatx({tJtEcjWnU+cZe0cyAq(CSFNJutp- z1dnfk$Cd`LM1cZx&=DgtVhIC0*uGHO1^<BwR4R^Z&*&l4IPg?Iei%ml$ml*Vh#Sy8 z{I@GWmSgaHBs@7{;LpIG?83uP-hZwUFt!QXsRBulfr*f`7Q-2wU8Sq0pwy#lTf3W) zsi9wXicJVjz~kk>WoXtp^S~hWfyN`+FM*K^;%+OM>MX}1au#70=u@m4gBz(Cz7(-b z=jb<IpH?UOQ5z`6!(<TS>t+0|$m!Tzpp5HNL4A^k2S9>`>MDkBERc+T{pHklKnz^R z9B8@-rkibTF!dOrX2qkWBNql2c=4-nyKSI|WbL4baVf{Zxa}kB$2e0woG}_67Ua0J zyG?)-_*aNy8t<)zXaH2v#XgWMM6gt3Tuvztq#{YTJswWmm<Pwg#`{29=DdRWT>BQu zDo5sE(Y6}(xO{pK2w_AObE$UTL$_8(4tSjS+aulWZSh4x!>=GpmjugJngNHj<OutF z;qHTvAny-!-hvJ|0AF9~`u+bTtP;tC+U66BJ`>(dhM@+gZ_X^`s*%6VCxr0uf=t^u za{ITlVX>8O*nA%4gQ`7CD0#ml`6_(S`C$D|`v3?X7V<_o=S%Jdw(z=xrpq2HK8%rY z_pVhrrD*lR-9PUns4Wde%-vMW9TgO#26`%b0M=qt`p17DRz|B4ql2ncF(i$^BBBW6 z1LJ$nW8|<8l`3ulu)*@cTZ-cRzL!SI@JNX&7!izju-T6O4GsZRS;>-}STT}W^S-bc z!CvF4P)YF6i)<C~2Mw4w^A3nlID-S2;A%?26BhuBU8zwCW@I`G<){sgmtOhEfW-3@ zm_i8FwFp5!oL@SJ!;yX<u@mGt2Ni<b$y#|(2%^QKS2o8emIvW^7BbIy6kD*H#U$!k z1WcUjmgsrFXLdAGg?Qz^0#;es8rJ2Ab<B|uk(0}4!m4v+;E?f8xdNaGUx1OTt~USv z&lv1jY%JFI>rC$t&X7vYRs*TX*%0U}$aAohA<8aHyJM}2zbwGv%YvXh8i80-4JH*C zfOYI2fjlby!_&g^p0oiM)xpbt@XW`BnO{OrQ4ysbvl=|cC_#8g#`@o%?!PPsGlB^a z4j@HGOCE{c(J#ZH{Hww3vCe7Kdi6Tb(Q_5sA+=%AgQZ`Q!d+}`AawdxRHj<bZpiyQ z{(1hjnw+Y@8c2!@^KOHpMe1knw(rKA>$I3}t~nvp;xRHLjD|~|eESC#&L@z;4`(S4 znLB*_Kahv0jpSfmLb7&Xa6Qe>e$<Dvp(tz6-@zWEL*xim5m=H~+{58MRnBz$y`z5> zVLK6cHL5b@@O5t>!C>iqJfQ+zxfE9yNMR4)E;=*-cfYSb)^PbCN(!8?c<$14M2leb zTA7ufph)zeLK>yVP_M+|(I-#<x+Jc8Xg(^8e=EJyH);oiNnxS$p^cV2#uWSe8l;L9 zqhMhcP)O*A<owu`KF<0D_|Vt!p;o1hKl3jsUWyGXip2#23R8GK4BoxF9t>%7$x)no zsNW{RPZZ`q4ZQgJ>fzqF>r)7GvQ<p%>?G^H&Hz&rdh+T|+rB9soZDxQHFy`iDy>_U zkx<&6{LeQ1v!RK%Wog}d{>=2joci;sA0%jR6{*{5j%*wui(Akat55CubXg0|h&d5# zGJ$<yO|Qs)?W9$5xprXNJI;47f^KBZ+Tu-b&QxzMa(?<JzJAk;V0XIwK9ZpS*mF}u zXFLM;H`sak`GFnce?p)|nF91d82`Lut~aZz-SqJDba9DMFvJ^sWy%dpvonmP5B5df zs~umR(S3IO%!8$;N)&4bw{Mq-4h5+gZA$T3hzV$DnXf((FR5=!KBwMx*(x$dN=F4a z>&q8=4!7=l)4gKku}c9;(W8L5H-;YwniaC)5+cNqmVjWmrHt#?d0O50@UKc2PFJv_ z=yOP>JUrEDwYkn6^+x7Sv%Y7=n{BvK>(H0X2YCn`5guybv}}!>fBs?np}@|HOI3-T z=+FW!oI^y@0uT=7KfeDbM~G^TZc6F}xfmwgkX9LE(GtHms?QGtmC8T<xF+F1%cY0k zocaX$rHDoY2LFf&B)rcZC3^O>V-IN+OL1m;N6Njy+B4&pIHGT%b#<V#m%n4&kFgjG zk@FiM*u5f6iUQ5bDr&l@&p&_zY|>D`y}<QAqktVo{NU!{O7#N}Uj#ys#9B=#=HcK^ z5R!yu(v1~>FUyLpECx8k;w(_@hCAqne@)SjWSBFVM}1Sam~8XV+wkn1u|9Y6?||PM z@x+u3Tr!Bln*BTZ6#*FF{qjqqP7^6X7r1}P!$@gp_@dq=i$K}J#1-RY?k1=tnLM62 zL~5U{jZ7C6K8-e1+ofDW0lmi&ko4bHS`AKC^F8)FJuI$x8b(weQ*6T-I`T9f$TT4K zO4%@$9KitiA<rTRmC)5z$)ifl)9j@a5Zz$4KN{>|jtcX=MDNRd34$7er`%-#rCNrw zJb~MDXNTteo)(O@V(*gKhSJ6gob_tW5%|D;KzOfzGNC{sIBU8W<7RRZhEDiKT`4Pl zF}cVJfP0mk7$nAu1-a5t#(jv;bUHla4&9l~4M!IbfdR84q84us%z;ziyCmKtIC^Wb z=TrOD_TTC&P+@63D7AoO%`Pdq>U^&_(#c>6Ec*>*CI%Cs94E&;9k2fw1%Lg)SMbI# zN?3zbQuoK3XjRS<Y};Wd*LYBc--jlp=RtVo49cG_!)qt(`=uCtn`(Q-{(`?jlEFD4 z#x+#xp#)SLmKmf7On4LtVel><<HHGe%|XY2LCax*xebJie5f>!k@bR`gwZM)P%DDM z^1}xfDh-j4s+{4#rp9|7P_%%`g|O%7g?)*Xc?X&edHM;?x=0pGK?>;drEuICIT&8k zfj{ul)ZV}-S^ypwEE3=pjd=iPGi<o}cyx(s1-vV;@e-v5!)Dz|Z^2kA6H*4Q1usC6 zl`y%ba4@NI0<8e@I~{4QVw{=vJc$tdh=YeMC9~K;RAQiiJk}0~5poekM~L)~S^+h7 z0!=$pR?fz4cxVC1{Kf&;!%f)uSd_s0x#==oWXdL?>Pv!QEilpj_E43y>#=@$jpU3x z*Cx6E-fp0$ii{LzkE4=giA#X#iUK2!dTb=s6(EX<mxE&U4VYXIiS<G1mg6&^B@jJ$ z<!szFHZd<a8Xjs~3J!}iOpBuUQ7z8xVJU##C4ry|QP;sTZv-qOB)+Q&3?!I4lx9L0 z=IK{iWyG9DR=o!0pLj;{+CVjmd)GfU{7;j0sMNNobzk`Y7gOV~o;YaMDJ%LI%#^I) zm%crYLLPRwqChI+GzNSEvd-QJtkGh&wtP-3OJ~^&014fIhcHRA4>7m^#@v$lCqH(s zu!=uZY8`xq!IKHVAD3VZ$I-xMWs3$_|MlX8AI_yU!odXQ2&kKLYEy=Q+0$StI(KR> zGZ#+C-=cj52r#kWPy@~uECrH=9GQM>ap5JQA_5I4yhkCyfi2W5Kg=$tlSf{_Y#$yR z?%sqO77W609@eZLN7RLqO1^;Z+jkBTvR;N&LyX1)rQxKX_WL${kW<%rQzqI;0{(}A zx|I*`SVK(cP&{tMVvgd`&0mavmj8pcrIepLtG3gD1_5O{jUN$KnGgGa{4;PdupkN0 zxcyoS!aRs`pAztM7fn!@Y`~h&$n3sjGgX_X>QJyS9$=kdX*L^a)?zs|M>;o=JgbkK z2i-Y-1o`o^#b9nV7yV_$%ny^Csi1RahoE?Y`n~BOTD!3*VYVB`HxPbcdQX@-LP+Q{ zU?H2HO;oOi_n%0YUuOV)@;F3=*ENH0((TBcf0{wXGeO*bun^A_RK+&=l=1gbMbSkn zhlPrmNa@m++E>(Z*rn81oLj<kjd0SL$LmUQgf6AX0-Jdl0Z}3)fm<{l{Mp<67B0+O zF1Da>Lsl<ZxKCf<cytJy`Xf9iwTz5+Sj-M-7%A|zp)%|jsf~T+CwI0dw|_YgZ$~11 zF>+)*o4N&l<VF~V>TRF(BJ2wUTJw!2KYh8RW((XNWwN}RvOm56vG4DELY~oOybCXj zyUE|(6#jb4-i>?BAEQ!6)XqQs2I*`@N8bnrUfD2=TFK7*!qbj41L|VGRkeNOk5(yD z<U@d3VWtu3W0hc(!x8@+=o+z@y|VlR#Kmzk*lkfH2kG)MSZA(#kwZ+FIbsm2m97j5 z3!J$_tSVF6^V-=fD}6?8fL`jZC*T<7Actx1jEiENv0s%={6A%CUUoee==1pWKGh0q zEC^FRJZc#U#Xy`?Oy5X67{_xDKu`f}_x!1fXshf3oQeQ$!*9m1d<PBB5jjHDw!CkC z4_&eG7mpvJLgGKo2OSX3GCY6^ZG`wAe~F<Ez$&8I#q0`=sm{Sk%Az<x)f0radG>!a zEx<;c2Rlrw0C2YkE`7KGk_FgQ0UBI&d6@>-!82VANG|Rpc81{v_!dEav4+<-{fo}B zEl}VG<Kyt~qs88tmE~{6rJmK}Aq4Wo_2kBU`JtG@D^|}~B1)^k>2kgm4;d5(zW;pT z(ZGLOp?y@O*5@DD)UEYai4&cMH+t4A4P`=}hyj(%IcNR5PWh6m5@Rd|-R<o)$+;lz zHZ*tprQJOI*I%Gc?6`E#HGJX!V(HxDqOP<5KPZM;ErFU{fN^6GM8yr;QbI;{sc}#n zuA(NgCB|2+3<Pn!Fow0M6~q7%xy}%GMDd=2C|MQ)CMt+&A{KX0kU``&GyR_L>G#L( z!xZN7{=DDsbI$9$Uazx`&?%03l5Ict<;<#_q($w9?s{)Wn-N>E9W`0&*yOU!<|h+h z4_{o98dP@uKY+(6ZJG{oTZO$-vP1j&3g@E@1<<5fA%}-7wI^IFYLuBen)tZ*0X@;N z%1L_iOnaizhl+PV({9dec(d(5NuFkdgT3a12oCv13|ofwhopuk$>q!RL0b7e*nziJ zoDLk0c^@f@p$<>MbFYr~AkgYWV=Z4_-n8(!)L$tWE|0QN50$*opc*Ox^P)FIV;WAn z*>Lv3;>(E&S|Vs```se@xuuLJEPfS0(Jwb{Nt{3JJf}5^UO4dOdqU>KVJGu+e81bS z>TwaLiX5b|(p3GEpa5YSRZ#6IOlD||!S+LJ0v^$z4ARss6|H}`^4=Uj4(S5-ozPb| zt|&WXSCxl@&t;&^!~b_zIdf`gs_6;MT>6X@^uAB%l3`BUqm>jJIpW{OCoxRug<K@U zggWB&|AQ&Y2C4BM)Ff`IGM%90<F*~vDje+x7Y=Ww%PsB>%F;PpvLWoxO;w;^LY`|j zg{AghjeHw75|JR5XCr?Ue~P_Co<~?UV%rIc!^**qmj@D&n_fw#Xzzl02TbGQ`&x!f z8(<xM8;XXKcje;qF4Io%PBy<5$aS-XPv@t>o^Z^c60ZGOEy+VTs)p$NlE@4EHqm28 znu*uWT8a2@18J+2e$h9QMM4j2ryRhOmTp-H%_{McfRJ7*q+d@Ro?xKygx;8@?^&Tc zJmM$%&J^M@&1ewhG(!gmPgpe512o_GtAWpF*{AR7K*3xlIXw>Yi(4YPm@;t%oTM^s z=3w$o>v$((`vPb2y$1xLGfe`N$EquYJepoeFsYJI8Hs)gKdaCSOiPj3S~)1N!|3{L z6`gs@q1M3)qvf}HUUL(rDA*`UOmbXyPMw$LPO3Rmm{$n0==1GWj&?-HS_n9mqkCq2 zh1m`ot?@W#2+vLtU?Ttj)h)aZ?uO_G0o`<7)2KA++Bq|D8Y$yC#@yK>?dj|XCZz6` z&oz&dl1u3YxdLV_w{T(E{DpTnddNL;PGQYK#18a!T16*aybIm?(P}Qak!o(;VOEi3 z0^Xt=mRW-^Rbu5VjQIs_Iz$B$S78Bj&B0#bA}t3NH12U!-u9Bn;Jb?Z2pQ3;^mm05 zj7Ts-TflQnn<x{~NQ?2?Q_6OcrSv-&x&o}wuM)y2pv9fz`C)7Q=vxPsPSrZK!2FkV zh!<d+s@=vEfEBjEFcJ)RasK>0DxezgM!&-$PqSLRpsz}i(fadf7X?^MFrIr>t(77x znAN5B7TLb!#SYvsf^nCV#ag|)g_3f(Gq6@6u5&Q1tS2-YNZ)}}0kSlcHbfk(hJYt- ze#Wc6CDc~UaW^|2_u6ERUL-Kwob&tFveeLBe4E(QVb^X~dTWIHU+Ph;i#b;gx~SgQ zSnY!()Vy}m@u(Y-bOs`kGx>jODwff(^Pj)7BeINz5vGgZ1UsJ<Ut?eN%>|}BNMZiY z=MPSAtJSxH5$x_M7gs11-@1RY;T{|aTj~!a+ZGUbO4e5uM6+i3%S~$G-+XL(9z;9C zajX8?(O!?N{)3-<lac8%_rcxp^-rWB@n0J_8gAF9j<r%Z!DseqH-COm{vqe1_39HD znQtAcIK4pn;a16Yt!i|bE*rRg+p>+ntyi56cp^>IlA^jgk#NI;rm;E9C3=@fK>Tkf zLH`o~t4qLWEDQG`hwo0>$S<S8m6j8ZSvJ@1O#q!j^?;1R@k~pR2pExiv*Dn^MbssA zFz>A1P{f*7Mc<Gv=otI9Cc_~;)7u>R2zUX$TjqJOH<EH-kSZ0uf2RXb2;+NqOSZqn zXRBa3t*9q0E}cOG2hSlZM_>8ZFat&BLI(@YLJ+pCa2;fYE7EN;f@qj>>s-Zg3#(Ar z#lq6E@fumj9+A*Xd~CTTkLD|baCfd69TH&TsB{e}N1Vf7R3qzcd;^2an~wsP?t#ae z4#(P9>Xx%(+*5?Sk!p%GlpR|G(#TxaO1s^fmf)2O-~=6y_G{zSrIjM;iKGJ}h`CpY zoNg}S>m|=MRw=jzHEg}kym1qZaeQD(m^8W+juOutN}~|byr2v%p7ar6BUUlkp-pbA zbeZbL^*(!YV2ria%MQ{X3T>}hE6C5I>t=9WrYYa}{!6xy@QxMd!3!c>@bn99A!!PV zo1U(T&i(Fp_ZO-18x`L67Iz!(u1`|xQ?A<N-mYEO{G!xjQS+{4sHQk|8p8jnnO~hh zmAaH#5CuZ!hBy~GN`N%o+m<&t_gOy!Q$?^wX}Xw3imfu&NJnC0RMJfAnC$~StEF|C zQ?b9coIEKEqHx(q{J<;T)(roxe2v1;QU+{I<D$D$W22a!eDC$~C}q5djJ2Msfpy%+ zc*bnczr6X_`Oh5ojVwK+6*s;?!DAl<IsW;f>CmL6h5E?E9-7{*jp`Wc>Cv~2e|RJp zR8sWo=?F-BfULH_N@H#JX*P-eR#Ww*`i8z&?A861uAiOUW}U<*)8yAWq|}P9`bm9B z`PmiD6hRPa#ol-PVEu8mT^00tUa>V-yKHhFaOPL2eKT*w>}}guy2J7C7b%tA$wU#T zZ=U7J3X{1M#=7yep}XRyY}6y&8+i!2<fJndPu(8gd|X9AW@=rYG`f7(U|%iHi;)N& zYYsgR)?|Fd1z#5NjHYHhJ6`1>C&@3S-C(#<%F}>PA!=<mr7I<-AV`=REldr}1jCn$ zMC7iLNZM5~!uEqyPU%M%OJrQHh4jmgv7eT~G*OGolvuvvbO3H0#@bSsF=w_Ubg4Y* zXh)tmI%-u9X3~d>zPW45d-KdSHWoLIS;p$eM?Ogz{-#Ar1Q(Xwe3H@X2|gboM^%|$ zQy7o3IuG&`8^v9SYH7Jn<+BT?qSPUIeDHAJFfP1c`aMc#*xD=<HK%pVn_6xe8JHs0 zO<6RT6pCKwEDk>0Xdvv0!978IJ1Ok|B$Tj6cA}~Ki*~Z5t2_pwPBEN08Ey!gO23bU z?pZKUBx;x(Cul7O%7AltXmoKOUBLy3r^($}<@n4(a}+Je9PRTmt-l0RTvRW!y{o-T z1!2DI*cxHG%bNL^#BXPfzbAa>YDc3&MWVpc)%qXf=186kh(r}-?#bm1y4{jq!4faf zo5Dr~S+gpz_O)JjThB$n-!PS;=()6HjU7ybKyI-yrjkgl$r^`zFR<O*OB<8RsF&Xd z-V|?%b14tjhE@PEB?VkTj-Jp2p+hCjc%xiTA9f&4rXQ%=p@7<3PHUCjj}rxiBq|h9 z<$&y1fRH(SNMbp((=|Ps8WyiJ4^0Xg$$U2w1mfYsDZDNpKUtXF*Q)M@aJVYiaumAx z`1|qat7y+h1s=aoZ@BK2Xgd-mr~<3HU|F$cgrgK|PC>qou^UH(kNce>=g(*kW^eJX zU|@uu5rZOs<P+^Q-DFhr1dI932E@;EP2u(l2JS)8k1G^aDc;y4muP}evEx8M`Vp@X zP^rLEg`|i+-?>Qw8{#P?f}hb1BKLq1FBJ(5)vn*UtIxY;1_LxT)>B*-SWeD9B9=Yf zO;_<t1Nb(<6^&6xU*)}ON#j_q(KB5W<k2d`p0ShO5pCGt++Qhz)5MEAIzfj?D){<a ztqO}+nrJjgxjX69I1h_-Wwy+K2OE5&EGITu@_=|=+4J1zi_-_?E6_nxo;Tb{=YOG1 zrqc+kV2q2vl!sStQ!aa;xd~9&)iL&_k5k9yjMWZFYFewc12K#A30_rwdC4gNn$nT# zM@=@cL56&Oyi_MUYr4oF0n^)XQ?DP}zH|qBvip@8s6<(#acin;TD`q`AVRNOp<RCS zV3mX5;Qe}j?R(+tj?<Ldx<sp~n;2<uuuW;b))KbSDXmW^9U_M{kL%hCo39ZJ^FA|< z@jw5cmie~R5!%3FiM#cu<UL_%aq+aURk@tK^q(!MgZu2RU4A3!UxEyl(Y7pYpU>K2 zbI+;VV>;WrJ3vfHa6-uSrDwG?^i-uTQET1`{!}Y(8rF1mrso{|waT$R{mn(*)xTc( zY3siHr0bb3U!+`p_IYK0J(h-SOXT3G_vb8JRs6=v(OFvX8|~{WC%Oj;)mR;9S!C8k z+BLzZ|I+md+VNl2O3An20!fEW8OVB5ezhoWvnHmg<F+n%6>5^-X3v0ei<)x}tM1>T zM{V~jawtiG<MQOo#nGL|Q3-bW)kS7KwZ9krz}ny@$93I&@OjOLex=n5^N3{e(e=IZ z8}-pu3+<JLka+uz26lc<s_8#jW4yG*y+!gHSJ6@7YL`5x9VL?9_~9NmiP_zI*t^!G z%Tx;TfiX?=pm^?q3`Zd~klzgvE!-s?Nm~Up$vt#A+j6L5G8fu~=vL`n$;Uhe4V~Xn zK%W>3N*vf*G%cHE7vk><&rJE9B6oL*upuISh$oNj>GGE)?+_Dm@HR{K(2EkZHBVx% z2&@>XK86muyik_3)7B%04jmRjr0mf*mOl|pR95oawB!b2SB<q8*`(GKieFu1let)F zsuohb*?w#^_mz89cSDyauKb+THhs1%ZF#(N4&Ha7<saYg?*FVlRFH+GSO!dx6?SC% z7f*U;&obzmEv80K5Y%h$CVfWDt()I{>wUAVGA_SzolOrdS$(;A!p!e2LWtJ9c=MFA zM{oRRRF)8)pGWe7qu}NNmp4}xWLN&NL0OI;v=|U{%<0%Vp#xdPiK|7^u`(=a{pqmB zbBFDf+(O@kXnsqrv_^^(iKqMN1<64Tv!+4aqy<RpJv`>4Eq{#n0ED><GTu@$cXZjd z4p!RYkg~wLti7bX`ufk?E0xXC=K#Z@KOhys8T|UGjh+qTX)(ch`F+i<!Sut{P<Tvh zpPe>PF-6h->u*)o7;8ZtGL-5CtSDv()X4|ZudNRr9tr(Kbnj779bW_e@Zvf+qOA;? z@pZ5>_YT1XcZz_A?5y7&!<A06gln-DvrcLEG)pIc1=$voj#rDQj1Fc*oE1h!#;un7 zElm7Xst8Nt-L^!T{2=~D4Xu@F9)9IZ_Nw*jt9@#R(9sq5&us9vi5^!{4An#!Vh}FU ztnOV`;rNhLKwSorNpRH}cN2|jM6krc4j&wN;@`%Kk#(Y$PKYvrHGZh4m-d%jk%AZc zyuE_&LbZ|&9OB61xaq}8vTj)u@x7L%-naBWgy#@3l`a9r)KzPU`E+(njrK}}cenha ze<qu+LR?l_N5@}_{;;J8UNrLe{^q1iE@}XMg?SB3IswBM7ecvC6>NTrHXsY*iL5d6 zTWH5KABmT^2CX6eT|{TzFwuoiN)(LjASLo^3`C(C*Z$@2F4UM|Z97Eda)|p7V_p$t z2xLG8NDB#|p=xe<RG<~Yp2>9=SBpp#K5*x+T?>WjW30q=q#CbULrXTukKW;tgaIK^ zBsLM5LNvKY@S;0JU#p``l1OdL{0Hzz+(J0LIe4$ojv$<gNE>?z*hH-O0@C_0@D046 z81P`3fAUReM>Cm~I`r?OX^J*3lfZY^(HE@c`;`@eC_uj~Ak;QuB!d4MjeJwlLY}ZR zb8v=k6@@YHNL+_esUa_*4sHM`_=bvtyeJ(n6tLMv?W8V(GtWKJl<iOJm@Q>!-YQsP zV>nwY@N5>JV3}(o+ww1Gp_m=D9;6cw@<gvS%#X-``GFtX29N$~dbb$TlL^Z`^^VJL zwcf7eUMLk?SOV{3v@GroDj`xtr>G1U)jw?MDhV5Qt(TMmDz$hSUZZm`5L?A16<~`j z{F-Z%5QEaek|E{DqU0i+_6d6uk*6(?<y!>AUKSiq=rNRZ{ZXP55Q*jCe1}DkecM7& zNpxL&$lv?~JFc~$7W)*bP~z&+l;%T$j!xkcMg~yuu?RQnVQpOM==b49v~umM{|Xp_ zeAHWWws>=z)xew|)I{)4md$5P9HK8sGXbAfjW_@K$HuAakU3`-`w9ZKIM{=lK{U3f z9u5v_o{mDwt9ITs7!7xpqt)HI;9X5q)$*S<O})HLYMk!11S6pBFY+KO9pF;9++ISl zx`pKy+4~RWRWpz@9A2Q$^uDV&r}^Q7oE^2N*e|QP@@{@{a^sxAsnNsfe@M%72Ge5B z|Nhqtsz$0@lf0sg)4!ReIjilx%sxwR=0c?RkdyYguJwu1cMc&fa?NaQ@F+DOw-t8; z+duu6?F&-P(}NNWWk>81`lG}em8478|J*nD#gj+=E*R{YH0gc>G_qF)MJR+0{qceK zs$6g(SG=6}_^j>l?}6oyouV=wq%cr)aR-#=52gAq?uKk;kPo#=Z~ucVIE9L9=4+<4 z_Cns8_4LNmE7j(xTb2?TmcJW9rAvp(Huu8nc%kC<u__kKxybp3CLT@1q2(=nl{6)I z-q`gE*3|5>v|$S}dEoDp-c&V72Sw_*@WsGx;%FC-sv=hNgGGH(oNP8V%)yFy;R{W- z!PD8VJft{RBc^Hz5roU$#&?GwDZSK0{GI=7xp@R83vo#LTbM`-moon%YK2{`qtm+q zK2djWn(sjI3U28eN2~7mu{C+Z{(9jjW%>t`Fh^o3b<uUsTb;M2GN+Bh-`g6tRiFj6 zp1T>TB>@1;Sd86>@X>^|wstm*YK5c3?t))(;BdM_iV$3z!WRdIK<I+w*SU_5;umY> zRDG<qKAH^oF10<HFVpi2?W#nX0LiWKnoNI|l;kxL47{sXN)|PfOVcl)!N=m<q<bC& z7QqA@>ligm889WmqmZMRZapv#2BbGhrMR`s_4&et4je=z_i9?Ra?jjskz81PL=B|k ze{8+Zv`6~EgjIl|ZbGzD>$OW@A$r)E=$8B?S}zbkk%K$V;)>cifuO(wiw=vw5I~NW zrPk!sptl>wovfNF49n<~MPu-!_sC7{35g3ELyA@8UFIRnzIca!j-|1)SGz}+J+Fhe zr-KB!Ty${KPD%UfjK8p-@HlG68*njCYW9r(v+}OiJy|q65_p~arEnceUrGE{pFEpA zhZCy2Q!1gL%xYnn&D7BAxyJ-Wc<noiI3{Uv6UT?2|GdQakJp#qpTmD}>XZEGnS62J zRk`Q$Y&{)Kr{f>W8^TzG@y30}!+Gm@#_HCRTvMwxrWQwUoFU%{N%A^vBYFVB+4kV~ zTU8_H{`RAoK6s)K*)aK^=p}}QJvw6d>-zK3lPAyW=E+XN)@d;{SGv5A{`ga=aVxk= z*U~S9>)KqiIRrXuGJa=Qy!I}xd9IyBaK52_;btxA6UQt+Irws7+ZWPuJx-n?vjn@t znd^k1Yl3SMK96(JOBX-x5Ky|N_@F(<R`4I2%Dzn<iUPUj8Wlx&@8u)QF+y8?*xJ16 zBO0`q`e#-f<)gceI5YH{fX$Em>tSui^gQbXaQ`7=*#z%RHT?o*!9UhAFHd+;g78LU zhI#;?@DUV6Dc;cn>xR`=3s2J?3RNrEokLm%P8eC^PA8kB;)U5KHP&e3u)l(2Yf$%b zGJ6Ox?Rk<n=zoezpT>>G7?Z;nXIThDq#UG~2emj3$>UWz)k`o3VH$XA!0vVI<eg-e zyj|u?7Tco-7H<lN^cO7=mrFnNBip-t81r!wXhSVs655llsWk;$1dv_7dY&{+kNfMu zbrcqn+{Js4-NK3ij`m0WVoV05)MFG0vZ)NbqgZGiAHib?6H4N>qLJ6zgw+7fl|sdc z``7jqlzXU?+6D0xB~oy6@+Hdewt%s&NyWmP^$<J_9@|p)3ZlcR<|Mc#bi>t<<h6<x z>S5<3T`xaPbR#OoiElxM1WNr~?C5f5xJW)*9tb_PeD08V9w_se%yO@PM#_C6H_yk0 z;gPUU3Fd-ROb8IXE<#j4x$=I}iBj<~7j=;=fzj-oAYlB4U}rs(=)&csY+MwxXK3L( zu(z<ar*R0bCSG`MdF*hDg-$J~yr$M?Kv=LR9)x&NI~SHOFsY^3N%>KPP+?WO;#!-M z{)Fj|H~V<zUSda*X=%N*cQqdV5+ImNktZUp9@Y;Ul6}Za3D8II_ejb(_bbC01PL^o z1&(hEY+=Fxx3@67xG^02eIYlU8_z(NrnJd)gry-%|H@wJ;z_R+R}XQ6&uTvWTg3RT z+ebcgZOA&QUHa+-;~v-KA=zQ&u~Zw8b0}?kS`f>;B&VVXv8UgZHd#92C<ktKg0l!e zrU?+RV~p2w-qC^{s|iTi^j^7zW$6yrm9BqEHWZ7jmc4kTIAH7=_$muj@Rv!f$&Jv$ zPQ}+ZZPGiD7~AJ^y~bg2)LT<%1k+wgYIjqU$uPzEr}PN$tNMMmp57qOTqs?<eL=tT z(1s#m&v8}>wM-*t^$lPH!yA?x?v79~M+6OxnLll4Q@mj9KVVb3Y(I7If;nAIhYX*S zTGuAL1^o_ne%!QW&V_~-_9dm(LdCZz$r8&}_&9ZX!VY2aR)^;d8G04FFo(DcM!51% z$;0os2HXE9eS9Tp#pXHRxbBetc-UQjPXIaxb<-Yt>>u}qK|#y^P{c&zo9Azwa+^(; z$3r>ud>@n3zP$tF?kP~BFp*!U{_l;;+kay`T>6ydWu_KG=+--z?k7ln+q;6;{7bq| z^l=LC$mvcV+R&yr1hCTMy;PbR?VuU9KU&lmv;WOim9yj4wE1#794$E<nOJtIC2_v| zx_OJ(j0)Kcuh6v?(95miwBWBx-<n&a`=o#73G<KFqD)PXuk#+^vt>z#R(5Qig%Ksv zmD)wdD)-#`%GCS|<GxJ3&8iZiI^up=f4b>IVK*W=6_qPjJKywajH77kaVA3|w?Fp5 ze>fDDo!6iYu})P!4u4fC#fYoNtG&F_-CSI><KR+aQZa3)_v)r;4!FG7k{?9E>3neP z>N-=nN;VKQ0iV^V0PD`tGmyPf>SkB~K6N?<F&P+X^j^-2e_9ujfhk#F>$Qcebn|Dd zKc{ktoh;zjtsyC<>Lf2Xp0$mYg5rKixbRh^X^Lr+coKU-f*Y$8BzmT((MM{n()U%i zZE6p%B)yZBeZE>?T_<Vd#v$$4=0>&zMSqV|4(+l)P6_%ms1<k!C~05N(qx|<!|>P? zE3nz_JUBqv{-g{b3!~LCPF+LDNvo+y&Tuh+EGz20eDuQmKZD|}$Rs}0c{wMy<e0*( z-d)se`PVpW(tW*1KIT_61O!z1m=?$zf<#wXo;=*?uZzSTXYFhWKDh*VT>sy&zLVrH zS~hQtvrY?a6QQt7B1_sWxcHnFA=7Zp@YBTX+v$9Z+hYc|0Kplr!#5=2)H53rFUG(s zm(cHt3E)Dqm_QfhtIt}BMSVMYNS5VBaakP5zj6Qb8aSwnpT4Y3_Shp6tDBF5^pk;r zC`IeMtBWP-*r68M-j~EZ`G48>;x?am*LMB9#g+OJ?fbIH>j<e#*S%jb%#JJ?b0?(| zEV0-9vjaiHkF3_uCp0b-=0v=(4k2pS_<zosGq{e0-f?(PTo#fI3Y!#R6D<1w`RU8l z-c>Whe(VDaZDY|TKa|1n7hB$!3NWQ=*?^l*O`MG0vv^&b#rc%);T8YgUiwcrf&`f2 zaMUW7FDRbQR!ppQm~<PT|LZ8rU(ju1N5WY+gS7+w(JYuCglYUyscYFn18L7&3loz_ zt-=p}i-5sLqSzoc8f-%uUgpM>LT)1up5!b(Oo6eVdJz{>FcCWzri<Kz02K!g$f=37 z^5#G^o$0a_NsJyxN%pNs8gaWr8PQ=i>OO&dQ>Q5}hN}Sb?2(l$OeJXT3+5HV`yAn1 zqW0U^E+zpG?CvUf`Kc;Vq1N%I2=3Qnk+4#gOHN}^7(=ruJVbN@=i+@t?M;(~_Ww5U zOXeof21hYddpD4Px0{4bBBk;Ziu@X{ZBUKd#6bXb_Q?6>1??i?_fgJId+sD+h$n)t zURJ94Rvqxe$eB*aU=Sw2iZ{{FuV}1u(hRo;(V0*#v;%r0#Ob+5Zq@e#_x4}$Dl!Xy z5O#2?<<P=7h#eA{I;3-Ectx^G)G6%WTCeSCRbn2kAf8}T@R!1t9EokRovQ)%6<3ik z1Q8&{GEqeLUoTY1VudM$05Z;IJvoV;Ku@`(m~um!xfogGiK=mTVtl>91$?=O_qh1n z6hBLN74r<LqpJFc)0Vns3YWph*Yz^Z8OrBow7a807_?M@8hLOID@Dh8xwv#6ACM4V zM59t0=$a||qSZ2Nr;=0^*gEhqG>@+6$;gsxax@GoTDog=pkYhYAFt@9JUp^H_Ui}E zx&`mrI^!AjBZ-NAu&2~^ZcQP-w`|>Hr9&TFBw!2V)b<B`Ax@FYF>?(?ln}ytDmf(z zhy5Metr9)*H#9t^SD4-lL%t=YOTAE5DC6zZU8c~17~m7&8<mUqFRTDznY{<ZTy5Dd zE6hLHE0^@US@l(-KOPM_v=VC7+NJBToLndk8G2Lh{QG@_ruKD}sUTw7`eTraYMR=V z5$_DW_xiR7t1kS#qI$e58KKcDOf0nL7dFV_nItloNUQOGxWIgDgX5hEB<=}OgWYqN zUv0nEVgS9;o}2l-lXG3{;lIsu)z|2bZdc0^rq$<Y>jwK^vyPUPY}}Uil-{c9#Kq0f zaL*mNC^bAGqBA<AX0zSHR@0H))A}DE3g;kuJzfx_8cJ=f6w)CszTg1o9{s!sr8(Ut ztoZilzNe%1_0_g1&oBK`;+kQUx|#+<DzISej`>^D?}v1&i-oV4<7OxDF>fwkF6Eh@ z53L>jWtn9FBGK?rN!`V!a>$4VmreDr<;UF4H7`#(o^Yd08MGy7WDz4+j^;FoxR_E! z1>X6u>F?c-kLbS+I1>;aj)pwCA@ZA_3Yf&GlpRd%)+)`}^O}ocVb+xv$n1dqS`g|7 z-Pn$q!3Al?xB$pqqhKBR%f6fb`x`WER=zt?H@<6p7mik-S6>cHnZ*DqwSL4S{j+x~ zIdD8hrhhl}&KP)UmO^OMO>4t)E@vITttrk~>j_AfFf!pNvO^a;M$k;At{o|xXp7!W zOG-aY_|BwpRk0UVS&9uGjRgqong;;MdIt_`1`Ru(W|a@Ytm5b~#)Ls6*69v0fiiI= z)*_g^y0k|6fPLWwb88(?*!AQ=H@74I3UnR$aT)POW4NC9A!Dh^vn|YpZ-TA{PA2g{ z%;)K^r52`FWa;1|d|Zbf+ZliqY6ncU5OG2JCyYo$*As3r8qRNL(5oAxF+GphBA12J z9$A(ZG5T&WOar(`Q&#g^olCTdA4<F3NZp;HNN66zh`q{q<-p<Cm(*#m4^z(jyURVj zRtkHuI7)$RrMnkot3_gXbbZ`1mVJ&XHkZ>A&3#>#GLcDL&N(&N%&Ay0TmArW8porw zkklBmPQN%hT%!LGphlQcy>hRTk&m7Szn>f|PtrR+D=~Cx07mhf%f6>nI;5RsAwU0^ z`<Z^DmIZ{pDf$nsI$V&rgIhy)3Xa*b2MH!$6_T^Q`j1c1r4YUGlFxpS_n9cyN>p6v zN6RbjF6-S@Uh!Z#a4vh6@Y4{w{Hdm?z7AXY<lq%FU6)U37&6G`gmQPI;*jZ^N>(ot z;d<=mpXZ5DW7QA5=Z`|n1K>^lQ}V`5yL=v^e0W`WLQ>!GSIjsg&QUFI-4*<?r2?8| zywpK}qzP8|8|48!*$R(cFWpI(GTIeDCN$ZTWC>)Yzpf^`D>hM%o1vf<i?Ye#D`0&x zs1s1Mgcc%sF1Gaot=&ly;JL_Hty9|bki}_3$S1!`@R`j6#ryhB^fhQ@e<=;@esQp8 z)$p!^`(H~{!|l3<ZvweStEpAG@lqDEM@Q&b&;jR|Z_(w%&IFj9*!Y`2?wZ7gIhUD} z5Vg=+Gf-z5iPW4efOe+~_f*ZM@q8DgVMV=YC^0aIAsd}3mFJnFK;><?LQGIpx%lwT zqfy`sow}s}S473GCex;aDV1=#jQzAw7CwtXbrM@d8!QtYmIq#<%}$8&)TTrCr?6}- z7@gvfG8`*ept2Dxv5ItSq4Ee<+R*!+Ku8YRWKpI8X_xH5%M6T6%hNFJakCP|r5NNi z3;k)4aW}&UX*3$m;S!8qz6w2KQD)L&6PZ9ZZZ7bIAy=%WHv3A=H-Hr)0;7&FnVU%4 z_E16Go$Lx>Y!ZU~mO!s$V$z|oF*Jow6E(0X2CB&|uo*_b7>^BYFK-EYF8Q`iy{W#R zPnbMs&>ZzJcsd*<;2Xl22zjnOgzR;Y4B*qVZj54vXCr`#FvUm}l+&awW@vm;B#b+y z-hb_1wVysA6GYn3T!53cFVD@AllpOi*0a^hBv6cQ2fFsQX#KzJ0A+(52R{a!@I0RY zb9U|n`RE{qiai|?t)>wO`|o^i1R-=J-xC(OWE4xCatzK|Y|z8y=9Pk5YHGB;LjuQ< z;a_LZ;6REb%gs$g3Ow8GmQZXcMlNAfcBVs;ger%gwc48=x{!{>`Ro_9CQwKFpu2kK zNZr2^<wO52Y2I~76ksdWy0<Z29J;xx-}$`WqU6Yr3A^nT8(sPPi{vZqJeY_<d3?n4 z8&awscY0TUvsT&v{L59VKYs`_p{o~{Krp5<O3a3l9j~hHsDx$Q$&7O4qtkk8jhs;P zfqQ=G4x3*;<o1@1lnwWeGFEzcqugZ7R~CgMaZ9aoiMnsByc~A^Ps!?m)p@4Y7iVso zdva(a$>0&d?pm*I<5E<mP7w^jY40WKZIBvO1hSI2j@9lwDpJIrmP76vFK>9R-)Y+) z<7H^zSkk!ftIS7l=5}#LvsI(?#@fR6E6qo*Ey>)LBg@`9GiHp)hs~POB?Tm2s?vpj zEB*3t`<CC<Mefkg?DhYwrr&*O`fSM?^lR_LJ?*s<3IRqJ;7B3QPUe&(55)fRNHXG< z<OM@y|0mM&BDP_@v<qCKdQ3B%ARbl;p+^L^F&81w<d`SY*PQQ;m!d4oLu9d!!k3d` z6a&2iFemPj@70URUbQIpdZ;EB+SRt!Q$Y>W0gA5YWKAXkU~u0aclXFxrOUWURe^&1 ziP6mxwuSF&<d@YekEoh_{q&?DCFxF>BsI>-6wPZZ9<(`l#v{>6lnjwR9}tvavViRQ zZv9RSttY1S)oT@oK;Ktw3jdTO=BAq7$=-RC3oV=Y$3wvC$kaH_CNl^(5q=<E(bF+) zMjBjO+MfDyL1OkytlX^KHy=cZS)U0JxKvVEim9xJ1pI{@G(~(*j7b5yyE>knLINrp zY&0R8Mxd#NM%!fi;eQ|$yV@LqbbDTEPTsMY=!_)T)H-ug%si5KeEOMAmH-Ebu$tuW zcFeae&>{9>5go_O`j6>&=4l3ES(SswUbAhib4wi*2kWOXA$|3eM?9=ku3vW^jy<`2 zq9LJ2|L@_LAbL+z$814El2=fLA^$WQNV>JYcm21ghgq$AT+z+HU^AvE*Lr>B^<4Ae zrty`sZ!Sv94=twx0w|f)9e*LZ(y3J3bX>)`R9ngX%bpCfs8ZXJ&eePRUX?%U5PFyR z)|-0Gp~I1-|61L7I3KA{chNOM!XzQ5o7Y^ja=h`<J*GyK9dJ@Hc=|H?mu~ySOZC5# znM{F_#kI|&oYl1m$cRO4@qg+wqM#+=z*IIeU6%0P2t7E#ZUDo_E9RQ9jOA6((HH0g zw>V5^7r`3tJ}?)gn)W)bo?0)G7H7uQ)5AlnkV7v}$s_~`9X}~o%L3danc*DWTTmsg zE4WRKV3LoB>|Qca*)f@$CbxFJ+ZaJo&)2Z;Xr>7N2(*hb0Wyf9@9LOJ+!dp0Rib`* z#GNE<^Fp90Zaw<A18LjM3h~v%@o~&4!XiOMMBe$lG&7K5$VJ8e;<~Qm%MhLjI+{u@ z&rAg)V4nzr2TDfR1wexX;5_qI2^{F%ExRl>R14hxdPdFJv=%@XZ8DA{Mw~rNa22Dh z#0`PM8Pl2rOvZrCF$_Wtyc#HN(h9Xp{YQwztc=ppw=%6E6lvxVb}XPstd%Skc6(u? z5lfl_3!kQ_3KT4X15OB7w7H2}SyC}}ZCK>mkiE9^o%bLvx-_25DXbXn;}i!HXEDEA zVDU%3p18*$r7BpIe<%2!uh9Wgfn^+IO_>)sw<ddDm%N$IInA38ydqgQU2GN09VQ&u z1xK(&b+4#xjO{=g-^o+iVWEQ_%K3T>-+}5;!2)#}g25KrN6WGVn;wM3Q`u>d(+}-0 zY%%@D-oTO{%4z|JRUBF_%P9B>NqYqS#360mCGeXv=OQ+nE^dldw5B0guEwDv8FSaf z&#FW@S$%AST#&m;XjkP<5F2Nkbl^|PrpsBjN6$N5c;fIqHEu#@+M(#lG3e(wj8+>o zleRk^9gU?(=;j~GdW};L)_yzm-jj>&dz9dfXfS><DsHm;^x7@ER#j-B1pf&BpC4EI z-OmMMr9ZqK0UMD#=o`(rx08Q=Yrpxh5#7hzFLzH(Q1rg?+mX@1!H(2b6-lb0N7^Hq zAE*B*nV8|vSXqtf<W`N*z45i0WcCFen`NgTx8<>pmASg8LGNn$cmJF-pt*H^t;6M~ zGJPg>dO|B19Y(OqN={5w8XnN}G?y*AFABk=MKp>u@qFRehU2Wa{$!-x1>)HHKR7&R zd&c}~TyX3f9n>*gS<L_Ji>ZoxOsZ9*q;yz$I$_!khW+6n(84w-E$;60V1PI%PsQD! zwv6ci>37TH*F;NAbC0~bb--~=jdsG!D^Y^YGS~gn7iRh|cvZ=s3mcsURB?K)`*5r& zJ<lmQo{TbuQ{%bx)h#?~=1@3JbHDbMp~KL*^HSHAu6bQQgzU8B8t;CY79?r%iwQih z_k9O_ZNIxUVPu(`m3Nt@uU>wE)4GDOD=yNrG#S@=CfW?ADFQiqu4EGN3wwMZ?uv&o zo&HopPgatbh<Yvjj`{eZrJ<Ns7C~!Gpa;OFNt^7nmIN;?guEs3LtjNk8!9Wb0#GTp z2FhZ`T_Sv_pb(1W)y3*R1(mJW6!dn+{BAx`lVd^)Ew%yItr-5&l9gSqKl?3bdxf~6 zW_3~@lKJk3^E7X;{(sbKl9enkt3IoPsd_t~?jytE&QrRGEPevR;!Btjxt9-@CJ9ua zQEyioV<$yZ@Z>^v%v`wKPvemcp)1>e%pcd)R6-Z91MIMK{mX{7K8AT~XyCk_d^Q_Y z7ybvv(Sh`UOL7feUTzXz^_NE@)D8qYhF*v6RD<>AlfYI6Fu%u5>pw%Q42}74GDUQq zxSkxJb=w|YFVeZByzF~#w1s3$J~d^LO$KUnZqT3`tH$U_PPv_fz<IeK&HaP=gxv9h z^yL(8AJ`VUYFq&=q~`p(dqRZw@pWHr+O@GhcBZytHoY@-r?`q^eV$Lf)BppL+k#y@ z&Tzoyr$xrI9aO>px4-*J#f?grt)KmLra5U5@N(5l>gY-rwKg<u)hWO&E?}}z`?7E; zgARomA-es!C7T;yhVra0rC;xaCs&FUi)fxL8~dp+?w|+f|E2VDF|s4Wq5-H@>C=f& ztI*VQ#-y1+C{u)M=00$%otEn;4RJF@Z<wP1(pik%HN}PwE3RYGS`{w*J;I+AU6acA znIEVxJsd6@9Jqx^c$elSfjWBOqR9n`)Vb>-HjwC}N&b&G=r7Qv0Ri_#7P$?Xw@2<S z)4SrnL4p(@$HQ}+#^VrVT?_k~2-KSQra@Du8XXKs=r^qu5Z2k;q+DIMFklycm6RV$ z=QLIbA=HwVLhmAXs=^K)yEdc`L~*2DTz!IRR0L{(k&ua4ZZ-$io-jr7b=fTziCs#4 ztmHhNO~S~NeM(yaJ8Q~M$wqBvu<&3+&sB$eB#xi@J~0Rt^4?kuLwgDm(cByNEPT2^ zA@2p}VUKVsn6WKxNrDPPD&@V6!i$I!M)-1^rTpTblW~hP3ePq{LjpiF7<adf(&_BK zvYSoCt<P2r3a3utM)fLU>Ze?YP}MLX4Q6sfYkN&`QHvHKzrT*qMvBmy=PPytwm({x zaGS(~8os)MljW6^*{WPP=}s`0VA}9?8kJJhiJU<OZtuixQG8n@KdbmUaz?xurz~V_ zJn&|Ug*>crp9iHYx}F~;+l0waSEZGq)KQs^0XC-Cq#Q_G#qdAmkMl&6?hw&T6fkiP zDGYQGbTDV;QU>`?I2N>s&lb!GMFKaqe!6U5+PK}`zdRz_h=#%4qy73*l4XP%_Q(cf z6|MF3$rl}e;Ty{qA`r~bMbxU22lvBHvG?6zF`%x;=85Pt%UA)uxei*F7wibNqh!bI z-~W_+{=$dpzkm7a&$f3}Eovz(!B(TH&&tTNv7dMEi2K9;;ZFWKHzEG}hifOPqwh+G z+gHa$-EV!aBqwh6)tmZ1T$p?FU|PTXc=Jo)nwWXriDl=L8kEjWA(0LC-`&i1KA_8E zJh^=r4m#pW74xsW<LEQuyj;8HX89Q-5BxX(<k77N%3WUf`H2E5^{1&lX6%cM{r&E9 z9@Nkkr;lzrS@PC`aPQiR;M*G}$Wn|0o?#tJn>HOgQGSN<Yehg)IFvFLkL_)&&e`Do z)s8C4>3>JZxx#c+`mBpNo;|$e@G@mjMKs0SE5*{|wGQT}3}9+<_lF_9%e;R{Kli=% z$>k!n0@es*N_X?ET~G?_NC(exwG9h!04VbxuRM5%w|bBZ{WJXSZO^r!8y(yOM=N#6 zJ?{uZ0m!PoyWeX73|>3)o3F!G+Z;Wgq`IS)KE8hRRK$OSp+?Gd8p5M;7sj8WzHNLv zsbP_bdW2l}>^n=6$L#+x<MA<21ti6TUCAk}H?Q^Iu8iA&Q;wEsZaMJk-o58v7}j*Y zu(4Ml32Mi%msb^JzMp-#c8wrL!%2}R7Q)1B2z&$4ouN5<ucaCf;cejG)%v?-c`Q#7 zBT1nXClAB~b1yFczbBtj!c>zFb^f25b9N4CoS5I1*;-HOHG>gyJ8kDs6YWc9^k%I; zMUL;QlYrArjf(>VrCYLi4lI8sW^YM*CzQ&f*?JDz5Gg@It9Elc=Av*l|2rFJ8o*E7 z;eG`B?5`8e_mUhsikiksMP^|ANr`A>WY%x%B7@A=Fq{D&@UEqO*Kk#t#v6bZbUvzb zo5n`oGb3$?McW5nHA^F!74)A{hh}U?Txy*VK6|n*JoGP1G##~6ULo>bZSH=p!ezEA zUnm*~bmI7y?7f(k|KM*~6gC_|J9gE#AgQ_LiT)l-F`jFj3DlFDQ`0}=)5Of<`o+d6 zR_}U2*oc$UmeC|0`nHeV!NPI}A^h?#6UgX{^)n!oB^_+F;f-QKPEGm8)S=Ek&V9eT zmv@!3Hhm{-Ap3-#WUgQW@A9z%EAe+8eMAGo1!u6Mj^Rf}I4t|(PW@gxJn_P4EnicY z{`m%ORLaGM^ZOrbPWy6YQ-R|Jsw}!=L>{_N|L8idQb>8)2jkizMm)|b{`f@G@f|`9 z0iv|#sRi9_*|^UmJmel_(6Z)=uvOM}Xidr9pW(8~A0JrguwCd2b>U(AdlaEEJqspC zmUAeDB2^ArZ{b4o4W21lHPI|o_>VC0hwBtGH9Ilm;tY*U#0!?IS&ZYDLB_*&TVmPS zs3wt*_HYkD$0?k28Jfe&Sdt*h2{L^#MnQc%(}9%2Uvk=j<c5o(B9_-$fGsn0hm>o? zURuUYw=p#?E8-dz2sa`e@fNq?oVapAfpA1%A+8%7!vw;O!7bF87+z*pm&U@mNa!ih zYS5*Oy9rOoo=C%v<WvW7bDYWINeICZ{WOR`TIGzst7ED}-q@Y@3|`T#<bvR!UKB=G zcFtOfuoDTs#$z!oGCrG*R4mg~fMbFJP7|pAa#0K8FCt^8viSGgv63r&^=2Gmgi8v3 zdfpXtakvw#4?bytHF}0LaEs*2n4j_`!ev5>cy06-=<jqEO(h4Z@?=Seu~rtlfy|q7 z8TFH(j;s=4bDuU8JLoRPbig7p`&lY0`hMc3%EKX*PY@PL>eTL_4ZLjKUnSf)b$l2p zCXwiZbU3wj?PT0qtEw$nS|eV^Us8bq3q?Tz<(9F+GmAF9BefzsbA_;3p{JM6+>}+( z!U9M*!(=_d?1B>o^yDq0;^p1BB#|)E6W{lwLGI$hE&fWrLa>fpR5N^KX_om+WVx~; zC!*)IYHJNw064%NS<`44m_TL7(p_{?liQ$S3qn@Bub-xyZUko3Y_ozsLi12FI02)3 zAh<(YdUtp8!RakJ1^k9<RKxnVfPjjwF1Al~ifGY0s@z_<>zG>8@Ia;-?hKdi$^BEZ zXdhm<zYK+$|Mi$Jas9hfrQS6NCVLdC6P#CmRho8XY*@0%s~BN;W%!%lI_A|2%R9#R z`a~LTmvz3?*ZM-dt&iL@Qy4*ngay<%#W8hIv?Jd-H5yk>-cVeklm6|(8reqI+7)kQ z7o2&)i^9=Pu-HEf=y%pbt}`{R^b=3iCFI8Jep%f2`hPB+xVp;`ntWwo9fuGKl2oKy zoMAohd?B^BIHgg+1a<GSZ$)|bLw!{LbOt?~51?accN<++X882|MJppT#k%=o?{29j zWpS)WKVItAI=%fWe_#X<$zoVmzr9kJJCkn>rvGtX+Shvb0LZJwd!*LCw_M)mUKdF6 z!t~r!>Q%?JZfDY^TOPEW8VyP5WgFnnX)-cDn*2}~#gwYcMYA`fJ$ytGN3g7}c>G*v zzjN@uKATV8_a@z+RHGkq?U(oNHK?X+ar#s8Bb_z{LC##FnbUjoYU=G_d(GoApC288 z^kfO!xnv*#Ug{`yD5$2}9g9G4>h`}UX*_qhLg~YhtFO%9xOmB#x({0t|ClhlMeykG zF@9Td_t)C=G=Z!Q!|FV~*V^Y3KI>v*tj3W@m`!^bQ{HTbw)ZF%48y6$x^bMf-ZI;* z9Twkt)yO&(4OiT;brE;q$^Y)B?|#}Iu27=VjZ%oYh2^(I8Vw9M2Y>jbKVISS#W0VH z9s^CZjwWAUSsd4qKp&HLya>%jcFV=r1)pNjMt=!Ko}(0n#g>lg7q<a@SMuAj)jP)7 zYid#8s`Z10oLh@|LRmKKo__avz%~3tx~va%ljS&~%m;nElMrS8cair+trwt}rvJ*$ z=b<(VuB&hvsqqJH0~$i!>YxoKR0y%1z+mYF@?vR_UB6!b)^*x?d?uyi>!0rCfG77} z6NzFahutIBL)2+v@#Z`X5`>nZt1G5VrT`a-y7jMaK$xs)=(~wtE4<6d5`w4yK3Y8k z%CK9Lf9tdE{9}VUEhL4JrO;w%fM?lU6SFgA+Pz1u`9)DCBjHnxMET!?nJhZyoKNAW znk@Vzc7|w194Qk6##{sabDSOeedp}$RnwAd4u1f8aPly)@YZE-B==4OGio^Zg?2|- zlekKqdF7yp8J*HeYx*DUw-MYT9EqBbxE%=_`m#;=`=~8heF_0W9=|%=VH*c3H*T%% zm*u6b$-e#c`(w-2Ng*?@Vr_5F{I)JiaL~kZt+yE`ivAV#(HC4^bmOmD56pc2+4XKM zg)RD;?3;rF(^PH9L7__+GP(HIs$~1ARmzI3Sac{`T6&5eV3Zyh=_lV+wz4WN&m<V+ zo}cl7{Wz}+ZN;=$A%a=q=%aME5sFI!(kXYPcv>`gi|=c5p#``IN|Z%xLn=*>aoF!% zYzz5<&b8}9SWC3b33WN}PMH6|i~}D03O^AXN@9P}MT$DBz!Hm>bc|tb^yS|=H^I9y z`+du-Z3GY=7%n6gB#KlNF%EIBJukRubHF%^KVU9oY3cCOoGd_*K+Dx4{nRRhFTes8 zTnLc!C0$z>E!H6!W`PQrF_T$g-kM-wo;D8#%#=x#&4u{nBS*baG2j$suFsk{7*U?e zf7b)tG6IG>e+hPq62*Ccjqzl@^2I9G5p*R~*nE+NV+%xGWl4J=Xp66<(`rup>AQsD zXA>e+==M}NjQJ5dN&`6<l2$9|4(AL3c(*C#h@#s~uN1a3K{{!tP0o<J^6&j_X2`S9 z;Xrg;nEj#j!$|V#*k;-TqIa+F|HZApywn>HVsK-~I)-LA`IP9ofLThxx-5VW!UauA zB<<?59Y`@73McRvD1+P7W}$RZDo|zNjTwQ)Zh|Pk*p)=D1!+Q5LZ1%@KjVoav2$g~ zeyQ|L#GoUJUI=#e%;b<VOHnf3yw=X#XDo|kSQpMGcQ!)4CCWD{r27n^$@0NC@9&ot ztuBlB?EKiXeSb=JJJ)?66R^U|5YU~Ed~{t%FsEH@u4ssJy9c8DkuN(~KfLa(pujs} zKHDDt_I?B2y86uHhlV~6H+-0zOdnZ$Zhh_V)A#>w3ai!iAl9c+8L94TdTwQ9+~G!* zO{NUyGZ4!vaTGSi98CY`^nfK7&fh2>GPkb5lsWydDP7)Vkfpd6JboWaMoF3Tl&AL| zd(&(0Nm*S~vgiTdI>Ey&ow-=6SR;7x)g9CNp5n$A=~idnJBUK5TD`mG!>}hp+vn$< zd2!Ak&l_tSzd7x6#FS?~%H6gp#uo!c(b^~Hiu0*<_F93BH-i5p{~s_?>`3ZtKKO<D zU+w?)Cb>H_gF^qeTsBR*jcy=t)wj_GP4VQkTF<?kpHc63Uj(vW*!ie(&6$Vs7dM#x zrt(nB&SIjqqQdy-$oi|sHTm7Th!k&;N_uy<algff9okrMOgn#?n0U!G6qNjrKZaF@ zXKybRJ?KZ_cFZ4iMdJXE)=@40*gR(=qwQ~Ce=2Y7zI^0A*FT(g!#VlB;Z5_}HFM%O z{om-tkFW%sFZhP7|6{Q5i9^z<TgFuWbTz>&f2o<tjD0u%^SFXsm+EWt35<ATTv&OM z?fT|9lCFd)h~X#rRB_p8<_vCJbu#7VZ?CNk&Chd4X}sXDN6-z`$IGKCo2-4RtOrLT zN!p;Gt#f_2>{!t+XI;}CR=c;}fVwrjsq!W91zQT;FTJGAB{Nh<U#~~1llVThqO+Fm z&-&>fU(ZeQnh2FjyH^GkW-K+}=zwcxV3n_R+Q@%}elP2oK|w5mTdp#r1Y0Zd^wK;e zoa`3sapUUJpF=hZeu>_+b}rn=*SB;vAs$-?4U=ZEKb(fNjX8s{lP5r`q|-G40MwRl z2x~3{tr5sk(fZkGk}720oErsnk1_L_MJr7VF3WUW00t+#z)X!KoQ&g}{s*~u?l*iL zQ=N>m?5W&-jKL^WN(KK5{vvH8x*%)E*$u}Yv&7CMJtk?0wf8W2^6RvbiBkn#uFflI zul&Z1<@=M9{MV`+;v5&PT06mfT;E#fUM+g_VvP5<9SlCyt({!GW9H7lC1x+TqqZP~ zZLos4cRG?jpY*Qqu*p`H1_Drb&p@<me8iPJZZ5l($oGcm8t;5|?;@OuSt#ZVGKL|y zkc+s0!HsTXH`kdLG#@UO-c>Fy+c>h@f_EfzudFm}hYx!`xZZn1o8|}Scg!U${yu{* zIX-(t9TF|R)PUw$CVP5a$IcUEEouJDnhfqC^DotokSvH0+GRcaUGc@IiZWa|rfID( z`yDQRj)JrFs*N>$AEt%6B`vDsLta-5Hs>*5$9y~Fc{>XT*PQ;Lt;Z`2C2qEmDS3DA z4y%*B_X=CYxWp|m(242+)&dHSUqb8_niYD+0!4`AE~*vo?R-+Hs4qjv@%<%CfVm|4 zy`DH2&?cm|)we=y9TRLs*TX|!0^9uGS=M=cPuO}BWaNI}02b`#)K%W7^U--)WQ>7m z=J_Hgki4nqqR{a@NDGA}lP=a5XDPr=8L?SK$HiRQn**FHEr;%;K<6WxNl@u^;iBUm z?}+jN&EyzO<1nlF0NYOHi6rzC-(J**ot?!Cq_u!KksM(9jf7H=6*Py;1_sF7WpPO` z_Y@b1GAuvtT_wjTEbxMGKY-TBC&wKWYo#FX=%3Rg#6UXQ?p_wZ?eC(mBezB`N;SOD zh8dl>J**3&9D)1boP5dDl5S%nzKq$n9P9{T#4zFn(I9(NI0)@Odp=Hw5GyEzBT^V( zzesRvRA56qZz@RttO>FtwHy8zrh+B6TzqKU@%i?}1X!6bVpJ9GDfiIzwqCWO_%WCG zM`aM{a}AyGLNHd_D2kh#$SZ2JIXpsynt;yT0<1?WK3cZIwXnHK1`Sr=BQmyj<Mr!E z<gQvtNm|8>9iAcNZeURMz!Az_H(ILlvqeZept3!>l2_C^<&&-WSA+`oiG%k2oV0g@ zgQ)>8E^H2jGs&GeuGgeY%;Vfztzb8#R0amG5hHj%?v_f7!RzkzI$ns6miBmv@iY26 zM@qam{IUPV#m_Y#Q$t#&bsC}n?nG6@@-3TKyHECC*g7?HU5nD%?t)9yyi~XRi1UVl zw^ulqtk#VEHGIbqJ_DX*yQd||#TR7LgC;E!=d#y*e$JgcziWOUd-607mCy`Z3Jv7n zw|;OW)AiOg*mn1|UiV#-YYz5Wqq-0b=gXhZfAYw<jtaw-A1{gBEH_*!<lL?UP}q%= zesjqcUK;t4AXcw)2^j{@xN*JhD~C_awsn!(MP}Frp&sRS?=liKVpMas<ch{)0_KH1 zT@xT%lNZ>f?snS7hzwg=r;yM3-E*b39}okD-9neWFODFW`Kab2mkVWy^E%p7UiH=o z4Xurrj_g4v)2{zMo^s+`15J6T*|EwE_+4)LYoe3>PQeS>-KBy3rkkI9_(0P@hjF+w zK=JJbZ!x!59q}(^{so|hWOM1wIXmucTYRJme;A?JEk3*>r)$o8$<LfUHag3oa7ahb z0qry4Z)e39;#bGT1W~$~OHLt#YwbzzT*KHhrU{T_3cz5fab1jcv0WWA3xZw;&<c;! z{jCq7=zk+o`zyf(_kBe)X>KWU)+Q#G7^gOWZaZbAuro~M<`d$O<>~dlHVheQQF~Vp z9r3^Edc7p)Orpxe?}%pTgTCyi-@bILp~R<_!8WDxidBZs-(DZ_a#sK;4jpc33LD#P z7s!{;1bUa96LdAxiJlO9U(~JCE{xIP8|KCIsN*lr`DCBYS?TfUSL5ek6WELX(%pV; z&5wgy9qTT{TZ8A0RFA$1(U}|4a(mC7xxX)d=WOqF8`{DvQHi39I6Imiy*)dleEY69 zHYa!wZ7SO0h1;2j?H$snSg6Ybl~s=KuW_js31pqWol)o_(w-7lFAi}o^!~@xHRlU7 z7c@D?ZQ4@CmR|@^2svcGn}k?%C_ivv&*TvrDqI3-Lw`!Hi~xiZCRs&2+|tIXh1Mze zxeA-0tBD`E#0RAZX!WP$LVy7OL?<!vefsM|Ey#Z}RJVM66}@6|1`s~O+5;Cp#U(&b zh2x#Q6Nr_p87Vk)m<eYB9Vb^$l*;g&^3x<F4@V&z5uq0WT?d6OzeN{S{496{WK@{8 zRv#tpflF}tU@!RZ8FgAE*M=(l;7?B#R8FscuUdmzfmP@zo3-@QCKn$Z(KX<9xml)G zd&QEX*Q#h)z6luNnK1<1IheNU+eg1V3VdUyW`y6}9;<L!#OpXtR)qd%d^3fuS^*@e z3!gfMDU%-l_7FJbY6r+@pIfvD{jx&$pB7Q5ouL`6^4u%Ab-kkAWy8v<*4m8%(^^p$ z-#dE^*E@&jR2E*5VjdO3%%<J0{YIO0mIscDPV~)mcC^TGw|-b`PJd`%5=pZj$+-!l z15a$`<y>kh$V9MAGYfBdUn~<6hf{e76iicBfEsTRVQ~X~D{vZ7ZCYJa0(~c}R1m9( z8hdzTIuU2v4?N+ASA@b5&=TGVV-uJvh$bDmDL+Art*b@1)EqH#rX$s)$Ou5>=;JR* z-L5hBKrZBV=D8C(3q@v4KCsgszUyKhlNMlsk(a$yAbo=JlHAK^6B#P7(Tc}i3%Mjc zaKMbc)NW`gs2ap`lpJxVtgLJ_#GpdZfkqd8P5>W=5qG#1(1@t;`$!E6j3m(1Y6pci z!%-DSUsLog?F3{FMMtnX_!622DmwN83G2YR4-#0HAG<*i5@{%i-HHSMTqZo}#DQPI z4#GX37z%F^bjsq?#9k8<5qU=GSSXP_(?OL9P+NTs#V*1eMr3I*i4nxG$9WO~!!qvx z|5ibOOm~q8HUxs9VTPFS8fnULo@yb`iC_3^E{6xFY|~H7#i0X=dB!7ru-V7M={9;n z`&v<-%9&s4tmR4**e&{ivJeWRBSY@<uFtoKoD{*A$FWyA2Az2!2sqk8Lg!?-W`tN9 z7$Fy7uFL;xn&ObpmM+yW1rn2G_}K=Mty#iXK}qw^{O`iM1z%4PnWG_#=rOu3h|V$? z69yWJka24E^==Zf8<o(-U`nxMiEJl^^@4qB&StCTu6+g$IshJ`41l+!1?i$3>usbm z*=ai$i3-9JO6eFt^smR0$k(&27tEM(>;}R6<rdV_(75GDN#NUZ|M(>fqon;^e9HLX z%VQxz?e6R|_w43BT>=ip-ge3`?`lW#QRPk48;E-(|1|d2qr<OWZ<LuTA<as~WQyKa zb;ge~UtAit^yEo{Oo#7iOX{ee@Ko0D(=^-?@7S}rE5jDNIlAA@q+Pt*3{w$DVAsdn z8C5n4MW_GzqVClV^U28A$oQldHTUy-lnNZE=8`$@>00|8${(LjSOt84JnGb0n!I{^ zX&Z;re^s{mLLsLcg@4iY;@S<eKC?kgON>3IKUWhoe8qF|+rx5opfU=}iYOtfiaWk? z_^Ski?cGr2Y=WbMX0RteM16W|^4D#-r_LbnIYHJ|<n0MFR%YnVCh@e8Q4)%4Wm<5Z zk#=|^hj*l!*Z8dY+nd@Z*kD|4%yyY`%A}Le=8qV|G(ch_e)vT*ZCEkb=@sYYdBo}G zB{4a?z(15?!}^_hTJ%6}apQCuzw%|zjwjt@`1k#n*^v(HlB&gn`xktI5ev9Fn<ZX2 zObWj1{cn`2GXsJ5&e)P_0aNv#FZNB}n4@&o+|@ju!e@Er<oJ8|cYn$5&AeIgi_9F! zoHwCM40HbDH@APfIXA&qxP4%GYW0@3YWf>w^MirIbE_N`tM}BrlY*C7yLoGnIyT_h ziKO0ng@tbJi`6YjISAzTJKcC#(Hv=Z7+vt+JlD*3c>3nn9d@~0%f4wn6u&vOAjS2L z)@$g^`7_Igw)Oe^Dfu33FZJ@tRAv{1{nLL(O77a~9nsVG6GLgLqAg25yk?C9Mz2H_ zK%`cZf~BujZhpCToj2Tdfk^G!;}W;;ySa4h5xvpYc_YoJxHmK~^ZD5x_rAQRAB^jt zda)@nKEXk^_}r`WJ?_gp^$){-+v?a7U-kIOin-h1w4~I(Q2X)rGp^cs=4;j#f0OvO z(4Wo>yj-!V|E(?Z_yA=@xG}(_%j$D5gm)aPd`H7l`<hE$JF>6b_xGA}f9qQ0aSsnG zK1|HAV;TRryncIZV8}w40g!9D5k(j}9Cx=+0UE1Uj^QD4Wd<s!d$J083)l5s9Sh_2 z%d}uOt49lHB{lVQK9ZooHV5L`iYV|~ky3}f;lzY2_yD#T8(553hwYOGqOUI9Rh^V! z#0Vm0W48Z9ThC-1V>*&(DHXZXkPFfjXN|oCz|>+CwTUc0VCiR7mU~9Mq_6_pVMXXi zM^C0;oMNfUN6WN{fSD?fWRGN=S?ucE)tn2shIpWk^O^r@;F5z!$4w4gVokaqbiYWR zq)o3n8ggoCW?RU~RoU)Q0^?)<0V>a0`g5RB+(v1&1F?xecJ$BCSE`Z<XF089YtO<H zZg1kA^>aLP`TGl@G4Cr>*<SlTpFBB;J_1!osr$l?lbWFcp81VoPHxTNuSJth5Pm+* z`%_YA`Og{(<r}>@{XR|?Tp_zp0BxY#S6)LGgXLQNZB%RR!)hgcS`=JWt0S*bbimpT zHSJHEl~N^3X~@qQJtb15$5)OKXZC4&mfbjHz&ijX2Z1%^s_EXmOc@o?je3ZwN^m+x zyT#GYEcBE*U{@rNPARYi#UuuvNqF1|@c|k0wf<pI9*OB@ijibkW{mb8#Htr3V}9>X z$zYH01}`q6c0q@~b6TS2u2Ll+*|UaD1_>jHH1{m(!250sbmNEEdbDZkP$vnAA9N3w zS(}C_uLsjK7;y*!+A4wWQnU58Z5O^qg*kkebazr~;T94l4A#Sf>42~_yPM6zJbs}C zlnz95;>H+m3>$iO+A_!6kSj_)3QmlS>94$*?z&H_1g53zOH%r5mAEEvPa6W1r9aFh zZI~@0{h+5w+Pssy2M-Beo9SvPtv3h^4eGdv2a_3yfV!bAR5hoj*bd4=f&uRlS87hy zr?*4=xWh(hc_Orpv8dHY1gm{i?VXHkEG#Z2z6k>mVjdo6)clWXA<N*xP&Y)fNrV+a zyE7M~9B6dZ_`=AuJ5R8K3PvhC_13!W`UNnFY2@(hIsFz!0d6T6Ec0|m+5>siHLsXj zoy3R*mE}})=FNqv6br(XS@)O2fKb=mqqTgdi|IfxO=%FuTFF`W+3w?;Z?UqGNGcXS zN%kSAOw@V>9G84regb(IfsK~_Lg1*7gUSpv8B&2-3?Wk5-y~FpElJ4(>8@BqwBb)e zX#y^tULoALF&d8f*gJYy8}j%ciUrt7kvC)pC>%FSpCo%qp1hI^zZnq;poYV@(k&xn zzt>GUdG(bu(-KuDHFcT+O?gR9&8>|uG9W>lv6Mal{^dg73x2Y`ihkYbAPZ8O*Zbjm z-!-D|-<pf%0*cubKD+6THsmXeiG*u8c^eLIEgTcj>!>czT-_=&R54*dHQRfS^RQcz z6loD4;&Uw;Y!*c>*O7$N2=7GVlK*3AkeX-59K1gzBT=E2<q=%`@6tD3YVy|8b+*>6 z(jh=%I?fB59lzLrSmahDLGAhsQ}q$<^M}l`6J=#5uvzNmgL5yqevRQ4yUNq+-0S0Z zH`lGvl9Z?+)9_$Gacc8$2Qr?p5dKqcBzw-!>L+RBF{^qRP0fyFGQ^3)<7Za(!w6@3 zQwy!sNfrsM(g&MWm9t=m*}>}dgaR%|fooc?X6I6qZlOP|fF~AL;95(2PJi}bU+zXx zF<Lx%YfT)pin#4}2WLM2Y20WjJ)kJpo^D-Ve1>U1p_)}~(cBM<Sa688fUv3VY`r<> zj}6bY*L~Owj*sC+sdw4@g~R3%G4YYhHPl}>B7d}pG}kx0V0Ps&m6W3|gs`-6KkSWY z&du`mV?I^SVm57<OBnx$#qvK&&;G8Tx_<SP`kb>z&+6{7Y7Od`9U~)66ahcaw0-V$ zig(Jd;UpjOxxJVfi8&cx-u#L7P`B#Gk&7d%^Tyq=S5hXkj>psH@0BYyIvYH+ewMB= z?3B%`U+8-R=;1oTN8}Z~Gut%(tvLDS{y#og_B0&a%O}NiijNb{TjzeLAKugUb|pAK z<C>{8XY!M3Lms}1(eD}|8vW5c(`b9Luf=oYm$T<IClAK+V(??Po&Iz?6FFMK%Ml2k zX-?@r)ZjgJUCByQNu9XQ$xml4{@=C2Yr}tUR#|o3{o9SmqxFYnBJHJ3dYXGHsdSyZ z;RVy&q4b9ZOZ$@c`|K~eEy%&@O+V|)l{0^D`n>6hQ*%D^O3f+IzvDV`wy=5F>13PN zyY*$dFerY^VXU>OU1I3^@8lrOIHf?1wb(&lDbUU%VCSbXX0pR=?PPFEiJ)RJ1Q0we z?L2jk;tdH6Rm50x5e?JD+ugxFbF{m<P|PFNbagH0!|niZ`^o2B?1RZ)GaX`a1ps>r zXSxmztZBGJ4y4gvr6+_PXp%o?4t#Goh;YJA%Noy<R0ajlATMb~=z}c*IaS`lqo2`a zYDI&i3wK((2xW{q&Jp6}*{pbU<lL!c?*?}rnmV2dI1EJ;z%dsZ;PZNSkEynvd!dGO zVjFin*Moq(q?7815gLZN9ii1^bRK)i@l_s~RM?qIw$fGW+1>f^>bzvr@|>a0N0WrN zlYj-d3S5mR7-@gNXa0=kS=zmmOlzIO1xd<%B|hEJ*Uvno8AoXbd5X(ioBQ-(C!uvb z^&di1+?RPkqaE*m5UCfB7wewTRkp#`IL!AfX%v*Q%cBErkddk%)jnywJN69WSGQK3 zeo<XEL3O{WsIZfg*2BLdzY0)`E2g?YE`psdE-z06@Y`vJY@S3_h5MebYbGnpWr;;A zwO7&Eo=9fgS6hhgfs7olH-j)&aA`8#jh2X>2(dC`5-jV}!*nsQ#DniUTJ;)cL<|=D z%R3kuWsU!KIEPoQyos&6e3H^tdq{I6(O-;nW;BV)VSjTz{EX&ei?6bG*%3KWX0D0C zj2i&eV?sEN@L~qpcgzjGLuj<{r?T$~nABRkeSrB}q-+a)G$ZXQC`M=;kAJ4;@(c@5 z(E=4s7YPBclTBePOPmk+h>|m4tkksDha0iC(Oy&M6-hY6*UP$}vJ&HQURSpY2$mvU zCR*zHVf!2=eS4))!E@VVibbJbZ0KTETyLay*+y)(np4+`$cX(01ZzNIz}6*NTn2Dn zOunpk2g2rDqS1xn&cJyH!xB=|1@yLsHE?l371ch)bQAlURL4tW>7e!mN|DY?ARZA{ zX#CcC;U>W`L4^fAB-|?S+oBm|+JTnMGTg*3Rj7Zg3_*ApW0llMjWe6t5ULnO?Tz|` z2%H}w(+W##@6HY~9~4K}F6!yaXca*UxYameBoBT>+24Dat_2PsoULpsW7-^|_BJ?z z=N$tzsuYm7q{7-9?kmsq7B(q^^@fjKN%ZIlxZ4h|Ta?@uYUNFdi3>H4XX$`LiU98< zQ6x2$DjJv~N5y=n0wUPt(Jca|U&3h#hHu8E+!yDa`zw}>WG~yK|Bt2X0BiDWyJ)qD zw&fGorvkAh6a;~<IKe=qf*~LcpaLR@tx$@Kf*?kLD7IC!1_`TZNho_Gh*gH9xFSPP zrdk0j8<df-LWci&(*Nr9U;p(XBYE>Y_c-@C=l)Ca*^;4A&}cXSG==z#yhcRt4@(A! zvKc7-T>3w(3+dy^pVj4Me3mJ={*4)zV=BUQ$XmlZg6W3fST}{(2ytGHQI&WF(g1@b zx8|;9G^1rIrBG~#di9@M%`-44;8~zwK8@E!<NyJ1U<TEP=k{<MW(Ir)A-(T;_am+< zaNq!0)9BtVzknCD%4c^3aL@F_QQ|p1!8DvhO!DB9d?3#5P6Z@N7#u*_l*9bvK#j5x zQ7Te0>K0Z&4=GtAq6sD@R6tC@jgj+xF!97115opsOzSu*u+blIX2gwu@GW`-;jtn* zmOPkYLaUJFUS;0v`L5i)M}V#nEj;Hn_MynpN8sGT=s^@??hwVMDm4|W4#+~Qun8dL zO0XxeX`FEQfbbUe#(hxR#b8=BkXvVkv|?lROoAp8rOECgnJvrMM5I1SHlUK$qGcVf z6Pzk$7ybu_+-beiAD67G-{yNn3>jex;NSPVXJGzQ1^zG&H2&vqAVqq32>6Qysi(d= zQFs^?Mz=!FEeYL=1tb8>9f8b2KMb@XwCVJDDpvz%Vn0si$Tu#OEk|+1vQ;-Kd#>(I z1oQ~55Hupc;Ef(F>nov5JeP+cpo2;hbvY4wXfBaC!RgWl6hDRo6!u1J=3Q8W0xJ&v zQc9~xEvKytw!r|U_z&d*<@05OtK6=eR>&q_f`-#QQRA~sv<C=lvW<QEl$itXQ-^J) z@2QeEe7d<sk8<0{o$-My!qN;b<mV9Xf#)2_4*!oL%}l8+J>&QKWcQFchz|>h1jTD) zl%jE(`{41KO>6$V5u`m$F7ANv*6YVVmXDm_#{|4Rx|#;e`Jm6+;(0ar_f^wNJK^W{ zq_-&hfpVRIkwON($BoO6yFGAyUL=><4^;A5FbWxWyYc%6wRzImiI(XA;dp54^~5Xv zK0~FzeZ)--4$`h+4J{%TjC^pkOXupFxbR57DsVBu%#wsXDt<|^o6tU!SeTB&=6j!7 z?KlxsJ)>-F(MCa@|J%r~@iFI+as}E6g+)J{9Gr2rp=ps0qS0PnQOmPR_~YABV0*DG zGc71ocPt2kMhKyZxGW<uqknyq)iU_yKTP>@&O%C!&DYX+Mf?+haDAEd1}Vx?G$B9* zM^hz6_Pwd|A)3Jb5XLu|#$j09i*<?FV_DA50ue|qm04)-#gP(axyS`aCmXZkEdXOX zp99(evTi>p#!p}qhyN%X9Q!h%baiRHy<)*@y(|!9(jdagdkbva!GEId^3IZjXvhFC zXorlhq~a_l=q!I4@A1bZLkGH{ET`I@9O7$fXM@40Ax^j>0h7$2=FfXW98VdFjWMIJ zUHDClqocpv_3lCnadjtzvkgvBmWgRx%M#)cttTD|m_%8<;}gOi#uOBN5{xvD?!+Gy zh#UVb^cCwB=;*?>xbmp7+Jf+*313$2%vcnscPD_?fefsEZ79MEbO4G#PEfO46XRoV zd60<Gg!?%1v{=|P$|^^6h*gdjzkAUtq$RGL^FsQlzl%$g81DfhaI<B7g-@qQz9RFm zSu(^$-o{}cUEr|<Ga)E;Aa<r+@W<tL0#ypq%;cqr-xxWg>vU#PCLk!4fDcDR?TM;> z6)*`?hp7!5on#Jp`}jgt!x;oZs!8^2xkz>Wkx7sd@On+~c@d>+hoyh=KuzD6co?IH zSQJtikJttQf+zn-f_kK%waNlz0HP4stv7-`2(DJ@Vq{-DwT-yl{18CRgbl&Q0|Lbx znPb}kA`lyGm?d5u)(c_i16v!kiG)T(4iTsZ$*wF&(wY?B5Mqn;)!d0O&742Ruv`=g z=t4oEPk}%fY(;o-GIwaHQcS|ZZ8)H9*cVDgF;idz_5Tx9k|PQ!@P>z6X|c7ai(yL$ z!T$WJ1PJ>`B*!};l5GThg+JD|FM{_p2JvV~;oy}4aykknc!DAW<L$(g-I$Pyf}1E4 zjuLg5%}z|{!G@<)k~wHr=vuO98-ErrC2UU<>eaNaWEzI{uuobhgr<g}+P=!fLL7|v z(Q|;~h?kIF&!)o4+Gs0&1++(ePbSk5-d5xZK?egjN9b&w0c`7_MLVY{3+QW|P`z+M zh&ImvD)ww%Uu|ElEob-<nAy0(iP-d8v!`wWX))NgL4?qXrAU0QkdyOp<|J?wj6`t` z_vs%aB@OBEi*WNGcbF6ser7w;UaGMx4uAttW;VuUc*x44QZ@3y?T#61>CJ>s5T?f? z&InKmRQypp*P6b^lZyxZ$A!2iKV5j#jzM9vb}-7t4$HY_sMdb5#e4DDB-gmmFcC(~ z5rRZM&hW=Yje>^MlW4DcE&Fm5qkFz{^f6QT^0094<r<5g7Za*kZ}m`#Fv$Sfk`6r= z{N1pl3baGQ<VJ(EVTAAEs#AYbh|T4{lM)3{o{qBKwU%}ktr_O)>$^~vLwqJ#@7THO ze}A7=HXYVRB@16K#H~aGzJl0_r~P!rNkyj*)P>}$?mBy`A$`L?2cghGyh1~K5uiR% z(8!wP(R;z&Cl{gK!uTv~T**V{b7mfWcbrW;(JYqDa76ukTJq-?@W^PX3qI#&DDp@J zhnkjfahiFLU^n?MbYnw9;)CM{-_J!~W5fIIF%jXW!5-~8V!pq!C0`PVU!Sn^$yEq~ z?<!gH;H<rGl(k_-oNqCHD97G5Jl%emF9l(NR3HoAaX1Zy+py6k<ATzYOs!%*s2$l? z4hiNh?1Z=_9$9tq%1e)yl;1m&+3I6km<AZGnQ6}8g|#=~W#DKb^+VbcQv06RGY+Ey zg6zb4Kj(i^?it51Go%PNr%ArQ=gaEnZ&0IuK?v*^-;ew{QFMLo6tu7apGI~K{P*Q* zzTR64J;A<8#K>Ugesi=w0-P*weMF3eq2C`uQ#OdsY>|Fi8hBV50kjI@>VV-zFtN1c z`+ZcRv%&yWTkg3M;?EQ5htd~aChEzWU`zOwTN+(9K^3*FICOUFL@Dc+V0NOU77I^g z_4~oHI5WP9W1fvE`OVxFuCxNUKIKKKPqg2dSi*?<pvF|lgHecVtd|-Wl(bTt2S_zC z*(lspy+nSna`xz3d($3?=>~dR(@|~gn^1f*PQOytr2WJA5l^SrVW-5f6B%{mJb3=j z&R(y5veTj2aW9l<?VKJWo8B4sL;@Ly9zM39cGt3N%qk(lN)i)Z%`SWBW`3m9Cf73} zjc!KhWbJMjsl~b%>wMPG{k;v|t|&-4b(4`X+%4(U6VH%qIGg?WgW9K4#S6Nvsx!ZZ zJx+^q|Gmh+j_Q7TvrU(|0d0{g&<~H)h6jyzICT{I?CvOgL9{lWOzj&j%5s1omhEQo zuTl=aljop&v;>_q*=JXHfFg0qY+-F!?hnGDx!s&9;8j(K(&((Dqr)9f@Yz@Las~|< zt}YBTaVr4hB57N~Eeet$UOF!^>SD`!G-7Z?4cM`S3>OnYasuVzKOiBGq%4QGRR|)F z`;Jj_728_hdMhs~%3kT<hge59CGaZ)bnkW-9W{!$IogOxBNuvi>Wx^2z6S&W;IKcZ z#xL@`(jcMck}<oiB44cu_Aho?Hocqzcp`k;_uQ6K1?R+l(RbOPtyPC&6tXuS8GAjL zd$<(4^X`6J2YJ(S>H71~fz{%j%++BO*bs}kKFIGax>qOF$nX&C`S;i=gQ_2Q)XGpi zn6JjW9E;t0;^A#QnTHk|Vlw#G3KJ-W;VgL#(8Ne4fN<Lcit^&VAN8|EyOE>1_MR_H z2X8jv9$W)e{ewfzGvr~1PUIG4Yu;Vm{Bb2~HZ!nC+=V&wROrB(q-6DE()i(M2;gI8 z0K+l=i@0EY0{Fw4vd|ql8K19?@teGcou5Iq^5s2$<fhR0zEHg&-+=R7?)mB%r>dY< ziQ}tXc=b!x2BPF*0p+Ef{%oznE1naXo~c~?$wiU&NrY0&ulx4`__aj@CPxd>-M|lO z=bXXpA!juNlO_zd8~|vj>2fe&6`JQGDtVxq=xhdn*ZJ%tIvPnA?O;?$FoBR0E{n=O z7}Ab1G`9)`STHyP-gx*>oFa}B{GarzeHp=fZ=ic+XcI@*QTj%>%s}Tx^n+of14Tb# zE)Yl5L8CDLp<s9+Lw&S2rw7#JFCffO7wzU@fd4h8AU#5ji9{yA8pP`^3nB^iOqlFO zVApf#M=)Hs!r#DmAh6)$hf_R}F@UDLMYX?<2v8(o*}=$`#BPX}$*eswg!trwo18=z zqVk;K=~x{NVi<|J^f=Ti_<n@_Qg9iu$KaAGryK`z#K9?^!nel)@l(uklEj>X9DqVv z$Si~N!+=xQbMsKiOf_fYZ)|G9s?c*9s6_lh((oeNvG%vABwZNSqV?UeYz%)d^dl6> z=@C$msQA`e;F#!Rd;%;L3NfTwBqZ23Rb%mO3bQmVRfE$eVrA(wm8D><|J#^C9t({G z2)(UfEh>Cfk6$jy%)rxNOtebW%4UgFt?hYrDhM&{*v*PvRIV+AtcbmB;i)!qt-U`Y z#p4x+?x6BOc?Bj0fDZ(QAbebK=!5|qY99PLms;=a2R@%<Uy|G4iQy9*qn_a(vg&w4 zqHAdx-TJh=d=ykwloakoHb=FuAs!HBNBh15YgcbL4iYEY#tgy9nb1Ns@N{LZcETgG zGwx=;HCDJ|9A}GojPq?**c&8;u>^)2-G#NvCip(#IYs&>?XSqXvW6}2XUV3gekyN& zm9VP8^6VIWCKwmk+i2Ug4M>O*a1|PFnVJ;6KSVyx#86i!_PV%wK5zkiattxU!zeoZ z%$frw_r72^qu~IRZMr!R2@p0{Gt0Z*FQ||SMo0nswEGCmNL6JpYvb&QN1fI%)5ker z3uA#m(xf=hw!Rn20Wd5To!)#|*c`DSDGL3hUDl)M?v7FJZ!eqt`w$TMQ*>bQd_iO$ z3w=GD1wb2!Z~DTX)Wnmhz^PI8>xe54nH^zo;1iw|ntxb{peDw({gI(9hD}j3T^@WD z`eLjCgF>RAa7TEMFqWbS!P^UJP3|UD(%cXOPFY}NDu2cNi7*k6dx}CYyNNesQ_cF> zH^?L85kImV>Q5;7rJogeMM^j--Baj64Jw~CH>51OHZ|(fnu?{62rb8rSGksO?R}ZJ zWb!iZolrwe9)S`vp*F|hu;6G8$z*Ks?KqML&<fmAbeir}f6Cu<o7?elm1@fx{Iy4x zK#&?@Z5h`zq2Dc^lo<1i8S(u|6~v>0=?YCx&d09oc(i{Qw(iiv`zGT<)VzsNPpazR zsG#eo<!lU0IoTFFvzU6R-?}nphApvj-2}b<H0R~W+o|pcf;HIK%)lU>?=>NutC%pl zuF=cQa_RqQs`5egmp3P}5)_&LjLeR{L5+|9%>UfrD>lU^KNZZ7>-vF1vtd?PB;VMf zR}Ebjf*qX3^f+@vIuT>zNj-NiR-1XeVo)cBD#nsfWzfT*w(|F2ZX0>lm~mG3Y3Awc z_GZF1DW)C~pWVoqecNac;rMJ%@#lOCm?@Ge6R<cusxY_0P~&@W%(nn0Ip?qA<#&?r z(98edxYwLda$iPV4eFm@_otly3jLmLeZ1w?u%}s4){*8&2`*}4pwG91U4}6(7oXrb zxkG%!G|I|<b9XEw_MLCu@*~?uBe$Qf{A*3ph0yiyHydlLyNk^O$vP(yQ#Ka26-QH+ zOyVIaE<W6{6hFT}=`*%WSzhb2Qhrd85ZbLyn?Wt`>J<wCS#v5H4XeB&r%pC_$}Tt5 zIxwxc)3f#{R`0?)pbe*CfHahCpXBPB(CZQA>d8De_2Wo!jOk@SuuczqAleVW*U0p1 z4Lxax2hcR^tAo%LQs*BehK7a`BMTfyAwlldc*%Cucr^^>As&1VxffYV4FVV<ICv{5 zl<~!j@vR6vjtECY*liosdVAFvB+wTcvRqhck3M-xym`XF(;xD|k8aib14fP+4mWSk z>1FL1UaVo{d8IxruU9>Zf&X@AdCbu&aP77>-_#TjX2H*1S$ai{lb`k*0xl&<SqN3; zs(DIpP_GTsGLYOl8Fpr;2j>xIll2^KM(U!f3LZ%HY8}t$J)?IHp=22-qt8OvN7mrI zcNjtuP~ohe7j7QY&=M%e?sfq#<qS#a4HcxgDw6#Z5BA^I=VUrXR!_g#98If)g~cQX z=}|j>^XGg*&1}LI)c0xOu$7AM5t}Yx($7&^c)ER6OCp`xTkO4!pCu95V6H9~c~p_> z_Bqal%{9_}<9fr25DrN&?)L(l2(G;4=pqr7*_0#}27a(rXw|fZ#|DOpWD1_#GC+E9 z@gSCfqDFC>2h$}q#M|U5xvyLz9+K4b)dK4!yXZq$lv>w$2H@p5w{$~22n!2fh!s~6 z<w@#T1_B7mt3)s@l(y-9VA_fIdCgyhkBG%f1``vaOPsIa9q8<P^28A1LY<o*=B!8@ zwx>P8UJA6gU@>AGzQv^<F8>{t1~3*QtpW66q?1kz)yCP%?GZG<s*M;60-lCq3bJ+7 z1+e4$p!Q<lrQVl20FNN=+6KMLC4K=Q%$2to&Qk)H2dq9YR{@eU4Ew1ZE45|VedEfY zG?9vgpeys~iq)?8Q#tVd#g^8YXHEd^zfZ@rc17t5EI)Mv;D^l=Ivf*~i^0n7Td2jr zu6I~6<CP2H2{2{^mLlFI)>Bo%KL-PKR@a`v`HOnE8L@;OP3Blk5RpQb{Rk38>x822 z!YpbF#QCU;#NW3`NJZz$OMMAW0_JI0aj;&@fvggoyB;36a`Y(tauY+)eY81N&YGxh z8~`{2M)Aeo6k2?f{31(5cW9L?`_{+@CLjAYoD^Z)32+0wVBGBRWil$0ONui<IP3mI zk>nt7<zuEmI?!Vye^nW$*A|RyNsLyOvW?$!mIVCx!`zVre`EJVPtln_W1M3uPS~hp zDTU%Y;;z)L&w|e+W;!4v3}m9IB~=!>gTCj}`$=tWqbI6H%q=IV*!2f@>%BMB<TAr( zaZ2&F9$eh0;?8BLGqUIE&ileeSqaY<r5Fu4VqQBN<hKTHmea$<F*MSm{yXcg)v>WE zI4J^804Ek#AW*IxEyL=70n}b}Vh}J2ul5O5+0mChW^8Qw`1h;@T@+gZ)`9>M`(C;S z+wk5Y{Dig_XzjvoL10HEMHyTT98q|S4P-J(_H6pKe76t1F)kT522O~5RNk&|VHX=w z&C00r;TJvdZhQ&KVS#j0_Z0N{2DOZ_KhoM3d-1;Hjx@lZ9K$0Va>66FM~XC1p%#7Z zPWNBi03X7T2+L<~%Okyi$Y)${eioi`)nWs<cUU%@?X0RU5HFh@v^Y{6=5!;F&6wbE z!SAfXv@-5HO>@Wn<aa7}$`DApuw{gS)QiDq7z3p{YYMf!x6uh}7Yxo|xPk$5lX*VQ zwYMG~_E7djTQuGhJT_5Apd+lcdk9h<y1yorM%0kL(eugR{g9M}%HQ06#9&{P#Xp4e z2h-Pr!T{9feDA|YwHR1$K<2NCet=BpDcg>?-5Pdp0rlP|*~2_?^qzy$M>AU9HCO}% zgxXSaU~Ec^8?s>}&)jv`&rqCTn0?RO;YH&^{8B|HcIL4|7E!tBxTt+5AKi7aAA_5{ z^B1016yD46GO(Tg*}Q%iJM;6eBeVz;_Fv^OXx+j4&Ll=1a{?8p@IB?>%-p`#lQm&f zav4qZc;$mbLwo96Ad#=3|GlQ`bkFnf6Nkm%k>-iyl&R+G-+!4?zg<>YQW>SZ59a`j zb&CGk5wZ1>p>=3La6A@%PzyL7_D}dV&p<8)Er^|mX`DH-xYR>TzqvatBl1_XWZhbT zAx+W&?_C$)25icuw+EtnU>@`tA9$PevvPgSwD40Ok<Q;rvEynb6Hy%zzNl`sUJ@$S zQk;x-hRf>QGrzS)cYBGlX7lLgPT=tj_ZDq^s0)>WkPWYYtmm%DWgR9_0coM0X?*Ls z+*>zaJr@2^_;0N6#9>OvY)j9ocj;NDD;_iDR@!U6$r6ZB%&8auDi0bLd5(XXsh?H& zEv5lDzRSis-kIKcb7?>Vc3?YaFtm@pw0i9j|Et@)2M2GW`Ro&*qcYJ-Zd)8Z8u<-# zp-o>$i_dDIpA)M_%;Kc8=lF3TdEiqR!l8m^Mfg}~R_!MOS}=aQxA7j<&W*F{1H=r> z8bH{qPrHP(3KmHSJ7hT!A`t)EU8uS~qeJMm2+lM(FCab^^JlKpq}twK*JkqhzK<tk z_ry>%7r8XBMQ9ZZ0Ocn;+AWO60OArE8l<Sf5k-c7@l=bM9YV^8f&cox7y}giMS!Ip z)QWY!!sFcojx~xEu?`$c)Lz=+rZNp6yPzad#sP1TGH&0Y1=%V<WANrerjCtk7&qgF zCX5BN;Vp(8f;T-PR0<Bes2W<x6UbDoVY_rCUXul|JA#gx-H74MC30ednT8odivu-_ zqho-pPa9S<gg2?@%`eg$Kw`}N(QHu6$#i$oR{Em#E4Ny!w9e0sqJta$o9>PA;u)Sd zFwq7X-#h3`2JFYf(C&f<Jk<yy{m;SdlilxdBN=@i21N|&nRo%7eqwyV@$ZU9dy$ns zs716V#Hey}iVGaPK(czzVSo9gCwJ+6EZ8(68?UhGhe%c6JV%;QosV}8pjg0ZfJGWY zJ~4V}fmRBGR>Gw#MOt_^_zNVd0)y9JRbwkRfN=qgFtD#YmawI!g1~TONg%VrNQd+l z5JUm;Mw|N_@eQvImW_yk#K<_2Y@hpoBU8*;peNtx4+1~bd@x&CgpkXacn-xm(*;d1 zpNxZx;oP!-?~@E^7xEmHe^`Wsk`JaHxCz3!Ixb$$K=xb(k~&FvA)x+|_W%>_6g2Yq z?9&nF-e-D5A(sFj!1JLfTOf0kV=Wkp0i2I`GU?GmAcl1g2vq4af~h7Y_W50!5$#wY zfU88P55Y_juZBgqbr_X^1!e$Z2_)9JNdI_pySst-Xyc`!V*#-n>Vw{x4{AHJ5PJ#9 z5_)-jKiCM7zR^_DVd68|Fo^8d%Ar9OSO5}WZ|Y*+o;NY5Z17J=V(>};*aNO$a&<P| zK%W4I=%XAIqZ**GV;MNO=DKwPSe;<rUk+-l`rO@NdKZSt6)GGWZwhmNDsGgd@nQ}M zEWpSh2*5rPR8T0Op8zGpQ=(N|7{k*fj?!SK#6ang9)mNK7*cC3k5`jYVI~wx=rte{ zTGP8*Q30eA@Pj}t_~pF4!DM{|HiDq70Q7_ImXz?9lN#_$cEG8c2cH|zH*A9$+9B9t z2yN<321=3l%2jepfynbMjLhCIn~7`cQ`A``Ia>-|!cU``bE#K|X9J^qiY#<$VU-2) z(%7=mUE;{mk}CQ?+ch;jUU_;jbTTu*#2l+dC795XvgYkuduq3VLSD3(C)jGf<r}N} zOJYpPaA&&ic7N?Or|TG4*1@XzXY?c+uj)0N@9<71+H~%mDnTeFIE<Ta+tjKJXRlj> zRw0+bl^Wz71b93sql{JEmEzt^NrvN9rB@6^u`zqi<*)mazS~c$MKXqc0D2%1S;h|H z_7kOI14oE1hfbcckp?wpKs;Q2vB8Eo!E+t{z#}ClK}@4on1^sC>T+=?Fi4jbnwq-8 zoeBgMFfljgt?B~YM=lF-^eHPcOTPnE4K<*j*@xW{O$b)55s50{7~eafZsV8CUR6Cr z(1G&3y(Lkn2^m7sd4!GekxFu0$`P37*DfI0T^@Oh=Q_M`jgziDhmHDqMx4t|N-Pb> z#s8aSdZ#xA>H@Y1aSLS;%R?F1h3VbN#v49MHuYEcZ?a4Sz}OYYv%IGv?m5F9*#*;A zIo?pty~0l6Xb+!GFo8_}_21A}XP28@+<6p%u`0%IuV4nDooQ@s<(q+hXUXcyUvueY z3*jHf5n^VV;^pOcYh%aF`dk7FHSnqgZ?npKn-*pO`|uT5o%yCDRHs1KAABY0kk6*s z9<Mmp4%1!<I1){r9e#$nOV<adRA;`;*_5*N9WWCf<}Kw1S)p_RjR&*FFx)zCm#j3u z^(U7wl;>GEp*kBI3N=>SQ3a9dSvJ7AaEEo4UkvuVjCi+ShXTb=xpqACS$6YR@0tq_ z5v7Jvc4v#=!LslnewvbG8{&+va7m&esO@Orhjw_apQtT`)wGZKZ(c*RjXgS!4=fAT zB;E+K`uR1bihG(WZLYpG%aR?lx^Hv%t&BzYjr5t02Z88)1`51tWA2%f0cmJ_Ztn8P zJF`BI=gh8z<d{v~7#w?t@ecPi&T<B<0uZu--4s>ADukF_?!99ds`ZanFR7LtjLT&K zifXj@pmu6%a^Qj4-)oy%)5|6{ELHH~;|3F!yTs*4U|Q1mqaM%T^()F{ffJ;!<dWR+ z{<L+a?w7aG?VapMI?Z{wlE3b@%scZHOIz?duA%U6?_G|ZE>LfW9(##4U%uXb@nA>8 z)n3UmGPhIAjZ?04-_pI%^JLU?vfFHTTLv<MH0Uoemgmjobss2eJsfL*m<5uBZ|AIc z_e?aB8}43c=6&;^*YaN{1|FCk{cBCZ^qSijV`*U3-i?OGWpTR?CEW5^RoG#jtb5-c z1wZ?ipkDD70n$pZ_;U4@$U4hA=XwRM&A!T(XPmwpB4r7XS1-SY(8mspr)LfGPrj;E z9~}n2L$udigI4EfHN=A|xF|**ZMS?`P`rx3Eyne>n|J8{7aN;c%Y%p?AxaAk9iR^2 zK4qpZ_}3B}3nFlJ25~gt@m8x(@Tq;l_wA=$w6Xn>9pZKV#*i2e{K_+XwmyI5u=B19 z44kMT@0@1`dHJm+C~4;Z1VLiwibFUF0z$$Lunl3y7tPy^vqVm#zWEh3=Xe(&Iak#5 zJ#sRD9RsmJQ^C75yu*+ziQrk@q!PCPcLu`Bn31Ks+8?CwS8U9MiwpcE0nF|YrYlG1 zDlX|skx4<c&E$w$LtC*wRGzBoFzd55$?7!+O!7#-;4Y(>`VNB_<#l(vanVeYM1-aU z)>#7+?dn&mnr7`yNz#EJD0A<=r@IR$Y9V*K3&+PZ4EJ}3P&AYy33oXB0jI0N8Y1Lo z%40Ud!#fE59(0!C-q;>nXyKG%%eW^5FYHcz0+8XlYYiC#praz}eG?;&DV+q@SZwsb z8v)rKT!Nu%pw)|cZ15O{cKnCj{7UQ~*NPlXCWt<qLpW35Bs+lihkm3debx}z0s%c@ zW-*URL6iRki507m!CxE5*YyfLXsPBS^~VFw!aZY?sv^x&%^?Zycfi*HW2O_!XsnYk z$7%?A7x38OD$-?Uq-yw*ok4R0q~{I>{T+xsf--Wb19s`0#e@N}e!}~MDgr4Nz9<;- z6w^3W_)A~{L!y5MMmB_DK9Zsa@tYS`q+)GU0)YvV22#~YjZ1D`K~4)4M#0VtFAWfm zDyVi<L5PTv2kSIo?SMK6u*F8~$c66=VsXf^)HL#}5T=c)Vp~B6ht(KhF*OZFGC_ui zhhdC>e+PacfYA;p<OmmThA;oEH{gw<nq{H9z`G~YpI*y#sUJ0TYu_+hG$f7`C+~pr z$Qy>O4tn6dgyS3XQ*V4C9s*H7gcWO2Vi!zwwAm;fllL?@@9Cc5SYdh!{iP3Zqj>dn zfVjJ(uvj&9F>FU#gXB{u7SU>Pa$viEBkq-`-yL+^1>t%Izl8sf$C8zg3OTf3_l4sZ z-~67`wJS3pghf0O_`Wpps}oB~#3sJjbw~~B(C#a|%HHJ(JCZ)p7Xayb6*^n&<v@lA z?W{dS>$hHRaamAT<OBv4uvPl1>`z}VpR*BLx{~&yQAa9(AC_Q7*B_fc1}4xvP-Btu z9X|fPDPRE)P3ORz5PlTyZd<2$%r8{9hm&y*)<BS)O5_9JuuGcIUGHPb0zRlkj_~&W zWBT*s;OK;pvEw3=GisPpCAGw(J5X_pq3XRolun(+@KF-eu~0VC=z#I{SIeNG1(_c4 z_W8mBEvV)C?NKLN=EB2suFn4N21SpQoF2FqCF`8p6%?!WYuXlORWb(n`)duFv=gja zfpZb)9VoatQw#Xe2u`8<-HSLlV-Ohz7&D5ZG)(DiY^KJq!PpC9D`2L-<9g;Xf@HOb zsS>?(1l}w`rLs?JW=CA$90LLpAvW0|2g-`6q2Fx>mr>Fj`vrH{VwtaCx@C66!lF?3 z!8&-pplalEB+c18vr^@I<p(w8`8~B7ir(Mwk|ZzpZK0UKJEB0*QL!OEA|NnS`v%Gn zM3>E+Oy<$Gwf=yM1yx0v2usQ$dKaKW;9h&p(j`;@$}ZQe%s+pY=q{XCA_`N6Cqgd+ zhDUv|LEPEee)l~2f$`o`cU-zfvb*GtlogwzCLea0(W~Pg`6<xl1GeYJyS;wAWwBwJ zgT>bm46`{4&EUjj@pX@31}e~AZjRj<GCa;i2;ct68L-`0SyuCcCilP_aUBHO%lAq? z`wN*|JnYFb&9Q}1*xpFL<tsh1T$tj$;<#Y@!;<ww&MiH>oHVdnO|zrIxOp%!G7^D4 zhg)_g`@S&d;ODb`5!#7K!OQ^dNUy}w2vPAp<tOqV$7dehGh&&Zp8R_d)$y`gL_1^g zg9fbXsWugkH)iT|{v`G!glQiAO+nvh-)=rR)io@7_mzkmjHrDwe~x~sw*;+m0}6}) zpRbfnoZFkTe>FMW9L}Vjx*pFN9?g!MIoa{7yOJ<ox^@wNtdjnj^8LT&-c5P`I4<Dr z_Px9=!V2@(XSbLClRTN*D_KYKHd8Uz(h^uS`4Y$}22MhL#ih+xoW8Trt3;+YEvPdF zp8U4^U3SK7-jYhiV$GXJx<|153g|OR71N3Ab5myO!?#`?apT$0IO0aofaazOP9J!$ z6_M6e)$*2gKSllR%7kgBBh7@06L!$2F`@XYsw3+u3Gf_fi%1yr`LFQ%r$_&35Mw_2 z%9DlC#0JJ1ys9n3nqMGi^ddY@=503G8$?LzyJ1QVngMYfkA|&qL+V0Oq!9>z2b#kq zh73?lG!@<n=T^Ib<_1=}#HhgOF=ruJW4O`J-ebMe&m8dVw?P1v%y9+nwlAVbT{c8E z-5s_Vy<EJr3uXyq+yvV@j3MBurFGdI$UiLHAW1jc;kR~3?25TIX>i>Mt?)1I<@HK$ z<7J0PM#juM8f+WD6L&G}sq^W{H6+3Y+Yn(TFYhlpdf4dxy;#FqZg^LHt|F#^=pM)o zt-EG6#F<d&gxus5kie~tjsq1=`!U?ogr@<*$_j^JOe=Zkwxjb08uPG@RgOHE>{0zy zjM7Mh^uEg0!oXijIS<>B7}_ye!sTBr<^0_ObjVg>7*loRFq?xemhZ<pj6RbT6}#ba zgPlPHabmj$2*r(-`RDI5^*ungc%t;f85%Lfk%NP6vibzFUQ+))Hram(JjZapC>hLs zZp_B;NFci+bd{(={d4e_(cO9jj^kPKn9E?iFgo}WG(qH85Uk^2$m=g)pmHZWm5|Ue z5CY>^0O1lQEf}I>5%D5bRx`m06Eg*wwgCUeP%(88I<@Dp)JunVnZ(FQ4GZ=FIDqel zp>Dp2l1v{ndPtOupv=YM1Yxwyc0tdCIikZILTR11M_Ivi<><ib8iZU3SWw}@p$pqB zK=C)gCx<$wXQDM&rTRKY>E9PkZv}Xf3j#$39=D1Z3o0er*s0JH_}k7b)#L%5z=*1N zt48W%Eglvl`Q8|mpn?FYm85#e?6F#{5!*S=U~1CT<?K|C(gZ_Ytc|IHX&aFsU=a(R zS31(le%l|>NBaSAT@HYTnx=u4o~(%h(-I^>==gkqP0U0CK^}w|avNy*+N79q#S8!| zS>Qxq$jzC*2u+B+@(em>OwK~o>MmPN83<54VE5M!7<i|Fk4XFzuA`fVjoZgyf^t69 zioo=X|J^az^E)i15g$ch_q=@ze<3`Nj$--hSr+}u?f;sAHokok;=jAWM2Fe<z+bm! zZ}~)NO21W>GL7F~{m8cL*}Fq!Wl`H`cS#rQHT7ln_f;7cCvNCmEeOh3Dnc}GLU}fj za_rSBsd$gx&(yeHsj(;K9{^>>8j7s_p56HEPP;jwJd6%q_mg7=gopoU!m}=E@YfT# zbitf@)baNY4SODo!wie>1^v#g`U1btd?Hpgu$0x<r|mzs9(;7XMwO~B<@;Ap^{bSq z@L19@d1yu{Tku}g*S0I|?BIRJcrKd?rw^2#P<Id%d~^_-hDjZnjOK#=f*1XU^hHyF zwt=P@@x@i(|NAFN+V_f&Nw%<q9%F(=H@`hVAUI@!%&Fp6>BzT%<a8f+^ml|qc|xea zw$ck<FoUMf+s`S`s><3okm%ECsH!uMGqv$~lliA*E)wBg{N+DmMf)9o^$l1Z{M%RE zjC(U#PjLxpb>-9DWrzmYJ1(@FO1Otoh=-P{w&HeW%L!^XoV2m_t)ZYikHIK#()+J{ zyP~rh-@Y3^o4Es*0X~HQmhmBB;*`QI1UAP8R*|G1AQcFa%=x}}Cl!ZXwO%F%mu^46 z=_CZ4xq&^LT&QdCqWFN*263V2(800{-VOCN3&QSd9S5U%nj@Q$ub{-wEQL}~+zpX2 zLC5TS<G>d~#SU2{k448PV#IcVy%?t(wHDHstm1yVfy|@|YnF(#!mSO<7h05f<oQK< zZ;yAp3^(Rb@j+u&<ayv`%*V4ozs;rD<N?)|UFwzU72#nf=)>27m(H~u?X$oT?w4fL z^)QEo{p=4ml!@kAyQS@Vck9AYlK18se+!TpR=z;)DK#z)+dqZi`iHzFu`c?Q;lb3M zhPn7CQf%ZQpZy~bnKR7oTWYdm6_Bok9lBV53^q{eP4UnVIXUy0*f9qBGf)Z46_*9u z_htk9Gg@<{A=UH%_+CH_g7*TIaAoee(tfAq73>vg6?1xTeBQg~hFkHrf9lxKS|*r^ z^op6moepp5-#Y;_(U~iBclk#XVGp{YL)vshNCz1Y138_rEhSPdW~q=0slVbt%?#&< zmcZUJgkp$1ny_8-WMmVk?9s)TEdiFTu{HT@xK+g|IDl*me1AW))ab|oipx;Nz!<F@ z9~+R@!b10*7rdhA@aCUtygQ4})V;4wrt{s|{fHvJw_AKrTYCB%2KTh-I__Hy`l*Rp zAH(n;6tV9&8xFKq8K@_r7~k;%B^yO?tN7kJ{-<u5rW{iXV}1us2eqYU`M%(Em-LCs zhmlK#<9(CUNk1|dV5-<*MO`s>Wn$x-tSddT{XLaY+a0k{uU_UAq!d?wF?(BPH6qkB zO_9gkenAu5<<on(f5udWJa+JAX<}*a?GwYQZL6UN?Fau$TuVTGLY|~@&l$IpqTSN} z^ss}*&AmP&hIl)6`=b7_gIM2|BC@lNnF@8+0S&-v?RruxEd1qI+QppQ<r@;d*t^eU z|AKvo0r)|p(DTRelEv%Ad$zWD-O%JF&0@t*+Lid_dwTwW1J^nDNP9uDU}cRH>-G`c znq;-AWn003^UrAzO*XO2^>jtqNliGk!r+yWB{fG)VhFQ8I0~3xme?us-c8K%2ql-F zPzy0pf==i-+S)Oh;ABJYM-{Wd@crFJKwLNsS3I2v;c<?kWLbvqPeeCT$oi!OnSL5c z0x3{pl*BcGah;!m{8m0UE1Qn1hESXps(-bWLXiL9J*hEG(BD844X0SubVIgfdk!qT zP?jZ}>w|3<ItIj6U$lqVQ)`b8lr-Hu{H8EhUk2Dk$kKH&3O^4xL1KHA{O%hJwLc>6 zNqDcO8Rv<p4%@5X?mkalaWbbjf2pXirS})m0lF{&AmTxe`j{>l3brT7O-EPTVTm6k z70xKuz!2*W;_*&h3XQb{xsTwk@x+c=R*uQOClfOWu)l0McsE(3`a<vn__lf<ZYX++ zd>rx|IVe)Sc$@&7IYcUoh{n_-cxP6^0)lLZAriRjs9}kt$km1@9NPDt#vRayxUJl9 zKC`8sn=gWSw_Jivf2dplj)TI6<{jcaHhe0E@w<z#P#gJzl$E${RzMnvR$S^&%>MTD z$PyM{OUS(K!ekdH#=!=lp{;Ck;8|<|0F$Z?Q$}FjfFhyR0_7F?A7vx3an)D~s@Xj~ zdDY*~VPgUal7xolj+Hp2mb3~U7y>Gox*OVB^v3m;>j0wP{#0#0511XWWK>VHUE79J zj5q}jY9&-yclW}23UjY$e0rpJ!>jhi`h#=&Aa{W3=S~*Z1g6d#bimM@3@eZ><JGJf z`dV;>r(r`PHyVyYw7Ql!2lRBbXypGx8)+533AAfO9un!Bu;V|lj2Z4JcAE7YN45Vr zPAU;iJ8eN3W6i=EwsY2M%C>5OTjfp3n<ytT&2aDMB<mGtA1frH!WI;c==vN|V#Bix zehU96^Ym7ysO|Q&a<JM226LjK`|Znc6!~5_+8E4)#J$Lb`8#-uP<}J};}~%Aj>ImL z(rw7gnLpN@ykvKBt*a+M0f@0<p5Wj>8y9gPMzM1BI$UNrXl%+aHm6Jho7u#fN}yq& zry_+2#@ZxbY|sT_^Fgf|7M`H~!{~Ojm-kyUJ4lGSv%7*xje7#92*szpvd{8dY;tbE zSKT%g0U<^xr1W;TO{;<fPD;a;VuvB7DMQxvx1eBh_V%dJFNkdd{nY@Y^zytt{q352 zJnECa`Dx`=4XUmez79=er^r>bH3chujuotZ;`@9wgQv;wVhJg)V~v6$0wbs=(Eg+1 zA3kjCm<aNr)G^H63pAi$#$J7%1v%(JQfL8uIRnayJrMgMdBW&%3TF_aG?XpK?7$LF zMez5`o2W%z2U~+Q{pd@M8~r>L1ODGe5==1Up~BS{R>C+eeYJ=j_|=JgpYCj9QSKjK zThKY$OGO5+$<^7|fMkXsfeBbH%!NrE2S)4caCQ<EIw7XcSIdja>d!{gYM0^k7KQF& znr#vasc|)mx$YRW6c7%-Y;|8b@r3Ucjj<d0LG0CwFD%%XoZ($I=o&S>1X$V-itTzr zXx=?MsYQDZ0?|zS@s5kIv=giBEK>H|ZZqAG!CO)$mX|}hI9I_9*tvi7sQ#*Py<EI- zK`@3Mwmi)1C`#Kr7{~`<MwEn3St8PBgi^oTgfX3VjI7)^@JU0|+-VFEa2a$?Z+#rI zG9tge<#?}TOQiVBm{R}r?M+rjPCVuSrbo&O_or(TT9fvmZD1#~Ee`9%Ac2^bc&tBS zl3;S`_l{+Vo*)2%lVzHYp_lW@)ppAvkIU`*Ppw|sWiogSJ_q$0R!o7ayLbB)J8LKy z({cl-kfVc_Zhm=zE-dB{S9at7bga+6HgZz2;j%)?oL5nLnZ0bK7vB~%X`EqT4*kw9 zI$BIyV9Lu5@hpM-#xE4%{DZ*_GmF7g+t^xI*Py4^cX<f~3kdYhEewIJiNFpE-9Pzv z&Oj8CFk6Ee`>p+~3=QYb{^S4t=eItKJ3VdknTo<J<){^M43fam?+MdM=OQ<pKKl0R zWmZOK4OQtgX5t$MbUwUJ9!KO)BeYdLPaSK{JX|%stQPlzn80=y^f}ol+ijd`YT~tH zr5ko!Q6|DhF;r&jgx?qsoW9!}4#YmLNTl<Vk|B>^;yTpLty$DlaiIY<8&Y_FLGkN4 z=aN@Pb+u8PSYU_JNMpFuKOO^I$0g845<4V#HQp)g-0CH8!o+(&$W$XYqlO<m1Y=qe z@x!6WaQQLCHTiF&Q-K;a(?21R-Xu+dKOqP!WW~JADIZ5zzqKETvd72B50!mYIO{a| zvX{4sSEUDH#7vsp8H={LP8(gp@qO>i!RS|FG#1f#>8ayM$x3?+QUi-!;HBX2J$o{b z8Nfku!qp)R-BVKo8(%Ti(Mbx;b6(^#b<jakW#DB)GmG++p5%hHVFX=RL46Ho0}4fZ zAhIvvH009PVwm=5;qqhTM9jxI3f0%#F=}VGA%wZ(g2Inknhue=zVXWCXk9I}e$(W} zm@?qrJplD}ay1NjL+Zj&=K}r1J&0%S`*AfuT29h#hxO;?{8(fxYw14Uet0X%UP*Q< z=W)2Orbkd{!UsK)qU*i#%STrzvodbwHeZSHuO%@GBMhv(eJN;|RldBN`?nWgtoE6f zpT*55+9Xa)57#M}Wi~^m>AQ#ToLghtfrz^wYn<=Og+07N`7RIiEwB;`^?FkI`yKf$ z#cNbE@T{_m0dbN%F(*uy(cONPX$>Dv*lxrs9&$4n286Q#jD$>s%;^$+Ys{Xd13Dku zP!L3*H_}6VKo1WG6!|3P8_=2JEf6IV(di)Tf)X|p`+T7qdFewbOO>No>Ni+{PkxM4 z3D`|=lhl6k#NYuL)LV;??2(X9anpIxpmE3IE*)Rb+vlZ0aCeON;gyDM1$g+-(14Rh z0%UBhe8oClj-m{Efv^-J$)y&n&FpD+fJW5nAy~Sy2o0dGRe)*+F_g^FA+oRMImE%t z4Qo3<I3qTav_UoAr9qsUretsliE0v^IwBiU7DkhkNr;lLytVGr^#Y`WBZg-$O*qKf z*pLh2_BhH7Y7k5=Fw<kn{P(EVbYZa`!CF4Tk0aPS8CfM5T$3TVlTCGGvZAKNz|263 zaUw7hgyGa!LcZM3;&LZiuOa1hklhW>67*^Zlw#!Hf>e#I|2kA)y-FX{r*I=eO2lT{ z8N81%vPoU_<AlT--PfYWjXD8Ch$h^6JS!6;OM&0QCErMlD6rdd{s=DvP+8%NR~Zrj zA`E#MF9%qXRm8mUzjuyPBh|SPr$)D5i3YSse#hLv{>I2gT0@TLw>Rmx$CUzYjxX0y ziVqbdWTf`cv4itk%gk2J`o9x<c-B}(_KZd#B?KJYANF?a;;B+*?+@<ooXIXQVng`q z6OXSJ94Q&9Fug(5!ecf_A>AF@<DzRu#EZ(5rMHHiXMY~Q5>dc;X?cvtQkKYLy4>gw zy3b3Rav5R8Hq@2YV4?IVdODst4!n9IX7mX`^)PoBTD$XVL3nNN%YOGQYnOVu-g>^m z^?&C-OUV5DMa{y@jHRHofd;8p6uY77Zg{y~cQuOJf+xox-MjAvf2G21X=uy<KAy?O z%Jq#$yh<(dKJ}27)7jXJ@j>mxjnJdoI9<Dc1@9i%820AOaDod0V@bJ;yFM^F!nCWS zJ@l%HQ|h}Tg{UBOMQ6av?onG%7ulQ|)?KcJ>ccPPu(M#m2Mr6j62^R=@+9+3zp}4( zn_+o@MCr*XcgAS4A#b9INc-yXA|*!77jZY;CCX8USLW5dF_@#{{QNEu>AP2`j<NIx zOw$OqpGP?&q4IJTZ*^rRi3wvK+ziaj9Yn&GfjiPS+-<lL{2;OdZE!$LLPTHth6(8y zB^fg_)gO~9#ia?`8fgW0Yek1GxAzcYH4bYF^wTFBNf(3yc0`Ll6?(A8NfwqQUnUK` z-r?%e)Q3g_XEZUG;UW3v*Mg~Ce_q|`quP@FKJ;rK@$hqiESNI|ya7%%a12ug$Ap)w zcX`|Q8SWCGo!F0@PVU0L9BS||VX;X|CRSch2sftl$OJNA4W@oLF6k}MUeJES^90_A zM+1zHf3TKdVmRts7^raAB1X~z3M$?rbXFP7HK>;H>oK2{(wZd7@QUm(|3La^_W&u7 zzJn1pNK(iwh7x(xMmTe0#+c^fy1Mc850atgz%rE=#_tJDBb24@Hf^Kbb6^7J#h+ah zSkyc+LxIB86S!u=KSJ%v7tc*Fj)lh?fDXUKj)G3(>oWe?9@c;9(YM!QOTxM+`V>BZ zddt3H3o7ip>!vMSU-W2V9}z&l76-6~T(FnO4xtbo1>PDz#CbbhV`UZK%K4&vS@-}% zB3++k0#4={{-+LxP{`U~&4Pz75I2*_E?O%WSEkFe?L?O0VVD~L070_w=bSvC+?@Qp zB}?HR03#P5CFXEE!-p2K@P3TxrD3Mw610r?-!MdVQx#I9Lq9+1O@lVT<`8j1#_G}< z_~gQ}Zz@!Op?VSwlcyl>$ExgJEF)JXG*?vAxGy~+^CCN3QFA~qp<;cdM64P&n=Wmy zQm3w5Qzkxw8A2I~SbOl~s{I^F7IfJr&{88yXDM$P7nS+}F2kNC-2$R=6U+n~C_;)F zAB&x~*bk7YH})gcaxMy&-VU69^qSAmEvXjimpS66a$$LO_3Z5DGG+jM#fC#SD|uEM z4`Oc(C_qUN3m5d3?^awNjG$-Crfq*Q?JW&WDV{y3A>=GPBvK#4I;YUetZwE};A*Cq zgDu`4kJ&!qeqjTRao9RJ-;-gL0RYZ&w!6pR-G#7!W(Qj3R?4IRBo2DHPljv2pV#lB zh4e)fFE4a|AQ^IHs@kG9X;Ay`4egt?S&u(;bl^W`>+v<<ae{u7(bs+~Va|Kv>~z4h zNJDQ%giNv370;e$BM%+-e;D|4#hr7Z^;bT1XvVq+l_wC+0*sowvT`NIegq41*uv;_ ztTevPZUvGI3K1e1bGO-oOYIIOWL!g*^QuolgG~3+aC6=>6d#zoj?RU~!^I%k{w7EP z<|<5;HVB$C7A6orCz`I`6Ao$YgtG@Ed^dj9MU6&C;iH2f>o=G093s|;F;nqgH-0w1 z9AW-5YTUsOYAyydy5LnNoQqfvsb}kX0}w7itqO4=CdW9bsFP8Qo2O?v0jQms==fHh zh?^2aAKS<(b8u3ghrX<l)kSez{#quDT!*#2N8h^3f9A0F(liZXi#$n0j2yjP{iSlu z6_JhfI>g-nYMY(cD-mS@{IQ#4Qa2M{34OND9nJs0_BG#$W^l*yv-Ez+m6zka=1U{t zzsiLB1zb>GC#*f@yA=79WOYtHLO$Mk3T2oqli`>`Gzhy>vYG|+UL3bREvDodq-mI; zVoM-K*4UDX3tykcMi~R+S`0m4LrHuW5zaA`vVu0Y1u0jXuzQTaR=}mJCMf;_L^!}E z7>>ZTHWj{!@aiXHclgAS(ChH8fm!@KZ7@wr+30jhC%Hq5&6#eDCaMq<BMT$U2BrQx zw1}}8P>rq(0sJs9;vSrD0lEa}TJnk#@O#tfrr0!I6?>1k1-Y_N*wUw#&x0!*o(b0E zUFwCkG#XU2Bk+bmX@OBT3YAGexCUTiL1L3yj6gcTh{a{bPEzpOHl;4Ygjn^itQas( zgiH=45S%9<!)kN@uM{bw$&w``1ke`Ub5sGi6DTT2hfxlOF<{d`7Ri&)WMYR(4}&Fi zvdOHpBv9S}1CfGDR_C)34>+h+5AF>jNBr{jU>T<|w~BUn`6s*eRAX1T&^!<NvVb3y zl*)Dkpq){UDqB_TAKxpEX9Q};F%F8xH~uvfn1`~FrG3q20SD=;n^zRRVb)B)bE;~t zESPK^1=mnOOyyd(Sg*bFOM4gHbekR~EwU9&-m<Ejn`0{chT4bjkxKW#O=^-$jhIs| z6PB||ZsVKg;8`J!ZOfrmt_B0U02L|F+H%8Ymlv){Uo9hO0^SCy-h>m~3SEbY*YMb3 zf)GX&`PeD!&ff;H4*XwHruP<|dD@(`dDJW7tsKfi@>cdEoD5@N3JsrsU+wNype{Mw zvg#mK-9z3%@Rai1PWT1#vb>~caQRaKVEov&OMuW$4v1!qgo1uAuuM8}E(`8FAN`n; z^5vB;QKTa#ATfI~zwlz8P#!?Nwr}j6vJ-PDO{{&naW;C>OWGY=2F~juzt!LN)lWM~ z@BMKLj}C^&WOLm<D0|@4(GR_mB<FAlk8X{!6V}F=f_jghm>I~FM)Zni9Y-x*oZvCx zr^1mmpDCtUbN&@o=L2htG1bJtg5W!Rcy-5tq7i!F*cWAFDg6e}ycHpNGb@*NeOcSQ zmB57i-SNbDtc@5vu-lka1T@IYh}j|2$hZ8?7K_}K5e7}LiX?9<^hCD@Pcqx{Qdxwv zCiE=bN!%Nn90oR<eCg;ec>~e7CsTJ$BK33XTC($Wt>dYXuR5_T5!YGC+}EXv4N7AQ z|8chyNd=;CfXNdR6cF9pemO0#0oE!o7&9(ivFt^o%grWp{C*IrWx1q;5>#GAY-BAI zf~<+#+d}8ZbVcG4+?FSN{v&Lg6t7iH0yw)7Pk)7vjB4k5P^&qzy4MYq8p%2gdXtW& zVAcN`u6{ovvsMSwM1((>AkKcs`Y-eCaaYK0CQl>Ub=(T~o7gJXv!tC$9B07X8=f$L ztUjnE8~5M1BN0TLa=t9QZ4OZ;RiLk7=jgp_r53bCy}XNA&Y#O5gI9EF?hZo-Dxi-J z5evR`H=*<r?B+#X>Q$+Xu~b#dftroc%a-#?*&%z&c&az@Z2M0k7>Oej{Bgu6@v`rW z^;B5`u#W0jn|>k{GXfB|VBtLzJ6C**2INhdIdGs#pk+d)%j|b;J?O{mYeP>2UR_<- z#IqgM7@5YGId6~FF##Ym6|(RFx|W>?(jaxfMTmtRH_K5+6dtE|2^=84#8A(&wtF{L zoT@3*6xTUNDp~(oMBDs!Kdro_-jOM9QmjUBD$cXUp0_*7zDV;I!>*o9+JNqfk#}*r z^?#HvbUz=b#0H?}TW0bl9VQhF*+Ww9#h8hg>7SfD@#(%dygP?G)<HCD0eQgb?gyGz z`KxAgzg>W_W)M7|lJ$QTj5JqXYPKIN|0%uh_)%R-Hzipezkbui%meSOk1dZ)uNl3e zJr0KN6v~uM665B{!jn(PmPG=OKRX!Ee!cJaxEeC3J;B)ex%B)*_Ow%5)!Kz!g;{Xe z8Y=lW`WHme=LUSX_ypW~Q45Hy)Isq_2W_i<4Dih{Li=mrtfBkqY<=uDbB2Fm!Kv$I zf+{Rg=@foYTU)sG^$^^n8j*7A-dC~5>pjP<Gp({RzqQH$HY%U!Sl!DG-Z%21v?}(w z_SxZwu~M)vkPp2Q;0c8<c(Tkb^W%a+!$U@pt_Nr1N<6(D02X);*wXf7=p4*6L7oY5 zadx_Yna;hKZx|k{6q8KKL+8v$wo_e<%pIBl_7S&1rp1B?(T-2>q~im#;Tu(zKaUf| zb3iv;=Qi)g`UwyX$q)fof5;b?9kdE9i!CU9Fii9(KW~_?mX?{pb8u6`7H@}lZ-|KB zvIokZ36f;qzd=0cdneY58)XLvzI0W0d?V}}xyI>WAzTZW9fpn5h5CY+g|&SnD`T+8 zv<gT+K#BuCTIoCs{45_Lh$72R-vz;D56oyV=`%_cuT}m8d%vpf%Lbo>-+@fNFZi1; zh;%SUu^-x|P8)o>xo}jDMaZHdso~XQfjT~AcV%gQ4PX{fq)6?HKea=P(`$($g1lN< zts%&TSnoq3J{irx0g24(@ox_FC|no_@oV*9uRwAlSo8)-^5x_;4<bw8#Q{A8y~ST4 z!~Uzwu<-$6g5fu?3$Q{dmF$0Q{GlhnAGeK#p<faK4Nz7ycYLB;!?%D^O=JsBy25YY zIa(d;vU-sj@tTQ+&Y5c%tB;W>9oD$}Gg4e5M^Rjb?N~u9=lXsp^A(76bb(Le5%{Tj zsHzuY69TM7hMEBEP76KhFkZM0_!Bt)q1r@~ih7L=xh*;|V$Fb!1K>9-JA}2Lh8(PH z&F2cVLzcq`9+gNwHY#0o#Y`%mpy5RcCTeaxrXJ?E76dCITTN4e&WQ+c0)%ugj~(nn z4N=281z3?mid-UIMc)^V>y9NpFq(lC%2eYyd{|5IQ@aQ8J^G~1z!NkjKOn2f?YBAr z;U!j?8nMsm6^AQQ0t=`|D>Y1dcuF>{sSA6iia*A?JxhN#7OH#Wt%d;~WgTW~$$QMs z(1?R^`Zvvbw`1Ua*yYv>%-=tG2H60=xlm_vO}wsOwm{`MOc(C?N{0NL4BKdO3M9i# ziCd4g#NW;gC~2ZzWAl!Iv5$c3Ud`RUzZXw-Kq$YJ<uNSuQ>8!EQ5niy)e@1%A};_L zY|m=RG3Mb@hk-H5^Ca-e#z^8AFJF;A19zDQoa%UXG>RVjP(}#slIQ>3%@)(hxQ8F< z?FkgCx9G&KvuATuph1-wv_{iE-;Yx7+RKHq8L!q(VVKF&jPfhUPXGQYm<i#?#QMTU z#1skiRru72(+#BW7E?nz>ZIib-(jfu3aTfvTB0P>k#k!#)59xfq4a=~YxO#qoD(PH z^n~NjJ_)VjJ+^;?)y@bO{SkGy10((%83m()ygK@H3s$6=6)2y9T!26QJTy5lRR20V zi~@;;e6q;DX_vdqfHARk%K%^wY?}3djfVw86!ck5%9pj+<jtMKz#J4@j6%}D_au*- zj@_>NKc|Y(7Wd$+!!hm&7<*ILltdHu<WTV?)GORelqb>=$1irOJR<Cemkh$%5gj*r zDQGzMx8(}o3zBqf`Udc_o^Y^NL2>SWYZZMuru!8`251YBYQu1KT)tIG>!}$Lik9;o z4)DIJCmjk~Cj4q-i^Pem)ZB>I7KASsZN(U2>50IGA8Njm(Pd&z0oRg;IFe5;qok2( z{M+r;?B?RCXskHFr<Tylq$iUif5!HR7vDzj_hbKlUrA`n_oAJw+t`$JY65ewwzm38 zVd;Tdz_i<XWJ)}Q;>7Cpa;D&6M=ACXy$9nKFE%ToZIO%_{IKre5aVt3Rr){c+kH{d zJ;%{?P8bk~+;rr1IQ3!2OMVjk&tR@15rATAXn4lY40)*D^U|DCi?x2rBvV}W*Ke6R z<^q7dS@gMz)SGO+H++PXRff;!0Wt((kFMQ(O<4PbF&9#&W|+o<JB)>18a6MerPt^F zkh&-*EdzZLOosKim*L?Tbz=Em?1UCKMnzfTC9E)6u$19O6T*!YKE(@vO%vRc-$Sm$ z!A&ubTEI)>v4mh!rQYNcUDThUaLBXSs$mEb^`${WTAdy*QDC!WF^Z9FrPvmQ%W0(b zec8{P8si>V6AEWxAm>|pY!IcXpWzcIU#KW8+}xzMYvQNqfH1_QVLHez<Z(%*+6gBf zOW*rqQjaeH;LC|$e!2VP^r8Q5UUZ1xe0qS)-)J1G{Uxp0B{CjUJ5>5;eCu>kN2GR> z&Q-bK)vM(ISTt~$3=}7etE_e9yT>~oIhk%(tQ<vn6Jo-tRa*JWyJ)-g_IKen0R=XF zO%z30f%nM=^h(Klx|lLL@+I9I3<gY%r2z*#Pn7pFz_;mjxOH6=AO7{MPwK3=+0p69 z{jGSKuhOM>8p4E$Rgarq`g@MAt>t{HeLe988igo&IVO;Fv3_J$*WjOP9u+4CDxpjD zKgfBj`B~FpTI_2E<t5^6n%kd$K8_!j3a;LHb!@tnIRH-UJ_p63*?(k)9;frRD~>*R zE?tw9)XzAKD^`GqM0!cf*}zBD>aA5ed9OW>I5Pui@BrC0(dN}<_FL~TYZMJM4+9$0 z4Bud+cO8B6yoU>yI}?O8<J6~<*t>xKi8!5km{JHi5v(^dH%aST5YIs2nV<I8a?sf0 z>o&|Q6(GZ4AZ~c~lWg1>F5DwII{%}%(iO5Cg0Zt5-YjP_MhDaWg5wC7@vN)`5W2jB zL@%h;%Qx6P@MyKl8ZJRCq-*I?QGq8>CL<YD_*{C_PsXwJ0JQ2)f5Vwg@k9b02HGG# zO@bww11zD*Uh$%9Km&t8L<cctX82J-5ESaYy!=<S3xa{8$%WE^e)id6$JJCP!JK)@ zqr*|et+*X(F%Z8cjmcmFr1k5yDEyPiUL=5@N%#t)G29PT53?u~pC23va8<~u2D46a zGH(JleuVU9Zwj|0>==MCe;P=QwjAj)q*(I!S@Mg(0t}jVg7HtxgN3FLNW`Gi?0eq# z93g=iVxFUN7st#RVK>NbBq|*;h;TO;9pdz*fFwc>+f}EAr8Wal$Vo%N@c@MpP7Scc z24SfW6T}3p9!sDtMQvt3IL{Y6F)Zb7afoSxi7`7~+7s6V0kt_`3aoR2&#xMiIW{}= z^3eK!-txn|a1boufdpeP`yL|X*pHP<xGLy74d>hD!fh%D7$#Ss1G{MkIKW^)4A@Rc ziF(~Mo$sIqM!x~1rlbMn2Z<b+N0ma%T42`+zKJm=Mwd{`wl0&x0A0+<-^3~4;3I{) zs|14^!(tFU@J?;vU4md9ttZjTd4nxH^{I;hrX`$cf9yC!4^xRxy+-~RZ+g&q)TiRA zi3v>v9IQ%;`w~GP?|zeV@xo;H?cwJ&R<8vZy<Z^IuEC1BOglAfu`RB7fA%3nil_MA z!nvkydBV_{z;}bwLu+4SeT4j?4<q2!hB#Vu)({W6@&g!N69t(2AJSEB6^U1JJq-j4 zf>E^ehzGcL``psIcRC8x<OgTN!v67guo`D-YjNuBN&5#WO|+~+mjAZnmqJjz%7hmp z!6%R!_gH<mysVve5f2BgrcQ`!{?oNvOkI@PEr+gK^a_;wNha*c4?fBZfCCjwWALHS zs6{)yS~G6*?E%Fhb>|N%BU+VMzaEQEm}z{%RkOhQKk@_c^uHNV1PX`ptmvRH|LD@r zD#COo$uzd(vF?1{_Tp6spi?WwjH(`n&vR=Y&)JWqgHa6~kXPH`h7)0Ka~a%XvgRhA z?1E|{VE^-k+ed@$>Al3@kjD|oFM6>n#NC*~-uX620ksBauuhy)&-1EW>p*)vCIEzp znqVf>01dBd=h}Nq5%-7QxQ3V1V5Xb(bI|BMsJ$+#uYPQIrP%Z>eWUz?nqVrvbCnxc z^EFF$2VGOd+-2B-ll|tUQ<|^6*b|_k&R~7YiuH1{Je@``>3d;^20BDhv{`jMQ3S)! z1e2sUiatM^tuUWc7Fn!sk)FgYq+xx%`JX>2vL1(L{d7{=UJj24XJ*i9JbVu7n8e_H zAvfw3ul9*}$P4n&qfT3P9cpH5!~{pq2U1rM@!frk@TX#+dMyo^F`UsE=`~IZDupn8 zW&|Y`bvbV<e$|b^Bw_lCyVZM=Wqba9T8eqcT!80#>oGDfK%u}-_$>SIbUvpm95{dJ zrcUNNpC@;*se{?qVX64L_v~87F3W%qYOTyta%HkWAgf9`7%r%~LuwKX9j$KA#|FlX zj8BQ-p90rVmU%(Ca*PAM@Sm>zFRsPSkgXOb00wc3BeS_yVi-={k{B&eObWhWU|v;k z8UBOPm%QIUL*2cnmZ~F8V9_mJ7?j(Wpc+#2W6T5ViNYEHMI>=%1!JWOj9%at+>`rj z`Q;LZYf01`b8Clw!Rbdd&9$JmMs1Tn8M#{#_asKaA;9o{AItEFwnG(dg(zNTu3;x7 zJu3dk;XSX5g3Y4oYoUJJ5Lug1OI=#4tag~V5>0!|OJq$&r58JFYK6wc!tpm4N`o|d z#`x=9dyr}f%^mf-4zMFObTvcqlUe%~opGVYJ15W{@qn3-;sQV}R*L6BAg0>eW^~RM z=?4aaKq^sA=w-Pwc0^NPXaVK`M162QVsWN0BiXSOL6cA(=PJ}ZF&v?$p2DJFqr~$X z*rijHcv(GY3KooT4g)-CvYhX2;<9BKw)Vm(WBJ0LP^wUpZYlhc--qNO7_8VKU8gzB zzyI70I~znhJWvkldc~LVu_hQFKQA-wvc}EW)(Lz@8-_RGK{?{J<NxjOKwbn-41;PR zt4DdpwZ-tuhtHezPwA>pC=1`*3;xuRDdgWD)szN6e1Qx$kP^iA#*!rGRdh!60%iMk z7MB|1G_fJ}#gT4tBd1(@YEtWQOdqtzgrGQ*8M)bW*wqH8gnq>4alPq#tyS~-hOWQk z9f89YS`L74MUW{fliP!1Olu5tDSw<g^KjZ+6K<;=@VfZ8oRUNXQLQg>>BKKrCq80w zvCy}Y`?ebsGY;&Tdjj73z^{GiaoFHVhtGBu-TNoN1fmzB;cBcp`j&AY4x5{Qy>_HM zMn{zNe<WQASd-Vbjfz*%+oCwVDiB+OObWMP9WWBOLPJn)WD-G;TA>t&DhNUp2x41= zY9e70sf03$P!Po`L!l}a0<_Ff2L=UXo)V^vee2Ngz3;yJ5R!j5XP>>-UTf`vr>Na( zksYb77X>yw8tUWiF#*1hB3}IHGphQl(@B=$nOKrP>rSpBVpYMy@A6%t(J*NYo37zv zZ!nG&t0pRrjC33Xj06rX!Mc@#=@s88uJuPvXjr1@*dM6hQxqSuCqlIA_T!Yih2vxp z+CVlR_Zp!nV;=I!3NsvN+t3k;0j|m4oy#hz0&@i*srCgY>jBY`ebCJpsS1SyZNVR( zfNTJ72rWtXL%HYgL--g@1uaBnL$a6qGQTP3z8voIB>^hGi8*H@c5hZTs3$nr`p~2p z(DB`5V32Vu;kR(pDVHFwwsEBM5P=>G6FgTAL9SUd&}{n~S_H#hcM60<KrWC;6n>&6 z?k{Y4v44u`w8HsqIUo596MGu+f9`na$?5+xOhOe^6K)^9T~PdbMB`JCq)@lNRDcWd z2qbU7q7yiCct5Uf;*2dy4iR;J5e}+ex&Gir1dsQsW*aA*$GM|-_T3EFLdz!52Bu(Q zVlpDsYYP*f#l~wJQeU_e<d}k;h6aK3L!!v&X4)XQ+6W`q@DVl3>TxWC5SNO48v_?H ziyJD@Ji`A3C546{iTTA&7GYF6h^PYy><BO2d-~IfL;X>FIY!J)*5|hA_)_c=w~5Fc z&%qxPz{w>u6w%O-fGeW%j?;D_T`hdVPMmOF6iaX-&CwNx7*dT$M43~dfsu%l1LlTs z6yO2&KH-NGou)a0m%EkPFa|B)vF4#AWD<ik6X_E&AEctXn6!k1hm+=wD+V(JWF`pK zno)D2C92$HwXrXL-d|hiAJ0xdSuKV#E%_>+O;zqxb}<@qI1%B{iKJkjfo$*~2AeLy zq`yg+Jaf=nNIVDkR5BNYd0G#?lV}g^r=XGX1Y*`~HX7Ps5~?;V94uV8tzouW-4bBu zV{Fq9a5s#H7|~S^d8z3hH6evHgYZlsv6+jrBGHz5*z%hu`m%zB*wB_%2QXRTk5$_X z(7E$bsOj9<C{drV+WaYvTcgGu8U5>vuT|}OxzPm?%`|kM5Nv)){55A`)!spDUJv28 zn5m$S^a3^dn^I$(<`myN^uzoA1pQ2{EtaqNZssqVl+oF!pA1w=frl0``b)E7V^VR= zwnvOtgZ%lpMv@7AOm<$~^rmVJjWF|;suo~TI4B@K;no-3QW-?Fzxt(0uj~8xzbTrp z)pZvkypH__zt>(J`=RKX$3}j*cJAwR9(RHh*GZk;eN@0$xa0qTxm-aVrNW>9eFG$F zjdH0sWw`Rw%17;ARPi{Z?FuH4_o>ij)lH#~pWXMW*=#+Cxe{Q7FeL9??bU-#6ECi- z(eaB7(kKBl2WT3=WO<!*%e#Li_m4Ev#ZWj$_@xYVw#z<f9g-z>U!{YS)F99x1%w35 z)6w5mW}&Ntk&c6afCTKZ`{(vI4l=%dIM}7rvETbxR5ues6ySSB?!srU&P4|`0^8vh z6f&OwP5E#_)%BhXp@B+6V%!vbnvW4#%$Ebd2KE`}8obc3xlreDCiJyeWA-W2fvV(z z&eGv-eUR-A0b*k$Yk_P0UMAMiLXh(<lOR?5CE;(%%F!5VvKqFa=C7NbT>ZT^sGE-- zbg!sghtwxA`(%JtQ^XWrguO(#B9yoP%bMCWq%X+iG2;1I2Ua+&As|doK5qG^XZ?jT z(_5o-(FYZQ(83bs;$FtZS^bns#w?6*OH;#7wT>TW-V(4j!^{!XZQ%B=qwGNAO~#qs z$TH5+xc8=^MQ#m0Dl~RT5rQt(0(4>+0ZvZfAK|ls8W>TQj$q*uF9oX^z%R<$;Oz30 zo3FZ9egT_Nvf01(Cu%tC`O!NUUZp7zaj?phf|MFAa^?i#mCU^Kw0L&$m+!x?iNhfV zq9HycE%>sJL?uR*mpaJQQh5U~9X!(8NqYo_%$~j;k{3p>L09@Vywz+kHaZ|hvgki& z(Me^ENg~HpEpoRMSHH!TMH2JDJ9cAkaak<XSZTmOsgsPxiBYO+^Z)L}f!cizs3l{@ z_Y6k}3V0xk(CZqjY~qmhfpOmv7<KZ~on7{yryabEUMv!>z#|ph(kO5-5U0h>xPMg6 zwVfpiPk0>6#EmC62uOAC&gTF9tleIHo;^?#paon>iqL%f$lCbprQXjRF`i(sO=Xi7 zM5vXccWfW~pe!J@Kj%n$Wit&6K`X8!Y0OSkHT)x2`JMGY!earBhy6yi+{8uPYd-j( zQ)N_#I&{8Ry#;?$zWgz~cMtzs#LlbFFS$shaZ2=eYxKf|@Ae0B*PL?hYLttB%*EFi zX1?pZ{x{|AwrTB}Bzf=Ed4JChm)7@9NOt-<#_cz6$iNfhu=({rHx#1O4?L6OIMB3- z3d0U!5Ov}_PYBI@Fm=kQW%aihJ=JKIGSI?Z{-5G)G6wG&&d7cXTQ#^XAgPKXK75!p za&2hIF6Kd?1M>*rLA68LQTD!s$&2ueh`qyT5jfs~aXv9ddqzNw>S7z7G}O&Q61TSI z!QIrj#i$MkA7_Kr8mN*<!t9QG3M@>QKu7AEbQ?Te@t@gQyrigV*zuJSRqtJr2jGAq zgM6Ie0-zSRIHY_~h;dEMU=cztnNT8N!J2Vt3zB6IKwuQ+K}Q%FV;t5G?0YJ|WP)97 z-(h(T0oxY*nM1kKL@JphoWjzkj_RhX8%{UsnWHJbZDD9xYvm@z>1mDU`)&1GzUhYq z&YwCzIw_2*DjAHf)c-3xyQ})*=Es;U8m~Mi@=itu(D4huke!M7Z|g*m_PqamTI6gX zIo-B%ETWc;oys<Y60T(bmj}_g2F6+DR_#sUo{8BS)%xFQzeyw=ywyX0Q(!%cz#Z-F z?cQU3@2?u}2^6ZZ8OPwrlM}b>H}3x*2Y?kuw2N7uE3PTFVCFd<RLb(Un?U+u##i<O zbqzD`s1y|BK+a{nbycyE^m;+qI3z|z(W;L<M04f;XW0qYz%FPZ8I7{Ch2(ehV_k&{ z{~|iSN3T#ko2~2z<yMv#{<ao`A2d7)jXj$(1zqD4y~>(od3C%JlYNHs9_@WN{p_Dq z4*8Ocz(Ov6H#o*Q@s4FOYpTK4&VCc8NP57{FS@DH4b$(a)Ee>jY5$oX1H&A23L<hw zOCSF<Slq046f#zT1fYI=G(aZr3T<&Vqk_42Uk!Y*`5;GmnZf;k+wX3gabBYG{d5Sk z#g3-(v0#AH4-22#ZW$`JwzZ6bSUANds2V?KD|?b{BfUU%<M-y0qadaEZwe*jw;dNR zol{%_ACI8h4+~8gRbFYSstk3;pb)A5fH+lVnu7Wc8>*qO=bcT2&l&)%=Vkwn6LHUB ztVN9$(v7n5N?qoAkEft{pgK_%Cb$kXI1Uys)?qm~>vM~70mO4C|L$AKZjMl9lKluy zL=f+k(WF-Ic4H4QW)r}Ph2!Huws`|-I5<i~*fWN2YPqsH1WN$YEh&;Vh^ZR!ToAqO zZ>~gmKomPfIx~xU-$nBcEJ;;iq&}J<NQtg4K;%Ox(0B3jFo|_(sG@99^n*{>u{diT z|Ce3{mWu$>M1iYfD23{hOS}jM$fX45tiwP#NHD)Vtj5Ja9aLZ3E-80j9J7n1?HY+e zHE3gyj|p+Yh3q%N=x;t_UMP1;C(a*IzXw9dm(o{jB6%}OCkMg;WXLb|lhKSD+OQde zh``)w5Tx57a%UwhIR(3e(pFs{Lckvh^P7Qb?Mu{z5kf8gLGmmBLC@n)A+m{+1|J8C z2T~15^n{=pjDT!|U)nxgvhGW7NHB>K6Lve8RWo{LP19kf1|h(u1sz~LMB~P-w?xvP z{$cK0?(>(bk53CcfM!7J953>=4W-UqZV3u^Yvfoq<9$FD>ly6U`)Blu$ek}03;k8? z=x(qdJf%*qBV?6(M~6LrDV6_mY<?pW>A9oGKe@9l_u~Ucma^`7cyKfPW9CY6?z^K9 z$cG;^vgvOpX8GNx9|v;Qg1e!n$<k?5?L9KP<Me;0y!a{m-)vk9lLlNWW3HuQ%R9Gm zo9UYVuf5Ch@B-Pi;OOm1wSHx%BX%}bX!z1GD;5H7qz0Eq2VqG3$VMh;Jn<7ZgB%|u zEQanX?c2ewPHtg`gzT@z%4eHpwuWuUKfUW=<GE#Hpi|;ElY*N!)K7n4d^T^zHM#@$ z-Rj}NDq&+97mjO+l1ono_QiBf>un-Uygw|O?Lfaes`<QM>*qqI2j?t{m8lHH<t{?- z`m$ozo<94Q=E<y<qI8Vk^3lZ5mlbbR+kkA1n~pO=07S<j09ndJ)7Jw=)3nfuF<}A{ z;-rq$JQHrV?qjd8#*ri7=BHVN-^iWYm2de&2>smhP8mWoamy?G$o7S2PR-3z5|$Pf z<8itI104WK1=NuIq;7_P%~DJCyaQe-@niT9iE*8Ry?f3E3vu0iV*mf*2Oqq7_Os>L zIN>|v|1&+~hcjFmEBXBD*zV)riju<T@{9YBsh}1g1*ddmWA|mGvDx2M=+$<7e`@rn z?uDhSelb}?D3E_0bZDz;{({HajXj!aJjjnOtG-wajdhQRhAis%<IEB7Cl~`OI(8%{ z>!Nd9_YeF>G#KO|kvfB|tB~*&H69xu0x&`4vq#0o-W*i=Uby5se+Okw|IhnYUmFJ{ z3Cd<TbJfsDUyalG!AGB&964S04M#x!$3@_U7c_%Zj2n2*n(?ZF965d%WSJ$|1^Tvb zVb!C$FOP9e>~I#>?@=kze7}6d*86o{7DF<xI1#Ek`Mk$5n>dWwsxn1v$haI3e454` zHMWQw<nM_6VPMBAk#>6p=r&k<X>nD_Y#)AoRL=xSBN^?T`*XTkP<7B?grYGwn%$bV zmkV_m*~r0(n;!-YoN6$#ISQ~S@f(JDtr+Df3ZI-3ZUq;eOD7I@|JiNt{2E*Zd&5NZ zT5OP4L7cBh1OBx|@i+8R-K&0JILoV$zIzVs5+6Y32lH?(u0Du91IasN2`)PB!0U;s zWy{efMPpCR`*T;()DwjNP3h`9u(|4$CBEm96I2ii9dBh&p0G;CtNw=p^PQ=akNyv3 z-~}w1h|#k?eV}pZy*phrrZKaCck8C0_7r|TKX<hmo^Ej>kY@jJSJ|1lmznr+T3q3& z;cV;oED6|2USXxv#(gH)@B9a&)af^ND?I}`xIC5Vscs`ds6x792NpuoTI~9GoasUq zJ)R?AAO+066qKhoee1%pFByymC^=^n>KLOK`f|6fuRBFg$5+R9DHVRJID|1)*C(iM zv2RX`Yud-R*NI_F!h7mZ(q!8=!m<CzRtL@nDeqm^puUYU!04BdmHpyjINI!rRkO4k zW<(`HB{D=N4uufP5L`30qhbshysRE8PhUc4$T_?<L#VBJ7*>G9qhlfyTU=XB4Vt(2 zj?gjia&O(waUQz2t<O+b4jKbMvxMbQ3`H~(YGN={u4tld1ivI&Hq<qk8v@z*OiR== zG?%1)2dYvIS}k8MAiW~YD`jEs6iA!lG76n!mv!8!!w$9R5N1S0WoKkyQe6_#2PPEY zYC*7&J7~RoRcvfhRFu%QKZE#oe0$#iaktt1s~+WYSkenC1QtsDg%br|mr<j~docz# z-r)u#1f4ixx7z?lUj`nT<?}u>*dFn8u2l7umgaMllW4~O543)>a);^V-?c$Ay%(lR zIDGP_RqyS9BV*|`+AFR%SsI=$({9g7N)|J<*40=LP@|#fv1*g*W%uT3y<fji$>$_( zg361A@pBdUP(%8!{QNV)e8Pes==iRG%_*GvC?8*2^v`(Nw;p}On*dcf%4Sg<z`HXy zyj2M2lDvmHj<O^^jVN$H?QFCgy+Rz^R=@iuaqfdtEnp&>*@1y4(!1nZSgbY0xd8Ec znP~+B=iW_1J+)|g+7NL@)l~HmFj(ZQ`@~GDx_&b^WT5fA+aJkC9$3>5XyZD^e#y&z z-Sw)`pL>ps+$-RPD(a;CKGU)2oROs6ArYHyY)xa#LI?tioIz=YN3yd-hPP*0U-+=P zdu?0AUPdz4e}Ash9Q0^ncv&yyR^)x8jh5S-3nrH65&jCCmyn<sMmiBUGkaS0d64E? zcQ>=eLr?w<Vm!Lx(jaF{bIRyt)aSUy@)w4ls5=2zg1a^mAE@gVzIe8$|Ni6ndQh82 z`Gr;X%7N<}PEdn}f>IbQBx!&_%6wu^sEWmSkS^JZ)jTLn@zmk#r-UOD1W9NVyu=<a z$h}P$rc20T$AK8goHzQQfb(OJ+}nJRz;i-4PDqE3Y(ELL1dM!KzddgT9vv!u_cp9y zWKh|xxD5x1?#R3$hg*M&@)!^VC^JTAR)CNs_jdyFpiR+$N(f<snf$rPU`g6nbz#5_ z;4(oYqbhO|@Pr}f^QD-=ynb$&hK{JRi^@pZCZk}`L<$biAso3vwVf2EE*wS@5?;cl z5$0jyelnV<0`MVdKlU^{nI+%szCk#@1;iLlkdfy^hS0ggl1HF{g$g|aq*#ll^X^TU zS*DEx;?Ha$0=>8;Uj(a?3p_}dKybh`c$`lT7}WxnFvZsPARH$qTI?xcXM+|+ouJq8 zq3lXTLjjXajgt0)3|0nbY>xGA3>Jk|a+&GMr-KVu9Uh}K#XATKGK9z@@SwVcjF02R zeSXZPa+(*fhOH72hW4R>eDjOYnWA;pG=Hu0r@YHa?*ZRGC{!INY;}_8Lu1kmVy0^1 zk~lvPOjiL56ZznQ(;3n`iCc%GqdpkGR3JZgqqlzp!SY=7=JC#$!oK!gaF7Ic(EUJ> z^hcY@H~gTS9jeiAReq67AHy2J5!IY1o|%?X%YQyOx#aS*PhWALF;C1b^b1-WQLR|W zg$JhojMs@Cc!g8g0+3Pg^kk&vrcukCW&E)<oSVP|(%8L455m^IO|AMc^mxlN4qZeh zpQ9)9+Tu^{2S2>Gv|V`Ht4=pxjQG0uh4bLdRg~8k{bFem`gv=$4iz-pz6r)G6%Bx# zM9JXQh*dZYZttZ%7H>y1M?2=;kI9aKX|70R4bT&C3!gTBd!q*~P=FX}NtW#uaMJ@s z;)g%GBxDA$MyX4}0`#M2YsYo^>Pr@j{|I|obhXF1*98$hUkf;MW}GR=NoBRbVtvCl z<%;HxWg&I`xbtPzzZCu}u7{bcU1)so^$Id%tYE+QM_f0RH=O$B^hU;1a_Cok>9s9( zuwEU{1#|L8OQX<;meB)(3E24c#t#-{_3`D#o@p(1eY|J#c_R69z&!-NuUc1OjQJLb zwKZATIHLk~lIQcGu&aZj(=@O%I1~6Om{%>+>~AM#ennsj(T{^?lTlA}pX!fjutz7a zCuBBU-|kbB$IkXdhLss={6gT3#Bk9}sl9V;q5pB8Ksc>W6bI!G?|ePf9|ibJPct@Y zfZ1hvx7F0?Tpu=hsb0_xwCllN@+X(p;g-7KR=sxQm*OsIfCwlGZ_k`t@Trq2jEkxB zP{!YOi#uX;UHa!O`HNoxiHQFMpBtei!uPb5n5`B_($}0oZb8AZ3rN)K_slVoQKGs! zGNT#selHd~S}MkwDS;5g<J3lFwAiTo84%^Humb3lG}u{$><bAA7wn&s$6K(>v)Sn% zRc?)1q~BlS2oWXdjPSX9Z*1Uti(mWIP3XmvNn}=u@xdpzMdyVVQHMYZM8`&RK4d4q zB6uwU5AeHWe5t2v7jBkMy2JK)r}ba;LbC;Fdqut_`xY9qs+S!Vf4r#uLtf5{(l7^+ z2W?vEhkRXNKoZ@&lNbX8_Z74+29xz1;LWiX4+KE}=bq1vAVuxtLrQSr-Z~LA4ui0( zNChfHtl}~zyFALD@EBF_9{STBk36<#<JPH1<*%&uQ$q9=_m%yZ4X$&9rjA+woX3ys z*?G5Dq9}!8ya#;)h7?gZgHS8O>Oqy)I~~fe4!NY9iSL5O4yz(!bn~y9&-Z_tT%j+t zN!)@oDTkBz(<b=OU0IPl(9BF`DS{{uAYx*ntIsk(NCXd-SfHebXppf}lNsNpTZ6-V zxfMs{l{f6(9F`L&=<r5_VK<;a;W8lUbxZp}gdJ#Qw6}mBv9vm&E<%RWN{vcvPtrgM ziN-HG)>xm=V-2*n+?ZK|X9SW`9xdnaQAl%~w>>AhlqsAp=#3J+Pr%6N(sZ6DbI$*! zT!X2j!~l3LDr8+=<P%PW_oNYmP(l9sx~1=M_}C+|Hj|BRusBB|2;!@pCWqR4c0=)# zV1Y>HgO-1Xt>SJ2D+-`)H1UW%=IDmlfM1y|;G1N^#j;?Dttms&BCr>H1OEY!SiV^l zwt}+}2b0(!_wZb54_mxULDo`GwlH{0RH~nH&=L7ou<b_O_;B_j_``Ie*MU@4Wxd<- z+l5W?!=qKJCNfKu)w1mZPCPmbGLy=g1;6Rb&%HO!ln5Oli$JCIYf*~4x~TREIF9a} z-o1=#uR0@VuT9RRmTnbT)E&IFxm4D_J*=3x2&)PUkB(}>`s;5>m|J5Hg?sv}{=3~T zcY2*-+#fye4Q3J*H39IX`9BW)564hF&%!a;aL3W19VbgVbkV-w3x!u=TtO(e9uo@* zRb(dbZ_2|kA|FJd)l#<F%YNToY(Uha%C6H5*QM+<%bg01mWXX%i<#iY<N<%NZR0*A znCkGIun(pW^#1v1YSc-vubj0DmRI0P?k2s^`H8AykGwwIs}S``EC<f(m`t6Gj+q(8 z#KD!_F#IG$;s1Gj{pj<Gntrg=wb54fpME~~-|{JC!R_Sebb+b`?qB2#s)n4&t-h=< zIwYIj??p@o<)ymm54Xh<QkCg^LctQy@$E@oY;lvOS_Ojj$Zts*81Xw|;kLv_Vn{Co zn-=T~0F*lgx747$A?zdMO)GJiwBVP+$Nl~~S@;Q~tMgoDt?=c2jQdLP{E*KgdUI0@ zz;z4m8&W8ZTA^M=D;Vd~@SXF!xTEBG;V7t^tla9wQl_F|MC#a}qRHE7=T<DLI^#sj zy2mF~#r+UfW}^#7GAr?)KfkJ}#5*6v{HaEZbh?az@KlhA0~2_oNfvfJ3ZCz-F6ibi zvXGd-MOUG3N!XjnT;V>|I3Envc_H*!e7L#7`ER;;3nom$Lq5$XsESNl%Snh+AU{Dy zBH$nkBL?z0XeS~b^6SAr(&fUkKkE`fQW12FE>WT^bmia={}+yG0RP{^Z}<VQ2sC~a zGZ|o$Lpfds%mCzV)Q4u7<hH#CzSQk>cq!za8GwQG%<y~cs|fJFVA>iwhoy`tXm>Cp z#z$D5M-#9=9oa89y!0tPsBv+u$o7#?Jc2vs=j7`t&}$>W!`jD0!yIc8c4fd#u0d8p z(eYB3i-2zvB#LZm3b!DCEyTZI+{@n2fU|<Z^eYGRW?tv*_$Cuxl6!IUNr_JOgkuXH z^s*8DiiN8x&9l2+Og4l<@OA+L6b8r3?|X%{&W(3MGvwW6%IZmQq|m03cD^;eMn^;$ zdkK9Vf~lLlZZ2;utlZmlUeZXovv#9t$H(di_CNM0E@=;XId0OYtezIZqg2@yraNu? z%zR<r?`{`0t%*rcEn_gX#`|l<?oL{JkReXCF7#kLA%^Y8%{|e0b?`Upt4gY>BT6Gp zV>Znrd||kTb@b{@<*l#)%skHMLjGXh5QW|ofQpgPp&Ry`t*w4yT?tS|LW60vU(kPc zd~5j>|Jt}oFQVFM{S@zj1%~I<-#s>DD>Ne}$n!;>arZ9LsC^4D(_5-73bW@9V(Y+0 z5ohguXTIWtg;XsW4V71fnAlfcX`hS{KAce*PP@#{X)^uQ#6a_0gj0<hZ!^9NHb6gO zoMe7LZ7~Am-i80si#~U+QGB_Onz8UAbmw1a;gl*w`Y`kB%no&XTlC#{kcL?cm<bEW zNf;^fqy6kP9-^EPXUIU{eBqs}mH6`MbgoD7RR5(zn%uj}9^|4s3}3zeNb(V5J)J>~ zraREru;hF=PI+nk_BUk{`z>{owU&Sr&?t}56;#a0orJE!hBTHwhAjH)oegz+o-BKj zt+p{qz#=@IJtIF@j<ywWAMfOnJ@%4NN000jGyA+hWNA%HFG$g$n;-)yPv?d%8<)9# zcXr(o!OpZjic+e4Q6IpVpD6wHpi}&F)m9{nH@&gwfpNGo4C%RPxT$CN9Ux$*mcxq~ zk7d;Oxlh_kpLp&>Kd&;aWBW-Wp`NFL&>cU|_x{g<taHqAYdN;XFv^lq58s2`Myz{J z={m<TO}Eh7>5+W9%J-ORbBn4*Ah$=v$O>-q`9|^C^zOJ|?Zw1z=!Q<{#Lp*56p{Q{ zY4u35-4Ag#c*gI!_gZHD(JX2?nOPms`PtWoXHFlQEbxN~@Sp@>Y|v)*q`oF|Gr|{^ zU(L}AuYj8s@OBCwq1dY=tKqEiADNR|Ty}@?32CpZMk0dSFn6vIlX4hr9^;`Dd?z?y zda&T$52O68kBKr*RrpKndvjWphN)@+;oKy>t>9$kBec}{N-u|;xc6|Xp^9jUUy65P zeUd|IFe@l<uI<Bf&jsO0lVkBU`uG`2u3|4IFry~nNdp#PAaw1c$sNh{g4Ndu1UcPy z+mtu9jkia0f`LXb%XqWDB=E1&%Qf!WHIwuTX`=RAu9}WdJY;prp66mJ{Qs4DGK6;F zDHseK9pA8@`}nc9Cu4Hc_6~~2X}AtGYWa=P!ksSH`=#vgh3}>_?WUCcIDh)>#Gb{` zS&!&-($m!uy5-Y4`TG^v7%*r`rNix5L>Cz*zTA9j-`WOR>WD==tS=S8KP7(eY$%4f z9QX=SQEc<cH^D1F<3M(s6wCm34iVFWFlOP`mPdmv&WF!O_U46^T}J+uet^#Z1oE~n zk@o*UOQa^FOyMOrq^}U^i);d2b|Nk=4W9wY5lm7GLL+kr$gG=waoqyuqD>m$8=#O~ z4vVF3<dprS<Yv-t0;m_ERA@xjgRVk^?^6A%=rEW;FbfwVF$-Q(N*N%pWf(i_;}5wG z4wZrI_2{o?V#e_*G!snc6Sa>bm7|24+0z7w_U_j3pHC7nN^OLaKck+3ehkan^r$^5 z<&O1m5;k8LhBtMx6Vv)+ON?#?27Y1?IEEiiWZmsgPvt}PTQxGWr$0O0rf1X;gl1tm z*kQzU$jK$bYq=VCUIMu*ChNF*M)EA+;W&iAi;r8{=DGtQoVymWwPWj9TWO%*$uP6P ze?~3cOFAX6uJmWl8-AT0vJQ-igN^_f)|*bZI3jth%fGo+^Z>`BblBE(x;fwtS}Yzg zJs_!Sn+qqX`XFR>MND!?rv(-4+x+UAY`yEv0BCD*RKtQ!s#)b+xk?c+HGhL{enL(5 zsOYugTAx52wgrktQvk#Liohekq`upy+^w{IGlk^4OXOZh|DF2a{HY_Gt0R1~->f70 zrrmkHPc{}K3X@|=>OD0&_x&{c`Ab^7L%Db!+OckiIaj%}=#gr*s%`V8>Y=Ss+=YaZ zmWT;EeO&5$?zp|vH?+Vx%Ntjn7H0rqv(#HeUG{#=Bo)}qD!e>zk`|2r7-XHtI_>eM zJ|RlZ6m*~we|$9*c4wL+KK5XToPbiU4d8^z{e>8Lx$OA9p$Xta1%J5N1M!B^LXawM zYB8zluc_|&_IBrUFMB)FUcpLiSiF9%;NL_V$=*MA8%<fJzRUk;{Ih*_gEx>l%^UX> z{m}EkRTUk)zbCrl5BnBmBN5(jGXEQ2Du$JfW5--+HtQrKjvjFgnEQjUs;(x-;}BM3 zwZNAhgKeM+Nnl`lD7ugs)EB9jCE(A(w83<`6;D~oH_OaJA@M{lpwl05s@AgmNtJSG z`F;%*Ju^=$y!A3tKK@-S-yca9He*V~?-&sZibd~C&+IgaL<q@E6#-h@DgIO7ezdC~ z6ronKe#AE=USWf|WFjkR@)dYU)4(NdB_m7lP44gE&6Czi%v1@purNWBGe+Q!FNNoz z1(uaDLNH7j`*;0EYk|%!Zc9wn?Zw!c1U(8)UiRXyfpMR#u?s@(0g>zZO)3v3*vgE; ze)~OCV)bn0hxsC8p;nCcX0!!N7E`rAK(;(PT-Y5lGIy?pPkj8b<rh7f43^@OL6ZfD zbtcmfZ3?n)Vc~?9g0qO2?z#}~tN2D79J#QU#`S@pPLzu@iNO=xHxMpBnF7au`bo{` zd8j-v#*jo{%tju_hCB?J!3b!omqAv6N!&G3^JBsF)WHdm+iJl;bA_<L#%4(K0Aw+6 ze$e8qN0)#ATO%Zmt!JZK_-~Y3+L|z*3nLa&Rham~UC!KAhuBD%@j+FDXgYic6f=Qy zUyl}8>w<8ZuyHZIfo%}za_$@<8?D+g{J7<47da3DvD$YS4^L7?Z-(*@L=n6MlpH*$ zQdME)5quiw_>C#y?>&EAs$PQ!=aYti>fkOvl-aPNrTe3{s{6CokRX5zT?&gx?09gM zaERX<-T0r=NoLmc0MX#$NmNCZ3MxLAH$Y)e<~pIPEPsq$cszb;zIxrrFAN`0oXWup zkOzMkxghUbab<8SB(@OG!d*?kxrvPa&}dWDSLd$vynHPF+U<g9pizH<bRU@GYkNay z|E6e&BI0W1%8$Zuk-R*#y3ul+!9gA+n>^5#nTBbvb~K4@=;%@T^h48I@;>kBBdO`b zEnZ!3^eWDymlLll?TiYuRc1ZrB;7U^q5kR@_Z59GO}+8ixpnkF?=BG?uO03Vg^8Ix zqw8wa)*##?3u<|AeSPqVwYO_qR=b~o!{E>oxAA|%Z%EHu(}0K2`-=Rg^vBxsPN&&+ zXNSzKX3q*R=U%|V(5a#fh56K=?No4)OfLgtQ{b&Y0_1GVk2y)NlIub>p7*@GcllbM z(96;Wjsj)#H>l6bOs|gl@LE=Gy-I8-?p8STjXD_i@mltpz!}oCK8j)PBb;p|!xxG^ z>!35aaLesMx;rcMjbbbF20EPLlit={)Y&@Sb5r$s>Si{bxXeMl*c;~XZqE#3MtN$o z5!l?*6*8DLo$98k>K_RvCW(_pBNDOKo!>8%|Nd|x-cbN4<D9O*{z<+<?_k$w6|U3H z9@GEIeh=rm0Bm2rJn@CMH!GZxf_6nB<hfYYL5;dtA>+Z#^=Gd~|JA5<p=J=ji8T}4 z(i0lXFk1=dAQ(WK*!2~%v47zB9Vv8$-BuWwV##kCuj#iuB1|TnOrDQZV5f|e1m&Jy zLBf(*Vf3R?)1Uj9;52;y2SNxpA61H<R$@QngV`995}-izM(B}JPlsz?kCOsSsz|AM z+150&>kCrG0XATNYW%+rnCw)b!xyhN1GGrTjxj8pa@+B)D8_>wjqtGlO+cd-QVV2s zFGjfs%$suK2(gS1#Y)d@2y<$s8=qF)36TTV!LTrKWoTQaMd<h7EAT?Gj(-XMZN#HM zmVhh)eLYwCmI=1S#N~58Fur~=ksi7o>{(T6qaNqqIws|hDg_gJ8C(P>TH)n|Q^2|k zZ#}hX=&GE)n4Je!CtRkX+M6`qqLdZUW;iNe_ua@PfN%qC$zfXkuwi|m;~}zht<)7k z4<f|z3&USi$W#Ng$dp~nzzI%f3+#QDYhVM~plilSP|mCi5I6#(Dp`IF-isM~=}(5p zFfwqEtUQxq!KKSi|1S$Ug)hr$E!v1f{K;nU8Njk#IfMs*-8poZ?A68UHYwI%yP>YY z!ov=XBuz;9a_oH))-$O+aP)zNI*8-Actd~EI0FxzMVRe%YDkj2A+F5CnL!HCTqwDA z#jZFZ1{ofiF^u?`DON{443Mh3TmQGUF9#E$*X&r29g}qBFHoRB&{LJRG+TMH&G;rU z2B=Vo#D*L%>se4<EHW=Ri$eq54m<Z}SgcaV*b6dwFvNN{jh7T(pE)1Uv~goRzKWIz zvh*bBK;pY>m%|l_DJ%O*mQT^MOsT}Y02>XcuG<1#9&PyKIlM~XZ<dKy%!lpB7r2+~ zoDuj`Ax)HYIKZIb3H4-{hVsG0%%1U`-s?FbbJP)4yS}U%@LA$qT702@<+j#LSa<iO zspDw+QCME|;;#uBUn!fVe#h0RI55@e3NPmVwAKctvS3;oR}rk0_2|OvmIg6SS9g!| zr+UB&9=yY$KJ9t6!ge7KUXJVsryL>b(h@L_UkO1OaS$<yiXnElV)S*s@9IchK10QE z>rM;)W8}#0iw`*wOl6S7s5>#7zU~D%rf<91OKQT2HE6`hgzf-0R`~G9cYV=<%Xa<u ztFWp%V9QroNuTa{s(tx4j4XsQ1hIi_QswyQ1{Eg_pWqb1)uH*n&82NE7Cd*l+K6_f zNY&+fV{cKZl!+meHt4HXil%YgeWw-w#%q{S0n9c|SttFWnyL}JL*r=LGdmiYZZ+_u zu*NPk{s|6Wls(>+#R3@N8+{wsw6q1B03(Z}#NT3YMIgTs+aR>)G&#X9hk%E#j(T!? zyn>;xus_L%zw+fn%KkX8mx{nXkzI^l0h|JD3DCa=J04)+B_IE;kHvT=gpg6@r-kqZ z?)5~fr-V8ifXA>y=jT^XsX~2}Aer>Kg65j{E=hr$c#*dEtNVNg9wkUH$&g>HAG!Lm z54W3+_51{;SNtx*M3B$J<Zn=l9uSg^?ZaT_$qD<ZFldR^WsnT{Xm7N%V6?CmJnD!! z+EAVTqs4a%f1@%uIP(?<6zUy=9qPzR^lxy@K+bvheuJ&CV<V8D5LA$ptynU?c53G_ zd5egg8ZF4&Bv856iX?<5k9}$^P4hD8nKLBmATT4C5;mz}O!j)nY)djo6K*lP0PqBG z7>TAYRMs%s1}0TU;a$Q7A35caK$JS^OZW6=*ePm<PZ=)G7_5u0Cu_n5=@o(67pqtn zpmLZ6>1Lum;=_#)VmdLsDlNuRY3VRiN8ut#LxTO!<biQ2kTlgQ3jBx59s|OOs{*Kk zxzAF6ZM8SDV{g4<GN*S%tF3F)e>Hv*UxZLYSCmbRovSLIJ&M5^g8ld#pbx-^lHXF- zc`f)IL4%rWVmCTAxq`hSw!%2aThz~yU_&fw1YaCXXuUQ074L(S4j9TqTu~#u!rZ1W zza8(6ewU}f2kwRCghaQfP{E*0agu}*RO#OHM&0>u|Jd!Crasvl#lh1^n_YX6CSCU% zl@fdoqiK@4LmQC`0QsG1jIvxcbbPgV@No(6;N)yXSel;{@8)<r-61D5u)SY^5!QWD zAjOcT9eLOnGy8+PqE@%01ckj=pFcl|JbMemva{*s^ZbfS8;kocYiMA;(S#TSva|v^ zQ%~z`ZGTh?WHChhTevz%&$G}9lX{Ng8N`pp)c}|&NMkWL_ytDq1~;ea<+;)0Vf9!i z?L^KG&W2KPcVOV<md#GwjMuesNK!~ohS67OUL9d_e+o2WoYyLN!byyI({8`7?B?{f zawq%aI#Wh05@grKo@`pY2qQN|$6oC2IbeA*<oDyBmQQPU0$}J-ND9w2yu`#5lFvgC zzgV)1_0IiL{q2QTvU1h1@3UYdzDUL<R6qI<na_|E#AH3Npq%vpJthEx3h40&I<BVu zVRYXX<%b$3Eo>8E`1BU9%J>FV3y9Ez`pKRZFlqpumwvZ3W!~bNrS9opkVIZ}7UJ2Y zMfhH5?P4)tz>wLjdI&N=`^w_?5Mn45nXt6LQv=72=psyF&@Y77gkQ4tE)A2+MF+7< zYA`HGa5h*XAL==T<iHW99R=DhX0n}d)X+bYY0L06vp;a(@eq!(wPes)EIBB^%Ee3( zbKnc4Ht@#84NStsNKBpu{?!eflznQDnc-d&wc^?^_<Yh}Ep>hf^9MjRNvJbGnN0@3 zn55V)Iid1mYO_GxO=08L@x;i?C=kHG^G(>l{sMVuOE<G|++e1OwHm-supNgPpb$T^ zL+YQE;Ea=75cx5|x<d}K@n=h@$xQ5H^qN^(mkpLA5b*jgsZ1Px&q6je8&rZF)M>Hw zT?<oHq`K|YLU0e%azr2k^LhA_!Hib*Aa*H+ClRQ8-eC1wL=M~@{@<YGnBYrvx&-71 zm#tFA?G^?x9Yxl=_3+OErxvEQO@w#yA;JC`84T$TTQSLT!D95Tcg8$wuzfsNpy$;^ zEK=FMdD|D6E1eb$o)C?$(L1icg?|d{IxSZ44V1(Nf)tnvxdukXq8)~&B{BFYKw`6T zDcdBA2MR{2;VG*(O$rwGrygd=i4eW4DI|jG(2l~KnLC~=f3mY@Ba;>fM&blY(N}0; zSL#cQE+5MyQn2z|y@nNIJ9wEV3Jzch6I`@GVu1flZWI$}{xHIKf6*UBSF1|C`FU!N z)JZ1eWbtaU$;oimc%1)TkJgOowTu4=7fkFVCnZNsST0BiZw{Q>&mBMRGY#U~C~{Lr z%T%pt<iYkYfa`U`q$2p6)srR=4k=>vTx*N9R8(j^h$kAXY~IniZ~xdOd(ksKw`TF2 zwSx=0s)ZD?13xDI5!&i-wK@QY)4&+4D|(V8?Vct8%SU?~<{o&B{<1OcIFaY`7wAt$ z2M^}EZxz_}<BEf2<=cKx+k7rguj*AV>4`N`H$u=M|KQ8LpP6bf`?;;x{R!)M^YEJm zM3Q#c!HUbhKMLF5QK20i@ULutjAvHNs4V(@_=Dp9bf<YcAPKGgSW^SpR;#^)(TLJt z)eLk}y>h?r`<oKu3HR8Q@*3+LG%N^1s8`eNr_eIH{;7UVZYz<rWEwXX^pQ7!JDy>$ zWByH9|8w*t_^Q|N5OJc({9QL(aIS}u4R|P+n76-Zk`}KRBPnN+fD`<gaMA?fXOfn? zgCY^>!gbCh7jzOqdabwAPg#f6wRoaS^zrKu37%B?U>uJdAp-jZYY9hwUkeW=$i*2| zRvS_JS`?vLN~8y?@o7Ozkeb3-Qc)JAj_E`xdX%Fopm-=*V6M}wD?)Byu$0ZHPs@eA zg18U^!@GxpM=79mrLR5@RtC461h_QBst6|G|DygWL<E3Fm}E&93V_!m5G3JsqE#Ab zf%&}nxjU8`h{%nz$jz}1f-?5fFkuiDTkx!he&2r4;1mo>(hCBEJhM^KclRHtLpo@+ zZW8aI1E5*A3$kN)`Cyv}Fc{ehWq*7FKb$#$4x=w+E$k4%lSaRP=FgZR==l>^a8830 zwI)GVVV6YV*AlogSU(9eoK|9(yq~hhMF5Wg;#`PaYY91bN$;y8)UQU?`K?b+R*%S^ zEb;bEeUO#SvUry$^LLErlFIq@yopu}y=QcS6;VEZvd?cWu^`Yo<X@>^T*^iIBxNiN z79&bEn&rX{MvmpT--vUV>TpzXVCv2rZbe%be%#Ftr=~nqAi!GuRB-Bkc+%yC**zw` z@XJfq$FPanG;b-Mb)qCIzAX^y6}iYL{I>C}Nrl7o>e@2FK6MDQ&Uxz1<?o+K^MP+m z3i%TCL5c1?a#w{ecFu}ez^_PQTq%vF{qP9d(=S1d!_wJ<h2{=FC-o;RW{M3OfzXO9 zeXH2XoCjG@aIGK19y3^$%5^o`I^ObNBy(zsTiX6f9puC(HA4I?4gp)hwo%J`p+AJn z>QIlBW(yf<-D-hCt7!?spG8~`QGawmy|K&};$m>Yqas(q3o8c}ik1NHc0dB0=J@8u za01vpnf3S9!1y7N1`kB5i5=^mht|M`vpyFUH7}O(eQa3J;U%EW-t8yv6ep3!ENGDb zKwu#@+`vc;Sh0ro^&Ez!G>~+1XnhaLB30aS<&6iHBM1Dj2|R%Gj7tEt*CL#+9Ku7; z+dl%n!t$75G8;Dl$Cz$<x_F3Z55IYJMX=s_uo{*}xBi2v;pkZ&mC2vLq7h>y!T!|( z>@yPc4?ALC;W@iNmr`m#!33*;JLKlnOZAuoZLqmt$sf$4WuT@)<k(K?KL{R8k|K3g z7F;-I5x-1ODyiVE3G87A0}u<@C%#PtSv1@iwnGLDKT+)Vpp~#<2TFpdXXf~xSlmjv z<=H9=D0Ez7u`%6n#JU~IZMzBoQ5bs%IoeV*oeeHwWw$rMm!Hw?tOGstenvwE9>4Eu z#RffFI8Cwae>=#cVE}wpjcsJwUSn80{7|Uad#@(s1RX?V<xcr*y-SkV<;wj0Z#ZSX zWUoCcjrdrgVIBegeb;2sPbIHM9RfQWON0#s>QzgWZunO|ojTGl9__GPAJMGy@xtjm zCT*Q`PAG2a;6MR)L|xA$didWF5s6^+gCGb{#COf9N}GVE|A=Wj+=O9f%Ae?_)0<!H zQFUtPWFs_fO>+P#<kx>){y*Frm7$PiZ)!M{(R{%n3d5>MGdCx$!>5}nRQlkp+vm|F zudoV;%7R_$@#<VmRX{)RP_CrAq;wa3{&(*WgS<C!Zl2x+YFSUb@?@t-xUuT1)sPg1 z7b2YpKLM*|;Ku;zW#bvDYw=a5M<ntgltGTsKkH>Y_5e`hV9jFw9$>HMsmN^)+V`st zNB2n-{&4)xS7(Zvxz~D@gzfLE9Te8`TAfggyNMzg3(MY7S2oh(|6<JnhmgPu^4wv^ z{*`II7gZlU5;z!xLvW<?Y0<ay5th^amrUXEsinzgh~{-sTXi$N&-*i$gqgmr(s;UT z_&y1@Y4%rS!VS!mFd%_7hO(q^u=+mtcVmC5@;`in*pA=1%#OtbyU~NS+B0|HkwMHg zQ7<YLMHUNjZ;t_M96GP}Dgpw4s`}jJlYyBBo-RJj3gIMBi(`-Cm0xmSv(1u-(JRcJ zln*m%>UkWTLak49&SIxwoVE}JIa!_}U8D)^t@v}8PbO}&iNn}jkb?lTpnS)iHh-96 zlG*NcSL^e(3Ir@Pj^agV;v12S3#M&Q^>G(-ZCD^m1Df&S`GPEXvp9F*Hxb8o7$S!| zf>H}7@>xS9evuf&SDof%uJj24VqPw==fU}FvS~RAE;fvBiKUV`Y-2f4WJ(j&f{4L> z9vM>~=m^$S3wl204H8Qf=7V=24JS<K2rnHklveuzz<@yjks)T2V6!KPER}@lghn2C zrsQztAl4PaYfb8hgq4lM5|wW=JZRqhgXdGw%2i!*jiKF>0MoY-N;M-t(v<?l<~QUp z#b{`tk=3N8@|#>7T!K~9k0qXzfXU@`l&yIT4k+xflRD4ssS||44v&J)7<_+JWiH^e zKp{ltbX8w~e?8c*jv{KZHZ->bO@{$}PGE$wvK<%+_!#-{naYQX1x9-B7kLpzDC5n; zaU+Ilei$8wYfd6VI0E5gh&B>@`;owtsgB(IJVtD$5Guv=rL09GIe-e<%m-1+!U^*) zljOuKy=BETpyT!U5X3!<4<M;kfJz*BAFOvhP3A$U0+8nmuB-qDOW6g)jDXl~)+ZDo z9P@+<d@mbZWMnrM4xo>5@iw1GF~JpGCd9Y2AU*Z}9>yK{B(QYqbYfSo#8I*ebbIrL z+{yHdAL*gWk=GgUuBc<T8e;V00|aggb|?m%QInm}ze`_%F=jwCu_VWZDL{pw#R#hH z%ZRF(%wYi=tn{8_^rT-&08lrRM=xXdrY~DC^iPmc!UWC+xlQ}7<6^ZL3x<4EA<S5x z3>m;|(=rpft-}szqnavlVMH);2#HNF&OpIl*dc&#5s1TgmCg+8uxaVbAPdBzUPOCX zdK4srI}E?hg(e6{=K2zHzTrtiIvJ$KC7sV<zzO*6OfiNNB<iPFZ6K>RJ0nsPTu|~O zJtn5_B)}NZ$le!;2B<y~0}OEJ!Xt<n+V-xQeV3%HOU_G-U?GJ+NLatNhN&pYCUp(v z(FSPdOV*u7nFlK5#E^K%z=LJzk0(lDYOi-ebCwCMZKA%&v31*X)GIb|&3aq!6Y}`U z<|7}AopA_OW@MlEtN2hxtnYG5^tOtbvZ^jAcr`oImkdw0>IzV3;zN*KgK=bUuw)je zVw6zZ7{%!TJQ?@9<(;x>FYcff$Ik~MJKG83!@>^v7pIO>1*<hQMRRfuQ=epSLf^AR zV&!YOccfs&DEHeiub)EY_VUl;Ljd&=1$BG7m)o-zn5!)MtJwA81rOheIEBFa;?dNc zyb%`WkcDAVRCxZ>vAH7jWq01)*>#b9|8x~-370s;emO^c>_7VhYg~j5X<(F-fliJ% zqrz8A?qa(qZ`Ru6SVO0h-c!4XI^A(7>G7pA0U|B%4uCx>&F_`o;U$HC*dk-~UsY1; z0p(rj?68Cp?$jbrcCXQ8uOnn`v%8clZehbWzpgb6xVgX%x@2OU_1dCoyU)V9w}0Nq z^z<6>IGYuqEMJ7}&B`3?pZg(^qmx_mANC%?UcwsNj<wG`GAJHoo8owI5vRwO)<E_@ z0t5LIp{dX3(sYZ(6Bt}z+5m?5*kEf|70Jxq<rtx(@c`rYklT#O#g27RgAJ8*<?S!Z zq%*f@*!=@PiaCL2iazM1ugD9HkYSz-d-1B}PF2?2i>ff<^`Lw+n_3vE;n4XpoIs(; zg5w3oW{AbNUwG#BR{(->gcA=>Kx7|x?*prcK{l#uK+0GC=_}&YbX#mdTZCcE5`YMm zAG|y`2{1^t>qEUx*f>s2%kW<t&Ea~J$dG{x?W&tbhLeU^X*}WGLr`XE&EV0xegRJj z=^&PsPt1VG8KzgS$*|BXS_C`sHRHd#cVC0Nvv!bxq`}^cBWQz;E`?!ZSMvkDImyZq zsmgAuFAgY663$~x3yuSrmth*5I!Z1Op^?!!F}KO!>W;1o0V~tMeu1tMgKt6QLzso) z1QG&x;FM=JLNdb<0Auu?<ths!*DdP5Gr{jggeJkiB4(@d%{i20Lrb&ppwO2w<0Inr z6IAgK&w>($SW$r9CuubPg6F38mu?!VXmb)t8I?(}(ZItS)phUo@d;u9HYr~3DvY%E zaMViuo3hZg2D->YplxD2B{-|NEX#KmnZ%Am(x&63_6GflT(mO|2`pA=kOh&G0Ol)5 zkccf0BGoM~>5|U2+=~I-D1vyJui9UJQ_Tt&DGm=Tx=AB~qZXu_tiv%(;;y(4Q_+ja zO=2o*2noRGDv~D@w35fNwBOyVg&3Zqw;VPE<#&g8`)3ZT!CDj}X_~cnP;7{Gou1ko zf{i@LLT!&VVSpG!mWSh{paAgFguQy{ie$DuD8tcU+1l?0HMsfxVJkdfGNiDMme~~Y z5e;N8Pho@wW>yYiiCcMcryOZu$)(sXMJX#hgm7kgBcZXYbx8YJbVdr$t~H>Jz~E#e zb_E21<m=F89>nR5d(w2&UP{YgL4aYddf7bCw5%l-O<15_n2ec#ejRXr>t&#Xl6N6E zypQy$dGB)Bv%zYFN`r#acl}C3oNeSdp}a!>62-~-jXJ*TWj+ZMM=hk(Osmx_J=P(V z69~QnN9`qnc#8tWU^q!D$~;JX$G_>VZHCSB@@L@9FwxpjxuX<6G_-ofG^Qv9p+;LA zwMX7j(DG}2FiS!Tvx&yDC*IOn7g2=zjJ6QeqbPubN+<#}5JvVwzP0VC-Xf8}BQ`1q z?$+Q|+Vk%9zwzCI*^mZLz*gp9Fk`)icW>r`A@8ZJCUc;1KpF?`2L~w&_&d?9P=%?p zvFa!%n*rO!h8xG97h~8Q$$7xoYz~ZuG&-eHX!{!o&}6WIyKSVv0z-otCP`T<IPHNQ zvV-nbA^OQKfZ@R)z)-XMRI4xpWgh)N?_Pk<s-7IsJ=D?j2~VBs>|=jlX=JUsLJuG- z4~D2AdJ!HqdZ)iuZ7pveWR2_NM-VV>jkxdqwaR-EyGwvG^~}ii<knZv+KQR)!=}fI zZbfW>hLO3{`dzK6nY2G@+PI2uD*15jh%FK7SZm47z6l9<N(*GExRYI;zV)TM_Hh^N z;Bb$`l2Fe=ur}#+EyeAbKom?$IdJ~MXp)Nji~kX=z_>Y<w#!GmEMjmJfV)-dYEsf; zhJ92DX1CM9Vck3E%=!bM=FA&aZ%$5u#UMKS!*|Yxv<beQVpA6-p@}OdVbBa6D0TtA zqanVA=1)lZvw@DMPm(csT^&yIk%}{ToX8lAG%$2P+Y;UC{@|GVz=EzSy{yqN#dzoW z8rMZ$GV;LjJK$CH=lMfExRfyq)*}`;a)SZZisUVA7ckz5h)^hI0Fp2d@Xt(qw38l% zT0z#-nLHXVQ#nAvhDMjBt{9z#5q!kqCHNBM1z2wlrl2{>0+>C}!qP{Yo&GO4rxLSe ztWuCb8hD6Hm~t7*B^+V;5WXTI@yL>sIObiDTp^BEA-Tr|%>9VY`N;2fn&*(Ha9}g+ z6d^%^L|L?b?z9Kw*QLp%UGBp}xBHtCMS5g#{J{$$8XsU^Y`K^d#9dA?AIu`?8Xz)^ zGsPH%X6*89)q&QeC`j{8If4+{oB$M{X(P^yE}{s)Y+H;p@m?HGMMvHQheR?>3b+z@ zFA`+K$$Au2#TNEwkiA6ikg7nM0fTQnZU9H1AW~N#NUnz~{O@3};o5TmuA=hJ0d~CY zDRI~kV$>z6`z8mLYm%vn=CCb9Si;;2sR1F@Yy}*SuS523BRC_-g4ccegZ+4tVsHcT zx#`O>X2v9DXe)pNoUR5u3(Y7Iy-b^47OyPBP>Qs#WF*R9AR3l`!kW)#ci8I7o;xi< zTUKLhu~$CRK1$v;D01b3%#7p(Mu@dq1V96%tIquprVv+!^kpE=mBhh?b7Xh=eMEm4 zlqW3orC%Y=W(GZQmG;D-RIg>FNZ64UTE-Ak&-k4sCvaAqHsru!1bAE&kitU(p<?}q z&kb_%#W|pF8^A>t=^-$6_4^nv4^d&rp>z|3LBzWgsA=G9n*i+x4h<V_L}uRCt2KDS zLokEIU)Zk#L9qmXfJ2>UpC4Hw)6K|=L^~W5bXZwi06%X_!+XOdPxR-;n3#;7v1blG zBA?)CbMQy>GJZX(JTtV-`?B$B2C@P43>o+ynh^nL@2VlG2M00oj1KH6l;(F~JNkZ> z1}+mgj)U5W9*}^L8phqVKM(!|(u3AZ(27OT8icdeYC^{g-$P1L=s*BCBI#dm77J`_ z2W35)v|p#I0co_r#bUell%Y6vhi^6?(h@k6&~O;2y}^Ha2J11km#YZ_GX;FJEJ4&a zFut%GMn!dK`<CGu5h-T34^Ou*uf^5prX0j$)a4JRA5akOra}6B(xX5nTyJ6U5{g|Q zKPig!>(2L}JwvU*y$&D!2`@1tiD7n2{k`Ks{bZ)nJo}4vN*|o^@10tXHGe?^a>ZoI z%GiB*ORJ&2#Z7Y=Azt&(dtx_FUYRvDcc>Js?2m_vOuq-m<MCkU*Lbn^_ZdemHAAne z*727QTRfhGsX6$-ioi0_pqP%$jFHJDMIR`yhq>x?J~tR=40f=#l5-T+OaO@z$7BW5 zB4A**K6OCMj3EkE!uX$0bXtwRlnF}z7O-OkY{tCc$b)&iVp@ndf{_~njp9O$7EoO9 z>1KgG=M&|iR>*PB2vYAAeo?%jNPrqMDUqJ$jUF~Yy^1&~33i1StdWW;6&d!>qgic) zxd{*`SZm0EJ3^_=Ex<ZKl)^j0m=!{{L-q)?jr98EQZg|H@npJLE5b9FOgziNtHd%` z3adDb%_N{iS|YYZ7?>Clo&<Q<$U<5M1?3=csJp65l&~~k9q(kO>W4fyrSKv@(uWm_ zn51`Djo^q8k%843&OhxZ8N|t?O9`{imQ0Yr;roHApmWa%@(t=FAU>QRIM2zSAmt#0 zKXUeS%aI2XpBcHIO}wb8UJ$9#%}LZ(wchQHfh{Ylf%K)9t~TT%gac3uT0%ocl_G(* z$^v2*)%A3B%Vt^}=^Q|g3)i&>ueGSvKhkC^HsFTQ`vQQ`1YHVD6foxyZd{VKfSSd1 z7l+3Htx4ZY8$sACy81N_RqjnFwIzRM-_1nZ89`XU!6(lJf$4%Rh-X>=j9&~ThkV`% zmEHw`1%+qVjW+w@KQ`L?r98kT!#5YMb-1;h1WX+#M8dLvv~3uxi1bcT2UZIP9!mY3 z;oOCc$iZl3A5wUrG;jvSn&zOoN{af17K}x+ha~bWD^Hr#AXju4|Ao=v)ItnQ8q=<* z1C=!lgUzK8%kt8SzzTxj&L#k}eQxE6rFac-bIVY?@&s~DhZz7vdK%WGbjgQtFw%z# zD!?9_pbwwoMLtT~qmLX?0$EQxGNjSv5Wz$~Vd+oO>&OJ{-gKPHKA@+*)Wd1HeMn-k zJ<1+zFJ7!q!Wu^Sdffi-9R^OhW%uiJb6XA8pb`beiIX7Pg?WeMj>CkgP;WcyqJIiM zK7<IuXF{$AFE<>?!TPELi+xb5qu-+rb0!S%`t+X|Jk;BGo_c6lu3XtC$jZbRt9{?? zTQDq<(rdwgB2^m)hanbG+M*nFID3bs1uY#tLw8$EN2`AWV+*DM0)nwPCkPRSVHTsC zZbE%}nB@$`ZVnzN>CvFsM~eHbyM0j9f$;-#%~h*t0%0W@Njknv?X@jU4w!$5)cNpX z*f(X9OXb+aH915PR2xY+c_yn@+uAxYF$axIc!u=C2+_z5cI33X7(flw4?&0=_>gTI zCagzGSpN;&9&w_YMJ<CL1Cq{xHn6`#RvB`67;c1(;`A|E#P^<zQ3+>;DSI-M^9j2T ztB@C~nI5u=lpBg5*M#+4ZTzn>#gQ$5J0#LybjD(k>r)m3YNZg7HDV&xZK(&_6h0L} zjeS{pOKT86al)Lny!RVsSIs9Z^uIjBgQw0Dou^YcY#`}K&HMM-8rnJ$rX6DYeB$=1 z@&lmOyZesW^~*gs;zx~p`|%KFd?Wm^NJyZMGp=0VhU@)WAVwDpjk&nCnywG#8UNey zg`|%c3N~QfV=WN!877tc7S2u&9+_&m>A|KYU&MOEP{RqPw_E7JcN>3rm;Zm-`p6<k zSn_PpTe0q^Nf;**d?EzUVuPSaL{5J^ei(GXOB^LOkYR~Yq4mNb74hg20z{%#K!<O% ztjtf<mLG^H196`KL#^f~B54ASNtRN9P)F=*5Xit`w16uSnP~yAC!fll7b4iKgm#ai z%>6HR86zscMpe+H_9HBf;CL{Qy;g*<l`Ga+iA#W@6>%<71I9#>mQ3+5Hv~rRgu#Y^ z398#L1cPZdT2}@_WGR1IY!zU>bq}oO{4juBNFpiL3DSVsulVL93I@TIAX4ovarGum z9`~()`BVky-UMNh;2x0Ke%yX^Db5%AHAIVF;ERDcBj6-%MX`((=wM`rp<E4_D8U^Y z@pOik{*OC&#~NZuf7rYvoJn7q2Okv(3E_KL3jA9K&y<5_hOMHHZ5DNAZ5!;j8KyYn z(ZuQ2ho~%Fg|1c%u(+2f_K=D%4B%Mqy{Gb}uoN4}k|sg7XrPV66kwFF$H%PEDR``` zQ%&%@aZRvXBiSJ;F;E0p@P^QK;}cYg0s<Zel`jXwBX~<yGRV>sE&=32M(of}ty6!3 zc18;<oS^V%WaAUsiBMIs2q#npf8ye@{CjDz)-13Dv|9C$8deZ69ak}K&m&zrJaup{ zc5}_LNW;>N3D*d6h@?VljA>3j{^X^g?|e;lY1K!d(EzI^#7}p?3F^gEk>g}O4m@o) z)cMPw!`Y@J)0e1~$<6};3_lTEC2lH0g1%UUC)kKI$bi66cWhRyUmioR!z=whn;f%N z*G7mm6ZY)H^X;OBSte4^M0hhU#wWlVvqAGY;90OS*9bLj=lwBig&>w*7rx{R(!EZx z5ggtsh)1wPG!1B4f;N|2N(z&e{keF5%VUwJO^e<;qnIa2)JoE#;1FskCurjaf)s;6 zL#pkq9tgfTZn|9(K77jr*9Nw>1EA9%{sbX`K)s-3dN@|%<oK|Uq=(S)Am_ytHkBAY z!iF=*fDbQINVmcfjt%%JklShDixj`TO_PHmlQMc8;1xhg*%HG9*(xf!Ft~MjolgR? zoD@lu!*fs|p{=m@V4Luz{#Ks<z(3@Q%2pw8yE9WDpvK$=4M0f2+E_H(0Z7Lt!J0)^ zKEp|Pv?)biJ5r!l64!<(V8k}dN{y?M;hJ2a0d2@(p*a9iXq_Q9DrNUN^hHO81(+ZQ zj@zABnrhVzOuQ14nMGzGq{JF}rY>JE`_l2ts2d6U@tapR9JGNpbQCu@gJXX-=#LpB zS{KmOMR7Ltk}ZHT5;a~TWqn<^xzg+Cayz8_jNXh$Dh>AdEp5mBlI?rR72`cur8ogZ zF;R<aT}%a9Ex!K|G^8t^xcT=^nvXpIw&t1m`()wsr!Aa|579Z%v(o<k#|TgOFcsAk z`3WLG@Q~Z)pSu&^9%GI7ix+=_2-}D@`nZLJU#f~2xOh7uuBLYg+g4F>qh&Aj3e?lL zx(Blr=E}R@%<Qdvn$M!o!EN*b@Q>h`!EYmUzpkW1Ag9mgDyAgH5(`Y<gnr)-{I7@4 zFae`!*3^=4@JK8JB3hE3a=9j!aN7}Gxr@u{wFT-dmJ<tFXV>f3=9{sx`mp>_M5&{B zuuA2fqG#I324x6=VGjLpq?LnAw0;=vSjUuNpyk{<=-1p!^VOql7a&gQnL?TkB%lls zDHQK0;Bfd_si7q%g|{urNG3zl0@7q<CVxI&B~g08HW;RPMfG{$Gv>n;QDT5)juic& z1Zy?XZRt)dA!i7GAp&;9o9H32EnlUyQv+&?Qag+AG~Dnn+LX1T0UV<uIAhD_Nq~ro z)PNX`7lZsvbpX&5iMkY4uXy;Ti{Ko3WA(g9DqQ65rE!%d0GN<d!1<HHz?5F2(2-vc zk{J{f8tI`0w6p->1T(VKs3sYQ0(c`N`3CnG`|r$<0WF>jCn(hEnrPWdhi&k$`MC84 zRNp*@S#+3&Q1s8WWC<Jy1OZzXyzy+N>Y=iZN~Ftk7@#fEMa#v@5<m*;5b8yQ_u(Og zVOUHlG8+&`68{-+KssgvO%ST3ymy8elNdD;U@#4|>jzQanC&Gm7OpIOW$poK(0VhW zHVAC*!)7R)U?4s&BnieMSXP2`ESfp(IG~tWgQO1g_;NTxy>(S7dTtWLI*g&5I7-Ub zfH6Gb4o<@1Pdt9W&a3%cM)8*5a3hUEH$9eC(8e9M5EKB`Q!m~D%;0Wce1FCjO{N|x z9Wt)G(c!~ULC-7_Ja-@iu}j~w7JElITfvTyMtGUs99z$jl^HU4SN@ImT}I?8EYy&L z#Fv3exU3=nwB6)&zJM4%e2z<jNy5&<@Dc__XsKk`E-S`w<Qd>%*!F7Fr-#II;H#6i zoc(GNY;bmixR3xC7Gu{LVC_)MV#5NOtxwX+Fw?orcWslyvuoHI3LSWf(t=hRL8!o1 zt#ZTXS&f;+16vjk32-9J5BsCJN3=2~cCGL;!-91BgcS_>PK1wuOya?@0Rl*{9$vpa zxOo|{r*Lx((8Q?->;qgA0Qh;@wS9oJRE5X|P)kPv38Ri01WCxnyMD1TmdORUYJZbP zA`&V6?k>8RQp;buetAX{#P&SkE9MIZ#Wt6RXIR=MQo~4rvmqi{qtf?NgC#R8TOD8H zbzcaQ7ly&vMbv)=@o^9slgQh%%@V&|?`XSeJ1}Wmb=%(zlmi;J|53|rg()Lu<$SM) zd73IOv&7g{2A7Pifb5eR187x#{!+Nym+=xKlVW2nim4c5Ij_4oTi`wX%vX*+o;n1U zbP-OVeyqUYXPswzxm|z3A{Gm>FnAfiEad(Hy&~AqV&8!h^p$LU_Glmfw<%N}<UQk9 zDk5o-PzG`2#FH&Y6|rNJRh-_-D@k{U3tr}KdL1ejBNbmC?fgL@?qwh=@y97hgh->o z@&+TBPBME`dikV3^8YNI30#!r+QzZ)s9A?xS}X)ljNytW^rX<p=t&y}wGq@%#HiHB ztQ5p_6nP6vvxSiXB{Ufm6cGd0LNtl=G_vF*uDGGH$qvIh%*^Zef2QyE{myqh3N!C= zKlgIo*L~fgBibuE*Q$C+@WmQimKJHw`X{{v)hnyg=ny&Oy17h)Msd+Yq3zHgraf)! zjuBJ@i;$aCty}O8-3Edn(`<4}Da&u8V6CzMHtEXeLQhvXkXPp;wHi!`dj~O?%Towk zo@azqLVy~5Jf<~^^~=_d5L<8&e*ZjJ<i234`A6|wd_QeRYb017Whnz__F|Qe+!sXW zvMf_FHFy8zx;oC{=b@h{%VKg67qxeQ7cEc???@vE$p@G*;dmg9h2h(g!nZ!`eDN<b zW)KF|=I$82rzA)tSF_F@kHi=fwV0=n684b52?KUc0SXl<1J8Yx$S4`ImzzI(7D&7f z_aI%@kjD9bHdqoY(1*~(8Zzjp@9i^2yf8TDVoTS-N+U&C>J_?2`7Yjq|MEr$5^(%P z-5wXl-3Xj=GxUW(Q9rDsH#^l={I+GjMIgH+{(u<|ALF#RN6%vnj1e``jo4@%J)GO` zvrl9O{@y3mvuOHsL4g%>E<kNGxppU61qpPF1`5HBc`(BYKyTx}QfyHE$${W|5#NPY zRZK4A1c`StV?s@$uvDQ&Z{H?LUTosTUU8w8kweu0FulbdRApl9m%cTi-h8KCmu`69 z?P|5y&5$6pv7iZ~{XiQX9^Ud<n&BGzq#@Dx*<cX??nccdlN{M+bvo}zJ_0ncyw5vW z!RuIx|EsKC7U5ywmq`3p2L#%S*}*VCK`zLs0N4-$$a9~4)`*_$Ko)lsNuPKs8JH&6 zxzl-(z?g&GA@w4)b!i4cR5y)3dMu&L6*OYH_H=fz;&t8$fD&r{&sO}{{hHvJLx&F4 z%milJ=TC52G;4UDs5&kun?6Z$-`|6vbFmAJ_rbymx{N_y327aDe}~`pHK%srC;>nB zJy*h`uG>SvohO7^s1`oUD;lFp%OIo6{_=NVRDk1SnS$*XGS>_au+JYpaWJ|W!9{Av znteeouu#j?YE;cMNFJ|shyDo5ZQB?vTxs|=hfclfW%ycvjL#0-iuAKdpx<M{rbh*U zn=gZMew?*Fd-H^Dp#H8PIy$uk=8SoQqmazfX|h9wXa*tCTqh+Y$v2Vt_)%)uub@YJ z=+xw=I(orReME0jl(Ca94}6jbF>~mu{qGzJwh!g0B#zp!+)X>7gobD8@S(*niCphI zT5!|gl_3sUY!tb|!(u%=XHniX?VkuxE8W%7K=FoA3P&s9vnQ~YP|eJ-pDUy|CyBf4 z(mO*$)FNkV7-jfE>-&w%$y+^7Xnn3RI!Zdy@D0B(@>AK>QGJ*ZS(>*c{)whLuZ;pZ zO7WCu<g_f<ERR}``h+NsncHDnH=-BQU2-;CA+>&4SZ%^lq4xK1vNFAU4O5qNV^5o^ zuQvTt+mVITV{d+XtvLR_q!-D16gW`c=-E*t?s+*Jz8`YJIDJh)%bZ0WTUHwO|6|6+ z`Y8;uh=Nl11Yp#^T=gNi#zSo_>8wXs@Y@l}T|aU`;#LB+X5cfG@fwAYCh<e<96ug} z#uub~gTDtwvGiMqQ~?KsrpvU!WCvV5%Ni;HW@n4q>Y5HQEEIdSHk1I}dTT?Fd=aqx zkiXqGjZe7meq#cpQkWbH05U{_9ZN~E<ebA=v3jt+-VM#|0nT0#PGIdzd|dys?{+8# z!S_uz%<a1&!k4P-Kq4R>fH<r8Xm;BKisZO69{CEPZDi%gC|s*A{T;P-;@yP80l~%v zUYJihYC5D<f?x~k+RdE82~k%CS6?~dV)YVp6?9T6oT|x-m@_)jXK@KaIir3_2r_6y z(zawwe=p&w$P4C6EDaZQN9rGd4VK;x6dW2SB>yuV%Dq|Lf6dvvoCRDwaL(jsN8iRn zER?IMysk}secD23&V;PmJ!(aaj_tYd#K`3+zN{!7IIK8^M=r1L)80Wizv^J6K_oi; zsTW?X%%VW0wBiZ)rpIT9_JY17OTmmCt#se?_E8c`T$!>UGx0#KVTKmKOmtsjuz@8A z)Z~Y`jF}+b4uQ`gRphg>5A7!>j1W34T+9kx*$BA@66yaArm_2C#vp5Q-@;L}#qrlS zS=l)^*t3<^77iD~cC5+53ey;I0t8pYpdkeU{WX);nm0tFX27&3_Zk1YVBzk*&Sr1W z^1v<g3gUML)=zmj&VaOgHK_J7W=lN9Scr&aXhVt_jJ>au`G1eQ7Fj0yVH}h8eJzmV zzMD(;1;s`I0au$w_Ia<M&DntwpEP}jVg4%7j+T!TOI$%8C=!53QfC{!;9O1%M`p0E zXW>lF?x@kpz*r(q&lyF|h;_-QuAm#I(L!Gc!CLq3{vw9tLaZ^L7QXQ^mA&D!JfmsW z%)xX2l^o1-9QSZ|5vZWZ&+*%$<o%HkP$UoaMAazf1dreg$p;6f*ykUn@2L;+^uB$t zvO@eEB&(NyCs}W<4;wW~+cVtxSkSYtXs-7gQ*@*_mWeaH&)1}n%O@@mNa-2%*whX| z4LlJ1)*Rd@BN$73zu5l{DG-g5**}gtIxYF5Oy|T~c-?0ph#GHJq(nH!>d6Uc@<g^> zen=N@pHQzCD9+U@F8o*6m@(O(Bl<P-nGr*cU1oaHW$Fd1pJkaVO|rEk0#0kUwxJ1_ z|G+D!<-R>`*+hEG`qI5I7q4Ao>4uNW*1crQQDDVzPm<*W(Hi`cv3G?KXVagQ?n;;Q zLsuMPa&{QHEy@cRd8RW^PF9}oj*B%i>A^1{LASv@ZOL^uOUd~QhVfTIR4Vu3YTY_F zlC$oZCu(=Iq)er=6%n;UJyU{tGxR6t&}e;rkQFFlR5=I<AwSEm7hP_8$YS9QRbJ>@ zFby{_D2K`~<oP0bnUH^COi1J|6j$UMj__oldOd8f5RFoN)??kxO&`6(N|7R*^P(3` zi>^+FnFuj7l3GlB4!yH54RfYU_jwjh8}tCSPl)Iz9iS=0m65+^+B?uZ8IJ6COivw9 zy9@VT>2ykB_MaA=;9<JciO9}0y=>)ccJ2^%`dvpKZvOB=d)AmhuXZB00Jnt64mx9i zutedmhC(#ng+?e*kG`RE7vMHh!xgL;R;4J!5|b2+vPy>D;FY!){GB>w1Mp>0ut|JC z_(oig7|J?M4I057SA2~`yPp;WeVl$QDaKpYiOoL1i2lscr7%aRx;AgLBB_=Z)i%zi zbp=uv&i>rVF;XYY=+o$nmL$Z-YbO7lG)oQK&;cf;be6fU^N%qz86xCFu-PSl4`b{U z`CD^cBFbMEccap~NZjM_k&nFyoR(>g0p^A52JmWTKsfHd>~dD@raR!M{odGd83e`b zpZ(ACgLT}=IyvV%7RTZmi{^=TPGOX@TrUY?m#Df88J>{mhC!-fkSpE57E;dVAd#&p z_U_&a>U8yz`;L))qE)@fn5vl8QoyJjIAElQVD9T#+Psi=vG7A08hGVoMzjm=TseVC zSAGIzubA|%Lt&!&(lkD@FQi2zS|0OvquwGr%O5qo@FDo11jA_HRsoXmZCJ)W7(*5R zm9h_Twed_Pyohx1xe`m&0ku~4hkH9y)$=e-;FgX_2QE`GT$}r^9k2EdhP(e--=RVT z7ii?OBO+N!Wfo*qteA(!vpX53Bb}KsaW_i==*`=ljRA?_bSG^p*~LNX?8~yvTbfb8 zV~g08B&z$b2jn>~?eIP{WkrA39Q4Gnn&24{q<}+5Cl8TR%eZb<vL?U>5~v9-t<|6A zpUa8eB4TM+t8f|$1sW_gG5&gdR0eHs#yeea>r3{Fe9#%G00xXBAJ5Zx^e$JG9;`Z) z7f$R!u8tSRTaa_Us@g}2h7pJ?daAN`d!A+_B0Ovx*DZK2K4^4uPu*u`@CA%UUNSVN z?}nq*mq#6#^Z6**f74(ZLR(0MbNXlx1kdhg`a68h4w6{$6I68r%y8c~$*k%y%#SHL zio6fqxE;lw-YM+*STa5UVO~^~z{}dRXdj{<9lm3vi+5WYLsMdul1z!q+PU_vKB|P% z1zU5g3sr)lyHhF*_ijURw!i&Cq@{j&i|eM#c~I|#6A{xwr>DN>HnA|Oh*rK{z8UJB znc2$|HK4yy6T0MZTuUKk)899Y_KEuL<fGMaUy8ig9ei1PFMES3b+`y-bj9*2IY~R- zjQEwuGWnW*>xiVLGMzYb;!RXpH4uXD2H*6j!Rwev7BHbCW0^`m1^yPT<7`petA)R! z1QV4_!k%CaK-6-V!JIHh7Ip}TL(Y%%-myc!A)#ns?C^cDae)O|#?G>ge$H1<o=!DJ znwqv`0#n2@;?SiI%693glpT}}nt3KxLqBq<@{i{fhCGgY(I{9=kxu7{ML-?<X6d2h z|81i1(llbXfpu`Y*2mwVy*t;H%;8$Fv-fh5#RkDe{Kmn9kD19P3-CnB`WfjZ%m>sT z?&I8PbAX%5h^GtP<TvIF5aR-9d$a-SrzvP2mM{~PaR9myIXn0?H7QAR{(SNg)+kY8 zLx|Ks*MQa52d*Q+4b_*tQ{U)$_*h_N1<oA*!LyDMy>&Q{=&|ma+sB&@gF+x+Imz(V zgp1FKIkAmUvy8$lwPrqYVwlGPQMl%Se+_wWir_N2uSI`6x$icpP&=L(2gb6EgFIJ5 zla!3I8Vq!=t6^_D%BY%}Rr@|0rd3(WzM>yNGm{ObrC^ID`|$+5ecSM%E}HgB_DO^u zk~uUlkW^M25J|`QQ3L6T!IKkhg4+FRdrW^ARp^eYuDvk%uh$q*W6&1f-uQ<DzrX?L zt#!y2Iy;+WDSP@v!_ul|<DnT2{qR2Tl#4<xb-_DFl}Sa2X;CZ3r*)hc-Ikp@{uL!N zx5pQp=*|A}96;8Y1HtaBziR`3{V)B~hr)9&_=5K9yt=gIfsI3ZU!~>nYVffy4rr#o ze)qd%Z+dsBM2$|44fGrx{Yit$22AqUIfY(cREEn@3U(GQNtmjPV3+(v7!ju|{vY$o zQnefUz2o$jU)g`5pKG32YA`Y%W4X9ZrBk=^R2lKJpQuoi6{ZuF7c3m;5eeM_&nH-) z2eE*g!S-jy2R>uZhbJts--A5r_>V~ch8923zs`cIzn6|cP}hb5M?S)4FU06)_K8X= zs&<&~qJtJ^F-}{!nc0sZT6N|-e~oa8dCl~s2h<1G#ZyK?#9>W-cJRE>%HpsAr=CML zY*z4s@Nu&=)n!*A&g?6U4g+~m3*wN^T*T?YFNAPwFz{2U$Yk&Melj$8w(S4bK-a`e zG%S96cmM_4ikV}-j5mVo6_5V%cbaFT6N}VsWv8a|g_!(I-;V;me!q89pVa~@R5QN3 zu1FK2tpVv!M5{-7im47^amkus>slAApLsPf17-0Mg_`!XZ+b$;{&xm=?MnxWJ>r(b zcBk70?MjKkkW@DP)Hj${UWyy0wtWL}o{%etjSQ@8-g7mVy%2u9v{X|~=z^cv8W4Xt zw!kN_me*(sZ~8WR@gHeyT*bk}+<p0j%GPgTw8<Mn^rwB^|3EjPw@9@vEY3Yadr~u> zas}Wy?5?}x&J_kctF2-_RX5ws+i{mnW(Gc#F8|KW|7tS}yf34DwD5OLF}%_S<P}^N zCj{YZOu=H-Q02q4w>B*^L1l}a%gG3TNUw?RH<JnoG^y$`fK473E*#I1NjFinC{zEd zN+H$Zvq=S@u~cT7sX;F?tOxW$mz5qkLheFsFD+c+o6{IL0E#zF8&ouM7T>Y2o{V{1 zB3_oWwMmq(8GS9Xgeue~M$H7;g@b%`ZXZE$rjnhr;~5v|QbF)DqO8f*F*%Q`;`I|i z{qPwGP2mC+G%Q+#FU}9Hg<tGK2Aj5)nv-%*q5<7eCOpvEP+I*=QFC5IzfR(jRU4Zh zqR0q$VC@Lu+UPdZS4){S&8=Jjeymi;2!ghF7vBa_r~vrKjUR~Vql`jHMRbl3eL$!= zQzV0>nWowMX!wX4efabm5|pc#N4b2*0cjCbk0ik@XAVlZJ2=Oq6MyxfQ%D&dr26{n zwSA(WhtOdVlZJG6S(Hjb$1<Pk)4h8OgBxj&lmO)Qb-m#PTe1(9=_}KhLqSA?kLgFC z`E#IMZ1--~1A^}JAC*pwdhwzB1T$Bo4A8A#yi~0Q>l#cj8$X65b5Y1t-}sMIu$ccu z#L*tj5%uGdB};uLh~XW?&MpT9z55QXX*T~6UDU6i@IvrHm2l|%ZRUiN!7zii=gqtO zW9DCTi;>0%t_dFQ5|A$YNBC}ollbZrqa3%zL}_@~Mhp;yDyej@k9TXxC2a**TF>YY z{YE9Q1jAPE=996v-(MYw_YeuEx$$kHl02Xh3IL25w~S8iW=Qz2zNgUsSPQF^$1<A> zaY>;QgGbPe7OxsEv}WdDB*k2Be=PFvIipv!HQJQXaPj3x_U74sHKI&>oJ-Z>GLZcp zL)_0!TFpQgrRJ<)U2=T2o(P|Of-dd$g$ZAy4pPNM9|2a=3?HhV79MerVksFj=sW$t z7y(!qJsa#j#*|6q_8XmOI(C>sxzk+A0<4bW*Yl>n_^|wq;&)eX_<BERs3Kv<@Am~l z2h#}lL;iQ3_b;BzSs&LDcH%_)q+1c4Y<fz0VcxJ3Q;m|B5J2A_=<4Mv&xSEUNkthJ zj~&IV-x9rMtc{eBP@ARLjCweyPUCgJ)zhTSHkM!aY)7`%mTCI20#N1CB#0Q7OZKlG z#W~3}-FLjHwXV)bFRXB+*7J+COa$HCy%st$W8yx~zOU^q9^zR3vHJe-FpZa`(Oak} zP$$kSyf^hj^z?sUkL$?TI4W;ZmtQ`!Euk|XxjfPGc2cROk<!JP;zeC~<kFh+pND9X zj1xl?89OE~F%@470|9m4QC8U663PT@0&J4ry5S3x?kD8Bdn`+2RaZyZhJM8tXVG*g zSrDrQ)(x_IUA3DFR*JT()HAR52dM#d8OntplKYK2?f%pT?e8m8m)1_`eP1m6O&^nC zMBoIa-}QVg>spwwe7yCGG|z<Q$wo8MX4O9ob$ze$uRE7NUJ7qMjdplmLu7c8JlcF$ z%yv4{Z&J>^Cr>6!;#<(Q3o3Y!>t#bxvPi*S)MmEEHD@MYtJN2=WF1ckxvKbX>$e_p z*(&BYrU)MQIQT({&ID+YoRc5nV(R+otr)O9#t~<vji$ke7=-}82dfvXp+5*0*iwo9 z#Qe{f%Bk>Qx*1F4oCvSgkDe@;%>bs$`5iiy{(umXju@hD{AXV6_6wEJaP*F0G&k+X zvmdLlA3q={<#eF*xR#%HxEnOgJrc?IXD)u7El)JZD!`L2u)mI0B7}>_9n0xY7JvQO zv;IN5_BlHY(Ui2Tq<s}k3W2_S553@c&wgmB0@cM5f(3wY-zM@L4%|Ane`Rw)*XYBf z2BQifQer9l8AvRDs)q;4OhxDbp9*B%B}I%GX!$SKwxYAzyCGMl3ALG~v!YcHI&wV4 zANBXK&%BuBWfQnP9oAzpD=)Js11NCa#ms_Wl&M?z|GS|XGBrwu$2yZDazA>M)o!BA zRO0Uv6akk_6)?4p|Aly}&sUWjUe!!{(%}CJH&HK55UQu)i5SaxQrG`!6LtoUR?-ie z&}|SuMQ>n-k`KD<zijnfsF6G{Mpb<R>rLC`C9XGe2|Y?vmQv3oMA4I6=p^C7`}5iX z_A_kb4D(nlv-g<Wgl>WUgoRwLItdT&Qr99?(|+O3LPfXX$WC8GZ0jDmyo=NnE6c8i zzcmKV%r3E$r}*f|!@CI=m%4^Q<oGrhRJp!hIwFdn13FLZKjT00-Ip!B3pW}AZ@J^P zlr%#mXe0YR!x%q*c&qAiBt-^$uksC3J(}_I!T5o_X>ZN9)KC5?OF1zM7Sb2;`)1&j zWa;;@{7=hMXN4<JBzH7F`^r3dSMcJH^{<5i;!oQBkW`^8DAN8?K4Jg^&ccCYv?3$< zMDqgUQm^IDP)YR<I4MRN2H(nMos?t7jty>K$|Lg)fsb5{eR9U!yJEP{2i=b+2}{u} z(b~rvp9Y-o8h@SBkQR|Ra*%yO+qgP~vHX`{SPsVM@7<4I`A@l~wcz~OaD(*T9pdF8 zc87ZoPzI~)zvZ40hdS}n#cfCb2wrkU>L1H`n2I?DKN1a1zrs~RsTUu5gh%n_HQos+ zlQ!;nfAu8wk`CiPVuR^EJSD3p&?ZqxuJ&0~8pUcM24$&CQ>7hhU_QL->yCx;fS#R! z-PWh6VG(txzmxl0#Nazp$!iO#93d`F)%rFEb2#h&R>k%G^-b+(0d&=O8sDXz7tvhH z(^`u?AOHFEN;Dx((m(?<p0x4H)as~9BR8Cvj$b=nYwCBikquksi7*&AS09flu#ft6 zR;eZ6dOuQBBZCX+yQcmws16fK4ul?^ZkzfcRbfew@>js`%#)6^Oj~I08~a_ibJSn* z_cIl*&qYwcEBBML4rA;$xjq900+zE~w>Iv2*9yn^RqK9oYJIP(ChVoFEW>@?8@GOV zz^~WkVR!oj_P^z<6=uWG&@eH+v41UJ{Ij5O*7BfBR~E0Il&pgw-Jvk{iCI{g5ZJjw zcvf;Heb>6n%2Nt`2tCkR*<^LxaW5>6ZPQvB9<J+o?tVkW#HKZ7V0UUQX4w{=?D4#x zt12<f%Ay&y&1OD@+`(F<Jj3ESh1@X4VF<l6ICe;D2i?^P5nUJ8*W0DOXC}aXxhcx* z$eUHx%0o3{ldZ=Bm3bBPK7~M7S7=#u?6B5uBx>iRO@Xaq^p?NPZjJSBEhvxF+n&{o z*j$=0E7wQI6FIO}dA~UJG$IUKZiF_>KB4u@AZyf(>8chbJ02BD%OmvnQ?_IVj*yEs zm&E(gVnxpr1y0AYgw@pnAz}<^kEScE_p<zqc}qt7c&|$z$66sArMkvUzaQbIODuf( z%L7(e(HX{NqVidzPqunCS_GRN4X%qBwz1c*6BW0vc!l7-?1sr3n&lA=+342w(wwsi zs-DcB-Z6j&I(EBnRJByatVz5OyQa#SWuh)cRgbG6S-looeyJzYEH3Sf4fN6#93#)2 zMx?zFJa#-c?`9#Ln{V7+61}kCE{&=qJnGWLP!!wQDFq%NsCDY43Im!w02Ja>MtmGr zm;cihdD#o&T9Lg<a65(}Y_FFZH|8EQxo`NWO>j72Z**Kth_YCXgH7po?&#uXFk#B? z*PCz+zqEMSp1Kk(nf*o>&R){L&OXMpz)6eiln^XOeoNk+y?VXpA0EpL)6*m9WtrEH z>eA<(3T{)`z5IW{c|BOX7KB@oS#)pHr*56Q#&<}aWo1FO*W^Lc(^k*CRyo^UhLU*+ zPL!bhkmqD<zW>PO+u8)(y;fNmQra?)aGdc(g658Z>!p70#V+>zytBND8yVm2nCLja zBTj`|61mB?IoGL3_H5cg(voXhrFb^6XM>Hu4<)BskS9OUQ?I=}{eDB%h<NIMgieZc zSKQe;PK#^3|8~PM(F=UvjP=TQ7H__<+7`)sOE!z>q^it4v8<<GC1beq?|;h!h-N56 z+52hozo4~wd|3tgy`F1ol5i9sx;KU&4fxN=p4T2MvYR{H1Y(z_*QoGf_@xc(m>{0A zFzn`Eaetnj!XcV;;~v$AZg-UdpPobhd)zYtZjH~t2qcaDywh*?8>juQ;C@ig*HeJU zPlByRsu*gym+-41?d={xKn=Z_D3_#7qVZOBlmpS$VyVi0I<6$(-)a5r)^SS{5q6?Y zTi}SG`M$r&Gy2za4_5UA-@LL~{jzP5625bH^d|NcTs;-=cm*8stA{0u$f-)RJUL?N zblbS~KliUPw7hjRfilbUv`v&pIXga)$|FN9UV7VyfB32Deuy#^$dprE#Z%LpJ?^({ z$}JpLl{Tg7%HD*2R=Y{CMIFTj{eC;Bsy=X>H3!t$Cu}=9JB-Hw#Zo=(+Mkw!OJKXG zf*2pUJb82b5^c@;odTha^lY71yEH%GRsFrg#t#xSofDXdODuBtSTe*uDE`_ipE;4; zROGS%aBuGDnr%G(>sAK)*6&k^W%uZz*6+Xm+as5!rjuJdFw&GglW0c+Sq6WIK5zBW zZuZwExf)mI17)Fxu=##K5^aEyw^O1;)?9Gs`jum`!&~=!n`D0Zw8El+9cS!eH{e=g z`4a`d{acq7@l_nhf1Le7Ez2NfscZk(9ZPEm1Pom<d0j}j&Y*~XqxqpR3S6pTPk{Cd z|M7>Tb=}dt>BO-Q7ukp3d%jX{zM9FnT$N$E%5mb5VZC&}5qf~E!<H7&n}dK5^SkMD zLg#<m6_QT_f5DozM=k-&wVvlDJQWD|qHWfRam?IL45s^y(ivTI!KcOsFGmg2B``Sx z<zZpwskakbfD)00ta(EeSS=O31?^{ZzyDM@Pk!3%DHbhO3CZSFiro!YVm2+EbICrI z2l2GJUn0hhxTnau9K&kfy4`)ZPePqS{?ouN5!S@j?$NG%(Bfk1m-6yA3}Lz_T8H2T z`Pt{x|27XY{_a2LutB%sqqs1%oodwcitaCYc7P&&V1JQw!(D2M>N)pYK<qZ}trYKz zs;%3}3sM=s0{*N4`rPL6^ycoUo|UC~skvcn$q|oHY0n&KS5*yhC7e2DF5Wz+Y-xf< zQTC4GX54+{S5>(m=pWR6aW5gTvh{Yf+Ow5vU&6pH2c@YJ!iJ_viT9__v+gbOP`$!& zJ&+b2(>XA}^tE<>*qat<?{xgIz2K$X=|7s}oT-z=l05d%*uZ#y-KW*>8Yd|{UX0iF zk~%qZzKOUw2J4)7?$fgoY=!lbPho1*(KPPf_%ZT^W#!_9j8>Hl%o<F<QRb;Wg=2G( z+=(gk4>nvq998I%8rxQA_h5ujB=o%TvVa)|wd2dB;v&pG`kocv<lzMx$3A~gtb_oz zcyPQ?H#H~e!LaeMc^xG!6G|Po*?l#V0KDo!NmiAmqa@cCWTCNLWlnuNOVu>zr#Mth zcfGY6s(?oX%y&_ACw2YQ_T*~a_JubJscU57MBV;?_g@PzrAogaXp3b(_y49U<#1;W zZb7l6pkHCZFeV2)w`KxMAlg-6Gf$u`NBa`Z;_p;V?>^Aq-IO-algp_{b*?{1+o6?T z$R;d+vFVu?a`R1C(bu?i`{pjG?P}+@aqoYph~Ct5kFm|5UpVTf%B(7?ROg1H+(?H# zA%9lx&2Rn~tcx<OTS?E&FopJpmm||2so1XD^}}FXch9}eC6Fk1a<=6@k+-wY{!gP? zZX8~uYHsqP`oooHC#Zi~=~@1`=`Kz7PXnO7v55#y`|CaRJcg>*stYM&?g<5k1f<CR zl3(R)tehxR^_c%TQO+^m6R_a++ty1r<v-qjjXN88m<fk&S*Uoa8phm~j<kIJ$zDgz zPfOvcl#@D--KMXsNKl+~RBZdtC`|i|C`6{J8ZsSr24Q1Yw`HO<b8DiN1W6??E|6ar z<%M-=MXT4_wU8svJ=suk+R$=-*T-j~<o4#!K5eV+eQYW$Zya&@bb?$N!f;xJh=Sb+ z865TM`SHPpre*PS)`f72uEklJH43dL<vv!~man;K+LqhNmzT9v6(q^Kv^5_&s$ZB| z9-Dj0)!Cq+vi&{{@E)9ZP5S>B6!pZRaK0~3mY>M(C+K+Swi*15=PUABOQTq3aD9qG z%<cU+S(&Ci#fVx?%5QC^u7*5&L4e<2)SAZb;sdai{D-k_SjK2OMc19bAZ8qo{1%_v z5h!>dbKo62cEv{8PAN_Z*dYg`u^>F%k^CUxVUZ(0N8f#ZCoZ*X12F5crA05Jh!C_( z)jgg&Qbl@|_E!4{i}Or+MJ_!%E=gWEof(*e_Z%r_B5ZlJ@qhSL(OXrWbo4qnXj?)p z*9Y}v>1|zJyx#?ChavXbw*_Ape<44A_)|B>F!k|7DJ<Pyk!qdn*_d1Dho<U@qt3)Q zB`!j~obB0K95*pP-p?z+RLWOrRV^xu``X_BVXT>K{Zv1APn~jn<*ip?{J=&yHvZT1 z(Q4H;`+2E%tDEdMud((<Zcebg)UrieuKfd<TcJ1zSsCrqE+&E-Pd@mHo=4X!RNJZw z>yF+c&&F?74zworq#Cp>jxVIP;&|<i-T@iwlKvMRsO@efR=8(2maDjAQ&k5=$b@fH zx*AD*<|MXB@T%i*Nn74-i)6HWQn~0Cn3P8QCk2bHcd3rTN!x~EZj`4zI(>JS-;q3h zq+QWYkMh8$(}9UY6}EoY4nA^u#X7NH<K+j#M#Klo=a@EZ=^kQbopAZ<9K=M^%R6cS zDf}j6Fe&y-FZITgo0m1EDuuw+t*`jIWM0>@-AhWP`(yI_<j$`>9cc-gt>SYh*Thle zyxemPDZ->6!In%5?1t7Pbo%sNnzm(Wu?Fn{R=C&-DtLPf^j+!`3%gX?_HUQ2$4hN% z|6^=S$qc(=^1EKO`@N6)ca47J^1n+(0fn81RDW8H$*R`kfKh1>>nBxsA>Eq9;&>=t zP;{m8$^UzLx+*1Lx0nyEq|GnBn`|)R@VvO9p9i1$V*S@2oFj%W<WZE@AD2zN%OIY& zCRemzoGQnj36UduuX@(l&BfWC<*zSE)837!o2xULfL<QCoT%^GZF{L9*eb2OcEV3V zKQzkhZFUBLtJmu%8IR_C{-3<~%JBUB%_TQN9+XYKqw#M1IK60Gf>N{L^G7aQ8;?FP z{{NHb3B9YeDa<r8-#@*QG5zMt7m{Lke2-<F{mI>EdG;vzV^oo1aBOGqaks|Jd*9Fx zyOz@`RcCy9G{e|^XQ0jFp}_99bv|;z7G`^87Ww@D<4J0<O<4JMWQt?|Qu?iznMg6H z$|J(^9k(~^_?F57VoD%|0{wu7PK@=rbA}1_FLS%yPFr5S)bn1tzH4f0Y4jxH&HSyq zq;KAvZyP<NGk*!>8q3e7E=@r`P~WwmK5hcEr4_iQ8;Cj6*rh5snbf_Z>8Fb3?xN~K zZ(5Zna<BGt=wpZ1teT@<_^rU0e5azD*>@pE`+DpA?I+e$tX$V$Do`TqkZqXGSD1@c zJ<A8+NB;Z}LPU)&@ut*O?By`59b4yR>BOoUGRu`_M^;3(#^%`rf}hm1t1xor>-m8} zZB5lUbd&tpoquhwpV!jx>yIj1(6OrRn?6ajzRp2g2NZbgC=+c~i~-dc3nsl~CcSy7 zb$cQ1zXP#Q;q7`wX!`QrDqpqjjbpQo(%SQ}qI(--JU03ByHmGRhMA;}Wb4_2(?9un z--rm$h<mHZ_Ahl+T>JT>g-WTTvSt-;jh=^pS(&udradA*atSkRJcSgENB9cQRA<H4 zQXRK9w=w13_xH=)^UuF7r`{$KG$!|`mb?99@u9wX*W%tZ)?x5})NLI7O~Z*Za;2q3 ze*Wjz4pv$IljTLkQhSzrB~fuK;0!K(5kE_cx&|hYflQiq+m7B16~{6+R}I+x-8&!E zRo_-fy^lT7uQBr;o@{5YN&bhM{Brh<3#t>Nt&WOTZAphC;T=OAW!sOA+k${owF%i* z8iZUztLfEOz#`ww6lq(g(Ot5=S-?W-`^okv-%WVMBl~%Mvvpnb_q>|>JM06Vzd<U# zXPv#<WFNh8Shrj5>t-}*8>OY2UY_+;t$Z`7(by1B;y%cPf4&v8sk`x;`wzX0C0AO~ zSxpSzb3!R*S!X2HHW?2bl}iHpp43OCWG#I$VAIUHWsdLdeP6U1Ms|H#S$icSvsQg{ z`=)4PWVh${5v>>e$4RG+Ay>`-NG>vY%HQl$-DsIf3!px<EKIsQLtmPE#jWRk^H#&0 z8r_gH#;!q9Tb5g+t@XiGd-pFN=y6Ras<e(Y{qlb~J{fMj9rvzu&hz0BU0ac~mY$#G zau3_-2FDe9yr3^lYU+O5+4(}XJoj>LPh`uMsB@qH<NPC+BZrOlCDSMWCVlzDpv;rU zt^ULQGX%eN#Wwnx&i|D=Of`{q-w9jKT&S|e?H3|E){Ux;C7PAC@jY+<p*^Op#eG}K z5GIJ*`AebnMeq%4v`^Z#@491~<{pb1W=QuO5b)&p6_H&ZXbUVK;&n`;ZNs{ryZ#)H zVAu7E<8EIzXKucb27B`k)oFJXS`y#KdZS%Z^Woc(sWnRcp>tl#Xk8Jp-`JWXKXuER z7TGmvcfh*#37dtTUjI${$Gh##P51t~JL$VKrdf9$4k>86)cC&kx|cn-Sv85boEqz0 zrQ5DnLaQrl&e+`bZtI?(I-)nl>ncSa@5onI$kL76vc>wR>~32EJ=Wa+tHq)|%i}$M z$g+Opy|>K&YC17M*>cyqxEy0SdEC!2s%zqN*V65W?RSk`8(L>1$<5~&-2{jByjg3Y z_Lx^>dv(2Ue?{7B!@RLyZU;vHiQG#O$71{Za(a(F_n*TcrpE4;H|*~+m&*e@-+Soe zkXKo2d&;`zjcu4^U4%V(H`d-)1xOQTS`_hGFhevDvYGw;y!8iWILlRt3{-7brHqW* zqJE(N?AkAHT%6MJu2PB{^xW-=x#kC}KHDB(9p6z=Q4n$btSP;`^ztoLRb=g-LP~RB z5mc@f{}zHFchNn;vO`7fsqG2&c+SB1SZn8D!*nQ4G<9v(h;_zqq~qt^6ra{o)af^7 zyxP_h!_n&bu5(0BZtH;a(Ia;z9q&;j+*LUYDaW^OdQU1gf7u)`aJ{d}=kBIwuMJ>? zcRg$`fs43;f==lB>sGtwqj>^dl-wnWC>UxhwjEP_YkWM^@%Em~!0o#2A8q+7HZ8*Z zroJ+_P<2wHc;REc(RSVt*ch8Xb$9)QPpC<aPpVs!3ezGJJ(5;-L6i~0Hv(MASv&Rm z?*)BLu4@3d7n&4<XzC{Ty(-0>E!TG?_l)h=(lmbjGK3L2<5h<2KW%ej6@yGKte89N zSNn+>2`WcgdijOil@qE1#%#V{uw}1^p+^rd1r=LW&7_-S$twZFd)~g@bm`8+n`_Uv z$2Hk)f%ZQixvZfEK0CItrDsL%m!D1~?-)Gl9(oJ%15;_aNUyJ&7Bm;ET=iwwzpZUI zKvz2Sjm9&?q3rU&+>ce&0n?K1$8GL=Wf1Oh`taLra&!MC<ta~j7p1Omy74#v86ry` z`~lr9gP+3YO4@^3lDML7$@<T;CzHAgT3w(1V`=N1KZ<0X{q+3vo}HID-YiT+OzDWy ztzWA9u5rwVQmZIDC1j@>zjyqktqz!Dyx+9vutB}z$FM^8!Ax@el({oWCbM`+e8Uy| z>6hj9B=e72;`>FvaS9%=)NZCxu(nfS{MkF+UR0%@3D)QtcTjCxxjw94f~s+JEep@P z6AL|y0IC_PTcJMQ?zSS-s{J9obyGokh_*4+ehTv2r$$LW#Zm{$Pv(1$Sta@lmrh1d zEM>PhK?|0@&E1&qIB_E4u5QC51C!DMow@*uc}P0<@dv5`(uije(>TlyhAS3b%AfPB z+9CSiez}?Kq3(L7V=!n~&rT~s4`PtO=#zP(_5J<q$1GcQMsU?jGMwa}?j7|}^6jvX zuMDVK|KUagNbMKV(<vjgy}ZqjM<0*7^=eDC^@Wd&O@-9wKl#0O?4|mW#x$+x=1!<q z?HzmGViahb`*zJp?b_Db^S;u-vbCeB>n6xkh4iP<I)q~T?L_aUT=(ZLnH*m_Y5fNz zZ;toPwXV|78QpKsNbLFK?;+0`rR426o>jf1q$cY|dqc#QIK`E8!>nIl3^B4$XY&Qe zO^V!K4%nx*@iF>y*UMldwkyBJ5uEg?+S<+jM6Umb#4DbyH*Q|Hp8#p7Vijx!Pwi$* z*wp{oE}Fc(e>V=5vgO~?(D)F{R=|&}w^a8R^<12y%u`O?^df>y$Z$jzh@R3SGPH*G zRksF)=|KJ>#r8x}9CtklL4&V^%I*21Mc#=Atb>s5vf!a$>*DN^!={>Ax`ugEix;h} zK1%_OlD7s*M>_#@w6S%+k}|03uZ#p0&4*P^LAH<TA|1K*c{Q5qy6yCD;K}_7MFQU= z#{zY|aQgh&$d>T{<U;Ng20tO8r55Rn@gCJ-o3`Q-liS3v43zB0_1$gO80q(IZR#ZN z#Ee2-qFLi3Mwx0eU~c*pe264E{h2)dGICeyFj#gmhdf&^-~BfWPM=n*x<UA*p1#lO zSD*N<q9>AVo>rrhBgsyRRW|Ofz}R&$!w5JKo~GWp9hQA*f`)X76$q#N9=WX0J_pHU z%WK;4RqYDd9#f?HAa__`8sI`T0(NFcP4Qd$)zzt2si9RpIq(a*o`*cQThTt5ffd#< z(FVDnW}oglSl##h5GRhcj!Q3Px1DX;`U2G1`qAFi(pfxM)OPxhGVLQ5&o)sE8&Xc+ z&e5c$uCn>B{P}FSaplo8Kuo%s`xn!y>8!wic6X_8c|IyH;cYpTZD!vy@!IdwCK|g9 zOA0+(NMum1bc$vznw?bn+_%ll!<|TPSDiuw;4OXh$6nW}96zjG#4{_n{EqkxYa-^h zQ%pbb6{8i7nv<@BOwL?!-6NOg22*6u@dxFXOXSPWS4{9N-4UYN7B?<F(EjU(%-u8o zgdhwiR=??Pb@bWVBSkj<Grl_G&1+}FrH*sW3wi<`Uwjjdh6h6pWg2>;*m2X2`-5Yr zw~cEzD|eO3u}Dg>%`3j)kGms{B?)uFBwu)0!#!G}ECIDYt8IQa)uJ{JT#8uEafAOU zDyV*%gaKY8b+J-?EnF0Z;mph0=X<tjJXB395V=8DVE*RttK9a3<!GccaH2DWTt0Ft zV$DN>W7y=>YV(8V3G+->&=Ga$e^dRFGuY-v9K{b+I7GXi1<uEFcS|Q)DlPVsh8E_z zQ`{}OxCjT~C}*u=L)TBWMKvGJ!<m0P+V*R4RZ6>OaG~whp7)rt{Feo#PQWH<!t#jA z()+pn!iqqLcg`x{X%!gh(q1oqrM@=>c;;qkFnSwFB}UXSlICB{`AMqmtsg)=y+I;Z z5{#yg3cmMSe!KUYs(g20u(|7$eU>VPO^lM_{|gDJXT?gzHt(;NIjTe}T4isybz0nR z<zR{<mBurWC@_^K#<b~%BftQ&;<96zRBM-;ztL?SciQ;=^w!1q-`_Fy%ZjdRX0Pt; z2vWXmw(->;j~;SA<@e{wDz;xejI@H|c3OnMkeC1{I}4MMeqYlX6RHMp*AKXtw(73V zA~DgVqxf>>A^YmbZBFbCFrVyM(;CpfvLZXo)Gw6)D)!NFa@q>oYuIXe&+W6F$8?7E zTc(i2rA2cTrV^RbjNKFyl<Yx0Tl!a}`N0|iauthc_PKR#V|R_1zMoQSsf*rA!H}1M zGGAkP<f^Vyoq37`ghJZPFaEJ3w$L`Qt}9?+p1x6ZS^sQlw@OXmyw9|*GqR-$*;d~2 zRe@;m+h`k#=d{SXg|8=#$$m*FAFgoJR*ZenQeND@X?)ZE!McaaFSZO&owCI3SRlU? zckx+P?0s4O<SO^ClFmctFCp4Q{6k$6X7*RJmNm}89;}Qs4fATM8?bq;$t!NWUARut zbsw%6RuK8|m@9bRBWhP)-R9DtWA55y$AYtty#<k{UlhV4Uqt)48e$W6N-y{Jgs@T- zZXs9NKFS6);-;!D6Pd?13mZe%bsKU2=d`h|TPjPnPiZ)x_1%C!N`rKi8oU0IBm3-- zMN0}t7JNBW{i1c1DjA8w6nUQ9FQOmHYsx%(F$5RCN~x39nx$SB`rfbK#)1Y;v@MIB zu;pT4ll@<--Ry0<rgTZab<O{G+^q<=cQ|^jvFv_@oejjEA$4A6XT~{!-xy#X=-9&R zzS9DNQ;pFJ3JEKJ=;vl1aqJ4XW$dbN{o%!0{cqca0;*w-XzctYG^{`Q^V!!HsUB=U z+Rn{~uJRVe@Xtouypr6nl?As^gtp}~H3yw0kp2wTxxN1I>47)S9qn57$mN%vMw{8| z_np2P{1#km*rbO`a&KMxpt60u@|C3w;pT47K<Ar5KC&6Bv6jJE&dMFw3T8pLI@YLK z`cKofB>B#U+pU_a53U7(Qywm9xs`i<jmf)w(qeo?SCI9SKzk7dj#X$lh^DNT;X0`7 z)M)KxWD2LQ?r6M!qc@<T>w24Hblo0y)AS+{XMjp~7Iy}O%>>QB+*_~zF%OZh5eal> zp}Grt4nsM^V|i)g;oxvQDMK^mZ_@GNEvOf8qTbl^b+vx!&76XjX7~Cd(&3XQXx-di ztx7#E-_%hRA6gQ3<?gGNS_|HPBKITE1XX7lnFgPwQ!v-P*EV5~I9X0kVQ>E9JE!XB z8@qP4-IgQlZx*0gX)o|13RG#^ZTUZXn_7mM6&pLVnybngZ?xEd5gc|}RiS$*C0N42 zM6%Aa8`V478U<h_(&4@7zg#){>iXZ;dnZi&P$xS2_5vfRWi-1@v#3*+p3fS7Te>yR zRBNi1A4oo@R9<q}8*SFLo;wYId|F%NwBa)zxeSS&rS!BsYgms8joCL)UXK^f6zhHt zEs6ba+fyApnGIJvY?W-eHkOooI*#XjvN0k6achA{x0G5~CnnxZTA~Q__x3)e@0ry? zc*whwlYuc=R1Ce625+wqQ4?{a(dR=OpFH|ntU=mG*~&07T1EQt;&gS;K8$>`aUcSA zAqG{CEv-Kao$m6IQ0gj@0umvd1#kY$fmo5x&*svQfPWET2#V|c5L7hKaq$zI7uliv zpdO?3fmmxRqA`7J0K`t=X3&cugK8hr9Zj;d+-15u3PW^X1uf<l0^DWDQ%w-&z+@^K zDHEA&B41>_u1K_1#(U{yo!rh_Gqxil=9MHWYyuj7C{9meoDFXWc1l4~_W<`cyd_ix zAC>h34kW}=En$utew2Z`(#g3Ogm+@%_sHM8e39m`<dxwArt}`0GD2{}xQqh1!kPee z{x+<!HI6%BC~@S~iZP}VKN?oHH`93{^iH5Cm7NOz(OZ~??E?HXn9Bh5RC>N3)iZ#0 zX-4;+hpgbmXT~h_+e%|w7^-&)zs=bXc~ge9)muy*uJde#3vXR995T66IsjW^!)$b- zX%+hW7c(sko}sg(v&P(@w?k+$pr6E(%^{yC&UM9KSlyU!{^xt977{dW$$lKx(Ixjp zHg?B>&G?HhbwAduFc;%NKR1^UP{2g|Nv@vRBRC0F34UDWB3rRGKt<MiK@_H;;-wOj zELHp&K?WXt!AQ+P&fYR43ou4vWfk8{)kVS($yc9ZiCCh;+%p`Kh-egXYYd5A7Q8DZ z^FTErkFBp{7c|b&x+2&P?buR>1QMTg)ufOb#O8)KI7zB&TD(Oz@11g}?9ll&L#BHs z2}J}ZR1{X_DRH5wOCzzNp^{OckPz3bnph=2p{h0F`Jj%~I2rCyD0p(|i$WGDjCs5+ zYFuUgYq`FEXnnL;j+v{oEqPju>8apdi-BCjl%{38ZnMu6PUL<U#R|o|BCz?v#>&Op zo;%m&9H)Jce`C}%=HO3D6P}X8qY8nQQ-&{Yn;)m%veaR6Ote(WPoNtA?$RP}@)yxL zx_W)qy#n8c5Mm^Z6CBjoJ-9ouZs^K-54VoGD$>ev&TQebf4`-j|5V+4?R@i%ij~(_ z^(G&DuIsC|HLJT{-R9l>?&nW<SHAr&?^N_fdxoodOo&}D*W-Wd=7l!LcN40ozNxzD z^}lHEqP2aj6aPFka*%u}ZmePGjQn_ws-SDWwV_0r$8H5l%)-Uh2Xf4CoBmS|f7v+t zk;~}17Tb&-^c3U3(VH%fnb7lr>bW<1k``=rEavcgWR?4>HeWk)y?eF5KuwNf{RPBr zZADB1Yfq#^*<Oe!-muJg!u#8u9&4X3-R3A+AFx5A`k>&sH}<Ped~Er3nPtc$m#=bP zX%_;RrR09<85{pqPVhJ^ypSy2+TS$t($=H<?U@H@C$9f>u&QVGt;jf)?&B9$W$3%& z+j3h}4_5S-Yiv^*N~#hxBMfY@a4M~<ktwBWSDxN_G}E4W!0qPPKYozT|KX>o(D!tI z$G6VB1WjR3<qSW$O#i-JXN=UVx=kr>N8)tRz+W<5@$@Rx{!?m@>@bj#)-7mKgdX3z z^m3JBuX2TVk;gGFRnslgTy0x}X)q2o$5(;ygDQ!h-1R*m-bhU%&z8vvY1*TnIDxn` z^O4J!O_i&*505&sxvxD>c7!HXZvA%MV{5J33tCt4b8+VIp>jk@u-Vfwi76qns&@HU z?oG`{KJzyWj*V{n`oe(gIm?p0FMe+wbK3rC+joCWcl@&P#lt_GS=uvp8{PA&B>S)G zD$Y_`P@1lLRI`sfaecAo8&ht*$D#%sjIiYj>4n($>Rt%=RY$3=!iAb?$eb0@0E@(I z3Vs9{zJ@;vZgTP(^QrK!8j~u$`S;D|d-W_B%@Dl=mHeFgo67P>F3)(RW6j<<PKDF7 z_XMNFaV%Bv#Z6x6X`70UHLeSZeZOrPikH6iuVgwV<{vV)=AC(m;Je_3ZwXe{*I643 zd@Fx6gSQwfvb?`jt(PNH)Jof~J+8)~v5OUw>Z|`un27h;xo+@$&(;&Mv)uW8#S11e z*N!%kk!dy+LneF%6%0Clhzb)Wl+4YWRW;9z+xTKxthNp1C&KKVASTwO2IPB2^z6Qn zplVu~Ma2=Onffl`!KmFbeWF@NdWKhy5Av(MoilHx{H)to1rH}~5+`fcDFx}z+7Ruq zhB&NZWrWaUh>J9KkDbV{zWoHLf@Zd*%qbff+!T4+Z_eV}XIC=2Eqz!))(84jbwK;z zJ8enAfd7mYOwVqyLJ^+s;c{=`#e)?h%|oH@HbohozL<@Ry8juX`A>sYX$`2@<Zgg! znMPY_=!b2EHR>!eiem1ML%YPi8#{$=Kami>Nyl=5n=hqu5(Od8V)RDMx>0F!f@F<C z-!zYd9xn0=$3!@}O=82fuGWkXQeLRVeBYSo75~~od!F#Ad|iU-?}#64714gYsB+q6 z|FjkBT;ywc@u~@CsO$8jN)sRI-#W9|5ne`p0SR1Fea2`DNmZn=$)?4uC%T*+qY5Bb z+{J4cKdL5W^?=Sr<a`EA06dwr<?61wduRm1182_GQENr{XniFZ083aAwsaK72UbZF z2%Ov?<a28|6dIQHpz~Ekc>o`b``N>QZX<XO+cD*4Jo&on%k~0aH#XJCI)|0HE2Fbt z$z*r>o^P|124F<Cy+sjMEQ<2sL%6%C3L!7V=NSt_bW(wh89g<pG1a>pUs5;su{+wS zoDRm(L@-7|{>_b9Uh!hv7%lw699NOovWf~B*helY!X0RvgG+zQS_}S($QitRvxu^5 z-6u029`3PhqY%?}ijJ|1M$8*>7adE43qLHhzQn}#3B!)!>M>Ll%<q&;k!x+wxEcjV zQE)kT8sl<xX_Ea!0_hUUCjC-~h*B>zsynAM&Q&7hz_Q!v#I`8&*}HbV)M4VH&Ny!K zGj{Sse`9x2A>b=`B>mypNhQCCfp9%O&nEE2s-V!v&Ty-7&3==u5@S<3^!N-Ai#+jZ zwfo;Dqpr<tfh=Qm<fL*eP8%lcy!QPzA9NQ1;%>`c3l*6)(z|8sEUNAbUffl&>gSF5 zLqrC)ljmMSPtA5d>v3PV3Trg8^bALmR?Ltd;(V~aP!`@9NNRQ7sif&7I}l>h4Lbg1 zXCnDbM>}nth0k~=U{=0v2o<k&{ggdeMZ?cT>!kKFf1{I61WS*&n#b8HNY;WU$t^gN zoV70MDn?e}WZI@qY&>p8g_OhRDMk;(y|H6=oAOkZVKTF`v>1wWAvK}`Gf|xGCxqyx z5-<dRy0AkjEr+3p{!-@c>^90iPw|Asz^?nwM=p8Xv#uIZ;dPIFyT*~PL9^KxyS%1$ z5SeJhjCoD+eNBhbaxc(TxB#P6?Pa+|iuNLR5=|Qd4pny}@MkkW%j#N0+dHE7!ozsg z3A7@`LlGHc+Kx{&e4qwmr{JrEE&#Z_b6c%w6Qxyc$ZP#>#1;wD<;)(m7r@z<4ksMe zv5Gc4Zdqaru*nj&LXJrFWQ10z%{?)~Fo0nJ4*tkNH{}*mV^PK4jkU~gmu1${%2@cw z=R)EtOZCwFp_v3!yWYs64J-T(nfV-kbthD^qzn8vD-S!%{G}EQxgj%UHh~#c1CGjx z1pjr66&87?k|w1RYQ~)T^z1U?-f<4cPMD6pEB=Ne7SQS@*`-Y8v!Wcu)1$S=1R8(% z;E0o?jACS`${(7Cj&zOEfi&J&ZR%zU>Dw&ZHbF+_?~DavXAmBTEBiU|>Q_wCpz6Yw zK>KmoKg&H$>MdaJrkoGrfj-{5?jDgw-YW_bj4{b-Dw=MvUy-gag1QsgyN&XX@wUlk zszHto;`Xr8$gXKDFp)SPM&8r#1MmFN`JQ$n=TD68?Wd$r#)YRX=2^1*quMBcv-h#r zp2y5Gc*!vbWwWaU2418rHfZdK?Tf&FI9(wA6{t}ySnZW?y@Y<b)4_Snei{u|bnh)* z!m0~86HQ36Fy}6;YW`<ow+dH2hF9aNQ7ow<Cv*yJP;$LGe>*Z(Dqj+Li?(Z2{57Xs zwm3=2E=p#W`A1&ujJSwiOiQfeoz45yVo;Ev&Aqik^Ex8MIV#rigiB;1#{pQPW}ZxO z)|tji73wC?B>O&3-$13AEeU23tyu!*<EG+Ip=8+{z)(3CT!{(AM3W-Qnzme3lCX}Y zG%Kh$eDrXS<04aSNawkbj^fdv{L?RK#xB{5$V+x&E|5g)RWA`0gxq?Xv2YfsbPleS zFR0q<+OE13%Sno$)-otOB$SVFjCV{Sntq8?hgiX3B$nBhQ#AQ6SCI`s*sIP=VbY&U znKz7T0D_-Fp9{OGuX2K7YDbKtDq2SjqZPe}9V|smpm6VsDB_H>XnRlp(v-?1Sm3w( zMlan=$tQ*n%t(WMfwR+zR07wsXg1&as?IR)UcBn0+UDSVW;<$I=PC2V9Fh3q%eIa_ z?l!7_kRuh|H#^-S;fE=G=O>!o^@>Du4FvuY1f-{U@k2sJp5j=PV{FVO1S;r@;q#qe z<-MLCxS%i?*V>q}_N1~8^2#FuXe)|%vz2@M)6V2dMPdM(qXIW8j@a^riQ?TuOJyd< z)9B%>d>b-oV;uTTJ)E`90$zabAW<~UW?Qpi6_?4oVd@njJ?iKpbR2@f#(4#iDJ+}> z+4`oBr%^Nx<b1Wa`B+AtP`O_uEL(^^(2)>HPUvu7`Y3=o-#=4>9-A-`CwR*>Q2_31 za0(voOk)xC0aVruIBuGEB`ixeieKi%>e!!!U}y!)>%9!y7%-#zBjSUluDys5dR#~x zfD;T;iX{yOHm5cytvtOwgE1S4t4vG0#Dnfmw1c6vAFN=WL}X<9R}WwV8pLqUObhxD zR2AKno19YRSG-u^gKIN{=D1D(Y9t(0Y23yN#Nq!v%r3RMiScSPlee5sG(Nz~QtcGP zVx<K~fnBvg$)9;SZqu6sVCFQ>;8Z|~B9^SH{&g^6x1}`cLV}SU+Z=F#64Yg~E$kn0 z_+bJ@LA$4X#i{Nj;)o_dnt-zwVp)R&i84;#G|a*QR#rflXa{<Ek)-cqRRROQHN4`0 zRNxnEg>Mv|<<zu(O!3NCr6^<51$YLgLvoFA26I`6|A~$wf-e1N+ljMHZX?=X;!xcR zQl6(>2$a);Zi5K0U@5rrv=|p2^EJ*HGjHH1ye#)^b9sfU1La6sZyY_Ov*(IgZnR*a zN!UTyY9Yp7=FkcNJhE30B|k`CS}rzszcIHjn5|speCs4Amq=n!hr5Zqpp)I4iJ51j zE-mI75PQ=irp>94&N!+C)RaVRd5cJZ7e^77i<HAK1a7@<|I;5i)xZ}~d>f?UE?Re~ z>*5r$$KlNWB1bG>%3J=iAQOpnHpqqB*=Fzb7f@pB!gE42&FN5%ol(47WlmA24$ti+ z{?+YM5BCU9G(kU7Sd>zO!a7;RD}}Lk6V63E48#1LyrJ=;{3lbY-S64{C$Ws#$ppgG zB(cp;E}9Yb2S!)Gu+0kjj?176+jS6D#ZxcwPckzMDH;O!o3eCtK7^<3C$>p;jUiR$ z9ad+cCbZIaVT98Kk=^jd-x{IEA{-UGn$Tcq1<oI%#oUbAu}A|Q#V*U@mJO1dCEh_3 zn^^>UWO5gg%;=b8IDmNyS_OVd9YQ`OvWD!$;?OOszhy(SluNwr^Pbk>O0tC!03Uf7 zoI@GHWYXL8TzY@|pdtVZN^8kzTd{bsF1qOaj)HqS<)1+<?3g1AxbL`#q#8c~kM5#> zz0$3^Xp^d$xyh6>bM&Xuv8^@}Ws`gbg-NGFVaaAjf~JzJM2CPexY;W5ic!j2tc_5% z@%$($D#(sQG>A2E$4!|;n!EF*GZs2IJhlUAOCBG9e<M(hXIge4?^9%}mTl0!Q0b+Q z5tNHo3BS1xod>L@U|No^Myc;KfH`G(i86&8#Gn%K212h$#V(+p&f;Ma%J?n!m_Md_ zrmSLMpMp*Ng?*6lon#;4+*q`Z%o)#~4UZ!^;@()w35dc!IcufabuK-a%g${IU_U)O z65Hugw~Il*YYcBKV>Cl%$%~8N&T|Sy3dP*1l<L`A@QT>F=A2dX2}Dbig+6pT#JTH* zXeQK~xOnm7NNO2Xw|NS2k=^w~KXy*xoK@&>JS6rDDWQ`7m_ApQjDI3~a;y>Rn!@_1 z^(s;LP&m&+H6m-vuqbiT1wG(WauHb=`4&nRSFO_2fIx8{#?x7fG%fk=ZqA5NNRH0c zRN-+coV1Q%>``o!E#e8`HtJ0x=zx<8XoCFJcYtE=70^>}=`PR=IH@-WlIUN<51^1; zNnQl+AI*A;R%{8~z-Hd<Phx}QnW9dK(M<rhZcqyEa!UKRlUl?_qd`DA5-Dbog<Ufd zem3N=x=UiQnQZZAo&Yq9Lg$(kt+%b<1&T)l;G;@atZ**xUesOx^9`Tr3KlTY5XOR~ zicBD6*!gH-M-`3q_#3}P)Z;D}%6YH8{Cv>}9+I;xIUrS_2!a-Y_<Czyhz<z?Q9^>q zO%!jFz!6;BM-ew8EfRzohO}<~baEl);%yyEr2W&CYcf+^DP+zF_LdnfYby!3-)Hd+ zrQ*>zkyNW>640I>P8fB5G%sv<c1BBq%Ruv4oIvnPd)w^Dq5x(_S8J_fBdWk-d=uUo z_!aN$6Rpo)=oTwvrjNnhO{kEcDPUm$CPNz3;%VnZ1?exc$xf$gIACrUug*nbEFmDu zi^b^^1{|<_A`mi-OeNFmHS;YTMdA74swx(+Zonvf1y!{)fe$nK#D681RHGowygiC_ z2I*mOe1l`mth`!_Vl%xLcGFdm5?AT%CbiMs@b`imgh1m+jX^c97S`eex*k5S8%$|Z zA(|U_#n1%`J#&O5$S7M^hzO9+nD8&SPXjOvQK+Z>Ok9MKg(r+k8*3pC&3#;1AnLWN zWL7QW`p%~3pQL7rg~>yE!l3n{Qeb}zli|9ktLv9JOtg$DVP(}a0DZmG;MUnjhp5C) z`Kz(z${Mcdu5Kf$6IsHd#HYrE$Aw3k=59JPBc62ku8K-YX*TFz4*|EaRPm-nhz|7@ zTWg%JPsuC;wE=%OPb8nc0zh9;eFb~bGYdrWrSggQ`>OV+c#^zXQp13Ac$^~dW_onC zWQ|ffP4-bGrr(l9y{pFNXg8$bKvJi_>mK!oz%?#2!r3!sO5;+X3B-?asnI&)8gchH z&kH0f?0oc3&`|Y=XUktJlKZ&tOeC~2Yk(=;k(-0?+iOI!t+lP_h98acHw$=6Y3OnH zSo99pl((087Vx`Z9?_a<t{YaNg)6QIt-9@qTE`}t=w*nvfK-w}w_4SEN<qH=QN3TK z{sIS|!ZDIGJ2|IM-@{R7Ks0K5PpO*ruyg}xPjrapjB%TI0oTn-WLFK*bV?P43f<b$ z1Fr2R8a!g%qSn>|6JT#b;CKl;{FqB`+{a@hf4wb&6LtG9T#-<XGOVxFmn4}*N|V#a z!aj!xkuiscAR<RE#tiiphRNFl;5l$=(S)m@reOP#x`mpZhHTdJy49kKlj<;c#uTx6 zFIqC4-{I;Zi7`@Y@_Eo8vA@Vx_9cM(HE~$=90Fuh!aX7}NAL>9o=whRnBE?6NkN7X zsGyim{^$9`LNasg2941Qn<u**>3vW{afWL&3*>X|dT$}~AL`67bo0zg5@3K9Tymm` zjX%!qN)zOpn|ha#6V&2g=wmmhr;!IJ42q{Ev&P%f70k#7@r-WaU%r8{#5`p3L{sdV zZX@27U6x1=D2!B*^qdNVtuhddQ(&9yLvCY%lf6g$ELo_sD8TXB6IF>tuB+A67@Lp; zWci2a%>KYa!CVI`L`BIY0&EL{ll>W!z9;-5&uLHmIXitGWdTRP8MZLT>Oyz2GulL$ zb^DkpceN9F+K5z5z+q$ytyI}>%p1OfA`5-h-LtznljaNYkYrnSh^pK`&TA0?&oi|f zg?s}r8)z2rZD-7r^nRw`FZtJMBU%GO-j-5ww&>2P0*LnvKw5?HXUx98qaP}9BC+P| zyBQ>BU6Vs6&+N-=B+>&;r;92R2Zk`?K<-;`zK!)*^|ZZ@Nq3+mud|tLE3_3N)t!lZ zn8PACjwtCC*=r_(D;PI*rI2&T{tRqGI4J@1YS^(AWhQpoy638$;V9G_1z}J>$YJ~l zT29YCCZ$OtGgyRIKP)!VsIJgk?2QyLioRRz0)@eE1Z|(wG)|+{-IW9aXX8Q_(ua5@ ziXCWkgr>h|usKBnK@$}XSRh>|N}TMVqpnd!oKtT;LgapX!9{v&Nz?5eVOC7v9Y{~L z9#PuUa&4+gzP!)xRdk`;G5c;Q`ZKoxz$KB&g~c_0^~mK)T$3^n*@hI4Felb^Z60g@ z4zRJ^T*}Uxb_x?xFrj0FVdjufQ2z<TAvqVt4ndM2(pH@C+Cpa*SIJNB^gNv;%X3|g zc^1AY5AVv(sTkdA<ZQr!8v%!6oMsIhgfvSixOsz)qmt9d3AR!06V&ifZ*{0aSMd3u zvB<Es!z_wOsS*{EdI4?7c2OJB#Li}W0mqmD1A2y9S2}`{C{_uus)Q7Cg>#z@iFC+x z??jao+T0+OOv2kFU*JACUI2<e#JDi~L4P_d&XN+DqC$hNHeU4-VOU&=z6B5A$O^Vb zFY%_!%1c`3EnnID7+5-`27_qxf!}Wbeexe}Zi?QNLn2FOj-IVNW1mJeTmv~62f*kL z{YJXZ82uv`iG>%U+7OQb<vgqyqY#Jj&U1h1V7(A4kdI=G)c~l#;=Kbn9I}8NX`CYX zhvCsxF$qhIV4R`b>wu>3Z5*F~mpmQaAX(gt8o3s+vuHdpimFkJ(qr#G$86fttWla@ zf<@#SxBNMz@X(!N6}y5_X^<tf{ECJzjQ=ALR~Smb7P*e>7;=M7&S`QOalW~DxMi1C zk0si1UuhEB68!gt81uvunljR5>^C&$L{_DvB2neA9Z>&x$6Q@BJR{DTbcsst^AMG< zr!A7m-Yuy_2H%~mb*>T!9llup6YrSfDq8a+%9?8(RW!RZdyC(Cd}1kS6yNVm&DUJ8 z5E}~ucB~WgRpP*<8Pp-tQgfAbcr%^rxY(HA{v<6nwqJzP07`zBZ5=Q|uNE8;zH{YC zjJoa0b8o#;SYSSV)JdVxD&xcq<f3U$PZz$*ne-pVc~pR+I^CvN2K|!TMESpS;U9&m z)rtL5+zm@a&03-&cYj)ISxkl|3S?ciY51TEmN{aWgq?Iao&@Rcn>eF2`!tPSdWVDo zC<&9Nrac1=ZvpwZ3&p!Vy%dK56%!R#$->oBQn>G0l~S`QhZ9uy!}d+R@vmj~=TS!} zqnLhRNt2`M6_GsJK#@cjG(?@XP>tbN9R#U}A@#1W-TOG1AbGr)g=Z+h`p*ouRpEy~ zsx0+qUib+gTqnMdz<xVR_49ZNo7-Bhj=3_i0~>GWhFq?+1}>AcozLShLr~20V4&ua zOU;YIx(GON>GJJ(Rj1hhmA(JHQ`?s9?v673opz52d|+8>6UC5D<f<n&)Z)gDQ3V*I zzv>i6@K{-YUTaQF_ibXj@Y-qAW*r72gi1b*7rxf5tEx>DMwG?qt-gFz#S)<rB8?{w z+L654@pa7v1jdVy_7G(wAS0zA?rI#FUR=wjQ2lvUSP@6)9;Uj-NFSOf|6fh#9?*2X z|9>((Xq^+GrKdtxF~lpLpj2$KI9YS3O}rrlQi&01nJB>wSz&$E(~-ph39HQ%Me~-o z5+un>4Fp|+_e4}~0&*MIvF+pU@m}Zm$GNDmeLnBY>+*a(U(c5a8hR%$*b+%4!d3iF zmS?N5o873rE4^Z9z-Y9kfsz!(_tw|s5+xag9#Pl0iZ2hHA;5AWRm6!qjKOlF@+PCe zR<Cbc_-3pZvI^Q{N@ZlGeu2}MmJ$q|NT121l8mrL<G;RQpYWB&ejG*zQB+at$44yk z%=?C^El-bHB(&L0&S=ml!(Q_NC^+aS*bFLrApjI5pq8D1Z)|`0DGEk2a0M6v#W~-q zcqX+Ql#We{Wq)4LEAx7H6DSgs)thV?pLhC^cK^KRP-<yYepP{(=iZ}(FH-M`k`bG> zy$qfHE)qJ!k0p1;(YBfi6bHr3fPp)gp?oq5{S;#yD8jVYMooB}C@dOGP<X1m8IMCU zG3s(bgdFGCpgW^6UYW>C*b=;TY15Q<0`wN(&#=8-6-kLCPbyg+WThkJk~1_(Itg-N zEZn3>02iDn_UbY-G_l=^mRWNy>yD+8!9L61)_*tRv89Wy0!j#oymxKZZ<XtIoaumc zBSdUSZy87ni?0RhtU>=|j4J8Q*Lc-BvG;OU4e44Ig5x)ZxO7JF_?;cz38T8{=DC19 zU;GdIPhI16r&igX&Z*%RP8{dwGtcwHbCDs9ruwSWQrist4xtveuP|y}iiqE=b?F#1 z(zJ^n8~jQ8Q@vb~Z`8U2OV3{|%#wHJ({t=1IyH+QCRG=|s8$@m#jQ=|Hja_b=z^T< z4pLzY%Xs@5A58!gZu0_GQRPzb<USw`y<B~V997@<l}HSbFY*ntkdsk)<{@3l$Hj`k z4Vm7F>gPqo%%QEN`^lUq415fAfSdyV4UI%Fe*3-p)3nOV7LNyR%YQi0Hs?QqlT7vP zA{%tp2Ytvkjd~9be6W&_kUg%IbzOjFHzQ3Zig8y@3C}cVY)-*ajBQF?Mjm~2L5{Mh z8Zi>At5w(f%_Ut2GGd1XTd5@b)9*>biNIYq$XOjq#5+uzv|qM?`)uqz8ILCCoX6D4 zs}>Ig2LJvwt5NR|MJW{JTs$1{A;!3zoz4w)X%e%VYBButRNq_b==&Zj7v&1anuqf0 zR2~B?3`X4$4w?$vO@vmY!6w_VgJpLBG0W;L+!m_&n_kp07cq4x@Y}YN?`-G<*aC5R zoz##V{=%`6A8RP4b!d~k(_}nh?jIUT$VbZU-A}|}Uc_!SsOGBWRt+Eqx1Ee)iAb=I zw!E+LH2>Y8?&YFvpW_L<8B!(Pn5%gq69<oDUv-hB6lR}aLfIWl$dwd%2`LQT6nh7c zeT}U<#Xn05aiLSx5nO}-3#m%OnA3KAjwne$W~sh}kPV=cNEwrkIXAHFAvG*q#*VD8 z^c46B58ROPXz#z*@bG937c40?m=l2%oIio-H}eC=oc%s}k9K911Nmy_fd55GAU$~3 zwrSg55b|4PRFN6@+LY92BZ=jpl`DnX){2(zvtIo<L(@-BIjn)aOR{Ud#2>x<nX0qz zp89bO2*i1SW7p~i;(7k&V7aJ++Xy;usbV~P7kKgZ1O;C;4}I~^nH*-|ciwZN?~d$u z#{<uZlCCumTA{cej)(h_PK?%j<awKx10tp(A6|Fyz8uf1V|3wR7UCgGnu}8)4ms|T zD=!AnaD!pHmG9r(y%+jY1}iI)wM)9|i-xJClORZim#v>!<|xFokROYb*C5iSWK@Tn zA$k0TmPHOy_thQ9vOhZe7+%rEyx6jeD$909(PuBd`KUgq{Dfd4;lN-2Wy5L{K_->q zl?wc0oi1&YKa+!8yoHwhoFhp)6OK@Zep#r35a`EWTft<M7*f|cf-0(|3{q$j0h^4d zD2kDfE<tlq@s03X6S%nP$56RxIlfu&?D{xnuP@YgS5KbmII)R)EYzwV{aWKM3}9n^ z&b(l9(D(sR^R%|2*dLn$frAw|+p8k5q>#P$=HjM6B1`dig4*fGe&TJlVl}xk3qXv# zZ@0Y20A_oiXqu|PS2~Y@qGsihHF^H5Zj-5<I&Dno^aGz;)&99jTnQErApFzd-LT>n zX1!noOy!jp$TPSlTDdWmTE+=|9e@SX6NulQkBIDz83{3wx97}jXB(!ENMY$mUF8_W z_-=b_Ih)03U{`gQ>-*=lbUua9nA0~=Q8*kR&(wRNNZ)UuIp{8j%s#M3J}}Z`Kkg%# zN-fm2+iP+|qs`Nmxs6mbDcVPyifN^RLAwLF7VFeneSh6`N7AKg^>&()T6xeqtf5kR zb+_aEBUjrNYZT<RM@=Mre|VcGd1vvveXEKS$$2V8ktbJX!x-hrK)9${2o?PSpfmfq zX1VFLjNsw+$y&^gEluYP+F_sdTDr2IUVzf>eSDOHBvwr35LHE0LkvYbf!oISjsM;> zuQHxXl?^SH<{gkRYK*qV8Edy>DLzsonPn=ju@~0u@;1Muz^P+G1WX;D3-(+|yjhSt zDrwmAtt&vxUW1Us@+E??&bP0glcB3_`l+OtbL5>pVs#~Mn^K`zUqL4$Q8$P(_0?(3 zA0FF0nd;<=U!x;l0;^QGCQ%lCUS}`L(0E-_dpOpwNad0IQP0?x9E?=Y(aqT8+8lRL zGP6`1*nV|UI>6M6)sq4G%y#`GPN{lcOiB@8V`$Mzkg-OySh!tl_W9<Dll_yar*f|( zt$|_~%*ou6NCsDaV3%$<;C1(-vH&GWCZ(4D?vRExK_<Dm*i0OnKIC5gTdU`>LUxN| zgP#wPM`l?cX;Vqe6VkNf6r_`v%XK}cKkp1p*YtNB6O>qe#nB8UmuBMFM{nI<y(F5^ znWTl{FoAT23z(7U4KfB*uLyNgEked+-XjhJ$k2IKzTMM1hA$SyN`e;0hr9QF+r8zm z3OENpacag#8glSpxq&3nn7HUtn&MJ%siV+^$}gqrCeybAF;sH8MG(*ZX)!svcD_~k zrSltF@VSG+j#r!e#+c?ni@7aqcjI@<qf;uS+P*~22T^#lq~Y0*jWwij47qH2o6vAL zV)**MrQM&j_ZXwO#(#R2%-A~05fW#LGm@*xYFK7S6^>Q9Q3u<4AVu@B#U{sUfl}zD z;ZNOOUm;Z%QF3QDBfA*FM9<%pzVKq*Ti*#J5tf*w!;Yq`USzAYvsGPHxSHyV{+k18 zjmrK!@HJ3Q8HTFnT)bm+kU6Pg-AQrTMF8`VHAOWKV#He}sjy6JIGpm^t+Ol!&0%nu zf%rZIgQ9t(eJ6O-_=bg={#hlLZCriu9RSdMfBV_-+**r8cAZQI{F~`Ew_Brx>3YRf zDj0!&@0`E8o3<ON(#q3Ezz$^5td*M-bG(T{F_OHJ*j-Eu5X-~wD+f1Ms=ZBbk=2OO zOx3hh<D*xK3w;HBzA4|Bnz-`7C(^LpkQ?l=e}N{WLY;-~ur+f1okyJ2|C(0n@YU6Y z3SPVtrc`^Ce@DnpkAc!k*Ej$T_vcSUVqa2jylo7oz7JZm7_s6V^vh%nk@M0hM+wI* zwdHJBy^p_rOya%1g0<psQVhAVz^gx^bx}y_$d8Yh@p^_UDGvIOA|^g?8wzj5#keWW ztdhf%gz##N2ckK(`sekhs%Tv3J%M5&G`Dq1$?KowFR|B1@Pre$RvusMP$dv?2_w2i z*IrfIxrXANi-2@>+63RDS*I>q{M%ppU<v_>Bq#MO(4UzsP~W{#e8%*gU(I&`q=QOL zr2;qa5}l6=Wr(Q{FSV+=F2>({tXcCInMdy5cDfq?3pxy&x~EURr3sufizYL+MgHXJ zg8!5xON?q@&?gU}>}HD=@{?K4Wg|vq49uB)dWfR*rAc6RP3|%sbM6w~8<_BnvWo5w z06lM6Bj`X)(H*o@vMMy)q^<sz@Upwhk2^{NFnL!{Wj?j^WY(NNic11!amp?OuTEm` zm5|<gM?Ko7D=FeJL{_M;I50>zJjS_26W|#@DV(}~^Vu|Cz{!l4g{|C`y*MB_c3EYr zr6>26@S9wyx-i3#7fs4?Yg@hm>@tcQrD4m_1oBRVkknnd@uhN`OhEQC>!4Y1|H3AO z-wQWy7yYW$x;kZGUc-Bb)7tNgOprLRYs%H3qYL+h`osMZJ{HDNRanNHh()wp1A57E zDgFaR6FhXit&b34za3(OHIb*xbH&P+FFJQ_C;$4<02iKCbPZE<Y)jS-{Is7QLY3Xj z{)&$~=(A@p0mM`m-w5jQ<wH&LVi${Y@7ZIddIFahk9ly_y0;-VTtCDGhR-(sGlP8* zv;@H*jTz^8^!<72(YD(HqSb@cS;8jFvHUx0;g5&(<<j}}<j`sHHp9-9BD||_`solB z5ZF56TWz0}NC68sQQ7isPHaU<#?)Fvn=s#ou<+=eKAV&7=4S*qW>lIvY+vh4f!ngq zRzmx~I|S2W)Wu;IEp089fRL-yE!%iYF%jr1)_K{4k7B4&jDoZYp!>taC$r8HGbko5 z6`6k|(s!Zal62Cl?*5U>v(=U#@aPj|Ng0K=KI`5xk6cFJ+)RrDp_QWM{pj<B^1mO} zLS`w=py-Cd@=l!DGq2_BRf+m&1~jZ&DBHDcG-?8LJyta}scHThLlq^kAhm0Ly)W-v zc=Ib&J&%w%ChKhSY7Xg2fmc#7iobclw{$%=E|5PbO9u%+8&M<)uM35Nc8g&Z_M)MM zSIMP9ld1dMXmoM;NaoJ%@ZWSmsH^E*G@hLEDtAi!Qw1e3^3rfKeH8Wi*-s>mTmq7+ zC^;%d!ZNo&(|XpR3sF~2;e?AZlwY7QlV{gEHihFM2sccGNbol9J)AFHL!hHiipz<$ zzvF3Zhwu}nUfd4o`4<y#nb(;*pcx+!>&EY5|Mm2|<<u5*jtzWHg0Nbgz!fc%iH^9y zGhBF6(~MOtMq2cfZf}|vi>gtiC^}GUp4wCTY{pbX+LA{t$OxuF;5ZTMd}>r6DH2Kg z*17JTEl}Ndlp8j^L?0EFSg=ycMumcjwmV@vk`;?KyON~n?S;zTv%0R+6gTyYy8wp5 z6(Dn2@R@B1l<+~>8V5?0RJ(%;&IQhFFG*&qgBZDVE~Hvv(CsF$Ff5E5j-qrb0R}3n zocqjs4THLKBNElJTn}f^Zs~HeBGdK}^t{^LlXc}()|jPeX2bZuKMd0Stm&g85spW0 zL>JkhC|->#5ZSa?Yh-nWE9YBQ;$!X&(uK4$*F4s4Mcp_l8LXmqw?a>wQHkAVKd1YO zipP4QC^1t>34BayT6j@jC0cHFn#G+P0tZCjH%tuJyv%emAPM_M($$@se|eY$4u2!| zgb0}|U{g+|$PJL^&KOEz#_Q4pw`Ii02!2fq{^A`XZ-~#)!WMTkQ&JPaOSP`X%TiRC zBb_(7h>Gpin%+0{aGwNf{yi8${)j^kgSLw}^qVP{I-<}il9}X2kd$U~?+1>*z~>mH zR+ANWg86=ic1nEGfo+d;-Z-U5Olu?bo~K^!0i}U^O!Z-}SJP?$Q;LMnpp0o*l9!DV zU9dk$tiD`#Yhl+z^X9w+LwXYsBE8+U$As$laHqgg?>1}hBM|5-zM+kZ8MC?SI_i9M zq<FZ8QLj9%T0Xd>t(F88b{5koYtuc0%B^(8<%??7SIuXAyw~>`qpkS)uF8U}Gw_h{ zeVctg^|iJ_+v^#og-OF6TcF_>1bqyPyQsFK&I`-KxSMx8J+Fn5P1^fjc?v~?MG*T$ zA^*a(tk#Ph3YD7UPdsJmf4!Cex8<3-EVRg+)k?dM=qT`|Arcb9zK9pHockfF=F%BH z5YO##9@#(LM-wtsl#empeL2bY(UnTu+cJC4^!@ujhUP&8wQpy|h_*>>jV`=8@_}2b zdS1%!TIC(@^<sh`Nsql~CTE1u0~#51r3J>RyfI$`#CCIk>7ja`c)@A{SFJG=#Xi)Y zF~A!B)x=pot+7Pgpn@aBaTQSfz5`jmc9xCaxk~hhU8W#BG~_pWUow|A$iD$~*s7N0 z5jB0We-}Thw`56qr|f0pw;tUvKLg3t*0-|C?XW4QC7bqHVE?i*jk}!P+MeL0|14k1 zuY9rdZCtQrkAMGnZ@b@$GiajECca;(NK`v><g#vyb1CzVedifwk|SILyD}{3@{qqg zidK?+l=C%#p4eVTH<2q$ACogEKkIJJ=V{SdW$RFhAI`~VZK_ChzIz*&c22<bW+{)Z zU|e6ivh}^&2Bk7g#NfPxq;pm;E*!aZo9XVcFN#-}$+OHJjy|d0%Q5T6<IV=Sn*1P` zg>1kgVUu@^HyP&4!lUSa8INt>Whyr0>sx6Td*HT>46_R(w?)_JT=sn7^B-ctuN_Ut zq^wGklWCR^$41}Fy1VmpLNksZ4jWO`#slxqYK>AmjyG26nkZ6|HDM~6XDW{tmnq6# zJP2>g2T@r`M>MLu_3+_oLqjH9Q_&nDX<%H^f+F9p{Lhu))l8+7;t5Hq@g+o~54#86 zTgdNxiC~pF2MpStv0!&gDF$?n(|&RP?gycr^XE|4Jw7S_D9@azm7T~h>i_v|kG8t> z76~D&FWi$QU7lhf0#1+edCyxeTM;VHO^f?VoxD@!pJ^}Ue6!GV*n$CS1gaOJPpZ_i zv(=NYOtIc3VZiKVt2_UFnlq>!+--PWg8kVw{+ld&l)bd8u_{g+Se(ptI{k}MvznJg zQ{ehtaKMR4EzWrUrz9uz+~$Ok2?>WRbt-poM}Qe!Z<Ubm+7vRH?vcZl%>?uyBGgG1 zzaSiu`>J1@{}o<+`nVyJj!g<714%e!rs~zkJr>#r7uR@<oA%ETztDPaLflClj+Pf> z+Q^-EZ&1~ekDLon#M&}KJ;{~$R4oNss@v2@-pu6W?b=B=sGZU`G_;6p>=sd{@vZvT z`ug|BW9b730Q1QIgnZ?^FZ)cL6N|_s2tsMr7n~wdtf<g6w@g;I!(cui_B)#;urfY0 z;ZmX|SsoJKo1@Q50@k9G?qDceMCtyQpNZ`_D(J!!AneeCTcnppd=6B6Z)9vUnP_|i z#G3Pmib{$IF{R(|uQjgTA?bif1vAHOFzp48JKHx$5ROZ00o9WfrwW#SufMy(C)#vx z<gIuiU700~03a}|6Iy1}IcQR$JNf;A>2Ee>{Nw#AY>FgRF@IPi-<k{DuqV`miHhaU zy9?jbjC-l%&O5I)=t?IK%rRoCcSs{X%D6kVt_sC_nysZ^WqW-b)kC|bb^Kz^L?nrO z7t-sY-d)ryNALH@<GkO_A`IKzU>*O)??+8u`387yr<-ZmL_C>jqkyAuAcrc7S8@4M zLPvL|i!33$b+0LJL7Y9BUoVaF?D>QVR}8^4XdxI~*}*ukwDwX6#3Rpb9wR-c!SS4^ z{4k%-%ETT$`iS~jt@1G27SW*VExM3dkP%!bUHOYf>Yv#Ff_r#}vu;>g7fH^6k5nEt zKNQ_Nlk@c96zP+LJ!|J&(sfsE%ewpIpP+Pc)x;#CcDF*rsBCiM&Udi|ner<oR&QM7 zxq}K0`5}xELr*ag#>CVd#r@#${T^o%kSOXNiiw3fFv<BQTo#kL>)I)A)Ac}wkh2NY zNWlxh*oM|+*^>$A@o<6a+VxnVP4^{=_co)d?Oy%JaW5Vy*6xAQbUzXdfkA0W^K?FF z<rB!ijcLe~+FT`8(01U)1{SV$C&fr{(?*D>wDDUE*uEcFpo|*n-$E2bQEMI3ARG5$ zn_|@-6$k0vG6EW!8)Ptj^DfH1Jje?@<KiEe>Ke=UeNC<(B#o}3&x+)AIwOqC3Msz# z*wtLF9tG>U;U8+Ad_UG|nL}-f1;|#_PK@%j{h#R3T~*ewC~g(++HF5bHI-(BWkKcZ zp=Py?KZuEW<%jITP4zF9+!=kP*izke$Y#Ze?N;)~9lHJwYM!}*8oX|9R;dwQ9CFmG zO=QD5OEqsXhj~jXXctyhW3^~CSzW$oOjXv|8{Gz#{A0?dK~_##D3XZB?^D>`s)|&` zJ#d?uRbd<uD0Bk---fA_W^TP7E`sIivc7wR90R}ar{$b_v^LX8ao=HHNU`eKt8qjm z5XH5W4R_nTPRV60^y6~4WbAEIfsMBBLr0BQOZBa3sc8UFu+hLcdyCwRb5=(QqJg)| zXeraf^!BAuBIMs<jD`h}kvD2zT6CgH-X#pq%(@>;%hFrQ4O1AOE{KxaSDv2te$>&g zAhfdYt>1<E?A@!DnS>ueQVm{HU(&osMdDv=@c<`RYWwc3pM&BY5yW2<cGW8*lt*9E zK5G}0A6E{UzC*e}ox$nwagjg(_s12lUD-zCyu>68Vnhop2I-6kGy+(Q{-lQX?nk%y z>5sjCE6x}vxg-n{ci34Khf^S`QrvE-Tt?t8;*-)^XTyN}nEn%U9r{m>?7tg=Uz#+@ zsbi6}9I(tw!>eONXicoe;bd0T$3LoMZMVsNkuq`Koo8PDx0)Wf-~79>x=LUCaNTjE zs2OP>J=kFACC{&h&hl4*fte}kp31(D_%NM<p5`w3`igW?W<l1+ikmPzN1NQr{Ie`s z&PkM&$#PjiWrdOK=@@BRUsDz|Gh5mW5@OLp1C^q{3_CV0PSy*DWr#l+9KP*nNqZf2 zYI@rA6?PpT`oXxFj*Syjf%-%-Y65R|($%qoBj|yj{pmP$5{w(nfH>^8!u@jrB37A+ zW#GPyBb_G8=SCJdC@pTu278yo+Jfo0R@E?f@KB&9ClyG+<fhRr3`U+a_6E_gSS$sR zELT|I41yiV7ZbwLiZpkyF0eACHsg~*x#)rqOhNQ-L1L(ThnArfoh)})37lHi1YD%h z*V;U_QGndQW?hr#zWhXLsp4l%AT$mF(8NuUxB3z_GUw_Hm9zRy%EoDNot&HLzIY#S z&Dv}gjebz3rn%28G6p{<t|#0sn4>Xj`B&s6afqr`?5QoX-sXviX$4VB3Jy2B+P>`P z+}2k>4Lv(tP*?Yf$zX7|17}hFY}Wd-8l5nF31G%#48dLs{vcE#!>7+W&r0!v*g?(G zJ6q-M6Ro=!2rf)TQX?n63&MWWBj+u};k3If&X|XPG@FRSp-9VsI4xPN^HjZ_w?YN? zQP~}vyGXh$y9uOC$~D#)|G&Pvt6_tF)B3}xP#y;A<)bNc$yXIz=e@<it*nX+cmT4t zI&Qpb0Ng1s*yq#Zq0i9wu?~6!eT}Gn@dh$<ySfloA|9Y(aDVr064iK~gQ>ou@<a_e ze1eC?ALR=0V5O+w@=NXY!$2B%V^_Fa;9Ro@Kb{3ry=@R3GdB%d8RNAIpzpEF;V|%G zap-!;f0ULuP1`-4d&rEc|9IKmsLS(kb(FO$2s0&JcT7+#?4^P7#R?9$^T0HU`Jhmo z#~5GQ7liqWY?wR3w+qe^PRF1N(1(zktOkjUG<zq#L!XA|#3?rHSkE{C$59<T@eD{k z551!d)by+Z>)I#sQL|{}X_VUGREk{9D(M2q$e<A4LUz`wtS%5=IA+WqZ`iJIQu{q9 z@2U(#YVZI92@z8`BSeFaqdTyzt0m{fdxPIYCccbh7QlbT9tFZQpOlHxwqeM#v@YYw zsx-IO4gBm^!a)@Aa1-~&vnP{m6KbGM*R}xR;dTfi@UwPY?uRo6gSQN$!16IB3OhiU zDlkJs&aXQt{~F^~ksxwvch_QYlPOlPF2<z&4QWmn_qloKvnGqFFYO%>$n_=8A5?&~ zAn0#^<R5J^hnHd5{qx)fA|Mtts#4`D)OIgZmGpsIUHCL8UT+}?fcox?CC1$@?r)FR zm26jEhmaL1tFIyyst~FOBD2}+to>u~5FzSl8;W;z5WgF99yXJ?$T#u$e#=2FC<?)Y zr+YDn%NXS9H3@S&pK%3WpFFDAC6Gp$KONGdafS$3wDzJZaY<pn_gJtPe~a7l^J-X` z%@`Kqqw=sris5Ax4Otn|O37ufAyi%x1u_xmKlJaJ{`Lql<I%+van=V838-5ShjX7) z|0ciVPjMdma*>a};OaVf<w^N5{Iw+r2^Pd#ygxn}kNIt{rfq{_!B#p_^r>m&_oDTg z^D%MEpyDmc7G)Eu26XKxS42abCA>N?iU3}#e&;Yz%7so=%spH4&=YG{_^1Xr98uwZ zKfuu<az2+UHUQFOlb@=$oq~QmcYKcW%EB(U(%UX)EsVGFFqM|>%KWZ6!X5^LGlW8g zSrwnkVs{(DJ{|fjZ$_Px!<{3$zSLRw34J@xdY`ye0?O%|ZD^@roPr^krv=d+GbrKy zQWx1qOIUT!g?QIHSf^xJ`#4#U00asUW~XOxZ^IzX;Zvgy<{c>~ScmjE>{UANM8nY@ zKQXqKC-D-Ao<Uu2;hryhWkkN<ps_&VWqcwn<;<9bHBVhZbW=_oM=y(O!}vq$qHVKi z|Dv^w6W|vT%siTS@0>TdZvh({MIzg0Ey#XUNYjFzkMhAxUjSLOy=O8<{=u&+?lHVV zP)8$F{~8Im*lrW)D}!Pg_<A!(Wg-4XSV{Cyi8e--FYMEoc8~+YPl0bpjk<!xWI2vl zo4;L+|K-q}yhkWlgJ~LQ^ot$ybQ)+n6<P3dVMC$bA#K+(I+#iYbyG-tXZfC`7U=Av zj_8)aTCyX?Oag&vTVJNHWRi2)GUo{z$1LJ{t}(rzj&HuAYYp>l`|KDGE12;3r~>fe zgVj!pbI_q}C+XW4+fJL$pWEQPLS&_j?Qds!Kx!db<U1fIx<->!w)kT6k6hb{3bRN` z{d==N!c+lZX9MKybT^$yhh_!M1iC#YAn8LDja*dUac+l|$5J1-1;C3G^#)Xa2jU%a zFI+ClJTqI~nD@q)7tm*!4<y@=O6YXtz;b&cFcE45FqO;Z=}w2T|K*-NIc{q@ZHd4$ za2SQ)+pZ)SA_tb*6G8X`DwToy)-S~rT&prU?6=jUVx0~!5UFj4eL-RjWqBGrM1Upy zM>76IY4uw@?ERu_Vg+$2g+*!1)#w+NSo>_4KY+A??BI-D0JEB#K;@gjknR~g*&OoC zo}@DKp7(126Rj=ZQ>!*5xm&^AsejLIE_-RI9@z)HSy#r6&a=jMHxMoT6<2VAns3UQ zA#ES2aNd~NGvAzPOOr9Fk+zTi@pBbN2oppAJds}OBp*h8bax8jNsvy9Gw8s(`0^Od znQL|S7zbFju)@dhJ*nRxat44Wq*GL7MKEk%7N|KKN|`zVy#pXfV)$xv<lz`~?;e2~ z^_Ym?)<Fjqb0G|2(;r*@v}I`m5)>byTeUZ<FKJLh(fexev>Az{a@ViKt<6rpDr@nj z&n}O`VI!|tynR+XoPZS4Czzwg@WidFntlR#H!N1sPe8L5x-l2)ui-&%6FjlBLg;As zx)W@@O0?qPAOIF?w4Jt<5ZFY!1a{$G{kY$36DM*bBHUf<76tD&W9<iD92_|AD{^>6 zi@!Y#u6Q{P065#ylOV<MA{-g`%bao1X395gNnGeLesX?#72u`}+hjDxN>%)IlKa{Z z@~J>ag_0~10vXf`eA=;J!llty>9dz!TpHiEhL5ZWh`3bZ{V`emaY0pKCVJ+L8(L=N zN><MvN+i>E<yJngK0K2+))<dbp2Kz?$Q#vdoB{m2D!jaJ@aBYPtCnu2Rg&ww%3Oab zG3tg2;)55~0(&BibX?gw(G4rUF-o_Z!P&j-J%T_}P%+}gljRANW$8l!YhpWlcd7>O zPlwv=CDE@T8aG{l-<5^35Na>ni$B+9%$X%*T5*n96+6D35NnzPUQ=tA4`cq8s3o*F z($7A#y9Qw>TcT3j0a@<JA3}d9L*rFwgrVsXJWlzu+IyJGw$V`3m%V!M=CQ3G0Na$i z$PvPwlw_B-u0WX)9TGubj+E;XNyHb(FBQ|xDt165ip`kG)_ha(b=BC^olGLQp^^=3 z6wV`Q@aM8(J6A#QKM<2%5OSFp%oJLAj-uFO{Mtk?67SP5#igHN{1UOCAuK*KfoqE( zDqj~7`LFlqrCEdP5Ol{ujWIN{l1<-c(SmI@WW4p#j$=n5&9mlMjl6|YSpsew(zOl` zQ~%2Xqa8NpBv^Vp_w04E`b@`-xPZojT))uholUhzGYGI}ihi5fY|nQ=<wx<ySh*Nw z{q}`JUz()kAn>I)z%A4)IOTx)q?V%+p4d`bKdEdGqh&S<8%=P=G-3MMX|2|yCPUv` z*!O-{Z?Hn8Q_M6YYSZ357x#2-o&dc$5{c`!Xpqh+-{rmQs6iOHy_D1_z&uL>CM7WG zz>&C<&N^cpIfL-E5UFCukoaQO;Lx&swwC7-w-5(1j^Q?gqeT*<fDKRU7`sF#r}NzR zewT<&g@Zu*jBB)_+4E-vS}?M_3%Nr?MacYF73nX>2DD8T!DJmZZ$FgBs1r_bocqmA zXX$22QxL^PWLUB$Mx+q2dHzm*e^=6=`WN$$XH3;4lU5UN<HY8wlv!M0{&>U?_C0g2 z6rxNhXl*M5yC87ZZU-44R=^^rd6?Sfdhcw4?N*0;LWstZw#_gwRIm=%8R@{Z^M;nv z^dXLti98wG2jnt&udF@fsshI&=JeXWd@=tdrHO`qj>0z>N=9!RT0n##r=Z6|Ur1!g zJJ{|t_&=CfX>B+Gcm+dWuP|ah$1OIaS@XP71n9e!TDcFuWed>+aU-vWeLs4qckYr{ z6e)2hj&q8B;LBjP{{}UVPbWF|BJUF`?*2H6v;tF#fc;@!=rfacBo2q@j}v!0@3LB+ zF+?!KhtZfPwr|duQMjo0*$=H^6`dVP^Emi~S0wge3yspNKV;oRT>I7v(b@CBjk{`b z+JES*hSyV<iA4q8z!hwJ-DHAe1=Qx^B843s)kl6w09%u>+oG_(PWnR3M>5uhW;4%6 zgvc7S^WDhwn(gOvmJB7lFw)}5xnAgN6wd%D!-9hzNSICEnAic6qifr1?Z-sGE-*&A zI4nW@R^$R?RY>;!`jI1R`E4E^+DCotzwW<jPo{;#ZmZ|+WR8P3X*$7~st>nE<U$Xz zpP>FFyGf#NpSO|7kn1VEDRC$hE)DtFXQzMWGnhDFyM_fKQ@RTclkeNINp|xGgZde> za1<F~R6!t*(7xZcc-<np3k9+a{7WBa0R^A3a1m8y!CV&|iMrz5=<AAJp!l}RFn5h# zAB|0nU2<`dyDn@fqSS_ocM^_y@D^5w-k#v+MWujM2TJ$Pji`9oK|momKzMMT%+&{z z94?rFj&r!8p@gp-gB88u6@xc6ip&mk+wCc2C+aOeXa*&~_M^Sw%7S5(mz}G#`qpTN z!8w4`{y$UWedb5j1JaH`O_Lq3%VfSL1BOU2KuXrAy*ot<8o{xM_=or!hfZO5GhwMZ zWUY==fnt@MKW#G%mD@YX`KH$Gu1%kb2#8MP;f|7$SBCLf7;htGzI+3PYF9@tG@Gn= zY}m|N$unR_#+8&YgD5h&fSOuS>p_AMU;#GX{VcqL;CV5oIoXQ?tf=FY8|FSNH)2ka zN9Le>t2?F91!_^DEgPFwPLm8A9KoezA7SzM=P@{i92}GJV#YL&w>Gn<v>@bZIN<<5 z77~zXM&D+NdVHaae2kbz(x|hEG(Jm1F@ypw`fNDKDm!fhf^XAsT4xLSjVMuZ+}KLp zjG%^x&Q_!8AYhJoJ8%2x5MgOtg(M#GI~CS-A77mq?k>aA!pQWAg@9eMnMRKZzS0mZ z1{Yu)L?ikKYjS=1dCpy?Mwf_+j`-Z3FiPdO4}cM_n+T-0eM*>L3zr3IibX>bf1?cP zB|+IFzG=UtTlN=W!O^wH7l|JTr{W<7Z@>ir^5VK0cWVBcJjf}%eatY`7Z*gaZfDT_ z7oZCy>S`c}PErGBbdCE*XPJ9iG~84QC>febfFh&z8CV6p(|2k)u*g8+WDG>L8|7bD z%FuH`4~xLn>|yG?*hJYIGN^XcuqX@ipe)py0}qEFYpe+fR-Du2)}IpiN~<Yvo@%M` zh7c|lk?_3Gr6N>F2CfhPXgoYCvQ!cKB7#8t7T-Qjb058@2Fw7GNb_{dV#-`2L|4(c zbi<;^V%n8QE)gIIk}vUufw~<{Z<YJYP&T^gqfchHOSt(8%GfW1ANLF2i^F*<6!3?T z1n8&GIRL0h?@p>!tLyu1vHr}oEO9Z#T%WX<2xwvNN-3$>1dLPtcNDyp?aKDXfuq)@ zPQDPt0tASpJZY)qRc-?_h*AM*7*qumB!iT>_CkKE03!P%L1o_G5Ye-5Gy{{oSo?6) zL?iMH=<iQ))}Gf0a~3mZ{pmpBrAGMA9Pc3V^_+-@gIdG+w+SN0vP|<g(L;sxF~%a5 zoM65aNd~G>QVQ#%)Z+)^tPB={Rl^OT`DER>uL9!$)zt)#&}|7Nh4NBg&Jk24l1(55 zn6sUD;URUX7t?%G0+nN+Xz#|~x&#1&c2hINP1jdzBkDSm2MQINNaOHT-}~s_b~l8| zJ5+Kn82ZK~u3IpBnI=RXKnrFObWbYnncljt3kT2K>95;Rv7W978GR&k)jLDE9Q1Rl z>+{Jl9F{IWx4H0=dgw?&<e1__^)IU4-K^ZV;LOz4r2{{g+!=lxn)Q7$bH~P7tK<M& zeBk!#9^Z~-b&Pp=`h&~W`D8Jc<=)0O&9m|zy5QVPm>wa5%uMrKbrSn6%XQare<NZ( zH$HUPp%1c;wwIbHRk!mW>ki7~Z{8hC4}M4Q-UbyhlxmlSMS4xLX2f~O8i{!@1#8pV zrYQuL%oRV7b3=Ffo6eO3rH&~-&>QIvxd2wGGTrzu>eEm52{Ri>xKDw4(RXEqXUcd6 z6alFVT%lGUmmAKbLHEHm#$1v;lp5Y>OZYy92C}23zEzhuN^bq9Q{<V7=_p~5+NLP` z>z^%b42)3`XOBY>NtiyJwK8~o<$;rf`?p+C6Oe(417!pdqH)Tr0AVCuGL?ZlGnOw| zR?{|-U|kFa`XiN=i*)@o!+Q?s52878LUS=(p9&t=ZVCM5b<Jm82nh_dZ@4W=CGvr6 z-E@`m)HUDq;JVI98z2ZIcxTqYR_+4)JhII*(6Fux*^WAjG~vDNfiuOqq4>ZjP1bxq zuu@<ur(fMEe!efu>C&m8(|eZ3nV6B5^k7HiQjkcbbJ-VKvF<&5uDFb%Gzc}_l1WV^ z9S2fha!;EfO*m$}3tk$!R3WCPoVu;_)RnLM7*;d3>AxoVnui*e#2HkoT)C%o0Jvo! zVMz{W`rsEBz_u3Y`VIOigLc<-ST+=w+|(rbJ26kYl2T6}Vsa0(8p1YO^x?Un*nRbT z^Bw1-%+|CgyZRzmT^yD1g||_4eNqV~>!2v$T?wxUx^Pmfw8yOxp?KGYu<oyKU;Ka~ zPgT5tnC&!qTn#t>?Th-dx`aTeFV?EoL?MW(`q#dXyv)d8h&;!bL#@o@w^r#0Te@Bf zeF1Yn+hH4*(!Ni=zHjZ52lLQ0#S$I6SP^vot#maR$2Wpc?s#I|79Bua1jLSnP)_v4 zHP=|ZNK6SKQD4J?&i?dAb<ZpB$Bd`+i!!5O#h%9T+1B>^HhLgTeQo(!vx*4+XM+E& zjRhaMAxYDxgsrDy{_zW>^%mjE(wb8oF?+~ib#K$5C#`!{4`+OSL!2?f=Nm<`Pi$^i zF<i}?Yo`N<r_B&lABE#w&!e&4%NK!bh!-hkX0UVQD7F9DmBTpoK06fzX2)wY@;(2h z55?f3u~_H4sq=65IhNn?#(uk{Kf6YQ?t%8JsF^)z9i7%4u*glFlNk`ttL-!7K`7L3 z)M1K-?`<Dw>@9Rz@}}y~EK!chSK%E>r!Nb>A}8M`h={kSGV6}##uX?LJErde9FEQP z;3KvZygK}%E<x^(x>Q_3$(+FPhmPeVt^8h77oo5-PUm7Omxz1&?4(m2%HM}E7U>TE z-tNrT+2<8tC?2kzswnjTV}BeGugba8L;A97{4=eU>-JWVko61lDgH!D=q`HGpR1}n znN{j^bisqQC5*;;%>CQ9y1yk|$LrNM9V#ONYVR4Nq_{rc+>z0G+n|1FlIJM}dJ8R! zpa3sY<zaDP8}DdcBJlP<!y?9KH|<Xw4xP)xAwTIQK($E!-k&)yeA`b+O2_y&X9n!p z><GVOd449)dxln6Y{78P<&gLu2vgS?bpdJteACOlpwr^F|12mBtXa{}7~oy7OqQPd z(x^+UVr;_68Hw!fzxFgD6z!3o>YwB;#h#t?d<xZ@<U6)1vKY8OEY6CSP3Z(R)Fh)j z5f>brdKRcJE#|rFebdTghx9-H^1T{q_%E~Y<HnEPyY)H;Ex|9mldH8<v8riGR}JuY zv3)@rty=b?vn(rLI-SlajeA<G%PYk<%s*bJuJz>uTqN?CaU0GKDY>hn=*HhfeZ>@X zIy;udIsUD$xY$abWrUD-tR^u)8~Zh-4$ZBI_>R7E!zU%!Zfna|6k6rL#u-Ce_H}p+ z5D|)?d%Ci4cGj&AkHuD(NuP=Ee6RDSRkwF{-Q~E9Tbi3t00j(_92=!OGqHb=Cg9c1 zXH?0W<MyR&<&GxL`z5!PM{VoxPSzh%)*DNEb@v9AT!_g?cxS9xddf6feLxN1@|A{^ zRp0jwmjq9KIkmrbb1Pby(9BNqBLDYhzplRQi1>(_inOJmuiXcky7r7SvOo77isq4p zTtt0ko$0NC-;_;3btm?(F1;@Q3U`J4haez}%F@Q3NzVr}DS?PP82;M>H#ponQ}xx$ zYWukUag(#8fOof~>1NoJ*7va?|MzCcl&@n#{1QTyg@-+}9=Q2d^{&1j-}9fC2X22$ zHTfKBQ2W}b^7T~auUl#{RoLB0^mT{^kc~MG{_wpsC)I1zS%Yj-(d>H^VwU_f(A1#} z$(5dp_|?=sZ%wYIkIyvh<}(v|{-djmFUxEh2EbJIHZB$@4c2L7-7#K@hBGs&C1Ol~ zt;tFeWZ<0gy6V)UBT7#`m*D@7_U&^!?lVC02TlJnllw2`JV+%$Gq3k4z8!5TZ(Z<7 z@W&&s>`8V!Wlip_qlBc3Ls_L~QzM0@J<4N*?g1~OLnctFE9-#A>_r1dc*0ZvycXj3 z-k&o2CfNfwzj@5Y7@Hz%FFD&fh2F9I*FE6L?6__@6mlz9cgi$YwQt>aIJ^{ep=B!} zDDCFD@u6KpDiZ=hqB=Ix%n}dxYP>t*zfFB1Ng80x(R<eShIhEXAa-^0(<^v_OQ)<l zg0&sj%Ma-m7dS_!<~jGuXau|Fl7}(oC<e&Ey$w+_1)<#)ea%r64IEM~D{%|0x*PJ} zZ<OmX)YgU5b<0Wykrw<`c2QSSe+OJ+E1&t}x_3<7dDhum&vsrblYg9P;{@BIP0j;5 zq-##NYQ6M!NGCNtbQYXE^b@-`*xe_}F{hGu*ky3nIg9ojP%eAm_R!r|WxxF+;NiaN zUNhR%P4;o$Z5p^7RA*^D0wZ`kkLqlM;V@gerM$63bxrY$5T@8fz(EK*z9pPP`*20$ z-9?|bvkb2?bz_00f0@Q@_Mg7}-|WgKc3bg@vRxmNd&Km%eQoSzOP2hqe;3CGQ5_ns zrYV0$Ad4mdmYV8-{NTQ;z3+59l$B~4z9u<KI{v%Kz9dU}s^Hfbes*Mk=SP}j<g}Ks zT?-2RuZcyCw!N-_wpDC6tyO?a*IPtv{lU26t!Jsr`sKrG>mT33@4Z{I!OPsh;eFFA z-6W~gU;0WquY7Fjr#79}njJEW{$@LuJG14D$X?HV^QBDdjIC$MIM=xpC(D&V?H83B z{nKaG+C|MxU=0WNKI=3}BVVtT0s?YJuWkQH#~JXgRNJRGrs&VZCVO|QURFcoYB$+@ zI9xw??yGF?52_#2vnQlnHt_s9GSxL9`;)z8owe9LGFK!L38A<T1=16qr`wI1{>VjX z@1z=Z-%pV~YnXTN*Ogz?Bq}%lwENoi!WVyrvfE@2p8kh)WVY>9d)S;=mag0S^6Sz8 zwKBzoU~5+N39F(IfdDWPAqjdhrzgTOrv3lkIPY!px|5|;{AVEg&p#nXFHGw9>&U=R zXG-|2<XJRr)aHa-SocNGMqNZmq-i0vm5ixGB;fTSPL*?Sa)ZvCF9I8LOY^b*XF5K+ zZIV5{^o3Frf3+zUzZ(;%`CK`~_Z@5MzkkMO^$aoTqz$tS>mGOh5`tQKNQ7aaZPvj_ zOvvLp0j<1yE*<@CjN0=<*_kcIW$WI<B&Gd*FG2F?-cIc|RrMDei5qL;E%u`YWgWWP zSKEAb8;|5;xmV9I?#<l#$$O^J>wb`!O40hPK}Yi(5s|k3(yE%+^8}TAMLa?el5^b~ zX-}j+ov|`dxpB(ek<Oa39c7|D_OkiR!Sn}i@pGh?e#yiZ8`sK->~bc>hn#BNo|@wg zojSKJ3Pzd*VUxHni#rGiEJer=fy%<zh?vxg{bPTwh<&R0t6i2mmHD2WuK)a>azn|( zRgZ_>tzK1CZu8Z@E_vGfq7pSf+U}+vbM8nM9B;q`S?=ug0Uf;#kGtv(>&XIj#kQ7a zS$}AnhuK@#xu73f1L;GhPK$k46sbBir~dIx)!8M_e+Q>KMHaRm2V;AT1NNgcUz1a3 zq){@9dK2$O5)kHVK$!RrrNaxszF`Af%%@5o-VglRbC4E4s1>_T0V>&Tqg2Gu58O^o z3Q+dv_5ZG!)c1|@$Xoc0Q32|Y9qVrdn9DDgCCg0G!Bh$|@G!t-)xF2-xG@vRNz>X+ z=C7aA@0--HqPSDfxGe3K5u048WXpH&n)4kV8Ok1?aY$VC4O73J;3MF*qUqTsdmrV4 zFJR#k%KX2UqD|dr%Jposa(aZ5_-qoYSU7yYbuVsF4*K3%_i;!-7tG$)@EeO&{!RxJ zvsUSm8daZSshpUm)IOar7BV<}I>w_Ds%P-z8(K#$ZCKg8iE`~F2LF}M<jLbD9n}M6 z-g0l0QUui<Ao}2r0)oAubq&mk|8HtZPg?YrUK!1(dmoQUeKvi_ZT-JH*HC7NuYnY> zB?(_&^4uq{U9<hv{4#41RGNYRt;61H5gMB|@ci`ocP7YANT)l|jjZZh>0x82btO`9 zsbc{W`-9FV4-;9ZI%%bkZJgHcPpd32WTllCkATtx@2IVLDw=Ouq@eVsS}&YLE&KEJ zcako7${f!bpC$H^(qmUkg~f>rRh<!M5)_+!J09Ch`-$V|<r2<_OHP<<0*;<$!umYf zG*u%_ERt1-4VoIup(kj9bnU>;G`UI#PX5>QoADv$2Bl8FOxh^etT1MDb-_yH8XP}l z_1FALlaZ>UsEyM5)LKJJjBzMLg79;v+Yfd1UHgzT#=Db#m{q+iaAP#uNBnW5zx`CW zx&Bng4FXRwo#eDyiC#1`f=gbGe|M~O4nN3@Y~(*W2iJUU1)1t?vf6UkZBn_|pkLoQ zR08}+51KEGDHl6rw*4P9d4#n7f8oTWXT3!O!<4fAH?$1L*zhkZjr*`Y6;=Vt)s#3k zEF>9zxBvaAje6<HR=t>yleqkdLtK=M*cVpYeEu;yM+cQR5a1WS#o>bmI3ZEIZ{kbF z-)!v9+Yucq%j@V1`>q!3&aa!GLFIo|<_UA{)a^Nsu@GwC^%bT%>ZEbmiM9<v_fs~| zuEBQcs>#Te0o$_ZCUtFTcjYfvG@G_Y57X`J_dFx1AeRoOwA#+o+&gz@UFZ8_TXo5| zOK9b@TNq={rG%p_{%sL$Tr%tE_CvSlzLzY`)*Uxa^Zlb|Y=J@fyjHG5-p+Zhx1>L6 zgrsV7c-)Z%Lisc=72`yU`nO#ymUX_?|GFTBZqZ$*4MN(wF!5kRtll=bW~tftkM=ra zid3dV%YX^1{<-1i{OU4~JZ~P13R8-sa5yDoi_)I3q}t=RJ=+YrNvD@QDJuOA%l(6n z4gT%prb?6EKV)vS<fkMCi;66x%VV+TjM!0H+Q-zp9{tgi<}YXMsQ$gAS)Q@oboys1 z2ENw`2$6<!k#OpFev)l^`lT=TrZ~>~o-xLOa?F`Rq_xnqKYEEjci&BvzLXyu7VjME z7qGYUf!nhu?rYuCWG6DT^b`XUvBJjen3QP}Luyj$(zU=*W#g~b_Mg97#+%13r9Zeh z>pm7nhy+86*D*73eXZt8`TA0WbX7Wms0ZKkOu@MmU(_u9?SoXM5`drzM9^OJv&ZL2 zlWwX<<y+My<%StqZKMrmrFIFrRsU3cpfG6H{+vllLg=FGuU7g0W_m_&u~!PHhG+)w zT$&Wpp19w)qU6rQm-CB^Q(NU-wDsk3z?AkFKJ1akD8|KSoKE2oMf&Hu8&>k_IrrwJ zMs<EpgZLtX!bVe@@?-3|HBWg~KLV`vzqx;ie!}t>iT8!r;Kwm%mYBVkchp2#6{X#O z9vp~&=G5puF3IuQf>Rv@XPGHB@DHY_BJ4OcB&=C?N71=pb#<Bl#-y=-RiHv3@9(bb zEZDSzR_#4Wu~54!GFovNSZHN(O~<1Z4f*|=yRo)}T{S|-M3$Q%7K{ioyI&fXvPJE$ zw~ubtQci;;2U2B=7tI_WDo3VlrQq1FP6Dz-7yqUq&HBTi{p%xO(@Qrlm0U)fZWK{q z=eg;(9=LsKdlwCtFJ8Ml*57$6D@iT}DmR4sJMqEH+*>a_VcNI@L`yA1QCu0f$>Hev zestk}b>B<l_cY>MOv|lxI*GHB2JZZw>Tmn^;;|XF3hcd44<ggaG*P~%r){z_{g$77 zfkC~i`c0dzt8%D(vq+bnT)5K2h5G*Rv@wR6w+*K?&Vq&V<Hbc;74~&EDe0FRQPDjX zNeiI-IOQx$P&wORUpC%+e4l;mD#zeXZ~UFl|Ma{3N!>ESmA{&h*j4*&XmbEzcz5VJ zEnW3jM%3KWU8S9umi~1CN+s+w+y>lk(ZYIF>DVC1v!DE8-c!k#(<}KVnt%TyEvE{u zsua$#SwfU!oONO`hR*0o$oc%DM?!mJZ>r#1P%`C0u-!<FD+;**5lrY=BC1B1MN`11 zR|~JHI-=URu-ZKdKVme?XWfIT#D_d$csYge;;zi|PdIyqb$jP!OsDc(_{p2htjN0G zX{LF>h25v!Ltmdj8y3z5jbqbmxo=%9yrMg8(mb!0cdEWf?RNnE%z3kq!~6jl8xP4% zI%SUynd;ve|HV?+TbERO$teuVfyQVA!S|)ber*zSH^@4zqA*L%t1Dx($I_y#J8$H; z4_lY@`vAlj{5{7H2cIL?{XKPxJLtm{VH_NV&#q53L_D12Ju=)Z?{pr7;&r@+#>6#y z97uvjvadar1)-l*UpTFFPodfotVni;i#NwOv-zy#*}qOfe)V#hdm?6U`s9>eu)D@+ z&~q|hV{93modcU3rH%MFNP>_tQ4f6azE9t3EZyhJ?;t{%oW`Mxh4helugYA)W~k@i z=#Rhi^Nnp?inp1acEm8X`?|tRAD5^!U{9CV+rHAs^6E&4*{drHH{g^h0ZoE$!6*oR z>gc^6Bm1U5b6@#)oL1U%BumQ6zi&}?R|$~YPwlQ7@<D1Luk}yS6JUPklt&w&g7d|L zFVOB;N{NPrZPEx5V_IAym7`k=qo!{-xcVYS=8JIePBSxaAHjDtXg~J)Jv*vJ_V)>I z8HRM%JY9`-Icl6m5QuZF3hP?jh@cQS5jVFDpi}dg6o@|+z#c>Rd%Yumv8akVN1pko zuhqAs{mTOsDH1i)TT2ARR$4GD<;y$y@Fvq9>qOz3AZRh;HvzPGG(RoRUMvc#grwV` zKhc58!3(J$f1qY#Pn*<LmEW0rrfFiTzJJk;Y--DvTPZw=FsH9;{^^)vk7$!dTI~A5 z-jXM)#YYJT*CnD3Q<*pSZX!W3f3-%)K$7(AP-@?}c>n3X=}%*l9u4aXDeE|=G$;dt zpY8PPvt@i4yJ^W2dTDyd$b`9Kv0^p;CdS9mt1LcoEAx;2XkrjY`bETrUG=`wHTzC@ zE@}K;cl!LrrSJsrB(E<pOjVThcXtij7&7TPymH;?q7F1aDR^|75C>`u3>|eAn<gmS z?XGafC9uqjVV7-9CDM)gHm`H~SJ|Np6F=Nx@En{HAk;XFYthORGZluVCV@+NPMXzm zUNDYSest}8BA~eGU~|?{+I^iAQUtso?Has$LJynUpuAmRjs3_L-V`qVv1F3a3GzEB zT1NbPS8$Pv7(6y*^G_Q2+DnLT;>IckAoSc-qguvL6+}r0pq14-iGiM0q1>k)H>oaQ z@ppByqq2-T!2tXzKTAr{Zh2f)A~~V9MdsE#<%m~gT9p4;xh;c|^2dixd1C^;YB3=7 zYqGzg30kKTgnRUN8rg3JmEGKB*P1>&IWFaJyUui=hQ;YJds|ftCKV^&-Bg$HiGEmf z3Eh1`_Anfw)mzsnIj_vN3XTdwQ;pt;#R}#2U2A?lq1^P+d-NW*ez3F+)r`@56;_3i zv)!&4MlXGXT9>3m;d<vygDSELrk0Kq^HX-qZsn?mRKi6#iD;ITl@3j-R?wGV(5{pT zKGWPeatg@pU_QH_<zkh%<`@AyfUZzVBOJV#;}$yjN<RTJHD>s^-Ozg(@j%mqQ1A04 zI~1WPN*9ppW80_LGB3)9;f-oaU>ZCQ9VUu2PgEw{6VvXZBBhtE+jO?a_LnVhpg4#K z5tFv)FFYvAl>5Map&x|mEl&g9OgD@g++7M=fB%q$Nr><?I4qIE)su|a`@*^7b9{x& z=hycJ!3Y<=nj#I&y1a&|Mfq`$0x=%J1~`zmEQmvRRnxQPA>?8?Z6zh}3@G1-!^_m` zeW4fyKAT~ot%4n;l?`mh??D|g6>l5D2&zC0gm-3yaPgiaEScFnvo+PGC=)#ZTtzv# zTsMND?KD=58KfNGgyNsC?V_8o>?9Og{vGabyH5dKCYZ-Cx*FOQWrF&J?A9xPhjzfy zv%ErR2I5I6qY~h!iz+=l(k^AoPSImc0pAK8XqEs*0fPlEQu~SkgfN$?Ja1BAXq0Tl zUcM|F^NOt9LDH(qVEHbgZG#Pk^Bdz9!s|J!y{KI9?K^#_cR4v;(-(in*CQP4suSD3 zxi_fTph{ZRTOtw%>@VbZU4s&*1i6oSx7xD#jQ3TXqfr~J7R<%Y#KPBH8%BM_dLaz6 zC(3oU_=R=)Qp)qe%4AWKy9oysssJ3#z}L0Vo!I~?+tYLduq)xGD{W1VC$u{3iiK|- z6_g62Ly!i9lEAzl;Yrdt(3c?i*Q!i;7CR>d-HmbCufscVu+@0h8aib~9iBOIQe>5z zm;?tqIw-5Z$r=i?=a%l?`R>e9bu;;mdM`6-DTyxbV}u}lj(<7l9Mt!Evj_Fe1)Jbv zwTq9cnuf1o(RhQ2!=<SCBv0`&=aF6BXICMD2TMhW*yOnGife*h*qX<6HEgEbbdw91 zw3JKYD)^L73tpd1J(GPE<X`H^NJD67WDxB-_1~twJCN~7N+XCHBtgtwQ$gM+&2sz@ z?Rcz5`yY`LL?;pzgo51qD=W{g4EV>m)3AVF%n;A!w>%UE2bEVrJn-*p3A(!?QL{4& zsSLqjtD?6~LO<t-FPG%XOetD-!g*`pzT~6ZN3}K<cqYED<-eSN7uW1^S&ZpSq;FTd zxCd<zGm=ub7xt-c6vGM^oeABKWL+=>6B;6=z?z~Q)k&sPZ*B;`U>T!FmjbUFx=7*d z<Xr4_9OnmxI)xloQP%}P+Ga;l@TXjzE8(NAx(dhaHBAny#Ap0&r4Qqf7`Vi%y6qlR zVxsNED#WAdFtlZ(J}G)zFd|yX3U|G_%wELZiV!1m3a|VYEm#N?y*|f|VisS9wJQ|b z2jcxEq(uuUh1vgeO1zi=Prs_&-SDVrVuZE=PpJ!X0gM{{fbO>@V+h8kHCrWEN;<;Y zq<{a2BWf87Rg(V^dUY6#2*GZEr&R-}$u%es(+#lmG<{{Cd(IvzQZcTu^<D*$4;)jt zA<lC;$5CfpHs=gU{BlE1%|}D)v~?ue1dQ|=l9W-KP_}+kDg2WVN8;3xjUL@IY$|2y z#0A#eb3X5~38J`z&?TeiVHgRT@Rk(8G)q*olrC_E4y)b48=z#JXFLav#2>Wff!oK7 zn&CiP4IXzkljMW)JwkQM1kVZ?I>|ZMJqzm!I^cNH!*NtVG|=-AKr3+Ga)Hsan}d~f zl#Fr<qH>psGQS|C=K6`=D5}PSPgNkQ$t;vY@N|Mo0Vm;{L=!_7d_6?E><c=BD#L*= z7xfRDC|uAy!KF2o2s`IhCKHI`?ja5v#TX8>v~>Zc6}q&rz;K^6qO3*yVr%GDd*Z)c z-_x>F^FkctGt3ETawH;<V=~#hU6~^92_sT;4Ga__J}H#ey=jz!)`NOIC3S3Ro?ssc zX?Rw#udRT|i?z<PnPq-B456Y-O%MPxckbYs@{Hyo;6KSi22J#PqmB)Kt_iX`UrMpV zM|2sKv@J+XYny|>Z5@A0;}8g=u+WjPa(8JIt4@K32_M>*v$C89m1x(R?L}w$ML<Jm zT=s}SHc3mP3@$7UfULkZWD15dxupgb@wDhnGuSl|^--kJ(?$129mRhCcBHUitTU!h zQK)SEHfjD}d>X;c;BAdbE78=VnS&E69o_~C3j<9kVPk_iOVClUGn^&8MYt;SI6w!? z2)@Lkyt$%lY^E(y<Bt(#z7wm(0OjwM5N~2i@;D=1%GQGRah~iBY(2q0WumalifALY zZJ;;#mR1nVBJJn)xDyE%lhyLk^^{90H~-^x_?mR@%4N8+#+?y0-YhhPPW+ciYTFOF zg*HJE`3R~eUd<>Nq~p|6+T>khjd4VA<t5G|h}HXPpl*pCF0GCqe-7e{czVQL_p_7@ zIvuT+_zBaAOi4$#%;fnYe`KCg5cIT(*KVeT$y5T|GfC=a=8@xk2ZV7^=033br$PBv z%IxTzaLk&Oq6q`&32dN2wW#(O?YgK3A&Ev7I%78k4+CU2;)@vRlijYa5Q2_ji0TS^ z?C8=ewOyC>U~drBOzkp88lZt#_Ln&qo>_PK4|kls0<ba=!W?o93x=B+7*s3p2JVTN z|1iJIeqv;X^7&vzk-wgm77$c&SnZ*2V1#WV%87uLh~Rp{e4H#6zud{7$Pb4&N^a7o zNrHEhvJo=>>e-^vI0)A?|Ir+{K|GVLhL~N*r9E)_y?N?w!OY{}2#(|;x~uYdPymmB z{0!Z(SQX^ywtHi~_ZOX2EOX0uGJnp5g36=|)?&%amCl0ti}FOK9jGk+(yMES7S1PB zbhTA8YSYvTX`lx(r%EZh9V7pLzMVM^nAUq$dl$!}An)mL!87>sdf0DIvL?YCX-vq> z=Bc;T6W=11;oOjL?}y$ZN1Pa1XYp>At+l$E1ej682ul0QG&%j1%4STJ7wKVsvk}a- zaEQ=}YutJ%EgtTcIIkbn?HT0B35H8;kEgBbmn+|3MN_yhE~S1^Ct6uyLKppr*bbfZ z@J3!=TyU*xes1!j!D=8c7Gk=%ZKmSABd;75owxM=a0cBoZJ#trad;&QT#OTj;IVpd z(=ws;#ry_T<I~W@L;49SdJP}HiwLI4lsm(Vc)CsgSA!OLPkuTlQ20STf`aOB0(@iq zO+5i!C{IfBs6amUc8$Ba<z(DyVlYeJs*Cc@GTbFWAgoP%4?nPv^l}Z1H6=b^0w3n0 zPmEnW#CJ2XgJ7KEZIl@%NRpyayD|S0M^UE8zvhU&239=0@pc!RwuJ*0Jm$wI9eU9x zrf^v7ZTVu@3C&9%2`VVky8j#A(S2c~hycj?ok81wRrN0Ds-tZ|Y;kV*sRs2P%I5i< z&=NmVGkcX3I*rzL!FlbxylEnlk5-HTY24+$>IT}%HbtqlHl$p<2F+69F(CH$S@Yr3 ziWugW+HVBS-b_DjMvgk#iy>CxQg{>U)exlsf4j)o1z0W8nqAp+HOXDUvtU37MRVP8 zwvbczT;-4GOj@<9a2y_B`^$?-wFzRC($yJ>u92ZS4p8gX`E{EiT!;<VDeX@_J91H{ zu%#SHvWA|@yio^PPyAJ@>E?FK;Hm;w6Zpj1d>)FwCfa5XsMlzvr9b@mcP`~jP9-r4 z|Lu@9iXo5|amFs{%&JU2h|j)EwM)Pbs6UCgRf;6Cn_0WZ4aFSV!?L788~iIK?Hv|T zR;?i)a}tD#l9KRxqX^fi!_imKHCbo6wQ%tx9V(CS1UwDXH$iTUS-hFm&b8abuu6HF zD|;*zBk(fNWjA=z=Na#`?{P~{0Td%Cpi2!-D2Iw*tbDKN=q=LXhd7q>{ot;s#O5t> zXUHoFQ^G~)x(Iqry$#_;nK_y_K`$N1VjQ`86sL>YkwKUC>2T<jbainI1@%{?UKlCE z%gnYBnJSTZ4Txz$Zi7FxAcht{(%>sN!&O5#P2U9uD>gCE!o}?UrZOhf6_CKQp+84) zo<Q_Zl8i!-ErUurQYZB0s+9IV)xQ#RmP{4OX0al4(JRr%ARecQAF)B{h=s3rDev#f z0VO!kf%{3gf}{83Ts^v*m>+?G2=`vaG)rOyp7wxYK2<W&Vj}1{;X=6*>Yq5T&A$R< z(@nHSaKs~JmWBm~P~K?w?ega|G%O(F5&dT3j)k9#cmWk9j!{;{b#xfEWl7U{d$Tuz zH(|r_`zNVPx)PJ}u+1DA_;A9JOt{zZ*t~sAh9iuo8%<Btu}9(RF5;lk0C3MZggdI~ z(IYQ|fd?hM6;6YA8xs-`*k=#r=`$UhILvhG-eWj2<o*}ACBWGQh<PI>2t}f5TDm8_ z96YJUnZ-R})R$_&MJggRsM}Fa_aG=1O*wqZJb%ss8<Y()?41Tj|AE_)KL)eev~19R zE{e)s?H9Rvv~eTPehANiXO)Rcv0#y!tfyVz$3yPGp>$~BMj@gjIY_itM~0bSv|fy# zMGzofbS1Q|(V(zEKy4$!bEBD#rh_^dy}<PZv5am;Qb9nEBGU;kYgj?M?M+krAMV4& zS`m1f`Ut+gXl-MyL|nhc7^7)e>HL%Ox-iIT6b+QZKIYns+(OF5s<~Qi@-v;pVsuv* zvTzI!!T2O<v-<=v7wNqUSI9-ALHjA(gaVr4G=3^lh^e@)ZsH~$i5IOxeGdo|$?sP@ zICT|-QDPCQ)%4ZmiX^3L+*xBZc9kV-`y6f#IvB5bmH7*ME~ZV-CU|kl0HIYTZdSXp z^;^SVB?@oGsyyY*a)G{el{p8P`NN|bc``<J0(NrB4@ztOxm}!f@9itulfG;>_2_;P zq+JPj<?`4)2rJuz1=w+Ts-wgtPPPj=qP-#E6)(xEW5kuPq1r{b>X{<uQpwi{E<etf zgGUcjBlz&PhbuIb9JV!RPubw;aULd6f)$Z~kH{TP*ti%G+=k@^<ol5IgTyJqx!fD1 zd4U5*H0(G+LdVJ7`@rq9%PF_Tbs^y)NJmkm%aAW56${0DR9=B|*1}?M0saVMkdaxc zp(!=54q|I1HfO6gY1BTieA0I=if92BrO3l!ZpR2wnI!@0AJoSr7-9q02&dV?*U+`= zbdb8wI~0A!WsIQHUj#)XU96XXyy{PsN<<e`fGVp|d~fldAY2?tA)rfne#D-Y<r!Ck zQN*~8fxky3MqEnFBq`05zE5b+;1XD-9b|f(5-F?%`I<s?gNzVLmg^zV9z-9P#ilE# z4HZZ^G0T9ZaIRMOzDww%o*r@LiFIGYv2v^%^Q<eRX^SRoxurY|f=YzWGDhl#6_?&# zFGZ=I7J>AQoP+K@u_pg^S9Hm6F@7dw+1sfUa?>x04kk*EtoHsL0rPz;@^z4|IVBM* wI~x0RD*@bvRign3&AFooCiT(5Q0@s7kgR)z*K+Oz=VLa3F2FR_<H7a+2T-g&r2qf` literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/70kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/70kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..9d506e0ae3f2c5726eccd7ebd4100c5117686daa GIT binary patch literal 160838 zcmeFZdstIv+CI8KELv?T+QZlaahlK|RhXjF3XLwA+J>M`1X08RnN}Q%wzVKsV<C&` z%vbFpDG5kvYeMC$h*h!5p`>;?h5$9nL969pOA<~Bk^mv6#lGM4`+mRc+JEi6|Jv8} z!yZJ4$y)FGyw7t#_kBNW=I5Ea)ML@FiC&{TJUpns;~#3~*FUwqdNA!D6t!s+6--go zJj%=C1<Dg&Euiq?57Q_weC>g+w;c`qpRbpm9QLEU@x6uk*;@QZ`3>WLkCCrtf6cDI z><Y}T!0ZaluE6XH%&x%f3e2v+><Y}T!0ZaluE6XH{GYG_@oDd*>^rc3=?j0t-Ol-J zj+;$*oT8R~qR4Z9?X?O&`riz~W4UBiW*G#s3bVgvS73GpW>;W#1!h-Zb_HfvV0Hy& zS73GpW>;W#1!h;^|C|*F`%_q0#Gk?={`A7q7ha0MzkdoRH$N9X1maBa{44pBC;kk6 zfujCYiT}I5|0?;u*Z=zdXTNg{KGonJ4CF_%90OT}*<Z6OFuMY?D=@nPvnw#W0<$YH zy8^Q-FuMY?D=@nPvn%lbs}=YJSA)p|>LK#`wm#b<b0>c#7sw@l#(#n2cgyKFCw~9_ z%rDd{)ErMw@-KdQ;orIQ=Fau<n)|S~_e1j*KD=<@f`=C@c;wMVk3I6J@1qMAJoe;c zzKb7!;)y2~`aJcACm;XAqQ{?joV<z09Q+-xx%21Fo&WeF3m$p=|Mjn#?<wDTbH1NT z&GC4a^7QqX<Lfc=BgMhh&c);f8NT@MUml*g#)rJ;&3||SUU2a-%F|=c98a$~<f`%N z9Q>T}@}0Zrk1s?%v^eH<?`P8=5BnhR>v`P2oV)Tw?2QM!m2YGmp8xQZPyJ!Z(}B<N zgO&xa`tyq~tqzZPW&NwK38O^OTjI8Ei{GBGV^_-Vf26*dwr784)_VsIN)8?Q=fD2z z!=uMOQYiBaju(Dj^u@`N(z5c3%BoZ6FVtTA_R{6L`XB!N<A1Jdn{_Si9i3e_Z~c7x z&ac1q8;qub!J*-Cvt?p($~tYcll$_(eg4m{-*4>yc3-}@FHbM8IbPo6zC1h+;J-P( zUUUEW!b6K9W4vEaU;J#?2lF2POWxP#uFU7IjD7IL8yPnqev-H9*T8XdYwkPye|BSs z|3BT?|GKgNeP4H|g>yhR`OfjBXv%4oyHZq1LT|gick9ss+3Fc;s!Zsp<0;!_C{@<n z4~zKrI$Gi{9I$1?<>~$MY+0NlPSFgtCdf0&;OcX&s_Yf7rR@W;!Wn9L{|pr$E5Z*2 z_0-`t1&5*xjBUWg+=@7&SESJc6{9oMO%cDlLdSPnTmyycyhjZRdZksB>a-||OwzGd zIm>P_DQMe}Uk0O(IK0}a(KvMUzzIrdoS{0zy`uF@!wglP#aA0U)3rP^(<<W4P&Jtz zyYzTJ_Pm-?I74ZJeQartdKEpX5cyLp*&R}gRkd4a%4U<qygb+GHo29tT#HV%YkGwa zO-L?R;j^+$QEb5l7OhuEEVcr{1L;_{dU%HFvgLbt7qJ&wW#S&KNo4FWh<hdJojyEf zM4(w|RhzF>$ilfw_KVFPUL3keSm?e?`@lxC!DXafNmL{+BTjAB;})@If?;Md59>Hz zAWa>0wor_o@7jM-#Ko%3P;UqOgspC0?bJ_Z`K8+wo97-iC|$e7JcWd5l+j_Q`1X1g z*26ZmZc(H_-6&@dN%Cf>)0KRtN4LeMZd8bEY2+ikmAK*2+~;-JL^&&&p{lEBquO52 z`_!pl=}Pj|Vn3oOrBxxsa``d*F?ysd(l1XtLv0G~UL;w>RAYfvyD1^xE)Q)r&rkyu zjx2AdMcHZ|RJJuKO4KvdtJmiqouL?^{j%YtPmh*U7|XQMy_-G%c7^l#3^k!=B^`px z2!;ec?m8(*CJqsYwz+x&l8bn1dq}QNsB5>-F9Q*?f<7QDbWA(-J+@4-DUv@rNLlFn z6-BW^9%JrsCB><&0ZC#%Rchh7IqVG8hRf;F#@M8(uKlNd8<{;P#bLR@LO=D?wPU<0 zgkzDT<#4#5g}UTrj$%_3BA$Ap{jAVG<qnpiZwE6%OW3n)kuB5X!mrKFpQ7nrtcCsk z?-xnfM`b_I-IC)k-LR=AJJ>@^2i>Df4t<kpXzJV9b2n!jf;>#zV_U2>;j$A)qFRq9 z{;1n8%(trV{mfTvxcs8Xj}_YM1UM|5845wF$-4OHmuY){bwmj+-?a=V#349a2WF^^ z!yo?Z-ru`2HEYA^PLX#Jk7Lohk_-9l`ikM$oa0e~TFX*L=D5}`T{lDJJ%4_0k14$A z)-r=C<X_zJ7tfePyyMC%WL@)U38GCO{o8w5*SW8E@W=WkYY$@4YYK+GID5xX-(aB` zqmGxZ$0p-cl+Z&b4muCz&rlBv(=-i=)%^-OluekSTB9w&q7xG>U*vNJBQ6zsWneuU z<*lweQuF0cqqVI~N7w{J$HnKbH|j&QNiupeLukY|7;ep9rmjZuYFz`a+A_|;R8Ed} zp_h8H{oKA1Y<<$BW!PU51dbM6le|qK?%j4XEPM!y5I=F7=U9&D?T9kWP_)%tjI)~W z2u^ttfzZKKwki-~%ZIw=o*4T9+2ptKS_^%X(bHqM&Wz0Gs5wPOoq#jd-gw~G>^$vn zt7)_U`>$Q{OTTKdDTF2=XVh8$$gZ(Jq-zIobDI=QYXnzmRi#Li?cb@AR<@bx14f&I zxgVXKXG_PyQCi=hq57&no-fd>jl$KL@R2L%krN_5(p48bhD3P0z;ChbxTeAE)PzMD z5QLIgG1-E*v8L;MbprJWZLDx!I4KSh@f6_#4UGiT!PdvAlAX2g<5*%5%urzr@{PV% z$dm5Wv$wYXeLjbkU>);<7vO_=iup?|B)W0Yr)Q{d3*J~Q(2><c)?qDer5DWxr8V7_ zr)6uzA+$Yh<9wVjC6=#7O)_GEmj&UnhG!P&Lui|6hB8H8@*CHhB;z(kT)NILLuwA^ z%B>2?z8PwCn36Xm+kK^OaP^H2DqToM8vB6%cEtt}*MbPX$y6)EJ)MlXuT|+vRHdlx zVb$}TI-c4pO?6I`DXk<4#|Pp>AfzSyLO-Ta5jCh9#`$2TI@&6!8A>h>3Fl(r)Wd`B z1t`8GZ<En9iMP{=)y|geblZOH4%T}>UF2jYujS4&Sop5KF{JZy^_7h(5l<H7)T|ZT zQvKA!y%q9S`84(!foEX!;z@PGsc#k@rbFnJt>%8S6Z<OW1tcQ3G9BST3ZI^eLjLDS z8bZ6qmip@VRh&Zp7+2YbQirU<)^)0q3%$pFKR#mD5-|yBv56;5C7+()s9zM$H9Pga zB2Alxd-86iQJ2Fh<fXF~*Bc^7iz1wRxEI%bzk=<o9JnZZKjAL<mN;xaS0>iXP*U7d z8R`t8n`HLugO?u@nI!4#ef*(3i<gcCu+S0*G9HfNd7X)=b`2oV4)`%PA167_?g;A9 zApy33OzFeKVe}-bjV?&pCOhcV^dMrszQMumxKiAqZR1*au0H1lg*fcv+!?A@lEK^( z_h4-!ssgJQ>jbLx86x&Pwnja9ty+>Hk*27UQTbw?m0-C<C~eBND$nn_7e$(cCW$Ih zm5jJv6I|ArA$f+UWLd^PjpPGmTlFtz%s3evof?Gcis0`b(0{<CEXIb8l%+&kN8Z1x zG5<mJO|k4!-L<qx4sOYK;%{<SB5vbUWc+=`>>uU--VsmXF7Hui9oIEb<ezy%XG+_~ zF}FtzkR#>H(!ZG@c}!|PYb(syuJuaSJ*VR-TTkvBuewkpNz0<077J}G+kQ@MJ??8G z>xj)l8hZYzHqA}GLj0^qpvT>BZP-56@9O?c#Br^xek-AqX|0wfj|rNw#9IZMOgaBG zx`7G3pMC{fN-F&Qvd5Ao={9Myt5z1FyA|5lu!JjT6Yhxo(zS@o4%XHA!NAT{D$$?+ zb{W}8M;Gx6`F)DIvtbt-Bl+qap4!rWZg25`&!i$wm6E56L8U1nWmB?lktpWg$#8n0 z4EvvV-7BZR3gM;67dmh)Lnn}@hO52uI#nqdLjEYr*oTDn7I~|Mr?eI<6*iSx1hq=5 z+P0{~LLb;DLv@{F?F5Q3vZFvs=3G8r<_8#4ijx>)QzcQH;h{Vo@9`OGGGFA-1=q~I z{O8tbo~x((fe^dKGY?-a6WGhDnV}4%F1AJ#oWpUvI7~k~N{5JTV_SxI`YEGb1NLTv z%aFBnYkT7#B{{$bC|DP6cAfp<mt#)(N*sTC{Qy&20jOa_?#%K#WbEdcd&Rvmk^|5G z^=i|(2ih&?l&)mtla;R2zLHm_rK!p`O~c`K+CG%9cv{9XlS<uY<}EQo=tbt2=+KZ~ zN2mUL@za1Gu8vq2YiVb#g<E~wSu1a|1eYq2aYlHRFN(IlAu^czTuDN|tY;$~nw6~N zhJV;QzPHMqt1a}oKku`p0{CFXcP8O&pTE)c2VlUOGk#2iB8t9AVs>~z`8z$5^m}G! zbH5BZ150Y!CO*nH-^<odrUkzF6WNlf(t@_>vuvaphXiNk<W;lvuXAEMOH~rOZYx(6 zEj!4wEGszIy8j;ws<5eIzjiF-_GUI|=S4-qM=vuz!#kNm6ROQfxlHsU3V<uMaA$fM za~8F<=TN~{i-f6e%#(-{b7I4)@>H!u2Z)yl^jlkb*8)7*DnaP&h?}9Xq&=O;XF9%X z6_RLHUa<sO*dcZl2oypALcfEyr3Nk%0*(WMM(}PgbRP)dI-Wwrb#<$f;>^8FnAkQz z(D08+jgC){>8)s)sNX#3=@TNh4{W)DLV3xZqGza|EAQHP2tBqA;pN9%Mon<-m*uWH zvy1cr#}z`3{qnG6=?RjjGK9Fv)x%}g(i}}8e{}fAr((2tdt@?wH1(g(63e|*xhu8E zfAfPjvv4l~<SUT+R0U_MA{{#SSD*f>o}Qec?qpSYpUMtZ-m5p3=Al$AVouAV?HyW< z=7HX>4>j~TE{_;EAHFMeolE148Z0<Hs3#*M`<@W3x%ICttum1SN0PQmlY)kxU(!jx z%sVV{FQ6jQAia-Ejg|Q7_;%g0@hejaYmF~FCNkO>Qjd@|^bvW2I)RSv>U<w~L*9y0 zw9a>iI;#@9p4x`2g9AKJnza)h$F@b`=w?tN7+#j(F_KC{TTgQuP>hj*Dh(GEQBM6` zcMpP$0oa1Pr?y`n%G3IdBMA#{<MxB(n_LEUqieuvsjw}IL^?$t$fR^jEm)2Of1#f= z5pOnld6?<Z^3t^qeOPgWycH!_=g{D!U7yp>gwVYravTYg6AUTnqQFRkQ`Q7`OOp%N zJ>k@ZwkjPH60;<)gI9lBkij1{V6`%5sI{w6A2q$3J+S}PCjn|5Eo-}gDX;{zEp4L; zH54s{kBokn35)6{J>MJR$wiVhlNcvl%R`}M6BSZ(wIp4~o^_#7D}EU9E6|Y8T0SiL zqfCS@V@Hm@H^$p}!PQqN#05$RJ?HbxxPXN9pGg+${8Y)Lz?qQd2GPl+As3OmDKw!? z;hGH=dg!Yx5<m{U^F#DsOoQB&Y_AvSQN%h#L7v!UgBe$LJRb#$WaJ%N`VRwm+(a?v zsdDG@l=@19MuJ~@r?N-HcTTw5sTIND0{tZNXD&}}J+2u>_*6RUcrvj)bsM%T1}So$ zA#W{K91ChFen{dYmidIy8uSN;VmRoA#lk}VoyN<!i{^Yv(u+EF?Uab8N>p2}Rp77! z>HxQ*=^9wK_!pfK$ion!2oG-bwJ9Wutw#YAqba7)Xv@^EL~c2r31Apw)LpRVdvNS^ zh>@=fczHTgT)K^EMEl5`J{gXdyLg_#p-RcuhXCQAwM6w)rMfOu8RTpcJDMAeMj9>6 z;fEKu0<jxpj6Kz#+AMFA1Ro^j&3M9>HAnN*t=I+j!VJYJeu!^xX}{<=mT(ShYfszq zvyMF<K@DcUU$qqbz6rfi#1un`{hs2C@Z@N5ZD~87*^65Bdu;4HcXyt%Sy0E9>lKI_ z6LUYJvcUtZ`!8qG>m@(y{hbPlbbUr72`me(FWeqc@#C9+j(WSD^f`WJz*aL&pu+R~ zA9g<3zOS))ph1bIl^Gr>X*fT<|8C#JchOON;LR5$3T&IDBKTU8C_ip@TgDfKN0)PD zztPhUvaPB_bM|Dv>e-uuPosZ`0@@+f2ViXX`~TAZXY8Nv)eDaMUYP<g2dp@!pr55} z13*`Zod`4M56;&f?4D4Mudv*$#d{f;R-vL!`%t=KudjZWARu{+uWSQ}k$LK=Tfg+n zt?62n*KaGv*?$>rScO&``g_~<IRo#A$GAsYWf2QZ;Z?xsdNj4D0RI@?31Fe=m0DaW zYOQ~!a(KsEY;vKazGTg(rQ<g*t^X=zynQ=1*g}u>>`hK<N{YGY>dx4*6kF7TTDA+R zRi$pM&<dnUFCWjM7nUm7MI%18REOS{y0fQ$9`B-t`6JiNJ=l-*VO!Kl|Jtoe{^%`% zR@sbhN|H4iz;#_M;}`j5h&WCQ`*6|wWmg3iYo;V5FZN;sM#T=RSnXPmhEzdXt@uEZ z7b0!~4Q`w&5zWuAQy<z^{b{sWl759JO;j+0wI{>5vT*tUmVT1pBS~ODN`}a&<$;h9 zPthY4E=Lt&3|G$JrvvK3%^p7FbOT7bk0_3gEzM5>B&oiFlQpQICytT~WKRnebBYXD zt3-r$^*l5hdfO0k$e{bmXsJAGHBy05jr_5Ec#T<vj89M$0%+NGPr6s4#xjna*e-Vk zukM$To4Jv-Gn|J5IK(eP2%fIunU~7j%>8aOeZMTq*T!hf0NR=maoACE@0>y-J4SN< zT#=tIlGzOP$4+J#ON(xRz0jt}<>5tuR;Z2Z-vtYl!2rm)`nnY*3ZJ!LFnXn9?4iwG z>P9hXIsoSLI(^ySMD$GwV3Ef5kNoL=3;#A}46Ps*L=r0<8)HY2V_87o?Oqv7tGF91 z3Gznc$$1DOn<B>s#;Ln9fFTH<G;#UUSkXoR=7QV=`hKa}++mdxI9@wsv8mQ8gnTu! zn@Y4+0?I}R8V*efZrs&FdW4l|(oIZX=J!kyFCz*m8myV`74-jVbgkc^8Zq{;BL3J? zLi_;1I*}myv*<iOU#$Td7h9Kp-75p>^_n=;^$&emHFKIEiGky))Y0Ka)f<uQ`PCf= zTNELD*M-88U=2nai9Ts1HeQpdqYr>YVm0g+BI~jlY8d4q9vzjlRzbUPX5L<=O3rf} zB@HfTbkM^Leh2js@71l4j^zZT7J}YF)Y=4>v2=X9-jTXd5zce<>K)c?9)62NYY~oL z(h`$ss{!$%w31fuv@GHrXN-^5aE5wTlH~`81X}ElF#3CuV6nSXu1uBySTG&pN!9MZ zDa5oZMVb`3Dgyv7U5lzz#GY*}_dYspzSVk@XC8TI!H(hVG!wH&7c=<Yi-pMzD$!CU zTcrJ4cWZvtu5zs@{*^M(>)v)77lDaNY+}^*w9R{;j+=S`{X>zL8vU}%_>UbwYXL?z ziqaz;nSD<mJamiQA&~+SA4S=@kuMzI_m^|HWWAD{7aT%e;wP%74l~ma4q|bTbE0LO zBZn?ds2dv2$w4r-AMCF>Ke{K=n*3C45s27Q0v>J@%)RxW4UgpEfcIz}$UvjtPSCmb zkT1Q9s;4hRTM(TIX?`<Q<0;j15B42d^)otY5zbbTDQ0)~LPzq^LvJB0z`fdr{6$p< zWqsQ(%J1d5Q=XfROq|>K^xN{$`#4_qHz%3s@whMcjXG^W^=;;%jJ&pgOdl49NVp0* z<Xp;W`+uxc1)Ykm^SO#@1v+V_x=Nq{bt!bTaOJJVo>9&gE&|65jSj?U*>AQcqE)7Q zWBf81+%0}!_7}axcNsFatUaV`tsDRg5L~^Pc1~0hx-(Xir^BH-5Od>Q9MI!gUgI6) zG&}0$(?Q=X60&El`I-@)B^Xsl5=c)6uM3b*rgsFH!LMd#NH~-2^?eJczX<0#o-5<2 zgy@s$o?9HGMztR*`KcefhqHyh>Xy0;oW>*UAz@-|9`H(1mTJlPONHJ)hvJlUun9U> zi}FYI35CzZQLbevDN6Z?C7+p>A!6&#p~ho>i(=>cgjC4rkO<tupeKP+2_PzywjZX$ zO7NLo+vm{-xa=50HU8`D6>8VBZ2RhdW!n*UN4!esf1q!^Q*&RpRM~3l$J#~pkDgfg zAd)9dVW!&8WqrJT;GD9x<}gC!0FUI|n?hsPA5usd;vC_(sT1O5b;iZt10Fv&+}Eo3 zZt;(*C5jigS2#uf=`Y>XG@P#cq@-oHaL0~)W4u$(1iL<A8cv11%*^}Qb?RWhES!(4 z<snHZM8H3iTNNYMg?qCM?oRbcO2LT-ntv;&rCP_1_oopPbjWHDYHFNtSxioKWDd`o zt}~Iuo+W>w<B67-db}9`kwl7a6*LBzFc8uemZkOhLA;-t=~z`oIF4qvzcYV}Vm^%= ze{tEaBd$aapiqL=FH_8WERwfhZ`2Y7u1}%%lcuEG_JR09^3<+d1bITxd>2Iu3|3<$ z_);#ZMwV+I1K<H6yBrF+Ee#9_sYf0=4|3IQq;*JO&lfrL2w-w{owcWX*Y6jh$Prd{ z1juQWw!e-lz#6GYP(ueC%}&jv8r=;jamK7~JN22+z*L`}`UY49Y|ad2h@je<W~gnd zR1~}c<E=Hn76How;@6r-s+#1@<ZJ<-Kd-vcZyv2dG^jGRRUWzFoXfp(>Tdv3t<m<W z;nn;H2Z|8fBPX)6em&^?=?#<%V2kJPCA}!VbT9%{kgR}F{UBzlZJ479U{D;_1OY7( zl5FCd+W#yXW@j^sxRq%vaV1KV+4aS*2=K>zA$tL^vLizF2%DV=R@4+oiD<xDi6Ty# z?3@7T*<XQ<5LgQ9LXVMRyv}QXGZIe3B|n@v*Q!$iDd<aB^BM5_=%tGnr0d;%gPXKF z5m#>sh(0G^kd07MlY%w3Q&pg+9JW9zl0Au@$UX#B;vKbB!Tb`zBMl*F^WphR&4ZMR zMkyVQ;dfUF?1E<A5ms{Di(~!)3x=|E>H*Us3Pw^uRBRlCazI0%LELbP)+^BtudKrM z38aZg9q9F16}d}H5;e+KbN)0BC}T2Dw;p5;%8r|C%V2VXJbhNSD&(PU3Q@3x&>0&E z=L6IX0#se(vQw8#C_P84`O;Bwm^>_s9{DPt67f)b2|kcAd5#uk8`|M9`u>SXgi)i} zfTZSaQ|;dVsaqtA-+K25JB^Pk;1`|8{(%o(+iZ|U4O-l_%t0EN4%E!CAkS_P=Uq&g zh-)51+e5NhffwNaZc5A<*TyoHXe&V8a0&w#NzDY|H0OKZL<X(|MW;}kB#O<)Ou!$* z&U$65%x4lJNajg&cZL$sniF7HQrG!nt4uK{(EwNW)EKS9hSPet++E-k{3*`FwdibV ziqhr_+MApiEfymoa4q17ggrOt`6JU{9%4b1ljbp=Jzs1I4(GA+NH!x^Tb|`z$brJb z6gldFc<gUZcnH)DvZ!HA5x=_N4SG_Vgch&A*rTuY<V}%a8qg}U83dgmLu3USStK&* z9h$HR>L$7ZNz!v4{&x0W6%Qf>fSHzKuQwTFM+tfxoYOS!{bLpA?OF@(Fx?CK@k(I2 z^-j&j-$<{gi2g}w1)W_Tx$40_oU&9PPx)w^`2#_~g07lU=wb*Sbm8~aMLS}%pB!J& zDNT77aAUH)_~Q6h*V#g&p0C@nIeSy*8Rh_|5V-`3Tm0WshBV&U2{~E*6;m6>p-)c8 zThDI4F+=@h``wE()Uo4dIM9%cU-@bgK_j1Boc_;m&n)RzEI{AwGUREUnUUice*E^l z<g+9eG8IXH+E-0;HBV=Uw`Yg*?L2T<pq|@Yzua6XU83^2pa)vIBKVT4I<+@oRYO;b z>U~X!gwIT>yQ@PliIJa9j$M9c$B&2J^40kTfavXr9w-4>Kg5!Aw1Sqz+$;7x9yRo0 zEa}zQ@OA$DTy|4NJC3s{zG3)=%`5>gi7uO`Zah2pL8e()6^Ry0(e%&pxo1b6*cAyf zwp9@mda$x-%NI(kFWv`yJD|Ioh9((>q*y^dDHtUOARl4H_+@QrQ#OC<)Gd{v`9K@@ z%$MGU4)oZQ?bT8XI22$(`+#w*vfl!7I@#rvw^j+jUz3#f_Oe{&G&1k~a$7Kscpeq4 zm!{^Slnp~eFdTGV2K2{)-z2Ed<;hkL)Z=)9O(!JyaC?a=oPQWFpT{&<xaMIk0k7a- z$QpMYMEJ{bH#O2EYCAZZJguXd#IC=OUwV&7Ko~$I1+?xF1ZNN~5Rq{+4wnqx0M|3{ zRfcdYf?JLJWD>G9tDWDeo%<ob#HmvA(5?VJI<)3~$0S{d#)gn5-z;_bsQvQv`;a6Z zC^x8GLGBdjeq+|1c@hG{!~_Q+n1>SQ8I({_P$hb71$?_EB%JQDVQ(s+g4B@?$5<98 z6R$-%bf>(epv%~bY9;$OH@~gQ+Qsf5WDVq1sky|$MIs#oUy={`6nZJA2$7;}b^R9e z?mRR<E<?HwjbOBFwNpp7&E1L&L(>^hxCs}>WuoqjOgt8SD`7Sg_=Owi;SwrbD^H5R z|KV~DaG+z+Jz9Pdc{Ng`X`frx0?8xVjC2HfAwX|S^LJk*m|naFC)<IBbCR*>TPp!# zb%gxK!Ynt)pz6q?h*~mG$~ZHQ@yu=z3Xb%gz@34RYOJ;byeohXGExnLo)ON1aCG@{ zEBZ3zKFd;~ZeUNvP&f#PMTI4+wo(t-#oQ0B2*oQbm#YHb1AJgxJOHryoKB#3RUyW7 zrneAvXjgimfk{Y1iwk=@$U~JVO$7@s4k>9uG8IDztw2UgjYYvFr+_ePjpJ@wlY||J z(S+}|2Z&L|Z3{(?IuxYxte><zG)E)fOy_x}54#Dq2>kr;#c<=O90KkYqYDcso;+sS z!X^DO)*1mG<mxW)Q}1UJu6xZ;?=+BAHO072(?#sL;dvw+h)O;>=qZ_8hW$AXHtfD` zGcbqar%Av3=H6V6pSqzumHi?HBx1>QrRQox6|h()#EwjYmQeyg^#+EjMZ8Sr^r>&W z7}UmuSP_C1i0ri)3cd$fb=(Jp&Yj<XIs>B54E5Hq=5{ueqs?A<8n=M~hlPV2rpgo| zKi0o=eGX4?6iNbTB&c{!8*V`G8KZXx>_A!khpyeCbqkOw1oa}`$)i}`bqg!Bjuw)q zq(h*e*Lmf!=6{|P1z`)<d1U}6?tU-eiShWKvs*VzSnl)CDivsLXh()rsWwIK%VUcV z#y4Md<W!(nbtM)c-&QJH&x}1hUH?93VnZEI@dNV0+@0gzAMR4SLOR;ac!%Q|%-p%= zuf9s};K|fH=qZJ4O|^(Ev4ZYhTIGl8cx>%JkysoOefZGn59Vg6eX^D<&uX56rfeHX zyi{ls?Krfx^Z2FfA`^4EYEDOrie3u{18Q_2E~J=%Qb&s>%e!dzzN#IffvYnVFRycF z_I@z6lgDCqom@M<Z9!!}+y`K2Zz9Ns!zb1}we_%gr4^qXp^8Gd9CvH*%ZD|E;Li;r z_&zFH=BBYv9(>=Ga;U3w-vw9VakYak`rEfnoCi1Md%b^Nsu&%GgCz+$>*Vl<pR0!r z;Qp|gLa5&)>rPxNeyzOhj0m@D)WR;)8qxM?iAu!H1KG60d>@r_r4^Zs1B!l77A1i9 zBk{{+J~=<kgTQ-WbEI1_xhaaTsF%?o%YFgS>Ob|R0CYOjpk@;~JkGDmbJ@bwBZ7MQ zeT9g2mz{wVAT5!^9M<zC^+#HjNPg{)e2c`PZiBjtATLMA6qzJx#2>I6ym<KzBr|eY z_Cj+Rswmv}5a11zJ@BZ=ta{s<YS;PG+9otY5FA#X&Ja(b-gI4MQ`zv1vT)>pd=I+N z@A!H5$wk^*#|oVjP`;pcLvWCq&-|kEV@Alb5U$DdJL}j$O>*=M_1T%eQS4vz;64pW zgJ%ENci@VinA=TE6#`gPlJ-RYG7bKyvlxdP*JeDC^XacPuJU^pAbPYP->4{Lvs<Qr ziB#UZbc{a+9A!)O&-wV*CHULkVi1g4BuenIppzcT^7)_ya%>i76f%xp6DSg>5^+`F zb+<BbBGm;wCP7`b=-Ijsyf5rT>=&`LooFF9GS3SQkhGj1uJaz_q48U^E|0ZfEov(b zDr66PTCC*QRPss?PaXkaT7VG2<Nn(Z91(KXp}5DSW3H4;Q4<o+$Hh&t-Ks>C9gCpl ztRGmOQM4oWx@Af%75F;@jCe8=1&wxIummm5=~Pd(AH&uu=(-K;*)iQ#gOZi#05IW{ zNG*)f^I$_NRX|I&4MBbkiyEZh;fRL5a!4dr`GiR5DRfO^)(obvo>I*32k{aoP07>w zLze&~w>?@4><%hzosR{DjXxHI0>4@8d|V<;l<uaI)vUx;fJiY*&82w3ffyZ7Yq2L2 zBBBq(ia2>hEHKDHe_4a@;i7=zg9h9d#lYZ&Y?f{-cu2R5O-1IP3ZfvC0KG&j<{1zN z$oYu)p$Aa5t&mu_78;~VUkkLNV{}*7F+PHknYwmbr)iVr@*Qys!UREaKnQ5I?s9cc z5_RpDhz|^?n9N)XBFKK$0!<Fa66O}t!B$?qf^pbz2tmm6Rjbj15Eu`Z4b=;JQK$=+ zk8(!cbA9e*EbiC1clvn2PM?tIb8hybc%D<!cLV$*zlc|WqY|ec0Xaemz4d`uw*Anj zhQ-`w9IQQY86uMy+mS&R^77HQ;$t#xO|FPse?j^cNAm!1Hy{jLCR_T;MI5!Gg;K2^ zRNRbS>N1LWXz^+-L7wh(4(K3U&oowX;lL<?i2x1Ns=F@3<I@K7fULOV9nAp)x_)9c zJLYyT7{9{0{SFY>+nxKN^8&ffP$`uLwKX%+VW)Ty7<cNpC9b68Bb#Iuva4j_kE^Zb z+!sng#a-;UOBlkM|623nd{}K7Ns;{Pt$)9u1Do+akib`&9zRM)_u13Ls0h4*;cuI$ zZ<-WzH|&3KG8iMP4|=xGMWCanwY2BT8zq_Q2DhSaEZe)MUI6L}HZGTrTb+PD$^-0C z2RScgZaysw&9sCRZxP@lAtsM!dR(7=O&l8Q=F%eUi?=I@irwt2x9NWflN`7~lu<1& zYhqI;`wy5xc=9%J?`B`?Crg%!Lx5Yzo6*xfFvHn!T;olWd}5#w5{BS1;uD>9B*KT_ zCgaT)Bjymsw^xiJq9~CKhodAE@|gW?GWoM0E7V0S<46*DkKTpW5`_bk(3uNW4It83 z3KECK&N<;(A<A5YvKb^8*kRXx_@hRGR~uL#dn(%OAnLIA;uTa>3;H-Ds^KUD{D%m8 zA_hta6|mWnM1^vU?Mc?dI|(teg_6w|95WoTrdJd?G@;HJN*z|}hI+_e%W>%->dg2t zn6JDWI5yZY7!<zB+D3sQT<vBhe~BPS7q7hurQre_aTq6?s1$+3pQuV^Kd$mzJ%FRu zsU~bx7gS87hAh9&q!uXL$v~8DxL~Z%yR)zH1O+KJofu%k=F?qnnn&UWrzaxQQQZJ0 z9abv@yvzM~H?v>92M@TR+2YipydHDngx-p9w;L$XX(mYl?@M63uiV?9@sH#eVf|g* z>XDbOdyTU$kn#Y{=wC8ms071D8uH#a#y)rJ_b_fAf)2^n;9#4W&xggKNI2;Hpa5D? zQ&d?1rU9vAgzlYqc)17Q9-<3$as<3dYsF!uE(61iY2C_4d<-ypI2R<Q2#tb$=+#{G zIBv4RSO(gLcx&8HEQU2Bs*Gwv>wwBFA>J!uxVjbb89p%{rC|qj7TZt^ygB^ew`byE zw|NDCyd@RHje%)Ab=iB2mZ!SD0p$aF3Z4LzLK@;JL>J_tJNdSy0LCO^Ky)@nEd*Vz z<*=Vr@=>pB1$#sSXd)oDiZ&-Pdh9POxnt<VvB7T*&bgMI=C{8G*{-_goi)pFO~+Nq zu2nT9TBUYZ7Ge0$Uq1F{IW!f}sOxk3RXc~uo;%^CV5+P4Rtk<e(KASdQw8ykty{l8 zeiA8rtprY3w;gDxENYQ-^r-VPL}0j)EbS%4Z7d<awT({H5OUg31`3g@;6vyPNG$?o zHPFuZhv8+$GCGF@4Ku>6oQgv&E5&N@3)lH-oR%uOyK+jBA&M1RgFFwSpwU)!1L`r; zSIKiA##SN{6_QL3RJKf^U%rlaTTH~Kv~>&3LwIXdKI6YUAAZ+DaV1xV_f1$gmt)pX z4*|Sx1pj~C14dcINKXfSz@Nsd!q9k{k|_3_{AY=qO^l`BxB=jOm0AlDmt+ldU}n>j z@lWi)0qREBcrt{EjTtfP0t(Mg@9DMsT>80jA9RLR`fg3gtL7B5;dGPlcqYqHH!H1E zSfhiq#y@K<_krQ*Gu2-l|B_>eAYy+LP3wuVx@_${^+<4qy+t!6S&?cUINdR{GbLTm zfx~I2`^Yn`=Am(Pj?w3)l0&T-v69ThM+<*wdO`V$Y=cNpx14{_InApnbZq$dEm&+b zV7btT(?{4l@m~u0xBJ>ovAadt+DhA@$8YF(hzFwZRg49fs&Ai<<QFn*O`~be<O*?+ z?V9=K`@}Roh7_Ce@v(boz50l8)|xetA%-0(G3&iY_g`;xEJ1n-MXLLP$tY3Bf~hr+ z!GOcw+L^UxA`fcxDN#<~%L_iA=)3<n#^#W-juJ;SJ*nPHs;Vl3@s}L<rBsRXo7Wff zchj1`Y>M{j(fM}=q+~WvhKA8$;arsn%#x(~K-W79hHw$Ogp7|rpLjF0gj9p_0;U-x z0uZR|@^_qA0yDTM=3m5%OM4J5=%C74L$2m!U;QVf4|c2-A0%PA%bC+?*sXat_;z%A zsU+kCEkL4qTH=K7()vI9Av;RSOOGx#GTrN`WX%yhnhs7QIdCx>%64ei+;R|@xq|Mx z?scd-9i`qc0C@2ELiCwGE=Hb+82NKEf*ouo7y?7hwzS3UqR^E@oZ8Ddc;wQJ=PV%# znAzX~Xm6^U-n*CM{NoK9zQZD#l&+-gBgMEUp=%(Ia1yqH$>bki9;1I~O3aY#*K%Ay zch8lq^;N*nL8>j())JMtSBUgI2nYG7;4<IBEr%Lu8;YFcl=q^0h!xR=kh5THPuG** zRVgUr;F&j>MX>1OP1J?4iQ+(Ok$~OZ4JSKHMwah{dre~YeDo!r@0Bz@=!AYEvQaN^ z+A3_MBVlWBk>wl!lrQ3x5aVFlB`!4>iNHY&gSNy1m?RnCS?nz`@#NuLAGIqbKhi4$ zs9+6OCWpy*TfZ8JfMhYyHS^$5Ae$ObtXc;)!c#TitUWbu!{x*Z@%dV}rAB1l;y%$J z>5--tw_363z<-8l7<fWkE8$?h0apvLx{D0THnX8r2G)7qLVO0~#FA!3KjF;r4mab_ z2PDCdZont{<)I|MR6MU=ehmyIETR8H)<}nes3~w?mHoH{2&|>ZqJd#VthR@dR{b)P zg^+l{K!R-+I&56f?iXZgzf6xe=E00oIe-t&>jYvY(E=6BB!uf5Ej(T1@9VM?kp#Al zKp>1pfK?ei*17oKfnqqonTcy~(j(P>3x*h+4=EJGQGgrvdS;9#?zw@!AFO}}kI?}4 z;B_?x;PBza#Yw~vgP@M9z~zNW6o?A+Gm=<|dZMFEA)nljxJ`t23D-jwKA)N(O85N& zKMa4MBE^Drhvk{#?146HjK>}hfR3qxWf2hC3P+2Zv?_-dlM98<krpWADIn8gSsY2& z*X4tr6-5pW^mT>ww^B14#h(&b1Szl85`-P<MG;+r_b2H1FG%iBF0I5?z>G|X$XBu~ z{FRv=eow)45oCdSbco<4b9*WHFPKRwUuYJYRsAX&;gJx^p09wE^R_T&pHT}$^-ILk zu3Z)ZX}QYNZ$9-P2Jjn_#-rD0-#bEw{=6`LhWhn&p+V^P-ha!W&+D^oFM@Uj6Gaxn zV=(zaZHU_<f=&*ST&Ulk_`VT7acZ|paK_|evh5#8hwU4x1aPggceWA(b3b4#`)m;} z^DU$^f@b-M6UdGw7Sb;Pr5IPXq1JW4ulhSqoxlx`l;!Yq_Rdg?@bv+QoXaNM`e`jk zv3dZ1*B72aTu)8bggHrKpQ{-iaCQ448JyfX=$HMOa8-urJWTyx#AV=|X`p)m3&s;G z(pjU9_@-eL2!H;o?juNxVPaAxNuJffR46f{XAruh9oy7?4E{(2Em*M|M)HX=hzll> zl_<4ymOzpKX1#?-Sw5)5_cWgpJkcvM<$z_w;jYg{7_^4d5<o+QA$v!-5z@OA{%P=_ zNn5`sz#JBTw3N6%c)&{K)(nI++T$Gv#}&&gS{{RZgb{#5geLs)%TUeRKrV-ZEOWJd z#>w&mOb(c#LdpEiDbdvB0W)S9xCA*N9p&jk0b|0)YAzz@#>Y0~Aoe|6SqC_d9&N02 zln%8L{?A$K>RCIFs5C=pbjMp#kV}4d4uuDKhVv}<nf~8EG=tZ1KEbml6O<3a3(j<i z!kI$vQDQE!23LC+ZAzHFFkS$~aK9@RFsf?pjj4l}zCi7uyTPUc45P6_I4p$@1m{qc zH=JR(c-nbvtMe$@^xOSNR09<_OGwUSe~Gh0PlrUo`X#wOS5$Hv0EEmNbyzdv9_SrE z<stDoCuGNP=0~TP)5ubR0g0$-aB?B%7_WN~l^B^1KT)OMz*b=?w`egpaSTAPoT%pM zT4YU)RZxHW18|B^n2@88dY37X&q%@`<T)}SIpCIHAsHRWfQn*i4`1tow}vFqB>H9? z#8|M7d`yX5It^o}`%h>l>jlSnm@pxZN4aCdBN-ds$8kAjM|sM7-w=)YkT7sNapSs- zLNDY$zj2*+5qlo%jwL}k!sf3aQJ3b-;^&e12dw>&x-dqI=?}1@xUK^O_lQmDLR&e| zD~28_6gQ&;(|uM3At6Cg(I}!ROW)Dn<U%iXgU#7uNh1I^iFY=7`WSn%&#E5oziqS? z3@k#-jXi(R@#BV`rBDGchM@|gMxP}xy6qVE5R?d>B?u`%-F*_Dw{EeHt&R&wEd-Z} znI&`&xY8g`q}b}J7a{6$Ex~`iaotP(@2x~+F`n4&-cC@yBXcQoQ2)#yk4p!LKE{JM z=0V%xBZNZ`cq5DR`2<v_;`#lGVt8~gmqgkWDLM`iswf04Tm?#uSr6|sz$_{v1VONy zo@?7<ZPMMGVIr00&bw<KB;;!{agBOzSvEsmS)V>uJcqcRI_NOuJj=D}xERP7R7xiL zHfL>xRZ#?aJ)hbPE3q>}eICh*l4NY@h1@Dpz-R7*sGDf7=PaB)mGh{>@qlTKqBV(D z;z5^#wF>z1w?_gx63;1jbfgf=YHy^g#Z=o9ofCle+1Whu(!W()^(*y#zsvD?w_eXF zzw+D5ocqtur$<UT-NjA2!iMLCmN;H5#SGVZX)7P3e6dP&FO}ef^@s8cwk=iO3zOul zl1GOW$)c?W(DjOsJ>CHM;cSs@7z#M86Xbsnaym>T0Le3WWI%y=zK9Px+RjuiwZI+g zN5)bB-C8Jv^CR(d(Ic8)7pvRMHv}ze_OVu+eIsGg>TLPmJXrv`>7xck#J$kQl{8G~ zK!g(5wW^n_lHgDt&s_ZXj(w$Ww?V-m%c*C(KE$a|Lc6S^Cw5ED-cGrw2!H-Ywuhfm zFOcqp_ZG=#b7D@%q1DcY1iVB1vm%HO!C(kr-XcEL<BGU;5!>YEuOd=D!_e7emZ1Ds z9AUG*6)h|g<9Cs4=k2OhRNk?{F-pu#1#8YsJV+A4kWljZ{Ln^6B{WoGclfrTr5md8 zp}uMGF1M1Z#RBXg5@S8%pK<6%^>|pV8k24PlQGt)h@Uvt!hjU@1U_e==mPYqdi(o# zg=4G2VXi`IsZ}&3w~sb{2S=4PYhvL0XG-gDkgRIaTbTijJ8oK^y$K#kVyNq!j}{zI zsE3T@T{!g_K5{biF<<Sr{#ut73DuDr2Z^HKop6D?7ecUR-6E-(B$g9GlL+HbqHVN9 zfVf17iGe=MhU9W~@e4U)L4^NA)^3d^G$5-3Mj19>$q0x<Meh(hemkWD7DA#t4H3vO z`3|hTTj6^|(WYR^NgpFyCgw?Z2P7lJaf6>4EFqdMn+o{B6U;j504WL)WNTF^C{G{* ztoYQm%u2mwtr%7UEH>?WN_gB%>JoTH&;%RZ$~v&jzSeTlb9QRQE?Ay$9w*wxllkx{ zBHcm-$8o0*V}e6R51_KZ77vU07&H#T2us|+{#u0^`j%^D`6j?JWFSz0CK2=~Vityz znedr1i4#p~tOPY==mhS8_|v}+vS^UTv_VAengjtf2!5y$s*D+qWak7LAQ(3QN||bc zm5&$D=#Y`AmpfZvRU-P9(1%zfmc4?ob{VNS5Fii^&?{%=fBOx|D!KEVE!l3e5RmK$ z;I}My!FFenphbmKgz^wPpLZK+3XLxi%#O`o?tlQdi2KeL2DFfo!aA(voy~J4T&UTA zXKsCl+~Y`@C<{~tu4ee3ge7UA+Q}imz)ILL*Y2=`!>cjCIR^DY2xtrS4~i~P{(vi! z+sYY#u_0UCSUgYA+z$MJR4fq|IhskcTMbMHhju=)uY1~KMG%BStbqp%tysv8=*6zx zj|t5<EG~Tb-YOFXXCWL}ux&AomA%YL*KXK<5Ik{n>wqIB^L72Q)gZ(yyb68R0J&+X z0~lR^?3#{J%<WsR))4!xYFDSbLq?Sa`Ro(gMoKMg{EsgV%<uth=+57VEkHd|`*HRt zK|zsGq2m$&<B-Egi4cntav2d30|F6$6?-Pj^??8nClAgf>dI%tCBns6Yj-9ES&Dvd zoGcX7;;?AdJb;Eme~MrziG%D|iE9U$+|^_XU(&C8rpZt4if}6yOUku8mUF}kx==XU z+m!jBO+6HI>&ClDIfXxbs}MUhI0Iw_vjpG2VH>{#nNaapqGBsP1W}sQ_%8VI#P6og z?F$68M`B8qA>49jWRY~t-B%nZs_pTtV;8R#>QN^le#A0o-7a41h__>d9vOp_EMUdj zLAJ})*GH~!;Z4PAgDe_CKa_W(%XbloK2`q{+l7EYc&`cexu1+JgeYu*_3H9ZRlLI^ zt!me9tz91mP#}iEpcQ8xL*&L?%v%_!O#N@@x?&l9F<XO0RHbAs-K%?AIyL}GPLg*I zy*>Ph$~_?35rD`e-xgeJIt`W!$BpFVs7c5J*z4t_Xg~ATLt|){uK0ts^R=lkFgN!6 z0!OsCm#K!u$(HJT93N`DLfiE#*)KpWHSqJWYsl|J;FZzcxTO_jw&dnhQ`$U|;_&?! zCGV4*=TifNaWCjKh_n6+Re#eyjidpBC>xTN*6*{|*wiABMj3AbbYe|T*X(5%%`+S! zlYe!f9wlmNh5Sd5Q*AD-6Ns@KTI0H283_WQff4!u8Lw6o{|`!t2G-KPDJ}bn`@)if zl-pg#t+|5-w7_RcbQ{QjaoFm+#Li@9T^SGdl5RB~@^`%~XBTo4%&{;&zM4C-w#)6? zMXLWIj(HQ3lBPGF4mi!fovq_3fNALiTS5A#;A#M=FQ7Pg>azB&0+t5Eg=3@gZf8l8 z8jLrLyZy>$!UX}8-pKk%R1M1&!JLUhpY3UacNaqZ$BXw@0?0^suzz4mJW)Loq<FI* z%m4|6_B!VNE*`}5J8_Hl?o5URGX^!9_{+9Env%6&hXrZHoSDCGkNW`zY=SMF9jyzW zOkUZBRt%{QIpQs$AB+em4i6+u4Z?SVsR4waEkEbf{H2(-0104uUdi4x-&JDBy@S3) z`frkMzeyaq+a&u9GpgWfF&6NCaOoH5Y@unM*w6eDu<O5_bc}v1xZ(~GwC<NZxggK^ ziY$CpA7TW~@w!_D1o40O)YX?Zi%VeBsFk~tB((*Zzoov2p`sF@8T2z_uO~wY?D=X1 z+0#H_pa{cQr_922o-sTo@bU9VV4H$GxUy<Vf!{v%yxf-NYN5!$*X~6^Q;aDFF#|ac zwV)G`frdeq6p%y(><-A`AUtcJU`M{R!UZdJ0X`qQjQ|&}hlT6#5u9vIzR>@1a6hoW z!75Zn?u`Zyn`0>c(wqIb5&*m`Du3(tV(7B41*dX=*N?i7D;e<bjl<=XF8ICuh+#)R zO39=qN^&??Ub#Mp?$WJSH=g{63Z_HbVEt512iMHOFme`9nY^tkc%7jB=7WKwqZ2O= z8V<WlJ~6+=C%n)p-Mv*;H&kE!WI)K_4X&5mBPw3%D~Y@Zy1jH^;M3dArI+ZTGN9C_ z*8KM73PI8y>r@^bSnQ5S0IZWnVee|h5)WM$k993VE_1+Pm$XB-YYlX0u-;Xk6@{Bc z#;&@%r!3laPw-AZ`Hgg}?Ua1SP0jcSF)V(cBOe`*HPyNDo1W12i+z8#S((4rDqY#^ zPM6w@TypVN^SeoryvZrfy-VW{({t|p3}v{;VG}fi;6eIptlmSvXUf-~TKk-|Wq(=* z|MnvLg83b-NA$>bj?}_L>4%Qx!(W&_e(3A+JGE1NdmN8{IwkMjcl()JmCo0u3r<eg z&+BJ(<9=3*mhi{;X8QhD3X#9Wc<YnDcVyE{srKaX1=1k(H>p;``3b~IaD`>r{%@=e zU+w$x?Co;PzwP@9155GP0F%^mUz#EZ@d%ihWobI`Al7H`!TLv@d)dZosE51A$_dQz z$$9R}OoZ@%zN>F)0QK@R_#L#Nhk)yPLFUwj<E9(wYN6nZ#}934%y8!~l6y?Crd@)* z-}v`-)lBabHZ>exJxb_B434ytIUwoCe*|;NZT|)30K9@OxuiY&ZyU}8jD|apq3ZTR zVMAucS$qEO*?BPMFYP=d(62ohTB;DyW{!<SZ}sk<0%F5A+E|8IYX!sNi;{OSl%x`a zL}>$KOPJN4>W?6^p(bHw1-w|oGd`Hi?gz1p3GtHQ<k#z6J)6<%;%H>O5x%yI_dd!o z2$LLp=Obr!ZB@s@mk)EH#g+8#(|tvOT_2(huYf@Sb+4cko+z-G(6&%9Wp%C$I%I>0 z?qb=aj?$;=->!yyW?dwLLBa&(1_#kmZ~yr2!hobt`wEGhcqKVv1(rt(W~hMk5F5z% zdTw>np0otRAw-Ai(xLPP@$;waMYLpNy{jMfNPs&<AVN2U44nB`BwK^Ta8tD93O<LJ zdSHSWYdwVy0T#;9eq3f2aJDXpvKUl2Y=pd1Wx+uK5*iXhYG9m-2?Z1ff&!V8AzHT( z&@Tfph`bELq@=4~6NIzJ>2v+kxfl{1xmN_Lu?%Bk?5n7USY>?#fFVq%ZF2VZ^*K(` z2<K}-i?|Hxk!3T~eq=CSz78VrDB62UNQ8KyAK?=K<pS(fGFb@~X+BT-gkA)9>!uG& zP{L&qlwjJaLl{C(anlM|fc{EEbsOxUFh$WfQN&TUUP4jF^f3IlDoh8W1R1{q&ML7P zAf=PRA(wG6)>1G?{DP~=)B>vfI_!-CQ&)bzW0-iSC4s)EX!XK%-k75SqOIh(lGaAy zc{QoApnVB(*K-|470k^IZR`saTgk``03}j54O7EH8I5U<;{}3rTUbuZ(!=Nh;*{8U z)Jztj*gjY21@~AHX&YqokuJ$hb{%$wmO!IZ5C!o_>(`4h9Pt}&!b(O%5oowxGU|<R zE}las;)hNEAp$rbFm3&q!F(sV3xb{-$sR<*M%@FXop8e>1m)c0%(s<*5P|(@bn_g6 z{@G}_tVK9ej<gu9HR!fO@2Xnoo%egnM(<t<JkOdze}`dWfszAo!W$m9h^f9!9AQbp zoew07NSk#Uk{E6-JD<|=%!7S_zzx8p1jT_LoKz!lZe)6Z&Fak4@$$ijz<uo=>;Yt^ zpbg_8K5&ghz+CA@TH+&^Agz_<F5#(C3Iusz%?M3}=g$a$H;m0}BHYg;HzllFOk$su z(MTRhJQbc)F#us>nVhY`(_@fTtDtWlhQfd+%wWxnv|Ad@$mm#|K~MNgWyfd<A3h8b z+{ZzE4!J#To!1MtOr&-Y@XnJEKrwLTUST17K9>*Uc$l0RdQcN<GWC-gF{qJPuV>bB z@Fa^t!`Z~ni#pzeGo=A3UxMqz2{Z>v9{Ml~M5D`i=$#Kaztl2-(YNTH>)vYwET9mK zeMMcD$@44(nlMCQPp5T9{OuGoMidFR=8Z2=-vRN5!=p{}MoCY%0*SqV{-v>nd(k|K zF$SU#s|#QG*@oyKOh9<>E1%0YMMn(~l!iwg9s9Eo+~2VHJX4A%Ibe1Jvk+`6nYG18 z7FsjEf2U|j$f)uadyvsUDe0rt_cYisIJ=9cICu@LJ2jh4yO~R{+ygMysISCgf>^a% z94IdYL#Rp;`GM&o6m9rNd3xyT7_wTd=R0u!9c{9+T5mXs$gn}?TkxI^IBSc;KLT~{ zx=;ybALO2!yT^UXYJoAy(>x|Kr|)H7Hb6SV(c2-6Zwb0)+GrMmepZN@#Au@n-ihMl zK~WPa>MJl`T{563fTNAXe6+6?Wa{L#V#R!}8aPd4yy4IZzEe-NM}KD`ihGZat-*BR zDE0>95<*u?)9d-f3Gy~+NigqKAOV0Tof?b`d{D4zYp_=g8BvZmiTs6A34jQQuje;R zV;$m~<k-#D_3rMi{p{x%)@XY76tUyy6rx!*pV1-Y+$c6)?COR$;9A57kN+Lq51zw8 z1}V~nw|5e1L626&*fkak!wIIFNm~OeE>Au~y|&f-$xq5n$Odk@S&zwt<tc=09XcW2 zTZ9OSNA0q=EM1Q$oUCq-$PE&e6KLCm_jqeK>fSB__y^!mt2vA843i`lrbKTu5BkQw z{0G95B6R9DIzmAm;^Vn`vN<kCB_A%3%Lex0htk;<2m3L1B*CSudH&Oy)~j@bxnCCD z5BJR;FGUU++airyd&vxSI~YWW4Uo{EGu&U<KSOPQ6T~XU8OZDbuA=NQbnC;z(AQQE z%3ZG$B0&BTj9O=%Sv+NDhII5J>YP8e@k%VbmiDw5f`Q3AN5U(e@Q9Tl(^GGeW**N~ z!P`OqhhGSl!R=f<Ny;EJ)xfoMZ(J^t%WJr@HpMY+@k64($77HR9tQFIQ4k(xl`qMR zaX(~3x_iai=(ErzPk+FJy#f!N68T{~D=Esi0sTH+CffRUZ1HiDckY+*$2*WQQR4>d z@nn%FDXjbkQD8vo80_k|qT8=e>Lw)4W}YJACun16CJJ&Vm)xx#zxw4=gAhtKZo}I; zlG}7naaDqZw{lZgYI{wIYCcbf*imH-?o9gd)8#2J%e@RGIc@G!Fjv6wQZg2p+*x}Y zI}S+_$Kya;z{ei3Q6pk@%{@kA+BzS#DH*Qmo1ZVq(;M|W??1Q|YZj~|6V+P(zCym+ zm`y@i>_`nfxGJ4xzuWc0xc;G|<D}mLEtEB<Jm;xhHE&*edd-K0{R_rI>^>8hxfmc5 z;Z$M*h>$T8yW={tK7DvY0{2J~Jdn=1{)?)s;dmqhd2E*o%^Nv7mq+-&o;}w1%B~XK zl+S{p`1cgjvHO@J=ewK=n465rO*aLvtf{uXdyu<{OynQn+XK6?n!f<fZSU^>E~_T( zQmn{yP@gE*gG|-SL`zXQq<E6WU(aVJ?fq3Eu-y~9vbO9rCTI%-D@J?i-fjO?_}iIi z_{Q#j8ax_B4-B_6Y`CMPs()<po*l+Bjpl<pA9-><QI8LJp$t}&tmS;?V@G%Ke)<6* zkuTVeWLD2+*WVS;^zCd(6>&%wl%-b*xiIieW~|AG2q-fh{MCTlgc4W#(Ydhf3L$SC zy)5bHy1JH-G|>@Vmu1vuLDiS7Ca+{NDlyTVhXc5A&=izY%~&nag&dp)^kx8Z`cOcc za#H{N;Do8-%0w^e_=Ry^-<m}RvHz}-cFFPg%vkq<Gqf!ex(ET334U20S4-5dBN(O0 zYQKD8&vRFMK4DW~(NZ)ir+s-DBCZXjJPYjnZTwG9i-{kS3_%;qaySn{qL9J>^xsuP zt6t~uL^RI4`>|Hlm3Q6mZoJ_|8p$G_lqrl$p^@yR$H2G%WwK_s@m)0zovlIHT0D<K zyniYN?=W-%;~E3RpBhKB1?Rg$ulHe^y4}SPcI$XnY<MY%EaH$K+IAOZ{DKuW*ORNQ zovhg1Pi_{Xb1e3J1b1Ow_TVi*_aQZ4-Xka&?ZqJCS7I$O)WnlRFe;3>0u%sqeeec` zTyZ?#F^R_MC$|&F4J52P;hI1fioOjG&HGFY+1&3l(4^oMCflQtY@HV%q6oP<jOj7w z-4E(gsYiIl4<BWdM4l4#wc$KWON&EF5B7f=Oiv;*^%2yOF@l;p`W2<JdCp_JN`Od3 zE{2HB5Hqv9-goNRa52KG4g6sSN+zZUWnzal2L2FCjGYKz2!46Wim@zSdIuaQ9c&K3 ziILh4pBwwiDQv%uC#yh%0c1vI%zI!T0^b7ZtfA6bp8y8{h|g^G0CX!8Y!YJ9=pR5C z(7vK6TIc1y-_Roewc#X32KwqiJ08Hd8{ph*h0`Aj=tf)|3fqbx4<25Es>e&Wso{tu zV66)C2gL-2)A!YwvL4siHJE}h1BKzW$8rDFmSCSrW<qaeGIIG)mB^1Xo1H)6orp6H z20MvAm5kY0nM6>F`3l05fu1}WWl-VSGMMYN4Qxg>eGGmlN(I9Q9EkHsneT{zreZiL zdP(a5hJq`>Yh33hwhusZYCpCVd?|Ql)#`ro#px0Z-%W$@hHpKe*l<WvNVP7*0Yn%O zYb`bi;2Ux!HoFs;?--s92JNue`wDx;-7Uc5>IZMtNbr1MtkJ<fE+nn_m!bQ?0<dR^ zQ$Lxh<Jp|`o>vBlPKrx9o(Zyn?z+LliE_Sk_!!osroc~5z^(vK8`#3L4bJ)cfkCx? z2)!FQ=7zJP2c|Luo|H!(UNE#X>1#Y(<Nm5}IvvlofOlp~YtHvW+#~n<aP{TVWPPk? z7jV%^KvO7&Sf{iE^)J3xu=S8>%b6d5VN$RyL#0{N+isvLK=Fh#eFSqc??hmZ9xzz# zyil#a-wdXzK92L?Gt3VmRvtFJn0<^MQ5V4#O`1{ibOC4m56U0=&`yyNKt&0@zKp{# zLCAVz#2?5E9gaCkVzMY6W>S0hw;z;kI0^s+nE7^)@;}g=YE}<Ey5(zykHd-u=#`(x zbHY+dS_mZ$!Di8KL&O^ymvQha9Hk^{44m*f@y~H|)Wl$mRz`Lciod&MH|i3TozE$; z&S*ALQLq1bRl-9j(xrnjQg*mbHXMbo(Q*_!mV+^|G8o^gS;;QOC<mg>KVJEtTNyM= zK@MwV#CtDmp2a29lSfyS$}mHy2MY`!5`C9HzSXHV_eLKU`x0aoo!#d17a%AeG@`H) zGn}&adQ0DQR0ytAgS*E}(%wQAx(^ztA@c`=*D)&PXyMCN(>H0C^K7_stJ(?{|8sk_ zS(3&ZGurZPe`!58*d7cs2zi!*1gN`Y4_pauS66w#0DWf*comFWSxWA=BQ2~MHCh5b zhOHBmn&e4;$N}AWl2?3@FbB=#$(O4Hb<2nqO<lX4$f)xn1ZBjmnJj%w#D}(>Cup(k zyGWjp5-k|R9HmXP<~h+lGIiXqh)DV3Ooh|>=?DP}R!orsP;SVt+10L2{032S6LhC+ zll0$UGf}=8Z-G!_Yy;wa<&DytD}c*jdNAu<Emdnzr;+qNc56<IK4)q>DbB=s5E5JW zvGlo{+<HQwCuZrH>Po^V;2|IBU5bF@v0$VlJZ2AE9-47d3CFWI$l%cea=aMCx+;rb z6oV<dVbXZxxJE`2CvU+{aZeYTF8}!AInWYY=)>~6UladZEfS(7NY2*5PIo2prTNI( z0JbP(6W5Lb%;Ceku5T7{#)3gfR2q;v6fpp~$Z+fCB0rMDN%vRb(Gp1gFeX?bl9af1 z2c*JpfCslOF?MFeO%TqjYx{fzY*9NZFz*;bbf_!<qtNB#jo0m73srlacOl-mHCn;+ zbY^Vb?iuc^-vNzC^lGl`ch%_X@D35T%41LHB)k_lFt0!<J}1G0bd$d|7qlpb_bv}d zfT<Eie~<O4oj4Pn^WsPw9)wUS$%LzTx%Vl_an&mLk=hh5PZOZ;m>j6DDOmG~Lh_l& z3!4@Fk1wmlcy8DO%<RN7j~`d9?jX-2dt?XBmxSZIaOiW#*PMfvCBY2ce8gI?FSaA) zqPo?LehG62=p%hXsu%vuSL*RJG1I@Y{HKr(r2S|4Fo6GGES-Bm)MfVn2gST?YvOGy zVA>euqT)BKR2muCuyIg#xG8F&mAGV9211G=Ls)rf8)5*7Tp5zPAmnXRG|9AZz#Ij{ zbX6?wm>>hlWti#rdZyn$yP7cbxjfHv&Uv5r`+f8^<trb(o45{604cZHD<}49&4myA z9(O<Ay{e-24L}}hZDqusy|dq&^G5b7E7r#2TZM0JjcyUCU>)v4CZD#-<AvG=2r@J* z;^XY2jl9>&R2H+z+7kKx=Cz$`4;*|(bLl}ajvjL@5qDB=sHa4z;$$)El8ASLRlSDR z2*XUHrI3s2#61uK(x50r*WCE-<#FA)z;hSaO}#Jg8kStruP}9;GY)YYtua^kKKR=` zg`*0=ir`nvsl(T$35E|}EFxot$?~#h-cP=fG|x)XgA=N79FWZjR`E5>rCAj6<OY<l zE=MCa7_GI`-2$haI}n$KWR)nDkoz=Cg0T9qFl%`)3oMN6fr9NTVQyk;!9%gY2}<yC z8dOU6DJ&8Z_O7Qk{PURk=b7|s%oTN7e!5YZlC1H`?D{=Qq(c8VqX|GzF{wYJPx<}e z2v$ZTM*7v{YuyOPZ(bdi69FN8-b<XQZrwcj0@Ro@$YR6kp0By4GW9{Y0~WI$UpjKe zgPMCijnC$|VE?o$z3vrVZ^m4T2GGF`n2=%#k6mkgUSLLP3E2^298g$MoX0sr2BP_% zT7`P!c#fXuB?KR-+-)kt#Pt}c4SHU3039Udq9u*U+S;|3C%Q<oKA9KDUFVrNVQh7f zgZemhjpkm@O7b!rcquG`ZMF%w<8W-K@zIT=u;!4J@lsj}t*_=hQHO4XgAnK+>XT)p z7`hIXF22EnXGlECYPsG_MlH)FZ;FS?Cvv<4i5tUoD(G?e1Jf4s--<y5W!#)9Fha6t zi&>kS94jc9uF5vrxuVVlaz$<4Q%8I}q-utcA`+uTs+PR>sj2>&%V*N~^^ruT^5T5t zmGi)Y)Ve(2m#P6pL!jNrG-(!$FLv02LxO2Uj>QWXFkGY{^j65L6@3#VkvfpOD~A^} zQ^RwEjfF#r;Tg}+sY6r$m*hrr-!eftXY-@}5b#|>oSPJq<8#@7f#@LG)VoQOvxdZ- zYxg3gCsatS1~sT1o}+Q(Zz)K-;G_cEVXM<CuRxCkDD*)U9Jx5z7x3hut?U_~-Ng-& z*0AHPWw~4mnV!7ej*r97dO_3fff#^np71#`GA=3|=YTA--=*04Abk<xa=0T{aQ}wd zTqVxREH`AK&ATu6%8E$@cqv`&X$fhGrT~eM6hL2tvC1({A`yYHWG@|=u95Go8{tyo zy<u31&?oNwPR%^ffVlOT|47hk+aTpwj^gx)_|yy5vb}P{6ibB!_YOD^(BzRjitH!w z+9(yI3z3MRc{_xn{RDRgk2F3eP!PU?0diBIOXW-?yZ<v)0di}B8X^EuPJ2z~&j4oz zas=UGhp#RvA3aV>S<=hr=1GS`HC$@-gTDW1<{FccK7{M{xad{{G~&!O#0t%i{Wk3S z?I9CFoPewAI$kE;S=Q6I3>C&tfCB$AmZ~<BO$jvS?+x#MRZc+pxo`jcNd4thzVg42 z`GifL@`Qj+wwCRDSVcCZc}E~AUCkveGuvL3^+4`>92yfrkXoeJwmSHo^?kLu=GYje z(mnhhHCsIGxp}Plu+=X#vP0P4Ew85q+awP}mzIg2#VNYkZ>;=`f9zUD2SYp`>Hl(% zO#CX^Xl8+U?)hJCzIofoiJZd&x81cnavyhlr<?*t=}(`sb=j4IhVaZ<mGXbt$)9hM z=`iQ~6Vmus)h_>S>(AvpId>kY2!1g0ujW3Cwaa$|T%{x;S<U#zvJQ}NLV5Zw{{CNF z_~x>C$Z3P2zFQ*xwd)A0$UieUaLgZ)`-c~L?$Lwk71LE1)i`{H1-gc7j(cLrb9?(J z_5EC{`3T%dZILAxvF1@o<P8{1kW4Pu#q%UN;1%1BCq2!19d5NuF;J!4T+lAKZ)7JT z2bWs?4=<Dzk_kyj)M<ix?X|W@FD|y1Qg!hDEiF$eTSIIPh9djj27Nfn)vu*KLuz~$ z$0}iohfcI+d$R!ZvQz6b91ptByx`=Z3SNu2N~(9%`He*9{vNNmk2>#emD89pDmNpa z<mrQfJ*#sFAlpa#Ia$xuq_JPOf3B!(4LY7QfnX4PgDw%pst#l+R)1lcY$y3nS^AU@ zdOgg<9S*${1@Y-Tn-`B9^G^?v+t{xqg$Ai1*j|{b$XK^NS!7)g4oRHRl-@E|tW~)S z#_f5}(ouC{*KM3y{RQk4=Ln1iF{qD^mH5QRIV}rPA({qJ=V8?-USK&N0<2Z4R;}3Q zQjEq*6h^_ow0{1A`tADqvHHSe*$XNAbw0(kD6%7@oy|v1J0IK}H&#1a6YsdGn3tV$ z^XXk1W*&@_IVeNtbmg6*gR-ijq*Ph9_BQR_T^NVBnd6@O*V-zUpsgmA4p%?^PP!s_ zc$_TxF06O0V6Nb{QT~Ty)6Fm5zFxJco~}}6Ygp~Q$){3Q4DQ^trCDVjlp9aMeiwL1 zS^A9XcP*bP29++_CucTjye7FA^#d`h{+Z(V!8<{QF`twQa){CN;Q8TU7N4*S?4M>2 zqd#&AA-yIbJ0#@QaGm-T_V3Ph?}|5nT<v(UNee27lpvCZkJ>yG9zJkS*#*BWMiX<Y zJXfn?6%?SU)CK$m!&r$qqP#l!{Y~3<2PfZLA<nL40?lc&TEld2n^ZH8u|#`o)k9Gc zkIyL5HptRM6lofnH+Fco_@hd8)PLLB(wJQpKx6PjT9x5_RB@2&g34CNbbhVzU#OdT zxXT}8>VX81WkV`I)@z^=>~~PP4K(G}Y?r~4TDe!0UMplpaCt;MDk7r2Gm)f}tJSS~ z|CrnGUwWv{MRHszeo%K}%h$c6b%KL4>hyM?pyYd0Lj7028~F7vB;^Z8F7K~<S~s8W z5{v<B&x1SX9aQ$uT#BJ_22CX=t&O%*JPAKG!_-zApQ1J%K5dI9bKJSs_}Hf%l%Oye z>TpfuRw9xjD@YmHw|FcDA<e1HM4yiQ*{Ovv_V2AE4w)P?W)8WKU<ra<Iqt>eMu3r* zVgA{`kq)LO#JrnhzhgJ%AF(A;GK+>FN9oy|(eU>;dxOw_3Il=^L7EYewP|En0*~!< zb3r^70a!6;MH0Uws9E?OAX>!iq0sVTG4PaXGav*h1q4BQo5=#F5Y_S#3YN}G_|>D} zk}#nnF`RUi8_oI$|7l2AgMhUM+J7N@o`igIdFLx7<u9-Z!l*Ht3PAk+7cggoWdslk za+e;f0>Fw~94S53_YZ?%Vu&O-fIh%H*IS033X)<1!gUFXq$m=`cH=4&OSVPSQkaKm zFb;Gs9TC171+<!KimXPOi+r_p{&F5}b~xVX&4m}lL*H8Lp!QW^D=V1uUhFCkB!`sy z;49B_5($na{7=k4EzKGBG4Ydm;T75Bm-C{G90{dIbn)qSP&>PPA~lso;>Bgmo;>6b zIGXH^W{sf#wNLvK722k}6)A`uLfu9kmut22#}>b;72Wd(^2GJFpiHnuuO-UTcRM*s zjm7MVHBwmC3SaeHRyC}n2a3K3B4=cQVz?qf(}}g3ASbg!>J(>!MpA`mur0L2O2qOD zwd58-x?ue@gf#1t#*2)RfX_X;hz`OU?g5G8CRYwUSdI1&e~5i+{L|1GV<6I&Mrs1D z?69Cel75K-7%L-wd%i%pMB?)BKU7osIpdIiXmerm)tivv{wWs-)QqvegDnV|3mh;` zV4C|Oh<Z7WV#oZ*2geR#o>OJ6NZUAOETU=7`5@t*P+Ib#;sF_a(xMIDKeIA#hkOQX zb}Yp~VWrl3A;O(C|EB}z(N~HCyezKMcUr|aryjL@@?Ali>z$qpX2WyLE=e>UONfXA z*3@nCPVA*bk299P^!q#8-@B2*E_{&xFT)0Nb>A&o<0Btw;srEzBw{sZc<UzL@R*gU z)$zZ>p54ncDu}z|<hk^Q{JZIJE{qF3XGP2c`>oSF#MCI&wK~Rm1<mO7d}d$7hnia< zJe~i$<+-%)f0ZsZ)}O`k-Nx&L>Nrj7J&w(Cqv7)(Q?j<WZnk`iO6cy#(e)@UqOl@| z0iT}n^TK~l=U3ueIL_()dSv7t`NiN=pYhsK=Wk`@!F5)H@|Vb*gD~NUEFi5a{;Ewn z_M`&b`0<Ql--~`rM3LUGa_>Vncs39H_gn5We_YYGvhw#^6!|z*{qC)F8uL^wp|;W~ zg-I9qDj8a?J@Iawn>k~r`DM~wH&#di{Kg1LpjLO%rH)T3$dK;<SfQ-hleNl)UF-U~ zwFcPsC$Iuj`{<cwhz29mLI$F5Jba5*%IBW{Mp7)%oLNHEW7*I5wo3#tDTe+cCUjUc zuGaZLdq_?i2NHcnTT+En3Ty%Ftz<Obg9$n1(&3B2s)2S1$^7;6)OWd8a>j!iT95B= zQG5AN;atJb5E9rn|5V(3^sM9(;Sp+iF~^>O8bX?#b|pEN)y#Rs;^NfQc;Z^aj>7ss zb?8Mqk%KHR<_)iYoAXR~qjcr&z`y{zeR%hx^<@%>>bBq@!NUjHHPxofy+RG;0<WLE z8Z7{Ipk=M5z4};?%E|r?{Q?*fmBERoJv^b6Z+#jfwjJIGnM?MawxK)lZplW1XE-eU zL$aH6x3->w2>AR?`qb6bhOyP29<s*84jRm?wfm`=R{XGEJg0ksGbUh2fhm%YXXy;r zqP)W?{c(T)px2X86${;aJ>GV2fAP!v+U*FuBX+K+yj0XxI_Ex8p2TjW?tB7H++}}A zF3$Vqop0i$Jsld7WIC~aL75)ym5<W=<j{s7h7uV2YgA2~dCVrU9*xr!7-bHClUaXA z#@qK?u%0hWFWcJC9}!c#fcoky^4GHWCplf%Ajb-hpP60D(HU<4)sJ^EOV`oOHk_s9 z@bFN?Cs(#?Kl_v7_BZj6JQDQhN_MO&cHHsqbjo64V1v>rdh!MHaKkA*hslBT-Cy>X zKef0QSv{CFNoknV*6RjrRmf1Gd~b?)vM<$G&~ZMh+c%&s&r$_CjI^`L>52Tk&k<r6 z%3-6;__in=MTVFiC+8fqW#fXjji&%OOU?vHYLE|v0bkr}oi<>dPUxx1daRSUBErRy zOb~c=KNRD+fB81cUfOr{yOdwkk6kERyCvmH$`#BvhuYT7{dN6N6qqBKY3j{ywvXE0 z)bJeIsHU_5^rwW*;;|p86m%%^#1YODvZ?su9IcU>v-CoLe8S(vU7Z7;9*$a$aiELk zwvspVvc}1GQorB`34DL4NhIqw(>KC#ydelpXs{ocZ(4#LFGu7^ILkvY<o$hxe>LDA zIqt*%#M&(?)toJs50X@)=<j@G{ak2X%l@?SZNSGu+0t!>-$7T}Rt$zA!Zye&lEum6 zi1{pz9Y=W*kj1=m=n@1`q9{1vwkeTHoXi<*v;_&2kF~j?htSUEl4WeLF`Nh%ITLgV zCIX^fl&bb(oP%&#$+|&!#Vieo0pl#ll_2ZEYVrWAhTziCrcT~YPlrda!c)_qF%}xZ zHT%>d;@V9gDAf>+fI}Q(m9Xe1u~RbKdeCZ$Ya*Uw7jGbECTJEbS_-ITg-j?wq9^y+ zTDa0fW@;)%WC<u@j#|a4fOAojCl*)smgQt6&j;F@!Z~nu8*%b(Vql5Q=^ek&@YHLg zn>D~@RkoZVQc#0>h(E~Q+4d2V*S}4H*GivbE4IV{)oYOK%A7Z@*20M+XVMIRn<lIv zc`m|?((+<~sJ!v1Pzf>KxkiEikAg_xHgZx##Q5<c+=QzGMWt7gr%Kvm@K?kH9BWqS zUBgH?U{(op6266Vt`HGhV#bEcy>k+bUM0MCk+Z?Jg@ZnV#lE#G1^CC-Ybl5oyco%{ z6`}?pA-IbxQ-GH_X^>WggXoV5*Fv76Xd~yMl8KPa796y~^G5R~?s|=r^Lm!<^7fhc zdqp}fzoZku4x_7VEZZnQY*A6~Wg=s$1gz~bxP}3Nrf^cDNrjCtVA|WR^N}3m;L>Wm z7Vt&btOIVK&&2_P=v@$NCsHta(FGaOVT0!#DY$l7x?R8ehsvR;x%w+AMYLlKo8a9C zX+4UR7jJnL;sBTd!OyJ=mhfAw7wFxyUjKf^J>^A@X82JbXiC&H4Xj<~*WQ$wy4p~S z^KkAqyb%8VPRHyQ>NccVeeV}mH95_k)W0pdyL>cY#`%DoUxe2#YO+pwZz@UMS*?0_ z)5@-qHxK7+l5LCTzx2+!SQ+m+JA32YsMZ<h+fHbH*p&Bs+Ca}xoW1i40@T$A5mC8g z(MWZ8{#NIQn}2(9{z{$txT;mP`uuY#HQ7GRR%fGCAN?#(ap{B79{a?|4&Wlo$>Pk4 zx8JxMFa1fU3e{W}jDbZ1ceE!6xxDBfZ<w-X<Yu$cue;vJgK2XiRFj+)`ozDt1@cH{ zd#b;MOc|9*6Jyr&fV9g)?4nw8sI>PY;QTvP(&5W4Jj}$6d{`a4uf@;4&>2L&H?BF? zyn$zbU~<FqnBbx7*H-+je|Qma%cZDsHRLm>2FBbg#Vzg)X{$M&?tr?=dW6qOjrMp# zwfxeN(d$;M{Y@cUUvJPGqRW&_xhO_e^<O<k4`q`QRrSQLUOSonoE{(!qPHSzjqgV1 zgv5x^FIRrcKFv;7{f1qmW#d~z=@BbhLrqC)c^ZzUh)5`nDqMDG@Y`xog^re)vp0tE zC|p-V_LkB9eDEZo=FU#FPUPlSQ~GuI;6)o;sp;EI?b_sbS(o%UvIFSMLmg~)KLk|5 zokELQ&^+Yc=r@11YIz}=C!uv-u1((CSv54&xj^I~fPTGbnX6^FfWmf;=_i8)gOFiz zRY+`b)rJ2z)E4xeWOcTpZ%4V?9c_w2&|KRq2y@#|_Oz--oTG$yAMV;5RlFWivpJ}a z<8F9s34U$D1$pN+JZspPxz;n+>@`)(Wa(6=F`-gZZ4x695C@Zf7?d#d>U<>leHLT* zMXqFjN1I1$aX=S(a_W+0#*w~4q#<#_4^G1V9XXBkU1X8u4W*)QBa|<thxhQ<R=(ky zhq8nEDKtI&pm;VI1vy7y>p?*nFS-K()6;~o_`2JjobmGNgc<8F+@u6at>>p)9aM{* zKgoaRzu9w=Us-l$gcB2^(}4%sH)4zXZZ&KDEiG^Q$>9R<7)rHg7tIRaed)tvx7S;L z>$Ze%z4pZWU!@xCMNNPF{mKT&!4G8Dn(HE|@9^se?mY8KH?Pk=`i3x^ym3RgG*@Q4 zKMAM%&hPv5^M0>b^s%0Ef2aeWC*fiVN^a4fdGpBNza}zpVf;f4);9XY-18OJ^3nzz z)WUV|We>=AfI!7E7_kCjI3O_EAoI#S0^5T$lyYh<Q@COT%xMgGVv|w<Vmo5=Mojwu zi@6wzGdHo9j~tKiGaJ2@cIFKPi5kfqwRp<lDvj4d9vpK=%w69pFVx2G$f)cZA!+EF zV5*!{)pCJPY4+*Uk84ytk#FO~kmDkzOjiHRG%^IeDMPrt8_bv6lNSj0F+zZ6DKk9+ zBiHh_#<FPWMi$HTXR+3_zIs>#05IuWj^~y<3N!24pcd<ISf9*^6y+Qilt{U+m>z=} z%05-hg8{sjeDg-(KnIEJ_C{F6*i@=Kw{yY5Z`kr8mCgxjv0%+Std${zvO!oa1-N)a zR>D$2?2~hX$w7L;;T_$5SO@@0bH<ZMlYH=c0#%c`MegGtjRgk5JB*T$*dIIe98{P> z2&d3kxwacaF)Q)fOd+EyNay!hIBS9hzQR^c^<0R~rC35Z;Hgv3_SR-Ovgx6d?Q-By zTj4&+MsN|v1xJWP#b9~!=+1yOcF;HksiuZu<>paTy@q^Om@WN}-|<p-?Q0VHwt`qc zM;Hf<izkWh2FF}j%ME@;u$9?dl-mbhs8VFLs++M>YZ4Y<-g(+dcdt8=ri56#1pSRB zCMN&{#$3TiuVB<BZ8%No=V0fAn-z2;$2FxkYoTDml5}fqbcJbiB4>QF$cli~S!Qbd zX-GsML|+Ci1^FfLEoS?busLG|hfSX1rH1Y?*=kzoE^M=E_3(T`K-;r7dL!vbnlq#W z&cRk4hgOWfWMray!G?5f@HXBv3N)AOaexq%5cSNLY0`4Y@Y#S7v@d!+P}GaCy~0D} zVc1lOl%`*>E)pJT8ml8e;EH(L1)2x$GcPvlujsPmIv!DY=lovT(IWY*;&;|Pt6!U3 ztD60s{<4k*lpHW&o(q`^ym8yBEJ>*;a*l`Y0q-$MDu$r3W{ck0LdI+#8+;Yr3grO{ z0j9zoU_jC%l}uX-wt4ahLF^ii4=qE8;Aq3}CONqI(8Uh%iNZ8MU>@X+B>z}DPn=#U z#zdAea*mt0tXuVN3_gPw$Z_KrOP6iO7+`R#h73d(56o(vboXY>TH}a@4~>}BX_P3P zZeCmi`jBeeM5D3MLdNxOdB#ib&8N>~tDNTlgqTdUs*LK9eFG1C-q<lCc|^M5NPCYF zaEvEi_G#nyKFd=rmsxIQTh?vJ9kh18dP<A+NX=0X-`VR8;On5jOIp{zxbx86@{5OF zrX^)-%g3x#Keb)DB4tIk`gz-k!fk7OrwyiRN;f~{7cK3g=e7o`!fiX+zP$YsToJLG zgZtfweh^zVXys>>gM+$~n|_~Yt9~tY{?{>)`yA_;pvlLz*jQ5*_G{tDr<D&6eds*% z^XBYH{c*-Qu3NX83tw7Pu6KG9J<S%V&}GNRCf}^lk%+2fJ7$|mLuAs&#w&%=SZ&BY zQ(K|6SHqNt>W7MBFM8xbeeR1EEa0^&C)MWs_J;G3ricr)t56DuUrs1^?V$a1pDlX1 zxVLK$vg^ywF?NJni&SPor?s+lSDB_?bDCTjD93PWw-M6QSwU0}s$LwfYF;f8TqZQ# zT-2rt>yKFWP%RZMUw5n4oQe+5n`HLq1W1AE*0H>hjHM#y#iNm?`z6j%U7dL`Sk*U5 zGXr0lLcKk_2_b{0!aFa=%UiF^RE<m>^GPlpTI^|J$Ly(6WC9xaBp329<NW}jh`yM( zjJ)I+`wDYofpt{DDszQsv*%Jv2o<n+?1^0|P=tr8WjVM--K_%x%uDt`yzfa@^Lh(; zMHIqLL8SZIUF)Mrwv8q6kJ%zxJaM!<#IBj$zP(v{Ku^Qm5}Pwl#C&2s2LXNrOi)d; zyis(Id8q8p)$VxdnwoMqP9D+)8^kZ#iOb;vM1qY$^V@bVpL<q{YT&od0IChE!aK=@ z&aa0hw;(?D<diq98z<LCTZVPXdq~C?x$j{AkOFM<U6gvgrFO;QiPq!$;dG$;7G6Qa zuy}<AX^pV=qLVXHfn2W6r^HU02`FRQ@8vgV2|kCRu{A(2UI$VeYw|ysE{Z)@B@~?1 zW2`<J+<@rb-bRaj^|K^K2snqwo|-m&lv;N{7eMbL3Gi7raUVu&ng^a(QE<S)>3c9I zVTEhMLHQIy$1MzB8fJ**KNF2v-MHJKIMF7}fj>nW_-uh{QAlrb!oZQ!Gb%B2Gx{9c zjH3zLmr5{fcd&`7hXU<H$@Fg<+n9{l2M02Hg9xz@CQO|l>tp_V@|E?cRIZY(H^bBn zbQs7Oo8^|Zs{i%%$M5nLE9vW4!!zE9t=N2y)%ri5ha(Ewl@17lpy)rC^)Y)ZOyEY= z30)%#<(hYP6X)y#---Vnx@K7}<WO40-hbm@7qHUdrS0Cl-)%PfxQ9vUsM}KT7HHW@ zal~Wxk|eYG@GL-Y0e<n%VUgcc5rwGTI0*}3B2B{Dj&Em`?+6?N5s!bzVL>RQF%mVl z?mD0tY8&V*B*;lpq3QLf)^9C@VD>HQ45`q%Y+6ZGC7BFX)*9qE%@G$6EStJ9|CIO% z>5=I%h6LSpw1qjU4RZQ*cmI4P+4G4Ff}lsN7I3~|o7A$EAP+BqZI7uMi2#<u%-?An zt`-10r*F>a8dD^X$JS9#8%Q^}SS$)`#VaJ5RCMhHOwsH{x8=_+YRShS6q=7@3bno{ z$)P1~#IqLy6><wpb`DR^jG4x6pp(Nm)35KTlXoU;W$tSaqp1l_D3Uw>*#mOyh7}7K z#@OLALKVVsgX@vfNkI_LCRPz8T%9*U!l0!g;ynCqfIv11jni1POL&$tUWo6PW~pg0 zcXecotARwRhC&66USyD!hF8g*Sq!XHT|5tpKb8~$HY<pwORg{a_kj}z3{ap<witjP zVhH#Vo^;WLQxFA$3{5)u9CAxq<02)h;gtzZ17r&~NH&$|RcP5%A_C&y0z~(n0@a<t zY}`wBxWEc>gkwr2#l?v$Bw}BaEnTNk!tD{wOie{xurL#8&d*l#YdSmEO5RNsESAr2 zhWxsIZ^)qXqOYtrxOU>PQorUc*=jMmZ;kn9kV$p+nMJ11t=vt{_~-OjiXoS;94AWq zmO~iNV=X}ti)BUt9Wy10m4L_?K*lzT7hlc2EhI0drUIs>2}|!jo^9N^cv;R9!u@cQ zKZgtAPgDo5BNoBsU7Kf}AaTysElRBo*+5zjreWDHN#H@&1RNXN)m+pBJ@$9DX*LXL z_tBl}$61?x{rOHBy$;vHECiul&E=`WbghoaQ<m{qx(8%tG<_?C)ZN%&m4ES)ao)pP zk}KV+*dOpT%-@c|(CTBoAewOp%iiAF-aE9Fz-vAJ-Lu~(dVW(EyPzps<F)j`*ea9q zw<iM@{;tq)?igBbY_-d{PX_1k%8LGn!}a<e7dB#;w9EP2mLC$OXLnzko*n7%8m`LK zkB@Fh_)2c#<dF*_E6qTh!?gzAj@~5$!$XS7!1%bg9sp+Tlp2+mrtTr>$VmU%iob3> zIk?#^^9ZXq{K4s-`CZN5>P~Autu#&347WuT?%QB#IhRoryl&{!i!nZVm1ngl&OyQg z*>hdpGwr7uLZ+$qOi};GJg2z8<aWPn7qELjS>#n%YIv!J&cGdD*}mE%#xkg#r<=4T z8IMN?EZcq`nVtGX!~6NAyN)nk?d}EXqg9b&IOn;7RsWs&>yoLe<$fU-oWd|BNt{6R ziI_&4jQm}fQT0~5tQZK%Z)EClssn0fpc<%zV`J`!VvtJJ=H$V;2<<WW`6nvrCK8nJ z78TLSw)KQphl&Q)9ME&=14V;P<zc62ETWB}npsUn4#^PGH}19r=`#n}h`2Bc{7kHj z-ED_eqT6HrCU6YNFWgp^YHrOC@V(e%LT|@t`LNtUW*{S7p_Es(u8beKMDMcs2qlDO zxWf+}F@}1L%C06|ma9a8)od&!N|o|ah`U{naF!!{g|ZGyr*6ra=)8WIHD+=RL+Ish z_1P#vxe`Q3h71TfQT+7y(+53tAp_8#ynH5%<8p)e)#BPLFk?m_vk_fsUSJ16C!p^z zVUC9I_%n{+fB0Qc>j<U{C4n7(xUei}DD}E5eX0Yk0+p+>HE_knnquDoq2=pp*Oktm zT6sYgTtDU#r$C$&Er8sd!|Hz6o90SO;Yzk@&?@_rp+QtnpEv6=l5F~{42lXKd!WiK z%hlH>@)wWvkftJccSr}+7KOvrB_Fv?)pvHheOkyXXEVhy9zrIgNl=K51N~48dc56> zw%fDeAe6Mi+t#ifUQg8baNd8ls{4}-jk_>z*5Q3n6Y%4$h#ASvplan*<&3ZT%r2{G z>Bx6s3`1Jv828I|)41jaP9}~Ld}s{@K;w@5|C=A%IJZW7Ry_&uf2_^^fTHvC=d*+n zM49o`-3$bfLzlN|nAB3-rWkfok%DQAET4Soxx;MAwSkeZQ#<}4`KeQJoI^qQhXn`~ z4t&(k&Sf1mw^<=|)V1_pg(M!c89$luMJPz8^I1;TAIn5$AN{~4sTq50vWa?u9ZB#% z=d1@cLH<ULOWEk37#<TEqqcd&o(D^(g5A^_<ZB%2z(-oF7_!T`R}R~HNwyy6-8!&I zj`uq7ExKR|@Z_OpI#^r;ip1zTs5r3(;YuRpPQ=x7sW-T;hx*Lr_~r$UQZC~J$7%$b zuSh9T9Z0)ng+p;q5L=nHGmv_1j5*$>Va*tA6nS8quoQ<#CPw2Fq0iIpligZu4~%4~ zJ~kFLG0C1M;_g&-3<ntazrnL~45*2W^<lFL2iO2bvW-{s`9h2YAv2Td0&u$*Z%v40 zqiC&7;^A7VzqQx2T|t;4NO0i6?2*T{I7?YJQXp7whl<6{21XSSFY<KQ1&~4ZBI|va z|IhxhJkBVpaOM{TQStTKd=gP;Z&WoaTds|n#6>{3;8{FA<h@j(fkikEBv=T-<6PKV zhbMW7B&L~aFlXXqBS}ax`G^d;zbQT)ocgXrEeF3r0PNE1g33$BmtZr4ZAdyqOMiXm z&nlL;&-l~n#}loBx@ZlJQ7Msu|Nlk?kfrE!w;XZ~kFMgVIbO=Da|)bnaD{w~3G>Fu zzvmnTBx4O_jLmEf!P7FA{ON|_eDZEf1gAem15ZoJU2a+qqLFX^izZV5Lj_7R7Uz-N zbYg`11^-l{OUP}82{TN~L@A3X&-}E*LYE`Y4L4nUeC!X&4>O|0Q-HE94$$?_Jka-8 zTzBQ>t7OiOl_Uebb2OMYcMSkid*9^A>`S+SBnL7MdAD@`?U-TR!ABfr5p2*Cn8gV1 z)f4rPzxw=cY2sSd^WwB@IvRQAldT=)r~Ebnp$LU*!~187m6n6h);XwvqV<*E&L!N4 znD(AWT4&fc>>zaX2-d_rvvpc`<<0N>oH$v6s+`{UyEXE%Zb5&FIVz%Ze{Qds0d;fA zqpON}m&S|GcD{!pRV+O@_jA+H>J_rOEF`JHrMIt`Q1HRD_F-N8hu$=Gjd&yehtpx! zj(4x-RC|~`vLoL4*VI9NYXo1~EH#@aCUA7w-_3HP)bL%RI(49aU4$&UUZ5XI(|vZm zTmUe**glST1&Ok$*K^{81a@0&qAB@(--RBUj(i!DX%~l!gT(``Y$v6!tKFMDhU0l+ zrYG%l9^(C+*$&EAMP%6}B2?gXajc7>4a7qNA)sKpdzxifAT=-4lXEe~QlCYIC;!ug z1M~O{a$kByO@d<xH<|N_2AjyLKI#`d_Z(sM1LuA5@9MVevbbl0&L{5^6F$8IFyJHm zZKo&Qp$q9qmvHBd$ow{0HFBAL_njC9fy*n(&*y1{|0$-@e@L8`avSYAW3r(l$5P2T zL(Kzh&esLNMv)cL;h=8FODA3Tn?GgHgM)?$N?fiU^_!+<p~r@_UBqlrT?6XceIS_N zq9OJmKg`s5aYz^Bx-z*%<F)@-ko6&CR1BT&s{C4mWLuzu!f#*eS+-(tE=9oIxq{Gp z!?0vO&#D0tg;3%vvt}Cm^^YdN``NbKI>Bqj9!NLo{AYno&kj`5m`B8gh;#M9v0WYM zLDFuIPd*Y*<F>$%_K7;BQf#4rC^G%irz%}}6D^0P$<oX0zfiW+dB}MUhrgdpPRVn0 zCA=4ms&6=+X!6<JT+Hmho?6U!9O5(1{wno;a@9Tc94`KwTpWgmt2^W_X5&+cIE3Ck zCNwGGA1T(E!K{C<QKf5if8$8do_~E~jk5Z4Fow^~3~PVlXo`(#1>^eWny<<H$$HEF zF$pVS1Mrx<;=zm5V2<#=EgSuce|SwFMTKIoQ$ygi0gv7=KI~&TW*J)am)(#H=ozn! zSHweS!NX#iTNg&K{pog&CaN!y$BpGIQkyu_Jam9vCj`~yR=b_2+KU%wJ6+mXO+vmW zs?IteyvPIX%x6fL4lBgT7-VqkmeF2it3?0*@}Xl%Da@3-Y{ebT8PVmWycN;@&KL0x z43ZHwEg)8Oz2=>?%QP_X7RDw`IHSp^{S0jeba5klpg2n+ZHT{Hw}(eUC0Bz<a;gx+ zp#@<MI7i(f+$;){Nz2w;8||VE&@Pnk^W>7j_+Bj7HAMGxQWKHM8c&fXPPUeO(yL15 zEk9KY3!Czz5F}%vN9u?!@gWkeO-!0-P99HJ?*KuDf>IPgUrn+Z#6Kxn%e7Ux7}x<d z7`JORSQq5jiJ-tfz7rD~Z5i?u_0k%O(`F%Tj$iy_QEtjEHFcZSl&dihEOt=SL8xF% zWx7ff{5+9nYPfmLw`@IC6;wMWUnsKJ@d=b%W_YU+u-s~sX2&N2_9R@d0<(0)%L4Y> zmSUL&&o}o`3U8HLk-XA8v`P<+Al5LYhG1^9w8K9&ImuILpCNZpItqtKZcB5vup5AK zoJg&q76V_YwV5zsB%gEp9j;>Q(mwZD18dey<H#YUUw^i^W#$hd@?uYw$c&i!Bk)lh zC2*Vag~e8SM?7KXM#a6Q0Wv;U#Iecr<O&-wUy$LL@&D0!@zzUnn8M3WB(&;Kily|Y zlbg)7TCSrj*ym3552Ls9$0fn}^9FRdYK)vHY8v9KYs-hsI|;l&(VrokGUT8PTnsi; z$W+W767#d)YkC$uip|z!xqV40A`*S}^ZxUH`9&Eg|3U@kidyx%Nf&mMekI-GlKkY$ zsIi-n9;ZOBXe!%z=_{7>?L1=H7TOrgo6B~dZ!H}Chh)NmpI|+SWJLYR%ihGUIWE1k zzPA2?C$j$5385Z^b}}d%nk_V>eLDRsqo1`-^U7%5Wq?U+xpT0iXT+m6&(aG1&^TP_ zeKM!vrMW{<dGI`>xXruuJdrQ$_Prpw0CL>&YP+6Lk9a!G#IGzWiv{*WVXcNfi_~)R zX!+pM?lwF&E{XxQsfDzxe|vJ7(PR}sC(dqXyX<lYM_qhXr@Ake-cYn*jjvY<KE8B= znB8?~v%2h^>qDCM$s^XNtTsdV-N*T^eKxO$XtuK2yWn1bHEZ=LrFA!Oq3OZZNNU#2 z^>O=LOm5<6Xq!i?!d!7X>*McgKcANGj6t)t%SZdl)092$UD<amWaG25)-L*Mw{^QJ z$dHQxM)z|%ZRB*1pnnQpOKg1XrI!n|xu(t^LO+_ejCQ)i=Y2`@>pJ$SbGC7A$GeK6 z0&5c?+bl?*s_L!1jw&-UcFJ3^#kS@a6&N|O4JDba<{U_`-YM3Rm#?BfIS+sG0H*r| zwFb_>6&W_6wX38s6Z8}GX@cyb6GRnL?S5wSxa5ojRk4^0e`gPnvG13BiXB2hEN5^& z>IH#lZd8uM(T_#6MZ*#hj3q(a=XR&cw?z`RBQn;KZlLQ>N4`~QsTS@DNFR{FVouoZ zPAU|}AbC3SBQFW2$ryfl4S8QDu?91lk=~+4%f`7`{s(0_qkQ-=SZ_#j(x*hHLvGBa z9bvAXz$t=t!9csXEHG0SbDt`xo`#5$vpZ0<%@?^dpte&DpK+q9HMmw~Ys^p?w*Uor zXed1SRKZ~EFa=?_TuJ|Bs`tl-_kSa^P9PfkLuf8gxz3WXx^mqCFyesoX5%mu%tuGa ztKXtG<9=rT^JKP==as=h<iPnw=fokeJ@WmWR|Y*!vQ-86+);?kDKx2?EAdB2LXVDf ztOIY02Xw?>@3<T}?Swe()nC`oGq2+8G*=^8Z#fj}`*e!cZ90^n0VV_#pX~`&ctK)9 zPXZ2^XgWO(=wP2TtL0|i$Qm>9Hla2XLg0e9R_Y_8<>}UyX>Qf)PKnkSgJQZWB8X3F z?=vN<IdIGa*5eh2q|9qDUCmjjodVJ0j>s>0TM7nq(|I!bl#9B?Kv$w2j1t=$1|b>y zaV&ym!MW9cH4jkjx^PUC@CSprS}=?B)P-Ebe>3a_T8Bj>N<<dE^n$;D!~{i#Do;Nk z__o$83i5k_JO)pV3!zdhGblsW9V=mdQ)T%S?ZYF?1+cS5<!+ZvpMXB1lX@&CE`!gn z40(=cm&4Hy93$3N$j^lSD$*Y6nqDp-Zmdw|B*{#2j$b%o;RHyb>x!5+2t#pE-=NhZ za1c&zQAuobmEh$@>Ix@`-cG;KvOY`Xr;v^rh!+fz2QC%O6@OtU0J30nQ>iIXo#48; zNnSLjcsTlAZYrc?Se_y@S>sH^g^jC^)RJhyE`TG`^|4s1H13L-Mw2r}M3?^BG^0=p zs~As)v*KOI2LN|yRYs{O`%Ik+yI2YM^MDXQ>#;v562(|M3K!vTIEN=YS)dbc2v^3- zIDKO6wg}t441NJh<4BdR5PTH+^f8J|@m>mI2b(z>1CqgO?}Z8ko^LvfAf}wsu2KLv z?bTFBZkc}bW!dDn_%Eanx#V(}|4kqBDMn<uY+Sdjke?BbBNg@YC(W|7s42QYf-Z|t zcoS&6kp{^qm6&KxBUSL6WjgvVus@T=i)rFK_Qnd#0r9S;F17Ii)-1N?bmcu~FVZEN z0GLb&zoZPCfFRXdPtBwyYXZ(J!@~*N`<!u57`8Y@R|%U~|8#svG1s<c)u#@Dq$-Bn zoFsndeX_?h&WN?oO|76tp&Nyjhx&z=$34_+6Vy5ib}Bw<3X~r7!5uO^l(jqDe*A2i zbW+EEsmT?o<lL4QSsn4=#=X|(j1>D(S|9#C-dMSgF{zwCulvqK<xzDjd|F;d^{mtL zH>^|dopN#J&#8qN@-z*me5gz47!!Z@M&F0WQI@xa?t0_Kk7wTh<f<_^?Kjsusn&-s zM|9iUf=}~N5KY_G?Ue3yS>3EndDuQuU2FViNdM|_{iWOKh_LBDz^EEb2K{f&R-?iA zc*hU%8E-uqAxrD79XR{+p+ko*4J_%*&VBh3thu;#KMmcd7FoHejAc~%>x(VbKR<Wn z=<CJ`3n*acBG0PJwkCEe51rkUT+aVvgDi`yn^A55g`Z<~RF){F?jHTOb0j^!BP`2v zmb<T?BL601DR?5I6eZ5QUeA#aUjUw6(0t^vw<7cW$%l`FzuA$c+y2@Q!;EW?lOH<0 zxmo&TBroAjk-Z`Ce+|?_akmidqP3<uehbmO`AAAdn8&YS_x@U6x<RLUj&4k;-le8I z?_7%Sq<aiY1Scq8)Dw15uefsd7?8SiMA-kuWUpVcuA;W^n7$@^p$qv-%YW!5R3BdI zet7@*Z^XfS_{+ZG2@}$;6glXf?0?ZIK;oUG=+bSwUf@#Hn|tMz_k!zdmBQYEk~B8N zgQdoJ;}F>EHMwHqaAE|T??rM>Ax21#7#M|OqK)iWgeqZh#lr}>2bxpdItt!?hMa^d zhkYGu6upcvq^*ehf*|^!EnBF#lCgNT^%*S=^X!zMmhWCe=+qdKf(J8QVw#Dg)&j%7 zN-|v3E-3~pCnB9>JJ8sN<`<h{J)S}Rc1?(*#NO`^B!%#HB;&L=n+ig>##)H@zX)cV zmwFz<>54@DZubTgP}sj>99eG7VV_aIw&F9=se*=7Jz-pjrX?>uwaPzZ)yxa7(<pp} zT~M6s81MbNR_^--bgLG2GFa#8*;A_uhhl?1_=YcC<dHrI6$S~_ba#36fx|S5&<kt| zwm(UMzzMM?_<4xcniA$u>T(I-teVhR<;?05JGZQ5K_pti^rmJ*hd4n43e5p&GIQ;! zTxX0fI>p(_gMEFiw5xwL(AitJaVM-met-Kquc-LXes4Ut@45J4q6dF<Mi~krS<qOG znd`zEi8=>TZ<Zv4T1KYpxYpTC<(|BWwXff8dC6<-5Q-M+`q-CWFf?zm`ID}}t+d3m zBlebT58hk<8vAz}cuD*z(U#m<;g;#NQnv##IaANP=TzBJ#BE%CrPq-}6Z7TIuD=JM zCs@#;`v-=gfSq%u%HJmOZ7Vc0|41W(sxA9}2rR_<B8qyeY!V3Ce=cD4ut6yOz>twq zdVIl|%rI6ub_OS3)rb)<hE#4Xph(Aa<GyA2y-l>(D#(FaZo~`N57#niZ8!rLaY%G9 zoXJM^p?tv;fD(mTGs{)w_GJ%TH{D83M2;aH?KFn?P@7ap+z3`t-K09a{2?k+S$e!R zoVtSN8X$avI|?lW{yM}$-E@F@aSs%O<&!x4wy~g!M$W)6_m`g2cqPrbfPR(H1J?Me zKuziCURwnkAdy-&y3W=m_FgIEwACezYvye@`5eyn$@Y<GcL`8Zn8{Uyn$+g%WC-x1 zN4l{C#Fse-JfG)vogw2eVp}jsg(*N+Wj)~?hZ9y>ul($ONs7fk)@VED)rikj&RHkG ze(X#lKYqvnq+So0v%+qieo*@;g>Rv5MNbv;%IFVZhhqQBx2X47CbkJEB9vkg+SKb| z3JereS6T!nRMk>9VjS7GTx2LTP#)&fm~F-2ijKx|R(=9Or>{2YX=mfT;9#Ig7Ncma zlaQ-L0a=z#D(;C?1151eRHx+qCd`Tu0zezc^2hy=lQ)2y;GF3ej70ISArIKX))(!g z08NEp+;kOE&2Tlx^c*r`%8zZB3N}&CiU#R{^mr+P4Q<xTWIIT{9HZ-X@hOmsuILs# za6lxSj&4zK9M{~4SKQcN7WmS+m)tUsu7&jt+o>$&(k(Mj;N7w<KUgDo!0r;$xra8r zzJuxQABaTlO7AS=rJXli$}V9|chpgTduB07qEp;6c^@ngjpQb*^yIMoD<0-`I|sRa z0K0OeqI^m0zmK&I=|T~L8HYE$c4+hC2SwagScIdmQ}R!kK4u?3v_$>EOR=})mjMBt z{-JKXksndHm1!k6T&`R<tc%^%`N^E=UwzI>dzI~2^p*On0}CJgckY*wA{V@~?fM0% zek4#u<gKN1R;lE|VmD|Y>EZ7QO2E>c54I_9&ha{Td4z7<a7W9{FO;s6?|=b4@I3S0 zvH8A9m@$ZXhxFb~<)koee&hCaDNVD!dzr&IzEw#FN_Y0>Nx#J%>dTI(8kSK%7p&`8 zyX_TXixJ}j8{-03CuY37mK}x8>xA&V-1V{s>13)9cG?7oR5BtL&37tA(nNmOm=zLp z=AY|VKeBv!hI!UwDLDVb_AU)DRnACQc=j4Lk7_Z%K>8@`oMlgqz?G<}7I`k1!y@or zSZ7l>#E-;=pJ>@cUxI&KUY^ji?T4i=(HUG}nuDvN(F>E1d*{MdU+e1IS^V7D<fZh% z))-z_-uu5}|A41P2pNjKba?+;Qd!3Himbqp4m(*Y@r>SH7&@Pi?(ihYmapS$d~Nz9 z?}dV8jy*OH9ZM2c9t*?`qrxjWUvtQH5T5pHRqmq#5(HxmA4f5DnJlx3J;)``#ov>> z0w6VW@x(=9me=6jXWO}KSYQm+>g=45z$awUM*Be@1W?Mh8nYX;bIH`HDsz>{IvIUI z&YO>eH0C9WhGz(NRJR!2ky7q!BB*Xd?&CfR6V7KiEXn{+Y<7<aGM*Jx@916L0qp&< zbUJ29PpiqO+ad5%?4V`c<b+A{R9;ITYN8g2_aX9=jubF}2GJWK;bs64&ZQY|m0Yt6 zjz{V54nb1fBi9wCa!jwRT0DNq+;|Un(*HHfNXe}W|Dh?#(;c}q#zD1Q)1SWRg*$qo z6`;FxJ>b_jft4%BDy|&<(Loh7lnp34(u>9Z47)z4tMdjutP%e=uKlnN?>j8udrs^- zpuKaJj_24Sw~kLg6=o+F_9@Y|b))l6rCrhbG>BOH&)t7W7MmVSZ&2TXm38}=r60Kj z^5^`;&RIR4D~6p4Gp)Hb<!)Bbe#Ktr$ZTm{g0U;H>)aWJRK;nczN|mcpztEOjCk_j zaX(+6FxwXK*9`Ms+X<8L{r!Z~k3;S=2)@mhBAxePlbJUKM*`6?AM{F*{AczBKaAHz zb2e!ZhqkE2K(t5LS~ya%xM5C2IXQ^)I2(-L#}~rE*mHVTOBmC+s_}*~sCj@K$aV>p zVq)4UPyVg6(6HjjH{;u^CT2G9s*lhY;{4z7#nbcyZNE(JGa{0zZL0*0P_(e9E^buO zC92nftVlBvl2*~u%G24pvzclnZR5zhLbI2%U&%YM{=TBi6{V|VEX<J&#rJhS$$}iq zT>EEj<W#|iX&dTz#6d%s003L`xU9G8?(3L@B8r_lpX_@{9PCj{1<He#SPw$R=_l5t zoXtsPsK|1i%zDv4@4QmtAk<AfhIG4i4+eS-1l)O~lI#tx{&-=wLYMWV{Vy_|{#h#d z<-FklTsI-;&_!iatr2$y3&@k0Y)emkvfr3x#0*KfoP^qH+Gh*MM<l#}mO>zD>S(Nc zxx`}wOpOrJsai-K!AByTBU6W<WJ2Sog%7O9J2Lu=|K_qt=@eIl&3}Q-aieCzNCgJH zW2k)LQQ2CX=xO_Eb4)I`U`+|fEYnBw40~NDFUV)NWn<u!@1$q9Hy0IOCMKGLlbK~n z==urrk!i0>&exB)R^;~Q*LTalZX<sIp%u3vXa^#VX$>}v0Yf<=A(RC~rufI;J2K}d z5+-4a1zE^3X5~IC<BD5Gor{f+s~;TwtF^Fa;_97G&aY{7bP&F`B}*UN>TA5^J3L2f zUbgP6nYR1o`$9jj^zL*nOdgE??}O=L?a*Of-7|LYUuFa=Pgu?6>+2Gqy1iW!YEBr~ zTIDFMv^_z~iSobo<d<$++j8d-bR`*??V0##s;w`mW^VoVb|n*$YL6F!rZu3BT*{$) zL{(sj2->f`@K(mFY~kaDV!0cCzs0zT{-RRl2E{G6-dTCOFF}`We#vP0RLv>muog@D z6T0K+q1L}YbA0=!8t<c3C8}N4Z-(N2HjHN3%x>4JJa)>0YK`(3Tr>o~@=ED??;XDN zJ#{V9u6{})9KHIu>U@rQYkgwerZ*=Y&T0)>{vn7IsbEyl^?(Z-PCnX}0_Tk*`+Oac z<GLHa8l5+te@+x3P0WKfm@9?~*hC?>8&&q%kz3YOPgtV7>sx8L^93?on9*?8H2+&T z>nHi7p7)nM?Xo*K?aFTJj<9dv-ckC@kL6kRJ;v5mGjl2b;TW(ozv$ev@0`<{zr8I# zdm1R?KfM21pZ3HW(c6wd@9DQ0iJ7&WwT4<V;bN2YlO36#MyA#-bOW8p?zuT$wsY1) zL*FlL_@~HEx23S~!v<y<Mxr12)^@(~*>^MW94IyaCAuN|dcRBhP<IW=iEoQHo#^;B z*iVj-OXwv+YL1TQ&|ia(f4b6NpO`#qq32Ti29>0)@sPUmKtPhF40dRcxjDuLuI6lK z1{hg6$LRqu#tv9y1tbeqi^CI`%?s)tt0~F(Ivx0knJA?~NE*hlFK3Qf=80HovY{cr z7tG{pK^tt#=Wqmcy~c>Lm>^_>`w1FhI37RQFN=W`*cwuYqzt7YR$PJuaZY@xru1uf zJ9ZJpmP(nqc>KuJ<8;9JRi@0~gQVL_42X3jPBIoXKy`#M9!Y;MtP+XkJ>@dLm!%@( z<Wi5Pcqi{|PT4s3QE(`h*MW;K@zpBesF;w>vehKe9iUf-KYMCwqDj9*^%hkp2#mLW zIlatwinW}vpm;bIwDVg_RvJzZyKDEki1xV3FW7~VS@-imHlebkQ9);yM{6Poi|Jeh zyCUXG61z9faT^&0zH65rVtbaiCGE2{O$|P`kHIkhY=c{tecVy1^e0n7dQyhNK7J4P za)1_2a<>1vAjh~)s~4N^*S|8RVZE*0^WLnQ+>)8=9yRu3IudZZE`hnt`Y%)184p~n zuXppqH>|yu>RWZ1ZI02k-&}o`E5ZH51uzZ>l)^fnSwvBYue_h*A6DHrH3c9_42NHh zZc|3dDN&k;_HfynwF}ySCvEvX>saGC?w(MWiSAuO8b&FRI!NHW#qqX=+wrV__Ij4u zL(C+vt|=0=XE5|*SO~U^uPp94rtfz2)N^-k2B1&Du^I(n+lHAzg$982itfN9+L$r> zSRC}2a_sY|2q2YPnz>xjA7YNWU=D%|^2UK1@thJI9tpq%ZwJB>(m(!Gz|zSXec2}8 zhfx7GDtwfHS`Sm;!>B*5@Fr)2viZ6&!69xm2gvuyE4_14n2jUeJ@6d#8ZUs<tU4Ge z5IEjiFmRn-B@Y=J2Mx<}&G8)VqJDV_=2u1t`%(z|49%Hq0s8Nir;rW+k(mFC{EMd` zp%8-tA{d{|)oIRZ^Y{Q}sSCS>2zNUY6P0iE=XEt~q!hE>yhx%R+wCTvfp8ZEC_wli zr(n}`H8VkNZG3FyS@1~YvjyOH0D1hr1anapW>O!3tL_N#)uiq6RY0Ehj8Ec@48S5V zQqN%d0%Pp@6-lE_%PqvZ(W1198m2|1xO*MDfVjm|K(f7ZdFLn(@MKEqkCSFq3Vj%} zPjvA@?>Jl$WvwqXD7qNW*%~Owq9j=u;s;d)3ziOsT@HDcyXOdsybaiEv>qp6sSQC3 zD#YH-rF^ujWYRLV@L7I%i0}{WZ4K>3b;imOqf~5fAM*7;>QLOYz$f`@$|}!udMFK{ zUs#5--&pke<HVk6g`Xru+h=Mzy(*(wFTGdKm-n>oEq&uy@<b&b6=WjlHOfDl^Zq%e z#5C;K)tBw^=-xrsJJ{0TR)f((bHGnu%ZtwJa@<imWe5Zf*MzXS^OJsOHuWM-%F4J} zrFk#Ow6KuGA)yhc40^RGHK`<2!S8=Cf8FSl*n}W3OIC^;+tF82w}DBxFj7oc&&C7L z(@(xtKjnf{FY+)2Fv692d(S^wcTjGPy2bd#VZ(ElyP@a@=dR#s*YhFoHkBP;00N7) zf}3TVMR<zV20CSdX|=dF$sTDBl0`AvFaKup@2q+g4qo(V;%?nhIy#UKXz+4_t6MtB zr($sHCa9Am6(!P(t7Stk3xL_U^g*2*wShT`EzlpU#LMK|?rxG%pS?AiMQc8kYk~%& z;19Q)i%~kgsk;A4<vie*@(;PZHoa(gJ1J)#9E<WtbM9z-+a2xd>@kXu-+!oS;MzwQ zHC=m%Cg!%d?iI7{Mb$p^;teK>al;2I9=YaSA4<(vymu#j&)&PMho-0;$xb7p_Q~D0 z6^7%L*!ntJm@}HW)*Y*^>kj-BoZ>NUuC1hk<~T2}SaZYR8ey<UBO%HI{-?11Be$%G zxx3FrYkqyU+`ASYwcD4E6vN+^txfU%=+1E6_nOHk8>jez!+Npj){M=Hs7wXL5)=WS z!NjWI?4Pzb<CqvQkn(BcGfk&;6P-5K(2S23z9#L}ZRu<O7qV`{E%`qDdqCnI7Fu2` zi8eTmIB%@P#P0&_jIVxLIBS7nX|6HRCBge-&%Yhij)|}3a|pMk3^tYjN516O*DL?p z_+35=F7@Uw*Q?Bf<e++1!jbJM7aE+sj+y2@bP>r0G=^ELYtkp}KUbmsZq{$}e^{~X z!dAmfBR4g)Y28jpSMNtEv5{VjP9aGeB%l$^qY%WdiumJu+k0_nixSzQq%hxGA;3-y zTxiNHnT)N)iapeOR7`Vm3}pI(->X!hRv*u$u;IM21^s4+`*Ry1!v<Bkj-jm)p%9HK zKvP(ID?SZ@;l~SH-|efhjM}FVXQSV%axt@>cB2o&d6Y8FS)T2ZsZ-tr(3&&t*~%<G ze`>gm5C!7nR!O$?y6X-gA7Jo%ia@%)$9{8d@U;~`=+tNYV^x0s*bY`AQ10620n~a4 z^r}!rEeyH`tAod~pwpjYJ(zA79j#!t<LS<Yo~0{(*ymEfC44q+!*vL8`sIzw$19R^ z3+o&*_PkN7(26fa*^#bXB0Zb0>5qHEEprL(2fWuhs6}CRtWPEpz*#xW*lv%=UiWV% zah(CXcd4yqpHa5n&)236cD%Eg_}O%G<9jS2%)tM7(3*S2I-!BF5!U)6XA%la26qo+ zk0w7mU`w7ksn3-YddgC77QZvON}7acIZY+Tyx#nh?V|fnocosHGY_Ixh@mds196|X zCR%+O>LSJOqo^OfN0$e(N9)Q#X&&ak5@EuuWxM~5D!?*N%Q=eihUX=aF|=&Jn!w`c z03SK(1$MDbB$*P1Nt^~8wA>XU&f!WMD*|(bb0!62r7jC%Mi63{IuS#`{K4LI_#TlC zv|N(_|7fyB^ven{I7y^%!lS@&1g33`B6{+~65G?Fh(6=pDtf!}@LLAEq`t%wQJNJ< z^P|`W@d!NqYv9-KDH?)T3c_$^pxV68odJh7!%}KJ5&M|K$F1R_x*j)1C}MCe-GL}` zZ3JkQj5`NDOu5Qn6lj>*y?ps%;w?;%TsSr;Mf_1>LuIUzr5P5ZxDa`!8-dJPu@dN3 z`F8uLJ28p9oN1*+MD|L+L;w^&H|uA>6mTxYRG0^%7VJi+oGGy6Y6*+c6~|9VXf1UN z&6X@`yi&j&3k6>v4kx>u*Jt^?%sG1oUJha()78CA{8Iz)w&01j=!YvN%&~S6%i!IB z06d^UIUn$Z`7bDFxdEO&Caf;G9HkIf`bD(+DyVJ9LCBQ>n7agWjl0%HKiF}L`cy)3 z1=WsMF0ur2<P_x1y>{#HHc&j?VasV~H`jlGS}<qQ{loO~q0KVdqVUVn)`}pSq?+L< zq^MomH^$Q$rqdYV94?p$MNd$RQ12rY50IecNJCcYmPr$)Iv_jn*_M$$<v^!qE~yN} zz}C^lkF0whm#hYb)TzV-7#@iHLC2iu$ItP9%1^F|G(iJPwf2Y(ouzo)#`{mc{N$=d z6R~&9{z>7h;?)VGBA4=wpEfMLDGH3Czn<y*zj<BL#Q>xjk$svA-#bmW5Xlg&{hRC~ zhMVJRCLoAQ4)Hp=2`+4>Y+heab!&R$K!*0S|D3v+WuLe{Q;2fb99M1o3p?OS*$<k# zL)lE_5N+zbM@UJq>VzB9;&k<&bf^{gL{ek_DJv(!|G+WQ#rEnHswm@JOVp##oeSsW zg}q=nBiepJ=lu&*FH+Le-#n?UfVjwhL=MX|MlS^1B|4klKcGzIerxH%f6qNB+--f* z9yXr7)nW)EHBH<g<nZbf!2Ksm(%(@=#q7HGqtusv6-6LN3x7x-lHEe6&27cKwd`+r zK@~M$Z${#WwFj47lwRok$?Zj#+0V!~xS!dqohoL6F<$91E_1Y}X1~u$5nQ&m{KX7m zuoz%Oo?8FjSdUkOkEuwcyPqqc+f(_;8+Dlvqd6V2Zk8D1V7Q6ir(v-6runU^%Yt*# zu&TcE)q`KPCLEWC4R$KLKv|xTcPV(cd~wS+uD<&`*V->pW(C)WPKO+MpUs}(<Q!pt zr(gf+`oC=%nHOh2W6R_3<`cQB$7XfRoivzy@zU*gw|$ryZFJNRwj{jZ6qh}*$C`it zY&RinxWiFj72aEL;HPs{ztpZaZ07Anac|AKQz!qox;gD~_UXz!&c5ID+(^lCzU(z+ z0Jj^2?`O}x{xrjkh}JYd-x@l<sOI?w`3%R~+frpuEy~lIF4mMEIzKbfxa~vV#Qd+7 zvd4POWlP(adP~{)3)kMyt@uOYM|+&jcD1nK+(c<=>smq5MHV$uaoe}+r^#vmJ`<Vv z*4@<xdz~1j#4<Am6t~>Gt)J>U>X+@=uY7ja-#jy4*ywfMJ0IAyCpk_rwljF``r9fS zdKYlpyH)yi&GnG@#0YYv&Lr)EPV`Q94NL5QkppN7o9YSE_tP?=Hcj!~=dMkX%Ji<% z3raY$2gh<g^AujKlUHll{$89gZivsZdb*Y#<d{BYH&i;}>hi<Md#)>?`jK$@&3_un zLVA!tY{8tvAG2M8MBXOR1;9j2XAF4G!HH<L@f%UeD>jZ9&x{(8<D>U1ep|vhav+AE zXC5h#mNE#>MkrN3Tmnp5$`^(4p;*TpdS&nKjn8)U1x4T4=%896ty*%)ms73#u5-jB z(O5a$qN@cJ7_L5$H|`usfK00g!`lDNBu=U<wJs~*zJj9HmOa!#eu+i&(Q<w91ObS9 zXp#|jxc9n)33z{LPh&5S?lC-|c5TjI_b4qb<-<lA#YZPKYLCI#x~_>gS2sZG#vy-+ zWJmpVyg<%~4k2q-Oc!|QV>$&4p3!;0q;k7>OU&GQFstUEWhZOiLOEA+B1o1p&?5r= zU2^h9tRWX!53}!HnYDQZ_e;8o^w1}1!5Nu(rII;UUU{fucmLfQmDzHgrbeCBQipiH z2<anX18P-Uw}%z36`E}cy^_;Kh@b%}&VJ2E8X8w{6w}&@;R6<^oT#kBk%3PZNhGnu zfm51_d2QgRKO{vuQg6D~LJk_jCJY?ScxadGrOiXaioDWmAExE>7%nUxo83n%cnW~L z)kH~&5`!+b;O-tC*90eGc^X=Hg1B2Iha||i!AW^MX`ILcG^IRHmFF@d29NAyyTmN$ zPf9!<=5f>rj#M?C-3&roq}tpn?3Z+US>g`ln!}sSmGop*IF!P};dsJ`j{@lMg2$oR z>n?Mt@w%1qZq%WHcJf5XQAQETGeWxPK<mXHnNus2KBLf(2nipyD7Z|*l@1V^;a*$- zSi$wFBM1euDUa=RY9UyuK|Z9n#1@J<JbRn9I01a&$1qYFg1`qSIQzqdZPZC-VWifH z8}@r%O<cr?!X9>UH<NWS^Wpj-VxZr+qNS%P8j*u{N%dSMe@>Id6FQTbUnwbcfE_er z&}p{!(&LB6Hx}S#E|<Q>RbkXF#dbwZYE%CoUJx4Qmn+C{QwG~vI2=^%t#<mVASNl| zd*KDw6kq<k^~Cmy{rQMw0Job<T4y$cu^Hf5?Zmeb`<y6MXkf6d835UrmnaDJt1|bz zsCoEvz&IClq18Y0*y7q7$DC6*=l{0Fd#UuY$SmthTe?2p)pRFe(yy!KujKn}vezgC zL+SmB^>ayH5T}yQQ>oWKK33&8d1#*u!kOCZsBv?v-=B4JS)8G*{+ErV9rhwhbhlxX zos1(9{(mCCjHDdD06n`^X&F*zQ(V9`bUbR|(sXTHD?y$vmh}YmKaoz(W~njRX=Iu_ z)d-bRGhp(Ge58T{Y@=PhRnT-Sc)`dJq2)jfYaG@98&W?!=5<`>U?Bg84oHrOs$pi5 z+B}*s?x$B9bPc#R|JgiW*>+4|HU~6<9lyQ;HpUg+s5pgxrX7n%5=g)hEs2%OmlyjU zlx?w<&@T|+>G)O(@t}HM*Q%4)8)~X9*+_Mo#F8qxXj(64y{_Cku9&b%{|;KV{xJZ} zQ4vt(o#(Rsd1Tb$vc!#!KTgGx)|SXRerO73dJZ!|=3321J?4ZAY+`?;)*3c*+LW+N zf@BrxZx}aI8WWkN=8T`Wr>sccxkiu_&i2kK&0Z+4{-MV)M!i8p(k#<1We`Jr?51DB zd}HhLw9AS;^Ixye(Y?a|?-)C$YA8L#qvzUmXeQc}raXFLW0LoimQCD)Ef}>6x%uIM zQLX>oQy$Si|N7nAYT1;+o~re$5}q6U_08Wra!yvJ{XRn&%c%RexF+muUHP5Q@Umx% z7@{j0MRPn|r_I@so|qQ#%h0@`eQu0e$jhi7jJgEswnYIYjoISn>Y=b-D<97M>eCV@ z?MZ9+R&FxQtYgCtd;YZ4>+jm7a=P93l&IHlX0-npJpWGDsg#KqcDd;hKi&LdWclE$ zZ#G5D|2^}AM5|(6q&4b}?z{CDefkb;872R-m9TMJMdqjP$ybckZ(=~fnLYD9ZEJ44 zwB?f>-zN2YJoKVh)RfkoO?3IN|A%;>#s~c~s@DJYJ-J`5A+NI`)o9Q9QQU)QrakX8 zc<a%0YR4JD5#Q@K*F~n$kC5IGh)dxM$G6E>1;~n9f#_;(1+ph|z5#KbGj*y%2v+uD z7Q*<`)k`@-GTbt0+;T|9<D76ls@p@6ocxJSSdMr4VAAZb>A$L%3B3&(MikeUyCiE8 zOJDUa4)W5el4?)<^hM|+dU8y<7s7jr37r1-!t2n|i<)&G!NW(+C9e`DGh7;#5#ww% zF(2JoD*`OS8WQrP(`g~Huj{VlT40amctLFt_9ii|-WboaW(8I0#%dg>@oRg>Q)oHU z-dgC+4sx0|*wHtYnlg)YB+hNPLYq10Zs%@k0nk>u+W+E0&$%IJ$;#?U-opG8cO;P+ zMCwB9tQ)=cPSfCbZuIp*=jE7QY%MFbCxis6T>aF1binsQQkKgC_ZO0nO0Um8a+)jd zpn#NuRwZ1`FI-BTv5YRV2Bd+|zuOUH{Vkw@_R%I3=YrKTFzeX>uq-3`sV9$?+N{v- z;z8;@y8h(fn*We|vNPIk_;Pcauxid+VLpQ`dUJW`qnq7wJ3y^DLL%-IpKv}r1|LSi z)fMvU%ApV6nXP{SG+jVspr4y(X#*N7-NacFw)XbBoJ0lpqbC#UnHpFfX~SYkV7R0x zjGV}%`)X5DaR*4JvBohbXbyO5BHKKK5~qPRB0*?*FLVk5{Kt5)hez9jte6?ZC$yph zhplfbA+$+^yfwUbKzB5URU~5NwpL|Xtc1kd6>cnFaD3(Irj)2|=-6QlayggtL_ECn z)OrWpDuvidFNW*FOA)dZ6N=CiK!P!<U}#HD65Be1s55ZLcCeQgaW*R+9+H6Gz@^f+ z(%kB$xtX<ilD>_DCMHE_9NfBn+qycU#M!!r2Z+jRG|Qim6$;dbn~-qD{w%N8-7a$X z01%MC2toy&T1yawS|v)>ZL3&nL!`z>G$q;Wf&F*|F7cz064I1*B^4=(hc2G|SNP>P zM)74UD$#Y`t!pwh9kHV<<5-{s??T>LId5R+2<)U@CsFB|qtv}bkpGA^1MA$*1@gF< zSS{}yivkB4LA;<0D)1aBOlKc9Fl<1i8u;GzT$h=Yp-87~+9>P`J;ZdgRDgqdHTZiO z1nP^G6LCUOQ`~9?1|69}0W5fI@5yp4;hf~(0}T;(8EC*7v2}mhbg@ISUNPrct9^ri zV-rYmde$k-L#og*$XK*lif+Dfjf~#uq71rFQd6zIRe8QhSQ+U8id|K*e#d+3GefFJ zD{v1MiXz6g4|*o;Kft*a{|`l0Fm12aQL!5D^Pdj7{K`^j@7M-XuK9l~eFs$2=leY> zR;{fluBt%%N{}V+6Ripc0<AU##4tq=#Hth#TLnQxA)(k-aX<;HI1*%UM6t3Yt{MVp z6cAj1vWI|#8A#IqebfIrJv~Q-<TKv)eV*q&_udC8SMX+5#ALoddNqDU;^**GCK4D< zTTy=1n$vq&i>BBM;V8Tby4w7sXD_zcAIuM4<BfR=P;$-0I2}gt{TYWg&ug8#SQo`^ zi;zTPSXWsTUcyr{MhabOVtU~h0m?+|Ug95xurz}+WbnqmI7XzI?!PKY7?r@JMrVsM zMYmZdovE%z8J`l4OhTpk-}w)@5jsBnid@!@p&G~WIiZ}XE?3SyA%+T*%%LyqeZHc& zb*|(pXy3KDE1ebXn3|q<w=*`K*g~K+NYaH2SH4qpzYT`DbrN(?cjVR6{QcAO3_mdu zXs|vhNjeVPW+<BRzOf&WmOkvp;s#HKd!?RALYQse6`R^a+by3geJe)SH%?Io|BF~; zrbt4;K`JRMs;nkxOQ`N-XD(r8Bf5vUJ{uZUN8=a#0Me;IL#GI!8k~`6>Q=nNY)q(t z`3oYyp}wV~Bmw6sszG=<pdmfu>wzDHu!$6*8vGuD8m*PLDH?KD#f2k$Ye<Mc-5rqK z47cv}ZV@55$Atuj2IqCj6lAE{)>aUHq<t*~5z@3LFG5#88A0fjcOAz63x=0_h37q4 z8HoA1RBkb+D<kB3C)<aqX-y59R!K|+Z^8+^Mb!m5*p?*yMH(nFFkiTUnre$<-rahO z+IYO96VeXi;g*t$`J-frZtyT?Hs=UaMxm|VU7-7REE&)3@2LHASm!2#O)n;XU}yBM z{yn<v(A<gS5KVbHw&su-{nYroDb5oozh=jDz+8B01EZV|&B6k^k9Xm9BpJ5n%fr;& zTD4S13gbEo7JY4JU(pI#A;M8?v#GpwX4P|j-YcDgtc&>^a%5d~yLLL}0g$r|y641^ z;9f$Bx2B1gkSor>I5{-LZHLoFG^;XhwmiITrpt%yf6{Q@bzu)hIQ-^JIAu`le=h_a zKPtbn824$;)Rhto(@~@GEC1wQL$ZW0k(n^_b?(%0kS>$3eL1z;1|C)EDr#F-j@+!M zh*bM@Z4znw2L-tEeBhC!#G}ii-0FgU2y0P$ZV?Y{q$`2jkKTFf^-ctvb%L2RTYww$ z?0X;38Lqm-qrMDU8c0W#iIM@3__Ad<Ka31)qix|Ky#6C_Fd*CDGb@Hrbnk-O^0nXT zXf#@PyTmFak&&P_5aB!l+M~^{;M7&UrVltr-lb-R6hYGjzfR4@GIvmop~ByE3_=bN zQAbJCAi%58YDpt35(4n~5-@T??RHX$3Is4g`G2;JB*{dS>x;Lr%<Y;t)QfX$S5{*j zCOky3P$j}J0n`PN6Plfo5fof%xsN3X3J{|M4ptBg!)`1tO%))&$qaOAe0MJ2qk`X6 z+~$LQN)AJjcIpG%P}jy@+wc|8;I=gAk14g_@egP<akUv)^`%QNfuh-#%>Ch-|G5e? zVrtDj!d)YpUf_x2MBX)Us<{rYF4S`(0Zr0-aH_%|$nfy-;I(HaBk_k1IMJcnLv&Pd z25y9+;vN~-6?eO3PAy^@S88$y32=A|L(vi%KPm;ZEgQ@G*4T^bH}MS+!x?N`5jAJ? z>rS{`a`N+MNc*{iScr#ucpN7J7uyFXoLJ=is6`_eH-#V-qYd#ZENJjx;?`}B^PR5Y zgW+4ALq+`{nh~H6i%<py4c9h~<Z_@SgX19slhbM*p`UN-l^BqYHmq*>hdBfKC<GCr zB;feMIg=Q<%1UJyNO}d2@@3+2!ticH14-pq{2c_(NlrkOp2N@sU^`>|G;(G~Sr7-L zI29%ccOd0;2BG^6YBvki+~;&-&=64cyv3Yqv9pk_q|>1d1~7<AJ_A)v1kP@BzR?Fx z#eIi3f?TasMj0WL35bzcFjeA`D8RryKf;ri^n<sDh6Jdyose!<;)P&7x)C)Bl`d8g zfkZ<|NF-(K?5yeY@XZ5V&;rb*Px3aA)oe~))-%db2L%2#VepDP%=S_-Wg-nkJ<hd7 z$r+?VhM?mEu)1e>-ik}9a4y?b&IhOefzAe;H7MI~90f6`C$L!X5&W^|(Fc&axpg%L z0Bg-h?g+^c_F)A0kjOlkcDNnNbg{Ek0nU{*Ms1PKCUGRA0%S2D?;2<ZxFssY6Nuzt z(>38Ny|2yyCr*HGA;T3<HFx%7WaYUMSU%{$dI6M>toScn9EE#eR20v=1EDeqKQ(ht z!+V#sn1SI!pas7V#~QFtIF%WA#OVJFUFeVSmii$Lc8A-s&)#zw2x4{SIF7mb*oddk z4F)o1E_t_d1Ulj0`%^?3D9d1Hnb09nDL5R%C`Gj@#fRL_+(s}NRDGDd^Q`KZeb?0A z3cFzn;kA!9zY_q#tJB&u8vvU0<CJsn=0MXHBlT0_8;J>j+;FF*-+726iM%&!5UK)% z%0D1W%2W@44k!!WD>kwz0<VxB>|`IKm7=furw}7M_~Z4t%J#nz4g8PmJTE`5V|egL zH75)}ZbEj(#aK&>`pPYK)2}omGxn|o_#MaQ9P>Kv`F)p&it-vyf8hUH)NJ5=`bt=Q zaR;7G6qtRk3pN7^8zA-ijE|ofxH}oQh-CV9%xy6^?PR`egL#e1j}|XFwl4j`?rag< zI6H8UXmEP%CbLu6p14oADcI}Aq8thZ`)w2?9~X$Tq4613l!@&6ML(}AlU@F6I1S&@ zgj2J=Kp2kH9SIF7qjO{xb~*5hwCMyliM2^aXeV}8R+wR8J!-5VrpvzVF)g1=&lYX! z!7ISU>XA7k>1^;+<!$eC1+OQy&d{MrC+QQH+pZ7i9$D!GXx|!>Q!hSM{1ylG9&xmi z)Ze-rMXL?P{gn~jTU%bpN--rF{f&0iImpHgS312)xf{uB?I3)KTBhM{pV4(f@tIC_ zkN$g0#6Z~5o4Uhk+LKsDe|uLSZ#t37bbr-%{fQG}C#WiElHRp?In?Z4O(e69nmC7W z+(Wqrouj0a%YqY&&fF!UolHtwcJFK!n883Nfi%qm^EdwPvY=VNwC)n^fB2c-J}EPF zuOF(%;Y1Iiap34^>2vx?FfDLT;Q1{bG3D&kFw?1P>9SofTZhqTgg^?!oOZY4{^1sv zF>6%te^o1GE{#Y+FMe$c^nf$4Rw2XrCD>uPN@n}Ait6X!)wc;f!ulrGc$Ch8e^r9h zUe_G$De<dX8)=8F@DBU4E92n6YD)4P(T_@}P$|aSCHo_zBYlOg>oClrJf-_KrbiAn z3<e-*Z0Ial<lMu$)HXYaf1$~g5wd#k(f#PWAq^QZY&W?``QqE*^IIF_<qK#rn@D9p z)GF}2%UXo5RGVO#njx`-cs;6e7Kq_L=6Hk`E+9U#{w)nR@0#b!;&^o9v^U;+!%oT* zbc>_y_dR;S44Ica3VlrN4&cWGPm-RQVe+1`$SNw?DmY}oM?8hQ@0>4b<$5^(N$7VJ zX)>+$l4?9bhoLj;0I^jh4Y(ALl!lcJGuDTcV!yE(_Vj{Mrlu($(?4x`7cNAmr-u~} zQs(Gn(A-FKkC4yK#CAi?GzRoaV9CJpq26%epuIW`TLM^F>;SB8iBZU2t`X>Za+5Vs zXq%>AL%Di)8OA%g?!C#0=Ke-LG+`|O=Xjze)*nBx2~r5z^3~4RCQi3h<D|g76_;?3 z6$XJ6o2g1N><}HxZAd*}6?_<VU|MSAv1K5lp%_EI;3Cd+IKboNacqojM1v6|CB2|g z1M^$de^nv~*Q;NU>{MU6x?Bl2V*F11y#vY;bFT+wdb$Ph9Mnolb!YB9E~B?6H)5X? zkA}9I(VxBRB0~r2t5%CB6PiFAiAc2r(<Y0C##bS5yiDNy^v`nR^wAF(+eFUdZcf=g zk7GPfQv10hK2h_p6-`b4tMY48!X=pB!A3ja#k@8Dm4-O9;j$M1mvR0{e7%G%Q8P}d z24v9V0IPejno*JGMR4X?&R5uib~u<pdFTX1DLxtTs;C>jWzaH!)dbWYL1O3v(wK`% zs3kOk5alE0<9a{^>UseqDP;QSB10S>4l8~e#Tg!}%z=U9E4fjErY=X)0L$t*q``yC z#}*pk;ys8>$*y>O0Ly8Jgy2kr%>czH+1;CG9mKgZhH{f7?ID*5>lK2FOCq$H_)_Fj z{X1~~pk09PG-RtnkB%X-n8En}Kx!4PnE?w_GSFP4upWE^>kDv!Xk~i%kkB20VIa+m zsE`cfE05)LoWrxhmv*AXX@wa*0WV3{3eBGnX_LpP&@7!GG9&o;bJ)3Xg+y%YN6>}i zELv-XupQ!ze`EWg>!vKnX%EyH&X8(g>%xl>vDFqeZ&ayNAJOE$nFC!J>JU0NK)&mE z2$}U+c#Ef}EHvfh;p!yRU~h8Wz>>iGp2nh!k?#eG5-ch%9E}(hl+(cP9Ys)x;>`e| z!&`xvYIE-F-5jEb1}_sC1<2+A<B6vea&$CcxM;P402l3`2AKE)PzvNBB7i7K)C5d7 z5l_v<P~C305z9(|xirqkNschuhx|OIE@un;)sGh#soBT5Rz=nm`7b_9glpv}3ac(n z&H2DGRvYv$CBL$vBPSuPQO)%;J#uifrq;r}ODChiHNw+ErdpV4a|jwr#5X3r=~$k_ zzATcGq6q!R&*NQ2Bj&JACOp(N^KWeUtLLz!4gQiz-L8MFtczg-N>h}F*YKU{siX9O znS1#n`imdAX4oEy34B`L(7E`s%^TBEUST!4+hMhl6-?Gh!hPWl^s2x#DCX0{q5u!= zUdjr53Y#JDHBpF4`YW-H!Gy(35^zIh!JOx65)e+E-%$De!eqDpxoi568Yp*a4%*TL zCM7e}FJ*V)rd~<WnnRbnJf{brNN>^xvBDR?D!%%iq0LOHF1NWFSU%!%Wj-1_-69(C ztoIz1K`qV1<TLqLbT$*KhIsV_{pM0dB)BG%BaQHB8S0F-y-y$31)c>t7|9_5NHb?w zhh)HJrYcPhvR$CQPzTY)@=YLh!7*NGOWABojl{i>X)G`UArY)W@kSxJT^wR4qVgv& zWTi(2ck9s(c_&|X5{nPFzZF+JPgVl_jnD~3@l@T=qDb8s*t==PP_x{dj{r^+bQCUa z-*R=dH;@Sjpo0+7(L0L1uZo6ks=IVVcn8!H?(JYbctwcuD2SS8sP#_QWLbpNcA9P+ zYC!)`P_%rXbamHzw)b?I;cDCQ-A=^g7o_Oa$S<IMEcdu1_fat!X-rs7!Mu7r2y|Ex zyB9rl3XLz}hS%^M$~2cToiK-#9Fe^>DP<tN0#XH~`i0}q)FPLug(Ke$e-uY=FzMjg zz_ZBsG+J<)ARe-_;1-_g*z^7xKd*J+NcWYIb<KkcEdi|jCVxSIQZK*cazz(R6u~65 zs75?n_Cr(U(p(+Ir5y2(=!nczLyQe7K&xP`;K-nE`|kxAnRmPT${Pb@(Bdzk7P8$~ zKSy!9Ur*X^eRA?$TPWA<CaB|<#>L!)7`q`8v^2+wH85}r$jJiuLk1sQ&}NSjLrj1e z`MEKbCtu(1P@65v3gx;>1C^~Kl_J%toEh2?`r<ThkYw!HKE+uf1<6Wb!r0UE9pCiC zRFmO2T{retefC`agy#dO%k`0I0R4Y7&gT%X&zfVOy<f8+HX}V@w$}+uMv@M@^z`t9 z#H$&Xr+=yVQS<$Al2}AnZJqjOMyKt_EmqEHKi!HF(CtYM9p&L&*04&SqF){wyr${K z1m+%J(<SN2KswvYfoq;xQv$vd%b0JqxIqSGAWk71u$VukqpPIVY3I;tVj%bOff5Ql zvOuR7bNcC1nwb9{h>^k68Da#*z!+!c1WGpsPD*<k@gmpANSP;?F86_)*LthEEkH4( zd@_h)9|pv;CFu%t+YJul4_PlYH-)d8BllUp+&1C+Thn@g8a6C9+Nr7KV{L6G3j!A% zRo;PR&xk&84RWd*D$Ayo#lGza(iwu2K#SJlKoV-aLC{x0>FESmNyjw;i3)-C0VAf8 zvCvV}QEDnql@|t9;3EJm*b$EccGjJnB1MANR{^4Kx2>>*YGF&tzd-?kmKzTAd3iDu zF6&c)9fsEGCSiHdF-EwD_^&R=XLj{FA#l(DWd^t4$F_BVG3$;dTV>%==pU*u#+$Sg z3-cS(NQ(}K4zRPtgse<_GLZW6EJV5@46(=lR1_ved?dcOC$o^Ku}pJOC@uhAUQJvz zIe&qMgkYG6ia7<GV`6N8cgI)kAR2>2E-q@?*8yRa-EY%F>@4Bg)QKji5=%y<JyWv; z+{nWtWEO(rQo5v{37xDuqZ2dr;BCgp*2?0h5aBE)QIWPl$oE1eS0X}fx{sl_oHhx> zfPEO)V+1H|$`rEM91#$?A<qkt0u^Ww*vts^w^4fI4Mdw4b-PA=;1UOIR5hU@FrtqW zd>=k;^ba@nRKT&reBm*qdCC8USP19>UBLFJh1NU{U-1SGiSXzNN+ahPqY9=XL&^eJ z=^-Dwg9}-L+WTy3Oi#+}GZ!-eckbX<u;e)aFuH`qhqD%bRn(Zn{C-#@Y{an+V{T5~ zX7&(Y)0A{nLB|H9nGQO29eO0-0CFl*7HmXVLmw&#SR_(}HL&NvD#nZs0Y<MfyWt8I z9ia`32)Pqb5%`CqKqW?wvJ$}a5OlK$Xn=|?h#>XQs2!H~h!wZ7I(Wo^KO1q;$r_bc zqvThN>8Odt3gW>S)NRxt0vwk{Bq!$F4u}Ak$fs5KQ^dgp2!S#olA`dBuYte>Hf?a| z(2mCNcWB37l~Q1^1x6(bY7sPTTPjz6tcY3SpO}dFTtWup7M0L8r3%yhUU*nb7^(rn z)yRA$ls5wpIX=a4PRNOsu};x-_SNMjcw~Tpkx@ZlALyF&e@)j`3_2t07z8!rFJ0_g zILG&}xC;<v*j`M{W<)2LLV@NVcr5?e$`w!B+uP?u+qM;=NvzY%1pC1cal@pREUM0` zlfNZi3VD+L1^F?<i1%Gt$zAm?haNnws!vO#o6=1eKu7F5Q~vOoyaY-KOmvzAt}xow z>~f1ahn|G{mTy8M>~D-ifKnMZ{MJqPmeafM(~{q|e5E${TU;&l?OVdQE|boj6c~=d zug)c@$-&FI`}inkFJJ4(_rGMOPBAvyD%5}|(1JCr_o?js5f@`d@C*nvkT)fZTy@FR zb1(|Vp67Vk#ERFkhtvQ{beS?Ra0Iw`rMxTXX^HpaG~I+G?Q@_BK$H6W7`Q3InVNf= zjj?3VM?M5-&br*~f^q&sBtcz4qo>y9pxuO@Mmf>R<!g)xNq?#<V?$!GSc44%7E~2n zwfCN!W@HZzvqizWNhE6{Ricr0&PVumgX>+AJECX@NgH8u81?~392AA98w6I15fOkj z5)08<;?PEoK91!r4W{utxhTJop~I}4iQ^VK6<I;z{hG4f13l+}MT5g2?ziiD2kWXK zMNjfR0g5G9$ck`ilSY0nOV<{5T)@elQ>VNxS_X`4R<Mgh(6Jq^%lBx)_+ymlWVzTI zZsPn0+4YWUJf_uzYawk`XI5p;r$(pcP%~0gp`$gYX5@6Qf8q+w&z<c4$R~G~Yx$U9 zNcjexWz3zkPNcGCCU<4MSmzNI=z4~*i#mWDl#CS|Ji8`a_t(xy#Qawx&BH=gPS=L% znGacmQ6V?waX*agP(OOcWLj`Hlux6`0?nr<gzmShqU(p56_G<vXXFIqk0rTOQFS#u z{8=r{Su&le(RRuoXG%`K^%7g8bJ>de5cxZyrzEq(_{f48VPE_SDZldGs5(pPry1ly zxscV6ju(KOwkzXw&m%z$d+Ah}>XL^cT5;{GwB_B`=!ym;W^S3NsdvOp20CRK%Fg~} zYrLHoIhm-n{(LPTPMu=g&T+AdI8*uyzmjE~y{~S9JnRs!-7y^-sqCF#IgPVDxqF(; zq#kc5o5GysH)Iwa1Maj-He)yZ>tf`_IO&Ib6yFy`RZ+uMHnUgvv*wPYg(16hx<mf1 zc_6X)!+`z41-iG$FpyfhY2~|rT9-smKRs*j@d#sw<%o;6Ch>h&7)vFlr>W7oZq040 z=!dgzbHnW(ar#aH=>f9wC+8jR+1sRl_190YOBgiueNs+a^xs?ePdxovi;*;nc=Z<i zA0Jbj-t`X=^idusAvJJVxe~2=A1&`UD8fPh#2gq@tAu;vX8pbXxCV#Kmn~bo0j)`C z0L+j}7Qv<x6B!V)kO?jWM$PjgivkA*u;Lv-_(%Gy7xurWUbN{*N&PY$!^d9<Zo}gb zNw_>Hw{$sXF`>Ia<|WR$&8H7jL7BkOgm2T}Jlq9-aSu>t+i=ruy=U?woZ*B9o)k9R zu6`?E!GOF`4Xl@f8<?<1CG`rTk8%1J7QmP&7%xP`>wk^Gw<sY3M0ey98}-LL7ih<T z^iGFWla9?itX(X`#uC@P^Ru}Zy+5Qr@H-O7$#ApbkBjTLW#JTsWm;k4whlsYm#^CS zU|j8Y?9s>}m~f)ZEPZxJ@tyN9-29+%p`V*fcpZjbmM#=hkeUy~G|@YzIru>YtekHR zLfK&;U$9K?mT<<&kgYc})dTAh5l9ns_+ot|fD<dNv(VXs53V>9h5=FlD{RQW+v}Mw zz~Ta9kL!$Af*oq47dPaf3dkABnlxyNR^1mTRK{FEyowYeDJ}1zNl@WQu>>DP_0ZT? zd*`4Z9!gqV@X`gfB5r1^8kHeF%D{?x1Gezskb(e!0v;#5ASeu1SeILhv3|iw&GK`! z5!^Q^VNYH>r--QhUveD}AQf@fL7##Yl+myfB?{=yQG6ikugQ4y9${3Mj|bf3Fl#mW zQd$ivD_jB2%}IdrWXLyYr5H9I3WF^&tr2Sov@;RC=Z4OP04YFvb$o~kzzP=}dk}jf zw}>&`)(zbtWNQo!whu-XpkWPi3DT)|<|<Ug-v9-A_UIPLvxsP&G~?6iz?ydeQLHnr z2jlP{dX#4|P*Ef1W8e;u{j7(RpuFR!rwAtrcF!1Ymjj&_Q*#4Cc!X9|w+qlI1GJjs z6d2!Ail4+>G13pipkibajL$AeGZ|Lubj+lpJsT0Zf@BBZP6C6V)B6%!vzo*-vO!eP zcfqSfHHEjqAdELRs0u7p=shUb5vwuHIr?TgCTB?5;cFnG!{ifqC@)ngh$0I&m#|;y zQkz4MM2}f%IGqMw^LXq_+`cXE0PY{US9FPkHBhR80d9trxM29pDR%ft*T{Or7w|%A z?tKs}XqkHKS#s;1yp69rOqq#oZqiyf<(N5T++=2?Zg;5+{1N1o(W$P>!tJ`Y$~I+Y z#vSsTjn+0q;eG#;i*XEZs7KAKX}u`PoYD0z9ot#qj&cuc0A{Em0iubR+fb$QD{;_A zS4z!(@cesnXI5a_+ppN3XR&S)gDHvBm?9KQyx=|C;RU1^vXMnW;#HgTv9yj;5&ECp z0~RiCjVlsrR&f{5VOadKL@AoX7g^{}u5={F09sr<WSlUVBqRqkulk9(XizCDA(T6@ zVn=qzJ+#@7TT<1nRgr4jl4XSXS182!)5g)R&+6tJhli0E10U+mp8~5a64THFAWLTm zsPV+}6wHkxjqGOg(tmc;cl*4m3}g?r!)Uh+N%5Vb&3|>4#?|s{1`f{D-jm2gv?yJ2 zcEPyF6>en&unfiJ8XR?YPSSV#zh5#dOW<3umZ-+jUfy-KGZy(z+(EKg67E^TEx`{? zWdzR62uT-ixYlpxYwxj0u`9clA81Eu5rV~tC{dCIT`<Br<j`XCYTnyndt|h&)+i*= z=Q;1hM4GC!0ZOoJrTe*GiYqP@RN^#G?L9JuM~{X|N+b)5xel7TRvgDMEkddU#DBU# zBe-aDXj!2lHa-T#MG^J@f&O5W85oNEya>3Ks<NBnWkCG8!COk&_=7)C6)MKwbyfOx zat^gTm9R%T$ky}vc1-eJn4tAo(Yle4sI10Hd#!7#?8APjnubLlJ5Tz*&>6aZ{jEmg zmQ5m@4x_lj5S_F0E(aq@zA*xuwq`^M|FXjJ<JWt#e}y4s63+f0vFYENiZuW=FzuY{ z{)e=Sh`=1d7_Zx|-sp<1u<TCmLOfZJal+yq{ulMbGza9+l-U=0qc0v<=7`Gke85QK z_`GCN<o&56Bl64)zGQuXt@zveyP`47%P8U6px*KT?&j?vGnC)`_Gbf|Pc#SqyDgLo zWR%ai)(TFOn`jC6<q9t!y_{d>^$$l@8J+eQUUlQA_P_9cO8Cf%!XRJ)vCW4x+H^(U zv2Q6Ci^jHR>z45F;c_BY7kM*ert;!%e>R?}Z9WjKcu8L3OxaS!Rj11uHk}M;45M@# zIPVJ!yU(gE^$_sUjzR^n<})jLjIZIhXL8zJ7IK1QZ1hksultREg7G?2ZhW#a;;Qfu zcC9Xsnpe%2WDZkbe;kh5b4L_#T=S0%?A)OOPFI#ZsOV-v7()|dkjLjX|8WQ+pGfF{ zJzOsWq0nP*2wVB8YSqzuC!hqNsdKW+mFO1CZp{p9kZs1*7BvqqKmAjK>s{{SJtfgY zFG++FduxOplgA!z2zzGtP~p>p<kKije1ksK<u!9-W70+m4(6IId;ZS52|@*P?)yM% z8fWyS!DYb8*|#&6O=e=CQSy#>#;%lWb1?xo3>4OjU(WB0r9Hvh0G4GQjjlcE1!E>O z@PYU7VPl-Y$Ybh`uuB1l0Uj4C=l6RUSV$aJs@nqj$7F<+3-quZ8Pia<*KB~mZX7tX z5~S`*b%YL==e1G=|GsmX^ZJjhY+6mM-eO3I_`A-yZGc&!b4N7hv2|(rCheLFFS%ZF znA?6>HvQAIegr2!3l5f`Pfn}oVTdz&_JFu0=!fC^5`)(&X+T_;yDRY$ln20rh8G>& z?L|1G^07H!@cAcus4U!YGQ_c&_ym|oSm=HXlThP?VDpm0C)u<4qM&ml@lt_L6Ry!q z?GcL8HWF=RXbzZ~_f*2Fv3((!2)?6=VITLL1XQcw&y7DXLSHBkM*^y3G?Bi?qy#`M z?5C)TF^FgprCN#zyRjEi0EDj@Kb<dj#G=!w_-8Td3m`_@(1pdMUapNnq3Q@?9O#0( z;8&~>cq|o1{!GoEsF*F4(1jr3zXk?u_@64gVKWb48k83_@-WYp<QDUB0qC9r{-d<P zHJOk-*}lo>%J87@1Ysjr!XC<pYh)38A&F%IjE4a0L?;n3Y&7`aBCH3HoQPO*0Rwhr z$V1?Li4+r_D=-356oWtkSilC04>*5*oNqGz%^L>7=4ci;Prgt^HQa%83PonPCA~Br zNem_)jZ!9|(*i|~kG=wY?Nmfm39>_@orJ#Fw<Ayq*+LNUugadI5Hi4;KQvftnw+>T zLQR#uGmIeuZN9U`Lduqvl0t$h2}RKt`3n*+bO|sr0y$jSzbeH5A%N_<H!8g5eu>%= z(r%c$zq*S4`oRcl8>I8-tUzKRzsTFx$%A7&xe-98FkV23Wufc}C=G@*5-6Zx1nQ!V zX055RrXO?;<RBU7ma$+mxE|eVn671EX{8|{A~DrU9deJXXf@L`lrRo+FmDGbJ+h@f zy;*{PSomcat~e>VbRo`lvots0B)>q+Mk$i|Y}M#|kB3yed9nHZo4qT~jE|l0u%=4r zveBYk%ayXZw_a*T4#~AEDkLcShqd8OV0+Xu#dT`w=YE#jYaxfDRePzZ6`^A0N%Z}{ zpSO@l)R!e2jjMaJ+iuP2|6zY{@K^9**;kAqQ+Qp|J^PRGHy3H|KIHLK%~;us<```6 zBa4U3$mvPi*_MoDkGw&UKn!>>W((^Kg#5hR=Hgf<|DcM|tpp#cDQ}=gvfg7Lg{<HW zH9D034$lIT4g$=h5-xx05`XvX)u*0W7CMvDPS#+c(QxA>+NSohfGqh*1Ujb0Wh5^% zrC?)1@z>JiFdB3%1}u8Y^xVLcyLmIK|2etZ)SE3~alxj!iaIa{Su=qs0cK3b7q{v( zBLCch6^Ef$m&9ar2lP((-2J~%bC3DdxW>uDK;hj6mvw%%gxndaWI7GkAil<;{u^qO zkwhacc<Zo0q6=8X(A(K`Z%6brG<ia(ELrdkekF1p!rFx;FSz&6*A*E9ZISu{vFy*{ zcN1@>$rhvSYrx`!eJ)NCO&1_a0%!-l@eFDGP=niaz%?@t95iw^RYeh0N+#z1x*S(4 zz_u-R9ok$Q3b4kcmULU(=so<TAH>^1`bDMFCL7J~+HKmhvhKj&*DSK8%fR(5#*#}6 zrmhwy>Bb^=BFSNAK{mNNSCf+0J<*(XYQ&C|+10%D&cxYG`wwmvK#FA383Ux`c`}{& z3=0(HY{?yJeNQn-ju4p(6MoM>UEcQn-LsdbCX`6io5}v0j%I<ky4H?#3)Ww{DK@7C zi1Ae&+^Q2*jalVY+|xL#gSBWQoeBfgF{9cgXhdsp-Iky<D%x}1QKWxTokioKz@QQ? zf-A;mN|N`jdXMsRS!fV_x_tIyy;OeJi*@(0#C}GbRULysysO8A=y3))?)=|ZXXueY zx0!mHk5Q@c;+^S{e9c)Wu(6ggoogI8d0^X72J~{*KPib75s$AWz&|+CH8FJ=DIx2D zIV1sh%|4RTt(R=@UY)7w5^Y=DeJpp*z0Yd@*q?n+9)GfL>*!k!dt2uWmUvy!{eM+_ z1#juhsVslZKMJTTRu3m>@X&)FLaC_WbY-v)H#Nl+diA+Eid2ytxz}jC9oM+uF|m5O z2^Fgy+}`@8_mr(q0DBau{W>=x(rkc#{;KU3Yo4xTlc{L|;mQLXKsD2_KW|N*{Xt5J z2UFuS9)OW{+;G#zu!`%F-(!A|jI}NIPz=jCXb&!Z!d}jM+Rj{yvsmia)tGokocUbB z@G`#EzPT!<7PPb^56_yOy0+!G{%7;rbuLR7ez*a}9oVoF&%&Y$?Db)5o2s-1O#C>0 zbR^=jA}~ZwD+A@zfpO60>q6Lv6B8azJ$_)$irW0f=-a{d3w!B(>Fl52Cg`zKa_zf} zN#D+(5oxg3K>zV*{_O%V@H^w2K98O3f6Gduk{p@U>h^4PVzN$rJrzE|$f;GMMqiy- zb7oaZDBQ`bNytz`W4Y#RgWha9q<t})>T>i^KNB)_D--+(kWz^JDLNg+ELJ23DsI)+ zzxK8%v(S#*Tb>Ym0Y6X6dKnnW+zOw!2IQ!+vCLUY^n(}g2#us(>iKLvNYyYO6qd1l zfZTods%2uSOzFL`eW3QkbU37^>)U|^>!UMI<Z)78+pe$DeCQxT5K=pGhh|&jIrK=v zoNEQ8th5t7j?kSC;xO6AB^Y0oGus?o3}s{q(b+o>O?Whe!6j#VS*^hImWH&#+iI;q z^vRlrSZ$=d>k}s=Tr(KNVlrN;m%dO|_N@u%byyGZ(Y?~%rychsB#=BYq#cRDS)T=U z3RviF8Wy^<H^tO8>q=$ij$uzTY4F9zr&_>+DKksHiIAdr3Es63)rfFfDQ?@3{~}bl zD<n4}Mu$zwU=kM5Zl$tJ!YKm=yUqbMA?J@1kYOxB($7px@a{yShg!Z9f&zjD1XcMa z<Bmv-1-$$cZn}_{fNoaHwSaIv8;vK)1a4G?)dh8+mTxix(*ftVp3i}V5=WwrE_??u zH=M9TsP}Lp7*v83oZbez=}#n;*%1Kt77ueo(xB(Y#d9zs2^kBFQ9%@i9f|VC^N|ez zP8f$&FjjgJbX)v~SYxIKV%$qO5iUVW;6^OgVug<7AY2gJ7$iETX<S?OB<9axG?Xz$ zw2`}Ed(kHYgbu{13UUXz3|^izG7pJyyFdubhXpvTP?AO%z6ZB2J;xW-*?90g9C1c^ zvxBm8I6#0jRo@ftCFq2EpjgjsTxLuBS`ouyNC3c$E!l;!S)f^xG>gn>9!2Vdu^>Dw z=+T#|JU~$d?)no|0vJImXYiVc@{nuJwV8k~4HODEzGZh(&GdmFMmx->hmuqQOV9#s z#BIG?+mx>*WWXnxLr{33V`irc$(hm-j9yakE|E&8V%;=gY9{izSEZZZ=pt{`)Og?m z)8wY+-@^<!?FF{m?dDT?Oi1T~o2D2a1W{r36#nrasi%0p(;|p3iqhHYGM#fD#{!w= zjP+Td$n!Y}T*uHFyRp;uqE?3F(r5mM!K}zn2TEc8{I81Qtdw(dW_)1rUV!odJW*cC zvrrT1|7i`9e*$|xc)NVXKLMiAUv}LPt!VB7p9OZ?eS6(ZS%-ooWU8b0uyz~_kKpS# z0@<5Ju+wxiK-w|`9jzmh-@Nsmgig@|Fg(H%&5Q@$1@;kt0Do|E-`e`qH85W5=}L#H zra#)ZL%ZURhw5dx=$DzRf#-+ery$;>kQ0e6=}V3CJOdiho<lr`0#jB-kIs{__aW6n z>E+(^{>fLR=c?n#OmB{Ob963Cl~aku)`S*unZekoJc(57q-W^ve($AJ=>Y&<U#y6s zSLZ*tb&?Cwsydu&sS0!s0Wcey`{#$oB0Ze(-RI1Cr!<3Va%HN9oDg+m>iKvA|F&b& z=FLB06K_dh(yBIt^=hHV?I+zE){LKvu~AhmC3)Wa=-hp6Aa_6r45?&>r~g~e+Z5e{ zvWeT)n5c#wJ}fWKv1m?$&;<=I-u6-j;HZ4W-W?-gL1Qc4yOPmZcWw~n0pvqHm{>cX z6fn|0O$UD6j9U`4T<AYGj$|pVOE7%$<osggi4cd+9?FVthH#T)ew1k(+GF0Za)9I( z*XO=ModW?D(cK~tIiWrTGe|dC!5Qvi(9!Uua-ijmGXC-XGoBic3F;!=u~m`w)W^&g z(IM5(pya>><4jjG$v=@94b&<O{68O=c1y%k!(Su@r)v+NTx)rfmv)BR&#{E1R_pzx z+{f_qWTkPW&@o=d5<vde8#fG(@13&(;z^4yl%@ER_v2R>@}``ImY0pQ>xRQ8qn+?| zvD)i90_heu&&AmfcP?{Sv2v=93X7K%W0TL$9VlqJT}tNu#x?iQ2V}kiDZ7`Qqr*z* zv^*}NQ@U&~sc5m49be1^>oq=<%fN^xnA0sh(P|@*)Zf4Kfj_vQP^O2?t;HNmhD9v# zUBM+D8+ek&&B93a-lY4blx+H!|Ee6ZU)Y|Nq@mX74MsrXZQ%SfzWZ~IR(V55$w#JN z%~^Ch_g|IAqtc0$fgVhBA7LU?^-_MFbF_N=*Dro=ckhTELX{Ux<8v^UOg&~p=w<1; z@TklIicdL#!61tA`ubHtW*OSIQjkdm#-%p8kpp$y1?o1a2lykeX7=^1Mc*4xGg{k+ zsvVnYCIN?ZMcquzu#S;S6Z>9-`D;v`Im~%eo&<aem93gi_^+A$e|j-APLgatE&uel z#%VJiY$U=AmnGRRr)Cg>i1hMX_d$~nL`jC?;a&3*s+Je~*3`hqiEHh7t2VcIJTxZ3 zhEoA@huc5&)pVcxtOq0FJU`R$A|yUMP)(NNmWn5@bm(YzpT};qo2jX<D&{tEK&dao z@4CBaMLtE`Ar*g=-ufqOuO+0c@AIRT&wkkL609vqa(uDkOYe^KRNK7y2nhNL%nZY; z*eQh2A%5Ctg&soom<4_-Z`lLA>};4CAl(Skp`%-Xj(llNxH>G}OcNe`BsPLwm?RC+ z17l|m1$J;gmKP70@)d>2-#N?z314%GkOhlBhgsBkz#E_jCp<7<l^{1&BKh%qXWN4H zFmPj8X#9iXL;tE!0-6sb2w#h4rtrfVr%vE}05`gGRNr&az(;YCyttdG8;jdAGt_-* z%Csz|#ZX`(fc;!x@&{e=e+)w7%jvk#d9MjtvyBMXXE^zpKOb5|PCzl;_|lqACE5!0 z0o38}p)%KQI8csmHaP(IEUCt@2-NaG)8Pim0?WE*$DbIu(Ew=o<hn|QFQ}xbU;6u> z#ELO=m8Luy&7kKl1LR;zH%^~}wp0?H6nq?`=mS~koGZzefE}>S;Nyl#fM_!yT?lbK zpoZ?Vh>C&*@eF4X&QY;>4D4rC%(m%BBV&RQRW|e^^TS#|v!WD-NT1UzMEcm5IKSZt z6^ztWWc3wZn`<Xp!vh9S_?2APj^l_=2Hf8r2IOT?gc`jzI%*5>+f9nH#sG-?>&<QR zX88hhA<+WHwFC#*)_K#w3JHU-+tsEG|CED@i3j%T1%%^^Dr=#JZUfB~5=C%6$wQ;Y z!GHn3h!%PernQ5_fQ#e;#R$VMMJ%9>S|SQ}-B>~byvtc!D?p!!1#5|rL{?r*MirvU z#L9JpA$;;3xep=KY(qroLPJH+>Yy?XVy+uH&n-*}dbV@Ol`99UDt9LM92lK4x&^&y zy=WE>=1C$050x;uyEu|@9v(@RL9-6xCquz)gDi@7I9_TnAFmw{%<&xBRfvW#C{AhB zXUlDRYL^42`D9xH)NC7Qu>8`Wx90OuMo2)RZ~}Nge50fZrU_}md2_D4*le-obdREe zYeV*DX7C%C#b^5O<IhfhN(woNBrXrrNe7_sUO#oV(3^GpksYp~r;<{U_Q)gT_fNs! z7>~7t)bi_KFNOENKiF3E!%)wTgPn(EKTPROf05DkTGWFG1d1G<%YN%`^WKW6$0r8{ zf3{)dTF(e2U<e8})fH_%{$_Y^weW3cMcX0Za%ME~#(|`-uXKmqIg{XYjkf(!m0Dxv z&KwU9U?N1QXM}ciNl^h!?Q`7D&qLSdO|N5x!)~rTmO4sNB!4Q5d&FMU5Jvwg_Vr%s zNs(4{CnT(Nc~IfgX5xkysu9Q_pYcjwGp6I5ED72e*R`o2Xc)E!d|%*CBO=Xpp@~o% z>k=xYXTqJi`2mEo&zWeL(obs2=@RQE?`<4zd}i8`kCo;&^MqR<M8=FV39EZxj@_%U zsLCjM(;fjv#txH719wLIJ@3D4j+4d-VVl=)avS0nX%DVJo69GNF|-dR@^b7O=$EJo z>G#{eT>20ZnjDyt=f#zx&1P76>3<?c?}e)XWwah=Y-hsU@%#`6C=NG)=i{;G+m&YN zNSi>-K*v$xdWE!4kP!4`oOH^crd`_-`e!J<Yv5q(z@U@TmBamq^i=8L@dZD;J9-In zV-}Q8(dIc|i4e-ea@}_r(vB&bOkz%DXqFy_oY>uK<8E+Pf>pIVLHz?IX%r4_@{;^_ zAWWlddK;QRBfrZ%hE^<Y%27;DUd<8j$eUx_*J*-)ghRQev7{P(H<QVeBHiSf(t+Kl zan2~E9nipu%gC?Dt4Z3aelfnxJw3ePdTAB!5zClkT5_xtbaw`_Gr5fCJwi&fyE;`< zvNAIi0(&;~iqnOPD2x_hOUe@Zw!iJIw;Z|KCG14jG9JjJjMT$jk{m}n@KA$qWb`uw zH27_CGYO}d^N_k@P1zgTQy%@JbI{uqYCtXMTLD+FVCBz|s^I{mE6xOfQi5J1^*3S9 z!!=N{4p3R9dDp5p7&QhwBw)@a=y8~xF}QjjiUX8Fx>y{v{^qzl<g^1+X?ycjy$u(O z>IOYj(Zx#feBPK94O%@RWmP!?V3C&<dXYVc9IW|e+v2;`W1K}^N>&)%c-uhdOdpE8 zz8j}rL|ys8CG`ryfeTaT)MmG$T=ERwPbN74qPEpX8*HZv<juBvD54h=BfUIs6c&P! z%JSuQpr*mht2P^ueZ<A2DTA$et(YZk4p%l*U{iXUzhOn|*g3kyzHnen_W5BHQOdPT zjxJmmh!AWhoVPg3$`8F*L18G)Gm;RqaNxOH??7$kg_+mInktqTI<x)8W|`BIoUFsC zh^S!qUnR;a$hv}N4SM5f_Zwa{wPLz{+qmD*ST)kYg63fYnvMB{H+&X!i2qO+?9F<k zJEQZj%KNkK1Cl$Oq)9{n#|rI=7sF{7F?63Bns7ZQ$G>sk5c?sEN+iRO6=U|m$Y#L% zC^1PT&@Mjb{r9oe@lDgmFVRn-0D$%f>?c`K_SpR&girS9haU>jd{0#NG_>mPA6n5- zzA@gYam;^k%i||t=YWaUbJcA@;c2%|8%6VCdxUtEojLh;4e#p<LXoi>7QY;?Wi7^# zP-T&C=%h2m|0Zm|Jg$Vlc&|9*<5`={wIn1??8X1)$?srM1dsS$v8433syAkp2ugSh zpbZ{Y7aR)yS7n|&PR>9^?7RQ_5#5iwFO8_#lLk*r9iFWQR(d|u@Q{tYg}BB{`^_$_ zC4Oa5=+v{BE&c+v<5?Av^n1Mm$#W0_0sg^yw83^{Rl(uAplnEk?tgtz%ge|z3R5Nx z1=BS&CF=<@+^p0aT^y|z%7VC#6vS%e@UADm)Q@3BUyA!N{#Yt(hIhf55QwL7dN#u4 zi@gcP(*z};1{JDa>xH)%Ow1Fofol#d!$8*jIUVo-V3JdoDX;D~)6T@q@(pv^<UVLe z!>b(U7OniiCKyEk&HsccKi7VXufb+~)zCri5#+~N2e)Cc!4N#3KprV{aPHtHDaxHu zg*l$kEe6Fndmuk1jEe$?TKHWPy$z~1FT*?M>iEQ)0DBiyi1bB|KfVvNZzo<c0)A!I z>1p~D-wQ7ijf_yc4{Fjy);JJ5Z8<SA@t`;PC3b(uP)&E1F;btFm}Ddgs0>5)jJ-yh z;Et(=DT}r$t{#(jQBMLuLFR&Kov5&NFzVc?ELL|~WKbC|!dO1+7E*?XB8wr8*2ZZ_ znzr>u)A3hU>P#7qqco^fSQ!3IpYB00=R-b&OTr?h_0E1mg4u?CWC_ir9G&(f+)l)u zWcUyrgX<S6n_Zy7If5WGx56GdGAbRse^C3_Ln(lBk+VR;f(kJA0h5ZpH4=hQfS_KB zNer#|b3WD{DxfaW4lqK&Ag92-t_8^h8YaU3EEsVrfC&N?=Im{~#7#ej5V}Kf%w@O9 z(4%3XTasjlYlL9}nleOT+@2>QHa>gN%tsE3u#};)M2ggq92=}?TpbV|6bew7;QJ&> z(3T8@hGA_>BhOoYCk-zgcKpC~&}dAHlkaQ9LJ-qs=W*MzJ1Jk_0U#syS|W4;Bd?eE zh-01LCv3wK=AG`H?Qsz@$%9OCUi87Ktv-)1PG{T43s9{l24Soc&o_yrkM6qiO=(kp zqy&IDb^;wo@y`YZ#9RT+%=9|KM_5l-)Lh%vhA_>%qfU&j*TCxti?MgkMoL|q;`aSH zAGiMg%U!`@>i|$4e)Q8#-VP+!d?;+*46X8Wc#+5H4{em>PLOr)^LKv^uezdoD)Ijq zs+7s0Qhyi6CPQZrfW?2`K1%8^IARQF7p7WhZWx5}4X&QKdlF*~sV;#WLjkNrzEaaq zr$|XnA)-lf*7@Hp_IGpRVm-F+?SP>O16OaD<6mTnCxHwQb_xe@shbEfakwcyFr2TD zO9S`BP96>YM*Vp`$ZJrA9~;F^s163zaEK6Qe073tckfuWb%M(r6)J7}+$fX%t=HIx z(HO&oH&7hCSX4?y955M%Y<XOFIBXn{U+SC?U%g%yn;zbA6xw{^iAmDpU=1!)6<m+L z8!KQ0LN-7X6N?N-1QavI<=WrsNm7q3MJ&sg_ka%4iGYtdIs<JHaG{E9T~H!DIUE8t z*y=32d^4;VvjoYhdY$XHd0S7Lwn!DZG;7F>0h{IgcLg-8TI{541FIaIUK!bITY8x< ze%JD#Sn2pc0S_!>v@uD`>j?)elv>-KU#{B2Yo9eWNyHx2;}r94vKSJb8?JSAaSh|| zP`TeD;kS)Mo=Kdq^hXsESb4;d*3J){7KlM6CFQ#V{ri9-VaOnY`JKbj+c|)TkhD1q zWMf$(jpLMIsJAf$92BUpZ3P3QIhlt<#OWJF%`5P@N3qNy?13sK8?Ou}5Bv}0HBo2( zSr+^?Wsr9mi@u07T)t~_;0h;CqO%DzS35%MB4aH6PS`)gDrrnRt&rioDD$<?ImtM= z-+ySaCqp-JBnxg~HvJG+Ho#a0yD33vbbsQH8B2K<L=6fLouA+IJ9r(p<Phu()_kiA zox1*#+WY5VZ{kA4$V~QnJk8L&l8-kWfWT%!<rcIZ-AHtebY9h|siKjkgU#M={*Du2 zaTgDyZhoIpb2-D<`TA5`M;~op4s6+}D==iJbl}3t@-!Z1b?HG!d8T;sl-Xmr8!f4S zX}xtFZXZ-~vfJHvrC764&u4DG%)JPdoL2swHo;VI1|kkE+=+*jkuo1eJJ%M%h&iQ> zJC|Sz&UlauzbzxhSQmcaBaQJ6E0%%^fP3Xsr2aZ@x&}~t?8~kf?*DaC;HjAnhWtwn zVqmnOct2AQ^mCH+{Hhv!XfnPAWR!UU@s6yN@0Aky!uT2(Geiod5Hk?!3Z4>BXmgeO zbDNX)3qSi#TyAEsYy;pS3duwbFz7Ac*L-0(XDv4?UhNg@cfJPAV&srL^OJE$BuDD! z50|D<!xu*T?c67Y-m$z@BZ%mK1n)KZWDLqJ^vDSlJrBI!PBc7uDa@R@ZDV926B}>G zy@a6uwkOatGcac3#24q$0pM=a1zefcwE6V6da@~)7I4c>cSIjIK8=@L7`W%}YrzxV zFzmx?GItCUT10#A`&@U@n!55-YzqRS(b_kH@UXIxtO;x21f{Pkw@R>@ECp>v71}fF zbLPPb0Q-alPF^!@Q@|k&?mlEr9#3~~U%sk@{q5<Bhi8(03wHlx@<C$!A+9#okjFKb zyG_M@W<73Oy0$InEkpA?r@tqrv*?_qY1pi$s#X2YBI=s4HdB`IATi_xs@>l%y}$dn zq0@rTE?QpRJT+)3ob-w?oWTW0HQ;iq#V`fHoTEK+FeV$5a?u`TrCj?eEqwX%SqJ~w zNaDQ`{I>n)E0houp(N0a!YYxQj_Be@gk+&J<p(Gh%-dJSDan|ai7*hdBajCC<|3Ta z>&vWhf8eDCO(U5-V5yV_Vzvql4-z6c(AC%x_7P`1=z&cycqheRW;)$c<08#5P2$Wf z<N4SiBjQ1q1JhwF3V@#&pm%Tqt*oQ4YMbIrhY^I)$Gxrsz2?AVa#6zrN=5Sryc>SM ztmfVb?0{Tz+4JIRM^q^gqhG9_y4fWR?<TJHKcP5y%bBS8IzQkR6MHa!lvZ=^5S_sH zt~jON23uT4+=Bg)>t4n}AU`e;J3dbV!T`TO+qkuWnlSnnCB2+<;DZSglLa~u+-^}- zz{IgOlYvKr$)qBbF$QK-&?wq;AmXXJi3%XtP2~+E36m^ecGChHBLpxa!dQXl+a^Ui zknp1sOjH@LOxB2xAJ(qRd@)<-1ojA#VuU~<4u3mHcOcMDa>56q;{sl~?@({F8IFDx z*6q}sFc>;0BXnNM0?arW=lM_&O1zVpI_jX|V_rrj$R~TWqtgf|lrjfAVp8C1XTu^o zu1C@<@1#R9f)>P03T7LLP1C@`L@DV`^uLidouDGOp)3KsZ?$|zWJg_23p_^l_AC$` zu;D@RN1F)}98hu*!C<QfH*Zv1f5(fBf%fBZ{0tNjq7K$L`#&?8h?UhCQQVQ!k+<aa zi@6J6a)EP5GlWf<vMcgO0JG;;<GJEP`!;ZVpLzHZbN-2EvYIHD-$HyOylwIH>6*zk zf;W=06jL)QPH}j~4Ajwn{P>1umc#r)1R!_VQoifxBd4xiX1h-@A$uV-5acsd$)0pg zlL$)@<zhZnaBlDfgBHlt4A1eoDcp`?8sltx;NNa8rGF5gSG;OJVr<+oy7nA=7QB!4 zRWaTiBCbO$Od-ANtsj=Qxn*m0EY6Xw<b-Du$2v=|C2vJE$a*?RTdk@ikHW!&;2}o8 z&pWm8VYs$JvhBZMVG=4CU(B5M=3f;Kv?r)&2M<NtxoabJ#O9%u$GP5(7J|_-x|RcA zVI~0<P=|RCBlrjGJ;|WFtCGb&BpD-^T3`YFa!r9UAV31}fLM>$=A;t@6f98v9Np<> z+%Rm+(p=ct9(!GnK(LyDCW0+kLfF_~A;64)^0rb$+!f%S>!WoT-kTzbInW*a9uCja zMdiQLUAl}TOH2oYtJb`(s>E)9V{Cy_1A@9==um4+VgsacVR(h$OxB*6@oCAejU_Es zQi+F63`HUK0I@`b2Z99^)3m$zIOMVc!Y+Y)6ZgiUTw!OZ(!Wu->a2d?-~J|NXiqc# z>473gF0zyb?>CbPrVwj>jO~f3L-Y^KwI>(_On%-JZQYO@`^zcjT7axloCSAuol)q} z<+3a!4`|Wi_9V}vbd~*8E_?W2m7OrUs3~+Yj8D0@l7r3*20EI-1h(+Z^r3WQNwtD$ z!K7g-kKnB=BVaq60a|r`W#Y(lex>~gma&E5>PG2Z+q&LMU7HS7M1Sl=Gi$iT)2OPg zj!TyXmL)HpSrIf!6RpL=4<M9adDgxa<?$;QOL@e7w8h|CA3aIq%lP(!XX?j6Ao!2c zyNf8?JU|8GwX#gN$;1jXS5(({t-XRnhN@?E0gWnYaMdUfW^}RRNW;@!Z?xkaA=~5N z%1odI;Oaa9*jx|tJZ11Ra>2jQ8yyo9xA*E|NWB$>N~0;=I0=@Q<T*>~3uXx1j7=$| zVQ6IV^I`)p=1ffMF&yP!43`xxb{8J<58(I_!xAai%^96rE<^KV>)MKQ%m!axsI~;7 zk5D_@zE|@8P7miB*}kTt!mLO$St&ZJ0Huq}d9Yz6UYGltjkWns6|lmBwyRDuU<!6Z z!8elYw<jYnZf(44wT=#q56vt>)iF)(dSL~7{<JBy3g#WS*~jx*PJ<<GDlcAS5D{$) zz6#TkEW&w#D8ikXQ03O(**UD#&LO%6WaHDmR==mFDPUCNpc=$<dTBMZjO*0s1daRb zk2;{JAc8qDtgSVft{pi?)^`B!y?{y?RQj&j(AoywU2bRfi3-_Lx3fM7wsSFX<E4%f z<e6~E$Jw5t`W}EXiCy>%Ry3xnl<UnJXA51q7&Q@%HG{n#{C&77lOAeCIih$*zk7Z9 z=f*QDFH%Q8A=_T*1lMy_Y%@h!^V>c5Ubd|xv!{?!gOfDe+(E-!F5T&x@!>x>B}tbo zwM43?R>#M^wVo;czz2)~bL-lC-4%Z?b)!3JS0P{J5ggy%@Tl+!fYDfsuz}C#C$4{P z{>MI1-IMdvfD@<oGBG;F5AmhG`)jEP3FJs`HV+v(S!1mGea?~3M;)bqq9~O1c&c5H zX=;vNo>)1-3r~+C&Z@{}em2anzZ<my>+NN1v)hKZ$1iL^9<8{2w|i4u7oDcq#1@`a zH0Pb(&uKwT^7^nsZMw&Moj*?lAQAjQ7HA^~1kYF(o(6-vl`%t{qxLUEgX`qy$$!ua zx9KctsuY-rqgetRdfFLv!9REky8*doYZvXED*jA)LjO8gU%R3>?vuiIs3&H~A~Xyt z<%En&`XWs*DTEjWi-XC1XT)AvjV+myVH5e~7U#}X+Yrq^5I)1edaRAUxWNJ3lV!(m z>fM^VU`MQM>{zC~5QYf+%F(St8M;Hx+A%#j3%S^VEHLnV8PnwkksYLzm?&3|8HaBm zG<??Ift{IFC+Ula&L(2jZT?OzFT)5RelSC%f5_2hYQyP&7V&q<$exA$@2+`j1h7Zp zI*P!nQk~NP6%G0u;Wd!suhf;X;EHKN<oyLj7b%kE=a8RccrX1!TdV)y%E_bnGhgU6 z?@5vA_UsN~_c375k(2XCsJP`?L6Q18F!18(!<`8h`Ow@UOM0205`f{02wvTsc_@v< zq>wXGKK?!D)*Zo1!yhfr6r(K6dq@h!z6@du3j0f7H`BiIY2vrT!}uQ1N=Sk7Vs>bJ z^@mYx7nClbRwFQS0gPCwTcfQF3nre|27n(#oCo?6q_&i4<P0#V<Q+bXnY?vUob_&) zaxjTlml+Ij5X@Auu`M<j5=ppPfQJC(Dvnt``15Jd6k9ED5>C>@vM5KF+e|A!84_`A z4z!M305@>4fm5usZ_iq8gcf4G7`XzWLV}f)!PFqfSsLj$!K6bKC?tEhE*qH;&O;h8 zN}oQ=so+IuqKTWce=CWKnL!K-y8Mtde%3s=EA%P@B}Ab$co`|z)ZXY$;-1}cRk#7j zl@;b>9t3Ft#KWGo3SQd2@{<Kci%th}mLB~(aRtAU7Yc@9^BoUGom=bSCGWi-_TZ~G zprgGbGYvCDetifl^ygVK8<N!ERx-|unc3Xiv_;T&Xpm$|{EC7>laIrZVcNku?-M^; zqw<F*Lfsj@zq;C=L7X}LZ#y}?iR!F*n3hNHC=}RF&1t_BMJxM6MG9I79#By(wJ8OZ zTl<FNSx6NXX`N&UecmZ^<BD8i_wGOaivPQs&V=)uD^}K>rl0>;<tH;ZbNrbA2T9-n zK(wps6^l>PtsB?I%F00Cl@iv*Tes|opC=Xos?!Ovc#k+(rYmppXHd>pYJbHU8Gx%; z3@2$vSw`BKc^jX-ekY=_cV_-hj|FKknabP2fqwCA%%k#>#CuDnCp;MN!iuDu+CFXK z94VSNwdZi8#cng@w4zkf0LSsv>Sp&*aB+{8(Tk2M+?g94K9OX^?VUS=H&+}QE_wI0 z+oS(Gx(C*B$*L!%SOdVuinyF3YV$(B*2+-IM?tC?Q#&WKwkWu-_<csOPB?kuhlCIG zRVL}&r;xt-YVf5?;i3|@{Odz&v}S>h5m#GKU@%~Rw;1B4QLIy5f|!}Z@Ta0iV&bI# zF*HtWafX)3NIRm?iL-xo2+sKGBzH?Z?(G$(H}amn_QeM&5)nLcDPBhKh*q5H8COAa zhz5@%yAyqX;KSWlt=BS$=}I(KZ1<jTow(h_`QaUXS6Hr#>C@E{p;+ZI(jAU|>}sQI z*T&%U1;G#frt|t8!bag*K~2a@Z#y1M$G7xMi?oZ3)9&tL?|eO!*njrIelsjmcVh1A zC%exLBj?6sLX!UpWD{>*m39$O0u}Z1a<jDB8s8ebUl5H+u5c|(vJb5e>|Jz%1g0gH zWWo-t7G3V@frW)<TMN9?b38Re%f&OiVYgXjH4X%72nDB1BIlvUno2Z_bq?+g<pS=< zS7asx9G15u??XQG@`w5>pVTLrgKurR<?qsgaP|$|4#h|2gVr5aO_b6}U5)=In(*EP zEss1%@n!Etr{2RmEv}!i?vhtGOtSY+cXeMeGD*XYX&`xHmEA7a?+oVfk-JF~V#C$` zIvn$_%2B60rrpoqbQnABJDXkKHc7!)g{!XUUgO%CT4mR^58rtos?Nj_xh0f8N%Fp? z_^lZJSv?{|^5kcmz%XF@)V8e0@qo-K5BC5^h8Y(n3QU?_Ow>#1{0b<vj12RVm(*+k zO4<)k1kwt0cg0N%b&x|6Egaktevq5O1#pFr!6{c$7il;^u>^~$nLf^Emzg0Y`0c0D zXxBbQr+e5C_A-fV&xG&J?(KmqCeD^|arnu`-!g+4ErxyfMntNJOS(9_?F~AC3k5=l zL$GT4c$8<7_+}ey3*f&&{vTe`_v!EbXlW}sQ8VSwZ|qNM%=zI-k^gNonh;@^>+<<2 zDmm7BP6OJM9j~e}=FEUtC?v*$9!>Ad8aB+@o&WsFpW*+iC?5hy>EJ(5&tjz^T_kgZ zS}>V}0wXIRr$|8aBeH_D@$~;@c$<d>jigJwnW>P4YfuI#2<#O_o>K|!tf?QuHql1J zJpxc$xuL<5^?5n094|r}<D%yHl%=}k#>F_i5qAfe2!J1kg26nDd;F&1t)4FtYXcpv z=6!b7$4k&_vzkkJ_?@F{nF>>@#s?47S#K7S0Q6TfVd;VSUp}x+Nhj|CMjd-$--~?h zhSBUVS*D55S}?7K)ESPAT$cc$RpiCE+Eklf%?rI~kb;4hvLm1|pz-c<mE}guP=ZH3 zq`;;@Y?>aOmJ$)2PVWBpg?{B|axJ)sD}2Ecf)%pZ_?p!aG{4;NX|DO~hmfRlD!CW% zUT>I2o(JbS9uu~#x9X%vBV*7_vbNrpPT&#@`_%Hq2wr-K19P$;YUA#|;|f`sV(^Tq z$2G%`e_lE9od3O@z3x8?bmYIm*{KZ{jejD#|7_Tyum9N#*<wXb*G|fvt9vqjY%kcd zUA|>#VW}>TNLui>HyWppz-mT{O)fBDf30{?^}i`Mjv|Vl{3DjG(P1>v$0xHM(cfx6 z_Fh@Af4;2tYhsjf8IPBOZXl^=Ecbt>vqoz&bLy(u2Z=70<LJx&uTMT6X|wLO2GCIM z_ALtUhDn}}Utc*m?j$T$2YL3GQC6P*?y+Zs@2$o`Z618)qQJ4HYtRpGtsm5Fsx;9^ z3c#l4HctVnzrp^Ksg(>{5Xp11e^nw&W0p+q9=7M%M`>f3S{UyC@o8FgPlsjM$C>+D zq1rrfq&g)7x|mGOzJ^ZTjUY<Yo_lI@E6?l((b+;4gBtXm&A>-`6o1~`qVrduOeCG+ zhO&KO8p2VOkq$-0jg3dWSf*LXIbc2_1|y&xPHv_7R%6KAlBVDXy}?147QROB%`RB9 zEIXDOp$0|tF1#xi9;?;7B*w6Qyu+NnP-Q|i7lSt_JC`xA8ZklC)=dR#NazSN))QYU z>8L!PWu6O;nwb7IHho}k%&^cayoeB)Jr8r(729y;5nHvlF0<;Vwky8J7%=!-6sEPi zCFwMhtj!IXf~=;ya?{NHgAIzSgi}>6j`ALWx(2M9O0MnK`6reD(H=E8ixtj>4}|OS zajpv#_no<=(O=l0!G&QX81c>5VWJrZ-q{X`3wiS7SSGND*j5Ffg*}g~wWSds)oC6l zj!}9E7{PpjsD}3(!6axBgpdShPjCc~&!DCXOE^@Ez14Mtp$nGG{1&2LhCXPi6qSBD zD8BgInA&J8|4=|)uh3G0i6wZ6R?9np6cLwQTtp6CqRG%y(J_HZ7KSVW%#ydbg1il5 zxYTcC<wY97zffi-VdsX!0jyG73&=>cSRrz(p*9%aqU6NUmjY`vDa_mmDI3#9knRKj zL$OQfO8~R*Qr)c<;@+jcEU-j4m5?QY^%@UDQdF`IXkg$NzwJonSTG@6bU{u5zp}al zqpkMb>7i|?VYy5)sifKVCU$ux0njNA`D!f#yloAK&P}p+@WRlF3Eb8@=Z!*rYM%Y) zubbcXz=Y5P&|3%;ohO+4?|+d|;IGbZf3$r*q@ZQkn;pTd@0SSM3p}2}N|l}jYBN9- zlhsqPvW+QT{rk3x=DnA66uMg;zfg5B{i^2s5s^iUOaiOiJLkx&Xx`R$;B)uynXseA zN!b)C;qa&XytkgdG*S4fFt+|t{q}E=zh@0oi~iSaX>j_yC%>+u5ie!Bha~;%{<Ia7 zFU}3pmxg(L=AWlZj7>hESJZW#(pE$tp$z(@KkjDusZOFR%JxK}R<(mW9omVfNX)mg z6heW73h=EKRkibF7pw7qRhF|G71Sp69VMJwh#ulEM@<%o*^j72rH`77`{$uuPL+fP z*S_cEpNYQPWp}_x7!D`3q8yITzbZ?a^z%a-kZD1~jCYoXvB6<kl<CL&1v6U*VqZ_S zqXyij%>y*Sp~yGoB;D6?u#79`ouz1jzf6gxQ7VaA1)F4`u4?;hg=7%Inq-hFn{!V; zYO)!7w-5!TpFg@Mx=K^Ryu#z{m|XqVHRC;}lB8U2)cYNW+6{Z!f)$1Lk3V3qX*m4i zLsdl#VO4J+rl;=5|2VU2rMEv;v>E+eU4h{r_U8W>t(9~{(#HduR~Rl|#dyQ`p2y&y z?s19^{Sd^8wd@MvER-=VgntalCM6%pUecAz3MuV#^ZEaer7w?b>RP*wh*h*L6|G(^ z5L<$b!Yf)88VFQqNPrs#6-1C$pcIE92tpJH#kNj0kuVjh2{I!H4tP~isMR(GsF6w3 z3aErxLBbd^_^nO9-~HoS2Xb=GK6^jUde#u0ikCewS#dGJ$`{{R0zQ_k%m1*^xNoo9 zSDv%k_Z%|f1EVyt<P3h?`J2{Nh{kF%Q<BJN4;9=y%RNcMT5IIk)Oa!aBgsikMbI4j z8>54-!W*rO&IU;$LgQ2?)D5>_pbG9b5T1ue?q0rmw0@FTOD67F2p_L{)(Jpv4jQ0i z^+a9jF+T9inW*c)leVf<ToWN<iUDo-#mmx#qj(cgRzg+*57t{iU%*I94vUKk`opMX zh!cvX7=)j|G~H({iUoiN#u_N*kiqO3;@NzMCF2inHvPfy-p9#+PLhKU`3bIN6g-ca zE@%qkt6tX;GZ-;=H4EQSRvLZNiF)jS)t6lgVkxl!b9@vHik8|><$FA)P9P^ljTjri zZp7OKb}!tx1yJV_eDfV8&j)@qGVB0E3=v<)&Rx*txLf*Cz#DyEJk+BYD%@Nbv=lcE zH5h!W?v!qt!L>aAE5~=1bGefXs2lSL!d1Ig$vzvY+J39`gV2VDKQAdGW(}HPf2bqW zge|H4VcYA`+p3UB+&t>2)z&7wHjhyN5tZ9?T<fYsOZOC}Ng3)JB5(+L0S|0w0x=l7 z-Zq%hk-L!t1ho~_X4~0dZ4cRX!D*11D4ZIpBg;kse{UH`*F=mGjwVSI6nzn5LwpJP ze@hOE@x!Bl`-euJCIJCVgJ<~<d&g@ZaZ-fQbH<<nL27H$d81Y<o6_%fgp9Z7G1@z} zgTn+LWU?2YpZqQU5wN5XaDhf{4g1wyK9ad|PiIm8Gddydig>q=T#@t2N$PYqgh-=S zSyyUm-)dd}+gEG`3Ms5HAE|5C&oRW7FpTG5djyCDrmXCsfB3rx_bL*41b{DNwAN!k z9sha1@yH0C6XDrAT8ag?4@AB+vN?JSUS#;n@DI9WT(@oPINw&iD+vjX1g=C3Z0xIk zt2^)iZF`Ehv~aAr9MKWAi?s5%{uZu)Bi4M|fSot~D|+sKeuN66nl$B=vHLF!Kv2e$ zFtIg|F&wyjt99*8436P!Sq{9~B^0uZ&CSjR?Ocn&tw=Lvvea>(`I&ztzUzVL+1VNs zBm_!n{1aGO`TRYpY^Xqsw}0g3%k+`D&A$?g1PB<pxn?Z52X;6%Krn5}zB6Z$Ie`HZ zOeL^|NoxZ*mwHUQv!xj-U9V#r_`76#z(*EebtlFtSg>9Di@n#B);}h*wUg#XCx(DR zd0-Zhcj3Eyxc@9bP6z)4@*mClX(&>GDe68K=76@0u@)H9=rlN!vEsX)_<6`x4a>ZC zVJ3ByS(iG}!d(NF6*!X|+wf49YmE28&JbP30gh9`ME5GmT)LJc+nzBIkrT2jaOnT` zW!3Mi7TN;}4`iAqe@;kWQB`|q)~P%avR@`@gO*9+zoBarvu^m3eym(EY|l*J6aKNu z#Ip~4U;X9YO$M4WhoRSruG!v9U9r-@VXW#W-hVJ-<*`+}bED^Y=N>HLH5_&YMD?r1 zeFn#Ew-$BK*YziBTR?T#9nr%<u3kAy?A5W~sRQT=V5zu42hIuFb$mP3eXPT{N1V{& z8G#r6+whQ5JZu$X|C@djLqNTHp!-;lct<m@W#U(iPOz;)9(xFX%{1|8*>^Wq2e+N& zMA1G(x$au^^vuye{08k<Ag`o#{LTA>@omx)NwX~en}tt4M|ngnmqn-FQS94_i*70J z(J-j1t@;v+=8vTK-)A$<?%iSFg5DBPXvY%Ms%+CQ7MvPu_JspxDVS0#&BNixBR1U- z{(p;5+;E^*BRjAuqp9eio&~BX+ooccwxV@ykGcVgcLjMD#*mK}0KiGB5T>l+<f9~t zXTLBGi{)ngoiPjb8bW^>P%^sxpFVU8vPr0}v3!dT;-|-xy>vvPbqq}>1kTt>1CS5m zi@|F|VZlQ!5|+6p*2yrvkw7AqxLKt$xgdN%2Zs%$WMnww?Q`*%9ZBivFFIVmEEMiq zIDJN^W0<Z<J)sZZ@ZzBexr!&_2TnmZlpa0+V&M9H+MjIuqb3(G^L4T{gcfrLgF7U* z?dKOhh?tdWJ0SBz0hNtKnUz6#mIcm4Sj>Ldx;2k0QIQ?TV?j+OWMWqZOL`IxS@@-+ zMWVna#SB;Tm}TTo&TU`(t{1H!oMN{HrYbD>vS6r-61R|O{WgG@WI$5IkoWLgCIO<# zLAY{6_FfFrPZ^8FvXdz$TwWk|dAM2pOG*am$j_=9egMmwo<W&;M@g8w8$-JI%Y>&i zv;`(N2+bR%l>&dGLh$t%O+7pThd>b_eC?w{?k_Z*`f!)Cl4@_Z;LLDf(Teabi3$GS zlkg%|2-eGCNXMq!pw6C}?tVJ`;7apIKh(6>3q@PxJUjOucXUrhi5i%ibrh?YjV(+o z<9yS{s{&{K^N*OFPA6I;Qd<LB!l1cR&{Sq4RFWd7czDO`{ztsMGsz=M1e1ixhD{g< zmSJ6;Vq?{Ft|&2@fLb!9@Q#4lme*EYYBt`ZkYmqdF*Lp39Ar4DBa5X)38`~HmMHj; zZ?fW!c<St1*%XzJt}QtXu+dX;zCKJec`>LCtzd>O1cR6-V_79M{`%p)7a!&pcPIR{ zWfF`A$i!_Js8jq~y0*N%^rL8Led-c?DK7OnpP^Y9wE14uQ!QuVP}aHj&MuM=1=eOq zwRE51;kw{&d_69dDVr+-rJ-@Xgn$;5xp1~-L~EVEQ(67lF$GU5V$##$@Jf3RgCpQS zJ(rZfoG`i6y>M^+6YZL6gc?K{X8r`_EbgLZiiX11e<NEg#TZ#hW@ZGug>JCJk-l_T zv;?Ep@qTckYUf75>|-zfdrNcW#TWXM(Msw~xJw1cI#G|kKG%1tSgO4MI2hycIba)6 zx|`_wJ2ai}956{&r9EEW3XFaO^d-}shedXe7*{5Djdr0fSPP#O#X67sY0tX3#t~VQ zeQkyPRwknF9*tS^zHjNrJ<aT!ieZ&>b2I<(x}>>C#b`4+n=yvU1*H`?IN)>hfvL6Y zM9ptI?h~ZO3_gY3Bg0QFfY?Zj=!b%QWLT1@Uo6pGDrIP{DTdpvqi){>lZ*`TtOx$I zIndncId~xIws?|f_Kxz&rSE8%_2KNV1nhmwzH$@tt6-8BZyNRGNjVsKczN+kIa&@% zW5y@f{#Es?AQfIZ8_+9?AgeqZ!lV;-ZSX-K$hDend=3Ls#edlK|6)YVyxSM2j|wA( zd^F_{4Z&xxp`|5m-CHOuu8mt+a(l)L`St`k67lfjpjvmdEUFldh(o%17o1#6#yX5b zVuBh&-Bl7lIrl9p66{%rN?(V;xC5hPtnmw~kdZJjAtk--r&*VrI#d$8uLqpigQxq3 zLjRVViOq5#AQS~*Ixg2PPUWg00PTia;{5mBUd4B+Mj-jO92gbaJIT??pYyAaS=<3g zUBrX4M-wU+0Q6WQap`e}$xIYJ&!h4BZW-#%Q6awq$aj^RjJYE50mK^})d^>--?<y- z99Jl<!^m!An2UK%QB+{?kK;5R?1Q**e!*9Sv)%9l5Pt$^*US)?wt_n37D)P-L1~&s z`L5L-U7N@xLG^d8e6EHfC@;qFLQn?q<<*xJJ$UCl<@r#6pm?_5jB}OH)pzs=-oQQ^ z=;b7FQyir6^{`rq%4Rl#=yXV94sv;o599_Ybo{T8YF%}s06_(Kc^ZMz{d#H;Vq0u6 znE5>vzS`0&=!Zsahi>#7&AGs`=+DX92Hcpro2fLo=${ew=>4jXSca?jk4se#P%CLV z6Q?T@54TrqSSFX#H3nF5n%PPHU+SC$_m0pJu$aS(BQqU11u5-jc}^TVs7C{R3s!lY z`_8xY)&3d5pB-A08sSkTP)MuAEK4VaPw?&kJ?Xy*x?_fB!e`rx#jpm6@nOR3dnMH{ zLrN=X%rA98+BUr=BFByL874^<qTuDQ`Xt6Prps4=5zpXfu@@~Sf=7(Q2lzicq46E) zHAh=bidX1?w$oGsliN*aQ%|{TH7uC2gy!ii!tw^~-;6r`Fl);oqDEKY%&~~<zU$%g zjrJ;`oEWft)Dz40kWn*UgD@OVI8w~X!37v&@e1gB3$UBhRPe$p1KNu~7kKJHuBLzi zg0ntGRw#65BRum@Q8;!2<U~9~j&JJsj2Vk+ALpP`4nlkIn26Lo@5|PqJ0323Sg<k0 zbA{a-nRDg+kl{B3oOkl!4^SuDon*v&fVM;$o0MC$*co{#8ujzmLT{h81g7NNjbl{> zwJlNomqlo#bVb2Qjc?7S>RJ=MLZb?2u8wT^+}5^H6^s40UK1;<rxysT0*3tVVzChx zrd_d*?{lvpO|ItoTQ2O5u)tdEEt9N#MUTnu{VyxPdU*Wa3;j1fml8g7pTL6O;M>e= zm!K2_9^FXB1<i5O#m8PP;jE0@F`JcZmV>hq^8ELoT^TyKFY8<dydVt?SlGvew|Glu zY{QcA^6}ZypNBjGz!4{vMoHFWTjcIF<7*UV!m3~Ykeo?q{XLNLOYA?VKL~8GM+GwP zYTcJJFI8(hXZCz?$KzgCcxNF<w;-|@Fvfd31{XZ$pZk$#rcv>4YC^XPpE1eku3oq! zOZ9iC&wcfQw(7Fi-xsEmuVnPC)F}B}qQ53L(Q(Z3G0OxFl7XDbcpoK?aJE$8i3c!B zjvCXyXRnr|+P@B&79~<qHia{`2Goj7)XQ=H3_YK!10%MSeseG=pJ9W@`cB)i7U=fo z^|o$q6W;~pYFRX~VP1{~D=!aWk%QXs_2#@u!lqYrvA+fG1s1*zvXoFwz^w>~%w8Yo z1<QHmMcTzM^)D>Fh*yXG`_hhxeQ*e)Vn$DPslPhHL*G%1-(seG)`6-IEyx6#+2Qkt z#mgWaGH}Neg>U1ZGs)j+J4t<V%j(X|nf+SNqZlS)58&Wq#F`TJ=IpJ0I1#7L@48Nk zrpdVN(5ze|;gX;Wjnkljj_PfH{^6&%Ht$IkhCP~2ls`C1{gGq$*%s_x=hEjq1aB*b z$StLg3{VtZ_6$|9o*#Ty;((>V@nt{<#9-VcR9P^55D%M=ldcq=!EGmmOq6`J7gdbz zGEkHH&r_(x=Fr}WHy1wuUT!yB7@!=&Ocw*Y+mP-9Lq;e<x+Wk`4=`XeZ8?*0z>_FT ziDjlJ9D0TlQ0B=jd2XnQmoDuQ_(_FC$T{Bv3k6p&^{|j2n{ZUXlH)qBAPsYlC&YM+ zslp5rG*387h|28p);)wt7D@qYQcI$_+LU619l|mJU*NnyZUdGwsqZr8k+%ryl)LdQ zkzFR$Hw9qEXe-(Mw+T`SC*Pwx36lyUrHpx#KZ=4r;$qZ*6_20L=U<da6R|ehTho;^ zp&m|xETNOEi<{ZEdtu$NfVY4Ds7L~^49*a0Du67bb%wI{axcmvRk8_U@^>rfMYQ-j z@8{(93;zu5qSu>fz^uZNORv|g>g{;=j<R?%V1i*70C>c!hhNt=a|gA|{se~+Y={Xx zaJ#p9F(?;Gd>~(NC%ns+U#ZD=&47aSF?TN*+uU=f`{%gRswM7txshAIg}DF^<>sN6 zSy!kh=vHut2X6s?L>=q+Q5`>XG`=#SwyE_1z6<VfBmYYMojpo6W65ZRlX=2L?&nW> zgj)9=;YI;g4et#@rQDr9=J#?0Tgf7Pz|;T1Hi*>K@zXt3R&NDAs6F0J+0(a9E$V(C zm_CcRYNM}b1U(Ta;~vPX$1!k%*}i1E?a@5~NA2Gtrsh7Vb}o*;Ky$5N*sxVrFL}q+ zpC`Sv`haD<W*nA*DCaSgAO5}Wi-E)E{7)6CXyjx>s}Hhbb^r7&_uel?pY99LsHY6L zIOMm;t0Eq+QQ4lZ{s$}n`Ir(^cYo<Siq53qbv<?PDy|1W8FIs4+kPBb|E$LF5Zoj` zbH{^iRL#MyIMp-He<^dExw6l2^?jUYU|J4CCZfSHQ(z?zp?;M%lgcw0;pX<FG5B@e zGiP2ZKbL*z!iz%v21VXYykJU<#~PH&UKI=I*&+Mptm4|0!X2?%n{R$|<mUl>+4+u= z)P8Hk^(}L)MIxhwSHzscKaBQQyX-^86H>KsItSBB`>%8+d=Y@V#&EjB^s1XfcC6)i zEtsZ>cV23Ccx{?RFBh_PCSp5(UjQny9Kz%H2kTL+GW}+U<=P3^m*eWj5FnYoMF+l{ z4jH(DYA%gdxwoUyBdQyeIFcRKuEe?VzlsqWziT57g&6nYT>bBNex+KyZ4=%F%tu8W zb<7EP4+5$po{Fx^B=j+5GBz{$mZ96oq^9w10+N6^lIl+8jrBS7J;>YpH^`X~-9?#O zeRrZbX22#7rF*|t%L){SW6);<*pE}c{rVP~sJl@?FnaaLoo#}Vzp9_yIbine5^wOg zxeYQPivXFTm>`~5yE&kaT9Z&9{IE=0`M-kWZ<cDoG#pY(tyWX@t)5$gqH9RtGLZi= z>7%5onyR<SnF{%gV*|P55a%<-ByUK5sd9ydR$=eN>BP!#wA>QPf9!6em{#)cYOhww zA~97MLzG-{q7cq%Ii$LfTEtTRQPqpj^?z=)%KCe!4yqVk^oGXDlXdPkxGh0x;Bcb9 zWUecDmWPd|jnEq^BW=DLU;nc>$*8?bJl7ud7sizVW@rKLL0&z&f!+S20eD^nln$K= zv2!PP0GeoSMw!R2Wj5Y?JvxFI$bx!v-U%E)Qq+^V>xf^E;0zR3MIxRJ#`07m+!)@p zV{H1Qh0G8jHF>v-qk{DB+ZwvOxU-gp-4mxCsLDr&<NxfUw<LZM+27f%jFwD8R>d_+ zJUwRimoT9<Km>@G3FRjkd6x<}xgM(G#J_A$-QFJm>e3#M+FNr~A530MznV+%e6uFp z(IP{9*M)+%%_0oNQX;hL!yp1-R3k6;!RX-Oi5?-Fl7!y+I0BN#FAP}!EC%D8S6+xc zl~T>(6ti6Bx!IkfSl~yP6eEUqI`+etKr2sRhj-=O&fhZd5$cs`RFWhvyZXbsMod%2 z%pg{4$}Lmklj~!&ZeH{RusyH^9}Fzf*Del_7yAvE)ACQ5&&x>DAP{uQ$CN@cC14Z7 zyM19<V^LmeB&~EBzFwX}HoakC46bD^m)k@rP)7K&T%#qX3*Ijz5-uSEyzuRIx@NGL z(ALu%pj5|>R|#Y1c}4~>?e}@4dwqF^PoKAo8Qk96w$sGPsSijESc*sn=)c>1{VWp( z5XiXKc0*GE>^Aa_)z0`=L^}ANt}yHPdVHc=8D*6GbHe;rCC4T@Km6kK2kgH-*u?8% zjH>IqSRubImF{@a9)U-iX(w18F<g9nY~LTVa#7Ig_9|ilfty-g`N!wzpOFm1gSYjW znkblR{!=Jiatol}5vFNU{M)K2x$6B*D~vx)WtpUI=@AY$q1VA-?r6z%@BN>obA>|& znJv@N`l(`9HlqSa4nxU%v;Msq32W@HOyi>BP6;e8W7s$7>G#Y=Emp;3PoB}&1_D4& z9!`HuxBuqVl2xxi-{(H^LI~^=W+^r2HwOW??#~Hane~5r*XJMtiX4$~6-h7poaSo^ z8R2>xyRQ$|tvuFr8N;?fh@Rl-%L@5yZy<ekKdiZlY;?S(KD^|HP!E87mHv!W_4&*` z$>AIEhts6RLm{`*=qDM66<krM60oG;dc(d|7StRN$$L8r)m}4OFC~6nr?7=q0#Zw< zVGK7)n+QWy6YO=p=eM7><bt5*n7Pi)bk6M(u^zJx;s1w;ZoP#4f`%M|43_765YwV< z$uy-nxett+L#U9qPzn~Hd7d6RjKfEw)CrP4R?vaC*=@<;6@<*EjPzc}#5paQpdxUZ z*Zpy~`pfjD*01r+34V?JZ>r^{moaCel)+W=VruJ8><&A;Nn8t1NPUYgHGw`}(=OS% zPZX|;ZL8I5^2lRO7pB<cpZfQ0XVGu1A$3$M52Mr5R1{|f%fe+b=l8*20CEB$aK6lS zE@>Zl5Hd8WhFr0IqEy08>rh2T0xYavR6y8^L1-ZYc+_)19!ufXMVi_^SZl;m;Ks$v zCPG4EP<437Awi4oL(5>A;!7e^0`Q^0PHY%QJBZIlFQ!rgi-*}Cw9$}re1Py2=rH|E zN{ISzNwk!J(jb<@me~&FoX~q7#t8~;hVliT#c+`=!Wwy~*pgk(0$B&bfv_VeUV$VE zXkbhr=)%B<OnCZ#gC+KMn+D8gG1|`4K@mbk52X8u-wvOG#xfibPT{)Gr@K??)(D5$ z5T<uA7ZSes?4;3VU%ur2!C;9tUys2xj2l1xhu61`)ceg!A$O^i$Q>0j1m!eG5AF`G zKo^Q_2;iGmaV3N6WiL1o&{KEa2{s#v3&;HK#Uvd1YvokB)R0$?je#U?jknav-!>`s z)=>$gi|ETxGW$2xUynGhZG5%G2JY=W=<OnWJ(F5XHCbvGqmJWdmtlCU+DWgO?A$y1 z$0A+}lnAgN#?yHg_qP70#OSgF2d=y|LV;@DhD~=F`y_a5qj+#SirAlawzI{XeU+Sx zbne*Zdpl|vX@p!OF&m-FHlWv)A$n0#Q*oA+q!Ivzb)lupOm|&*G%{&x`yiD|k~AdS z{}Xfi*Qc$?ru%BXKW?16;Cb3JvI7h+@ooQp@^qEc2+t1aPGKg(gkOkH#sNtwhLBL* zF!A^NsSuGX|L9;3XZ9PMk^`}9?~`W7W)8`&w|y-nY8=>Wx@S&56eJlJy_~`5yWR=! zh5F<B35Q;U{G_%w%P}fe;vvSs>||VfwMII5+RIY%I!$J{6g3kDwngD)P5$fCFUa7* z`~AdIlse0#x*)}mPshoP>2KB4Z-hLIB#B}|s|QBj;o0x67-~)GQ@ciyPz)(AC~V@} z72O|2hK#`rt4b3DHRII7w1|h%N&|Y@U!q;@9#tkVLloL0>RIR>h46!57eiu!-5a;+ zKbVBX?+!ki{l^^-Su@ra;wz=sn#QgE{5$|)VjpZm;!*V`x=ejCxDJNTphaMD4i<U2 zjVSmz6CeK;DKA9!E~rNS2Y7fl-%(ye_4|}LRUZ77c?YG?&K>yz9>8_9bB>d}yPmdX z<(_}9vw{cR!A|hq!KWa_M+f^34JWB=5@0R++v9-84nhsDsu8&p8}N3rMTcZ-WaFxu zq1xBZ1FujUL9&IDH}<PXh|B0>((uwXZowhyrLsOGgC>Mjd5_669wORNazLY$%l0eT zWBv7z*VIm!r=^jt;aa0&_{bluPq85lZ`jdVD0<AqJ4?QYC>Bi#%XIP-)Slcl?HjeM zr!t^1tGMrm1B7rqAg3rh9a250b_DG0elT=@@7FkcSxCT5Q^qwn@nf>HX+rEd<D`F5 z)v!L*bpHxBT6~@MC+KLj>I~*STzCwZ%nhv7HwQ9%+v-A5_7I5(gjHv;hv#!f2rd2$ zQ1KjpZDX%=&H@WQH#xXzh6kav0x>scTVvP8^`Dpjr~enJ?p$PvY|G&6SGSD*%B6}w zBZfUJOZ}yLyPqE34A32Tx?)&vyL4vU7mk@M<Q3p4iQ<0yRCdLGn#;Lnd)w`s$i36k z(}yqPymJIKx@yHt+1SvQb@F3h)~9kY<;93rl{sEl^y-qwcK)IfWT0$8^NU>Lw8xzD zrtyEBIw@FRba6QQNQHtvE~Dd_vMdGSzHLyDk#F|M8Rm*^)Y`n<U&hTb_w#WMuvn%E zx6O9b(KG3GjhzjrFp`#Hy5<S_I?5;5^Umewut5G95uRH3HG~IP74e*6ZtQ{|wTr_r zIBB5eS=%88NVsKSNxDQ;69&FEH+EKcdBa?~1jPxCZ$!Dg4sQ^^G6{_8ggzVrY=`Pf zuQD_x9(_Kh{&{+l&}rewBX;qrdKM6*QzahAuO>ro0CotHmNEv#qvqC}7sX6?@cA-1 ze1<Ufdjy|X`?!3Gu#0MMuOD3rVcegibqFoVarv?ZRU4v@fkZ%|;dQSGCO?+2*SYl> z{H+m=pl%4%dByT+hOd*kIgyIuk!WJ`Q}s;p*&xwne0bLt$F_5TIsC+$=D2h&uCd!N z#&OZD-nJVCC<{*eF&SyV;|eoraXZ%bS0tLwjJ~461?$<yoYn{Mo5eeO181?yw{C3a zQ<Z1J(O10}UFhPc=h~J^z`)a9lFz*>Aw+=E@VI#r4(J0TFGTKU0?jUoS@vf;d{fh4 zZy}NGgFFFiQxqGx*EdiLaONvk$lBzGy#JZ~Q+Ui}ECTEV?!ge;<!c=sH&(1iq&NU} zIUafD+L#@i_J6;IxP$gzbSODq-<!X71}`XVuQBs}52K^<%AY0M`2Y=JKcf--?{wdD zS%#wiWXSu~V&ljw&-U#A_W|m0Kr|<@FIl~$o)KUBw&(@IHmb+XF7qJ|SJ&HY<kxem zs*fH$0Y^A&Q*X}4tp4BeKBhcqmxLaJ!ykD+ohx5Qt_&Tk8+i=gX@8El!=5@N>?>%` z5^~=hxpBO34yD$fHp5;jgGA@gE}OT;mtGpNJ-pa0M_G7PvJOdl@9g+zwc+`XX=l}w zRALdez&PAEc>Q3|!Zw&h;l$-A1}+<*s+c~CC1f1T^qk+1XmgYdOe0vHa9%*&?R$Bt z5_<TySZMgpS~G)_GpRYncY_WbK0;L=BNbHIqxZD<Jvwy~VtDMqAJub1Bk{gt8$<ey zQ)`%F1V9~Wgsg6lO-m!9jFwKHspLLKO$2rM=@9$@W3<<89~DMBM3Pnx`^|m5$WujA zZ&_jT5V;AF9Q=SOQk58opm6w-iG#eN%udfT@HB{r#=#gv#$wEiW1+x;*tt0`fzH3F zbQ-SrqA<X9H82CmPeJXXjR0?!cuYa)*d~M@8+u5Xfu*b>UJJ@W_cSC(D+-Sgrt2FA zlF2SL4R|^=2cJQR0j0Pmoa6ivA;ZGT3LEQK4K!u(y`(+^FqJnSBS5SSIFqR-fQo~1 z4a-XOD=GSGkypo*sVB-dw|yed)5BpO$OXH@M}nM$*hax*?2Ne%iWFiZK`W8^KGOA( zUWM@o&KU^gYqk+KJp8k0dG7(K2be%2w$$T=s6j~mUYuc~%s_QmW|E$S`usMY3W~nG z+;c|`Ok~}7#927|fCfmqu5RXNoS8tq!Ki!G1k27_3mzbnO8ozN1jpkWiOXhMsmE^L z!4&0zRtmV1tfBxRPi$B0k-JAwe0w2v#O93|ZVJ9Cb{Q$ADa5HOnp!RXDGc)HNXL>< zlk4eCB8Kg#q_-pd!pzV2e1(6EEIH9)k8Q9Qdm%2ZIIb;t*IoKj<w+{+RN(>e*kS5p znXED7xI=r#DC1fLAL0=jPib&x^F7AZ?h{dkLJz=OEv;}GNGFqV?b8t7&frJ~C_!m& zU35{>_n$*|;mEkZ&TKmEE<KyHtOS3<#dVJi-I8w*yv1=Z%NrPzn0DvHgB+~v|D+?X zc!qJWZk3{^`f_Tw_LgLNIO8#$S02LZede;D1Y*hPPOOhW|If=pg1eIyqrNpF4A0#v zgv`}D{Ig?}9KX6Tn==J>sX1U4hRohXoqoMzb6KJ%`QTT(LQ%?3$r>v+F|J1XqryQS zib74v;O@+RR*}q`btBquPj!R+9>e0v4*ur{*qpAtKF@&r1JSZ`A71NmY13nSn@I~f z)Tt;>=n589qZ+poJa#g{cTWy7NUBS~ABf`Q$tGiN-6w1c#^p*pF@No!{w94l4;^+~ z@@L2=W|+yk2_BGr#|(;X?0LnR{Wpy1k741~h|mfcZY@t&l2uEW=W{wAt4mWvJUcEK z5`w7uziOVotb)@k!T<2ep>qyc4`+-U`^s3M+NznJi#qQpCpMPKuM1w|*<w=Kzq4+Y z&}(zR4c=r7bM5SToBDXvG^4bOOSL1z@XL6Z;&k(Ee0D{^Uqo(2xR>QohFO>J!%3is z>A~*BiC(lLG@#F@D^bpLlyZ#|N1-^q4PXD>_Mqz@X6(8G9G$?VsFz7W)+y58&?wq6 zN3uY6m(ps*qG|1@CX@`eyRIu>f`_?xRhcf>+Da(GNoQWn#Eylb<U7i2!xb9w`0Fj? zL5>mYq8cP+1NmWM6|S~;`gv|<!T&UJAgb8!J0&Q9hIQI`S0}NA4B-PSdr?`*dG4iv z<gB-Yfl>U(7iaKVgK1}Vt{`cN;C8G9o;si-(DB@dx}W-}@k79-dNA~JHsjf)&~B9s zldz^sQBHFNEwX0L?_2rLR(q?Dds106h}o3}g~9}<MniD+N$FBFUPyp-_{vX|+Fo}R zKpGX@ezfyP#4*sY(?Mt(C!NXtbBD<A`uIq{JAtUUkSka6B-9nvAxl_SSv?})fv$0i zZobo}dw2g|dzc8W^NdvRT_Sh=^<m%y?Tyn~_5Rv1nlLc(Dt84&bXd;`lk#O=QzseR z@wP)ae5-=jr=CpweZrK?VanI*PYRK;z5Uc_L^6NzKKN3wfc{}&4rkN|S{(+cca09o zvlL_KJOfSgu3)Z+pU7pR)JPP1d;QEchPJN^f{kc$lqn-sH6U&ohtK;)!BU`ow$!t9 zANWW!A+tM0M`st0Lo5Q6Zy-%SJQ1D%#!tTw9|ZtGraDxROQk4xP*!6yh|oZEy9G_- z_)Kj?&KwbEm?RM_g>|lv)Kqtg8!Z+i00bUd2w5a^90Zm@=hq|?3}#N=qkY~hp+rJ3 zSUKUCEXKQqZMBhYBFsXPH)^6Xlf11x#6A^DU%YpoeD)F(VL`b8Vwq$9t<0Al#J|Ku zGjOpPuF<C%6jG>nQb|s9rcpq#_ZNBu6h_+e24Ml_opwOAmi!pEjuzdFX@@SHSesqK zb_XM;PIm#zFz&tC#Ml)9fOA1nX(=FAQ|%3D7hhmkAUvga8Q9_zID%MKe1_W#6GI0w z5GjVax8xh1!pICf?*{WLZUTZn;LFzIIN$gtiuN-Rb9xR>?0RAQ#^>d5{h}w4=N@0u zW<%K`3}&h%RezUiHM>&DJPHXm)5nrzPXzDJz;Cr{3!k+yI1q`n`0j==JK79jd!%Vl zpL{F$^MieNJ05Y0yQPtcO_4Pz$<dvZ`PO#o&awN^&mx^nh3=z>@*3|)Tb-F^SkiHD zA1o3=h^t6tCSBw<L9i9F1;yO@XIEp=4t=|pgf2+c!(x2zqH7U_;Mfk5^KYE?Og;LB zic%ENMO@!*#tbJ<&2E-gw_RfJK=2TQPtKlf+%-x}e`HAZEsLy!!AtRmag$fmuUji; zbh!Q1sUCMWYmZ8HFLOj^jxw<7iBYIm>XhCZ(ITSxK?BsA`1jcHDfX4eW@6vB)3YGT z{5n-X0i|wpNzAL!y5oN=y9?S{bjLS6)WzL1$-}R+4+83z(vA*i3mtZtS5Zd>!^SO$ zJRfCreU~3lM;;&8k{pKoR`bxg0%|VEKTYu=<kem&*wK%DnB@Cof0MDl_6W{8uDY{n zaSs+?C3v#3t(rbU<VkV(gt`HQu$yz0Yv;@>d)lKnuuc&nOu2HQmjcWcJFJz=fjYXT z|F|^@;w;hJEfyt*U^mHY8xNo(KMMuJ#KXetU@vj(FmUb1t#w56;nV>_+t=LZ88c43 z7~g0rPoN<r*K=$QX0|N#a-zh_0;U3gc+3W?6$JYgtC2MdhXsuA2`9}L%mvJY=7QkB z7=Y6R5>bR83(#O9<30eVb`9dupq+QvY0}Mv<q>o}DF#L3#M>+0mzxXPNZbw`i~{`N zVnS~ygQ;hx*?G4V6f>|)t;aC(W2#uy0HZLLFJ%xl7;;)QD|g_t(Y80{E!L7!ugq95 z7kvw8stY|XIv2FPhVVPZa8+1Tdb{2x8?IgR3<Z5G*I1m-c=_hE8AuGSz($SP3ZGpy z$G$KhAApzo?4S`#SIFE>)LNjebemG*MAWgq>v?;<Igtpcz<cr==EZkvIQ*&2JL(6I zycPwCLT0T$V)dc@Q<i9g0N8OXZGWA;#~$19(<_F_>vI_^58>8+F^G*;j1nm;c3*bK zk?%9%{`e&~nK@!om6=y_GZi<27I)_zWyz9YmG!}-I#Qn%BTw|xg*Rod{<hPjsd%J9 z4a-bV8ryoWhAzH2Zbrs4{<}YRDvFOYk<vw>QXt{*Mtl9pIHw|U_jrBJANsb?4SiCP z(CXXHd(0tXHu~^l++QE*c>7n2*KlZByo=+Ouqn{Y=24C8$mRkBR*3(PcV0@8!qMSh zz>2ZOjI*}|n*bGv{2EyJe7}V*1ts?4`a8R>Ba6~|;l)I&wn9G71pXXAF&k!=vFlKN zLDLK~$MGg%o&6&<b8RNF&xz^I?(&zMGY`Z!>r=l-Fv9>aD6{O={;2;lA3Zec7pOp? zLj7qy{N-jYgWC_<GIn7=;~agpTXWRyA63W_R3Hu)GB$^2HDfz+3nkQNBhU#b2X}r& zuf1Tj|B&XEiLxi3OM|_?Tnv<l+i`lPw&y4Q@qPVIp1Z^|)Nd<ybDpIRxjv2l2CpR! zvCWt4KbdjwbxIe`F2Yev%7iyXUk?TTSs1O=j_481grf<+&K*OWsE;s-wEIH2jxl_E zWLQu)W?YnHm?n#-r-3%9l3M(gz1e46?7CI;rOSmO*4JlQJa{51CkH*oeE-<@9~(6p zQ7a>j5*=~wW7-byaU{4ahC{-#?t64Oot{Y>Lp$UJPsA2dE=SO`yOmad#mP<?f7-$5 z8TBPce2D7fzd1>c6AD%|N_jJoMDnzjE$ih^+-l#jN0AR*D>`}$9Y+ow4*!QP3h)id zKz$p8;_N(qWh4{Y&lt{E2#xA?75bU*Q};UwHZ&Gt7&zphYc|#*#R3?%_>MxFe;5>D zbIUsn>xVOK4US*-O!=ATqn&XMNQB<<LJ4}u13JqP5?F-lrGXNd7~8-R{qS7KSx+nW z<-!a_do|^XVWue)zz0IJml!ZjjU&j(c>ZHTC<O~4>lDj;UL^P+225tQvjIUW{94Ve z38GExt%0GCEM#I#+z?2Cwy=l_?<CBpK7xfgF1rBxWCJL=86W<EIz8S;Vr1aGlBy=~ z40`*lQ#yZeW2=2(xwv=*@So%eG-jr{&*6VD7-^!KV7a&e$e)$jWu-UaKCD|V^ueeb zgDY<z(~p7WXMD8ItrzX2f}wrtGj}5vhg1JGyZ#IX4fgT^XqiEzgQ`(ogSNOtnQ62@ z2M$YY>>>iYlvQq2$yc-GACbVW^cf5OA7Dd~Sf8$K&?GpdrWV4@*#zhO#rsb{aeBUT zH@JKkVTBM-Fd$3qzW#0P+o^;%HZ)aoI!5n$w5r>6hU$Pvb!!L4ItMq85w8^e4I}<? z&qLg}wgg+rvl~B528>SRD%Y8TgS;c=%<q~Q5kj2MuVR)7&hgDj8Gu}(h4X(X)_q6W zcgak$^q;|+*J*<_H%2h|lnIYaH=YPRN43$1CX{2twy({R20T-|Xe&S$5DDV%@M_go z5m-PMXQO7{Ct_#q5i}W&Rz>_-donGVR$OnrW%g6zS2J4+XB2u)-3w<ShX6(VLC7+Q z-h(~v9-fXr$SVvaYXTcxR_5&bq=LJ2#Mn-PxXSKTySxmr$rHjqDS;eqG2W4@V#LDi z9d^5*-C&c}JtQxAohDoT`72%FQI3s0IVPcTsS6$}c|BG+^X+iNQ<?(jCAQu-><{dZ z8gE9X1hli;k92ixw4eB*Y>kLvlYrGi<2@H%4HHb`V^fJEcPRjc_BP5k_{SQt$ZNx< z0BPj2hbI_H-MfH@_%|O6UwfpMZY;$T79-~GvXQA^c7|L)W_LmjW2WRaBVNHZ4#}n^ z?{0W`AWY~*oIlR_Ur4A~B!BecDVoo_kW^()TjT~PM(fRRCR-2vSs|{6-%xKGYFtQ) zaoZ<xIBRt1Dj3TUR!=FWNo?M1!?91H<B-{j`+UsQ<H$cIENjU8<EWZg<Z+&m14L+a z;N{SSKCr`kc;W?-o)^c?gHtbd@^N#hqqXOdEr)>*g1#6e#f(~;uipuH#af=X@ZW7h zN~BJ(BGo)c^*%k4gUoWnXt+~CZpeU!84(ijegU-`Ene)r5aJq8p3j)=_n<{#NCkEq zUJK_B%6JGLYfBFFfs>X=GyX0dfV;LKtyc+L;LUk|m^gaR!xPW9r#}FYl4edx*X%5X z`3uK$yoa*^))YM?9unQLFE<)AZFIwP{^&B$)j^R2eKTcQ1gStqJK-e*ryolWjzc(4 zpgP0N85tmA%SsZN;{|Vg5ibYxbGUVIb1jp`5C~yzPWGE*1uFcwk11aeuc<y3wwesM zS5_p#-9SB&x2RvB)q<u7nju0_skh7ebnGoM>7W=2UR<OInx4Yt_bAqoss`vjNMsnj zr;yc*g$V0~2;jj-&cL<2LRaYcF{a?;a#+4z(jMUnJe2xO-8e>$i|bns(0396gB4g2 zye~UGT4I<kC8LD$if%Zb;Eo}|b(sv^ydS**Ra0^}vZKgXijex$Dv7#sXmehEpeyoy z09O%X9UTcQwHbC<`A@N#W*Xs9;f5QB>*_*7gSyQW|75@jyJKpWJ)JZTA1P_wp7|X0 zaaSm^=VK$qGvmVR6!Y2ShA^RbfFH5k0s9g=t|1gM9&Qu^pWbE&t>=-CLzcjY_tZ7! z#eSd-K$PK!eV3GLXGi9?e3CJn?FvdChO~D*g<0rkX7HGSNRo44V5wO)uw=poH9864 z8<A!<Ik;J{`&hi<B(jqg1wC5sBOR@RjY@(b)F`e8bhbdiUGR>w6+R(k`rXBa{w~MJ z$-Sr8dj;aNXX*8wEv-HLl*<^x<mYhkP(UehaYZ!@JvsJ8Z?8YWRWP?0!)+#i7;Xn* zbEmEWH$yD(z$&(F%8Os+24cbKQ;T7VhEhAa*=QZbESpJcC`_hF_qFUG3S$Yphv0>@ z02W7{+Qo^{k93oRfn>S?d9bX6D;w4y?mli)e%j_$h^fKc0C~hEUtgA#5ZyXI$87eR z=LH4Jlg;3tq9h?PuSCL@Kf!H>59b&d(0FyRalt<+=0}Y@)<lU(Y`();+h;?*fijG4 z(xf;W`E|mXm8zY4yFL_tuz5%Nn_16jC00<Qy+Pe>K3ilj$GDA>d}D?wnY9(XPVOj# z7#4TAR-oAfyUu}7a7eKv{YkT^sQsO>a<Xdvkk9jg&N=TI=%Q837qT}l#WRn$y!qVL z#H${|RZ>`S%~#rn4%7yFOamb*lc&PAj-V@G#$=vR)s_dy38QppA6(GmTU^k-YYPz6 z5L2F$w&&=j5A8vMi80<Hcnt(}AF_@C1KZS=P6qTJLst)PgUs|-O9DX5!s{VqLX%p4 zQzmfQkf>if_IbtZNG|N>#lvgxd1$19t>kw?x7N0l2=#h|dicjXKj|3inDWmK#YPKo zpx%b9&_7Mp*(g5Y%^kaIRHWv?{x?L1py~gHj$h@drhTvu;B$25Ehq4;(KPboum?9L zKtZiJG;Y-h5-e7%)gqJ*&_ClXN}9FN={WFG);Sn5**YC3d0lz$UfMg#{c=$5fiR5I zw2RL=>{^72i=t-lKK7~%*YxAJU}2)QxjFpsQYdKe*jev<@@H3~$nY3u0)&Tk%QFA< zUhXfvVf9JIo5C2D-?L<bl=q5}P>z%vVh&M(EiTis3VW3<kC6Y|ejhJ0AK&CtkI@jf zZP4wPpOY2tgV=3%n8UqByR-cy&{9QDna*_&GxT6nm_KAd*^#%zID{ajIDX;%m#!gB zTEv3Gb{a&41^7&B^s>C}xZOBuN#>*Y_Qjj}nojGO{TH?2#^LS;Se2%%{_X7a{=9{f zUQNEh_JQ!n|8L-9IM>2k4^RY&xEtEjr2xdAw$jFF`Cj6;4iugktwggS#EqKX4VoHU zA1p(>b+LlT!~D`agENih%^j+o8cgRAJ-?0m+OH=s*MMc}LhUZWsz!b%>M{0W{mB?# za;<}jpc#Qc1ztowc*RH3V5Lg<wK`j9`GEVym_~<aHp0_;&>41YnvK|eGmvM25f>!4 z^_^{mrb5Aa#Oq*FVcMq<C?fzt3<5!~&U+7l4}cwlxS+X%$y6+f#CSG<$uS8DnRp0Z zI>;Ui(^&}rLc5P>-T|G>>99H?XBlXZ-pEJU#xi0c^%AmKgomQW=n)d2&jjBQN!Wz* zOFA;Q<;xCYTl^LzeT-bpG>7u-&CNyZP-QI6EW)1~;yUBOK7iA3R2f=(pl1&G`wf6& zb0xUk0UR%}4e(l9p+AXX-B+_Z@@n5iGAgj9-sWSktRxdkQYJ4rHZvg5e0^bnt-IWD zIl6KxX$R6;+Q#QCYlAAk5ayZcaenC{c~MClV$E1?c4FrRcEtn+gQn!sd<zs-sONhh z>0;6ZR=!;!z+=A#U8Kt47e3NybHT{=5AXK2w5n^u*Xx&J37@Ab9%h|=P4-V;ys+?z z;<I&n$Pu(<K%fToOpeY#0J@J5zD{AWP-EoTFp@|=%4H%C9*H*h(FxE%eDg4x7sIeC z88xB~!IEwPxM$%8EF3RoeQUyL7?<}H;X1bkK!6%6n}o%uw->~!EYJLO?L6loc!y5s znhPBQ7cT~HnHJ;Yve`t)77FZ6EnejV=P4mOkaDV!?CQSWI!ssGu^IwE5V}D;AxUFW zDs-0<peI?8f)N$Y1)y2i3b4)9$5O5@$7SHjU`gWd&%ImVcn|VYh3t?Q<!j}bEa3rW zfntqu*qnP=X6mc@*&4)>__*CS@bLuOPHB+^``90`g}E)SK(fwkxW3!(NoWTEis!%h z7_D9bDnclvU5j}}?#m>Bfjh1^3F3@83xzIpa4a#9a;?~D>B_T7ar$G1s@f4ec$q~# z^||eJFg<`)ivb8AW__&kbkAujgH_8X<Yti8=E_icmDGKt5XYl`#0&jXt2<IA18iX0 zOLp;MP`y(a+X}A>AHy7QL;pqb_dq@6u(N(Ht{u0!mu!&SvD)^uldO0+WNck6a!lk; z$;3CAqbb?_MmOu+-@hEXOH6ds)yJmOnjg-lH#8o0$XKd8%c6?35pX{`skVpuT&UkU zTCr2D3Lw=riO>~F?stV`FU&UGtx6Bw5b#!R9F%n~W2rO}W4NkZtyOZv*igl^)>z5t z&u5t?rA?`f0z0%jN6ATa{!mTUaa5%z$%N1}vgE6v5DR7StEl-yyA5lEOKMq&<H7?0 zW+Wq#K>g>F&(BC+;?}tL91Cm>9e+WdmZGI@&&(N>`QB%q3Qqom?8BhGU0XG7eUL@V z986yRmS3d#37vcxF;#-zGCoA7jv{*%MZNQL5ricb$>@@?I^w3D8!v2)bu`|xrZp7T z2Dq)f?8cpjV5PpSbfOGlh-gsM*T8WTS&qM>yrdp$0vL>|^AF+7l)vaofAt+rBYBGT zBRWf1AL7~m-7I7y{G>fzAe~B}oi`zLQ;jPB&#zjB5?`uhgk|d+DA8sT7h>*2M=H;@ zQNidhjQ!`kca#=@gM;U{RnKp_7+WeAJP^XaB=eV(NE{f206P`aQYzY#19-WeNk+U~ zo?;NJ5n!4yn#K9YyFKoN0h~Fm4tNkc6V4<LWhdU&cvRN-T_)-_Gz)eqR%E-rr9zTR ze>NN<Ylt2S4GYn>6F&j^5Mv#Yk5DHNB!gpP``1+bz$=7N(m&Eux>CEd6?>)5FoKeT zk!3B0F2ErI-ZwZ%Bb{|I$;N<i5CKFZYziIX5HgNJMT^tGEQcVUs95nRU_S#=U5=>% z?Cjz5i6f51@`b+1&DlVSVwx6*T3vIk80dd_3hr!0Ic$Q^TwPQ^0PBNqn<B+Y1uOzm z6^txsdAZ9Ff;*W>`V17tz#b3|juLSLynqiTlD+LD&aFHhdtBKk;Lu_A{t*t44)B(V z4#SS2wfFErSz5kS;=B;WNlg`omYwY<$$TfeeJ>>&N)FT+yxYZKxOyFznr>*yXNND) z>un}ut$vNF2m=ef%kWWL=S2|7_BI3WH9|K3Ove7acp5Ph-&ll{oAdLc6+jyJ$W%<z zjuhnOL1X}-o7wC=Q1~iw9{9U#UW|aZ3|tC!8~8RMKb(I`M=m63qxPG8Kzy-r&~@TW z{`_M>(o*ywFt0{~fI(t&-49Pp1WEd?LPRlz>zHUALhOKSgwBE56?yTC!@blW>t-zY zi5wp+Ln;FM6h=B!Loox-6+SV5i7arVI~>gCsj!DH2N5yYIGE*`7jL9qPQ+fs;>PZj zC6~RJUXz%n&e(r(9$3E;ph*NV%Eb^yX&iwCx*u8S=kVO<e~aM@O=#JJMLNb4xRJR7 z`~qRB)Vxr;7*#F#s+NQdi0nJ_l2Ith^Q;X3h0)3|-zPmjX%z6H<E~`I!W;_C_i}#- z@=!pvw2&zhRO8GXU!Tvo=*-!AR{$BdWi*&C(dUz`o0e<2MXQ+?{ap!fft`b{aX1sv z;#d&s<1XJ|fm(c*mr`1alLz^70ocdkHt=8o*W_%#njR3IG#93r@Zp67Xl(6WaH`Nf zH9GKr{h2Y_z|;QVp^nXXjj<a$X#?rATiNDUoF{zXiX~SJrYOnyt-N?Y9F&GwH@D$j zDadDS^1B>hLC`y~<V&AD$5D=s7c}7;BkT3b{DES$?*@feQGUWpbNdk-=j{PYrf#$Z zN{PjHRp<;$#Tu^H4+F%~{e&m0P;k-Uz9~wG%ISllq$qsF{K?HPtNxOGkm!9y@H$<x z0AT>bxYU8`f)Bs|M2a|)LBf-_4QSWYHuv)r2(t^*-6`tbsDD0V*xYj)b46**?A6q4 zk*7ysHe2MG)S_HE;rL7T>TNs*2q1t^8;15Lx)>^$hT_{|gyXb-V5#yN+g|ky{_-L{ zFj&&s3~)SrE9o;EwQ_HZS?{oF-G1A`T49gIfE0e&>bTRUzl=%fz~)_f-HM^2$|CJC zBv$m1lUdGpcqU@mz^O5vq(ostl3bPayZ8?$!)kZ4T7JtC4^`D9KAY$)px7-703fr6 zi@7iCwcBg|qixiUqYJrXMBS@7B+N`(XxpnH<N+{ruW3$6>#k^9uty`4>3QZ;*+PxF zBF8%MBnAx^doBA<&GfwZ>NKo&ZmMW8!CFOvoJTx$f?=1IIEa9rnj1exncajvufSFl zF>N&>$BU_wjrhbDJcB#zA%yyQeGDM%>;{z2wU{a5Z)JO<jvd>%+#w6l8C+4jsZfD| zj|T@%Ou&tnmSm$V9z^qNMCw-SL9nQ;qyJ^_#p5@;%ysTZ!TBay;)hL58L{022{MH^ zfZ|mRl*BQ0CbLm#p-nOlr!2jzs)?Ab5r^Z&x%fL$*k}UguNgAi{<3-6kQ^hl*w%Zg z$_PKK0^%y#xfE{<rY>{;g`qx-WSB-!jbI*7@9PLYpdy6^U=2m`b25{;g1^kfc8F51 z9tf468NWm!=cizBjftjf+8tZ<wLE;G;@C`^1|jb=cd-5BD8Ydxnd_9yN)fjZ1Sn|> z%0+C=u{^O&3KeLFC}Pwc;vLN_T8yWUoVg;`G$}k?@Rn!7{hLK#E=U+fVW<ST(T~1J zyThW6456GyA57j*?bTG&j@*oy0a#`_gpqT+7$fr(JvpCUhL(UWLMMU(8Hki|Fd|y) zQWi5#6?AKRVRRq_l4Rs$Zvu!8of#ZaSgKnvq6fT1PMbrea5n*W96G!VZdV9A7?3G- z9L9D9N8s&1oK8}%Am3v|0H=r|pxi$IUC>r$om#lZ0!f_%dCr+;Srbqz%|<eDAnD+H z593W)>N6^=*v`cxUXbdI9)K3R>>%<Sa-4%``6mWPodd!$xEUk}fK=YY=W)!rVayfT z`^ejeRMV<~HJh6~HJwgBJOMKuxSEr@9B>Mr0b%&J62yMp0zB4i=4_47LGLoy=_r{I zA-Tdh!x3k24rEPv*2}rE*q?wz78T+a!c>K2zQ!b<qwMFfk7>deoaXRz+;pE~heZcw zWH$Eb)9P7LF*v_oE&w`$1@9?Lx#@!@Vt}7=^ZLj5+7A4bTW0tg9sr*f;DKxdh~+o^ zXoclA@${dthxwESPzf)-^Xm;W7Gp}hs(k=8=payfdt-^89R#5gixFca?7&_phFF#k z=H_Ws#DVe2=b;4{x8%Jj=AwBUf`&y!s(!Q*%c3K(J*`92q;uC4u$fPLz=aH+krO-O ztxwE;>h1JKbWj!<%TaY;ZNH=B4`>}I2FEd_xMi_BQ+k<ar03@3t_HWb&u_`XY_v{1 zMGMZOGlKyaCQyGEnXaJli%Lsz3BJ1EzYifiO;YEO-c(M(`!{;(hORaU{Z(O%4;h@y zZ>{?zaW4e6xuXnL%^X@|mJ{-=+DLP;I^@Jk??{L0Xau(_b1_;#*$oTydIvQ;J9fN@ zvv?hL<_+;jhYrf1t#aQ;@+}!jo}D9;RmN~L&nY-ja<pBjm>gz8UNYW<yrM3UE+_(j z>{;M`jNW)%{*T2UByXHK`szSM3^UqrCFnM+eT=u;zxwZIa>q?xG44IYQIyO_#hQ(m z4s718a(hmU(5;6Td+Y>~Pjq0|7ULWXlc6xedxxwd;1_R-BB`+rlAVM*t;U)(xhM>f z(4%D_Qd|wIfz$@gMK>l3mI;%#n0Gf_V(GmOBh&}vQK8rK-)>S(%rU_y0y=%Y00%Z< z-l->qh1a3oV?nFpn|*s>4|Aj|5C6thoQwzlAhTgV(}<(3gqmEJXZl~L&B7^qp4b#J zlqLmGwGCCygPXo#CLDl^L72BGTr`C9GM1^Wz?1m5v$G!1!6bw%GvO9g3z@6E=V>e5 z|J^#STVe<rjZ>VViu4400i$X7`Hh<Z`+`Y2#Pn5Kjnq{L$7dABV4o<u7U6Xi#drf2 z%+ujaep>)N77P~G;kAGpN}3e#virbOAE~y&8|x&8l!h>2g2Wd9HmozqRCoV?4r)+B zJoHn~3Sa4CP@Eiuf(8Z#<{%F5WO=|jtFn-E@4Crhkfp({5Cb3|0`;t8^oklNa0Kk7 zB3u-f4M?Hl!TcU3gNP_6W+)YSUc*IzFkw&F251}~=x9#C<QxaI5WPPVw!~UR>i5RH zk)gTnxU(5ex<uSd&~fk?(KgGFMU&g3!0YuCUtPgw2ZQh7J>Qa{dR2lzO&m~Cm(A2( zH84-{pPX?E;sCyw3a!kj)H7{Bp=Fz>GM0UfkYzH{1Gf}FHXOERYk1j2Y}g8{7%(uY zxWO}SAVZEo)Od@?r%#iu4i#@9-+_va*u@B~fG;<0wYP4y(&>mfpZM2XZc#T}0a;VH zEymjiQfqB6L^lp7j=k<7v8}FRPPf|(V!;B4!s3h@7^xUP#xA!L*obMd4U3F32^o}l z9^kQ;6J(eWUFY8-4a)L~JR8h{JYk4muk6dHpZ-(FAjc2qAlfcDFlGXvV^J2zE(f{+ zAy5WBc+r1Q&MF2caFVS+R4UQX#WF$7Ui-2a0JvyEYHm&|Xabzx-WH8hEfzZ{rL+fm zL0bllQXQ~tb^^KA#lLJI(DZYxD<S5wTLvKPBRg$C5;?HKQ9(Ngm<Uj<jtsGBc{Uh) zWQmP{>UdWZpvt7oe2sZ2?qCso7BJf+zxppen$S}5$=Y#%cHY>Eu{vQ{0lNlJ>>4QX zZ?{ol$6x~p&1EwzAHeemQom#g`5EL5!=<3qjzwLNO#aH3%~*g0y4vZoX%VtbaD~Lt z^&RB`T)vFv9mIkK?PHRs?KIdH`-fZz(HHKQrqeqJ)mcTpn6?~e*&q&%lZ^Pa<S1H` zf1+ou4Jj`OUvQGNi@_7f=z|kc4!RW*^XCW7@t|k-SF`?WU!wl8(1zn~;3_-^ZvH4d z<&PW0a%(i5+m>B3f^-}Ji=x@|X-m`0o?WEv#lG<?DFm`&y>+z_*}Lit$BeoJak^94 zF<^mWe~?%1o3Xr)^~0uUw!<Ubo*w_U!>hgI3?0J})NA-ms~a_t$f0`49It=v^=g#y zvLefvH){R8oX|^$OAy(>?I4L@A=psk@iPbgmN%~jnHPt(DND}MUVBIR^l^Aat8x%S zRY_nZ;c$Y%_*fp07#{+vrVX0WIlmc0@FY;#$8BvSga$6&C%igour49QMOB3V-%zhH zlHUy3Tk>q+E*uoswBN<-c|HPE$s$56&VeRnuCeF3!Vnr6IH2ARxpy~?&uuH%%FvWl zz~ZSN{;mWK%|>xmnE~Y|*>2E8G^4$$AcVU)xEka55+n^kp9Gq5s{@onC>2u7ghV~0 zXhD7-Xc3<bXhGy~UN{Sj7FV9~!$Q6z&LPZW-t$7+itk3Y@C+Q*6o2fK01Ck_>>nAz z^lfMW6HV2$5h^Wm*2J1J@!)yo<uM2-CkP&QZUX4M5G4sI@z6YKLe%4>{hH?>kWHU- zUMd54K}Muqys?_FG^z8lzur-9mQJxekx3xOMM|_1^*H8|DE9$hfUq8sW6EOS84VW^ zOH`Qy1>-psh=qKwG^s0fY^?VY{*2ryEGy5h0tK0b?LgL-&K3kA580b@I@KA=_TXW0 zp%&Rh8d>m;upDtT*9uclE+fB+qa9V>!r7|XkdMU?kCPGZqNWJ-Aubf1ZP9lONMI%G zL@<uxJMf5|K|@$tYfs(<Aq<^?n;_Dx4I{+V@7JNVsxjebr5*?MX+XQ0zgWnqciF7x zgpUR6n)$)JXn@n>=5I`wK3WMs7#NCm{#%LyaV|&#Xps!?7~a{v#u4zCJx-__0!$1r z#>24mFx>qxKZolDCbPE;Gqyq?2N8e#Qh?Le@_ZCsi}h$^3&86LMlIg=7a+TzXI?GJ zbK_bNCQJ^R1%3(@>8usSOitc=q$nN0H9VRRi8qky4_~0OZzB1?nDVWG(y_JxqU2%o zd4s^O5yXhKU4#<c0vyyIo};zfmeGJ)yOVsElPJ6a7J;ICxf=AFljh)hur@=<q3k!E zcMw<gj)EcS;BT2wQb>HUYcDbvp2GeQU;?>|aKg@Ej#^CY&pW&dPbNP>Uh=w_g(0kY z_;T`2n6H&*OoL88(E#-fUV~a_f+*s<URbGk@awRq*2*&tLFin$3{wCC6D;^3{}juF zI1(Zg9CB(33;h(_@sd%+TVvL7ng*c7!2}o}M!L|ntHzX=3G@Ny$;!u@>Cwerg2jQF z+acry`4m&ia&NNK6hjqYZ7*PQ6g~NAn^rMFtmC1W{bB(gLb(u3oKqG*;Yh<CT8i%K z%4a@T34bPO!Gh&z3u^r5F?z)i1eF&9E9>){2cc2C8*ub_t1+-dUzblvBR=dGALHr> z63#wLhB^gvRW!b*Wu?wxVPUr?qB-Pc^KZOec>mJA-&beEA35;+EH+r|f4#XKPr4Vw zw&gTuS%7kNH9T&x5rLNZLn0PF_Js1v(cj0VQ>#ev;gTpB>=GnJR?-eV<3MPsuEt`H zl!VHmv?I*g_>lKzsIPX^zFf8WNwCZi`Rzmj`q+5>%xK~8>iq_LTbRWU0LQ@+8-$dL za)og&sd0hwfR(L1mppRmS(4b7&w2rf0!K!({MT95HIO5kYH|Y9@tWtc9P+*p_}`}l z!!Cb)2)?vOZqN*v3o(ytTkb(u1oNse`Nwt!LP9?p6;hQ=w48u}D7Gfz{?$MM%{#gt zSBnkD8s}Vb2K@a94R9xPy(ks1eeQ=+-HAswy9tPFJ{jWKJ`fN_69rF%oCn045GxcX z9{^YxbkN88=YXF^hTR#VkFI!HAz+|Gqbx&fi(9)b1{E-dM=VRk-}X|_(c;66mJv2R zcEug$LVcSQ6H-ExxcNC@R2&WWj%2qN!sG<fGR;O(IXz}FQCV3JkRBO_H)QO%TD;o& zK+;*D)K4P5F0!tGi_<Z}+29bta&KeDVIv_WgG)u1OnP@iFvK`rynmqOCUd@N*sGFn z{VWy{tmKEIh|Chpac^q*<@MNG^}b-b64x)7Bi@4PtPqugvjJ~`F-m%}lc_&8o~3MV z){W&-k-}EvT|Z=kWH-Fp7`)+jZe;d(&m#zLh9fMwn5ImyR+156ubV*xL~@)N1~@yB z^ihzt#sx+O80r!IWmYVg=cv0d8&06HvJL$u-e2&^-GL9?ESfhKb@rO8c<4`^RiMnF zK;sP!erJux^4Js(B`5^^2`-812Mzp>0x-+4($OP4-ku<T>Kt$d7q%38yP#<tME50W zCF+R_-A#xFK52r23#vlwMz&4-xy)7@gqjfaue?-_z2v(ky4Yz7u?$HaMEC|-nX7%S z{;-1HPzCBuStJ%#?1yr2(KqrId}7I&j9pHJp8DLjxOM)h$XzxYPar$Y%`P<+^!)JU zAHly_0FZWwi9HOsgat6+lPDvFrvw;eV(IG5nPic%`v*?YOx=VlL{lkVsBFB<c{T(r z#c+d@pK@7hxe<ncSfB9fwa8e+A|Kt51pPUX&Wst1@r<z77#Yk>sxdDO#v$plm0rW? zDH5Kf<>|gLTIYnj*IT6T{C-I*wx=-^*)p(&8!>2jpuS}x^dnz?FF7kv6t7#J)&l=m z38&bXw_x5L*c&{bBhiY728Dj+c^4S%GBD}zAcY_xc^1ZFtG%CzeH5fR#lS}o$6D15 zG#m#{SWdm@ZZ=~H`vUD?_4z*1VFGeO92JhMi}#;rojL_~*vkPleCPN+7|6<+N{85s z2BDpWv0C5uvy3J}knzk<nY%7xR!|YZ@;qWO5tREro6+7355~^rXzZn+6%oFl^*l~K zoX|93x%jf@H_Qy&)W-w!GcTTxF)&tI1~ENge(5(T@LbqJw(KtvyoiO7C1l&o>jO_J zb2l#NCdiUdG)R3UP;y!mg95q38@0Y!_CC_}Ino<mq2kDVmSAH~L%g+^MAotrCE=mH z$VdlG>|e~-VWhuC*zw0EVe&Yh8<up?2UR0hHy)b^8H@fwp9+NbIp{~K{~q%=$M`_& zG`xFWdc-sO41_ayt?{}tZdYAY&l?-Q*R{EZ-{Nu8q^%y#09@WQ)R&+6_g6!gFJw`* zTQ5cF4_yuHM1?|R6A-oe^tYWfHE95h;<bH922xVxw|2yB&rlTX4)UXO6(Iu;7MX%^ z!%;?T)hb}p-unn-Pi%NQT``-%42s^sF8{$6)OloU;`=wc4;2b|-8H1b!%s0lVQ=cv z+uB2(?7w@RnFgWBgakLIH~^QF%uF@m+kZF7N0ErFw?3m@@lXV4#hIM0D4xm<c%{fd zR6l^xC$_scWS|89ZIrPP%%Y&hCOxM;{4SFgt-<G}tU={C+hA}K6GI$DLltPtvzcSy z?)9;Jk)HC7qCW1ci&>QAee!w!Mh46}SlYqg4xBr8b&Ww`dSd1$M0JJH0$gl(wHLKK z%{1uq+*tG)&U#pYLzq4GAkhgynnHVZLwO3~Q${c?!ZXEoSx$T&#?7%*7J!qjz1CDZ z<#V-Aheel~qe906?av`S`cq$eaw1M7Oc*$1H$F-fEsbz*=2CIK;OE|AOqGyXlcq8U z^$(^AatBaXC}ipaJg+aRq!4AW-hat<h;M}veu@F7vz-Sv(puRD<e=e!$k13I;rh`$ z<AyM?BX(+RX`)!{f}R8OGG=-ZYiYjrZf{$%8;6#;5Yro*b&Tnw=7P~?3{$*Ow5;#p z130Y36Y?L&^m;v1))<F9(k0%Jt&RD_^bc(`;p>v^NYImy;~d}U=A2g(pjK?RLmQEy zt8@P-3RWAod7cgAttU~Qe}#^q+c`++K*~(eM$=K8>X_u?(?D3&`Z&Kfz&}2KxeGu! zUF!^AG>akNB%%lBf;x#Ch2JlyfE2RRJiqWgUv5UVD40TOeq@yl4d}2i%OVMYgJ?_8 zH4w*L?P8h`K$E|R^N15Ht`TXm;Q#S-=5bNiYx_sTP+QEUJay3V#2{#f9kdifMo-!} zE{%X2BvOfySt%&#D9qQeMJpK@K%$Z{K@la*EjN@jYZxF$aW@f_0R)j{Sch5sy+70Q z`n{e%&Xd5*cey|Ja^2T`-Ee~WQFi(u*_oNvI=ep@A#vSJxB7JzFPuCtx#uRI9R|ms z=iJA&z<NJrLXyCPd-VtU0drZ^>+IJ_gL)M!u7+K*>{u_lPguatTxblQpp)`^f2&15 zt$e)0DA{6%JoZb8YQ$12b$Q?CiBN?*cdYM=i#{Aa49t~dA>Wzz?kz~v+rU9kP4VY) z!v^;Wamq-Hc6_%9-51`r;NQE;@=&uc0@}F?Nc|xa`YI<sHbP*Rz2<%uH$taIp8LPO z28sWEDdjAsJ+!$U<1IS{+`r^GfABgt7chLp`iX<20vb@m?>bg7ZoX$h)%NYX_e74n z;E_)JE6pj}k@4I6-6PscVy;sG@#J%s3>wtmq~7HlvYt{rU%tK9jvekalN&-BH(N}J z1Wd;h)&#Q$qtI&EH()}eqn|8u@o<w+k26nL|N3|TkkQzzRnjmzr!}}AYcB<{EIZYa zac;pGnjTCo|8n|B@`K+x21D{!w5OVUy(ZV}l{FQCVmkJo2r(bQLKfD4p6zy<L*Bk< zu{P!kp3RKg!&<Wxaiq$0yYN!8hzb!?+~?uigeQ{`jTxy{kYnvih|Gj+HLxhlcfP@r zQoz)L<d`Z}cO&|=gn@o`6R?i%zn4gwZf>R1E|&1<RU`K?b(%Fq7SG_|l$DHV>jA<< zd7az4O5DOei6Ya6fE8`MG99Q%l|IP7CwfJ)%z1b;p-Qb$3*Pbh_0J2OGXpK2RluAo zSXUIE5IXdR8g%Y!^JQYPVtpTX^Bl<z()z#XTnI!IL!aqB_vviqa9Q`<5hZTv^k}-M zbHe6)CYQCBqaN73l!-o9go!8x9gnp@OGY~h8mIl~1SV08B^v6>g}97usT_nB#1Jwt z5F#A?KBC00xV%NF+=i<PsV2wt(EkAav*L0XW(qXU<I8{yO{0=QL~$uSy!GKDHK@I$ zt7K-zQxN}#6boollh!C+RGoj1(_#Sd5;wR@^0L$Z(Cfw|J?ou%VX$ATzwoq$yO6Yo ziyAPQ<zi-1AIDfMvy4<NnOFc-qK-03p3fR0BFcgf{9gyDV*ec!fBb-ceeb&TE>Z3e zT^I*m**67wu<p9BP~RT!W;_eDE7G1pgG90fFI#yUQ;C@Dnc$a24~HQJ54gDh26%-? zz%aR$@Jcao`N$x;Cae2FXr>l(`*u+!D0@*S2!`L43okNU1+fdNvCsB{(-p~I>o`bf zFV&@zSNd%K$rYQ$v?Xn`+lWoX3-`6kG@@zd_T=&Skw}Spb`r8$aGEF>dwt_pYOU-( zA=huLx-t2mzWY><{^in;(G)xWqmlwC`;$K*mus4tvdRC6FXR+VFcPXoGj{uwx+(Z8 z7OhsZ^hr*Enz9k+KY5BaHZx4<eC3_;2>e>=K8{m~;Psa1x}ZgnR9Bd&pl9Y?j-TyG zO^yX2P~qyUNX{(Xk&JFKQ~g5qbp*Zi|AW0V=6j@UWmS~AXxjQ!?u`ILVA~L?b6+Rq z6c8*%H;2t#Fxi*BAm4@50rs(K!Kchoz~^R&kL+j`#Iy-pj)hJU=O)ehK9r65PxJ>s z1uOI&v|u~Ks~3S~eP8V5nlKQ0$v+-%SH@Hwt6b}TxSt2}aX7t&CLw!Ww!25V)N9bh zh;e9QeC_{4a=4>tv^d}->EyS3{rs8ej?>TTi94i8^gg|p>33vc>G>Q+I%5b$Nu?BJ zf!_fO`%;1PCzCwm=WuFLa(AwHUggU^gPPEHo;xY^Fv_=>DX1JJ_Z%l4I(oQvNDR}_ zsPWOA_;j`;Bxb}2=)?BW0gA`YIBmiBJV%1@3=MCR4n<vV#`O<{Zc6VVxp71aQX2N& zpoY5V`0;8AvgM<NR%jcJ=Vz|_<Y_^a&&Cbx7R>$H$VhLguAFHZeZPtHRxn8$$#$C9 zHe_%YJp16)r9a<a;C|38Gif<k#OflC6m@p4ep-ED9QqS1+$OsWB$~L6Q(fq~m-1q9 z?dxB{nMpO%<+>!`W+`C3+`#Hhvb}u?er)@ugPohQT|aL7W3Cf(kGZNR3zq}+u?-*6 z%44Mbl-2Nj_wMdw&k^r<AwGj?2c%ZWeF^W-fl$s8Bs0N~+s*Nz7>S~*5$znC0vHYX zNa>xiSd__eM)!P&S?$oWU`$9_A?&i%;2mdzy^%fLV?UclR!R3u(z@>75R47(ui`ST zVsCIz4%=)xyn5D!b0DbJGx;BpDP~jgwx3_$@3!>YNJ<(eGRT;MLe@?b70(!m>qK*^ z7)LQzW?RM3|5&Vm?uh^d!i~6U$0j-3Ff-vvqBK{}Q4tKE)uCsGnvaW~GEV}hlI{L| z&dMcJB&g;EVkx$v^FerwTH$N}1N9T=@lepsIWlO~pvivSXTY^+iD_m+lSSDA|3(-& zuL#T{T}u8)_P|G+XXcfTDZ`Wwn1ql5Lu)?DDcc@E&K^03s_NwSQ7Xv2jrUz65lJL| zg7n|rzC909*d>^;l)*H|hvo=h4aX}Aylu~&p-cLkW~lWO^q)}gqUcA`F$(_t6JA-| z0AtoD9l6^p`=r90GMbb);g@}2D^XMdTQ*J@cVU*v?HESYj|WB!neOQ=CRG_Y@2l_a zurVg4fN~;?;bVxM{=*o8sS@tmOzaFJf%l4^*cR$76L~lkm-@Q&UdD^U1<c$YAgixa zq+~jmgnZTuX!yZM^&JRqt2~M!ctZ1Z;87=eGCn}%3vRxashRc9s|AyGD;jB&-&HpG z??`@3h>TDoF^WyrF<qX5`1A>R3PNpu!t*ZJ?^tyZR}sKIz1h#n1qjcy2#RG*6)!>F z2T_<knA8DQ!FfZi4PHw)6<jYoCoIxKWjRTKAm@)UZ`aBQ!JvWf2<l6`ps7w+(o;5# zURlhJWTVM9P#`<|GO(uYKj_7Dz!Kgw^LZ>;0VFOVmkI%^v6pNnpT?wwj~z~rWhPK0 zmk7cYRu1PY^4)joeS0SW6Tfwq4-~z7G@jEn2|m9_TAGriAxh@xPwY((RE=m0o%)-< z@GQ!#DH+3<M-t1<NDtcMuB5%&7S6NW`QGQPBQ{M9`DXpO9iM~Lu9t@NBPnr3LsWn( z%?_8(F}Ex>Obn9Q2Cylxf+v|%ySwLvkt_~eKVU*6*Q(5%yP{tpsjjYc=Z@d}x{K>s zjwTT3=uBv_pBkR7vWJ<6#3kHZ^R%MEjGNV!<$EVxI(kH08a4U86VAn@y0fp49?Zm< zA+(jrN*x^DR_WHhLvs;jozNS{B0#d*osWN&VKWr*v+RX%T7CB3lsS?FT<1Pi;afvq zdgBe2rspfpm-se*R&$YR4`_~hM9?E_@pG~%4IZDOjdqR!3AfdA)D&zINP*CdTV{(Y z{BaMcX{)3m>S{5i?12}!iYn)>i4?B?G@bchQYE*qr02w1hteH)mTDU(z6M0eIY~7Q zdA~&<ZR$Is8F1zDXD{%r&cnMq;iA*)7{b;aq4Gq(*aI%HayZ{myHmkX0*6kdDv%JE z(?$+%fY=EUn<X-36iISL`yS@ZXd0wF$Ren9_=^Z-7K+pMw**ng0g<p?%p30_gRF!~ zf$q|5&*fpt;U!>O{*<xsM)}J0qI$<sQ5~P~7-lHO(tT3afFudN!aOkk^PA);YwE`d zqRy2IkJU*Jc82i(#tAy57X*!VF{s9y5|9ax6ao+O9eDj5kxx7!RyQ8P$rcI9BI#UN z8U^9(9&*rKR4LX@yWb<R=pPOFP(rt_S|EW5o>sSlVG2nwg+QNQNM_GaFKhg{rxUP- zRuPn#M{4!SCEwf%T89yi9W*p*Ole-Ybagh+6KI6sy_)U37mqyCBafj6Os9f{Enzq{ z656<v7HlYkjb*FFqm_~+{vtia^6)cIM(}X(c`nRmq!pw?GmlOL0M!ciR`U8Z0xhKM zez>jYQ@o2%<COTY3k&q%QehhHVxzYd%uX$_un2z*n}tTK>krTC``xBSyfZgl<WbT1 zTGeX<Dnf_#s?ZCeP-9P!A5!ow-~L&u(KiIl-ykyWcJ#X7n2g=tM|jxa`iX5H?buUw z3<$WMeiD)6<WKegyZb*z%+}5xc7tV~t7gCct+N`f*)Fbh(gIx<G#a<KM^iQJf)Xuq zWNfC3Ku1mO>N_Bd*;Ik}8l+A*Mq<)VXdjh$t;jR_DsN7R>{;cWc_?<2Y#tfe_eB_> zVhMe{h>=2UQH;$+_==__s&Q83OzVA`I<&H&GLgr;JQDszdJmY4*k6LIIrQ`<2&JC4 zD5T|iI|HZpm2qzRj8r?HrU>slGH68W?4FlcE-7+>p-WJ%C0Ae<g?3>o?`HzIB`r9Q zUExJ3ng5q>7p)rjZaU?WJYmsvPZb<rV(cpLmtD#*a`j)hHqlAO1?34bfz*rDmqj4) z00qD#Su-F?qrL7lDtpP?O|X^*%}F1Gx~*yMioR%6{iP_~DYYjIQ#u9-Alfl#ZrVFy zJH;E9>ZFv6v-iUN*CsvZ|9-bWB{Gs-z0h>AjmYq84t;091cpDI)l?J{-a)pDjpl@Z zQtQlWc&Vhp@RoP?6wr>0!3rgG`8~g>h76iRGWX4A!SMudMr=A)b#Lk0=o<RSBmd;S z{x21Ft#<8_0$KDYf}?Cr<Hyh{I5%QyGfI1)MtSGHIOf#GX-Ay5cwz-^2(0>A#2#B* z*PH#?4fctT*Jd>6oUu4f^k)uFFTa4ZP2z=XVM&_XrCQGAy!np8X&HHUO~Ivgv<PbF z#`g<Y8!4Iy6gNof%*jG{qP-ka(oO|uy5qhu09l*4>pm11w*Y?KwlRh7q@$03x+mL@ z)ulJV>zLgW`Rw-c99^vdJmFfy8R#jAH4ufI;D{kg&s9BwUy;1i%`eOK1}a7Y(@gSe zxnyY_L6Qji7;M0M^c)Y?9BgLagy`9rX^TTkDeyARK!-v&e8H?mU0;rfum{S*&gy;~ zw)>P{>w8;BT9TCTXvERDVj42{w`knqe=aX#_&Yxa(-AmVevcM}Ix)dqx}DPB6w0CK z?fUne#We$Pz@o-SsaySfWY0<eXot#Sz9Zsa>GW||7D90)K;eCbmJ0+sBteJGm?ier zjYylbl!kd99~%*1cU8*P^#i-$onVJ<z;Bj6QJblpI8$|z7`GODVLc<B8%op4@=Qf# z`t^wUKq{n*hon!q<2w-@JOUZIFwj3GBKIKV_Zw4|FVE&6J+J1|Sme1RP%xgkBZej1 zi4}8HQ+u(4l??}saME9yNqyNGvX<ZafHiQDn*>v^*W)EycjP2_Ue~MJlXdN);S)wD z<2~4wO2=W>KP#cY;<KZaVVCE4OdO=OG8hVC?y_c09W+RQC%>kbu$`=7j^WItCwJ%q zHezIR-}Ay#Vb&G0Gs@;U>qY-6g0_%vAdK`p9`J}%qgo_(_ty^iYCBLIqS4x@e~&=i z_d1PGZki&*Flj+7GpAzKX!0BWd4h-z6{Z)ia-ZS!`o6J^juRuSr1q1ZBq*wx*PPwP z$b!^Sp5==)0^Ml+*Z$id*Q`=@`sAJJLmLBA0hs(rlnBfqpgv-n;Yuv=n3XR5tq9On ziM3l&g$asAF>7mix!Zeg!b=O)03lrC(f?wov6C&w)T2`cB#CRS-R5~6Cj|aM(xpkg zG~$cmJ&_|vZa@AqYmevjItR<2cO5Zf(n6G0sB5g29eb+1aKeprtxZ!0_sCGdx<Zq? zhZW~CV!`^KglSL{`%ho|3r(z5d~?}OLDtNU>NC}yaANQUeB@Lr(;jWAnK(Ayf5h~2 z*Q2X`!pzGVNA*8283S>Xb}Jo+Sc>I}pw?4#RlLH^m_R%ef}!a>ICgVZh5a%>_|DyA zI6~%N5<-%}@R92{L^#gwCf5*?{RbhPWl}u&QM*KA(a--WF|bvhZ1058*1UXsT&H^S zG~T#tAK^)s1^cDDHtOjE3d0=)5b4+oj4^6u$A4WM8c24Ugz^V^o?Y)UZEP0)r{Eu| zn6#~Z{@CDO6-e!A84`}4m-i*P1UuE@XeL};Xr-V!PXbcAbJ?1eovWext8Y<^?DQ>r zJv#!vE}}9`bcF3EXi~iXFTGO1i5=OmyG|4_ACH`Lv}Vpg8#PZ3?Htt*50EEQxRKNj z_k8j6`hJM<OZQJi{y??O?|($F!+VJyPC@I)>1_To0DGsb@6ApA17qyVc$WP%JqU6v zZ7X2Hk~l5;5!F8!-Ptv}F@9smTPlSs^Q(A}%iQa1PlH(f9`Qe@Q8Om>ArP6xnDoBs zL$?-qGQuzbOm>%;j^5q}V#G$^^9qx7c8`N%MukSbpkNM21lp&6>1CQ>FAC64i16F< z%d<i-&J@P&p9s7B+1TuuR3oph3dw4dXe_j%6iZ*|B;8jL_V&f`jX<o7-XJXjp@(MN zY`3mxs(>3YJ>kgo>d|JwZXOzIo;0vwx7;=|sU3n6sSjn=gOTupEW1f_X`DCt_guYu z#N~qo-^bqs9ia1md(+VMGTOqCp?=OWyWVWGfv|aAk1?DH6`gGZ(m$~b;)outRPd~y zoxbt2^(scwKP;FexP$^chR=<x^XB>){hWi}G~1Sj0V{%Fd-Ui0?ohFAW~uzfq$lVH zZelq*bZofeBJzH|T@+2CwuaZ1Q%N#q4)`kn!;yV{A+%J4FjX$f@vW=KRT+VC*P>8` zf6$4$ZpIyG#BB5v)O7TSvZln7NO%rXsv%u$K+3hG&oPS9`+D7Nl^?~zjy-o*h`;N$ z!9Uq@%$Xr;DW_=mV+;JA>V9xeP?AlVuKz@(%mfbOnWmKqFZU}=#s}L5h2I}u1!;vz zt^2!X&+cY*w&&$=ntPzd2A(OcrgypDz>W8Nv`ItI|4+h)b3&7I_x$43Je!mTDl9pb zPre5Rg$mR`;gg~ADF3I(R5m(}ahSy~6a{>@&|RCsyVq|kk)4JbUkH);z&JU7H)E<i zJ=qekno72^3!%-`{?mg`_~#ElOP2siHgqia{IUQkHE#0_jsh`zU;2Vkz5_z1zVeH3 z=f5Iq_MhwE$NH~d3xD>r`#DPnC>c&l{(Q&y2L;V&lSM6Cc%k;n&s8a}_f}k0gLx(N z^3E<9U|^)ctvx5#O9gv-Dyni~iCMv$<hlBOOcY=PG+v5qv2S*#net4_*c{-pezqVv zSNLHoLmonOsAf*f{Z8o&oQlQ_<NKjB-!mjv|G%ayDf`$_i$h+a3OC)2n&FJT9!myS zD_<v{9<(K*!|nW5WgNi)rTmOS-8%+OMYc8y7utL15unpcvEq~%r=B$*FwcQXSSQ_$ zT=TWMeQit=JF(}aI$pn8XbzYm`LKH2H{gR#*-Jr76|0BzHw{TBYA#5q<GXc25%Sj- zbV*B+iq2Mih*7##-c=)RB^Fplgsg2;+zqeS##U}{xx%ZulzXXu*F^}X+r;`ewnn84 zWXoo*!*4^`mmF#~Bb%DPclB#eGkPc7=o)?I=uq$E#vs2G2`4pqNRQG0qjK5eA}&ry zr@p;tc$#a(0=|E1ylQqNvY346Na<PSko{jS7T`VxdPq<KOPThZe85uPM&@YCIB@qn zAAPrETPm)zbh-&HA>$N=w({{0erjeOXOBr{7CS>Oj$X6DC~QaI?;nnC*N0L^bF$~0 z$`R*N#qXSewpn3>#|PW=wg%y_pkQMPm_&9I{8+VP6QpwB*I}U4*7F4to8rIPF4lPb zL&l2Nwss~gn$^|=tt6KJ{Zv14>v)>BbT!!G0s-I<H46?1>?zFi$Wx>7yQ5&Tu}R4@ zKhfL{JEUeh88U=zFP!2<hXmA^Q>-Tq1FnMlM}b1|4C=G-jwrlq1#YII*o5N=MM7X= zGQV!vjBhf1y<~x?8Yex=upbt36C_yB^BBfIvG+3t2_NO)gKY>7VTu$jVIFNtKl2nJ zfftQ#Ar;eoZoG(j>tHZ*d;qS4&m%~#_py(n9A@mHB#kPnbh=;;HC52X`Df5L*Bz}z z3u*l@dOxTc1u6oGd{>q9;zy+-tbdYUK~3>-_%8G`rz9xwIXN^dW<Ms^2jQD;QV@+U zLqneS&;VxS-5gVu*i@eUQQ-6?v#KvkOZ0oHpFv_5GfCIPuRW#q9x&&#rv}+xw&>Fu z4$hwSrD#{Rj#RxIlSb!7-mlt-BF6)NeXe~J9kvtlqiE9PBRcQWT&g$TNCZI_2(SK6 zbwKh*^TmDAfmC%o@2|hcL6{vH1y01Df}QDJoJN(*(2+9SnL$X)>l~>X6@x*cLb873 za`>lnkB`kq`;%Ugg97E@Wy6hdBIQJp>0h1QO9j>lHEG^ahtF!)!g$rYVx{IjI*fXC z-};N9QU890!nrb8HKOj;lMDEhzOT*ebo}RLQ+H9rwi$wUAE_FG9rXV6h@az3!f3j9 zGgLl16K;(vn?tW+xpa2$&&=ujj=LS}T%k93tq*>Ku_os?`D82;eP%q5?cZD#wfd>I z)_#3oy6bT*(WJOHbq|sD6FpSa175#JKU1l+Zys)UIW()<8lOu_c}tC2!GxC%J@WWM zbuWU<ygZf%gj9HQesDy!(XV5aU5K)WpLpzB>wQMuE0xW$=MJjm@e7i&@ms;!Q6bmv zNZ;TM?4EJP8rr*QMiP&Q(|_1^_x%;GvZCszGtG)W2HLbypVNx0Mn!hWGl>IRMgb!D z@J*~@EWUr~Sj3OL#+2??rQM0%xR|czG4Z3iQ`}WwuX6|C>3PNj#dAuol-KB19BR<$ zmX26<#joqJeZ~nI{Q}!^hc?FG_#`*2W9_vZ{dm_kh$|xL!IC#$dRFJR+p?dh{l#PZ zY_5guE8(Cbc1D=YaSeKUXN@9rwO6Ac|JJQk9xKo&x=SKEUW&f)AncgalG!}j3!hY~ z|Ji7N9i+8r-VrXN_VZP?dvmky1uADOsz|U;G%ZV#OE=@8t6gfySljQ$cV@iOe#pz@ zI!qCV)x2Q|e%erdt<Y>AcgD-{XJL_oMWP|K&Q-964Ic~jk$WGDctbF&F0Xm|jkAT! zt#<pkp0DHpT3lBRrA)p|v!Ktu@sUTY^Cc=>-Ej+{LBHIdZp*o~FT8g8v?~4SZ^d2S zz3(`ey)IwzurRJT-5#B+9o&k_ii`f$C45D3`tdJH5}OW^&+Xr#xI1IbqM+d8Ay=rk zA^a@@+nZn2_4?i2h<OYUfg(FQCVk}-TWkl%D^_>na_F5gLgJaxR%qy*IMFlJ+|egk zXIm;W$m47YYx{j3GT8p4>-`^U&v>(h(;G;>J23CZec{zVXZWT0CQV%2TzdA?(+i~= zuc(2U^{UsTN^^JZygQ5w)jgCnx!2JbvxlRadEPs(<ZXFQgMR+C0c#%neYVjzuVYpL zptS(Z6z0bI@s7cFA3X1KQuq68fRh?|%gyDLf`?H1bhxGHpa~(0Gq|+}4~_-D^i!nC zzIpI0;PSe1g<fIr#QQ(>^x66~K8G*9ldN(SwLdc%Sfjf({NZEiw#OO{0{V+Vbo-MA z>tBl1(eFy{-_+naeJ<KovQ#;KviCZ2{XFv{4{7AN=U!1&n}`13o11F;|2i@Y>yH~t z5|>$+f)^Q`a<T7aG;)OM{<WKdlO=hJZS5dej9z6?_R2FHf}am&3IF5ZewO2e-{jN< z>|{HNv*KGr_ZTpcIrho%Hp4*WUAxW4`A4o*y2h|j*VKgNfr_rJ6&f8KrUCQ+er8SV zBE8D7dH92}v_`+wYGUp_s8w9Suj!NT%AT9$m-YA;`D$oB2gf5Cp0MarSx{)pLhZ9x zw(DGzGo!`srvY=UYx<oFS!ihSJ<Z-*i}RepH;KM_Z^fqA4Sdq)>%x+yF|nz^111-_ zZq9k+(Y)6YTWxDzvo6dIw=!A5<sP~C@R@kSv(nj9El=`Ht{=V4PpovIZb?rT&hT@b z{UnE$sjI2!8cN3_TFMyUS@U)n>60cdk2kpQACklr$;+|Q%TRrP!v0j|)hm~x|0mUL zQy*>}JWBm-(cOhzUjZBX9>UA7)ixTu&K3<&yY{QHrwH7nqf9zfnPN#RcKs<pr>zF$ z-HZGhI;*-IM>nWo8^i`n-GO^=_R3s&Z&`HmY2R$cn1=oWq18{TYheX6ainn=!wBQ{ zAIfq5n3#~@saNk(E|sT>5?vjbv!UaimNLE8b^hvjL3IumCF95Fk9BMedN1)~*%?`X zO@DLs84E$Mi;=Az{WeT!Ydz!DJu03gBr&7ooZ(>Q=8!9LYt$Jxfz<)?*ZKUsVa~0I z?+!J|iw>}I3H`f58^KD{NgcZ5^FC`CD|seJJ`aZ`?N60cvUz7{6`%3rldZ45^e^71 z*ox<`SQ7o5$)Xybw+rqWtG1noc%<6*yN~)c9Qv7;Km61(eA7Qj<Iab&6`lRQeyHtz zTT`y-WCKU08{Z#O_OrjMm)M0fk2=ffDbt=ln%1$fh>nMAz>wF*-)SWQ@&Q06g8}d| zG?y(!kz@6}e@7^;*s`a@nO;<>w|%ia@v~*kV@-;tR}COi=zGYV2eTAsz8iMJsyI?; zuCVEq7Huo||NQGJ`^36mG_9t4-*u??Xd(&Ymi2vHo?Y6YO4rC@c?u~;bzY{QJ$>a@ z#}YFVnqy~)f4WpFl4o~;Tel_Aul$`gNK(LI68VT<X7oIQ)!Dc+-tlX`GK+t#&g(W7 z+z5H0YXCi-pLqy&6KrDY&(`x>%-{QTsdrVV<?CvZ-_VE`y;o}9z3T1f73G#}zN>cU zx;EFq<|l{7q}IoapO+%QFk7|5F_AWZW367Y)%lpJuS9hW(e=U$FS&c4<s>P{?kQ@E zc&vx(6<zaA48HlR*2;%5wTNm{Z9~!1??C(}n_SH<VI&<|?Ik+b%bAR?WBRxny@C)T zlnsldl@6EH@Jhp)Z>6Ub$D$+@i7T`%tu-ym`Kc@U(yV4($E@7`NXS>)RziG!`{0MC zd(gD=qW$YI4dYO(itPH~w^x*M>j#S#8no)bX_lPtMy)xgeYUwxuk`+OXrgG69`*Zj zm0?ULtaqr>W%>ynhOW0x;~Gn6{oA#cwh=?mdB&E3XSS%kSFHJDd=-W;1;uf(-ZP`} z-R$R={dE7}o7Ty@&iI*0c6O7ezP(}krFYUwU4P&=ToFcZtsua39CM9c^Ok4po#r+& z`b%KQeolKD@;yHrTMqqCFvq_Bki-(>*ij$g_4Ol<ca1c^)~d5`0{h0hszaU{-Um;Z zmnzE?x@KaN+0E@;&Yz&l<Esv%S;jE-CU3oDnQ%a6d;ng6>x#U}*z~RJNb;*$3c*g# z%O9M%xOD7ZjYAjs)Nr9ET%8+t-PO2Vr@E4x*05#4hhZ?kO@57X{e*VA>?WA?R@dMo zgb^lG9hhiw!o>X#XXUFDS<cOiiFacB8f&U`-Sjpe|1?SGcjRK?jAdR;FE?&y$BxpQ z@H9o+v*k(5rw$bp(u(AMfm2eZw{L<-P%)#_c{^?KkXxucI(bM)G8P2CvCKPr>gN3b z<Ty;Rd+}!IUjcVxuUoIXp6xozF1WFV(e!5FrkTe$1WtVQK$l<Dy1i>Gy5GZXR&C?7 zTK2C^GIZ=~iOGJy_~pfzgt>ir&0KZYhfV*Af_dQkErfTgWkcBwdYB^?zS<BU-E4L# zPT1uu?=OlO8k==+oX)`>J7<<dO7L=QSS-Rogm*@Hh4%8IF(fXl<CZb_Ke`N#hkfZ> zA7@_h@`=|RpR*|xmYmp1pg5UVX8&gE)M<((23gc(Z~f9uo{v0Qe=pOOt-W->nd(Rq z8@N9`VDdJ=T#y`_=J+{t6PH_5)%E3)88oMAw~uo>pL%Yk@!kkNaF+y=YWKBcO=EHo zIKOeMmakCDw}wcl*Kx+}v98NMFN?mu;g3V+YSZ2YxlC9wWC*TqS~y7dLgI4KZ1w$q zFKCZSVP#C`k%yt;lDz9~RiDN})2m_;8O6E%#7T`VqjTbP#r4=o{q25=MMv;7%*WYJ zaLX8EucnZvqL;ol_*(OaE9+-t0n7Yuxl5x*9=|;ZX}vdp<0o>BEb_F_AU3XkQMv>K zNIha)FmzbU<2(18T!#Fps9Ta}nyF~XoR6=3zN6}LvTB@-#s{T}#nm_V8)`F!_qt%D z)F1_S))z{_s8<S>0J<^(ysP*71x`3HG?YAnD^4h1!)CfVk(FdFEHpeIo6U+Ey`f06 zn>=`8@QL0dmG+>ngUo~t=+_Rw<d=^$P*&o*azjg<m)q%^SdCot_FZS%V)iS}(#rmO z{vpSXOg`PvT(Z0dUPE)*zVOwK6G;u-j`oG*;Ey~aa~zdfwwJsbPE{ehCqFEnQEjbF zAAZM~StzQ9RNxU#Tkr|zCyzY7d^;x0r)BI?-SI~r19;5F`W|+_FRcH)_bTdm9KMc{ zpyBFkBUU@iCX(DG(hDlm$LB&At>f+SZ9D4E$qpL6Y0O~_;-y3zQ|MNT8nMIS%UMTB z9DM$Bqx#_DhLEC;@*V0MLnoFGZV9znDy>U@Cxr^@h=1w99O;Kvg`aeHt0MvtLHYL| zab%CVuCb$M@D%A_<=4Z&-51ydGNlk81lp+y-M>jOdim|_0CJsUJdUb%Z^MDMz%hec z7OiACN|UQnDgXWdKDf&Hop_?HeIXW9X8CeS%XTPkeD#N{zOvzTjG^szQKaH->c@)v zvAEi7MOXDyzlPO$s-b_jcz;J_ctPj<dB%-t`}c*qmX|rUr*$l9iD_{)+3DE}yd;Vz zbmG7xk0%ZHHUW$tsf%X0#X3APQiyx^U)k!^t$MI2N8fZVe&I)L2l|kQjrhG|>aP|5 z2^o>v**<#LPs`0o(eh2*S7bE~bICD;rlJSI!ijQa{3B<Qtv0xBGACn~cO7cbt2<7; z1ouAJ<S26HMemWCi(jKS=$by<+<E%!7_oJyqNu^J<cZv`q9Ss+yyRKqKbF`BRT}<F z(ubL?vb3V+60JW>>6#30n13q2G)l3{nb8N;UyEt9rs>f4)y%*Vm`Kvwwaagedn@Dm zX6+QOuCOy+F7s^J4X+ted-jXqG)+!m$wNCEEV9U*!r;`)?EcFRD($7t*Mb<4!X1fP z4zYj^MN#sD&hEyH4tNN}JxFKHYa9y4f8h(n<$nLLbdThfYSq47cToFh_o&oAb^D{9 z`D(Re?fyp|&(1XkoN3>q_{(PaF5Fcz(3pVB*!wT+bYJ|u80p~clO6Y~T;-RvBCr)W zEqcZSa0L&xY4;fIvJYB}FG^>pYOvH&^+Dt5AN(3tZZB3?g4PCAmi0Hab~|i2`lzq| z`TPt;bIIB!r)NQo&KYYE`Jc99?r}v-MWkk!wSBM5#}$c|>-_p1TBGZQO8Z~Yv)8b5 z+Cl^S&->DKkjnvV-+B1)TjL&iyfeJA^x2T}|LeXoTD;Yh(Kr0UPMoyLul`Ik)*K+c zs2<JpsS=#K1pDyHr6(PKeR@^UFXmUD@ncxg@k!BK#a&(D%g^gfSB|W?qWJ2+i`jFU z&)JWW`u-1dJNI`~YT8d4{<UgVeCaPqpXgRvzf|0Ki|D5hdKER{(XNP_Dl0s{m!+7$ zPws8<v45y=$0V;NMcWeXewAI;6)^RlJ@VzF&+FH4D3)Hth&6Yjafsp4D=aIVR;jQ( z{mqPDP9L4-_-RAOtdrkQtI|b@I5W?hq&M)}KcGNfv+UPjlyE~?bW-ag%l|c_`xHOg zaHq)TxF$6RC|u*Xs4u5BtG~1Ud-F#pH|Hgk;~x^!8b<F6Yqjf2HYsBEZuD!Fw~QJv z8I&<NvB;Spd186PO3&_(vbCpbqB%>QLl-WM&MRsz*7mUnZ%N8oXtmfY>r@zTPiyNu zb;D10E)6{sSFqo%ivL=gl4lAz+wD{+P~6<m5vbSrNDnJVqt0NFI!cOU4bh9iex4z$ zwVt2m!}H7Nj*~Uy+&R{f`r3hG(k1Zqdm|U%>GpfQ$duuCSQ^i}<yr0d|G6&Y)q)=@ zMsIg+{y2v0={6b`fPldp>(X4tUk{jSl>1df@*2r=7bHFMsJK=?(p9SM+xo=Oj^DSs z+FKOmS$++9cZk5jr)Dhg47vHKc0qyj+ml~i`>7n7j7_)L{=(8gwWogB{Brn{Ga`oR zYH44e+`HD?@YCJ8+LQXA#-HT^cTAaOSD2e#YCBF{(eup3R|h@vI9e5k4gR<5@t`4= zqbK?L-+f!FY~>wcvTHdvoW|+~*@4?>o^19xl25|{wIlErR-<lI#6<ZO>(xgqRX{Un zMTj<Dbe>-OS5d#*w6Zmg|79so$2SeG1bOtKqTjpTwxq0(8eZhNDGzQ*`ecaVmiAqx zU3Nbd#o7EQD1v4T<e@f-WAWrScXvCE%jR7!dPo(n6T;%{Uamo-f7kpwB=UGPW-`#H z+i~Ru$H1<zmv8oX%8+?W`cUQy(8UH+b>EUQxac<N;B#NN_S<KK0Ylf>i*RvMuW-|f zr<81!o7fi5z8F#D%~D*sR(Dx?Tsx>P?(=2K{&f%ZeE2Rqmd<tb&Ai*I;Jw>p%kPYE zjL5$WPie`}Ki_RX_Nf$S+plOib+>oZb{*gi04elIUB^ewP)>_S7n*H#XaMjwALil6 z_Lpxu{k+5bSh)Ar?l=B4`1o~fu(QU#b7|=v^@c$0gW`*^R_TlVQ7vFV7aQIm{j<>) zeM|d3@8RXHMM1+-6h{^Ur`9*_10}b5Cw!u~k$3jfaf@QM4m2@MpYxDrqWSjx`}JLl zJBfx@qWW1Lc8Fa_tJ?Og9y+9}m-ojtQ-2!d{M#@*_L0Z>q~DbXzf1Z=QDQ#7ZvTx3 zX9kkh|Dx|rBCU<OrT++psP7Z~g4vWuHFBGpS5)a&uHD~!PI0LHRQbf;yELE3EUk-H zvr(y^LUGGE;%w8M{>ecDhV;5<x&0$-@g;#<|1;x*Lrl^<UwJmpSZ&I+tpqcjX3<ag z>FR%Xo#>WqQX3dNNJF3)|9X+*R5S@QJl#X--BD$KZhYsv7xtYqcTTwE(=zV2WpC#@ zPCgYF<TK0q(V-g$6)qo3&W$o{1^Ge9V}?71&u=S6+n>8a#6T=YM7|><6<uN47dXAt z2y3sx9H6N?wCj=>NvkxsJaOmM!g6h`Y76VOk5x(S8S|uXWIaBXRy#9xYOQL8<uKab zVI3>ImmPC{nfR*TZ;w3snBn$*vCO-LI-IqZT=O*~?!VuE#_$v^55wIDZ>s=W!Q^h~ zpaV^}A9X!v{_Xm2DYIUmG3B<s-<H?>Omls@Y|U@}d0F-N4@<qa1|RBJ69R0$OY&>E z*ibY7Xr}ehy;I}vbbfy4Xv*uehWD{B989@ChNkH1=zfK=U5`9=8h6$G+R97|-O}3q zze;y=Li*mkSz-J1`wyX<kd%5dtV^NwkfeTW=UEl7Y1?;}6tR+Psr~5gj(ESDW}Eu! zqPvk@pRC(oaX<2-fq9PR!#b*rQqd<F>d}1pxuY$nU3G`fB=GJdm8~Y1)V3rk)9>M! z<{h_#<Qt}LpzPZ9X{w`rNasUM^ZBcQEI%+(;XL=LPHyP#6@4%>{uIf>maay%M_1%k zwe9gbG)5b%rako0#j?x-a+kVKo#7L!&&9>r<o0p0Zt^w~<OdH%kX)I+x@hW{=9maW z)<jU=etDqlT6V7^R=G|^ilMOG?POpiV7%kR#LVxUhaY*Q+oHpolM1(}EFWA*q8o5q z?I{ye-5JZ@Xr8%xQLJOyzSBYwZ9{PyWc5^TbVB$0>c7XFLE^}8BT(DasPyhHmdkb5 zMI3P5xIG~GdB<OU-E^DYcieR!hM--tZu&Oew#ChR|2|`hx<7wW3~cK{_VkeTnkO9a z`>fVJudVzO14D0m^-?>RwTt|Iku$-*bj`YAL+J&EVQ9@;l(VJZV?Q|5kY;~QEo3pt zl#0{iZ5e-sAGmj6&9b=!Cg07S-OMc{m#c}9DN@IYB;AHrUzU|&64Mp8AyTg(E*qTr zL)KP0UfcXRTYA^_YhqWdt~7<dI(31fY?Zm|<A3+AwN{B0A)rNs?7oTFF^l$FvxD$w z_J|YKTGwCXV76FUD$O~`zGUI$)3P=CKUD!$<p~jZoAwoxJ2^T+jrP>QFz2s@NH|~2 z%T_VwE82ArRX)2(m11?ScLUV|ldqg!dOY!pBE9v2?2FU>r&Ck`ZGYEcz|x0ky;h}R zU*-wf*Y0+H18;iG^0_+K4P)!I2*tynl6(vFkslmjfWP@f8U?dbjH$oKDv}%XZ^sx~ zMz}ZNaR(Y~fsdGbOMHuESl8S47^CuOKGmj;kqVQiK@^8;(o~x@KesEqYU!}F(&qNd z12oKBPHW-I+s+@hI1j#>uh0zrA{Yb=WxpEO7x}V>N%uyRy`0-MUJhS{C6O-E+>+6f zZTgl(S<4X^rX7Pi^kg7~DXVq0d5=8Ke%Au5E9}Dvs74tsxyJd9G8{2(3_fPj|4Eau z)!~Yota!Ni-WrS5^*caD7Kje-CCdNsI^EWvKD>5k`PV+J4yRw)F?Gcm`Es|h(3i~7 z-BEvIfsCa}7W*pZ%LgI@v?ok^#l>h+Vt<xPlnSmyae~_Q!iGP@4*~9+u_PF69LWD% z{GfA4?(#^-V=Z4bTJ%?YgGPNxeyL9DNNS03DNUaJY0~&*DJu89rM{{B^BT?4;$V}a z_D9L_$@CbIEX6n6Ugk!&m1TJw>O0F1uluTL-8RWF=GxcLt`@$dOB9{+6<YI&%m1~- znW+I`eWf+d-&Uc$Fm&uTX5Stz)=>+C&y>Oeo8#B@u&N(|94@iyDYZd#MYldyomKaY z_OH{>d@cH_S;@o$h&qx`GDJ!DJcGCfhsyU__o6&dcI)`6&j4?JG;~@ElNH}CdWFeV zJMA|{v(Agrg_Ll`-MBSp)wWGZ23OY3S=(Qq)3~<%T0_eov+ubTAAb58XMHaeV>__K zC0AsqS3_r#H*d1#Nr`bAAyif5I_|O-#=4#}eiM*mwOq*+y(n9oDP(xpS>XVdDJ_sd zQpWq(z!V&<J1+FQy?Wx;>KiojuYe3INhruxc4f#7haA!pXYIzt$5PM(dU1`bdQE|B zKw$*UpK~1=dWuV{uc*6bCeBFkYI-%F?yf7s)wD!C@}<<yiGNBruAU_a(d>uQEYWd9 z4ZC@Jn@P?`y+L0DQ6N^a_0|13q3NbPW#V+HU5hyTaiv4Pwt@D;JVO~{<g9_fgKnwc zzz5dI*57<mWHrx@M*a#FlL|-1POsk-Pq|O-Sw53-yR>WPe_3|3Tx*^9mVn4KY*E9j zumK}#+09dzhbsSW$|d>~#+m&vE^U3lhK$aT-Rc|0-v=YwqGeQphC7d!c+2UpZ<7uw zHY9GWGMoeS1a22CrXs2J{OOq~_Ar{NCr|DMQUVOM;fY@U<cL4{UwPvL?82tSti)i^ zTX#*PYeEj`I-<K)d%`#x>Lin7BomsvAl&jbGu?Q>mixL6scWfcJegS^Zqs#eTCJc{ zL`2IY%@h>golHv86Dz$TdP+ISyGKK@k8bi2V-?jeuls6L(RVoC<jN;mAzYhwE+ncF zGGw;o`bGr7g1noKm%2iIY&6RkB?5#a2f>*GZF;aXae0C_dz<Z>f`xl`EtEPNbM$=z z$a1q)RjH05_vK9-Vcl*?G9U8kTGl)rj?_LNPASuVvgo+)GU;rOW*Luj#?_+Li-+12 znofn;b!q>`#kyh+om|EYRvLuo6h)iLVyzWo;Pd6F#qgU%L@!G4-W?=c+4w+u+GXB4 zqS}<-^zYzf<*Rj^ot50bg6n+m=K{l_gw3b^xHbR8vL6;$S{v_vQ|qj33UR??jV7^L zF}eDTolmSKv@GK$5?~%w0EG&KDXZEzH%58D)oM4NiauvJ^sRPz_l$)fZK%Dcq$2*C zZ@9JV_bT&^%D0Ygc(T>xSE=%`Rk}_{l_gz)RC^RHZg`z6IAl6~j%<y9sKwX-vnAZL z=FM$iGz?zdX;>GTxWKvX9i#$`Z^R831HLJhu}!${%H4lg85=tDB31utE{n^_YZ^9V z4F~N6$a0smSnMAVqZG9!&v;F|YRC(p_IvMSQK5Z@`sR!~uU;+>9{T*c!_zF^YC0-A z{z7r;R(_3h@9C#*fG|a_nLcAPq++?y@o_1lpD_7l9fAh2x7CMI-R7*AEJt^QF$9`E zcACASm|b#x|Kg!dO(FNwI)3Yl>Z$b2`z*XOHFuq3Bc}apLa5@CeqW6Xy`@}whrJ^9 z+-Btq8pAEp*o@{jX1zcyQMC3$z!w@tmDqG+-S>M(Xvn=2&R-MzCDbIPfwd1OwQe!W zFtvvI&&hnh+$6hMb+~y+fsi=y<Ouv#wg2nH<H8I?$i1e%gM%&=QW$hRe>Bv(vaUqD zyyev95aacS_Jj!IsXNW{eoP}Qr9dcl#2;)d`lROQ^^WYp2R4BDfNqO5go^F}b(&mY znrlD8=_Z6Rr(SCi11?uJ>-@hCy{}k2>*IkBHYt|BJcHTc3-9oYDlaicS(NcjzV=r3 zsO<5q&ApUJXVb6y91;7)`DNiZMP7A{Ng?)eSe0IA-J(C3C%t&;M|Dn(^N3?Unk}0= z#Vp)=N^hO0w`vWpHwqr?|9i}ztC_gHe}EE!cp6fj*xkY%yzFj}MUBu;hR&Baxb#Be z?oK?wvZCkJ%k8FNkbFqeE3VEo92vYhS6Aw~1T4bC{4+b2r@1wu$~^(cu0i);O=o&i zW@4%h!VGj$&CJ9D4Qsz8-mTueuc+o#T7Ynm$t`eY#Tj9eE;|s})@8H^m>aK3Dg3*X zh8;8(pe8H%(0q3^U&^I&g_Giq2X0AcAGE}@nsCOzM!^Cs_v<=yPuHIMAW$i&KXu#U zAdb>vqoZ~b!i--NAG38;W66X~gqf`~_J_=hWPX9xk0!NPIGg$Q6FiE~jgi6uY`Sty zkbbUeTgbU~#+a;1KReSc!6$r@gQ_Y?F2t6nNz0<vR4qEey2_iUX?Y?vXq8B3YwacZ zA;<TAI9nqv%bvjj)!5k)@}{2cQH1B=x`zX(l!Q0XkTi~DbbJ`-8rHol)i`OOc@L)m zsg6n#vqMBn^d2T&hGZejlE<C#%MuxLFC+xJh-EmZY`wTwc#&eRl3SQGK$RqKHP)!P zc02&YP>pCp28(dM%I3p16Z)WWrrB!7WdK9bvahhUm<WH(eLWJ{b|QiW7go0|koM9) zNxQmZgqw#dTFFZWX!L4ATNB)Nm_2f_5WV_yxRZ!MsAZ`NF*`?ol#hJ34R%)<51a!u zgm`_M>zw89p=KWmXcUW8(z+O-5UnZbpE@yR%^Zg{vDje_U}~}e0&5B#s|u!Vtd|fk zU{*;V1fl09y=iWTr7SpB-@rAFrZJtUnE{E8cbp={V1NXil5H;H$InP;6zku_JmliW z(9EN$3!r>{{ebc0KVzKHc)t^AWpJtmUqIG0!oU)1F?6w)<zAx}bM=hnGEpg<Y+Eb} z@9!Po$XgRTQux5D8mW@;q5yTEWM678DiWr9l3=Id#i1g}TrsA-4?#@*G<j<dZi$&~ z0u3&~{{|ok!>c^JJce4yp%JD6R8$3@$PSW0WnnK6gijAC%P*BhEl8_<$1!gyNhY%e zKz_b6xJ2I@_R4Kl4Ig9T8n$0fbn}fb>ZM*nXOD&VkeyV_sBp+Yjd-e!bI@qGrw-)* zDzGN|DT5<^J!B+VAr*J{ZE9#<SA;yBE$&ngg>FfP>?KrmPjOHQ(AFw6G7{0;7UZne z!j+UskouTZ;y?XdZ|oNABWOhoL$aW>Do3npH<OmLTP2!ymZG|dnWyoWnve*^>_ypN zJr6n5r4oyk3G6o$P$D%TeAu|h694Un&Sp5REEYgmrt<5e)px&RuO+1Pye!|jG%PUW zDjg3>ByH+@_ksQlWIIJgqJ|+!{CoPP@6t+YxgVkHDvZooa-%uAu`w@=#UM<8*383? z2o>{``Kmh_#l0m8p1JFLjUj&bJVj__$2Tpj;{F`B;N*!|Y0HOWojHYbx#ov4Y43lk z8L{YX`>{?Qh#<?6j539XEod8m?Kl`5y;yBitEHP`{)ju-boz)+cBW$v?BF-n6j`k8 z|CYLj?3kYkBd3sdlBlYJSR6*Xmx&!mNw#M7OV`U?;g<(@eBKhDulV>g)1QAe53A#w zlG9u-4E*CjzUtLMfwJS4-#K(QUMlqyZ%OdBNvJvOevEG_4{urbf>g40p>){q+ek&= zthdIh4ULiisbfM8$=oSxejWdt>(ak}yM6EVDXWc_mS~D-u{vW#nm2!Da&JeG+XO_# z)S>SuZbg~av7zP1rBpfo#w=IC#2w2Yd0ZH&?)pIeFO6g!pp%?y#rH0H*R5?qh3fYI zYH_S1L~>KNQ}My?*Dtx|b`GUnI_$UE%j`U;cwo3eeP6Z8(0oBVF0FG@!Bj8^msuvj zy0P4mJ0{Fmrh20^W8sr(q+aUauRB&WtbNIK;r6RQ6Xs^goV&_Y^g;9s%`Fc`bNK#! zQvgGj39Xo69M3~+d%^3a=%8`P(3Lx0UbDn%JaB(gOVyu$26<)=`(anxs-r~2&6fuz zu4&n_rK!d9VzIWif5X1#rU^;A7z0bV>#;NfFrvnJfBh#u=YmgHUDe=Ji>va7&c*$V zjh)?dR?CJ2FOCb4er<dw)1F#nTIem3h=02pv3!EneP$rYaD>FP;c({4MRPv2q843X z2)fo3Hg=}Lumt4odB=NCe&`y0s*j%(a?IwVlbY~26Z~{efmGO+I!hL|HU@+jC|(F& zyz)@&rX!w@JmS~-beXDTqlz5zo5^o#@91N1FH0kp6|r1ma};!8G~Ea|(}QYn1-(_| z8a((LhiP0_TBxhmku-6P>p5<mx1N<5%I#U_`(cf2TL|(oFtUPjq5$nKnnS9$&3C*U z{oL?kx|_aNq}7nxtaGI1!-dEe%U%Du65Zt}ZnU(%v{m1`N{~3!KBf4lfK43kp)qv& zNk{DI&RqK!Daq<hi~O-N*~Wwgj-qy{E<Ukc<`|`B*sSpCk<r~tYt+8)^4@vwfR>~* zjK9KaWxoh)@d9Uo{j-yPy7tQMr|Y9zFLkCl;h+u)R1aRpl%ljWnpSWmt7kJduvcEB zK!DlybPX~+#Z@<IRLaAdan~;y{`|hds`C6kqfN+ITZ0_<zm+%(Q>gjg&mVGxExt*@ zWUtt)^VE$N;ig9hA^0!cSf$zV)r^}njxC_a@OfG|CZWkU%f*)MG~|&CQAGw<bYl_G zd{kBTbj4~29%DMio$Z0#2CPEO*{BFG95KXgwOm>5C>s4RUgcNmv}8ov-&;qdFsHH5 zFv2ujDeqt0a#P8?Z)a*=rh8+{R>?N7Ga<MkW?+4oQr2xl*ikq$IDS*Q3#`*xn0^5F z6tubr+klMemWa%R%41}qRfE{jF~>QI)HqxE%3u04=84@3U~wk$la5-}hy>w24Uoy| zD;qhGi@BTVP6k&6gMqV~m(}TCyW|;l0{NVb)W>XV@||N}mA%kK8Eji#qwK8L!1rP2 zwR#LhenV?D?oc*(DE<{|8t3X8^yM69C0oV3<IJ+|<H1}D8NXjDDm$%Zt^DV4zW&FA z<qsE;AQo5QzmMU$5r}hi@%RP1l~iJP&ptkS#0<x9aj{vl7C|q#Jg`C~U+$Nx0I1|{ zNu1D;ScRjQ$KOE)F?qtL&e01HalV_Ot)DQzXCG7)v)%2xt=edO{~o<YJ7tB055~G5 z<VwziKUXMa2IdXuVi(uD|G73dePQ3!TQs1IMo8fH<4mbRZeMAFqu%6<NqA31=tI*D z&Jn_}IYd6AFd+;fC3IyNy%We}3`{6&b)gKU!=Q$H04Q~PZt;H@bLMU}V1NhJRl94m z85Vtp7i@ZM8n;N^plCh+-LrR6rg0Cy!eHsl@M7KIai)4WU_#}#Zs*%6IP8iu7M6lF zv$LD!l+<VId<ZSbTjskC!UEDjvOJ3Z2hQYSC^l%f$+G787>cEK*pgC#t~8Gl6iv^i zOt$XsnX8R;9^&IGuBa^f#-Kao-*6ZM1fv;-U!>sU1d>i?*|L|gC6qiua*M}rWnjJv z>$n9z#CDBTr<tizY$7m7p&4!#R4*W#htm((%?C|_;0`Y~6^Mb?cElg~dB!W)XXEh` zIVfts0w9XJoV{=hd1PxT_L#}>iIfWRYr)-lx1gdqX)H4#HA^%4ks{^0celf3BgG7t zS9(IMCqwG_Gr29-RDmCM=YA@g3ArMqa+XBA9FwBr5M?92G&wk4C0^@mDzF8kC@()* z0~P^rOUBeuuizGH^PH>pK2!X1td(U2VuKzT&TejZBX1sxlA|rHagIwk9oJffn@CdG zAIITY4O^q}HnJ)Mv`u0lT|h9X1@Dx_>X8kyiiQ#!NN;W8a3D-DRu4nXTUuEr;%|1w zV=wL8e=`?vEchR?tj-boNLo#uK03xNYO`O@O%ok2VYaoqN`lP_B&%;~Tf0UUgnDj0 zy$~WekK5pA%?~NDD&^TyCWBF<%NWAk#Nb5^d-Pn>xJDizv3$q<W6!9l8V{0dbJvx6 z-9Z)F13}c|tScdslCqv9LHjX#$r#!=Vu)DC^UZpxlY53`<esqlp?>@@3VJS`b2Zaq z&v;MegM_q3unuR90K$wga+00=@FT_;UI72i<xBSJ%62=B!f-{|pMzjGAD^eVny6RG znz*mrj71U~Z2{0+2!E(+)WLCxE>Ja)P_I&Y$G^d;>5gT%I!oSiCV0T|RvvDxq1$|0 zYAH$UT%m0x0jWY2PC0?elau;s^xvz06kA7d3UCeZNMg+h4e`_~n*^kWVYf@jL}}6l zF)rSZ4AEOZdsYc|>E&p}Wg5e@O$6~vo$1IF1Av<YG{O<rNClNMaJ!|OExhChJ9|BA zN$$;e<-rO|pS(<#DR(~ve)YXvj6*$!R>2q$(INX#4WA-r9x$Q9+xz&qiyge*w0gX< z5RTC-r(aXlo}RQ-^|GW9%=b~uQJ{JecgB94wNeNc4xrSa6j3x4xq`y9jS5zh6Aiek zDI)YzfGL@F6@4CIjLxytt{xklQO3qQlsKqZoPidKw1Wt5Cq(;%<M9A<XNSmmstgmC zgvyO`)%M3MR>fuJW=t4`In>BBE9DX6;RDzR(X83Rrc;+yEKupsh$ZVMl5!+x3kwQd zl=b*NG)Wi6hZ7{y%n+c(qv@=}`(ow>Ah1@KRK3l;c1+=#!g9g|JiOXms;CL<n=@jT zHfm{*YHldg8)30Su85r>LBSg-V>RF^O(Q4ek9C2;iV76ZbeUqFDMhMJ)aiYgt|p0a zMXKafzT((rqjHPX<5y);00Ty@gH)7!HsfW;zfnC+hh9_by2KVp*jK?O;UjoEt=oGl znPuQ9ijul!j;!@O<1Nl}vXjZ8E3i+pJx#BV8_P8y^U2h;FM5-1ScgJJncy9dxk}Uu zu&VbfUAx4>4Zf!`a|jull9P!HMK4W2ZfjvtJ8c5|ju;@>04HDLZN*!5$C4XERoeD; zT4}NdjWud65;clcjW%-jV_3b=Dl#$=4@=4dsw<3~cdn^62B-4CMD0VvrG#SPftx<K zkMgr8G)A-4wWew_d9p*Qbw*7NZXsB?cfXBtn~;u5UN|ozIvHYml!l<~x*<A2zfgIK znb0(m<cFGEI|vZKEMjKW>}boc-6ozz{A8JP-0pxJYP3vr?me&)7FAzjri`~vRWBMt z)7c`*HaY&TZYNn1bc|zFdwXnQwMRv<ez^cN@@&8^G*u?Vkj&7@Bz1B|Da>pj3VIF3 z!g-#~q-RuqsqP^Lf^LpJ2zMj4zUzeM0VP}Ti4^908Tcg!*G6|DV({N!qPUHxnlfi4 zlBg<jZG;VKCisblHE<cZODPT^fNcV>TY<0WH=eYod)TP+ETq`Hj(Q+l5^a=QM&tCf z1!7|<cY$<cY@^~TxU7ew`Y5QbH>jy!rGUS`=5Kie@f&?wJ8cBz!ze)aH!>E^1T>1o zDSg~R@+lMic(cWhBH<H(`7g?)y69VcCjp&nu9K%1`{*GF-+>F7=f>?G!-<k?>jetn z_Sqy3j!#5YFD#eDC|!jQ;?V<)2(2P6P{blWj?KjaJ1_^*pl_VBf|YvGUXU5M+LEDr zsmL{9JNVAmPpeH9cnnFTWMtXz_CCWll+wQxeya^Si!MMRXq<vGJPQ5<gC@NSQkg@v z^L(0EiQV5Qx1t?Fju9(%aUjk~@j^<7<D|&o=|xbmj7T-TsBI$5n<tRI2q&@AW0spU zk`n4YbPC6opMK9Cj$#Y<bj2u8L9`m+Kpf%&2*^8s{bS_-EQJ*lyq{9_9mF{-{YfY; z(QZWMtbG8Pkk}(RlnkeGrha*as|72+n66Ybx+4e6TeJ&-Ekvlkf)pA@nGNGF=pjR+ zZ6wY<Vlz!RI6e|7Did%W0hq6g!1WaD(C`j~BX{14SIvDdXj4_TO3uG5<gCJSW%brc zn$S$-L2VOBpDauCwE6@W3rWmN6GnOeVHjgJ0I6{j$l`4xV-W&rv*f!ld%P;S3yuxT zbCh7DTg6v#<Altx1#M}a*@@!$9KW)WsU!+o-UA6&K?><8i8?S)DXNF=mJYd{&;-{$ z^61nD<M;n2&a?2HP)%ctyKMUUK#eAi^b`D**fN(53?#5=E|*lW)<b`-)CvG2y20#2 zh_ajeo#BlNTQz{4Dy-!jE!pZ9$MaaX8VUi*HOg-oQ|xy}xMK!RI9s&I07~XhPOa|G zUYb_tl2xa@QpPvsrMVU;hpe2fSuuac9m&=wiXYM9G1|oN-7`s*!V>Ft_BTT`&IHe+ zt~$xn2k^8bW`@|CCL4W^?XA75oacVv^YJ7CLn7G`{~?IB*7CInWbWKmL~wihAF%9s zE!8Hb>c6{Z+eku5N{OcfM<>-qO<J#b5s!`r6fXirKZSkie0c-|+af?3P=60%KLG8~ z!tJMCPgU6&A$33X)k<>v0OGsmqTTeeM7k)v+(!5T+&qILx&IM;V7EQh8n`<}eO-$Q zWZ3alO}IrP*To{NGs3V$RCp0Yx-47z;F5v16_6#moMX(AE!O>SUBZAIt$<ab44&|N zC&W@4&;D;pnxQtvPitB5!E0+RcSolTr1dF|#)yir9}9B@h4aF))Au+>!Sz8h9B`(e za0%=JhYC`SV6;X+?jqL((!_R4VqSN~Xrnn+*XIn4Aqa?@AxxEIlIwC>n?{ZgE`Ci( zE+HHu&wTa42|H|?<l$6#jSAO|x#OM(h!$2j&RG$eq6wyRE8<gKo>=igXo;u0UbW-m z)3fck?G%K>E1hF=is>HH-3!8Ovg48Zq$9utKeH{Nha{F0{+K?9sLFT^XM-bEmwE;- zBEy@oFkaEQ^^lP{x*9df4GJ>+>&;ax-zKrxsrL7z03)qHaVu3gT4)%K);t0ipy+KC zF(I6sJCJu@{S_IU!S?j-zAg$1kqbm{)20yTK%?*F_(&nQheZVipK7^+gd90OPXZo- zl`%RK;0gYN0qLPiig<V%IL1rCd>p)8N&sKl5#maT0<4~9*o{S;A|2wO9T&v<sTVv~ zp6SrJu93!pBPpnSJ9Rk0fvonDHCbE=NFBy0RM`jBOq!GbabF{1R+{LwX30cDKYNua zxY#0+7=^}dm=AUinCwkm0D-p)9cn!~8-|m@w3ABK_X|*uW~OF!s9C(f<BEs561mfD zkh~&x1qz1SegH!MAsc}y#7vn8OpQ_&#zftD7?gy4hbBRdB~!zNTt)0u8>0t;=F~eK zc$)OyWP$z0useQFHbrMC3?ktpGCo1lgNo0kxuPV_N=<&-h7qEZdU>{(g!se~T7%-E zkzBMR4O26j<BuotbF`wG0e;Hm&SJHk(Yy@3G=_34VzM2D4}Sf)!p@E;_l$zkUJ~0h zAjuVzO*m{Fv4DzswCe^3|F%XST5Xo6k@q=JxA$?O%BsFK870Ej^D5dBySemRbUUjN zC37x$r4RgPQQ$<lpXbAEv)92eAg>^<jx;vPQ-i4r6wm{jd|C%Onsx(Y6Hb_aJG?Xg z_%z6UseD|!xh$_xtfcdEeY=agKpqDhCJSzeuaZA+Jx@+YX&~84mZaK<(~e^KW|8jQ zYE_tRt^O2Bt{W~0awwV|!_!i&aVF^=afWcX;%y>y%jMNA?1AqgB`0H8I=8X#SQQsa zvoNW+-bhYD2Z=n4`vXzIjlyW9yCDujm}k5YU#2wx&;Z^g*wL5<4x%Q^{glARBV1M( zV11zfxJ^q8QYl)?3m#W_l09$<54SxtxrU*BpcT-Yi}+XaLg6o1o6a@-_X>eBHWP?N zPd-K!zuO~uJonDXnTVaMRDO-MDM5EC-47Y`G>2oiFWo3cM5=#G6?8?L$PGef<kPfv z1tGji?kD0A>mG+vgYT2*c~CNksYHtkp#X8L01WgGcpY*49yc0@p3mwU;3FEN``xAI z)j4rC+VkRL80Fv__NBYe&$QYbewkM3fJ^Gw*8iV2tF3m@Koh_U(@raQi{tL#8M|@j zE0<TY>FGA+WA2pL{6X^>YhK7>kn7Ro^XgvB(#`4ycN9D#Oh&Bb6KMe5zIqA{frjC9 zhfJ<EC7@sxXKOLmOe~P<%hmSIxpCKz%2WTueXureAQ%A}+Y*KNi0l}!A~O!coqZe< zhR|MaV4{mgnMkJI<4xg=P?x7Yr<9Q<Q}-;jAG7Qd{;QE9ia(43BUs3PS=`uzbaL&y zQTm`ehBCdPt5aeSnK2+8M;1G&Ag3eeJw64|Sz&M*w(-fjm7Gd|`t#HEAN8-$te~#v zXzoKBB}?Qw2;2s9T!H<vsIp*$<HOkknwLV(Y#AWvBKEc?1=8Wh+bC374Psb{Y+g1p z^XJJ=a;3uEqTAD<q3}J%8&x2;pRkO+kN_Q(j%VlpD`}6)M`$GQwW&sHc-0RKcT@I} zS;c17n#hdtiSuh%oWbuShRx+>N6uNVam8l&ZDBaY9GIKUh%d#e7!nmVszwZ-o)80( zwYh@MGqb*51=*51V9%Ym^-xQ|waGCk(-=Xf=)&34MYfm3VAmQjG?ANya?k)Q5{9Y0 zMTZt6f4B{`G7E_oHB3x)6cN*wCL92uN~<d-e;oBU6&e<c#`iPCF1nMQ2w$jzQ%$@v zl2yzqM^~CG1&$RY0`l4eB((h;aVB361ubJ+`YgY0%3@N0*qNZR+=eHr=JghrQ`xaQ z*fwlK8CC%(Llz-?<BKe7@W}SWX!M{_ZD)f<PD4<FH>MzqAv+SVK#Ho6qaKXUTsvpW zWbanAvP5buQh-UM*R0xX6*Ul#AU;<tk^wp3CHx@vEehxZdr4)vL%{gpBF9%l=B^h& zONEK8HsurYnUvYjqrf|4Cj@6FQmt{zqI44ix8KiMkA1Lo{TaaUfLX$M^Gv6#j;4aV zshUDbExPucXtOxYfJ?3(LzJ?uyad6Gy5!#XL!7eJ)kt2>mHG0t;-l1>LT_ii53ERT zlG`h|;oJYFI6q>5OU?=wwSuP#h6!*%VZc*B8%(suZ*A{=2ZUbqBAjDbn}?~TaEC9D z-vqE7m!_|df}Up+YLqijUtE=~;3~YbhP<>MuSjg9Zmb?UvxR9q;(uO~9ECVB?widY zQkf1x(o9YTmx}WR=BU1M>xqAwCzuU0tkZedTI+<AX|*Ys;%aYlXA!%v6w(}XWnJQP zW^jIlQ@D+OJuh|CV;0ie+L@vjrlt^&A>5`9*2cKtYf^OC+r2Vt-PNPEev$${3pb3> z&By*pk~(tXx4@WS$`2Ff62y_XpYo@QmNc29o0^K?dn)htW1n4WuPk!={3_kUMIuS` zlu%pV@%r<`O75H237{iy9VVK!)aJ89lmiPF6}0qA1*u!L*&VVhyQKHcP{9_0wzu-Z z6MZ(6Ql4B@bq>g?71++2Dqg=!da&*7ls|=ECrzZbH5gSxb&?{}`%^(>Z?l4BvaXaO zPET_x5%=K+f9xd&`%sNzQ^*;lCJ~#A(JoOtbxi;9!e9w3o%$Q!7~ySTa2&LRbiB2E z6T^4x$P-7tYVXSXVri&*o5paP=;=xRI%OIqx36f?_@tQ`%6-M3$c*e}r@{VKUdptG zwL)1{=dQKGl#5ZSEuzIfXXQ=m@JezT5XGhoo<q47!-Lm^Ix$^~|5wwyz(rlB?f)Jq zHEUUMw>AUDCq_q2vBgR;WOB2{L2U#z!UZYOh-_0%;u!KRtW~#SWDp6>850mq)bNmk zCTS*)sG}T2O+e!?g34h~V3<Sy_h<V3U(aiwm!Zsjzn{Z>xbEw|Zj6K^-`jLFeQ0b$ z$`I#aJ@pGk`WiVTNP#-M_IEZqLgb&9^GVY=%aj19oj6CjB6!duu5q$Q;&s7ZqH<48 zNV@wlYQRFnY#K-183XR24Dga6LITt#?VX@j{J^2X>2hhqo2z9X|B!*5SAgsYF<NLP zat?;^9=gf=J-&R?<RcB@yY#>=GUERBB0`Ln-g;CSM9>c6x&<X4H|xWIwBmH}Yl4WA z5(>NcI#|~Kael?e>hoOJ0f^V>)xM${uw~%VVVpL53BRy4jb`e+jNjc*i~T~zyo8}m ze+=LQB6*3HP~Q>{_U$I(IKWCgVjhhm18`=`81Z1sbYqv|j*wFTOHi`EGdg3Mva!<B z9@mmeoZ*%4x+U(;^_k5bpiTVgibodEG=racRz|(~l7qRKIL1e2s{6hr0#RL$y@MoM zx$pD=1cKvX`uCjq6rxlW4x;8N+CVf5JEI+k^ITrTz*X>o+)L$=)H1({^r21bLBKpD zIf8bdPC8u%rzQ>L1mRji6`7E~t;iKgq-}9k7n;5|2f3EzBt%NJ>T!dJW+^5yF}Z|5 zcY@{+ZBHkQZUm_S^}KVy!upRl8l?VMP1ZYTO0-(p1B@|&3H!hEsg;M!AfQBm_P9`+ zY&mupGcLPWWO`YU=yJ+}J^NR3&Bo13s08>|k}sqBu*mw^F`us+h*RQ}nFM4kly!`3 zxq<F8t5_=wmce0)ko~q5#{W$2j~ID4rDB$79g{iat9_{o+GEEo4If|W+}c=iLtO2s zpbNVD0csrBddiO8*=Fg?JnjRly$?r`yi^)Fv)QZ={DTN|G!CR+{$jM7J1|7#q_bov z){AvQ4LF%CI1@wi_KhA3C+|v1Buw4Sb#gWlaeQCwT^=!}2wW{y%qupY_&z7J{M2lR zjcFuIMN5=Av#Ir^si=eidx;_j;dgjZa>QiZ`)KPcAPV~2u{(+gJx+4hc&`xYYh_b( zy3*cD(c+H*7n3$qjIi6n)|}Jy6;j(0x!lpe>n3t)lsU2-pCrQ&T1YkSW7=GhV1*n@ zA4FxJtT(3$veXu@bp*AOf{x!60{^1UR7hWaQ<qH=h9OKkqXeV-<TlY5Rh36U<=?z7 z2KVafh?gt^<=Q{_{;R~&^)snCS0U`L{DB{T(<$9O-}dQuq_b2n5<<N<5po<Lz&aBc zBw6b{-P4zmBlKi}{q)1IAG@=v1}l2w%W}HOfPmgx3xZKf5F#8+)2~t4P9U~vSuAj& z2}2!9^2wYa*}ZWSnuq=WxlhzM%6duxo=PuhTq8<G>v|JU3t&oD#a)w$2r~LH)r%L8 z|0eo<5xaWX<ym)f69p0n=t>B%)aO#Kv8#6lm`Pl3Ti{E9a{avCRce8zPNIVS&dQSQ zcxKK<1Q+ivC{nYrzpRI|x8noTckE6^yC>!=T~k*EJCS~B@q3E&%+%dVm_qy9rR`Fn z{zrN(CV;nD+|Vh)QRQmlyyFzylzl33lxs0I6bCWunt=2t`TO%CT=I@<ks6XrV6cAH zdkgG;ncZYlK;R@fj}Tn!&8>c&O~&r}THeyI<(Z4~VbZI)ak-)QadwXqG>aRqClE|W z-SUDso8=k-3xIz*hpL@6>2FKVZASSBCl@PPM#R@42(gEBCO;lBmaKz>pyc1t*8zme zj-D1(VcmVqi>3W3Fr>;5!@Do$i+Hq#Mi!a)fIQc~S*Je{(5>0~gEtUwB_KzFS03MW zH-W;xKS+w>Ff(gD{WZgr#01cc6Cfq*Bnkx2<wE_q{oY#1^R%o(K>&k^%dC;^bCl|% zPkU28pKe%s;C-wrcpG47gelavS=4>BVyCqBv-|Hll!Vs)aBR0}lfBn^OAo#9CPLmn zZvHd>TxNvWCCeQXpeD-@<q-y?T7O)2<+jch&Hb@i&^lFpcN5K!F}H-T7}PQs(uU|i z@%jieMlGfC$Nb87g+94P*xv(5>b#$+XAmWdR-0XIw)B=KyJ?;Sl<TS7iN8h_?C!EF zyyMOsl1b_-DyJ@vFKz#`-A6RSRD=|NL&4%8Sgi@O)m_P9W^(U}$hfx=sHc(7EbtkX zukJm2S%6E!`KZu5Up)A^2S@~y7-PlQx0Fy0ov4vSjQQA<w-|iA2h`+SDJ|EzJs-vi z<qCpB@{DnVA9v$df96Vm3}|l~UT9U2GE(3pR4#q?rTx!PglP~>DzY5w!jY|uH8=CS z6{UQ%yM?^%;JWfe124&%qp-1qkar{$0{Ckr==R>ICs$AZ2&BbE=6KI&p0zFb3%Ql# z+l4D466v+(=jDj-9HSzjZ{>rqnG~$u9UmexKL_61{2%q>Sxs8sR5w$EV91?$TMBI` zEKf|j;XB(=ad5Kh6IZ)>+~6nFB4;%^4+8^Kdqt^~)UKS%7=BWzdOS<k?x@&{g)uNG zZC%d4ju9V4;Zxwfq?cqw3)lz|j#%VZ$JFL{!w8lfhY$RB&bp@s6cjCFqo?ofiF%qk zpP4GXgvLL|G07{jJ~r2TGslS4^m8%$g7CCJC3g|7gK1C^Xs&(Td)wp=KPwIVkQi`& zH}6^>juUVJpyyO$#m)mUIn{-Bf?xVH&KXaV1yEMnrImwu%T9714ACNIF5RTKlCM|# z5A){@I~3hht45bz$p;W}PZ3UOHiw+Pn9%UCevLzzjdHuL&e<P}LYGMfq9PNa&-vtP zDeeQpgRLVuE5S+uCbqW)z8nRa?EJ&)0w;izYr|j64a|5;>j!?sHZw(uDpS+SFg0<f zk)g8uaCdgKdhZ9K4F5hp4nJ%NS^DAPxn3(>m)xnQIjcfF{++;#fA<<v`gH+>>{K34 z&qeJ&cnvi<r)6t)WfZ?)Jnk}yX$$xAjmnPk`slbrGh3u(H%(~th<;hK<H+uaOJL^$ zpcLZ<=&SoHmV6>9nl1T?=D<5b{waMJvJh#@{-)eG$<Lrw9*+4FoIW(~VbPTB8Jb`c zIx=l)6Wv$61<+1&ioeExdYkgjXc0d&o~d<}Fi++8p=1C$^-(>yF5IpQ`109q?<1=; zAa%He3T6EQzwRb-X}Gb}tecaSo!`hoTv{Q4VB~b?yRqAIM>0m{iy}6%+<szq;|*vb z&Z-yc?<a<-ltwsrf+nI4wWY)ppmO`MQeLIGL5l=`p%%NcRj(aUEp>ilCVu3z;r6ZZ zv)z3r@RE8k^3Nh>1i8T#gRvs1qaqVviJVCX*1JYN+XN|YQYujcGynX$U^I!p6^EVg z>MDKP-!fI6bs8>G2eo|>_xH+3Q**D5`MN<663j{>!u{8Sv=U;v#F7FihC$M`y8ztR zpk(@lUiC(L%iL}M!EfNgwk-($C57?3jafXFf!g{p>CUw3oi`LW8HnpXG@0d#Wap+P zXj;~t68U5f@ya*<3y2FN@>Vy(D-v6Ret`O=PfqNk7X;=^Jt-z(PjZZF<a2!x*k2w` z1_1>E<*lspkqAePab%L|3Z9XKb^S2xhxVDtckIV+YXZ(lREHuHW{N6@z0~L$v14(Y zT5hM=0PEifgx7vDCPlH;xRPAcdWpK&ZcXEJB^*kZ22Tw+YSH=UZyBDg&g)iQ@!!ct z7-ms$cTXWrvIY4`P1?+xQBp%${UTZ4oP37KIz%~#W3s5JD@?64_Si6PMtkY@fkzde zJ({en&{t}DgXkapJbC4G&BI}h%=$6~ai;GnTwWbiUmghf8S;<-ntDnzG=HB70A+w# zJ@HkaCk?}^^LPd?CT`NtHp|6-5<yZqB-;d@!h60zAN}X0Pj$}hDG}8!?-Ae?*d6!0 zgJF;5C!XZv{~Ql^X8J~l&t9ow&TL#ue_W8HXm2~4_LmdJiVV8Og^h>Re^1B9QQoBw z+SpNUKf6malDayHXw=g_mk-@LT?@{q-7KJtqO1q;qG87tH$QrfzXT|MUt+|x`GmCx z(n5277qfCisg6NknvpX_8$gkM`b57U`206TRW&+>=vLWlOoaCY0g3?RuXlsYlkFj* zBe6N3f=D>OGwkI;rbU&J(>F>1xM7WWTWSCSYFbbGV|&N_aDTOaO<JW?SH3?^<3|s| zvF-^{->m=0ORd2T9(u|A5|CGetLlIkGP52O+K3?WvO7yfOipA^QIK$fA@@AnmHaCY zuTwXu*=co@?j5Ux;5l<LC<VHHSsb(7Y0Kj?`?h00Jg^;?mHv5IztR_{JftC}h7jfR zv`<F=jH&aiK_!zL@n~(0>A5}`U$#i)&T8VhvRi83{yTnM-kTLUO_<xLU{U0p5Ev8{ z#FS1!SB!lly*$NZ)ZfTZ!;Iz(O$mpMuDtq%o8P(nW2ZK4o%>@@#y;6|?`)#0dwD)p z6*t&sfLu^0c23N%(|UvTAuziX^|7nV)?ZAYgHw#4ZwR+M&ic}`x2?kY5p^b8$~v>6 z%=jxAD5J|cvTu7BEA6I|P?>sqY`OHu0IvwBQW@|IMTbK0oc&KI>osx7BH^hq3l+VS zt{I=ajT``Dr!Q+dt~&Sci{v=B52FU^U6gkvxF+AMaI8VF;ZeQrSX?n=<M-S$dYT5C zv44tlxwd-k)`CAHlpm9yYb(uZcZWkQQd!uLymcqk>E*5<3LHAuzfHY-rfO`#d+;;I z<R_4J%B>BqZQ<XVlK1i2WVi^}=E}DngJv1zg>MLI!e=ddcg7R*mi~gc)^=}zV1Y&T zH8{BfWm{~I&X4SkZ++!Ol_HmfCfO1e6>U=V)BCb8(RoTU+37Dr+Cmg_e_s2HW6XS& zEVpMUl>VHt{p(#`u>eqW=0w{phY;qRC7OaPhs#&n8|`#9unEo8D>*ZdaTSv?l(%;e z`A+?N92nF6r!&h*yMmh+8h;IoQp=2SE6{ni)(>scIc(Wyw4zGbW8;48HY^XA)eTRn zfnr2b-dksV9vUW;t#>V!%N||^CCSS=H<fExApqce-zHl^QQVBqNeLn>?M)&uRod*5 zKk4Mm*c8S84p8?dUM!Y59ed<mUpuU-mMD`lmjm&_#!vo@Y%Tu*++;j?<5Zq?G-*OD zC~dNS4N}fcSq~Ca7C<~~ol3E>otMH}iFje&y&U~CKeAl|v<VNMWe+ftJNlb6Zt!>O z5(LU!hJ&DfPhQcR?Xiv2P%qhITf%2}3*>@o+-a!lduWv-9In)2IjM|4b>ro6Y}{7Y z5=zZ!xnr4AYBw>_5<*)tTwKZQDF)!a!)`0uZ!-j8xb)lB5&4oBbZd}+L2|D;i-$OR z0rAA<xnBRC*~@9xIV@R-n~j{a=I)^CZB4!+Duczk$wxJ|c!)EJD1OI6cTIseF)Qn; zr7|Odd?+;!to!26md<<Iok^x4<Tu-opCMgaM#yb+Y?=>-#{&~y@qT%K_D0Ro*y9#l zd~ENdXgH|+?fGQyZAH|CsHAYyEohdi2`ug7^je+*e^)b5zOBgEeMUnoVE-D5T$Quk zr<aNd9vtue+w^6d@tAhHZ!1C`OX&Tr5LYa_zc3*hn;7J`$Cn6GL=+=TM9oG~%div- zp6o1br|L>oH^tSg>bb{Ho4*BebS@7S<cc`>2!!WyV}j0Kps${zBy<|LJki_{z=pXo z?%Vpjj897B_AdImd=6%cfXn2kH#UJ3-_CMI4VJ6@0l<S<d{Uku(3~tBnmCsp+`ai9 zIW7HsXUc+dun>03b#wl}7D43sjSUU;02gvdIC4l}<Hb}2*Dhti{&J62IoJnbs;+N> z_EQRpP^p2swOinxYC05TW399gqS@QX#(?i%F3g%&rWF;06dtc>&!BO)GXQ#s|L*Mw zc=a8AVG0q|f$W5N6WTS8vP7XEb@kMhhc6mkH)^^E4$1WPjn475Qi==Mc>i5$%N|e) z_QNkXLn4H?MWD5IVdh<{#&zg-P5<4@>VaXe{te*+FQQST;TwzL=js>&4A{Y=ye{xa zt1#RM_dcP#BNGMsCU+d#+_7`etFk&<=1rCGI?n&;r^P_r6PRD~x4>+N_m<u9UQb9S zj^Xa?rJBFYRM3RgYt6pUJi+z5()J#8q*@JUFX*lg%7Ic^0Z$TPRo`dHAgRDAuPyBS zV09)ZATll14m@OWMO4Z6QcgKb7aa&7KFgj=NDwa$iK9E?$9FrO&=;+KB3aiGmM#FK zXf0;@M4k4>Wba=SzL9RuS7BXY0g|-DhCkHil_Jqxf{6-ex!dlq#nvj?NtZB0%>^TF zo?bz<!wIyuXjSvr&ti-~&m`OCihaJ*BK)qhXN>-W0}wEj`f<e#oGXVtzw4~jg_Y+! zIdwiOmZ_U7Ihoj`NQxlG9K%~w63_q9Jp=VzjsH^sRtGC|mIGNocl|M-FbaeO=H**U zx~2w`CVsK^JqvVM^2IuZW6}$=;Ihrh7g&pT_C=`>u)@1P98v`zL<e*I!c5vlDP=v} zE2;n%y|M)0zCiO&(*=V?rTBG)CpbAdjGn}WDA#cz!}H5myfiWsI^I@#GFYZK(>uQJ z7qI5~xKJzsbyO_Z6o*M=+)GP?$J&*ShZ(cwdEca6_W9Zt{K8@t0iO6hn)L(*ects# z+$)D>4mQcXxXFSwo7ioZnmA53$|$%H#j{TQ>!hgQ{bL>)BKws@&<_Ofqezft$6r0& z6?{fKorUronXARV<xuKdRWX=DJBFQ{%p7?uv8^^tWp_^C-`%63miqjhK4D*WqlleZ z1~$Fma=3h+xi4ZADSFGyptPlFR?Xy&YGdc&{jv((@@i36oaiXEIP87YyyYAb+7fK+ z7o?NC?w6JD@{B40*=%KMCs(nxu)TG|;Y}x!yFR=eNXu9t4@jwLJ+(4p=aKtZr+O_# zWRsjHGCN;7@X5uRlTaAcyKR!S;iAj4yJgWvOLgA*3jMrS@M0}*TD8(c+6uhu-$=+? zt=ZHsj$19|y^|R;D8%rblzRPV)5PxPnngDBr>>F?R;B7}t&Du_rFiPSZ6yi)r6%t^ zHM-xkKPPW5a|1nsutC~`Hp^N2um{VmbX`p8m5%cc_jV+vrR}HAVvM1FtE{VPLZjkQ z%IbfX<H7H?SpTx{BU9Jn%k$jBPenE50TP_0dgZ3f@)h#T-^@@kqGHs+1t@Ctu3ZT9 zLG97bdXZLa+Tt7AAN3W1^-{7~Qc9@{J82!WBKdk?=wZdLLzP<j)|@IbkBZrMInv*~ zm+U%Jc@J2C7d{kY49igVai5n7Tr5J?PiTkvefd_UTJhV%8|1+8)pfmpS-1jl^-8+( zmg=#F_68nM6npo8e10&KL0{e@O#&OcSJ?5w(`rjb+iXQm(K2Ii!a7E=(hm)vNU|_e zyNoYz7Q}Gh@KfqjpEkdF-}txDsG!$Z-os28x=!2AQZ1GqqB(Z<x<Jp)+=H&;v~V+j z3;9*|K>E<xvLAU=U>?je43cDT;|l&{55bW`ui2NoVZzk>zHFZpF6)^!f5s0=W<gi4 z?E2R*OiE=NS%k=GtYh9&jp0@Y{j}J#zt!6-^$|*7GrckB|Cxy!FjolRtufj7V!|$m zG%~fXQD=YU-X8<LEIi$%GGjN+bo63Oit`NZYrLjC`e3S{)B|rhHi#OT6Hks_C`#c# z?%sb(3^;Osg{tcXbA}528*X7YF64RjqT7Ajhd9=%-U|Y<Ec2h9C+`)q6f0)ZA8o$H z|J;Fg({y<$fzQ&bHddwT;*Eu)R=<?ba%6fNmVBusdYao780@D3EI2<_Oi;7>#Ax+F zhGpBTrJl>4lh<h!Kp^sKWo{)KB{4=rsbQ%tG)=Ry>U^fjxn1<P0fMBp?=y8hvCep+ zGL{G(zId|AY+sn5UE5(49ls(!YFWtRX^mYo^q%(jT0Sbc)a1Wlv2r8lO6A-x7ij`B zycW%N#IueGn%$rmV4{oEIG`-o*h(nNzx2vrH!R{ttWrDoGq_WD0$s(d!VBJeDoHqg zcWJWhV<Cydd=N7Rl;r+p+NQW*Fg$$P`#foi>(CyXRU`YR|7a}{XC!e}xV}w2S|9jm zFHoT6Ti+$-?(Q1T>`@78epz4`Hqx%3IE)<nft|W@YfoaH&nxIdB3#7O)&x4r`iEgB zX9S&Z^Yo)VA;2Y=^^U^?^pdCqC(d5|rqMCxW|`w~vAe#%HDQKI@xPaWdM3|fm-{bu z_$-4GfdMY86FWwI7AydU?jZ`u-ZV?W2m|kH5G26griaJ8?AP_?QSh#Ze=7Ni$otn( z)kf<bGzp;>hEPzAcC4#IN<mZ&%ps%&$~xyMz%2^Uk%oWQB)&*$a%SE>tzO!tT?ybz zOJdH43m6Zxj99Q9rpY2GT)k4+DX<m>%9a*qtn{Dls%fDP1%P)6FP>XHaHY%ZsT9{5 zLHub7IXJdtKMeN{m)6z3$M#p~OU7i_&a@B2=8RFv|LOdGcH<{^!MfLCwm07$JjWih zSaiNYt0X8Iac_DpY#JEb0<OAP)bPXUmb4D8NF6n8zHRNo`0J=<tK?AlXvg-3I66Gx z!_s4%+!;!(>yUa}R#;7$Tg9U&t2aArj!bZ~jLt|<@LU9iX9Bel9zgTjIXto9!%9^z z>99c%>$j-a?Wa@9CD=xBq`(tCA2ru&9xOlsoJT;rGKHFA=*4IsMwonIz%ff3Q;pG< z121tOq};Iud%+`8y2^dRv*xYuH7w`Mf*42g5YKT)H)}-_^Jn{msGId%KKRY>1kGM; zCcJLd-0qjh%XJlCD7Vt0GbxRh2`KdH7ImR0PFP_K5%_TOW^Mg}0PQ#)cKWBoEI8@# zG4%28D^E^oNfpI)$_m#O8fFdi_Ko~2?|Qtkn=7p9`G?43hPrzcnBP6vuNxB5r8yUk zSjlh{FsygG6~t^+qL}ia&^&AFW)UPR(R(oYD9;m5uEHADOU19<pV^|JBwR?&#iCH4 zLBv3-p9$oLT3HVrx?G8UI8uBT0HoS=!1Iyuw9lXkTJT~5WvzILZid$zU2CJO4NIjW zI?*r!Cw1a@3d%lv6Yi$@%)L8ksAE&3)l~}|8Bv`O32V`{!(yY4?t($`pG_GSGNhY8 z^5tH@8G#}cvAV91AxpnXn2GXI2aF<YXq~7M1|tjDe5;EZjC+WV#Csn|BMhmUo)Jj6 z4-&-d5WDge?RQ6nsVB*itAb$}G8KOs6@;R}+oM@ob-Z^6b3(KuZ1J$D-P#-+yvVzQ z3fn1LC6b^EAYZr0aa=r{C|N|vGFujbB@xvcX$kS(Vh#?37Vsx3KL9ON>hF=1T|$&> z-lWk?`gTsyxtz?T4b#mCDl1dKwNz$&`YaJnug!~z-ZDqOdW=Tyf@hYC*&dgkq_1^K zctpsMuxk_<!~D8~O>(1s%uJ6i^a`8QK<wC!ghj^@k%m8M?5U~%2rN*hN>pe?h7N<_ z!hm$;BkAN1qEKTFfs)f)cwKHI6n-bmDP;=f7Lu>b^5*I|26*H0pyui4zv{uou^)%{ z?ght3(a!6ZWh;y{7s1a19H)^6(LTY6Vd(6@cf0fL3*%|5ge3uFYV2*_Bsa{7u3roT zDHLl0)T(t^H&#I|iZ@Y+?YI0nbqqOJ575+$g{NC^{kh&rv{Mny0n+n*;fIU_k<?@g zX)gMV2;_ue$a-<2+FXAOpa*^r?gDKG2(VBT1taC5nUhu(V&qPrC%I@tKtn_dNq;$; zpphf5!(4Hr``?(S>tEg5xZas60mV0^PZ!-HSvcA<RslBV6h77-8`3<&6lCmfxJYI; zw*f~F=A%uE`nQ1=70w<Wrp88ZBmrUq#*Whky$_37HArc2XM6iNAU<9iA}KY;i~41a zPDrxN?Fsd!oK1Y)NYs!tPzLeOS}FCnhH`)fPAF&Qi@RBqi+2J@Bz?O3uo>J=O#lmf z27R7D(FnE^B%%32)2K@0e0K3wS3gmVpa#-=D3DH=*l#~BP*^M%JdKOH1l_Eizc`Qp z<pbB*YJ{pi4vdS*np2iJn+&m;-6mBB{gX3T{vQ+G-a_b$M_$a7MW8CsH8-RXA(u|S z_H5a5k(y}Z%INJdHqc$;^y^*iHZ0DlkLt=nZtnR3vNK%3SvVgTba0JBHw83V)ypYl z()SYx#?dV&m$;o<jSag+ab+4h>dRMXIB$XliaC(Go^Z3dFcUZDKmO6?Ao#O<YwNf1 zS9>DpxfT4TvgEaDE}uX;DdoFLs{Hfxq8*s&@Kpq65w4hmRTI=J;>8Rg5qN5wug)j} zFffYu#_*XnuD}Iw2Zf<Oz!O*sR4pHIY_|Now}}Z*ph)--`cURX061u&_(FhV^S5pn zk>N;^TH^^#z)RiAi(3YUeex`)HFM0!>o%jcKI9mrH(&w*gycA+N0+}>3+~?9`2%Mh zq#gza!quw?l<x_y@Ttv#+J=j*Q1-NG1ytjFCX5#qYr{Xf|8U>}`-GuxN9y`A#P=GH z*<qphEvos#4mqdfG35opsGS}e=R^t}j`^TRg5E@Wl<;q`^z62|+LI*&wuMgnzLr7L z9x&F5GWKM&pI|g2ed;hf2jv?iR%BY6XE4%za7t*IT{!Tit;IHdC|nRF<bX{)U0M6W zDRkR#>sTklazO^<ksX`DFM1eeu|<2tg}-rC;H|YGbkGS-T=D=xcDH<+1ac2oKI(0J z2qR2sPo0%TDU%i<VVzFRR|tL%#49#phgTF1RP0Pg-ONA5Pk^(s=$?$P8JHmK7--EA zajX>x>L?tCUCp5xuoKsY!h15ey#3meZW29WN=h}M_+eT-7peWr1gWutAXVLSuwE5@ z;qlKCuUZ7A2Il~taayX>Ls_cY_#yXRp0?b3XS5!dB-Rag5Oh~8H-FfCZ|VbZm;7#V z<;3UVq^bw*vp6sZX%AqH(=$%TdxADzP@>r+WpDf8{8PdpZRIFz0>l^Ma-a|wPQCk5 z9xWVDdyiwe4Dr>O4uha!^Go3oWgqLz&Zf-^PzBjZ(5ap<;0Bl_$Q`U%SpN&k<yqzK zCYa<6z95zmD;eNg1lh8?k_GxUv$8nyoW<xz^#p<tM8nVFyv@QnSZJ2BG+v`U2w@6g zY*jt^{Ej5b#Vw)lwoD&N?-28H$~ACTpyuewJNn}ysVtvO&?aap!QtpoChAhK7!xrn zr|$lc=p!eJ#pH{+guNuVStApTa~Mjt7LI&Kv+|fiH1s!#gdKO%)BKPU1o`3er)B@F zfmQGB5F(%6*hG&eJkaUQe$_`OPww5!x7T$rMwt+1(qav2g)BLXV837pP4p4YauOu2 z_WW)zFnVC!2%XbhFB$E&$PG7-t`yB1B17Nb@fTG}vb};iezemt$uV)%e=uP8X_JD# z&uC#ERZHA_!RMUoDBb1>JDp)XhpjH>!Y)g$&)50!Hee#I)(b0-UR<V4#XgtH2593O zqD)O}bUfxg6QSmplj%R9lP&pLYG8)?<#{0zv!ftm3WG6V-SQrv>CpX2+eHEBqrHB` zhuC$QC=fIkELXj>-Oc-G;Zkw?e@s^N=l}|)2;sfvH>dYbc5XdQxsYI7S-()a@#7S{ z_Yt>epY3X1m_bhRt>{q2hZA_@8SE8^G?oF%6ZMu)cr50vSD%~n54rULJHC~2PoLw0 zbmKokmt2wAS<ZdFeeSwFW`0V?Ro?<T@Du-sSusyvn=<?vOM1Q1pVl>QW<CK5Q)Lgo z%fV?<0m-{f*0YO(>+qA6kVUXddt7y75+z(tx;-Y8q@OFh{vXcC))Aa+XI*&4Q?Cq< zP-L7ze~vPHJa2UO!rrk3Btfxm0Wzk7#kywgX*wl@e?$yV9d_r$X#Mb^lGgjLZl8N} zg1YD<Q3#L-Lk#iPmZj9sg0~te0ET&v(%7DZn_c{;aL*hMakeJC@NRK|&;HM;tcht% zVbc4|07B%yTn@9Jn+%KkaB!XINTtAqp&An~yhF4((V6uqd*eHmx_L)9zvrn~N+M<t z@hd)pJ@Cm#I{IL*R2~r!t=(R~rV)eZDkbCEoh;9(pG9~q#8E^5TX}HH>dBgzIQw~* zAQ%W+(p5D&z3L*JbVIolHw{tqkDh|HdJ?aUaitoj9$UcKXRg>2zqU^N2w{!cL1up_ zTe6&%F%wt+=%rEQdc>cE-YYI5tv(UDy)2G`w}A=c(`ytah~gLXI`*rUB8YVVW97A( zFsU35bs`lCYEw`AXtdEeD}jaQmxLZrTHA)6gMvIGsx1>6^*g&8(>0GIcW(+-dg9%` zf4%b1bvhTCz#l~8!^Yc3GOkfcnJTuSW@vj^4Q%A!W-|_#!ZP{<)39r4x_^B=ep1qP zoY)T;L&cIFZ`?Ke0iJua!o=<uasF$reYEWu+(QVHwpd2tepp=Yk!Wg$XGI_+w`Xtt z!n!SbIW^-y2Fywa6qZBF7)cvp(_;E2nzV-Kju*zZ+3CX)WopqmWZOPoI)YFNtR#wA z_J<Ge`!5KYEr`~)!OnX#O+naMBTfELr7#GBW|1)cJ4-o8DLFidDnR?5;F`y3nVCyf z>ro;%e4g^!qJ$0OkIHVyby6lVjNk~feL%RB)#=Wr@2e{0yPkubkb~^-eAPN{HsmJX zCtCd;=|T(Nvu?d@^-Hg+fJux?6ne?Oi6{>O1<VK0LS?-d@JTDj3@buXbly?s*u=u4 zN!`s-MnkOF|N54n<eQ;7(M8P02Q}`J{G73wK%HF4F`?=GN<a!Mj+xNF+$|S8kZq)F zhsOPsEcfD7xy0WJ4xa{95&omB`P#B9RZ!Pyk4{w(OspoCr#*JAzCVzS!kN+%CtT%Y zt+W#<wSK}Mq;=ixZY<Tci%ENjVoq6`PT;^wf{98Fx=MuKR~WH@b+)9$fgfvcTZ8)O z6{m$D(s*JIv2uXgFJmZoG7jR-p3$f=W7EWb8Da?GZq#UkIe957l^oL}B1D+~_>pdR zS{g127)+>JsMiM9paRUlLWn|gBz&*ltLiy;Nb8EU%ZVV|Id!cPUT^t2mPyW7b`%V# ziw;;~4|hDgL1mzFC+#fIZF$zf318`9BraP?jKkP$&w3GoQX#;YCJijG&?5z(Q-su8 zji(nioiYR>Ny(z)4J`$s8EYUzi3Otk%)xu3Msrjpa7>(;OCsa+`Fipc+^67OQprrg zH}FA%6SFUaan5-ZfT@ePtZYJxte42g_2u_gLB7?~&EOH;z}aEv9VT3{YySjguo@*3 z5i3Dz%v~g>ftvjm6ymw9dJW}=X^pnKK3~Sy(F6>FLh-9nKb`e1!+w^NHt{Q&%%ZS1 zNko3sx0b7VbZ$1$VW^9*MIH-s0ibE&cjqWfZc6V1$YS1*>{kk4Oyfw~2~&oa#eOq| z$`9Se9kbGr@Y&OXT*4#Daxt><J$^<s1A~sUK7~2G6Y_Jyz%@<^?paHycO@?;nj2<} zoA{G_6AnUBQY;P75WitJMSPSE^5e8{mPN5sble(`i^>!)Jx^IO^Od3PC&kc6iGuSM z^;E|ZP!PqfJ&l>Tkraw70<zW4=VssqFAH%W>7K7}kVQKuYDA>OT1AahgB?Ki5ou}r zPWVE?nvkin3D?GqAb7tl;7{aN_qF(J@?9zFAWGC9e32Y8$@Q4I1KA#wyBImGtl=qn z(X!-0#R{W*6(pc|Km=IpB+X3{M;<-~(>8B;5z4wHV=|`8(}lXAlK*|?iIyk(%MMW= zy&6n`8*ptK@Ss1^39N{lKb7naFnC0i%38lAM*Hk~mYLQXL<=oWI|DOCN_>xFP~J9e zVk~-x7*eak>G<xpNLQ#^D+4|)rh{`NBm`Vi!a|-6t0FqnEIZUe7z5NcMGuz8X6AN* zhzV@pu;sB0CaPfEfd|+LxKRN!$eH*H0bcmO`i|`48tOw-etVk=ZS;Q<U}AnLseR^= zDCk}!^CBREyvyh>B1cWeIS?*!P&3CHX0bJu$~w_ekbCO0TXLg7w~7eDZpGh6kPN~; z_6{}7;|$0ae0Sd5QV={FK5dD^++mveFRBr4pr6sn8&m|nqP1JL95Kg+a&M5G=~Pd7 zR|N6)>6N#4Zub=U2KkmSWCSF$WZY~cCv_fj)ep^nyf3Ynq4&AG`l(KCiS7NaE1>}6 z^Z^NSllyW3&XQn?K(^y5Z_BDZBL3g_AQg=<ahM0K5drfn1geO1Qpp=(I*hOi2P0|S zh6)xu+k4eIgC~1F&5cSRDTx*kMLR;uND(-G)CMF^P5u!}Q5CXmYw)ZF(c*P;fvW=Q ze~yP<xb$mC!VjQnIm;RCOhiK1eJLi2{D_J+smNA6u19$|R)l46hUe;kt*UU|+Qggs z?Ho)VCbss+_-YjCSssJ2yK=hW)#o-gK{rrc|JYGh4;l}F|8~JD5Q`Mr<giI_(EgMc zajP7`mYwq~FapK}xe~v=G?#`<5s0LD$BTaHYD=kJeH+=ytYxyYKVzgKU>KC5#UWtG zprX^!eUnyw`l7ruPp+bt(Cx+(k14-c`G8RX{<DQ2pu&;;^Io6o1PyMv)s>p4YEe3q z@Q?depYkr_+@|2n=|tF&^4M3z1@Yyhm_>T%%g>^nfUvwe*DPe2Ta2^o!cR01G~XI& z5<;-V6dbd)ew~+Y5v6jR1f2iV!^kHB=tF>L6o3&3wUKp;t9Feelo3J|YAD}<%@)@s zKWXM2&Vx5Ste87Wp(S&lq<!lq0Wv*-L?z*3lbZ9`&WZOR{zvfMuxMV&Fe?6wz^ADR zv^6ajBVX{^vjLIZ^tB7U)ObMPC-yEamhV20jdtFdDV+L4YUKlCd)w!R5d;a6Sg8n; z&!V&MGXfxIR-!=1`5mq|g%kV1C;ndmMKcT|F8sfj-n%)^wMpDc5*C8jq{t`qQ7Ynb z^AyqRb|JWiknoV3cb!>vr?SXD-!K%j^t>{dalT3{b?X}kvg6R8BZ?B58Z<eWWgQ|u zqH#EG?(*3%7&&}05oQ)l0phrueR#zk-nZ##%I=0pTx~5Y>Yp!YcP{NK())F0WiGYq z)%sM@Y*1T6(!dIHGLej+C`X7D6NS%UHMIiTMqMSfU{p^uEJ+WP8-KaEh2rdaJB6dW zWzJ`)?~NbbH|O{0$rV|@to_Aw*tu-mM{ssl3h~O<;$0GoEA$dD7Z|*f2dN0TC*29{ z+eOW3{DY-v8pO;{ujq_9HxkNXXGU8n|6;bIkBFfr?$%#M&ABVQmg5L}@mt=5t322Y zL7Z8#LGg3+)2>FBymm>X9;1rBJ-OGHsU-^Cn*wUz8gJX2Dtf07Oz4jAKk3%I`7wLQ z%{)l#KfO|ZTe<1uq8P&*%^}DYc9Rei6xs&e`VhVH)9KaSrXj`{0*GE}l<B&E+LIUR zfmemrfi1i3s^ggefexK{{X2S{==1LnRGRxsCgjV8O^OwF`t!Wk3<Oup4-^P$cj@3u z4ifbVfs^wE8ZFqwyW=|!zLj<7sm~Ln^A!aGTN5G+Jv(M9eu;Y8bBeiZ(pT{WSo&#} zEK%+19%u=cI?4$BR5Un=!<oFmEUMNtJ31a7TvXaQ<cr2rT!~}v@`N|Jr{|z2{mU^~ z%*zTRe4pIAS}&j}!<NJ+%5z8+dWE-o39(yH&a~+EdsVTW2iIeae_y`NJ*(WWmpC$4 zxgqFfZ!Vy|jZ+40T>6<|1-zZK_MG1Be+*cE@!(9I>dMK!CjG0e;P#eg$3s=Ynzf#{ zR31o{n1S=0d&4ij;F}EKc_PaxTAPDRY;0}5DdsySl&*ee0lO+q<`t`bm%!*xhzm{y zCNy_XczjjbETN7F69`Jry{ecjHGskFJnppJOw;PsF^}@$$n{Jrg3&92Qp3@~mrmvq zy=Qx`o<giNQBKt>yimP&u}aqdFls8o#AWph<J;cetdS!MQW``^SmIZ#y9oQ^g5lku zd-hi(dOP_|x`ocI!QfyIO2eruol!L{HhGNtST_i_c5b`OG$y$A-1MUq?c;CWBn|Gk z{{!fc7{9k?a7ANfzVI?zg@VVvRcq4PXJz$zrM3SQ?CHG%ve&w@iW@RIui{{uu^Y(> zhob)fN}WyHws1f$`60WYd8xRwrmnaD%M|0q^*C$lrv)n(J6^qp3Z~0+f);US<Ysl0 z<WP*dch0b6zmlRw5OE6fO_F0GrNPB3!lQdGYbP8q1<nrky%(mDOV<}SC8!uvm<#8z zZpAx}NnKA>KjWpk^B{zb#PTf-$O>20{-KWOB3Jjtnxm6#mKJpiWsR^+LF&DlA(>+f zljXQU1fxVVtOW^|l`s0pP8**_u%P^o*!%uCk52@gvZT20nZ{ujXUi8&kfws{Cp662 zw!IVf;jx4?tJ)$!eS;PBSp*993k=LHyQboR35GDrN<`bvr2HXs6hHs;;hcyd`<!>c zz89-gh7j}az1^pf?8hx-R~{(uwe>3>WmgaoElVu#7CnO++Xq+{LMzmR+`w&-_(j*D zPhXYwEjpxHA=j_jaHiPoIvCrN(_ZB&6}bVTjr+PB0mU248It#!_dWeda)W5A<gVT= zy%PfmNXQ!yPFe~(rQbrb9)ziy?-S+A+7Y-*4!&3S%)!Ls^{3ND8D>~h|0Sl|5^%gU zzKN#NMBFv`NLz#B|LQ$6%6pAoCn>Wsrn`_y#Xx#0dA138E$$#TI5sELxsTgSp@vvV zY5U+Ivbo?GpQ}!f00$lQ;UOZ@iH+;k=w2uv6gm%cya1DaI62dIyGQ5DU2Wluk5M+N zGp!qv!{}jA7e0@%f@J7CY;9YE!UzlOc9-#2S2a(>f^uH0W8P1FlhZs%<o0m_7P8}8 zwc)qLYeU$i>|JN-Z7VxFxvq6SXa!Qru5L&9;x{ADtq#hA{Ex})kByRkIq#_0S0*52 z%wCLhdBO-}P!t_Ow9<e{@%P_AGUmfKz%!Q0RpWFCy0gBK@h4Y{i5nT39piM1#BADh z=Hg=6<$5JG$U~=&X7&8LbE?3dzQ_UoPqmNWkBtx6i{;Xwa+z|(5ncb?J4)LG<Kdhb z-EXg#wWMY_i+S~me7yi6f-W2zTTHlq#Ku--Khih?8h#OjBlx_p3!pPp&J)TeHs4I; za@`=+p=mC8>v&FtbD=L)tA^G;2Be1Gw_GnPTHwkGUg)|mSbL#-F5XqEq(}4jVa%fe zrec5z-Z9ANJaDR*nS+s?bGF!3XLmfW(%l&O$AFLbhWA8tjyX93E}B<T-t#MO_!UWx zG+k`)Iq99khR)!5t{dHaVvjm#qkyw>RXrBIq45{AgAeON`cG+Yg#Y~1^Rd7Cek~w{ ziH+lo_T<-H7fuc79$wxxHAH9M{<LS-K_}_YtK)hS?}uM|&lzd^*Nm8p2G572rNFIJ zE!5weVBjC22S?;#;6C@-__pP;4PAGXcb3O#oR?aZE~REePiUw2DwA&0;<tJ^UmJf& zHQIa`jCcCcwpf#X1#t8E`=sAQ$IAoe#oRw^BAbFye~Vj3^64y$4p-YJta*A>jPCc< zdVSB0CuIuzCQHr1zU9nJv>BGBhE#GRP8uEAs>8;2`!7vtYIV#MujT8-epFeUH$xvU zwg8O95lb4>*l|Ls>HP;?&&K}Tsq&J}T&Zlz^t1L}E;eya{jNwHgv%YH`?B(-p9e|S zMZTBUF;+9`j{%RT?&Ty<lwF2QBCr63uakQeT|;PkpBPkz)=h3obBEyJJ}Tr?e0s91 zK6TF3COq<Qqs0+x=;MR&#tV`z8527ce+(ESP6GSo9Gkj*>^=%%>$2Q>o?G<`nrefu zD%u%R=DHbP)7TT<spw1%xvI*&yZ4U)riF*nF1Q9~DF5m5yL;ZqzV?b|Tz~Ixe+<Ys zXN|5UybXkW??*nMS9iNQTuwKDStIW*Ypil-Du(PwTa1T?{BrtlaeoXL?xzZlHg!*w z?DB_aom(9PpVj#N{&DtTl9OpM;=w-&?D6EhW?Ex=&RV5?*pDAG&0|KiMc*5F9%hS} z8K8}hm}CE^V}?t)X}Z@OzV8JKbJD;6Px<}dI-5ze&elCUGPd(|8CzOl3O@ble^QM( zixL6l^?9!ZDlJA*XoM^lcHJYx?P`4v_6!(AU2V-J`^%2N&8EP<+=Am-Wm}Ye&Q}_H z68qxT4f!T`Oq|-`yKEKitv}8E{^qR4TIJQItn;u`cq*<|*%rk{MKL88(R)Sb?1ldC zl{d=nR7jWJI_w+WV1EPswHr;lFWFylOgpX{-!(-O-BWo3U*?<~`~Mzui}EP#Gje?; zw#%_8$kep!skdFT8>K^9qY$iqlzi}hYv-xi<vCqmXZ~d@@0r>_6Fy<U_tw<meUXQ! z%QmjAQ1qW1o5N-Dwm)=!YaeoL{2v3<#&M^LQ^;p`Q8|2Q7T{FFg<?z#E8$1H4P$WK zg?@wPv$Em4H)EZ={_j<Eah?$$vNQFmzJ-T~Xp1Lp=(5EX;yBC4C(QX_-BRO2-4;cy zBK_R&(jic;NPSx4MSVz2LzK<1q=G&Ig+0Eu=1}UheX5>mm70wYw%D_z<(FJ9nOwsi z@-H@F!@l&5aW)oLDkP_2-;HAX+I8aC7yA|m3Dw*j0JyZ}Q|xck3&Q|hvGelo7us&P zo=koIW=DM2UuL7NO^C87sI|<pTb3>jX-ul?@?DnI(UGMR#bqOF^I5e$uxIkkS+=)d zy;q`eYYu1;7O`cAY1`ZLGBnTEqVAQTk-4g}TuxW}sULZ&h|Uk|SkwRYuM?)G=_w`7 zeqvjM>p92MhM|7C@{um4WWJZrPa|8;ecPZpKO<k0*;HMKLfZLsFb|(84{C9Sf&j4( zX|1Sr{~_Zr-~LwgH~szGKGAF)^iu9fn1gZl(mf4-NgL*{2fcTIWVGvUgYy7(_1DC+ zwgnf7kr4h7aDDg~FN6nNR?p`J;IvQ3od{bcvZUsMb(Hdhht$0;yBV~AdEyj2O?m6g zJ@9U4D$`v<sD?X#`aRB9+5dStV{NC;;79~%wjSs>fJ(hkd6iSQ>-V3oS5LN3m0?!k zV$kIJaME>_Z}p2B@3qEF$G9T$t=lHXV{vv<sn$M}rH7K{+)VS|!ND&auE`RU*zQ|? zv&xQavYt$A5IVK6Z-gsTmLcI(AZtxi<;rm3;n88zGRM=9%If+m(b4J|u5nFW`0kH= zK0u4cQ6!dxcfRhnl3jOu5+B%x9EsB9O0@4WMP@QxtdtnA?AhM>D3b^Mh_ul?(uY^k z#jih_F}o>vnrOnz@hK?eW6~U@8B$+Zne|dooTwqDwbxf+E6yi5zde!mubwZ9yXQ(P z^iR1W<4ts=oBZrsFt}oL{E-*#R&?|&h(6J<yALXOu4~tsd4dG9$I<cmDN#gSzUJKQ zMuI@&yLmS%jx_}@zizucP0>wD`bf@XxY!!l2*N&lZ`L$-z&wFdwQl_5#hq&jA6+Bp z-ooGbtJaG?xhj&!(9;JU6X|d@KfWfNk$im}JFRTMO(T30?HHC-nb|$7%RCBr5(Xya z5#DanIGs6N88FP9K2PsoqWnkdEB47bvd>;-NR{i*x)8o!l!xVA&-^l8p)+@mEePrY z^Xb|D?~6C6x^PrPz3)+W(4oIK#8|YWPtc#+WQY~BF{q$()CgrCE?4*b8{U+g58qd} zZupR|9D_Z)w9-?t>7--vrURz2gdnVHWLueItkE;Cn|Hsn$YeosU6EO2CKM6a6FNU` z0ormPsfKYjW6aNaM^9KOL6}H`<LETm!?aGND09@o(sNhV{7-$gzP$cPbz_F-f5U(R z?Int?C#?e7S@f)9-5t7m9R5hA@MsQs4%7S!=eMlW4a^`+K^w8jt?|PEDWJ+KB_YFH z`;&GD(d!gp{i>$-4|Y90^}jneuv=dw!XCpa^rbV?aF)^Q$T<Ghouj&bAUxgMm}3zM z3oBWg))61o6ZC@Jw|xz5BbbaD^}~IAOnWI25^f5p=`5Xjdhc%sH;sBJ3!HptG3UIT z!Z4osX7&)r#CfBpabf;9<QIYnVbc7*#{M^Lv89$@wEK=6t4nbmWa1Ye9l`if+QWRe zrv$Ac&lPM1o_msC#!ojjo3_z%$56GM8V}>WNwMi_4E1lyZr7nK*V8}kD3VTeD*qcJ zx_u%<W1fyj3Q5(KI;8V~#+YC7u5=Jgjzpl{+GxF-^~<&+^ysz?Q<lh+@84W`_Ou7O zC!YrSc)+5tPE2!-aHx-=+O0cX|93_-IwRMvWP3ZnQVwJ+a#VD|BL3L!8>ski@_1x# zM&?s-P|J6tsIeD}DAO$N0TZvjI{3cv_cx3p5dQqt(^mk*8(kNuopX<=&BXSXD*BG@ zG0V2Pd^#;|qSuY+6U0sh^K!Z;mpjrsihnQelfsaBcwQs2jxoH|&`VU<kdT)rVgN+p zlGtBp|Mq;~nzG^$W0H2?jXzEGbTwoMWDd7+2xwE9*|q&_0364$8{}T9mbBl?{|r|S zEV|{-TPQblki2ZwF`XB)q6{cf-Ki+?FLa*G!gPpA%6d}q?@e8w{93;(LA&)uq55*a z^usiFbCKi7F3&H0{f{2gPkZ?T0M~%oO{K+1Wr(fu&(2BM?{_}G^HRf2a0Bi@lwxmV z=YE3sHb0D(v*8>4N;j!2xvkg{)m50;Y%a37c{&ke@;Tby{4wC^lkd@CwXMVX656_8 znfBf{a#r=8@Qq<D=%gs}ni=N@i-?1^btRX3m*<Ak>MN=gpZsnyLDRDlTVN0S$yf7b zy}!r<HdTwJo{o!OD|^0;uO8_L=}G}+_iDqevtH-%os;0*Cq<+TpWT?(7k$7Klxf;+ zZqX*GI?K+&(qW={gVsu(cZl+z(jFVNOd658fO@w>KE;eCSGS+BH~X>LuN-q$$X7{c zUjJVFN>R5z)s*G}-wvMK`=o4m&>OH4x4l*1LEWqp<h!?h|IE$}XAcAM=LrRawKL_P zAa&xU^TGouHYG<-?rZEO#G}iu>DtlOru7$VkB$=<NBfKrjp0jG+3gu2FQ)o-Jp-$L zETog;(7zf=*BwNl)XS{Q8Jk6J2?FZptc%e6HQHG^)wrl8l`<%O&3rpr?#;5BH@`*3 zf7||tnWsU-UM&e$Gr!a|xc0a{^>1Bsg%kI>K>~{mveZANH#^8UD0PlJZP}=gHjAV; zwq=p$k;tI<@-fa{&VF-#V)f={0p!=GQUW~h*s!<v^(D<GqCc%4W9?DzCbgX^=x%+@ znjt^0^aB2M>+cvoVYeEyzxLCNsn)+KDwH~bu3`des*N%FHpvzzr(vAbe|xL_r(c$| zTr>_!-a}$8=CbdW=tgi&4byZ^MN>>?u1Y1KyQc2px8uho9`3L*;ijFnj;H_h!4Ayo zm};cpNt_iO!O|lxqq)Cz_RH-_KcqfWma)dq&_Tp!FrNHVqeSYdEIigX8Pb#Ywre{2 z7|Z%x8N#|orfz1YADb!W@Xb)B>u762&k;yA3q;8rvet8n<vrP%^Y52B%QvM?LAwE@ z|HER3vB!)RP@dQ~(lNdm6bl1!_?H*y5~*J|r=mgOwDaX@QSs0(meHb6nlTi15Op;} z$lL#_EooTnn0$o+y{?f;Pn*nowULks>`TO54IN;{$xAi=T{7yJAY*^tfKM^#RYP*c z<F)Qs<%?=53eD7FXg0_}POyY>j5wS-My>YAsFw!xy&9sQGpEdFF`6HlrpLY_c%pSV zzE62NTxtt`{<OyknxkA7$nhQ&#3LoJhHnv-A$({<&H|1rDwl5dhxSm&#Pv%o@ro}T zgI6RINgI)l*Xq?{zgCJ+ki`ov-|3j1;Ta(PBU&Q}XKP!hu!@mQ2fVI%HjqmS+E58= zD%e@jW-0>xcD}vN{JOsO&Pn>p*KCN?4<#iWHJ8?XMElgqD>`@4$ZDTcPWEorJb$io z21EdknK^e!ysHfA4ivZkzVWWu93^}z07hiA7q(ts+dIQceacHCkGGVQ&=;WvYG<T$ zm2k?Bvd0|A>og4C(`cwYXGoP!IPI-RTdWMDqs(lG?l&RVKrgOn+bipCu4#3?G9>TA z#l2@r1U>xDsIIRz6WDdUJkC!9ih`3PuW>yKF?myeIU*a~<h8WDC{vbv0zFAo*{`|| z&C(C0xIusbykxVD|3EWg#&pf7)G1b%N%qU6kTsn3h%vPr<r%C`8L|LiTYF_+rTN@6 z%N+k+>0eKsprP*o{pM0F{L+Kd^nnU0L2B4=Fd^s$wK<z*0CvnM0p49uxb$fITAx~7 z&`1>Rj877Mfzy7KLkZGNHeA&A#hqb*-hG<ysDvQ1cgjeuEXi4?y~td2O%v9e%SJ{W zk_v-bkZ1Sgz4c3N$=%-Qktbh%X_ZzQ?(h@Q@EXezw>qSSlB*do*X-EfI*_OP{njdA zgig!Pt7gLOG{5Nv-sW;P?365*tdKFrRjNmJ>^!u#B((>rQL5XXDz!e(SpBknzgC`m zZ%B^s_S@zmi{B!)fJr!4>Zcn9B??8Kv#4Cr{!+t}*CCZ0A6*%9FhCRtq3~*xG3$be z;NIfs|Fh;@X>#riijaG0pLzP9B6zR6Inydtad=V~;@;i$#8CcpP$jdEX#IiynA@Tl zUjx6m!?|27_l1TFtS;UC+o?C=u0Lq%>uyBC>0;MYwU|OJm`I$=>40RRYs|@T&lCOp zzk;CQY9H!_Uw5+5aAt)ip$|XL%AjQ0<Zo2@ZB@K3`_=Ow+5i<EV6wk^aHoQMEKT^L zHX|r>ui9ez-DjyF18t3GOw&7+DsNx-$q8a&f!Q9XqP}`1;uzu!9h*2MQzA}@v~f4! zLXj!xjlJB`<v<rys=1Q=2kj=Dqo7g1G!ccXDHb^V;s&BlZJaW2*-7n#7@Y)xq+7oy zYJxTqxd98cdyRLzv;U~KWW79%f}q8lu%9L`%s6d@Lfc&^!#yVqUB2VUKv*M!UlBp+ zST7x;kcT3Up`L@fkADxP<D)|JlcG3C7)UY}l0KV~IQ=x-q#F9zWgm7ErDW1LP*%q< zKl`R&hu{;T4Hd>10ZohO$(ie50E(c&y5;a9u6Xc52Sv@{IFA(Gvd~kOqZC8$)=>0? zt_-to6nuK(5DKtFj8_K3QKd$|2FAh$#tcwijFkGEp3pC$3{u96b@uZD;Q*xYTlq(y z`WZZ@K(M{03I%kk7fQaJuqcaZ%QK$bMeVOvB$jT84?vI<mt@(&7%gHwkx%yi8Zb>x zk$rL>*bIROams$&gNPkPVQ{*x!ulY!L=L^g<s6{$_LPej=9>%P<A~(=W|C;%4>F!0 z*@D&vy&)Ij*4O?@djTV|fNa651xK$Pc;8*AtqLiQ7p;q|H6PSV8@7m61eHEvzK3t5 z^Z~&)V4Jnog>oS8M$yuF!Oy^iY#a-Fa1EmUJ@GWe{1$@r9Rs|`9_m#sh?l>*=eE17 z1vIOiyj;2L>0+`V0uDKxuVu7K=JRX4u5Lu&2dQ1Bs8DLf3kvnnI)YVpySp9nGN^}o zQAS8n<c86&eTi_x>N9iCA<<a5fW!us!-aq4A3$_!4I>uDhagn~uNpDv^GV>lq9!ep zZb)Qq-B4&Adtx$_LKg{XX51D%2oNh`b3=Yj9Qh0F6_5rYhc)Q~k)-gAB=VtakO)w& z*TE=-=B!P^C38HGfNn(IlNwxxQn`EvlmniX1{v$+=^~7^<amEVz+W)JHo{CP8@lbS zwA9SXlE{2gY@54sx7Dz03vLX#L>=cPg=-Zqqc&8Cc*{x!JKnQncH)R~O1+pzkp#u; zWkAsAtc$Q81)Qj-g_h<kK8-qTkPJHq#X|VXeR5Dp|7oJm!LX;s?g@28B=t~Kg9+?T z*t0!kW$uT?y-c{pZD>Newy{klXMH@S{_T}#_XeH#2f_NEx4*$0@Z(3zn2CmRBPV^g zvHNoIDL<9$`hR%VoS9RDZrQRf!L4VJUO3Q~*zDZZk7TaJ@$djr>-@sa<QtAat~l4| z;pM;y1^(~JlGtk+G>m1;aJ-v-&&<nURxKx``=PD_YuW&N?!A7|6BQ}Dl{1hrXRn{Q z_+-OrziS$I(XB^7k&VB_CE28&%X!}nZCVG8CveA8A7z&FB*GXs@1XEcy`O`N2^A)T zUqG|2^oQS;&TdySRgPSnqo0k+yJ)KyV{74)k|jN=+{mvNvYOI_z%Pffn~Xly+!j*o z0qFPW=h2111E++-#v&6jMB>WL(*s{ymIwm~4v2_Ml#`SXj5ao9R!*2mFYqhwbZ5qd zHC*)v*&-cZ^uJ$%YiKh=m_-~qer`ziUTJ~qx=b`d_)jCeuVeBDOoGF%8?@Jcx2n5| zvo3~1bX@hOuZNNthrW&f7f)7@)0|I_58=bO4CV7MpkPKhE)-`AuDlS$;B4kMcxR<` zcbEi@_fCzd^1XSTcCu~a3SG!pTJlLYWp&|eu6lQYDUp@4CfOKBGm`)XUCO;)!Y624 z{vm-IE(B=dYi03pTh{Hn$gZ>C;TmZ4GWejPp9Nb{O(yK-K>(GU%*c4R*)zbc7Dcs? z&VfI<9ZWD{eNamTE}Sdo__;|sO8-4Ot$v~xKBWx%wma?p3mJh;JOb6ODwngm3!NX1 zBWB5UXrstPsu6uKwut^){D(m=B?=wCG)auQXfisNWikQy9lQg7-@stYgH0%Ph!{qk z>eH(6;eH0mkG-Q=i#M!L6^NzQavEkg72-4yQ{}y<FY}Ftn^&%S5t0z&&xGwn+SsuP zG<bq?ioj;Y4-G5d1_cnU(G(X>==VXrEXT3(VSAtn`MFP{AXRToy5u6B7Y!tA<XxuR za8<zIg|y|ayOccLk;%?*BmM8pyP~UFppi_|!DI5dTnmOZh2iQFk$@BJAZ89|2AB-J zJNPngK;Abg6VS-(6WZl4L`5*JgQf!51g2_jqeL$5?!-1vF+PX>t$y&z(2Jo<)L`zS zHi|~Db9n$XKjBbd1??Bo&@3>@e1tMCCL)UzP|>+?V3_*<l{t(s5wn(4rN>3^{6uk* zO^EJuDJ67ytpYFnF&XGgEHia29s$kQ1sA(-!(+Nd41HWKKq8UZVFt@e-sagkmMmKH zj)kS-o^YwnRC{-I{P1`GJcGJ&O%u&VSmpj>ds_6<9*8_xpcL2CG{O)Y^qOQwA>$z8 zp!59t%`N5Y8UM_=`qO17+V8f!JOLRHexwD&dju&bzB=(1`W7eB)$Tn$nX#W_-g<Sy zRLr|TGY8D%`B*rZ=(#4>p`DPANo5$@gsyo+b#Is!whgzMNI(RhsAj`8o~CT27&72H z?}Q-nG-AIXP?(9W&RcJbZsQ{jKJS3-x)!TkF}nx_V9}8d%)lcj4ScH&n^H~Wpy<B< zGe@`!aU!N4vk=mX`fqrK^5Hu;BJxc5isJ_9`1l#n>mC#+F|f#duz*M^VkQ}k#|lS? zIgqFh7+bVfOtvG-Zk_+wvzT%}9S_UdWM-J!3bZ3;+~g>1E+-SQ1OpqPmX$4nOd-Ow z-Ps<A=!oIe(%RDz6lH-y`be6bby%PT6(0oZv{>C-1LPQhSdWrO46}xcFBdNYu!?qa zAuK*%Z;+m%j3U<?>SQA&W&yl(SaN&YZn+;X&uqL1Mp#qG%Qo*A@V;tD2ZjQ#%*8e} zckHUyy3^Q^Vp>~WO<&M)*BaKJUTv14R>Q`I+VmP33a1Fkmy8>f4>?ZdP1;MA1!oJ$ zgS{#1RyY%bbO9@$*YvjvHmsS#&%T6I-r=%4tTsditi%VH@P$M@0YHrhK7FBF*6!9> zsR2bQSPwAotrw*ApB~znr_K>zZoHtA@&&H11e^iLDo@aiqNUjl@lTSmnFk;MWPiHe zBu#dzF8{e?3$soKNxifW>H6BF$w(@Ro)0wLgTeUZ`UQiAJxJZeEmqc}9wb_TIZ9-7 ze$3{^{uod0Z6sdROrgJ|<g^(0usf;DYF<Vxd#_-?0{cV^r?`g)gjdKAtzOJE;=IWB za!Kvyf%+ZY1#G-P!9`U!lC!g8zykd+;Tb#lhTXJLF;1}^$6~zYzOF1GD<G^S{b@Li z1e)jt-9<ZQfT|}NTBc-cwW?=r4HgO8K4I@OnUg1{f4QQYPyJRGrj;-e5rP$Kt?I*; z<-9h+G=!Ka&t~kotlHC5ygn8$hmoQjWp*Cki%Z2>UgVJ<6rxZqdd@<AUMN&0@!qqx zmccGPPC*|`=V8=4Sr?5M<QxS(FSpm97Ysx#R4={|frABu0tK0uz=G)sndMFDpfr^; zDXULu2EY(0CjshOh>+EWWq5sIJSX=;?)>xx6SAAU@I*lyfO#8qL2*>@V_MX_%W`-3 zEM^+c2Ez1VZZam5OR_&r4^+B)EOw{80apR3b9XO<FnqjM$Anv5!j6kJK;Z_9b}zOG z`KwaZ+#$cwfh~rm5SY7t+}8MNU*?S*#LTpAQ!gm@6q39*1Rl2KyrTqoVJpG5Kth#m zZ3Cn%=;}fw-1dR-MBaHEA!{%Em$fn^77r;t7}qTt7HLu)&4{E+fSAIgi;)QuKemZb zbnT*PjxQt1))=C5d~J%X-sGjT9fFxIjC-N!IUZeOkMntE&@g6ka=wzZnKnJtA?(1P z1kBypEIV^=#Pv5A%R>d8$r!0W2E4ZGXD@pDtki&9hXn^1?MdBvK4Obd3@W4lvg9ZB zfW{o$LXj|Iqh%a~<|>I6X5?7KsRGW3ZSNI{SiXMPSZ$-owGd?oBJ5@Xajf-WfZk@Y zuC>a>okM+<4JMb4=?Z*ex3Z(bCJdT9VI}t!<E2gJsj=d2wS|d|_D9hI+aNyLrsX6p zTID%~5%V3~-XGJJ%O05#-^;3y0+f#cvw^9EBs*sZaRv)Axp840o&pl!kXjtc-eTH{ zcz<h^1NffGQzr(MO>LUpCc5INNVv0Sqs^;m@Pj36TP`G1w&U=g(ZF=Gkpj(BS~hg5 z-_B<&8qx2gB>XKKT?TQx`GxEYGe!QPm9a96C#RpFgW^&v6rgIdeJmzi#BPB%{>Y>v z#6J*C0<aBAdWSYCUI3P^%PM>!CmScp;s{#k+htlJK>7w*yBS+d%GTYY!HUqyUg{q{ zp6~-9oH8uG=rT^<$*h}B5Il~LXt1qS2IO<KMJo@vyl7PyDZKY5A~xl}ZCl<6{9Nb} zu--S5OoCJBZhhZvh?+>6#yDf1fys$t;BO#3JN{Zf5p~EqVZ;=^vHlx=jkWto+~s5s z=0eAcInI1@GVKaH)p55o5vOqrDFa)IPYie+>)0O~>OM-0TNE*nh7KQMUAm}^4@C|@ zcrZ!CYL;(#XCpHn|8B7&B%qe%D#`b`5DW+wY<L1$OwRVJL9WOI`a+thXxijE2V-v9 z+X}$}$*stco&5%-AVp2$SO1(<*IlV2)Sx`n!8$U%*pe}9s;QeF&<@^2u)+?6sfB=F zv|Fog4C7*HK1UFTJNeoWp-yVZ7GWQiBeF&^WtXs1QW5Z@gCF5*`{Q04CiDcnrAJl0 z05ixg(>X_2RAJxJS9RZ-W(8DXiY0ghMqWstGsR$pi1bC(Y^$+hm*gIp$Znl?MdzN% z%epAhJr*M0!RM@nMwTju+cM3GJCzotc2WS16K`0)3uOpO>Uu4ejISxM;GP&$l{D}r z>7-$Hk5=dGN70-h4q*JqZUHT#z0uJuSbXAp<Ao<(TC$O0Ya*4*qtlA$&Us|5kSe0O zC^)nF>4Ll1b0$|Ff7;?|_jI>;H10xGjvM;N0ESkwY!4ZUlgy|Ry=r9(5L3|&S?7EY z3=-2({ur=ExOL?tER=Jfa~a8kIZ&<_Wc_g1*i=UX{dNrlcr}Z8L-WQBniK8Mov5{~ zMr+0+!QH-q`JvBMJucm|j?^DI$yI`DAV2_!%b&`I2z;O@@1pQEDO|C-t3A(RB`r3w z8k%;=SijH^nGi)d)D(ZkLloL<v9t*?PukJ#?thvwKBhzj#Nr?{ySjo(4KHIDy3mSK z*1!31eO>z-kJTDQ#wyGp{HotVxLh}|n{8TLF<qvjrvBUXSJFCqlOhj<8e$p2N%%h2 z{3r=wCHyW+E#2ek4^hMEX&@LR;t%6_8gd2hV7<)yUQ9BL{hA42*VIbqORi>84ZZ3V z&00#!j+q_^aInKl!9$1`!<w>o+`}}-h4u5TentYte#>*%Ykt(WM&zwf3|m8K{*1)M z<9ZGxuMAN;DmGfs&MkqOSu*upm+&9XXI~rcL0aX`m?w(deKnl>!)aqp-mAa?iKM=z zNBZrf2U!>dZN)j_#8ebT|Ic^X)*oez90V6!X)o)0EaD5@WaftAK!CWa?AbRQFFTu3 sm~SK$>klZIVdbX6Joq*(GP%wXfMwy0b*WH^IUi<c;=Yy<f86;00C?%VSpWb4 literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/80kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/80kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..934c3d287e45bfddf7c663ad57c7587d2347b4c0 GIT binary patch literal 160849 zcmeFZdstIv7Cssfi}r?MTc>R>P6-Xg3N1JlXk_cuHUxD72qG3rr=kqCqk>S3g>0&w zsxxgO3CLh;LIt@9g?g)k4AhQo2%$y+u~h*p3D+7V0b(wDbKZ~sF3)rRI_La#p67?X zs1TC<t-UVqde^)5^v~0GISZoR62HZ9b93Xoi+?!NzrND;=HB$}9L|OfoB$4oGmqop z_A196e|n6A7avULc;L@&`17Vie*g2&OHYh&IiC31<M>_#{^M{*@V^D*PqV*fEih|= zSqscsVAcY&7MQibtOaH*Fl&KX3(Q(z)&jE@_&>n{3F$jicjfF^`syn<?VKZXX4r(M zIGm-QDGO%)?6Gp?E1dt$AS}oyR+(iGh!tjk&01jA0<#vFwZN<eW-TylfmsX8T42@! zvlf`Oz^n!S&#^%8E5X6xuY`ra^6Ju8SB8^+36;Q^3mpPcCb<8F{LLMI2fx7Kyi$e# z&wTw&@^z2@_4Omaa|~X!;2w<RTeBPkvBK=HSqscsVAcY&7MQibtOaH*Fl&KX3(Q(z z)&jE@n6<$FuPpExt_GV2oJYv-oBHfe%$@v|T%a%cJO1+{zguhmHu3w{r*CuK;LLG% zC;#G?2mYNqZ|+<VkGYR}dOkAm@kbwj{IN$Ld+doPy%#+3<iaN(du+io3l=VV>glJS ze%x#EAD(&Y58h8b{S<i<w>kJ3kGb>b&Yl0%6OTRd)c@;W)8BCx&YSbyT+SS~7dY+< z-R3NGo4&%~;cDk%^MWj2{EuI5?zqNBJm<}S^fA2P`~r@<+nhP>9&^Z5<JEciKF4F> zT<<@=y5^BZF@N=ZA>*mwj|;w<=lkc=m!FQk{(v9yUgrM!k3O^b56?d5_oBf6rGOQG zdTnKBSoj-j-+W6HDURA07r!ZCbK;h*soS=v{Vo0dJz3cw=IoX3JMhUrK0SEo@IRHR z!lI+a|1LRpqOAO6MP*g>sWWHKo&Wa2#fHZ3|9j<!AGNKzwvNuO8{Id5{^i!M_xg>d zfx)5Sk#UQ4Vsgs%(C#4Ta>F_Q=da%n_J2FqLY&Lp!()zzCpnj!dk+4av(RJiA76dM zdrgezUo#fH5d87Hr~X{<)#=OgeM4d&JpEqg^+%uKulUt(oE&ZDWdF|&w*UXr$^O^D z{`a|VaUP!ox@qB@g&d0Ga$5QoY~l^NSE^~MS*YV?*o(O8loGBYdb5<anah;>lws2x zlcvPfB}>ZCO><WHmd+O%H0@PJm0_B5lpYz8*aw|0j$u*3fXtHbtFWn4#)NGx0u7&@ z>?pMgbyT-ho#L9P<}1UfoB?UUHFq&LLub+nO4iFIzP5~M&TXo9qghP_jdd-cToa}9 zTo?Nl%r@Sru#K<L<3nWI7HXY%pXj-Y$xOO4JU5fphxS)UGey&!mtBqO`N9@Q+UkX@ zg>s}vi%eQS316K$(dxSB(g_Vg>@U~mN|)jdgQ+_rKdRj-u=*>hU|jYzXM;aSVbhEV z4U@9e!t;NT1hr3d5;nP7$Pc-B@GKqFWTA*Rwy0gzZlz4eLt3qTX3&AtO7J?iP7;{E zR2e$Wkxp~Y2SoN;`m0@r9@c78(gtyWR|FMeqc4@t!4Yg(c*&({PF)dKDJ|mS%(Yg3 z_bakA=3KQ)=iBEK_i4GD>Y3)~CB4yeFPb&&mTAslxhw^rl@=c;)CpUd%8hn)5}Q^s z5HIE{^L>?)USZZQrmrMc%${vO5lP*zWcHN0Q^A${DaWw0ZGWiiFwUj1T&?WmdeizS zj-YChO_oy3)|D&80;}&S>olh`j2i3VY?c#qq?@KWhVWealCtzbyQLo&&`rzAan5N@ zvOh<@Vw#gU%~?N$uivn1nyUI$HjA`~Dqj7#g55$JqU1O&&ZQ3}uaNReVsL{6<{|eh zDt64KPF^_8sloZPJ*GJ?>Zplr5pXMfw71Mkj%x7}nRI+vit8+KLZuXL6(+obQ_91L z*_osws)Sb}U{+KK?flaDcQrO*2x-wtUa_FWq&0P~4;FLP+fo$m^3b6<yZ#%IHg!gt zDWxYmn!kLw<J2wDulhqqWf=d!hGrF;sCBjkQoUl9Hl57<;j3wmc7nEc{73uUzG6p9 z1RWeHoaO{aQaR7tHO{}BKQR9z?S*O1U(1U#lcX@tUP{WPn{Z3X|5~%p?nwV@dikx* z_6+;39HBa;c$%}E%31%Qmb!H-Nu{I4?m7jUGZIJI#u25=(h=Hk6&^N{6Z>R$DK1^T z5EgOsrT*ri^K$ABBb_>dS)gcFh6!7oc9tGIo^f>C&Mtj0u|PB+Rm#{<BMF8y`!wg( zo8>zeNQ)Epz>ySsRl7QJnv>&f;Me<IXjIaFNLS}BN!l&pjq&kX)5+a&xr2Gs!NQZL zE>9i$Q?=`&d73j7=`u{FC%ss+b(*ut-<O24wIkeow^8+5xM6ImhH0JVe5k<@?`I|i z)r$BzF~6y7vLte7YVzvoXSIE6Oj-(WWICDJBjT&+F`*%Z-M8t!ZA^$C9X`1=MMPqD z(^T-QJ5S}Uv}LekY-8Nwlu;^Y<Ig&0W9l<TX0T+v!j`#lnsfIl{7knv>WAaD?^Ep0 zmLb?GnH83P5;3F4w60vb*5YfWx@nCg{T=FoUaz>aoAzW@)bHr_wHOslDt*c7%b3#q zt<PzDUP-m`m7%VdNrYi|nr6^0ODQqwcqQ;}+GQ_%2=^3>Eh349o-(-XSsVCDiHWs{ z`Q$6w=*@JETyj^Tw+h>oRFIw-EVhVD_JV1S4-bb|kL!5Mxhj_-Sj@+59Mz2ZyNjuA zgd|;G)vvHA^ICD2>S$RB&y4ib5-9eqw8J`lWh7<#vY_J|56wge)nlhej4E^7A}v2d z=T})UXs0hC9B<f*`1B>%ISqy#t}GEb4ED5X&flq)SPv^}?r)b%VUk})ye8Et27ICc z8P(J^Zs0CS%@jG$DVQxH)Aa$7M}b|PitJlE&vkgIO0O34t<-QOlSQ0%>gr*tTXrwh zSmT|iN>#7bSUTHJO>>%5?al(1#?ld$&sS3R;Q=vHeE?$ghR)}TIyF;f7V{aC*wZo1 z32A4HG+roBihWT#>=`hfu#qFDCN<WMC?t8Qvt?49EaE=cg;$V!s4nPI>5Ll&5RV4E z^3->{CV3=`lpt_TRPj{?I;h=hRN&CIfR8pK?Nz{Sq_QMgig|<zVWr4QRIkiZ{)jX~ z$DU;wokWh{<!5NQno(TS0=kd*4qaOvA;u}ksIh-?_J_iMNXbem9w0Tsml+(Rq#Nz1 z8<aiW*?>!IL>?Hk;3~c?dUuUc!XMXK=)SgGq@E_`&UojN?yz5#R7ksmNy44KAHIC6 zoC+kFp2vhJi}K+riB3bWNWg@^X*5k`dX-+q9z&L;%|^y3+YU3azjX25my3lhlbK?i zRKBWcso1lakGH$P)*Xgn?7nh|jmnA9It@Wgsw{;$Tg_+gAcY8AR-`_uuQKeeGSX(J zGbN7nSeZqPt4-w72%u?BK>*dG6KHtFyb>hkY0lnBfw^BU>CsMeWVp)scOR>AHSpz< zz{q};9yc^CF{IK=@=lJx(c(<o@=l6FhiV+Zu6~lf#0<J7REURfvo?D@GG0!PhvG|p zO7XHs9_<}3k9g-a<vNS9*LZpVw_*ARFlZ7S|9FZ#yn2VTv1JEtO2akJ#9#F(f%68P z$~8`;&&C$}KQ_~b&_S3dyZvu>bzAw~qJenkf_m*j=D3m6Uq^bP<?P<(jeC+B758K5 zn^6}k3<AwxO~}qcs3<kHFGciJO9sTAW7MFgIN`3`JRfI)+wh9ndYfj@R`lAl9iryf z;WBq{uscl8_R%A29x2N4D_^J;6m!*S#rzDrIt>T4_=q1lX}X0Hq(Xr|suacl>8Ewu zJ{#t$lVqX-<b~T&?@Dt%4=UHhUsBi(duj&YYXCKANjBHnuj?1yk=i;C5Px5`m`QU@ zeEpZ*_kEUZdu!r@Qy0DI8pgCx`)8^c^-dS-#-2fO<*RI(CKbCcdYWUsT1Kw8B>r7K z9H<;0o{3uNi#k=-=M(9n85y$jEhLfLuN(^?U}J#38P1{hm&;L*1&%g_p6LljNUdJP zTB3XzV<BAw^b*BUv|EPc;-#wgGFU`iNY|daxcGjqxO%gWS3qZbWFTnf3mcUV>7+k( zQ^(g>4S8>0pXQw1dEs&n3~KsPy^Y%ZU~r0ZwDgK%=O!<^e4+R{UU%v1+bRE8x#&k6 zBEzm38CA14E}_0l5sdJim}$=UVwwvVE*A?>={EQ`T`H>FDv5u%wHnsdQ^80bKH{%j zp_0I`$z?;!mokH9m!Wsl<Hvruqoiw9EE~hrz<pN<4UXYAO?OuH{&@6s+2-^!(hrMe zx!HdPhC(cF`amTXl!%Jg@Red`n>=)w-LO3V@WsRIng0a++N9ooxOxqIaP+5KLvYl@ zu1}j&9kQ>1T-B*dwu!TTdb@sdTxUY88=`dGflZ&kCh3)Cbbo!bWB}3c#4Y_NZpq;f zfO0ps?UeSOJf+KC6(=8w;vcXT&3!-fxo<D@HOar$0=<-MzOHk&{pWo)dD$}`9`mtj zfLqx!VavYWOd{#V45CpZ6*gI;U@xYRan=9j>;Yyjfoma5@>YM#v5ha;NkUh~aMgL* z5*Gl8hF8L!=8Oy%00QHRB8Q(_sHF@@0l1MBMKZBb845_w+(0Zlb;uBo!L{Se(Rm1J z_N+}AJ*VFqVGxWVhg+HCI5pKPRnj#Iy}UN>l!)ZoZ!@%vL(vXgC~%!qG07a1=>ZX2 zuUD`oOj|B)Dqv^=5KM*45{Wl;8h|=$PEfsT03S*p`}VYs51bMvY@h~DzTJqt%pMc* z9E~+wovo-MrZ2PKo9|K}hqg7p`)YQp>mdTXBBOiPLFA@44=^d_(YIp{=&g%Ln87lq zb3+809lR2s7|+^VKc?^Sa-_q8=4nn3<8XBT*qq8fyI&H-CbAZ<9@jKy;%f7nhj{{* zWGPU2i$>4f(Kut98^@ng)1TxbrP`E8KFfViN*;ci?R8ZVWXpbUukQgHZRupC*G*c! zX7cKxrB1K0mk!C-lElL+a5e~0LN}p6!*}&?FPAPrx>}Bk=&z)4azj*_>zrle&O!hw z*u~jcI?u@5X3ZK8-X+vK_6+rVo1mNz;9ufw<iONoD#tHGuar#Eqc4sBJk9BAi_jZI zrfVKcQc8Tpe)Yw$uEkhsKRnG5_E!mT2x~{aU|qGZsvQN<O6Bki&`8k%UK(^ziOxpF zRTTr|%bLVo4GFerHz48S7`qbXCF_I~rOeUhs}2R^pn9X{AQ_Gc8!337Azb*-sIt*E z%VD%0xcb!|yo>k@Wcy9XuxEfKQ9LeLd8x8(35s?rKHoB;b+it-H_=US4RN-ogS;o* z8KtBGsUUVAtV{b_TmW*3+SO0vJwljN%~VIJ(koCZGz3cU53o+0Iw@0(Vs5jPS&{0< zVN2)rE8121YNVVn*CAIUavhowKaRJ^#F{CmEq2YoTSda%q5+xJMmo6t>*@oEgE#nd z&{?78ALm&O`l`XkGFyQ?GumTZ>pV>5ILU=vH;VbR^=i1Xn+}Fs3L64eS)`fb)eEHF zQgv#^H0QgKz5UjHD<wY!cjl|p*f-$XVZHzf(H^oi*I7%yifxSFOYkMKf@l-|ns_6T z%0WlLxJo^>f`V8ys1AJAFI^e-OtG_d<VvP!AleOm1u=5&OvFTsg{m&iWJf-*1X7cL zIV)G#)9`VQMj=85o#3+q1G*mjE+?AKz)E?j5lFsLNt(Kv(nkxlK4P|x=SUYh5Luey zwMx<Ir-5hn;p$K$;&Ax5n8&O*A@+9zAhTufyJ<s`t(8}a1OyG#Jaa}YKmwMoe!g+N zdPCPPo*D6WH2XK&E7dYcfFpY^($!*?jj{Xasm2Gl6Dh!^^`kd(7xOgSg*suzHP6mw zukn9Ws7^|A@OphY@F&x6r}wbZ8&8PtEw8BL&Ud!-7)Yhi*HZHz=7^hBzu9abxgNS& z`wLtx<QRbd%<-(n-OZc_pQ*Q>=kL+MKvi-{FWuMJ9d9qw?+M!&Q%r4CHIDln{3Q+F zkjhf=PZ~-Ey{uKZp<24{=odh|+}$z@6)297IMd(xHE(?DuWuC%Y?knD4Jsu{$77NP zTszL!U)0a8cvy5-e`%;Ma)0DfoVY;C%{Dw$zT??D#`2rK$F#BgVY~iOq|T!>@>*hI zaYAn{e4>WwL!C}{rT;pNn*rR`O&h3|c-{}UUPkV9wZJ1IwiY9Vr#X`yXS0I>0p^7U zUy?R0;$;4@qJMM&rdJu#QK9j}qAkjdJzCWE(}*(mOnplFX)U_{5cXL7+nZf2!Kdy@ z05+316H|;gE>+nwWn;FYrP-RtTrCgR)oxXyn6s(%yT{k_wv`z7OJGdY$|mYNZ>j9X zZvel};Q*S;@ATjMoA6RSE=Eb)(}7#3Waj;4fg8V2QoSO;&5f=W1O#hV1WH~A6J8`O zg2ONgNFX5)0l+Ts%xhjR5VYS-JRt_}(2w?I00n|c-i*XE@PXacrXZ~t{<E^qDvlyo z8T0&QUNKrVDXHj3Mqn(d$*vjo#U&}@3UpIasv95PW0$4%mCk9G)4hUX-1g3JWf)$f zo&g49jS7;%m^&Gre8#A;cB0yB0bn{YQa7g`SdTg<HnC%<3BfTG@G4E2%8Ph_<|gF9 zBv<2UzASB;!>yQ`gLZ$EWIMzxY-kDdhrI>G&KCPHcOi+z)7(rkFz*;OdVJZ(?|3<e z2S{-OOAsN&50=DAJc{2*C0&LbO$82+&2u0c9qH>I5kGI>(w06pQOC0lkLv^l&WlE* z2)edH<V4~at}I5T3jaup`r_{{3EcZD5<M>FILd&w*kq?i`6}Wagfl>veA(4vAB>e| zN}PsZ{8g<K`z`yJ;35<ewNgY7Ww?@>q@A(h`@@WCDmb*0_-N*uwVBiyAC78~0>>Nd z@_%urIe;hd2Y3_HRlwc@E{^^kZb`v+RFf=dAI2N%BVCOzyGxOwMCcJ=mzkTOGFSz8 zJFCuV2n-h>4T<?xz5pYUt_Dg97wx4r_Vo4h2hp0gD<wVbI5k+Fg|~N|#ZRHSjdkFi zLlJBV_?Yyl@A!aCk`S0KfoEo!nLh~NK!(U+cDs&mF#-aV)0Zm59x7rf-xJ??0T59W z$s+V)e5F*Kv<t==5ice9sIr*nny|PUg@y@q854%Q$b|+Ex<!E;RSV;2Y!<+=c(gp; zAK+`q@;H@Rz3pwwqE@9>Q2Ty(;tid%)z!G4?gN>`8xz9l@w<g0?K92qd;>nM_7BT* z+eUJedBwF7E{#APJTCg`*3S~QS?n^{2f5j&i(iWE{xP(_?%)QeN2ZJ=fmdr8S+(iM zy-SsnGqQdrMPusz)90UMO1OLM1vrwhzqG6~tM3mF-}%uC*^6YZm+w~U#y|S+wKe?R zYba)qWmKj5{*`1A?`QsjK@ub4=q;{iy3hL?_X@z`IMQ>t*}~Fn@7%XLQWdt{5;VhL zR!TMZ{_%+hl~R78Da=U?#SEWG9_f9lbF0N@aa{~V^}end898`JxcILA55Dr(?MPcx zzr3=?Ja=Bii$5oWzVJ}ex1%(%<Gd-;XLRa*i7#8CO?sm1xxas=xu{}q#s4QLiT#ne zqLdJndP4IO_s5+Lf-!cmc=L_2+LXLThq#m7vTD0smW(EHWJF9!V{|V%K-dDO<$FyQ zu0fck4a6yBW~!$P?N1v=b*>NzybxV2cv#ZlCSKcsJi*qLNU8=^w!){-{Zw@VNDQ)I zilaD6AS0yik@>)m5s_@vr}-}`Y*}<IV_M^B@B_zUKK0#Gh7f(_^;kEs%&v2FXa6f( zx_@tku3Acv-OI+hKZo|82(NML-mCbpdaXK_*K~kQY|7Rn=-D%kh9~!aVWU&Knsj$b zFo|7H?Nxl=yjGUG(0&B<5j;?GB=^gL>qa#3H8apd5t#4a2{+Piv_Fj`*H-f}IeM6H zHI5Bb7S6}@ZJx&m<oUh6RTSL(DmPFq31+=|fJrBn32p-OXv;%5=dH6^su&;`T<M8Y zQP0X<ErTr}6{b0g?!ePK{JOtzw)7%)rk0g9D)i@7V2l+r8R)I~zD}ixtC_t1Qs!~b zqY_WoMD5!(bYRp((4xKDBdLz1%suc__speCpQEv3Fsx`x<E}A&ZBG%s0Zm{Ud#1!Q z`|f{MI-?x(eC1-EO)1R)`xi}b?-6n7%O;mHp8ChJIYZA-w>I`LYIEMW9qFVN0cg;P zt9S5jZPevZ$bu*xTQ&)`>l0r3f^xjvcd1Mdy85o_eg_D1f#W|DYn-k9a*{R%HMW4L z04brAX6gYvao$X+X$a_<C;(XzK~17>P8*-*jJKs`*b6{-gKWwdScMI~Gi*2-l_C$t zfMkH~1j{ZKE=dARY6;fx9IbHlM35#mCikzw&JYUMgY;BXNbA?>WeT7*rVm77U@15& zk|#Q&@_8Pzw^=JpS*K1GbJ<jHki!HoC7f4A8ZExeoy>UWx)ci84K=ndKV)aQ<t}5) z&?ebFrE@?6xF+g~V->AH#l!HhQS}2Coz@7LeGEqLI&e)W;3`vO_g#n4+kAmfZobm2 zFg(aYnJF<{X3sQ-KR952t~L`0vG_%YQ=oU|<fA<+u_G$}8-8#wRYizHr6L&BZuIzq zEn1W^&45UvvOO*Q{@DSM=a|1@kQoGVeOD<77GoS?qelZmU9DhOi&i5!gn%lj5S^hW zi-a;*9JRU%PT4_o3ppa85}}9bMq9Pt+X~x9!j|CtmqjS^q*YXBze5L0G<wU(4_z~5 zND>@X?^CN34~PcDTx6X5r3Y+_W9%C1)$;w4;1M(h5_K3lQ$x=U@lw>}{Kqcxt;T9! zBxt@0EGGfLiCu?5l)3;A)rD^FP=rm|5a4A`ACRICt0b%jsXLvB7bG?O8L#3Mpznfl z24aLP0o&x(NZ<gp<*LGw2F}FaO`QfV6zqZI0FxwphcIJXqyR07X-<0A5yH}s47q!S zU`DVct%Q$xg@&KKQO_80_;Ai?Ombu??7x^E6nYfGwHn~o!D4<PN=+7r1|&rT1(K}< zNZ}~Cq?T;Y62keRiuXAT7;D+R%Rx;Rz2kvPb8Z7f3#67)rjwim5HF<vZS$prm~CP- z;M1J9;xe=Y;(_S7pO4$Yb&mp|*PI#_pzotv)*nFR(T=&Ch%n*d2+1VyVL5WAQ_@}q z61;L|tP&<rwU^ElsBG$Oz%~OQFVsl0aJwOe8N;g{dxlnI29~y~w=GGcnYzOr63jN# z$sAFO-s(?kYi1m86!<_*J6A=ZK?3@Bv~f~t%51FE3dV#NU2T*}<FcOcn$(Q?yKBMT zY;-+j_09`~y)%T^irz`Dau*X|mdyn*D+yKvALgUIL>-e2anR;@1(vW|tAPfpjLemS zYi@$R6WwCr!=e3N!4fql6N5|-Cmo+VkRbk5vq)41U=h3*?ImoOnXvK&*;xCDc}9&b z%WY^&@s(eeDkBkWxYuFS{)>kvliyC#fXgN9eTiQ*AY9xL@JKr3T*Q4#mfKFRIip(& zHI@zl|AfkiZ`^y<7vqqC$9PYt{ETK0Fr=mEyyp*3M0L+|wFLgF`R=<vyZGb(n6&-u z+W}unw83^aYlpyNt^8%_=aV}~bN?&P(bj)o7P7Z^gH-r=6d7x1Y-Yv7cb51&6EsUs zPKjaG-6GqFwESE5zRx4L!x7JF^yif5CJ78ZAoz6WZ>jsm{mM}EvY7%yTz1Oh<WZHu zuMeEPB=}5P^9-A(KQ(7vJp0q9RN#Dpl6Iu?ihcenM)<N@;w%!hwFpEn#I|c^KH|mH zv5HLGQovqc^Az93b!C1JKx!G3M`G$_`sl-&9iSe^FAGY9bQ8J|%^;IzS2l^h!(8a; z{Xl^5-(^F*1tR_tEuU_Jf9t5J<KDK_gYe}Z9X}HhZt0+U-<m+~LA152z<(H}N@;=i zIcWjVy)5Z4_(-67UnMa}fp+tqJMu69q{?CsHJtq-U%?P;gHe@$?IavxYoXY5nO_VR zdIbom6aDC)`*7nXJDC)AEzn6eKNFmM<_Cn(YY9{Y1Fn{UTxCM4ec`7(vkkdoIUh5V zBlBDhV50HuF3cnhBq?jyW<XDKF`9=Ey&WhnO;8fQ+Y7&uv>-wi<)UX`6Q?<Ik-PvX zK_gJ4rD5xVabn&0OSaWwq>)yFypo;r+u5JEGTPAq*SXlQT#3;d(o@rkP*Pe<GnIn; z22_IXUxRnJ6`ut1=1wL?NaQ74TD$h>X#>xUzuYQ(IH(|_MD|S75-JeW6u_5$c~qds zLiCV!#Pye%F_Z(7WTZ7s3E<%feMbybD=$@d!<<rlg@9C3*T-mzKm&*dNPZ5K^!kZB zG%aKfWVw1+z!)=0NZt-#%4nGtR(>BD>9j?=IWL01MMlMqY7<yo4Z>D%6UR_Vgd-?z zNCSynAa!e%4Z}rLeVxG3YGh0tlB<wHQFF`WU~NjsY)T&`G%$<Vx<h=+AZQ!55fD2Z zGnxM}$q_aJyxDPc&sF0>5^>5Q<*r`vCzumWbey`IfaYef7%gTDKpL8c+hBx(3?!L< zsiZYd``U%@L&9UmeeAIaujsMwB33wr+eZ=pOv;x_(fJkVVDCh&p9n))!uzE0Slwz5 zTwX1vb9eAN^0m593%F%Z<Jn-pjRZX~n0!>Biw^(hSu|Rhk&ZMSK?a9qO&Ukz1+*1t z1;qj7<8ZN6B%N*u;8<uM)*36BEV#Ln2NY3YFY3;XQm`+!SgwjmXDs!}jJdhys@P{@ zTx+s}FhYb{Bhb(ggD0BEJArOj#t;tMU3<Io0LD+4GaMI86{4{~4@){MXWM~x6|-$g zTJdUcaUM!jM--StxTcsIGl~2{+WS^}DL0IF3V$jTS+B$Cz|R8Ch)RH>;m9%eOlcMe z!z`Iu5rHWG^pn#0Favyb@62SzNU}i=KT~AtqP4N2)sGm0#%`=TG~zl!&Xdw=^|ktQ z#(cct5Fbp%purge#@-K%y_RmOMpOP~{C60X;d+DETN{@$cZ!7c=o66(MBs6{Nbw}^ z?ze<C5243QST{puir3Pkb2&iZC&m0P_*K-6Yv7ZC)<0bG?D%KLb~%vr?t{oK=F7Ha zAS}?kXeK)pA^OrM`>x2IX0GIXxFq!`;fI&0@ScF=ym=2BH-v{R7g+h{)YN1)eWjPX zp9=oSD|j84>`2$ep*aeaAD6X4j7B}TK<A-O(#UGXJhQ)hQ?`c^ttg?g>Wbc*H_~L0 zS>TFn_-_$Q`tlBLRv;}Unr;eQ*_CBIc?V<m?<F2#aJC&;^=AYKnR!b|V@&mK+Eu_u z+Cu@4ch)2dK3x^n$-FQhqcw5f+^!6`U)AaByuCHZxraTAxnF?Mk<yoA`u?`>nHsj4 z3Y6H#JfLK72lhgp3xX>!=PKJC$-DVq$_vEWWOcu!UwnVrhuZI(|Il&&T~K?MFeXx` zf^I%*ED#<>lEoR07QGiHRP<uVc{Tj=k3QZJ+g093?(hx3>z1I0%U&aFll3YpesYR+ zDX>^8CUi&*Ql!>3xO}S~hF`r<%PSxtC>(u8<RIomwdg%8SJ4aS#6bUnSfDZShhbJP z5D%=OkhzE%*!uQURtaBax5&(r$)finjaFYoZ;qcR`|%^-5P4(%9Hk_JLKgnlW;hK! zMRG^447EByONf|OG?(F=EX_ox4gcxEpi+c^`e0avQ3_G(AW--xLXE$mA1BH1WXdbg zMPPUaO@>o`2;+7-XMnE7WySN=k;trS&HXM+IKY_!^V)~wJi?2|;PgSPXVTOc&i`z2 z;6Q^XclH1#aX(r@G3sx=Qt8L%-XR=7;z0D8o`>5d4@;y9Oi1ubY06*sW>EJIT7`yQ z0CUto8v$<?pWL()_JVdk?g*TZz`t8XQ=$XvFxTQ2@-Sq$&inAI<8R#k8<=m#Bmx~` z9|lEq1e%kXvZzjuL(f9U!P?R{jCd2dgjpOddLHmhEEpr7&>bT%`<8kVASGcc*CVsq zic$=isD__*wt#}@jN+gOSr9{};}Wki%=J{ZY%mRA-@tPFT9L!Q1?(Bs6Y>q*cfk!h zBGOm@hr!J;!K~}8m_@^&$ZD(jRjyVRygo9L6h8<?CK%>jaRPY254`{a$S|43A><O$ zXu?`0?YuaIi^f~W*m+IpXrkw!MUVs^!h54qX4xT)z!@fzgCmJ%hO}lNuh_b%{q&^f zQZ*DrJ=f+Kzi79j)oQqo;80>@MuLpY7NSV-k{ivD2#PUu=AT*u)*n(JWDBB{xFio3 zwsFv^AggzxkN)k9bdMIfjCAp6DvW*c_+BA057iDS1vPro8{MkKU@L3|pIoUEOmm(u zbw>=0ME+g_2jWoSlZv=#2k_P$VxTdiD_N_IQ{9nS*+!Wqyj}oAkHVJ!a^5L`4tQ5R zA|W9jNwsi75?InK35M6MUIdCvP~yiMrAE=p0<J{~QEL(i0(QSMjvpdAC3NZmREWL` zt_x4Ba6mo6d0QSuV?5_<tR|)|Lg9IegKBSO0qNH6mLmU`5nyvn91B7W#yrju@%pMM zdAZW-1t5o`;J%gzP!xP1;~Kz6v0v~8%SI!a6X5RpbJSj_z2`gms@BRfd!g8~#Mx>r zokL)cAzT>=>;%p#=CVM;p2av1*b+xsh!BEBXKsmJG6q@(QO5KTHg%iG4?x}N+>(c| z+olHR@+CUS&3%ytx?PyaH^!{Mox#A<hBp}y`++pHf(d!EOGy>`h&<FZdNniz3VZsd zyXSF-fRNBCe$5=c-Vd5{Ao>vr(Vna)+;rWis{-Z=TY7X`x|^R?n8l!9@mZHjpA4iX z$pHH`Y4*r#&2vcp#{`U&=T+-|z5mGqQ0`z=43gk{VGC*bWajYh8(CEoefIRt;NIFx z=YwBel4d4?u`$y^h{{TzJb1YSqk7L`KqB0Mv17FbeQO3}W;ms(lCb38W?TC{rTZP! zBmoYo*%RAqggILX!;r+L*a1XV50oh>v}a_*wj2UNU=6^nD$)>PusO!!`fi5T!+|dX zRUZcY9pkf)Uj5MsW7W#VzDnpd0?Xthuj3~Wpg1b9sih;l`2AdEq^3zOnJkpHjP(Bk zkxfQ9+^94Bi@N?7h*#h?)~NI~3-LZkLnziN8=Eo);68kk2aOG=Q{Pf|NiX8B4ClQ8 zXU_no?u3pZ8!W{ypfcnV71F)bdlz#D6=;Pre;%(@9f=7arXEGOk{PzY;5y6!=aZ69 zY={*CAi^w(sQKFX-Sd}9jra?4av4-)zjum~5Y#g$@n(Fewh9>((_q~F>Pa^?%?x(l zIc{R$c^g>^-Afwk1iv+8Qa(d6(D$$NO4xentE`>vh~<fn<A)mru5VEN--J?h_ZsdV zFq1P_ty`)T*a@VT@G~k2y$r46`0t1hc_noCDKHc84QjB`SxCC_GGt953Scj$0+QYs zL9q}l8D5F1WQGQ5p1B<03*lV>L2B9<iH<-BD8Q@f(REK=4aaxEM<|gT*)#dP88~0@ z(FnSo5GKuRROzc+Ke1_!i!O*Y*B_Id(L$XHau%>OUvK~#)#5YZ`^DhXkgAYCNtFHF zpInbz;<Rnl@d+1v1f$*3xpxW-1fR>rK)<`7mc>ML^d<0IC~`*$tu<Mw!+YR5HIBK@ ztd=0tjDAuy$F7u+iiy`0bg5xxj7j&vUAg3nCzT|XMAhWe^`s*?>Ma_G0c%6lTsMBh z-+|~RcSFTPgpu8#z*3Khj3ROa2Q_BY>(%64HKPGdU}_;)g-d2{1-LKh%9Ls@SzN6~ zD6FIg`SPu*cwE&-%f3)VL2gC#J0n6`_~F^hXd_&W_xLw*+kV~;A>ap#?3xzT0@6h2 z8WpW-iCJ1Gt`^6$HwMJ<d;W-t2hVa<8I@M@=66Cva5#oDWlW>oD+sznlC#pBjYs&F z5j0OChb{m_4$1l<?bXx`U5uS>Dub^9_bPBhS^{h7A@IQvH^G=PbEO<g$KX;NQwsRI z2p4APMTkn#IL3-H$UR98m=Bz&hW@u1ZIsDd9KRbmv?8lzs*`17X`h!hBLS;@ArvrC z?6J6ofE<X9{3V$2jR0yRcl{De7;N$CxvSv+om39bJY@BEo1h5R57waOWpSV-+3*s0 zypk^2wk0XWt38=L@<zp@4}Z*C5_$J{#7)4U<-W?O0i-gBd_ap&q%7FGeg1t}Uxk+U zGc|nh0ZP5m7tFiJ@0|yV&vv>fs+eu=kn|WlaLCBflik9wM^0~LzOK*>Y=PnfxvV^E zaog?!#vU-=w}ut{l13b;wdiC-(NvYMdLG)NVbe8k<tmdsTeu`Od*@z|B;hqjvYNT$ z<;QqtfjsOtI6<OEQHQR2@4gYqDj#B%%o#;wuvMs-B)y>(0JBYB*u1qXmHmOVJrZ!B z+o3QRtfKC1<Z6bBEim>LY4#wcjnQr5YUv%>6%ecj0hZ2qn17>Yy@Gku1;4U(G=WEf z){t<orju^%`xf7-g(E0g#FXzzk>6x_Cat}bJ-D$aUL16)HgHcDzw2vX6&umdm_nSJ zkgg3pW>0;vGmCJVzRfK24DZ#E;P)5MwQ{pp@S({$1PyV4J@cfW<@8N-e0{kZB`{DN z5H`2n@YeZ8@OBc++p~9~TtoXZ&EeHiQQbm2Ng+luq?INI7Uh{hSM?CA`cmexJ1u-! zDvz(3y84L<8G&FB5#b?+zoZ>L-fOtflp7oa>TRp_DVD2H6q14~aA>Qc=*Bcd5)9=W zla#?Y(h8t;fB-?=-5rKujShV&)Zzu~{Q!IZ_Sy$fDtUk@9M>&VLC$_9ha_anXl?f& zRR&`87@q5#ydeyAXao5Go_XZZ>&cHuUPx6jGz6l)^>wo641*8D(Ngb0v@kunpP!JJ z+BFt~zP_6Ee*c~A2aWI<+~05ML1x>$0N$fwoQvROA|~HefbS%(wYE4wMKPU3VshY* zmbcM-gCdAiO8h=Mf?lhSc`xSqE{HY=r3wZZ-=56ot901{4JfEFK?w%VwN=aem8dGx zgr-B#u_8m~dxb#tj@&3Jp1~mUQc&4FVyeVP;=fSK%`kxZEtD=v(u_inA|)83h20m= z0nF7nf)DjG(;Oz`1jsGioSaSl8dj=B@BsSuTZYNkuvCDw8pd}5$wCqb<|8`gRjv|h zcBtkdsD$wnMI~$<m}~aTA-E(ET!H^mUwP<Vl5HoimMZB!fIyQrHd%I05~v}R15*iM zNRi+dbcg+<3mNH`YY4u+!NS#LmQn~|zx1YWMh>~dkEF=CU`W;yr$z>vnSDA2V=)kR z83Iq;6~!PWqKbZ*Eg%#_SH|T5QLG!!e7Bk~4Bc@AS8cq8cEW-p6k~uy8{I<xiLib` zc7Ptv_f><U$M9K!YS{@H9FZdzgWx(#*qc#*Hzx>4O#Qq9B_Z|Z5h)KRP7p!PPUxW< z*E|;DnvcajKox2PP+Bk}73PpFhhC5YO-vs?3jpi^z^Mob{ZgrWC`AiUj9(tPqE2C) zr%-+Cd6QQa0!WHH3Rp7&7~}RKKpe1g{K7Q^=^{z5Uc{UVL%Jjx2nASA1=h;$!+20s zl+MFBfmljWc5P()BRQaN{5s}~=sesjAtOYguhj9s2oS;6v?H(-;o<K#&YGi0P>%YO z37EQ2WHXjNwovN>u><A=QUqk#%+36JfS4~|rGY266uM#lnhDE5Li7;1up(<01WS+_ z5pinCY7bfR+nDHMfVGRLxNk;@{paj(My=B9!OZ-~`vtg9k^QwnzvFBIe2#OnAMD-# zy_fy3P#f^A%OvcgY0eAXE9CQVu!^F=<}~y0I0n|yp7b>5u~@bnifm|wCY0grT}>Hu z-T=z4zV6Rrp)Mkd56{GA%krKSNw!nRhtS}ph+pJMrs7dT1<Gb;I7ef^?9)_^Y16qf z1F6BM*ll7ik;^Od!+DSD22x<5^~U;gqoTF*U5J9%G3GsyZP|e4Q9J$q3=f1(uf8&^ z**ft$@|>W6D@#?Pu5gT04wxH!%FS@$VFW1f+XrA-FYxi^BS!p5ft?gG%!F#_>drU} zlhKZnS?ykWt{AOO7SSAI(&k6mcFoL1aG%xmW!y^tXFW9#<$}0`Ca{mB2AlzCcgkSP zn&v<c1_gWrTEop4W2EBV)MG-!S&~Xnnizfp9je?5I`&IMTMlZ69u?{Yk^KrN?4e}@ zA#Fg@gWeh5{4&N31b^&DlS2*m5`PClsbMN(#WRUzxY9Lo0y8n=%nFQw3VMj5e*|1A zRm>%GVd2OX<p);kh8=XY{&RR0bT-Ikol#)1lW_BIMsb!}10k43$?JzT^v)ulhQC|7 zBxMYzJ&J`S?=qlh-P#3WVWxB(-TY*sn?S=K*Et`$8YsjG>dE<lP#X)-B@bJ~q#@pw z;!S))1|e|Zt}z1Fx#LF02*w*|MnLML<?5lknCBB6Hj;09l}pFRfC~=WhhZ2R$Pj|x zM$6&anKJWAcswaS5YMHRSalF^4j=ah%0ZWd1Jsgeo487rdLp2US_!LG!Bd>Ls~|_u zf$YP|6wV2~3Te!HiDZ&^M2%Z4OxbW5pB9Wg2h0mFn4M_|j%IIVa*5sm*MO;#Xzi3r zHz3Tw?!pSo$m(hy)GpvCKB%;3N`ShEFj);VA;~5Vhz0mW{tUdfnezkQzOCiXkhFGt z0F8kL5Ed9)qz)A{>#3QT-)WkxzE!TnSO(ZaZWg*q42ZX3<c*~Qn*CmZxCLngZvYG3 zidG4!9ajYzBN-Ec@FIf)7$Ey`pnajMg;|_Xd4R|(3(#6PTg>tE`GDQnTymX-{#n%X z^OK(U;$-jL0u4S%kBqjL*GE76oM&E&z@}~Hrnbn@(!t`U)#zq1&O*U%>5Y3JdQRkQ z{1_%fx)y_<C2CM(`0L`;iwtZk>4{>9|MM~XLbfZ9B+wPA*;r{IA=~Zgmbgs12BAfO z*(Sg$Lm=tlq^nW*pAfs^L_Rn-Sey5eoiNNUvkwt6#zVc`AqU3{R9;5fzkpQ}ZXUS% z8=+GjnGqbI9H0c|su9UUZWwGT4==U)TZ|_FrB}~4b{$@uxe@-0J1rb?vxv?d!lafl zJ)OY8n7);rp&Y;9SBQN!SCuKtAHgLgzx28|7Kuv|Tt;w88%J{YBz_(vL=`GdmQr*k ze=)K}70RJbbO!(eQ`9sjt8@;NoE7oxcpS@Xw(}XS%Ubsl1KG!Ih#FU|OzJ4Tx#E{U z{e2~2dh~nYPA3vpRg9cTj}>N$xcHhO%=@g6x)-+Mqbg+XMBcd8FIzSAVDEtq&b)GU z%D91N^M5U5XX*YCDtP|Pk`O&NRp$ZSjD$ZGEH+(VQX>SLaD|@Q<(dFZT<qhW49*h` zj!FmKoo9$KtXDds_OGkv%ky~yao*yAxJ(JQCfd&I^cKbQ<==ii!@s2*{IANu)`bx^ ztD`|AFiH!hPv3-M-8YBl`bJr<xO|hgevkIfHmuruNIBmZcV+aO<_GPdgz6x(Hg&)3 z5Rx;7yI<LtZ5#8gk9sgM&DnVnOCYIF55#WK?cjr~9cqU7UX2Kp;-yiW0wRX55gv-} zF+`(>tA&b}zXwzXS&l(xU+^PX(3t>NXMcPxLTc3L_v7|%x=U2VBuQ+GK7g@U&kg7E z!@uonf(i^Jvm(3dafn<XYg>ens4LR-iHv*qdtvD4I;*_&#8!jKX0-zVHTZ1Qvt8$~ zX&_pgckjvnu2V<eLPv!FW0Lb$J_y7Wo;F@W?IvXy`K39fBb5Pof=8`)DS8t+Th88} z$lSYqtvr&Dol*!vAXJEb`i*<Lf*`*$|GNMi0ZqzEjcqr=yvW0w2-Rw9LLLVaSQXGy z%e#muRVPO)7-<c@Q;($tqNC8*`qA)VdVxADf*yj|Q|)RHKq2U8Ol4<$ed<+k$_Q?Q zBW)dpteAs80}3L0%O$~B??mbcR6GE80-K5?idR^$g9Q|THthzo5R2r`Ic?Gs%`DPB znmGz2<KUM?F-B`(6GRqSZUTp$ys@J(!U(k9m6I}@g5EoVh!ztEpg+)KyQkEBCW=0K zNu7pO8VRnT0Xopu{t7U8M+-S?1~4H5>)|?kLc}nb=#2(QFwZ1(1LR2fV>FtEN!ro@ znJ<MQ$60u<U7o+p4nRxP&4$3kMnbM`i7Oz}A(9gah%%4hE+fCUE6YG-VrI(&ivUKT z6ppL)qnK2vk=szyfxqT3X@v5;9gcBqVAN@@402<6WP}UJEk6K+1{)Sj#sMcldpOc0 z=iyr2D5)O|xgle>p9mcWc!W^17iuHU%QU#I0I4rjMnJEl$K%uzG}}xP>eykv@=*>5 zY8Z7!uZ#q82z^p{;TmlAV1UP_0?n49f^8bB1mQ9mKf_-`8&UcgFo<PH4K+faH6YZ8 zhOi8Sb<nrqRX{DA#NHy59?H-W$OP^HjN^-7ltlx%=+K7<nRW$tL&EerI4W$`oUNkd zn8YdLh*Zx$xEe&d`4F6-C2I{4{{@$;sTW9T;dql#!%@wHa9`*6^%ZOy7`_%rJzILC z=Qi9oT7)_*_y%H04iF03HI)st<bVLnW|Z`W=(&<0NG@Yc_99_{-5d23g#!U0>{mg8 zTKWj`51gtD;N?AyNh?GR)1Sx#%jrI!lA5~INuXI!N~rxaI`CL%S4JYy;!;?&_#a!U z1v9?UD~=YS$Unq)aLYJpSW}f?WQ4f_@O?Bea7X^i+z?(#Hj;xr%JIUy!D-GXviW>M zL3)LdQDyGfSFFWJHY$dk&yW4q=XGla&bg_4CO*6%+d}G68U~aG`CeZQ7%yS#=&|PR zrRou~eMFD?S_A0&yRar$j94H2^48$GL5wHS{DbYU#*hm;Y1rO1h)zM43z+B6-XN?m zIvM-0pWB{v0(pS{<&bDk4Uwq_8gnKolf-{tqfW8eirj=bp-tE(->^y2OAqP%pRE*N zFY6)JvBl`+wt(U?wAYsW3669FH4&KBXU&T>kR~D3Z*QmXYsvNt7A=Fz<$Ld*$L@^N zGOAW=2B0cG5Rc4pGCsctwc8H6Y~Wi#)&EY~Bi;O!-hu1H%_XagWzP4+!UpO_*T<Kz zf&tuw?1}C;v)t<YDOyjWVosRBn5L6^`fe{t1*X9EgnYvuj5I%$vIan7@Z5v!R%OYm zu4m2wv{?FpZZO8)hXH#h>ADT!mlana0853U5Y=vNg{Y3qD8hUdPIjBeosp$>g1Lv) zSs9mo$>ae_AmHevn^RW+#*&smA|XFKnS$w5Y1$k70wg6M<{W2B@L^%=pw-ptI@AxT zpx$XgMq(DD#a(uc{h8nvm^PvP^BKh$esm+bIj+Mmw)r*^?OJW!j{Ci-y}v7~q#!xq zuszqA(-smL6|!xdtkVWA#_@Gn&5Um(VW(kM)U9)FCA{z;#_9^^9zd#+wRzXV4-Hye z2#GaZ5Ro#oS1+6%R9i9*i5xU_wSm5`04Ixzw*|{vMuIc=@Q$KQbE@EJmX0t$*##-0 zK^^Y_`Ebha-9X(>2}XYnz;3x(u8N0x2xBT=Wzpe=YuY>>aY^96$`Udzq3`=+fC?NB z94Rb9c1#zOVWajX&21%8*>c?6!E*Xi<+}~PU?tjRoncIs)SXic`ygC|Vu8p@_s~1x zk2vL+DbATwLXj<1RL-Lr9p5BX_uC_`R}lFEx#)p+viB|iY-h_o5f;Wkmm+qh_2b=z z_tIY5T-A>mI)*-lpvCryd=meNkM}<8TM2awfFF`Q5@a|QfWRwSPeLvs`JB{D&?;ao z3OPCQa+NKM<OYb#2;*NiBk7XHN_i8VtlJFET|b2FU4NG9xlZ~ocTn>*zPB%qr1dTT zdN|~c?HVciW?bn^TCSSr?9V5i`O!j1TFVIN?+gc8jZboioInwR?#>Sg>FDIrnf>V* zEkHXs_$<R@W;FT^a>dvig0>K$i{a55*W6rLf?}Uw#UwV#Tn49Yt#Tu_BcI-c=LVE3 zaXlKF`Ja;h>KE_nVsx=F*as{<5js<@Kwrdg3m3gB|F$XY-edn+V&`7~6aR4Z#WH!+ zqpL(o=R0%bcTD|fC1gd;hrEZ&^40T~r!uDJs6&ElV`UgmNqus1qPOh*@yB(Syr8r( zl`p(L;yIt}wPT;*U!%{yoQ8=c_zX+Osqf;H;UD)a^fjHANtTPtZ48_%g{?O&f0x|; zx}tX^J>AD^HK=2CSxNK%zSZ&~@>WW+OyBqDH0Re9-79|KUt)j4fTtm-3}w~}?ep)! z_4j4Q*Wa#!x7&vWuCw*^)12)ohps<dqJ0xWJ(D@IALH0&<SJfq;!nlxd27ZOPrdnf zD)xNig~j7Pe{zMl^K-Izb>Xa;f{zwNm@=PB_^q<`{l+Its)oNUPMA8A%qYj07pPZ> zGonCZuQPk3#k<)*J>tdF^3WBUMUrYPv|>(-brUQ#0DiBidqHw&;m<=kA1+95)MC)V zSFUUD#Y`u`g>0+G#jHDCAYGC({@7H;rR%@t{%75K<@b?zcL|@()i{Fm_47Jqb1DxB zMa&n>Nv=hLm|vu?|0=NV+`s!T<ve(@hOZ)I9bb*5WHQqy(QC`r;zGX<zmk*j@cmUU zhViWerB?%c7Q>CHtHrPXsc+9u5d!u{$Ay37hS0Rfq8>ZObC>G551#n~7&t?VlxnQM z{;&Ff9X(cgFx#K+T>ib-^XM>l@&UEK_T39N&M#Z5&|3ll2-rbK+eQ5`;fb54mi36R zj)$8@1_MeF*<HrE5vbSrnrh@gC~dYIc#gH1v`^s1HGfZ4ipjQ~uVtk7V6FIM3fj^v z1s*W)K?Z12L<Ber$^fA+Qm(Ttf92%pu;Ba!kc+71AWR&C??~&Us=h6dGL2HEPq1E( zZqs3CNwOWnsP|wAXjzgE%JVw>#-49n^;v<Ai?+Ok3qh2{ur2S62akj<?Mx#NwLmdd zz+*bY?H_GW&s&~~QOV`sA^p+pNw4ox0$)$T^bcyg0a{~qwk3U+n}Avi4k5-s7C0-N zYzo%+A|WuuEPh)|0fb>{U`KF=SaL&HVKUn!2g3%j_uxiYb`@|e*g<#gt#XL4+L;~- zN^Jo60u-O9YJSm9@k-=942K`5d%&0zA~>5nZqK6i@OKnsIuM-#=|?$M;Xm<|5TYrz z22>XFizppXC>Dn?hNNrl0ocnyKYyKzl`l526H_s=8ifr<wCkdoy?LnJg7gY>6WfAk zmg&Gc%gYs5C&!#nUSn|D`IXUg%G6;*KiuPuM+5}S16oVu;?@KL*dn(v+dxUA09dh% zw*<Tq*0L9ZE+IYuG9Hgki1aPMa|Ha4l@ory7d<#a5}mZzx2oScIaAuf5%`eGPWV)@ z@RAhCv7!iViM)Kj7*r4Dm-f|9qaz1{SL8XyYnOkGCpAEQHN!agyA`01$6LPi07{cs z(GG0=5V{dCj11Je0mx^XvxL|+;cI{pNpj&8kP$qSjB-y_5uvCSJF&w8CO0h}`csTF zt6xJlhPuIx4`CUgejsKoI)2$zTp2XDG&DK+JihXS3ak<i4|6j?C9Ov~0Q~lMdmsUw zj!lL33fc!2i{emH570Ctckrrsda_9HdvP2yaYR#zl+<rY64uJFsmfYDk%xJMAR^;Y zK=Gr!=%y|RWg>vyxQxrtz=^R>C@;72m^AjYO5N{!uk4x7{xTrG(s_vaR_KgmV|px< zN=?^I_AECc0J%bsE|`d((7v2wnKgVCPiFBgeMBM{d&vUmgD6Ce6?3!52qa&iz;Moc z4Q4Ez{TNs%v8xU>1IWD|)LYQCaA}?ynSKq}OFTQJa%P&I?@Oc3!0O6XN>tWkG1wmg zW7aFpjCPl1HRsMO*_8P!;r^Jp4uQ)Yg}jafu@bIwHy8?Hl3^vH99j+BJ&4Y~{?#tj zjous__tgCQ5aqFgZmQ>AbK&_Xao6t4ddi@HE%*^`ZI1R_NvK>9Q^4JJ`c6&8Pe$nD z0Ql-8{WUpT_S`0$;vlq=<Jh0np%F&7!|f<}Yy;Q^vU%k?Z0Z69fMgt_h3_DMQ;YZ? zo)PWBQfBqJk32(sRq>1w(RQN00wdGk(*gi!0prm87A!*jR021#u#<A#vuHF@u%R#z zAfhv{T@Q|a&opOqq2a#obMf_O*nX!H<A}+^4O<a1P`TB`SR?)s2{or<m@ui;LOU{; zZDjBLT%F56@`8A3v#YIO&r?DosZZ2ltdQ8Hd4C3zeGR2KpSD@i8Dhpw1YZcBfq+$A z2thnl!1e`S0cg9a5TX`5q{;cR8b)%YCA6hwp1k5M;lt;FHbXE)N79kTQm`F?^EJIG zP~Kxsj~alsKBOwp>aXPzS!Mx5i3=or&BWEOaV|vG@JR{@4cP<f)1UuSBp<jJq9kA) zY&Dbk?~Wg&0YfkmfboWSD=rmo{S;Yo?a`JdWa=-Ggl$D1&4?;0$i$$&@KM#zNPrZC z$4IS&r(l8b))QcchglSp={|vc34YIfgEe2=M$}%lEbUH}`zJ>uh>|g={iHJpza#b4 z^f`RQ9^?*SROd3-hUTpNt%Y<BS>hdd{(=`mtX`VY#KV(7W_pa)&w*a?LPvT+`-abc zp7<p|`tnx1JvlB8kDYd>9ZI-jUSC<^iSm6P$bkDb69xujYl1RO0e!_TVC{Ge0bBbO zXr`}5m4>za0VuZ?^a|3aS(^PlW|O1ejDLm}4KhYN8f68Cequ>7X4GT^f<<Ky=uV3< z=f~nC7Z4Fx6JU&NYH6Kq%6R~J7(xynpHHypQy{+m@hBRZxxA03i6I>(2l}2uJb6kP z!(-nloxcd%q2PUk520NoBDF*uJBm}!o;i&75c|9Z-qYu4KGlSt`29HCY`WNV&8@i{ zFN~&ZDxuTnh~cClZ4NNoB0_D~S3j<d;v>`em%2kOs{E%v7y$CN0z3xFHUh;%414C3 z@#k%nz9R0OZHpiC1_`?st3zFAP-B5BrA7S0w$wYcqjiQgfFbexuaV)O3F&~1=>YUB zCzotn?7rptwaLR1AJv0MZ2SouXwvMZ`#w9e`C(_2Gl_Sps|+8x#BsO&<<#>fq-174 zQ*_Eu)*}*ni@8O8(ht=uI&)k3mdPM{x~FYO(U|h;V9Vc-OtZPrwAS~fpV_Q~gpI8` z%VW01A6kmR&!#UkrOyO|7->gxt{jlv1M(U^{z}NwFZ3EF`J)T}y)@MSpcoq`+})Cy zj+PmOkpH=P)0~d7`ppmSWWMoL6FrJ$!{Epf&-ISLC-%IlijwE8{Gs@|L5Q_AQH9Qe z-6HVDgIaPA4mcAwD8nXxp1fUkACJb7hfVZ_U~&Zxxt8bl@QW+2?3Ias69#?NcNuh8 z-qaUJnQ-)P3%buw)!g&hBss6WyJ5-eczD$`XNeN?*jv(~&wtYMZXeqPv~};N%#JXK zRpfZaRi6!!AJslCKlm$fcckl$JQ`%##lZvmnti-OlRHuZBVEr{=!7yjx*jEC0I7Qm zM!PhgyCVAG){kFj^NMqR&0F~v5yDQrBK-(*Ouxl*JXvo@#U@eGFj%==AO65}^OxLo zdH{qD&e6L`HPX@ogOmC1{o|SY;;=)u1u3bqIrd5QJ%}uc{-Z$~M@vzKF)Ktylr(HI zx7@^Zm6lcMNbh*Azp{PvL-cA;-=I5y8)ee>!xaXiipA4a^x;eQiy^y$1%$4~Qa?}( z^QoLOr*n~a_}-u;dP7Iwm-McI`_IhoF5mQ>=B$BIeh?i2WAb=@)0w<e6ejgVT5Gh7 z4o!1D&J;JJ$3}%4*5ENSxt%A`t7C~LIgj_?1+i}<JPn@<h~(MI(q^>Rc-kFADR4#% zuF0e9*05&|U{wZBaF9%9*^TmW=<cCum-KYHE*kd}O0qx84LE?Xn+<&BuE5X{FGreB z0_IMxEH_yw`s36h>;jPCP5B;S(aum|D^e)b<p!dP@WZM@Y9Vys_{h2<4+4+zBnysj zALtg~T3~F+-4k$0JZ^vr`~=@zTO120#yB|0^jIJXM3aOwKvljx)na5Hm5ZmuNNapN zO>R;tTFWCG*e*Pq2J<674pvWEFz+$9<k-OPiuo3l3y~+}diFHeQviPCG!@F|xrA9w zh!w$%bwn_aDY~zgD|^QP0Uc?@E3(}F5_Q@GE%=a}x)W(3N&XaI*$g)@d>mR##bh>) zqAVwE{hb+2ku4jK93U?_G1B6In8J_uK4?1fFs7qWs6@%B7Dx&7QRu1U`O7h*CdDBh zqa(5cP{c17`wFo0nj88fTp|plKsGHD`vl{;DHtqRHqJa1%7BVxxmu>gup*yFOunZA zMBYo|t!PYveF^HDd6F2Rk55FRI`WD|u5%dMxEf$!@#@F1L<GjOOgYbnfCe9;&fZxD zPndzVlr!B&jB?#%=|3US*s!ICz=!CiBcJzz*bf?B5a<TS;Cg$%{193nSgFu$7shPc zL_#O|TUM*kKt^jTK=3S~QE~9hJM?=|`$G|Pg=AGsJrdfl0vI4RYC_QmCqe!X3(+&! z9<w))rFdxKYiJj!8`pP{r|N}N3&5A+FqoUa_63?2?E7R%q1Df7#Z6Qzqc^m6P%mI` zXBon*Aw~!qlUw*ygjWL(kCcIYw+vt;1QT8+q|_7IX{`QqKqM+`OjYKx$sBJy!-+h+ zpua+929{ZCiFOk(t`lPPA2W~pvG~C~q-$2L%ncJ1P|yX}iy!<naU}gT#&wdwC~J_H z*7<Psn`?tKQc{aE-E=LcYmE~N(%8>V>0?csok7@(v5YQez2_~bGYESm8<9K|mmS2N z=xc0!tamL03*ZO=AHpL5(nm&LlPttN>6AEzqb2tc`4F|w%wc`z?s@*z%Y03f!YtL; zeh>qK-+(LuFwQD$9IPB)0WDw&S7QUWE?I;S5f1T(Qul*-nt3o)MPc4iNf3jHnsu2P zbS`-Y0i0JFExuPx)XbbL%{I_R7SVd=<7#aEW$t<S<6biJC{z8Y!txOM>XsSAQ~Kn8 z0P;}sUOsvT+N-M)M|x6<>qQh}tPqWtW6#nGP$xy-_>0do?|!J<%rf|x0nyss^nFQh z!oq3J{LjgV0B8K9(JX@Zz4g_$pRwbLXV?(zHF$jCWrBy*$-9I1o-#`aD<H!I7e%zd zb>Wn$_}x`cf1P_8n9pV|-H{SRmz)W|OaHp`l8SvBv``%u&LC~7Y~$_t_r$IqJSu{+ z_=$ypT=1y-$EC$nKlHiIV!D8;nS1OCculGB;*e?1^)dvU7F(_gWQ5)rY&@7Tt0R1o zZrM*Q=h8^Ct5jSdBb9;<Q_#OBH1;$+cTeZZWI-5@s|F2NAMVU5z*0e(GYd0RoxkbH ztsS|oa6zkYb;J!EW0h}xuoZzQvnbAAZ{upq==9BiXhDEs6ITySzD*j`6wofNbM;}? zQ=wSRb+m=O@$ZSMKP6+pspDsJ9i~dNs{ysYG2u(yjOwzI%mc~_!xT}fq)vLUJi~xs z4*29)(Lo}em^7e8mS2=O&Hws(T`Qh_wDNje;CtGCp5GiOAhVWHbrps{%BU@8))Hq} zhsePCc`4HIjq6x{Mj3iImoy4^PAFsIK{I13=+a#JoVtzSl<VS1lQOsHJu#I5E$8S- z4kSl0Z#l46fB_rw0g*Nm&xUwE#nIwAyl(Y;ypv@J8#te9Pz5Tout6BT0a~m(sP-V7 zN47)``9tj;fJlPa93KQWU}aezZ)6BwLQadaxqiqEkM9%o!D+EOkiVqR07$36OwGaB z7OdfCX|(b0K7(vAd>kEeHos_wN<mNVP8F}k1I(mF*vNcrJ^`R{YIM=g#+r{YhQmyf zhpKNnj`^+l&F}a~k$7rWK$!nG-jJJOi8qW4*LbWU7E|?QlBgSL9d+OhA;+#FJX%HJ z`Gh&0OVyn}9;Gg+^ev!<mSRe>`&bbaZUV>=wttZqfv1GdxtTY3Yj6Jsm0tdO-WKwd z&mM8EwnPjR8lpeYuB?B*Q8*Q%;}#HZ`jqr}sAX!F{`9d?NvqoJRChw%-}V*XJ_p_d zA_bHVdg5vmp3o!TH|gamRbzP<c>+vWRdLfo+h1;9zP5%teoI^}sX&HBtB2(un>qZq zToM1n*QlZAx@@dyj7ai`e&;r@jk%%z8{Li_79z05<>1M2_Hi9oy&Y8Gz@}K6{J@r* z@hzS2Dt>dE?*gD2CZu~q*OC{zDsQ|ipFdgibrj4l{l8c`^SG$X_5BZqp;?(r`OR27 zF$CgvLUSQx<fx5<dWKDL0kOnmq-7u+9Ycn&PA)Yg14w8x#43uKTM91Z(L$CJ%9<u_ z410nMAnQ!O_cQ%o-#@;cG?@8(p66b!`?{{%pzzRbId&*90tgLxbfRgt?8)lciZ{LB zvXjh}dh=bM=cf(?CVL3M2I;1{cK8OfwqD^;?3haX6dK<DA=&oI1l)6mD3qMd`%k@H z*`!ncAILv0QKpS^e|enH_^v6Ux}Mh-6i?t>(&h{^MtC0yqC`clNBNV<yv*-nLQ{jH z_EV}^2+G^Liq^ciHrIpZJ_h7qSr-<x^hP9{)-W!^x3C|4i{Kn4(+R4ojGs?+XccPE zRcmgjJE!SneGbWMiTcOMB!hXuEBUTxKY=7(SXcc@SPOq}G@;M&)c2ml%Ntt#U?HjW zMS}(X<=$OV&B!Uu4sqLki;sbfQD=sxjXt>PPl;#nR5Z}u(dJNEn9vB^2xfE$yRKZI z#I&0ikZ25)2s)w^asHBr-x~-VqDMWXSimGi2tNpm8L5a$L}5iSHciS`bHv3ICYzcc zVZB6(jO!w8GHka$&^iM#Tt3P}8YrOJgY?!}#N9Y1Ae8BPD)k3Z{^r#~{Lolv=1>NU zxofS9c4LYM3CnD>%oZ9Hj(EU;tpL^N_R7>u6Hl2B1z^5R7@LL<uNH1FzzB4!5?nX2 z+u{KZ-sD~Ag#{tS(Xy5!hV+s3X`?<BZE)UE1NfTevEZu*`u6LowIyRbN^nKw{k4hE zA)7C;NBh`-lc^x%Gtd4tWhk<rsm@<R6#n-fPTiX*v08UR-zP{=MS&!i;<q8LJDnge zv{aV?uRb)=%8|ZWU<}+A5#!7!wQhpY@*-`$9_K7^erPA5NC@E4I%WeT4=)=CV7%^* zI?s6?u#pIq3{h}fnVCL%It=4QPf-A=ij+)@No#vQ`)L*I#};Eu``niA1S-nESF1${ zi~iE6peXWcLNd#2cCM#tvd#-?@vY|`9`3l+2`;<QGU1(h6kZS`5+OekjYFW*7}J1s zu-l3Wolea84DMrT8w3jozLTh{qda&Jv9F^=hSLy~^np<GUD6$g#=teR<cT8^<(Y$E zl3ZCZ@?s&wq|6ujj8>gkZa5}PbK+fvxC<L!M6Z0!FLXXW|I-QNsMOuU<{#MP7c8fC zz0!SCMsW$S5j%xDp(DZs+9{b=Qf<196h8tETe4_~JX+`T4xr)6R3b5fgCHGYfJkB} z_EVoq5P(`!Rv`BpInk}*dxfcTO~5vOC>{U?aAVo@*b$b<zkG81P<J0Ofx=!OgeM-A z*FEqumAhSf$+ZSPw1on+#Bg%+^}lbus<FJV$P0lFHtKfpO>$BS%QV@34X^I&^-)+; zW{ES2B49+XMU<T#mEf5rL`del@&LpK<^5qxA*X+@Yb&Mb#UJR`G>w`mspf~P_tZ^U z@@LH=<wy1}Yma;zV>NQVuB|L@#uFFutMJOaASc^PGZLq7-F3WN8@-i-XdztkV3PLR z^>&QSQyc?+sTvsX+1l3IW0Mjfz1k(s-gSu?LhQP(!iFq?2K6^N{cG1T?S&X)+$Ujj zC;N@QgHaBj^f$X)ft=GrUMd%;<oqdfo&@YV2J3V!#0|^%b}%d;rn=GBu38cXL<x1_ zFAEvXQPXkyb>C;F>TW%sWFMNk(PuCKI4wZ`N!qBYGcm@qp4HTCfH889L@RZlOFfk7 z(VpH3<+|8uypdc8QZOO9j-g}-=%fP1RYz7=5ir3I^;AYvu`S@I`J{Up%wq3NdMQAV zE|$R!4`;7I5G52>=efLfgVM^K%Q>bPVsPSk93?UU=oPk<!zEG5zrVx)8H$Bb!KqM^ zt2ZSR=#C$gi1Ne)kHojwPNC)h6)mtCI+xCrU^)^LC%F_y5+cmdSxw&BbRa<G8^uDx zcKewu*=!;@2HHtx;Qaniqi;F4SvGT{gzPi5S+tisJ<37pU)1T}RAJ&`z{DzPq7S1; zwVgt`7dFJ@w8Ntjm<$xS@ENu*2vVE(X8=g^v4p7wkTL3~HU`+oPA?>+RJwFc=I&=c z4`&^%A=f?${2SNA$gPa;z_2(Xfs`nEzI}XuV#$GVrRi|{8XQ_%^Q@QyXOw1T>M}<R z6_DZ$ytnDz@D)}B4bQ2ZY~HxUCdL1^R{!71Z3*WD==rW+4d6ylSG;2V{I_aaWwvWj zb*u0Ca$o2EDbeJQ5|c~aNLkH_QEOYKhQfU)J#iv1NE;Ma0S5+mfe6Lo*s{}_dGELw z7+cGoK0B!W{@SkWYaXu%Z$!1lvA3;gmihs9KA?@gQQbLTJPECgw#vRHwGX0HP{;`C z2k@j9Se(L`^lI5h#nuzn*>=fJZ}~)MG*uoPlv1U+Hel9B$K5NmrIqXHEsghoIC(Nh z6xG52aScuPF{Aw1sUG3xa2eeW_PdAQxbJGZXIx7Y-SQ));85vmvP3GdXg2{bBGAe+ zi;qZ=&TK9ud2QhBB3see320@SG;g&iv+I#kaUxD72F~i)-#jg{iV>YUZ>Q1DruWcw z4ommR-Wy|869bH>zXY*;+7#{6GS7|si@5|0(r|?GY;lgt^Kw2icu|Z78?x40#(SJ6 zJl5)Jmp&dz!emQ85zQ{4nX__oor(z6bY!@e#E*B&rl+dJGZwoQ2HwD*NubjQPw|&Y z$)tZVRbq7GUuI>n*f7hcpN$Icyh{xqBs!rF`vn^DBl9Hp4CEtlyy(bGb-uGFT*uhw zQ~ui-q9=>FQu~OQ*6FcZP+QujT)RBeA=&!XCl5w)U>}b#d^1$|HU<tQ*3pmXt2QO~ zf@(nHhB;O<->5!L#bMA7eX@HJHVNu{e{usBs%Tnf@WmQck?KFXExO)Pg$u$mbx(x9 zGZgOLNWO{qbgLJ<Dk}Ivzf4n;o@t&KCJOwCE++SHsg};&=p=FSqH#seE#j6+cB#v= zY3M8n4kJFE`*|1Wy5vsnj8Y(5OL=2q(gVyKp{roN6W<TaU{{#p{6K&iAXTPZl%t}c z2zC)>JWt$DZ+1@hE$<yFk^EH&`jAPTWTjbLQ{X`(j@3MYf?ZR`6nP{L?qBVQ0fnx% zH_Gl__e}!{;<uv}vin;Fz|jJz<%~%}IFg@5;buahV4gt$Z<fFw6TmUAKd2d}5K=#R zoB?i@J%^GpQ(zaw)&fzwnIbu=k-RI|7&*B0PzXzw_cl|~3hAym!xqKQ1=BvTXqn1~ zSOapd^M9y@SvCe{q@BV~?tDjGUHqoPd}2rlj1(?{<t4tba0&YV4oCfyy0{eCNj6U* zmoacO)p^lB4wQ)W*K%Y`kwM`w7-{tZ|FtY!{Mxhe^+w#HolS${zmk5+q3b$oIH!vR zvUVKomSZ?TipMtk9>Ya77hdPf!`tg=8tXF*-?q61CgJ9teq74qqVyHzO(>^RZyR4^ z(;>xy5eF6?xSvvZp_Ju14kk*<-4w3s{!NHNjy^EkEQ;@s&tZ+mF!c<viv#^Bk)Ke! zh2x&(MOx!$LMv!dGO&}APo#;(&Kg-yB;x|ceFSLALE-5!iw2IjE+)vLug;-#K1iGT zJjkH~=YY^{&p;SJgIn!7TFeL~eIg`ul#(JR<$7o#3_%)=zXg9V(aTcte@OJV0DM$; z^t^z3+TH{)T4w-B2)+~|^u*8AM34IZt|HxQ`~1w9O}M4$U%y*45qCbs7eHIJ**pF< zaDDmHhRoLvZ854oeb1;uC{va<ZJVFD;<QHDCofb1=bM!?2pk6Y(kI&{rcR04EKT~y z($_u8d!kydE{ZQ6yfOiKNt?cWg|u=L1=1bQAbn3|`--kHC8~~iJfX1os@-Zz^5CG{ ze2eO`r(#d{sevzO<794{4e#1+O7QLfOloX93n*Y-6LvK;B0&FJSCLJ5ws^Q=7`k2l z_f_@NgdCwaDr^4N>Wv&%?6q@e-Fc`j8?;GYVd$!ln`<}+TajvP{HOS)Giap_tmS>j zoIAhy^-1iiP*uM^scVYgmcZOFRNgwhQ<l{S6J58SDRy#rUl)7YCdDtH^S7aRo}str zf4hh8sYqFAIIYwEQ0%pMr|W~?LP1w+V*i$YV%I@&)0L*f0wnx3=TFH?Yw<}I1;De{ z1!I`ADjxl8{^VrT*1_3JTGfA~fMh2x7{5W2qwzj%pTvtBDv6%B1&DQ?%X6~_+gB*v z=C(dNjT{KSv0slCq1Av9AEE7u#7KiYUA$lvQzE#x6x5Y2R*t!b1arPw=sU+EDRI<7 z3<k#7Nr%6a^Y@?3gbu*jQ>LIuRfjJ}JUj8+xbRM@axhnm6wCVsX+j4!t4aby_pjfI z1_F|<pyuaF`&*G}M2?FX>8ieOu>=*vp_rh^@iPH=Ba@($)9NsQr<!uh$b}`4u~Q-t z!3PC#?!3UQ=}Ve%%b6+uBPP7C+TvZ_s+VfqmF?;$-ntZN<oGwB0Azp)`F3Hha$F-e z-6V<VIJI@IrIK*5N`!8RLV;}-*|&x<X!!LYn1}qWzSf^k`;bR^BI9p6Ddq^NtgEso z33)`$2fG=+=R(Qt00+4^e5o&BNkUor!?6~`Bgt;5ukZR77!Yc_`O2x0=O=ygq0!3@ z#u;7Qvr^e!-?~+qC@9GgQf)(R`40+1p!(6_<1a;wc;cx2BiSrs=I<4{M%NjM-64HT zCTT`nyhe|+-KF)$p@vNAhDvUps#e?T7t(UJcq`~;e3iq~1H!9OdEc+$o%}y`9?TE3 z9xLvXC?d$dwMDOlUGRe-z%(Q!NP6h!x+*u7ZsoLE7z6RYMtZt-<~%DJ@DS?ufs)f1 zZT7)mzoH5^w_p5%{&3@FFT{D=uIk^)dcINj9{iD9q&~`wWZOF2VTi0SWrYLO1@D#_ zCp}EFubcC0rc$x|DT#%SP@Z^im0%XD7*+8d#5*VEs2qmQa<r-r$eW59t`T=<ih)1F z*wESfLgGtU^}9&+3`|SS?TdI=ftL%NMN5bFj`Xb-crRpYer$fgl=0Cs^=GaPmOPXF z$4?bA>6~Rc>WqBU)3l@Mi|C7j9V)0LLC*s7c06ZZ_?kf8gzdy&QCh;aOuZ?T!b2o1 z#YEKsDg`OO-&Pcvvguk2Co%GM05Jcd8<?QYDCKw7pcN`)@CCOpcd#7GBtrKnhqfUU z=U9t~ZboXqNz6qXj!XzCj5i1tF=>#pgT^umExt%I!VWACTN432NOt9^FM)>AV$UCQ z&GyrP7><GEs=yk6b}sll*a<=k)5(2sl4zgXEWsggNvl9(gU7=3BthVW!-MLgH~)tb zzW^~ru<UYbIRZaD37Mnt!Ue>+Wj*e4lq}hS8SRLNcPM>=2oK8XaBxaVa|?*fYVre$ z#2Bn=xHo)Q28YlR!QOq%_{<kb;+As^YrVC*XgTrGbud<Ll#D4NC+_Jr8~1{(r;mKb zR7bL;H3Vn1V(5#)$e~P2o8?clZT7K_kT;aeQ4{pHEET&!1WQvbUQvBIBaZ$ge{9c{ zo{(31lRlUWq&h<Il?*gM>Fi)KbOB;w1QSO_^sn<0usFl}n2bfZV~~IQH~Fae@x_(} zFb4Mv{QoLp%7I#496E-mzgo18t*!5>44=d1EjW#Wj(Lv5fGFGNQ+9=ztI}a=5k3vs zOxrBib%6~5ZgAazfF4qlJf2;JFHp(JYQR6aDaFCONSBlN0*|FsX?lH;cqOJ>zg?+> z5Re8ul^TbQbYve6YP#ym+rmHDJ`{UXTLgo1MNRAT3eSfkg1kKyuVc;$ORU<5ig=@f zh@@IDnhI-?Knz@fNkO6(#b0L9O1UQMp$J5E7f+J|M3~v{$p@T9v(UoaUxZ`{1$a*J z8IEfnzW_U_%Nl~C1nn<Oe^tyzr7b4~lq4MFtNR%DR+E|P4i&IIZP>h_5^1_@uvZS3 zVEA6n_F#|0Q))ms$67b67$`x;z3*yJ_rH8hj>q=hqDF<6yh=8zJyU6Q4GUB4n;cL+ z4rHH`pWU#ZTe<#fs)F?vHL6d&Y}yUPr=5z%l^0@VhVSr(;Vr_Q3Kf|V(5T70Ca`4Z z4V_#doW#<DNnZ!P9aMB)QE&GaHkaFN%nQ?%wqc%|hISQEn{Qh85^`p|eojrw*G4l% zsl@$3y_sK8z{ZpbVSkqoUb-kO6<84>dYT(*mD5y4aW32Je|Gq0mVO5Q(*v7WaHjpm zeG6Xa9pwq;&x+U0^X*Rx`XZ=zid{sduc<CGzS!BcZLlZd@#uR>8?i|yFi0O8Y7y%9 z9IiJSPM*EN<MC>!@!PjIe|MCD+Hsz1&VUUgRfX&FrM>Yr%XBM#-uC*$b-TVG-FSP} zy^qp~L)l$%Ho6c-T+w?2XFdtrRZz)e^KH0o%CZ?k5t1EssGAEo^p)3p$-k!wZsDTu z-*FKbOmF*{=#n`skdV}vEBK4yFv>Z%m1a|oGG$Q$fz9Q)kJMxOf9LdBj&69B`gcwa zr%ttcZDC86R2N`OdndD2&|j;I<j)NHd+f5{W2$spMF>*$EcjS)Qb`XZCeEC}NtOj~ zQTrR6>~}&4l%~COs&9#)nTgb_9sEE=Bn|D~EB`jp>g1sw(C4j4UZpkd(l}Y_*|8ZH z^<}1ek@>#S*P>*4S&GxlzN3ia3Zlc27dXwF@-?hVcUUc%W(H0U1J}L0sD$B>-5~&B zm^WR}pg}T?TC|4pWIvJjQ|36vxl8GvyDPN)K(yu`DqLLG5N!TdNgJJFHpUA5T-$dH zZZ5hO5^d@H_YjQj<aT3<7ue|0G=<sOLypQImeO&ExvxZgRaT}!_6*RsRt|PU=)eO7 zLibL1RLQ<sl2xhm4+wS+D)X349WG)-OFaTJh}MX3x=$-|ud$rI0LRYuX3aj2f{_>d zh~-@_mP_4&l?xxj3!;Jdf3kJ+ktci2=C)|u`7Z+m`$plKhgylG;!4`leTBS0_eo%v zD@r7&Hgemjl`afa{Y1oJ*OGTM()1(tA??i<$AC)*@cI3VR~YC>e+ud8rcgwH8*pB- znB<YEafeSUraTg0e_sYdmRS#Tb8JYaSqdaW2Fd~R8TYBy@x{ux)}^bNLrrw~!LB_i z@7m+zA!q(+4jvL(lPPbky4_TX7Y24En*8SJhPWLD3WM!CXY6t8eCNcKFaMMzKNIq1 z{a}yNFG0V&oQxF)@iV?C;FGJSsEQA_{dRtcN|db?1NEO|ni^J*?FF<f)t$H|OOb|G zFH*XlxYpYeG@9e+Sdr&(6Ztd%U~g+qszBR$kmfTdKOAWI&+)WXYm^?J?n*W>G_aeP zRKstc>QRyqp~unu912z<&0knM4nrrLs=p8!0+^W0EY+=HH3sjH(pnNGCq?dL4I8E7 zQRSQzvwFLa>DXu)BjTZBI`*SM{v}Oeo&5Be>HwWl@K8yQa(I7y>yM-Zu@GxY$<RE9 z1Zytzl{fx-wtr%xLyH6axQ=}zJw8xADE2S5h5l8byFY@X1yu&R1I(r87lCtgy;fs7 z&F&5eB7Wq9^sT^n*oR4D7Ez+k=(XR3hAqW9RX$Kc2cjaS3%5uo$;gIcf8aw6ce=XR zvKXKti*&4XHdm#M+9txOklA~*eywkN$x{KyT!TC<R1Zw?7*ho(+vUu;_VQln;itLI zE9__(Eu6O{(<ft<Ox9mCvQeSLboh8|d3{ci4M}p^<PD%3{bTjE4wv|c*470ijFwb& zd#k#q=Q#>drei?$=Aa0^hAvgx=uhn}aFIeR&NKob&2K1L!Rdo$$s~9(2G~V_jey*! z7R7O-g{3ACcPP=ygFb3%^IxEeY8gusOVla0h#^FQ9RU>H-@>Go#-P?4c&h5)=^`1_ zS_`4@L8O(aT=;_#f_<}H8Yvhzxsxp4xXWy_V*O}GRK9cTfqEFu=oCa${-Gd_5zRo0 z-*ffao2CZ)or?KmgsM_R!(wKGJSW0VWmDQnOXHtXrGEOtCU%6hWht>rz;y}kE=PC| zt{p|<QHig4JPU`kXnNdCje}bTKS?NMrnUf&F<X&bz{p#NN~Eq@*%K}}5784Gm|RSS z_d2r-FEk4U9|}M@YC@j=7NIJ}cMtzF%M4FAwFzI_)wh94MR*DHFR{kupCDJuI4OOJ z#p(lwp=&H3p{rMX3rNLM-H%(M9glx>)%H?N+Bw~4qgH$DZDJvvV!`V_FwVep-Bjn$ zT3MQoKFtJsh0}KmYt2wG*1}^Ns3MpzjBlDlPleuYY9~Ar`nbaBSV1YI$BazHjCo2Y zf6(OE*XFUyts`5dZggKl;(@=CHd0pQg>4n&F_qBu2|N1v01pS$4=x&xa~`O^a1LGV z8JfCjFzOQwkINrwnd5a?bzk_rNmu)*%&0D1v>Pr$$h40NJG(n;tFB6PbIq?~DW)2` z3#*o72UZsLe-`jf`}C8BeyG7k_d9c7Opoqw>1_@Bysq!vYtP&dCRul7ig)4BmZg1k z|1iz`QTV@1#iAPB9kd-ovdsoBB4n1s&-*z$xM6P$yc+U$-L<Dp%kf!Qv3%Q4JC{w| zVy1F|92}Xae{tx&OVv>!Z!U2(4JAF;Jf_I>)pn%&yi`k-Tk^BRY~i5jyJCMwUAa@> z$&By*h_Nqf{OF9je11}G-=WdnM;$pH6imuTd6Yt16iq-Ml!@L?JmfYh@T)HMGw%)F zR$BMY*DB3Nt-mNJ?9E^2O*y{W@#L9#56{DvaG>8YpZxY#*vw>;;Q)$9bnyS{Zux5R z_2MQTc8th84O#!z|F-khTF%qB-^i1P)+iQhwCUJPFw{^vbh!4%zxA)f)=b4WbM-(* zgPtAVWmjDV=y6e0tYLlHRfAEr^bs7h>LR-j?p|xcSl!Y9t#<nRNCYNd^NJL*?YJ&` zK=#V1o^iD{+{o&ai%IW&7w9s&D>GvkWZ9@i6IT{?cB~}1AM<ijaxGd%IfJvB3+NSk z6HAmmiQ~e<dK{9GZeB{mujFELmxCxOBWe5-<z91~H9G|axU6+n`dk-C={-@-$wpuE z?=;<BbI|QT1WFKX8zvx3$i(Pky5g+ZZz^cG%G4CEh4otV9qvx=&(iSz$g3g6{w2eA z)T`fyyp0f=FcbI>=afZB3*<wuPFu_z*I1!_m^SKFhfbOuENLUHq)@H-L{~v!DKGur z>sIOKV>Bp?ASoZNnSYiuuxCvb-0=@Hb}7V?C5)0X?#PGEb~$1e*(3l=$%FR>W>ai5 zzx4=^HW2cv6E!wpCvm)Bb_m@pAJLfNHOGO-&-VvnDQfh)<vVAfM7DjIkaKkOM!q6< z5~5R4*uT2cE-u5^>aE4Ks6fY7hTFDdmo)21+q76ZAnfDm-V&I18GS7dy?SHCzT;NT z9kT=8XjQq+ljaUvQhyX>C%*^W<C2c~_g=Qx3E(MhM2ot%xKXZf!ly_))>Ssii!iwh zhzVXW7Hzbh+>hpu-M_;s>r?R$;XJSQB@Sh)hp+gl^<n3%<eHg6rfW2q8aAk4)E%P~ z(U+U*mb}Ku1XC}tCRU@Il6I@i!7F|`E$XwCPuA-cj>kG%A&xU4JXnyYv*iCD6N6rI zdAJ1c8Xc3egmNv5q5y=QHh&nN$ygavUMJ(X{tr}L7(P>&GYWD2C2OleV4CTzBbcQ| zY&Ev#c~yPbF?g}<!qcIcja6(Sq+(dkdcu>#irU{x`n_+L;e5e49t5}n{#*(E<s1I; zxjUH1;tql10Sbz=kec*XF{fp<)AI{K`&r^*k>R#BYfbBUlz20l%>i8L<NPRU9!%aj z;#@>+XFrf`>N@C{zD4lb3f)p<WGx&fM^7iEV=N)vN_ZF3wJdE%F%79|j7So>kZnni zG|1)Vc`Mq}jIDL|7;uX^z8LgsIm15?XkYXlf=C0p2C&7S5wGDYal>WZ?$KLqBa7#d z*}8t+!|6PT@#)CcOr0vB*okoOivWH#pEvC}A%nK%@M&iP5RF4QJ%#|iNGnJTu)G2C z6ByGEs2MA{OSo(GU9NL@4i3pHMM29j@_xYfkV~4_mta>|77MTog852QIrovFGIy8K zc{JN5sJ*AjYJABmoEOcWCc6ERC`%NmVusF<r1^fUm8o<|g9V$!9azn)!mq{&KV}%& zi_njB+_DzPd3${>#yDyQ+HF~G4C!<0Eo}#G9*|rZP=w#??p3;_*b0sbKm``~#3?0r z8*yhoSvZ32e?c+G?}&UY(j<>Gh4el<wxiet2rjn&`08n!bo1(UBSo!BV{c$w<;R#& zogV-dO4g8C!qABV2J@eO;1H6vu|hca*fK>)#u*YTbkG<oQ`jkPd>w%?urHyj_)p0% z&BK<ekazPfZ=c1YejYldv|%dGogxwHMBLDOsOLK%wuoFa$)Rn^4^Oo>!aN)w1#egA z{`+p<JF7S`wv6&CsKFX)UvKi2l{?VBER@~lXr`)re$C-G2RNF3R!9@AWJ4ENRtcp@ z{8^O!fHakXidw`YZB+!VMIK$0CSY7KW2LU!&iB%(QJ%R-;@tJUF>H&C0@ED%LyQrp z9(p4thdPqUvIo79<2^aIO-ELpXOk`K4kJV<$MHRT{5AeI<1IQQZ^^*+>u>)l`T5Ev zSk^bq%$2Mm2f>I7ac*OURf{75u;;;-(HEnwJjTWtM?3OBYu)?D;V})!Ua&H<MAtB* zWt~l7&9vw~DixpFS@XIXXNg+wGJI5redp@t$TjmYWEL^3JbFRu{B3@k&y)|48Xb1c zPnjM3b%<4QL!YJ+-eCS_{pDK}KbzPETc@(weR-bRK0i!)07ob$E2g^7>`ynU-!G>N zhNL0Q{nlYNy+FU~m7uHK@qZOV0btdH-npM68PFE-a^<5uqdXTr(pjA>^^$s=`V=h) zBACIF$1xL`PvHJ&DtY3u(79u*cf-;1r?1S^)kqoq_9mq~>lh64+o9R|=4cD{nDnLn zY0img$>X(er(Cjo06^T}HNQ5ccZ%Ec4=PB^(j;p$<j2)Twvqh{E;JM&h%|1|oQ;|m z_^b9N`;3Sr-^2N)by&0N@R#F#o!%a<w2oRw9nDZKSmK$5kyD8@q3NhyTn@QX<L)x% zgL#t~LU}EUwE9@g_f^ZfCUcWqrg~@*00C7B9KO_B^s+R{tNql+Sxqxk4j{>U=Z~Iv zkG!aK8dH1*E_0H7$qP<7{p$JlL88c`jTo8Fh#|ashas2aCR%e%Z2kvyfSaEBlDSAE ze`OC}e;~g^B9>}l^`7QoV3Ui8Zn;F1gtDV`j5HZ#@ypF86LztuFJtG(9~6TF4#4+A z<JH55j}>OZEl1qkcS-04;)yf&Rfz&J0HuukWT~&hX}pim&1T*FZiS*~s4HzaS>6{$ zZvbBJ-V&EoW!-Ig@?gQp)3%9({-LjYi=C_@_y7VG&}4u_W0G;~w3qqhL7nn#ZV#=K zda}M~NvzrZvz%m6FX&OgJL>i{r|*BwKG=TatBi5h6IA^`m;oSEup8|0A~?8jKj-rx z$ryyaYCPbs5dt3a#Gw)o+;SXRaqiscrtlDZKy`lkUJX^}Qa4#<4+wIG*lJw@V8SFq z%x7G99OxH27RT=XQ?h{2a?g*tF~n{E=S(g%Cs_A-N?e8Eo;9)uMT=wa!XTG*)GmBT zaTsXXjh-5_@qMx7tm#Ok=gV5Nv%|p5Qu7PC{;%~D))YOT#WJOf0@PmLANAXgcA4V} zy{YhipmT#_rPuiljbb79CE3dgL$KIO1SU!>Xxmd6YN@>b9pjMDdqB<ddKH#|n7Iit zKtuH&_)enE&tE|Z;`XKZ(RegZ5(@;(A?;>mf0GXb3|2vluHPRPC!aqtnDRit_f(3U zxmY+~B5PDv31S$rgbB10f}jWHLnKH1NQ`=Ed?w9O-56Y3Fw3liI)|^Xif^J9`Nmbe zRrt*VE%Fpw&|1tOVp-b+1bNwFRD--9YXF^h=veV`5P%qVms*q}VtweQ6bjZrCqigG z7shi5r`1j}b{8nI=*DZ1&I#oubPR^cQo*?*^WitXwXDl^1b^3QMeGq_yE7R&Sq}O{ zXKqnlk?&tjI9&cVDruEWb$G-TFjKO?pbUH0!e589p;%EzBM6-$7##9V1w9N|ROyyb zn#~w3QOtaq)(u<Ix<ia#sw*9}LbnMN#gG`zU5t^m2#rD{BZ2)jkSFVkSBi14SOdXE z9kzl<bBb4be2c}8@KUgo$a&<@30VdeUUViyxOi-r!!D&jfU&|tTD)H#^0HiSjG;xG z@A6iI>Tmrm)w8I1YTZQ`e)|@$^Aa~6oqaCSS7QYaY%o~jWAWw%uwp{hbVN`c1Ou;_ zWeOM`r#M--dKeRdmt*7$HA}Hz+)rkPequgB9ptVGzircb%et$W_LDK4;2%tmFOmv= zOg>eP8k>~%Sav+J(-*MZxxMx0%VO*=WW`oOOO4I1R9~p}R9ct}2b12oEfzAhk=N4> zKR>`oAD>xPmkr;IYGR~=-dZ^CqhvxgQ5AlRZ6l0>6_Bcv7eW5GoGu$^T3|C!;JwNq zPAi6FZ>l11iqi)FQGI;;O|$n%CP2*Qn4Zs|VqFu!H)hlJm3K=qX^GPwpLNtxdu@A6 z2w<5d(9+R#cI=UD-{k?sdA0cT?we1)85#>x!oV)XboP|yvKL_I<Tm#WDG67vOnCHS ze1C6Dw2nu8%KeW2wW#^pfxUvhx@pabfwkp7pnUcyOz4dv2HS1(jhpY<KF6XD7X$S2 zip|MJ`YNNpbJa=8fP+TPRqzzgh5!8EN^gg=E=`kp^qFGKZ)Ja&Cz?A}aekui?l>mP z7k7PsA8Uh8az=vMZhQCwbK#mmh3`9k^F)7-j-cJ;m7xNGW=F@vP&%Q_6;U(lTF$Wi zri*`jFsiYVdgFL@Sws8R>HDVm4MVG0X+llua8DO&7yicYH(QL!$^^r%o(ajyJ91!L zo%^oY*_zm~SvvQ9S%f~HcZYk<n@j_h_C1~1KIFFrBdpbK5UQqoGcxAXuj->X@>A*L zb`VUJY%V2usFsR2Qn18eQC$y{nQI3NPMgnAq}$<{hzqA_Ai>;sbh3GquwNfGPwI_$ zS`?VV9H1qO0}P2%fX=t9&%f%n*X6D2TsC9^u;6+l!DU}?ur(_Ds?~0KC^Q=&53Ohg zj`QWaracEYAFA*gf65o@d(qTpnXHhIfij4QldZz)xX+N5J}VplWxd#_yH8@TefWKI z+Tj<C%|gLrzj65J2f|K-I5uCJO+y#^0wDtjbPHT{tM#%P;xea@|5gjDsIpPmPNHB! zCBOW?NaYAYzL)91GEqA!?}Lyo2-1KY@W|?Jv!DX7Rd{6`dlVif)hyy~8||h!qyDrT z8^A^U=%h6r0`IOKw^hLuJJ*6vBqP^KlnTa{c>c{aoJzomgrTCZG*a03`B*v4L?~Lc znC;+X#8mgsU6l{BeVv@mi@tX#CG~#Z(#?^JpRA5c`YF|71LCdmUK5?T>Usa6l5ZX` z4o!c^Wt)ErKH8<D@Gy`cr@BwIp|zW``M-rm+qfSxGzAVL<<dh2hc?%xjSln){UgMx zkv9YXW-$-yNov-QpBnwmQsLBSHmQ191mv`~_e++4KPznI7>3mbes6By0U8*CH2>s3 zYE3~=H6H@e3j6Z3vtQ8C{Ix0KU=+k+aRQ8t60Ry-+(tq}Ii$kv#4V3ogvmo@gve+d z8$2c<*B7YcLC2OcVoaV05=UD0mZ(wU%`^qSA@bO=<^<fQL>FB7Zqb6#qOk;W+XNg9 z<?$vR^Mei$4)Ffi(Xvv_61;E(xXcnwOPxw_gsG>C#E7WC&0B}D9PFG{nQ7Qp0IEGG zglU(AtAI6eC>`3io4%nxQF7Ceu}Rn`tznZ89bPF7RU@w;1Fu(+v7TjlNfZ0TDT<T; zQ+f*pvyo97WAj^9R8tvLz_8V-x{8cjs3b9fmZ=uJQaN-^=j{N)oKpi%xk|HLBXbmz z_cL%ee5vR==qU+X@odiUDA0{|^M>M#qpvI(NqPmz5{ygE=tsydre})X60~!dG!WKx ze0e)xCQlwEsfg(MH_2H&fSn&H9l|y^v`DfJY~C3?w3i3kB8067b|gqGcvAYIE{yh} zF#>~<JsuS3Mx6q&)b@_`Z?YH_>04Xi6@mB9Ojk10fz8Y0L;w;Qx;#}l;0DKzTXab) zTH}aVSHdv##Vwg#t_qJr$PHE)$^X^B9?vOSW_G9A9o<mO$rrM)uLx6=mH!ivP6x<O zPk0pq3p)plL|<0(7WtRC$ZRy~!A%RS!>c|q2h;jyBy1wu5lWrrAjrXlSRA-}8L(~? zB%DYI*<O&HT16;2B5w@n5-eWzWD05DhH6Pa-x_MeW@&h_otLcxINW(YKDz-EN1wiI z=kToPi%`VH%JX8TE^tB0cZ0j}rEL$}6P{rLIF#>5a0Yf>_vOR+AMBcP{qJjw-k*PO zEcR}bv}JejX7TXa<w0b4NvJ6Ebf<sc;QzVy(Mw;me<Z$jhk1O<)eyX@0~gw#RwF=I zE{-?Tz!?T$;r}Y@s=NOF_sqV<S$tv^63HHDa{iQjxilL>sW2m~?$<W1On&xD7BBeo zx46bli*`1iV7vIvsp$JC?`_LoyyN*wiyO;5TIZU_wOkDnE3e3sKW20e9}*F0Y>_Z( z|1ruoW>R6CtgoBn&y+mf*gk!gZcX2?>kD;D_m7~EY0A{Dy6Q@ig|^q!h^9ifvMhB{ zRYu&rNnDxL!uPQ^suV-vT=l8XML|`g+S=$d^FXJ~(2jD`Kv(i9-x`m?GsOZ){xuZU z(z)zSJ{gO{<XK9wzf|^v<xe)aWtULhpU-$IrX~+{duP3S5xyDR#r>LJfGw4P2^po? zlZ>t6`<PaFuaw-8r!?GN6cLSK6foJG%I2w@grzHbt9Tq^<36!RjgLo<>)d8O<$@sn zuBl8QFzzqVARE(pJ09hY7W)A?&KHA2^0&L1!^Ge)AVIWn8rd}3Fp7a-46uI9xbxn? z!PqIcsjv0U0@^z=+H211cAnb0+s*^m7X&#bY-G5&2Ut+!{sQM>wY(Fin6qfh_*Sxq zX)g@6#8(-i2bH?VVf=|5D^<~833pjyA579P{*uA)*TOPybr&<9Qg;n2ZQy~III@v5 z_64{Urn4DzFU(@Ce?z4>zC_tKT<n@me78T5)z7klf>Glz#OWeIzzL~aQGD8&>=)Av zj~w(&{3^viD!7t@8+l5aIPOzw=Y#2#^O1!`UJDIJCwFs7WkMn_&7<J>D~Mo)6(DVG zV$kVMw0acC#ulBT>vqH^qZg0&AEl*C6<~(kjx)Nfb(n!tkiP?7Bn*h%&+O(yj92I7 zh6N4N3n5(!WKOEGS#UlLxe`%x(jyAm${Hm8(g<`zbk$YY7-!3-7mR+P$o9|;`%ubQ z**!%=?flX7MNMn(JDBbte;?k65c3|?7cH=p{k+3*kZ1_6<UV1`PE`n|+g-l@Q@KOD zgJ9jS2D<*NjT*ZtGipi2XUQkje7>S7S-1a`gd63SxPLI|e=IwtbiqNfHByC#8%nVx z$GJ*6dNzYozbkRdH9)<kJ^hQ>{XEM%g*gllORCeq0pEBG>z$jyhVh028S~|arMEJk zh8im}fpRbmGxyX`CPQeWyM##`j5}NQW(tc<e<q#tEAb02kc7g>siFsQKecrwVbffo z5Cq@jqCQ;hCw8n--FSj+00?l?1taSte~XK6tgD5Mg9q<zv6zgqg1O5~9R|%#64^~l zo)B(n^SIEdo1hufQUI}0@#uUckj6>{kkM*5%9ZO66N-9v-4zkOXb+Wkg#vXYiXvrk zFh!ag-Z1=yZ-{Tu+N|f3Xe@-Vz(Eld1DA<Grh>#ScpzeLd5PM*DBFuQu+btycMfcP ztB;j3<P6ChqQCn8qK>t3h<D)5Om|NxHyU(WN3h2oiN$oxka%uA*QDnqrmAsV7e3m7 zE5#ZPI!-7eJtz%4eqtJhknAEu(DtDV31zv2MH106f!ZcUe7;rGbS+}v`81rJFpeZp ztq=+d5R0U(jITnI7J|<nABS2E`Zw^w1}ae~%xO0F=ogI5q&yF1tvW64>OmmBIf>7! z!1|~uYXZ9Z57T`O7Nm*z2M-lg){wnWG{AP&zlG`nTTx#*C)1~2%-%|IlG`Y#KKe_? z=;d1n1w)Nis#=0;6I|uXbcHx$Gaq6&R_dNW?<3ASTZwtYx*R$}i{^zwebE8M0&6|{ z^H|eOG$~kZ$+HrWTwi*FOfr7Gc>ZD}Jh`)2DweGa6Uo%Qjs6}5sj{9AVn;ktZ}(ek z?m#@k({ch-Ic8K2maOT0uI1zB9-seG`&IYvZ>ZrzGZHG-Q|y)X?S5>n|4=7$w2-aV zz5g)Z11F9-{M4k=kGJ;q$p-&<af;%<zS@YO{N*b1o65l(mWCf1tz+NbDAUch&#x9h zn<#WU{^Jj+!JFT>`uXc6@@%Y)Zy>XNFTPsg@o_G!T*}2ewciz;lEX<CG7qsy<_V#^ zDeGO&pSR6Cm+<pM{*4T9wTnpp$f*!bfDxwpEM2~Jb$!>|-0y1~0b@5#UN?Va)gK?X z=Tv2iA_uRXcNBs>*&nrbd4cY}Wl^Tjy<lMybT&tJfBgCPW@kCo^+Jv~oAJ-e4OCU) zT5&{5pXH7-Bp6N}el~1}a6DEyn-}IjS-+b@c`#<<3bxMyT&-oum<kN#^25ZHXl@vR z2m}8xr~!yMQaAdaPv{NfC7;+Fs4dHV$EEnuXLjCL1&=*_Ui+Vxs0P#SGJ4G`|GwQH zL1bBu(&+JtYYy=OTx!b-```43JHDxnJ3nRZY8>wFiHG#3WM$8OgDR?99pAVH_XQRT zKN!gO+*$9j;%Ujd9S?qEq6)1t=ZVM729MoX)|l!-u2$rn2ArSgcnqFZ-mf>_aG`OU zO1h*!ZRr-%ue7PJa(Unxcx#gTnqTQ-9Ho#6e-dz$bmT+qb|R@X%DqC#U2+s4#Xvl6 zaa+bvSkd2M1vc!uYZ&vbY*nPGd-!#h0U}PF=Q<0m_|%y<GbwfMk;u7$6EOo3qOQq_ z{o;_5$I=e#sG!&pfifQe;GGHjH+_6JQ1UttT=VUKUrc`5lEx5~{0XiATNE!ZDKmj8 z&UX4fymv#zaxQ|8Wt1!KJ0DK6l!%5RZY+0u5-`7F2-LA)gBal)9>XY%F-hVGGPS$L zTi-XCq2<QsPTNMF>jQ#HAo4PGrd}V)cNryy7!-n-VsyE#5fe!J&?Gwx46}Wi`2~r$ zRF`ZKq_rP=h(C~%FtiZYFxM(E;5#vz0<l;rF}5VhgvzeaZNEegM8^7thTBdPB-y^o z?B&-XQ3DP$8fOELkIy++RKXxjq#39vRCe-}xPD}6GBPYy*b&eL8nWOf$>G9Ntw7+t zudWv|_H>Tu(iQ97cd%}%;4W0Tp)Ws{wS1Sff3q3pV*lDT?-tp0J9L$oX)<4Kdt5Yh z5f)_GZqCnxQ!e7bw}rg=H`C9V=Aif@&M{s8!Kem|%>U=q@tVajD!k(k)sTBj<Q-TT z<$^mnwe9d}nxUv$VIkm4<wFr^oBl@6LU3NEq7w^9g{puIk(Ri66^dmu>sp!hL9~rR z41%)2!$B<m3;6tld18uv5U`5oy#IZvzDQ|lUYd@Kga3(?=M{m1;SB@N!xJe$j_BP^ zCUQQZ<^X90P_By=P9*dpVd=ro5*i&!AaQI(|CTux^l=78fzZI>A#ghLSBT}5;S4Lp zAe@mC&LC`liWhwplE<+KY}mIXq4cJ{6g(QAt>TejaFb?J4*4lyEY4!E@?90q?7=I* z5~Aue)VOIQJ#Gs5R0~4}C28@(<~K<ho((8iEj>jM_=M{`*AO_@NRgI2!@K`?0DV#i z^j1tEa4<{}ZfHCGX)vX6+!?+W=q{st@I^%6=9F93+xio4Lb1$kN+<)LK-b|NrySbL zKG&_OnP6J3qcKfYw>oMBs6&K27JsdAMPCyJbZpKRRq%o_rkf%;5(98I9^3?yufxp6 zNeLCfqhM2tl<@$zP#9oAWp3B_jAkR&P|4@b4+4f4&J;S@<^n+tVo=EIU=3^T8TIjR zT=@6f#iU<$Uo>8j-09#$l4043T`2KIXEf_4p-H$OpxZS-;^#{TSf{dQP_S|48ce1o z)NU|<G)v4oEk7w4r~H^MJfxc;I<%@{H5PtUSf_Y`VAnolVA)Lb6pr3Utu|=()N2%E z>^FVU9Y%UBK;#ZV<qdos63<BjKyI>+Qtt&4@mf`i{1cB-WRG`+f#*4%Ot=x!$z@?B z4XXn-|Cj#l|ITu{^u~%GqgKn*ApJb5>e?gw%+lyD-}<!RT!i|=Ls?RW`%!al--RD1 z@J#;G_dXoTFKjvTZ@=VOs`swk#!05!*sM!G`Tc7YRTxDh?Rf9V=4WlE9LtQowQ`%U z{Az%m3_E|>7SQ`#;Bu;?D)%q+g~t~bCffyE-QA?QJfOZY`NRH2l%^4WP7FS{bH4p% zJQe@_+eWG{d>3~nBA@_7Ux<RpTj{29y>Rd4`$aeYEi^?Z>ZaWI_XOYmFproIm}E## zO`^NnV}K<c6_j~zU|7u}J^qt3%1*ez#pV_#Jz69CdV2RA(a-6-e^pGmbj$4G<&hf9 zts)D57he;dSNUx>$~YCX1`EwzD;j@&-EE*G>c!t>)4y?TeYa!!5-FDamOmqr%G##< zb7_b$YY(3Avi~T*+fUy4RvOnn_W`!in#-j>7ryw(tU|Z;>t&ai?4_7Hr`*jvFK)0e zrgv~Vhv!jO#xQRdb=%Fzk_X!wAgvjW&JMhl>e?6h{>d0)h3rglF=N`=eLJ+*=fv28 zV~{=v-7l7YTUHGEGnZp&p{mHRll-2q=kL0gzrb>NoB{@{1$V<VQ>?tP8%`_`0vNf| zSj0d)gw!N4CFc-s8agMIBbLL50wata2gMIU;6A2S+n)yPT}Hv$P-PCbikNQ<I6pon z_zfCP+AP63Pi5qbJOHp_n9?(i>iut(EeO#Le-YW8?f=ZjXKTjB@jh1fX#rVB(^Zk- zErT48h~CevRxK_PC<Nc_V~gcVjbb5jIivTJM6N)f*X$9^jFx<h{Cs?2cZ3)DA;cqF zLa>#&K{Oi;0!u&k3Q?>j%qVA1)KI}FM~(ZMX!f|mrSt>V1$IPmeSQLsvy<G*Yw?Vy zzC*9BeCrV!=uCp$XOsO+!A?t79n26=8I8Z&zT@NB7vG)%z^c<X`mP^gxU)!oDSc1N zxDOPbhA6wSie(R$eBaHYJZw=MQdTa%ZrTX_PV1JH^}!zepfl5T%KT-*{^jInt#g~P z{FJG@e{vH!TouVC!S(KI9o*(Ro(Oi8dA80q@EMYlaFhhxNjkg1L&rP~d@zJQ`oR1N zkGH0nlEUB%9M@bvRoV~xv~bV5(3m&Q>6H8(77{sz+@E8bdE(>tu8F#9=<iPcr?wY; zOIJDhId4ix&x7s?_q)_@fpA_0*S_5Q=F5(hE`+0pICn{bKt#mHF{@~0sM3~31YfJa z=DoY=yEU?N0ahNEo(>koamE^s$Qb=VdrFOcoiNkPGiJhn-`9K=7_nGj2r3_bkJ<^V zJ=;N6pWxyu+NJEMKr3@lcqL>H>1R+dag6Y@8j8Z-)J#nGVf7X$u_TbWgvBr!uoB5c z_#dVR<-Ran7mV^%Ah5=z5DEh5>MVNEFs1H$OYfs}Za1Wjpz7H3kS`J;MsOvf5@vA5 zOUcpphC={I66@m8L#S?xK!>R;rKj|$lz!@=D0Q<V{Gk*jN@%q!myk2QW9vK}*nnFa ztOSoSMGMCA`=^0ds%_d^Wx{_Wv#Xxp4t>?fdMlQV)=@SV5-J5XZlFyIUZwT5SM$(l z4KHO=lv#Y-ENvA28O3a~NXA<j(kV;}?14z%(_FM-s>isvko!bm#40IZ3$fZ^tOCt5 zv>4oD95u)?nCK;W{3L%<Sn@1sy%FDkSjHX)DPqUgSj=9T6g(K9lEA*H3pzR@jVhfI zaV;Vhyh|mbT@MQ9k8tY{fPa!rye)rI9HygnY@~tsP^nC{=;)l=T~A2XbnzRz1ZTLb zoc!JBPw6jJqnoA(D6gZM!=?=}W!n*+umKW^f0=cBj-GPp576O!x`#344Y$qYMe0A~ zuiW(_v3&h%#&$k#2tKc80Ir#)9&y`4MQ(lXg2TXtqYuf@jyfJP5f%pH&to{z6<YWb zxB5o^)O+8v#<6mX$HgWiJgn5^@wF#f3eT9cwtk;wJ}>)iowDcOh463OTBn@M+1K}P z^^8?<-e(`rS3QEfF<s_%MRxs9iOu@cH6DX)Jo1VfnWw^$hyS<Qq`t>B?{<uNP#$I* ze~odXfF}+{mAgz{nzFm9aqD@;u<a`YjH;v)rX(gVbo1`Hro$dI92dS0m_2Izv5B`5 zmh;x&b!7|g$cca4`1ec`g6V=09t&aecwg83vV{8{xbSYd;EJ3{3^2dBe6`0yS<1@# zYBM#?vbMvzx_W+V4Au}%Gd7MnGPUa$vNdas<#{uRc-r%@OwJuMj5_jS@>u!k_O{m) zb1FUSoU;PEj^$05x?-nCE5={zFLE{<b-I+HSvR6m$8`Su;4AtTlY!Ec27F!lqmVs! zx9;)SGgSU2-0e+{{pd=reyZ`lu-O9&OnmWb?-v#?HtIvJF*yQ|?{8vKpl8Y9auNmq zyFGCCjv0?L2ex!x%Z)LQrZ^~Fbn25^9$sOO-wp8`$s)nKE8Qx0Ezjt9?crBcrwy6h zm}8q$9nN*WqmAEgD_ZtT34?mFU24+#XCatm;~s!(igT{{x-cW;3OPxlf3MemF~{tn zS$au1z5Tz!=+Jz63SevLsf&)MjT|S3OGuK!i`H$fFORD^ls94fvoXbXNDzpn>LRDG zU-ve6ZZtNZm>($Ddlx|7G8#Be)uU&Wo*03_7XakJxGkRUj&NzJVuHf?7Gl?h`>;og z<pNJpy2X7#p|E_iSSsTtc$iA_3!#y6yWyiPV7#bbeL$C*t!UYMK$%fR=4dxcyqx63 zyj&s@FjV-h<$E47rO&zZ4<Fj9kYuM<DL6%kHY`(<rt{v3DMq4TuiyR$yTJ=w32c7g z8b-yUNQIsCJr_I{!z<KwR_o2~tGP=ubINUL<nWtevg(T4UJDE3Qc%qDfR6|=#ISje zStMk=tdskOmn%HjG8U>d`d<BZRkWVW$XtP7zw$%VUB8Q~;Nr>$3hQov`h)*i{o=P@ z!~vwPN`Fm2d>+kHqa*xs1`3Fyl`X3de?i{*U$?&tyI+8B`@^fo_q7B)$42Vh4>Jh~ zeoQE)Hf!Jtftd$dg-Nq=L@${+qCVH7#4(cw^8V>RB|b?fNODm5F`n-F^~{zHrW=B# z@$s6Wguf;c`CidQ*?q>jPof<W5jGW(I#L*HOeslYfFWkXI}7(+&i9z`KBE=3bK#oN z#{FzNvSQ!sLs7SyyMSRkq@o#%ubq$EtGG26BJUu6$RqAH<RtsqjG_;yyG_HR6$_&f z5uzZPK?v{(MH?5-XExQXje`d}M0ez;8Usxe{$Iq3uY~q}=lnoGPnxh~coC2YDiMul zll|>*Q3id?a#LW9u)JGf^Myc=_oIyg@x=?qQ94df0ieRS#9p4V;1zMQz+1K4^>X@E z*qR-asmq!AN!}L8Q73njA&up4(W131!wd|opwVt~>GqwIm%>*upZZhs%`LVR(WYt( zIcPWpVH|T<Y^K-_)CB?=;d`GQqWN%l&8sgb_7F`3&Bemy$#Rnks8yo0FLqTrmcmmx z=4CD{rOZ(=MTs3Dh7)`78#4iFXq)I;V~m+gdW-4ei1EOO1&nbNG%~zXak>OKn{Y<g z*&Fo+`18*K>UVHpKVhO=z$Zr>AQyedpgV*5p5Wsxp(qmG@ciq{B%xu1`=yDU>NQwQ z^$m=rOKIxwBvYH}fNFYpKYNC#Vq3n$M%4`yNB+_gnQ6Jb@NA;#Rv*>KOs_+)Ryur( zezF4+i20-*%!`<|;6)nE$>v4z#Y-KM!CZW?@w?CT?68d8w1WQqS2e_bH_kgUR4HB< zO!Q^~0J^aQv;ot7PAB6vV=Sb=P}mihv8X{`Mg5?1@}1)xhmmB6c@dKkQNrW+BP1vJ zUjGp9&ULlpl1JPO;Z3xNgC%xEIK9W$iRJsR9xR~n$U-0kG0Yzv7>r{L8$IYI*sBc6 zbCYU@Fn}?uSOJ*AWp+pQ`_V9dj`z+0DhhV7@?#d*Ul@G1Z(rs0)V~{>Ob>p~FgohX z1|dTp^H4pW67uGVC(gnbgTgO0IC{bckNEP&!0JO=l6M}|hS}YV3F^Ft@qJXePt5-& zw4aEnwu$Grp=+6vaP_JE;q4eH%iP@mn521k6`<u#9$(>`qRHU$UDBMs^5ZOz8l?ou zTPv&?-f5)Q!_S0;z3>5IBvDr`I11BTzeo**gw*KYxbeF$%r>XpHekQV-wv-H-M46q ze5e3CFgkFP(<xm0X7)i2Gpoy!m!;NnJwt@*G`%z?J^$zOhi&xcx(aS#et(po`Z>WO z=^sN0vqm1A`BV-8k`R44{+hXnml@B}->%<JeKlKu%|>Xv0(L*j8_VFSJBR5ykGOcz zzh!OIJ%CCD(f2>_Q2X_5R$G&xmT=IHydSi~zFk&m8`V*W43$yv3RU-Sy!QBtZ{(8< z^75{}_uAQ6>Wn=ap}<G|{<S%v+lEuoS1amCX9uJH*Sc;L4ktHRJjoZ0%G?~X{r%70 zxz)M!#GF6QVnxR6s`X0LI_cB@-A~4iBuJqC^QRm!wq<?x`|C^Vrc@La@`M6OE-AOE zn@*<8CX8b0YT};{tV&Q1b)7i%@(v7*ug~!<4-+>@Ww!yx?%@u8ea}74`fBgxJ<joy z3b`uP{rVV4K<mD-=@6^EF7xRkR6S2kC#nu$^+WL)wyykXQ~ehQFU_j^2nw>Sy4+OK z6yEUL)eZNfu^^MdhQP+uU89gH9Khg)y4Zn4=swYMfn@ti$X$i)QziWMg1CWNCjIP= z@SjlTTijRq(`)v#&Kv0kwhL6JscTAO`TzBe_Inytbs*T{*4Dm*Pj_Wk7!51C?@;l8 zmmDhkYT7%ctEbKQ!;wF2J2LmGk0+Z&WYe!~d%X49;ldaGl;qr%OP`HpkanLrzA@MF zq<-P3S5#3_SXeLx05V-cXkBs$AK5+=UWg7CEG|ZOuf(+Pv*4X4E$mVXue8&N0~_D8 zptAH;`=EC9gx_Y@#i-E_7KPs?9*BHln)$tp3%F1B{I>=ALtmGIcjjQR%cPCVaaW<S zoRRFcp*a`dWHL!_N1u!OJ`^6|uV-JP`6#|6mB!gow-<4R&YPBaVOm;xf<R#_5KO73 z1MPlj-Z-Y>)^ox~K$`BZiQA&E8*|&vp|``F4{<J%A4a=Va!T|!!@RZagw|!WK;gGn zJ~z2V3_;UdQbRf>o0+}=1WQvf45UdI(+}i_-rINC_swrzL%saH%lDImzVB8g`cF>y zG^an(w-H*Ylbe3=1PNnRAz>kYvE%Vm=y%|Nw@?sMs6VUN|G5AciB!6bT;|8VpGq@9 zhOaUO;2^=3{Ao)|VP~7&$6oO7q7t$cjb3&*M|?~4e&T*${@Qimq7!UV*yeG{HH3*H z0c%~>v7*N4d7?QZf13VP!XX7AyrO^lLgCpBzUGi*4E!ocV}k{ED>s0(n&+(AR@7DV z>tP3rp+knO#_yu7eCS-ZPysdxRhp_$B}?&P&H*Jj^JXe1$Fe!APu5oukDUlsfXFHB zS@D%D6(&AU?1ld=8SuWv9Ed(JHB`tP`ZtLmHrG*1>G}Lw_R--)SzH%%?);QOvWG3{ z?a2|z81{AL#E~bE_+^WXBMcthLnBmUDQPboTS!_AJe~jlLPvN|UHx6f9y%C~Ow_h7 z0)nU8EKC~40ND}JK<rrWke-MD<AT(nc)BNc$HXX2vp`x|AI4DN2059U3OzrDjcDjb zkh_fD@NY0T7E($rA{vROx8Rvm+>1(m`W`?-48VzqmoXCqNWj8W*-+_$XL;;2rd{UR zMWnLU)=XBO3TlQ#uZCDdEe(`M+)35<8Z)%$TB#;g=xW9xRbXn%+Eq6IvFUhr8@<5I z9~7LD>MwG1+>Wd$tdTDmSL~d^!=SojcwtnDf~HrDW5p;Plgg<b4aJH^KU5qzX56G+ zktop{juxAw_SPGl?~t0Of743=qe4`WVUl;aa7KjCMqg@tm^OkW7K`y;D6E$ZU5e}; z1p@~FcM5*1ohM-`cr1BD?W&61y%9AJgx*ZHvo-6y(<UA6piXPi^HZ59`~D?gvd|Hp z1%x9&SCWPC&K3~BYT#kIgDO#xI8r3LjIu#_1RbhmU$RBReGsTDZg-hVnwiDlwi|QH z%FceHL#rX(UBYwpDA4!0#1Y53tg3d%ue0H6&B4Rg@x@Jb$`EB(;U$sw4o1X05j&;U zZG0#jeOKvucs?`hJL^Fx#CPr4zlw%T3>}*6wpINrYgAlk7sJr)LV#&dFa&G+sOA?k zFz&{jP50Ef8vr(YS+9F2s6FWCE_r@247tnwtd1E<N|>E(4%IWlHeOO>Xw7%YF;iPJ z51xkK#KFnS>gaVbG*uDi>i)p+LZnX%1R>QFD9_Nm%o5q7TJ=Y?_C7?jVCB?5CErHh zm(P*1o6ofEsIUqQmL6bvb2|YiAhl*Rt}VcE{g3|XdHa)g`;HAS$m*^OYd*DOPJetc zBl}LV+uZ21R`-7h21RB}P2K3WeD+8xhTAd0Gw#1|YYGZ*DuyA7)>R57_4t=GnId(W z<`NUN3Zc;U5Ega9P8Z=i335@6=jn@2><#KmcYG93ZYYkbw3|sd%c=OGqr8ikvRT2K z%#M)D&ue`Qt{<)0GVYg7Q9T*APTVnl{`3b=*j*DM<l+xctxs*22_Yn9XMa<W`kP6g zov>f>P^%v5KJm!EtUR$Zq&{P#=MF(J!@n>kxXH!IGdVOd@#SlaU!7+40ZgJ+cNaUY zci-mDHGfL3_1-RW?)ZbocdR00`HsL}+_&zZx<U7g@KGsMKb!KXuPy7T_M3NRjCi1W zHm;c1QcCqvxVq%f&J(Zay!|Y*lbu=2R)O&lf~0D#BfJbmIM9`K+n&~v<u%jHIFX69 zIh_1o+A6nv9QxVb3NiMrkvG)5oz#14o}y>Qi^X=QAQeABJ&Y>!(y3HWmuM@U+VfAz zKZK&KOA0PnAJwD$s>kKYra>v|)=8ztUw=GbKD=m`b;7m5|A{7QZflteQ?;e?OO>Iz zkq@CP3CH1@E%CK=A!DwN3cLFDdELB8gTtA{ouy;!Y7D%YD(l;Je20UdamEuV-H||d zr`|vRb^iXjcXxR%F=VR^vgt<|QASB=ZihP*Em*b2F{3Qo$7f*U_yLJWNzA~;F(k(F zy4yqJDTrNFdw<wM$n#|dN%~j)RPIGMsd0$HE1}Yk?@l}X<;Z0jWoc=+W|O+JoW_rP zpV6y0K-@Z=KM5^y_<ylzSY5T(d@^p2A*1yB2W1or@EBIr3#9-{_FP7d<o@tW@F->X ztTzKlt55mQ6VH)lT^0NytB6_Z>3b~(m`lADg|xXK)v#w>0?BqU)YH7@CKLFKEr|iK zYCAYa_Q4|ft|-1ZkWhLQtWe=sl^B@8v^w4Whu4+HW@B?!#3ye0M*qn@e_IdUMf)dD zUJ<c3OjfwmHz1bLobT<GfOp8O89ze?i=7jx?s@0@W&&`1&u$`G(Up(aP{oX1nM`!~ zQZ2lF1ZyOzv7)GPE4<6VTrR$}5i2W$QMkdZt~MQ>xF71f1|@htn{M*Lq$c>9XL*!S zXR~R5@tI6}*-hDf%I$dZGJ1WcZtlqRx3Adnw@zqf($rv#vGaH;QS=T%I)8xLSnoul zxi43CO=iL->jC&5W|8bA2yUhdYkxcYkbW3ZvvLLaM`e507j`0p;A>b?>=vY4Xgh+Q zzuL}CSuY+rLrR7(kVmy{KqnYABYF`|%QVmy8E7CwEtaGv+=P;uLMO-Wt4rX|GH9*6 ziREbe#Y=*tD`t2Sg^QTK##0u;y(epiLcv^MBP7#jGH9KpuZmVBrkR-}8@SKG)bFK+ z5;Y-`AIqnfZGWRGCK4GGNtQ^teZiPQ@SRCe!jv=yIp{7Ta}khC$DId}{c#GgRm?`4 z28&%UV_xEX@2ICi-3?+aQ!VPmKTYWLw;M@D@SB;J%p`_4YnCVWHH)Vuwo}A2*y@5i z0Dp{@Q4c!`it?@JC>UUm6q79bo9sNXxX8aPHHWa$SUxzAy50c<gWXY<zx-anSS7_` zi&2nwMi7RV5iotPfIcl4N87@h-Ind_)M8o%lEFP%%_PxMq4_e2HqT=a0dEb_%t)F5 zvD#``i$}q#2k<><Jb@QfNe9N1+t2|;_}6FQ)~2`Y@o2I8$l9KpB1p=(1AQTWtTjqv z&gp7D)Jn9lqA($PXB{o9K_YlC_D$Zky3Iwick<pwpXJ4uX-U?Y-?-&mJ0l~mLgwaO zd}m$$(+P6j@(-2@WoDfK^1r)Mp$&N&^5y!cjR_6ElfxNrm-8!v=e>>zYG3Qx|KsV3 zzWWS}FaPq*Y|Q5Mek?ty`0V$?FKSH~8CVEJ*-*(w0y2RL_;M6ZVazqug@u^h8f^|q z3l!Y@q_6b>xy>McM`^kmuyd67=7RZhX*f4Uj56!K&Jh1hLqd>>+ckS0Bsl;ChQ5J? z+o_%l2vqQvi#<41t1<0}$X}-aq4??&Q0+TKLs7QRP8ZpTkqM1H;|gUI@YH=eTQ)Wy z(<#p|1*eiKb-(NR^yI%xLV^S@m+!LNvw>^PG-A-ip|16=)ZgURso7>F49WUs&%TS? z`DMv#o$PW6;{P}ynmvDn8qHL#+~-pF3(r<zGtVdD#n$UGHFL<30*XC|Gtk#ZJE5D& z)DYvmbDu?CREqUqgBR;hOrEBGl4Ig~uz|}u>bu0yxmW#PX#Hh0@RY14seH%oh4GUx zM1|eNMk!)L1Y!!hOuVLkJsq{mKnxLjn24eu^0V&sR|-+5;JvMGT={X>X42m|l!)A0 zW5rpu=8EHY>J-1~T|LfEeU^Wr@s@SJ5K^D16S%Ac8o#XZ!>^lymoA1Wpjfb~FuV0^ z%LU(ZYn@nm7GE5)Z0L=?Ct=5fR<*eQq2H9MyeE%x?%*pHhD;5(`*HWd3k;On!2#9; zl(?=<j7hw|rhg05HNpG|T>j`t1SGDnxGf=*qGy`2Gqo!;mBAY285t{6=>R!W@O0W* zU$Qs8^j^)VON#nb8^)8^nZN(Z<3sZueV+a=`?PJunwSpMBbv(@MGs#5!$Y~j^KkC9 z!NQI|CELu00@HSEy0NY0Y*AB@gSqn5dwTD4ol)8poAxI0euI6#2)*6EwsXV7m=jN* z?P$`?V^}S#uJdB0NxQe`FSau->Zps!+j0G;AC0T(?uOh|(G%wx>rd@7&oTeHt#75O zXZ~xl^DQz+Fs8>VFaOf1OZIQF2rnD5)?PiY6Gc~c)Nr5w?sL@alPGe}&*GFa{1L*; zHxzc$WTk0`zrqz9%&MVU4G`tygOa16vPDdZf+b^pX=ac%$(N;Bn_pPfoXMCIBFa;L zGI&mx0FQ-sbEz~+CPI2@lr@evcJd+hP_WWZ6=@aH*YY7TBtWRPmpjtxAVcT}pQQK; zp8TN|2Jhzt-YyK;iHF-QP`pP8?gBo{^;lpAB;XeJTv@JElfgUlt6sJJO~f%`w3-;i zvI6p~FTQ3xOR;RnB_F$`6lMCi)=|@59Uqxzg)xmzFEh==o8UDoHbJ!{(y@u$x}ND% z4!2`@x8DyoDU09crmHGjKA*O@5kw1h%c|$M<W!xDr%OIQrU>x_NS)kIzWAp*6@}Yv z+S^uJXpP77K6YS5N$^W2^7I>#CYDb}4bA?ut6w?jAC46240ctVRL&^pu)8rPT9@_c z!A$cj@9q`1u~8M((EB#&7+4X--Qb*ek}uERG4%g$>c>;o!k!Q^g#4O-&VJom(K1w5 zs<%s{B;jL3Q5))TS?B#(VahUSxaQSn<8BxPNDJ8LXw-||i+m=m;c`DZCqn+os5h}< zStBgI`|5$i%NPzBD@*aw<d{x#=@MXO(-DcR3@qSMM!8Piqwjw?lkIq}a~~qpg9VOm zNYE6iDnvWN;`<;qAe=df8Yt~~hK%Y#KN6kF_mA|^eD6wTC4vY;o)=?H(}3e{fqy<> z*9hq*{+7f-C*?<)Pr%JNVxcm?FP_PwjOWnyH)JwkHJ{A8WeowqTRm`*pUhiGx!p@i zVQ$~+$XUU$c9p&t(W(2XGf2QfE%>bzwu6=Q0L8TE?Wn25bI|STXYFV|TA87UmHa)F z9vGvJy9|j(dh|gVQH=e0V~V+vc`%KOoN#_-{$(cy?vc3<jrEo`PvkbDQZy_#b9>6r zs}@2tkweH<1*XdiN0;5b5rEBWe5}RhAkKU1JdX5A?%&NMf0$C-6s!s$=qYs>Aj=Am z1LWk563>J4CR4tYmmQr`)g@8eK_pJcz1N?@!sitd`?Sd)ZL*jdgb00=L%UFXWbzQJ zchKu*0R>U2G)gXrI{*bxteB|ucFg#86f=VYXP743N_gu_rAZ5%rbfgVk5e`#Nw?a; zi_)dR(cAFrG4w*jh$P9(zAz&qPlNctBA-=_kmg)_X(mS`FL$Vzh8rV=DJ`es?%SG+ zpAO;eO#%!2b>fQ5<iMKFYb>tfon5{3)IMpuy*3QzPxE7$DQ8vnk^Nt9iTpcf1U%$V z$>M6Jzu)PEGtmEI=}N$wytXY`xsELrr`ij|TY?}cRMesviL`16NF&HBNUI>?SP%+P zAQr8PR**0itqC&E2ts8Nidtg;jm(NND3gFPBupVg-#Y30?swZN5R&tsv(MgZueCOo z-Qm{9rO)~VI$mJ>n7bX@vz0L3qIL5vf?n_c-hLqlG*%m@#!Qcc)CQ$+-#0@oav|+0 zxtLM)WjA7k?ID!KfGLyHykGiVJ0#Q>$q21JA5=8m;9iwG2@>esNb?+>98#lhAbY13 zbbp<cJ~UONJ{Syoa*nv@DCU|xCEW+i)9B4kXar?f#iZK<_l&0c9J^;)KY?*XFGC-u zsAP5J18bHAp`HN(NAJ55Jc{DqV#}ir{>=o#9>5Y0{SVPJz@|*}VrbFIaYDf(WjQ)T zy?gkTh@5DNK);NhJshmw_nR7^C&AE)n<r*#f|u|f@9cn?a2~Gw+-$mcB+|N8Y-Z_z z<LWa@kd^UATY@p7nT&W<0hrZJJ>h7M3i~h*3u8MBt-9g3!2xq0;_9cv|BJ?U+<+1X z1HSlJI*~bF2<{#lSC9=hFIzjoV|6mLzdYmrrs&sZG;X%y-SJ0_*2)x^igl8OtWnYD z)dk^4F4wy1zz9=P9R-&y1`JP4K;X<jR-tjFOKi$==OlRe1#SBq#{yi=@kR)gmi?4c zmz<WAY^X~(1C(I{TsDc|<k;_9sWHiQC|Ln44`UEu3CZ)AOATl0795_@AIB=a9ZAz# z#TlGE!5>}|GlM)JIL!q~ce-8wdIe)lbY*kbD&Kvm@yA8;_?6ZlHh=0L`V9^Q+w&%W zVc6zlT}uKzEgH8DgmXIZ4MSZ@Hu?uj=gzJrO5OL>%QtTw`Jf+F&zc-V_7|adMqGX_ z+CZYCpuD1a97fFGGTc8a>@LHYNa+BW|C?VAPL%a<&A3~K%S*<cUl-@V8^2cqK&-gz z*_pQ*k^iU_Rh~^q%nSa$31cX|W>3#n%cecQ^7M6HY0A`6mG?!}hqst~_TUZYxD~xS zuot!TCo?QTt3<^4vDdSbGd_8oj0h$ZO;3M$mC>&;TaH_!Tto@}O!k*jx1#Y>k9gpM zTpA~o>M$UQ$gP+c{ULJ-X)A;_`)TEi7W5<o%0nzLP(u&a6IP0_LJdE$oE-~M4ZaQo zmc2lL=|Prei#THrI^M9wi(S672?g<{I)e4WyF^y&O^0H}lz1=m!Ds*_3VA~7KHCT# zbS6n2aS$z%tKRAh5wR=NQVGKb*ZHy^k0xJT^cA_SF<T<L&<q_d6BIEGjzbQ~e`|8I z^_F8+&HGYy6bwM1g$CmHrJ5*rp`XKuQKHC+<+NeEA5Nd~RR`=IrncpGh>1hco=gXN z0=WR88n-oQM0RNaK*w8REv_Eo<Yox1AHVcojypZJTClrz9)1$>62rFx57(uCvd-cx zhGc;fQ@RAj7{**NZ1#T2*8l;>=;wv#QzFGG`>3IGbNZNzLK>1>lI`YtZX6C<iZRKn zLS>@re&<9Ml^4Rbg8hu_8S$q{hh6#n80ESHa2xG~*J@=yX9fj7Vl1-R#ND?FiWq6Y zXwU}1(=%W1rFf(2_~7Ur@nFK{2F9)ZPP|*V7c)P(7*p3}C*^s?9meg;L)`8HC=e#T z@V_{-H{^oLkWHfOA~`?wp_nucuRi-GsP&D}yL6>;p&{#$7~p#Kg)g!vJX}BN<d{Hi zOutYUnZkjehRz{I|Gs%jFnu6J#HmhF;ws+%8bi*}`+uR1M}7v)C<A~1TZe4nQA7&9 zNQ_UyrNu}fgw$3HyZqN*)`kYg23UBc>MhWALH)`?L5sKD>KFiC-Udwi2Idz5%<prI zCBaU@j~iCP(}KARNl-2W)YATaa~anBA?(1x3=soRG~@>#)6m$(OyU9b;K`_MF}8^+ z5kbB&FP5R7z<_ub<XYxV4Lre&gk4?8Wt?rMrx*nDhN{h!O{+GAn8i<sS46?{Vh-vM z7WWD+z3KqrfP?~O@mw;E0*tj3k=OuXm#w<FA-h2ygsWf5ugn3Ovki9=aSN#6a^tND z%1`fP>>q`ycOL*!8R);L>><2HLh)2(a!oo-b6L8uEmtmr7hEi0ta7iP*r=&k{R~H- zM^NLE%6%7H3WluU_JLJxbrAo8;wLw=0dzOu*7uNLoVkMwE^|?{19X%~udoiL)_5sT zsV`G+DM<&2J{CUc7y)l54LtRPzF|mhihiEAlsjy%Y(-UC1J}MXqxY|m_JmV(pCV%; zpo_anjm%T`p*aKPW(#C<69zw!$#<mDcBa<7v2XRyPg?YOz!#B)TPT=%xi>6jW%z0a zEW~eHBE`Te6Kv(_2#-y~gms;t55oFkw)TP$M?*x6@}T*7d<`Q+;Ow(Ea&sxfdIJgg z#KzWwgu;T2HXl?Yg6`GliawMMM1vCyQb$+*HTzEF07_)Nug#O<kvdA2q4_}OoUhws z`m*AWiJQn!M(7<a%*|4H^{C1yWBBY4pa2PqP2>xO4(PutZ!&frZA!3|Y+4yi{79=o ze}fFEKvntE$7^4q;DF@<u?^OPo(g=ejF%<FR|mwVw7*nxRWcx=$U_SIT-3qN(}vCM zRR1slV}LV$yXmZu;h4uZXKz@U>GaDfQa-u%GqqXTkGUaOBJAEoSCfp+Jxb3}C|HqH zTKegw@@f96+nLqAWjtrTeqx$>vp@KIIQEuboyH5G^XrSKfSN1YZRmyvM}*Xbz{O;9 zadT}q16zlZ4`mqwLBNAl@3FYLuPR|5$>z+O76z_^%^hAunSUSKU*_XJ30X1tDBO~3 z{hKV#j0d*0m((GtO8b%N)`|Xnt1(U!dOE{~sI9MBk+KT?sC7rz_8#=M*}WSBh-{GC zjG)g)j(Q)=FOk6}Qr;xpif(|zJ#bRi*DfJYgy?P9=W;a_`uwZs3lD8GYF6sVonrp- zr_Nf3@;=gA@yeB52boT|L3|94p}I~C`EsT%Rqota`IxsAM$m2TQa-7HQy)>M(8CwP z^5V0wuRLewKmPgV?Tb9m1bxDb3nnK%>~hHJnS04{hsH`7lU6Z<sMju37Gkv(XL8x0 zyw^(&Bqz>!M}ZRG2IpqvJVO~*Xl7II^?47s(NtB`^zbcMlTpQ(>;hEVd`P~yhq<}q zyE^Uykm1lS#!+YybZ*ld;cXb-^wv1BCujBgEt#mr($CaTMm4LxnkkXdhpRt3!V7{y zoIZ%J<>4&F7uY`4E?Yh|eDwGv%$NK`cwz-R+GyGqx3r==YQUb;cAK`%YVqk^5?^Eq za-_mD(etF-TM_qR%TeP=lf?ouy0<m-GAW$?GV1xrd9-R)eIh=gm1{``m{~Wy=-gmK zS||-HIKo|zUE;0dv15=&^sy~4wX<hx>v*Wo^LGe?FAx~9TG2|l1E|Q8$fjV(rWypf zAFQ-lZ;Ndf)@tAEM}rT~6QL6{9&#m5#!+UU4j!F@MX1HCWX&1dPw!r?#s=US8D$(n zO;QI!=fLx(=$W3dRF(c*MqlG%E_kfgp52+#EiUk{6{jRKQSwU+89#C&W9shUa@f1x z^dh#UJx7~iMdpI*!9*pN&GUAAiqsBDSituNg@>{14S?^_pRLA4WKK=)UXI_T<MB0w zPU~D2`XZNaC#K^L(aq=Cu{6kD-jkA%_?JUvgqL+fG&M~|=g#h@Z;ClRd70E)4-ME8 zw0@w7pTiqTr*LeFwdvvgalp8W;)1O$^fo%Ve~cQcRw*UlRlt9`dJ>JFdj&h1Q~y!> zo}BLFGFvMuzrGNhXWR%t#)fTR3Fr*XuhH6Bx~WDdFoMoPV6!Ca0Iy2mF#nVJvsZfX zarff?B#{U7hxr+R1y|1_#U9*DwJnSIxUMnp7>*NwoMq*=Ed~g03}8H@{cr(TCX#}p zvI!z)ty>15kIm7U)rFE0j}X1N7i5SA@$+zHjN+dpl>tJe<0F?qgBp;uKtBuIiv>Lp zPio*cC!X${N|fV5N14D0Trh}nT#^=R5Wi;%Ce1>M^c8ApP_k9HOu)>0?)jD55OrFl zu?zs<_$cXdI<xc^Y$te=L1xlqu1iM#$ZM@JF(E+hL`q#WI7+UFH4v^_!CW0?eE;F7 zgZpIl9(zjvcU;R$RV5T7PLHJ(@EGq|1v_BhM4Dl*sm2SA^b&JPa5zM;wI?45^49WS z-b2H19-6LNP;Ov~2`|bRZ#4}(2ckBHt2aS73RG(uGXu~ZU&nwproITlDHkd1PEAJN zD6vS{B!aszn)K%v!WtqIvSpY7#I41vBAq=9oghq|@Ia9LVDcayv^~+D#?F_<p+W~O zjSTnF;z%_k_rcLOlA8e6P(az%NrVVwhaVI%zuCWz9<F*Oc1U=!=?Non=TZS_OK!?U z9Tq#}xv3r#VqeS^=}`knQQKT{V<BE-Fl5f#M4IEf#kSwjI~3V)W8&UDdD5%AJaQ{N zvg+Q9*;sAU!}7BpA}xM9Kn^CYJkes`c5TX|@xebg3bZ(-7Ze^RY7lWK@B&0`S#tPK zgckVQ`~FukyJf>F1wnVU{XM3)RG%?B&F>R{N8Zuw_ewchcOClSa^rMNGVUdQ+Jp9? zMXay3_JCnAdo<3XVaMOKCJEFaiu@G({){>BPej!KaikV61Wg`slk(<%EERngnZ#&^ z-5qNX0|@UB?i(@aNGKi4dL$GDA$8JCbIe8vw56gF_&e+|+@p8kJ*b-K87yt}8e>w& zVTj$2DHv$f!TtdlIat5q;iIzjUstao+OeUut^}<yST^;laHX&kXad=w=92?;r`5|> z)#1T!+O}>%){Zs|uvT%p+9B59a_E4fJ3u3zfZ#&TpM?7y(6{K;lrsH<UIs-3S|IFC z{D}SpW-h?U*ey}jK<7oEpj4X{a{DP8A+-Q^eFXXkm||sh`9g}W8xz8*ag#Cl|EN87 z@I!xIwV@L9rgyvd>4$e?@`R*qb&tkUVa7`#G7RLd1<Wc~)+yPeq__H4$eyv@n|THC zJa<VA?kIZ80|(!(?|+q0c62bOBB*Df1AsrUsIOVmIrFENxYjdCS{S<zUijrGQ5a}t z{*-(bx|tVia8y7(-arjl$*^xgHyBnUl*E2JJx#lvF1oPj6WTRU;B1%NIXhu;k-oG* zKIh%=;u+)KVpMAUI_1{kXDPBt>KUoOLoMyEuq^qenUXsp2TFLhYe&81nqlHr77E11 z3a`^^N46Q${Q%!ebPI&lOJ-DLvxcsh9U@;E$KQ%7?yMS|(U<M><zd1@V~8E~=bH%$ zMcW6d*LAT>*IPC1BQ(>~3MZUy<+HTg67|mRx%O^{+2fT}yWfCF2}BB9X?U$!)FC(! zPxTE3C6Wz?C6I2B0Ou9(*7)$v)bC^du2R1*p;i>~rzvlgeZic^{P3Hr9vivpHh-kS z%g23{pK`={I_k6Frs=R<T)d8lksE8t%ivqU0CTw|g-c^1q&vpHn+h7&cytRMgiRlR z=6MQ3=Y@HlKFHXNOe?|jZrImjKGDZ_q{)|d)aVOkj|;eA8^fNqCdA+WGT}nEm@rOz zSHK$dG{i0#tt9aBN)2)Dd%*C}xFX-gd8@Ftv6-Po^eEm$3*{>=4)(RIbl}FPb2Utq zt}iB*{fI^+#ug<RQxI4%=MXMDiF=JLqB`wB9r@}Cxd{918_B35DyX%b@h057$yZqb z;1}R)LMM2GkPwPf3yt^K{(qfdg2+%>I9P$(jje*g?})2xdzFj&qSa^=pGfATnRaRa z;C{6C_U`g`z(GhMx3c4BJt(ZBg_0(K%1L)(C-9fMO~#wm&@ttPjqvqM&r?(pmR9bK z0!Ua2yWhd_CNt7APr8HLBU(}W3xaDuZVM!?!)dN&pe7zoj;lo<&)J4t^<myCi6vda z479(yIF(soq@%+Mlc<#X?9wmWwfNO}@A0Occia&w<2<MoC{kB_(p<IbeqzedzCF>H z+9F@^aLB21_nYVs0Qw+j?+DqT=*v$<hXO2Wabs!T;W}jt$Ao0Rq;-cry&v;ttUgdT zz^g{qPe5-W&}Epn4<|QDfl4B0Y9j~(P#h@n2X5S7@7ACYH|7JbCLM?yJ+OvIg*k+e zy%!w}=X5ksjWb@U5Hw7MR~FGxLF%J3raUNw>1SPJHhq=|ZmCe6!k_#s`K{~3`;ZmP zPk^Dlxvp~IIx!he+k_qnd}o)E+aFwPGOhwvQh3*tL{&4CKo|?b)d41rUxr1&Xz%yI zQ&6cBOc;MepXq%M&=gd2KB#2D-vXBtCP8S=!Kg{m;S7|A9Y_mMtMW|H*4u=L%Ip@8 zpyHL{&4|p1B8oJtkO}wQ{;&Kg9v_#JxdIBqBz2-xpM|e%KSWQEu&d$L3Lp(ybOCaJ z;{?q460Xjq+QSIEJ|-<%NFTvn@oxhc^j|T&#p;u{(f!EDMf;aHCQTl}7IW6d>XCb0 zI`|!7sH?UKd@#V`?j>23{foIfaQeBV7vEJ&=+0Q%#G;f)z*9t1jL?b^XM^}xd~6|F ztOWA7O;nyJo^?DEpz;I*fy+R#*lAZ3ehP-PR1DI?r=`n$kfkccso+(1ZtY204@$6m zAYgDb{`Z3*8L*sEV<**wiyz5upi(9G6V%fbOtRX=1)6}x9x7pdttrq(UA=z*H5bx= zVZ-w=z`iu$9B~!Emg|eTC=a{vY+qZ0684YUG+`ZN_02J?S1HUq2cqioMi;%84Bz}a zEiF|iM2wAZowP&0n{}S^=N5y>?WOY4ZbfgH&v;wQ)Sn`%FJR7`{L_EwtiJGQ)-iP{ zwh9qU<+m=tRI_)ne_WcNs7E1hEx|C3Hwg_jC^clzQ?+Aa-x<L?gzA*?2Dwz17fciO zVDYJ(8glpDyL+|Br3O|V;7_688)gOfNR}G;Z>5!n6a&3*#D}X!uedJP+m?04MJPBN z8)H{`_i}x8xD9%JGNHwQvMFb3+U|D%570ZwfEng7;jxTWH|gaTj%<$VWZzi5p%-i9 z@8p!VDm}Bb#Q4%hE_;ljgRx%Nx`Lr?y^*lDDMEr3Swt=4J-1Dud_^A@*o20{kvl<7 z5jSo#vTCj9J5`_0c=;!;`vld#vBLKk`Vj2QRgR=k)ah7#pQ)wvOwi4M32qn47oQP* zem!Q7AgSYrl^-5Sj25kxVwa?1Z1({vN8qd!$s*v5>jpr(9`ra23Wqn5b@R>`EH1qp zFD$F&E(k#}2@ybDHh&aUXuVv2(yf{jjX3!Ka*Bg*YLA6*7Ad0mxf$d$R35yrVM|E{ zf?~%TdXIud5GLxtf?#~;s3Axa@Vby=<JXz<@DW;`5Rp`yH9_cu`Wjc?3hm#68V0D& z-I6P`QXM+-Sv2ynxu?=jp*Mj98zFq4lBxe{{V6=1^nfx~pL+9H{-8bfrLAF_dvk`w zI2G$1=8Zh8A@KblDQIHKmqU?|*`@HFw*({i0;#dZpVg4gPqMY!yxsPVOu$m+^Znfn zO<;8dvk%Ccuqm#tyJhhCEGhZCU|0JBt$Lf?RE~f6DOOe9%P!_TBFM<e-aL_%GDJCF zU2-X{d)u1Ez@zBT7q25i8VQn+{J<&C%OMBu1eZTqJgVVQ6Qtb?LKaRb;*(yOjUW(R zl=2bfm+}L+cW)osu2`$YKnh%9G4<E6PkCV;{-r<vyqp_7o4Dj4XH+-JYclK3kYuot zjl8aM(_8w--ETP&Q#ag>IsX)V?lFA`XF?2{fGIxcRBx2-;KU}-8D+l>PBW5T5C3%h zhE)Qd%Sog8k9Foqb#K$zWPYZ=UCw15BkZ+uPmP)KVBN@tsQE#%dhzIF)Mqo-#?CzQ z{Je*|!}{S?<Y_I6`~~tdohrSV2QstaY7I1)>SUppM`;x~c%a0vrpa32Ue$1dW=r88 z2671a0DHBRzAV_nhV#bbwE`xfzS^$EhFw30q2EtkvEMtiVf@;Z%?0<EkIFCqQDej? zLy_Ik2kHu<XqMf>|EOtnFx5L!Z!jrvuyKl>j=XKYDd7&Nkr?i<D>8#iE>25ozyi!0 zz;5hGQ^i7-0fI!6IcLlst-z&1NR!lRLt!&wCb0Zwr8S7tgcA<q0n#nUZj4OJtc0Vn z{%oz=I@}oQi^+w4G-+;(YM{{0c`!Xc_g)G}$^|$B3NjQ@s0EiDstgeIWTC!7TTtEc z>O$QN;aVvb20fr*LB&(UNZ2b@0#4ow@8eKY`0ZSET5q@u5r}EiX>JT^bF#GoPTKDC z1}XK)@FJcdv3&U~#An8~f+o%D6Xb^O38<y)HsxFY#iYDRsZYZdYyw)?PrC2{LnETE zX|6dq)}#<54q$2zkS`>7>{^Cm4|f-0B5gPU)p1a$$9hTyDQU0+Yz@_r(Of!sD71PS z=m9FPo6f6q8Oqx<4nRHJry<UV$MRWSsFHFy_(zV!C~AD3iB2I_jn;z<8`YEJGb?)E zg_Z|qqbmPMM{JrkIaAeeBqp9)>2Yg*B10q~!njAK^l>vJ2Bs@H9b}Li7k6SLvR{~t z`9Std<Wi^&fo-bjZD@u5|78fTf-rA2P0K!k_EH53;#3aou9SUCh2*|hBL!VKV2E^Z z>*(+xqm1^7;jcaiB<#^?qS1!!y+W2!hlqn~8<9Mg9YKu+=1L=|GJO&g139E#L#y5M z-`^O-B<5HxU`_?1EeTHy$f@;~NlDhR_dS+{0fg2Zzn5T1o2Jj{VsHU4CF)Y;$a%Ew zD^f6>3jiykdOUUu-Z}GAI>Z6bF;$%0IgHr|0}KF=7{XsS(FsZj)TJq6bR>|fAi*Xv z)2DwwmI`4bK-2-2pCs}!es1S{Se&C82WXC19v|ol3siW@5$AiN1xEFif?BQtE<dy7 zd@>@}VD5Db$mMp${RoA^9EuR^G)xrsif;C6#3V>HS`-~98<y59j>cvC@23r^0bU-$ z2Xsbgz;0}SJS<ULO_P0YQ0Wa$NGkG;1psRTnD#0yf!)5j=z{x!6ej^!5G6galty1^ z-zV~CN)N1t`6d3&Wdce&nCUQz77uNO*cuE){Vq5zPeZi@E*;uuh)wWa#a<IZ>Bfx$ zwI5E3<kG;J(*8mpABuaVwLtO6%IyCOQf!Eb=INl@^t|f4;x<jUufzTL{u-jy1FZ!0 zcAv|PoovTHYNuRkvW_403JU?7GB0#a%8dVxZ?^Un7e{V}vl#vdmzeVBX}jxcuk{(f z%zrt2<jG0&u%KYhJ((`37ekE%AqU+AyHTF;`Z-nHi~USG#XF2Hw68nmye^LrI{nBS z&x{d*S%J@hY^41257;9_a_HM~rHkmwN&U+U49U5p&RhtFOLZqh$!WDS=aX62xWy;Q zM!tcU85xui>Kj@GXD}5Q7?(%aPlbElbxp(A7RQkXUf6lBn+qWOs>=|PZ#2Ok`I9qi zoWx^U;C+(m7<wE2{A9cRQ4AX!r$&=z*kfLs8Ds!h9A32Wz%u0s_#v*+FwX=>j7K&` znTymO%le_|O<UscX8*CFPyW&D?{Q6t>j!N%x9R<Yd44rWHsEg{#e{J4lN;9J=d7mj zSs~{0@DZAyWjJ{B?C6L{x!prHtt(D;I%6|-1?1ta?l;_h#pwAXkf-}K3WBsB6Ifz> zZ_afa`S<m=R(7`4T_=5V2oRDkbq#b;{hp9X8|Kw|6P${0+z@>j9hZpaFDUVZu-=z; zy6?peQQ`yS#_0XPD;_o$xQ+0+{`Jb~$C2~GLwR5B{%pi~-5zvWfUO)RQt2!hbCFO; zoLe^-cEL1CAEF%b&_&#NP16B+Z+5TNjnvo#*_Psra?v{rY6sgwyMnJg3;t|=JBO%e zP#OfeYdp@PDYmSqOcT~)VCstL)si=)1s-Q#@!$+Y`K$r&4W#?HhfL+&w!J>}m_vkD zjTPcjkd=EMwS_rk{MD=B5j5D>!&b{+ZEvhS1438#NNZSV2gEL4Znt~hk_?2~WOL7+ zq@Ojf8YCHG255?8-Jr6l$iR&Q@d`*yjncS~zkGembEh^5sPMXGcv{L06!|op?ul@L z{Xc3Etud5%9&Q;R^TeH^*IfGNHYmRE&@;LAZ#0^tE>}}%`r}{jxakePNDvk--prnT z2H84niVj|l!BjP$L@|V8@?T1tQ!%cC9XCo@0#!(t=FE}V1tYyS!<0#X_;HD3()|Xd zA9FUvE{|%sZsx*$GDQEMvhU~5kH_=Yl!yliCHCNd#|GYYU9QqSI_5D5oS7sV3#p2C zOl3&zM-0J1$OLq#tMeV};F#!@7Z->wEPM{SjxT<D`f`<?uf1iC3uCI<*s8mVtI<_+ z@WJ7Cr#DS6Bb=6DL-yvaTMVXa`sC=QWS4COit)?%ttp>YrA`Mc;080xm+!wlQ&;j$ zm}Ev?Em0O#t{rLxDAOBReJJqRT&uTmhM~zA*u3+`l^=)uJg@VM!V(LZemTLcy1O`g z@$qyqi2Wa7y=L-fz!Pi6qyHMb0-!+ypixm!<Y`G=Ccu1O-CSRgwj5VF#}GRgRJD7_ zf4~A52AAfzxB}o)`DrSmpz&4MQ<2sdA9iqcN^`8OeIpxr1p3i%bif8Z(Zfx&{FVtq zG#z)0p%qkpn90D@)^rH-p7T?3Vin&KWmuR`!mij_HM0iX62t%mh?dh%!0yD}2t?*z z-jJ-q&LPY3Q25sONaaFJ6Tev$5>SZyT+z3qt1iv|ioDjFG9d!tD)z6?rA_4fcWRKv zgi7LK5ScVLfiE4f0(OBfIXnJ9B?35DlPf(K_H*=1pr0GK4X>p^ZAt}Pz(_3<ANa$8 zhMt&@o+M@kHsZK*jBesg^hk{|0V(ItPYE%SP<g>U0PQghQZX=wmU(|AV}3%uhXC+a z+zYu$lya?osE8PAmyNDsR6kw?U}VcCPAh2#22n;06;Wt&=VasFLbrIzloZ(3YVSz8 zof5iKg|^rteiDh3EuC$715`C~<Y70&uoLt(gX<s~fyW0<7(OoWgs>4a)qMw0GZBqE zc$m{oL@{-6eI-T?pclZn2dwk@3%KZfS!w_B!4M`k;qHZ}Dk=aGkt^=Z#4-^AAX$WY zz>v%f<tseV_#ht6YLT}5N_-)f!9dVL43t;Pq(H$ji>e5%ns4p;t)OVbbT@eTLz+hz z?`+_6B&ESOkjdJZ4n*a^qXZ4jifsHQY8G9L#suanqaBR1i9wsFPy~ck0=>~DLV%wG zdO1-f;%5I~hwqI7hgTe0OB4j)vj}PB$Xo#KLNd_tg1lki8|1PAgb%bjX|WFcBenPw zaMC~|w&$p;VQZ18JP^YAAOS;v(cDcfAaFiRj!>=*0Xyd4BRWmY0U<Whx_}x0lTdh` zU~GklCUB0)fD>TuA!%%~R*S-TPJdV|$(I9o@K&P?17FVkUsfmZ9%tC0C`rZ&8wp}z zoJLS9;?oSRXEQhu3<lEMNES*~J9ti~itz+6j%=<yB=@?>EKJF5nR5uv7szJIz&N$b zfc!U4<55D`nySdg#)bMkYu>(1_GCt-GhqlnINe?SaC+P+ZAvx~^I>HXY-X!*nhIQI zJY_rDegCXFk~hB{BX0&06tz>&DBoT9uEeUlII?pd#>QBR@hY}Pi{dnA)bb7=*TRmf zGk@K5k~5r<sLg=L6CE=N{2KNU-8hQszJ6IvMYM=$<Ww9Dexl3SUw`xeo=c>~18(;^ zFfWso^*NE*fa1ty+Ry2UeP}T#at}=wD9@S`j#uE3&Ji=hS<^dO>?dj>&9}ic?_=@) z-^rfR2mv#lUzz{CYg2;hp2CE$@3N>dssnMNS7{C>0xNkLXxp5e+;g8|)UJRQb^w=B zmDg)+k8SG)o3qZP1}!-pRTqs+HC;uzF-*NKdoYf8fj5KU6Ob&@%Cpd@htdk914(|Q z%kOVk;5)rRqun7$lc_qO5WJ}{iTG$KCyZ?5e(d3`LsKvF5Ag|^70r@2+#De~n()ZQ z38Rb*yA8Dhd%%vbvqqqGhE)vlT~jKYH~hIiy@7y(ruPaq2lw7O6xIVX&*KDtK!DlU zj8w+O`sN>OSG(Ah!snsMNdEEe3ZQd$Tba-Re=#7Bqz(y1V+&<Z86`ei=%C+t`1Mx@ zh`<ij#IVu))ioW*u0~b5Uq7Rfs4vu22zAfi?}eKM@;i8GR!WTKjF_zF1o>%^HQ77- z?Gt6oN5U0E+%flid?v)(KfaegtpkV<yPE`+qRb;^5+n-<I~MXdf2RC#R9*HeXM1c4 zk~v8So!9m?$LQ}XSBeVRI`mCXLF5TKxb1L(@SVw05j>vO<WYXJ*es*@rq^KmPu?<m z64rqXs233=u5Hh!55*0M*6ta1<lnZfK|`lI26lMza*2-EAx1>xr#MEg9(GY{pO}W! z*pWr$nzOpIsa~;|h;t7Ea*cm^0|a+)7wPO!F_~!a3eM;XBuSaQsoUqp)`rCHTLu1X zKhs9OLfZm}?y5xw$xMUA7daJ}*ONsBUP!FL`cbYu5060E#?e!acifZ)YkVY&K`iSF zu&+#-55ggnTw$oXv;t{KfjS!F{TbZ~>+KJ|8L?qD;W6ojw#evV&FwzFB}LgHYi&P< zH=F}0bm>6BbAC_W4l{e+li=R_T&qsH)K`0NR@Q%H{K8EF-@tiiYG4dASf1B;%Z~_> zPU=QhtyAzg$Ap_HCd~0)<&qk3Mpki#zj1!4^Tqg{n4TSLw=2FJSzL-8fo<T@A#u%H zqG$Vf@{7@28uPdo@@|oIP}@Ij?U;Lf5qk`pyPj-}3(Uo48#cPrSjiX=Xd&gO&ollZ znDe*Bh1pe)^NgN0=gBKZCvSM}#7+U(f>7!61IP8BP+oO;%$%c5>oD3Ux=iY24l8E) z>^lM|x^WyzMN4O#Md9Zb%dAE|>cd<NftNn<JhT0_Q`k<{{Aj>rsnKoi)!KBg-$&%n z4m^aus=Ct!!5v9|pxC(VZN+sBd)~s215Es6{F#hVBP*GJap%G=zouTe9%2FpM9JRE znV9FaZ(nVQ|9%2!fKin|#$=EQ9etY2ZvlTnT)z;INgNdlK7@J4Lnk)PtRvDwJuCNh z6C(J080N16PC0BKF-YIB@^jJ+er;`#nR$1_CGz(P;-Pp=J;J~`Y5>9A6t+2lLQ=f{ zyUyj#gdjt(`|H(JQ3Q`Mz6_-}Dwx%~DMN!w4>fXWm6N=P7D0_<5-r#^{5YKV)KpZ& z8Wy5}He=r$`(``LV<y`kcBvo?OoLU;NZ1`wW^o(7DRylK@YqDSN_rVo{xAx(6Zr?g zPKbIxoPDicFuE>|5<IG0p%l-;gvTE~P!qW(t8j*wMWE`ylgg{UWY1LOK=Uu5Pk4LH z2<l_pLC~i1IgofeZ`sHR&wD8lhe-&Dq0RaN#3kqoOmV>|!(4)29y00C7=?mHGii{J zQ~`Avoz2QFydgw(8C3_!pN-L$q}wkU+F4kQX@<R$wZs<&QF|aYR)jh<g_woS1@J3| z<`1e#YUI{`?LtAy169ROk(^2#-%)#$Ry=9R0;o}V8{v>--vw==Pl3gaSOc5eAq`l( z5rxMbl3tY4;9~2Bo;g9UL3LQriz#~$w##`w%4^xUM;#+z8$gOv=bcMMc;B#cM4U&N zL8}F{BixVX>js0l8H7EV3lC}d(@+w$H>g=4QbD8Cn9^m>qVXVg0!x>X&_}#s(YFB; z1!k%+IgFc!gay1OHE8e%p@1CF8$)kkJCUfb3X{1>i$?e2xdxyVXaV;TPLWL*0L-aO zO^Z^vCetU6z?n_q3PLQNDzT_5FTiZTLtCdCa5*5;Y9YT7*HS)Sn#{l4smY<h*a_lz zG}!H+Y=VeJ4+gOihuedWH-y<53L+(pnuJXhOn=mHAEN4j^H>@~Ta7tS$NNB(Etq*v zaZwcPp0OE=XI*LPke-o#Zb?y0A1D|6Li=v4%bv$7V#fm=4klHeyg1+0!7k*1^>6Gb zZP|J*o^%p~y)pF#r)JKC{+Jb9KCimz2Xqy{<*h?R=Px>WxJoi{3k?QciO$wxvx6IB z4;!cXQ!E;hI%SRIg}{Pn(%<pAnJsTNxI3I~ic#@@1iq?gt^4k2%2TfObioqkGjm>= zmcQp4#(c%s1-pRh`Fy%)yJwd)!5@QxhxD8_Qr1aCk34^!R+_hJc5bB-RJ~2qr~GL2 zfpWQe(FA|qU(xV+!Bygll|1`mtRQ@Xzesw+cO&V&<r3Hf8)39B@J|rV&=7*#lQT72 zW^3ZLJ;tqFK$)$scG4}u7JeVu3iof7?qxWQK7EShw@<@-kj)=)O0^KtxPY9{8VKBR zyYqchsKqd*(qXf~ZN3Zu>S0FTU?WC4c9E8(`e74)_ot<@Cl3ZtO!^Q<8UuucPIj0l z&Xe9!r4rdU_CYlTo8`|~CbAC>BuUw^Wfx6{6}yNvMmbDBhB%wx(mh`5GmCD-E^g#L z)6;p%79z<eE*aa5%nw8rO2ZDr_!oyK()v}E@BVtRfM|K0UCn9_OEj(IGgy}N=(g=i z(z3THn}3s9-*ad95jnt#!NX)eCUW!^BN@9JG>&N$o1n=_o@c)vsy>wn%!PU#-jH;* z+y1Ok|K=AJoOKylOd0X5>O!aFb0!t)ZOZFPA!;7X1TNQ)n&wQ3{!!cG?6Wb^35j?` z<klXrAR5_9FTUL0JPWNle6spGh%MkxDFo=e9j;}qJ9QL@w?a-r;(UBisqZd-6$pZ4 zV+Sr?C4Fjm`<Lz)fTrSaZpcN(h;<zDwK9EKAPw0CQZ*1nahEQYau9{t&3oMc{*BwX zZ9@oZaC{zCr;~Qu<;qg|)81F;kL7_BBLGi|YmU+Ns@f->KrvmJaa;cPM?-T)6Q?Z$ zG+keJ#<eO#-|~>4pDd{fL7V{$xevntl!gK&e8GEQ^nmPDI^d}{%nP|0i|&vXcrtLA zwJ*PScB%b$Tdp4pbsAz5=VGRjX#}0U`>fAaAhG-+geeNjoLfuqnDkcQ%n|c&480nq zX7*+w^^mBCTYFm|@!zd=$1iS$4XWq$L*YI2NX+(t)Ls1&+WUGs9;~n3$$XE@Ww36M z2YyRUPL52=>eGIVZEWtwnJrJgWVd_wPR#~8jB2b;3Kzh{8E#wf1i@p*Ulg??lps0S zBvSP4QLSKV(!y?)#5C@G*OIDD!I$5LrD@Hsz~;rgxD7s0^}qCxM4-Q72s|x1(_)FT zX_oakQ#Txe@@_N8Wy-@+ziP#qf}aY}!{~)A#rTlGo{JzZE1#{K3R2{xHjd~vgxL8h zK_^&TFoF)*K*DAVO+9tpk=tgD+=U2?;12|HnZCJh(la>abmPil>(=!&#=M}FtA6r8 zce6O0Wm=rVwQ(ix*pl=gpR)3US;Cn5`&di@Wj?YnQi^6Z9-EljT(J;laYW620MBY? z8P?<TI70(Cb7icS%1!^t@u7kulB1vam;ASxJ7cRJ(?2_%A`79E5+_Q0PQ2J_quPOR zE7I4)j&CzpaK=|%Y&_aqTv2Ru1$QBa!4}-8`X)?RT~X0eX&n6lMd^=(@Z&Dn3yR3G ziP~4KG<pz*!7QtxY9d40X0#U5Z&qsTL!&*WF5@YRsp6zXJP#;g!8A*>gQ5b1fU;l! zudS|b%7<AehC46wN3)Qd0CD4fToEnq#;|&~+xyDOa<|6r?dKgFs=SvrX(M6XN4`E` zzGyX^Pn3%=w4y#!4I(*!Awxp|LK+w-n-|_?BW$343EGQ*v1i{tJ7p23xI?K6_1#<~ zRyOhgv@OlmbYa>TX$~d|CbxhAkfodUgMOi+<1uL&>@Y$jv3I@KKWf$(&hG39HX0vR zFL7&vx<2Kw$t*b7(%=3!^T4PFw%*YYv+Mt;-47}4#jfac8h`B1Ie~yz7X>c@!T$aH zD8+ZpQ)UgoLm?=#L^OtyI_j<<P<^Ks;xEMG&@g5owliLZRCn(4azJS?Tdo_KCj`wF z_bnb2{t0_HwDM)h5jq{BpGK3=5{+sVac;dT7a6|2i9lHL--lSb(}R6Ni01m4y@X=- z6wBHGtuwtt8o-)Q=<22^&|o<JM6qZ4DJ4J$9kc+4keEeM4>%p7%p;tMZy?|Afkhsm z3O*{gbT|bjptJ<~B7rm&R<a0{##Y$UXo3)SpkFhWjhRGV(E$F@)~Wy}1UTcrcyBA= z?g&-PUG$P1A<2fq5TaCNF2sF_`ap!CiqJ>73cmtUN5`WFbO!ayTqcEdk`eS=0qT(3 z4sRp?93!T|95IM;`H9M^ZHC*x1CUQ(TqBzK@RgbeFCt>#08LDEGas`BtYG0cSA&;< z*3+m3$mGk>BqUT;%y{HlgZ_ywJT9U*EDe}2WT_@e9|~D)4EzVk7_LuLa(cMT#Zfi- znR}DZYwJOm1;#!-=vxRMVSR)z0nWkIYl{g*u<nC9m12_SCyj1ixL+`B@X7IS$AA4t z?egK64>6+C=+|%U&Fi4NyL2zT(w}_`$C0PW$;tnAF~&m>-oK)Dh_-!fz;%4N(&PGX zlGaVXZ9BP9VpBHE(UAX`I&;l2lK!Df*B(DM=A1SYE|OWV-au6d(3_(v75?-kVXHF2 zdu8W@)Pzw=g0k;yXVe`bdSiYt3P9i={F2!pGAU^peCSB`FE*DxcwIlX*yNSuW4oN| z`TQTXA7Vz>OO@lj1rB3THJ%#5PH&ArVu*nf3uVeSsyg?@$DS_iJ1qLB;mMU0(-96N ztn9$STH8HKqocL+<A`BEZjRXZ-UqQtZ*tRda1DTiBn+?Mp`S8^yC`qTA}%Mn1EOwu zdB+7ZG!DE*+z`1Z-MUB-kC7*sGTMCeR2mg-typ1X7H{%>EnHnApL`Glio#Qp`nnde z`cZeRCjyYZ+bn9dkfOW>p)__+aUT2PGJ*c@5LC%UXlHTnnH0YqNg?V%SSOf(Z{rJh zeoS7IkWIhu<VFGHvx){PZ{$(gh4e0jjG!=24EC1SzBo`|iiaX5{ij+{>*iM`cO)ON z?U5{Tt&b$+gcj{$>3)!8$nWKEt#Wm}rQjX5;Ur=M3CX_h<Bys(pAphv761V9UNT0r zp;86{>!S_x<i1M6JxvsNtPK6l8qy4LBVFbT!+_>9khmZr7)*^jYcmLDJBFO%wf^7; z_VR{B2*i@-1+h!mmkDVJhs^cMU$bpVU*%_%eY#dn3h&dR`Lop+&hE4qS0ASd8+BK5 znvT=)KcCEh-Fuf`SE_g%t^C--E!M5V^piJy`6>Q6ADugZ|L})5`Dd9Xo6CB;h>>(3 z4C77Dq@-49_Kcpr)ffhk1tDFwC<{pziDk^bmUI8TGMY;0>lCS??<iq<qUg=P^2{pI zHPDcu#YJ?v56KLCEU5nW>nUbPt`Qe#7?&jI4IBBx^XmwBN<h1TVgR5b4nLm#)AuqH zl8na3QGYI=jDrQqvjjLb@tie1<*>@0Z2__hl!Lgq>b4oe*iRQd$4Nq{>B)|PFpBUO z;L#ZC|N2n<2AjH)``FUhlsR0cMPEoo&ok>rnIq3i7YQ8z%j$z=<F}re`Z`s=x(mSu z9VWe?rH0@d@rd=!{M{ki<9%{!WciYOhP~~yp%qc}Og_&M>htx~F|;zH$&kI%fP0mi zv-YvS9k{9}mlx1#-3$%Y;*+y{Y2`myveG%){~cTjZP`9NpLP5iR?;n0TimqFY&SSQ zEax&YmKx(H4b9c4>HA@tqeirApp*@ABE#q7EM*y11|BkByvQKZ+F)%@4>#8mj5S$# zI(`HJIB2K)M1h+8*f{H#Q^@`91^RYJZqw!H)+=6<6{~tTV<vMxO8>k&{E?G*;`VVR zTgtD10D<$-T;3)zRK{hC(pXw!Omd0mTMc>Z9J>ETaUJKRpRslZSI_N(O(C{=Q6rG| zl@51%Uf}$>wj{Z7rOyAj+aGL!^oCf{aXh_e=ugbeq5@K@8w$F?N^@gto_^&b==eHz zy*$cAf*c2z&j=xBLki%BJoutdAxX-C?ycdSb0tT3wC`sf%J{q>&r)>y>vKa|#t%%L zdr_r#KxEFC`qYgjJq>Q(*%{AwJ~f=r<=d*bUG{f*Tget3PoL>hwmT1tuF$l##@J{R z!u&R{-(vHa`ehh{GzI1?7(tW;&s5n9W8K=)s{O~#`1J0*ffUUvZgQ1?^6JRwLpxE< z(L!NRDmE39UWUk7gk$Py)^+s$N>-of^jG-i#*XU`mLwYBrR>q$Vc4q&A$sh>)d%MW zxEtEou><UOUQi&1(bjZy30g#NX<CP8Znz7E`pH*wRzd+vwqa@}Zsn%6Z?$!NM%Ni6 zC3{ZB?u*6zQdsvwpen`q9cayfINYA|11N;e<I<S0QIgxCw$$Dfs;+_G--mt`AoKG5 z;OZ|5fl7PuHs%k2C8_9h$xH!n)4p^bTL0`oZL1}(SdpZv$>B!mN(}$Hf0zI<LV|?n zM(zN~u57VOuOub^`PS*iQtiu+oUhX?{{sS|L-n#F5}GAV3ByNj*!Xml1yH4@HS-hZ zMZvdpb7XGFw~Bsf`Y4Ik8|}7igRw4YO#{|54Ca6p2FO|AgGoyp4vPn0e)cUBZ;%{$ zv=xYbk>oiaUJ28Ndm}*2jI+1G-IB^9#=DgSFmnbtfK|eO*a<Y`6ObZe;Ho|#P?S{- zlmuK9cqf4<Es%zsM#BPTguU70s`LPuEj@vXfEGc;sIy3GbWEZNqv+pYfzH=n?s-&l zfq;<6%M)^?tQ?6P5Xqe|xaYLdF`YxC>f_Z#re1)`VIDj-krh}&DbjlubFazUTl#^U z$_8MQ8VLwOj<cGBZo9#pbx0eX34;Zx32BDIoe|Oru#k%IS$JGXew1K!;-Vt;tSWvw zqC@l}UML)w;N)|2B7EeSf~bTko@8fd;HNnimzajzbn_qm^^e-($<sO*Ds+()bTDE< z(vZ)31>QdW7<T~%r_hJfzPlOO%|<1PsBcb8T8CffS07RQyg-+`1NNCB6AXAh>-^#M zyHB0#BfnG602I?DoPIyxv2&aPxkfG-6IZ~Fn)0p&ZQxvKH=+9l5hGzKFu|E4w<;p& zJ<3+R!5sKiWwbvk3(5EenQBvaIMe8T9pzORn<_DxM8!J*PaRsdBI|&8(1*HYDZjcJ zEn=C{bId{JrIk_l!Ue>aQn+_;pCEkn-43mxJgi>$@}(l?X$dwjlg1CT&iY4f5&uzJ zlYo+N+>cIj-J#I?_~FN5Ow5Y4)ruB)9t^(LeLF2e+*=%}0SouGXOyMIT_3tWXPpN7 znQ&GE{j#3DxDcu6MOM;$%K!!ef6le}f+oWOWP37?{-ZW0;8uY~J9Eby{&5g}p~e4f zjB@Fe-1gn}#fw>}o*~`FZ4mnGZ5K}6k-<OV5QF)5{Y;nU8#;k+O~RErfX|p4EE)*t zumQ)qEmY&zlM^p3M8NvAPb;no%dsbj;Vr0$yT%1HF=kw2!&vuZnKkXV`Td1&*sf^h zyKT!L$}ah>Ygo4){X(!Dj($8G{{I~oCS1`EH2r`<WvHylsEPPEi)Zt<?b#-OvJtV$ z3|lMin<#w%a&>fGT61N^fe2kJY7m^L67^OVu@PiQt2H<KKs&=DVgp<Vp-%x7O<8n$ zQyo~(A)0I=6;moS@z<_OfR(4LgxzRaapub<x%gNO#wox_g7im*eU%P^f8W9P$_@)~ zlyDI9xlSv-lCq=yLehYwx1$7$Ks_l0+LuER?IVL`UqGA+qIHKSK&UDFj<TjS<D;Fu zLKmxE1;RdF!&SxA2#=cNxvK#40O1!fa^dFgdAE@EjOTqa^D0O0F`y16_~b(O&XUu5 zd4hJB&UdtaK!%630XU5Gj8dFQC`vpZk~;AG!^C&9R@l>WOJ%7Wy9ArhfwQC7eCHJH zsfEbJnLob1lw=z!(`?7m$*sL4sl`@Iuf1yOH?7lO^3{Q#W9qZTwrG#A?N|Uojdzf9 zEACM)3b)D9CE%E=N5#mQ_zeC>Pe~(7ez~Z~M*=XBSc&L%z|um@L`PVk(~XP)YHI++ zJ(0oa=e3}dCTWb$f*=d|CpxcLfm#Sgxp>ckw5|#iUqCq>u`15UAx900K5Y6b)coB; zrcPTucLz$woY_;!INsaPYj(R_Z#6CD)4|R&e_r*XtBxCt(hMk(Y_hJ-(692F%?GC+ zA7}IXt>Iqdh29%tM$=Y#?Ze`hR0*vNR+I#$W8=x5dXC`A2E@+I-m*L;EG3rBVEmUr z%CyJ$oFLB7cwUew;8yy`CyFdGX%al6GQ7=rG=?=%({w4z8G4=@)ot>WK8j7^VbfU- zI3nQg`)+A_g$e-U8M@H*8uz@`wM@6^2fl4_=|5^V_<1zK{qw)>f4_>xe|Mxzk@K#O zFy!qB!~F@<o`qR~AinXugBTrA>z-4@&#%0Xj4xi>>p4ulGlU&MLA1qi)=~)j8W<=u z7hjt70hJyFUHPI#=#vq3Mv%l{joZ~!{4!Lc<v%d>yE2E|t`@4{(|=6cxNgEJ<*uFf ziVbrYUA20T&ujl;jvbOYSuO8}MTS=Ix#oAEOa+~}JgP2hsS0m@VRsPvHDbGndwc89 z-=;D3NyZzN&(dlaEkrj4_6{>xSj$g(xK~gtEQ*>TGtyN%Y_vl?UYB22@a>G}_%)B2 z<GGBW^bR2)Gvv@m#@lX!VxVp8^2@C2SkTn(jbVCUxpWEDFO|SQ?Vyx)ADfFa`TRlh zN}TXujBlydDegFQZgmf@lZ`Zb*4OiZTwPJ5Unt(pU&%>>Y;5ajb*mNd$)dg^{^8Nn zM=rl(>++vM=Gj^@c|E;sKKyJ6!z!wcayZa8$5Oi^mFGp^oRYlLmEb9&*zTuY`aUIz zby_CWCG2QkTzB>A>LZ`768yyC{182OGXVt41t>nmFy@$TeKNGLTRecx3oM12d;9Ps zdW8hDPO4$!@@LKJ;;`)@_~1Fg8ZNv?_IJ4pas8t<;vGQ9*an#SCkc9lo&^Vu$Nm%Z zF2_~3C0BD4F-fBE4%s+<Z_2s3Qaeyj8KX6Q))+7+uG3wlqfqkvN(Fzj6t)?8+jCaK zywk&(yU5sXKU{6aLxP08sg?)P)S9K02Wem8V4MLNa2V!ok-C1<bin?>*oSW+UNo@g zBz*tY4}3)o!BUAD9gRr08j{K9z(IG{E*ON%bHM(!Jpjy_Fa;D%g&0^q#eD@uOA;_C zK3cU{9sX2f_$kf(2JoR)4>yOeSBr30>~b_P5NRQE2{oDnBq$S55mEz2;$C&7IS5|R zwl(OfF^?;&%!hlhW&MFZ2iYMeM3&1uG5=%V{NvrLanvqGHW7OpLtOb+Xb<e^lblLS z%1P)B?z!N8fh6|gM(fs@EZKD@OnW4UwJ$@8K4oRH#fP%%`F>rM*zZA38$vJ!-rMn) zUc%bSC{(;b%(l+C@{Wd*3T_z!ty_kK0Y}E2J@r9`K<vYaxykNk{zPL2N_h-dUC;>5 z26P%6U_<%%x)5?)9Up}}yA;$Bu!4|BU=P@1>;ZlFk3cPP*vPf>Y`;{$2GVyzD|@dL zBPwwC;@0SobXs#YI)rPVqL#&6nLa$#RNmI!R|IN<;}ruj5HAI(5zj|{?+(h(AZ;~M zLP{7m<bc47><|~<WGn;dIbi}#$C1W+=76FXU)xIRBTc3<x7ne3XlPf`!ZnfHcq>xX z;EBxLh9gRxJxviFf%)jns?pgPJD-Rtw-=^kG2jVZ-Cej`>d&f`z$+Qob_MIw!TER& zPnei$8~(7ZPSOkBJt77|P|x}wl#S()I0~%@j#`{9Zq@y<`4>5F56ZXT1L#i`j|+l= zwD_v1S}pUj{{F9%!8!ulv4c@sU!M9kP!}IOxI1cqpjr9V*1VDJSybgiE+b|-%sr;f z20o7%+KYFLcvn=)S`l($Z2CgUx(~+sh@uzJ>)=S5l<c-0=U=pN?gyGo{=5{>rMOAN zO)4oI-*xsxv^4%MI-?XA?zTJgj(L{sflq2h_z>wwJNGkO?st{M`ce{4|2Tm60k31@ zd%fObUbX(kz?>|(=%X*j_F{W;29!#6T$qL$TOycxU=8guoN|SIZO>PAmBgp@GpH+X zFjUP&k+rZ~kwdcq`9$ldJz#0cpH8<{{^njk+b;Oa?KIT5K~2@jfkh=P)ib*%Ox`f4 zKN0&W@HZtuC82Mu(k@q|(0r&$ud}f@l(>U_4IR(;JE7AjG0y`SpVk>^pw6>634K?< zgHIj-cD}L(+9QJ6;HIAy$s_D$It8|k0q4$@Zdeoblm`uqt_;H?ehFDTZsd01?{+V- zhfrBX-=wIP$ZBQtpO`fb9b8%wxy^zJ1>MtLf;DD;$8~=!zRig`a=*Okhf*aTF1xDA zXlDFayv0|YR1A%h`s#(wf9G*%grjx<7yIxU^uajuXUnDEy#q-p&t_VTy0Lcg^z4@b z+ZIwG^;LPs4&FZX`elv!Z~mNIo^|hNiOGaZPb9z}$2C<IT<lNw!H9?v&jlflzITSX zjNTA2>LE1!C#P=F5}Y=I;Z6V{<U;+<HC0Osc~7jim`HuJke}oh6jrXvW$46VG$(i4 zGUx>Kf#+PxU@OzN(Vx#2`kEs}V#uOozU~)q{#|(*AecYr{`4@*wn{{h8z`@%+inGY zWS@<S>F75<@c!U@X%BZEH_Oe#iV$c~F9I0XTsTr3jJqI#wFzzjKS4c(tSgZ~an+{f zUef!f8$`&%ytu%Il|@MxrW3jVZJE+11M0GL>xgmzyk5Jy(7rbqF9RB)!riY;n{)a1 z#+%<9CM}wS#0LijDjkEgaI7~NeM9s|$QFXg;K$&uj}3x8kqQ_OIw1Mn6Tn0-$20|} z5RnI`pq`tkEg-W+;}N@4NP+`|7I$2c)BP2{9nVmTsyMJ=Z4eQ^6h27wLy>tD{`?Vu zm62J4L0u*ZaP{<S(^LG>8(-gkaN@JepoRaAGM<{P>A?nvQzit8@idv)BUS>>1P!WX ztz?@Fi{ECYlm|9Zf}d8L{>oNaWYtKYHcXpdM~$vdg!fIpN+US%2kAj%1?tNs+4sM{ z7+3J)+a@>~xDT`AgO&==Mj?qtp~q%16L~rV%?EHzKs?2A2#icewvMa;Y8A$s<T9s? z%$ucUZf8@HP5V|pXH$a#fpL-Ru<1c|otBp+nsif!qH_k($Z360*I`Z(vkxYioAQpc zbyP<lJyOye_&$Snq9s)`YTdkXbkC5ndu*!bbmB_(g#R{&?KBW>76oo1Y>2awtRhs9 z#2#xpm3FeK_i_T%k|@~IqXmvw=J{k(qQduUE+WJ@RpS6UL$oS<VEuz1j*q?4ul>bR zsVeV9!g+Jw2h6QN-r}QY1H)tx-SEl-Y5H;h11|w4En-oq4>i8F|I)#dJDj8K(r95J zY|XICv!_;x(uG>92vZ(YoCB5$A`peiP`RY)!f+WlWvZ-jVCv-dyl01`Op6wfMftSx z8vRkDsH$el!zwQ>vr41WIUzWw=fjyA>d!01P-iu=y7LUO>h73Me}C&;#@`wrwt5xc zjZqi}qoAEO>c4Jd$DL*CyknUn?X*AUmOC5Q90T_`YMkY8bB67=-)!qM{()<)c`>;d zn1py}8&yID9vx7t7P^8m<`A{_)@8CSVK6(bo4z0VBeHg`R^I`ML>>Zfi4PcA=@45x z4}*|km`K)Z4oH;6`{wN4t<8j+R3lT>E`1NuO+4D_1<*h5!XVqAMFxav3YlBDIcK~X zw96N^0*HM~nd^?N14Nf(jFty1!C@cKw_(nYN~lf9so0wVsqdmy3J+7#dL2N!ZZ3?u zS&=;Gy18~31!8I0kMXsMAiHZQ&F`x>#}|c-WS>soH@}&FkN@$zpt1hoi4L3kiWk6t zA;HT;sv-NnYIJPiYBB!{7Xc@^t0v0@6&WFZX@_lRY)=ac`()<+JBr#d&*P1!d&Aif z!bnD2{V#ugvuyU2mY5+CxV1a~tEH9IO7*)%A7fHyZf^fn|L+LxU*)I{kA>6UaHc>C z&#(F&7Q5lwLC?3sqmSngo3(~z(30N;-e39kaY|)WT|V7qEH}Oi%4m$hl~3ff-fwgf zD)TEAYx_63T&UyGF@nuCas2X=s8<Z;coCD6!qC2yfl5@9-ti#BvM1`&?EPN?BR&Kk zXK&DtnxR*F7V*}M6=0Ao)D|ew4m$S0lYG`BYNG4zaVL;(5l$wfKjb;xy7k0e#^-7> zijufh*Jhr{jD`<>5@~DQq@Xh;-!N!kL8E-5m5*)D`^Lr<?;oBEDKB1P7A1Cr6ZHay zRzVA@%!kjmdz|yynq7X4!oDV8{pB|bwPI^IkcoQ1{He?m(Qt4=1Q+kz^f{#WM4s;o zwdJQVof8%04^#{T1ZDCM$b^!kOr~T1f-^e~2^wh7pc$QiHUYsanX_T1{q-U*LQ~Fw zvt4ZdPV`5zmMJ`_U>IL{Uxs015Dh4QQz`W^J3ToqxqJ6+CZ!86vP$j3^cjH%T+hOG zL5wr;-1;554?o{Hk@ZQ=SOD)}p)b752=}ux?{q|=Kqm(QNYNz)GbHYMcl9ROp++Vh zysmqBqY>Y8J<$-37RbtTZvL_Nc)$LL%84R9PA^*u=-=NwZ$2vYKRM#(dF}r%F2N5b zPrdvMNH@%4(mC@2r1X}X;Y8*(Rlfd5|6pu!FiRE9{8@EpH2-ivZ6Lz(fl-69U0jfF z2oo1njNTL^qVasBR)eVlps6HxBQ*!a8KsNH6ck*z)}VjFP4#c3<bixCK5h+()#kJ) zv@+OOI*gvXZkP+F()X{vg*=eeiJ#g_(oCzR(Dm!F_Jw`yO;hwnx46s$qC`bcGD<~- z2B8aYo;VY;sc~yeGn9*9%Ep-<N#R<nL7Lrx8<zkg@xV{A@v)G)IbOsj*{Ol)27vPL z$%q^Y<K9TWSxN|dYv3vhoE*ljuq`~MmY^)hfU|$p(8yL{EQ4u;?_M1MK(#}@Qrtb> zf2*JLOA!x-v7QAf`g~E-X^1&YL7JIXx^whG9*woi>c$;26anJlK_hJlN}(LW^b;?* zhFd>RVs!3^dU)US*x0j+V)RdTz^C<$5SKa$_i^K*k88w?@kO&+ao5ynab`)AnLgQA zRXTHACR+3oeLP(`E>3Idy{V!muM2;-CLsSFXeSmL!{9)S3>}j0l#Z~G^|#s`KCU;} z{1a*ooOfry?}S=knV<0X<8NcZw`}=O@wc?VjIY0JtyZVmWHS0g;dO^xw$#?T)#krh zKxUB2*A=|@qC5CwNcC4lV~wZ*i_Q?+@k0Wc*^`^alrwcavVWS;?Q?zd{eiezzmnyg zVRej}rv?_Ty?@C^W?blt@gW7}tmv%Z?}1yxG6b{@1a*$0sA@5KoK=z5vbvfkLFn59 zi?0Ai^ZT!I91x<n<C!^^{Q~jUKRe6~jTZLey<;gLmyNEXb})7F{AAS~LhVq$wD#vb zwd!K-J0>-JTaQFviPoAjzmo1gcJfk5KPw0sYlqOi=w^noPhs(c9szCf+pZa_lBoan zNS4(VFsjDBzy9|1fim3t*p~mOz0A9A@?GKB2QJH3S!IQNruSoTA?Jk`X7xsBvs*TP z_Q1yS)fZ>jzw0cn3Lkb4Uo4ehLExD5Q;Msi8b&KY1zJE-FN{1BkDl+;n6diU%ZEs| zvLGpBejYQ|(?g`d%C|D)D~3h&t%-vT*t7sh;kPvG-#TQINpB4WMHHCkaDoH_8Q?&O z%1u|SRGerR>NR5yBK%vCH?*|HuoT_z?~gpsUPuoj-PmTh9L4pCs9_-x$x6_<pRE;z zb4;036hs&bk@Go7q&Q{0#D`CDCco)3`}bY<rf(5LQCBl$W9d}ln2wR2lc7F@RPG92 z@gQZ<y)6rSB?PGzk|r%V7VC$3m7z6FW;i;2$Sra{XK8^%L`nd7ia7@KOE#EEQCA>? z$zafD9grnqZ@W6Po<^JlSi%=SWP$KSIwq2TIr1bCsf<As&%zTVDrdd6mz);Wui9Z` ze_|O!T&--%x0hDmJDoC$8Vyu8e_yJYChX-gL9pLchqjnfTvTEdzys`xAV2(NtRnT~ zp&ny+3F?o82zAA{dC+KY5Yobtfpa7et$M`6HybBCja%R_Rf@01bDdg>mF}lW{_H^q zs#*U1*z%NGTY$tY#cDgjH2gMT1x=O(O_?(M7mhsH`Z;j!e{jr_76Y<C)a;-mp(Nly z;QY3trEsfWQYqrGOp{3C4P~yXt>#?&pRkhjv;jgrEx@nld~o_EF^Bo-L^PxfFyXGt z&wIC<RQs;PUYNh*jLzD|9&Vc`lJ!66uNdz8uelXm8O$&Viu-UfG<z$~CEN!|nwjzx z>Xm9ly0cCimnTn`WF+Vc`}K~u6N4q9-)u5(H|@XPv?3hHsw(837#x>!Wc$(HnZ>i7 zh8Tr0FAUtEGTbuQW5c&Se)WIM#opWiyP4VA{0O4eA%9*!)KS`{5Mkm(OT_^XJbfnS z{(LIGXh#~$C}gl|rkO0fD`*S?^L7+Oqa%dwppr9~=GDc77aKkukH9FR*or^&|Gv`A zuL)9ya2Z;hN=#8iSuTtjmB3B#Yx(XN_vTZZU*kd7;602B4>G~(%y0j?@A|9X(&{NS zd-3V<{?_5$8d$$KE!89AVSEyIUdDRhnuttInIT+QgETznA-45hzJPF_FlLdW@Yt8D z;|-g7-*JqaVRffB^}^HU#s6XfajEgVH!KHY1xh(X&t$xDAKF!FL>cA^BZZwy8|=Z? zrI#W9>}#-Z*y#dKg|y`JrO`q=v^J6cxkRRdrweAOL+pa6`m_uo>EeU#=`#!SKkrZO z7TZH*oRee;?GlNEm6@O}17KP2#v;@}8_PMM@WS$5>RS~4@G2Fu;pi80SY2c&w&{73 z_Aa(5gBmzN|0}Bfp4-g1K=n&$w1nC9&_yhyv+pU(+MaEm=@;uJ9~`6HJve{n`rCqt z^3(h~o`N8_XwN`_i$usnH*d7lO*w+tp&e!$vTY_SFJwpSn(BsprSNAQF>_f?ciTty zosgY2HrhX1P26^48E=(OE8d7<T3R~1aJS$N?Lk!LX3jFE7H5!xzzH9fjOG)0TL?uC zd&4WPF6<rRCmg*fT{-1pIeO4w0MIL~`|}bleNVyLE@O>*Zx~urL~}yJ_w}{abH1qd zs?b=*v`Bl~qn$=t9o$wdf~WuMA*Y*vM@7>U+}p0mSHUIdf&v*yZe;Q6Lx=4i%a4x_ zoS!tAGi2{}td;AA?P-hGt19zdBOacN5_ByH@T6GMr{Zr>+Tpb!!rLIoV^82%!jpnm z86IOBnnb5h>vi73wkEzvJ;<3Zq;Igv&-kSgeLJO_V?~bZ8pWG9yQaD%FMm5d_$3Pq z=b=ZjEBSKvV)g%G*no$+`a)&Vb!3Q`{R2U;0pth!vC{T;H96{frdPdQhMMwK<m~0k z;nwJrxQkzzw9uD|9op(poIlSV^As3~yT8`Uti*_;emm=KX20|4`4BTqJTJY{%dOb% z*=eb5rS19aVab+j9Ag-=;USfKMieooMlsz6C)c01`jt)&=0Ach>>Ws1c34HpyUD=W zCj)IypScJT0&@8Mf_uP>#N^RX5*<@KI~SE5>#E3ZE7a!;wU-Jo0bIC_OE`&N1^*kv zLV#kL=TN$`29QEQYOe^$P>y5^ra?!>$Xvo&oQv-qfG^L8Io=1Q#_<OY3uMViH&l*0 z|3}hw$2EPg>!5HEwNh|Z3&fTnL%}0j2Mq*{BP8kxQxHMwphz7Q1ThFiv8`fjB4L$! zOeh<n;J^V`sEWn_iVQ)mh)UQ35@u%a^Ue9=-p{$`YD|8=?|9$meFmmEHUy>c^U_ZU z2I=Z$E3vAe;r`DRvWqFGC<)d}5KPqRLX<>apk}HY9q=kj(;(E#sS}=BHs%r=7Xe#B zGhKEN@d()Ewr(YAZ~|F!Jqu7X>XQON6tw{3xe$v3$*8}wPjrGZffr>2a|A>xjt%He z|7Lu0KKOWq$O&0KI!_SyG_L{u;DUq8QM94@Mgd$MD6c+>GpXlRCU9Zji<vI|G{dp_ zcmAVhJUp(U81rvPFL9<_jw{Pih`+<M9Mo1N%Q6|>7+6POglj@ykF9X}@tAq%{i-5| zyA0|GU6RNG5~PC#%BY&M@)yelTg2Lc1o`X<m{lyozw&JdB+ax$9z=dPw%cc_{M;C7 z%i}2EM4OM17-Y>cc!IQ+NL7IaPil<T7JqU~vS?ApM<!k<`n>zMJ|6#hpXrJ57na0h z3dV|Hh#}6V>_WnlU}oNlt{oy$%LRk4SautN(|o)O5L{w;3Fl8avbu<PQpy-rPS<n= zTJSEEs*|ug;W@4j9SyI&HhBB{_-dZRMs<xt6)(}r_pG38IR4uWBO`CgI2aXt0VZw* zpUG7{1y5mbtGR&{j(PB=(aw9ZN7LT+(OSMC!hC>l5$z2(K+Fty6!>V9{Q-?SdWv!X z^TOe3i++G171n1Ogp6Uo2Ut{W6>~CHv{7sE3h+)9ruH#J6Y|EVb>_BB*M!@spWXwr zLBvrfsp>{M_VFCHox@@DIBmpY$xW5<xv&0ap*(Xr(Tkg@;(vwvP~Hi_`I7zDT5<XI zih)Kv^l}-o%?XrPPM#)na|A8F;YRv?a%8&_x64Fhedn%-=_I<sGI?O4Ezj^Jum8XB z3V0ILz2w;1$e?k0C%aPRkY|Q%QhjPVIG!q|gDKijCWhzHO&yP_Z1?oZ$*NuO!63uR zH-3MvI?<PZvfSc;oQd-vNqefg*Uv)vD&$7fZflJdVP@i9q<YN#qDL;fuwF`#Jwzdw z|M7`S|IjxY%+L4i_{!l}e!yimhJDb0q45;=Fb&n?DcU<b4=>&Wrkn)qKCl;2W_{^f z1JDs;>d;|X>F|Eb?>1ubf}2`_e|nd>S1Zl|#66Sn#Dsq+$UGu@OBCq?tz!oEf*3g+ zl{+H?o4T!kZEA_OB}*5st3_7hCJJ5^$?bzbUs^-|F@*(y1HhLz>e<bea1{WmP2@-i zRgZ3(#O`o^0v9#lwW=o*&TSZOg%LjsZntD=(9{THlxchkfa_x`*k9+~5oj~p{cN8^ zx-)q6i@I{`dF$exHTWW$)`X~JV)CKDFLv)L8gj@%#n)djf}$~WUuop}dRZX1U-h^b z(WvGJcL&91hp*wGjyaBAd!Vc6W})^u7Cn*c{G8X}o+8!9M44%|x8a>bc+dKudj%`j zV}PeKb8W$zchq$}snhFNICQWo@VuaV9#!MrXZ4!uVzA(L2H_QoPb_E@U}$7Xzn0GX zI9rHpYLr4CUb3r?K9r|1S}`Nrg+8xCg4t{w?rK1^n8tRCvHRdO<*B{VpwRLhZ&V!L zXdfU^eO28arfW0>s)?J~1FJg%Ae$gey#`^Kqa*@kXEfrfiAJf}Z#%{#t%u(VD`XWs z?z3i>(Kffw8{v)jzbb4Z&8nGs2<%8StROX9X}jGRF;{3T)^a6;yuAs=F^tKAsX_lb zulC>dEe??RRC+2G6<x}dc&fu6))6S>dwj$0-l+`($v1z^ojT<Y+5@5kmq5co9am;P zeQ$J**5r~QcJ@XGSe`-h&J3!#pbp>rF395jFslo6p%^o;DlFKFHIH1DiysC&?0Aj0 zP5Yzh-q<n6|HKaPTtJGA^^L_aUK9kvTdbk;eKB+NS?VlQ42*HejB|;+cjBkhFV;70 zF?I#>AvHXkn6BnW>!(hGN)DHM;G?@>RYx6d)&&+cWF4O!>$6t5&j>EU^g35W;FgcP z&4*4IRy;-Dt%6Cxwe7iMHYvj%Uz@bvT*xw?VGPixT*%z!wiktK1jN{$5M3jQTiMG5 zbg}{IxjmjeKA;Bou-x3NnC77BlO6CX%?x5Jrn(%6p$4YRH2%3h*qQdtnVTzzyOP5K zA75IO!H)&7dn_T46WZgbax8hw(qQpN(b3zwFQX`MHDv|_9L;n7Wfa-TOrl+MdV<+F zPS89`{H~9dlNHbJE~YR2PZj;QTR&4X^x-r;f(=<332vh5<UK9DDdCGS-m3un*D>EC z6nP@)e-33l%QDI1;kz{x(S5;lt5+YY`Q)bm$oSvTY~cjJK;brdjE;e|(m>7LPMRsI z-q+F1{d<;cI+JM#8SND(Qp*#59F2VNAtREx_Ycft6Ip042_uXlZ~im(Jr%SFnQ%SM z4cuNO?5CQBygBBGGI~LG3%7oW&WZd3_fMR8AY|!JW*koj1TYL3PpgUgZRZ`O4^}E} zjzD$g;2+`TohJR&fywtsd@s8*(q-mb&M%$U7v|s4S7!VO`%OUu@575OT|bB3Q;gzp z>9qL%daYTtuvyDk^%%`<cS6JTrF&~$a>Wp-@Y$oQeh$_j4?e$W-`6Vlp$W_jIv{<< z*f~Z1qIo{EJ8qN+KFeq)SG>~NYa0Vb9{gSAxQ%6f6=Jz6xV;fgR#$Y_)XwW})-Y|} zdDsUpBnB=ATqr^F_8p}~Ng-=+VTUZTLBZ#ZyQc~1ca^rMylv$u0ZB9Hbc#x9zetb| zQ3RIEI1iaXEK-;6=qDq}{T!B%-*)ylF6ToQP?V(FPbG|AVAi{sQ0c(M@H}NcP{PS; zF!O>^3D{W|hKr;ooSqP9cY%et>ZiEJ69`g;u`UXRy`w7##J3iM@rXTCq5H%N6wv?{ z{lZ88ZHy|u(SaPAnOiP!oH4&Z0f#Lw^u4eS?#m=T#@rL%#~P;8MIU%=ENaFLO{IgO z2|U9{$R_|{^l@;XKGOhv6*g=|j*$AX>{#%&24At2DsQrx!GqH!uc{Eg3psxl3X+eg zNaezfAaAweXHRZIV6>mn$vl`yK^aR9Rc|x~l|my1-e{1`OD{0NR28sQa%2ZDhaxr# zTc!K5|NI*Dj4b@=lZ-@Qbsf)99{K3eOfVjIN_mXd996F=Ku1?oq|hpnK@Jg3Hb0#O zomV9V0|QYA#waWfd3PQ--m0>UU;>W^joJGie0eY3@C8IlRK8_zoUX~Z$xYz#Md|Iq zaK{VE3r{RrEO6*wvgUlxP42+Ow0&@pF?Zlv<2x0L=(<i28dva_5;`FcPDGE7-2Y70 zMmOGzo))zc$Z4;9THUBo6E#2Fe#VI|x<`sf8um~zK31$9zQGGSvTjb<Ph}Y3!uK5_ z9Lbbj?<soCG^>EW;VpERKv)=vcL9r~G%n)IQ1HB)g=%thVtRVNE2C<K*!aY^${p(; z?wqe3IdBYdvyA8MZ}tQV1CYysWr>SZ5R6vgW%L2uPVh|BNgLbzUQ~uZ9GczEPGmVC z6`nWHl>%+d^QX(tW=!9njCp>u(WJBE9?fDi=nE-vzuo@pGo0ozyjS3G5%(zdxIk;T zr-(6R@b1v=B6@udgK*-A?2jK8Hl3C~{eG4UH2xLXNEzPLlm9v8c4+i-uj${fyf|1{ zo{W5$_WXgG8*hFL`@N%)Dt5k)p@6bKc<qT$f9->I`&D@Lxu)E-!KJ-J_Pi@Eq+td> zM2wuN2h;G%Aw|^8$6xIZzB=HAm$75TfcRys^6RqMQo|8O1YQEr+0?SK+}1KMWjmx+ z@n5NEolGl!UKohVjvE<`8dbq0_ZNZxO+o$Wqd(+O9Bd9(HFlMmO<$my3<RV`x)A`I z1VSaR_`7W7H-bm$DFCHt=vYAuBM30CrdP7ECDTvxH5q}ZTTV)d^+d?XQg0VdRi$uF z|2i)CkD5U7y`V+nlA|Cxe{(3^(XEI>)WY^Fb~8VgWb9-dB2IUi?VGc64?KUE*tTKf z9IyiBp00PnU(Om*!(bX`tt#!EcL(p=0R(*XSI=y-w+3aMzX5I|+TpZ+cR6^!vLAs) z2*+$%VfBF)tZLQtM19{e6bZdL4`q}KnkY04n@WGeQOiRc0xcx4xVvTR{?%RFa6xH4 z*92A&^2Yi<Y<kC*0sSAAK`Y^SV=v#Ri_f*>v+&{R+Q5@7K-6*UYvO=qVCy_D+cyU# zI!Dpl;{%6;Q1zJb@?;t6O{nY|9n-g+gPJ56Ptch*#%Rpgmdf|KdAVKb6N%jh9&-)I zBM`vi3aXQp(G*$Ga%t9#t;lNW#f%3zAzkOY3lCW}xbQ&E$v|ogB(Uw`?pKm-$rw3R zi_9iPp~>_l^fsj5;#!5f8JtZv6Y&VO6Z4{hjSay!S<W@+>Ttctw6j-+q8mht8m<M- z#L0oybOOyc@Hdxac7Ljfkc??Z2ufz)oAcV}rZEwo$b=`z?-u&4D&+olr2UnpfK<_c zjNnj*xeDl$f5Vyz{}xU$QFNo{u}6<zx%4~#+4*W{|I0CO)X2#i9l2HTp@xT@Qa-jK zqiHzzrpTR!;~VKQL36RyiF}8L9>ClrgYmE^GVpi$h)zh7&FhpDD6|KX??(Cvnesrc zcmPQzNZZBg!~X)Hwqfwd*BAH5yX15{WIT|Kb_FQe>-p$Tdvj4I2jg4j2_WHt4-+;B ztvKZ#iqv`rHq{r+mcQ!00<1Y}aFE7$FliQnNnkgm6_7uJj~J0f8)@DvzULAs_xjbs zBge!oN2yyXRUo2Y6yp*aXm*zo1eE;Y?#p`*UA;#`>U)Mhgp`;@qx~+kX{$N-+1icO zQhn+n5MM$wdv^NdG$<B5NH3^-@_iC!;bSfMF6~Ki?CJin9EtOfXES1Ah>GZK!WZiJ zyQ2$C1N<dcdAZ_2oweDXjnUD)D9OfcJr8xQPAv&LWMNs=?vN`Q=7Q|YRY_M^b;2oe zJnhB)?_<}u(6ZSgPfTJhg)l|;(HF)0!5U;$efFtYT?JArQ2#qDf-$PaeYSnfR*SS6 zMpu@>nC-Z?jrn~@ZqMsm1T8?;qaAk})j9*gSi*B%nhuY-+4yzM&s>qH6lBsWMlQ+- zi1T3l68o}rmW}y2HH@m72uAAOXA{D}ul9-bB+)5osnC&Wu<LMLbrs=%bhTi#JuRY% z<P$KsI#RR^u3sylYGA#=m0<oiSVK|eLZ8$HCTJbtV^K%3waf;+{?wxLww75)d&nKL z4MU0Lr>Zo%Q$9UVlS$CY88V?K6L4e0n2k+<?F6}m5|5hP6?$6P<6Ge1)~K_x-7yXY zjkT5c5!UfHbEXqVn3ahqS+Yc24wgbE<;dGrLzi6yvM`sGV-6n}y-MSWBpnZ;SB$DC zKYG+pS$X?VG|dzS@(-!kV~<|TpXNV;`N;`~w*b!E(B2<kBi&D$>ci?fwPf04bg-83 zN%Xm{a*WLmq%??NF&|DEk#Xidi+`Pw{5E%KYM52792!A*m5thk3};IHC*oH;^x_;c zTa19I%x;NK+>Up@!dC)mLz*?EA-bvoxYN=8fLd^=6hhx)OXUBxxc2VEgbnR>)ouPs z1lM&xPLuaya6P+O*>>_DijhPXgr@B(2z59(8r9`xcV#!v_zKWKq)7%XmI&Lrzywk? zY8LyLq$Ev`y)T<NuxBADF`M0K{0c6L?)+$_6y|NlKUIGbpoqPBcBD%%72~NL#wn{F zFT3dClptNNos;OiZOhnKD*)FCnbg<9D?LpyF1vGuxHv=hw3ZjG427*L-keWd<w{R# z#uhY5Hu-v13u^8$Kl<nq4QS_9Fe0D(8!A%0P0wb(bwL^NvSpnot`ElK<pqD~P{s3p zlx(LEm!A<3-sH*LZUh$K@pQ)MfcO{+z=-zn{A}l6J|_sBMOM^O>hK7vD8HbZ+86K^ z$0LkFl@_@8EQ*_?66zqBI#X${)!X?S?T6GLq2e%TXa8Eg-}`CTOS4qXdT3Nyax|fh z<O{U<q&p_aFPbq)4qTzSE_nbgfTvqBM$u5@<{)Rs?qLCfm!kAYyQ+MwJ5#U_i~7N{ zn~H!X7iPWqDR3J}g~>-2;g|bSu~vehWL+ljJF6pGYs;o>!AlYYto+6p{+W?1>yK#S zKo}9`0<_cBPc>=FR_hSxl=^I*;|6kOi%<>Xrn8yh4r7p<5Td2Q8E6wrAvY%*vrW5M zxH2%1DS}sjlpa8BGTz=<#B0+9gX>JvH27;hnBsuIDa=7>1TPt!+(ftRvcXbEI|DKR zA%QnIBY28EylceIF~b#qi<=6NeTN;VE2mxn!)~ORqM?o+5B^YprDGsCyr~A@2ON;K z-Er@<rGGNtifa#QEe1sgE;6n1T9XxW{K8D;uf`?xjd`5B6IV7`V$_vPCqchQ;{4AH zy`i-4m&>>=QW^=q=V`fZA%Z0IPSU*~ko4Z`RhS}h7<VaLU!s-e)K|AwVLQD?q7;n} z@{qs3)v)+d>=l*)^1*Sy)nvdx0`N+E+nBa~>5lfy$tqQmH6cZqMLfc@FMFkZQoS^B zgSuA4A>vSW`>(MvF6;P@hTUa6cu=8|NMlSMd5yaaJCwYBRV3rI))=E4)pEFDb0E=S zS!>D(*Z)>pp7DduPx`OD;>I2+A=+uwLc{$hIbTp`GvC!ih3Smm<5q+s?dGA6Q$dxQ z*Re-nzXnegMf6nQQkP5nmvUiQqP_v%{@qyN$)R<|ig&#d?*_wKWz4-A(@tJ-^U>RA zLr<vx6!MC--SK)V7xl*Hca7tVIJ_P=vr*_{wAcTf!CM6N8l+v{<E+tMM+G^QhQfEw z*E{5l?+=I@&`7?H^kI7^$HZR{EdDNd)bB*ByB1S3pkI<{?bq9e*c(Z4noRVQyza{$ zZS*ZTSX_$tTKzB|M$BAMg4E^2faIJ#=8q^qvHI+7Rw^DmO8-~DpwLYx`i0S8a@&sf zVaz8nxC`i9xQ_XLBfVzgd)RtuH4%})9FV*)9U1)YTdN(B?HZ(EjjSk{_G2icF6ww> z>CunAt3EKQNNZL*fX-V>9Y<VE7L|F>CBC)uuI4p}8Nl$ugXZoDJVMxxXf@#eu|E4A z{UmtSR3c2+jZ3KpncW*f(Ix=;u06gr2~p!tCwE=fGBvQ&+w}nm1MtWI-_f;4tVdjM zVwBjg3xmJvng(%$u<~<%JO(jL^A!C-X2l7)3$crLVIEyU-1l*}lHQ{`Zx#GV@k?ac zpCNgm`@h(>jqZIttJh4p%lMr<gu671t@9mn;J7?mO=gTD%&-Sm6w)6fffKr3@l^lX zjp}nS1|cPtAB=h;p03Mqbox?}Q+HGXsxh{qCJH4cOj9ts0AT}n+yw7+u?Z})fF7aU z_Th!-&`KTe(w>o6wcla?e??yxb^&Mxt($=}BR|?33)D|XPbiJznn+205yn@<YF@LZ z2!(2L4@k}^u~Mc{l81OK1jndmf-qs)nC72gJEN$>@W+xbdK3EVDAr&BHvy@~98kgA zzuL6LGP5m5^+{{YN6a`t;g=F*AwTVp0>!bH1&}5q)%<p};omFONqB<!faIsrlCz|f zCvTU7mmvwfNwspH{I+Q-XMZ-I!9eQjfoSXGZlp3akbVtV$OL#W>Bj0LFeQtRLz;`% zt;0zYf}%5zEucSsi(^a<2Nv*NB%47n25AKj-^HV^B)w3$qMhk4_~>=BY`6g>GMPvG zH+Xes#$>P~JZ4o>=B6AOHi~to-{s>Ho%u8mPS!!(GJ*EXUDI11$`G^wMFoivl3L{L z*=@Oh#rvsWO6ZJtsyi<2W-(J9-0$J$04d|(3Ryj(f@Q*6alY@dAm<0OVt8~RFA{LS zv-WybSc_~Rw1M1&!kk!oqx$UbC4nI>1kX(M_+n%`9K=sit;+t#kMz?y7vx7ZIwsMw zq0^aT0TBLdHomd8-F(6PeT=s`)3yh*R#FF{Jc&dK*-D`Y2*(a7)3)UvUmICrGbgu3 z`Xp&fPa9?sEew|K<_I`ln=snEn!)x9b~ydQCg0QbtOEJSxK8ZYAv5oIv8M2$4lYh~ z*q6c@n^=|#GdVesPuQSBH)$0yGd!i{6cbbsZ#>Dq$Eq^7*MAW+3R7D%ae_b*=ISp@ zvQ3@t!(RwN2LT!)G!h<q+R`6*4oQ%oM?9N}ba{+(k`RGTM^0#ftrpN?88Z_~S`ZD* zab~4w!}Ao~31qP5EVw7Yydec*v1Mh%c>zX2m3(Bg73_V@MtFB!dhW_CUfeV)$-sQ$ zvG{8c^X<;uuXbpOUQy*fk_G=7H|O{#Z);wq+{1|OTBkI|{A>m_eX=@G$TCle0@t+& zHnzAjz3V)cY418;-S|ti>_nHgS<dMH??+gV-M}#sJ^1VjIuw{L-Ub!KJYlull}0n{ zILv{B)dE;fhMqY4z|r6TyFEc~E*a_o6;W^|)7J5PvXX&1l8ResS6lhg+He(dT}kI5 z7D)Wg`ce2NaemLV?YS`O8O60p)4Wa!3K};BOa@y8W!=VKxI5~HzHor&Dr$_5W8SY0 zk6Bisvtu!yx20by<yr({SK{-M6=^ph_LzlYC~v3gVw_-9HR*SCRPt&f+?bdB9gLjM zXad87=T6`FD>mcD=&&J&AsYV#ko-!`50%XYH;Do}y0>P2!oq$RMsq=VYsoSpPZ5eS z=iRLSUn)3Klr1t<nptvtrTVZ&93B3X7hzpZ0yj`3!}H^=xVNFqRP_8UNbLi4wrI~u z+Aff!0Z3MDD0$l1Y#TjY3=c|o+rXI`kc)+4E0Y#Iu>_~ct}PZp6z~L!zN;B+zG@5= zOlw4|D8zjRBQvP_lC^ppW^0PxKxSr;=#r}bGeY3-J=MRKw?@S_p1^AWy9Dsokk*n# zOTUV99|9$kX9Rn)`~7=@UuCJpumqS$>rih!)6lX%1?A82brrp&f6uWyNnO<_EV`G8 z(w7i73a&MdSmIv;nBo*W>n%7&;t$-Y>8>2u4<W&#&d<@34^y=$jD#Td=1in5^B<$1 zzkn8Jn9zLfB&Z9c{bsDkkMdwm^^d4(L`e{2Df(4)7ncBIbQELV0Q>L$FK?_FQzdNx z?{6oHi1Q{vo&-0cXtOAYRN&geO+p3;9P>CZ6H7d7ftVulo>Os^fk=#Ko8MEnj^nWI z&s#Hfsc*(O#1&Abpa2Hdy;1wJHKGOsP?)Y{x*CpxzaVr9MF5OeL&kD<;bVe*tEzJV z8_g7Bbh(aX2<shQF=rB!WFYytUtJeMq6sfZgwHX%KcEVxjE7U=cC_Bzcm;;e3Kwaw zRu0U${rPX<4_PCBbn)jHJAy68$m|{|`(ZyG+wjiRrQNRqc@iHgENCI}t7i^#)nTRg z0D0u2TEUC5#{YNX>9yR^<5e`^(v$x}bxDU+`V<)4)x3{_M`8B+Rm-br8Iu;kXu&2_ zld@W+2#W6fWjvE!_46kI#&~pV$LP1mR&3l-JMaDA!+=&fi>53;PTWKsW+9i?N8kn2 zim_&AHED#%{Xr)14_~NvHtkP&EPjmJ9tQA?cSlZq_lN~I!-72zkC`8aY_~Q-G1Y=q zvQk}N0ptJ8uq1f_=EM|)j@;+%kL=gA4Qfo`Hls@WxhQU*h_~kP89ds2A&a?!Ht~2! zhR8O4a~srnz`6?$QBBJ`=fN7fOVouwl};Sh4-eKxQ>lXisg6vm*BD96K3Rk!ahLCh zk*Za{j*CByi)lNW3y0#A51#@Sp~(kvCI0XaCE#R{gRBOMb3o0d957m$fZxlzH!q&B z-x<#yY^(x1&Mx<R)_U~G(}OV&oN8mu<QzbJs2R%ng>x_au|=P(k3;CeUsJ(*pML|@ ztTf=*cb%_pVREe=zp~W1g!c;1sc}Q!OcVj1R0jJ?Xi%4ykJ)Mdd$LQ#gfcZuRrlm0 zN4+De5U1An$Zvoox9!R0vSeB^czi?;vuCsLLi{|@Pt|Ftd{zOKfelyK4l|HKNuq)X z6UsI0n`02+N3y7zwc6RO!slu+fWOMQ-NTuGL*tABi;HueAWCMKJY%%Cv${@uAd;RC zV)gKL3XbO3wFA<g6`SNWBv2QnCZQW19yE2A1+f`lI%B~|88Owje_MiOe@iTHV#N3d zO#G5Q=4K5-nhK$QQ)y{FITnWo0^_^#Tk=7ekfB~A;nPK5-O$Q6LA?))nC_5Q_j&^E zS!+~(aCygz0B?i5QShIg0!K$j%QKG&!=Rnb=)R58y%)jIa8nu1LyG~aoL2Lvo0)aP zm7bv5P>%lhOf;R1I-+xVJ~x~k1{+Y(1*AN{nn(SjxBc(l+_Zq0Rlh=wT|tAs1D<Y^ zE7th79MHTT#b6lyS=1#<Of#%}@P^@6sM(KjU_Ju<UNpP(Y1VZOd1y*E$XMuw95>=8 zzv4|cm+uFsfLP_FN8j()+FkwFJyE+j=A#>d4(*AKd~NAZt3K;rBbmH2u_E|7mz<Qs z?6mIBU;EBW#AbNIlQ|)O5H&8?1Cz2c7x3gSSZ}%}I{CS3cLnAT$FFl#5-iIL?N6)M zPWP5hpXWHNPuULW*Wb@)pKM>e;ppe@Z(Vv9zb=YDY*>||2`bB+l3@z%Cv~wK{i^fa zO<RZIULhCXSCp0#UBZcHWYPt6@mMo!{d1PAw6Mjqy-;6>2xw7|@xOQe0MML3lsPYT zZ78NF6e$3z(o9(J&$}<(90fT$Y93g{Suxd7f2G8mXytG}rWG`spPBAU(d^Bcw#izl z^WQLMdGJcIvgG|?+TcuL-7i5+Q;#>9NBK`Gc+1)6De+rz*VwUfU>kmeeTiu)NUM|0 z0w`M|o_&e1Y)rejsq<u1h}~&LG$GOe@a8$_`(Kfg!quOQ?Mzvo(kYy)^;y5mS)Mgy z-W0-o<wQAxCdi9dLh|Ou;C}{jeF@;>d|!iF7;t88Awl!0#JR%^;tzj;R?}jOucnVr zLjj(bomfk5q0Nz=v{VYqvuShGr^p}hm3&Wl{9a8FCeUrvNWA<(8G^nPmSL!mpXs9z z$bra|q%HdXg?|^*VTdd*{men_h(oa$hG@m9$1UcJYHz+B+WEC+-LShgzq)gJj%rW9 ziOLgeSApb}_j*(j(FyGlM8+cY5-1<H4`}`vpS&TFaex{(0+<*G8PQYy>sHNo{%S#| zq+2cY@$6t7>ITy`c$W4l@8-98?}B!=utw*Ob@n?Zi~vFXk|!R+8+B2gecZlMs5P>L z?;OERMA72EzI}e-@(N%6AhI<Rf*AhKy2OYWObAt%mwfhCi0%>FKA_F17OIf3r?)D^ zwvSE-9;{P7{Nv$Id0}Qr*j#U%rW?D?e#mf1F;ixoy*z^B2R_0?#D=y~Y3}^X($q*+ zpeQeoYYJ2(_K)P;1Md^Q8mOczom($*sKiEK*RJc#;C$W^Ua0fp_giwu?k)BIE|@5S zLwk5)&642RYLDqPpc=Lo@Q0gEfbJawzed;umgkJwIrL_7qkNOTfb?;oCZoIg8e&-l zj^}Mp;Z3fb^kimu=#jC!&?kx;ec%OL9vsEpn4fZx+^g#`4d$}N^)L^DUw1bw*J-6K zY&6A(sRM&Q<A<cZ?Dv#v;3On}nl&$lt?3x2!XL@eX+--4r{^F{Z;N$Gi>9>Rww0m- z)G7fF>AWK@U+e&~QGl0sao}CTqjvfmKp8vjEuogZd!<P`T=qhGeNg+#>#D#B#R3G% zpj&xke&dsAnAzh+_K7=CUZA<qBK+o|cijp5cjtGgOA*0H$fdZd@m855i0cH{i<+#C zasa19G4hjhGz7peHcgNdinI3RGyO=`SnK!TihJ?;>I8AA6o@{7C1Pq@VYi{H7{#;Z zz)71KRX9D_q)dxOWcdgN&A>#t!nia)3TP6r=iq9Tcy=tXDA7I$;-Z%^!RrvbVR~^q zwWE0D`A8QcUttW!)}$ZC!|zY=ew#JN^e~xu`O=C|P>G_zW<?0k23t`mK?%6e3sGfV z-b986&Y;hRW?E5?X#-fBlNBaS==+cf2u?AIEz-aMfazeuaU@D_|CG?XD+Pv!`A{&L z{}2Aw3l*y+z8F4<t--_d&<`dm?7=(>WcvUV&?f~y1>)37qEFCtGpQNX+3@lYawI1S zzAJKr6``A9bJ0h^-x~rS(Nlq2PtcIVQ;%m|N_TlqAA@}{iw;2>QMZ6OxK9)WD}5`U zF?9t|6aMYgMyyJwcmtgXj_@33KIquDZTIKKV68WlLz=$|#Z@DFg0(WPV#R}mC7rx1 z&=oL7IY}!!-dw=vG6r*T4cC`B7L3lzb)2P^qSJQR2qEj34BowdoA%R0Oc*}k>vlgU z7d{Kl?TwCQ_vpz|8gxOhI<H_f!W`^KU1YL!mO%5Zf?lIe$l))RBVboIkP?N2!4@S# zD<?eqO@&}bJ_nd%sR1n~I$`R2JF60~_<)L#DcSGu=eQ5s(-q4U0L+yYw3kpR?v9Xt zF3~9rMQL6GxV#}x2}EaZ<Z#5|;h4#Zqe|vg{zhx`Hodz)1w0@+Kxk^u+t<Hqba*05 zgdQD4q|)o3O%`OREpWgHZ{+{^W=~FG-LY5XxR5_3?*d_rfMrxv3>C-hz!eQ3&<HkS zDhoQzNR(Ltfj^rls0<)O@T<e!QA9I&Aw}&4C>^gBLjB((B6?6Ut#CZzwRQ{?Aw*;X z47$w8y1#WbKnPs9-D=<WD}v@dV#!X($P5q+$f?1k=^sZ2S<m98SJD!dAQt)aipws= zg^jM+Ihxll<}q+sB+g<y&pWh~{_1bHz%vi`EWg_tUI2;cV>x_Zf~Vabx&)6^fm$F( zV|Kr!pl8SQq_S(F`H!nkh*$_B4)9r<BE?M`;^KAG_}_H=V3PZdo#Jexot=HUACyyY zB<(Oyx-?galZ|B~?}O30^}&9$yP$6t(WUbVmzI_)mUyx7EJ@u#9ep;V$$G>Fhp3ec z%LO?OOF*ATXN_ndBxn%`6-ZQvo3>QoSZGMjh;w+#9$e)7b&)o5v(U5q8At+kki&Ib zfMN?W!{$gt_yKGROvb*1F$WtU!%P4{)?i)`lZj9(Q+W1ph2Hea`5-a>0O#BdM7@IT z7Ge?Nn5d7^&pN}m3m2Z@J|5O80z_aJTL{F9<?0_`lM6!+gC9Y23e$$nup~<wcW51G z?57st_NL08<|aDLp~AQtEi}x%2o0B0<M~{Gzz<Be&><pb4EkHiHdp_ck6tKCSZ<qa z3Tl*<Arx997Z6heIw};lJ_$kk2FQo8pLqxA9X&o+B(?`l7NoK^r*fkfnV{(Xjd=Cv z@OPvZX-luvzUE=*OXP)3-Oa7RC{1we`fc-MZK2>I=fFJ=Y1Occ6JB|{&C_#>yP;AF z^W1u&6F(D%Q@inR;?j>~xouHxD}oLR-x6ek+b#y$7r$|SQf~~)9rWT@U&Omagpf|s z5j+==%Q0>g8#&6?rVS_0e-zh>SFa4uNgUDcx(9crKMnR^8fGS*Y}AA#IEC%8tZL3> z*;@+<l^Bi)d}di;H9kHgmXVx0ozYO$!t1Tc=y6Xo4a~h$diG7kKp83X`}6iB4j5sn zm8MCiLu-#)tcHH~s%T>u*wc9U{BlrC@k6_xZw-9pb>U}a`dQ>uW(4w*?wap?|Mij& zUmbGqEf>M_A-R3;p?EBd$OJihc<&B>2|b*KUjF8t#>SBgjO+Gq1ib@$mX56&0vw$X zJhGyD$ZwMv#9{FJ$XZpZ;`3^f(V(QL(%yG2t_i&`=RJTzqsdRUf#rya1o$?#2M;aE zYgNA#8ChPL7+@@LnLoJ4u#Hw;bq1XbBqlX`j>))D+uYJXB+T3?LpXZ})(7-X4S8B8 zCUyb*XDOI>a-#@A-V=;CC@aD6!C&pqTTmm}@)v_&b!46qym4?J3H_E3crhX5cmh>1 z{-P6K^H%h-@cwNoEy|brQkCQab<!EvWhSu``+IZg{2eLvt3e4O{dMKI@lrS0iO4sE z9EIcX%7spE?<b6*yL{~AlP6>X-UyA4Yo!}O!@b3eieT-+&z(0D%c7h(xx;fE74l<T z#r-IK(NMrNrvmditTmXjGL*ejeSrCJxx=F~Arw8r%05cUlmKB~!0EX7dfHeZbJ#e= z6gU#v+m1r^1B~S?o&mW}NzJfJRe8|}4o1d^ZziF8h;;_d-9&NH=B2B#!Udtcn3x!5 zl0VLQgZx@oW2}eX|AKRssk%cFD$otw6`nG}uCKJf<w=fLK&qGU^#~0xJ=*#s;%2~C z?ZnKHSg--_aDqq(&Net@dc|<4Hp17af$fJ^EB56-lml6_`U(^n;B>4a_SHt1=A-iP z^Cq!ur(q#G)@OsNUIyG$Rf&5E_dMzyKz7jHz@h}0ekbUX_@{Td&c$Cdce+H(EO3Fh zv$1!d?T}ig^!`2oU0oBTrHMb}qrG<FOzZ=6v&(fpDtkO-lD3=AjoLa+8MtB9im*QX z_zeShqiGkpQF;lTfmOk{vFk5@>z1)+@MF#UR%JQwz+LpNxG36K^6)YdK~SQPK2l;( z=ZH<nL+8EMrf6$J_5R^1bM`0fHe*L1P9v~<kU2H;d6xA8;xd{Sm-H@}AA9R8J%N`& zCzxfdb96>$`3;4*@3-&3mjE3-W5vAv{nHaRxRS7NK|dLQG>yFMgIGs<HFb&=wVmc= z6aMt7Sy}+DI~X-S-%L-uKSytL85xR1d+uzhf^FHwc%G&hG7zkL&5e?m>K*&d{-KOc zQPGvIY-Udv1WsQn9TZnpwHBlhQ`sL~DtHWKJ&dZ9{eB<r{-w-#7`*fd-SR!ECUMP_ zFg~5*SjC&A-rW+n-!L=G8v2q!OHuV_A|(hEn5e?u^78wyhb%bb+u#vOM#hW-Klivy zwZ=u{_Z?>(s=B-k&a>Dw1U^V=<sBR``dcCoYK$Nq`z&xU8avBUzY?4axK(jT7Sz!Q zC<Gg9q<xhxYrE*eLQ~_CRW;vTm`!Z^SKS4A+nGtlXO&rw7D(cEKlEVfQ~N%}r>}gg zb&{WtBTtS#c+^K<4lNmUtnz_^Os}mIRI<)TE3=@%V<4suBrTZX+A)%K)y2&PLJzE- z98F+Uqf1KsjM;<;a{9$JVthVri;KhNQ=o$dtvty#va;?w*^JpTkUhl?&4Bi$PB7iK zyf#^~#gWbX=&^VShA9YQ7qV?k$U3IiA!G!15QN}R4Fl$CZpOxkj};PuNx+@Z2^amG zABeFj4G^WleS%k}LpqvfHDd`hT?2ia$85|oHE<}%_gDlMR?Nu-P>(})h9s)0JeZ8t z1<aaHFvfazK+Nc~ujc>=#*jgnAWuZ%3~&Z-TN+`KSmDXoGq|L$g_6j@BFNq))4R?C z-vewDoDiP+P_O}(&SuY9BxFFVn2xFih6tz@_}UQt*8wat!obO=JD6UR3mp$5@qBO> zP}@lFWjK@bvQuy<7fn?yvIs(}BtWj7y6(Vh{0UH0g`WRVvU~$quF-_JWK0h@kJnlR zXK?cItuFSDFCuRcdl&3h)GBF7cWR4(GD|%rSm-uIHl%(UZIq!&^%1h^b=MEamfaWd zm$pA}-nsFEgG>$qS$*)Dsqo+g^)gM4+IiHe{evLJJRfJH%XQY&p!^}V9+_9QF|p3A z$6mou9n#C%JYvIoR!HqsBrOMOa>?Qk-MlIT)4MW3!v7__1QH+1`30H3DN|wb#2sXC zh54rKqt0dGy)g!_sa3jQi;}M8=TZazlm2z_j-AF191z?!A>R&EQegzgLK+u<+g;c2 z!#e;*_Z^8|<!G!312n|Hxoj+W@d>9E|7*e)uX6qg87?Hil-<Eea8Y@^=vIs}{b!mS z`iiOV@o4C1OT-#=S!H;Z%C}uv<G5i^)OwczcN$bYPXUT7-5OXR%fI&S(vaQYV_cs? zCn*W@<J|TB82;eR^0D>(*Y3f)Sl-NVbW)soB)-1qkL)j5|Mvu){eVladPZVSShUMG z;(A<kG22Va9=Xh``uH@@nQ+2(E28T$nqr!p#w!DCX4nalq2iDRmgyV6(BBojmsjy< z94m|+su=TlkJmBQKyz{W&%7rP7F~B5=Y7uleEMih{YyZ(bz}9jWG_KRLyeF7lk=JM zAIbt5dP+=t^Ocpc+cKAmLJUVNaMpH<VUs7`Z=H!c=!!&z+1yThUOS8Z_Irz9^mt== z3S3aYZDc8NQGt&SfX|QQt0rLnl?c#bU&Jo&Xf=_bnoB#%n82n}r0szzJ?W!kLl5@p z;#aeb=okzSrLv5Zbvdns9dZh6y^!5<OMJ=gf+^f1u(gMoSdSB8=0t&@y*T8^`}Fpo zfkp~dEK7A~U@a~eq7J1X;<f@E`5;L78RU9OPeqV9!ko;R%Nv#bo2j_ycJ+8b0!Yhd zt%G?x-wA|8sm+Xy&>`@15$l5V=U$k~Yp*BaW1uN<0)Y~s1o|Fs8X1VASVsdKf~Hq{ z9qlp;gz6MD0lT&<P=JU@smFEIPgX>F(+Z?LETC(vMxO1s&kk0E!f7TD$+$R&AR~Zt z_gb)VNY6l;4{|)c#-~|lZpUX?xj0?Jp@P{rjOHk1Rwi(q7npAq1*TFO9nZ&MakRkH ze+KR)FF00sV!{WlL7(0?nhqNJfjVT{kl0~Dk;YF>g*QZy%SJm$B+?i-2`MC!H?!w( zcGCP%^;i~3&P^?!*0S+|IbxI+;l48P%~(|B113_pNME3=n^8+hIonCiZ@bO|`an<M z{Yebm`G*IbC+M{=QXYdxhhkq8!t`0Zgo9!p#e&Bd+R)5@D39Rx0_?Inh_Zlq(J>|x z&l^UF@Y4%gXj$lq*nEOWS`ZNh)*~^7Ha}CJEdZC^I>X99A7zLaH??jSdJ#)P;FI79 z`MDjq#OM`|*rqBuZ?jI9<I`-zEVGW&#_->S%$QF?vF)uhT|d~npke|XY9hrD&TqS} z%^|$0^e6*K3$1|6;B&-^Ue~~%@X0Nx!!zn}4J1o2SQ^3IB6yp%lJ(_bH2Kg;kV_S~ zl_JW+^Aqa~9Rx}NJuH>Q(awfn9#R9gaqzqVu6|wvG3CTlHc<qi{drBgCA{xEs3vD) z2}jlOKx^!NHq#ciPhP&ThQU>I$zYo&sw+E5rrYL(ATa$Z@j_r$(_x}fqMGy2Pkz?l zgJz0l?)#UZKHu4eJs*YXx>-=rV8!55pJu8Tcz0zvtnS0l!}W1~wsBWZJcC#Uz%r!d z%AJ`_9D<DCJa4hNwvI|3BPZKQ_>(ue%P@HF0MQB#apx&`6iuK+6b`r#l<I#Zyou|7 zo_S|HWbmH))9oe+uJka}m_~?wIw1jL5pT(zdWA7B!RcVIY55CvQdgpuqlgxA#6Vj{ zD@St3mUA<UWTIOhLv5X~wa>z#=9vR@QZY0XgvB`6M<l^PYGX}tbq5%WfDxtG4szZQ z+ra9{HHa%GQ<EW#LM?{<7vT9=xEu8%zA+RJ$8KdzDsPr$hD8t@bfxTqy6)O!(OceF zkMEWu)3DBiA2~Bfrc7ucPw=*?<?wz&MA39de|jicBVwSP%p{$<$9H@7Tthq2h?AUY zmbP<Y<F5(J<7TD2Uvx=Rpr5cO4_EdwA*Tl4V6aPUal+W^Bfr==?-dt9Nt^>UUNtv( zO>tH3gvmC1CwOt3b8}o+zBG(yIAV!H$^6UGguRW18QaMy{hI1u9n;4es+te*hmDn? z*h26d?vB$G_TT8gAvLds6XWv6Hy)l_(8xx#$}z|AK-E)7!BY$p|HSKh^rm7~S83w| zan&`loOKCP=H?~j#c~M?xG%vj<wNxnA_f(_2`9Z&@2wiF2~y&d8As)Ku<pcvl8a{G zvE~6uRVn^FP>y*PObjb%WXR-0%n8vWj)Au`+*N#hwWNo$<p(Z8CTzt6{c=<)=%9hC zKNg^SPiX}YT0Hr*gk=_q-;xgH1p`Y6f7ouL?OxTm9s}UKAOuwgMDsYiVDaT@%H@qW z_LAUr@;(Z?gzmEJjdYyDvHmiM&i)n_dr4gv!8}wbM(=`w?<-%3fN9WtX){6cpdmcw z1P(6oT^%o2$QI!I(-EQYJx&?JW(_G79{oM=yuIeO&d9nGKoyQsOF~KFf)9*GVP$}& zSN|uNG2N~BQtfPhEYTAqE`zXgF0@b^ik9(DQLA%6JV$hTr*$K&vY{t)HB?sEfRBTZ z@Zu)dkbEIu89BSTQ7p40FRTYE7K;8Umu`w5%1X{^8PH&$s7_eXgic9pAsgAk&ER(D zA)&aAA~Yrz_(_(E0bIDSG7j=5!+F<*z>OSBxHxrl@y!^$`B?4UAT5*Blsa82FTTgj zG{Zmu%tnMum0*2f+-w6AizckeQczJ)EUYIj>wsN4%WgJ>abB=WRs>H^h~wO50+>wN zg1#IeQ4h#}m?J)a_O-Dv(^|VZo5hIPs<5%4SJIzMAnk+H%ZLDe1OU%8Zk%VR0@kxR z61navQ$o1;TdF3^^<P-0;Lr_>lHv%~0uh`&8_p`x<|LkWB8r;^PcLqi^eWO(MzJpN zLFi7CH{sQaQm0YC&bIg=>(t9F3z$}`U$662M`1>RG1{_g`Y`7bBZeLTyFn7p<8*e2 zUIZ;KTWmgKHhA|g_^qH{FY#2QSvj755r;t%Hx=bPM*5KYfyiSbaSg<;sKnUHpNI3~ z2(Aadll~f1Dg!JU8TpGcw-E7@oZp4RpDbx1Bc-8m;5>Spz<%HsQ1^E?xq@PpxrKT+ z>lBvH76v3TESPi(J^a1l)q^r9+lfN2<U7GzEbG!)RQ<S^nfMolS&%*wBAu&0sx;5; zCb_4%0dkUqGrT<A)*(~g;VjP~7x<ssCOccZ0Gs9S5y9IH4*|1O17fYuQZIzgururT z?--!HZ*yBe+a{OnuLUFo7rccIpmdB1Pl?<5CD+O8#z>I*(bwOBI`D?02t&ngJN^Xa zkHgOfr$Mgi#Zs`hL5*66OsRhxVI%i-ZX%ULHe6lKGZN45)EoDv7lEv_m;#ZdV`g>c zI;xdL2uq_Ru%v<M^Wxn_%Xl4%w4Gph1g$tdZhepO%8_?=-R+1D>0|{KfLvBqR=rq# z{NvQaS@b*Bd_YP80a9ATW4Q9x{L50rZfU;j7Lymmq|a{zxY@%*QbzQ$gsLEaEjo2y z<C`2a3@R~Bh|BmGI{8@G_W2I$hbD?qiMCXQ5C7i*2DOm!^rbDZb25LE8Drj&iv?n= z3bp=+@_DvP|GIVM9ljW$L;~}nMbnk$xs#48@czi1I57BssvTICyn%sV5-d}8h&F&2 zNc@}KtIoBwmRGEl#g8gR+t0_bHRAGMD%0v=Ze&0(uLLjsdiANBqxwr9mJ#Qdzc<=_ zvj2fL4znhlOx)+&-n17|e+xFL)<1FfUP~h_9b!q|-7&afM|Zc}qeaFyzF`IzS4w_7 zGGQYtZ_PrN0b8jC{$1nu>p$e}e}AZGcsy(wQ7t|Z1-~Xx%{n`K_v!O(kKn$|2ZNcT z=-t!tb|mr57by>t8z-U5<*Wg+Q9}OvypP6{2Sx3Y#Zya%aw8=BX(ug{UDWW$s=gs+ zC$_cMqsm5alHGVIwb`qi;e2z|?9To@p|852B*W|=KH9<#?)hu>f^CXpuzthfpk~{> z;}(_|x~j^_G4nW0MxCE9hqGK@7JC??9mudn9Q!wgffA{B07)5`pVvFZm#O1<C4UU< zf3O~+(7=x@Lro0deQ<dj*v}AFr{HsHq76hL+Uo^prqcA2wdkkt7EYj~D#&z8CX`yx z&>I~DjvQ5(rvecO8Biq!XIOEnop5I3oVbMp7NS0;xz#G{V@MK^TrFfcfZ&a}7-k0; zIPp=CLIoM>`YBrQBim3*0fTy`hYc`Z1ArOlqnXg>B;)m!tMdz#wZ-5mB5lN4CoxL4 zbLF$qI6G~`i3CpA)bJ@Zn}7xh*Tu^VR&5mW8$^Km2<SfrG9IqznPB2#G~6#wkh9Ts zAd77#*q6fsN8~BRg6-})zXhKuAShjFv_&Ig=5S76EqHN7f%t^V(2wY9#MMGjTiEz% zDyhwK*+&+Elt#MY=VYaui*c}EMIngCfc@wtY=K(|K}_>iu<k(m-W!7TWp=Amr(yRs z#u&OxVVPZmQEdZsuW5VS=`~%&H~~$hDEpz|CxRa~LT@FSV^`qpq){U39hub`+w(p2 zRj62*{{{vCUHmCaz7z025N8Wzz({{OWlX&DI$AMdK(o|Gi5at73p}Hv6=o^R(HNis z$0XB}WN$g?<LjfuAa@-TMmU%<c9FN|hjUHp)fzm|1qVkQTnkXqWVxxMtus6&+N&Tm zoSIE<bhwcE7&oBXei@E?ruM40?f9oU`X_Iq8PkerygfPpZL0I<m=ij(vwy+_L40o; zh<MBF7>)&nH2&$=!t;PV@YR4ag5?P~7(!80(jnHP&lW+4v=?<SxpKsqTKojw0dj)5 zsVJ=8<{@e=fD#At(2aa>O#xNAe!$GiGFwdJSy>Rl&F?~zCrjc?P~S7Ozu}Uq8R+Bl z9M(f@hoCdI(NzVlFbt_-@t}sLG!(R+1l+hT@$dp=2ngC9U+}uc%1TaGk(~<y;0=DZ zqTb~LGkT1AqaGnS2*IVpEah5oL(#!poK>l_$od0L%pkxQPHu?}F4Bl5!gIiy!sDu= z3CXp%$bJFwHY~)v>MWwtFf@7Qk=%sYG(7WklNw=84nA{EQV+mi2?q|DzlWjnFojfp z-IsVVTefY{+h>Qu(2oNOFibQ5buD<hf1Df91mQbc1Hi0Nb#{pe@7aoHX#6(&!gzR= z16AoLM%B<_DLg-$G!nbEDop_vO{3NcT5YQhVYzv6#gl}sm!GP<iUojlc~1$9lL}{? zAn`6-^Oyw6^q-~E^9CEPR%vR*RVSbizcAPsSH~NDep<QuW6EU7v%3+rMZeun&hNxL zND<b3H|;}v0DWmmM8`eVG#UTurzyTT6mRv5=m3n>)5eYe0<v5aG=0o$=@E1uul88L zD-h5=F-;1T6@KzH^*gTVK``g!hlx?erv2|3(DpWnDr)r99v^FJ|MsUfhrbnaA-W@6 z^%~ybisOS!)hfcZS2d22ycfker_V+Zq)I}3+IXF{n(lqlJeK}3tri~zp5|!V_Sn>q zP|*?72KdPR(Zh^3#Cc_J_t%?`Ps)^tdeWfKfGv2acV}1)yjwJqEdu3Amtc(wL3pSe z(SU(=vN`_!yu%1J(p)dxL48Fw5E>I8*@L}ju($JZP&Ya~5<Wr^Iqp>WkRA9iaIABF z+=^#+eGQd+F6qPC<_~zL1T#)_O&+Uhk_k`FQa?t1EWi2=&?qMC7+_9B1b|}gdM~C~ zOfa0Xe@ht7e$c~M7OV+zqe{IS(GB57EyNv>mb_n<jVfmIF<wcLi#kF9LK60=C%G*k z5+x}<=wA)NOuw7WfP@F0JFjskCo!JGr-5{B+fls$K*u3p59OyeX!lr6jO$!<UuoVL z+=&~<EDOO(v!NtXVK+~XRA;*rFbXIH`46>s*8gz@xO7V({6i7VaR9iXn@Tq%W`Wbg za3Ff3tQqcTVxcbIF##qN9v2`U`0$|}BQp)lA{|6S@^~>=C2Pr3x(#)4KW6u*=8ZOy z6SobA5H8B9qJuMRfzX&pnWS8@wb6?su1+wPBt^Mb5Eo;RJFx2%p0Z=0a_A%I6#g6o z!&A5QR75snFA&3kRIbot@hlmRYt;4x8wQa!64w%{bAlHSJb^8nkR3vCf$TsGiByj# zd_SUalM$SC`GZ~(nw%TGUpp<l!ZbH9%peb&eT~%e8*N~diW4!D!#{PE1GfRb6Q1P0 z9Q;`1V;ul$gn<!QBR+DhrByobIQCD8KcwLLh>*&Cgz#)Y-!~Ob1yAx6k}7aF;YOi} zf~ZOdeD6;&YSrGr7x(+O4~mG>uPqVL6-59R8xwQmO-%&gLZg7DfK0tGx=4_p!+v&6 z1Wslr$?%m4LMUtM3-T<2b!-u!CG%>d!t*_?0p7Eqfd+7*olU{l6rN8YDFKFiiH`9% zPrx$>vqI6Y7XjQ#3WHY=oPlOAru$xQCvt}tcD!CB2Z4p^aeO(fwS4IL9gLB9As=w> z{~A^Q5gL#5xL%%U4&t!fTF@|(lSg5Rn*rAL*+1mtK-K#Ob+-Vf|KfZ2D`>zhbI7HA z>KbBmB7MNK`;`z-=D_v<_d<S)x^9LH_Z;wkObBd37AS2f+2ZX&9QU3*yb2sFcp?16 zL`?3Y?HA0C0E&Y89jqMWoM&@%PTgK!JOlmLM^K<-17rI=j9y_Ih6`cG8K5li2gkkr zH)%-Ip-Ghx2g4XQH|x%9b^y$eNV^H4>Y&|*zAM+(>wXN&lhDQk`6XoR$W&J9+cRK| zj0KvWSSw`HRO2uz(S*Rsq;P;ke7JUDD$jR{ORX!$U5W|;Mb#ElUh!JV_xS&9F?Ev> z`@s?{p6=X8&+5d)4SlhuNoZpd@i}1jEl`kQQg_~pAMdkiP)Mxqi(LsgqN+e*wI+T+ zprInoev1_@X?#2MG59{X+)Y_t9^AB}D5bc*VU|~}nlsPR_ZOW=P;UINs<#|ndW?(} z91yoebDfUb?7<^2(l!j^tCor-!3(+Ij!R+cz+{ZrxoVClzJE}Ae0Aeq`Y~|uiAnIK z=zWkZU^Y;$>D6u`i>6l-ln@^0JpH_M+H}Ck9#aTFF3A`WRaZ~DskZmKY!H0-t$g&w zce>J~26Ub)KVMaxv{1O@YC}Qe?U3Mgv1{@NO<57dYaJL9*Js%o6?;}MA8vGr0_K-6 z!R$j=Kxyf!)H(@^{t;s<vKNh(;WOcotnBr_j@{NFLF0|$aKCCB+)Tz8gJM;b)V?tf zbK>SJ@#!qALCx!AoZTo_wvDW**MV+0prR8VxxdBACH$M_n=?l-W%r3>_ITkWr1xus zj`_a;A6|E`h>3G5IhSDJ^Tr3f_uLuCgeWPb*N6&mA>wEY#oxhd+GRztKrsVjZfHF( z!V1B&5wjI^qI1DU!O;L<9nUTby*B`>Q#b_DNs*<IMX{)jOeD;sPF<y~1l;J4*Wa6G zO6n#**H3|pu9t8iRcRHNVY{$U7o!@<Mdt@PbSNoK0O*iev8NPjfq?Vw<gn1AA{-5o zAUIIBqjbZyQ;g(4U^bf2j|s!%^dKj`B!d?5%m9CZ9D$^SfU2G7=C!y$B1w6F<&F_m zd1GrM;$4~5NTeaNh0~B4WNek%0m8@bAS3q{Hf|7<yoMQ8YYwEvvJ*jsa@B_{4?g@% z?dIQ!9e6LPlgWE<f`w8;6hL?4C1Mse|9c@D${g(HpAlK9stjS0O9JHp0@Hql3yS<H zP7Y9>pUuP|918`{IXwcu1_3Bita}QEZ2-r3#S0CU$YJHJ!Bw3uR+wg5Hlajk%8BM7 znGosB;Q?tTu)=uNGRq(r4;CTNtnOzJSxG_c3G-~d1eG}G6fi|L*b3qt9tzj>0}C@j zGSJ+JRs&3Pyl7{L)pbQTlQBH70kU+c5=r@vLbnKdB5n(LCaOxb`*=$jX96W7kt!1H zX-}yNd|y6WFm02)(S<#u%cej|m2T0)e??}VpeCoEs+ivbszDTJPE2#Xy{Y5B_pxWZ z!>aMyX?Hhu7Ff10b_xdS!oy4f3?xUft3Naxw&R%f%Cg*gfL{W79`4f<1udAutbbl@ zB#Sd-?uhsE?2Cg1U|=z=C{)m|P%{D>9PT4m_<v9vuOy6&<3_fr=r__&T_q)O|9(Dz z^biAsg=UdH$y)iT*>Idi1?Fw7>CneXjde(#7%p+JN=tLIj?cmqgTFi&r^rTzQ&Tos zR~YwY&0yJ~<ipC-+$f?6;&_9$sq-W7hLttwJK+f)Z4WodQgUvB?fA^q8;yFtH~u9U z);nVO>DAJIE@T1x146!dfeIYmc@D|B>c6ZP3AD?80lpi%IMp=1E`a5t!JN)PkCtW* z6H?ZezxFqAaEXL`dH8d}`0|u`S$X&)=90nHUjG3yH^~;4OgA^PREDz7;%wHXpX%Zr z$>d^=0iyu}5u0z7aZxq*JfG=9O(e|8K4lCOeDPg;&CR^XbNzuvHUxWPdO<2YLi*Hb z-i~Ua5n6ndD&+sXNJ!qbroMs3tz|E-D;b~0t!O&hEAJIQ#&&4KA+{156$eYuif3g7 za(D-qArZPh_*!^vF=u*9Xj5nv-)JaQVTsCd6jh^RbxO66CBr9U7qvK@-|GmnK8$Hq zQ(kah(aA;&G^&zIyLn$?40`~l8oLc3id9tD>)N>a<ex*`7@c6m;1N2`T2!=YUa0tR z*y3a#ZR#PKw1Ni1uBqYX>|#e8Ce#e8W0y?4U__p2-MAGnar`)$Cg@%(rj0L~2w@%% zMGO#pC=aI;;e_!o05jmh!W!Am#5DXF5HF}G3H1l|{}3fRqwheQTh71Yu00?`bw(;l zBN<vvee`+&SKuWDc@d67((NXLOx-Ld#Qv^S3Ph_NumBr~LZ6T-wUlGvNO5CidbW-b zuJ{JBVGT8EY+&eHffYEM!}_yg(h`Cw?l8tAF6fC#K-%Fyp?Qyx48lM1{L_?aM%?_z zF!<>Lejdp}m4n}d!vzC54pn&#_gx7<OELr_7tj$K8=43m{dx&HD+COp7B;%W#D6AV z(GAqS*xBS{hXub=N{B_^$v!p(&NFo>Ko-YZeJC}M@`F6&10aSYLI-a}!86s=rDqE? zn?Vg$VS_+42egu$+skWF`BtJS)s0&>=nlXf8xwj|YA3mo5-`j~r-;~3oZi4)q6s%# z5p9US>uiG#TSpxwpM#e?(g8NbawJi~7~lqAp#Httj2hQKnxLM44zmRhIJ5yAfv7nl z2&Dw7yi;;58(mxf{#a{FV*N<>uS<1+%^Z%@sPOEwSuuv_JWcQ%>hTa}yn`)#ws8mc zb8-_kqx;!nBgp)-+uVna=0Gt_44o4>UD*)s!QaZ?Ci}d;37oo6nzu&H>!KCpE$~?U z3F;`Y)SbX2@o027f3n49Ssc+=r$ewRwjQxfmbiW}CG>0@4$mc9W-KA|VtH3V9%>;9 zpCQadiUBGbSmHriYJNYHlYQ!{=k{C_vQV++lE918%`gVWOUo5)L=_Ij6%cX2Lyx<} zxHfi?LXb}?+dljst_CP`&!g~kvdo!^n)eQ8tBbpqJ>wn<7jzApRH+S4k^n%v+^G5c zI1XY@vMU2-Q?F;D3_6RviyObIYaDggd=zuahFnX7^g2{|<aN;pHiA&{JJ1U7p-7-B zx!Lp%7T!gLQ9eJy5>v}_eRJ?*TaRjkSi~Y=#ywb>@Gi>1m(nG~OeAB~6MmUFifddl z*=cwv&ws4NSGNMgjDP^i(k&~_*$4%i8Rq~9p+&L0ik5%|SP34?Ax2w~X!qPdtDprQ z8rRQt0U+|wGmG*_b*6l76U$RRhOILeu`czljuMAhRooE;&3EPk0Ks^FDz&kzpoIc1 zPHU8p-afE*9nYcqJvAG2v=$p2Jg%QtQ%B9UXX(dY1U2fT0UD5%T}d!ac)m2_rKKPM zsZw%`QFZp;V)fZz3n=tUNA5-PYH#tB{jSv9>N%tNDP5n@bP=97ur~}|RjnGP37ypa z&(u43Iq*Hth5ao|h)}H5>+a^mg9E`cwa>2gSDNSk_5pkVF#Z{9Wc<@|i>_{|Swb*S zh5pSE_)mdCp9JdYx|H{WpIL(t3N(os(9Dz}g62v^=Jd<%N8&+5t)o_~181JK*9ywP z$)|rPAafw~MOtt@=zTbhUlN`R8s=0hCR!w|)3qKjU5fQA8kOL=93wlBB#DP^PS~R) z_g&pZ%anL`eDq6iBwFwQ2Zmy<r6<N@0d;=|(T?esA>XqXl*Z_tGu#Q{(a45FA|1^< z4zItVTDEgV!-H`Wj_pjQvVxF7c7eQXWy($E88EN2DIi;dwum|cTF|5%XzmF#hkGNH zk}wvktfb%hhXPA5ad(R;*OG&7^_iX-&l%xZBk@?7_GI8hjC7yDxCkf7%7MG&ltzI9 z{-Aa^@hITCFjZwR$jvaFLKg`=6pp^aE|uKFgDVPRscHoz6aq_**x_T-HNh?feeYRd z&4~R%pJQbDLlOEB5CuUq=wZ6*3&944j68=x0NoFWp$SDim8#1ZfR>bppwB3TtN>rb zV@J)mb=;Y0ff?RLSbm2h_o(ZNoaH(fnS+we;hWL$J7acOuTa;`njII>LT?m_t%;dR zjT_*0O~^cOzRWK5i=8RB;>=O6kKqubAkzjlC0>C!2qPd5&|)!J0@N4j@g>LMoVGV( zGYX?~<QS!xG||ZoAxg!=3hWcko?|H=a3W47pvo<OM~HRcd;sAFbrtP5F+Oi2gWF97 z8E$(qWfBD|EBQa5qH|kkRan!;`nQh|)Hbqf7osmFJe4_~o+#<3`<4kat(^NsL6n8o zVo!|2Mr^WKwsP)C8}pw?Y>qi~N{&MnWf0W#pw0@^XI+zQN2TC}YC<+~vSN&hg?5g1 zw!aRfpyEu-LHyE!1sH~fVE&pA0@0V1DVEwWT%Ew-P*`RIDEV4|+XD2H3hZGF)OtKT z>d1crGtB|Pg9%_6;z`xBLk!RuG<Fbbx`8u(cdwLyPCF3Ox5=Aj4(_&VU_i`A@Biuk zfx;u;7>@5SuU0pz&u&ijw!u&gFO`HMrHkG4P@18h3^7Q8OdnDnn8qaIY7#mbT?I`R zN#>kk4-Y~Mf&re+RJ#-0KhXJvzW$ehz+&xW_Cl@yrLn_#EYwI~;(~@N6??asVv^Y7 zwG2oCydD*y+h3Ay30rr}vY^G1FSc?W25TQMf|zLZ41DW88Fyw7NtC;RDRaxhZ%iai z5Dj1%9I66V9C*nXk+3Z`*_m!?$a#VmcwIHlPO{7o&!5?sAD*3d3N{J!O1prIv*R68 zG$H<`Oy=<aayr?6Ij<=H7(6_5fW#n`T55uhYv-giT)X@~GLP%v5U&kf?H)!3O<bj# z=op+YrJezf>xb2n+1+k($V`lm7)Ltj+DmJxqwe>*6$wm8ud!9=b)RhK8O6ChziS!a z6A&Z~$7u8dMm^e1Wd+)W+SWzC^=9NBy2=b=C>vci5@11Yt<ZGD1=alT%CkpA``Y9V z9ta`umT_g-M$sz)kK^nDTk2S`3AP163C5omE28&L+c?f|$VV+n?<1x_XutgU8Pl`^ zMMB7YOcpWDf*6Vig08)tGcJq>w0j&!pp3*-NLEDStpe&Zg5e#{QLsk)%0pjBj|4tN z<OKxxV9`!8R7A1gqNxlx?*wlpylb37_?br#l1s+rT+Au0w!uG^S6swM6evQkC*ftn z)eC;}*2A4BN@*u)FMA*<n@H8u2joYz4lkR?xOhV!WsDAdR6)vp{zf}@^h78*TR<Iu znhOmbX}KXh8+-Z#4o?bZE}RLB=`k$%K+bW!<)AZmJm;;!^quf|69()k{sTKE7H%`U zMA+##ttNrK_U0M6&hQ~OPm2>_UyLxO(V6Sw;p}ZddQ0kpsElML$)BcU%mLnn<r#4Q zp{Pfr1fs<h6*AB@4VZZ&F^ddWaRXqPlSC&_F&Hu1|DhaBywB($MVFIc8e`D{iQ773 z5MGDz*Dyhzh*|&=6jCjKf)b<w39IM>DLAX3^a7d+oQzbCy2u8W8At{`VC7*J!jk|e z#5^C37#q-LWWpH6K`JRB0Ml@ktdV82EW!5RI2Mn<2MyQMtti|If)FEDLxS5AfA|U; za*AOvm8i!U%mp`!?Aul3MspnoC2ydQosOjh{E&mX&CY54voGCcg)(^`9K5l431r#W z(Sjld{G~crgk-aIpNG>;;E>5d(E)m}gTO&-7A3*Xa7{dqa}^x}P)1?;dH23gar+hL zWuJZ>Cxn+1;S5@5PGQxcQ8l*+nqh%^lUay590qTAT~U~0dF;Yqk-0gd2}Fu`GH=Sq z<i&wKdx;echrtSiMCku%dh>v&>$UwK4KuSc(ez}<Sd4<?QtELbWb#QH2DK44L?!Bo zacomi(ox{!!OEp#WIzc^#so#eB$rZ9napxz$w_g;4V6t6Sq52#nfdsAy{F&rkLUEL zF!NdN_q|;Abzk?I0nt{?EW<V_ZA5X;v*h0l0wZP2#N;is_&5o6@`Ky%w?vvym8zN1 ztCtUBIcmZtN?IV>PT|cEHFn#Zg62Vzriwv1h~q3IWPO@@|Dxd@2~9@Fz(OkVQOlK5 zg5I`5oj$GSC87rXJj4I4tEv(6Q(Y&DzC}t1!GI|ujY{{H&45QGeOo%pgDLUF+u#)c zUnO<3XbOt#lC+x4q(HUyXz7oKr$?I$>5uXvaI<e(D#gihY}T+-G&kv9b=gQ+X!YmX z9|5q*hrUYfe-WB=&HRlT5E9C0CU5HxGD*tpa%ZY-q|rQM>j~O{T+)m(U*C!u{msEu z*Zur<G9Y{;ovu$f+JI@(*UUZ9JAGD#mQBS=dw!D|GUGRogY!ckyH)u!pUS`f>~RT# z$|BSlg~-+vZ(Ajn{cZ2`a8qJj{^%&ulEtA<IAU*i4N{HQuEUP!KbL;PTtks^f}hM_ zck}J~pZT_@mPX@v7=A*sU6!S);CrLrPkIVjof8}!jK1O5t4fb`UeJA7{7=8J%PT_F zOxsrUN<bZx7C4^^lCLNU7@X}F@m6UIC+Jl7my>Xt#`(`(IMgzQPvU`H!TI3aBkxeh z=DgldC8x6h8U%}eY(30v_~si)1p|tGk~pvr_YsbHJ{cR30*YGbE_BFC<Z24r=7}1S zNcb;w!{KlqNxq8IH%^_X%Apf0dc_BmvYv8X_^f)Zidj@86fyxHO~qjZ=l+j$iTyyX z<U>9<@4<<_6k9f_f!Ys+>`GW&kF51?Cfz}=)lci6uH^>}b9&Nz*wH)v2*CI^JjXf0 zq2fk%rUJ6<9wlG`1ir<eP1XydB%Yqk`3ev@g9i%<CLqIoUJOgEW8Li(<W8Uo=zNn@ zx3Iss80biQp6Fb2gt+dy>gyrIO4!RJohULJ{Jr%5@DTo?35#LTvS7nxeiVw25jRws ziJuC4)7_Y$a%M01(UPtZO_yBwv4(>pn(TO2G`rviK)8C*AKX645PTSA;R7P?aT_lt zem{mkyu6=hvW3|UUqQQMh7j+RvHW>lu#`5djmG-Z{ZuR`v;`F7K=*u?LZ#6r8W8NY z(;25~d4{;e(Z0S26BGlnwfV9=1KqoTBK`=v=cl0+FybCno!+n&o$}{HhKr^FaLVnA zj`^_tL(6Hr+C0Pon>L9rFAL72H*iohYtJYWU%|ICh<{T<&=T=?ZOwcnBnlQw49`8q zhg_zZ21db`>1jfWB2meJ@ZVvqbcAgNH)-0W-upGf1A`m_68U?WILBlwW7B820VE_B z34$$|TJ_(HsLvWRnapqY9X8USF3foB_UOX4-v1dABs(>9oN@oI$j$uW04JQT$Rz!k zt)i%3TO+0`cr7#Ek^NOk|LZHdX;es2P4&UOS0!yztp%l|pGHM4xWn6sCSkMp^vR^C zrX5I1G}O$r0zMqS)w3!g3aS-jgX8cjSLX~?%KniQjFo#66Ja5zQ^!AcJ2Q(|Cc18* z6rr=SZK6rocgDbO8a!G$PdKq@(^yUS=u$c}j0-mUX0`cJzACRTMmgJWN}#jHDz3JA z-)J21ZFS9@kfAT2yiVx244f?RAM_5?)t6HTzVH&(l#OS&0jiF@gsV#TZbhe->ld4= zX4Ri}t+w>eP7}K^$F|I0)BW^|+WjO5@$T0-lG~OC2Hio4rBk#5GGgW)e#>i{?|!#O z!&Rbv1q|?f5Ku8AVJT5$7~A^x6W(`JoxFUU>ULQr%#`&BO*}m{D_`I2MSf2aryZwJ z%2SkB@YT6LBMvbGKm4t`bdvEAPGJWsMy0gjsM^PT+dD1XywOy7RT?kWScQLP>{sb5 zWdl`%U+-CsKSgpyJnHbmT&2|V1=5fJ@z=DKhk~!kU59?}R*gNgO6`eEvxM}<*wXdS zeyocW)H>h`6jK0QSH6{`J+5iv0kLJHIH%U8XY~!2uz$w}9*rLFkd3meyRNyrc+AKv z11Yt!Y}L3;uYftFzU}g#ugp(any?(S;m4o*Q7gH+oELJ<3VC`C^=eMf>B3ZtM4CEE zcJi|5Ej|s`Z0>LpBc<#B2qw6#9qy(@6AY^*;d3tcfv_t?KH(mbR{+F9+==A;Yr9vl zauPok6XJDV<Z7X6WRcR4%F5{>FO6;#7p`ckgH7@Xn<6~|1Pyn48-WvzD7_1k)TFob zEJsMI_s531v2n^#Y?%BYX=?j0u~LUJbqCvn%D^lO1dFJ@Ky#3T6xBL%<iI>Ve41UI zTUI$bOidgP$0IS1w|~uNNswRhV{G4{x&WCkPSm&zJH)K+KEVR)HW$~tCy<ls%B9N? zSTFw*eaL@-&YXi8`WMeOIBCkrM{a*n3K!A1<$#d!=95v<H_3=h2p6TQA(v1B$pmq? z9yBieXw5><$%txtFrq3(J@k2vhzG`#SvkuDL^^PqKzsb-j0sw2_FDuO?ziU<SZu)9 zF_~+u;ESl=iA@bjuGq6TxaV08r}Yx+-bkS7U5iRDpt$G#i&}X|5;XcGeW$=#uMPp0 z*9c!S;><hy&DId%4U3=d<3-Q|bR?svgr0P<5IK=8nfmydAuIRNLH`4Mb37eVJWGu3 zy9a&UnVu~6WmIf5RZmi8#Y{1A^2XM;@p5<25%%>}C2d7Lph>zJESRdoPcb2Y9u`$V zI$(LaXp;0ww#nfGVK$LR`nyF+r*dBy++E<2_@rhAU2N>{%_f&0nx8r+giO_tl_VfT zQt;ga-M$m>n|UU#Y77^CXwCCp;X(zaBv?wB_P%2vRHMC#JvGFBbYPIHBMojRnGBp< zzqse0(w(`K>xQ5Q<<po=ArBWZm_Dj=byB8`I<PWfsSCQqa{b9UQ4Z6~H$H|hW#j-R zZd(3=qV>|>Pt?)iYP+z_jcsazr@&Q&zDe6JTL@1BU5!g;26o(*2O}!0&}5$H`{Uua zgy$X$;~2brn7~4#ZK=hqaF>v85JgDBk|N$k6$y(i731QGBwxD7YTwy^W(iY0Mk}5k z^v+lsiLi)ahK(ARQnHVK+nG9W^bBR}Xtg7DVGpHHRvVeJN`O*uj&OUJqjl)Oc|B-p z`0i&YHU8BB@3o0su-~jb6>nXn9yXrZx9VvYHUxkgfwN$&*1AY*-T#ILP8o^&AB&<6 zOcn|hR$bD9y0mkzVOwqw=0((wqx<&v)KO0OlS^yhkg&>a%og5V=z>*>@a&C`-7b^K zoNL%}sNy$|w|9051qITahd;&T2bknZxbcR9D^V49Pk`g%&T98XPc$*c6DC_v#?LHC zITH=3zD&;ld*$jPpOo`Lln?z)gsoUF)xCz&N^LjUn~vTrZ4-}3<kk5<6jfJX-cx<k z3N*DLkbtfQ<D1}Q!QFG2{kVQ(OL;goUF2}DXae%ZQplmS-fl7Z8tfK`TNn*Lr^;WT z-nB5!9b6X_eF~A+MPqU8n@`|&4+tfX(wsNU>eefZ`XaS9=rwWD4Omf=Ts@!PNTwVT z(_olQRv&L+qD;J95`2tw*cx=U+~^HSCo@m2ndU;Wemv2?RkU>lX$_GnfJfsgn+q-! zRNoM6Qpi@QYQIm_z#s5C*i*DucTVw}z&TNq%~FTCBlDpj%Z%6F$({U?(3w!_JPkAi zo+6J)+9FcHo0+8sZN?V9KEppUS!~&3d}|h;VYfK8LIPT)ss8Jq@pDwo;C$1B3Kero zTWd6Ldazdpl(4^fh?=98CybJQ5u7Z71a0I*h?|Db#j$0n*`Hd7!b$0#Ys7-j20z`K z^hnDXhKvK>frkmUV=vzOF{GE_9%|ZygrZP#L7*EX^mxiwLllT2iF!}C4&qSSPz|1j z$1bm*)01=VpQOsz7ANeI61hHt7mUUN!I7uN^^~a|W;>6TV|t-z(-1iY0$>t70t*vd z(<gNCYIk$;NBfzJrbQ-1a0B6fQv_VhNZk=ZKxf`!IB5usK$<*1^WRuyv&()e_dF#o zuV(HgaYU7wOhHxR9_BK%?fwj_5XEsk_S}87@b%2$i7At-{4Aw2g59a$58#91M#07o zJRnfaaO?AbF5>1Xctc;pvsp9e4fgDb+n$9w6l>2PfN4xB^BqyyNkguV3c$7515K-E z2!ru7LYdcFPj%bvos@Wv*x9`T_gTkeaN;(>L+}502&D9Z{1M?$tpM-_l6r2PwKwr& zt!L^lo>--k{CMMGFOi~N1hyg)(%0MTLXyJB_H<eZudR))<{>cg@<6eTsKd`+Y1roG zi)FjGr^=*_PbUQ%DT)+w+5QEKdTxVnnbI_W<1x|lNfdcR-FB2VkhU=h6(06f(6mI! z^nBfOXKGM9(l`bV98ao`S;dO|(m2$=ACO~)4Oi)HwR0%CHE;IAPg35-%;|aY9r@`` z+^=(l+Ar*6lA=^podS_e{Ng}X&W9uY4$dZ$^V>rQVp4`L=RC5Fq`L{@Zku1x&%<A; z6QG7+NAZj5mXH~*Dad0}&HGllXH!v!4{}S|I!Wko9jM!gZUH=yJ32Zh`&KDk&h}XH z#rFoKIDlMO($)}A@E&4bGiSg|yIsV*m|=c==03xo-q%*%?KkF)FkU0W+=m8qHT)f@ zc<h$LnmTX~^PM+dQjAA3fZ!SY@Zb6|+NaP%6rvX~R}00U5aYPrQQ`08+D*L~kg0Z% zG`y4%qC&=!%+YAQbnKXPCmh}xJ08m9T?<BDWA$IaaYOLwd+jOqnVl=d(=Okx)59Vr zkI1%BH7WOHpsOO<pdVAZiQ#~Z)YH#w7H26yz(3()Fbz;w44b%lO;3@osm6Ra+t6>E zDnkUbrm8(ekSmukw8Q2a&4Ty(xLAK7=An31q0m0KM;k?+wJurA2I-xVFDPHP#SVL( zQ#O?>?9RMOUIzZ28IfwHa%VE5ZU~MO9&PuufQ+RX;R`m>)0<CO8tlqw%J561k5SAE zMa_Mpa$l143IHBJT_*mEM&BW7;by-n9ONu1CJP^r1MGqEI@i#>j(^+O;1|T@7Kv{s zdlScrXTmaUC>Cr2fF1jHkC$BgQAtyX@zyG4s?dzU`gZv27_MlubjDpq%H1_>282k1 zl<JZLbO$yft@D4xL{k%*CS_iL^DRe-LD2w65!wur*X7fc#;GD8@Qa4Hc6vkyE@f?E z=!of5J>bh_G_pkg8T%iOfq3yc9BM9q!OzD480O}9k?Wqvd5+uY?s{&cM@o!8c^XYQ zY}kgfV%XAoQE)dl_CtnQ_?Y<w1>OW$G_aT;@&CYTu<HJ0oJ;sE@8x*2aje2QVgH=j zyz*xU3ivH?E7SQ~_?;ms&h9=ZiZy6uDcUV!m+OWHzB>(w{svgaOCYX{w+<I{$8lK( z|EK!|R-;5Es$)^L9UJgIVBSh`TEGMQ_EK;$b+8%JsGtLNqGkg5nw4D^Q1G+@H<LaC z`knjr2uMkAKhme8Te=7TCO9!9Yj1NI^OOeTj2`bNi+=DTbcJ$!eJ9R&v~q9alk+<M zNt!HlOBw^y@oEaPpttIvDP)s#?KzyWd|(JeKk?&%-1Y`Tv=+Xre3oAH!eEI416Z>m z<Et3yd73>Jf)D_wR3*X;1GoT!&~g-DvM*L&tS%!voF-<O9BUXeIHMqo6x>k60231v zH)nR$Ngey#X8ikA-rHUwH3S@eVdrkg8eS&oi+Vb|%VVNDrI`V&XcOsLPn6NcYi2Ln z?a^-21;d1WYfx*aO;V;bU&K5eOgNws#u98_81dH1{UIR>7WMh>fy|T=24exLzIt9m z4Q@O`-6?2WL7%;--J9-+oq=B@uc$7XIXxr%&0dT_4MtOI6s?tmJqgM}->^4C;fpie z1`1uuD;K9tRLm^oP7H~OTSrQXDbDa$-Jm;B8IWj1ILE`7sk&|ms#_s+0ci=-E~xg3 zN(;Gs%&n`cLfviYjsl!LcJPUM5*2m&%o!WwIbP3I8G=@3IV<eO`c6nMcS19CJ04U# z3nus}xlneqpIWh|>61tzB$=Cz>{>OhU^nV#y^1^sh}y?`7IBzZ%MF`e3AWE>=jLsu zwfFu-ub-fYD2T|a03)n(K3QEFXS##6vn+Doigi))|52Ec+h|@LcYlia$`mYkp_$1~ zdfHR)Qd0uwYF}mUg{gYf4Wj>U_oO9~ocy0Djsj8<f%bPslfmF|hkHo^3=?DEZw_*t zcN73CnM8pRCRi~_eU+dF{P=T!v%*49D+^Af9bZU#r;i^{1bMgwtYc5FB>&xbrSD_i z4YXp@%eeL3ZUR#PmQ1f%3B;JH2@v%~nB7#l$Gy$3w|3k?TrX`$v#`mjRH_F$7^u&a zox(YT8Ly?%JHU4%LMJ+JVpw54^AzlzWDtaOHVJ|)LS=JZQ0P){DYl+HTCO<tgD<`^ z>xr&<t@F7|!N-0}NNqFE=_tl}808Q%2OFOyk<3CD7f;Y&qy;)oD+X|Ou5p{HR#FyI z&U7%JQk(uJ9mJr2fcs$Nz$YP55$?9AjsNBzxXXeW_=3U-W)QnbY+3H^0-=I94-4KK zv=^=|w>%4YZo5ypXn@ZRV)jGI9q1-b%y6x}AaS?Iy1<QwdqqZzx@|c9TA!jB9&?^> z&`w$$!XBHwiJuN+TA(wPHGnK`@%4?kCw8xa8NA>@roQL99rc>Psx?S|{Gr@21f48P z6Jo~SRAs;Cp0k4H*p<sW`*XcH%Jr}=g54I6<S;<FMr)JB8T~-YM1yR5y#%`vBK@d= zA2T&r?X|pD|00NZ8_ERVskfPHg6<Al*>f{|4B->-ErsbbUI^`reod;t%g{87jC~oa zGS4DtFs^TGdeC<>Jz}QJMT=i4mLtBfa71OD&<UssQSKPd=%&zsOkePyPXqPnGRcHD z?YOMH>nhv4nXxJJPbLLq(8*)oNM4lpo;}&k2Uf^1;x{8Gh}D`%K2iq=a7}c8+4{|` z4eiwr7f2r!PG4PW50$I4&Hrcfwz=FPjVHl+6r}brdx7@uk3TOB^98`d;zMU7-oGeX z(@YGIHwfCK;fuY=1H@xv#vvnIGn`H-lms_J`iy}^`7gjxqSwEm7b-Il6rl-0L5v+8 zHvQe@qXbf<nW;z%{!L*H;Xvp>3vk%7^L5{!5Ao60Xoo$ZB$^oV{-SOBu+E9X(U<vp z(Y%>u@b4Alx5KwQ`~!W<weZ#_H;?#fMelBRuc-6@gKo{C@hO?{fk8wDv^gy8hIu_w zg(hW46@@br^O*AfsjBll6dHt8MZg|ad!F*mmCBFWG9pk2?xarH+|0>*1Lb5}o#&b! z{}=q~V%1X(p&_>9x=EL$n|($mcSX%b@_*{M269t4#{&-y`apzxe(ve|xteNcqGaz} zc(*0+mky55{Us{9L4D+_FO17FL^Tj*FRnA)ThdU`#(Dset%$<#UPJ?o(h>;HvK$g^ zJ-W+zr`y}waNx1q7aMZ5Od~|I>ZI*bQ2ifL-}V)%+Rq^y2PcPhOr~f(xkc_@e+NpA zXg~vG-<em{rOriBwS&yDy1C8w)t%u<PpZb9R^L-~fA@gfS}~t*oKunAT~wKLQq`kt zjJBVd<}G?@juxavQlERh+W#rGeslJMZ?uLs2aIRn5Tvn|c=<!p)yb9Ig#ZEr>ZSg+ z=&mTF8IJ9_RGWeXGf&a!;9ah3KY4Fp+rLLTShutkMaWK}Hg0h`4khS7gfvXX!^b(_ zkkb<3_|nJ5aY#F|G5<bMF$dGTNCWniXd*w^<A^_WKEPW{2S@F0Y-iGgqyfQ_DR57e zdP|$1iGpsfPO=T4H_Vit!0)U$dX4u1s=AC=1(9#T#^WLZCXa%Cg9%_-n`(1<STVH+ z1={gAWqi?2GN3Fg1vNsF3q_rQ_bQ%<qR>W@^%9*wfS9ZEqs@%33&A`Q`z;8_(Enes z(QC7-w~I^*BkW|FZ>rV_6Q_*cnQGrcCaI5uH`5Zr^UK0yC}s1i{{}E5!^>FnF=IL+ zkAg8iW(y5vo%pp_PtnI1^`K`05e?H0F&E-jD^rp4he|{QkPq$6*4E7HnEyY7)ClaH z(6Hf}Ba9x3`^V0x!r0!&(k~`}NcmW8jy_X4)iuz-3X$pb@LR+ePf-Bx9Lrp;u09nr z=Lwj{d)eOP7gT8ocH7jsp{~_j!_iSU10Yv0M-;;-yJ3Etxw?$*`@?<XKBcwFqYG7I z4U*q%Lr6y$`THx32I3DoBysF86Z|>T+5+~+GRlHe8js*Sr1E$DpB@H$=PPbEV7q4c z`11%CRPS5x=YLG;_CNL>jNcjbz&;9`dv4zs>}JMB4`tb(Nwu-bj-rxhotpUP>~<dx zUd9_?3d(NfF9LNBee--3w4(N9jYot`D_3`jwE1V(Q3o8iboh=Czt&xBwEHzfyWdJ5 zj1qUD^6#d*JVSSUKvUv2h4sQ#@1Ir#Ov#}-8UDGvG}*S*Ck<xUm$9$r-I?}&tjqrI z8g^fc`8d)h*`C{W2if(pi#Itx_%6=aQ8&DQmm)kxe((52s-GZbPEGjP9p6qUejwfJ zd-arM%+!hXBoel$UP}&lEx#WgJSE`t;JKoiR-N^kK{IPq%;n++)x9O_(n?cg<?)D< zt{a=K=<ApnYd`U5N%Q!qbUCvmJNDM7m<sc(LlyE1{k9>pD*u@QE!TJozj1F~*WNdl z;1Ldgnw2C89Ya4|=B?cEUt1qo8w&Mzo42W|_kV|mV|Rh!+Fj!|u~pGEuDst6Qo8Xj zdG;Y$m6+h0QCX7oJ3SnGm!rVIVk6&jpKiv47_X{L3Z9a-DxhQABV$*HJlx7_e&s3Q z&|*lO4XTZWFC#=WnFcLS)m}U$^VTT4*YfE*>WwXy!k63bwv8FJtW8y$)$T3x=S`gU zuMLus{i+i*hpSr6{NVPu9#^vvuxPs4&-TC?;`3YhOa`G%n`CFv%w1DUs?(P7Qm=*# zU++*HeduT{QtnD+a2X}|>MLEUC|y98w{c;TcARQ_XaBOAt)2&4U-Y#$+{`mY>Fyaz zlH^HxYUE+Ls}lY~8!E2*8X=RO<^e)O$G$QD(Lae35xNqmi?!uVeZwk~X1}9>s|Q!- z7Ihhi9LtV6`LBR2v^TOVV5On^S2M$!F`)Wl#9NQu&c5;Bu$kpFALVtga8EY>UxH=v zSkxBdFSnkdfh?pdO{uE~oR4c@qBJkFwyW<C)9j|e2B}-*YP`0+^{4aBsGf~KSz_2w zN5+d-oz1uA)l^&4H#;6hO74z-L-KC!ERqie)lwP8u2*d;93u96UDDw}GYnc;vZT$s zuqoBHf3mARhuRODS-gt7werB`&6z3kv?Huvl#l2H3aDHBcihV@CKOJ~$LR(grnRM3 z3Ne3?V%9!4uX^QJ;!;&ngjV`Juf>#RcTN<VzI2wtd~D)`B}Cz6Bgzs6cdefpF)n_D znd?<u)o>-(f~TBKwFL)NWpe6c3Qy?o)owm^z4Dm+=cZ0XoFZA~bW*geai>%LCOf?E z9e6me<nLqU!^By%2R?SQad)Y!ze=?QvfQ9vHD-2udxgWhdtl5o<!3`aPQy1Ux|J~t zwgjm5TjD+Y*S)4AnZKkOt+KGK?fXOXs``wM;(^5Ax>?nhBC+u9=euQ}cstD<V_8IC zOEyo<MuvBBNL}HKgR9MZi*V9G0Vfq`A3_X}9$iTKV9dPAv5n;-hc_&ceikylX#!u3 z_|USiKEzU6^aG8#lg?Y)HEq1{S(Vm?;Mt0WD4gieUMnkdkI^Wj(e@Q^XP8+%IbXYF zSc?$rzkf-mYWO}jAmfEAkP~-(a+w;(Io&ulKGRG8lO}epa>yr-R-f@<&yjn^GW=!` zm4eaHmNTp+?`x&8bN!%PvC4E@kU$=)_j%qc)^FR>BJZPYxUR)JLO$COknr5q>_m<C zrIn{hHR?V$4v#+y%|go>k&2En`@}31&jeF6c9c28LsRZ`er395zV}Itc)QNqU(+w^ z$aufRtM*(-*AwC5jx+@>6$v|Q?q9HMi8GD2k7y`K4me*?VsGzQV|+SpdAxhH`QF1| zMxkqp%6PGbSl7a;F7L|g4;|-mUAJW`3*=Pt6!o$AvpaqMxajzID^9+5$1FLL_@C0b zq5hVlk0T@?`mx&|`vqE17x7=tlgcp-wP^heF<9RX4&rKnClG{@6jt5Kh>LaKuJKCY z`7=&(B|DA9YTU80yLf8$w=w4Y*4Vt?6&|-WKHa^AXf2C_hH6pYKnNsl_~+5)YAn&9 zj)+p*Cw4VkQcBC-OYGMkEk7m=_(fFc@{4+Ne{+r69hkPhvVs!mrq=nQ`q;FRCo0Ew z%?%vR_}0s`6_|K8Yzchkqq3qZb(Mh5bi?Cw6^+L$xA;7EOAAAlEh3F$m3>_<E}V=S zPg7$YD<Bq2bXoU3RK)!BM5V9X>%&$Am8RyQ6S@z;`suOrtd+^_uTu8Xr>lXVkWgGW zQg5-gf3%1>|5Z98Mi<WM7Syft&?}DIIbEY$`O}KSa$9LqP^H~SW~95^)@x7PvX5H) z?t|dxE~fA7of2tOIVa?{I(okjcz<<nP?f&4!X4#u2)~7<l#XSlq<&-K*PkQrt9DIG zWcunmK0r)AYU_I`Of`rewGox5wx2uuC8_Rdcv|xRRXj8+SLrr@izTjFj2Kj|I7Mf8 zT(34tT_4<BgfaMh?Tx-XNVr`Kdr%knWLJU;tNe4G=VQ0FOIjN*+bJeeE==v0+$4Ma z_prq?+7hc|cEmqY)#uT-cT|t^t0-?DJa!u%ALet$*!#v~w^A{tz_uA>lE&jmRM$s$ zw}@kL?`84<pYE;7A8Ved?bkJb;^1p@waPYgZ$}$LztX0H(Rtmr+D-CeIs%?MnoTWR zx}H2oW*;ot%rLTDvy7;u`O0UzHlV;84r80K3Zwm<J^eCjyO#ej%?B}$APx(0W{W(e zYdsf$E~hl2$R|&iVZPVcUzT;^N-SbNYN(o9d^S^12M5FvkyV?-N?!7_?9w;9Mk>yl zo*iBRK>G^5;tuBZ?hl#uJBO&gkdA!Ph+m)V$R8#+Jq+eIthR^p*=Ia=dNF|o2kirP zvaQf=`a|mXp0!dgN&&M&t3&OX+8kdTFkbE-KIo0SG3)4AH&?KtWQt?_-ZQGSC%@~R z=9-w3r@ULF_}cLVERE|h8UU^U&t=_?|43WCo=Lj;ROQ7;#(uz`oOgId_JXCBpS@nh zkJO~pXq4+e9zewlKQ1QN(0AyFryN@*e77W@YhsOZxg1x}xlZ<37kI9&YSURZBzDt^ z2H3GsId#ScNJEZ|WSOL6lGylS8taVU805Vd@RofdcWe2XW?uLEoqijJ`c1BK-uX_s z0>&|-l41`2K|u$0^53uej4|o%ZCJ9UQZJ^G;26}`S1FFo_}qh&Gw_rbO{NQzWl5g$ z_TK!e*TRZAa+I@2NJ5uhb#da`$-EaDAX+1YTm36<^v&^3RE?R8Po0iSjBS)!$_91t zZM;<+HDB5aGce~6<4wB;_6NbM5<0xLeYZY~*ZUlA>D&^@Uhy)nhe*aF`EbFOKt<OP zjl<HV{$->%`N{M*C~jgKViGPdJ`TE*xd^%}ZVGW+=|OR%@t6H4m5K+uKKVM@CY_Yf z-l+Dx)HEn+mzgC;)@ikm-F}}MD*{Y1D4b?l%d&GZZ@2Q7qv-&f<wC8{D%&r~*3%=T z8@YdaNV%J4v->@YbJ2t)Kl}cD{q0+t6(0#)N%_3gTg)`5tQXS8Hw}tUdPTcYo|JL5 zU)OfJFvr>^YKCeRjW=6|tmDA$5e|latiJTn-iD6-txWwkkA4q`oGb6mng+1Ox!N0Q zbBxZ|I(}0raw`dH`72S{tbXm<;kl~vN#?chE|uQbKjfNHEY2I!Lv0%s2=#J#KQpz< z<cCo(kBYqLEK7p%QMu!7)s0urwVIVNA6`mm15_|MHV+@Cx-sBfjN1O!XS#s%e6`)= z%vO)ukh0>Xou<R8q$)7c4T^Cz?HmT;v3+jv)x*xMabX<yz<v8=tI7~W`X*>Kwz{SL z9AhJ1x~=ny+PaeV0VyIy5MR7M)>9gCD$2b@m+?v=M@Z3B#r#TWUi6KqoU``l8W?@~ z;N(Z{R<%`^Z2RujQh99LfRwu#nfuQK?(^C=BG=RUcB@%Y#1fM<1@E<CUsOfhg4WTO zV|2T&?(>A1IHf8n|Mapy{0ol;ctqR^kKp|yS*$D<)zh+)4Zk*qzS_jdHvx(y+T@Tr z*EA1M*Q{I19t5O$Ok=qA`R_5S(pDwrg=-f&W_uc2ww)0}yaLMLneT{B8+FLLILqFC zaor&4Q3*wcy`VNy-w78)oVxw7m)0pt4BZmlCb88uIHq&sm#Xrke;Rb(4NKIH0l!sM zVE#LBRY&`MJ<RGTnHd&9&!yHJaj2rDc<-dP0TG{TKq7x8Q7$G4UcNTD(x4i6BxrNA zbR@nxuX&_(L8C5W>As3Kl`_kjb}Fh$GH3M{XYG#Edg6h;<K5QH=%+W%BRklc5NC9J zYFZlFvGC?g*$!pVCeb`P`Xw>o#aSsG?<Bnq+xYYEtE4hLotK=B)s3N74<M0hdtK3( zUD+p~$S3hB;`yN+0n!oUS3Zm>+9%SsxB*)#&MH+DI3rRzLcaKNz#o2_>=nyDspuY; zDi{4cVZ@}?`J3Z5C{r5W+5nF=xKOkC|NGd-ZqMZ1FH*YFW7t;t6y#I|*ZfuYb~?i7 zjq+tni9YhAh=a53FW)G7`LovXHsfy%k#AcZ-@KJ@e&;1kjcS`RxkDPd-7cFN{HA_y z@BPnbzoBS6dw;7BiNL=^E}0RR5g~uY&D=|i3sG9twRMG&(xW@t(Y&dl35Si><?El8 z-~WW8djQ{4dF4fC(kJhZf2r%+MyYV{J5Q)=9>$~ZxBnPXnlN8FJGyJHG#W)N$S~R6 zOT`E0R60`~A+bt%X?G~LSiA3*QN<j=l~AYt<J}y;J`2vNPIkBhP}Q$M(R|6sTfECY z6KbT&<b(gi0+RjmM<^C&Ix5m_As^Y5eE#^(?)iZ9+CTtZ$L5gha#7)H1^QCM)QLdp zHamPxyR|Y;wAdmyXnw8z;}Xv49c(#iUZyko(Vv$GHO*f8(BqYlwUgd?OP?<zj}$y5 z>U!WWYMW`i^~-+c+CTN4F{+M_x!YVJUTHzSVXkym*_Fn4Qq!ZGbVY5=JieFmuGmfG z{^#m=bMODRQohgTqbYMV_Lu7};f}WLtSp_XXf&-AZ7chfj($Id$jhuo`Nc_pyv9a8 zX&;qMdl~<zslK{%xBZp+g@tk5J5Oes-NpANYKZT#-CulUA6oa?7Dw~*x0ePP&wVmS zYHas$yk4`p26Mc5d}CHdRLMsQZBx9T&gcKXgAQ%^#HL9G&A)H{3rJy=8hocpD_>i5 zyyEC{Kdq=O^7?7N#U0#k%B$^3+VYp)S{G+}m}@+3?0S@xtXf95#Qfx$pCXz$!x^)5 zxg9b6ewr(<EOq>l(h+(&)9_T)m4k6bN>Rxy$X6|Y_8qC~(UqSfMehH7OVEz)gQg>s zHeXY;PAWY2S5o1ub?fyqR(94SNIxPshZiyG;(zcmdqP%x=F_m|q;bcusw1;+w_lF7 z9J+C12?pMWkG_#=6P93q(OYl->|7I!W*r5hX`$-g_5j5zLp!@qo)4^S+KiiV<(aC_ zuTJs!WagqY$vJ`3x#d7ra>U}yTaND^yM4Ljq<vJ3^a;IcmS5i$@*@`i(bDq1_BzLj zfB%>A1N_3(&IoocGj;^Fj4B$j{L1lD31OdQjJK|ra`*PTZa?#y#@l&3JjS{9_S;g& zZcl^a+DJuef4Rs%%}8a<Qn}hR`$-MEbpU#Ie5xuRp?#hF;Q1RjM22uMqu*Fbo}PCl z(z!jZzgOeZkGQU~ORNTst2m-fZ1Vobt1`?h;<mNPTkFgYZOl?%^R+q6)u3-jW|8LI zdl`N|F`)42tCvj6oD(;^=$#U7z*{h;ww2+QM^Wh!*)#2mu0d=KslK{Q|G{55F}qn( z{f-n_;r>hR%~J(`Y(H@$qzR@%W9o*HDeX4`rD)q1IG821B&?qWQJ-X&2jb}*hOCs1 z(WLZ`-HylU?eE(QoB^sMEB_bxciWb{W$E3gJ{e+k_RNYXUv}m}-dEo&8+)a&+#+vU z&={$>G0-75cllITI9|_MP3WF~^rn#HO}YeWyldIXrvOMkETf9GuzKSMwSCmOG4A#o zd3MWs>G!=W%eBAd)x7wAVgA?q&uv?=DcjllYue%Mg{J2$-8N(TYYFFeecYn6esr`* z;JWH$dR+ApN3@$W3r@EEdvvh)Y$$wH<q`WIyS0=g^qO(~V!i4c`$eC|KktsM+-5(7 zEbC*p^;1(fw-?8!+cqc~zq;3aXWEFL;)hnCCR(C;9XS<^s_~1g+uE9GIUmkJ&GSUS ziH7!GrVmV;<#&HiTQZ4Uv44VTx1W501M<nc8js#zKXy|%W@X{G>Nbpgq5aQtr@5w| z<MlgVDJrhyogyeAAtKf84pf!<{N8G||21=Nio8pg>@eD%Grd!BH{$Hr(R<2=^lOqn z#8H|3j#WG%d-z7~dR5iFZsqv-s?`;>b=vZvz!N7`CmiQCb!b{1wVtW2s30vqNv2A* zc4NMgyB++?FDaIcZWS`=a#*3ou~|N3dMC0=)nb@_y<z_e#ajO#Yzb)WOl#S6xBY;1 z(9mH;C*qwmSJ!sYw;#Lw_4rR!#g@NjhjzT%^8NZ9S<%jd$(43?HSJZEZ#V<nZ|Y2W z7l?d>^Jv~Beb<|T&kQ#;Kewf>b5c=`h`T`nPqcg>O<YtK^u4<Crd@M;9v&^E@dL#Y zz14KWQI^sX)pESaJE?C@t+UD??PJ|){q4NQ%6q;(-&9>RMZY9l`yJOrWaiw9NGz#w zE9h(crt{gqoi`Jt;q&!xbv@gWUEXiAqsvh$+pMOFX7%B33x5?)q&B5veT%xuaeC5u zxJp&=ht$Gtbg4eD;Cc_re<hJHHk@j0B!h?veGp%5Y;<Plb<YY^d=YZI&Gf0XV@B-3 z1k2y&Qf#}ti^}iXADvDu?!LT!hSOYIDjk(RuWWNTeW;2qsD801SA=B$rs!kw>`1OV zOzB`jA#AI{NtS;jwtG;le&g$B?YZGkPCMH4mb;{~RfK3N6&tS}J!N<+%S;q3^0p0d zG-sBd&s#aRDyp``F`(sp0nm6XqA7v!Z3>ZT{!UX*$5{7-h>jNyW-OH&1_+Vr>I@e` zzO<p)+_kl3#Dq4FXMIZA26QH$c`2J{98lk<@YT3p$Bx^Tzxsd7DX{+jQCvvl_0uQi zx8ufBut)sfFQ9+nH_K|_Tpv%IYIm4$>K24l{wEJfoEcQra`}0N$dD>iG<%69R<DHK z{#E){;8RP^Si@HQebX|+a%YL&=p@Bzd3sw!lJSX8GAq2&B28!Pxzlh?3lmCBD^=A| zXRn%i$BnHvD>`O*Xc=<JAC_cPoE_U6ZOZEtzFXvDP-RSJOv%gNK2IK^y?bn&WKJEY zi-D7KjAa#_^)Kb!`0AcAAyO(oOvZY&B<U$xYUWHVtz$0TyQ55=cfUd5w(i}TdAF~x zFn#omcN^0)d(FRf5Bg5oTD14NEd?Z}>e!~z_4b$KAyN01pUyUVrMP=7m0~7)uZ846 z(7Cin-*KcXioB^$68xarG-ZE0wC%aP^27GU#^N}M$JKncFw*OTl#kFDP3(6>?WtF| zSl{RpsPBfqP}SyrX_?r4+w_L^4$uh!Ft+`&5me@E^Ej!?U=ve+JIBR|PX)<38`0JK z;k+{)$hCpyhYrsslM&L9rFkpn*|aI2p6b7Unx|p$f3LpA^ik2>P2z@Uv;Q^Xa7$dY zS(Tg_uG<dc?+FTzghKaM@=Jry7*CPnXvf=)kq66FA6xngL;tfaAfLx!rKE1iZXRhL zIpAToBl|CpbxN&Iy4M#-Ez#_6RICQ?0Vb(9&$MyXjwt#0&vrGGZaRA-RnLl0?TGKH zIVitoMA+J1eK526=FDkHS7(|UN3vxr><l%X%6Y6!`J+d|&0S;D0v@|v#}UWq*nMX9 zF;YrmsXDe3`*tL}Kk`CEWNS`9-`I|SsqW8<SN4Y=S$*BsdgY{I^NrH}MV^EFQ(@X3 zP3i-=No-_4P$A#i6;<A`r0b)(Mu9CSVaJc4;%V%k-Ykl*Qvaa!Oo-f2mBQOHI<`*F zv9?dB$+>O~3RHYF>DrudbLNNdMkYii7Y)r$^AWY){@72Y&F>D&Xy_a=abEzWttkQe zv2n2vOf5H~ZSvCf1LY_%Q^EYibN{-}oa~w0^{IxOBO`_`4W~-tJ|gdAFWaiWXWHhI zq5Y-K|DYVvRGIRR5Y)awrsqyYxDPNZzGxpw9cLExRabTF0Qtt?OS+7=)7fo&VLC7S z7jWO{`=zrV)X(Lx42uxFIb=ri2h)T+T%v9{{^#Jor`0|P4FQp@S6yi|uvz2x<E?S4 zwAEcJ=N?Nbr6ytd9jB6#yo^ky_?m$D@6TXhb*(aCJ^t=k{ZH2(#@~l%HDo@ZU_x`L zvD4T+CVS`9vz@2EJ`vcbt5`d}v<0MJ3C)h>wQRmB&AHp9xZlvQs8asZu7sPH??rl5 zkkGV0rQ<~F*fi@Rb%2-#L9z{qAVx|@TH_<dK%23(&U2MiqEU)BQKm)pu*9o+as1|K zEk1w7=u#}17{1j~t0yN@4cDlCix_-nXoVv<t_T}iudcrO$+d^!_u;%$^*65o?2f)r zhX{8c6=(AWTf)1TWp!4<2Y@;?^NwvuDr@{^kt&LRDpE9$T83^egR24p{YWr778&mj z{;C!X_}DLr@M=3uCizglPPIZiShu<jyOd7SrxiYRK@h-9-iu4$>YX0#-e#uTAz&k0 ztpNB(d)-^H`+MWjifv<0oq*5zp7T~ll%UR>o!ao)H0AS47u$^8y~)}FQ#w9x{oIgn ze;v{@Sh`fBnWJqjImfB8B+W#nfmMM#DN}4*W_9|5!?Gpt<zG_dzzO9X3i;4lyYVCs zq|=(M?}%@OV*l@{6ESd|C$CE~w(npU<Oi+ar`U`utq#$AZZ*$|U`gKRtIa+)Mb1}k zTZQptj@)qC{NZj(M1ga6tZ|Iwz4$Qv9<bRJo$OVD1t*m^hh=DdjDP%E$e#D6s!f=7 z==N!?^Ug`9bpKu<aKE+o^Rk%V{?XWSG%lppT=UTp955Ox;+c%muRW3f!G;OOqr2|| z*+0M7Y&VT>((PC&zj%A}GOP0Hdv>MZv>)x%4_`N(%r@?QpYFdtYpCU^Atdt6skf@s z?(0)q!J-~?Zb&P(XK?$^*xU_T&-G2DUe!jt+fBiVjB-vYfydIwQzL6b)5j))=>7g( zX^Zi#AI@{3Z#anTqWj-`pkcGw!iEwc)~Mk_);_1c)wxa;b@~-)tn3$tQgB+W*mL-( ztaC@UqOo%iN$1zDmC$*+GFt~7<qqZ+Fd)GyGlVZy9anz|Fj`+I5Z0(@VqLgMQ<^&Y z(C$QY$I2E{vS-Y?FU3=p@_zE=LRC+(9Z|Jas2&re?V<`CE3XeN+F4NT7#w2u%3kY9 zG#%xFa&G#oejR(4k<%uryVf0E<+m{<HvPe}j@4c9_WY_=xZeoFILD|csVx8`qv{B$ zKP0>;CUpL&f2vGQzimUfL%tDue&O+XXL@(rltSyd29kh|s)DW%(a=$x+qb;1_S&zi zUWNZ!aeR)3D)|{w?IwnQ1=s0X@YR%i5x?7NxwT)9%WZOaWZpJf(WO+zDmcIntCX9h zr~c7VBu7E^KX%}V!n-LxozQpf?vAgMoq3CY(Tq7|skp7}torGbH-1yNO{nOyUwe<? zo`j`olrrDa`Pm)!7Ic1M3EQEs>I@;sBE4j`CRkNt()@Uu_WkxVs-v6B9bY~CzrIY5 z-dbH$eSzEEUjNrY>1e|4RTLW&?=_ipKHY&9)OQmes;)nFd*ju63jfJ>lcaI9cA7M5 zail_J6Q;5=W<gkAtV!pry)#m0|2IKr$dXjZA={N3Zt0}%UW>jntB$7ps2P4N)HOhP zr$TCp|7%CfEJhw8jAXKGj4OgcAt1M0J})&t^gr?2<fu+#th&{w<CBYyqI)gQQ(haI zlZXB6dd>XcgW}MxR(qg&_#fNXtqQ8+N{;4z0Uk?Fm$8L1R<g~}p#uXLja13d{$DTq zd#dXr<BIGv<NAF$cC5YEZdLx!<Hzla#s$lrKLtJ?a3|8Me~fX2ZA8-KhPyUs5cve1 zFxX4MhsAbn7aNrnU}X7cp8q}2F6laboj(T-jNfe8^!tnJm{!ptoxt5BOl`gLQr^v( z_f8-5h)?<L4bkWJnl1%^l@|`PR&8=F6<u%G-U-c}hLHbuD2}La{GD*~-QI8>x}NMC zR3$s;)YzWeQ{X(k=Ebs7{h6)Gtx(E#d*cNg?t>Sg1q6e(_Hc$~m{8pn(OrRz09RYN zChW6*%Lg<La-RI@r`u-7uwTci(o9u0)kEVgyj<IbJ;sjqU6U)5`aOH&47*11cz@@& zM!c+swPPg`fnb?K9CeCx#z@%B(3!g8`qZ!AP=wx2sPMnsDp#Jp`nsS~SQ8#L_{??Y z2P~<P_OAH#bx7T;Ds@P0md9=@u9dzU(af-=mDz@ZdC1YQhh~20(XEe`8h`ElI;+jw zKKyGhh@x$XtyFdtwL+z8f1a5K`b11U=VhRP;5^EMhawM53^#^o05NH*KBmC=Q^0an znw%~&$A$otDJ(7Gm%-nh$`8PWdv|)MYovpmtR0mpX2ELHVbe$<rhBeXrcjrffeVG+ z*t8Na^N+U^F1<UUpv_xmtR`V;?7IyehSq(LR-3){2}*VK=I+0k>^*gj$K#?eecXAG zDVl_3w&=gdEZUtVy%d1Sn!>?@nG<ta?Zq{k)}wz~rGwX^=r1(gO##*q?L+UEll6%& z^X_7$Fn8j;C-Xo-*LU}qG~@-wFJ?**e51B#fwJq1L%7E;P*|;S2|TV?1gD;x;L}Ac zFQf}!09M^;{oi-0mTwzE&Umi+Ff_z0;9UL>b5OP}+*fTLdS_pNjCEvayr?$U!&&+( zrSp*n<s+%R3|Yp|(q3EIzcP(4Wp68!jLuri0%c)JV@_{J0S!-+m}8x)YOYF^4!C#( zf>xifRE_|nt~$^&sL4pq6Q-2xXds>vtr?vXstz-;XtJMh0hNsUk*FbBth6s><|o-A z7MrN7K62RshhFTA#8|6$FA{_JST=6^fWtIKx-H!7HOPVZRKm8r9{(bOPXbMuOIsX8 z0VXnZ_UyQZx0%YdUhsEgOh8iM8S%PI_6df;A(Y;InwiSt=eujwO)PNb`5|!csUV3W zIpE4NL<0GVpC;f$r2%XbM`D@$fJ_CcX37wJrfDwn7h;SdRIE8(3;muuM(#m;R+kVP zsoYd*yQ`OV%v-|E%r<&*!Ggj7Q#Vk{*gMgS@bTC!f5t(BWa%e-T8gtk$c{0==Muo5 zg=wNC+(S??g?iCHv?pd9(>)CuC1P^vLR*R^W@Zpl&8lb@v)9+HjkIpe1g;SL3gW)? zl7G-$(Y@PAW56^{Pw1mV9b6srwYW_Yymg%dG*QN^eC!qi>%e+P+g#?-iWr0XW1Lif zNqhSo1PK2zo<HE$7-Mifp&iN?M(~Nf^Hp3PbFs3Nn_c9SjQSB<7T_fe9rWCPHYiw* zib^bOJ;`|_n+Y-6px-C6&e>X@Wl(=qqp4A@;)axlxPNHC7I;B(!(b>_7*#a`kjM^9 zEumhzqY2=Q=ZEkjc=vQNY%4nJq32R~i&<-)`qc#Mw_?l~r4c;f{+I<b4=|gJ#xoCH zH}{+oJ#D8@zoU00P`E>D8r82oAPt0WCX6k+souOT(=huvhzb@V;}z!9ZT>O&hIyI& z#9bsK7!R(#ERWGQ7AlS<p=2lwt=%FQEc_!Q#3#L0*kxTnKSg?uDvgy*CKSQiFXc-p zNkhAKPB@hPTPqntakDV4HP0vPEwXFY?V1!_TP{_k+Ej~IIwox1hSyoWIKH&eK3pd? zx%O&;LyA{ME2-_L(+BlF*DuNQE{Aq(X<a?BHTEOS@bHJ5yDzI+{>~Uz-gak+*%~EJ zt;`!mGDxbR^Un2R!dN_^Fx#5bSz9`=iquEg=YRDt*bLrxZknBzM{5q4ANHvnQU2I% zz)M<(dvIGH3Q(P33t>IRQ-V5qI%`|UKz_B|-I*D%)Y$Ovm!$mN#>ij}<9{Ot+cr=l zjc%3y+#9-6mkfJ|=9jImCcc}c$Vpc<KGw?P?84C*&$!Csp<b85i#sNmQrko9)4NU| z{$_3<cxCr1QtJzz(y>Wj*F5Ka<>BqhI(aL*#jbseS5uMbXvg@ICU!&7&cA4R+3qJ5 zub(9yQ-3qXFnfMLRFm#AE~T|Va!l~~W~jySPVXYx1kvKJ+Elktc#MQXI({!%->$i} z+c!-9Y-%slfAvE~ZT)6VfWb4nTbb~##ojrOs?E`wmC}25^od!f?tlb39(j|Dos5^C z+AsF2vz*moWct~0`qAp3!bKfZhZm~WUEKZpPqeLmb$#0=d2sF5fkCQY$-TxV(0k;` zT+47^$OhpxU&qWCu<3u(?3uuN%nT7>_NZI0ox4i8<cY&+?M{&gTfRPoIPU--`;OX} zAjX4`r?1LbD(;~fN{0OP-XNFt+Ny7@|Ll#=x~|=?w%z<=@g}p?r>P=dtvHuAq%_C$ zM`+;(rHz7B(%61Z*T0Bq09NQweZlw;P<CZ|KwDF90%>3Ux#uin9m;|)OB*dWjLZET zk*#0Fwocr`<=@)fu+u879UAJqWe_P6nH;RU+FOU_9f3uBvU0KzN%&kp$1vd?>5}oW z+gAr7?$>@j!e-vu9wJxVXh>m1SzzgoM>#61N-mn25m6deW^P^b=XSNbq9ygicO#r@ z4Vj7;;zEX=+}!$P?i;4`&f4TV`3R8G{}~%e8E-Gx1QUXZ(~b-Nc`E{|Vs^V5Jsb;| zPY5d%M-Zw4h3cW$-VUETucSENJsR)HNq-o#a4@kIf2&~aq0k3WF@(CpA$43z3$Ujx zTdW<rZX2|fgB4n$eL%hst??Y6)?be+lf@}*kVTDJ<$s1%S~_EkzxV%CYe`+`{0DRU zqdwA9PF?AY>iFeRj4Sr8Yo99({E(P_`B1hHW@@geI>>p_c}n#>voQO4raCzGs41yk z>jqO8+q48$R*%)(pZ%^tEZ)hW3tOX^W&C5;_tGijg2D_jR?eHpizkFni#|f$?!oZB zYi^6X-O;<7Su~$CykPC3wwd|Utsf0uscIh6WV%AZUuCU-sy%$>dA-FD<Rg+k&($`g zY~4)xME$^~9Y;YP;GSiCXLMQZdmbN#MxRQCfu;t`QMD5UK6c50e#)HXZI{5dmeBS} zh!RKU$w|-|KXmo!uZW(w@sS1F54rH0ra6nZ5nTk9N@`nMdcf!EN@Y?|Z2@FUZ97t) zLdPKGv70+iy!rMx2}umL{|Yy|bIt0K6OExP3nK^<<ED}l>RDeIVDmPTv%qGcwF7vv zKbFWs*GG(R>>(TyQam)Gvs=A4<ihV~l~)caGc?`=Ml3wY3aQwt31~HoXv9<8DZD=i z>^A}l>$|GSha#M<!{>{qLs;c4Wk4E8(yjH?22N471psGWDVmj`3oH=|;(UwJkkuxh zWQ-aWhzo*KtmaH3LBm1zVF&#h>Zw?_`9|kpOOksM(>h%us65;~Kbia%8(=Yq$Xy=# zn-Focl4nI)#l<TR5IA<?X{KlY`WpdVDVc=yF8W0Y;cBt>t@a;KPL>!pb|79KL_mX$ z3Oz>Sdjbs_(r4!9C=5x4k7a#04YAlL#u@8|GU^;5d_O}iQia9&V)YexeU-qa+&R?i z-Qy$@{e$Q@V0a9cophSh70oKE!p6nUVWR?xy}eT;mUY?uPxEc9nEirbMYGXQdxvZR z0rd-eo+%>qyGX`H2=tIQX`;Clt_gwU#|@wFSkG<NeV;(ofN>*@qc1jm(F@Cx)}c&1 zhHY{1A-`iu+?Z2cVvHQzivdFNmoRM`1b}u%1fbTVt55hiMP}@cEu|jn)o+Yw{!Q`Q zOCkfUR4A5>4mc)G*gnpebdo_MZ9bbD*fn4X0x*G)=)4_NtXR&o5?p3s4>pf2B!lFL z9hb718!$1EgfWIzpOcq+02e5u&5*O0bVjLsOMod5w3zq*wpg3a^jdQ*X@y~aGD!-^ zDbJ@iOY}J<>Y+T!$TtTjl(<Oj8PcgAX?G!JT7swCDVdnTC@WyK$_ZzcR}|tOFb+GR zH05;~&%oaISd7%r2#Y<6-9rJ!S5&tt{qva}LXH#&n2B9FMTiDg8B5zl*C>qCa((Xq zB4DMHqjUc|6PBhH4Kwr`TXLN90-cUE@D}#jV7MY*s=f$#D2ywj+cdVzFW67*p27@< zkP05fk4)cr1ojF!rC7i?&zWms*#mAX6xo;3Hjk~tcwwYH7%_4{<B-t8tVy-e=kim% zGV_3V%Ug;4cUC&9m*^SLu;J{Cr<~OcVz)V$iU6FnahO;}oUdfMlyl4p7Au(1{N(Yw za_SP5JV}cnlS)-0%HAeG##$b0=p2SBat%`|t#WO5L2k+_!!_Z_v>*&FQ9@ZlV;tFi zcI9y9An|ng>Rjs5i&<h&&u#V=%yuD47fN}Y3u_3Ug3KC|fNR8jGh>b7riG^RRHfm^ z--KKksGd$Cym!WTBa_dt05Xba#tK4PEK@B!kxpU(f=enL=huRbp`(|BCX^S&fe(TV z9C}zwL6t%!ipdUfCfNX(j_JVIY7<KPT)WEZnQTj?x<?aF+sPo7#*5sO+L}(2#lC_W zboKCqG4Vy{3$5wlx$`g-Ad(0)pc0m*AZn&UNGn)KL_q$tjPFui&k4}qmYb%a36~L( z-ihRkw48r3wTsH(lSx9YWv|@anSwT4i9gMMsF>27APT2!u6qKri!{Ty(zI!BDRB#T zrg4|7mi6T)T`xMDf}T?cnFr}w=9H<Q0H5CMg(S95`YdF~RiJxy^JoH&<=2>kTYUo| zKltt4D})B1P+V9`1WRbrj!9<{g(4<Kf;bhWwX292;!GN*QVG(+;z=`&@umlF{UF3# zzJ(zP__^Jp?mDRN!b>?P>?PyJb<YxZw}bkzR>pVKHZf%K?V&mS5HiH!ZpE-4B<b)P zLeVH;xd=mdP&?o^(Mem5Jt$Ef7T>&}2fmjG0MDnko8<}4Di5`{+zfblKt78o1jDJd ze5dLbTf#Dy#_$+WZ?dojp1uyxwM3&z+#^U|V@nNuw@~>}uyq0}MSP$r;By&)#67(* zxhi3xg8EjRq+=f!MLD;UDMmwcDXVZD(}nk<MEjU|VM1qRC%p_3PeZPZxY;`FOl|*z z{?Kj>!5E^s5G}@*AycgYmQ}J@j7~j+MYu|aoF<Vy`@7}Y@%&J`qNs}unGn6a#rtG^ zCLR4+j&lVxOpF-e-}5jskrx-G&5qC>$wgxJQ=?4Eq{tdgFn3rWT5naYeTC+MDqoq3 zFO?(fT#hbm#zt*m&|Q6%ORu?NpjIpfi6F<I$(AKnrf{1a3h2PBN}y+Ra_?OQO*X3R zIg|{%)@!Wa5CK;F5t(Ds_PxIi(7<=D^8n4Lue8?Vdjuzznxym3`3CJPS8<OJfy=~6 zcB<3G*-grNl86Aa80eSXp=*Im_~?fk1Wy1VNMdxU_%fa%$U<+&dK+aaj|vLho%z5- zMFN_z*dR`bnIe<}2o8`OqJ-MKQmz$VexKTlq}~Z^WkEg4l}98*uF{AMVm|`+DxI>G z%p#K6_-b@^oAFUL^kL+~+!!fBj;bRYg+IqY8_6A}DZG`At!B><uUMABWf=vVGc1J5 zN@5-o-N9VuII9ebcJZ2om>}cJVZ3NGoSl!|2sWkI4CB<xWNW5@07me%C#5Tifejui zU>%`m0Xl~SBD*%0Gh54eI0V?0yu0xt^@<VcZV3pUYZ_C<EnWfZbFyt11<PnUejMBb z4oe^<VW8yLtj3FRS9+G@{PWh4W@b!ZOn)&w7bJ|kI*YP*i^I|mVncitW7XmSE99?) zdh7s5-<~{bw8GDmi!=wE=k#Tu%koQN5TiQ*ML-LrDDxWGvaR!Y+rWZlQ2>rp!Q3P5 zMJ~ltj?7TAc?3kNWj?qtO%gT-^qtF`vI`!$Vv8=C9&OvM<AnojCF~LQTme#ZH7?n< z28V&82}L($u@tjoTg_-S`D#kZejF7OsDxYRa#vyhkB$trp0-`gj9>Vw_v@34p2=oK z+H{wA!O;T_FcxI6L`<Rk^+&V|+shD9qC0Btq9fsNw-vdstfduTa~=4pD*JLe^ypo* zuQ4`wi?nNn1_hEff<z~otYN{@q`9P?-oihCP2qyrzDss=IUy>UHv$Bg<89<*i^H3d z5Uz<dXff?F0c7lqHY0y3(4`pg?8^N*c{<S+LyFM{2C*%;4GfD=&O(ZZk^D3nvhmTS zt=?^;<4SlQdbx}5eE9ti&jFanIK%?5%=)uMboM0MfRg<T!7|TYB&wg2Q2zxSK+Z>5 zv_q9la_;z9&k14rFsIs8Gkqu}96Y}ZUb#vK={F}}MUC{kiadbH@LEM$^=Ww0q$5|T zWHOf6jAv%G>Kz;JCQac$$VY-2LY7+d#zAlkkJ{)k9Vh3p7gSfmXg_r*?KgqBsyJda z{x2kI3mp1!;LyZZ6KIeu)$P{wrab<B6<gN0$Q$e_Z&o@h<hPKvA)JZsuH(_3wu8c4 z30!xWI#w|uDYaAGcUm(uq%rKJ#0^dH&Q+X(hBEw#S8*bU#0h5@ec6SR)n+@#W5sjv zA)Hb{<==zf5EKN^#Ron6sIC<$Q$f#JdLa7wPl^1$znPKowvijf+hPrZ7BELpQ3y!W zGa@l4F-*8KBdXJv)D)tz2mwJo8DkX=oD-|Xt@&D2b>9nA`iG0S7_kN<on<%GddE=) zylctXhX!)i!-}fQSS;cKUil?{JA6S&wV#d58ShDy%tHNZDUt~7mzenG`e92=nJ5-x ziUKr@BN1kcRX#@<1`bOOMV-}lX%Ft!Ak5Z3trO8=wJTA)azzScTC_$-cpNRvaZO2$ z5C7pARf$U6(?i$FT^}XCnoDo=+XqSF8+N8{`c{D0j-x=80s?HxB#pEBF!ZnJCNO33 zt>U`jDcD$egswJ;sd#65rwkLX0OaL@YD|_4Gmax7JfCy%{MF{#=C*&jxjOZ?@=_xf z%L{mPY2%C7X0j@6gble3u$$>C6s$Fx%o<MDLE&VJ>>o3hN`mTjZ>n_Fr$c#2l8`tA zHF#tJpEOfmlTT%mk-1ufM&i@<`fVrBTp^tsx5wBC3@KVahY%{H)?wB**cCd&SQSzf zBX4)UIIl#+?10rc_kc=$NoJ>kXE=-OiU-f7XcP>sQ0b|<ZQ?;Dn?s6wAi>DNrX!~r zDt3*o#a~Xcf!w!Q>(^Cr0@=Hfq!l9@Vn1GSFRDQ=tVN0C#CN0M9OaW<Bb80hE}{}* z0Lhh2*>|{;M4S|jpNv>^cjToRQSw_!Y*`1=sz_IGb+bo~Nh9;r9mTXm336@nvL9Q1 zwT#golMdQ(!U-E6y~H3c8JsNCDyxgMEJ}g-0q(2AG^xV(^~bqao2_(cN)8ZAiyVLO zYM6uZNgw(|zM?!%-%jeu>`uOUmQ!E{(YF5R()cju;-8@da|A<oq+nAwDLg}pTmfdM z3;jnYsxMK<wRx3ibC4IcNx;c_tg3ubeDSO&^0}NxBMGRb(-nnI0U7~#340bb;9U+k z|N3Tc?uCJNB>3G26-I6+!Mq_Iltq<+WQP3&t^%<(vPX^JWK7ADaPssZ&~kR(nDd19 zFJgZfJ+I89YpfE(dycBtRf_D3ifwYId4cdWchnSWVwYoLe&S?tDTa@+--N~D6YC7@ zcEfxC@O2cJ^YHNNnQ$lV@K2<8Ar%2RRoKNr8x0AlyI|ocgQ%22(R8dhEY1s1FwWEk zday=kokk<yNJA?_606t|mP?#MRBCT!UY^8jED%ah&8TIGTGVxTkL)4o5A#+?VzFYE zO=cSK3(<`p<v1bhP@uequhC7Xvqrptjow`w{F}ye1+TP7D5VI|B>>#fO5zf=r^uzG zT1OG-ngu`48HfRWXMr^3aC3m@)YhnnPvbfjj~II9g;9ea6e#Isk#iZ(xB0nwCsvTq z@xUs@9vm+~R&mU1JPcN+*@o#mJvfW{<|0u3I}DUMOvl7i@uEb;+twd^q6$L=%J+}- ziU7G#2<C4Y`woE{lSO<N@^QIHE>lbFnxFKCkzq;*1{*Hpb2)R#yzqJviIQ?Hlw~9f zNVtCE%UWYHSl*yy5AUfoT%BBN$V_^Q(?x^=e&*@24icUQ+B7I(#1Ls$iOmusi5x3d zsMZ>9{V1Lw6&y9v!-$jo9gVpXRoie4X4yb~*XDQd4G)cbLL5bQ4Lvi_pQNmsT+fn` z@$$DUfLMYy4WVaprCdFz?=wmL9x*Fn@0{Lt#yuetv!M*b5lJj`PadKn)nlzakAfs> zymRS4(8ft*5~qoG<-AEm3wl6d(hq~QQ0NLQSs)v07$C*UiDdBh<mqf*rj~GDC8&Jz z;&~iJv`kgawP_0+CqTn^PHP1X>gv1^&@d?d0F8*vmNv%cv6v6JOP$ESW<e-BPz&&c zkS1vBtduxI0(YO}kHe>~5nZ&B;M`|6pksq$#ngRTFAlwi<Zl3*#E>GPHkoAhrbsi^ z9`H_Kh%O9cAiP#zd{0qpGidEwXzwAxn7dwC?r9VcjxesxpDvvs&s;tZu$lIqD?^IL zrHw|}ut-J4Kz~WNRR1{X1kJnVSq60*p_(|V177N`Q&Z<4tkaq5rV&xA6HF7WbN4n& zH4jSYUg=O<CxPT)IdAd8$RKHu3-=A}|B(fUX-ajok;?K~u8<yskW$azVNwJ?y@Kmd zp-aldtq5Sq0wDEpsE2^hkRQ4+zx7l?gmVJ#&nPslcE3pvpaB=b$^-G2YvO<GGxpRL z0hx4K(f0dJ_$G>Z;d)q)4MGdOo94Xi^Z>{p2MB@SH(o@fhZkvN!}`?FVPiK+C#_Gi zqKqh8uv-`%JRvzN!W7;ciiBkh#w<h}>f}RHl(q+)EMD(<zaSs}-3Im`N*uhH74?3` zL%|cprn{x}+S^%7T8n%pcvDo906gheVJsGOYx>+x)QnyRvgUFInvfeduLu$yBfE6j zRN%edFvTlKWQn{P3yXA^+LunIi1iSJ5m64>>Kw7|6u-=bve#>M4oXQP@C%o#0y2`u zQ`d-Bu~TYhS)vkN3~7atvYVG#;6ukGipcQr`&iEwOwhR$^HS-M%W!!-*L|}B5!w-Y z@jUnJX79aPaqvMCMIp(@u30H~d!Y`H(b}d5IDzw(;(xFPqMyxJ%cZ&t%8oF7j4RkM z8}91tIwcYHwpT<NIH6Cvs;QFjZ^H2t2Wb2x7e$jr18KOP(ds=<@z=)gd>+y5^DI~N zaRP+w-{INcf{TKk!lm#}WX>o~=5t9@#-?`3K6hguae>B;3)*o2;Rr8-%Nm8N>Db4y zJ}*a-22q_ZDWWt=#y9NDSiWGRz9^YNX!5_d3+&r+bcwrmbmF+WYZsC=3M8KVquT83 zPMR#5212`uG-<M<V9XOdPQqqIKFTE+!mLWe)<@+^3ae831rPwsfJk7tHjDSaZ*Y%{ zr2>+*yGpy51vFOp66fHBRfk=E(b3c2yX@1ZZ09Wx3K7(A$Mh2E;eN3W1Q#+JXj&Vc zS)sO@(BebGxATGg7rq-|QeJjObXm_nK2T1JR99q<+l<R=LxA|(%1UUOznh|F?7wZ8 z$T2|*cFy){l5Fpbse1ff4`z{p<zcbJEFjrXa?H_yUA*x7^`2tzE+Jz3cVrm3mP`w< zueP_SgsEpr%SCnh6vjzdy2hHqaWnPk8w$XJ&A%Q0s)f*)A>LwknrFM>I_jWfAAWXN zlo5f|Zqxp$k*CLCfS77d)h~%cM?w3GVG1`K_Wyc17qBSnH0)dHqP0cpW?zPk8>8bX z*tCP-z~p8-j)xu3r$8z(BHIjva1`e)?4VmQGKhrcj4LP-2zg3HaxyJM%t<_;CSWpv zfN~fR7-r_}`~9cy`mVk9x=e@RegB8&a6k8RKU~c4smg6;t-IpH5?1bOY>Ak8!k_{~ zBsAUYG&Wx&{kF{2-UpGeY^}2rEYx2f5*7EYM3gJPvg=_h<W9i(T2E(QnaGWl33I#e zz2uFi3p){sqnPBYRCQAH3eO?1jD!zI)VrMGT=_92IA%2-Kq4<=#++`%eer@7624M5 zD`VlM6%@Eh^Oxa)3mO<yA<mjBZiIs3C!F4uI`5u1zidUi01OPz0BA_>+yJ0YUCUwH zYhLgGp<Sn4e0?+Em(8XHE(zg@7f<VR43R4G1RxM#HE!}u<u<taoQSV>J#^memP<6` z0(^;8RMr=ym#MM?u#?`E+Q8$m(;Ajdg=NJfT%G%u1C-eBKF)au7&C3?M>NBAnLtPk zcAhpnL9o01LufV{q4OT=q$oX^1JBG*M)VL13HJ~+_I1<wjRN|DIKcEelY1HS&e0um zySuimdeTYq=lKk=rZ>@uAgF+SBvdPb5JiaL>D;F|suI-*j0}qLm+ZbOk6hnxdD_+W zf~!IZ$Q;d)q%-vR2UwOFxIrD~3PvA?lWUQP(F;3Ot~>HIfx8|l2jXg4QuHSNGsf&s z{9zMWkV~jcEEVxr=Y@kYRU)`NQihpdw|cMk8xf2JdwyX%E}g$VD<j7=o2Uw2OtlE| zgkq@)RSDvn^R%KHGVQv;sSUc}dYs-mRI)bRqr9aC#$+vz&v_@&di|h)QUswTFKgPi zlQD6)S8=SfRrJOct(J$ZqLz={Ca}q#W*qk|tCsBJ;Z?A%hJ|m2rUAZxsU}boh{Rqz zLY^qX-0vub>ef;990bQt^0NNu7wDAkcIj@n=+xgs`8g)c;;_e7<PoFm?>pJRNbcRG zkW!oGJVEdA<LVWvtcDF{$<+wRQk}M^`%WWj2sQjp0iYcj^X;19@MMMJI$zbaGw?an z*~(oa+&2IL^60B@)nfhzIH`z~k=^`qq{;o*CE17&!n?Y9e-@GBX3M<1R^i>?VT%a6 zfVYG}Z=lOX05sT7(cc=AJfDAs57cbf6meGsyrKY>BchF^3>Yy+#g+YDfh3yF2U&%V z?dbhL3h|~Sh-?nH)Ezaq;i-vuWByYB&`5>xyXl(ML}1_D=PLF7c1$b&y{TdT$aasF zZ0!i2yW%qIrY;^sYU25x6F9~^8MEZ+0@Z_gvNbT^M5?An4~<5=2m+6)&xC0SXxAwd z2b_-!{;Rd4Ek1zPg5jC^#cm)X5kgwKE05TIA3-oQ=^jatk<eQ@K5hG7nU#0%ac#r= zo=?vI7a;(}3Ez|yLK;$NaS`!^qK)Fc!;W_04=SdsS@p&}Do>D8=hxR8bRB=?$ep`G zgo2SiZ#_%E5f(mMxPNu8wvp3mAE0PA;abf40S_Md{3M4zgiH$Zl@68$B~qb=(6nb2 zppnun6{ixOxz8b^#6kJG-LUoe&u<wR8;mWnaJ1!hbE(IQAeMzPjEF1$AGwXX7gATO zRy>p2cH|WHn~{;OFN*)+TLePdS(a&O)5H(>QgV+73@@8b%i2~?uRtLFLz5c^kv}Ou zurViic+W&hOgcF0V4!m_1y_EOBC8<e*zeN6D!onL$ah<HIiy|L$$r_Y)^5q_j+=gR zzUsV_H>QiLm|udJw83+nVhp*Id}Gn!?Lawolm!?mYJR)PeN3(jK=CQ{3-mW)TZQrf zC8@gIp&H2-Re#V?R)00m6U6d#^bF9B{)~Ah0m;T#dD<?^3JvK8g<e<eLQOnFyn@cB zeP=sx%ROOr_c6$7)H?((TiGW_08L5h{|d<#38$6BX0oS8<WTI^1k8Y(a_)xdbh{?I zAxcPyz5!5MN-e@2%RjfwnHXcyWSn2i<=#f7AxcifyFuxUJn|%+@S2F!5~4-5QglA2 zh6i3kd#Tns?fctBZ<fOo^SwmV9vvPrg9_8AcmL?Of~~QYDZGdFDKFk5Xm?9(U>Js9 zpL{N+#ObRw-iK_USAx&EhJ;&tT93wDyahr`>Uqz~iGqXv{CcWOT{h2WO9z|}fy^KZ z>;)#-ZQdL~)PeA^^U{X@==LmQr&~OBNQHuQw(h+hs#duQr6UGAn~uMH-ufI^n=ffF z8=VE^^*50G5J%_`rR=I#MrVRxmI=%7TUc!Oe?H3&kXDI9z0DGt_*lcERcO>6f~|0c zM01jZZL1ZK@D0gXS+ex`>K8-FGZ=gJlXi6GUa$`tLl&?;Xjkx>HRWn#Rs}0TY745B z4@t;Whf+cdL9bcrCJtEq%IF=rxWDe>49AVkoHzR=9pFP{qrh;sCCoRK&b?56Ql~D* z{OpY<37DsL8X%(xIC1G~7jN7-sHbBm>1ifJsLx_Cylc!eibrSW66j>B$w8nEG%fw; z6OCY)%ypjykb+|E!m2@=FgSfTtSG+fl>tScV_5LsLbgalEwJjJT)pIIY-v&A(vQl0 z!IB~ic_UFdlwU#koniuhioNrhQR~DK#lbuC494giHu@I86>1Eb{jJx2l`0;|ucLZ< za|nmyS>>*x6_41>q1Zccs~Bj@hhTh^jVmRS65MnV;iZK&t&o4DKy^2xtdR_I;*2!I z^J5%T>VT%5r|sVQ2hOjliSC2<TMX|<Y0ehiFJRU_z`5Lg?oP@t5Bo9Vja*$`rf*mf zU!J4&^Q@(krs%Ur%y{UlhFuUya9dQUfQx&Y1ZT@v66*!sN>aR28N<I{k_>!*GA<ci z*6w>xQsep7*sAGUP3$`6u@xEMH6oT?tYR7mC@*Zy8#WH08cVtJJy_3gA06!JdpEv} zDrar^v~@+<0PWk~6@>#IxwT^Qoe2&H1WGZ3s#7GF7Fx?OAO-mXQzOL@r4N_vO&Z)> zvKqU1d%g%(n}B69{XEKH1l0*|e+y{qyVNH6c;$hBvKKg{!o^M`h*Q+=1F@n8#0P3- zG_AOjcpbTvt{u@637MRsFwDG(yY-JR(KhG<cdT-k14|=Dvti-|n)Yg4>#=^=Sb;#i z+Z+n3oD#Q2r1cu+aM<<Uyr^lGk%uiB*I%x|T7XNc{+>A!?HN=1TVmGzrx+O!r8CHN zXT*i&8qjW0#3w*Pb{#G)z#AroW~DUTyK_X+khSdj^twxl*L+4NM&TODjl8IWqv;=V zclf)CQdYTpx?`7C1%e~d7)3$RxN@AKgWeUn-2MFy&bFrOLW#b2wvssS)&W5@UwVpZ z4slw~=nSe`0Uy}#X`-9XDtd{wG%bmJp^?9Lp9RE-<jyDLn(SQ4^PPlx9Nb@F2pW=C zJB_zB?l)xVd}6seE_u|Mco*hb;F7mYFa$2X5pcI%-$<=U)fO?m$-Jx__pE8XMaoT< z);azI|A1)Dr5OEyVk^fYk9&79QTj1HpK_n9r@V-faaMl*Si|2wcu9I^deGq#i~fFs zw!c)W2XXm)|BFPtXJN&Og}1qFautu>@|Hdzy4)`-ybA_qF;}o;qdb($8?5hY(s2H` z#5MCD*{ZzcQ#x!AYMB_4t=iw+wjkj?@pluNYdxwb+qI4jCxu^YQM$L5tK(s_dTl-A zbcm)edL*+EIj|AM+1)y-)l1906y;;5)hKMDx_>da^r)!7W1y4X)DMrM5;w|Yi6KYf z4m(FIhALRX{R$0f1WkhwO+|F~j}xRHC*{N6eqS$|x~d2FB8Gre`eF0*mPzuEwvY<* z6jv=wF>gH-ME5yW$LBOljk;-BIqac-`wwiM_b=-)I^{YmHNjTJ#v^e;(?<=tppSl) z>J_@%#hQxF;O0>EY(lj7>N5KC<aHCK?DY5ieH}S@^Ihh#IiRR$Qt!uR#HK5U7)ak8 zNp}71)j<_bfeK$W-qs7SV>S}4X#;^_EaF_)!zKjfn@+tXPfOTfwX={QP_2Ruw$<MI z%6pAO%Ji7Y%QQgi1RzCk>4#2rLmC!e1RAu^(UAzjiZI<6Bf=PYUj6v&ow1&0CQ=XR zKJgUicAL~BN%D=ks!vuVf2p)xdYzX%(djvdbNM|uZ4j0841wGn*Lsu}al5i1@$UGY zA6p(1RiyR*hcAG@&e^iJHm~)J5D}=iP>6rdZux>;*gi;wiH;Do6vp*<qWV)nJ49Cn zCWzcKafvq0?~_|jjYGAH`irair{Yg{xkK9S7esdlAxe0z^Q<Sz0a{co(qMv%ZAnVw zxU}g2gVuW#3mbG`CVO5#F~!#V>b;b5rsW9(W#}R0PSovg5>1ltWl#iAWJk_2PN2>` zT?JzgLHdq!#iR-U1aeavFhf0K>Z2Z+QhTuJWOUZ(LXmwnelqE9*er?DiUJ9^Ozlk( zy8o!Vov*g{whK52^d1MOabCy~uPKG}Y{9Mdl?Uo;=6@Ub$*P<?bM5usB7?XPYR|Ez z^lMGeopM(o{l!E}t)G0UXo&uC0lr-iqC^k58Y_3lbS4>M$P_AGL@~@tzWC;Q>lD}2 z8dxEgW*mBhAxUwq>+Qx`#f?&%>-Xh+_n-kcIV5Gdu-;B^oZi$w9xYW&8Tg_!Ab7#t zYJ)M5MN6-Rs^GTOmW}cs{Rx_x>1v9pUBW7KTfJ+F!!yp@$jVk_Q(2AaE7}8MT^1m~ zm+&C>*1NM!y3Q_|vAa-$>T44>cVOFLEA+l^S%ec#hh&qb<mGEd@5wg^78Tx0abwwG zp?9t6i+%OK;SWD@@5vtHax++XpS|ligiPJ&g1zN`HS2QANQ{HhN*nE$S;B4H(dYL? zTq%(3H}O#R;LjhZ)fL6DECq*;Smo_{M9i_9&yLf*P(fOKIPS$m{QPVvKe6>ymhuSt zU?&7aoQK0cBTY~4daw<LR>XDv{DC`9E+<=kPCmUtU}*JUE5e8N?$#gH)?d59cg%8Z z?8$6QMvCl&Sr$-oS}1P&9@(zFB5h~Z>r<LMS~U%#F&lv?zS7Q-eq5+d&?(YsyJvpm zS!a(c^9OxE2Syq6Z7JT05iZ7Qz>mD1rry%muhsVZI8fSZmw-0I)tj0hDIOXHcUDCA zR357a!y{n}F*+5b)N@@N3#lo24w1-(52qaWEKJs9*K+~N-DiaHT&Vedw9O<hhpC#y zdW`?VJcY}ywDwKRF<%`dFq*3nFrxZ>plDC8#Uw~)&D{U#j&HI8M^Z-AQysY!>Hxz^ zsMN+K5do20c2YRmXm^bir5I1*1H$((#A4Y7f*Ty2)tIef=(nb>?L6h-J+E^*;7D;M zcTcAw&316kUygc|j{`Z<ML{vw=-idDL^xK1n$LNTG9ze*gD&Z;)sTYHa-1plnhoh9 zw3G<#EQt^78GXplih^MZ^`;py>l{cbwUDJTzv}tI+7KuOg5r_5S%C1Hf_6R9*}{3R zBJfX`oQ#>l#x)o+1LD-6k^-@Z!tCyKpk}G%-;}!skuZ%EbfSql)`j?jD>Ud%%yxr< zGQjg`em;C$sJaX&Pk6}esV_aN{|4{g%&ZsFLdwMsJ*ze2Q(8O3Obil;7j+!MvNG@C z{n~`f^sb&#Wx-1k#o8&KH;LlK#c_q!6ViP+?7U(8MF&;sVn%a4l9hM42#dNco`(-h z3!l*n#Sm~j?Hjl}jNY!lC>l9xbT60JojhTFl-uGxoF7zT695Ah@(>)LyCfe)eNUHg z?umxMFgX$!TGsDCcfm3CTpu8+?ZKNHS=4P=gDdHGq3Ax=G7F=$nN+`V{<;1g2$e`> zH;pUGv{rSz?34uEcsAoND5DQ@Z|Z?4Cm(8EK&?SA!C-ihku7)#kt#Hws7C?OZVoQB z)kN$eb!9T-5i`hLswM=OXVJ(b>9B=^L&uLCjJj8+5*8cJsdN7#`n*!&%ac`BoNj)^ zX^vlie^e`VqxOsQt8R9EnD3Yh1s2ck1OCNG%4@8J#@85gG3mYV7hAa&^*?hVFIWS2 zkaiwsZ0U#Ny`TC|6yy(pch$AmGb+4gtxQKfm?!*=j{L4<q3LcmYb6W0)9Ndo56r)N zfc0BP5RRkFuR8*B^n=awIqMp76S`q>WlJG13I2=b_W<Y)2qR)bq|$v44tn-=-0?L0 z7A1voYwx|z$z>-yo_J=haUe$r79<4d5{v(1poWE=V;(Fq44K_v*aEFF(ioGZUULfa zT=ptf8@flN>GVHHPpLYQgkJQ17N-z(l<%w_K@%G9Eg4vs7T!)tCuQAFd5{d(;(_^f zPrMZ#Sg8-`31rkMWY$YFsC!L1OQHr~%pto|vZZ0->sMCL`YT~ge$&_%ckO69GF6pM z^e>nv&I?6lIXA$;ac0cL0g%&o)?eB5?CWeBvVqM-0Xetmp_tqVDFgV==8m1W_M$RF zi->NYy#}1YHRqIHI!H-HC`Mpr-9GYxnQsJ8*cBCEcjn;@byF<!`C>>QtVmvK%bxb( z(w-=$)xHQ5roQS0MQdwNn*T(Ywm0L;qC!6M*dnB0>_jrpTM^cOLk1lp|N425GEG|o zu6~%0ZjKnUM6e)Js3^wXEP5}rxWSBs?u+~og?M~PgzkkgEY4RNZ?a{^@{6|5=VxtG zO;!9f{*is^UWb`%!dGm94|}HKk)<SXVA9qWs@(UndB^Ea+Mx>|19+IsK#*w<;p7wT zLG#Rm)b_jkI1k&5({?ni@l#G2q3}%jT$<FX55S{jtInLziPHiOzSa_%^ogQ7E32_A zf^46gs9mVEfWkWs+ZW&PkvS^3!}s<qJZ&D4Rv-^c`k3;yE@-c|W8RN%Q-^mEEo%i) zt>lNa@MU5-B6e~hs9@UUSN1vNN_fnwi*@X?%`SQ{=Ktc*#6I?Oo9Ee?(;@z*B~oF5 zCDp63dnfIk+VSR(eUnui@6DSEyR|`D<7q2g(t2e45{K9Og#`310%nCZpQZ)t8)khF zEH6%Y=Bo)g>*Znp`OK=w9&uTug7Bb_s%Jmm{E@5V9Z!g^KCAxTvJ%)huMA7yx1h7! zU52wkzjmKezA8AzP?33RaJBS3fx8ce>3f%6Rdn?{#O8*oOVTu(Z@ioCG6S+e5-Oam zIkG=Cqo;4R_t0)#YaL%y*;N~%r_sc7Xjf$V3wgZ<-sqp8Q$D#oGQJ%0L87+f&C`Mi z%nRfiqu!t_K=Ad!L||pqA>stY-ceq_OK-5vrs5LA1j+#kIlD4$N9EGUGOCJ=NfsFJ z`Ami9+3{>hDit4tE9s+v?OWl8WUX5*oM}*6UdBBqRE6ZdE(Rtuol<?qJ$d^9&#On% z)^C!_lPHSu{A;+ab2UG$TEB#EjoTo&b*&o^RG8U2GHo)NxZq;};u45*{0!Bx%ccC{ z+bj2odYH)fWhd{6=Na1>{8K{CDtXvDQDB~N8v+#YyqilELtnS(tFP(FeSP(b%um9v z?x}CvFym(sOlsHSjKKg8GDAYH_ZDY)jFE}wE*;pf`f0k_)Z1mHCzqk-5o0Jt%bV5k zhio+)AlVS;v<%a=I?^gN_mJMT((<i!WB<2h2AHEx1xOt)9@z+~ll0c8=fg+Fs4|CN z^vwRYL@2A5I8`peeX8SvfRCAam(I~U4C~&7fkOmCP8)pibxT`Md|AN~9CwyFT}+L1 zmnctK;yjz~|E72j@UC9&P?NtT&p#iq@2ctcOIYEx$Ut~H<@$-5&2!5&StCBVOu^mc zwegLP89!N8^^U}|UMZ&hA98OlRlyRofn?;(U$wYFtY3=AXqH}y%FJ6aQy#XOW(D_) zeKd>^3W~7XC{E|$9C_H{K6{AHD&NowR{5nF<(-Y>==b;4eaR$>Av&shn^m4qacp4L zqRe|SNqs7B#d816^X(L{_Er<@P~7HQA9+x8{ET`Dmlg@_(NmZWgkaI%TRjnx)*4nb zH_Z@inXLJ)6i`Rr9k%c2Gp@P$3X{sByCt;kgP{qfA*8fvzFn2&&Cp~MeMz0akg&$+ z8vfnk+J3klSOmr<lvcqZj=L;+F_h+aDzzLJm~!WW-JgvMv3ERdpvL}f2~ADpqn8jH zR(<)x*r1Gxi|^%-`NgSPTSn_d^}_#g^xj(?rn9`1wcFlfZDb%FHCL1S9Ro#GD(0J& z*Hzv_g`b>TrLXhO5S+`+6P&!NNFB-lCZB{W^@b8xS6Dk@uILv}&WCT!xz+?1prY|d zKW5tjJ1T@LcN8=z#yzj>_-;Rxx{n0KJyiKkM{n(70VHmoWt@ig4_~xTdCZ>G@Xq4p zZ%Tz}&zrajMOJUouI(}0N<)6sznqu=z1uZ2>s!~G@08!Zw`?Y=w=e1mfn?_{(@)Ee zwrPIl3*l>B&|40PrfE&ri6+dkB|&nRtUME6O*m0qJ(a(~>3#(PHTSK<mT^~0+p4bt z4)$@a>8(FA{N80Fog?c>|9JQ#<6pAVE7O!*Tk36057#Ow_a$h<t3(mv2KppHTQ6mt zS$EeGW1b4z|MHsN9m^;`nFm6o0WX-h^FOcxCay0AV=qUd#nrg5@u*1mJ&=G!ZGW2- z9+j0)QTyBWDwx#RTsmgj#^r7=+OHG{&vRmY(ZaR&R-~0xSZ2?_h|=gF7>?grqLj<j zf(RnAHR{mk&0ANTA5i|nFJg>Re;+P2XY`@{luY1u98TM};nRWOM-y8m!Fxy9l8`v7 zjpRG4@$yG2+>4iWYDD{L0W;CLiPN@k+aEyIGf2e)WiFq&L=DN#DjJna_bHF0`MYA1 z1Yqf9D$i?j<&{zhFXYBMwb&y_Woyd(vIus}VX4zm(>0wnqc!VcgRQ|i8(yTaSYP(? zFvpeEbr7S3-g#dvB#Z6a_5=h*->5SW(xh&F{+hty)ON46VjpU)ucx8(4_2PVJkbX- zqTiVVvZ!7U<&|iiTL}rF(loKH!WmKZr#!7eFmV+tH_8S~yi~gJe9qki<*GJ-LXH9r z_E}YHT$Ys{!Fkzt>(~i17NHVg5?I{YD6d;!+ItG|v2@zL85*)S$lSuk@Q7CGp4Q^8 z21Z<IFv?SUf!RUGwz>!=oHcEnz*g{jZ{Dnu15DBa%BK4`R+T;XlwT_an{enS{$jH; z`#r98(0f}g-zKuEGxd%U5taRj%NRrSkdrn=2hne^4YSrGRG^l)HFP@)PEMZZ@b#CU z5b>n72{+_TB#PmFa6Ta%73U^kL)(O$aJ5Tn>|w+-CuFGzEJg0X*32IBpbZyJ*+7Ea z*GK`j#E|Kit$?!zIWeuc+>dTNtJl4+(TDyMg<)34JeX^o23t~3vteZz>@$@aD+gLy zqZ{$sb*gJk>D5SaP#fgKN?P|`ejMV~QfgTwb|Mq>y7O;!dN#>b$^<=zLw&4U`wIH; z{Bg{Kd0G8&2Solrt-0RQa9C>4o}CZw346~?vpK_c+Ez{-Q3bMKV}v2lnNOIyC<)z7 z4m?JX!_&0qHIt|&@&vPp))btFy@n3E2pct|n;(uZ2h{Ma(+eCt$9pq5x}%A6EBxfb zO%BvyW<z|ya*0%qYB+c#fa39A2fQZHjbTvWLwfUMxkfiKW45Jot%{^f!U5UCQaYiI zleel|;y@ju-}GBxU`}U0UrzcA_9|KQ1FCB_(HVKnK_lnAJwxz1^dwPVao^qyhQ~cu z?i$FJT0QGnt2O%^=CvMM*EAQ|QNx1GBtE0<A{tOP>xqoh^v~g8*6~h3oh10JgyLe5 zZ(%;0!go~q2e~s9*jwNn8dt`oF@X9ClroW5bVWUMoS2W}kj_-N9q`lR{$%fs@p>+D z@)QJg@EWMJiMzya{MUTCx8n1}9i|Wj31ZotClw94#xgd?!c&{vT^kC{0vW*X6GPm* zb)pj^qsRCrElD9@g!v=WXgSls8txnMK!X27-m69n1`>CPfRyB!{izCr9Wxy`g&OiQ zn1HY~j4`yDh;y6nVJdi|{gAAI@5CH9RJurS)?Bv0Q^dY=!lK4F1xFiuWx}q~w5Vtq zX|f*^__+11!P*c;f=26`L0ntoO8sa~j37uA;<LQxEP|d;M6U8RU7Y$UJ)N#K@I=_I z2|n1%y<3-CtF&yWvWiUXy!ZA(1V{u(BelW6=N<-Z{o#M3E(=--47R2{Q~PgL4!(>2 z26ZGh#Mv^F72r5HXbxqtl3BzKUH0Cwk$;6+X($^tfwtP{)<%)PH|24F_Ga#3YdnY2 zaj_OgG~r#q+k*cx0p*;?_m>%n{h*ukkDAimYdN{^9wtp&HkTtVTD_QnKtQeu4txDg zl63ed@G~V2ZnlpOHj^bvZdfK#8@Ni&!#T9PvdIYeiX%!^-6VRhWBz2-hX*m7oO!7% zY1u4u=&dwzJ}SCR!xtUq$D4L)!GxlzYjHs43>Y+ou?n#8ewz`SuEAafhmvk4t;e5G ziQ`0aIj^qXtK)VVsNs8W3hq;IYmUio5z3G+@2g8)i+|-Qw|MNGBVHptklSQ0ZF~V8 zLS~$m=hXFAykVJ=?>Rxqn-dAFG&vU8Av-bNAN|&NT$#$w^3ejYQJUuh#==b$U@*!o z`Q1zL@!PB%=wHWaM)Te5!F_w%l`rAN)<Sk?26Iomw;X2S^<Vo-Z(t$obGJ@i(a9MU z3Gt=#1w#yL$d##`iGJ}yzRcHrk^J%#N;uLG`=T+uX$$z#AhVuE1XQnMZx$FOtQBuH z*JaiQ()cS_x+VQ$udjeKHD5lBvddWOJM6OLTTZ{M{=S0(923Sk?%{BKd|j{}21AeR ze5sT$X*1jm7}a$=!^^NOxIw=TuzgECRa^sM$GTP`E~n*<Fh<mX@z9p2p=5(ln8n>6 zr@?KN(y*gx+0&0c90n#O8e0tngeGqvlF-lyRedEJ?P-IcZN)>1PAmTE5rT>qf+wP{ zL|A4@z+1>6BNm&yv0kp?-b^57sNCKswPS{qYg%h*a6)p0iai7-q8wM|zh@Rx<aXpo z{K|;0fL%*d69EcJFk*b=Vw!XN;ud)R=trrXg*BU|2qbYsz^+L5V!NQpP0PS#i7-Db zFMtjXPRMQyAT30iii_t4U{A@6?KKNHw;#x{0$|{c=TMSY+Zb3Yb3etqzC8RSxdvNV znjdi`0LTr-uy^I0v}qjsD;Md~r02pu<MN{e!2^?&Lsnz1gr1i@bo?YcR_VC9B;txf zB>k48El)3(80F5h?@eb;E-(k}puT?i)C0z9#h<g*ftQYe*$IK0y^!udd}#&lP#K7f z5#$`eNpXH+d6j21O}UvFqYM0Cf15RwtXmn!=zbHUDZG5k&VH*QyZJ0!WK&bJdy`L# zGb1HIyJT+jfika)SJRI^eo%DWOSHW{y*@Xif(GCNPm|GO4#MiCqslaC(pj^nn<KqP zuiB)9+I5W6V%wTpai9u-mVk(ufBl_QjIW3VB6E#F+{qqA_a*mz<+@*PQpP5<LGtH7 zWZ7b@zDryH2onrbvx`oj`mZy2#CMwY0ITAX!9qS7jWr_ELB8Z%K-o+U?KL3JOmMnm z)<B}78ZZ8jU8#CO*~hBh@iFnXNey8&zt&mLo=9s2b~(XSnsIRUrjZn`ghV3`P0v%H z`ef>cai@DW6RQx-$OqU63w`r@QlICnM>ADKtg6r@;NwZrWz?}p003Q)TaP?pe{P~7 zLtKrhmp=3ySMjtK3O4l#(4kzJms7&^z1dOaB4;Up*o@7J8k1G3yI*_#U4R!@fzHb8 z5&J(LqIGX(_==`0CNq0gzIF-&1wldS1P{x&R}-CWBT#eND+<3rk7KXMBCd-BGkn~j z3Gky8sDYyIdl;pYq<>BkG>309TD8-X=jnZs#*I0_^L5X!XQ`;FK%$2|KIOGRG@}pX zJ4d~x%QrYtTCc7w-<P}XWGrvbdEw43KDY4mOHGT?U27<{Ld*M+FTm~<<P$3M=+!sK z?|lZ?ByV3d3!a2Ym?|^XAN|C<Ul)axuh>f$RlREnO(2mSfAsUC`S)(vyMeK-s6NGj zTK#jw3>^~(1oX9|88v0G^a5ZKVN%iDYn7Itf2_s%6J-*JaL)3w=WY1(M~&+ZBECZV zQ6VxDL`%*(U600|HEPH^(WL+cxRrH=t!p0ssrT-?00#7ZYbMT69=H^<vBIsC)`;$f z;|r9CoPqds@0`TiQURy36t`f?@Y*-NHA^99MczcwbwO%PC5|xp4c}~L**nKH4@zL} z&{M>E*@})!j?24<Ei|<*{NQ=_)|Awr%AfyD{~V`2h#D~BHJ_)Mf@VWSm`)!8m{x_L zCr7M&Yr_d|3W~89sfGoXlr0*Uxc=&&5{5^=@vT8qSE;F?<#??1jY}!^Nq4vSI%XVU zXEWw?Vv{U0IY0F~ZcvKB1aLlc<w}@)Y(8u}Bc4q#yh1l_xpd@W*R^hG*AgB!23@I# zBTn!A*{O3(6^2etl(OVt^i(F9DBGth$q4i{zNg4kZ{KQ(hK{WqvLNnS%3kYrD(UwJ zmyHU1H7`RJP3TQ~-kQy{l(Pb&It0M(Ua5Fb<m{+=fR~aH)?Yn1H+}Ti+rDEmnXW%) z9<VlfAv6a;X|GE=6muozn8&8^MoOLbR`xmQgtN7jEQXFm2-&Xq%bic2iz9P!(SRwK z-%B}om8NI>tIHkOeOH_^b4J}9r-L=Cx7NCvRVPfX7`I-(wsF=I#}cv}X?`2&8{-8T z_Mr*R@t&avzfuSd_=;6Wh>z#EA;W;O129tU$<nP#QfB;2xdX6E**VSt5W$oxxbag@ zLdMYx=T<5tjixFGDQHV`e3RO?;b$VOWd_XtiM0Qvt`61^8Hjcx!Z20qorBG%w|?J1 zzmoBGD2+^*>STQh(fJ?!;(>ASTxClqMu`FkIe~Bng*o?@M>=&FYRVn=H*5dlnz^Rh zfbGDss^LSKIz@3ur^Jw+t=ov_O<-C0w@7wl=UZh-2$g_=krf6bV5U5Y4`kAeAWtKl zX%G7-A*(1?Ps*8~_2n*hPv`C_`=}=2>cnj^A6g;QMrk1;E@eD3xxWU%ioQ67J1OOV z=ayTh-x3I|Aa8l20;P1dP|S;Z%bpaFQP!V>k8Sjl9@k~gGXR53;-iZN$_ZbV$Nstb zkrztO;!^+2Qkn;;L`LyVdMy;HiNLxr-WQ_pK`#QCwk**}QPA+vzjgc-xAZ>I6F<o% z=RQoAXJ_shy(jL`%O9AdU0DFwlSj&!FS}^R+M9k+DcJnT0*~ugX%@f|p$MyFS-lV~ zIpTdvgF+lLr+c4+wg9S}lX?>MNsVPT{)1rM@bXY^0gnM>!K-HW&#FX?*V+8Z<(id+ z^tc;SXyDWhm6t8>1zv`px?LZHl!Hu=$=Ujv80mYIvq>rk?0G2Wm}vEevhM>q&S7bU zV!=d?WaG~0e|+wYRD?J%J<uwBDQsA3%RF5WXm{5I5wN~`b$vM{dEQyqkix~xMkyTZ zQBV+VG~v&__GGRVvLA0#K;XJyNE9tn4e)W{J5#;(Hp-XxwJN7;B!Sq_(A^j7K36nH z<xaG|16!X;gfIEHDiLrt`u=DTIlDVC14Y`+nBG|V;I1!~Zc+lV5*A5XsSRkuA5vHS z^YnmZJc$0@K&SyYL<B^HH;$dRp+KMxxK_>8h5kpxlrBsn+bSKM<z6fr*zw7-^P_9u z4>$ww*4MdzU6u@U^hv^@ko*yqbj30W97lxQP+rz7w9Jx~km`ZhCiQF`coZvjsR#Hv zr_;fM;c29CY`=JX4CzvemykL5YB-fs{6zz!gSHG|e8!q}hv?tN5EYsWT*fFH&ms=# zG-&b%r^|v~ylYxIfcSkVg+^zXC6wAswGV5UJuVkLB?kDM#s82`XDcT`Avg{pzV*(C z&s=geJ}Fr~D7sf*W5M80P@-6E5rKRK7iiiR15YnH4jxo;7X%a^ik8I?JuNk70T3Vp zpK_O^J+iblmxNA_?r71b8r|=7a^eqp6?BYKe$bI`B<K|K7i8`9%-v7;7vVzanAAZ$ z644@Gd)Y{bE5C>XMtjY<59we-N$I92vbBv1Rho%7U9t1D0p<<x6eXGqMijS=6raKI zdRIpOqd$N*AvhWda7xWo2rf|)98tJMs*ptY)w6V|mCN(2^`&MG&yg_=<4&u4sd>_e zty8-oTMz^eQg$l!t_GTbYIB6{YW;4};y2)Z%iI6|oL2x->CMwCHLa_~c0q!hBu-4c zJ)q+<St@%vlQE0po!HvAUxy8B6zqEzm}C#GgV5%H+*_C-?nyR68Kh3!`>p6xU|*NW zF<`7=51z)~gLlLdJLV$rD-+7dvMI!OG&x|f?`ew$0~bYS)30;%YF=Hg4~)%LCg2Vd zwE;k}J47p)3fXiantgRn{|?S4Ivzrv0Q4klngZjtm$k$J%pFx2&#AKto3Yh?khA1n zUQQ}P0z{BV!PsRKg<m(3TiG~CBS00RQ}4~KXYa;v0)6z=v%JFH>vgH25q}1VwLnlx zk^SeK@5HUv!O}H7vp#x~V7jmvdk8)TyUbH5!*`UA>NjLMk*P9WWV7!}Yvk?PQA^T( z2EyR9JD?}d{iEMoX9=@~H0X@Q+*=>$TA!QFW!UGi3YsgYgv?@;&YKxtCBoifLO5P? zo_3EOLIePUr)&4E#i_c+^|pzV>&SWHRaSQyB$smsXz)^6?-Gur%!fSGCTzY9?B(6M z83!0`M<BxY@jsG1_<64{pwSkGm1~}dr-P+o5Ant%88wgALXGluPc6oUea|Zj^d_jC z6Ot|4V!f00yg#0tPlXnTz;a^2Gki{FDd*u<LFL-F*49b2)Md`zfdjRub+(l!*lT?C z$p=k00E>N|3x~yaRD=a#=fR~i*UN*S!WU0*k!f@8zJrW7o`QUvL$Jrw!nRC`DKXJU zou=a-i+n(>QSvp>f=(XEY5zjlO5Z(!!8cJq&^5$hWIMSw>lOmNkcNc&2$Gk`r)i^Y z6?U7PhF+}9Bdp7Lj+!0y5;Qp~!c6kurNqL~SjbND#(zAQLcS_!<uFZ6Nc4&N3Xu|B zhw)dp%1?A^E>BepORV<Tk?fuC_D5l~(R*eveo*i3dHHWK)*fsanP53C(3jpBn?1uv z<XxvmRI@}BjqoN%aYw|&Ir6zw|3jQ^q^4jTI*gHB54>U*h5l^`TJJeQ9*PtgeOopC z2~!-X(-<Q$>v*a2oS*tV5&nOzZZ;e1bS1)5tRHEfEsQ>x&Aej)T{NnZMPM*y)$Jan z<}%2wKuAl=RX2<B<R@y5jH=>026pcO`E$}whxosy`chDD^zGM*d%J!;62g+TJ*zZH z0)k~QXV>mKkG)2e1jfZ{AuTwRk**@ojchrbajW)o2|w_+li&EDle$WYNB{ffH6BIB ze+s42_L@Bqw-O;ppS`WL#z5WY$TFfM+Q2pI^j)gtbkE?9kNMB}Rh5_)dr$mbv0WO^ zq_QtqNcl&mFpDUI5jaCWY|w7^VlZn^Tj@kW$ftooJW)}+KuG1&SmExU>d*E@u}@{= zrbK@<{77|ic0k{Pcn)wEh=+}OO|5s*uAK9wy$-7|Gc7x(Ho|LMhS=YQ??>x5PJ)zw zzt&$gJ!zzT?Yyb&Zw<P)!mJtgHv0N)L)Hd+&fa<G{K;wv+dgEbyV!T-E5hzCkq2M9 zQLbFmo1@)`m$R%X71qg?)ZhBo!;^2BrQVqnQegY{H^004j{i#t#&JYZAMnYRk60IJ z>DPW4UcG13bLA94>|IYmUP+3UAGbYnihFsco5%`tcfh5FRlNAT-}bXzx(2NX_v&}9 zV+?Qm$3x5ferqeGh6AaUgG6kYxUaF@{>i<VPNk)p{87=$O4e;%^FV_w99!sMQ7UNQ zY8hV{)BZ=l&qSR%ISFzML}j`qc0V%W;j4qxCuTN*aQQkps=`7)Sz(Vb&^U>>HkqdI zQR<e9%I|*7G0Ey!%#IuN4A*0uo_y8mNZl~Xkv0v*CvKrDZsu3UyzOOAy9BYIzPxGF zy2aVKxt8eeS@CTI%~Uw_o$|pv_o5x5mN;a*0*iA=H@5TPvMj?;mnBNEQo7}>U$^?V zT_*3pKF>LY$P>sGU8vsUeu!1?ZaRn|NO!dxc8qCwByi>E9qJBoyLdtx$K_wF?8jVU zwBp&;Gsegv+Q5t)kUN)DdTB*Qij{jMOai0WH39Ejom8$=tV{(I9FQxGdf7gH;|vR0 zUA4fUsDtSPvxMf+39>EGn%Ai=>AL2L-)}HR|3;)un6Ymow4Uw8);w#O{CDa;_s5PD z=%FCGfczM$Z6CMcT`v+O0524D^iEoYAZP#Pd7u@R$YEwZNLXD_jsB^%pT4beypUqn zdE#xXi26=O+48>=nBS|O>4iRfq<qAble-dLwD~8k4w7HJw*s8~kA7>nO`-sY-+ygR zimGD*am?vuTRHW|1GyB}%NiDaAqQ8*Ivw(j%Q=kU%=;}@P*^K-GJYDq|FX68a%(RA zhkI_C7cNbH;G$<(hqlk&`>&#$&On|X=n(S7jPLz^Fb#{;1!UZbhC1YGOBMpSMn~bM z`>#=w2r^4p4>pAP6EsMMU(SktJDpYx1axr3rG>4F$KvE3)<+$6LyB7A=S@7hQ9ceC za-2uepV26rXkhkeXl?4VA2noFOa(pThzp^N>dWsN)=)SCm8qamcWd|W=MtHRP|*7P zwYrRX9U&jx)zns{Ad&vq;a%+mhz&@90-s8)#9|U6SwJ!)qphT~mw-td_vo1dA;L)| zc3P3GU+&oXwb8HrvSr$uUiS<i58^M7yGx~>&K@YokF{H~m5TOnZIw8NjEZ)T9PPz; zYf6izoHr|Kq<b?mXv#F<7DVze39Ph2---EcnUZ<#gO`>+)o$GGG{|9>i%7b5)x^5^ z(XI=J)KgddZ;4&eJ#0_7N8zm0-AW5LFAfi|9)oW!g0FjfmeBZ&Ca{=Ez#TfiIAP{R zEPDW)j&hB+dJZQ%+nec^1>8r!cFFgve6Cy&(+dCS_vSv&KR3$CZgIFt=HB%qm|<_C zKKP@b|BB9FcHt(vJ@JFV;l;)l7M=e6uEIt!G((mbbUwbmvAaxEaL#;(V;0&(d$mPc z@|taY4V{TC%{!v6zxKn$-(0IZG&7D}S7g~@6dvQ==<Dl$*kP15-58tYcF&jO%=ueK z1%Iaa?lbAU>!0CoVuPqhLf$}lY1(!Sv-J)EAi0pk+E#UC7~`Q<f7q>isyB1R<Yaf+ z3YW$iKFfBn_Cv{FQoNln-<ry*kIqlfACQ*hc}J)0@a97})4idDj}c>x$yBd9Lr{sz zme2dX+tU28cUy}8@J4yqds$=Ub}mS_uBom&x;@04ZrvO<W-zY%ADd}uTHyWKJ@o$e z*z!Xy)>5;mnlFYnr>VFOJPdR(PkS3xJ#(c_ZO6xNIM-JsU0?h|PvCNR4a*kc2Clw4 zJwoDuOZsE{M!$)ZrOjb<G+)&a5J`8s6YgsE&ui<Q<oN2o=^6bbet@clw|<Ff38&`# zw=lTu_tWjs3-j*g+>$h=&0*0!p2IwCuXnojVBYDj2NY#}8t?Ph(y45?0!^_Ir|y3f z^+&(Iq@)KPXwV15-w>?SDt*XG-RR>gYrU5_z$c5P>&ZXZrj&P#fAzY2Badm*^E0}a zwg;^Fxx=Ha6ic*Z2UR*Z4l3um{ag9aOxrDcM$VNLxWu~Ch^}nt3#tl)_5H01ptY=l zxBjNKdtSRTC`KBRXeB&eGFONjocspcurm5Vtunhedrutz%XhUgQmgTget-0P<(I$< zQJeeD`){><7etrs6#rnINJ?xJN*o>iS?Zbop3SUVi`DBXE_j`hpMC+U(`8j$O>9=Z z=Ti-)Ea>uncSx__L$PQ6GdlD|)pmErdLCKM)E=_FdGdh1Z<cG^hJ@+LPC|Gzl8}>; z&=cAnzCuJ`aj^A7jU6w%7<WFtWvphU?ZJ0Va`1Z@iY-=Z(KEhrGRwT*;Jc>V#;jHF z?v`|OLG}{&YzWqM`xnlai&ApD1u$^$Vp(fl0E^H=8>_GzRzyL`0LvQ|Us>&b))V3U z*{Hl@yQ}+{@c)~U-mH|z(%;hmceuLosaoZ8^iSBl8v-)!Dmb{2t{1}>X&^uTteGU{ zOnYx@xdP3)7wjlu#n2|-sA?PE?C^eN41Dhk>Bq8*@lU&Uq@@4Rul#S<HE(G?%UGQu z5BoRuJv&AFjy~gs4I5kj_D8>5F~8_YE((g@!aI%bJEu7+o{s_rQZ63s(QlJmntQz2 zCj)N&YlUV=VihK`^`zugOp^|Mc6t-*^wTeuqB}E}FAe{?Z)D$3nx;vP@)tfcH|v9i zA@w>oD~ZXMEg0M^-0il&$aG9$wn}(_79mXamhIDDX+;`!Eyq^g5YA=o=reeC8lP@; z`kndZxra5=4tX_I7w<M+i#Wi(g}<qL_Ld+gEtU@=TG;6FBBGY#UWDL4N{~rNY_>Ev zdaV&py+S#yBjMRs&c3MJyfUIgZftAT_s*^TYs|ZOXQr&4s5$vZzw2vg>M&k-rSBI_ zb7Q&fHzEHwDp%BdXRCxbWyK7p0+D`Bz6+>@G>+1&XB2p!MgLLl!#0D)Ght>-=g^8; zZx){o*yVY&SKpo5*7292-*>;eAy}$lPJ*~~Ur9Ram{a?g&#t!z46`vzT{lXx`WOjI zC0t}qwupvW#zgpelnFJ_rq^qBO1Bql6dJdD<lj=Nbs&i>V&<lRIM2ZCg!7)LfFpkQ zcBkZf3zDatQl(?b$rW?mNk0|B3JMi;^7=g+7FY+Ke6%$^sQ1H3Jv`h>c%gRLI{`%B z_$UZi?~*AsF9Fx&=w>o2Fm9;h`U~T!!*@@w6UcsgdFRFM0+OJA`armf8GXBJe_wqn z|5?wmh>;f_Hg-zg&+n+E$hum7qU_Z1tD!+1nU^2`nVQ@4p+U7;<>%e$5!21hZT5_c z!&nt?gaCwMVBw%}A$t32%Y4X`w|>JLiqldmaG2)H`%8z4LV$aeEcFq675viPcI)FO zi~ruiRABwx)fiV>(((%%Y|n(}>N8d5)|s0KJD(=p!{VjokogJ4VNpjSgXaVcXjlAD z9ysv#4*yL#7|yTXzL-Z>;C(@`yt;6+`swx==<XM<HC0G8hWMt4Wm2s@IO|Z>>a!^= z2b?!EYD<N<C<}Y3#~8Jk;ai~Hl+@|d_d#%NwT!6DD@+;MK7?5Jd;OVsR^3_o=;+DZ z2Z!c9Fm*1;ZSt*@_si>Rdw<qia00zs%eYRYz1?f>xt_T9<cfNSMQ$#WmuMSNopo{& z+N!n6ENW8Ru$q%QkNqn9X;--`?8A|J1~Fc;OrSm%skwRb1fw77v2k@zDO0JPMwG|> zNv4a$Y20%Sy>LP?X{xf_0LFBJstq0JQX%XegNoD#{J+U+kDgU6{b)AXJMX2$sf3c< zGXk5jAT_<K<Y@1x5rygA&wieq(MDLg1WocFH~04e{q>5Yj)0Z}ozHJOD&)CD648{` zam5gHqLZ?>bfS2V<GbEh22^?0_I@*6Z3~ej#~LrTf5`BH&*~Htp9i>37CmN-GoG&x zX?i00n#;=Q4LlDO_(b(kmp@(WQ5(j3^V_$Tk#76<mOxDn9!TDgI}}I+7eyK)U+bOO zctaQWyKQiJe@Zgu_0qG#I~-y}k9d23>seQk{s_c>iiW@k0TMcF<|#H`!|(N~%J#K6 zzsH!>*7i@<0?flO`DeuPzF$l~Ss!cNm8OeOG`~1xs^X@6Me^p!2S1NEC8@kA_6MA; zb)bx$>N3oWW1ohIu7Xxuk+5$AS14ta;S$fnTOkxOe+Vl?btg-e{SA4I7Z1vvbB-F? z+jeR>T%`635{N=U+H|!}&1+TZJ4fh4zKZIWs?NKbr_+rO50l6yyjk-t!~}rvq^=3Z zm)iAxw%$c2K@|mk;)%aHeR`6Ed)*98%_(p1UQ1C@I(zB^r(~^J@JM!d#5(g;d9ntv zz&3WAM9C&(p326!pRI*RNJu|o{Snid)q`Bm*%hb9E1vPOUx#L6W|l%W^42S*A%~ZE z?7c_B-i4)%rtRaz4IL##b57h{yP*3Ja|mw<z7b4Ktnets^~KNw&RS;ljFrc|T@!ml z*}Hyk8?6<M-I+D4!IQqahhcts$4jrKvYod#Rpy#CwWPdft=*S|X8FpS!R|mmZ)UQH zuL&HIM=7rLfXKMk_&Vkp?(lALlIiwa8^Pat<A2XqlNoj^TyadtdrfbCS~s#?^O@(^ zEs`T8{_Zz?j_?je)}U6K!uiO_vQ4M{2kD`_-mdXZ`Z8kO&{u2(_fAT4d^1Z~Tl`+e z?LAhyZAqrTuxR@>HPVW^udesV-xBoQ`T@Of39jSP`lgf1aWbLvS9&TsfGeW9)o-ZB zOE}Xe!7N5KTJ>350}?uEP{bgqW!_ClnSYeztM`@C@%@1Swf%=bZ;bY?0nF)(d$sDP zmf!Ya6<#eJuiRqnP<vnMSq(#r*w3)=oGsg^aXh)f^f&qR2@A0wYGqA|tdn6!lYW2t zm?|xFDEY{}y?xz@z2${3o3*1%pNVX_{u<>d(Zd<8F3H#YWFLZ%PQdU5L!jCy(|!z# zJo!fQwGMl)R%H$)r&x;d)K8Lc2<GWDi^5WSwzgiT2O*uXt*?8!JZWv(l;~$3aWA1k zt}W<5S~!RqV|gQ&kGE8vO_d*^8a>ILTIoNDu#Yn4I<~Q3x^s2!E5(f<v9Qu6RnYA@ zNxn`Qr$qC+pCB8?$DP#BBK-Y}Ep@6dil{SHm9iENmKReV5vA4qWPM7zO1Y-x67W8= zos@xZB1v1#mDyc!JfdgC`MmZ(C{ZaN40S!e!G)*W4$J7M>U7j9yHh>|=xCQ6Nj18T z6+h1{b4WkF0xr>IJ-d<ffaD8`J##f@ik}o+Rv&*#)2$6$*~bo8%oNz_VNvG}rv=GR z*f!-JF|WPLGNO6r$dGXD46>YA46eWO3wpP^ew=Yv)w}t2w)(i{yP{nJWh(D!nb`7k z%_vK=X409kLLk^fsCws@PWhza4SjpwndLE-<vS=ou>$)tU|#$EXdO&{UeinSMEBk) z)mQf~>gzOri_!)t+P5^%C9_qzBk4KY$NY_C>f!fx&h*WgvI%7e8zO0)<BqSmxvppY zsrL0}=0fh;TTL}9gq$^k{+!G2r~JKRf+aR<Z?#l0jp8G)<q6fM7YwR2!~Lik)Hy~_ zD%U0z*50IrASnqcHT!)*a@ca`@Ot^7DokzfJR=2h_4mUh6au6lKkuOVGwTi7fOuQU zldw<!><`|?-|{ej7(X&~cN+{KPrh=g(xS1<h7x8F*H|vf%&DDondIL(#A`Na4#oK7 z@K0*w&}r5OllFPaRnA+YA_Bhc;dI%7Q|vR&96gXqu`eF>Su832_uyq%iC0Op2iwtA z*i6Ym5Q?^}x>=+DsH7`vuxqm)E;Ag8FJJ*(Si0s8itC#o7D~k%8_A1BqWad9=-RSp zjICO3vZ{wted?5aN@3_#_(aE4@+<6j;$ObMaL_-s>V18{;O1qE5#Vsi)rxJXn)J{; zb*uN42E&dQ_CH1}5IkLVIme}GtLdZo{~YAc5RpDA1ZccX6gCb71X3Ulz#RG1+&zC= z`oW{?cgBFAepx6-$`jh_OOaWokmw~R5~SGo^dG<Y4}&H43-x$Wq$5Yny6K~GzrXFE zR=q`!pbF)2AxXgRAwXzed&_)<qVW=-f8h9Y6E-ey{9jpn-annnRL$_WanR(rjRL9@ z9l(OvvvlFe-qpXmNZ-yp8%QPhy!SU32AG8}EDDCr2a)cIEAg!Q_(-fLnyBG^#cPgo zQ-V%WiJW3nh<Vgsb-0FQl)G&`gwoSIPmQp7wyq*VXv}rS9Ynd;?p^sl1r!xs!RU_* zjejbhVv=j__=rY><`d6DtJG3Qlxqu5mtLNuhoQ%n`1wx8bmk@RaCE#?Ae0V+!-o^p zwGqgFXqkR5#eUcT-HmY;P!9y<U8i!htQ9l19BN&+aKGuaf5b)2@1r{W(lyM<>bi!t z;xtSUICyXUumc`ts{avG7FBFa{HcIpB7%z&kXuDq=Mp^Lj5JMz9s^VOC2L-keo@Hm z+o?G~W>p^_bLrdrt?O3rY~MCWeb(R9>M>Q91*Bg~;hb?=5*8#cu6=mLk<N&UI=<CF zHGAl_6gkRJl}%7(t4Ku$Fa$?YshuJwBSSN+wCuDE8{QKhC=E^dhk12%?<+sqMI(?m zY#_(rY|=b;bnokOv}bOZgP2|y)bY@%AaOjZtNh?E=1PAyq1D2jgnLOHyYXND@B8#m zrc6ome@6e=OY>>#E6g~PQHCS=`xSk!?&OFvr7`++9O*dKt&o!(gh;4I0de$O9Nbh# zWNPcIue|i_s+;$2byRH}nf4Od292PAli5kPXC7yb&Zb{+7jHWGx3od3jlXX*^%qgJ zK~kGFg7gOu44*r`A}7O+Jee4EhTYiOTZeRYf)D%OwzcrnbsEpJ{*MtjL_D>2F<_Xp zW~P4PG!~p%zPX^h<G-4ksfyFJ53#x!{<|S;$enYY*+S<z1aK_GTY|CWKfvJ|-S?$u zLg(I@?^$sy!=9!Yv^Lm(A`sF45O%lI+@xRCacRM)lN&d_+U^<5wmduX;&-bBEzbv9 zmi{L058$8;aqU4u><7-WNPDA4_59sgcHqvulnosk#@gQfhc3XZ@vOzhJ^jrj`B%#e zPKSH+{%%2Y?~FJd*PxPLE>@d*wlHr;Bo!1PF60uwH7=G$)|*xwGu0KFc5RHYjJ3e9 zaoZ0r<IuPs`z9*o^^V*Qdw<K{Pdd4smeuul#j_EnOWhZaHQmbK*cN4S{wf(-!OIJ! z{{d4MMWvbKVMjmr2z}9yv*uwk8^6wi%7M|bz@Ql9S$})xz95}v<~O2hb3UyP?F4}Q z!h!cZ<+6d3y^TR4#p2Tf^;>-Yhs%7=p)*6EBJ6+XASR^VC0g1<pnWc1vFU}cn3}pj znn@HMFk=9{JLmR41K&f~vntJ`-a8rR(+n^qKxn~ed&hSE<B@`b?`P;Ds?<EyB`DE0 zd4=eSn%B&CHkM*QkC{VN7@VzOGa%U;Ih+^Ofzfy#6ondFoBJW+j+_mqj2%Pc#+&~N zdpAM!4$b$G%;2J?4RlyUZe?c+_gbRHXP#R~GARtNEzw|(qQ4g?HN^;UfdlT$A#S~I zPU&La%yc1Zh3m2;Y9nY#PCz3<0>#bwbG#FZ8fYQ9kJFWd6u<Kh=R>quK@V7FNK&=l z5_;n;Unja=q)S!UQA>O|Wjhg5EDbP;x)iAfSu-YtWlq10;UMdHU&zS0k0J8WZwN~; zLDs!Ul@Br{De5}@BAkhTBzG|94r+ow<5wV|8_VbJJUCFOk0evw?6aG#%7p2nh953! zC-8BFv`!!HxqjymE!Jl10|N@p(OPx9t6gY&SWjelM5N>|GH#@^J1<xpU5ZlfB&4Ds zX1WlV@-K7C-Q|M3-YCqZBcCQaP6l4Gd=WeZVnG2X%;;C#uzDkyJdV~BQjs>>Dr(sV zZCg;zc_9cG0zV_MpRw(p0tGG&J0SJI*aWeMXfhcpafs~RO=FHw;z2t&47#(APDEBl zIYZ~yD(Ey_{`V7kJGb5I?~Qt#`gj2LLdd%O?-E}Ky7Qqw^cO>>%GEh`BqbSc1H;3e zR$;#l^_9mXb1iH&*T&@IMKQC-H0gYX5V#3gUnhoCEoR}y%^b#v1UhiQ;97k%GQ9PW zrI^s@o0BzTeOV(tNDL-znublJ$h`?#dz_$88x|&nz5*qQbqb*EJyd-TfkC*>NbJ4^ zhoK@5%7G{hav-+aAVp&XL=`i69{z9=O{ezYP2`_U$~g`#)@sb6?hAZ0iAKvs&^U2A z!lCJF=4hW=&ZfY9b~PaqL~}JwVH)qWc%hPGYP$$H)XM!`3R#A!7OT+Mp@odyl3NSS zH|fk!(1QWXy3npDmp8`Yz0zGt`Tr4<7Yi8EEo>c|bzR)xUwYHs$3|w@|Fnf~9&tzR zK2UE%#!oOb&|a?cgwu|OV}$w0Wm(LPbBIhU%6d9FSO=Y2=xljc>Yr0po1=}Ly!Z<5 z%0Ma0?c(_s3y(An8<_Ly<T{i$M2x*u`&@&cr2~glr8(|lh>?TQR)V8la)7P|I5;B| zSkB}_d{a?UKTrx0DkUp3{j5lj5(@cBz4vw!i&0jcKxt!V;54Zez0Xioao8X+z^iFb zphTo8>ehVX%4G|GII$1b9g|c+9{Dx$!L&Djlu+A*L9c3ii5VLvpQ0SMy8dg)nB_%D z1u7C`FkMj2SBn&l-)kG;b5SjW544_F`wo<0ueP3>4_h9V=#}zC&&j+t*+XC497YMS zMVHR!BOJtsi_CPg-|=<Bb4~L+hYDX#(+Rn}c6{M(of-*0L{9Ge3fj&3`<6&z<(55x z(W03j6N0V+^q!2efFYvC)pvv^R2D!do8;!gT%f8_$Os)#WOj}aWT`40rYZi)N7zmx zmTV>cc*P6{_YtJUI67e{={gna!NIf&fU|?V-3i(HQ6tcY5Gd|~uEwR*K(lCAK*vw) zHaXVw*e3q!Ys<<9&P{DBb0A>YDj;VUOM&^0Fwm9;rM{KzgFKe(E{VNf8A_P4SE45P z)h@HZV`xfa_ye>)-&@VP!<iK-D_*ndnNSr!Bv^RBX_+t6y48I_H-=@!NzxeCI1ioo zV6Ms1yWjN8<uHmxU5bRcTtcR&c8RdHu`NQHXjRp+JXD2*&8wK9G>2K<JZHvL1c<}? zT_V!wY(6|VxiiMNyw5D%#OkWM$uEY8vm*}7vjU^qKKESzp?2jKCaefj?9u?q^Ii`1 zNPsef5L?7|(2YkO7$Ygy4}tvP;Kp+#sCX@WV7U&LRBcyf&(UkLG|*{7m9>g&Rc!%l z!B3*%kE$WMf6#6i<MtJ8mN0rmmx7O{H7<83i;BvNpc-D)DqQCM?0^+z7c^thJr|XD z(F(<{zn7ShhLD_NDjCpm4H7WB;Db5Xbsm}QUbN~q%7!b)8`B1M8`jhEa5ycj7#^_` z`$~U&o5s%I;xVbWh3u@41cs?vB?xN#DE$ZYDl;su!N^i#qul9UUtoS@oIV7WDd8ix z2$#UXC<Zt*xz9Ea8cCZ7c|W2v#ylq{4jTg7G{&;x@(`WqH;lwwBTVuH2p&BXG{$(! zUz92cEh9woikgFim;ho$2wYirNu}wmlRuv)9P2xmD&6no{qcfVrS6hPXINr!s0zDa ziso9PinIE&L<n5BL=fTB67r)l2wecnA<R9sB2ffDju{8ePVKd}jG@2LeUydg;0OkJ z@~DZBS37uB!D1L^7y{)N=VJ!LScde>A;y=ciu5Q0yHs}PL4OT=S&S71rrF;WtEm<K z)F^8Am;jvH3^7C@UP*_M_{Q2YaVr^jlKtxdrUzD7>6gZ>exH7cCdyXdCAgoYrpX5Z zSgTu46`N@_hXKYlG?A4$?~FS`)+T1#h{dVV&B6xMe?1su&Y^=JSWN>lc`btJ{F*{% z^B~TRu{GR@z6Rt#;fjV#RSu!V1H=7<d3tjwO|z_zMdv`I=V{RAb4Srf75v181%WZ? z&`5-|6o=$ozvBLb+c;_>7`ET1;ti~>n{~{4#z+tVZT}dD5YHy&O?f&CDk&}#IG^7q zHhv9Fuso)<@64{`krrCfF~q_&jSF=!BykYCgIJw0O0UUA-+$zv!>eSk4lqwVGM7Bk zQ}W<X(<t=;`G|p%otm|ov~to%s}(cBIjT3B={sGm7SuUw0-O(t<~ibXoJ5wQO>@f_ zDS3-B|2vNB&o&8eRJB$e7}N15eCQBS+qTU2d^$%>RzC8ql1Y_dbo7X@X&mWSKg{nh z*xdnZ$TUN|=$7uCibPKj90E}^Xs%7~&PP~*=nJ^Y*CClcu5>V+sqo^@f=4K=5}f6& zKZqXAa6uxyRFRf5T~LaN9E7~mZ{BLOjR7^dLwvseGW#nUokTkNr<{8s5Mer_?;JDu zMH}tH0Yl=&;2vRwg^xCb!>bc;!Ea$f8H`jEL`Lj)*y{_@uEG=nOu3G03D$RxTEa*H zz83n!r8>I$SaEpPrOe%eJ9x%2Z8MQY+Khhc&7xKWv3Pp(<Xhrifc=6BUiK~ce|*X| zmPFAWg*mm3>bDqGb50&m5ymf{)=m_WGnL89aW1SbC;Hkx&*qV-{+M+F$gsuzoEk}l zYK^(p9%rt5!e)$+Q_*n|I*|yAxMw<z<ixqOLFi8S98GRn{?ibme2OeaH2s<<3gFDp zk}3KfpeB+Y2%&Ie)UXF9-?I1%Z>+>^1E)61hlCplOPdl+W1=mXqEq$dZE|!5Jo_TF z2_=b;grS0KX*`u9d7!WQZ##gk^(HbL@*wa|+j&8VXCA8`ttG;4SXL5|;`wNTK!C5G zu3LdA6go8;PuKr~$ct)4<KPJ=h^foP<j_vqS6M^@dZzaKnIe(FVTkj+l#wpv6HXsM zC(s)U-4T$Pu#!07B;^)EPqc5|5<?K0_gwiRdC^Pni*92P;vjZS38rbuAhqcTtKsZ{ z?Mb>MP$rAi{xH<8Kl%yLjN?6Hod)x41=DCTRXPQKeRV!tg!7mjl*U<DS}!cRyJX9t zAg6>72v6F$Q>)y9t-g(>$vUa_9Mgs>7z*plWD08aV!kW_`}nk7e=!Vpp$P6POehHX zNN|!B+4Iy`K($pU@b)ac)hYP!s33^!1clDSy9SB0T3j_irL9^lC6JGA91(=~FTUxV zN(-z|!=Xvx7fo;V5{kt^ycrrp#>mV?{otVkP5J~1pr`JuE9txi$=b(O641>wZ#APx zw+K=Rsuw3RDxf&fC6TYBT~T=V`it+Q%>)6<$$ksY=xz+Ulr5js-#4M^m~%EQl*Rp; z%+G<P<GO#5uRi8`VR1q6Yja;098Z>0&}dTHh4JS%K<N(hdSL4uYre^q;<mD>$QpZ0 zH1uZy-k*DYk~kzH`2BU<lzns&upG&}LG#;Wb)MrxbmEM#{@1zI>T}TLd4vX-i3`>| zac<(w;`^|oMWW>#HB}=Beime)-obwgE8j_ju-2-i%|+2dxy`t8{IGebClgkBZxVNF z_)yunmom;<@g-1qgpT)Dj@@-arj?+3|6l)0q>-9y!bkh4LE;P*ZI$-1?aarh1PliX z=hbf{GW$iCd^&AChvkPCJvfk8K!~eI-(8nOSMyb!;77Q-cxtA)W(ANtRP5FW`rw~$ z3xZcZ_M?Cf`eox?Ah?}OQ3Il8XAwD%$7`AOb@{PrIUGuOS%e<8`&$baKR28<#R6(F ze@4xF(F$&$NfTmtgjcVYnE4~>8~k*Ri0UH+0tFmYw^uh`&MqG{WGddY)Y(kw7^YVt zodomII=Sv^7PW`<!>!R-eh6dhE+NC`fQZgfy2e-yLPp;(m{={YMfeFGu|nTE?|9@M zMX;#6FBSOKECOP>^f6U*9CUK9=NTj$#7f_Y9`Zg{qZZtdH&-I&%?T9hRJ3?AkFj2^ z!!t-HT-4|mekntbh91mCD1ji%5=reW?^TV<Nuc5TLEKrBm09p>J&-;jnK6i0Dm95V zid;extQbAa{NhqK5l*Mz)u*#4L<ucBH5@$w;XJD@Zvs~H8QCtT7Ib#&;d-&2gz<f` zb7_(0<J$;O^V0l<jb%OPR2M1$yt>_Iy+0fj;UMTykp?F#6AcR1#Uh9!AqcpmKNF2r znyoIuUJ#`^NA&xD7J<JUhcBg$&^?!IgsAN#84^oPt0xh~g%2Mwp_Yzy4A|m(6ykA5 zfe)f%b7SZ79zMi@-*Z2)-&DN2=p~^i<uiO?fVI&hw|*?_=QdKN`aOY>YfyLmQ~HUe z3uSp%=L>CuGERU4HAk{NM9~=m!+z2gMxC#FXTQLh_+0!Z{29@#6r~Z#grIhGb&eI5 zj18wgzB4fLeQtczm<OmMSn=9aNa$}Ai|2Zu27FE;_%^d>xGub&BkTZ%mm^B6DPQ*T zAW#qfmGpU}la`O#&ao?qQ`K}G>G=&f=!yE^utnp)A`%kyc`iWr9gZihYb|@QDG4fC z^|69dV@1KxatAR6<htvZJN?G!6n3Hq?%9})^h=UxIxlSdKXs{K87N|Rawcls)Pe7X zrEKBp!_}s~*oCh*C>jhr3gDI)FnEZIDiRy8r5YWqevo1g4KW7RRs^Ra3x#C3yZ#H# zy&vTd+eB?zn1xBEF0R#H01V(-a)PCoyCY&ODQjRzlyZEoZs<$NT{A3bBgTdcUGh`! z4pr9P8$3nM_;pjLBopV@vLbuV6xWvREwA_Xs*k~4+sw=CKmLX3`7{wO19R)fAL(6# niY0_Q;D|FiRcj4bsc~m=?V~AY<tidV@}{P_A#0O0e_a2+@cyt` literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesExperiment/90kPa.jpg b/examples/python3/tutorial/formation/chiba/PicturesExperiment/90kPa.jpg new file mode 100644 index 0000000000000000000000000000000000000000..d46391f26c941b004021bdfc1751c1bcad1a7ce3 GIT binary patch literal 161698 zcmeFZdsvfa);{`zSVUVX*w(KdAWjJlVudNT6=?L8sci`A7r_H+LE4I?^khLO#$sLv zJ5^_DQWB7+tqBzrISAva%Auytv<(4jlw-95Dhc7BAPE?9dfE4r{tnl*|Jr;1wXf@k zt*t^xo@YJlS?gZ+y4O4X+w^Vf@%Yz;uTvf#9@Lxohnl|gm*&^@WV}OB>()_W6h+OU zygXi@Jn^S_6kdEVgYv?kJ@DtvheH16pBEh;4xqg8wMX&2mH15s4C6nKlRwS;nz6u) z1!gQTV}Th9%vfN?0y7qvvA~Q4W-Kscff)<TSm6Hz3nXQHl(s8(_o5g6g5A#ga+aG- zc!Hu9eIYM!|JiHV@)xN8%^*C!pIBvvK_FI``88vK84Ju<V8#M77MQWXj0I*aFk^uk z3(Qzx#sV`I_&>)2k$;JdjQLA+%wJwu^uqEO@^2*B{A}nDh%&+RzscV`@pteG6!n)= z_^<oxuaU2N{jaZo`3J|~TMh2PK)yA@F%T=v{F<@Aj0I*aFk^uk3(Qzx#sV`In6bc& z1!gQTV}Th9{Qt@VUtl$uJfI#S|KHqadu;aP9kRe+@^}0WA^*2jy*u&8*QbA{UZrMv zdXj(f%M1U`o-=#4m)GpM-rkSQd35fhkItJrZ{B0`{U3j9zTf<L^B#ZdalZvmJo)64 zkNPhBucw~)FaIZ=e1g1*$1MDe*KD8Jvwfa;Y~Eu}{J;J+{UhZ!XV#CisaYP+Ql5Su zv-~`!f1)^8?QBe5kl~B}@yo*#Ykb6ej?dhAc)^9oDNm1Cvpl_KkyYc>`|y3r%Wt;- zpI?Z5WI@7P-p^(}5&5@*@8$&m^~{wg6R$tuE_*vG-)HVq3;*lsXF{Iig)R<z@uioS zM@7fHy85-(1#!ao4I4LYPTI0{+m5uI@1(z*@!sz2oKJH1i1!}&?C+l+JaqUUaz$a$ z(c-U^Umq_mJ8`o7R7K_4bLTI7fALaX{lEY7)6c(Xn{>@>?H!$6-M`(qdFO7w!8l+V z92y=sTP7wSTBmGwvM&$p^MC&OV`KlfefeQuo?c$Fyu8W2JUnypdzPQq>_5Noh<|K? z_gk3@o{jw5oG1QT@ZFg!KEcZpA3XVX*7dnhabLU>GETPU-r4`NjphG;+S&iw*#F+w zP3qBEpqu<=`B60Gblfnynro-2rS$!BWuo}HmdAD+XCl~bOtt*%!1Dzf<B23Wb8ecd znx>8x@stBhOI*LS)Ya$8w$S2@9wy;xxy0g15$T<l6Xt$}Rc#M1|7z|7VZZ~yG_`iv zab+NOntI-VpJs;pD+}~oIinZZGeSgMRa&N&J=ap{Ar}XwW$M^-?AHkcf`BY>rcILW zw3PP<IkzlfbNXGTF}jPXDw$(AV3i9764<jMTZZxafS55~Jv2>q39<T6&!2YRo2I@m zXzwSVG^yVg8z4z8;xi43X-c|&7T0x4E)2nn_|ufwI8C+395cA4sZp$}CcDY0S>{T2 zohzAZj&*1vl>r4;IId--t#a`+HF9j_o@uHRKY<Tj^{7<Hou)Rc(h68}+%z?GjBYXG zySjl*!hWf!S1d^%3v*`b0#s>O+y3Cs>4+9NZA*s%hD8xpRl0NHRIseY!q?a`1a_?5 zc!CnJHKHD^pm;!F)NNqRQ7<#qEEYCY&{V*VxstP~DeP$LK!Qm-z*I?<Ty=;bK$1E- z=qZ}S>iBhGOz%cNZ9oBRHWqro%2?W4OXgim6>^lE;sAAnobKK9v{P>%+F(<qy0R-( zY3dOgAIllW*1s<lIxf*eCj>m@G&QS&D{F;0)Du_t`}Q)w$H?dOOJk&TkB)f9$O%zE z<}}q;Po=4nKNe?djoO4pIa57NHNh)P(^Pe(g=vqW&KPz4LVWwIXtFStTW|%7o~BL~ zPE1p(LaM1>)*=^8N>YMSi;dTPM@P%>WyW$<7J&~wnoYr^_V7|zRLmOv1rEL4w0fFq zkjGHVwTX=P7;O$oVj`oLcNFLy`UrOGHIH+xmc{be0W5YeS<2BI-l$XGqZ`0MuL$+j z6vNr@<?jpi%g8wy%W`OY{ef0XsOKJ@g=^vK!kkQl%&KmzKGd&p?R+1*AdB^=x-;ec zHQqOp?&)ryrsnVR*Z#-MR2^{n+r?a|uia$qZjA|0rF3BFF%QQ)^c*Em&4o$y1596i z*SFt(^4yxQtn|JA;yIGl>C!kuL;kvgX{wuMqaF3XuUQe<y{7$5bMQr>Np1C;rt~69 z;H!6D+4@po(5IS6QI88I%3`|d2>4`nxt@Rcp{U1}sm-PB`d)F-?;Gw6M336)M7;4M z)meM0He2Wpk@uKW&o0L~Ezuvp5mbleYnHKFZJ9dbn9Edb>^}AWm;B;3A$z8mUTVON zxX}HDpjt@(<Gh+~m9|Cq%SFqk3>JDKUAcYJ>$w|(J4!9LyYrg3YO9)74hYXVZAHJN zZnJ$|R9?)7Teeu1G+6o_^BcUCIBrRrBpI%KURw89V)V)zyKn}Yh-vCsiTUKp2Up|m zzr>NSK>RIf%f<B!f{iNYTAy%0tV*|QBG2wBg@12T{#O#LS$;-g4N7&wTehyPm$`P* z>s$tAqOJOyr>wex1kUJijDq!8pU~rskViQM-byZ9vR$~OJ108Wf=D1RFjcOeJ!Aj2 zab-VmF3=iv+iz4}d1R`WUS`DsRLhHA-Qqa;Xo2lxiG{6a9yaqX$>;EO!HO1qpiygd z7V0PEOp9nzm1?igLl{cSqKmg4eVn)xcbdA+jD%^GhFFg6MuJV1%%;f&9OrpUr~<d{ zs>peG)#D;Z6W2l;%a!a|wNW=9<eDWG;@WCUTba3E>V=PS=zArWsp05gnJfJPQ(f|i zWK;xey)JyMBTKl0|FKw-SD-W6)Vo{DbwP+sHr%bH{CY);96!>cV3oGQ8V{p3K#nk} zHtSo>!@l8h{W3&G&KTC1WQ83VwIh9lmdk0h1WV%;SM#H>Lzl^UUM}k0Re@^}puS{A zR5@9w3wAt@NQDq()Na5@CNqr|o`T&bW*Ya(^jLTSYk_T!=4_^<bT~p7)2Lv#vgSkm zW`k4|8Ryi%Q?tr0$b~cm`)S=v#W#d>mk{Acj)ho5o}zH~atFlfiFRwD&|A%yyn}n5 z!LbfXS6hPd?$gx7)p)EuH2~2IZd<enuNok>#eR$(L20Ty_}4l7WtvJJ-s8N)*Gx)M zo#&2=mgz;4%t)x`9A^_g0=NCgp$FoED?BA)#}Io~rlKcR>BTH#JSODWkH~S35`^pW z(czj|T%4L&&x+a6<M8qZ3oM=P(1aJaO5>dRWvwJi>+R`@v7AvPApACDYQ~mhgCB-o z^5H0RxS2K?7sskZnj!D|!Eki-oAnn|K1eXn#yJo3>zs9A$OzMv<tiP)?%ij9(;ta% z8GA#wI#bKR6$xgyNk$LdmM^zBr<`?kr;Ta2fsBcGz_ynoq<D|{3xkm=6zq*_vx1QX zxe8aZ+IlN{Dp(GGRyUAyD%3eI;kLQb?dM&6ebW@(cw7|8EVIhRa;8dNGRu{A*!`a3 z0mcx+wFKj!jAclQ&S~oRm^`x>u>c{jhG`&&?3HQDl9=NRRaE_fd*^f}o#R(FwK$+a z_Y9&@_^A}8TGk>X?tq}#Qf1Nd5Redhzsuniv$b$@6^>%omBt<3#nmaW)Vd{4%^hs~ zShf8Ouh`N2@6YS!XLb15iX^_a^!2Z9zAZE1HmvvF`rXZG>NxUluYjwTh%_l&i|y-8 zpGne~2DK}hv6}yNKALM@5-$vATb=<>D9~|>_`jS~AL2>(#WOwZsF1H;hV696|8TNT ztbWsFP$g&Dn8upDabuH<`&~aF;|(JzbWZJ1w@9Od&4%iGTRUuW@#8``Njf|>?BHQ% z(?pdfxaCt#M61jyNgYE@<UUj8cO@W;=UQf2{B=!Lfc=9Z2iz_>i;=`U@2!|>6LP!4 z;T9hYX(a$f719h6EEb|E(hGRSNcl)(h#O1Z|7o|YeptBVk?*7b)8aA)F=JudY6B_J zfMiq_UfQ?Dbj_2gM)nbM)s2Y5t@3z8hS5POt*{ntrmBL{M*%cW2m%AkDm<gPwlKWp z0A4UnnT`q8%2?$!uW@AP6`_h2g;fqHuo`EW|B;A28~?Jz(o*V5SvuQK;HX;+=;bdi zXeWRv0144rxZv%HphcSeIA=rMZ5b=R!Y%0h=San5sMTiC)6NNbyjsBiT7P6|1TH&V zZ@j}^e309oW(k(H%Gj;Cf%OSV@ee-i=^o>{dOqCZTzsis)>`1y*oT}sSGARTZ+o4A zc#A4qaCe?VOn19i+1OB2z9ThZ>WzxuY+3tMqVUx$J(&}9@WDMDSDxB)^EZSsn&Ibs zX*b?dn|nnL+j?PjicLKd+SqWg;kTPzFMhi2WhUImIRyih<tTW?Mw=>qj5ZxxFBkLR zQ6ckHJH6yW9t@P5Fio|@AX79AjpKyO!`15!-KkwWm21>}_g-(hYnkg-(SQm$@5qC@ zLi+6FE}O}CJ!|Njh3lCrgt@MF&g48yS>B3(ek`?KDzXhtQw2-D8Q;i^FIBWuEay8C zJIYkdq`IMUTptq4_1|^MsSmF<ynOnjvZ@SP$#b5o4mDJDon`bfo1ecw@rt2dN=MR> zaU(VFI-3?CV&eiuwA4mjcj{LnMr<RQr)YR{rtaY!zTTE@vB?Env%cQ249VQ2VA+iy z3kL)nkRRaB8iXdXB&FM(0sHFnPJXt0dm5WM#wBt6XbwM1a<`8GSRA3n9Ot=H27;-0 zPK&E2GL8@2nakFcc<a3F`e#Kw$e{71yfFi8$JV;ii$mUUY()OMXyMn_(xXV-Swe)} zL64)bAr@HB@c_%<5uZooxE$tlTagFHU7;QcHnUE(sr7g?ojLG<G@kn5efF}bmuZh1 zc0Letvm~QYWEq{>z_cq|xd6wO>U#0?5-~kewhO@`bk@90GS^c~kJf#3j^<w<7*uI~ z)6`&nSLY4{WgX7=?Wx`DiVX-gN0}+(d$A+*yfmrr<8SDUtT~$B)NkScFikx~3hC~W zM9Eqo)H=^0fc6Ryp5gXM+RL*Wq}pxyqxcXcO9flk{oD31=_|E!wOn<Bt8di6nr!Al z*$?ZlerMBhnFeXK@O=Y2Dw>4*p|)`$=ag%AJxoQWsP~G61zKXHz^u6_is)tR)=pW3 z-hw=)%1LeMGhXvxFN^7k6abx%8ND#fx4)tvcZa}M;Br@=y;&8-Z*t<GH}f?;TH_Ti zGtu5sX?{cZtk4KF?<ic@?DL0}o3i!c(RYyl2AKAE)w-8yR2peaBfdbBod10hr{Lih zgLJ>~X@ji*=VBhFgIml<D&j=9C$nbSmhoEmDDKBmwe@E&uLUl(6>$-$C4v=qNYYek zsuaNJzWR&o*(hYfj8#wKq->124e0N(+N5=8Tu%#7QE(Yc+kW54g6o`Oc+Vt0tR<d5 zP4(Eab-~g(Fa<K~Acc?S1EAM+Y9>F4MAoyVlN}qA%m!EASlCYmTAnK#<s3Y2no0?a zzRz@t)m)Sj)?inkG7-k&YY?A2$U$og#X)cA*jiR>E6}Z$B*WEWWUT<T?AiUnxK8o> zONhC>Vp7!{69%XRc0eUF>I{Vo)mDioO4+U2)&4?}w7bQ!To<@ZZ{|ux;qeq-$JbBh z1i-1=Y3IS!3f*Oqt3qJcM6gQjDt`f6ODYC)NKmR033TXz$f#Xw!B66tb*ubr3~Mfz zSpkLFo8m$N=NQrmkj(el`rcT2)PTJKT{M`7HLi2g8u2&q+>Njax5TGk(IS;0J#YM2 zV#eKQp>0E(gAuoxmUxOO*0h|k_3xDm@zdGjEU~&#)>;CiiU)8Z5s*t|u2dxtsX+kO zz2>zGP*S*-+-wJSLKhD()fMiG&O!FscWpM%*)l6L!mZ#cS`MJL4p5<NBz5qBaMhC> z*G^FY?j3(PuK$z)uo7M=NoG@04_Lq4G{@jFZn*##NmV-PsT=JdY1&HVbdN17>CDt) z{TJjubS`JqAf+8vyurv%Z^}iqHD@Gfmf2wD+u#HUIUomCan?_XemVL~P*LuRo?9}n zF9qC89cPTMcUZSv?DP9D{4xsV<e=4NBw|FN-%)99kp#9)d{gIaa7<I@Y%p)DA}yyQ zdE3;ie_u|0c)mafFk;mG37KSFm@(;V{>5cQFFn0G;F$H$eeMMXyI0_F*F8o3mqR-x z|Eb6*&eZbNJ7uUd)a<sTODTEVrjp8r^zS~Dr?9Nhf6r3x0rm!KZruH|W&!`tIr}&d zKh)e<gc~eL&MA%zk0{<<cp!P2dQBt4b%L7-1K&wa*;h&TO2$ZL%eg=w;jb{@F93@+ z)7G<lv_hFRQ#(!lGW=Mybeov&l8i>9c24MM)V$!7MIu-jza^Nf=JPcpKDYo$0k}fl zF~6$1+VEoWVffLKPnF4rn$qLisS#0P`wkLcLN;DFK%oEiti%288of{~*@>uJKo1>T z`7|GR*fx~tz2QN#DB|a?$HfF1?v;%G(D2hVb*bK^RkG)-Id|#D81dbG%dM*9EFou_ z3aHH-e}Wm>j?&GpnN*vv=G&yZnxsIM1mkaGvShX#%Tfb228hp~K-oanu1YRIy0z<q zUHzShg5`1ezQ&&6&_|wq30QTC>*^~eVKE*+3wLxtTm(>)ABBw`MF6;^O0~I+{z5NF zvLr8)9OB|FK&Y8o2V6qnJf}jGf)lewKU={saz>B8uFlj45OA6VM;pB4t>h?;h()~# z;5$^w4Cs&0`U6d<F3oyZx{_r^PWaj6u|}Y~KdPEU4-f@b33j*)r<dT+1>?F*q)t<R zDrL8bnUNscW=a&iKL8Sj98Edu(aPINa^G;@aC(_*r@z2tlM53C-mY`lfokW%Ox-Tp zc@9C0D~)5F_>8aov;$&rFR7!$$TCS>xfs+B)_XFCD@iZr7U<53B3x-%`<iRL2})ZU z>VfmFGQ%L>Gxx6>ZGQJqS4Goe12Sr$h?^y%?K&hT<#ocDS-A3OgbvCdN1eh4y29cK zdM9g1@tdY<6)X^DwI%p?6o3b=4=6G6P4!3^C1)Z~zo|HrSK~q9ps1iDS`l0k)=I5k z3I-4Z5Q9$&-*?EuiHDIqqnH~0F;9}_hvPu0H`bwkPLK20h~geTGR9>l<w8e2fFO3z z5*_O4yUa>hie)X*a@>E{+gOU36nFp;J7bX(hWxG=Q9WA1D0S<eygJluYI9qu87`u9 z=-}&efnXGj9*Qt)Cf0{Q-fu=dDPQlwEzsf>;?=OP$hB~-3Ja`5Ug<A&*B%x<mY}l^ zdeW1btQq9o!(;xi{qaGB=MmRCSTjc*B7}ovvSWl^X#u``^HnZTn1;}OM+=kJ83a}X zDxvY_>|G`;!lJziCgA3HnT5V~{Vf3jAbls^Y-~{dseessM560f7K%~J-k&dAuq>$< zFCTkpD?Mfu+;P49?~zt8f)>1Ol2QA{(^*B&XZP7MaCRfP@eVIPmL>42CC=IW(m$VG zBy$OhGkA7bqIdJUBmWTX<J@#M^_N78)}0wI{=E7vq%{MvZB)ObkoouT*G@B?T9mZy zQO<h9XyX#EarSN;s@6>105dz*`^vFx!=lLO`#bW5{2$Ds0LC79&id)!`*u{<PhBiy zN8^@ajT`HylyC7-)Wfi_=Eb~d$16i$#)kZI`tFgJqx)TbH+Cpm<)@~qeq`sIk;W}* zP$SQ(cBYiX{<Zt=rq7UUqv`v{gcW-#eIMT@co;|LI)GOk&37V7+Ou!a*Ws${rXQC7 zl$G(uZ8<1VA>gL##R}t+uUfnLO{0ydso?23N7$P4lfTBlGE%Mrx>#m%^}NHh#GJ*s z?kVEgn~wl%Tn}JEsGw8;;?V@7EeF`y)guT{TSxbEWu$6K@nc61^IQf=y30}G8H0$I zk%$zTvB`wGr?tfAy)cDdS}KpHxN;?kvdJRwRCg;;^inF2u!QSis$IrdjvY1M29(+* zk0glV!PJZndgSTDV}_m4ccV<wR~}o_N(kGKte}*YKKy!WC@=PoKG<|o)(ZF^xI0lm zE{e2X|LD{=c+=Gym$6JeWfb0}=jc2Id`@FNO8$cDmyPCc4;Bc|R*MlB49BAe7ky{6 zWo?|MhWjhH`K4xOebwKd<tY<vl9Vk6_6dMAkKca5sd>f94C98Y>=T^7=jy$z<64e# zfWXYU?Kx~s!`R;?sSk~}vKYNj*s8(sQpLS-ECyRE&~1%5A0+vPb~#V$N^_-PSOFI* z|Dto$0b7vE1u}N;G4H~jD}W4}*L7-&L-z9i!C$hXN<0qaj2M%-{F-F6+EiS>Q?PB@ zt}$-qpTb;UWQmc1Q77)c*0}Jbwjx#FeZv55Qr%Gd>NwZ$w?6U50>>dhEu0GYTzpL2 z2z{scpy|QDH?9*a`hE*Hkp!0|&Pu2pQSIw63oPU|;zrEgeatWUgpUb$fmAX^TXs{h zh0dqL%jJ7a7UE<PNH`l=#;)Vnamk&1B0(<dVF{P^y;_?9=HU{7MM4k@^(s63s7pLf z!WR8-2nZ0q5lGSOHW;=MA=7kXS(Ak)L!!aQ$IIV!>L<~PIMwemQc3j(Og93G5~J`T z-)8}Yb&+5LJdfOyz7_xv=rD$ob}^AO5`q<#HQ~T4?Jb~MJ`AqP95Wk;yR1j_<`E>m z)zSQe7w0_-AJCf=O|xFM1ItDrP`1aI8kac^8G!$_j{3n}noJ{h0i<v=YxBZ`*Z=?~ zTO*`9UCkW_t~qDZ#noWp8WgP-e$&Xkz<7G9^fcY6=M@JK+<&rY{9?Yd?xiX;CA{Qd z5O42w%v&eZKL{YSdE}gaGyVbNH&J?j_tPCTpH$1{5TQxOSEaJ6<?6uNuh2Z8@0T%+ z(!=~FzP?w$aqTXNMdu?Va)lZBhT%#}Wvx;M^<JhfgxaELu>s(oECL;dZEj#K=w`5A zR4PcM?h=NG{^F0Yi5e|8P~>%(5M!jK1oGJ~vj!y>bb9Qt%JHu2;A#SQWsGwfDpP9{ zK@%b^qK(n`Nu-FU<hYy_M$a<%i~!{bs%ZgF%_p}aclDRxi-9Y{GzBOf(<D3B`=`Y6 z)I8_;BS53YY|SA=5#-hiR30F>J0y9#wE<a@`^Xb@93?)3duoyEmb$SboECF|gy9$8 zX1i&EPS(8tF@lN)60l?-s;GWB9UeveU<2KGjUwHiF>Ce|3QW=-v9uL~#Dj~(#PLDb zM<Vx5s*(#SP%5evy4Av)rfz0mNCj7Cxw@Zc;mg2K0ten7o-+vkErzQCzi2b9nq`A! ze>H$<W#@wZiRF^M3)f|ki`9-qbpS96B5lGINBx-qHd&Gk-~BzFs^yIZ<I410CrJyS zDN!s(&&ggdjp8>`X9mPyZen`jNP%!-<l-z?{OrcZCFXc44^e}jR8L+l!<9q~A7X1t zW!4;^GndJ(3E#g&w+5WExqX`Y^L2P~d8w@sN0zA#kn9AR6#ztmx7?$4{CBAWg;@Zn zL0ZPnO$Wfks!J8FRbU#^M-Aoh2GnCH{gmws0LreaIZ9N1ik6aje?rrV2DN5~i{QEx zbF9NY+yc0is?cK>A_x#1yKNH_0p_w$TzEOXn1_OA{{mNXR>FWAY`ZyhcCK`fQ-<m- z4G3?tP3@)DptuB4d@?r3#w{?&)pT(HT1F+0y=x#j85cfgFps{Q@uC>@o{mqlAYjpJ z-OIUhp%IM?R}TQ3a8=;Ly78Cy;KVZ=Eh3wVpQG)0um1bGoM3Gxt8t}|Em=;m*T{)D zg&y1zVQ+hdcyqPgv}(c4DNf>L22rg$zDsdie>m@uLD~*NR@1v_P3n`WziAyHgRzmK z)80Rw-Ui1);bb?VuF_p+=TDtWte3W}c#i26qW`(|#9r+|`kk$RmPWr+rE#POW<I4^ z*!b#6-N3d~9mw&kF{<wV^ur(K$)=Rz0<F_O(fZ?=e%Zko(LtX1{>sh(#H$t&VpZLs zb6M`ApC~|&wlR}goA&Max!Z2A=yTDhLQ+3dR*wn+?ZmI1xoP?>IDhp4y?hL@^=Ofv zWUL`J7Z7dnH>jv74jhF2=M6_Q+GMW3!=aYqhWI0UQ-gWFJf~<WqTbQNA)ofv4x|89 zf^~erc%$RH;1E4hu1x*wo_vz=TV#0!uBM?ie?4yd?_JgcEr2nh%xRPkb#!i`h;6VI z0JN(~`a1@eQirCfJ$-BPZ?z5}zs?S|%@@l{;uXJEYp<iHZWRiHrjT5=0v`Py6Yf=D z+jTk4;JPJ27s^qD5_6i0aLEWzkqezIhe%PJi#y*}jt>U+-j6uYaQw$u1M2S{J?EDB z;YNi!x47FKGFNh;jKCaJ{HS5LnIM3`x8S~^B8c-Bqka}}unJ>&ae@x@W~;)L!f8Z$ zktF-+P@U)_b_)6EJIX~MjK;Vno?<%JsO4q}*mJGYm^^oX3Gaa_?G&)^xQ<J1Wxj9` z;sV^WQPJw^*|eV)p9P~t7{Q2^a$69B6W*7tW6es?qhj>ske9K^mVDA0oTjp3zI>Xr zXMc~zaa=|w9vudu__f50D2AXYDYx)1ab?y8q(T@$<^;hh#|!Gk@=eK}z(-QlLGB{F z`nXRp%H_jgq;#Z<x-?7_P6JN3&L5{IgdhV+b30FtPG;h4Cb&iIN-YM-$VDxLtaQKV zZBmG!XB>$(_Fz3}HH^G0E=uyG!-cd-jY!Y$uL#aZ>2V7b{RqDveJL4;D6G6aUeOw7 zP_!IDI}TRoK!tES2_*+<AAiqiS7+*YAUO0miA-D0+rD)Hj21=FN@J2#%)f+9+5nUZ z*!~@iN}@;3<tV&0xw79f5*o1M_|TW2m1q-MKR6ClkW5u+iv{){1HRp~A8&#dv4Xvc z48S9#brKpHj%f;;QWZA!=f?pm15{?)kSQf&Bo=fL<1F6a)Nj6xn=zqx)e|O=NDEq) zgG^^fPlLThXMnYUl}K=Nh;VLGIl{t54{w))l<`{!gpTI?|M6q(^kmUqVgbbW@RF~E z2#qLuSKtG&YfA_v=E(4+!?j?jtT`?0IE`~{iMhvT0+^fI!DZv^lGXO+!Dy{Eho9M0 z0DJNJq|tQlT4}nwV5K3N=wK$Ug0dX+{Hb_@#;#k8RF&k8$z#S?lTAVj<5NzVEo0N0 z&kHL=*i5ZlWFHDi>I;cHgn)XoXc1P6eTWmTYe0mp&P19B$l9n%*R96=WvWksgbYTP zG2!xIy6YJ<?xj&~782!{?rfZan5at-B5>xs9fiCcfy%uIWsUi?&Re<3d1U;W7jAy7 zwJ1Q2{;b#r`Vl}sJf6<4{4o|K9jJPNy&3I?is$Z-q)^&q3B8DYhtN}lp~0XRQhWvW zy3mqGHuTF3C(%?v9UY)<Eb+dc2<^uzf3VIe5eNBig?z!JHJDB383Ocwhsj}v!d)fv z$9|GL>FT?AFW5q&S`s%$tK$>^L%WRGE9Z}AfBiw$wiMR<Z)6<agH6-a<L^E$8W6oT zAk5&6g+>(iJG5&RqZ<seCR8M70&Y4?cg&r$=m651*iFmV6!B58mZ(W?n9ND?Trt_< zTyfbkzb-&+n_ssp9Aswu_0h{M`>^KYKkofjF391NV+?#p=cOL*M|lh14#_~6-KMSB zCgiHpN3Gh8!I$$L;68Z82rm^eb9Sh}vICK*al51=uU@;5I{5%v5IE~1S0DRoxehHY z!uLRQ5gENm8i#9XuUD;y``p<)wHMIjenmfHGd&csH{SSu<-!MDvK^eGiXO1?$^j7w zmSgEQ^l@87Xh2R}1v)DR@?}?_YHav>@!OLRs}Pi1=m<xV!Uz!yAR<0^?XZ(cQ~A(c z0@{Y_RK#V{Ec8%0$l1B$+Q3?Z<a6;Vl<%rJB>cajBC%_m5EXZ&To3?Z&{?$k%rVpf zYk>}QL|TE4qcjtOry4oa3Yrw;Ps&EL$4R7s?1m>5t&9#^gHQnkf)tZ*#fUiVt{0KN zep~OsCsmmx7;#&`(Lqe(a#V2Dh~EM*NL>lD8?&|{JFOk`+|w^57k?}m#67Ba@a1iE zPbX(tizV1Rya#%TT;N5JM$J^kKGIw<zLjy7`ROhz>J>O_bnY7$dw~Jlu!6w1wy|SB zVV9HbNW1MZ9S0g8Xhz30T>x*+bG2vqG_AhP^q?$7dBBcde)+*YHpR}gLjuz5nD?Vu ztnxm9>qhcbzZ=o7d_+oPyBVD%m^I-(@|2rL8_6FC8wJ{yJ$ni#hLE}b&lar(cDK!s zIbgEzo8`EIBuXLtnQxcOB8_6wOPIKN7-1Kubs>yiDFXdNn$u;LMUDuBy+Vp;4Q&1~ zd2Sq9?do$*9H)D<>m?S*y(0H71t$yH7;a*MmS12i(2~sYJUHY?6hEYEHtRSH?~eZ; zhI&}hlOQZKT#{c897j-nxfYHz#y!O=062;SIq%*Ifmp~Qup7Gexe3|;oUW2%zp~03 zInYrL18A}~AgCZR^=Atm8hgenFO*CzXn{wQ{=<!qpk%pdKmgW?podky^1DKwT;v!% z1onrokBl1j=|?CZDwA(iz1}qFDMsf5tNoI7tv3&g=vGof6$_NBywu18-)9R+FyJ>C zD)7Na<xqTCc;Fk3p~;D`N85+iqI<UzXRIC`^o%mNdcbp{VN?-pd6~)jCsW6T*8w-K z_rONkxj-33KrebEXtC306Tl1kkfT7|_Y=_08l_3qpxK0|#_n7hg?{uhG(E6wG>(n7 z-Oz%ek`?udnJbRwiid|0uF#Y()$c_QKA7El9bz&>&#R@#jr}CgY~;8_U#Uc+rrNm@ zf**0Pv@+JHBPa|i6+?*+l63)6>howFxpoSmV3ThInk3aP-HZ0aSeS5;oA-x7APmq< z7JB@*5M?eYq7sFyhOJLP%B;NP^<ZCd3lWFdO>5<GXvKA?(z1mp#4PyZ{wYK;q!A!l z*|WkhvUk)s+#tBi`w-vd;U-&gV-Df#xLLW0=)$mj;V9@4frifZD1V<V@MQGyd6D~$ z!q|^|!-G~&XY4Qw14xZ1UiG-pI*1qpJW+Vc*&Ixc{U{^^`+b7leNn_!LO*oJYXYk! z>B<e-_r2VDxkq>PqSh{LMW9#T_?NpV6bEMfHnn+P1qdx2$SC>#s7nTyA^XDcQySk7 z!|ASAQn&K^<wthhVZV8-cGTHK50z!D4?0*x?iM?B`opAG9gm_EA*o=WT_*>Q!r7D1 zPCE|^ia`%MCrD@cPh8yjYu>T9hnzpe`=Zre`(4gr02*xoVm?`ZW9_&6C5{Gnz#`G2 zbgbO*$v1z}qEiQJg0u|@S|44Db4`DMpx7otRVW#ydzt&td%)N#`KCQw*G(}BM#vY4 zZot*^+L523ws8v&!2+YGEwq`yTuDab`iXk!)+wTZk-`OG)ZEPw${|J%sYeI@)pT3d zs$jRmgfAW^to~NEMrM1<(d2}2`bGx{&L&dArBDRKdBJID27MwZG9Yds1ufpt37q6? z!mClfrYDLV0M+S`cjAzjhShjwfYK>IOJ7TZ8t(mZa_@UY0sa#6p4-wWgM1y7Ly@QT z(2k-ELx+7r9&-RaR}e|)VTrGQ?ECB<L~MX$0NCpQ`)*d|WTp-OTnBuNLJtOjCK0kn zcjqGgwf%5!rV5w~)q5IRkhJSX*drq(N$!Q+nAFa5RY6cZqKyVrr%jwiu9Lg|6RVQ5 z^)CRP&`3_;fUIHB?)J6~b!n-B0e^|>YAknJaJ4$Mh-AOhYKT1enLTI`s7Z^Ukm*J{ zahq6`l7#4lD!Tx2nuxJ7R{0BYat)-<iSruz7H=tw1WX67gs(%W1F8xQ7B`Vz2RFoz zao8`)SvJavlQNy4giv03JI|Ykp*QGds*lslNB{(de^o{|nc+%6-8h|GG&+q}0!S== z9@l4p8E+0oi_?l;{wXJN25JH#KjRN7TssgOmi9aFQ=y(DJMf{dL!A+mzvdK_uXGDR z(qeKWP-A5Ypu06Az<xzKn65quyheiiRxPk0A5OHpQXP{4uk^cm&<17ntIKt6N(rrP z!jn^6H46vot55qFIGdP-0A{8U>rEydqorKg)G#6uAzcU#aoydtf0_!9#?~Y_CP`XR zB9R=#p9xSgZbA-K_1;ZlcmrWKi04X5d{>Mc{B-+>5O2&{^y@VBjutFZP1W6y?i;%{ zw8~m*{^Upksf?3G=vh*7_|ubxdp`(DgG@A|-weuo+Xh2NnY>cB;*r%wPspK1#)^sk zR(U%nV$ZddLc&(i@iCYkw}fn!znED8a%@m8ii|&i7(>y}_@IwMsJK)8GIm?S<^5dg z3V8z0ensFsUqSy)`p2zciRE-;j5O*YI#3*Bbi4??1|%O<5l9uOn#-oVfYUje?XjKc z%C4VPawnz?m1kalT12v1xyyM{=+K2SlQ|(?SwhjNrNeO~uofGydG3;8$?NF+GVCz~ z?^s>=uXzI-oEqqn0-w)Wv@$xB^!*B(8Ktpv%j|qY`k>97xb7glU<Ex9GnBXF?$C>3 zXB~*b4D`+nHSc3%k@>RM$Cn>mRDZ#-@3R6u9FSQyn#AF%clH6|`k!wM?q8#skNhPU zy~VRT;Psm)uZ;vfDcf>Ek=V9Fx<)h!;6I9ze#NT0iyV`QWWAej=f`nDWu7~|ctXs} zk46N71qwZm7{u9Ah?8HR;rhn{^;~CbDu2vYJw0CiHD9tC(BNMRSDJs)tFF>JBSXmA zFo_tgsTA==XjTQ|*Wb3u5>$^pvd17_v4*{2%SmMJsaFb@;=Up7lq7u(Lf{09t9GnN zZ(g~(K7ZZI!r+3*#l-yTh6<i~9ZqPB2&=b$I<PT|K$VvG?{)`H6mKT@lqQ(6{$D5! zcaf`%tuCdfdc=j+-c;xLQ!9HAxlS|%Xio_%uYk(CiLgISX&1}iTMt?Q;=0;!N0O4) zR}qX_{$$Z7^LKP`J4#e>efk4zopx=$UATyJJpf9I1~fM}ee_s7EY*obnC1P#(B_K( z5V$HUXz{=%O+;(HC{k1xnEA{{XH57yd$#^`q@(Ew;uu-f%M1e{z~aojpKk;!nsCc@ zLc=O^*x=AZy{PSxP<)AgeZ^u0crvmJG5*8X)QJkeGYcOcLjG4npSwjr`*b$~0D851 zh6=85cgF^}mDeiul?^w4gR;zB7Qjbay`CvXfQMLmcGftY>B#`XRJsf5q^*@Y?ryi< zG>NT=8Yxm5SkUa>=OkDUy|Q#+rEq{b1v-4mJ<h>M0ewJYYD6&N%0btq2EKbaEf?j` zG&N@2m---glf@Zr5NEpn$WgJ!UcK}5Lm~EZwN$=NzJaGE;t+BHLM>=JbOPGW|Jwqc zx6?9BT^o)z0rvF>0}w8zhJcQ-X^5ZbTrM*_EHugOVjgs6m*ng4(UNh)DYU&vz2&fN zMwCZdLMH?U3Z;mb!oVvQn@JT?Nu*v7Z@<k%?uQ2*g*~b*p~$chsv-OBDkUKouo_A& z_!p4h&<V;<$8!Na9<WYA>+4U1&2Ko8ivOUp$qk@l(H#<_kW&&8>eOvj9GWxs^wr1> zBIm&k%^v(L0jd(@0LXRlDYtXDoDsf`@CH?to?zwdL&gsO6d_Ka0Zr(#%YBfvqi3si zG*f8gjT{pM_=`Z)0ybp+QuL81*p+%q=Bhv75)gIA(6<FpjAW1;5Wh%feG+X6SPiHX zq&L#>4M%->U^4h_6ij=9Ex{!|K(bE=0+7i{Tn4k42=OU-6k_5es(lPMa8O9%L;xJX z#@vlZ-%7R9AE(e@Hk>4qKvTK%oOyVasuEN}hgq~1#g`F6oF*b7lb3xS&6TQAv-L|4 zq45Fj%|oJ60<-WLvi5bT!(`zoXjgfmcM8fy0cM;%dkEr9b>k^u{)`X`Z3tw)Y$Wv} z_$HDYTN4i@ht8pQEkxpC(~BLKhJEN<_8iJUbDIo=U<$fVJlBf^C45`x5eS~DulWcH z3tac3P-j3<hHrIt6adH}+izX<B$j9bu#ae|;F_JfFgkqy90Z%yYABkZV~|02L0<M0 zUk}EkYa_-v;03~fFV}lX7~)ezVUoD7QjH0fXaJ`5LI}(eElND2F~`817a;i#e}RFI z!}M4W(Ys{`jM~K5>evB^Ip$}QCg90y2WOo>@YBbVQDLxR6bZJfE$^?=S5m`YfkdB# z)gn`Z?(An|8A1P?rsn+>Wyr^|=;-3di;h(6xy#zo{*%NToci8GaiK@nuzgJhU#n<6 zMfBIE6G`TwJek9~$`?%AF+crTG$PYk-Fi5r-4p`ayx$U5<NfL#9CVw;bYkDq9B*gb zeb@`hza5-->WfqF#2Hjk{k7#gE<2JwzaLzHkRm}f%iKS<bMbDECQ|jIYRF~J9ww;_ zcZ$(3uP_jhF@}3}5-pXRn4v*W5}43gw<I`gjzNx*5!C8N^&fH+^clA5KxPO6p}B<3 zk?2saHwUA@W-WyBW1|M2M!tk+6HXEcn@ALPuB3aez>?SqukScw4o?Xw+|~V04~QQ? zrv<Es{X>Vq&0=bCtx<uCU`3Amrksf7X7&gM+%2tY_stdiO;fu;gBuaDN$V7nmS=Gx z(VS>Itpnzu#UM7AD{Bc8c{EFm35fl^k?1^v>zHVZUnJk-F9M;8i`*T(80~RII!g~E z>H|Io=?vCbe9eP5YErkLA&(p8$i^oG034C<n417)G;vECW16Op;KP-^=+c!FIt1eJ zhLTyB&%t~`O9i+MI9+Mjr>BtO|7f?eH8E*2cpvBi^up1s2f)Nza*7jf#d0C(fx~t} z5LeeB=cAA#Z?sV&80AW%N%<fSAS(G4G{ETs?Ax70CbJm>xI#kZ$-q3E@W<Q`P#M!5 zPsy&jv=9=Y%-1^)bLAV=gc-SqrUlv_#&(Q5po6Qx;7;YGCvhojAnQiPU%lHFlwKT= zMM8aB8C3m^c-udNLulqBLb@4Oa!FRvrm`YrU1E>T!G9+K0G_0Q-9ycYkGYT_;q16Y zn>{sSh(qA1QA=Qvh#F^66Fmg&#X$gHL5PW^{N`FTX7pnnf8)yc6}OUzhaMJbEL_L< zhh)1AB1Kz9f-Uok_ZW@}zRoFj{D2UGc@X(sl(qKsO>ZI#8IQ#hQ7pPV58L83Pz#`` zdkf5O<S8L6ht_Ic*s9wSo?u{U83>aJ5GX*o=Aq@&lp%gnbXYjB4ZZ#T+DLg!_gBpc z1B>!el5j=`vHZ!l@&hhJ$y2y!Tf&;S`SC#Jd!-^su1E|PsY?5y0R@G-sdv9m5Cp!E zVwl?w5n*Z~ib}MFF=|FSrOx_bIeLBRq@)S1p#O0QTLZhM1IF~+V<>Hfy7N|%7t<&| z<i4R0ZlM1WMn?(_Os~Xzn2V~icl|65#;+iOY>}%0iJ$uq3aEIdcmR#o_I@Di_3N8% zn}>#w#M<L&>HfLt_9kTG6@#uG<U>Ft?n!iyUArrs^`N%Jo8El-HT3zJDx?Tyq9-#u z!rq)mutp5g#d|{JyVwkyzHU!fYFs<1pq(F0rT@HPFgF!_b>MD6$nHMKBQabE_2ooQ z(yQk?KaljDWX-VZR&VQ)ug`R*T|;H*GUUAaAJuc}SL<=ttc*7BlZ7`o1_hr{B(|ra z{XY~q+w%1C^|AXnYA?hOz)nd@n(lp)&wd&9job&|C}UmM=bxaR=h0$Vzsj~045)Z5 zxjZ7rMm8C4d=@fcq4Am*n~GiX`zzI2_GiJv3S1Wfe=^Av>G(t}Z!9dDd)&7-;bXLs zE4Vp7c%hshz9m7aGx;%zSJfxiNkuJX=CqpcMRWB7;>;_gjP62lQ_=t6$SwIUX<Ho0 zR=Wb16upy)V3iFKR?6om?kI1&ZWW-4?a?{vuc!rbpOt%@^=ZGo_&b0ziR*h;9^gGJ zq$hf#Mt)7ZAn$IG|FH1Ry-XcMZjd48#~=RmMEml_rv3|NLnXo?(p?f^W`$@^<1Rw$ zjJZd{8Nj3-9hN!B*cM=*tf1~~Vc9g5;EoE%-nei^C7Sd@UmYzkR@?~%JngDiX%pr1 zP8ooDalKc~zhq(c&<LP6Y^ix?gnfMu;AcVi)*7VkEM!W6q4uc}MQ7fn$v1p$L&kfj z<BA(|p5d#~SVEkXU-l9!rX*s6Y8~ifEE02~?FbOvt$Xv>WQZ6sljQJEYUg;QSti5? zk_cv7upH8d>(lpK^S6rrQHIC^yh@_DKB5)Fl^X#Xt7Pog=!oX~!mAGe4B>X4zViM+ z?8XJHmatpQB}lA9;b?fk__<g*WJ<8~1}F<1_33CN=4x6>yl>hvkkq(l9wDld5c#1A zK$fV+P~J|=h@K-|1b2?U$@EqEGu2{#bGjNx?E<Jcbmx6QU?Amp0CmHyCQ=040v)Xk zq&OocQkf3{%z=Ap!mCJE@aUAX@dq=u*bwK`DwtaiwIhUt`*op|niS=ta3u)9><K2k z#1aIi6x16Zd=<P`i9iU_cX)UX4|gO{NK)|nS^aJ#3ywYAs9TEwh;d->J;m!qgq<UU zz2a-|RTr}BR->&b0D}$an1D%wW&rYIC=lu?z(brKtL(@USy2)M3YXiP4>T51Rwf)M zmyE4+UI$s(U*d_FBlwaC5^h_#-`&Pru6mM2hZtj`&~=yR&p{6X<E@RPqB@G+UEc;^ zOF|(=0hSWh#RD*yR56laF{mPtQbk^nC;$l@7aH>S`v!x7Y)2A<dXW8kV*z1e(Jc0j zz?q*cqzL-V)NKwgw?M3@53hXPEO?HX=Tp*b%q4wB#T8@6C+CpIB1?&qNe2<x83%fH z%t#nLX+~Jfk4DiF9+UU6IGYmC#TeHaJ;b_Rpu5)3auR=747P-OTy%K?#||l_5CCYJ zI<q?SI&YLL`}iQGW?k1DXjrmaNm<pqakuVr3>X~(LzJtY3U6$3>Rsg`6@3dCm%zr1 zL?~;#?HDp})K@?QOO8Ri>Txt5AOk+-JYwF+qSTWhSYx&b^q!W({tZ+rrx^G}8V>-3 zRu4vW$#D&t#ps9cUxeLuk_B~kAde154^o(p1abyu5=G*r<vIs)K8hIkm~jo5Zo#Gn zC^R{L<iM>^&~rdlPNF0M=&i|yXw)i6CS$tL^36Z^AG)D~LBAmNwJQUHQY~;7)T<Ce zv5X@lHEK_mD14akxa}Z}?9cupezDJcn_J!jy0TM?_&GQ$^3&S07!tOd*jgu{skka3 z@Ku)Z9Ld1RfA2oDG`yx!kKx4a7drD`A%gZq;dQ@WJ*Wp>LCepiL|o!G*EufTw%~8B zY<BKI>1E({LM1^stajB6h>0|oXcmA+|8~rmj9Zf~5qLX!)NmP_d{om&dW&G@tG^m6 zJ%A_>L1M$<$<W&>ky8?1<#8GT6etCq=WUo^@Q1h`+3p=dB|By!Ljn4zVc+|QZWHMm z=-#sVpT8o;kd28<+Yxjn2hR)VBox7~%tzu~INE%-p_&zr-MB?C?NMM?R|@qJ`YVoK z(VA%wb~y=9yWc2Dc~e_yLqmrhC5Sp8^SY}Fbr0?>;I?BY^$|Ndrys#>q<qY+F9xne zYFf8s?us4Of)3_)P9sWZSS^O?1sFk(MLN7^sR3EJ3q@l9X(g-$M_2UsM_{Mj=tZHx zLMpa8o9T<dLF6jd6xfP3&-%_r6hpQlM?ItTf;GU>)eDT>%b&Y|+H-8VW^_=t#Z7v_ za^=_Ne~vL!HabDaE$9)z-JZutjhTOmWuTm}Ecsfo1x#+A4S+dDzHdj14BfVS_>2>% z^Mfrsh7DJnY-+SZ)XsA?+XFWv46|pT0~9=0g&G<om5A#(i*h1GUJBbTgyZL=d*D$- zV4;sU^mnG2`^lBo0L{qmqnwASRs}+WriLm@?i&FQ#v*8aF{(6QBn{lYb+jf~{ZQ+) z;(c;?0G#3kU9|x9D6zSzEc@QNtLN@-PX_CS3I;=x!I!1cPTW&c3CruEUpmZ{#&A17 zNd`C|a3Xog<2NP)vRHs$;#jJkocFLt;Xu;Uu5)PjInSfqwPg#dF$dwQc>RZbQ+mjR zM1Z(!(N8UTX%vb++<m+Z|4p9wx|SedJ}!5aZl4=`BET9>E_`<C@H7>~dDzxij+djB z-MjF}OQEK=GF%GGeX*mBT_Rh?8_MS7pJkDyxKANMqGi<JHVK{;1bWE`IMv6e+neRY zvl84+a)j`Z&q6f!N5fS5A|yqm<ZLPgUMMBEhCn>%B$g2}Xy`=T1AsD2fP+#{qnIZ# zi<GZ&O!h{i(oYGc(3KbjZa%T}HEy8?I-T@bC>U{k+H4_4D<MOm<wpuZt@?0Ft?w4D zc!I*L-EkUcr{-oiQ<&~nr6VL_aq)5}ee<IiJ4h7U`d4x0b-e##^sZO=_N|uhDg|II zK~|9-74n-G)6&WxmkPK!T<FxmVT8|Gj9OfPN@!48_KjSea~fk>exf^$S`hDW0KT(X zhfdVo6@ugo?Ro3of9QHyh#I3SHsoW4cEuNLa#4`1MpUXFfZVY=W^}aVU*nr(>I_aX zpBV|ZgwFa5D_UKkO-$XU+kp+D*D2i}CJc<_=IkBDO+fJwv_I_E4L7g+5pOr{?Yb~c z$x@LTw41%Yzi!)|)J>mN|9hI6`fvWGw|Kup5cmOfaJJwBtwd>32V}}7HT?y6!Tdq( zzcf3?4t1&KU1&>p8M0y_nZjTg=!r8G!CM^K4$T5OO`L68aL@eS%2%BaMEkfwJ5Yim zY_3@HP}DJbWMyAM`-ktSepyquG#!!$1NL7dN!h#Wr@ntY6LIMIH>G{T@t4>W&!WDR z6FP}V7EpCU(4X@03sZMjEEgz*2mac{KkQc2uaQSBXhFmB1H?CV!->|0r?(4y#^*i! zP`$dXT*}Tfs4>XEwP-P=U}9^CWPourKUlZ?_7_3H<1aqtlj}eao&aFuiG8#8?RzVS zKTW+m^<fTI0YCud<3t-O2#4k&T<d6&u18q$u3Za>n@fQb29V@Dxhp5LHVnKZQx2$~ zpm(Ia|DTu@J+6cHY`=1~<C61-qJGZ&YAYI>N}Z$Gwdk9>ohPgZM{ggyt$@z4cp&MD z#BZZ)Ye$LMc~LqldX|K0*MQ!cRT(*OM0L0OO#Cq2hfZp+wTPpJ%mI!~9z1|XekmF7 z!j%2l?Qtd)D##9BZ+LOu)?hh<*#?Ax=b;GSJh5-{nm>^OSr=A@kY-Xlo<v_tj|t_> zYu>Nbq>A=s1jvkJ91vZv`r9vE0_jrC2gfjR6<v2^A{5eEq+KTKUwN3mJ}V@_RDQ@& z_RP&qwQ8<H&nHT?p6-rRk2lTFrz2$dlVFgN*K$I{DL@gccd0I`rsiSz`&r2t=8eXt zmMmHshM5%v2afB!V=@qoaP9_efI^&&r@AouXu#0-(jpNP#2fHb7*Hh`gdtLjG6xcX z3D<l0Ru(?B3M~?0fLRQ3f*=ZgOkM#pZdjT81NrGDvv4+r0Uv-BT%(a=3&C|GTCM<9 z<}V;PZ$(%%>4D{Ph_0j)f+DR^$6-54*%T6i(UCi`5ka1@w3YXf7`e(@33Ne{6R9fO zM9^}l2%v<!<_Q81nY}9!4}r++ctDnl5+t(&3#xJ>K^>l!qG&nQ4{eHtts|mYM8bq7 zkiGk#hwzJgIANL!bdQpB>IB6cgw~RI3rP8c;V6jqkSiwI4)f5_A@@-0Zn1Wr@Y7x1 zPbwdzcSri_F{2g}k0{_vVR?0<1@nWncs&LtE}F3Cb^K;2Yzff0F4Pm%zImUW?krb= zPn3f6+jlg|0QTeA^|SY2cpI`?Xb#f#Y>gTUO)y^TXF<EH=GggeGNEUSv`a(~t_GbY zU>0zSi!p0Qq&02oz%SJAp%3ZqEFO#HjlvG9Y|5&N#)ehofh%Yfra!yUKURd?YfB$k z?}frf-$RHkyxB<sjV#l79UWOT_rN-&C!pasOuDqriIb3?-~l&W^Pt(;j7k!bzbgSi z6f!j6{9C%sx8>1c-{$OSDVgIu!tRWudu&B;kl$kzkl^5J8V8{t>VWKu-rhs<rUNDc zIV4~2<&VTs2(>r;y9{jy4cKJLEwP5ul3&k*Ju|P9v%oz-Z6hc8fnkg?o!nOiD{K|X zNZ`RBk}3@ktgzRonXx0ADFL#JzGmvODt&ALUiN)XBAH6=LPkN~!-58J9jYHuxDR3P zgHnNB!Wgt)@OcMZX{wzfE-CmZ2tP8ltH*61Ca#k%i~EbxD0Z(r8W)4)f#2h?zV9&; zLRz;a-UQ>@(*<A&0RqUNJBT8&+I6-Jml(={M=l<O6Rg;K%U-U$gBGeD@YLMac;G+o zhdbad?Ul;B_8u+56OFLzY!AJVy$nWbbK3}_6d;3zK>7Bu^R-Zc%I@7jAVGP39yn)1 zb5iKp_tHTHo^LJCCJ5gj5PGv66~Sj<pf!cjU+rtK$|Ymd)W1#{I^5DD>}D{(8-_XQ zrzOFpDhR%a7l*{{eu6$<_DAQEzpxFk`H#7b@-Y;*!iP_+KpN48vcJOS9Ea6-z5Ff9 z<NNA~^oocRFms?rtkA;<oBPj5eJ9b&N7{)|+&fDqWHEqb@qXd2!ajF>LReVnS;R#j zMe(N)RnVL~v<TIyBpI$;lKeAzB&F!NK!c!(q#=yPn5otq4%!8UlU%s^lQR$*5#D~} znAa2Z9{e9s26H9=Jpy<;l=)?HWDOqsPid{d8v+jGPh~sFAWVbJU3hLZ<66}0!ozJ+ zf>yKX1e4(h<@lgF^TzGzN~6;Z8UVA9Xw$@a4{j<zECvXHur-0ZJSbI(;}?cmNgziv zMjP-ct|^#aTT$MB1`3V^EDuUY$;M0;?)zHAbESccJii0;H#af8aqf5&0yG2}arocS zoY-HVl@-Hm)%Y5)OM(G9FQ)NE$Q$ywUSY6#$PCgI965O{Tr>2G8~4*xP)3j>6j|nY zp1jzC__|#+$6#jNl7O%{=dY?X?2Pm&BqfjjcJC9WMHr+Gk&$Nsw8U!+Hhdhp29Pa- z%@>dejKS{7w%V`ea(23I5jDyE^0Cl;%k_kGXWE5f)0FZo)N%-pgCI#@80dlahmzPO zS8_iMw$NiH<z@p3bB^@!&NYX?U$n49uyJ~ovGHB7IK$41q@YXJryTs}_ma^%^tv#2 zUjtHZH42+jGocrHD1U+A!FA`R0K|n%t$8CEFAU8`Z(WX@+(@t;(Vrxf^W(VrK!9xs zTkewYhzAk|5<&#AFF!9p;6jU2pmbasBwjt+56tIcxwvQ-sr^mIl1je8)5&nE(z4YS z2$rza$}_Q-;rDVtfO^R7D=2iHQ0@00$A-kK3$D%L9>*ki8~A$H?&Hz?`o(nq{)JFq zk!my!(|xkYO2commI^Qjg(wlQ)5NEIm$e>`hXz(!X6Dyd6(Yk7lO7uBe}Cow2ls~A zq_C)A_-SGXl?WKkErl>^-nN*ab1RE-Ol7K+cXZZJcxld}y<a^1KIp}^%iYM649DKI z<g?3X<XvJoG@iTj%;u`+igE%T2pvr$*Gi@BzkIz*>0KN+O`*(iOe|~_>y-(*kkrd< zc>WJu$Jj}PE{^)DFE`3#+GN(JXp%oSJ&mnyOR#0dhCDUvIiJQlM4Rr0ycPA+)IZ*d z4hQ|)HHIb&>w{}^Kj-!}fny4{?!?}UpZClAUdPobuziCE+@L;YSaV_VUxw7HuiX9c zsTE;9i^e~%;wr9qE8pL-gX>qWM4`}#dQ}W(LLc~6;g;cT3k!1JdgQ`BZ>7Vf_zmC2 zp4BEymL)B}?fcZ!(QW}G2R=jFy1wCz@>KRV;UA2C9Z2~MKzDMe?=v6m`8>|laQ=bd zAi}Jp&i_*%@WqfoBJv^iK0h+=o8r+6Eo(-$O!Q5yed!P`R8qihEvR3EWr_FCn^!JG zxH;chQ(H^E!+*d$)MJq!jKphyTDW&pw{n`A^V~81<EWsF+T0+$Bi*ftvXM}oms$N@ zQrBO^?7|DzKLnYc_7rKMxCxz*g|mWLe;?<eMRLZT&Yo@5|3_hyL}}1Yg&N<oWZSx= zCdf^qm)j&MS$j7QagG3H5Qgn)ZDC@b7P4J3I|tMQ)#Ml+up|p`7^Gzo8>B)}mnAOR zj>jswYN~heH7nzY8T_<H7kSD9+HaM5ex??ZAv|*c6j^IuB3k`Iq_%15Mu){?XBnm< zA*U`nSVLM8gv*AqR()j~sNh&2mtVT*-1oUMjTPe%XHOme^q0|Z9C&UA4u31K+mfMO zf6GFAfjYB}&P{#cUAV#`@QHW?OP4TJ;GCyuQ9}fUxMKV^6Q5@0n<f2tD>Q!moOmq) z7Dgpdmm{JNeOm}1XCK<c$!_96V-{-ZKZ5?08F6K?8B_V8o|r!}R5*1!Ma#)N6$U0x zL9<D{fy|&Gwf5TKC<vRZVPBvX*m)_qFA!0L6!c<IzAt$s-r8Y=Q3DaCIM|&6(=`tc zhSS&L359q}8C+TIJb!#mE#`0b2aEYSZiSme!l@Po_!xDo<#`}!^;7P)xB-7`i?8*P z?CdU1Bs6|Env978?#IFqN??$f|9Kjn65N^&@)WGmVI~-lD1w@1e`qkqWYLu2NuvhM zgPy*Vg;NGJ<`M;7SwK4GtI=UT!AJT_yfI@3=juRhjiZDIFJ`e<JYd4(?N?-Y4vN!q zs$UJBnzrH)G==+)@8|x8b~hX?ED9|)c>)*pIqR|NDO~P>O-#6uD@6`OS}FyYv!PwB zfm#@~9PYxf1})ZaaQS+IQjoQB1Moa34>RC3&v~vCgVMk*V1zMKmIj{3KAU=6Kn5qd zMYI|~(L4;mirF%v{tJwK7KD<DDC-a@(X^x+rTd>obIeV)p&llk*xpT*Rj6;Ek{Dm* z6DUN_@oIFaf)%@(K_-w!W;~jq=}_C?Sp8TF`af?-qj|W53DDGoh$Mfy!gIlI@EkNW zIcey)(HRrT%gHku<)6VNS1r)-AYLO+qnNl_f*T0!EUigIrB3CqCK|K|*Uq5TxC_mB znJgO(@o#b97PK)S!QM$F$*htT{{(J<EwdeJWT^h@DHw}na~KuP<5JZ+Hbv+~!csp$ z!O-V_0Y5Pmp<*fkB#2K}lXOBc00q@2NxNUL8j^-mupICbJc*I3MoPfQDV>jlbZABs zg0)1ed|b@evp3d@3q>K+2UGj7HCQ|oc6!k~(w?`hLJ;@`I+h@c0Erq~UUiIjXMCsQ zekuMGF#=r&D#ve{I)Mo+qGULk*-`LY`REAGk@d<J(h4)Ne@mFA{=F^$4>1FM()C)_ z*L^zyusByZWS$wOcVFdX*7c6=Zp1RTe0N=#4?mXu*`xU*Ey^tn2FaSRzfN1u-=`^` zjfXKMgSJm~DeDhroDK)S&z{4nw8zYg;e_L9X0{=>Lhz$fM+8oeJcCK4_^CI|A0dZ7 zOi#s^qgsa$S*?scd>tcb?hpwrYdmu!4Wd*u9hm?|Qs?7L;e!md7NxQa@IcI!fCvu# z!@;L-V8|M%2hT-27V#T1QeGU8^Aq#$9W+9~O=okS<OQ`J%x&Clu-}A2?JD_1z6~eV zh)y2lTyW}KHm~_k+W3iEpe{|={3g?Q4jh3u_A<!+ruk#{&f@7?0Fem~Qvo^UNwawW zsD&MG()Ujwp!fv#Sq)XjS=Tk^65WpjieUF{#PF+N`)=N$aKzrmanj}wRU|i{v1ms9 zvA_MyU~e);1&HqjVJxi|vDlumefM*9NJuLTCxw-Ij`O0ts?b*`T@7erRKw_1rwp=| zJwzH~X(N>zDtYm}+;$zuZVU6hNJf3C<<dl(Y~6ttDTWdMXqn)eM_3hFE@KZAci$|R zzv~vwnpPJlVwft_xbTI+v!V<Phb}^%#u&x2()*iH8*ve5?w=4}yjdnc9NwtGGbA<` zxfALOc%&@mDF~qVet7yb>`{c^1A}ePF=6td92F6cZgEy|>)wS<?o*rwmjjR-B>PVP z_n%sT$26q7&egt**NcFduQvy1PcR>C0hLq$`AeC-=rhuntMQCRyjWX**$lzA%NTHc zfH(f~nc3}l5+-MKWNs<q8S#%$OPCHFol^JsC+P&m^%Jaz5Sy+f4~cz#5W@c83b#N# z5Tnoe1X@Fzj}~JlMlP<}&mbsPPEcgb2H|vcke!QwNcUV@r^`U`hfrI_^ok3g03577 zg=ed|I^+mgJsp|9j3ZCjuOxP)+9OYt%&FW~jYgKXcono>#puR|S}=`9MaB)vRT#4x zl4B`+JgN{d>i=Tt%;Tai*Y}T#xzve7t8WR6zZeAf6ILoB11CGfV4jghQ3L6u#K9~R zAsH9Ou)a#mOpG9rIYWTRrnr_ONtP#MNt8v?R8)3QkU@lDmVWPN`o7K|r_<44_<Ww{ zUatGPt{c$^w=)mPrjL8}Pm@%*8RXi0zIwhoUsSCO=ey|X0$zh5>P1|`BG%B9-;y<3 z;ch~Wz%#?g2**_@larix029>J(Mozb?Couc3-*{a!V~A;gfZ4v4v9M60gNQ7?$oMB zMfs4zX9sre7U-r(T`NX4ysfLR*t(H)w5cFKVmWE^x$|n|YfD~$?|-Y@(w`Swnl`+& zVKaokO3C1ib4~wlUOI1Zlj+4YfoA$y727K^6@y(0N%g6s8~f5digh5Vq18>2jOB4p z{h^{_y7tPVB@b@MG9*1s0NktAC|%+LWEpF|yK}n5?8I=Sox3_aJ1cZy`Ka@bNJ6$0 zMaKRei3hNR&ZpZq!11HMD;~S9@4~YyiOxzewc+YmUpcaM>1%-x-o}GdAsTksZE0Hd z%9c}xYN7Y<&P~X?yk^((@?+W>+pUHyj;P^1K<0mjxlP4hV1eJY!%8)CPZ%}aoEzzD zx*9nT`h=<bUA8P!ZInKvgd){H@A4CizX{uS3~_oK@(aV+BTp(-&3&~vrgFJ>eiN=` zuV1E^Ovz<;1g0x1`}tS(Q1Lo}<%fHOt*x4N;@q`aYZey3xWCA8ygErA@gcPpXudh- z#TCCEbV+SuxMCDa##(E9anr2|ndOnV;kgO_e*3gwmtX~Efc;X>KVD3b>gCsyEc$gi z@+_4e-LSdziIp0KZ;I^k!FRg9l21+FgaNaLN1%Eum>ihh{rpO+Eu9gEz;Oc9OZNi3 z#WC<zchBh1er%LK?wxJ#oae+qIyA*Z`E<HPrH=tFm~q?oq*ADUTT+|*i8MMNkDiZ> z4Sjs*EZ>VA+<QRGuzpi&Ev+>6&yv1Ig&#BQr#_!hVLroC)hEb$TF@YbeRRV9v{v%a ziuxHy*6yt~KN<l(${ELDWIps#<Xn~07ajr+8+HFUvcL$@Swd`9;?alZH)i+(s3LJ- zId6%wGSX|5@*?9EsUDRWzbkC~3OT8@HmHO_0poq!GRM@);99DbY#G|V;Zn?V7~cTa z#NdBt+ZxJewSe=EXuaaQsn!)+2>}s6_Z}A7K!)+u)-CbimBUp)bdY59DiLAzDD^@r ze3p%-Ufm*PI(thl`x<@Fr9Jk(I}hq&Uog}{QFp*k;u*yA)>SxTqm?M9KSuo61h}ZW zJj%EB(VqI6Tmi6k(%nsC%&#FtMT$}N)?m_mnn@}+M9`l^^co2SYc9W487#1)0aOi= zR0zkEH9G|NoRW&s)42%Itrlr?Pyrd}VOwOZXHrNtj}PY}308Fd(+EOBsZqKP`9s#& zJIQ>k?Swg<?g1IGY>QIcjuw-T)5nhxPw>!i)iJ4><d_$qLPDW*Iri7P1*Z@$4v644 z@voJ=^}@tp4*DwoYPyS2eN5P@j#NplNH_x?Yu%ZoCAi3vQZTns&jx%Db>vqH&euNB zgj{jXk8Em?80&;*TAO0ATSWXtK^KW3XK&~<(!KkmD&;3>2jc@coqI7lfFFVih4<~_ zU?&HPuql@&y{SW{d6mJWpfN$aI|6G7=)FfadpCSq>n&%Mdax(g+9U)@V}*Ge6}Cs1 zjv8e}yS|9D#myD%wkqYA8~4j&PDa~CzGj-zeA+!*2H0MgpIsLFl7h}*I#O<|l0Yw7 zf_4#HmW|?ANT_{0ttU0a96o31^b4S-w&OYW{}s{U0Ha|KM}jX0{1`$U5GjU25jNND z6u}1AK&BdxX2TtAB!8y!P2_V5QQ@B`5YyRWp1_F1cfW4dfNlymlj@-RkG>X^yfZV> z9=51EuUu0s8q9!pgu2~!Bdp3di;5h+u^<DCYvDIx#(X@caXSX->jWq3yQxLwG+l<* z<lEZ?YHGY9+Cv;q1Ya=XQO50c>a)5WbG*6>FNSIJ=9LYJ4<SqXHR926TshdS*O}EE zQr`|+9iz+Os^A|V^WkstIWxPTSlD%J>On@)RZA;pAHpzjudQ^sqBjSSq(Sn5#wYvB zIdcaSCYNW1B{jNA)@zbKSVQ8u;*u_Za63}+0W!APYq;|NDlY&2%HxvT%YqMz@Kee# zh2NZuu-|nsL;gqp$j80Iu}Fg7wH9)s7iX-Ac8C?C97K>(B1cOhtY{fX>p=y7o+B|! zoDI0RFR9el<0srp_tqTj$D+^h_|ncf0$|&>Uo@UElzifqL{8tG*%p?Ht^^Bm050+0 z%y78h`w~JHfP7zfNs4rU@lc(OXmELNE~hHrWQ0z8SV|}>E1X!{rU<U|MF^M4cmmYP z(x0vJGFno+MgoW4NN}VfWAu<?jdr}b8p?}?+1FM^(qgjGd2lomNL|+d6*|*#hNjFh zb&Q~k5daIfp}_aIv?>QBxY&eBZmZUAP6J_K0SAqcCj)^`mrkgdjIo(0KxT2eW(So( z@Z5BHM4KwXGc)*#KQT{}LX7)9eR6~Py#JG)(DVv`C?cg;!;8}0%faR&(`cLXfM~P! zYjr^&pI0bCdOEyzNXqzMZRknNv?&4eB$oI^LdQ~`W^%tC@VYzCNgpluP_%`5O>NEv z=prUB%>^Fxp`(nSMByUE)YhAP!lWT|8kQ;XB2?>wwABZ5bvxae#4b$>ULH3tcEE*i z8?q1;ScXT`v4%s(3^mC?HHd1&rxu>yT(==+*RT7I|I-$+HBF?DKaTuk`0CQvx&lQ4 zJ29nHcU1^U&&>F)F=5ZE7pLd~EoYiJUbb6r?x_3Xz-v72lZY}b7u`vd*G_e8eg9zN z7ZYy;kW%qQ$b1nL)W$<i>aKWHGJ9J-ChM~ofNCg)Vr){|lShvlsTs#ox6l_;cx_<X zyXC%Y{bg#a-19OfY;6h&T*ni|2B*r$lRH|H>&9}IRu~nQgw%u`0L<&)bBO%P6U$TE zdNN)7AafXj$q_^zc%uA^x3{g5_CI=m`Y$jy-UGDZ`VmU|>j%@@e+X}i#v2?7D{=5! zbyxSh!^-1=$W~30n-mG@Xs;Mmm0;fXWAXZBtADpOgLl;i8D&nrdsp&};pGmbcdVJx zKc((Si-AC!gh|Sthrg8!&%u)C5kg~Jj1pG1=%`C$A|9ohG9+bSQ~h<Nu5k*X#%U3# zcX2;0vq_xk-x!F|j*9w9pZ46W2K{2u7MJTICDF!p!g(EU_+8cr@?DK>{4S_YLO;bR zQiRsba5Sonf+k>ze0Tlvz{lPk+BYegSDf5r`amocIKHub%NRlqbe?R5ugtS@4E&da z+j@VVoPR$d5Hg7Mq_O*_vU!qBN3}WR$Fp~(eHBLp8<&~YX`YXM*unHOFLH~Rv~fB` zhT9jv+O(fig5RM)%5Six_42xBNH6`>MW9bz<-@1p#F=83Ag{FEOmiUe7Q+fkafctn z$Ec@|<8uv`eso~WVf~+N2Aexu0EY|eTOCmWh@%DizGo({cN)7i0ONK(&oqw+T!L(K zZgs(6ok?;U7AduD))>=%Oei)rppq2O%xR`+wdKg6JB1vY!;yxt(^7jTxMI|=wrFMy zpe@3$Cj(9p09kP5ikWN8GRUQT8Yn6QVw_bOMMn#_Gyy1KU{mFWHHF%8lA)V$TTQ^L zw$2Bvf^8pUcA@#8cB5iRR+ZycniP|<SOUkEM0JvaXm5@BRs$J<eya(^CS^>O!xSC1 z4hBIf-z2z!nZP|`nE`IH^<y-pF*tG@7(@m+%oc}5Fpn46BiO}ssR0_T^;Q5Rnw^ri zP??4)X010^4|0FJX}Jt~T-Bf+TVKgm&aM+&eDkBEUNu!#iRW<na4csdoL4ZdAMERq zSYP3Yl|DUokb|CPULbg33<Co#7pU<tUzEXP^@MSSsLxJR5zg<FU)g~a=}@F;-R!pa zUYcCIF0f?bErs!cm7;@A>KG}zB|Q9^su*~LVqZs&q2LmSsN2gyw*ZH3VN;tI;F)Q@ zXbak|Q+1LW;YhW9N`^R+!U?nW2;fQFhE+<EyN?4nlHp{+D4UVoWekREMQ^3qDG_7V zRt!LN^JU!zt0liqCTdA%73le`%Z^%ZGi34<yF``22!jZ8P&GQ(F-@FNWQb60SmBb} z?=@nbfyp3JB>p0vZT8CqZW>h7e_0Sc=h{lc7-GPI2T$tCH7w!@=_7^7)Jpe5_p?SS zES0?Ie$V`7#*?MXtD^?^BU_txKKes>fBtOCo)$eNlnc4@*!EaQJjtQ_pXT`Mqqk~5 z-B>(xyDT;~Hn&!dkCRS?Tl}Z@Xb3}+`rpuv0lO&E$zJA)c&uBW_+{haWx8uN)wR4z z5v(e635AO|YK40{Pr$0Uzv?x0ZD5z_3#|`xlI`}S^Z@otu0}c6{94Z5AkF-`z(?0H zqUiN%ll;GnaQC4&*lVpZ86F>P;@EpycBwn5X=NwYp)NMRrg>*(9FBK*?IvwoX{)v! zId$$AU+0Zx54ngHf<P&*>x_jj#(g_yALRs)=8x~KUvXT%!z0){C-bcrelH1WXj-S! z9;I%~ni*jHzyDR~zcQJLc7d%rME!1Mz#Ho3>|*&^583@W0k3)0Tgtr;TR-hm9<4lK zjU4?fMgFYSW+$v2Lgaas{*$O~I6)&zcKmN(7rzff_TLVzNRAERy|HuV=${T_GGPf9 zxNPf6<d<6^o&YDQ^@{5kX(RUU5PZX?o~}bZ%|$obarB+v^+hax2~`gC1ZoeCHtw3G zkUW#39VoX`+I33Xyb!{XC{4gzmjkYa0WeH$`AX=Wa;y>QfN53wpz-6V2YVpDE4=#M z_U)8d!qm@7gy){HYLuD>BpD$pnv8DutdaAC<Sjgef+7bLn^NXR2pu$q&VVkM-+@p8 zzRg$WeQ={9#6JeSh6A-JVKS&nPfpf%_SGW$Qm-tISGWz2JF4RE&Z)@@ZQdI_T7-Sy zPQyTbP0_P!0y{?FdhCs7?erj84YjeZ@Q!_82k7Y*De3AsJ({OB>JSXF*K!?&V#sph zV15~Hv*wFk#iRFFN=x2wR<y}O98XOoo>PAjaFai9mM_NB1O_q7bgCH0*+mm4^0~TK z-q=a0n4eGlnz{6sngT?d{3Us7Lt1>P?^gj7a{b_u4_@9Ll-#{kQ&(TDc||lt{VmR_ zgr=c2UB4_pW%jgeg${v*_PdXsU8?_FvZuL}y)}aE+daJ{Y0A<4wi}%D?q6ShtH`{{ zaz^@Bcc-q9Tclf(qI%l%TO}`dZ{2t7Kl_ejmziFDW9Z(($p!6{ZksA17JpMbco}Zt zR8%M{!`H-sL_WPXw{OcA>hIq+;;JXk^YmZS3r!y#6;+Kkdea2_Ca#~_Tb<bP^x8(> z0GGJcH<Y;b81cJkNvOqSpckekEwlWsYvEBJT)8ho9Yrl!==+4dNGKs^?B&<-(XS2e zJKv(<1vg)}JS#~hbMj<_Z3XcF$R@l+8(l1lQ+VC^<6o|5Cl?Zf&osV(6^l-0Hif_6 z0vi+2zaU@D7S;7CUNwo>_Fu=}FFma7MbNc6{Fvp{ZxRP!d9X_773%D=%|FZfdI@+X zD<AsW{&kG}C}vOLE`|z!?Gu{ri`IK8TzX7>kOKwPBFt`|iKk#CI?VVNoDS}-zV4DH zc7o^@Gak=rh?NM8{x5F73W=8rmk=bARYIRjcS9GU@_*I>(^2%gd1-Q2gog^>O0N+Q zY3AS}=IU@*G{pzBRuE3}VBVWL;YP##2z<<x0Z*I$W~~6Cgww9~&asvs5rYP!?xHj0 z8j?daLR^A{JKUb*!h^D(wna%3!h;tNq+{ebumy;)wlJGqNaXe<xJ(epitOrgA!0-q zq1oxa+vYbN0Q^v9aQSd44{`R+=>pQq84~|4)I@p~7M+NczhngyEKT;mP)U_;-z=E6 zJ70kJjBg<%@?LQ+AJydus&?z#YGVfy&t@8>GTICJPv{eZMovTWr^Cya9iiiiyAK?k z+1jwbW8}82$0Rq!H(YajkEM3V6&C|N43*)k<ORMa`Y$CiG+6fl%0k7KHL6C;)z5I= z3V<OftPnZ)KR;y`L~$VhGaj5J_?RveD;?8WKES>oP#)MF19d@ap}510qQCBIF^027 zP91iL0-dekxFbMS`l7+2=TyOwhv6WMh_Nvszc*Q<{|WycGYK`V-wPaGLMpJWKGDyP ziVb%{^nwR#;uRAA&uaE?9&r&Bi+bv`%@|vfvdvYW<E>-N-7EGmtq+AoRyd-MghgR; z8XXB%D|m_Ezrl(i=!-;R!I5Qs0(WJRG-qh~B1U8etP8D?&O(XNU&kZO%^D59#UGen zj$l8fj%obzThd+3auhBwy1M@B7Cjkc3T3H}#LDMa?Si2%<X3l6S{wJQFH@HlJwC=p zGZBdc<PGKH+s$)6zN4p5w`fsVVxat6Vo}9&Zt$SCj2W)IRpI*H(9<gE&}N+8`>}9- zVC%J1L`{2dqG@lX$J%FWqF%n=KXg`ss(9g$ICG@J&OaR<eiJJzyG~SrMsYR#W1BJe zx<~ANOJ$pJ(LLq=bjr>e?cSpN8h+NW(!RXC;98q;lc10CE|c3k=v8m-t+_6rHs%x) znq2X^n)BWJKH59RQVxm|U*gg)%`Y&HuHCG?@Z5`OI(e*boPwa!{d|PB<{O_@%Lre? z2Mh%v{Tw-Qfm02FZM_xkQ59SB??{!iDoIVii*zrH+ac6*QfidkhVsUWRr=_#9ru<x z`Tata3HFd?tdR8oLYcQBfwOt}Z*zWFy+Lc0v=sQ=isi=HA%GcE=i`|HF4-|^_0k}x zTef?$**UgGT7rLz;lC$)-D<sezNS7EYD<*MA6HPj3E@KIjL9`kO0X3F$ybJUv1`Z3 z(<@JK`Q`$X`(xXMg}Fsy`C#X3<v$R$gw0KDkk;lr#@3R+VLBe%w(N-?9-qWgP|U!E zlf)06qBkrnj(QoX`*qv#&lmqK_El4t;?+v7QH<DU6ZsCojzH4HI;K(UWzR$kyjN)a zvX%U^x(w`WFQ{3L9_9MD_Wt&MsTr9DqUyHohO+O(%T042?8PZO!V56<rl~(eP|~vB zPS`An+5<pEw~yHsze29Y$ANJ54Gcc}pkmcBg}+n5`sr}0wgk)@=Or#bTzV}-y6DlP zSHi6l@<yr>g<p`vmrXU<KE9>m5Q|HZ7k^3&+FK9$!Brp%jcum<puFCLuss$h1cm=| zo<hNmIRo{oF|cc?y@5dg<01-pb`Zw=b66B<b|xa;KkeumM<V9$z}YlvPEFQGsFFg( zdnBGx{5b7Jd?myGt)!J@*s+OuO9)<DY49xwwRmb&ddPu&DioG@tYB+kjZc@&t<fFC z*9d|jQ%m+Rh$IlcWO<w;is>$NRkJhO!}f8Ae5tW2Ve0sd!>Trf#&2-~^df2um_8II z6DrN9@qA0Ax_!t#LXY`t+rl0)IcCtHN(i+^^7TIdxG8q^1-IF!balNg<!}svZY@<m zH^yJTAA=iH(9g;0mjYX$RS0EE<n8o(Pbwz{jLtg<=>#uJ4w=BMmbCpn{`Y3xIDrpu zy83<t<#y@CM+;`HJIj%Tei%My%V104nb9QsR;;835?&wbvX%&R@8eEy^~I;f{U}ex zQvlv*El9(ql8)j3{%_IUi&IXY)r_09j@PT(G1Rqa#f~RybW0STT3hLgh`iRZcNl=D zDP>rD!GBq%Ovqyu5VTRCXLEu}{|y=;rR|bt*(+Ik<tgaAo(8+3{y{=WSG=*S#6X3M z8|Q&A-7ph*@1QKn-Bn;HEN;^M7=C_p+1CG(WO2YwXkFv7>*B}mO>N-^6W>)$IVV;s zKvfGG=NnpW4!6!Nii4)iNdYH2FoFF8kE;rN8EBVfT|6d12>e$XE}}=kNtsO+E(tDz z7C`5VjKogQ40aT51ldq}Yp5Hz&r3ngn~OHx|I^`P!M{*?lMQ)B`ZN}PNwb~=T&6G* zR$_c_K~(c&y&xz_SJ${HU@U@^hR#8G>!!>;Q*FEgK8U~m3DV~(!F$GxAkx7(3@3sY zRmNZ!qRj{>P}6L3#(4t31#lMk6MGo2mii#yKOLaFDZTCg8SWHv(mMiNYh}Jb&cCg+ zzMzDGaj_ZoR+R%3TWLO4^$L79s(nN-D}$Hq&C}_<B`5NN6MFXgF`N%B1-jfQY{qGd zEy#J-NuVHjIefz~29Pt~Qpvr>(IfX{@`7f)9J(`mdd?v3b*G)p)i^N}7gR?oAPl*H zak>WivJ^YxrqJcHlO)|2N)U=Y7EYR|FPTm{I5XXM-`}27lc$iduxAAPaiN)s=wQAl z8;GwpZFE%%$)xz|i&8H;I&Y-hX910$Y_63dO-yRP&1i5`b5CN}`nmrT`17g|mE?ig zghPA1j%YUe`5dH=gd%>g`XK%dA8)BDfLeH)yO(6#$*l(oLK(K1$+~TISZb{c8ATxS z2+s#D9r}7C`}+POS>$M(g#FN^6nDxtCJ+mDCaVzx<XdW+L<GkGEv9!GWtuf|*{Jf2 z;L0TnVPBj&ynR8z`qeJOC!f<P{{5b3hHqbm`DE5p7da=+0V3D)D&SD8VL%w9UpAft zv&B`QB8Pa|uFIam;nm>kooJ~_#lzY$j^c@|&v#CLg>RB6C2AWW&#nfu;j~ur*eKkx zpkH7;P1!(O4m!d&ywza9nS|ajJJ43^?>GSvgwJ1rvjDYE+w!q68LY1qJ!j-m!-^SR za<`XfF#fTPFW3658~fXO&aG)&YZRM4SJ{rA`|e>>=9pjJ0`>b(>J41D_z=pd?$!tI z$R2gGsmWdxGanQz51)U}iSMyIe|PfV!h<v_cTuQQNgT<sJ@Ypjz^_y^aL`x!{(F1( zdoAoljYv2s`R|uY7~Dy$=7aBszuXb^uq57Kiiv$JIQl!*4QbDBee=bz{)#dC`d|=I zLA^T^b8qSGV}%u?FR=O!aZ+ztfM>>c+!plvl^$;%DSdAHAHFR33tRq9ug#D9P}O<t z(nsp2)h#dm>Ch9t>fTt8q%jtD6~z7N@KmnW97oI-z0U86-#B?Eig3R&Y+l~x@aN90 zlXP{D@A@^cyEu7Cpzj$^QA)gAe*6RRV5EdxPS>Wvl-Bv>f?2pPP41HZ2Rxg3*{B#F z<hu*bPgxwO_}ZL~qu>o}L}SRSE6H?T7yJFu)t%>dG-X8GF52<9NWk!*H`dnJMD21- zS2s=xB1<Rib>x)6A>f@WR_#=JrV?ezUDlfktXratEa@uM-Z(^b0}nnM^xNV4{=nOu z`bAz%u*vE&l^UP7V^>$;|4^*(2!j|<9QO2u%Zk>9&7ruJq>a^*@RYN2bRZelTceH| z&M#?GcsK{Uj)+ss261PsN;bG`>+m9szAkEh;Q`bD9|uJ-G&f7aTC3d!&0aAOmP6|J z8>=05IPa+13N<35ye4bBj$hw)oDzVj+Qs=&1ru2JrO$Hk%h3)R?FYHg>@`wg$on>3 z?iBR;S<{0YG;9`W5$}W>5Y2jsBp6i9SI+U=!~G}R&l$pbh5MSq2uG+@vz4ZHsKdRu za``*DMXmo5Bsnat5-UASxy%D}5=MeZq+1ja8(+cI@#bEu*iC`7uE6UVlT?%WhLi2c z$2YYt1(3Zy^YWshAY4XH5Bh7D6Q+h^dI3%ah^)su>`02&2t$PsE3mz3eeu#y#Jd_r zEG>E#Yq1Z{NYU4X$Xyw@@aN+rX3u(d5<p9JcI%Vo)3>Qma)_q(NFc)0S5C9FrWl@K zsc^Nc_bK{#)*G!2C&P9^Crtg*K|qpAy>xpzMirmx3%_yl`V>8X3@5qbIdf_XQ!A93 ztqwnM^WW4lb%lFZROvCd*4TAqbVrLyTJ+peF+P=<2bbSzC<ERW0U#uxz*o1SVAPU} zM#&&tWZ_xw8m3oB50^NdZ#VT3-U2&D=}Sw6)iOF^hBXNrm+!h*sw?yyzEF7Db#^)p zlWjrd;BNQ+p2NQ7!b=Y?#<<gyC3lY0|H3OD$Yr!3u$caWSLcs)UO-EQR@3|lqj>>l zwjK!of!PqF754%uM6jx-cK?EfAdZchs5kWQs1hW0N)P#pvh7iwVF_?-5mgj_mCwu? z=ZSn20SSX;2#pH|Spox;3Fj1Pg`<&SD4yme*z=3lkT;Ovi|f@&3M2!&l<8}O99SR= z14|sWg&c?n2bI381BytXO&W-&GRD|ORLeN#_fH4H{>$8wkVmRMD~8|#b8I~{*oh&G zb+tf<^-;sZ*_4s`2Mb<X&Ibd^^XV9}oe`wiU~u2t{3gg`zp*n-Rd68%H%Qb_a(Lt* z^yM#ch+P#t1a4XyM!IwYt>4Bw*wGm;?3kusFbE??<;`Uyj4Jh`dH@8hp{mpw448#o z$~yXPaq~y?3C|lUYGF>02}=vx5+sN^)&-c)Fk1x5{*vKUM(8a9_ZdN?0!d`_xXh6! zgpD(!1g_aCF}#*DJ9vV-Gy7nEIer_;*#_5Z@IoJDjg5T>8<%IhFU^G8k3Q0SY{y9T z01t#|xLZV0bf}oVGx6l0v*o)VLPV*cZV1aL@zfO$)+MXl^$Vt)W=<(4cd1^xFm<@> zC<OQ3nV3KDw+mX#=mJ_R7R_WhDl@h77u_|wMYagx-nWw=4h-yGKtXx~`B4PK4f<^X zNinZ<&<8gE<)5gJ3*~Eqom$+YY@cV1`_m!0)bNyrIQdD;&u-E>xB3TtT}P#3HO39Q zdQI9BX0(mA`RNs4Ng0b9CVrT#hN6(co{dBBra_0o2pcKVtZbDakr2~q=M%<2)r0DV zw5Qr;bx?YM#oDLW^?Yd$F4lCFzf_l{%eB2oZ;qI6;8OlbAH8hgog9tKk`ls>Mec_` z1FqgydF#c8_Rq>}!=Ztbknqk`yCzjE;g}$%%7<=PP!jRt9fr64e9XH0?x_m^**y=a zwS>UNB#Y3#dr(GSeZ;cBQT=dN6WVDMgmJ{PH@jPwzN37^Tk1Y!Ia%EK$&d9*f*vli z9eeNbX_6J2FK=yr{p^)?V>@EtB;${hf3nR!cI-;?5BkM|q|>&-Nh{SxHLlhD%<4FB z%C0j%_AGn3Y{b;s2{-Wn8FY<XAiFCu!0o0<O>gmYdT6zlq|B1)#!V4Iyj9YK?i=ly z*4-i&3}TK3NcK`#!;Cc3&t~hk#;rf*E8Om-=A`&m+&0^m8hX@C3IF_I?y(ydZ(ZO( z)Nl--0G|>b`NJN<`&*`MnBVHxC0yA4s`d6UIMtP}sS<7^7OI;nut1uj|L)Y>eT^|D z92cyS>#XIL`$cZ<`|lq`;<GvGj|mhDfh~n!sJ{5^_t`mG+p2m`mMC3~dEA=2=}(7z zgnY5fJ^Q$@m*&@LRy<)43tU)xdOTrPc&)a2*Wjkcaffs&DB}InycPSV-hE?|D*Yeh z^<yDZo2!0sgr@!Fz_T;=V+ffw4j|DQ`7-o9#WKe|wrIujdSRZrCFHVWlkpO4q1&PE ztl%hp^7)Io%#1*#Sv&%nG+-X05e5vL4L#u?6=9m}PF6Otr4?V0bg9;buHs1Y2aE<i z6fO{%NN*VdEHZ?Wo!>&opgqG))$H`h)#ZwPnru}f+k1_aHGk)|*ZS|G2^Fg*zC&<> z;WQEIBM;UCc7Ms&+4N%q2xwzQ(2{>Ue-wXdt1KD6p{>gtQ|JhIk*)!*%#XNdm<-X) zN`_0Fb8J2iCxRIS<{~D-c+$@1Hg@P1rPX?W=D;+<PUH0(UZ)f6Xn_t0@(Iz7#$DKy zE@HAKfPzvGLC2c{TX;im#G{^HNt!OnSgfOR#QnVRCul!yVLJJnHlJ;WGD1elG`ftT zY4$vUQy?O%u#*n-VxpcnlKShw8pX8q6;oS36KWeUDWAROM?c>cV>Q-D9gs`Y&Lzy4 z<RR(y!ZXZEyFD#p6kva(Lei9{c71+iP@v^B5NJ(-Y>UTpBQJ0oa(FtG(~OD`$L$oJ zQKq$`^zp4K`dA{0x3`XI2M0#`T^rn75%NSsD!rq)>!nd+Z&-_#3-MU7_15Mq{IW^i z-#zqI_s!o$E4Xf`@PF<$<dRVuuRf2XX-UOH)z)H~-=J1vMZ()3{Em(Kecu^W0+;b4 zWB1SLYRQ~RP6glRtjwv_W%GGPq_^eE)~lEWQigHUXH8$sYvQRQHx&=s@~D8}P*UU* zZ=3-TCT!E4!DTo4sc9^8u|*LDQ^qxMEtq{0#RURRSmwmI=K<xBx)qDU_x7Mb1?EJ` z^_N%37Iq1MHrcEdh<>PDf*f2eRbX|9V^4Po1`6AEATy!;<%5GrJWT-UyqUc8HMbQ~ zG*S$py?4G~V-riA*m+tSDy{>+Hoh|_vYt?nb_P}v--i7@wAj`o__v8ExUfDif=z$1 z>n0C4%dQ>mv*N9T%b2jYdQ%LmQFb<#GxcUqlrD$^r4om1<jo1h@xp$Qcq^s++FRrg z(U(;&hL(ZrUu$hJI6J9JEKG55i>eipk;J6d0I&p}cskA}>_;#NS8qy0XE}yRdMFU6 z0-WY>ZUmnpZs!y}UA4GQmEgPYSj94>K-08?l1J#@oo0h*xHzkvgWFk7MC<RM5poIQ z8JhNi_zj2&8Vc@e+j)2X&+w{wnJVlJMTfeG_^*7EM@>eoWZ3CU+3<?7Lu4fK{ul=3 zw7J;6>~KS5T?Ig`+bMAci{~&*W<7`oa*<Jmc<qi}+<6o<%)#4*vuGhhZ&Uykf5}yh zANv~Rv{^P=Fuz(fQv<3lPa&8oM6Mjm<LJ;Vm=<djVx6H@2gyL4%sWMDW(_@zRT+Y1 zLJvM+T7(l6ST6AnCk^L800?WTy#RGypa)JU<^^%*YM7uSzKN={ble%}6T;w4lKPh& zoCje}?OQb-%3<kVFr1La9Y&mXK3k_Q(;b4+gE*JvO+(_`wjO*dd9iSNf%`_Qu3YQ; zAvHiuhQDNW;^u1Y`D>5}!HCpdo`g8tk#nzJbEmP@oU39N-Ym<4A~|p~AOMr=9YYon zHC2>bx1rA}rR+SB7nW1C4kFT;y$|(?E$0k19Io~??}y%KQoiTegYIFteRbvLiIVu? zSkGhvb^Eu@>gIvhBhH=FE;R^ppKz}+|4^cDxi*Jf01%5MnD^2k6{#yd!}DuX*=K`I z-M5PxO8!}ObH8iMFXgwo3+O7lf9MPEWfZ{ttAEDlL+?o}N?BvC_14xgDc}W%SPfcJ zJbmNZ|ClQb-Ki!!c?K{@74hV?+^#hdAI%jb;A)@#0-JUDYcb1`KTCMF;OiTyNxik^ zljcriSp1N!CC#CGk0s@RB&O21U3>03jnCd_4~HeLO4rx_rBMQ;el#;|`7BBI^zq|& zpbOe5aY+mNY6Dtd>Q+tilg|iVC+z1U?!(8wZ&#l!VAz)Ldj>lWFSpO4{KR!LSB*QZ zE-IQ}8HfV0s0|Wiu<<-I^wG>QGI<@7^Mczp@HzeyY6rVy&DqL<|J61lm&Zqw5mHZc zUWklyeN4<7^IIU&t7x~f_U~n?NNZI@;ja4U@OXL@<U-IM#B_IP`f7*Il(*`ISPUaA z+0gV0{|A07Zzc_r{RH`67iJ9G<~4$4&HKIb6#iq#*<w9Uw-=rvql66-Y-BbVkbwu{ zt9EdMW_fvG%E$=U?o8)7e1^f6U}e>^XYWJc7Z}h05g335g8&l|MJG^R!6RBFXNf5Y zH}DIPyJE5Uhwsx)Ngghba0Geh225wV^u|vF7wj@fSt4=ryYBG*++o;VlPNK243O?t zj`RuVIg#(RY!qk>9PRxXK;!ba9SfTCCt9QZa>vDrwLFwl!Pu&dYA~E<E!v9Fd%D<a zvo%;O7VGL<IhIfioS#BdQaSBEr^gA+y6!6Dq7Fn+RZFPe-}tGsd<(>`?(m<*N(}B~ z+lp{3R{!wn@O5?3B_`L~tb$wc)eFr-mLHeUz34Yx^K7kHv#akP*Q^WeRNlxLpP+}J z(JGpeR(}ixuU8z!u6X*qCb&x^{3ENcRkPlf3qGUZa!V7VqN4nncV!I$;Eoz1*%{wb zJr;{hSZR%Vu^I4|V7NqCR=r^QIQl?Ajpli=wua~HqHgtaz@)}yBS*ei)GjY`EEZ=t z*{vi9`H_BB2cP};CrC}6{jaIwk#r2l_&ajIUN5IdcdG)srONP!j}}LxTrSTbr!l6- zV}MjMwuJ<h%kTrTqErVjlhJnek^)2+{J;G8Wf1fseyM#8=1^8XNpO+Mdg3qJ;54D9 zj$NF}#H=5o3N&PEtE}2iWrrQ43;Mw^Z3L5S6vT-8fD(!Ft(G(glBg8SQ+dW!h(G9? z;JG`CL8v^KgH<GU>@l2-BN&<xym74Jp;*W=7pL|btkH9At2eMBUW`~&A;?K+rXUbE zq}G}%aX_~sG}~J#)kmQo1oL04Q(xm`bRST>$81lqNU3WDrD_VaBK*ELQDd;+MTWY{ zAGQ@_2{9e<<`Wa7U*Y%BM6;X}86eeqn(b~3XasWX#;e1#Q``W?TNR_PLBu_j#xPqD z;8VS5d3f2H95AO_wI0i0vhoef(&LmU8u`i`J$6Q*ShOAId%@!3L<|Z)yG;7oAT?_S z*+0(1L0+`U#ySu%8Z0*%5ZiiW-dgb^d^^4&fQ)Tn@cU&tXUBRoUQT7ki}G;%9h81{ zPO7M1ZZ&Axq$d`@9*Lhcp+b~P3xuPjTy)>OKfnhMcE`2g<-n+mzb$0xDU6i)VWhK) zkcOx-NLbTSkeP4DPTqhfqV`tf=d0W`iC`X35Db~e3n3y--?kDQ-D~(yho3h8>F`0~ z3Ki_Fen=NQd9uaT@btvb@BFqK$<;Vdkl@Y(Tc6)Kkn*VHY5C~fiHsi?*aamNBuAnm zuDv?P6q{Emc!bu{)>GfVI{yW~NxzHlj{4{=?cG^lfcFJ;%I;1nXZZAqj?>&*t;@3A zEJu3#N~Sxfd|i6U+)?9|pA5eVTv4kJ(mQ>+bqRSNB)n81u-jF>@&d5;sY-K<hr)WM zK$R5r`(NWP3WVM*qbA#)olObEVClg@KiMax^D+iKIUgj=_YQ9y3Y=3`JLmpim{+>Q zBE4or1@=iQ4BZ_A+iONv{Pf(5lHLct7n|_+DlRrWOVdh&s~7#iRl|kwhoCiXl7V`7 zY4{(7znInuqZ8LiNXPo<n3}U6R}Ag41(d7-5&UIM4og}WL&ULd4ga=wOs2<sZ(jQD zpPw~q<$6v|W4(L*IzBmW#m$Q~-yP32cCVH_9f@eJRQj;><}+xTJ)U>{q7V|c?ka!$ zDmN>>V$-Qt)Lp;HT~`Jr2Np&RY`P-nv>k2wN3dW|KU_9a^z>rI3bX{km%8K)vt-rz zf(&`wXXFL$FH{URpt5+=S+1~5nlw`v9BfLnise|urDwqjY*~U^s%-Li7UF(Esw%*w z4*}juW*Nc?z$G0*c86DTj!pn8c^Ifr-4MZMcDn84^`(2btz$mq&d}5Dxs}-#3a-O? z62~|&h;+|dcQ#XtL|o3OwE&&~1KD@7kql4#5RNrbE^R+hZ*sEiHt0!izh97Vxn2-2 zv6wbjajV#-y>kpdHy+mGZ0!JvO~a8lmohP?$P_y@U&3$P*tNh*{GF#S5ZC~$g4yZZ z@1-j||2EX}oWX6ld7(4Wg?*ahr!Ef`QJO%oB;X%_N7$h-GzDu6zC0pC9()LnUgPBv z(*2$LJB|OhcW&6b_=(WY6p=V#!Iou%XZGNYbN1jnA502<!+UoHpD<nNoxT$_v-rHq z;45#B6*YWjTX4vg4<-CJ;E5g7_Qb8uzTQHNS>g6*4(95DW{<4DBV<l&^m}zm{84g2 z?=@`ZeSdt%$<)~vzR1xq*i$Nb3i3u=J(i($$)<npx_2Qd@)5`b@$RBffAz?2UCZ14 zR<i6A2R5Snx3z*E+b=D0`SG5$gu6svjB+g_h}73*5sQ5GrC0wh$UCA3uO}0#g?Uw8 z95Kw8{_7^9yzMyMF08ycXvFmq=^F*zyN17);K+KmuuNyr6mzTyQin2*E6}8dk<Nu^ zz+RY)yr3TT&H<Wcef+BWP92myIweNy{E$_iw)$+I(+cr=vG_?s{Xt9@vDKS*2f8QD z*+zb?efoDO#Evj^9NVHfTx;&&&*Y|uIEn@d`XRF@w{<#BND2x~d;ggJ!Pu4okhkTE z+3paU>2Y9Rv}0e1T!tD|cxoDmku*GWtkDuC2Hylr1)&6E&2<y_tvXNGZqV$_<}^xg zM>_bao5U!6fw&jKIV+6eUg!Qw{|THRbR<_cdAOmjnj`$RL^9YpPNuT+fb$a2n0W{x zY<1AOB+TE?jMp4$IJYi=@hQ_u|0e@s7krtXG~cqPV`Q1|KG5Zw!^M=f7R49Fay>i8 zF%9eK0L@_v>JEg*ah925VFQUGl-=@sxP>UysSXMiQ>z?)K$j2R?VZK5fk}>Y$O39# z+xQ<)6wx(1v-(ZxvI$|eC!2P8yDOx2<h6<od*0~a1SpV3G8HCx4oX>uy|^WgNYxd= z4gC(~yjg$=OM)-hcBZV?y>R3L-a#nOLF2=Ww%|V_r^&XAmc}2)A7HV%te|xSDcl|> zvb)B)GYvOuxip3R1YQ0}Ck6#V1$!ic{<XljmMudnH&IFzGngT#8tndHdHkppcMN;0 zv-Xc+3=yTHNSB9P4t_q9a;uoabFsRwm%0Jdl3OM~a^Z&*Eo7QvpC)~tye-sSb7<FK zx^LEm8(=FmxxQ}D{%fm+yp3rD<vZhr{862<rz~M7>*E*AqeD0O?%`#VwAy?XeGGv5 z-IEt4HVM^FT-h(@d)pE}tA}&dZyqSR=hdt;p6OQ9r@d3UcfsV4?Tgt=x5Y7GbjgJ$ zJABJ&HrjJ_;n>BwkbMf3MF+z+&i?pPZHV^Xvo{TKcuUzb8x_8><TktIc;mHi<t4BN zxId}Wl@B=Ut=}3JE%f{4%ys3x_k+}?L}+9t7W`-<MBR>@Sv-VQ5rtha45ODmaa8L$ zTy-gU(~}2w9Bvq_lfju;+URL?f0+T)nX5a#e8eJx6BKOAZVP|tf6eZn^pW?eX|sEC zM7MfCk<(coEf54jWI|d7Ul4dU;m6+=DDIpRcUQCsNzqXd(*Y=WdF2WFT^PMSeJI(k zzTlgPy6o80#uA}(TxCk%`ec-;J?!nhbf@0TmA@C;1nq&mZ91NYOY*6-9TUDRv@AGT zs<k>R#hk(8Bj(bz0|_z;G^J%XG_0%>6?4wHb*+BC*r@m`F{{gttPjL^d{}w$I;R<E zO8MWYr{8~d&+To>n~`vQ<`uQMr}b&E9Zon=oEX<DN0=-2`Q;g!im&^%21_R`n#^4? zwFiuX@h6I{U=Qz|SegmO*87yE)dv9$^$X@*@wA=*t%1wOlJ~N#<Kx_OstfoPR>lg9 zaq4*q*OQ_#h*;OvRlyd3U<lT?E(c5FSxad<elW|?*tKYYZ^*BDRUzCI@F<I3#EV@O zFb_0RN5lkbz>&BDg9QXq;HD|SPx&oP!M)i#XNsECXt~Ir-^bv|%w}b2ys@Ky8co%> zqbCJ*v&&E2esIJ)*g(|PZPcWAdF?`A;NkfYjFgZI6qT1Y@oj$G;<TzjTkGG?2tSNB z4+-r7*?Qqv67Zphq{#pGyD&^1xFoDK3cxHwo{@XFML%sra=L6KjzwZW#tMIvd;heQ zP=OtY`kloSuD@6#=hEeUw&fX^sv!;A=sp8`<Zt+;Oh2-${JhArhbW*s@|IS*>-J>> zndp3Wo|Z2ORwb~nK7d^kOf29;*WO+pF^aio9Uga#N?iXgfLggLL?s~1omA<=u}YiI zI@YH!qiVr2GvOI^KGuNWm&qiSrEA6F4bEF->yPi;*m1G@y(OiZtHa}1Zp8qvd|-dq zlGcSKpHHZ?rLbA795hT7MxZI`pV64)C3pFXWVvWYb&htsL1ufs$m`fzP^X^mgY{}+ z=rzTRZ%!TAy_DKPsvcyD8#bcSZv2BWR{n3ESW<h)YU#eRF6zgzyhk|PNA)xp>J*_I z4Kme1hm{}`>b_EShRcVF#m>RLeMBMbmqu_Dgd^mY^ff-md`Zml`BeENtL+JEYuJZ- zZ8^&#F->>26Ln`*Le3?kF=OGLhY59$Fx(GO^_k*F$Zk;DS1#K?Rna;@5Y?O!n2>jh z3dImoY$oL97TAX{wRVfQ5ia|Y4d%NsCy>CS!wz*^GaFb8*136#slz-pFzpS=J15$C zr8>2MFSsH}(E-vl+8UbQ5uOi&$5=*c=Rn2Hv7Nc>h^JF6-jj>~2Xq_+qSrJa`mC`` zYtjJ&uZtajZK14M()&29Q?qMI_?b;SFMvI}I6Oq|?+6d-l8=_!sKAryZac!BEL%IC zsr{DHV~F(glO9aJp=k5O?_7AX!twDY3{AhO<37oa0m1+!c>_+4BvKe|{Fjm4-6V;Q z(sikvcE)0!YO{&>)b-;Go=vvXaC;j}0a7-?Z^9o%#S_G`SXa_HsGpj5qo?M|$>;IK zqaFYf^&(|>le}HxP4sVwsw+`Zq9=d^HJeweF4kIyqiz$sBfUn_M2Xjh6K$FaK*W`X z5&Epse6c0JIS<9Fk51t=wN(YUlg{1U1R065&c)Xx??Q-(PoR1<TqJ%~>mL-)x-d~5 z%|tO!%ZL-GC`sU-K~n8Hw2GBbabF8&&LTG4a5u?yl8S#0?+EY|<fdgW-hOef&GSR1 zU>yS{SsexZMSb*U{qtIz=W}AinLc{MdY$5Niolr$>dJ10_f3g*|Flu3{9*YtPwTA& zpW+WA`RGmc@|HIT8iTfIr)?T1)u0aT!XhaB>Pr=dwy>`%5f@q><^1cEIl*pec|<RH z`rzlk_V!<$`^}-#FZyiE6z;7NU5mm8w?v&Sa*OJ*DF-$+F2TXyCB41kcK$M4Z%&H~ zGoeyUYRkk`ZwpuFSGx(MaeCr_*DN8BnjI+0%P>^Bj4F<vn#KzrNZWb;!S<!G2=GBQ z-deperPxzzRrk)|gBlw))wVVo_ipZZa#gb~kUB!V)w75HBhK9!-`bbToaBAWZ>KY) zO~2V8nb@pbn$gMCsSoU)_Qv5;ueL2(Xx-7U8REAsB9*zT5O|T}PIf7eb0hmNF^fOb zuysYw6Gh}~ALV4St68_=BwoXOPfqr5=fCc?dVg^8_kp)o-NE4!_DAcds*KOhJzMFR zl(fH%c4E;KVtdM(3XhWEO5f61#4`OlMi-P=F;)HNr4t2#LCEx?<U`uKzwO?`Cm2#? zmJ@nT*rVt~?Pq1rtM6u_B<&X;w7J4|<cN3MOTn!RI^piKq~;AtS>Ey&oFH{{jo&-e z;mQu;-swTRhC2Hy0v1EBE%oB?+u5?TNdyoOCjJ`5W%BMT(zHe1K@KR`zX=_z7at~C zzCN+2?+5=UOw+~WN?n$-!$GlV0>z_np@^Km=#dz<*d4bT8#cZ%w}u`vjv}$Kfti1? zd}BFFJiNTL3<EMfCdsUGaaN*?17KqaJ)g?Fe;QQ2r;Wj_@;97?&1-SLmxHxgT?7P+ zn2#N-di0PB+)Z91(i9%!uw$f#@NjU(2CpTXhfZ6F47TtN$Htr&iqNlMB=D#g&LnBi zkdU=v2}x39c-BYbrCh^9rufm7zE$vB;{!anQHAF}<RP-!F@)b|xLwf}`s9<`xLp3_ zHnxn+PXGA=U>F0wptV=t*=<S-<wSmx{ga;%NoutCL4Q7i1j>X?szXWmwNs8Ya+1AF z4f<&UcAIawMFW(6zO(kuA*_u^n06rUO){TcNQ=#-+8Se*!)kC>Ii!ukqpq`x)u%P5 zPO4=0qQ_Vs6`x%tyRw#yo__c}S#Pt7t6Xj<%l@xX|7qWJnS0Pt#2N+`Q_P{RP|+j) zsJu7E^6_Ccq6_|Z$@HkXHIr<$FE75V!Zw3w-4TDCoRVSpG(NETvbuziPPp88+^*A( zobGUU?REMIm;kK4R8#vkr>W{x@h>>@0R4QDDT@hze>#9R3sgC6gs)DOY8@6ZA~wlg z98WRa6BRxXL+@ZJ`by%q>D{zS9IN6L=a?^ZxVGan7a1V38}fJnAMvP(*5kyVspJ>@ zKHgN`+xoiyI2XerKN`lR**l$uMIG85Q-TYrBo{YYq$M1p?;%zby))s?UO8b~%_jPB z?%7J%KaXl5qzL{jD|SL5x?Rd0yRdQvQQ2ID*=0L!zJmA42(%TI%G`XhjG*;UPlxCx z#jhoXUEhRajzuX0OUwSXbyTxH+d<Z4w;H&jYVRODd<inIXoi&ou_6p(d`Fp4tw2&& zBQEC+sN!HL69kYcb|;tqfLzs~KsHP^X|kRW{iT3S!$WJKXERLQDFJO{XefGfsPKdv znmz=`F-p->b1#{EB5Nm5+TTvN-SlFC#lD*GYADy$Iv2(2{|K}N8wTOx(jzC!R5Gqx zi8CL_1NnxZXRgY^Q?7irR&?GWWO8Dw-B%q4<F*lfV4hlU%HmnrJ{p^I;Gq(9$#-x! zO1H<UBxU(-0IzUdJbQghvu5%H77@PL_G~~xJmJ28dE(TVtRm&(s(Qg>zA{?*^5WFW z5V=^#%Rr^qYgct|7+|UKOMO(PqFvzWl(Y6;u-}p@4j(MU9b&|c5nD}D>lHh4x-Y)c zk5UDUiP!fQDWMWWU0*<Ff#uK*((;i4W<ojO30xkU^V8N0&8yR9y#ggY5UE$wnxZ`0 zZ$2lJB)e8LmR0``KQ?@=CEk>C(@FBMZ2zmDM-HsL@Xg@$4_bCbZ;jezd&cx)b5o_S z^UBo~k59K~lwga#-POLaj$3Zry7`d3r&8oW)n0{-uTE?@f3C5tc5X|t3h%^lGc7%k zZK2`%aVGPfUxd9Tt;s$qJH9Tzxju%n^=gLep8GLosVzEw!VnTIaqh}>D_r(@^T#zy zR?(mAOZYbX(CPadD(}7ETlIt6VUNM#sy0iCJAo@rE=^f-eX)GWD}5w8RBa64rb)N@ zHF|_kiRg$iKnY3s6zW>K<c~u(>)hI{MWZVy=kp7n3BzKgB19EG;_^_;uk(^za5E5T z74}KVyAMnL`?tBPbYrD^??Z=iWG>q;Ez!FdVVi?P5Xmuci{IH}n)$Ot;UtP_oVTYZ zq8bP3fao-+zFDHTOz!(f@9T+o&gv8o(0OgU_Ni}pY)R*_N=H)6mX+1F9?jF1tufC; zntfJ?{5T#4V7so>VJ{vo-j}iIyf3~-Hk-`*B)fiE{_m)64Ul|I253I`p`W_1;{3Kf z+s!{dD?N+Bus}S5jAx5pc(6`9MA|T$@!ap4YnZJKGSbF2ufnEoKM?0Oe@K}(RCpEh zpM^`P_&OzhSIZvs$fp?-p8fG2aO}|L5M7;3_EI8Y;M?@i`>%e&xU@?57rJ=z8NB-A z;C%7}F#S-)KQ}3<Cx@dWCwz}PBW0BZq_%$Mbx(dO6Nmw1@A#qStgNkq+LC?fYfwZE z`XTX7{R4tIpl`MmG}$ui?RRk%$^*9T$sN_QO!}-UpbP<NMBA0Kq-uVStHWdrCD7Z2 zQS6oK7wP2SL1Y1YdaMCs_0GBO|CIPb+;57B$Vn69aItLwD}Z{}oSoR=<)!%yeMrD- zV@a2bjY<7%ZUdg96e#*s_>Jo0;d&#gFO3ddxt*Bapl0SYw<d2{F#b{T@;4?;BuR$5 zP6~BSCI!~c9gK%|TD<>>VR&aUFe(O6XAgdOy7o>sqz9?y^U=RVOU}OmljU^8LV1XK zw8w;cFRyIaDdAJ^hW^z90CUS-pW_Ju$X%kJrc-?$)ej%dV71z3CKkN=KHJ7ID;O#B z-e+)$UpD6TwX)%vanK=WpFFJI;wwTijEcQ^73MwAK;&<&C>PAUSURdlwJr*&?b)M1 zClyRy_yyH%K6YjU55N2B_J6y?CHhogxy0<D%J{u`K>cpp@xk4Y97H}mbr4}>6AlQb z*i}?H3Sr@(a>3Z4)O8+*ip14<V8)1_D!Kji8D+v!4JZm89QH?18Nuht1gQ<SD6tif z__+6_G2)%PwHpc_lf(NQ1Li>J*FgJTaG}H$jz-0Fo6tpg$WpFTE2+!HIZXd9?k4_E zfz=9Q_3&U$y8^n8o1M0#gd3{x0E<DtWj93<!cRHf6^99jFORvHFWE5MDau1x<v#|1 z9?)2DT9L%*LYV}O;Oj;UV!=L0MVuv(?k{e-JTinm*Mxp|jnEnhUNzmEIJ$gQJR8cg zMiO-uOBe=1Qld2WcjBVj&WP{9LG;0~p{*(zdCyJg9Tu2%fQ!DRy0Nm4#G_88iHk_1 zfT+%T0^{~aCL$lINFOww@L+LO;ym$eqy;Vd1+b|DU>Iiio_<OzwmhllVn3UvaHW6i zA4HKsyC4+bf0@sqU>7P14H_<M3w)iE1#H3MRI;4&^qoBQXb0tctyX?XmeA?>y{l>Q zZq-|uy%~3Iry>^f`f4&RE(=oaMSfeupfR5%)iv4krvZDjh0K7AO&`hQh)3rV$U;%y zSOy&3Qpf|s1&^g}hAvDqsx(2X1RC5=(z3RsHpI#Muh0fk><QxTPO<qJFWAIpV;7`F zb{dEt?+>q$ffUQ1Q4;X_`ta7fythIW6)FLnvl_*Ga<@RNC)@k^rqYt*K?`=qWB{ZP zQdR}?M^goTyZykjF@0<d<hsd$N70nNEtFpr-J<7KiB=3-(T3&z3xPD!qbO}`$C#fV zP<j<_n|HtY-ZrPF6OYH2>*l+c?z*T`$&$|<=wr!|^D8G$8fvMJdYdw%#&m`#ALp7q zhfNe~2?I|U9-ALbbvkvPecdie?^gYqb+|X;cByXRgBidCpdf^+<~d~}{w>RB3E&8_ zS**Kwm-UGS?zopDZ!K#Ip*RL7oH09e^QCnUM;`*I8pF5c)sNXZ^Z)I&u9gipAL&xh zrrK_y7c|8z_e>@f@?6Ag1dIRer6Y0AyE)Y}5HL$OHIB7B|8J7CyXLIo4uHZ*T@k(x z9P--1^pLXBPcQkY$E;L%_RjiC3X%|_9MyRO#n1#HRXI}Eg%$;s1odKFkx61-@wK6A zK{8yYhga)s#Ef}%VZg&GCrF%IH+%)>X>N{r9;_(c^4pO=S7^JU{`SEgzFAV_TIHSh z#Ax?gStW}mB2pVwuPkKMwQp(N+%!dNO25T6;cPOHBST}!?mK%2S<mXR?ZLI(c1_F{ zabPwLXC(91%I#w}TFgiP%=zk!lMA@WOej%mPC?|nl(GeW>Aw1Rwx`#wIF|9+uOSh+ zKo(jn;1AojX6K5-vp&$nZ~kCCt_6PcyT-iTKjW>}`$pg1o#66#FG=~)rQ_?kRI0Sm zwYfGo%bJtd+%*(o)yZnh{|<ERJ1$Rnk#%L<ZIS^;pq5T!w>wRB$(o^<zT-Pa20nOo zqj!(f85i*T#c-9)|2ot9-1iOFz8;<$Pd`{mHsUpz2OK|C8KgR~>WvJ&VES!s;mSnq zzcf8{fd~tCJW?b6Mle0UGa@IWZ{DtA-^jHsk(}$97T&rnF}?qg=G^3_q1Q|_7;Wh7 z=9T2HZF1rI+vT0b*H`pBn*Zvo*OrXC)6c`i|LXHiU1MPWw~EaCW5vCgpQ?YHQ&V2| zwl0vlmryvBtw{7Oz3LtE_hWzaqbuP?XXnq9bLj|axJr5_e*#?N6TNWAYwFMSu(Vlb z7s+Og<YXUd_MVo!r3m)w2d|)>V=V@gcSYcLe>$9h^ALH}w<Bw0;NxJ+q(zeR{-cG8 zGkfRQPW%6RpP<n16=W}4l(wH!WEf04P~hgFa-qSJoXy(r1V?`wc^hGzSJuo)2XYRI zz+dSx8i3CVv8ZY_0~-eweeeX6Kz|%>YIx0g@$x0hKRg|xF3RC<$AzU$sx>7Fz!y3I zhpg3afe;0zRTRjQ3-4~~t6U7Gnjz?RIl9j$xkXF5rxBCAzkZ6sJ+y@%Xgl%=ktOKP zq!6)yB=BQfROTBKuHa1&db($lTyERFINf7R#uCdUrYc03$mKtI3A%Y6Ww;JTK=kt? z`mDoJfszMyoOb3n%%0zoo%^=~Gio&BuYOER;G#A;pNKE9LpulF1J4pWv4-0NwpSFr zH=$Vn<VoR)Wg+cuv6^Hx>8(kt`u!9#)taImZR($Yghs?v0ON*l1lWBep%udiXrRSB z2q5`^o@FN4mPPN!Mv=@BEy2)*d_b?5eku=chJY-VdX4&6w+HtJ!J0RN^d&`lt6&Ac z-~`Hura#5Kz@4G4Ow7v0^oTkDVqmjzkn&7S$s^@5Mik=&A40WQ$A=3uez9&jQ_Mmf z5IRy$A><(0;BRc}`4UzEP>C2K8@m!^Tb2cY#v*SdZ|kFMi}R#C_IM8)PsaD$rylHw z_Y2>~l;)sJcuXz?VpW){R?*+_6J~+%$tA<=uyS$!7s3Q=tx3!I)DC$`k#CjmB8iHN zA0YLM5@t&+{cb@Fw(R4<;%tsBWi<<+)Wt<^ZwXkZ+6U065h_Oxe+z2{qN7wiH#f-Y zv-emk=Us6T_%bvU8Qu;!iU|(v`}8*~u3_~|){~oH1cQy@jLBc4oX`#+-VhvwK)`9h zW6V7ti8^5-RgTUF;!#V&n4V^hL7G}lp?eH%oFMaPif|JE5D*nE8(TXZ*tsklpn;^k z7Beq%Dc&pFYv+hWsE<gsi8p$LI*NHU3k!3FmhdW#F_F6v&ogtCTV}tohbUuHtk3od zCSq7|fiD5rp=3!LaJ4|{uL?(F?9l!*g1s<`>4|?mA|30=fGtp*??EOh!N#ct{dE{} zWF|CJNEq8OS^I{~F6y&*9*Gy0@D4w{_tpe{2Kd{zYWDZIYakel1F{9mZRr77<5hp= zJjjC>MYu&7<Om+y99Z?8BHb$_`9L#Oyfv1hjGW)8kEsPE3c{!OnDT2f5+StCK<iGJ zqENDJ&06R*YH0I=8;5se;Uh)gw8I1YB3X~G)}4pDiB~#qM(y_J@2-51p!JhAop+pY zo^msh{`|*~XA_%?Jzs4&7y4SDB}JBK5cRGubc&%@l&`GoxVqxokB*&zzDjduTmJi_ zvs?=jSe)AR!~a(H6u(z<_S>?44nU-|(0Pq~a>a{+45ltVlDF+G0C5(knpo2)tzQeA ze?g7X<F<T7tKSzNMQYYB>7chd5T;4w{81e8Enl&<#{aO|SJGwC4#zB0taTKV`Ak## zfkO4)V}EbYGqp6aBdav|{fCw23-rgSS1DI^l+lU#6nT8Yv0IpEsl<e&;)eX_w!Bw1 zSG>sbXBU3|+Of?AEtHhvJeC!-9234`jDh2i|L36$BVyoWLx%F3wS(Kzn^_M+2yh{e z39)(ZUPUTnDEm_(L(b!~xX1ev45tipUj3}qE+>}tw(tq92i<pDZzv$OP22t#+5Gfx zftPBJW$wtSK!H#`7gL!v0ryHq{pk=bmp;Vuhs@AYvR-#b5wZJAUUiB~Uxka#H$8Xi z@S@Q;9JzDqv~z5#dgdo-zop;aywcgwDmXL)mkwqvUK9Q7tTzJwz1W#^;brWY+OE2z zOj&K%H76&r#SQ|0wP;7c9rd2o$}eZF)s1V`s7<kBEGJ7+nh(G4bm93VNvUR=qU8r+ zb<=t^!Tnl6$;*Q-kNu*0?+Cg??cAE8;jm|*?nzT2CSinrP_>1HZ(pp?|J`_hj^!+E zn5o?g4%NQq%v#4SA{d;omqX<%6I#21*SG)T&80(>C?fFrH6DHQ?ksk5*KadB-CVDP zP~z8I8TH1{yTdzP*`cE?zxGCP;y?fPPJQjJLA28Bsy|`a|CQyZtG)}=IZEmCAF7;J z%uK!3F$Q0Xm5HTSl|P(!*+LP;gJmV!MZ?4-=k>Q8O4&lWj%XqL6ju!V@N&%l`c9+# zc#3-=8=*@<0fnW*p62TT0W3(5bYtcP*>q%3G_F^OPsSa^+^Hp>>5js6w3C`O;-e*J zHQGB_`;&v2KW8hZ>7z$Gu~o|m%aZU7SAu+hE_s7QuzuFXhxG$wQxOD<U4dbvd`rDF zLA+vorJlo0l;q0Kl$f4ou**1z15r7R{Y3sxGD^GRg8OL3Vs)Ho24IlnXna-&BGhsY zspI8}Rug1?Y=;imdWnC;=hfM{e5@-X*70a27%@+(Iy#<yJ1&&y6fo}viS2c=x^7R` zk!3gokup?ir>4-fx!CvJ)=w`UVVQ)PmGHmK3;uBY4sU~N;FF@g%f(8sb&><EO_~BS z=h>_$6s~?uQ-T;G+sNqfk^q6*6t2%$tG=2Suf84d)-w6ZQdtib?)T}3$MiCxjq!IY zJ_?>OzP-k-<pj@W{;_6VWn1K;t!WdiMR)JxS$qR{uGH8mz}Ir~VEE$=>#;#)gP!n< zRbBo5z{=x0hPvOwTjOH<hzpgrRL{(1B9h<C&Gy;#QlQuhF50S<EldTFLJbN4MF6g; z4XCP@jSxh&)16G*M2AD?a8L~RY`Huk`;`;e1~Y8&Wf!BWjLJmHU>NMTt!gkrhgfWY z;nIF^E;MF`2^Gf$p&Te-E`)t7RLJdU6ddEvZ5Pps$*kIPj029lftGE{)S{2-Ys6g7 zzWf}3XQ$I}jO#dTj)cJ*1=ZYY-Od*fJLiZ@rBXk>w1;;K9{^e|K_y<^wxQs0QgbyQ z#Aa?x>SO2{M}mUVGBA}p#JDknxe&I(R27};_S>$r31l2s?0Y6fdz_WtJ|H!HwjPmE zZ#hh~{pkQxDJd$0cD=}r+X8A=*jH&Cc90Aqu*B}yuZ3W8NL+Y!4)Ji_7Zr#*t+n_9 zZlDu_2lV&=wZ$=iXO%5l($&Ecp!&T^vP-MIQxIEj{{zauKZP3sFqd);`=aYx%xMgt z&9#=@izVfSBbjpgUhL$F6|o_TH*V?-tr=A~XO6H$&SAL>+OWm?$YoRm)gouB(p>=8 z6oBxWENyS4|3p)QctX|L3Q9^U0Cp`?kcm_bGoX~clcf%5ELD|@L17*rkX7dhYa~|j zr3pL%TP;x_iCsq<bJ7G*5gc}+AuR6WIm1l;tS>;`vzOB(+d>Bo(<7z}uHG_c5(fNg zP9C1+BsYYVYR0;o7sJ9{b*y4d?ZfBgsXd2S8N-7IHoxe!?4jh-wU-}kFP~ehQ{MJ9 zG#xpva>s%K*q+~qk+SqdfOi&UldKLZ78L_;vyqL*o!xEt#{A7ENgPrR9nfWcklO+~ zvs^t;i`?{z3&k9Fohc_N3@3dKhFE8}rTwq!Hs2iai&y1)h<qMmAeCCCkHOgYJt{a* z>8!B+N+hy(T~L3XQ@8_x2rJaU&WMlP^}j9<(tq4G>jx7;68SvOjBuf_C3CN0o}yDY zN`wVC^O}V4cNUl)thKYk?U|475;<+Q;FbYasoD1k8|q{WgdTj*WPU<BVZ9ZmqEw(K zV}iAMY$bnG<zj&Sccx);1=bk^6l8q04E2hPxYwf9%C}X!Z06JLUJP;a;1}XP9%Jbj zHlNxdFUV89xBTY&n&4~*8!+uu<y^HOHq^?zGj5!n-XbZ3y2U~<ngQg)<L+p>Z7Y*{ zF^h9ugSZ#lN^~5U_-q14sapM!>!qzbraPTv33B)TJ~yrJrpgutqF<bbk6coLC}_sQ zbF_W4;)8=gcAS3kjzg<<Z*Hr7Mt)*BFXKr1KTcYfwy8Hn0(V(k*Imoq?1W`VXmi&7 zPnq(;7#jIANGLjpY`CnqDnlC9L@)7wu6ScEM!{I+IG_7$Xkp)D*~x&|dz1G(AasU5 z?vxDD>z-S$+as}88gY5SAvc}s%=vHYlg_QJgjaq&(&>K_y1$%fUCYbGV7=t?b1t^J z@T)!<8AS@u>z*7E&&+eLK!n{;g2l&?)rp0_E;Ns8(buVO%Om<e*W61B(<)0ZA5Ivu zT%^ZQ)oT1EpD%vv$4{+?Zak0@5;<AdBjvjXRz14j4A-c+e@4TU<X`@KW22@2Y~cda z;bSIs-{+5aG?Y0>GakDo9n2Fk7lThYE6fB9XG@-iTg3}4UsbmJPUWn(bx(dC*fWzZ zAhptMc*xwm`+nU+YtHJ2?1hpT>#p@y3MT9yU*GT!@eAc^2YbAA?i6YdhJ$k`p!MmY z)rB*m6m4Uj89grAR$$yWHH*?FZc0n7$1`nChW|>?xuQd)Tev%TGK_bl2bNnV9V70J zSKbjIxZQXbVhe5zo9aaeKJh~+Om7~#oHoh(Gqq?Gz`wD0T9@`nI5lN+W0Us?-=r&O z)mD!?or>vIm_VhV5MfO$$t2S|Vn3l^4PD2G-ep%5{g+qK;%Z`{?Epi{1^(~gi(P6b z_6y739zQMJ^I_-+EL&LAM%({c_y~1!&LMhE-PdU=_iHt|dwc5|qKx%}X+Ph^U<Zd3 zn=wlyhe<MQXxxU?{G5aDZ1Dcf%>b$8O5Cm*4j9sLpSPC;2fHp==BT!-csyqL`8ezv zn%0Ly<H>^QN1nK}*OqnlWKtA?ypgd-`j<I?EHl14bxN1W%g$p*+Yy7r^49(oItb;Q zUbZhEfulzoJfqPvSDI>BAmA6iR#FrpN1xCdYNInQEi#woeMh5f4@t9TD3{{FJI8k2 zlpu(poPzX{yb2sly8Q2g6HlmYuLWUNgN)6kbq)B6e)UU62#jo5J2!}pLPWfSNQp-L zyb0(z`^kZN@Z_@^pCV?Y-0&dX{J|?yVmVBq^eIgD14Vj>ui(P7&}btOxKO`_QU+Ir zQH=M}Dx1loFmj+PZp0OMxT-|f3l~kKf9OCnL4k~N;rQu4@mE_!A6#1)?=hZz)YPdB zPLR%_UhkYZn078E!~FkQ`tE?HukL+RtXf-9Twf~?E1@ifx8Q;TkqQlo(g=be0(q?< z#YI_S5Qs(VtciqGq!MH!2r8h0l)PALWK?83Sjq-vgc&mWdv5yst5zZ7bMHO(oaa2x zbIQ)3IWBQoNp9K!0>-wW4aWr`@>Xs-3Hy%*)D(TVUoGrl%8R{0Na{Ky{G~3T0>Fl3 z+hZTa4@1rw$TR$Rs$<5BSYL?|ep_+@Xaj*ItRsem?$(H&_z07L`Fif8aRz43(x50Z z&B7Hu1zIf!Uo{S5NXSt45oHb9NEo>A@5I!sAP9|n#jF%;x5}Lw*f*j2Lg<7rABI#` z|5l~y0{B4gb%fAG1;p6u%O_Mivnl;HyeTTs*Fe>VEc6AIOYZ$Z21Y`EQ-o7h^J%n& zP57ZhlXZx@!v>&v&=MVxe<^Rc5+*(3DQT5|y$uWRhF;hR^dT8hz7W%siu*E57eay; z{t4WJjwdKD^MjC@ukdxUe*{^Kjvp~;$O8LIlL5CBNPh|J38p8Q$0*Nw=S_V!-lXIr zB;A%cRWG2m?86<Ry#fsEg%IV~1va?cs{)QP1z8V8gjRBEGi7lx_wKB-7)hsmR$ga@ z#|J6p4-ME5-=8Bk;`o%<8OmMwPy96NJSaY2EFrf1B$uaa2iJa%Ibpc)i;xzY-GTZK zTm-_Lx#{-k`ZHX@_-koDL;D@@cz~A1JlBmC=0Es%M_b_XBtvKm0mV1Nz5>*XF(*B8 z(J^E=3I)Qb)acXHpRFDOmXrdCoxVQeX1odQasVtyQeFrgaBG1#{>CM+4G(G)GEF!k z<8ND>Y9F7i+8lwm1vqAOAyYpFa}ny4rAkTR*RPTRB?;%MtIH}TOhg<l;3bodqs`fM zeH+gsbF-?xrH^VI=30`5l2pNBIsCQ=DJSF9JrcBad6sR0Uj=md&Ea2g{dS|UC-adH zmX!!J%%4wKJ>}1$v#7&{@u%)<a@E56ai@B424$E+*8MFr0uG8KU)*d6;00V)6AQ@T zHW3#xH#9mBVB(#3YzGZ}gf{0#<N&xgMR8Sf5mHOkk{oTi;dUdohZqxf(6a!aa=&8} zp|dM@37G9E+a(0mr^Y8oVrmF@2r8sTGSF)v{qwzE{;3KoEKWcqg^Rv%0_uPfr4hY% z7Rm%4(ymH~f7<F_XL_1HJH)(l374`u^6c`o#90Fard2fp@#_X$80xQBW>*a37G7*B zSp~`sm274NHCtP)_#xrqs4YY6WucekrB*T=W{fK$Yk-LllJI*N3lq1yW5Hzq|7^?~ z%DI_eWgY_YestzKx5h43F7|4<cDpLG9ZiiHWCuLae}JIxZ7E-nBeqEnqf#asz<imS zX?-HR`iAxNZxf3yNf#1Z9*M~Z`nW=q(mNkIV}5_1H0hljy6DoKh|7pOZu;*v=GUzX zuKI!#lPxdiE4+LUyqG&77J{By(NONMH_f-s2qLtd10J6Jf}U5i-Q5pA{N>+m%$c%Y zL%V;BCTRd09baL(dN$8<tQ{o3m@t3q45Xo2#0isw8i1*|&>UegontlIrRu3@bGX-( zYiEy%6ABfXS(Ra7;LFEirVg#SIe7hdo^OTmO3#?8J#gfoWM2_}x;5ZpS<iIhPYi+{ zTA=Cv2j@e~hrDg;s3FM+zzpU6-;m-CsA1s@K(isI9zV$BjyZ#TpyEW*W>uo?Ay`Nx zFYVhmv;|)WEw<?w(b4=Vq_7CvU|PS^Mv1+u4y?2fS^Ihfn8<>=XezF53OhYrz(nU= zSbiHPfSUVbYH9{{LkNSOh_S5m{Be{i2ulWEz3U@J><rzU0fU%rP?++Vz7(<R565jT z8>C&oU=8TM%y8M$68JJq)^*>$hky}A)cOXUdluExlkCAUn*iWQhkF$BX&bbuh*==Z z2*84k^E5FXZ`fxzrMFbR8ig~_F){Bh9`b;P_K=$ID&Xl?Kocb@MGG5+j+ferAEW#d zzp8GJ=Avpkx_=Fy*p6^#Mjo8-`IqT{WZPOdRl{RUIBKN<OGQ9ixH&^%nW+3-ms}Q# zqC%%JbpfMmcoyADG2yxJ<){|QU(C@=I2a;VfDW+RG{@1=5cZ_p`{^;*X)F@3L;UYY zVFrt8>?Q2}L++da(nMT()FwvFYX#{sNF16{SPJu8g!TAOb{Pd=h&k2~IX%vT0V+D= zIY8L+a^!U;834#&%A=}wZmJ==YcEG|u*RrIQYVmB>0_i1DjF|AGX`&B00ubNigm6K zo#$$v)rX*E1}W7L1YCTDoe;WKLN|25#>|MVA-r1oWej_z?<5v=j-b60lVeNt(uqJX zD}<QNK@?*>$s&{IrJ78FqKuq10((MCON7Y)@^~Xr;?6bQvbZW-1O-sD0k93{#G%H< z2R}<@%Ymm`bbDMW!I1+q3i%?Sc6^D=Mg|1h+muY~7vW})zzP7Jgfr{|C9Dk+@i^f@ z$1*v)0r|ZF5A~xHG7D(ul&@c^6S64u+RwYQ(8O01Wn+mp8_W}6z9=>>8fb&DPKc6c z7x!mZ0m*B$^qG)Ps$ujKC=a-Rz^|p5Ku3zy6pmx8uXS_4f`(HgL7lUp^(1+MSz>>N zWRTl?Qw=+gzE2v1Vx}yb6iuXS4hmh13xEhqUn<g!v!BO7)JUjcRKec)9GEYYk_+}z z0%(U|QT;zWDr@k+{9wxlr$#bfuy%owsYyNqduo7did(^T9$Vo>!Mr3M%?zq?q^ryn zCwD780PA`r!pvLOaxokRpY!42MM+kOt2GSc4c6zn0?u}~m{OYxyJA0JYvo~I^k+tH zK6b1J$%&`v>}1Ylp~frQg`&jXN?e`QAMnsYKSgHOYSsBi?QyeK#|e2|Ta*NVGGr-v zL7>ExZUFRSpFj9{J}_RO9AAL#_yTp;1Qj2bL-GTzp5I~PxRFID17cbt5)8NSu`3D9 zoA+SE>W>aE2FZotZOp!bI$c5y{r%QDX1n9B#&`aYgfTpt11|c-0*xt6^vxzHaQ?Or zrNm<INF3^MDJpm6$jcpjtNz$d=4RHt`t!jr!RAZ4E8uz<i0$RE-|x4m)_xJZzVKPV zN$&6jKY>1hcvmA)_5kLrz6Hi{ln<Uqe&&ZSW_=IISh`C_tc0Z0AxAj|0FI(KZLP#d zid}oaV;@*kRA3uuMOS5r;LAPK`G9ZtXPZ$~XdmD)<ZYNXTZW^Fc!>Nx&eNkUK-m-E zVxrSsEA773(mQ)S=+xGaK7erW{qU8;v{~vYb_8X@%Tq8E#$XD&odW;>@b`<t$UIbH zZV-_B^>L@m3Xd&&KOMALiXSh&h6Y%_{-|NB7*AtDDNFmNa0;6d;%oUu#+P`g!l7Zh z32TFS28?a#E-Ji$<I#YNQblcPwfw8u2OBSl1BNObG}kVr(B#Yt-tg04<pjwv#>={U z?i8-&K+><IgSAnIB(G&td}lT95PW@^)Y}_)R}#{))Qe-90;`<yvQdz!P8crh32`Y| z4S#-ncgbK}Rq1MmR$R%dkn^nnEBtPZ{nvWYB8K|h@f5ppGVWaLeFDz9RlQBjPtPP$ z!VXVzySQTO?e8DNPlJk|hXz_SYbpToMz@e%GO^hY<g{93ajm_qXt^)<-R7W1=X<d} zV+cfwMYHS1V;yI6vp3rI9UR(Am&q6?O<P$ecOMqLx=c?#+%d^r&FDdEiVPA>H*(zl zC++QZ&Z+AdAI46I5zDH3Ggu}p6Ag6f>xVPP!mbufS_fmQ_b9qI7-{MHds{wsEhWOT zF~Td;Yq0F^G!_JN1e|ck6CBnp{ME)Zsuts|PiB*r_CIQPn*)7xN?T#m?wn0luA$SM zZr&1XXuO#x{gQk&NCMc>03Tis{w0b3f~VhoXF6H$S7dWl+AgozQStyq(q!j4x?ab% zg#}lmgi$*%O=D`D{i_XSsAFkUMsZU<wU`LQI`)gdjd-gS5lW4d>Sl357DhWDif4yo z0LxxLmPybf!;G(5O_0PAFn!fl#Z>LKSF;h`2Lh%dH@RaR6E*Eh_};bakUPA!gkM|| z>`n<04aNnwy9`lHWoGb4U!uQ0=eJ9gL{|i7rkX%mHG`r)4lMIeHDKM2Ba~}ZjY8q8 z9*WqWRs#!HSO&Q4oiiY6PuW9W{N;NaX@s+l0u(mWPKTDtfx%aEp`N2B+FuMrGDJrn zZ;-q67aOpCaCP7A)#Rl32pD^yUeR9Vo~(h6r0VuNVE{HR9<VhYe@YxU>6V8Mae4f? zLA;W!Eq!DV|I?lMUkZ*e+zB|}!u$Zlk^Y+w>f9*4Swb4fPj?rCKw$Y0BfDI9xUD?) ze)8ZVD7>)fXovCnu<=ql(762{G+pKmbuR0kkXt|-hH@McDEVjrRTEV$$2(@MgGKwZ zEKy;O%Ygg1(5g()ro^nK5!AGOu44CBO@-S>VU@rhH9p8B8eqw=(QvKc)0T#Gl?FPl zV9^Q?hWJqRf{fJXjMi)H29=jIx%G%nmJetE4@>;7*aW>33<Ya%0)?I1NY56#{&x*S z{)Y;=9KPu`VI+Qo=i!FSo2366%t%QGfd|6LE)?fk;5Cubdju5++AOoWTqszV;~{Q> z@-CNp5p-Z!LGK&UMbCjeS;<g2!Xj!C2&c?(x)WXD4+v$RrUgyr3pl#SS@k@^VXjbB zK@38f<jrwd(PG9)!EH#VRN>VT;|TwP$4Vi^Nmi&S3Hfe2!7^5Y6An00s3ol2!?T3S z3S@(wnhXf~!TBcrKt(a8OJBxt?@^_U*dLnkNz??R4boE;oIel88Pfb9#(pHcjW(yD zbdrmCv>B2w;7e>q$><Mw8MiG3cfd{%UV>bd>_lzbKrq(fj08&Rz<dly_#K@YeAisC z4T2c=v*Xl}zBE0i@*pcg0yq%L_8SGrT}>Y7Ud=F-Dj1@F?$97Eg6NYp1<Lhw;7fIu zd@iWrW%z9pKtEjqE@?W!XX_B@hi`(_P<AEzw<X-@1kAQYm_MMWh5KG8U6wB3+Azrv z!zoxpkc0$*7<0djQwzvNk{QB%i+lde5N9Va2=HC2NInl+3+&ZMtyJQ+0g8K+1T4)s zhE?cJxV~Zo5Mp9}I#Rpr-xkac-<@T54a$Arf86$DaSw*x)TV$&_gXu6E-Lw}%t)=} zwkWBwO5KHbDn65&o_k{H5*EY}zS)=kFYVwa{W;sP$^A{0){1Ogq<-KJl&EXM@d`~z z|H{LZ7-B1c(8m4XYVpwz$uwrqy>%ECD8y@PZMTn#nt_We?Q-gU6n%AOpdv&~U@JU` zX?}#ZGtQpNzysgwV*MBj2=^&8GYfF;=0JA?4Zjv}BeJ_qss{1LO!F_PDHh!lT*`=0 zn`xzct%6v+;v(Qzx&0U?It4bQYDcT~+@^tTW}yb%Wvq=34Gu)D<aEOtIYwhGC@QX_ zG*AOcsgIEj{Egq_bOTmE8jYX(c=K4bZ8DV$0N<^TTe_EVOgmplOInZ8%b0n(V+ktb zK~xC}-y_H|K}f(JQM&x>J%nE+?E~<~CNN=<C_wNTVUp&gNJm38QHJG-@^uGxgRGS! z4fRZ=>-`!G2?9!6h(~WeyEu*Z@IPwThrO{`&<j@?@*dL%KTp-|t})u1xXasLtLfDC zpIG|RPNzC}UmO$xAVho=pq+pdGY;k^@|AY_{Rg!bhf@T~Z81HsDT-p{r~M_@JialY zJ`y-yijl^@Jn9jUgoXe=f*Vwx{=OvtM#L%ftQ>l<B?*r7Ap4_5>4}k;kr}HzPvOVb z#wvx>=;D|Qe^24wUQkfsuW%VWNS-B1Iy&%J3&vfrg@{cN_``sd_FjhM6YL_?rn;%8 z)?88j__sY#zB-t!Gs1`Al~%m%PnZv2c<Dj>s|d64zr;VwU9*lll_ziZBaYCtQ>ZB$ z9$gwb-SgVXU}8<w?{ezw;JeYQ%Ngn`73ZA6o6_WJhX>4E?nd6!N>W9uGI{LSKWdju zCchaN`KT|^N7Sk<EVfysY*~KvZso1hFJNoBL;lD#9pt3Tp5;7srj@v9x-5VCp*I%~ zxsf>;u<UfhleyLpiAwfw2&z4Wo7*Xg+U*%J?XMVUPauv$c9LbQEU@SztL_1(k3d0! zc)Q{2*`oiAvFUosWbbdf|55v8&h*-r*PFH;LnA}#M@y7FB`tpM+;?@W;qC7^)gZnF z8)@rN%BZpP;SpgXcP;n`kq6&>2x7lsD6$V>zmo`h8kcwZl8;n|&FSIk-G6z1CUl(G zAW_yYj1Y~VnRcv?U>vjVyqJED(Ijet=&vZe;P8EO=eF7PHE7uM-~4Xs&FRK>FYa{x z!93&0T(SX9WPZfKg<tj%8VG}2y%kL|Ly%`z5pc#~Aaw!yMR^E7tEv}MD2evOn+AQs zWly6pU6q(@d3?IWFm4WV3sn5@Eyhd=kinU{0x+_sAd(@MI$#~tYig;B@CWmLWCIur zfq4*c_aMR8s6ai+7pFhO>4)R1=6nL{<*S~&vkPo;HFCb|839@x5|Rp7J#PBaAblpp z<t%D2LSxf(ay`^W&DuMuXLina6&mclYO6{2F&!i#(u)jixT_wjKUZaB$?k#z4AZz# z(%Un7>wnTsOGGQQ0j2M2`~QJ`fG?-xyJo?`T@c-PeYOHBhtbyU?_g3V+uC4@rOjQ? ztXx<1kDBINk%@*mB9xd`H!}QlQ^tg82B}io<)#AK-A)JrP2ppu_tTBS#OYD_W$gpG z&SALSi*b6ebi+(>KTCf3Ks{-vS&8HqJ@(tMkum+W!v#NpQEx!%@CR2_c|8`8_RJ26 z51Cps3HSCC_NbxqAnBbZVc&?_@oBh5J3()YBg)tE&fX?X&KV;IeE~p)of?m#EsSU; z31IZ9f&>VML_!v}Q$vUz)`TI9pGh(S8CNc>v!Iq7z!)xobny$CB*=6cnW{lDsEo{* zr1_l^VvXi9aGFz-WFz>X_$E%gV3nEAoG~gFf?!WzB*ZJyF3+{VZxCq}B(b(Vf9r#w zHHr=}L6x)_{ZiEQP%(-VB~WPmn-&<T!Bh+;ntWWXh=&An0tEq`=$)VO98u5_n;cAT z$&a@J?O`!ASZQz_aApt|BKa75x^oa<iR3wn3jZ^FO{iT_j836#moA{C5aI@>nL`3# za}y>YW6~-*1oKdp19TE1$tN0I9Y2K(RQahR>AZ|iyBJ)|mTEfb_!XoJ;0NJy9hh%N z{5xr3bVU(9w=)__m^!?gAm&~UN}qUr)iUo~-LRuO*9zDG<j*<)7>MU8&>;+bt^=2h z1wGlhNO=5I-KEWyp{0R{j(4C!x(I=qJ?_wI;_43$4%+E+2$}-y(bR=G>9K$Xlz#GM z>AbUmz6sSK$i;ONBwN>4fH{C{2nOLhX2c#plfi{#QkX;6gl<lw!WZ%KvvO_ytL3&@ zD=>GD6yGpK;!2klC6=w2;kzhOl<PP#H;*bc=H6+6GGt~s$9&NOj2ql~@mSwQo%mzw zKcSBS!w&p%beTH_ZQwE$N;OL}jca~evLV_5uSw_xeR{0hz=;!O$U7%qTq5=y`0C1n zdp`Fb$2to}c8l8a&oNq2-gPp6CAYcdR5{1}irbq#e0?Et^82A^#PqWu&PwTJEyCU_ zxTx?dOu{zuhqRp5okQi<;cyUwLLc4p{`rcUdk?=(p3Z?Ne(nz?rVfk}aznQeJx}?B zQNpc^kFk(N<s+|5@!EH8?<0(rCTXPq7yD0sPt)A;P;z6GdUz&u{~Ti_DQX*;4pXM& zWV_*u*5Mvfa(gpfQ-)C!2aCa|6e<2u12y!q;ai`{4bixdp`>p?ri5&aB({uhFz{PA zg5$SWg21jy0zzV{S=N6N|KutdHVRyqUbaIG0mse}CfoEmpBMmwMbH$)%~APufB`UU z=ryy<8FrgMZ_t$+#bh@EGQd0<$cmp9=yocTyv-mS_g1N({FL~U7O<vZX!|$;c)`RS zjHiH#K}jd03CXrLqnU#Eg;=qtC%cX^0;vO%{ubxb!)S>7qxQ-bH!3l9>BU^V_Zaj? zj68AGgR5Vs5KYLceb#MXK(Qit9C&`uPB-p~mN^RRAc4h_D|_PG+p)Rd3@40J<k1D> z+~GycSTeue_V>5gcnf<3=^z#~KOUWuxZ)B}w5A1lq7RTwp0*z`<rVB(x&jtZKycxQ zx_QH+6tB(T{=Z0wzEoa@+7H&}O%p4FJgzW_{R~F@NJDLdEDf^u?w!MZv*aG2!(83l zFh$miTP(!G6osB#+8@nKXAujTzl7h)KT~9t6kZ6A3#_tA4BrG7trjpEI?=UZAD=aS zzb$tBlNPb_*i`4JK98Ya(uvy`Ix9j&kZ1D3hpaTlmwJrpl=|oSZx8bDs{BWd-*Qsu z@<D8RT5$+R7h)z9<m`K8LdRI{NcU-S49cXB-!1ycNu6!e%f706?%O6&lim!5)gZ~w zR>%u)wY<03z@LdJ*F^L{Z{p*yjbCeU%HDe&uV$}Uf2&c1Dh5ur9t_v5b@MB?7QXpt z!!?I%V8N~$fkp=!GG5CrzRv|RkdP9Ay9`3YJ0^!7h~wqo&9XCQ8=g6C_qfZ$d2FGF zf^f~6z_Gl{UMK%i5g!_`FcM3|V0}EX1|NJJB>?(H+EFRnZXSAnjN2{^Y;#-rp0>Cy z3%uSQ%n&KOc-X<kuRDG^UN4`t6SPo|<s2`3DZ1Kuf8=WSVtt`K@AI|J*goyqBOMiH z<KicOgjHI`P0z)jpH9Y(pYrVFG_J|K_rE{PYx06CshX|~-P`|1M%SP~!GGYdX`sZ| zr5Z51c@{Jd$Z;&PubhCm!1?+Xjfa8>^fZv)wUEodoZsZS8IdmaER=i1TxHRJQ9dKS zT6!4euhnGg%HoP$;_U5BXFy1Bu)0KcD13BW-IG@jf{^SY!2lWDY7ARvPX~b~W8-(% zse;I-vdcIcgNB%jfn6W!^GZ{=hZ$-7%M<=oV58w=^t;}AJ+uwD`59{$13ADP1%t!& zT5(cC;bR^%@2nGCwBi044N3WU1APy=4TP3YiaDx)4{TV{lY=HY2KUIy&{%-c+5hO; zt3;Iq^G@sX9|+=Rx-sKxehlJfyD{b?Ke7f{HGV^Q;*%t5^!m}ceiT!G9j)*T+lOId zKwCjDCZ=IUvu=I1TO{A%lFBRCg?N1Z&Od5!$D{~>ScV3^Z2CJ^VSmg+3Q;w(-rKa{ z&CYk;AcTN5zf(&+5Ka{_VsgVZ63X*Klu{UTs6Ji~0ct1>(E+~bM4Q!*Pzbuj&j#eK z+eJ{h{M(N-ut3dK^ie8YQgtUlj3LrG8;v<c!|R`SegIL^rhX58!7hjcssU(dcug$< zfOyE~;6)7AJplTPyYVV5F5Eej3}oxTGD+b|S`U+ci74`W8|Brw?US6Kv;&(ACkK@h zf|Vy`Nsv*86ug9n2?GT=ZaE7~41xhK;vOtFI^eZ4fYGl==AUEvF}emH8quZ(+&eUx zc}x{3=eBc!G>VHa+T3(zaJ&)G)`n(Ih6&;m&eIdwWn;|J9>RP=wWP0*<Gv+{lKi9q zVY`NBfjk9E3V|MJT#(?uS@#xstsvFBjgL&^{{)ytV$f*^+Lsg^O#Kn?wV>dDp)m&4 z$aCd<!ahsSvYo-$0}~+nSi+&tVKPFhySZw99hADdcoS?01AHrR*&8D<nszdW9Bix! zMyvT^w|MsC!W%%@m^yFBsHlTXiDs(B)`Et}o<p#tk2K&6gh5w;j?E&NC_{yeRvlEb zXy@!)iP1|C;S*4gXMy*E0|4^1z3PIfIi||FBQG-p9d_Z^{+$#w>{j9p@57n-&Q7pG z;m+V0ihDWq&O3z;cRAbE-+z(N3R4nae&X{JY2nl{=Q_Ire(ruLr!8#59PqW+bNj>2 z()><Oa=JuK<&R6zZ%RZbWcmcnQMUSy=(iL$jACmndvcv5k~FEKwh1(xsJnjy$>2`% znUF_3nqsYcg^v&u%<);dkMq_bDCX;K-TeF>HBs|z6%IGV2V0w;aw~BUl8jvaIGmMW z!t=3lJB5tBoAa-TyJM2B>43EYi{}Pmg8*pY+X;}kV#+)4AV2*idJ-(g!M;q|S8Y~~ zJb1@Y#&oU~gc(HuiUJ!fXdgk$yq#E|v9gLvAit#gYWCMZZ~gT_QPey6(^$n1`w1Mh zgA7QzGuT7G{%(92f$O^NbIu6+V$98Mter64Zr?boci8*n32dceIy_y#qbKlH!kIz{ z0AQ(&et}=oj8Xj5755Az23(95b4eI-2mOJ82apw5|IzpF8Yg#Moq+Riq`0tgSwdcw zmtVDks9^hH2T+1ti_%MmvB0^U>mcVq4ll(G8sDtFt*Q1FdM-+dssmWMAE^K#$;31d zemn&sEy-74$#?EKa1V61@O}GMz%c_aOiWH9V#J?O0O+J3TM=TmE6MSOf9F=(T_@U( z0?QYy<RB??B1%S132CPE<Z8ZO#B&sUr}V^F?zjkiET~4?xRQoca#Z-W7$r|ok8h4| zOwOMB16~G2AP|d6J?T%6jozI_`#_Zpjts*Q8+tUUpErB_3PZOZt_x7vkgCc-EDTKf zJQU)txk7npc4Q`FVIg>hn}*G2hadjdzfMob3yo=W@LRUQ;p)njv!!IAo$3)RmI|7@ z$t*of4|RJzGa)rjRB7u2F%VB^7pDeN@SGu+7kyH1MZMmtg*7_9Hngc|m_>r}muf;8 z8XVk{UYnXWxwZj>pW)Za)yhU2gW2G~`xf0z#hp_BW0A7w!+#!zbMz2rB^ZN+7epoc z=jB|jH7OC{-)EwSQBnr=8_1=cUc@)6;nuDSA_O2~wd6lX&pG%^7`G^Ol=U43W0B3- zbL_VtH(;sPf`}Fxmwuu|H%_tbUQ<T&X|j9gevEHDFnhzAN!vIA1mXrKbYk=gpXagm zX}i%9-N(Gonb`T<V+aP!$>$_hBPBqVS>Jzh9g{mYjO7P$Gi+g((^y-$b=)m_vU9C} z(W|2^ORO}p05QsO<Cpmnj%aTMsqi_szWv4Ft{3t&l1RJn-gesdDD$YQ@WcxdGR3D$ zwpwo=#VmW-Q<cnEDDz`)>GV%rvrif<?)@X``LP@7(`Lj0Sh1z>_lhl1e|u;=H8n$O z5^b&T0fVeIE;YDH$({7|UmNi2z%~2Lb#<_G^9_sIG3$Hhw5fASqjRxfi7v7vHwdYw z8ggD1?vV_RDhrZSmfNssi>sbriJh@$h~Uo8<5odTK!~}$*`2_W(FJCLJP3=C1dM6| z{zN6?Y4$okfyWt~%+xof_);Nhcl8WgVt_clr_=uHMPp8gj>4%ImwKS{k{9J@R~ldp z#!Tp;|EBTHA<W(B?z@BqOBv%h`b5)sy*4hf`u}Q}{f258r@(%#n)1_#kh-ZrTt{iY zY2dHy&^*U)rdgiV%gIU0hgs8Qn_kMW;bmn({8?ZtV5wh*ZWCN7G??1}1OK*m^0fSM zq0CQKJ$QJ6CQ=rZexxXAq(J59g?x=h?^$c(cgH34Kr0;J;!cuFNVJ1fjQF*!CM5Zk z7bz_Vl&k9W-*&*62M+%@&vSmB{a4HDW*zVooq0d!CZl{7K&+pScK~3ScN;|G+PpPi zORq<b;y4$?yj(;S5vmK7kK`A&BbRz622R5w(Zjj)IzjB=<A~b|Kb#dmAJGCOAlN{; z^SN{VP6#s9K7={GC5_R8IrKz7jvT)~3r(dxAkx8P6oLx1dr-AdFi@C)0m30zD@%v+ z=k+TmFnXJlJn$N>JJ%tOY*(Sm4??{e+vvT`=i!7<*kP##WSls+kPknOVIWw2c)*?2 zFw4Lnv~4U8zr-L=P=7%3gTNnBx0sjc=VNFdxqBdWkJra@OTjEWRt3!j9bCBOufV~y zCZ6Z83qwCX%>e)a>U9L7sT5xuv@;CmYoMV#a%~c0(U1)xi`C2Cr^`impb@-xs21W_ zsH&%5@V}<=($S%Tp*NhQKTXx`)JAsF3a`*_!4ojKgd@3AldkPXIM+QalMDd^_zg<^ zbmTYC7hqzA%e~4z`p%`0CgDrgSt7pg|1pN7O>nT&Vb4_)0|3bYQ*C?G3dP(_IPK17 znb&0Dk)lckAYl@HoZj1jwX;mYNDHJ~WuI=qV&l;yKyV=)GExhZ7vuk6BF`;{MCI&a ztLHEbVd#>n18eS8SzV?mWQ7N3PmFEfKkoX3bxPoY)Dv!XqfOP!Z+`AQ^}xK{DzFmm zY0~}}9%7wkf7(Cx+!4USq!j(hAo`4PeT4oP+kWiBczO77LK1i=oJltRBl_85jM_%) zeDcMk+pZrj{;>4m0iuAA-O1U~iG>ESuFU1se~__YEo^$(7%Vb_j1OuKrDgJ^zbfia zOmh-ooq(p(i+dS@_YG(OB8EB)XOscX!+1g0B?Jo|%uaG=3MG%%QbN*?0ZGCakEaG( zR#Ir?w}S^o<<J^GmzM&ZPjuBU!;V&oP(|^-A2p~+NTZlaZs0wCB*rgbsDRE^PAKqM zd16`;Jm_1YL>W2vlaH{5E9ynA6<W^?OS)*dx(Q)DlzBkeypfXv!e8SISNwgMum%&n zS(vXgkuUA%!K#O$VmiVyW!kmz@@L0Y2TUf_-X~O*`_{Da>W9=A@bQpq!Uf%i2H#r_ z;+KWtB}DQA*u0>%Pzl&oR&?b(t3w^9FZe^AQpH_BfOxCuZ@XOt^%`U!T4xY2WFkBc zF9X4^O1<F2H_IA*?#0%g!wo6>0T%0w-a4rGKs~Hs4)|O{#*DK980&Uec;p|gokTyG zg*aBn!b><B-*EXo>J$IE$d@tg8fMl)eV}ohhTPxQTqMQHM`q=td*zK0BE0u?e0Z+W zUnv<!aOhzoiWx04L;imo2L0`B5pa(rE5qc}wlej3I8?}0F!vy)0RS8Jy7q3Zz&DlT zLzzM;&@!I5-Rbk>89&%U$tQqUJ8#5m!#o$c&B<<(j&O*7!r<>gDt_>0{qRy7=fmsQ zB|0BRtqQ3SWOl~mzsAh+U1ih&{X}(eo&CmJca7`*W%i@T7CvBjNd)k%iH36ilM18a z`mPjCe{9_Zt%(~|@b$^<9t)o<H(=)<5o_uA&6Ra|m$BBKPM3w_+_p0NjBg8RUbT9o z>bQlRJV1wcA~kK;PEROgz>e9K4Qg8N%P)T?CzwHO-8jzNywp=0V3EgNXp^)v+5+Ph zl)k28C>M5)P{a&-O%RXNSD*zmkbBfnH#JNz1Jey*gn`Y@{1hZ4v@y9se5s%9HZt-9 z3t)|F>%g9DSjUYwG&#Y-300x+F&@@r>gRVfo`!{MPX@nXQBkGVnQbpbvh2rwBe7<l z-ojohrA+?mgyc&mWiJZIJN3}n7Df^Ji5syOo)FQ)Yf6d7vE}rzL%mgi0OM-bzrDH+ zdW7m(jp;LroDul~+O*##zm$K}>|=3Hf}Atg&pvjVA}%w1dSd&>@U4?;v32rL@|gSD zx9Pn3zv`Q1Iz?Htygxn9J%7x{(oE*FSIh#4_RTzmB16D|^cL-l3F9#OIA)r|nV*2^ zfIJS@%1?~VIF4VqIsJK<<L*atXnUkT#*YU)<G&8xKjtRnW{AJKlkovl>AMu~-3G5c zi~Xb&L@!B4Y2@KQAAS*#L;;IDN0v37%<J#I*8FS2eFp*Rqi-FCCpEh19|{k3vx<*; zn9hB2M}MvctKCGCPsS?C-2STAG`1}Boi^j6=|?zQAo%{_;#+%ya{9d-Xl`y#G=i;U zfM=Py4pC6@;>wvuQ1N{AlVFX?1|xbs5~z{O*oMHF>h(xN($N6C%jZMDKePc-;O<#P zw~O1mU<WRuxY+?vKny|Ya=oO9@vTzBIQLUaaL3gnVa0y3+~kBD5)GQy_G_TDOHtts za*@>E`FPsXHUp)lL0YfIgdysJEtA+1^u#^Mi$)EFVixg%Nx%k=zTiY3+egfB=OK^d zU4osO1Pui=9hCR4oYjDv3e#W$ibUrIwDQVK<`LbJ4us-dh%Impn+~$ar?f+tgFQf; zeN<R$Xw{(TaRs8M+W{@%%*a{mweLKy({owmPLKok^_;nqDv{e_h<uUq)Are8RPLJ! zPa-@9UwHjrPGSZ0<$kb4?rrvb^Nf`wBQrW#hY?kJxHw;yxKT;|QD=GYFiDxc3@>$Y zo0~xf-XQIPxjYi#QZl5NgrPyt=T?xa#sUNRArFY`RLFBc^$u%#NWFoZq|p*B^Ch~7 z;&AJQn=i0!sK`+r*7v!@VwZwC*|B#aADF!kUFA{@)=4_#$L+3X;kOFdHg7BGz`n() z28*?9(>#ni6@Y<(C{M<BJF9a+x_rHdkNHD*#8~hLU>Trj)(1X5<xNy~2xz2XGA<3S zlKl|}nUrTBru1yK!P>(ZyISoWatJIA1P}rz2u0_?zJvh!3@RUJys|O9iWr=9>|KCH zv(yhYNiL$OTc0bqN<a~jdm(0p>8a_^leBf{7^R6?jYqD1wV$!A5~6%pHU;gSN15Yy zI6EVmLg(9wT(HN%dLUI_Ncyay1T1q*X?q$t3M1lP9U?sJ&vZj0Bs`jdQII&}Dv|ry z#j2W`P$6aU)FoQLN-+Ky!!H28V-&P*?lxqCDn&iY%nsK_TVCr!vq!qqz2f!F4v2yK zKllk+PWM3nr>z$Led*Y)124Bc8tsRx1bGyRl(yUE9s_QBsX?~ZnWS>G9Q;y|TE44S zy4Km23r)Ax?BFzQ?Aq**j4M=J<5CeSB-7SG!A%#R7E89@tto^x%a3CL(+`rl+MNI% zF4Mv`x?T73s5)j9Q-#AMGbfzE`{fixa-S+(qE3HN5i*<k?)k^9+ShHTfzc=xeixp8 z7u0*)$bQ<Y!vQ!`m2qy#*s?ph$0b|dLZ;a)!Zw(pToe`E%m_aoJY3=T2FXGqd&Di> zFegbO+{Pue02Cyl0rauI5s0)imNTdlWOt#{7m~-${TY5-z|uPpXAvJ|ge0<hFhump z;5IYPWq<V`Zk;0}@5&o)Tk`Br<OCJ;C!*`U^w6zJoy=TmSeS&^^c^4q#5eJyUw9{J z-{u6q6_XHmGWi&3{0$2gMa-6x5|X}T#cL*R>sb^dr%0FGW`p60)*=?(6LsiF7lf0D zPD(|6WN(%B;lCsQS9P!AU(<eM(#X0)PXb%N8hV(zw!TW8FcBp$0MmQih!}5&Q?vvq zKVGWU@=91=@1vdqdwu0DjB7E)BtmRCJktb+X$<*OwBzJ}%!6y&*#FGE-XY`FCK(gD z00VJmn13~gyaF<aM*{=KNBHcSA!cB~H{{?q(5wS8h&;%6iOG+z(!W@ryD4fn-wZg* z6q=2mpU8w$jS4UKrW0MIil-RLCQ=mVTTstXFbo=>ASM1hXJA0N@>uZj^ws-b)~(=d zb8unm=4|+xAcnAGEWRDx{c$BQ2&9~%lbwB$X@4xPOA6lnYpKISB(`V%oyibt^Qw#I zc!?;_l3ak3wQvxW@^Si{+S!aixc!pbHoM|oH6sLF3H-fQAPkF&ZpYTm02n76oR9Go zq5j<8U|jsL1knMs*xS9!ekhl4u163PusVlsSv+`96FvW0by-4UhrTY7p+?JdFsj0N zg=*`-aNE5#7FNXs6iWaYdTlyhCsPX?V`z%a747~Q<wL$!7#6oXUFrR=UsZpmpVOK0 zteBUTG5QT`ILU*dBkatZj{5Rp*+tT*Z?tR>&}>el2^Q1xdEeEAZ_t6{filU_bla5n zUYb_ZXZkl9;ON*KI(FlU|Ni@4?RCACM3RFi92)zcw!&+6e+y{qJy7|S8$Y9I7Rntd zG5SP^o)Y@nwk$cRrrkUu@O`eFe*1+4NhyeKmc1E@b`AURula^mKM5?M=T5JUCE3gg zh#D6AU>?C`%q~egyUrdz&Tw{_Sk@DSpcsm8o|omi*dXmniqoqrR|q)^R(R)0+`?mb zZVpE|ghq2}_DcwA@K><k(%WtO1F-0j;=PVfB}0}8Y4}@PI{|=vgzx5XT|xA5cZ_o! z6}yt`?4{H8aiTZG<P#SdjjpWHJ{6@l8=n_p-J;u6d{DYsA15j(a_-$>L3Z?68&C%H zWp1|JOWi+i?KEjbdqhN29>5k@Uzi#4HfJ<_qDx?*!Y;Z?u1$b71&*tfTRvetNINSk zvHwTy=aCJKq1l2_qz2Eg?_Xw>yu!eclKNnKgKa1}`33hsXMWD4Ks|tk0{7KqEQ~L= z?uIjFeLyPw#!-bZ2P5i;Nk0w=HMjJlA=e$?PL#5KJE109O4yg!i$hGmaJSAXIYfBG zTvO1jlx{_X6&shMtEem}?EG<mcrRqoiGBMMzuGLmCG{QWP9JG0U((-RsT5{mqfg)} zd9C<+>fQGJW*(wC?WoFO<w_YXY2ni-j6Cn*ISlvFeihw6aq((Ktn*lFVpb=DY>SGo z`)o+c%iOxTE}F}`hz0UuU5!|jd-}UM2c%QyNRSZFJ)2^rL9VN8sbJorT`#K!<hXM+ zP<`BT7!VFF|C)5*De>BBtLnP5#k&FY49vGQB&(F4d{w>*w!SS+%=gHRVWB8?2>bNP zl|+T_UQYw8v-YaF{Y#gU-%x(ayJE7IVs8#UNu1540Vp@~Vh^cUfl%mWSuepp!?m?( zFBiW9TA|BXaOmL`AkLdNUQYz3Anr8WU6iyN88UV$6nG(Ff~!9tb5yi9g|=W~;A6g0 z$%(IeRi(VSF!VBc%SYNXe<so1b3m^m#w~uoMpRAJh^Dwy0e0Gj3ZEO|#F?S&Yr2xH z1Y<DYr@>9a_5iuRC#_)!gEf&J0(`>0h^f~})*3@bg=n4<uND+sIY9sqpPxW8M9nzT zoh{YmzGZ-d^@$xo6QdnnuVG>CK$251d0H*6bxQ#4BLjS4siw<==LWc+B&d>l1dc*< zl(+EhBXdzYtNmh>?P@e!TlPd{EA`vM<H|2$luI{24Wk`B(xHL{-I=^C$Q;S<0#m{D zoB;~!KWfj0b`pLoxHWzX^IKNWhghYMy!-7WGujZ9IQY_o!ZFv&fSVDa$dEpj%}gVN z68{SDqXyI_L}5^f1WH4lKbN4qx<Qlr?_5eGc{k9*0ua)Koz2`v+7=_0*Ra5t=z=*+ zY7AUWvPa!OE^g|u6Y&gieZYLPDdmWi%zUS*s>FZPN&pc7m|&n!1G^0pQ8DI*m>1<? zBZklyB~j);p-#Lg*Uml7<8FM?a0Wo@RA4J|g=Jj7GrMUTRbho5jA^Nrs11~kOugkc z9)ea7Y_b>&Bg2l#{xewC0|$&*g4za(ao=hv!}t4L5goa??b(pSW)qaT7#M@g0?v~+ z{XVXU$gY-<_s)u=E7PGhl2iyv6!Ct-=K@C$;*OINSlRat>Uow~4m;{^mU<B5lWZ!` z@fo2QU&bi1ctM;L=2oA_f0$txeP5y#tW;{4YysOx`6B8|9?*V>TiKS&_B|Vn5Sbz` zbt`<Ue4*4!8Gg>&L2lY!5d_lh6^i8kduR$ZrKg<6G9lN*-nc$^#^Iu27k8+eFf8pT z@LNu5&0$AqG^Yx7bn)v7qGaz1GPCeGbW~{9v1L66rY#J~ML3aWp^MgoeUqj~6%Grr z*Vm2hzq3;a`aFLx1MM+vmd#*LkmMvK#fz2xsw$Uly9fmrN_<#O6{@bidzhzQn7%=g zvI$D5f7Eshc8h@j<DZ05KM!v$#m&ha{n(EZmOem%VVb|Dl=b_^kllGXpsQd_vB8Fm z$Jl65yEoyt?F5S<Yn{+1*?(bXeuVa+cf!tB{&ziy9dtfV<7?84Oggxx%<oMB6`<gC zR0pL-Epbtc6K-jy4F>+1B|hZ8UQETc4hS5lFDu@vL*wU)D(m+0upp>-i+L8?+?+B$ zJd6RDN7$2YS^}KJHgN<1m}YTr>*rQh{xvs8EL?*A6LM$U4&?dbJ^&P@Sfb;*4ucYk z&Iukz$PLe^NQD^pIEG;37UmqhA0@G{5<#flYQN2Q^JkeQgK#YLrH&zO<bx;!;U!J9 zAMa6zOAB`}>J()2MYj{nH~xiM{}D<vPUsnh558xOg>gzlfU=Sn^A+0Gv}xlX0V`pE z#(}2qjygSZgrO~#Gu?<o#i#$*M$D=w#{`iBeICB9GD+Oq*tf#@3}uqjE!m**NWqH^ zR97~Z%e0veCP30qFf_}j8rs3Rs@S3A!V|opC^XNyUV5Dqriq87N^bJ<{nn({Ugej= z1(ldD2B5WwS-N5;X_ODBr)Xw`yK2++@`h{hJYujsie7)JaH0{uZpW6~j_I>C4LQ>E zA8y{YPKeiqk8jWHi%dhe+{0ytuvxmGZEHgxwi)}28msX2mR)-B_;4SXwg<$R4}!7p zI6w;DlMMABh-N`48_x8pqa>nn4IyIs;^%aWNWVZ|sz4tE2+4~izlexZ@V&)%4x~$# zN(ncq`dKrctNF|rI$M)3EPJL;CW`iSnDx~sZU7=6fm~Nv+Nl4Kz*?m3LMQF5Va*q^ z+8a1ssw*!vqgBV}49<6ga8?o0c;okzd;Vyk=%Umm93Jqu+R`}i^F~qESw-Vz<08Z= zv)Y@n8z?AjP2r}of1@1jTigf@sknd6fYKw?rfb225Gyd+&RB#(l}L&(m6)ZjLx4!& z^3{$NewY&A9GOL<)yB}m5IMWUiIa5-@v#Al53`@3@`^1^-Yl5y_1|<!A=&*0e9ZWh z?;T*gNgAywq2CSH5NRPO`CBrpuUh4GA4#^JzNm%y3L574ru~<V2Sis=OwKWZr+rO* zoB{}Z0@uj{h>-fv6n3~puKw}Wvs=y#gLJS-_dnaN``S+F8TtbaPM|WWfr0NThW4uE znofGF_I`7Yl;z!-X+JL^Uc(H`=A^@fDL*r}Z@!VQ1|W)5^=xuq4#vUr_2*Y?+=CE@ zEWAqbyI!gF-eMc$t2%Q?F(rfWPb$aDtZ;H}Vh;^ypHp}uX73viL`PrI<y~1!<uL`8 zg(zq8_2)n{LEgaPImT5REai7P+tQ#x7}A&u+BabE0Suu9`^UU9wVx%^Vm31RB7|c0 zG5K1>y*pM82{%|*tR6e=u9Ya87tKB7iEQ8p6(7|y2e)v{=mR+~Zq>z#{tw54D<jo0 zgd2A~Ig&;l$px&esy<LD<UO-Anak;mm0_0`%KuRdXgmc>OxTZ;-zL(C`fB#f`y;~s z!R_$-PL$2kdeinh&p5<!Sl;K{VGAlTA?Sj;_lB`w6GWnDnwjMjel5(yL48COe=}4` z8HY%T$L-K_eX(1IGOpXz@yqyE6x028dAMSx0z2u-dl=Lhv2{FlI<%!itDP0t6IqBj znh;ixWgrVU@j~RjmH*kBqjx#i@ejv`>muym{nlae(WL8N(X<xyzPy;y;-fo+yv9n< z$0ezS4{Xe%o*x;lYbw`Ak>%m>;@=xDRPvqZ-9g3tAqUe`!4l9(e+(E1c6M%Rz`*uB zKpZTLREfHq?KTaQ%iH1UCF*e62{Ku^K&VH-P#Ws(N1nbkxZJcO4ZK7W_ca<OFa#;v zws+0v@yNJx4S-s?8C=QC$;nbLq0~8}U9GnS$w(O}Kbb*`q+E1nu+qfiBRwmCcXf?T z5(~UhtO-;l?e#x>YLNDudK|n?I>22rK1+Dcd&1#*4Py#)zv#+{GNhgV-Q-cFjMokw zCt<2{l*%hz>JH$WlH~O}(7>znUY(v#n@ypkD}Y51&J6yewmcQ--Uc4*MU%RqV_EUW zN;smjY}_<d_tfDZwfCnapnUu$dzNkd8APff*{>RLbD_=|<s;F^{Q!$aRSUT{d(>b7 zz^3ORDAyG2=Cd%a<mi0@+a)TPlaYY!tjavp&}op16xq()908NJ130A`RnZm#@&pX` zKmz|3884z67{?gzK+rS(>;TO8oUBOL#fyLWa$dz{+N2j@=bBmibXM+M(}lF$p9oO@ zE%5;&3}%2Fg4qK9(mzQ$nT%xlfC^H3-kr7sxRI|K0PPH5-dJ5d9e8{#B2&i&c>Zpn zP9i#F#WZuFmO#`|+wH^voeJQvN}dOCGmSWYo`vmS+#DOGmQbvuE@_uni!y(l34b~+ zCR`MF8mMT?@v#)FLB;jirSD|g=Jaz<&CUz=rG)LKV+EYPu)+2AATHy>qO{Yd?_Q35 z2w(HdLUD}Nb%u2t2unKQh@J0Nrkw5;$~@*^KtV{4&Ci9?b-0H>LCN2&!!arMN~;T_ z2C?)qh%X0ho0MFMUTBKdxR!GD*fnJ~WmG?!M#EgU1$~iEXv^4@i$=G;&4sZN@;><M zmnB{>=|?ZS)lbF7M&<t7I5y%)#pwz~uGQ}K5Y@ba!No*_gH@gU;(<hV$+E}OqqOHG z=ajDr#8<H2&2Vz)^wBxocV9Jrkj22o<Z6!Y*ms#!ibN*`S0_hIA+_gCT}9s3S1<(9 zY*kI4&)v*Dw)yB11be$^E^eBtebwU8Fq@cj@22m_>P)?0&kfcR#-c0C(dNFh=)!0> z-zPjV5q;0n8RR9jIkSqx{OLbh)6vd(g7cb<N1lu4b$=@ouHGlD7$%L7@N6hDSvN_z zo8F~h(x$>&e^avM#c=%aWgYAK`^f2@=*aJvK<A_A0TG?d*^;zzAAI+Cy}0+4hcpmh zkR|f&9%FSkcRu}5Uly^V61cFK>Tfq#QTew?ztiD&rQPG(r%z@~KMbt$?+YMfIPwd0 z->*HtX>vGkc1Fc^4kPBGA3{yP;82zq3)`z`LVskSu_KsB;iqgY@Ow|Wx_NUzA+khW z5%SPYxWqj%B0@5`%|?HG%}vXrML1|6<4|D|Z53Mb{=^TvKOPxz08B2x9NHRo2du)U z2KKcE&(AnBESh!eLiGH<;pKGoC{GxmNol3phrPW#cCs+9j2wBS(wmJ3Xs_$sqj&#b z7f-{4EA>a(GkQC&l-X-t(7FqSR5xZq!dL^Ky5+;HL2s|7z~<kw!H$R0E<xb(lA#BZ zd=lnJk~0a*j<T-U-WARxTV!@1{LSEgP%@k%p(P*`Ds+>hBqf{w%VTs{!Uh^WZdl|I z(pQe`@nWRwQ~^5sd@LwY0vzUlD8jqu=gq<66*(A&^jYR25mKU}#7~?tNGzY1F)ESD zl;C(jS1Q;SzJ`r2L-u?IV+&gospE*1h*%)Ac$@-leX^m{(BnU^%6?(pS5Ax)*glWg z9|(#44`v1fy%CV{%7E0b5EeXYz;xr2L7%N3X5Xy?^aVm!6g$zQMFbWT{xoBl_|k#Q zFq27LC-D@+kliRzTFO?}aXVHW1B!~Q29d+9Zy%07Bsea?Ube@mXsY6838@RO?>R(> zek_?k%sDtVCoVx&_m3K)XpTv`3Td45Iw<*705724rj@nu?x{jt8!GwWRC9FyXci+d z><a*#UHsYMZ#xD&ZFR&LrQrOUL(GHPNIRC<_weSn?hgV+#ddrQ{h8sI%KG?*mv2me z8`MQ6Na7aoLhLbXBjd}6TDUe4ZZq|srbM7-W*(2>{6wd8BFMDBIl7?i)W{EFRw&dT zq<Dem5@l5;yl3!yVQE8Hb_Za@7v=<HB~OYc4=3B%cK0h`-q;$d`?(-~-v?2-fQ3tu z`OpeMwpR=*I<%&fwOh$(a1@@TzUs_6>NoTz;7!lOcCq>(fsvJxoXgq8$<H5wcrw}8 zQ*Z_9;{HSo+lDDl{I?Epn<pJ2*q@TJCINY3O#!FgDbZ?+?=$w_xz=~Y@`>1f<)<d1 z-fTR3G<C<Tp9nZxW+eK2Si*}Y2(kY7f!f&P_zJGyXLcHUoKLSQ{I+%lfk+WTk((2P zg^30jOi>BR8oYp%iX$2$$~uaCQqfuGY8qm@@K@x<R@ErSQ`mDDB>H>2)fssO5ovx2 zZwf9~afKJv>z-$I9d{{+9O$Q%JsDp(d1_lxo&Fq<0pnXRuE13^6WSwOFL%@t-crQY zN%T`JTa0gb=J-X=ik}9ZKIfhSn+_~NpxE8nC0IUDr3Ycxs~|xG<{mb*q}s#y3Ib|H zaMs?PLa{TXF*TAwJSWb++HZc*g!&X0w9&)1Z@CL$vxQt7oDA*1(qe025bNxux7%s& zH@}z((U!B--p$YkaF#Kzw}Irdsp=E|raM_k8h(Cdkn2y)?K7a&C21qo5z1HHj~dDO zbQ1ljD@*RWUK)&p_36^@32bn$z7M0_MN@IrzF@qmfhlnQ)?f^31VS;58kpY}EDe1* zOB3IC7(I1qYV%jhGrN%u_GUmiG@OtNGn1G6Xl_YM^83R3{uN)we)u9$K7%z5VA~bW zxqMxxPNH-|5S`7t+X-1&abc!XP1$^-^?bmcEjM>7zk0I=Cz{OM#uIPB75i*>or$wg zLDcy{?+q!>z-B`Kpn;*6RZ0Q1h8kb_qt3?02*=DyZkCtWx*P!_pZD;~GMOpypMDVJ z6uiX#Dc@zRb~+b>2nsjO=8moZldXB@WY6Pb*(aI$a*?g_ens@X7F_|t=v2tx!GB)& zvh4>=|N77`Yu-mO<VR+g-ia`4p+3Zf^oMX<8W+nR7V4(7I8Y_%6oMnmzW1j8qVs8L z^hg6C!5*L_fh-@ah)G#TZ7QeuPd|c*iu)UUE({t2$Y&(I)~%=89bl3!89wIvvcDl) z0Lf_&@4gSeChGv3%>K;~Si)UR{gvMs{OscPZh%w=#qw0#-)QD)U*Im(@riQ++?~IP zBHo49&6Z*$Vd^a~8&Ud_sq1hOkJLoN791S1plVT)i#fO19eW)wVwN=&R)m%Th`=Vk z8tJXFKuAG6*=&H1-nS1!EqEm3jh!`gSDzqGK3^l2?3>T(&d3VLZh|_>si|bO>;FLa z+)V%-bXJTkO%`4~u#Kf1I)-;9*6h!K(X4fP&hKsYTcjvT``;;=hP-Z;0q{XGH2O4& zs%$`i*w=ZCBENWIc-MQkM4dcbnyM}XL1~zKkF@M~g@~&!CADFc7#5Z^^6Wf^&K$79 zSQJ=#p@*O3Kwm***ZWXGb0-^8nF0%7VMK)JWniYOB$Vf&Zo)s#bXT<1zr<Y%+Li*- zB#8!>B55EwI2=0E1dbB;1wr@6pg=>6w{e5?kjUn7D`C$&;R&a~Y^7I?0zDLlu?e>D zYn3z;OMXqK{wVo4*v>Icd~C-SP8@ongl<P%kjRY>#_K?*o*Fv2dJxrPriT>VDk8DR zKFwRL1!qmngl0jag$N8X99M1+OJ%UlsPL6+AZ=a@)&aa^4m&r(TOS7BQ__$LX^$mX zT57Nmg31_QCo_^Vc7f497Mh0QE{Fjn21%PVenLddq<lgr7d-)&Y{hy`H&KP)_Vd^C z+nXc)ZCYb7Zl~4PGFD*gX#WZuXp&hVbB8YLVbs^$D(jYXY#<$oh-6b@xdqR`$`Rlj zo(+0sfKNH`t@2~hJCs_p7dSW#kMIDvQAJ;Q4~}V13PpmV2vJILVX6ZCOH^s4%`*0a zp;jlc)v1-JOzXB3oZV8cH&*C1&P&#7Kfj_1hz*9+xI}$Ddo1^~$>JUnZYwUxzlB*! zH86PTW9&rkA-xPG{Kc>(-85u-v*%2bfv^J@(h8z0xx+UPbI-&T?CVRygQ8QRsvshG zw}b0m3E(coc8sbH;-(FCPP{<xq_!~WFswC>4GLfXz%q4gBDWCG8p(^Sfc8FvshdoP zp7GvuSS0Y=kig3D&!K&6Ez^pc+wItIfnx9E2wX~RF%`8Dm`_CBjcR6`&);8E70SgW z3ASiAuhhug2R|1X+2h4<e~5{11R}RK;(m~o_Ti)HwiXUneAaLx#7-6w2qPnqX$l^E zwTcto)_<>8NohPeWvGi|Noc(Ttn-$xofoI7KI#jR2B1BUrQ3|;I?;Py;juA)?+xcZ ztf+*>U0w{K!c^frMXb#9<9Jmciwd$d5Y*zVj3M!jmMvF%Z7yGQe;UOlS9}dfgHxs@ zfUHzbPq6R%>4sx-Tfze+Qg=m2Z0+lV3FcMArZ~wvG*Yi-W!iu44Xi0kOeBu$H9LmR z3}SjMAzDE(km42GvYid-7%;E4;0z>%KnYR9l`RYY_AgYtG<gw<HoM_z_$9)D2>fzF z|AK`S2&$HdC&V}<>L0aIJqw#R3$Lyzyb7)$4$y>=N{#P`>o=*QG|y{4s}r_!N}S?m zh>V7h!1r90<l&cx1-~Rd$@j8jles)-FQsXi?7;JLgU>Ku;o*uwhH$#Vr(=Cni{gn0 z_UbH$%<qBDtP;|?=TZ~G<G|$dpkerI$&Gj2|Nq&q_gIcoQ+l7(RS;g^=Q$iSSmak5 zi*uhs(yGl=4An{7PAD(3(D>{&&UGm_Sb5-sWT;jG20lvWoUP7QRs6Wb7g7pb9BN=a z>?3|5pqb7N{f;M)kNL*5Ie)vgodgdjpXu$1OKX0V1Aof$$IBaQxIg6mND|N@pn2d$ zl;{IQgZX75z|RSrUKcQB!U08=(V0&B_{NK6+1mp`%etX$h`}V)vPPNnrexBN4=2e3 z@6HcOKOu@2Uf!#A&UlsHBZ!=_d=qFoB4Ko|dChuVbJ*YH#|gWa!kJ*?!*vQmeC|Fy zw5SaJIN;BtXGjz6?yuU&L9&c^pMWQ7NZPU~2gTm!eQSMdH9|=k$9#Ht`e3a_fs#(t z>nCEY0}2B?(|s6C3OMAC1NL_RsM&bIqU%hLO0I}xcA*V}3Wz!km;;!x`8#>Lzd7>= z4kCO6=9Ktrdg-%K{uBZPV5-n9NjKu87%ShMJMzUhh3z8br>gR+H@RiC;h$%Qj;#xt zG;r@wO%1ke<SU|{lWRpjQE>Fkx=D_Fma6j6kEuH7aWZou8E6Y1#D4c@C(VjX<C-yC z7;lr~0}3@smC@>ItWC2(?yL{E9<b$u&_Crn$D6Y+6u+i&Xk2B127D>p_Ut=oTx6_y zy8GESopp^7sNOi>&IO9~lk_5l-ITRnv&pW4krBY49I>K0_OA}3$K%^F_1fDYm@>z5 z20Jsnng$L2uiCSc8t3Fp*Y>aV3&LnEP-h@G=-X!$-QC0Qxn;mKSbAZO%I|@!-9_?C zG-j=UvAPQpD?QGHPT;Hzw6w9yLyA+pFq2Ii-@L`87^Ido=KLr1PA(-@X+WcLPOSth z2Y$D7)M#-FtEf2xP!m8ADT`b91ZRxn3=<zitLphZ@md1sCTIHnv!w)syEKT>Oh|@i zfNE_QSidKA*I=B}&JhTp_W9#7OH_D)(@ch=Q?ZX>^Yeo=PB95;yjrAtbihVtVFglj z$yw|EX|5t|tLgc<4=bb+M%s&UDax~Ine5%nUo4FX$Ht1*w4uE?WY!zt?XC|qyyvq$ zf`<_n-Rq%9?zH6|vPys_A!Lx;Va=jAi;GZIUg*RJ9ASzMzhBZ-cqwX$@{NE#?Wq5Z zD*|IS`kPTC`-&}sipqwmgRIs5qGNYcEV^(na#D^|86E6x>yP{5n*bAy<+j*J-Gb82 z<)<wHoU}ubOX4j$zUv1!9fX;4-AsI|zqb)@WC!>zg5o~iE*rnuKV%jIY|YdODj#X@ zTwRGRB~gT4DsC51{8-pu8qwjSe<lw!j5LHqhfHiB2IH~HH(X38pI&rutaz=HGyzrz z<&A$;Xxwex<kJ|M=P-iL79KUiJM7>{;ZIcd0<a&x8Oa_0bJ||`U5Rl2Sf?--AJqyz zE|<y49Lz>a9be+LEOHxX!{cZN3PkhTPWP@V3$EM))d6&#YBk=DAyx_>qdGBk#1792 zq;BX|?Be$?JrCImF>PI~r-2QBW-u-wTfE=#nKdj~W9n^pp)22`=*Lahm3HNDlbREb zIR=Pwv~BV~p%W?rzGlemz%3e4LSS+(8JmU;xXRpj)f{_nklBUA#Iz<|b$ZdzsK)@Q z2{d7g|92$=?-u2Yqzq1wYRkEWyvL`}cE<_~{|fh3HxSdz5u&FD7UYhxk`#~q@n+OJ z{L4<#FXF(L@Bdw370*Y1TKVQ7>ii(aL5ij*EE0(zn8%PLJd+9^k+hEcVG7plK0&Sy z*w{!^huZToO#(P1YQLL1wd`<Z&4jMrgsdz{zb(&9AK8^WKsE{1btq)-7*<tHF8WbJ zcX)<^+>CZHj|Nu8rh!g6dUY9)lgy|_!7hZk1sv#TCTPGRt)zlOB-QbOu+on(M(fai zMly&_i_m(7*bXAFkm7ltLxmsY?1H`=GFbdG>`pvb?d3>^*h#McT|$@|o`Zm08X=QV z0`-XV`~=^xz4;2kjagX#p`C16O>TM)w+@zwdTK1KC|^A7Y0Lut7d7oBm;gqotHGfO zS7*}-a`C_(zyx|mSkCnCTv<7RE111ouFpFyUz-IlMiJ)Q2~^?}y@>kHlxT0@A+lK! z#>nW-hg4bp5z`X9pknq+R@Jd?hW^A%<-%V<O29<|RU>}%d1y<-k(6)P7cECI^ntkT zC_Su$JJb}Nm#B|mR&SpTFjh|B4CU2=i`{-nWTb=#5*qy&oOcWoJ+kP3NEa1(z+bRy zW#^u3yUTrIe8_)MjDF&xIWoaAA;l|VyR2%f>1I&<N4g8kBTT6Y6_mTUDq<=rNxjXE zvWN3=_&{`mV`apQjO9fS{RE4k+IaveO8M71b~LAs-<e#_>Y-}^Fj`{6v{{awx77IQ z+BG*mObmH@>i7h<v#9Y_6{BD0z8Bb{E)7Fl(JS%*KEZh#orZF4ZkWG+51L{=sJ&{r z|C;+b8uyl_N=9@Z{91as*H}!_Pfc!GXC*k#DG^9@*`pZG7J>V7Gp)I`Np%0B{O2iC zsXr<jPRP*m@bB}e<MMBdW0mfaxPL^l8SfL_EF11xHbZ}O1F{#)pK-elQ?JuX+T5fn zPuT;q6}Mj*?iLsEZS02%6A_`@O&DLeb(Frb#qwyCG7aW^rLwZj9Pi8Jbt5j0;Fy`o zAidpndX^6=aVy^dbwg>@Hxt1nM>t1{^o4ioptC7FF{YSY^PgA#4+uI9Zc$aA+r^>I z$1Ntbb2ITn-fDuS!+9FemrpfRTrf^pA+huq?tEQGJu1L=#8zwBpO8oeZx<&J62D<% zm?6pQO!2+lkaRvLW(pp2$NfQ=SIMgeGdU}jriO2)Plit05J&$y3$%cd=NR=Ob9ltV zm<c)N()j6*?YB$xremiZ$ImEac`MpgYA|!&<L?juV2lBfJt-iUD$AT%B<1!5B5Rqw z04OYC49K>-srZXJ*eii?*^s+(i(839cbNnV3ett_y*O9aGC{+eJ7QbS7#pp7$R=K$ zcMP!LQ7n^3IRQ0IZ*HBWb)eoQgd!GDRUB>fN9&lr{1Ko%RfGeihXjVO>QX}A2CrX3 zJqPCSUf^Cq+#U-fhG_=SLVWvvSACL6Cg52OE*6*E{P@N}rD3qF=Q(s82ElO@9J%1R zxZqupT1e#4H3)K*MeeG#dn!Q4#rGP%8QgGktHl?VUzMiUUPI;t01TNU(pWEBf~G!H z7R?%>SqO#<5@zrR0lX7zL?m!a4SH477jUkYAeaU5&OnjDMF2);Xf+F~Y`Yj714kMU zAeVFynf5w*+{*(AEK`iZhAnf;`GoE49~GUi_3_~YTOD<m=%PrH+aF;cyqbf2Efzd{ z9`i|tp7XXN_huZnJm!~7LF0v?04jY{Xl7t<)uOfnvvmbqPV9az{0&%mkQ-}Z|427@ z3UwWvxP3WqW@fY<t|cQ1!K9z$omOB6X%q1UzMvb4d2MJEQSeO21TvOP>V&y%o$$Kz zJ!uO92^bfROq&|qQP?>t@UB6;tWp+o=gRJB5!~<pvGnb6P1gPUgCGx7B%(eVFdrFm z68whd0g+*8V?!H9K?Es<2(<`g;uN?ED+P0taf-~1I3oz6m<kGM>Ks_(B&Z3foIyE^ z<JjT(U7z)PJ^wrvjC=R}x!;HDeZ8;i_JmAr0!3zG_cn?~3ddyB1}br&KcGYaPEy7P zh=RqHFh&YP;69D@SF+J!9v1dE-9N%|mzbIpDkHQVM~?TNA1s-^!9Y6>N<_O4llXIi zzgZrBFKfftlMYQabRWq+LYU2w$(vC#T&r>aHw$7Td5oo*W9X8g$CH3tyl?X>=8}+E z!4P`{oYnf0a;{lc3rN*EtYeRey{{~y`0x>wg=$kQm14XKLN`IzTOXRFEQXX{cS$ep zIH~BCbDw_f#Yi_y%0^8GqZ}y9380|}k{UVyGS*)EDCaw7QZ~J-gpunk{^AMJbC_pR ziY<)BX>2dj6?QajkD+<N^_cCp2t>8&%<rD36y)X#lCa_9v13PXBSiVUl<6$*M%WYh z;1z^H&Jbt5r9ik2YhpP4gsrRXb^7i}TzWm0C6kgd5)Z@agACLjXfs+l7(8bKA;D9r z7dh+SA%B!3O3{DWr*mjxl;E`~L^=8<QoO+aiS|8hllZ^0{w3Rbf|YZTz<drd5<;W> zQ<Ukm{fYq_&4F2u@s>YBmX|Rbt+Av^>ed73>I5}USBmFD2nT?)lBd*r8S<Z@eM@Qu z+Pfp}*3kS8w~Egj^O$ai;MdlT52B%}->_v=yE#A>on7xDeKO~Ny8jyb+OV&K*%24- zsOn#?;n{q2dZoDe7^*T&5DdOPohmvMzg0-^jcTtWuHIV@+`WFZHWbIl0EF`TG2u_l zs|i1hJ3StG^Fp}mF)4GvM%jqhEw%meQP<TT!y&6i36ZS7;LBm{e0CibLBiF};S;=} zonZ|(XO-jjFaEwZHsdWaQn8_JzDH&~-u|m>UY1ot-LaZGZ5Ea--%NG{HgA4|Nh>Tm z&(v;8kX@fMlSGcS&jq6v#9-`|xAT6bFil-8d<1eT?le&qiZ~ePGIv<JeH@e&XmZHR z{eJWpIU^;Ruy*G5JV$(d7~^#%<%`dMv&l`o!M0k!nyZILEy#}8FqKH%g5oVg5Ragn zW$K!Op|v?}ttKX4kiy8(PiBsS5tXM2qu0Q_38F$cctlB?h<7sitnsG($?)sVc>0e< zt_lwd<^A&ngdJo=GG%$(`d!np&rqLTy97aV1fyGm>Wbt#g$dDS6@WXA@wKY_z@M(6 z$AJf^Zo1SDx>`~d#QzXR!gjf@4@P|`W0*iwh4`tuN+INPq_{gR92y|~;8>NsIe>kK z>;I$G+FUj>+}NNTn1Fm3I~DB%qISKt<WU;xWeApEMO}(!l{iEJ`R??E1OuR1Bufzc z%1DxU+^EMK#R-mT#<IrWiF6cf5ZrMr`gc_ZFkrn)N&u2fFup<#)OeiH@V1Ui;gFd& z6Qkz?KX-giKK@!0Se`i`lFg*gl6LE`ZoyM#MFVIV)ns-8lh++!BU_fdfUtcd@K>{R zIfNfD)h-$tI#Jv+p{_2`Ry@klN83yWP(xhxDZEW8Q@vIGEg=g=ifYGP&m*j3=6Mc< zeOwDz<RPDF<@<KbB=(#nON3&K^w`X4(ALX(N4}5mZmwO<-YQJVKRJ`8%oHQ9X<{(o z;x(!dAH!@maM(K%4h%QC$t)4+eAyq-)O{8+>#YZ%TamM+9MpB-3Tv!ht`#Vdq!u;= zqt4vya=IHn^9aSD7^%E-j8BHlWOV^q06p)f{pea_Y45;M>^I(WM+yTogU=f~EIQnJ z>mF#X{!MenZ<gl{wryC1Jr{f%bbk_+(%<Ld0$0m8!<upb(<4(h)`CsesCl}z3+#VN z`*ViU?-yVxc2utEQXwA8HATUb^eXX5jE3ac51+Zu4|x!oveaTzWtHI1N5Y3<uD0DL zV#P21A?6=Nno;-8yk1}y+YAEdp+2^yc7m`tU{|7=j;Iqn@VL1aYJZpjJyhFYlolLI zx;w({kQ$83LOi%C_pkf|p&h0r{2UYvC90a`bo-&-og%J-A`1|#p`wTio6mgZSHi~; z6V-m*{*ld8@NRrQw4eN&L$3U4LLC_LLHgPyxs~_&iLoDuhREd4)DP9N*VJRF>MsQ! z;YB_HYJBM{|7`l{DO<(_{)eyiydnq`wFgcxDW?WdQuU}LFtL`*Io@Ku+EBW+{AP(R zkIjXfMYXTbJ96OuH!lA4>HJg_3VS8b#GwhtDX7rf*MDTI{)@x5r##y76fU*b7T>M7 zEQm<wEpX9r*rcYxPlg?zm-s?tRLXT?uA4;>Yd+1~5_EP0Hjz91tBxf+FkXcvQztBL zkP@hAjFs_=&(=@4l1JB*SR%4r)WDn|gr6_}KGq$sWBw5=yDhTJ-u}Y5xN$PNo=;$* zs(a!fh?b#b*<=1KEAW?rm<tZA=R(-EL~yYi5j9nLo*BFQ1vX%T)T(hv`Fl2qK=_4l zC;l>A>qeSU`C?yiCgX9#*FQC+a?JqWX`uEsa)FU52bT`z1W}pjF1D0F;sx3!5!*%a zK)CtJNI!bay-W6*ObQ<6Xzm_>NLQZJHY^9a4_+N4pq=|hdPM9u;OLUw&BndSmgKwO z6?`_FWLDd9gn#0}uUSnPl|uYu>!sESDRHfpa~|MXy=I&5gQ6JZ{(`WW(@^2|#~us# z-XM75x)C2RU}6sc8Z)?z2+LrXd0laLD~iV385ut>ul@o49#}rdLOj4cf~4*ow)VjD zRxl=9xzocH)z?2c1fRh2wSIryZqHWLL9=gYSWw{-w%j4L=`+?R?{o&C<|gx4c(j1J zjV^1HQKs61W-wxRzs_JC->9s-G+Tkdv0aDUi6Q?2J1y!DCf|>OC}egY6J#R52-((< z7@PyMzUAjfap<=sGa_Hf@S6jq%9l^^_UR5mIeEVS<T5+t)>%Glk3D(VzJ8{*Qt2XR zYWK9op5oD!F__e{V5u+|3OX|>BFazPTj85|RZ|OW3!Rcno%&SJ)T#(>@Lv)qHYu+` zBprcbJ`d|BAahbsUe`W-y!E|qBunWif{p)P2YuLp!fI!^Eh~GWM|z%lT^79y=!23< zC|iZvkQkODV)bZy1C?;!Oj)bW&$#q?)%lsM513H^<Y6;4WgmiNV^V>BZHEiAo_nai zhmY=+dE#BN6f>PR_23_MVJ{Xn`9R<DkH0)YVai5uhL8>Fu-UT~1-#X1Us%sU??-go zx|@EFn*B89sRIlJT8o6C)N59VL$DmKzaq|H(XPnG<Sk3AC6GkVfT^U+g9-a7=b>IF zI_6Ok@RS=+Xenj*cFFL&>l!YuzJn1ig_;>IDu7x8y?pBbo9@$mD(`1Ko4oi%GL~&9 zk|B8&$ac>HTht%P(9L#xIFKtueP$!TY-A_af%h{|hQuPfGm7fwsz14Dkj|R1g@g63 zob7%Lp1G;s{%lC3Rna5_q{%Q})Tr0nTIIFvz(6jfnKwMqcNP@n!=&_XGe5n`(-U?= zxFuWyQUd`08r7a{1SWA1fP5c#B#bRZ&hw%HkT_<7d6k17g_a5)2FAzdjeL+ZNU3l2 zDO!<G5lfVGvH^Aj$1&8#;3E<8D;IPn@ZxB9b^Ue2)@0zT!1Rt>{P&M;V>L1jsEDs) zUuG5<m~gE+)954G2Ex$&7hP9feJOnKwb85246|vApk-(U975A(l0!t5az?bj&x=uu zgPlfgE9+Xm>8YwYiQdBu(iw$beG5)VhucSiLsGXcy;*y&c^mOcX|J!l+Wsc^i|+q) zH^+G}Q%iB}YrR=2lo)R${WH8tpKazd#G0rs<L&pBZi$#IHC}|_GQJ)dZuf^R%xYTV z<W8h2Yj?hW0M0Vl!*|*=e7X77wurJo<>G>aU&awvwtdZU38Ij}%iF#v!Bkh%)s?2k zUvQp1`D)|cU9o?xNYBigUJR^#0&LmojrTg=O4GzAfqVj4BGPwf^z38KQiZe9U6NgG zWtL)N2#DkH{?d}F{J>?&K6mv^`=Q9QAy*23Xyi$}oAT1UFC)SQMJZ3%_cgp(abmg4 zbphw->%(7yvPhJ;Y_RWIxpC!hg9@*mm^=g2>gS4t9a1o8hHVPIU5;(mIwweOX7BhT zE*e@l>(LotvfM{y+opY?4Ksx=g(bYohX!oITr*Hj;ndLTRG*2m)iG=<nyJzTCt*Ia zLBa^ZLnw1saP>ypBM+HL!cYYg*zx6JO<3&GD+zsQ!0B0>KVr1YHGKsU_*3O|uY9BK zVBrIMd<}w|#_v%N16#0m9Wws0G2|QNU=%~^`^*PH6E_&TQcjt%^(O)&N^pjtXao_{ zjBg;zh%LtIR5R3XqAUVefLdg$NEn9!r3tDDTtg{(lnj3-Jls9HcOM*S7`TIeZ?_4p zWUsr9>97ap3z{Rx(`K=qjc)@n4kF>fak-8eKl&d%gh;oGm=nci03^9j2mJ`*q=L+M z@ziX!A<)R}z;SV~Bz=>N?LoF2D7#w_J@hn425VF?gO>)=>D~(<GF4z3!&48KJeo-^ z6wCyfY>1XVB{z#k;TMUO6Io1=J1>SDd_QJ8U_gRDN!5X|-haWLC_g?g*}`%&CRD06 z)=tD9j8}bna^^DywZCZ6dzwD4tV?2dYum&)q@<Kv1c*@vE@xZ=eB%8-c}ZU!JnQe5 zq-|!e{Qt8onyQ8a^@e2tQN`g;;dBO^s8}5{!I(Wl!G+;X(TEn&IcVlCH)W~V<p%m} zR;-x?(HiJ(zZk-bxVWtsHf@A9e^Yi-`DaPQRn0{l*NvoM%+q8<U48Tvm1afbi3+{h zeIv$>Ti)G>;hqz?jQq#TUCm|>veoj}0S@S}em&s=KN{ADMIVl>`Q@;JDus!O_D_uZ zD(dQ9(#G(X3YsC0*o*RitpCr>P|3K%H4z>fM&lt>jM)`imcx}hN@m5KUXDke8SUSB zId0upRjM>{_1Qx}EU^Xt{Gw#+Vw?l009QUIwV!|Q9dnD8hY6!cUIwgx>N1M}8xoLE zk2MRkIy9Ey5=4UG>uE2q|ImFw{nzR?h%mu~CTT0QywuXYfv)HCXLmo?vTMWq7etjo zpC5(7zS=wP?ke8XZqmjJ*scien3|QPVI1Y39JjY6RB~@cRw`HsAnEA<+kI&k@U(Iv zThMLspwLQZn6q7T^*!ofm)Q0eAYx>SSH?SW)u+eYpC#VPAv*%4qTge>-jPoKrypev zGIG_F1Bdx08DYy2<Ju{q-)Omb1T$QcldE4leOOnO@aIKH$f67pXAEoSwIw_zrgTbi z$jI=YJR4BN$%j_>&H7`vhdI&GP*R+f{rZ{zs4>oE?(lE;wS-WVc_DBp3AT6-g)A|A z2_LmTXyc+PCWny`)s8r^)~b(Zz6Rbanh?^Ll)kT{XTrk`eYyo`3TgkosJZZO2et?4 zQ`{yo@7WjidkHsoPoLKeHbL2rx4;i3vqRA0tnebB@&U<_sIeN>TfJ7ZG;^I-s|6ka z2rxphKi_(bjQ{rF#c>~IvC`y1O}K<K%{K~0S~p%F`D@Fl6Fhj>R!++qf-QB*(Ozx0 zDtV_6G9zG`(zPv@E^XYE1l>U_Y5|?~|M1b5+nADh0KcuXeUW*_u`h`^9kzH2;t!zX z*w)8@Wr#Ked&PqnLWlhKK{?<#)xyU6_K>$S0$~4Em%qlP2sz#5CxQf<SBl*6-N3z^ zuvAT*!1uznl2LIhn2*+@mL;OAl?6Zj_4W|k!CUuQqn%~%wP)hS@9ZxBjE^Z(fF<eA z@ExBK;-^2$tm%P@R5U@8VfAHySuI<|XGZnPi6U?fY6Lzs6+@fw{^=9~xH?^=$UX+8 z`m9v;K_0Hl0Y%xU{nhi8RzIs{==2HUYY(=Has)VoSdUhf<V|2O^AwVGe<$CngA^~- z;y%13t=?bsAz4`voj9h36Kv{3$*`qJxC$^Xs&$BTmVmAepa4=PV!tO>Gq<D1Ym&`V zpTP6OmsvAhdTn!3*CSL$(3L3R6>2Is==ext-i6=x-Tt99GmW$qo9%^NMMY27&ti?7 z=sd8IFod&q&@Po=+431QoGhyeEDUWkaoCr$C-1e1>CHtob&`gp`QTe3<nwMC4wqO4 zO!FmU&J$1;@osjpG?3IyIO3LNE|Ni6?t|`0A!B;Q8WF_MYE-_sGq>zi-l93K6WjjE z1yk+1%^vA(<FRLo#&?%mb#wtP#CPh?2f&ec+`csZ!AnMZy-RhxXVU4OLKt<M)4;=X z5;|tP8RJGmvKp8<o<XoF4FQF}1GGR>8j$-(q7<9sM#~xEFwFAO-*<wOJU~2tLhz!N z&TO-orKa`qPDzJNF%4EUOMq{9{`Wwx`w-EYmUlE79tSkk+|sQR!0bUh0ZeD*lt@SR zLn)3l5(rrl2S&_N2UBmDbb(sqQjd8Ka!DH4^Pth|VShw-UC?t!79^<+GFb|yQ>Mhq zDd`()8BXy!EEx=bmE&mYO_dhptijw%lrWN)v&Q4IH|E>=e5*`d*+`$&P&#p&m*s(V znJK_1v_P&nGfg{tv2r8iy-bO9wAHdVk@<+t*kK@x10n1<Jx$rQwWqG^9jv~dP5lP` zAb}#b17_nXCNa&%gf@5I82z%V(fI#pr)sStLL!?YyCD_>$87qjN%hYR(E<onk&(V~ z*I4YU$mF<XueNYs@4;NZ{}h3n#S+zLbsVkvY&EswE8DGVlRz$pTuGe2_YMA<A@py) z<%fQgFj&^0n2~xPtTtPbZV^YHxgT8#|2@AN^Zh46Alp^?v-Dg)&*5!%%NQ}%_2we> zEkkh^(G<rwm{}?g{_zs3W%*ig+v5+JoeSA!osE9x7yqqg$D+~eti){0*EjT4!pCu( z*-zjBTq}B)W4snjkZk;2EUvY`#e)_KHN#WQd$ram@KB~x;6YCoZytJx{`LksoeFjD z7i{&oGo6a6L8C#v@Ig^R-}u2`?rB@Zni$vBV@C^K?k!nam*mdCNl$IxYPIDZtaxCr znX^XE17t)tePp0=19WNN!w~iXRFtvwmkh<ZE5h!ac~GVhWMBC{FCL^(tk7HmY@U$_ zGhUAEB=qq!bID-X04ulb;M)TEl{-PKx$BDI>y>A<f6fEphIy0oB62qVz=;9%JuP#J z_biUXypcq>7bL3h3EF)UyCXIvf)L_MdHXAXa_{3&_wl2&BiuSI#pl>pUXyPj%wmjV zi;xnu;bbY6jK>KQ=Q>}F77o9Tv4-vZZXEm8gy6+QNgKjPSkA;Ii8-dFt>ZYhXfqH6 z;4cAm5VpLnloamh)Gd;VK-VRSb&uC5f+3j6r8)D}P>V%w_d@UscB#g@182Ewrl_^Z zYH6tmh8B*Su;UEX9jzi2pn=?3#D@oQ8=}p*`8|11dO?5P!l7Ym0&5lstKs9V*jPBq zS%5J(Im;ZNn|P^GTXCxs@%IEUZcPLGn*69ggjlVKU^{Vp!}qla&-NP4nU5rz;bP2y z@d5O4Ysi&*&Wm`#{EzJAUbs<{uONn!%$t2?vwsy1wKoQ`OAqcgfvPY<9lqGGWUgNM zBU%3rNa`k8)rxCF|ElYte*`Y)-t-XCWxv#nn*RGLqn1>IQ-=m&iJ=6@3ZSN(_j2F7 z+3TxM9Wei)BmW4ZD(K&x^=<I3xE^sxHOmlV$_*;x-&cD-KYqWwGM4fFHqE7yKw_4K zzJDEbGrncV;=T|2?*m2wXnPkx1zZGj7GZBj9j!B~+FR=0U3VF@Lv`JAYXC{5i`71j z-{gqkUa$a^fK<)gdDr_#%x|r@H~o8^VnuZlu~h&+4%e5N;mv)Yt1W-`pb97^xH4P- z(eFr>uKyX#QpgGNL2=w{XH@aiZu+ogRVUD=D%`CYWxx@Ov_ls=<XfaxnpP3M71rY- ze3WTVlt(&-eLy|Ok3sr<_})j{pOzi5&id*c^h`$4lEHd&7gfe(WW`340-SC8z+t4! z^}qm>9(K8G{cXrc9$PM>`bfSY=n-?O`RYe&lLJ31I7G!7=)QU;)P{R1F5n=eb@N@u z?ejaa-t68?i|nIT5kF&IHX~!-)~Rc6pNeH-eon;9w%UJUZ&q6XfUCFtlKQ{bCQPVK z|BT_K6^D4e?d5UCINkuAA>fpJ;=V;g_&bLVSwsFAz$%DU-fa<<z%NQsRbE4d4~D#s z=6-JL-X!Vkx}krknm~k(PyF{1JEWxfP@qipuj38wNAKf-e&kOwJA}}1eaV4CJ%mI6 zU3DB2Owh<uNA+j>jh&Ex@vN~vkc~A{i%>|B_d(fsJ$6DTN*LEBFuf+$Xy{=p{@tJx zyK9>;_esFh(DWKknDW+kvaGi3$ObE=TlhcPWlaZ{7pWBj-^F=-$n*a+`%Ro&g8yI6 zlX<WG#p(5-WsknTLw_2o`5z5|zyTA{-XbLcd#>4HnF^(K1Q$Yj(AWl}g~gzUk+p&7 zc=_CyQ&sWZzuq=bB#g?_FhZFUQIuNAGf)x41PI{z{I9^*#XAP|8K!o#U$0=Z!@kWR zMv^WtWMj=E!>>k|Ex^;oq3B761~E1{j;#?g|E(4=yY5(@BMr18(6$zCr%zUOh^_q4 zioLQzRL@yN>ldrb9Zo}A26VupzxE2Vqb>d1124kp7_GirB~&@hxuY}!D~mZjoOJ1> zW9Z~ZXZnTq&PM;iMw03#Lx4;uwS$Gv=ZXz{$P~a7*zpp?@N}gY_JdGqXZQK<dbB3| z(>NJJRP>B`3}s>x<96Q?sv^u6VGeT#qr>1C^AsmLel%YP)OxLuU>2M0A6Msq%qfm) zwSdtbm@as{XKH(+Gcu`e*g-@DZM-L68h9+^GqC#FT+r9`@@CpApFLBiX-5I2;5RAY zB#Q6{#;3hz|J=O@E1uitjdY8c6WE6Q*=JhRd+3uLjy{L9D=dSP<}m+<nhhvTQ5LIb zGcFyw*7YWK0yYL?IB`K22zEHhU-kQkeW7A1+X_^d!GqQi$&xWj85jY<mkfU{y`K9b z2NMte&fGNc>18fL^oj`6m^1ibfe^kz@1vTUNw1F^(T0!VO$zE(;6+932?mQUVjNYK zAp*U*6UT0|&HGhzVWu>nIw<=3rpnx2TLha@WkphR!*|f**W;<Ad%Cf#u;rPf4<A&b z#<^6og9Ss-@19VE-Cx;+n?F}=u*3{xZx*B@wk(o)a3QdTiS7I$*q$N24G5ABv-`ZD z+yNwymF*S)8m&bzE-aPVRbnX&(_df*LIKe})n57TNg&vIF4g+?#9=Hf4LD{dUIxeu z4+JsjRey5~SY|P7lwZXIG(kQBAsq6mLtf;>(h+&HJiJ)Dt&=ukc}%n!=?tsAIgb7% zF7@9HabFZJWfVhQ$JD3tW4Q0Iz1TZez4zzKQGug+-m5LU0`G2Oh@oLBr)QhTQ!gd| z*zY*`scQSQD83f6q8Bh+ni?z0#`t5Tr?~f%n{yw%?E2@x-I?~ry<K;B5k!2lgCLv1 zOn%5G5zj6Z)*XnTBBIRBafy8~Z}z@9*;ecGzZ|z&lkc+U#ff5<vw{3KD?vX9$J8CE zv3J1^cg^nWk_Iq+0MFJp3GZ2iKq!p0@7*!(bXsGAU4)l(i}Z_97Fehz6kT(q!oT`7 zP&fD&SnZ5&wpzA0daliAc#jLHHbGO+^81j`p7+T+*`HOmVetd~8RT}aU*hfEwHtK= zlW(n_yfnYpHDR`C%y`Fa$pP49nHLrz?yBqRLJZ?}&RUkMw?aFVTP5m5RB5PaJMred zT?)2&bb`~^*`nks{^SJ?)2Z{A`nsSzaE0}A^>NVxpo^)kCae%&ZDZZlHR44{yY_x8 zl($g5`IMrGsRGUtU%)*8aocD-{$SgH#z%RNkXW%L+pWam`gvaV4htC1n=bw~H^nx9 z;Ho<j&A0%0eDs9eJlrUOvp)@69oT4smhPx+BHT1h^%&G-bB%{_$5VXjF8ech@q@+C zmO3yG!&9^Pmi$Ka8S#d()cg4&kN*&D@Syh~-p8xc4JvpY>W?Q@w|ox3M~Zdmx39ar zGA0v_U)o6L2E*MEsC{j%0R5K)96#$Qvv(v368!B<ZBRPiv<4mjC1W+tRV54~VKf4b zJOm43r!#7!FO}d@k(J1fZm9{F_t3j12%T9vKL(LL=WS{UQI^R>I(7!xvBgq3pr=Ss za6p?`1g#wrlri<$8>Kr%+Yuskd+U<y?Noxq@Dj};%woT<B%13;>SuiFRLm@Rwu_|r zr@`}tg#)kT+e8YBSPB;M45GB!?{ROogOf*KetiUZKG<ORK`7}GCNe0kr+biHH0yHt zkUxj&2qPgxv%bVy$FPZEn>)~Uteyj77I|LxL4hn*)>SN7u~b#MdAVXhM5ze>58HdC zbY@ncUkv^-xJM=EsUgyjEf9gTcr&~+d!?S(;-QH*+fi#Di8l3!H=&82$}osRB*R$w z7f*fQdo7QOk)hZyNx|*X+mGu71V3!~8}o5XPtMz90o$>f4IpS5s=zoAs9!`kkD;hd zv7BJOk>J96^|hr2%e+}u$GLa@*|WZbZ3%@Yvj4%Ta0G48@iyz_yRE51-hf6{PS~=e zzZ+fVe0aL@A7GFGe9E91d+A*}B4z_2_<oG{C&Qra{>Ec38v|r?Gh`_1|MHp;^LqRS zCTzU^mf51!k=FHJ1wJF`VHgpVx>Y1M5XVU%d@HFr3$QVug`yzj3GAO&fct>8nw!9G z$J^PG59N>tr$d_$ofTc%TB5$`as#=^pKL0Ms=}{92@OXDr^&&xFc@tCsCOs?b`J5~ z*I`{Cm56J!?e>jktu7@i!gv=Lx?1e|fs=rY<pd6b;a<SAjEbkc0EPgqC&65Q-@PQh z<zTqS0T(eV%b(FgMXBl>nU1B~4p_sci0J16-SEaDEj5Y0<l@a=vuv|m7E7@XftDM- z&85td7f^Es4WF#pmgiw0g^86i+>e1I6-!1w=o&8W8(+=qs2j~w>PTfc%3jiU2urB~ z1uX9p!wHfDqomZy_@n{U@?WSjoG%}$hhAdz$%<{Y?mf7V(@n!0?=4+xcD{vBLK`@p z(C5L>6aXJP%79?n_&!&-BfCGc9C<SE)32OoJI6Z$lbQX9J<Zp_Zo)|<t9fM7X!NP% zVKsKn2~t8@Ai?is{v?3_<V_hTt#9?df&bAg316dC6sSz@Bg5#a=DbwA+~`Ghw6&z- zkV8u|Kh!El2u8O@d*yehHC)|R3EMt%Jofa9#@C@@es>c3sy4Ry5evK7iI-m+&qQ@d zW0@de8YFyKudI2s@!mgmX2EO*L<AS%GGNW}^?x?je*a6Isdg>*mCRK(FWWqq>YnOF zFXsD=HjEYQC3HOVIb*_(xvn8s_~PQqjg6Chs-_Tn2RYDchX5CZ8T1(wHi`i#uqG~a zsgJ{$4L}H?-b2MWU6W2DT4GS?AWCqBF^6+vjb9Y<W9G0*W<cJkxp0!dNy(hJ91$0T zE1GDttqL2Iy)AgP8ufOHgm9@#fA0=UduqGraB+9e8raHik4DH$nEL`YwV3nvK=0o+ zJ%w)Wlwz~`&%vpA>Z%fgb|fXSZA21nE$0B_dJLY2F{tQ#{IR$wb-Lkcm+G^)S$-I_ z6szm?UlG04dPGr}CHHwFu6D3c)8(9B)H;Z<3_1I7LBRyzGTTdu1yplG6V^Kkm=AdT zJLSV*xQUGY2<1@DaUaON*z+8|jCoLEoXW6T)Qlp)m3z~xQMV~K#lw%%Knx0<u(i2( zV;(*pwr);&@UJ<8DP0dBCdbky`lwCir_-li8Qp$wZc7cjr%H@B$UwweMZ7$RM-%IQ z51NZi&7Zx?b^Q}^Fe7z0Lri@egW*y3ood||yomCM@s1~4vvE0DUpdb>@=RtS{}3u4 z2}k1eHThE&KUP1^j}Df*p1~|40Ee-ndF#@-mivL`g#}-z9%4Nk2krL^$sgPE>JNW4 zCnf7hAu~Otb7y~A)`ZEarhN;;1SSka8bN_I=BZA<-^{X2z8GQL$DTe5&4CF`N1Sv# zYx=X6IF>=y+_JfMyXNGU;aPO;nTo673P_G@MmwVkJ`$KI?3MMgb~ZajG3mF0U%b2b zZgu)t$TKcTb85(tHNcxAq?9sAFdYb4R5g0#;BLtvjEIBV)ngT>Y8~KZApibL@kn#C z$L);`6Y5!<ntYyD(Ea-*JlFW#ijDw?W}=b;@rSX*a`_bw><27!AyA(+Yim=m{~L?o zCDvIWD2FYxK{JEQh)R}_%b_v__KD!<1?Eth=K(?~_;zWHgSB?sWj^l#bk(mm)pg(P z%zy99E}_P$b2E16VryNl303di1<{qn7J@22^PgA9(q=?r#K9-Si(BJr1@{mglRhFF zSWaJZwv2xraeXe_ial=*6pG{2Kb$j=8sQh=Q0(j}J<3b~+314({0WHZlI&l|r{1(& z-1&nNu@-u1IGfg8C3sT1?aK9AX25h~L<0$#Xm%z%NU*9Nc9+ml(_pbg=#2>n*h6^b zShyQB;Uj8ogRWGEv>sBkH-S`yP{kxdj3gs9UEy$O0qB}K*sx;YnUQXc07C(Uk`;nq z1%MIm&00O@LKK5(z)`Gq3wyyffY`X$%EnKVe;<NO)}Jr(^;<hKL`Yw__W<zIQ9K0= z3j2Ie?jj}{#4L`!hhbN#43|0GoD9S}CwCKZ<r5Njj#4NJ=j%`%8a5ofwB=c-;U;V? z(YdC>P5{so+1cVZ!3LX7{@eu`n*lE8O&hr1!tE1vrj2OVq@J0=*Y}FA<j%GY%Tcuq zF~Qg<LFujn+JW`e`h7Ft+DY*9xCSIlAgh=k+9qO*lLdcKq%&*)5WUn=@_{b(V$Y8* z#no8?NsJxq8`-q>7J5e}Y4XUUew0^@Iumb4<<_4p0K=E5CU0{3TpP#w3i>|5Fhc?z z2(0r@Y{X|>voAZe=l@W9A?tSwI7;SA>i&t_CUZvY?ui$`REx5D+gqJ2N;JP6`kC2` z1$-erJ4pQ3UGJ<<H+%ftT8Rx`V6%8;v-3vnKLb!efEIi~oQpc%XAqT6(`wo>%CHM6 z1I)3!eK!&S_&Hc7;cG`B8{%b{4@;g3?K8ipKy(P#N70;J_zdp7aN)y&BE(p;f+e9> z-MciQ_{sYRW|KP9!gVv?rYTy&Vq(3tATz5o&XnCT8{-nCemr`9Z<~{FL+^v2LP1uH zA^@{?fYpuHL7^jdNw`PCHs+6^q7yJoCiKJjZ(sqVOT1Hmr|d8GM6SeVkcSEHhhF6b z^vTG+?N+<VF_IsZCfO5r0Qo`Hg1wt<v<)Xg&Q(SD<y=Em0u_WFW%ni9esnuT6~&Y7 z0>vivWP#NqL*pw_u;-(cQBpkhIm!~Rynk=&ioWXy@}9|}VqKzibsc96HeOv-hClqI z2#ByHYJ+R#c*)W~bqrp3)Bn}R2a?wv`;V>fni^wk>!6C}-&}VPxM5@^P<{XlQ@j_) z%PUuxmT-YU4I{2-I=*Bx!OOR=c=AV_w8_8gn*Xoj?Z<Z#cdo9P<b5B#VxA7XetNVh zb#&ww_G=`P8T&N6h?*}hSuQa@ZOtb$1tPL(<$rPYOGXS;mJ0|u2fm<ag!{0NJ+QhP zj7qG+gGxW>_Py2_VALm|6#uK`fE8<!Oy5G7&eJ*va=UX35umJ0ShYy4N@lFvh($=6 zHL2S(#bGA#4+kNoZ+L1nFCOdurw10f&bi1eaVH~M;IW1v<*82@uFc*FPCl~r=^j)z z&@#iJS6AEQ9Hj%Zw$9f1XC(KCaN(-ShuwLwVlxt=4x<xYlk!yTX?M_vhCoJe3v!V= z<tq>wgicAx*aL#<I^1N$-ro?%AP+XAqH}H_<72?_9g3C)4u(+MAw0}>d+lHH6~PV+ zQ1afU4-JaL44&XUNaqtk8(+^GrKwwhrE2njwC=*DZQEOAHiBdueb8t~D18B&4(A1z ztu^Z6o)Syc9ScD^&%lK@^)@%|N`hiUu|yN5zc5tf(^Cj%8hW3XIXL07Lm&5`Hj&|i zb{HBif!=@{Ylo>{z-56D$bNdjc@bsK#Q5zhiV7xwN4+jgSNZy_+?zDy4u&H-R#aY^ z-gu9(@acOsV{Z#13Okg)q`wa(68!8P5Ljy}(uSm1&19`{)4<zEbzn9`x=4AvMVi}1 zwNPvKQ~z)^CHuw?9WiVLt(#A{aH6^umw0<#fT+<SqidP_hR0&3bJ`Q=%A;v=EA5#+ zxG++kZ0&QNOMbl_Yw+;#GT2icBQFXXr^bVqxn%aNo~YO`Ht+r}qgT5#4CcO`V>3{S znown&p<bdF1P^geLX+t6*%OyGY{o+ri>S(=w$k73@C-61?o8jXhLothx9!@cnJlbk zBg<GF;`Vm1&?R9dk4mUY*_qZI`4e?z_xaMmj;><|J3aWQzv6#{{{;XII2J8GR(i)- z@<U{P(p<AU1N}`XZ*G{Er=+8%YU1_Ry3B^;sz1J_7=`vF9<P~jThT`|O#AY(IAJFg z*l+iDZ+xvPJ?1#XezQ^xZzCM$BT`lU_})u)CzdlHk47LyjK*Wiyx_wIwmzTvywCs? z1!GV{uup-ClC=9JjJz34Fop(h7!rUTt8|cbXZ1GCAjvJIm3MstA&0|D9<bnj6@0YX zG~vthkqAqG&|?BDN6p{PR>>?yx8IV!Pu&wY;}7yzqft;*zliCY0^EmY{kD;G5n}#) zO%Y;S6q=P?5|#Jqnhyf-imvOQu)8lLcZ@Gn)mNBNAfpoO;_y(9314WPZ9PKzz&_v8 z6OvA!7l>RCUh6^Uj>QH}>2edoh7w{P7R;JZPN96o$FwFMR=^Wf(*pr}qSC>}A*&-! zauA}o&Qv6fobD-Mq*0m}*wYNqMy(d9K_zPjH|^gf+Q-(G=YdA%oCXdIpkhSJheWlZ z8n`b$$$uwqGEzYNE)d%1<l1&FnzUAn@GNi8l3dBR--#F@j7OypWiuK!*@cc=$7E)k zZ{3XI;vYLe?gS19&>uuR<R8TMc8*TNOcm^otv=M_Mc9kU!^QA-LO3l>MD=hsqSJ+~ zVNgsRbk1h*U$}TcJApp?6zhjLxewv5qMj(bs9*y?)2u@giwlO-2ek7}<3IfZW;}^m zIvKWfz69aZ%X+RJvBL#|A%o%&*sNf4pxP7uQ*l!SHo1a8K?9Q7Ey^}`<xcI#u8T7b zyte6P+>~{iYD#^})9{A1sFR5Eh^bo@d9G$^Uo^I6X;L%XVeA>4M|#?AN3A2%fRc26 zlI!5iwer#k7pg`KhE*qjs^INX!wU3@YldH5uz$6?1|l4yX6><+xW%gK+t{y*y!U@F zFFoiZ@5gsTLFe^a{f8==x#(FidO6^Tq?}=o-nvP&ub<*&)>Ku<OI%p7F5=KE6F;T) zzlZ#HGeafb;$vk0Q}^57s9vr9;ZUSDtK=C*Q^PLOvh$<KE0$a;lZ-o)EQ%4kbfW#9 zNeI^kN)vG74au&}?w4VpHC`>*pE$Q=mnP3)^1^O+S2<B_nL=PQKXLt(n)>3^R`a#p zI$_o4n0?DtGa=$Aoaf>7RB~XO&@3W?Vi4Wr1ewE`KG&hN`zv<+v`Dt~`TKlv_}q+Q zAnn03*ih7{LUf`H^cmh57B#F6?pqBb9=;16V(be4jjIb>AVh!#i7VUb@k4bcx0r_t zm5M{VU0KLIsdBT79_@#kf=e-_A&!4G)JRajVads{Hb684V4V%M22oDxz_iB=^YD~f zt3&%7t0x>sNtW#Y9z!K`Hx7Ni>p|eZM64(a0fIZ_ljGdmNc=UaTbO!*wPClJ8S70A zEWv)HA`zsPg_!@bYR^u-kF1r45Cuw@$fr38t7HU|E6v@c<)8#3Eh>H?Z5FEGj)^x| z=5z|{Fsv-MQ&Mxf)B^+BRxF+}!_XjtYO}#-Ku?5B=1rC5HRQxvDv1v(5bL`wIt%Wm ziAEff%yghzf$?wM1mzUgpTYVVlWIua-Fv~bp2nR@uR?Xm5q<XrK5KX_FqMWxLp{t> zP-ts<->THN&hmzK5)bLGahWA~-8|S<4*HAnTB7x}jp&lPjX0RFcc9-$Itg+^I?GG8 z4ZW-)69q^8yr{2oQ}plhGpwA5iEM;6JZon@zCOI+Ak;t&ZzPCcAa`9u&USHlmO0|t zngLvM4BLgwe6jjP#tby1WDuLM50Aa7_wFF<ATG_spfz#};5w$j2e3ot20?o4$qd^l zZPuVwcVJ`~`Xy4>c6A|5&8SVu>TdE`F>_(4Ey|ZIjJF7*-%<?RNZK?5vt@-dssnue zEk?KiFiH!o79o*?>kCK0?NzgVilN)4OOJ|;W`8I-w$VFjbXSdN0ib;*Q9uyYcFj7d z_D8s`R;=$bky)HSI<BM+;_W1F-Y%vBS~&QJ5b+|}?iaPVe=vVoUsRu{5p|ePTEtm| zAYnP!R(7!uq4RU(%o@F*-h`AM+xlkBM<x9*E}Ww32&Xo3cFU`!Ka79C5yY>ioWN6* z%-C64o6CA%A6;5qc7#B~F$bN^7DI*`O+9X5#u*p-7h<O4!nVrCSoN%K$zJ|zZE2qJ z=oLO#=;4Gzk})B?U-9%R`|;P2<&!_V$|&uXP2Jjsb3^Xk;J7QAD<iAWlsVz<a^D<T zvh09Da<6OQRF`oF*NjkP5pB{M%3V+FaR_~iaYV)AO9$>ae_6^%?RWxO7S=7FhA`Ei zYEoY_s<q86;et&)sBmONis-|}Lq$hkEk~sQEI742U+p=2DE3ACZZdp}B8A+<)0H{f z*Na%#mB)k!L}kK=#+Sl>lw-IL`L-ISv3BGEb5vI`MO}M(EWy3I<#Y1AX)$f|@o_WW zfW>-E|0xI3C(iF=cC?G1NrB$sCom(do{U_<W*j%L2uB~kNnL+q;2=Mpno)2y?-f-- ze*{Ys7roFlp$pc61M2exW54!M+o1RKf!Sbl2+pnC36uPXfXf(|cCpzWXhx?nhEHUG z0Ol-!y0Wt0JOCO8n>QfQfD5EP1>DQ4AE~CfNC7191QF9*2Q0vU`#Gfvx>n)3xM&J6 zIpNXrfl1V-Jw&hUMU397#qe8odxyMxsHD4d5v6<}qYNMr<~{Jx3Zt>jD3H-DpL*Sy z0iOVp%?Tq+yd6urv8fEDLA>nw(dYya!iwZXWEFUg=4x?|0PsJ-&tW%9)hNL!(Idcw zS3h1uS`iekh|P_eg0(&RumDVTh(SyMVRx_|^MaonCk+HS(WU|YI)D`L!e}K+t`2y| zbdsk~v(svQqfuz#0YC+cfekDZ9qc!Y7;XJOnpw`<D51hk;xcreFQmc{A-`)npkWdX zi`~ByO^B!7!wl3&;bg#Kv-%E-j8VwXs_QAfoiw|LWv;isrU>;KZVHN*37eCnjmuUQ zN_`+FT#T;_-o--bwm{^RJN0FrAeoVK9-Gv`ED+e6IWBWaB<kdHNd*Rk4lqnCF4jhr zNH-gA0x<tuNgZL8&^VD8a-hsCkAdL{8bxqaAYSm4HG+=?#|63_#_Qs7!-9smPNk#x z6HQ(TiWGe;yMh7Gf5Bk~(fP<QhezQZa7l8xt8zrn6pq4`q;D{>@7M}uurR%EMV!!d zq4r89NB`vxm{;Q)<g8f);*SLUe5b_AURKuQEngWK6G2@_FE3qagBZF!+LIIkJDgHz zaZybOz~$dPA<z0v0WN0^h?@{K?h$-vw8PX#PfKB6)z|mb{`(l2D!>BU)3}OF*wwLC zXrLfdhYjyNO{(h9D6IlcDDt`fZC}7XHdLZ~57b(O#5Nz~ChWB$iFm?%8^~uS%BlgQ zd4vTb76&^yC)9_-;l{us3_bwq_47W@mF&=q1}^FGS-1AM4`Q-jR0Ob?dQsv{6p18w zB0Sn*R8(bnN`_eo8?yy%c8e_{B>8schT!s`-D5Li7Vn4JFu;7jl!caQqfO?(BOVoc z>N{f=1D#AT8_|5x;-FH67M83Ihk@wF>TL$FN>G|L#L&K!hN2v_ff%-`It=CjK}pOP z<XEJ{Wmx@$o5%%@J)x@KgCi&Aea=Kv?sN(lvBUm-SLBy-?-WUK?yBQ5c6^^sz+jQH zzy7g)5Eyv>sJG7kcIlY0pCEpN)&rV1YTh4GD~m99dVbgZx`Vr{r9T?I>(OwzwYDcA zR8m7}pYHp|j1W~hYN~~|$02+I#-h09kSvhzj5NhOhxdlIZoIcKI`|1w4VAq8o+dNG z+qE4Se`WdSR8Ii-Cw9_7tRLg}xw9?1U`<jZ&|!+bGSxj%^>T)S;EA~~tO<H}^7zmL zqhc)AeLs8l0OR=KMbE&zLgnB7iN(!+DHf<6;x#F-h>LBKK@Xoow|MbJ*|Eqo3GX~P z28<w0uDP#H)s9e8=k2>AQzZIRU3y&!iUo}C5Q)r^LkiACggo;^Pn|iATp(0sG++&* zs<kZia%+xYq!~-zmXK^2Jm@E{FL@IxoH-9_+%{-;sIOLBskKh1zkG0CeCH3nqu3jo zN2>8cp5l7)ElcWUFvr7Vz+wU3pI^t7F-r!HbP+rtVmAiVV5H}eK<H@zpvdZ|7%$nm zAZp@o4kEh(W-w-&zVld0&vxq`xv)f%O<Wpt{HgBwYPr!ratNFe&c$@|4STv1ViPE| zSIbrRn_1RBevS`?@iOWn{%7`?K@YCG)DSkfrgv}Ugk?3_2ohxGcTd=LRE#pT#+`oi zCn7A1p>T<Dx;ZpLLV0g*w+PXwi-1?bUED$mI6Z(IV|a{@43M`K%rS5=oG$(W)&V%U z#n2xKMA89#xo5jVrw9MIH4%_0QhSz{v`!~TDhJGZ71kN#XQH9kjqH^U$U?VFJJG6O z`!U<RJq<3iRfwvigkNV82c~B=MkYjByqd<qw`%i+PJ%N7f6a%X0Jl)7fSd%pU!%y@ zIT|-bB3->?$sQqQf)^*qs8G>-@edQ+onQ!#v(3&AEsR@)T@*VvfH8oOFzrDf2f{J3 zGA!O1sWK~+w7_3;-Xd(bK}j~zl5nuwj%x<PR*tDO8Os`Ad1IZ9KUd;X=YS3XM-SR^ z)^k_g@aaQp)UAmAINP1b8u0x%7e8kqoB{>bECS$D&cgA>!nKczLAT+UB!Xc|va&Y_ zVHm`d<GyBK!ZIn*1jsLrL1By%-*%4_B{nSnFf?>dDM;-uX5_r3Av_Y;tKx;nG93a& zJxxb=#)K*ttK2~--nku(yY6xo>1;2V6&jT4h1U2|u{(wRm?XIm2zDtvv5(Hk<-&;0 z1RMFZ<N*-}$S=ZXUe0*~krx_?$@+vjgC$r(8FIGx?ulKXEs1^K!rKUIAwXn6$-`!k z(L1<5+&oy8yPd?g34YIk$^Y2L#$1Yd1CW)EFjmOZ270bqV4FVD?A`bl`4o)aqCNLm zEujOwuU>Eyy(#K+$V|l;K7{q;6c7C1Q!O_6I3+RfJCGm-Y{J~|R2Cu@$i+C|t%|hh zV_m2^GI{SZ01x_l5v7)VFak6|JVp#na>s*}{V@jp^9opM9vF{;Y}Lbo)qkSOK)pRB z@}|t!q#K^Zz;7z53F#LvrMC}0x9LjqiGq1!J~pD$1FP@Qk!#?NXzJ>0n~qJg)jg?F zFWJms1W*#gMXku~gvOb;97hb_+1m?^6L>vl>7LsF2o-}jz*U<*Gg?)0&<;SQTh4hC zFipH5lt07~aO<|gh{znf24*pfKQD<Oi$54T<{+mc*QG&{S-ZUiWH~o%>%qGS>6-Kn zkY-IHOb0S`&?R{V(QcSZ{{uYGbScbrFZ{t~VE=y3amzb-vv5B6zspL}>9l$6%ym~+ zC!K<JL@tc^kWlt)G%3K1tm|z?b7H4|@7nrx#6$8o+;e}w{ld>@{l}#~vq#LtETRew zqhid{k%R8HgRwb}I(Yj71e?NPu6e<85moWjIt$}H25Jk!iQZx<y7XkoJ5UanA+S=k z<?cPXci>3y&N&vEYz+3vN&d|R-UM^FcnsxE*1oTOTs``IUecdFVh@!8QkNoLu8If= zRWoOAzZ^|&`%v~p?8HNHc&hc>J<LH;71PdtZ46LQZB!{a)r`o%&K(7<CMXt}gt*nh zxl`MG3rq3Lb{TLh`xWut@%Ea~1R{*w=H%s6*$g&zW~FkBD%N3@a-_`a3F-s&x~8~@ zNUH)(-6+&<LI3l<y^b>;JDrYg!f>F7$1{cIt=M?LMmerAX7cr>>lQ`*b@#bXPkE0$ znvmz;*{Y@wyW9X*Lep{V>*-V2vrm;{UPVnb*ZF@_wfTjJyY3N&FXR#xltrB0Si8_M zzfR#Qi$z|9`0*PAo}w(T`b{+w$uF*_TyMr@o@1dnC*^WQL7b&(?V-xqgw1Q!H>`2? zqy9&e%!Ti(9P^ppk2O8kgO;K8BT|?5DQOXAkSGTpW=vX5pNFQmRCUv`IP2CS+i1zW zVadX&$anZ?*(jo?s|G0OT={AMkMH~FX6`C?Xb(<7j5nORyV-D(8iY=rdQ#Y+n(7N# zobcYAvWR`3o@X4*0suys23pNy#i<X+55rRqsoy&QGF1#r0LC}o)$IKwZDu-6szy*G zyK(LAc)!|LeI0iO{Wv6@)RVb^ru;0NoO44+(tJ<00j6)yi=?X`4hB3#YC*rS_z@@- zm>Z%z0)Ykn|0QpOx?#&=gvDPH6h#6K#@q5Nw*@<Pk);iiRA}3DRq(tlY>@ohFyx`L z!nzu0E{eYq;Pwl#b(m;8^{tl`T_Jx|$TCaUEln`s4TAZYyhCc`k7ZhPN3aOOO%{U> z2kwY>WN}YduguLLRf+LiHcR`7f}n7C0>O4=2GL&VI|TV!bl>nXbqgQ&0W~SF;aE>D z+vTPWO(cYkAhu04VJz%G0$3w~ON;^@up*EK3Gt)}qv3H_mSC0wu7|UL!yq&!=kp*Z z=Q3w!a~8aiK!4&0W(qy2aPOQ-2SEtR4v1zf^G~7aNh*BM0dm<kB*iY0xh+<v*Fq=^ zKbmo1MjT8tAqL+_P^3^I%6??{2h2uQErhWwZNk>JHf+&tnk)DvJ5idX*sK)7p)?3_ z=%+kbcq%-%pyfbCO!`((wfjBU+aP-drOt;vAR=ABN2f2|&viOG-g?5O%Pk1$2Wl`0 z0PZNzJAq~_TH$r2p!j-YfY%QCbW20d`BNyAcQ|drgNKK$eh-3aUhZkU%Wgpc*~uC@ z){r}WsXG8T!EXerimnidE2}o~G7E9jU+bJD&snn_$=CKPaM;*3MusemiHGKK9ltZ; zV%Cw?kTVab5el?;NbnPX^cyM}V6%yI>$yMS{ZaHfXFkc*WLbIM7Z^);e1elw==tAK z2;+gBfP$W%{vKX*DAf>}T+SLN4#eHOp}#h2V<duT=Ttfh5Te8j{1?v+dKMT-f{cHe zIakevds(uL4Y#|*&KO(>B&VcrSbe_f^)bw0P(*!t$Z9O<)69Ql_c2gC6^#~pE?dAT z#`C#glAy@Xfv<A}OMMkSyaELMo0tb>KqxHQGXR@11iFs(*tP*26#RRL7;Cc|mo80- zi)yhkT7cY&-zP7FygSE{*+4FS0s<`%>nrZg1O3#XDpgaD?gAgM5ZU;GgI=_q3l2jo zZaVIyt#CJHERT;bxLhBPD@iFe{cvzn{v!8G;#O0>$gB3u;&1Wc5bQ|V*qDBg;QW+L z*T>#~t&JEHw&w>>$iQ4L+IyvCE_Qe4!hS&Xy5eg(I~cIQr5;7Z<EGCUcr7e1b-g!x zarDobMs5W3@S^z{@|JGV&-BA_=9(*YkDna7stHO6io$ed)P891p7mYJz8W72{Q7z9 z(KKK~44!hanRdr<>76cN=YMBI;<d?4$ro6|xQ2+{syDZY2UaAsvLHi1V&|o;8-vI~ z#&l8kKK@wU^tmy~z0v^e$-Vw4g4wo>kum81>@YOk&avSV(cEvEWqavBS;7d|18H)S zK&g3IzN;%wqG~5lhnRZPzLk-6w1SR9O#B4`jRyKp&fqKpA{OoqjtLDIS`X=?2f&>0 zHnZ(Ib)E?1|IK&I16ZLA^sC!4BYEv3yv3Gt3+0G!6jPh69qlQ5+6{Jc9rhBiwOl)l zP7mp_tNJf-+xiLSbb-IE|7Iu({cf=`2|ADhK5FdjUUkN+TBhc_T4pWT!K{Nm90F7S zOvWS#VB@54eqlNrDugo=IB2Sw6}yj|d2ROB;RNPiGXp1QVn9taR!teC$r#YXzq;NU z8@@~INF0=TyPQYFejG5rALVRyD1}ifq>XLPsvi#AFvjvWHU+Rl?L}G*qRRd?obCcj z^zR{^FiE&~mOPrUy!bv_5m^d<d(3p^(7a;#uM3b=22-M{*AY71O(3UYj%F%|07@u6 zylRv&w0ew_b2sMVd+^<i6+>OwecKRudN?I!8LQ`L%*P<M<)I6k=2)i1JJ1jWrsR)w z)%@^cO*I6&ZrVWnM$uEuD3XDAGWaQ0BnI6Uc=Waa;_7YHhGb!^qNdkiVvE*btsH|K zQab=&og;Hv+`R&}bt;1z(1u2P8iJhgD~X$fIyj<}yjdcE2tDIyOmx*1q(w=uZWd#@ zNZ$Jp!ZKJ@#9$BT!&Ev#fjhu$wl~rVE=*?om44)C6M69g)S}(X#?ePb(UUVzPI!HN ze*e*GxZsRUWf;;BeuDw4auHra(`i24#Y_l>Fe2Tc!(h&&vS(~Xxb3@uCs~>Bk%2(( zCZB8cJ*wS23PA@8M3|MW!&m^>A6K2)xYT%x1X>C*tYj1gTn3m9%D%kcY;fyQ2M3}9 zXd;bQ{X%<GiEQuI5UJbS^&5b<JJ6Uj)ac{mm3|mtCw*fI`ykBf88P#1KyGQ;30<cN z8!+W_jxL@Z{EB=UVn^a-D82TR`Irqs<yI0wT5h4|7GWMXHuB<4O^tVoAQ=mQuF;K< zGqSOM^%*diXr}mkuA@+WYI{`UDv+6MpoPSbp-rM(k3j_wqMdnCo*-X@LAmFu%}gNq z_~v#X@LSQyNDbw+x2HBd+wC<{g%_ea*k(8YL1-Pln{nM>%j-pNh6gzZw*{hNNu01P z+F!hNk?eghGcaRW=5Jj_N)-@OFmnfNNE+&NH%W(>vf!o}(A*}x4sHRAf?V=p1h0*u z{un^+HAl(=yB-U>ql_F!pj}|$gH?<zE*n8Xab7N&wfJw(Fw216SxP=wg=(O7jh<EB zY!9~uRyc+nl1_o~qyv=w`G2&bK?R;q(YMR5<SB+YHkU_8NVX|lx-f-EUmz1Bymh7+ zEZB}t_WL3k=l)L|(5_n{x_bGY;|zhs%JdIVRqoU8aC13{%Vuryi9<}s6dHC95InRk z7x6C!h$|D8dvIk)w^>#Qxx}FT?cdK|lpR6|4|X|5ez~siXxmm?Pa3(j=A#HkYn8-t zlS|zcu#ked255`AZpQA4QrN~_IQu`^pCRv875BG9zK}c;j<Bt@EhQsmp}<l>;gP8x zcEcY-dE}*J#ld~cYbRbi_LK2>AO;m7zUt+gGJuqmTvNoLwGDz}D;3?ju7l|r@=``M ziHx1BD`3+^v;8M8?LIa_SmAuX$)_*c*FSN51E5d>WFFmD>Cv%xRF-GkD&zi{->Hfn zT|9&2rg=Vw4W>t;%W+B_NQ#k4gw>kpgzgz_5dLOMLuud2wi_)6AcirhTRrfztV|^| zR&lWFf*F~%cW)8}elFnB>I8-0n?DlPgCtrEHF%Py2gjvBefJ0ojVUCCVNxOzCJx7; z+GPXI8KMe069+pml|*IU*tvnh2=FgALa2v102uV%+rTLJYRddE%}EzK5ztVcnItZs z&=q`aY<Jk%(SFIrA?uYPMNdWhnj`=}h`{W8fQIIag8yqQj(ZutBBv58pI&7&3=Nb5 zY%b#2Aax-K-@t4T%S>dx3k(5XxG0XC!BlZ#<3ai*#zp&HGf5cj$pr`4+W?r5moEx# z{2sw#HrwdW@08#G*I@Cwp)hWehHd^qTM8-`$pn&lYZkLYQWM4GVio}=HQHC;(ftMM zG@%*CQCjw@QQ6(X9eW;4n0PBu#zV@ZOq2&MGQz(gaVgn3$KpB!+WPZm;j05QMh-{= zgfy5Sz!`yBhtWSh8nGH2RYcg1MuTWfEv)Fnq+l*1DdRD2S4RsFUfdHxIY;etpNpGD z&)S*u)+6%5L-cTfAkeD6(ieZ;g>W4YRq8&rd4K}B%|?L8z~paF$Je9iBSX%WIQ;15 zpQqD+;P-i>`ln}qO4dLPo&X2|nhr^h>A~^FRSWF4X6(lo4|}U}ace4BOhZn?wvF#T zkOk1ZAQI?(3qs)_%DQ6Im8W}h9M^$Aw`quPiGLn0(Ay7sbSkvnz^ILxFTjen5`Sg^ zCMN3Y&zf3s-Rg;)*yTV1y|_=ekE3P+#>IqEZ%}wPu;4lf^)!02txW5wG0$B;fLZM& zHFqWE5tsStUi7RT`o@kaCv-*bmhVN#NcCScVhocRq*#Ur_D#ry<~j%37#V|c<OJnK zD<=`R4l{!sNA?bEG0n$$A=rKv*)Zuf`~jVPz9`vd^}U2JckHmGdwR~{C-8U)j=~Um z?jjlq<>~eALmd4(tn8g7Ks_PMPu=2T(qp&?yA(_4SqiWdv2+icIfOkdqg#UmpI3r< zx~>BiEn+L?mr{bSqelQE3IfZppb3S5-gXQ?yqnx!6V_^O%EHBufN(s-z;6O8STu-5 zG&kXeaezq%?j_cAIOZ<Zf{XW_V5lAI)r=`VBR$B`DJ3oy74tl>9VC4|Hr*gsMxUG= z$W8g2J_HdX_ycmgb5n5McSi&z=AOp9Ic(V)ln@XsBtq7X*&7#zxn>~(@8R^C`1*QJ zAQlfMCWC5&f8{0hX3dcIGLvV8k0S>#+sYpQJe3fPI6{EUD_1YJE?JpyL0f<P-Y?R- z@f+X7TEvY*v}pp2zkTQ9t>xP1g#NduU0PRJcfaOcd(Mr<YxZ?l*!{3N1;eksEv<va zqhm&iTfL``ZDn`h=UMBMXqDU1H}A%tm4NdAWh-7U6fna@*;gvqJkk@f_x`+0ebWS~ z(~1j?x_Ky)*Wd?$YDeLG;Il|yyBW<U=(NvMky2^uB+l6utlNO>G&x~+3+jg#{yIsi zCUx{&G>HugJGbj#(h*f(lEAJwL&!Y4QSaYv82D?Rd{nX#BT?r-D9@;%d>DlQi9#5t z8-M3X5}j#UXEC1HP0y_s;m|bHbHPeWD;*mv1;urIGN_|vV!s(*v>PD<Q$2SwmZGg8 z)ed+Vh+ghkSi^)Z6QR60alw%B+Wr#ki^9l7kS7eI;lQ=C?ZC=Kdggm6WALXa8-098 ztdDHQZaxle3jChXhZ8ywqP4;t5QjP2Mb|RtlTr%{K@fjI{gA{JNtoF3!3vQx_HBqR zaIl@-*W735!Nnj9d&#V`w*x4k%BT^~w^rgU;JH94j<^Ywl~^Q#AQuglI5H$$bjSOX zZHAO1FyRu0;B*hEBbH*x3CF(`Qhh_rDV+u;kiT-`shuY}t(HTK76)1fZeXWbrrSHh zgESLSm|+$2&)Z_PtPr~!YcU(cI|%+{LO7o9&Ot4lZq)S)7q}irIvV1GsHll4W{!d; z4NdZZRKiqbVUf0fWPl)@+u?bAtAv@7bjl|V)e{#v+W_yKVJ-%2N=orJsEqo~Y0Syy z(+A-{^$-*-x)d)4rgDils8Z3{Ngqbe8dtW93@;$KX2X`bY*&u{y;Pj9+)dLM*3nbd z_#UT0(?GeA#9ei)N3;p=QeiYzipenF3oj|n1cbGXEeLCR7{lky+6A6L=y~h1%yx3C z6UTrV4{6e(#w|Z71_yUIIU6uFVaPP;SlQ~&-YH0200_ZJ0zO$G%k8x(rk>`mgczAV zpUn4c(G$GqjQa5{TTr4lu-x7)QpVJ?8956ai1G_Is-xrQFx>0CU_Iu!1z1{UhLtJ1 z?_+IHa<9xB1HmZ_V1_}72Mxo05Gtv9U&P5f$iOuPn0T(Fx0y26`&_#)5MXZD>iUK7 z2?$M<`N#~NVE2PTkq0(Ga`dtHK_CO+S~7LOn0yBv_lZ!{Q7QZ4WCN_qdE0A;>HF5; zVw%#tNsX4tL-A<%gDEQc(*t@0xUgbbx#E(yZCq~s9Lt%ONo-3j+K{pTjELo>&e%<8 z|7j}B0ucEO+4?B0fNvoQ4dh(T<)8$uzjD|j%*lOF8=_I==C5%QcK>E`Jm<!2Paz;@ zVRymjmyx8wx`XVN@y;AX!rY8R;6te8eQ0DT+Ea*UmXR3mlmf=jcgQ*1g3lKcIvoZo zWFGr19z|x#xz&Z<he`egn0&$SkLJqO{A-#X6CIZyyoScQc?nyFtIdU};2s!YM*j%% zGZ_=7h>#r)P5D1}qFK|+5sk&szFChFPR2RU_U6vso!?BkK7joYMn!9Je9C!4o>KFB z7I6tdsqKB!LLPwCQ4$_5#4mVBKl{t|@8i~e!4Sol0}Y7nl`&;nstw4!cT#w(&ogBd zxH14WfAPZhxlS*-kk>G4{A%Qf?owZo(T#4RnZ!3hsa+F+#Y~K!fW#?lQtRap{+dK~ z1{DG75PkggAIYX|CwsT`kM4x~ugnN(Ag{I_BTeQaaS^$Y5e?>-SoK9cM5qRGFhpB8 zVrU7vVT@EmO672(GLi}U9>MG`U>OfBa0{$cZS*243AZEwA&dMQNy9O0T>*JiSLM8I zodt3)abgtCAk$+eN)bOReAmGOILAp5joW-hkWScYLrc>@!6iKV(>bhBbol*|itT}P z$`D9i#!5`=%kzogqa58x5r9x!OA#)s1O<NvW`q>_ZJZkX>#CAl)gff}Ql~_oi4le& zmV&$H>N!~rK;SU0#IwVv@C_7)C2*AP!#Kto1r%7P*{IV6d3a(mGze<3A?Zcv3I0}O zx16X7J#IzSm&iaq$>dqe(3OcIQKq`v;K)z?jetpHgi45j#z?6W?*h?LBR>j^g4yN= z02htzD1gTAMf_BZb(pa%IKpFql8lp*hYA_@q#qh-eZELUxJ8@s%jMuz2NB*SkWLrL z^xuigt>w69063-#+(oGMu@A!R^wi^S$L7a<L`1+L`dnfbi}4L>yJYA-m@op4fFu=G z7E65<HKG9)p|HuF?KXnH<@G@`flwPbp`=gfPB&~Y+2+^X<;@qd!Ky)tsQ;2a(v!=_ zPOh~ev63!B5G*UT2$A*q9mB9xj|_KXKSe}!!hM7L40g4!ez$|YS~m|g1!durrfsO& zN9_oi)dcgeE3V^BggfR0_Ae$)B97qfBsyqVxxmjY6gti<Zr4uIk;WMQsR@G&kD*>P zik{83sZCaTQL77zdmzi>D#7C-CkI2Xp#h`sK}H8?0ap-k&<2c>)iHI$Hoz&33?NRa zsz>(mTv>#TCdh%qh3+VWl#8Yksax^}FBIMY13-Ecc?Q&5=AwGMV?AoiOv)re>WDR1 zO_%N_kFOi)5M`?Z2L{BUhw7Vl3z!OXa45(q6HE!Dsw@vTV}S&^GY<zau|&6ndj%$J z3?`l)+c5h>mc{B?FF`d|-|>=pW2+5cl0X1#Jer&}4ojA0qbzq`Xgrlc&-QLcN?ve- z!bgC$*9ZT&zcX`l93gGq2S;d;`;fDUZRfmjKB~jgw9gB)3(pQb-I3I-uD2{ajLZ?> zXezVp+Tr^1kCDIOKiDrdg_twK=wPB36u0o1n7pxp4vKtz7w?y5gX^My=gQd(P>?#E z7h2}UyKVwsawL(yV^PZn&$qyR3ioPa=wSQZi#5UiC6)!>f&x?xh(GO7p--LQXB1-D z+K!{zd1(#TK)g5x#n%p^fdGZHs<BuiV2OEw-qQfB0=rso$QAIO4($s~Fsgz~Gia{X zSumo}K5buY06mFEf|_^_?RJ$hY!vX0a63ICkNniA-bMY^!HSLee=MB|Sd{hJ#?dr2 z>!4`10b?<WE1a<7Ixu?DGY)Fw8fqw&7{{~>1a%ad!ph8KWY|J;#sI}F7u0em(?pgW z6<jb8b=Xms0fAv=UccXe&Uankb-r^DX5RO|Jj?yu&;2m%Qr5{}!?N4w9mAb_KW{Dd zIdUs2L2?)9X5nNGa!SjHHGN$pz_nr*V3NI`no^~T@g<s%*ZARv55mg0df)=$$8~v~ zCqX>Ip)a-E(BFrvE-1|OGE(H8)3LAC(+KF*IBc3Ig>;HBFT0-80T$5(0!m6Cdp3hK zR2P7fp<c{b@Cu<gIYh-cJhk^Y`CbK5F$=ZP9hMgPK7}5trU>jrsg|UD0nOi$C4l2! zBD^LbN^)m-Y3UfnHL~^^Yu)7iNBX+1`^}r138*M$W>V|p%E2bvj(V++wQeHpKjCEL zi6twgoNWH_mP=fuw5Ds14AND@W+k2Z_cDYzF-E(o6p4Ur!J_3%ydl94%8NcNW1wob zhzoj<G1(oKq@`|?<k44zz1Gl*Bnl^P?<ERC*8zDe`0ZZ!(=#!9Gmxrt#fT{jcW)Kl z#}m6*wc!7Gvk7Jcffli8mAeCR{<dW>4l8u!1#Ti;N%wU5HNYmpu5h2&O?TEn%q&h5 z1tWUr))4p6z*7mfMBLEGARfV0c%G|QTk==4xItYK^EC9jQdA3eTR?ui2DG9uOK^TL zqd(C)Crg|7V!~!imSz-GM)UXu<b{!V?R{W_Ufv*N#Im>vxhar9dgPEH@_ov0zow%W zsJ4qloDKZ2X0m=B(oO^j(TJK)UOx=7Ak5nC-R`7jtONL&HF3Uxy9E;ljv5!F#JH%- z$I!0?qXc28ujrUu>cNFy_Mgt)?o`IWUg7o$?s;TBc>!$RDFK?6LH+-6VRG^;tXneb zf$h-+8@l%E7^d2zja$^;O$^ceen?j|%D(^pt2?RR!;%Ey#9j%xbSohVE2y2Go$nR! z)jb^(pkoblQRkSr>G~9pnE(v4dA8{_M57b?5@?Nt-&_ayI}4oH#l<|%nMj`5Wf0dQ zAvIXn2_wM*1+s09Fo{dMcNa{DQB-U2CVc{H1)X^V@!ydQ4x=iKIlG73llw*SY=)_| z|Lwh5R-O^OFt%^LA`xN4aID8z3q>PW;gVkE!4Dyb5hLD+|EjzQc?S=WMP`#mz?v)& zvx+*Gxj<9Jm70O*gX9LJ#$Uolq`=4+V%Y!tREg4G=c!@rS@L1&5O;HaFK7%!43IT^ zKB}XZToLpcR3*e~-X9OAuZ!gYRQPX^8${=5qv!v7))epX==n!<h>0G|_<lqed31p; zeab6?En{GQs~ypEdT)aK0e;iEBH_!E)E4{ey2}_MfDi#vf6{h1mX$&A8{x;b!ny>I zePamqyuk%SUAvZisLPa>NB;Az0~8YpK45^rX>5c~>#Vl7b`i6=pEzFe?HqyLYkSHc zA-V_LjO*cCTvJ`0Tm3H|;wPAD?fm4Kn>1$8{iB|Swd1jU6mhNf-^6PI&ddlYO8R|u zUl24S1k+u2tJ5h6*mIdNt#X##ZomZWG2y|DDZx|vq7h7U$LV>_VYAx6RI{j~jQ?fA zcP&c)Lc>9AoC=r7CA1f)hfV+1CBSJ+@!dIZe;8i4i`-N%uB?iqify=wKqL9wjA4hk zp@IQ~#`q2T+AMrij86$H62$bYXLlo+BH!i@nLQxRcB2SpZt2QTyD9b!(~Po{yk6Ch zM<}Mi)$E!HBT9h11X)$um=F6>ZbtGC1qrfDK2kl*O|<<Bi<L^y1eNKuzC#2@9Nw;L z`R+ZYcI#&T_0Y<hEB8A7q75=ipx6tD8&Z>{>;F?=B1jZ*&n-l0PW0!+7{(4q4Fgv; z7mgH_YFg^Lnc9k><^Dg`pcEA8gG3PsHSc<UHf5vxOu7@e>l$#By4<vhFqDQZoXj_= znn?hitM*|WKsi(<@|S20_!>bZq#NHx(Y-IU7!=6T>}{LbP2}v_*^|UM&|e|`zWFsL zb>hp_d(_ss&)kp&kG;;q3Ato9IyE6Uy(j`{5Yi%nF5GqdmKGa%wvDMO(QaZU*Eu4q z%4?H?=w5P$brytSeDWAsnC=d8^wqt1&4Y|!2uupv{k;Gz;M?6EPoy=zN2H(%sR#AF zHZUPw?L|AE_#AY1`u9iHDta%4l!HVo6MH}xy8nF=EU6h+Ze;O}vv$vCoWss8A1j|G zmPD~8BWg0Z-6Pl$SV443@TxVvpBKts;@_BcUgjN^HaYR}t`YqI=`BNX3$qBObS!Uj zy9md26QG-ehaH;mqHve{9F+Z?l~d=Bo;BIHxN}JFZN-*^?|l#sVue$o({X2&W!EP3 zg0<_HMdn9a16~HwWoBUpJYlLa%pm{=wAOg#kyH#*T6Sj$l#yfZlfXG$cJ0j*0dwf2 z#7?dw>Z5THN*Dd9Eg9bve}CD_mjrhfRfE79(YmebEch4`AUi`AoDm$?3H~E0<}2K# zL+Khr`lNrWy}ZNHrwJ67nziT+88SquLW;N`G`SzW8Nv@~CrxIx2=ChK4$ipfTm*A$ z&)noGlX<G#G8?RTxZm%)wG5kDfe1s*snI;1pWX?asvx*yjE#TOtejw`jLpkGLbZvJ zYSE#)I5$(o7!yPKbN!r4gD7avKGN_;ZEL}XOL3uAu@8g?0_jhNGhqlm(hEebKYqxi z#Ch`^@NR`o)JHXY2DvGv1&zBY%u!$4Fx)K{_3`bl^FBnx--!%x>zbaE?W{21gmH(J zS(KcXFnMmvmj$uWfVHVx+&~nEB<P)nAA73@c`q6{u@}B{_-{>$DD`q>Big1gVqf!G zZS3kS`=y-L{^Pso);lPA3v-FJ&IAT)eVU>fE5%ZAc|@a`<skQ4#h8flv_*Rkck@^~ z`aWvDB4wNED2R-`Q91f(<@vC51?_vk)L`^owT}Hp?B;#mJ+AJ){+XNXzWBr^yWjLg zDUer@a&~RkBkb9FL;qmc6)K}}++eHX`+1O%iO+Z9B=W3eyN6{?`#wekiR??9yA)4; zs`L{rw?0Dhtpz*S_kxCK72O#M4oHcJ&_XYzi?yN^xgL!xj)WHw3<fOA1@2?PR)~wG z9|d=a7x{a<o2fl2l&2km!6bZ`!&hBT=>gvS6GtK&(+X^ex+nvKMOv)$3kJlt-Y_xI zC@3r)RPCUiyj4`A1hvdOweC+bsu}i2Ob@b%Zs@dR1#>hg|8{}w(lR92=rYC!_mHe~ zS(qvUO<F%~6xJLqP%&U{3jS9i&KMY+3oQmicO_tR<%Q~DDgg^lY;{}hLN$kRtZ#l# zq$@Zcr!a!$Eu=xcX2Gi`vbu)q1H4z77t5}D?f`n=x3Sqc9%p4A-lma~sF1VC943a| z9zu~-D?-3E0tFzoKP>q15e#gabpeAa$~Fi3LKIVKF}3>%$^@#3-Ik~&?9CK<MZYE| zA9caQdy@MH@Lk%;(O5(}<fF}g@hd#YUlnFM=%;jK7OoU?RZnN~3ajK)BdicboNQ&d z&Je!4km<fQ29IWTEaUdFhx3Q9kAu{*djKe9UEQJMEu?JVHq?bGgv=B*+oD}-P&Fee z7&(P}j9x1NoQc-1u7Vh3KQ%0{bx?Oh$p^#u2fLY(H&S!$Hi0c&rMgY`OXsrpEJx*0 zM6jaL0FX<rJ2lihQ+gqBNJ3z1_iyJ=hRfxIeKuqrU|!>76jU&H`+O)hM5Mh-?m)^r zbAId36r-aDb$ih;9yRuK3Qvf*Tfe%u)PobwNwS{~e&Mw$THPi`-VFT;^FJb)$zP&l zefqvGxZKkeq34Ry)Pp_rnpMqQKnNfXKi<d;jbM?6o?B#8yAX35#>Ym|jZ&F6v5zR$ zF!b+~SSC?W?25ubdFSb^^lGSm_BWC^%bDCGavVNpYz;+ATf}q&u7nwypet3d1Hz+c z0ZjG#g3?kxv*dmMOAOgVOnh!WE$Zc}DNuWBoAJmmzrlZGcGUFtnEOs=!uW0@m4u`j z!M&;L$3jt<o@Mybo%{l(a4;DSk+tB!j08_&ux#RuYZDE#Z-~~_;{)V|xoi>r`l1~5 zEo-@3__k>i<1-AP5#TwrocEHGO4GcjO`gBY5KKT)EKjO-mLdClviqnF{Ra&gd_f-F z2`Me(Pj_Kk4*i&Hj7S^g-&{QSf@gG`RZm<oO9b7$H#N=Dh#Dsc9dtS{Ssnc7wK>_H z6jo=FpbNZZ!StiL`rU*#2F)pf0QAI}f{-nx+XtHq6l+MyKjLE}z(l?W>cvv^WDpLZ zjbOKRAuAt@Q(phvLG!s_lzx*C+;Fywl%W%I@M@kreu7%Z6+uI3kGWm9ILz_pY8ZBB zrD_!F-t>%{oR}vkHf~QTEstyYy(yMk3p$_<sz`p_7@{yKUDQRxyhitYX(#U@^h@u* zuR~R<MJPLXeOhBWgXuITa_d`$WgYDC6P&mzT^xtMY!XAQmiCpT;G}`2vsEjJYOVvY z2}%x)1@!jpy`PO<U~PC(5mbSReN|K5=AY&u^@k@T;(~k*P*S+7_YJk@>nl9KYl(pl zmRt6T;8HcQ_x)f^K>B$X-E7{6KGJxY^2E9vGU9{#ct`;Jtgf2-vs~2vJ(zq`Zad;F z!cDa9>f*=+ZjaJ>px8-mF{y*oyC+J!V+gZWqy{>Y=2!587*8S)gPJn_hrOtfiY`ri zK}6^2ZRAWb!kAYiR*R2wNd<G`rW?mk$Wx`!c;c4O%W=wra5%Rs!ne7^psrTWqvDey z=fZk*yC>q1>$ycOSP`qa9Xt=jkrho%?oX;xEhzUCM+oPz-fnNuxh%$!&QYABmT6UE zzo_j*2v^B|i|!r{c_y}{+I9VumP~A{Mvgw&>~(ICkfwO4t0n7~?qyO#szE(^Ze;$X z(LMR&syRa);%3v4O`5|I(PDgWUI&#D5NGY~(O;gt1M%J9(xIfDP-{v<x#qiS-b&7e z*Q1U4v{-z?_^y{cT(rIrz|sH{)RVpJ<Xm)Oa$uP;_2uMumQ1OGf=#C2e<WN0ETcqP zDVjpTbKXLu6o?Cv?KQmaNTqX$h`nddL?QsQO&{3AmvNdx=RySQG&{|US}|n`&0eSD zvqsF{o137=UQL{@>pVTCL|p3fd6CcOv!Aqc#3rxY*LC5R4FbWXC#H3;Js+@>R#aJG z!q@!KrpBK|()NJ1h45q@&kkfaK!}U^VS8bOU?0s?eo1_B1b36w8UZEtDL%=GPd=_f z)~%*@cOiE^o-`cAj*@?kVN#=uSfQv*CXy!JitZO_ubV0osAZ~jiY;=1HWX%V@KD3A zh(^lmY|9WqdIE7Ki5xU-UT#9xF3zn0rM4yqj$-<uVA>eeQ-Y`>*NljOdo1c3lVjc= z{IE(C--Z~neomevN@SBpy9ekyt4YXNK_<#8Pfgq`7J?WSuCLd(bJfg=6eQ7Mhi3A{ zjLxA&<wi-;M}$x0<t^fO-=A4Pv-O_2_&%W#V%b~lTsq$tWX6t?qu0*+_&Y}d^rp;= zihJVM$**Gub?;9ip1JPG3qzpxcWEvj+G@7!j_PXiOwJ<+j{Y6`-GXcz<f$*Ri$~9? zNJuH@Sz{onSWw(`JVz3O4<~qAoziZb=ut9n<donCfTQTU8xWUc0R0v>6%+#8#_U-i z${4P31I{ubgrYXFxaQ=GhBJpZ<)}RSq4RG#duYJ;MoDJVEybpWu%!F^0;(n~8ZGpp zR=<A9)ExYGo~!z3GcJv~m3x+Q3XJBun4un;o_S(YQZCbxr139lhC?*RnER%OIL6rv z_bIhN`NzWb?N(?FSAUJ2;F(l6N93p2!;_X>8w>7dfhA^Il}~=cE?|b%&6|HEmat`& z2&;D6t^CM&L(3Sluyi3OF)_)hbG5IlU@sZ~5yYebb8u{w%2R~IAwmZeei<#^Ek&?9 zv=FqVyK~pOnBv8huDdbVD?^#fudM;VA!vjs{wCw4cDjb`b(95-7k6m?5&RNP+<KKS zrAHLnTZ3Bka1<KGZ-eL}@;9`<0LY+`M}TeXh)7{__RaSUKn+OaFRi0dXjZ=0d^AW! zT;?Tcmdx`>`!~q((9q{LsHsSCH(kCIzWW+^%s?!v)R4Iq9VLPCf`SrN`=D+C2+YXG z1Y#YPlHvgOX^-eUih>c`D2V2iE5^`_L;NKQf`tM})%ef=53$%lqoFqWXntiri3*oe ztxShXB6w@m<u{Coyk6PJdqU`eP+9%|@n=5W#3CB%;<-w)X5ox9<syW3Bj)#a9M2+- zetN_3<tt~CRb(q9rqpxQRdXO^`m$D+>v}1*lRz~`4ucm-sTQrnU|rh8$M0$qHVGVm z=9{!6SMT=kgl9Nc2auJImdR|DbmTfNS6oXjrl1T)_kVfh6dY>ihHm$cqVrXUMvz?z z-;T%V>#FF%QU%b5l{Xny3RAAciKnHBE+<;rr19P~JL`f_TSP3=z==cj_jHesnr*ta z8)z9647Eb^6H^6nOH8iP7iJR!@A^5`>^ENXKnSOb6nyZd{&Q-0`w=yLc*0qeBd?#2 zzvv7VGJ3@L17S+$Y~^l7w&M8HArbjXlXv-zfcFi`rF<IyeOHT!%(a?~uU<?r<)mwN z9W~6FqU;#rMkjzFT~j&<s0dJ_dN+oZlsLFIr!!=-AvPHcEfN7il&_lg@0ndxXb49K zx>5Hg!`bc6WcJQw)DB66hPdq(l}6yHt;s^|x^^dF#B2)ja^%Gh;t64*2{6igX}3EB zx5;qiCWa1GV)=Kw1`|6rO$_}XKOGn;x!{Etrq+I{w9wW>WyO^ev3~Cl0n%fdE5C3; zes4>AGSVmZf`!m?_SVn^fjPY>06zSCK`gPukMZf}QKelin+~<6f5A(wYSc$i7jw;5 zNdBwUEzo^R|ASpL2?wrE?@c5|tf=4MMm#DKR+pk6NDS?NgWUYrLT?b)qLGYS57ZCp z4gmmfALHdQZ~k*d`@DonUpj4e7tLNvw$v!4-wf@}8a{KoL?SSna@l~c!Hws=rOw_0 z<$=0&^=#+4-Vd`P^OtVmRMYC7;-f#iX67XF*o0nO)B_|oF|S`TMr;HnKsetR8hPub zAEH#Ud#=gBBZvRo+=GYg8QmA6mawI<aSa=nd(VPE!&X1}DdpJ1D~`fi`nn;hSa0Mk zF--Nq94rvYWx%gzM`0306_{xT(H>f56HzW1EPR7AKubi-uMNOeR8Nkg)X5!3nK(iy zLhVWJqHM40#ZjuH6`W;Chmc1-@L+e{)2Mj@*2{Jr+pnJtVn0yy%rIZX#L(+KYB8>l zG4$QOKwt;92Pvg3npPe;LDZCDtQk~sH{dV`X=S4jn+}hnjN<Vl4>W9QHNr{Qms0>@ z$hMRCbtUZ-A<IHF<rr81gHWmy$-gm~o||IlB5p*NWmweQxG-k8kfP4ojb+G5WhB<v zie0QN!~&*@=_n*sn#h_<7<GlI&4fnVdD_SDr3eJ5?IMU7+bG1K-W64zTiio9OQOE5 z7I6q2c*0-}fW)M$ANCIaeYREvg0B8Sk$}75`Ec#Z&SkS2GkMEvXr>9^&_$sX>FxrS zocVLmClj*D|5LEBXjd=%^d!1W+TpX1qSe*0sB`<~O*X}S>AUXxG@YYm&(v0m2(uh> z)$=}-iTsow%uNz?Tdh}r=Bt(T{LDk(=7*y5_af7^8UGL4mNzC48vyOMC}S)V0CeD} z`595Z@EZjO`t-FKLsLfjrm50rcfCO&dUr<rB?81$j;)7k(wG4m<ZJ7?K6Lb-n|QrS z<t5m4V!6VQ7ps~HwfYFEfnakH>6DZP1bs&>IbfXPO06;>YX>u<ZOLjXTnq9kwowsg zz}jTPY|blO@-0({y!v;)*g<S00$<u9hYUd^eb}LiCp>j=SsCLK?`=TU4EiTzMvqxs z#^c@dt`BnkHJy6hC_VvzpC011iI~8d?G=!TzYs-NZ_u0Icsg*65$Tgg%O(@1lGBs} zmCu|>A{9+{^VRf0oa@AEU4<V?pH55{@TITxg5X^V%upDKkV#_*RtEL8?HCH2!2h1o zCDJNhlp;q){I}p`wacKZPW7=d7B^pUrHx}FxjXkw-;pSe00)WE0nj|WhUkV@2B;z5 zxCB%Lsp`n)VM^n7wVzIV;d=q%fDeyHcD?U)xR48k;<-v=*uDFUw_1i6z8`X=``a~K zzQkh7o*5TGRs)E)>=7^oBCk*U7N|=YcTv~~h(E;6ii%ak)?~HU@E@Se*B`ub{`LBW z)tefg?j5MNkG@^h;%m_O{ph)~zpHx_DuLY8b|ZepBq11pep`~dB5-)Z1;T9uVEvU^ zy#^r;6D-u6+;sVR?!0r<o`4sW3BNpZTe^sdYqNqRxU!`7XYNY6SC&N2QbKS@@1Q^3 zpGLp`Q_yQA+02VNa#}#Bx3piV2dRC(iTQ7ZwW9cQuEn8kYE?k*pv#jDD>H>k#IKo6 zi%-~dJ5tNyS~}$VrJUuS-X~;^ll+$zmW+p=tXe;``Svt^`urJrVxIR7@$BS{n@&I0 z)ibWMvsNA*I>PQ*CXXq3=Jv;Lx3ZqOrL6_4a>OVd!^*-KTJT6Y3I<N3^_X5HYwGs; zGf595gu>#WWphKyRgPhSVbVfP50d-ZIcwWx!^bXc)qmYAJ)#Vwnzy7wv(L6!W&+}? z&Q4#H`=#Tp*l}L>qBPwk5o|&>OFP?li~ilX-U~>#8d2f=<!~QeMn}|G0T4P`4ddf` z&$m!%hE83*Tk~kILhp{kfFmDB7Eahp`oYV5wh`I?V(y{#{reC_Cy{_I^9m>MhjB%G zob-FMZC&zaQh9-kdbDpo`e;$bZd)zm8Vs9#1pNj@$>(Vbv$DVo&|Km2-JIV`nUL*r zv>+CUHytBPnfsL-K{f93Ud+<}u;$6S_QoR0d>`-s{SAlN-j4H9<)miy%1WSpw2^gd zp|FjED7z+9oCG~k;VNOnW^AYnYA%7X&1aEo!-=|i-P06^(=3@c5ZxDqd{uib`%gYc zSE(Pnf|4;wZrRjsrgrP5pJ^KS@)gJvx<a7oomA)*xsJ_z`Mlq0M4-(Cu71Y8t_y_6 z88q_U*^klu?fibL3|gb8*|!Yq<+HDgL@b)pjc`@NbzrvQ@m;;Vi3AfVSBT)Ia%bPX z7WmwAdE)~w%M#_JzMwmVx?gsS=R)BdCF^%Qy?R=OnxG{)N7PxS){Pq|9@gy=4u&>M z8q>9TYFJR$o|6-uDX%azq|%%ABIrB>1wM9i(YL0;HLRhWDav(ccRjDb|ML1;A8T#m z1*ps2_}`o5`$nrLe}UOkNI(rxM@LDe*X02iFMYn@OTkT6w=o+RpE%I)<v`IhN~tp; z%RYkfG`VFr)X>Ckd^I1P@Y<BmC%h)-EJv#m>UZUM+{c@tOLa8cydPAE2;`mceO+_e zoCwOivp1wk&g*g|<R>V!r?rVCG2-v7wTAimfRHeqhUX8Oid=yvXosS&WOZTZ0uMea zbSG13OL>`k@-O}!Dt{uOKwtc9)ZC<wh}rCG@58p*oUs)K<Idj;_Wt^QtFg!JCC>7; z8STzhWc~&6rp0GGb=L0ZMaePM6mHmZ=)s4CQorUt?0f61*)MQ#r<!i4FVycpj`QyL zwoa`$H@I^KOWSM6=?2a4aqD~%s2zr!e-j2mmoV~r|MqRnmiQy5*_}NdxI-Lcgl_j$ zy;~VE(q0grQi=)4Zl>Sq@q#*C$DE)MR*UX&x`U(1jCH@m>Hjbv{ey;EuQg#!*|F1L z-nXqVE}eh0W8@=lm$uE_4+IM;#{IzGABZF&Z}BGC@6X)&)67-_T2|g-`8lXpM<)HR z@oLg_h|+0OZhvv?v9>X7%DU;gZjN{5k@vKH02%5P+!W%2xVouQx3#Hj+w;1`g{1+m z2Zvs957-m3FR$s9OQZ5Vqc(htby|n9yIaSBJ9g^~a#!mYfb#}L_ec``_2-sIuhlO! z=-%{W*344_MVa)HNXdM<Bq?7?Th4r>;-XArU|ykLp6l1gKP4!O_$8Pe$p3-ROsdRE zym^uzY1x7we?zn;Q1RU`ZRWjkVN3pms))GaAzf+1qh2hfP7E)&rIx?^xu*0u&!$_6 z-wmxG41AJoOAO8a8nrWIb<gJ8CtT>3n6>@5fzAgUk<>z+Gb%mC9>|XgfbXh(F!cRb zsZK^2`>E2xCadj%ck(>f^!ap^O%SlTtyV9U>~Z5Bst|)$nT2<((no3CjWvv+zIprl zDo4+2zbvt~n?b-S#`<inIng2edBcH114D11E1%t6<hkjpeMo88f7DGM{PE1~Q-~kD z03ofT)9C(n(CZ03NwDQ6G$E^L^cz3!`^um%5_&pvN44(|rb6(#(*|wuU*44TZ*pe) zXjFsg>^01*58D{zZLKy0jwy06b3z0dty5~}T=mQ@{9uSEq8npcTXioe{5>UA+w>?6 z({jr5tz_Xh^bbwnX3nrK8yytUnH%6L)Qlf@G1)ew7`b#&@J@|+dP(<EY+w(Q=eiLd zkf6*0UQWe0n3g=qeF@d=#Ex~h)D@b5ahBsPW3Ka^S4>Njs044~*BIHh()a7=;qxCD zUV8oVAG%SnJF-B{f62?dyJ(TBN85@hJjPVZ@dO-#<MV__tIRupnF}bU?7w+rxOnuo z{_AFBBjEV3Ms8F?Tk<QGq<I}9VzIZ^<AktV!g_Ls)3b{F=2(Wb?&Eb+Jy?NI%ifCO z2)HkhVo@e79B&UE`?>sdk|du!Nhv`8ydO|BaEOf^^g%*_L}>NW>veEd6;~b{v04BC zDMN&Ho(|0Z(dNE+*R_U*v$=2eVrvdX+EPAO_N<?+D;ixdIn-gF>`6JG_0V{4*^l>G zkiSI9J=#|H=i#qoKaz4@dciI@PX`U|_k9^Hmw7iptNDIcQ^GG0VAp--nwMpXr=R?} z`lHX>iU!!l2Y!l4=<-N^EKlL>eI7(Mwh3MCxaXR`X-{9%<C~{LDrkEnUIV*>XAzho z8`_LPcaNRct#AI|Z#Gn#2VbeM206K)FXUdzS)`Sfj<OkDfKdJ8y;8rme<QT=aKL%1 z5AVK4SmQiJ!Ee47WZx<AKu15Xh=)+bdorkke_JH#1I0z5M;l_<qZg_#1x2JecPQ~$ zii!h$9YdN&Y||#z=1^r46R-~F96I04@gMQQ4{LeMrzT|@W&VW2*p5e@-m1i(Rn);E z9gVDzNVGK*8s_ba{Xll19Adfd(yto3%}e95U)m`3pe$6HJM#(MmPwq1D=}?zO~+R1 zGg~|YUmt5pa*DLR$K&5DE1yQ*U3fuBwX_1}0Z;ZLu~eC-6u!{+a*N~D=Kg))pk0vb z9&5yBm-iJi(G@CUd4<`rDQxLNsnGkKc#SQFr>@L?=C=GmTW*f|2e9|F0dMEgP@v1z z+zqO{+v87VQ^r%Yeu|8@TuhOu!1+lJ7CCe+9w#W9p*fTC)FI2!Cn#*b_P8BFxDAl6 zXPrZrQ*}Zv%e{I0PPJ$PW>JsVu9`Zs-=n`Z@gW{+yS+oy#yn%Pmp8rat5!Z*B}<p< zP9}~VUcZ*`^_)f+pWl92!d*bkTTOlWt$AC*N`K0y=Kbi61p`Y3(zs5`U~S~GxBPZ; zVUNqXO<CbBmL&Tpf~gl~KgoO$weN-b1EEgNZc)}|eGzgetm*3LBa0Z<nVik6;Cpc! z${S_UsXXb>uA~Q_f1^zI%G<oexYm(dj)eBStAAVz3O?O2Y7aE4MfaM`?RfWGY4V<h z4&P$k8br>CUe312t@U-^Nqsurdlf(OXnwit)@3R$hIM5Unz@gSZVtyu3K`P7`%ap- z5A2w>r+ksRN>h0mv=bav*?4nvP@kGxIoehEF~C~uRMwDdNgcA^M+c}qSu~NC%EW0^ zHkLc>`(I&3-+H93I@3%f@ut|70->niy{u@S{)N*W%O2VnpxPn|(d6NW32GewYQp=A z(1QSc@spTrM*#B%^Zhch7g5@N`JU15mH#7xjM80+7;mKwRMpNybq1tV-U;2y-{RC? zkFPJZDo&E}XQkAh4m!H0cClyDl=vI&{#Qu6<hp7p{r0rMM<2Y({ku?YBl&b87AU*t zXzUTQCp|jsmggCnmt})`WM`hS;9wPw549Y9xNU976nZY67fK_DKZK>f-=I+bJU?Hq z3y&X5;oqRP9A2r<^X?MAR&nkHB^(^2?E0R44xzP+*Qm@3s~jTWpi|$jUGchi67s|h z9}+ZIRxEMYrPn`Cg3rIYkH$3!#_!ypK_fdxnOg>4%UuI!EkXCx)EPjs^hfKpT}jfE zy+R35YtYpcTz#-s-?pOPg{ny(x&HF4@kx*0rXOw4*C<IJGjKpx(`$qflCHU+&D`<d zmj>K-FY8!*v!ayAIXK!USxmUQ+w~88b>zePFn?#LG0cVyP5yMi2EF&j;Dlb5jrPGB zf|!qZJ{@~pyE9<J@Y(vJ_zCI;Y#e5xTg>CtxySQFvitSATVs{+@E&ac;At<;3<WQ^ zcn#5b!I75KL+@=VJX$f}wEN~y;>Y?F|7$2FXcY06%t`$y6*F9Z`l#$;V}F&hQ4zQS zyyuD~!M(G3@xB;)Nd4P+vc!x#d2rB`_hab|`B&<x3aN3%QBiqI2wsyIk+RS+ve~$s zb@=x1`P&%4whaZhPISC&(N@Qgbp*!PI|xPIGjWs;#gHvue7_@AYiSwrSu6)eNN`iw z-*+}b9uQ}}JdS3CaDg+Cs>~R=D(K<iB|qpNjL{!DxWpv&t)+JT(6?D?$llntyyKfl zPb$=JLQrFiVJSRwYqyTCt#IxYM_#%5D5q$o;v~1)NP5#tx$N+(8oT+)N<R_Nq(a&( zu1fo2sM<c<F^MX-&y0i#rzo7GF<rk<S^7ra(YqI_7EY3Ly(;u(;``I{UZrNJltCpV z+$GMNq;kBY`oUpSKKcyumwyD!l*-Op(W$>+`MpDPqf?bfRX_M;#j7P+pu@-|85S1t z%&npBp6sam7Jm@=^GD;6ox`Jqkh{lR&TF<`me!knH?L$QQz@jRh681>Uo<a8=G^$^ z>7;5919M2xp9OYf;u8By9pr!2w^!&8`?m;0s@-IBhqK+KdF2CwyzY%72A(O|bu;@s zqu%oJkI``P%&pXNFkkXpn@xn5_$~8=VQ{9Q$9cNaG3k+gYm_$V_L{(Z+t4VqYEA)) z(_N^=GCYl$Rry`iZ)b*IZq8GE4>x!eJdh{Z>GLc+xTn}vdXC9S_bKLKfr|vMuR3jE zPwRIUW<GUBEK+^NFTN*w-^9S4nu5xPT?uM3=9`T|gy>p_fBW`>#2Po0<Z#y}>Mo96 zdyxm!_vEjBO_A%4xo@ekD$Y#xb(y18&H^V9ZSdGC!=%HL0j<BA&q>J~YKSZF7nOsT zXZ-+pGkTi$9G+!P#lAZ&ai^x`R>cKt?EY&nUNKC4GSHy(Z?v^?B$wvCcGqT5ch@_Q z88y<FutSkj;a3aaedgBdbrpx$aYlAZm<acd@V|APuPHamnja}UD*b}becyRgR^>3~ zujMn8ubE{H4+v2XnU-fLOT#Wlt<V=1>$K!8z}1q|7Smaho0GhvRM&UE?)C(kR60|4 z(I?OI^UaTH$4PD5HxbTfmYR=j_*CB#7g6bT`|;sN`CvRjmvx;htMh&7!Z$S)1&!cZ zZ2y$U8ey@A(qM>VtPVTa5_e^Fl=4TTuVJY2e5wzXpxOG;w{B@hJ@FpA?6=N4dTE@d z^h(ePl}(?|U0d4NpGKsUn9}3r3KJ%!u}tOr__s%4CsdwEwK*=bdYFiNGU}h|rB|h5 zrFE32ZoPf%=MMBp9d9@6tZMWgl+vSp_LU_<&+T!QY+<G&uhQKS(EdGS$yK%If#>z+ zq-qhAD0Dfd?>^7AO69vje(U8exLiw2=dZf(X};F>j?^$iplRebnSFNF%F?&~Y{=Sq zcE%UeH!j!baFMSh+kEf1p1VNT5su=prz!kQaX1TJ`BO{2C--|>9a%xR=~b<VTE2ZH z2DLKV)Gl(7IAQ<Zti|{Sn17paw5|U$w?}nrmEq^S-#C0c=)|ClkF9N*<>v!;L~h+t z7x<IC$1O6?w`~)ixxIM!(Pl+%dF^>PW$57P+h#PwG50OzU4Jz&b-)%8cCfsuVD;iy zgYJ)a2mYh<?ynPdPlDq$rS8+x{~7ykq^VH|3;a5#V!v$RZbx~#Z4w`v{YW-SQnnuU zqx?qtAr5JVurRO8j$iBeYfW$|^-3nB0f;)MB(;sZ=KF^4?UlazPs}5qEGZ?j{Ptf> z6_HoA)!pvnlV2qpcIzGP!H$|r(}({%ghe=z@KUsl*EQ?_qg^Yv)qRbo&N(iwuj9Rg zOX8KCANk~m?Qf2|vRyv3^3bVu&8D;ZZV~UO>;r519v)w5A9Fa#Yr?c6(urv{eZgxY zu=-@2Pr`%_z%QUw`XWm;3#n{voXsKMW6(y0)K!>{Hh%N#$APmYW!YmUr1elX#x-tF zl3vA6-tcYw*9>*Jy+hNq@A$>~x$8~It8;T^+-u3JTK?-14)91{Lvc~5xLDH;myVY5 zxa*s5{?NpkjCTc(F`b9qAFqEnw#p+Y`+)jb!>U(g9hD#GO8qZbRXNkny*EiJ-NLos zUzzsNhR^k@te@1kg`7#aU8G-hB4KQCyKzJIJt51xE$+&~o3|S*w}g^r{M0APT9Y&S z@U5ZBaAmhEThBKx^wa6hdS$2I&zd`pzw>H^RcCUEYd+N@4RO8D@50mlfk=8P!%L;I z%Di9VEYd=?T;|Nl*0=pzcS7yC{fU@S=!#<O=<yuB8R1NH^z(I`t>fK{#%QD<+bgS5 zHKo260yfm|3~%B7WvN<Fsf<l}thzl^mSSqUa@0(9@sDY;MAzqBm-F49zMs0oF1xE+ zl3%raw&s8+zq|W&BLN27$<^#=o6<D-hi|HHy_(r5tL-_?;gQ7&nbs8Ia4h$RUttek z>1dnXHeI(ko2d7K(*Hx}4{<kfKi|y}rCs+^i1!F^+n~I2xm>6hJ$w@{-ohx@-Elwb zE)MPRFKQW6he@xm&^5p8&%OS7^$Pocj_NyEn#Z4>+v02gx5>mubaR~C*!E65`n!sE zl?*o+=X0EgpK@LKc+IlqzK%^124&~UZZVyD-^Yg^lm^-B(xvvh|IxL+@J3rmljb$4 z<W1c-hcz9u+X7^_e=c>FH))DCjA@&2BiyL=y?My--7_~j)2sLS<%X9HP*)o!*lV89 zUM*|qNLKEQ+s+jq(J?qMPa2%xm;0c*>z`xLl<Iz;t(dJ?(|GiY^pddbYSqzg8&(JD zB5l~%7uRIaP4=(ljiZWa1h}Vje4eFmQ(o6qe!F{vkl@qs;xMJ-e)4}@*wp;Sj}4)u z7I7O0ZgX!P9P{{TQ`6K7Pb!r6L(Z>k-u*aBdC1S)p!{d1Q{Otof-y>IH!-MrtgsnP zXQ9u2dN;Y5Dwi@qiC@X~ZyNP5yI19<A3|hSk8wIj+>dd+Vuv0*`H_5eVy?rwVZrUz zmLY8`!amp((JuS(R&LIF-&E=H%I?8%bdAi*Zor&16~+w^kcA$JjB>~E!^O8dlud{K zn=o~S*UZK{otrUp^+C$7%ez~)_Weg<PLQd2w7`1S4^4UcXQ?x<>Sp`na}PSIiI{6) z0X&V{z{SqJAUosyvm^=VW-%Wf0yt3Lx-Isf9ix`p^}{E>(XX)7`SahBecv0u=k^%+ z(6B~7b$)T<mClXCT?K(#HML1kIo8AN`oFZwPfR^*+f-h=QEY|I5X2EH&A!lfIyp)g zZfh1AgN6o;G%hUj?T!f#lJdT@T(49~FP~fU%x#JN>3j9>cJz4bFRx3l_x^6R?fVAD zx;2@1igcl21(Kx&NUQ#Wm1%#q=R>KWHU`}mHZ+dqr6i>+{p}C<LT5CiAm(1xT9WWf zAvHS|Naop}zoqPb>~P~WRf6*GM;XUUlo1_E4Aa6oREw0ilxaC>IqAv;QoS;0pmT@9 zmnpB8_KX$n#ARBm=%mg~@jCpw`S}Uvw)H*b31clS-s7Mn=Q4FU*!jZvwBI8V-(H#V z%38;jwq)lcovzXG)ZH=I<o5aYv28U;g>vJ^K40H&v|WE(5q2xWanR9`^x(Iz9W_4E zpL(;Y-5{o72!(Wk!LO)o%kAp$uhPoy2s4BdJx1Y)h5<4gr2C4F-h*!cn0i{nD+l`g zrmrR%I3CnBe-uI=clhJa6ZpA*gx|%^OV8X=Ode&iuQiz(EJ^AU8wvOp$hWCvHZDlY zmY62xA8o%LwRQF%;2mzNx3rAOWgH||_V)d^W0!WkwsO;q@t6C9$Ja@d={{xwW|<On z&)pdM+2xcMm$l!Q<&0mM{rJv?k97s+%^!BW`*1Bvm)Adw?I3>vw$;&E$ABE2W4QnG z^KI6J|6Tam*I2c~Gzy3O9T0ad?0LLs$ez3Ta(;Rs!CefjbnZFdN82xtoQ%o4mCj9# z*B_V0-PIMu&hfo?xR+XCY94yyYzO1jkxi<idFf;Kt{tn#`Z=7VFE=RpJ`5TyTN_ej zPi8e83N$YIVSp6TDBpOcMXsmT;{_4@;s>$A^;Z&#XT)!i!WteNhpvOA6(?OfbgXTK z>&vz(FFtwxa!<Kw#)*VpKKv8t3P?#^PsM8w4;*+^F6EyvjuTI<{YVB*b@*^t+xd=F z%isAz_sIp%7MsDBWX$;*LEVRIJ!IuL<2+Zd@`COmIZN73Opp!v>%oLxzDbX_zkHBu zkS|YgKPAWf99(w(h2zvXJJwB`Y9al9aMUmsG;=$>e_;+`OW(X*Y>m5fzfVH_73qSh z5q>8Yk!<b2{zU0+P=CW^wdHy^-JST~*Hwc-2{!}XRRqW7x4-gEZnEvNdsnkpiK+Rm zGc5o!+91d~l{fVrQ%-!KmD>TsD(IfA+F;PUEyrDn^s;{U`g^8dfBQDed2ii2l%IH- zN>BmMy$!jaeKx>dDGeHRmi~Zh7jwS3AkKVk-2T;y@v;~1mk9y3@VXqBs|OPDiW0Vj z_4xGdySBvI)1uAqAoI<s^RR%0=msq|$Jm$u_vl@fZ`(Uofx91wcfYS?R0B85)LFe? zTioAAdDW&?Xt9*s6)`3#U?!_^f$x_wAMEAzAMaFqC>fYKfufJSy|Sb|%>69l9;NRr zuN8QhSC*+tX<xQDam<q}gmc$v(g%HFwl7yS!FcpWaEeP|j8e}lta`;{{mCPCO!H)8 zY+C1l19CAS?KGKv8y_N~OK0|1u}G;5FnU7?ZnVkH9LmxC9aJ^8+VE0u;X*2i1@^1$ z;h&1)_rMS4b3R;?Zk=V!X3brHrz)#s!K1=j$L4p2?_&~Z9R7rS>J(C_OVu$==0BVB z<lFumazETe;^P<i^qBHV%7KM8S@TePr~!@Z$ozI@3e4lPmpfMzH%4Ze1)#5`P`>ZI z!jtQtxfO(8Xj+-KI5tZ65!i)vtXf}vK-QF{2tmZ<on<4jS#2;&e5EZ1(!x$uo%2nv zSQfy?eTKWT#QaBd_spLG-0~X652@|?0L>|ZXp+^<DfF%~GHo!dW7c_p6to`A@w6%% z&=1__)6xCWX4C|ZZe*U`4qIZjbCt7f)@f3A8dFi;vek$@Tkm)$Z_C+}mP9dNI4&GL zfU`u2Hx~w8soWdgC(e9+L;^$XnZ2+TrjKJ(;}$VOe5#mSJIYLq!9mo9?reYJWjU}{ zZVf8zW@;%fgzO5Ew~*iw&~>Lu`Q&Abzn{CGwU;s%NF4Jfih-wRA78I;KX)}(dae4; z09Do0wzrWYDW>2aMu@cG7L#&2nz3y8@|5aX(lz5dr&|<fPLhW<md#DF{PqLN-v9uF zxR49dMyyZybf<ah3Fl9-2sWR)!|0JwbXO;d`}d2oBVy|(6ZXmN8}#Vha-#00SaO?A zDV9~|J#*_f#Bs6$d?~_d-&@gf(b7v{K2{eNPM0qgXPaRs#hOpnzi2vk{})QIucz*S z;Bhm*hqGDq79_RBn2HQzZht7+SY%OW!=wSXf8c&D*e5tLQ0Bzy_+rnWpuf^jv48?j zeSlWipp8+!9aYpeR2lI~%SeTDoqK>gz0(3kvGdD|hOzAtxqdx~5O&8;g@kpX(zd?- zQh3MKN1NgL-OAoOu=&s#0ZJXu62{<+1dcJ$7PhJ^+-YjfuQsaxb;rU{xTTVQ8J49x zc0ZBZGWZ+^RK6LCr$~LRSI@qu8L<3(MB~49>_d0K7HJl|vbef&jwy$1x|1c@36??| zl!_fg?dJ+AHkfyP*x{ZfRG=RbdAaOy@NYeS4}4)Qw%cRs1Daa$DzrM^w6JlSM=vc@ z`e~jF-zR{5gN6)3Sp+Bg*1!H+ZIT9ugw;X3hgp5@Vq$yH&l}tR+q7qQrEU9T(R12T z+@Ld$^EqIR`%9v^tuVJgv}~$SMx8VUl;iw#{p^wl2~#a4haPY;Y=&9gZ|#=LBI2dG zo|H!yg`@Fem8H%3urjSh7LsRw$1x#6t9a(t=K`CeD>CTr3rn88@qzB*`uUE{3PImW za#H4RyKz3)KBYXdO%tTH(B6xXN2$QG459f7+^fwByH1AuXpY92&22s<TUCE<_=Cnj z{u)2E!P4wbO{Y3fZqOQ(XoLOnbH}@$>nm>Va!q~n?L7Ci`F5ii8%}S!;9#+OsJZ%Z zIK;%rH8L24mG82`#~*YoZCY3tZQQV&v$sadE!rxo8lYS5-{!i><JUGcK4B!BgTPE& z{>$|bOGn1$)Ao(~glN$sEhy=GmqJTeS|#TtlHHsxvhSGDldjlJYjuANwU5>&<~z?U zub9L+WVBmXw0fwSL#PVBuKVPJS%Ym)s?}|a&Kgwh4nVPXWL9E_K6CRXsx_bu%)@{& zMbWf6D@%69)c!?WOS`G{dPR1j$A+}_^!6vWPEgA8I@|Bw-(|>wCorWgzrF68yi5Ah z3;qi8(ZK6T(z*q37b!@Ey<n5Inu|zfj&WNiM=@3joZLxQ&hCOU{T^e2S{g@pT(nQv zkW@JOkB4LO<=eKb(cRa1k|QH()Wm>yW{ed+_}8Bo5@x)t)A|1B^$=t91SH~G{eyfT zv9NT?V1VHIWpk%eqoGWDu7}@2HM_cfNTvRx_1zuj#-PX8nynpgbibX};~TlD$fmgR zILKj)uo(=xyB8mJ|K(uRq=yUqq?^RU3HN|-o6W><=ldrWZH4QHXvmphs-~+=lxr3g z7axuLbB#{hKI8C{RZSVsRjD4B-Wpqx5Gbk4Y{j>Q9WlyApQiArFwy&gULI%Sz~OI~ z(7jom&W7IC3&5c=%NUxxV6`kq_4k~(zm2^&I#uxlMW}Jglk3Iu4dc%Lws?!D_oD2t zJ|rgHVT);=9%);BlmJ^Gt1L0oML6)Ox=z0Xsev0yC)@izb6dI98fUqXIuxSKePC7M zQJJ$6Z*V4p-}Lq_o~>bCj<divcx-vQK`l!=2A6qNUZogMK~7s{_D!Fb8u)!%WYAuH zTib13UVriK3bfS28p@?pfETuinHqcaS~~l#967=GGA$){CdDc{%3_Z<GgnSU7bv`C zsssZGF6e(3m7cS^m);rYbEng<zU^*vXmft$-T8UEf_eM_qK=M3b!yAT$D>Vj+r)*X zzr}9O7+#(0({2n)dtKN{=%O;3LExZZV}_;_dgq-|+e6nr(v>xy5Ln19v0e@JgEe;# z<atjv)i!Zr6Z3L3Z_^j5#guu9P+-OotXY-Tq@)z|AmdS`DmyIh`r@%AnMU^~{(j2N z4{?&5tZb=-K@``dcaof+WHD0qSo`L75rb*dN`Xyt={I41acZlEes0X(ydLuR>g<+H zKMXc%{1=*#w}}!t%H5Rz=zdr{XuGDoZVutg@q}?f)uLZW*>d${uHOvI&PkUBLpDi9 zhO08_$F59LP4m4pa<yoSY%~j&OA4FY=j^*N)p>(=$AF`oat-4vv-CQi^R`Gxo+e&r zcjwrmTq8J|JD*=+ws?J7-){JHjw_r$xYxJ&U(TDkrSdbzX){c93Y%Q-kQ#EbK;}j1 z@F%uT%1hH2F*XXDLf@G0+cdAG%SR5CPG*wQ6mb!pA#KXy^(3Z{Z`4F6ds4bJsgb+E zY5s(Bp`s1=ZPRsjpXi~Ap`?*6H?V!vEB0Ga%M@-AHW!;l51nw~#%(lj6nE4yao!<x zG-2EPq4X(oNm}MH%NYwK$~dO8<>I9(;w*&}WDWF}-k*c*BN#pHhQtTuSkc3jY4u51 zD^xhCC8}m?X(AEn=LkzFjl<WvEfa3DI@=k|MNxI;;-6=0$*HTwEcH$4h<4U8pvp?n zPs2YAij)`9&mV+nhzg-NzO*_28}v_cj=~o4fL;TE0fWB46DBqaL*io(Ar=RYINgWI z!PpADkF=d@jUZ|E1z$KTo($RgDN*R5c}KL%S?*hLjrLYs&>C|5RkroQ@=lJ-A9OhV ztvJ4q13IGa9i%x3#UX*OsVqr*)tdSMKX)sZvRj9%1@suCEIlm&|74O(qRn;E7I4^V zM7@W4uD^59gx)`HSKfm>+-Y{Yque3h<&?mc62{@<BlAUz1rLdY{Qr955JwrYz_-&3 zot+oM<O^rWE|@4w(3i*Q+N0`*a1=f#F|PvKEok0*y2wba{7HveGTh7g^l^%UsSm^g z!P=^(L{&F6h$NIHr^If7*=R?q>PqGR`!o{L1^Fr<I$1+;I|S^AcBL7a<uNS-6L>O? zz(@swJ?$C^1Q!8WIcr(m;8K3fV?&qu&r?~tbRILQMSvzF5E%^$MtO9q?ITXq@HAXM zCY(23>ndvT(!0R7!fQ6rDd2ofV<JLcr=CH;t_M+ms%yErceCHj@7Ffy)7b#_2(z{0 z^4m7=zDTR^5DxQ5W&GX?-B#zG;c><h1Dz_7-quS)JA?s`Qv0SIYmYe|{Z@6FrV>q$ zd>k!Y?c?ie6|b;%w}nvHq0cqt=1SXU%A|*qE=1{e3!9=lYxCI^Q8z+)eC3ugd3O8I zOleFX2GTrv`H@XlIOhFr+{BT4R)?f&hZtzA`AcrSVHn#M*D%Iewrps=(f?TX4c~pF z(eHK~v3)XOi%MfDf8m7)$2-1TWD%VkGE~mi6Ynk#gHT`uG8a1mT@B*pGRVlsw>h^e zE5jmdzmTpQ{gR}QM|ZT^-&(ovBj?Yti>E3-OZazLzbhK)t+VH+Lgc=ytj)GR1*atS zb?H%RRTJEoOtWd;3%fh~&q1r&Sct|ybj|&B7bmX$V~n+;<d;HX@zvM+?baTocPGxO zCV9EHmuSX$&($<*OkS^E<9lb0G_Tz|&G*Sm7I8NoeZ0|bfAIA>*c=VXxlPv=kA8?x zdCPWMHRz{hiz7HJsr)fw3-o6ro`JiEyNo?aK2>?|uy~xA`nLGyj5C(G?k$$;-^kLp z7AqhAe0CZAL+dVm0BF*-7Razn`xD#`Qaz3?$7GhRkM1D#8}u^ELXIb9%azHk-#UL* ze0alW>lea|-M>G6^Lad5xc04Eckqto9|*y!+|cKX0pvuagsg)<3tYjen!C!TPYu)u zhw1N+{%uF~&7GW(Y_liKPv@e!&)mLgw#<LB%6aOYZ}9_rbb()l!Bo{!nWVFqlZ(c- zXjRM{y>;BId-=`fmyaAsIyB==>5*!X-1LTG$ro4Ux1YYKREdnf`Se4_k1nojf+5g| zaeIoc!_G~^CTKbq83Pg~uesd_vR8SzaYmA5%nx|4EBU0QobJk8XM5<H1}dXM@d*WC zBqezVZHl6$!E^89@Q%M8J##y699RNsmTYP|=~yVYTw3^Jw8p~iFt-oiB8DUh<iT~# zbGgX0+gwdMVTz2}X>#~!Ubz?7tWfWNOJ~*u%}80S+p_qd$goO7N@C3q%GZQu#VtCB z4~HN>OFGJ}PK7=`)p0yy-Y1>Hr_b^I)Bn|lP{tlD3MsTpVRtL`Cpq44p1w_MSi5Pq zU<QO62+Yb)S0j=Fc_o~fK+v6FM?~;Cg-{HZh8;IW?${O^+&n!>Eq}dXH}twfwI50& zYRPBqx7e48;rrAO1U0RjmA68a+kaWpe@!px&<v=AW`EADIXJXM`dGW<x>tWwAIB6V z@76W!_BFA36-M~Ep3B4P%4eU)*AtAJ8U?@n4_2_=luqNOjC|)lr)I{mz=L*<!WN+6 zwB<Kw47+>#J|%#}T2oU>9U>p<U&7S6?THt1BW$9QDlCuVB;B{pclP2xLJjj;%(g8@ zqcnX!g|sH=%J>@XFy)i_XKn$S09aq6q#gOpJ7EPwDk=U$BXCagj1nVyDm2LateSSR zaQ5;s%`lPXN-8K1y@GU{_8G&nwx?8H(lt93FnG+P%(fe8MM<$n*Q9Qu+H*LSK2QxE zdRq<Ye!btaHC@LwW+y1$u7Jb_r*%%yO@)qSbyk}RsN~DI0xXzRoPlVol%9{Tv9iEg zS8@p%tx6I$qtN+xarK94XSQ~UC&&^1M<dSO3wv2E>;0Z^>otUsFoJg!*%f{BJo^$Y z@vNya-FSQyX9E(nYlg^A8{J10vgllYPo#>g&z~`<eGFRVldP0Mw-FIyrj4)$hf=z2 zQ;E4bBEua~ywvk?c$^OExZE(-BG9F|{TAT|MhU*vLGED8%EAOb7uPRt-dVPha0|rE zVw2El!LP<3@MTq1Q;C)_Psv*yM37kn?hnt3wLVDX@!)`W_%@B8XVzxH3fKpQ^^E?C zo<TUF@R2<<o@qBUQU-Yt6yWNjJxpy9peZG6*6IDTxr8=6$gjMTT!+J>rTftA-n9>) z(^3p6Y5}jXKV7WmmjlK=5%)9>=X=0ghq6cA|I##CzxA*tL`Od!kSS>6g8MPNP3Y~W za`I`Fk*`-A7X;PnpBM>r??AsidE5EPaiQDbs<->v44H=db}6Fsq{IAFXMZoHa2VtQ z1FD79jUK3|W-zrAI|BkIZF-;H0uld2xrT2#D-dAJXT5|3g4aKXP3pFp<G?SZ#{3(# z^~QGN(hux&<Djz3>6z5kfdEEGy4Iz_5_529xeR{rN!}Y5<SS*JC&}U3Ym5wH;iS{Y zRPCjS@odr^#Hu!|GyyZan0GfzR+%eA+n#8)jhOy|F?1Wg#fPM9jc9HZTb?;Yki*w_ z5+|Dd3lH?I3u6G$0vjf$3SN+&CDj*EuQM*@119#F<lA}D5<kP`4aBwzFG&j$N_tAm zfha~TxUyCn(-%)W><1@@%)3bRUqY_$qYcm%QyHeIWhNpiMA4oI6kYv=;3KI$$<fSf zs1ay2`}6DKNS(1KfBCbg2l}X5J_Xc)2#bA>@j8GEk5cOm<-!JeE81BWCeA4YQ+BMe z%tJ(iw5)N@-|yD<Z$ttACzqsri+^4t6U6b5$`UCQkxR-^dRX_q4G-7?;m#&a_Ev#p z(4?&?%M+D`Ul~M0CyDqG)ZPPZEW3&Rmh&C*=`(wM{|B*4ha07q28tX)r{k;n@m%Oz zD$ixqjmo&0$GBt3s^xY;iF33bh+0G`z<Ph2QhR><R$qpbw;NV)uNcue&~RC!EP_x4 zC#PkI-9NpGK}I4vSJXC}t8{I&EU#oI3A;r@wmJBDRm^gNmAJ{PYzCE_=j2AMaTP%j z*J`BpL&BqMnAgEG|EfEKl|&cIC9PT${ene)g0f+*kS|S`u)vqMs?2km@1p~(9EFBj zcz{q$h+qm-!85m$Mj{k~)QTvrDNoXACpSUbbX`ZB;KvUuv|J^FhPQ1Sa@9tN%W=A; zO<wnd{_*)x(-}Tm9NoY7-f;JGA4NTDp8jb+)c*Cl#?e~iqIthVW)>-;NK^`xB?~be zba$AO+D%beiS$FCVl#7RneFy4zp0LnYH^zoOv>sdkME}Q=WHTm&l#+mibQ@c|7CIu zMQF7Tp8~CyPmS?R5=Wqh!-L2<Q2SfR{?P?p&hF+WZ%7r)Nu#OtM%K;>mk^H_5BaW* z`+1N7hIw`*$z1E^rOt65#YhJcGeh){n8<ZY6f1re+1jb;d`4VEgSg4jZXe_!Dg*vj zVu}!1ud4-8i=>_I)*Qzvas1Ch=fxRAx^m`Ce9<sANXG;wp+3%JiJlfCExY!Y<*CPj zd&n0}Z0gMt@5xE|;?UC>>tML7dw}vt9xxSGX0pC0+xCSEg%Ej2pf@}v(My@mH|Atv zcZt3is)U$MV?}hAZWt;hJ?XsEnksqJ90p=@03$E(Nk~;!=tSAEm|STG38NrPZP&%o z5~y)(LaTzYj_k3$T}<}tCQP|uoUcJCqGJ~*J5X<is6cE#v2VVs#m>%2us@}g<AWq5 zokJM$S#s<!QW|G6G-WnZdyBIZg-FH8fv9F`PT9ZSYoVk;cEgK{OuKq_KORd5NW?mT z`)r=hh_q@Zbf8ow%oAZvg$BQOw{9HDU04<mo~BA?D!VTKLMt)5lAA8zWn&Dr7h^bF z4@4dc+!W?}EUgF}Fl#ZMtMVO;{wm4Pq9v^$y|FmUxOQ~P$I6f%KhR~d+9zITi^ydx zs>N<<H9N%BV?YO&d<`_Qge?3BW^^Pk!XV7Pwq+!~%lLEQ?J9ytbkm(o(3No<pSk@k z&^<(j4aCH#crY_3Wl&x^kTbWCtcqzh2$o@q`FF~t(~+le2ystL6k}01YEdeCu5r9U z#`G;PJeHH`qJ~;u@z?&&h%`qG@;4A=4QeH&P~wA{(};^j=2g*TITta5ItDvXo*AFe zi>S>RYH~#F|DCFtJTZ%OFp;9XLF>(gQQB-YPh)VFq|>|?R<{*dD=P@9HlF~&vgbKA zQ@AiEnUTtcB8n2^9<)r+k~mqzMzHSuA-8Rmu>61rLIs?x7Hg}`e;=<_jc0#)<AB+I zN^WD~22vHhdjTO!KUnLsv3*R{I<0FIrWV#e))T(%!np*Bt{xMrRY?sq(aZBmpdU*3 zF&a}11kW_JBZ@iIilB+@A7A#Y#tP{UO5-6+>dqQAk742zj$8TEJ5+~FN(F91lpMT@ z*(9t+GUCF#9Z=Rz8u!^f26KpuFGfoALNhh7(%Biojw-|**9nDpA949xuLjf2PwS>w zUq*KL$I{p2X==p7$($Q)DN13IJ>!;e;P~}q7Ep_BO&-&=A#)e8Qv$Zhl-9*c;X5!4 zoDB-5XineAqRz_+tIzHP@tD|4cxRFDq_G_IeJ~<myn?#=SjS&h4%P^k%4l4~6nW%> z@i}%ehz}d_G)~v3F#81?)s8E%LO~BNO}I~yDM`9JR|p|s&8)Sdhh`#ngL2&cxk+#y zXtfj-L-zoNBHS~zH;TT|3fj$ET)Un>W#f<AT|n3^71A`vqy;EPro6bGO~-{YFqm2A zjD=)f)A>z8I#(`jvDTE+Q_{JNhpoM#1?0)JiIvi|Td`3hz+lQ+;4A-_8DG~+o^%BO z=YRZp0lNsT3}haVrh?Ca)R{>%r%0t3pnW4e?yE=60iC$JBKvYUm`QYtkE@_-dYWt= z)lMYEpCbH&x#%=IHcb!R*8qPQgbDjz$VZ=g-;(5-zbNR)ld2mzryCdtCjF_AGM&06 z2Bi#obCcr?T@^yuI5%Zbi7~bxp%I%Bp=$KmDsK^h&8-!vk`SPyJ=4t?ZVcC*-Tzyn zBe&%$gw!ZXmc?0O({TF5Ldmji=ZI}9A#FN8hM>q$uAQ?yVlVy@`<-Yfgl$_Za~_9! zDv#{YwF|WBV5uB;k?xsj#-Bx`W8sJ8{jkL97)9R!xEpuh9<gwh$65#RW?Cf&?6ctq zn-tB?{Up#)k+hbPB*!(JHb0jyxlSW(pU3wPwCB)RA(iIl1H^bHAy{Tr2GC!|*beoe z+qQ%h-A2qE7C0-}Jlg-qV8wU1Xd+Ie)W!`VAQbO$lLSkxC~#eOONwWPkDe`Od*L)A zAEDI#D4cOzxD~Mg>XuTM$^52>xU6+s2J+R=3J~>g$P{l7pjI|kcbcVA(M3#a_VEl% z))=-jxO=3j&L>{!Cqg$qyT*0;r5uw;9=Q25&#F|31Wf4@X+<vQhgyaiVAOgzS~hYr z0W7O$i|m)^?aUr^kM#d3ko_7H($k&=uL=6UadH&LeS`&ltnBovIa%Z>kQFd|BWe=V zjEK`w+#OLjt@2GH7lJs^*epV0ekP8LH&G<ws$wX#27oPREcI7PR$d-lqW{3&EJg`* zqA@}gWsq(uBBrUA({zo!5_zW>6Z&MQvPfsE9`yX~Fn==%I=iJsk1GN^kdO<2M5Pf0 zkj`@^n}?o8pffEpDV^xa__0=GFvuv~%y0i+gb<~vM$uW^e^|_DL~u$Og26S=J)VWs zGH%y;L*uu1*Ty2S)I@<kqt-?|a*Ifb30Xotk1WBlNqF;~mZT!*eVg#XZZhjd9WT7i zahf}h7A%*O{tOKvtl}ir&?w{%uEcnLC)7q=;stwu`{FfEW2`~zstv5Er1ds8f&6>B zn!SMW#Lx~L`tFbxIes6S^r?K`hPr|yAXJ{zOGu*{a1;_@IeScC@;8$#sFadhQ1{)V z@nq!+2{{QWXg{m!Ekcn(O?e4Ph?tG8rD%yYiD9P|l*8o)o(oA@v)%T7KyDhT<Qh&P zzYtlh*o-css|+)uA{#!5uM<Met+^hHRGv~839wLLwijILx|Z;RI$)j9S#m;5A>!CW z52|kxvt|q!a}ZUO4TPnK{C})vNSD}Cbg$6@SB<@T%GjxV)M3@+0R%NQCYq+He7D|! z07SLmFx8qLjp32kCcH=_CSqIClDb;CfP_20!>or;*VP9II+z%^C{kJ4Zv-zmK!*)6 zyEMCRsRng_x#5>^Q!I|gJ1k8MwrLjo?#$U`>;(=m?t#dtQbl?u-PM@{BP8yzT67=P zD{LYFt8nsFCg(mPZ$jgHQFv2-fzyn4+o$kA<-?%!WAsapG|v>GuS6RPjacmYrus2L z5Leuvk(Rw2j+s`W=fguYWx(es-)PXf+!K=a<6!OJ*K<fz5hgTArL&c3qKUgSzp_L} zUQS`7wrXa`(Ag6fprtjn!g&eXby^-zV2G?5CwJU1wXdF&J4(b=2U>>ZCJ{L4ivZR} zvTn+!SK}d`3TQw$lPf9Dp}`;yx%H~MKP*)6FQ^EhFi4KJI2TP4?Ycr@T}1D~jxa$> z{V6my01_@`Wp-L+i3e2*g$RB$o+9rjSX|(WT6S$01gBGqQ}SIeNI<nMbYtSOz<Igu zS|)XsF5!eAlqfzZ3st>OU7;eGT$-$t11gTRn5#o}c7V?m&o4RMkoXOa%&Qi%V$?BE zXh*m@Uzl8hIUcmPaygls96^k-Xqe~<N)tIE0l}9&9}o`}nZ(MtW+B<pd1tyXuAKu( z83|Q1hOPOq|A%(e<)&9ml1bz2^s~==&J|*xWre^4He*7}tOFHWwk=wP#<|^m0#Rc# zmbZ=h@aY1mBA+)ho>49LSSUi-Q4FG@S3?Bl#A!@Qva0P@s`bQtB3-nzc31Iy3p{l? zY5UB7il7lmJo?9|RIGJ;CzL-}qUx;3o4w?0x46a3qT%SFbij3_B<9II8C!Rdxp<VN zYpKEzdZRm{lJ}JwI2f2iwr{nmnyC~5RUjBy$h-q4?761)j2kwQb4#R6Ku$&3JJWej zj{*kWgtK`HBOgF^&Vq(In9mth=&9pU`ty(>UeBErqIf)d6-BhNl2r)j6Kikggf9S# zqa-0PDPT)RPob*bGgj~)M0~`>G)wOy7s&sXrB%)GJKN!)mBvXWYj4BPRzX$;udzo= ze5|he4-un15I>>)!q+aV;|$-88C2fTkSok_p{;Hlg`XQ!F@&dQ4v@Dv^2pZ3&Eg%U zSqiHbk=wCYB}OgX)WJ5SQ%h8$4_IsC)E3GubU;PFNbymr1mnZw2)@H2Ao+fP8H7_a z*qa-hNHh-$!@#+Yra@{gI(%wDI+HbD3!p@ZZ9fE+IMc+10`q`Ye3f08l}}0`;*1gE zc&99JlDRznWB>2o;fA<Ijt^FkzKzTz!td6w_B!{cRvmUb1Xa^^qpnfOU@l+hDj_`` z+N)Z~@w8xh4yA|~1YuLspGs4wnfo)MHp%R3@=X+{xbc2xf@q&H?vQX?dF^!*e-o}M z_o=BINjWQov#HEUB|j<Y^M5?Od0f=>`u?wFN3C-rsk8+dPmGN#7J5>2Wa5)G4rU{6 zxPVk*L|O()IEK7S>!?{w3?h*^<59#NTvL#oGz~}4QNT47jb%iTWrl5-rQh>4eILJn z&Pj!t_xrWn%XMG(bz|s92{~Q{(B0xDv15!}>0%v#o_z^Zgow``2-oU~+dM>6->|3E z2DBV8uqA9@EeQy!K15^P)E7+9+n}1Ezj54#*UTDtt=l3$vW5oAx=27(PgOJeq}2{A zlRy)!?VApk2$^yoZ)mFk5%#7dLO01sm>~YZD=dHdeG$umld-4-a{ylAT;&O$G`DUh zbyJsq6cV^i+F+G?y}Buglw6uPi$O<{;1zn@dFn^r_=k8&fxD{g7k3(@mqIZXLLe!_ zmzVFwK-T6a59;S@ew`@FB`6$23o=Nqc<*6O<h6*nWtQ4gt|QcOi7APX%&vqPPKMlK zMucuY4w$VJ2q+^JvPI#VY(qStdJ^!OK(u~dF6~<FW7~{#7a?k_bSl7$F$Q}rI5m;& z;DQ}o<2s+MO@kPCaVuNEQR^u;P!JL^HM`cd*J@YS7UPCFVQKNVc9U86<t}6Oh%Sr3 z9smk}Mwa(r!l6aQv(OOi3xgR&Ejpvg3dM+Sp^2{$$(-KjxR@Hlo_pu{vewuAwcJOh zSHl&%EKkyTv7Q7pQ-}2#WbDhOr1_p%=rRC3UeR^_<@Cw)@A|e!>9(3@_Y||0ff|s| z!PebDVGNN(DQ7%xk2|0f27H$Scg^rj{1lo_DFK1e<ZGY-BJH>X&EI`qk$DcDq4<3j zEqM?6j*Jr&j1+}0<bS;vV7ag2XxoCD5T7WXgy3QPJSYiVx4I<^P`hqXVTNfHMfZc} zw?^#!l7V*6bD<!R94zQoT562KuUJEet#}x(3-X*H`C7JZ%JTvuOBC;{B<Fea*WDsa zr2aoc<Q%f>K#`DNx!?9jVNgaG-@&m|nhU3?cf`;O2B`}Fu;I%9A<H~h6dDXUAZ@oP zp_IbG7<Oyr$G6B+2N@#d<@sVA#q%%mM!Y+X-0yRaIu?EW8Y|uQ)b8>9I#b#a^FbR2 zRtyCn;Wn!XG`JZLlVu$NCVTm0B?+&>G_Xe`Rs*NwK#4>|f>$|r*oC=KaR-IpgP>-0 z)+@=B^^Moj>~cjjLYUGCS1CDl>-5!=?_zJLSMEZqM0kmYE%WVnK`>(k08bRK3QXbv zb6M(P(n{T;h;_f{i|56RD%bS!fQmJII}<T=@*~W!e%OjVEgY7cS${xBMx&v|>Heli z&~YwFcW_RCF>bwpQSj6DdV9=uAaV<7oque?$!N)JWPT^Y{oX@U?L_awxmqY$cy8Il zMJ0a9!`J+RL&L84dN!EVH0uC1B1to_ho)DCv!B`f?JgeVG6`U=e%1kIoeAO+IM6_K z*uex=@2)}RN_hQI?h0_SuV1tFvJJAWh!R5ob55m`Wx)GbuHJJh$SK98!-E{$W4=%h z_BEO2rNs~>5TjzyognEf!lsRu|Ewbx@MH|qdw?8N&9(iy)|44k!R3VN?a8UXY6AQj z_yrSlus^XD4p$&OH0*-@m8F;aiJ{Bu|1)17g6;6#;?l_vdZf~s%c&Sqz1>EOjW5e- zH!dIyihtW%<@45^P3x861m=Io1htR>w)VZ#mr5(Rq2PQ>5AU^^vlNiEK>Jh-2mJ5Q z;irw-e67NbH-G?-V%A7{vHS7*3ilE5B@tn#z0nzh1XZ>N_j*W|7JF0FoD3R8^AJ<C z_${mkNdN(9cS6+pe{B3-3;0o^1#J;UxV?dI-ZIG(oylK&_V%WhbvIK&+P8Caz3Gpq z!jn~|6p@NljK6qx*}#DQhe0*<5V4x>Oup~>C;uSuh3492nGKAujLS|GR#$S%KSS~o z+h9h6Jm=-^=>L^1mo3Vq4k+W+jYP|}<a(<3Hz(&f>mvPUbKhgfTU&i`3Z?j3wPM2v zkv8R>y)*IRHxp!xzFUE<+GIM;lw<k9HJ#qLR_D`L44H?KTuH56djK8Wh3<18F#5BX zv`Ech;a%rX^eanNEg~jo`?+<hyL%j{Y_Uf~94n(HD!z>?Lcysor*9J>uGe$r#K0M@ z_nF>$%upf7OBUI!Jk5>(V>HxcUBck`ttr_rucb`Fd{Yyxw6s0(>l`#YQ%beZl?=SP zHbI5=&&_atE-F#;zO2pg)=AEK*ZF#7Z%7|0tOv@<?0=ztY?&hv$T>#+MYZY^lh4}6 zgn0tLl6|K8T~!@1R@VMGubiK@=tCALG^I|_d{+!xl?Y|b8>RQG0kVcco+{V!LVd{P z(eDBzVZLeNu?DYK7Lr|ND-k};P2TbH+Rs|eIn+;Cd8K9O!b>*V4*(rPRRozk%4U^W z!$NI#C8L={Au?@zx<;7gP2Y!O(KM=*dF3mTbc7ku=8&R71ngG5H~-Ja|Ce*nDzYd} zm!q<uNX30zJ6y=T=_`^Z*Btk_1-Fyk`m4tQn_-OIc2w`ZIqe^B_Y<WBev2K_kAhuM zrFDMTE_wSo@x{w-3Wr##VU*B4nF%@O+Xdph1XaEM{QS>!#yR2uI4YViUGU+x*Z1qY z)ORRG^+x8BUl5alx|sg1ePwCkX6yl=fy9(6f`;=-y-$t*nzmzj#KeDb7Fslu()b03 zvWu%f?RhhJ1@aEoi1a>G+o+_7;HCEJ5u=Pcktf*iPNZioxS_T;44&MLJrVH>!7Tu` z*dL4)F6?+Ux${qk*~dCwED<OG>02VB(%!T5&aR8OSrWcGW55q<1Ve$>+iTdwKa-Lc zUDK-}t!R6D+`DM$!!d6Xc3S{*x0b7KD}E3FRJFYd#HZU5v<n!-80(!x?ABm{X0iW= zHX`G%-TsV(N2cnu>aQMJY~VACd;mf^@DSHK=P+OlG_SJ#OS{xG0i;i%VoJdRs@WJ6 zru7dKg@`{A^{+g)AUe^a1gn&<_bsjt@2Kiv8jTuEMF0-<I~Hr8-Q3Z5O>m%*5Ln-~ z0z}ir06?j9vbdWYm-Sr3ZVBYUaWU6ZW%8ASZ|bLTYO~o62O>Pxm)zXGYHz5j-jpFc zwKVLT!b~Oq21mvp{F1~U`Jp#F`d$W|X{j$dnW##cr8@X9$S}@ZCBplZ&Ih{Hb=n*% zH-g?yl9Sn7NroV75l~X$)#i?Xz<Bp6zG&)e>S>z){fe35^m~qo#052L`C0gDRMY|T zIE%Z2Ox88x&jLs<jkqrz+K)r|1MelAY(V$KubAtN*I??oH*Rm;FnUmg1=&XGBEsvK zrP6yh$&OD569WdAw%5924sq=<K_qGp+V%X`0bbrp#OXPc99V6RfR!GLMW4{Kn{d!+ zs;B4laNer5Q%#-5R5llZnvW*@)aI~KUSlns$)qxbVp^aH9jOn|aB==x*Ra!}O6yT@ zPsV2d)#HQuLrP;Dal<tcN4Ayk{2_SRWebrN1yU7F?WiRKHKsLlqPTjZSd^c2!jqL} zRb+RZC>RZIEwO&y2>2B_gkA&(jfg3IQF!5kd>L_$08om3ks<`y2M@;KKSL%__$xW& z7p&zwl?}TxBPt|XyaoH+7vaxJE6v5$(`Y4jMcaHSazi2w)6L$Sv$RKbnJnMiEOu2< z{q$=Z?W@Yt0_1zgp=)c?q%7SA$;X=oI=Xe@lN6-{DD}OT7)1pMLS%>ke~!#CN&Lsx zHfIuPyoiWstbjj#KYe0<!RUwu=hD|~&0n}VooOfl*y4!tYHe2Xwplvd&0JXqAP=!@ z(bONufDf!7pD>By=ELO{)q(BC(4fPDaSZ^xkAu^(rPohY#HG&GQ-FK!Bh(ki?r~Ub zrxZ;<s(8BOO6QLwD`l<qg2i6uifv~4=Hn9$t5$2omE+`=qTm<xYALVpGG}4{fbfY7 zObm1lFoYxhXp937MQq>Z^+rW@>>mKfvhjwhC3t(f>&^5~<%O5UYZ=p0sf`xResbYv zoX85m6Z37vXwg%Ob2tNm=bi3z!kaPc>wNvYnTW95z78mN#8YFRnG~Ba8d0W~Rigmy znroaYYg7H&S4*`j<W=0q0e#JkeH5@;Z83vtMP3o5@$AjB%CcYH(3^H+w{xg;Y)loA z_nExD*t^6_0VRXQkWZ0_3ej=FdchZpfFSwlh8LE6FP-b}HwrKXKwO|S*>7h?A0T9D z{6ovo0Z*Ks2;1}g>&pTvMbv{w$dLz<wu+?GJi0ThTsl2<>0*T`Fmo}3x{`E($XxE0 zw~oO|tXW<~nObls`X_m#(GimNl6BG6v!~Ufq$Xa#+?*M*Zx?#bm~Q-h5Ch19cZaN3 z#sqM~#{BUd2@UYWwz4PZO%|O@06F4#7^J;<y3Cs;bumD8KdN27WR+{GE&fx?qoy*E zk)z-wNijFwCl37c&rngsCy}kS_L6L#c<+X-=?hKieZ#IOny4J|3Pq_HV3)v-^Rg~$ zs;5|T(Et?*eqO>X?0uNoQ?r>xKZzecvh_si!8L>TQN7PB741qn!?Z68`f?%bO3ns` z=partyPUY=a<88=p;w~tqv`stcY;}2l$kOq10}6GKl@Rm;p$`n{pJ@mBFypJ!FF47 zW|RbEM|zt*YOY8O#P^TY)h@=Jht`~M;2VLC$SHOOwVnkYB}$>1;~AX^hhfIRvLD)R z@YzCh=CFg}A`K2W^#2S6l`AAQu~9Fq$SfJq%DIXFO}OKuq3zLBzgSq~2&+;iNfn_r zdLhO8lB#h6-{{w-f%FUP?=He+SLQOLY_$Z&Ma|cYAv?WL;$`8*V<q<y!yIOCp=!fU zy*HL+%s0k2%e)@iJnQE?@zjdgs3I1$To)v6Mf65%*QEAP1+R05;=DJ1xA-s{=9Pk= z|MtwYvBi4NNcS1RhQb>RofCXvoI7YQMU!nYl6B%ng3j>vIM1!m1}umbHsG@91eUg~ z{7_u$7*jF*JrprPQ18t2Ur{u!+Mqh>=@OB@?AFeA$JVrbvZEJ<j*4Ig*L<9>&}UvQ zoqm3|)^+Y-jmi5XJvS`;@SpT&Bf<2JQk3Pm;kZgkKZF+?YHG<0Pp%aNI8F{*wt}vR z^HHP6uU8J-9qv7Zd!$OIWc2Z)W<9tA9UrEf)%juCey2R}_7Pxi`JS!{jc=7=Cio|t zTE526O&l4|`SCVEtJYnXeQ7g<j=g=8FJT(-3F=rJhCha9>d$;89$P0juuPFcW`xYs z_2-5sZ3(ik;?~$)$@&ZtR{EgaZQ93wcc>MAG!l=+X4|O!lP;Z6S3jpPXm}3-@|@a6 zMv*IL1sEBJC@hxLQNH1^^ljQF!vk7$D}P2w4CVvoLgiV;u(W%d`$$(mntd`JqMmo& z;7`9_Q4}htJ2r?I8nx3aCt?Ta`X4R{@TZ-Tz*#j)qHcD2f~reBQbC+GeYG&rq;*YI zEW(X>OZt^`{4$@Ihry0D_J%LHs(Z`mL=^Nfu2&v%O^zY_<sN=5r3PX}`^GtkPwLeN zjG?MO7x{|!oiclQPFPkhaHwYol1jXStT_J>?bB&CIDv)u;BC?XX)kx&jb&>Vl^a*W zo9iaN*f<{WzPZLEd~8j4q-Ei@Q@xVZN(x5SQXa*0CPi}m28!(%7OD)Vji<K6b^QK; z#+A=}Mx(f*xhWTjxgO*Q={>}w690Z;EV&2gW=ysnTAcmaAx$lXI$|u5`c7`Y5TPly zzT^i4v3$<<%emgO6lYP7QgmB8unJq$bsr+sbv*d4u<5x5^@3$D7fQBVQyj%(svFIn zCL2>YRxO)t@S`_36v@l}FPHpJ^YRAZ`Hm$}G*N}QQG0n{N2a`$&UGM!V%(<6Gdll~ zi3?{Ni4m`W0}9A1b9!Ylv^tyy{HC1F2XC!>X62?0OX+E?5@5P$-mq76!o^tEKJvA3 z?!qxuDvo|M6p#o<&VNQmNWt3CqN#Sg(lZZ+!)RgbZeN)bF9ja#O#qT7${bKW)Gs0E z60%)?2INq6V4l+sg#<lBvXD(CZ&Pu{g#8i3>$IKFYh%#3j%<@24sn~Sgp-H-djG({ z_G|05+JiD1pVIZ?Jdkyx6Qns=+Pgct|EsVh+w>H>fFX`QUwr~KSa%v_eWyVmT<uNc zT`{EN-%YvPl@8qg?~xK%EE?)k8wT;MnFAICLpciSB!&X-<2sGM2U#aU?q~+98U>|a z6prRPZd({@z<-3lHlevIqQHBF@(||Tn=gF(+(=9Hi%xQ_R`z)6@Gk{0DUrK-#(1i# zw!<7vR~^NSd@SF({eb@LHPNier2yf1HdX|-Tw*IudoDKoPSo@APcf;lit4TGxG*xR z?7=;-3Ry9Pg~zObml@71nOnY8;WmS+i`?*hbqzpiCjmzD<=UHSya$h*pK+=84AnZh zah$ufunJy_?MmPFGmapva8B*j5#NVX%gi7hK!$G%2?a!e_XI=)#qrS;SE8Jr6^S9n zGfmOtS2|#<hzs`DbkcnT4~K_`Z{l^FOaJ0OxmO2ODY!~h-Xm5|UFL~SlbRl^#Xh}5 zPkV&w;aAIhelqoaKTfsKa$gcojCHs(@rpKtgA+220R##dzgH}e^_cIy&fCK3UH>1f zs7TV~M!{j3%aQIrSF?*1<xd4#0TF3mK1luNxP05xD4>bKGxb(@Gp#@h%l=1!yY`n} z*N?uumk=>+l7QIqqy!ub0iYP8>K{=6#wRt@8`O3kE7n%w`KEH)nUre;B5OL49g0Yw zP%o}vIH?G{N|ooxc7_qH#6~W8pnEf^G9@aBPN{0Js)XsQ@<jv6?JItw*(uR7ebpuo zF<3fj)UNkSRsk*UOCMKn*D7g<Av}7}=Pr2xM<n{e<cCs<mx4Rj<-GB|InvF1-ub82 z#@$LMK}7HrisbC<u$?z%bbdba>9XB-k7nW(^yL3!8Lyw7vb#oK>RKg;KxGaPk$KFT z>d+BzQ+UdCjl7i>y<UjiKyexhC(p1dUn3{V8VrR7+qA<{2g5jb>T5n<CWev>;Fa8M z*s845U!&~)D@aGIgH@I_aHDb#?JLOx*cPr0TcBiZZX9DFyZ9rYcDd}a$&K#{@RayL z1rE0AzkRE9N})l&H|fI)I%gE$VVz{x?Mj0#+n+>2SJ^XQ<&wZSyLzc22UK{GY|&~z zmFH<Jza6UWd&EnrrW1me)q-5{dyT|@IP{-4_6*24MP9m%?3nI=L2Ibtx!6;<w>YJ} z8C_|8uGCafebQB4TJb?&k#RA<Fe5Vhtn3!FF;X^MHY_b;Tt9A`ADPqDZv&qfKB#tw zCU9*+orWSA7+R1aBKp+%$n*z&sm}AxNOlG8Ku#+d2xpX6ch%|+>cG|C)_B%ZZq7L6 zt77IZZwkm8+d)YfAcpzY?TJ@6>5~Uu6FG71js@Nlq?V|_3ZBF{_jyB~K_HgCtZ7DB zz_y#P3+}h>Gp6Z#fm(@Zy=c`wQ4hoaKvP{&U1oaYh{$p|{!v6%kC861t^$Vk{fs$A z@dXlZj4GgHB-ZMa!ZC(%HLI}*rlfJz=_mYpT579eypGPaXbHdn((GK>yTn*!2dFH- z=XHeDh=#)_R8!&XYfeI*;7h8CZ0=t)uzyWc?KRuRwU4@$=9ubBtd|EA9~|%3HTScy z*c|!?pfA}vAB^qVpLdEzDeA*i;X>v6dU?xNU+Xl`<O6|=yYG$L<H$QY(cJA}EW{Q1 zfzz-VZ_%Q1s`P0x<FEI>Cj<$;bDLdF+x35L+6;E_*cqBCd|*xc#RI{)mAR(U^r^4) zfeu0vx2q;|o>2<XjH$YlDt-v2-zy$d#$`+El&N3~I#m;2D*Wx$$mG^3nqzP=zzSIZ zBAfEU6wKX^O9eM92Vb)N;k=ElB+z*jF2DjP<AAlB9ko}p2aI^fpjzKCKp=23aNNW6 z6KTJh?JufB-ub6o$8h`cB392&`@F$5w|b5BGPTXQJ}#X(`F+1*1V5UTh2+fD_6Lia z{cbp4l(ih)hsvq+(Qy(v<#BJVtmVl5L7AQFlR4XaeTDcr{%Gd6mJGhL*;W#0Q5Ftu zMF&xr7His}v!`KmMgLyHmFUoyJ~`Do{q%|&<2aT~R1bS?EG^j3pYu0iH-UfRISjyk zbI8Fs7o#(!#pUK&c$8FX$lowJdaF5I_0p7I*bduIGKM|X4bOV9s^#Y~*D^a9qnzP= zh~KnKlKPK?{Hn4-6DF3~Bt2*tP*z!duG-O7bw}-$tTeYgjJvX3YVTfxY9bYm=CLeR z+Wop`GcKKK{lAJ%>3(*klP3XY=g?eIFIF@K=Zb?AC2M|7GL7=iy*eWC!E~wAyP0FR z*M1krlj|5o^`&agDH0{IBwbY^kTPezQTx_UvS&sjrs_Vi%hxIav^QPT`r7I4C-foZ z-BhDJ(JiY4Za)|`nw@lv4D@~MwehP%N8MemRZXwp<Qw50;GjmTtWMAEp69>I@eVl! zi{%Mi4CTMXlEMC|(^hM5sS`wVZd#m_cCh%uywD)WsJ1F+yg<~hn7wcCG0Q1ZJGrE7 zu2@hIvgn87jqmy%G05bd%XmTWJSk~==AU2ZW@>Ep$L>(BK$%uicEwDXkuZl|Ky^Ui z0w?}AT+y-dX|H4Umx6{Yw-dy3wMRTyll9_g_tf-pDqY@fs=Q)-2!zoXotf#L%0a6? zwtz^F$l9~$-QrFvZHA97X+%C_9gm{XsN2q!M`Vo*V2R%N?9PRVTa2MS;6RbEBXfOt z)WePRR8bnW9@63~YW6J+@gilovXTNyLFwwgAaq#)4s=kerXLkO-vLIo;2e3}yX)TD zxp1+!|1$zIT0gZ?<e<37SyI=W=~Thid}0=|=K7j_*W<S+yO2`ga3Un^%2LortO@9b z{SPgdAlm9)KQQ3b&iC7-e%npn_l`w!PRJ-H8CCR+SQ~SE=<n4fc1=Jl(8V8}6c$Sz zV=F+1IZ;nniRL;biTF8Kn!8TUOwhExKq+usTaJK2uELSssA(NWx39VJMyH5FDV-fk zbrlA0ceF1hP|c~mNtI0}U(=b`U^WY2<p`<sn@)c0i`us;jY=bx^D%!EK+#C3755=! z@XXAT?ABARUtY%T-+?s6mefRCD57o}Dw_+2Li<`^ysytUEtSjanooEl;{NZM@}hku zY5P1W@T1rh_Aw@>4Qeq5?%p`U@8F5A(J!@<$*LEqdtsZ7VEHJ<t>K!$T%>c&)EZJG zxOM@{mp!r3jACZ`e!lwLSUMitwtJr*IB$i`Fm)_bdFP5OaNiF#&~s|cCyeN5Q53d! zRwkC5^b467foBIQRfVK~5RjMcetG;xyL9d~k+m5EV{@jd|9tonT=ur>?&BiuNYcFA z{Xbl+!!r1Gr58g^jcPd)%(y)%tH>UhKwKNJV^d9Q;L(7z*bXfw7Z{FEz{<c=)7g2I zrearbEbPa_zRD<B%A7dusvrwG+HUhmP`Mr2+EW0H%c_8(TZ_IJp;&h`!CYHT2~bqN z$GJ6oHL@RC1TrWn&2#6Toa7%)G$C@?YoY!d=7T+`I+5!kBih-0fiX1|bSr2-{^A&` z6SyBBVLcCp$+ijbCDNL|cv@N$(ogA=-DeCDmZGD$CsTdwaj;~j=G9cZo32w;HwgY? zy0&ogXCuP*Ek302<`XE)(~$#IUrA1Yhe7<sVnr!hugDs&W1~EK*`m3%<*Vqqvu0X> z8ft&aO5HX>TCzASTI6Z19=glOJEum?W|n;@Od-}f<BDd)LKL`fSBif3qX&f_era+| z27J;lM%{c+bmV)%l%{;leMndwX{85Q<ZnjFQGt89U$lDaYdH5$1%$iLQyW!uFnzMB zx_mh$2^?n4_#T<o%I${9-fP0jVV_d!A_sTuuYvaA`wNivxs}p;YiL*sgpvrUT6W{0 zMVS_}GlRG=pCdx-WTIH<+0!&RNdK^(MYuR_)D`j$lQeLjsh*~|_2h?O@7z$EJbC(r zIfK%5gN~&4L5jzYKm-*WJCml8la<RjrlfYFBULxpUn`mib~^0<n{B(?>)h*=$A{Qy zAvT0FTIuAp=R5XN{%bP_c^3JvqF|~ziZhXvMS*_7Qt%YPvHl+L>;MkFcFXIH>SVb$ zF5`9;&nFErV*J5wa}?P#=n!a91^b8)0m;3-4`(gcaqj=F&u`k;CtXJs?XMnF$dODo z@7&91vdfy<heDBPqD2gb&gjzbAhA|5VG*EGFlRO)thA^{xQg{ukvz~HlS$)Z*Izv- zTKv@`X+H!?fxC_dW8;HksMA2{oA#Jao<2!re&m69x(?AG<NM;dT-|-tKW6P>x-JY@ zc=PVHE+$W#GXhwy0#4DD%6=suf++$%f2=GzwwQ*+fRv=SI-y&q6FA<91RtZ`@DoUm zta<FE2?)#k3msuz+Xv%Xo$1?GPZpz#KpbmJX3MeqnWZKly23cI@>P2X^Tg7gKl$E2 z@wm(`?koH~jb-`}C}6>%fa$q7xR7x+p?G6lZVl5;@JL*7n@L0hCm-}69zF*-hy$Hx zm}yY=?zX<9qpiI2e$fpTQ<92>W4R+e_7t>#crdiTrJ6ag%KJU+P%W8sE`k7K7PJj} zQ=hgQL9li?dJU?!SiG`!;I(XdQmT*fvMHlNPI{LX&zQbGOra>%HwMPC6H|wXR-C20 zo<fKrH<PQUk#~SJ2`b)HMwu6ozBPxP3RpT_ZNu=a6R@W`htyT1`VV(H`F`Jg-YcST z;d%66z<L$^D5re7B5&6i^aur*Z=doWQni~-P1pG33FuH0?;xU*hFmVVC#L7SNQ6u6 zpCW&Bg3vwHS1R1MhDYPgazOX(3>LIyLrTNPGO9M6xoW_}K0+AOIaxrao02{y6?V&6 z-`gko;EJEF`;<C7@swxzZpsaSECQXkZF%fjp+Us7T+j~3MU#-~YhVY=$*^!_c;}sh zbGl31Ryf5)J(NzBt%&U1+RPeqtgJ$XCHjFB0*plGgrMYfRf8vbCvh1z_M~ewh+I0y zrXfd8@z)?5w%Z1-4I>=xToTEX$fyM;p<zp}>jiQ{c&~(xLh8S!_KP`n&><VZujvsr zOonACV9Gl6Y~c-X^{^Vl--=73ED0KFM805GMI*PDpaOoE4wrjG1awG_(sOZw@?6>O zAR?omk|gWo`;We?A>S6m&5g0GmjOY=f&>?coLUr>Y|}YmP8(Hks4U^HjgI3)eoDsg zW3Sav!wkg4i<oEjMvzGgf)2TNe7e>_^ThCH;z~N!v6%F3kn7Pj#Ze=$%|Bwq!-r^L z`gEU<Hv!9y@}+OSsXoi2|7jT+Ck$e4g8By8cg!F@9lX&{@K=vr4i!yAmAojcH<DiF zjnR*X#ZW^8h#n^rq5SQ3n~5=1g~KEGraG8ka(}Fc=T0}CWs~VaH6P5?+&=Wn%)#FZ z3-6=CY|3CNscSeTGuF~F4B0M`n+IeC=tV%<v9r5q_9MBUqP7*cjGheE3|{pbF$}9a zLDn+UE5Ta7iN_u)@zHM+r(`%c{<?eMzD=}*+xWuz9qPf~g5p7$-Rr_q`{=~xtm%KV zL3?M|i04?<B<a{JZ)vS1$imtV(+O7yQ&=aCn;`$<>zO@nxY~ynX9H2|Up<J$O^Cc4 zO!or>WE@l{CM9ef6QjuLOM2&Y*2hv#Q?)JXp{@zHk(@xiu26ew)dRl`M9R)oyxVQ% zX{Kq2LQM7xs@lBn9)@v2Tp!WVDMq%UYsuuFcku}ICimfOnz20DNM^}qvT&sPkk#bU zt*w2-ehZ*}NNoq+blRk+SZ~%EnJ8{fVr5{esrb7fJuM%Rp1q>LCRXkB{#-jIK7$Q9 z>jy^RqM;&AqI0mIbQ?R%yS>dEzJQHA$QPUWu;pr1Hm%2QGtni{E~P%qx--GfjQfH* z9Xl+(p7itNv|!LsU+Vy+nmmn)ow=1fUE^j1^Xi7qMC@+F7h~}D6iqo*qJUeo4QIi< z9U(Bm88m$uw4<0(9VF2=Q?T)0Ly1^|L>QuG{imvkd&~CpgV;D7_E>xQt|z{yltCB> zhLR;usXD>Rym>Ws8BHR>3SN!0K@n2j0lhO$8-rWp;YE|rbb*-R=ngF`^3;3^^OeQ} zuOztj8J3y<_$q0Yk#UQR2t;#>Z+?l+83f0NeMJi+OvYREk&D3CFyTHlJ`@4t{&9?g z{iFP7)ZoCCj6G=<9zf95UGMBJSq0ZZXI#|p0bSRk1qY1miv7#~briJIdtj$FS;IIm z3_CkB{N<?;B3$KHF@NjY1;&rwM3eS*WzWKZG<9cC`WVh>T8#J{dcB01Y`*%;N+D1Y zV2BJn2>h6j;y}@iTF3Ao>IdBr5z*V&W2*792eGb9ULEZS%AY=Q872XWc_9NCNkB38 zS4sx%WPv{>^q9Kl2Ly0#CEy9Fy>3P?!n`#`8)KIB>sq}+vF04SQz2xL7PpjP#n(pV z>N}qzXei&%`_(H>Z=9f88B{<`L&RE>mH38==M4YBTW;pnaT93|R1agOpw&a?F&E{* z{R7JeGBnLfvwAZj#$A2tGIG4o;TzK%X0sLnK4SmXt9mg^V6Z@wuW3g$sp)RJ0TC-S zXpeV{0~&_%IHp{<yrocF1dE?woqIcNg;(2^HJ{v)@6$4VBlu^zokW#$f!ILB_<Che znQ2vuTLwuHktT8T>5W;I1bAwUwGzsdj&BGH@HS7UyhTDJ$_flf^xHQ-;(%2YgF)~O zz&1oas|k=+>aubMUgN@0`H63;|MwMAfm+mCm;t}f`=}}FN2<R4xbuO&!t+&~#2{$h z<>ZBV7>AnhfWLa2Qf0f&;H;8!I(9uwwHj3v$+T7Odcv-uhL29h6wtE?4w`snS?{5T z2k$3|soj=F3AR~zKIq^9aJR`21x2kzFyk&Tg{ImBHcmLY?TOvO7g7o7j#s~u^keLM z_zcqu4%oTntNvRqIhi{`9}-4o_L3j7;oH+tFX#oU^~W^5^e<>+Cf33_*=_X<P`}a` z>pfo)ukY+{oFubf#NmSy#Dx9pwcp^J9l!(1vV-{W?)te0A4J~PrA0%G#`-b_^v?M7 zP`D}4lG8su@_L19WNs^^0zCgttjl@%(Ia*ueLq)%EN8Ci69;1AK;s0Z-61)w4HZbw zXnKBTJ$|;i@ed+Dx~Zu!YC2x@YtJ}ETw7*{xUjl`t7jww$56_*O`HPz4l05ZNgV<# z+Ld0oeEmA1@=74$y{8tw2dRW?L>y-kj=7U|S(8ON0Eq%6iJbxm*|bqgAX%jq6Qg=^ z*y^+Q8$YJkPR#+!rGNc5?+SHqxWis}JXn7f(70t)?J1jui|DL}Yrp*==np-B4mfA~ zR-bJ?B$~Z<X+yp`dW0sFQ@w;*c<{m8t3gCgSV_%Y2bRD`wZ+^CTQI}38-Xnm^l_LP z$SxYD9o*3|UlV3^tz(%9-i-^ac+%hNO^c2Qg6bstcf`Gc6O-GyAR2}ZZC#x1Sxr0B zyP?J$iV<u!L?29c(M?@-eskv#bH{u^z9YKAA=rpzt9Q#+m!qqAmq|T`gNmxca0FgE zD9|xsh3y0TRcQh;C^UJhEQ6;x|D|F>g2`w^y_~3i->#bUa@CzxVjY3z@yet*7YxFg zZ))`ji3vutCeVP1Y=;Q2wKK|srgT0PUPGA4++3&Eqpm$gW#sz|)^T#fYo9j<OI4PD zPj!-#*><T#hKW(42Y|7?Lu!X_JT~~dTyM1Db%UmN^B`Yqn``9GW`(b9C4o>c!zuQz zTC#O!&HmFxw1>eL7Ej~Z5wMIKog}a<&9s2LpA6x!k(!9?#rRKAv3e{jeZnNsp-&$@ z=$KiMHFsH+pHl7<v&ma6gd_m=g>u?|_;HhG!0SmrmTLl@(gb{;)}#VeH&4?N5D*Dc z`lU;JuIa=Y+McN6=oFpUrvM~Ba|Tx$G%wIL$<kJJZWey<qp%rMI?;hqWW!>cXzC8x zPHC$qqmi|Qj<V}^EZjFA6AT@+^YY46^dEIWwEkfGc)~*ihOX4zO_xTMQa2>k>vvm# z|Lc5}l&tAf_Iu&fi2!b*T#v1)h)CB}r;pKF1(*;rX6vCdospsz@1s`9=(WXG-n?%V zGOC8OYOdF&tjvIn+q$H8xRWlD$l~u{H~PnDkdYO98bNoVQ~%<Z*Uf{k0r-m@P67nc zm#q=D$aC1${(nN91Z6Tf1y*1Ju5o-*IgyB~=w#%88sh|Ch_7Qg7;kTQVt1~H#NhX1 z)gA-+T!O+)IP5j<_y|$pc-ks&N&8a@23xC>lD7V9C=e{^zcA)h4_EV|Iy`%lsL5)E zk1bo>2XD&-VW2JSD}ptFlV6J{usK@@E&u9qUEjI>^%ta%$jXxV-I1!hbQF6<EB9y` z9M0A3yD@4zG&2k5UzC`lB1@73WCT)#0wB2tUR!YUX`G|c1r@SoC3ZfA$Yqx7sHTnw zfnsS!9TMs4bu<ANUg|%pL?s%WLKRppI_UN|G~8mkl|={om6Dn9MULPg;jr@8*UemJ zsnJm}JkAT8TmIO0Llxj=Is&1H)w+|mZk4b>?{CGhFsxGqXaUlxNb4#eSpZP9bo?W= z&fuLWfBRZQ&>ZQcBgn~)W?az~5ZR%q0JkrF50m=>SZwP!P@IqnJH?1@o|{X=8CTx# z_lZWX7xi=*t(Ud^tYGfMq9XD>zgsE#bDM+gRh<SpbQXyNDOfwLulpIKS7{vJmFnSJ z6>&~#f3mBnFw^RYI7eHIniP%=g>G(honI{me%AM*&FTw<gLoM5anxTuUe_}&(dvr^ zT}5#Yh!Bv|e7TJd02y&=cB5|Eg#Lq0lAWKcp{0{7Vj4lHNWBoIE~2_Xe<iq3t>|uq z+73Q(oF}4B@DaJ88&yYxw);azC0<?FP`KAk<I^eQT53|UJBP;IUyUWV``Xlu%X?^u ziJj@Wg2JeBbz&T{XrHWE)7cNp#IOcV?G#G#;|O5eGlUP``dMEeg$&=4QfnE^v^*FQ zg%l_#YD6gckF^2>FAW_w*?YOx8sxRBx^1tor6UByg-*@4X<$_r62037t81yTiyJ)R zfvO5|3tEH-1&a+|-pYKqAQ~72unfGFH4w*xx7lv!OTZ89QZ&!?Hp#LTB%%zB_2cH{ z1Q1MmJ#;R32@mta7ji7TZfFXYp{*rK+~XN+h|`qx<@GpJ9}HU0fX;gR1kYYllzqMv zF><Kk4PW=}3h$zRB{iIcCF0<|K1Xgk_a)1iXL4K=(8YEHX)*yL#Q1mWVI=aawWDfi z$!)9X-1rzjA%HCGTX(!xAP_W!6D$gbWB9;=oZ55b6>bNm$${TWjw;NM(R5<#|B%=F zk?f;lk>;^-L=u`pNu4q(V81hDf#4EuuR{PS015CsmXpq)^g`7#?>r%sncUx7B#y;| zSiq1%r64U<detVHzs13onx;KcLQuq6ZLSUTgH}z>#KZ=D<3Vsb;-{aNt7R0?>rgvs z4qDmcAP|K}FA_v@zNEetyvc`ar0^NLD2m!^2+%ZQzfbJ;wVk140m?;3r%#nCf1@SX z%n%2NI}xdy4g=}HvKw!hz@58-Vm#|el{iVq3WHXN##Y29DF}q(nzIMW78!-L5Tu{c zO*0J%Gho42(>)JL;x9DFIFPq1g+;_-UMZQb$+JSAr4U^vUWt03$aq(@O(;Z=KZv!> zN2_LlzqZ47L23lyL+2`?-40|#W23-M>oPWKE=moGwao%@g+^Vj8QR)KvO<lEXJr!W zr-S%d9X;Q*yz#bBOjb3uY^g<0gixyCaI%Nc<J8U7%ylCW!NS0G#+qH+@a2L~kd*{c z!*njUGW0YZO2r-Nk5K>pCHFR)0WSpY%{;1fC#7B$fSds-OJeil-H&`L{IRGpO~PAw zZ<6DBRqpj<68D}wVd&#NvCdtH?`4OS4_3H`D@;gP3k>k*<agtomz`;g)C1cLT6w=y za9^0@ZZ)%cq6f(7Utqa6*Jd17a{@<9{6u;q$W9vNaGGC^fcyji0-mAFx%Hpc5NQ;@ zbS|s6xVj`=%l3ch9v<*?3D}$OhO>4?=>**b&-&UUY~{zlja6actC7th2IqtK3O9Q= z@m}mLX_p{w<tK0UWc6ZL)v{B9^R&+!`gAAQi$6rcy>@UIV~oGB!h(lASDq}np6n~9 zi2$ovM!gNSjE;cMTHvAvnNS3YXZ`b+|NenytZ0fC>;ns15p{?Il=8Pr-LhCZJt3e) ztH_{(2^tBZHw!kAPqJw<Pajg-7)+R9?IqG>*Dod>JfZw}KpRtr8{~p>09$5!TqbWT z<qY4Sd9P|+oW081?;$xKq5pfCWj^b44!aAe0V1%G6m(YDU?R_F+x05MT32X^5_lqY z$fFy?aLiFw>KH^qL@HAXu%0@3+M>@?EqhYuCnvL>r$_BWG~Am%g_@p3a#*^%rb|)X zhdBDb&Ba_nJ}H9WcCBb-T8av;fq+X=ar}!}<iu;BIFAqb-5&|)`%$s&)=tTt#8{?P zt@yW`|GksJJp|QJjr8qV!?4xR*T@m3Dg-PEc~vmUuSK+7M;xK*83Zjl`u3(mW`lgo zjWuWW0%T17BX+da@cVC2J&d1&p?IDTSN~v17M4QmiV}S{E8CwaSe^H~Dx`V#rHAZD zl&m|2l<t2#*?*t2L9(8556A>8a8=z~A~X;u#5(@O$zOFleR-KE8<nDpbi;R8^YACX zyw-4U@K^naPlsIo+r^nwPO<IQu36n9WW||hem*GD0Pr{V9@RkI&YMI{G}P%yYDF@< zAS<!O_FJT2yq=ySV*SqV36ix;BL<|S3iVHFW^L&uZm+%I2fuL+!AvrFj^t?oJ7QKU z(*jyd-N(#6j?<<@vNO-~k(PVbe_=3f56FnLxbuX|WxcmR-6#Lsp=cg{dHW^zf8_SG zrU%;Ki1ev`zg=}$TqlIXOOXA=NZ%i3E0K}pUKuxne+VhKs0AB3V*2~>@*h}zeUl0o zH?zvjxcKnE4ZS3LUx+2_ahl|<-2TG|-I2s|;B?L>O*OdACDjFQ>s_x+t}#p;AWo#t zVVRVTXn3qU;$6N&KnPv6@kvfCicK{Fp2_*YdDzdXT(;!;%MDK<^yJyF&=*FF{48Ns z^|hcQM-6?)#0(=_^R6G5P^PK7Tz^c)DPyD|)FDh3v@&{CqViZ%P(W|o3-4r!AZOxh zeeUdBQ}V)3%Sz<Zjo9|`3C|JT?|Srnbw#{kl3><wym#u=EGH4YklwcsUYVPwyq0PX znIK}pO=<BN0g_8gE0j#%e%)>E+N_mxGSL?;-Rd{yXv^(eL<!jfn7iUO*<1z?`KxPw z9e<&uS#@Y>G4aJJd49R-g%$s$1^wY41yuZ1VY%>8E6$8&v;Vz+3WUN=&V0c3AKy&+ z=_{FEaskVJcH%y^0;_#E-iHBvtZped6QT)7ygx6Kh|yGx7=Y*M<`pGpLY}Yj-oCO> zEY!eTropo_&s>9`_Q4MHIfOF^78nA+NI-7C=-<DUdKSNjJvH_(;?2+wxNEO~*fZ1A zvaR^NUZ&zp3u()b4TmmG^x9qY8{|^0_psF@y0$ptrcS#FwNEazfnKrFarZkv*Dt91 z<=Uw&A6?bHq#3gURXdCFLd5uE3tOV5yCx-i3Vz#UBr>{UcEv0M_d!XH_<>>*s%VoE zOXPuQPqLQSw1IJ|C%mPKY{k0NpkA^PdG`^Ch}m;{{+fHy{Z6_5>hau)5B%tgwwFud zMv4$TUg2@)Pw2EmkaanQ4S|u?%MKJs)WyRJiT?Ks-#J}!Ds4bfks&nf-yeEY;j5Vz z=USDVMa*CxclM29#bQ{MXBN-LwcWP#Ub~ZA1Nv3NP7ZQ@l#nXoNRMPN?;I=&{}rag z79N}RY3+DZms;7cS4ux?^#t_HRae9BIXN&!A^#Th!GlZpe-7cUNXb%yum(jw1i_qa zRrl(D*aBA*kHw5zy=T#U!ISx0&u;GJ_ciV=W_Ume6+ITat5NV6)(7vwM_glvqpBTu zxt%^=f`VRy;?HM3Z~H?7+2_l;1+fHP?bz5N{o2+N8){iNmFVImUG{V$Yp!~y%Gx}9 zU)Qo^?-ttRtgItY_sUt0r#>%Rx$!9xaG7eIhE!%HfoJ1-UxJjlXw@{;BB|%^2B*1S zTkIWauQT#BsnDA>!*t{GUk#e#)QHP7q?VUhtidxnk{Xw-dVk<wJx14@YhTY;oN!(c zNEcR6uCEK{rO21}5=l<zt7<@h4E@hlA2ado*xfl*c#^MNlWE}m3jB9ZY}X=lPj9m~ zI510CWoZec*!1yXXFmUE)n7gSk(%Q<NJCC`uMBIXWgl}T6*ou|$PsUO8DRaMCo4_n z*%m7M^PNrcj<9zYihhf06}g_Q)PJ#T-k0j1O7+H{d-|^)hFu-Y8l$f6PH{hP*LRd~ zfvd}fAtCvB^J-x)=|Q9Fp(!U8v8CZ%k4(Tav>Z6Hv~#S~IZM`Z-uQ$_V>V>vGO@y( z*&Cjh7!G>!@Y~Lie=Wq4X7@$;DJK$BO!Z`>JhL+?wbc?EHL5ZDu55If%zsR!;SJY? z4YG?9rE7d~`*?3@*kj+tC3kJuw%rnFef1H)E}45(WTWkR*x^TO3Le78)!x$SIR<+j z3=deI&LW6J<vqv>ITZY;cv9w$ov&hy-#gNu)d{MHqVLW!lYy(=#|$60x;5pO36Q_l zGeu(N=b;^b`zpNoshh(NvMALRY!-zlx$C|u+A+vpgK!@W!B%^RCU&0m+i<rk9Wu=N zc{8Op>#L14oJo#5TlEYGRDKc!2XAkl*;@Bp$0-bO%}OS9KHL6{R33jm_K!dWB0htV zf*-m%Gvk4|*q}P}cYR9<MV_>_;X%D>k@=A_sb>3!$E)g=d^dw_*)ytZ(bBc8Wv13; z%YVrzIb6C-=IQjF<N%xscr#S`ZFEgn`*!c)MpZE^*ydrH|5R|{5AtyhU!je-ykM`* zlNBbThe>hfV;QlKap^xfKbv)~kzJ2}?DD?+;qHJ8&zZiyB2&qguz6e7G(5x1N2_7K za;l<Pbs1BVpC%%?JnY^2_VpaVfX}{HC(;Cr(W#5NTIzZ=b)r5#t5xx4SnSWhlSO+D zcuUiIq`#tXo$-!gQl=+$1JVc=ObsLryK9&LdRFzoc0TE&^}P0p0|xAvG1fF){iok3 zkb3M1LiPj}C-Y-(to`+0bxXUlbEgDaM_#@sb7xG=>{!&5C{KCOJ2*iaulxLRZ+11K z-X%70hBq@ztDi-y$HYM*k>Kd6J8Cv73rA4CFsQv|0l&1K@BRfZUbWW$EwP{na0*HN zF!1&7d45WJK^^c(n7n>|5Cse^vqF3WZr?Yx=?#jj5P?8E!86***DKW%_a*5zWk7}^ zL0C~;u&>Uu#rxc?sV?jK@e@qi!%|20enn$-OHt_h%s&_Dn_N2WL6v=C;Kfxet~G1n zH5)d~@cTGnwr$RhF^g$|Ti-F+*Q005Y9H$!U3L1z=X3pI*KeAzaFsE7_Qfy#^3E7@ zmwrK@R{e9f%zxzc0e#Zz<L;ebDedDi_x%0(k(o1%ln6$knnf%yJ?5ih-q@VMxl}tr zkP3FoyPjw{(b!y<s)4rOFtF{I$5vruR?N_nyZY0+Mq0PD`d6MZV<OJvFD>;f`ulOk zS;&g3j2B3UQiK3e=(W&rTyrH}@0|mfqRa4fcb`4^xLZEi7*u`M?^~NIq#=zK&#ZZ> zuT;I=M_j5iAIiGM=4DS{4qBUMv+UT;s+Rcktq-E?jKN6sIlSy^M0qQTuDO3KbiU+# z@?`$fuT*`~F6DH68T5O-`JDGR<96BOX-_l-rwy8_yp*aptBu<?z3G}`8irkoK|sT@ z6c9{~BTdq6)a-e1Nkai-y+Y6h!G`SvSG`r$C+&$_eS^X#Rw}gJA8)t5eE!(j-&Ctp z{?#jK#m)BL5zX+deMv3?x5K7)J2JvF#%^z4xjybiE`dliT~tYF?;%H|fi-4TlpnvG zwmiFESH-N%(i?S4F6R>ZqQ7eGiZb`=v>ZNLRA*5=z|h_lM|9N9NzQjPO*QFc4wRG; zf+hvK85tm;D=I!dWhj~FNWq@q;%8gNPgWjpf4B@!V9dB*<;mZD;jZdSR69%duMiCC zxh1(Jc1iNiz1&#)hh4D+8gY6zB;t4w8X_Fsz`z)+uIn5@ZGG%i>GX>&fxk~UAw68$ zA0C?b;26?~tI{8n>m47OAFW=~nIgtE%+qDmzakPlL67GDlCUvV84E6d7B(M*2@L_L z+)z=VVIV7CdR(NX+ZyT%8vp9?CGda0TPw=d=u@%ihdv%eQc8<MQPAbI-fGvnCgnm< ztEC-Nm{+YnY+8D5;<m=rQg1e0K9C`Y6_edrL&jB$D>hf*Q*Mr(I<H=O%#4^xwKhm_ z+Mn?A44{Z;sk(a%ip1jTb^NT+6nEr1LiT^7ofaRq*FNA#jQ&TtVTDcbw$&_ykDOvo z?j<eu@y!H6kel3AmQvLRL#>}W{H)nguDX3wjYf9;H0`RE%!l(U-fCU`Db>wBcYdRY zn}Q6o_D1Qknm|?|(eyA;KrKkSA-2?+6+>rBu!_gB#PZS~rVc)uuBo|HJWDhXAODWP zBtL8V)cN;D!Ef(+<IHE70G8R0-Rg%8CLjYP?KnU2rxR)aXIrJ;f>GtYGdlq_<Cbg9 z#6N#)FH%s*^xljre`>|yd$bqVt$5>173rSw$BmN0JIPZ!O@CJAx4nqm_37QZOm;1O zYLeC!PqcDdL`dx$fBDJ0_t})|&O4KX{~tC<Ow`~{b1wuKy3E*VYecug>u>F00V`WO zS^)9}RoCSBbgj!da3+CB!ztq=ho$BGiaUe@bj%oZ38H?>SQ2CGtB$aeuRQ;4nk-N> zp+qs$@Pr6HHyNW%q~bZ(E<fGXa4ICtUU9F$B$wJlVn8B~*Q9S~Ubo<%@Q<zkHFrAB zjE0SO{C@4TRSRvqs)hcd@;IMoVg`zM=1EV*SZb}53`N!9RNYcOJ*(N=a!@(CmSWhw zBZAYnDIs5!rmi6;G0D_VIa-$8+dcfc{5y`6-t~dxUaKDUgVVI|SM%Xds44pkaAY3< zc239hH3n&<+$gd)V{)@0b<*YFo%)A?Ju6a~IZ%?bN@d}E1&B__i(B#STjB>+8l=-t zY$t^n;U;#_G7O9XFe}sS>9McWt<pd4y})!B2xiD?`&bLAL;1+o82Tc#$X6sq6<b>; z{C2QPI=AK?hyj`rjmis9FgOr1N2Cp(kKkI_hI?~RS@<+u;r-T-9{Xxchf=d-Y4uD; zkP*5fWE~romP;$7*+wmILgd<>{IJ43yBtd%dslj#-iO1EF-tk60FkuTFW>WH_Sv_t zD$>Wcq<kHJOwcD46{$EL0Zi?9cGMBG%syar;|iNQDBD3KK2Ix85MVi$N7Zq0t6pse zM`;9dY5z@Bo_=WfV`o?C*p4Nw)_Ya|L{J$2@nYvv^kq2L;4#=HPi0c-f?p1r%GUgL z^7+*S@3!uLN}UdG(agD0h+8@r><VPZ`>+S_x)yYiNV9><!DimV$xs@=2fQuN*p*iI z$mXX!*`+SOwbdSeTAopVkp4=Me>B^ghv~vzU4gL1-8B)uuC>;Yd<;46mh7aXjVpcw zA%p~6Y7i}<QGtXdJ7<*Ki<#F~S%{<<1(qCHRl!{SpUvMa@VgaLe*n%;bjGQ?l7OX{ zV6fhq9p>j!6GSW5nVX@|GwTz2!}4hs?&^L~XzFiw8dtc}o;1_O8SXvYL{!U#U@~OT z*ff#EQNctDdQ~@Y%Z58JAu_%G&kN;f%b?ZeeX%_(Byx0$uCvupgGSB6R5fhLUEX*i zGv&HtY1ixR2?Brj>^{s9dpO>p`tQvvCCsy9z;1=AI^V1P=FTeyq%qHowh+{m$h;fU zw{tkxSNE+s_E(Q@m|6fnX0LXNGHz4-you+p9XuVAI`L|8q0*%psnoX{v}6oIm->@y z_f+fRjYLa_ms0tI!ua{~LTBe(@>S{dsn#VX$3O_v^F(8N(QefS<rEO9(QoaATjr@r zNn2p`hSo(kb^3jN(5h}Zb|z9Z*SiqEQ|USYjC~yB=3!@~-tH+jtE}VWYfU!0s!~(? z%MxITxqs%2Ox1TyPL4$f&1qViSr)Oz>pyZO=<6p9VH5}|cM_a`6xo#Gm%6?8X>C79 z!rlu;ig$JMG%{}mgFQ$8>DS%sHuwmIz}<r?kIoI=ZqPm@Cc07`Rv~ksj=Ufxt8!#F zn{sh)YPnsvR6VR|_V$`C*`J~Ab2a7hlr0boFJg$Jz8@-BZ8u~!-f`tB&+eIVo0{n^ zY7S;)KM~MXb=JVj8P?tzby`Ym#@J?o?$U#2jE95w#N?yBe~o>{xxQ`=={D0l4Jx4_ zW2QK{-`b)$^K(m@y#xh1EI^C&E3G#J7wTRmZyyH-RhJ~CZPja04f6!j-sFiFI<NIx zqE6iUPt$V07S+7f2!#9ODzB70b}MZmSp}h$()8HTA+Q4tB|u7ZJ&=40*ELeV`hS8A zR%AyNS?H7yq*DMTRhD%ZjqGu)@XB@f6Esd(b|);5sE<@RlR!Wr)h}-OK*Nx#hqnWL z^{A!0sc_yes@Vx(ZWfZ!x19nb$kX)$e+L!xMd(@C?_MkXqon1(<=3X$gWWUkor6v% zy)<=-m?WtZT3dgNPxt$J<=Yunh5KdivlO^eY@QR?!JCq;G(SY!rVpDeWXJTLRAcn# z)i_LJ3`9O^Z4y2R0H=S<nguot{^Q5gnGdDbs4l6LN={k&L$|={L=kJB=k`;nV_RzX zIV_5A+X{jp_n(|<zzi|QK^QRWIuU7ENMxFA&UAgdKaJ>uMCr}nFsSpymJ;`%uzq%x zu5~~J?CG?oK7sg(Isl-ryI!DH<2Nu|zKmKAu#=(KQD#>dsp6K}#Xt(oCj<GCRj3Ez z{H~J1P^ENjJGZiPg2gSn`<%_tyVcG3p>s7}iy(KI1^n1dzgtF&H3C=m`;YtV2zK5| z2;neq;9z9g44QzywdttpAwt(_oR?-7FxDf7n^IclxksRdqm2Bs5B#dzx!p^7qpED0 z_@Md5vdaGIgp<v`kM)=K87AL70&;sZY7>*-1e{74w@~gf**cTu0wXkHt5RI&w@mO` zVB4-8dwNcAvBgi{T+PRpc)xss_8Y^$X54!_E#5sPHIbWSH7DR&A4WL75|y8;S_NVZ zc2zU=d@X-JaR{ifsF@zcju)-`%sprEtu~D^yyeh1i0S|NvmRac&a3MY=8ccE{OR{~ zOG51N7HM6u8xQpIVFkuq3Mx>+<K+9Pd5w>w&QD8Kh}2!LKJka+U!NPlR(zB8qRwAB z`%7g$0)>LB_7#GaeD%=Gu8Mn|H**cr*V8ovD@|s*J1Qjr3%w6dkQSpW0iNSo1?_J- zNEgBizkB0+qFd&y*Yxkr?VKp{_8+@?A)K2h_DNTqiJrY@1}q~DV3js;2%Y|WVpcd# z8>T*XOZw-&g+>9hJrQGlLAp=v7&n{$WM2%!T;{0pzmXP&Y4HmrG{!~2v#v{{%gy&b z`tViIla|s`mnaUIN-I*&-GLQ_-xaWGr1qO17k%5$v*zBhFYbzKdsVYtFi6_1WuDu* znoogr$YYX3y&1`WIoh;t2PXA{_MPXVceTwg_^yJ^cK5&U-bXvJ`%#5x&v;v3ZCgiY zY+l#wz5>5Jce$8Asx998MnR~7K8<b+LHslz2aXLqKAoxM@iC172OC$8b&t{yxS%vn z>i+mED7U))MN9hO=d2;yO&$Mjtz<#;^IY&OSC{)`iV@$&QvsP)S%zp6wV+1%lIRgi zU6Vz3c}c-Q>tgQZCl*vuPM7<c`0*>xdtX~|M{E9bZn?JmJ+VIzDL6+%&hqmtqLKlL zN+CjkjgO^oYWQ>Mw~(K`gDcI5%B=68)^y|QCp)UOPgTXFInIO)a?nhPS>CDdWVn|0 z_SLwKld+UU1aB>aSQcUs-(E5P@iDg64}MV^<GMTcDll}nAIvB@47NLKN`ZguEnSj! zH?3eaeQD?fh7<-VGeqMr_-tMpoqoZ7>8t*h?s3+?V{htJzBsB}E0-2iLrxO`jj!^& zDS7(TaChNrseCc|vE@#gfRF!u89oum+9$}VHSEp#0+8UP$%4VjJ0{IcEa{l5N^~9X z;LQ^~=Z%wtM7}mSg!(`qTe=@*|H(C8pmWhw&rk|CmE^Q&Q6#u>S&<XOASo*Rhhas; z%rW$-UX6XQOC3dj^X+)^($FD~JlCJVnoLmKEh>;X({)wU)%c~-^v!biRosq^7Wv=Y zQDLN0-VKZsr8j=z<6)dc21AbKXR;I-z+m_%tM<+eQQHx97emDBGt;%>(fB|}#AS61 zmeGF1K`5F@-oOPJO?imD;RZ#qCqo|T0}w-MlWu~V1c#|rm<{f^$~%_gjPNyc<-}}+ zB%%S?{bmn!2W+C%w5Qia(%X-~BIt$M1hWjT$9=&~qG=kJ);Xl7Q6dopg(_6pwx~dk zRCWdMSC9_6`$nYwCV|d*b(bj4{04apc?n3mv=JENyGe<s3l_DMEzFl_H{+gB-Ms$@ zvx7k7?bSP=<YZvv1QY9a<1VQEaSV2r{!p2<H;6um(6AC_rj8>AfL9gHhEQ;hH@UoA z-Ro1T1*puabde<#_YHjoJM{h|BE87tz7>0F+GW`_YDj|3^egsnp^EK!z7DBwo+wGj z#5b7N-a}vX#Xys5kLu!6$voDpE-&;^nwn~Mo^l~O153lX(RZwTB*$WdCd|`g-kQ$u z{~u9eB8^{Q&9qApfoxK>Cz2T=qON2{#O&ceq>3I2M8(j9eTKwWAxM}oE@)xZ36Bb2 zPb%F_BofVpLP0Rf399}Ql48>X<ac4QrNyzbrB##C5SNuTD+`BEM@E8{ieUQq9_fC; zqIrojZk;BGCVG1{Ei*zUngi(ASpo`)IisjA_|-7|DjvqWqJ-EYfH*{5B7o)jQA18f zFBNn*af?RCy^kO4CFT~4Capr{M8rl&auK{P@8WzTs%57;PgQU1{=Rku6P38nR{&(K zO`5t{e(S1=%lGr>a42^yrjbPCsfnVzd%lZ18#ueKk8`05z%m}u7soF<pUZg^FGBcW zzerJN?JGKj3ebP{?2e{Of@qO}at(*Omeo2_Kv#XYBzjv|BjN#Mr_e2ejvM=`uF+19 zlSLa;?Q)XJnYu@HqO?uFjClP{Wl^dv``tC2f${DGtR0tjywZA0K-t5zqGNUHFbH8B z7Dv#IvR9brb32fsA-11*Dd3*k5-KGEBtw%M&kKs=Ko+m{a#=6j{7e{zG>k-NT&|<@ z(Ex!fTg_yX$qz&oG(ECx*1BpF92K8nKy1#Wr>(TTusrU=+s_dfFerq%5AtnyFah+e zE_@yvw2v`G<d|e5cV>96pm8s25-dyQeLyT?-)0}Q3Isc}G(b8IZzBl1VXE5t!^!tY zg&_edY)SX|^ylwT;u`&TcZhEGyRoC-3zE!NChp^8?n__Y*7PRdRm%6SFfi>xkZq9# zCkquaqne@iw}4tLL53U{C`7Yg_S0~Ia!^r*64@L`ndEJ@&DU#z7%>}LIz}YhKO1Az zucn?!wAO`pA|4#iR3czjJfA#k3@(Rq0V);o8MYD^yd&mIypqH`w#<@RBAY0J(2ZgX zk#|RnWl><Pupf+_<+le0PhVFf`oMfN@|83FiH@mcHw;<L!MCQXK^)j79#BjLlW%l> z5kz3cTk^NmaCDVoRtvwtS)r%KS^qWzTris~55FZg5n~F0XV=4c-U-WE0Q|5Uk3*P8 zY$u9wdxo7sgj=||(($QO%?iV`uFgq5iiBBY^&^KE`c$B3Xa9PgoZUcYP4EK(vSZsT zSQRS7Gn`y4?r}^w)Dy8o04?`xpF_OK(py|PVdy*S;iiZ*md6rw$btT(QD|a$=S32V zu!>fa^y*!Y6leON!aTMOg8ATUj8U}#)4lZ@Jc>ix4gV&}NF)?+Tr9}x=xJC|rN{~F zau>k^rSYZ)9L+ZXcW>ZAl=Cn(csi+Mmat5F5%z3b_T(8h3i2I=(Ky&|92V43bgWwl zZiRD;itfX#Pjo@B-?-TgrfiwuB~~Xd5TqZv_UJq@E((7G!E>T^cM)_&VU@w&38kxD zS*q^!^yp2sb7_G3W+AVH@#iB6T9$0>qrjb^>JFI#^UjbE7So6g$E*A})4N>Opwx#5 zAQseVJVSwao}Y|#h@YQnq_R!R1y;>-oCii^p+onnMzEl8igO3ghpC4<Sc-^-%u$Zb zC3Hh@_iPq_`7>?^BBT~ku-z|=yKA7#)Gj_+H&~H<P}Jg->$%uz_PlvLdqWfT`G+W( z6DLu;D=33gBEV&Isw{QPw(Krc*zd3`a8m#3VY+>p)njYxb4|qtZFTNreiLglyA%RB zLC%2CV&cBPdMKL3OTy<qgGflC8~U)7mbuQ2>R#~Pk28S)+maU3W2TX=P>7_^4<>yt zlse$rlU~cJc9W5cV=J7Snn(p=&cpFf3?u#!JUc=WkvYJ&l59Kt(|}}Rn;<R+k9%;o zQg*^Ot$IC@n_=22i?B&sSAT1a%k*N<V9!A=tQ)VNp4s`dMeZ-{66d=8;(n2b3v<t` z0TO9b!w?L&_^aBTKeRnrJK1f4jiWy&+LbKcxLry!AB+Pt5U!e_S&0TB(Tm`vT6#lJ zte`RliOLAZcKI{m40Jxkff2TruUqO(MO$4Ewc3pfIrD;kBy5|RK0IH~U`k}kV&Z{L z%(JXH$lzB9I$l3#a~9v~Tnf7x8&EMG?Q|bgB+?Eug)IJ4!4(FPgSr{U2VN1;n7(X< z(4eP5Rv3IsZN-r7G>iA5NT5rLZ61`_#U6#l1kwoy0}(yVsGX4OSl$#d>5-+~GP+EM z1}QXfa1}QFkBA-xFvCSJJpPk(UfP$3uB8vd5j}vnuQZP;+l<YDqbLnTh!K7MGmasT zJTa&0Vmiu8Ie(jk9kO`)J)}{RAO)I=_flnnL66*#tEd2LDRopdmmmM9=s4sC5%jo= zSoj)}NUi~wdN!imc3rlQDh;ZB7&gy(rB#KqTJ*|rCq-*KBRr+}w~x~DNzUoC1tc<5 zTh1FZ2a$<VHtlM^+YAP`29F=y+;ckbTc4YjhD@9OCFt11GXyup2zzCMFPJZJX;_b7 zli=@gHt9Xz`nYM4Q2kZvN8`mS@EVgY;YWNujhm##S>}*X!c7c*PC$~1FoWSB-u$dD z3aBWXXcj!j7ZOL*@6hxLj7}7*$I6v>3y}RGA~pL=4U$F6b+UMaM0bK!s47e(G<_uq zJwg!#3&t}Ok>^0qkCPhHnsNn_V9Vt{?Rw~&Tz?|wxA{L+`^Bs;f{x-KMP6}-Aws5x zFmV}=(-(`GljAoMWZ6OtpU6$%KhEWI`c$tuXVCaVb+;jlxNlXq(A>lPgt8o)vIshH z9yXNiRE0Ajlv`XFukHjnzb9u&3NeU6VyEBDk`5gs0DP3gZO|4WKC+!0%hCuk1QHG| z+Gv(DYY;MXT)B;!-YiuL?RDbfN6mokPl3eiRnI~QUoUh-#E`sI-3JsIN-^SIRF*2n zd29QzfYb-PGoKdvy9j+^NCivG<cuGzk&}W7IZLS2(+H@0WiN<F=$m)(PTCIL-k6%C z=KKo!F4GDb%md6tpv!z=BFaa%>0kzm6DF#?1g~5BD9=@OehwW)XaR)m^f5``21EiR z1J!ZE@XbW$=tIOoazvcG?IJf(C;EGTHJ~&gC_1Fgz{9k|xsLH1DTisy587#A`2}#F zroFq1Rp$WP$&{Kad$Qs%eyNuUj%mZN;_pSL5_=)3(({>3CDPG$Qv+&)CYr*129sG5 z-ljcw>3!^#iQ0ka;E0n{q$g8JPt5RvNqlTg4>WGhZsA`&ejNt;SfnIKc#?LcE$ZI` zs=X&ZLy-GLBLW}^!7|DmJfqAqyG9i6xe=l<-7_H4378LAAX@TK+ur>38%<znjs32$ zA+%JG!B&#W5#Et$a=@B$<g!J~-0H;GW={(bNW4ju4Lp5L$XE{4M4wq^t%15DYJ-gB zv1%Q)mx)2x>rEzm`F@->35|+4&e}DUCB$lZZqe{96fpyKP<<gW4qhQbCPCw}5v9@t zPj}(Lp>{GdG4r9e0w0YwOEgFZtv<8nkee|aftm?SxkyWIVeM)DV9jTg(8KONk}kEw z1D~|3Mt_dKt<7DJ{c`*0Jv`IK==|x=u@b0MHw+<SZ>vCM8%EVS6fJ1Bt!AXCH<SRK z?IOq_nyIg?;Jz{Lz}?0cxQoI{6<c^eg-A1&a|7j{S38~-q*2mU-@G6Uh0T;*H}eJN zL22oDzB5D6NaKi{IglfVP4e6_0?6<v$UVfOi<1`D>TR|f@)xvzFYVn-%MKPGN}eol z5i>6!iaTxY<gwYT49#7HNTX35Dv}F+gAHt-xB0fE1Pv6VRFy^IZt9%NPktbBKVj*$ ziWYh?QpJmKi1H@iKAdYxngoDCXw;rO{bBJB@R|Rv1f5~|k^GA`oya2%;JYwiQ-?ZY zKg}+RGWcPrePm&z05!lb56&d%{JFQ8UY)lo0xb}nN|j}3&lfqkz;_Hf)Dacr($6Gd zV<D#*vOXwXGvpD!5LJ+OZaHumh#$t0ut+%B%RnIjFGG3?N`*54!#ONe6w(Dxo12*S zK%+|h+Yjd_G9^Mzf_aO-C|%iuU9(q1<D@c4bXvB}*Dn40eY=1wY$kGk-T&9o*@LtZ zhhaQJhHh%(C}e0_Q9&V@3TLh$G=30NaI9M(m14!VDus~CB$*OYKeHG=K&=6ZL_({9 zEG?lW<%)>5qGV{7Dz>ylj%X75dvD8d1nz(T_w#w)=bg3eubF8t2I#KZx<F^&JV5N- zkCQ3dv5M13SdJXb^xFUUCM08}uQiqV1y-2Je!~iSRc^1452rlRN&0HN>#@hM0Z=5u zo6xV7pz!vNam$0G%x8HzKnM;fgcMPE)^m@nL7!>VOL($1%GkINBri59r4?Y34geMo zd<e|+S3{P-5~_0v&PTeq{R&BxTZ=(fOO27`t5TW`3N7{tMlB4)&>e|%IiYS#;zqBN zRy33c@%l{-Pz?AX(eU)GdYmV+#qDUP>44LjS&OKd3)My|`}<+(pduXnBP8<ma*#!p z)H;j@XIHybeWCZ`OB<~qtU~WT_tt#lhxM{kC@OhVXDb01733FzIc25L$s41a<caiY z<)_e^4pgVgppEWKemlt{Wl0$&+$!o|6#F2+bdY|U9Z|iSUfyA?4u55Ui5YXFh|iI+ zptZhBOk}36F#+869@?)T38a`~jLxAP=VD|4<P+BiRKYDzPUf;$F|W-hb8OLSy^^Z~ z{sYkSdB!{4(~K-0-tza)9_7p5!};M<bdd{?89!1#Z2tInspO2xr?%&u>jBo`lDKBJ z`wDQDQ||l3h>=><G-lS8wePj0?-dXQ;l9aZ^ah?Wa#PX(Ur|+fr@M?qWz3i;2Ar(* VV76DI5zKWoA<pXF!?1e${XgE_NA>^! literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/0kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/0kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..f5989dd57c271bc84d654c2172add0d80a20a341 GIT binary patch literal 115298 zcmbUJ2|SeR`v;CcBC<r1WUr7)D0|3AN0O5zAz7x)o+jDXM<k^z5lU&uo~?ysoyeMG zH(4^)><n4PEYJLI=X}2BjK1I3=l}oxoLA0sKQqsLU)OzI*ZbP;2mL#J2-<P>wEk&` ziHQli4E}@Y{m?0B3m7snZT#M{@x#Kr@p~%^3o{GrR#w)({;{!dV`XD!V`bgOxs9D; z;|E-EadL2N3^peD`_V01nVGk8u(7iJ^_Bluzv!PJ-fdgVnYo#n_Cs5EnV5N*=(UhI z1Tk&>i##UiKR--cm|3>6vH>zU!54~m0P>lc0nu9l#o*h4;B$zDck9l5$4;{HnOtGp z@3u?f&g0Z=5;||I`Omi#B^9sU4q@lmEwD#WNa}#}!9$0YlvPyKj;o*gL-(}a8U3@S z7tG8pE?Qo?cHPe2!O_Xt-NVz%+sD^0^lsR_@cR!UV&k5~CnP?7mh>tuJtH$KJLmPg z_eI4YN<NmB)qJk4t8Zv*`qI(a)!l>t-rF}kGCDT?b7FF8dU5I3^2+KOX`Q^m7Zb$% zH(TKM-;Djn7cbyz%Z3ctHuz%N;tl>W^RjH+cZ_xCNfWj!ZhZR{?rhto^EmZwHM@l3 zc_RPS+wB~?C6$Jy7B^V?i?jd#7z_FT#MwWL{mWM$#Kp`6gvZPap&%-AIUR~Fg=f-W z^{8})>tK#KC7yL=D;U4e+Quu1jd~{^HxrY>`NTvQx*a4>hhmyxymDSy*CI^4XN8pJ z+qE&-NZ+ADqu*fiG%DWRv%^Om(VU<|1!?QXtmC^(wD$z5fwc@^@+6_rLe)k(3N_k6 zK+05?_*>eTE>&@ZIU8v2FjJOhxkC%<TyXyZ<Ox%EyY4O~qgwH$t)*ZpxXVJoChI<G zjMJSCS<|8H0=Zz0ga!n41$>xGoj&~U^(1rotB8Y80mmq!B}s<@=#ct?OUOq+!2=Wl z^(|OXcb74nODY{|6zfMmMwFN-q1KuEVLY$-BvfEfM~9Y#Ve(Jhm$JUG3N#(sR{~aW zp=L8HL>x@vPOKJR995-xAt4`T`2M|~g!1G?=ukst31yBNcC$wy3LYKor>!D7!N<QG zd=;!*AqZyLAl+&`VmddT=s*o?rMY2#%Dhh5lH>Cb(e_5o^ZYzKcYaZT8axjVh<`O^ z+aQ#s4@14{N{433;A1x3x5^kt&@Ld7TZ(W#W-U@BS(V&FhkQC6p@M#0u%Wsov|H$L z>vLXx^3)Jn+)M}^It&$Wur4t|Sm)M9M&QZ)?_CV)a7!X_v|2jUrfUxbi3)+ogym`8 zDDt*~t7R|?*d-M-c^+Qo)fQF)%UveT(9B9Gtu&eBf`<+0>3rNEJY_ux@fQx^);UqM zTd1$*x-KMnM5h%n%kyg&Q`d$ZPt_8Zwg3@$!pr-tJ-xIJ01EjVD7kbfm18s;%2_U4 z=Kva415fItFb;w>lECh942dsb^SxI-0r_2m&VoA{ffC3`6~f9qw$UspKOJs7(2rDh zu5-NC-g;Y1228$8_+x`5&y_}>LgZ9uARiq%xr-@zgMX7D?D|%HI)r8e_bz?U`-{oL zMr0C-%+XT^@!uIOEOl9dX$d7W%nj(<_-Q&sk%ip50QWb1q!FEWFdk@RTS8gHI2BC0 z&k{8=K!+v`Y;+-h>`3%FG_bMSsY`8nbZ8gc$T~WSB@4B&iG#JbMv5akJ-C%6EO|%4 z$j3m&QLtKWq>O3oh`vOpgPnuaMV(sSmz9UG-^nGkE%WfgXE@9&0lPRQKyycrpEqXX zp+)DyZE_O`Rh496l5X33$tkAa##VRN{b0@8XZW9xcleoyUFjn+*S}QhSzrqbQ1uMh zAGa3C;%i2J`GhHlmYV^XFziR@P$8*((+Dq>?|7*-T$!z-cuv9J;Av~?_FB7(L9DNh zSyyvYXKbZ<qNx%|x;?2+>$U2b4PJOsQhHqR;Q=S@G^}hLEgqi<-!78yEl(>YVr}7j zzh&FrwwucjBJ^O%dR=>wifh?yeYrtx<h5{59KUv%<l;HW9Z$-V_+qRyxuQO%@US8c z-MC2sU@JkwR2lc0yfV9@x6?OdpS|F>{8n>X{ZY@j`(JqS5jFD+@n9<5MEh@?@aRGw zFAvMSwyH_G#+jfeRm<jU5=EN22s3P}Gf5oLl0yxkf4ZclaEnvK&FN5zO)HIrA?EXJ zx3Zq<OYHOH^bSECiB_;XSi0O)@ai2Ez|LM%I%H!(Zrj>AXCse<coEiUaD6nx^+&&h z%x`++Z_F>3&gILEB<TGq>2^l&>BJjRmqbP;52FDBHaZh%K#N@7|3*TNtWu?+M)p{o zVY1ovt<O>~L#?KDUh$#?s-FR{u;=SSP&CB?T&5(KfC<oxX`4m`ViC|hs@MZZX77gy zD|AR`EVIK?@7WKf{t(Wc+rml($!2F40Kkk6qSn}!Qn+Op`A=gU6pTbbsTn}grrNA* zY(I-U*ux_d8)m0<m#@xflML`ug&X`#Amu_i+M*4s1&P4WG%yqdH)_3hf9_`Sc9Vh| zvgt4PN3g`C+DUTzikRzqR_z2<D+w=@{7T_=VO;iq(NIf#f8d#u<fZ2iy_^(skAFYY zV7%Rl4mnT3%X}Z`5N-xh4jYXoA)yEW9Mg+Wm<C|R&*DekDWAD=?&!nVM|E|jgp$42 z)TXS*F+RdH*H%g{&5>F9zpnmMQ_<Be%lW{l$(^~;rTf36&p&(-rQiZ@+V$7A3V<6` z+6VNQ%aauD(aj(Bb&qHKj6ac|JaGQY^cKBccb=7sLSy)S78R-hPMYDh=p`j4o>i@U zI;35Wr4R|jdW-{`x?N257pIb*sJ>}YNmhS#Ht%cO8;H3{n!kI~E-1~NLNuj;^Wp)@ zku>bc{1NHy04gR8qz&V#j+;g<;je;a_0y;GB^0I-S$3=K-%W=&Fq@VwLQN;q+6{lx z&w{K!tKJrOrj(Rc-aEci$|6c%+fHrrq^1z=q8FN*iWzmiv}(jbvY%hypIp(jFM8bc z<ugr(zF_4|O1Wt;rW`12-X=fRQCz9+V)ZmiGQ{W0J8bIfE~d&HN1=rWo+TJ=#}dEb zgCAAQ=j3idC=a2Qk3^)>Nzuw?GSTfX`1!g`Ybb&&yn4K+Xj_GpTUxoK_fLoThqr9^ zElhI5>W#D%PXdoim4d#KVA|8qHzi76O2j)f&8rVxwhz`+WYmEC1x`&ryN921&U~2f zNVt&vVdv4~)pJ&6Ur7W+=O`V*^U$8Qv92*{xgO)d`ou1#cHo2#JpNSXK-NF)IzpJ} ze*u)Ptw)}5e=i|hDQl=dkm9zsP2g^xcu#hs)06dM*A;)CueyK471Vvx6Ff1KnTG{2 zMWYCe_e4$y%QNb@65~MmbGx>vSE;v?e|n3Ho#(EOkHQiW+FuDrHJO@5O0lznR>&Q1 z)Y>qvCX3iW4R=L=+NC7TIx>fE!YEhNpIs@q5Z~qX_MLVP-uHu3cIZosaLm5mZh)LD z5nq|7LuB?8mQ70azg0|w5g$ugJCv{1Mk<UJQi&Mi>uy5UfcRNx1od_WL*5EpD&Zc` z!Of%jgDD*9p0vmh*sYay%f}jHUYBX6@bA67O*+(c6Vr_@=p}(N;M>9x`&?r-x6J@` zd_-8IoOa17SJ?8vgOIt{T}QGwn5soQ^Ip$t$^vBHgBn7Uc~iL2jEeBTfT*5W@pvl9 zzj{M6I(M^cut;9!8d@Df%+fZk*25M_hsLA@X#UYO_FSRhO?&W8^CEXPK&@Wvl$K>6 z9dcM-o!IkDF)Dniz^{yF3mt04Q<>?IeF_)MAgO4E>+*<$%t^!wzNxa%0cYdl3j3X@ z6E?vBll+PB;UAmi;T#?bkL|#&5OHKq3)$bG*-UvR*NS$)#X$J!&-j|Th(pYZSMI1W z$9+0bdbo{PNDWURqmbY(rvJVtqeVYdO-j04=cV5~lhBV(9^Ahr_@rd48h_VjY;wje zac+pm3AM~;eFF0SH?+Cng<YKaPn5%iJ{7=}cq(rAN15YK)UoSVeE15V6O@0oxZ{Wk zq}-aaxq+9$_=O_|O~0O7_NoTDX^U$kT?F<OoY>TdBtn={ZE5+t0qMwXJ1c@dlip6D z6$UMBo$&Gwu#2QZ{jJ3>VU|W8m2<8vayIzcXM5&~?{?<>p?K4`s-yPpTGPa0p&dzn zv{GZV;5{AMR#L~q;?x(`wc}Y@H_JYex!LdaFmtpsR7-nNRH?IF_`>40;ut+l*12~& z;VdO0et7lqXU(eTeGBvRZ`_!5HUILhLoHRe@9pW}gJMtlf1(606Y-y$?+56mlVpsN zmR5CyTw*LGE-OA3bHn;UOElE*+QXG|+?bt~lO4)0m=(^}%8R9l84X(tfc$Bmhx`*x z_OmZsj2_`Gz9#p~GykyF+44)<WZPK@C-20dgnpq!m{+qw;+5dA-o`4r>oQsBXyA6} zCPTDS;Qndo;loGKLw|)nTNtC7o(wxu1>dU|JnPQ5p5Wu^2dkHrzzk6NFkyYW74WjO z?OvYoubhPV!yhd>7AEMHysSTzSuHKs9{24yv)Ysmk*Fk~f>%%OYPYQBSU|s@f9^Nz zRwC)y>IaR#*1(aL6OmHYCFL$#606#&;;1}(Uaf{7H!WlzcgD?_P7}88I4N6U;mVgE zs$!`ic`NKG*NdnVk&sUYKi(PUS$=wRh0h`9%ZCK+S9-Aog{71s=)2}iQnoTC+-*uF z&fvg1TgUD}wVr;ac(*1=qM_gAHnw9nb2zGh0|E@R8nD6;^ssHDD0MC%^Ap<0HS1rS zwFHRIJ%5QB&w1^mbuXA>CO`_H!WjTbm<j6yp45W!8turPn$e?}32mVZATe;a1sfeb ziJFOCQGQ?*q{>1#1v26za8BNz;-|E?{u5oeu(7rEtlhb@b6^bSphK6S$?R7V(3izT z>K)wNJ31s`o#7dDjAe3wXZ;4Q5q~Ij(h<rX6b8Y>IF8b=E|eBJ>AZHY8tE??C2d3r zy(WNiZjj50fs_Le5}LMiw~BudKqh*Z4y}M(7FgE-p45~r5kU5P04o}kaJM|=Rr0xq zwDWYR>`)hE(T-!5Y8xZDT`!Z-TbdU*dF-)DPypp;)$IZ=)E-hvO<Bt@5r4n%MnKbZ zpW=_#x3>leL2HG5xx)u4NAJsO8Vt)Gk}J5;9y_mg|CgouBc724P0zxl`Fy#&EElV0 z?}!U(K4a%OusYjaoM2u}-!x~3i=6?M*?PBIO2;V%q7wsrp(K0}b=P9%<HZHDxRa!3 zLpCa_t6zB4ogZvF9dLBdW%U&@a17NnY*EYU&Ke>7{kpu@F;fcZH;seq`bGSRGS816 z(Vs~o4{{n<xp=-W`4FWRf9vgjD8=t;#rshqANS$nWud|Fp?r0#=GCj6138|Ni6VKv zeLTloAm8M|&kF*BK7N>8)vuaX53<^t?{%AI8jE(b{tLGycxbl(JV*N3mn?>ku;Q|s zGte`at^O>x-R25R&5+fNgnvdF;LH9?;HcGW+IxyjfY^Y&FyV&KIQM0v8Jq3ygRCqk zzUf`x@a{~OT8coRKw%1IsF5z_Mvs7d;6}{=IF!&9$^RciMKgM17Y&^brR^FGWY7GO zvVQ%{Q;OGPxeA@dV~=xI{E7-GPaC>u_r9zf;}G?2PmrC}txk;TI8#xAh`6FAFxv4= zPP(9g@`;mE?OpeuHOHw52ey>DPG>PoOZ;R_$0Ne0k6`xSn|tM0)DZX6_>a6d;c<e; zMg6XUyiDL#*&O<l(24xPe5uSFh3``(`MlmGKaMfKVfygWf01^$s+72>q+yVdcu~O! zioa`cQ|F03zrw|r>;v4#zW)q9p0v<8&y#TrXkqy>C3H%gb0Zn&&4(LpXOJrK^`w0B z;uOO|PhdClJk%C5uz`@pm0`>}R85C~BW#OwBY{VGIN?SP9+CiZ*O6Igqat&y9@s74 zL!`0+x!WCSrKQ3$?RFV%2C;uz(%Uxx@%Y<(1Q1)?kT^xz9n1i{YKT_%V_GXMDOjBY z)Djdlf#vT7_EH!Ip1D-&JRJbi35FXtHcZ&j#{xOk7AOv4a_83SW#zPC<I|O_dJf<b zp<s0~m`7%MlTY(jFQkUd!!tkrGC~z#gzR!4&6-DpD%iKQ9ER(ZE#)>4cGl%4JRVbU zxcnS5qTNGSX*6a{eu>R-KGK}kd+xYN!j5_?W+D*XZi!)ytSC(fPucg)f(GXlj%xPa znf}W2gC8Ek)DpJ(piY){7O%JD{j?b|VaFWx3rP88ty(L;3%kdsVCIs(q+{|T6tk4A z&gGTDa}5tW$}{N>H_aEJc36E#ze0y}-#pzhw{O@&bUk0xWoYe_{9S~-vq}=d2kq^u zIF&p7NuM<-ap$&C$(y|*ZtsXpW3gKUqDTB6xN81UVyq&zH!8d>N;lB#3Plh3f-b^- zZjq_R6<xA%63TqOGu``jVacsMM`HKhV2(P)Wy~5#2u2NI3BpwQY#Ztce1COPa(wAy zxJWKtS8eJ^{L`bYYlbe3umc>5>?IYB9<SIw?4O-(R;uMmYJKupp4BLIRs;WT5UEBp zR~>Xz70Q~OSuBvDWE;QhYjGF(Vq|yq<Mq}Ye&D@XR)`-`hfv$8+DO|wUYAQZT3Fsb z{v{!KeRL`bYVXn7iPWK4$I;vYrx!&Bb6&r`b34~f&X^9Bb8n%sA9zo7pd1R2A%zY- zj21^)29Nj`zTf9mG-WUUf-7E->G9j%_etv$wL+1rg$1_GeotDYYS-j`X}pN7eett0 zYn2&a>@WZDm!tW+<3*L713z@Ji83Mi(e=T{aCX?<nNQ-Po-_+xQXD4m{kglEE-vol z{8!H$ADYPUSi^0_4JDC1$I1d1YWuT)hUmoB_oa<r6yZg3dqB~)x8&@b4xE$teLwrB zTRy!T-m)xs70&lvcmNMQvmh_r#}ub7rWxJ0`O$Rr(bQP{K<(%PrHw5zsB4gq_FPlm zJ41SQW#obK!STp%udbImsi*|mzWzA!0e1!NoiHTzj-ESZx_CKR>6~2KgF!(Rf%vNF z`MF>PmpEEF?BIg!U8qa2<;U=!$~!UlCf=?jIOV*d%BZyRa!c|P_+9I)E9O<op+cV| zg|Ga#s?!Cp(IF;Nz_pruU;nCKJHj>X7gRVDr!iS}SJy1_`PV}Sr&X_|ibO2tVNKB& zN$mL5I9gnxrg(O!-20TA9SM~27&~FC*+`Yi$C9KT@8XY-@*bC3oIlPY0*aGmb#Kb6 z-ai^>5<It48ht<~ukKo-v7Urlftk|kB7dlhMM+uME9G*1cMMnbu^5>!7PcFsS?B#M z%wC^z(#p@0S|F#U)wVQqxjuS>I>eSOx~%|h)OE91II%n5v%J$2K3<}C&tB(k_P`kj z`zxQO;<R_dHT&cq<!X=+N4bpKm)Z9<35UeoaxWJT7j;pzd~Vua;40OrX_no*eJoFs z@63hR=%O*!<81tI<?kI?{yx|@Q>R|iTTpO~_cPbsEtcMx%io*C&)(x<CVAvtiu{T5 zc%zurI~t>?uv2xXSB?la19H?Wba6X-AljnT!g$M@<af}JclLPKiePV&%leBd@7+&c zOcVqa_Y6>vyuH`Q`K0IB-6+)^p-fg!>CkSI&YtX+VH=Kb2NyE@^WUF+$Y1f4tMrCw zL+6yX$Ty=L#$x#jO2{#xjJ0T0<+ksG?(67}pJ{Oe775mHLoIdzJE6@5s_V=j+M1At z4-?46h~l_u=ge>bnEn{@$l)K5pjKunN&sZ0pv*9n1gg$6GO-)20s>N6xRk=RQ4Lqe zu<Sfy4`4lk&}QCal#^$~0yjJ&tn`yP`cs&tyFmF|UuCryRZnO%pS$8Sft;Ab5iny1 znO|%yZB>0Y(s~GFM!S)#Wk6M|3qw(3a`4PUP$4(lSU$(+QC#Z47#)I;s|DTiyl^A; z1g)A{2e~}~q1w4jK-*~oQl9mT|HpN5(y#|%eOo_>o;;AN<*y-yz;j><u*{w3G#9u6 z7&)$|gi`-pd#e}u5UO`K$V;2IB4)J~uCKs6`#}dmeko<Uu&k<Sm%(<edf!zpT%6#I zKsVd4Ax<BJyNuLOpLqWBi7qMGqU>OWvYiU^JU>L-ERbzf6QbVTfMY6&1%|FScbmt2 zyj$`@<91r%O_$aHw-LQXhX{G)&yryWo;>{{Jl^nge+0A&@1(-SKW&9RCe|Q(OP-ti zbl=F6V$nD|wsosfDcKzR0O3Zy!7NnSOj74+5xyA3=Ti1MF{;tp;4L?kU6fkyt=t#| z!xOn<m>oY_vq&lEzN+5Kj$@IPd!Uolx<FexRHQc>Nip$}KidX7p7ea>BII#$=iI5V z?ZJD}@8_w!aNs`3EMY-%r!WV&5bZPa0+bg~)O}^icUiTQ;yYjQMX5^W_21D92-j-J z@YS1bC%V+41T~GMLn}0Hg{Vz9l;ie39l3w`=348O!Ak!Nv^!ed0cVNh-%2QI0S@7& zrD6J3mIc?Iu{Uh{`t+dDM^K3%Nv}Q#9Kzfs?2u1?cg)3Hz_jkj4J{9!)J8OAMv2MW zl4L{K5wNdROki;y=lk0Ead3&%O}hgs3y(K|ThbgIO^2>8+#6INO46a7D0@1@e_~ms zu~jQsa?oB|@NjzYmrw4+W%yR1<nf-g>{d8XQD3Q3v036p!qwaQg+6pB#NVZ?vZQXi z-sd-sb9UYtMTxu)<6MtYt;BH0#3P|AL0{na*w4|?-hOo@wf8X*Q%=I#vT_x9yT8p6 z-Pd$6tweW(J;PO_-)K>1+*alAw5Q%sR2t39Phd7R{ksz^SS961w%t7_`$xkL+hE^V zj$f{(2>YFE^t6QlfmpUY{wvd=&*N9UJ_r~swZ)Vv=SfzpUc{>6jL(!4q@;6aJFLuI zPmYx;+=z4gG;SeswG8|H)avbyASKd6i$$KufaSL3X7r&X!GQOYvnQFo)Hu?lX~Wj? za{?69j{v5{?vfCm2dO=hrA7L&E<PMwZ}-Y6_>NRz@vhfs3GlUtJW#)#@&a#dQ2U!J zp=#R|;ZGM{2kj5moLMa<F=YnuFN#J^+|^ubSJnvVujp70lR{Tyy#0228<}DeGe%A# zH~)bqITiM9u{ki#Rkjd*;Vw(S&ohaK;USY3fkE+09*--|E1f^YmBqz#O<NeKHRW_> z{=}C^p76P!y7zRVC1hV8)dn~|(XaeP?x`p3cyam6-02?GVm=!yorPmD>&<&G$?v0f zEgAg~>+W%J>(ejjFP^G(b2K)1@#eEsQW^G1=;wo)yw)F{1-io;&R*mn#IkNVF$qaN zg&X(w?uq$oNoH<1p|PC8u6I{X$x?!_$m%F>|73Q_?#8=kI%44(9|!ycK7MnNH^G{A z$S?oOBw>w{dT1p_lg_8dKdC>-bbs$G^{o}pu#2n$YPKJ@%b8$bR%I5l=lZ_WS1rBY z+_*j-JbA)d*ocMXsauufTWFnUBx&EF$~Cv!M5?+kT_jP0<j1Ei#5+TtHRZg&@-TI8 zy@+A&R8;A5c1D*cdx>CSX5jjdG9CB0IBd?(GD>Thm&)7fy*)Oy(cy<fNq2lct;p`+ zI?-aHwY$yLyl=_AbpN!Exs20M4pz+tRQR4*ke&ia`^ZL_n6b?o-7Z8piI?ikxBJDb zFLRjIAUGXfM!_fi+ggj<i=BNAV$mO{m|XB&u9Nr@JE%|<dLTM^ZA@{~E-{N}YIr7D z8VQjpEI3sMFNr+|Ev{`TT+<ua9?cS~lyejw2M9eWV+AI7yU``vn}eG9`_3*1fbOTo zUMbnz{y3!BYUQ7PTk!FX2~;$9p6R|0oI|2J=nl$yf*DHxYSEb+k=Ib<op=*%R->HP zVuz$DtfMcRz<2V||3{}SnW48vknY0sqyf0Tgh#4O>5vZpfH51JHyskc4RHT7;wkFY z)93YKb+LSksJM&eZJ55a_*r<>_8AEF`(X+ZH>@q9{7)-92Y$EQN@fKvg8&i+j`5X; zlo=aC7k{g!tC8aDBDeX?#6EeXa92eP)1l&GG?{$>Cj11A7Zl?F>hA70FcSFGH+H-7 zsSnci=7UHB_BqR1UEsM9@$Yd%B@LKuPC-X#&jZ};vfjKmd)c#Oy1()JSmS9+ar`5H zi?4&iA)GYXoAN{YV{)IG6j*OKboEqWC8l-?dSp^$#PTsqeCt<(wbE(Hu>A>*RqZYe zawOmqDK{e}swr)EPb_~l#@1k{-0vWNHPVVIw!M=^4Op~zu;Oz`oW}=y9&_~F*ymoG z@Jx05qiI!Dp=vgZX9XXYDf)zH%8c??Qh~lw|NXSi7yY^Wj=T{KezBsK!t<8uOW~eG z?@-Rsyh4l{kxNPtn75~B)|TzNX;}Z~m_M(T)^1{9P3w1TjW==tuW8AeJ7VyW>z3|r zX1-otg)`Pm7x6U-w#OE|p58m5QFkf6>}BrO<@-Ei&YajCF8J7I^DE^|)+@epHV>%! zDLn7tE77}DiWfQSUheN%xTart`Ik+43|DOJTH#}@z0(5W4Sr2gWE)(c`{>RW*L-s{ zMSXoeHD}yCC4={Vdfa>s>-Sy#W>W2Yr=GEw=`}#cqCB%0VwwCylyK29e&ST-)E~BJ z<=PiVO_#E?@~OE~;t?>>c)LIiny)ZObP~lQtL$&1xCY<!|CI8PdEe>JpQd`MjPG^y ze2>Gp?DCy?cT{oR-21_3RP#BPa<v}8KZ6CY8s~@NAGbh(@x+qVxy}I7Q5SK}X)KSd zN3Q?+T_a!q?;7k=kKbH(7_5L-Kans_L*frDRLd08oX8(3X1Ih;cdrK7jke*xox0fl z<ets>G2XTZ{Zyx=nZ8-lua(@AhI4C2+{kTg*)x3s>c!)c6~7Mal>NbTYnH?jQF`NX z=LwY1gfg0o<f+V;dl9{7ZvMdC?+=9^NlJYaP7qvoo3sA*Fne0SFI{ELqSHV)xlkl_ zxA~sQlQTA`Rj=d{%xb`%<s}R1!7ay?=Jt;ozHs&`yI&e;ay7zfeu>n-)+EzNhmPlS z!rV?DK+Ci^D#Mp4R#2-~NmXuZwdGO1ZCN5-)nqeES67F<EiQa9YO;IOGS6W!Tg#ia zRya21O*RJe-|*Zs892%OL5MZd$=~t3OMkQP{26;op<_EtgR^8_ki`xk(p2fI>>C`g z8Jvwh{j1MXwaEWE2a|LakKYmx>5TI1QKY}(^NWuZ18PIpuNF2m{%pMZk6y0ZCrfV{ z6<&f?%3FCH*>n@n+vo&-YTSSN2<7YtNbOH|e0HG-s2TiyMkLF|+v;MURF7Op$)L%t z?<iZB{P1&~FL!x&4oPN9KDCfUE-=-a*t9Z2gdXESn|BgkVgsmIus<KaFAq()G#%I9 zZ`&;5v=1P}j@Kt3(ZeOHA96PuqtO&9VN_eR?zXKwC<|>wqRNPwDaFccqo><ILoka4 z(VyR(gfpaCmf1DKo(dk&{_4A;#PsFA5+L|;8{kF|H&e3AUu-=QF&=lWEJ9ZO)Xn_e zmX|e{j%&U!xA={Ke<N)fKE~zqVfOOr+lFOv!ohdWvLk_|t$!}3aB;|#BF&wsNns4= z)C*7#ZW=JZU^wBD7tMEy8=D!JW)!wJuEnH^f7|zoM-daaO?WteIPpGijLjXCXRnqT z&AD12A>QI^>$v*-NpF0KU!Dry`*yQ%tk`kMBl*?SJeQ!augbBrm5Rt6u*+-1a7{Gh zAXu$M712=vHP9cZrv=lmZJkzk^qo6mzC$McPqPFmmL1&N)Cvq3nM~mx`R{;z53`bw zEN0>{V$U;+oLjQ2VlP~OYC%0j==F1;F@t1hp@t5HLASd59dS$BHbl=!%>fxY<EOX# zKBU5~IjtC1e<io{^!<`|w+c=|Q`(|o{GaKNi!*MS59lDS1yO<-2TX-N<o!NBe^3o} zwPrndMRB(JAbHHK-08$(5;+kRdEd0w@I(%ZbynC>lt{mf-bUuNUoR?qmae}|-1mO7 z1UW>VZ1EKlD=De!NGq)>iE`TWVG1bGEhG097pG2xw9+_zcjty&D^XAcBLE-=WIJGb z`}Js#409KaMhJE1ly<*87MRrDcrImvM7)0c^p>y!=2a_NP6aBJYP)EjHR2dqb!Vi- z-tuYLn3bY<{8OIcy+dTT1zY*-R+Tr^D^A<n(PcLcmrx6Nc*T*Nj84qeaKp#>?XL!! zn7*?&O)ytNfe%N~-%sf;-g__oAc&88y3_Pr1+45kuQ0Rc+6#$HZ=OHzSe5OL1i-nE zsFj*K=#wdGRVQ>;V}Fz;tG&3VnZnr=%~(IgjF_DGr~;i?f3>s1BF8Fq`VHYs=n`uR z))s#=L-B`;#chqiiP-T6s0T_+tBJGxBfM~dPs7C?%&28S&vBcKnC)K;;_x$QA)jdD zN;-5mgkrb+kz)O{Hj7eU6d>&D?SbDi{Zn5jtpDfn8=foq*D{^b$EJFK4vxb$!RmzX zp~E-CcU7tNPHXK?Qp|MRYy0E*Ggi?qWbXJ(!o*}|RWJ#pBwN|rm*pSyCEig&g_|c; zW+qDfk#sll<1fKm!pv7bebck;UdmJX@S&G-BF|)^pz%}dxaG@3XJ(ZaioVysIcpC! zafDsnrg`06TilVlpH^DbD&#ZYP)#ljmi2h5%+3Y7M9l6ej82reJoHk1t#Ah|7ZK_U zP$QN5?~a-5^U6Y=UB7l&CtUir+hni!pBAmTdCt?-i5E&)#I_}Wq&aoW^o@-Pt~~$8 zpMVo;M#bHpJ`xqr%zH%lf3qraI9zq<q@bPTZQuZh%vuIX=#vl4g~Bq^+jYJDF|?Pf zs(YfC4ocmZbQr%<<T2G#n$L=mf0;-0EiGAI3kZ+0<doT-6~e=oLe0%YzI74>W_Min z5IehJK{_6DV!!n1(1WndRQ>^Sxvof}fUl?6`Q(=P32au7%X$3gGMf*%SDdb8+iJ&J zzPGKgkpD2%G5q8JuhkxFk;{uy7siW=lS6@vdE8cXIVoa(kL!($mp!{8M<NHMBey(p z&HBmWp|#93@HxftLsCY>gF=jJft;1XgFmmH$ZO0#X?<_~WUIK3oAKx2gdWV^s>;gB zrHRY<o%#n>Bdgl>S6`!^H1sXp3zQ?&wy&91;(gEct5(MV*0l8!H?AQ5pl9wo&YKc* zvLS(fD=9n|E89Hyh6!^XRapPDqGRtBXZNknNgfzHZRpLD;WI-6ep|x2r$>TgM&RV0 z@fd3rcCvlhc&AcFO0qg3i@Jy=rf`cz%x?}lQJX?g=;mV(VL!)^*Nnyvx489XroxyU z>ywy305V^*9~@%R)`Zwj8gIsw0gHVjxOJX$%SJR7GYkXZmf39S>!X~xH@!M|Jj1m= zJ)Zg4=N$@0Ck`^l{#VFVtk@Li^SAiCb}H(h9O}$)@i=<#(1x80ep>iM%~kvjci(7w zuE_=!(xG=fs*EnlN{jDW4lRvxhL&dE@)B+>IsQ$tGX<Q)eEDDLIKIFFLj8ZTg^Pm+ zqfTg?vs|9+`SG>d;8QC59?k1sLqTSDX!)-}_1<t49D!3MwXwNbA_sv3-rmrTT2?MV zGZL9wC00>h)jd*NSr+T~LS=IN_Lp1fk3y@*j9Jb2K}E=J3cI|$1RysjvI}M$Ff}-W z?!@k5kUl*DYlV698yLTR8&cyt^e#+vub1AL;KMqx+xFgad4lwG!;{i(;AqZssv~nz z5pdpTaDUa$V$&E0!5kyhli--p^JwyvO@><#P{Wv(2AW3-hX*KbdA{5M#)tpTYH}=t z7)RP$8P3glc37x_LsFDbq!g6&_G~=+TW6RKEiSqtBXmg7Mik;t9OYTxf+bJmdWvP_ z>%pO1)Jiv;58d8)(1y4`y$5PF1ms@1`lzM`pe`3)1BqF|w_uK_1>}SjaE9lok@_Z} z7t)Z9TWP{QPT}ST&6_Rd{V-`Q8WiVpLkd<2$ca%pbPGNV1%gAvBIdY_iLm5Z=L{=6 zXpt#{e9$KHLduph0z2He6SdaAj+e5*+{KNti-S|Qlgx%2?I4#1@kJUN%?-(XD}(v> z`XH3QzzpYu_O2(Ke;Kr3aXmn8WuUjMei$U33Ke$1f-sc7nyxnJN4T-=bjUSvU1<E^ z=KkxZGg|+5_tjZ^aTpwgg=s8!PVKFL6Vc_rPflfiMsnaEyQU$T2YA$&q9<Snu;6NK z2&mfkypTLk_!fM4qZN(!F-5f9;0gknH~(-8F^d`u#Ndltmbi2QvQQj_*SCRa!5Z`$ zZIs=$RDr-Bp;o{hdnKlapr^)4hwcQ?TH8_i9?Gpg0t*8)J~AG3u&$F@5$#c=yl_c5 ze^Uz*x?KdMxVhgL#n^pxgtC?8*I5T(d^t$!4`gi`1*<uO4dnQ{xyS$a8J<hvj#{J( zqO*oxA=06*-OleB`h1|2Dz+O?%_UBhr)|TF+k}VV#+cctoFFq-VoKd;3myYZvV+LR z7AS;{bA3Km7?`x7Jb6u=%xA8=sin8_Z+j2&*aaB5?t@28vV)_LV7`>%+udEHP2(=e zJUk2@JHgft8gs09WX7{C-#6OnXb^bE*x+gYzz2bIb2A^i;V}UqEZYuv^1w$wsN;EU zQrFHRUfW@li0mbNFp2|1l~P}$0@ED>n$D5s%}`i?9N`+%Lb!De(LodQ%eRaF*?lCf zOMdQ;xU=QyfwKxh!6T(-|2c54%>|swHDKN;pzw%`1Yuy!u@rzCnlParR1k2WlB51D z)jQQT8Ks}tbob!p=cjJ_E%ho}AUl)&5g50$6F5+Ppe*ZLB{cU-%_-Y?NM}74)&asb z8X){xsSV=yhkaMl`6^tC+1GEW(;;q|7X@*jfUQrUXrAI<f<aqy(~_v+J#Fx$7;0e@ zjzqr-K3e>}^K(ptO2jMH_=v`!Rc$)tuMEm0?1ms#LJ`*4;hJJi0AgYZAoOm>#T48O zRzeLQ!s8|=K*!}tW|cz7f^7xT+MV$$^}CgQTSe51g6&t$3qx^Z$LP?F=VW8n395t; z4~@BjM#U_qA-s`n$emFHQ6+Vg4>HRbw=e%VTyJx_rb|!BpiFhpkf$wHhL4ebkCz*e zDBDVNM_zp_gWAB3W`W8!c7b{qH*8e0DE8h>-Kxd6RPt7VX0ag4P*nW0^WOn3&2AuC zGUSORK5|4Y^N6o4;_9PGr<KIXY|#`FVbo$Wg+rX-v(j}<gZw%PUD0{|i(z7yh-||) zfwwHg7Z;@|6YFhT2@D&*i$MqS02g_0+lwmCev_fhoRsX`>m=^a6-R(ZGB(Rz`2a&x z#rU_+9_LM~Ch;$J7UcwFo1MJSC(QEbrQtb`?j|1`atb75*7$W}X2y*-*(9U)lPTQM zr|!w~_E&x@3h|CyP2($J7Hnva08-pm9}3D|i$I%&sm|CC)M!11JV)E=+P0O4VK*)) zccZu0i6kAqFJ!*|)Y?1NV{7kcth&QSv7|MS`vl@*Qn*_G%NDrnR+Zrww%;q1PUf!Z zR|y-t#wHUwSPV0$+f^S$L}vo|Sn`X%+j!IB#?I=7$?4ylv!_;H9e-tAPkB(?D9SET z>0-vv>~Y5upUe<`(SR}}Qh{S<&;rY4&|5FO@A<I&>D*0uRXv%zo=aWV`9jqAf8*cf zNhdre0ru0Tb3I}{drSC#QOy{bZ{~67A61`BgEfIDIgA*%=Rf^-^4P{2z6mM@-nA=L zp6-yLG;1$?y)za#tGe^J8XJETp0T;K4acx4j2c+j4tjTQb8IKQ=Q5{EeT`p*<P@nW zDERJuS-c4lG&a5C@f!(UZA0O;=K0=v_0o?ezvt;&%P}=HM~&fC8D9lS;Y2fN{%=;n zCF;YoJ>BTl!QiiF;z%Xe_E36Pl%H?Xx1tJ9<aIx70*U|j`xcbGvK=6W%;kAL(44$$ zSL4e0YYXe`k0)BL^x#5((?0@m1i;fVZQ=h$L9&rS=dwS$vaHH?T}^FY%*PkkgMB2U z?)J!U+V07KbHK~XM6X$F)PNg|f7^=K&RU_$@d0yhRsXaEU44OOlXz*CTPI}XvN~{M zhd_pp23{qV1DgIX0@=j~nC=aALesIYD8W9o4gkzv{C~f|0^%A5yo_el6D$bfKKO~n z!%qAwKc4#9N80KQes<@Ly~Talh{5_yH`U}f*~Ue3RZie5Le=w(*71{jgeCff1)-N` zq;r%z@&CsA##<N=DUA_59l&8>xd*On_w$9;EFYaae8%Kr>_=<n=tR+`Tr7hQ<bpS0 zPM(MHpibXr{^8&z%gCeoiwR$hy3Zo!hEe?=g}_}DQ>P^0z|QwNGHWm{Db8T0GFlPP zkG2Il%~M`I>douzN9?+f3UF-`T)*YVcZqTRw;Ra@<EuBnBP9Al=Mg0vt#d|ymhc+w z)+|-!dlbXN^0+Mtzqwg}`me%p?sXv-uZ)>nSon`5=|){x>biOU)@kk5Q&x<`l)5rB z8%BcF!0|>(B6z>;SN2S{5xbN3LAmR(fgRgh!uK>ybR;4>DkTs<YnX72dXPDxpcDAe z808Y$ZGKaRPYy?dBX=H7{b!3JBt+Pp1$QM#5Lk@a40LZ3h)L6gU-blpgc{YO9w;lJ zE|$=tDjrfBvnCqs3GloHE|#7hmQD$S(!tJU4?G`7b?j5K<^fR~b)TOebs3bHsv1bf zY_g26?HK^%w|z{9PROAa-Xi=~#vd`;-t{|02-*ujZEb2CeRLI^mXZOJ-^H8Lp_eM4 z-~nVWgc?@v#!W=xXhgU^SdKJ`oR9@=|1@}?^$!oBfR>Sw9`dWOi>Jqy)Q)Sqzv#x2 zbe5ynr`&*thz5D>rQ!flKyozYI-#Q&HO$$8n#gFNt)gmPRd%{o$lvs|Q7b>Q?ax1N z9}RlCoU;AP|Bv-m13>7s*9uFXpy|4Kmb#2^{<t~pk=r=JYqV4vdFF=as3h5p@EZw5 z75j!;caX|!du&CCnW6qU(*mY<T(4yHRdk-!`>OM5OG_~OkOylq9b%xb>LF+hpP9D6 zZHI@_39Rw~GMKCu_xu3uPEC~bYR}6OH(l<uTM6gC<i^`Q-sxp$XLsC~+vM5B)sL4@ z6}8O?FFc>*`|CRYNGNEwk~QS&D7dC4n{UdbZ&r{hZOCo?+FgICu4#&2+Rppcw9m`j z4CkcXIqt7q{9Nmj=aN5H`#N}Y>K)mc#_#iE&z8KrZF?VuY*V(y8KRs)$NV_kY6A@% zyl}=vpx)!darU_0HOo#a&!V(#Tb}Yc|KahjlEkBzrY&}yUV2A(ozNE=#-yhWK^9w3 zL(_!*0J!B9@|8fkv4C2?f@VWM@F~dfZI$~H_(Al;R2R8+-`t^+d81g9pW#Zba+WT_ zz0*-&-<lUDwC6<IeyK<mIL|p~{9OMFhk^dVFEh^^=R8Y^vj4<I_$eG!7fr#y?WxFD z+}~^1XrhVk6LWErXD3$A(w@J&z!!ZFkEUWR;XG@90MyC=Ixm2bman|`3OuoZoNaBI zmRWfOSGS@+0NZ)4PkRm%`)%N*KzZsPYn1D7dpgpBBe@pf*0r$Yx(4jB1UR$t8cn_L ze?*=N;(;d1_0&`l5&!-ACpyIsOBFSuxb`~pUDBoOL%!BsyZzc~IC&6W9tNqvh>Uo@ zKN88gdYuk^cJKvLaiDs{G=L|NMyvs>kLk|7!TtJ0hol@n#WTcT7E@>FP-q^`b(jvR zgi;jX;dd2uXguuZBuw<c%q8bcHG8{J_9HDPpWWZ5C1k@?y@ty|-YgPm?5L%miF9bc zSTo3AP^cyIAX5``9&V9uVGbDR>1c`yJX{P;i;j^|BhrL^2_#Z{^#&l$1tcj=%W$41 z_`i-3wKM}c`44I1Kwtj}<?xf<_vz5kRBOM*nbIg>bT7}U!{x<!Er-t<?+2p#g7X$g z5uK}pbSO=W_LL40du`#R8Z7y918NzZqG(P+kBK#d{1}B|4cL0o_Bbe2_+vme&OsBR zL-+Gx*9EfTLNBn8?U57U5VVZZXTb5qTuz?;;U7Vb==TcuKS?x`9K6&g@Wx7jT#(oQ zLoVUhFQUVEAV0Z<4)LOpUh!o|+<P=4Y*mODr6K!a+B?)_J8X}ms+0f~(E~Jz|4vho z1?k_w(PHu&aJOt{kUk-^@V+_RbyRQa^RJu_v;=?fhGGpCFJc$@adRN-JMB+73QYX% zhKwRnE8$V7Ns#{~D&ZPWBnTrxL0lx(f8W!US(Zokm(WUZldZ75I8{XzOMRQGu16KM zpxhu#AG2(shzEVWVjXjqs!-l~iVm4<sEpb_DzkU>B4&M^q_{K^K?4U!@29{wqRC1| zy}4k^GVpXrx*agD{TK7t_ZEn-!3OiRE2A)ZCp_LFzr<sA4<t0$P?U5L<Jl#eBv6Xb zRNRehS-WQ_z-juE$fpj&8F*twAgq<Ibf^|U_lGr_;KJ-@I&`ldC~d-q06>7dSpc7u zEC_`EYh%R!&zmzm!XONYqeF5|aE$*ERVtM#xE}tW7m{68o}q>&QT<YnFCvYAoxS4g z2NHqo4E}E(qkre|fXs(>c#Ic>U)BQa7E{qwUFHoNe-+e%Cb`N18!!D~fN&SkKFqGL z=U=5o<LnjQHkug(94r6E1X?3u;xjxV@bAQ}=mr8H;I%^f3Cj++_dJNOa4T|gW81BQ z{=OyfpIg8p8~(P)b+&h(;nvn_Y*G;LaWP}q`Hd40Dme3HBa*tt>bI_<t_tj`4lRlK z?QwQu$1FFy=t7GX5HA)awm`n<UQpuPp1&bq02>#<v9`O|b$0`5Xzvx=#Kcf*Q_|F5 zCnb8}8Bh>v(+vX8)fxeT>CuGbXTf9ldS>WQ+>CfFFef@Rmz!?Wu(fbDl%jalaZOxt zIJx(DlV~y1)P_;~FGCITX-5ZbC;;}uBEU@4KXwgr+=$k{Y@P8Q(0|--`cEBO#FKL| zYgn>{2Ku!aka%b&?0VwzS2^5u`QGG!H{}7idx_Ty0zH|hF8yC%g`VLNWe|is6;w<B z6f0jsIKg(l2Q^D(YF$tkTx*2eU>P;r`#&sCN8g8sCh1T=>g*c<bHY3M*^Y}}1bB!& zvyXNJ$~R;H5rZ(|KQdn0_Ydez=<=^kP<5|u_?wiVuh_r*%{9IMxr6-Y&J_dN)zMZm zFR=U;dE}212?9tEJeEgYUR0$97odKiY1=GB(b;7vs;EBY#<cnqb9bZ>ey^q{Ed_8p zv<;knF<+zpv9j6qM6W!IMosDg47q??=cWAPdXAe;p_g`j02N`-ZEFh)DgX?lHW;>; z{Q(&6+mP|JMk@)x>gt!0q680GEY7~8z4mJgRi&(6TN;6<eshdFRxhI0DRe0I{jZP+ z$_%o<U;~-jQT7<BN+Oo}2H<A?<~te4Teme(dPDe4fg3sXefV#`ddDS!m>68)xyWf; z+NsGrRB2^hT3qasn;R%@m@qzk$I>jrGgAM;)~?-}TRu5FMyI0}`7wWi=R=AjJY4jb ze+!hSfSs&%z&S<tU&W8QCO$$q1B8gPFgNUg-sM9uLUZ|u`D|VJ5#IafEu*T%_kx3; z;y(u)?zuiuE<0j9{ZgF=)r{oat<17CkF?;-)myt2u2h=Uyj|tzPrm~`)&>?T)z{;5 zuX~uw?8<LCd;UUKp=5?{vu?APlS^fOIf`?#0B20BPtHNNW)JMPlsn)gY2`B-arCSH zK9e1X<uwlnLqpJEamFaHu;>K8ze}k<aM&^DN@)IBOZ@hwxzT*+Dfg=9uDecacpXdi zl#Hq1`qh*6djQPpsm$;v2KZGOBl7N<b3(1P<}-QdqK8L%2lihU2ras{cXbz2i;0a9 zV=Qj6Dfr$6y#$G7%mwhG9=yz-A2CtP*{dmic#3>AS8xCNBm1$j7hVk_8~{z&3-alZ zCV<9;P(+ETtA{PBYP_%;D9)wa%^xbe7)jI(*JrEHuwv-P_1+H0zrke(K_jJXQ$(J| zkbxXz)~H4;@y8*Rt;pTtE_42sCt|xoDF%NIbZBgAd^&ddSHB4HFqV<uHa1hn9!egD zbj}mAJ__7RfcRq0jg|63UTe9?KoOT+y@OX-RGDwp>(6h6uC)Kx&0uPE{H=u&Eq_nx zhl+HU>)<u1vS-E`A?zlPU#h!VGG<2FqOw_3Ki$77VHe^>|Gj<!SqO~qtaE{4_Srd^ zhl^~~dpA)t8IbA5(c(N}IQ5RjM&_1(wwd7?l6k(^Kn<)0)3yF8h%Lp5zzqZ98y;01 z`n>U=H>gqk+b(f`$p&JghtX>S>q(Q~PlMq0z>T{AzL_D#peF;ujF>|pN!xhWJPtg( zWg#3MQ^tTA?Xq$&UXbAhI}gaB1elTn047P)`vqFU0tY-b(o>;Ri9^^E>CmBlG%P$@ z;scD>Xm|1W1iU0w3zh-iW9mpp;^MXGC{BbU5PVOD2IAe>QWBWWNY!(=cpgnOU0Byg z&+&lXRcjrN>|0*Az2K$*zz_#!Q0aDpr+7s%qXyk!-T<f;7sM%{>lR!8eSdEL8P5jS z5qN+e|7pwQ`q3fky#jdV?Q5{bR>Sh^Tl5eLtUi{TPXuqbNo>>vlOd;#_C|}(D1u4> zJAmryk#Yq&<39t4zj6q(Qi7T<T*(s}B&w48v1{NjEU@Wrv^6Xkx-v4kjIYc={QjTe zB@w`#4|s>_g3By{B!!txBt9SY4x?HunvOcuJa6$gXsfVF`EL1z{58pghpX9dt-VhE zIoIuPTP%^;FL^mC!%fD4T)FZIE>BHsPN(nvIh&!{%%A30>010@V6u8R_uAX8qfcH9 z<X*_ow^Vg7Pj}L7j#qh=p)}Uv75O7M`bBnOAC?EM7D8PK+*vc);J5av<(lo8c?TQ4 z&mZ~<3SxR|5bFn$eCv-Bj&5lj@fG;`=$ZCuvna#D;S%ajBZNJ4(X>Vg`?-}X=nFY` zQ8alqgSBw<X>lNYzNnqOvW%i!(km;!Ryo~Adt7@v-HqjmMw3LEHqs*<W*44u_@SWA zSy}03)r^ILw-#r6ysD=0YVH|H*L~-1lvS}-q@Fdg9aQR1llhV-IkcQ3Wq2XuYh}`t zLN-I?U5`ly+3;U43<3oQFAU1UC(-Yusl18c+%hUG=rGcb7O&zUkkUT+89kH^8L191 zdYwXinJo6)C8)EX^H8jRxu-xul$6uYi*v(v_82AL2S8r@7)R7Em6M=-tYD(3`H0() z%rXP)+KWnyYz#&+^W9yu9M5Zdok#y*mx2#pC@p)}Wmi<S&%E6s!c5yN`VSug_4q>< zDvqCz#43(I$$T}sttjcIv;NHWg#6rG^3hLMr^hb1U#wp0zAL>4<@L%mB0fvdD%SX6 zMc07ujWqA$I*QZ+S{!QV9+qe<-ZxW|<WP&|_7Oi#OblD86q#0+zF&dK<8&-c`^9f8 zRl%;@u^#c~+wz*X6)u(5;nDDOq!&#*XVlNPy4_J(yia`C`}?v62ont3sU{iII|iNB zmULq?Y*pmhl7gFrtR>H@%OpRG(#Cd`%*h01kc?KZfG}(B7}4Srd&Z;|A2GR(4u#(g zIJtFcz-8@0(Sx8?rTfH-DO|y24{q9&WW}?%HT!-+2!0mT1c)lSC_PJAYz4HB{P1s3 zSu=;(^V7>eh8ix4erL7vC{HdJvXS$bzL=Th^)XmMr$i<8NPoU-kT+*dh0Xo^a~TE+ zx1XH<>6EpV{p@_-?RvM{m@@_T9pmv;+?IoOrv%lyR|DQYa*+C(ctk4Dx_{g{$2Mz8 zru5)aYvQ_1LdSHC`P-@wv4X?bMB2WD*{X{0U-o6;4cV@O^Uwrf!r~87NfYWJ(gItx zKMyy_yMfS$2o_g%%2Aa^UCpTFlUFa`BL0Y=)#Vvd9PS;LeAX?d-Kn+13_uXe0a^lb z@S@L$hM~mSuq(c9!`Vv0CA>bZ7ggh|epD4C>g-CO>PghDmbqUEiQ}|+Vwt&g1!aPy z+8ckaskGKTSaVkXS!u>XQJhoFj733`tXCI>`kwvX*IPw0M*N0Poa+@T4Snk60(u^0 zH60H4rZjQB?FDH0io3uL>bJ4OvTo`V0Pk@#<*+)<sT()+obawHbrEGk3ZO$=H!F@R zJ<b1P&B8nB?(3iKN1eQ$hkSedv@77FWL|DlpM~mhD|M&CDtd9Pw!iT1pbSwr6C0Q_ ztyBMnO3FH4oZxY9gneON3GbP}`JkuvO#6}hjX|AU8Dh#;wF(MDtj`&+S@5mA&@hfx zell%qV05SKth{;LTKvn2^7<E2kA~z#3zL5q=j5F@_~oX_M55B(j+}#9x`Kx-Zl+^e z_tY50rx&iD&<z?6Y6CBUM3bactHpy|7f-{zmoy?TIJ0L~XURvc#Kbxu``YAovz32# zG5DTvaGg#3-9K~WEXAr|k|Gem2<^V9b(f~WVq&%Xpks`)ai3FP(Bl!|)YZmkcS=it z#oGIH?6F#NeS0@fA)w&xIbKUlh^FPUAzL|q$9nap%xT-3nkB~L88XFROPs8p4YtRj znTHFmq3cAVd7s(&oL&BL<N`4w{;Z<sYqN}|IZ<^FGmC?!KLh5c>P&N``Gri~s56WW zZ8P#6B7T)0sFW{NkM;ml;d+gDaVkim{bWh^{Bop`mE+J$g9qo^a>~k%p858W`D-@% zYU9umyEK^!EYT4Cy|7j_NU#UL>KFalTs@3DRdz2qhm>gY*w#{Z(5Oi2d)GF{j*EAh z0*Y__9JVuyMagMtHdG_hU*geu-Dv`b=R*xm4Hw_Ht2<9yH^=9zR2B-;a00}7jS!OU z2RJf^-6TusU6Jr=-0HEPFPv)JLZ1{ry5=hULfOQ%@QcvT01(>j+XK&pBVS!sWQHfG zybHtlIVQ^4L8Rs77UF7tN^`ce;($|MGbutQp)=2}GfPFwt{kcjtk4!wU9c-jP&v61 zdxD0x2HBJX?Br@cEDdsig7(o~u>rV7^iV6Px3spc6ef;vbG4|s^KmFon_@M6;~sVA zd*v@=YfSaO?i&C0PQ>fvY*5h%?e&wiW+`RIZ^k$!jDWXru4<aa`!e+XCl+%U>d9*q z13J{+H%TDrHiOK|1FqeTD#Fo33nD>GYmK8O+On<Ql%e2ABB*tVnu+M;XQa`8USJNY znnV-rz31d#Ju{*z+eXVjWurDN6&%Bo{j`dKW$*9`>J(pg2Y(`B=XrSPoOtiY!g)|) zx&;D+(3hwVhtYV3;|COw75(<Wg&y2cOLX5gi}$;+#I8O~pBR+|(jSs1nCMVe>Wtn$ zgzf!{E`Qyi9+1rLhKm|#qA#NX{nxS7L{P8UVTp92m%Y?c2yZOBWCO@3066?<81T!c z38%N#%X7hvUW91^nZ2MMXT97?Qv832`_Hf@o30BO#tKpdrPrwRZlQxjR6sy_lNte$ zCPbQaqDZewRk~E^0s%yjNEd0+rG^j@5P^gmAj$QP_fsys%k%yCj`w(fk%Z)&b7uC; zx!0P#*QVS}AA#q81jAl2gtmbKj(nK*`?-lV>m2||8J_&Up63V9Esy`|)}PnwR(Ngz z+&R~763Ar;aoN=+Usxj*p_Z4t5JbN3p!4bWgGBbhLv2e74PYyD(ENm}GGMaX_%C*; zL6?3c{F*TZKFi<ZgsEdbH2c?n;7{eON&iKmZU^uOh8@@l{}3r7dILf{3n9Mn>^`_l zG^`pz5H97wrn<>}8QrJ@x|ASMa2@mDqvH`Id`JTv%6cd_)NY*6qNI(V&>jU>bR?d^ zv$oGddvIHwyIK_*_czx$uhs9s_!i{`f^k)`_!E*H?V+m;y?BGe$B4~c?gB56{r_Qq zJ1Aj^98HP=B!?o(sp>$!9|CZPJak_mf$+R(7i_)x8AE_TOiluxrOU6sC~DoUupm68 z9lVuq#F7Mpc~+0;w3x01Z4lXm4t1=pwE%}nXPRI2`l2fe7jefOTma_HN>p(<)IkhQ z07O7g>-mQfKU`?){)^&7#9tJATzGO4l-Xqx`VjUMb`IefCDAO1>uRH^P}d%Ela{Sd zcMW&MzUCE*V4E{HI^k}-l*)VnY@flLJd(5RJq2v02G~pxFr$-5upS=;iw1u}vG2g6 z5R5J2PIDsfP&n^_1m<K8M)MkN@x}55?JkGUG$$&r5X}bJDl-L47Nep&G(}j)N?M!z z1<>=ty4v(@@F-YqaW^FN;vyji*KIuVCR*ALPRrxkY?EOdo_=+xMEn`@ol?9!`$E~l zXM6;a(X-7T=bh7D!|eH`>uJK6cHk;LiA+U@(_Lt{w)Bm_d@QrFKDAY~hBRdEb?q8i zy8UJU*p1cCoI2{vtK*n*v7L5XTVi1`7-ouoleDQQV!tmCDso3mya#kcdUe_E2)3KZ z;f{3;)Gj0P5}ubj`H1|&Pdc-R2b|N*3cd1->uxds4TqQSn3nj~ArPVq7z$VDd>Q)8 z^Pkob!tpuDk=w)c$Yoi)*pM2xiA*Z{B$dN#RyF(0wMQ=~1Ust|e@IC${(#Lo!$Kx- z(#97CLskn22p4a6ZsPdvu!0H~T=CL*UaM)JE8M4l=qJrS-LRbXL7f7N1%}TdJq2iX zyJfstbH_?ZSOO0VOeEc{md>Jf)_~1LgQZ-Me~^$DEozth84vR78ObdGw5T{QmX-YR z_ANyPJvE^C{eP$ZEYq3oyurZs=~cE7q+@SSy!#EhTFSstQB&2yF0d>W>GlctQt)+& zRr1FIFihHyw~u{Av^{i13?XV8{16fwvh3aLE5I_&0CUd02ZD3ZB<GGMfb#xZLG!6B zSVjuaZ5qfPU}7qCz?S4HJxIvNXlI>LMu@35!RtM)S?>IA64CGI2o*bUt$YMJhx`$O z3jtQFq6RJuCHbTCp33izp)kzQNgDW4*nV@{wEu1wogh(Ao&3xW07b-3X)#!I->;%~ z`duXcxorz?{EI_F`TEUZ?OgbP-=OnSSpg18^cw_m4C<S?rx9&55Yj15G7+4u16D1R z1qdI?lJ>#5-8hNq*we37&so=~yOstOAFK7hUz*GKv)5@LsBQ)9WmcT~)IXL_Ajphh zh;LMbn?fCoE{-8EVjy()mdf`NTl>!%yw+mr&6mo6SG&mum`rVw(D5bW1@Pss`lt<X zKh_CHM*%)`gAIa<7YI4~t|8peP1f(>^`<88o^Esak)D^C9@PZB!3nmPEXcvBghSF_ z6ysH%z>~O7=$l2fYC#=h;J@Zu9J(dX2yDp84b(bb8*Xu}dIG*-f%u}0a?m}LAT#_$ zF)~)@=Z7XnxkGo>5eHgQg~WRY`7UH?`}q#Qr-!@<{%WeOFZv_U4R7JPSsS~`s?H74 zS}~^*$RS|&2u2+2Z0i!4^2r9`_&stjEE=`F;cYEyIU@<Sqyb8DGa!41FDanA(#kF$ z{nd63E}aePPRhv2kqBIWPZZ5PnuNV~H*S!ilR!ES5<tMj=>ItfpFp0SBtgy491L~! z$152LIlbqW+yWewhL6tes^Km0Y`We+a%XmX`e)m5<%l*hMD;j&kV@7sY<Ed%yR|Z; zQ4*}B&tU!iBkYs{&<IDZ9eTvP?|~4#o8oC*x7NykpnLXZo}sR9O^^REmm2d41bha$ z387-)b?h17x5N<JOz^`kz)!r%gPo?Azc)k5U2EN!!EOzjqmQbmQmFs`X!t`8k-u@+ z98&x2aPYFsdRBFJ#h>e^WPWg;Cg)%Q-DhfigWX)Rt>3UCy|XwXP@%!+AdJ-aWL!qZ zL|km*n&PQDSXKV4$;e|j_!23qCaVYns9&u3-d#(eH8V&-Sn5`=PN-DDs||M5suoX+ zlf{ES)ek!jr%k==L-^8Gzc!|#<Gj*N->3Vnm#j;PQ70u=(ELTA!(h6RTDU-W;>P&J z1gi<LUm1GoQ@y$tP06t{GoObag<S7|zkK)jx!B{!q5~CK4t~l`H;atcEavL+igsdR zEGsk=JL_s^$S(N3`1iE}t+pOqsR|Qq0qTwc8a?H1=c%v67--9VF}18{+OBVgL?9gC z%=czxL!<|%Bs-IcGIbwa`Z?P!yIQO|NYc>wN#Fdj;NoqRC<PJg;fl_7r}puu3=M`5 zZq4U}OC9D+mUZ%o;EJQ>8&j&*ACB|4jKJ?Rwtl~Ly<#-+wTYsZZ$)w!?rNz}?^|l= zht(hJ8!XCV<n5vs@1?58hDm6?)zf9?Pd+vwM(J+2q70eXS)+zAIr?)iuD_;DJJ<hq z%0lUd8tx8Wr{YpbZa1F?Z%DA3nqf$RX&tPSo>|1km?MQRKL9n;DlALH>*-~n&AN2g zO~~SJu+TWR^1G|$cgr;MLLU}J<QqtvYjhdkUy(B{;TtV9KsxK>yJuz=<?|=tYIK>F zgK29BzrBkno=c<6oQ{i?NC=%XO`g_UorFj9S>ETB@>mY9WxZtkZYV!}HH@Mc*ra6Z ztl{p1VZ_4(HeXZA(Ko|koe4y~l?Ar>Q3<cinQkYi3tDhKkeyb)vPAVM(LyyPe}77$ z0k_va1>8^J9dXf53fw;$y$fa#9plsL^#QNNh!ZdKwoESH4QQ*j`ZmLam6NVS(FOBD zqtLCw^K_3^uY42VPQNi+bZ9VDi*%8Xal^BF+0(}rCdYo~!1HzoUmR&`r!CXG93hr$ zETk$f<@VL|L*f`wD|K%%4yA@oU?B$g5UQ^A;)tVfZ?PH_U;1Q&Wf}7uNG@ur*eLiZ z=`h%rY{?7pRuN&DgA&HQ6bHlo_c~WUI(%x_>OQp*zEdGFzN__7*#1YGh6Jy#9_JIs z=Fb;G!_W0JoO!p!8cd(oZOvr`-whpK59SM0c{i~ptxHeH@04Yf$tZsHV@oh}#p!}Z zUZ$20=gr~$E9#F~s4!>3SCkC%R(Vd3G2X)0Cwb=2^-^RjUN<@2kg_0VB&R{auO&*0 zWj9bXsf%b!h&C^bRVaFmn}9XeH%8evynn8ig-w;AC@VYFE_{+f{Upaq@q%RJH@^U9 zV@pnF(>QAVu_w-nb>m6(NeNBLj?01Zy4aiqGa2cH%`X6Idd4P&!$LKa7iRK*Exc<+ z1`A7=JD+Lue6GWo3_F7lz`)v2k=f8uWnlv3lZo}o37hKrI$S3CyowXNuw1pkA$#t^ z%efx0nmc?C&m5+NF{t5@!%xsO$`XOr1Pu(7u{gA@UtqAaMHpHCTpw>-(UNO$yFUEE z)1df(eVeCZX^e`Ty0zCr-emaiSM<5G@Z*-kez1@Q@TXF<c%AzTOJP<8d}!hO<L^D7 zfz)zWNb~yd=ZAY1xQ|25JGaoLS=L(F-E{FD-!5uY@hpCgy?R41MltWI8ch*SR*3I` zr*R}UhtYjIKfJ=gQ(sG6jc(F4V5G?uAiE#UEdtZqE`<K=j4qQn%^f^5|KZ!iZ<-!I zc6IcM***0FcRe$??ECu%<$AQzHTvHYv@j-R3*3gCrs%V8TyL4h&xvc|ERXSzK4#er zY_FwV=1%jaNTDhgiKJwI1LBMJ!UJt82+!3CYsFeNew33)I$k|oIAJ@+%jdG1QrX*% zPW=>~n|T^1^%s+cnCF~!CphYwW>=nUcrraQ(Qy6xp^W0p$@pWfl*_6rHa;$;KO3f4 zUVC!)ucr=G7CM}WNF6Fr;j=a3>N2CUpE+$5A}2kj-T`5D5*8YOf5dGsx~5GPtPR0* zBKK#oT@X(Eq_yO+j4|)WD~4f?CastyssM>Q1_s7L(%S8Nk9B9CxW}!DDns=MlEp5& z{;C6w3up4jrQ$TP`t@T-l1zU~zqdz^^iTs31}%ts@Ie=Oe0nh|>UN4=veHB+{2Lkr zi~SyBNC@&N_jS-ee{D|JvwY@fHTv4y^Gdzm7d<)~S`2RYDlctOS6=6s?rNcH9-nBJ z2^JsWAI&N<8o{FCitU)@Zs)3Tx(iFLPbZ|14WD<KXP6JI?YvjIrd;tTJ*BTk-L<&+ zr(nvkbjp~WpeJ+O(B~5ut?uDeDoc5Ud^<I|Cv8On(i+z9509aB?OpkU$m~{SG6S&< zU2upTLaF`XWbmaTo)+%r+t;&M;^fF{W0|D`nT{gfyzC}r1_mW(I(0lsBoT8;TNs~T zCAccg(7Q1=DJ_eS)~y23icOr-)sbzR?Uy=wST_WX50!4op6|2R%ZS>ddP|lg4=@tp zxW$|>38etRi1Iaw(U+Je`r2Ca4oeFQ`Z<O&Cbv&qj|VTRaP;uGF4wqBaovvcE>rC= zHQ=5QxtuyowQf;$r@&r={<iIj`<aFnJ6V_353H_^7}ux%;0$X>pOYWUmNzpVm(lZJ zE6YEn^x~)gIZbPR-}aq^^3e+YFKcr~7Y^h;u1LF@uT^<wE6Wkqbmfa*w?j;%ZGRRz zOO0~AEj1|3;@2=paye&^Veq^GxoEOyun9XJJOE{Gp<a#;J{cHLHx#JBQ+g2odSTYE zwc2`iQfpVR`l(34*Zhj+tBN<{3(u>~BHuVpe}_y9lBt0sOUV%2=|3J;9B4*D+4w5m za*;~6-;0p468U+Checn^b!lbjPJG^-s4tH$8Bg`y3On2~APnLHRKEg`UvOMm%-4BD zn+4^h5H`>R=i*VDorAv`V14-2;)(mS%!waMM3(2f8w6H-cRM)Jp2k^pm}CpN3R*ok zA6L@NM;A;5>WCM`E8csc-TQdaO{*#YQEX|ESziom0xU*uM6o}4OXG_{z#Mf}T7eyN z(Nslw+O0jwQ-Kfgs2IX#I4najx?Q7ps^Mmqptc%U^FX1(<8hhdQ|wy-FT#X`3YnS- z0PnW}AK3zU#`34fQMiO5#QxbN@+IKwg-j!cRq9Yg-fbB9c2&G%mG0`joFzm6v`OCX z+rgn8Kz{M4`MO{pqX5)&t$Fj71~q-yw&Skd%0tgga*8SWk`1`XAYy2F6-u};4Be-0 z5&t_#Kz+O#IzZm#s{R$U0s<>8|Km`2dD}aO$lwGah8ccCw0=h8%w7HM>|GAsS7l;Z z5$Q_O`7JlFY%;edwyU0r!delVEQo`7#H;-Oy0NqOc9k~(*$@UOlX~>_3s*3GR3y-o zmqP#cQ&DWX(80LqK6<V_^?Jg)b=3Sq0zo`H$?YJndu^w}lJAxPBj!50>;vrET5KhP z`pv(&PZ*DH2Kk05WW9<UDjE-Nqza7C?;F_$O}>K8*P^%m6$Z&vUJ2xz#VWv@L_tR# zB?Yu@lj?R}O_@;DAlje>+y(f|pqNa+?@KGE0Mbwken8MAQR(lLn{J^#Mu-JK5Wu6j ziNaaH5AMh`08|zZ0N&?h#J_%)g70Sva$zQJY}oYjbbmwR8LEgZ-~OT)P}xBd`J{eN zWf5XN1&y<W6NDSq1SQuvQ0yqDHC=!f!VrfdzTI8cOxK(gybw0y<t7uq8eA65D}U%p z<Ek3Zt{dTD$;>;tL<TGgvGyF~6iMQNL#t9<6_5R;bIDTJOdb`TW(vZI?t9tTLEMlV z`&TE3w^1OYH4BhEL%_aN3lN*k5d3*?9LVBBPEZG}wz9kgeKE$_Gw;I8I}w9DLBEz3 z6YRFnLI`pJWE%S*YU|EJ#HzbkDYq@?xvrY))2&!iQl|e1YT+W3AYMh{gZw7V)B!&J zu1V;=17OYnoYN;%*rJxcxBSD*z=)kY1DbP1tXw!)BA-`~1yOXSz*WPk&=bUU*YJmT z$&<k%1dBsE@`x!}5;vEIYuhraYiJn}6F(<usyAW>^ugeq4^)+ULplN{dF8sX+@5=L zB6#(%y4kzFb{%O4k4KSPc5h>7x+B(1YD8E=v_s)>^_BWH#V2^9(RA@8TIblu-1IHV zJ|eEj6(ONz=&2KAn&*e~!2^&f88jopiJoQ(y`m;rznq#LG3`y&mmx!6GYx<B{Z2(2 zuGqaT#ARV{ijsVGkCfBQODZlPo*?KhRB>3};N|e%nUB#NS?@h55!iEL=E98u`KK%o zKDE8`CkHuJ-K-B1c2bMI|4}{%TReZWa5kqH%8r^}N+5{PcWZHGz{7(jaU1PgkTrH% z!5c%TcCZ#UZLMMr{bH`0AJ%;_Q88-NzfL6+b@7MToHfBiBbS%H5xeoEd?gF4MGS}m zi8+bqsgUlIp?~~kgyx=A-;=kUynXH>0=zdUsB$0AfpPykVqw$8?#jI|=OouBD|_NJ z`q7gB)*mG}W^tMI%BOLA(JTSW-vegPN;kxto_oy=Upw2`qZmKD_H2M5`zdDZf0be0 zI}aP*&pRyMlLCbm6t<0hg&M{Iygrtgwk-Px|A1)oLM*dDH}-(G>N}wd?f5WwckH!7 zB+Oy*a2C_B#AU~Y2-pT;4uHa07DDeWfiN87e-0(Te-uP7liPIZPE=G3z4`<lW14RA z>75XqkVYMibI7IL_`jk0DZJSjn^SnZ!xX|B)ju#h<G{95A^8UnQjJ9H(}1Ni@dcE? zXo{wo2kiO(Xhl{O;ey|IbuCKVKYr`|af=H)LBdcB)hKFd9lZs|<<dI;Z~oZ599*a~ zY-<m`-#{?_9H?ra*YUx)&j9&?u5#!ZGUw6D8=PJyAVg&fMmz)o=%T+9%v=k>5kp-! zX%mIL!JZ99^}p-8%ry-c;cug+#;+E*znfxt6#n_(VIEkWynyh|X+rd)+MZrH$}5!~ zZ979Aiwohjx^-2m+vC;g8z<sDqbcU{s!<pjz=kYMVafZTPyw0IRgxT33Eco2A_s-T zk*Y8gs(x2}TUpS$eGgAG#$qX!;;*DvfURB)+$$6iI2njA3cDjoV@5~XHmXmzoMTBl zG&#7Pcv;3Zg6})Y{RTHPGvI2@)TjMLp*#WE`|=k>90Zr)gxFeh2f-;-1dy-AfcVU^ zL<XdXzNM8{t#A0CWf(H!UZI8{r*Xjv$LoHr$|<^JhBz&9@EQo{1qnVBUH_g-VkKVW zNF$P_$*yGP^&Fhm2Bk9#8fUOEIfq%lFAC|_J#&Sk{tid~o9(J=ir~>DBM3rl{-V&Z zA13n!>Hh?~l|F=?+|P(;y%DUST@`47AFJCU+Ts<hr_BQuYqEt36)Fa{H8@RUKfkFt z!F2P}abwSCSQIXf`~|jcu6z-JsRjhw;+PZI3GXVwiY*YW>L^D}hlWffg0tDAAdKzv zxI{#SZ^98fkY2)d3jak>c25$V@Se`u1k_bvf=;C(b*YAuxNO-f*zr?&8o&&oe}O4b z&0qK(9tj~^nKDDeP<9||U<*I8VB(XB#i-@1{zYLk^#gHqs!O%!XKy~aRyax_KXXhR zjjQsUGy+zX0M0SMj(+EW%u0SHOxi*0+k8W`i624`LtX@66yf>0pd)J#Tug8`dfQ5w zAAxy00wTc!EPehSV~|{Tt^_eSi~0fTB-E4u1A&mWz~d%j0*Bf@qq|WCB9`gz4>e04 z3dV`dsN%~O*kMBV8`^0obTOoQ=RqPbq9%>Rk`M_aJbHxK_qJANjr@gloX~8HHc6a$ z^hA}7&;J3i+M^5QKel5576^P7tdP8+-_K3DIM79jvR8QBFd##xHa0U8=uUW1QSHHq zvCeKUE}1yxjyP(DV=f;rAsG8fRrVt4oKN4_e|D4mMaT1{m`FtIOM+(^1O{BWul&%K zDiBw#Fi22E*=-z1<eW$0M!{?oKZ0~g__srHOmRmQQJMpI6p}9Se=OMq!cCCLd)Ppn zCJOBuLze(u(u3G%I5Gi0t?6-tzmn?>V&HM8bC!P1X#|V=A0vwDU0~#Ms7WnyjCzM8 zQAP$z{7?m{eV@>FF5~(Qb`HajcX=<I&BCvMzW@I*Qk-4Z?4(3<8U&K)N{D?PVAl&; zpPct!4Qbx{W4j37RmF#hDLk>e%vGIfC%@el^dI^&3hw9s4U4*s%L#`*FdjS8K)~R+ zr@tsc+nP?XeO{Mtx03u9lahBR>cwcBEkRuR9QtVbtVYiPb{H_QN4DPoXi>$`2Om%D zx;)=4Avi!Ig2f0wR`qlv6|UWznj<RJHiSEcZ7ZJFFg1CZfAia^HhDb_>Tj*2I6}#S zD`PuZ1P4lIY<}sQ+v;Qxv9g?TjhDBnMSV!PnwWQ?Yo^4u#zFD;^9!kxZMxrzI}f}E z*OG9Flj2Ksf*rG`R79>Mz5R6EWe?klq7UT7i<;Nq_Tp^f11^9^lU<^TF7le$Tz8#j z&5JL5PRtP^cC_#9X+J#hD$$DfSf0piv@D;}_b|VnWQp=4P;z7Cw3rv_X=t(+UzCMr zpDS&yEJp6aIl~R~3_H|vuIi?X7xVKqx{)RVI?>EZD%dz5V^WUN6&#s!`qkCVRfTA9 zRMIRke{+I{cGJRgkmb@0e^ju+XU`@ocjXg=<IpG$z7_}pi$Cc*(q;~gl@=EW;ux_` zx;ZQkPyPAuwKtnMi;0IDAES838waNce)cJtbmoK%oNSczEboGBOfZ}8UZ?WK@!*Tj z_37SONxs76!xq{iU87norDWS~x>}6@_s1LX#}5pKJ6Y4DPD;HXw{p<0y~aYge5)`^ z;T2xG$IVv}jFLMQrdD{C7XsQkzUvpP)WoGoRbHjEx(u;5RwCWhr|nXX!G88(FZc#Z zl@52k@46E4aXnx_qk)f<k`$X<zvw*0yR0PJFLzbRFw?fS?=+`SJIR7ZMDJkWl5v?y zm0FhEc*MAKSKwX&=FCWbc=Do}w4g{8I-!h!ZO^HRe}+5khA}B$_w8**(Rf3T1*(me z2MS}W=mOQ=<CY?&<W%c3Cs;UaC%@_J;Z8Q5Tf1B<GWWTJHsE=KEUp`?OJo+jH?c+* zCrpEQMuzFmJv7~h*KPnh!vA4HxwHQRR*u*&8%3n@LGBJu_CRDb+k<Sm``;=bY(4me zcz~LO?&c9-ctsF{$kRf3&sTB5EgyH->EWw0H{E4IEgfUyYU6Y+NB2YH%hZckf69*B zjk#V{&1tRm0>d~V4Vi9ettF2t(-EFyHzI;XZ~$H*s`EzHgSoAogg%r?4f>XeX-QRI z@4os;=^6FiAF48|PiV7sTQLZvU7CI&HQKE3ms4HeO3z5zrNpA7kj#q)Cazk0o>}OR zlD?$rSh+;x#rWb^_FmO&E(S$QCIy9*XN*EZt2ppw5#E<p2F@jgw$#EML~1O%LtW+= z2$J(vlf~U=WL2ax9|5r-7)_L{n40!Q8K!mmzi7dI92=<S4~>%vA0KbHY$=;@H7STM z-u%SXf~RZ`HlQwpQBWR~1B`o$JP0{0%}!KS=5^WS&?$WD>&98}ke;R|*y{eQ2i}4+ zAj;s(H#QT$aVo!9E&j|Zm)$+k^|fpGw0V|>Lo;F!!4)GJF~@=9k}>akS<vGm{-f5N zOIBteaGx@@pFLVDHR@r!Kz*X0QtuhT=&5xMpgy2{Wd(xMp+STps^QVWG%HhK1^(pM z<pfzHf?>Y78Mm$I?JMYvSp|z1u5Qm?eLqxxg||Gz=P|_gK%dPx%Xm=Ipt($KZcS=g z=gMOpLsO%mq+RRp`!;7`K~3h;^29)Gr3irm`^=%<$Lp2n!_?Ih(~H$c$25oAr||7M zOhx%7g|b>N2b@uY>oe$Ml3f|7N!hkw2K)f(P-)fr<QSQo;IAdg?DVAGeNeK4#-~=` zPE?dca3`Os)~Ok&(}$Z3J@9j{G#455@br-_*NNP9No_DXCA-Q&gzr?{V8WB0-0tFD zq4R|uFP(8_F-=!%t}!(*=H7Ns7H7X+S$lYs$W55W<pw(7tJdK2Ip=&MI$ES~qANh| zKnlV7ZDx{ib>h%@z_ga3``Z3q2(Paj{NC{u#?U)9krkfMbHVIH%@Lw^xpNM+_HGHT z2^<0~H?vG-b*7`gxLr*3iRQi3>lmMCjZC|Obb7qi!QYT}Iw0p3Wkd(2*y5ZHa>dp! zLubgTM@_uJ-`OxRx$ps6EZM+KuLdd^FVJF`J<@4d7}{<p+^D@^XUM8WLmBb7)1%+G zv%%c5c{8+h;d+Ysdmq0b6K%sE!Bl}a@N;oN<-T_9In;G%rcPRxy)^h~RDtS4{_Kf0 zcMT>F-Q5?0@ptlJmys%Y6ihU{rdhLrcJ=jyiVDIo^sMh{>s6xm$S(nW$j|KaqrdUB zCJjB(f~ILYHMZSW0&~n@@s{d&vpbtLm&LNWyXmJSJNyxyY}*+hX^e5f)eH3Wag5d) z=QhUsm4|qztS4jSV)xF6rLJEpHGDL3t6j`(p&>?Dj3`GCJ-od<)gLwyRf%lc2t7Wc zfqNL1H)DmK>v2*Xbftab+%-SrN9T3Tok@#L<C-uDm$2rzm{M)DWVkBLtbWQX+3kBH zzp%{8q^E2@kJa^A^D!umVwWu;B1&WdpQ#vD5;u5xppL4oUchMSmvU8fl|l-+R_tTx z`%EPly%NpLh2^htmbbEG*-RFj`LTn~QB2-BtYFUR0<YU(GbCACi`7rEw69%OUAp%{ z!=10DMzOv(+^HRD%I-(m=kqRMUcGIQ1;jPhEr=_l7o>lbENsws=JhYEIapVR+>_3d zxF>PHp{ACK7AMbwKW)43RFP*}Bbss@(g}H<&HWYX<dP7JVDO$KLRlJcML(tu@UZY= zSFzpz2OsA+DO<%TfvZ&OYw9UNi87)TJf6bF`54`BSe<D^i)d9xuP&GQ>KUx4R@AmA zoO9*UmjK0plXa#RpUWvz8+Z@(_*6CMIr=uZByMXg4^^bwZFY;?i)z)mqRGrmDcYVY z?is*if~ERmsPAqr*e{cZ&grnUQjhV4U#<vEp-fxw=)08IY1}CtSrt|s*51?AatY}) z9@2&>7P~zrVwf+FaZd^tDa~8#B0M)D#M$BYFym<jfdROI4|CFZr6rA~VI|fj*w2?U z+T!cE4f+`clMlEMg<^NYufNQ<JIRyKMP|mkWns3kIp?igOWVB{MhblEdt0;F!>8A_ z+Fgr#;Cu@vE{z6L+$wk92&O!UUtzW}4q58!jBfAZxi;MFia(CUr1X8TLWf9;pXWBc zJ>HSZLg(%&K2YoDdaA!I=8ah8@W!o>M{gQTra1KLu;QYvsc3qnE>&ll)hZg7L<k{8 zf76vo<9*)}P@!gKXD`dL8`*Y;I=0%S?B3npCBN0IKqYxQp@lO3zR{#G(M{R@zC{ja zCA@}HL1o@{bhHvJR(U~(rQSaMfmAAsT<NGg)MQtrP{_8lojEeO6eFsc#erN7ko!XO zP0qIP7NhTQ3bl8j*6vyj!4xk$kBV%T#-CWA!VN~!KlctYw8Z-md0$A6zfVmCu8ZA1 z&-txL+eEoUzb9Ah*k1Zvf_&MaBslD9S}Ciz;u{u3t1>-c81InGd4HFOC{@IKUN&<x z<b?OER$Gf8&Z?OPQ{t6%?e0jOM%51^mI`-&x9?YLV$vAdhUMbFor><hwBO@Jzj&%} z#+o7WoAa>(Kl)d+|K*Rvo)Y3BDs(UBvzsPQCtP#895c3Do?Edl<XFYDp0@|}!Ng)E zt3uNbnXZ>NIvXV&bnr`?h};Vp&NBVgco|_*w9@8T%--gFEwy|X2!Mcm0m%b#2m=cD z4N#7oKY<p+KY!Gm^oOSoJqiS?20o_f?gLJG6VQ|g@G1;q`FsxgAL#NqR+2WjN1Pco z6)YR5ru({nA3^ho^ZIq~)_c%@1%P#{lCj2yI?84Ze5jl*AFr-!E5?A2|6f)l|0uw` zwMu{;oGjiO186b=pjE1dUjXK+jx3mxIpUxoL#wU?1ECH6Tvk$D{||4z=WlP`+WSx5 zLEE8N3nTvzS3Xwh-MjCZ*#X$$1bahrFq8<`g_rb4`vhWo{uwcYNREI0$Taa!C~yRq zO9hDJY~cY$MiC=}5CBo$NG2bki0`&H7zi%AIto$?@HoUd=EseqxRy^Zx6Y!c?e-^x z|6LFJEnVufFNPsq?tIq}WHWg|mrtoQpQBm)XYc+K)>MT23)U>zM$?c#pU`g*#t$xN zz^`AXZ_83T?g9O&XbCjo|Azr#A_NKt6>EM7ow%I*EHsuW^F?!}``Uj*I}iUIet!G! zJ}m3`!?6A&ldk`5WXdQ2y>m4YK``<?fAl{iGnf{ll^Y3rdhjIU&{`MQw4feS7k7i) z0bww4u|l-Ue0U^EpY~9z{M}Deu>rOVRC>qR<1xt71jRp0{1C|bhhYMyH4rXEi3_|- z<aQK;omBx&bJD}N>IL?Tr=_G>W5b34Ada9m-<`DBBTAI-VcxK8lzK}bx86?7y~c6> zE>d!o--7(j<e5(MsC+z9<Mv)PA-i2O&Z`HLl0AFd?Q{OgDoS=K)KMbg>*@YK>fpNk zVPVFVNUenPcfB*@^Y8pP;oSS8{RI4ekkE<K(Ubp?EjSKNdJx~41xbM*cFe{0U4`T& zTr6yI>Zuct+SaX`S1<c^%PlRI{4puHbU^5PVy5l@=zJUgaR+*H*shCenSrQUM${ly z@q-;Zc_sI(|NqhcF(pQDY-0AmwRSznpPcvAyjAk^yjbMw;weD$ZDqT6_nQ3k4GiMd ziBH{>qd@X?g$d~0G~kAEToMi!5nZp{E2aqXr-vS4U-D(FBXdu&DK@rV52Nt(G8sH# z!AJO|8|+h1Vps)YbrHIK(W=w)F~NNA?rU%1^@|T0Y(z^L6Il~at6PhpkFMZjWljJO zy#zJ0$;SNZM_yAfcM_hHZ^=S-hMP417WKQqv<ymuttwpv@rhtdtBfPA8q^SvzI#gj zg9vC#$YaFBHR5VP<!_n0JxY=%sBL}u_itxGuwS4h;ytQwLfvxd86c7uu%u4%!w(7+ zN3{E#O<=Lm@6?FZ(%*H+zW@H=AI06ee0|8bz=&-C%H1l9f*BYu?rzn-2ISWv*zr+7 z55TvsilGV)?7|-L1susZpby2#Ody`Fv%>H71Tm`mzvAg6a`3Drt%z1#)FM9u2_>aL zSwMc;kM(AmkG=msJFORxT$|eWQLFt>(j|Tqved_WrU9TG9<UL<ho(F>o|^`GUCoGf z`bF!N7r#p{$yFf8w@jfs-^Mf>05$eMwP#Ox|6NtKQuA-wz^|vXehUmv0LJ-%{s2qT zwlzWj{aWvs#oXz?C@eh5fQvP6J)#>(;bjE$<?MZX$v4oulZcm<1|LxDh|iqlX~|9L zFM5<E!5|IIA595z?Mi$B`=(>ELpn_~Be?!WL8Gpjb3^yMi~n7m#r3hUAJ5BU*u$o# ztzsS|s?a8Ums&gD$9tt`@mfk?Tmo_b-&}`v#@XL3qfBlTP#Jyolabn2i||aQj6Jd0 zPj1oHH0&7&+C42uU}b#uP~IdcwCg_es$t-eW%E?k`VKU?*=^8sogG`sUaz5T)TP%Z zJRDQJ1~-ror|aHxReqRVV&Ro@b1<^`7XCyVjNTQA2ubA-UoW)3UZ4fC05c}fyD)j3 z&zn`})nIOoyJNN(zvyA%^{9_e=O=nWFf3!&JMGgHDx%U&$p#ch<46dD|0+J@GugX} zww#%K{+OnRY6>S-Ufn|V(Ac%aI-troqdk~;s7gtFA%WrB%7@?_rN?MAdbZ&5wARH~ zwM4}iZ~N>cDemxnes$Qcz<Rmg0dt0YVea;jBg;rLE64Yk`T=1BPq*a}$V)Sa)0fVC zer!Z+XWp=rJM2){&KDU?*EB`dIImB``mcYOTVKLMXz=P>-}RDfh_XoUg8fAiiGnhD zehKr$h7F0*1_wV)X;(oZIiWeiF+A_W=1Pm;*On`R4&%+-dA?~KtP0uH4!EK@nbA7Y zj4TCCzeQJ_`L=O5-B`2hvHCD(tm&4~>znOwatSAPnQ`zn&RpMyHdJjU9d7Ry?z>D` zt_w$?e^}pM>&`8{k)Tqi;9;uf`eQ{YpASK)JOMFJ6dkD3yAar5?$B<*-h9i`@$TM} z11_~SOtkvLc=dY?%qAz91w#}bB6lEEzP0N3${gH;39cpIW#PIxWrpTg39$mL>CZ!E zSqsmeCaUViYv|pe>e!b4fqB0ahg;VS_2XJm%S;yDoXfNwwQMx-Sd2+26h#(_DqcI_ zjSciWxNT3=NVjLB8VeIN*V_{sHOvx|b}-1ampdH0$Y$uCb}iA%>JI9OXG_Fd9bR^U zwG%$s1PGp5#4i$_Q-6#I#nQ;WYZ)PnezI>G&h>M6T~IeB{v*+;J_&xl)0?TknkFds zT-}?Nufb=XgHPirJK(IoF&)9;1bpd=ein2A61lDQ5IM4uZzB>Dpo>(J8A_c!y&d_! z!8Hta^^7N(*B4<;xSrp-AQ|J&j}Ai~mbE&$1}!K)tPXbxiC^IN3n`Po^ZkDAlJk`= zrm-qoU&d}8nW3bPU|O78S=q{Fub4i1#ow!ep$Ta9iA2O{CMNRc(=M8^>rh>4X!nii z_Ei$IQ}yV6-BYI_DDkkekniJi?@M8IC!r~gZ~MgF707mIx6R5eW)&eplijxWBBkX< zB5h?MF=aaXCMog_XB0K{J;G$ES|ofqcdbadN>1Kof!YK+=`7SP{jODgE#}bi(wP0T zndX;DjmK<f?wng3N?DvK?mH&eBMqHWa#ZH78zVa86Ee&Q?xof}^9c;AZQf}n_3x4C zJ*SIGQqQ+?<ykGSPjKGWSw5^pSB^{3`Ls{H8uBKwtasrvoTscUqzsa3gJs@PDh9h{ z$*&mInc04Q^nKL3hvmy0=!HX*viT*U-YXA3QJmFSvyy`|$nD0?!tDlqJFSfh*4VbB z-FixTlz&=lRK+9i=rStTDH!J8$}Y{4hLou(FRGhlnd`+GJu1CfVSc`5Nk8~kzR8tL z3q0$gi*bD|9ulf_bI)3Uquf*hdC;H7A2)Ml-Ep3w<Yl5z&S^fn&03|x^ha8jh`3<R z)fNHLn_N=vqv>{0pM0xt-<BCH2~Otj`89W>uZVvQTKJ*%Ui^%n$wkLfDvRFoT~?nb z^&H}9QIeH*5jvxb^)cG0l(u#s{&ta1FB|tCII(}dV4#(H%=4wO^dK|AqMf4^w-=?P zRlIT#va%64E;|v$)HZg4HOKD7oO!4Rj8m<vXMQ4>v18->tb;)uzd%w<9p{P*a@ahe zMyoLYL3w!~nX;pbsW^S4<GxX<K%59NZ$*DG)2Xp!tbxz)d91j4I#*>jyIQEFliIli zI=tb0M5MAv@Q{LJCmqPaN!vXgXD>8V?h2n{-=-N$9ly7}hV@RJ!xUWB;L5u<@!k7W z!6x>M%e}9EQ8>A3EmUTByW>M=2@qX0<*rwm6TC!=Y32MZYU=(w)3^ecfG3lj#RoYl zSV50%Wo|+~uDA0b*<Uu4d}-Od@cWxslMhd-Xg8I|#2&xx$P}qoe#$si1!4BJah+Rh zR=<BKo^$fSi#dU@_yK+9>7>k4Avez(4$EA$IJxlQ3XgzqvH9hE!?Va}jUZSd(q(pN zdQDWe$qg|37NE!{R#i?fKXaZb`7*w3c$c8INF{DqC|~77U9&4<SaL>qG)vwjBL$>D zm#^;0&hZjlD|}g?bSnpUGSq@()uIQMdyaSPz6rKj6ij9@NxWRj#fCMVZ;Vq~ZHFC~ zShv0th$z+IZklv5_e8Wwmsy(WipOP&O`H2RH~Q3dc7E+z2!V?IqWf`r4GHBY@OB)G zW^>{uVv!Z<`q4uYh3~3IZPOn-8<y43<Yl4ik-E#tcFE`hCfq)uGn+Y0?LD5$T3}>a z2id^N>a*$}&Soo8&gU~QW>6XTKGSA&j|sDYh&B?^3>Dfe0%y^El^J#AdlruNFMP+a zP-=`#+Tv)T4%2X&WKBtbuYz-;N6P+;vw<epfaOTEX;Sq(3IerV9b_bO;vwzyAqVu~ z_nVrAPUqzQY~g+XlK9G+{n28>l<N;)#?OxHCqp#YdTH<6xI&Xpz#jSpcR+ZcwrJKB z1>LUeigyFF9}1`49`_2;aHvOJE*F>Syk9HO?#_`TBh@o7`^l{e-A%~A&B;l)6%d}k zDK|0MyEb>n+wo>A^9K#SP5If)awppIUysk(dVHgH-;V$>IE$qB$|s061aC~jWc&P5 zoYWxG>?9%6#eA+Te@?1?{HCaSJX@mbExN&UNk0C(<bAbo`LqqaTfXZ;3*~!KMYVSn z3mtsrntXir{hpZmKp)~9y6D-jk*~Hsm<*?xvU!9t(21SLu(jbcOJyG{H1ci)y1U0^ zX_Vx=+SXU~hRlTjf1*81VgpX75NYFg?ps<n8sxqOdrmBO6VIt{1dl^^AG9cgQ`1Lf zSi&Az!x{ZsXtfxGFCpSv5J}2{AerdbS<lFE)OSe$^<kj&s7aZ^1TkzKwTk(R;&tih zKUX2$`Q~duzHu4x2?#RZ;P|aL?8zew!X`3dJL}MGfpX_bJc<~)03u6(lm159PVbl% z<uk<MD)|_AY??xkywRgn`7LaqezYpLmG04Z|5SJMkEAA0H3E3C%sa6CQ?rN(WDZDa z<Y|gCC9C+rcGiG2kxNAG*?P(I%j0;l^Ro<}-`w+aZH0sZ>BWyUWCT6w0FJ9P*dQw} z{sUwDRG?S|{E6sS)Dk#-K!cS*{TcPOPTXWuTdj)$*EgMSJO3bvUOK_52mp!;F7N|T zjt_)<g=$#=JOywHs_b_#34bLBCINr~JqAKLR^R5*T8Zi*aimuxb!LH$&sjv68Yqi- zqXE=CV+~+AG=fZ$C71}t0D|McQ<)S%W}oJ^<USF)w}NV`-FeH0mx^-Fw>6H^Y!q~( z$3}npL$3H50&{)>u{4I*0KPg1>4<VcZT&>;?I5~7`~>nQLpBK7<|G%nDEnh}7uI_q zcgKPLsy{1{3_09JV~qbvsrb*f%bXi_TQ1frJV}y#edYeNX3D(x_laxfEoZ@0cav)1 zEB_E{{=d6_7N$ES&3$R}x+a<7MVrr^*49r4)DvLTs&0Z&YX{jw8AK7-(Z~}DV1u}n zW!M%0u`z-O3rHX`GImUXuqT{B!sJh?$|wf{79*{{*ub~SlKZ48?RR<E`Bc<q5@K?Y z+=~i@Ztpl*KLi)K^hlQ!kV8)FEheh|1YrpwnZ9;r@4??h^4Fx!M};tKL=3y`tLEqB zRuFSA<%HXH==~ko;Q<N@yNhVmgf3n}LlD2}2xS1r>=`fA{VOUn`wY(3|CsTagpLET zE9C}OFTPONEH>y9Oj7=q{`>F%Xe<BSHOP_I9$*!GBtI|tnU?4*qZc0SAkN8p;=&=L z{y$mN@-}q;#57{!oXPTumwy_cbXnm~8UIu1D<2A4EWc>jQ(J_1$a9(WAFZlmbnJId z)8Ce-|HnJii>efG7n4mw`hyQcPg8ic<29zAXYO@Z82(dB#Ya<{{$&h4=5@`nIq{9V zGrT&+PWj}{>WFgPR}<EF1a@wkv`fDER07dv`UWuwHW!pO8APxA{f7B75Q~?o2yk5x zh5jN5=w7wL?7lF4mbvM^YKAys+XXlWV%Q+b9sWbKH1}-G?j>ATE&R|i@M5-wJ#`L~ z)M>jPk`&IDA?D-=1V#pz01S=WDflA(h5fVG-6yr>eMJDuD3j+TU+QkeNVVKcIGOsw z)#Pz5`BZQhY||G?4gFQ<2s?Njf^rX*Cvdj6C@JuVH&$9Y?Xk4*jT8;7i!)y1pS;$_ zb5-SbqExDeahBPw+bD^(0;l$ECtIZ(UsjBhV(q0_#&>;mw;Gmrp;_<A;jGLHWUE`u zvebs{YS&y6iHUueU#2HOKNKuX#UKkZbk1e&+wOm4@Wn1TL<Tw>$`M5--r!mi0>o$g z2TB%lsJL&>+#Vl)p`4y-crxr_yl~#*+RJbO7kh>pzpx<1-J1k;oFeu~6Tm1SkQPPt zlPraUhc<f#%)gg{FzW0vEN|VSE1&9mTW_oOEcGYZY0-|!9qAq$iRV>^yjUU2;w2hg zv4h7geC>?KlzFxAr@Y0_5Gh<8w6BA6P;r}<_wQ3p8b)m22g&>pL}tU0ex~Pd)!#Ur z2D@E|ha*UCT<dPjVe<9SCX^KuC7oKX{7mnTcKfBo%DrAv*)L4vHDqbsE1rH+z_fn$ z)EgCvY|Mi|t)>HPv|V&6^Jx2E>Ri8~=ERTK%F(<k!F*HyiWYAAH@FGP4x(W?_TA`3 zE!tK6)|*EB3NEZB+fL)zBEF@*z6*lk6*_4(VVadjq~b;$o-bw3wl`W4lN<95kz&e{ z!NUiLu8%NGLNpQ<ot{z|fgPmz*<Yh2^hj*|O-*92_}Mqk_8tAsB`xmfb04|Glzppq zpOYF|1cFC`PXm^|aG7PQVk69Jy5d^9^_7vpt2Q6UiPycnMdh0HS(22>xMKK3Cf=Ig z5zpuoJkIIkbe(=z9tT-d#eRk(oHkAo0@}01Guq4-TV5_e!m@>D1u|Ux*hajIn@19* zr(Jv)wIbcF_+4tEi+L8-h^Zn7quM1SfizLCtBWB)18X74<jBKNgZuGuzCuzv!K5j| zG|D?XmFhe4No<D%yrP`A63Z#@;!Nr(Q+q-%r1<sx@)s{B!_Ka34h8e8UK<)}dI+bk za(f@Im7=-0rktV1!Sg=|w6`Lthu%bX+%Fx`&o@XGnTqo-qlwIv=Z3m!R<fQmWHj(9 zHEthCF6Ky>R(3oH&#^n?BoF1#6^}}xd48f9ln`%yw^}E7M2B0h&E<}Jt=dogVxQL* z@s1wuVy+*}9*Yb6aLe<@BZtP9z0kDa2`JM)R8z+B;SsXGj)|jUh>Yc*#p|FEQ$>wj z^;1@xT~TN1-)F^j_IaxFC4Nx9=%^jOlzgK_(;u-mffKYM<lyQhr(6~$TD2KJ`B+2n z66sSiamCILU0vrkOaget7Z(d+;51S`CTZeKJnmZ+yPPEq!j&7C@Ek12gQpHu^~A!@ z5;!|#vd@pymBFJ~&6`>EVaM3w*DuAnx_ULFZm!g*@~UtNO-Bc2+x0L7E3;nd#Sw(Y zV^aK$xhCFa=3xhWX)5iD*GHZg3#p0AdkB{4Vrl~q<p$nudm!G9ydBQc2=Gr#<+)nI zOx3JZ(#33N@TFhghF^W^OPm7X?T57ejLw9DKve>yoM=SK-GQD9R3?1n`FOf^9u{@Y z>EOBJ2kE~0FX?6q<t9~5q}P|`G6D*+g(e==cJsj+qs@I{pl;B~y@k0f%q#K*!n8{L zh`_rB<qNpD@PhQdJ^vZ9k)Y}wahl%XuRV`XM!t}}$ezp_U3@5kXxAYRkr`v=bz_6& z=tF|pt8p_Nr1}^P=R;j)mk-K?Tod|p;-r~i?O1&!-0dGz@((oLWD6#Wby-B>(tb_g zMt1KL%oY$+oEZAf0C@NZWD7qk<0fi6P{q@)fRH%Ha+*_XnMXYlcU9%dODVJWs_zr; zJ+G!9J>;YhErymY%>LZkx+%5c*p+9JpokLD@Z@JU6J5qgxWRjCn=6aVlw@eG?jmay z0+Ek5&VHZRSl*N{e;HbO^L)gHu!0ocF!o0g_H?Nyo=2d0yoGyK9X=n&xj-4FL{m(N zb~SCC%83c&*pv-hdM%0UZnE%$^ap61>RaPtRlePtE_~O3uGf2=L$a0rbf6}|qlV~& zhY-b91RGdNd={YeX67wf!lv=REcjUP+77&To>_5E-AiY-EPEq(?ItO&4jt1XhNo|D zLen}<nINa$44q1gfrrrDR&}E57=#xq3nucyJ!+5=26sB9?Tzi-t!?lTs)TB=It+2> zXMy5*md@6k4a1U3y5M9Z#@YY==p*rUwxVQQw_JVJ+^5LaRC#x<8ntKHOoH|9T{j~d z+Euy=($mDIb?53b?R)z25m9`z)6NpstArT=Cqv5DO4DZ&%#@Ymc^G4}l$2H{4#v2h z1JomSx9xVm%)}czcY|dNxQUOd9L>e8qPiynDG003c63ClIVvVcd(=CiOukvV@L6dM zXOrt?r>W#Nch^NVe6LRpOibYOLv^}q(^Wyh6KW5>j_+RM#lj=$%T@Ayi?zQZKeDK% zX`}=3w6D3@(`%ki<F%*jwaOCYI=%VI<If3%T&A!+O&Pbn@oWOc%&Sb3x~eiR5y*{M z31;cRXkSJ+3gqS+`^3xLq0*a*F?w$i^3G43>NS?f0(i>_JCcmPlI;k_BAi1!@>W&F zdRD2+xXD!S;M=L6iTCccQq+Z9uQ=SR)2%hrq0jCUpIlUz2rj$UVSDY~*G`k<G0WS= zdv(+CnFCh>(~(ng@}6D#iFKpR!3y}}X`Jq-CF-SnPegWM9Bs-ByKW+jS$9e$r_^Gd z%DK(&`G1Q}F4ioR8_V*x4qenqE^XXIQFzG_<?%(6fudzjAt1|txQ-E1;SnTq=2zXm z_{L&wV?A8Lah+BJ?pmx3cX5%@Ym0mmk_VHq$O-k|iwvew$3?VT3)U&~Hc(4vSc&S> z7o#myUEIBcXgAB&8Ptm+3vZl^?{zHVr{|;Lsfr9f5j+kg;W=2ta;$M&EXo|U33qGo zYAM`bVBA7ezZ#M0bKbt+&Ax|E@PlH`d<sv$IX3s|;S<*QaqZZy#&SaYrxr%73^r&z z_T#A3;rHRX464LQ`}g5z-n_E>P#`m;8E$h<_}xVT4Nms0A8b=&kG;A4Sf${?ipc%@ zi#~pQ=}WHiYU?xAP0AY)c-<)9_EjVNJ+m)?I~*mxHwl_GZ5Yg9DO2)_hpmudnNGRA z;VC&&Bd4J-rvYo#Lnjq1G!${F*$L0M@Ff3@+J~Gl_#<SHR=c(EM?0H<>zPk#x<2D9 zK8V$)UA^u4UCqqU_$=olCyGxx!>n0L!P;?Ni_59{Ro44QN%8LAqDlIs`kiT4#Jp~N zpkcX-9>IU3Bbc*kVom9yMBJrbab&8%xbVp~0iziA7hTVGHK`t6%$-7|lFtB0@(8sv z19BQJp=j_hdh2Y5@DiDHuTkUrn6RV}giGpyhP*(!#$kozx2w&k?Vi73jV$KS(*r~Y zMo3dCC`GQ#sETvIGO;PNRL8@pP$xPwh4VG+h|8I91Rq#=Gw<vF<RV8$wDZ`l-iy?J z#&h-;R(>T%9~|WW0U-;qRXZl=4d`~|lc#^8tJ0r)sdKzY^58Jv7XMkUl2gI@FGsPX zrhlrzQmBHhBee+x?E@5oFeL&v>nPxq2DN~>x-#-%%MB%^&R0%`i@oNOll%N>-g7h> zSk+OKB|Ikp28p@*5M1aDHTLZZa7^^a|I>Ib4#Qo)*VH$P^L_5&*nf1j<Nn#~qDF-r zP4L6Q22!9PIaKI4ns~{4gLqIyBK=NaI4ABy4l*T^s|XWTsuUj3BLmiQ0Q^FJmjmNo z@^~3tkAUR2h;BfyUBuj+e6U>=yZW<=a1jN*GfheEgDpVF&+TB4?wn06aN@=+Nm4wK zPeb(HBEH@fJOWtNkG!@FW8S5duL{7BO!b>m$-}1{i#+hvFKA2TDNl|bow*NIykr#_ z^v-(DXXA8=?|%Sh7pD(}@nQBnX(j!OgDgI|2H$%4Jmi*DA04R;r+0eqNV9+50@JaN z<x{!~7NIReqgov5i?xgmv}fd6yKR9k=-=a10Y3@O<V1822ta6Lyz|d-s#-1$l;Bqw zI_Gy7SRObzow+@r5RERU=ML(Hfw}sHJQi?-u>iFy{$?+3MpLYS8ZL<Q<}`FXx-!Nu z?tD>0Cm+9-6#w1C;Yj->|D53S$3&Go`K#_m1f~}iGQ?9oo5Qr*U3mN3fL6+&osi9A z??IjGa3sb5fm|ugJQwIh$WvN07Ky`yoa!9OykhMX58~yeWB#;W=gI_N04}hDeUSNQ z>VAWZ8%+%A{fCmusJ939&KO_T_XOS7DVZrY?5*rY2wT8uY}4hCN$C_7f733a$>dJJ zt}JsxNr%$IE9PNwsabRtvor3WBTsa#A2VDRI-wa|Mye}7eAT2sBnXkGhM~*+lq4e4 zu>k_84kQjlOvh_h?K)%{6tWB4kjp&2(G+}9KC}t$M$l?+#KGx7z)SQ~m>eZqs*n7~ z)z@Z3qdrw!Kdeb{(Zmk<GQpo>HV?ocS0~8!`R8OZHMAa?aBxNiEZI{O5C5zQ5iI02 zwziO<W%Ky+_xBM$K6MA0NbX92#drgR9&AkJQje9*Z|u_|rUl3;x`(V_L&<#vN=^I% zJw7{a>Exd<Rma9bMXXWkF?H-&OS-|W%4~Y*atC}Z8M24d|GV4AS}uTf`#)u%R_k1E zcI|1W4-c%%+rPa0GXMC!rFWGsM;iEg%6Sh#;IASUpm#k%DZ&j5J?Xl+Y2;rNe^0|6 zoWS4pvQ!-~tx}|{2T8iGje`|^Z&zQ*JVvVhZ`vjB2<_sH0IbdaorZ33G9D}fPR2iu z`Bnt55}B$@hXG0ri6tW9wQn-p6DAjOzdT^4JhcAVtowIwOeJYRdWJN33ReLFXge~+ zf-t;eUpik2#V+XX0U_GKBi|L3d0DD7uu|NoVykj4TQ#6aRY7F%$jIg&?JK3(8?Yk( ztNwx6)Wdumhhk7Yz>mvAo$YM=JhO7B5!jf_)k!CF0Z9?^RNRyw-0nUdisT7fw1Vu8 z1MWpd2)Z#}PR}r9`O`ncY6Yh>#H0tT==hDLmp9m%jB|cj!N|`5(TA>8KXMnjbb}`m z-LdGM=>zKNawx3^Pm&9tLVnB>KUtB!Cy7@k(ua@OtMj{NFcmzz=>Lbh_l#?5+1rM( zq99VFgP<bPK`A0NTM!Tsklu-abm<_SC`xbAl`29g(xi7HT|nu*lhA8I4J2eg<Jsrl zy3c){=iB??{lr?~m&~l0Su@waUDr<aE=}&=bIT*pex<JAZcd_Hv%DFSHO0X>0{Kd8 z^8fz07v?U)zJUVLF<OFI-REUVQG4m6Jf<QgS`cR_K9(OyjS{r;_%)VKi9i3RAH<0u z=_@cw;4@ewFb<W-=qcp2i-rKAql(3H@xajPhR7}7an#GpY+a1sK9XU)LTenF@xrI! zm45utscQ?8&g&HAqHT@mxkE2168ZxWAFUCKJff#Q?cgv{G`T7v(!S_5%ETI2U6Bh| z`?7IUJ?<0hu$z82g*ICQv1yj$v<bEkSgb{1FO~1M7%1js!|4hwXyFX(oE3u>tn|$& z0Wwd+)_(uqBu1UcJAnm?>^p&u!mIZCMP?nw0goB=%)E+j%PuQ3$8Z@hhO)gAn_Bg! z!p5HvZw~p*+u`arGFbI(rP&+MIn_d!?YDl+!o6Hg9eL^<?{8eGDpjPAp_U8TH4p7% z*O(rkohY>Tvf`C_E^s+kuzpzRCYzM}lEt^}Z1;<e-UJ@!ARh8dD$N~K8g&5%8_y?a zZ1G$0%>+ag)~=l(wD4pw-6m1osa<oa(b2LoJN`vdMRIw*hrf;LZiYm}A~KUccQYR~ z7nyOD4PzC6SH`68ef1~D5QhyJ*T8}%MT#>^OnOfqdAqmgHw=Fb=$*M;S@nTM!iM8r z{^{a5ZXbbgMukmt3<uKaR_B6Ad6uW(HtE!syPHMSluq5)_Jwca1y9PaxjN$x?kLV2 zy*M*6A~SX_2i92*8*7_8x%au<Yq&uPS@!@Qnx!pc6qCE%F6YuAS!&N?qG;2{)3usn za~t7+EP-2vPfK;wOy4&&N#oY@PRQ$^%-ybYK8)8$UOq)F#?@yC*~?WOn<bRcVNodQ z=y@{7dGc4%eAAxwU%{ScmhvzfdHr?N-lOEHr`5?9SS=G8u=7EaRFo!{mMos{&R?~l zf!PRzLn?H)_zG;qqr<@laB*^CTKPhC<USKeBdzyxlD%Y7Vq)24hQ1FMR^m6D$tRXt zRf3)(@2VU2w9Vd*M@bui$h3zRiq%_*t9zhAt8u(OyKvAaYi|=aXx`3itT)^`0uQP% zGRRaCo*!#;oGF=UP3Wrm{Pe9urrT+%m^XBi74;`k$6RDOsmlEpRuY@!gTSvzGMEch zADplEruN}#ziS8&+Ee{8*w+0tNVmDURUiY;j9x@sXmB(|sX$u2FE*^*cB-h`)a=T$ zp$+1C6r*Qc5mj1}B0NY#!KQS_`SyoavN~>b6DLOgs$@kiwU-5x%PLBgcBEvME4RUs zU#E7--{$mogF#6^)HTZRw`-q0frdG?8C-#CwHq$lb;&?-|K@{k=JJTtEouEOX`xoa z+0o}%B{#K5S{($1q<$e5?yHEru7lFHXW%{H9OPU`ZZYI>=H+92$hf1<l={tuR+fIz zp9z2S^z*)MI<5^?v6Y?#^Ya0DkuPk$1p*UKc29aouaPt_&wblqN-(dpjMBB#G9PG5 zZ<X_yZ?HtAUS;Ud)kq24u~H&)m8cbAa>>23!*e^OymGKQj+_bGl&BxkteF}3v|UU4 zPC8@!d~$|(pg0YiqzJcto~vfA{N0SQPs?y_ttA$iCf3R--&ZXKX@O|tgDS_0Z4Ess zAK34C{75HAJNb}-xq#uxZoY5Ks}<M68d7~IwJ#ac*aM}Sgpp_-tvaf@f2-Zmt&ei! zNw_bcM}_>O>PpJ;+k-vMl<qKYm)q(sxBZH!;V4$dUg!8+GT}ky>VqX`M`QPqM&s=r zZAmBOrlsJ62!GbgCgYw9$(~BWsrjuFyR~ZMj3Pz|52mi+k(r7mF3|*YRCH9SXCg{r z1kbhbL$)<;UA^aG7Dp&Nj4(U-DB=gHOd^ZcGQ*WFQpbocs`h1jm+jey$hlVtrluRd z;xi~NNhViRq^ov3Hdjxvgsm#*$2@HapN@!*D@{>j0Ix<g-{gpi%r0j<4o)+m*3l&T zX*gfpIToix>*(J*>ZhS7ac4A09~RkQ7iZc3eYaCJ=$44h=t@AsjFPPqU%sl+kDlbG ziZYrJmdK@-1Xt`F?mD&)dK!<{MH?<q`_m9+F#>OM&{-y)uX?EM;9c&fo<%Fo*Y3tj z6o|&(42_BW-bOzu?~V66&4QW1qB6c5MQ8$VeMcJiz}VC1Eph4ktnNLVldubFcV*c= z-N#M@)QK15bB}Y~b^vikcmL<GW@iXMEw2C_fj={#*@Cp}gfy{YL|QjsQzwb=%nkMF zR<jsc5#U4(5q214STZ~RI*Wp=D^$Ipt)RnKuI)J9B08yJZpqJZw|)+hkINmvbwIAU z_6ldk>4vwPe(rY2hJT;o_xFy?@10U#&hHbY%U%+bzwbZ-NgdXPZWXZ+0-nO=niYN> z)g?~=#)?2(hkdRBTC%{k>smSBnH_2JfKC}=eXrb+0zc&%VZ|z|H#c5~I6Y?t4t~p5 zJUagn;nRZs!iUya+gU&E(_(kd<V)Y>WV`Q2EIP;Sf4rLff5Dz~p@_u`&OcM?R%L3| zH$)0Hq-2$odpp*}ES&BuFr8KVPJV99XytdTKr-?>RfZ<wSK}(C@O7P|{%JLH?%OT} z5@i(B=VDceUJC#BNB>BweV~h{nERX2g8W~M7O}u*|2Izc^8l=$5<?=Fa!yMk5;cHh zX50!%mGg90X?&jK_^KozEH$ad=EK&;uhT<OB^ir-Z}JKtzlJLM7v6!IxTd`X2<dM@ z?x#ZsQqrR>Om->bv5%43ZXQJW=ib@=nx#Kz3*KR%_~0C1Y6S4W{{}!beH(|m-cbeY zOM&G-t_4orwo7>Ml$>q)=|vS9tKZ<<z-f2^Sa|ngxI^o6Fd*7M5=UqvCj?ZM>NPPW z^WACQIuN6sm49EB-D$%{WR;PLFOdBW?Ogc$cap9F;uq>GYXEVtYwmAw0;g;}e9K;t z`_m|f&VGW{nLc%$-xdPvuR(YvfaM^_l)-)~5cDV3g)RFEouAakO|Lr(gL1Cmc>D8< z%&z;81P9pPrUFsr?@S8$h+i|JJtkl;a-G{wf;2u^m$dA`6tC0Q)H9o8Ky&*4iZ0I& zfJic*9SGxd{WSBpd7_6Ze#lQf4Om8YXhn%7q)l8R`52&hSe)|P^PeBhz^u{zgti)5 zFaN%Ldd3JE0#urvfqlkPQ7iyRCmBHav^f6EzhtJ%TYv^O^kj9e7wBRCy5=PMEgQE^ z>9;)H)pI`uugT`lfz;LZPFy(thnst^Co4gkA2JPHw#)i>whV6y77ZA5W8ITcxCOSA z@JBA8uH@k3)t@brHeCny%m@M`-}aAL8Cm_N8PR{nWDcy}?mvm*V+ehSLqj}x`rL2> z49Ovg>)z4DXGb6U0h4BKLG4u1VC+L0>|4e)z`eQhCsB6U8rY<~Q-Mu_BWUR2WPvZv z72`-qci3pPn?}s%&h5q`CRqtR8R4+~Jr5HmqXq%M4KPYdXc+oQYpMPJBasO2q)kzv zy;OvT5xSFtfkCz82<=yESN6N5q9)rkB3$k?>ECGOXU}~(Z7brkD{oYc3`349$q)Ky zyXW0^MK7=&AD)8zmc@f6uzyTw08cR?wP@oA)I0@9vwH5Tk*{S?35QFmcC*s1Q7L5E zQgrvP^A0JJeqH9!`NK5Pyyh;O19bt7Y4z0>8sCTAYrU%6noAD%9R}-c?jS2w`;0S; zqgNo5cNzTck)y-{-?_WfS(>g*Xvd3*jc~um-{#KSt7Nf}(TMO!m|Tp2_s})tMaO(? zFfgQAXwzk1ic#X=24S}@zJu!u?S$(=${~eW4XH(Gi5Ws<=;dX-(B!+NQ;iMs^yznx zSW>cmA7Jg!Q*!8?=s$_9rIa8Hc(T&uy+@#a$ye4jPo(5+Wr(|e#f00Inkp+sz)n8N zyE(6dqVsZ<-jb!cy>M!0dy(vXR4|4c+4*#I$Cuc{&NNF8FBGRV1h23E(imm0@`x5~ z*djebo^YG8i$2sm=1!<mmgF;UNBlKMr0y03<FUYs=O*0%?1GkTB^%Y=ZK6pUlXGYM zir49`(c4cld`P}y)0xE9QSzEWEX)-;-k_#QX-KYcFY~IBT|zCyeWHC&M4PAECNI~@ zf}Op`a%VsFjAY+!q<Dk=t8Dc66?R^ZimWiLERBYZ!Q2Z5>Gz%CSNs$;<GG$X<ttHV z=aQS!=+M}mh~lqJEkHJVvhg=C(Vd{|+4G1%VXOoVIpa%*f}LNNncTH!loI;GqAHS- zg-@pEN3isx7`3y7QO#QAB32vF%FZn&l;f0IOF3Q?`_fmpc-4fl0!JL;PJTr#XVQ2= z<z9JxozLTK_Sn_VWoREEU^kJ1nvyffLm66jv}uYVo$oEp^L>crL8m;%7A%mH*->H5 zju!et-Pg?PUl(fg@fExERetByHet#TTyk*vV<;h$T%?t<=rduOmBiN&=Woqgam!P* zBiVj7a^BESLI-PK;_10Y;4G~X$fp(@pB6tKiW)9rr#enIC`3ryRM5s7o)c$C@Q%x3 zFta%D^flz@qL)u=;?wZ(ovtpg0-l@-D^Fj|o>I^6y*!jbt$rG|3Gxe@!}sFFY{v?7 zIk@C0Jfp2H%Y>z<7i@_klT>g@o}!1|*a;l5XUbtAMq!K01LJ0W!aXZjpyq<MIWd=f zT%I}jY_e)MMG-|cIn5?6o^|Zpt(QDkiP#ba+41Kq$}^O(G$=mN4o0%}u+^#zl9I}? z;Y!Dgwp-@aO0_|vH8@!tL2*M_kpjUAn01u0M=QNy@1I1D0uzRZ;in~%*I>9Ocq6RZ zLSLYPb^~Q=(dr4=_t26JT9*`dEkwhm0&n{r-mSEoiPVvllriw<vZ@$`%`DtqLI=on zI&gd?e$-l@;uw10;7Q*+gc+OkR6N3j?@KJGUskhO?x?D&dwW;%-Fw=59*!^cKPGDl z_L-#9U5Hsgj~jT_?Y3#Hq@mGE2@g!}4)n5Y<yS00tgcfJDdzo<o~}z*jQ-)5sBgHT zQJmj3Xsd-r$A8vQH5pJiN=!!JL<FohIT+s+aT2zToU!G3tI$$NkR%Q6hJT+l2Lc<3 z&S*Kj)d>Zg%^Q3VX%{L&WR0Sg+c?Iv$Mx3j!?oM7J-G3KWR-INjwC3B|1IB}BhrjH zujh-{^oA=Nm9?;N$NY-w>N$*<zGG3bZ(@*0BN_FVsmpM4=78Bh7@B&`9L+EnGe5$b zMcf+|+6M41h7QPqa$gJS&c*eU#4TNUn+Aly=2TjCLx<5Wtz005Sb}a}a1VjclSy{C zf#c&EtQ^t;rJlsDw1{(iLYrqf`rR+{(Kho%T<f&+kPwn{HLV*I;?;e=E%WVFk9g3b z*q=m|&KmhlKH^at+EP2-niVPeee4!0GnJM}67hynad?PWR&<G~UTQ}a<J$tA=r8TN zz0`0H#)O+X+0G(BZ=PFyS(~j#RFSZoz+Hh-m^=nzDGS$`T45Iv3sTq*^BELa6G#YU zRVGKMFB_6{T&KIm!j)`fsMSs9Y|cZ0?s_vifAcE}UbppNWWF3AuRMdn^t9AH%?DbF zJ}fAlS%Z;pXAjK_k}9W3cTZk_A?Iw_F;kpf$xWVg@mwdNic9sl;U-$G6UGFwj9cLI zK~{$z&_Rjd)q#>?a9h%x)sy+EFuf_|xMhVH$#3{jeSE&b9R<K@n>0M7f)m-0rXG>B zM;BE>$WG(Fj+$^{m|2(;_%tT_JI1PX#$q1cn35>@z+Isqqr)t5tnpcGpJ5boA-u;` z(qCCgFKpOKLoipdlAY6z(F8x7$sL-PuQI6!XUgXxJVc68s~5Bz$!R<Yd%tPIUFpjQ zGgs2SyKkzIePd0-v#z_CMdW$DeEbqn|Ir9&X$i<xZ_7nR6JupNAQd1pp^4Gf;O#6M z2>F@9iVSCqin7+jbLO(uyTZMm)h3d9am;qG-In_p?mxjS*R@eSN8O;0S>OB0=;i@V zzBDSIdzgz-tQv!f?ysqk%7$W@HFnmw$s|-u=%YixVpo)`*`gO{;`9_aR6uW+fZQvG zIHX~|{id&$Rcwb&<4{gRjUA%0%ZsnQMXAsAUZgYCj_myr&M3NmUvd;Z!lLBD)M~mQ zmbiEVW@FdK5h5v<smzjV@9ZkkQNBKwM1Jf0=iLWi-34Dze!6*yO)V?@&`p3|JW4mG zHpOFU$sXdR=u*IbKGxVMs|RL9u4E(>GoM60q#vHrY4PCpTveNVF_rLjBg0%VSsMDG zh}GfTfaaEQ%hS37ZH<<0e|Pj;dnc+Ss)@&!Y)Dcl4=*_+sSd&4HYmJ!*rzs@$WdBa znLe|5%gXxEZi{82*SS#hnrEwI-(AwD<^>`Nj7FYGD%i`YMj=IvN4T&=DSZ8~%jP`e zgD>6ejs4XZJ`_`n=U2<=eTt{$FQ8U8!Vsj(KmtcgxLQ~`5#x3OvWTPo-8!ukws^|0 zqO!hfxRO4yDE5bMtU`q(qubV@Me?MWy-dzGt66JXFtofC8H`hSD7vpLWK&Y^{u|m) zB0D7G3XXSbeecxO4l_?}`gm$Az{7j^86~XrUNM<JPRCI6IM;A&apO1|?CCsvNw`F% zp3ftXv*R4NOa?1wk1vV_m-$Lv>7-*=Xe!Yi?{Dc&GZ_53O#iq)@`c}%M`?c&P2NSj z+jI*C^IEHx=Zd`1$ls&e^0UAgJ_Pg`TgHX<&(JU7^HZn%LmE-rbmB?xhNRp7&`0jF zpSC7)_hJ^E^vJt2n1Ewip7jLS+vSX>;iuINDqg6*3CFf0@4gWCdI`G{(gsG?t{kSK z*zxSBXC8I&O@CaR>0OQ|?MSUJ^YUPgN(UhCT?FKy6_6K-;E#||Qs#R~{LV_*W+)zo z1YB`fpRwiUbkTO+Zr*|N5zFOXXNF#N!W64j*ryrBFK)x!T$=H5X_l1<N@Xs2L+X(a zx`jWcn*QK5;QWNRE8RAS7MQC&;W#J`s@*wzip%%}Gg!4ID$HO2{bq)ZxfA3o3phGp zyTq&qGq9MCS9N}3cLF`=(-vX`v471t(s}mxJ0hBkZ~*(KqEC)sr{{+ce!uG{CIk7w zXP{XS^rJtC8gcrtiC9ly06Z)!>9sutEe3Faq~{*O_qcy0J^Ka&6QN7M5U+*U-@F<j zfJy4xwQ3tym-F-Lb!Pl6rFq240Q9GE?9>;sCt~o5WK$9Zg>KM8=AkE)#nScUq_A%n z$+2{Vx7O!mK=-ejgF|xnS~#Jxlkj#V(op*62>+e!OvLjMEr4%?eT5v_u5A3e2K;)U zr11Z1m4=zgZvmrsjbH`WPxA@SVS58G@de<8`5)@Mk5_TuqY2&uD@HGyqTIs+DBeAv zf2~ze*?*bPQME$QCm}-OYauHs{#srxu)h2F0z}t=@bi;oq8{{z%UPT*XJ)5ai)_4r zHQy(P-$(%Z96>3B+9Hd7V!vetKzl~FSM1U8v2pmq#f7Ex)T2W2HQ%d`%QJ`x2GL7@ zFwZ4%;P)K6qxsd2m*)~Zj-_)VGBp2SUI}=pxJ??FWp;pSbd&z8)9sk9JA-o^1Ow4s znjgP@y>O29-N`*IF=<=0*g>%>kW23<@5Jwd<YNYZql~>D2yV%LbzggK@g!N$Pld?2 ziABNKa=MJ--0tH;k@0``e7z*(vN&I_8or$Hsiux-r{No@eE39g-)2QW`9J}9;y?h+ z>MJv>%MqOmJBctD>lWDtDaXptV@1R!FcU52T3AoKD@sJc=^Z2eKYVpVgj)w-5nhmr z>;oaK!=Rhw_#^>ZU~}gEnDMmw>)D$Cnhc1G`;&;A7K`h{kCxED)@IimG&zRHIQ~m? z%j(Qh7f`gE+AZFmeME7CUwVFLO9RZu-!ZQew{P3{zk2WXKhyI1(<}asZ(D^%Wtlg+ zo&Naz?~&PZ6O@m(e*>7(<P5;9p85LkDK123UjEck?BpRzykX!aol^^;1Me<Cq0`W% zKd$S3V8!o4d!q#*$E%1mC*h|T=OQ1*9@0Ln@sd)I`eAnb*E)ftAKvPC!Fp_edcpqZ zdYS+CJk-y>Gf$kanMyEe@E((kTel<ayq)6nA_L_J^5q@>T8j#QHBrOJd9DECMP-e9 zx-IR37TdH-*j@aSDBb=TFdJTGtZfFIdwlqIcYW!cSHS&m`fb{Oa*ntQnCR@vt*3}} zc3{3*wUeK-^%qa?9#b8uWKuWvx<0)D-`HJqRsBR-GYY9_W%?GntjOT5Qn*@}GAvfo zQZoJx$l$UDGXF{RL#ZFJzi`1HFd_V`tVV3i3Y?NCp`9m+d2aW98OMt>!X;{EjG>5s z1*2|bkJ@U3iJjeq3a^-QkNeU|(mdvVx2%U}PkCFBkpB5p!;k!4_`GOH(>44P2o2bL zx8w&q=JgE?*9}-2y@cO+Mw)Cd+l@8U@bGrI;>OdNN@mOAJ!gfOh@`luTKt&@rO77N z)2}7_F(HqF@Ulog+1B(s<!}9>4hM0@O@Nz!XI${x;gZ8sD(c3HDfrtedS#celNXMW z(|+%jsEQ2u)vFr9cFUYA(oUBwcYgTH_9?UD1K(nX+OF`6Zp0R-7TIWO<%-9nM0H}r zqsu?Tw@2P+=6}!0Ui_@YSHszHA5V;lJ`5jlyKdgn#E4Bzzf^_k3)}I1h_bhOR7L1- ztZ0lKoh3?qcAE74A$zKx85+HtsBoo}cQpMXmUKaFa;h210GN%Ukr&gz=|$#ghEf}G zG<>QxCc?0yqW0Yh-5qm7-{Hk`ZPvQ>^2|5q89Rm`s0qXd((#mj#H_(cG>ln0u*HXj z>g|pB`C*%OW04*&sVVic$eB+G$hdk~J_a)A(Qa}bX*9?8btF5kz~D_jw-Ve+USvDp z#~?~mYuKiRgwlqc#jUYCL3e$w3bGZ0u|p<pt{_WZ&s{9qa`%&Mqiwk^&_>{UKA1bG zmbzOA=*Y>YbqfRShdGtqUx+!p5{>ikH{rn!;fz<k{TnfV5+QG^Z%8wY6^g(}J(XK0 zJykA}<~gwKS<HUtr<HYx<?a%gR7%Njxis(vDyMp`t(dKc3mz27*>!)oG1Vw8R!OIE zSSwa>7Y@hOV`=;oS@^XIw(^IwRI{9162wh<HJ)nIu`jUqT=tP)&fj&NkXPxzShX9o zF7&mlO~kd$kyVlhj^6cL-(~WXP{uH=3r!ms8@BWEo&?9;bKI=|khI0t^QPC@<8$~2 z;_r<duK{h7C%Mi5Ue^Y-W%V=-FY0K8f{;TEN)BJb^As50<mn@!*u-yx3<h#h_oJS* zy4i8;*rj}`gCjfXl~Qun<=U$@QQs>Sg=<sFjx-ew`n2tMd}k%r$dIZMoay@9@d*rj z#y<4QsDL+wTj|rK@h0e0^9Plja)puCw6Pfrkk{(?JLsIikCP_j*@=ma$?F=Xafwk! zjuWNS1k+iw)>mFsaUc}ksupCzj#g+jL|oRl6Q@n$FOb|_pH#*=+16R0x<Y1hsT9wT zu{>9*kFSeKgJ(~gsLqCsU~Aip>x&zc^NwO8Yb)zCbeCeo?c0?El9G+8G&4j)S?N8~ z<3DR>$&xcxI<xBMs}E=<C?zc$br+;koAdNCe+hq^n##`N#eo7wuk;nXH&z90hFVw& zZt$6Z<IbNx%6k(1)}h3*raJNpZ9d<0(rYIBnn;<`cWuGkY|gQSlsr)I;ZuUuU@NiH zu`(7<sDK0R1UH=Z$biA4Ao&=}<OkpPS~zs0w=Q10_3cJTP8!V&v}0DR4N0Tlofui~ z!wD}=v~ehcr|nB%SfsEqh9ddzhl-REY(~>`xjnt_zRahW(GttL>R3?cwxBYwycmD; zQkS9(b0PLMIiB5wz5hVvcBj2Xu4m){*Ndj!(xSS?gheuDQr2z?sTS&J5=vRl2bZ$a z(8MismpnyLvw@gc*j1Y`TJOY4vc5Kz3tQ*keGeB)R^)rL_;@#ZrjIEERb#$FSZWIu zRhDyA?vNHqq+F<-|A^|!=G&gBcbu8==I=~-iwTeT;?$m}#614lDOWoi)km+Bcymvl zDpIU2A$whG<!xNDhN2X-8&NU0sgBu0&IMKeNpu#=icAO{aM-d6mMh0x{J6k}U(L~v z`d0Kf&_q5=rJ%NBkWujx$RUWHtBT$X#jG4EU`})25=1;j3IjKV?ni%~e8N#Sj0)3{ zk7dwZk1%(N{nW$Yrm~R%1g^y)^9>ml(3T?QuLg9R%~_tWOt5vGZKEf%B~~`UD)*-i zjO0TltQM2iDzXYa`IaKLDkSAqU$g>Qwg^{70akkH$9epZcPF`SSG`>Gn5jClIv{@w zIB3<V8y=#jX;t3$!wufNwIOV$glEYoh|n7t4OTwT_bIP)Ni7^+zYorf{|cMdAT?Kg znu$8b*gK}*c6c5X{YmuKIckbsjiaej!~81~P-5q=4=u25p~A27JXobXnGZ#}M-c&C zjOFuyt`+FO6FvXypw0XDk*EucTetpsig#iyuDjPT#J?ha9z*CVuK(*u)xtkfJEZA^ zv>;9>itoSrpB7~E>aL5=6Q6(2O2m4o;&kwPJn89qlfMv@+JC?^;=hm!0-TETp}m0! zJKhJV!`qlcFL0)HH*s_wh#Wxi6k{No6bL@y!vJqE;75OlLL9Siz`~LUX|D$Y34+Ij zC&$YFao+Q6^t#NJMNL+AU3x53b&2Ibw<nI^RlQ`~^iJ(ir5dvPGe_@V5b@uAsN1<B zm=k=qp2*+fGH}z5Mycf&%eKRISyEPk=={g4)&J1|=Q*p6S6%s!o;t8vF-O5d3t0c% z03<+>QR_Wq_g{kIzqe40r?>*M<-fmTDb#sX@DV)RYgCz%!6Gn55?_h>{%@oup20wQ zC-(JK)M4PfE1u5?@z-co;;9~wJO_{^$rVIi_}m!)Xn8>X*T`CX8taRUgDE?=7(-|- zMsN&|kW<H<zH#n*4uTn@ulSGu!q=;NYykd*ACH}rBYJs~m1UE}U3~fe&MR`<otlil zeoAlP9|4}NT>yEVJYbk3fm1if74_kyzc2gG{FX8oUOe^?*eoK|r!LfI9DbTKYVE+J zVQ@TIu1qrcjr5v`=QpLaVuw2DIS{T%1v+WNFm9r$pPJX?zssL(WCK}nZ$pq-Bu|j3 zts~<3C3MCE+%Lc!yBUppJ~#MEybiFGZ~?lPKdK=IeJ5eajS8SV{@MYyk#RuN4gxqk zzzGUAjrbHoFYM6xC*4bKff73Gzon$5fc|{Tp!`PwCoSWDE0CFt0Bp_)ely(nXY^+b zS#l~dqZ{^Lakr@vO())0k#J0Kp9Q4EfLw+O)&xuQ$&vkO#BI6#PubmiF$kR8@Nqmr za*q(vba{e&LPwBKICiXSXp|HV<_2sH2R~p5M3(A6=z9>$Mv$}wL9@Ajof)&=Zoqc~ zQ5o2ys-LRh?}{c{FnxHRDOl6ox2MEnKTBe(-#`}mVH@GFd&b%>O;^C&)q<b-iH5b# ztU*hY@ag0&(Ks#xIzsA=l2vk`34opgwInN;v35J0@^uc}In4^fP@PQ2pqE>b+^yXa z^|Zy9?y1i=raSzy#3o@Geg7%gwY?KvkwI*05R~MM{Bcfs7+yYBQ7fEcZ`RF}r_wqt zEb!ivjJdWtap7gzmowo+BtZ-o@3J%_1+gOtp2VukEvw4?`kkWc@^OL<Mkz;Eq3ttG zxmYi~^)oB+;#5=asQ7#DZL}gq)bo54o0Wv8la(9<GF$Kx*drii)I<_Ik7$7gV)WM- z5y9Ijs<oK*PYIO+yYIYoDe!BODU-;%L?0x}9hZ|}6}LdvmIO}J*xK^C<KZ+mp$Lm; z74M5YP@m_#gOUGu!vDeNLi<Qz|BT_|o=YE=aI)?EGe0W68M@Y}64Wl4T!$KC@@-yJ zWM)k?R^^^2b3!YhX-Isem!+GiOVa+xHgNg;XP#?e@OeJn!&lgYc^IXCJM?@-##udU zow}fU@<>TdWRa>}%06BBv=Lu>T43S3F30d%i(L+z4+(5RI(kbpBrv^|58;VaPA%~B z#};C)5^zVaT(|hzRE@Ibk)qV-PYX*2saG8}A|E_+8p(gQVo*__mEip)?SeXz?LkMp zbH(iq&6duIes?>CNeu_?^4NVp(gj2?fgXPw8;q$^o2=JAP2Khtz=-MtJ{V*m45Bnz zi29<&&rnfNHee@h=+|f#M!~*!)9>xKNa%g*477SiID!!}pUJ|2&A>n&R-s$0PoA8J z2KoAAT8m~q9(x|8BLCPic6Oc1vXUIWPKAiMnJ~fhok*gU5!bo-2FE`>X?L>H-WLHQ z;*}OunTK3AS}mKlzIGR=UfXZ-IV=y81#a+qsP4%+lx7P_hLz_{+!VB5Ls&zxoNAjN z(0hk?th2{L<I9~kL2DEGku82n_64%5hLM`e>7!%nn)Xsr!?E2mvs#>SyuRNfUbeA3 z!d_)6l1aF%9z?5GH`J;x^890C+VP9{C4N7n1Z9pxn!>q#3tx95camDIFG6sc+{#bu zdo?cd5!_?BoF>U>;@YPXmT>O)$;0$T)6JnIO`IyBujy*zX>6rhgm*@Jt*>34t#@&# z&1oszPKCXolfTr|O8hpa)+<C-lBxQ2WypBp$H<+@7AdAf>C<<37`n4FoiBZ3AvmN# z$ZMgG*ef|C!*CE(;aLR=ueSF@R~r_)Qtn;(@^Ny#zimhknL#a0fp@|7Ei@_{VfAtM z*I;KFE|l1LyNtgbOBXwcRM;Xl{}kTi<CZu{DqmAO<Zy-d-8Z_P+89Ukq_dBkXsmzc z;I<1~_UwCjnqPryR5%PpI|hl|8N>6TrW8pY`q|qZzF#TdbKv(q*nRSl9VaXGopwVY z@k_QcgGQk4t52B9na7%+S2&yHHFUM&&4$@~$SsjWvEJO_YJOP>W-j>f%WpfLKaJuc zT5smmICQga(TH1e&Zk`y6%SRI95_tHqrvD6kEp60wqY_teSL~&0hvG<@#YAIPNnp9 z;ce_|RFRboBXDAet4L1T-lyuxn(4Wi>3K8hxvaXLskPa)Jg)_feDej!n<hq2=}S#) z{*#O^3ktDiJKtVn9K(2Xhuu7pHL(vF0xaaKO5ZlNa)rrNQ!dF5W?IA*jx>>PATCOu zUj@q6C6OK{iAl(vGjGTIscerzR@wtM7e()_J@p+jH0d4l>8j#2Fpj`X*UujZmE$z5 z2^X-?1;lF;4oo%v#$-{ls)(_IK1SHu{hA}UW7s4<BvB>$7H>J%*#-QN{fZ&?OyB;o z-wPe9SU~7281WgJuv;sh8b)jD+n18yBC=hqKtsdi(k0MW&P&S^Rik|7-2(Sut46L) z_C42p9Z!Sah%7~gbj{^RTj3>=(!6+XjfyX`gTkNHD+Ty5!n2gv#%ya3R<v4(2rD^u z<55*?kM?MVvV<Z&jfLvOMb?YATIO;D!ZOUqJ!Ubb`>hfs{Tr2j0;6Y12aK$VQLhW* zDqk_^PUMzBW^=#JXIk#Lrc%9t74_^BkBh>}x`Bf>vdWAPY#zP#NPdJM##5zp4{rj7 z6@7oYjjA!eVo%@>mmj6|k+SXBP(9{f8CtZe8u?J{Kj;yN(`0Wf<IQJ{Nmpwjuw#KH zLKuwMn0++Ec9yMa%neF6=}F1IQa0!?DI|3eJM-o=HL2;zlnG3PijCiQu)eP{s7EM5 zURx=VJ6r5nTYOMSJuXgl_ieltzh1TU<96I*xvqS9<z#5&3Ij)|HY(cdf?kK0Oa6;T zU$z@<#QO^v3Z-wFVkpwMHQR7XPg{CHsD_0jp*K5IqeRXNr@S^t20$O#wfV-KuUiIC zrd1ZYVYiG+lWQJ8BHeqKj?8+4Q*`Neu<xYn9gl8`0LtR;VLd(_(96;sGuTf%$ZFuW zrLdX3S2e)9we730AR(o?qB^koDR!D2X~>j<;NhXBZ0K^*AkAZ+;&tBEDPqdFM)=`< zSXRWImJ}k%;JQ$dMzz-_9u%HGXGiKU@*qOoX*kEKCT-E{33~G5UR+lcQqbJ<y;C~l zh_3{O+z?aUvNOpz)<%0sVKX)v6-gdu8fL7fIg=~52NLxw=ya;i_NwtEY>z6=%EyZM zgrsckrm}NAb<R|5p-_Z4*Y57|Oc=Z5ZG8WPM14=O=gFIAE@w?x!ZvgYH0yR*qNO{p zF%I9OarPY7?#NYN$lT)6&ecpCiMl16E4yA=qCkO(iujoCcXsvx*sX9-Iy^gO<?F_b z?n3sVe9JaYH?k<FaU@oBiZ3C%g$`ozZqew&))C?ZNp<4jH%W<((JIy}zNUbD97e*= zhnHATHrB=6+0#Jt=R49=E@$#pC612i2o_ZYOdHF2EqN7ChXu@v#mnzLh6-t712L=% zjv;))(Qg^M6&9e^)(qq`kxt2)CWcsAq+Dgx+Q)PoS|-k{(sa`ITiG~`mKb8|TUE~t z`(ZY)*C+l3@YxM--Eg-lJM!SeLl)jKx2-?kZ?oLF+i?=mTe{_C?h~cqF(bJ0EN0*} zdc8wTN18&h&Q<Y2d)KU8(yViw`eEd5!CZnUU7=Y_dmPXJOSDpB*KK*Wfz#K>nenc$ z5H--on9QcGa62`8amtk&%H`#0lW}#@`h1%J;9fx78tWD5YyLgSb6@)|+Hv#_`m@f3 z`$&mpY;I8tuFq;6aV^sbDqj4w+sd`~e9HCSbhwL&TF1_L07dUZPqtzEl+dD#3ZT!7 zojdfw#uVg+Y8t0#fVdBz+315U%WxcLVN$uu?XsyiEYf|sQ-wBn=EN$g=G-sBZsS2N z(v1n&20(cIa{f%nI=I^1R?R?N^*rSd)f`@~^^I<Zd~7}<g(*`fIg#QId~->IGr5$g z7rK|kE4jP1&8E2(yVc@6+u6@Af68JU;m{CBvJB%a>Arl|*PZZr>U4#W&^spgTPYgJ z7#fNX%plaTF7w=~!~^&5O)CH|iI2mG)~x~F%|tpLpD}{f{WK=U>jkdCzLB6#0h;a) zbgm%MI?=@k@&R%fKmqym_nSYi{{Va}7yNVqlotUhXgE{YM7S?-*Y>}#TT(hHAzZQ} zAP!qVV2c(DQ1r*~v2V_E_}BwPyE35I___-I!{GZT(H&ndIcnXp)D_3yC_l9;qL0r5 z;)^=iO&x2Z-)z9*rdo0uFbUp{pJ1!EUJ2!a?yvu(%Dj;e*#NfmDvu#e^nAwg1x3&! zVqmEnjDI})MbiC<&mTl!%SKP1d2VbQoI-(*|0n+@$WV*^Ij1^mCr6MIsxfsV1YrH- z;W+ilIK6C__wj5wULE{4Q#5GJ&VVKZ8GTGN?FX8ZH6TK*g0@Suz_$&?2u+%Q63Ng^ z>;BZ={_Xzh1v@(?j;hGnZYrg-iXqQ2`?(<UFb?aBU_DxcwWQgAa*uygWfIArW|)G? zzq_zGIB-`j9r%P}4{WwJmp^DjNtvJgac=x-!kBJ7{yY}8z{7g69XyW3)U*jScCU}u z6xglLt#UZeE$-#5D>;n~y;-%eRomiIAi!2YVrwqmZt71WJ6K?yf8t@&J#=sI(q%>E z1$$ZwmhXSe>jpk0?uV3lypg<)OuM+FhhfQZ%rof}lT)ssvR5-=se~Q|prLPk#ek@8 zzZ+neM$@KWLK<=P5!0hYB5^`}?z!PxCbRO|6+<g8n^95-gO1@!rWu1n<x`n;MR-iv z;N!NqKd2Gqn~;?ba@;;*LC=KG<4bKIuU-qoWz)-(m-{N+y6jweRV1AxZk?`>el0ft z#qcQztEgl>2JA5eLIx%arwpbe1KjSc0m7XiAhLuGZ^RGr?J>0Eao>@6wNhp0ij!_7 z_&x)VtxTW^oQGktAdS%(_MtfH)lEX*7w~m@$j%^;hO@$^a~4))Nu?^29*2pxWvWVl zsw@!b0C|p(gArH}kt<}<AQ}%MVW6%{4LfiO&jZ)s{%9Xi@5ss#S+9B|d59O@H8NJb zC1e^i{myfn%pEdu$hwCjK0Se=i<MguyNuP~+b4{ht7id^DETqw4dGM(s|$M6EXeyp zmq4P3lNOwixrCit5WEy}mi(~2q|y`a1H)hAA!sPz0FToI2vHHz`Rso5!WPv+KxvdK z$V1e317Z=4s%!)juRLfjo;vq1=uzYQGnk(Ck7u~PvQCL=FCc#J{8-h0<0Gwo03|3E z(w%yNHJSbB^H0U@JA}bu*a`uL13Vh_oV+g#s4dIh#(s=7W5(<QwxuZ;_9*(a8DB6X z$ncNV3i&m;nxID2zue2i@pIpW#^I3gn<OENL{dbcZ0#R&mjqtHcO!kLFGVz7{oZPw zBUvlia%|kJOl+;?g{7x$d+T;_#nmm)-Sg3aPR8ww$8YmX4g2*j<p2?R1Z@|4;I#U9 zZJ+^fS<A}+7cXSl@9U=s$_(q=XFcdVNpAai8S&f7D$2N25A714yO+vcJRtfbs!>Rf zrg7f!pc=9bGE&L<eodbGKOQ{!XUO-Fy1tFSU%VaZ@#mlGNDOtWw(s|s4~|K~zea48 z{Yk`T1Sj(D+?2|LBDV6;uUQVw$lF=T1FqzrhuJ)Y4qVM#(3ey}@ll}&v==&qZw$JJ zE8{kLAmnoSKb#%Xy}N8<lqETXv|WNUew6CHgMU%jE5!lO)V1Nu3U)X6!k<K^VuoY; z_H_6_;D;#jMC^0%thh>c(!^Vi`&u%<HPWUHm6QmP!UWsSUAn<*Qk_nn)C%{TcX77# z><?Ud;GE0!_fw2t9GKW#ClB>!v+dWvUz=;A%UHQtmr%i%LppHY*--gqfK8GU=XuH= z=er^1FGuB?o$Qo#%FtjVC9Qyl_>*Cx@wevaeA)7B)jqBp_%&23`dHnEOSW_zxjAKz zmUZ5U$>MOYulKUQNw(q=uZw`tc@}G-=sRMan?CbzujRTeB8OCeJeW9mLJ(bm($)06 zbrnBOWX!fj^5k>JeTHjJ%G*~nwD-h1H>}${=w8px;^|CK=x@4!H^vm_vW7LBDZ$%T zV>K80Xt6naPz+1$g0bN8j!sjoHL5bbn*k)!m2O9RD7aGF+~%{pM%F&9qtFf|^6x%k ztz`LtR3X*J=oBpQ_+6cP+K7<~%Dg)Y>b&oe=Ly+5OZEOp;=1{zW<iJS>uUzh+g1_( z2x_GYgiOo64c->Jbxh6wY3Gx23M{O9%tO&SR;PNq0k)rq;ZBD|bdT_g-oHk58VR%D zFiB}enu|LKx$|c5(W}QT9j)%k>&7pM0!U8}ae#&yEC<uQYJg-;V0)C`v`w;<+Z1^w zF1V@4L%wV{+mhQ0zkD~{?EKyy8EPr_W|`N3Z5aOp=Tx$F8TZ21IT*=bE$|vIKpway zLW33!@#Qg<YO3TGR*{Mf`fRm_Y^aLDn2}eTZTf`j@C_cbm3^ucL{RPFKdC3Or12En ziIQ&Ij(gcysjiq^YcSBBvx9=<KqAzx=5qvtfJ`Kdt`}#%vSN0MdRUo~xD8Xa8`fQ_ zI1p{9S%x8Q-64C3aYo_pgko$jSv3s{V>!YkNK?YSIAZR6NfX{b`=ID{*hJ16O~dp2 z%>zeD-y4Ww3$%M*0Fy5I!glb5Mxcj=SFixxe%Z$gB8eZ`GGi2DmaSZG-~G~jMU6?$ z214W6q-`vx!Bs0}b3Hwhy=XA9aRl~qd#Zeoz=;8@NG5j+RC6qJs1n2zxSMzRt(88h zA6ZVN<>!@Hd5O|_8Fy>C{227Tx!@;cfUa))A<=4Jl7Telc;WGqwoZ#IS8q}&oO!hB zJhw0@^|Ndj?#y@OvsWa}2(&cPt~58XVM?MTEs8n|H%xdiFUI<zvRSQ;?8S*;U&hyV zZl!+z(pKm}A?=mDt}HS0sm=!5*rAmr!q7T9H;piy+?w-)zKpZ_5Q52#zUTQtr$mR! zCAutW8yWuvznh1SloL3#QBq5eEnBM4R1Z^rJq!V_GcoqfVLEJ5ex+SkoF8sqxaML* zXCNKuFsNY4e1}hlDWvC?u~fH;_+{qf(zkC5GqoP2iR@=kRh+7|9X4HQ7|a~<H7yp} zaD=fB#Ni&Sy{rlniMq_D&)WCqI~R}S)tHdQD7l1@mz>2R*ntj=hSB~eG7B$UWG6gQ zR5a+ZQ@l01hMnlN3vu!qv3*wnC6-TQ36>N~5Z96l&!qY6qLnL8qmdGCp`*>At~NQM zi4?ZKhTOs55Qn~z^s-opri59p$utMH4JustQ9oIzc0T4kv#|3!bLjCJt?2n@9&$Jc z2qEdDp;4W)<fl26d>jT%n3w4<OdHCQ{bXn>=nktXCzX<9L@5-g1*kG(Wn_2T63u7T zb)g-_LM2MsjM=qI3=*1Er8WgTyKwi<%KOr}*Y^`p-&-%}l1fU`-YdY%k!a-PdLK9o z9^KRsM*T2o^g>u&V&8((yR<))T_gt%-7f+ieIavKeO1uCJ#8%1hCJau?|p?tW^-X| zoz(ev##d|xt&SO0Qd*my`i*puFG9DBL9KH?qD(hbIE@%()tZ7JlP)zoVswQM3q5qB zJgm{TpF#20s&v(R2S>a+mkAk2^9L}mxea>V|Dr8{3Z1dJXD(8ei6K=SOVX)JB-M)9 z_Y>QK%U8!bHeT!9vKNT0ovvElruJgT7wR&vOzVE=&|6{<eK~F3Q>XjVz;@74#n3VT z<mmORG&a0l(nF2CV<6Wg>W)jk_7MErTF*pYZ)JYXV6<cwgN_3WesR)PV{EtcpNBEz zx05i>x)_D~wkmn!hyU1F?D2xk)-~VpUT-V7{cneDsU+#qwtwiUUFOG2uwQ4t{w!CN z1m9g13&s|LOC*L<GlE5s$E3{H3Sekpbs3KxGZHO>bnE{Yq8mb=&WwzfkTw4J9xLCr zt;qZZ!nIBY0MBp8O0$)9_j>h7H6VQ~{YMAXp%WAB=8~lbj|#uk>gavF@yh98f%`vm z%ozTO<XC?PO2fiW&(Hn-!PqJcPkDcEfa$QD%Z_3OM~TJWXFJDcpL7u+Ua)UPxRh~( zuoJ)us<FaW?`!Wedw^<@c1Mf`D1QGUeizXJg>+?5{5EjWzkr0+@K39U>GSMtbN;j} z*>qm0(1l0uUS&xUZE62wjB+=iyL5HnI1eUR7W`-b)E8E7)DJAw)W2qrsdn(95Mq5F zl~c?3dy3mfQs}R-%lZvI(TGr=`Qcfm|H2U!)*&DGgec+d*7<G8c^%!uL}152_CPuN z5J4mt1v|bB;zuSZVB^?!{0DGCT)KzADNOZclw0;mEKj9Pba=ZJd)JYl1%b^m{5cRZ z{76>v>#6@2eCos)ut&Ww*O&iNn|c<*KPXSmKm!hF8{41FLrza2C}Y-tP=o?a;a~sL zZIEzx^(d5e^l;kkn5tG_OVkYHc;~mlUm?i@%-mJ!XkdAY5V`+9MnFxyq9RzWCYkAR z%pkFad&Jpnu4dxWVugRcBAb=J^Nzlf=uyM&hZAZ`cJq1OrL>8Ezb1Ll<Xv97mOb+s ztR`gP&KP9n6tM#$rX+wIpFoQ}MfC-V>Kdp<@?M){2<N4HtanqY<5Igb6dh-mu}7FY z0_Jd_qs^phO1@q@%+I<^h1(&fi;V*<d}hFq0F3c#D)>0ta0@RxuG6K6QIzG}!@1+J zhrr||@ukFq95i~jDbk{II_k@Pc4x?_!=y1rAT-sK&<s)-L^FX=E(Y1j0XEZq^u*2| z!7a)A=^{0iVLhsk8Mz#CT{1&g={Vy4U};{64m7!hjtaf=CTq3(%MZFFr|*h3#I+@& z*f;3Tg}&CQk&#NDlw<pC=F{Ys8DjNeI;nz@N(7zti9pb{q^g64^^I!5Xs+g2i8BYq zUNEa27Q8w7M@bub1gN_LFY!g|Sl0V3-(`w8<(cWMZk$zc9DF4?xq-T$V84)(L4vhw zrZ6y^mVa8`Q`?jqrQ*2*bPBe~PnKb6er(9TaTDO48tDs_zJz}PsJJKIl}}cv7u>(- z#GuG<f^6XU+C+jOZ@cb`)mq(!+L|pkGoNwl_KCXpRciHI$fu@;LD+n%fpJa-O<x;1 z>ssBD-Mm{fXIygoV_Wx&t&l65Y$d)A`sdocnI<=qpWD^x7m*T2!Wwj?q(6KlzxbQV zgmK1K=tPn_b}1if(?pHA-W186s<fvl{Dkm~gUF-Z8#o^VoIDp)N3p2v0P!~tu$EVn zSAVZ}8v{{0JPAf^bICo&(8QB4rb8HvoG=)?A=#MAyr|7OQ8GUk2D4#hR9O%irjk&$ z(-ax`K7fx&50f@=@%l*4`>7FuTG?!yJA;>X%vvuXTNHKjdS~2rUAvxU@qnfo_K!Iy z%345>T6Hj*yg%yxv^~Ku8Z+cVJ1M1RyQSHj9J!EIF+SZ%e9~Ea_U^|ssf(ClEpbFJ zZxr0r+1!ex>tgto07X%X&-t-V<dWJ9lKLonTd=4~MG9c0YG?KskvADaxJV;n{fJ%v zpxg0fD$%3jsFJN%s8V9G`8JQrRW|{q`uQ=mY6)<5TwpoPNYmEq#3Z%2s@A{agj8-R zqM9xMH;{e4uR#zO|FW_TCH!_PcXUPqQxN%+*Cs>Y%X8RJ%taucVT_X)Umv@#(FwyK zT1vg%5&fZAXwb2KNy<CQTlc?(iBmiA)GN)&Mc_}$VQ}JHk2@=quO{0!_NO7NI<?Q} z<C>dGNbAuGAusGL>gy^W=_xy0)Sh;ZcqjC2(RBx^_A^t|o&FY>%@9Jr&Q7+WA~Se} zB%ktAwwkHbRen3aP=}eKL3#&$61fFRF0VX}c+2_hY?UCfbjyD+t|ce`HlRP};@P}e zPtU~>P8>1CFQJrn_Z|;)`pOhgWSOBM+(%EMTEbAU-*=IJZYh=su(=gvoNU^{-K!Yo zQ}QO{{Cup-l({d0J;PZFD*`lG|Ni}tSMUGQ0vQIv$*Zvat7^D4L`UgCqs-nTggr$0 zeJe>G_p5UO@@fV|Yk9?@1S)%10&I$ag`xom(cjmgEb{@#;8}%iL?4KR8sB+MZE~a9 zC(`u%4%3#r!`*wS&S3zzUz!aD#n+2}5;djZt<OdNrYK_j&xP5CIa?C^DNKdo(M6qG zG7XDY%!~c3&w2kpAARO`W7>XIw_1E_t#l-N@6))UIguFP24SfLuCaf1;p2ZPWIUn6 zAR?r%`$~^&N;+Z$x`T#PQoC&Ol$~##M!8yfzfKfBKmB-h=d8>*p@wxz{ljxuE*$MD zqcEgOw8iGrm#1AAp@$X{(dTU`e8zS}qwqA@o``mTrpA%QGM-PKL4yP)yHV(V(mi9t zO}QI8PW%k$yD}X=GLnd&1l-MFwTMY6b6wjTTB$rSIkei-4HGjVmBa{<C7RpzCR~vx z(fZt-As`OdWeN<`X0h(#5_gH$O6BOD6Xi`_a$18{ynt5d)E4^Q!HVRp3GyahnJmr+ zwI!5Kt`eS<J+z^n;MdA04mBNrex{o$Kt<qfMtNf7d`6)3t%094WRs*F&VYxR?oI-H z++bsDBdgujHNWSxfr+u|yU;BZSzarXk+G2q>!kYIG2*UrQjXAl$VE@Jb|^Z=R}t+{ zem~O(89ahN=MJ~=h*J?r$T4iaGhr{!rfcUDk}Q_SmeS>ZGeK1pW&s7KZ)J7I+#AM{ zR`Ot2c}dWL;Ri_zA1hRi^bOl|zskVK*`0l{q7PX%rjHl(@ZY{S$BtU#-<r`tK9`p~ z%WEmVHj|Uee7brk4UQg;ed(d0STiYf<hDF!a<yBCky#-+ztzjns9vB=_JU5MB2r7t zP75xcP)hG>uh=<RSIH&r04I6i?VK<E-rFr93+8^B)O5iZ_)0<PTpIcaCE-Z|Bf={W z@6QM-&OUG}FupU|F}N!0<gZbB`8ogY<KD3FH%vtL_C&x2qHvf2JoW)^Cw!mPU>z4! zH06g<J$YK21nX;R$_7Q?fd>+5TlCvm`Z~J;m0f=P_H2&#ZakKe6(aJ00TPU>4bJld zL>UnTzS9&*dlVx0@MzLK97}CHJ)J>j(hS#^WnVe8RbJfCXwYqXnDAmZRxkB5%~TMP z<KI75EwI@G!+GJEPjf4wAumgP1%tm%_NJi7<o_g6@mh%PtpZ(>b<={0HMG*3lE1&7 z9ehVPCb;c+ysfFT`<KeQrR{^B7WBP`wn|~~`7Z5ZTtC`5O*|Y_I>dq7oR^<G*a>eQ z{%v(0u1Ri~qEwok$*g^;k81kH{9u8kABjyz)Ge0LMwrdF6^%%nlfErAQ!jViO>8)7 z5mK=XM@5<wsM5|F-@>U_Z}PgGo!n-NnjB<JzC7BebyuQySG9%SIINCe9LhxaP9Q$b zlD=hxHCGy#Yn{D}CP^{m+E0;i4{tkZotT-NW*^Q>w(C)bh%>i6G2JnH_jr)WFKfAE za;g=2-JSIkHvBLQD})oV&A8lf=6RirvCS;k@TXvH%o`|lD!)4FD+2&l{9)PoPS-6W zI!2Kf)dcgw@pBpW9P(z4d<S7kj^(CJL(N=MjBz+1y<LaREbLq`Oc8!(BKP9iQ1K_l zlI#zbHFuuZCL(vfPq^&T7n$vreg7nIGt=-wXnacQQqKj(1TA(FRpq!zIZ-7(X|2;a z>mjWb26l{g4Qyj5Q&!NeK<ygqj8dHc+@wask}bc{uw`DCYFMOqTv?m^{gZ}lr=vOM zVuUU95?F}MT=;u%PoFkvK6Fy3JCN37ED3c>@l(K^lmC)DJ0n0fgAAZeq^-BR+r^PA z7hWgkHR!hEtBH=DhipR7LwePiju?+TPuG@ox-hk?>jqJoDdFGPs)53c+4;Mtxj#rW z=`C?G_RX46P#I8Dx#`Z@k_G{JF6GFKH{!WrlIA4}p8<GmNfOdGGVF2matXIHvmd7; zHD}JR<e>6Pdy^s56Dar06E%Odd5U|yK3QCZW5RO|?F(GO%JbOGm>o6OT^J2^FJ9Lf z{4ifJ#PEpHaGH}UG?#M6Y*cyqdfwrjN*i?<zF35(hg|*X$Iq@E_Ye{de&yi~T(!IH zGL(_2S{gG`%MDLjEgMKb^ak1>(Y5w8;+pO1Z~qT@@BP=r+is1bh=?===_M+?cPRov z5fG5xYorU2-hv=ek=~?BS9(W!C(@e~sZs-kBGM9SfROJQ_da_+y7%+G=MOl)@W~`3 zbI(2Z%v{&H*0okfsTy^mtdi<z+It?&wx^v@x`n#$i$@}(?4%p@EId!Vu?&tEYS~zm zYHVh!63QUvQ0ak8MR}nj*N6E2=^DA{z64+PM=VR~$s-&Q!nS0e16(^H)zfd$^IaZ5 zr&z~yE0b%vY8eD(>3sEkR4Z1=kdCh)vd{6oNBAzs?NC2z8`brP8`fRz*rerd%of%e zJ=y`L^RA2-gJ5B>`d(yjy^L&%yQ5*8B1f)VM?*t%w2%wq90_Tu*1hXmGD0=qYIHDM z!Cq}<Cr>em@BsH!S4JfdBzgIMYx@4JA?JLmX(Q#yxk&MbdfsQ9(`MRX^mFsIU#R&# z7mnTbZ`$FcA4{`Ryk~n{YsJAuk9b9uc#n&r_w@aIF$HX7+?0ceNT^53S87;Fk~~F= z^kZG<H|Bd0U7cd(x?)|E$*dV$R_?rsRzthAqPc<7yk2)pxRmvx%@@@KpsRfy&`9h{ zR|Z+3<=WVu^3q>MRh;>rmmf}2e0(tLpX%*`*9C;bn$m4-p#9@#TtI39gzxn}2^b5o z?f&(x4@kji=p92wa1>6CDVlbvQ))xuaGqVA=j%K6M*D+xKP$TzQEyY`;V%FT`8Jlx zf0dGG9%nJ86?(i&VZpoI5&!E!vFA$UZ23FW1x2c)IQ~4cYegNc^{_mRxKu}=1p#yu zYtvDDp@vh!wlC3RTvDqy05Nr~2<{ZktUXRvCLeV}N$uR`PgxT2EA$#3@1NL*U2dpy zz5m)-4<@IC8VcSHULVZcnfw&r+GMeFIqNYZ!;Yf)-eq~;9Xj~J2EciW?Qd1;);+7% z?VPUEqcjX0Y^S`nQB?LMNmgY#$)vZ8<B>r<>k-@Iutona)4uRp_%)b1Dlj5VrQ1T? ztTAHSIA()ydQzbF;)z-05SJzY?k3XZ3E790jl?rSLzS0ukk!+eGJZjR@k`4tJQaxS z=ghWWC7|b*ZRN>tcuG4__Q-zW^j2-v*%$L%eo;}eyf>Y;OB1yK%z^AVhXgspo!Zp9 zOkE0BDk=M%Kf_ddP3vmiIXZI{1#`ZPRMmE*fd!bu@Aovtb3R`g<+)J8!6#)|03X|s znq>>>PW6I{rsCNJ$QI)h)z>VwagXHR@UKSY?=-k~opkH-t?@ZsWw@#0_EEP`g&{1b zSkJJvVlC|*o=sD5w-!a;p=@+oIpn{6Y|fJG&fy|4Sbg(2N$n%EGEc8JkEZbpYyIu% zvY$qt8TfKpA~o^N$GP2BQ%=+on}v=;n~3@Co+{v;OC%8qp)XGk6O^Sof2R5Ed&es2 zTZyT;XEbjXHXc#kIOL?rW>``q$c~ej1S&!Q)xZcSgkD$#IL)-Wqpc6SKsN#ii(k-2 zuK>woPfkr3$KuH@c*j#=kns_d6g1(U=SHdvL--QIC=hFQRbJf&vgG4D^m=_X2fpBx zlYW)p-6tFAUIId{1V|9JTur=2R$$Ub$iY6o#=Is`ZrzWAucyA!YccJ+<OQwC`>ypS zAJ7#V4J}HwOa^~GUe_O$wmZ4fMWb__B^hR$k>ieXbmU5}Uju1$hg7XPAN@LJv)e-Q zSyS92+MlGm^6!%waD4IDo(nQq(27sg67K|2MP2^gZw(LZ8kF11nzr`DAW1BnAy~To zg-h!58AS`kSD{%~ee9O}XX5ubE$5tcB1P#mPPq63_wA_Xc<-Nuc#<xZn_Hl?BN$8Z zpGoAOSlSN4(e+&x_hrU$w4`baX1%`5o5?=awl<95qjjV7ozdBZWnUnRgwrg+yngYJ zCq)-#x_ipn=14!k9cbwh=-NL<oS<Vlg+ZM_!B<<2=t3o6IV};ZKQx^EZn;%cy!UwZ z?nVU&f4hwm|8@YNu1aFZh#;g`EmrBO?`!Qkn<gA1m#w%Hyvx|bEO(0tn3!&h$;JfA zm3J{LUOhvlmOLmUOWGS0tyF;x9F}Nw-Ep>7sT(V|cVu69e1D!3Mw}2s+|C<?=f#XP z6h8IJ^qAkFyG0zg$9DT;XX^{Pc)vj*&&e^OZRGXs6AE2_gMR1oYK3_-H*;n$X|}_> znE>*#u0jib?rQp@L;j)0tEsW>sCF>}XKzU4hg^$cn$pl_!RMI@1ENL94rXGVv$V=$ z+*9mZD}S1hQcpYaSMTl|T4_IuMtJ?YnE@wZ?GwK;;smDj2CO0uzN(UCTQ`bmxYcln z*-VA6mLg$%-7?O34Gr~?jGZGaraCR_&&w2kDX^1W%($F)i%E<%elNFGpA8r)`Y6v1 zhqT3Q_b3(rA~Y0}SWn~{F*5qf7UH%>@mgP-IDO{lDDE~G@aln_*k=8wSI-JyEPMn$ zC+505LZTp6zzU-{Zqr?LojbE{;lF<w5_nH0AUA~6CTP4}F$Ulre=NuILe71NmFciU zn`dHcC4A9<z;8N$`DC8}c^4gy`|r))RD1y_{_!c~7>EPDO*w6s)jA8FkMPa6Nch=B zTdME}+Ox5vowWWKh61y*4=XKjagu@1LYFrt5Gzb$0K<Yg`*Z>xZM`j%c@kUHo>?$r z9U|PqM!;-)_0`3H2$c2$0fj~deDneiIOYO|AOCuN#TEGMU!AoUf<b__yZuaB_hUaQ z-H6>@Is#ObFK5O7fUF2m(0{er0+svsu8IJt=K)7*;3YCwnPGlbGQzj~dRm8D_j*NU z03yER&;N4*OO9X!7#jD$+bi%R+6vPKai*r@?cSQHwZm28$oE!J!gn2_d^qd=I#vSr zy3Z?+Gs;It@XITuIe(7;VmMLe6)j_-qEUZai}k@%5~(4AR~OU@jFUz{Z#T&UATkH< z{zDKTgw^?bQ=8ZTXcp}k+{U-%0r(uyu2E=H;ndLZWp>dbCBo5w{c-MwuA7RM8uG6l zieKqp1W5V|h~w{wOch-qi2SeD3Pe6>0Li`_vHhV!utkFquP}`~1{mhmxU1;>H{KQ$ zzqTzJ>a%ujyEq0w_g}q%XL>+rTTSOS!}7;#x8l5pI1hI3zOfc24xlJ#Qu2MaV=XG( zk@ty=+#fO}zUxgRR4A-$<I_Nu86A{yd%S%RGZPvJ!Y^c#h?BbB2+*k?KPDHY5p|qU z{rdW|TC;<!O;8Yo{@01HQ=m|gW>cH`i%l5HKU{w2d4`L8XIsOn>kbh{vXjv;eKq?% zV^kJ<L)MgSmiqPi`%Mgk1Rg_s(w|6hk1lTEClEJk&34VcvhvU+k1HrGyb{=E8vyAY zU|P@>HF%Pml@<#zO$@x-+45W4UIy6<4v^@r;PlGJ?h!xXR<2h9CoFHy?0bVFCVm-O zvY0)VA1*hi0&sdi#f&0Cgj&#vEw*i$8xIEJ;0~xi*(;;4IurR0?&oa2z2l#bHZ!z| zg8@5%=+)S;CBaq<U6_PPzMq2)v%O+H$LP)6FIU@gPi|vVD=c6o`zxAFz8o7VuWk45 zh*eopQ+#sxboZ#jceP>14g>9K=WUX|g+5BFPnZ36Qe*nTL_gzAS5eO^t(^(<gTs?o zRg;0D0TyXYB=@TA8tNP$aTg|JpTq(Ha{7rrx(*T4E{8qsq6PojHM3RlAqpovt|Y^R z?j&4TI$82f){#F{nj~*M9dEtn^z~}+05gE;pFn;fdOTq>tEbTc7I(WKLK(SZv{IKM zmV_v+dBu~YaU7(?u^vM0LPak@k{eD`3*imDOWCrezzhQ5{*Y{%Kzb<cIaiN5G^`>& z^jm{^WToWVsJ4eY!~j2<_5@Tzw-fgoBcvN{HC=avbZ*(lb=|I9mae>tb^C{a3Q&{; z#h9{2qZU1!pLKs-SP)lhH>hSAK2=~o!a=t|(MaIlVt1qNqx`J^H8FG59A()Sb=cZ0 z-QaZ+O_E-q^`zGd?6^NG52EGdm_8D=w7zcK9GelymfhK|aX09lu!`x0*0O64eAc?p z5J=-isOQ?N=Pj3D>j!JjjeVnE+1(*xcmVJqtB|L`8BKaoaz~ovNzw|$FmkR1T5uE6 z>4rd~A)4<<W4Y^NY0X~9-WXuJ_O_pXd#R~Zef#}|qM502c^Tqoa=pjB-klIGrz)=P zG$e+o?RXKN4K0*5u^oSI(cu})69Qmjz7pR?S1fE4rqYlalLi926}QXUr$EC(X~Lq! zMI$e+uJ>l5Od95$Ql@X%G#WIdIe1H3HS)f3k1bkl3&oS906;!9;K2P9poc+AOH2I( zUbahPb&d0*nB{lvr<Dnhw=IR-B*=|4;&)&%v$hSBRNPh(3ni{3Z-^OC`TmtS>WAtx z&fw)-L``%?O8u$4LvJjpIzQDDPnW7~!_uaweNyK${|+Nf0~+6TK?JaOa4a{tPXlm9 zVL|q0(}?>8D&S|Dq~$X_EqMSu&0_G1yI`*CnpjC*N%uZGioj?Lgw~17rUv8gJVaS! zeXi_rB_Hjrq<WncP~K<l)S$phTzJj5lC&)dGP(Ep9cj8<aK3=c{l_IO?4%j2DqIo+ zKw9y)?XgMhs@zRD#V^-_g~p}Oq`lnw*W`Yg|JA6o^J*qkVo`To!{byt0?sYZapRF& zA#p~aNhNb5fJugfk>HWGiF=8FL7h)C2={guu^m?Gtp_|SKFBp(y3@G4xw+N~u#WBl zl&lIUuC%;D9a!ZDOz`s!#NZpT-;F<80k;7{o)~<_^(UW8mFyoIZ*KmpXUA~Y3bu)t z+eILMH@Rp0?vgU=$UdM0ANL?WR+KbB{#0KkII8?#tvB$VY*K7)&*>a%>`H0V?tS=e zN0d3BSY?nk^vpg}a6ODx*)br+OH1%+o}sr_@&g4Fy6Z&rAA*FA-_H;`zQ;gy@jcDO z<)18{?jCz=RH$6%#vL{W%>)lM)kb9gxMPcJ`^DC0ToP)A3I%%@xstiOLNeX8+_YQ* zczbSx-mfP_Pn}uhCHOQOX;{c<U7;j_QLnVe<zdaVCd*JYN+B$SI+F#h@x8+~;m_+# z?9;Tbk$jAM5|tyBEUfmPZw?FZMo{7i(aJ)!IPheG1~zV`scwGw{@{4WJ1CEQt~X44 zJ0UoHwaJmDL995!M0R+v<8X7*s4fcQ8!j?!;HX=jB2lh8`kLj}gXwZtxY(HxCuTFM z`sH4QE2EdwDpcx1b;`j0m$JzETJfs^HPP1f2Q#vZCWop$kA;5%*UJ7J^+{rA$9LQ< zEF7bvjAdIvmBAfhDSfYyp>&orT!#S#51I|il%Y~t;2Lr2Ay`G8rR!Vzj%E!?CLA%K zSiL{z*|Ed}rk8ar-a6N(HF}lZ?QEmd+&;s&H&8J*!kM*4obb}DJjqh3Yn@8(-beAN zPRDG_4)PcyiH~xsGXDs_(-?XE?2FfyZmTqi-EQB%wR{k$gS~#aww&EXRCTdQ{aP$Q zXQf?eSXkPJn)s$Al7Xae)-b-Dv8J4%r1eMWDD5w44@a#ukyHM(z|sqyfLECMQZ$_& z_I6%?ejPTq0BPwc>NuCXm0;|YoNbGk*b|Y?)Rq1a#(CBtTgWjaGS2`+RqtX09!-H? z0=7ZA4fWWd=X$EsFY6#TaNOgyg(h`=sKy$ROiTP8_->x+NuR&ETST9AWU<e?1r{25 z2({+|ixZ8bPENkE3v|K9BcOFSpFL^ve%lmnL!_48@&O>9x*6u@{X%Nl&7<&63j0b} zVjvgiSr*q^!M-g@SAK+-H@0S7!xpQuGSek=CEz~xE!s~0Hq6x&bH`_V9?RAD-E#4V z<J|ay{8aM6k8sPy^6q`MCwE~HofzdCH|)l~2U26XI?h?!3Sg8daD=RcUyda}S?%O0 zfw^p~vrQX5G;^HW_|<C?I4WN5HDkEW@gqbEb&aTtp{Vk)rLg<6LlTrZkH4ybOTmm* z^)CtgnJyQDVfLI{+gARGtw*cZ?LJz&PkzBV(Ns|z@Tz6-7D`t-V2Y>Hiivl2w)FLK zhork^FC;XDSK$sH@!SC{V!!5QLPM%Ni?&YOmWGR9?;M&#=9cDs8mht>*4}YMsCeDG z@%WTI#Exiss=W%M)hkc>z4dwk3*Eb2L086Y^GCi!<Bro?K09eI<rNH?LLSlcTe2%c zWz3qzTE~^9bu5q=CTz7qzNy!XK`na}*qg&P_hN`WDc&?MzOKv-g^!a}P1`gOYxOaD zTO6CD=H33~=VTPhG|IMUGU}eGxL(1=TJBD!w8V|c_gkH}EP;%HY#5#1iKm#ki#0;~ zD}E19kqleW;4_@ev9NF!h+b`&FIVav<;ZDBd(74;6;Iw$cr$)r94pe!gM~iAxON6N zreDZR=taxYtPVv#HrccN(vsNP-?8b~I>h1oByRE9J1I1RXK_l$;;8)tv*S$wjf=jS z;<)5qH0M}Qc3Dwx6rDK{mG3_|Zh74XmBQjsYojicAyPsgwwik!^QuDP^RYK=M!|d` zBg|J>oMZU$ohlmCO?QuitqzP{R~8Wl5qb<FT!1|u+3V|NjQ^cOcwVNHzM;L6UQ9FS z7r#13e?NgrT=V(sm=AH5MxJOtS@IG~CnRb6ZAW)Pt0F})MMv8P--Ka_){_nCwaYc1 z?})VW8?Z@!r?7Ndf%XO^cf~$dfp<D5;>_OPdwqNjeJv*}l3Gk8isuuthdq9B4BGj@ zU4u!gkG-w9r`9VC#jPIa1D$sHIy3nUytVTu%u~Gjg=(2941E9|5d*JQ*`-G9hsX;} z;H1$>{B_b^JV!`M<E``KPgJ!hLSh;lvSHWfdqn7*qn5l}YlHYy4!8iHcoD!7EN(Q~ z4hT2Vd#EQE`OKF!UC!S8p8UzZAYs)z-^KcPtBBOugvp}bhbR-CxU>UokazEJepvDc zxw-g}^OT6%mTVf!h0&9Ab^k{8bdAuRpU)%-z^R1K8g30RR=>U9Z3gDu{5CABGzyym zJ+i;E0#iv+<5jI|TU+OWn6+$`Wq-cpSm7FXh><#s5|)*V9V!}3kIMO_Yp`gWv^i>+ z?=+S9v{zH3$<%q$dALOhFM~bo!*gTbu0kuRV6ld2eub$YuYcH$atPM>aq|@ZLvmHK zsvOFg-3g*HAMh`*aNOs=Z7$-@dc#mBd*xoUzYz<D>qHpawUSLW>beq3F#s5qt7()E ze<t%u_-ZxDcnk*YdnXY!@^4E6tg%h*<e7axqI^z5wAF-kN$`iaK3&m=J5dGp$uq<P z;(PM<u%=_{{1x3IpyvlyEQ!kS{n_<2)0N(y&N)u<<|!24QAQxIsy@t2BfiU$y$J(} z4)9(r9^q(Da-poU_k_qm5%q{&F~@R?xeko{itfV{eMpVcS26`WBf)B*AWjA-4vlu- zhWW21wRIbnyKn?^H63bpY6^S!N1P8WpQL417w))&qbl^xutD8#)Jd!k_di&R{6la> zD}DR8k_ZcS#E_nJUVf^DLc(5kH^<KtC1^LjnDR00^`$veV2-E56G8NFuGqc{PA67Q zNC=3U?9^9=fVX}cqrTqxR9ji^odSWs_H|It(|ecsa62Z-uxTgusUvnFk2`kN2>v1L zvP8h=iSpM~Xuj3#omQbWtR1?;z5)M(-*S9aTDHl|{>B;hT2WtHKn><}C4Z(fHo~+p zm_u<5aC+nFqa-~jJdipMQeZgm7F~dzpnJe6nK!SVX)AKq8rt3cAgsVvv~50|xjUxX z)0Q9B(B$r5=fF!v2Mx6cczc$fEk_kW-SxiBA$3q2n|sRXPis|Kj5w?x^s`ItzZWp? zK({x2-UiuyX^*z5Z`J=2vj<Ldm7};qSY=5mt4%Zj&_I|*dXf5*FKLbUubOGeMlpPR z%WXh_a-nob(rC_qUE-SJtc^Eo@olJeKQS@7`;<OBhI0Jb;dVs4dl8h;^p_hpettMs zU&Ks_rAeRvo;CqWmVj8o1Nme|X*xSMeI6PoP?Tnz|2Di%KVjfZ?U?<3%q2IW3p}Kq zqy9ESZWxKl*UQbtxgJ&d1?r=X94#Wv0_lRu=eN}P9q&ZU9{Mr|<jxZxlyAUkIrAO! zwgcHh#Q3+@@Y_D?;ik71C_){t`EHw311I0Otu|!o*DPDyxVl1w!7Y;a3d;xAQCUC{ zo35KtpfB`TTD+xz)%K-gq4(zJBl)SL)Bmlcka>)tgqkJ=!Qv0jrN2g}+WmNxq`1o^ zwVi;>xOvX@@7rh+X#RiIMsxjH;GJ<78?$iP#c_h+P!w0T8U(9Y>w4}Cv{w*g4WkQj zuay3yF<(FNN)nK+_yBO224ep=J!+%{Lv#}Bc5ac@x31t*a6Hh5keD!{TctcBTY%4~ z5!3;&OmgMr5BPr2Z%b#p(tikiKo`I_qiw${un2^tLs!kLN}L|OFH_6r`63LKIjRhW zu(k{01Sa&9(S<RUh9e?j<t`?6Pgo-xZ7H1&M{mIUY2e$raGA+Z6v#e!t#5B^Sekws zCjvF!U7M;lOrC1|{>=%8vO9Jr5xJzbyoJ)B8BDoc@gw1<XT8BjUw;0VkoH)s^o0lh z`x3(!iw8r!Q1Pe2+0X{6Tk?4uUu5AI8o(Vh^F1azg7Fu}%koBxs-W#!W}_=g1h0fT zAyL`4W$*d<Ne0V4KKC5DWnwx@Cnz?ycfGo@Rnn^1a=2(|=;5$zG<$_DNQ^rE)vIZT zw}6=3D(bQaZ{I9K(1PCV2K??diZx2Hgcgkxdk&F9$+mOd6`nErt6y+da5!hKC(3Mo z%cYK~xW-*>$Ysf_7)2BKC)H_;NPulsD?*$_liWtNF@`DK@!E&MFpn}BfTw{%&XKOV zcF%tl3UDs%@t3H+6Qc6wYUvEK5w#M5*Bm@nR;k44wyC*!N%-9hdF%vP73vc}U@w|> zIr%=<p6j7YRUq3>qD!G7wQHX8r$YEOU)muzg2POLM71aW`gFaLtTHoA@D8zS2k;J6 zutRe4fsqK#6<t5R#>!+|$L_V21?~RbBek3gIfw^hX#5a77<`0*TDk!3HunQmfPS$5 z*IN2FG^>v1#HMQkPvvO*7^8Dj!@+L5H0+ClDRZ@rN%K!nB=bxJSI<6u50eUW@*u;I z?W6vI0m7{7%FywDr!bx&^uH9wGf4xUVfd4sZG`K+_@4?<sKtA@dG?rSkvLM{O~vgr zF1X+Q1;4otZ39x-SQwz>1{!ReV3Wk(+GWD013n19QCF5+_=M{P7Tj6);uD4aez(!N z($H3NBq)XOrN(x`+wEbMKi0j39*`LSS38abVnuZ7AA%OjOEkQ<^2e4>7JI#gkq-Gr zyZ)K;+qYj=n@Y9=H~>m709GJfHx<YMeDb04KLiEHQ#3pngbsayJetSjDbeMofG7E6 z1*9`xAS>}xUTIq^^5bS<L%t#Kg&`yS4*0YKpi`v)&0d$pm+tt2Dj<=@Qwu;Yz5qW= zjB}b!y@zpx)oBw15y@7jB+SUY=F9$rOhf=+pa16_Q)*A_wu(4k78YC=bs@Q!hzmM< zWdOoHtAp=#0dOn`Qx0K(_cP(=g$^VJ0gx2m9mqc=2!9Furr`m<nJqT^6Q31@n>Rgi zIsCCR=3ytC3@?Dy2=MjJHG6@-+dL_ro<8hh!>s-6{CbVRXI%^Jr!Fh?N}|`bA$N&y zY~gnBUGRffNMfMsUJQc+9gl{`7pIuQt`x@2h}PRhin6M#DJV0B3dLtt{ojX(c2f`1 zJ(>sQ#~CcyHhPV|>E=sT_}P)kb47g-FU?y$tMrHSm$#?10S_e!SRr!~Hdb}x7uI<F z*iP?h!vM1-tFF7=srk53LDu1VeZ2(Ev2wdzd`tpz9jm@VQCQKAaC5c)GF?+p@Zp}i zLHLJM9aLgJKs8`wa9&Hv(YO|tfbVSw0bRX(zb94iWD<ky77%(?H{&fO%jcOFpa2us zy2H<UZ*n6`^;6wblt#78{KuHS2tHWY(;S|fiT1l)`7BpKtiM<V>Lw)knC6GlK~zq7 z^LI3j#yRfp8z0zXl$k8ldH73yZt*Jdy1}bY`@oF&X*fV&ypRN%8Vy!1)liQynx8pF zqv{a1K2E4kx*Vqu)i>AI%+pMspjBjg8}8+Z_SbxlbaGBP4-!5B|IlRZlx@&SOq!{Q zDcRo1cQKxuNkWP`bE=R}^?S<JJizyVeXSh)^f}6mYSE-oEsv*8S1c+wq+6$0Rj1HU zO6?A>LDV*n%2JnseAs1TAms}{#%`xwIKUU}(3glcc>Nit-843Df??vA4uTi-(55-( zOnz!gW|JSV%aYoRStWflBiQaqSl#{<3qbNjGT22-`Uw*4Qd|INq9x}SV(sVpl(O|h z`m`I-n_=F7!>Az}&t!1u>?ivvHoJFgZ|{6jyxW-SlY9h!k06m}1KoBC6v3h{czz)n za9lv0rYCJGxkad}%}vSArdX-KSe<SD=fSG_mSBbHtn~}7H{Hp*8|a{s6ZXqb04_vH zhDYKVFhJ&1N&E9bHl<fAX+_F?n2n~Dvt600ccsK)Q(Z%>myx{fmiVByu*s8gD~faM z9uvO5qq9(+Zo96%n0RQf*)8hx5dEC&fj4K)oSsfii%tr!2R>sp3P}{Fmspjmbh9F% zGoNH6W4U;hua9h7w~$`LVxnAD4HnFR3!En>CX#-R3%CryX`pLP0)YF76F3acnr<<Z z*D^NUr-e>*H~G1fB9lm~At*4;y>3{S$sqf&eDWy+a+Jf|-+O<jYo&5F0;QLAGVvG_ z+ohp7x4SluGoQv_gOpp+FdHI{r+D1~KjPVqRGSb#qHeHFn2PM%lb&Tz1E>?hfDKyS zj09u^;Imw+)9trlY7f1p0`yqRmV9DYeRT3KvuwZT9p0@==B%yvZmU%oW%dZz+0i~m zRv~v5(S3T@R0s4Z{w5Jh0NR5DwLT~<ntQ>@j}d8}aN#fKOykpV(2S9Lcg}M^?$*#N z)@4=ayFgK*vo+#JKok0y%--2BK0PC`sPmSGhH|!m)ckA@uTR28&_<MfQ!X7B;i^YF z^NQ;8WLI98{`$^O4QuYvZGn8AN;|cD{)d@TO-hfwO2#5%#jSISd9{WEC^17TS}`~y z@6~d`mBPr@M+G>6s_L;iFa=g|r8Y$rnzqe;a%$<7_cHNO)%wGFKEDs(kGpl0BpAIu z#?76=&poToDl6Ap9F{c{N88XdIIdV{_fkhu^E@;DeXV(}#x%~%kMrpvRHgkVqwD;_ zsq%3XfwTd<m#GK`a>5=NiqD|n-tYqc6WTd*>V*xu4~QWuwqd^A)PUZupu^fwvIC<b zM9s{u<EqviWEC8F3=RjLDMIph9n&gO^U6EWb?J~7CvlcrhF{Ek?@rD!Sk)$#Z#Eh~ zR$CX!Gr6PMsCq0V&(tqsU>B7i+9o4A<GR>h6?)%L8@jZiaVSxLo=ws%OZUM}y1*(n z=B9)jz2B58jcz`-S~-2El!=a8(oJI-(IlrY5k*^*c}cLw2BWO_gjLDNb{g!=vN!UL z6^0xU8pz!v(e@8PD5x)s`E6xcT^O#(nM+;YKITXLt^1qnl&Mr2BkcJYz`B9v@>2j4 zN-NxwFMj?RhBh+KQf1lGz0^DujjodqkV)=;`@)6QJ4Th2#@af9Uh|-$JQJgWN^V-& z2VvDubjChoz`^pMj^Y~<T2#<Ez-DT})UFnK-*H1@+s$g8?7PI-Jbn0zpCG$!s)JV8 zxljj-*m7Tl{2lDWi>rMW(|OK>TG?Hpnh~c4U)n{69i8utmx_nW)sC4-bg15J@(aKJ z;N$CL^^|2^t2;$Xozxzhf@0%0^FBXFOw`wle^oR*A{x1oXd64?@Kp-eLin~aNrgt8 z0dkvnP+PB@{&}J0t!@M3a9*cqX|<@=&Gj;YopnqjI^FsP`~aUcwo@xQ`+9l1m{VGB zWZqI2Z8lJaeg2EFt;W*yk&UR9w9;aWAGtfD^bHnE+4mGqGrLR|P#Aax-vlTXWl^CQ z<nLu`VkUhp1t#aspk@{n5_M@EtSk6$KR>YjdO5K`?8@H9DDI!vzm8{v2`#I9{Y_lR zw!m7^B#m}$w^-#NU!<81_zFaS>m=ngO6=q~vx7R4KHU`VUu&_E*Fn>r6k?Tfu_|A) z$pb|pTZW3tGsooir@HqXY9?!&YNJiXnBORuH3-*M&DOPsS!&;dMGc6io$tu&kvTg> zQa<*~RXeCh92|%x>YHL~-}xXUThk3qPuKkfWLYUiMx;D>daVy$%9eaLR#g)XR+B2L z78GP|pUyW{Bw~J;D>WFxF)EUnm&piA^9}^KP$ABk*sxZE(g2O=cJb{8=Qx=RI-ip? zUK1soYpmA&X|FqCmL8`6K-o5^#N~xo-1F8gu1y2(%%L*KUKS(6$(KL`=`xM#@m;## z6r>fY(lqNbBY1M*btmg-UbKsC`e;MkfZ&HY6*1}h7}DUM?bo5;T2M#h@yAyF;zGyd zH27SrzzT@^$;~;FU%|`cRv(&&+-%<y*T+xgH5l7AM5#zcQnc1*bH%i>VR-O-0Wt{x zXzQoB(@R6$jCl{@;Lsu8wYs#+Jbqyf_T=$^6>U|w!LoojvfCIHO2Z_6B@X&wc_msT zzdj<Vt!<a3V!}rwzx0wTw9%8Rd(E@YUTQ~>FKPX#ScT+q7A=WxK4a}q!%|{OD<hiS zqRz}4udTBs7+nmcokoNYkg?g+36Cx#+qnZ|XXIH;e~mk3f$Hlf1p^+R%%m_HESO5n zhksx&$V;-#=JTb0$Ydk#WZQ|CvHT@zN!}d8LiHHv{9MQ!ob7!?-}eYomtE`7RV+() zL4!s0W<5kNMHWEY@1h^Hxt3sUjK0&ou3K-7%bR)NYj|pB+jRJhzbr@TfOhR^A6XDa z>^J-1b|}6PzSE1yY*mA!OG#BF92#CrXYN8Jt2Oe<D;nTt9jPv!DYlr9=fz6-H+t`^ ze_Kstll(UMOX!sW^J>#VPX3TULSXc#z(q)HXlNOoW*sI?gOTiBa|4wyNY~RG32>er z!I4PnHA75cc-o%$%RC~V-oi<4sS1h+-10eUT%Ibx0UNtQ+%A6y!<^=xdFz>T92_RS z-3U5>(xN(>EhhIpAATEUOZE|^P+dDIVI{ga1wX;pjg4Io?Q*5X=B}`;k9<a7bkoTM z%(%bLdU`@NNTIN<DJ?OAE!o>6-HxRj^%WStT<?$+Gq2xWukOagc<`zH-G*2G8K;SH z2&wab?f;}XW@&F)hn@O9b1uatRJ{)Y3S`GUo4hwA3oYsKcL#(cJz5EFHH}DZ4@mUt zD6q(9qOxyo%Y@Z5HyKdRllsC^$k+@B2>jhXz2?&>w}Y*OA2Y=Z%ra8hUMn`=mF|0) zwk`{xWB2CarSPAeEsO*a{`wyaW-ad~_?1*SYl8?}wq~wo$_-ED!RJ6ueztWH%2Cf~ z-ZBW)V)_?H<hK46iN9_gV2rWm<z>=Ye`-m+=E=b2PC81+j@j3YT?L4WR*?fC>ULL7 zd2V?iqym7nYng&CCFhOIb!^hAG(Wf|-^?M3`b({}?Z5!R=G(N3Qv8kRm9_^!paS)Y z{PqnA<R0BOkU~Goll_f0%YR?&9n|>KT|1zWO%=6&d42HT5^z>Pf4~tse*+LxK<Ck> zbYvyfFGjnrt?3~k1*1nTG)Xa&9X|Uj6Ur}#_gik`+d*e(<qC{QbSfa_v>1xVf>EZl zrgGU~&U!|ZglFTMzR5qBS#o1PRoMTjU4K>R|2Bj-(z|L0kelBC36Lw%6W?4V6XKtq z9MSxlZ#m*6fh6!>Lif{u4X&Z!_UahQkp4nm7QwfEF+1|=9|A8UISb;q@bzu{6+q@i zn+WlL9f9yM6Spj%>t$|!i0H$x(KL?-8QHFn^x=PGo3%J7kXOD3dL4rSN{nff6T#nu zNb55N(46s~r@ykE%_7$;C<)y*e-T+thX%vf<cPlmCRf)#k^kREA<BuKPAz<V9*s!f zF#8-YHyYQZtPDG*N&Pb&{_cc0AZ-SQ;RrsWHkTvtP5y7AG$WY+JC5QD;V-&uXO9kL zP_b&@73mcG+aUmn0-sM_`Tj3xX&jiq4ahmM&?W94f^GfCl}7I##+t=i`(;;=_x+IH ze6#NsAlzNx7>{lPZg$|_SnQ*6fMRw3w*@pjn!p4dihFB>Z<ahPSKC~hiVZfqxX*p9 zBhXbO-Eng+9T@R9#1RGL;_M%S=}#09O$b2VVgYpg?H>XeUmO=uF&>kK?{EG?V4BU+ zj2#G^5@Yft`EfORc2s&-f%%vQn6FN9S3o3(4p2+6`46{wMkM|nfJX%OVaKk?1G#H# zWb7&3S=!I-t51zON>9R!7yLFI$sVAXFDCxSVH-lCz-u?*+W@D@H21HO6{?hgXtH-w zt!@z>?i((^c4OpT5N78zga0~M5IV>V7%+h1?f(E!0fGVaJ}v~93?x3JMW(}*Lg`cS zG+VQyM&kk-&zr^O%_U$bf6T5nvC_YHg*$7(Q>VgzG9ylbe$w*aCUDmfn8XGMS{FIH z`r`-hSvE6{J@rt=!K9WoX~O|>z|{@tn*yw@E&gVBw`BqGzq5+l0%3Vlf}R5_<lTqB zF(b~)$pK7D&r5|U_e|@b=QCk{Pb@SASj}r`9q^en`1upHa-8F<nv9AQBwh~n4}lw; zw+A?qe@*<PN^ktvfVYLkvj>~swqrX1WG5%535nIT`^|a-CS(*}2SR56>rG)DIB(gP zP6Xd(fZvw@pel=K{fa1<lfVmdlf5}H_rpYz4^6unz<ItQfw;T|!C%H=K2do5s~c<z z^4B>K)v##gNB+Qk<-8&37d5XsD#uOu>HlNj4nT+IIpsO(Qp4Ivk);~e6F4jOkqms- zfT;#4*XD@)AE$Mb&;KiO+XcP|+1CAgmK>{<+sSmq*%w}a+P&9q(TKZzK^PdZ3IFrz zf_HifT@t3?@$loKtNT%iH2`~ZPB~*-=lc|^CojOImJGT}x#X(XQuxw+TkEfB9V3SP zJE;^F3@>GvqTaZ7Y{(J~8eij|@AP45!5Ef&@Kj*^os{6v{Z{vWLthS?;E3HA6Sg?~ z6DQoQ%LrK}qRQPAbo?5mg&xoKg8xdCXS6cmHe{?7azK-gZv&o0V|kUN3~5sXV&4Si z6WOHo0tVD@<!1+tEw9Ak?69-!(O_6}mMfVYzvAa0J^gKE0P$h&x;|b^KS-g|j@eK% zQ^PpR`^j=tbYYx;bYUrH>FyVc*Sh3PMs@GtU*>9s>GyU>ZVFg3oRZvO8SkOpQ5C%x zKULUShZYLiZRf*rV|p4w@Z3M;*=D@?_=Xur9G9ndT#o%)*1xo<MnNT0@AT7)<>ckR zYvwkxIOp3b#qRb>oKfdK;+{2&H+1AIn<$#lko=Zbv;7%2pLEFu;EX~&>bH%^gDbg$ z3xmv$Y;zg)lM=M^bu;|dGLn=hqMr^-BwBFLt9-_CT$te}Ew7@p!&>E*wI~6zZkf?; zEoMt>tnQ3=>8zl$tTfx!$&2S!cSKtov!;zZp4w4V7Yk4<PHp04FGJf&aEh1JI4~x1 zm20;T6|KvcuHS?)ifNTA7|M4Nw(Jz_X{?KzhJN(ne`U(HVW`DvM8^08`uepPUM?Nq z&iN0)_h>`D!6Dr9)qs+On5#*QvXhq?8P6B;Sq*6XG<9FGmnG<o?+IiVVZalVJ(f%; z=J5~{b#gWLavAxV<k}LMJEaw-;MPiR<@8`~-Qs~8gJo2is+zSnhH`Yf0vD?InHl)i zR=W#fD62Rc-lsv@Bje@sN-~yzHy=ISVtwP##deZ^>4%9{YNj>NjT8BjcD=xl!!><6 z5F9u&ce+cw%n(2h$PEg8J&k3iYqoFj75H|rm6p_UhLIU2<L?iSvv&SabH|Uss)cVk z(TD{w!{ycAQkIgH+Zq^<H_g72NbMp&kzn~`Cnwi`t2{QP_-FtlI$5Yf__okA^Xa4k z4P&*lVp5Tmex;0T#`lfpf)Y#3DXMjyE%}?+!cN8RIlItZgXR8K2oX-V!?{$&V}@2n zT-dZkS%O^NPAOjXTS9L+@!ZrCxA-r1VVh}Bv_k2?w5_5{irC^pY<BltR-AoydklX3 z)S|5|_F1cYy>z*43~ZhwsI%{zLInduqLBfJ4wg$99dkc}r<6}>&PDWC(|H$Gn-;01 zzf?G+wWYZF`lZS=pFhcDB1$HD!l!IXdOXo-LQg+mGhcd;hNnoGDmZsAzUmMGxFQ68 z2QkY(P+i@p#*w#%AiL@4L>GICu=sIOO3JXD7<#IQA3wJ=HmMpeG#S)HDWBdDg~K`v ziZ4V1$4p&&wMe0OW^AckVmr$ivLBO`S}+gcwOCyA^ZgL1KFfBG*?h=nr1x<+X^vlY ze@=TsPTRR9*gcw2e@lfjWW69S7v#XFl6f(%K4+F%Fp<2gX4I143RDZi5g1Db4d#L* zS>6uat|4+V*&=@@k)T3e)eD)!l8h;a!Nk1%-OoI)tqc?Mxek4IuUv=*1Y)L(a|ck! z2zQ+RgtMo+FLU6XiCXB8kE%^LTZ9s9&f2EAIYarNkM5k0kL5twK%Nu-RsI@!G`#iU z>S)kbxf5mXuamiGR6$OCL+2dn$E2eRX)FIn)Wg>f`yCQn)5|{Vh?^~DZ}IZAP#%3i zEr{v_^D@^v_QmH!B^XYNl;mV*=q8w|*2bGlY2{Z&NikOn4RITM)*^o&{X#~+NRd*l z6)Nd%nhcuN(@aY$ZWhTw*>NshqB>-i(1j;)KtuM6;fIFk`WDJ?aXG%n4-A)hF=g(T zId%|E<J~>OY5fZ|_W89KNKGGiB1jDOblvq4)&Sjn*3J#!t5kR?M@FLF8m=(fef{(& z_4X6H&W{yuKB{+{FsF%F^4yT*o_k-FBdX4)vZ!M&5fF&tZS>Rj68<F`%lRSANv6TR zq<k^m>_t+OOZJG?7HOY1`lGqTD`P(u%24AMb17^|9FjV{9{JqT#rp2W+>$#B#S`Wc zBJ1!Qu=x}H%aTffGp1p-lAMhW+HKzLjq*BfVT{Qnb7gd_w9mQU!29V|^72`nYd|Vl zTy?ejnZ|`Kju_i?A%#<igdiAkw>>{?i)>-cBTd#~o+LAn(!@(!+sEkl+bu+W6_v>l z6$Xtf1p?3EjxJVCtW9ZvFdEbu*;t;337^TEDi^egAkON0X3QR<Z*4Xl&Xu~tOE7z{ zIv}Gnr<EDmZ4Q`(!}J057UD|u<Z9jYN#aIQyt?{}_*r(iBG%yO<0}3kh9X8MVo3OC z%Q|0L!)gk4FkHxE;8gzVdjr2dKzG`EoS~<dVGZP3KPzJKx1jLz8;Hvb5K86GAT#yy zi^?(t;d!LBZ9)EAEvVy-?C*!}a>$v_F7DDX`|sG|=O6Z7CGfvK^D+&`xXYMV`CU;- zZPVP#uwi~RMhsT+g8%)@2d`Xj0792YAatq1i(g4ui9Ms3zXXE4M-o4#NnhNCd280O z45>Y5xSjM>`s@{60`ynx`bLH~2nZEEIQL!pBLKx0>ObQ-wJd=I9jii#h)<33CRUt2 zdnh?T>)~p|Pe8Hj&%MI`3UmoGD!*rA@57fa%Md#Qvaf;B%^G!p{~q>*KmJD0YN`;& zWkup_@B!Eg874}ZT`^US%KuO2F_FKW$NDCX9{v^g=KeWQz$H7?bOsl^2PkR&Ly%fB z^*xqUv6OOGrPWrF@Ei9nmX@Yo&;7s7(;Ml*KV@7>Ab*d~HVp-HL{!-{Q1i2eGknq9 zPcK9%un_$gPx&KC`a4LzX8Bi&_cOOzi=OKwah#saVem$-kNb!}{8h>y>qdcj-HVk7 za5<>N661&e4yY#V2s@tBd%B+_jO?elAV)8d`2?=t&G-L0d9i<mtpsM6O58hYd^?bE zJaSqu{S<-2wq^<%x4sD)UMlo)?-l7gMX165T&%z(jG-%Wp`Xsd_%~C9e@3!-&Nqd~ zd8ScKj%ioAUp5l^4$WXbk^kb${Og#3Wc<%8iM-qh|Hv0|ybE}bLqp4tFy?8w(IRE< zNE6oSC^K6cM@05@|Hopvx{sF!BJGN3+%K8<KVB2?)sBJJ$ejV+L9n~`+zZgb^?Kmn z9={R%Z3Zxa1<V2jfX}9@xAl4e;ORfz7ZixRvVP}P(m+O7gf|$TQ3WI_53}*jfPos* zZ|<@c7KN7sz6bCJ?wK!oWk~`5tPTg9xBHDG6^NX$5AlkilL17&9pIXUSQ7zQ_UY%^ z#72ON01@~Wyq|Ux59BU7<`zC#cY%vWVD!@SKRnR*fC|-eGU6ZsK0AsZLc9kb9Xndy z{`Wo%hhmjy)T{9A1t2d?wg9gR>D2&<P9l6zsr|PiB@|<X&)h5RfzBb8^Far3uCa&{ zQ=9={;ox6_F<oDQpK*SH9B*Xf<ETpEjFx45?;3$)_z!+|%iN#NW_EynEX%(f78do# zfHa2k_k1dueY)Bt1gw(ZK4segMV)sW8jpeFLXf{DcRrB~0`?LzkZbV1DCF_{`OSGi zP3*s41A4Emz%7{d1i9aEK+|Gu2~2gYzw7Dz*-e7Y-z@KGv;!`9^wQmRgRi8*=nv-h z8#%szL$d~I1Kl$4kcy+%iiQ}C`beh$r2>KJ{37Vs)^wcGM!)UFlbY&Y8*T=l8bRYq zuDym8*Bv{+csmGC&KNWd2Bzf(-)U*LB`F#dT^IHo8(U=BRj`E~er4VIQ8_^^*(gVp zx%%VM11q<99*S6(ihQ+@>*|cUsMeY}l{DF{+Npg9f0O;!WpF8MbWmXo26{y~Pa1Ws zzu>2zk?2Xro^i)6H!*%a*3!N#z52mX_RXL2jF|dL^cQGaO3V)X7g{69<c7Xyk;?jq zr@d)GEsGHIRkN3B$z!Wr5z5WUO4rR}-$QDS0(sG)!R?#@+St+31+11{77q4crpt7) zKJDe0#mEp#+Z0M&;CQ_kU4CucBCf&u$t}M~E@E_LH~e-hbQy}I$3i*|oC3w_FcOFp z!BTH=A98nx2N_=~3cX$LMo(xpCU=U-RTsw@dO_XUPg*{wEE^zqF{|L&z>AX?SXVTj z1>Sis)>e^SAXoN)vA4L;Tosm(*U+5bos8*$`qY>O-EsEDM-qyfl@0L0jcpp?BxKKC zG<}b%B$5U@+?ZRaPJ5*+YW_WXm#I+DCtD1zvAjpfzOpCO!@qwaBU(^>4oedY=GfUl zA3IK!?sCW+2K!z#s~W@rc9_MxFS^u@<wj2=up$^&BP=0Cay7IwmKiHb?%x5XP9Arb zL^+3^godt<KS!TrvwvS$kf~ctU|Ul6a)^1<{`Bf#-qSrP7<jn|Ng3dOp$e0b<pOYq zqe*tew^x?sE5q`yg|YU(9Jx|iS6M9HnJuxqsnz(c3ULg#yiEK``?KXM-CRgC2Gk>i z*!8>+gJt)DNCUV~bRhtV2^~|i|9KvYR)V@qtPhv+s~5L#NAelBPmi&6j&q0j7(T_f zrC44D;{^g>=+h`6Z%F72k`gE%{~9Of+dY_nRPbUZ_BDB3e#RHo`iG8hnnT3vk_^UG z?_HJnpb|T5Xppd;=(sBKk$&}_jIfjTdUYGOrJ(-0pPI(fgm(N)yoM9v)oK>m3I(Wp zynEuScHiXt6~mnMp!5*F<REWey~MQwl&QDfE|1w<r%s{nz@#xN|79Xh!y8?wg{`|# zf?85#>rLVB!aU}NI*~WaW;DmdFCSb$zB@ne^Sh&sL_W1rT^M37y^SBsl#P#M06h$N z6}np4p%rd~sA<@#kql`UfvKoZmXAh`<bI}^k>$NR$(H7CQ$|Q7?xDil<L=47C-5fD z*rbH)2+ky)eJel({R~kngriQ-#uSFiGryQv;5cbmCAZ$!s+w|Lg+k4AY-}CWXBkJe z9lsS9b%!O)_D8Tswd%c6=^7;roP*b#e)We_;(_OA)qbZCjbrl%TKRip0s$^|h?wW` z`HOXHDWoj5L#|S3vq|<I#>w-CPnG@b&64bzylgIt)l&~9N{V}hUpeYbdN_IQzUCSg z^d1FAh@SbO_q2k#tcupp>^MFawB<`*n&{-JXPRXhH%;X0=5I~v+paUB4eVqFNk*a} zAmEl8hJ~CY0#CDtD~MnmF?#6h5;Zmm1-jKLb3J86&Wrrf{db+tYDZf3{mG}rR3>E( zFW>XmD8EyVafksr0gMbWcF3Le%Tf&Aa$%T6A%;I?0vptue7miCTJlirk@$l-|1;lY z%=`kMLe(QONBXelvmozpZ4Nupju-aOK$)gyjBC#@lhTJ5?sGWtiFS^F2QeqVx)cvV z-gUXg7A7xEXy>N=7**|)y<-Trm`ub5Ho(_qS>VuBN_uRhc`KmBH5!7a!}b-;8UH-z z=vi~0myHIN@zI<-OC4p+QcfJbbIHM?d6#ozFW-+CN}*0W>aM9S?NVKGse{K*Y`jk_ zm@~Xxd9jdQYIs0Bc^?yaZx9>UezhJF-f6YT&!XuKvf?#hUpLTA;x3xVR~pPsW|@d~ zg<dNj$qBYy{E6eg{FIB4*bf#5O6HQ57|rOM<nhf(9N!AI@_Loe`+0%k^~oC1{7;7c z>E8roF&cup^eAXXCcNkTBodQrgzk&EUI-L8&toImE)2F8QeC~akvrQDV|UJ6Y*LeZ zhr3ABACFw$yj*h{zmdAK9|o`4Xh0+Nu_+f1aOQPr`{w3?2CEhOstJ<1wh*(_!a6a> z0n+|2eYc+miSvFJH)CKLe7c3C2o!}yqBc7<;5t}fk@R(E@nK%$)4j{L()JSAWd!5g z&b{ku<6FORMy%Y0s{2>g_`O@tX$x`+sFsC0hOY4EhPq8b`zZ2uR+~^DN9p<|+kIB8 z5P?ILWRkv>f^upUEV3&=C3N9Y^tbArWB}*LeEG0ALW@#L6BhZscd-3_#+MJ7Ql18% zBcnE*K16ddQYXm}E1~Bmy3ezsF_wE;%qCkiKCBO$6S~g#s(0Zw1zQKkKP;5-x(g~y zU2FZuJZ{AsHRR>P?n_rL^Y?L97>EHH66*~n#sXc_Q9et|-)n!!np`h@aR`VEUFPZp z@i2y0DDAdtn>C;9pFFm>`Pi@t67*nBW#`fc#fOZPr$p~SC}hDXvo^k7Bbnq(IP-TW zF-3X}&4)bsO)7PnuDbKQWR=XA!Qu7LKDW|k1QU$3L;fxnvHF_2XS-sk^k<fE{lxtQ zJ!8vDCc_7Aa%G3&&QOj#5~i!`I)wM4cC8kT?tVp?bt{r;QkZ9L=hF%K&?UvYNCN#L z9_H1N8pXx@RRPi|c1`$)BoSX##9~B6Vi>*9iJOcDHYC>h%E7#P<@`#jMjaFD9oEp^ z+r{AkN?=48U20g_2!Zi^1>Nw<l<cOPORn&$-0^LiX`k?PFE-Z%97l@T?;HB4ik1{e zO_oJ`lda)OV7GkeiDA;mWOspU0@P>9Tlt%Py9og#GEm*|l-5TWN^P#{0C%@zkJH>O z=<y{^xhK5;l#OjzkM96X)h_DPF5=9#vfnNDut%N;tG8VG)MfSiZkfjLUZuBqjymjE z`Xj%uoAMJaDq@jEmY4%`+2`_fp~s{U8YrF&%jUOg!DfWUnF>^4Uf1mg$(WX<dHGD& z$IpwHFltF>o!xH=2YKmKlaD>;>crlpchqd-)hr48-t;KomY$=si_D;EkN8xYTj+zW z*L!qt#M-Y6qw8StLER`v6-wO-UN0VQ8J*7F@@M?Nq$Z7H9i<=VCOIXtl#CTBx4up+ zX4cwG!T7GKyhGT#GT~Ivi0=6+&d<xxNG9l_P`5{9`a>WnbPCy<a#rrXKgWJ(;v;U2 zzixeN2BjHU0S)ACnha21wXojSnXF?`Hp^7hZf|rfY|2t>SGA2BaPYA<u40c@<>Ev@ z<i)Y`%fN-3hjW=&LnjR<l?3o(T!IUJzzokx=l$iZPrD>#)NA*~2|m<~&e`$Yz7LkC zi4u*j!yW>D0@ne!-C`8~jt`BXLc?Tfot33tsqswcj>|Ty8_?EG^Od*^6kVnxW<;N* z+#mY#rF+?JB<fd>>Y-keOoTv_vV`=ESb~e*R0I8p_`FNz5@4MG$zWXx`j<;Xvk(is z1jrx!fMzStS^`7FJ0KY52Q(bN{zD*QLQ}bnI3opLx`DrG6YKpB_9_3gX_)$fO~)%3 zf%Yo#@A+arT`e3(tnmP$GlT?ir@Q&??@fZe7eExu_X~l&S9$&q!8|Gco7pM|A7lgJ zHJXB>6>TnnH;MoI&3k?D19hN8MI&_ikT91NXLpE8Mdt(KxAe?xj|0ke>8|IeT5G(+ zhU4HhYG9|9Tex5oAb$VDsG<3MP1XoNCAQiDhR~-7f|1`%lSODP+&iH4y)p=Rul%JU z7_eTT;kpa}T@pd9-`xC)nOUeiN8pFdj^Cmxo1n*Vz@kt37ZCYB_-*)b&jkECLHVg} zq2z%F4)a4<_A%hg!BLU(=H@6y1^3299@y9C@)w5i2=E%A`;pcq`3u5WV8>T`V}Y+j zA?IgWmp6>u&3|iz{%cc#c^)QnuoXSH^yFHo8?iLQ=6C}BmjC|QW#|ET#e)1#rui_u zlM(<Az+dnxINooT_v^m1S#ZMGecw3SKYO12a(dl8@OKh6+;`~(h@fIMj{YGyJ4y%s zGJ;nmCjd|Can}hPG&Sdq<epb*fF9RLUEUCt@O-`bW^BF+km|~v;_zK(AaptCPf9uT zU&GNe9m%3pguWsxuxWZ`LBQ<$H+B5#436_0jyu;lhew0Z>0AF09BxT&;U&HS#CDp= z0n{DZ6O*v7z9K1~M_EcJv5)o<n<t=tK#24qu;?%tcRWzW5VK$*@C2X-Bz$xS44m$p z@$>2loz-xt#bEU(rUyM4YnOpZW7B_B{|G|y)UUz#*PNHX3z~l%^aj90j)&Zu+pemQ zbNzq#`to=v-|qj>rbr?pVhUwT%36|9vd2XBZ7RtYvXkX56=g{XMV3N#Q<h|%>>=4H z`@SzT)?sGuewUt4==*%0-ygkR6Xw3J<y_~y&pGdNuKiCJgVN>$50Hl^wQ+z90XkRw zfVg31#qGBy>;$ggV@?tb-6RJSbqk>~;bIPVAY!{uQ)1=}=D4_tlY=LZne))yX<FBP zrJD~TZz8x+9w=v?5&?z^O%8Pwf18G{5aYo89+VT2XktJcNbmW)B9>Qo!Zaw7Z1=^C z#2S#hvr?+w$5z#}jAa0C><5vKIAt7~fCUM9pE#&aWrI;jI_)h4DsRDM-!=|-963x+ zczqH4q0%#LT#&GiQ~$OFzD5*Ta4<Lg`oQt?4tl8kqu}36?TrY<pIK>a+h@={98nou z84)FBorK=?d}Y{F#B^6MD0SGjh?SjNxxV-V(OXL$U(j-ba0S=362@aOY@sX~du~>b zxr3+*%Yt1i?f?Ej6xv#5KoH-QT*0Jw56;+Rnd0xWUuZJ3R9`;pv@;n>QU-yO(l~G< zNtk!su(q`QF9fm)>O@XiGd_^A+dd-yDS3kb)4Mqg4@Lt^7AJ#~9NV|9PS~^UMSR<) zt*a`JaO~*19n17$DnB$MMWNxNbL~1s0NVcK$ZE{O9?*HJo*d-xl4=e#91T2Wi@S?` z98qh{C*rBrq;)88$8UzVY$s@qpXpYi9(I`kza3N!V6b<$8?xcK(kbQKcHbr5hJ#Tr zNng@9+TzuXgP}##fho@LJ;0eovk}b)^JnGo{X@b*&Zv(TUDUz3UaC693npl;F4`Yv z5o#gn7i{EB^DdbNBGAl~6CjjxeDm_~vuhFDC%>QhF?Cj5YpzqI*tRI^Q(vQEyZBpj z*wVvBQ4@wCe|>oO30?Zf+WaaS#a>C$HM@CcbKe*SzA^6TsZBN?i#xQ0eAd<Iw~RXE zhAvx8sEX)p31VwszF;ZV9lejMH8X3*mQkl$jPXgVTYJLw=(}OG=aerNt=JGjH~t;u zvv|M9r95QmB9ggp?j<`LZ0(R(+p>O^DJ?_jEa$ldyNi-V*+xnZiVDZW82#5XprE6w zuQasAed9wvHK)XcTJ=}Cs?V(!dCk5h7e!ExiQY{RN_t#2@&jBCZIs7!R;K-urdCNX zs-tA;G=D*Bs8wR}c`b)AbF4S;kMc}P@ZHLUNI&Vrg(i>E+**e?8lRaFkb$R8mb8jR zyLd@-8EV*>9{XHWV8K=Bw&rt;khOM37GlHG&lHhPTK+;X%`RgCInQ(yJDLjz%?S%T z2bor^*w?Tc(w^&>6B55=tu*_-STb|Pj^Dpq-iBSikm-b2BXPxUofr+SITP2zzV<$L zC+`fT6V9g2=pWd5DpQ>GoV=Q2mz6-nCDI#0V2{yIBJKv^(4^Op@OtelvwL4|gbQeo zqKVpx<LW{3tmVn#?)+udZ_dYe3X243h3j2T^lDxCO39YCcPEKY_0z+ghHj2S5$VqE zH<>iMjEyZ=G`kb3PK8NJN?`5A_HiA162p}7T6?#P1a);>H)E~0z%+^pWEpUNoFc8l z(uR0~)BKSy>vx{r70%jSl=qTgBJaAA)Rtl5exoAHk}Hx{V8-8cR7+PL$#6FJ!_uUe z`lC@tS1WAs_}4s@H2-|wBEZI;Eh;s^geNUk5)Q|ne1CkDctqXUSYRb6R5e2IV0^|} zBKGiFvT*iW))ltSnqW4vKK^vv0R2ukM>G+WOf>KSiNhi6ktq=?1JWfMJKB7*>eAPs z52}7Td8U*E_B6X!0#cRK9C*{g`HBmSg{}df?!yhd6%hj2mNI)I_2`nK4a40>KNPCo zYjh%@Pt_lH;hShy;B?YCVS!aJ5hCy~K0h2TaJHn&Cw1PUwJ1ipNMbD}s$JjUw0&eq z6y=n(+P7@&2#sXFiZU(j^Qj8iso!4C6^t7=jE1F34CDJWvsD~5hi^8K6$k7NsS(EI z@Imj3(xy21Ls18bBIddgUQ+CSpK{t}ZRbrCStc!+!<amt4!GS~Ab);;ZTtfz(zMO< z0=}-z)7bcsGC}vLctEdd6|Zt$*jL}Fxhds)-~1bn`=9h@bUa>3rJYEVVJz=jQC-TH z<eRD>#&_DCU$S0vI$Z1>&clqu&f2QwF7YTj=qNg%qAf}13H59;Xq+$V-S>uD^Wa;3 zspq0etnJ}Rb?K=JZ`y6|Yb70!tb%Bq>;ek={Y#I!EwImC`0{KRVw{SQ&=I{7vA)nh z?b_*L`}IMgyxsngbH4K0?q=*wPZ9S)h6rO#5H7Q~d_k6OEk5gIme_ys(G=bOg}i}~ zNVM;m#le6SmOB5TK?8B++lG##FL<7K?eU*Y8t!D(z|u6om5XA-y1Wk}qluqvb#!eh z;SqkRn3_3}2(wczj8FDU51Y98%hZYA`miimonfyYJ`JpxfwNY+)c1_Yk8f#2k`w~@ z1)^LEkSosll}JX<i?~RgHeIP;-&wW1imp?ins_?K^iOj=X}Xwe{*65V!BS84Gx8BJ z0k5jqR?Pq2Qv*Z&gP2g`a{tLp>N}N)NxS4zmUbu74b;SB6R~GsDxbBf`KtJnb+2FZ zM24W-XjS<8q!~UzCyiA6FT@E-=9(8<*z`%8my~0lb9m}g20px!K6O)FoF5a4&2_VS z9`qp#`)TE4g4#9z_mkh5-;HV}WD4Xs(*sav8T`X>DAHeMpAlJ{=z-5sX+I9_DM>W2 zD9H1XXnPX#?ea)Q1_O`efk;80%cA?w2q=-C6XWo4L(ojY&`<b?r#1dS>f31=0}UIG zyVq1%LxvV_nJzRixV<^`F(POsG(#Rz7GKK*H*T<7$L+C|Vev%a+gCmUHr~Nm@ikkg z`dy!2G#&^z#dxAE%il%dVx@$CCb(&rmm&1<UH2n#PhWSk4o@f|)uTp&1y=5jw#@dX zmtt#AWTW0nA74k?&mXmaPV1MGAuf<R#jh9}B)PAuOVgPr?4G^Ni4)9wuLqYgMGBGu zAlkwqAeHn7Q58f9%8_nQ*uM6>ofe^3M>=2cUb1@Mbn+TV`)rzY0rU<EDefI)Fk$f* zgwl%Wa*AbiOfyl*PM{aQYwY0Oh*Fub=B<VnsFBOPP)Ph<kT~0frWV`BkaY(%NIBVQ zQ!IDLqN7>b?p%5Ct1mST-G9S3^!BS64s3&}>H+1h_niV#R9z39qW)%f&EfLm!<sy& zzb|LlWB$JZtK`<Nygq{H>Lq+hdm=8c^<tZOBgIeVSoP<|-4XS%;dnalK&XsKW_8x| zAI|2Ee>j_we>Y7V5Z;D(k=qdNqy-jx{@WG8#n_jRu154JSl{EmV{{{Ym^;quFDO>t zfg2Ha23{6Dxk2YIESBD55#|<pJ)`S;Na7b8Wzmq}$o!TM)*tZs<Oer?As#{#3J*lK zq2B+7V^}WyW9Vn6znLX{6x-<soM#(JdAwUIph>`y9|Lrb1+eU`xal=&we4t4!`QU? zl6=TQ={NOx$<q0&=A^tv-Ae<Qwfnyi51^SgDi-pw)&4~i{RmVJD2JP{-zoPRHOl%1 z%;1>Xr<9!@%y;Uygv_;V!?t3;d)eMW?f-zmyIsAwXIwUiJ9vY}N!XKTB*?v`;SGNg zG-;u2YmM5%q|7bNvPVZum<wA^7^@hjytZkKsw=3a{Z7r<ZoVb|x&QkjhSS1_CRPZU z#W^2tU(48Ko-z~(Gxi>WL6b5{6rwdtxDvT=1f-&}!a+!(-0&ULSOHSfIr^@J2NKea zOOtN<H(%{exN~nGQcjk&O(%}b#nw+I1jDdDYVaU%fX4%&)un5D8Xp6m<L~ZkRywC& zr*yfwG+7oVKDo2&qqcDcbuw2nI5hcJfCJ$N*m-vzh)qX>OVhnTrK3^fVkW2*aYC;V z0ol{)Id&)U-IdSH_-V#)hjCkalO?K$@&FQ*9|xMJkrnVDClX)=Iy=~{22e}o5eC~X zATWYMXo<$LHl};CAEaEHt3|35f&I4yx)DVW*qaRq%k2&sX6vPN=xccdj<>B&`NI4+ ze%#Ex;XKkrE&Bg^t=wS$8l54S3Wd(a`J0}Ffp4%&RLp`v#lBu{K_A)4CY@yRi9%j7 z8ATz9Q6>Km66WgGPOJ(OPxAVUc?1*r(KE}t96y>9hX=(qMq`up@^<|8)_!dB)<*uN zWEOK7DpMm1Wf*~CUdTfA>ATBVLPb?z!3!s;s%Go~u>Nvjz_Dk+?lv103;$Pn?d$Nq zZqPQb7@DIWHNtLf^G`I>1U}wZx!VCjKi3E@E(l4LzXNSaisH73exC*@T{e(v&8kk* zshWG3YL)L`rDLBiFUk@aiFo0aCQQ5{j$0c>QYcJRuZ`^<<3{!&Nwef>mTh}#IawH< z?3c-MwQWRDBvfBpbw8&f*8_=^jK<9!+fc#Vq)F6sn;(|H>|rUbAz*CD>J%h#-Z7v0 z{QNSYXgsxs7OPRDb-tY<`Neebr*TR<oOgZOYmHmD>}bV8r*|EDMa9_|&Eq_|98Yi6 z4*H_^2b3b)vvN5+H1I;<%i$H>eLs!K+V~~S?z%wjVJGVWjqr!Nm3AGx1X#ZKZ*dGD z{&Jh>0qR;DE8@s;`oJSteYWHQbu|t>X8c|jHgxh+hICFF=9}Pm+@Mf1Y8+4>=6_}x zpbu%jygibqJOkn(+<i3_C(4G?nzYiy_o+y(giLgSvjaGU*cB6ExJ=k+^0QKoonxtM zurSd^(R++cGX@R5^yY(_TJgXYrbqdr)=Z5$QoU@3RM9iD{Pp$4GORYN9PTKChQB01 zxBeLn^0E(bu+qp%fh2h?^%vq1_b)`<b5J#@IOIp6L(xI_MIx{o5#sA0!nCW3h#3-W z{5jM)FdhVp5Fc3Mx;X_o5zR20r@4=O=*=VpwWBtiF)0tFHF~7O-1$@$#mkkCDVe{H zTlj_8w%%Sgq@!*ZhF0?NlFE3NvT43Mggg1^Zgq5Qe6}Wn9sKl9PQO3wz*m0NX4Y1; zWSE{lhV|3}kEWL$V$@mm`MLTJ;vA<9^3EHktEs<XdMh@iE)uGCU9C|kbhPNla&{dV zwO>Xg$!M4T(cIhZQgh<`-(CHE>{kpI^Xgh`R2oh;<`f%~WW1Z<g9TCZRY-RD#DqrH zTbtdPS(yZ%WtnE$%JasnU$4#)dYE^I8&%fr5dMZUDI*Dz#R)9ssQsR-oJT?HmU#|K zpH}!VrqUXO=TAo|<6Lrz4UAvj4-9#RaggW9zgHe2XzS0vnqIRup8$iM$&<&<;0A>K zaC^N^O-HP9auICv270NhI9XedIIku8py-XG_2!OY@=A(3^W7_zA~gjSIFh?p9Gk77 z!|-YN8+0%?jzf4hGT9AT)`{8giKLn6<1EM}$h`G}%m-%$$_X~PU$b_(wAOef?d1&} z^AM`F`pS7v+7E8|PTrIHJV8A;r+(u5frR&OA4i2Ns$0dTF*?4C8jsAjO7qOD<tYe$ z{0-bKNT3(4ZXGl#J!q7cXu3B=Dr;S(EnUk;#bhcf^@xDx`1^77wBU)j87zsHyuXMN zTP#knTZwIg`KNUcyM*YG6{TD&F-N*izGl+-G}ZOa$g;EfN8GVzv9m}0LPa|F9gh$` zxfn@610uk{3rQq<F?A+cl9Ez<J)P*PLpU)OljU}@b0viEe7vQvO-!m#eLeEc?EV*` z>=v%C53eZ;9KTD}Cpmk!JsW=6hBCMNF}(7;U1({#{^@e2ojTznNe>&CSeTPb;-JJk zJ?}an<kMyMT>DeFnIDBi^6S^WiUdzNVp#eVlCD(P^GZ`fhc~U~c}mOxLDJWgKFt&5 z(^9WWV1DAaqTT7Mkl?~bPHZ*!)M<I5_rzRmsJ#8r5cmE_GkDMCI695*i!2InrduL~ zc;#EIW8>zA>n~s}H8s@(aV{@!o}A*Zc|n8)tMD#pfghggstwPoIx0W6jVDspbjKcB z@@s^>EJ^IKY>9rPm9V$I*Y-_mBqbg`T1%1v_ZNkcu6b8PvG|k46DOp!17r8+5+hyH z+|nwlEo^7|j5Ws=E9YG;lPt?Sl*!@wv0d)<?qNzrHy^u0W!Cdla33&!k=mUwEiqpX zl=*m>T)c3d(Eq?&!a6v9^6jl|N1^AD@mAICbHfeqY7jo>R{N`X$}y)e*$<%h<Lr7J z2m8y>NcbzzX&SgLow`=_lGbH4;VS5WG|RhQW2-%LeUuh!#n6Ld-4}cp;{AJ1_1egn z<Yf5v_DC0@vYk7th1oo13Dh&F_i$a;o`gY)pklT>!E@Ep!wyPPMMWkm+XxzT>-QKa zMT+#Mtz8Rv`uwd!Q;$)-Jx2`=QzrG(j_%eyV&G{;jBZNW^~$sZ0!}Y)9v;?oPE8|> zS*cIG8+&=Hq?S*vc39^4K&f))7yP(jS;?(YHZAY0$z*}Wu!?;BviCh&<|u1H&AcPi z%d1uNKkHW%DX+xoB!pRkmsBy7-<exK+Oj0f;Av05`puht&i)VuN$opP@{ISnvQ8iW z7tI?am2Z10EgBzpc~^Ujwt0#;)8d}VT+AlW%|DI1W^>V-hgjlN#C~2zBPoHBZ5S+Y z;=+>(_naeCy!RQH?Y$3!P-z%hjS_>hhWt}WhU60k1O?nXqR^5cJN6mp`M@gX%$ShE z?3RJgv0ch<4U1I0uH?V6yIouo(ZJ*6&RY;UF5Jxx(<&3V%Q&e%5gkcqx+d4DeLb%a zP6wzybEZwryJ%Y8nSO85Ir(Q_>T{MS$1JX}P?<vl14`LdXBfIYt8E6=xgR+&N1Nhb zx!+u~IIpY4tc0@0*Iv>M3p8!qJGpz76KkSHDXxFYuhnp-jcEM{pYv9eX=M5qH>X~W zUfKtZ#9>}nv9}s^G3F{FVcNpGmrROCT;461gSR{FWN3Ok4I=8Q*Jg6nOx1{aSQC8{ z<^6#<uMhSfq3Q|Xl&r2LjauaIx{qdZV^{1Xv)o9vBOuFSPxvkj)f;^RwQa_qpUls` zs`9X7m&o<R9gqDP#eL)jd!p`HcMo$S?+U>1K2vZ9=A-$SqQ(c%j{fq)QO@7rt$wtM zjAaq&>#mzU;=u0auX&lNU(7+Kri*p&AOo;8yP$!zxIA20FMG8CkAd*xV!QWl^ObUy zY@u%JEn~#0)NJ+8sly~&Q;F5<JTuwfUxl<Ys3JaNU&S#H?N7<u-e*;$xgMN7`bAwN zlOsB6h5R8qx4<yG%U%uhigJh!^C-vrRQa9PHTwoqn=6Kl64V3VFikovnB<+i9>n%h zV<a^BTz%BNR9;pU&qWexh#ufx3;O+TUefNs+;>rfzA?$g`My2I#HyS5%Eq>pFG?yS z{fjzObr;%Q*HS{~7P@#1mKsb~LQ4qdGr0G}11p1y&#_S&;vE4)nKBX#T}nATrA`Kq zMRFNG__XLgM@yU)doFkL3NE&v2{llN`D9+z__L#b#hifof_Y>vpHuLuFuTnZPa*Yn z8_S(}i9V$2O{kn*tiD`*P+qXoKjcNicnNx?nDTC}SPK?vwpqH!btgOLld1>1i`zTW zIU{A(Smpf=7xwA@RO(%cemuk<E4utjnDN}sbAjg3)lZ~ezVBfxQ%+{KHL*3QwW5r@ zG48qB8>JXC<c;}KdSc*Sdq2Hq#n72oqtD*5IV7n_=eD_<>Rd}WuX4zypxI<z?2x9) zS4stb{(0#sj3-UA(}r!J7jL*V)HT+1et8zHlig;!OXI<!exoZ*b&x}F-p<F7-||BD zCEDAc`Y89!Eq^%p5xD%Nz0<Gs!Vi<^yK<6GGCVabcQsow7)D12sT(SvIDY4e=h{fO zNJ?(NiI@Z`oTM|FczS+T*BXD4{%5};9#t{F@8@3LVC@q8T#%=2-dX9JCp~;W7e`5i zmnYAM9M<z$vzOL598`QrkCNw!$s)@%d+ts-@i6RCZd3)jGqlgSl+818HYMQXP2LC% zyTsU0vjsAxH9I$xt%l9b-IbAO8tBX^b1#8~U!L#ADDT(awy|FGH2a{0BfRsfea%RY z7`)D<YPY9~=j$dklht&5Vh&)eHJSNa)y3aT<i;l{oK2W9mU^+0XRV@=?n*JI#215h z2w#xd*kErlH`EaH?6C=d=TQrTH>Kwy=p<$H4vSVkv75i6G$@pELGjc1#Pbqg2C7F< zTsRBlqyAj_XNes$VxE@>u|Y$rxzl@3OUtFz5ad)kupNiQBtn$A<lKcS;@xeAdUK!j zJUT|R1S)v(TK#~t%p%R7;YOoMM_&QjQ<^3JoQgvGy)9KT&(HQ<xL^_8SP=f2d44Wy zFVB2TCAJ`3X)*Zm$NZ=8QO}zNE%-^0glg$H^|5=A{*Xmbe;4k=aB+oT&8?Kq`gDN+ zb-Nyqlh|7J3+lQN&u1lB%y`0VkaiXBhxHXoPdle#Ezb`LTq@HH=5c3wX?Ikbm+$;_ zqmOUKPwZylPYaDQ`Tx0Xp3mMoe!+Q<PsDW;vW+i2mN~qL)H}Y5$S|{(6F8pSrrp2g zVeC}@t27we^m4>8+9mk}A?%8GC~5S-QD1h2J&M<t!JUyB2HU)hzd*Ju1JM+g`}7N; z0}7zjT*SXkt_!U^bBlT(@Bg79bS7)x5!R#h4ua?{cM#E<A}+kP2ejfU0^Y<)0Lr%< zF15JI``SzNW_F@SPRbp<@%G5AGpOsbN0XR=kG<CyWc#E6SjW8!-tKB)5|DU#`Vx{J zV5)`^Nq}gajcvqk{sr@D4Vgi(lFh6h?x^4Y?JDXceQ+-<_l4FhYVCk@>yv57KN604 z*!%>RT7$0=Tl_&W<u(T_cyrmTr@uQ!Zw~-v1~eX+x*y&a^(4dMR?N4M&;iEekSh7V zM*2WhaC;2s18ys@pz}U1?Wcu=Ws;R9bJVGMZB0d<kgqGi8?^Y}-k=EC4rHUw;ih|_ z2{pa;lJuVqL+%|UC92^o3qK0F7k8kcTLQ^j4ld$b)}t@Dh2>ue1X!K4$gSU$Bmh77 zom|GjSa0c)I0={Wi!vZ9J@LO^4X!`l&g4#Pw;dper?f6b_6vM|;m5Afw0FwuYsUQM zx&tTJfRh;{!<UeXKs4AuVsYCJCbv3y^zI>u+sHHDe9EyQCc71P_JDZf|Hl;;n)<6o z*V&bmt7Vzi{glvqQyxODz0YH_S2w)he+2Q&t>DdWS{#uSxlvG?GNrotaRQOmDhq}t zo=<ULuIjXmhrY6P!v!>m0zkB&<^^H4wf*@NM}zuIGz$oQnc=3RI*bv_EpA9ydK^Rm z64rDjjd>q}&S~GF^(j<1!ghlI?l&AvTmmu*c;inTom<?t)4CDN=>zj?`=RcWaCo>u zDF|7-sG(%rP0Df@15Pv(`4XU27{;xSQ{(}$-0cx8n~z#<T=yTEKww<~NH73iD*y}T zDAH;8AV^8KC%MUc<dYe@VNDy76!g;-?+3?b3Vs7Ax)C)H6v6^Nbc?<d?io_cB@V9{ zyrz_2(+}<~769KZX?M%?&?Pe^z?wn?(D)4Fk6W5|HWB={z{!()x<~?nmo&cC>0!kD zr!n{3>-`&ajyw=m`@`N&i~7@m+X<n2Vq*d6a1=+(sIiTM35dtM0O6NTaafD$^~M6L z4g?bk(QpxT$<X=P)@LV#4$E_BxUZYC0$<LzrmaB{=51gSbX=ALH5<J_uqI#t!5V0d z<bBf(ptsuH{xxZ&|1ZRfW?nz#9NNTM?<TJI?F5dy^*e6Fabp?6z%snf9B5pljawh; z|E8;Lgnfh>ISow*Kxd7$ZQUQ502d&#tW=tSn(0iK#vNFSQJEuEc=Hfs08iy-)Xf4n zjj-~SSj+0Gh9;8|byNZ*iP>96Ja^#apn(WZT0HM_5JW+;xnZh0LIX<FhcS;7aryZQ zp)H0^_?48(^T!8!3U6NGF?Yy0UULNbjwtsu{SiTxxAGG2%(P=}JLPM+Lu`y!6?e3F zgNSsb@8bSDj*|ONSypuAao&laZVt%RneFSoU{^2bP~6yceF$4lky|mxug=usSFg1% zV;Ltqbqnu&9BO2kTC6v-_sr?;w{j^o%PrIVetw?qXUBm2u58My#J7Qg^P`eyJh=(D z>S+2sWV9WlzMEO``S<l1ZqKXvh4biGu77U1LDC+n8&iyJn`+IgY`QITq~j3nSMAc& z50ppVOhnA^I{7RmJuik^VbM9-#<uIqN2R5^{apz?Kh#$AZA?EFzX)&_BIjD~{gg;$ z=Dv%18u_zkV0^|7@UK1)=}9--=oJYrxOl~*GDyOnbfzW?-JG7ww?of6p)cl67?reT z9yvI>zk=OZBY6E{z;I946Nj3kr7;Gxt*P2|?0xBK?TI5VdET{Yh30cb79FX1Ej;F2 z1GA65h|rZ|)+y!pFo3(X1<ti4o$RKJTHQ+$SZWRA=Bs8JW*St9b{L5pnV&Vso7VL0 z>sUe^B_@>Luaw%8J`h7AM2%q+`sN}9n!I%!R9RW9XX8l;eUO<Op?Ud(&R3+7cPow& z7JwTtyFrnv7-7CjO|jBoE)O3&Xe+}>^l8$+^zO0~$>W?;?cKY5UGCDeQic?s9;4!X zsxC{Rs4koC`;Fb^gZ)8H=x);*B#WmPAy}8_MMAl8TGL*12M*?)M@A7HD?<zQ6;j@B zCWP_~BVHDlUr3Cg)f;g)uM|9rUVIZ3_oW*U7mzi-5Ues(L~B{1;c({VVWVsU&UcP{ z$s^tJ6RL~lURJ<(Zv#hB!)@5e@nYVG*KePgD?}*L@uKL4lPk$5LT_2ubPJqwtB-hN zDp=>{%%@RYz?jOKWqCRJ%~*j}!A&7ZeaLA3@#3i=JC-LelT;7sSYG$bP30?(;O#1Z zvzB^J=cV&KpO@z9hcq7rsVl9;#*i*}(i5khPp6X3c`CPy8HX5#<1v*=LvRc3bx^Tm zmnBQYpv|(!)4p4<TvA{QcR828j`_Y-*C!}bdQdQkuAmsM+|4CEN>r4<;ms9WrFGv= zch!dW-ziD6UiswPbtn9t&sc{g&kMsZ-i;2O*_E{4bXG8rrFjQYN4%SHte(7C#FJC2 z*K!G{XG`;RCPbHu#t~}APoMO!qupaax+^!7;i$&vZnhK##{D<)o1tuAbIEr<#H|<; zIx>gQhskEG#U~sc2PxD>#X+-9)6;_1NzJ*II+j62Jd8&5(gb7rP>;{EKaVqDGJYYH zYnmIT%$fqKu;!`}j!Ar}b%(85-cb5`TQ$PR#R)2+*X<&HA)*O%p5p54nSPbG+Dui> zrlKt6y0u(V(XoM{SmkpHJ*8a&%v@<{rR}G6G%1-lTVq2E1uN}Nm>!(>l~z4~duKGc z9ucpWXiy!@QP4V+8*=(>QI4<pCw~%2pl@G8VLcc6Uc-glPib+Ifc<19<jtT@3>cii z`v#}v`wP!FXWAJPu9zJ4yV@eHku+8KGU`)EN|yrn^Xq5wOFi@}{TaE<k1~wj<e~VH z<Q4G=1G=+S1OTrqkWWjw3y3#UWu1Z#PejqZJf4>+YS`-B9gyz)%uXm&)#7IU>kRYA z8%mnhdN+z5U%FTWD3W+1y;Dn#M6E9B3M5mI^<ZX6^3!=~(Ui&$d)Y|W+6}b}o-^{e z_j2Wyw!9TO%O1-skf!>OOd0m5n;^=j45ZXCXx*zlZ>(IU5^yd0o?0DUujZJ>YEP(o zsNzJ=#egqk1!IQ}?Rr@tkdm%r`_l5VzneDyPY)?U2K8$J4moeuxInj=f%~($n6+Jo zQ0Hz~yRy^f9WdEk-SB7O1?<3~WzBYAV2=g|KqKdQNx&w=`!{3?gV4oS2lOh4`Cej< zmfh`vo&lL5p2%Tp%2Tj|>n|q4huUXRIrQXEOdxWF%kURsO75KwYw#czpv+07rG>cF zRH(BMw{B%FB+sNX{^|yCnxdUgYNQCpWChe<rZRDT(4^5UVjGQ9N8Xw!3}0>pc_I2m zCaSh(02$;e`xkbA43#sqblk|<MFteIzhJH*rEicphf@%#OV~9UFt2iG;&S}<|2()5 z1!$2p>!6p79gJHk1I<`ih<;#lKRWC3mUYPohbhqPBajUhCeVU8e#8b3_phBu{~PM+ z`14^uod4dh1YW9^Pw_}zV7`-XiCozC30O`i_;N-Qm60DXuOk;Fn^8*)#$FDbg5Xb= z`a!O%NgiRofqB~8c;QQ$P$w8clg=kWWEpCKCJZj6hkf!s%I?15Ha%xR!2sG-=K3bP z6Eq?LJHpPn4?Js=!dU?A0$ZYk2CThx#!d~{-R8suSXL6b@v4qoK~xoTf$H-*FYKF3 zRkN{hrT|mE$iq@RlL7zrbJhmL-1;xL|Jdu0PK0a3MHw9(2W_9_U9G4O;@I^)AV1)# zYibE<#X=weN3>5M>@h#sIw?Ev0K%MLLd!BcEr$&Ih5FCK5n@!sE@jsztW`eaK#|>@ zVYm>`a47`|U_1&)(p>Ot0}}Q*0}@WoRbVnwl<<!9l;{SDJ+WL5_HiFM!eJG>vL_F8 z?D&bB_n+`Q4&a^kZ)7;F`QRLOhRzy(m;?1Q=M3hn9qv=g(>XjdM{_E9SD<rd-CwPM z%}I`6YVm=n)m~(G6pFIzCK&0oKPZMnF=kI+ljjUAA53sClK)P{987tb2{lRBk%n@M z=>d0-1vw|YDBj#e&Aj;wtef}uapg9d&eShW@*jd0_V15vZ{40aMCAOhDRQ`^r~K%j zY}Nm1%#;1~l~QxI-dI87pNTNd14R4Ps-FTpI_sSH1A?TT0J6s4?O(0hfT`10+QFgp zdF}l@yEeHl4aechrSHGAQ$H6gg9Q$a56IHgDM97{q4ohLRclqIyL&(RnLP^dd)HOP zlE`}N?}EupSpAlbrv!OI{;I_A$YFE;M>~4yR{)-kTNw)mV$KT97tTWi$^8qVxGp4I z9~S^EExMYp8}$f-)BT+qE^YyMkPEbAi%h?O+1kPS`nOXHDlI2t_;qewqHWU_n70AY zz7MrZy?}N4It*>fj>hIn7J*K;7u4EvNrHQAPS0~c*BhppXz)pHYU|(HrSQ(}#LdpF zoxEwiqI*9pu`|l1NbQioLmty(FV1J&|EtCB(fKX$*(STz8|9)ltqOUe9NJYy#nItr z=XgvrLCVk;{96K@&PW*;&=P0~xm>dzRT+O^+e_~dUj|w6T~|g~oXufjaLhe=tDvqA zFS*_wx2n6|ME%LT71-lS^i$9puo8)M1Dc86PAtZ;hV9eaq+Z~ocj0Hey>dH4YuRT# z@bxdv&fVDieJ{2DAaJ*ydy7I%x`XpDCp{gsP@ZFvWub{xrx8$9lYqz}v$sALs0$yG zT1>dmP;fyjD64mg(%fW$%!aCr*@%5svB!z7yG-<r=LvoldbKskg@Y@ZSfV-h2smo< zzcYRtWpQgV#TDDgq2WfK<Hj&Vpxj0RFJ=MPNX7~p0P*~Vgg)G0Y_U1G9T``FAxoRE zgTGi`w&4Z(JvX_$|0k|I6E8VD_H5A07RBl2<J{&cPN-3A{rN1rSzE%WB898if7fey zhly<d8}GD*2wwLqaSPTcdT8do8*uH^`Z!a^tD7^`ou>4Ar^3*BwWz#yW7KsV&4SA3 zQ${B)+n$bza^`APPZI0I7cQ5yg4TcYp30_xz<h`hktg{~8bi|K(A6mDUJ0P6f;w#8 zSmQJX*9%ig(KKlZyblnw+Sp=o5@Z#Lv~B~ur*4mDp1EiVs7q4OrOTf|msk7yj+AQ` z5Qs?=bNTxpzMu1rQaM+^6CVC%$v6`C>FFA1KHPUO2cyya3vnNK-298?1#nv&P_;nm zv6HVfz3=coWg+Pz1wAZ26H=8<wrbXr<6Yr+Sm^ZJOZH&)Rh}1L6Yh2wHyNEXt%b^? zhzTpgGyOyZ69h>zdW;eWvtayO?5ZVg;HGN(>ia`!a67ahZ2<k0z$e2A_nqB1bf}*a z)9HPZ)gz=5Z-r)GPYGR8agm9<SZSu6^G#c&EltJNQLXS}5lA{m=Y{InOx}ioV#F(> zpP=yQ#;0)~aXw_%;rX9}gMR*=*Fnsn_~3NxaeRMS_eCrIyuAr$jTu~%_3L*c#r4iA z3b1p35*)%3&&hp(a{8Yvl>iiy9a&-Li#(7w3;e-oQmWW2cR9<VLCro!cL$RIeLeT@ zMdX~Y=Fhk2fhsS16_?B7eUkD97J?fJW0Smu`X4Rlb(}gp=hakWo?<wA(9mZjML)yV z%!wwAZP-Px$aL`$e87mfjI0(W3Q#{KA5WSJZA>PzTz#Y*q%-VQgg)+3YZgdtR%`ew z;ZAwz4Vp_o_I;ODt%AGyyO{6y_ot>!LeTY=)WF)ek#!js4aN$!TF(K*gr^nfN?c{^ z3DjliuJJ09W9?+^Ar!c-zRg+4d(1G%PNS5#7~de1a4KwHVyHV(Q%F=SUg_IN=)l?W zsKyRp>EpW4l^rW9z;&H}w7fS{bVUzaD(QA#+i%srW?@g85+;;2EO_u4HDF-_vz3Nf zm6yUEdP6uYN<SkwG=9!<uC}2@)ll(*rJ3Co&-(N*v9JWqdb>VFaJD8pSCasTNoEG9 zPv7%IU_~!s{BT4!Y4Kl(dYXw`;3-$s=;)m3GA7m!W~(yYysbd28Z1uT83KY;G(*$R zI#DB{&Y+&Ad#y8aD=Gi?x$Qyy_qqL-AK?x7Mk{|IM1CQ@09?Vt*$E(1oHz=98(Pzt z?i!zYO)%AMGa;#UmU1-E3OossIpbzcy^|Wg#f*ko$A={;yS+Jq${N^EET;sc@yX-| zAX?#$TjDm*au|YMLj%B8gwk7wL5)#yL=hA@<zFW~=gsLU+FnXc<|M`mSK6@<Pg1v& zPuQ5hH?YJph}kHNjoHmMoU}>Zoz#<kRB_jL^&YAtwajDT--!M2Ww8F8^psaE;Zm*H zFT=B98xwGj26{a?2Sx?7%)brurMCsBMxB<-evh^8cLJtpQ@JN>*${gz-AltUEYEO5 z&PN3k<8oQ+kL)s<{eCv?Ylq^N>1e|X_ZO`5E@$~}M;&hmyA6Xl*Rt}IqV|51m#aIo z@9XfAcuNO55Gcz7sOiFA2yR&bk@LksI}xBby_&aB!RIu-of#c=Gs{9EhJv&&BP<a= z*(8+9sMl!5ahrBhD;BVsUd-a!aZ87cgSLY#0YeU?)~6ERv7zcK&(CYe{B*l^Kw12U z7F#6wku7Q(7@DO+vVdjs?^C`;ZM`*;(h>j$I47lEih6fe8}c(LljuAzYt>PPbZT~# z(qWq+B3C4)s|NlSS%X`r3-^S;zSjzEweaX{TreMx+ghu?%&gbL@8&<OqMVZgCGsUd zCWcg|bBW$a-TA_58*HeZ#w@UawZi(rchdhF+6U)enbqs<JSDBOu@*+BYq^h5(@;_5 zZ|mM1v|B>}th@u*wjfYtvk5-=;4dAx33f>e!8ntNDqyhoU2}#(xAqIeuPqT;F9*WE z93hvH(?F<e6X;a@UqaxvrO75=J@DxRbo&<~(Otf{Q81>UT67IrS1>gp4J@WG22W3k z0(8X9{rVf%MBzts*Do&iT7|H3Tlo9Eym9#JIST!#A!ZZWOvMF3BM0M_@wjzbT_ITx z?AEZ-Gco#8_l-VDdDW?j&Thy?#STc;`ei0P4M2$ZH?-~qoh$=%!y2<h7Y!2=wveI= zAR``6o@9&3B(vyBi165d!*XZi)AsVjl^3En(V7!wdq0o(0}HM2MJ@oXt;uOBz8x0w z88_<UpH?f(TS0Nu<P|h&;@ZyX00K4H7l>Dqi;O37@h58jt&wlhe$e(n>dLqMZw?mh zdBE3<CS9x{;~~;W^NL6C+5l+CSQ~#Jxg5E$8v}ZAe9sdUF3<QdF%@>^ddX+gM;*DI zMAUdT)PMN_(x@MF#G9jEAA@3?HlGg~leQ-pJb9}*px~hU#!;44>pI+M4-yzicumYJ zb{KX;Q5GzAT7TJIcjZ`0tK;MT?Mpo08BE}!A^gu^W$80;tk72gjXSmByo7NeKo`T{ zb>`@yYW-Y?kTa%ZSQ-b9CTf0p)XXY!5&U{SO!4O&YWxxKPfk7%a&v{{bifY*C^C+* z@7g6&lOelsrS9$8sWa4j3g>0$*Jk2Yo8qZE0m3N*nst;1wNXzs|DSRy$;L;p2QOtw zum?5p`ub&PAQ6)@!I*`vo~JP#`-MpP7qp)67#z)isiFe6Rx+*Z>xOBxNpcLdFTBsY z<?rGLegdelvfCVQ!DkGt{Dz+54s1^173YmoE0LmZh`1U|DI=#p`Lj)(_I6@iyY^_4 z9uZ5@dqqyXd;Mo!nB4JDBar>lCkT6RJjuRU(DcW&a91N=eQ^)J=O@iXHnu#C@@EsM z!nYMo6<~6Dphjx&Z8c|;!)AU8K__k`JKn3I&O}%?UtI)p5nBs1B8~K)?LXhY1-LUC zkEEmBX)h;z3D||b*kHQ3&s5<h19r>#s5$I%272=awr)aK8GDZSeoGsMj!esP&@nas zvlj{ftU2FK$?c%G-7PP|hWqxZqibpRl6gxUk>((F5K9ld+9-tCe<9T@#X;UOVgERe z;#;v)MD##Wrm41vJFf&mMB!uQBO#tprMi$TC8HvQez=1EOJs>B5>N}Cc8b$KgpUy2 z3ADqR?;}$uyiazByLT(#NtiO;?wcPT-qMZma9LwP>z=wEcHW4J)x12fHL#EuYZBz0 zoE&+sj(MV&UwxloZg|_EP`9!rOObKDCGwz#Ne$up0B;%E$3zI)Nxlv)o<J(Lb?ka$ z*of~`cMj!63MRb&T+21WTo<}ikiUX|XEa<!2}4cfd&+{V-py|Uq>(1`5uF3<z8QRp z66OzEK}3njUx<^UE9t)wAw#WjZT=I~GJ9+Km+3B?h22p%R86UPqz+!ZeW}na-&ZV1 zpv6X~<$}kv(yAmweX$@Whq}~~fjcxjclR6}D>mIcIp_m#EH25^FYrpf5g7aNtgQEZ z!}~n7^A|PN0TkMk3b(pqsBi<R;6Tx1JEqhQ4WS?8_3~<Hx7~hDd*0@hS=&&tn>MSF zROZVjzBLuvT2_gj++=2w0@(~8dW+!TQc>b;`p-sd$$(<CM>;Kgz_3GyeWR!{$A_0` z^Lj5btXxvM9?>Kq?EANNSLToE5VzWgj$Vg9oi}^>=EGFvm3i1$%6NHt#P!}km@dKJ z;)=@t`c*{&4dx$VN<V`%QU}D<<I&jlx&H4(sDFN*g);CpZ_hI3y0!n?CEBvF2mBiU zssyp+aSJ;GDB!F&1zGCY`5w91d`nqR&@4OSo;M+VOG#y!S8ui3F5G;JYqeEte`QnZ zz2jv9qCHJ}P5?c&c?7mgaL*=KDVX2AbEnbT@SV%1;9wZ`ZRx={;1zy73UxZe3c2Ke zj$k&~q+TMF@$do9(R0_snwqGE{#_5AcKa(+{ngEu-?Ss%o!ji1;R#>FnwoR$=6n9i zP$zDk`T&iHldW^iW|~(IAm}<r#i%O&)o$$3oxqV9RI$Gc5>$u#K@(}5)Ta6uU*`n} z4Lk{z7r}Eq_(x<-B2X(iW*B4*Zb22u)t|y^XHa-eQ2Q^XAUJctF<^TlIz6gVR3_bF z^3Xx^TYF9D#SJ%QS$2O`MS1@M)gyQ}2r06Sly1sVhnr=K5aZs_dl`~udIOYUSvIlj ze{@>#AB%9{@9WzQO+<9!G@b#QCQBtC`h6@Tcyk{SB8Bt-)YNy9cLHA|LwNHSwnRQw znbz^3*FS^E=JVI6FUgDk(QRAHim3lPxtv0Hc*s)a#f$OA>rY08>5Muzjl+W@e<hVu z|7ch%;F)lR3fUex5fm=#nX{j2AquqHdcSE2IR9)d!{3dbUDn@xl!<nD#uaMQgP^~j z+sU$J{da>*V{pOmd%d0~Zu|UzX4Yv3^f410sff#;(`Lo!*LH#+?QvNa5ihkPGVeiZ zG>qU!_Kk)MGR-=Y0|2NN>0fTJKK+1Z((`~)P8>CC5IkzszP&G)7F9vmltt~bn1(E? z_j#T!!x6BU3h?EE!pV(7T+Rs47oZvUA`9GU+>Uo;YeX*ocSo>44`3q8DmU9YK%;TX z8_8{O@7WGeH{Xex5)6pnQPK_X11<%>1fcEB6cOcqA<#PEgW_}jc-7!FW$er(2-bF& zqt@@|VuhuFUOg=cmo$RZ$DNnB0FX?^;WZtg!J&Sn`!7UP`w*6Lp;y=c_IlI`mdLM2 zPBa7!(<5-q&}83KvCh93a<Dp|1%rviFv=o%x+IHc7?$Ay)(f<+UcKtO5l`;6xE;g^ zdJ*XP=Y>sKz4rrgQxCiKA%R{5_-X-)1)P2``W}#2Hv5;vvf6-;eBck%0_YIdRl6+y zS8f>$vYb$Rvag$$2pWU+W(Xez6#*srfT8~c;keO<&Du>AzB~?p&R=A12Y)>32~^E- zM-Z(yT=Snw*|~fH-nR;JR75qBxCL9(<YA3zPTr5f+U<F?x4y0NOH2xdzy88~n~`e< z$@TF?V8k6eTWmOLAQH;ueMpwaTeS|z_uwtN#{JC0g>DwLy`@i2s?3)(oE_p(sy=g6 z>8&2$-YT4Xo_BgYJp!Poa58OEsR&#b%iW&XoVzBD+c&vj&2~D;O`o&*c(+hX!ZDt; z2*TGQ`mf))g?#*{*LGvx_v3ZZUFKh8*oennNm7=pI$d#3rPUm1`Y&0gUdAZ+_ZeD$ zSY`0Jt@Dz#(n?#7-?evPH}owE5e*F6iy$1u6+I@{oNFV~dcDxvqyM0R<yY=gyv53| z^+xCt>VmqZ$3vdeUlbjevLinRn=oAna_H?>hei*F<wxaDJ6#<b-vd77fg0b=0XwMt zL_E}dy$Od$UIPcf05!<igqld5z!2$Epar2D%|`vYnV@<lX%&cI$a$G`3=B2SZS42G z!j}vNQ<8_9OcWhLzD-3Q^xem|>p|U7!5ho$52P2UhTbNt!Fjkov92kVuQMujWyYoc z=oR^V)Iu2)ZqM9pfm_)72{;6_<kUbQME^NdM<WAp8wnr)72^HB{Z|6W3Es<NnGLjX zJ=pMg|1rU2(5m7Q2uo*;gJ1^}RnDL1u*yjBRM~`)(f^X@$yUf9q87gVclVAzUuN>W zie6!^L6zgy4`xXeA-6a5XhUeN>yn=c;id;sOUJKm|Bo!kcXVn3FGv_|9D>qRARR{u zlCuwiqCNXhdM7-6Dvo%(aecmfC;ZKHh-Kj;_W4G}2M}|&lbZ}c#^>Yt@54&Gq?6ro zYp$S)M>RS%txJ*YV}qOSMZHKDLjckLt98fp^a}!p?DrldUwrs>O8N7}A4n+U2@<%9 zTysOM({z9bWc*Iv2%y)A8$YPp8080P7iCqWSm1JGcTl#{K=B9eg9p$B?+O*yKLd>d zwFKIED4<ibFd%Wn90pVk{5Y@e8WlMEe*VgE*=OKlO<3zr|5yIUTya~%Cm)>kiV1){ z4g=xCz63bsi7OLT83-oS^!%>dQZ%m0i%Bq4Xs|wVf{G`8+#mXJ7dQT0n6$#T^YJz+ z5bDp51;aY#Y>%~@`?LF9(JfCaKzK7z{b)Ag?Z!gm3m6j7g5*3;hE+kC799e!(WcOF zL)Ule4nBQX*rH>d5}|my!YLrEv#rDL&m%Y96b6KYFpi=)BkS_u3LsuG_E7&vJsIIU zIR#IISSx85ubA7quf!jC?msBg>j92ODDdDa6gOYH69RYVP1=D_8v7c}*tBceNFQ3N z?+~9B`;|C}^Q)QjAAUlOZ!oJf*QobxV;LDs{uzbfg(?Pl%f#0<rh5I~Gz!n=4#y5X z5KqZEG~0<=Tm$zOh<O#R!q5r8vh#f)1?pe7HJG%p&}BI^)g&i9H_^B#`0*ItLsxf& zU3hIV0H*jO1_gU@1ChvuF!aw>xIX_e1o}-H@ov5sZ1q6Y{opdYJ#a5-KN%wAR5uRV z9ID{t%kN|{^x@l4=6bu|DsPd^F8r2g6|1R_(wahVcV`^)!}O?|RyQVdlXOn+tL@^i z)t6Y#*6mbGmh%(+mU{cA^Ib0`75juEYSpw+4jSre3KwtB-p<Nee~0>SgM?F&ks^x1 zbdkh-LT3$%89wdZk3;rX!n}m{nd#G+gKC_8YGOS-eGQ_N*SPE+F@5j7u9`B_g@eI@ zfY&Jq(}93=0+Et}!png@sEZ=*M=@y)b{(v<8vT(LR*|IqJ%&ZV(W#R={JgQ_Wi=C# z>|z5KMO$NoBh?s1Bz<pMb6}hK+;;&>Wd-}r2$hx4q8v3OqH{N}@JL3e6pHbVrGJRQ zTLnYi!z=N?8K=X6PMFp%sGo~4o%z{ROt<7p@Xd!lp64yYej#3_b;De{pb70Dke+b` z!7YwBEtu@RxbWPcVhr#Qke^2esEGv}$PJNsg-~m{Kw$T;0w*RHY994&{)Hf_8$b(L z!NjMu@Dsg$GA~4a;iXF=kQy6o=waEF{^d&TLdqT-kzvE}IWh7~a(0k}zB2fIVz^1j zCv}On#R^H(0OPfzAZupjfnH*VV69eAAKOWx`G_NOgH9gwAZX={a$f^>G%^4f0to<Q z8lZ4*0BFkn!2qvA6EMn3n0&AsoZt6(x!4Ctyw%bts}=Cwnpwenug^u;9q2kNO`5zM zybOx0lE65@aJp%yaQ(r3-dfF=bdWx1gz(l#3a9QYc;(|!koXV)>frYRfP6hz0ZY(f z_!LMY>7ps#zYwW9k{cxYm9k~be9b)StS5LNrzq5EHz8<?lgq<Ch{IcD9OCMQdvLkE zsr==JMDMm8qHV*<;;Jx{E}1Rz7ebLh(f|_e3q~C-2EbMSdblYH50uhfr1r)hEUs_w zNxF{ukNBwkM|{A5<$wXLiz<2Nxf85`wz=i*<k?!1TJH_I^5Ke(WIL1BEl-fs^Awej zaT}|c|7R63^4=eyii<!pGB8W-P;M}M$OR&&C%{MMVY*x3>GhOE2p^pTVmQXg>0yBR zbwqzpb?`q^75WR*q%Rrj5~;x6X3CkDj<0l4l4ir)C?lL4xpc8^!z$uno*P2144%72 zN!c7V^xqGb=3UuK30!XMI%E_!WScrvPuW?qzMH5d&cQf)tBt3PLG#K%3HI8BRmI~k z14q*0d2$q2E5Y^Ix%@D5et899XU*OW&qkt>DIpWzE?*Ni>OM67t&!xdF4Kq`TPV`a zg{%8$fP6_<#N|MKVz>toyNu*?A7j95+)t@bnMpq~E7ywO)EA2}Fnqes6&&KG(V4n5 zPXzlh@Hz%48*mhMcOVB9*NH$Jv_Y7=3`zO?A5kwy5&0Tt__5yKx|T4^xpu5moLu<E zr+M_Jz0fAb`p$fLyt?646^K$OI$M9&+e=@~?(Nl$9HW7QAZyG{sO+fpC2&*iBPHS_ zA$Zs%WKh4fmXexcxvmz_aQO6~#ixh+6UQ{z;zB-~wx$rV@R4bl?gm)UhK-Gi`kx!c zFV?@d7YJ9U6MU;EjlvnX0;cdtH-g%nk_%aiQ5`V$l(Y<Iok9)ic6>w)UI8;oMJ_>5 z9unRwgj>7*Z!>MI6I`N)nb2gm5Fo&-zXjOmw*W)s&%o0)Q4{dS?TzGvhS0+M;AH|Z zr0D<z`=Cho*0HO@t8tO7P^R5#kOWTe(8~Rd@zm`=-328dN`cNYY`Fj`@jK!0jTpQ& zHHFje_gQTJ=PY87KqLGu%NLD50flfZz;1m2SBFypX<OVt2XbAyzYA>Jz9KZN-66jE z1tN-z3!hNN*`d08P9AVo<a~IS86968*79%Ti(}HAU?KCx5yg4o;OUhFuqwOrfieIJ z@W~+{=ZWB+2#R+bL_7un;;5SNzfAEpECi6nNZcHNJAx889WmTbpmpdBBWg|hSAI~E zvJQqlyMrHnYuZ@)QlN$`+D~Sy0;?HGQrhUFU=B`oA*!?Sk2bLVk2YBFF8mFVBrxls zV;KV`8TDIZu~0ZMzgMYuW0j^Q4T<}}Ak*aT1vrx&y;~y^-(UW%dPLlZm8F~E(qD+S zzxN|nOm~8w%!eh43&X*~zvoN$XTHqfQAuFF<c;|r|2^Mr8f8;2mu)qq!)b}3A3%7k z;xY6`xCfKl-ht>jEq&3-WqC4&4+_x*6O081ssp_)jq8&8XOBR341=56FhSr*efZCj zs-x+|W5`e9;Lpf0!Da5>%E=7Kd>thbg^$kNP)=GMG6?XM^rkNALdqwcrL|cf^=oQB zpon76wFEOk*#2b!5KS5ghJVPUQ;3xDabxCnpsF_Xks5duFv7Thj4*0Y9x4N%cnLz~ z(ZhRzVqLqgN`Wv-|K|aI&u}BV?cph)0WN=@qA0d{?*t=AYw4>7wkY3j_WXr6L;Oy( zw=&D7V@~D)aom_|@VYd%3uy0s^*|n*e<2vCpr&+oU}ONY4Mny?IAk&T-F9XcPW#`! z*?JnVTZrOsg+{>nMOp6JA#rMQuwGWn6lm3F7y}I9AonlC<qSLc5GYobN&P)xA?DT9 z-+PPR*xOAsup!GEdkbdVOom&55kC&L90)V<>Ddi^F9`<Q4>F_3-&kOPZ9N&@>s;CY ziJJ1Nrc!v+)FjP&H&m7ugR=|nf`Dz10N@}MYfX6tw2}{kOpRg$2jI?px9L#eb>brE zsXqW_jeVXweL*`?z0~?9SNDZULh>8WQW5>4$2VBBv~#4<996g7?lOByPvy3&EX7D^ zj94X%#g$m6oU2iE|C}l8ST%HXoW5NDqES~duK`o0n?`VM%35N=T=~?>SaDtpf2rS4 z9`giCp?46+NNTeDSa(Lou?TCkpkC31h--TM+()RMQU}K7v23ErC9mfrZQ;$FK#^^B zBeajoYi~11s?;$0nwE1$TlW}MY&d2U*6yF%=En%c{Xx{$srZqDJrhk0jx=A#U5wip zy-j<XsJZ1`p_|ztv3w3U|07{W0<$>ILLq^Q2GAICw=$4;YTy+b{Kzt|`o41iv3=M1 zXIBy7fwQ~jY~3=j`6i&7!w7B_-$d=I$0<dMz=4zV)0+OzP{i{G=9l_&DLJb}E;fta zcfICb#~<+apWAW>6#vYVZ|57}hd#Ltyc$Qaw?fX$!9!nL8n5cx9K2F}k5)nA&CSn4 z1&!O^s1Nf2{Y6&;7<=Mb*EiqkQQ_F=m{CDj*~oRq=Ie|Sihsspr^x?!X&?~v5g}_Z zPk!)LnmK{@N!HefW9(1qG^d|BpdF4lHY?qUT$%1)BZHfn*buX`sNojj^)XysV#?OX z_#K<nIbBO5%u~Ptum_F{-;NkS|Kl*<)>H$t_4yjr_H0^s0}(`sfB<HhuQl!A*q{xT zf~DWQqwLML4jHn$&4?ASY%*MkUCvag2LZT;Xo@ptTK4G1`&c|LfM`xSv<fDa_5E|> zUv#w{2}R(c%FuKe#I3323K1rSDGqic7CRq-G6%%Ad%FhGOTbzC=K}Tz$c<VCX6y#> zZ5%FQOVt7RbdAmk7;RH+@U{GM%)+i<P|M(4t7|wYytYFT)G|mRS~p53qCkfb=n}xh zP-=!s_xArFwyw+46W>f4fxF&--@G5Yb%D9A?y&IMPN>@qRwz(Gkc8oVF#zN2#V3Ec zczSriuEtB<5KSwc({IstjNjgo5`9*!!K$g6<FSZHs4vgjo$vsk?A#Eq1zhg@Ozp`8 zN;u1`AbxgC<Sx6kW3tGhnIW4*k8#drqN{E(P$<Xiq1E68F{)L1G86C0IDWjEB18WO zw+B1=8Q<ej;hHvWXr2!@zdSvfulI)AT_a~l-z{=Wb&{-J`^eg5(14Re4&G>xo<$F$ zD^Y{ig>9(ea%dfF?E1c}!w+Zxm-WH~)GkbV7o+A!(foxd<Znah9?Am5%W1eMe=)1; zbBrS_Cy80^#l;}BH&!rfJ99%jdJz5p+WXQ#sJr&zu|(EM_H`;mNh*|tQL-hCWM3=E zG9g=*WTa5G2}L2J5Xur+vShMvN%ri!A=`{~Ff+Z!{XBQZ^Zf7sxA)WgeyQ`D8NYMR zb*^*m%LYv?Wf_#&DaZiWLhXofobm(8+Ce_lYzXC>Jsr=s0Rnj7$^R;sgiQM5bqHW? zBw$Dn>&af$6G*dNDRPj>?Fy<`>P99#!qiVcX!IPdm)L+iZaZJ+hc06GBjj!;urP8D zrw_m`jYwe;pH-ei3cx3>0@NKs?99N`{nA7BgD=aQ1u#?h0?ARK?)*pxV4BQsv%O2s zFv^#D%HysGa}{t<RLvZvlJPR6FQ~8ZHAmd+&KNSi-4UT-x4k`c*JB1`m$Tk<_06dD z2K4+2icFJ1_YnY}wgTu}2g-6c*J1!2l&|h_eGe|d@mb0jAYlE_y}Lr=|KPrHuwAGW zjydZ>03$@eg(POyL#Br<!A1>pKy2m0Uq1DeWELzw3IqZGD+4OXL%=yM-I0gGYN$^v zx*;L;-glE8am#nW%yj_ivN<6M0bCaal+5His9YkTP<tsrd{q4js1)JDb3MkBIm4Fr z>r>5_UsmtayXep%k!zL?SmCxw=sY7SglIsK0q|)Calcum5OCjjzA-8exhmi9bGYlr zm9~mbySbAcp*X2jKw5lS0lm^(N@jx+HCL=R8R|EGLn2^!^fY#bZCe=?C;{P^-cLC% z1Rn7S+6PjUpD#exvoJ)h!raZh@CkTTAqh}CD%<^Wp!BMPAYE|t4^p_j&VMQGcA?b1 zzjQn7h7-C&^vzfv(ztSXi4W+$x@1W@6orG#OL>?_!GeB1qMM)*o(&mQmvdE>KR)SI z`b?i+arfykuD0VgQSQ&&0o~aFvLzglTNc1Gz^55G#{+gv%(dm@WgI`IU|Vrd^KMou z`+23%*33Jo@io}yFYNbitIt1g_Zsyf^vEB_W@$=k#4T`}1e{Rd{z+xYfB;;690vYL zene3t0iLw;aP$QiO^-vL(QA|q_xxnM_OT2B%{!CmY#`TBooU(+z=Zzp4Z@6~f_hDl z3+T;pKFg!=+llvqqE-P>G2NxU6Xn(bs(?I$NRSL#*v=uKcZQjO@koTEpe>7hR=sN$ z(1rY4tad_1Av?g$@D`;g-3Bii{$Vr-*|pnlmnU5wd~Y8JtCzfZ@+_S|6Yja$y?VnN zM^T=~4!cZ9(n(PEOCu?P&<!Z)1oCJ2-awC``=O6}wzZ(L(KRJ2)9s@cBCLWS*Bz|7 z4(w8YJ0Cz_7piZJyX5-WWD&8Hs;-;y@=aPL4QJ^#yVLXuyrh5y)Bp^WhnA(r=Bv~X zhDRmoG&(H0a-7GClU94hq6|A9Hb~GLYwiMd&UTRB-wuG%<XymqkHXqe(}J*Bio9DW zWZb$&py{kS_Abo<R%XNwVBi1SBES1$8LQn$ohk0VYGv6g7TwI}Ap9v-%nccp(+_U( zGxcKfUF%6zK#KpjTP>60$Q!Tmwp-xN6yMeJCOydwjkAk}@X<pcTIv9J3(yGSYOzZ~ zG2|LRdem?K*fYGdsv;$2R<p^JfnS8D6WXUgz;6V&)_3;ETW;5#7L*}-!8iAAQ=pyu zynC~i1U>=QyG4<EN}hj=u_M^<&92J7poXqdZX~wL990g2%1iooZ{2VaIyivz%C>vo zVE07BM0BM=G)d)Mo|JVZYKaGMKGe%(wqdGM{tv2R>$vF|8JDhuO7F|Mroqt2dzSwI zO4I~SMJ<yKgY9$w$rYhp+`0Ywy-45et_h=J-mJF9qp6{)liHQs3D;(<m$-l)nEMz& zDhT5F&l?AHlj<Vo*p{nhGaPV)20Ykv&+sdJ7;XkBp$5Z$VO(xryIga>q|5QFsL5Dy zA0gbanp^R4JH!mpPF**A7rIq-7YYta=toyy`F!%i!+RQE7*r)z50~zCNkGs$w`=!B zW7HX)KG<_Ce%9y-;!x97%gvy#3gZLu*j*cX@6QB4X8^+2P%GTop^)9%&1&TU4WWZ> zC@O5h<ITVIl1%Cp$+|AxjFA<Sxm_Rv&kWK`P0jv`w3Up`X0Dd?6m+F7kC}u$_J8=0 zPU(T}9aI(kEdcy!cn=8)-R14rb={4+<+h}ybb(5GrO4zR+PRT8qZxv_fHe9<0&qSc zh<*zkBC0~TozvFb85(3Hvq`Zb4azHm+ouRgXKf9l_VU?E(EA&<QBNP!wp+fJq<ge2 z0RP+7U7A6XO101^-k+6_s@L-LToP#M8ZwO?_*WBFx)>^di8W;(nRjd3M*&*Y-X21( zZ>l%X#NMaZd!1S0=DM299v?ahA3fQv3`~<1@XZxel}(m!EpYgvR;Ou{w&^w4XAaWT zb8eVcg=yNFuV5C<<y|zUm!~uFWFF&i6aK=0Sc#XaMnOG4I~8o;qKBpq5uS=|#4++I z=`ltd@AT3#f{#MmP$mEBylg0~?}h)6Rul~})xa&Q*d#rt`O#*PPCBeupJlyX4=UE9 ziI+XmCfG$Z<qMD>>Pf!lKy3fZ-##r@l2CgY@A#GbF#|$oa-yr1sJ3FgpaXn8+ufcU zyLY;98DU8WH)YnvfwKfO<$ZLuBim2j(Np=P$t6CCMZvq3$!w)kz#H|r-efh50xXZS z0PakYd9%D^0+?-E3Z-_hIGG}Q`dZo@yvkUw3Fj8xb?wP^Kvls2(zyNI@cBww9yq6; zfAw5eoB{Tjoh|Fbg9;K1kS}9(37MYF6Sv$X>5O)Ok42GvsSkpti;7i)S^gZ$tf|tG zly8A{+Fl9+t`hFsr5Cz)Eh2^b$RVawOgiW0a*aT6jK`+!yVj!&y&{v1Uo*fGcTOKn zN|hOYg&Hv3k(hU8-jQ9Ny4og9HGwvFSlJo5Xuh>s+EGK8`iS-DMfL(%@MC9-SGbEU z)-v5F+)>hU&uA}|^?%!lbVtt^qIS*Qy^~uGmbJ6vUqder5=^}dZ$$0gqlAr%>Dd4! zG1WaWR5%Y-3RkB9m3|pClvd?eVFly^P{15%Qmv=q(@Ya{@7w)bIyy%C7nruHKVJu0 z%?CJzQ`n|kW@{YKTae?w!>x^=R9Kjn*W*%HmfD_M#P?3&ZrG!6yWCM#z5-)YK(GA6 z$c_K%<&EBjfZt}YOB~x`&J3y6%P>YJSnh*l($bz7zoV9?Hu&id<zxT7?d>y%{F=_W zMzs`8s>uUn0S7S~UKDWhM2<=esP8|e6Uz?=%<Qi|&Aaig%!!wBo@aO!c-RehLBll8 z|4^q#*(<qzYni5pp_(ObcNMs3I{x{x$x?Ico<cunBJb#LNLcBy3K@cD%~zi~?$AEn z5~+br*U)do5>U1V3-!AY{~&z1*+og^miffS^IPGtrU0e4yDX|eWu(3-@6FN%l6YR+ zDM+SwlX*FGeZV~tbqO+U|Ie^EPL;p;=n{%}Y5iT!sRNbh<_%vQyut84X~3>t9cI`a zTzOxSX5%s%<}xoVtrhiB!w;at1W-Ugr$1w0OWC>npuX=8ehBX7<sY2u&A;?G$7o}J z-bgsOb{tBl?Ekg^MRnOhjf&me9GKnzkm$@$-bkH~L5tblh*R{Z4&xe{!a=J+fzF); zZ2cE0V$b=^xP_ZF!{A@eisYe&VPxMP5stQ(&PTR`fU>~v!Ib~orQlgXZ_xLHlvvb3 zBjn3cf=J3ci^g<wAAbvW8?@W4k-JCXR20|Kv%x!;qSo<%6TpUBf(j`M?s$aB>@z!@ zo$-M`?K?T*VdYVUO&V39mj9IuY5s>@&dZ=YuBt;i_&Fq^<D1I~=W|a*H<`1k;h)T& z^HIrjUD`hvL@0Dot<9qS3E}!P$8oq_ecYrU_Ws#cAlN6pE!~9yyC`BZE0!LpzkhO9 zO?+P`itrW*1V0Bo;zU($44i(3Sm9QqK5$`6>hxCNzxhKXS5ITI03SuBItsGN+WFU3 zj_?SPRg+mSNr6M4qC%R~bP+POg4$pKx>ipUNE9v$ZNyajTD_+G#nUYDik4q=U_<cv zEjt4Dw(PpYeb|$z0_P*C#t^9v|9zD2BJ2c_Cw`XWd{)17aMJWgw+uOxl|1FA40}kY z$r(3@C|j8zCGC`E_dVt5bM0Thp2}UnVoyi67Dbdv^ONb!E|g(EM-E;;pmwk^BIM3G z_vGqA(gAXY65Tj?lQ)7yyX5d~xb(#>1})$}T7zGzMfCQcC*UcaMD=kb@-qwiRQud~ z?7j#7&uQLlNfFToZR&mJ&u$&<YmsXc35t7@)yhw7HYF5&?92J2a2s|^D}_01TI#2Y zkbi5u^+Tnzo@qtdVm)Vy>W<j41iYG<=dMCx=w!;zW}HL%i{=+}RFVffTbC79SbF4W zDtpd=(k)w$C?y!2RWm?%`V|E8;LN><(<vEB-l3Ckq(at|gS>nGg!w~mZ08`Cji87` zVDWK9y~>F!X$9Vd`r7)fFj9*LsANLb9;K5idcT0Car;lbsCu5vzQXr}tZEXJg97_0 zOJgVHY`pN?Vw^Lz_c-m>^R(IyF<naXiz(aC+hZ2FNKppTMvg8i!Zf;RNyw)t|G2O7 z1<B5p2#vnlA#=^@eqQ<`@FR@;E6GsBx7maCW?x=Zn+}?2#T<mx=q*gxrCsPY4imi8 z9lb{_<YowD>j%BzQ2(FOxZGYqKOii^wjOQh(M<z8(OBV*N%QCs5Tg%%z--Prra`Ft zjFcSRmAWe60SsI2RtkVSPs3-?APmpkpXxz%kBhe;*{OBw0~yKir(A6TP1|<(-wP_E z<}Z>h5O`g-?qC~wj;QXj!Vi-|q<=$(;0;{@Uq-PT>_B8I2L;U8n}9KFuP2m<2M#AV zX!07AGYdk_&_KwaeFU66hd-M^wryUEZ+=4zunVD{r(vr)l<9Om8mkmMX3Y_ARh$gv z_O4?rOVG19c9rRLmOVmPG0`~A*cOjlOE1QsPNZ-VR3hZR-HXoeYjLhV=U(;ffh1il zIi-T#VVFg}9~nVwe46)Hox;S~lOKPTEJ(F{7$`r#b(y3>427u?76S&eSSVxO6AUKU zzD=^!A(>vR7U73LdX=?czg3^yqi=x|^RW<w>%6J}CVw$hUYGH5C+oG_?Sf1>B8R6f zPIGM;NraV~XAwJ09@v;ADm`{mzZ#@I2g$X?!{*4TM5!vTQrcfj&C2BB7xHxjP7_It zojo*Jq<vrTgIgF5@93uQHD?xbY*F#&=e_`$PTKu1TVXhSwHmm3<mdV#dMYhND|^f| z;&8*ij$=y8yf2NC&(BHK{ok>io*i{z|CK$~tb4+ovZkekXByFH<7GwMD3~g3^ho$Q zVV{C-IePap{KPc7_hu+0d$%psJo@{>e)^*PBcc%v>SxT_Jq0aKyGy5xW;IV7Q82n3 z4w~a8wHYlG2wOG%(qZ|)r0<<7iGP0Xp-2~<>CiEadxg&qCCWZmVC;~i5%!u{XKeq> zyx6e-O@l}SKY@@2!1#mrb2o{oDaS%n>L}}ES}GGP61^+18uDY?CjD}EN|sS;1kkf2 zc**zCWTp=S0nAj{S0$TN4*`nX7VuL_NPzD^InNCOdZJm0<1fGe_y8iMR)t*>c{B|q zOgf_n_TI)6wI2^)zzXUJncGJ3+}(EA)q&l?&Jbq|-+)=nog%G^cJ|_Eg|Qe4XBcJ! zkEU$Nqk-8P=JuBo<S7hsMpe1GgYYyCpxWI|N3fsIPVP!8@$Pdie;c5h<5s3iM^Wt_ zUTx500KJ>nFw0~K@{&|L2pz^k**M1phc0$#MckgAFP=nP?yj!{kpl7X$Q7T$*S9H# zhH<xCt28uA-dl5&>p+8?#qiL;@zeK;TEbqnVSUbR#;&X-L;bMWg7!Jv&fIj9(cn`{ zTJ=F!hss+m@GiBveZGSCF~Jz<E4eZU>!z;4vo%K)W?nEBdQV{q_4OlYCP&3t?RQOi z*;R^xbxIM{@JpNH<3k|?uX;GG60nr9R=(epr(<wNZ>EDjs^j`sePwo_E8);jVfnau zPJFX=jAd6j$DYANsZ!H|+1xYNR}Z*{E|r<{63T+ThtAr#NQ*x8;*r?w`DjKmA{SC< z?c=(W#5?4V+{w8q+3wg~=Me(0fx6U(f>RoKT>)wLGtUL*$n9t8B-A!@+%|%rVfaK~ zZC=O2_5cMGtAFLNppx<R_}AzV+hBfPH^F+7X6SV!h8VOZO*&7sQX@92mlZvY<QX|& z-%8r+YL!B;TdN>ukL7X?6bF~99gj;_J13s@C5N$zokpT0SC{-!<@6BgetxGvE6JSW z7n^*7a&~7_#J7|{=;vQ-5Wf=q@Cc>`&Npar9^auFV-zpOFm<ZZuW$|t4D-SI<V^VV zb2x>bd0pmbeN{VAaGWv1?<nqYrC*v#WhDHvafEmES`j%11U>OM8VP`^5G>v<X<CpD zCK|eD@DQ*knNSgCVmjX0+{FJN@ywQTu0i2PANO*0=%rRXV~~<1p&10HJ%&}43L@Ov zUga@0(mZgl_jRd5gu{6#QWm|K(Bh6}>G%_crt{_b$w}T{TOLSlv3p;s9?AXM;<Xk` z5dLT$_Sy8##Yg;4{ik7z@(@4Vcx!-_IME@Cjj`_Dr`~~ro9dc+Zt0)pp8`cnIh_RJ z*MZR?bPKi?+i}cag#>B$KRwOU<Z_Jj43ckBFHsS*j#$opAxYb{7-Fs6v-0{HqU3d2 zar^b7c>zp<dzJ6s%(3vhf(5Oaj(MP2T#yZjI9KF>vvA4V8@_Jm48Q0uXr$S&WjRh+ z?iaJYU1w0|<=!9OBcEpRbLNNTOsvs*gaa3Y*yo_S^{B+tG&8CKYGd>B>#vWek0N8A zv@R<qK8MRRw|<7dHZ3EzImaQ8sL><yeN&vwABqiZ`=Bb1r}BquRStZ4I`8Cn)=TJ_ zc5tNR^AEI@!DFbf$gYsg`Y~y@sqVf90^=>8Uc_toYqM{KOt3*buUXA_$qsAF*N&X2 z)qZs^?r~5Z*QSA4S65^@*IFBY`w{)~#gRHr)i8g!8PdKqKj?PHJDQj8qeG(E_h#}| z$G5%w+UFN)5K$XKr+hY<-5B(tLu^oDC>z`~gx58U4Lp(;{F398#!5esRTgy<`v+?b z0`ETXe}VJ*ch$Hb46P&yUik7TjJ#$KPJIkV@e>8Mpq3k;A)Nrxk<CFPTf8~Nf^CwE zmf`-k76)|zQLpW&;X?%;@C`bkQE(Vd(?NG8=GrVH0{qDv3AmJT#>G9*y~RVm(Hl$I z4#>0sy89js@yc-&t_r?2w{2~yZ6$3-fjx+?1|?JYoMP&j)|!J)yu9)?vq3b+XR`ws zC>TLN3T6hr7)4c<&Vwdo7v|g|pcyjae{O&Tu5()cC(-HM#j{lP>Gn~ROZ1-wbPIFQ z{5YRk9L6_e%(2%1D(fqh7&$<8L=ex<!*QF4tqDUI1FFFSP+cC%&C>S}z>Xh_bWl*K z07UAdM1Nr#_B`%ttskt9Zv?p4uV(k9jmd1#4E%<ChQCZ^-I?e=cX}p;;IY1N%&LX! zvR{5Bn&xxs>^0Dq?QhV2^q>wd+dV62i_(W`UBRq3WH*8E0~Ps_CmR=P*@tAy+o?C1 z2Ye)d*$)1LRamq3&oaxK9)B$`;uHQ*gGOnrq-m!*lL1Y_F0ii3^lGXKz#^R&QXEnv z=J*9Jd^R}ukbko~y-Fr<QzlYLWpm+E#-)<ysjgL;&5=`|R1Oid<pfKVSVkIJUPL4& z*hZh;z`1t4%Agze)YY$7@38ACJQox?G$bq5enuVej1F@=v<}vH@0_mjD6aaGOPYDy zlDx9f$c5uH^+%!3a5KWZ*LX;z^KsrPfrX;>nNvzq_re1{slPZTyONs&cL0sG9SA*D zShmKkQ;rzIQJw3~*E=MbM02`&3nHtN0ONo^#eR~RXTj%c$5{6$aj>;Kmnua@sNh;S z(E5xAjN^J|qP<7E-6EquY#iZ|`kXhrv20b2;r$J9l6fd1h;3IgeD~{=sb!6gtmE1{ z&k&{kf-|$Vz&L*e1+n*i@BL^T8s?M|uPmZr&;5hjxcAGjNU}#VJ4-d@qh{T22&c*M zG>6fd0}(xL5AxL`UOr%Rhwnq(hKrD7qKxa}<tI~}@5XH0NO4JFm+GiE?B6rYt7JKL zKkN&%#%(5+NtQ*&+=49w%CFqwi=AsF1f%-SsdiPc`I$$ao1xU)DlD_Fn?jVjQ`)2V zs;tl~4Od$~{0-UfcWYf6-&~#V*s{;MFmTlG&G+F}Oj9YAXe-kfLwTwOIG<|nJ#sKf z*?nYDkT_cn_-=N`qzR(Sw0<R*ts9GM?b{qSDJ?GQDx?vxP^@E!^`&(s$<fsKA@Jy$ z#Yb^PrKlSCUX)$44@dN%mBpgoU4+OgIKn`ZEdghaV(>;>@L3RjJn-=`jyaXx{p(hj z`8cc=8;a#Fl+wY3#(mOtw`0<|p^S|+WNN+4zPiddXFJ*q>jn0Emu_&2+5EfI*D^)! zL|+ZOd96qsws=xvMinOSjT=Ec@fVy;uTDByob-L(##AX?&n@-t`7D<|ch>kPs?a~= z2I0d<a0p?s`rfaOzOQe$u1{PXJP!(aEpNnc+zdEwJ$=f4=vZF&vEz0=*W0pHOuoWo zdi8{G;WlDhh97dDZbn3;eSh_qXb@W-u4K%UPs?{(x@BplF??n9gKzKa!YA{|5f+G1 zqUcLmoAujWUi<Fvqk#vx`&tgZj(9Qj$^q%?bSTJa<nzP24YB1%Nxt`Q2FUe{t#&83 zTl})(D)F|$7rzV<gPr6%(7KiCFE5R&(-Kd5a0(FEPyN~toSmx5Tnkh7X1Bg+%o-od z<*?S!@2U2>+UTOvdoWo1XZ5#bh(yl9Yh@|s1t<s7c#Q**YT*;hR^$VVR=d;=ZL1%V zr2A0vrF}8I^H$Q->Xj6?+p;+wVq)mh^o~sf0dh<1C+?O4e-GCy`9a|{0ak{0YkWst ziS5Fi#+C^MGa)av5YLv>oZz|KV*Y~NsfqmwjQTn6=c;LRI3iI3kV(+E@^7lF2NSf& z>^sI8sj`vtZmkZ7cv<PmVMIT!yitezj#<QHL!7{_cBIuEs<=&l+o3G|znbK=|0YOW z#R}wYM)ZfuI?PZPJY#_U5oeDcDJ)R}QqIqhU-Pp>Lu>-wmqB+eBvmpDEr^)^C*H<& zT6=7T(*D_<MZ+&Sv*Cby5^5-&iUg;ExGt(zxO!9*ABlN5Qp?c44r=x&Esi@6r*93X z?Q%bb{gK+`s7dn2>16gmmNkOA@Tswr%*o4YZyLp1BT++{pySftz%(Fn0`+F6kuKy0 zHOr0GWrwl7>3;J%&7N^@HDqA}mF?V3-Aq^JA7^HpCK;+^9_SEh<8VeiH#yl9JP!ZM zp}!-2RRb<X9aXm5>r@PVl;ixg#Ju6_vjs@zxDxpBUgcpRxdHACvfHb3D<~|KufSN> zT0Pv00V;(M${7*qFN!bo9@hqz0O*Vv!>g&i((ATX+Bbvew5O`&v)(h;T>EBwy+#<6 zaI1m>1qTk^I()byFJ%01388*XAK(3AoJBr%{HvZhQO{DPs`%d8l(tj<&9{$xS=-be zl_WF_eKY;80uMtK2v*j;c4)6I%`*hfRHL<fzSo|QE7TU3O**exvqbej_x5~Ee4VH! zSvih-lqTT$zAIB(t*_#e{@T^>bbgH!o)*FyDMvo%Xf0)4y1Ha7_$ywb3M1^8#7`6_ zL|Sv&Gfh5-tKpd0KQp%Mq18%3pOg{lu|vmvZ>bKHiunBHe#y|()IA^J;&a7f7&EW1 zisRmgwrbAss_el_PbH+CZq4s??0fE2%s~n`y^#{U$FE}S<o=O;XGL9`;hc9`NndS9 zjKJ%KO~v;@1NT)`B2L#{(v~XGN6X&pYL1Q$8n!Y>K?RxBf4iQRsK$6j-lj#I+v|+T z?YW%EMtk=&*h5#pZ0H-wu95}T^}FeR)Nj3G7PuU#d_^{X-tWxVaG&4^DtOLMXGDg7 z@bw}53F(_tCO2LnT3ACh7Y1$#?K{QC@$9_9y-hNu&}A**oS@|BolN71;;oV3ucQw@ zD;OzVeV8gVeQtm}A|(EJ%Jol5Sw_OyQpH9wXNP`5ZmlpwMj$F)q4*@B(NjdtgEfZP zrp?9*OKF04$Uj&6`WF2|-dr##L9Bxu6<_$A?UtsW1#vyc+8Z{O9+KQykeer~ylm>E z=j-I$5?{D=IQ_94>?w+~f_b{<WG!oHIOe+Q@K=LOx*q-<iCPc~j0l&&lQwy);d>mc zU}yFk=G;Udd$j<8*bP;n@V_CEByD_k&4;ltODp%xFO{EpT~+vse7^fmVO10(o5x(L z7I{gE1gEKoIrha&li!CfzdfX{-byb*GX6xV8fH;C|IYi}>{#)WxzzlQJ6W%9MvpRY zJYE%54&ZK`f#I(qGd+m&BqTn+RX<6duC*x~W3kWG0$V#wl!S&?h})w_og~yO1$Cc0 z#Y$-k4x&mCH-NRzmHb@E&}AHowo)RfzhgC)u8{rp<_WB+e7$BEum9RhjUY@3$L{s; z*^@mH#UyYowy)+EVcyDROOetcP+X;p(EkFq7BX6L|1-B3uiHLI<4jRG&I&)dR+c?D zt3P-#!pm*>)E))>Z&!f-e^JSkz*z$;Lf2VCXN-n8i#jA;rscl4t#iDk*G}mkf9^+$ zH0dZ_;)x1u2F@Tj=9Kfu>D|R7r;MmGm$_9f0=@YgNyu?{FRuO!7E*2_5#c1KBYkDA z|7G%)_Vq)p`X`6-D2IvTHC8f&g*ODvn)O54F1Gbi917tgp|U@32B^#sh4I+06ncDY z3cd>Z^j_cmyUa4%%&0SmC##(x%d^&kekOSF^=i};0nB5Ww@00vO)hF}wZ*&;#pfWu zVg#K@G-LfR-Wi_!S95mzkG@j4F#x+M^@cdVrB_L)uHm7Gf5E$%SgN~BUizVpkz;?1 zYY*TbV<{_>npZ*YUH|6sa{tLhx5i?4u)9UH=9sjEo}%GYQcswT&(wf6*DK>=C-y3n zD_*z_kKOI`lw>PP$oKeU?k#eGIg=%z#%o;3AkM3Ae$JJDvUoYgKCCH215~3TmCy!= zcNSW6TA3ETu}#%_>f$4Uw-fxC<!2}4k=}<C5icstD@@Q$f)|Wtr#<X(=iU&!w-A`A zT;6u^`p2VBdfrY}=biPlfn6#lf6A!#WKTa;pKvS6L=zK#`rH%##dyd<N3E4u=S2Y& zNi^Y>b`+iLxb&kb&xQKLwX6tGsqWR=_B#b10-~-kyZC*2;eWo~`sG+j0y-kLC;Ggr zSL%SabXL|6t@g<CXAkCeKT(mJDQb8Jhc;PBxEu_xp4?NNxS1FV86-H)`mWBEPIgDP zoeI}2Af*W1J$Jt+Y5-MV1K2gra-8J2-+nQz@bPT)mZ`80YwrPq#VFpk6W7X{7w{W$ zVh@5pnN?BB9q4@64GJ2R%b_OT0jK}yg|lo*IxcTB+S7`>kgj>JwJHw*-hT|V?Q60I zReu;JsT0HvQ?`{s3~2-S@gFdUJ~)Kng0Iz<H}C)4$5E$MFPuR~8w&KQ$0Caq6!>X{ zF3^JpK^*rA3X}n2QQ5oWYBt$tk^bmM@8FSFY3HgnztVxm*}&Nw2H#kUqik}~l$cnZ z1wX#;vJSG$t#{UQ?YNjVzhrPHpKi&(<wP7Dkp^+^G{S+ljHqQY43q+*o*be^U9x;d z07=x1{NOJ6LThR5KxN}%YkL~_^;j##5Bv|R+&CM`aG)C4aiBg<EwFs=d?QK>WP8Al zW`zn~IU(F|z$R(<5(Foi-AX*a0Kl{f2gQzdv)RTD)PyL|q%Au(LKi+HqN|K~*kzIk zd>8zx-XIS8)X#u03x!WWUp|6be4{GpVFdE(cu>oeGUOFW>WLxlpZ=98R16JVNK>)@ z63&1V+yzrs#T~WKFl^T<K2{tqYUgs$H$PYSd8xNEe7`~q<emUD0`vt6^KtT!zK!&r z+M152T+ix#7dvK@<ik>y_~~Th;g6`DwQ26G3q-4?ItqY#Og3$D8LY);5JGwy>}Nm? z#oVi1<K%2mzg^bhX8iXQTL*XN{JM`P;|JZlp!BroLYLJ$7FNp&2qFnSYqtkjExkl# zAQSh)d)g>;<dSmtG;c>3o1Ydw=hYZj;E6ETQ#TT60!;Ru2YS+ge;vGlw-(+fFl&If zu5D%Q|D|YVdTaPgY}d^zN=2<~QKSqq`X)Xt=L11)#3<@sRGnv7>PMQ=Duep^oFS<Y z0(QQ697r{6t)s2MNgVAY#p9xqJts7mla=--Lul4>>GA0`(EWag2trl|+gG*g(r|)7 zrB6%5@M?BBt}PHxe-)y`I5cEPyad1gL{8^PYVghXl&ew)TK6FCA_uWI;K7Qx5cvm) zvBl82iH{vl1-MYg68)sxTDR|re3hBCsCxyX$<M^z=NluStHP8ojGaWEb6Z{vWS5E} z)^GU{o5zyEhj>1=1*6lj`}_M81`qv)cwi7WR7DoI1ij;BxJi1%ps~-q6Xj)`b;@BS z+*75X_EWRf$IgXgnw9hXk7e^2P8D5Y;-9hLox^P*X5o7$x~!{*L;@#<HNs^2CPbaj z*a-T+E63{LUr)V3$uAFGeCJ@=6r^-(DnOZ~CP}6T>x4#^az6&H)(-I!j=pB@H{wR( z;z?@twk;1r2*sl=0VL$8vec+72~qgNNzTJ^P3ov~3^Vr`TJNu|<W*}y%6Alp3}~v5 z%Qfg-QGFr5Gxu=e(!u-D)s6aYH8v$cG<i*YG!EP69agUxS2N6IxzX{<nAJ@3X_fO? zh}}mzE}C_8B|2z`5uY9)4|~i+5b3un=zJWk!14~1r)7mOMqv_Wt$F-3@xalvUbh+d zXjLn;*~X(S99>?rVRE125wTmQ8WY)rVJmmIF|I4}-6+1!vg&jUO%LDE2T$bl2(4=` zi-^5r86->3(LEnac$&F}E|%<{|IUZ2P#{UtP!4~tDC(BRezF-<DwWUTu+4iUp0Am> zRyRlCZs<qvbBG()E$v8}mz$koUAnljUoI?2Dv4?Q?rN>&qcNmo>D$7jMA4GdEKc;% z`wW?DIQ`GPevjhRw-}y{({*t@7EAGvJug-IhE{FgK{v)cI(#ydys~-C`sozoPwls~ z=2!Pw`Vqdox^9RQ#xs$A>45LL^Bnp-`uqq9PrByC9`+pL+G|p=@Ms;C`JT2LX>zlm zBQ*8uuwa%}O?2&rsFkrCl(V&&Wo?$lq1!`4T9X`}_TPdnSXa)9=`s3N93>pimH+Y# z-(Am3d%|>W`Qua7)_ZQ|$`LkJvjU0veGc*dFI@AP#_iRL%q(+@6Yu)lpqolEDQC<r zE&8no9b_AoQ^RjYrNK_getI?psxnN4!6SS<LoeL;A%4m{QFZD@71QHnm|wWR9L=Y( z+HTMO-f}h1G`Wittp%iH96#O1323&DD0z7`hd_~KlB0QB7(QEQN++7bZ(6+1yVVSb z4s?FGz}vRmIw(gIq7Hl}J30nvvimoQ{lPF41sppGE}QG1-a^Zb+)(L)Gy#j)oOx%Z zB3n`VTz>Ly+Uab3a16Tv)m=f5=|NN4zX|NoBP-f|IudK0oLM?2Mul!gU}ap=AlI*& zV|G{-h|c<(Y0|iZAj3bkxJ^!2r9T#>d@oUx)$;q%h6jywFzX<&FVPe*x#w6={f({Z zPlav-H7P$eg67ZQNpIXbxl#Vz%Xt%31`2p{m+Ye0K*KBpOksMv@Em9eBtf~5kLm$G z`4L+hikqJktUBg-?iGF0coPd>CH-;|Y7pq8RBYr0W(>Un8Q6{nQTr=s{|}?q_H6Le z=5M?HFvX{yePZ8sZ{g=O-~VyTae#F<nDtO9u7PYi?g8U-upno-M&4`D^ZZWe_$IE2 zARH`Bms%2l`~<2oS_?FI0U4OlDbx=E%xf+Wje-%q$Xebq@31j?9n5+*u-iS&<<Ct< z*+s~<l7p2{S-|>$Muo=TGOb^q1N~XV{cxN)cPilH=wJRFBZlfaVIPWtgKpJ$Xasw0 z{Fmh0ig1$2tkOY%5r)8%A3>Vc&nHno1u#<;0H00GaRC({))~p}@b3X9wq5drR5?!; zxQ8H_Vr-mTOSxUD2$7Ph1LX?gt6ivUN9q6s$i(&^mQnZht=m--5W+1yO!5VykwwCW zKr~f0l&a8n($$`wumIydmh)KB{d&p>#Q?Giyp{^tD2kdfeD!D7rQ%!w{ePuGsqXQt z*bk!Q#88VMd*@Q=FcYd_KOBfeKNz;Nv4plmDK?>-<7C~NM%&dB|2@{DF&|?14Ka7$ z&eAli%wD8JZC6?HL}f!f3_w(Yt#>m;b$G286_ul3irq<u(xahDQ<B%n^>(4CfymND z7|7wu-%eQh|M^G%Z{;8Ttjsc3r`2dYYzR@H>zGAQ`oYaka`RUs*}n~d&X*xJa1s;n zx-YU{Q9^~ci10BeO{0C$TD(JX7h6TVN-Ixl^MPW`QuT8px3(_4Z!RdR^NaT1Q1{{Q z7K!i^^XZybFvp2uh7vTVEBK~1A`NTgjd;?JzGl4?o$s)um#MEP*HfmTp}m+^<OJW} zIk)Jkv*9u%rFA(QbGT3DxSVich7h!KRV>L7I;Vr(n1M~9szRl@wbe~wNu8OBg+fyc z{bl}l27WBqw69DSe%_PddiH!&Yj+OH2{>oY!Vgm9u3iq<*%VTu#`SdWv1{i0-f%sd zavkoM135z2pK++=cKA1tFAUoma_KQ(g2xpvMmM{uG3qhKwJz5>0$;?R*QzqE4W^Tp zW0qj!2CMzgyFA8`&df#lUVlc|C6Iv#|Fd57pAooU-=oqIwi&gaQg00IJWIu;0TtqZ ze5G!JaZx;P(AA{|)du1EZV)r^N>Ti$!m=o-m3Wo>6qx9g{~D@8sFv)}hU96h%PVlR zHJ}TC*M&;b4ENu|EPqEdpdw&@Mj#gx{(k1ukRzw%#c3YRV{e{*hab)Tr*}F}$6cNA zbu+VIxJ@6e=i0aq2xKw27<kB(CP1=S8`V%9a?3lCrwbQ(|0dV5`&$0&ZiqYGUTfmR zq!sisNIvI+pl$+>WUJP1h%ALWeY8OFoUVA|fDlBf!q=`xq~NNm0QS!+sn@$l+ILjm zNvW@&HcN~xZsfXMdmcRRI8e+|QLjK=i)1q0*8W9`ujU2@|3Og&BOjT@J@7qEFZx1E z(o3-1;hpohry9Nu;CFxDZ(*)YD;h}14^;i7p^S{*0rD=$QUMu&?@D~j`?r~qS0KWS zL=emIKOUgPTKYQ+%U_(98q+-5ERr|f1O1<0RozDg0WRt>NZ9R@9x%I|Ae=fHc0}yC zkemBZHWd<6VVkLlXwd5YmkZKQ3{BRak%T6adch{YQ)+-@krYL-BS}&X-v-Dlole(W zj>k<c)6Oq#%wQ~hyVL(*?)I7dy?l8c>(}x~=qK}kLz!-76}-2G>Sa{Jw*k`jrGDK4 ziN@}VFD_3U!M%ZX7h{Wnw>A;;3?%$*pNVq^#iwxtO2}APHNT%=>eMDA7j-I7wN6WP z8=n()K>bg+=P{dY7Qh%MLH7d{!KFt_1?fMF2KQHJAuVmd(z?Z6Fxgc6wx0HPrcDDl z^*yH9dA|`Q!iOi}ow}W3-mSstN0HiauoT+XKk(4}GXgPo=rIMDahXoSO>UzDsc^=# z5=9S?@IROaU_*_Bo%o-WdQQRIgm3-D&A4|DTxY=>GO2C{)leOBmB2dl!Gr~Q-7r?K z21~~$3SQ0oPp>Y1Yto$V=sNVh$&l{WLEH<`%{Fz2^FKg?W5_Xf-N@ZsBT_)?mBB~8 SMta|#GdlnPvH|LM@BaZ~I$1LS literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/100kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/100kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..56de9f48c9109597420840fea17d82fcee63f490 GIT binary patch literal 145545 zcmbrm2|QG9|37?0b|xW9G8IK6W#2N&S5n_Xg=CpZvP_z6k#M9Cg-TLNV-49VWH*&P z$rh6(W6ho+%b4ZNbNSxC-+hnoeLwf}JpV_pyv}vTxvtOW`g}g`&vu<*eP<0qn~ohZ zI|6ZVa6sq5KZw-_8ABVukb`6G_lC6}F3z>z8@aeRxwtoSbN}_9hmV(=hmVJwn^%CB zkALk4TnP&B3$6{;Ci%ys8#Z!sZsh0T=K1SS{y+U<eSk!GH&}BDb8_s2Hi&R=ig2)M zAv6SWZ2XHn4(NY=I5u!{ZRF+wWC(yiDBc9f=i~%LZv+&BzYYSQLtG*oH}5!bh+EY1 z0?$rQF|}I{Q+VYLzx^nFs+}UQe$gwGkAI7Vq?Gio-3p3(lr%K8v~_g#jQ=n>VtUl< z*y%G?);4Et&pBOkzU<=a=I-s|d)?3fM!@YmVc`*XBcmS0J&u2p@bp<?YFc{6tIVwI z*Y668ir<%%mX&|1sjaJTXl(l2(fO^boAkY>cW8KIbnNH&#N^cc!tceU<rV5GZH+Gu zi1Qz8f#3gN>~DOD0KPV?$$)2#FOCg<;6JAb*Tx+OxHliN<hkG}x>M~Iuh`*-DQ`dW z$*G^Bh+p(-=ief)F|=!bjkUix`+vt+=>HLC|77f6eDy+toE$)SoFWhgVsKWlpx82a zIt|u~NoTtb;h)t&t#aDIq#gDS*AsadxAKV750V8QTbe*#!Ky6iK{HI!%q{;m4>Q8; zkg`1IHVy}cTP$egD@>ch#C!X8_@fbnaTb)HwrasWCT3|Q8LR`=Iu6q&$c;AI4hk`t zkq$CauDu}M(#CPFS{TgPz<h_Fw6)3^oLd!y`*tIbIl9_S#5l}r(F+^Pz*O)z8wrQZ zyO>b{Zx&?Fg0k}Wh44RVKrk1;hdGQXrGH&da8{&7DMI=DBZ#3q3kqaGdULqYQb0i@ zhK%_dB4r|G!GlX-L5;F~NNH4wl?G;&vkxYTSWiIt$Lm<o!d95}llZy3ceE1Af_9XE z6>y9!PPHh-WZ{I5==l+C=5-|W{j})6t|y>eRT&o4P*p;oWrSVrmWY8z2Kt!G$l(y( z&x)xbnw3&urZv*-R->kJ;wdhSuvVrg{-^Tm<PF*W_YfmL%rDeWrP)*S5{!^va6kHs z1<x9xT)lY49S;^XT@D{`=(<+UK7z!6NUo{FdH9uRtt4$)Hw*IbbcOQ!Ou&YklrXPh z$LvpB?^R`lst~6`S&$M`yvDlRFnLwj3>k(eb{67}*AW+F;+VB8sLkXu5F{oP9^I<S z^uy42^DmaeTws^9u(V(BqKMH}4Y1sK>NL};gx<<jPRhU6fSt-C4#1Q4vygbfAaPXy z!@P$1Vr_z>sv?J50kf#zVjSPr<Y-(=Uf2Lc;0rJAu=l-gxEoL?-ayY`K`HzrSy1+3 z!74w{xKHrJ;bitfh<+m2J^n%T93jtd=>w48Ip`R;qaP%P9MU2${US74CFZ5Wjl27h zs?JsZLZgjdvdUocMe-kOEcq@q`WGO^ok5~3=#Usk(i;DkgM`(MW-JKH1MZ#sp8FS* zO6D{whQ{Ar2Z`SrDJa7&!OSNm)0_=hFVYkXqN_mO-vIYl{1uSH?_d(p$hIftQDY1+ z?G9VabUzE4IPPEqi4%rnSE2s3)r`-z<+30#xRHBgf<TjQ<3WS9H%6n8!`;NC1p;kT z{%~m!`zS;wCtCURqhT|-P8VmFU1ty1ioC4aL-<ZBVQ%;Z&(*+T*PjsPCncEP*s)U< zJSb*t4&1hH9ARivZ7kCrd(OE%=yPy15xW~=;B{2|F>O<Tb=ZYoDrfymt?oIVut06! zz@2d`(OfsIXfGdgWHWOz023$s5EfKGZC^Jc?aFgK*BYV8(@{LDcJuht)>fff=d;1w zuPwNjb5f=qcXh`y<PuG~Q=Zlv)^Q$x;Y&~M_8>(B9&*;Vb9A+Ncr-#t=E>Jw!{n%y zx$k|pZQI+fE=ER~!t(Vdmt`uQvUqxPg4<{-5xzumqjLHA6Y`rLmnVuourm;hDNROk zBMn`|2?<~;!CM*1-k);Ior~U1T~T@VLfrQ2rz3jzyT`o$!jn?W^fSbVqih}Rf8zvY z0{OgDQhsgsDbY#biRrFdo*R}i)XB3j+qSw>(TL$bOh5J~E-hIYO-Ea^pk#+uCKXS~ zLkZd0PxdDC`U?1kV)n+WIV+YeHsz<jV*uFMewqb2*wETGw$3`JBB9sGD@?dPmhHMU zK#}uJx9XK&i)FKU`-Y#G{weQyRO;#Yn{BuRb|#gu00A4_$xNU{xWd1YkgcLoby7cT zH11@Q)uoNkQqDuIr|YiAZzD4TjspvOzA6pH(rv(Ha#9JH06U+yZj>(@1^vPl`w(e- zeK2{61xb&->hLvv_CupDRA4i2SeX>f>ew6rn2`a@3eQ5aurfRUY3zgi;V39211Q>L zo1KGWjZCB@O6F0Rv*8`lI`efhAnhtx<7XVHkj^&R*07wP01QnZPe+I&_A7U1uNDhg z=3h}sf4MV?>p_aMyzmVfYZKq<&A@8q;klCE$-+4HW&e$aT1w&WXKwQ6p5MFfrk11o z{b+-QkQ)nfpM)1h-?Jd%G@=<c5=%vHBLHwtpMA{H53_$3Km1Pf=!Fye?>)L-S64<Z z+3ut>X+MVd-^%o8rROkRITilv>OT$CJv=krcaK=!njKlV`&;4Ey%#ZRIC$Nzzjjmu z+-Ni3V@Gk1lZ8jtf7shKmhm(GU|v%Hsn1gzOvP?JE87N*l6KfsY6CcFhF4-2G&oSp zhIuT=sDePJkcUj!2M%>&9Q9`>6CZ28Y0*m3OFfqRrR@#G*`y%ewQd(QW{nX81>n3; zKsgeJTscdTt`4AL3P9R0iQ&3#go{WGQ87!O%9B%@OyJt0vvUgz;>WLBwg@woz-&MH zH~q}d{ImLPac6Q#Syj01=3O>1W=76B6Ne0>iD$24g&Ft}k8{iB{M5_8R(B><HtmQV zJN@#RflF_Q<~pTZHyG6n+G^dVI@(cOrH8Y78Y3U-|M?vu<@Gm?s%%&3xk%p<ys&FY zK!{?gmi6quYY@gqx}}tYRJp0!IZPyY{sli@cnt@mXj_+cyNh@$cX_5&$ou_tiNANv zamU<*Fs#?eO!g(CaMfyN8d7ObYp%+by_Ac0Y5Ju%c>Z#TfjYYe<jn~f1UTQT$v*o2 zSI3hxN$)rB*ZnwaXZ3|jMh@?1K_nFOX&d(nyOx`>59|+$akK*`wEN+Qau=G}5szW= zc;5@4bZy<L?E8BT*+^f({DBm=wXFkp>x6KX@lIdv(r*`T`hPL`BQC%0tEtq%=~uY~ z5K}bDz$9PfNQf%Cj%%<FG;7+8wp}mtbGw<|f^+s2>nPnS7iIK?yx)MMX}F9q6J&?n z^24kQ5kF;88W<5C2vED^#2Hu4h;<m{f%)@WGBNbV;%fV5XBWS_A<3J}6lC~kUJD&Z z4waynez71LUozJ^rTTXj(`U!WGVTt|i?z{eBLxf!p7OejoY{{)1`T80F5zh#flDQa z107sH`lXo6ujk8*eoxp~RkwJc@xkkIgJkjTUc3soPp@OT5r<unC<neR0=b-H!Q;6e zpmc|~>Q^w&+2w4t-5nV^`$%kWCO^kV8Q<L3GX^RE*(EW9Sei((FqT~r{tbxgDU}Z= z6K{T8(~Qn7eEMAS=LH9s2NA2Zb*pvrM6;k#1qtTOSSDYNbjZ3rcxP}{I18Xw4`I^K zHi!ketS*mBepQc&SjZ13M{Qt1%_IgV3%Z;v2(w8lmhHMCN|7^>QYkuFe!Jh@qPX(% z=9F=V5P(THDX`Lyb@FhJh=xZu5tb-Knt+YU-=Nt_b2`V4xf^$U>(ig{pJt=>aH?Op zrNbHbVRxBQ8>N5|kxauNA>TOu`<{#x{m`~7`R4IU;mtESv-qTeof|?9$v@H&|F#~R z+=&YUYvOUkEQ;D6g#7*$+MKygn4kWiD2D@U9LSMi95?i%-1R5sz@-cRq6N>%n!j7T ziIgYQoKNMm{V%tY=Jp<M`u*ItM?1*V2yKLXBl9g0WhdV!lEXA=%PQXWD@5~dt_-fB zzMaIX4cI!mkyKq^oV;57wfWCsw&tap*%#&o8Uik7`R1UvxQqNyzj~v(qxS7e)A)RW zGgWn@N`EB3kOlFU)S<ZCdc(eLdY0D3wL@lh=6gNN8S4(!GG7!`9TwVpW}dhBfhj)o z#Jj^0TqQCAB)zd`&Dy7K6y)VyxiaHn{rPK$PKrtI+an>0vQNc-Vx-PfNHxuO15MMZ z%I1j+%ZH_L4{YVmt3Q<WBm_VUOw7>Ay`>Yv_|3Kx9hxsV)sEGw$|lR257|qA{OK2p z_7hGDxLhzFJ1ku6wC|a3o|4_MigUaw?cC%;w;o`me`91gm$N|P^~7bhjeDEed7AY8 zAR*`~TeOq!{bBIlz5B6)e}z69*rS^63}<SkXzB~psyneeL|0Go<Dv$b0jd}xuL{`# zFUu6V?i-)#CM_Ouf6=wziAl-J`aQ2cD(q{I`>M;SGwDE~Xh>+0^pd`{+kWJq!xsK} z9x&utBJbN80FAxYCsG#^kTUHB&2NrWZXM&|nB2=Eh7CWi+NeD2jGI0^MHbq0NTt%o zLp1NUmaUrnwXmmxFJcZxL;e}!BzG9K`1I<Ms7v<e_fLdVO&^if7Lo^{?*=caS(^9= z&q=Mg<GbHEx^@ldboX(@dp5~aP6nKB<2m3kOJv+^K!AaM1gx+HJv?hEN*xYle$s2X zX8micmO%9E^Ou;h?AQK=;UWCffx7@I90ibsAGd#kO3APIWE8#GAa(>lZX|sMBnIA& zV54IvFw?P1nvr(F+FWE~kP+{NvvdDM8yju>XLNz%;c4q$xpixE|0vAQg3dt`S*cOb z=lKN2E#mAu79?k%;TwE_YoZ^udWG0X+H-rt70Mad3WA9-BE4Z%I_>s^`%3snq_1Rz zx)vq$SOUt0K`tu`QVtSGXxdI(EB-+SndluBv;=ZlU|qXWDajk6fb1m!EBX^~mnuCq z>BK$eDHc?|=Nn|xPUPIxHcIupRIY5g@Jr&*frnbbf%Ko%UisHClGKt<<t;-L(%ph9 zflbf-i%TyFwFXK<D+RqdL%XX+?y49ZA5z(~FaJvWqhC6Af7|NaM-4X^_!cDo%G;Nl ziL-0=i#ns@KYEIva99ZE28$TnNON~N+Zkw^W$M*ZHby_bZM<LfHkDMw5SxGXaDL7z z?hy6apo7-(@@Ek}_ekC&f%_%T>n+iMWBAA<6tx`b{3K1fTbKL#!K7OHRf~|iKA8ZD z@^jt2X48qZ0fFOoIN!pO_c1#0*WT`gk^?SQ7LG{!dk+;aN)JQ~=IPlrFJJ8J&-RT@ zkjcH#i_&d@ZX^}d%t;LR2jIm%rZz1raywdY_nhJwjrFwu3%BJ^%xeIiqXRCN%-<g7 zCT2EgV5iU9{aNA2>j6ydB)2D(^o-gsn)R2!G0RRyl0}w4Y`|VPh=W+7_oDf<gOK+C zH`l?hrkB>dJBO{IIuIyOnEYu*G|t-mK5!4hm}vlqaz-+F|7)mNc5jT+Kir`qq~AdE z%^NQ7GkayMe(8~5fjjz<u0ZAQn9z!}!L!bV<z0A}n6Hw-&UV*2@u$Z)ik`@z)eV5r zj;(Xj`T6t@0s=bky8is6%XqSTLz%}^CZ~ejPwsRQvh~Pb{Lb*%RM(=0xStk(<i3fB zlhWN5-~{qAiPZ90><8(Cc>{U7US+F&pDf7}@hkapfb$K<`<FN8nM&1Vlz9#P<4+RK zs+mLacaC2@{Mbxf?d(gwe&GY(e}?EL&UOAmWn2SVSg}aIJ!vGcmW+$!!Htg7NHuyj zG0(a<`DB4Fup3nrqs0nrAY^l42)_z_WI@0YwnckV!J{YvxRD=4l|b&eavol*$T-yl zyA{2MR5c)Xx}xn2wYa7{&%@0i_HRpk`vxGMc$>cj;z%4s(>1-p48W^~8g@NowlWh# z^!Pz7LCpYI{&rw51!3Tsb7k&Rfgqh=yK!aBgkAk@5aYHWG>FOFTR$#prVUvfsp2+u z0gp(B=+VGD%2Vrnnx9?)BlH(M{o^kq)B;Axw-2OQzp$VR_BAb=?K*iwg#$#G!Ci&N z9^@-koZv)^y2(q87TifM3EA#@n=^Y(=vqG6RBy*g0ixR?H>95#W8mVeQrIkY{Dj(m zgPvPcUr;~9;X!;Yd80q(P+4d3YD?}<hha-T{QiKz<lpw%wW?wSN&o!mb7u0cN%PQy zg)BY6>&Yl566~tVVKUV8s|d5n?tS_N7G(0~>89BoLpIx1^S0pzS3aoTLHIhW<q=Zw z_HUKOIa43ZxDyjL^Nz@0?UC_(N8uQKv@tMt_-3Ss!5<|STC&??BHCh1f~+pkO_9&o zB0^1z@<(FPIR`iCSI;-6`@JqGxhA>y(e^8xF~))x+(G0J%pifhm7$vDz&J?i`<R#% zU-l3#+LvykGx<3F>HgN0lek9M1-^}JrxuLpRtgQ>%u2T^GxVjlK7OdmZJsitPkJ|i ze8h5AE4pe+XU<H|=PT2*EZ+6Dc*}e?cfMG9sWn?1cyF#H%KMZ-j1a>JX?rJvJ9njp z>+Qqea`Kl(CKI9dZo|z;9hQ3xD;#)ae%nCy>({ruay<80u%HUz4NSh>g$x(^o<L>l z?ZJDoXryIe@6Ce39d1RFmsMW~#!GQLeA`o)xH?`d9lczT@8}-zxMf%E%D&(FFCNvt z_*s>?%t<P~se13XtMxnGqN>jRA0~tZ<<Pv?`j7)eXF|{P2lO^yri}?T4j)u_;*J3h z=RGEV@u=?Lc!tjkaU*dsk>)#E9yC|mm-RFB@T2<Pw6U`?B1ld*DBAXv9DCD2bVJ__ zxcqd(hj&987Nsu2c{k=F;lXD%w7I+Z;*|L`^Scf|n)ctH9F6a<9hsxI@k9rI8xUna zH&FG<P?%X7j?`2fi~gE=smx7FE7<XM>F|5v1-NJYB(-Pcgz@S5^GO;f_O(S0NNGvL zS5N(#4N=3zG1Fle9HD2f?unx~UfekM;Ov`t=aP`*Qzx}X6f_rGk{-kFT4y})smXf^ z{1er_h+q4dF6G36I8FnubyR!%mIK-m!Kr}Yg26cbiSj!pR<E9a*`qk6?UW)DHJ?j3 zjXg`{BQ3`<;|dJWS-1BUCTDMYLLYnJyp>=zTy0relGyE6TzWtEVVTV-T`n0=oGh<< zQ&C-bzrRW9#AXHT?!&otPK_3(ayt1|8q4$Iw{bQl<zcCs6=vRe!Po;2l*71qu8d@! z3b3(yZR}>4m$_?>mXcQ6(k$q4{|#mjPu4cxe60DmtHoOry7GK0I(=c?64UU@hu>!P zA9cBW;lpH{(PsG5j(zuY^r?vJz6`JPd^?)9hCaCFU4f3+hEunFe!4y1V^^nvRaUdm zXs*2I(KC-?i$=M1dBoqUhVNbcKF~W|r&rRGpYJ46BY0<ntsnmU_a^kQa1<xiC-+?R zPomEo^~|1;2kL5@wKreSmLX(7uBHVz&ttn|ZOUvcHoQrC2MzjVjeT2^>Pf_{zNq%w z^7zGgesFPjKV$FP@Lqw(-OujCXm7gBVfT~;ZL#d^&T1KQ;Qy*PmvJ+%@Yp@^%BO;5 zSGF~DP8!L4HP2=*mM>wXU7wV57cFaf-H7bEge|RM#`W7gv4<OK33G&TBSBDI=X~GR zgfzS#N6tnS$4$AviU5Fl6Hgmf`T<E9zAD2=fXoz>8Kx6K)p=U^(ORp3jFc5DBnz%p z!}ai7oA+J@u>OSHX5DR`oomhoH{2&L_0jnIk~tN=f%3VT)^ZP~p4@0Xd%=GkIXFus z<3|-aU#u-{_wi1&{UFGUwjdYFfvVUS+{TRVgQxF-3c1zV^4b3P<5K!ZSrCL=%<oba zfg6R#nI9Q-kmq9%s-1WRXgfkiDl&hI|F}d;9P%Nr^7et~$p^Vu@fuPKIsv8t%iMa- z#KD!o$cf!0^!n#U8?V#$V0yNIytH{EVpVJ7kqYM72|5U>3&}!TRkTlkJ1%5ce`8sY z7$<cl$kQ=wP{1D%E~hrsC!DG|_-&U;QC5gr`DV3Ws2?((HV7}nl45!%@PJlA{z;Fk zTdW_H-YI#Z@0C_?71tW*Icz%b5~ZqHBOkW=@zXyd;!oD}MM2B(W(G|8(^0xK;S;jG z<hiwf*OlB|T>8gGH*Pd9qgfLo5n<#j%*9Z7MeSTJA{ApqapkWQVjAs_zZK?ij?wA4 zmh(XE<iVU#{H7nRnbc%#Z*|Xk*U{)IN$3!xF36Du6`9UN(=Gi~kF~+BhkR3U(msba z&l-mbg-E8~&DDD0BCN<MXG8U-a|Yrlmost$HRmym9py=PxQ!CyJ5xntwB>XAZW#nd z7&c_wFr8_q;A$~a2IdO4EA_91>WsTo5Vt=azI*=aO6!Gzs+(t+w+w{?k5R_Hme6$q zT_R4Gg_+se<~u#(YvBFzRMET?R3fMf%aK8Y_&elHs_E|z;H)K1*X_Mx=;NQ#h^0?! zaQN9$9q5|^ca+IW%>N?Zc<uf$q{Qy3^KPxVhikwsZ;g#*L6_#j2h=F?ENC<4G7Azv zxTw|GYM3NHaM?&oDLv%#2k+u?Qmb^*Sa(`hD;%V5rqQY1EcfEcMK7}ge-;#a6IWhU zQYU0u^QLju*)O9gLBwTD@P3M&Eb#z38oCht87?H$#K!ss)RolU#YauLZ8cKaSDCxz z>kP$v#RT6<@kaPEJoNj_=MRrLYAH?mnhwUKF|7h5W>V6>yTMY`yIg6GTLx7AXxQW! za^n&IZ;#Um->od{l#K+LQocC$`;|+t&+mFO5HQ*r$!gM1QSFwmQ>u$IYUl^4i6@SA z*jalV8ZA@166g70%tq#7IpMqUvR6m22KAoJJSsYHv2C##yC+d9uuy*H5a)Fr{xk*V zkiF`x1Re7ukYm29Boq~y(k)+BWcCQ>&oB6P`#!ZB!_@?mhZFM&>~s$W^*L+KiPQ$S zzqxQ*M@Sw1aOQRJ&Jcs?<zgzwt3dJjZPDX*3|87T^#l7VJ66MXVJkD<e)Zy|(QO`# z(h_OSe_*L@1w9)ac8>{`&qbWM!xi}RXo3<vX!#;2IDWzBVdW`}Q+ot61yN2$TY*~B zkG#qo{~V2qnEh!IemGW6<@J6efaBwRnxFSQ^=0Z7S4__y>DDe5b+9`;ci_Qlvm`#L zFh*>_{D*8;H_o%yEWfXKvewhp;`oa<HM<ha36F2rC>n^^zke3w4ePsKr~ROmckPpv zlNVLH624vX!53Q^XTw4L#biFyJNq<j<;e5guBw+G&n!4!dH3wFY=nMk|INVCuQ*jp z!s!mx#ow=}1dGIOX374<Q|a-K>ko0<-9E#3Ylj-bsi<LQ`iNrg<jdvNR-uxYb{x5A z>-Xl$rLmBSgYH|+xv0J-)!8=+>~qcKFL!7Q&Tg^X^|3cyCP9uGAZjEnGEJK~EpT_~ zUdr}*nUg(}F=dNc8Q*;QN~8*21+D%lKkOYBN67wJPHzpnuJ!ig_HKvT*a)TD)LZ@^ zmQ*$g9&E8R+|uS@-MetPZ0D4}wX)lOer|&~OoZeNNKXNzmGaQXryVm#grv!bNV_`o zoPUd$DJwA>q^2Uu>7*zBYOO_YC(JwtvFH!XgB<W&jvIP`4^*fMe2~MrZ5(k^xCirC zM#L+c0uriRkZ)WEFUURzEiT?<!KpQDkL7x#k-Z-t0|-5#YzHQIyVfP!o{gFQ#~m>U zfbNI+o?R+lH;G8I-O@k%Z6UgA6KEN1KH7B&IEMsp&>d9q1v8ZW)uOXDr>$UUn@N^N z+~(P@W%nr1xkp|$fxpSa{)bLm5?gPLtniJ5N&|3xj)YX7W<iI=`z?5Q{8$j$3*i0{ z#CO~E?%wM!mgg%bDe7WeZ^O(K(8u6q$7dke?}O<S;*gPy=098E+3>r?RvI^O8Dx+! z@Q*Fsqfa}W#ND)Ox)_b-lkpO_lKtS5EL<Hm#Da>8u{6GZnEVqoUNGzfsH>~*xVglK z-chfrr~b&dH}7Q{2+z4z>Vi%Tqrb-umNejb-GcWrp9gw7XTB-4dfB~jdS~PJ(Z(aT zXwv<gHeUv|h6*rMuBr~2jqdx<q{e;4<y&_(L2h!hl+P==vTPoHL3H(Eh+#T23BG(# zf7$389@!gsj+&E^9MhDxrTdY1EZ*_>U`2qU_(!A_Q|x#vjS)C+6S?Gn4vq3BoWk#a zH(Jx<5b;Wnbbm@)Tlyo9&9nUXi*z$`EPYz@3pL+Nqwj87=Zn6a9edww3wg1mlZ<-H zxIq`5z;4paHn>2E8{U`rMB>+Fx<PIEj;kl@{~Wz3VrRI8Qt+wuJK>WbvYTXJ%bhcP zyj1X-$reu09uc*p_6ui8pPo1#n7{rs{Gfi_x%l#zIU5)6qDI{X2%B)EN6&sORW#Wz z-Pq?4$uLVs6~Y%{#k7j&1?pbz?4ENnD>(n#A^m~iquP~%hlbmyBqACDnqp`U#9r@_ z%`cp8WE*U|al_YO+S^w?Wc!DQ%}#`X?|N4gYYW}FM_;CY0y5r)n!!`bRqtW87A=y- zjbBav;fU3&eX;-aLZ)FJBWDsF1yd}9BtBt93xc;zU{ETWHyzYh;Hx)3B$smTI8yUr zvb)+MyrcVj93CfjWBT2G^;K)X$dQ=l6SxYUZmB;*q%K<I-6lP3fr8>GCCjs&fu~1s zXn`pLO2sGV=IR~u8{*&f`6eH}x#TiX2`_)3;@t+(_iVJw)zjQ)rF1LelMi<;20M?m zk-i$A?Rp&UaB5VfEwYc{wlLj0L;by!Q_^r^Wv?f#jVEimH&Cy5EV}Zy(&6$yP}gRt z{843B9(EqYNRMk`1*yK8qB&==lC!^d-}!!T>wWoMU$;JyTJ@Z@|9UTLN+KX#YsIGX z_|~KXnMYf!B_|F|J7AWtCzarr10@$1Y#53gbTwvoj+}hqe!cu|S&-$$D7Rk=)V`G_ z<wh2yn<oGZyS)c3)8d$n8yt_M40|-R_ig-WyI+(yQ|9_dnw71Ghs*XBoah4`6-k{} zC-C@<6-^r}T^n;J8bidd_)1O$O>n-K=8kr|>3Ry+*L>sG(aW~d2R5A!$y9zplU3Sd zpw(N|JJ9biF!Sih?_OK&qMMiaITWf<0ShSVQO%kCNMB{mi&FY=M#Hz?Ej(D#v3R{7 zJ%V0`%C4FhoP(AsT2Zb%CJCn;4hMZ`+<9a#{n&d*=TC1^R)Gwt8T{jnNT!3I-Pzt< z-TOjI1}v|A$2j8hB2IL^6!YsGl+TiXY9o)F;i$EAXk~{8Q}%(8$OOE=15h)6XC7%s zE|z?5Dz2~3v027#2SA8TuMa}oluDN0=d3kGW9ba?h|#t>FGp2S7Fvr$H4&@RbUUlH zo^AsZ!O!Q%*1S0cXY6WO<TD6+Dz)3_%Z()sj?e#<0I8R}fEy{|bjhN4vHf_|Slo&7 zC>1^9t9e^&&+BvO8oaQ!`5OWMinNtQ*_Y3Q`6{NoPL{`Q4Y_rU4+$!3{c|x{kYBkB zY3{^KY{i34y#zyX-GK82+X<K4SW#nP!mFS(^RVr4Etb{dyx+&~M~xHL;o&c(guBF1 z9&b>dy;x>G>tTb0`k_}=iS>CCex#CsTrHBHSM%0Kvbyqn^FB_Y&Ou*ND+n`H>c}my z%PT|hr&#tuh)#<(a##!0K!0GK=1;wLbX(rkdt$HkCgt=$t)A@S+9b@YlYg9@$z<W- z{|?yU_@z8#{uK!?`}|drdrPL>qcfMD+A#KzdjedToFLhm`^196ple-yuEYi2HPH(& zvO$K<{;5~*`xMwCyA|(oQ^PYoeW(1LjZzcPq|vr8@fsF{b0;o}0v#l_AQ~|HfTO^l zw$uOT55{q^*38IMy1U(b`2(I6ZU^TRX$hdn`=<31DtbV+v(lNaLH%w1HafTcQc?M{ zbTeM`jl0cqv`{^o%@;(rq@=ndt*p8v#!d45Bv7Jj=H4whx6b2fWpQTS?hQG1+dvVF z41gSv?Sk*=GiBaCnKN%bOs+ejvE}W7pv3mZ6UpOL$|bKO8^ZEAm+hF@m6#NU<Ggj| zuxoVnt>Ko-wol7P?bOlnPf<hL2Wg&jj;dL$T5mosxe2vn%dehXz|7^6)Q7V(I`J1H zPCm?QPwj8w_|Dff&RGQo-5bGvH#VCOFI0#O7G)giJbj`P*7W$LHZAG&Lhh9x>d#wt z<y)cwaPFWOrsNFxzuIP3Cw)hMXN&>&WwfuA+OcGVM*)ZxB`M*4CH7VQ#m-8bY`c`H zH{_$Y7r2uNj-;y@>OXKcUiv}fkH#V~ks2J!2{YouB5=Nc!`W{9h;4qiu0zHHp)bed zNYhwp|5%GE7IY_+?z~t^w|`ojNv|&o+<L>$hqPhpr`h4KzMr~Re3$Z^Ub&@@PIdzw z9D_fF=#jtQ9=d`StJdk6GTfP{{>pW`<B#XhxVL>nW_72Zj8D9(4xxgSWFueuqH1Js z!YvI<gmq%os|2|}67M9G{+7D7mGi=fucnS&3%OeF-}lfD=30*DH-2axvwgYe=#0i( z(f9f{$1X!n{9zY)4K8^bp<Nj}nPo+-(*D01KGF(8RD7Ol@(IGYsF_U#u?ceL2Vd%~ z6l`MVAkw{oI@F4rTOLgGUe83HU2-~qI6}e8bD{_Rr%h{4uKU!-gfnGavb;&9Ot+5d z-qBI1rRV?jC*Xvdd2yGozg*=r>+WqkzuJ|!C{>?3B;_pc1svd@Rm%Vsd+46Ebl9u( zb`!swc;?GxZOIr8#a(yhUB)gH`Al|~<#8jl-_}vR3k$YRfe|sb0?I;}p(vhYM$Rkb zYbQlwX482e*<))Kbl7KB_O}@eiVS;|BHmA{Fp)`+xZx{%Dyb!YoRAreJ4LD~cX*$3 z!Obbl(ddzFp<|_u>ifx#p~t&L>?G}F&d*Pt87nSMx(!^+!?vRHiBZ2KJ+5TD>=uh2 zjvi2m-tgEX^Cy>&;UY(WO|t9z#EhuO0=!55K0CF@KQA84ZOl4kAHI61747e7Q8V<U z8^67}s;X*X{5)y1+3w}&>b9L9ofwBs-YD1(l;gHzZ!@#RFWlpcVMjmVbn7``Vt%}$ zZ_Yb`t8%j{p+Nyl$*8kcZ9bwy<XN9;!p*dz1BL1{JC<kVcMlvn>4(bjpJoETEoa}| zEyq7CaY%CPfxQ+V?Q;28r$$F|k{&seF^{Dr3(H3RS|4;`)`g(Z)rTO$evYTDn2##8 zc=o<Zf$`b)hwwoFWWHoY?%^;pfOrmBtjCmon;pZ%Rn&<^b0(J+o(*uz9X9m#(vOBu zEf45sc=V;ma~`PKq-K6lk@L}ig<SQ@b#cCUi~no4qP~g2&J3K-{_s6(b}sc{?gJx7 z{cpJY#=v()CAfeEz3bLycS&}JqE6Y&H2P6y+U1s)aBGR~SM|<ha1!(7f2BirjthkP z|I8N74k*SP)IVXnIMMy%%g5s%QurhdE?plCwz|d4dkw1hCr7{$IBjYhkEbo72pq6b zLpx?sGat)NWKOkgWkq$@aB)@nBi9#N6JuVVuchC={c+TS+e#c%gq$Y{i$Wy;xdjk0 zn0>&};0n4ETZ%#Y^cbua<|lsK;_chePd5hNg>Bn@-SlXP(&0zE+ppmsBi&u_gn}nH zn)96D%2`wdocB@UU-h#`Y3zd#{$a);a7^fVEN#*u!!sDD;e(b2rcW}z4=8T=zT5=H zO8>}evTcLeM@Adj&dvFD*l2@8QuNzM87S#Vu08v=&M*s_pZ7$DS&+KJHb^{S1hu+> zK${|V7b~mQgG0HPr7k!R@>+Y)filMk2ele95?-M<VxSMG%Yj!wVwV3kgg<5uIk*cr z!xM~XGfU75X-Fq7H4z^s3k!qh&4!9Tn7R@RigP)k`O9SF;0O!41}i~9;Lxy)HF0es z0&T`U!;S=6WSSr!bcjBayrG=T2RClUtn{stb~)hh5J&mY;MDB|=gGBp5Uv3|&*Wix zBCp;m<NtN72<6Rj!g-**>kH?d2Q64)H;`L7=xysMfuvKd(ivC~p8i+U)d72-I4Z<~ zJQ7x=#}wE1U)P<{`p?~0cl7)aI0y?fxkv&=8v!TV7XNW_>QxPr4gV0Ef|Mgkm{E0K zzz$%+!~P_oYRB^e+As3g5T&(NG|B%oV&n-|l4&A&N-dO3MhFnY4dSBQxigTB`Ut$r z3!(*k&}($i^fuH60>6)00(UNJaNGkuHEtGkE122Zj>+@UZ1tCz>t~A6NT7ptiQ0-7 zjUW{T3z~WBT9A-e5s>2geq#)K_t6!~(o|jL?uSVgAgSM-xo#Aq;|?~E{~ygg@qe7* zIS20OMB|XdE7&Cp3;NRKUdYzx1Eo~iEr4o4G)0xkOF}zDgb_zMc^Cp9GuPlqS!)X( z08H|M$i@*U#9{aPJi=CB(kE4ED`=XiwdT5(-qOF?dytP9VC0fN2|2_EjzWU@l8e2% zzERhWzd_a!Vesfdo_5ff<IbhApKbZR)=tNQ!25v%iFp(FAaHJOy0i-(l>owW?0_eB zmj*x`&ubIEZ7vdV9I}kcS|EjB`0<QgdMgZIx}!kT`7{043JZ`c{ONQ7+`57s#!~Vs zgwTI>?M?fpI{Qc5v5NGd8MWY$;j&}@JaBI$2%L%&Fz;kgcqB%HF!0lXWPlq6Fu5L7 z5Qw0XqxUt%FU2tlW0uf#NAdh~W3PaP9!(o$bJ9%&CN69S4%7@N%c@`r)B9X=vJi@T z%y(`TAY9{dL_9O40eyGq#!|XyrAIN}>NPzUB&_@*Kkfst^>GZ-7yUT|v?bRqi5Ze? zgC}G$b0csxHZ^2_@%PS}2Mt<Lsoe2Vjls)CEa;{tD3kD=1hEo^yvhfEDmDNhCi?`0 z-tEK(`By_UFhhGt#Bn;%aaF2Sl{7NvSc$ZDW&BS0Zg;t@GUi3T&_(Nl+r-fWEa=K} zng#bbLrxmS<ZNIv@bhViNHh;}YXm{Gsa-ThPGyVs#UD!b4o5zHGu1d=u03!P)%HkP zl%0K_murxy(#rHkQcKIBHn5|apt4PvW85JQnU~DV7JBO0wcIF^zm{)MEX6e#6aVbg zcYsSXYlxNv`4TAiT``L&^vXQ3K9+h!15M+JrBlfxHWSJGXtvMFRt=8l)ybJ``z3xh zO!gdwXUHMwnhkn>UV%Qo+P0C*w((+YI*<#v$bH*hRCVmDGJX1xeCKvI^i9DyGBljA zUiO;1*_tXAfBWoV?v!?-_<Uzkc3_s(p)<W(x$eI_dBUfw$)AWAgM`eUv}(c0zVVjp zWK=kjEF5bbt}4=3^|dI}FM2smw1iWtp*adjk+=RfD0|HVZQjaoCxl`~>hZK$=0=aU zjVQL=IHTEx6{?d-RJto|z0-K*9ruBi!fCs%un_`v1>`<K#0SZOt^Z{UyiKahNpnKs z1qw;RpZc`IMxA(+Zx0m1Z0dH=UmZC-j+B=C7VolHx44D7-pQo&@6B10%c;7l_Vx70 zkB!^-<f?F1Y|S2T0_E{E`8N|NLjnUhb~Y`rT?D=Lg1f%=DxS_>Rn<0CzT>;_?UHDy zj`-jB$35<ZN9DkNI&`i^{mR-9@n2N)0W3QGu<VcO52r&6fGGLR*|--!@{i=PjXPo; zRP?`V*Qh$up-gW!TKIBnG-yV9v#t)0coT`exx`Ck+Z1*UENBP4ySLen6MnO=CQsk6 zNDa*{(o$2qvHfN7IzZ50_m0QkNch$^7*T7T=a*Zr@KFAHu9^Klj)vx#QIa<Mt02h& zST@c7n^g#I^G6A#o2M#<d^s9NEpd{h_bh2XU#D+HmA=U9KIS+Q|Ml-%P?qZ0PYs>T z^^G)`xa0iEL*VxYZm-gVEf>0pp}^_y1vmoW>44GJ|3*QQ`SH%hn|zuoTHj3!jBemd zUt9|DmyfyAt-5ZzCjw6ZFRvWCVzX8QZm{^<Ry^vgm984=xAxP%nfAoQOrqH`UV-b{ zLFIj!9mLT+Aj8K3uad$KP5l>vh_M5vcSD`@)T2~-h(EIf0P}V6f4sl~;u<!*jAhpo z0tn&W2gt_5ZsJQnp5C||?Pxks<1O;&ny`{NoAsSuSCe078)s?N*+Hq~>gO4)V}~TS z%JpuQf?gg~$kyy6{VU$L*uaKJY3%6f0uBrBi}c{Rn<u?ud;f&eQOmQBO6@sg6Sg(w z5ZH7e2fPV$=oCx>b^12z_loN*BbRwocI(-gyIiuKc<ujH2;x~;J^B+O*!dn;PJQ+z z(QJ0AY#0UoXq($-V0^t>uX(k7uXERa2|-?|)oTHw=h)YOyOwOQzk2g`gv6fd+^gYW zc*6Y85)tz)24&i!_aC6R9=0Wt);9|<|5X_7JvdtN(x|nK&CTINlbACL->#mzcEqUF z*p8i;G7q+9!*GZWINnH40PnZ`&YI3L=X3K@+;{0wP=`=Ugk;lrM*^~`N)8FIhsjP1 zMb0Proxq1a&@5qkiJxZsL@62^x$|-BJ604WC&S||CH6#)%w@rI+{BAaNt`18t|uc@ z%!nytcX<h8zJvu;qo{4123W8s!1LzgY<)Xy-JT36gt(VS`aX>5*r8*O0#O@dM}R3~ z5tNv!8>kjMD(tWA9S6wo_>cu1+=rQai-_A<l;U~c^|?h!UEcb%wW)FB{zY(FN*PRk zhh)uyUTT4Y2avrqW=OM(I37)8QsDZKebf=;pbBXFr@=eyfA~lTwhRw<(^A9E9vNNG z(KYaX(M6yhUW{Fx^aLIv7UZ?(iUYR+l4I$Y$Q{L)A%PCect!(r8S^Q%s?(!V^{TIf zPQ_8)KmYXFAN+JNS?Kfs!}{8RAavSpN1%-}O+0<eaKi#Wt`7O+G!BcHFO)?ez2Z9} zPqQNbjf9N1Al3Q~PlH@gZ<3vcaLUUB_wcDbyHz&rOL^fWM>qzNQp;fK3195$5bz0s z+SCsC6D|jC-3rqOSx_|OtNHPNPf0jt(iNvBhY7uLLj~amCTV9KCuy;<i#WS!{hSN( zr)zdCD$bW5Q2PA&sL~;>&AbKv^Qy7c68T|6t#@VRE87Fr5VdxK&Fz|Uo|%!MZPtC} zR#oMN{vE^Pjqwkf-IP<yE9CLg8ii^_(M@)uN>*ZG_?6Y=6N@gyC!<Agzwf!IVDqFU z=bZjNyZ7UIo&%oN6<2A>yGivLHr+%@arH(P)NYKXMh*Z#8;!yY;Q~RdoEnaq7hN-} zCUJ~y4ue1gwz?h9j0geYXly+QMl{eEwyJhvKhlZe)@UM|n@37+N=k-nc2PAJY1msd z{#ZnsFi2vGrLmy9@q=^7S<9tFViOC>fEPH}=abd7Pq+st0Lrw~0>=mKU_nCW6dV#| z$%1N+QT)IOTBRjILqWv3u+pwdW%_Y{@+Uw1<G524)CU5JdVS$+!`YW3C%+9p8<tm= zOf;6dbVT{_DO7G3V$M_sR)v}|;9+tFgZDd=SM{Q3Bt!xTx#I}Y&72_t^cRVxy83ot zhMmB&Ep#(#L^BI|idiNuYxk-*FoIz>$5nmr3gqDEj}n)riU5LbUI&_HGc6D_#EeW( zagKa9#e%$MDta~h38^QlBdbu)86qI`RfkFV3FWI*1s2Rocu2~(SXPahnjct4uEzH& z$X{<@ga*APG7QcD<gB3|W<kS$z$>Y-`1>G6#jL8KW~ya?mx)Cz39B!4&pPS??YxNx zxh_AA6OmPdCoV8k;Q5^xdb_m`3+gLGHhZ-bq=Vb9SDzHVz)bb5FeJ|JSx)O4!Hl;e zf8M66MqnlYgO6Phm(M<H(kIm*QP^1pP+!{uubwt#Xo3VSHGvM2onaFKa;ANDp748| z1?@h>OsF9&9$-PA)j<v5CyE<xv<G#CwL>?rm+9obEB@C}vmztpUcHf@d}A$ilS|%Y z<d9*P`Fbi%OX}fP0^=FaGFBLFYhXc&t&CQg*N!`Ze73dHZ?8tJps4=YfaQqgFd+83 zppb5I90y9I8<6j%4*RJ&%MlS@M_OW+BUclM=>J>Z7XQzA8xvyh6;ySY_eq{RLV_s( z7~B*V9#_{hQ%kRSgQ$3O;#U?F5k;U$!me1x(O6{B@;~oZgR=3bYLR(t%o5c=c`#Pc zUGHnQZ^cac)p+M!b+vsK6&^ABZQs29a!rTd{E%ZN3qpxw7WX4<MCwB{a{@Rh@!)<$ zY<}PtCM*z-YB=F?yu5EYPuq&RvaPPN&tC6W%n6yC3-M<!T{|P28tZW%UYH^;FTml1 zMAXbznHVCLm{9lvKX&sNX|7or@A7thGg6Oz&li7}`8ar2&<G1s+n2(E>fMMGa2v&x zj;$?V?C?b)>JGex%vfhxH>&Qu{FZSvrRWM~)$G^<q-o1ORiJL6vN~m@cjiLLXQ^=> zD(U&UXOdJFvv&DMesGR)eUZK6l5seXq53Ke@TDoD%ikLb2G;$X1^qmo#Dc=rm~Y^T zZ^66ZA%QG-K5<4Pwnt+5&AsC#G3GrH!_x0QrNmc?2lMIx2WEvu01(~AEV^J&FvW8i zi`aELkY~|@C-zO9(Cb{rP_OK~_4&wF%lRETGN{%2maX>@>_>Rv!jdDf9s+UI0OY`r z0h~X=xRYsG=6A7F6EZyi`rmGhv7n*MKq(e<<Q9d*g1BYDF`=<KG^MjzkOid~QGp`f zMs0={hGPO<77zgz6o-0E8E1g3q6rwumz3ey?<30<rQMgFpnB|vjkB$46mBhT&_f-? zVGzmYW#A&yEUEFpYyP$2xYSN$FGFEoD0QklVaAU#)3V!GtSj&s4-aSTEbRXL-<WRy zk9@5WeV=#*P18h2VyTCx(2UFFsyqlVuHwA+gq`+CGeN}3>A-eODE?zTPp*|VLjkY` zPkarQWkG`@wM0hAYrTSo*a%sPXIF{{-&ck{HSEM+*qu3iME5IZLUl%QydG8sFLdvx z6$rzvWX4OF@fi=-$Om^37q1XD5h?eo!BOTj|8~a;AZX1=syY(QIaGiM8URpf2JYqG zH&}++I<|(vyU|udt*f9m5ZB6ro*f@hW5&WbTvlFP$xO+-^oiWQN+K8bh0kL68~E=W zmuL`T&_V`QKX(_<Wf{5`xCMh9Glxy4UjVUSzgx9Z%@H8N_7{wUEa+oHB)p0@{m-hI z@b9YmjS@TKOLwqy_t@1s^LAcVbKz(|!b9ZLm3`Bl`5!iuMyN-H1xpnp?HxoXVgzo_ zwL8^0!`70zm_><YG4Byf0tL%>8e|iJ8J|PUF^IF)zbPWP0p5_}CEm;qZhfiNnMZoI zB!sOg*>e3!6XR5ir=GmUA8C6#j()zIT(}=f{Qs%8ugG^{XW#+UT|4Vv?xJ4j69^?s zRO+P734?<w;-BFfMFxncQ!;@NWnn>hp}sg5;~ER$65KM}(Qj93yajuNMJ?yI8wf5T z-<QNQKnx8wnLtw~L=dSu^QtUJW#T`mkQWQ0e8z}jCfwHSDuPghX1vW_B=?vP2e@nf z3bds3ZSYY*O9iT#TYh(!A(^lsf$0X!qDmmJ<{I507_shjVWt?|bmkl|9x8}<K6H4R zaQmg?6u0RK9oZjQAjLxe3I;)hB%b*PJf?1nNW~3fn1TcVA;0{+fs#!CQD0i?zZomk zkQw?f0alFC#)v~jhM?}%mc51mLZ}GhDt|2119gwMs1&FPRyH1*Lk_2b%6=I&f^mVk z1f2ZiubKZg`Se|UkLhqYKv!||8b{)yZ6$D?&C*q1&XjpSB+NXVNOcVa+Sq7SWN7F= z7UBeW0NUCmLjf6~vg_Z;2eEdzB^BVbv3U)aVSq>iWQs=r+Xm)mA`+w+c;X!O26({x z6ANPGrTwQ{>*#Mm2_TIieqU-n>q8VU9&+$v?v-_2ED&axv}<l{4vX3nU#qoDdURZ$ z>xjq0oC6II>7~s(<O}*es$NBVWY<uK#vGU1inM7c<Mho;>?BsONMHY{LUEfW-;nPU z0S)KchdZ`!%2mtdf6Ma)<38(Pph7<d&U!XP_}~OoFem4cLY$Ke?uuL#uT%B2%^D^< ztgMVUjKFuTh*{=E(wZ}@RPytJm;H#1>U%48BlY3>s`2K-I%a3a5G%#f1rYg=i1Fpm zG}*r1L0p?X8|s=qA>CSQJ)Mg!y0^Edf9H9L+eJ>>m&JPnn_4U#%-J&`%XO)b81xb- z^Mf<sHA#3;JTGdzSfIy1L1~h9F~@Z0>ix^3qc5&E$nX~cozKr>K?a~MFn1f#;P}?f z6H`4_(8Yq5&*iNDP!ne^S2t9jrNt!3VjtG~x#)g{%N0Qzt9)HPl*X3-DRSz6#4L!% zAyuu&o#JoS;!BTZ#ctD&|JmQ6&)fKP^!)EW8Hy5to#Qs1)9f9rTs+8B@T((ukg1^O zv#%^w6o}aGiw=^(iS-Oz<kIH6R&VxeBXpttzitLcE6~ez4XjwzaE%{Y3g0{ioOYEz zv(OLavwZkc&(oGYFE!exlF0}F_6zEeXX3a0>-sTdBQcCx6$Gt>W3$Tl=6M+5S25EW z(CM{<-MN$q#x0w*ygBb!Gut(!{CvKF5d?gxee3W1M`c7AxS=1t^aUhrP|ezdexO41 zuV$6^OCAt2--}(5SWTP&U(7<3gd4>`<Z6W!gO1pKAlp44!dQFLKMp*+VJ-q5)x;y9 z8KBuil45(k(FZ!?2hUHcGQIGl?#I~rSkSe#u2+D~41iFD+mtlqvvn8?%H&lprUDw} zYle83aXGQfqs6Z&{B%)-ACwq&fv>0eiDCX3c*x!=sNWfbX+O?_9x+g_J_N5s9Do;p zkuh$1uy0jD(rURK_T@xs)U4s9;bIWP2-ySDovf4w07m>zHw+T*rXEL(9)dKU{IyJp z{pCa>={3^+_BJ92sQ&lWMD|w^xl1aAkoV)vE~JQ~eXa2kKcc$I3HLc8N6L;(F#vP_ z+YmF_=tv<mB0y$8fNAWKt{Nh)3fr-uN*J{9K7*zkuP=&9At0p~Bor4`(56b2o11AG z#77fE3|zqZ5%|_jrCAD<^H|5Iw8{+D)hxfj7iZ_Jdd2C1Lv{)M5{~y&i$V8y4!=q` ztrfhg)60CUnRJ*mqIwH<#ztJXX*+8tK=;7b^qMT+GLSe~9V}N@X?wpx>isiu`5jX7 zn90pY$tLj>MxlY=TZ3PFjwc-RepDT6Bi8ZGZ;IyIS+MQN<x<COIf<v!Gt!nlefJpm zdewVpF;}yX?2p#fT9xm6XX!o*>o3|Y`q2*}Ett1(L#b+|CI!2!Nks?m3p|@3E8p!= zxpAnk`N!_|D=IwS7fTD0&tCnb@Q`o$VC=rVjendvW^Xddg5KINL=_OevD8EJ=Jr+0 z$ZARZUVq%MS)0mY>sEiq8cQvjNA<Hz$rRf;u8&u(&Bk^+?a&q;{qxtKUUd^)gHwy1 z;#ns%_fCE^+jH2{t1<;u6knW3%8woLGr0e%T24yo-d0HqA6KQ~gyKxgwzz0rJzp!` z<MGuuyv!WcqqQwDE_z;s-!3Rx1`F~zokQC?kDgfqJK8s&ibEF@K4I^`f|uHhRK+F| z&iRF_RExT9NwflfXZETJ{QiiqvRL>}o8r>y2X}nRqHw-<w5WnOBHbal9`lY|7uy35 z6KB;abIa;fGs?;k=}zFDoIdI{pSiF^mG?Qr6-(qRy}2FC=U?6xMb`+NwMg$M{XMEw zea1B3fFp*sB%?8X#IU_yrOC|etNr`v#1j>tdmRjI^%v?I$8!>g>}rD?(|2c^=xZyU z!GmDBTrHy5%07LB*Q?q!tII2Tk9WcNmeM3|#8?}<^n;iLn-Wp*CE_jYTbG$1Ljvf# zgtvqbtum->fd@M^9Z>ev=)n^Tbn}nrX2&W$45a%VP5V?e9$x!xCexPIUo&<vCtLPR zPM!bUvMoq!j2I%+Ta>~N1kOrb%G~gUu1Xczu#rn$!Lqed#YaPYySoZJ(w!wX7n7dx z^rD{RNuFrhymQflGA(tt_FKlucaJZQxhWpAbmuG6)$}#@5UW-wbZ?>GIJ5uRd$l4r zn>%k7Z;a`+T}|J??~`Hel^Er9JIeBYY8T1CIZx{qsHXKQ(~fpx2JfK@3uYrnW>3|8 zKo_or1j>0*rfb^V%T2lp!uHPk%x!Yl?rhogrYc5Ri@d?E$DVWFxW9Z==moKA$A;C| z;Y^0;+@MPs(bbA#SV7mMN>7n$u5-_J9&OvK`17UNdlUKS4Y__62A*HVxF2%L#f6{I z{PD#9f<ddOosf*LPFH5Le`&MZIgsO`9GM2KubZg)BKKq8ewjAj7<JMn&Dz2%OjG$t z`qW{sG;#3V8_cvjE~k<tFm5`TtDHmTs~mO6Z+PNJQO+{wPy#~~9=x16e{B4NIVGW{ z&>!#EaVho)aE^tGRMpwp%i+emW)7^Ls@wbKu~uvSg~XqGw6ghadWi1C+t{}(C<NK$ zpJw-l85t~gj!HO9%J;ztO_ZZUeVQY8l$Ag1ZFUR)@#*v40p*9H8+B_h$?fO-mN)qI z0yD>yGrazA`fIPLIQx9-_E*31;G3&gR`XJ*5i-=<Pp-voy-;e$ck*nd!?~vcUUy`i zl(1*L?Yra@=*36Q^y6N~yvRP*KXt(KF_9bhY@W!ta{;&tH2pvUsr4425IwUpNW8xs ztW8a!6ntDBTe8DpsD}d0hInhOEq)w|951)a@sv875_ez`zdyIf>MmaZI@}P=yo>B2 zM1f$I;Xzjl+*jI_ry1lp{qdCX;Oy>Rxr<NfhDjcKuauN*-V@`}U-A4iMx(4gVBV1X z^5XDRTivG&9mTTG2NFvA3Qy7u?Q$x5$fh3VJzih8WjuHBz2>9bhm!Pe5LGN~k578_ z_<83;9kV8S-m!TPlfwC(QOx3qWfSUwv_Q@Fr8z0&GwArvTq(LKAT{)qy5WoYYm=WD zRbNOKX1_#_)%dy(jW~%t`XUwiKvIQ@l?EZbA?%EgLKj_)a~UGvMz|{}F=@GOB>^dI zzEVEjZ#!mud3SW}8(X*>qmQ%A%Y3l;WMH3-$m-QncuUD0YOjCPH>dmQ{X55kZeY(8 z<mam<c3<z(*Z8XRY+FE}lg;+!2bHd`-{yRY*FA`RSJAC0Bbv=y@%xiXj-i$6XUqmB zosbHjo4~!KsFKTQ3QPIn#N7rK>|c9QoTE?=&e@`ueyq77Yv76m*23fmvqX@niaJF9 zUxdAPKojk^EsPZf5drB6N|6pq7m?WLBGNk%kS-ui0tBKI5u_+pKtQB-rT0je-a%?e z=sf{}07?8FfA@T^_}+8Q{Vx+jW}Y&Wz1CiPZRhEuM`ZM;!E^D-M8v@!5N8bS96jnI zrvkczV<rba4L=Ky|0z&Dow5c%0e6}yP$zlLIuRAhR0<BQ0Q#RH=z+Il3V)F;H+q#E zN`SX)Mv-gDu!&z}8U>npzGKKO7=->8*;<A@^5A)LC2|4KaE`uNgNSa{Uu3TAhoRes zN8LsW<^EIKeEL7N&Gx1HQTKk!S^iz!ECojQ5xTPh`FSnhj!fVaR)kQ8_y*avTU`C~ znrw*|xC(s7fdXVYQavLO8Qab0<@|M+O;$in0icN2@4AR3DubO=G<2W(?oR~qSoVo8 zzvH5M5X4@oDLUAV0{<`3H0qoSJ}$gUs!In@N$vU1V||E5D+feBqNKtTA-pNY+{V1D z4C3B?Ko{!+^#Y1$*IWZ4kN>h5d<m``Ed%*U$-Z~^i>%-gphO%bdhv;gO^oAm2tmaf zr*aoD<DGx1EPkht?}8col!id1km}g6et_P%s{p<jLi9p?etC0u7>TBbj8Qr*2JY83 zPI&FMQt=RY6iKfvKrDyY$<2BTz?~>+r`ulm-{&@R$Gtn$x>>&EtM<vM$FtXNF)tkp zA$Wq|!$fiG(`iH_B|GsHD~SMjX#g1m7=SaJ6mcIUHb#gSkG<?G@@HJ9XkF~R^<1I5 za&bEG?@`AA)zLDDx=mR3DHfJaAV_pzitm7j8UlGRG(U_$3j*YQ|L)w0?fq93ZtJ1c zhKqT64X7=!Rm;_gyvG*_SHOq+G?1I%dQ2mZ&Vp0_9VT{c_%*-tUn*W}IZAn2-L9!| zZ*MbnIx_M+y`!dycfe-DCb1u!iZ}$M)kp@EnYCnBeQmwoslBGVN37LL4{}ug;P}6f z{S|;pf{33Noelx3H(K-=&`FtW0y2o!nlru)NC-A^dto*!O!h&2${KJ_p(_F;w_hrv z-FfgA*@pEmvLRG+Obe8_6+x`qXIF~>_sq=?zsM%pi9*TXPC2@DAV>C!{zX08Z60}W z>JED-PEsmU%z1m?Tz0+p*<ynF(dn_X`A2l$cbfdKX?$N6ftQcim6_N_pWeJ)Ke?Fv zL84EO8}mEDM*g<cyTf?&l!`~^^LPl^l6*1#yHDB2iG9emKB>ieZ!fUTkIY1lEX^P0 z|K)WE`cwqTFANCd5eGlTRc9I&1z1x`FIPgYP5OGS8tojFNu2rXzWBdRtfvJwV1<n8 z{oUsf&xO-dgXPjY04RbxY>5}Ow+MuVI<kPi{Ks1|`^1UA{t9r$nJpOnvZZ5J=CPX2 z8|zcaGIO&9PDiB@Ak=SkLo6{sHur!hNd*2;1o1d1JOKM$_tbC4gOiE)V;HA#^4)c; zM6$p0t~d0I-4|G%VeOBIxe0ysi@7x{4}=zap7;w?MfGk=7N=2kl<D_n@JEgbB#Y22 zevo7Ne#4-gFXK_*O>K`CNPfrB5)UW&rxOlbiG4)yGvnujXb>me^6fTd9F)C_Q4cRd zce|R7xFuP))H4hSlKLqP4Se!s9&YEOg-;|_KDGMMesLt%V*5oK?}0@Ns5B3#wa2|) zY#Uz;asLjN@N^KJhEb{vTa^uNWPZ4rY|Vf8u9NGvvMx2ZmAm4*TTZsO*e}CSO;Bnf z#uhfg`bbLYv>UOn2Mp${Jvroc!nv(olrQmrJQwwi%dL7kJ{#tJzY52eXR~Z=m0D=| z#xvvM;=*{m`Sr70=g7`VUmAMeOAkwpHRFMD?tabSgLoy;b9dWJ@ogz*#tDb$foGy8 ziZG9X&=Tx>xuc!W9~<8NQ7Z%&w9{zHtAD1;*AvFvni!cwVJls!Ix*-UrDZzcsLz0; ztiNE0=QwQYhf9|S86@f^FDl{W1BYVcsxOx`;^eKZuorDUz3uYQS7mkCQtCb{Y@2)$ zJJEo!@R$X4zjDHZ&&sa4JEME)SDf6lR-|ZXKO22$9f>XpjFq3HwWWEOyOL`Exops} zNcIK>$=t}vV*P5v6xG7$((^_z!$?|$0{upmonwKVP5)W^@z5{)9C)2{WQ&^1Xak9S z*e$O>T}xCgZA`7e$f!Ous3$t{u6Xcn!Pn+3=^)QA$&z(FO%;MXrt7Qm4o~o6z*Ev$ z9;Pxjt2&gsQOuNqh<l!mmjNTQ57&16nHG!dqHVe{6nK@Pc?!Ce690_QggiDw2L*ne ztGZ&k8acc=Z*?v`W$`HrSofuX1?~DE@%CtM)H(ZcQbvx^SSK2P)rUo3HLfzDwL{fC zEVV*6);%<GP$5cG@ROjKXsrmkO70S>2F{6-D?#5DTYGP0WFw=SzCAwC#PT5Tf_<-? z?bRuYTXzK`?=A8!^_M7kt0|(P5pF4A<?JPysh{?JMTf<8hx6SKWe?yJ*9Z9Gy3d)L zn!R%nW}RRD-g^so+6RL62mxsgTwzt_#EP#|^zO((I-{KN#Mn9EzFWB}%uGxlf-YHl zGIubyg@}DjWzUx~aFtk_+aEkscBz>jR~DGw^(vX&_PueSH1H_dX=fyNTv@lNJxkcA zHJx5XP2qF+mpn@CkP%U(ZY=a={UsQ6BO3>{FlgqMt*}J5p^rjSv))12dQSm*dG13` zQI@Il&Dg0(E7ARc+Q_fXy`nGEjAkjvNqurcLvSrznsPDjl7|djH$g5Y+wf`yb}Jhp zs&+g2Y(Zvxys2_+>$?wT$70OoP1C+1Pu6q8Re^e?j6n6-XyrnHu6u-TnSuGaM+3Op zSF=;4?<=XkJ$>qGYKcLHm{Mb%f_bo3`3Fg@Wljag%RCDGKUur)ZGo_uFUj0*gpVuU zV(aM?m)&>Ct;x^{3_E?s+gPEY=IVFT#w80860t?GxP`K6sOj2{WlM@mm!*N0bC)G= z>+|9!?LAJ-^X?px85?|BS$y@{b>Dl8TubcHfv9HifJB|!fd=}r;+HY;`4UF1tfo*( z#=3x%QWxP<#kIMo8Ys^#=wDEHW$_s5n>w`is0#8XvFU|~hxAqM51m)bb(J(`18M`l zMeM>1`YH0Not~J)hszZdj>8bfL-5-eR<-+&ss^dDlgg<0F=sOE-#qM3r~U4CE0f00 z#LU{}jldO!liD|6O-)ft)hTZ{hF+ERcd5cjS{u}S$9em2R2y6l`K-uf<zcCF>cfdz z+_Z3yI_)wB0o$0%QRY)#9XJaT;3Ay8tqV{UmW$KYn#tDpB<${;&*vRY>(x!q8Ooxz zef05W?jyS-mFG24(a|$SlJkosL1Gkv2LpW*2c`Ro3YL@T+u^G%D^cS#Ws?t3<&FOo za&z__6Prm-Uwi#^6TjThV*?cpkYlKE6Ge=TJC*t7V{d~pD&0f9N~5Ymq3P)dmC9yr zlEutI4j+jr9hwdp))%cIb-cr+D7^kEHgx(5jur3Y-aN?q+Wy4zT@uV<YqneAUe%;D z7umOum!Y%NP2H4wLq8p~j3Xucg#+uqzNm(8+FD$_H>2i~Z5H}m&sCc3$&E$WglV)G z;!<ua|3~L!jG9Y-f}K?V^!2);;SEC1GYB1#vof=|(QM=voi3Bt<2{>489G7kS6Qff z#HaM=4Ya~o3iWif>2K!z=*5B98ii$T^JNWc8Uep@gxl!Ra{ebnwL)o47A`eUts9=2 z6!QuC>ggH>J~{EZIGF`cKI3qnA;>6lyIILGJ(&r9pF{mrjkwx{3lq75*K^yrzNcOw zE2*42dA7_R$J1aK@kXn$TCP-ra-Z$`JKNYT6Gz4OY1{q}@-yk*vq&Y%89$P|CE)yM zm~<6?>&{4iEu>(TV`NdY{*eBCGNb-{<u*^~18#v5XK&BP$0y6bi9U^R8}5NS$4IDr zZk6yJ8_3@ADWY68XJ;mIZe6OrX=(W5z-?w&hj}oso6SxmBr+P^%hVIYRL2q;Bj+u} z`T<2-e+K4(X-&*onij(`lsH@Gu3Vp*G)ydgdjBFHZS$-Ca)lSMmh7-jUatJmtVj@b zSrk#gL>dnE{7H1My=FPK3LJf1S$!Jiv`-=PReuiY?@@cNj@Rauf%H;<<ov#U-B)}G z5Cmx8Xkm{An~xREVX>nO3}rEjKPcZcw{!$DyIj0_tNqFGxsdN82wR9h8(Uq)pahaZ z&ED1BYA<$V+h)&PSxCE@m@N_$b%N;!7iwj4)<SZ=Gud<2mz8>rU(hhKZjo6dML@T| zL-<m$Zg{xz8lk7QBD6k|AQkIlM7^_QmQ(fUaV(o=`n-lqhr5N0W}vdNhJ8YA)E<vj z-62WIcLIr3OnJlpC95Ic_ZHp)Q&tr2rg|$o6~|v6DPHw+DE2|f+4m2(DFbYu(tJ5( zLfLw+I?jd!07w9c=KBN@s7+FtZx*5fM5Ht6>?J|LKs!HWy{m^;#v~$`>`kxLl$hMt z?03BX!}hsRuY(u+IvLZ3Ne7o1hZW`Fz(yETxOzMPJ|VYIw45&SLRo!+;p*Tfq+0e& zFZ>Qh_@w@{h=2Iip*T*k&{}CWmF<oEeBM2FBC)dl8Zk-x8Gy+>8tS^NaJK9ZB(RqR z5*I(PA|Blczippf@H>b89dJ{tuSn)~oV(_ue}%LEH!ApX7X8gV)y?X<>wNS?4MfEF zqdQ=hj)ZlkwQ2y+9T7i*MA09(l%v;@rD>MMN|j<m1UHk^Ef4397RhD3LkD_<Kwuw^ zhWxzxTZ4HNg&mD@cYrqi$x-aEjKqGtxQ{3yzk~o7c~$Se@d;4s^oeToNOY<3_e6aA z{PK3%t`T+x3V%4X6H!ht1^k$vOhe<6Y6ucJ=c^W(iF}Y}BB!}W*Bx*wb1U5N-Z$eD z4qGLms4nM`QsmR#{Y!<2wFG<-*uZrP`6MuqEq5dxaxK*!dSD{qjOc13O%m0?yd+2g zI)0CN7WLPF6h<LvX2_4X_KRl}4+aihYZjLMS55wQ6n~K-3b=qH8;Si0y2_{EJ(0>F zFiTGwuvJ6G9TvQF>bcniBke6K{<VBrSapIQz|lqi0N@rpd;Bl3^7=%Bg+O9TX);KV zPa%_i_m+>kBmh8nbo(5IE&8Bz;$FpUEAzm(NXZ&;13R%Dej^-GcK~Mk2wKVgt^0bH zpRxmd-MI^as{iOp{zRDZynZz@vefm2eI>+Us%CyQYBd3sf7HzUw8xRHll|9pJOTAC z$MN|qq2f(uCF_uC)WV|UhFGZU2+%zq0WJFD5JF%9Vs#$uE0Y$o=OELvCqi^{TGSXB zgh3uxTe!qsKX!HUn9w_Fx#$#ZfE{#u&uPB`|M>JDBZho+{5?>Ya#%r_An?!0aTNEP zoA59287iF~wfQ!#Uas_ss#<`RMCTwv@+pLD0=Nm}ijp9fSsb4w?L%>ZVgTI8cS}%a zHDcmqvaALB3|+Tp)|CF?Kq-0usgIZjqLC&C(L04)K%wt24Ik-ipmX%p-5+uIyHtg# z@hlcq4^Lb<)^@Xn%t=EZg-x_YY_B_m{2Ops2a8r7_lrz!lzk77aA9O(M_Gc^&$aQg zPu@CZEr=bPY;}I=+Q!ta3#OG*6Np)A5Z%bemp6`Z1V9V?XW&L^!cLT`#5^AkWhPe1 zrbrjx%1`G*LR!JUPXO?jVjpoh4}8h-YNg2i-Aa%%(j(X$-~6kSLbXBdee1$|<7)Yu z=}}?11IJ3)YG+bZvcRTM0E`*r#V@i%L?D@kb~yxhNKJHyE&?s?KTD#Oh7Ba9z0DCe z6QG%HP<{HUH-pTrR2O7p$DxEnpmP=YUB}`8zNojXjktxJy~8T8qrR?sC}#r<hx}pe zvywrUICVY$=49Hc5tDjWxB!&qhkkdqeRW}mL_nN9g6vSfv?9WB`3w7G&{fJ0gR`ik zqp^#ENj**qU3Mos??I;OK@f<e2}-hUd>$tdb^vvqZr_GWn!Ii{!(F_c&!4^AHEYf2 zwh@Iiq4omla&RByFz!YJ-I*gu;{x4J17wGTG?0Q1LlN;sC;wW4h$EAJ`?VMeftbr) zA`PK?4;T^iw!g^U@36%jQt!(=qd_#%AKnl9`YIS=U6+MpAFtJkz?(x3B7c$Ds1p=X zq=V6}8?f+Bg)q0g4;i*Xt!+;={1h|QM2^mw_c?0<K;Z3<5q8fPiIm8#Qm|DIJV;Ct zq;%vs-7hj4fYs~EdSMZ}G>5v`gNR1zL&cAuLz@n7Zki?|$1%0kf9?DNk92j6C$elU zLuvN;MZqenw#%>5epo;j_ed)Khgv`-X!46JCX1w4gJ|MJn1dN9Au&OBqj4hOzPW+? zf-oay$$~POxLqAE)QVe>*#(nB4?<#XDFhvhTxCU;W|627giHVPr12h<IhFwZB~p1} zgL=KT%Jz~(ocv*&<@na8Iiiunj>C$N2pW`~qe;NsosFNEAnS~#jE!=!t(U{EezMVv z%#@B7+PN$|t@q|#2e&q_!R7n3p{KJ5yb=D;pX!ipyWd*k?=f5JNzJ|&LdRCfz7Hg= zm@$*NZAPfX{WTYI1$uzY`&mSK2&uTv{*xLH#4Zc2%P71C`)TA-GGbu}e+vv!fTsmP zR!^aJj>9R4^-FgIzEkA1{4#M>&VKQ)+sTe~jIs61m*uh0Z!WFQp^JmeKhsu*5h=gO zQ~(9pbm)2v@P8o7MoqH5-AiI#o$(;jK?oC@ClOop?ATuD3FJ~dxBwK46Fimk8X)L1 zL&(Jq)V32yEnf&zCHb!ZB9jCaCI9_pFCov708w}{bx5@ZJ7K#O0l|)tD55IY$~_DH zNf#9xiVk>E_RHkXgKJUQx9e4lYmB_CNs@nmW~}^DRMbve26!z0^{B|xAt8S2XQQas zyU2+rNEaddAHmN1*H`5gz)#^tuEoeen)3b9I7uuO4LOq@k}&#h>!bU4Z0GQ{7sG&% z`FpO9W`=hpLtT5${?F5c{MYpOf@e?z58|l^xo<bJ<OdEF2p8}Hxy%a>3||+VF2K~7 zz~1U7XguYp`Kn)#5%~GtqyPuFlU4Y88ZL^=D-!5Zc6q9a1waHyO^_aK7K1r9gco6U z444=OpSYo@X&=n?yvI~bu{uTcZj)W5@+GX0c(8~-UDjS!d|{_zNvvjyU2VMHEelU( z3(dPR&CcH&B|0UWUfMTyn*|pcGO;jzT<mv+#}@n6>(;m7f(G(hLZ9V6spJgGZou3) zFP5LBN~I$`J(N?%PeHN$DE(tWN9tJ<1+`?MLnpvMkxt@WoiHXZygP}iO2a~q;&qIQ zA(Il5162WB3+~Y^bPA5lPs1gnx&rA{=DsJFNVRR!Ngx9V%-F;`5iKkc!CaBL0%Rc_ zt*w)SF2-f!UCX@T$`nd((u>;t4Em`fE;HW2m(9NIJr1|QU5m*x&I)FB6S(c&ptbDr zf>xetvK(bo9&;!1Y=Fxfi%8qO`+P1}6CN{u#TQ^MOLn$SQ<va2Vk~`T;zoogn%8|e zO){eW@70wYikGkTun2rujJS|)m)hh=D={#8kkVwz(79E}b`X2Jb3!Y|E^=@2jCjty z$9kcd^s1`5%@=Bi35Qur!r`_Jz85TO1;X3;tPG-UXN{Nd1v1`SwlJoB&30DXB_T=1 zk={n7G|5<8JI~~PDKQRVRi`&g-WKNF1fiKA(NS4{i~IqFxi<KUBE%lm6~|t_weIyg z$(~OC8*aSo%S5T;11)AtT6hDEcNot@Vq|H`8|Xz}a=6DxJ;PEm-6-J(_$5AHTQAvH z8z$PQ>R_Zjp!dBZQPa;s7<*T!xb?}gNXbCO82(^kUv<3eEOgvr7eY)efLmh8)rL!d zz?HF`n%JV3<~Wmrn4S!D_q88)T^t6QU{M;8<4+8))*E#3=bP8k$aHR!WQgHF(pMmc z8Eu4)7pjM$s3g?v4e>c1sqK=rG(r-TOC0sF0wo+j#9h9Ret~vBJE`=wYb5k-)sWGM zS<_Z(vv#WBvz&oE1()<;ulAgK+H;u1`U?NjGUJu?j{b_DQbC?1S9VH1jYf0qkKDm5 z=11Zg3SrTgRbn`nvvk?UMKkyv&#PQ-R?x_iQ)+eD+B{1TCl=OUGj2K5gLyw3ac8H* zw`q)U;C*<Sd*2vF?2c5Szh1w7|M+x?P;!#%xjFgEKewJLZ3?KKdn=1n^X)>Fc&sJj zyfty;ugZ{kH91zeyBgPWMLi3?E`4nJgpaJACgqfnFy}<}c<@i+-L%T$ByO9vOv^|v zGfq=tDoB5A(yW5%pT#2D*k2dpSzFoYaS|Du!9NQO$89h*1IY%0YQz3n@rwbKNxsiM z%qem4qtnCq*(Ywzg69AbeKnzVW3VXn-rCn(SX!IR;%lC`hJzok3U;7pdfhK)ia2bT zKTRGO>}{#tJFU+d_5HEt!nlG2EdM;>gH{;3wdUKJ(A*{(o$My%ds>cZVJeSgdpbr- zoNa~gCnH&%C7vCKf331h;|U5pZ`1!MFHG5-M_RH-p^W@qG}k(;BZ)u8C+lm80sCdR zHAciAQT(5a8W-7B8Qn2L2199T87&cM_|s^iYmr8Dsmi%3A++Nsecp|Aoc)-0Q!oDH zV6)KTysQ8k5$>hF);43CNldAI48NVKKLPtZ(d<iwV;uWjHZ=P1J+d@`x%3Bjin{PR zt33Bw;Yj4mc3w6UL*mO)BkCWsGld1S(6>l(0+V<ITX_}w5E1qwc0jno!gp`LkkaRc zcdS#1fpM>s(<LWLp<2xbR%5E|c)cZPfZ^-+Kv~Z)2tP5i&Z*sBBu5Vy8WJj$^~tK0 z`51;#b8P2Ur95^;NpQaOwS3u7dUKrFl!JxM`x{&-Quoh&iKk8GNK*NlIeObxCnr7H zBqmk7DvhW8<hY(kap<g*)LYRI>9)?sA-=W~q)|RSn0_zS$tq3?#{|`t9ZUZ0UF{6h z^J(sO+8KJuT0yPsXW>4$qTLU858&{N4Oofu$o+z!)xb&CIb_&Yc=$dLZFT#pYJXV5 ztQ_#Q_UpvOu+)jDMoU|--gO$ZH-u`1oeWO?37?{Z>~koirfG93@QK}g{Gr|3oaeRb z5Aqm_?kuGS?(Ot3L5oc%=Ltg_D4pD;Whga49Zi%|6VbqKRM^f$ypgeN9_hZ+$K7eW z74&1S3u}7q2`s7n>^#@S*t;f(b#9#Xw*y2#?Jb-Ux~OS_czO{%{c-vn?sQZR%zR<K z;7Vnwt=la3+B21j7VoUYyNl?G>C26Df>zLhRK;U{J$y4Z4MSNx+#RdB&I`V4#*umS z9;L=CwgzK0>}R6}X9=6HEB%Gqizg*i+y#cx?w{3+E6uv3a9ZmVIwV7RU@^(-d79!` zJ?i!~%#w=U$E%zzWytZpCOImcWpA*rj0rvp-4m7927GAt>aSphhP(n|o!{mpu8ZA0 z{R2McXvtv2@<_;?kISZ`F>({u33xgXig-9>5Lj_sUXyXAmj@hbCD;OXD`*}Ln4*kY z^Ox!kG^F`&>Uv&olGd?)`(scIC(@*T4rboC*90ApaJIG1!Vk9UP4h_?+XQ^>rx$*7 z7$LK@tKWBx89u}`PNTPw$o@lk70|M!y&<HVzFmvjfKdt}@D;UWuIl;H)D9MiZ=Sb% zzN~y))zyMOKh9>m#>i6=ugRidrSrm8c3z$T8)n#WAg(xSt~gJpN_i+Gu;7+JUKL-> zSaom>uln}6n%gsSTp98Al3Bu8g){uJG(}@B31anAvWGtERb-tLTvf<Tds!d@-{HTh zVR!M%O8Ro{RBuDdSnteegD2sJ6UITogdO7%Dzd{`_7&@pfm!ZvbGjtj^OCf6%jmgP z*h5DPzZc;ba;lkzo<o>e)znTj%bmsV!Ax&+sH&-I45vJdZ5>`S(oV1yPBo&esoH8i z8!yFFTR|~!jQL4YN;4`HRT|eQbW42zZawp6$3f%)jy^o200y+Ye(3!5wM!<pO9=rt ziVlRpEZNv{nm5w%pA5FV@g+Zkk<{;dYS{P6vaclG6Mf5mpCbqqt^1H_9E%OdY~Q1r zAN1ena$I+%RJ$6Y)L0x};@7}N{W&MbN+K6yhsgpZ{ZvYw6FSZzY7*UYwl3FVlrkKj zR{3<(!ReauMIX@5jn#A`yLdF2j7=VzQc?#M1T_f?^Viyr>a3V)HR?1!_R9!Jb=Rc} znAHsR#H2k!&Fs8JrmA7q)iK1)*YKO?BkVm2@OrHY<pqfBX<_U+g%<ZK+ox<f!Yx(p zqiB43A{{BbSbM)NrIb`OBUuP{`*-5YsL#RtT2bny13S{wV-{QP_o;^L2Fwf$+k^yZ zTb~9O%l5uwMV^M!V;t0X!)piSSXX2$TO!`Lb*rjlr&E0vnZ{~0Q?pcKwYAQD5f9`4 zocG0VV>n*<r1G2$v`yq3USNh)f+bhS)&R!K0!P;(`OaosttFn}okXcuvw%yZ`#WXE zF>9l?2>U!wYr7BWX5>*39oX&soPi=f7a1YL{K2{C^nIt^JndQLTiXtuX+d>^4RDWU z?d5@{**x!uos|5KLha13U&2`EeF`};&UT33oJpdHw#TIDjVnZ_>8;Xp%Gky4*Bw44 z@ZssP5KM9^Hm^0A9#4~ICnK9f-x6N`i|oR<ap{f97{jr67QXvu&7aM+a6Nt5@^U)@ z-vXNFlp_i4WkZMtU0FJe0)9429wBO+$V!<c=i_1>)it!iQD5m1d1qrzS~=CY@Ip4U z7NY<WK0;7HyFaSG17^3l^8%-HRr)?gme?BZ>8cwUj?|Y!a<3aJ^P<g|HJWst2genn zG;$nn4me0}8*T{koZdIhNd{n&3GkA-qo52!vJ?)2q;s9b&(n$ovG7e^&~6btGh&j{ z4hiP<u782z%#y(j?8hK&<ol-zZ2I~xkJNADmQ5Llkjrxbz2eFB4my94J=RD3F7`Ni z5J$SvL@L+>^+!VNxN!CzC&d1H`vsAsXdZ9^e}R!4#9%uRE?`d(Ex~07LVnla`1x=b z+9A)DhF!BSI)>le^}z0+k3FrAYxETu(Mg*;8`_YsZ~Cq3>Z6@EN|H0uy3Z#^2|Ump zH)IKv#H0>>0P~uKB_`A_G>%K8yKqH?3MifK_fLMVo}u;E*dnqASFaJZjSk1nNTud! z88RAv>*TsLzsSCsX^136c!N19K&w;#BFls!cm475ITKRf-@(Xt?FWjA818?!j?fw? z{qaEm9Hn3vI^-BDpS3c;@Z)qd-q3G(I1#R{Pt^FQ>L-hwCr#&k>=!rx&<lK6yyoGf z827V<W_%~kGV$HK>M1=t9+5q;iB|-;lzJzNoq*ie1nVU%_j_eFf7eX1lk6(|k^90C zcvDd9gIogP)<PZ(;MmC3|9yu4+pkUf_t#dPCZ_t5J3??ShoGt^^*2_HvTsHl<<oK% z8w}rGZrnKUxdK|24cU4Sz=ysE9Sla0poAPKaCBwc0goq2>@8A=HOY?J53(-_N-&|X zP(QUG+mGR3X4}hVjxb9ae-lvb8W|{T#4j=q_SHv_eZ*D<f@JIiew4>~X66HE9;VO~ zvQWNd7Ai6;BgPYMJQ<ZNdC;$ZETK~)1g5KRs`R5t(2;(^KBs|A0_WP6f-NNpz)~<C zyLvw$Xigl}M$Rrfr27yu&f^KMJJj=?!cUc2Gk;q)=JMtFGLU8>3bVAX&|od*Z4hW^ z{fn!S$hagVBer0)-tVh?$>6nTXxH<VKsAmO$?ce_{IZXk!%<$>VyjWA&yG~!>sA~A z$r6UE4=Qn7Z3ZO?;^9vu^Q+EXm)s>Es8(lc_*{<opXdNG<i8qO3aEas<z(D_@rgz8 zeQjS~Xeir_o}2r2>VMr{C#?S1Z4LcJQ4UE};@)Uvv5TxVZ*JpzHa@f>s%=1#!vAsw z>VP5p<FsYGlN69l`)<W6;4O#D{#~>7o3e`^owtVnB1>#eSd|dK!d_vG_>5Sx*FhfL zL7B$(FX}m8l^RLUDPKD*;60{re&e~i*_}&Mzk4_wB_rAY@Q;sAzW|%!DxmoH)rn{H zoQ)^t80rSEnW%WbF%bHpvJx;CIQQ!PXh_AsDOkI4L|Z!acjd9N#-EpWPC5T$s#Q2p ziM)XLZZ%7)etb#>m>S9So<V%4|4-B0p?u_@*Po6btx8xvTCnix-0y#sf`jJ-J0tss z$hJiP=*<}f9uK%!XGDBq_)CgT94LHH2fXU4Vay++t>0ajK7*Qi57K?W1#g1b!6eB! z8E{<hhLPYN>>IVdb4t+z$c_N7IC_nwke<B(it+}a2Xm<JedOf-ku(13c%<j;1U`!U zMOF!kA(Q(pEffHE<h$Ws;tL7Q0)Wc?|K3MH1o@Ar)@o#7MI&_UWCZAB>vk;bw=<K( zk=BYa6-N%D$#nm?YJIWy{)Sq0L`*?f?_8z_9$3t#qTp=*)e*6<s1>?(8pz!`31KeL zWICHvU>muhh_i$+jiOJGnGZl&S(;L|xQ;-hf>>g*64C48awVAA1qYy<dv@x6Tk}`s zW;)DaPeC<nT=v_U`v${#6yizBYcah%ay?rl)^=y+LK)*yn|oSOt2TLK!UgN}H4fZ) z5I|kdgdvJI3B1rTJN951VqxzExYCw{eM*X)?nnCi2F6Z-G^?9zv(L}WuKOB=HVZ7H zm<Y1i(eTBuDb3HjuMf_73e9Z)_}0_;a^Rlp#R(<d<ML(=niR?$5P`#caF4hd-;jhK zedbl=A>x%oj*f-Rs;7|SPXda04mv|iJ3`H9nI3*A4PlU<LNumaCWsU)8HSf&3V1ZI zB})gj304Kxm|M<H5*b}CXVMKUczo(dr8(S#zwO7<D@n|m!Cb@g?lDi3Q%h!fFjA`M zIz=gEE)pkP)&_moq7d^HG}y(^v0XF8X1%!4$6bK)(mdO(qM5^gacQt@o=;fan!>?b z`L2R-Azf&CFD=Xob3PHx-6tz1oRn>MqFLE9>m6Hz?htgW*4bFKUbFq=4MEHIq9c7= zd~El0g%%ry)El4MnM&gnYIxr6+*TPs80lyyaN2Y6nBQ&>nJH0o`>M7$C4b5MK5hEm z1#+!jZMNuZAwCLcpTwA`)mA=z=D)3|o3|>;&H{_$ie5JV@-sI}&err&lmjnUsqvTj zIrXW4rxS5v_VRllQ0dmp^ZTbwRM~@?%o+IKCV8q-E70?A&GKh!MWau(tFX0rm&QnG zB{&!GN253}ayNYY695{A1hbvQEr!5v<UnmnmvIgi!Lkw<_Os)L(+2n;l?kExf^>EI z5%Z7@HQFu0y-azdEH!NVr4JR*hr|-34a5&slKD0hE**t|2Ea9(Kf}Gshh#aiJrIU~ z5x7w9*y_NC=mu70e#6OS%u|%CuV&qV@>b2&IBK1NpWPm6KCDKApK41Y^)n&|R_G%o zVd(~(=J{s?Bl)X8S{mGCy28?d-FsC_{R!sXTz?L`>F4Gk+Sbfx?T~j_Oy%{sXKGoP zZ;u}=#xhiaDfgNCc%{bHOMyvKkvZwf3Cgh6nJjk8o(v{sxu^5w^a$s}+7hR@Si%N> z$KD~3>AWMbH^?3{I=<D>pZ6;F>)Wy6x|?~8L7Wj1H+e^5^z-F;+wZn!ctu}6o!uYw zg)}JUJN%36Qa-^IXSj`dU4Y&G=6fpWaV^&4b!px)`#d|n1UREgLTFsh4Y$|I$E$fM z>p74dq8ZI~L2Dby0>oGKlz2N-+jzR^4ZH{Dc!i$n?Saykil`<jstfn+vpK}W#8o(z z29{I!&23oC7~ZwdvG9cMI8nnnhe>B_-+xPH8+Hr+IaEqByLLg9?g0jM@(fA$yC%hP zQO4L_pDfZC@)Cg&E4+zTY^)Ne;?&hoxJ}nwF|Hk#@?@Lq{rvlauJ0vE=Td68V=iV- zNBZg3@WWExnHPKAw2S$a8MT=HsV*rdgGX7#v|k)0s>ABA&6n3gN{S^4!{xehKSiH) znD&CW)>cKdsoF96DK@gHg8xRd&Td7ZhbDZuNPy3EFjBR*7J8^?hhTNz3`KrvYZ9UD z&4<Djaik3UEc;-0?y1+opNwq|ylTIEm=taoHk`kAT4~%M(YY(so)NvdW|m>=B^+;& zL2$>%W7{xsO;nPjjn&CnGj*owYq!ni6DSX>EX$OIgfl`GZeG#sbSD2`9-?cU)r;5_ zxc*zIPeXvt0>Uf`A69EPqE~UxMEF$fZKZtVxLEqjJjIK}K>x=*LL-=ac0a*%wiS8- ze!>Sl-*xdtXp?gd*0T_5{mfd&Sc7?gtzyrs_r;IvH%)Y&?8~varl(yNy+$kQM3j`{ z#3r44@Wnt^@}o`bM}EF3VXxflq0uoq^aMGZYDeL%@Zj>XgG{|yCqH~Le;X!eLEE?B zKE;YzTzTNlk=94zTnj718Lwj`mxuEL1FXr{qU}_Si<7Ksi)K7pP>irn%=xUt+XMtY z=+h)Vd{iscHkq%g;;rW4v(>|e1aEr-1GO&7Ia5j}Srbn&1$Me7*_b6Zkx^Nx!$(;! zYx!oWgGNkwN^r*9n``dehZ0i@p}Wsc)yCbBiP_rN5VXE`sn+90)AJy=WBo`FTLUmX zwueb+ib5l(0M>5yLWB_{1k}*%Op`FmX2!@dlt?FMDP}AIwrJAdS(Ty8aIdR)=EMT( zi&GHXMV5|wofVVE`U)ZYbt##7sBkU6!T;f4y5(!$@r#odV)1j$U0rS2tS=%m8=Hi> zUE;0!Rp>cwT<qe+)8q`aigiO{GSU_v(H2(-K*TX|P(k!1kC6Qr7KVup!vXx7L82d5 zFxagoRhpp8<wGX)Ty|fJR-kfwe~wBSH?`Grk0InDi3*?Ah&WwHP{T5|c!ew-i2cAP zHcd0&!mGG&W0FbSbzQn)f?}6(AJ(U+sv`9tF7Sk<j@3?l8Io1SM(t7{anK-H$oW<E zQ?}E535`3N-d2(olH(b8Gmfs{TZV<H7ik?VE^fE>ms;v-FClDvq%?*Ko#e=2Dzoa5 zy;``bvYn}<y3qQErp)i7G+<-&7X>x>R26AYusJphHRpUR3L>2um6HMWq-}tWeT%$U z2IGv-9uj9~US)XxO?bL>#me6Cinf23kIc&Sy-rsC4NIH7jXP!nZPz=m1{Y|GYOg59 zOIK+2j<rjUEZ6W|i*j*BrKks^LovzrvUz7)>3Iwb&h^xD4+rYetCI7(q`oaM*wT(M z7C4Bp8Om9=9oCA@?WnU=(ct&(^}6Pdi<<$<Ow9t9A1ElZ#0LSM$wV)BlR5FxmvTSV zP9voZKY0pGZ|NlL#S#XCi(jNuvr&d{BYa8`UJk2>K$|c=C@!fhw^t63@)#{X`@yru z@78_C*vPA)4EH^fW@hvfm&W6odi~kIK0uZ(zF9Cj1*k9+irMA^-}q0B?TDOO4N7H) z*+9m%!ch;JV0iIY@oQ%D`+;0W$m0Z~Q^>|!K0MzJd<rT;BvKg0><q)g6U?oUR31*; z7)53-@nti**I{Cup7NvKk@nSP-qtbm6t!>n?4+tgxp{cAe6*jXbtLU4gc{aVhv81E ztBV5auK9ku^H#yVaO+FRvkKyMal7V;sr=EP_Y;fTb!lVqCCz39JC|^d*E|VfN<)u- zLf8nGa6FAfBQz-gqY_aWEUnX=(D2tA-0_Yl<kg(n6zmi)WKeddsrO8CpInYt5pcTE zxm6UdhfZmMgm|g9bj$5&4wi1x7>pakA<4bU?looA39vN_C&6O=GuLcc<liZu$VhZB zh*TP@?<3~<N`h{SJLx2*V(jgLwm0HotcG>ig)EPP%2?=Cw~4z?%5z^na&(ky+kQP= z__a0UVe_azX$0tes1G5wy9fr3Vw`}@G#U66awv5WQ5iB1=`wErY%tY*y_5lSdw|I@ z5{-d%*1n(D>#~jF7u)^Gt5X0o=T~_os_U4MIT^KAn87VAuUy$-`qMDl5Tew950T?E zyIzXZsS=arW`5i>YjI|%*}_@{787yM{p>;HV$qrzzXUgvPR^SG!;gy^I&TpPD6GNT z2_d7|%dx2r-j~#!@>i<e64b``4Fm2?3!GBTF`Im0G|5M6RMqz3RbnO?zNfwykP>b1 zyMuBfutYSfrGORPOW@Q^zS_6xC?vEP$gr|?GC}%Dbrr8<>A>AfA`K4N7I(TX+`u;? zlPWQ6ogrVv_ix@b)-tuDQFq+fAUf4dk*XRi&oO8<;o&uBm9<`9_GZ)GWU~_*Obq>K zKF|C}H2UfAJVW|qqKoDK=<5oP|4A+YV)j#j%t3sAfm%TwoGomv+&psdlEPmT#N`fc zM9_=H&(7=Uk<E$Mpbm(vkSI5Ep!a_&qduJi@0@ruf}9g^|3wCv^lsfenNdRE1`vn= z;wX3M-yIuwe!z@KcdjG80rT2BEWh1ZUD>3-3I8c!8v9*j2dXfNoPpnjgarT}<gXC( ztE6L~Qcw?a<lr&+T`-i>ibp#bo2VZ>`d5#}zv`QS!#)5Z^gGb~Q&Wi1(iAWeY&Bte zq`Mx_opsR2#y;rN`En83r4gJU?bL<usrsG{4eWuyrml{XgrFuKIAIGlH%W5ypc*iY zup&bS@Df^}54i{)I4B?|qxg>OD-+V)Qd4NXfbE({GoN|tLoE?ulKBb%U3;ek(7Fr| zDgmk{K#v132r}=tB8IyVC}MKK7l1g7Wi|WLITL}$rC8#J!7>AQl|KXj#R~E)&Jcim z&zc4T5l#?^D23PMdHbiT32?o5m7gN}1jybpvaw_*n+qo%?3`w<6Rc9j<48Rl^6f8c zS1|;db`-HVjM!WO0wi{9usw2n1-Z9_XsuoWW(56ah;y}3_R_(Y$1JXFw6i}P0bZ3} zj06(<;ZGD==U=X_f1f+gu41?TYKhE?D3SOZPbO4iX58mS#SH7ugQadG7CSBf$Jq9N zAO3l$dcVYFj;-4&qzmsFJ(L<6z8z4Ef>|rN2WAaC`Fs-z{7`_#85T)ZK;UO=LI(CA zHf9OBjYn(_A_67VX>CStNYqL_s14B}k8R=#JwM$3N3wK>@qZov`@h#mqKZBEr@n=L zdd<~nvZhYQG;9I?Od(_zqrTU>{pmcg-TG%|0RO~)UKidAAsa>Zx!=|Vd!ge(|HJv; zdx72DP6Yp;47I-lJv>0pny>|dZSi02@?0QC7NX3pPNDZsiHVeUTxYzpV5;i#M~a*w zV}+_M0H3oW4i=CdFQp)V?YzH_=6F9*t=mmQ=^n-zUZ+jB{n~!(xoa|hCl_(#ETu<n z%3j`NKXPe$rTP<1R9p!?9CT!yU>98WvL30XXvFmryeAO#sPB(Y0aMq1wj8jo{O5HQ zkUnODGU-}*Yhp@z`+{n%+yDhuEcwxGdl3?ikO#>}k3=fM4<!Rro_ApV3WW$Q?%Kz` z1IGTZ8-WO5oF4<JhY?Y-xfbt=gSPpy#daFvV~QFizP_H`vJVy?wygM~P@yebIxyK4 zMq7?A{A}KArnQ~8D?&_gj~MUW4a06W<S}h%saIDWs=p~J@IPUh+48zF3KlLO)<N2k zbpK%$%l*u;Xk28RvdxgXQG{F{cH&!te0SzoYxKmFUIPnTK#tS7^$f04g8iJ874P_i zHSff(aVZtd!5U!w>=7%d3FdlMe(2V&YNC-LrS8NSSCm5?N6d84R?z^@8wU4yOJ8=h z$$V%IMGSF6hvh<?6!O|YsLz;obo%<4fdwx+=Yy1%6iWRip~4kkAsL1;%!yxQbp99< zH3t##K%=<Vo63IP@pN6`Ba7?goq;qJ)nctn@7hhE&Fq0*5h3-wYJeG`v#C~pSw{J` z!0z^=j&YQZ+Ot$YSVo|~=>3KJoP1S+105CuT<R<Wk|}GJ>G%|R;>XrtoL=L&$?F)j z!}$h+ntiUKgY(I8yRqB(?@ieu9SI`_^qyML;WPD<skzA~a6C;uA~W?>*?2n4LsPyK zmFT5dNyFV#LEXpW@lOrz)=tQc*v#{tD=aiT6?9rp3oty!Povqig0!#Oc8D8hG20DB zm0Ea0;}ZC#LgH%d%Y2x3;kRR-h~`VO)4i)1{x+(^lDPYImoDkyMFxhvk9;FVcl*+F zv=X)FP2*%QrEK!Lv7eEnfZh7$wGoFCIkYetawPGm+NV*<UZqp7Oj=LI=s#7L<hgLE z)k24?iB8~Eo5SH_yFDbeySLLhypdx3rn?%08mpqJk@!CR&Va%f0i_qMXCpB_t(uS9 ztP*`!J(HCSNt2*`RPA--1z#55UOAybaq8pal%PPuSTUo<cER>@b-Zl(4O7A!2D3|9 z-QLThG};VVxC-=UTf{}eV{CE~u4pzhl_AQtsKvwCeTJwszG5UlB>APC#^xRu(tb#Y zd5&Ew`r5JWGQ;KP<6R{W<>7l&Dz=Y0=;jjlYzFKkmD8778pPN6Ooa9ml0|3Ql5tjQ zDb8L^O=FMq0%D<Wa>!+nW7{n%+Ss9Gg?#f==9w(RDD4|`(L((86GP7r=r9>Y0ig6{ zLNTaW@9VPH`7*BOnW?gCU&lMbS<p{ohT2#XokVr4og+#*l&+A;HqAP<K?B)O?A%O1 zHP5y%Xa;>Wg}Jp{r^zk_-IJ{vS(G#G21!c}SPxW11S7HP)UQqX@j14K5Il62C&a9# zZoplg8HUsw5t-gtpJx?vTW&lvK>3<cYtoUbTp`@(<v=06+lwa*VO>N9Hy?IGy!5?{ z6|AR~A*FhH2p-72b*NDCqoTNz_x#E&ih_}JB!79UXF4TE>8r$TLQ|6yb)H^h)qpR^ z9!E!us85B-MAgNHY{;z`kEk5DW~cefUOJG}Z2xk-NRci~zl+N5NACN#4Xqb#Ft+VF zZu_}IYW<BJb-eQJIvO#miW9kycZ=A6I~~!G*p}lw_No_xvz0BLjY>&+SvGI--wQFB z+ziyC2+<E4`_@DC+_240R_zn~dNIDYK%cuPaEDUWKF`72K6^yu8d@jSgSFxTtJkqw zk*<!cb9V}zFum)Xm>TLIi>=5ra(v^hBvGu-q$%5IoKI(GwxKA7O6^=u{rziw&4d;l z^31h6w=)qFv%B6w5Bhvhk-Cw`WNmRl3JHy)@+pt73h$|Q>fb+G+3h!4@!N9q=CTZX zzL$4Nv$<=P^UeI&*3F1lKc2C%(W&GYX*6^Q%k{=y58eNmUcd(HmVtL)i<(;UbqGCR zoyi?)GxserO`>2byQ>mo_$a7Y+t%DCJx}*gKZNPy?T2D<C86k^p{KLFZS9<=?FD>P zXzIr|XoLzHx1tn0&xiF#AB6K}!>{__{F{=+%kcCdIt%hgw}xf>7+*ekmS7T^kQ|d? zSFAsQ5~|&3m_=5HT=NcQu+60AQ0myYbjzE))yWUki#f)j^^o|eLmiuX@j+_?@xwe5 z#c$;@I#VB|C^R+%9nF*t9Nz_48k60zs8Y!(;t|ElFu@;KsEY>BtI9a%FiT0-7~~A> zMsJKNa$8$^RN>%0Kkt8sLBw0oadd-0#Z7%Jnt^t7TFn}TS-c&gODgqjhFZ~DIfjuj zI{d2WMPGS&^+P_G!e+BC%aE-5ER`E9Pr0rpVN_XBuRMXTpm4*yCVn??qWVd{pg<js z(7Uvh>)9PRww!_$B#S%Hl%9w4cnJL%6=YRMMt0AYd>yc=P)znrbP0;&qXi)EeXMdp zd7RHTLKxz#baL`dvz!jv+QpL-&I6Zv6I3*eb6U@<9IO@iQ1^)Se(t?&SvAdh>Q&p5 zuhH2m8cBBg0cq;*N!t@zc`WWr)i<<~l!h`G+g0*Y*DpH$6uB0qIs9qV{o0}0dS2Ru z$s}n@DW2ncj_$MfZ{pL~-n4kp3Me$S91sKRhCd-aQ)_CB;>|0~(NFc8Evz0{JpPm- z^gJ;M<+x}iSx=8gG=lh&aDSEvX^^|duv<?twE65xEJ<=ITix;^l?Tg)_SHzms=F^c zP*#Gh_Kt?_z;E{Pv_^2ee)i)wLB*_#Dd%As(K;HLxreclb2&X_dg?LC8_B_W8wG9y zgoqpHX$ZPQKiHg8H!@m>r98Pf%z!UfOd|#*TOg&PLKunuoKV$^j{|lTZ1JCAPxO~} z6VAtAZaLhWZR)exZS7d-7{4!3|AE7%qvctoP$jDZ=ow6wSlqG-ne}Ld`h)Jpn4z*f z^`O`U#}bcx1C(L6<AU`1_-z$|VD__tw(yA3E3V93?WOP1-?RJI^T6)6O>@@+5vMgW zMRQ=?qH?H!yWjDXy}Tz^u&%l!_nCQgwCB?x;sm^wWx2?0O7UTJ<=3HS*D4YQ=GQk; zlR3i9bv*B{<mCV6N0F=`P;Lr3kH60zY?XPhp`xsv)|uv<5VdE)XZLw1eLA+h1LdwB z4tK@oN#^*q-ly@8p%^GKqB0D~mLF<1=v)=|<f~Gs;JV%MHdZBuD<(%vV>=?aoSg|& zj78k(lejI}UHbjrlwI|li$d>WlXuos`aOxQdqLg?FZn}hE+1>Z*E{Mv?0b2@_gZ^u z7z=ONTUH@4#W>^QnzHv6ABDoBGA9kP*~J5xp1y$a@0*S3uU{)&N~4|?p>5PhI4MNW zDp!<7ML7yp$ypU`v^dxc6;8;KF5!ygzVr4qsh+);!J?iR7pvij(1*oI&I-7yz`xkG zG>x?=Tn{bc*;o5TMt<6+oQ)3OGUG&}YLR!>$urANSGPiQRar8He_~Rh;Ypc3;k%`V zw5YLocuCqsZZ4~bE#&sUz!52CXNvj(P9fM6T|~RITOFR5J>Kq+ZM!$JD$aOaDT6CS zX_DT}l3V57-IIRT?f3JEY4w+FQqDkZoY>&p*x})!1E)ZOb*?Q7e6OcK_MMRlXw!XF zUPoBx7#F{v>q~O_#d_{I+68)Ny3AA_2Ra9v$kigX@=;X*&O^PWdCa`<?N0u=!A5@i z>+jwghyR>sRxwl%@?F2Ll<lf)WEJ_9{V33J_wIC}8An(z(|Se*o!9n5@_t`&UJ*$6 zt0JoclKBStzrm>wgKqXjh8+ntg)8q`qBw)dnVBw~_j+%LIs#a3HKVqUgDjvs;^$Rk z_kW=o(b;Ahwe{Lq-BIrJcxFzh&};qBV}nDZJX*`pt&8OVF$aJgU?7>%-?-(!!IkF~ zkHp_2OSng`Kk?Pvyo`8(LK{l_A4mFC<o^Rxc%!ISs>3ELcHarei^YY7zO+>SE`9Cu z-{+PXSU%b+mYfr$Y-4Lc%}XBezR)As8>tNox(V?9tb61n3@fQS9^0zS`M&L*fO!=) zJxBn0Ie~;Q$4jaI*R`x$4IpSIxp%`q>kmMLJ|tB>QEokdi$)vlx+D13{%?c&6aU6{ z2zf2EGvCOYx4jed77IO-i<!<ty2K~2)eS=;NQ_#3qCC1(>_?W(1!O^0^Gzo3k$w6$ zTb{-FehQkBgikadKYDPKK#pF68c5Jnv;z~5MbK}+5P<A|UxbC~fJo`BxnT+3faed+ z@1195KBagfIbBcfsFB|%kYqm!f<fBi=%K(nke2RDxnQfeJD_hk85;{5mmW%GwqiQL z<=mbRJp%4@+z|Veh9Ftofmpg%6GArgJ72s3Jy=5Zq~*o2DCBT$a(ThK^5^o-^qlDy zJ7m-Y)oIUwQTAHjDZ77q)EH;&3KxNbhB1(n9xIGf84`R}y5!)vF&qBi4x7|-iWKKN zEZREI^#V?k-(v)-L2-8k4EruGWOL@zd5_;fmf7iGp)Agb?P^)o&<>}2)}8I<$H%x- zE1!CYq!QnP&C(}{INY^4Ugq{6C%>DZd@!4&6a42-_V!KZ6Vyt-+Jy>@q4-NKr-yp? zonCiGP{@%J4Dqx1azWUvZ*k*YeY5ML-(Fp*=%^7%6pINLYLuF&dyPpKR;M?b(R-=h zrXFg_idXy$?cp9Rvnj}`99&bIi;dmy+A~!tj#DzDeTWi$`TncmCkFPf)0eQlfpB{C zp$IvQu}LyPGAz^Rjd(YIgHp)&73FbC+MecED-XeqwVt)EuI3ZC)!k6yd!!A(vh~d6 zI7l-hP-@rE=7pG@<W`HvDP-3h*=3=rk;~m2{QH3(bb;;UY<y5;%)ST^CrJ}O{6xKi zl-f_hZ((c3@UG1VUUs?+BVOKZ_O@~h;h6Dj?Yd3;-Ctk48JWMpk!}1EK6->|F>wRg zbDnh*d$9>)QWx@qMWiG@4(adY&v*ImX<;hY7c6XLXm*-OeOR7S)u45Wr_ja>^3`V; zx9)g<^_Nrn7w&3(zXBXjY;utkhKj_Kp8#Lw7xB+>-k}1fjjtRLt0_D5Eu$uRb_`P0 z&qiWBoI3@B1HzbS+inNCLVr{vi6^YVKU%#M_`|?xBFq8v^ph%uL`;YrRUX1rhZ~6R z$LQWM2(>0VG4k@341dv|&60L#uLSmAH2WU*@u}Q@xR=7-Kkw@aNWRaN?OD$1x@&%y zCRrZXNP;rOKPQ2Fbw?bW2HdP~H<^0^JK@zja`jD~ds3#IB!d@RvO@2D8<+FTrHx}+ zOY-W(vUEhB3iTnL_xSK%tyud(Coo&~pS1oY62&(hRYp%%PT6$IiEbMC<4SSQxz2lD zJoaARfYbtLyd_o$@lgE8Fv%vdiUe3UNJ}6;6;wB2o8K=>7T?d6uCR`B$#1jeyzE&Z z@@Hxp@+jLNxJ?JrA>yhb;?L|C6CQWwHBs0;HNI#ie09Hkk*Nm|ivROiO|aI4z+R%W z(}F-rznh6gb3#j25d2p9Bx;3m@5Y4wkFh%g-L7I^w8O<88%%w8dGWaN6^dDcl!IJc zHfw<jgC9h&a9^SSW4NgOZV~A$_=!0=jon;B&8$n!{vvC+Ew-L=VW;~BPnq9VKX@a+ zZro<eVdSQcfn$f{Skg<r*ud-c7Trw|Z3Evl7Gn$6YD%`L>1#FG;R5Kk4;GBKZKuU; zg)S>+_&~=3++5@2KR;6AS%P5I5qKWtD}*`Zc-j2yggu+=h)@h%5hEVD7ADHN_M+zH z(+XX(*el{)sgq=1+Zg+$XcXNoU9*gZmxR}+DL=HMXU+Vm@jEAvU%w-<h-8oxK!H4a zIf)WmY+PPu>+Qh36Y4SYZnLD)?@n=50$<33LM(0b1MPN7#ve0Ey#a{J!m?0KJfd}+ zXZJ;hgEx2LG*_QbB*tCf&8&b}<eU`KWLPP>_}-|5+}T+{Qw<_gAv)vY<_6M7WI@^9 zvOFR0|6}jHznbd$w?QnRGy&-~N+&ewRiYqWKzax1O*%-BKrHksUAh9H7wH{@(5rL- z1rnO{gl2%iGv|Kq=lkCG%&eI;f57~97FpzE?S1w>`*VG+Qf@T`AjGnD3MANom`5h@ z^1aK2=gG;2_bXCbQrEO3xbFIt@b=HOhO(c7%Y0lQcjO_fhcxgWBfnsy^V!OWO<L@W zhq|pZEb_Z#T6Sc5L?RtMwd!OcP*3sm80vP_kGQ8rzwjiuX@oPJ<)q{0r8;(_7a)DF zM0;#RaW&2eanu}h=CD0wElU8e1c7UNjvtz4N~I6|0Uxg{=AjhIvD2vdJQS%5yTf<k zf*HSEwGkzOWF^u*GVkFeaQ{uURifL}^&U@%s~6=3uzAER&qS-(GmEwJ&pc{dH8quo zgu{y4JL%y;N%B+hdg#NoaSG`H8yrvUt}6Nafqn+2A3tW(n4quj7w7@bn$rk9@r~1T zk_I<Jgpq{phITnZd0cf0RPR`hIs`!ndKM4z%FHqf=lr3<Q(OAcGM<&6llZe_?#oCH zACN_Uq4y0mvR_qYc^9IM0sIR{dEUd6QJyhuk1z*`WoCH!h;JWrJnn`pHeOiHePMZ% z@}iBHN#+OAE3sPjEnxt-+R~|eB`lW<!xM7?iRz+;`CK$y?LDgOL+m5^zQ5=GDjW2p zegf9(nRc;}X>Y`slgb`Rn|p6~ZS_x&aF}%iYieiu>e2}o6bU20YVj{0Y@GTr#Ln#8 zh-}W---w^vnbb*39N@_jTH|}hchN*{%WG2*+x<NyM@qq2-KWz-O~trly@karDaGSF zkbRAI%ySa<d;)qW{3}kQMa9$l5ki%4pU?KI0UwHQuHVL2z~N1@cEfWeLoSd{VGh$N zmnwyJeSuz>ntI^Y9`U7)D}=!V_7uCa=AWGw5b~h0ZW>^@AXm@#PnI5o=f_3O5!=T^ zR=)=wOf7D4z6f;@twC<*vfwhX!iKn0bh+n(6UwLw3+m@b@lk~BJ;?2ue^#r`)fA83 zJlaH~`FzagZm`&qJ_wryZ3V=P;R!L9=#{<GOKF${1`>|fDpo?ko?<>???t(zlGz12 z(yD#E{oU{8z8aw^XF-Y9Hcqo`q{dsdb}f*ijjAzD-I-GRE*Q8;+q@sSaIaZm2z$_v zXHBwQ;Z+{&x#(9D8!c_@yj8RrXzph(FPlCsJx9mWONFsa2(G7sk5c%QTQ~ueJkzIA z_pDTfv@N*~C08V}oKB1Qd+^oo>V8@U#`L1LQFYRj-Kw|tmcE3Cfve)lTd}3|8q$$d z7wzaNceIH9MQ`bJX+X#{{OeYKLM)qLdJm|9KE}Oag>@099c*^CgydGQ*8*v@%p!u^ z_)QAx;&-lfiSm4z>)USkqZzDZytqNCA;`RXx_1be^jrufUJo-Ljwdh0KmMAmJF_`$ z*EoGrzAv+E>M&~?byGmIYcwdFgu|5crv@XL_wfo5+<5{xCiPp%<KiwIcR`de5ui<W z4?5B3Wdenp&o)5!rjC|LdEHml*|s0rXR7UuO)WKzu>|luNYV<-+lS48n69~<**LGV zs{B}W{eB6#?b}|v*rqM+$PM-crznmO$^Klbqc{C>#1&g2)T3^InTNKo5MNhsdTr!@ zU0p58*v9jteZo@n^Vfe#rbX*ysAg{C?}<fXPwTRs$h-w?LQ#vf2-?W90>xbGsN(Qq zkdsEpzOa)ywMqly3lFQwd6PjE!!=WMP!|&na@4h&LJ!aw@pkz*->2BH!zg=P5wp=8 zS9HI-qWPM*;^W$`35Dz-PqN$DLjpE$(}no2hpZX!hL>L33JlFN^8Dy4Ddh6~DM5u< zw7d55l$w9}Z#LRY3Q<$ez}PYB42txlB9-6kejhJ@x5_om#HBBuSqW(IN6v+SaGr1` z7q?>Pk=u2Rc{EY1bD5LhHswUWGww$dasR4`TzYAjh?zLkn4?GeSML*J-mmG@;WA$~ zM{4;~Yk3B_R)5_-qO%vI&!S58veg^+t!W(2W#fU2Y^9)G=9BypRsh@Os;3<EnkpnQ zC4~D+N7d;Wt~mN@yL*Oh?Vh%wtbQ5?y{rTl49*cU>8B|THmk_Ku7<c9|1c=UlccN} znZV!VXoLh^D!~4#$>x^O_EsWaTU#T#R~TVh1tXmE*Y@dN-1&c~!h|A*4dOQ*8Y06? z4Bo{)7{gXp$FwtF+Bz?b&qdbOV<jWM0*)jutvcy0G(K8<l4bU<BH{xd_~?8582+M! zY)Znx&z5kEs18qbKx8KmOg_Ck4UWm~Y^d0_Vr!2ujWGOZy0p}`1cXNu9v`^BuRnmL zr5(wTcOQSVT!~u&!Cmtf>3iQ0b*w@b>;T_*R35pT9#GI^4WxZt+HDf;yDiFquK6eu zev4x-fZe3<rr4(9c4KE_r(ujq>Ab<?RHmAw4wa<Mb-j(^(W`SA{%ZTebEcHwF`c-G z4=}BCTd}>WB4Qi6te!%|K8H#^f<%1HDz>E4CCGHPx5Y}FWlJNeSk@x@D0;8U4#WU6 zng?R5@gfd|KVcT`_t*NEs^9W-#P=L52G!1snRYasj%eOBYCTeOBz*JsEkPG=$P9ol z!uKD4hP_NaGsSGZ^Mui_nVhQmwN(mM*@<1%2GaC3qIybHD5z8wIsB60pML+St^v$& zblyV9@sH8F6tT-vm{_J<#24Ia3TiEXbWpm~J*;9}F`{koZYckVYt3x}hAEL_lu}>< zp5_wSMRF~b7Y<^(e%S2~ij)`T!Lwfrbx<ykC;dL^^E%6HYn4Ho{JK9u_w(maAd~o8 z+NV2SLQ-7cydTR;yb`U{Tu|m~mRvJb)QjHOa`kdI<zcAbB3e(EXrCx>V#Em>$AedY z+ql|dfBdxKU=A;hMizsme^1APHOa#f#tYKpl^P$Bm#QS=1~2EomX#hI<<)7wb6>Tl z|IG$Y*9>;Fj$)%|?ZVQvp|*ui<+93mNoNyZ9&tpC{QTr^lrR!W@8Zs-l_W{-fp^4q zei2`}F9Er~^vasvg&NxY(|n;7Nj9!0S8|Kqwp%A@=QADYLo%IV?K=Y#34)gjzdIR# z#fMk>Zr%^j2o8+(X2Louz=Iz&n;YND2%z;o_DP)1<*<KS(!U$uuE^-yDGIZ^O7HAO zcin74u22CS>z?XcD-HV-9|Z4{3#+;aX3mj|x~1MrQ&bP@=*l<?EO^^AN@bUkKS6C) z#Us{d%cG4ouvnjR@6+&1JUU3pen@Md-56^A{Y2Ugyau6dM&3fZ%Xhln$+2^=rm}LS zET&Jh<1rR0rPX5y9M4hKCw{8IGMgi9E2yp_Qgjjma+590tLp+JSw^jA39w~$+^5!} zRNs6^hU;9~SwJJ52d6qS@b)z6<^ZanLI(mu+Kk6rvGP1vz4>pstn>bYrd56!5^f9r z<tg^@x9ppQXg_>bxqN<x>5XBg5d6g2ro?g>2B!wl2i~hRnAqyRT#x>uxs{vbSI$3X zu|Ddqi<(+Y1ET$pI5UZ;UxGf0!vne0?_Iz17mf>&_<@@fBwCyrANfW!e7&rh!DgQI zuFS$zpyk^QCP6N3qAA2T!dkQTXw%2?4pNb$Ur#oiN3yb#td9;Crj6sOT4pL{Q!2;Y zB;dnhRjddki&%VhhK-BQ##FC{-);+EupV`v!?|BzNrMrecJ)Dv6TLLT?AU5-1a*iL zRK?RIuT6a0H%7t<u5Y-3FwyGeIMZr*^=i|8wzE}riP>iJ!0f!*_tC^6C8?ZIY%(b# zPtUomzpP-aDMA;=Q`aEjEBA#?$ra4ouEg}e3yVj3#x|YRZcq0fich{Zv`MUv?t5Uj zDNg<VP8u=(;-3mh0>9mR?nuvz7SLu2wV`F?I^Zm*of_gQnm`=70ic8zX8MCyHZ8K| z+a<{hz;!AoP`{W2cFH?$kS7{yn-vpdwj0#=Gs~mF4JUl92-J5L6vwox|H3Qg62dFD zrm7dW^rAk;_8Q0+IFG9`LNqWF-{Ui*%m1nLt{0~uzq#&Q;c0HrM|G_edS3$t>Tkv7 zon49Y-N#CrndALCG7esns?0ZaMk#J>TWtLc`}j;UtB?u^4>Ub5aDebYzw4iBQ_BXi zWAx|yPaQijr%$<DEhWvZBrSs1;{Ok@2&v)!g5mbzjr9o^#7_aVjL^ruz_l-m$?q3@ zE8{asy<y&-rS<hYfDE!yr~2>TaIXz0l0RxST?G{%(K?p6T;%4t*^oDk?WuEmgInd^ z8oV2n5dNpA{!D84@5GF$f0eddr<eR4s)k8NJqw#rJ^M)#!`Zxd5)XK9aYxtv1HCx^ zGmGLk{;vWQYqBxA<d<g`*)g6R&rS90>J#6JO?<yL{PNF;-<<siVypZIBr>()1E~G2 z-B;<?i5qFh@_AVv-mz=Hfhh2;l5)sDa6-aA!|;S24=lQWML_y0Fur#OUmf^MXWkv< zQW}<g?{iP)0yNwN`Da)O%m9FZ20lo%_B-!_X=df08oO*ay)iRBRU#*BSc^YwfyF&d z`lU9(84;ku08jjD#0&oQn0>zq06hPvaEyWNMaKg7lBd4jc3@SO;qkpt!WU0DFO9YS zH3DurxRaRcmg=KYu-yN?1b9}$fNd`$00&p4F8&jeLGZss7p5p6eZBfGdn7<0^3OGp zrtwdRyCv7Z;@$mjOoa>s^lpEh1wfjHY3jEWJwxA~l3;DksILnTw4dIJt30%g<31-H zaudLoa%rTKRm9$+Sh5s0m^vL3T`~WDD(AMuKX^Y#Zb@d&#3^b<R4u-+yqxd$BTmYv zL|r$_mw*$>1dbQ7&w45B48cS|`Aw!zwQk7IHGXeba-QyX<BYACdN$eaQw$z>2^SU} zT#^!TCAf;KqDC%LPs*EO`;XV6UEjnWe%?-oI;l3a*2Puie{3BJ3U=ZXcpj_s!yelE zs%UDHUWnKLe+=+|Rx3aaPJNGW?jk9>BJkpzdR$$Y<vj5KL1vDE2Z5XEBbVJDKAX~} zYBX;_0G?I1@bx2S1%<0mdm&6F+nY<e7?x?%9Z-9~<+A`|W2uinokk3``qjT2A?4ut z>0HmEKi~R2eBN|T;&%B6XS`;-cV3BCdEZY8r^W$U+b?Qn7L`C*E<}#Gi+Z%NF&j~4 z64Fb23=YQ00aJ$Spr+#9YEt~8t3<qiDKvlA^Q<Z2z|URbw%>gn{{ZT4ru;Uc{kG9q zdI64j6@vXff)J6v0yhGXT}Mn!z;eG}+S`rA9OA<(fdzgY-X==`mg~Zuq+hp49Z7Kg zTjcXr`Y%xs$swSGSzCtuxpP!S(zXQ0{Ykj$#+TeU0SI>90K$t8uY&K^l%;z9Bk_4l z^6#7wi&X#4`@qJ*2|sK){!ISYcgj=)u_`B^(}9c3-paosR{nea`R4!532FFXzD)EV z0(0NLwn;OB-z8Nmt4@1M*!i<mEH%!0H2^87(<}AJZr^7yAJI^xr)sT$R{YxCtjxV4 zG9PGJp7yPJX645`z#+!)uPR4F3)c2?Gq4nWqObg-&xYbtiydz!DW)BXn0Mu@{HZH` z7L~+ns_qG4&am;~UkONe=)zOv4dU~9^B9|XkSubhah@(wuGlZyQzd70NgbsF=Eqv) zh37PjH5=9#RUI6UWSCHb&E-qj8%%I-=G%7jgosv!(pUKm`G!Ub#=Po6d!x%Lr!U^! z-eGAMRXttVhhPu3P_xS!sQvp(&&j!ZE4@pg2;a|)1r33E124eXnz)gt9dstcSuuKO zXM{7?nJX5apg=ZvGQpM*`T7hyWD|_YV$ML-!~|F5+A9<DW-a`<W0;cWVI&a7TRe#w zPSeT5_R_iY3z^F5daCN0C&?D&871Qilj^h9)3IIQEc$8CuC>-N>CV?1Vd^O7U(!Kl zMmb=*6dt-3gAJ!U`(T8tzXO*_kt(w5hO;bSVAY7L-O;pWuvqHOH`_6L9l<vvK{|%m znyX%K7MkZON<yPPX!M3t@r5%KJlhW88UhTKy1q>T{<+jH^h~33Z#=>fgULuD1YLOm zjW?N+uXti>15$jK3d%vHIBKvlyoJAuBgc{&U_8F8#fkN&pS>Y3sw*)ucV<$Ex|da9 zHNatN<=L2%V<U2vzqzU|Fv@9TKP);`@3jRpN;rFsrSJ0uI=Do5suCA7l}LF@|H@s_ z!hQGB?h=<!!E9>5;S2`xc`@NcUSltUsF}CbSH(Jnj7F)u+U{~gyp5SfS<yMCIBE^a zr1rwBcAY&470)M)hF4{&Z+?t&se+r!NGbM9`)pk1d%q(x(M8*{J;qR)S$T5WJtrfC zreP@GxJ2+YD&j-CAgU|EiWX<MT4{Rf_q|=v{cM7IR57?A)_Z_5o-=XsL9fp%@c4k6 zm?USsbitIw6@@i*4z+P(t7P3>k2K;B;`bS*o-)51mK>sLY`n*+{Yd%c0u+RTM8gQZ z?J#ZM(&xNfTRXoL_Z8?=TQZxnEuICrl^(c1A9Fpcz55m_AFjwrwR#>+4|FkLG~%ES zT??Jya3D+84??+Y;${YINY-j>%ppEXeHqPrU(?q`o*rz<AkuuBa!K);Yv7vlrSA_N zkrDe+TT4wX?MeNV76jjr@{lqQBY!v7>#E8?&~Pp%j<5Su1rg-&&~aYnoJl4$2rPnd zO<25ysc^}Z=p(`PyZX?<OL=)ZrZ;E@KBJIw-}_o+<`o$aDTfJc73|aaD6#WoW!}@# z->w=?LDVosoGp-fDNl?d&8h}L_0^zwfs1ERWHt2D<C%L^3n?YxI*$t?qu4Z|XFfFg zfF7vRGq%z@_)Bo^zPm?*8mhg<%iSqlP(_WMm>bQc!!7OL@uYVU8KG;*n)9owz{ay| z`;W+kTcAhsqD2p?AeV>Hlq!O(kW%U1-EHg00jhyqdONI42>bm|<Hs^8`^c4Oy^W+P z(G;_eO74ons?;vA(K>Ar3|tPiQuSgJdiT=QX6IOzI;F;>eoc?ByuX7EB~ehSel#Rr z@fw8Dg(N_3$_rx5QS)y*@8I}*-^efDY|sLsmJ>^#M5y_j^O!@|Q?1l9Di?dk7}-oR zR@*YBC!pEgTh})*!??E9j`?p|cY0bu(VdJ+t8T%<*Y_zXiS3dOF6NeW8e_Abb4Jz- zcnU0##XE?+N}^^vix}v<fm!Lzxi5I9?}Zkp<UED9vu(5eBkk{+cQOg21voOF+#+H* zk)~aC?i98(Lh51giQr#5Oeq>knqXCu1n%36uOIN9%Qh0Qq@laC2l2|N=N^V>8$SZ% zxin}kR>bFprkeycdE6TC@dxJpKf7jAI#XJNBhMXpZA8nUuwlw#M#J7Yf3K6Q0h<{& zAtz<2eUba+^hSj?%G2o$XFtD}YBHa>UgbiZx<GiF89W6Rc+1X*LF(}`!9_a7&TrUa zuF{J*-}4pKw&(JCu*m_f+(mn0R-h29L!qgvvp68N(953d`#?GFdKd<(<v~`GAdx_; z>?-U}j0A{cd-0iMBX$2iS1qTNHWN>8`a!p1xp<kj`Y({-rSbKI=33Y7-_~@UL~*jh z)Hs#9@j1M$KO}y!2w7{m4DlL0FYn`g*Q0hrFV}960uc6e^}wmFzh7*{3c>v47muNO zBO1-|a#E7~Gywr*)mz{c6`{Srm+_*L>zrBeCw*I#V|wGI8iqVf5)T<9*SEEGW6k5v zD~b7np3Qb_RAlFGh79ysXvL4$Ko1`FIx5WHhzs4;L(Y~H3dnD%{;*9#aIS$LA;<lB z=hbIpv5$&nlgc$rGES`crrZ55Me#(_a2M<MK;Lz@0LQ(2*snl8@9!|RFJZ#on1puw zRQP`Ci7+Cu<`~>Rep#FGQR_J2-8Jj=JiH110WX7EvR<THLap?C-~@0ef{t7*)n2ij zC+eKxo6v_rCX=)I`gLB;*(r&fWWj5zo-rXDczDA!o*WB8txK{oVVDOigSm?df12$t zTCSLz4={wiuJAVPbMi82yCb!1{_totjy@uUVFy%O-R(((muTwvz9-%Sd*-JTrd7iH zg%ItQ#M{)+3?=+olhV@GR!7|$|1#QGt0DmU=@mLnNr_gk@N<pdmcPtXbrmXq_6_D@ zMh&UhFA{WD*)5;v1?QKs{Zc}e$Wzhm0t!{yOdBj^m~@H0_ZgM{b`S|{r7hJ&OLsl? z^BTjjAVM#c6_Qi|cZ7#QFj}BkI2pt_ffO2HIp2O`O^3}*mI#5irga6<!V9Bpp?g9U zS+^-}sp%b=Zs|!Xk=|+=bzZ;lTyrd^i1N><7vZ?dWnlUhU2{3`aPYPlARm%@TE4;x zJb+!H*AUER>7^{}cEb$psZGK5+5O#IFlP3&ZQJZ|>sRQ5%jfwvK1cE|dMEo4u|A_l z_DS@7Yk75f@!WvLPsgp^{}3<>ADp`VGVY=5TMOb_H@6A!vo)9z6eb{0je52%;Gkfn z5?i*KdQt6`v-#b$$bmQr+L$f{PWd9arHzd>L{u#K%xUPt$un@pu{bNKf}R$8u~=mR zA*Vf;@8wb1KV3u48lKzpun4$}cWBIR?7K{b%IwMtiRLI6Yx|z4$p@p%iJfpFo|Vgl zoe{_j#~kv?xS!N+dfTmU%*O~Tj79qAMb6`^IQzwzC_x;a18~fXYG!C&zm+7$=^G^C z!l?AKD!Qb)(z=)KP5Y!QjizTkoj$wZy6v!A?e`Mp0OwBMby?#n086bdgB~ii&#-?D zB6W8%O4p@3kfPQ9WJe|DkpC_}&O$M6!{HAqBc>^3Tqjn69sdOTGg&pr4rR$CNUG5^ z)!@{e;gLvq_1n!WUwYl=Oypg<?^#I6J&Kx-z|rJWPuZ6--UhntYKBfL?LhO?$M@CE z)Q49b+F%j)u%KJGfRmz9mX5L?@*vq>!!YT7@A8Cxuy;J0Z*)wthRK4KUQtKfbJ^@_ z%N_{|UfdTTGl?EYigCZDb%v8x9kxr9<ATg*<=xORF`pc}(xx?=Ow)cTm6fUeF*Xtn zPZ%K+2=%B{IU+oPEWvx{*cfmR%b@QMl|Sgp3V82OE&K}1=d(XH;#4Q|h^q-r;wN-? zWnX&xmf2!g#9^ld)O;Wl=uxyowxBWH-p*Dmv#$d9j&g@J-wHV}e`*hqI#&5%$or6V z<3MpDM>rHFc&Q2_mbLEdx<66uBHQ)Bwr%#5-@Ig1a+mOPTfi~5v7s)z<R%Q?vhH7P zM<3IRxGIooii~m9bN|(`=091u!FqULx;P}9l}>{VSL)3W3hpzxNUdXIs8pnF*)hmb zw-b|6EDul04lZJgn0o|R_fJ{0_!-ca4n3w|#K}DeY&x<RS0aFFEvT)MA|R?ha4n7Z z^nruP$@#*WDA7%F6%koSwde=_Y3#OkXvYi;996xqinfkexmPV7#N6$PSa4l5c+;EU z?gaf<|EH#ZZ=P(tNlMBldF-RgAXUcAG&YxfXjtb1yzcC^L~&H*R{QlxOT?2#OG*F8 z-|5C8%7qhA4ubcG*s|yKo=8#&?(OOEIFj#lDqN*2kS;*A0W-!t<QP|fM*ec2H=0U7 zJ&3dVmcXAlE+j*2+n>QW1wHNuai6^hzv6V<=>a32R0%eN%0nwrtLdz?9sX2hM2M-W z#^j&l5oZi7<epbMSMMj7mTOIE=(ldvgPr;6nCM<xRu(OAs@Eaadj#K9vF6TfiGe{` zkAa(nR)6t2Pz=#^^;r>NizDSpt8l`Gmnusgub0ml9f;i26Zc}j4t^#_IJ#hGXdi_8 zFAkuhF9C}g>ecFZdE|$k_n=Oz8~wHEZ>o`D^X-N<RThjz2`|#DziN7c?yR>YYo)F8 z*}{XH1)Q<{T@1#@O_36O25V%-bw+iuR#6JhJtC=7?$#M{I|rw2Kd-0zZ63*lfT8lN zv>G`)dsFrLd3AqSO?|lT$nML|^3b}B7Zz2Iy*AQ`1vEbQAiJ&qA>c5ZO<seX-%7YR z=o*~w&mQ>y^;`vi<yHNE(Q_TlJ)^66zjkGExUX}}0i^83oX?X60PQOufC8m*?axXO zuxt-Mo`lP;HJtcXSWt$3;JHnLu&jEkb0*OQIU0O%hkgTKZ^<tm6^tZb2R3b3Uh9+= z@XUNCvJM^8VpRHg?`-wTO>;Ei`i=0GMRhD>UHtF3DY-*Y$ocQC9N$g}!h_GeQWOFw zTOBs@nyWs_**M723;=6w;#(kFSs@02KJW=ie0kT<skr?`Cc&2ceG(ln3wLJvYS!IO zTo4vA04K()gJL?Fal?O9X6zQp`{KHFByN?T`w0I^6CDigM<q7Key~uDSC>pXha63I zeXR0$t8h^dFps+N#yZ5mOjlq6n4g)u<K$@tw7uIdG^WqXm*|`lzjB_34k|dDYfrar z0=7gWXQ{ZnOKn$gXaSo03y~nL?R0&m45OgH%)9pf*wFx)8yOiH@ib1Z?A6h8)gPMY z0D*Nb5Lb0e`0ue%P3OTMdk(kZ^Ym48N<ZI|LJsa$ETt(Dgs8Lix4A2hAF6ldY0SFY zH?}rr<hL|7D<&zkCowVtW^eEB%D?BIgV;<^;3eiDE(zprc}(IZrxbT_9v6?@dd*-% zw-bMvFAc`BC&@)F^L-Iz!2if5Oah5W@x4TzC;)-G3^=|^D=S<9YB?29<n>&h$niCR z$hbRDrmq_0NN;&m7Mbvy?L2Cqls|qxMaSQw){+#EgtD!k!Z{(IPee((c6u@%@vbZs z)t3%W<u?5ZbdYsD)CoLoz<WHH@L8rq>i0V~JdPtSz8vEI!fb%hJ_XAuQf-!{i=`!? zH`)WcINJvSTk-sBzmXQoMU7htr&<8cu>fyKz*CB${~*U?g(LH7i(>#W6YHD=Q84}U zt|-Ck{JLC|zECYOTJ<gGbp<=|*F!Bd51dkMt;1n%7$6*_2f{kE3X0ApoW)C3nT&uI zPvU&FlcqK)yDdpo!QnSjQ{VO9eW~)4s8dQ5wRgzd)`!}lX?oor(9n`Pd(hZ1uFZfx z0IjjGKG)VaUj+O5?eH)v`t7J}_Y`s$NUMvVr07pB+1>ej{?z~bs8_2``USiFmobE} zwEll#44ppKKf8O?aFTFuJA}9GDqY^|Y;hp(Osx_I5&t7{u1(c`37su!9D)dEM{QDM zNbz#F^UWf(5PV!AdnaOK$6Uj%in(&s+9}0_23rg*rjq9dnVnG`vfLLSk@LUTMO#zi z?YpE2&2pE<fMyKY1o7y?8N)Gv=X6H9)>Q^jkSuG!0T8z82)+*L+J^__om%_;$@AST zn}&DO!&ea#Vy)L>*>s%nKD&Z9z`EbC$2LnJ>Op{Ov2T@VNW`b0ON%v9W+_&08siRT zUscmX=JLwf*+25uf3IuR3=sardb}g+ngu}W2myj#fg2F(J)i>Y(Zl6c0MN+tSBgX~ z>!h&!Q~0Hrr8;3;MLP9>9s04*&g*A-y{cqVTAbrgq~j%=?B0G(A{4HEnTPL4xW3&r z+Rw&=bJNoh8OOwR+&9St@SOFnakC>iH+q2*HPLKJaNggGs`Kq+7f^~XF$sc~Wgzwd zQXV}*Nof8p^DVHgJ($hI*+G^luH!V(*4LD+5&t1ztPJj;*tCB0c;d7;9R6E2;hG%y zD<^FKzjItw*AvPe!_?CK^CzhC%^_YSZy)$v1@TvK`&~<={}9B^i=gv<#GHL^o?|nI zFHoaHqjf{<G57LSb)22gP9Pb<zaewEi~v1v2ZECX;S<LK0gmT{GXD2}H`=*k{G*k9 z0L@eh#%cndU)KnL2H{qU1BUK)8?ZIK!y8|E;@JVFVs*58NcYA$pyW(i8puCbY4c3K z`iwdM@gpEGsBt5}&S%ph3aM;4#<dd<(_zGfkbJ0&9CcPC4b*55PyLm;l%%nb*a7yU zxTi^HbWfWDAFDndv;FVWb273zfoC4WmhrnQf?`4SQeh{yoN>U`h*POw%6XynaS1;G z*~>M0^l7Q<_2&4mf`BP&VqiAIfh6CFclfM{$bb-TY~|229qFKipuxgI!^EH!ns@)U zuj=qugTO+PTFQX0_v9~HHZ3(>eBTHk*Wz`C#8wKoLS@*KieuBb-S#Gn`TRPQGQ*_0 z)PJA6c0x-=pss>?FJ|+?+a>a?T$$p(__H>Ig~ip4JRUuI^ekHZ2|&mTBe}u(k)V3g z8pjiWr~D5A8WQW&h%3IdS+u}eD*|TtfQUnyDZJXl_LyRkmGjrjtW0s|!AsQ<(bT4w zNuX(+Q0uz9y={!PGH^VUz<lVrAm2!R?~-i2ZDzp#=6hINd+EU=$CQsXa*T`_gT}Tx z5(sQwpMn%d71?%3kAM6QF>|sN?H4b{P-W52X}MvSVZ{S(39jWRAOs`ta3qD>M34J2 z$%N3B`IPf^Yj_OF)F*p7SNgwMaQlLzpb6%cPL3Bjfx^RhD=6liNURnM3-;;jlcHU= zwUg#en|Nps`JN)Uq6%E#bpw0w)nKV_xg?mJw091E1DC?cPL{969kX0f?&zc^EkuE# z?o@%r-pwkSY8sgZLFIT|T!PEz-LEj^>2@mA`DwYkaBu$#vdOGrtYS(&V!b(PO}AaS zfr>pzkG<6nbdbn7gmXZfC_IFT&C4sTRqFIU8sHkuRoYd1ZY=vJm3d&J;Zl1(J^pLf zf}==RGP{Z;i73^;&Pp9cZ=jzixg}l+qth!V?Z^6Njz6ev?8z@{m+x5_RZn8HYuW{E zGme?P;_i9ar;^2^yAaY+Jt3?kZiskSlM-z~Z4C*Tl$5Gj;s&DpsX3v_m3D+1&qewj z9DNUqR6@D=<C1d6X49UEjt*km;07V}xl%n7m{PGup?Tr<q#q)tI4ZhS!Z^+Ead90~ zuAi^SwHC*3fqgo&*4QkW#`dt|oxm7=yMZh8*+k1PPA;j>_R{@mr0?1NJ{qjJm`YVV z!ji%M(c`DAeb7H~@`Ts{^S0{&tW^u@N=|R4zOA{wZ~9cOLsPfCE&Qjr?&5irYuc+X z%=Dt-@420i!)SjmI>q8y-O+M+1S42Cq-<xYXUT-Si<?WuH-BQiN9y!+gR1GWHnTnC zg}v5P;YZ1<?WUN{B1_s_`;(4-1o(Tg3-~p>*P>MU>28Q6JNj3CRRR9jS^}}xfn8Jt z4W@`y9}x|WuKl9!t4LEivk~X&kwOb{Dle8&@6RmPC<}d1Iuj>f>5I1BCtanj!|7n$ z&ft^&tO64GrqF5wti_9`uHz#tMd+W;YUu=gV2$p5DR0O7Mc!57WikF;{k(z-54wHV z^6oo(E0>ty($wi>1P>frT#UYbYXX52Z;K5u8pS_ox@RT+@z##FZ2tgEWH`2>R#}ut z)#$e9S9!{(4-%A2I*D*V5SB0{E~|I(>30bb^=_jXO!7^Cn`fYaBqh=vyd1JAH+a(_ zY4KTFpwr!tkWc2m9U<>f#nCg;ANX_cuoP%A-o?Mz)UP_E+1%h$Fe(_`QDG@9A9}hE znvti+`p9dlij35l?3j8un3FRoc9aJ@iS$n}Kh=wS{>sooi^+qQA6#FmEgi@+CaaGC zIcWmjZkG;HbKH&9-!N57&{}8d>LE2We@Chw(~z6xS%ECK{wX%b>7@!SQlpvhPxG^n z3b0qSPa(qUFyIo-re{M~ps)V&tE7-@`LblK{28aX5MRyy%R-f1Q{ty?-4muAG{1uh zBRiNQUg9N7o-d?9+=`}iMu7_Ejd{GE7qvC(51~Y&bF7irfufz8!;AI}?|Y#4T`DWx zPqyvZSv0n}e(lN)aqhA@?!cKl@9uQcHOzIA!&IglDs9&W76n%lgsTMZWnLupa;Dv- z-dAhmFltbaGfYS;Gc#3iLBJPErbi3z8jm_RsYrUbz&v!4D3-c?c@MrE$_#r@#pRsC zD*+oS>3f1_zJt75G+1ca*V5QDk`!KpVr3Qamo?(f$NEUrc9V8I2d$Y&^p9v)5pRV4 zA}Uz(40e^}pZCt}^#{!1x5f1jdb1}-TdLCnw#}vzAn>dQ9Z?F$VATt$3^7<DvSq<Q zZ8i!eObGB<-otHwX;?GkMKM|ffIR9?WQG5gXYZX$O_dq0>HNl6F;z~5SH5Gc?cbGX zeA?fO&<v3db2goTqUctLyPWbC*81|O6do>{L67@Fq%f=l;hp>n>2PlvBg~FjTB2>5 z<Y2f_G%0hiUZ5WD+rX|se%d5d;hkQ7P55HD3C3aeIwPP6FNX6kS#o6~z+A1@HY^te zx>H5Z>$Rq-in>1oo|)ddB-S6X6?q>w^k6!l?D!r1^b7O~Q*~Uk3$KRtyseI5M@b*F ziW!=VHaG(V^Jp9t7@>@MO&|kAylJ+(j3zlvjiJ|R4eh)@3Wrr)hhM2duZCWOj+-8h z!R}H7P76Ijh1Z*6$8sm5+T8Yu&U)m=Kz*5Pm9%}~2x?Vk%92gF62!eJ4rR^<U&7wG zuL!!EQhEpt$`Gx-1WqpERb8n0aCzS~b5=Q&4)RJe`1KLb^+Zbxr^;7zW$=>xlz0U3 zeFDvwb+@%@D&i;0g9%p?7C@`ZA25Fg^6m+U^J`sj*Y}TD&qP0kELyA9WonjgyrT*U zib6Ce8a^{$x8=A+5F$4KyOo40dy#803vOW2&RIuc8rQQCGX494%t-;TM%@~Gc`OD( zo@<M%qeVuC(-U*OVwE1R*ly?VdjZ(&m+B$R$`Bg5#oR^tEv}0B7OC{YBdzZER*ORc zT~$tBhU<AZS&#7T7d6VM6!*btwl^*d*Iyo+H@+!G9^QtE8DqCTv}>Ysq<VSuq?$Sz z!{?TFCUnQzy^~)hs@_}*RU^5(Zdz#j{Tdtp$IA2DXdaEcD*gLT7L|+5c59<ckBEYV zhKXXXxQ%tfs%I}hNe#HOl-b{9tXhrIY_B2ao)Hi}DL+5y&>MDhD|gA{&vJ_#R;P(p zvv-g$zj^n;(cS7#NGA(lRHNOgg<^``T=vy(ZN4Sd>el^&55IU?A#$i|No>>am5gcR z76YMx;2XCr^0)$~A8$^$ss-%N(>ZG4t(kE%=GsG`7a>C-%vXq4*SEG6L?`{O*g^Z6 zd>)?dVrWvys5vZ4kJbIc!}w?K*my)k?K8|7ka-yjA}hc#Y~UjPbI79~ZgF2+x@ccw zt)s<vEfomgdtJbcbZlI_8QB8g_bPQl)s&AzT>|)3{j4>n(RqEWVm<1skD1X54R!@^ zR}(9(;sxt^H?X-C*FwWj1?XyafwHX1(3Y}5<iO@&&Dvwnp4>-Q84cAWu1qtFs_|8) zBRNLoZc3URvciqOEL$v?4O=oQ(eLs<41aud^d(A(C#|;cV&FD3=Hur1C?X+FRsuZp zUNhZ(eL4A!8M%_NYur)8m?K;TC$~0#w`>KI9u0jSB1In_`t?VI5rRQC_n}cWi=ffQ z9!gI`d@0M{rOMh)BOtqA5$`mwzy{Nskq2SuSJUDgK%wGM0`0nJVsTAg_S#w<vHjPQ z2#)hg56286Yq0a${iUolJ<EF&w=h?Kam)g-6su`1L0vDh(2q9;BCwv~lG{bD0_ipH zAW65o+H>tc-rS2Fm3fhIGO-}ny;6UG_+q{bVF?l3AqUV#+RhKCl{+1kt=)FyZEeA& zNz(JwgPe;dHK~(S#R8WcO_&K9{2lBpu!0z&m#aJjm2N6?r|v|{$LcY?CBlN$TXq{- zB`F^hJs92X-T}d!q^w9$hD7$p>P4In!#xWl(j{RhT6)GItzzAA1$@@~Ok5%2z-nj_ zYcX{NiEpMC7(UMB>PCyTOK32{oaf)CS}4VeL0s<Y_1l7V$VxA3eEs>pr)o?W5dEZi zTu=Y~ngO$c=q$HG1xs@wQjADxC^$naL==l-las>+IFEmxN~B{Vdd(twL6NOa;p>># zX_uzOBh{)tv`iw~tdJA8=50wX-P~VXRORKh*XwjH0f9+gy12Hpk5{?ZG(WAOF<SEq z>^mzzK3d|M`skVbbHWo4Dju&NS0;x4vd>jjy!=q(^_BD;Q@%#&HiSgpI@lM(p?_7V zK(cJQJ!d4V(BM+ALp|m~^21FNVWCAMI>7%*<(_V*mz_H@jf^<kk*-pJ{JHX)p4gv< z3XaKH#%)^QM4#4rCt5+7me*Zt8F^u*2}Jf5a=p^AL?DUsPjg7cz#MP`|I4qZ4|Vkl ztf>O~+j&@o4>|U~D24^j<hZERA{Fs@J!8iDn62)>c3sRRa-u@0pm3yoyOnl1k1mhv z*9d>@17dHVMB>>8A03uP#A+oEg@a)81^9=!?$r^XC%2HNf&tuwTir)rlUKNP@-$`$ zh&RL)wjS+01U8A0^wbBb>%Cte>XMZ|$n=j`fDwOoyXL~OeQ@_&%`y1>hLqwSOy;Rq zlfG;GOJ~HaLp)1<#Yf~>kg@eLZR@90!<H9qAT|$i3NqZ;V@OZtSmur_Pgp^{`}3a` z7G@LW&mCJni9WIK`Igudiy;$#kuk(OtRM2`hs*p3x??f-(sh1&cqyhmkR|(7i#=j& z6v424vJen^&1q97(9?Lo5<JUqn8uz%Qa@`ZPRpXq6zI;YBEf3XDp72lw_sF2_E_DP z&(_9@^hX!lRaz%EUJ8f6jyh*@C)hYHx^EPvbLY`uM+nCna{7jhVr-5UsmQ7f2pNB_ zdK&0kMO{9}t9N3nWA+qoLLuhM{yv^CQ~y`SB0tI>L0&(>Mp^SSe_G@@D%St-H6aHk zVh5DJ6fyWaDENo#JKpFy@>1)9ej_aTOgOYcXjw90ROFc{my50l8zZbRajs(E(g9CC z74i^oh0FfFY&n5C->8{9pc{c^sZ8&~zUgUtbMHEJ1fA2Zk!k4MJ0ggqUmQJZ%?J_A z6-vo@mcRF_ss$tf)(kOu%o8Z*e5&a=h1Xnd7czf8)SQPLB{XZWl(#6E^cR*D|2_8d zt4VYKY{jTgXVKP9z<$fBo)#w01s3hKK2EqMnO)n}0jlxtr+62HGa6c-K<4sBC8lu6 z()8)ACp9L$f9}eElpnmF7o1iZ*F4u@O1c?log@D@WaY2328r^-JD|<;=yz)R(`Bm= zzJXpJ4}R2YT>cP3Yl{vra$Y1`xWkzpP4cQ7Y2AKxx~T6Q>@8<5_#IhAUftmvu}R+W zdqkNoT5z{p^Sp(<AlQFyeqO)xf3N`SShZv|k_hkP`F9g`7L{%|fy8nJ3j9~ds4>-V zMg@z!<FPKV{Qts34OiALGDU;62)wTuRV_V;93I?U;Dpz@RsHw7W+BwnS7F{0nCk0L z{<zQgF8>B;UhD`(XgA;J=Dzdo&Q-F-V;uy1P;cqF6CemG0@TjGQIzEWGl+ZV#{Zxp zr<@7S=L0%suXReRZd{*Ve7_U4srny+$MnYq|HXF6X>NF$s=Ax4hjKD5-KKa`{y+b^ zqQ-N{y_9zzptBC{{|olK_1~KWgfr?Zy|a7^k-7~ynYgL)%>2vz`^6pe|N9N<)}GkU z<O5)FUA!u!cQ)aFZjsl`83%q2I)_3oNap^15A*B0M34r0X5Tu-waeM>0DSxnyTB#r z130;jJYnwq8`}P#N&YtZgjFXtGFkmeg!iQ)M&_EX%KGo0YIaS`=~@dM(neYU<!xGP zY@YrTmOFnBS-reaMdlva@RJ)yYX2d4Id7f3;~EjIe%;-?RSTGRKcR>H7xw%w{ImNm z|E*lG?qvN)s`2ftfd4faI)8sv1%T51iz@m0T%qW#G(d8@OuufGIxgAK{NI<q396=_ z0NgZ*rYj#nV(Ru8(1tTDUAK@BGyx89cX-hMAvh;%y7Dy}snnqdKKnbrk%0DJ@r=e& zmcoGb+S)k$Vh6ChcAo^ub`gMA^$7ss0S0bizW!6twd==%fU>v%{?OtV0d4u};W-(6 ziTgS=^<P@rC#;q<28~A5L4Ij9+4QfRz6U^3Upp*>NJ)<Ju6lX-mK*7YvNxry&)Cs! zE~!(?^k=ga?xhuPTjQzL&K~9sK**T;nX0?1nXKK|1ZP?Otf{sqmxk;RO1FvBCX)SW zNIdN0szU67nd<3vAE~^gz0SMJ(h2RP!V3e;T*o|0OPn4gGP5iC@KnnOso(D6fto3r zs}|S{;+NwqPF!!e6u=G%h;hC~{~VomzuyW-_PSO9NRkR-M-h9rQtMEa1?Y`fp~gDj z{rIgT0_d3BH%eyxWW<ww3;M(P)rG%wWX|nsMI|{`b*G7e4sLaPJ2yVd!l|yVFhRwT zZf<KpDg;a$hj99m!}cEnwQ0`UErTr6S*PX>_4b7W|Ar(~QFl{ZZ>LRjPzh4?7X0&1 zif+a#^E4FBSE7@dWK9LZH;|j3jbMt`_emFU=^OX<NV&?{;4f*h1dUi&r+EK~!b=|E zmqgM)1XzWsRPn0ny&VnWlEMwQ>DE#%t)arg4XwQ5E>d}S%=_K56kOD2Tz_!L@(3zC z^^2*Q>*8_)|Dvh&vU0Gm0OqR5DBc+AvH#G8p>Xg^fgVTleJ@DUo$jvCE>?(xyYB$J zo-Qu11RC@dYuN*Z^fL8&G?~pVx%`oAG_JiNd|}v8y=dpW73gt0(ab{aTHSG?$GV1R zf8$aGPn3sjt$ufXV;e%rJkWK&!MVDA>5_k;`n0X?DuYAS6H3#%tdg#uukFyB>`@3r zx<sWsZQBRBDui(7!zG{KJ4QG;4BeV4(42VJ2_iSU^5_4U-a7hc%>Dw=pWug$aktj4 z9gDSI)U8hH!_SzmCh^F(8-5cTIv(~r=2O}kQ<fPoWbH^=PhL++`Mfi$=klvx{=nGx zL((25p<BRThvrC@;i6&fJ@OJ9-vJ&6EA+&18Aa!}7)uIOp6`rMrr24h>28KP38z79 zbQYLV@yVB7CU{%in?x6^i>&(rf-Qom1GG>Oj-GX&b5n*(qIWpB`g+c_zM4O1TJiVV zyS<X1dYpi#K19)#qqI1B*&x{J2+voiF&)Z#1=mZMcheqcH*2+I<y1jgG<&wpiIO$- zdRB@=6L2hjLI@j7qDF@fZ!k}<^S$zbdjB{O!I}&aRZ&z6NWF8L!w%@bTYtNLWOIa{ z=woVeR97KZ?uj*&TlC#I{netG+FWHcJ3GCZz6yU%HgapAOI^Uxv}Y!`QdT>cF4no< zH)W$@gO;JCWz3)y{2IY#>T{Wx3_D(f*<b<lAPfd86)OM8KMTUHnU-d0J2$M-n6OWB ztm-EI{>aOrF^!XIsVRH#xs|O=9EcvKjw|YXh(Y2!k+0JmnZ_D^v`x!He6PyoC+<=u zlg%mGF_>~R8*}rJ4R*u21ZxUPLWbTz`n#B{CmhP5wTqA8mT3?o*G|6H=xOuNpQK}o zTC(De>EkW+#^zCWq7~F?M}dN#q!nxd^c66gIS-hs6w-3BvH+mhB?;2&n_p%vIMgMb zFFcbx8sbdwcwRTy%`7q^TEnZvAF`4Pb?DAeme2?zv?_4va;`cTIGA0kYpZ>cASLc_ z$j|*Bf*=%#r2Wo_moIX*r)*|_LU+DY#gI$;k)P{K(RPr<GnWc2Lq!^lcXf0@OkqJ} zF>ha4&cOR?4gi`+gA>4>61!Jx1#OwTNH*4~3x=hX-ZGC_$yM^?5a^CfA9An|>!Y+6 zUNCXJrJFFWC8hh0grCED+nBCL+2-Sm(U^9-JN()9Z=y$W@Kx)uWqHg3@Vtlm?>i}` zur_5n=B*J6-sUPyQp7CZXGGhv!TJ+P#cE#>TGGnjz@Xt_vWyr%^biv<ZDCX0<kZC8 z6hrb@_>)k9@!BYw(VB0Z1X78_+!FYLzI#Nd_Ly7dBE@>%)!@Wfmo}gJY1r_vj&s|x zx@%^3Zo+v&|MFc7GJ@xm(NK=FaX7m;N~2&y<DUG`F#o**z7o|;i_~+oa_xK%A#hR0 z{(f$jlTbm)uRc#tPil4fV>K!cWkyFwc>)5?<Zm}y;*{3zAV>D~RWQ~cuE98u<6g6d zHF-KZ?-f^m-`lQJn(ntu%?E2O@5YJ_zKbz0=Y#%oh}-$o>&dLT3L+b-hWDrzZ6`%6 zc`6{pgg-5r#(EPP1!Sa}JWzJJvuSAi86@$&fm~|f{`N8myMpB1sGDkF&PpIGb5XD` zoe{X6C>gCA{u-5^Im|Gk^pKy^TR5G1n1&Hkhx|ztm@*+g%BxXmfneAzG_VVhVwFif zWVKIuwb5#PDo==M%nd|-8s`|WpX%59;2n#QR-`fx1)QlWH4JtjZwkw1OL<gDRpQKQ zHDJl%D+wW7crP3)=FkAU(r+E62--6_Y4NvXxxe^BF+I;-@#At$np~7k<_7wc^n39~ z^zo*X83pi&PKeuLLuFNE35;!a|Kv(zcy3LlBYuaP?Q@e9rP3{Bfg)*G(=qbA@_|<5 zSoTd7oxWgAG|#s@64x<Qb)>HgMp4jxG*=GjQU5g4_$gMA{=u(j^Xbh^y>#N&NtzOc zwj!QqX<=QI@=B{+tUG@iLj>o=;So(%4=~;Ff=>MkcFF<bq61`eQ%h=-3(G1WhcO?I z1KZ07n3p~|C7%M#o=|z(oLRks(C9Yz;jD`EAFwKxeIb)y6AOIxh5O7ULm_p&A#^zR z_;MZQ$id$zm+?wx85@!0{>zh{7v<8%#o<|Td{bZabSu7!*I4xv523QlUX;ACevfx3 z!fmO__Gj4zzbX}pR`Vy73|D@6<2UrB(ybPCmNl8%#CT)0C8YbBwGAs&l2lKZ=;^%r z!b(w%B%1gZSL7{DvRpMr2_=+(0;^{z8|56HPoYvFuN-(^ch<MfBPfD>S<-$RX@=_= z7Cj)}&?XJ<GshOc73k!JdaQkGP2Eg&cZb;>A2hW6X>4eEmT2!{@Aq)&rDBix`8t^6 zh3PlQ$d3cIkw>`?D$?{)oP(hH$&*9M!(gpfRmrcrQZMrcn#bu;?G({ogJ85hMic17 z?sQveWM$jwy)aAzWu?kU%SNX-*e}Iei)^*d1FRHh&-=UBA5i9=MTg3`xs0<<2L)ZC z>Nd=S37%Yk79T`2JLXbe>jhSRb3C6jcY=A|g=(TD<9H(d^8mfS+MK_jEUEK}+ValM z)hjc%Ps^_~&r~&o>f?FOS}R92xR>|r2)e4eK0xe2w{anh69d*X;vFO#>(^rmR+!4T zv}A{uS<$4C`;};;S<s*!_6eqM;}N(<z4_fHkb%nyGq)yn0oW4E7)LdE^Kz>lQOjk} z4fWRt`<(Gf%6IQ;a@@A(R#%I?Ye8W6y7*K@wHq&`bcff*>uXVqT>x+WqE>6%u(nT% z11+xxc)wr!yZW;APc~M21x80{8OL_P^in-!`(v51A5e7(3B4k2y`)~l921Qc@b@#X zG;pP=SqdNO=NF^I8Jy^$%H%1!H7~l_qan_gA+@rBRa^5s>F$d{NS8p&Mws50&IyoE zO?q%*^q!F5YU{gwk1y)%i6rVQ(ImBr@9zRloASPpn=sZHdDTnB9WT5NMy1lz&7ssX zP&V211&7IsX}kRZZ`>w7De)I)9)mQwFr8l>PX!W#Quk|W+tWrzlLGZ>0~5F0UaoOG zU;%kiG=y-h1yDGg8+nHhtn!R8ebvx{fxT+$L1M2pCXMU<2vub|9Ru0Sb?<RJp|}y^ zDAee%bVF1D<E(d>tggP9RSs8FwGj<^rli449I?*}aA`{o5Hf*b>BuoVl)^jzwGN`Q z5si7_Q==M8NYdP7+42~3{?ZsfmcM?=&aE)=#nNGbR~U5%CZK=tq$`{$yalVIm<f1X zd9?TwZhpuYpKl5<o_f~AKKnvwHzx5G_h!`SGnJ{NXwJJ!OXWCuH`GFwZVfwn->*_e zf`3nwb{3iPp8u{!YTBj?r}H;korzHWO|@FF{;pa`H~Fozm}XqGgeNT^wLhbOq+b2Q zO<yrnC8Nr`-&TpmtN-KRnR7pF%6aXbz``f+*ZP0PDJLGWXeFXVJ|W&D$E0NIX*GAM zE4T6US6bxm`xI5I?C7mo=tPDvj!<VG&4kH{@9?RFg4NXxiZ!6Fvu=}qd^Wq<DZ3+7 z)|5Mwl_Ly_;$?la#~swG!Fm0{2^T_L*gq(`9M7{cA{|Q5J=5TVy*Tf)1R*)|G{@0n zRhG&2CHaOxwc!+=(K9#|{x)Va{j=#Jo(2a;O;Bj&?|v|v6(8Xrst|0rOIZK?6KjEK z_*urj_Mu>7<ngg+8OzZ1O<d3!{Cm3u)(EH^(CLwQ%|aKwjQSW)wxN*L%J#3|`X+85 zU#>}I3T#?ozJByaIqXIDAEeF_eNPv?M5StXCsB=vrI`}5^-g-txPSoiD2g+ji^!=P zivF3e{QlKo*b~o+QGQ$Bc3BhX5b6sZf;BkBSUkCPGfBND$tNJ$g?q8)V$;31UFnl8 zrsbFVbpPtnUK1rkbD?kbt6_mEB_;)29B5OfO^wh?DVvFCQAB`g%8gTb$VW{5>%`9% zfmZeA)K<LH0#yq=l{($o-EGmbh(U{whAj3T%7nfi{26QEZW1l24_afD16j16WC{-V zG0!+Wy?6`#Klu93s3z9-4;02quS#z!y-P=06s3kDy%P}-0@7QkQR!VkK)MJabd=ta z(4>iU2{nm;^aK<`%RckGAKw4o=fnBNELPTJCUehyUDvPO;rQBsSLnp1C0ev(lf>tw zAP@P8IkvNRv+h6zTaqOZU2YZ(3R#8U#T4|}osOAT=H-T`11VqT8SHXmoR?CTuMxQz z)0gBga<Ni3u}b9X$b9F6S<YnK*u;6Ini*&2rccJa#38%zn7zvdCsv4NVZ8=-t#HGf z&j1TG9TYZ6vC)gl_oB;EeNrT7<=(U+N(}w;{N46^isJcKv&7>R+rG*Y(hmqtI22px z;WCc4jBie{z^)GOE3|xGvVP=Aa}|Ssxo<3m49eNiMY=2}I^3miT#6hcJs?&RcGtHO zdQ@Szx2JahqKhh7`!AoC<;x|p%#2?p$;Q~0D+bGg>9!f27$2JT=0S3&<kI349aN@N zO$jPrEP4b#Pc6Qlt{-D_O+dD`NjKc2+Hq}a&ZJ}arx<O>w!p#N>50N~b)DxSXjqy7 ze!dj*pjK6|hi&0PE9XenqQh>1wE-NAG~nX#aJVdTdt!(`^|3Fj7*q8PLH;$Q!HzEt z>}e{uyKGO=YSg&0;7WZnVrrokNQIBnUIg8+Z=#^(UQLc>*e+iYH1oO3WoOhE^S)+1 z)&b*w<sS(UYKm`x0;I|K7$vh9R*TGj(^AdjS-bPzX2{;+xq?S82mM|?UP~&$GLm&x z9t>dpZ;3_@tQ=lZp$QUu^Ai%-+bMitV}Ipb*S8b$9pdhor_038=Snc|{sbpL>H!&s z#9M@JB1)~7wjH>p<vYz&zpXCbd$rnnCY>h`!s?sIn&O<Hl`0?0?9G>VS*{M`ZgN~^ z^P&KWgH{|?g6dFj)>A^RVlu8?LXz69b70lfPK!S;gr-hE(Z)!|V59Yu(|!*VaSJ0A z1!0g+y9LW!KOBIwc!Xx7@`h3{kfz6;-p6u5Q##Z4qBX;BX!2#hc#)y&u{>6_^;^LD z_**AZaf~Wa(xh^)!lA4nvsGrJr_LfVO)lRLUPrL-9=>pT{Z%?7Mf8Ww;qIuCs=3n4 zpjklG^gG|cc~P!Pv%qDfLg9`)T_|a)G43)SFuy940r+sW1khe3L1nm@$pl0XGh7(p z;UGxF%r*2?B*jsNOFC?_o|{#Rq0&3F7){8pYYXD!{~=2QNH6s$5alkq_;mm;5SlGt z&$3EP{zc-#lhUzbI>pA;FKZ9^kDpsH`b5qtdtJ^l_EEZuzWuCjf9@T*;tP9xQbaU8 z*AM3*n%DjUoN#MwVha@t3G_N)FsWMa5}2bCm!e88pOfDrr{8$HQ{%N2kdsteZ{x%X z5`O-YG-vrYdsS_Y8#nFcGA(sj)6^|vZX{|O9D6hI!Hbk>g-lT!B^*Wi(1vZM%m}fV zKbBl2nIC6i(k-l==QrSIF^%qZ6|R_Q>#-6!SJLz=i=5#CCCCwtC=&)c-eGKMD%)ma zIm|@?s)g{muolm8tPH5D(jp_PVDobP$+kk|L@!?Na8V4W-ESX;f^&3<sUzxOu0tl< zHhX9AgtG8e+b_w!qQkeUus<<D+TE(<0peG9q<{|R%c>k9ZokrH-H1MNdX3@21K;b= zQ*4AcO6&5*g7))!Z};T2^rC&yx_+er49gC7pYzc2ucs-myF}}6FOj|#GfeI;5LmJF zdl)=!Xx>KZO}GaEXGTy={^L|%a|@Q=&$zU-B$(n#_5R?e2f;-=bA&zK*7h#lbV!eB zgxLAx3k!Vf7vKl%P)J+<hwK{K4%%~-2s=W?1yIM|X=nP1oiUiM*~53{!KLT#v^_d` z@sQflLwqw;^1-`L>>C2f^`f!?zvhx%xnv6N9%>rsYLrzC-A}Y=R;ph4M#n3HgERQP zU=<pdSw1VCN50oeQTkr5m!e}D1D!UmW?Mj5FjjKAYOt7kF(Nc;G~Fe6*v}2ZRldVr zf&G#T0K1c7OQaHOy$|FDSP;(fHbVKr??j$eZ+Q9MMHLG^4a&OG&heL*`+}|)xR-kq z1fi2s;s$;d05;-TTUhddn3+BCKgOYQEA$3)`|_;Q`!>N(7!kE~r_U`GRY%7<o>*xR z>0iU4D!jlJGQhDloW?X*x9oxbR#?(c{-&w+Mr~|Sy49T`^N`!N71_TW^fH$1RWock z<xJaE%Pvgi@ULGqA#CGTF0*jvBS>;JP9JDX<@qSrH^P*`sA%|S(hUOWS8G)GUE2hh zp{x-_DVLczGVUZxv}uDz!>f==?)koQb5$6npU6;|TC=j&J~Bzw0Qt+Zh~v|IdE)4q zU?P^b>Pz)iHp%s%pG=f&ptl2&*JmWWdZcz%6&3>BYCI3b?=((Jpo84@J*VYm>J(n} zsy?f#B+K#ItlR0Oy$Hc9<#*D;bz09g>q`B-rndh|s53oS<a;qHLid$9*X+KQc*(MG z&`^EySX*gI+tvCxvB7i26H!UG=JKYE4Noq9Tx2rIpwBlIp6Q6p#7WrF<R|}{ombfU zxW&wW`tfIlM&3LAg1ZxY%XS56ADZ_~`&)S%hx4j8b`(hpjKG5iwzjdp_;6&#?9ppi zEZYXj+3ZC}og@&Be=LQI5QbyC0*&H|I0!eo4?fdnUU3Wz!fQ6yBSnqFKP;Jie<!29 zmG$}OJZ9nINeAfUMr*wHvu4YnRADcQqg+%1hwMLO;)PjetOj)ol{8e9+(;C4F(q_9 zkN)+AN?kGSBiD-V*#$k8+l?Fc<?(!yf9+JNBo|(&82dd0wc>>m>_k$kClcZ$T!aLu zG8znOw`XluG_Av`EQ7&M;F>UL9Gnhc%<R-Q3@Q=#k_m8(jb$p-jy5n1xGcZN7C$;$ zjVfE4dw1tD`N2*rxt{99ep<Yj>fLi4sEh%YT9`#DYNDQKtDj_?InkSGI%_je`{>yb z>SYrEH)N>9yloh%SbTTGMn9ZD_!uHT2{3H>TL0erBW|<NrR{PumQNul1B`uI@-SX3 zd~Bc2RaA7ZX*0SZtozIQ6#pk_w-L-FfKOs)dfgA{cF&qfGPCkJO>1;SJp&DBE40PO zZdrV4Nn2*po5oL|(;n<8S_W|oF;`s-R;0wNML{^apjZi}e(X>^Pd<j183I{$SLQB| z*7mL0Px<MQi{@u6)jw{RV0z*!x1?}jO}}d;x)@=nrrabgo#JIxHRUy3Hf{RTKpomH zvhBj{obRh^d$L#B-_<CJ|5nV6pNDdUJh`7`ntkuLFCAMrI99TjU8}J=0k-@Ep{tcw zN}*?FS12-5!WSRgKd{P2l)%xaBoMB8c=DKgN&<^fQCY4Qlz<LmushYCev;iH!U^UO zD~(DJ5aIe{tL=>s9_D35!>+AI*81dJU9%>1;S6VLSXMWlDEoaC>}*eUE>vjwwZH$w zuWVb~(((bCP-?mDy$`4qDe%()kZ36<PbdP~;<w!0QyAub%@*~RGf*?R!o}dI#`eDD zC5H=J|K3I9WewcT0DO{4EH4tu8`f``39uKXW$pjI-NB8>IiqclNRe8^#82|ccILiV zQ{Xl(bL7Bnwauhexr9q4qD(Tg!fk(=Osjv($PBL(fI29o7Iak(*0NvHeo>9c_q}Os z%d0F!D{hjMA~41pSE^;&KZ8_c6L>({@i9(BP%%VD*6U?a&Lnr44nuZodspGxcKZPi z%Kwm=dy;^TOK;2LH2yED`G5JycU=K=g8Ve`>wm0<Un%DS>U?2XKIx$)@4^3YuhhD+ ze>(?zk}?0=hs5kZM^DN90np@%-L=c(KXs%w^7F0Thm`+=QM}9GUj>&)-7}|Djpj{h zr`MO@3mx#g7H(v9j|bsLJo$h@21Q-Zf2?_BD?TQY?Wo=YNXM0+U0|>IC1%T<_TLoR z4_E&$Uv~cAe!6s_K<FrK8UTm=D>1hB4g9B=&}CThC8bBjhpYcihP7cX#-^Q;Ek^*S zdu&67`vsi)b1Cp?n*~yjDFEy-FI&?8_xR}z4-ZbEmXy^|CcUe=@y>+b$bZOOf50b` zdH-(1QH4+-0W}@IAWt$EAbWgS><G}u@59#sYBJTvpRgq2AL#zxX0ADenoIxTwI6g@ z3znT1*MSyHjQ8eXJzxpEwCn)MIGz-D1VArm*K*-&KLOlI&u3vK>X(bV(Y}N>3BCn* zo+2+imi{60fX8%1W}oy(<G;miQ0js)o-7PJ;}6#@W1f<K2Q>sosd8frZys6^c#6F% z9EKlgf}5B;jqG@uAt!HuL1Xv>tViJYfNCp!JWCM;)=p%SoDC<RaxOa=h)mjdSk*Fb zn%N5K!>RS!49zxkuGpM_FEw^_5$O%nIs=&xZ}&FtfwqR|&wuw~tQ;hQKefk*TcOw~ z9VyY2lg$Am9{%D6sy-_BF1M(^)Hx0F68@53`h&i`l7Tlh^8#e-ViKvCP<jqF2L1#N z54Qme`Pf9VReVzS#f-!;JE}rdQ03KDi--TYdOs=r8F1NP5_8OdVr}n|CO-imX9FDq zEoqD^u}HY4sZ^~1OnsWDI8b7!{;|1QYKZsf2I$Wmyq3%#gtke$07&G39flEcp@}pc zDis^p9eRcvR44Bx1eFHxea0`u)z)t$)YTO|S+3rAvoC$aLJpv2jlCJXLJ<C#9b!Sj z=NkO1B3{O-=oQ^&uXe!Xk8>OVS}f=`5F1(I1!gX!>TKN{M2Ou$sWGUKcM-|n)7B~i z_hv4voz+rlOBs7&a%85R?gUw>MRAZ)&t!bQkt^XA-aB!$u+W)({E3;gZ|3kdF;E#g zu!zb6R~%^=nI9KC8j^}u%hF>&m@=B?n#Q;o%)F}|Z7(&}lhHFtEy&{Dn|rX7br#&u z8`E?5vXpeshBS`DZDxHW?nu4)4oA_}?#?Vj?A=cM$O~W^)W`znL^dJkZ1Yyupbx7y zSLD0fWy0GlB1Zvm0z{C+VL$^BGBaOtR=Jzofblv&g|#1Etoc2gvfPv=?!Ji&@MKSr zn1@PUPmgDUNMDOk`4}EVSp5vGzj#S31Z2z7__(NA{u!Y;5+5w852*Sn#oR5kEpnJ1 zf3(;5uB%>-vX-hnHTG(FGHs{HkgyBK2n}(Qp9~PMe25$jT}wscTa&wtJf-5*xhCp8 zID#t6J<tO=ISgaS9cnqg(LCF)UYoD$!1m0&<ll;(q^cR6BV6sk{l8rk5PC8nF7qm@ zGRih6^$?m$T3)`<ysDK)X1*l841?ovW!(5A?|Y|8+$ZT&R%+)BL!Yhk&Do!qS;C^` z&PY+ir-(g!QLY2oYBuA9-{cp!`qzh1YebQpXjN|faKFQyc_hyb!i~Yz1j03Jea!x$ zceuG=4&uk@DsOw@%IMOsX>dh9e+$H|O@g`F>+MKTE%_Y039|1BNYO`n*}|n=36S-Z zIK_cle)sGmIs*Bd3*B38XFrt-Q$KSTSf078mUzf9<aetWwz;80^oyUre=MrcB!q_( z1>^Si@kS?+gzS8REKu@OV-BN%g}<7S6Zv3fVSvLj<{;d)e$8&oH==yZ>#yX?rc3qZ zVJ9YZpDWjNQ>NAugKHx}z42T)-1xFYq8F3YMU9zI#H69t=xJFfe;e>G6+#AOL~B}S z?1qC2wZLj>dD9{Xj(+f#X4X__bl)&xD>+>I)hK~&`3ax6Ass^=a)O)<g$Nc9tk!zk zQGsBo9Fj4y>~d4~O97P*`8KJ_<A)iC-iM|K;2tj?fg%fog~LR_X#dKgKyyQ|@n1*x z%u2)GJ332Ka!KBFzm(yzHG$OUZF1eptD~!j7KMUcZK-V80vTAdRQbFhGg|)6+g~>d zURf=$5|008Nyz>y+s_8ZJCNofS%P$z@#rvP5|1<}LU;%JyYX(Mbd7;+C(aAanL#1( zD=R9*j~P%FHmCnB-NgUj(*5%b5QfmlHPdsz7OV-a2_zoqS#Ny!U1WJm8PR6U_H#Q2 zIr^TIzrW9sowsF|=P0)$rziG@qAZx>A2LCrla^H~e`O&~<lJhit8gW=P}_NFyQ}b^ zR??Kn`Rh+#Gwe9Y_rku&5t)pLdM9RZuB~gtXwpz%ueV&QwIgp6lo@Exj}g|hIMv2# z$MlGWKg9DFGxc1#kiZufM>V}@CJ4nfEv@M7VCubJ7D4xcdxBc;yLrkYpRqQkvCp@$ zh&P>)H$H!KVcR<mcwSad#+|@#Hyz$Wk6`wl%<+h2kehavz-;!sk2hjg^*pF(#W_*< zfWeMYDqHn4ckz-Ds>8D1C}EWm-~Bf_Ee^1jQ+|Vzu<b|7Z=G}xW~~f-TrvQU$<3fu z;+^vNh0~XFxockNWWdlE=UNPBT4FIx&wV2N3y7l^TF>nUVaoWjV^PF1`x`<(=plgW z>$0<vQ;;dE<~+?9WN*(+TNI=du#zMr^;W;18FINTdNd^YF{jbbBCFITGR!E~zF9>e zU`AIk{gM@{z+p{KwcaRhVYmCNM0wg_zA$7S1{0;y3!E7`4;8JYF;}(SLe11t&iGn| zDkV%=w;03Rhle<%($p2)EfrcL?=hfZkU<VDgd2%#PN*%`l&z)Xliyy$FdOXdoW9>z zzLe4!XG`<#fE8KrRKRWo=aZQ`4Gm4N?>06z$MZjZ@<CK9QOVq#?8=WTc7IWa<Pr6n z#lsdP8G?$n)!M4tnPi%0<e6r6mbVK$5PA~O)DV#BMkSQf;dD1c-r#H1Ah{7_B2sOW zi8R&c(z8&!*f(k;&)I^_FoFbU+ajtnn{zJ)e`k#Q?QlJ93#J$TR!$Y@Xku1;z&AFc zrxbd7S!A{Z7`DwqEGut}IF#S36%sYa39T154P>_#Hz83=+|Rl7=Fwjv^0j^KVZ!p% zyB|K=^wAEuj)(BUY;^gOy`SQlt*Nhb*Y&Q`S`MB`*2qE9CNUF^b<@9~aHyE~jae@s zd(G}kL%cmMZal%%9a+dT&3_{ZVEx1CFI<6$Q!!(rBfj@xv36HaccWDOs>A6$lo)i7 z*qLmTdtl$Sq?2yUXB})<bCdDaVYnr4EJ+@w#SQA`Fp9o-jEOK=<xHqkwM2|mJoecZ z{FD4c@!bb6tDp4zF<F^B7CyMY2Xtc<!0vc`gJ_L5F?P3f_f1)L2L%pR9P9Zv5D!_! z5MsPjU96BeUv)NTw$Nrg(9D;rs`D|M@@lm(y(tV%G0A4>q2|5;VM3Tl1G9ob(H{XN z4srr)p!e$X#5e<D6z1?cX;NL3FgXB|hw~6W&ggaEFBjtWr9h3IEEvJAo))(~Y~qe^ zG*l#mGyZkTyq0GtfOoq}-6oCn$Pr>&G2CJ6yaNDk1<f{@_~-!)-a0$0!-&sN@+)0F z-Niq$@oWf%Rv9~fgWFcc!9ufexB6&a8g)ja@^G)|3z`n8gf1hjG!o`Nq;RG@;p^xt zQ8tAo&)I<et!^AxJm$|zN5pXd&^=dmFK%%r(PzLpF76ObOVOu5o~f7tLA51}&-oU6 zd}A!>UIwLE{RF4aK=n;iNXV-pM|bBRaeC6JBQ`Z|;M~^n1yMs?u}5{zHHe8Cz$>ui zKCGq~=&f4B?jbp>?QI-ZlRp#Vf6jc|)hp+ziqVX#me*=lwhCoaHpxVq#H@-jKBx-6 z)Q;+MDuu0KisSy&(_ApmbkUZoAumkx%!@k1!bGM|J~YWl3``>`j=qRp7dOB5?6az< zM-dIacR)?l`zCBu&{O?VL+ANh{`mFS1e_mbs`*<!{-ii<b7#?=GN<sn_}+vr+Vy?Y zFC4$;_gyfD96J^~Y*yZ0lKe?JZna*u&$D$G-*<TgOueF;OH_IrF>RzNb@C-4EzV&v zkQTWo5q1qskx!(FZ_xUd|2c~;I{DSuES!<httx1WlhBSysT}HN*YsD*LxK|8)x5)6 z)+$LZ#GI%hXLV)E6M5)NcPMj(nR&g@kGT|4qRr|GWF?Dzx?(46xz)2>J~)ohu{F@a z(p`q^<K?h-qsLNf&g^%IggBRrE#*ox?~Trn&<^-e$b4(4si^E?Revsgoc5-eTNQFH zMZ9KoS=^)cxQr-xFrM#W#N~cQ<A>f=4$Y^i6))Nmi}qG#!i6Hw9we>^`eZy-tw-P+ z`mrg!!?m_L#JLJ$l3_Q2D+p~A`)97X`Q56Dq-M0G@o<CSF_2P|ZreSky~T!gO%*-y zPK1zwTx)NtcwfITBDfqT0B+gUm*v#Oto8>pWm(n^WZB0R?ZDeq<24nX)*>%m@sGBw ztc~AyqXOovN2Lqwo)@%#EEe<g$jPQNl=0MUIp{vHsy|p2Lz!b}YJDbIj8h$1qf3pQ z?knAhuU9gBH%IT{fS^*+H>Vz%syBW*IA8x@k{RU0W*8$S@`(US?R8_H8IHV0c#%u~ z3fcMzydQdSaA=hC^eQa*<KVt?D%jj=yf&9VJ$gE#NYf;v%-%cZH$5eciVe^P8UB6R zl{#jaNb-Da(xoV~sy4eobKF(7@iXH|ww4lguDTt4mQN4+E?@>ry1qJ$KStR&6#Jjd zwkfMMrxxMus9(!cK7YUOn#z0sr8!zZ(l~_~^|8(}s)zmp-bAcd9E5Q3zm!y;ZaryX zLg8)EJ=;N*84st18Ze(ed{+CmS)V`v4E+YenUnffrcc02CdrwGfp-HNEc|>=-kmlj z`hhh$r4q1{w0=~pY%lDj2CXLd#<f@&s?(oVQ%+T<7^+YEWOLj`uvd<nW2lY_nZc|M zO)h%L_ps;tt|$j`LU(i#Cou`*q2{F9k*HJmvi><;w5lh&W8a-uTj@~?*IzVriItM3 z{vo4R4f_DI#TgB9T3smOyl+p2IpVmD>m<F{9`WZ`W;2e2@u>}?Efmbek9471a*hWI zPsV!f2ayT#+|KmzJhFt8jr~8}t=Z_*(h9i@n|@B&m}7qap%0lt4mCzxP6YZJZJC@L zu;jEtVHNX~S?9R|GaQc#e|z`PUQ3eUcH=3euSae4C@-)fRj7m}(w3$AF{N$hV#ki2 zXqk}07NwSqU!k&G)#NR<4!hK|Kb4igY~teo@bbb&ed*(VZ(Bq-8D~bPa%1ks=!!I# zd8Ugoac-^*%@2Po=IpvrLaaIgfWoaf^;<t+rj{MOu;1M-90rm*$HtxQ&aFBnu{tA8 z0nbDP#^}X$#&5ql-D@(U6-rU({Z-7Re*3{xpn(?4g1AH=`_IH_ygj<i7Xc9YV)7Z{ zHL@kAWJF9f-g(*f!+8MT5F-L8u8S|YmS~B|Ut3(ZwTE?LDQD%zJUq&>EW)alBt0MI zX3WTHaxd8q9NB5p7uY)+UovNP{9qxlc}Jp^D%I}Z-jE7}<jS)w*^SQI<*c0n68{eC zEk@q}-vXAEaC<IIcjBnL=zOWF+KVc4pDYe(gt!Yc)VN5peqOZqq}>9gfd2+V$Mt)s z!5aV*C7p#xRmG%$&at=hZr+}?`@y5Aa9+uWM;&z=FA-n-9*Ngf%>jdj>l>Nt#RG6g z*c?E7=uJg0MAvm$V&M!x*W}~TpcT+<LDsmWG7|AXBI!nJluKT7(LfA)%7FjvIAC$G zUtGT|=wT$jB63WV0*j7~8rz8}xI=bgVO>mJp@-k!nA|$>()RcQT_cuaA7jB1U%{ti zBE@rw?Db5G0Wn72u1`=EI+t7dwMKIxB$*?bg-yD=hhBR+_pG(ot#<$Sz8c<BJi!*4 z9afmOq4UII>Z?<G(grduj>BaNHUFjgPtxNeM&u2Orq$2JK3fG@IZ|Risd?Xa4?d|1 z^c#<TR??r8`10J}&KcjPH&@8!c>hnK1Jt<mF}>cc&EZyM`SuD&vz?~_8yr4WTQ)gY zkUKVB^==)p>6Nytw(a*+l62>-)~;9fi`-d%qoh^^p@8-<;9Cc#2(BhA*(w!HoQ3LG z4`2(t6CCSh%vhvFOGd?7ysAi^Y~79*>R*diztUO=gp$mwxIK%~PqQcr^OY%;ezWMJ zf=FK)e_2K8`ZmYs+qionVx{)7#&TX!dgA(2&D)7vvAPV&u_j7)QXes2V2WMXTVs}= zetr<XC9azPGvDImZEv?>P?znLKR=rIqGsRwSVevlBYw!5h{=23yH_<`8JA*{p2F&o z)Y^nlGz_emG;4V`;~V3kqoSo|)DL<?5+-gFScY+~X}^;Oz6*9KsB?S|6r+4HrI#1} z7dK|9ndUd<;We%E@%amXDqZ#lC#l&)ReJArUZS3S1kcxg?$;i<OmloMd=wfgPkja( zO0WBAsaU=VSG`2224l{7>0$OwVV*(u<fcW3kCKe%B8NCRJom)hk3;+za<hWorjETy ztbYgShY0y6i}NHtD2Srh&7QYk7G@##xMJt&#RHFBaJwhVvmDABgZ)1Z6)WzN=QcdQ zm%XZGoq5tjT?87)vnmL8M`bA)$kPQN*eb+O(iVPD;X0__ac@ZH>e?>{yEeeCi26up z<B&Rfz_eehP{6@#8^so`rVp8SVmI@R-Z1oD68=`>Zh4Y0SFzk(79lkNYTW9ZytS=< zZC<E##<PpBCOr82de?NJrB#}F!Olna{ez$Fw^U<wzb}niN4bW!{D{(8jXKwjoP;;< zqS9iD)bQIx`42nP>lO?|OGAP}t*@_3Ir{NOsKZmY@`40p2<ONf-D_=7yQ^kheoz=a zcJft^^o2Pw1V6d{H+rwu5ibFhPYK@P+%<0HYkSg**3Ct^R2sz{WOl2z6C9N&>Sv>0 z2~|xH4pnxXQT!)Z{g-l272~46!$Hb%$-K6C*WW`GvXvtS8c$7hc@J1{dv7}(OW&vz ze4;+4H@!bDYef*Wr*XK4VACo?3b(iQSRilzoGU<#upTO$&Q7PMtexEwEzR+PlM57J zghT`9>|AX8{VOdH!V7Ut19JtYfz{tq6fJHg>b0syM4JnZ@%Z<{@dovA91DHakR+$4 zc<-3~1%nI-!?xdcwM)5e|MgUt0{aq+mZKBZSo>GXF8pji2;u*bopW8V5G+d1tuLN6 zWTNuKc6zD3n?``_(zC&pe(Nte8fRf*gV55#oN<i>#$s`{)KZoAg#$d=ziuM&9{p?0 zbm^FLZ#Ius)-|dCqfg5)I4X%NT^n03C?MinU53{>`jQdjR(qSm?n~q7OwH#(^6@qD z^4Su=r!zum-8Dw_K`AlEfjENg!%p(ZN8b%lq4qTNlk{G0*{vKdlv;F*sEmDyRdSYS zxut@oA;q}O4uP|oOy1eQGx0n^mHKXG7@PQQG##>;c58~5+Bxvxj*FP_GYkziD60Y& zeRU2db7{83_oD8BcSYt;{Ax`KHui9$Aes#hS!7(<)(DmFB5{#GcR094-y`^|2ShBc z^@!xblU|1)iM^KJ_v!M>A9D>(d$73u%sTLT-jtPG&E?E=wNc~S=VYVnzk0ZdWM_&o z&GeM+p=ohF%QsF+OWdU7($W2H_C;Y~)V{5Z=+iqximI8mk7?}o4bqmxu)MF;86&@) zNui7uxB5a^6D0D^rbmbSvKQP=&T5$SKYEx9WTh8f3zY55LEj50rzuG|Jv>PwxbBzW zx_SFg&=wye*$wJpO}`X)IHw#r3R)EwLS<DK{)WB_Zb3v2m6P0XiAufG;w4|&1lc`i zZG4XF@)6)7hr<q}#9cOop6HHg*1pTvx*T~dz#ON;I^0DO))<~*>h2AE?{^NU=h7GJ zunJxN?ZmNWgN!TDHI$7}&ha}5yzib-X;_00H5UxvZS4J@s|7mE=o8Te6X6&Lp>}KO zFwCs*kl9VB5Q_ivz|%3qHe{1Ym+ukP1bq?z*z%Z|)<0yOiDvD;ffVdP^{e>517Y2Y zCR5J&K>m<W)Aw+d4_(HqJMb5FGDBYcR(*`x-5Xh`RNtI{lndDtyZLa>^IJrrr^H~a z_l@nG^l;_Cc~zASJ2r{tLID>hy9tWxqiO6C{BN|faCw2WTUt}9yVbDN-C@8B1aVol zFXWLDbT+<SOe6OdHR6rQtuF_&y{F7F0p}Fr6cxph!sWt!G0c#qL7#(Lpn)!R0n^&p zO&_o}Pe_k*(S%&PS=p>}Mn;lJV!|msJHE(1r3Augh@iy(Zq)NZnU+|%XNxgHsH)ao ztShw4oD!_^=A;9Kl>PgsQ43$DH!1;jY$v{WFbA+VC2`q?Kgu-vlqzyq?-{kNT+!3~ z)^^q4r9h%j!lt%R2EWA*b!*mcuLa|EdYT>eEBLu0AU#{rB`xN+cY~WvWUc>CZVesJ zai5Us_k|y$-*H+yLHYS6%o*=pmM;uIZW6)$%Be{I(rxs9myDbN@`ne<n`MY*&utwE zexD=phI`SLK1aGDsk#o<8zF+3r-#Ymy#3-4Ho4dL=|lAjR!7e?!IlAe#QMe2zaV;S z@%2^CnBI9iZnr+HZ)zdeZAeqKHmwD7wc}QNW{$kjo|}1Q^1B_sisOpOBC+vi`nV$2 zc~x^@%4<>HT5cWi_frQrY*RBVL{hvwH=Q#8szR%d2B|o4r+@qun8NHAsl1Ig{Cutk zYaIYFG#OCAnU-Nk-{92U$(9N@Fz-v~{s9B}Jz(mXS_pOT@ux8F`Nm!*a@%hO?>(^3 zH>55_FnX1vHT!!Xg5r1=6xv*lgl-%h-(%8N)u&{7vfeWPRmf3^tkNr^M@1axCApqB zCOJH_nH&NU(5y;Xo=&bgq*M$lmgDc>I#o<k7bhAFScS9ra}>>xQ$02FWzZ`V5jHI6 zDcsR8HN))V901(<IZn4vfWr3ZF^MYX+zQr-S%?Xgik99TQz*rS1#}h(9ZB*Zx!#id ztLRR6#XTRuAX*)BXIwyce}=c9_&=D#w(A8K<2erz(q~HaKk2}OIZbQbi+?x>%xv_g zr`K_aNJ=1EqbsdmTh&FE*qgP!8{^r^T{>3iu31YICA<)D;tcQPKMVG>uWqewDQwc^ z{k0W);TuDsj{0;uK{={dS~)RUmSq_7U{$0|%Os~;>P3k`yT2CW=7v3aG<!XI9m1<B zZ2!?apM6sQcWwRNIsGXiigYPOv=Dk7c{w=+stu6;S?u#)<mwwi-**xE#zT0X_4u84 zf=0nJLb}bL|1*vIPOf-~r~q&k09*O{8}P~D{r5G`%00bV9CvU~*9`MK@N&*j5c1R6 zcztU0)C2h+^v17<4Nzq5_s;eHzGa{C{{qhvN#DMSv2P?!3%JCLHVj?4e(epdZH2tl z>CI*MLMMO{3cgaB{1-gtMw*_5Z;{~VXYiqtkFNy(b=ax->60ks=Q!lW5d>ey()s&5 zYWpE0{Qoe#wEw#+X0uPpIjdGz`zn_o(=Jye$liGJ_Eo7G**@^J{|m)J?m~`OJAk~@ zIMR#ir`Om1efbN<m|u4~r!Z}uuLaUuy+RmddEcj&w{z^N0@AQMY@l_>8RG|P$l?j_ zF^>H541zEHH{2zE`^p5Y#rmZ;E^$aJMxQJzdjI-?>biyHNjA_vfB<xNZ3gg6#KBJ~ z2Z0b!9DrH64}GBQ{nwYP?WK_JJ=b2EEN*-;sj|6LxHuFVP#4-ke-+T<EnHj!RA3)y z|Meso{|B|qOC%d6*a)P)Z?x9>)Lw9vAUUl?&(8b}7#6z!@ARO{OAyYUHwFHaq4*EJ z_l(+7;^8g$zy4?0r4r~LT=UpF*ym_ysa2aV+cZY#ZN#o*ld2eiNB>d>;GqxlWP$%5 zcfiQFsVUB=Ess+teVW`QF!^ekNFVv<I_>{rhkMPC(;F-Bg{I;&$~vA`Dr5iu-~+L@ z`2))1w^XGa-c}5nd2(GLnu0Kb3!tsb-oqFGnI+q+B(V@Lag(u%mNted;<wQ3N#d+J zR(I8gC<c8Y_)L%DW767RfUp<i4MiK~S6U6iBitGcM7`2S_=NCsSEg)9Km&Kn;3CsK z$tA=?<Z>f<9`|DH(c0<4BLKpt3TGt#Lsr2SutZ&Z&BAzd(&Gy4?L>8g-9Kc1db0X} zR#UMA&_zA~9hL(a=<l?}!-sLGyx&FgZOw^ehB_P~UP!-^gkP*enGbpTFljLk6!_Ex z!Kl(-qn{>Nb9}~iq2%rLio_`VFlMrUX>P7LEdSK=fa@|3wL)$@%c@pA*WAnMb|w{j zplax4;&!K1CQYPoRprW`x)8YQA<u;qexiPW9^l?H1^_<lZW+7^sBw*2VJ$9J*E?6W zy{BKPqIYo$S)Q2uVk)9XAA^nUvewhivGyKhssZdU6@)vWKih;CM(|-Le>fbQ;O8b2 z)G01rHWGLj-!`I~jH?xH`mpP=pJBU%zVuKL=m)sNiDti!Anwn9_HkYD84XL7{-XBl zTKvbJu4(vsfsK86G4tdAJ@0mh{!zufl`DS8?-~8S>s+y0dwlibO5fK8LpjmAdCndk z*0t2+Dex{!HTB#N^f&RKi*P%5TkrUSwtevz$YPE$aibCf?YT|h?nx0S&^y+Z(<eO> zA`2c2)ddW~d|(*Ec_OatjdGM19Q8_-uHgcJ>+b-#zrE$zg2y@df{I|Yw-H!w>i{Dy zSdgYu7Hy{QsCFZ{ewy<x)~_!l!lAqz1{nESCKa%Usr=md)J1wxqPl}$$OpPO66MDE zUE=V`{AFp=;TzJ8*_RT5D%BpjFI{F|7_(=KLA@x1W%(j^DC3W&z6R>QqVxFU@nsDU zroXaV+~oa6j($nZ!Xs>-ukQpM+3dZ3X|xwa5{ffwWeGBVBFUo?<=1lZOLBmMNv`FM zmZQLd>4woF^~u%CPwE`7Rr-YDE9yM3DBX5^*<a=8&~M%1%H}D*PbyEU#eV$khJDOl z*k`oK)}_|!W6^J5x1g)GzHBB*0Vh@jkRT`o9gH<h!#)mnRg60Lqr&{D0D8itP<s7n z=bC1&>TqjFp3ZFz7Sgip073aC<hORe7bVt^XZ@u*xzLcQDWC@PK+#4#m){+1rj~$6 zD4`@}Ld}qqya$o~`5PCH2dz^=yA<DJepQ*dPrU<n*?`?qsceAeH}dGwD9@^>WWchw zmzP#BFW!{)7Ao=@aSh0Mg26E~|Bx||ZdrTyO}Yq_s&$c=+S@-hK~~%u@7h{9fj#nJ z5<*7&f_c<ssO6V&C&8EbAXjf*;$w_f3_%R1Rg8dH^kXGU<+LHQ;(>gnwjR)z0Vw?9 zm|9PXw6ggq+p1EFT_@*PoB2_2NW{`Gs7dOANd-H(XOAHA4a}o!EPIrvFhyfu(3UY$ z-hbZBr&BPZ-8EL87afRfW(b!F7<V0t%xdy~UPvR&7dI~SAF`2#LIoCpMAPD1yFE1c zdv(PX#8RV{X~#DtlTRyR4tBQpu7o|4bZ$|we7fYI0~mfV=-umdJ?qMp`{rOAH7e~} z{i>R>L(ea2W4d5l`Ln-!LHY6qOC?Iw$N}1C22vT7r4tw@v^lVUlR^LB(uDR?KR_`d z^g2$YezaAXUG5BiliL}xc!x8e&QIPJ*auns1YT0E^owJ9gcnF}j1k4fL;S>K|E_@( zCN4oLW7xddxa+m2+*FxC#j?HZ%7|}Z2x5e$p+T$%DJ=8qL)s01r$P}<i_ww0p|JlT zFRWVwthABJ?ky=8mXv!h)!GGC3f)N0=HrW>dvh&@dBT?TMg8Vw0!i=}oQlMGVcABY z{4QZwi52r^auYn=bLnbg`E2`R$H6@!cUnbf40Ugl@~(`~p(mPW=VV8P^MN-a5x{J7 z7bR*}p=?(Q_<i3TtR{Z=tV*Uk2+!k@ctNxqi+9S|c%Oh3sk0p!9GtE6vg!eMj%6%B z&u88h?UAg`v<NRO-#ht{*uLTkrBt`KJH8`zO}6UZmFVG(JM;S6^h`|i3iamr_Z9iO z<4(*8bZK~R^WICug)3%rwhM#-hk%;%4Z1CRrX_MUmfd@uEslj+S`#MoUs>@ZN_8F7 zq9%aIw+P!4m1f|DVnXB`f;6oq-EAQjmg!>Od#YMvB3yuih-uLQT)i_boO(nikgOU! z>GxKj<AH@e>B%BhWb~XmD@+k<`DTl#eJ%s#uqQQ^+14f1UT7BWm^DvH*@<V^QAZ5# zw^DPJWA1`F)m^HZ-U!k307Rqfi$vLSc)t=%_N4Uk{RKBB<vC`_q%lN3MR25kqiFtQ z*PsX{<&@{*w&C3Nj;)SS|79Zk0wo0AcdBmLzsO}Cnu)Z`W6Co*2`(02zPAAt9)ivq z8ttK2qeEtqmvieUnwBUyxyVM*(hg}RquJ*7gR1937B!aQ+-%C9ler(v$0%Q9nZ}69 z7BM}|H^ocE@i1Jr3lLi(Wg=&Jsl$QB?bhR(ZRN|B5}_EO_T*n^5BtT_`3^IX<2$wP zxoNxRJQ*Y9WlD?1{s;LxpyXoO9uCqnyn!{5BpR-FSuc0Uej(I^S1+yDRhB}*DHb1B zN-eH;9P_t!w0CtK)jib3e7X1FYJ;oOgO?z5DNs&trks03PV}e}=8NlK7E2Eox*j87 zMMG}R;xjvWU~MG&-BX@N;!^{W0cKi1_WB-%9vz~Ez5p8^-0ieWlVEw`NW6lDyhf{6 zy9TLx@VOg7D`1=7FkQg3Rk43QYRvOdd2~gQbq2U%g>ePvbMI1$muoB@@uoT{+Glp- z22|7ZXS9<^z-6BI>XuKm3%fCNP){l+XBE=4S>T=J>je@TdOG0p8!xwBX_ltIWL$=f zuQtj^^7DKyK^LiKtXs<^JVaOKK{P!vCidgg)(@jes*&H(^RFGTlN{FL4Mc^Rhv{|V zs8Q=fzOJ;Vd85qjkVZSB8_mtV`EtJw+dteZnG1COF4tKYWY2PLVk;J0*t9Q6udw;+ zUiMLme#()8Le)=~cy{Js5(_9rT?7`UK>(#m?w9u{GdJ9wIoxV%X4seFO+SgB*1?Hl zqV?M~2K|04`&@VulKP6T1}G5YaA8S@jeU1g=K;p|W@lSZ;cIGdjv<8kve%U|=QO1o zeJ+#7TK-^ZES%ZmX2VIQ`JAMAh|T>%1m{Sr!0ocS4Z&$50;t$UFP@F#9V9P>2)8kY zM)bC<942PavEp>2zeg!TBT&Jeu`Ivp>UM<{?fejY(eSVlk~cb(HCCNtY1IbIf`DHa z^Q_~~&^&LBhW@2wH+!2hB0Iv_acv`=LoOfQFxS(2E_UJFOH@Qy14QjRO{}3W5OwYf z^kFWy(+|P%CAI<fmBBP$Cu4nF<3qyi#tZ)LP2h}DfY3+Qeh(v>3mKvVx;QytlExZb zzf&YF;#fWi7wEid^{_#=8<DET_#UHCg_}resrDdE72|aZ!49pBmmhmXU`HZ<3i<49 zYfVWEDMIHgVcc@o;?nk-;#b2G>Lt9G*rUKI!(6&|3_f_m_h=lX=-&i3EKf2T&KPJ( zw7L>B>%b#!=%k{*x+@Z(PGXwC2<(>P5Psf%pw?0Jd)~&Nadjdxwx+u<TwTUoz$S9F zS;^pB%KN-Rt85qZ0m<<+r;WITC685KQcUV{#YN~*Pk@X%=DcVKN!xr4EyBkJT+%Uc zNj}jHW43Ge$Yj3oinKNntuehx*D$M5^%FJruvDu*Vjj_Ru32(Ru1)-$wn=YZ*L;0_ zRiN~1_*lZVJCt(6jYRfy)@7im1tS(oW5DX^0@V`z&>_^euz}dlR&zSZXPzcgK8M`j z3lwv`2C2VBzve)M2<>O$f{ET(Fesj5>kVJi?1h9!kY|0*Qc{HBBYr;{f$pEYyN{dv zs%_g-H8S;RT<oJ@*4%aqe2k*E3-XQg^f-~M$PR3N=c2<&hK;&&q-VbalUb_k`wcmt ztVYoWbA%=5<J)+d)O%^&hVq~4%Iu{)_e$gHO|rafQX6$g%b*6fGvV48soSvmb6b3U z%I{j6d7NGon31J|zx&7uYM1LMTFVrr^pw+oOW+3+W2hR(*&29WLSC$sxg&9P^MOl? zb9(e>4W-7tyWbuTF~n{~6<G4Ed!zZZFF#7vdH?<quJ%mMwon7DA~<_vs8Uq}%bXa% z`Bd}TaC6zUanrk+bm6s=^V_%bJ#FTH8f?5jV2pnKxs`^_AKjbZW!7KCBZ#WO35RKF z8R+h`dm4plp&zMrtU#TJ$l-B8$82J?MNwe3kz_5!_Y{4xLgj{14l|q<qiHf9RYm|5 zWm52Qc}wI$tB|1eWl2C-T4E&m%!MxY@J%Fbk^z3T(l^)@G2s%@urnX#NWXaCRnnOl zB<AyEU3~vo=pD6)eOnI=L2928c_B3Qa+4@5&mB3+t*GPXb)oI*akcE3rohsB<7}~j z*NoXpPC?81V5X0hwB3rsXWqjgZYZ@U_R{2FMt82vQ?XxJU)FwYw=oH#@BqEK+_mOp zwYX{S7MEwj-XEeNE3uXk3};uBEdvwOHe2!D(E&*jlAaOr2CVzag-u7_%58<Lwxm%@ z4ixqpdIZ&s0}5jUxPBN=YwvxX%=VOLh8~+{zAHVbgyi}AC3Tfb!UNs2(sskk?K}%M z+6<Y$$s{}%F+OYjGTOt*f<FxsbT{jc7JepW;y3ufq*UGddG$JSZ;NA$8NAp(+9O4@ z#l{UAv2XK|sZxF*8UeLYVVEGYdPmvLbm#joX)r%s3jhBQjfJ~)%P13jl9^YZ`8fV} z&vjx5A>Xvv1aAaPX~!n1MlfM+Wv=-7&u)2&@h`I#GQuXCCn&n&UvFwHf0@!|b51Wi zc7{0Ohk>jVm^UU7&~wob(Nl$k@cWm8^PM=}TVRC1#CYON!oh*T;Of2jeO=}v^9*@S zgA$FK>e}ZINdurJ*Zsj7%?J!6+0p?B9e-1k_Yc_<0&hao`898>r^Y5)G3{JNjDpYF zGed+dY|C{_cJR7MB%w<9#nFj$iMWA0+p79>jknUsi2eDer=4&Yg=sInZ+mB6Y?xJ^ zN%w`XvM&w96-=W}ev_K_Jh0Mi?wM6p7WIbanD{`)<oc@qnE~?xkyaD=2c<T(_SGR5 zYJsk_lhK}DAE))$e)os@iccF{e>ug!scT*INZ3f;{(ZJJa{~W@ETKir9*nU-lz5zF z*WZkjo1gZmEEziVm-uMJImTv|$K(`fpDFb|e;sNX%0kx-=>wd6T$?ZR1Ja^b$u5gj zr7*k+B-)nPg`s+k82Cl@+4M9cwVeal^VkmDjt$N*y3f~CI&SHz=dLn@nM!OZctb}a ze}NcOvi8xAZx&MaGHX9Aum^_OhBK+D;B1dvi3Ksk75bmvj4&JI)WY_)xFMxs&e)Q8 zM9K%8$@h9)bMt#8HcXYsPB(MI@UiUbwC=A#4tFk#Nj$JL3?y1Sk|SJePF;eyg$*DW zloNX`+BKuVjV&x=@Cc+;h~SJ-k%D;)-C$R1#)%eCsRfE~@^X_zNh4<qsINU&Bgc8^ z!c_<?fAywc7-$c%?24<iPme3$#{n7S?OXj757O7EU9Y?yN|HIv-W0eQ*AJqFz!dv} zJk}$$)YMUyv$W;KUaPjKoLgU~MKa_~7+AB+`OHxJH;SQ?>5+@TY|5e&1G%!>L;HQt z(_6m!K|p@O^Us7^O9q0wKeNHX=+b8ytAeNc$@bi>!=GLY{gJec$qr2JkI-wXn%UZl z+WficpONywpw3o9+DA_spl2bP@<1K_dKV%Cxg>I-b>h@GMg-%;CTSx@4(5#S*UExd zYcLeL8qA{n#O0t<B}yjM6z9Zv3DC{Ruf+`7Z!SdY+~Dl>b!$4Q>~fc~1IqfWLFyWI za^LT_xT*+J|HS%&ayhESBcG~R4gpX&2pC4N_3(we;Jx?KuxW8T^u@N#gzL)lh}uV$ zy1@u#ZO(Yl^46oV!7Z@wb+%vuv>8=fk&JrRWpd;lBIn7p?O#^D{*K607EU9Ii3(dm zq|6<Y<K`Nvd$m>U66u1=eaoY<N-bhwKzc}2TQ|B1?|T$r9WKAV)zI3FPY>JX)OVsQ zRjDgSlyzkKwr4BNYBvTsCO(0*^SgIXCb~N-?P>AKeyFlUP)>;X9gQw8_@xa7tnTQY zbQ(bG$??OyvjlqX_rBO@e{mp1#;0l5xJQUuaLdH7T#&9{hqU7t?PifJnc3wn%7lRW z7B|-K5%BQGbI%D|`z|<p(?NCqW@-7to@%6O=u4(yvHP%RuM0UhY$JX>Oex}zs9RV1 z1zP`*1ERvrciqJn^4U$Bnh*q5<_k~Wd%csm_=IY>$1b~Z`udUP^~1MazIC|I9`%<W zfE$~(*x2tN&_=YzxAr#>aoAg<j2E)&V}H{29`U<vD6*0(%-5tarhI%k)}u4jw@J>c z3Y5N$iu;^|UL1Y&g#Z@Lh=!hd$JMXThl4BKT8Bm>1ko58BNvbJj3Yxr*FI<44;IEv zX4gf?m9($-FFbi`T<3%|3Q7gvEjzi4p1SC<{C$oX%}y{QIt2%W6j)*eb@MiM`LTB2 zZf`%I4k$6Dr%`ifG)c0Gp)zOYfVl}7KaCMrXDL9N-Jf;WMpyW;_7aYP6$K&xhfK3O zOlWTbH=zQ?$F{Dg-9}GhYc0+P1dscbxjNkMQ=EJs{&`x)aCHP=KsPu&2fuC;6k|Qf zCTin5F*yUY|110{!XZ^2ije1FD~~nWK4)XMbXs)y7bPZ8SBtxk>g=z*3$lggK8{B? zV*(0I&L7W7G}lVPMS+$;s5QsUGlTD@=^F~AJ3d-sr>)nLCt$n}-tianHP2TXa+cS> z=tQ2$5|bX(4@6RKhNzRvqpIGAwwdji<VB@~f*c0F6_g6M`#sPsFAyw$SHP)fVidMc zmxQsWANYri<s!t1ka+lH`a%qg!;Cc3USHM>a&2vC$v9xIJLnoqngdtIw#4YY(d^il z2}x?YEV>YIB8;6h5Tp_UJwrqOY=`qf)sV5_4y_evM6%^mS>3QkKk!Q{w6gZ*XTQ&% z#yzsrFzTh}@-Pkv4GfO!9SZvza30}K+S0~v#q+hbC+?i>Y}W~NbauP=-b?V>INf@t z!N47VYs9yXBs$v!Uy>bOYleUEG<rmM<L+<`Li=mg;KKX4lm$-zo;HxGCwj-DJiyLr z&oF;(!wznaZG5Q?x5)~p`H729Ix%<Q(Nx!I^J`Zcv~LcrJ4vpmUQqx99!i=&Pgfu3 z6K+a+#ah1KsLP^pu8%D(=c6{fUk_PCCGR|NEa8}`HK{)=z~^*Uedg&te@dDLHMOKy zE?tl{cHjldOK{wxI_6z`bfpTtp4V&UkL+wK+;9zIU2>M*V!ZNHh^}!89_n-I$We9L z7NQy!lDc-QM-IKS$}@LiUA;Sk1yAUV@n>IQcEFzPtl#6`<u_#?yG!-;{QZ5E$coEE z(siOyKboc(P|@%%!VU+E#M0~JL2R}T{efH!Gy@~I-)1LYM^9Z(-b*kWC?Izw@?z4G zK^Q1$5>DIe3TGs0oj`8D+|ME`2lALV-t~GCJQv%b`_HYM-r541pFx42{!I%qjH>e< z>@nB93y%t1sFd^;waj544?Sif3fo-2`9f>4`rvd^J+7lPS+9%Mzh0^4xzp?VXtQH| zdvSU8rwCCmKZHY5h_tzwMOGol_v8(&+ZH@cmxapaE|%<j&o{Jbck<$1HKn1&PCN-5 zFuwlKH{0md%#+@0s(;@`)IV*}ObxTm&2rMIO&O@-9NYQywKLg7c9=IO{4OzzcVC)N zemvCreVdhI>s5_m3<Bn0oqTH>ox~4WvdNk@c<DM*`?1(1tuQw@L`Iux*(i{<t7oAK zRyuf#sK?7p+{I{B`bYlV>EMn2J>fUG=bu3LwO(Fi<5Sk&JlZzo!1F+&Jk>Ri`?EIR zk{%&^=A0RNg4RYsZo94W5S?5wYM$zM?1&!LMbii1S4B_AP;bMJbQ>sor#>cyz0ett z$t@3x9M>D%gjK<W2hWwv1G#eKF!X`L+2(u)Ek8>H;DMvGQjt@T9G|V5iWmzON}Jo# z@AtGs1BD&&e{d!UD(mRypMP{@i71-%u+;Hh6E)v>6}{pfjEt+w(!!Gl&kbS2*w%sG zXmt_16w01nGpRo>JhZT=uzaLsL=sWiwaayDS$;;3Dof|+vqq=l3qe*18q?O4HKHAC z2Di)sM-{U{TSF!513`%|ap%VV-eK2sLha|iLS$hvE+JMO6sy)8i=IE9q=Mrk_=bAu zh<&*HK71z1#tN?;wV$`Pzslb-Ke}V8bxmi?S%P1M6P9A5Yv-Ijs*iYgYOu8zQxiGa z%hn}DU<JU3!Lg0k_2T;%k1JqhV*p{j?4boEpEQafF_<r&{fRm-1*u5wL|Yv)GsqdC z4lcrcvdVkU_GlV8CcmGTCM26CW7_rZ=aR1I+Z62y$tQWiakE6<g7y3DUVI|`FWQ4x z<^CVO-ZQF+cnkMN5m6M8UL`8MBfTRiU3%{#y@W^)5{Mv0x^(Fxy@nQgkrI$DT{@vk zPXHmbc;~!py=$FwKiqGbERxBD%*_7p=h?rf_Z8(Uo~|oyQLZM%90ncJ{5+C+8WvJs zD(=aoY_)D54>}iQd7lO;NF4)@z9w8<p>^E@uO&F6;Y5lp_Ge|6F>+SOsu3!$r3h8? z^V<1^9>+Vn6&@FSY>VVYsMqm2*B)5y1CA=wvG33zFv;?+Q}Gl(?@^&c-1uX{=XEL% z6a0tcAG#?HzO&&}jnAgQ<+NXM;^ft<vD8UW1Zr8n9aF&PQL@J@Fl+pC5-FL;)0&3- zH0T)bksz@3eoOJS4sTtgdt$pe`okDn{=U^829x@l=?%=a6mojqG9qO3=fEAoJK6bf zZBz@#G9zD&PCRgeSg74TH5jV?mG?Kjbwq7mb6%$7pkQ*E%TjyUNF$YxryiDkyuU4l zma($$rknpdY{lMA;tGoL{(~;*A=T2q+^(+_x00JFvN5N(s#v?&H7pJ*)Y7eF@PTTB z#H04{{MWB;3Sa_Q{_d?K#ToBCfd~f6gUwxf<R9-Hu)%^RE8H%?Rq_z|pf%db%E;M! z;j>-Xn?%av+yfRML8kE2nG|+2zFR~7Q{%EgcKw_vpD!uIFiE?8qN=J$sNaSEfhFJY z^V^C1&to`pk<6;8vK^IckZ1<^v(A{H7hUD9mn#vcnFnui;;K_@TwXrzjhR*EcBWDE zY{^RGwiL>B&#$}qsmrm0_hcY|PGT@4qfp@#8Mr3!c<<cUPiOwsW?$mSv(%SmkH`t7 z-}+MHR-&Pc?9T-U_qv5W)VZ2UnmCW_66-pJJaG$KZ5i@lU=pgyvG+~SE==jwo^Dr{ zP1feYGw$h~zGT-ms<gTcmr6;S@0%k=y7^q{Ix!Qae?S<WcpR58YHZ=CcSdlJ!TOp- zj&%HNpa3d0sUuEaIXZ&ylWAqSdfo3;MiEt`j51X4x3bRS**g%&-$#8nHR%WDMV{}p z*bhhDYkX<#e9BrqhPFuS6Zmc03wluRfHnHc=Tpgb*S@)quSN8){g}2##<fu_gUJV% zY*D*7JP5s*7UmgcYNfBBo2O~^BKCB50o=&GT&3r(_n~19-9dD9F8>;j{51=~JUBC- zmXp#hQ9#R6E;to+>5Mu==8lkNeORZH&;G#mA1MmA$OMWr)5a6#Vk)(rFj529-0R@} z8$as}*V>!H4iaeonb(ZS68lkq>U_-<IKw`1;^}RhsMQU9c?a#_WiFs)ZS0SpEGZB( z63g*H4Pz5OZ+=v|@E^G7WO>P~sT5$`A3s+C2wE0aOw(&ohdj|XqR0(}?w?ZR1H1R0 zH^Fhrr}CG?95<&c>o2Kc0%#fNR=-N(g-W(vn)KPp$-+hJ%R_&ZFW2gb`hjDnc5GX@ z?{hVN59VKDk36B9Q$eCMt>`O}8FXh2GLm^#5t&|)<Z&<BEq#?)OM)3!CX6fZms-w# zHsLb_skV5@tkM*tY)gXuW~H{x**>QKk`@7DMEsUiJ1~CM&@ey<26w&p__Yx~nq-L) zt9z8~UH$#1?c{JB|0;=tY=0bX#1J_h#IG3ZCt_5^{HHm@hmdtJAAaZk6O}EOj$$m! z8d2E35kuuj^7!sO{gE(*yJ9z!CEOm@tN~2Fh$Ty|WoNvvu7+;03I#^3qC~rgzdwsN z;)p^7t|A`qG$bxB&-1!IknnL<K1vCxAuJ{MB79`oy7zc^R&iY!nIK?)!vFm(F5xEV zOa(zrQ(Qu7GCZ5AlPhUyO%O-l^F{Kn?n`Ef<z-;kX_+-9_7D8@k@nS2XJ2z4mc5}M zIOshY=s6%I6Znc4GXka=v1UL;2SA=M0UR(2``?>7cg$w5!wx(5(EkY1%cf^do#rk7 zW*Im7x*QKNw8fcR4=by!PUZgBE<Q@k|F^H882&%XGHS+0`T(RGD6N@=dT8UTOd#>| z&fjzPk5W-QK;tts6VRh`0mpU+?KS8BwRw95_=61&+M9s*oBQPqEtYqeNrOfZqMt*L zSqrHbV)$?M(;aGB0<VI+0_1#8_=+Z8<W?V`ep_FB_($*&zCR6&K;K&i)Ww$@z#cNM zT>*eO=D6GY?bDNJ|4jd-7~3iU$qX5{fLycAZv#e>#v4p0TIIhtUNQ!W0uB*H_$;8r z|KYPhx;u$`?ajtImJe+A*3jPTp?mvsjBa1k^?#3=VBPgqcjqzlr$7G)E(wj5{`YgZ zbW|3b>@aw@#AUiY&yjKaLgA50@b`@Uqi9K$IGzIRg@-TTaeyo1zaD>kRBi}-5X;${ z05#xfGthfl{T9;@h)rEfs{qwRnQEBIaKUO^PD<zh?#qcV0cd>3H^TuUuvA>Ze?9(4 zav(x>L1+%2eP&_ln?ZaXT-mwz<r|qjjtIR%u-o!vdZrZumYp96*GQCm{g>b$fz(C^ z9~6lkBiAT&o_xNOs<}C@K+ya45$=hmXVhW(?_N8vPiime7|uG&oacABt+n39^c}df zNiz~luoMQStRo&>%ilE1Q8>{oKgQ*Q3wIgpxa}s3l0IH3rg)D+`-$&%yqMm9J9TY+ zH{0t&>i8(O@0=p=cbCLsU|0a8cjfnkHAtvPr8r9do+!PH8br2iKqi&6LCI4%nP4+* z(d#88?$g<`o8lmHr^fllk1~1!d<7q)n@-JVR1)QiH`o2pmX6nyjy=9D4%uq}hh@G! zJzz<K?w7ip-LnVcR-x<Ezwq75w{MEts1blikh*xPqD`tHG%(YwiS-D793iPg9F#)5 zKY$JRp?eJncnu*lXLP3sa+lh`5S<^&N3n$pJ7W^x$VhN0SVk0xyv@=dxI4MjsUMH_ zNeoB0Y2;9=yd?@y*=NBDTeM&eSGu!34>d;kF9()69p81cKY2O!Qens92nG2)v^E<7 zGxUT#L+^-!#r)F`9FR|IOC@hb=tiC9&K0kMxA*_rmR#H6T1CVtUfB&nTqZ(vwK?Pu zm<gzEiSL)9UE##A0PImXFMN8w;pfNw2NcA6R`ly+a~x-FQ*FkjE)2fWC5-+@h0uG` zABi3$O04u#?|0U~qqeXJ)DZ)&MIpSyT2kd3ugB%PHsZeAhKK{6LR_c8q+193BCDVa zr3%FZrw+qMFF}42A0_0Y0RyBQ_qE^*->G&~>MXgX23fj$8m$#%Am`i0T1V$i!cz=l zKkZ7+9A<-yKu>i9n(H<;w@tD-8nrc?(4N!BsV?4q*|V9zm_x61@1hmmbFFbx9VF@W zK|J1P04YpK==FY_`@-m_pZF4i*CZBE5hM;Xze#>R^A@Lo<s9)~kEA<3;9F0!v*x5@ zli;8$FP3-I)f$*v9y7Qxe&@&xl~|rVXg(F#m%TD|`Jf%jhwQuqWcT>U0s!cqOPZ82 zv%PuHndWjrU@?CwTfMLLqdd|!F)pt&dUqPvRug`u%{lweW6~gwcH9&6O0+fQ=~#pm zad;aWTAuzMBp-|TSg*}!VHy9}T){)8CA<*qUt+avI{zm1Y;thig;s2ZKO5}#K(aMT zq8T3CNey5ZqMw*v6JmO`T`q^f0siZ0LkSJ*AbElW6tuWkfb#m?O=6IMOABq!3WL>e zXTMqU#g3F`z>24^DV@W_eSedbXi?72xrIJqJ@A`Q0t&8&K};yOKh!jJl<=cB)ZHqL zNG@IWXtU*-jQL*3Y}A}=PjdmLWwt|y<S~hqy?gJyGl|kf0fWzvJdHe(G8%a|zLoZ6 zPXKsg(GfjEmh;?e%7E3}AM)`lkDmihqANuxrRg}H8mHfN((h3U%{M+i_-n#GdE}jk zz7nl(sBdbLvoIFAn3-5q9kZJwU$h*GAD5qNT$4jwsb2H6;W*Z$ooBnO3EJf0MY~dn z=)ci{LVZK(nR?Ted`J8Ri8kCyuHScl^(GB5Sg}H&lMvyHSPcA{JpL?g8qa=xAG^}6 zR)JJ)dxh3~u4$`^9R<AhfwqOe#WEqpbM~o*UrZHTME-2N9^&bu-1KlVy(vd63t?m9 z`@x{qv>&l9G#C)7GyGRBL%)61D=#-0Q5!#Jz5+0V`hZMb@1r!IhgVzXma2z_k4!r{ z`yO7*7Dx9Rwo6PFlO(ek=V(!7`F~%h<#!sal&ag(tK0GjMQiEQY`-t2vh@TURfwpQ zo$eem?tBK3@9SLpRqdgUmVL~-p6WV1lUar0oFn?l&MI@Ie)0tF*EVp>t8Vce>Dnvy zf@Oy4SH&G)XA*bL#uxgZR3`u2A9iSLQ03c5sJ4Te4i+6m9X<JD{Q%Dm1!53Z>fn7N zo<pxN@Hm0Pv|c>Nw7sCYvu|qZm}gZZGfa(W(xS5V$HYZ~f5dshn{PcF<{F5gpLklV z3hL+qOaUt&%0BIegb-MuDj0{zeF{~)z@?^^JKY8e55cUFvh(#q6iG@{<<*D`b6k0k z1s?#{{P6W!NqbpQ)Rjy69|3Jji~9{5JyK6xQ=EtfDL*`RN7w=(j4cDQD%jMNQ|?cp z)O}M_7!vfdB`q7-chmx$iifxNoB8}L13{SRemp%8ruo7KSRjVT)13-LSwA@abf&uS z1{*4sTAcSCOm14Wm(F0J#LA`!iz*MMZi9Mt1^vjS`wIaab9b-hugG!23R9;D$~l)0 zhlT8U9_S-}#%O1xd8MK$m_|agLXfjPg!ktli}M|Y2Xu4DAW8g02O;Q|xAt%CRYV9M zfF>DxGCcpL13&<MobeUAd>wA;Bb_Y|E?@XLQ38d1c|AT5lqmLS_QT4P4kG8ynucPu z(^K&l$B%8g`M?<qZ8-0tJs0zGx{TIJ>?j7aRj5-qh4hWPtN7<NW^m{suli`hc(urX zjXc9oel8thwkzZsO!O^fZPwp9OHvDLbmVdZyzmplPxv3CI`bmPqk97$4k)%Uv6d-K zXPYHskcF0N)3Lm6yT--)@Bcny{-B$N%%kT<gahALT2Q|nBZl@z*iEU-1I*>533esq z+SIm+pn8PkEVgHtrm!eS`hAks&(T&Bk(#i$t*w_ZlwwfQOwa>d{0~9x3MdEaS4X-l zg!P;us7_GH@HMaEKx}!U$>Gg>oVcCcY|3>YX61lzRXZFnaFcTsBn}N&6AwqmGOxdm z(CcUoA)|pR2Sme6mo(`T^lre(3!`?!etK#W$zTKOQ7FsV)`Xl?(9fJlaMIlmPr}Yx zS6$T*rw4)q<nKEF_<6j#^HD~p-;28UB@o%j|0FqkGIMrK;{ELG^0Rk>r;<y5J#;;` z;}X?9AgM;t4Fmnkn*ym=ZN>y+G|2wzOt-CkZN6m77yY0yGBb))hRoVnH|evlF4$OU z{S+0w7v)^~Sxikl+mlvjj^p)Ekv*}L*rHsQs2X#n+*DQ)0+M_Z0)n^R)H~L7=iLHf zIXtv-ve?6tkV88D(@YKc0inxykJM|R=_oaj6gqDZTS@1UW?*+hatT4tegb46`8)WL z1egV`oz>{9#V~rw)vRJxoNMzC{3j}*!OoL4mYPLx;)S7(X~^seBBI_tb`4T#xSgEu z+f2Q&t2t+C>2i4Bx@VU%FFyv!KQ!+HveF@vgDjG>-wQ`1j8Yh)Ov1RW_Vd*1vx<r( zj*r=R>bGgu;py@YD|07j-Z+(YYYKcHs6Mxc?6#$)<=wjRHWj~b=D!#BX2b{ISZVg8 zWc}1me{k>Xg=c{?BaPm+^w}3o9`+401r9iE@1U@qy{#hwia8SeZU=ad<y_*O4>Eq_ z3z4D{K4MK8t=fqutBnncjrWOu-S$R0xsKtP@Iy60O8{*l7MR!(Z<v+gLJu97In~Fi zpcpK?mMsd~!j}%v_K9qBw-sMW-KV{=unHUo>a`nP%%|1ae*f!x?=Zy&)HJa&w3VQ1 zmP__n_f#X_U704|2S2NFgvR?~^ki%9Iug*3vF6S$zLI(Ly#58^35WT)P$@~2M@U7o zJ)2%G>tRk!vNd1(9}$E-J{_87mKH(ZGe+b3P)nRvGSEFV+w7~E$x8WzPic#R^B}c< zv0kN9Pv+c2id3?#mUsRYf&~W&1S%f=-b=sz9V~D3ft*C*dQS!z-!2)ob%ve^`1+{w z%z%yAF*_yfdmCa)r9~*Zb*h6OcXjp>8~;%h^eGpFzYU<rQt-Kc<>t7)1*PWM(*vQc zdHAWX^D4+S+~#o<dL5eIV6)w`tuF4Lqkk3XEMG4h(Gx4*V@>gwk<_bK%09Fa|7Z$E zf3J25A@J7Kz}bv4u*C#6@ZCAe{7%fr!EyO7pzT<J^{}x6({dHe`B^nC9uy`c)M=Z; zC*Jc|!x4g5Vy$hx@BVdwmF8#7zFP}DtJAVr7@Fv`u={u0I%}Nk$6f(vE#ssxwQ?jI zzY`lR>qh2`4y@K<Y)KPDp7Oqt$s_1)?vv4!H$m3HKBa3ORPS+fYe{E`DN@ar99pqf z{w>GFW<tdzkK^d4eM-ufkES{wbvhrBLo?4TF)KfaFsbce*Mc3R1cA>!;77anL@lKR z<@y?q8I^(u%h>-BEEj~b@`w1OdfhcN#2kgnG5!g9GP!{hMl8sE0vD^?udSQ5YmGC( zbUJ>OR{yc;U(oPCb(ZYeJJirTVq=U>@bvwntC5H;8!^?a*x|v_84lrHuXUz!(X$Sr zw6`$sJEBdSK<URgck@fk0JO8?q!cTY?)ziu+KaInDR}nL%rmDO<g=SBJc*NhEk|@4 zVLr~`lCwBOfcaXuE_G|APe;MNc;qI}hU6tbKYvlkYQ?#dDuuapo&%hJd8_%##R{M| zXytvs=DtZm23X37WVqE{D>r`9o;;|`U>flAf{2uhob7_nqa@+W1ihbf2-R@btMUX; z04eAN9e2PwhQMUY;P$v#lcuIN!DZ{0d+<_irn=f;`;;69HPaL|?m}Z~^f7)~?7fwX zHF2l20O-&BVM4*uNQqcy;Q|-)^I(}~uv;Q$avz=QLi(qwvAP0*Er|05zA3NA-`6$< zW$QFy6tlQF#N~qUH+b(d+gcly%d3wwaG$+Y_`01wJ3&TzQ-iKDHY=hf6y<&6qSM<l z>0YP?<nR^Kl-k<sJvMOCE0v<i*VCT=6~}DoL3J7Hi0<r@2LaYKLQG@GHCq{~cnPR7 zlxnfs5r28=N}Y>-n?-w+FF7BJsE;cIviemzrhjK=z0%WWQnI-Ot&Rbb(F16IPm6q1 z5EJaftmqVGE3O5cCC1R>{N<G!vthWTcR6)KeN4#`liN($!t*y2<eI)g#5l<-D_oL6 z3uXdFJprT4H=84x{0odDhb-?JdC?Qn%<w&RQ;P{t6g1dix<;aNY2d40t;vG~VOqaV zWwkAE{sqwRKkcI}ISiAIs*c%~TN!E&KTaM9F4rQPd=gcZ1vc-q9`6iAU@v0L(sTIS zvivQ$`?B0N1$^%>jcGX^P+HVP8^ucW=VY}hV#PV2R?_|B=-;K2$uA_hzrtP@)KC=O zQ$#Y!lui3QJ5;2&9HqATUR0**8}sN~6_<;-gx}T(1bQZxRbl9{da;z^m7-$Ol$5o8 z`k3gzL?Wj&w;H1N;uri~rX;P{>J?{(DCEqiiUk*%aAOkzw=GkaWFG3l+C;Lar|j*H z`1^map20wwx>(xa|47htt;U$6==u`yKA2K(W+K2+Ywr1T^99obFqoB;b=jrflinCy z;rWUM|2Mqzpl%g(2P)8a8I*?ER%ooLo)B@hl)L2dUTAPr#U43a6nfDt{?wqXzw0)O z#`DANwoaKaR1U=v;AS=D(Igjfiz<tu%#>2=)RFo`UwNWSE2v|-y-%3~wMSj=WWJtY zH;3^&Td4P9K2<YQnL(@scM6ty*=nZ1bta32ORb7_b-P=e92PiB)_q0xnbzvbWL_+i zPksB%!!-R02t|bkceS0O>chwRU!Vyuxj1UA@F?rLqhOdnW>2{qW7+;|5`i=?cSi6% zWizQ4C&{D`jp3%7Hn?-=_P$!8N<zo`iN6{*%owYkmXw2n4)Z>Dk-ZB(M+0w8yv4Xs z+Z)5L#ESG@Ulg{0o<?*o^WVT1McCX}c_&iyp2h~9TdQN#JIgd0$IqKuZU+Pm(Kcy_ z1Xj|89J!Q)al{$>zZT$70cO>`vNv^yO4gWy5F^x7g#iXJ`Se!_p4pj+iFL_u+oySc zUmks1zRhGG+H2qRP`x;=yZ`aDoLTJgJ14DB*FKTbfssB#d#(CrM=KG3TWTq=euT=E zb<j^x-JAEQ^(XS?KzGV-?as0P^8HWRvn+K}K9-8l9)~Ya|2|4|NH*_dg@_NH2<3U+ z!{$a<*E<627r=0S*y+HhzXp#4!t>5U!aDNS4p{WaSGoe6D=a>3So+`RtpfA&@ohBm zFiJKyp;LYT12CfP1^w<h^TTmfK#$H`ad9~kz!ly+?3cFy1r%XMo5K}yY%5x3DYV2H zz!pXPKGFY$iV$0q?emrw=b*VvG~y#rYJ9{q<6haUKHzgjdH%unSD5{F{=@ICnri-a z{-R(=F`8}ssjBMd;jUW*88^094yL{@^P|Glk7K5sT1pkw3O^+30v0KC=FR4cGIe8E zTNTgc32VPb_jTmP#p~jz%6kSTs<zK0#(UH=i@B$%xs1}LtG%ao`eG$o1bfv@G7{fI z{dKK8uH>%`Zi40R;lwN-pvQX0NSwQ8M_QnVfA=6#j`QMFekqN@j!r~Ft3;#I7QP)+ zm~#|7TJCWx<|tfL1ydDY_F2Fk2DkSjMU7UaJ+n`{5)*k>P56NK-2r|-s!xK|vd(yH zrT*v#+2f#Jxeb0jV_|qvOiuK7XYr^@L?o|_bio+kO(C*5;FG;iNx|SR_Bp=%B^M)M zQLGO9eW&wDbmtr<2!-dsg1W7LQ=XMzw`$}n(b0Q>);<3ST(0bMK9!XF#{&?nTSUms z!QXr#@8+t$Egx6p-+$Qr&a>?iByET>0%5%8Wwnr4AX^5UNgN+iYr%b5B(ACXo5t#D zodV%F+lV@gJ4H2L@Z)_`sq9FX+8hp2&2fZTOtJCfb>~JiYFh!w0gF_WU~=I1uy&5F z6$<ap$Q5L2;gtqdSUC+f?;cyWgyTSq_kg91V+*iK6{)icyBYhD!UIeV`YsRd5bDKV z*FYROGlYI|R$9kc*F~Vnf?N3GD`4umFB6YU1CqRm!%&l^CO>OyRCN#G&_NrgpZtC_ z6ps{%-389{aei0YLBm$m7?tQY`l}Z>9^=$=oxoRW)804iM^|2ku0v|+>xpX)s&9DQ zCWbb8e^y{v>}veL@P!pT2~R0>8?Asdwp|?pbM%_Iory2A<;a?}D%&o2X1F<U%so7( zRJ!-JZ&UBL7898mm+QLBD>RpfvZFCkayK<tkE&E7M{WXJNJQ6kVyUd1;lnoM$00ei zx*4B)`WXWcld(e2ONyyj0mHIk(FWzH(slnlBkvT^2p?)w-AXeT3K!B*<m-)#(!Lkn z)nM)w!@4OXoaE2tl&{}yo8rBB3**$<Eb3=#$&WoNdRQI`r#xMa)&2-@#DQVt`s|tZ zf*rHAAR^3i<l227(0;(Z(L9^7#bpc8E;YV6v_Twur2XS$Cxaz_-C!mOh%k;G>oT_1 zA98SXhydQ;V8|7!+-_sDO@z#zl(_A!%=4w^{R;Djj~d(kw(|}~Y<ygsxa}G#Wta8i zzqzDUjkI$DN2gpY=E<M?(xEXWdraSG7M?OrdT<+L&2E^|Kzef+JzR%g)OtHAyOX7J zaqFeE>?(=!pis+Lqbv)DswoCMErz9cROV9L!wTNhrnvhnjv)geCF_+w6m^X4Lanic zmlP@&G&6c+7Hto(0c0B23`9Q}DeP5l?}y_3NesujL)x0OEW@or+^kM!PlEHMLwXap zSo*^+6@BI@p*0EQFF(>v)wZIghuVdE;C259KJ71{&iB|OzXv9c{;k-YlifQNoF|U) zZxm+rl2IRwK9)(W7etASUw5qw%==tF;EU+84#{}Kd<(N2{MNnA60s}gwPXo(7;vZ3 z6seXtE=<0j;8Jss-Ch9Ch|>yv?dhNm8d<3y>y-s{!D)Oz^MvM@zlXVN^giL3G@$dk zqIL!rEsO`JH`h1jyv{Ir_E}5j^Lm0WPd}r11^6b+`tI&*k50LfV6l`t?0{!L+H+Jr zvEI^EW6o?ZRcfGcL}2HU96E?$Ou{8cxL1bVG)<@Xo#4qJ=CoKV%;HTm_jIX@9Y*jn z_sWi%+pF}xx`++;`)m^}lMjDouK*O#wd*=`6DtsXE$O^^BeK|?nh}_tKO#5DBsKtc zy-#x982wNOG0$&$r+Yyn>ID<Ihx{#lR1N_yat%TBpNLn_C08lS&d-}jKRF9HZ#htw z@d$A$&sTVUE91XAMRz)OTQeW_vStFN0Vj|0Z$zf1J3~C#9;baRoZ8xY9VJQH$|c{T z9BlRa-Fg5s2ynNN!$<}CGCS{Fi(rl-+bn(TiI8c%vMODdVP&!6YN@*{VhL1}15fH_ z6NwU?8HWv(kjIq6&sUA9W!!<R=yJ5Pj{7e^-PnU6*6Dgrmpx1KOkd*^#BsXx=t&jT z8Z1Gl>#a>>SE+-^@Dp`@Z`ZOWwejwL@&lKEhjPpwmks=)Jc>+7r6dx541$Qyr$ke4 zqqW1KBo-DH$=;J)y$Q-)>O)e8M3k<Od+GyE(J$!}V34yGTpi|0ds@Ug>^$fh@{{G{ zTV~cNpM~Fi?spS>7{<Uw{@9DS&C0bY1mt_el~8&8*#T3+>m)(z(2gfJ?QTKLE7$tC zeguqV;<S?F{$Dta)4W(h<*wOA!<U~cPTt@>mviCg;Sn&jX<@A0i^qc<WNTnrl-1Lz zzW`8&p7;AS%(>Deb0|~cUA4*1%#hpDkj1`){lwS7ckF6~lnJG|p4Km3xO4E~=Zduu zM@1DEddV!zkg!3+rzvUnBjTd>nmkV=F0zPzFiH0;zS0-$H!L>h^vEIPkE0}4FSM|9 zE>!Dur5hq;5J5}TmU1fB2LYadLK!3OPByK{E_oWCmH00T04Ss=m_Hc((;>sPQbAP0 zogXR4Y|Qn3vb_H`Bu*oGtUk@3Jorn6UR&a?n^HLuoPLiL-8kHS>=T2<3}TJ3rxX{B z;<^>kuI{vM*E-|S)D+z5#e5!4w>f|4Nc!xA^<7qfcWXQaRNx0q4rT2xeuRu#h15br z);!FkcBLXlrexB^f1g6^8B;$|o1ijl_m4vv$Fn0`W9hC~5Z@=Xb<d5kAvQb=0!Fvn zfR}g8V~q}Pn*}s&IO%*oIGR5MwbFj&vpG)JHKcsAKplLRQgfVX;-cAfI8~6*uC`RF zDTbii@fT&}2nd`pjTo#>M_Duq^eGE=O>OnOEfu#4sXQo^O7Sq<)y}9d8{kF;p7Xvw z0+NQb!puZvSnwn)h1agw*@)9CvS4PS`tf?r`|jc8{0Y9rI-QK~!ruADW(eO=gIv`& zKBwG%VaW0bHip07{@nx@@Wbi_t{CpPWo431A-le1sM=V4#=0)Az5}-zyB9PmM?UQX z4p_G;EM52makEfDSl0b?7=4o~$(v6<AnRocuN6nZ36@~GxL^#rDlb|c%iQe6o_rNj z5L{bGY?C5MeLa%3)fBTQR2p6JH)$MVKMqSvtvd1zTDbr231=TtMV#7h6HK$iZ_>xb zGsoG-#g{0<*q<YhRp}+8w1g)0eyE=uks1CW65(bm!yWg-xE0^kN#PUgYBGg?j7!|o zSQ6UP_J13Nj{b~MtOdNQ_em$`n~oyoYa;qU4{@mh@P|-eO>6B$J+M3Yo^5>&;iGS} zrT9_M-NKvnQ&RJFTGY^Iw?nyJ+s1mK5Zw=7w9mhW5s)1Bsa-MQ9OUoAbO4>k^;L3h z>*L<QPd|yEG<8?cgMJ&EwNH;UM3!85T1czJS_Dq?gZi!3uSlVZ+o&K>>}*uAMCzqs zlN>621h!L!p9k)kBSlC*SK{8QFx5j#-JlU#f)|81C&EZvD`s!auSfo|68b30=$zaN z*_29^vpphxU!rT^kY`We)4WU2U~Ww>UZ`0YvPMR6i<d28tV7{*|22^u1ToV_yLtmC zB?}MELdGkDp6yZWYPiv8DsJW*&biVr8gCMKs#@cy1GNDcDQG{v1ezX12YVyDwD^ah zY{48Qkaqu>0=?FKf?EeK>EP5)f#idmWH&h$(~>0PUtijP>ZT4}*9okDoIZ}wLZ0>i zKt#c7F`Y^1v>u|2m8-Wk0UDn-jyJ(yS+-Xx@|pi0kM*yFr&*K8ak=DBrI3B8qj$?? zk`Wlp{kgtNO5nKnc*p~>&_ji{^5%T7sqpaoxM_08%PxYr{7Nq|zeWWPnzPjB%bTd| zl&lg}%c>`tE;X|Lqel}hWE6ADyA0Enu`yu`;OFD4J{BpT7oL7u?|6*#BJRH2il_)o z?Y<NZpU3KTOE=-2+fF6!JVHTburFx=EHp%#F;HK(+SIn~K3L{h(Ba*kJOjemCfR<N zp)`aLnro0Tq2_+Dygc4NXKxYw^c}l|yqfS>6}MVnUWK!3Y0sJlL`+r(1*Y=d)Ts`8 zNf?76V45BZq_m_p3yOn)t6n#JcYc?8mwj4Kn`4t_>PwXL={M45JOeKE_iKl^r)-Xd z=ed5a)T~$UwI?$oWvHdTZe{9zRN$>C(Bp9&S@bxLcLNPJreB+6q!cAp;^OFr>kvs- zl?$nCPOsieJt-hxsdN~CtdYJun_vtmw~JFz<Game@RFUJ@Y7GmIRC%j9$G(kYGejY zZA=_~^-rjIls%gh@$1Ssy>mt0?2Hf6Ge1-KcA2%UBkny5uwHp=uXCj~Dz$OGeY?%) zKY_@%b%6lgg&olG{RRM};Eh+Tm<F@p6~tD6TH>c+1_93(to3z7(Ip2yga`3o{P=GV zcL8?2)c*&4=hnW&{U^d0WsBp$E9k*zyMVEJqXtfb3bH4GL)PU$_y@Angjwn;wbK{~ zHFqM+`5whdXxk-!Or3;pAH#<tr;G&v);!4oz*5)-SPEvlz-#{zP{DuRT?b(G3^M>@ zJRkp39P}D^<C%{Vm%y%hfmwzBN*(s2?g5Mj|NR8jtt3#GNaoj>HEnV4kHR*%f$fPj z{Nn>gd?tLQ3s0R7*qNFCe`dTry!%N$d=henlkcvpx>g9xUzAI8sJYO2Qrhn6aWvvR zjlzAxzY+)io%qNH@3sey$rp45$T+beOuEZIf~5#NPJZ1~M2A?zrf44c=euNlvEiX8 z9&~$1HrmdEp6y3OcRui*8gJuTFQ2Z9dB<a(YN|{8{g9q;zU`zNV5M7M{#hACauPOT zR}P+F^Vir@*dr0RGb|swUfnAPqi0WLBXzTaL^s9HlW<bdNhMFf*#Wgu)VNC=a<7jk zsJW8~-oFU?I}CUf2u=ka1ub^g`-QvFYSv;iMkpR~%pdfIl9ftUkb&@%)^r^lHZqQD z;VqHoJnpn^Z!Zssseb_OnP^PfI!CYeJu53swD#kUtm9r9qXwm+m{aNCit;1U-!8^= zF5<PLC)zA(Jn6*4y&E|>$n^gq!}DKDV#Pn>DP8nk@C38&B3J2a$D8S5H9T4CDH0X( zbk-{aC5yP3vrBV;$LzMK?YYpHx(h{FS9H?Be^UJ;m^H-L-_lUUC9TC0>whwtaAyhM znpa>I`p#7TD5BCw9L^~B4CahYO(E_L)W1@cD17iNhF9q8t;JmgGNeZ5y?XVXm=K<k zz0(E!y^E_myL?w{xLiC5;aYsCI78TC5J$)m8sF-1)?}^{H>f(lr`s5-od#u1wU4yp z9B`lanY>6)W4L?8OfV>zzD>7U{k5r7*XQ{*EgQ2_QD%hb={AlZ!8YPUFFLryY23Tc zX(M>ZjdU*azSyMe&t6`f$o`h7);N4%4`JCwEO4wv?8{>{6mj~Pv@?U|6cMM4A;WRo zkhMLNw(8babFojF4af{5`(xV>x{=B@z+9C0Ql^w}_B)_hg5Z=R6)^8vyA$^+_ROA^ z*KdB@#65VB{<Q6Fp}ZIG?D#P2ZxmbjXzv#WA>zz|H9p5PE9_XLj65d3CkYWH0|j-p zFt^@KfC$XBX`Fe|9DMD4lluNmt@d*;xS@2bP0MyZ=sU(SR7M(e-gT+{5kPPU#;g50 z{V8(8KRN0z6YXScvaUI*Ax3UsAIU+_n&Y}3^u_-`CZ4_feFKpwNp440p{SmoF|4%1 zWWg#`JM~4!;XeZ4*Z1a7dR_hz6hw-C0u!$;)=z9V>ohUkw6rp0Ex3Sa$<63y(aIEa z!^$e02W1degZ)-hkhk@im5A@t{25!%&Loe5Mi^DvU&kDWy^AVsj-#qs2)pxzC-YMe zkQ4e0YumN_xEkk=zL3#J%abfxS~_=-w6#p0<`=BEQ1plx`6ez_)~dEXP4E5L?Kl)3 zTZuOA1=bV-M7Y^rU(h|6to?d)E`xJMj9Ghl=c?*Ac}&zItJ~9nX2*o5x-xo}Tp^a- zCZ9s`awrxH;}7JqzLV>-pZ`9Q{!!QY`LvQo_PI4Rw5`lJwLx&Oc3Iu~hKv7DjCT!f z>(8&Yz{_ld{%wy25!=2`SCZ-&xiTA=a$XjXVB7gKzZI>gr^S6>kQn_TH|>TVY8>a( zU1grE7y5#(LiCNHszLG}<5Fe84r)|i8+V(?*0d^66+@#225HKby)RnHqCd<6%Wo$* zF^<MM{A74m3{K^(p-pG9o7m@L{jhLkIQ8`a#M6ABDQ<IJr;y&-l?TW)E&E5HjGO(@ zK@Th=7<+T?c07ZY_sUUYAz?7CK=|FX0@sNpXQ`2x$0E)F#pW)#E^*7$D@>jWbd<l_ zhG;Xe8elK4llTJ`bSoF0aQ7bp)3pzFK?xhR(;+&^XgUJ}t&Z?6s-XW7G|bbE+c@X= z$XSf?PYoYFAX3q*F!{TJZ0wPb%b}h)45GyeoHfm~sjY$CkC(5yjQlcS3_%F==LDI| z?ANXgANtOshS-J!dhZM-X4)&0N;m#NV)RE{ZK_B5;swNcJdzSq<6MIFqIF_Ys|I*l zmjK1Z6^P{20YY5`o9kIZQ!L(9@)~#~rqC)&m?fo{8g?rgnYb9T7*(pDR{uI9FMc4E z{Cx$12QnzC$@XV4E6SLW?OyoZJ!UD)-=&6J1kSY0a_xTAVZG|%(>UkKjW|MT<UaF< zr22(?L4JCBO91o+c=3qaBr);pR&`*^=(=|94~Aady_^R%b*+{iOwDb4H<iUb1Sthk z^bU>4)`jP+s*_(2CS=o?9m%fbf~Kt-->E?`nP-LLr`mwAw8xCJ?2V{igAs*^zb|HC z@vtF$pWwD+3ObIF$5-eg(Lcrp_!7n_pbIEkt`fkypb~+sRC|8BqK_$BFCI;2W1#Ud zO7KlM`Jx~>uYMqUVH_PVJphHzt-n|vpYn*YB{@m9FiY~%(bM(V)Z(jOyD7Zz&q%}s zCFHQ-5_&r5){kX|$h9gTLTU?@E18tIlnbRMp&3cx%oOfv^#%ue1zh8Lu|dWMDIb!! zRb0!g?z4=0ld2dttJ<Z?%B$76MyGc_^Q`G>YqilLKCT)%`*f2F2kwOPwmtd_N~;>t zi0VBWzZ_8v3}`Cpt*D%Qwh=bbu9aPFg}l1z6drMYX7|n;?(nK)2TnfQM<Yiu1q1_@ zJCm@5y6dtfFo>S0_ib?Lvl9?(5dL}`_z5N7pb{QL3bP)+_5k(d((ENzFAU|md~k>@ z=;2!`_YX$DL%a|68&rg?_zk`7(kOz-6I+2(-j=Pur-P1GEO;ch>I0B`X7l9_e=eHM zf(~*w;6OD|x{;o0_;tK%qSw}Ced=wQaXInOzN31k!TRTX?F?#{!9uB|(6UnHDUSO~ zSw@*x>bSJkkvt42uG4mf9;dB@sY(t3zf#8xq^VTbMu~ENL4M4kQeEx8)$7D!&l?J6 zVy?Uj1fpitd>~kso{ZS7nj&b<hDsq0q8+KP*Yb*m=V$7%h>adc9AsJ2q&v?N{nc>= zILmU+q5%?t`+84qtz+=pYFxB`fyslbcK^m5JXLGUm9%>8;7<zw%C+>(7etP?-hJuf zR*mFHgV_Ks3GqESDV)+8gbvVfGqH%?+!#tTWM6uvODs`gXpTXnSAUWD@5AGRr(Z|Q zyk3wGQF(HtG2=j|ZN*|}r!BqiZEt4!5#>W+uh6XQOpn%NJ>SeUsWy>M;1huZcLofk zd%rus3#-gS8Js)AIhieLX`q|@j3j5N+r;}O`KBIXX3|po-ludjx^0VNU+IeXS_F4> zrKxh|i=SfVnLx<#^}lnM5y0e3qCA#RtJ%E%Jnoa`kq-vm3nftuCaB1ce^E?wb2{&I z8e+czj0aA!#Or<`rvcKSd%L^dXOpMxO!vOmF~73d>8<1SP<;*da&1uUdZ9*^N-ZCd zdqs6kev>5cnj73=KlZr|B-_{N$~eYfS-KLvFp%fJW$VtoLs$P^b&F~LPlDLV78Az0 zf#VY%uoj%PX#Y5hkf*t}1bmU?F5i#v<krC-M2tU-<+|_jBD_2tYTt}2N3lbMICTqc zISGn0^c#soyN6<2SD&cox>NMDK;}x=I5_CJM)aeC{t<}e7jAQnr~$FV6-Q5cO^ZNe zOl9pbqq~Njit+V56Zy&p)Gl-}vMwpR%1|dICG;jO5Fa*h^6ne@q1jpP{1ITbtywDW z&XkX`qQe-6iyTqmwho`@_n37geZPtOM_}q_lwrF4;`so#KP{y+W6ZZir;|uC-s=Gi z>rgzE3!FrbZ43>X*RfuJu8sAGoijhejEoEw7KM?H44+t3)_+%H>3nASE7bGz(R)9w zKO<z$)?*z)8&kD%?0FHzpHrYMFA}pFJiJPWejXkXQKg)DZf%~s!5`j83SP*Op(<!V z{3zqzZV7I98$!8~XN5d6IWWFnV}AV1Gpt<CD_<&Sa&A;tWqM~79vVbnGkNWrha-L^ z{=wjph^*ohevYPyVa?c0wRmCvHnGX(aIcI!^w=B(E#4<UviD)T-#TnY3b`FE5_t-K z?V^t0niyU)2(y19MD~Kh+Xp;|X4Q-Td6C;i0WI4@_s8HlVB*;9>*c$cphDUBXc*f! zrw(wzWgd-}hG)n|<hOfu@(YUM2`qu%(K@_go2O$W_>mUlgIBA%Yb)gVIjPx57)!wY zc+1Is1`Qr3Gddj=ruXG2uzQV^iog-yBP<dl9*$V#9QUrSuC%7+mRUrkD|=>n8&XkN zGz1-|*2XS1Oe6N3?IkMWsu%@_Uo_1_%@RVFxtFKArlZPAv?xl|3tV+RrDSbKY(t~s zM9LIBOC#nnv%Q^E@GhCEdV#rZJ?!0ltU&ke;f_QIGSd;uAN)3wUw(X?9Qi=$MH%<^ z3v8Ij<7Oi8!Kn=OmBaND%xqL4wj-?&_o?46hfP?;u@oxRN55ZLx#rg3zS$JFvYlY! zX2dE(mUW+n7}Y@sqs0khU!9d8aROJuI7PLJHfb-S?OqUQ$*e~vRj`jN?V)REIDl}Y z`RwmR@29@W)H_7%bH(ALB)|F{MA>O?J#UTn``qbK(qDNkiiLklGM%hnXr<quqaf7_ zkjx9&vIRTIlyZb6xbyzKmuOSF%zb_$Q^%SY*1PsXFnLco#?>%JuUN8AUso?hqTxG& zbJU_Xv_0c2DZCLL5HnQb5oG#`KKw@s;QB<heEm9S+%7p`xXcj8PMJ@yg+LZN_Z6{+ zS~{zck(@4R_4mP_;H6>kiS6-v`MI^LuAxUoiGQqkAxxh|d7Si|HZ%(2c$}Ylb{S+k zrmuOnTBv3<imt_nfEe+@E*UZ{jZynDvi`PZmY~P4H3n=EtqNDIC4vXM3LD&&RQ+7f zyfWk2>G^|VaQ&+*a{^~RbxlB~1tjW2M;MbXan#@*YEqp_=qunzm5vcEy|pQQC+05t zI2cphul)&x<T&uiheiWu9l$kSX2)!I@i^(s!Mn#W4PP5)$2=sR4(m}NgZDFr70+7V zOt9RQdp9PnY#0RRhRUo9lvJP6fJiw9Ne6|}#OvdELS+j!={1WF`!l%l$F5%6Q29_- zY$y5JG1Kg>P?r&syHXdyX;U^;D5aatX^_LGT%V%4V^r@lDi|FK_tSDwKhq|FSx(Am zV2U+y#Awjmqw_U^=w~g$7R%b+Ek;SjW@`R!;fE*2b^;GBl)4w@3rBh*i&y(<Y7;hm z<w=8Bfk{en;7F)o>R9f*v>*YDa&~35`}5=b8##9pRhJzS6=Z%|KvL{%*f-NQP89h& zgRfQm-U5an=fAgX)|~PtkJcuuhTj;B(JuzQC0P{`hjW|09B>0|yOWpWE3m`wo7yQd z3wZ`m906QvlZn1sV@oAz=Lfz3*m8xW&H@t5EN?Ja_t3aDOlq=wx-1LLY!#r`qSg&- z)GcKk%-jq*UCoLY!-1|y05!8-{D54(cZ|$=<<V&;=?=md;{+BfWxYE}N$Ffpy7xNC zT!S}3xkxp?L3M`9(cC%aWMSa%liY($U_sv{f0|8+&OK<y46bW7G>0!)_X8J{<@|s` z3oBJI`LBDFu^U}p{7Y*PE?ZP>$cq&dm=Kl<{t&#Pd{b})1Z@~%_OaG;&{qoe$d1Ha zmERM{zuj7^-w8?X*~V#h(cAshwX#{u4YMZu`;P!fk)uRbTBC%a+C3c)o8ygV+5*>j zZrs;RL+IY5@v*hlsoi_Sntp6ckoLap6_xhRuo19ul+nnKhy6C>QKp)jLbESt9UE;W zXV2@Fw{&E}^L=EDQI1*6`7y3yr5s}#q*{7~dQ>ik89i5TES){o%R?*gj~MyPCpX&+ z>AoU66UA<IUYWu4ai6aA02j}P;&2}_>i!}e1Z~y2w#2XD-5k8t(L6=5a-dbcqUPS9 z_xQP5TOODmY9^X0e#!CXCaHr0-=AAMTDTfdm>kd=`BcrvJjI}?J?VhF`Dlnb-s|m2 zUF~yjSjv^i07iRlcHaxV@)(+rmJfx=qT6kI)6BkLhJD9Xiuz%Vfctl%R?uXl*(sIt zO{T(^1_FXmCKVKj@!Ag~mXHsnMfZn_#uLI`;Nr2AuQAK<{Q2dzKjXb8+l()*vSK=a zcZ;jpr3%#`SDUmY)r3lBg$BIZg8cP~7zUG{nX1fj&UyYiw*jz>Nm==H19P0+`pHGf zRP{Gj5s%)p!5u$eo^+$D|5Ag>X0psYf2dahKsVpqdW4ZXbuq{j2%bQyax>2~pLe1F zbAmN4!U9v=9Y43F!T0>?HJ0bM+1{k{1F@t6&70U#jxRN=3F(F50=WZklnb6q7kOAy z<EI!P`-K?Bv)S==Y(I+8sS?Il&>0D{UDIa5l?AkGn6}r1HCUiHO!*(ya<^x(yp4Yo zC9xLEqN@FDeFa$eF?Kpyy1v0cfO^QS(%7IgSNk<)wnzIB-%3RN&2yr;hZ!+yjvtgt zSw<*SgW0mH_;UlK)wS8y$wD%Sf5<;^fiqX)pK5|4`32lrG5cmyldjqxgnb+>u^TN* zG6J$2X=Hpq(p;hwHF)04tzss_cXWnppu>hL_vM|{GopizQ>0wyB}GRVmzwYgC0ENQ zn~qy;wrj*ho03KPUpCT*=Z6KM>Ep@H2Kl_N3lFMyMcMYtZMhVwU8FDwCf;gnDs!dk zOh%p+<zG;ICu0!r_1oO;6Pya#zCWCg9V=w!jB&-7Wb2zWBn}<uLB7;?&WR2FN_t*4 z<nyA@;K5x#x{>6|pyEJB&%3A11gjgMrDw#)W%E|;SV{{_Y&<Hn9nvEf0(p3!AAtbB zA>S!O6{fHGF1`+UEuFrU53kD)BRJ7k1l;f1^tb|CGfaQm+&S0^i#ktm4rKb)-#T<` zF>ub}G{+Jn`5Aws|3UNEiv9gv>-6rdW5CTQR#7mYY`{8YEUl}KJva07Og{3S6~NBY z;=K5|^E2!v9y%BwRMXo#8>G_IZxc&FW8{Pi@4qWEClj!}XAq@_&?i3#tl!8B^|py< z^;<n6hSnKOe8XmUh+J8dJI_~6cG*5m5^2yBHkaGFt-aWGtXh_+(zHn*<Ea|I2dDX~ zO$43nnzbUqjD4!#(<U1c>b5##YwnoRQ!*LLGVT8wSGI|cOdw}X_~AvzF<cztYMQaU zCKMO(u&8;33MdqaQG71qxXAK7>|8?%e>$(3Lk;hXXn*&o8HSw2!B0O8Bp1y<?R{8N zVv4t|o?xeHANt6YizVkPXtHs@7aOMRIi5&XBu;309xs49GhvKt^CA)}eBoYSxv4nC zr9?S2jSO}tW6EsukETM3)lK3ZcIE7~)Rc_3@`;Dq3oUj)NLV%0_=mBlHB@fvY;D16 zI?s7E!sMw2p_%yr^BilWU2pA@^0KZ;Dx2_qj>l&!b+f^zV@&fd9W0oQ7f|CaBLLjj zaCd%IZE`i$WF1mhLNLY~D;ygC+?m}`>q$l(Ow9|^3DnCE!KZ(&m5N^h4GD7R1ZOKI zz<Lyf$+tFNd~L{gx{18ms2y=<;IwVLK~vlfO;xJ;K5zZlxn(p3P4?Lj`>MdiMQ?~B zbYH`g>q@fSw4g=I{5x_!p+{)6&)<wz>{!WdiyNObf)y$?PJ3|JExs8&W4YME!CK!M z73JFzHFjQRMeeaB9$ww{B6_HXj@##jVOgM6rO8C$zLP@N3~DB`@WAyQw^UNL8AUFz z1Tfg)Hn3HiIJU-da`ZDU+4kg+;aFB>pIZudOU2c&e``^iu4`+l7qd6zXtE)XGEO`i z@O^GF?CQ9|Zky;&ISkVfi(LhU&X%qp2pt*C9`^hM^Hmm~@QeR^7l$I03GyD{Zt-`a z6$%aQedjIk>slW>%+Qar^jcfIv>10WtKi{JVq$PnofnICB|B`ZM~1#ZQw}GH=lPsO zE7KQ6IELYf`x%nu9yZ{H?tb!J7N1^Aygad*c}r8XGZRZ<YI^bb&;v|gA1AJ?FWTi= zo<J2>t7>Or_CA|Qmd-{mG{ca))l02WEGg+cr?PKH<3Rm-MA5p$?t-`JDEN3dmm)8; zXO-jC+!}{^y==S7@2KSgooJn~doA7@<;ud9`<r2TifPCc?J~Wcju$X94DCMnySc)e zte@J{weuQ}d9<wgm9V8)Y`zKiVd`k#I^^=1VeCdgk^Zv)pM<>mry-yL?Z-jC;Z&2T z##uNS<lvN#z|w-0@?~wcLHOX@AzQlba4c`_V|#g-NlkXaB4v`MqkjYtc|fmwi9@i! zp5jc)fA3yWS1yW6HAcN{>}@HW@AG?|C=^bEZT(`a_p7x#CR~9*TVNP@!NG(z8!2YG z%cw50+yE|Bvt&=X(9>{*Ob-s^R^t4-=Cn!dYoXl21-lFL0ct0M1*Pg0&eO2kGaaq0 z0}}5%A}z91tqO#mWpOXrJT1_JZ|Bw|>+O(fr}5&St2`j-ttC^Q7gA|(9TM<iMBH6c zc@+8V&6>`k)~4I~(-_-tm6uyE2!M5_gYQM)hh0zVPKC$o$rj215B%SdotX|{wS0w8 zaicY5!d)%bOkiy9fCC$_28#mn?S(D-Vv|2s{hqoEBc|>ef61JH0TAQ8@O!dYOfe8( z7V{^>)-C#~Ys~V;KY}EaMrNR$R~(SO?BLH-SM$YFn**tX5m;%y<oH_^{!v7Z5!#3X z-8<s<A&Xdk+B~_{8pC?5Qk|;fNzCmrQ00d*_Iqz_0qqEAc847C-*3*?Y=rQoa>RHg zm>K>T*_;SWw&oWtBU-+&H_tZZd+u8s`856UCY|4&nUyT=3d^zPkoTx`-O`9>;q&w3 z^^{eDuu+eGE43=2D1x2SBPLvg>6B9T^k7NOZ}ZmPCL4wl0>Xtb!W}cPD^LGJ?UKa= z_n*I#p0cTLJC91+&2pjRFCH!209Hi>(ci!B=+76R#0If<GDi%fT|VLn{j{2>b`ISu zS@6HE^oQ6g^hDmht++Q3SRAK(=y9a|zdUqd%C-Jza$TMIcy2{ZF3Z;e>CaYBdXD%H z-f-G$+lN+fgv>d~npHogT=c9mVZ;eMEZV7V{Sxm*kPq10WOFabyv+{F8)DZ|C6;+O zU9)=gBz%3_?gU>A5A#e}DP9Dr6AS^DHEHF41Vt<7fYS?viEvs0<PJO;rqYa)@M{Z} zKd;C_F59i<;{A&_*`cK1A7dh8xHm}nAyCD`K-jYXo^GDHRSC%Esfe53@S{(7(LDS7 zIb8U(Xy8lvY<@p~aB$bW#3jj=Yc;0v`s3Sw1i|n>${(NqzxJOqg<!)}3>ELZrCXBe zJMoufjfW^0cA|x*flvyv8w~va5cbw#O|^mFI3`je-JqnjAPq7_>5^^`$ua2~IYl}J z2?YV^97v3YNlQyhvr$sAkpsqj&-44^eV^xhUBCDJhl|0ropYbKcb`x8<^GS<bPD%> z?Oa8mExYhtN!z5lwV}ffoAxhT)o04y(?6jM1Z(6f$E76EKYG&t-_cX*)xPfnh|GC8 zQ#-Dv`12Aj@WAOYohpGw*ya+bEM6hTLv;I)hj#$R(&p+`Mf%tOY`v_~w*q<3N+c<? zY<(n~V7`ixz8m`0n9Uh#LU{f&gaeovT!<F_Z#%&0P65vJ5iMOf?{H{g;#xdsNws%M z(lg8b7fWbG4?Jw#Z>_#K{rJxX*Zq??;9pdvcS)bVd2SuqElyA>$KxuQ;{pQBXV`C6 z<k`_*BKT7_I?vGifD3x0|H=n0iqmoU$M+2kY>a?V>tKnp)T?;1pyGD>h*2v7@BNf@ zpKct;Ii~>ThG#$xInoXfu%_Y6D}*r7zeJ(^xSzLj@4$Z0{eRBrsj5(IQ=Ad9mh-I^ z!{!lFLrzE;67vPP+MaFzZ_T}OA^KgBh3&_O0Q9cq*b(4z_ZGdnkwGB9PRg(g)$tko z24anmvfn;j`f`*rb!|+~iUWUt<}cAP73}g9)R%;N23%{ufve|i4+azs{F^uY#vKvN zjC77j=+E){(CsER*8cc^jM@R$O?X;DXsJFa2mNQKd;;^ZW`u!sDk6~LiEDr2ueF)C zkM><l+FKGw=cLtz-f>yJOXnl<KCr3dxCL_0jmss2If|0vZ{VI+&cnK@F<TM0GaO%I zhUK30wUJMd6s7I6gk&$~yooe!`0|5|t>;i<%xgsu*2(jiX!WzT;8niQUm^~|^jVAk zGSmR&n9=;^goV7baz&$LG{#){Fx$0qc$WGhOw0;Sq(WmKQiAdB>EOOf@D*i+0yA7! zP;-5ju+Q&hMhxY}4K4fhtAh3<<p#eaQ+46f^?F3S*`S-l)w(h);7W7V&#23koxX3& zESu4|dc?V_uz<1LLw%sPem=`<#<<>&-TqI}(3Y*tyVW{YM}bJ4I^~Rs)5YYnJ35Ss z_GKcDU&;^+`>ac)axNtbSw%dgD>cM`8Wuga55U9mEl1FZJX|1F^=nm2t)(Uq_q#Cs zXVUs3Qwn;f&(~O2c<s|J@AD0XI~;onFv|(NSe`X5!?NX2sD4*n#GUWg$VM-7hF@2h z4lT`Fk|z<b@yxgoP!}x1oUc1BI|QL#|BE-}@+Cdtg}?tS&^Bnj*iYoB>5zGd-dy{U zMAhdc@b=;LdId9}-x)~X_h}Ag#%1Uun0*Ihd?B}QE{@zGw{uoY4sOtVcQb3rUWrRA zRnc*SU^@2L5*E+S9Td>0BU!{)q54_B;AYyCY(C%w`Di)5nRdXvK1X;BMWQ1a`jc38 zu)Mze;ElzpHBtK_{URYY-qa;Y!OI!%FNXW<0abq0{LG=OxEp!6gYHlgTpeUB;5dm| z<Q>INtZKMBzB|Y@<X&^iV%)FIBVnzN0m+?mZjBBvE2xak4|AiKllqgQVD(PDHbhVx zR2$(@_6fz4!Wnv3d7bpZpy<txB<3I+<h)%vLt24yi@IH$eVy&}YE{N5?EPAQcM|D# zdJZcVNaYlgprp10CV+dvbZAJkV~+IE{#IM-c=aEy#An{VjMAQ+-rVUHC;q`*3%^=> zR}dMUNl{1^1#Q$=Y+y)Z#PJ+nlCG+H6X#4kb+Q0P18u&jZ;&_~UwxY?Fh(@V?ay9g z5T=|b$Z4pSj_bS9=|H_Qodjtn=c`mOKfibXvVK^2<)VWy*C>$Lx*@u|*BHev>uGY= zBlNkZY&T#EOr1g*&?S}-<}|4^DfJ&EY-kk1<~=^-@!N`t$7)pOaKafk@g6uXI9>y1 zRe^totE+szdImrP`<U%aANsS5yD2Yz@=OXZVy#3jp$*SB$<y_kS>Ek))NIAN*-h;G zSm_USGoK};i<RRB=SOZ8EnP0Yw%N~eF3v8<oN*GM-;@$yWNc8v4!BZ|*f0SCKc^l7 zaXY}OU-p_@I7Y#RV>|g`B?fvLoE68!)m<sN;aw^}4ELMVCf6O6j3Pr5rij0b#>=Tj z0I}4&$X^+uH0|$SViKzht$2!Nk_Gx``>8C;Vo-MEA3k7)Sj5G@^(vsI`)mmaZSAf? zeSLM6_^(+W@g}{{X6;5670)jmPjpNVeXzH0^so|#eO9><`}?)as=%6)oLHjy@9t|V z*~~OuN(demtO4ADN~4|5xNUnfzeuIB{TEsS36YUlp@L3!tx&-g9;0(fp<~@GBb78e z=CDZK_BgZgBFCfSg}6_j%%i;s9$;pbx4m2{v7?%vKRewaq!#8D%H(>brg>raW0>E) zEiWf}NlbL@tsnx|i0$Htx2F4sA!L`B^@?P}ub~s<Fih8JRf7WHpGrl@<5*+31j52U zNMCD=uigYP)XC2DtbU_FE*ZF1IZkYTsZ5zOAGNY7%y?|9M-auX#O7tb_Fxk1Qc2LF z<zZ5nmDScRQ~DEn8161R@xDc)zJx?(S}!3027x7V)P<IDgb~Q`5`e$2&G59C!aRie zFOm79G->{rN+B(8p4!zPXL<^UoD~o2GdvtlVZV@oL=!iSvZ2O5Yr1Ny>UadLx=^LR z*a5HUurns?kJQUcnD`|QDq*xmj%Z=dtlxZxq{rB=;pTHhu)Y9%7A|?k49N{Q7=gPi zbB!O^wT+9`Gr7G^+N)XQlB=rlyrEU|bb~6B*Os$JO!+`jei~1L){PDHLl%dQS@X=a z8KLIrVRvzLy7iYg9VYl$m3%3sqz);w1Qc{zq=dfrt-po24~Yjho7_ct#j{CjxTNx! z2Y+zWZ_7$jm|~90;I2=xY}|@ph)X(CjcSukT;-rR{L=gig4&g%DYI^KvCYiWGl4tt z8%NwMMe_&AO-=Sqrtu3b9&hb2h)x3CBsSmW8oN#L9O!nrG3}{fj!+><87k(9WwSqj zEC!pEG|p43G&<ura?}eQ7mmu@4zw{*F}=7BpuaiJm*WHpq>z7Dd{%cqwfml`+jF<R zfGx>$SL})w?qrpc*c@++i^CH4r_*03!>ckUIiler2y(sUP9YPL^%p{-V%*{A9U2)Q zRT_LvfX#F0jnjTy_N5y1&!A0`;x+78xB`Vgn3IC^pqqX^*zb(0wsycrrTEN|@329L zcjS{ojKFYm3bCT+cbSbS=$;hs<03w3;Uchznard~@E`4gB43DEV?jo%s>~S9DQwBb zw0i&H>XM6*7-<9B>Ovm#<B!??<}LB5kVzxHy%j`io-x%%WomG4pACDP4Pe&Yx`Ll9 z$@hecj-Mpmgzg##jod)ze7<Ldm~wlYva?{)|HnSX?1q-3_O}AD!-+dId-JeyWL@ri z0x?b$4K({6bmmeX2aQE9i`D;Q*{(Lg@=RqkhCL~*$sZ!)sdwGz|Ae~3efS!z(D$^P z?393AiRz%ivjL4~2jLgOk=3q+!M5XDA5|yT6JJc(hmpk?(?75uE-HwwNOLkVUFQ%l ztI9g<#cgA}J9D_-qf{dmZ$qQd?!6(eZ#7Ne`7sv*pn6xM)XrNcS13WYh!5FcW2*Rs zlF!Q?BorjfDf(0CIhfJO&BbpBNCxDW@Let#cv_F<Ys(gHFz8yemd<-yPF!f<KvXh~ z6zNzMi-_(Scw(M)cA!jPN`X>nU!g_MP_j8iiS90)C+l%}i;GW5SZtYg$$kY|lmuc! zxer1qV05ECT5E<W2nNm;2QBysMQ;5VX-PAV@oQeJ7`&1Gi*m?lY}*E-Ha5R@>NkVB zDg}%?9P^H2eI|Yt5-GngD2l$<ersuM>kt<`U^B73bkD5fd|9jOk@d`7$}J2@wYKxi zWv+-J5?OZ&$@skM4%XXc8Jb%O)d5QewQA^y5$<2Ot~as1?|D-~64|dxKVw5I3nTz| zWc99z>f}lkp6l0FWf$>lXrdLPFf08wOgQOP-Y6_H4Cn=r^N+gGTVTqw(k-mBvtPBA z4A;&tG|wFH79XIE)zTwEOC=lfacxkt5=MY;O}u9TP$xzWC9}cl<>R_7zDZxqb|*DJ z1N-EmUp=hPR1y!-OWea+WgBWY)HlwnZzc|iw&8E#7|<NiBxuojdGto5HMs=^H3e5U z^Kvs!`&!4x*XGZC<rcdr+P{7rO_5NyOH|un_tN@iq2=GfjrYC!+Gc>6><iTG+N}=b zppzJ)kb8K1Wuc8LeB+MJ*z0@d4fx>N24NHTB4SDE?k8<9c_sfP(q1>iH>pyR*m4%H z)EamutkJIB{%BZMI{Gp-`@HC3BkeioLM#C}B!~sFvB+z4m>(CYd?^od(l#&(V9wJ) zSW19VJ9-i7`eo*H<ue!kn3AYsl)fa*sohls$T{gP2YDXOA0v7?`TqIDG67NszmK!9 z^%OeOZyXb<(-hQ{2)}i$(D7Al^xdhK3S*}~CPU?bJZ$N>;1KYo#&+mKY*f@A36>GA zJ`)1jqz@!S973TlKV-Vm%##1vJY<O4^7RAmC=Q{~>1@p9=_0NMl>jnp#AUCM0Cn<J zfb??i0F5NWvHgO&ym&^ELiVZ3;kvqdf`%pc_NJVN9kmi63+sOR`6>bFocrstKlcuS z4${Hi+%_A`P}+$)xNFmY(}W>2+^?3*>Cj%jXGlU!Zs?&gdCYw`X-aRBXml*ACaa%q zRDz2aoLHcOQf0z&dt}rlGkZE$!G0~@O}jU@#?y%wT9A&F<e%(*>CrQz2airPqhl7& zXxD#VeIg`OWEC{1W0e2p{z8Q5w0@HC<zqbc72I)ZKU5L2a;H8iIxzlJPN!@Y$%NO$ z-ZZ}&HlAe;N!@AKXV0U(4guRzNun2exi?;v_B!yhQ7*)t#sgxDaJ(}PjOLhQ>L7Ja zmk#A`XJ$LiD>h{rtGf>Y=Z*vk4xQ9cKbLGC*|EqK_^npx$`c~E%C`>)Emd%!RgO9T zZX`>vD5T1{g)J(=@h#+Kw*KMHlKu$w@)BF7Y@t~74}ZD(Rui7*l4Efz^->Xlekcg{ z9y^H|iOg8j#hJ*xLtsO`5FR5YDd1;cYQ`u=dQc5Zd9Oo9YKl{IMd*ycFOyir$BxK( zJ&ss)=u@*90@WwJWWI#8dL+r?3iGcrbw4*U_6b)6BiKd8N^!}NLjr(682SmdjoP;T zHsy?3X*l)j5%}1x-5I1gQf8Ry05_3&RyNkV7tD643$*}>dAdboVH66=727%Y#(nms zpJMf)Q97<5jS2Xh(>PBDvdR%LKQhU272#9oNQHXw2Iby129GE3DH0+5Jaw+*=YnO7 z_uqHk^n)(}MSpDhq0=zZsy9GAnlN$CGF#1b_`F{c`hX56wRyU$<?Eb|zEdgmpgp4S z(8-M2Oyv3x>3pF##ybiXzh8y@QQK$tkMet!vNNa&W`8{RSouCBlfbiI-ye-qO5)Ga zZY*>$!(~|D$>Q~!^Zb;AbAz}ff!fW4Ld52!IlnS;)uxzTz0cJB9>1rE|GT2F-syJc z<UHoozeGWi^>k)^2AL7+y*$n`75e%w6Q+u0e<SO4_u<&*Ya&^NyU05K_a|eKety+# zA3+J+br6<R(e<%MRPvg{Y1f}NY%&!ZH#r8ZTP=iCsN$Nj23?_a?JyQgoStarF|13r zz*&y1tNT{o{H^+w_ECFi1_)_dpe}PY{Dg9FS>&p0^3)8YycN5GnvF(mHu*%7NC-1p z_c{+_H>!*r)u|XorXBQKe~=s2-UbRA`(g7Yy~a{4V__i2U!ij_lyTc+n+^6x@9Frj zZs@N=;$M|Fk2J#Nv>SbH#BdG2sc9utbf4$k5Jy>xh(H4*_DN(W;EFDBW{@EPPu&2o zhjS9S?G;ybZ=2pH$+ULiiRm5120hH)2n^j_#L||{RLJRVeoSE1;pv?HV)%f+sjSp% zDnTxFjnpd-74%PLbSH?w3xz3TOS<Crr2)8I-yLDyDUnfOS2;+fJUsqmqV;ANExX#U z;cCIJ$*4Jl(0OD72Y@qB5+(qyG}v=hG~t3T`dCvf_*v<)bBkhweWpcRg^Z9y=aYCP z&9v;2j>E8XN+F1F=UjLOog(M6%U5`dNjC*PEW>HeB>W9xg=EornG18)jU;*QU<Z*X z;~W6ZS8Fd#B}E+uH?24FDE%N8y8D+%>?#T5bnwoGyp0WxS80z@QTubka%ppS1)3tG zzx#6Hbwc>Z?>tX8cphSF`LCPV9TuoS*Yz%Z#G3ZHY~~TaA5O(PX?U0EHR(v^>1Sp} zWUCsfXwMt*3#w+%^`{XAvbGfI9hceGaDy@&?m4!3q>>L;*#!z~G#{mNQEH>v1>&+5 zbOkH7H5ZJ1ryq_c$m*wx)?tSF{d4J07M5V$lS4(j<}=NH^Zn5ZN*&hqhh39TNA6}k zazfNoT?dda@T+n3lhffg1rGZAIL+0Fc8qYorgTiOYH2S+jDk@)Z4e?1^14w(gf}7o zU11n^!;9-I(D^@)vThp&uD7UmjorX~)B#q@nAR7yxoT6c)qjal0$9KIZY@uy)Y*pX z_<rT(2xixu-y5!7R3{eay$tU8?X7qd|8QJU4C)5-&NudET|yRoTaw>U#+kXh3%$wI z^Q23CRG)H99=<Za%!n^7xO`o9uczi(`U?#0k%F<4xj`;Bx`4khdr5}7K!=~Z@{6m3 zh_z`Wk39giROfn(8d)c?Ix@y<n@f27EXLFe8u*sPUQBDGI>q(&89kczFm#?M8w)=j zB8#d}$>!J3+kc=F0K$9(uukHxc2zU%(pKd9PYFuO?tm(&^?Xo>(yTVZ434(K^stN` zZl=(((3YpPst&bnLG4aEaE1ixsD5u;mc~@!)QRkVeSW%mICDsET24ERGWXG8$Il7L zx9?^iaW2lX4qc1yH(#NxuZ~bu2(dZ!z{#(Y>E8W436AVXt44qQnHPI{!7H}(j9F`- z_STO`rDV5j$v4^-SVhLVkz~#U$|+$9j;Ktd_Nwd>u<=hb)e!g7uOHArMUDrnEbFTu zEG*vdJK=Q#OeV7)(_18E8t`+suS=3D6-g5N(f}!`F8}OL5#P`eqa1-`y^SluG?sDE zP>c~e-J@cZ7uEgh8v@H1I8|!9Gu4H5IH}Y$#L{?`#8t#~Plg$M+0m$7JE@M&6#2Zm zLV|xfiw`J+oLP%b&8mExs^0e{gMbSV#G^rEwC~muxznA|bJWC{;6`=sLwHX?!1$V1 zVv(879j=?qhp=$D(?+0~o4G%UK)U_jRJ!HE&po_ul@(&$TrtC)(Ku&EHB&yWxg-cW zBd^Fl7o4y4vMuO>l0Ntq=Ab(%=G2B1K{iy;YU@Ni?|V70-rU?WCGuxILGQFwZAy*q z(WjTQ9=)udg)c-mJNR({x-lgRq3RmAOaZrAZF3i?GtRVXInBl3n))vewE3&~p#f`A zVNF`PjG8>F@$3Q}(!^0YT+HP&rtw;~i~?1X&f|GHj7IO{3&P@QZTFWXjnhb>?oP(l z>THQMs1RK%EG(>g%gWBGE_MQ~IW%W2gCebw>wDZHvn&xc5-A=di)dUKcHSMrE8|co z-FG&WQC$ZS-=3}I#wg0@%Ih`MG(~Rs{C-iMEK+cPiMhT`C1G8q*ug@NF`Cy%z9Snl ziq~5Og@Z`Oq7@}w6saa$_g&#tzOMQKLO-9mK2$oBKJ2Q=t#5uoapX}|tW-<W{{!cM zW;snBsEe_3E*rG6d{dxPT-H<(lyhtjR@pb_8-X(QW5#4YZzyP68)50T4Z3XwjI(^U z2ai#t25s9zb8>oVjD3=&eFAWG^?{~>-cWvvU}a2EQGc)SbM%w5Xr8Ptnxejv!WH3; z1gQeBuaLOV_r)JPAIAdnBPC)Q7gd74Z#i^@x`obwFnU%&hU1de;WoE|pLg_IO^LAd zX81SIpM4u*0ZYxB&(Evhx810uQru3XieG7uNYk+MCXn6&vXN=A)%&XDL#w*)FP7_2 z?nDWad+rk5a_%#q#@b7=oNr4C)I5yyzMAEUPWup?1O#|WBCl@R5U!H2)n#jU719+y zcG}v}&m@+&1XnmK&BP{dBRGPJ(iZ;`jg#M27m%2$gQBpERpy!t1_c9q(>#C1^NM8p zBBTpto%K^wHZ#4`%%&Sry64w=2}b~lQD2e!(afD(`c%RXZOiy0ISVYiRkEfH01KNo z7sR4hKoaV%$%bl^kI^u0g`o5ZaHddReF8#X|BZ(S`+?W!E`vv3iE#)CB+MP;EZ6_P zP;b>$8>IKK?yeQZD~<P^Zxy%~L%yy?p8M_NufYHPZ~$!Q>w_H<bDS)}lFMQL*|3j! z4AxW5vL@h~>gRTyKVR%v1Ah{Olzm{B_W(WeQ~58^!7l(*1)**?0`x!}Ko8Uaxv&}k zX1Qj_oT;F`ItaEQjaN)mY2Rhf0|}BGcs}ue8c|^ffD6m~t(?GneSm6k?Y{~_62c%f z|Ayo>a)dwX*_KGger-}Tv*q>sv-Sk&61^S^JPG_~tFZr&4>!J4T`8_!82^VD$On%4 zvf(+bE+Y{%13M|bk)PkZ@*ie{<3FP(8k|9{i~0g(6qNW8<EnV5Ih!fW<;mKECU)DW zZ}*o*ALj=CkD-s6*rMFeiGT&gbzpo6z^ML3f=qJHvUF=-#j!Pgwq;ct3G)wL0x=W) zepu!I?*Xg+_t<b^k@#>lV43s$OOz*RXQIrO0__CV7k~I}r}$Etr7qEX;c^Q3-}6DV zCHNI1if@N~2c5dW{>_bKJ!B^%>ds24&+!j#^&`NRuO8kAjopHwWHSiw00ssIx|sSG z-BJn!1OKb}*XpLpR`2?@SMT~wcDEDxx<s)=Q2T|!|2PxZMvbE)VCzqa0Y>QfHXQUH zI)=+x4+_?4WE;}@d6&!KyL^W=GJ(il&+_0uqfYwISs`+DK^~H|0LK6fI;OFF;$9NF zKFtbFu)k-S`>-i^f2q$iDexoV9t3uA2YGeLvG$aa0fs#jz4CG2(woZo-@pF6W>x$S zV8kHq7wdv?Rg+JFYfiH9%8T}zSM0;DcXfLKUmuhE#U>)dJO`kyJ`BNTB`aHq1Pg)U z*?=*iHdghp%B@BB#$TfTFF+9G6ik3<@gIXBWj_aY+a35n%Q@-hZXv*21p;@+tO`M? z8F;rz=gJ`?;9SwZ5)^1}B#^9Nj!=JzdRFGwx<Z+7HLFYRJ=RQ@PFZkgc4m?J$O6Xi zno!OdbMV}T^K?OYK&1GFxe$}xu~&RGL$+h82cvVdVFeFuO6&CLr0deWx?n?kUNL;H zYB^y}*rMLBa1T*$5c1J!1%^?>Z2<YHfHV}yiwzaTi`KVGGxJ0&muIF71%bit0VTQ~ z75?OU?KLbn)w!uh*ai<$Bw{|hQG+TK>2O^A%oGQJ3e2%}frCU7wQ~JN*^a;Y(?-vL zn_An&%EDigRk?L}Rz3%@?Uc$NXIJK{I+fVq$WTsuQK%4sF#{L{{!ts&FZ)(eLOJfe zNhF&}*LbBb8C2AE)@|AJ<CPTpdZb`bTmS>Ri|PkC&>RS5b@n!x!W*4S<HEquG8W?& zI^ibjy3FtDGc~w<s>E*_tLcz<ojXXsJlV=}Y0uDP9^{D~it~!kjX>6lyXd6JB^Rml zrfi-{6zKR$q)vFLmw-orU^RqfHFhlCn%@}phiRln*8WXh1nJ8hPC5rOgA(RXfpL^_ zz8euGcX*8Hgud)drODOiY50^Gm+jOjb5968>KpyjsYh#H^Mr_PcUaP$K6GH^9)WWN zGi!mxpJgWO52yQIupOLcx2l$^&=JoSb=|S?d0@<QpUH24ejxL?RK`9TRuCw&SbgS? zdO{7{#>U9j#Q727s{6Wi{IWqMG)}>ur2{XF{e?=U+>U4(W)&s3SMIJM+!+?TeeHsn z(z}ftkTH2p@i|Pq$!YfA*Q@oCM<)vL#P7byhbP|daE&e85`a&XfO~=94u17AB@=x= zjZxtyb>5`@wmX<hxtwQ;!rztJcBU#6ctk7gwqI>%gpNMe?@>opOc&`?1UChK^H~$9 z-_j{E7oIp>Cc|W*st{{23d+?0ak+(FxdZh>8IK-)KR{o8c1sx4q|uZ(RHz*(S*$_C zUXvb0OQz9T)A!6-^W$7G$Ws{3DUUFbORC5^QV5+z{b?>i#@b>nYj&h_p4XYRm9ZTg z%mI3M>RzvJZ`d^zp4lf2u_?YoQ_f{*;%X|Of83)5ZA*8nX0&;e&;xtE6+_dl_ukQU z<lN8M7p=SX-E>BoMzEA9;)cPRNjFEli6RG9x?7lYx0jvYR6*iGJHDkM?N<Aw+Uel3 zrFlfr#@iew>8CuGh9(auy2vB&wP}}0bQ|XeL*=h_LN~p2G&Hhz%0|TvAQ|R^))%?* z;Ux?X&;ei;@bRQ~LN^jao8Jw23oUR6mE6Q68dV6?+bT$E_z-F$DiTWcD?Pn3>q`{; zYpSEZ@S`897=i^1c8@<|->*)&qFsr*FQj`wq)R=u%D$)&saf4=*S&Y?YH1I`h1=Kl zdJON!*|iS)sZ{hD;vBHMt6O0P#*rZUx$f0-1e5*L>*=h$k5HW*6{GZ-!(}U^Q-gTJ z`2CkLT;k30jk6ROY4jP8Gr|Ja#fbK-(7XvItHx<qkcralGN&cPR;Amg-H#i~IaGUt z0uHSgH_x(i($HIN?i&7!=l!6%^sKU9zp3#)I9J6o&%4>&nU(}`%ufH~eh<5}&tFrx zUwpVmO|?-_l7V>ZdOneEm!W!nTgkI@i=~%eVqPzFR9{<~ZuE<F8>W8kp+vLI(PqH+ zxNb{hJ3tHP#G(-pD(;z}WlVzhq^p<=5BMg7*z-90-q&J~V5v|P*JX67pP8+o!XDb! zm>w*Ti&)K#Q<T8k#I@b}YN1@b-I9AM+)+lcD0;f}*3pcLGx}EaL40A3Pq9%a=cCw? zZ-iw`b!3$=0>+FB8`7AhKfUwE{e+kEPTPR7<PqZygr<0zV^@_|uOU4nj9daq>zsR6 zLYS-XA|#;!;aa%RU&#}G?Z(ob@0sd%Ql1I@xy%7Ka>zNQSWB<^1G2}n*b}3+={D&g zib7+t>eGn**{Gta*AW~KuBrWjH_)f5v}S4%>Ch$Kg0W5I8Gx{|KYI*~^efRDw+2f{ zwJZ9>KW=Qri=-`Azc>Y@;hzmdz2n-zRo@V-hx5L+N;GMXi<l<UzSs%@Y@RfOahfPZ zU^M)kbwj_<39NpItY_H67A=R4WFAC<9F}O5Fn{vUG=)2XmWoW6$lM?YG$amE`lo&u z@+n^X=4tKNMp^pv^}ZDOVQpki(pD(-RfXdHV6us?K=pv$SBu~59N5`YSfT`+qley~ zxj47b+{N6&a-i^+x$2YDM`k=%lS3_&dxsJqQvIP*O4(6;qG5m%p2SCL7U>YD&7d<O zymtaD2xxw@KVFea3sM*t?6Ge=bZeZCG%<tQQ5AlRMhgUIdAkqbWdLFKlVHOnEnEVY z7?qAJ_&xu0N?0<kxu>NgyP!pKxqv%Ee7<WogHzot|2g+hrdUgs&u(r!k!EhNZ<xa& zPnW{Sq;#I7flK^l%|Xer`ueSDQ?#!Om%d~s!a*lDe$Pgt0^1&Z(t~IAD-8S|)ytS+ z<-BU(%`DR;bD0iF<f7uJ7&Oe5)fp_(Y!QDM4){kqH9>EZZs3(Mpzt=9uk+B4UGwg- zzIRG~1}j&ZM@=4BGfCN)F9m4v%n?ByR>&Vm!ID*e4^fsVP+S`Btgsy~uvvV!sdJB3 zjjEm;iL%B<Y!v6-#MIlObMCCA1T0yxJctJ;41$n#DHzIdAgKFN<zo-~&8c8XEa?-- zi<ZPQ!zimHqoxdPT>;H#zVNb?zB$D?8p)5nH$7NBbZA*L7~fh6mq?n+`kr|Zr%0|& z87Z6xNzhqSNhhcu4`oGK-n^&bd0U5ydMV$k_nHZ5nWg6-23l!Y+Mg*R@Tf#XN9R$7 zq^hh`abdY`CROMfvd%;u%rVmRK2GMb_^5{>hy6LL*BccM2AdtP-q%y96>D5dAAM~j z`<^ptX!tm{=oe#M@NvIXawQzPgKaR#Bn5Y@Uq28YKoJ-cq?{(yhb(|f9h-t%97YzN zgsXp`-%t1XAn`%l`~IB22-S>)?TORgSOL!B)T0rJY5XqF#?d90)2zU`IR(|!YGByp z4oOxGaDS6x`OrVz$fCjDOw_?B18itRh1u$nZwkIqMwny<b+%pt1a+|{XA75$c%?Hn z6t1s701>QLce7q2q4GxF|3+G*+V38}LMN$hytOKoff)i4QcqRWN;>M$7Qfx$2fwm2 z7>tMPf4voNy63?D@?FnBD_O8|io!%Vo0j-S-k(9;v|eqVkv~iD4esVQJA#MH8d~Ry zPtY(L%;zQZ&z28SwfOeuH$E9ha#D5aGGAqDsUl9jDo9P!;!cl$zvdgR_!+@uSR$)Z z4Vnm*xymC*;NHK$g5J8fX|fH^%rF>dPKVRKl=yH1vf0wnI~a<Z(ZU|eHLbq4kpkpM zz!wRv8BUIkqlaNus@8hZg{0uuj|(uQl-kt#4mxowNcI`+S@)1@8MEd?t3K4!s>u;? zysR(lUHRL;Ctt>YJxvnu(ywduUHCII3+oFNS$kZ0Mw#x^^u<a`hlPgZlF9I;ei9!a zqWJv5Ek2#XFP2mKX=$le69*F2@6$8al-EG_@OQ@*+`VB%zvj)Bb{nY|pTOH(_L4;x z6n?M9n46rx`qli}j}_&CbV0@`iUBj9R2*uIY7S?i_IQB|n9o-<VtC-K8R}L{OH_^n z%F2t1So!hKq<}8zwgPx{EJki3m<=F`fn+d4Y;i`hrnf(;^u*S?)XZE(I);6M^X$49 zOP^Au{WqUGl~&JsalV(&@#HaZ1*WQC{fT2&0L3$Hs>|%R41jZI=*1MoLNuLASpF<C zG0XeY5ApI)HXBy9g8WclX3|(Ih~q1?B}sh>Kep!=r)9Nzwz`a;>8G}6+FcTNe>rWW z-oUZ*_B$APo15uS-!%=Ka=N2asaUpW$yy^*so<<vq?=i|71{l>Om!(uAfbre95f%* zr3dwz{0^$i=sO4p9`OWi?E=8=Ar&r4moL@RjboVQRnwPfJ{&Qvr>trWmq03*SW>TA za`k39*r4xwki^0Mc4!WIT!&x?^AmZ4X^OM7qLn#S+4>3B4oFZ?T+?1brmR#<6<v{< zeE?6`<73gpliY~2Wr_}6Mx5f9-p`aND;Is}qB32$r%G@ic)wf9_)(7IY5J4OYg~7{ zk5;;$e<jSa-zO|5tvVnhfFetMnSBC>%Oj}cibf7Tq-8<RqC#e#Lrj>&%*gC;xY4WO z>PRd3N<}YX=)otzwjRWUbdr?bw=aK&2vC-EZdhoa)X-Iz4XRP~k5c5rq_IEj#fFN* zgIf}B`wAEvZjqMz3MfKtu`=5ek)kvPRQd|F1v;kTYfRG~2@hu)Yw*H2rnRKIQ2iCu z)_3=a41F`4lWx*e*u6!t<0{P?w?fk;SEbLUmP7JCnDV+^C=?*~KR5cCfUW^`L(c9( zZ2<t-qD&}pFOP8p*0<0CwWfANI!kf-(!CL>A-+hJd5RV#(|1TuBeFH%@tMGd8+wMs zQbr&FCE@#qc`ak}gsah9w3VoCdWg_MKD=AGeK<vxS(!7s=mP=6rP4nZt9|7j8LW(= zWQM{;eAymI{HUs@YaTy_bG-4F8>yVQMl%$g^`Jqi7v$xnMLi}cr1^0R?a>_DV^|@V z?4kR4Q1G+*@`a?lRHpyLcuHIIo3YRRIJ<r*c{f}1@Kupe%gYFj<_PjP5LGr6_!gyI zYz~`7H6mg1)U!k>uC-UM;BJ8GM)e#^m-{6<VOo(Nr-wQ}4p0!ol6CK+DT(LFh6Y6L zH%1b6SS&ndO&vKYWiuba4|`bERCX>v{kKF#(9<0=DFXtopI_HO)9&10Z4}N4P{1DF z=us5e2G!5TfB?4YI{ppr21fD?p6jcPxy!xXjEsi##(i+9GMG2d&XZzN;+rx@RtQtV zYhm&fD+T%C<m5kcK)x6@@vA7|KHe75R3Aq14d>lWpl__J$$ZvyK7kmrTna!wBI@;| ze)X!rq3*nd8nelaq(FPcS5R7)v<s9?ZRljHYman^Xv-yso)oblM%M)Ei$ohQUadBX zCe(hZmis=_rO?fmJ^_~-|5C#kudGFD#9RZHGlbaw)}+)32hV(g*n%%jr?*n4*kmv; z8ihv$F${ef>X*^H*?ycwrCYhV;e&CnMItjp*0rzzHV6cuAIDKcu&@^CNMBRmii+JQ z8f^3zlqA~>a;Y;v2i$nn<7X-8%0JY;sEud=Ijta!*q8<VXX#K7Q93*Y78HkfNm<#s z;02l|e=oC6!i$@84h#b9mRW|P;pO>tAGtoTk=~+Fc*AvwzcYeL>Rgj?sfYVjOsLN_ zSDAY!ma8v|h%YFUNKLuT0+*xm;@IQ0F$(W7@^3QC(BTk)`XkGh_#KVZlIU<_7P>pS zru<`+GNTHMUpfX25;TmsbP(*5eFSl=@=7=jsxiFnR)KS7bxg3Zr@hdLl~=$C8QH4H z^CfdjbIZAYX2$EoS@?mQG4*ce(MP-0Q7}3J1#Wb*|6XtiW+t1yB!H*`lasuv`9$uC zlFT&SoBjOym@q+^NM1;g&#US!ndG0ualnIqG=foh9an@UL#M|TTDi2Aq`0!1BFF|_ zi4TS`GRAPmE@||335_nRFWtXWo+$-FFmxqI_b`K^06hyx4{Nm&9jw(Nl2^X)`8qeY zmc%aoVwFnhr*MxJcHln!xLWn&g&w`Ev$Iq^BZqL`fa&uuw)%P|5$k`6pzClJ5yy`n z8KUhh1*dYsVrY)r*f%&;&hNH0w7cqn<m2dNo}5ff2Vg><uKwKDQWDW^;00G@P=38L zy$+X4D^)L-u*k!kbX?VjvRVGF!}Er)=xBq5dyf?*;|HGfcq$ZexqkztAvDB3RM@AH zg=zLDRE193+}p%CB1vJ6W7igT)$_+7<he|el(a)-zgq;y{LX|9Lo!FH%Cy@X&L62t z=X(2--_0;#068?}s#zr6CX8L&I&H_q*}!ggqwh$7+hk9P1Dwp}SN18m1`yS}ANNgI zgcVw$8_pt}AMWrpHid$|gUCZUL#JT%B1xAj!Ow7d0bijvy5xlGZ76~z**jjZ_|THL zn_cfy`h4Tl54CqO!Zn-u=PAB=MXA#jpAF(=JusDvA?M5DhGl(&llo~Y)%n56xU5ut z-IHKrr|$FHX1ZDYgQdXDSH-t8wX1n!uk3Z%Y>)XD_Qy;lCVeImcVs(UWL(6p|L{@W zx}#b*fpl_@UZ%o2)}djMx%H9l^m%CAIxC1@3o^V?q$+fRcIbhFdIBPaX|pNqenNu^ z_pe$VlabK4{tjYX6qaNXB?$e@JTkLFpsuD)Frz=b(=$A7@s9kZGHps$xQ$rqopGbL z;%X@(k#H<=ula1`#?Rmfn2R$NGxBeYzbd6g5^JLgqc`#w2Dr#81_#GeD#!2XEPM5L z=8$0kh4uRr*XNq|ew)7vF=qj13d?;DfJp3DScXMzxu~%WruKa77Qb=5|6U4*Tmvu7 zMTCr3Z<k-JA-XW7K+oFMYXAYv<)dfb{u4GIRAtd`kW8Pp+WZA1yrIvGx^*I1uIaa< zVmdp~PBGu7N|aTSgefafyCI=sWpvEAm~ziNlR@9HUt1{pgfeqy4l*A>B-L)pQa=<Z zazXGLQ_wRW7HX~wy;Mq8zge^IBgD+~lE24y8k(V;u__wTCb;&*4z+ZU7#x7MQuY}m zN|0Ag{0;BH@>@W3`S{7sX;d7PJs+nZF1{^K_61RcTmZ)?TYU(Z8pZ{e&T$V+8N?Us z%ce)8mCa7)j!<8h8w+9K%V5060<}0x?)RrLS7!}<j4e1_8Am$hMgWbU(%4z;Sr|%a z>iBt~Dw++VA0c|8_wW;o1&d@DLoC|p!;__{HTiVswYa^BQMa10y0$Sk^XxaSCUQP* z1tap@>+s5I=Zav@GyTLtY5joBFVFe_68bI;S&pM=rjNiZocWVRQ|x#}Lh2H~o)M3} zh`P3%k(0*VRJ&)*eF>tWm6z>;YsPt(iqO{whF4XJ4}NEcR6tf7tZWZfrDkf?Jy}^4 zf2J^QMQba-+T-|Hy+~N>@7IU)_j4qI{;9o<oKNcIh*jij_%^vGT%5w_&=$#$AW323 zrBCm2Qcg$B@R2aSGEFMucxTfvyWfd@d^&<XpH<NIa`mxL1t3btkJJG!rXpjC$~Ti9 zmCl!vnA$DS!UQ&&5*P^2=vPiUVQDZvPe-%V&E|D1qr4KxWpL2dT_U?Vpk0K(+nl9n zA#=gA{&^Fk$tL7qYjU;D|1$o8Ooi8>vWDWooLM82te^(i&^r|lq|lA+P9|gB@lo7= zi9A8aRAz`G^vd~Nbpjgpo3qZDs45r8i=)UOwB}yjG!e4`g~8TYM6dio7k9o=WCD3` zkAi&(<qKC^gtXCF<+bV)<CO!@ah2a&(piiRJ|dUU#IY&JiNFIchzCx8iK>XtV~KX0 z^J9tf(C+8gEMYCki+fdatsFG4AEawnfLY~dgy$5I;e`o4LKtWQ1RXzk`R^A`*+yvf zp5F4HJR6&7y;$Wq$b}Q}0DocY0Hj{`v)nJvbk_w&j3+?rG_F9X-8MeL?CbSrO1i&9 zKLXwJff2P_tSbOvcn`Ka037&hEYavch;=DO7avv#0O|n3`xXAi_@6=2@m&RTT-}1a zeoOitJG+RuKoW*5PTs9mH$zTfSLttM|H<K#QlJ4o%M7#&@L|6-t(3h8BmhuenS1gF zcFa?i|CV$NtBQZ?rU+~+5AJLXiv_LU@I2PNqHw;E1Z?<vUlQ<kh|R^h?$sR=PfNxB zynM>K0F^u3P8eK%aWl$;Se9vP0zmbH4$iNl4gq|aq68lZFiw`U=Z2}*Mqpi(Ks5m9 z8$lH>Fl^0<80WI$g>w79b#>HwmHTF9!}EW;SH4nI<Ft?e5}hAs0Y3q<N*d6`ZcVrY zNg<!}-%9`S`5bJ(cZw(+qJFf{V7Zl41YD4Jo}A$c-RB$_ILH6-t$e);`9Hg3U_P2d z`5Y2RUToK_Wktm54_M>y07t{&0h@h{|9yQH&wByGUua*zfaJcc?Y~4v+tS+v$>DLp zSu-`TMoWKc7X95{EF*7>t(+3~>;SoS%JBohZsfoJCBkAo2>@37*ouwF+XnM~1va(^ z0!}ySHUKs3_8_k*XoA<|x$CBc_Ys1c&Gi*c09edTeV!ckaDX%ZkN$Xz;_NF%H;MTn zY!v>T?v=02u63kQmSX_Btu9-}Od9h~q|oZ3eN|>)Rf1IJT=8U!>s|3OVyJrWS)3<i zyf`xyT-?G@uu}Jz2v7U?IiNnvhbZ2?N`N^hML|SkB*7AwK`Zo6np-};teZ&rL)b29 zNrxfez4H<n2Y|LuS3R_QiL$#=ss5ge<6ha10d#zVR~5uPqOqB-lQ@|5Pu`!tPn3ok zLWFsn8b4Wm3QPY?2cMD?9jlp3m4BG<m&gL<tcw%y-_yg8p^C<O?sUlDy!%Yl#h=-s zR&GMW#`HQ`(vFhSWz}LOuYE51Q2w@wB|Dj8qp4ebOeX1Z(MjZngY#a2-$@7;{qbg? zFwHo}*49K^WD^iur`ow%JKW)wr!QTyx7y5ST?jWXETT<y5;Op2MH3CNk10_CR=RN@ zFpNPH%V&9&i<d3q{b(2T+Af7cFEa>4eM^a(>^7akf{Bn}4VW%=<X-&O4;#TMSfB-S zPm#?WoLL=RSt)!x#ynJl3tJvio2nM}39=}VXwV9s<Ct5cdg_{Nx@i50`Hy6>Jw;RS z7SJ9$g>mY01?gh9!WBHrw<p1YR)}o)=EpLL3`GtWCfWcmCf=G45k5z@=N7?T;vX93 z&ko)q>9}#Wm`MT^P&i2-4iV@>PoIq4#dSgCfBHgXm1`myxe{0eJvWxMB<a;>z<<7V z-nQqM{Q^pJnBz54ioBaE$?RD;%g1fySBTzGZqm@rHG3#OAkAOIsPYIl-X`3|s)sr? zU^bJwCF200FwRUP^(l#~K8a0Tv!RHFlN<T!*R%7C7if?cx@Z_NM+o@*R*bX8c{`vr z6FAUOUGDeh5q)2{a-Yvi@P7@vV0@8?mWO<R-<;WC>=Aa*<)4o6Kd|1;!+T&4V(MM_ z3H-r)nB}6-Q~f9Vjomo<e#?kk%QMXuw2loOVRTJVK6>RE#cFmz#fFfWP+u%OJq;XC zhznX3jS=-pAhyWukqRvOle|Wz?f67sSGTd|<+y9~g9eamL()K)(S22xr!zY|M^_e| zAg225HcwOtHQ-g#=ZhJcdW`d<06lM-a^-7HVflt0^&}eN7PBIeE)=Obk2e{-Lj4}z z)$f0W{sRB8@emp5sdL%^_iC&#uc$aNSsfLRe=m*-c!_pFJl3Eq)1@MRBC%tK8HERW z7_oEEJsg!lr>Tt?oFc?1=Vn7Y<(#*Jbqj(?aCU3JT2i+fr!+R!ftcvHZ?QAu1-2HR zfN#+6-Wr;hi_1#llrKurbdDHl@A3SizG*%`M!%o&R>25!{aO{C7Rwq+J$aBW`~nwf zq2|j$3c=F9x9`{WJ`JEZY*d^1Gm@8<im$r|u|UtpB9anv$zDx&a6kudHD=kjL?puB zWHzM9?QuA%yKb)Bdsle4<VG(`O3TseFEG7H-vPQR^3|oaz)7Qf%q9EcZ1ak$l7fgM z_8Oi;+#jgDs%vRTP#pdAYQ@R5mOJQKEa=hfpp#j9u;^Wr>KM<|vM!yYxx?NdiIn({ zxsnsEW~v|EEQVHb?{A>`EV^p?9DeO-^lqdIUNR{mWF~u7o4JI9nK5NLaPtpER%l!B zWa<M3A+Db8UwZL=0(>xboTzavaBD>pZsAT@HbGc!>};gF&n}l&vRq9JcjhTyQ>5%S zYm($VFs)m{_nX7zqn%Xh+^a-#v$1%Yt5!g!b}-l2AIgd2!ao0gVcc52V!3?;7UPRH z9@Fwkb;}?Na>lNhzZhL$w@M=Gl{xR?1<_$Ng%kNe@R+oRh8wZrb_SoH4Hl+YAG!#b zo2i&=Zq^%Q@Z-0R12NsP_~)ZyzA|9_vZU^3I%)jVK=@L#%@d7!2j-?geV<e=ok9qj z-=Kl>?qM!B&qOc;+rRHxju*#D7T2J5H6bBhrb0ppmiF7D6KiS+C^`&W#Wh(alAj|+ z(fs<sJIC}jz3eHK<Y#Y|0oM8^4o86r>IT(0M&$?J#ckNGanSDUN>#6ch%KJebyVcr zylIRKvVCoT`67m<G<xt}1>^ivCAkRyM1uSx^gT+Y%ohtgeU6LCbMfkOt<FO2nd?-O z(x<;*@WX`E6y>Na-H5P&az))dcX+vV1O)q&;{(vGKma4Iu`{zcu0WG#G4x>*raj(- z=GU@C_|a=A{jnQ`$hL@$m_m`P9MyR<JJ2sirYm<IczECIvQ>|%`K(+a9wrTe@%Q!3 z8?;%TJ`0ev!TjLGu`5!H<~y8IAMDO!9R_qfy$zE=&!w3{L%SS6s2Dc$kHQt`1&mx~ zqXe=_bn5NQ2C0+kOLq_#OAdC$P+J5C<xU4vO`3=#znibHpc!T#J|!IJ8rsc$_{^K7 zWL|MlaoApPGe9;vI~?wbL@@NW(|jk;XQ7ox>neB_qi61cnOn0hblXSb8@Anc_Sx3X zqlvSGr}qbMJ$@9iF!16iDNIgvU)9zLA{q<Cpm0zJYvMwKrEeoq&5{)2j|2QYB}Ax4 zc{@IrG(Mw#x~!>wQ|st~S1~Vz^gbna0i{!da;15WTexJ{F_GI<Yhc!mMufZoGh5{k z3BAm!7^uI}*?x71rfN%((5m`v@tWighhW6uAzlZf;+4_x-c8}yeszAf$o=)Xg-NT9 zRPexnB&-K#5s9%BTXQt)^sRd%CC}G2m~E!tRj$jS_i!d-+E$e%rcB`pR69s6Q4+{T zQK~Fr>a2Ebp#VyJdt5oOlfBFIlXzW7S;=W)26~^&WJ>tBS=gMB?Li{_WN{AByTK$W zndbp-JVsj7*|5*MABX<TyeXYasYs8Pshin1=NHDSD7cqdF8vZ2Aa_uxaAxPHTNu`R zU{4<9^CrL$YmY>n3>#yi7Tw6Z_445XiZd<6Ww5f!LBDec(r1v3)tJZGsM@B5_g~<G zt3W2eF4o5Cy~el?D1y1TnB0-S@;JfB@vTrC0zdsp;vrjxi0Q+n0j8=wD~)rzNa?#@ zH&~XZ^%3cbHf<4t8UyD1{Z@8#K>?Q6`j~k6;>tYP&B6u_gJ-<Y95h)3CgKCW&?=TN zms7MD>qp2P{~q8OQX)Iki|dBn27z^Hp1x6(gDg`LMlgooM)GV}AeTcU&i#yOn@)*` z^D^1u_Y*cFO@vbF_-`^b?D{RBi1*)P5?PuFJa`qHS$XkS!0w2N4<zIT1e8#5Ds%Px zNZJ@JB@@u~dd-u&J~r57gr8pPkf-~!X)18EvF?!)8_`VD;<W)$_4~6o-+Ja#3*x>o zGwIZn8+4xNLzNpDx&YCbta&HFPs|Zk>Rx(bHpXd=S8xsHQbR9Kx4ZnFp)6Mk3X)ix z)A$zLE;g#mFO;jk7J;b8B);?Z^j8pGZ}V>N`T04x?y^%T^r;>Vm)dZ|y3>=hy(1uS zccoT=0dz-^!X=cceL})YG3W}0N+V>Ibd>Pg$D*pqXT*xjKYscit<K-{j6C@rnScu7 zJ6;zDtVQ}V=qI4hjWB%()KJ`~jSdVl&KK^-qPIT4^7YX(f1W~Ap^6vt9PPcLbS1MS z15A~bH%cmsJps$o$#ECY_vVdu?{Ejj)cT8dq)~#sPhF5&L&de+liHTIF-KRZOJY*g zH{2-4_o-|ift;>zgLNHkl~h--)reO`#hlrk^0vbT!yO<*HVta`aOhies`rj~o<{5d zKqZt;p59B4`r;{GZ8ha;<ekHwCV+4&=kH4bOlR03v~bBjXl*Fzn#(viP&#r?(hsa~ z%d=vHTe@Hmg$~-SzAqaiLVArdy_$XNDBPfvHf<*m)TtX2`lPOP0s)$5Ueo%SImjez zhjGhxEieZgfA}iOH_tJa%-L08ulAK<Xz-if7;Xr45E;sAql@MHo^$Kx7MA-S-<-RG zg<ZL_Q*ei#SnjcWg^8^E%faB``>*UgH<CZYFuAAkxX+l#txmvL%D+9iXte<Lb1nRx z>DmG|#%!-RJbDC)GvjUcmnuChEcsz4Pbo;%2RX)T8(rn<q~9)lI7n}aFgmy2J75^n z*M$rg)X!VO+c`rw(8k2wY2VvKKcOmKqIPI&3`^}W`X%pr6@-IdgtV6F)Q8r{Ng6sU z=@dCBwRSHH^OxEd<+)-2qNhic;Wt46qrWo_W@e9{k@JtM_Pzbl0Gp8+<(KC%Y%0XU z4MpF2k-&7V0cZ`8v$_2ovtZTa+{S<v4jppYInzd6mi`%51(RCce0LX}ZNWquxVjaA zmEX3ZbajJ=N{s<uQB+po+C`jyx3H&okZ-wVrB|D+&vDFJ1mla}A}O~FNjqai=2r1m zYby(NS~vrtz>H21Db8~Hn=0$sDS@+A?FEIv_cE}%#4fov=Z~uVfEnI<Ehj#S&1)I6 zy)WZSqV>P%$7ZFdFaOcuZ`Of)M*0dCPw0UkRu3PsW<)m~Bx25UynFPr1q`=sJt)xM znk<FiNGoI(L?#MU*2qS(O{XN7$r-vR9i*hLm;H>IuolJvh~R2T7m^CMbBV6XhC|;g z1+lcc6GIrJj2Y&q3+E%+s5{AthWB!wwi`DoFVRT2HHoE2v^ij5=#bHx3P>m|;1{m= zZf?~VCDSzJd%G1&e(EnYJmO8g7?M6gtK9w2+44br7!zwb!5CWC%|X*9cB!Vm%JzD! zmz}d?N~j=H*lsU!0}*8WemK$DT$Wdw3jH85zUk#B*9a?<9asdcUOK$vq02Ho&J$~g z4h{rGuTD}gAAM(6{3+sUeG>OH`Mg4+f^B30v)#PGt&#YRt0J?_gxvmDphOL(TA;i{ zx?RqwY@0T%K;vbY=Vm-ywzp4xNuD=phl5#$OAw`dx7G#E6FXFfDpNvenMX3`faZRl z367UVbn6$%iDb+aMFRoB&*!>|9D+2&<4#*O%c}QK$flXKsr8&khb|uA3Maa?V{m>1 z(TjvnkMG9^1gY_-&4WdWqxSO&bHGv*8SS=b<}e|&cU<4x21)7EdmtJSUq_YUr#9&v zz(y~=Yw;3$5)~UN;1bF_F0$TwN%1!8W$aCxI`D7;t%}SK11^WcTf-@jOkTx$w;O28 zqct_do8u0+u0LM+wT6H({4e(2^RLOR2^)=~Vnaj)q>J<>(u+W_00PpagdP#85s(g2 zVxd>*N=LxZdk2X~6Oi7d1_Fq50s;Y&c$UxETixe<_VauHfb&ffbFX#J%qnxu%r#cm z(*mbC51+!qCA)Q0#OqMHUj2GwZNjnQmBXvpogWZ3XWisYt{|Z{FPnZ>mP+l6`|p^Y znz0ubLz1mEbCq>6r3O+;Dh9){yA%dvAI{LiY1cRh3EJ3Z@|P7gmF&{)0pF9X1sw#l zC>ps1ui0N*t-?O=PI!Llxp))Pw!`U3SQF(@+XQBMIa$2!xhSi=6>0xwTl$fTQd>l} z(QEytvySaI#MVZ>zVOVdzaBla-*1xeP~7(lsh>Uxj(R4;vq`HviW-t=mqxhjjfh_z zUE>@v;5ciMW^VR|c6D)$D!{rruare%Y672zt!@c_II4xKO3TD6Tw@+>eG2v4nJB62 zY~@ypSOO&x?nhp@DBF+U@R+x;ihaZ#4`1W2H7lhvcST*64tA=D%@!@b20Ph^d^$OO zP#$}KLV-9j({?dXsDZAv=CK@2)$!40twKg!12f!8YKj%qD!6GNF-{?*U@1=&mu8S+ z_?^{rM0;11__i5VLd^C??iRAB)sA>mSxA=D;&wBgIBRiYpG8h(4Hjq(eH7K0(m0E| z+HS*I<1rI%ZgBZfE(QcHF4~ef1{-b`dPHN#vC~7yR*84hnFfVTN|bDOA4V8#GQ9|# zVCgJg2-G#(&aPgg-7IhNC5vdAXrE@<>;bJI%NNxv-iIvPiHkVyx>HibeEM+lD)%cH zzlQxMcUfyN)ZXp`#ojleL3U#K?`gUe;w3@G>J1!o{#j>Rw;tANo2wDaWY@wOM9b|D z`LFI8EAS?XFa}}7B!WL;9kq6a0~_Z~Run9(+E{;GqtJ#exR>vl+0`QOUgw006Zi+I zLNk>pZWUhE$=k#g@^sM}u22TG>ZM#B%|F?ms&A{FeJQsSs`t@Z`v%~PftnECHJIbd z?`~p1x3979AjRe^Ab;}dDaPuvMU05YbI-%{JL`p?A8#nB<M$uGBS0I^;Jfirz({5D zTt=n`=b>>-YbyKT08MFSb;S#wjK+w5z4iSfYVR)gsP(K=tT}svx~o;Vp%%1ju8uNH z<`nMY?B&gB|B59UuJp*&i52*2l1sqYn!flU-SHM7jvSlRX)PD({yR&|679liEW}LY zOx7-(l5_%*%1(@M@RpzfMI#adUe}_|#uSu)aADBkTl0VQX?c9>Mo*qeV<+3Wu(N^P zSjIW-54TU2)7^^ko5IGXen%m?3_6W_<JyEmV6f<?EIAKqpn~0!&ZnX_cPVBO4@%<9 zR{4f?SsAbyAt?C8(5w-G(QuX5d6iFMm+E+`Z(?meR!R<kr<|CWV@@~}BHWFfBM;y4 z6m(tV-DOgdTBE9%b<AliX{AVsWqzd0?xr_t=-QG~)-B>tP4+3=%9apIM9GPHn-TL! zSE?iAI6R7!=U#q}ygQg(>&aH)pIoauL-ASN;6)DC5nU>+3&jzQSMeLz;^1o_6^5;~ z`e3@yi>=GqCug#vOyovIco?zIWU49*qCcZ2>nqjjZ6@;rl0X?4Sf0UTH*%k3W2Dd+ zWvJjTH_AJkjOJ}NyR^u=lXG9w)$(mp60A^CJ7oTCo?1ta;=1TQk8|hw5aUt8l|9V% zA>};sW1$ijp~iY5LG*&iM5MqQ#}`VB&PJ{+D`{JFAnCbijj)2%@CJaZA4cN`BuyEu zfdf=MK2VYmClT6Kn+P(v7ZsCQ27s?(_&F-;86?_@jnVBu2PEnLLJkKvQG{mzQuIWB zXEW6KCwl6Is3EYjd=b>?9ALRFY64k`@Qr(K+zW8Hc{WPo6Hsv*4l({8qi57v;G**k zSol^K1-|Z0Ek$Mn$nY0{3OcCot@{QO5gGr0PwyMq40tH_<a+XUhRM7yb?sP`A@XGu zq|pK3nh`nbN>Y5r_CLnVN;0X!omI;;x`S(&JH2I2#v<X6tp|R<d`Lo?5hC%r(6h)- zZkT1v!KtFQXHvy~Agt1Yr>2$$u4M>J-Ya1dio4lyriYw)xPOQ~f$-8Ex-tc_)-TG_ zrTqqNMUfvJP=F;i3xmRsiYP!_Fu%VO)5LS`M9g|o%6x~;>i<QY^%d+d<c&aAUyy91 zOMf8MeA#cG30-X2eR`il*vONv@IyGzHY_Z{Cl~n#Dt*QfVCwHjiQdp{F;E=g@F#j* z?D$p<tE^s*kXDR2Qpw(<C})aMX)0>|h}k;wl5`xv?(~q(KjfhGhboHVLm*964WS<a zXlP~16PG1tZCwZPXos$YdXwJ}wJOLh-MSb`df!g+8xEIelK72eE4W6|9j8(1JQTXo zFn#!5C~bXI)`a{ya$$vZ<Oif&^VpwgHT1U(s0aGx8Ht52@d`aC&#Rq9GU@-(IAH41 z{zJ9^kOwghKM<Di2VoJzT3g5x`nOnY$`NiP_TUO5{Zxsx^@i6UCbr!UU=oJRAlC8f zI|~5q`{<tu0ATM|T!8xzIlxpEAkI-9dMo$hTzTx@T2#v+co*3PB^kYR)Bcq2z%X*2 z))hoj29V!4Yo0<j1fX*Rf(KvGommAn4H}sfpcQvdQ`D^zs?^L7I9}C7V;>J#r>x1; zYtZMBpDgD{bueK5r|dxl1WF0GuevR!zez_Fx*fzt^C^hfhrjv2?n41F*D^$I1|g8! zZP3GmpYyy8Dh5)8Kmkp^JcHbM@J77<sUUF8)vvS6w3(f_`EEIy`t^lYUH7xh$suW^ z3sV<KzAPkSB4n`00n{JtkrSPvJr&4Vfqv*BI8ryp@}wImvB4MSl$r}vbh}b&WWD-M z9H$0$d@=wO>&Tb`s;#$?_&Z|g{W%sQ@zN2*KLQWV2X_Q#-8?J9u67>HxLwcg!@EJ? zsN*6Kpu|JbBPavk>tK#NV0X$V+WawSj+pGN(H6HrwSmco?3ZQ%{m(~Z<QcpF$FSzJ zqrnZzGaK|@JQ6<2U1=PsWH3-QT&B01Xp&*iy|3FBVEjUfJmYHP3|<73cf9~a*>K1- z$Q`cSY;N|It4da8r!PX$RS(_ib+%x=V9fon@1y|g+3m|glvQ1<4?n<~tLSMmGN<05 zyhBPpy5H@bc_r;ao%;_Jxy@|z`yPcg4>_)64iMK$0|Y5<GX?Bk_V1=}@sWy4sTVIu zGW=H0wnO`orP69u7N<0q;Md@sjeqkUVbqmj;rO=M&J$&<Bvn@z(${<J+}#LO4>N<= ziiU^xEs&MjU7yN)$Z(mnaj1yK)0}bG$RKgr@oVVgSycxQrv*A~C0=0Ls8uPiNnRt3 zj0%ceHl)^nphcDH$<7B4gl@)vOWWT3$z?WL>)Q+6ypIWomlM-Bd%_D0SL)ctm8?Yt z+<LqHuHK7gWqhcpSxA3s#Cp!)l>Q$3<FqUbUyeClmHX}D*(yAWS}H~=2W{T{hNkO$ zMttuklQwH2DO-kpvm-nBv{7Ln2A^a~^`q|J56$ht67y0-7ihU_c^!2PLtF9+hmwf; zCHUS$Gv9U==4)aYCXY|vw?PI^-ZD+1E4t;3;&9Qb-Sl?_S2MeOhG2Vb3X~{SgVUs8 zXTP#w^ww?R)(u|>J_ALt9?)nhBx{bg9yi$*b)&akDYd<hm0}bv?JT)7$A8a)#ZBhf z%`S1IV1v}58{r~;BFDqw1L-IphAlqlk<h{{?f-q_=!ZTN58ob=C#dfiHdga^cW^)T z=Br-oJk`#$ClE{yAPJB_&I&@7<XA>%`ru8E0=1=|9)G_6#UUkAGmrXg!GaF&vy(@3 zAer4bhcG9ZF25YJ5&`LL$8c4yOLGhzstIrEJB=H<vn{itM>Q5$vfZh$rE<&*lE!;y z0zLC%P`rgVM_sPO-R+bq%bD}kh%TtjAm{G9p0#m56WPK9hxHNITyw28jo)`(jx!uo zHrfMxZLnA)5y50CgXHwdySJ!0B*PorcSAw`K0E?`YArIL(3=uFVZz+BQ30nNLr93% zy=e?LV7${Z`QaPMa6_}76}i7qBIb&rZsY|mT`<%Yf`K3y2=2b;h{bBrh?U5T^7n)* zV%iyxJUXw=Hc>WH>T;*){v+e_)*kKc^l8r>u8~;rhqJxGa?C4z_jWPnLxuM1j~nFs zvr8W#d}NCskaxv{N(rZKN2&;cPBTvO9ReLVN6PV@4=cl#YgN`z%(@<iPYk!jT=ru^ z)!rq>fH;j%lt*L}fyE!Yet9qdP#NZDe%K|g9WLqo(J%h$OTFYc8};Z|j@8-I%i1or z8!yr-Sz6PAo=%5u7Vkd8D-_x!!u>1EB|^lem^;tlUCATpG7}CBHr^ecw%Ho<?B#8I zWb^hy%O`rtxxHd$Z*jZ;PL|~(iEnc>`0+-1uw^yQHzP}xGt<r`*gnemHqw4iyYkcB zE1!$h73%Wi$!zx9cio8DP^%z<4>o@zDD47Zur^VoTwRi3;;9)jYYczmT^p8fALM*W zXUig-3+CnLkvSH)%VfVOkGBz?B=F%Aay=|{2X!A4xUjOkyCzrK8AX&F7~Qt6M7MER zhS^nF_pzT&HE3t4{rbgwj^edet68yvvf{eX!V9;C$wzPZ*CYmvL!cCeAg*hU(+-r4 zyf|yKV0<IEi;G{DzAyJygt-RA&eC8ujP|%`WF_jUE=n(%<E%JmY{vcQTth#dF+smZ zX796j#9P}sjaKCOrFc`;7{&NKW88@UTg=jUM6tcYLq7JwrT8f02|6q5Bin8nF?$aD z1u`A7<XFn4P|QW6W<=(4-OgTsn5vPFv&QI~8N1U&3*~jc3*9ob^!^1BluzQ<-%iT# zT~a-*#JnNmH!ScNZCiYH3eVi!Hm(<0j42E+jE@v+*lOkfxR45qnCBMe(F_UcYiSLM zxaX(z4Rc10&HE_cW`^QgyAH9yn}>1SGT}tpRS)MDz33^`g_dU>RjRKqc5-MOy>(bc z@UsYf9+VrB8|bV%zpQ9~EsaYyE-owae&x80m=EpL;zJoKtS8=8HMErO93NB4P`lo4 z1#55w8)ZQD>a1QWZ_4S@(eGjx_=Vr)H^-Sx<_>Ab+RZSF;yn*FNuPWfM+jn@M%aLt z*o~uO7zM9)(+1YsHr3+X{UXMG6}1u%Zy<%9KPbES`g0A#0vCor2YBh9fcR2#7Zc?y z=2?TR#q5fX5nmyfI=<X3ocSB}Vqw4Z4P}|u>+|>4>XB!un)0`OzoeBPd^_(EV^oQA zE6rAY6r+^y(bc>(`>FBs>gmhtMYA;$r&wd{9(i=m+X>Xz?QhQ{v{L%R$)R?UL8kP? zH;bDiwX+*^%cYz#v-zboS+6i+6&jKisUno)53B1NQhSb^inF+&z-l0_bbXUGDB<Em z0qGtml)CG1+_5}EmyA4}OxYBrUONHy#CnJC#$5uv-Wr>8L5@<S+ZyDl7CUUPizXH| z%VI)Q1xsz&XRU@-I&=!vI}7PFsPuFh)2gyn?6Ylr=&+Qu_>0X#J}6ja>dD>%v<S>( zqmS`QHTz6dvK5osli_#X<cC_;ds`-WtKG+yC6OJR%0{!K(j4P^tE)YRdP8OpDZBie zout2$38NWs9ka$x8|HEjSj;r2dQH>QQ`bA3A}Qg>!+q%=F*DBZ%Uq}C9?6AGc&Q9! zi!Of3k>sslv{DJbn_Det5!#}tZYOEBf61!LTh1YzbcL8MV>GMUOZQ2J)nc}b;k|U{ zNE?Qx&6Do3%!llcpSlsQ&+3QRVj4O1n>Ii``E2ho1!t_Kv|9Sh?)v&+hZ#%jfPqI* z@8a+4y3I%HpUc`2drsaorP^jHSdNP?pQF6EG|l3FykNwa38$BdlAYtDjU_wQb+iT+ zctP}j<K>sn!}|Ns50Q*`?&UNZ89S_zLy#%&=KEL)mU9&o&|r7*GyEHDK6P}4b2<&D z>bPg9W|=H3qj{*$Zxj#Vje^RbP6{RzTd0T*(`)WobuM&Jt8Yb?m&cSj+0~n_)r;(| z#%&f;ZK{*=&-z|HC=%9}zTUPlB%CK4aJ4?N{4FX35GS5esnFpHO6AQ~Q0oCItEl}} zz!I8Psrbfob_)IxT|U~v;N#V%r`IiPi1%vRll~Mf9%=h}TH-vb0Y`8m%tq^0+2xcV z!)=Wh7+SO)GDHKJZ>Y|2A9Nw}Z_IwHoXyTFQ$0Q)Bj{|a*5n!u1E|RS#6qo(&a*>_ z*2oFInT_X-r<R$acG|{+-qv=E-!K#nu$eW*LEX9<k?aN`9wDDZKvmUwpJ(i|#>Wlf z)D!fkhME%gF8%>-8F_B)u}g;-oqf?YrJ#(unpC$F(DHrmbi>s<&%4UI&|J3uQ3g<j zkFXCK$4zzSx=fju9ZXFv+{PVu-Q3h;l8s_xp2UP%MovqL1a5<?nm0K%cg{oU%*(|V zGiusYjpOvL9FoJkH9=m|9@H9R;J7)RN~7y|z0fc-(@-l@?lJNt!rhmd)E|l^Z|)tJ zXsIiDWA%7^7eyQR*rk1lv*L_>nLtmHj0F9&{ZIO-*l(9ONIn5K8!#0ct5dUr7rrHG ztWM0T@wG~0f&^zmuqMatA~N`eKUvfX2R~8`NV64<*j|%w_b#*7(_SO7)!48GwwSUG zh)&$FJNEtuWVdiJIyBoq<WBrXPgL;B^BueuNwFuVnr;}B&zoKWWe~#Ma|pq4?T?L@ zhg@0crcBGnJ(3iLzXtGyx|PSbn#5zJ9&DXH5zP}Vqy8{_&gLq=!ECv-Tdqv2oT=X1 z3=8rb*G#S7#hSZ(H|`nfU-os6d6dl2MkjY8sJuWX{&YM|0ZK2`;^cyJtAgUC99TwR zt~Qlka&~7%hq}M1exAL*b?3Qwvrt3OUaY|c*Q|+muzEY`5l_0|I!drAZsp84CU;Mj z(b2%BYO9@HX!Qp~=NgTHA47KB6FQl}-59(pws>3ubaor@mGanbVy54;i_gDWl$~qS z_0G6+%dq^)gsb-o>%)+b>~E-E?W3F(=mm4fm(drzC32eQI=)i~39gDRIebOiX-)gw z?>=K#e${y5^X#2bE}^l@L-ohGb*PIFEeE<AfsK6MM&wTRziTY1u296Wgqm(4-m4#~ z@Q7AZ8BI@-*F_IA(YQP`zbN0iBv90pMl0T(BBM@Iuu>x-Iqs;H9G$IxUzszH+u$RQ zSG1SYmYDex;rfR~8L8J@Ax~aEK4zgrsUljsLrng5i_}G-p30;LS_oZAE7j#0c$cY{ zoFGtww{EL2LB3=mCs-ZIdbl;;-lTr_2Dnhup}7cE^9+vw35mK)HP40H?gG<8*I%<n zIG^Dt$Wa*n$R3e!Yr&^X_LhygfwoEw?}ziwm*+@_#jN;zoW+bpDo+VMVfK(muWRkp z>_iujtLn-k%?59Qor73|eY8w`$>n}Rm-E+#&{F-@0pIRMHe5jAjLv{Bn@6wwh}eoX zwx$L+jZdXs7~Pb12;nhQIFfBFUDZ_S<_8rng$8+`n+MwFpY+O=uUV<v3x8EsYs*Tm zEu_~B4awPgYS0@$!Lc7WaLwP8^;0gchl{7F=hEc$rR|49fI%fQb|weQcI%0*QJgYq zy#N7=<*nP%Sx^^@kUKp@Fn`df5mvcDF(G4lCcdAU%+-^<mr<ylzD~vX)oP<*J`H6( zS(kvRGnOR`UcUES%!D54*Lb;KjKY>lRQatfjGpQ9eRh$FwVFtcy6TEr8^>dt(kfvy zSFYZrmzk?3*4T^Laqa5iB16A>xz->lmNJcNOJnqFOCz>MIu+__pU+qA_u#L_={|Mf zcJd>Kw_%u(O<KN^9{pd%pT3WeAHY<0)V}CgOxaRq9d}x8Ez3@Nz_00Y?4>t(o97)# z(=ZW6H3u7|#6*<ZO|ST{80T2_$wvdB;e&e)>pA(Pr0<Whj{`#*r2QG?C}x+<jK6iJ z(AR{Bawf%jjcT=Y7IBIhXR2%EyHsep%-%|dFDZq1BV}W3nPu_B!<!!VgeCf;1$8SG zui8<Dav3(S6_T|IREo>kx2IBV*e4o3<v*W=0))$<_}REbge8bKhCZbjsh;gtUaLIg zW4Y0i=sMiGN?UkCc5<XnB;}pQoQ>VXlbo&$Umt~Vw|B6Rp>5M5$Y)`#Oi(5K-rU`Q zn3<ED18k8k2|-ob&>+zu?@#hEd-wD_&zH@t#kDI+1@0CS-vV5aiE=j+AM+L*<T1FN zfF!HAwTBdPZM|)KrMDf9ntm>A3o7%!qYF6>fk2KnOgaQfEf_0uMo?_EWmYbH!tm>g zR_MfPyTO#53Zv`3B8TxZ3I1gy=9jxFLUGhL2mQF{O?y1T6l@d*Bd%VLan^XVl~do5 zqm<bH{_u{sJ17sm*DfA8hsJZ$HXAV=Ri*>wm?y%qp=z>ZXC7x>8937;VJJV><9X6$ z`lKcMcPOQ|;GvuiXrLJw{QV6{$RmEe6S_7uBxb_*p<l*QV@>0jXW`=*%*U<PuN*ny z+2?O$ZI!p5xmBu)g>DXFsuqb%N-ao&;KmOKe#dL0`3EH82c%M9bX5fFZ~^1(iz}%6 z44p``8d|{lOc*PbYj56Hs?xr;FrGjga@~Vg<VZ_++VjtOU-c7T<(g*3CdU^kgPeu5 zQFF}fo6V`y9(f*5d4<AHear3O<Fj!nfYurfGphoIN((_AN6=51c8X>D-ecsxt4W$a z(t_o*$A<jNR@0MZ_@#m+ccaFxTpRe&%$n*XM66wzQa<%#;j(1r(@{gPl;XA4LzSz3 z$ni+*wVCTkYzcY=5ON?QaIn_*x7(i*NW3_7Xr-)`PTj<Ap{j0eJQi!0L*=f_%Kt@I zmrmw5S$d&QyfEAz<4lk;-%q6-t#L|4>+PnR5}_%?O4S3W!VMpOQUJ)N0?2Bv;4T2# zT0jczMxoO|@hZcjtu}~7oRnC*>aL=0PE3{%G;KeGC*ml7VO$8_?dI`Rlsjjp4gF=5 z6E1q@0wr6BY=8&}iJZ@YR!TaP{4x86$a$|t!gUSeU33MC#O4klFo16boB~7A?gE0l z7EtxK(dte7Hyq0AtQCRu1Ja?1w0*KjJcHh<0EqBG4A5f9;#frvfVTYjc7rYpw4lp- z+LpbL2zrp^brzt1_u*?`kf1|=p&9Onst>Iapq6!}*{lXJ9C12P9iQgC=#zfKX8&c{ zK7#+}gFfP5t3111pD?8Jk>iqBe&4xWmucx#5Xfmx-24sy*#;DY#MrN@-B-vXM8CB5 zOgm{Hb27h}Ll^f*DlZSU1EJqcen8?-B&B*}^RXY0q0mDWBvt~shmFKPNIQr^+Gr3I zH%J6nFXmrRL8X#5WbXzcj(it&4%r7@nNNcdS>SsH*(5E{V1SL^T$@KS$;h6q8dSSh zh;<m-x+`F&{~-S1sZi~BCCgK#R8()K`sF$NJy0zyfzzUR?Kw52Sxk$@xk(%8k(eiD z=#o0EI`I!zUYt5tkR@CfT~ttzm3wTG7%q@KfV9S(@wlyj<O(kSos5tRF1gNd+4{h> zx$P-`KE*_t$O+9^RX&K$6fp<nH#Xt;?kRIU&}c@VlsG8w!#k+4eHRlo<-FXkp0%GK zu&dIuyF~PrzzCsY9@e-?e!j*qrl$MEmynfBdt5-Ls@%|Uq8_7eDqiMo1;AiOz^XF3 zPmlbCJ&M6~-&f-Vig$gZ4;Ric1~4d|P}1I^p7xIF{vVJk72ce58<5t42tl8ko7m^2 z1A*OOkHmNBAtlYxt3{{iE;CX(@oD@v56Iv@nr-9)SlQ?;vKLq(rd%zp<*Dv>N(%=O zI?mgS4>IT;UWaPSGiLt}kn@enflt%-A`KE1g#*c>9V}}FJ4zbsJn=UZY>_*b&qTi! z^!{3B*1*K8?*Jbv5J0q+&!pZXNVoRjI{*XxJZ$@=VRIdoYoeTE*cQMu*+F;h2(Krj z4*a*(kO|jQo&o*rDe<%<Kg5|oMzpm#D2#t;nWzWW#M_=7U3MpB#>j`<WR@YH|1o0Z z@0pMZ{v#G(H2yw$nk&Vj;u*83hCpZv`a1jG?$tcxN7h0R9=Qw__P6x2o!?~6{D26; zHz|pUxqp6@KQ0Z#$jdI>bZT*~Yi!%f-g$8OC;iaB4u2F%4;DWwbY&L#ou<gJPEBu} z@}gllRM}@MKlr3$g&iaUH5t+aX8#9#P8XLk3*V=_`5j3-0`&GvGQ2(#O7Hs|F6s?w z>0N$4-8mEWO6Q5}r}T4)|6>Bv`M?N&chDGxIbsC_HLIgPj#~<AFeqK-Rx}78Uq-O} zA!djsSe=oz|7mp*k@d&FpPgP4rQ9boLXNT;o46&C6P_2MS6-!`iPchoIQfFj=P$yc zAsmtrU_`1dv;c%fT+e?%=6a9^%g{Jy*8vX}lFT9i-81(!Pb`2ckjuUxlpU#xJotwB z1d}k~iU7e145?0Hi@Lk-h+*S7@XU5%nZuHSZvM>1{#oP%Cn@&GaKFN(BN{C%TgPj` zqmV-|S`$<dbpDJpsIB+`$tk+_>~wrP32OEe+$Sva{{HtjvO#Y;5JaT%mc<3c%x#>s zg_;jn$f{G^R;}N<uW|J&9nD<~;zePguH=K8Z7116h)$bm0xj3B<PeEQBHUXW0jhUf z&U-3DUz!bscYhwBVtGBX{i15)LU|*-0jt~j(yb=$Lj0b>lR2kVacIIgMjaEij|`eV zzv&(#NFno8L^~bBpWC6RE`Z`zuIa?NnOw>&=6^eZo|2{{P}9yPw84Yi6C>M;k6}C> zt<cXKxtd&?#~2xoCs_AsFmQf9|G}J+qrr~fpDFIrtH2Q#%5h4?U{@%)Hx0hBz+<L& z7Lg)8XS^vG(vY8&a`dZ_SHg>_OB}6LV;t4d)+RS?EXQOEjMzgoy2c}CU~9A>C(i~q z)F_VED(1-AJ|03E`8s9!V)uC5BcZ#6pN^$7yvl#3&v#AD7uD?T3BNYqZ2mA?`Q}a0 z=vW<39WQ6@oHicW3tD!{tz5g4H=4&_r?D16ol9H2U-GEJ<`-4t<+^XD3Tww^o*eKq zW2jO1m^>xb87GRis@MpifiuwFO2aDVTBfq#=qIPzbMT=b_M|y8Xk0JF2?`XZhah~^ z20Cr}%_>4Z9@k$ROCgg?7?ZnT(|8Q;wfT{S+FL7ab|)eQwG{uf;VJq>v0krUX^du# z{&D~AcS)x&CGuRmrN(YIA0w(S%px?p9XVq~pzfLt42u$tq#K75_;JT4W7w+?E>`XZ z7Rh`uKUe-m<I460ugtGK(VZdvw?f%_D^4HuHbXB03Mq$i#XZGRmW!ekZe8~go;%_0 z8o0-9Y^p=4ZVk~Nw{AMfsPPNkT0?Lpm^-+XDAQl)ue*5=uiG-FF4yoRc9Aw9Ig^Jy z+L2^)3u>uydURplcCu5v!uzp1g@v(hc;MNQW*KIhN{#8RGkV$7s&5p<g!DbN?b=il zMCY^p^=+oLTJuahlUX<F)ZcKmzW2b_?|S0dut+NQ;|Zh-Yqp45(fvmV7wgyTD<YHJ z6csN@%U)$M6-1v#o<~}2jAt5$n3(I}P2S<(N@2s6=^0Z`sM_6Zal3jf1OrPw6FkHd z!Ext7&?R%B8TvLn66Cjr$cff94$47DT_gcqZ(xJO(?s2oyab$0xluROIPP)c)QB<- zR3IciIAFH+qSJ^(i;axqj0p!pYOed}T$3Rw!NNX~KzlHqBDOMF@38%#+<?Qw+<KZ{ z5vvC&-(U^sReW#EZj*;sQU@JEl%?dNW21BC<5r1ZxE3<4T1G$P6PitFQ6aNuWuJQR z+TBkvERVQa#WkiEYo$#UqLQuu@!I`-Mg5anF0<5Km(`P(Rbg{9=*^3In^jS>P$myK zqa+84<-${&MH#alu1hWqui0uUBc|7<o7Rt}34ERSN~5W{eunoNf5+SpNZ<k2^8nOr zH;tOw_pau2{L_h#jVGgdW)0rbY;YvUpvGE@qxX$6u6}rX9jE-2|BfeZC_!Y#$ORtk zD~NwjQ;Y4|va5vq^=2tMxY|F~Wu>LXp3EqB3-d`%a=!AaVTr$Bu_x%j>SZGrhz149 zNDH?1j(N>8(i6igXxbbYZJr*Qd~P6Y>>`%TL)kYRb{r!msUeRja2^E|(mEOH`8g?r zVP@{#$ddV)Nr%r#Y9<Exlluhs0Db;|DoUbJJC?0y!X-~dB%gOUImOn+R^tqPWlm3V zRW@h-pey&FMq;5#r4%<lbhpLfStHY6B|J2(e7!oq)ti5yU-SorwjGrn^-R=R!Bwbo z$j}CLK5L$pjP}Cn6Ika<45A5Y%@T?s2P_#V)6v#6f0x2rs@oL31hzV^&<0h;!xZn= zSIUOhF=`E-#WY~UylW^b%wH<}DXQ$yA%JW2nzsaM5}!JJWhkpOxbm{OW<KM>ktq3d zGmx>%U~k`$&?eyKTu;MS<1)pwyR{^x6l#{#tYhD;dDPeHBssvkT+*;mRhgGpx@r(? zt@oQ|p429c2z@W@Z_3H(ERZYga;2{X8l;)yShMSy+-Ku0bHe&^`i|_T9cl1H%u*N{ zF@*B0n!itNb;-}Q|6nfT6>qJ|Z`;l2fnjjG^vr1@CSX+VhDR~B!5x%XptCUFQmJc2 z46P3&0vnvU#y0#^LZ6mRjvL+Kics)!63Di!iToTDlI47h54PKZ52f^LV4<$6&$O+6 zs*sfZeYZ|9tO9R;?W@(+MS8m-k%qP_t9SYpPa0&OZPi@EPiPZsW$5=tp27mrHfGt@ zhK-p_m6IdlRWQSVH<p8*_P6fFM^!|%Oh2%Q7khBMATmy4#N&jF6ufzo>8wd|E&ErL zgs*<1gA;F(`ZE0N`|N=|DNhr$&nB6FjXBk9j|QBo_tyKnP=}Cgb<t8Co<Z9}!F()R zd|P?AhLhM8oUZX(l(cXK2eMj*wUEGo7eqME+?6~3#oF*@O$deU_Pyviop=Sy>B744 zQ<nAImN)KNQbpgi{wSm&iiaKE0>0ciUs*ibcr)$As+a>s2Ya7UlC0v|ZOTfaDnycz zwSAFUa!X_syO2Mpyn%5X6uQJhOW?px+}NPOzuZM_zWt(6h0%Hm$EC)JO2PSa)kFi` z7+&~p@j3Tk?>0wuf&n%)i43#iDX8{bQeUFU<jpFhFQD$AyoEJf$J3+g1)P88S$Zsa z^=ZV4F#nuinM|FIjb3xBGOumoZftty=d`*ZDc!`W8YQFrv59itPWEYwlMk%1I8RJ% zhzCK>M(Uvr&#lbGV(mBT*Hgs0Ozop{xpP}PHFcJJV2AQ>5BIsnR+DQ#AgZ|HP#GBU zrMD}S(g)Iws>;A-dY6}u)z#;h23V@pSjO2Eqb<+gIU(WY$5}U}u^Tqx8cEykF-<wV zQ%vpQyt;SYrtuQ4e8T9<RFg!U=xyT3o0kHtQ}tdPxWD3;)DAeqwMdErxd1R?vK-B~ zI(Ps}^9B62%Hf@uWqS89t`LER3`+y*@RG#q{rR_Ih*^LZ$n6&Whau!lLmJhUQ8Bs- zN<S?Ip6oc6og^)P@1W2Hl}sb$$|~;~s~G#aZ4t=MoFnDsM>WcA(QVFyD*c+f_8nu> z-}ei<M|hStYu{tO;KO4bv&y|?y#v3<aPU6KR`FxKC6u0V{1Bh_Do%m7Vff*<!CaNf z%RM^GVju0ZNTf}rU^#Yz+VFQ1zS+Q!Y8uU^Os{MK^I&Rb_QW#9J7tPFBP?wqWtmF3 z@dW%DMSVU;ORA|UWu>^r8s(uPK?-j%<NUMjQK&Q4ue{>Wt~E8o>&dQr(AN7mjqyF* zG}H6J>_(o~&YE>i%C}}ueui?3BJtd)HCT=ZKY^=X?&_3vqQY<*L5FI|y_#cZ<(2sl zh<d$9*A=faE#;J>QoJuEBd({u^z!n|_3e#bmJXk+rln<p&?_${-r8WRZh2fT!mP|5 ztvnwCPj#dWzHF=gcB@W(*=}2`lei#exxv%f>E@o2#yfS`KCzHY9f#$CWhxe=Hx^15 zjb*EgS*;Npvc+uF3$l{A)pe~Td;IAgpL|uxaKLU5F5PIMuMRS7o@oz=QQF+eCVU-{ z8eAQ~DAWX5#tE3*yKo88fDjFS1!2Etl#C|_dIvd*;8uYSb@B$p+!AtEs_GxXFW_xS z^X)cyAH;JRH0@qI$mEfJxA1uVTsXVK?67JJe2WZRcAp@H;ADwbQtw=q2ik^XXZAv$ z`gE!8H13V;4Q)9RB%&?fuyqPm=o*XoWq?}9!?Kv<${44w&i2N8i(j?8N5kxP+}E1G z4AA)6Lw#>{01TgNWB^W0!$75mF!a)-k%u3~c-gH5B0zKVnA{zKZO`-*HZWTn9btAf zrIvz6jknlY0XY?|GD*DZ3q1U}6MB^pdN$|2T}Rde=lnsZwo`JNLO0i=Xgy`NA*fZ_ z{&_jz7mVE~1CT-H&7!Vdkhv36h)?+evG|!JHn5Z*PE3GeU32ggv(*R1cx7LvW%v@> zYZWsVAmG04i2h9KID~4IuQ6M7mz(dxE761$hn9^)Zo^Shf|`EwJ%mO%Qqa}cCJhDK z!#}(j(Wx2w19HK2ew0KeS-)0Ttv>AqzvT^b9b?Yml!)!<?@KdJ_tzW!@SZ;)oV3`; z!${=P;D_(#$OR03beT~M@Y<tyDYd`L$tDpI$OfB=CG<%3VOx?3>a)MwxFF#LsBwSs z1Hy|%RP`h0sqBEuLA$ScJP(wXOR>-ZXU|Dv4_p~<QYRUjf?Tdw^J(i`q!)bR&rUB9 zz~@)SkSjoseG1OhgLp2|O(2(1;I@FW_OYL3?FGa{khHiVM+szhuOIn+*1>pV4FE43 zw^e^Y$`CWXL`BigZ)i*O{*B(3AWWkz3MWb$jovtfAv-id{^V-n&m1GIaN!#CSFk|r zeNltRZlGUhmcy`Z!+)*sUz2<E|5y0`Usm`(KHx0m-{61hT~IKee|-7WJLCfd{5wSw z318GUNRqt@oK6HGPX&TSmxvV~oap`m@rEg7FN@PidyBg#IJWa!leMkAK=qBpIsPv2 zKZiPWRsv=a2Hl%tnMi~Zj{)bkaU}%s6}TSq6~eS65+8%cA&?7-!ot$SEUOd<((`g8 zhPn@bn<StAAL8DTY=|TL3;igO%o6;R&#KuzQJ^8pwm@KP@{)o2smm)yaozYik{r0+ z7g_E1o#@^D8VT(5GIFC1S}h8Qhns&ud`783a;Ptd#YlRHEQf!y;(SeL@=-pPLo%>d z(;s8@T5W&>FLw<(3IB@7Oh3o>`wP=eVoFa;j!&`n^Yl<NhWX2MviYb2^kw9yOTff+ zNfk$|{_Pc|*I-(u=)rg8Wp&CHQP-m~AC-1Hr~P^ro@pkqj)u{PVA+gX$uq)sPk=k0 z{1|#8Bzja~IHNYg<}rt^((%{D5VDba`iKpZEC+Z;H3I0INvs7MZJ!Fu;d;#P(H(U( z$r1nWH;Uk!T2B{QQ)R<DgW0^F@3KA($u?O-6TI3<GbEiO06h9zyZKMA;zyeelMOL} zoI|3AUnD#w+_Yuxx5x3i)xA>GdG*BeSjcitKI(opeMq+WP)r>{F>wsl|29KvFfrC7 zaagR*s(=6mR0OX{lWFH<cx+~wXm?w1-IbMD%8YsmrtFEx^1Qci+foricXTz69=+s7 z##y<Jo+&_9S5Ee62(D$%T_5Rw-C{U#MOJRpn0%?f95Xc91r$RFC_=83=EZ%x-%}nU zvFni-)wr7+cd)mSJLcCdBGXu~Jd5Z_M&TqowVcZ9>eVEyir#CWWWXMCoSB#{LpH~9 zfgnHF$ocJQQ8{+ywbf`b!DOb8!NfBw^7D9qxXOT|1F5v^>Pd!$sg%%2IsEfO4c~q_ z+0AB;6G$cv=h->u-PfyYE{7h`H(so<b%rzAep=mNwY-1EGcq~g@ji!Z;{~8VcH~C& zb^)@YoY@y?cVq9X`{BBWtJCMI_fK7ywfs<OC_2e^*nu)fI}_1p<$MEcodKEKI3s!7 zwKsFJXIc{1;!EGc6}&QSM-u%?C%+iCt*|>c^Ojg=!4xc9SzmHrd2!q~iS!A&X##pa z0@uO{L+LF^%p_gF53IEKGM0qiqelhUrPl>&RlX3tYtJD8)B03>HuC~yib3orI`7_V z&>ma9&!4%KMBr-z9n*Vu7=*)8#+L6D59g00&IdeZBI8bpsB6|W9c@~624h9x_9-L5 z>rqR{D)+S{EOY`o_kOVrN%xJc8KAUdBXz$1>8c(HCq53a^LH%r3(-|;aJ1CFai_dt zsq%IdL=o%(Ncx>BkaSo8XGFGtXW3~#NNmYRsb8|mxoIFkwL>Sa5x+^&RTAi0%5&jv zy+s9c3)77+tirfW#JJm4P27O5b+eFOfFxFoYZCUpSWbo-J2AcOv#~-?pJT`(pVtS> zial})zM}V3(dze#f&Si<5Fnpej=7?CK(Konb>=2*Jk0wgnT#Xcgm8M$n*&F-%ZQ7} z%=f<ESApsm*l?*|yR8?pi(Fmd*>RvS9%m02nRW{~Q4^{u)Fwa0KiFX1WN!+M^R@tI zoWtQ`^rvA;2tf@Wvx(AAXn~(;yt0zYFvMAfuqm#fFhodY`IVK1r_$(g8=Q~hqSKZ2 zcYc_o(r_WPTn$>kL5M`Keg0<gIx)KNoQIBI`beF#z<0;@iRzP`E2@RPMu23*YV##2 zl4}-Cf_Q-QK2Gdh_GZkidajv(KMJ&rn$3!P^2}zMO=?m0#48Qkuh7|Y<YSft>5X7G z-o%!L@U+MSx%-J&Y&miz#9=%idpp-W&Vh0H7&9eNykK7_ts7rVl3zU-J%{WqCPX6% zLtF$As~6C3>m(-ROlAvMa_=%pbmdJf-`$bt(3@IVBuN_vrbXd!2mt#2Zo(~ar5XSm zRz&}Q{jej9<j{)TI<iy52vBnPK0Dxc$r&NOmOF|Ul*gxd<)YS9XKwU0lHrUUD2m=- zIUXr(lG4L@gqQBtv*`(6@4@CYQDbbyF>A`3d$SfBYhpN>Z7pJf%n_8a+T44S#la1J z*EzBLq%l<m*3f${*HFA}H?G}mzTPB=r#RH|9h7blb48fIcSCSfLt1#URv1;gGj?TE zH<5`<GoA-xqt3*B$JIXXQ^9q4u}<HSv`W;P_AGiFg|!OwzHxZZ`zByXlDo1ZJ|Zq| zD$*FjV156<;_jS6EbrAE2senqQg?KO9*_>U_Q2hx>44?-PV!5l4!V5L2fd|%w3=9f z9=dnsCICX1-dS=Yvqm$L0Kw6MTNPr8KtAITNaYI}0S}rHvl}jofeqYlKe0jYX<v1y zbizwjdkWMk-`k8Tj&xtwnd+a#wr*hv;tp#se?XK>aC|=?X9{lvL>blxr9|2k1Ke)+ zJfPCsfLcQt)$)Og?Dy%j8u=R#uL<w9n@%y0olOcDs;|>+nlb)NenIY@u@JJp{!ld! z+``BLOQpyTFdWc*$NQxD-9ge@_|kIZ8RS^~hxLWg-Fm$13nwV{Kf2dO&L+uFff=}O zuKe6pxqd(v#9SSHM_DRuf|WrT533I_1d;5$9}p%Kve}3<jQ;M7JdfV205ukKm7{;z z19`6xA`rSbN>YZBY^4P8mc7T2{Zj;KAVZ~KU?OTpRnXJE7xfKVEgTQcy(KRwT!xXW z<1ROmVeWQY|DVtOgn(AT)_iCR9U0-3@Rm5;H!t$=i<*$L;6%2S`peAaDx1@`!K~TS zen7;SxOUxFBdtimxxRhA{Ha*MXwc?2Fn(bC?p%Pisn7jWrdOSGvjVvIUi4>lz65zS zr5GY@8Z)RCsVD*OJnRJD976+CipjmDm~gF<k|eA2UzDTuU+w?9&yC%in}Mwqax9GA z&~p5KkqvF0!n@qJ-ee)`BR*l~KGE;WD@&F;9s6S=-o67N*`vq<AaolRf)Y6J7g{~< zrHbGJTX@o1Npd(#RFUmynA~U{f_BSzvbW@z$<|#}aVlL!jU)1mN0gOH+o1bi4u`JL zc8w15-L!K`8aeRZadnC9$_2#k*SM<s$sHvA0Z?QH%Wf11`Z~c$#(JXxKOknst1A-z zgo}p?VVxQqP%9r)`uE{*4_9Y732@4VL3f&gYbW~OgTQH|%h}LxD#Q%Hki-mbUjjb^ z%RCwf7tq#7f)cRwE*1R2e+x+a)NUs1s#b0SHsK@Qx9d0IYsXkOH^M}TD&~%daw;W$ z0n0oZulsF<@8<eR@h}#gxT_?oJ;PE3eMz{P;qByb8g8h#H%{v(Ba&s?KW?J*Bp$#} z6#j)nC+@z9O60-DbB^CV8+HRm_N(cNw7zXg@tT#Koj_&XWOB3ghlfsa&p*!kL@zF) zZ^RKtX$nTO3l6_+ps0z@3z2=|4u{wZnHvblOpMq_?!}vQK{=j^N2C~i1L_PraA}0+ z?L>F@JfdX34D)aIPS?b4Vrup~RSPqx=<X{FY>FL{R{+<R@!s##E2f!ci>dmc8njp` z{m1Q7)jV@KezatAQvXv_J8yZt;OQeBob{*wY|3JN6#DDLbV2?)ev5cRAZy6q7hwMJ zb7lHb@47}0E7j}2AHH0YXN3Qrz(0>qt1q^RuGwMY)e@yyQ7!pbMIPjmy|Vq|VD4Cf zZ_(C)a-cwxW&S@doh7bQa(mjt?C%HHQmu`zb+FNqpFToVc=XTiD-h@3H+pW;hY|EQ z1_>h0r0~*_(Akc+{RM^-y045r4aDoj&cuD7BQz1fzV%zY&Hrq?@{jS$2=~ral^`Ge zfMj_pH1zVN)V7K2vvk%j{}KCqCj8rl(fXz3dP8oq#Lb0@1KI5<+o;QI)**qh4`@C~ z5-Asq;J;j#<+MNBuE;YL|DINUA>06v!dFTAbgGH0jnRuMHy=gHBVr3FPXqV)DJ572 z-zem%ez{edznu)X3QclW)DnG4A%PYqF3j%uxtOhNGw&pO+Q&ML-`XX@NH^W#J8Qu4 zMg*px+xo*T3mCChD0tAB9@M6|VT(*7C+un*e$ymd0Zo7j0ibp++fB}!WqS;|kzpKA zf3`P&Qu@y4v&rXcPdwx9*Ep1ICu|}Q=lgfPBKLtGwbzk;4)qa)A>kl=*;C0U__3hm z+j7ix?e{h2FGni8@zBLGB<9vL7Gn&EYpzosd_|_X{CfTmNZ2r{)<5I^jG_}P*;)Rw zjy9>+5fnDDkoHA=Qs+n>P~w&~+5e}isqu{73(wCV(z&n0!?uk`e@#}N@()+5GIJ3? zJhCyQ1L`Dfn?Z$B)OGW(#iyOT`p9_{psRZ<+u-Ys7^Sgw=;BLof8=~7;NecX4Q?(Q zKOnbFQXI#R3AY!>Z{6w4*yq1aexeTG5&NrYdwuETL+(i2k|5E^VczENw|nC%$~mIR zasQs$^ZGA+<Y)f-2z0-kD&3F7zupZ|Q=Le4l#G|yL@*sXB5<kquVFHKUy{7Ih~K%% z!bib5EC%oqlW?8<x_RM_{7D%{5uVr?|4(ADUoRqmwy63eeCt>wahK%U`RnO<o8|n{ zqBeZTZzKgs%7Xf~5UaoRt@XEjE*<FsE-^G6xQo!C5e|EgZbPq6hSb-N>2r9lBN+Y| zp>Tr?SqOj|S7hPCzjcFfZnAw4Kl54K0>*&vHH3V#e&@M~>;-G8(VzKm#n3ehgJVI0 zSOs>!*rNQ_f^r)M)(4B-+Wu0qE3f~ys6H~@J#e<nOF58mB*nbHN3h)pG>ezDB##!? zJ?o_Z;2Z_S?UJ_4UuG5gw^o3+v+ME$5;bQ4Fd~OJN}}Qp?;P?mW?zOS1blVB5<`^K zFroag5o}6_hvR5is6EQ>n7~wGRE8?n)LUrmcK51iX`IA|;%Q=Rd*EFLW`flZ;;&9W zJcw-bQJpCcYrKvx$I6w@pr6qsY6N?$B6B^w^hX-hu=x|+rsIgfIIGkNg~l4hDHR!e zoN=@5?Yp{cC!}bg(iICzjHu3W$Ex^g5^Buii=jc}nXYsBw=Ra;TYVl^k%?EUq=|O8 zGhw(?58FT27>kz$rSy?s@(yPgs=K_ff_QbgR{rEWX=8nORiiXdIyTp;geSqzocUVL z4f8L9;vN#nyx4BuwFe^i<$|fc#V_tU^*2!DjF}SD@s62DGY>>-<g6OQ?AJHgu^*6% z9VYl4AMv~P(8{$W%eDBh=z?!i`{xQT?vox%VI403#;N3@l-(68hqiW0wb+3Vy18pY zE{s;pO12?{BCW+~jG4-m1A^@XKxcH&>mja6m->QY=@Ql>v6mYE(zt2vCfiEzD0E)L z71-^>{;1X8)<)gFqWSrtvMcM}%{M`;9x{E$d3k`N3i4o6fiLczDEDji9~s7LljI$d z4VVL}Lf-DpW`1dYWxnH&t8^nMr^S$eua6@;f3{p3Rr)nh4;~mYJ`otQB!{9`BBbSQ z+OI7u^S4zqq#i%qgWe%k_KnKUq(4BU$vpma&tXm$;q`ljm^tV^S>(Yw`qN0-U&}`i z9y(?@aO+l6Z!+q%(^GoLLJsQhRcHOnqL26fQNLVENzuyxbcmAuao(9nB_CLLipqZv zaUvV|j1!Rudr0E3q13;`sAVhMGVb%SAW!-Eha+`_ch4lB{)@06og0Jel-W;^za_aI z?co-Q5!Bc?4e|Le+e+x4UD5IrTSVmYot7@1w|aQelv2#-w|vh2qbhm6@o)Wzjd<7$ z2wXV1@T5S(LVt!hCr>Z>UzVi<K#zWxAsd+r>!oQ0gY91a2(L)b*Mi9MNn|gG1~jTc zgzG4eg3I41fehRo3j}|CVUOp&EH}6q{$?zkV6~x1ep5l@Z?SEI^Cz_fKz64gUASVx zi;JX2;6UB9UC7VDJ-=w9^6J%MueSgE9EI`d?|q)`AGOB0zqT203%wdGU{A*p9w+Zz ze)h;#B4j1!ziehy|7>ICc92{um*f<DHQH_xLaALbO8d*o(vR2wYYvgiQDo`Qy)^z- zP2R7BB6(V2A2m9;cK`&B0i>S+Nk7wvMo_@HpBKjLbR$4c&yx4KyX9%*B*VxB<6)On zAi78?(0nil;B>Vy%hnw`qCfMAq}a!e=7BK()4Xg+1{|o&@u1gPKl)XX{j<}<o9^_z zEZZIEYzw{Om*{yRkXxK|ph*t<`vI2-^2+`8PRNC{9qQIm8!YAi(MjMgL6`YL(~oAC zf-%1!SHLw(I^@qkAnRLy%^uRRBi3Y$Y;Q^1NLw^ndjey@;kXVL_xs4W0fp{bg|K3z z9XNFP6%4_D)V>YQ2H9$&BengrvuWDKX+K|A{0C%RaI2`SRuCxk69_P@Bm&PE^7&_c z;N9lUt8I^2_U(wr?H&QZXj6&c0T5;rbb4VO1PIW~V?M^gE{0%7@V6hKjX=&#Pk=-5 z)-$P25T6ihpab`5aGDw$?T0Lv`KUQH0#EQ2&_s~{q19Cf0-l(S6;=;)jv<ikht%sd zD1e1|BW;g-`_hp%z&m_IJPAC20eP^V_8I0HvyAW`M9#B0fbj?SL)LS^tBZn1fJSsD z9CivxxOaoVNi)Q3(Az<%C%$F<fIKn+gY(nw!>CNEz?)tPbvT$ocRmvUKLT^Vq)E<! z-T29440d)vWXz}9ir!+3A-4Psmso;KGU$s_^p9(xTR<P*uGWV9GoAu@Jpb2IPEbY! z3mJh^_~H+U$|B+|ZuB7EVK40fc0>L+0?!|nFGoozfqvFgK;Q*Qw|ap%D8c&;{r&Uf zEEg{l{T+KZi%EWb;YIB&n60B=i*`kRXEk<(P|L*u5vV#G-~s=y&OiRrBzOMXh)!ta z79An&AB-Z6$%xxK>BoNRu4dpAsiSI<1cY_EG-lbhDhi0;Z~kKlF#Z1v(qm;dl^Al8 zDJAJeC3pmar3t!qI)>EvpTFh7s0EZv(f3EWz}j1_MC&t4AI76$0FJaKOZ_<m^CtFi zy?ZSCfC~D;s22Er0$@@02a+lVddU!Qz4X%pGO*Fe5__rDv;+F#gFnfTA&%cco}WQK zFi`;nXekM{<BZd5!0w+MKnebZ$dv^^{cO?-c>?Z;f3+?gb+ogx9_cSPY*Ut3=9a>y z?J@}NZ-<hIA&^<ViazK(1u$=8e~n)s&+pVH1&JA817`cFH}i_*S^ObxqOeoDE0}#k z0*OQ~H{}Ib38KNJwOO8)00*i7Yr6<x;5v+d$X!$sm$=Lk)m1Web$(|@EaTTx!C+ax zJ0KP!OU97B$?&~ZJ<8Crf^{=hMWLg9QFIfjJ~?EWZ)-HFO+hZ`JbG`l|JS$>%s+Y} zPHlQh#Pn4AbyA<`=jx8|S@BvGhi@;^5)UsO`S{1a0#o}nhaTJ=EkhelBmEJH?MwDy zc9M%V=@hnneuu6b1d=Mqr=?)Ae-FUG4&=sc`Z@HU$&H5e)U7QC73X_z)QJ!}SMSO& z4-XRqx=7wwkY4-nnWW0^1jm)CLy82#ek;gXZx#O9(=U+iQW-|YaQ@cWmm!c+g(qph z#>iY7MQ`te_N}5vrbdrD0@~*b$VOz!jlVw@8*8$#>|+zlx)V#sDFnP=S?a0ZgGT-> zLd|2+EQIH4=#`*+*LDO<;`;I^)$J$W@_A0@%|qnkV1GaE=O`RtzWWqtqBDF!$M?4) zO(X)$LRRi77d<p!EVsxqPHlYmOiG0hkY@e;CM;%UKr)i(jW6kE(~cqA!!SD&2d5{B z99maL++Ss9UXE>zX1j4yN-i$yx5n02&a^{u8+N2aB&$C3*LxSHk;izlV>kCRblrmG z9=q<OpQZnovCbiy(za-!JFV!~MR{d1x|iG%VMz%3mTBAY{%{l{pzio%wB>{#^gOvU zh#EbtW%*@6!`(-**g4n>x<z+I^IE20@|R!wPPqPeNs?28?edc%hE$K*rk>I@nozyF z`p%^?+`#PNN%@nKV(mV4dn6=4y3hg7Zq)sY<(yC>RidXw$JZa0l?&yHM_tf)wEr;W zmlcAQ@JHBM2mMR1MXLIBwSl@dAq;`K2CsSZUqQMdZaV+A^1O|}%IknmY7md<*}10D z2QZ{COa0Ved{^Cks)jR+)NJtsBIk(2l*%)5xcrA={V{syKO1+Y+^_G9e?UT~RyW>8 z^nX?{>(KA%Q`eBuBv<_xGp+wkRbNeDR9i7V)BJVqOm+8u>F7xH?}vf`|Jc~62Yi05 zlyYwvqg$eWeE+d~mRfZ}6?5bf++?O9vwv(VN)yG%#Vz<D-kPicCqZ~t1f7Bdo_8ig zQ|6k~IsE{J;MD)8w(kz4`rrRQMpRacY)4UwknDL5eGn22BeSS%vSl67ut!2hsElM~ z9Gg>QC3}y;vG?ZSoYU{6d#`hR?)`lK`~CNRm-BwD=j%Bh&-It78+SezHX}bbgXq!| zSG+gM=(j;lw+iiT@$v7e>n-rUlCkKCVdDGld%`uzg0zRRhH#SM2c*(Y>GnrhWD-rs z=+nSmM)E<WF8mX~F)ebJ4@M-c%9p#7sC0g=h)#KV@SV~i{y0XRNBfshq%#XgOgM*% z>1P~J@SK+vxrDT+h+$2E)X!KK^5i$$q9lzSMkD`O%LT%HggkNwp$oSVeE>&j*D2<Y zTXm{RddKb>W_lZP&P+x@CLxKRpXlcIQifGe=JfzuRKJ$M?`$zLIEh7=4Q}aYg4aj_ z)HB_JEctx}>OZXICV^_F|5mi$3{xOl*mc_AFM8obQg9cU?Id%ZhzBH;?YDkS7}0oT zczt;Oa;<|%V+fn0%t^ZMo~%Hx`kzCNiz0URBUJjnBW4sUf-*Dp2kSBn)ftPdn#rOc z!jH;miZu}LtEVPrBN$(nx0cB#bMSZpk}Cu_ISbGqa-#=znSeG)J&fp6gJdWHZRhS7 zP%iWKd;IE0#}b}jLv$s^!!djQ_%fhDo^$#WAzuockHb5Yyad0aSbhqe2Iz5I9sW_d z^z^<T7s>=(5?UAQXeS{qYh!(@01FINuG>IC)7@>S<OM%IG6K+oMynAV(4njgb46-V zYpf+e`s}hU%s@Uafe&|@>`sg{c1LrJU_F3bGECTEg^bPs-Ic!z{9(BJZ^$t8dnw;C zklf?HVB3^yDU|!+_;o-fSYzGSCF?(FS0V6Mbzz(RJ!%mCoRwJYQ*L0Wpx!!a_hQuX zaG>{8kF<i65%AHe%6-w(j_8BVS)VM%6215y|Ft5qJCwYwyW2}+@6Lv^ZQIMjS%8+; zK$GFGH(8?qEs2}4p^ni#m}WeDWNQEsnS0Ckc-0tchZgXsO3({j%(E7;#tx<pX3Y%; zG4nU!C+485V=&xfU~BeK8TGyc<^j+X`+zaguJO1CvajWiT*YT1elpD2z~*9c9XC=) zOW!)-uS%F~{zScX?IEgaHba`T-^jx4Ic$QGX%Fb(?^rvtM~)*JX@#~EenS++(%?r9 zxdp_!bVbGyJNuy)hOjL&ICBxusO&LJ%fq-+yM0#;x1ajp+B#r4&Y}<<%@Cky(Zc2d ze9W!iLombJDf#!$5oCH1%7c|I6TSEzg1xOg4uRlgFTnOe{<Id?CHa%nlX7H#Ljw+( z#L|7(=S!fM$8Sj7r*6n$Oxj_y-`xNYzl`_-DzU*?8NdphI3<7`k!Z5H1lu^DZ8h*W z+?j-^z?LqI=w;ua1@x>!3>6z`62HNZSh(xrueN(bLBxku+hK^9<2l%U#!Zu*BR>&+ zMaiH}8fQi5A?TNCeSWY~ME0hMq_!yoL=w`47&{9<bS^Mk;Csw*1El8&4qqAX!T|xE z%4fmg!l(G-uVVRAx}2+Iv_1!IZFTU({PmN&*s;Ehk6^4)V!3yPaAamUM143$Wy55b zqG9(pB-9WDfrYy6&a0rr^&iwT`}uL-h?Dc^fnly8^LCHICSWxggw&WLBZPlOR!Rrv z4mFAA`niT~eSqB$OVpJj&YXc*AZlRm0gZ~o`mp=yRS2d1fE+{~rsw+wGOBOa;u+}G zQ!hMCb!5+YOj!j~`WhwRl~Dj<8qb&qxXA{%1i7Ku=T6QfZupY|)_6a<9lDjQa+<~7 zLd2H9t=pmoR5m_w9CVDqL|Hd*HV~2<K7-nz3E%wFcm&#km|=s?<Ha0<AV0b{T3|Q2 zCad#{^wI;J*n<=O<EMcqkZ6Zzv0w&V2FbhAI3<TeBWDa*msj@D*9xo`$UJ|@<#=pD z$6MVDoCk0tf@mRUl0LA6e_SzXGGYJAGF@<{Qu?B($Dh8DJpGbeU&<ej!9?NK|FkgS z(eJ~NL)V~VD%gX^J0DYMD{gca&F?Yi*<b2ZeF*QAF~8((WlwaHf-k|uJ?(eVd_N(8 ze-ie)_k4x7+lM(Cv-BJHpWmTp-5?K1LUs}Bw(t|gyAO)z5l%ua2r?@x$L_IM*p^k# z>+Jopt=~)%T?89D*w?FHp{wH(I9I%1@eJ`Q3%!)HQtD34%nAI+{_8m`fZ8mtw<L?8 z;lf#9E0G`$4ODPLJckk<Z-EH1BC6)MR+xdgf;jYAGdN`C>F^v|B6_l>B+_$zfmuh` zc&qBn^nS~Duad3PSqvSyx0G5H8lk;NK7z9AE0s(j<8Z=b=1n-Oc>Gk3lN)2@c5V|- zP;M%%g5=q97||v>O50<f0XZ^Xju1BLIlRvuAiWkJ3~qftFf~`RUTaaZ;<<WneizvD zJqEdVi+ERW{R?eqC%#bSY&5(Y)dfLoOHDj6dbQUU6Z5&F3`2<{I3e}~BKrF!_IA>$ z>=Zlwxy$@=P0;cBDhg#y6OT+#$Kx~-fNYf5mzX=%0)UGgM0W}jpE+ax*o<kP0Oz!B zh~`;U<lQ}LvM^xYfBG9@vCnZ1?(u)Emx3<fOS{?gqQ?S1(w-&2f|(mkGPCmt8;m4$ zaXPf}Ja?a^af2#rIi0JridViu(-qiPH^l<=@l;^Gh2VCPVe23OFee=HfAJH3-L7os zDrp0pe2;1TW$|lejZI`btX~f?$W&tW7|wKvvBoqT^w{N{MV3}Q3RBhQxkbr$<7oC^ zvKp8`S_#gJ7ys-6S<e5t_#?z*;v|6Pun;EG@*<nzFZhG2v>$0BY{X%r<M0lPOgA35 z`o!fy_@#XQ#%ZZX+&tYVA};0=NsPN3zTBsgAAikCzm8#b`5MGPRUkHVg#?x<*4=jo zjoP8p0BxYiwa5{K+jaP&Nt@6q(3U;u(=Sqda{5-#a<?E!1Lp)#dx=Q?_Tj!&T89?; z$UPj-!+)%!VF26t>rorJUbt`0+UK*Z%eH_|9`Nn7Q<xCA*kOi7(?(~cne(eEJ%=~> z<Tpd^4eFyT<8#(#czPTY{%JlQHLmA#4D3Il(beI5UYwsXV5x6Yvg=Y%C+g{Xtx8#s zZ1<EtG8rAd0~z)PD$-Sb$TW<YxgUB-Q-WCPS?i}wZivT9gse96r3S!jFG_N+<pvX` zV3-sR1kyqCEI2#RF}<6CcFMNX?b4$%W^@)URvP`_=h+uFs>ACy0ENJm@BoNe{|(83 zv%fvaI0f+Q%F7wlFhGP5n_1%PCa6w9lk0{3XP+%<G)IN!K%BdE!SarU<<B$WRsqR_ zYO@?>y+V8A0P2Dt+lL{jOK?v5&3TV7^edW*7@*m^f2b=t`8>#kN5y7OogVusqn_@m zF&oA+r`9&3O*Up*m?=b+_eZJZSG2F}t8z`U-;jnx04sMR`0@d#@(IQP;08!P{Y<MU z)N><&q6pIO60o>+_Kg(U7eSM-G2vc0Q=s?4b~g|;X4xKfz~O_~oFN4vVuXy>K83U& zzxd4kbs*VXSDqk*&gUX(pg`(7n(XcThV-V;-avYBfE^6qdoa=o7||GA2cir>IDmuR zVGVn0J(hJlb2g|(>nqHC=mibLw!<(3dtSOB+hn@|)B_F2Tz3iALoJ8ntANhwkB67Q zHrsZC(DPQ!#?`%cQR-Fwrf(L#v;4!Vtkv-+a7=sqI9nSY32}502*>&WrPWAxr%&_H zawD+<sUX4dTY-J3daemKcO;y(h_Ls2U}k`^5e_1SHupe0&#M!iihk3W2IqrQ(&}aP z<AE~qkjV?Vg~W4!5)S+$X)8fEJ2543b&DosbP0$*(GqXm7QAsp<!=KX#?jq~cBIG| zcctr_Yt|<#wR#<%Q*8I{J(f(NeH1hgBih-Uht})MMGU!5Bh_P9vI8wseNSrt`epvZ zDG{NT^|#?aS2_V3V{2r&WQ|dUXvI1knRG$Tby?H_@Qah!$|L}UOYQP!A0m1c?3rDm z?Q;O~Nyb@0npVuQ&)aYg_EY?yvNhCdhHAw}2KDtn$3E8l#ZgQ78`5(ZT#PsKocV|m zD9!^iM}$dzMi3})Qy{FuJLl*5Xz$N;!nMx~+0En-$02p^%iAzlH%yk)fjJ1<?fx6- znQH*<5sJdOX-@H%XUBO7r``Q)JK|Ep*sa;v#zq##=>IHx|IFJdb(I{G2~!~^f08(f z-Ckgkby;Vb9JA=W5c$gRa}#bFT%B0r0|!JmWPw^cS`747D(t5`;+^<Wv3mML+Hh0) z;EvB7>RWQnQBS|5&?f!!H6uwP7S>f+qq<*EbXcPf(DNWT_dHqa<!qf!+a}}bt`Hsb zy0)iy4vZ(7p=-fB$>7P@`q>fQA0K$`0WZ_!-*Pq%P54%i;KWK%*26RiccfSSI>mV6 zIPfc7{pWpfYcQG1LH$C^8ZJ7s0x?vhTP5ZYNkQ#n(%dJ7SN!k0Pu!6aNEIUHsJ+S0 zhM)#b=Vq<`3aJs90@T2}dmJ+SzD$#F>7j)4fD98$Zv$89pGy_a@f!GA>H)g^$L=ii zn~Wb0lf9HQvH0dsJ2bpTLan~hGa+xgf+rDYA|>RN?>s>8L3#<JkNl1OxVU_QjllG~ z!B-meHiPjPKr_9iD`6qE4ysS4apr&+e5IuS&&yDfifBAPgs%e5ltRP0zJN`RD^nWM zL(OZWPVAmhykt+oy(MC_WLddaLBuU*!c6k+(M%$G-27mcde_~rL(Eo5uSL*p!G`wO z&4%{lkSUA*g8{+F0f@q<xr>4A9`CJlDo>lJJ{@NxnnG@uWcI}0VOSN~u5C})d5DY4 zK^ID(L=vVoH}zU2nA~5NWlvrf#Xq?>(26(%XWwM(J#_g#9J&_|LE4aF0iq8;E$uPo zLABirqbpUPyG7H^syMK$(~cGSAyPgOpY_~4tPZ+HQo75Fe}N4A&ox~IVllG__h{Xu z!iZa||9*nZmLMIdP&0P~VtUiaocOvCb3-jk2|yW*Ap5EskgOu(u+DWnTj$0MRIB)| zY~zV0&gsVC58SW-ps5n1jq_IW>MYYf?tkl!>%pTIiE+Zp%dN*NZUGxt(aX#=+qX=l zEY9c-etb(Zo|$(g7d2J_l1pp%E_z)=Yj7I85txKMilHEhMwEkKDQHpnS8x6?pETP{ zcZZP$i84|a+Uqtl=B0T;dCsepiwdJq=yH3d{U}q^jYqidEUqgm_`dvI9X_AdLAvml zTNyP%Yz9VO44=frn%jK#pWjHKp&Kyy=8+yG*m<mNK&RI-Jz(Qf70n~}wtD@xP~?jq zm$=%?JEls^cT5zFzpjjLd39osjWy>8AT7_ARTT@XOB#~5@ml1bGQ_ZWkF_Wa8LV<d zrzg=ZEu|yk8d8kQQfO(*P$1TS7`h3fR;0J?PGflAyX!2g7g-`X6vn^l3LG<p<uCBp z|AEB*)r6CbHt0eM&B(sCQP;2+jBRmtX(i6UAtgrmdea_aYVq(4e0km`&=tThsj7jx zaF9A<*!H3l_6ZiaaOw2Ob}W712R4*%CRg$e{?7?2RYA&uC)Dn&PrM!Z?#o9A^RoI8 zqZ={af{b+Pa->(zNVO906<iyX=j<;%qq=iVvMmkrq=(UNUa@B(m$h}S=C8P;6lY($ zam(?YE~wNS)G3PKW0zr&r2OT3Hg{_TFE_rQ!pJw8MFb`KLIDOu$q4k@MyqLj1#70x z=DwQ<_y+pSv;kB_2<>XpH5e1xAyok$9cf6{K57*YymANtF&KhYU1~$bFAzckgq~Q{ zsQqRMY-xX2g21j&=dmCf+3-U`YhvGZb;pHv$Phyh@ycat5aJ-Lk3GvYU`~!BxN(q4 z<a!6-TvtCL8lC~A4_HDQrwj$$^j~7#fjVRez$pc>ns$=?g?Q8L0_Ny^I}-pIpG>xu zq<xQXLcxy;b^SK0AnsZ9m*s{B{aH){RFP(i?z7$K%JK@KmoTIp>S@vRN=D#@Wv*FK zbWE?cD{x3M?1!J0EOM+k-N4+<9Wt~yS@s#FBiwMNDfFdwn}e~f@g$mV(0pwBo7OHg z+>2uIp2_y92Cgf0_`bf`yYxOSyDDM6J@O|pzXrEDQaK+m@!EVQ^$fRybmL;ZZho?m zew1RGARf`L@px52aqM%(V7{yo`loq)eC<4I_t*rt6<-LS(7hv`LcSnQX_5D<@u{kI zCf%63%Zrtnx#HvYJS+0)r8MTF&zD~;4`YJA#pt-6LAf~bV>{^{&c{Q>tmF2f!23Xi zL-&O99(CJQAD`u<E$<XX$%8CKXI#%vjV|3B-F@T#FQ{l)8<o48w*6^+OTUrr0)=T` zO;YiIQd3Ww46$DI)L#wUO6)$CxBc$#yo5V7bZZ^4B1THBhGX0wN1Q`Os<PWDUM%m8 z`ZzdS7-tKmd1P`%wWi>Kd8e=JR#1sc%G{RjEj=SWwWzu?D$m{xAKm)M+PZ2gg3Nx( zFqZi4i+o(l(Rq|+seJSoU7zH~-WN#rTPdT(@^+{IYFP`i0<=H10$u)$XWlLbF=d5> zFcRUbhTg86r@<AbhOP+Vj<!?mBcALHp#T}?Wx{!e<Bnyq7JJ!)UrVCqhY>RxdH}6e z7&Y1P0L@$x3q5UpgqLoT_I+?Wa@=Hx95hN6!u$0!>)s}Q(;_((9#lAgwFb4u=|A%u zvP-5#d4C^u_9li`bH}y8)QtLYo~i(hj31jJbH>!8yAvK3C<1Tnr6&yx$t#KA9=AP1 zY!766qA+{0pt8^U#~Csw{HfsNot1F>o|v?|BaJOZjzDvLSLh@I=@F;sK?~>_#lG67 z=qs|{hN1}gerI9Jk;bum0vLCT<P*Qv&d2{{EumtI;`4Y^45B&MJFspaTC(RQ);?ud zaEG0|BG+;Y6N=XJ;&<Tn^<rWvL>Ai^wubICjdYh}AR(TUI9z(HnP8f?bOW_;>?>ti zzOc<Hk7<7&0iUk+p<%2j#;Yl9NDZ%(li7Mkwc+|lxvT~;V5!N&$lcX%_UUVgYlqs= zcb^uXuw&WP?Spb|z=Er#F!W=|m`5~P0zvxk%3t1i!xNT3K^i&Z6bXmQdR+rq&KAip z^smP+<%|XhE{qv<wqzJRsi4dxOVo`X>_>$Ti`1_+vpun7S1-+n^;Y@yp-UF?R!;p@ zT?A6#GSweC(JM#k6pN%v;ki70WOad+L%z5|5rzKgX@bc@&s$7|t2$k>XcXUhc3L1T zk@hu7Eyiq%7BhgZAn#uAlDTxbu_EG^biJM@890(}LId__x|%g;y}rQDqU(=KNXV2C zqgR7Ap}{cZcAY(=d+ubV7@7s3Kr90S0*jC3wH_anYw@sO__|uWJ^nN1!-_e&KU~W) zdtlKnHN@^A`w8y`Eeo>AwijStpiq1L9GdP$Jb8Rk2bY9!4Ao?wnUNdzO6($_l)v5q zD}_t9%%@)dbnKTAW?AboT`6&@$%|Xm4!fq6*7Z<i$)ZCBrtsG1E~F9Mpw^oYPVwg2 zQTC@;`PU?0y|h+z>tOzlgSD%4Ur_^#9%(uL&2L8^d*~oQ<0<rVnEo=B3(wd-2&!YY z1l+hrHJ>EY<#WaBKBi<<f9eNTyE^HvO~><3ZMKuq<m>em*0U!4PBpI3BR&+?s3M7g zMZaOAnr2fT<{#?YaL{k&BiS^J(~ERfs8-{ig}ewdsde(hNj_=+Xt}T1niz#e*z~UE z-h?iIDT|8Z%vQHYDWX<O;KjF}+>5KwYv6k}2DIFA#9OaS_~|?^>D?Qs)VX-?ABzIj zQ6$<SkZb)4^Fxe|<7gNBTU!USRCfbUV@0ou;JYMEJ69!|yCMg3=IkBC_?d0Zbg#@r za`TH{Nf)U|8h%uk!#CA%!*BU|K}n_cwG`oV-vlKpL&iSSsX;oSO!oGbvo0_y!y;uw zT=&Gg9Uo)wuh_Ykk@{fga!&)G18Um!U4El&RQ^G*{mBNeSPcH+>X8LaYwNM*(h0xo zq7Hwh>7AyQIE6KI&6c|XqqmL~FYcP@<Frl8?i5+O<~9uDvLO2uzpY-Dw5yscL{iOn zy}788NAPk+=lkB=Y!}Il;(*pjwO2Hijs|wjd#k%$21-4z`NiK}rmnm5S~lXb(zR;# z-jI5Vu8CWzc9$esW?LYRs1^S~MB7I4cH>97kR>j8c)sGPN%FF3#vYT|Z4aBNUrT3G zPXSFWPo@+&A_IX1(dsLX7?T8=aPm<Qyk4k+<z<4ck3n%;*0e#8nZ8;rYc(-TK_k{t z`wJ;2L<WJq=Bc@ZkHYUTegH(+$T@^B4Jv^%gFZw5891Y71eAgfCnwcbsPIfYm1O-c zR~=wAYar+ibWriV1hjVtV9(3b18C$?IOc{RV!8&lx6sSMK+;}olXO|L*iiUcjq8yc z3LH*ty~)6clFI=23?O^2AQM99N(wdXfOKy2hPaFU)!Wdvr!aVRHN;yUL~a>Nffah% zZx8Jphxi{bOHl;T;GbtwX#Hq3D)k!FN&^&Ao+PwSOt?<Z17w`e62wS#B1X=B#E9S( zr}3pF>x?~G6i_VJR`NQI7q@m1TDvlH)FmL7RoV9eH#J!jEXS@#h#vSYr$H=!9pnM= zIENQm1r5$XIhbx)yf>SSp?0UKN9ZRIcGaIaf`xd*3&7Ij?7|~b0R*OG2V~gTYR(Up z@24-guD+d$I#{4s@V~JEi$fv;^Jqlx=BFm-nLe@~4~}0xHqF?oYYT9(#<So6h1OE2 zM-DbqH`C|4G^8Et<mSSr!DD}~v6Ha|2<5h3q&&SBQ-_zs*mj@GTSe_3X+TcM8@h?b ztuobFru=LgHK9<p$+npox)fQ`CKHz30_WWOWECSVm>{2%IebZHYc=kCWcj|Jh#&Fw zxs311AGAWz$#W!l^9`dSGv`W3=^xWdX?Z&A_Jv!c*kzp@9#@~}1M%vrkz)o$501oN z%DkVP=IyX|1A`dX46A0u*l7+#-T4g(yk$V<L=h*c%Hf*ZlIqI73WrKzHE?kV3zO#_ z*W>YJqXBj{?~J+(Ew|+@LOdd*NGq$`u17V{7QS|lHfg%{&ZsWjq%D4P0)yJK^g6oo z6Ca7rk+}Kl`w}-xf-X`dTWU07MAMi*2c(`mVaTrb-2Mh-_A;<#@0eK=f#>>us%}}r zY?7rx9vidc{NyDt@n2o|HR)8z?JA-cUtO}Pow1Gs1#pEi+hblq)uJ7F0^Cl|lACGR zyqO)0->!;mRb$G~%cq8oW_-9~uYXp3qpv?WY72L7TC(l|(aeYt5q!rWMb3&fde~t^ zbBp_2&XBUi74NR(t=AC>+bMK0cvdVOCTg6wT=Ru7N0g3*A1<4TYLeC!?}gU}U#Pw4 z)1ADb26SxFBc3G-5@Ykpl<p%9#w^J=yJWr^pHHo@G<Q4Xp0Q6~?`~aBRdLS8qn%^D zmqiQPPlba}I#4I=nGdfQdlj+^$fc`$@&=6|F>`Cv9{zsr+n-Q$vP|Pb;nG7Gks6Ov zZ4T_`C!g_3YI8XyQU3Zg!i*QdYGZOT^$oFis^YB^B-IR#En*8k-tf5RmiG~6CPb@; zZv(o$PstwKdh3%A^4j`?S0SfPzRd>&|0EEm2HDAKfRTbeGb2Xw?5m-bTW;2@O_M-) zaQo4i5#7}4T3ptK3|*)RxhO2$hpj{>srLxe5arqPb98%o$v^s<8AyPmS|Lh#^<h~4 zeJ7b_icrh7ddQB?ci(AQGZx;#93wByZW~)c=N6`#ROG~cbSX08M6Ix$eQf%5^NbvW z-XDwEDz@ZSXawC?_OA)h3h}H`|9;<NSpJ00rG*8X+>K^+gDy)3e)}WeXeF9>6WQ0h zh8RfFQB1i=idWOOR??blwx3silj7P5_)3BJ$-SCsFMmbh()w&Ho-t`qecs8AaVRv0 zS;@|uR>K@*m;~)!iK%8Q4^w}#)kG~USkGzxhD6TId3IJ$_py7hKI(Ij_u26upKS{p zv9DNlB7DMNBybL+mZey4`42qX5}#byqJ-bN#+~8u?vYRKOzB&)LB7eg{jmNa$mR8= zd(@<BSueQzsKV<bX5z~ier8;ktx@!P`HIaF=bp*E@(al`HQX;9?V|gL`M6$)69xoL z9Ad@3n8C>#9rqF)wp&~ziY27I>Zv{kedc9ZZWS?h2D}=?nb;q2rT=2P5$?t#IyXP5 z{)Zu@l{L((9B@~D&1*m{)+oVwW~?zj^1V!~!`{@$X&TGG*S$CreV<*1{Zw+oe%Qy$ zAfV98Np!$A=;1)y|7VHzu0WG1V=KD$jlRev5HVzl>-bF>0{i9lLrgFN-5!cNVr_bO z;OmKW6c@xtP<yJ=2sT$7>=%xo*s%oKo*iiFz*+Ji<@_b626DorB>2s2EPa4BWjqJ1 zDtCwzeiMi@BDt0^n!Izo2|#=R#8uRvyFf;FFeQdp7LPHuv`Fejez>GEGo@QI&f2vQ z3$QsZw($3e8EZHT;-5ygS3zfPs#3h!3IKJI-hU0dBf)|LKKlP?Tsr#+wEyHxD)r)U za@P3%OPT!T<0G0ZQ{fl|5Zg4p3)`D$r{FknBxNHA|K2@|mhq;ih!Uu%fQyS{GK-S* z&v1&Y!k&-65}?$JA9x6@yd%rnT3VX4<W^P|oup#hy5Oj~nN5ee0kneY?<RXQU|GlN zlCe7gK?i9WIk~fa9;hJG&V{q<yrmb}RTJ&ZzA(;7C%xU%$2Xnc(y-665<l%0aqOmT ze>3SREVa~e>lWH%Cp6pZzHGtjRs}YZx8HTEmAsi&rng2`mtSIq>7L7<!PwteWe{Ht z=(K*mGXVcGe3UEM17xt82@T4iryHsq_rCmwFv`kNq@{TW#x2J;TlsfcyV~^R4T#B} zNx`aP-md5>mxWz;*!^ISlmbthc8#;N#X(*OSMGHm_Hw$tngzqJwz5;InB&Co<U!kG z2$}rmIw-M+bwg{u;5=u-pg*_%R%40gOGV&HU16(JpD4+Imj=cN4gSVhpt4=8<@A_r z*-+E#ztpakjrxy(k`es|W99*(Z45uXbXGZD$LQNeM`hnKJY#Y>Db@TlX&H_if85qZ zFqs1t>T~+;-0k|5Cp$Nz=KW~-V=)yVo1SDf_FE1;@H5R=f3PeFEvT~?_srW?T>!?w z60G25P!1M!c5O(yQ1mruvZUVojxgDdZW1N|fBbeX5J{+x*fH90E@b7aGu&#9LwX@e za#<|^%`h1>)4`}_&goV|SFjR7ZltMxONtN{Iq|;4`CshSeJ&MMRt6s<bC--C!84BE z4Q!Z)b4-I4o9_Nw9iV$Qj&G>Ob@0JD19C09>ES@drRlI*u`OsF>bWubDrGH>ceK_^ z1KDm{)EL!*Jb8ZB?;}-&CYcm0)XRKN7BjUy$`tZoH77mrVdl>SCkCkHCGxv-$}+vM zZzJsP!F71KZutwCqzP4lh0?XNy!8GZ%AV9(ls{o))l3-Zm!y;3KFkWMf<s0{JrXv^ zE9WPMOKnp)y{*UXgE`5oG4`uuw^yETC~4$09}R?hTyaeGVQg_fHEuiN3tD`mac6sP z%Y~qoZu3&h_%A3q!#Ge@%<_`%ek0#Xs%h1!KIULE^^b{6J#A0i)gqHsaC3X;ozZfi zb0;i{R9PhKuK4sytM#jESf$iCO0~)^P!H5zb|~;{6yM|v5=vA_XRZPE25VRvNpY9! zjTmctvPK2%Gmn|Wu;xLpmiCOQ!nkFN@y@pNPqdGYOeV*2X_1%5WTCB_#k(&R1=0&F zbN`|q_hbwY84r8Cr(yQ3xVKom(6X>$D^aZIv-FZFiremIyEbo0{DqLyM{cri7?!&7 z3Wb=>>VR-S7iPP6-BWt&Hm~@PuCFUMIFQM$!#M^)7xwr7e}L3IbFvA%!u81O;b*Vb zs{Zw)p2$yggHfXT8Zpt2PhR}0u^i)=*C;u^&aNxsuv##<c1=)lBO&k{GCKYk>&-@9 z9&zao%KEqB0}KsgJL=ySCxqX4rIb1)-;RW{RSOu|8&|~|mUrr(zZqDZ{Msyx(%xfD z=HIbM^OcBDMGcOP;?Hj#O{}@|&Lr?~@+ZnumnZI^w=P4cAerN$AiC2I=ma1t4b}n7 zi}Qz=7Lm{Menz0}hBoV+;?_mGeNM%5nC}b|TP&cTqGTbkk1isX-`&(qRYkwV_m{+( z>ar<HHZhMQA@^<?B(M1Y1R%`@V!H`=8az=u_;8SbOkz%mM4Bh1dcESoCX*&2n&EDN zfjBR3Wb7M4z)vH83(Qo}SAw4qiUhbHfeSwT7Ce6L#GwDN5}ClL#OYb!4)+Ke-nRyp z@d)5asMdfIhEF-_#R7Obu&@4PC}k!2Yaov0_t-r=naOGVjaf==XZH?jCGjqp?Q0ZB zN2d9nh8Ef(0iP>{y#YRtga1iIoKVPn*D>~V+_IjmjGWqO2;iubjKEMlDmMbmF#w); z#e?pifW0Ko?B_zmSq_CFIYnaB&|mA;e{mnxd~@gGgpeeTuK~+@8nHepw4ax37X*O2 zXXrM(7r=U}LA=$$$SJh0|B6QH9a}N#&S+uE_Z=R$B;MDT#JNxT2%<^oFn#MCR1D=) zH+L=JG?0$;Q(;M=tyNgf3-S`S7s!2{-D1x^;!R&FznLJ~Ijq*zcE-&q=8+UnFCAfO z#M6T4_Be-LHCYYuI3G<CGc`LNbo6We^gRfWL6rz3YT<?LrQ3JAZE^%{d-ZxLL=190 z-i`XII2c=$d;cnNP2%pdm;W*JG&pzS;V65!L;No63!+3K%sG$d>R4VNCu5haVuUii z-TCVxzL%*;kMjQVl?m@}*z&_<>|HgoN}|G)jU{-isH<N}*e)2%R&9tG7%PB9L-QAm z8IV0b7rc&l3U*4i<~zqgB=pqYU^a*99^)l&WnR{Zu`;aGN>`1v$xEeg4_T*<;+-k| z?m!^&o1;k#n5SsXXU5#Y-=vK*CA%xfAD7&e;7K}av)L+@LYvnxLL+;BW$#;wJm)G! zpaVn14{ek0=N_<(W-ieH<AHaj!Ej|NFB5CDYLpnmYFnJR3g70t{iBJx#lQau&iYLk zY&3nX&5Yex7<1G7qoK0!w4Jf{ib9<uj2SdNNoMi7-H}k!%X+zEqXcc>slt|OvJ^GD zaDfb5AT#?@N@!FN^hBjDDK<9N)V(3!?QCTqfJpt~tb1AC)&*eXK3sm`3a{5``pPZG z?}tkSwM%g3W9;!+7|+^v!-ScRhkJ(4Z0i@y?7RD7=QvMQb_-2adp5pq;g{0N2uW<G zeCHljx4XTVzq+mX*}rCM@IlF0nY*S%JfFU$7B;#sl;wTKi(>^=prKy8X<p|Mfm`J? z>0!aubq_T<?<=N{YBGcCRh>1C7-&PE11Vyg=!86`ehVG_=!xFyzl0q1p77n!3vrW# zMmwQSc$uN;=-sDpVG_{6C~0rCv0x>7NsR_B>Me+=uly=Tc%|YCo?(UJ!^%^6?jh^m z_=t!G66cYV1!KODHIa31Yjj%xo~ql26Ekva#V3>gu8m#1aO8F@jGxZ*GJ>@Z<Fq=s zK2{QXN!Iei!1pe_=2GR(d(z`aH1jEn<)!dlr$^XiwV}bem0ZP4X9r9Z8e`8ImDRFu zH-MZl*tb5W-od((EgR2_SY@Q&rQ*vEim$CF_5Vz+DPwa$(_Fz?mgqbEOn>WrCh1!8 zS>?#bX-;2d?Kn%bK6`1{>fX^Q?0V*Q{;O@uE5+mQ^!)4_oRFGmEA<4N<802-xmP2t zFD%Zv-Ql`sN-hZB;__i2IiHc`o;1~MwdHX=kfZuNRbG-r;ico1<JBavx2on@?(w|> zGB*-5lSCX?t5PGRC;gsMG5u`!S>6<b>$g}_>%=?U36dFi31ohy_wkl|qITP2^SpW~ zGWgl`p`j-B_kuYr5zSANUh)J%mUZild3vTw3OHH&(WA;#^1oc^FR(1Ns+;F$TmLk> z9b=#&qS=`%t{`iB)U{b1xwRff_rqaFR}5A^Z=IE3y_a+T32#wk$Su(iQ_8N6Y$H>$ z9p<ZfH}bDtmnKhFcM4$tA*pcrHQ91xc)hQ<mtJ{mg{MS-T~T^KV%%2pYxZ$2SN5ly zc|3?}ALK7s{r&U4qB{9+U9-3zxYY8Cqv=@Y4Odq*x;Scf<)7@O`(B>OX(K4nKyDFn zSjZ4@YD%`)s#5Xm59+Uae&#g9{7AhQJq}AFW}P(O59OwG5%V%7`9Pt-2lzohm%vBt z+#!)AlZzWE)W`Xq2oj4}bovS&&QPJC>Rx$<80fq3$dWFeRUSeKte8a^VCcYh)?)Fy z3?yZQWJ!RY5%_t!A^o@*Y4;B75lkYkb#X*<dq0=5gjjX}%WoU8j)Q_?9i)E(19UWZ zxBp~V8se(_-Ic;JoVel)pD36yb0s;o?IC#y+?vdh*cJj{5J6b03YO6Ya!X%2A!;u< zHta_+l2FnK(s=)I!B;j8<*Q7at>o0lot<+u`XG?MepfLuqH=sA6GiwwobB|1C;pIA z-p~ZJQV?+f!Cw4DgzS~qB>Vnk+QLKCP7W%c05>h6g>$*u)So<#{~sP~^OuMTF?&4l zzlsgCliUPsw;>g^*#rPMJ{c5dBNksKu_j9L6(poUbUlGzjB|BgH;8_${c8yPX(eKb zZW2zn?>P<v@#P1VMS!>L-!&9pLx_CL6In#LD-g^5ESDB{qH-a&7@`*l<AIksoAn@b zrJYh~Kf^&c1T_Ji$+odOtdsm%s~{l;wO9c1It<ewjKnD_cdUr2fcVPrfu!v--LUZ* z#O^3?!X3*!U6FGYFUt#jV|0H!ZWfUJwN$^v0WGZjVs}5HM`-W;Tlf(N>1j~S1~p%S zkY3CpszuR$L?3)odYL#y<!&_tfGgNdmL)*96*b@EQ-A!4%!v7y_#f8kx#sl%{RVXk zOA!n8zQX&y%aIkKk+NOh&D<Ad%cQuy<o5{u84Cz;<9lQlZ#`m-61w>l5t%}(vmc0n z2l6vw5e4d=oiYk__(l8%VLVg-Vw3o-ostIZ-@g)7a!LPHkBMsE%}$?#Xf&S3S3`H= zb97vYoT(onhl)0g&wpMi!TR3&4S9-~QT7$Ru%B}z3n=5jW7<;)GIEXqjNcdpCn#Fg zr;rjCW61R(egla6e*8c<E5M!!O<j@?z4{(+U&+J1OxcCueS4A*c~pI6j)U#zpF^!t zm4irBOBjeEkaJ@N)f+&v%^(Oa?xTZqgs|2XY4O;+dZ<O_D<@wB8h2G_?o9Je!0JKb z4t@yyLz1J<RjhS#kMqE?*fG2J&Q#nFubu*F_s4%j`ePC6oiGqy@*GNd1Ozzs(up%R zLm=nNrJ=y@)L}kIr#(B6RM@mbw+c1{Rt&sYiOCTl#iMBzl*wym=>2v<iEAg(ZL0<R z*naEW2zDcU9X6(N@C5Ec##m`<Bu~L`#Mf?;$#v|iK5ED{dA(J$5fKWG3|9j9sO$uY zl<$#qofI>Y931k?sT4PP+RzC|mTvFlGTuXFCwb+=!4sHBVX9@<fR(V3+Ke_E&qb+O z;HmoG-|TwSvzY#T?2cE#i7S*2oBM})BhZyrwh{Q#@eBx4BVZx`6b?M!gi{_&+DKHt zuE-(VmOV}zGWuubZd*Syu<KE4&~cT6C$O}(xpJHB_-B1LrH@25UodqF|DN?5@(&+1 zC_mTjVVoEfOA_~#=QX>d_sn}=0dUuWM@b5H1}};@c)AH^;pBdfd@`QY|D1}m6Y8HB zH6->H7YGbKIc{tl21J+;oth=U&BD4=9o;A)bV5mSn+-YODDn<wd1$`s#-$ntn&QP@ zvW}5G#4xjLWNR*{qjqMYQ;3><s`&;Couo*-IhL<AJfp=dQ^`#v^A1l$>U27wM+sm! zADllCDO^aQFq|vyJKYHn7_GEPiI9#A*PjX_>@xAr9wH1-$=B-RC$lJDN(H>=KM+Nq zT;^;nlLy%1@*}SlzcVL}CZ{oIkrS<-=n*V@E7<LHTzZ40r0I9nbCm3f+gT?6n=*P; z0>-?Jr(}Xn8Fl1RVU$w5#TM^<MNs)5Lt{D>5eM?VU_{R#x=NEKvjaO-wp00~!mHZD zypI!^Ng&=1a3%)>-Rhgx(63$S{r5IQcD=!;g^52${0z9BzF@N0iwwr$*0kGF$Dhoo zZ00Qg@7ru8Q>F83s@K3-g@)&PN`&yMqkm|+m9X3YNYm2uIw>TRO<y*k<3Q>Wwwo|* zz%FGnE!~)O*A44uPOIL1ebUL#Cz|fyT7aJseVq~Y!B{DMHu7$3_FahwDdVp+_oq@w zv?WB3N)R(l7-i2==T!f5?SPAPUt3idll9vO1PADg?tm1Lvf{A(Z}sz2>*9-RJG04# z9$<T|2p5F#bQ8|tbyeD`mvpe7@!@M>p)d7E!FTKa;k!9AF;`{>6Wt06qTvHapG;oE p7u|%j{qL<HcZ*M}>PhVF`0(P@dF@LSR}?sr01rHLxuL%Y{vXz#`6U1V literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/10kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/10kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..b0a807a89df57e325cbd7990b11fda7274a6f1a5 GIT binary patch literal 112182 zcmdqJcU)6h*FSoYCS62CYE)1VRFn=PK^#OxL`6Wlib@kAy?YQv6a`cS6h)deX%>2m z6ahtgiPTV~L+Byp<Zfo(_n9#B%-s9C_rHrD`JA1Qz4uyst?#Nkw4by=Xxo`nx~Cup z1_tN~_y^H?p_9-SFl1oZ_`PN0hlz3HH!~9xBNGcV3(N2SS=qL-u(GkTux#bn%ErF& z1D-fJ*f}=_8<YI;(Jjo3jLht;EUdr($^X$W+82m->lR~1ZbpW^&=y_>MqUP54TORq z2Ik+l#{m7$55pElCT12^uni9I2l?B;_8A$$rkTNx!Cwb}_aP=;=Iwiqo?zj-aFunh z%MQ7_&l0zaYkjQbzt~EUkiX^{#Kyi;V3(lKzWtI?2c#7gm6TOf)lUAVeM;xF?is^N zM#d(WP0ehs-?(XOXYb(V?&0a>?c;mze(-~khmS&^N4|)Pj(PbiHYxdCN@`kq#`{m7 z^YRM{i;7FCs%yU1*42Oe-qzmH*@gSr-7_>iGCKBad}4BHVR31BWp$0XPTHW00b=}v zEb#je!u~=RFQ9A7#u>0~(8aLD3;bu~Wn$iQlx6#g3#?aN`1Z=(-MT~TS>ne^HgWlj z1paHTt?WA`6o&RKY>@UlW&h6z3;KUW*?$Q8ldc|!laT=&9wRS=hA51sG$^7No=%3< z!r#$72eQv9@T@bM!?-;bmY%V!l)Ks3>8A-CFD__9u6JZ<(9;GOr<hgJu>eyZm?Op6 zH(D4hCGXOpktUclg^qIbX!AxP>f<yhCwcum%h-+!n!E0(fVK2s(geQVMA=d@96i#8 zM@p0z`5Rjp%qqCSoORSsm`PKk%)$9}PPlhJ@`9nWReJ}6K@Dn=xfo0ZcbEuRraeTD za=6hT3mTN3b2yMax(-2K1#f0jrlkLTo?t9Z3YCI#*hdfz2^!>2gVg37gNnco9-;B* zra(dM9p_mc6KPPrST9l(T4<zzUT5rualFP8P>$YL8nh@3lYU{pm-LL5S<|3Bg<u6o zN;;!ls8j-XOeJbzM49S|1Qks4{rNlrWyy-rpt|xx@+>9Txl14%9vSGRt|D52s^6uO z0u{>y!Au)lH(w8(%8Vk|Qi7YQE|_03?-RCUct1uoz0h+!zocg`E(lNp=iolnkMpb> z8)fRjQ0_a?py?9$sAcEv68aIe102b1c{m%h7N!)ZOzNUR-tBf!POmm#sCFUsw)L2W zzGsgtCFl@#I*0~IL-`w|ix1=1xpk3Ycw+BoN4>AuMUhBq4Gn71z6lNz9R!aG%Tm42 zq^&vEN?<0yB_(Up9K6h{DXajNyF#3%8Wob8sWNdnkL#?bvatj3q{S@6pF4<M=Ri|$ zqkkA{I}&9Pt!6+h&(aQtj*W9XS%Y8P0*=4~UfyHj;i<77?2x~XoJoTc*+<f$jOE;Q zb|7(8@Pt+Z{UGpIEZ`pdAZk87+iT?uI6pJ!40z>OfH-nO3BNKIUvCtf{SL0*-;0#D zud{#FWOfyk0h2G|f7>9*W2N3Z7dhD;z(<2l>|lu7p#Q>P{5rEP4YFnhubKVK`khE= z0}>HUV(<D2@!uWEEp}XisnLbgjCIzoxG5S$J_NaS0P1gfOCnmIU>uOhmgthuF$$P= zk12Y(j|NTXS!zT4@xu}8P~XOCC(T;2XwVM0o@Hbro+Q-5iUMmhhoKOyF6_!;JZW3b za8UsLC{QIcOvdo}u&#K!?G4*~m$hnm-<BVU|4AyOZkdDUtKneJ==g<60jitz*v0d# zJk*FxxaIITLQy7~TzF^IZD#+p*V0OR$HPE%*VFtjNZWjkgRk}w8EfAvb<MK|`zw3+ z?~PmwWAZT~y?w!uLCs77M4anIXizS(b<+s9FWb(nIYg1QEq_+dPw!=OGgr-x%Xe7b zpJ!RkOq{mb*A+n#kJau<d|9jUl~M1F2RWh32^Zpj;>Iy^D?5{Cr$e|zqMNcb5<=JJ zfA*TT>~3*heiW($OVn!L6e+VwXYI+n(?VJc@xbzHmPjn<OKf{l63h40T%9w#D1nCs zsq4f}2moEVBTSKTtI8_5k@s=x)}dE#_)VLtPN_ZV8gu&{Pm0jfuMl^J;!S)13ne_- zko#L{nfK;Zu{IphI{Ru^eJ+F(CojWvY;_=_5RJp=KI>nO$qC#jGRl|+C0I67i5NmQ z50|;cWKT?w2ZvV>`e20I4XNVgZ#hYyC;)bL8`2<46H*Iv^Q@&T66A?rqr$Zjbk9Y; zQj8zEWN*za7tdxN9*)*IE8%il@a6aiQO6j1BBiYX0@gd=sX&SxKmTP58HW_g&mBu2 zjXW1;be;KC;uWab@T+H(D4yc02Q=*Ux)2mWHUW<bafM(4>xJY^qa3kNXbzq4jwP}6 z!uS;$Bs7}Z=ArYdU!gaMWBb<NVnLG8nRx&(BLnC)*2M&F8G8DY=?6K(p-^H95VXk_ zb4#mgkw?3DM4kuV(74a{)nL;Z;P&Ni&@+yd3T0@D)~)8m07W~7AtTrki?xTd&iPyy za&8@Z_jYe6)6>Ko65Ku_#@Zeg+kw_f!1IMm3EYnK%l>T-HH6RmU)f8Ty?*RzFPEwM z^K{*LE_)i}FbOa770@8;G@=+h5<x`nApmd;FTY^ugX!Ok8vdks`l|ks$IqX9{aTDK z+-;*WX)%WJ7N$BilQXGyjFSJl`Y&~PCzmvb{UaCd&W<cTT#~%__)WN+BfN?0@2%tj zHOkZi>ruxS3EU%_-|XoeOZgRbJUg!M;`ga7Iy>&ZDi(!CaeGY4lmVPHz-tkU3Jg4} z8rd{RvoxMezz^xr4=lg#V5q%38T&%{L!(lhTGE-UA1xms#&44RotwCzFnbbFmjuR( z2M9;(kR4+Y(%A+?OcI<njHB3X8aaj}1s>9UH<c|eHyOjUQ)TZ?8pMv-v}_)FDu&v6 z?l1D0lXkY^V}5%=VR88b)$RLC!gV!os7#zt7s6ilwC1K@Mx4x64cLh{=hpYem3`Y2 zF=qJomAY+DpyDQ>+%y<f3=lSMksWQzFIRIke;F<j<o*3qeB%2KhVl$Mq4`H1g&1zT zLf=5CA|>P5!?z){yHH~h0V%haH@BRKarqs7er(kk3?&J#s&?gVE!*dkTq@!9%Qouq zZL2-=6Wp*`JvG4t&*NAjr>h{C{Ic3vy!fqnl<l`UwZSVl1J&i}B_MmAL*4hr<LZpl z1#@lDm*NVxA5pEGH8=V}#3NcqXb_Hv`m%*(jb6%i=m!?ZcQCX9Beeh7ml9i&?kT5X z{CMvhAapHVvh@5lLzu~H=--h1mX=N6ZXEOA(0IECOHs#FKkpyfzeVPJZPF1uKAoBs z4}6Mx5g6xzoC=hsmvII9fns&5rl@DJm%ZP+M#mc-JKBnb#X~iJ;E$*?d>bx~p9wHW z?s}ouhOkv>ggQ!y69U98A$G=&F=P`)Iib&XBw&Mlme*Ui->~(17?`k4S5kz1<~^4l za-tBmGDm|*Yza)8gzE1ic8ne$i&@$fuhoRfjpR}Y7{dEbd|Dss3^a`XxPl=u1Cxq> z0Az6UXih4DUCo0URuIoz{&o3i{nPg)>IwY2UAIc!Gu%XUy`%M_KnbvIA;`_l^Q<nL z0ZMgP_*f~`%sf-rbpNBE+2=bBrm-_rig;wbpHV*qkbM_=(3-@Xz->)02!8{jT0+^g z$ymS24asQV$##rM;tJ>B>L6m2ylJ&A)-W10Dk(tqi=eV)3I%TB!6)_0-01+dy5lD` zOao|;?fUBYt|s~Lki{I|5}qwIr~yY|q(L_mIAOYzilBQg4V7YyC6w_^mfY)eIG<m3 zb9>^rWgx&LKLRY>zv(<2Lc-wDZSgAvEQ!P9&|je0NO3yToVwppPx$4psH)k}1B~)l z@2W6He%W6v-9pHvgd~vANMHxUzw=}yuV48>VTaS4<cC+{x>0chd$$Chka(`b-?15+ z9I%TV8^>dhUgonn4tf3Q+FbICUzq+MFNeYUq(4K<$;hGp61!jMqt~x`^X0zAD=sy< zVF}U1%&L;vzPG}-`Gb1jmR_57D+jn}qBM~XJlhIZY_cF0AFNPQT>7a`GHmPivOCqp zkCWDN1EyB?I9XfRQ9`cv_QLmIQ-dPKjH?SAb-p*#Ju*={9eDfYoqa0WYCf)g8(+x1 zL6jXSKQ@x{nFehw{K~^*-xJ)i?NxFo(;ku8nV+>VV}t`#Lw%E1uEiyMX<=*rQyom2 z{wJ*vra}>4oZ8r{2IY%Bx!KvbZp}Cue{X72N!0H7cq&jz>?Qv%wBQv2uDao&zs@_N zj6v+;s+N%BQ&aIP^3TLv;(eh-Dtc(`@rph-X1nP`o8lWrxidAgVhLgfLly!cewyPU z{et6sZ{{vU40Gq(9De1IEp2|L)NJdaRu=q;yHC+VOK1_s)pQVeMcb~ou!!!sLJ~R> zzy&$ec{@37Uj`pPeiAYGyX&)s-mB?Kxj`)BOM1hz?ttwIR8^CzTvh-xK&3<YbuM#Y zWvN`A9#Kj5Li{05mhEz*wF}?Y9!RZ}Jlq=Dq{^r=X-Oa`2q@vy;yPMQE7|9*KhM4P z9dap@@M!jh#@-*p5|?9;V&z4}4l5#y%E|ojted<Vb^XpJhn}@ZP8&|)xwf4+RA%DD zmwivkR8Hb{@Jr4&;m5-u?-YKV1I)Ah(s_l?HsgCiG<TBDbG+PQ!XWfh{Vg$F5fkDv zsT8TV|C5zn=YUFAFGG~eHwnTy-zzPwM=fWu6u&wIC}<@hh0f_=-3U>>I)cbgXd~9F zeQ(t0kD7h`7Cn~n-dp2AAp5lcK7b0R0VH9@Euwi6b4sf;!?vqOj9|t!g)V`>z|9IU zI${Dn9kHVL$o!5n6aFNKh!4UUS!YovHJSh8T{yC`wsfuCy}P|{6lSMEX3#`>QYiF& zA%=1nJNt<SiCd(2+&RiL(Z{oX3tNvnaBsp6${Y{|&cqm&T(>Tid~d>G?Lj5dTR1}8 z@DjQ&fSq%LSXK;#95@irwCLZ?@5h5k^gaz*0kJI5uKhfT30p$J+3y0R9GieUWywi# z`j4p>X;8_54#=bx%eb#)l<0E3L`G+EPT<7RXG(Yc$-gRGb3D<zh=o-pjY9<7!`xf` z-(Gv?7hUIS_7{TIa(gm|_Lq-5JfyBSbm+k0oLjBW=TsgpnW{bE8Lm_J$c>%LKAe^2 zXx`uzdP&85^dft_7MG(v%&YE`>|lGj-QP4_$F;F|jI1X*-p6;3h|8nwSV(=gFmDuj zg7|9CQfYPdJFl9<qphd>kL<dlwn74ip^_S(*LbSEN(lGxYu5XxlXCBz&j)_(74ap= zyjDG^I~_|J;LtO7^!Qv@5Uvt+`{Q0H!S`C(=Mf=qx1s!Hp@ERWY&G+S)obm286IIV zB3V8?JgSY5Ph4*Gyug6BFJ?z&(zjJ97Axc3E>jGn5iS<L<F+^t^)`U#FyEVn3-^Xu zuxSk`*3(za&z4$kbpon(j>UzDdqwQyOaJ}A(W^F^yYeo8V*~oafE~2Px-A<_TXMM# zurM8O(z(82-5E?Z<iUXgfytSsggF`;JOSo`8$Au+P+U_a`+pVHn%){a9@A=5;5t@E z^2i=8>D5g=DS!PrXRZV4xhhB5Qg~2l^5EqgpG!J1w&6{??%XiH-HtIFW5|mZLCLEF zr5)R3q;qn}UpP2aK6Re0Ql&)i-%{)}mBuJ3{)^=u4iP?e5VQBeY?57GUF5Ixzh!+0 zi4;^7^|b+UnLtv>to0Y6<Jkk*`%*LHeohu<^LiEbA7%W&Q1I4ofht{5OjuAjrWYM^ zS<V28y07P~^+K0l?($o<KJKGGe+8<>&bQC;q}&ElSh`HUH>t_75sdR@!}V6vNCj#= zHrqHq;asi<&>LAEN}~~AAY^iN2(u1V(jZ_6Tf$t3;G;Yoa6LN@Q2@Db$EdZDk+G=- zddv41DX&BBcZQj3C^1dBT!9;a@81&p@dH3S{uXZm#0oozA}hLq8Guy{(&&6fZKlQs zs<DGyf}A?g{M|rba)ZHV%!(bR{6RQD_rk3W6}Iy>K~A;=pny;A&|JB!m^^g;R5^=| zE%=B~pc)CxBQv$hrg^F5QiA5->Hgo9Pzfj@+hGu9%~^viSW|Ka-E+d0QcEa)#?cub zdzvF%s?UgMcHvj*&$Gn6jn8m6*pSw(uX-VRTdg@G0UX^<@u6dB;p(;?hdwt5>gmfJ zQSZJx^@FFMA0EWi;F-PACyLwi*Bi5bSq@)d!yNJTPgt^0u94jlzsoyk+Duo%E^YyO zx|puU>6yS|gM;m48MKGK&E=uDnHRjfN`tgNyxcasXUIf!JzLaqaP5oieT1#OLIT0v z+1*igGIQ#SE=z38_N^ll&fOv|p9l=2&zb!rhW#EnssC1ZUP)|sct}gQc7V}UvJUdy zIxoJuQKk}`XJ%<Hl=^!6JFoY-g|~Mde7^e@WB5tV^DF`QK=fcdUYH`AZb><g>#dB9 ziz<Ew=N*2htupx{>gAE<wR4X3uq}KK*-gwHQ7z*d@=JebRIK4aY<}@fmc<}(<{0kN z08(kqSRrMnER;4gy^teAPCx&tr_oL1yTOfXMc11%_<{9iS|Jo94x+gznn=qhUPrTA zjZ7b(Es0B9ADN7WTDvs1BVVmq#;m#hPc4WJWW0ZW*EQ4S@Oc_k%Dsikw*NE5mVCfp zhInuAaRdr!960Eg`+1Lj-sDZ$H=I#|49`Axe~w)ruMrAc&CRiL@O{y^uV(G=(y=$s zYu@}SPg`Zg<@?D#Ua~X(q?%XW-q)`kA0rc#9Z?&26ni7Sd-@AX)PriGO^n0@eAd6O z?&#<?#((X!>fm^a`x=%RI~Ysy7%d5yujx(y6{PjNwkLV)vIsAd*#(le-Gyg9v|;U0 z4}EXG-16nq(3WMvYjC#D{3Ceql?iG7Atpa@A=%)eW&gJ$PbNpB`f5hz$t|p5cRB|6 zsIS#!y;3A+R)!xbN{xjzC0#GJS5mrT^}cAh0DBeg9zRFy9??H(xNs#-LH}^eqX9uB zfvAe9x!FKD$4Kfs*w!(=d;V**6+edmWY+Q74^cM?0~0QuQyP&}TyBhe0e@<qal#}e z9LV*KmHWYeyYii&4Gm&21XQcY_Vlj$wj!KUzISp5Bacm#+}Acref{Hr)ReMKqDbgM zR=lD0Wg;7HHIf>ctBy*)cldKc#<pnk*wY)r@kYZH7m5mFyS(y?o@6~MHo2(EBm$C? zC0{?3R(yWa_f1fLyQKAgt*oy$_2+fORdS3JRu}m1Ihquf1Sct$>bhY#BaS|m31(uw zHIjDG*Tm@kNqdd#w0-lW#N?XB22Q6ZAJ7L_(?z%DSQ~UW=L^SlW_y&jd%&uNIuCAY zeN68=ZF}?Tm&r)Y?Qqqe!%s4g5fQt?DXv%8_Iwi#dV1Tf6cr-sC~x}Our<eNU%R?d zdIQ&JmIUAFOV1<nMp;x@`9I1&IJo?CplAB4T48rijty@$=lw0FUYILCzoE`N;9(@X zXPJfl!n%KuPwO6eDlfNPdAnzZNPG%pr<3dGa%O*oNwLZKEg#}OL4#iDV;w7k-La1A zZz{ZYzIZd9b0@#6k8<$igC33-U9awkD{s5UVE&Q@?Yz+5mEJgH$=)P2pW>JO`OIVf zvX`92w?ymOCpATy3^M4G<tu0*yXX>@yj3MvpGTe7t&6Iuk$oo77I0ln{CxblCMU?Q zGZwUbL+T2~k;|d^ky8$-ApkJ_Fr;DWen?OwwHPe`B2$oNn2rTm=V_Ve8>Ip~Qk=V( zz`2nPSHm!EKX?<sdNjVpxXU0T%YX^4dxBr-C9(G=FiLiS^trCmYB#zTUvE5n)q5N{ zK8wX;Mx_|vY%FbFc|Xiz5JW~hk!vMDR4j7up+^tH(~m)h+-PI@4DTnAiG8Cq2tuyq zbjtF=_1xpsO3GKr<pprn^i#p!PT`T#v?c!j>!jErcl`R+Uf?~sBiBmbLvjK7U<$Cz z-Pcq{xC|&cwyTg_`&yIPlXL*xy%WTx4a|s9jfqndm}f7jAjmEza0wq$Htf*j(x~-W z<-|q`-U@KB3LfO}Mz~9eb+s`UtB-f=JCv6mC|9ywZjPs4#Ki>JO1VJLx$l2eDJJKf zlk-mFr$zS*-yCyI&UJQd_IDZ9S+EV2Rjif>-v8p|Zy{0Vs(VABRd_oECY-erDvGH> zb{D=j_U^ouwU6o8nNenDgJP0#{3C=LX@Z$3hf;~{t9iJ5G@oP1`<U>03%!rr3^&46 zx^HJbl{<Gla}=|!zd4PVVBJ&EeZ_7xtb7-Ag7P)MiU#HB%!H9Ic*~w?f$dIsBsmJX zpV&ToGMFoH*Sm*VN^fkrr5MFch;C#?e@DX2lq`S61vF((N!)!F&Df~+B))KEiLBnc z>i!`bbtyhNGpz*28nmFgf#kiiW4D7;#%)WnyI&4JyyCppe08AQ?-KQ{2Dkqi!dO!w zS;gNr#IQJ6*W5J6<`rAr)*mmW42nP|f+)HAC}0qCAHPlZ-KV3D#sY?458l#n_fD+0 zCQmCcc$pF{$=m$*6pINg%wc`rJ3I?4G<UwSUupi?25?IlTSw5K>+=r=<OmWpXgm5Q z4dOq(tW@8u5hpQlQ&Uj-UEudGZuup+W}&#TuH^J)I6z)kp<TW~{7v*VSKVB18WiN` zSW;g2l}o4kL;dUxuavwPUfVIwCyC}_*rTX0=<1#C@aOpIhzKv=uZ1-aF`<+8!kUK; zmu2m2njyHYX=9oRZU|e7)3IKI1+6hFCFv;-ox$*As*$h2Oyawr_OM{ZK0A`t&VfU} z)ors1^m)#{<Yb7j-A%WiG7-QNN|wi#Qf+(Omuhu^!)U50rbxa>G+*^3ROF{rlaCW) z_0P1K8#|pCEtb0#>GEaFMC4jY{LhoCu5EV|h>uMcc*6XbTb3KF55x-kf0mdz!RV>N zo-9cnvXGq>Afx;J85TMVgLob#c1aZH={|S#X6O94`>>qPa78@M$%YyY+dSrhdT%Js z^VZyH{c!c33YR?m<<k2*djr*{SM!Msss8*6qG99r)z?}TkNNkOwXFy5vo1^d*yOsE zL^gRkN{S^l{ANwG&+Xn~xqpnaWIp85eJ1~3r(>ky!3%E!?nEuRKP$VaaPa_V8Yhp9 zrZ5m|@~PD9@$X?gA+x`<A8190A9{a86X5uGuj2Q^FFmNL`K8mdr@EB$`7F(~=8ryI zZ`g&2`y9Sw(V$<fv&+$?M>nT8f3n8K?!4Zc57ql(OX6SLtCmvdwJ3NM;07Oa@FevU zN;(gViA(Uw-FmQl*V7-SB*wbq$CeY=bnYKkFcrryu-M7od@-|l<JPBFT4Eu`iu(Ng zi<%r|FT@+R$u2LY664Ruc2NtD#9n+C^`iC!!^7P(l#k{-Lym{!&@;W*9S-=LB^5?N zyRPp!b<Nc4!>#LMffL6agbkR89@-TdKDicI1`;>hlsRX2Uf5UJ^G+m2oaoD^Da1QX znla>fxbir0cdf{|?#b}t<@A&e54J+V+|+>e{t_*>$jJDNUnS(`U{9rwmAktvYa&9V z?-B2Me_1)Sjq`Zp1&y68PR2cpH;ea9c^k{vA7N)vpGSx6ngQV{fV3i3^7yn>+6b2r z{seAcd-jbbUR@b!YMtOzNC_Di{by+{Y<K+3Yv7Caqn~Di&t=-97TG|CD%Ty+%4%VV zoN|1+U`+{0B}pPdGPyY?zru@RuR)1xYXaxg2DV2qJy*y$0*?WNo{%vI6MWpLlI_kw zPyg}C4hVqmmxb<qhg|)zNQ3#xf9h?4sv8q1sc%2sc^w#s7&lNIJmdjpDE_@fXKX-P zLzA}SE@-kCWV{zUAW3E!dHW6gO}6!askFt>)z<Km9XOt30M}+Xq{5H}Y4P`+XJz%G zK`2*%`=<~OQO~X(&o`?JrIQ5t9ZVmCbtO?};8m+vz}fGG$pq|>rikKyO5qvsr{!i6 z3osdY5HPThtvn`ATb^_DGyiri48<nm%5Nn0#XW($B6Nrb<>y<I*!p1nFHm?v(+{A| z&R#tOfiFFyuH`Sik&X`qB6abvnby7r=ntcQMh+I%VYb@eIY@o&?{*{Y!)K$nU5kc$ z>wk{cpE5<^p7@#k7!VHPpdNCT9n>8?{N<Y*%PrfEu8Mf^$?byfsbm?kY|J9x`n5of zchore=J8{znjIMApuZV0GbJJXTk_7X=ll^EE4{%|Un%}dq#2!WbvK#fzhLrc#oG+U z;~jqybL7)#b+=_msv7Rel(Mo=C9BD+oPuStE<S=ht@wkOqpQ&SFuDCrZ|0tZA4CJ+ ztf(aLe5Cl0xhJf*DQ2i&B}5J%j*S+WyGd5BDcR$EuJ-JxAFsK_PC{-~^UwGyFJwPX z-IOJBSg(llw)Rd&zHVN*(-w=DaaGY)M;AO_J~)2tt65aZ+f3%=hdiSW9P!&6anE1P zt(1PVSn)Y*`G}&M!1Ect8nHtue}Uuc+r3@$HoCc2mMq^r<$PYVmitU&_mn_Lo$t4B zk|nmsZDji!8=nkyQ6C=<^=UT`iNM`oo;BFS`~FmOj;;A@-!=O7T@^TEQJxtLp+xpE zS~zbRH-0j8@;57M#hN!q3>VWhvMHI9s8E=2o=c$0nlJZ`=meVQkfNWZ{2J`+_a&i- zanGshFOyvr=O46n{fxvo?(muZbVPpL*z3_qc!R!UsY;jN*+9W-=d<tOo;5-NQG~+P z*>-=!5l0lqR6Nfi_e{U_`vyMzKaa6ZKKpRpcAyMi{X)dp527BMD3{15+mnjOM%d^t z_pjZ#G17u-I(fPC#RJQWqr5GTdMWmc(>*i9rIpOWI{meSE~FOL^ywadwfwQLvL$J) zlHYi4&k)%|i*G$^KaLg}SG49NdMNT`UbfyfJGcM-&&R?~B=$84M+>gI%vv-(PM;F+ zeW$c$(yk{Qmn-sor}3_d6VsOHRnNFW%&Pyc<wX;U)D~5R*}Ws@-Z*%cJS+~la4pn+ zZjso#_D!aq2B~Iqz})r)pk$gKp5nvsTu`H1LHRIqrRfpAt!W~jl_VomCnww8jgEXz zRSxY^N!7<-m`lGgm)X^4P1FbS-}2Zs5ir46AjA@8?`L<>vA4lz?(|Jlp`+Uj1Jh*Q zki?`9s4Ml9_YCw|4$M41wbWy(oac9)ok6mK$9Iv3cv^Ah2+~_t{icYlN2%*rYGk#> zorzNG@8)zpQS5AxYX+^9HuKoAYR6o()C%}gzxUKZ@|gli<*XYnJy!(e4F2d5Nwf4a zzudF0>u^xvz=hjC(N>PxA^PoacX+iAN~BA?G?73qG1OeJY^H|@9r}SL?*zQa3Q#j= zZ#HgEmNnjNDzdlNszJnl4?u`*?~g;G(uJ!9nHz=C2r>mfqAB{-)k+qmg*H4<Ma0OE zY;Lqs)2*W-n1!5(>JKO2lzolMZ0f-;1@~+I@L5q{`2MdO5PZ88P$P()E?nl%w-^r{ zi_|X(J*0NhIeVw+m17L5>Tirq{<48TJ#862`sK4>w$drrb0v|&fp^caApynBXO|N= z*=356hIaIXFa}iW1t?OR28?g$I$W|M_)c=irv@Y&1n-V)yimcv_2>AL&~fZ0Je-q` zd59flbpz?yYsCh$P9{i@7iw)CTbn)Mg)8*UQo?z;HV8i#Q<XTFT{*>L2K`7Xjh`u( zNA3bHuMNRf5%hyVl}2SmO9|va`_V6RrrulGuWswnKWMy7=G|GN=zUDvxVNh0=+P6I zz&-r$fc*fol8r2+;xJ;bQ}Y}e)6Ab=y8hCHasc1$YfEJW!OnaY4GM;CclO$07q@O4 zJqINNMCkPIy7m+#!cG~@7$-jkmv`^>O5A4_oPZ`ZMT7aPX^^7>c9{>zAhr=vfawPe zx!$C`-oN@OdOMoa9wm_-%nKxrx|G@<Ux+2efF$pS<|>}B0kQV78)OCIlEKHYtk&y! zC9mG;ZbkV#Y!D{}sgX>6AYz4u6>Z7I6@}sUy9y?O5ZyL#Yjm`4*Gn#r)OB;H%QP1S zNiaMBa<FY%On0vi^~t%+1%qMySAB(@ACCsaw$|$>j1vjhT~BQZ&S6|Nr)HF)6Dd{; z#%aTLVHJ0W8*iGvEEzSIM@7Bl8QMKaa+$Z1O>b8EP`P5y)oNYhd~OjvpM{ej&PZv; zTnjn(EW0(S?;FEUwr}H%<xs%m5$m5Pbr&9dmV9)Fk8-NrP`?aTbefZ!-evPfJk^Wm z>|OJconZht_YgD^GY7m=Ma{no-9NTBT%F}6%EL(ROoIAzU&M$I7xSddI<@v%dzndw zdE(Ru{ONm(ED7;eIOi1ken%76V*%sO#~z^{DKM<Y%<vEM!a3e`m%A_{ra4`zmMKrU ze&|Kwrmcm%BhHu8p!-4O8_Pvxi<dQN<k~!cVIMDd+?J_dx>~`#zf^B|tYq7y+P@o} z>;f`423G~D;eXy6x`o<Nq0&92u{Tye)o!;{|La#Qq8-Sr>U8w@L~2DK5ribnY^}?( zk9uP6DxgD*W6M)x#D9yuA5*j>cw3n9>X#-RtIowNrGkQP^6{(-<2m(Tn#WAv9ymRt zFrW9c_QRQ*&^PwrYg^T?yJ@2AD0`{JdCfxJb9I%Z+`vQbFBRE1VaL#!ZMhLK;#UUW zs;%X2qh=yPJ^m`hQoo%~Cwe^7kXP4ju4siwy1Gnsqt2Q%XJ$D}RmNN@W)j;PS46dM zo9-DM6<m4!AA15i)C}@FJ-o%sUKw|Z?rkzJw3V(fJ0W;O!W9_6L8Hb2qV<W##zMiV z?^?CJ{4mtFtIE5=8Km|-l&~GUn&&>*Rh-R&kd}-?dlnZ>ZTv&RO*v$^(t>zc6DXOf zNK-pOU}oDDcd;`Y8l>euE4HLdgB}H^Ci3@@O0`8|1bjTiF2*%RjmM|malDADF0m}g zylQWgZl(F$^s`l&iEP1S+t7>syym+sM6N7MUK-2KkGls<%(IrfE3u(-yPR&NyzSZ% zHXJq}8MftxQ`#>kca3F+zUl<Kg4mSMN4XfMoWtgFkIr5@o>iZI!s5aDiDs0y%lYb| z=q}9eit_UE#qle+?YjF{!zx<#R@zWbob$=u4TR&KRZj!8(CdNI4~@3Ic*ABhZfs7J zlt<<#4rlS%LqP$)D+xT8%Uj&}hVZlQ74d$_c}G9X&+J*9mDoRU>YNu(iuW`X*llr( zt}b!*X@L{F#-3Uzv5{_;jI}GYCB&)W(<lqpgamG}(7DY{Cwh|$3OPRm9`<VtY0Y3% zy3wU4H4(;SSe(EF0Fe2S{^$UMraHuW;{0Yz=`-0gj9ur^UpAmJ8DZ!Ex5RQwPY?O@ zgQ?X4)fA`RcTtQ-tGCG+9G7Bz{;!ZLU$)85=Wq0WZ=csYG1#8s=ziqEfek$u{4)QA zk}3Ze-2I^Lv3BTAE)DwBrA%*<%r*FIGN{Sq)70dfjc?)RLe(bu_5{$0`SxG;p*qh5 zT>bw<3zr9^!jB)*H(j3S>i<!x_a%{Sm-=<j!8=BGsoC#A_Ws-mXn|8Ewy?UGB2vHr zbJew?mlboY={K2KAy!se(K(!7Uh>@Tjnc%J>-XF5p4_V(J<npq4>CeGCgYd63ITF+ zAUk0C0YjY~s7~z62jSBTuvV}azux(eAA_oV20sOh?)KC<9Vo5!eCzJpjxUg|PIyAn z1+?b8rr0s&<pJY;8vA?x?0GW%Adr2Sasspoy^bJFTBf+%0b=;Hv5xAV!0rx`TOMz> zfwA--QB8*F9r}?bGhN@DN1KT<Xp$n|LyAF4Z`a0W|56#IK?@5m$S@6(w-kl=V@7z^ zx5SgCuwD5wvbCTo7roL6XG5+VAG9RQQyzd^4IX(=sy3p24D2owUIT$yPE#Oz_&joa zA25dclrY^3pcYd14!iOV`z(Q*8x(K0l=i~JwFr=$%M8j{#UsZ@XwYp~8VUeS!y?Am zjfvt(GY%={I8Y)}1o5C{*rkLmC3rTtemi=tcOAFS5_2Cr%7y}6w-b!#Hp)Scb*Kd@ zE7b)_{V0R^^H~bYo@a!!L3!5$&b|Ulu-GneZY7|$ttJhEPPwuhK!Y&k-;1u6)=#jb zTr|ijW?g7ZYIFT{Q;*hvuf95<7KT70EKFs>acD9FN<^3c=$uNeMl#_39aE6ZBOH2E z-UE;WNN}<^2X?jRbuMWR-xMglQHsWS8zP!6a2cM&n=Rc)NTURTWAMQ)i<@17Oyo!4 z^{v2LumH72OGP&gWpLn6&@14Tn+gn%K~0T?2Hm|wZEi(pyDK((3(WUX`A9fW!MaXt zMl?r|(%ePG>`f&|$Tbg~;^ul|IDPfe4oX*)U1#Zoait)r-=DT=6sY0=7|8xdagYCx z9v(CBib|LxqP1qdLZCrEIvqaK)%idwRct5NH7AN7OWle?S%w5-M;Tcu93V1RU`X63 z3myeTvH{P=3J8RjLv41vFi`1pvZOT>iO*PZQ%P^-&+;DRz5@_)-5ZCTU<0j?V7`QW z*Uk>&rf~;k91;wV9%pR@g*lci5`AyW&y8}rHE_J2TH>gFzy^W7x#^-#cvJu!mQ@=( zvA@U{YI|K1+p#^5*J|iOX!;^95Y3LE>{DB#0M#7@lFpvyMVDBB?BFWHT)24+(Xu9F zmvW)bb{<Ubke&T4@=WQwfEl?vfy2dT{?l-;$q9^#4N&g{ka)y~0XMMfXac|ubr@d@ zG6-0Z$x&-c^h&gfL+i$TyDxR+^+{LX#co9tWP6++0%I4q0|TlHgk_zxkm_dEkif-5 zJmWFH4iK(h58+QstV2B<@>zMuSLT$@wticU264;0$%*^|bbTC6^+0_O1ZBxhOQMH% zwZIc%==l*i%sMIXNdC|E>Zf%|p-C)Jq4jrGHEEEaB1n_4oddoS8o$m4SLLe%5EF|A zu6HZ;X^wNC0($5G4m(Z;GA>IrDi=cLt;&$*&XlFZpXN7P%EI5|a9uOby@wq=N`r2_ zCY@&)r-%#jP#No}6wE?0!W+hl+#Nv>Wnw2uic#i#>vF$zt>vkz4jl!(66Jw&JT1>< z_~^-Zf4c#RhnlHwNK#P=)B-q~1~S|6^OXD8A%nsNvCl4Q=8ZnZ61Q{I^97j(!=qkZ z{0VSrW&_dUAdh&$6Fc-W4{B`zTN^<<rGO%_Mv#g45tE4ob`;%v#p~*N*<Z!AMd$c0 z2aA~zScfbFZkwPM79`2z>n+T9I>zsylYuNiMb^jGyz(<mGUVwK679R~QGT3}cxX6f z^Vuuzrz@(Q|I2&NvZj<{`4`&rGW^qxPF(5{W_t4WoW6VKH*YL*5(H!xxb^dl^o+l- z>5M*4BydNZd?3r)Ti%ox<Q2A>%vZ=LSl18=PH}7PJ&^WV0MaZ>aflB>kJMsFvs7lM z7G@qgZd_9AwC4IM5-a^s$awF`wNETZ*FI01cLtBd6W2iO6M%i1z}fsSEO67VD8bEh zJ;;@e<F4ve3Ldp#mAN;N57UX;HE(%DYaA&mT;lIMziILF4r=G(-u-MypIl8+O|qyZ zKdP)3WfL!VG@>i^xWyA*OyifRKp0{uz_8Ovf$1`+t>-@UcwG8&)>&3rN9MlAV#js9 zAQk?<(C_%79Uc`2{IqOe51mWj67nyi`4r}xepdWj#TUasb#RpI26WW(pZX(sY+(u6 z1QmUsS{2GqwaJhhG#7u|9SxXK-ma>`%Kr^VUtHRXrDF=c1m?Da+TF(ts|l~!)Ja31 z^GQJ&c}j9}KD*!MZvup4o9=l0WeXiGgCRA>*<M+-lFuZ5X6afSW~gfjAH^xtUj<3v zu%?szzi0)gs5cMSJA)*tz#pe0iG?=1$lWW7uQ$nCUYQ5-zLz?VL^b`D1;t5LeZ-*I zERRR(6ZdaaIdLp)VR0=w-gvbO8w8C0L4YFwo{nk?|Jx4Y4D{NU{n!)_DgD$|*Yv>@ zy}2IfEfIddOLh~xC;at+m6wTFGug-i*PZ_hE1tL42$hfZ8G9-FB}Z%P3N&1Zl4QDl zT;_0E8+P;ni14j}RY_!rrvBwXcF+T+TisWospm=LKyPXr0A^4AKQ6EUzlIJkBk1KM z9=LD?zG6|ZJ^xDoOP`xzRyqUKZoJQLb4wf0X`kVyoct!;xJ;_Z2uQ+LyiREzJF!bx zyhm6NdV5+jL$MwAr@w!G3mqaQ)1#*?Xcj*F$cgn~w$PgC6MgB^7cM_9vS5se5&f1K zPbUMJ;3mw8i!cu4>068oq&8_r7S&Ho_;UC|CNUR`^8X41_Oh57IT{N%-)+ZujDATJ zou0~QghKr-^M}<>dUmNbthXM#(RoCGbF1L`ZC^e!`t?6<1RL~MZ~lsq)|c83Dp+dh z8=NiVHQ1?Mtjzc1DG$@LmRQ{8VgdSJ55u9`k(9qOYHVWSHyo=Serd78`Qq(Un$0K8 z={HmCL|1GW4paf{jpP_`zilafI^BTH-b?E6_2&U?T#X^SzKyrVAlu5t5nl@!Z$pt{ zjLvBXHuR}tA=Q=NknSDnFwk=6Zr^(*FH~HF)j@Dav^bvWJgc6zE1nQLg<q=0BSiFw z4rPByA!VVE237D7TNu@?0Z)MC&2cpKXfw5s9*_)lD0$@ZEWB-xiUkkw+9-Q`btuaq z#Z*y8JkNTF{@R`%Kz^%dH0bzY^!!JJ-~4<LX6vV3`%uA~!Y`Y@)sH;62D+tWz~uLF z#x&@y5=eM}vll`SDRyGV!?08WTpM_pID#BM1j_!&@E(hPcOn1A;o&Y)Qt;(dql+r4 z>TYj3<B3|!5$lsKz(PcTxYjJ+UleRPf_xp{mX99dXhV;u)KOQ_RY~RTPGz#r9+oPl zr?;Lx>w4tQ%jE>F@BcUJEBgc2X}5ViX`HI<;!*54%+c>W<ephS%xkb%9CrGa$A|>U z2>+KYq<jRS)=zjE#DZ#*^m{19cUuoN2P?++_zl%Q%buJLxZyF<xL3GA_-ET?=e>?U z@73*<dphy`w6yo`rw-EkhN+_@nYdl*>K|X0xbuB}^8zz9<ECJYqbP-Z#gq6oglN!E zB4G{Cdl9a-^S1<8VmOqG2%&i3MSk1HM+opc@1l|4rdLgsDM$vWJOk&q;jF`84tiwR zV6Ay67cl-o3laF>T4~kR6a@`20Fct%1`z{lub8rjazkESjRd_OZdJhM%?ax$Nv@k9 zAQWETwrN5GuB7s2L;x2KPnZ#Xz>IEHG>DR&{9j&r%|`(l>Mbzkq2IyR2z-eKRf3Zn zOJhs~{^TE*C(Uu#0-mn{hv)Rw@Kso@?^?Y(3afay@7-Pg$hgQa@ORoT{7LBXXaL9P z_wXPP$i;S{Vp#z&Er8kIquyl<(TV3Vc3IkAkp@+t9GXY8vX3jTz95F=_8d;}8;S_g zIwi3U%jz$uBLeSyV=(=X^z!|GruQXL98m|Y1392wrQf{-J8QadtomX~PW%uY!hGFw z#(EI2u}-y)a9L^=Fli`H1Gv#G83Y^+;^GOxuCs^VGFZ%|0PC^1XXX=TooWa&fOVk# z<t4qtl+%j{pB$d2vd445gchP7fQ9#S&&Zej&o0QT`-TJ~B6qhkd-{tJx~CE3?Lb`m zuNu%@LxaA=)1bX#4f}zQ+leMv!0YxS3ML?=tRgKmQ#q`8(1a#$01Q!i@ZVl>y9P(W zg9bF{8PAPKxOpm`co<E|Ta;yi>n%VIVWYw3{nUy<kM*!@NH#j}p#M?AM8)7s_}+jZ zBP+FEU2Gs97<#V61urDn-~pCs=YJd=;idmRZS8xjy?`dsX7auD&`Ipyxs>{Wnp+_~ zEnuJ8?`<+v6mIxHhH$U?-E#B7<!8M`$^RscPcK-F(;$xNI`r}(e{~=%szWeh-1=W$ z`X|w=$)j%pnz>0$DD$!B=>G~->UEOVbo{-yyQWzD?2EJDzscl3?J8AqqwDZ*ocX)r zi~NiqvnB##HhQxAI(~_ihHymCphN0O|5I)#&aK0Xo=!Ri?h5?)@QnsN{y(O!TBe{C z9_0m!Wg)O`0>tXCtm-lvpAA{C)-Q=PC?w=oyFM-c?GRvm@fXtNyX)+#AJN~j1W9nN zA)mfs$5#v}0w~1nN~<}V(1Q|yCoT~kf%Jz|<0-*9{|D;cq;3w7@Ef`hq#uo){G8*+ zy8b6|*#d@Tgy!mx;-i14HY@6D8eeZ$D)63GM&e03E5zWTHv}vVlCk?o=^u(}Cj#f> z6A)lG5J`tFHxsR`Q~}yL4viy%%^)kVSdi`jYV%$|f4I&@M~ev%ZyWzM;6*_ZevV7P zTtVR-|6PKAO=QRaT>}25wg0S`H6Y*nKewlIZ?>Tw;74yImjuoeu+>lZRO-jGmMQs; zqhSNgxlXVD12}$QyvbFz0=oa#Bkl|^S$#=-Jk(%a_|w~FsMU37>mN!iNpvUp`L_O( zX1qu$fd8(j5r1dGKPji|FlL>>0xrRV3(soh_YA1H8q(7yk5Vm(8yar$yN2H<$Wx4& zJeRZ4e?O>yLe95>hLhHdI|@Kz^*+GbU_V=mY_14+$|o$*AkOh%VE4@R<5%x5%)a39 z;dxLYh6(1#xx?*klP)N#FzDy`Pl}r+s(lM!$Y1R<>hHq-5B3!p?2X&%zIA_B29rd} zo`t!@g_D+D>Y^hCtlm5QI3gH`v7S3&jxw~Zf@^gm-hlI2GsZ^bqne(Gb5{6P>0{R~ zHKq98c70(KU5Z71>*WdhzTo}ve43emyMy%da8&Q7QX}&-<O!<alIX@It15waaI;<n zc?J$f5rQXCOKl?v88u`n`NXOXJ<11Az-p2bY?|XRQiCH|%%}Eh^M?07v9r{bkY!X~ zNe9-8&Y@F_9aT30YC2i*XhV};BcSOD@$LnwURH|3N@|$xu#88SY>#&ItvTK!9F;vs zpZc*wztVHk=sekt&|CI2a2aDzYaq|U4jBNSr2aqm?cI8UXWsHfxl@lCB|r18m3MVL zcg!Z78LYb5(S)WP|GbS4Jf+R==BGUyCX8GXzSA5bTR(E_^P6#W{|<)c3zi1-F7Jg+ zJ}&q=0Psx!>;O|Y?1z@wlnguRI}iH_YD%iJz3Bbx!0Ysx4fp0Zpr_i7F@rvS=u)Ql zz&i?j`*9C*1Wr|iD~8^hKe|QuZjp_|+Lpj06aUVV@jQ5)!wdk{ckl%WrJ;2()k4m% z`KFZSk3R1|n=V?(lwRK~s**KN)c3%wkAQrHKWZU?JGvb?4lFA8a*Fq7!s(tNna2yP zln2h}=@ieXuf%)ENoCYZTi}6>)N+^iNkkJkb(X^G8&|yO1`vNEaNjk6E0bfpj?=Zk z|L2w&bamsCrGqe$2s||x_*G7LaWf-GnSHGzKc+OgyF<p-Ptc?6zx&W;9a-32aQzNI zj1iK@@NMIxUe(w|p+b;RA_>h*KcTM{Kr$`Z>+rf7{sDURe4aJ+@Po3|a*kCU8WfpL zv;l<`4s9CLHsQ!=K+dD0Mtyx`DdD&AD~l-7MU8-@P#L!$?0??l%3=RcIU${48DxT8 z081$ka^UHY@1rol1$x@qO!ZW}_?P=!QS^7uxzs@FS~XV$u3JW})RAIqvax?YCu}J! z<3b9?shvpvJ@Ww;8f5N<O#Ra}E;+E^|6T##lIx8@PDX<!0o15NSO9REn6jzQ5k7xs z0yY$p_P<3m^vSjN6?p6}%%N&+8hP&S&?}4;NhM|JYPjhaJ#_yoqp1CTs?t1(Q8yMF z-PpZPcib20f04R=Ee~UoT~N>q;ts`Io@x)azc7z-c#$Eqe`cy9Osd#5wc}Fio7i)$ zrJp}8Me&mjhvtdmIy16Kmo2>Kt%!nIj^9LoOs5k)dyP8VgjK8?o=F73a&onhsffYe z^=FY%Tfcw&)=2@;UXU*E{*T;|_C9Gy^cjliwmvT={<)$fp_AgaGdFk2IChV6q4muI z^1c*gt=!!DlS=rd@ZHZtd?eiMP(3w-tPjg67i^?-wcoAZTrOYflAbhc!u6YtbGv^& z8*w~4#^ej`#ep+2y|u61Z}=G9e<Kzpk@5XSam?q7QG=7UNzc)29y~-sJW_;4f*gZ$ zCuCNC1A782u2e`P<bJj8kr`R51Rli>Zyw!+>jaC-vX53SiSe~3w>x2a{I1@RGw^aw zT4}AxR&Nk3JDAn@D<+}}OVE)eO2DD+nYldxIMJUA@2|w)zd$i<%aiHfS0U%<pwP_I zbg{}w%k(*{)HZbZ@XU(fp}9Ct;|4i&v}d`y&Rw?*!zjJ#D5>rx`vdygwY>I<KRRCI z+waSCm_nk|Sq|rD>nJ`!9lEULa&OIHpGt<=g{b0vTPy4{iWa+1&AHyUrBGU}TfJtx zX%NdgTzM$JxtpU7jRO4_Jl*3pC@%MSR-$i!$qC#n#UM)~aaiwV3&APh$JRVR(F^sm zDn>v~%6mZAyK_DpX~7bHLlGrRX50vqh#;|U^&n=azgFi=>PI3v8}CiF2<rX1*1&dv zn%eN*tY>mb)3d=-uh+a`n|-$D=i^biT-^MPF1)Ej4L;v5oFSz#vz?>9uu&<7rGGj1 zeJX6~YWi?VQmV1L_UN0O;TJYC(+5<gQg-AX$1r<I6x%is*?34G>*;QoxpuM+Ptd^< z_o1rd!wLQZ9|-dy{sGk7q1Wd9a`V+zN}bjX6%Y355#OE8?K7*HFYvZ`t{Zn@luLey z*$hR{!gOPXgF_zQy2Ey--dG?;Oz7T;QWt?IEBAa9%X_CL-S_BXYFyO~9MhC`9XOKT ztsRTm&o`y9<;PVm{wb3bA=fd7i*C9H@}k<)JSs};E9%<Diq0Ok2}!iN{N6p;_-NFW zTkX+tx3MShrPQ3yDU4ric@y&~A|LxXPSt=AT@>dA(9(LP9~*ZkZwgP)p9g|Yj8CU% zzz>wIb_ty|PV&nvZPYSyQ+=sWs$Xe)`iFyt#dc$((OH?-gmHvTo-9iw4?E$iF#N>5 z?FJPcD|>8i-0?TeFl$gd>B6+OCgfPsz+5wZO~Nkvx9e#82NxrRKB7!aDi7~ZxtIBf z)Fhg&6Z_pmc3;|;{(S<Oy5#T8Zha%?w%6Vk;KnsAnRRrDy||$)wbT&1&HmC0)ZQmi zGKCkF$Ddr4{N83ld7Fg2jkQA)_v=u$zaEVEqC`wa&t!|%zE@;wztSF4=UcC<xa-&T zqC(ryRqrn+xxQS>`ChgEQp~{!Ycxd=D3r^cngclwV*7{<gT?a-rxm4~6lT$<7r0u; z*Ux_G>s$XOuWrwIh+OcqO81q9$>r3CS%sBi2Y(P`1=#a!M12fBWR=Ct(_P!5dVZPb zW&fDB`<8o`fIFHy9Io^5$EUJ=zRuCo-r8qU1WP)l+eTNz<J6=xUmRG{@Nyr{=!^^v zJ5Ypp5b27aR868InH^}kIwFqL6b>kTBp!6f3fd*~PObT#O3Ti>ZLqH<!|qbQ<t_<Z z?YqA&$$q?kd#7A$)PMm|Qg+5<SQyJW?MObZGn6T+MRo5#d9H(^mtLQHFnV6HXZwr; zlY;$0EvUk*$nEy0_uo)4C@~vg0Qttw<aRl<K2AGuBJDt$clSh`qQ~JI-@9I0;ldF7 zW1@{{rN68>y0+tfdV83u85dcXyld&4!jMYkceC1~1z}A>=>@nku1&RBMbgm)6v9?Y zNa{5tMx+wmD$N@2i|rt+77o9}u!io5)^n1>pDZi+95#HTPuW_VU4wA_Ih&39<&O2{ z^=7)7ueE3m<xu$0StGSwu}@#W@rk_WWHxI$aMY{4pi!i|=|n_*c}$mub^gT{KG)x6 z3w{?UDYNWz&Kd}_YMQ*(s?EQo^AJP)->R_1+W(e{6`)NQQO!CdN5I!&MUdvO^)0M2 z8{b_7+-kVq6F-F~vE|ej&C?A6+3#Hh#?GmZ3Oc%j9DM0Vc8m|er5z|Y0ltY^mnw;% zMmF!HK~t*fxaQ7fo|$SIv`+x|WuJV8@l+i}p=v&47Ok@`_ErzvhJB+<^$$T_L}>hO z>HmLQP@X^!$tz(eu-(07*ch+ZPez_BzXJ~L1c+u1!uWY4{~E{@*7adQK{ZZCQ<w%3 z;!q^!2r@|Xb)~^oO0nY<{l=lkvnX`5cz<E9s$h;U-6c|6%I=R~rVH5lX5i^Y5KjQN zDj^xh$0Ow!P(UI(;0dAeGr@&RRg{6NPUU_!ERhIbGAIFpPr+DHr{Px+FbiTxzw%@L zy7r+GVtqiyn_eIE{ubqN_3?bSPWtbD0|iLt2qY*B^oPQvWw?q1MP(L7K%IPL`c5eH z#m=Pi@oKP*+jv}&_{~1IdHqc^>w)f+W#BXBgi(Us+!;W~&(;byei_uo@l*%bDewgl za7|*uBEvf6OK*v1Eo-)0C*8Nlxgp!YpH4{O*MM)ItFws*g%b&!JVYJ76Relbs}B?k zmwguN?=Kl0$yVM(c;+x@dFcawEP6`jaRL{(i*zo6x&<`kf()feGE(<eUfDVyTh)u1 z8LY6aapG0>DXzr~2~JwcTSbut;ctT*RmV?JiST3<`+pPbaPxoNV|MeAFMuOE!MBnr zQ`f<oZE%&{6>8n8v!{RYQppG*C#Xm!f=G;{E`i<`H~Ou2z*X+>#7^}58t_d&fTozo z2=9w7?C>qj*_$Kdi#0yIZ@Zfn;t4@@p#S(3;3%5v+W`vYqdXuyw9q!+U=N*`h&!SP zk5MxoKt#9(u7dX8<3}75=)Wm1@G$*?5p;YqX5PWj^7zKWQ?jFK;o=?r1WdF4>Pqq^ z!Y_K$Wmlmq^l~y`7gKq!$yga}ckK2Z{UXXzSK&19j~3>g5Hh?+lNWexe-iq)b#u~y z&^WtChs+G#S^B|Mns&=&db1?Fr!O(H7(XU_zO=Caqx}$`JG&oAgxy5*!@{B->nZ+d zs=TPus%z_c4LZ*z5h%0jh_L07nJKQ+7_{xI{1*+?g{GL~>8Jh|J}+do+OIaikF7r( z%8PYRS$*e*8elwl(@2Z))Q{WMOY;bu^$-s?aby)CVv>l-=g3BRLUB!rJFMJNdtd9x zJkIp`zU|z%#IS`oN_|J9PooQcBOWS<vR;00+{^s)C#O@6j)#sr&s~&va}(G7v~`WQ z;#6f7=f}z~xpFx^ao5+&1#jrT|E849uRMS1yuEgYq<68TcX{(K9<ef=VgHm7Z)=GV ztRXXdWBP&b7C&c>OI00Ml6>djCdult&$hUd=(Xy(U=-HwEp9<gqL`wq9nHJSTFb;) zIx7lX2_Fh0FCBK?UudK&eq!;*v-*tjZE0Q!-a11-PBqwwHU`Di*s=@5x$NF=IbN9| zznrd_&nm4lsEhq3-_x&qAj&4MFtqzDhEY1{Nl9R`u^-2@-Oj0B-!BjQ7%My**<<>R zeFtBq#HT>DvA}u5NevWkWtQD~hn=tJ*xW157~aP89&`1lrwFGP&SmcnN~n`?{l92? z@2IBsZ+jGv1rZSG9h4#+RC<k~bm_fDM5IJOdZ@9`t8@h+N-qYacOqSS2k9g<>4~%e zA?LTf_x_G}&OP7v#(3lXmxMv~r|q3N*P3fC&R2oT%KERejcdW}6tw)-hD=FZS$@cw zW<E(gR!1jo-n2t|+lV05iW^u|7NC~dpyuz-40@Uqnx!Xhrq*HjXidtvfNL~IufkC) z%k};H+$`=`Oqn*#_dv2ToaG{*L1p6@ZD6)vF0NoFcO=c!$k&Q}Mv?AGC6`HeBAOn@ zu%s_NeJ7Zx2M8>PG|%cEJQ;>Pjb(ruTa11j4sMUdbFHBn7Dk0V-p_P8I9%6o;Q}fh zs@7I7e~C9&O3FH#lBvcVwgTj%jc;E_;EN3FO08%146JQ@TBXYGogjW9E_2uD)<eIR zQp;~MG>cN=#Ypl%PEh!KGv5OFvyI!|g!WSJ4(FceO_f(bq$8cNj2^ZW(K(4xOH5eK z&cGWZEv;ll>bF7#6AgKlgv6W&jqBpa@EXa7%h5>X#aKFgU>B}Lv<HJ9&A(5tm&ftN zdXa9-r#~^b39*yCE@C&(n`ptw?s<=&ZVrSS_mCY3@jYzcXteuMz1w+lCuAQXJbs|j z$Y;CKq9)7<)nWFsZ}@sWD1@@Bn&k5?eIP|jrxlB(%R$iib|9Dkz0VU{;@T9rtaeFi ziL|`8E4w^FYYx}dGT&=>Gb;`s-Bx){cNs+zvL>gWxxsd6jQT#dD#1N#u7@Z?R^I4R zbrM?8KuV2>TSI_skx@_9C^;H4ftC#0`&wB-0X=VyEPqdZaW*+gtW@>f^(|XHit8~H zx|U-22UvCr9<wClOH<y_S9Hg`9OEm;<11^?wRU~9HcMqN7JvV)(pctXO}%vK_B=A= z<s`n`Wm-)^5h40d6GGw_P<+jKB>f^`xJFC~3f!j6zRpgAr&tgW`2+I#+q4-@3r2Fi zqI!6oV_0;+<(lfwlVnpaD$xt4-7R69&?yI5mtZ)(f`~sC1|B}rVz!cChn}aIGQXFP zD;%HK;o~sBf9I}3r#$}i7dnmb^ys|Fcg;F|jsD}y{z~WpQs}*L5jtFo_VDC>>}H~+ zGWNPqzVnll>vPI>GoPA_=ey&gUhAo$S^r?Ca%>_?u_(8+QG|Go@8#CsbI*IXc;_xp zq-^FLWzt-XBrn$!cf+tnIJN6uRtQ46PkCG`in*+^#Mj$F{@HeIiAZ?WDL>&(0FSFD zr#YoLwQjYRWHQzJ+H`u}k*L~yaRn=%<_?RQnIBQ3iP`U`VuPA!9h+{9$r%P<*6BvY z-)^BtOD=w)vQ#<e!qY2ztN-Ps_X`r82)FzfuBq&=2_UFl2h)6*7%XPWql*4bK-%45 zaf-_>v8vT7?iXyj>!KbSGU_hzbG=bwGgW+PxdL}`Ei!MMOFBQ(&P*F`?kQaO<&S%u zFP`5!rqnU9oN}zoIS9>}>2&wY6@wI*enBl)+_@fqoByhfV9=fI^ZfT%nAWq<6cH7P ziFT56IA6D_o-IAE?<IK;{O4R3DWY+kCG;=)*6V6K3R)@z9$|Ka<Wso#`1li<a#1HW zJlpkB9S2Ep_I!W(k;)T!j#Ufng`o{5<s8@iX~(I+w5LFgXYG^J@6+u8<iiijEP1BR zIsIsB%T&)-XM>=tfjY914mYI&yh8oBoM?VH;|@>lxU;9p&bv_(Hru*4wU4Lg`8aIh z?nlAKY_Ie1ikPbiG>IH{4s=naZp=E><mrgezElQUn!_{Z!R-)1M%E+~%A}`63vtFP z;}w1Z&J<(=Mdmki+y&#N9d=~Gmp!6wJx#i1+HE}Ch`t&d$z6jK$A%Mb4<!a<aFo>g z1)}N9>en_AS@jc7r;VJ_-?B3VzL67!TbDm%^{siPL~-!e&DudfI%|vn#9=u4@<`Ez z4THjEJ?c<#6~mK(x4Q$u^JRH0$WY~0!<r!>=Y78msl3~p&&E4ANqfj5sky)n>BgH_ zvKfurE_2R2y&PG%#S<xQEV4B@kfsK^nZZ_GQLm>GvZ>JD2cdLzdIo|je$uTca&46h zz5wBhtIq5yv3I579(SUrv{d!B$Zs)M<*apX<nS_hv!{Grf}~w$-gH=a$96<W+}y$0 zy2j*Yb&RK7jFF*dbRtU#|MzBXE}4uVgPyh$hQQMO)TBab%lhshb`|=@n}{OI%5B%q zPIlIURk2+uoAr)QmIesr)YqQ0>W2E+1^jwWkNNc-b-WJV7tXC)(Zf#Ypb;YrhhYS2 z=za8lA~{;s<x#`<e(YsLU-$IPTKrm|>JMR|W>th;TDSg>PR{M~4))X7-Gd2$Kl|cc zPh&l|E{!ZoWPRwPL)wY1c@tQW@hc=u^tytYt14s>-?_tM^sT9i#~-tZY|rIkvlg}^ zfqZ(4_9uT6%vf&P0l4B%B72LCDs1zTlgP?Z6w1r#VznIuV_%>%tl1vq45$Qvht};Z zLLc&CgOUR}WZ3hYIKrmwSpHZuuMItAzgQXaV5a)2(NcY##MkaZ+xK5fq0nL;^yZ&L z5>dNet3vt>oTMTrUboHUC8oMOK<*gh4ls*UeJro-Q5p1;*!#vJ558fKQR|-Gb^SbT zld1PKc75B5G#@e(_3%Il{|qJtAo*oM*dC3`36OP}KpYDUg6hdG-CHPK;R8UMRP&L< z7696SaOYX@4vRsKnZp`@z;5jn(fn_yU)qxrjbGEGm~0^chz*&?(8*Rg@OygeE*<he z(h9;C?W^Yzq*=FL!v%9^Cy#vp0qk?m=A>Ro0x1s}&>kuK;mMyw2=yi*nFMmFZ_iFt zwyTe7r|Y8@S@w$q|E2%~ezE_<BJiF+{~N%yiaZg5w)J5}^+Qi&nFCpH?d2=`(<p@M zv7fQ15fJ3oKH~SSK2308f~|`dj5ELw9gaa?_kMtnSWw7~CD2~B8|)0_%Q_47$6hKq z`-DF5=TEK1Ym#GQw?K`P%d5`YuJ3op6Mh?o*^~<Yl@oH~XIZz{xtG6fT(*-tfimGV ztg7jG5DXzwE!*V$R-tn6OofQf#ho*-UibG6{Q{JIQ$B9G4c@w$IDG`G`*sPx_<l8Z zCou6Wm|utemiYM_(tjjJcc-@YL~ZAX)AZ5mPGHhm!Pq(Ef0#d!hd`j5b-GaIiNe6# z4mnb4kzw&<K8O7`dV}~q)${i)QaPZ4+Os-2M|GSd<mb*#H(Avx)FO@tuqyZ$&I&;C z>m!25?mv<ok%<2M)`t?z3L_^7g0t85qEx561MJL6-H!%H^}ko3J4wFYC(V`Qb0?x= z{X#WKw7Uib+%GEwF;$S)pG0Y}U?Ll1hYzr?Ow)wgD{a8};{-x3@OoGuvZeSwT0n@7 zd${;<QuYfcuPE~DlP3{G)0w46l*I6#M5|Magd@Ngm_Y3$LI@}Z?IZ!ZEu!AP?Ayop z=aM8NxC!H>Nu1FkgXK>oR7S+<@i&-K@Tb!RCj!m6=(9pGK;Uxb+Mgx|*n_T3tuw~u z$|iofL&W0#Ugy$2Ex`Fns#5+WQkY;r?EaG|njMqo0NdSi1u|D9KZR<*i(eA)I)Sc) zj>}cYfi|~Td+ivA<y@o2TyTm&$-zlAei{(TF`bc#{fvzKntD#f@Cv2^IaNK(75B3I znKTd2Mg-ug_sIpPS%Ew{0Mb=W#&~<+U#5Y05*!kHvix5%wbz8Z)u8=>;|TOdPFkCU z?~+jVR6D<#)D+@6^SzCJlD$G0Cdd)Id+2ghjnla#?!{g{5mONx3<&!h$g!f}>e|%S z)}~t{;<DeK4Vl@6%&kjX>WK0u^9K=`kS%g~ev17ye7+%^B4Ma~H04%O*v_Mzvb(Fp zxvu)JBPY|WH%42~H_X^+%pha3SwIQ^#eABG{9fU&2qd6wfG|x@A?TkU{m}job1OSA z1g!$Rr3-dMUA=(=A798j90Md<p$Om?M)HIYHe`<jW)ac>F#i<8c5Rdk@H`*z$9v$C z(pRN$x_QTc5`FWkg`d5IV**rCCp~J-ljy29k%l*(_t!P99TVsYFZoXQVMo^AU@bx? z?64u=tAGn+0ivSiEg)_X*g3yvslW|G<&OX<c|Qy9GY1RSLRkPCm_@Dt4##B$z)5E( z0NeC6bOM9iBhlU|0#<<H(NKf<2~RZtj1sm8%?RdwRNYESq>VbQavZ>O!pc%k>0-mc zxM$B`N1j$H^kJJ7_7m#05k~Pd&%BfvxO|@gH$aOMa2E|!cAow~F8=FvfZS1#%K>mt zWe#CU0bNKmpu!O@dW+Qtmg|Y~*vyQ-EA9=V)QuWtmC>44FmcfpcJ@q<K^i$=)P1KV zw)`s0FFx9Sb(Y#BXY0<x<6%c4fIf>I45;h|xj{`OfGwoV08R;MvvVvAr$S;z9e^Zd zBT(qz^6i8Wnb%f=7iWS29(a(L-%k3O6ZJ0}ux>?x8Q4s$(u;J7Mp9b%G^F6nA2o*N zRzbi7O5~&lAyTDH1TP^0!q=6sm)FF$P^QV>Wn|KCe8_qIYC3ienEU^Sm16F&VmysE zBZXDqop4dF{cL)Gt4}WYZoFzZ{O!pTa-f8LB`D)%bBm?)y^Zu<N5H?#=ckzA|Bn;( z00R#JJuw_3sm7tOtkd0cpqBcJ3}3g!TP;QYaipZ}a(hr}R|{YqUxS`aUsdZmUL5`e z`+v1ggX}oYftG<6f!9w<7qBWX0y%K4hGPu^sG=>c;Q<p2qWImj=@!%5KAes9b}d#C z*EpV_B46aN@4?VO;K5lAv<SXL?&~D0JzOHEamB*X_ydD=2D4vL&70m4l_h#}hY9bb zTOjYtre;V5(83(WRj7A6m@4q5zpkl^zRqBUJV?DdsO+*8^JH$Svh}O>R+9%bAw-w_ zL%s?e?sQU6;2@n~$_7!)Nqcf?P9Nfj*pS(z<8U)syigmZbTaSA9ZDBhHzV!aWGY-w zs(bu7uh2HAwCJ~KSromKNMuRb&K*lk5!&9XLpnW!@jjIUf2kzAIjUk0cdIdOwk}&` z>b_H0*iSJzdSEbvy#g1THT*gpt?j_w#jT(}=&y}+`;(}Hz&VDrODFxJ>uBsXSdp-9 z?DnkUwp_=>`fD@djlG!dP-r~&UMukp2<d?*<{6kCe_J6O+u0TmEo!l1!8Rd2SbfJr z66|Fjn!U0d;EK&}wZFN0UsKLq#clfL9a%NmvajLnpgd@T!Dnno2`ZKb;yagDj7w1* z5o!Q=E-<2;6g6aJPbLxj?=B0tu<&dpyLPSeH;b*gg%DTue}`EE565SbJ7HEJ95<%E z_1Nk)EC6e4FeX0h(iZJRTaiL#IyKMr{6k%a$?J|mm+<R#B4j0HE0?szVTI-XAs)B( z<&(wRTW)!$lxtaZRr7WY>srLuX}VQxRwmf3Suw2~i9uV%b5ft+{EHJ>2aB|*+6+B6 zv~rnJ4=VB^N;KWAXbM`g9Z<`CTA~OZkOS{=N*g)-fjVZQC6?ab8Mlw#B1T2c(cr=h zrlAyQo}j?%mfxASQ|yNvdc=$02#TGgj3REkFK_>_;IMi~$BP_ib4S5Dz&L&@M9CE1 z99!~A;RZ5thrn!QB0A?UGa}|>qd)QpuA6ST*Xm^#gXW8BGP_T9N9#@V@~04O39FKW zd#6z_`<>TtMt=z4@Hil&{kn;BJ%b!;jX|`hM2Xc<8>wyXotV4Bti7d$n6+JC(&?JL zSCuLpZEK7v^U5H|YT;yfMQBjqZU4JCLo~(JbvgozpX|Un$IPi7gWXiqA@W*e#-y{B zFygSKh0j1W_R4I>Q$LrG=1(2co>yo#J{f{+FV&_?to2Op7OLNQ_5OyWoiJqN{fKXm z@hNks+`Z6TY>od@Q}rh1c$WR5vA}lSMrn7gz^V6`<mf_ogLK)6Sa}|h9Un4-a2-Gf z7n^7UyV$8g5YRQ~suB*4MqXIIRuZ}W82j{txX9I6%_241>j76y1Xo_I9rnH(z4_Sc z{4HahA<)ObaU`1pUmyT)m^_e^_fb|^HaY8HI+06o?&3K4m0~%GYR5+!&AfDOop(fw zLSH&RiKe3z<lYuyvY5vSc(=^Q!m2_ychRwtzTjr^^Iz(&CgdsENt7(IilfIXHEsmR zsd0RW7A6Ui4S(pB0%2{qGutNybBIF}Z+RgdDHw4;y15TS+KeO;AzXH-_O*J44v+y8 z;Yv`-!48g|=J`&-R-W}k%e4;iTXIQB+nl1Uw*vYfJ?3!8A?vS#Xd1Pv=ZSAAsRz}v z7*2U*t^ta~6fSFKcZ~<5JG&+gDi@YN$9RTzugQ5aCBf`M>a%DscV;BBHh0s|pD4ah zXB>)NuNix;b^CoozW<XUq;;A$i6e+g;SXGvGM49+2RT@~W(;L1tsOILnWCBZEN0vk zMHx1}(l5OdaqnVUR-f!Uxh{X>MVD)ME8LZ-ouEKk=tNtB>hOlQf@nAr#YPuj=F=sb zTgw_`Eb*zh^O>gLJ;O5WGQ%;vJ$6d}0DM~9^oRXCwZA?Vi8`n(n8jr^V<-J3s<BE* z_&{cdN<T^%%h1lBL>hJW@jxMOmVx<$IBUb`?c7?loC9XeUmDA4UXPPUHR^4A0a5Pp z@r*a{iwpEgdp4TdReRS~gP!U-G7WWiuUH?nU(I36yu+?7m;)wT4RbG0p~^md9-p8t z)HN5M;GGz6oM;}}&Z}T}6jfems%)LSawV9-ra)TeZCDSr2C??~zL7A0*75GDejeYb zev-*hy063piEf?$0FdDcW0M`)_XDs#&JXpp9t|Z+7Imb*4Vil2CDG@3WrlmWlMAp; z|1rmywQv+67o}XE^m2E)B+4rpN$ZJZYDdkp;P|z}>jHuZw=A_=d=qV2bW8#=zgf=B zialkftq&qf;b-EF?^a2Qd--H1P}biayOkF`jP7an?SEac!NhNGb?en7`o7FB6A^-* z8c(WpT|EJqYh23C`y$~;eNn+Qfx-xvcOv7@eEI=@V^K)B6FgGkw{vL*YDhQVy4!UC z32v&+xXkpGXL=kpwJ2!CVS8d(B)srL>O{uW)<TJ1e?y#BO~sIwwA&~uduc{8vGKc` zkkir#78-9F;_}X@|MrY@Fd}N;)-WP8T4p~_3uYWG_>{x2r~&dt*$``DGTL0{VYlTl z6m3?VBdgeSDHO}TkP_RVRPtScXjlx%(u%z@+;bw)sqN~=Vn43eDL%U0U&co&%7|Yi zTj+~@+f{>HaB0z|_2<GNicQV@b!*1uz?tUu6KuD}_Iobpgc^=;N374ywTxceU3i12 z;7;?I6}(nzdj5{l@?o<JX)`u?0-e`3PYEZ%rF0V5v9}x2w6J8!zR~X`swK#uu$gR= z*FrsxIE*8tdX+U8pZExWp%T(?Ar2g~V!)N#pfy#{6v3WFU`FO|4J-tSikR-ho)NhM zJ!u5O3H|i#%^bn-P!LD&kNf9e6s^nD%vf2CGgIryjV?kBO#F85@m6H7xiy(68|%ie zEbBMG`K?4)uo>WVR5=+^s3fEfC14BnHXKJpCdpY~GFnOa6K~V5D+ilFNM9E*#TR}q zJ1EVINky1l%e$(LPOisNx3FEs1Xmt*xRB)Gx#onL;%P@3=y|55_=ImZj-u*gR`%p1 zC}rY2vLJ0758f<Ec=&@MMdpa{oRW2n<HY&4Ta(ZU4UAoIR;6V0(o~vs-ks#ych_T< z@nbPQ_d8|IT@jRIa{}RvLDUUuML1-q3^K^mesiDw;(7*4JgLjI$>O9;%h}oRO24qh zx_HqWcedZwyv?^K^n)D*ng?;ACO84m7r$syC2S%a2No33U`?jG?)6G_*+#x8cQ<>y zk3)?G^!@XTGBuW0-Ce_TOWma;t|cK>?OGW(%gY@Dm$~h`9d^44)g>de?fQB@EJE}1 zmTXEbbX%nyO*XA`L!s*808H1XfDGqFC*IauEeS4=Lao>FsidysYORY#+_Ll{3wAs4 zG_*~0{>r#>2nX;rf5QTMh3jdpl6A?oXmfVbwyBWMRoMH4s12IWbWoHjk=pV%1NF2o z0?dJ69H<pkrnmNk^d}Ox^k0kz6xp9>R?m-^iyw2IJj5$tRia^beKze=@@2ErW_W?R z5N1+Hwa=q>dqwYxw~LwVA4i{4O<#=Qvpu?zNCbXn^CNzETjcVCXW~S|a-qGKDBlok z;r2>e{q=jSU-dfN-=Ip@4p6JSSRTt^6me+4WaP`!o1BVVd&tHa`Z2jbhm3~q23nx7 ztkK!@9=~3TjKf4)l+Ek(E6yx)%c@#*bxtS5e}}#*fB(P=2uS=psh?O5{Ka;R&oa1s z*c1S7Cr8Y0ftZ^(d3vY)k-=5u85wm8pV<GwgNn`eQ#$wy^4JBZ<G}-qvUN6$dxe1F z;V(9>yIBYu0N5+Aq(5%#<3&#Y&_7uRUbmJ4bjkcc0U&T|SOI{*DZ>H!I5moi{R#F* zzfJo;$Hi<dWdKs>S5Z&AnNTG%zwxWw@{t_O`%nX9+!JLs6B9QrZF%h4zp_Puod1(8 z=KpUW7IlICJqjbAq<w?~1`j4YP(T7i^Mg7p08B9P^$zm~NG~gst7Hc<ETYCD2?u_p zdKBuiRf^w8{9os}QY=2LeXV6mJll;cAxc2?($MRS=h`{?zs)h$R-X_E!UJ)cIEoS! z>^l{F-WaGtVvWUf%$FXX(rbr<agJht5)rIMk6nK9-gEiWiMUlPS9Qi)Vw6_KIcfHN z)?#+TwP+1O;1&=~2ISoS3N%e4IhKl$x9WFWl&@&1T4_lgWK9B5A~?XHxqsHRoQ*@2 z!~PM5F!<+3hD-3X<a+3D2k+l_wY<yUiS8%uKOlezqq-$s!w3rwZQ}92H!e=nz+K{C zBonaHTF)$H1v%y4Zf8<UF?kn9TYNvB(@pUWvG^)*<jzE_#yA%cN--#JV!3@6Ob$O) zqJ^!*$R40jQa8=vr?oLkW_oW+m+D=RWtN9ft_T>h9E$u|MQ|p(@hj><JLq%iAnuG` z&*M(CA34AH2v3NSpC@HKM-){9%iqHmcbUb{G_s=wqB+0aiAHrp!g6Z2$Dgf4bG{`n z624DH-uM#mXk!wv`)#v8sLP|s)$RFR7t9Az0tukmG61^4!1ibn5iJ!BkuA4jc8=$= zeVF^mFMn-bWLbnK{|vXCjh#uHQQ>R;Z4~$YVi|&&Tz?RHwSZVo)b?7G-AOKB>iHiA zaRH-^4}JnDbliautB@z{fay0i6yMdneAP0}l0-U|goJ*dPC!5Vk5Pcy*?*j?0X#@U zD$RcjFW7ceL(o#pO64&R;$7;7U(h_-UcGQYbFS}a!P2j%$lqeCb^sIj&8DZX6$P2S zV>_Bx6C6JqRGbf-YgI;8Xwh#$pTSFrJiM>cf7vY<B(eT_ok(O%52%O80LK*dtzT+< zBK@EK)t@k-_?N~%%YzZ>J!f7M38Y~=@d3@i*A46z$JhQ8p3kuF_X2gPM6Eyn(HlUE zzdU)|Gl+r0)yUXG`lHnEK>x{Ks{2a7_~#a|w|szl>Ssf<1mK_l*a?L#iMs&Wr9JV< z3C1&BTs(*jykXcikyAI9B}er$c0EMTf13Ny&P@a2vj*5U#j*vhcNH*#9d@9APv`u1 zpm7Ph5{T)MTL7sa8$<p%Bv2{x-+nzrwBtAp!d>8$H_i9g@}F&=a+m4nxBjhPiWD%D z|7o6bwpq%hzvT86=Z1b-vm`Bw9G!<v+Y*#()z|U1zbt$1vKNCe&g`w=&5~DeDg|Kn zPCoGICccUxWO-9xEaxU&2TZbecGrb4G+k{!y|gNXBs~~tD|wxO*Tv4gQ)n#NkVp-P z?tUli&xaP-jQsu#-gD;x7X*?ZTHiK*N4#n5Q68+<d}RlB-MAIu(hT}615GiktBj{$ zfDY)5?X^{ViO^jB{Eaq|_8hpcEa`<_tIdsmHN)c`E!;=Uh%T1ADm@SXU@)&{>~848 zSFBcaeqA;*!(8gjckYBLDlWbFl9AbDb3XOy5tzCm(EO@z#dLM;07R*1YC1a&nXu-L zM-51IhLyQ6)F44!PIAg@DS}*pE<Shd@vX$8Q42Hu%n!?qQ`jU0JCF1oT!24#0e*FW z{pFU}2_&pSUS3el?^F@JGO^{_Cs*yb`-bbL>vip_J95B7K7dOv>BszV6ALZ{WtD=0 z)2}Irjd;HGB)93%D7KgBh+A$L7p`-LI~J2bd+mD5xjsDodKoqLnR79-swSOH)oFJ8 zc8aZ{Vyyn!aJ>D~>Nl-&4`XDCiZA2I0~AEt1Et!nXYzU&)VtT|%*1W|HZc2*o7;ih zak$d<2HCcx-5IhErG^D3{PBrCM<_?Wg56s8T|b7p82|pPBozf0hZ_oH{uZYNh+J&- zD>-v)D*GSM`yFh&gqbmMc<8a-JT&=-58_4zvQi^5!Nn!7WLu-volKj*M&%sQ?X(oo zMdV{KK*}Vvc!Z}$Yg0mHMw;o5wIes>j0p*a8%)^)?l;D7)}81|O1f1p<>c5fD_RG& zJ&zNVHnYR~0s2$mA(zGU$vEkL+qPh9L4Z}ZLx)EaAMZUS^((@pspD?(np1kt>L=6p zkC|f>QV0?Y&;*I@Tew1<*22o~ZXHpaeQFw$KeW{N479H4rc@-RMJ6&YC4^5CfUrD0 z-f(f?1sgAp6~l}UY0O^><R~}y3y?+IMreEHCO}8Zn+rST;>!wY9>lDZrYPvGSWr>$ zx#mKR(G#udkWNr#N(68RGU2TohKi?K&7wbnt%vZp^BWV#2N9|5&x?fy)k&Yqecj?J zj+rxwNvF-FXum4dv*w0cy<A_l^pRGw&)L3~D=q3%ZPMoP_CRRcsbB-RLrJ+(o!q^) zd-MjoeQNaD_|mdxfh3!qdY%~f&1J5sSb-*Pyzps4le8nE*#7~J(Kg4?EGLo2a-u;# zZ#rGGm`eO|fm?UlVpu07__phf2lEUDx4&))phY?WzoBnyO)O*L2+58?+|w1Wp@w_K z4OL7bS<VNd{P#Rc!-u79YJb?AXstyhZ*F4WC3ut$SyE!{BFBz$NCZszl=1a=q54kc zk@9k*I_KMv)$%`yvO%m^VN-pPj^UOQMrk!=2B`jXH}yLQ?xBJUITt=k@%c$-=SZn% zuJW6$Bk9FT{!sFvZ?hZ4Ljp?3waw~AZ%pPYMqg7dEq^U+U8xht%f7)*!C4!x!jpoV z#FT-<fm9XXa}QUlsT={f=uE+EdjJVsV@<NAIz4iCIpQu?m;-jkyq#1)K;olo&4*_B zblORcjzGz*@PoZoP5Dm+*@%Eo71bJEgGc`Ckqvf9*o$%-Lho<YL^wL$`KTpk5RhfD zr3~lSZ0466N0vre!@Pu^!z<Xo)WfFEqbFYZLkgh70RpO+Aj#!V2#<Wb+J@wX`!CEE z8aQrQD;j3{2ir<hBzE9RF^dOLSoWw2Fg;EL-51n{+EQO~=qmz5uD;`<X5X?u%;bEE zQxPmv@vYT(^w=o+^;a%?n|*cOf<+MXc#eAFs%8hgC7rjjabH`d#JD(oJHcuMyAiuS z^kuNEj<#SSzdM>?taUj5Lm`YQ(>)SiSyECBm)x;POLgw^NMXA@^5g~AbL|?sX8xLH zBHt5A+(g`WFqxc^jpqj|$G{sQwu5`T9w!>NnHjd;eWCBCU~}x}D8I-+q|nJs#-`$` zWXH~co1)3N+)ttba|IU;?bSKSI;WXS#GdEI+C}5MqGf!nIKR2^tH}f|A>Fk+^j9MF z^a_-nqfM0x46>8>BsJZT?+NmRRx_38rYis`AZud4X{%H>AcusV_WT-++vs)MGcDo- z9lJ}vtZY4vSh42R*yXeiP3<*>vBR8Wzfm8=pGJFXu--?n1|wDmOL9(brlX^&Hn!;K zCI7h17wKvk&(r*f&L9ez#HYC)HFipD+zi5ik+Jh6a(pKOttSc_bjMZ&i|n+HRVk@T zQJ<Jrm8)Lq{cu#5tD3C0nG!aW@T`S9Skn|)S&76*g+_?Vxc71us?StcRW<JT;U`Zo zqUeVy+7-C56eKA&qqiZ{ye(M<A4&2BkPg0%l&7QSPBrz-rgKK|cw0aeKL#31fPFy* zu6~D)*D<X&kREOahMz)!eqUw&cEGQrD^Tb+al|zKTdPRvpYCiTI2*!!;Md#;$VzE? ziFZQJz7-=f0FuA2fdazWpUsQ(N6)?ktk3~ZyNljyhs47*|84t5B=pm-PZ@X=-S8_p z#=%w`D^16dOCp|tWe(8F$q4ZI``NbX(tovWg2WcLw#@%H_nL4Kz<f+ZgFm6oTPzYE z1f)GmfDwNbw=o)s28hG2mWfxs%K<q#5io}0G`05l%$tAh-~^!lGaZ~9i3IMqAb+sE z{tk4hJZ}_mwwV*rCNF?wN&u4iRd|EY2moH7huZ$k-x?HpmO@jMtHU29e-BZ*(%R#E z8P7M5N%{`n#ldz)V8L!FFzlhosfWv|?jSK3z{OU;FDodNa4Ly2QX&KwI9A6yO56$! zc{<BXf1dNZ&nMqso^LEWcn-52{Bg<Y>CY@ZrI0rvz?eWN!A)2y5j|cr3(gDO>_{){ zS?*;h)yb)mmu4}9<J9*=j_{zvHDpWa8P^w&a}xmTF#ZS|03^9cO#&?(agQfFTO*p8 z>XW)*m+W&Gi_t}o{{oKEfTBDfu(3`9kZ^K6kf|>M<o^GiE7t(Z4d8~r7Zef10k?gY zgGf@G?NXX)n+7i_Be9q2@zV+r3MkxM#Q=rCKxzJ!g5S0Je;b3jA+i!n{%)k=oqt#4 zr744w^CdTHQ^zpg_z=)m0!*FA?mx`m?Km(ze~mtF-53)TLS3hP^(yh85fabsOOGe8 zpX|+}^nm)-|C`MJejdoK29*Hmb9gIIbdZMUD}yE|*M=idb=*sO`Epf^T#vkp)z3P< z5CK#Ff0{o)kN?^q#8<p_W-C)W_axbeOKj$z?7<Gk7lA{|P6ccFZ}+%ghl2g=0Rem& z8wsxq)>D9kpc4{dCj=aX>nGH@uomuOAUh2lzxgrXr~LaKP<8X)&FIeq@Hy!0UKHi5 zOZZ+)U8~D(vglT`y<+~#O`651@2qdQ!MWPs4xjFC?~HFK5xGE&e&AA{)D68z;?#^$ zn|}TNuoLk!OmOx}c?+>PY#N~+cF)}7+*ja8{WiwN%#Jw*2d;6~Yj4l}JP#WqfL6%p zOv`(q9N^a(q&fSB_A6kADS_~FLJNR4Pj719u|yrbF@E{}hwFwZ3=<AP?ye&b_hB8` z7(0CMz^SXtia_B9ikW#Fw|1+g9}0x0o=3rg8r0k!ghr=mQVT2JM}574tV=zn<xbMt zk65Pt!f=)0k1v<xMK(K2a2oBPOC|V##n?+Yur~5Fnl0ES$I(kd?Xln_g6j^$Folrh zOqX;1(6yoRuTj*#_m{un+%c^NBcR9H<oK(&*8z|Zj$q8EPjb?Q8a^BvtVz?~RP4JS zx)t_>o7<CIpL<SQd#P*>Hd(*0(<U!zTw99i8p2CrcF-kwPAaIxil(BUrkh_?4X2J> zU4~J-392fNHs)GDrVU#Q4QL3b9nw15Zq)IZU;UbAW?GcX0snWnT%dxpx#Op4Um;Mq z++|ZXn^%hjp8nhVP>AMuo>r=3rA#FpREFS>dsQG~D4=*{81hcdY+V-!P=ngRIQsw< zl=qi|&lnt5Gpwd^4CuDlNAV`yUABMxwhM)~0CQwow%P;7yPn;j9vJ7~ubn3Nvo4;x zTa6NA{B^O!F?(?04JIfyCLvEVf6{ak66ruwP;mNUR=%P%jn4`Hz0EEE>VrTFUMKw? z=LQ!Pi~`8x(uczA8=3XS8Z`27F0EArh5(*cBxF?Xej&ixpIJt0YgDPmFmM%GMqIxB zF6U+T6XvBo?QedI-dhmAMR)}0DxMj|PK2}T96)O_n_xc$@-)?sF1}){*nrsgHRcoq zD>6fABO|+1Q)h>=3~C}&|0K%8!8fRz`<ocK)><+Oit1~M10j~#jdRWkLq**K`&Suq zI^XNIS6C^jE!^6F{#MeIPcKA-T}zCYADVBI%#_UE#2!DoVVK8IgJ$8j?1zS4TnCkE zf0@6q4y)kVV#JaHPtOhrJcOR@kN94wONWenU+u`=toWAaMUT2yOX8J%VJ1Q=wgL5l zJ<MFCly&7W`vDvuds}@;SQ8_zbOCuD3PZCXFX2_te$27VP{}PFdwOrZsaex!@yrcc zW#)VpsnD&Qy72gQ9*sBg^wIEg;aKebPFN*RJNz169^;&V?r{mu;0iqfqXMdm+_O!= z;+xbxtebOcu*x3#H#QN{k21u<7#732MEi(+uo{Fbh9^{b(bN3EtMgEVI4pPy+^S8C z%hR6l=SD!;)~CP}cXw>;Y^m<q(Ui(Pe3q?B=pE(=R+1$l1*hBY6%8;e>Nm^j#V{p( zWVWJj$>Zj^uwEIag+&U|tnUi@RK;#K3G`zO%iB{>pIP=l54ZA!7HA2~>Sk|D4!IVX zNd>KsCaHU}%0MG#cJ=cM^$UnY2~-exmB?lfR%KDL6E;Plh*1!$#%Sdp+qEFCKpi|z zDVoj7re+XjQ)>xro}vM)-Se&F%RMSWy;Ls-)5DbETTkSGFzbb^a_tCYxls{YIR^E( z+6jUp-<$AGscL5surSqJeuy=%tecUGpVeSeJQyO{6;N@M+L;1>sWaYcT(C4g_;~uh z=?@4y8J>QjPxwzFy?R_y(NtAZJ`SlG(y`cIH6lo69UMHHjqM{JsZ+TXkLE+PvW{(l z%IRM!aGI=1)UCF`U*1P6H`=1pn8RW|qNO++%ZB?JjE&3|mAvK*H%nw5KA5w2skobF z#K-x*wYya6A-9xaiKL*+`>}^&NmAW+A|pJehu>S6IcX}3TJ*W)iTI)1{U_+TQ*2G} z7a#_ncBX?xvN~CpPp&$AQqR-m>$nqPP|y;s=I4Ma)S@X=_muN)V^hEoZzbhHTP;rW z{R2SFL&Z32V^qWOK-jj}-biuQ1vO~O?Jn}hMYEa96iKY}z5Y8Amy?Fl>%g6{SMZuR z?T_DZxvi~%j95X)6@TS7YW7uis+uxF%IgrnBnMRdxVf552IH`uE^Qn4tod^@pd39= z5_*W1Y>SP6ml|)@W3pOPHFML^v%2E5=4hpb404$^i)ab-IIA?{(im4{x3r6xS?NWt z_w<^C`vCO3P+yt`;JN5+|MQE}J`E}#9Fx6$5wYQT(I<0^Sf#}&i;CotwQ)@5J$pNQ zCh?o7EnSn24rM9|7=?N?lYUNAYIc0o+K6%DCv+B4yr4kHtl;KMqS;ccXbS46lLT{M z{Q9G?aFSd-eNYj}P?D6)=(3q^;z#g|emcM5s=9dIR%7-mS8*2Olm$<W`9kPRp!|vb z0-h09ZjFWq%N%4q_LOHbckm=<B3GQ+ZrPhY&FX;`XF-WVjH?~8V`QTS$acuocm@@& z;#~9b9vE?C7}CDcyoKqs0}h(1kSz&0OsOh0?M)DSsCOhBm2m!~Ofjsb0V>;FBp66` zS|lfZ@&H2h-4`fb*7#c4$Ej{2&U$lBL*8m!)#W~&Uw|SbIijyTASv@Pqj_KW;*)L` zpZWHkFc2l-+}iLOn4Cb;gECLoS8l8WjPO83(=(H^vjW+}GghtQwIsB4y=p%mx_#wP z4S5{S^?JPM%3i5{n|{#P)2zN7cg^fH3xsKX?ravT4OdC#3i^15&Q5v`{OXJOxeT3X z(*fFuWV(hzw7^J#QlYqj8{b$ozX6Y#fkQV{mgX?RNNm&)e6tKEg0VXQ;TGkZ_;GO` zG#nskCxrk~vxd>6N>&A$iu#6{vXqBVwK^ZlN8!#KMBy2;h#s|-FBxg*`A9fJlVIRr zAZaDed?B{fp^2pdIl8?^!L+`X19tTLP*WDGE78tfU;X(H9|_gRPvd=(*cg%?79<t= zOXA!Y|0H6;X#ks~a0^$iQ4eos;~Gaa*cC%xJx$Q4t!fzNoEK_{5%RBy^`{p8Qm(`> zx2f1IAqHk~Jl?J?^fv{d497U|{APl;oJz<-cCM;%)q9NlO)k_|n+oQno^utI^|=}! zcVObp6;)GG+$VaawwNl!IxNA{j-eGY`QwM#OhaT^vbnr?eAJWCSU9?bx&Rmcu2ZJ> z`TlM41)f(OiVazz%btz~E&YvG#HFQKP+LWc0#tcQe(KKed90vODz|MhY3&M(xM@32 z)a?0|Ixj?y#mv3TKDu`T4ygh7<Z4NMlk9lM+gd|?E}krzyj$5ZbZS;yQKSjNb$L;8 zA|G)h#>0=whw=IcTgn7^%5AOekmeHZB&V)u&UmF-@&b;U7@nT%<kWN$-vWtohuHII z`qtPgcu*=(O|Ge88f!j+zmLIaD!@GhuKY<<7{8*rSfOD}Mq+&{1pU<WPO(3rKWpN| zwH8|7pJGa0;oTSDl+9>_cWZ`SnDr>zl*x8qy@uzr!QS!$r4Wz$Xqry8r8sY1!&sKF zf{FIWdFprEp1*oOeK^{f^ger}E|IHvdwe6+A}(>sYrGv>B`OobDVq~q0wz}va?*1> zFyvcy&XuU*ho5LlkF^>g<r&bn+Nq894N6jq*~?_wFMzu&4u*|Y8hMO4jKGs*JFpQq zjiayu#YGS&#sE=`hK6fuFzO@ME?3(3*ZMBD-d%GZp{LAeMpEpjnKo$1SlKUVusD>y zO|N;D5aaqS;`9eD0UOsOhku4^T$~R@{xJ_O2gFW5uWE#`A|%_qM{@Mhn6ZvW@~wyQ z=IuU$5xVX|72NkM%1aiiU%{4`MNYjz$Cpdm<jmV_AU2-|+mvrF#}tT7rA2YeZtpn> zLn?1(4{N6aR1qquq;8^;bV6Z6CbkrB(J!nYEN$RgAhxW_AEUFn67MXD6ix5}pMkcq zxCfQ<NBiKDW8|WxC+!hQ?ZEeZ|Jy4Hm0>~OC>OT-MKj**)4~W;jidw^#p$sNrqBvV zRT?@GcK;+&U$y@`$Kfw7@o_@SYHyx$Xy4I6b-yuQW@OcpS8_KjSwJ3<0#5XxUY!g7 zJ_4F^y$*Hagh=1i+^lP=kGtYpUq?k<C6-r3xSU~`>A%%X0OL9Hw|A~+)|&@&8Um2` z;fGOiCCROV%0z4Hkc5K0lA|l;u!$DH)#!!L-)RI0MKu9i9fR!vk(y}FQ5|B=->DeH z1DbbVhi3MD46@z@gJAkETP-5bv$Xpk3~MKJ-%@$o{6v*D^IcCz$K5;GODzB3SZf}! zM;8E&RR_CaWd9GAg~(k`mZ44bwaSxBku#lpsbRwv_jU0jZK*|Q1Q3*vmjv2F0R3kF z(=ZOo9YEpER3|FBf)4D-y;?K3xE6_7!vInFFNRb3d$$alf6^>uW&x%qapQr~>ei3a zT{~y@5vg^7z+cTW27!`{Uts{iM)<FgK<yRY^Eu<fTX;2lK`|e>Nuzt5e9VD5m;1G3 z<4oaa29f)F`t5%iL}|_%{S@mD$J9hcDGp-4Q1Yl(SuY3l1adzCUOPZYXA$W9$217o z3I8X;XFCukR&?SZDCDf6A?L*6s1sFAb}n9O39x7W#jFeKK=@z;Y-1U;cf+!s=sA#- z`k#o(SWh&kLA-aoyuwo>H^U&i3s2vjMgrlAK?&H&f&Cwqe|6?7)<2;K651bt)a&8q zghq}dorIZ(M76hTC&zUP=9-JzH6O_N`AZJQ0cL%V7qqjGbpiqC#D_%oLyQiwEPz-3 z$2T7ldu?iF-8Zgo<bw~Imnfcl=8k;34xt@j=--(^rzc|P%<8ny19`FcfSJK4jKA&I zpTsLsp_(_ROe&S>Hg}RtV}_OGzn}MtC_1goh7GDyoZxr~Q^TO|+{CANnsaGq11FwC zxQ`>o)e-VS!L6L}X!f-8tXLD|w>sqMc>qu$pS}<{W0P+P+Oz}{UIO9o`Ep~ttdncb zI>>SKkv->+ue;oqSv*ymM4mK;;4K6v;gt?-zFFnhq(59b6EfK-9;+l}o|S-T$kr?; zKWI^oBC*M6sV({S?RRMl&Dn9Mp@h1U-2zalC+zsr01#a1Q-fr$yIQIUruugmT^H;S zeQ|E%E^9ii@vkM-{Wa%5#{RO#pRoJuV}YbJ)iE|ZkCBz@rPsp-H~@<>BiOGiu%DT` zOdkc|?!o+in_*r5h&VH;yaKa%(bvUzsV^ShL<M^sd1qGD@pmU#Am&$95qnH>4+wBw zd;|>{UezC++R=Ww5|;UrOQVL0ST2I-YbJ1>9|I4fJ#skVH1*6hiJZ^c6IkOOtL~+l z-WX#sFYl@~vZ;uRX&6sAv$mv$XDsj$pug7NG?3SJ3>7R^CVWMd{u+MTJ<5*eT>rmL zR~Yw~_x<GeI^j~Z=HrppCe~qRmwnQcw_Bf{J^SGBwD#RMeibHO!R_9=SI%+0x#&t@ zu7Ycfl8@(*-eXTT_Rq5KS78+20+o7|<n)|8_UDO_SEPH2OZgD2d%X)Zb<Myag<Dei z>+Y`qv$B~Y%E*ZNJd!@1iDaSaRhz@z4mt&(<GZ-G9m@Q~&*|PG`_uRzLfG3EsA7m^ zP5uaqx%*h<x-sQK2@zgx1QFUY3o+FMwK5GvIss8%I!7~#aF>n}vNwWpE!Q)^a~8^L z@(ZcbH)BjC9|R5)r<QpuaANI(8(3}Ga?m?eYsZES6C^IQ9XZf9oZYJ=40hM)Y=(R@ zMz;iXNA`U}5ZUwhJt3Yp7se+feuT!DO#2ucF_L9pyT@`3vQj3@H&EkpB_}A#NBSr+ z=c0giT)UZeq1GB$IiczhsN!hg#Y#rkP`@hQR4`@mBN>iX;v0&ZaXj&t7k2ct@G0n1 zbXIH8jZd`Z{-i<AL=lA8a{{$B(E@tRND#yK*1qA@rjh3A&|9q+l85@JNUl>{u)6z> z^XQuLLp{OA)NAbJ9rc)UJ&a0J4lc)Ij&wqtow*YM)jAeXa~46+R><?uPQkcyg5WZ9 zem*ype=MoeM8%iE<ujXdtE1#h!<rl9#v~C(2(GO_h=YQa`NmVYRo(yw9zEmG+@Nb5 z_S_=Ay`OC$Bd;<o%3^KQD{xF&S_{zAt0?$reai7MNPr^Ch}(9i0FUI3orpPZ%;WD! zGU346YciUvVGRN3Y3t&9s8hvZ*{|8JwMI7K0i%U3k8S;uRV7U|>w8UYXt%)3{z50B zxW$e+daObYHo*$Z9=4z96v*MPQXYXG&?&0|m#e;6+i<68>F?a4>=F6)*p&LP?3G5> zigCgk9J@KckCh}uIhI-ow6k%<*pLPA>IbV12lMo73Gt4+3X)F9-yStEN=6Dgr^l{Y zi61*dtCL*=K_o#f3m@{)j>WdhS?@<3yLkJZ>k~hq6IrNrmZ$jEy%l&*KPo8r%VUTm z0GkbO^b$L>94$KbvSXcv?+ji1+VOH+a@WKP{WrZInzDt?sUB^-Bvtxm>~tU}7`-XZ z<$lv?2I11|8sW~MKSu_=!mWnUXH+Zp+~FVM7Q@Hwm#V7an{`oEu2iZ{IWO9;rT1ny zDOqY$m&?p#j1Y%<d3yz+b9kOC^LAugdnKht*)RvBO~T)z2`LJk<4Mw}=Wid%2HDbX zu8l8OtZEqwY32APW)|}6<}O}VzLuB6JL38}R*k-0h@$mRqH<&~o)iUp>GcLz^d(h) z03~uw1+79ak(yQVPPX9I(tTHn2jc{nBrazg9(z5xo)(#%cAyHxbsma5cwIW-f)_#W zT${IWoFm1|M|>RK4m7#>8RQThKWB<qiedJqj11F_3c1e`p(vuS<h|S^yn<sYO~h1W zXZ6|o7R(uq6NW17yyDAN5}YI<o`c7apf69O_br|hlUg-6o|t(8)fzdnEuWrdqRgmX zyXO}vdgQ2ktQUyQI2uGQHdv$CgRBH_X;_~2I4Ehy6n7%qm5~Nnls5($TKq{IVpmo( zI<D%mmZ=oY@#elQ2PMyBwsJMq!X>5M*o*#_r^S^6F%nGGQ3{u4A!QC`;)slw`H(|_ z5BE8=;?mMKf~(_?=NLz&sUF0T=C^c|J-AT<&20R{6H`0Rd{IsiV~}@g#CWB_NnD7@ zyZ&b*OLvgZ#uNW4>%|Uwu`iE5*UV%}g-v|aiZCqdcT9Md<)a%PC7>T{s^?auMQhW) zvLi3Pi?CTxXoMAjp^sa?G*P5IKqk*y){KZWD0XE}Tf8Jr&kIs*t9~(K-uawySSms} z?nonq%APPPg5_W(RjC_lFfV8>nEjsGk&usUO-oCghANC*xScZ@qhXT0o0;T~i)c`i z%Z=@`7Ny<dMQq>>(;suw3v$t>?<H1xsa56lu|3T!5jL;Cxy{%ai$y={A&%~Mlan{A z0Fu)N`fYw@2?tkSw@Dfy9JMK>e#lfh>K5@ANAnpps=7B&5C;y<lPa*-AAm?bc7iiN zLmqu1t>Y2|wxkB?e6V?!J*PcBj=OF~jpp;wO&;?&=BlN5QGS`PGbL?}6fGGFSgWGN zYD{bx!pUDg>)X7^yeX?XbD!c5hE=3NNEg?&e)!XRb8b^>YOV?2_rf;k80Bw9=wj!^ zvuD<<4W1kZ4x1Gr*dh+As_VSJtysxuU*zi%{!-)KlEmkZ=8+u+GC<Jxi4FsBYVAXl zi1&vDT0`m*Mn^Ie2Wn&fJ`39Cpb2Q@SQ;vg#k5n6j*H2%?3+$Zs+?ENBtu2Jny^cv z7Ue!9PkI=xl+)o=06_ZM7SJuN0tk)vRBWOPi80d-g;U_wPOji$0Ye9WSqB9KN;ZuI z4=U`w()0L`{-A32;-h<fTyEFCx@8yMX3kP<x(Y)Ff}%<d=<Y;BM#fu|Xa|&(L%<r6 zeqE;ZmENa7&4fm8PZSQF!7SVJxNs3m87t2pb1SqmUbm8-&HO~I+mM^_{yU9S-E>1f z1H5%+A)qI6VBe#9O(0wWodFXtd&a;s+zgV5Rby&+E}R@VX!CUL#!=NOL%%{uDe@Pj zAu>Y1fVAgVAWE_ElJGeHEa(`*j5Qn^o>;8wic!9e2u*Zi{JO{k^ad6GH%ui$4f}d! z@e}~1gTbyq?{njE-;fmX^ypEy?uBPD5*Ofa*@%a02Y!Qc0RjZY<oSIJ{P<cP>=)ok zZPge>?0l@r=rB-SHu8RQotKy^m1xtx5IJq8a(dwdfInZw{sm_4(iOdcH3e2qomrNp zY2~p<DzUXXAekk4m)5=r^b5Vko*4qG7XZHh>Q$&SvM;YN-ogw?`xdW?HvEa@&cAW| z1zUkDo#{57^B2gY9oRT9_KhjxUJfqrqYj?tf+R`lP;k!ZT+*bqJ3|77&Jcz3ux8MY zD+z=q3c{<(Qj;deRH2*ATl>;<bINbavO66(iR|DX@kRH40a%@jg<r4}GnL0cpK`M^ zD^b<}B+RHiU!RDaa`p(V_<$s478yGSfo$r4?!N(85x|pNu?#i=<mU#H>mpYCMK4Sl zp3JPf0-LQ4Z1#mE7WX|+k~8eDgGN+&wjp5w^4GaDoDgvmXXS^;k|w4ala@(M3qJqy z{@f-x(2ma#{%fsO4upYx=-o-cb$0T@g&}~v3IS<xFdz&3cx784cBG<Dd0OYy3cAA} zMmi~d^754ruhb5T)6UHQ!Z;keMt|xKUe+`4`s=06ISX(Y(7?_WP!|YP6pOU6|6r^E z?%Bk1|J8x7yai|v2tNKk-w(73{PmibsMrPQ$9G74>JI9!Q(wUY|IYp#HX#bQm;LMo zNIw6QQ2mdkuxCG%ouD8LngOpsvH&#$-WoVGz@l3kAOEy1ZYA8!1Ng}PhpRuYNZP~- zs2#_UC&1E9*jd<}Q92HuJJWNpfFEegvX?@rmHZ)gt{E^UCNlPO0n|O%KZ$BUNzV;` zDIM=p{1hcb0Ez7X+jX$W_b)49K-_7L5;^)q1@It~St>$cQt&T<&_w_;oyg&*+i@Rs zkpKejm}1cAIJXnvsr=U)BHG3Um;GwccFF!Hra6q{@ihF<7--k6^s{T9@vo+X`xH3t z`BpH_3{WBKfP$^)2~#J;lm7Z_<*TP@eY2<O%<F7Mvpun*n@v`m`1(WZsx1ZZU((3N zRl?=!KZ*E6aKLW6!cRrP#u5@*3^MWN`N%FfBU<5R6KQMjBBj#Q^A<EWeO9@_(~<Hz zFGz9dX6Kf-4Z;d9S`{GBni~B5wUKF5vKO|8sp5GbrwYdo75`g3)M24a{>$pb?gR~# z<V$nZK$rqMbbM$pozEGuCC++dFLH=y@*|&p{EkQRy$fjcP<qmn8xjkh=T|P@K|&hs z^f5b8c<~a4If3$#@sXA$PDqarA~)U?F(oUt@?@I2gXY1H8^VUwnryx4?NE3yj6zNp z8`|Q__6~bry<tKOM2<TW5<`-&SB=~wOAS~arLvIArQpM^&h&>Z2StcnHr6YuK7^4y z7b|+Mtj{=>Xi#Y2y;OHN$B~%DT%)X~rr)^iY!>gW7om-AAnLy3KmWZk<cm$fCr%kd zaP@(@!CEKfyHkByt;DpvlVy!>T~_+8o*(r{Gg4n~HvNHj9?d)b;ID>(A2?!IB&N7G z9glgj5()0sPB}S<(P69mEIM2<kCQbDo<y&lNCoHqsA7$4nM0u9#L%pT2N)%6&mvvP z$H0N{%_jC*cxyE|T@vfwqV|im<Nd}q$%h^%Y2b46PT$>*WWob%LmYF3-EtuRl>d3m zKuqPkN(veie?jf5IEYpaMyOY`m8H(ImtLkcRTgT<NgrX8d_$1r+HO{cTxLov+X#?^ z**VQ?;>A1QTnlhED4rJ00W`UCfWA(O{siYJ=Wteis)n^_<!sxXzRME5D-0h!!>_cx z$d88XXWTldX%LqiAXgt;e)T?gG+-MXZICov;A~Qr=D)6%*MD?`qtrfq(t*87ESOkU zV|}XvTh=}jZESq)V`vCdLn*nq<p9Ni7S%@*bE@?o>K)@Oqk7n**h#m6&Y$)+TQ>rH z(7^3V_8ob3KmFzaYROxwZb)nzR%&^g%O`g7c|3mF*6CeD(7T5`PX?2pI+wT2S5~)> zpFfDexU^D)vy&<?vpTm|J`{P?2Fb)lm}dQO`rs~h?}JI6tY%xcwE$UpmN1!Gi@)G0 zT+R<euRdzDh+=OS31=t9i=)-V8daLvN%sAW0u+wBo^9F~j^svJIg-k`DQ3EQ{U7$; zGpwnmT^q)V6hVa0Au1q9mEIyzlrB|zi-<^x5PFeFkSblNN>%AydMDDQiF62^&}%|7 zK#1?U_x<eW@!sFDzd!Ha_g_{ZGqYya%sS7joL4dR9q-{<<KljgSFq^cWL5(Vq?vT) zvs^#QS%MsPK93;!+Ilg{bX*&Dd&M{tt#-4q+Wqv=@V(M^=X=>8gA!(5p_+4%L%rpV zD;4cOlB%j1*-J#VAox$8zb}=X6&tZ=ww#V9i8YPP9ccM}JBD7vy41~z3um&+B}vNU zJxta+dKYP6(rlz<;IzR{BkUomzoFEfj>ZShzwYWBnCzLtdi=<p9|)P{Y{H#7c-AA@ zwpj;so6?-NtQpNbyerOGx!p>`KNM<EUb>8$na-8Qi9aA1opKOw;1KPIXj6r>MRYKV z?%<3|FK!X__L0{f!AKunRdZhc_=RBEx?A7(o3(Gb4fiz54fI`Pj;D?io9pq-X~nas z7D*%<UgR6+74)dkoCP}eYymfx>Bh77BT3g@uT5mqI=<z3x2xq0>lMzQijc8rm=aLd zSr(sxHQIvueDNDWRYTu$SK^Y|E}Cfv&w?sg{Zi}o8T*A}g&#6TlV**dQQN9!eozg$ z=~`~mEa!l$ev-5-VVyh@#jO5CFDt(blP6hI*T37Ti7~LrNgW)IKTZ`nkJDn4=~_5; zj?2|!fKIOK<wBI?!oA=2k0!@2s6&YH>jepQ$9bb#DMxNW-e_9yjQKuP`ED4>u3sB# zj?oU2M1>`fM<H+GuzKayuWbM^F=DaEL-_e&)t}wxr)CtnsLn@Zzx*JrzH{~gaPx-% zbwe&?w8O$!b6cY9jdbxrmdwKt0U*zH)k3UOCgD~ieOt8*cOpEjvG>E0{v@^571d<x zVZR?x3JKJtMprsJn2p3_SHJtF(dY97Zz%F1<GZk&wO`Vgo_pJdC=O2b4XHEvmYG;9 z*@erb-(l*UqafZn75DaBJ&HO@^4O&TazWQ?SksofLL}t9x7~q|A#cZ0r<L+yJvJq0 zo~i&<Y<WWz^BdYk7wVx)hx>vJf}Jb*x|!sxr85q9m*bxg>qh8k38!X$Ki=i(J1&K1 zqynLaxEyi%DC5Wg34DUBdOBm4!~S5Z&#Eb8c7Rr$F5JbvpxalyvH%n1FtVU!8;s-_ zG9xk3G~}w_c@0j<gR2UQMGxlKy%W`*#_3yGIXH5q-wIjLmZ>ju#NYpwxCv@#%-)0^ zWf1!DQ>`$jd4esDe!(NX?zOdj<}4wxO?%96QHDA>;?po`P(qg{vPRd(y1!QBL+=M` zqZniwx@C^tf@q1WuKVN-K5`%0bv!Jk+f=wY=GbWZw7UMiq=kxJ_)Koi@yGjtzg!>B zT8WwtTvy>gwjpc+ZfwH%JZuXNn0DVPP~sb**Pr53x!SLp!U#@F8?0l+1!sxOQ3Y99 zidWmq20-YzI>lq(z988XcElB&n`=Hql6Ollm(#mdSJN&v_1Tb`n<NVlXMOE=V#HhL zRIX$~8^7!rEGR)uJ(2!ua9&Ezs%gQp<uH|l%WBYSSmt4Jd{b5dU!$V_rke&H(KS~^ z9!jKR>I73Gxyo?GGesz?dK^=9m4?~cp++JVH_Ga@l$*r3aLc?Z^4oK=nj{v@e)0}j zjNeUyMb5e*COF>Zb@(FoKAtAurD%QFtUs^PI6%K)|Eck+O4P^EV#D*CdYydO>tlX# z0H|q0SAyF(Y!|yCA>vpO>W$6MJkfzD&X1n;s);O#Zahtx-C$FV2`=SWZ65z<z9b&% zp(8LYQ4+U%)P)DKn^+ZY*(Gb0eO_}>NLkRPo@3Kgyc+#bBd_oC5*63iyG1rSB9k*Q zsgRG?zB&IUyYNhGOF{lrE-+ZN0Y<AOlBl~98S5Yx=ioHtMR+zd^f;Uoj7tihn>--w z-fTmaS-Z#x>Yt??iMFdt=<_{E$xx6=wY=q=VDh69x7TV^Owp}DGqeE(EfYBKx1m>% zuESM@r)In7Cg<$-?G3|jZM^E)V50ENHB~L^w5=8J$W>wRgV8B-$Jq<-AgS?yvKrMq z&p;$ZtrV8~mV4x-h@@&U1j^H9m&lYjE=@UTX42&%I2OhLzwx1Hpqj-i;d!FWF^tul zs|5&avME4%5J0(;ChL}Dc*8i3m9Xp-wU@lFYYa^*rJSecE+9OgqC=&&skMGFUb__S z`GKy(fh3Br33i83Kge!dIMe=CFA{`ps2P(;xec5d9deG5rl<i(k`=Y*PYrpCj`NGM zyw%s8J_x1t{1Ty+dB~B}lg56P)^6HS#P$l3U(b0|?T*Y|&TdiZ?GY|{pJ|rXW){4H zYT=WX;e3`n{elhMR;#qfuUdW}&V>e983N9G5Z_3w@rNfK?3<D*8&!2HgtpVi$cF@a zJc4vB<C^!kjc%)Z+l`6U7=3};U%GD<iBvtX)8DG?b-KwY?aC}XOxQg&_nVrllHS&^ z&LS9LOFMdt5s!zK;SKj>1%--lFi}(blq3!+m)DvXRD|$x-fuv5&788~R{+1>?7gwW zVgY>|M`Zn2ZlS|TZm35}p{H3CW4~WtMc3U&u}WUF?tPhTbXF#MvdGa;oLeW5Z$%eM zszq&eqFM3aTRmdmpYmHdyRUV3dO1g4kB>9*imKAAf(u*3IgF747o4unzY-0x_3!># zS)iPam>bG{Fxv<>2(}walc>AN@Y%sRJol1rfp`M%l_woQWc2>S1N#3L8SO6y0XV>) zfzTVs|MA8Db!4=cXZek)NG9+`7s>(k5llRQ{irqjcLB_`3(flgIZBT>9_J{{OnWvT z#LXge!+?L={XDAduX5~(ivBWaVeR9Uxdcx0jQxHz|L)#vO%{b5e=*{1MY|q$f3F(y zO;gL~sQp2d+%gg%f;V#jas@YWKR4&|9<Vkj5jWHDc_JR?9@P5S=HA<+sfS&N6<lor z+Ri-IA(vk6{!Ip%+RN;XBl*-UTadK#GkHgTlFQD&)AJ3$+D$Zh?^@9QJ@7K5t6F6Z z@c)T_tB(J>1L=+|g-8P$?c_$9*YLPv7`aOkaKJ+TDpw6l;wA1QdSd>*2d`s=oXCtP z_t_Dl@5fDQ1cS(kvG<}pIsYDh;o^C%2)8&u0_rzeUWu^3{H_@EcnzH<w)03T)*pNJ z#Op}1RlgdFKczkMfUVxA-dh6Z&hc2!#}zdoMJz;jA4)twNhX_z)InEM{0wHMz6V^q z)HTg<R`59Ei8-i?h*TpTlibhE9REEtYyUm@7nFcZfcI0zbvB9*;^*J!6aQ`iv-UiS zbBdf~99|W-VRym*U;P=GEGW_|MVZg<IMI$(0_)-GCjwCHDS#-Wd;H}}{~q<fZff4{ z(^WKUAkUUyp!43VXy4?H|87NNK0qmQ0=hSKLWu!Je(u}9Zo{kPMwd{FOAUXM_hCr{ z@5mTaw3^h>B(!txyUyjgzn3EB?>?L*bjXbs_qYd-K2IZ;=iMg8f!H1#VlDt8yBIT7 zzH2dlka=%Bgm@{>K~6BoNV{T2;;1_6HiQ3hz=k{KTj{QNR8JPtcD_})#2K|5ff9v% z2IC%_*WM0Xe4KHdQ<HJxJiHkw;b?OxG(jxwqO7tbXr%U}Ci}H&s5o-OSw=}EZ=`5H zJg8Y*Z7t;>Y<493H7x8hK0v^2><U3e!JmD7-?*{oxF<@ABpQ!cbJ<6!@AW+bsFxq( z90Ar*Q%w>YUBQtOWJjGEcPTbR+}s>kufKfH=pN=|TuGU3Ui6;A@^(U2FprwN_o1ek zg_a|ukn-imngH3=N|X3rc0KVTr{2_HYlb&!%(ta3?4)wT_CP75CIHa<%*qtN%SVVo z&{zGl7Pi(bTGXkw?_iFqMpstqWlf!SwgE?+x8p%Lo-0^}4fL*4g5T<{v0YCZf90)_ zOhKDF%Hr|n{OZZ+x3cY&v_y~kjm8R|KnB|8E;{+KAx)}*8X&%NbPljdQ=XvlWR)<< zvez!9GZ1ORUy(Mowr0Ku!7m%@biV|*HZ>C#6P6-o8!3Q<fCbWfTpGkDo9H-%6vCIP z;ys%R2ng6$++hz!)7mXhlczZ$UyyO$;sMXsz`obT+-~CEbCmZXJ1@dd9#3`oN&euW zFbHO@owQIi?YLcM(=U5RX=eX+RZ~X8^JbM>Cu)TE?^gEv?$jID$X#nwm$a7cG=BA} zH9juiM@d?GR|=EQS3RHK$>H^FV9NKX0Ou9ru}kZ1-NFg_=>g^-l<JQ2j6pPgxsRGz z;1N{LPi-pIxD&7qAy2dQJmUH-`dNjwz#Xv3Oif^aZ_mvSu$uS{HG@ZTMv3y5e#JC% zZ^}v7U&Z?%Y&EP9D+OkamwUCM`O=jV>25K3U3sS<{1GrH^#fKmdemBHA!upYQgD^! zF?jTA<<l7jjZTq|Yq4>z@l(qhkBZqanzGyjlQNm>ue(^3QRz0<dvO)P>Iu#}T9Vu| z%tkRgm_of`iKYY|P4#O*$HkU<>9^?en&Z#%q4sG^!0}dY6a`@^@kX?bkITLIcxfdD zfoop5r!HiwG$Qn&1z|(CpP3|<-*&aQ+(+Y<avwwh@F-Q*Z2O$5k-99wINGf<9OLjK z{CHp^o2`{wiFWA&#_U%alg~IzF~jN&u{`NRM$xcDdtp(IMx*m{+jktSzkR9dZPYsn z=IKw;%a>GeU*=EL%*x)$H`(VY6_5Au+b)WxE?ockaj7o8j35kdQ!Hu<va#1+)?f3r zWmcrYN6py7KI#Wqd$*=KrTT&+a~HL@y-sC``ooQ8_><GN<{JbZOeAJ5;Mwr=s^*Hu z%E%dGb8{cD)(SJtC5riXf@P}N+|f$0()z1tTi6xvwieV?B)RXY0YGj$0eTSH#`@B+ zVA4#@1so~@nHcM#YA}m!N%+F(Qy&HOaE)W4pyJAT4cbAqJLt5%woJFoq_O2rc$A7@ zo>A&dbzd>>A@=*0IT<=xTDl#SCc3p&x>6oP?=c%Bn2oecb1yUJZjJIwSZQ`<y)Js) z{V-jk?z7CW15#vbc|jyNS;YTPB%1T)_zLb<`_w(l6(K}BCcK+{#Xk0j_N_CZ;Lj1c zc188%hp*zQR<SHvhgiV6K+CKRZj*;^qvnqqI6p4<&L}~o?X!%hElo@WlZ>tk9%Y5V z^J$J3XI9i8qHhotz5_yCRr+^w?eS|y3XIX6pkWb(!J{UbM;Gajw{{f>q)neFu8JjO z$3$u@ygnmp<mu)}Zg9T3fujd&f&Q{xZHZmIi-WFqqIhK7k(2%m)_P^r`!sg7@!m%p z$b-bOVs^`0394Gm*(_Fe*)Yst+iW1RJn>d(dC=1OaIWmIPLuhgP2%CHAfdC(9G94O zDo*rm7=?g^nmWrap@R{XX7Rosow#Fnq>>lSP!+90+oi?SI*HTeje_?PJhb*$k-&^| ze%z$KSF!6*8uv8MjoyWI`>H9bks-$t;ixe0k2|;R9+s<>8%mRL^Z)qKv(!mSSxBQ- z#u=p6qXOL{EN;*G1XVo9F)O0re#3ZgE00X5jLy{u6E1h|aRqKXRN^-otvNxx?S6Tn zdSlp^hT)r4N;PS$qHF@4m&f${Z(e+wcOm<=0`K~TIE~muHVV@;iQ!6HP}Ob^wwG@= zb0t0@A-k%16?{<fStG1)#YCB=i66nH%|fYHGRpe|^Njax>cRt^_}sTggKi!hi&O5$ zvY8r_$}#j<aKJE7)bi455Q!J5ga_)6O{i7=M3gqFyb|;PS6c|)z1N@T9=<nYTdTSf zvMfv%Md@faWBn4$tcInfCVKr8s%$cOR{oVWxG6o?BliW5efrq$DZkj()M_+_Im^h; z@{UEEkmDWL^M=|aoiNA4+km2UK7X707yav8p(>b3wuDh*_UB>&ckfGdYS=gOA?bW_ zO=j$$hf38{>kga_LX6Hk4hcx7-VWxWx9y{C3Vfj=Bx@T@lnwgE@8LXZp}Mam^%?4^ ztJ@Htl@j|aMO#g}Z`p0Rd@hUA!01x4hIlIvM5Q`Sj;>9oFgS#ZPDw9Kzo0ig)!yxy z`5nJQL+@yZz1ZAtXgbtkDox->?<}8aoX$EZSqxSQ)W_co4YsKn`t^`J1?58LEv)*G z(yT9$j<nUyf4nDNe}fWr5#m6dge$+=_I*Q^#04Aj>evkg(<nd)y*j{A+>v(K0;WI8 z{eEY~QF)P}FIKSp%3`=u^tB<84~CLD7HQvSxDttg%`+ea)xzgTN9qSt+Ma#>P4>dq zLa$A|a`b6LyB}-)h*C#YRAa$A6_<-~=nPWht$OjtedA_Hy{d0Z;}+3$GN|ycA3ed8 z1qGFvJWzXPzB-Nfv%=zWUP+S2v1_|NlHiSWx)WW3O^0_RIt15Cr(U^qwo#ckoGo`~ zAT5=^UnOg6SSse&IqV?GJ*pn7u}}Xu>{R(1B{mQ<o+xYQmwtevWOpxKU^7o*bERj& zj@1yq146xDNFJfsFOLl;q3wT*WA8Tp>+2-!b?%|_00cVx3jzt4lBl>H1_A*bNxRQ* zF7AIpxZs6&kFog|dSpVeDyO&W|AjT5;6<SmM(jY^9uUl?Sc@V1cPBJo*4#J!*{?rE zlA$Ig+eS`|h`~bW%>^JJ?>^n%&@KO8z;kZtBw6gWCYkepV|G2&qnK3p!(0HJ{vD_3 z)%-W)h5YLdz75`IJdF1oEm2i`koNWduY%^k(f;;90IJ*(AOcD5B*mgX!R@%WRf2>J zXyU@Yv-YWSr7M6!IRyX|dN2pztDj0_9{=AS*c2o#YpUN0bUu|?awBRQlm6~wop@b! zC<}OFCIM6Ssrcoey`bm)txt7bYUD-Jp-mQ-weyQ;Ib!w3d4asZt;%x^D=NRq?lJ9W z_QjB1iL9DmWjHrN_#P$^f5i)2DRLoW!D0DdNV;@BR=MytEwLfvi~^qbC)$13y3t+o ztuKoV%pG%d)dL_1dEQwWTWrz3fO<*gIj_H)R{0loV&%I~Gs?mCxX!>?t>(WLqW$>4 zz<)t!3_yM0u#;o$vnxi3zu<ZxFvyrX)Mh41E;{Rv&;FGE&Mq~#@T{jLz9~j;zWYS= zm-5EnNWK>}E?HDR@^203pXdIRcy{v`B7jK{zz1IfFsREjKz1*)-(MOX8YsZ6_uWX^ zf)^+bIy47pnCyZ2f1WdK2F#N0y3WcG>m~+&6k!_u%N?c-xCbu*>sx{vF=DdF1ssP| zZh*we-vo#<v5N$?0{&P?+~EJu=d}wBfCG-Kgc2x7$_;2n0}?2^@BqNa7!wAagZ}Vm z0UT!JaA0@;s|vk=`+sLm=8^qbn5Z7J)Cgqb-UQrXK$X<I3u1t`kS3`GjK@l!d6ELE zH<|wPIghMJ1lSc_O*N<6#9$|Ylc2D(Q)fpcMSs~IAY)pxkp*b!uc4bAho3=zlLaD? zHy5Vnn2|d8!?Cmm!(oYj0qydJ{Zt>%aWV65IY)B)>7&F|?(2}o^B3+yKX6h5ll0d_ z2oXE{@=+~~bNfc<9bkCV2|hl<aKU_pNIy9AHFv>i=6ng9-_;%yJ~*ZFHY@qSzH(e2 z^9rm@8pS;Tv;b(Uyy^ARo-2KYUBk@Le(hp+Ij)#e?c=&O!&e`m7``X3B1rw2%AXW^ z3hBmiEue#{LI`bnlame<S(a7Rp&r?n>T8>rTvYPt9TD{!2_Yht+)=lh>Eh9eAdnC2 zt(@m)7a)UOEyuytL3iz>X9KeuN}6-LQ~tGa_@z5~`-)?3ZI}jyr%!A^z+87#?1t(m zZ;OWANsWc1H_h?{>vq6x$_U}aY!|1;No5LktYq`_SeQ3gJO?fDpK{7_dEK7rRpPqw z{%1WAJqVH6+Y-6D^gb^2vxAdf#HePc-jZ%y`SOYy=9ikhQgsq6^Z<Fcm&k0aa69^T z4o$O~=8q=+0<j>hX_S2zP4;Q+kH`XL*R+DX*9KZH9t`;^NdO7iX2T;E+ZA{SAYAVP zpm8^rY!hoXL8v-3OR;u&-hM}{dCkHpeD}P5`W?v6J#L#@G^B*nYovZZQ9>A&gZANB zfr2<8oI_#MV+mK4{Z3S=Q1h(H%kfT<u0^Q_x8I{%GCPsk*PRRA#j(U?jUd533%*fq zi;TH~uaMgXz0#pObH74$quhIKlgIet#LVT3Q)7<2NBSPIjnWJzqbqVdX)*Li0R&JU z@(O|W^p0>%=K9GBIuC=?9YgB5r^r;Xc$`jsSgZ<%Q#?;${B<o%+DBx6#_apodiFCf zkcM#Qd^W4Z&7%Aosl{mo#lC#c&vM5?iHyb}FE1GM&G&LAuAT}(WiU@}V6I{G<tN_Z zRn~@}4XY7b7EL*QQ9xp$USQ*cu{vbpgL+Ul<&%tZ<b|^jezFq-*wVMqE0s`cxaTZ8 zAuw+((UP2yy)Y*?+<x+$_UWdJeZJ$qpp$-@7Ojkm3xd0d(fCcM>oKflcZ%!C>#P9n z*t<>MmQfM-(B%_Sj@7UX*V(goql^$MpAz4gj<Jx%P@NhVuOvgOzDPaSPy;=o``(lh z(9EWU&A7VO47`v6!jZ=K*|Y^~Umv)A_N1Ihu;f+ajR@{yUoT2jw#HE}JeO`ZH}-wI z4ci6elxgS|aOzz=#qn;}EzZ#pjd3ag2Up1z3EnH6r)Fac?MIAz-PxVH9Mf@v?+PS) z%rXm0<C7E=8Pt%~#PQHI=dL3gRqHih(;opk?)in>b@X~k68DO-W~<GAHmGNYM{3WC zzoezH)!$fl-!pDCPLBIj#@QO5?LZ%ww|=L3(-&4)+v<_e%Va8~m@VJoimC>;px;6- z5b3`VhO{r+&2pd^2xGl%o{8@*dp(Yr(s>b;1rp^x;TQFg#dqbuW9?cFz;wvVINlcR zH_&Se>_nSk_gWIynkChE73z}r(QmRR$peq^7j?`uAx84lU)b!0nw8RLA{<qNrqVdV z3FO-<r<!)@QUs7yHu5&15L+723`lB)IU+4`05Mh0D<fYT=^vqOS>dzY7hPad`}vk? zf)RG_AF@7VQy+YHuL28x19d1R@BuHoTq}I2B>}xaON*3FX?2BTf!Zw`Z+1jVJ_YX- zXZwaEt`~)?=U>cc58t@H%*-(bH@Br)7P->`c|jS%xtCGtl*FB4UXpr!*)6`#CzDUU zrN(pDzJwhXtU!hH?Zwqjhf;0XY+K(cV&Cim*=uF3Zl~stq_U}}@n|(>YN~4qOm<50 zKfwYq0!$0ETMc*zP02&g5%)Pp%(~m{D9(JRU+GsusJ@DbTpu;In88>~^6ZCk*zO5S zEEd)|oqzb9C`j<YqmJHHgf23*MsaE2x&lkNFKE``l?F#dgrAuus`1!V@5SD^Xr}7V zLiXNL`r{ROhm6V0Z{P}*Ej*Ss09;wx@>;qrT^x@JjfH2#NXcb)79n*@B-_OyUNv5# zy<WELNuJf^s%DOr!LxeRu08L@QH$s>&MV-nl{3~0Mq!QGp9njE-$htrfS_`tzo{#M zXE`r+L*RRV3PXLsgS$4TkF^TfK;I1yUD$87x|i2`*gd^zm@8djU?G#I&M)eqem5@A zb#hm-XL`IcHJONo;3E9RQ!@lYDV-1HCh8LkhSG&)ERk~hhK$a+hN(CC^=&QFZ<)^y ziGZ|ZJV#|liuJO=Jb3E4Ykrr!ja2Zzy86ZD^ndQob_#iJwi=dF&w^v;i|&80Se0I1 z?PW*Ri+0C+<oZzEzF0MYL9|#>6RZ}{EQDP15DV4y!3@yk`iV!INz;@m<E<YDmxC8h zRVhoNpdZ<s6p4)U=ohf7+NUz!&o*07mD}hjAnu!tAhxOdwPLJM-i>E0DzjT`de*!* zZvvCw7=AxiVsKWpE?j1Jkp`#1)H_U+B@AaFWrm1cxSe71!6Kx<0xfu>Ith~)e$lpF zN8=@`;!EZ5%Ny3NPA^8S(>$HN56?au5@+P_hSJu;=@o-bC-wDLhFqfSn|yroJBt`% zwS<4%>Cu@bc41R>7kDq>j$D$JS<J;vo)&8EFXVh35oPvy(q7;`pKzzs;IM5d-gzU+ zR<DHB-O5lm|84P_0t+4*b=Zpt{Z*X~`Z@*>Nl?Gf<)%^s!dRo>9%!K^**NSuHP3a3 z5Y@GoTk%`_+&onK=xb;@JBTb^Z+w2Y4SmsqfHrLm0Cp38z2*qtK0L*Ya(!Vds@(p% z7W95d-}mz6d*xXP%joM6+C?a<-%mUtuw|BEtP*{7vzfxtZIQN31`!-mBN^O(K&Re1 z!>VIb%V@P?=B4&Ldb&kAPNMAN8E<F0IDy%Z34T)A2BT_o`Mf^1CSkSk`qqr&!LQ0H zM}u7;L9#sS4I)gmh2Mf0+xWO77NSrEy;ytsOC%%cM@drU247(nzIH?nh(Bepwwsl1 ziUEfJ3ram8*0z|x>><u<)F!KyMy@B?y2$_RIIg|cNNa@8V97b)^FvTjtA4u`o-S`g zD=BMs{WsY)ciNC&vx0cqpzR&WVtJ*8kr%)VI8@k4q;aWA0lChw>v-+^@M1&lWrHwF zJL_t_0l9m&NPawL4W8Ztb^+c@)ri{-a|()Ee<gW1(};Ge-cRRi*Xy`xBJ8JRFNCGx zIyEQ=<Myd8fo^r++jQ_WRVAdKBz{6*!I~xSPo8ShPn=eLRPKZM4>xt)SQ0Ttld{es zh?*X<MA2YlgXeF3GCB|}-d}#4AR=c$IH_=vDve_K`?%e3i3t1Bt>MSX-ODu}ZE9nm zj%^lc^CRM163<asNv&BBPnxN5PufSm39?&DRc2Hc)x8)!){Ea-Oh`L^zI3SBQAl($ zT2P^0ku38eKLTuXv8idV+}d06e%R~9>#ypi8h}_%jpW>-Ub$xL1*JYO7$_wSoLVA* z*scZGHNu<;UI5N&`6frhgJU;z(1~j_D@>!QDNg)G>Q?lkQtjf<qiP}co!iy>fbb1! z9<W*)63~t@7h?kFt{|@#5WHIH90o05mK)<!2#?qA@2J`YTozTj{`kifRe#f$fcw^b z`e&hlyg4%=|1(mNAdPid(B9^7m=y_Ojb#1t`RPLP&XF0sNfGPN85uCk7G~{*5WH*V zWe_W|4@A>3|5tX}Bx)1Dt3Q?e#5>IC<DADtXmCGcorIe0-As+@*NS)4!BR)|c|fEt z0deqpo`$9G&MIBzokc$NUX0dGnqh+7tSGWX=d)?R${2*Wn<yTkI|;bvTA-Pa!5pZ9 z>fdBOzsa)Qss_C`&kSl#2hIf2KAo>3G668#7J$j*$Kl`q5iRR4mki)=KJOILeIxKr zDJe)Gx}>*#Ztpxm3_MT=H_aW%Kne-KuQd=S1b`&z|Km!B+znt2=gcph?H`tqYROMm zH}6yY#Ul_|sPDI@NKM1XlobY*f20PIl|1Y~?Qy06DQ;Ivn(Jsm0N;3p_<~xy<u9HG zXa;RS=mF<iK6G;)VA29+pctUW&?Pm%_Dc>-iRr|r^Z&`!8#{aIy}4t02B3YLPc*Oo z3U`dT2sCG?eew%>a(!Ia91Y~13h<u!{uh1xbiRV93$)D^1M~(r1!XM89FtAI2D*D_ zN{0PQd9f@L__gUcsrkuoGDXm|5$!*(buPi-Y`oP`vpv_<&#S$Cjz7o+YRXTb1|q?~ z)={l#_JEc8J-`7;20UaB&oTf8rf?TEmkk&NmJfX+2#5CDTPq(8U{vgn?_ZdpNf<Y3 zAYLS(76ibTJAjZ<o2h9_SnU3QpcO#wpWEi}U0B-B+fa8N9}ZlzanRltQX!#Mfso-` zB7EvM85|W{@0WPgEQ<RPx=f*_vEayfjkE9myiu?Y`A=xMS0IFAG41lMF`hF6k!RT@ ztE5qR-BH_|vkG<;fP)1hWfy^r1@}VZ$2i9HD~slL2FRJQl2NDP10J~%+m^G+29?9B zo-NpWXw%M-Dz+KZBaJh~4Ylm|<wL6NarYU}6<g5NPTJE0^n$Uakk{9`U_s+n778m0 z48=f|dpF!oP!r-Tf9q_O>RXBRzXMeL#ZZ-1;A22Zh(yZ3XP#;R%aH+G?gB?1Ye+cR zEH0vnI4rc!(wfJATi$=Q8t!(g&_+T&1#Vk|1PY!<5eUFz>4N%L677GJH1HMpIWu&3 z=r>ugEg_w+s50|jss`0@xODqxErl;tg(95*ONJhfqKe7fpcvB_BH-8r^3}8ngJ;>m z4jTZje*qyGQ4f{K?AE-JyyS}Rnp>#d61RFk{my&mst0uP2)vIaKRbcpN;KNgd#nKE zMV+v2t(^yNozfoT14(BhgeSr;i()Y<8Zrh!FCWm6J?JpW1K<jF2zIhG2UPi{|7Ta= zKZh|Qp>uKW&o9PpE=5HsMvm#k>R*5SFkK;`ZTyd5S~BrJW`hCspC>Qpi@(g-i@lvW zgLEq2d^$!&5Z!mOS7bm^W+LzeLxIC?ZkQw~j0Se`zobMp|2Zo6S+)?iejeV&U>?^# zs-Dkbt0UvQ7KkA95(O9_?rZ0Fk6woo34pQ3FNw(akBQd=bVvP!Vl}90Gt1m4D@|;I zwl6O2cRc@1X7BJ<&(O0oDAu(3FGI(Fi;>c!{`ixb0-Yy1)}z^4#=znWB8B7Ci?0H{ z-{v-*P&2U2`)nEiS%S<z?j9t`aPIx$+b`uq#8bX8rhR=xm}071r;;BKBHU8zcLC3l z+X`g*0Gzq>kdJ5BqZp+<BsjmHmaDe)DbfDp8;j4B8`pwwhVg)J-q)M^z$pe;5v0$m zVN38sH0dhlH(A^ryvkXEz}%VCdKGqc$ffsrk|A3BcxqiUqBs=i3({iK&sP>ZFkm=1 zZUH|eYMmt$VOVfPa#H(@oCTi>Pmw*G{g<%q)AzTRb(f!s?SzXq29{B9eK`?ny$A2K zynxT#Xr{z@bcMK^g)POH;g%26Qg;UXCA30@G<?e_F>PYUpKabYD4o-#tkpa-Fp3~4 zR-nckVJ8d;YYUCWi{=V!REqBF`q7-CL9&@5A$0M2$cm_gxY5&YOuvcQacFRJtR;^y zedhu%zn-^XeKc#(F}s6awpNqeHC^Y_C$YI<MRiNr^0f`KX$qETGeT7U08oa2YsDei z<G@wP*O%wJ(a^F!Eel<(?vdxMN4La3%zT+*iCXf0Nt77cg+3PvNGCh{;zt8dmZ)DI z53J<#lO*y~jBHmF!Ky0hrZ*Vhw|3kdx&Fd4#g4A;^UPc4PD_RGgQUnhVm`lt^N6{^ zh+eW@%w9wP`q)OlB#TnM@@hMdDMoe`NJLH-HkLCE{?H@VuI%*XiA$PEvCmXgQ}HLP z{e$6LnJSq&jWv-;^ic$%7n?EZt4Ppg3MW#1f_o_*BE7KMU`tGaPmMIahNq+ZbZ&~s ziJltxLxfX5170qVs^L4@wv@n=(MmNp#kI)Pp&gRHpnY9qA<azPXUee5CD%K0X0pY@ zg(s_eNNoKXTXy_?A#3-ykG>{Yal&JVq1Z|E<|5*ZdGuN1bY_PjmM7PgS<WHVp({~c zsH?zha|o}Y1iFoV5eNN5XjqTRn6K>>{kG^@;MUef7ZwB{>h;zv4)rqKG<o&-cq?J0 zS5AYL+gZmkMScQ)L+C3=pl;+|?_yV*rqMSk&MSDEUvH7HFB`K=30s0&TkiJ^t$i4( z@e)jQz*{BuC&SrR#iJN@-+*Ky>Ff&{Q5rZ$+X%-3I_<zNP=FbYD^PjIc4>_^dVN;= zGG(&P$r-m@{}P6IrPuAkfD`D4Fz#WdA5b0_wW~hcYmCv!e_4uf@0|c7hjz?-BYX^1 zc>@$<*z$YIzb;+7e<S(<X!rT7!1H7GdA#h)jSc~sGwZ~w`}L_~N5bao4a(;I*-bmI zWDvQ+O2I8ZTXh$FfI644_z?L-=_nOpJH7=j8O;Z$d}{hDk@se885d7s7^4o$duN5H z=TtG_fMDyHqy54zbETYAC@$t3JV)uZSJCubyL+!jnjTRz;w{#Dxi0z&maL;$mReWb z+>IoDmezbjB%)En7AL;=<NboBN}CarG$tmLsJl?R<395Y<NGK^Qv`Bdg(tXC;3e+X z!@U+zqiz-jwW#uh0$WuT&Or$rB$PRnNLA)>em(C7-4CwBoBUgy;NJA-)3Q?%5vlSQ z5Kl%9g%ElfCSx8fJG;W}ox>$gJ302;iTz<Os$V?Qc%;VN>8GdVVwp(Z38B#&aW*#0 zWYH|KA<x>XGdGR(3@4;5`zjzjrH%oE>$*#DX8|*^kQPR(9ADU*C`?IzRG#(u6=W!< zKrdIx)u^$s(=E;bEXcZm6qwJzXbp5F=LR=Q;^Q9U(sHAV(NznhJh&lk?(w5d$BVHO zEfNKIB?w)<=rjw*b-}#eircoW+HXvYW_j_p(IgO3b==)}8NZY5^y_3aD!UDCboViS z&is4z03)cBD^}vMvJ}S2ZbJRaA>z7srYYW~Qh}>3dTqi|#p}g@BlF$9NEQoK-GD1# z-FL1O<kGEoO$oHEN9k0!*HO(G*%N_Ba1CE~$|B<iS(#pWdGU%e!L7bNwP)JH3q<#Y z6MbHmp@QjRAXj+Zq@?E8D5iY5-g9j16*?hf=*i_hq6I56tIo*`Pe>u_2gq&S<W&2f zyQO-?HUnmK>iW32NPb=o%#&i%q^};SOdstS!JLxd@L9eTQ#>@F7-9`<09%5}L%h(B z=)uOsJu{X3>C1-Rep9YL)%V-KhTV#)T<<G0&YpI3Ntw40=t5s;=I~C!BBB)T+F_!a zqLWJO^&IMdgs;E0eT~S|u(d{Hcfk>NubKC9)Sm@cx5tvL{U#HAIJp74;K%Afq8V#s zLw#25F7YnGwhwQJ&T4Qhmy`-N+cj1vFtgcn-F)O{__LtF`GMn4LgswP8|)SC;lqLJ z@ax9lZ8ahH(PX--#iPU|S542rp6)civ0k=1t7~CW{-#fO2irPHlx;S%twCAS*_U<) zwG;2icQ@3j|L9l#<+<$Yp!fd38^O^iU;5#pNc^3JJs<tHE>LI)C3sukIo?5DK;Mb3 z{n_noN(est!Twl2C26RbHC3e@Jvn7KPE=X|-hwd;QR0TxxUS%oM{y6{C!Qg#zhL^E zI@P$;EGKJL7JXIEJ$)_}+t2^*X=veDCVGL25HXM7AZq=b(-?WO0G#b-8roy@x*tE8 zDE;_Q^X~mQ0si9rm-#BwTj8u?F)8C2)JPS^I-%Sk5|{a!B|}3+L-cAJ#<66wIHy+m zs!-b4*_b~xfiIGa&mCz6v&%i@N76vcLxZYdp|h;`s2_Eo9WaWI##py_`qOqX&uU}M zJXK)AGg%>0j7#DIENuNRTvf8);@$iU7qFHlG51s@uq;oCGPsl7BC2GSPb7xoqO!Jc z$7*a55S?h+a=8!4S=nv538I__pL!Lw1z)yhjx=VlT``ffk&|m;@m`d+?LcT0f2=!v zB!OQiv>(QZbi`FWAUwco)5Gf-!xX|wh#<UX=!r+lY}1d=9=7>vIhOYsrBqi8Ypa5K zwu3@2H`&PEX5xK2%Db(784QK3p3tbbdIq@qETUad_Aml3B9iEXb2G;=wP=R{66hUg zSuV!LaL?$(>eJlI-b2R3&hQK8oXf7H7RFVLQVPP}!D^Vc^6?r+@`NthRz!qQj)t#r z6wPNF-^^K-;*#Pl9|k!_eUJ9{y(~20ZY(!I{Qbu;cD(deJf{n5oh27$?Ql6>0u7YU zj%)NB!Y}JqG!30$-w?HNa}i}AXIV}gYE7qCu`xR~q51q$ISVX$v4p&wbzT-tt<;<H z`*Pt55C4e>{|8Pr>H_Dakq5DqV&-9B2;W~wjb-5RL2>DSaIhio8^5!GL1?kN#5vkO z;G%$hhiI2g4n<L>G3<wKGY_RpV5bs%Ogj?D1EYa%)&m6}?z7MRiBy4lT>pWNI)nFF z{lE?N^`i?lb#<|-6KUOCiR8=o9+YJKi3fZBskQr$5%3F~%F7hlCJLw~Br@^$GGDw# zb4AkW(+GNr&E+?l<u2g9OeVuZ|9`1T%0J1<He>6zyxX0e8T;L+)>_lu;T_s+GNpfT zKInfa(i1@M)v3_e_j0ZawY2LO?mp0U#q*H|7pja%LnEkF66*8>)tOO@`fj;NY6c%C z7vKK}M7B@~{S>gP60*2+F;RJ@Zs~rX-!r-7CHPld4bdOqMsHAS%Kk!s@PU~Btcw1K z4!Pvwq)iz*T7ZQWboaa=eI<SE{u>k6pS)u%BMMlJ|40Mh{$pI##2Y|d@irKt;Mbo5 z*-dfsvSnExs@wQeFj(pjKB)4?+VeZ`T>y93CCWYPw_$Bvai(f-P-BKXH<JJ7!{+WM z3E*!<K+_1|{6gkcWdDPnSmL%v`)A9pHqEs4vN_GLN1JFdq(AsoRR0rKN(}vU0wwv6 zoE!aLC*aaO<)I-Cg+)8ZTPms?31fFD-{oH9?5qR-$*IdnQA<pKwbgP6wRXGq71^#3 z;EWXk97sJ`C5nh^n|B}MI$kMef^;jL$rm02dT1%;0Q&@-3C&DEG2QZ9f*JN#i~{qF zg}t1_S8cl&f?q9eJ`MWC%mwN|wQ82222N3PR3uPSuDzU7wl(PN@JqKue!U8JWX3lj zR}pb)MAVet(<~55ST4%_l_+i&mGYV#wQ4~gNW6nn!IC~%4ZjqwylSG7a<Ay3gdX2% zhud$mu@fV}Dsp8u6i7&20!ETTgbzV&o6dtN;X~eIi(>*pvN!Cq>(hEdct4q^Ym)hr zhbVx&xmxA8lWAfy`P(EcE!sqRvN%^7=Kv!qI21~YFftt7K`htQx*fr(+&NTq%#TV9 z$A}i0Yt3x6c-cC&PXW_CkX&-_E%LFt<+F@NUwllP6#ANiI8kYs$nr%MIYlK(S^1gS z*&@}Sf&;Biwhu3j#2D0sI02^U(u)u55iTr>yTU6c>9Ug8|6+x;(9Mq|kAs*9sFiQO zMw^iWH-QUZKG2SOp*Y|$s9ZF`^38_Zb~7B8ah@R14!!2Fzwjip`*nUq+(qY0ZFhEL zy2yTgqPZ1*vJY5^0$l7plaWTyYY<e<x_Hm02=_}p8HyUTLv<Mu8DFEDaM*_^&>8|> zV*kEm{Y9l9rz8n)esJ=_AHw$S&pIHUsB@?n7An}p?AJMjC+(gm5{WJX{oI4%$Ns73 z=0NMbB#IVnu)G;II`+!ORluG{Nrsc_#RD}+w1F7oO^ecP5u88=v?5{bqoWV@)WYmk zUD^h&>c4lC>h@kA^#UDedFLz(X)hf#uA{mwRQ!0{NL*!4`4!)>Pxp#Hq&ysWuwpVQ z=#k|3tIaV5MbhtPT2>x-UGp&9GKw29y7bRgw>uvbLKMniwtr<k#~;z~ymnSa^Shbd z;l08t?aL0*A)dq5ZtUPq&ZR4@{+He2x^#6mNbKcu3BesvsRG=rf?^ch(~1Q-YTqDu z{pWxxd{rSiseP=N)Bz#ygTD=WaU)AuOznW9pA6Q7b8333nm$Q095Tu0n9CIyou(wO zj}xu}W#v;l><C7d=gd<st8sDQ^&P83B6K=<rn?<)No0Mn(cRz6bZ%LH$IoH3Xw<HG zdxy_MAmWbUE?+5Sfaot4Z>VlRnVT07XI7OWFcrbzZ6nopv4XpIxkTCLnRmf2zbp8w zQAIUghItVbj^BD3qD5mb`>;p9-mH;p)EejXjB(iX2y~4EU%w_Aw~ykF(HT+BGM_eX z38Q-#OigCkd4F|6hdkxa)MR~N4<jA|XTK|IPLm}0qjyp0#T{0e-M0qM7+zYEFW=_~ z1_1}(fA%h*x%}^a%s|$UB0V&M9!`v^Z@!d>lGZH`KRFtFo~VD7D^_{Y7v}&YC?7yi z$a&8W=CJqK9X*<_14kS;YPV)TAGN^t6FBJDGky)DqO3Px1+RqpVf>OrLqIwPWaJkk z(<{#n>zX5o+?Z9sLRE8yLocZOd2yc!3B0$!KT+f04fyqX&GUSX51f9nwo=SWV<M-Y zTFYQTz9hOPTGE?tAcI<(@ROX)Z1(bRGBY<4AjV`m^3NO3SiA(IRbogMdrMvPDA?ya zbC>zaPoUcP|9<c18vdOYjW+vDHa}B(ESAB5n$&ChO*ZV50(-{_+Wyh->ZON0WUZQU z;v0?fUGJ`9ziw2^Il*E<sCCBmHrp#v+U>oaH|WPtp<0J0MiCi+<+bi4^SEXmXz_M* z>6u^laRr)?yI9J`t#Eq~Nr7b(xaoH?9=sCxwuHAb@x*L1{%Nf2ibf8lN@8r54Rb#I zms9C)h_^6GBopqK#6_5DueOt%5L|A!b=`6CqYx|KLN&Py#gUn@dXf)?bs(4cIZNrq zfh$NMoN&sbb_A4>#K$405d(s^wUIb0E0ck#(n*L~G*gdoij9w)EtsO`@67Z*f8PW? zgt8r=P{Q%fD_1O<r2*KuN`!)7Jhwhx^X|bdQ`zD6kemEU>?!&piIa|mOH|h)YEBw1 zg?#>C!}8pPK0&pHIcq*PZEZxozu4z>n$%SDk!crf$l)2k3oJ;&DkimX(EBBbQvd0C zr+0WSePB8hE&uRQdCv6L_=Fjj{VqCw-P~=xJk8H@gemOmw_Xb5&4OuyZ|ghl6+*<K z!P(Y3hm)vsCJQYMc~wZ8{cRvTxqyNt_G<o8N4qvtAsl>3;SSQAAPblYBGC+Jds><` zP6)v<YvWZN!3$TRSzcW>w5^$osRR_hlphX=V7}C71WQv-G1_xIrV~b5FG`1#z<&L} zktaz@f#kv$7oTiY-!=9wc8?NzQ5~>sD8QDc?(?o5b2(&YdqsKfbiC$eD{}q$K?Z?O zC5q^XMFeZ($>)D<b>YEnrd=UO8VR<6unJS9r%ng(eCvvauMHs{aQSW7j#h29v%IQ? zq9l!FZsC0oYq8V{P@1BIU5jpNwtc;RR?~Xc@i@<+C3Y#?(<_oyi*~h9Vt&Ix$Nj4W z5XUWmb@8z8DY-5{x5ae`!wNn;dKYD+=UhnXzCP@9H$l!J&3h>0t6y*WB}Q1q?Wj{@ zpcc7OE>Q0@xjEz{z0NHcUNJeaKv?_`5fP%f#(4uW#w7@{rXG6qIl={14&J_Ws(|#w zt+q#@T2K`kQO#W5Awmvr^CF=~rjBQYlWpQN8o4cb8#<TEhld_Xjcp6=H*{JhDjO<^ zLG%2&q14S+{l*knn$A*C@PY99_oIT@jnVr@ez=b5Sq|Jz__k!zR2G%Z(#(vH*R?)e zmxsc$$nS+t7cJp#(64hXB9kkd^Ig#j3KQNNz4LR#o6XYoKf&#ZNm3^kLC#&561i)8 zzi?4Fm0(rWZqC-+SLNmpM}JuU$V>jL){Pnef%CDVd)@PVr3cEIr?-<`<LgMnK{u9S zXSXx*Txdf`lrKzv*c?7Cq>U^o)bDt3W|=0ZpCOlp`w(81yA2q#SXe6;ar-OzD(MER zOv=Rydz(iu0!|kP0{y_=yFm4hKnFD4mdLKe46QPrZuApw%ad`eRKl%aP}OPq{c0zd zjcQNXb@c`%mkefr$H!bFij4pekZsKxh}AhaACUq_(Ziqp7~>tu@_pMeF`TmP*s%4! z=x6Ur=cnnuw~>DR&Q)#1r)N#bCnZRm3OuzOktD7iN@5uQgrX;CZQK(T-WFb%a&yb+ z7If)$Q{Z~@v_Z8a`kH!q&jXWtu%l4??snNcVnPBwch!%Ec!^+vn<8DS?d=wc@}LDd zNKtqn&Amt-6L6FhklkhIy-7Vz|3Ij(?D4pQxzk=jI)@dG(8t05L0$LgC_-DQ|4vU2 zr8dURS6WjUQam%OzO%dEs500VP#bYKIs4skcGS^Wrc&*2)~cSUb2gt&>MH*eWLYSL zS6*E&s5E~ST+J9aUpl$3RyIPSfn$=|`)xbuOf9^{zxjcNnkQd-<TlUA9hcnjGzzr+ z$o=wN)B<H>frbQ<gtoz!UP8)M5c09Kp<cF1aG9Mdvl(8a;l5YyS1I02%g;_@O5f$$ z**?oQs3|WfOh`FmIZFkSol%o+iy%_a>@}QGB+@L~TYX%sZWIE;lj{v45?dN`LZ-IH z@EeJ-f^=;NrWDTByql3v?}+WAz`x1tfY=~Yq-n;HBaoP>6}14S*nAc9w)uvAHHMbR zEj5;`ulHDJdntTQEA2+O{a~p$Z{klghTbl&FFAw(DuQygn6WuX<YjRdR+>dyqr~`5 zw-D&lw4|$(+FH`;aYm3I&F~`S1a-~L%xHZF%WM@hIu?i|bN1T=e&&}p!Vck@{6bIS zU4(UF;b~f>cW{|la2M<?n7YJI*a2Nm8#b(z+#=F=k2kccSmDIcaANmG!qap!dw<cl zn7jF0nzdV(kTprX-@w&fZ76m^$v~@7GX>u1jnrqmIOBn0dtDzl^?jA=m^TQC65%Ux z-jR7cx@G%Ub4&3|9U15B6qxZDZy>yjX}phzNxZ>$-cX2v8>sxPd$B2V$5{Sr@Q&$~ z#rGJQtOgr<OATL_+8i3*C<Q*kLl`ct<}K+w922!0xP%u@%h%4%4R#XT7EB*>EDfM2 z5n2rB9Gcg#b^ayZ%b;7(EBEo?_ct~qYFu)QoXki41P6y5waK1tyM>;`x~5g;{X1^L zMm$a?E(?$g^THyFTgo&U6eFz<8B%fYv)^_OWrt>+0ZICV$j73U%WvZq%0TKxxSpas zb*VOkeD(MSC>v23hiaP|tHeu{u|{qMZWZw+Zy;*!`G-*1{WAa2xhTsZ;UeK!_I34g zJzFn_VwY~^(CTo><C^StAt3YoX<ql-t$_Ew2!UFh82k<1D+my@9$y%HH-t3s9EHFO zo7#0IV1?`VuZr#Xssb`^Qh}nuuHmh!t8ohOi?PjCXDR3xBH??|;ZF2e;i`GxT?)d0 z=I|nJxqij2%0#$$On$SL`B<89_VKr_%JS*+b8-bBl=X#q-b*hIW^BXLn6o*}G_bD7 z#%?(eR`c;~?`*r=zVQ`y`FUsnyHT88SL0sJ^<rse{ZET48}$=m^L8V_TH0{tHa6Nh zwfPZSW%q4uTHS7uufh<o1)xfK3s9I)?NehzoQ;1v=27^sU%INMvxd4Ht-;B6O{Hw8 zrzmDAqu4l9v`4m`5S3E|ryCVw5#68S<-S?R^}drOr>bgE9#CeMff%JB)d+9qIiOvk zM<_hBJ?8RSXj}88#F-S8(X5}7HtBX(8|^u|D3~U<KfAH3xlt?oIL?}7n}fwH5M3wA z(I+oza#7X;zNKoCGwm4pmOM5`#SQop&!ciSxQQ*}pd9&&7Xhl452}p^lEP2!E%gKx zYJ>EW%l%IDnnuz_KQooq*=5aSzc!p$&QRtA_w7aA7OUnj;W%X;E%g~LW@7zW_=E}~ zpR1-`RH!n+8xqMYQNUlhX%Lj0y`3&h*vCmP5Gg#c1Cb>9!CSE~VOdEOotc?{0tJRT zTFf~&x)H2S1Z)KX+kO+!D}av=7Op^vqit#OoH8FKf^72Hw*7icsKqU&2iOr8tuhVX zbD43wK%DU3g)a~9*)%a79pf_IlEevICWAy?+^mIohvBO?4fUbzm`nY|ONMm|#Ze== z<sTE7waJkFA?Mzf`ulNsGr<TM#k`?HmG&Zs(sg&cu3ZFOVEJ*Ej0KWRY>=N%1z%ZB zZ%sqN`8tKRcY1WkgvT`tcNvE@Er%MdPocpX%H|bq0A;65!<M-gMrU8OFEL=1<kzcG zcXe5bT)rf$h)exkfvjT4A702SEv=j*@G^$kShF`n2oX8!Nn(7rX3o9N{TbT^4R(bw zqpf1DA%zE1I!vEdja6o`B(C&TuZ@o;-MiNbPbGbTNdLQZ)HdmyU+=5jF15oez?tFe z$S}dr(g#q;&lNG|*5v!8N>H2@m@P06-wQC;Z*C-pbMqc?SRm*+=41!`eca|$1Id6_ z*;*~Kuh*Q55vsDzo090|$+~~B4b<{I$FDErLgSND4MNF&TduC^%OXd}X2eG<4_z-= z#NK|~zMrx`Bsu)3GzMH@LI5q+Hp&)u05J`Wt#J7Fz~Fc8TyZ1Ul$?RQ&!{!j0gd+Q zI=a)Jp8#w1#`j0Z@a)CNbqjlKuddeYd%l_858ryylAM4Ukjh~5G2D6-Yrc5z(@XXx zd~Y7nLCCA^$iBD@WevZ6uOt{Qu6BEoj&V}_8zj~F9$w!TZxrp(B=<0DGjZ-|tv@8j zg*mblguUMw_e0k=J;z_fk{}KH>KcbBdFbdEdl@qoFpvG*4Nkk=Fz@(+LvGzl>0MXu z#}^jg82Wr;IPl4Z@B*TFFzb$8vH870w~HH>)e@9RSLWqn`bJ-CFRHXtQB4#{nx)*y z9J!X8LK#5qc$%xDk0q!c$$p}7(<S&8t^fL!cwY7SDX1kJ9{lmqL(U>?kmYHM<;`J7 zo~EWs<1t3(jiIPHflJTG_0HX}oo(<MyZNysxHAfV%d&UH;!z8p>*Q=J#*$x1TZgsm zW2xY01=srKbL`@wH{3S9_(NtJ4o(Bt_0fNlJh!MtO-Hr!#Cc8yrN3+iTXrSVr0b4u zB-9j%0K;Ye@%hu0s?uYs8Ps^&Z!&R%!jkgA%7#suQm3ua<wQvz_Ojy-k#Q~g&_7!z zbE%r}HY44?3*_b>aB2OM-bEB`cwrR2oOq_lhBLQrMUuI^quAW}OUT%W4X9%z1=ud2 z+dwve2muJj`14Zd5*ql2?^+@!zrZK-hLY~}R~uQ+QY_(g6iaIA0yWI$7otU{lN<hr zDdIv@N#Hm1-XRdT_?v99P~%S`I_CA(WnnpJ?c0OZ|3lb&M>Vx>U!Wi=MIq8VQR!Ve z(t>gT0RicqD2OxxX%Zw5q<5q%U5W?@D7{Czbm_f?CQTA*AR*^%?|8p+^u96f`-hPL z8DHCbXU(<dnv>yB`mpI2)J!K@%Bx?(YSat^L=ZRJ3Zgy!_cwvk`2Xsypa1T<IaR?j zY?3q_X(K`%cIWHsY_aL|$v>7YN!&dd9*S5~Bpm_dhp(1L|2~Zge+!*2qmo<R?9$V! z3b2`*T&qIFJG<IM&i@m2vm2KJ?4hQL^OGciiX_!BnHASivbfk`@BPx6ztAv&BL1C5 z8@r+);`gz>lX3z{4X_8`=Bh^UX4m-r4H5mU1Nh)7K-nt4U*GsocZo7bKl)lnEAfPv zd}-Os#aX|ar0Z#1@W^dqf_E?69OLYqeLGEa?1So<P)2`s5OKs;cC=jjI{kvgmxynh zR}%y8NbMmE$7;q6TQl33V`t|zUrJNGP}jr>_E@uH5jYPx*LUIOTNt%Dt#Qe3hP_4F zyu>G=0$Z7wI4VlGZRvDdF}9UbZsS-uKWjDiCl~HZkb6Cj;$$fj`I)hEiOkX5Eh^xK zlQ=AK(a$K+SBUj_)S5jXaldH&Mj$VSbXNtZgTFoER^vtlE3mfEAZB#`QTHjH%U`#@ zd%wML7|Sypw&yh{-}N^Ub&a3+Y2ypA++_H-`wXrv<lTbrFG8EI;Iv_a(3Ww6pl-1l z%-e+wCtdSGW9ed@$|INRLI5<AggOn(#{wi9fQnbPE4F2Qd*UhX^83KpC05Pgv21r` z4tk6rfK!z?VU35K);A}frL1SgxWA*CPE!zw`$};VKdp{>*5HjQMTW|)&!?qZ9VazE z8tMvpDEB%$FnF|KDQf9UT2}=Xwqy;f(lP2Z`}|O1cF^gboxTSNRX+U|q)PYe-0;kH zj~=!c^U~otS6FZA;zZ%)ylfrBtO60=CAS%a_DKR2_H=dWy6N9Ur8O=I#M2C1pvh*5 zZg8dUo^LU%LVsLxkMWW8;gTkrx|E25k;@&((a#`keo<ssq0x&{7_VSTc&kUevgztk z7Yq~&aRJSmXkh}1Kg__j>mNKG=ZWKD7=f3t1uE?q61_k$5?J6y*e9PXe&o;#m)~wo z1&c3;h%_%HDc<Yt@;AXLIo=2ufL5xWcD878hnr80`Pc3v53j2s12>wlt#shEE<Oj` zb$BHc@7-G?K}+KKVnpD~_?wT+0+Ht!rs7k84BX-(`S#>v>^%(MpgT__)4`tbYSL3E z9}~AMFH`Py2y@6q5%MV(Zu&OO;(MEK1hdVyk~=mIL2)J-L`Bxd?z{(ijid*tZqe*! zcoKA{uG4wHi=XdmT7N?ADi}hP&;=jHspG}#u_hR(-gkvO;b(8=O>1QxG7`?ba<5xy zGM7vF%aMsF<jpFWx#XfbxngKYZ`xM8+9(q(r`@A;akQze1ib3aXTF8ARx)Lkbmo*h zBRUyQr+m)+%QM&Qk~CiXTp6PKz_fZXKP3SP^^PSmcJ`OiGpwtvSF6MsA|zWKzJBA# zzngn4jm0PS*^)~M)bv)|it(aj*7$nZatU#_QhroH>s5@-Cp5Y1UiLL#pL+uKRF?ak zkW~XqN)@BAr%fE3wPwP{m!p_$>I5>{9}{=Owv3;Qz?CbW6lUx=C%MxqywM^7SB1DV zC6|l4ALmlew6eky$yO5|tX?v)gJ!x1kK=qk0%h0+WfAUi7krqvVTx(iTIOSl1y9sB z5f`sAXy=R0%7MtMx92sxDT2RlO$Sd_RXm<LmjC!TXk+Gyqn1U)o09V0OPiz#y@N!y z*!cT79gP`Vbs{qF*Zn^3<)~QO|4JbK$6e2lqh@8$$FMrdvSs{sP9G@p{tZk1woP!V zbB_pQ6{UMRe3*Mx4`?}?{ed_j{q?N6T{fZpk8V7XVB)WSw<SVD#X))PpBnK*1HS|x z3(@L$7?3WqLgtn=cK-f`Nbp(@1hel#z#(o~)chv#o=fHNi_GbE74Z!yvP>}$Y>+Py z%aKqJWQF1)^pk?d#TP*MN(-;`aeGmB=EOhAwk$j)t7l+%x_NLKdfeoG@YAhh|F=*3 zBA4If9K<b!=bSPCIm(tjn1U+LXL6BBXc8oakT#uu1o*>Hxb}Sz$h501HYgMH^&5#E z9oBk2U4_4nt)u*#s8g4!Z5cQDd9p%^((hi2Rue7d<OdO+#999FZ<TpWn<;cL*DKRF z-IS2a@uXX=;teDCyBL+P5-?Al&tuQm>Z2b{Wv|#b#Gz*QhZ>)XmG;#M@<j+ym0oG& zRML8f)2v{`hdu+WI$_8oe!(s7Rq&13G!d2<E9tfLlhdZ6-8rA~eQ#eEjEu9|2qdR+ zzd)33L*eeb(fr`|_rAX;Z#UeG+0flF<?9VNWYiP!;qaCHIH*xWu10YuF0?fqy}8Q) z#u|98EZoGp!!1^h8$YMrS07s+qpET~iLiUEXKP4Je))A+8}lI(Jr!voVGd~X5(e7u zUy**Dv-sBhBrnU{xq^yPse9GRMS8(yGt5~lHIj$=W88k<>-pkD23UlWmcpW$>T~>) z!4lLD<FfnGg+30w-3Lxn+Qm|1+FqmQwJ<jDQS>m(Al&_~O1@kvt#Qq(8tdD6<rt=@ z8~G;G6lL1oRcj|D9-B29GOiY?ev_r>eiU@Cu-I{RC49GG#R75-h!C98W9xb#%uXI{ z{_f7w6(zD&Ri7&p1^4G`#u+aOZp1B`grRst$)lFfK)Yo)YG*K&<TYKOF)R&zH48J> zc3OAJ$fA_w?TUg>)!ng%)~3%?ia$)Kd&~Ur`N@kuE?_kqN5j|?fb5*{H<6l@^=Bk< zv|@QevS|h=!+$VyDR)`p=hElDVrA;_iR?1<x7!WkOLQ1hh1cu!clx}zlC9Q$uKG$R zIo2<3`DK1_k1b^O)Ie@6ik^F}Rt|A>ufK&SJUTHF7&$p|XXq>_DdZn5H4Zh=7`(?n z7XPz|v7gUl5vb<D`caI#(HMi1SunGb#7?6!x+Sem-Y*t{b3JMkZp~*uDF$?@1y&Z< zZ#E<gX|h-LVS@VNlyoohn$0k*%fp>HWV3_;=v;b5n=Z)t1-3^Ooz|%c+5PGifOwO3 zLVdZm-b$9WUL?`DKCI8NVsyb!mwmwglj8=0B|cJA0!&TLaIYd2;<8wNAm|IoDvNVy zFtMSBdWxmqm%@;pi?=4cT@anG#?Q0!%VEX{N~c%ZAC?>&(=^^iYdqsg@`_}(v7qR< zuEE5Wejbz2%|>Mw7o9?pnD?H^Lx!2}pp;)tr2ieSsIP2`RoTGa+8RPzgsuN@`(4&U z%2(d@y;LxdKBc}aGW{6t`$o3R2S|r0DX7n^VG6IBx8-}#UKPgnWEJa<LSDiSch54! z=It;tPSu{sv@$emX`g(bp4as}`H`WQRW76tmYQ?A-NBnAuT34LI3Ey-iVp)KaLM6I zJ<_3NFrYak3~r>j6tkybd^JNfLb%5Bl2aYOa7l(%SCn&xU`izN)$P%VOWkx*UJWKA zA4WvpM{V(<4O?&cHBG1b)qG#GcNC)8RvuHQWn2>sK2RP0nLmwW;Z9racMx2~TuyM{ zc^Sv*$9J#Mm(y^GD<<}~ivXLDC`%P_i={y5Zh!N`6*dz^wsx8rw&aQ8k6c>?Tc!6s z+?HZz8#T8F&FVHs&L3gjGyF}+)Ac%K{jF=*wB78&-<yB36r(O8yD(Skz5l3lykk5X zu)1^@H?rlMRWONaWyc<_=6uEJMnS515`0$%bvu<5s>jnbYRA{AThWElC8k@Lj=M|m zax-?%BQ<CwarZn%I7McW7#vEZ25q5+W{e8Bvwg=ocBMsU({M^km&y@o?`!0R+qq-h z^&w@%+<A^EBuG6*ONr|af4pBIIxSXM(m_FfWjMzAX7y*r+I=5qg-F@d1(8JG_r?Ou z*Wa_;?)*&78QUDAx(W?*hovj}biRT_*SN@Z%Y}Z;`3vI<dzPc>u=cVpifQ&v*p=8> z#^~2V9`jdkm2*GC4ODdfBr1(h6{I$pQLSyD=ij=T>1&vnq!(i+sAxBEmY(F{j1t6V zt?b{hy<;$RsG%#GTRIZPB3WusaX-s$cMC_6(;CK+C1=D<ky;#C%zd9GML|{fi2xXa z<?S*7)4(-8!dSm5U7D%}hn!D-Z0rUy9OU!`Z{{NH-F7cj)N7KpB(><LX6?z|R5CqH zX|BF}{S;Bn-d(p+5s@w$89;|6wH);pG{|#!<0#!Ie0ri(>U^zmqNZjoY(nVMUp_x4 zYm-!8jEZG-j@)C*?b$-mDS-Sj&PJ1ARj55(?XjN<!t|-Hujah`YU*V3V;)GdrsxXK zK3EIu%I^#e_^GT+rLm<TU%Vq@QY#14g$wFrMzF5(TBZKtLUY_}AyVTBk$2W*)EUzn zDlcUQ`c{05kIV-5Q{Ml;%1U9lRjL-_Mwb{v=Q4P0p#U|J7;QPbu(Vr@JzEJAjW`&( z*}06`9^J_Dj_9-zqZ0qLBHP=Y>7dSP)o>SOucTwC%8#;jO42whufg=6_@Oz1KW&`^ zh&O(3c1Ov-<p8Q=oz~2amE&BA%l&jF*2cLBX;pRdUk;gU9>81XqDs%~W0eFQrI)JR z0NX;v0*7olwD(fDm*iNpAlLV8nv8Ep@>+L!Q#GR7*kowiB;#9Vx7Dk|JgH;NGJYVU zv+2W8YGnl-pOjKc9Yo!vYV&iq<?f~PEqq7L<_!3kx8=nV<w^6i4{VAe$(IQ-SVa^G zI(1bU9lv`@6*!w+RkE<nkPX(7f{i+)_D#Q~@ekAGwoN!uT3CFtT&I)`?V4vdc2w}^ za4e*<w@%Jlcb2ynw`?8iT{tK<lN$E?sUWbLO|-He-eW6PZ)UTjR#2o<D+sbqb{a|1 ztoPO{kyUHSk{u7D*Ut!L(qS@{0`inf(m;N!a0jq*YL#{H+(uCB9Wx!vlM5w5O<gS) zv@T1l@m^mh=G|9uB^#3AKa0HD3?`7b<e6gqzFLc6ixBo3)~4@h6jwKl9@Kq4;aY`g z;&_3_l#<XK7O+exfk8}0n`H`n;EfZL`FX<t4fNd;(+?&oL<iHHl}W*obayCIz?_6{ zOZ0dWZ;U#Mv?HuBOjxk<)%rlX!B2|Bt9{ArVTNla05_l22K~16cIol6%*XkxMT0N% z8p_9f;DZ%hi9Z7N+m6L&fqU)oTA{zaBOpamux<5WveKo?A(>5Ilb^G#*%yFcbZ}*i z)KsK`da1U;*uVhEgO}YB?H_lq_#t;$F}$XeHL<!Yph%IYEn_0pr>SJ+O!e`X1^I^2 zZx$3w<FH9MCioNdaHM@5x+nbU#L*cy&*aAUFnPdXcAN55&h83OMxV)1o@f<=Th@mS zt?sJH`>F78GZq6~KE4r;h$@nlGLug3q6Y$Ku<tRT_Q`O5yO*~jaHMZ2(8Bg7e_ebo zukkC*aG}*ZSgU^-&r**ojDy6r^qjC@xQC<g&Z`ylI_|<pr7!%WCDPBvtS)MRjAn+m z)6Ypz<S9kMd}H24x(JaCDH>?w!1%08b?%1++>Gv6qAUA(yT#dEh+lCy{UwciaMHZV zB$Tvz{2~Qn8;Q5`$Xn{<;JRe01<HX3Q^#W|;7ialm}nbLHv(GAxOXMr9IrCTJ)Sx( zlpflzR$4hJQD4zVwDtyx7C6sYMRY@EBpzYJ@prIq?VB3D6C2gmML|Vq?gxoy(h!l% z2HqhE+ym_i;`pZFYE^nX74L8Py~!6&IeP}}Aue5~%5vU|e+{JrP}T~9w?j1SniTS+ z&E_PHx_7;A?vDEKS8g@Mo%Nh}B&A3z9bA7xfnNZ8>zVkBk}M3G0!io@XCWG%yp_5N ztqbGFH~)CV*cZgCnpeet`E?L6ySn+t^L^JK9pOD8)t3HfdBMAn-ZWXtOHbImI?P%s z^y1*IY8jU*wP0nYkepS`d$8RgNL_pHRuBA^(*`K?co1ZY6AnFcrmR5~hWNPS$9#Xh zAY+e0`=SCx0H@={m(u4S@*h|Bz-VTD*B%dalHdPG%KE}D4qNha@hV2CSgIg#VXmbm zKfbcB;gWLa!xsUG_Bob@NwF%Xqf-XqovDk@U%ii-<=g9f|AZotlzExxZfWW{Poqfn z1>54BWu(hrqg_JRwMz=Jb^A<;Z_)W|DYJUwr7*&uBL>-&HHS#|m3~eNXq+tP6iLy* z1iZxtrSpk`%xoVN7!POEudZ`ULsHx%uwSGEwRtTtY+~>1p}eOSbwZlo!<N0|A8;bg z2NRb%S-SQLq)&}|+2Rt-FYA8{e0ZCb^o<PL;f^v>>&+2Y1xRsk;liCmP8)Xl3PsTS zlM0Dnz7M<ROF+>|v#nXf*Pm@!ZJ=`ZX5aghq)hML{h=#BGvDEH?&V*2s%{jrM(Y9) z)wb}VW+k)g_#hYL&I063sU(rfEfn$$q<y4&aoGg=hqE5@IG|GE%|Q-uPz-a9(TF4Z zvZx-w79^+uz#PH<(QkP~Y|0^rOGTOhX*=iN9q~vNe<|tr{N74e4h38v=#vO7!-SBU z@khkJdn%Ms3}e*sfv!rCfF(j1k^2!avMG>-`@<(8{J(y|N5TW4aFh`%>&$lDB6`+= zNg6H`#owBhxd0xf$Y8vn+89CcHUK`I@g<r>eL${HUhQw94@;+LM5w(LHVCI)?=LcF zdyp${@M>*!DSfLn8bgW?bA{{_5}5=4-ETtJg`5KYODvET@rl2Qnm`w5M0ce_E>&uW zb`5a;6H+(Zjk$G`r<uT6uS_~B;-QQI3|qzdFoPbGQhTOO<2s?rJdo<VIBAXVW(Z`B z0(m@w%yI%69aoXF@~i5d+5+0NP|P06{9)m<uz^qamHlY)W%15^Zu`7wFU*Iibu9wA zIVANu=rVPT@rCDqlwbZsee)vzVa;~YfN<EqJ}r`Aw<?v+#iUy^7fA-z_cY~zTzmkY zemd>2;Vw#Vnp)#|k?FSMSt`N6yg)_9713_pi0m89%^B_4xBTy}M+lWYk4|I$;X`6( zvdH>*yyDron_bpMwpyZzIOttuucD%}#2+*_A}g#X%8eS&^Gk}4xP0F6RHAFWU);sU z<Zh3EyJ^53Br-{_0aLbjRA(MLK2x8)Ugst}j)_8=1>6BHC4S&QN-rEPr6vF-Ml4iC zSHBd@t5XhE2R*R+>#i|7$b1T@vtPl;pj-wRTcsyZE$K59Dx6=5jdtP$Bl7~~Tp&H! zw<n~?%0xtr{(9q|19uEF#eC;jG9P!A@pIUN>NW6_8*n_mTujQD`SQOy@Z_WI>WO@Z z0yVjBE0$baWsPTdv`gQhx2SDORIj7j+St3fnFwNwIVl<kJP)@-FFf4V97wnWgkWX1 z)E{ezxt17i{!L`;nN*j}-;43<7E>GP;jRqxn7QF0?xDQ-Iw5`iM=n)pD-SGHOZv-O z3poZZ#&B+pyRvstpNc}NBi}qEytH(ced7((glc~CxL`)2!yT56<_H83kk-Gk$4bZm zi~<Str9hjUOu%jAs0j37wJE-y)yB;-6J+fK!9J`(`~-6Sa4@DM{a-r_;xZrvO|7_? zM(hU@qyl=hsxjP^+l>)!QU^u-&#zOF(hvS-m_g+B+r7f~$KByHqRe(u=s}=Mcz#rP zh1+Ux1K*>l*dkDe=P^f~J^@&xAnf=b?RhLq=yy(k6D@=ju#i>b>RwQ^R#!>jWhVZ0 zcyo5c&X(nc8;teBWf=GC==cBEz)Y{ga$HuT-S!mkh$X$yUCfLD_m3hy5zDbMRZd{E zc11X2QYZj-=a^^j$WDr?A60bZFeARP66Qn?q;LSW_38y6xUtB85wb6-=x1=a2bWph zQ_&u=InWCjeE!{hq1xBz%Aw-;enX_&qOH7<GP*uW#Pl*wBS1T#=wNAdpVWkY#YNza z)A$$3wfzZMqp)nB^u<|ddAvF*ts4}bbA`Y$2h&0=#aBr2H)}nyM?tBqx8z#Z%f@Ss zdG%p?`WwO@WPd(RD16(;VlwxfsW?bB|9nH28P1r~{)(p%-2=$epvokSM~<v?wI{0q zG0Ke6i=;?V+k>zv!^3C`acS#2_hoI$a$=jA(E&e&U-d0@TQjB^OzaT^EVo{Hhh+%a z>P|?mk>GS68fBinb+8MPUGpD29MJkgtiFJ_N?^wdfUY~~Ii9<qW}K`+qX8psN*_8c z9!?g!@Yje%3>G}M@l9l^Ex3-eA&X?GIDQ5pO_EA8EYeh%pK{^Tq-l|HRNLOu6bnfi z)eIOh|AA}0S+tU3ea&?KDZP*(U&oF2I_VYsPd<-zC>X)`4fK))9>rcaf;cnXn<|QU z<aK6`0AobE_M?*E#?=_A*DEgS9iAG?7glhYl~~ty^8D6u)Qz5#@v2lh=U^8{gpWI* zJUX{A%K!3CO+xthR_=>XCD8>)2*Af84wwcG`c+z|8_S0r`_d(tbo=D6R*jXseoI5L z#hjYL4CxHx^ShBAVd5j<OW-U(l^$@qMjM=Te#Y8idLB-CYd^rU0EL(Dx5vC5{9MJ{ zLpF|tyy(R(e6bdLJ+b2bV4c^)*V@0O$ps46xF}F!hQmfIzJe(f^j1KZwnm-hfQFL_ z+BwDfMK*&c&dz?t(CORq+%=U}jViDuM^ly8H|-Kl=h77V#OHOCvIJyV#GGi{JqyXZ zT}SJ>t}Y3ES`u(6<Qj8M5xKU)L0p{rw7O(XR?h2*E~AX57okP~V<d>9NM1D;?;Ls& z^LR(k>!QRnnVZ7s<1k2gDKdvaiIOmYyjpX?cv5!pPU>$Wz@1qNmj!8Gx`7w=^z~U8 zbX|73#C$tU-ClaMeJ9{b=8tEoQ`(M314(%?`$X8Lm5QGIaC7M-oFtqB8;a76kc$ho z=gAYPD9as@+?jF7$Ek5K>?w>`ENXtPl2f4#c@rJVYE}brM9x^8c#b3OBOuP87$j{D z%02?GwK}{jdU<{^Pdk69x^X<}^ida)L)t*Cw(-`bMswHZX9w9vVVb89X1FwV0bu-e zpn1c?cM+@FoZVoMm!NZ3GnRjK&qGkrz`$|c(XM5z=H1&}7#A#OH<l#7M|g;-4=sSF zqUBr`$P^7M4*M#kCf%H<qdTML!gn}(7_}Ci43#XT2P7Eu^dQQs!`Bp;dhDn1&qTT3 z2X{&rY@?p&WYZrQSFlWm3cPtyX6&j^Q)-w(dc~>w$9Q}dR2t5Su88+`P%taTJAQYQ zYyp3L6_VO2JB5clxiaf;g;%V(s{J&|E{HyEr6_%7^8g=4%qDo}1OyJ~Z@q@rDgHQJ z)DwN}qi{2bF|zvNudO!W3YTn+q{zPpqTW4tfs0#_ZO<xFu-`QR3QRXDbGnyk${_aO z87Rsp2Css0i}0!1K1p=wB}bpNv^J)<iHxwLLWGj6K8@<SUwTbvC&QnzQj7tZv7~#B z7@1Bb4y^wtydrw4t%7m}t3+wrY0ZZ9_n{w;3ftN3?wio8W`RduDQk}PruYmxad{mg zLF=0nX2x~c_@*K}j9t+d?AW(3>T?4B`6$XqYoSii+<FL_+5e+$Wl}s$+7utzUQ!(K zu>|K-ZSzB}hCAE~eY8Hz3s@$$q+FNMP&Hi3+WDwfA#+{Z4F$Qfr6e>QE;$^Lk&AYV zQc(V|q%-afl2(n@1_g7O7<7SiF7>l;VHzW{)+kwiz%n{y0%*SPNe$ZkBoZx*leaL{ z(oiV7)qX`)-?GlmvaXJlqXl;lE76uiL%8akN`PDxDVVwEVe?p{S%t6uT)G$apkly7 zn_><~6Er`plP&|#=0El1diMR{wdeBzZrFPt2qTM^G2KPWfar-S4BW{fJW_2TICraf zNrS4;y--ppQn9efjbVE<I^$*RdaUt-s7y6|M>w7_q=833%6HxF#6^aoW+LE#U*1Zv zaCF!TdZ^~JTttkLwX+d7<(~*;8Y&>ve!SP``swl3g%fq~qnEG<{=uHa^ib8krONp+ zpbu!QlcpPBA?i|Wi%(-;AJa>h+6lerk!O%_xe5_5U89NV{<e}5akr$E6+@MQYT;Qm z8>RW7VlSu;PphRhA9Pru?;E81mU#cA_ydxX#JD)|PX!nyQEcS$1uv>6A_oPEfUD;% zz=C!(TQK`!!pz=UrdO(MMr`<9xuRy}GiT2_JbQ2F-S3Q~6S0p9kOf2`ym5xk=&kdK zdJeG>$&4H}XrxHyjAA8YwE@xVki6~L$03}ds)1>i^@oa1)<nzhum?D1lauoO-60XN z?evfUVV3HGlvUQ=rcBe}yt*61(nYCuGcTW5m%$YkjCggab_~2G6xb~v(wnwRVrYtV zsm))&%#1u<bm$otTG01vO?aKHOeAh-i`X?-2&UCFJHMp5`A+G`ExxgXQ{aV~Z;=Tt z<DM4UVkJ9%b&2LjBO#i5VQ+5f$1Bx&k9OCB4E4IiyNi<7xZK|*Y9GoPn%O2il~0+h zY-TKmTVLb{P^-J4qWkx+SjIC-zz*d1<mAhA4V#)88BJLAx7*2tjDVu`U%hk#txuKD zbgw7WF^K-aft&~xvB{4cTsO59pJqpm#SO}~uxC}+c7%_#%MLWg*$Mf5eU$Z_p7FTP zKp&tuhHlEa7ZmB|y*D;Qk7}mJ*Lid57jkRYZF!l5;PrqVz6ZaJ@d<6^fI(3oTFS82 zQ=PHw3n$SlbJxIMETq0Ui>4U*w_2)uO!0`1d?Me}dQLhhBGVZk)5;xZ*Vv3%o3;AX z=>A~OYgo>XCH!sP#$fsK5{<4yaZ5)vcj5_nA(K;M(?%)2A=#HVe1Lz5#>6Bh`Lxn9 zviDFa5~`(9!|<*{<;P6=M$Jc|B=MrySg50*UZJ(oEix3LSYs%ss%1xVlS5tZg=OpL zCtLl@^&@}8T}X{}@k$OEVT=HQhVW{|D<jyp$9`z%ogtoTL2C!s{4;vn$>5(eq~T5O zabnPyKpVIV;`wmYA>1otS*F8{0~Xwo&6uWg2sDPmRUO?o=PjYsSK302@6nnLK35vp z?B~;q`sOYe;0RkH+y_GZDbU5+sm*a&1a${?dt7ixJQ*su?qlwIeCD_@yj?*I2Mxoy zyEo_$9~uhil%6<A=18(R4rv%}&T2X@h6_(|A|*D)Myf$`r6+ID$3a_@tr8mf_d;Zh zQEDXHI?fruLvoK7<A;JrElOe}th!^91Iwq!&qGP++eWN5kKS*A$${1)b#(9&m;x53 zEjtv!BmE88%yv8vI+KcaU$GL|_G!r4uutfhXC~!3@G}Bky1?b+A<Ta`kf^NGMZ@*b zaR-}^u>PoPSxV0J?Ydlk<aVStJ&M@UH{nJ;K39%=qBomTHwXvI8Slz1ULMTYz<Tb| z7n&(a0Qg20z&AViSR&)^1YTHGhj~kDOP-awn~yVJB6$LpUU)!F;p$R6k|u!1>Be@p z)Pzk-eUPZgU27sT%S|@#we(d$7&Au)GaTWa^_SU#Wl7{-Xj8LR7<EY?kz)NLr4%5a z*8HOLJhqo%H<n!dl41GF%+*?Lk8CDj>^<ZJ@`%<dmPl2x<e|ayiW?fu6Q;EvL4h(} zJFj)JH?~J1d!QPHO7kvGH6DtuF=?}~HP=m!qw`?k>VM<XbK!?11UZn1DG9;8(9=_X zJSY$)Ke!u{R3EzeIuUjX*bE`M?{uwoa90N6k|XXyGnI&kNnViB_m3#ElfX4GY^mUx z(Xy&;@@aFn%BO3Ao?izoI6x!Qu1YU;Av>g46Mn06|F)yt>qx9hwc9z6kU)_Bq7ae2 z1d`|4$bH~}PBD=ecsII&W}C&XV{5V>oJPX5I^Q76cKz^I|J=WjyzuwV$3M`AIfJ=k zPK1kr$vDZ`=%!EVG#h(<d~W%(CeSs+x2qs5BO%1$lIZ`Qz@Fv-lwtr7%OQ>(8*r0J zN_=o~L~lW$6^7zI1Hvezct?T^uw$9f<DZZto=;9hlYdOE?gKUI`>HV$PDueNxQ?3{ zdi6Jvmx-bk>1)LL4uKdjAqI$2|8oX+j#>E>1l=z33&X_aBZkvGq%(8e?inI}OGH%v zH_7S0CXwD_-h{a_`r~vv`{B&edO3*X#pd>vC%;piaw-4!EW~-xlkbY|pT{CIHZ0yJ zDh?+!sHwq@>EHd1Ge?||2iF>bl#nCjh}Ke($S3t5e@YWMxE*&f?#^d@&a-=ma;x#0 zkd?b>gxCGR!9&i+iAPKrQJ}Ny^N1<UQD6f%py#Bb7eM>cj$!mly>}N&)k5{NWjC>q zZ_pk|z@yy?jK2wN^bs`zcLM2-$KC_*?hhcrbGnO&B{D+;jdUh}5bj}_=H}W&e5eKP zHs9s805`D=$IV%wE=xXuJfec)&VUxkT&k!BBpae<9(+6iDBAkqdBp*Bt-FZ*O`z2& zhrJQo8!#ck>PbF*DRyS~?w&H+F+GrbYNvDqpadh3Te8IijP?+gB|?xWpl;KH{eD>q z0G{#D@u!Su=|6TZJuqo2J&7=#_uX{7F1^Zz8~d+i8$)A&Y!G6n1Q;&=kC_#zmw@SW zcHcd@L2|fnJP+H8Q*<E7$!moCu~;xV*y5KQ7@&d#03;ToUi3ab4A_h%LRgbrn;VsC zZt)~%qoa2HJSTtPLgVHlFvxGa`-oKaH#5#pV62Yaua-98^TPlp!FFraGK94mY8@~f zO2lBYlZjuedLjNC5wdc%4){nk@R2VB;AnpDkps9$zweY2=c>kICFQa4-80V(@17N9 zc6$0D;9opNFG$h|1jO;jKj(J!8S)>=AurnwJ!fU7;g=&B@tL^~Lx-Pl{MV^_rc7eB z2+9dSN@8gU*v{Wac1(2ITX{z4i6g#quW8`ftd1|>;d|wO4o;%r{#%nA(_T`y;7M=h z*C%I}J}zXR?d|;HN&a^1q<4SskxL`oa7LVyAun*?RqaG6v`yrDp4B~4N6Le}9zf!Z z^~gm2kF(Av(7r?bU_+h)Rh2TJKMy#Bn{K%00E>4AfoBEE3Ooj=c$|O<^4w+2`G7(3 zA+|b8z!V+`@ofP_-M#?baX<>Ft@T_VxEQ|_MV2Lc-gJwcDod>Yo9OM!Oh_TD0Z0u+ z=afJ)0#c9%4%@&t^ENa?@x%V|(jI3ntb7O6vQg{ya}VxQw#~tUZk(Uf;>daSxDv;{ zI{zLxMTc3#ug2=N4ENxlN5xG_;SZa!Ur-fH{OFi-yP8VJGVhOAgj%A%-00TcW@JDI z<#u87o1l&L<rLc>nOHq*P7c(ol0PXb2gA$~4{N=6kL9#S1NIswGZTYa)`j&Qi`7%= zSZmkj<2Q${ool*_SgC{GKI;G6SI$UI)>c2BR9SXE#BNY7F^i={BKQQW@x-Y?KW6@- ztVHN<qA*0&QU@Zkl?S6#h8ENtSD-}+%XciYr*+7oV6Lb>E$4ccbMNGuA(pk|rntL* z6TM`Yk@R>laG(nI$8i7~s4fMf4;W4N>0F8p)CGkTSfDT+XI-*c;c>a5DEq0KR~04W z(|6}*W-Kg)9ERwg(26W;42)Qpxv``^2`|+Z>z`0pq)X8;yXSFGol(TQuQqjrG(o6` z64IDl*}n08FHUHjKKEMSjZWp4OA5&=9#0<sJm&FftB}Q;Te^5|In&;lUJM96<AcGq zkXX1V@FmC|&=0OUfO&REz)-6XKcjVuN_*(b7T<fi2M8C1>ojKF99tXf)Of};H#=0s z%t%ek2G$DbXW486QNeOL2t+_F@io@j9LQE@8PSaPJir#0T_7J$6~>s)<!_}YkvJA> ziO!YL?#4@=>S;35J-ChgEBjU+7SP;IZKTW&c3E|?mS-0=NZff?sjaC;Ux0FC(xSQA z>B{^z>=Bh|=7AG}6}#D$LnlcNILqjor**yZioyvs8<rOLxN)js&d|c&5miGp8ua$j z&p&d#C<p2oBN(@9(A(|n^yt>U6uyJQQ5U0{GJ0R#RHu^-eU17;rao#7(b@Wpt@t*< zD0klg??fGse0{@39;H6hY$tEQt~%b`6<H7ME^Zca_-OMu^wy7@O3-dwkt3M+6T%5} z74JCO%#YD%y^RI98Xa=kg>t5I+v%2!-Q7?sr`S~I9cJSJxjwyuszlR*P){N=|4X1b z#C?oUyn=ScRyNCcjlZ64&6rEGSpJzw)vWGwUdB6&HH++jEjbAC&6g9&r#$ExXr+4q zr_60zL6FU<6m6X>N4U7;KFa6i$`;q)O4QNFJ313^!&8;6SUsCF1ZJTE^!j`k{+V=J zuzQD9hf6Cto&Tvu=&Yshdh^URoy#5LIT3L7x3*uHGF3{}WgHIMxXJEXse0&W^UYZI z?JqhnCN*zBv_(PKXp+c&%(Uh)+X~Bziik=lv5j<(A~l1g8dE)e>$&ttS!TtDs`raB z2~$u?goEGGoN%)bN>EmT-!X5-F@V2i>_}K-`+Q7uWOv_N-jBAJi}rbaqJ8T)gTu<3 z=T&vte^E9*;LIUVTv-K#?O1pcmNVvtBcN0+QV?qYJW(?2So@@e^p^sQ+H{@wp3f?+ zLhFN8#XjB&YPYN59eksz5HOL4H=K|hj^>cU&cWT>j+a<e3g`M=d`jfEX02Lc^tm3* zDu1o!8<ad~jFf(7XHRiWdOusi3@3%{?@2#N&*sJs(*BS$PU3l2;Ft(=*~s{-=G~~q zXt(FfiqpLCKE`KTx2bRP^H~+`zOWW}5n!)!?Ye(}y3QlxwY0WD4reKbq}Ya(wN-9! zo~-$7gQFO<p9E^4>dr85U)8rG7mJ_x7kr^E4T%x776kn?G#Yp8Pc12o$Sct)Fhu1? zDbWx{!IuNr0LMWIz9g0C``>Fav`y3|rQQ}HQ_XH{)6CELJ{In4u4N=rD<$DeXR~OJ zXY(F~i=h|dqRY+UmJ>xasiIM@y6`6FUz!saQ3w2a#-r<$nY%a4E87@<7Q7av5$AX! zS$T%&0!?e4qDTYbqARg}sMyw)5)0>DpdnEvWLNV3?9=i*)vB;Qo_peIfkm?l-|e{T zx{*za;4bj%zlmsCnP3!u6PaEBZO;y(u^hY@hI|^woexf}V%7CwtiJ3I4{2ey4;E~V z$+>8_+GZ|Q7W;q;9^;jlEdy=?EG^00%!2%3{rT@sTSNMK>xsquGu)D^6dp+%F6x{0 zbukK;Py+QVaES~#*r$#iI(LI^!}4*(GPn=7nN6XFWQwJEPf3lVn&U`5dAmWZX3`-f z98n{)d$zJa8`h6<>!={#-n`$aapXq7ZJzZVwik2$so%b=d(@&hXu|j}+FnmdkNt@U zovp@CCq@GJVL58pc=X>y-B2={w9Z#C1oly&rpjnyr8ep>eh77bFsoRVQO`MEbLF)N z{hGuBI#!2-kwR~$Js`1ojP*u=L(Cna*SF1eqmN5{sxtnX6xFwq&}=+#)t!BoIFqiQ z@Nt3Kths@QA<rSGs#DZS4$&PS1SVEu$AVQyy_djN(Yl~*u^+P=K~ta=)*r4msU}*} zHy9$dSlu1I_PyD^?HvoR#W|S`U)CaFdH0MbvrsbmY}>%Gx}b<>mA{x*#O1@7lXOz0 z?ymbxd@#Li+cP#$Osu{2nLlimXI<w52VKcX%B#b~^a?efV)-F2BgfH@V%^!XLY<0& zfbU95n4%baCDGB`y0K=1Wx*Xk$n`}Bnc!aJp`F&XNc*sZ1vD@0X>=bA2`GWz%#OB; zi$e?*PppBmpacV75TP|dQts7I^z(QCJaux2j3zoPGUHDhAN&-#(&^`7lfL|pb|Y?6 zXh6lpcNIheH^Bsa$+N&_eC=p6cTIA*G8Hw|`SLW)N9O9!MZ0H4)0OmM^Og_Cdbl)W zC2{ahOH3<3DgoSybLgd(0@G`QKbmGJ3RuZ>BuvX>_#rr|KB$}+I?#nR8n!mqH>R4! zBuWhS3cJ<#a;rWnRD+rEpfabVO9aFpRVR8xpB4_F-VdZ`K)k!4`<3&rFqg`WOFdAx z!u31#v&cr%z7%TKu(1QZRV%GuLdvw|reiD$S(FyjCY@&s1>Pi9oSEPpI(*y!e*Xv7 z9e$T}S_`)@yAFPwkkUKS>7aXTLHDjUa{{@z|8ucyg3fZH7>fOH%CPN2qm=!hg_yVx zr!t50O}(DCnv$zyhGZnf`e}T*4hKENW{P4=_73j`cEUfG$k?~~y_&)d*~*R&2<iy* z_Gt?)&bEk7E}ZA&u1~{xK%)676zPRz-FI{}wN<(DGV=?v%6x@6c2u(ee**MXc{2R9 z)1Lv67tZfLkw1dnAq~lhuV%ZkB(i|aDU<jk4rHf)iXA2>uM(On4y1H{|C3I%o{|W! zR;uVtzC)Sfg|Qghcypr7ALa4C#hvQEBP77M5qJRJnnRQV@-$5>Z7!EYsfs7_8yp{! z+!n7Vg@{7C|3ARskrVWQ5{Muxd;ox<ZG-qXPA@j-s&o>P-1uV1NZK#NHMB5qU(`bM zSnq$LGS8HyqIs|;5UBnZH;+Tn8GSjTCmxuda{zG=c^UrC$e7uD3Lp9tu)q16=v~Rg zNc=UGQqZ1y^HUj;0lpjTO%2_i`+qL`Zr`qgFc3^LL6)KC)FseAvCGr+RhT34i)|gP z5N9OwXPy0wqSgODTyWX?54is$zfzZp_au3g>AHO%S^i7+AwR^c-@|`pwskL#D}c>S z1(uXBsQbt2$LvVj9y58mpCk?Kr@1Z-<CY4E+(s<-{{W%!e_%2q3rqz*h?dX_fX{nQ z>!rC-cx-c)h-q_R@Ze(6OZRTEo>QbI;*Ybx+xM@~(L@pOn2<tVT!s=Z;xPp-6rz;; zldBDm>BODS>q&k3r!cvc+k#nt05QEkuu3jvnF-;Z5A=ACmk{I}UUr1BOwW%M`xJC7 zX`K<2)l@$uwy%%)9ep{FT-qlntpnMxSp2qJ;%~2s1gpP8)+k*71D8;D?|<8w0!4nc z4D@1=1Qp=)EGH{>47z~Zn%V7qqb5!HidXh8j12_vJ0A%~gHsxSu<v0Gp)r14nKc=p zi#)-u5)^^Y0UkWJEEl}8Wr2VGKbIWkD^6H>f(rPg7g=a$ToH_11MZ9GfM+PF2|!c1 z0=a?s#;{2M;F2ET(vy7?$m|FYUw9Jo>Klm!EWp@{a6)6n;m4AHUglE$1bPiF)eFXB zu}K$)_??#D4RVO=0Gl56@^Ih^^m98$2`m_X2be6NU+Y!1$i4Juzr&96zr7H-*MHgD z$U!e7dSaH20k6)vPrCoU22`w@Jpr}olcoK-1NtUYYhWwl{oGFH&M1gB`2Z#ANwhsa zboj#EZA0+HlRyUa-ShaPbaDJ9Ip=O;JDB*koC8M4aToG!#mq4FCIbKNG!n8~XpPuH z>Q*p9{w7NBJXSw+8?7T~vqR4>v<~e@thq4I*IppHx#>YnS@pZ>c(&%o-GG}I$wwAk zK(6zt=IulcJJq1M{zO}*<WM1=SmH(E6UbGpZ9Cxxz`R;^qleWZZj`7$BXFd3r0P3S zQsyg<Hv807Hs5(?>w8I1D6#t62o3NX8qr~EzKbkLPz00}uZwZQbvIh4fx=w($`e=h z^q9xIpV&L4)-`!nuBmNI<R4~Tg=5>_nD+XuZ1xDNbf4>FV4_z}1MwQZsEhmOW)(-# zg1&2&rm0)D4OPtvhAM24k8dS1JdPWk*&{A+bXg~)emh{h>ezPI1!@aC%=Sbzv*ruK zlYh=>%PvYxPHA*WF`$MyEcvMf&;cJruO;0Z3$q9U3?cay6nP^$`>$>pl^Um*KQbIg zAFp9FtBv^jVkxk8dzM3oCoi!YI1~6&tm_6Mii2hJ$i<_p91dA6z2KM9HviH6{r(h# zqoZ(3AOJ&tJ~dsBazsVJR37Z{-8ltU?gNiW@OC;VN<jtV)*(0C=|+K7N4eC6NP+0! zcS6d)(1D&@>DaC)5N_$2yJ;pWG!a_x;ZeL~&{fkHiwN9Z!qlmfJeKqW{u0(7CkBg~ z1&7%{L5TKtG<R+3r#6>QbIc@KPitQ}_qe;=vT!V@OMhV4^YR9#K#)I#KwgA-iHLj! ziU6uw;OY3)oRC)94pa`1qrMHLc77$i*i^Ces#F(HwJ@KXKa+z$@=xonGu2XTSGVJ; zAa^u(C{<j3$o?>m*1XkBlR6}+F`wz9YKxOxGHpr&trPWT>{uFS6mSn{E;lowH)9XJ z6{9z(LfPcAG$%Voiwsiri*^O&-a;Lv81GB9l#$6L6v>Z!eJUQ@gDauyb}<<H&PK|* z4&Aua1elwZ^HxTuT=JKMXJH$AyORz%y$)RI<7OJ`{a*mPwv^hy?HbKfU^B__7VJBO zK?JoFGSb~Kn>+aaxKtKz`_+DRtu0X(A$-I!Yg0&F`aSN8jE}Kzwdp>gt6MEz55R#t zE64~hjLpJ5hlQJu9`9snb!M~6eL+qt_$f42VPjpMvUs^$?>~;Sf5;kXe)n?zfJv0< zyK$WEo;}V3Z$5^1Sq9DIprCDKS{j(UnC?)NmG#)YY}SO2j^_Sj(1AQ@GwEVK=O=8% zckW{>B@gCQ-2{5iHds3dbOX+hjj!g^xF+)&izgL5osvjR)On@2+V3p#w0!pL6;d6V zk7U4nkSF_0QyN<gr4>lZavCqb$3Ik^Zn(+f`68chR%tZ3rB~-gU9}<JudO!SC;Aq~ zF7z})xEgW;dw+wkLV>l+VqT;I#@!G#$}F54#jmjD*MO?!eIcf~%|m@ve-6Q+#JGd3 zdX@%?1SB$MmD2L&onAPeobPp)(HX}ol$fbV7CwA%slkzpBH~Mv#1+<33)IrCA8L5^ zunhnzK+j?HE8Sp85dGH42cS!Rf92kD*Q2l+3$s*<=p7h-ZYFVd;t}`ae!7~W)?XCb z`%&Ou$~L2bc?IL{44Sr$L)eN{6Fu(}AcN`Zt||V+@8j;`=3DgRWzfm8P}1;q^t|Oa z+f=?X-I)UI)27^h>Xo|7<K6dxEfbJFnNN(#C+(+tTEy+l-&?SImX%l0jLbf)$OjTE zGvi{i_K}8;R+D9#1^Ok$-N{aVWJV#I;Ke>Ch3|<ODN>r=xAyycmFQp{9Z0rjNGYsp zg(ug0Pw+1-&*JUW8%-8}joq&z3n{qlt1qJ>^gyevo;+1tx$GJ)!(UK$?AS%$tF~sM z{7KztxhoTwPn9;IMD{I)6M`;Tt9w2v(*cULUC!CvTDhiZa`L)nT$Jbg-jTM+N?n}D z;*ME5iZxO)GBnZA-O|dk>*S-gY^U+=U|7ONI~@lCCx|!0;xM`>oh(25WmZb9_F0~H zk{p2TDE_Zh6&1B~Zy6K!2O^v4=(&g|#*xkSG#d|sLKCv;x?sG?#$A)=Vcd;gnT8D| z_j;{bSl5D^lb@~p^yp8WAI!;d=N-|on~{b@yuhaDini;NDLK_gX&7fZ4z|+?P85a~ z-PI|)TQo=}!|HEkWAD&EnV-rZ%v4}J!^!FLd?h8SGUq<i4Rsr`B9jy=yupNmE+)P! z0E~?+uSx6Jv+ab=uoR@zevTS5s|mW&P?f&@An#q-x@Bo&-c!|slvv&rTu!(W35I1F zNGi!O<gDzts6WCa|56#~T7M|~zPd7QO4pP-mW;yeIk&R=?QWh!dKt<fF{JwJG@Ncn z1-xI79$YZhIgz)vQ6|OlY)ZJ=d{(2PANYp4d?!;h@zH?9^GQj?W{3L4<U-BNoo*32 zXCr-sSaW?NLKV}aj6$6hxngabTTDOotOd~)Cvh0v9z<+<ODMA446caM0$nvX6Ae4o zrA`~O>CXS?UuqEe7q#1qO2>q|2cr&I+<|W~xM5E)$Q4iQxiXhSkJpr$wfmVQ)e~8x z?Y;NB>}cgi!(gAJL(}a6itDbH8>&h+0$(7ID71`Xp_^@VKJUz7k)QPFddS2?*|V{Y z(J5&ZI3K};?hZJ(-p?48|5m{3+2;vCZe!qr^}Me%JUbR%Rcb70vooH599eX1XDqPp zG=L!u!n30~0od05>e+`6ilN@u$TnC#vyie1ekP2o!*MK|F$%;h!nP;2XyK#tibw@N zjud8$YO^Ed&(z1`BGxC9v<gBcH>=fkmHu)R@8~DWmm$S8os5htU5Ckcf@xi=t>g|m z9-s?m%i_Ze#8rH~6&}u&6=X7MJrfHS6|24EauyRE&&$5T%l-n-9g!wv$H?t4UcJxg z!Vqg!<UD6MR%I-^bpeKJcRYP-xpRHXx_VvbMl7skq)fX|PCt5mtyD)phRu%aY~Gf& zw&GwI&oD<IpF#6>K&x`_lBZvn!dXazk44F>%;$D$&FKqXN~eeAxXZrQomq*twJhvJ zC-D9}q}60=cwmGO#nS@O*Z;Yu`0eBAI0+O*7|)Zlv0eDJVi>O`x-QtO%*b1ioo3X) z+mriS-9bpwf?WAU(@$w3_s;kBw>m@VdtSqM3HK_2yg3ke<whM;Hp+fdqQ2kMgxhVh zBoNRl;j&Yq^%SY3Q38i3x^=G1hIJjP$s+zmO>HH6uUSn^{#l+uIz8*i^R3|3ieuxY zeaKPy%SO@PELW<DjFCY=bO<D}kG}%q(Ps1&%gD29kc$_Pfk&hUzoJtRE#e!+>IFbR z{vPT+F^&DrbS3vv(I|3_ANW><0xa$K6hVK!CHm<AgoT2EznJ1nQ$SW2e&Im;D^lD$ z`qx~=sWt)FstmXDQ{6RzK_dEZunL08*e{2Zd-PLN|B}NWUG@GI)~W-PZhGDeIQZg< zv(1<PZ1X?9D|AH0q;ak56~I(a%$ETBPXB&rDPX}=O+5T7vi}0OvQYE_B=k+dDaCwS zFb&|6hXS4t6~OMk7xo4|jfjG*k+=g?bV}#@zx%Ezv-tyKGe{!Nu9*X;(TDhPzbR_v z=#RHV8*^<_X%AhE4{mbF2j2ZQtdyJsPyi6ayAWW36hB=4k!H=MawgpH+dsPqKY*+l z+hFL+BU!d2+Blm@oW*S~<DS(C{>uY*LA1L8;AyyEsR%m)1Qe}6@=YlzAZOKbkd7GX zS<sJq2dOFJF--_tsN7WW7Xa#X`^e1`@HZew<A7BmC<E)aVm+HIB=Q7c=s&YbpY%e% zVzu~gC&Aul^Mh!$#cfJvH6Du#CN$)1Dl;HgWX1p&+EKT${}dXR005bzfz-v6KZ_#z zQT{=fDYve2K#im!riBW&_XyDr@&^PtJ`>dO{ENRZ(*IkB{6UfqAUX~l0r3PMk2Or4 zwalhZ!kPaxN+Fu5724$8IVumU#6JN}-vF4T$@%xo5Ol`Y-$aL7GFt@6-xfY4p-SYH zhz*;vimi@@Jyp+iF@Zn!*#v8r0kBf>6i?_l1EWin*a6%$fy4pV>6E=P+Z6uh>Czz% zw1#L;Q2_fop!R;E1gRI5haRw<n`r!2f6Tp}gVjFzo9OH)1NaGW?f+T3^E&_yx&8jf zk8oz+yAow<%6I39NdX&~l;2p?Z2SL?2viCGIR>xlM_0K5xT;6;tps3PK6R|jNlaX? z^nqI8KPNlMgZ!uFNaVHj?=DDP8A=e1;wDU0zvEPAy|0mp>2dm6Ue^vixEv1{l6nyX zb>)9{0HALF-&JKLOh+8-;t3A^KC>7ssOeK2oy#tNA)x#FT8e=KCj=9KT#JEeGV$1N z`#o-=FB)U0V)r(NRLE{W=b^t~cG*4&q6`42-heHQ#J}SJd5{0w<VJHolI+?sE_6Y- zQFDsjeQB5Ia^0ydXek)&dfJtx(gme#<-v>KE{koQGc*)A)gC@q@*MQL{{7o0A9_B9 z_S?C9H>=iam7)ERf9TZbya1hg#yOq4wGI>9VX(tcTx>P_!$dmWZ=NsP;g<7Js$opl zK*U)4r>{>Qjs)Ga8&1mV(h|x^K}rTt9=&bvpj~dY<K?g?RnzLly>dk2uk;bLb8>52 zuV9w&!fuTCCttMXIyxHZ*9%@1g-()l;JWo|l0AC-So-3baWaXv#-Rx@UsPFzo(zn- z1JWPI(Zl3$mfA7A)XG`eQI_9dV@LZDJLOyA>X)b~Tbc(63GS{a<GRr0P-^p8lrIB6 z)fSz`evP&08O0#*+`%Az=$lNgWlP$6#9X~bYCuZfLAC0vmC~!0`M%UW(QVOV!^wD* z-=kX$I$+J>f6LuW6l9bi)BhwQ%qqM??u9oui$^S*5nXcbs^qqx=4hu{MHkCR5k@~> zEd}C_^}#9QWzbjR!*?snj=|Sw0c(qbMfUL{Y_7$FJ!^UIOi3a1)2k6=`6=&K9`_X} zFTVg^{{*p(H8{~mgLW^_r7Lxv$cQCc1;!IW`4+bo*T7RxEW~R3-LaXqmEKy-SaYd! zf8>qVUUs#IOwVL!`ZBd$=HQyxX!{i(v}#WLaecMf<5Y6Vh-0(V2~?8L+pwE+6tx@k zV!`#BcO_N2`UG-rw-0d~@xmrG4}vm{MhjWX%@d8a6<z$m+HFux0@=zyV!3X_%JyQn zN6gu3ba?efk-%bCgF2<A^{7DeS*e<PF+ZP%hm@!Mi2x>kucpG>F`M&O5<g)%p4>t@ zwhXT|Rdz(yd=F)1&Qu`m<E9|9t29Uw-H`5FpSX?U4U^%dk((;Pt6hWxe&9f1sbeMn zwE}4w6n=l4aC^sx7F*P#Bs_Tw!_$Pi=EpBAjGu9JrBO|1b+9vi_tIDXaqzI&btm;q zI2$&9H7Drwlm#gD3EN3FHLRvjn(6m3-wPjFsCpjp)g$`5eN+zyi8n#Ac*V~`j2`SZ z`>$YK8C5W@!IvECj4K~<4U`N2<-TxZw27`kBQMFbpqR@;gLNwz_AaHnK&f)uz<LOX ze)srGT<>gFzvsOouX&mgHG0QY4C1hwQ+OISQ$dZYoPSA58|>a=m}2&1RV$@Lwqd-; zXQ)I+V*NvD7he(ixLyoU*bK<PfR`EDujR}Dgw|Q9*qYjCoC?+lI(igqtNs5__TF(# zEnVAi5EZ3LS6W0skg5WL2m}k#1f+LRiZlUf5~ain(nLW(K?q8dF1<>mH<1ofL+>rr z07-m@^PEHC{oLpIe&2sdcJ`h<Gi%nYb**dG>hR++Q*`!pY-t=o>zGhqw-J^qBG~K{ ztJx(+Na+)tD&Dk8aHt`wU@)*#K8gAHZNeoCO<7;+Ifg$pquo)V=PEL9G*ZLF(Bwta z8u>BMu0?*%+(fVVxVWjQkWk<|IU1J+bb;n8+;x`;Guy4t80(SKMHe!S(OWnD^B!GD zu5O@z=`rS9<=5w?f1Uo_qvgY~hFMbDT?EcytZns{f#2~8jA;31_4{SfAjXc((ZWd9 z4Hv(&tW>iukG+TF8~CW)9wz*RT=C53BfE<kwYXFY)dv|LS}zxUt20p)GMD|?sT)}k zr0sO+qsOha3ut8v@_fBbWh=)!bJFGApENQZFO9V{{YZ4NV*h#JrE;%|-n&xM2^QS? zmeJ}=fZuUDb7t(+9t?~AJ|cyo3tp1%nXm}hH5-XOvTi)`NSv2VvbHnOsk2^s;;M~o zb^rLw_f)o!c)`7T^JAFk?_xAndvb8`h70h88ZKylw=8U&jt-7!J-e*PP~pbAG+jU= zvDUzSVJY<9J9ox1m8In}kZs16Q)eu-3hD31o{zcPfy(y?qc`tY2o+eHDpt#AU|Bnr z&2XIEn@LE#qT*T}Gly8PJO{R=+MEFcs|kBb5L}m_<FNbsYe6h$?oH(<$24`mthnU@ z+m~Zf;VstA&i5|nzRgYuefRZ4yD#cEHm<sIgxMxA^>}X@g_!+0x0LMIm}tRCRgDXp ziky-`O1y+O@=#knTj`$ER$()K3iD*eo5_OW?-;TIQm=*BvUyza#6Pc1W_vdSC=qcd zZzjWN;pL#JR3*I{>r20rSR)BJMNf4v<G#w%VWL0l)q;1j<C%&pl~0%0y+GSNTQj&s zn|p2TZJFJf=?YHC=<g^hxce<^Z0hVlaX`wdwQ;~RNfY#m7Ml31oNt92#VmQbQRCH& z5?&YI@<uTER(*DSlI-NWH|{(AmhQVI6a4yE^g!k&@2ckra!g2!b}1jEhh1v@h74cI zJ^lI=*JVS0?c8ewLwnf*7cvk4gz0q?XlBdW0y8)57c1H2qmXnyR5aaQI)VeT4`^=U zMIxitX6rs27NE9EzkT$g3NooBf0_A*t9V_ejZEZaWI0>zv{yxR`KjcL@Suk(Ldm?# zXjU56wxhO}Iel`3qZlcor?GW>C;PS@MdV0d)zK65RxJr~i#qF;te?6ke|(Jj(be{? zcAe63y61%BSl@{j#Gzl<JaqL4cM<lHi+tEb>zS$3Wno&c3DX9F9>0*{gQl$yIwjxM zUOdJi&=VqXC!!uz&=5wrGWP%rRV(krojMzsXkqAp;k0#X3-lB#7!j$Awp$avXnYmO z&)cTgvzZx8ep)K=Mf})Dqja<my?#Q)SR<Dttdeq{b%z-D`Ns94_#2Z$QjtQ+z2O$` zwVZ<92dPNbei>J^6Ptf5RwW`<TiiQPJHp;m;h199@8D)=JkMev^DZW_AslJ#GQz9y zuFT@{4c<o6F&<x(1}cAE<(|jqblq_EfzB7H(1*tS%}Ej4#SWN<+n|8W7)X|Lx-GA9 z!lZ6|z1h%6eLPu>N}FlQ{~iA;-M->zK2;AM|BT>N>g!RoS;l&+8*@E5`fd~4DwU_< z*)R$$r8k~ktKFwNUQIfww5;d;R5!cEr4v8;t~08N#NStO^ho}E^Zxtqh+vdUsKbmQ zKG?@=6kxmtoeUTkk-Ch*{#zYbq;5gq4Yes&MYu8m2W+U{o(meJes)c0@i&A6OEnH# zY#0{;d^d9JhJE~HY{1dy_Q}Vy>vLTbo4iu$PTKRGsC&?<WPh$i{7Pe>@GYyzejD`8 z0yu>sjo?K3KlUw39>?EYuBSUOkdn&T(-m1!a$+PaGu{v(a!ZSMwnSU+tlp7BZ_s>o zk>`5HLL6(ZN=w&OeY4K;G>9zDyqwY}VPb6F=hHAREB3TjzqW-uFiW*K*Iw((#AeXa zZS#T5iC}l<taED2I#e?6(tBUXz2p;c?@r?xr6VyyHJ!YmFL?Hj%zrSxK7ABegBRL5 zi!(le9qI)zz_X!y7jmW<HyCDcXLk{}UG-f=D3rts{Q>y3G+kmLk=l(r7PgmNq$*c# z`3gcwp06@$fpXu_Tri{g)6obY)QG6o@KkHk*S$Nn1T4bKGjnD%#0aAV8T8+q<Q-Tl zer4&zHozY`bJ8H<<jI|KUvLKSz~oHBS`n@nffJGYp~8m}WUZv0NC#YFMdPjKap!TH zCp#hOw94iWq_?tPC;VAK1<)^F9Jn`t5C?#0-?MmFeQAsUIe-p{*U|&3q%yszem$D` z1iZQ0Y`pv^2;YFH+`pOMuj2XhJKxxc4>q<sAHLrb!cbxDzNAL#!Wojr6}$hiz<azy z8C)1tJ!6eJCEnAdoprmgwzaEI^N@=L_&C(iRWbar_M-;Gk@!!4gQjrO{6yHE4CYoA z_xg3kcJg`vDL(|~rb#;VXGjq;N8<E32xY<>1@hz#`U8ijw}<CKz|DUaPdP*4*=dms zLUvRTWM=6;v|7~jN)wBo>(r6I<{Uo|OB`F|gvHKb;KGX$p7pfcrcfsx6ZKe=VhpeP z=Yd*G1@JZ|>yM&ii#tpID4OE(ul~o!;Ob&y>x?utPezf_bt8kz+>gFb3}pV{YDEE$ zm?R-$JH;b=VhL26x^Z8w5y|4HhtxsLPeL|1_T4m-&xkev=A-i!*gWg7&k5J1pqrg# zP^_AV<_<_rxaBCieYM-uvA8?)t?{{7kNZE#cmR{1EeN>KFRlZ<5q|;P+@XX!!-mFT z!U%*QNIwZzxUNf*U6XczMoRZh=JzPUjFLMWlez$VjG9HR1JibUvHfTq$;oTaL@->= zfxzFU1JvJEt)5W?lX5hhJg230w&_yU!pM{J0$DKZ4N26_1Qd@4^&hx_m)v#|P<3Y$ zsLV;+^95ulH-aj^HS;dZZDvZ&ex5l4#F$72Y-SAnw?Bb~q%_FB*b>{knl{f;$x|TX z95pp1%uanNgtj6EGHv&-tse8avhUp@wgJqN{j)TfhU#|5a+gk}qT$^uNj49ZIb|rj z!B7?704M{n%Tf29NX%bBVK<@)rBZ8>*9i>6j08U@0Ux6xtDa<9-`k;4H>sUY$(3~H zHU+;Tm_3p%CKBjrTnO+6K=4+C+#{t0yP;NJIU?5UVSBqmHnKX2)z41xJ2gUJ<#LJ; z2Q4EcalrR+7GiH9?toj4^Up>s<fcdFdM7v-XAQ+fest)#RX4%+ofql=(sYtGX)-3Z zb4UrKhm!%pW0Ltde(aoVKenLQC3%_hM^coYb`8bb#sr#lA#q{{VI<>EjRpkq4d`aW zZcJ?!-h4olNj2K|CMS>jYcS0}z3~o65`p?b;-3TIA!*jY<5g^RD{ooVv9l1R{OKmn z$G&#t1BHlwsqvM7O~)(>^KKt18(*6TTiZnj2xcESrlPe(X8150mdWPMRc*4vCmc{X zasFDw?kRb|RvjB!o%s#n??o*6f|Y{a%Ex{>od4At8<>?rC%nnJPPv{#To+LhwcW|5 zE{kY;!wAaTxvNbN;PVB{f}z*6L-9$EFQH~SX8nZl(Up9fNjvuAE&&QV>3)b{0=pKv z6m=-yhj~?K%OC4B?&!jXlfmYX#*rK4p||8r6tOE~gC_5#5^wJD1#26aHU3CFY-9Mm zO0vcwx_5-Pfbg^PV?}w*n19F9zKG3C^uc0ac0TE!If+^YEQTfyX2e&=&PbW}kD4#4 zOUx^##D_}E8Ko2}&7&7Fqp$&uiLuwuG3&bcwCutq%Mq#vvSP_Nx9&nJ6YtqOSD9j- ztN8S~i*&zfIq!ciIrKN=@u|C^H~41}{sdm^w{e$10%I3Jn$S}`Lbd7*f4v4{#zrfE ziGlwdxb5H7=$k)a25FLQgDy`r*<ZD(sig=d)W{#k7gTZ(ejzAOwqgu8lhuY7%Y`}Q zHJqtWWv`^0I9#HUe{TP!YSO{73Rg0s7I$fE+00ypYB=)Fa()Ay{c7~q3_eF*7{`R| zz(kBHJzw-xL$TVMbN2u?%Ge6I@sN7*Fv1D`@Fbg-jdQrExe=)J5YgZ+I`ctWD6r>+ zC15P%U+`mSppUw9K8z~5Suas3#;+m#_Ez^oy`Ub;$BszB&{lI%kG?CBnea_)Ks8QZ zJ<ew3*#pU`7pdxd_RWAv98p`(5)(x=6n0V1^mF=6h8Ii;J2vO=W|-(|3wj9@7nXfY zbFpfI(?$ZQVfvBTn6^;AOYqwk^N%a)_~Qr0n`;zJj<uF3Q@(@@%QTf{CGN?FiGi+- zdeu5z9}_Jdw+MtXjkvH6-nb9IItZ#t&P2&u#7^N}u*SD?0A%Zhs#mKx3SK-kN4>xu z*z&4x2HH=zH3R}zYc-k}WPRwBG4ylKHh(U@&cfECBNMf)lGC5khc#tc9^Wn$SK}*) zxK5jV4>KYa|9Pv|=E%D%?gIum7O#nw2C>&rdf0snF8E3v7g@XCF}tX!VsrA<%GA_; zM=4va-la_HtmJu??ein-$Fg1C#@~$$cl1QxcQ)*s>8T8T<bT&Vg^uRt3mZkHc-Kg! z#}VP7C;8d(Uql*6E0&14&Ub5vM^6|P2OyPhwOz^*R-*3yq!j*+|CqX>(ut{amy$JP zo0*x?a@^FSE^L3@Fpz?Env-Ll_7vx(2C`EpU{vrcH&&4W*~{Y?=&Pg2<7yx7C;3A! zja4MAt_E7FsF=3NUOX1v3Qy#3&h{Fgsa1C$n+cT&JA{K_VdKa^gP5h5;W@<Wi{y7V zr-yro6Jw+cK|bnarM(+>jirAvzJ7p-o{&HcwrqJ}^)QSzNP2mBY_A0iR%c=~tkxYa zR?nJ|YC0sr%3`ZpiaP%yUwOp4rQiJACHotLBjT5%m_nspuma0zdsqF?=v6J)aldwp zyrg)3AmSnwXNtL~Fe1~>%-Q#f$xg*9Kd)iV#PAhl_A%TU6!sTLEfunnYFgdy=)dP) zgRs+sJ4k-%j>!@zJR;*-EU4kL=A8b{x>My^mrD5;Tmuw-eFL5$>+EQ9TtAAtx9(?- zyhwEjH?^YO%|vHLq{I}|kKQ0v<92welu%BBhm%$9@>UstE%c?|*;Ru;XJNKo&7<(o z&5}JLOFm5<w(zB-57f>gQ#KwCO?eJo=Skn-;$B4s<9J4=v4P{L!;WRP0i6QLzFu1G z%Xjk)r)&&|e$1W_%1_Ywc)^DJGIP%AdOadPU~wl2j-H^a(}ZI4Y8oCtjHbzyl9CF{ zHir*vnb?U)>{$oxRQ7wi3g=d*aTwed_U{ij(!Zi9;R@xdAluXN(d(-?2e##b*V_aJ zO>&XC-qg{YLk<_OC)>-IRo}f+R2Fn{xwUn`WG5ntp+)wA^M^YRP26U_*I-!#YAx+^ zvYJmgw>DFXs$Y+Hh(ilabr}fp@uI)kq2k6Y$ov96s@HT&2Qwlk&X+iJ#!jUfNAjQ4 zang)zJ0daRk$mc>O1h{0`qgfYi&L`vdwPDYTyhv;E~-_rhPGo1#&sR8PDyj}r$M2^ z_n*Z}3==Jv3iaNPK46OYE;)#>A4IfW3Bw(Z03|(hgz#yndn7&pkg|BpIe&~(XgnbF zEUm0?@vF1ZntN{7&n7Zlw`GcUdny|$+1lOyqPS~v?Ri$x600~yX-fm2D9?s1ua?Pa zfb~08BTw>SZYIfIxI>Uy^UU~_V_h8OXs?y}cC4`Yx{G+r6fgIS*JiQz%`G%|W-%J^ z43hdz$23fTo=;P6_@LO|d~qiKb@+C8VNZGC><sh<GBHK`C12cXF;m-#Zb22TGz&WQ z?k)9F8TZIz?uu2H>&@FD!A>Ti86&@mPj&hYkzIzZGH4RchAmxj*_i>@@RM)^MsiI) zU^E%STJvyKb8!<>KUh;#wvAJlh!d=zU%zU7Xk^;!ne?YaUFx)F!;Kh5wAh*$ir?>1 z74z-!_`or+YR#aF4dY_328u&{#M4cg%1cm~y6KcQ4ofYLttJF_)DiCDg1cuPRtH|l zCpShb#!JStB%5-HhRmqDtA31B)}5N|oC^0U2sbEqbr95-TNc27eAKHJp<6fg(=fdw zacLr8w>i~VweNQRcUAh2g<9_6DbpW)lOw|SqW3fg36F*lqr6C*I&|P+L#6=~dz}9_ zgwa9-Zm<<xj79C;zA4YTe~34@>alaF`xnP3nb5G8SsUe949D2)ZHr1vi-P7vKHn`} z>-^d4+ICSn`MN<Oyl)~P%#W{boKtD*Hm2dlMB!@Ppb<--$E99SBuw-p{juUpF`+pT zTpPZf%#qBzua)ecR$*~nv-oj8HKCqQRLQJKoq6v{Ezwe9A|uWEj_Jn8pTCfav`){* zR86m1h^A3qOr`7!!K}VCmYCNMrF6^Ec;sPoL_29T(Xl8tx`y&KS8<N1eZ1fWB;&89 zv`5<4Fus*_)4$rk_pW{&Nj<{t6{xwIm=|(L5sqp={$kxy#wTW>2`oxAaS9{CQbKpX z%x(9zt61@lI!6igRK$HxKTpS=a{ExS8%;*rfZDio#HvGAt+7EhIPZ_G@_e<yp2c&k z9I0OTt-E*B*i?efmFoQ{<D09Nzf_o_Y^XO!VTDi}i=RtBd;K<)vhpmU?Goz<e}J`r zUkyPj#!-2kakxq#>QTY34>oizjDksSJPq=<-j<zgYnk>D8^3wgA7P@$eO&73w{-ip zCV8WqlAKvWs+}eS`tz=nvSj0;YJs7qvE;84Wtx+$7T0}5F6*Ug<mnXnzOdB}D^fKb z%KjLmC)znJPk~+Eqwu)}sup^gVoeEGRwZ}s4Frp}i!0?iB}!9YP8eA}5)l)fh@lXe zSH1X#_F+L_;b2px0HM`_$wQ9fHm0R*Ol=8v{p;%qeHmyiC%abs2y5x<Ve9k8!%gQj zW#G5JUL$*B9TYqPU82hH@xZ3$_*h`JzO2uWaCc8tln+i9JXnSaU)Tv*%)R;4DwK-z zOHjfnWj9uh9UeB;P|qGGMvGj{60vOIM4iW6dNqvC(8YMnDgIPJdCEccBNld{b4qj_ zpDcuvmDrEt?`k=_ZN0JYe#w9Cir{(m%c4Pog900v7$Hp(;~YwK0KQI&!dX{_@Qk~C z*G&m;0;)%>77m|A9+E>|a{aim8&v+M3t<08<=1^WEzw!Ym@h6O@D&o;IxT!Y)x4<z zxwz;3z!~E7e`#Cb5R4kp_z*ph-UT31X&g+kvO|nfx0_!7q?=h}6%P;j)8)UM8dA6O zXfkkG2g7!^5%|MBumcO*J|7#VTKRM_Yubvp(JF+ANBAbiydC+w&jr9zKLM85ObB9o zW8XjbF9tfx3OHAvpNI>gG)v?ooBr^dvObNsGT-dFV(m)E1P<q4Cv1s65R~W~wNpru zoP0K6jpyv%6iSn%GHkEA@_~o%JD(;`(0_PDcgI|IAXUF1hX70ydY9B8%~FTy<+b1M zQteI>k}w)cPkODw^L9}Ya=+vM@W*Vh;F!NFq7MWv+hcMwybbbWYuB^3-jLS^PUX56 zPalpa)aq#-82wCSA4twU>xms)VD?tBz$)GdFyxlSJ@S^nzx4C5uOeVV{~t{&ks=oc zD(S;j<BnRXb7GZxuH3YjLKEn__ud+z55!D>{9=Ku5b%9x<--7hLlQ<JjG8I4+hsK4 z4g*1gH7Bn0n=)Lad`(fx1d1sBAMKm`S?_gzSymC4oNI<Ax9U|U>?V#JYdQZNuMVb} z#3N3iWJO@M#qb_3Gg{rz2OrzX%u=2Lp>lNDofHbr?gGxq8_8n48xz@n8gp7r;Jp6L zd^V031J_y*eUh1F5TT@1817LUh}SEvWjmK?l7lmQ9|3oy8zBf8+RyYy*8s)Lx%@>s zpqySv!ZhF>0|*4vk+@b0?l!1GuK_5cNF6UESm*-+_S|86*67YBGG%~xd=6kM3dOL^ zw%wrdg#wTY@2N9l0lCRs*G{JW3$(Kc+w4KaDUy7KczFQkHFK3IqM;VKf}Am1dSC#> zVEFfDcG}7RBAR%B$~1$BK6?H66aX#!&4-3CH^BkP8@#1y-;RNaX>>4Pz+3{oXhlRq z?(I`WI<Y(i*?RyOMYrn@Tf#}cK$uB#zGn?oW7=@ugNRCW<82DfJ#a_UD9!*B@{7#= z4VkNcyl%XaGblySq!>rx-(`9IhG;PM#q^$Z*|vKu*0`~rv%@itSeOJy%2OQS;)H86 zgp%TQ<{kr~(Y75b<nB27he5XAPd|oL{xFoC<{>!acvP0x-LW{wdSkPIS1XGU@j*j% zFD5SrrFRiCh9CO<lqTsS%eZiSbXk^Z9p6fmqFR@i@_Kefj3z9FYG?xD?3b7ZH&kcP zQpVlAs1p?~AX#^rna<dB);%Ai1iSd7?Kr8!WwlFbCZPUGRNBLsXEhwFa^HURCND*a z5bl%dcW9q=IgQZ($8cYw@<X?Z`Lg1XN7FDCwQSCbpWqg^4LY5L#XJ@+j(6Vf^uIwr ze*Agkp(u(U)Zg*s7(mM5#sq}O3nHqUda`|(M{}soIQpIP2PG?eY>I+Tb+%}Qk56Tb zj;I9>dX>G!?e!1Xe~#J}HJ31C?5{kDs1lby1edBAIf+GJ9P9F0M_V=Z4mId>P8Row z7PM;W=D(J<3|@+I8#Gry-z{%N_kZ%VzhgIg%^cuLTH>O@WA{I&n7qmmvv0dn<{H|q zD=;oscMpBh%_(JG?L(!JMKluQ%sc_5v*Pf@tT0nz<sUQ6yJxHZ)HPFFG8IPl^05`g zJ?;@`N=nyI|CuwxALv8(#fN)UEX0R#48dT>CE4MlayA$rJC2~4e>q_ntm%3RPWkAK z%Bv52&k%x!@6!aEn;T}K*t31LPF^~ifo!PSoFfY$h0tOF`Z;Tv$X0H$154DyfqQ|E z4p)!2>7dGVBMsiI4O6dI7rE`6Z)La$y$yK5$v)@0VAhDhEfhJ9E@d9cC24W$7dSCY zl@t6BHMm=$b~ZWvYu83gtmYZJ#By(mpc{cVGV{*AR_OHkcqw-@%W>;2KH3F#@5%}@ z95FhHJ|Q6|q>HWco)D4Wn$TTcs+&~DBR_vAK*}r@E)|9@?c|pgggS}144mSNQmJxD z%|JGUNSl95J<=NV?vZ)6GfOI4qzILM=mb-AeyX~v&)1Ib5DVd4S+TgOla&Ud#y$4U zRPnmqQx06s#_rO4Qt+S4f=P^_Qf=D8lc@V<RukwK@@LHb+M#sFnt=tZU|Y?WHWsb) zt+bnO^+mp+GN!@F(T8#I(z^Ns=g|t5PvP#2impdG;<-atO(rbrVWGxH<3?9b__dd< z1k@w%5P16J1r6&(3*(qOy@S0=X1+Nt*#BUdYp)VA5z>@hO72%W%$v`M+|#fd;l+o^ z^MYiVeiYcS319Yl`!U}us=ZwrxhCw6S7JG()C04kF#Hiq!nc)pds|N&<Kp<hqQ|p< z>@VH|%H)|ZHgznlmhLHVOXPgV%ye$#cUG7=jvp`R&mQf;Nv1j&KP)P`$sW7#qKiLH z>olCj>TupG#3PA#UA=J|&(%^T{~f*iXUQz@q}|raIms{hAn1jls_N&62QQL_E{mNy zi?2J`?6xh9xfb=v+|y3@{<mbMYjJ{Fu9NCjU1=@gq=34l483!CRIYk@&mDY;a|P>| z=Cfinn;(;3C*kxeC)%GNVuZE&9@F>Cb7wMq;%aR5V?A8B#2ZuIzLsf?wZbmhPWlHI z>kKJ(x+eOT2KNl%R%6!4)o{NKaqKePD|wD}k3l)jy79ZCO~UM#q{=+&vgXZ2R*P7E z^l4{ud32hanAUi@ayABM<3CGkhM@A#_(&FY$g{zpkA>B=Vb!v5?y!JOcI#4BdPToJ zl~Wcn{i1d6QuJ6tMe;vY<^^3l8)=<wFn%*J2gi($A&4!E99uQOo%Lhs!0DvJ4>i;+ zrXfBp#ItsDM>QY+tR2CZo7?T7F1kAcpQf80xyJj*=hq|xS$D_HC${FJh7hYpoWuE4 z^V@D)&ZfD~!x~OD)jNOIGrg;w^f9(P$n$>QEqMdY(=Ds{x)_~W)pt|o$-Hq6;UQCj zFXi>L1M+Ju&kb}ljp=8p=)d?Dc~Y9-m%3!Mr`UkeZkW*jgz+}&0aYjG^`m>^x%+0= zBGE_(oyEm9v*XmCFEBZz@4XXtC>elcw@pBCOf_4R_)mUkX3@-*l7tSnWmGoY`9^e& zm!{x=Xqe2&SMi-!t}>Y1x<!8>{Cs9BTRy}0^Q)z(-r~LbSc{oT##%0!@8b_PXQw@P zz9@yq&Hq$AQ7p!*8>`CF^;Xox-f9E6C>yD_l|iGf79BoMuNl5Q^)08x*Qv0rUF;cZ z)zx;%YBhC&FS_2zc2ud_$x++U)oJ|77oW@WNYC`dA9+JVF2yA$s=O|&8%--e6mKaV zkFa)lZ&3)Qfn{$CiP;X8KLc{;vD>dsqZ^#27xZOpU!}yWFi+&KTiL#rKI8dlDXHXs zP3dIW+mHE&ZLkjIPOOBhEa=TDMC3zj!dcAE>+dTbQl0EE;8JU5nin-mNo>((2#ru} z9=M<R`qx+@b;CmYy9tB-n?bH0$0G$)RL_U#zOy>nbWT*auza|j@Cs2ShZs$@0H<3q zp0?v+182I%>*|)`Bl*4-tRBhA%6V_DZ$&kn^2v$6KjOZd5|jN2ZL2VLr{W<M44Oct z{s=QOArdhw^%(gS$Co(h5TM-cf#+hWh{r4`=Q=jpdY9DY44x?tw~P4U`7|Ze*jCRA zxB0p9In{&(o6gUv7|R|GMHR)m^n%Z0>GqY%Zi*_yMV-bwykQ}AaL20mi=M*zVwCC4 z@Ax&4u!>KVp?iu<zaeo_EW?wZcPzWL)ix})WPyT6@@qlm_tny<jl0yM*{R_7L*rwm z{ADk@WVN`CqXh)Yd$SYY<Ky^C1K+2M)T-uRwacPZVpQR;L#*nogjG`EQxT5CRudLA zOFBj+ottq`H9N~b$yY1)3g6!Uta6uzwK0g-;K~WXXFsmpJQgZ@r4F^m5rMA-cCq5U zKK_%~<gkfMIlT{eX4CT?OvS<MxfD73gwxg4KG=Ju_vvRwcXl_q?N;c#8b5UwqxbpK zxyzTm)3w9ZK9suf-y3u^k!+K<{Fb_P_ctV54fC8(tA@ZUd#GX@wvhb+1QoG*x;=Uk zU^H=e2(9@jt@dRiHj;cbbO@WE_!=;Q)Nf6F`5ZK~P7NiY8y9wfq|kcBdu@23xP(K6 zI96Z*+5$6+Vkf9E3vmRLZZiTW=$;ZRpUA`ji%<YgLN?BBs70?G0#?5#VuRb%6T&PX z3GP+{MNc&G$8`VrcALT-Fqg?p$w30@Y(fde9!P(39Q;Dzl7whHJ4pD}wL_V&S3o2o z+d;Cg*CE!pVrP-N$FeI+>6pQ*Ja+kvm_74E9CQORFUttb#{;G@a~R+fA5j6kX9~bm zHvR?9#>skai}>XL)2|nQ2fnaujJE*U%oAuI?-vCMI}9GDuerMo+hyp}GDVT5rA|0R z$}~1+MvjN=K!*1D&)1D16SJW0ToCeWH0~o*>Hyv{sD?=Q=l9zb?DBybYFApgkU~P2 z1*;xEvq%17>%)@+YqU}*7r269%BTfE#T5*HBAv5H<4Aa#k3chb%smc$`5H+RH#Owi z!Un;V-$~n$Og6Q61)CHHc$S#}c^YA;10*=&p~G)0ZB2)Pj-EuUl#PE$po#NqUeN1S zpN=Khq*plnHYDVAq0%0?G4OHjqqplk<WB&HLGUlD-!n~t!(i)ZAt(>ik6H=pUmZ*d zcHuS7pnB+aghl7sO_|;)lHjHXSw6lL^sfCTbZ<FqsTE3ib{@n|J?jAR8yaZj`Q=QQ z%H0PYrJ`qMAVCd;@4cv5b}2l@m^7?8OCEG^!Jq<W>z*_Zb?hFsJM-)2&e5Zq4s#1) z_0Y8=`@TdL#OU9;NL#MgecxqcE^{$E+{pSCuU)^eyXg$EBVGZBNl6z1u-qm4+bNjw zPqPs1mt6M7lL|XL?VPP*OpfbmRoxT%4%y7EPXuT}m<nPc0>PsIM#k9=+{F+;*h?Zd zZmI`rRsDU59$d;cH={EM*MBQ9r<%`j%=~j2X(SWkiaMBIfrGx9WigS(rOX@qM!vWd z?e(@n*!88yy(*nq2N&WvHUo2WjSbLvv+L7uQ#caG`fK5y&^H5Z$JR^3DS?p+;TPU0 zbM(r2Rx*Hz<VCC$uP4xY5hoaW(7aIL=O^cJm*x_Un`qO=hey<#^FA_M=q*4LOMpy7 zHNPRgy<)Fn6T5V~6L@vYKbp+<QN3BnbS?>5aI!!6Rp|ij1=A^Fj%M;fn0-!v>NtO` z*nrYFU04M-hz}OWXp~Nbn%wSO2Ji+5WWnSI9Gk2|x4vO*nlFAlf7tdgdEEmLItQhe zP_sg-+n{<Xg+FTNu2F%3#5sf1Bg}j$u^<w;m1{VZ${HB=s3UHAC@%eGpYyKY?5qS` zKWscZ)W=0q^91h7Gcn=pZ9osrw4MmtIp(d85BQFJC8M_?lM;<#9P24;Eoc$>R)?y0 zq2+z6oW$&T_lu3;iDNu(6dzfHpeAX4L!6>_*rtS(@eT~yA)Sr@Y*|y1O}EZdmtkf@ zY^=d>U-raqV{`T%FBA`W{)PmB8ysoib3$k4zG5S`f;uFnMS8l0j`%NVho3*DN8tLB zn*QucmiGkR63S`s9NeI~k{O>+LC2^#-fDhqaUA<{Ofh%ubWvB#fIwBr-W3UT&&LnX znoE}MJj+ZgU!VVGX|W@T3_xw^$O3OXWrfZlRV`3Dhn!OP0e1Jzi+hvrY_-p+MX7z@ zyK>H`&@(HxyX|=R19el{iy!kgCInrz)w>*2CGAU6zJ<mFdl{4&_nQsvy5GWoMU18u zv9)f8WcvyGh*e?~8v;(Z7qp#3`>3s!&zJGVP*sWjvSoX<C(-3wIa}BqCU-dVYZE0y zY6#X!svddBhX-R@!|6V@U5&S#sAcPYn{IFX9Xpd?QWWNXC%Q3D*zwE7A3wyDYhNVj zxxD=lIkB?~68#|Sa+utXx!rMBQ8X7bOhdn2zbfzNSTDMK!7HdduP5F#Po6T;!k&XF zq;yOh^O1X{+9AngDk;aFcX7j8qRSqygHgMMMOsayNvzPrZNERR56*<MR=1=pAutg& zy<QiF>Js|Dl=`bUt7Y&Mlv@vUw6ZghCk6F*SD~4GtVZeRv6{7&hb;V!MW(~tlT6{y zwO}V@`MurKno=7$F7UdDbOw9hc`ID0K;c=nZu98YrO$&^FbC8Qmk4Yz77o<7);F07 z+R6aI-D~h-|LV?E19pu<=}z5l!P}`#&F{3!o&|`j(yKJ@@nZxE`)W-uSCv%Euq})^ zNNHydfnzkCvD>4|rI%bI)IAGK%3rYIpWy+?Wi*K`XGv?kZnZvV4E^Gbk9<4sO4a~e zl^w)h{7xZ_UK5sEU$7c5gx=;3Te7E;%V~3&dSWJO^X#}z82$^&5z6HA7+5VnKtJVa zyu}!dEydMGj0?m}!>~pK&H~n5xo11Zp5=I?)|ydK+q4Xm;dZ}}Xs<4VpMHnI2ROR+ zLo^V4OEt3RFGW?ZN_S@cES->U_KG^I7PqH#cFEZz*4S`IIJSmBHio@xKl)(vlO~;j z>PNXUR}H50PGcDj!jk^r<I<Z9-zIX>RrWY>HeR-7CS!Al!|8CMbTo*y>e$~9YIjU5 z;Teh!vAPO({0)g>j;7lM;HZaA21dhFb6pGvjEFU*;XTt>f=@TduJ!geWa?%#?m}C= z%Pu8O4)C?B#&QUT28yYKpIkC|x&ECi^%gYYhKW>Xr0T_Jrj$9rdN*J-)c{(OJ2q!` z8U6G1!E>)Jxw-7DgZVqE^cxb%1tN0Pn-j2IP68WHNaL$$z>EMp=KuPw?^%bEDF040 z0U)3|r?*O_a64(gA<ub!Lz=_P`(V~>!EBYEw+EcRtuEUc=?Vvevkr#RCt>R+(h>hl zmzknp!X_zL_gVp&hOIL(ni1Cm@{}WRZ@mA%dhEWsJ{F&~3LD+7-SOjrqpHr!=ZpzC z%3bVI#|9=kNJ)t!obAP(lto0R-i%A1b$d8^?5A>$M7C``7*Vh(l^_=D-=+1&y-UjS z*z)Dvi|GV~;k?diC(7HNQZ!F8Htlfz7Afg%zL)5-=MKgvAq2KP3>}Pt;SU27vT`Bl za~U1SY=t@qDt#F<<HaY`8#bPqadr(M+{}Z0mCV^a3i{-upZe4f-_`-k@{k~_L)>w+ z*r16eV6*6G2ZrpnTRqcnwBNK8<kEVgp#=Su9hK(;tjE*)=1SiV8>E=Hq5X&Pa4#QW zn`R&0Z)lp7uY9zzBTwTPtkFP@xNWaC-~yZoS>UZ>7VStZ2<>09yUB%%Qc^4zd0m?` zms_fzxT$1U{|AdO>|Z+k<cbAx^KH5GJTr>dK5vt-r1Lj@koDjN!Vc`RfewXJTWl$D z_Et1mt&8@&u7ZsrzXTN~*`kS!xIHGxNYed><&eqgrTMLUQ$@^U&o+jYDo?roYV{L@ zmJu^awPkQPifG9Yhu*+Z5n_pTvnz09DeAFiS(8YP<df!ma1?PKA&4Rl?N=NCPPwH~ z3qy!mb;JK?9mPnVl?m;K&2eeDh&TT=y8tMDTt){(zoidH4vt+UP#+kfOa~L3-5Ug% zuDI+ZALg@doOJWpz?n}|Cy(UO!mjV=_YsZHR8j!`4|5`Y!JzkXe6+}Gq+7(Ty@xkL z!ykM{wu3GBdNpc|>-p?&$S(Qq!xjgY%b$i*qy6s9R7b>-p4N~+4tJr(#R|b^$N5*Y zBZy-T(*w4USs&gTSp5kxW3%KHq?Yxk!WeqTlNZ07x$w4p06A0j8zL7$*kyw3j^nQG zE0VC?IkPY%1#U}oZ`Oc2yGDF|oA#|ZIsakNs|l16I)pYL!?IAqj)ZUg1OX1iui25O zk&pyiRx^ZUWRiX`tvH_?-OPf@)9oxGx7!maNRI89(f#v$*o370@?AUK68evkGaT(l znSpnjKZIxlzDlJ!)E2l<@pNFR#XtrCnD1kXC_(+`Q!-t7){_wLeqMl*nsq`J#E$-c z+HG<YgV}Cp713r59`o`ZHaE(NBk9)3os8;_@f&2#TAF)u4Y*ar-ekv?ci7G-pe{B6 z!XfFQJky6ysdE=j$iBV!#ZQfztSY;_?K#1lAHN|$w#kXcJyrvNeC!UJ#oxV4F;hQY z`0luF1mhj&EeW#fj{nxeQBuqJ0gBkUWs&I@3Qw9r5mwehh?=7KKTWNJH;V`Mm@g${ z0$5%<G^W5&vC<P<E~U<M*rwyS)odfp?M9>bPjA}Eg|b$oaZiD^_C>|Hk+d*hA>2Y6 z%BEVSF+KL0&KT15`NP4)Kl*2!AnujY!2F+uEre}K2Aaf+>&LILyi|M2a@^cIrk<n` z@9*dZXT-3@f+3RFiJ?{F_k1PdG#~Wp3F5s^WZ2Hd`#{(GVJn}M{+XVmE~EzMEV>`P zbq<@nXQ3kD$52|>Ss+B!7@>=yO~|&qrn(ZuthKjO>x8<er!c_T^_XQ733jfk6SBT{ zla-`ukYO?M89vUCD6~n3P1m?#QIV+%Q}mJ8haJUt4l{UBLlops<rqd2)NRLB@bB7K zK!~Hfrsq3$d#vxZJS(>0_9{gfPTVtjfz7PSf46>2-fj@`>{xSI-kaum)x5mC@MHXy zSX&S~;5v=9Px2AMW@N*ougXvaZpv9`c1u8Mucl?q3}$8Cg(n;3i1>tw?a7@oJmu3S z_mqC;PSZ=r)Keas=HJ-xnwp}n?}R$av_CQ!*bAjqn-qn2iajiM?z}Jy!Y+FhTem<x z<zWm^HZ*YozagSu2vzt9*le*62y)ffg3YKUT|QScA7qBGAzZ~r1Q8q%*h|qMU5)rw z21r9Q-bH9CehJ%T@5=bTFo3di;ef*$DkY=!S0#Hk%4~}LB|-%|o%B1ecn4P2C7T#Y zgfh7`r+pi}N6CBtD93b#)#5gEKM%!9geL7ryQ}goYy46l1*d-nRt;ZnO(|5rEO)#4 z9LREVuny(_S^bi^Gn_-P`DlEH#+UIJdWPp0@g2Bp(f^1p*=Fqma_v+Z@ZXkj3;9Gz zp4j|y&)0aW^X%y#wI?dL><&f#+lrsZftF88qefit$9g00Vedw9vhYSeD>4ympjcr; z9mp?aciLxP&7VXp1Q32WCKB74@wt~Jhf}AFKE%P0DAx+H{I3h2rtP1c=8o~Jx6ezq z#b2^MD}{+K{6^A569$QU+JN`6m~_<qyN^O*b&L7-+}w9&e(JouEJp)z>;7-b@z9Jv zZ1RfBrVIXXpOtBV|9F&~14Z~Hy(4*scj(^r8Id$Xnp)gJ^KaGirSO!cll+*z9`E;2 z$grP|0*BncjhKzs+%`pL3G6_Dda1}>QCf*k-F^v?53>Dx8EPH0NLIICvBnDKC?|k$ zFGH`@@)T09)Fbefc<x~_ikK{-Zaix6M_}B|f+!FRvJ!JFfrs5n^x5+=ANYanSpQ|= zQ%Fr9c8-HMt@#ANg&gX$a!v_peyMFwdvF>Od1}U8U#Wi?HuD_dCug6WA_;-(vmX3j z?88J2wO_CQu?W=5_80Pm|Ej@kuziH9#{t$w1$Mqdx1MhJ_rQW=Wo7r7wCXii|7^zt zc~_v$q5~-+8z1jORI@a?l?Q^2sG(P3DW(puZ%&Xm@`voGLp-~6WU;WBJOuh$*gxCZ zu|kWTBg2Tk0wmx@aFzRN7$Vh6Z@g8xv<#t08*mIhP?v{>K|FZquX1Ke+GfPh3P&E6 zk->iT0w<}3+f?si3<x4;p%&gGP<@b32|<E<1|Yvz4dFU4LjQMuuSyDDqc$*JBEVvC z_>a(b)24*=Zj1n^7tayyB(jE>`nN1!p|)W=ljzR83}UETfIQ=$+bR7{^UfAuhOPbo ziE%&r`_&=f4Mwy7u5X^bb&&mQmTW)&*u#NSJW54C?L?i)0)I^V1m=NjkWdm-tZ-B_ zE&H#4K05*=2sbeLF9Gi^`02M+m*{Xsgl9#0zUqI5yiduee64U(DK2UvTq0a6b|h9n z2YKc|VgzV8lCqKwZZL|j31uDgdX^;{Cw{$aqOfR~O{k^7r?Y7)JwuJh`Ry-(q2<<) zm|3BEl$F>ZT@|trQ9}bWiO}!3?_>TI_%X*RUf$19iR$_6dHtdy_quEV9ix!Xe2Rr| z<8p{&za9C63swlI@GO~$DlR5$G1XP(srdBW8)HrsvF=PAvK`COmj_QhyTyI@-q<Ul zpDS&EVjS*q<s)(w`orLt#j396fOidoNivIlbi2ld$<SdyH2i2{y2V`dIa$V$vb;LB z#`LRepYQP|=0!Zvdtz6D-LAD*BL|+~1H=Udj{UT1jP|HC`eLAf=WumiM)D~oW>SP} z`_zG9*!%4HC)7xto0@3=vmFKCt1)_o%}K^(GmC&p0d$MXAk8hsV%Qo8lDIMt+M(8t z6@lka;l3Q|)l5s|@9t29xS5LrBXbhDoI`jfbg`fUU^U!Lupv+yQQrx|+=V^;Hl<}> zK-<9O_u0rQ*cweVp&W@neEaCnf1Ys%I~&1Vq>1_OsXm(6@`3%+LXNAm{xk810;k45 zPtd|#fc-My0LPrbBED8Ku;>Gp%W0voeN_J%bHi;iojHp&Ch+n(F91~g^6H;oAzqhB z<rTVu%<|g&4nxC?A*uk<zY=;Hxftt=nA)%Y2m~v`9=djX|5+Y{Ynkn25%Z33Fc!Fg zlwFYLPbh~3l~16a2e-?F9S)aBJCB$Gy_gj;0T1|JIY5B$f5-ImiMWAc5-ld1PbYFp z9XAp9s3({AA8<*QLAl2oER$&Wzp{RSCzK-ofamv@OFGv%{=K6U`*z}|EDM0GFoDty z6CgOi)=mN4Pl^%;C0y%8ZLT4APh_L{yZinZCQso7a;drf4+hTZ#nSsQ)QMd()B4@v z@aOSh3%;8N3~XuC%C7`khH`asf<iBPvr(7i_iRm*(vs(T@dD1A^cIxqlVsT26jq84 zkj~%0jZKJ^vBaf5)cOu6S0F)#0Gq(yWF0dL|1&`gDn{9#jX26_Iz=@tbc~^-js2n5 z`u1p|aXa8{zq&ivZ!tfonF_2<2&mA<mCg)2k&zL4vFEvhBdCGHG&InIh7)LhL%`9L zWE7wjO$x<kp(!FB$u7WeeY)+$;PY!{q`0!i1|%tQMWAyPIQWQ(4?WNa?~%E}q{y5S zZc`X)g}88Yw!Z7NH%K4&xkR(r9Gq2}L~XBjY%QR7a3DWF8)RYMgF0=3+?~NIx_W;4 zWNNCJag}<#JQ4OIyY_k2l9|P?`>2_pVtZQx<S)|hBPO<>yYr}@<t|_Q5p5qWwik6o z?=LY77^oRm(dQmM-6)+v#bj{&;Q8{y-rz7*IM^m@6gY<u_(NTl#NW+6vgkV<5;wk~ zay8tF>m6B5hZ*{yP2vzjt`l{x>BB;IciJphCMnvWyf^9D3gmNoe#9q&mfXz6z*-*! z5+X^^Q~GBzCA;AFPG%Rph?(Yl+j7ZRv1#EiK3_TNpU!A)v5W1j2NUo?pz4AW4&Dl| z4^%={*)-0))%Fpk@rA%!MrXte7$fG4NT!T-nKXCf^MlU!uRf9r*ASzNVK%Ufm~OBz zhE!$I9mkrOVcLQU+K#}D8<vdYbH7}-N;P?u9`CVM@>*hOQgG@$buPp<{D>#wU`BK7 z0dfe(BChoy?jw$v%s=K!{^8p8NJdF650s$JD+#|0;qg~e^mI;dK2`;3r|3oJA#n`r zW3cbOGHrE!;=P-`CiN-pRB;9>ec1)r`@A-9ZPacS!jpeB@kh1tFpOPfIlmY=2Lo1` zbr`MB)m8PCmlCib)Cq}GIU-Ym*`G1J$&WZ1F|zm0jh2<X<$GEDZ1$4)k-=|QFK>dQ zoS4}0zG^g!4>LA69VdpVIDa-Z=_k*}fgij<iq=LvZ`q&eb#&A#++n9?dPV^q7uz8N z7DNf`eGZt>(R}@fF`7$8$wPDcxq~W*QE!!%q+*3oSAnwfSIU#VTWb@cQXFx)UuF~N zA`7U3gG0@a*~Sf@dOi7&my6Cy;Z(PQ*TJO8ldKJW0B3TuBX*aOKMXweT%1IB@;-F- zO4_`9#SJ+<+Q)e?OOWN+Y{q{iM8dahn}Fa0R8IdVr=)g!e?#D1j-^4(KkAbPZm4KQ zOa*xz$R_!V>_J5!Ws1f42NqM>c>flH&p5c#vQ)%!ewtH%9B3E4dw2H5Q-Z8t%angG z2Qjl|v4^!IE_{d?#swF^`y1j4+n_fp?1ej=boPKxmj+t9nTRfgKay*;AXx$rBD=7p zIjg#f*W3wWUip<lSClTC3*fW5a`mz-MuAg=xtiFYu!H5_estwEs>cLT0n#a!4xm?E zrLrD~(Zv>sqNVnwbcpy=$b(2?#wr7qgMn_vn7R(wTbkUUzwlvS!-Q~2C(u0p7mY@n z|3_%q9{zaTJJj-|^VvuAfkUrrpRdK&mm&XIfww7+|GDEmL>?@IFF8vhR$t?lmlE|2 zO)~@`R|g&?Q0e}=wxQc@>rEn#^}`GsYh6ZrR?VGh0rHoh|Ldv`Qw9^NUX1rnU1Ppi z(rP?EFQPpzkZrAJ^j<LI4WvyqheU1`h?}V(@}J3dOk15iF*MuW>Q31>^U$oD!Ov=_ zoq|Wvi@2N<7cW_?&#>b60DJb&NO!hv-OsJZFI)#M2i}52hAbUkc7|u>5GRhpi=-km z-9JJrSv<P3fiA%3Z<jxGTKBu}yZj-6)-Pz8aIhSdh(h~u^^d$<%wgk=oo%;_oKD=R ze?WEf(#N|c<E3q+Es|Dp&el0-)4RsK%{{Y*rnc?Od8fujW!O0Y?OyzsMneE_Pg?C+ zFeTa1ktNPmSid7fm=>h0I=v*@2PF>e($YabuP?-pASW*hB=fyDK`1k@CyAvWiUYPI zr!BDtv%UrKGaxFUL6CHrZg(0H=MmY8ogl~q^CsJNr~N1=xR1RO0C)c+)mr#Sg4rn? zu>szULMliPyqTrif&mqXH1VDm3kn?j?XmuG?zW_j7I*{>Xgn~S9P<+nkwm4nbxFz% zKL;#cNcI+*AUCmZ_X>_?d;|7w82mS62-^H)-}s?m&e?y`456GYO@EUJp@G{DGE;dr zkyiTc+GhsG04^{BY~`kiv`p1O(k~DpBKRfwZPaD67`B|V35q1;U`=WV(9dw1sqlsx zgJ)>1PM5K7UCY$xP6xq1$~qNR>DLHI-?>_U?93P7g(M@$fwoRT=J$nGuqH~?wVg7C zYu0XiW!&{n9WoyBjrhrTXh@{KK8W2*<YUX3_dzA@h57~&6U8`Y=$0P#vZJ@v*a|D% zsfCB5!ZI%Ynz7EytEa5)0Ue|@HDh@>G}%K`DN6M#G}`YXSb|dcB7j@GOQ3x|o>Plr z_OZr>W%+1fve0p93o$RE4X#)}R4#@_3E=AQ877+LevZ1L#q9pnsFEGrJB8Y7*kMaF zsE`6XKnr3!Y;9lt0_T(#>^EGDz$O4Q-md<jaM%Hg83W1q0PVkzO5w=95N-SqK9o{J zNJ9)W%|nC&`v7ADAem-^JAF>1ajPeS9pI6Da2<kzE209uOP?j!x|)i60(O8$s0|)t zU5J4=fDrb>^ro;aD>F%VdGJ1OLSUQVmwOUq!C<bB{)YS$kCALUI5MGdgqXoWGV9N} zb8ZE|8MPpdr#QYQ{bmRGA}O|W6x7@*2a<R;^^b2)q#b~bPPx*xOqcwC`LERN5M%I* zbf_cY+P1~!>Tk%89*2CA69~ZLCrOIX2Q>?LiJBy*zyYk{ngrRWeQ~|;A2<mTOhKat zU@1X&8TBP0%<XVif;nmwx+m$rN&F1)U;-VnhW`il@h2A24bcyHiI|k50NP{YXyz_4 z<#{*Rul)(N_%mv-Q1T~(AA*wqmQf>K$GrYhpId?a35^tiLBx^pjBbZ+HNB5W)<1&A zDi`ML9)nH7s>^7k)Vd0(j^(&GF{oIpcV4j-b_^#W@Iw&Qu+KnzF2VZ#%HD?n7C^#% zL=Lv6S%Ca~pG$Uu_qt8Wt-G%T&PdEf^kso?=8Irs@E?%b04IoG1%qP)_(HvA5CE(Y zuLzmce2H1Ah;W$Yw?jLKZ=Ia0bC2wVLkY4oKvyO1+&&tB<Jkp8wXE=<)CE>)!(#Vn z!!D@jVhSiC6*mGuU1ch}_KHo3yV(ok-K&Y?HSWV7hOR-!j0yVy`9Z35R>asD!0R~; zBoTO^<q0FhjzB6cd-%i^zZNyjy=})B7G{jD>`)^H&l28|fy8;o2*H3}^a}t~7;yX_ z&q{cjOF&H+0I;T2^H$f!lDx?RyJC=C^o7RK#>?3V;s|FWYXK8zpALiQHeglwvt{3+ z@{Cqjj*I9kJSF<t6sO}AZM%zLm_0h6U}qFK5&zm*;N1}?z%eG;qL(K!QEi(tQ{f~B z<)Y&=0Q-go0)P1D6A?tUBH#@Hoybi9i5d<*Gphzc77CVxG*G!gTWhVnQMxodMQ#nf zDPTShX0vk^u|~0vAe_l+KLR5eZ%fDGzQ^(jy)xF*C-tt<=O`#QEttuXx*NJ=bj0CT zB7W5Ul0X|#)6tMUD7#x>>7_Ifg7+7HEp(kYsJgQBKtYKk`dns(oS*#JQ>j{qGHNaP z*Pn-)Yn64dPwHjxj*m&)4koe)fbg&s0v;I!E&!`V`bAGrfZS1`qO><BG(O{8yqNI* zOuvTj_Vy8n`K!+<Fi^m2H#OM_n*VYLNxYOXALHczA+-f@*CAJ(ZHm`)lH)1fQ9BJD zOi=KGEz<#O>I11P3y^*hjASB9w9j_vlX5j_d%PH~oIbBG$@oktk#w~Cc);K{-b541 zQ`eb?LCSuT0f(-J&7wAF!oXI@R;mbb%^9b$;rNU$fxJ0-gr7LNdT0NJg#Ke)efrwz zF}NU*Bf1EZ*@sBH?r&kZEZNxS1lDll835pktt9|0OcW_V&mc;{{+f>NlcZ|p(Q>4@ z<W4P+km=ZNZN0gjj$C~Ug6F^(LA(UT;&*6O2;+dwm~VGzh4@M)TwMMlZXL^>@Y*%r zSUu#|@6r?Vjxm2AOF;Dy*YbaK^$s?K=BTuZ(xIVdLzR4NZiwe@Of%`&3K=w5%x9rS z5ObzWe|B4NJ79TPvb;CH$6CCWN0@%sn!XLHV@P7m-#)rRoZ<gaC>INTWg67Fl2Kht z`sWhKt%E;?yn($1l>~`eQj;`oZ8w=0aoMNcFZ`xIzb0f7+-o-(sjYb0Eon5UHEknj zhtdSmR}GT8K9Tu9I=!zi4_0B{#S!k_=O-j7zRN!=7aZM3yC9~dBk;dOt?$<yo6XWY zsc3!WwHAho*X~i47u5m8LZZb|=SVTJKV<E$qjBhRM4HOoRMV566v}zbpPy#jjWAPp z;}QZ2a|3+?D1JqV66xCdUkfdHb>qZBl)7ie4gR+_0@?U$qa3cw>VU3F>{btK9}*MP z+{MCnDSPW6fAqQ6_SJ95__eQb9KOg_k?H#cVJl9*l;Q>Q1`D^oc@TgTfdBxAsLuXV zwGFLqcJB@^3^;T?!U!u?!xX+hjh9a;f{j5t5VP#i1%hP2pP70E{#fgdY`#&EDJ_Up z6JZ^tV(Z{;n<ubOk{P5<Kmx5hak>+UAJcVjAC2@cOgFc<Zto6n<H$=_enEXP;u%bE z7Da5mX%@g~`+6$p-9EnQ#Y9#$ObjuY>H0Buit?BQ>Z^AO+^dailUTuC->_H)Q}|a+ z(WXB81Vkg-Afc2Jn90Zdg7E;Y16!nVzKi4@{>;=yi`+8-jc!m=cDJ2EUC|A>`hI~c z7lDT2AH&8j^vYR+=sIk70}{Uv5B<-nyDgWe(8C*IA;z8!L9!;U0*1+JHy*YX<U*U% zeePhH$4~)fLzf18)|*`1>EX5EJ}u8fxCF?XNYCnlEUW>usG+|KUZzK-UBT*g4yr(e z6Ww=^7ur-Ivv%1!1V&D)Ua`Fi&~GK&S(%1Ri|qywTzVn~{1KAECTymy<0){-JCxPr z{LyP`4l_9JU9s(bJOYV#fJ`nB;~qj5gcEqyy?tm6RN1-uWv;i9txzWZeI_3@<92At zo%W-{%*}{utIWrBfQ^9I1jGKK!EiH}fCU`zcA)bB6`5*Z-~Wbu$rdfjEL>Q+Hz!d( z?0@cc-$04<LT>?TjIIMw`adOGK`tPYlYt(9271upG-&mJdb;EfwX@jnvZ=L;mzl^i zhy#xze1j6_05ZQo+@V1O2Q#vn8PC))eN{ZE{G+pUL}>!8cF+Qhq<yf=NGAJ<FmZeC zyYOh7=DJFm@5L_LNb>t(Zj+<Bh(B5+mS9OG8IJ`e%`OpHC5N(<q)Z#js~3unQji0d zj9qp<>9~?i?3Y7y#Bwd!-nyj-%EqV|WimdqrD>mr%MBaps6Uz|#&JMlUt&jHRNr7T zD~!K3zBm+b(bBYl`?6mFwvANE5!FzzJ-Pi|&6XN@6wwG~sgH$VS(aYgohecw?u1WH z&N%LM7(X_29)Z_G0*&-KcYzg;0e?%N%_eTmLKGx|r~M1?VTU{I4F;)oIHVP;>c#t3 z6R3@a00RF4rbqzD@H(hfs`Q7*O?#ksjtzpxdJrtj)0?7e*!13MK04G?$t?Q8C*<i{ zBa6Q~4JI1m>0tn@7UHXbly3)8uW%{?k>#=-da0~%H7fK>;3>WqYUBuFGYvs9%|Oh| zih#X&I@o1*6xEy#6dlP>WVWE_9c0XY#5m<dPbt*#>{pJagv`zU`|3JHvNt;pR37o6 z0zOXNFpC8%wru>4>;z?<)7hcOWnbyKdp@RE=omVnlKcPF_T}+VcK!b&)r6!%wirbz zLfHu;LP)kGTS#IE*>^*Bkq}CnQP#4SeJ^YFvX*`9jC~!<OuyrP?wj$vzW4Lr@2}3) zyj<70&UMabf4@Jf()Df=MJSj6?}}%WfC9~g44Z}_9DoW~_z5oX?PCWftj(*rphl%! zsHc8NoT0_`s*QLXJO$z?^gq^t!PANOsh==KjA`q=kpjnG@aWWGI%(W6fv<2tk8}U` zi8uO&Tsec>9znj&G9uX|-A0<9i<at&HeSRg-)iBIHW|2Tk4#LYZsGxAb^oCMB>fzT z)a|5dySvCVYY1DUlsr6lwe{r=1JoB)rJ)DkKiTQz(WH92l=S&szsrSFe#vh3V7cBL zVxn~zH&aktNu;*ie>@0<{Fl&y>imTn$x_4Jc8a)PwHQIHu!=Y~-6BdCheGy%Ucuzi z|MMhJxhvwISyy3qlUu?qhOQABoqUfvv&yUZpw}8o1fGh~1G>X~(JE0oE~x{I+L_7_ z;D3cilWayk5efOYU|!mLUD{zCQ{MGoM`F%;K@v|q{-08Z1BA|=B?AfW2kw{kMCbaa z2PzmuY>hHRVP;bFwJ2+CB;m+C(&hgF)!7f&0Zy^~*<~Ycy5`;zwnOKQHLp|}RU}NU z&;cTSLvzy8M=Al;j~bBzTQa5Yw9!!YQ_Cr9a=M&CUtM6i#kEZd0v!9N4+sKM@XLMl zzIb}8)&ulqL5DDPAX8q|!;vMb6W)pHM=#L#9FRSL^L$^$KpfoR_<$@Vb^^Y3&am!L zJEnsFj_*2^S#*o<@yG?w@FoF4T<ETWy02!SYKVRMKSh!;gnp*#7}A^u>KbuVnr}Ib z-|50?>@#|=Pa!|pB;r@Ou|yW{uB&+Xm$+&a=g*0fXG2;W2xDU=ot-oxGT)tBc!rKj zhS__4aY3xa8jqLfUXIt-6nccNfIbH&y}Q`RmWc$adLo&d(4_64@)vSW<h%zg<zd>~ zd?F5qwDdf`Tu?A@q~Q(1*}3_cbd@sX2O$Qp_{rkKJbMBm#`<x*MTBhgj~??dyjdo$ z|Gu@3Zh|09ET=|*{2Kin>;&ArmH#X1Y-vaTy(p`<{ibwz0bg&gIEP|{+kNAP&UUdD zRGs>*hZrF)%$jc{xF5mBLq@P~K~T=?8&J6It2t&U<TH1!0GqWkg|`}AY?AW!KVoWj z*s9B|0Kk6}N^k)F>(yO!(jZAZ(qPK>4`gg~j8I2>Tq*(K*+<$~lC~U&jPL$o8D@Bk zS|8XA1Zroe7MxYhb`lO%{mmLgr|cNxua)5_qbSx!%P8_aekEH(9!^n{RvHA!@+?Ic z@WFsl(R-1oklASFc0#gWmqAMO9G#`RLX!2vMcyRL{PSmY=vRJWfT8o9#=V7n-Um&X z%!N!&rI$VrFS*zYcD%RZsS8iBQabd$=ChoS*YqLoMey9QA^0YAC7ZIWABo$HAbi88 zldXXmkR1q){6hd}3(Vw~-R%TtVND-OtS2yg*lz**#&*geh7>JBEdhd7;yEM?epUP9 z#6v~p)WpImLN~F%kF<d|WO^5B*0c<&4XftA{DE*7q&OXjH6F@wwI#~Mg3>bBxMlc* zrD1#!?;pqz{QD268HjWpmI%VTs)6qZ13tEJb+1!8vcVt7IPgi=XbpHFy8$hiAAca9 zj5g&Z-u_)TpAN~<z^UyByYlP*fQFWvk`K0~UyHru|Ms2`*Nb;|c$zc5;2d_e`f)6G zkd&ZnYW(DNC0*;sMJDe`Ft?;%ku`h&9EJ)l2E@-7)cf+hrCK*VYk&6jFDHXd`pNEv z2keAYZ<wb%&3oMDSDT(AAdMtxPkzN{-pe~Cl3{K**>##)3&S5ipJUB@WAcW*b2Egi zcq5To?YB!EbE;pe<<ZM|2x|Xc8d^s_7D}%S+PWd$9#2H3^yjQQY_cLB(yKpgKy<#~ zXg0h%Jn1pl2g#h=%uvMsruZ=%krg%aSu39&?_&>eHiY)zawRkKhb)^q0#&W-8xMd5 zcc$d8P@n>A8v_btnK!Hzup`-#BiJksmDR;{2DL%M@(WLii5v7||DOV*2}?ymPWP70 zQeT75=)uY6dU%P$;&~ufZl8nUqf*s5dm)X6$r!PVu-A@INiTWGy#vA0tVVMeibMLk zbdmMr=ig=_B*L@bipTz3>M>iPOW?Vv;B|?--6F$9??jH7(}jR;|BsTIbgs&*Un4Ai zGZ)WrT-W=4>JC%WS@M~9$cwVI9lsfaBY)Mp`JCBh0O0_;{$)ik!4tkJtd~hz)22>F z8e|o2=si%!2C>+Ud$zb9AZhsvLqPkSSkXZA?+ypO6xqN|_)l|60|Lnf=z|Gj+)Ql3 z;Muak7Y7kyUV{QB>4Vo0`u7;4Et(r^NCH`g^Z|+$i1Y3y*EtwvT@WTMEAtUm3$x)> zD%9r$dGgZ@33f_ACDpa#almW#if;f>>4*{}=;A2x!bcR25d+~t^f7Sa^0d-|*n56h zb_|qTiw$YWu<MBLGpJl5hXYbtwJl;aaf^Ni`DHjLFl3o}@jN0~A<xmde<dx|$`qt@ zzO}*{+$H<k@{ru0n!ku)I5-Bn`Gbcp1XUNEc7=YkdwX5~ab3&waQQoeio1t8w9;s} z58*5@tJ9hJw1&xz)3iE$@qu}^tLSL&ycBgsdyQI9OT1xz&V*%O!YEyWW0PNBxq}gI zY-~x<zkt;#xzp@^4~F%IDVqWYo#JJ;yeNk&8$<iDfk0ZIardELDW6!<9cP~1n#nc3 z%oYUPqSc1lh~EwyAvm+-#_ZXlW6u`a=m)R#IrYBHb$=;d=VqAo95+}aX?yl_QEX&w z*>hTg)h}Le9`8PYK@n2Hs-2#Re^sb+jSeAfWhx<u9)%W-)j1-U?hHc^(!9OEr4Fs+ zD|}(G7AH_2=4bmF&|=Meosl^U4}=>phNF0LRqr&^e5pD9yo7oz(<~@gxE(J`h$XV) z`Oo3aJ`DEXY@m92QplWmSPaOlyd5LYd&@eZ3;Hz=&c&&8zJC|hG1N;w0fj^l^rjM9 zU@W%YQok+XN4<H2*N?`xqIza;)lX`CgAO<y^^rEf*)FM#!oqB_K`nBkQikejat9{k zO1%x?US!Q>?=JM3GLWK&j(Eh)nPL#0)XRSLmGlnL#+90A;|5qNPkp(`j=py<GxE7G z5A}8Jt|R559mx=czmM;CSPgh3hB}%fo?19j-c0yOJPQHU`$_MYWXTW|nqrP4uSW6V zCbEI+K!Y))PAjo!`Q<<EQ&}=rAv(rY4||TJ&wkQgr#~|h+sdeyxiO@xt|n>xxH5(i zB*|s6q%-okY)8)Z#V_8vfh&dQZ-muWInr##`$#)1PkjZvp+Y@J{l>2A&MoL&JD-#; zt~J113oIVCP9hQ*hL!SO5j!e~SUAiZf`GF)QkjXyQoJn)vroUns<xB1)!X!n%yP3P zCmFka=VRJHTSx!QRr>p14~P4+ReaXrljbs->FGTqp%_q9FwWInT=4QN`jwz(g*fY{ zq0~(d&Ch{7!VY{Prv>s%xlON^%-37RcVs_toaS3==JBY{4<$csAUo#qy^RI3mPmbW z*?D89Elz8xp!ufx*1J2(u(*k-0a#n+Al{-#C9R-p>D9)(14V##|0jWYC|cG**B11H zd{DblSb4VW#VyVnMLK0|U*j4(cwK{KP1o4+nGy#pYw2*i$=^+_9B|GcubP#kJ`x{u z9LwH-7Hy+TEThRSWh&LOW0YRpyq2>KTA>~mVKa0e+4~zV6k;N(U|GWXhPtwOh)zh0 zwvt>U^zhy1m{yAxV{2)7ZiUerUsS>mD2THilS;$?fdH}L8R~;;8zmp7qB|$8u7a{N z)Fz@`QroN-M!9c@0i$iT?C%Dx)8ytv+UMx4r3m7V5VG11L^Y&O0lVRG?sVdba8Kc* z`APSpCVplgT?r*4mjeD9G#`ka8TewPo&*f<J70wj&Tu3PI`HUFFGD;i7yPv(bKx#a zQOP&)$x`O=a$ujFD*{;oD_|<M<GC2%s~8wz!vgGp(J7)Q2iO6vCO>6ZkBc;p9o{jk zVZ6;{e0Tg*uOtDOzDs_6$o4h#=JyoR$|6V&>GlzDZScFR`o!}OB%d`I&e+h2)n6xJ zL`pnHDl!%KCSY{}bdF;0>aPoP%n0`9hQ6sdaYxa{yMPPNzJXpPa1mCxBmCgwd`Rqb z<TXQWh{^8Z08@f@AcxOK;^8NJg6@Z6k}ZzPUi~UQw%s$Yxy*p~SwIfJTGWs3Kjy#R zljSF_)MN7u|Kre$(z?bCJ_F|KAFK8k_r8QJ-X9o#*i!J&?t>2nl<M>Fscp5L@p}_= zWNk3!fm+Y^4})x(h7hE$ct7tyF@yio6*+;{>jBJ}ad*O>O4iFHK~Q!E6V847_-DLT z*k=HW4{0S`RQI^Kq(o|(22mG{{0@bU<KgEFxLLo35v;T@4BxyM8rWc7F1lS844O27 z&X{O$&_$o}ycbVBfI71D=y6kho9dTF7SGk<*_JM{#nRM|rXObVX8Yb%*V)=KMIl%| z0HuM*!a)Ie_&RH927m$nF6zi?-eN{&JUzz%8H<4y!LnR8%9d*yL>Z_s)Gqo6$2V;B zWePI7ADUvBwsm@8`HMkBAsiNC6gW<JBdmr4L>!`55z+pUy_R!*iYDzqbD(R7f5&YE z;B=B3bFipmfs;-2gTnP_hsofEkK`|Tn&;LUC7)u&6_vE{uR`eu?yuvwavrFGNJ?Sc z*9hw288+@tC#Eaequ1UPcxXw~peU%<)<;W+aa?d8At`Oi8_Pj;g+E)_A~=L7rztb$ zh882#CDfruFzvrM#*iVI44U~%YcCbBCDOmo*SAOqmY{>-d9Vm?hVL0;s>~}LqGC$; z+@D21gXm|5Y2j9j&ry8KQguT?qvDRuhu;LGWMv=if`*|cD~vYGaW(LH)<nzUqm{f3 ztZN|oD4;i(Z|cA`DE<e6P&y2Ahiutma=rpst+aqgGR_S1TljG>f8V#KmFiQrQ|%Lm zMtFg^c_1Hdz6XbjU8l^u#+$8V$t4``gaLV|o|%<QuG!47ZJj`@QNh%_mu;q@e!pd( zPdFc|DY=RinHZ>g9F^t*y?0%{HTN6BM`8Z(yovJQMw=Wymvk|%2zT%izj+JbR<o-7 zB)Q&8Zl0>Pxi9Mwpa~Tp@tVzAju;)TGYajCNolWB`JGyl=bw^`8gAzHpGt+gZ~JWs zEKNkrfjGS=7MXvv%JRd`-3Sq-OW&?t?mr!|`8s+nktV*}VTr32PQBiVX=m(jH+TM= ziPB0J*A!##5#2knJah2AD!E)-_mZ3(zyOswA?A%WymIZ&+a&&hly2c$JwMAZ@UJlm z*`B$NJ;NYao@>#AzG6%hH<y0Gq5fKw*Qf5@T7p7-$JFhgp4=)A6xev4>yjN8JTtlF z{;1yFy}RN`TVJj74~1;5CH$!trq4ThmSw?G!4PzHNd@0RTYb~w?filYkx1FXB?Fl; z&nUNV?NU;oWtgp&-LdKjJ|})kgK~aX{T8_>n%7|`%?TZF=GfIS&eQGEZ;%+>`Q*wX z5sYDR-%tO0Q$NOg?3Q(cbCNDwVan3Si_lMA)|{R*nRN4^?RB|>iV1Lm1{Y-P982rq zlWacPFB#EzE(HOd9$TU#>mC@Iap{~DP;+ok(<l*S>P1AIRvgrtA#hWBPd4j@PWHhi z#L{$S>mgtHxr-l4JuSu~PK0D+xAr;Kv~Y5LcRN>z?hTECQ)4ynShxCp)X{b}@kt48 zfQLf>XZ=4SIh`gv`|kW1iUycxua<|YLt2Y*X>i6NI~0CQcuEbFk@<)K4D!CUx-S!V zMehtWV1C_<Ir$%XM5&+Poe#QY{3BuWNg6U*kkjnjvUGg|C}!l`ePi8wr)oZb6W^-J zaug<M(MU&T`|pY^l!bHI9f>dy4@i<$zdL?XydA!%MIwGRciUTPB71><`r}?9;11k- zE?wi-rH6jjJ3z~zT$YP$I|+*&2NF#3q&E8jdF-eTy>Vp6wdBPcJH`NYxA#BBqr@8E zi+4dY#=o`OCvOViUSy)z7m#ZgvO#qMShziXt8_7lCh!MVy{#jk+~35<#S_pnS;6aI zD`dr>Bt0;nEbf0i`RJNAH~Q{NM1)0f5m(a{#tAt)^j}%~J?qP4`hVq?^n<?jiryT^ z8aKY>0=c`4+Er(4i$r7+P}`~yll{yRNX+d2a0kUv^z$S_pua4i+*BgcPlok{?--mG z_dxvo4<|rjrm<5e_bn6qJY-?Y<Lw*Wap!@B22QjdkYE0z?L^NMaPt7zQi3ihy?#{% zK&6y@3-4SqaH+g})%*e;&mwEz)K5y1JxKaEGhC1}7is&bXS*=T#M})Mb7n9s_Z<9d z&CAsCA2XZM=So!FtFd$Ar}D%HQar|Wej-mGfp%rXA!|<Jv_@fpYm2AkY#GBZ78|{L zb)5R^Gm6c`6TKS(grrJ7Pmf;ya++nWnje;WI=|kawlWLTr9_Gzx9Sn1wW^tEYO6wq zk2qSr9t|{9P|Ibv9pS#~iw*0g9sL98PphZJd3#Y|(9iO7Xx{pB_g+(sy}b#62re4I zamWU5PMpc8_Og6-j(FG5$N*I_`nbO2l$3)EYh3Mczz{#qX|%tU+~B7TZS%YGH#cu4 zKSv#t!sVC~0xHkA`rTeu?X9yt^;^j-^|!7>-GyrURf<^!4+sys13r@4t2wjWkL$&l zp;9C*q39SU>0<WL63}gENgc-Isr(aUp6&#eioCtlf92i_(NaKEfCAnD+t|(}*H6Rs zfZf||^!aVZY<*AjZn=~27`Mfcs*x0lg`m;v1Sap3(<@Z^jpt7brSTR7H;(m{4{taT zQiW~(<54LdAY?&PW54;7`xf6gJ6Uw6wOd;Srg`2)zpN*vG=zC!V)7B?)0EfXoRbZ? zVn?}x;nuLQN?1o$IhS>++BFp;?v_}?w_n;^=LC&R@cKCI5w(+^@DA_eqP6{oNBeJw zNcL--w|UL&Q*wAoFdEkjXw2JR*m{$>)~hl1S;XqS`(1SH#zxdvc~r7#g(+TjxgogR zXlzh!G$Lf-X4Ft~#QF1fj8b&wxpfe)&ZX-Zq%WQV!>fq#hn=1;=vUQpZq_<)quLzU zM>f?{DT4bvqOuqW$Pk6$$Bb^??HkAqj@(S*;#R~M^!iGR4C2V^3Z?lwc+CWVwQ*_- zJgq5~uGNuS?%#OtHx?Aki&ya&8P6>Z9d3$AjFz@wrD#uq2-Y&VIP3Iz_MBRLJ#&@Q zRBR&J26=q4gfpU6?@pp)MypiLnfle%;;734+4qf4dhB>{PgK=n(r49KtVJKqJT6?4 z^rzQkAPZiscm2q>SkV7#RIu50O5rC%jCwdxcgy|=MCGGp<;C(mYuV;ok*9}Nq(<6A zKi|i-iOs0x_eiQ(TbWvkyp=>EYV=jevnP30MCJ#NXnMGP2>xcQeJV%3Iq0E1u3kFE zcE?;JaF+FsS%gUA`P>M&&=Z%Fg2O^&gK44VO6kEue;_zTk?+yxkDAx(LtC(e5#sZ@ z%-LBV1?7`}BXr2lC(sRTnRDa)UQ}JHa}b5G@aAwn8(mZ?j?&lFO^i%A`^;X>H0z`% zqSHF^wm0lm`JEv-rl2OOAn|qJ@t2Ku_pD=oJ2hur_+ZBP7O|xuHsZXQ!?9PTRMvp& z;`}+RVnxw=VdIO$3e%Sxqa`&X%^%xQ{HA0?V@i~u45Q<{DbS1vxk`Wm<T|Nrf;`#J zgZ41H#tzGCq^LYu=otfo>X|&L)S+%7bzU+Qfm(rYt;7+x>FKs_qAnrlpS#6gu*>HN zi+pii{pb<;l3izL82DizY~vXZ$3Q{g1`VX^VzkT|PvBeqQ>B#4UZMtlpI53SsO%CL z;RC(%2cnF`bDcr1PVfWdIk`P)iBi?R7)&*|RVkoBoqqMLL-8B&HgB{tWGX$Y9d}~^ z&?;}k0nGit1Rz1*&?^k^^}4Fp*`G?Lg?g9Xvfi82;EtS_yWtl-j80M6)f;I17WfxH z&j&s|I1iK%Yx|DhRw%F%_kU7cKFqw$%Erhhl3;xOrA&iV<twr_4Sk@#KoLUw8gjF7 zx6f<U7BK>_1&~Fjl9VOsh{OD|ubefK8olbj6(Ea}U5)6-1m31O@HRDpw<+r*GMx#> z-MIqZpvh=wT7&etkg3Oi*C*M)jtnY${`6p^ZWB4Uu#8S5xU~$1y?F?mc&b__U+PFM zbg{CV$ot61X%`Qf6M`}0(rV7E^iAuv^ene-{$%l6)Xh`nt<92LVQ>+DY#OC%4BWi^ z=|${MP5p?M&aEyG_G4`LfKX?$u|bI?hMl!>h5$X3(XgXW{QkJ3PWYWdQ^(|>S-7#O zaOu=1wqu7~=qI124Pspoqf#QPbFIaUr3(rV$i8nf<s{*uI}WZ>%1d2<t}_y2C|G;> zu*sRxM>S&PkX-g>Uen~ogfOH9e<(6vxaZ?Y)pHb6QI})>m&Pg&-cPj&Zq_IkjxCKH zwmOW8q0VT~*R1pN9AQ`nC1Y|Y|Bn$7hUGdmW61uv`XV9=x&}=x$&rF{G*HmUHjbE* zalIe|Azyqzfl&))<HX62ij~Wy%tnW+w24wV(b_AG1hyND#Y1NCUQ3<zFq(1|2h8G0 zi?~xt$LqB5AMV{iQKCkA%e<?R$DP_wSZ<^1hUtGdnxyt4+UaQQQzTnnw)~RvG3qG^ z7bH^JUfH--HwFth;~r3J%H}*VHGKH24##rD#@2FNofK0!uSpU$OvU>`QNCTNJaI-E zRqZ1+ydknI^neHVewnK7DSxAzGgp`ggFR2HlM(K6Y=z0kf%_4DeS*i#A00P)l5kqE zqnQ79`v$tl`&8qns-SYIBaM~eXN(HID-77wix5=Zyx(K4x5^T&rpiNZcjU!Tx;C~# z+!;b7jdHyEVK7IYW0L&VsVepy1+hG`%9+Y4l0h$;<9BGrY^#UKaJ|*;I@RVlv{hoC z#dO)+y}N@K>9}nUFZ-f*W-CPr3B>b8#P$c5OP9R@1I#`?P_-JD-MkPKl{^vL;NZKZ zbA1_FFU`Kp@WP2dr1DbPYFbw|W4;Eh|A0ND-T3Gw@<o^*jH;XlqXw~rAEO<WDy%?! zq&WVRL3Npjj}bz{0T=D5yn>4usZhi$hOhHOXCvuj>t~XfU~Ud8xf>kN<xHa>IBSkH zi)%+seY{jcmT*{^zx74(?5lToPFk6cq35qzFXz>1;7YO8R3`Skv6st3>@V~uTx<8V z!>N<wRqed2Gxd>=8%o_At?r+1Ha)8H2#E9W-*}$LA~yC;{`$90X;OWN-VUbmkQGh@ z1Er26Z9N7XS_ZA{>2{L0k`hz2e{!aef|LCdeegxR%k{g&i^(Nby?pUQqq@BK>BrA> zoMaCNvdfOsJcMFoPFuPcg)CSr<d`RakL;giFWnmR5crzWc723)t1A}#mi4eRe<pux zO!QPnpAvcY{Yxi5dksQ?h|{`zB(o>C4v|KGE2&cSeq_jn&;X8^Is@WBWq#T7`^7g~ zE6O9A&d>gQbG(>o+WuDJiFHryQPl@l9_KJwFZd1{=gm)<oc2Y{jTd?_*H`oii<{+l z3K6)+9?{nS2zruVW@IZi0@}62IB4N*3QJ20t4ce}qdb%t>o}C9ADNq<t00=To<TCN zVd?y95|tkniTSqF_|sCzNN+LXEy&I5o@Zi<@>~P4$`&DwXvEfyHUX%~cbMLaA|QJ- z9K%08Z9y(?#nfy0<*1^8K%Nad;2vm)9Ui<kz@IdQF0~*(5jsGss9^i@HIcf4gLp$^ zczpr=T|2(Uh)y4&EL6g4*f-$zq)CC|f#CK*!8t&JQUy)W_QdO5t?4LStlE4!*Zo+N zYOzKZ?+3%mkgp$#NR`!Y2kpQ0=AkLl-uAi16>7&63GeI!AHUpspELq-ZGbOyR$;{Q zfS$XITzoIX60?VGMUzT$vu|vI>bz>v8>Xvn2@8WDfZ+_VuRIQW;u=ICX+RPc4m23x z2H33`2zUf)20&2qJ+Bjed;c#{|NFBp0u(U~ug+Y1MlmJ%2U4baK#z#>?7Kt-YI~}h zE(-e+7bW=N8@a;j3)b)K)}UeICGv!SePeQdpuAre<Pbd5i2gjq+0Jmv0YnsE+J!!W zewgs9%Z*fRaAnXr@NY|ij_fmVSlJ>06+Kb=!og(yUSqy8<$cN>8M@s>Ggk5(NYiSA zplCQAtN8^_dgVhoiMInt-KWT2K|D4&+xGuUcDvryg(wHgE*1f)r{OyYJqg)O6bTMT z=Ik!q=ZH(;AIS0|3|Iy_M-1ny@E#4s5#n9Q_AU-03rUpIfv^ASRxZi`n*To_9GN2| zx#w)<(qRhZ_tWsret;j^#Q~k|-KSu@w~I9ThmMhqH2M6Eq=g*B@h-@snYlI-WrjC? zBO|jlORM&pvNx%dkpNeO6-aW@7UW+5(&rGX98r=BEH@1(LW##%m3G0$szH4apkSiN zKI20P-sAc-vYUVB!#mX=0x(QUFLyz7XtM!s3QH_2TFve&e&+zXEE=s3R=tC0?_!6t zNpUOMZ!v0HWOc+<<g`M5I>1TQ?-P`jT9WdXSdj0gGO0lxhp>bGfYh4?WF-8<CEHx< z*?~TkB=jSC2Z_WcEWoy@!bEJH=qG>*g&V@ZdRa-YevqkK8m&+R8#xD@qaUhj2QMK{ zyTJ1O2fi}$SGSE<kbLkzcFZKSUESuS305CU(4-CQQbzcQ(e|lq=`tEBfH<eYF%bPN z$Ypo)v8KCkxtBuK|0^S%V6?sfU%QxT3E@dx;>TAYzrr^xr?C5D$n+)fCf}EH@Xu(8 zl?>ojEGIHP9=J@09N_HGUEj~GrjzIHe$L7aFtM_n?TzT&rKst(14VD&`LM(akWT_2 zr8Tl&-!k>(4=FTW)P{(WcVg9u{UCdRviFw5TYT`LnJ-h@n&KJ<Jyi)hs;E`<*jX-_ zFCurZiG!Kt5JJELN^#)ZaT+8;c|elta&5-lzHi`AYjHy2_bIFnyby%r6VNX~k^QAa z@*SH_qFdt@&2lFCRBd1RXVoXN{+cvz8jw$Zg1(O+WDBq>?YI6w1Oc#uWUL{>?9CE3 zb6SPB@i?mtn-RR7K7&vMgo@-iJ_rZ?6xQ#IUTstRjttl8wb9b<49_a&?yoV!o%I5{ z76ghugN(~mG7>~_Dd8mJONmqx3h$(1ljys$12n$KMx$b?{^h<R)(`qXQ*p)SbL8wU zFg@^PA5F&@kF`Xs!ZC^)7l!d`yCZoz2+6$ZJLNO=6`AXQHpZx*fc&)rP^2{oXNkkl z5ry_g;H(ofQrq3qRh?)Pb<chY<PyVws`|H^mVGc(Oqpp!JY{-)TIogu*AV#D!yAKX z_|@nY*qGwp2&D5PN5%AYP~!8!>YwM&;lvxI@^puP#UWQa;4Ob30f1_G|Kr_52mY9z z7mDM0`V_LVHG?*A2g_;+_)Y(>>CzQo{k!v5t)5Wkz7#R?^+hY!5^I4Yhl(Vc<H3s4 z%&Amu&A=v+)tS@Vo;?z;bQ~mNWR)oIxIY9^0lBvelJ-VmQ<=48Sld~19(zGm-$X(F zk#RlSVsC{HuIqp84OR&&kx!wi;$jd-*qF+{d_RXi)Ehe&u)-{fx|~<uhqO^_gQI<8 ze*q3|WLt|OJ4E~w=jgyI$x-TdjqUCQ|8nC;t}ht67fg!_&uN?X$t^iVc{~R1czx&e zBGFxO3%!)IHv;e2wbb_x)@Fr%+d@^;JeBHYht)&xZQb4PvA3zadA%LGGo@SqUSc1b zv>tF<+P#|{xNX6QnbrH2c7`pp+JZ0BQ2t20p?^8dNoC#E3)W^uH=lOg1gp%%9<jTX zpX@F4zi;L20!s*+K?2PUqL79R)&4|(k__cR*VWiKJ13-Yi;eH2m^U}L#JFbE4;*U^ z8R*`|*54K$*Ry#;pD<e&?W}x4oD+Dm;7G#vR%HKJ14tu0c*N_$JfC&2_Wfrs@n^?T zzt=&1@!n1Y@Ynr4$fH$bx^wonO{J}%%`iXe&3Z!?xI^0B**I`Y6l(=jvy6GOeDCSX zoyH$GegST5^nc%%dnm+|@7>1+kL#E3QojsB-HpJ4V^&781SCTM=y3a_Kd9Sk%`ApE WZ>IUxl=BqUV0iEK!C(IQ{r>>*O#^fQ literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/20kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/20kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..ecb09ce22f286b0947d8e389ad498f896c3f411f GIT binary patch literal 114954 zcmdqJc|6qX|3CbeEqf)&Iu%8Pl06yeNRm`S_DZs)$-eiNl2Rx_DIwXirR>{e2_^e7 zS;v|^V;{4;=f0ft{eI3k=X1_||L*(0TaP^6*NnNY>-D-`ujgyMhW3Lt1Z_KWO7|4R zz`y`q0skOcA9NDh0)`9>8^5<~{4g<Y{AOliVq{`rW?}jLKP%f-7FIS^7M86XTiMt* ze!vqa2RrA+U}KU$KDvdOk&&65m4)^9KlwlUMf(hG-@3(^k(-fWAGBpV1LJlES}lZv zAO_~&x5ohe&kw^EMkZz!R<I2Y@COCk!1fs#!KRtPj=^6CfcGJ$?aVv&9y!6nd*LeU zK9`;Hcb_F~71PSA;=9;J5I=g&HHeLU7yoVn!Tkp$Bo9g{C@LwdsH&a(P5YG2Y27o1 zmyC=}E}NR!T(`YpXYb(X=I-I?<?Z8p?|$%ukcW>#Bcq;2$HcyP8TU5%T}o<NddB;Y zpYjU|i;7E1t7~e%)YUh9{np;m+0~8v(bGFTGCDT?b7FF8dSP*Cd1ZBtxK7%jiveQ% zgDmj-55oRJ*LFbHmW?xD-JpwMix>FMxSff4?-7<ACoZsFb>ZD7e|PInt!GJjRcvBM zFB15!xwf(I5?2`Bzpz2t@09&NBP{6u6=nY+>`%ISAx=gHaCnT{Av8o`ETcgYCGbo# ztQP)`?m3WsPJw5g(HzF@wXpPzW2M~9#?CxV<amBT8*;rPM}wX=!Z^jO(#{2#^1vJ^ z$+m4}u#~t<gGQTS(lk2S&7<8Lg{V)^pq%9O^DN^#FKF(*qXO2_gGrP41`}mViE#92 zJ02-jUgT?PWiYGc26NU^KVqg#jWUPk*E!+71ITlRt~TwR3<kBRMdlJP72IjUZ<+QG zJ;vcigDhxJdX8)$drUooz6##Vq)bcw`8>&3_BK=!%3&WxG{k9;KMhiwcM2*7J9vb~ zqniT-w0E9obxNW^4WfNWacGf|0(zaX55{dbo`iDrzR;jWA(-?N`>nKhtlXLg?JWW; zI8o9W<wGSCxnrwP3!}<ZPb8>thWF3sNhnKBm<H8X6p`mB!MD2k!{O1vKI$r>6{z}6 z@@=4Exd51HW9#PYq0^bs1UpJ_3)KblQ~G`4mJIL5h^80%7tc?rxr+<@l)ztbKkEB= z){Tua^<pUZooUcaDSX7T>vk#q2-*pb<n~cG8?zRs6t7I`ra|5v_E1irHejfB5%sq9 zxP`uFuN);v20If(gQTE>4bsI%@ax>V$Ot^S?~{|>7wn>N6t$KHwQAo02Z;`X$Asjl zUTD(RoNJ{p6X24PHR%_;yj@dB0W5cgI72lmBDYYb<8vO@TTf?W2jMA;IfyTJ2)oXK zrrt(>H`aC{${|`UfLNZToeZ5D=XkOfzqkb)fd{<2*TTb7;{ezpUp+aK1|_kNrb8La zx$Epe;;P|Etwj1k;ITNsJ@z5gd_uO@%4cwXX3!b%%CP`3<b)D_<yS(3QC#*rxZyw_ zQqi%_{z;SBRa6>GzKs8EgCviY2Jc+tWJdrm4LY%tA%27Y3quL(%(^tlniafe_9N?e zBBcySL^O%L`wPT(cQm)eX$7Xn6wNT!Tf5?>X%JZka_a=t-}IJ1v_8T(Ad#&xrJ>^# zFzsGb^h`eun$)w@hWHXjBG#e)jnz(?wPw+vop1xo=wt#(u$2`B)@BYvAzIzomBj?o zww#gT0Qym&N@kd}VdRLeScjdh-Tup3wcFoR98CB@Dxz-r1<%*O!JaV*3sd}5H|z0> z=UI8E5t(qS>;ytlCYoG$XVqio@U+j;N_*$SKy}yCe9uYSe2s&z_7WNE-Y9j?vj+Ps zd-(5*S_@<HF(SQr&X7UPOaVlk>qBTzF0pOX2)94m-mE1=k+r>GPTo)NMN11;t?lJI zEbq^=tY#+7SncnQpoqn3cPG85)A+)u_u7M;*zJr9@jqdE%-qV}<k{&EF5#HwERDp_ zwfP@?rmcHgZ!JFx)q%z9v~LKP+oZGhX5MKft%Z1C`7}$#7xcxqJui*peQK`G8D5;o z!-CXzVJG>4uG|r#NV`>MmD=X#P2ZGx`I^tPx%!malkRc1-|?gvJ@XQAXDHdU_rFlW zqYb&gk&=FIUL9w{5u>xemeuD%IC1JSOvhG7A_~!vMfY3(bV^R-Mv+m*G$_%sg-XN_ zvU#}7Ev9;7dp$V3g3yN|<ZUHOmcQn_{YU|@v&WDIS(=bqnOo*8<&Ypx{2CRmi=cZh z_LXG(&@FfK*K)~Rw(LlZ&RKDn(*iFhK8QHQ(i16V4G^%w5l;nD<n-w;TgZ@6s5o~l zeJtu+ywP>$mq}Nk7Q-)|(IR+?uO85_SL=dM1la^UCdL<m39J{AH;r;cL!n>j0(UHl ztq;bp&>+FF)OHV@mjeoYK^!}_2A2qsjLyshfEgV`udyyBa!b?GpG-f<83~1wQh=aM zwVGR6)d)Y@%_AHcY^!mf_lv=%Gr;Z7-JoXzDHF`l6scd$i3N&w3`0h+qZVrq=WZ2n zUC6m9^X|>QP^PCzw&L7A!p7Pjl{<jeio^3oONrc0^vnKj54D6(2VOdeo4tDM=^&q} z`r~x{c`gSU<TwQ{^A^$|><pq9JQ_hn?jZnh3@<-t=!fawiyrx?c>1dT;m46rzI-Xc z7wxf8nX(wicneXTTgaJIdq#<WUHzx}QD>Jl#{;7m?#_)aK3tNx`1p0Wyc4{M>+h}P z0X53hLhCW7=ZV~-o8Rp18c+EdeLOq9|KhjlEjl~zzAO=e#&CO0%9R0}G{S2UiwX=p zs~XufNV6<~Ou!H8&<`xX>}06BJQep``9qUZyxQ9{S>IbfK#X4{__{W6L1FGBqAmf9 z7Y`7QxM6$7Vx+4bh?oR8Z5T(f-!yUxc^fFB`))d0OnxesX_v~rT{MUtvuW9U^mHt> z?c87FGbinAWnMu?Vo^!O1Jxb-O~Q3GZB-^us0(5*ds=f-Fr&_9s|M`E8^6}~#g~8G z8!>M9=B2t_Z=m8Pq1-eWQw$I?Zj~ErFQ`y+GJg>+9_0P)V?xsVPKJsMd%^if9z_^# z`y$^!$zmnrIoaC~+Fh`zn1EC`95uI`jCJ`Pe!g$j7z!l`t*UnCZ!O>Nl3XV4_0ul; z@olTU^OM}LS_3uF1JC1BDX*&_ko=<NmRQLfv1q%mzto1V+z3=ZN-qJ~^Bn5FwvTHv zP8a@akGT|IxZ|*D)ttG}cOo9qI!uFbJk%GhENk>qu0ubtIKGpi4H%&V&pwyhk#tWv zkKiZzUIU?P?UtkGuNlHjUPJ$e6tuQ(0(axs2Qm{K9xTP3SN*)dYyTFN^QBow;P^~x zRs!%T8iZk-2XZP<j$XzU=m&~5ZJHvUC0-7G@0y%!J$AMi3yFnle#akHXZSi&k}w-! zj@<P^uMK0X(+KsH5N8C4U1Hp<J!8lwjB-Yw?M%c5`7E!u?Xb1;dKj3vO;<vgefB+< z9&(}xwepJwk=PQMHVM_=MeG<oK9;bwD_*M&lON5c5HN)IUHG(q)EQ_5owtG^F$0r| ze*k1~^XQjkBD<OgHLNg!x#G+6k%p)5OVtzk_PB19xM#SD=msb2MgCG?+d_~Vndezu zHUpIEh|sYzs+oDFkm-R(L35Ei52dj)R0(@zy`NQ=0m!}^J!DPVp2%%YF9?4FqB=tP zv#B`0stw8L*u{2?N&E`u(CQFkl)P!RZq_gwG$z4M^^2ggWeNsv;=xDt%iQSzwR#e! zG)x0%klp&~#O~&!;USATzNI`{Xiy`L!bpQ|Byz%ZClx{WTox+H7)L1QohrT8?|8nT z{Kk%?3Clo$Nqz)aYGBiOIEIA5W7`r|2v`z_iOgT1*+_9F)0}$1Nl)m-&*<v8(1VOe zuijN*jQV__M5>jLO9@FNp^?B&hJWYDX#Rlmg`!U9UlJc)is?qj5ANF%ctSi<g|Bln zHaTJ!IW~^R0lmy?aUAmc)3v$enXoYPKVA-l^+|t**ppGi1Euyq(MPUd_2$ieg;!i^ za>Ej0h?&);bNz3GaPx=szAn8o?NJVJ(L`w?op`nttmsr>96nf~wxsN1zeL#99p!gw zh<Q`i@`I*U4mdeG*hyTz?)JjBU{ix)#f+;99QD38(mgU!yBxO<9KGdJ*<PEs_H|+* z*On+ZT5)VN=MxRuTJ(j7$)Pv6bKA@0E~dT0bF)9{V8#eXsFwOVze0;k=+eU0f~Pu| zH2sfSAxuTWzBsk<myOC7eR8w2Z{D1BHvZP!u9BqPn|CTuQuGDiPqe@l0<Na<p})>M zqO?KW;;NRQ(^FHiD@UJ+x+M5Qi&XUR+T#^{Zp;qT$#%upjPhq{<wO%j4TdfFLHzWK zhx8MU_q~z35HZ4CU?cm|BU{S+OqtnMnKl;uiMvnHf=g&&#?^EXc*WSQx3Y-ryh0K@ z9KZ$LqVslg+&&LIe*7e2=y%s=3%ys<onlKY=Y9K{XWbFo9jK}%S+%SHW`N3u@#|dX zz{*m&JUyb{ItcQGJXyBSjnOW8Q+F`6N<y|Rs#%p$Wy+F3P~ca>sl|7;nO3pSTYviX z%6HhMNZg~v7aD(m3`<;&MM{(x6+5knEGj1p!n1B{*Qg)3Wg_#eBWlKQ8qc-ugiN`K zGjH}iB~y9v+rck5UxyzLgS=DtaE>s~@{3z5ymlGi3S+q6>O|t@7ZZn|AL?(2>57;T zmno$vy#pVu?7Ie4y89TSUA~GF&iP(xWj$g!ho$({BS1l`04a1%59>yV^2G^6eu5jZ zX5D+ECV$l2t2gNJjQ8Fe4+7a|{PzP?I1L~PGhq?Klay0dtr@mMJz^9yp(%I?1O{$a zfYA|?=$VKW#Yg6Ml$r1+K}38A&d558I;qM0AMe76m9@2d?e5(j{bMjY4Kjl!)8B?d z-xgvicd>IHX^@yjipQNJOq2aQ>o>6txP$j5?V-#;A>d4mW6AaFg30$L9oHUIA$>)o z#0@W@=K|O{H;83LLCApv0Zps^?ScV3h(zzxpcN3y0_{4$la#n66rBBTK+3U6xJ!=w zHeUZR^&$-_J=h7Ev|$<dw~i5Au9r&dEdJs@apalO9e?uAO4l4u^loBNb!pQu0rxQX zrvKMh-UY?ixmx@Mp|#xJ%;5tSqYq`&^@e2*%I4f`i~ObXaLH8d3C~Eqx<_u@uWZ?@ zG$->$uh2^>-eVWp6STOT9N_KhKFN-DmplAT({)^%O2)~0A`|_*_lUTB%Fcz<XAAR2 zQ74Emhb)y=SHEpnb9}V*l>gz~SJYNWz%W!%6Y`r*byN%D9)8Js|8z?J-L3P1U;2c7 z3DU1r59!Xtkp?;R%$+<w6%~f7MBmQa2POJmEB`bq=<POKuq-$jGL)@m-ne?Lqd&tV zELJ$nr<X^y3G#{0t(oT^^!CN<ta|%(Rg%TZc#q38!&roi#qYQ+#zVag;5p3qM$y8( z5f*G(V~X|674x%YR$HBcs-0tTA>v*V`+3uUKXCM_jppwB3*gv*zA#{itg&v(1~Zmi zZi6gL$D4JoZ&-H*Q;nnGK!L#I%uvFdj18Uu^T3Us0dOd$DV+VkifT=7jh&8ZwJUHP zt0#G6kCgW5rk*@{J(4rm5f!P*QN9!&RF*t++4fUu7sf8UdG{S#^V=O5!*PcE7-7^= zb)dB4n~Zc$4*4?&hswvUv(>7Um;+l%oTt+mCB%NRyu%?vrw(EEJ(zoIpI;yK^ZajF zA3~x8R7HGkKwQTEwsg+=v*7XU!R-C18S+1-in6zR6%8C={J>E7#&3ZtRart<P&lR+ z6MI?S0E)h^cT4NJE}#76H*EdfM}GVaRE?YO_{EcQ8%SZ<GWp(=CdWoFzC9amu$n<C zQR{Kp#s!Jzay@|F$nj8`i~s{6ldHp+b*PF40Ylgt=0XG?<>7!E*m;Qj$bEZ8t&NO~ zO&!o%-p5EqJ#xP*%v?i>Y1-uq+z5RC*0{V60P*-*z4;L<>=25q=mus0Ry9bY>lw9$ z8W*U>4sr?d>Ok}N0DZ{~2A?r2ah&!C;RM|aH#bz+-rEE@*&2WXKDlE{)v{vp@cB~} zEIM}JBZ7fyBruQk^d_6;rIt$x`UTGn{H}ybKndAoL74T+8f3wmlQZa^6StIELJ6}@ zx8U)oIZ|c%jEH78ex>0&OZ=OJ497!_X+8R?7h<;6nKKf=(d`l&K9&})Zs#HMsZl^r zU;eOq&)w<oJOh025T+K-?2SHA(owM9l=ahc<N_P!u&;mOl7(`u+|GpE-Z?X7y5jcn z3((WWbTv-TL>?O)Y%j;4J^b}oK6;yZ;k&CeNc+Q!ZF75vO+?nSMVyA#KFi%l*g7i3 z5!{_Uo#iJpr$6hm#KrE|Ix2pvN7&^ffnh9?**{{$?~$|mZ$;;oME8V;w1#U37+odn zAm6O>6Ka~ItFZZImJWicuXeoidY@Z#d-tKpJvSM{Pja4T3BU)UhZ68Y6uERu%5hv@ zRa|^@$ul@#_MNuM)br>Uhg;UpIW@p`@I7P?F?Uq8oNL%G{hd*Xh6l0b`7=2dgQVGG zxQ~NKl{I6fq`k6W+U(3ijx;&_{KwuVH{ovvw%3ZUw`A}E>&>)6C`=kcb5S&r){onr z%x*R@<vm*x6Tdz>6$iC-YwSS2ShI{<bNioK5E;yP|NgFPri<)(8dS!;h01o|6UB~v z&|jK(Z|HFZ3TYZV<d^$tuS5RS4Y}8x(E<$5@_IhStxwbnhOOr2SULJWZ`xnGCcAX( zb!6@9pA~7VjJN_nxyMWP#vfJlD?0iIv=d^bgR&#)0*_#A6MAMoqeMKYCfdX(Ou#4o z`|3_kZsUB{POA=0q`0qPnXyB0B#*Jufce_K^q)amk#)Vv<ClfEBbnVGY1>nD=0iKy z0rk-L#)~bVKMrqM7Ptmy`^-OrhhCbH<{x4Tk`|H;9$F53J^W;9EV{pTbe`PG8g{31 zkeB*OUCt{-Vs>TZk)q^ySo7QKB@RkTcdXtQj}&6B!aWn`h&`kFCk+>_#4G5_wmupZ zP~wlSoc=WzDDM<SeFxh)CG^aHiLv6t@SV&$KKCKowkR<1;yI;J3B~26_~-D)mRV=a z+r)#p-f{BZ`EFOe6R@E{42FPe6}jHNRo^y*bK3V#?oiaR$<q7UMyap9AC#O{wn-8W zUC2r>w7yJa!>vY9qjJ?z>GxzmC1z}kA&)<`6-qD~sk~5J6xZ!lQ2Zq8S&7L-RVHDO zoGktFp{(-Llm4#)`a2}74`^k5v1vH3Bc_sLq_DccchAYBs5JPkVwtWRhBM;GQ|VwP z)|;bg7ky2P-k)^P$WGfoPfALzZEECne)0i*kTqRoYmT)+=dA*v*sg4kvJMYewMgf| z4XwQN{?m3hu6~}1(%b=8@0ER$d5nnI%ci(qVcYvvDCp^Jw=z_Sh|^KiSB7ml&igym zjnW&r#<IkDPhX0R$RA@-W#!A0dvIv^$6)Ww7qz0EoE)3&HJtain0jHZ{P>DG^MHqu z=$>U3_7m&=;b>aV=+mR}JCt{LW(X&wK=wMhPA+E-M3|JAoZs>x{v$Nxl|J6NBG41( zwEnu%YuEGF6FGMZy89`I@*ebZJnw#aKU{g+JqGg^G-%g_j_&lPVN3RA$@vt&>`!MN z^Oe8gEV(IC-!Y{r+-#6RpDbTN3);t&vgEHSx%xcnx^7)uLyhV;iLrp|YZK-ZCNw!g zcAc@X^(#_eIDuRaEr^<SObr2m>4zbWNDV*&8mT2{eh`_0G{a0B$U4tRM{bk~@JLDS zVj|~8He3zEwByhX0P8XMR^x7ij4T5txc&)#rH{nkm&hp53DW1fN~=BSI(&oi+*R)h z<oFyGj~SC>e7&)>dDZ<eiy;sh?Lw}V0#UKZy@wu?g=Zdv47t(9@)_PwqLTW@Xb^;4 z%juHa4mWU5P^&0kAeZOBRnt!edpm_k%F>qj2CkFhhTZY&Tl;|b<c?e`dk@J6=z}T1 zGIw85o#1ky<k;>aa@{LUW>3;Vbk8mjmo_pZMzto+Z^1nKKm|c=F_BA1M%l1ak4vM@ zXO$BhC2%vq#VUA+!yDl)CDzx)UaUFZxnCwfJy5=Mhx{*|0bv&tWGm$YLFc~z5vACi zbI!MR89yz)U-bHzYjW-_rxt&g5uF9QP&vgK@!$i`U;GvleXgc26k3IMP+-DYE5YK} zYGhB*D`W4jn_2srj-44}W;Q4x87DkKxRGX<i6WCq>{!jm6`*;YO5ewZH(2Q9aWmM4 ztMuH?d@6tLc;*;p+dxYiG10oWvgeBZSXjkw=mh0UfE5kO*O?6?U+|VY(+b<4@ObMa z=ze0y+{s|Bz}@d2W+}b4<CbI;Ga<T>8U39IH&U|v6&KKyy`}N@Sv2FKJKpk!D~o6K z-BtGw(Wp=H(V1-{IMt#B)D0x=l^?quq%vVwhTZdG<l&WDYb{p?EBr1|?`m-SpCODl z7m-!`?LrJof_2SJb8KF+)o=a&LeiiZWFm+XtB(SPF!%A><lcQe;$+Nk_~p<|4R`OP z25a(+0)v++(UQE)e{YE>|H3b<&wIybfko!GY!4{SKidFqabxQU8gzaB!Js@roCfVc z-=IN!$Cs5FS~TLt2XAN!NWBaE_SvnV6xSjcKi-|3-U0_4)m7*?+9>uq=9;T+t~U(| z@^dP!DEh*sQ}dx=&ekg>KX$v_IOmfjb5ZOOR2X#i&Nui|LQO=3m+zON+J~6XDF-1< z8QJozUCpxuw>51{3&9OxOL0EdXRx3(ZlxqO?V&Rio=i3J<)2M@_rn1esN8Q)vf4E$ z^IQEkt3aPf_9bUSgzav+^|T2;o>00xzLaX$>%LT{3misMO;JViMWXqtC!w++rG|W* z7^i=x-Q3vu#8`>^%_x`8<0it_N)vvZTy<@~qd<IYvcMDOzudaqXninF!2gr@><LCs z74~Ea>ac~}96uR7;LotoRTRYYD5+b#Bwshu$(x-sZ;!0J&q!qg&e?_<1KT|2f%<F} z=eO71Y5Q>Xo(k7d`17UrclHIU&#V>@8B+cE7DU1(?yIl0DIW9hD{o&9-fvx=lGp6I zl|(jqI!1~kHU4Hzbja=5VtHVkvvfY>(tRfXpQmG`;Gqkz1MWmGx<4zwsBrNhXBsDu zjiwL~Yx1eo?1^t-JRx&GwI66jh{?P^tO;;@qEGRg><bU7YC+k|+^KHm0$xjVt@$HQ z*Bf_Z;y;D&Tr?OE?do=N>DA5YE10Tvu|Kc(`a{kBxYC5@_i7~7w_6mx3~+;wIeL-? z2&G-JqGIB_@;4vs+5PmpDT%TE__5_gHl6#j3Z`QC1r~d`8_#DKZEt>jsU;e6thnFL zzqr{+?m~iLyWH|pDly@FTsO7oaNNar(a-BnFg)BdOUX0m8FrG9N6+?QcRJ#4lvWxA z?Y_SE)HPGD4>zxm2TmS$6f$5UdT3W>_~cq-8HnF#SLU4Cbzy&1?>pgGF`_T8rr`D& z(ySrJ!<ENLd+LPG^-P7AET^Y*daxA<<faC!50q-TMMWiK{46E61bZswRqg4vtc?hf zx<|b0{dq-Z8|U$+3mUsxosD}JZ<Oqt_BNJwILywXK93IBJqyB90BOan<cS%pv{5cW z{0ZFtj%?ed?Yh!Z)OvyGkWw-(=Fiev*q(&hSHKq?KtIg{pUZSWEwX_ORjxatmDS1+ zHSP3t!I~11N|Hc=q;qplet{Q7Ux5<W)<n+f4Q!8Kid4ur437hZo|HBR6Xb1F$@XNR zXa0C)Cj>zE^Fq&l8CO3n(rCW&pL$!M>c#|0>N`$%T?fV?)(un#Wjw$PCBK*Gj15R@ zXwnYc1x*%%jQ64kCCDtJZ@z-R$+rG4m9}`g+8SP>6UUPb;Mxp_R2tGCEx!KqtgK!% z2;~ZJ{}kdO;@REn`FeGsY>IGnCsSUqt_11~ylV9lIQxAtnSdSE6juCCDLe!IxZFZw z0VV?v0tWW+mB-{6%X3bC=3lRcq1c37`HVzAyC-s2h7Qx9f&yz2TR)8d2?{T0`T^9{ z)u(5`|G9U}wc>?0()poKxIW<()7qB+{SnlUsG*{I%vOgxhp4ao-E7l7d@_2|y=b_v z;m26RDN_{giJ!^$L7^ZHs?069A>A?A&tK(PZrXKrS0;!}?GSKJB}<EDV-|VWuLWwn zqsGHGjvrgq?8G34{LP4&DT(1<lXrDT@<m{*^oGiOCHbn57IcBt-DHaYg2|&5Z!;8+ zcfv)?;g4fAJ(eM<YPcuU%F2ROtR^pW3YW>c_z3ch;&)<>u0r3#<c`;UnR^d?5D9#} zqLRpyNAV$ZPg-wN%uv5dh#HZNi{bxugREX#y7$((y0c?`+s!q05pt_rek4?TAqQ~k zrYxBwdc~Z#wRbV{_H36wZLxS6R~=(@WWn>rgX71(m_?Vq$z)!B$TQ~1k+97P7y0tn zO4(P76(3p4M-<&eo=@=Ah@DCW3mjkG?CYMl(apWGWcltXXJqYK?lX-&)BGXzzF)&h zme^jm(H*aCd@|HUe0)6AXWTr*1NVG>)@YO9`$O$kT<s@^?y)!Ts=*nH@XTTerE-ta zLix+MiIb^Qzgbx;*1kS$xR|DqP05@>g~EjMT>RD6yt#KoCeb`Hihh<y*Wg=zpA(B2 z_nxZxJk?!!{y}^9k0^}OPM?{NhmWosdp#NrZ`5}xQ|T5s8z^w?eD*!uvnD7YnozVl z*WqtC>V)E$PT-Mo&-7crZ{WlC;~3l2vk%wp2Fu~q&qR#F5bCjsa_P}z2U0QF2pjYH z{<S-{qpi5+lb5@mKd`(ww!QUHAH`vDrgxUOw31m=ufKN4h1ANLKGW;3Rxln`z9gkp z`Ww&fSt5IA$<1dS$I*fliq@P&4@KV0%htQ+ejT{~<FU{a@%_z0F#_u@a~92y)2I1; z-zlw`bm$4i=L$#eGTuFTV#X4^>KR{zS@qw&yl6s^+@h*5w{P^^Ye&!0ha~|Qu7x`M zS|s+ZeU)yYL8{ptFt<Y?D47<7r}!{L3TX5wD9bWenI7idnkMX7MKUsVcDCEo<iz__ zMP|23sy+t8T=tc@+`b`evLTS~rpNBdfJw$eL6$HFKl_VLeT_c9PTw#UJhII&FirY3 zNmS~fx>9dN?_j^>;B4fnrCw9ze821L3=)+*zKcA>(~7f)k-qYp*TrN#N`2>26RS1u zOtjiS52x#il3ND3X3$Dm3y(dkcI-t<t$@!B`%WDqpDBb?&br~!bA>_9;Ex`WG)ph@ z%f0)%WrK<aFWmltwsOi2(eHS()2m}hJYD>Si8ykJq4t7h3q3^W&<`}XPr{3=05x;= zW#jf{S>w&7qx$-+8igJ90)*K1{x~EeRkT`|xltI6AXD(8nj&9Zt>i#jXu}g#M2rl{ z=0+Pe-Fhm5S;&c~`EUYG+26FxrXKu4;DF|LpA`j$Z~wXhfj3(LH3Ha~qGi4Ui;2+j zDE-n<8MTwQvUizYImV!>{@U2&FB|yN)0XC?Up^aVE1PybR~jW0c=rq&5>V1|b~%xg zUAhEm>_ATnVL+vxpCY+w!1$W3!zC+%_at{hYCy6<@Sdoq3zd9Ze@r|HoxpCw!(URd z53yscZXi8-t;Ar?*#rslLanW1>#`@ka7DgZN;ogqMxjViRq;dFRnt6X(D%1x39}VP zk-LD)Yr}AL1pOdTrAZmlQUW>90rZQU>GxI+tJ`|@4;gQhes|U=W<S$5?yV|0dh|pl za*zBwU_ZdDWFrfyIE?74)O^RLH1o(y*I$@W4&r-!?Wl|(*qN`ULBY`Nu0DJ0;?|9$ z=b&VO2%Y|2*WSV;*g2yG<Lsy4^6uR}@%zjIlhBl=NHAXw4RUhCF7pBz#5N%cF#Uib z*PFD@`{w{fZ)Z!|qqk&7^Fr|>E@ckK7ve~<Aj$iorJ5&fP_(1mmaITrGRO<dYP+6a z`tqIbR+P`fMln*58p-54B3e{b*`8cdSrqQDyKo8!(QN~_CMSmuz2uT8T{p-2Omh*C z1j7R$2ivy8^z`XapPb8FFc`sq(O1}&cO)RLtwBF=f=IaTdTL8>4&$mhHKQDzM6p^h zP8+cgtGqkXbi?#T>6rOZRP+m;;XOknmw79>^cJNLRVxl$ZPul?&Ml(nvv5a8GEzD) z*Fw%c%Wiwy|CQkf+t&%k3Mk<5sP&JNx(g3JNj$p4OF7kHs9z2%I{%WN*=_S$EY*wW z>|OKHU10z?_YyRcG6%g=Ma;hl-aoc4T%F|x%EL(hOrm<EFJeT9k9|^ZomzLTqueCJ zJZbs^{`9>?mc#@r+^v+O15PHc#{woI#~+~|DKM<Y&hm|HhjYB^FLz@`O>??cEmNLy zeb<Y^%~%V1N1U&qLHC2mw#&t2ix;(N<hp!+As;Vy+?MH|x>~_~KUHsftYq7yI=ma3 z>IO164p#@N;eXs4zKPmdsnRp8u`ljus{J0TfmbhCL^_c<)tQ)y$<)d~A_z&C+1i%n z9`(lFRX~Rr$5o`piv1RMKel*D;I<Is)z8g3R$Yr(N`-|z<l|WvCUP1+w~U*<Ie2<j zVLtyy-G?(bps(z~*S4x(chf}KQ}$6y@>>MGf7Mr!asy@DUnsJ1!cL*H+j1jf#jXs! zQCrL1M$JS7d;L|2Wq!M!PWF1HAuq4nT+s@VaCMpNL7g>e$;@(`u8O@>!X&yizL@IJ zKGQokCb07AKlTK4s2LP=d3cMJzclU^+1G4dWG7W=c0#~b+!YwWA)}^2qV<W##)84A z@7lDz{4mrvtIE5>86@{V6t^3{n(sc<U6Rd$kd}-?dlwf?ZTv&RO*y2w(t>zc6DgUg zNOK2)e|FmychNH&8l>euC%U9dgB}H^Ch_%?%Cv=J`F%V@FUB`TPb8$>ak_}BDYY!j zyy{?+ZlxJ%`pK%?M6PhEefar-?dH2Jgs&`2T^cVah`$F+%(K?~D{-N}c01opdDFc! zY$R+@B5ccZ=d_<p?i$Ms{WXd9g>fmNk8&~2IkM*RkIr5@p4E_k!s5aDi58T%%lVq& zm~PCT%8H7L#fdAp9l8fr!zx?%RoPHZob$=u1BBzARc|A;$m@agca8S`1j80HZfs7p zq(|mQj$2}LGC={pD~UXpD_Y%ohw*dnl?i^y`A0q-o!z@SCw^e?)HyGn6z>@-u-jr5 z-Q8mBGyErZk3Y3gVk6xs9q&+RPmEW?r%@KH35ndIp}#geo#;(2D0J%?@UUNDNNWaT zQcW(ssYx&<!{P)c0D#Q*^hXC7G}R&26X!Q$O25h85$rmT{;~m;$p}LSxTTg`dV9&I zA55<fs-`&iy^Cf%QnO9o;J74X<iA4h(eh1xK3|jfdx!kK$)S!EC-=h-4sPhVz~}kT zl+2@l!QBt)9&0jpa%s@VZe@CtWUj$$lR-@;pQa|?XnF&;6sa~J?MMWjm~Z}dAFA_A zz}5dxv~YP)GW_^4ebeR1?t$-BdY_ZncB^0a9J*t4mzw<^Wbe<7f)+SsVk@hQDIy6B zFjsvWdRZ~Yntqd+m7?Wkm0cqR6{V5(uazdpUBBIa_vBvH*m)KsK9CWzol02dDgwyO zf$W6o2MqQ0pgOUu0EAD^!CJvye0t~e@`9>;hCT+1?D5n&9Vn$0xpmKNr{_p_7d$E9 z0$OukQS2G>^MUa`jr~1;7MV;x2xK3joB(Y?uOdiOmMJcGfEYe)s;9aqvb%%imdBfI zU@Y}VRFh$Phkm5VOxHK((Qcv)nxx40kP?v6+r9DGzf^{4(87WXGD3rnT8cn?v7<ce zTM|gq*zN*pxjN94i(cu1vmw`w4_XrDDGxxd29G=_QyW!326mSTuYtfUr#X;4d>%Qz z9~eV@N|^2iPz$Mlhh6!KeU`}04T?8g%KBj9S_DYWWd`M};*sN{H0U-g1qFbnVPRwJ z#zYCES;rJ}94L_~f_Ts}>{8;EQal^numio;w~pIyiMfv*V?%+i+eyZA8|5IUdej1y zmFj||=1F7ze3pc==NaK_P~P=`v#)>>EVdh*TPdh*t4V>NQ@-35Xb^_{d(qX>`U!T7 ziv~Hzt_zM!Zmz#>>e2e|)mKN<!Z2urg{e$94ozl2iOBLFol~hbNCrHxa~hI<ghP)V z^#J4m5}Ym0fnDu=l}q}CZw{2&C`IGE4G~QjxExQ~o-NfxNTURTWAMQ)i<w=5OpcDi z>sx`hU;%24mWpl~%HY7CpjW^vHxw8igPIx(4Z3@W+R}#3c2{ii=AZAU@{(|%f_0tP zf@qE+Wx0!r*_%p`kZV3T#m)7`aQf<_J(R8}x6aZJ<H|r#e;{qsC{V=_Fp&L^;vU~0 zJv?UM6_qe2L~G4@g+PP8cR7BdtMh?Ws^~7TYfcnFj=B|xvJ45vjxn-QI6!2sz>u_2 z7CZuoWCNa!6%Yt5$GYqUA)wOd<Vb5M60fo1rjp*upXEKseJ3E~x;G9v!3J6(!F-7Y zu3eqPP2*0;I3ySzJI>k$3Ue%3B>LW#9~<R#Yv6c4wZu{VfDHnDb2G(V@EAWhEUR{S z@<6dK)c&eAu5(BJcB|nFq3MgbKr}msvR`eD0#tVlNIH9(7hPfjvWKe;bK#aXM9Z3x zUB-nv+jS_pQ*Q3Js552n0%qm!1df!P`A@^WCMPf|HbA`-LE;e`2He2vBZ&Yv)M0!b z$RJ=rCP%F~$t%e!9<3Yu^}ghlS0`P47kd;<kR9=U2#j6a0Su@v5SDe$BC4BNV<Hz1 z@r=j(IzYGvJ%leUsUG!k*k|P(Z@F^;+xl%a8pJLAIw$Hg(Dey4)dTe{5R@f1Er}l9 z-3m{NqUT59FzdI0hYNmm)I6<M3Vq8G9olebRg(t!DS|W!+d1GXq4Dc%aCLz?05Q=R z;Ci=VpXS^OR6q|O#9=4MK*r^WMiqj{yj3~U(v`B5^uzo{YkBzV9Ik7|x%aSRM`+N^ zSETbS6BIE)9x7u!m4aDFMz)8sB6mj-M48w{l4O)V-?ls;RcCpsx>H9%uT**P98YVc zG%r2*?r%0AQKp6JhP*8<g<1he(?DiBVV-gyJ8V$2Ao|Hg&AiE{MErJ+dVv7bP<Zsq zi$4G^&2AuCJmir;cw&!U=0UA3VCy1?rxZ{m)(A2YKWZ|W$d00WuVh_aFZ+v_w#YBO z%fX^%1lD28fZHahg#`)n#Cj_;o{sT5>0}@aP?43_mS1tES(-d^LcC*-1Imvx3J;B> zY(9I%19U}|^M85oS=O|29N$7meujU#(TPjFLQGHIoYQyj`s$5EPJ)2U0=Isik)H7v zHl5L@$wcmmlMm#!_f<6K2YH39Ci50C3e-1-f>YdDcMqh!7JxJhQ5+M3(4%!2(j1l9 zxs{oRjvJR0yR5ms2**i16g1v<a_u9_k+n}V=3T*~3B)xJ`vhR0CUUm?3k%$|D@$?n zTn}<3;<>B)l!C`>Sf%d`7Ql4kcFp@JqBVgO7cKF1o!_+hc}KN#@$Y^#rcbTDReftw zM}Ab*Ai^eA;bcTt>~TvVJfFcYQGqbTQh;HnlLFIaP+QM^=<&Gh#oR49WgY4J9*dpV zd4p8={zAXg^A31S4Di#kV?Fd&`j(J?5zVJC@65B3-zq;F2C9RjWH+Frp6}Ej!DA~+ z$R?=h|JbHbajIRK+^D(u{q9)6tnv<36;{5lIQrt!RxBM;=p`_>4b<-PGOQ-O=2E8& zea^oP%E(uem-pH8reG5w9NToq<1bt2Y#j=zHO}_Rs*`vo{v%7*LYASvF?<ZCOn((5 zk;9r!^8cb0oFd*lT<;9tN(O#E9Yrj%*-h?QQGB&Y-tx;mkoSGm2_(AtuPi8eYt>H- zn#=Ndq&|7yw%VCvX$y;M@$sgs-Pj;t^bY|X0q}H0Q|RAz5O1K@vFyjDD5La4TV2x! zQ~dgRptpGV{cgEU?4I=32UcD>V$EbD2V8&tFRX~{s1>Xj?>F{R_Dhb@*5z-!5G}!U z`?$1hT03^^Ac*j-fmKOjho=AKKz7mtrd$0N!Rg4i<Uns~I{;=+zCSLo0KbL~FC*yX zBmuZ^g}$QEumj)9zzd%nVOBbWHE!D@Z*xl-&}pCHrkwmH-MCDu%m{dkuY8r#GJayW zkXWyf0QBaxM22Dq?oWUJ{1!SyN~T9oJJ2jF`^cH~VYc9!=@Wga(-$sB7F#ez#EN{) zOrVp2OmGwC#6=hf^7O67g_4^zBa7-MDs(ygA(N;JM)`jQ0()6hjU0moobRz`JVw7H zicU|ZHA10*)_Ga=lb+pbjq7cPY`YHgb8Zz_zwOIwM!$aEMzBGD_2#b#X?>~Vkb<R# zzQNg|?FPHlOO$z^Jmq0})*6S~Tr5EU>tQ(dIFSlg#*9r&{6^xm!!Ip%-nw}ElxE9G zbNbDcIMWpyMgmnpdm}j(+;3Y-pGh}hbMTUsy&f6R&easM`|Ct|EV8Xa4Dq#q@ir7m z#+aNAU_+lO7ExXK4C&sH3Ii>7?hbut@<YXhSsev-#)#pW&a>)iyW$CP)A*%2JVHc| z>QD}p7Eu<8Xiy~&v6WHX8t?>I-W(@Wk9Jdsm_dm^$I?e0&%)dHs#x#<uZ^<TSBJ6; zQcRWg#Ph5&^w;+E0P<Tsqd~`I(err-pZWP>%+`;64xs`!gkH3KZ5VxW4RlLMgURpX zjA_stC6Mp{XD^5zR_ww~gkh-!xGqqZIEoyX0cHPWc(28PyP$v5$VfNoZSdt&V~Z-P z>Ta*Q5{O#M5$jVfz(PcTxYn$|Uj%G9f_xp{UVt9vXh%<^)Kgc{)o&|0oXh2Id048H zo!)x(tn1-BFP0OzzWv{<uj~(8r#<EgqzS6Fi${sm2*<#!VfW02k?jVHC1Iy;dW?#b zjPQTiLP{P8wSK@eAQn`cqTfRqzQ=mFC0H?`*KfG)S@zUSfUU=9(>|d_p&#v+Z|!sX zaj$-#{L{&Ar=`62Jav@PH%uKPNyqP2SI>J<>dyP=^>fVhteb){j-nLu1yADB5TrrF zNrW{(??t%A-ro{niQ#ZAB8cLF7y0a(9wET*yo*MDn^`qgrXU%h@(i5c#<Pw?Iq1<5 zgSD2WT)_ATtwi91Yo*m#Qxr5r0YFOi7(@)Jy=2NB&JB5aH45~4xK#t2_e)4eNn+gu z0ip2vwoMZnaJ{W)LHKdu@T3{h2h8YJO@k=e$^Yf0SG*LEq22;h9{L@6g}|3+P!%}2 z@ifLH;7|T>dD0w*E#&zUAp1*S4PTAr`li*lv#6Sf``+E<JjO*n{=d_H;ZH)3#{f7+ zzlVo_KrVI&mdNpgX#vds9`!C`h|WBZvCC5aiZrO^<nTPAm3>@!^*J#lw^ugBZ#W`E z>y-F5EUUk~jxfCIwZY6k(#!k*ncf#fF+?4-4&;D#l>zrs?40Ssv6_o1ISIpX2=jHz zS?eLd#(LFy!ez-hz@*`P4d6z%W)N^Rh>Ir#yUred(_k@|0<6d4-r0|sb*drA0M>){ zmlyO7Q%)ZubaG^#%AUXl6IzLW02bc=dPctFe|F)hx^GA@B7Ao%v!}l(p=Sm`-VDa4 z|EvYwH8kjR0u9<H+IRr?xLs(11-$Mss$c>_%4*U=3zfr~2Tf@92EY)V5C82Iw`*`T zJY+zFp7Gd5!7bAXL|HT?e^HJFZm<A3gpCH9_tPr|z1AagA=&8sL;gnyla)g+;Cq7t zjI7iFb<x2BVCcD$7QB#Pg9limz5j7=gqQyNv~};T_5qqiTFCd-L#MER=ThniYHp>} z48KF_fVatTak$|FX~Mmlcgrmcm!I_&C;yW)KD}TyL4!DE>e0(G{^~$jREJ^2xb45Z z^iQH!n@`^YG<$=ZSnlJ%G4KVb)T_5zGYR+J?4D-vb12Dz|0a|Fw5wFbjjqGLapv!e zFZ?56+?oiC+1SaR>-Z&78p07lgJjg-{!h7~B)1+fa{BEla97~_hp#l~@&7S(HPVG` z@Yr^sSQh;2CP1wI%BpUoiMfykYyHwFgCat1jqB5r-(&#eOFok>-(6={%|m~~5+uO6 zhJ5^romerT@S_m3D{bazLNAIRp1eeK0@5E+gQo=R{2!=$v${Dz!msFlkbX3F_PZ5N z*7ZM$%jP#MC$!Y$iH-fC+N`KAX}o>isla<$8BHMVsuYEXUlXu2NZS4%rGGfOg9x0H zk3fLkKqMWy+(NXrQUz%1G(3R_w1BL@Vqv-?sLgu;{oy(r6C=t`ylwp3pce&2_%R_4 za|MNW{&xxfIhmdCcM15L*8a0%)`EQR|J<I=z0r<#gde?;SmHlVz}7t7Tcw}CTCU_f zfrbq*=eoT958(KL@g`T<3h4e{kGLzqWc3B{@o=Mc(GPE%;WpRdt$!%71ks(~=iByA zn(_Q?A^dkmjrcng{z*CIMlkCP7H}yRTzFQixMx7k)sUJod6a5N+|Y1~-!=R`;V8wJ z$#Xdy{r7|VC**u1U^r#HxU&!>R__C>4feC6$mI%yrvkzf4dR>#26oR}KVkL$!rXHn zAD#!5qL^TgoIBj!Ht7N)3PXOL|D?ESBHA|rhWyn&qy8@J|6pH%!QQy7?pyzNWiUyi z>|OYkv~be0TU}(-fYp1KA4dcOG0t-r%u$ZEQ*f<G!W(ctYr)tE=c(xl-^vQ#Ds}Ao zrREgh+pf=zV#=_{Z+$#L-xj<do=-FL?{Jh_9*OSzSY~8?hCE3XSQ6Q|WL3@o4sOwl zAkV_VC_?ZQYN>q`A)|&ZC7xKdqsMpw3Rq21f=zQAM{98;i}}<(?d{<MPwXvq#pM{) zSJHv?qI2lf;>OfXfSOKKKHAWvR|sgjLcIGxs+X1GxRM%XHzMuPE!V3ZbMx2s!yHw; zN1pnzLqF4V(&#+djnG@}G;kSXQEMR2!VVb#pQPbG_wC(!gJ<9HM!Qpw7$raRuRH4M zdhVD_I5Svvv!e-3JN<bZA9zZe-z`XcHbNM^By^`GLat%-*r(SM=z*OKEf*{e=w03m zn|xgGbpYU-0N4ShZrBekvuSB|(l;LV6V#N{TMi=kuLG~sXD-~E&w!q4d&Ug<_@P^w z-UII}^c}!G%;7&(8Lk+5bN<K{p}WO4;%i$14^RF(OD6K+bq+HCSl_@GAe4pH$JPkm zdc`}fG=C&=;B2}`6;paci-=0rJW<~Rvpx#)5&o!!MDCal<T$XX;L9oAp9!aXhNK@a zuu>k}LeHdlMt>pRLryBAR@ws(ZlspGy-y;Vz^StoTHm<hMK^%>nt=PR0bH3JyLFtd z1^z#`%%H0qpDY`KiA3P3xxg=T!b@5hLCWk)J^3-E$=w|?wtj*hWB=WUHtWp7?uHw7 z0%DAie1@+ZAN8uiE(#Wbj1oz3cIF9vwE&WC#a@Tk)$k9{tLO8rsj?5sS1UMHb!bpj zHqizYRyee2Q2V44rvW*iiW>9vk)wp)#;+`*NEbB%-iAuMeP{pk9#;<gf658z49g%B z>;hOyd5{Co<h_r^02k<KR}0ls@#0_Zb4AnNJ?BybscY3-VYq%7wNg)ttIfv#`JA|= zsGJKaoS=3g1^3JcS!j^C8#4V**SO@tg8zF3d`qr3200l6ngmc|j$r}7X=2KzMk2ia zw+Pr!M9Tjr(a<N?!I%HByAX$}wQ1D3yTdOrRwR{_rK{nlpY_lKFO8xP^s7qoBt_dU zHo38TpYFUbJn%eq{aQZ8B)hP%55ygcH$BxJ?09Y-?f5)H`oQdTXP9J(Yij4E)Yoz6 z+R8rVEk*N@4TtB6Vmh;OZ!cST&sz}%vYft(e4j}tdiEK0wF{|OH$D>&g5~AwAX8z3 zee2JnB)5Lc``SeT(O!@)@cs|qk@7xiNc0(w=&?R8D)y<eGqH=}wktPx+Bj~na*_3o zLh}9;WUa#7`lCwtrSLtGAwJ^n_Nd-kLe_`nlnXYJy4vs7Z!A}=bW2T{HRA@%Cb-={ zosBr29c%I#_x#`)>At#G?zTQg_g{-fi)Va$UK0E1V)W2d-P=esn+Fe(kbo4Uksznw z+)3%x-@u*#i>nmU2)SRZd!<L$s(?qa)0;<k;X1+MvfQJUOQO6T$sNv^Ucalh@&;bF z-mbLOW~(=flpo4!`WYKhjV0*F5yjz9_sra00G#MgMfX<{?q8sow&zO^?5~t}a#U#H zX}(zPtYsPrE42^H%FeC`$oz`uG;Wkf$9Pt_>)dtAFpSo#iI(hHayY23UANsq@q6d< z0*C#Xj?+lAI*V+MwvOTxl+0x<mwRiD`&BZ`E<~5?-&*OAQM}l5>X++%I|`-Ey3K2@ zhX%2%!&Nc`Ej=9dXcXwb;OUvDMRB<&uo8U(OitkDC<a*?Nh5kMS_#etK6d5-ie9J} z)v^5YlHP+t-d*$ANGq1`8;U4yGV4Z|LIjBQtA{YV{I$AfQ}c-EY`izwBB<}nS|i&* zYHH(qv)-vCP0vP8y*~5CZ4TL<pN>c8a&hxDxol4zZuI$f;S4E_ne80)xs6H*EcNqN z|Hq={?&c4dBqW=9>W;k58F_9aJ#$c1GG%A(aSXGUc!^yjk&TB0vYzgSnQJHO@dO<# zaX+d$A)MgP|A8<c;vYcG9e!m#AU|JYrPO8JSovVT9`W7j+<vp#`9g1-NZt4gV_Zjv znaxlHEldw)Bsk>p%{y#&8jSg4MFsDjD0AU|vU1Nyv7&E!%6+dcrq)&6z$r~>_rb#j zJ=$@Y1H983TfSe_;+r-}5p*4Qyy&KTFh9B@&7-o^p|ZYxy!foFO-Pc}<@fH%#z&&3 z-Rh1^xQ#z~FR6CxoWjJ#*4MEgBMPve;#Ca@F~#w204=Ro2C(sW@~80x{dpkh#DsK; z2K+$TYPaB7<F|g9WldT}ZmKU7%Ji%3PJegQu-IX2G&U#wiZFq&9VN>V$s^9VY78H7 zUxz_u=gM9i+dKY-8D@=YCtaA<)&!kO8<}fou8G^n{B|Af@Ze&EU>?fEq)PTc%Dv1- zq-K$How#ova{JRh5A5g9)FppwaqAyFx1;VhKR2#<$*i+m^tr9F<WghYHit{kQTv`m zOBY>Ko_KOq;#<23<;`2{ZLB?-ctD4;<JC~aXC-1XdNy06?!6*Y$CZxQdfx_J#oa%z z7Z=%uu6lny$@TeK&bR6Vmtqe^SfeQdK%rdj)E>-n6x~m394eVtIISq@tT2Z@y};E< zzJB&|fB*W|qv{TvGUUP^)w(Y=OfIKB%qpr9J@lO*$IqT`BjRJ|A*U>Ap6=Qn-TTu# zKl}T<{ny;P1l*C_k#L=d-#?b`_q`P(<*j`tMWD1xs(oxVJYG#I^ZCIg4KMeRjIOBA zu!F^j2a&G$N!27ek=cQkt0Q7aZPB1o9`TSnR=_^7Z+gx5R9bfaZG-)_8TOY3EO(3B zY2W>MNiOgD?OpP1(Srs=3AtI55g{z+j1&2|&TyuP7S(;=<hf3YUV20Bp_qAz-W{`! zObQN%w4h3}Vz=8L-+x8LqC{<g0puM&liTgs_Bid}iL`@h-aV7?iXO7I-@0E};ldF7 zW1@{nmA{-hx~}tndPkV485dcXynE@K!mvu!H?z7Ug<;Kt>4ms)u1&RBMbeQ46v9?U zc-v=4j7TNARhc#27u`u%EgE@&VGZ3IqvtG-KUrS-DQv{HU)frlU4w8vlFi2ba_4%> zdJA36*IJ~OA`?D*)<|u4+|yUDeWLC;o6VUH9`WiZY!dEiJ`vGS5!-EHU2yTa&-HiN z0^j&c%PsqFWetW|HBVh@)8<>!d59tYZ&lc0?SD(f3ecvDsAgSJqu^_?B1pfm4Xv!w z8{b_7+-kVN6F-e7vE|ei&(jS8+3#Hh#?HB(3Oc%j9DV6W_KXj}r5z|Y5x#+1mn@B- zMz!psLDQ<~xR$PEp4l22w4WdNWgmS;@KhZ|!5Us<4z05;`bH1jhJCF}^$$UwM`-+R z>HmLQP@Y5&A63FmVte|^v9VsSo{T<Oeg_=fNf6B(g7Nc6!8MR8tnbHyf@-{urVtGx z#G^>e5oD0&>rR8KmEtBS`c1=+=TPVvv4NsKRe>B|x=W;Xls$Q1rVH5l7U1bd5KjQN zDlr+xCm<CVP(UI(;t8P%v%y76)s(@j&J}((EKvw=GAIFpPr+DHm*E!>FbiNvKMP|2 zy0%Oyu^}Mib)OIVK&$eE`b2?S7yWm?fdV9R1QHYm`a@yTGF;7pqB091piaIrb0-w~ zY;RKacs1C@Z6dx{>_)%ay#6Md^+0#ZGVmF5!YILR?hGL0XKMo+zYOZ)c&el8H24At zxHc(qkzt+kxv$i-jy2n@i|*Uw+>mYHPbVeuYrwb9)!D>@qRB)~9-<EK3D(QzH3y4? z%0Gz?43v(IW-D(ZJaYuJyz~P<7CkNfIFSq7MLHKj-2xhNL59*K8L5ABRN1-!Tiu75 z9jdgeb>6P*Q&NW+7MQX+Y86cufWHoHR2@G?C&5$I?Eg)y!_EJ7kJ&AUKLd{J0^dre zOkD?Sw!_u-SE%)?w><qzmP$tnIYGtJ5kz7XbqVyoxY2LD6RviLCwHOe*MM*O0W`%t zMz%li#*W;?oV_tRu~_TV_ok;sA%PH75BiT!0gj@nzMY^@KE?yWLkn&54ffE9iI@|L z@EA4g0Yrpr@G5BkJ$~3Jk^Y<V0%hqJjG*I_G4oD_*2lIBPsvWIMT>Xz6EQ9Rt1HQy z2*2n}mtBRf(96lBeQedeW@BZv{juA3^ouD=-9<CNKU$b~M#%79&F#Qz`;*YWt(%hu zgyxoeOvvoeou%(wWob8EW;RR0d-@VHi}7Q^r%MY5@*IZo+}Q(266_{Y5Ed5wSWoeL zbJazaHeEZ<YtVT%@j&TSCxk7R%uI2m#-i=!j(*lqU1*L?o_Xqj;nPA^o5N}&{Mh<~ zOn#hu%IZ5e)F9)b8%A1;r@r5=8L}qs=c#eBew0v@aQD!PHD~{{*_{YCmn^H@yDVcc zP8jh*+zy57H?_-l)%-kW`f}UEoer{1I`Q6#R*#1^IFGVp2Rd&Qe(dP}H7=&CEU)lt zPlSum*iGR*jl#n0OHvah%@<y^#a!ymiYj=UN}c>BBUvCm&o4bF=a<kpsO}wATVj#d zFZ1lwibPPbgCg@q=SHEBwB4uVUiwS<f2|rgqh!ZAjPL3DVyvt`6y~=2c;Pxok!54d zmQE3#2pN-l8mp@Z_0N|S#|;>Xhp{%w>+DN=trb6bcNi6dY$HkxhiOc#IxgshmLDAP zmbG;vzbtr!$?yBYMDW?x;^ZNoY82i+C~bSBob!FC{PdPE(^<LfE9RN64%$2#zuc`W zwpTCm{Z8J_$Zyb03}c1CJ0fh2%RlIUA!*Vpw)DEZg^p6P!_CDLLRDg4)bc~w@BLr2 zy>(oZ{o6i{A}RtRNY|8>RJvp;($bw%LQ1+NX3#0E)I>mXbl0Rq>5_J%djo_4WB2#+ z^Lw6Kyg$$9`Niw?`)?z*>s{A%9_M+S$H5fW6GMDVPp^J0&U_hq6Q^4ctZT0uAHDMz zf%~PLh5gQlkDLQ+=)v_S*iG_9a5P=<lg(n?BB=<9)MS=urExnhdcC(fNb{To?Ie}q z0;%XOH@DQNWN=%rj7}C-=qu7Y7SHYzsf~8bPHq_T7tI$47s!&jUnc80rnDDkvNhoK z*fQ?P>We-qLP6Xu#1&7CsRZS-RGDW;Gk5J!6<QiFIw3F2@~vk5h`T#;Zq94|rUZ7H zy_vjpwu{P+H2Sftwi^rWfDqMR1UK@=s!9pgyi=Da5?p~0#Ke(hYR9T_-&`TG->~)G z?zK*DOBbD}9}^8YQEU{R3wkN<m1t#g_tV-DJ3^JTZB_e$;o=qk#t!S@L|L(9ZQ*wg z9kI;VPz@4NAvkv%Q-zjp7FE@7<3sZeRRfHG$wIQ&8Dor$3Fedw)ifyBzOS7{YNnDN zc_B2)L~m6}JN2ZtB_Y2V1{TtCi3%9MlyBk#s23Ow?aI<`F3^_zgk4-1WTI_hoTzFv znG!h2O-UnWuZu=LaGd(If9nk;og(KfXZtrZtSp4t$JG-tebb~K8;7~v4yhWK0i$B6 zW}i$uWm=|v%e)Cp3ulBY|Ewd4>QX237elrnPR1OJdStN=qplix*R<L|tRLS+pRJ#U z4D$wI<(f!#f+W6T;V5gRZDV8cc1YMf+bHWq)BPW0PWS<rC$wJ1x+9&pF1@WzQj)k8 zL$2xY85WkwhFsdzF8nd0j>%GyD(TnOZy3?9l`-Hu{#5Lrtg#py`$6p9qFZmFPM$;+ zG6hMQD>D13AUAmV)6dl9&mYq{Bt(#sofr^p3pI`x8@_lZhl0Jv5n2CG^I~LlfDjKN z*=dqbj5~}Ke78}=%v<qa+21HUh1DBsU2<kr<8nk-qE<V1gEDVoq<mCOM_%AeP-&{R zq9AJHnGGU#RomxESH7<zlIbq?x(b(9oeE3v(ASox&X$HX86cgnDwX?Gb~FSg4;DkM zSU1GOFF4A%b4^{|6P8`J-fO|@Mp-e$Yus47flbguTQw}FZZh07DXGmB?IX#M8KjTD zAY(K~5r5ZA{B`|9Hn!AaMJ8-oY%Y_i-GIGVg~!vm<jH2~s>~X1)5(;MnZP6{y=+2V zLmWH|9-cpw$M}_49cT+mwCge*V}J?D{8$ula`IKMSJ75?RBVG>tA^az$mD6kdXm^P zeDlKC8@%~JERg-GHerSNz0HHI#xIxh<t23=Nc58f<zi5i@FJOW2Lrg<QObm*N4Ec? z9Ybi4cz2FTcKw@s%Vr9kJW=_3)RaoBv3yw%O7=Bs>c-*oyQ;5uETSWN`5RL7o?f^W z_eJ8?+0}eLfo)MU?Nhmto$UJNQ3lbm;_X?PnrK#HHp-7HLOpT<KZJ59T1yILZ()m+ zl@;6rc0==cU$l&KIYpd!DE6<i+{G@$0J&7s`J$pwm2}=mHRR+Ha#L=P;^PY*7CM0% z-vn+}MmgIVVNOC@1Ee99BLbd-H`G|lbL<TmqHExJ>otyt4n@hzCDBa=Lv!q^93ufA zX%_gNsIV6XWv#UE26h42PMi(9F|2*F*|J?KEG~1;FXQ>DUd(aEgSZuw0+M9@=Dm1M zqa*NpJ=ZlUXon!d#{8{>He-Vr5kI&-eQpQ<33S4D*y6bim*nUyTH~hlUeoJ8y-rLW z=;)wWJMjbk?WDTG-ax3Axh8WzKhr>I!ay%7<D0&?;w{o(Ps`TJ4Qp7~A~U_>6pH6G zrFQ4Gbx})Z-?VhImt*zwsj1hP&~?Ig$wNkw*2$uf4uC>o7s^SKBrz>JQd*P2Jrpff zre3X5qIX-uUDp%RbQ~)KbX)TPIv5@=L`|Y8Cw2|Wlt0DnboIZmxZ70LQ!XTb+B+UN zc%#3glICm$<=@5wjsaH&{YAitle9sq#<KJxH>Fjp*?pYax3(tAX=x_fkAiqQ8OyFP z3HN9!R46mP<lQ`>dK@lVB+trQaMdA+PSx&`H~(agdS5(CSjXj7i9C}{Dfzjr2J6p7 zj{M)mNiI!b28uC#eI?};Z{KyA(cM`J)ftNT;FGjSJ|SDFU9HGFzn67oxN}#z1nxCi z-wk5&_sUBj{f3M!Vkr02u4b?&8`Ha^ryieEpj;hRpjPm3W}3UmufPWgxwni^yc%!k z*|2Iz^2iBI@$lQtZ}v?lWLRs(d7a%qtL7fF_0-i8u~ug~-_iKW6kA7@o9)~^I0L~G zZ(_O+?@v}SYD7)PycID%OCQW#z`Eg8-?Q7AJuVl|U=rf}n9M1u7NpW>6y}0xd<pA{ zecK=q3Ir^&l^Dx*{Z!|vz|pfT_mY|JD+yJIv=!mtsVbVe^rtsR5aQq;RiIkv7etIK z9S{>gUwAXmT7{9bliFgKC`SdboN<n#TpdMRr`uVbOhS3x%;p%ato4KjtPGoE3~pk) zplNqjwg-&!d=zLPhg%j^Gmgb6az|hye``#8WZhl}B#kSgUHR*D?V}7XH3g=ofm|t% zpV0-a3jXs;w^gp)kr(X$14e-U2qYIiH4~neeX(L8VX;VXKYSYnN^n{jyl;m%k6M1K z2>&Cn)=AM~5gbSyI!hPamH9Gr;u__;Y5MaIL1BkKqQ^f2x_^cCTbIy3q=p)V=_L31 z9Oqzwz=G5$6e$HhAORhn{zU*cHs=J;>TmgBLg*jCa}jE^;O=O2$Y53ACNwRhv2Nhr zpz-QP05ASg^1@FvAl>_stn_?*{Lk^fx_ch@{9Hp+Oh!FfxG5?Dtt_ua4n~>CI-9jH zjK$_vyNfy>0)&D1ydvn77$y&&EtT;MsI+*&vT?B*96(uqfDzv!_ZNYRBG;ez2YhZg zhE)2i?>!XT3W}f|Lko2H(bKt1bFZCMdSKH3xR5_|lIi}uYK2KKk{<j$(qZ+g;>pOV zd*jOb+fB1S#gqvE8tpk$3Ocu-#n-qAvuJo1sqrIrYKW9m_$%iD$pIhy(fXh3lZV#8 zy#c^&>01EH!Cz=zzVZh$3n6T^<V}NBW&TCLIfuv$JX$~B9u6Si^BC~YInccFsCKc7 zeq>s(a_ejdJ+mKkF9zIvq6L(E_@D<=&Zj_GaI$co7+CpY*iS&vnxh1uGoPQI1L!lZ zkk=CvYu}!NHX<D78kaW{Hd7bQmwSdTd*iqi@vkib3<&*IEIT(HPXVI;MQrg#lt}xt z%58AN!pf@Cj&PLw1VH#Y2Sp91!MI>JbaNSeaNDetz{MMiITAeca9-7#81(^bHdwl) z+`Vvn_5%Mqa@j-}I>;Wff8=~zi`BgRy92#g1N#Ud<e%2!W^g=9vaA)u7G^vvcZ`)T zPuhN&)~HeXNY=p1h`;G5hz}?M?<W0=rzJM>7s2ZEBK{bH0jRmOKn>0s=r5Ttb2eMo z@%aSVcA(dm`0hv|CTA5OtOaeOD1Z*mAyyWU59rQ=dcE^s-Jg!ZJ|rv2`oLgW|Ag?? zg>K1C0%tA51$3GnbblL&V*LSWX<*T6QvM>4odg~A{Y4N>APh8RtOF%1paOMmW%E<h z2brgl&Uq`s7iPO$U%7YF_3H!E$_C_<V2#jzMBA%-MFy=4dvt#h)To^SB*@<bH&GLC zCQ&^r3Sd>HV-#zTcMGihcs(Klc<Kht0NEp$L+t4?AjphWt3n(f)&ZP11Dx%}-9IGc z8;qLdY)T$Ys}*bKBt#dET&QAc`T<h`aN|`4Ae#;L`ime98cbkm@a*)y&!!R<f;s&H z9OP5K55+Rli)6w&%_05NpM4y6vXjOMg$gY49}vA75K=Vm`C|wfpdi6*CNpJsV#Aoj zYbNa119)txB_x_Z)UY%^5n!dx!pMJa)@is8!&4xpRPm9D9fCM9F)*$HV88$QgHrbY zWpECH);jn=Fb<gPIO#w{FmS?DpaBrP;mZXa8?++jj3zb=f_?D<dhBVci>En@#T^ZH zYlIukyT=AIKuga;9X|Z|=>_6%J&C^$q-YYXx?HLSI&6P`K6xn;x<(0GFaStQ%%M2e zh4P~_T8(fB)?VZ<0=zk}=vQmE0su9!QIr9mAsP&*IaGI_+f<6U+YBkVvl+Z2p3090 zwvPdl4+vaX0F(qsJSE~!5V*2KGRAgDh0h4Q1H#a9J83V3#Q$#DB|K>6IdCG|#82-) zhi$RIAVa#kflt?4a`lP%su1l_^gh>)zpL9y>y6@PH9;KbGz51Fa4mW9BLCrgej>0y z3dCCQgdcPRf&Ts-$aZbi$5LS-hmRf2`n$V9;n!wpZ_84zZ%Mt(a4`T5&L8_(zj1^M zBeO7lsGZ|lca6q0WHIK;@Kzyo5V)#%;InT3#0j2V)HwypgnRA4l?Ry|%Kk<0X&u80 zAZrB}!0?*}BZ0+0tTp(n0K@|=VDs%A*6se@=s*_f+<Ev9i@=f#<gH2Zy{gvSHP{&p zb$41XG`NQ3`%8!C)j&<3@hlOsR^|T)_yS8H|M#^Jb1EH%yG>s?b|EfTdaO-|V10ol z>Hq6=l{Z-<VN)C*Yfm-07Q%YOYh)0?HDsArO6qtAp~!PLo_uF32pwyC-gDs#U+KGq zVNYyE{=;~fHU59uR0kTwSj$6sGtD$;42WW`DZ3rVTc#BivuG*`+#dgZS1l&Le9=Pn zZX;!nFHE7oY$+X9a-XOB|G}<0lLV?MAb&or4M4^T?LyGV-o(jIdP28i$>eetzWYSB zm94`t$1auZ<xS$XCWmLQ#|i*egJI6iH@sVj*m>R|84w1F94KAnSLo~Fjds|2_f>?& zN11$gJd!V*og~dIS|Y-B*h<zWnN9*7i@jC*`uQ-_GFlFGAK*&eu1x4`5o~~IjP<qI zw3OAx@LJ9Gs0OLN-__GXKNM(nz4iPAjAHIji3k+71(Q`T*N#=K50|oySWM*D%Fi`- zzB6)yKcHxebnx^qjCUqs?(vk)x#0CfO7va}`>=9v7f+sWESFG3t|(`Hia<v389gqt z4d)!U0#z1Z?L@h~G>nqHa>Ynjvp`R;Ks~lBXk7sttk&nr7-ZSEvNXn!Tpp0zh-usH zp1;*}mVQtga?{NId7EluTEASRM3!Cr1!?wZ(u$8Bvn;IMPZM915J9Kfkulkr$TpiN z*u{J^Y-#HWD9ST~A%K<HeDUE3(X4oipv*~-SR^<-#7<_cQJQ1lzgK|W+C!;ckW9G* zYtS`+8*8^{CfBj=Kx<At3@BIS`&gXWj0^rKA1h7ee>nBNFwvw)uu2q_+cZiNG{whW zBz-7140UeY4Qr7)%ao;zCTVwbFc%rGHdF0t=s(Lpz5i{ZCIxLWWzslztax_&+t7Of z1G|8PJDgVd+<^)Wo6th^`<3SOr?Y8!rDA*9y7iX5Tn=+8f*RqCfpJJE1$sp|y1dTU z+Q$?@&Ld(kXcu0*iIPMQL5#9^ep<3viw0*8s%OyTsrA8?^;WcgIy3u#4y}g*ullSW zCScc#)}ds4xSN<qM`~#2PVg1%%F)B|Dy0(st;)Q0wY>FOF3lPbyJ7d6Nih!axX08v zC5lK`mj;&SIlOen-xO2&8h;xRS&C;gx7#^_U9ai~8IFs5=Nhvya1`Et?z6-C{_Ap% zW;^>jDT{HB)xPx_*qZzetjY$6+#LQQh(O$sy=W(U6B~&FhsxfnsTn&!+{C`@8?d#> zoGK1n$Wc);v8fAoY8j>c>JYZgpS|xy5p?gRVh3a<&9MF~-(MW#+yy1|S4Jw7k9b7V z`%~m6RZOs~ZRiAKIgX%BNP_N~8y3CUfcmSj$0@ptK$u^(KQC+5Z1?jF|GYL5zvAMQ zkRdT3a%_Fw=aFN9YTA)|a*f*&?4UbrYK7|pX&{I`L5@~+YSc-OOH#)pZ_DPoT~{$z zkdsifyi`R_hDWa2;8dS;5B`?z0#P6p9(ZEkggSt4_^irfVJO6<jT^CaX7Z^12lj!? z4QcxEeGg8U%8dGnMt465=RfJFx@>KrISkGU1RfWREj)oefw!Tr!IwngG-fs^qW*yd z+PAnnD9(wWW&+zks&#c2_@inJtOd7MB2e0v-1!ww$*PuYe-Zr1H8$90J5|EbVhp;a zou?eyGA~r3w{Dmi`6P78Baj@872>pF!d;J{>=P?rwZ?uVXf#B_Yt2Q5G~6n9OT4$W zyn!&KRT^y7OndkQ`x>oJGI&iHC2fsX48yZbJ&e5pnN{>~f(v@gG)~mLar`#G9yDvx z(Bw)~bIeK+ocCUTAfE^OL2uR3k7`X#E{St|QDf>fW<)cHb!XL+L>$bTt4`87nH}5q zgIkqe<>sNGkM2^=kL-ShNUe023BBbzeq0*H6`rQIkPHb(M_Kl~Ez2CNw;2YpwXk?! z*c|JQ4A2KGG^(n~x}zLF$J47N7Eu>hny^ZSIEdDz(o)PEYl!Sghg)I{Vr1knem~?K zGAXb|i_Vm)Y^v~CpDtDzS$+<y{dgNSC+Vvtjz(rN-%}0W6j?9!-Ggqoo~rt@pA`iX z`s5wHn*iGjlG;tq-&9qWrST_2jK5IN&7LdCBC6iWF8<yvvhD82uIB2<+?W^V=;+Fo zn!6JBX-h^K;JHpKM#;#R`g2r`Ir~#AMoS%nseNSI4aGF=Prhk5FV9Ui3MEl~Oy#YO z#s~>`spv(VOa+otyvZrg9LbfDOGG3q_wfiNIO&ci933_#B$}EezKH$0ukzDJy+$n) zb?4bS%0{xZ_>p0Qp^7t!cBa614yNR$POy;*HAh%5!}~&^98}o=27o88z&HKvob&Bv z>CxS7FbbdK?`Fm|*)G#19~^C7?B}HljL@&pKBtX%+$wAJqKxpWOfm|Ad|?-kk?t^; z#t&dpUUOn&bH1DTl#oH%q>63YwG5kT-k>%%du;gvColAw?qAYc-<OGrxhxF@igHY{ zKs4EA<XmEhAOrN2G)mXqe7rl|x``XjZc`qLR*gAoUoweokDRIc2I5f}3hi1megUJv zR{l`jI>mG&k0M0o+(^u1kG{MN4f#o29iXzH#^6(H;;29<Wy;6OSdh9%nm|`^q*Xrc z#<*d(JnkxT|5L}99v8DNmB6e;o}_Y}omVM~yw~>B!U{Ha(_cQr;G4q|oqc_X@1tB( zQ3lbXi9?u9w2YJB^n~GuA5=vaXct2p^|zi>x20mV>_vUI#Zgzj3^F-PcSWKPM-?y! z5K56#vGP%mF7X0;xPy$2hTD$Tcw3)2^xmiU0Xd|VJ+1~nG}^$7I67=O%Bm6DCJMW0 z8)rM2$u<5H&Ld2=6V1`wStaGqpPVYGTy0<{_iB)=MO!0X3=xjMi4z9Xi<E}pMX^ax zWGTJB?nrf7eKmyatWp`KQC?9qG(SC*_EDWJgm;v;pGx|Bvh6KbN-hoyupM0dFm$wq z%?^CSQAX7cwGG678fZ^gSTSc+Dt@4y_T8Yn^NTnW(zNho;w7Gr5>y#qA>;RU4dL!( zp(KW%b_F`B$;B@H^OQ^ai3RKlL5#JHTuyfO@SEYn5x#gr(3>w7E_G2fZ2axTa-9aH zbQTWJsHG@lK=k41E}p(FQ(gj5Idk+4bw-w}Kf|?;oUkhzVbdBxO_Db5n8h!EWG(is zR?{1aCeC3q(>5oLmT^Fja_4{!&dLKM1Y_^8UZv#Ze8RTw{{X!Zb|B5|FOQ1$Q=70F ztF|5OOx1XGV4@qpB$z~<Q(I^izvWB9-lg<pVC11IA-tiZLguFjoVP1e7E{uUgexMQ ziUJsY{Pacy9dVLH#*vO<n|gJXDf;0~PM5n=+(?3=`c}B&P`9$k$bB7Au|Zy-N`>-| zrr2EnhYpL*;X`VN-?x?(8{6!&ikBXWcq_Bc43geqy|VWy+{T&)bI+XAoB=M9A){xo zYwQpof5ZWfOcjZ5i1Kad?Yp<!<g1MZ*k7Ig%%YLsDk6kiN1O~(-z(h_RlJ+l@vsp4 zvgrF5Ts@IBH}BL6{WE_6&XY*hVt9tALWDwYB5bzZ22teUyG{2CV@c;XTDUMtC9fS1 z=j5N($T4T<xIbhEbQ`Zd8dxOf_KLamE^is}7AJhlAppDeuXucNKvEFh(5mioU$heP z84AK*!%i-8wPif_^B5JG<AGcb2=-tW)=tLnDmT}^#;xysV!z+eO(p(Z+RkW+;wF1c zI6Eoy7T_X;4pL~>BxCFG|MHBUz+*R71t;A}TG2u-mfLSO_(9z7p=fDCRm8Ad92`|L zX1;pBsT1?1oj%;PP5W%CxdLzqQ`5;`DjRmv%caSF8^SW*-{9I9WzCs(|Ls4)=Ko9d zxexjc5AQFW!-p(y7X?WJd-<sm(}Cjt3K}13j-ezk81LWrY&8U<BLlk^4$NdZpve4D zfV1sqTD>V4rKh7VYgEgQfOUC$bP2Bmfid#x7-Ds2Vc!{@Jq2XUU_g%q$FH7=O)TW( zQr^)x(3TVm0GoeDodrk`X<$!LL3s@piD91Ul>xUk64CYSh_;)1{t5HdZ1Pl*lGh8M ztUXaOWk9T->9_cw;0X(W?yfFu0S{mKY!oe?kr9M9)B5)x8N@@|9DzR?tnNPBL;Pyj z`@e;w2fH`04u|SeA}Hr*C<V1kJukZDOWgkTg&E7^$vgkk2>VSPYBFyJS2-vxDRa^3 zzaz`OBJ=M_43@q;91eOc2=oepAVA005C^!W6tF0e24Uq9mb)hcFiHe^%nl&THWwT$ zkl=d=wQBER22sk+_wSOoWyoA~18+#10&1^+<94k7oq#-*hM>v2iLZmAsM6mxrMqq` zRulkv6A&Iq!1RPpq7etg8oNaR;3R(zpjhWaAg%Lh7()U;-)LY31@ix=9~Sk3&tt~y zKk``jlQfR8078b~AItu)DGtNTOOpVscMg_HhNBSV{_5Db#r8LSRLw_<Jx&)wy~JFa zCQtO{B194d%7s~ZO+(ogmV$3xcNhfr+Bw8psMu;8$=tSc-FIUFsiMolUDxNBw~kjx ztW?qE>4Ni#O7!uI?CK~~YZyn{o_=o3riqyP6R-aU^1L7S$hOb<)^)~q95U!SeAXZ> zKHOmQlBeVFk>~|>%lY)xE3xx(n<jtE1>EzKsZYFR@l-#9;$234(-1mFKf?6~bRznL z=a%VQ*5v^$?k3P6`L`4&b+DZ;ZIA_iV2n^{Pdt@@BJORMWH*>!`5!qBf)^84Vp^6< zfm3#93^W0p%PWQ)vD~{RvbcQqJ_8S>pBtqcJW>O^^8Vu$5dVX6pIKR!(5B6-p&4hT z2;t_F<l;)-kC8Pl|Mx3^Mu3+HT>-TsGW*)|=jdy+(`1K>SfmY8IQxQUE&+Gz+yL<w zH(}bZ)|KCP4g8I0Rea#~UjzV``5M6hkfB=Q2XG7oI8s^Hc6if5+a?>Vz7}Y>l5jK< zn`r{O`JIpy2FOL8-whwhOf;|uk-wCz3wWgeehHXO3Iaxz^gxoaBx%}!79b9h0%9pD z1bM%-OpK5KkErxliq|+P<@f7Ef^!NyW*q0Vc|0zJ{*rOoeGL@cQHy7t_~#8$t1{$3 z`IHv4Be*X*3|L46-USlbz_phYojGWqH*Oia!u5-+w{RUefd6eNS0a3lfWJnN56~kP zM<6Fl3q50h7|H!u1I$Qxn`?oFSf9TLW<h;*JipoXAOGDYr5TEsGXVemKCVK*3r7PU zCIF-fKxDY-O<+~=58{B7E1+m2^6Nuanp}a)AA(MTHXJBxaOd8<x;Bp%Kbe6Y8JtXz z{q2)tOZe%R)HiPzWbZPN`TdHEc1s$^e#JjnIGlpUmH5dG{X|eXcm*<`Ct^MGH;kjl zyru(TmQJG@?lMu764}ug0Im)d_oes;gq+dg>5J+D+Fq*q3vwsGt>=vyP87(IXaO92 z999nr-7c*?D{33wl!Z<;!4cC!vRTWHvr~Kc@#USt{z@-eui;so0#?o!fN187u^oY2 z<9r9rvKqVw;~vaTerD?PZEBD1EX9m3^mC+MH79GaQpz1q<lzo!=uG<pA@vuv%wf!6 zY)`$PNHJxXJjf@eU#7_96LU2&N&Z@RaI~KQ0qR3Gw!2MgzUk0dFv4S|H@9kmO00Ic zXP~@>{V7%aqYs~E{d^13o#>BA)1(IXo;ZA~I2dh$iSthkn!w@x0Sx;M0C|hwAB?#f z<Hpn-URT5!sSVedQBhA#^i6&il%KP}pO7cnWh~0LSHMNvx8~!Z3WV{cM7Cn7<k7OD zg==`mQTWbwwQ2%?O`f+SQ>2jEov0q7!SruVaoUE<wIK>INYdo(P3RRI1ihe+4M3R* zqmo}28e-p?U`&k<GxD)+NCEXEH<4zkv14t-)WSs*;jRnTy8c~De5TgaKYbQxv4bFD z1@|}2rC&*2jH>#X$hRC$!tv5~FlkY4=4>4{SUqLSdpDA#l9)Ms+q8qyZ9s1f4qc+^ zKOLh|VZ!ONv9AM#&$4i|r;q%##{4-j-O6aeP(1hCmq{3fN&DAA2Yumb`Ip0U9FdBL zO0|RRt};YUa_l8v*@+C8p<S@ou(E+#3<x;^%Qd&37a5KKh<$DS81E=iGxZ~*u_f|s zdD78&QwkT2I6L>C+8HL_L{`O>Z6~%Tz+nKMU8UiO153S#l{Rc%C!H}Gt{Nw*tYvpc zUj5$NJX(n^I~A=+(~@a7xHOQzc0C%s(z)R~;1DnVa8!?1b5(bhp(K$p_iA4bk9_YV ziin6LRB>^v<yjuW7DkJ^hm}WZkO%gGZz8c-pEu^2$M`;>OJl5>)QsCuOW)pA!w-f& z&9#E2wKAo9gFf-zFA#3Zc22>6LtK$1_CX*+(omooa5uW7Imh;f9rU{YwVIUL6X#cO z$KvIx3U;Es-BODf?XKq>k6+1HDP5}mpkq(|j03l4r#~uZKYFhw1m(&X*PT#p)Ryl> zNKmGCY5(;|O&b>8QO8G`{|u>4nc$?y`ngc$^z-qt_S!ZzXPR2ow5*QAiMdZ~#?!M5 zQ%*|Cqp@6dx-gYbg>YF13rT8Jz3HbctuF1iiCNmk)>mTiWPt;~`Nwe&E|wBwz1uPc zFdCu!qn&vE5u6mm25;O&3n~x&_{Sl(7Owk0!dNvsXgngdu`o<2k}ITYFnEIaO2?)K z>FoNElz3#-sa09#VTZ;1Mwg#S{o;%_lLoJxI3P}$B{M<EOaJ^+GdVVzN#l;7-J>W} zscoMqKh3O{{ioz%t?KDo)eV;wm`W!90JXhgRGPpcwY6k}R{MAm+nrYJgtyV268l=_ zeOjwa>5g~0^w_S&z111Vd7?m}q21=U(w?x0*AIR`ez!Q)i>{8WA9&AVt><ES@59O$ zVHq1n&Bt-*g{qifj5sPb%AaEqaT#l=5-mggxx1t_$K2F}c0$yvp_c#ialEneGP~E1 zDFwHcj{E)e>@-Kr2@&<MMmGz8Zd4wS6CjDh$s{bhR+`2hr7Rn)jWzb*j>s0dZafoy zA|{ng^Cp=_&-x+vxYnm4KT+;S;|ca6$gM1?7*9P(=`r_U`jJJjU1`W9l&Q%VeKNvP z{r17I=y9oNw8b=u*Vt2#Mg8}J!!Rbs=N}v=3}1V`ub>SJlY<L};RVm&#WI&$$k2%m z;BZl9@eUeqedF0ox`^J-_ttBZ_sojK3bjlF>J!;a5^X5&DUC<~T;2ztl6kwY^L0M6 zd^r3u(W{Dc+JAO(BHLiSx;QySxfFs2o(Z($ZBNnf(>W=tnfR|&*|mLUR=YFl?h~aU zoC2=x@KZkZ?Em?)*7N|xC+Q{POm8>ZPLnA@vMnX;C`SC$q4FlTulSu>7Sot{t4E@I z8a@8s4`qTRG$_%~H!U1uvCfx^a%R`O4`r!iHB{%M@Kf>I-zpW}7`~V4nLy{q$@C99 zwWKWdERNg4xv}e=iFfyN8K~}WI(*gM=!Jv*97MT1Moo+-xVSN=QEp6R#uC>=o@wV* z22S~T8w=;jQG|F>&3UD7XmxOpxkv4+JzGh%A@0k2g|j|;|Dp+;3z@=Nw&U+$Q%~iW zgHn$4y|y_<o}@5x>Ui6hM2#v_zOJ@Znj7P7cU}!-51a&7lx`EA@?l|0!-4nxMH_}V z#*0}Tg$(LLP$Wr;JV?&h^FkXcJ8CmyN<pufmGRLIi-TB!l5+GZa3gx-vw3JP95P<b zuLv30#<5S*aN4LnFfA^zaLMa|mUq4+4Jy%Wun{71&ivN&aG)*^q`Fxa5;KpApPyq& z9r^k=zWkIn1gso*Zvc3{lc!jq>AW=<jqlnA11Zu)uCGLwa=A}=h}UxIHKr7k#;Pp8 zVy)$=4D9f)(*8E5oV@?HsTBeB?;e4P>fiEmfHd*1u0LoyXpgz}q!wt{Dld^f_vYip zk7I}>Mj!|<-vx@4shNMiB|!f2MB_zh)X64&F$jdY1aM!l1%84OEj=cggHE;sl7xDN z1JyuZs$b~|7P?|zO+fwK#{~c2F2IR7U^5LkFE2NAIrx{DU^kHP`t8A3<L?aow*+Ey z7P_WpI7VRb@CW4hC6IxGZjBF4{(dudVMq%YN!%jj_!8Hdzaak2_*Vm+^Y1h-7_(3V zq1XXP5x`Uom78*Hh&`6KYk(Ujq2`rmze2G91N=j8$j@y+FW(`wWKj?J>)+~fYlQH~ zjt0>t)l0RHg}C)uOk5O^>Hq{N1xj@=V5EU*INroY;2HE^PVKLx03N!^f#5L?e6)^e zs}MZkSJi7u&?*m-5f)qfUPlj->$jY=`v~n}n8DXyBUptZDJP+;<Ir8802vKJhdUtl zHxNfZp<N9d+=R3$WBfAU=OWws5P_$i5yAYe>piGn<yC_$=pYgxhO6PJ!%@HG<gO#| zl+7e~DEZlmGrIW9o>)eW)ztQTl7)7O^2}Q-s*E=W4aWHb7|Ki$@OoLmKCWIk{s}of z`GtL1jdyV;rDtalOi4oo!D^Kuq+O7GdVtmFfnkqyh2p4a77+BC2Ltdi6n`d;)zbhP zFLMz<+`Pn__VJHzE}Vv+m4>|-$jJG+^2AVVB-e-8SM=M&IT1Oa_27RQcFO31nxaxu ztTrNu{cgs{T^ASGH^6p60?nwaXrQ_IGXN1%&O6UPV20v2Uee<5pwoi|q*_8ps^~X0 zXR={I)})8aWxZ^K)oyzHvA95B!ORT)CI0rG2fp;jia05v0%+(a?g;c)6WraK$;a`k zoMZL>su!Qz3EY3a<$VVj%kLgAYv=+Spdv^_N75G909U@J0(5_VZ#=N?@TJ&EMPOS0 zORVJqQ|!4_fSU<wRSxk@s*Q8(t!S%qYtP<{>p|5xoOA0T10>x3-fMtR)!(n{0ltr) zacxS+D91$9r2>W*ZtAm4t1b8KVduX9e9qSAy5hNu8sDZ7L$@n)R)z(Ax%zAI%|HAs zc~jQp4k!m6F6`FsQC)C9x6=THs=s$#$)gB@^=gM1X9^>rOLASvH-4AA>P-{rYC^2> z&sZ!cP!567`OBR(;;GhBRi|cpZ5E~Pn;QwN-X^6XJ6unEL8@8>R6Xv!S$@bv{0xOB z1&(7qfTQ>U1Ds6&67Zu#L;Y1x?dKef=QCDkv3_5UPC{Y@(>D+Ol2fP0Vb>n`x4TO{ zdkvCxt-HhY{v@-TNIM`wmb{Z`Zb_DD<@*{=vweJd1b^^pk!I9Eo-=K)<rD<uL};@T zv@us+;Us-?XEZ+BXG)h<k8wEEKdldSXO4B|leT`NC+RAp-L;`9_$?mbt67pjLS(72 z^4ZvdBjwSZYBIL2X_G-d3(@)^)&2lij>1Uow<~WLU6;PDa83ljI-6@${O0eAfxd3y zSX9C(HMGD$5mgS1Vzu~5zsC1){?G9{KDZ+G;E(Zskr`4FaWezY*fle1Iw@^JJ0O?w zfYIZjAKE)y1WNL~8onA_?dYyIDzNpmF@94|O+&l#rm|2`nV%ov4j~9lreU8q+eW#b zl7~uqWVKCsu{7mg)h}6)iX84s($5aG_Ulwu_Hscq1nL}E<tYlHQ+=MOHd!t9bE$hr zl~<z^*L89h>hGvirgO1pb8REPa;{aF?8dZkq#TBT$PqT6>+6$J1LdF1)N;+S13Ri@ zV#9MuB|Wch)uqcMv-2nv&U?>TIrc^AFdn*LNl>MXfk5s4hV0E*pSII4ne^z%L;mhA zGe)G|S$}j)Q*E-4#_i|}!nqaCNxY&eZ!*rRgizgaWSY**Lr=CDr$kq20NuYGQZWgi z?HFi7J>Z0$lNxR*FLMsPQ_~M8Cxkx=o6gIT&BfKlbF`^HpZ&zP?+q%;+t$L=fTn9v z-hhYGsnq8h0ns_BQ{yq`pHm`s@NLeT(W-+w6UH=~3{}Nv{F6zypWL2lTH#7N61cS* z1JQfNx_wn)yK&#_bFQ~7PS_QzmtH;LC562riaHVQ(Ej0HQsol=WvG3u00=|vyQiNO zwo@q5N<7LiZfU31PtTSkSMhMri(%EwP?;^7hS~^XxhBFF$*0M+F|}JiF`1iRPV!zi z@!R{07c&d+ds=6j85owwtjITc89n-LNcW14Z!c%2osHN9>ZmbOi87jy5&wi;ZIflh zKx1V|u@m<VI>lhus=Mol1+__LOkPuDv{whuLM<C>lIK?`71k=4%hhvD&|F=hDqR>= zAkW&#Lfg8G-jDm2N0lqFNk}lMn)TD^+@PbEajCYH>+J6g3HeVLZ%c*lF{R}vKB=6; zCSXVo=`pbG!6_XiXloJK&-DO3YmCox03J7?Cj;>>O5y>Osa#VF0PH2F#t%r_?clE; zf;x?8j9eV{V_5PclEtrK4(?Yo=vs11?9C^Y;U~1xvv>2y8(pKCX9iQn5^N4xy!9p1 z%MJOolU{z%O%|epan)$HbxAD0e3w`x<x^OmBx}^2ut`}!vuLFM*_%ZQ0|8u-o(Fcf z+&|058Jud`wostuW82f<25MM8blVAIWFy(535lP!>P3YOJ0VC`*1nA{(eIClM{K7b z#2t5bZ+*=U>;+Y5yaI~kCb7XSWY{9~$tv<^a?v9AI!<Nu;4`d!Qv5DSP2K2@0NayJ zkqQzmr%RQ`@eiv7l&3&Crz%+Rq0d=<lO3v*5ZWrqs5>sp$^UT_2SGtDn!lF;+c|=h zgs1JrKN$l3=(i()7`$cl+WqXdbrMv=;8g9G!v$u9O(ZkzVpj&LlnN`ZJ|r^7()|S8 zT&CrnHT#9%vi?*`<FF1nbtz7DNxnWJCHiZ()Wgi1LSM`3{T;MZ4Gjzya(fbgw18}O zdPVPu9P_xhskQFg7UM1HJF5zo-aol4%#&X<S-PDStfe}o?UATwFOkc`RG!W&(N^Jc zuP%%y&d0vare7BHW1{|42*1E`w+X9?CX^d(VfMM)-QEx9eEk{wd`4lcnzK0^9+K_o z^qwdynZ%B)qr9JxyC$j&|IBI(?H$#mlZ(3=E03*3pL7PYtxHv9(u_Oq9JrIUzzbRh z;{`wNf2^ULp5sdKh^4%wTX*fcR{4Mfj2Uc&xQ_F{tZr?ip@&Xjx)P6VJsULiRj~~9 z3!MiIaUb8{=bzWTrd4_)NlJk~))p~Q%h@6H4)rNLq&Uk1tluBbLECO(v;%lHM%!H- zYGK!KjEib!BFCtz%&rMCp-J85`u$J7TeoZjhYDWs@4d^vOT)X6JlZx9l&fzaeMcc3 zxy_h3t?A#-oyV)|rdGh++PAK^5}k*Y^=q5bx0Hg+>~4snlNQZErmh7%)q3*u1^Q0c zc`47LH+1u^=`N~gaA;Glbpo}wD#doV+#xu!3qdYJyhy@q*=7z#KQH!#Ug9+&X$06Z zjPJARV!roenhL3bl7T0mzLxnNLK#<O^SmFM&eZtP`5UQ=5Ui^o`sh(p&^*@Lc*I|a zZbIPp)rxkuhfHKt%6v~+<CU4?UNaJt+#19}9Z#9RX2VD~AVeaA*L=E_$9J4$Z`-nP zy_?@aLr}_wb8{-@X4>?r%eim7eJQP{hoiC#*VdF^m9;UBB~5ILCS>BsX*H45mZX5} zg~&tY5v_84X(LiNXaFPa>-LSd$By0bM)&;Qix!Fcv0P=Th<oNZOWJJbRAO<W{(i60 zT@H_>X~jW{HB0Pdn9y$FNG{*eWqiE>MMUmZ`7WQZXR91M)OkUA_L?6H^A~SxQ*+B} zkV&2zYssJ>uR+X#0E4{_W{QnQ_4~D*z^fpDYq@g4JjC2?;$__!KPioI!$a<?75VW) z<=Qa<@$wHtD7>Kzz>y+U#pK4e?Y^Eiz_F(;+M_j4Q&p;lJE);8{*tlzM-O5&gmyea z{5-0kDAO<8zW3?_3SkTSm5<8Zk)aUp9E_CWd*_gPHlLES-f~5^air?dOjs);Ph9BJ z*FY8%UW=Z2?R?74{mc9&c*?Xk8W=?r^^b)xbLzKk;`ochqP~M6O~RH^wvJF&c1@1$ z+C*x)NM8Xa_OPydg*Qz4mGAAY7@DTgrwnx)<S7WNCJ9;-G3R9Qa+db9C&F#_&8qE6 zoO#21D&N!<f&1?H1~d4^a3+H&D@i#C$r(Hf2AFy+?)WLG*Kj<lq3D!i>7&}H8XK3| zkto)PkQKtD;^fgpU1<P)klB_&JsV}4J1(+0c+>9Pz_a>y>ip)jmD_V1A8h?+-bXsu zRcICo9W#f%D#i;qAZ~av+ml~6o85rF@Z<%DPKxh3mGeQZ!ndPmH)@1ah*$G#lC=vb zpQU`$4khUT2nT@-K8M{X^01v}eh&RCbZ`&q$wf1%>AhW*`cx$W3q-w~9bxm*ysm}z z%#+)h;`+ATcS-_B&1o@Mba%`_DT8f;Sy%aCH0bp5jH%)WmLHGHHu$NwVx{1nm3%7C zqNhnZy_C|G=~qkRt@mN&c`E78QDgN5ZGB%e;Iv}+Meo%HgM<~kV<Ql`N(>ue2)upl z7=2Lq%-&7zMuy5rCM`X^)JU*HS5;uS{DiJO>N&c4QJhGdA~u6OZ2lfL3v=ZO_C8v5 zv7`VT?(d%8l7Z~0X0}jbm`82wDQ&esfU|L5-Xv#Dd911#xUquZf;#R}_?)7gx50~? z7@Ed_{0x$g)Z{p8qQhptzy`-E@ye~rHx9?Sb+(qXkB;M|nc}~FGm72S%j;fv1Gx;g z9Sk1)<gXgPfQ*iMsb7uC7jZpo^do+8IYlH_GaK;!9dC+PLeklOkSUvb0EU5Ynrzm< zDEy7=P|<;ECOVOww7vNo38eRzP|qo!v~v;7@cG_%*o&oH8#*bWtZ3uWj(1K=lCN17 zu<hkwl$aKaP?HDy&I26OAsN9WbPOZ0dI`yepZ*%W2rye=VxeC8$5~5~wrd{aT)o8H zwb#OX@2G|YfJ7DOlz{=D7E$y|uAHL;sCE_t7-}3Kop0us_L9RT&#1{mWV$EHZ=_w6 zVV>%8AC>)7`X|Oz?S^c?5%bV>(`^Dzpuat74YH4g?v6r(^~QJkn-uNNU^&VwDom2v z*KpZv1>N~2_SHCmiF+GhSC(8kjvzRXc!q%@X)*wrWs3lkz5&hw;Q32Niz^_8opp4_ zEQm>sgd|*C<6eJREue<~fjD)V)c%kMz5@C4*MKT*&iqWTwWFJ{a$LOV-goP;FU<GV z+&pEIfJ;$zKEZ07UDYH){4c2YAK)*RYR&#)T4mhikt3cu+msM61NnHp@f_OuC-RwW zM&pa}=e|PiE>`JC`h4%XtegJ!jlJNxuQU^g14i-RW*`J^;B%P2x@u0l`%y)#>e$NO zYNYhgoflT|l1v_~HN3w){QzM1zg)olgd-P*zYSu$!4b{2Hx)h;aw+}kVmTm^^&4_d z)V_f(Q3LrBpx@uY;*})m+|?Nz=*iMjX4r-`owex8zStgkX~Qh<e6GAm(EP`w167)H zIRS&)@&q0YopXqAexi_At~8z=c5620z6<od-EO?X=PqIFAB`S=T!X$yGwZ2bi<*vh znBt`eyDrG`ce*Z;8}c6GFjVX@!E69fB$YEJ&^U*8|A~Ez>oJ#;ppG2D@LoHc=<H|} zisWan0437Y&Oc9tr~!}`dRJX~=AVZT;syE>uJ7Vymw`<ijoXl_cg?YnSKm|2`_?z0 zQWo_iY7|`V2|c+Cq)!6-3G~k?1NT8Kfb`7)84Q1xy6ypg)b&+8WMXGWV(IaPMQ?(F zBdQCz@_P8`5%3zvl`|X_)X@%fK=~Gr2l7Auz$X50P2h4Aqe+H_wz#nexr{sk<>ST> z#kxY!_XflnA#jio&tLHxC<7{A`!IY%?6M*3_b+Oi?yl#|sM6%O&1LKr-J4eGZYFRV z)`Qkm#hws91dbUIXvSFa?9xZzQ{KE1_6JgXza0P?z*JK9hZx1&vN|g_Q@Q=8mMy%r zr?dt@>hA@hBD^(3WIvAf#)W{l6QC-2XOY0M9TJ0{9@+yyz_CQ6S#jGqitJLL5sOt( zmDOSI$LpUWiq5KYphGI;r&#Xaqb69m0qvn##RF(w%hb#hu-dZp``mA5<IPmj^ImEA zHJ|%;1JU0fZ+o#?)e<O5l>JMo%#-U-0JteV0E+j!Qw97U8S1?G%Ly7E^sI>9cexPU zw<WCn1l-pCo>=hjp%WONcTe5|%9Vf5id&@}L-x0wRR0bdb_)6>O(H3t!E@h}eSQ|M z82wJv7)?LVerA)`?%?Um<fce>J?00sY!E<uIXB7t1{}W<b7Y7!cgV6C=x_o!^$)qh zyFZG_Z%mtRyi7A&N6QRTX|jiVUwp6{_kf;C54L3n!N0BqZqAj8=dR)-+2HRyO);2M znI*x2T`D`$%U7J|n^*k3$<&eGlYGJcT$YA9@9%Zs73?H!XuA73S-w@l0tHHQa*aa0 zlAQj}!zEhyEi#KR0{>V5UG<6h+6pLm$pm=jIgWVV*H9VVD#0zuTK89Z3#q3)oE6KR ztM4TM2@}K@Us*Z|+0GmJN$6SdXh?B6X@PrMIIc@Aa12QQ5I6CctU=282g5{FMPmj# z%q0+GB6brVuC6cM%@_+Km3hOrZJvmc_oh4YXhg#_QUv06MsUt2paGbQfA@wgIm&iU z&{;c5bZ*)no?SS3<h{95U^nhJ*%>?4;j_>s4x^|Fc$TIGds16#BK>tH(u1G$^W%#S zUYF#1Wp(5FS=QMdbIPVHe}Gye7lIM={4#8^pKhU@5Kz~ApOg*;2S(LsR%JN<$1h6I z0M8FC<F`G0a(EePmTx`eau$ziqHqp8G3$=<$Z3e#GH$NixJOLmek<y+ZjD^Z?TbHW zA9UGoLH4NA@Xf&b59O51Hg;SWMi$>^xXv4YC%-UpD|N{=X13M^A!3aX?^p(T;C0Ze zU0_NH#!$@Aq3#@yp|Mk<gQjVPRwwd)dPX9%qKcYsu2!w~O|AHhq)4}EAD>n~j9fbl z5xOf0bI~v>#Gx^bb0%MrPB;0Ez-==mhth4m6uW!dAqua*J-;~}*ast#rNzEQg?222 z%W{vy{VDuV&4g{W4NgS`4rKuqlZG`6#ll%p--d-a8jZTyUF$<Ml`oZ3X0k>c+WU-m z{B-ejneR)q)b8CY_#B^Z^L1C<*j-*)`sa?nH>uBdXZpP^@FoY3OY-e5&BU~Ve(t_P zI9;E*o4aQE)9mel?ByV**;4T&z(U#*n}rU=UxO_|n0&mE(8B{5y2!an+7223hgxDC zw1C}F6OZc=mDGN0cuCftEo|vskJqJE8;JhdXM|;GD5$DCTn3EMSp;>IUVz{pV6KGS z9)=%iT-Kn0=lJ+KrDxTt+C5edWRX|S^~)#iQm!fPE1U5Rbo>nMu7pl@ES%gc>{Ms$ zda_R(-G)MsS*m;Fw?(=-?MG23_|Nu23L}(1kE%(7M$_dECQ#}Oi>a8_rSH}<0s@tX z(e-1A0Zq&LcgCZQJ;u%L<D94xqHJuwB_kAl*bZNv0XGK={`)fIr-rzTBa3Ly^7_UE z6sWz3N{#2Tm$<m_Y>rk}a_f$Oi@DEs3a?1;iuC(E1R2<VcM5u_b@suZe=!*IV8S1Q zj%`m^&lD&hI(T#RGC8K=n-kyTZG238M=$e6$H=b!+g|<~^<J{#@=`6_)^&y2(f&09 zZc!V4QUmwWVuhx4HzekTVWK%D(+<fKP+o)eSoODhds{KOMY7f$GFC-e@#zJU=E7M& zBljMCiuC!MxT)f(ayM6<`FSvM;dKiKniW4L%Z|}m!1)He-0kcwTvN_}kRl#iCJ^>K zPWhDN;U)b*-I2bUwY?lSUw;sI^e+M@XArQmk*M7;7P_Hg92s(^QKISqQ<IHs>^I+4 zRrOQIeBcPLz5QG~d5=AwD)NO;G9@lwlt-1M2+lKNLME`HYRgqGF8t7GnNm6In$=SY zfd_=Hs{{rGuP}ZW)IIdMh{UfsPWdS{KI~GR>Xfp-7i6_4QDVft=wSS0J@;Uw;QexC zR);Usy=v+tsf6PCg4TMK9M(LATmb`Fl|&?ua2~y%yo7F^zQ;UEHG1*^CT07HKp-j3 z7$cTd_#I1P7HW!(^ZhK4eJM3~({7T+Ygc+EQrRNr&SHJc#CWzI1^2Pu3MEjHi~Nhg z84{YwhRJ&iIIC-P84IKVv20X@gDlS&j>GSIeU91toVzBo#=Xz?zD2BhJxkIyOkO4_ z3SKZTE%s-{YM?+jzb*zqk)ff^)df?=j^_LFZ%hj4E%y?uii3M8aBsPSk6*eP`~+Rb z${93|it?MZr8<regq4*<ySiF3Hopo>xDovR=8Z?{b9FNbQ3fMF{Jnb62OC<YDFd#x z4acaQG>s2t3d2!p_7m~3UD@8;Fpdb!Uj%R6dxrBekmY&>ZNVz82A>MGGFhn?!w)^R zqqx+ehN&M5HMQEhL=x==lLJS;5e<Y}VC)yJikiubK&X_t!dn>T@`7x9w|8@D8Y&wc z{6PFHN~oF)8=bo`Z1iEb-qFT+i)IkEL5Tus{Y9`@08}NPH?f_LjbdQdhcNhJ%&^Jx zhttYVr5Yb@Mt+6O$@z0!BawGt*XoJ99o?)l*kQaJJu=@~&}SuYeOagJS;*Df6<68D z^g*#Q{K(z#nm8k$MWvAAr?a=-m8S67f1i(J_cLX4H0!%Q@xA_vZMQX)rQ!+DHFQW_ zkjLTCoW5u^U(+o9Ex}E>mR9_Zk$dB_NK9!Po(~S-0OzOWW2TlohEqfEkkrzvqowK@ z%G!qhB1IGF4t3+s6b}_t;P!5Zb>R{g{)AXIwE6xQDba=4rrXG7Ig^%nAQMefLrZ&i zp(TR7PQihZSgtOH@%~{=+P0Sh1N%Ex+D_}hiN6R40~vkV)hi>lhpXn~jFbcfo7j*A z9%C9cgN|Y!Ts>Bx$r7KY_`IIq5sDHOO>;=Q%QFdJH5=&LKtVMAHL}^gRqK6|U{OuM zM|0!3L1#Z}ukUlLW^J3U17m$3uEBWtV&^!=F*dDav>mCC?;?P!z-EJ4`#Q#M@@1-- ze7@<tVK@J5k)yD^)@-=Wx90Snrw}3?@8pQLwd9K_*8<$=5{tTW=XTYZlD(U!i|!cZ z*~!bVO>0lAwPL@v9tS#xd~-1@)-88gamqEmo2RB?pG%YYEUcqfD~3hWCCFlfPfb!! zk8K;_xi8qsFQ_-s#0Ib`K1UWSJ`+p9T#-Ygt0%YM&d4$G9*fkgj$8^9y`Tj471J7v zOE0wHtbtnop6JinKfu#ql=JIqzx>t4;TG0SF>#%?j+}ToU-lP$DkTqjl#UgLJWA&g zm+}2jG8|)$T?<Q?Ib{9Bvv>kEsOi%;tH|yYq-6QnqCN1(hTc)WMaL3s5Hd50zuJ1G zt&|X(cNmQ&#|UbVqsmmH9Xc66;r(^#U8I#}a}Ql9J6R~iYTpgN(PQUjyQdWU71JFq zNlw)k10vzFRjZnH^y|7|T<z(3b^Y7ONH1u_U+^FWeHtdbur)nC&RyS?%v{&2m`t_) zEQ{;qol(7lp=<%8@zl?g97rO%_WhOrF#@K>a2>d&ESCP%U)Tj7lz24=QpFW@UtG7@ zzAWbWf5l{rYYvR(gH9s*Ni+l(4CtzYR(N911%+@BnaN--q<SFt=0p0hd|!p(^cbPQ z#0#TZ|0(Kc#falxm4N3UXIBlF&7M~W*yP)}8-1Ts<SV({v-ni``1Owf-gJB?kQi8F z1fQLXTrmFASI7I@*B2CvG^@;?FothgKaSC}@p^Rem7DU%>s|ljxT!AK|I6Iotn_yj zT%uOxXjsmso>q$67rCGxQF$)#KYtCA=bd!M$-p|J+b?d{)HjE-$8Z=Zx?FoFc{%rd z^jl9(4U|(~I)8$$u{J=q;cWOfn$U$-Q#``jJAb3X+|Wd3Si-DAp<XALVDEk>fz_}+ z^f#zGkF~`A!NrY4e)u%<f@MJ`&T+{ulIMw6{N2mGC!oHnKcGf2Idi~Q2mq0`s(*tZ zUfxbHM%)k#(ECSZD&}nx_8kZAr3a8NKVbSvZF6qDhtJKzMSxENUE<|B^MjocJLH$x zwBJ?Bg)|T30Sg`kEclT6!)~zLvHt4sN&QHocOD_9ojNE1ATAMfgw`{2I~>&-`CM66 zubk`B$QE7EO-lTQ<;yQNs?oXmK8Iro)Xtmc)SXE`8FQ?@D&WLtt+e>TXztys!mI2s z`*p-`G)16h2jI#$=r4b44#jh?38?>8xo%YXZIAhY>KFBNQ|30157GM<=H3LTvghBu zy0-E!E~*Q3QW&?HQ}W9&^61K$J9q$)><0dK4q!9*n?mal-zF7JS6`pw;}V>6!L&aw ze@(FT>mM7D3&&(802)3c^YZNS@y5#mOyXT2tzecxK+U{>d#MTt?WG+v#AgGEs#s;{ zW&)J$0TVO8R3Y-N0o?d@L4Zky0g>4@0_WEaSYqoEocyv>g#S&rtp&hpkNqmXk)hxL z(K!L@5|!WXm_wH{eo<d00U_@b@{`3gH4FV;qTc`YTJyqr1?$#x_Lu}7x`24Lwa<Uk zZA$^JB$oXs#9t0wizhBXqh`8ZT1*d!sLmPP_S^K-uWD$nZ?1jUH*z(b{L-+jl_zoI zb<HA6bo+1iZs4Bjx~veE11PX}mZKqIRjNf$$~DC0tt#nA60sQHTVsgIPnF-V-BX;B zCQanKs%_v+aQuFY_gi`0lmA25dxkZ&cHP1#DoB;yL8VF+=|!R<T|jy#0#X73(j-VA zN|i2MsY-7FrAm!->Cz?Cgx(WC2omC1``OQRw)=gr^L_ua0?A!g$sBWzIR?c7!n}9H zG=G)Qdr&-<mQ|C*e82N^9S-_K#CGh3?Z|v{9WtmKGV^7t=>Uif2vRr?35L4e;s}^l z0e*p&;RhHG*1&OPCAs=%)V1X!`<{Q7J<)PE*Gh4QB&4sBt_9d4&J;FK;C9dWHg0?* z9259{#~#P%&wgHh`usdzof)W4@g+U9ig9p0hA<9<rxu^4!18;Py&OvM3Hr_0^$3_; z>5x;-g`2}G(h>bvEvGg)<XAWy-sp?IOzC63?;QUyRth7#<p&S@)w|1-XMsOi=1f9u znJwI|&(S>Ma`ke91P0t~fxE<twltBiN$x5!3?=W^1R&0%-n2LUCNYdHD|=opuEE6Z z%>7clf7oo*E#0cpG<mYm>KBV7x_{CWe62Ntg+Y~8uVACcq;$-0>q)6;Qgqhp4rYqG z!1Y0vOXm*_lwr13pn`8M^=}f_^2IkmeaUY+LWKm%42X*^a7fyK@9q-wq*ofEovNiy zMP3x{g-Ko2_7pN+U`^4W(j3|X*Gz{5OAw^-CwVYs95_CI?1+aI`WkVht7?fY#W^B2 zYvK=%ZOC?~E0HtPV(zd*4du5|bK;ro0Tp787`%vlSh7xiYUsZ8v<f}6K?BJ7T(=Ym z_xZTBz^j@6TJZ2^jKcK^uK6DUxM~gFD9Z;JLE0OD))TxsayJ=kc3g6v{d0tD8(CwE zSkC4#n`jxKhdSv~T5n;kn(jO(7jAcxe%9ufti>4V#uYtlkP<!}Q~j)l?Y`N-bGmFn za&@y}7XBef>CnKO&q?ZhUZ%SYn+)#(oW`4mCzlR$>#4GWsI6H<yTL~=YP3|@Pw_C7 z;(NK(%tQ{eiJ%UhO(&Cj7SCPn+AVn>yW+>^?^P}Xn767Ih}yw4DvbC_YD?O%lMI;x zZZ2GnH6>+@k8DB1wV|Mklr@U8_Z<`;aT}~@Z{Pglwdw~%Q!N^2AiNHSEF7qs!6U%f ziaIXYJ%E;vxe`;3kJ?+Z;U-^dhKwC)+Ix#Vs=#%1nE3foY_Dnwz6%~o1JQvTJ>TRA z0kB>l#RpTwn#KJ*<GQFH%^t#Wu490cNl5lQe;){yrBmv9+9Zcq?HWBji@5o=sth`P z%#2q9=uPc9%Cy*ou4`K=LfD0D?Dm<u9p<hHYGqLeUaHTy^@L8;@p6`=<3%Yx$@0_p zFF<i)=r+dkH|EiwiiLt~Wu%J=hxpYg5G%VZf(Csv3kJzC?qWRK%AQN>k&UgeV7oU1 zB}VPT#kI%3Nld~%8~KTh#~G)TbncqCN+FD9AK=OjrHY-cKH>+kxjH!Ht3sUq4)W{{ zG`a^x$@Ku*VuW$`^F5bUi=dMRT%~KLliG#zMco-S{dL%$7&oi+5PLynPWa?yR%Pll z{U2_M)FaWp&Qrl$i<?uQ&1YSwyfjT+B2nDVX@2VQkINX}g=!n~st@j?NRR8Mk#=CJ zEuduCNgEq_{Hiu-m^i%s0LR_n=Y<Kns5SHC%CdR9!cwzwBa37vWK84@YHfz}-Nc2^ zB_2*--_-tsXg_*8K;#6bGmcG5)5!cEo0g2+cW{*-#ow3AY%^c`pu+z-n=jgmmm%CG zV_|BeV3QBta&Jov?-o*;tifbNs~*qot%Djm&`(_$Npn}4w;VNyO&d#UnN9_7oT1aW zE2Ze(KYizF{&HeN@y=>ed3i=U|K)+Z93Mwy)TI$}f<}p@<@so`Xk}eboCGGavz5iV z5u5v3MQ8wxP`WoEEy-M5VgBRIZk^JG2Vq~}q1D=#9|Kossbk9w*4z`Pv5R3XH*lb3 zmN=Lc_7Fo|SQXJCwiG0AWV3Zeq!cqLk+$}1uEj7<jqzG1H(qw%L403<1QoFO;|wjh zE44hUE44(HfOM~7#!H!xBj61?%Ait+VRvAq<(Am-EaJYzj*NWxwvLZjr`$Vd7pv!e zHw|oqu%t`s<!9^=B%@3f5A4nqOb4r@i|@vWP=h-a_o95Hf2n73<~m1$L#{X_n0!8y zG_Pb-Z8T)g5L>X05-fg)1(6%{=uqlVULBb?Scyx4d^xM*ELtk-w=TQYF1uxdl!^^V zh{S;Nf&9By_p+;<OHbCuSV8INuLfa+V(P8olpDLwS6d#IG#>gqxLxYEBVyuJ$f?&G z;pZ9knDBTqm>XX`es9vZRlt4(GeSP(=PMWimPCB5j%Tyr>v-m~F8w6`+NlVaJ>dz^ zg&>Bl*Q^ws;?kb_O`<oEKX$om400mnCfo4hcyZ=X&4)h5{Kp)b+?_8E<Jcb*-d=AQ z6(=&_PcY8WZDNq76k9GZ-n`lzY6@`#yb~a4>@PB(VP|UZ&?*itphU|YL}Q~ztHU#l zt5_%ebSaNNP0L8c@i3$tG{m3Xw_!l*hware2Z=m>TjB3L&)-x0tbY9NQDSR>T9}IC zyA{&smx3z@Txg0qg&aCT)(#`BN!!DklxJl#w&QwQ-W@|F^Fll^_5^WkJ_9CB+s~Wg z2rDgQl>O3p%PgTLYf{_uy_QL)@8@f!hOOF05!`7kw1za-DhvCzz}JZUcoDSY&-%J$ zPZkJs4qfA?)X1nbz~K4T%Qxd<rLP&2*Y0zUaFo*z(It4S$11C^<FoUi=^YE#aEMwv z>0Gv$Qc)R!wuXae`SENX4pw<jsgh+{?y&L3IhsF>Hon7Tz$@32LyLFMBXCSBb6`W! z8j&qZg|t-jTb6UODx7s;7JVxPpJ!Swf`oK|4k)YaolhT4)y^K>iKoQS?v$58EJq@U z%rFvco|*&qdzs4oWu08vdFg=bNy87V(&`SDCsq#%;*D#Q-{Mq72MzVJ$Fa$sWq5h* zHoCFa$z{WG&)STXjD&8E1)`1>GJ7e3RQb-xb91UI0Z}<*EN`;)AbL{C`RduiIYfc0 zJ!#xNIU=Nr`m+<}G2g=#jpzN@bJEcx%wT9}7YZD)j#aNJiu2TJoA8a<Ro%gGlpwgf z1xYldz7=pipz=_oB4y$uv78QRF+u0PF-28=MguAb2wn}7Gxes=TE|*|sH^++@cO+h z^}T{`(GE}adS93tthR|ywu!kAuVX<SxiO}{SVH#KzE>X2da@8yGS+l-f>gE*#&-FD zhIBt_$L9z2spQ#{V=_vkDIuk9=po=2oC>Pae}*230in6D2?@`hG-BIAm&tRE$(n{* z$2RM66*#>Ci9Wua^!x6a&O>bn<j#jUZgT9i+cX8nr+Z1O$tmp3%}wsb{gwG1Nizq< ztYES)lyYCyjX#aXSsOds#+I0tMt@YL)P}yB%y#{hl`q_q!fPv?Z-hEfWzzF4#RxCC z3<N$r&ktsBvv22}UJD7*KHGUwKmKE&Wl;6@0}~5%6Rlydt^1g^TL47)0B;AkU4$Sn zw&<LJU>Dnf`@6hrL8Kb_U8dB-cedQkoq2K;vB&2itnTzawCUmJRnjYov*e$Lc6k~W za&eK}a0Y&S<WgX*TIi$di5A_`A0uvzDC6DY>kS!7e!^SM&KWX}hGkC-KajuU=?0-7 ziEXm@#QdOszX1&5t+&d!gt8Yn2Ui@CCDWO5`wOA1097`RR=6cEy_f7&OfBYSvtZg< z5#0V3(7?HoKsP>8-TyAZjy<_lhuRi0EE#U0o>_u^K=F7jEDH`TG!Pm{ZU44Zk{5j{ z_3PClR${U7m*CIJh{pYk=V!TjaLWxBl8Rh5Ahzd(Px}$o>&gXt;0I(pKj-0zA81Sg zgL_IMD^O9~MNT4*7;NIa7XCaUVY*TXV4c~7UnhY3{KU^ckG_*p17!3IHot<}k18)V zADxA6-lGKGA*1`lncdXy4~l&WNo8lp;=zSb;$@&ml6`sm6Sjfy>Iq;{3ExnEB`pNN zoHb?7KX~+$HUD;P|8TL17C@N;(*#mLrLr>k&!Z1CA;4m&64-&I-T-Z*;YZAsmQA_; zI($X(k2m{d?!S2UuaqbNJS4J(JfH;P<0=T~h{5`<KYJA+WDmKG(m%g6O?!`PzT%CT z!{y#zpBGWNYd{_LF3Vvh^B?tBlKqx%fF@oZ(XZESW8M7AjjLDm$eFa8ZAfx=+&ti` zZ$HpT3?vf+8df#Z1qp|q{mq12BX#}K4^+sjZ!_*hUgz3v|238Vo`-M*9&Q8!u1Apn zDC&{;FFb`Gj=~k!VXl<(_a1w2TWpTJ?5s@xx)P&+g|C(njV}zHdc#L#2_*+BfHRi+ zsTn+Z%cbw9^o3z4A7jqa7nH1ot<tpWe`j3*=1g)IJAkkL$5-|Le*F**LYvQ|n!Hv; znrpeTZPq^LrVJkuAf{YMU+w!%qC9($|M&E5i29}Zf)n4#IM6G8Q|<#dNI-lE4mOd0 z&%6x(DmiZsn8(0>gzjn11`~)cCDtD`CsG%DkpE3$JbxbdJoOKHJE?LbXgxF7ILA8o za0n^9e-Nb0rc(4uo>pA{bZs%!|HZ-e*B87_$l$KYf)mr1fnqQZJ-iL@R`(D7dta3Q zyX{{`@3Hu;yqFTVc>LB;{<;b1?=N`K#Kx;p-wsI2-9$Y7l|i!f_jo2#(8pn;4rcO7 znV~-s%DG0?xj@2vMHVnSl{ol7Q~vj~HU3`I7j_|1&z=u`ft1(hlymZP);`1jGij4C z{Pjc!Sz1CpF{HjaNSEX}_us3S$7)IrJhyi5ud==Cme==FCVV+bx3yj$_ZJzx;lC#$ z|L-xZsTnUU&O)WSav5aidC(&v(&(UyZPa9CcEL>47)WI;;F5vBiQ~h$oqV5b`3ihA zZoeMl_#^Vm@oq-nYnwOR3nyx4V+6kB%oG~OLo;rXoA~nAE4eFu;<yw+Qc4VfFJ&vr z)>H-0!6`+3#RS%leQ^t^&#|a`V~U;BD@M9ED6Wzx@_ri{HDQY<5kP(%a<KhQP;zZ( zyFP^wwS!y~olX~_PrLs1!)H?YOUpl|N1ReWA00lD{$zIi9rk_IEd36oD6Iifj-W-4 z6q>qs8O!fSLRMgl)}4n_d7A>;!fj)jv3dFa&?e!>)ve=;#p&k3BZ^bu#bB3D19s)J zgXLVY>Hcx<{CUj}1pRKZc{TEOsux_X*GPNtX7q@M0w#k&UdCIQVGlCTc@666I}2Sc zpQV}UiDj6=@9;H8KcsJxn3?E%RdPVjl%a5Q=cv_LWBR&VHj8O}OB|0wpPS;hvL9rZ zO6BFRFMm(4G)Jz8$ejmv15Y6>ur3d){5U1K9Zs@XMT0qIY3g%mbc=(Kn34NtxxcB3 zM2Je#g1}0aRF>n<4fNInR+#cK#TVZX*@}2eujG6(y*NFn?oiXjRxqxoR>3JHJz?Xo zK42MaXP4zje49WK5-5E(*?!4@j1wFRi<(Q$Gqz@R?Mf{ZYNW?crD{Lx(A&XM6Q}Q3 zy<7hU?_6NO>zpYOhthcJ(s!B#a+lzAc<$dMM%*&khdwjiEK$A=Rr;JmGUe7cqd<Yj zF$zp!@kyN|51xkeVuY$b4#I*)4qa<)d1-l^nH$k;G8Bn*1%({aja35knYzU-M#?$Y zei?h|X(Svs_HZqi>ZP(Xl{Qsoxf<lN7P1yzeULSmQdCwVclAuc$RL$f^Jl^g@^}%O z{szXj42ooz*g1jY%!tgnu~l{M5*;X;kU2{*9{xCFn2mb*QG|31?Chx=CF7M_=|1b; zX3=gu7lQA)AnR3LV|}{8SCjQdRd}H$dorLflwd3=q>U5ubYk7*neBr<7d|Vc8FnG7 zZx-TOY_ptxo{#?Mk~J+##YkLpdD&Wz%yVl<^FMyE=v>oU*92V);Tmg5i!ZoSw7KT~ zVOdHO9#_-*7TWx}PpF^Kn`rC$0$G=mt8DU7B=B=|{N6xz^I4y4!t5cuNKG`Ip-cI0 zLjTsJU!fIES%p<-NL;YCPcembiJEb-y0Gn7@RWBIn|G7>%Sj>b6PyM*atDsBIX1-E z^o9^_6uLD0qI!X<EaXPoF=Z1o9)5Z+=<9o*<eKiP@@R>=dix8`=_JDa^BRzI!pzyR z3U;x#>NS|rcVJ!u!}99rTd)8@{FA_zf!J;=GZIBURix>QFqHd}FcgnY6X_0l`0f3r z{3!fTVdt4D-WRIB?6<lfRdIP2G2UM0Dy5K$m_Z56H|!-{JCJ(E`Yt;}iucY9o2rN$ zp$Wh=!TYRJ<zoFf0^M5I@>;NMOsuN7_Drp`UVu$JKQZ4}H8qTf_j*KJ>bw<_76Yf8 z>gWkbk(4P9)br=)OfBc{Ul&+)D=)t<f1VD9j)VrMF3@2Yp5rDCDzvjb%R5|s!akIa zm7DtbWO$b<HH~L_6_xp*3{$oE{DA~eRrip+K0tZt^k2LTa-R3;I%y*xW8UlSX|T5u zlRmRzomkXP7B^atrV>>*9qf>s;k7D}&!uP+!;c?lVBh2Y(N%An;9)<5!0q+Fjz3Z< znoJgUEgQeGku8R-o?d~*4Rw|exIdSb7amRu+L<TCm=>eK5p9ZiRrLJLvFXl*yKNJD zl}Dp8U5T4wB@gJglrHd9h~))5n!YJ|M|Ap5>IL(g6+~g|!-dOOvxsT*wg3Wq&_mvG z10(;_DH_wSiI}3wy~O}Cy!l$JQN_Ca;FG+eN(?2&nN&TbkVQzF-h&~9UvNLL9|zmC zwCa)7YTzH7RUITIsW3UiWT<2UM|(>f2beTy_C?f&vlu1myS{YDWX+{2);f|In%o-B zOW6cnJkL_*13Bq1;F3FXXn^n&iO#az9nLIsi*xi7s42AUd0W_4cj;lGOtQOx3$vt5 z!+XBy5%xZM*WeNMqB@|pyBkZ2ZnE9x<_3DpqU$1Y{t13V>brbRbwQ?Em?;sfOsywL zYkQch*Bb-FyeKs8)Ld0YGx?*qdSeMp=tcbfHa2__5AEg^o3yfeYF`x0*0`|n-a)y( z(xdI91M)QKdpAWZ#}43Ef+;pYmz9-DyYt*$PR?&mcsh;ltW4xbFUSXv-l|s>{`&My zA8q3LlHyh6o`=`pE_&*Bd$7e+#XvVqOrB;Jj<9t+j-3#;XjhogD)#~BCh5NyD8yxH zU?fPqdh`>9aPPzAo&0c&>k+9MZ%Pfnhr8IhIxs|v3Zv}|jaw_cm>A2{vn^}49%Ph8 zV-sdb+u6AhXWY=6>u9G&%q?XHOsk+lx-n3GEPo??t{G6}%-?;)LSYvn9e??iBKiAo z6bWxDbGES-%3y4B=W(!b3*O(MN-p|nvMtl}dx6R1UjOV6RBR<0qdV;_6i_efq183! zZu&N~mpBL}QQ;#F4pcyhWcb&Po*!mvKh5G_9(G={=7Q9V_61Un4l&jT_(Ow-M3Z`A zYZO0O7!7RgdjyMF2M^{5*5GUgk5T8vA&zyUM>aJ5HyG2sEPHP%c6(4f;)aF<WlwbV zJHF`})i!Lk&IB#Bu+Tc5nsRVFu>Mq3hhP%wH<-@$QBx53`6AgfW8aZ>f}n{r>Lf~x ze8xZ1bJO8@U7As0SW;$Yj!N!Q91jU!RcHK!*ASNeG!*1+aI*fUSm?kGn<emid6)J$ zW*p{@(REtv&hR1JKRB8vGin&)w1f%|XvfZ>z%~o^3#{w$TNr@(b8}4%)EuwCS~9QE z9n67sZ_5U#0=BuLLg{TBUp_ZCju!E_R5y)^BbMqS1f#9B?pV*wDToj5^73igH$+pq z1TAAU!o_@ZBXrT86vGW^sIDfbOhh|NQk<w5kdOAo2+^7HCk^(s=F@2~4|YX`bSeQ9 z?n~ns*KS<=tnQcq0BSqFn_F+uQZGZQs9eO`hWk6LQZs~%)gO72bKmK=T^vZ*z$)KQ zFX^ep8C0hr$hF0MdTtr6>K=mK<Oa{Dc4n(_2OhlWIav<5991ec&Uhx?gjmSLM?<|F zj;k75zN;)dVvzo<VwZ_hJ@Z>;2)*(`ad1|P4^LMs4^R@8!ht%B%<<Fr$A4bJmD}`Q zs_FEiZ1)uVC`mrL`!wn3@|mOw-SAlDX+auBzq2YzF%_Up$xYQ=ZP|{gKD5@pMm;7~ zBiZrlik2X0^f?;9nt59bAbnJR7Y_g8*XWLW-ER`QAs?y*t|)QL?X44mK#lBCXOjbQ zv3=gouv=c7Io2_JdT?^WHO+CyzoON3fPu$!svrHfOZ1A(8@Du><y*BmSySPu8BLF4 zQ=ZfrnAKOB5vx0%{@AIG{p{D6hx44(%UT~2_H&hR**vH%q<CIv8VkAK$j`XXZ!#4d zko$K${ND)mzi~E_Lr!7;5-EpuI)^s{+wxQc;lI&z<Z|94(-{zOmc|-U|6rT+WqQ7` ziy!A;KbL%dOp90&DfwJSLILF`+C#<*$^Q?az=KZln_6-*BoRx}I1^~vzXLkmKxP}^ zBtbvSfHWutP{V!j<&QyV@-}?8Uvbhufsw#xWI88)nGwRpklScL<oq68z<;1l>3^g6 z#g$(fcm4>x_YF0V6S91N76YOFf1Hy^{M-H)Okn<*@?x@5^TGY>PxnsB+WrpNcaK8g z)$Rb@Gu@Z?pyE%YFb%a!m6m7vL3;RH|4hBsJ4n}?TLgg3M~e>u&YT*F-~S$gLq+<E zuJ+B)=V$UOJ_KEJ;@@Lz66iI@3V^el4s02qSpVlJ$fZ{fX9ivkN|HICR+}sOr9g2u z$#7Z_DCzCgUTFT`m|+6{ElN6t+@Ggbf;1QHx=Q#Pl2k1vsh11T5}N;0i2Vx%e*JsP z%2hkI`YOK;7Lf4pB^*=xovIX-KnrqrIN}2Zi4nCI{Qno^X_(~Vc+_a}T&v+fC!*_b zlv&o30KjxN@UK&Vpl;>~Kuyxnzv_<v?I|z#<Mk_wU1{1=QY-lM4QrbhO|*p92;}zL z50t(@MbJA~0@%X=p#ECXG=YN?BCLpw2*>XiYy@8emC<4NuPsojkKY)cho}tP3YGb% zkFU%F1xVIl07NF}z<+HlelwG^5d=z*V~fNlxdW!5?-wlFfS=U2z30`Qn-(U2__s~| zr68dHXAibb@xP?oUs0s>5<zyrIOT*b;eTFlkT(D2H~1$dci%1K3owHy&>~RRW&11V z;r0<oJ8;huzeG2f_yRVEv+!v;Qy|}=17M5;4*0J%WPcNCrR6W`G$4iq7%Z2N-T~4T zH0kX;xMjKX7XWtLX8GrJ2}y+na98xUHk|De!ab%~;^E5+v**Xe2d@<Rfjor@z#I+{ z`c2ZW9SnejX)cG~B)R}$k>^Zn8<ifm=ex-1@=_(CeBR~7Sj6`_HS?n8_&sy?0V^%O zk{Wl8{EQ2n_~_-~M5dc_a0$@TeAVe)Pe%BR7{HVtPs;?C=CZZWet=GQ)mUs16%v2$ z<JH$dG%Z|??p^^hd-*(>UV+ky4<F2Sq&;p~U4*=wVKf~K<f#e`aK^|oyU!Tu?x0-9 znqEw*6-^ZKyc9l&%g{KWWi;tpCZ;L)e%gIdL`w;+Psx|fw}oiQ_mvEwyyf&5D%yla zP~Nk>$`s?eaL+)5xrJEV)JLj@WB)rE()HN;7i80t_<Sw{otVvO4;&v~yK?!F-w^>w z@3fCxB2Z6(YCVpS<T8W5EM1a*K<*okf$tp4CJ8-J<Dgo2RNeb3mhwI51!n>`Znzwq ziQzx|3#1(d0&t%Ss)`BPO+8;xEXxdRhPqeUeNJOOl<T`@M$r&fTchdmR8@RvciWZ} z&j3I=6{+0EQ@%Puws)0uL(lFk8USK9SCZV^o=>wTN!<Q6Z~<kL^N^wC*#Q+hF=NC9 zEh(RM$xHh5W>GG0h_~LgvT4O+|4h^7B)qked(q;qwSj&F9vpILEw0GWIhLyE6(^&L zvfr{7!fZ~oPn0T_&uCo3zAHgbcwI9<ybK<~*gdE-TesyqFJW1(3VAxNLP3zm$uvYC zS$%QJ*njY9h$fe}T_Vj<pFe!ggQh10nn?51WyRt~yum)aTL0^BlGxljjfiI-5_*F# zS66>8s86t%I@+fN!(FybhbRloa3jZOF&71eJ*c!8pM9aM=Y!7UGk3{=i<rEPY-^FF zqOLic$8gd&u(S?ZSZBVo^D}UL(M_pa_*;j0QKDEq)q7R(l@|{U=Bjr60Tesj#*T+z zJZA!A_Bm}`xM}M@<KVH%Aao!?>Hfq~w$h_m>2#wObspu4i_+$VwKqN3wwasZ8p++( zpttrAMRO`DM;U>9L2ag+8M@7V<1O|-R}!Q=HtTMwHQ?}YN*HM9pkm9y$%rYeJT_I) z#5ItuQBSyPYU4qhAT3#FLBS~&_9em1P#B2XQ?;WLzJ8Goqzw;d!LOd_!Gv&ext+8O z8~P<k;0NvsSl}abjIZqzcZs7P2)?Fx<=Jn+v#c(v)>i5!I!Y2&=!7c-65I%&Mz6wv zUGEK&#!Gd2TUg=YT~ktksA=nN*Ku0%+dLFVc#|$}$NP>JTX@?btL$M;^RXV*4A_nP z!Gjt4o$wGan=(Ik1RY*cGt(Wo6p^%T8K{u<0{Wym2QpNg=E1bgf4N<Acg5<hqZ3%^ zJRG@{@oRBs1f&1vHwisJxEo<{X%qYI4%4~BF88XAbw>JJ>qBheX0#Und%MHsG`Wxm z;Pr^hsWaEUEoMEDH|m_zGl=T4U#9SDy!la&MmKOQE~{W7Uk{P2zqq0`pec_62lNsd zptN1@>+Qk@s-u0qlFJRXO_-qf$A3*ghP{na+4>6{OzGE)-^AUz)#IVtQy`d%bI`-? zcW&0cQ<jl?<9Av&n_KOI^5tf~c}!f@e(w;$>iDj2H9!9|884J|Kwxh~@BAIX83AMY z-lpUdEQ+06h^v~1yqFs8ElbI`TIFe1O{cSVGp~>8@LAgRwR@v2u2t8~XW_@C__~h` zyBcRQ+rWngi40BHpoM&Y43b(q1XBA(;P!n|^-rY7Z}^g?{Gv7Q)7(_PMOEHMoI+wB zBO_GUar{$-XZ$c0oJ5y9i%rv~sk)Eu5V5Mrs=7d(ZJk-ju9Kt`<#f`IS*>v6J1vho zEN-|gQV`jm6CG49i#A`CxurH-yw4G9>^iJm?TvR7Qqz-oZ*!N|si4h`<wzB)Cn4S; zDtj|k3q7ed3{CA*7+{KvDVmM7W6$Y`1A@{d!?2}B!CPh3E6Qet5}^eDGMMbd&o~tu z2Mt_AE;@5t#A+gdcS2$}d@}moVXJ)(y^VmQd7sv`PtX-L#ByRWK^Aubn;zGqm1n+H zPHcGO{&I5f<|$JTe(b^MDx0|n>GhSTCh%F(uZt{1acd~cF%sX2Sqy8SpNF2qq?W95 zL#J8Nb!l=%Mx^QI+=8FpvFW=!c=?fm8vPXuOWE*MJDv|P)$w3jVmGpeCtjJX6ed_V zCKKaHvdAT2;db>(Dn@C!a4uI^<ik>@)TtO<v;}W=&sV;b#2f2FFu|p{2L1?f^XP@q zQi0@Rq0)}IJ&8229*M%L7fHzm-sx*u8b^1R*v+3ckR@UyQ++rsQyg{s(`yPr&q@x< zA0OA5D1b9!9R{bRj=#sr-8vnP!*G#y1+%r_sv_$Kl+HQy=($u)s~ff45f5GXk_S_@ z9-_h|`&bRHVv5G=xIpIP?sahjzc|Wu23+<;_Yj4&oY<yFExPm@sVNau^4CM;W!90L zDzY0u7ca*am=R>(JkTolc!F@(J!o0%CHPWrP~n1wu1h@159gP3)x$vx(el;MDMaoa z6|J&K6*pc3)6-l5l|%0(R^WNgWY0P+!%Sbo!>?zwgFff$sM~Rd^_P1*WoG_O(lk8T zNWJ<fy8liv`D*G$PaS7_hm?VrVbNTjnHyAX0lNy@_8&}kA<%Ly38;owsYie$)2vMO z8H7_l8<#1J7e{nz(8;i=X9-Ov>tTbZ(xt5>$osV=+VWZ&fJYOX3K>iQUxhX=s%-*X zr#P|v$Eog1HTEa$b*pRnfv)aA<2>d2g2ntfviGwCFTT|KrQKJ->2yymvZ@FWz?v}C zDmO3{4D<p~puv^eV#LZvkLqLB@nY)wq!#G27Rp(nTszB2ArMgTp!n$JFmFV>;C7-h zYVwQp{!sq}i<FN+lXqH_*v?LFOeb6;YhN+$C7xjTb+j-tO(dgEcHK0LGmBWIol-X3 zsyXiKDnH&T6lkkmx7jawoP$(zl4u`c!Uwiz6n89!g03w$O&)<S{U&kgEQ2mu1kT2| z#VBOp)>~ev*wwezg&KvZUx?Oade>mis}pJgs)_YS4JTqouE31&bpd{5n=iXc3-J*_ z+%j-+>N_Zlyg&}kN8LG2*}E9c1xU(QUIwwQJ942`Ux_!0^$ImH8<t`&^Coi4yKEMQ zNoGV_XE6?~LjQFGECZ;=Ak|vdF1+EcW{*_1rg3n8%kBO7V-Mv$lN&+?MyZyc(q&jp ztbWRz0x{9$!Sgf~GQ0%3E#^!U%KP;=LoljNf|Xj%GF>x73F>#>i+X;1&RRYCQo72s zho^H&S6LN;KJT3TCP4xEraL%fyME;Kf(qUdovosDSFR%h6NqHDV4eIakI9w%($FN? z;S8@nHSK_yGblfR)bmxHDxGNs&oA;IJ%a4VyK*@sjtUw^S5tlOa;S})QUaRaoRqRX z_J=Bm7Znbl!X%Yml%iDZ8!oSB$;9Q08s`tl4DAhMZ0%Z9#-FpD(Y{t8$44gO;%VR5 zMHg~j^j^yruGB6ws42=zT06-wT&s0(np|bfeGgc9Z}Kem(8ePtt>7*H0eu@Se#Elb z^L1kCFc4W2DS^lu==Pc>C3HVEMTP*i5>dc=83-#R?{Vn@fjOh{zxrLx95J4!7p&n; z$Y0kgWnWR`Y6G7yY&eGr62pZ5btFXE_@5a20`c_MH2m+j)l0xTqzz-B6$W=e*K3my zZc&EPAcVLhx934`%cV)oZeWn7w7P(P>m@U=b!0R!o4azOpd-3_Y!d*s@Z-J;jAoqs z6AM3LLPYoe51+6L=G=;BX-J@FaK<h8ld|85STI0<to}}R7YOIC^!|&;3T_7-FeMXP zM~Go{6OS)g5P``1Ep;z2mJEVo1gAlG<)IP<)DjRRUPr*l=A*z={*;1^{2y-!U978% zOP*EVcf87ffv@Wh^q0|ZlA0aRdJpZ{5fZIe3t$UPpz!ybL^$cy4dMvUP?*aK+8+Zn zM!kQvb`xIK9v}NWDys^Q7r1_5hfI6Be4cm_2EwK$gxXI7i`d<hkmw6oPrJPWua+8T zyl@aO;m0rUw%LAkr%v!VEgulXIs|(5#)&e!zexbY>3NV&Aea^Jta=buP>8LMA*Xe^ z{#>M^gmi;vMyWlA2B#P5Uja?fZ<vs9$jU23U6n1aq_wO%yAPFUZ{x(tG;JuFR0u#R z^)GpeGp>imdS&#Szh7?}?>?^b<P}Ci4x69gauyK|u9k6oh(LbgM?b!?Z!-`+d#w)? z;F)8d!)3DbUjSuIg1PyJbw`@09aY$;u-!}RsHUfNjcEco@?43*hv7?Rl7NHvStzkF zcl{n42xXZ-06N2gR#AQY=y_oY@ESNiIRZq<RMkj4f#)s}l6D%4HfCbr`sy<)(|Dc> zU^|uD@WnzP-O%v|5BJ_RAg=lWABp8T*@So05cC;MEe&#p`NIj_9GJ(&JO-AN>C1rP zZtkxw<kTyL++8sZA{@Y@$YO#Eacly<PK2NRg7<vPdnN6wG|-%F$|^2ikjVDw+n%Pf z|COfPoio}~TqyBe0&m9u2aDJD0_|~7Bmv(JH0P!hZl%kbYPs_kW(jx5UVroII;LU* zFml_JIQRBkaUqTRW1NIP#&=~Gy6E}Gv0HUWPxnW4Hz6(Is{%Jhc(l>me~9nCV*A$~ zfd0AUi~v?|a7}=}XW7W*)`>SUHz?k$klZC<GCR{T04}~$fNH!6wBM%#`1S4N$oUHy z!&d@-OsUC}x|4b>DS6>RQlr!5)yG|jTW-mf4ISWvO9=pI^}XPKrqW4-0hNBF4v`W5 z&t?|^o%BfNJ^-y4{Adif6s_)f5#k+ysfO3q@c@J75{bDu1Q?KQJL37-`zxdC!&T&; zf5|0p2KOm0N@fXHj>-+iw@R5awJv%7Yyj<5{REm&|Jithe=R&Cn&g}x=rMx2?=AuN z6msQWR4!iQ@H21)g|&)oR{@Wb>cyBAFiye%{~Dc3Z!UNohMOa=;#xj<s$;(U_0-_R zi%sDhPYci~&WhJ3ToX|nT{=%~F~bN+XFi<}Z@WI??gx7-l;L9kxyB{mxo7Pmq)4~` z{isr1j`O^s5TDSAS~-zz5@>b~5KHOd__phjq#kllJLP%7?h}&;8XDvH$yG;Ao80H{ zYxX`=2$6o_tkVz0EX-&TEg5%5J+YTojYKb8dMu{{+JB7nE{299R-u?3>RMJOG*v95 zE+63CFQq4&`bha{{R`8*=L<Y|Nt!sfKsP}8^sM#1pGFJzxHJIfz)a0m5XiI=%{5rl z2<4k)X6#*ivq%@c4|fhkMypV`#fdDN7B8($_&Epe)8<mP4oz6vW^%23yZ$8&!}{HZ zjZ!NTC?(J(k`2>$o5c_x03C}h;9rcX`vW~5*Sky#aK^W^jOr>1Sqk_s0n#FAEki=( z&8WT~)55=WaA`iBGj+;NEVM&9S07v})sx{hl-_jsRAW4zs{Pg=6*5)1Qd(BKHI@0% zG}b{|dW+zpLyH1g!(ZKYy*3L|WwBJNj42-|&TP));xL^M+wt(zk#0zQs>wt>=v~&L z6g&(YdfVa+YJ}P0fU1EsfeRmX#zc596?b0Lie2xLg303U&S%ML1q(Jb^Xerg$s>m5 zJRYPZtl9D1d39-slN)5PWm?}fV5L&!&NW&S*<ULs#CO2EF!oG$2Gu-2OBy%aTPm|N zfy;>y8!rZ5aD6`24{7rofC%<6Cqd2{Af?hjYpmPY&iS8b@unJlU6)tHzc;M<Su%Bu zOLaDR5NjhRoRXEs?UAjemzjmhHk0o*30M4dd@k3nLXC9}xsnWIDA0I#g#|&cX38%} zPzwi+kglq8d2De%NFvd*T;E67$|hobkeUv{?XY6$I6)p7Ah#1(K%C%VxT#MHvpBDk z$-RIF^&DEc=Fo#F@OIKal<(hgN$;<ppx0=sJFS=(cwOo6K6dn(k|14t3|eDX1~-7# z2-659Twd-It^MZd!A+@A-H>fB#!JsI6c>F<dDmK8htn}iR+;qd9yIhT{F2eJKQ|4Q zScTR^#MLshcUO!_Kc;6@=T<OiGaD#RdTOdbC0nU*Ai;=br7A08uT#)2XcSZEVd87_ z47jB$2d(4QMD=MGmFa2{6EHl5#TTZQv!41u?LQjQRYjysDl5<N;Q%R>S~no$pHiq! zA!!t1U=|Y&UMNEXiLa%1md;%g@qi)oWvqS=w^H=hNV_EAem#J*Tp>FvxSLy2YR+6k z9o0&@&x;K}E~%(B<tx$p;tJP2M%owaBX<IU=2sQ$$yd+#1tu(@z^eNZdh8M`M39?y zN7w=KW@G&a3OZ5uL(I9KY91?ywLkh~lGsw!!^7C7Fz?b3%!RkXU8JQzxmubOy$?Pf zDGNe8tJrgDtZ8Uysh@D)b59a%`~prh9N`R+6_BBTX`dZi+i)*y;K;&MZa_0lrkO>` z_c^vylyD5L5KODK#WRq<bg*Gq^^=USDyp>|?So#<a^W=JvmH4OES%1+r1SRRsc?7j z?w5(!e16?x;iMJcMdhSbYm}wfu<}^LhHqP9&P6X7Q6^4PzgrV=>=Vfdc5D@yqS2an zm1#-|@!0j2ppDI$f?h3WdEc4buG;c`NG?rf-Fu|HyI_~C${0*_IZ#BO6|bs}-97J# za;TgwZHgvRYmJJzS30`5(>q&54$56sYFBo&a3$QsBha3x&~E?SE5WkF?^79r-_3RN z775DZ11`_EO13;K*8+KJ2l)1mcc0BLXmJXV9rQD2@jRVWxoZxC;uFvbtOU<VG2b|; zj$qboyYId@*yw^=L$G7((57VDIO7Y4f$*mfHvA}avvy29WheX=BaqkHxbSjljc#z{ zCpXl2+ULMxm$utDn$$}}AFUp8V-|i2stE`}5xdJ&3+4fN7Y%jPYhEhoGh^#Pl-lts zwQfqF2HifbLY~0)f(G90J}`;Yf>m)fxSZ&(dsub-*!Iqw<slUt<6&qcI;DwxzH-~_ z^QldPLJH-w=r~PTG`VS<{JjH&U^|f$uYeVNl)HrNy?bT4{bY1*Q-vQ3?;0|N?)d4P zG|iOgTs{T4jPG&ux1I88iDi$xdwat<m2h_KhD+!{MxiR0RamEvG8Opo!5OxZm^jD0 zjP1_vg{y<3wJ*J?<HWivnqH<Jh9nn}y&GEP^V|Sd&H*FG^EfWM4GAtKM6`He+%;z< zLZ(d{>KfU*e|En6SpOnR<Dz_yD&JrQpNp15b06!5%*f0D+BO{fxq>L*D#7>5Ha>kp z2$v;W>9OBMxn?^cX{VgjDP$%=`u=%B_^LtV=BbC94pXQJq|ngNGfDTBEf}H#j<V@B z8(bNSiHWu5Sv8L)P``Wr!Y<ujlIb(P#n096)4Pm!!X|)!dn%cwb;{PEJtwm;$ox1t zx+{>zT8-juXN3$1gdN#AS<a0Fvl9Z&RG~&aC#Yj&(UuovsK`~~>1Kt?Z;~f<Eg1}4 zsZE(WHGaxtH^>VIz0zW%P|lmV-9%a3bZFj`3M-1$Il(Gt+oCyLHRf^7!d1^WWTs;P zSLdvj-{tpNVNsqW2bXA~yY1n$_^ZWpGq4*tUl1!yq%vjzp=5@SL%T~DPB=A=Dc^VC zll5e4$++bcz()^o(mmKH`8S;6`owrX!W{_8=NUJ@Bb`TRV7^UhD_e>l`2iodrc}?Q z^xVt~-e>Qf49Mgy+7^}`JoNa)AUfMp|Fo(wWplJsy<Vp3*(zgF(OOZ8u_No5ilZ1G zVz0clAVcds!l<*(hx>YY=Q|C3xsm67H#aau1i$JQD+Qf-j0UYjC!Mf(c`Cc#giDK> zN#q(r*chVWjOOWeCqw@x`P$IpQl~42F$)u4f-|@rZVpwr6?c95${*o^Sc7CfmRPyE zTOf{mCpNvViT0F8#8)lrM=!ABt|R~-X4yJP8<06JJ#X?oEBTny!60n&qqAP-&^g>4 zlc|>&5}q3NG0N%jLIP%yViqtdjU0u$NHE*FWSE4BIG}Txw3Av9VWV?u<e7#CD@p3{ zTW;TK2fTX>^T;Q)F?@c9BPgG)(ho2ttpDz1n$*G%NF38%GUu+u%)InU{hh+DVX#z1 zg4d;pn`PHE{V~ec{X}I)P7eX5O{1y2q!U2hBv438=ny_$pM{yrGHbr&V{;3ZPKs?6 zztwHn<xo1_ZRf=~`DxMtoM<#8Y5vlKk=L@0zd!5q?Jgh8L}8@yhR;EVWQ5?_2>w=j zY$oR9D?BFWI+pB}J5Og*P(&_gTDoYi%b4_;yMylMhL+?&zACwlyg7B)qNwdiSYMhW zArAMf+I*p#DdwGVXVRza4_P_Ts<B-BE$)wbguCZi0$8(fX#_Jl@S8H+bKD0uIMWdo z6YF2NWX25nRF(9FB)86*fz8Rn?9iwODE81r62HKAdXPCSI*3R_7sPIFvnPwu$`l5K z60(_Qt|v1h1$%IVRcJKp;ALe!`bCqnRs^M*#)%31WwKV?&{e(XnXPln;+`)z2L1@K z{~h&<94>!Xq$QUE*L`hMfj(}2xF{=?^M2FnPc)_fe+j@BdH#unP5q-C;s+ivSg3zO zX63`Q8JEdoqo@C52m=xMABf_AA{+w9-_NhS)6>U?FY&Wdl7=X4|I1Jt&>u)fBn8_` zh;%0+{!-%Jartv_W3%HIUgjgBrimh=;wEXg$**%>bDh6m3jZd%Ol(~Qs@>8Tdf*V( zzu+n8{2a8b@h`LrkR;{)^#)2T{Pknq*t?+hBp{A|Ubk30$D>UW^Zy1L^7E$0$JBZl zR*%((TJMDU!Y;FIkhxa<8$N<80hH4^eGUU1%2@sz=OobHzr2t@-92|zG_Kj_+v|6P zE<c%X({^ajQxX8j0o>&8aU_=iLhL;M0Nm1&4>WGw)dLQ2PSZQm!cQ($2)YP*tzWGE z7pMVo0Hs7diC-r?zZgtqNOb=_Id}a1I3Ta2vH&~Jlnq#vo!c9h8ZY#j{0?Oy+9H>D z&SXg3{{UDC|D1W_iN{w!(W9ci-5LEd;e$&oQ9wg5^joF>zcJnh!3|)1hXEYua9}l- zjjkk_|Ne(o^lW)%t35|xb7Y$Ae3Jrab=EEA(0vQPk7)2I?foP8`GpeFvj2}gpm-Tq zSfCix^&Ryv{;iTo#S^9*dgOQGy#EF1ryYS3=Qr_fVru~~4c+HQ7Zxnxy#?T(L-15B z>#&6zQ%~NbqmRPXh4WpOXgl5ms$Q}{;T{BJG++|=$7GKB*oNMHZkS|K)0i*hNzV5{ ziziJF+OO{2Ru=*AU09|y056XLLm3u=NTA-B@4R-8$l11962!<iUW*O%8ZiD|Jg&lL zc&=m`TZs%<=<ka<HE_uO0*cGSO|)cqqosu2^Lw2|KWtpss}p1c&B<K~3{Ikfv;g9$ zl9ou<N=tm*2bkB$;in6NM_yi1VVo|&A-XF}ExqrJ>i8+8Qt97oRL&qdrlo=jV>QBj zwWPUt)J-B>TACy5bu{k|1t7b4B0x03+zXY6^0~zU&*$qqQ_LHR@gEv@Z4n53v&JY) z&I{w?oqYdtV@iM?4ekdm!e`(N1U*^iiEt0T4s*uG6yv2HzCEpHwr7GoxV_Y@Ktits zwA`;vgV}1!J*npKW}UX=A!7@eJK+m9LqC<h-Fp90+T!`UdwG+GIk@8_BR!%LriIm5 zcFcW491PEy%!{-5B=xFab7Yzctpc#<-UMIYUhgQ@NIElO5g=cpj4+z>iodXbk5i55 z=h|N&1~axRjjs&84h4$TW6r7fnKvj?Rl?GE3VlE<AUm!=bWa3P<om+3^*FE1*pQ34 zvfDYPar0=11S<FXj|S--;zi<MQ$nwp_L(lW_|5JSL=<C|p_S)+ctM`DO=L`;z!2I? z@uH!Zi;r%C!-vRtVae~GyiGG01zs|XhC7QO?w}5PkDD5fQ#|^o5-+Uo%CFxn0R$Va zv>2Uf;>SF%R(?oCSy{fXtaM6Pi9IqnI7}WQ32<Zrt}GsqlK`F;!x6+|V(xjPIdm{& z@A?+vN0nenCFP%|{QG4dYP^-o?XjcYHWQW?eO@i`nQ!Yyw*t*vbEqafsdkHc*5pA` zcfZkvlTfV-#^-&UBq%)f6QPXZkT=zoHh)U5^(EZoQSz$*Oi3SRgu~60_B;w<bsi0+ zeK$=<K6qc#`f2ipQU(b!aB2SK*TlQkT*cJYk7xBX$hZ`vUz9G{xQb{QvQExfusP~} zW$I5-SHhIcx`LTMM(Z>tp&mlCZujS}ud1U%$FCbJR&`aq$<Up9yk*90h*&VNWxC|B zcLy7spFy&=PvmivHEUoN!uGqryXvHsK42Yt(1kPEBhX<uI4nH&5C+Wjv#(SAIUV?@ z4iq@grak<i*_Fz>+>=w=S5{e7_^vw$t`SYRKbFL4Hh%dWO3!<Pf|Udj`+DTl2U^+6 z<3-}#<=-UF;liariFqLs&`VnZ?#WDoTXuSv<)ERo*W$IZE}<VSwEaMXh6wQF`}4*X z`X7fEfQ%_2q7uISxh!?+2ZY@tA8-oV&Fd2_Vb|b`>pEGQKw{%I;72t2XPd~LSMsQB z7?1|Kt_kEqJ=YBZ0ZF-!z_UgHv=8*NviDB?q#U9@uRRxcpc4L2MnZFy4bW^W%KNg2 z*Qy%<l2e{%Xu!e#&x2Ru_+=vK1HkV9O-%9oW?V9WhRpBDgfX;u*0Fv0+T+zDd_v%T z$#YJcO#J1E`#>Yx&_YeDUq7ED*8R`*gSsf%xT9}LJ6>ZmkD@qyD;eJiq_npF|F(ei zM36|HiajJ=tNLNt*_AuX1Nn<!+SL?~SUJyio{?4j5nwR~8$6F0oCluoRt-GjYg<O$ z<q*US42*x4p*;OkrIdd%cGuB&>gD`C>S^2iuo!wJN~gx?(ay5Lc6-Nrte1eKYltHX z|ChomfquPRu{Qz3%p%*yGEq0b7vs%57Fb@s9T5F+Ie0t39xmbCFjTwq<X%wEd*(!J zaVIz57o2UT-6a*(EpGNtwK+=P5@whTF_h-^Z|C}6Jo}i2&L>|V(Xx1?wvw>h!qK5# z<etzo<Q8mxhA0)$$q|`{G|Pj_^b7aktawm{K?k(ByG6%P+I1rC<@XQUBID((O`lU) zXG*k<VoSUcu0tY5Db|HDNOTYw(-75iV|faf{)V218J}^mY=#6=&iAC32B$qg&yhzg z2M9#pT21iGx>$ivlKx?rs!<MmgiDVAWNlp9II#(_Pv|wgT*aU5?0CoosXnf)iw}&6 z(eaB3NZNX6ZroBV!dR`7)L+!1gNBEB2Hzk+CRK#-BE662ptkp#9K+aC=&f|hG#jSv zhXdR_t{>ivdr=ct$>l#A@2@CP4ZC-q9vKBwmuO?!>O;3$seZ5Am%eMi;GL{msjnz) zb_W(;-8Dcp`Y4|K_P}b{G6&pq&>NO!z9Yujf2|~I@s96@ok_NX9)k=xt?09Yf~j2_ z@7y|E8^f#H0arvMmZ>a@V>`#Hb|FUjtmu;dhKWfYkJCa!-%Ybl^s2fHudT7GY1wuU zQt{(0z_;QF;c+7l<(8qb(^<8}O`Rb#_N*3CNA4Tsv2T@Vt63DcXK7BII7{7VX1*$A zogguI{o%PvF?Reo3#-vHPm4C|N{B@9=`U;kj7cCjcTp@~n3sNWL!6t9HBaPQ+OXcL z@u8*EXU6JY6Qpxh3{Oo%uV)l{aTLgfhlx+|a>FaZ`g-io+&9jR)r}JlU+R<A0u4N3 z_@=*WmvUu&zaSmXZRI}rF>e#@2<S)%RdtPU5K-&s_0X0Jo;WA?RoGn|4bY$mctS!W zPzxtr$pbRsKkIr*k2^i2F;i&<8qztMsy>|i7yFYm7~zx|&%rcP@xtI4-{eBQf+B>l z_ylGL4Jnv&^n@^RJ7v7wT0RWsfl_xU8-(X4In61ll9|c}DD+Kcx#<~xDAsM7bXC+H ztJt+Pwo$sTtJU2T+^cVm_s4E`0#%(eg4-BT($c!WO+uHeMJ~{(z9IHRu3GKNS0_(N z)NMhb#*6anH-2<{JtB&pza<Jmr8+WLqGjeCI@3llBC}R^<#Z-wx;{6#mA{!;uAhBz z(=>BcWK~2ejf~<RA9Q5b=ZqI-b6&EeOo>xn7G2=NI|Ho}P^8VcuRaCPTNCK#77zeu zGz8iPqC~6)zi%Z``niY}nAN`lWw7RTAHly?MS^N_JCRYAFKW(=2xQTqC@dsHW2Wso z>|U#T@cBxeDpO00-}4hnN8w2O1FLU0A+R;k0{ga$#SsL-H)v&MhmcZ*sj{qMJ*Doz zvQck*qs?5FgNSV2ScBvyKK#fLE60{$Ht1}KoZ`1_71dQ1&05x>dueiWUc1tRqCn(< z{#?0sW+_GRn0E>X&JXMPCRQ=F+PuQEQ2R4@R^N-$r)M?V{aVdc&JdcVGVNut*XAnR z)6)9PGuw)h;eIhTdW)SI(LbOOK`Lk`UGd$5gQ*4d+r&$S#Cr)5Vm(sbLDXmT(0q(W z*9iGMff7#F{Q-*Xw&j~>al>6a>^x2y;7%y8wR!9Q@r$WrP0N?uq38>|>DOj$1~X#~ zYMus<=Q66W0>b%7H#qeSRO;)3$`lCAhu8Nh-cX?*qn@8rY@IK7%bKB8G=KcwF8Zpa zMT51?2V|0&8AC{bD_%c+dU)H>9B`p?DU~POF*H~(Ta7kw-Bp@VQ_w1OBTDLT_$9BO z4k?4Em)-0kX4#g$jy#Tl5B;i5C*5w)w?KAmA&tJD$VAvVpwKPBo>xP-d`5%cAsE-6 zw+1WDREC!Wah0tI9B`$DLd`QtgBVMhe)f_-Ny&_Ql6EUi!|QpKNM^`4`TbdN2Z$MF zgqsB}OCX8`Zk^bMmkQr!^~ROe0zGA;k6-dNBx@_5Z9n74ERV96thlPEL9=cDX7}zl z7s8`~j%PuNsk~|S%z}xt=;J{C;qz0NWUjPP>q=6R?a%aqHJ*pcw8wSIG#1_R0Sn=l z!+s_9LhXSZ#h3fo4^j$MG&_`|3tB5~mYzWZ8NRzxo9T?p%!}JFSdD*Zsm^{o;_Oe+ z#~9A4$gF;etAdm&p8S%x$hS77&D?sHomI~dF6`hQT5{;{vat?OV$-+Az8;Si;Dva+ zZH&gNrwxgrKBttpyc2@3S@XY?=-j7=E_Q?IVH()O?i|ujqw82=f}{7g9maHmYtJJ; zYN>8*iqXt|ny#jq&w#^lS42(t+ZT<F9HjwliWG&Uwvl1dN-mP@N^)#L>yLp2Q&(8! zFC7if5ihs~n9loA8mH0QHP%PA%yKCrXq;_FakF8ZxXbq*4YF9R5kQd5wq0<yq~NsN z&}a+?j;sZ9ngbO^e2u=&%GupPii7n*&B_}tPHJ!MCX}DuCyDPZx#X}3A|rBc_-h3e zL7kXVf1cLGX<J3e(YvP8&sbZ0Y6^%^?pw9~b}_k!gh$*My}4M+6Jd|*hk|>WB4W_< z^7xk`%T;a}1LhA-yyabXF!9H%e3`OUOnr%Ft`(ypk~gLN-a@B4{khrGyS)~bEI+2q z{vX2LI~=a=Q5%*>LWmw+Nc1jxjZvb9i7whi5M`pbQAY@(MWQBpqW56*GP)q56Wxp; z2xipLCg09^ukSp0e(&|3<F7sbuy$Fqt@~bg5%k^H68^~KSu>{|V~*w2O<)X_eXIFW z`I!-rC-NLO^0rTyy2rCqo_F%NTH6$yqHY+!oY=lNw)%WQ=r9U%!q>CL@WuA?cWuh3 zx&o#oZyS<2rlMhD-3iMnsPrA-B6D$*6th9glU}!%=|sIEH=e)<aCtpUQW;k?D<|}( z3sVZ~-Y`-#7`vuBrhIza$?3_kn0GFr@*sjLNy7|qoUP&XLa66)sT)SM!arS)Vn5PO zzSX*|C8s4>?$P8QRIteTT#WWM!A(C0K*2fF4M<*1S=mQh)l1x*ii5+>9_TGuFzyJ) zwQEK?3Y*B<_$CpTZjn-pX2xuCnS{x3W!}~)zx<H%Qkaww*l(vJky$;j_~|r*rRZI# zR>_v~q0V1OLwvkFvDm<)t9Q1vYu)VV3+_ect3LvwZF<noU{XorOV==fRzEB);(wp+ zRYvaWsJo=4%dcnpxXA4r#eDy<;AORs$n{+eMfdw43+K&1#r$U9wmVZ(`J(xXkO5Aq zVK0eL?Rgh8XS<S;cH~777J2c?23S6_or_j&)&kN@H*%-MZR>keJ1+!R2uA$;-K*6Y zIIlFl50$;^8IX>L;n^R-ofGEV`dLLW4v~9Bti0Ii5_taXQeTMz-NB-knBYgolqbf0 zzr+c=B016z?0fx@^v`KUKSX4fr;Ix}RzR)J8d_Wi7VAg0tMWGDTHVly>go|k<-RBZ z<ByCQ>4wP#yo0;ihJG8KCP^-XMH1^jE=*$1&UJw$poe3siRjSk$m?d;4_@qHLZkF^ z!8ZlPfn9EF>@fqDsB4F@)wqz<3aYLA!S%(EYkcq%uZe}{^`Jruvj6s}x4=UoHA^Mf z@n98-o4D+GH7SxvFNsHZ#}}(J44oI-V*sp+>RVa4@EnI@SOAuX0Cwk}VmQg!kn!c~ z3i{`=+f1%Weyc++W?NFjVgpW;SMK+^d-CPf@^tLo#*gC#S}~iG2FwD?U^(<UY~Z11 z2m3|qkBjAZxfI-=+R9e@e@%y6hgFJ@J7d-SXnQ}W&+Xqu+1(-jadeFe=&1f{(N5A% zkI7c>vdtR^%KKKMlXdQYx^uCZ>!*Njxs7>V;9EOf)VE~ZLdBUTli<iqB&*=L1!9V| z!d#|9-Iu@5^&~()ntvVFYJ8<u{|H0D!$J{c%y?nEn&qbVc2jPx;k)o%3XTPJ4$%nM zs0imlvh_wuF6m4=*~~AN{Nu8>^A>h5>+4q<Wqx{UY-m;Dn4d)HHJj<%iEgexNprt0 z&brzk^t^O#3rT-Zy(L}1l)~GxQ|@J=y*@HbhCJ^;5@LvZhrQZ$EI?+mKInLKjc>gx zH=H?SbCOmDPyOJHBVp!b2<x_7@a0-)BBNrj`?GY^bA8JGGMZk~b^z*o&uh84xzI^Q zWXd7({02MCUQUK;GM-c}9=(1J{pgWr{w1yEG)@10kR~1($T1TWYdCqM{5f=p7o1sH z6{>Ly^@ZiEIF~}Y@=|f-%vc1ceh4}v;<-FrUbS3>C0Q6KA!UdX-od*<<(d9Bq;pjW zidQ*-903-%uT#$3<p>wyvu^_PEt3BB@zxrGA<sEDG0xz>Mo?mL`Mbt%0*PWC1zaaA zIVThF_-EU4S;q-L14H4rXOZ_?I0#tmt_GYZDcw<{1xVd4-Aee#IUFc4zYYKE_=?*f z!j~o%-`0<RH5G3q9PV}l`Ftk5N5!AoAZDkJo?tc3kGt|efF;2yG#4Xs(FX4T9XkV> zo>y+F08{D-U)IG-W}#VN{x)*=DgAp}hg*01L}vgSy!6jXX*{)y7al&3$3ZYag8zRX z=aM0r{?0pSkYH{)+U~2J`f-3Zi+yDicmJ+KoG*9Xzpj<QqwXK7uI$sl&j4aFQSKct zXQiQAPX%U`(!41%L=bRJqr^063h<JDb8LVx<nND<iH!fv*c}zwRysE{e4bsjN{ewa z=2XdBH*nVgYXdazUzaR#<;x;qbXY(hjUlr%46Ob+R=Vz+PV|4=B9+1|x`cS8>E)v@ zkBMq7u448=eXPj0wyhfKvv=&exdzzS147|ho)EfL^SO=J1>=a#ciuzX`#X0-pWP=4 zA}?%G^LzB`nV4*6e(o)@K**HDjt{L!(S3DW-v;We`0z}s@%BONOjHOPej(?k1gRTw zkbeF65t$gRnA3z-NAO4OW(Nh^@Nfvj*71Gk5Rq`brZyeN4cKa6wBoO)nXZamZ4GF* zU)QnHT}&n!=$uzfaoL;=*;97eIydIon-~WPJco8=b8lWKpHt!|ki-a!9g7ZDKKj&g zCAEbBp>2)<Hp6{v3#PIbf3p_VVkNGJh4;8ve{I{%yyeKnCPo>NQKjM$^Am34b_J*} zA(`3p0mV#gnONVkP*EJNu%!0;P2jJZSxku34nMZTwXN{tK{&t}0S&wrVEVf5iDD=3 zQx3nr@!Z3W%*R9#LE1p0O~UIX;Z`jDYsn`C{tmV*&sFQWMo98LUv0}frow%ww1SoH zq4b*kxYpBx?e=bqSKH8#=Q`xxJ*@OYH~g~4Lc81fn-nQAhw1eh3SW<F&EGyT$_(u; z?hOF{n!rdM90ycShKL1Or8D2WS7YB$=cLSAl$3Lv092)C92;Tkkm2nQa3|e#psgJX zJ0;)i(S%1;x3E#alFqH2tpz6Q$mG=~$y!gwTdz5HT#XoDaa)Z!hI~i%dckJUC-Fg6 zce^1XnR%mhGMA#(gsb3r)#H@$3rML`J%q-UnnChrUi5VYgg@#oMa!lV3tR7Rg2)`& z5C$mS8Bebc^mS!H)Yk@`*edBCBab~jAjbHS^oMM<^uOK(1L>>LHq&*7%PuW@7u{4< zE3#Eraqj=6y??>>#+)^Nb<xx1QBTLhf`oRvam}6K6D5|z3+Ogm{4yW~wkNK8uSglB zEpDmxNnN2u2liu@e(=Uky_<c!gcN-?Ag8@qMK(HauIa=3*3WL3H78_-aO8Bg>)s6y zyRTt>4qkEVh0i|gH-Qseh|<ip*UVcl!PfSFxHR^UbZ~k=#PNWV@K&WF?S<*2HwAC( zlYD79p*Kw2KSHd4>P>@4XgowOj5L9_K7r1{QGs}X<J!wF4BJahWjfoh&Q&eU%__=~ zKU3>H@AdtP<Z-U%*-l@^UT-^E#OFYZWS`iLKeg)gir|Zs`Ay&_`E>+kWveumzN|ZG zEVNTeRo*_uHY}2UUyP{uo8#5BzO2<J4fD=v)5Nxo#trEXKC(8A{GlER#pn`|m#v0n z3Rf*!9Kx2YMzue5r^$aA!A;H(KA!TP74Cn%ld2P}%pS>5F<6LsPvDU)XZ+q9LMiaw z>G|2*kA;ULoYWotzfjDsYXWhZ!H$H!ZjnozVKP4wWja!3O*dGc9w{zviQrUrACpG= zFvIU<8FQKN`13GaZLq}EkY-p3m||H(1#8)rUpG)!hvj1AeD5BWZ-1A()Z1dX+f;96 zZZM7J<S(mHYU=#q>7~Sg=NK)*>=vH648{NSx89O>7@hgB0PpX~*~{6m?yrD(SxpIX z&WQLB7ww0mAHSj}arf_EOUDi+;BZNo2NyrDBm<gH-)6RpmpjPq*JVD2!0Y_&gN92F zTGvpLzb#*76@S~oLdE~&-E0O?0STny@ENzC0<P5xe|-og>B5d&1kS_Tm%o_o*uXaM z4|b5tZa;VlGye!<&x9@$5ngCE9M4|25P|vp$njoyx)Ac6AHG!g%t)XPZ*r>V4pVRl zA1{VktgyuaIh3wL-P&n$$9YvSDYOU`E_!d(Nl22TO1{y_-Y4Z^n>0}NRZNX*)(?@j z`065rV*qP3Dwukt+nQ-?$9qRwukOt}c;c7KG=orXyo$zck6e=1rB@>efS;$vrC6M8 zkHX2T5~IBEI4(V}4Fq~IKgm>2EOvIbZ1%{c39s$m@J2zu)3a}U$Z;&|mYQ?QBvg5z zD<35nH0F_f=Q4A_(r!(+a3b6wF+>BSzPbv2xpSe6vNA>8$jO~;&nOv!qDeFM8dR_8 ztBPBwLY;^kKUALd+Y5^8v|W4KtaU5<somiS1&;m^=37~D0t>ErwO7u5_+)NZxNbJj z=kxi)n&gHnN@Oo;+>6ia>EeC}YMZK*0q=!-PmtS7B9|oE=YksXv#D}z{O{vvB?ot> zWc5Uoek2<r7S%J>TkD+W7xh~}4~q_?R)x6+Yo+D9G4CSj^h+_Blg?8SFHEk|n$~BO z8HlCF{g`vj$WmX^*4HNTI%fzH#8JV4Py-}`q)2GGV#`OzWqP+mFwIY06x8ByyvwQi z34SV?m3`&vm2?^9g$7oeh3O67`m}Rd{MWPgc&wWhP+E@chLbA@RN=mLb)$-6_ax_a zj2fmtS<IMyO!ZIOc`KPWtCA`h^bzX7;(m=%-DX_^6bqtN5HD2w1am_}UQ3+wO8ZNt z%6-MEv91gHerhBX)RJLI)O80Dwcifn!m(k^msdeyc)FkB+o@@>UQq6)XOhGfb~OEp z+pt~IiVU|Hg$Iq%qrAj}1eIGM_ia2_m)hASou-^whcyyCTJ0INWVQMeccndzw!FAk zdChn5-Q6G^5i;jB*$_w;O4OTg<ud-Go`i>YnWsUPEPr*+WJFUD2r5@!!Vi=a%z3Vt zVZ)F6+pBAFPZZl$5^m!TG%?^f*9)~37eDZ*2qFy|JoM$ncgI69H{nO{ryo+r2G5mm zRcmg8NDq;{ps1XBhhDeY`F;>1$Pqaw-7)qvfIdPpc9^YmndtC9DhCK%`L>qVl4jfj zsqX}3MA#!7>jk+U#@Rh<tqOxXS!{!&-7g+t6G9PfPgR=BDT)LJNW>PGtSvP?dpl1n z*B*&AzyC(O7{%h&??$bRCGAMx>)wkBP&<D25f-^VX9ey$i+XJy$T%yE{*dF@Q5j*v zdz^Cmy@xh`?icj?V2}#xmN83xSlZNDRD(nTt;B@Ou$pJFx_J{{V8w9d6J_3<cH5BT zcJimNW(mx`H!B;>6VoCC)^Xn=sZ305ami@hmU>+9U>%>e4~x@OVM&)H|2C)w+*uWh z#mTQO?{uFl{Imx2#U%(u&Z%7lJ#t?nSaaQ@%-XDDfHj}#4$`r{@y$xP%~xHq*jGuD z8o$mlkmK(<$hi@eL-#TTPsD{NS$i5rTpdC*tMS6cdq$r-_j9x6nC3x0SF7l?dUgQ; z8$k!s8srWY+QRJ(r1nM$Cc*0RQyp^!37q(eQ-DU7$PFja%`~Qz9+wxRoyFUJTeLQ} zSeXk$=gU7ov`ZKg9tF{&5@uVDxiQz4#4$WQB2o3@^$8`q#jt0<O2xIg1y}fO|3|+I zl*Ki%|IVCr+RgfeFIM9cVWN}=3G+`Ik^I9LHj8Yj@2?hwh<4aZn$*e+l2JplQXlzL zHv7(GWgE|$G-96culT$yN+|eX(o+i58Wk`lB$g+aqRI?Y0z6->$*SMpR;O&^<ENN= zCc7mFj%B5|%xY!Ctai>pe)X>I#mbqqpflPG`n7Q$1+XFgX+cRc)t$<QDj%D&Zw6}h zZDH$AxU__9-If(<Qr;1s@^p>RIfvZ2Oiw>q4T(h!Lr_G~c~QO1%e`%c26QLlR#uCh ze4m>pc5Jh?DpL<Hv(}==B^!(h`Z=ww0zki(&lLdfHbr84k1|O3bM<7a2C4-rB#x$t z3Q{e2c+gtoH0N64L0h*N?I4VFN>%7(&aZJ%RNYZ$+3SEV(}j$|DJxuj&hMd+R~*fO zRdfun%#VFS>Q{=3+<VeI`Hbe(LnjxPSVk2a!mk{@2Vp4*oBJg1n<sywp_6f#U2<bC zsVP(aI=P^db{}DDS7Tw=R$JbQfi)480uO~9uJy%(Z2QPT?E8Qte&eiassds(|3rky z^OC{x%#bRX$ye1fY9{4HR{Yu$j=C6AbX`I}gm%CQ4Xm}yH(tBeA&D;|S9{NVD$0IN z9}^b}#CpJ)HKNy>C^$N)e6OHnNEz+dTd!AKsNxFH!OSRlKbU60v0-^O_Uf#JKJs{{ zE|tCMGk&bD>7DB%Q?lX@cm3&%#T6>(*k0V(h*4w{>BynPB^<xQtaX`<6gf+uASn?o zWZ94yiI2yz??1%$C%4tdtVrk;JZuNg=D$@R8+JQbj=>8r09rG`Rt*ejm91ls5?9-U zCrvY*achO-ZGHtBbLSUF0*kiXbzWd~-AK#Fb&r$x8EuK2Yvf(dSQ>=-Z9R*Q7<q&p z_tg#bQ(G6NU4k<@wYt$>;cLidq!21IgT4>OvQ5}^yNHFO=W%!QR=J4?p+TlVpK+!r zEicM8>iBI}5edj-!?3H=vN2t>0Gx8!7;?>-w5S{F)}5L<-K=|DU9rj3HrzYVP(5KS zKmX<Kll*4`*Q9yb>xYPU&^}}wxgX*K`@10FzR23;o(HPv$Xaa8(!9zT^^7Vu5SKcL z$7wR_PJC(pELt%<T%H7JOmx(dxX#7%<6MEg4u2CT56*cw-Ol4|P0*g!V|{PD$^z2( z8B3$Xm3)8BYQbuAnx@Zmpb?5Y7JOVIm?kX-%AilV?b8=T4j5-8FYG4D@wA|L@>-P3 zb7q+JHkx@MxU8o+{zF}@*{d3j+tSoxo%Ravn%=FSJCR)tQ#lv=x@nXPbTl_;r|T!h z%N$fXsY&{cuzBz>Xa%+|9W~|8?|iFX@XxXP@W!~8LA#23=$^S`6$wp`cD(c9R_g=a zu0n33?a_}qw2>c;xm0Mpw`bzzjY<R`2=wNVxB8=m6o*j13Hn?FdghKxYzntoIqJgA zbXD;C`^(04?I}gcdczyn6MvG8?b>TN6_OHjh@eM$-DtO}N^$b&8_7w%^-KMarX{9~ zdJih<dcU;JQT~$Jk#K($?rZb%xzIiT!Xr5Swly0D$c>Ci-}rTj=~kOWJm68Si|TH_ zgZY+nGs>bd$7o`uJ@s0o^c$4z#9FF^{2ki7MzLP@u3VTyk6Rq*dXPS*%m5cG6c><P zTk%~f{U|>m(V24C)1e`K$!T>#a3hh}<(;`EyU!b?Uf=RJ0wcW!WibZsdBY3?n?+(t z@v<(=GJT?Jy0ZlWB7tT(g?6n%?>+dx9W?R8cN=AMY<rXtx9YMOlxY_-Q5mtAzv44^ zWg{13-RDeMMv}bQ_wIE5{2Bfm8-oAB6kF8?j$n$*nN{R$I`{o(lV`>7zP7JQiruiz z@T;(iOoy5QEv?aYDtM<fLWhk4M%o9uz4z;4Xo!Ygqcv!-gzlKNC(~imI{aKBNF29= z$wP0%SG4;0N#=wLO3Htc$bb$%wSHK_vP<<TBQTnS_y*@K<33^@*-Fr{I<9Jkxhe)k zsmLNZDe7d+F(Yg@p5t!xR>~;%msk-yGSMsGZCS=M9^(BXSwxb7maIG%SAIp^bb@zC z-V?)kCw_PL_{BUvzCnRcKxbk_W@`Lag93AZHVCWHLqTH&OX>+gObjc0?U0CiVXMIZ zro*%a--)F5iHDl~iN;D?*I5+X2KzsaLB+ntsMN#(90u9MT;pCes5+{T?G`RI5Pl2h zs|x`q8o0Q+5ZfZM3CVM3N`O0equ}zxA(_Q0eeclg7rTl*whaieF#UkH;FI?e1SAJ> z10dU+Tm2}J7&giaAxF<t(`O6`pZy7{u1>@4!1E;Arp-<DW0GvbI#G_;vV>-{RowOh z+@^}!5?9sNE{8SRpkCH)Ao^Y_Ta_ibJP$ekfS9h_d5X(%FS#>RDl+?N<;Gn&8G#3g zKIBf29<a+t-1-2ky@VE+ZlLZ;S~xAT;bD+{&>L)z3DgD88Xn8!^qKMtT_~fKxL$oe zJ^3Qa@S7mCX!z)CChUR@fr~h|2^j^xWjzm`S!ub14HR1<oLhu!<zp^#$+ZBR-_@!T zy!3_bWs)QXjYu~|bYx%)&@*5Gg%#|hIC(kvI`0xZC?=#p=TqXxku~vAJy1z%=QC>h zCK9n(2%xESXKH`EIo<vpM~ej?Ths3ciQ%5sTKpz>K_}w$C+DW3_FB-zRU_M__9wV= z%=k8-=oT{UO8mG_XDgJn8WnMBc*+v2oO|o?8KbM@IqX@^(6@*yLB;oy%>~5XYBJoV zn)IoB{_XfDCwghT$6}$ewx%}aCTU%Ft&0gymF(h~sWRF^eo@uDuDbedo^HN5=bN&` zYGylX7QZgK%BMJp<>*mD&3B0U=Xq;>GYvnsVd?BBf|uW`h_ZRF{%D5BZ`it(I!loX z`n?n?%2vPiRVf(&w+%#%doe{WD{eGfN#<HYi!JkWGUtM2Z#i#0>?hjf_CM;?l9`l@ z7xIw_(sEhvFJ-9s^k$)yj<Og4xdepiO>Uo{pSHnc!#j0fQYUo<4LW+}O0|Am6a*wv zX#ldU22eMIdY(9Ltmj(!O31<P&a?a+*PCZv`aEGphAb1#_ldbuC1TWGoVL7C)ZYm| zH8}vq(ikAdeUMb$jHy2RaGw^>o(f`DB2`3~{89NV@bt^A=TzN%UcCFV$(5_d|N2_j zU3Y&%j}b-0l~^<x-D>w)X1dh`g_zX6iROdRGdAY~>GO?k>)r}np!sAub5B~@*tcsh zhJ?Frm9ja>_FHCOteCz*E`!Vow1E&3`Ctybvefd?Zq66u^oo4=7w&m{+r%kJt<v>> zh2!`feSuZsRVV(mU@G6flJzGqMSmsd^t#q>0tgZCJM-`5aKID%g&%x|1D%mf_Y%;) zT&-$?9>FhD8@37iA)Yf^zX{HT2)zCnJ72(f@G3R%89?nfn%W$*_NVpa-V@OF0zl^K zSg8@v{@o}tS`PI8!N1&C{h4#dG)lw<jD0=+Uo|1Ye}4)Uv&9r9c`+?$t?$0Q@dCuC zaP~(RbSDo!;dYJ#bs=1Us2PzzX)XYfScOwXxShEG4n!iHiO=$D5kz3r_^)XYKVhA8 zrQU<n%JfDgP$2ny72o{$dKK<b9efwqdJSU3=HY3CAm^U}*%8qNlp7!cUP#OXPoB)s z;1<_2qf_0NFHdI*g5+>VSU;3&db)Ikf=@ubN1PhebBO=$p;h<YK+|lPDqgAVH-Q!N z>2v{sFJAsKuU#VO;duU-B)}&uape!1IKCL{;Uuc&7f<MGEyVA`iNH*bl}5-t(l1(1 zJ21)&y>2to{}?J+BTysrX~%Cc!(p5C*5Xe-DZe_mYJB_hh)43}Dj+z8uG07X;)%O> zJfkmQ@6xps$7Yp_ZY1F)91Eeou){^8NQVYm`Ox$e*=Avb(_flAvZLH3Q-V<~WZK6r z>c>x(oPIcQdEGsIpP4i<U8_I=i0SCrc0~>($40L&M=5e+*}7b`T_7DyJAFA`3f7jj z+|yiMnVv<oQLCiqr;^M$OiRl;KE;c=8PU5IzWa+{hO(o7)P13RPHfac`ng-~P$u0T z_l0>)&PX8W&}Q_g0?vvbh0ug>FLVa3x>yU$R=mv@Qy`$VZbUbx^AZ+LT==7f3?Ijg zqt}eIh-Odv-rFbKxw3Oqp<e4(|7PllIq_|Z=(>{jTTj`3=O3-|z+5YX1J3S`mES@+ z8tW}Wi86m)`((f|m)kDdh@DP-QfXt{0&U_9bl=T(9Vhp{i~Ta<9IOElw5*AMbDA5k z9x7&v?vI%kWr}@Ft&4p|apWK??~l&Rp>MUl?ZV<|!RsLOj);SYlN`p#SZN(Y@Y4eA z5N%frWsIo(_)Hn*X_S-{p3Of9)6x8JZDhl~Z#A085N9gzPqWLF3_wfg3uxtZk$Zqd ziv)xsA46_7TwbuD%n^@?#Qo3$m+WhYLuv^_FYCFF20D(`^8ikM$Q1tzbkYe(-%0={ z^#5N4!?cX~;QX6lF$#|Zt(yMwZUIwU2$vN{9zghm>N`4CJS?aFDvQaz@%OhS;qNa< z#qBF2&ZZ(LExHly#|FkrOKxAiCg#V>;9d5>JoaTf2TnC!2bhrfaC{>Wcxsk>r2_cx zoLY7H9ljTimxMlgi$k=U7ZWIlWt$ESY-hKpj7*=rL{0<W`)0tGEByZ+*)>QELtc%w zK!c;&>0!R>b9YpG($@-8Y$dmAx>;suIC;luO`g8Yq*h6aTVYMk&^LW<7IWy1;4v?6 zvbjC)_DOr^;@$bkxwY>41=-{w?^<i5i-G1!eM>Dut9^t$=Ydssb7)S}d`l)BB&B_G zML`SeJEDx)c%w*y%UI<u#w%cX;tvf`5A?c->azDczB`XXth%U0-CiV7@VhNWm?Ubt z(uiG8_Q|PFEfP+^oG4A&VmX{XQ7}Hy<=~q9EV0R?!|{+SdJK&s^^Y0+LRll$Xu`^f zO+wMfA)<pw(QFjf5N8Ob;Es?Flvjk>Nzh?DO{@BiJk%&rBju|K=_@DoO^0`{Ia^~s z<40C}A@3$p>H7T|8FMB;-Fu6+)LOvAG^k~*ICG7bQ7SjX6*7c;_<}wPAwy4b*_xU1 z!mz|J-DuKwuz<<a!27Z<g+F`Tc+2P`i9tq+9RH^*H{ezF{0?Mgy6K$%XU=T|8{Jkz zfL^VaIAg0JT=3+v|9y2!|Ju~di00H|jwo*r=Z}8GDP^J9w0;XAx(TI(4)cPv*LBbx zzehDw&k*r+0>dZD!aIULni}hj-U>~IJWN;@@YhaA^;})V(_gS)kYN(Rtaqfl>I0r< z3Rd`#!fypf5|Sr!YHg?j+~OzM9j+J+gE9^<XP^30TTPhGkghpJOg1wH^!f;X3kOky z#00Q@lxisc`c_pq!@)<mrjqcHLQ{TgqyY6-i=agR45IYX2MgU?D+|`bw9u!U-)M^0 z{D@0r8jYQ#8A{}Vj)kW3^jX$=<3yN7k0m&Js>{Yi7&dr_y`MJ#rqKB=s7{40nMf%$ zD$#qj)t_^t1hpksUAfHuX(-^!pNy7BzZ?WnXVq+sJ<jK8dci6z0fNi0=j!dtauO__ z;hrYFKPIEeX-ny^r}?;_(Y5y29;ddtJSSq_jteZcFo#j}o4aPFXDx?bxTpEbWo#yD zj%gHk)65e}R;RFX+-2i@Z5%pC?-$=LjUQpVb$AIrRvT~UncEJzjwS2M^0F_48TLT^ z0_N<bO-4#KL+ofY<cVq;nxmXskZFQS@6vc2@Fe2Ex~=}Q9Di*Xc>4nxz@V8{h9#nw zD9cgB``hiDRwAaOhkXc#_Le%cJ6e&NCYt$X+|6R$aUD-qMK2Tux)twy-R>q;rC<>& zdBFe8mHa-!pC(>=P|VX4F-b30lWd3-Y%dZylYrgHnan1V9Lgr8xAx4sUG^;tQnp`Z zBV)6se{O7CU)q-?E$0=H)OLzhAjN>tQEwEaD`Bx6ON>lwRZ&N$hiy*~IzNS%m_L76 z7iAG1;Tcd6X(Hs)A`EXxUo(CD*~Q^8W@}l+hm3ozqRxVf_n>^;#NKfY+{PSfa^37I z$-D1UZnIu14KH8#Sn;e>?L?icz@oa&q<cmvRozxD#a2!CCH7di=<4f_cNdnm<9&|H zj8xL3dfyi`-?VdDq20k#U&ewQDA+>gt$8mqfR+pwX!o3S=mlfZkWa-EOD(ebZ5PIL z`5}RnBp1XeX^TLz-9w|s`0r}b($WLqZdMxaQhwP84PJu?ElEAGIGW?2nG^JnJ!#t8 zNqP(8WAg`Yw-uv<gkpw0KBOAP_JZ8xB#oWlbzfSQn{da=r8sfPn3U*cmJO0;e$+1K z(lghaRtSkX8|nA+f{Ar^&w+RRSE|S%xE8$`E4Nl?Aua^O(I*!a5d2l&ss`|0X=FCl zQP0WWj?pcYb_{Dg9qD7crpSJwj*~9NPvu;-G24+i-9Tc1KwmSVUB)2Yy!j6%Y8EAT zQ&Fz2#@FhTR1#G>dVC)xg|l_9HWEp8Jze6@T$MSjg?_M}i9htUK4{SuQWSW2A+K=8 z?LkiX8gSN&U98?Tw_K<+@Zl@q>+{NE^z16)s9>lxm1a;kOi);5n9NcPA=A;Xt7)Ea zsoHomcg#V%*6R5->Ekt8A0qPmU+;U~2UpnZq7o>;yp6$3-yfCK$iGID3POJ%2skPk zMVV8WHT!PI(Hh9R(aZ%==BT)_05~<utMsSekRzTol~-YN@8aCCK=YN2t&ISq()Ypg z472;!SiC6c@`!p#DPE;5F;Bgy6WF`80EPPbJBNMMAp2SGcx|jD>b+p<e$AEr=un=I zE+y_rR{P}55#k?t5=~ZeB|JV~Q<9UW7t5DocJlVWIz%lAV90GOzMpH;IvV<LZcZJ0 z8KGBY2SwK-Oqsk)lJn?k4Kjbt7x1teKEx^KK7mT5r@g+=LJRrMO>YI(1AWy_@ma$Q z4Yf;>Uq|nnt-sX~a}g6Do}Qz8shv2D!npLkTp0l>b2<Zt`*K{+a4N~QW(^;1?^ugG zAZEegIb2vpZ2{|I{4jNeER>JO@ch}8)e=0*gEybj5p*uzwn^HJX7<sKl;`*c{l#6x zdl=Mz8PyYCW6^OaaheMsx)X6Bjvyb9>*lp(7EFBD`5DHpX|F<|9z9d~_JNs4T1*qI z<k1I{$JR%s6D~k?g{yvxY0J_#tv0J~mNPvfv{=c_RWI|SBHCZj0t2>Y-_lZpih;q8 z!?OJ;raIXk>qXyCd}?brsfixN+taO3R0aRo&S9{Zb%Noj$hYDHW<yvg<X-%D2471J zp)cQiZ?-Wj@vnF<)9l^Da>v3yg1X5B`fmpM+cIKyYdx6etav^UCu(Is^qHkDc^?|L zG1MiXIA-*-Dj+9;McE{uC$4KeBSC1va%Ii__I%LzNx_isRAQ0~S9K%=9U^_5ZsX-g z1K+~a{8BIN0=Y(#?CJc=B87$N8=~okVQm2iQG!K9p<75YxIG&YBc9FLQMA*gXmdok zS>$MQU6gnw#)5aRw{1C<C*1)7=T}Q)4EhkFN1L`GGRJI<sKdFf3WadE$ketqPF9&d zLTa$vP1r6|`iK#Kx4bvlC^J_Cy+wFZ6diPB1<YhQXN~LcG*_>X3{5s0F4?Tsn?@^L z3lrPYb|tvcCr0qi!;-#d?|a7aGhAn|e+g_4^)@|N?J8uTXq&#C%~AKGHfZ*FoET+U z6L_$f@-vrFLRDArU3d2`ZLvI)ER7pU2F9`uU(=H<Qlzr?vKPjj`Q<8oE{&6dg<*m8 ze9ye*WQt9ai}VAfcRs4?Jx;b&HtNw&ezvw_SNLP=vB4`RY2I@~%rcs2hZLKHwoc&& zI+9qeV`bA`Odm%)dqR}w!pJc%xt7)(KNIen7xnOMp$D%Yk7vEdTXoS<)3IgDW6&%i zo}uhGJOgDF6@#po$WncjU@|IPXlYrHSu@1c>wYytEU%kA6`ayx+C?W?G;A#m?5M_p zjsW!ZT=LX~|8teDQFyb%v6NcYTB}yl=&;!7!B_>YjJ%}xdC~J6_3V<L0a7o|eL}`r zSwCCJ&Gb1*INp!kTF~qW)*AK-0bS<fMS{TZEc&v!p^alTZ)xY5avlR{MovI=`T++D zC`fsYrwm+0fvE<H7{{*l&C;KQXSclkO~764svuCXsCOdX`gLE{!S?QtY_Rjk6$sMn z5WH<gM&Jm9O1Q-+QY~3-u~D=tdle1)F=+iruo2AtL2k5~WVshpxx3Qdhz&aNTv%SR zr16p*a$T|z1T$=~BmVAXA(><A*`tF&O&ewqI>kG?JNDGdV)q8`?@c3G1F<J)aL=&H z9mBrna?=J%wY7eMjw_^@t8ZG9EbVV!nb=&C#gf++$I6$b=s)<};1})QCHa_usDXrN z95FX-`i3D#zlnYE-A8UE?UZj5nZ5&+hTUxYcN)$b@L|yET;ifStr(XS^iApXGP<cN zm>auU?tBvqi{=`aACHStb<FY|dpgai63@Xb@e8X<Iggzo`((g^y$XOhqq+pod3qD* z*gt)&V>OCEDQbu&`cbxG#K5eFKk*{CK8Du!cJ+_hJl_!s97J`<uDBAQn*w+VbKRn? zITE|i<&5iLo${orsgE+>0`RBIw)0G$tpD4<#^qB0$E*n;!HtSQ7s>w!Z$y32R;rI0 zgXLyz_g8FL0@HX1UuHYy{DoqS>i+JeA+-1#jjIf4)MCj>ozFtya+bUM^Mv6Dk3-t8 z|Kadd`ybEXL5Z~v>PZ@SyhF6vKYo4RQ;T&e?B6&C^e^F<(!W5K$zhj*Ig4{Qn?rxv zS`ac&b_B8;vr+bsW{jZWe;WP<Yo0w(1i(rlyg&D8crYI5sZS*B{Nzu#;5J8|0P50q z3fy!~Jp2bG5RHXABQ+KJ_wa^h+omCRo2^(c4F@vhFX}p1Tv;xa%H{rP&Y8UOKcB$E zC8i09pAh|qgP<XAF^#5uY2Gg*te<K@D6y&E1T7So7<gZ^kSSi-4|24_15CQ8T=M-1 z`~&v?3dSwf-T=qt*MXkXkvxR+DmqwtY-(Kai2X5U!S?`rrFp0v|38ha<`7Kg5a1eH z1EPg;E}h>6Ns~9`nFQ9yEs(9>|3Hdc50#x0_=9elmhoXCK+;k_4v^3gOCm3?LGYIe z*j!RYO5o+f4?uHuyibYcMS3-+3~r}J@LptiUED?C+z^hEO~bzg#(;y)Ca;W{{==E* z0e^NKaz-R_dGVWI+i<l3!YDFVXzOYtPoUo-y8-Z{*`Jz0IAs9F{sgY=<QF`i4HFKK zprgS2+4~LvZGxx{pqdryfd}@?#I5c;)gr-3hK!LiCn)UPi(IhH32^w&D<8r}UAzQe z`argg{&iwMk5tjMmq~)`1R=p&^9gsV`zr{%4ox-wzScZEB@})}jJ!N&TUBCIyaQbK z6!IK6of!u+A=DQHtz3_vE?)!lEBpJ*4VLGV@PFM}f}f@GNZer>zDastG8{nWUy+C8 zkaNHYH(dZ>81U^H{mvg9qO$bdBU^kt^geH8!e7H_T-=@hO>jsBKR*Wb0TIS~!2DcY z0-X@;mqY$_gB}Js2@-u_3dqV44*J%3!Atn*Q`0g|&;E}>65z{5@O5neKC7=YK-ik3 z7r=zY8&$@^oP`|8p6t$vdmJR+eA~2>`R|8K?)gub?bN>q7SpwA6<q#~?cgSs_K%y_ z8hHS`mj0Kq9scRQHC4S+1M3Z$6@PyVbk~@<cKJb@)AD~j><xjyj^%Av_#$Nc52;Az z22h{$z`V7+aH>&nzojq1xe%PYbFba1@#4~vFr-c37?|}*oj83!S0<nWL^HplMgRMm z90JRLK7+-O*&O1X_^_%ESa~JO(=74gjt2t3jP6LwyGS670sZ*U51&a#o;^%h8kqxk zn2#j16T`xWx|lLkm+m3zv?OThO5`4m52iL~Vw*p|B_)lWF&a#L$H6E&x5S64q6zZE zRK)=67g*HF#%sw%uWlx_)C3f6b(|B@AgF%rC20z&8`U%W5A8<k2Mf1sLHc8colD%S zjT$0niQOs{l6+cLgTnh-lCYL}wZiPujnimUPD0a0<SEO308G=QyUu(l-TOz8Ilov& z=AGr{WEO8dW|?8Wa<>=|!Y?{VYo+Z^X9|t!#4po_*&Ei?a`tVhCALLQ@orEFs+%Vk z(N78PscUE@O7rnIq;X(#n12&IYl9v~eugu{1o|7S@3XRwF<Xu0PFA%ZPYG|N^9hX; z)jLwl+%h>~wu??Q5*JBc5f9%i-eZpD@GLLl?^p@n*29q36$gp8r4Drn(WSUH`_wg? z&snH{F4vFL9Mx!WB#tR<WaE#!MJ{kijN1vXXPoE=WYo_{bk;9{HGY%wdnKjI<xsb{ z2Mt+6LB?(Q2E~J{?M;PY=C}FK&PLv}{3*_YdctWnp2;Y!!NNP=$R@pFdnEac>Pq@p z(=fFvmzlo_Tyx%lZtMhI!JKrZDl)oJz;b#(lnQqO^OYS+E!sXOXuo70Nca}%C{kJA zxS#-S{yxl{7RfFHnFk#wA}_PrSpeRyT6%~1Tvrtf?Z_5Qc+`xEN_ZZTKk2O#C}cjn ztT*K<bdPG$KlSaWit*Mo?zQKstAjDS*Bek0pl~FGf`ErYHq|J-dL&>J)zvYr8_S2P zwfAJ(TBN=%f2-8<u4eHQKV#VK1+UEz_KDvFb`;dmkXwj`%eSqPML4+9bbk9x`H=vr zuJ5*mn571v|L$JJ@ML-HafGq|;QhvX$*<9~zt)!S;XF)1-Or%LmBr)Jlpgx-9+{<m zdd`N{6X~Pilp<z6E$;ElyqAi}cvAb*hn_g}_S2s>w)&3&OU>insjRK(0@Hbecx@T; z(F(()fWr-9gXBfdCZ~Xn&cG@vKy6!n+0ZFOc<hS6O24c-&e<_fc%zX7^|SW~RQR&a z={_L%$oOP_NI;cSsbsl2svmi!ohfAWHvv(*+|Tw~<49L970k9Xn;UC{zlMo=<BcS- zbWZFn5oEGU4Y2++PE0<Kn?5VVDa7%~yqRGohG+kB0*u?h`W-u9$@+W2v!>|24;4X* z%~mdZz!@h{I}X2)@E@Mnu;GsNa(Q8}B>D25zu+9?u1n+o<dAoj+jsoHZvsqZ-N-CQ z4_obV+d1zNY)BVdSXS(efABdS?I$+k@5f=Wt2wUf!s$CYTiWWv%sKrFd+~)Et`P}) zhr)T*43_FALwSokn|-)$N(u)g6`45kX`~8Sq)Lh~v<c^(uPgVm(%J`E#dhnkh4nt= zk}JIpMZ5dhtLFt(hZV#mzT%1cRHm`i-84O>S3b#-f{aIE9#KS|74-%ab&OzJdhuM< z=MVbY&~9Y7_I(}%684D7X>b7Qc1z`2ii2;2A+=VGmfxvneD{UjIP&QTAxy6u6}7{L z;ZalMYRFz9qn=U!Y^Ati^hSP2SLo`(-1}%vvdhv|weP1|>z{PiC|e*mK~Qi)yCha} zFY>6x0-)`}EvA{3$Am9@y!;ZRzAx0(z4t>H9;e0#MA@bDT0?|2jLE;!cY$2tv-P0Y zYzXd_0$2uGs%|wFbp0pY5+^S2wx84vZC1tbp(mNxH`(2EC}VzoT~q5jRsZMm7PsTs z7YguI+$HZdr1M@5i+aX=T6MVTIb0_aFp<Dt-x_P`!!VnloGLTt&C~l{p-SW{&r5$7 z8N(vMTd1g4_e|R4j5h<don`EurwdePn`0PaL<{)FBg}_;QQ+C|o*aU9Sw~;%n^?CC zc5~@iS4rloYfh`0{(=%ZBRpT5CRk_f9`AXu%~jb5qGcYM>X-AINKsw5;5y4SR&QfA z;(dNrT!3?b&Pb)#7p+j#Eo&8QN>e~3f7Db*a75Z3%Oq=kejha2?YbIAF>kk(a|?eR z$m6N%M$Y{v=xOe~Jb8`6`h@|JwJ?(j3nbn2SoEVr%OMs6Wws12l4!=D1<T;fbsir} zNLaSQWsV|K(0z>Y_JE61DURD>zAfN<=h{fgd=~$jeLMef*1lvN;yE49uV2;5%n~=2 zwA%B8^J^s))P<9ho#gp=T}=3Wf={>{>zrK<_;~mh<qHc=BMC!27*o|7$14pjSV~kG zqq@t5=(P*@5gake{3ft;w>kATvxzRFcyqHa{QDIKby|bQpBpofH0=^Nc>s@rUzxLY zwQ>Anx>11|ws;g}klvZsP!om@R9K)(E-{U?@bM2C)e<YMzt#RM0NzbOcfo*hh}-Ln zM+e`9*{WkABNKd}#mcmw!*`nV8E8UnOvE(USqP(u1hOgkR=`&_S-G)6Y%D=mADzw? zfC@ftgjQYg@N9yrj&w_P*c8JnM0hYVeJsV{Lq5%ydv8xEPXUAMm4+Sr0!KPLUxwL) zUP~YfMBN#lZ?<Xvs``WA4#UoC>mklLiC0{$`W-b|t`BR6TiG<WzH29QN#1Opi1lo( zay$@r@%Q!%Yp>k*Gi{E!Fr`xE>UTd1Y9TVDRd2r<@yJ?$isWsNUUS}i)1EG`3WM7m zf_5GVs7;Ac>7M?x;0gut%%WEXOBXDc1qh&N4umae2O^!Ss5sMwGv7WzEUBjevY129 zT7Of+A(m>T6F1L?@8<J+lsU7NlC^Go04@O3YSl~Wv{WSP1t0X2a`Core|Pino08)U zi^hULf5jo@HpI;<7GCaOX9{Pd35O0u?}cY$8sa5DuR>%oY_SLmLaVPKk}$<{{pr>R zD|_TmBK29Y%jRoBJL6hwF-v%;dRD%gPn@RV*N)1)Rf^uKFc8AHAyOic3KguXH;E|8 zLF;T!bbFqWM>E8FdvZl*qlr>XrcnwtTr}qQX3y*A`#)foZ=t;$1zqW~%mbD`7$#pX z`(>can>11{syBj4%ndab)`D(!TXQ-{RO5u%I?LP1GjkexxMcK)HiLEbJ-rIFjC!8A zzwH{2&C`}izdea1o2uHeDOyQj!bSC1vjg4Ll4Od#yLDC$;IX}`!<lRgqvn(@OHJlM z_WSX7zL;4>b4!@KGk-)ue)$o!QVb_S+FMzGNAXfYl2|b-=jjrkqF&TqtrZ@%66WoH ztEP*_(^6d}zJKoqi8`sGoVnFcYr4^p`#e22r)LajI4yK<3{FoEK9Kj?9D!f|ZZBrt zeP{AD%NO4v_A)J(8|%uaz>@WPI<Cau<y`A$4vAHMlN&KktZTvmI)CmjoDGy}QVj@o zskY93#dJGc_vXWErEIP8*4U!4%LEu-LhiF&W{Ls6cC+~`bN$5ii4SV#Le|)^!2#{9 z$ET0Ne;%OvDOJF1;XlgQd_xA%w~bbrf;O!u(dbkEB0t^1@;q%xTZ1f1(3Nu+{PYt0 zB_c#_A?VrkA=|G&y9pu0C7as0fn{*m9GBq0hM+#9pDySAS{ldjd}3+c!CpMD7U!V2 zbO&|};(^WmzaT<U|MP57NW<54LaP0);>GOKooz_!1kkoOdAB_EHU8s3O;AJBeyOZ0 zMAz`6IzMGh3*uRMolE_B{X#~IOa1JKz7^Zw7$V_csNu;b6^?#y;gaTTM%9cu7xR?j zrZk(Q46u}LfrHHdFAz0=&AE8lf9VJL;hgg?fR#n}DacYUP0(6Nf8EWnrHG-Q6>()` z?0*`Xz#eCdSFQg|VDg9l@RbakyJmgIutLLg{QZrG_U_~%*2s7Oh5dCafMlWEN#qY^ z55Tq!ED3Vcd;WzZ4T@szCe56NpA`#Jq?&1EwKR@^0|+|)Hzc|7U*t$i)Zc)w7>SZj zQH1<jTTM6uz%jwk;z~a}%?J2T7UanR5LEOZxLWLQUZgCKl`hJJZ7u=!#g*v&<Gb>H zUU3^s|Gw=6UMb&U7I>xm@DAi5hY=EW10V)+V*#92jh7gZ?88jJpY^+Pn`uysKh0W} z2KR-^kqBh{>uLdP^Y^VGZUsQmJsBh*jryr;HZ`VUmwg|+!<T=bVI-MK{nu*dG5$#8 z?|A@V$)5_OzX?Pj7>djEoWHNWaF8gh<No^U4o}vy@FFtj1gTB1{J$W&hE>SvHJ-~L z5q#LxkSWl;h4q)StoFY`l+mX5Yc<X`VJ{>Zh@AKv(gQc)FE<_dFVL$wciWoDu%h2{ zLW1!1tULK$TGgr&^Q5W#zpfb&gZ%SEl$g!`ZXCAQL^nxlFxfu2M$a=S%qH*Wk!iaG z<YE2AW{lprzI+i3&=Y_X1W5V*=h&OT)F~JKg=rq&M1tN%jDmiU0ifG5g23{ReI)6> z+m@z_fCu(NZ24#yDjZ6(`A3<-3c%?Z{fn}U%A`O1#0Kcnhix!a`j20w8{2;o08khJ zTcXm`yr}?8V%Ah31AYwowi2+rOkw;kB0)PzaP7eg2od~?Eq+$|Fqga%s5&AExeE{u zLL--6_)m?^I||A`@{UE$*~X=shc|&yJqUYF0ni#7`u`jPeak?m{B?IzHY}FseB*Q` z(2}<QB1j8=iuWe?(}E;#MS)j3UOwtEZZ7!<NEZH2{}P}+vK9e`ng`BO5^p>`!v(M_ zr)0=WFUXn_;~%q*cRMkVu+E6wZaAcEFw6eygVObXj5Y$kpId<&!Fs&B_ouP<n`uc% zH+(-}nFuK3DuKa&6X=;7t<`NoJ}+NnH*^B}Bz|i)0Hmk1*+X#DhwyhO4~>f?nZ2_E z)87P|?=G)~jLz*=qd-v!=tY4ZaG{2ctj_lP6@Tq+k6ZQjJx&Ljw$NAa`BAYdE!yqV zOv|JpbU`|}+H*Brdv}+4WQC25U&%J5WI=fin5<>C*`n*&IkZ(uKGn-zDl8EYRfr7n zmwh<b*j%EWY$w^ShRye^YE0aVVa~`HM``UlyfKdO>=qGV@5#$Vgu1-gQH0xL(sXd7 z<v72dW)J)#mM5Vyr<+c$FvaP(O?{gAJvwq}cU-{ed8AB!jJkz|yENRf=mVdR`6akh zA%iRvvuI|Lr)OGXaC5SVu}@n9Wnej@cae~45~yflzVEP4G&aOOB$LqjOV1*@bD|8w z7+VtA-D?n`eT1A%-bQR_BYCE#v?Xmo&rkXJJzv>P=>*`j&;n*5*L8snXVxHfjP*No z25ru{q0+b;&&*Rq;;=2WxFAX0Vvi>v%I>)!_U0AQN6+lvW#7W;)nW-dW|k>0#DPM0 zt(ahtdQFo4gd{1M)OW#b!v{Us0l#3^ee<Ms;*0?r*EgDLk@TuLV$(<`(Cma|uzcs{ zs;+zwgp>mdk8-<EE_JHjGRz^L?f2rG7vYN2+!|lp#1dCWdAS>>5UNRJADn}OVAYcs zTv%0u%M9;fODpISWptAMq#&~zR7js&;44$6?;6Un!2d_`E_hM1$UiuI84V`)WI8P% z5fO?PaWgTmbapR-4eW1nxmxh4Y3~Sd4S$`uwCILkm*I%^e6i1fXUL|fiYc=AZjhxt zIVF7)We+9=qH^SXf)OR%--oq7B|G6yXau#Bv(9C4G-$RRFscBn(FMM`I7EMJ_2#2c zVTr$!z27bRcZk&e2Z#y5PqI{`8dA&L_5(3mSF7n-RWU<o`Unx9KnhBjxPC+M4Z8$0 zFX!Pqd9pqBKOP$iWWIQT>b$OX&C~)*;ue-erEncHqIvmJ0fg;?&|Eyg`QP}kLh%OA zG!~hZXZ_u&T9iq#sbsmIto1n3g44-3H<5RplV4oocw__*P~FV%l}`{_MVTPg(W3_% zDAO(%`Tlo}<C3$#e8?;e!u7e`UA=K@`xR~+Z-6aLp6_Am@ybp2hi>O&JZGg@@sOxC zE5D<qZ?yWgWD+-({-zA=r)^M|)a;a>h>Y!7R^Fvdg|Y|}vO$Ps4T18aR{s>4zI?te zg;Ek9&dJR6JQ1h!rYd{l!3>#2ar}b}d^`7Vg0XlLf$=J&J@O8IoQ<;1ZT2@oFOum3 zQVd<jyxNv4tVToc@RRXqeFmgB6353SPD1Iym6KLO<P{#A;+A@*Kd5SZSw3g;thnuv zp0ixoSV^z+$095eh;RvA>He(p*f=~#L;A8=OSB1PD!Xh!jEz98u3+`ONV->Q%wLl< zL{DX4R+-N{8=rlav@x-)&iq(z&oC$*JA-aZ_uU?XmT(-1&?>%WaUmBT7WH=(i#J*` zrE)qj@G9an%Gv!*@H&574_mycwM6~Ofl-<TOu0D?)Y@J)L>$dzLz(Xw`{+v1HYJMN z6tk!3Z2PK{xp}{QGxU0J@YR|bEA%5~uLsNwvoM&JjOXY{gE(U;Ugwz42n#Roi1>L< zqp#)<w+y}Jbie-QK`cW<{9}GsbpT2@Ed&24$U;bP^*WHK@gel3z+<{il;)uhZr6v* zWV5I?5~>z%_u{#}LZwt0hbZC|D8rjpZpXH>T^5rQjsVlaPCC=(Sen<%STk7Pd14k8 z<`#xTV`$&c4oGO%JiYJp?wxVuvFcmVs%}M2JMW)pF1;dQpaH$qwR|qj6RN`lD@3%V zgDCsltKMX@+Iv4M(zk&gc#aoYXR~MNX-S-7MoSD)nXXgjT3!0O1zbhZxYc6=7kKXs z;E{ic=SN1lEDDG8(r&ywba}4BCR_R3kv*{NMX#eU>zrC$)L?W_OD5R~yQW9GD8A2J z8tBxO?oKz!^DFtOb^UT`I<G=8rC?D_=4I;K6x*Y5BZ32lCk3#=x$40V4t~z1?c(Hd zg@;R2lZ9{Y=nIj}PAn;J1ZQe;h+q5mDDaEb>e>LItb}QG1mNs`l<F+g#Q$d3$s`>7 z0U5jK?$W1?alNR~o?eS@FXB6Uf;;MNRaKSgL9d#$-jgIUrO+em%jeP^_!j3lm9om` zyd^Q8vgZfSfja|!H@De_PPq^y+YVheXo7P(aY%haa^yzmgWc#g<p<-=InMQpb`uu8 z&V5>(@p*P)t?wF7DH34a$5*Dx6{!G<kTQr73-02}2d|LkP&!5#YwcG0SXemPw88nT zdv(K4`BBfGU(bg<6=H1cJbzOPoum7Jwvt-anttlU-aJt$$mzHa`$2aQ${o+C!g_z+ zC@Y`kQ+6rwB`7K+36|MjZXeUx*k)9q+chjNA1JNIhnPAokeZ(xN!34dBUgNHY1lDq zO(AHetzTFs_r7E-PbH&A114fiVzjB^o(P^(EBSViT(HC9z($T`OK4{e>2K%6R7EPl zfe`=Zgt$U1SH;vu9M`0^H&%r^%g>$*5UW<+s(f@`(Y!NVgxeySs<!7*4G3M|hT3^F zuK~<sCYWh&KxJES(J*?E6g+9NzGe2bF%`9Rea$X*80KR1Xz>5z?mMHJ(6)7hsHijn z=_M*v>ZS=IB!bcfq<2seX(H036O|@isR}|+dY2NA8l@_|Bfa;QAVPp7zU8@R3;Vu% z?ilay`{RIM)?9tf^388rh2Ogtb}ciYPu2#*I+Gn;tKm53L~qB)nADt*$-a>A-Xllj zy6LOwTE3VvrH?AXDx>FXPPDDR=Nh}bD%BW$%A{-9f*lhTo~bVQLj7%_gy%pfpDt}1 z(OBtqda!z6ggCvf=p))R!=bzQr_*eHiu{{}*Q8fhd2J*J&9*+8M!a?c>YgJR1rCj= zGM+xM_nx2z`L{dRuhc4f$0l-{lxM9@=lXEvYerIB<xHewRH|Nl$H}Y{Df1-DcV#ZP zzdXgYDZykafb+-Bb^1YfCn^j3M8<^eRVi{up^~VjjjPi}iGz=XZ=a<w6moqN(Ew4w zKOxk}D$i11@c)jaDaM<pt&Tn{cAU*mrZj0auZnT_UQ}qh-tV=+Uyyn)hCz_cNk`>= z2RU>E88KB#2J9C|WfLL{Sz6bL8p_OFrE{?0zzmEoG{;X&zULnK6fE_MxTtd1C4xSy z(yvF6FRnVUxB<$7V{MtDtkrOxE`C{0J?KXHu-#@%BE>-~W@wRexs(T&sqa1>Q6P3& z|2Z3tCF`ung$E-G6mqg<7xLvRuZ-m9ax)b_-Lx|<f0yi{YF<$Y-GI?{;k3jw6O@x? zu%QZ6*(JNO#J;mSKtX3y77@He&)=n4EP`^W-M_LhtOWq*r+=%>-NY9HZ;Fth#1Ca6 z5fn^4X}AzFnk)g-#JjjPf_~*;H$fn!D7@8jwGcgtSTWmx&=*gm_sQXeC-4pfMF*S+ zQK1_s*1wD24*ae$db4S2`veGxyCZfknYllOfyd?*ed}R9zzm<8%Yo$X6z`t{)leG{ z%L-}7e|dI23Fx%v{#CKo<L75kTlD{5nEka1jQc`AYkcj?vsBYmF5=ypy!eZIQ$G%= z=MfFntXjC8aAH;Qb}k<&p!5vnI3yzO;iGZ-Z)z1CJ}6b+#;9yTMmyeofsGWl9mRrg zuv%i0SAIc$tVpd8B@hix*`Ov+##A<LSR51t8eb8^Wod0Vs3vgTt9(=iYU6+arO(zr zA!HjqWAcwE@C~-%quykpQe-)Thjy56x4OKkhDdLj{_F%apRj2Vt+v_k0l<C@P;+R1 zCmH<90-uorfsmy>r+&P{+YirV1af0r_=MKWXr66aiQG)Rt_K3ZQ;6<$_-lY?@OXZV z-4?Qlo*}CToW$P|oJ4x=ibUR^2gIS8c<UQi9mB7EJ0J+WFF-RPzFq)UjXtrQgc{Ft zfWRMU9Q+O{{~5JpNAC@GuKG);VJpYWlgu<rtol<-?E9_1Vb;`sfFAiHQ5nx49fFvb zbRq)hpyWso8Aup7Be#bqHts_)nObC%Cek%NpTe3vUWvz$!Q%V$j+G(eCDQr9iGDl; zcuVy0VK3UIQ6(S!Ef0FyLi6^T*Lf-ri2N4LfZGH3N3dJa!+`xeWWf6UBMwBQ|6T!e zp$jCT&`==>+hMiTv+Nr!Ee~4Ga>SvJjV-kJ2$s$+bu@l?*9`U9Py}j&N2Rx=C&otB zdGw<|Atn+3oD&c*qf;OcLA3SH==qLqC_{B{%E!!Fr+2P;q_y>>tlnQH15tgo*kfby zJVxmXahp2UANqmtIr{S>4>?KNnSGY}p=wL{e*(NWD2|KCCN|Ym)uISx{xsvL`CH0Z z_>KFgU7T}1`w7Gss}UkmmSoFt6tdAA(K^XRZ0&RV1!1#GH1v*DW{#rfUzF0l6r(aE zU6~ikEp%8eIAfNh)P}}zFaLsYHp~K@EMIz!XR0LsgGS}1`mOjezZgS5>dE487_<gU z{Uw_D=6ieLq;VK~e7U*AtswUhFV3*VFDYqp&5I-IPxICmULBIWx?=s9Zgvkq{yr>w zz)upd;gTCz92X<gCYq(9edW@lIgO*fSzRqY-M?gBYF4dMvL7v&pWRY#(k$Veo!@J2 z0mT)+dBT25fyr|)EG`2n9x;$)U~dppZn9V@T<oW3h5%PBm8^T0G%0^(e4bAHIhR}= z;YhnXg)F6(HF?>fY>~IPcCMyyc)&ZWYfAc8dQ(KM6W+)gV-9!U;s&LjBkVg7jfRXY zus}dIHWSV0Y4P27RVI0yNBBe7+R~4)t0NUDoUdN#JI;}eYMJ8_4=?$iBjg|)se?gn z*UfrzjhPV?tNMgTv&__s!nBH5^%$li;=qr_`F5v^)t_Wsl0ygId}zsYmFA2q!8irD z^%i6%2Dk-k(X{n>2E*4sso59FpDNNT;^pOiOX{BOd9}fb)K|M#)_n$XeytjT=S;dV zYQ|y^KdU}Q?vT$s^B1|XMn>=L%i(RoDlym2D`AwB$-@p;aD#D%9qFMNYxnl`6)(it z3mbXALf1%7v}F{{0`jtnV!DIF251I4keS0es>44&v_ZRZhRsepTMb#3mMx<<p1z*1 z6ETjJtgD^*X)A17=qU3#u@sj+H`NT>QoQhxpYZSPyDtVE-JQ;?9cXkGH*B%m8-~-G znDF0sP)#x>5#<szkS&v|jl7`T5v*eFLrv-Xm=I5t@dXtVzMzB96tIiFN)D`@H#N}M z=!OY);SE`lVv|<3VS{0rppNi!Li42?k*&!NmsQ!C=bkmnc_NzNr~R9Wa4ANN|5tC} z#GIS-O}jF2dt|yb1Cp$rO619Fb!v<AUX|Oj&ZSB}#LJabl{>g~sry=Y%W?XLvUsUl zG~u1o0#+z8D+tm9qg&k`ANh7q;?7BR2h)A41it$XO2MavXwP@EJ);)dM+~zi%M@zN zWYSycIwd0kxHd^i{GG`{fW4uko_1W^nEgikPd?9Y(;|#B{wPbi$VZB2^cLcM?$u>W zDst;Qep)E2wkyH4a8|zU&hESICQbe9?aai$dPy9zrFtu<{u*8g7m)Aiqc_AE-SV^^ z5~4k%g4C>wG5%1)rG6nVQ6?~$+()}qmBlptW$0NskAta=!9!+W>coaATJ!@a>M>l{ z6<^-m6>S`c$c2?8)0NVysBPxOMD3K5<d?^2uJ1?nesQFe@I-y*#>pMt_9ey1V{~Vb zQEpSwEXqOtmrQYa-FjHE=Xleny_4q4EL~X=?d_7~$`n6ZDKk7ku>&q$qZXz!*^SqY zKr%Mee>hdVj*u=4w}q1~TfheH1}I@pC%R(EH2iLYY8P)u1@6Dr2uz*bn2+xeo++_E z86&8UEN$nG=)mYb`CiLzqx6n;F<LB}w=Lb{LMGzrc-f*sgkV*l9WkY)+?8#3)W)+M zOV4I5W8__&6k%iCRyXRLmywaSdjFnrV@wLnHkXfs9ebJjnZ*@cC}s*I#{%v9`V6wA zI5d?Dd(b-fQUc0mD$7EZB3FPJ`;tDUd?|)iNKExsJ8Y`lD_XL@Rzo6^UMn08m36nl z%-!rm*t8=VJlh*-99SfGLxAJ%r3H2M$FhphyQxb)>enhi4Gbtg;+}A#c#>g#JC@cw zAH42|8ou0wOd>Z<stH<NK%Ryd>&Huvb_ZQ(b$(LMQ(qI%9)+cN>hGRb5xHp1@xYa< z*olA6R<a$`FCxrPLp;YmPo44S#g#RuUaQ0qBMT;sHJmAw4vi{aH9Ao57DhBM)7sum zHHwJ2mH&h*%66ioQuOBT_uInaqHcfH7F~$((CmKf#iwBQI?%i?a_(WQb9rGWbwH!F zQAekeaj=F-`HWgEsM?fwj{YxPQrwjmmu$^A{(+<gz4tmVw3~FJE~g-@Eh5<*=`3)a zm{_1!yp%+|oGL5qszl5-zXVZi%HoK7sgB;8bB=X2iYH8&XDTNIwa3N^$i78>7TugQ z6=>Y^7r^qa_xq;uVr%y-{=y(bW-)~!!R4m=<tsucJ2n&JPFK+suD1)XKHn6-ENo38 z`+3?F=QU?Z<(c2~ZN`am#UJJrTx}Wl2sL)oJzEt%@>u9LL!ykgP+@zghohadSB9m8 z0Y*#k(L-^i!`s=fao8eDT-h8f1bf(oEUT}YsR3bj(Y5-^8dAFO(LHaMj>@N%Qds`N z;<z#sE~Vyqx_ndB>uT7smXAL1lcukAGlLta2c0H$T!B|7EmJz%otM`$S7Y#w$Dl>8 zj!paYCtay7&tdw6`!hjb?t5`Y8NF%Kq$dPkk@1w#D=~U!aQPjU$<k3NuRZfjuR66t zN{&+D6#}cDE2edZJtz?`3=cnRXXWhW_((F+U1u;{RghuYtM|iLdBk?&gDcE>6PNQ_ z**3^{F^vEOjElyA1cy;#;&gaB!Kb;}cCg%$Ts3;{&WL$!pWTYH$CLX(T-&!q+vIsW ze=wiVI^|L?>v*%tLwg*A#<0SrzKk>Bojy&B48uLP;&uZ3>XOeq72l?^j$EW<er<8q zv5)c9nWVch-n{FBbEcNhIWAS<u47$)Cpcgh3O6%noM>?&I+ej9wBN_Z)MY(rRq{^| zK!uuImkiREefOIm&drEBQQ@pLX^RsSoO2nuzrGWk>lBbw{gTrqrenC!$KU7tj(RDg z=9#Z_>k|vj)w`G8EX9{R*&VR;xh*I229(T+SCrRI57$d!DHoW%q7zA>sIS9RZJ%;R zKVOKFWpt^D#l1c~W3-d6YF~$job1P~EauCk(Cb{Qn3&|aTE~*NPg)YHW~nJWU0e6y z=THd7<=j~Z34_`m&LPM7nrC88=2*@Iv-ebDr}cuD<%^j8IW6!HQzW{{9In_+*CgwI zs_WO4XJF*uf3YO`#lu<l{R0QFkKMFQYjkR1vzB6`DzEmJ!s;*kk`LoebA7dNT65$M zeh3RRsuU|UF%?#LTl|~#J@%lwTGgd+<Be^{C7aU*<ZcTuY04e8zfX~Rnh)fp8=$T! z(I)al#}`^LyEdzBN<AL7JXh^ve+@I-oBgb;?akhs`=SzgE#bv17vxfuL-N-r6rbfy zU5_`c<?qtFyTZ-A!S7?@1`953*}{p`XHKJ`{@)J_qGx>Gj+tPF102hLL1@|qJLl77 zODE*dDcw6M)9S)ycQQsGwD&|yFKiz@od!iQHWddV&+kBiJ8>65cweiUZR9D{*fX}) zJ(FVMbB1^D9kpDHx*fgKU2Bz$;HUDuiGM|YioAhaMYA<ODHLYwUb_=~$sqFTY(}Dp zl!rsx(CD!D0W{N7W5>S9)3l|pOVl{5iBG<TCeZ8gV*G+sH}`|0ICsbL`PsR){bHQ_ z7J6wH`W4WmYB_p9133>*t-dw6xp+D}ja{_6uQLDbF^1Wq^n+I*hx%+ih?>D-{gHFZ zM=G_e#2vDmZtZj2dZjSKkuKBDts0=;h8(HuI-Y;WTmNA!WmNQMU}95rw)NwgynODj z#ddie7~V97i31y08W>D#_(;g_Xy|{Esd}}>ah54rsUmdFtA&2P<uvT^lp4U#{;?SH z{Fy*g8|Xpw4xM=<#MSbcJ>_OWSJR(iu3-A<?Om7^e?Sc5J1V*S^c+c%{nO)!;TizL z<#{H4%tW&VI{K6ru(?#xTG*n8AQ2k`O#imu?B8QF*4P_%IlPt;4JH4Eo_GFlmc)JD z(Dj`RmIoEv;-=48#pX^HGqWB3Mtc4+M28qqAiU{Qe1JnN+N1tyO<2s`N^Xitc{t=2 z$wO+d`Yyt^u0B4%JOq>{B_+d?|AHt;ki;LGiT`Fh1vq*!267U+YIOxve0zG`AlN9x zMDDS{+9&>w&hs)7e4+_w^I4wBI32g(!qzy%&Iv}x@80+Ds@wCnf=?8AS5uz=XoF!q zDM-6WJ9ErD1th3{%qf9PP{Q@llnfJ|qPeXYZ{{WcuT=*by;;X+7d+EM`LiJ39}FZ7 z<uX9hf6PAbe>k*(SEaM9D3Nu7Pk4zwuUy>NDSBKkD*$F|85Rw`A_)OO$3Kn$5H<d@ zBZ?BjAWN4qg+p)oS9K<CwLkV9((h8Scp|-<4?kwCW#$3n@jsLkGIsVvDpy82E~Erp z4!X-Jr+fj8Nmxey0I$N{de7+;=YNGRJ6j2EMIl7m2|6O+2_+=8*Y&uwn{50P;4%n% zIKe9ZOyz(D(((aZ6Eo+BfD<4BvA6TPqro63E^7sFz8{`l^}Ph5p8DV*MB>+UO58e? z`Wq_(GzPf@{^AbH+hmfvMi0kxSM%cWaKfPkNw(P(Kp1aQA1oqLz+P=I{eb9h1kv>} zJ$FxNGc9*Zbcj)0e&Y2f-g{{j=LEEfG?Y$6&sG3cSA=3-Iv{?uzz+}jP7ELSGc4`A zv}{=a;lQLAcS<4Tsmg)=6i(euYaa)o*|wybrTBZGhq}NoW_ZwdT;v^l@1WwB8&t`e zRbJ|+8!6LCi+P@1OZtyOp;W((^(g{4bPi=j_Zt-kBz(#Twq6@BX|6Dv(UNJtK*48( zdf`hm01H2oMky1uMU(@++ae8o<Q=fomAAmT3<0zDFh+~cj!_g<u3O@DA@4;<F4F~) zZ@ngnqXB~deG}}CR8cTBy*HTSC&vJZY%OAwdcmw1f0<<pkBuf0!$!0&EMwAwRmWT) z)SKPfH(25fY>ws{aWuI%*f!B%-{m6@*6lMNSuC?8<a_XB+OU-Cih6!~a+YlL!+#ez zgi|Np03MzCsjd>l(c&AVCg+-XdiT0@YATdn;f~k)2nZ+nNbSQq{xQDjWAiW73dIu0 z2+qW;5&?u^MQk%|=Fsa9m3}L*$gTkUV**@S$2XMt5u{unek56c;xZ4WOjY=!!r5mu z>-(k37DyAwZlUF_2Cim?V6rAZjDnsRu{1W5tJ{bNMETT;LbW-~7E(&}r<je->phb{ z$pU;W6yLB=Vz5>S8s{N<?HA<RPvoKH?}Gxeg8AeH*O_6L9qb$1<rMJ^wQEPmVj%-7 zc|}Q6T`#r!7bHe*-B-+vL#FVQTKb*1bc7v8Wbyuvf1-b*1uJgM8FO{F4?b#WjK&5( z&-=m<JF_7&i>lj2W-enSBYLNlgaE7PYoVdh&9jfPgQZObzK;3U$Y$(0o%OXLR43}! zIZ-;KvSRIqby?^u(p|IKIZ_s0yq0htQFr2QP0hGH-}V_9&j5irC8O_mkCM%G1z-Yz zdcD3sqeZ@A!8B;v^3-sW3j2VA<El(cp&&3_#CSs<+7()v?$l|Rw0JHg7*tdSZ%<^t z5$w%?EzA^;ih{4dh;taVjI2M8zf|4lSbH<y4nZp^<fAdTHP*;bP2s^PgBpyEn^u-< zu1C7MJ6wF8N&8T4M0Gy)P&ufUJvVCloupa&slcL1=GjY~^40H(_*K>J6sl=R^6XW= zv$pQ$YeQU$%$=@x4Cvg(?*)GRp7&i=)?O$1PNd!B9Szr(2#JV{34LZC<&#Tx*VOJD zYRz_(-~}-BsZ}#b4%^A=gLtW#xB-~p^3zfC-JqNmvATDL=ULT#$`b}ZB)XL{)S^); z(~52}b5Hq^Ukq^h*ciu$DhL~D4qNZw*WBeS!J#=T344i81V4tqw06$wc6-fL(pK<% z!aVLVd3nB61R(2!AsprCc6UG}EX0UY<5XEu@l2BzMf*K)#WpZ!mRCE5nKw&~GF+1_ zt!U9_bTJLxE3p<W>%3@)T-gePV|1a^h=#c`EH9pJuccy=6G81MY)QRVf-5sJhpUF) z?&Fa%$sBA@={-|?|9N5G<m$8_!-f}s*R$KAI7WIusOY{Df-RLMPT+^C+U}jKDz=#` z?WxXTNWm&Y@qYa)W0QDJ#u>8SMs{7s=U=8py?hD-viW~OHqN#rr;3GVv$)2~?2JB+ zcsDt)QtfOnX|B@vtQXY$1tbljKc`OOJX#o}4!VQ3Mq8Uk72_IA3oox&sEm^5B#Jm) z^vu+WId!-9Q;Xi5>7nKr(Q6zr&4t8kxDCNk+3PFV%H3`(`U~qX$oGJzRPJPLOb|NQ zy*L<6TPrYw6Z#2ggvY*0o+;WA&a6(DT<@f;d;0_FlT(3;;fm9sfyn{nUzihkCBMiL z1$?jIs`4COeb*{#tCm1e;7{cs9(cMoRI{nG<W~06aE9x@B{gpuE-RN;H+k(uo56<^ zf<kaeW~6r8U+(WW*5uV_QlkuCB&)yfY8z8i6OAuqSa|RYBG(CfSxaaCQ*8Xfdd8fR zq-dO3KDUNel5hf*i{;~uer=1c4}q&~l(2rS0mr_H=TV5C+o?hi<Q`a!*e`w2aB19q zQiHC=(WQ-e>Z6R(qjk)ojm}Mp3SupA(UYb|SxciTZ6Qz2P>f_=Ewsj>8(LKfp?LT# z`4j^#&l4~2ScGf10HeaBM$4_p+XvB-Pbkcr3hM4tUVJq9mSS3|0`+}$>SVnLPJD*9 zDLNW)zDSnRY6bx@R+W7+iYs-^v!_+0yKY)8_0(Vpqbl$wW{kjd>rGd3DnnazP$HT0 zrh0H#=GkV01+$Ndb-V~?HJU`p{d(3`kF3>S5UJ+WbIyz8VXlHtZ^q5#>lVJu8UOfc zxn+B|Q%Nk~ON)Q6rY5X?GFMYgO;uv76?bor3C8NVPrS4~=+1gr!&;+ZqW*T11RZ9& zUwn^Nn8K^VCv^5%;HgXT>D<qB0NIZ_y90<xz9b6TvczfoDkQB=YLTtVL_O!KNOH^& zZDQ4QH#pgN-7iO#KUzYl4VqH;e(am4?rs#$Z`RLB5mS3$6Dm<?Wzs9;E}vyz&rmCG zbzzt2&E46iH1zQk$=t=x06{0(1a|>*!yvrVG@3PYCzTxgG%>&EZBBdksz&B2%{aOG zC+wnW`$Ea~f_ZxtD}@xr^P~-szagtMleg*FEM0XSWfEWPBR3ycu-7}X>2KGB*J?55 zcvz+>&{hVw<7RDVHlWq#>||DyG8I9osJ~YBVAfg8F1)5DJp9Fyc5>X_f)|&IRdgq3 zw`pdn5h{w7E9fM|W{in9TRpnv(s}k(Zp@-m<TEkz>K(<_OEz-|`ZbV?7!p?NIAcjV zqJ^MGMF;KFtZfL>C*SOQALh`4u43p{mjLjBy6RVoPKUuUtkSm&&q738)uOPU-0l}- z19EIiKLcoM6qiv_yeN~2uy|PHhineLca9DN31OnB)WXM;m5b?f*_5NTCB~8_D0UGm zB`xN*WgUG!y-X!4X=@RykoZ&le=X|h#MKq5m1i5oTfT$Q`Z5i|=<w%;iKMnj=1mm+ zpd|SQ-?BF>z*gA(W$%o7c0hOBK3(C5eTryKFSVLBuRxaNpVZGMFJaMvweakf`is3= z8}Iv?817^Sb?z7(INZ>g<c`a5t}AR%r2P~;DO;-4+AYfHWCrxeAYbtrEm{jtbYm(< zN!h^9Gb17*cTqRCgX0%nG-Ya|x;6&KPKAzs$}PY-ne@Y$RHsD(yw_oLHNn@p`rO6s zxK~HXtxoXSPU?#VP@K3-9<d};^J?n-f`!b&r#C*b8VDO+fhxVmD&?s@!}-E1F3o%+ ze4FJ4J%qhr{{%C-kWTyFgE}>Jb`!eh`_2*{^|P-TW_-lu>gi$V{9A&g^UAH%gfky0 z5<VDt5loPAxL=T2!)EGJII&f&mr6fw4N3|<5E>3Ow5TjE?-i<T_d#4`=1ID8@r}am zFd8QE!i{I_dfnI|>R{*vU-ubPbB9?xBWdGI2A2KZ=yZaHFgYsdC+myY$f0c|$ISQ% z-{#j&=OgQNgLjJQJT<#oX9g!0U)wp)QZv*{jE`Ha_L%y8SZaH2(l$EjPD4oUi0fuc zBhEbvy%M=#J~wAMMmD|GGC?|BR0ottD!kkfDpF^u!Ns&0G2_Pqc=iT3NTH)=%9LSN zZ7+>tYnD8ows!c9S4Nh0xJy}5zUk4)$dlMN<K<czwU}Qu&uMmPmShwt%CjRR2Km}e z3v_?%{dNJ<ualzO9+s^sJFtS1WHM+Nba}siNl}S*KH+kDoIZ<itkw?@zO!6kDYOUC z8d=wTJRA$WNPb#3YOxiCu#lWD*bsTQ>N1}Z6K4I)suv0@Vue2%>3;lBW^SW$ATr0! z!U+^eY6ND}(-oxot$mZ&(Clv9b;w-Rp?@o8tgp)UE=sv17k#887cYIQ)mxmOF9L)| zAmYe*5ElD&xi3;$JJ&WNaf`Eb=Yw}KUYxfHalj1Y09MF2X6YA%clZicdDkA7{(e~| zB+3GD&eHCHJ<x-tq=$HMc{E}dQ`hly?b3^(O;t6o{)V6z=P3fX41wKs_Hif(7gB?a z*-j7mSt}<Ryfm)SHFKt)NS|3?Y*o3)!PCo%M%hTc%!+j}%`98(BU+VFYVkF9>CI_= z@Qsb}?-Ma<&@r_5W^V3~*Pkc*Fbr7M#}swtBh`FGR$=M6KcTx9Ug##-y>iA^Xb}cf zR}AOK4;$ugt(^RSnqx=hU%;*LM|rld&-ZbfHMLwPaPPITU8A@fK@pX`3IfRgt3}3n zyjHQp+x{KX4O*<EhCKbf5bhB(TCu;RIpz(JM|J{9_CNF8fu(fJR7r-v+{s_&Xq$W} zb~{-5i-K6wUH`0S*VO)#l|(95vvU}*Vun1Li%|~2UOh+g3T5bOC&aGT7<pug_Wom4 zAg<oS_@GVn8aM-Q^9D=2W+t?Bs$=h<A}MsMV#Lf&=xs{_0QetM^v-GP<K<6=7>{HQ z^#3#!I^8KzsHRY+n6jFuG9Pn|qv_7+PWre15D7i%OV4S`f4CDWQ9jpdwPdF3AhNcp zri|D9@2YOCE9(7Y#er#dRHYdBMUHI-!*X}<yPk^s3%c&s#InV%@uh4~u9)z@bl{}F zB=7_&03Zc0F@?-fZb^mX96Tr%|CqxCL)!CmwxcBMT2=G_ZvIb$>1G3Zn<D_kP7g@I z;vLP8-ofK&pR`Gy!kiBUqNH{4UpO!3O#8gP!7ll~bmCOq@ig|LqPZp$i}z04LFF9} zQm;n+btj^Xf_h*Gel*pP_a1=x&gEYKYIk<k<G(=YM{S|or$MN^NC5z(C8+mF0Zio5 z4aVQN>v_B-ut@>Zy2!!UJr~49_9-d}t|skiC#to8f2I|ri~bxy@Gq`qVBmN!V0oD< zZ>LfI21);gcRr5MuGV5hv}U3SZcg(8$!RB0zU-jg=)(t7eWm$^U#7N!d#yr)z(<-7 zP~s<$FX8j#;C3?m1<3(5ShN6}A;S_8I1RPU%pvqb(RhF0jxaae2Nfdz{M<w40Z0}} z{y??eCx=gg9zbak^@tRR7(jwk4c`PS_g@tf@@x^?WWR@exv+=CEHNCosIG#cfFjTC zsBfNV;!P(YeRv;iUH}DW7kL4nYjHZ*Ae?d>;ywDghs4MN7^u-cPJ3hf=Ozk7*uad` zRUU5OgCK5TJWlvj>Sn~@6_YLEJKkbR5OFU<%wzn)EjOYzjM$lxa{wwgTowwCf;%FE z4sQFOF2Twgq>7adiquNxs-F0gZ(=N6`>FgMOh@Y~6IX;HYE)r{p6j8W<MwSzvwphZ zFMYVYPxAH&rS<~G(#`gJaUT*560-36k?9GuCEu%yda_nKclv}i*7|Sx2jF=ITi3Bz z@kW16TpbqO41+p_SWsvP7-4XjCT0C$$;cB9ZyYu1GABNj=~sO0->Jf{J?Ci&o8<Q5 z)e?jLg)xjkAt`XsRya-lh1FCJ3|UYu$vwyP*35~UHu?7cyc*8JLMD^OwfVNF8wvgP zm8y$b3lYk60<E;Q&>Q}}mL(#Q^?Z1D%+$*Qx2l42M5qA^F@D;TPBpvZM_EIR7WZV@ zp^2fng8H|&TMtz&q&~&v6{tRb?G7&+#?x9VV7bT9W$<QGoP=?4M(UVW{Q#<U$gQSM zv#YCbe!Q8zY=x2Ieo=|o7m5#et7-(B&fvR$>XN;~z!YN?3QfYg-ic^%OE<({=@Net zfZM;Dr?VHY7Pq-?@<QVmMEWi+Iq+kArZ98Inr?phd(BMg_Sn%p(RZ2QA4bzdLbf=s z^s7k<=mFoNE0vSoDUs0O+31bun43z&wW>LIMXX%tkSsLQj)f<0G-ZIw&2BMjvCHvV z3Q5#(d;e|z%c75zY(GL`_z%*Fz|6`6PPGbNz$oTCM;?Od+<Ga2gf36YmSEm}bC8Nk z-Bap+lpQm9mC)qT{Md1`HYS*v>tmA3c{~a@aK0!Y9-<-spOdnK5jN4xzK+Sw)%xW< z8V-KbxqYKs4TehC&1`YI#2*%tjear9vNZBu58h|0@{nZFb|V3IKE`R?`H*Q9COqWN zVv4_sg+~?pYCB+jnk!5^t4mCohbV=22^(8hlVMwSmtQVch^f4;z0Dal)2`$f+Wsk> z>&slJw{`?pe@QdQ=;rHAbxMo4qRh4!v(lWoYp#llUFRRu#2%WRGV`FtaJXubzKkul zh`po6(OY>gt}bxkVeDcrz|ZA5>%_jZtGCiJ!7gSWvg4_7h8UX}k5(v7|KM@Sec79H z#S9iJB7X2lj>Rrjfc7l!f54$`D)IUQs=C_2?NfcKRIquq{p8qB%ks*NFNdPUK7Tfx zJ2rd{9qwzK_hq`~`gI{v<!THO3Cm=2)$$S<EfCst7kJ4rDv%<w-q)Jj>P=MaP&2v7 zrJLP7bTAx5ginrp3hajAd}bLnOic$+k&LqqxED;1cYJChW$hV99Xpa@o9%q;6J1-K zcM(@d-C|bnmr5l1K)=K2!K#QMY>OejQf0WvqHi{?uo^pPa4qRfew{^|-}NR#+QP}4 z7uKjGqsJSC87P+bQ9G^Vgcz>vEwPXF-#d~6w{bHLi$5o1@5g0LZGKoiw6t9k_BZa@ zxSGcwvyc^6Wu+M(oznTy*pgD2nXQrL=asvYmuYhH6fCAj_0{T39{a|`rL*|s=hTwl z^T`hcUKxG=(<2c52tGo-dke(nv9YQI<c?M-%W2dH<K<KqOmyhae02wA6KU9p&2D@6 zinWpO{gM<G-kPBKNZwCIF9F)X(in^UY#BhjinVx-O$2WpotqYi!vR&Loh#x!{(9|4 zbMb}>mXzvolXk0Yg=R;=3`MboJC7f}SX7;y)n@(1`xTC=Y-+D_-E{!4f_gq*u|7be zg;&50JI<<$oLVc@aQDmgN@XZP#cF(Hcp9tr*kD(j<W0D{v2664P^zg^*mYchMfhiL zr$~R6Z$&FfPS5?B>}BGK>9ZR=eav_*Ymu;*QGGs7gatQmc@Guyjy_`Y5;|2KDj$DR z6_=p<#mIY{{-%Vx8CTkP<~1LqF3}HJ>D?V^RSz;%U6f?|?RDeQ$(Z~!MMzrN;L7yM z+}+MhCO<{rB<<LJ>MF3J(5Q=BRr4Qu5eJ}L(*3)Ak;?qvgX8XLiX9?%dvS@tA9u3i zH722Z&gn%VOn7Z{0hJn_ZI{YUJ3jUuRbJZ7zJI7U{M7j?cX`5@nbWhYT37B?Rtd5Q zIz_?DoHoP{#c(#7*pTLwlfF6_{q8WgI#7fD=TNj!KvPAGxmoKyy6jlqcs374;-hnI zuf6IO;_XhJgVVrgxUtY(E)D=J4}7tAC^NL`kn9NGaGF<?&8Jo8&w83)-FU8yB!T84 zR}j<AFGx7FGI1jSJKV&=7)liO@3G(-+QbVBbq6Oo%D>m(SJ9D-@^K5f-+c9QM0wlE zs5bVu$&1Bb#n24WTFh)PI;f^w?l<+ZAG+BVvfYaOPj_9zP_ca)*HKTqd+#-+@(;|k zjR?EG>Fvlh3{o^6YE+2G)^QH2HDJ)Yq+xD5U@eJtRnuJi8Q$a%BfR(L^K3W3MmIV! z!h;`Y)rDvUGz`alH?GScYvppZ;!c^5DS2hyea$B@>g>XHnkoaF>vQdJAmWk8DBWk| zg<23YpDSmPtBZ4Oy*HaYmcoR>FQi2p%ym|LI)78F?Jzsg6rUk`?-D2JLidOzk?I1l zejAG;yp@}&M-6wc_t&cD-=6oZX(BQY5gUb?n_{z(xy@N`h~IVt&Lw!pHI$jjmU?{* zeW&xAgaM<wh2sS|>>8G>mKV@APUN2bpNCiS?2wosoR)U~rKoo8plJk(c@`C;h>AM< z>La=Mmht;wX)E*XFKY|#zNhD89oj{4x8?Y{&JDiv3yfE8XO*cP*fG#qwBxnA`r%#C zk5sw?37c!0WFaNv^h`S0fp>mCI}y$tBT4|?(ngmp)Av}YMfXlwOfJ83ggy7cDJ=PJ z(lCtPa~Eij$d@pxNzZ80XdRUKbxoX4v9V?6u0VSxsx%cVV)1oEm8*a>_s7L>U&|G$ z2Pf(-?={O9q+rkE1!|&xy2tk#>OWvHZ!{%;`1bwDiIdwWg9b~e-!9%|7^_Ue84}M< z&2*C!N6@H{mpkkN`n~Q5+RhwYFoNCFzj2mDGGo-bt(NgB*8W_j_=L&6RLOV0JZj10 z*b842#ziu5?Q_G8@L-w2c?(KHdJ&P|GsGOjmC89-ymRd?Dpo(N;mW2{XKhZ9qw|B9 zj*3!Q+MAU1171ZO6S|FEu*h+`q&e&0nf2RC(n_-9F+nP>=07UAmY7=j#p9QBWVo|p zVu;Z0`sh^p=}-KTXSJ9qR%Qlot@P!t^J;g|`1jETDQkv>ze_hC4&-m6Iv=p83Dxqv z+2T))3z`{2FyhFXlO9%OOgbI%<fc!xx;nyIA2`M+sa3EWYf_(5kqt1>-?j{pkR#oV z{y0oLyFAI>UoNL<S15aPT6%pH1g7rvTc?g1mTsr2mj`GJ1U0Fp-s(4QciKIaes#)5 zXnG2xPdz3zN4;)yXbK#Eq=<)z2#bsTP7>kdOuoh(`Cf!F$3;RES*6P9bhgx+1v)gM zFQGDKU;EmOybwXy$`@79r?p-4!@}bS-}8O?)|^w`uj%Zevpib+uy_;69DTsEh%oo0 z;BZirZta!~E+~|7`>>L+rkBn?FsR<8{UmG2=H&cb_XXc!;L@GJcr-+l`A?Km2g~@s zwe!gH)ak#2^<{Z5J!g>Mld>gv?`5#@MTS1H8TI`aI^=5R^?wz1zdRT!nbl&k#DzDR zpgM`~5!b5f>+4c7lNN3EQ&rhRZJyp&y|2m@<3Lr9pj7N>Y)SSgMRjk%D833{iqG9G z4I7-W>&a%iRx@dqH#}GoGs?gDjf;K*UPg_Nv5bK3UIr1f)tes-!wt)c9q?^c|GyC5 zLxHlLOBJfbiE|i&ALziAuKa>{ClY+}e?hXcTmbj_W3OQ9DD<EyqV^Z0uWEF;)}5F) zMpz=oclD5%5Xpg7Uj{52Qhf6R1M~}^%7c)~&(FUgqBqzzfckzx7HD`E1)}#1K`@)X z)zE6zX`jRlQH?%0UnKMF98wK@KeLkH%S#O8|Hp59q*cHgffSJt_YZ~<W~784KhsYB z&SI_XgU{1Bf;{RKe2{V8s51VABYJHD{wiMrVt8p5y-%&NqXhu{mS!Pgpf_?-z3?5H z8_d5+<lQ-d{`X1`P@o}p=nKPIF<ST+8Gytt0K}RLAKf7_;*dE^K!c8sIQV~*b>9>6 zF9y`5J!EpgwmIGU0x>VZOYlJw&N}22S%TC7`dDIJH!%=3aEHX0$Ol@cYz49;3(s|9 zmGRFW!$JZ0zYyZQ10)*(Gk#tOSR9sMcHf`d6bSimAMlYzB5w_5rYuBj#mB#kzgs6S z(Y;RTKzv??n4<qaifGNS{B0kp-e5D_J&gj~XCvsXu;raPrG{3m;I8dW>4iv$=fp?7 z1D3ubktXOi^Cw_l#gPmELLs2<?$Cq~57Q4_mBBzG;CmC!dUsBDp{?EXR(XDCJkNfa zc0#2^N!cWw@VpSwbJgi^wi<c{@s%F2mX44aNTU)sBsBrwd^EM!{0QgRuUHu)q#sms z{YChdFP!WSE>&n?U5-P40tHzHGC~{&Lt6%f0DH>2i_w7XiV3k*J)4t872Q-&JwT(J z@$r-Gcp{DKGexUkkh>0+JCw;pT%ialu-=+m55w`DZf+#ah`;}kKM5_X>T{<?tv->U zdBo`(K+219JI(<QcH4g#A(?sJ>Q$)&x1pzos)D6Fv=WaJt`)f+4dr?xdYh#Z#LW*_ z)|W}ch@Xeh%dAoatd7ZYb-9#ir%+&C&U6|5G{k$@N_zryF9ZGa8~SzH8APQ7;@~VW zXZ`vRe`FW&he0;}^_Me^;4i}>!Xf$J1XPmTGL1t|ifHTQ*8x${p1&aDAgfw>>hHC^ z@Mok&Lt&7ves>{QTLY_l&DXgE>4s|YySY1(Qb*Ic030U!l)x|_w$kS#MIBAGkqIGw zGCx;xG5K--t+q5(rmtL74jf0kXFX)s|Ez8F-?HgPdv7rLv%2*bJ_ylwe!RuAV61tT zY0U&amINo91dxFGHO8aR^grYo*K>24gk9*<8l`yD++?;v##H1|SxZT*SRxF9JcSKp z`S5x_mTs1DgA+^EI(Z%|)i~D4Yldwp%(3%8U@B^_Ly?Yv$wukW0x!0}tjTmj`~}JE zrwysy+c<2x{ndk(=vl23Cg!7>u_hCyzSfv|mz$SgwJo>joG3VRlIAO?WTc{NUocNt zSm1Dt!}aSczaUN=i=2P8VVS<onzMxI#3sbwFBq#wR#y)@YWY{<62X<sgGTuY%qDKQ zXL`oozS?>6>7+CcJ2PR=ryV>L#a%zZLnBZ`%I`=;f78Z(ZcGA=;|tmNfe;DSokcdo z11<Qq&aF~=WSNcQwJ?RKQI$z;-j3iMrPjZ0cD$~C>KfC8d?srR?mDN#N9eD^S1h#? zoTHf^Y-eCTjc{uv#|Zxj^h#N1Kij5lHf7&FsgdnAintUpLro>R0cwgea+eots2X!; z#M5(sP**B9_)d_*jUAeN2XzcC_?lzqX0<*egG{0$+&v4pFa_1c8#FUxog%mD!y0dw zCG9#ee3H+-PATR4r2A5(Ww}f@<!A&u4kkw&oMi0>DvO8ep*zmWU|57GV!sE7ym{vw z3nPo87_Mvlb)zb3@yvtr$on+OhN7yc>IUpzefUJauWL~vf=}vhoI1RcDg-jzJwoz# z9@VUn%$_z4Y?u)}-+13jal3U)JFbvk^U1tf{Ka%CgJPzfN$p7Gtx2sK?inhw_U&~= zimS94_gI`&W!enF@>RF9WnAp8#`<me{e-oEa0BpS())jhUBV1yWBMCm)V;OZj$VY2 z51#5bfbV)TQsHcIQC8XEwWt;IqRVvhHf1Njat5Z|p|IPjTyLE&4(EVk_nJh4pci1$ z-*HyvgG6pi2N*5JFSW#eYbHOu?)sgISQ8n?Tvbl5dxMvPN6&BtlHHT|s&nQta$C3> zeg<!bi=T$mj^g?oI7Dkd4ha@bt_~Xng^XIgZ6Oa;5khKua=m_`3eV~}(3o{Kd%Iwq z#lYmP9dO5uuewjyQFUzW{=IKh)|HZ~+&ooDX2lCwJagROXLZV;6n%O%y${*^uBwu! z81|Rj#OLQV2QTTSs$QGmL9W<rTsf2;w?&k<HkxZ`;N-36PW8DFU{W}z;<cgC(`6Em z5)JaRYKJO6eyR#8-@3+&>JSiW&r{?pe`}2`9!2k};9@bzT^Pplg{%|Sut8v!)$;tR zfd>mm_MDG7hlUtyxDXX?Wz)&`6VIV+yF{t{h1R73$IZkiZ#%u9Ey&TDS+W3sZimsS zmzO!X(O9j<tuywFjH4U#W$g?l9PydJBbxZ|hwuO)OO$gyzV_YKg&0MIG@%^snC~<i z{n?V*S2Ep>k;Sc=H_&ZOgsIgpYg9HVIRCz|<1G5no<yio)j^DtK}GXx;Y{qt>Avg1 z1#>O3JiHC4gu7+-E;%22Kdkr}6g=F2zdj$gWS|$LR;M=~lgrnvx<L>1V2$lbq|vbY z*q6(qpEsc68JUsE)S!ke(blzh*NuBTZr7~2>c1g^vngf<^ebDK;a?DHMv(Hc4~zaE zKC5L2Bi>wS`UMdK<cPqZ%H;<|eM2vGYT=ooL_O~eWXV*E;Zyg)dX87B7Xg-G`gePR zSI`(xR}#G}fY}4BlLe#q?-@S<&Lhh`MVTlwtsf%zQ=kgC{DzCu{tw_$J`G;hcoxh5 z>pSMa3~~ywWcR;dU;Pw4qXje)>hcX`jpsA^aHd*uu7_7>=29n(QVHov%vLc*3qgbF z3D+Jd8yH%{%*`}`&-GGr@xkU)S2gBM$CyaY>OBVlZtZMM63VWwj_KVM&nE;}#N`e) zc4^0yX=a!>lxfB%!8QmfXnT>d>$?wogk|B=BB2PfqNaL*@TMn|4)6=UQj$%KD<5ml zGV18^t6@xPT1DOjZCt*4A$Vc|%23OVjh<5ux56T$U_5x)+WKha{+$`2))oY1jh8{f zYg1mh6T891R@s=Ql84;U?K_5LZ?PUsHb&R(xl%mJSJ2V*-Fx>gQ8M{m#v+k7J-(t} z(KZOimT93s6BLsx#8x%aF*shZu<ljZF<$87>fo^Iy<2t2<7+hdld-<veJjLOq3!(x ztq2a5FQ32sg1iX=lN)>u*9r6pOMpr8lm-6(_H&DPphjJkMo&5s&J4x-P6_kwClXKm z4v!%mViDa*NSqiPp93t0|NE<({v5vIgY{&14jfXX$%zriLpF%#cC^Vdu|v~HI4UhJ zI&F0FIOd+p94}>4KG~%?PQv_+elflSH$_zV3%tD4gg1ThGX14-@kOcK>1bCIqwzAT z1%5r7jyb;kfpGOCVX4xrVuvX=prZcK4*sEg8OqP4FovRM-Pr^(kmXG6%qPt@x<rv* zhm?<0y8(>IRMi3R&!XUG(#3xs?DsQcrjZ=`MJSb|GaZUI+x|NHb#6zpZ%8WwsFzgm zH4q`>yut7b@>@aqmm1Pbs7eQCL<xGh`6-W&v|z|-{il$asQ`Igf*oXp<*Mozvi);Q z=#P@c2dBXt`|72FP{0w=*4gqq%P@iTAy5VQP1&J(6?MUjvn{uxuIZ<Yc;2B>mHe*9 zl86s@3||BK(GJ}Wn*TK9J7f+=J*j%w;~vu#dDQ|vk>@^@Jq}fafY`>LK4|~ZRBBB4 zNMVh7{e^<}P*ru2Tv6P{G|8t_*aCEp$tltTy6LOBVS+FGhos4~>y{gxP~r=)Qd8~$ zMJs#Nskz*n$VWdEW}X7ANcs--s=(zMYI0B=3X}~d2HKJ){ZagmP5*{%8igg521Dfi zq0xdDlS*-=8QCX`Al-}93x>z0cL*8@CjJOsdt7+p>|J+Mz#%VzvrTBx>%Uf*sNZcU zKW(}14a%}1)(1%9{|xmXN*UX5h){O#R_dDG%P*|A^kmZ^74ogi2>#I{g-;I;jEReZ zz<3D)>uXYFe_Z(-G`BzK*6mv;>EG0`Lq7i6TdK)KcR*^EY3pf7yxHRi1@?nIB>YGf zhW=S*0Te*?Qo>aRHk_ubt4dyTMp=8YCkEY-=OWS{({{60(c9!;w-wvLcj(OIARY-w z><Z&=vK<}0t7Qs8R;Tq(Dv3$?=;CqkrBcL{!ZWCuC5S7DJA=@XK*<l_!At!H)Z}yX zlHVWtS<LkD+<h<|^i_gHDGV{P3112T%f}O4Hjd~f1A9*c;{K0RU1NWG>kwtVw=YsQ z8re8d=}X|Ikc%ZAT!0)b{tkRWpCE?C@oVpo#4O<-7Rq%9ol86+9#cD)1Znty-1Ujx z2i@5FmcG6R{Q+9oioL;V0mMazNAEH2CoQj~U`)#Cx*nb)k$-`=Nt!xp4dQ2wYb4&t zCRP{!EQG?S_t%koJq1$?Vx8%6p#e}yPu<u_5C8^ulnpS$QmMhgN`iHRj>$ra`w}D$ z#|)3PsGds+a`(w%c=V~i-Fqf2IqZc&bUy%t4uZhaYd~*Q5o@ssPW3-yY|njvwe&fE z%>74{lP%ArP5y%v$T7O*BE~;MG;gl$d3m1MaFcp=H|?x#)*opczR({d@U8bZ*d8AN zVa<mxC1_a8%!R(aoqbYRJ`a5~9*Fg^3Q$FcM*<9k-rnm?S2emaJ}&xY?FNgRuI#_} zK=i+7Dvb&R8~z|(U0dw?Clz{fpIrVT(Cun8bzFp#Co93R`!Jv2K=((0Mdcw2v5WW@ zArr<Ap6g0XXUA1Fq59$6RjHc-HnvfD+ks!jD$MEcxZ9Y;n|Gx#Nf<6G1MOh?74l@E zo6%iB#nDY~X)jQ-!D!-OY66_=qGJ`jVFqTxJ+7P&UU+tqJtKZcVzj1ch@CQAXj)&% z+1Ev$MpIlA)+qOyk3U#6QlB=9mfsb$ec1LmMqis{{sHMCH8bKXD{)L@Te8hie|E^Y zJo42?*Tvk1cd0)+{8HzLo^ZmpElK<uEkM*3;N^f<;qB}cLCVv+Hvec~`Izoz%X6~w zn0^(UA=c0gEBwNZnr_v*9+_hcV++tV?XEO6YQU<MS(xl|Snhg@eH7bI^*O=0{U!F? zu%_5@YMr;_L29bm9G_vjTc$KuQJ<l1V5K8>hQ-Fyi43b=pp5KNufP2TQ3UEAk@Y$? z(OjDlaL9w`eT;h!-pVduxF+iP-ACGh>!}?N?k;*fa3EkDMToa;Ho(2d*_=&?bvlPw zmC81JK8*73nUuyLqJ15N3#T3OSKQj2DC}7DGe!$Dp6=24g{xJR+OhC0#OwNe?zo`x zo#I-jXX~G{oysoV^TIE2Ueifhzq5ocpxQNA!#>Hy`+b})@y|*5d*&Rhx~_jh42m3n zNYQSVxXgXp`Y;_AB!VQv?`j<`-yvNK9R^nmu#L^f_J?i$J}LCAYj-*hQ0*DF<=?)% z<SE;8ivK^H6_P=mF7bvlqIT+lrVvz|ZWNReR24Y&s6s!AdQuY69YFNqCG7B#{5-A% z3@iT;)P?Ib@xdk03!jwcR`N-LH2sI$CH2(d9{d&&)iW$Nop#p&Df{T_ZKpXo2cIJe zv2*Z!(&&Rt^w%NezsF}_89wr`PeI{J_q*(KF5WDVg`8}{-+Ss%t`(0#9M1Qg>ZU+^ zeLA%|b#S(*rHY!eS<ricn(I*>`Gb$2p;wB^jzpZ!1TV)}^uZp2aB?8^-^X6tUaV=< zuc07M_4#L#YJAo+Y486qS>R&n-=xlbf;c*;n=zhGqo+i)w$4HPE_DC<l&AkKku-b= zJud=Q$C4V~X^@}PBo51WS)n^`bN`G5wWR5v{eOd^sIg&cn<Rh;RO|OF^Ywr41IZyz zyFMY>GYd}&q^ymm33E4CB>sm>#i<2o<aFW0x>jP~V5F&qm;q8d^u5mX4HACwuEm05 zuZh_4B$on_KhMl#93K;`e<||qNF?57>kgT`qWIr~IClBBV*y(q9kHGf=%n@w`8n9< zbara5UM+R&2F=e=nhpQi<Ik8)IOu_HvI7OyK@Usr-`m+9oVCj_LXVlbBja!QmQj#w zCqdS7{)elW#{M6#?9+pHC9q_d(91E7;}B}y@?pk5Z&=!?-%mx=zZ`Z^8OMHpc5cJ% z1frx6m=XyJpYo0YOvL;&m|<DKpBf9Q3j`+<s|v0E8!MnMl}Z_sjA#<QU^eKM`uk<P z21*{}5cNo^Vpnay{gluK?xSm5qo(sfC;yMsfGpk6AK%cK)&|7^=y_343^w`T4w>QK z4P3zAQ0;x}f>=QQq;DR!o2A}AF%Fb$_^Lp7+KJ2(AoDw7Ee|*r!;b#~+1&nj??Hls z<QFqUYZGz{xn#cahc>W>^f!QJqg+fW+7T!df{G^KKkD8DtMOkDlxGx3T{C1j(B1&@ zWK(3jsI*E1Ea+FDw67)og78B+e!H5pF!GmM9zpjV0rup<K~fV&8Se?yWOH;{VKoFy zpno9Z%O%-s>88H4SgG)|vX*qe*>oFs=S9&e3WlCq)$){d2eaEQ5MBh=wAGKv`T#-z z0Gm+ww@q>m_=;dnmb5`A(XffbRGB-z3=pjDKZumwPPGpVZ0KV)rd2ii0@1%na|4<! ziJa{wx3##2DaxKMzVMxp4=Pvh7r3)JNyc`)&=dWd{3_TipC<ld1V%o`mvOH91YQM@ zLJ`?LhgGnr;tVw$xi>>{o4w9;<Q4QLhQ9SU<tE+rWYwF-Qh+!G$LMH<K&gmqX1=nx zQ*-9<CJP=c15)s&VUOfJ5HqD>xr*$rMBw(<7CwCByYU)xf-4Q0M5F*y2{u)c5Wd;n z7?xFKc^dKcw_}olc)vRD_uS}UnR#zkeIt_Ko6YkqE`$Hh-VL}w!XR_MS0-5ld=QBy zcxWvORD-2ySV3>oRD$+a@Xa225HQ)G2~aYYRO(>p7sRvQt{+k8v=@05?B^XFM5)m4 z{Y;L}e_1r92pUqXBs>8;j|`=M@97w<2R?-BUvxY)#_^f6Q~Ok^#974h<uY3cp#3=+ zdDRTM{}{1DW7h2U8x->D5&9?CcgvTbU3K}p4YJl-ZwgBhp}!!RuBcwmKeRvqKZR#d z83ZT82)Zb68HES?<`Q@^i^#y>R{#F`iRjQ!V#B8;oZ;`dN6Ya4OWXq-EieImX{5XZ z!w{f65**O~3WM~V&<0dP<8~(j?f#hSFNiRRfEa<vGgSd2(5NK%WN*_y{MXJt7Wy#v z`$t_~h|TXd27q5HQxzNx5pb+QDPGV>^goO9{uVw&7WM6lLoBfEc1@-VsM-D6E%QMp z4PeLp-A2iDj8Z-iH6G9>frtobp&j>+8oj?a!5yqB{JRv}t`>pPo?wGZC*F{P-U655 z&@<@+08<lO23Pj)^vGfm>F)`8x)00x^v}|~(xCjvVIr|w>PODnr;4(22iuWCE3P!I zI5w=-A!Q<dzZrm4n;}o)k6?7!N1wZRPjoi16ku;YSq{VL8(yStcy^sdAn?$A3r|!B zo_|W{<2sOW_6@N$lSWPy0khbS7?v!kUd4-EFf>u?bf^8g@cr>?7w?0lo}*TQv_4NL zQFaNedHTKq`uijFQkTf#t^ir{`jE$8ndwZ=6;vWNx?!MlOs^U5STSO0+wu@+dn6X( zgqtJE34yyN9dXHQ;xSG(`P-6dgY~%p+t|fc*w4CMR+0T5;Y30hWJcf!peK-Z)Cn8U z4}66Zu|fq7tovb7N>|^xj^8<rqHpl4-XkKoK?+@PbfpELLYhbKVS30ck6)~Xl;>t= z{Y=i-q)adqt)FsnP}{E(8?8Y?urp$+<OUnJx)rdYK7zxnPjnyi3vMU+0{a|&|E;Ty zZ9-qQNz0kYmzPe<H$#j*eA4<Oq<431Y9F6SB(gv@*Iod-Cpr|cS#_oS`FMT0w9J+! zsqeBHMJyBGhvf*{Jd&#X_ayS2VE@DKI)}<ne&g=&^8F__{kR}~7YI}>|4(y3N(>f( z51#tX8I=eBvyer}jej+}XK)RR3Pu^1_6ciQ>fT_>q@N)C8AtTT5k&Vp%f0nGr?rmo zgu_y^yAIdC>hwma-Ty|DlJ*X%_Vw6`d20pBN)>vxHYFhfWu>flQ<U}V!@3%#I`n=# zjBmL7_&&W$$7xlFO^m=#n_W*rG>n4S&B5M(vA0$zd)5Eq$0@;jL3Dq*RJUwssZ!`y zp_A6C@+?<R#Kv@VZTz3wzB-`E?SFW*w5T*V6a)nkl@f`8ij;)3q=Hft0qKx|s3;O5 z7f=y413@Y2QYMX3N=nD*+{gjj?t6B>_p<SQfA{y-`~LSl;+}KP=X^T1ly{B?{KPA7 zq+ppIud6!!=x-aT-wvp%=&qCYV5qb?sweugT6^Q2EVBXIO(t`5quLE%U;YVsf?%l< z3b~2R9%jM68~qBi=@cIfZOycfTzUPjajIb?=){G}hw&^GOUjl4g!{x&(D)L6GcNW3 zL9qZQvGL*My^IeTZ*6qTQr&Mpx9m~+MibKQlBy^3<D1kC)<gDv{R9Fie5(R}`pY<I zJtr$cw)B2~V2E<Mp)Y8VoE;-ndizB<hVD#3`j@+R?>3)*O>_Snlp{cvbYYrQR=UdF zZLSsdHnvlD)!orDrS)pXnIa5QcZxI=406n$0|UPn^!hc%@e;z85QESb3(?)HEl1hd z*tlUYsw~a4_>1O?V1or9ZEq{l|J>VE3VDndjcn~30I2Fia;W^273}IN{6||-e%8s8 z8vAIN7|WJ-@spgQ>WSP%lXr`~=+!MS#YqnG9o<v9(~x4@Vs7pvFAnfC8hO&Bikcw& z`eg|BrP1^Efo71rpkTi`%}d<j{toB0I6YU&b<uM!OO^qkCqIhgN7R@a<$zkdv`@SI z6fvPBu>+(DDylWNu-2&7`(2}ai=OE7K7X5p?@K@_+$90J2h^?U%rpM^gA@`M{55s$ zYQNHxD@s!Q{mkE|LHW8%?!n!&P^dplF=RJR4<u;BldtgbfRLd#ep_gT^V>bs|9tZ} z-Gdwi1JHb~0d5oygty^8P&W67!o+s!9q1Q%68(eBVXouqA@F};XufIUfP3zCyvx$7 z?L9aM-(Tw`+Z1gu;U@<DV?(}+LV{uEbg3i%QbiQTripNc3qM%Vau+D5nY?C1%hA~i zvHDj=6Nab?E#76Z@M3GJqo@?^3Pk%Ebs_2hnds?*C@BN-4Q{;_SKX4iG`)|0YN<A} z31bX0Lr~)kbryjs74F&^Mv6R|zWfOO!dy$aU<sA5dUz^KNkFQSauVo`0w7$@p_hN7 z*xG^2ri{AxRy*Zi*d-eKt3~%ZeYUfUgtvG7EvmayuK0%Q9W35PlbS6NyC|E3W<q=* zW-KDV4itK%tU50Hw35et`R`JL8Wqk?Q>QCrBX}++1vxak+!vP(vjTL;-pJjyXFcka zg}W3g$r=_+3r=<7yCWXR6>&$)L1W9%5wz3(mo=S0xc>;;etXN1xX;4NOkT>`vS|K^ zLrKiF>vyv=X_#E6fLNdcu7@i~QjZ4`mt=NKi|QG|U5}3-T~vgwcU0<9wfZ|W12o5Z zl_S7@H3PDjTuxs=pneMjkpbXl``iEbKGy^InKqe--mtc?)8yX{fjs#T8$=nprB};l z8u&ag;}~K+$*JNzL`tRsy21ck??&XfncGLhCRqNmJFFlR<R4a!jcl=710hIc_w#KC z@F!g~2M)tOAs1~^A>6_vgdm_z*raR;Jg0KmsS62{JDF43;8`$G#<fGp>d(0x1nHs$ zZ2fn)ZfPF5a(<drDezI9f!edCOBKXtOa&hl>ZJ@IGbgtS*yh~E5cM65XzV>h8=zRT zRF5%GdM1Z{09r7s9H>Z&M7erd&Q>%;2&5A{>z+SOvP|tcfu-kSG+{Q4t_*C`fpJog zREKGj07$E^t1!VoJSH6^NOUjf9V<<}GJG^m$}%UtUnRMZRoB_JE?NJV&~ciAKKn?5 z2L{0tqK&(?85`oA+y2q5|Bor_fr0yq%GV(fJ{A<@(<j<bnPw0OquC*vM2yT99b(`X z>2kU5904dD|HRAH8SJnlgh-$i4a1tc1-_1<w>SXAzaZktT=h6=pD!mKizJo7!0f<> zx${Oq!C(d~3+S*j;$>D4vQe@8=1+(zdMV0R0lKb7n#lkK2?oGW_&bJH={D}$zQs0# z==CG{(3q2J5-MwuD|AnZQ$YEQaW(gN2%BKy-2n#P8-WfKZ8>?SSkq<bHUMX#!0etj zDkwH9aDR#f*3G5RCq($0+~9BM(CHauPlW(P3XBq6VS=s?A>wn~C{rg~=n~1*6~Oj~ zO(=V;dl2b+9c}!nUep;hJ|dbFFr=>|Kqr@1rGAs6sRb%G#3B^wc~2@Vm#8+nZAAME zDB*Q*`xRcYBR-Pklx3C*CtcXIU&sClY3X)@NPWhZ62h*7HpqyX%VpaODgd@3e6Ugb zZ7vi$3)sI>9QlL>GTWQb?Stm>x5*(cFGMdO(x0#LGa<PV-_R@TpwBBvh{{4zzh#0c zdB8jtZ9uQ=Gu+186B)9Sax<vkP_%m*c{uk(K158YGW`N!B1RNP4S6)cHuca0+Xi4+ zh*ainZzPZpU;C3`Ykkp<KkazlYsq{Th!DgTjg1G%LZBE0@zA^yT>jtAj<8d}39Jdy zmNdXclemAnR@kLxT51LdyFAxBdMAEB$<Zd!?-dgvJO@4h3`IxcBJz^L^GRsX_(pVF zhDhf~L^R|As%ogb=lgCXMf$8Gn}!Bg#+9_MU`&XZRWFeqx&j?D!J|nR0r+fs3T9}R zDgSOYEPScgeIms|L;3Q~RpjSJ1F6@0<|oL(#-P6tGlI~0a&uDHTL4-GSTDhC@(|6# zaWQ?Ced!&C)H{?oOv>nn3lL*RK@O4#5Tu|{Xz!k(3lMN*X0oNE!9<9}n+-8;%wI$A z@O(V+O8Q|5>`H88R6W(~1$Iy(r?qCk&Dgm8Cj_(#jhjKQvB!a{6e!n(IJpHmAv0W8 zMlAbJnp`T6)ojyf1;!)=ygnrI7XBI9uy<vX#o{45_~Wsptv=zJf@ezfD^hBEJTvnk ztK;8J40@IP1AUvW3R1pMj(~lcnFHk8sD<Nh>5vZ%oOD1MPP)&z#fg1KdHiH*#AKV{ zYUN9ewkS<<6)Qlw3Ku4+6)RHiF`3H0a{{2nF1X<bZL2DOtuy9#N}R6wv@a%z_OhYX zES3ELlDep252Job2eTv64#%qc^-XtU4pyjjIWL@f?PWy`)i<MYcw7pp5}{%3Lqm1S zYgM9VKOLT|`SMJeAH9IAV?5J4Z{7V6gT!x^fan+c8Hx>w*DlW6-Upk2)x=RAKVAhx zK^P|6ibHO%U%P?}yanz!+Pkr*1icGf`H0c>Emq|A_(+R|nff6ru*=(<cHWk2RkPk< zHH&iTJ#lneWP)?vDp9Y_euWP3Lr(-yj@l_mtVMY=%|x*a>U*1)S4Is7_uhQ2X<^JH z@|p|G!r3L3a$!Z%1qG1fIRtx=I~TSG&LGwB0Ya0UDu~F#cmDuMjfnm5<C8qZZ}efO zPwau}$G;srF4W{?%l;_g!^kzwK>wT1^-kV+@7HD-|2_9|r8_T4gJ)#D8j%Q5q~Oqh zQE*jxrk$(6Q%l#v7dJE+9PJ`RCGx(Sf*n1z0y_fw1VPfC2k^VQhMNZg9dW0q^X|Fy z-`KS?@T55JtOkjAvHoo0Bbr923GjUG^$(HR%`RU3U*~12yY6zPrvDtzlyQwdvOd}| zudBy`0$!`C^M69j+)1mT-R$(9lUsa&`FrII7pG+%Njt)SJ+4zEHUKyr_o(J!iiq9Y z|8HiJm^IsT-Y!*|gmlZ-=MxmOnYbBFhylExiZ^xyq>$7tpi6nA2U4*pRw{<7cPnSE z)FR$$(5_HR?9=lTbcqu5=I(~+h$iC!QWb#Kg+nww|J%W7kyHqhgySgU3(r)eS>x`r z0Ky}L=t4V90m5E%<EU!X?v%Ox=1WC^R+44ng!k)0uIFy{RO}13$Gf!$-{7oPT^>HE zx_a#AN9$P_`UKYaA;_**bMR+4dqU)gZ7^r}I4z7qR(mN-SSAt`X;T2tu{xsi^n|AW z94`bDcNZ99l(T#UE-ejXL~k|V+vX*pHj?tELKQ90*@OGR3}%7k>LKflbL5*}mq$}_ zh+XJpDBNo=BV(M7%+2Uow(B%cXn*2xiffyZo(;Dy58U1RNKZj<{x=Ag;Id(4o59?0 zdlR;OpciCPQ<J#0W#>Xsj)FDue4oQB)k-nDcPD9x%sE!ndOXA%Nnz?x%A@hyFu82` z9OIR3LA?~v@FvmtlE{reUUO|(0Mez}K&~M;;j`jAVn_zSm@*Ux$1+K6@-M}E?)=<4 zY;L@lz@Toyo%o9iVoQM;h#DvmZ+HJQ9T>%7P^nKxQtugAZ!$yRFRs}y0TmfcQ|?X) z%o~~ImHBXOf$M_bhsp1aJz?kFr2YVO+Gx4{lmxsD^FT{rj?JIvCE|c#kD@1gd92Ct ziQdAHeRzpCAr76nDp$t`o?NJxc`jOVFa0se%ml;qEsq^^1sE&ooKDjVe(|(HEMdw< z=sHgQu#T-nI8gQ55ZiOGL`$#`P;r4<3=m<CX|c{oO>R=ZHq9+TWXo1;5a@uXc^8R& zF@HE8F#;t9!N$(?s5*dfJZyW71_8{8Sr6d<7u;f*nn!g^d2q{CXF<&O^Q)kf6D(k3 zoWBs|{}~Kz#3W%=#R0(ANG$M}1q=uqIfEVq-Z8}bCw47^Vr=)vuC@9b$FC#5xYsg< zDa_=WkPZqv_Q>pDfHDV~@||zYw%=?7S?)l~1gee5-&2!(i*M!G!xeSXhZoLV@vG{t zZnP^-2e%gblnA_-z$0lDrgT23kp#N|?kS5fpRwn-+9aM1_p7-M*AyGldu8I|n^5dl z6wng^QwI)N%02vKve*^NzF-x~rR3bieuz8EoO)~!<5id13c34-1@IqG?IMoq%DZTs zDT2BDY5RUR0sYR|q!g7*!JA-GJMFvwUX!{aSeXheR^&>Gab>e^`D2b!2bg0%pFSsK z#3ZZfi=;p|bI*a*_XmiQRGa`TMt+(PdH1I`<IOJ>b*M8-E_=vMDYe1Ufg!o)z|=*> zU}KacX9bx?*54ZMesoFX&<e@U5X2jVh}=DUupYGMBl7N$eOq8=HRL9q$`vM_e#3n% z#bZ%g+ETAfVwqzs0+eE813m4EZ=5B1Iga!d;_FK#p)Fw)Bur|wt?F4y(5?FI@M5gy z6vvq~^h1clFI#8Ak!_jHW56s0gWmRHpX>*+?J`2D%vj|fGQU#A*OC1;xQRy}`_ZR) z;wD?vkAIH+*QJBP?{Y)RPN0;fAuTCHIO2<Iad+N>BG*IO-%nZIB#W;cK+ROw4UlfJ z2ux7}wd)KdGYe`kIN9Q#UhP=A+36mFmSj9}c=G$VQ6nb9f2A@=`yL@}*Nv4LwT~p7 znkm4e>w6E<O!JvbxhhQLdCxXT$&OEd`>PoUj>UCDwq5!Qb}QZ^Ve0Dh(+Ek(O4KX? zh%S*n#5_=XeroRB@kh7hy8%{a1s!2rO;wJ85ngRxpaA~Ozrvvsleca@vJ6|x^{Ze9 zLTF5C_*Gd`1S3pla{e_iJ^nB1r>=|vGKHEse%elqK|hj47x@$)y?ldz6(B<bkpXh& zs!awJ;m1)f1agO3bmvqG-`TXS&<7s38;@>B{w`BtTi=cXOp}VSsSBl2i*N3Zy*v2O zI+k;)hPSHpno86DrWB;8<XKoE1Wwri@NMknLgy>~no;3~sBz2=ss}<Hu|97Tpmq61 z+50c6q(XoZV9EcL9IUD9c5)r&>w;omdW)yJPi}cC#j1W!2>%9Xmzv#n_fpDvOsRPC zul$aaUo>1^mAuV%N><)bV4}~&%rHQ_<^ES51O*N;ZZPE!N@RdLln)uN*t1?K5ip`v zG(7XAx@<`-Zbq_{3i@H^DLy!$L{j#(?yW0Ye_tajnut7XpSVI?n1($=aRf!pQxo9T zz0`4*jEG0B!RE;^Mm<~28*_f1pqag!fN{KNS@c$<XTJvQrx_>Jh5Py<$K$pjgZID> zFIv_8L#<@#*wr6e7??Md8=rambZhDkFH@MM_d0FZnd7;I)N}`>;)!%A06X^7ABiK_ zXM=n=Gp$di-Q0IG&U@m{)p%r`xy2p`1n-XIkW}7%JPygz$6wqz7oc1hbOh%geIxjz z%<H24S&OCyVYsf|mlpQefsHqjW5hqI4&lV(q+57akcE15kRRwFB@`QHzt(6~A{K32 z()H!s@`m7GI9sH+f^gxWMRIRNK*R<L%Ne&hW2cB^{hlEkI%oEbU-VB1{5MgG8|LiJ z)L6S?GR7N|lRJ7!rCG1A#8P8@+lVo8A#YsOM3dK*etIDbF4uV}h{x_xp^7s`+PR^> z)~%vt>_tfa(P&8-RNi&G*N&QNC_Q$vC#k<E!De`XFa7l?TIYl!3+CJqwkqrtYB2{N z`=is4Y17{X)`IydWAl@ViK-=M@X1xe!Cxv;{^|X4{jn(AxKz@ET<Gr&Zj9YI;FTzY z&A$ZRrATtc*fLq`_{YIGO`fp`<%KTEtjhoTNpmgqG*AuzAISyDZNQ5O#P#0|IDaxp zfFCoA0Of(wO4GU44%!W^+u&jK*lB)T_bX=Po9Q#d4DR3h?}qC|FFigc8MtDwJgLs@ z2I8e_$)s|{6?rE;sV1+f{-*NT@_p}2I^+f6yn*ge&f7No-xJ;oId_Dq%te*@zH!^I zV0ZStarDXqI<AYA@o9;y*X&NZOIc}ia|lNX(JiZUSp)-}=P=O4%3z6}W|T&o>YQXJ zP*g8KEqQOC6~&ll1p(#xQ7&RW|I;533+pkNEm|$o4&wYo7WHHfSF+=(HGpcwhC2v{ z!cYJhu&$nC5bm#|9_yvBrM&fQfnluT_5gCzV*4kPCK;v{(dY@_-EdFd5}1_A!hvxg z=tbaV7qv-;a0i1)jY1%YAOO6Zx@|rJ`%>~C;YgRmlqG?;>qr+2Q-jzZ1x;X>b9pLr zE|OFvz>?rvP_M>ZAmp=DMG}ocpQRIBzyFhMrp^!)SA*!wsty_sQ!&Hv9bR(Rh|a$x z)}Q}I#b?gT&ek@$7TKRR@~z(+Z&J4{*L$X4w;3*9$+p<eq5(pj)}YIqQbx$hUiVx% zW}DykS$vph6AiVWrpxja^6ui87G<$J<HzrDHdfL3eU{mIf_cUdbWQmDTJ~eK6H&BL z-3`ec;^7|b(!qI_HKD|kMzygR;uhLmb-Y_nSk~x_ev0;O@v?xFH=e&u7A@0G;qDY- z^lz-kxOuK{6?0$a=KW0jHTfH&a3f(fk9l~8HLLmL=EksTub@}y^8jGnG8SSlY}WcO zg=miJNh$9isVGk*xiS^3w?aINTc{G=dkftZ?HPRHm~34I?2(AfiqN^mF{#LPrq6l& zRL!OTUwK8RAAV8(RQgm}uG(X#Ph|C*M7ZE3n=`79I$zBn>+o=le;W&v`&fONP>WK+ z%pIpKruLM|-_cVp(>~DO^gdSc$e|&)PM5n+UrR~cqe7Wy@5ip4m7P^T9IR<w@zXb0 z>f^~%*~fIopS`OwTA~j&Wp@t9=kM=PkMe9Y8iii@N&lbZ^wIycfrb=;I!-SE>h?>{ zK(D7{p0iLpSaa3(B$;0zdz&2__9UpODS}_WwqIX@t%+v?Z!HQdL->mL2HS9(o~JxR zX2_oHroB05ANRawLUK4+0JjL@1Pbd6`?d8qWA<B|8fyq5O(xxEfY-EDS$mwTy<VTd zf2Zz?ToK~v<)&ZIcLW5!lT<KKhIoThi0K;G&O(nW)pS`Jphz*-w-fMMz<c#7RYi%h zB*Hvt664yi5=BE>{)3WU#t$r>h<-%-8gjEKPmh>HP?0ly>=AfS|EPS*yONPaRat8& z6N$rxr2K2D$2Vom%-lA<k(vMS)W?v^xRYw!WeMNZSfl&;2NX^@UnWj0&slf&hpDcR zNS%85$;MTwj*s}7zl$E`)(Tox^{z(qpj~I&mqG<X)NXbxrX!@xyQcTQ$9yn7+>Ln! zDmS6f`zpsW=X1nUBpXWi&9U;WD6$cy=Hudmp!Fj{gnig{f-GYuPrbC!(8Y`^2ekAf zXtdXqnoyi+YGR?y$Rfj9X>omjbL=HvKhNA*r_S6jLlIr!ZBjoLZ`(I4@nZreW4;u{ z9vieo&f8VPan>8Xc;>hERsqRZy3z~EAHUPdvgYp)0#o-?(TAnLCEfSK)9K*ue9a@6 z;e3m{wceK}$=wtTsbS@5G+@$&j1kW4FooR4+1_{aQxi_&yJ_3xA?$ckH9QwF&bv^G zV;T$O#7Ofj^^2dg4hw$=!yc&*imONV?~Ip5eX+PZEP!JJUU0UBq@;~9=<##(X;WVn zH?HFcf^kdDSMjpA+gh1&J-0VXjV~*njoqh)$&{m6nXX0LN9-p!`g$?d>eK35xjYkm z(af;Yo1a@r;@8`F|0m=v2)W?*OAVqOp{#nN9?^&8v01NE7*_t+VLV4XV<(T{>>t=D z>m*$JXzALYi;^CzN)(~HB1X@lP68DkqgBTPq{fle<?c7|k)tCE8()okswdm9=TxO& z-wq$b`8P`YllCK6X53YqFFVyqh%v0U3(unY)lL(v@j2d3p^_tpCreyvx}8f_e%uel z(8;gmEhvpCbKXbO$&d64*7;T6IW=}G{{WlQu^klROBc;5GER*qAbIS=XE`W;f4lSD zUr)G&HGZUx_JFZt8^~3n1aU=b0nu-LB_F?orPIL=psY`P`Fv$4+cEKi=Nw`P)>dVT zVzsCez9(Vd;j6DU<(D*~6ZWYAB6eG3eKD%s3wIvO11>4c?@*Ecns-Fawmv&-g779~ za<*yFd|k0zATe4YKkKEBc6?$AzX|_P`yE-Eo<wiQ3=RJe*Q|%--y88gALkVuzU=v% zDIMa<`Lwij*rx*dFxN^H)-re3h=7(+8zuQVEn_q*Y*llB4wz92e{n@Jcj#)ei^}%F zSIvk+`1>0Y#l_gk!Mhsb0_WZuXR|U2f@UMi=7%$&kBggAtX<dOaSCnbuKZhK%1h8^ zax~rg!RdqT_r!X6!$!EpZ}r<9;N>%!y$ZK5KmXcf;F7a;x(?&8l5{ECJv`Ah=k44N z?i7O;j1Hf44{M)0`re)ce%X=Eb>)PyB99Q;8VGsY<24px)7yqS6Q)cJ{`;XKmT#C> z?%S+J&E>7_d{yxF@aHmSu3q1^NFDq;O;cSEhJ9@Va+4k)Hv7ON?5D^rY#eDvJ`y<E z;bWQd=>kQ`r(!%6|1jFezeu*)R5J*FLUe%55%udQ5bB)nAP}QzjbejQmNuDN9`h$P z-lvg74Sj86ZkPYLX96@2V(c8?UC4bPYFh{<p!333$DqUwI7bv@=0=GjpTxi^zM31# zv>76?<<s+q0Mv&&NeF=SRhm@o$9^(`arA#<&WVHu6@j;K$7v#J@d&;_4GA*js9TT$ zpACgm!l+ia^Z|**j30(iI;PuPI%1^KI&=4~viCaZ+Rs!3b~p=LjyDYf?DGgvscfvb zqUJK`IKc=8!!1$*Y3oqj7~Y5ee4PcmsQOv1M>Orwo>I5u$LI+rZ_+5qA?z&mN_)>a z99Q2tQkEYqclFFlGouP429~402e#FnhzU`k>DhK}MJ?@F6m<S~1vxt%h>@eEK#qCh zd!|GuSq~`(w5@_$p&YaRKfZ#Z{}K}+vL4yTyKh$bz{97`GVsx_MomkV{6b7{k?)Zg zw0ZN`g{o8+`j#-nB~+=hBId($#m_fgS;l~DcAmFF?yF**sXB+<nXhPjBRORZqy_Yp z@~am7)A6F8cP6kh5uys_3U}R;v<IeB8_k_iocFrr^@Mr#k>*`XJW{~{EeYB~WO1SI z@eRg@aQ(d~Zy$-|Xst@TW8c)ZZXLd_j7ca{wTuXFEFOtHtW;KJzYkt9p!dEBo6~=m zww1^9b9+Zs88IUShRbNQXCWv`EPVfjsQV}#ULJAfwODMWg;R$zM*xcRHA$S*f-aJ& z`6{lDu)$tZR4~e&&6V3h%3W5~77DkscmAM*iM;mXyl&pad!yX(#=Pm)pp_7NVo?=+ zz#T9)9A}=A`TdqZS9EJu|H~dBthPr+9yf5mS1S={-pqX*=Zsd9E{Szn3*<*xsGHe4 zZH5GecZ8jj;RvmU3KI0MS0rXczQ3<%`+eg(kHU>L`4)l(@dY6mTcv3);L@8EUtVK4 z`6#9;`dpp?{^gE+hz-vF$<nDc7+3QLOR*MdX?ITrl*-Lb`8g2xhBW|GbXlY`$IIjH zoLkP=;d<V)_)hSp+HCuduC~a|Po`!Bdngk@2bVA;Q7gmoJxfj_w1@TKN~AJE4Iv3W zG4==A&2ak|P_x5nzYc5&V%OUvzIb5r*xE^@hKV;|X3o%#FN#*gJQ#fbp2OVmfO!|a ztLHqQz_l6XMv%J5g@e_=4pwp4_0IwUN;pD9N>5zY^9}U=s!^>H+-)BTx*;bwrn(dO z$5ff8%VH1StvUEw@|jXQ-LjcSG=hgDNigrqITb2t*DBxo`k3^C4bnAJ3Dwiey<O1! z<j9i<XAs^-TN6?8J7&E7?*j{TE;Bzd`27dsOC2&D64H%9hN~UHd*mWH0vd*cm5XC; zuB2-Gh_7bM2g5P`p;-GHr0#9u$cDW80?<Y@`#_c<oc8HrMEpTtCSq^<6nruYQjS1< ze-}{DX!*H3bu!{|(Uv151bs{0JMBz#!lHR@mBgHaLh^a1r(?!eE2nWbR!#eEyeL&{ z?i82p?8%vT^6L>Txi9YpiyV!;-WoTQVm7F;piWQXZk_e_^HZ=0x|N<YTNK4zdVicr za3Z0NBXD*x3esu+wAU&^$NOV|@#I)=&9H;evyi&$5wN9rd{-%wUnD7Ttr>)x+ue_? zmzT0EHuOXvEmeyYFN}-&qIr*B&z^lq>)4l_n~(UC9XVxNAZe8qK5N-hWh$CE_P;gN z;=QIU75XMZb=ak}VOr2I6i4pVrd}2D>hs`~?(;F<U$j+TdG=gw4rw@R1m9G!YOzrG zwe_q1{12Yfj5L8}wOsQL8!_5G`nG;|IzJq~aYXInclILE7t?sq4f(nEo!i2?6<LLB z3@0xu5kT?;HBVL#alf14^4Z|r&QwLpfMBYcBSV*_<-zF9Y5u(PAS0}Z2AF{qzC_Iw z$?R8KMaCoRc(>R;9LabPvre9@@*f_{o$(&gBtAg;+PTG2sLqGj)nhY1^h{to|AaWy z(*F1yD;&$*-bzmWxLA)^Ih-<s+}?*`Mf|H^GwPFg+PR}U)*{Wnaz8^Pye$y4*-72Q zfD=GZ8I}Z66({L_aX$6J9}Jix4hedU5Z|w&V=6<D%b|(XaVA=sU2Pq>c__!O1+z%^ z$qdxD_yCuIWJD`Rq*#1|5?B_<HHv&Q0bOt&-URMGAaCAC`yQf++_NbixpN^3kyelV z5>Y~;Y;={Aq~c2IZZ{}4^uMmI_zq{f{XXJK@FmT1wX4?~B?Y5NAYT8E2$kXlX2ie6 zmj=~1$}7YtJw$0QmeFQJuWEtetcX=26x7ktaqNbc%wfC#?B;_Lu6i7ylQcAh66EiS z7Jw}HaPs4kHMs9Q5!w2;3*v?)53@Vl*ckdN4-Wol7cH6gQxe<mVIoNIAXX=3K!Fzk z%Xm8}1VlPO^`&{Q&-_>W`ZKP6T!9ILhhoLr6wi#ZtP2|&5OWYWp9YJUb{7k>DmT$* zmMq)~XC^TUJ(Qn{G%Uxl|A6=K+B=KHylk748aZ0^6z{#`f#0kp@kQ1k_Y)K|0-^*1 z>Rjb(2n(p|cj)&Ueuem<^OF~aao(8W@_VC*sI<co#vN64Et{>kiZy17D;3;&7ha|9 z{~3CWV1So;XVZA-?A+OV;dBTZ<M*64PGv}5(vaF|WbNvVJsW{LJs@Q8h<SOGN`Z43 zga#S31$q#WlyMTZoCorvq<sV1K5R0M+ScJ6`lglUUqKeC#0jTxh}t}!VHbg^r=Dpx zixWSN9uu>{YAn|W!xp5mg>?eXQFp4O0%CvYNh|#L-gDyA{=654#<IU@Y)J8-v5G=P zvSI8<1Df^Z`U#AY3IP-YR5Nim6KsK{6NYadH-8M`PCoL#iux}1ITU$)?cI650Zf8T zXy3(pbJA)2I%t|@b-n)X07mT-UpOJFJp^bb3@3VhU|b_J&Dcn-XI8^H`{UD<+_Ntm z9`2q3aw%`|Ojd|k*SgdQCq7g#xiZ{X!~Y0`EiDD!=DW;c53d*+E|%`n?)8_E6)|~u zvJSJ3;#h68=TgzwaUtBok`mp=l-<t;Mp<o{-z-=dN&<cDUhQy>kJRMR21JaJ60kR_ z#QSFy`fut?^*=f2Q*Fx7BoY1^*-#}*ObhW2#<Dh?4e05-RM555S{}t&ltg=ST~v4; zI_?pxqB#z{WpmI&A%=Iwk~VAtxeh+Ao_VMG=s4XHGJJ%Uz&UEj>;_{K!6&=t_PeE& zSiL-W_l}LiPfoRBTxoqAt$m0hKKvv8!uHV*J(CYE#eL;hGKR5CePPCxEPp#JosSER zho4Am@H+Z2;gN9l#?cCB>_{;iR7gbwbiy8CI`**3oMf6q|8iA*#^By@nlzEh%7UuS zsn2mCjXL3?{Ea75yz$QR-^D_YcKFhz+qo_VlqjaT*Tw53-mQg1j10_LNRuSkwT#0C zTq`B?<V(XRL_R$$W77(it=I9tmpk0Zm1d1NukiTGrw1M@?aj}Q)7t8p;p8V%+<2@m zJx<z;UuN|B8r9g~)u?;#L;kom+*<HjQ6FZ<K%n1J*#C@ueCeGT$%KK{Lzh`;Gh>2I z*(e`OZaA}+g%~&=t!OmoeKN2_hx<X`);q_t@U$%y$D)eaxc()L3=qLkD!KG>zpUEX z-)hcw3xVx!P2IlkI<KU~n{~^W4~>4<Y*w<E5c1uMm3mo*?{g0n<K+#~uY2DAqm@49 z_{72Ig2FBl7=x7CQI1$b`ncZ;UyGWNjZ*tZ5C$FL$t}&ZYtFTGl|Fd9Zou%znMS(O zuYtmigb*Fl7Rh%Q*6>C=cH7$0pj@UnzV}({b58CyD5I@G2rih9a}{EWdj+X|TMCqT zkf?>6Ay<=Ab1bR==;zM5l5NQtNo!}nQZk=9u$S%Ju{Z|sXNw(8E~d8vhSD`)DE)!n z{F#~2A%?pM>gTLm@}*+l2;GeK>JK}8Jf|J6u>=NBZNqjZ0QcVq+%<oar>%v&f)rA+ zl6=D%egvqpr*^!2W%5NX1ajVg+XSd)=L*4QPar_mw_qYwRuW)<6h?S<Tod>FvAf2D zfz-P1ZQg63dQVmJ4loJ)fk^;X1a<n99sHzMqb>|HYuEUIe(-y)^z0MUI2i{vp)>+f z(jISc5^VT~Jt*B}oTL;0fcVGmAB<s-MS6eEV87vtFf@br8I=}+H}!7RAX#uNlMuj# zQl$^3Y7YU}tRXhPqu5fZlak7t2*<pxk8dq=J&<UTJha05IyBJ{*qN}cm1NK*fTmOv zxZ7*IoI%A4aQBW}h@&hFMpgfvm<0F4pPDn7diwj@9j~JQf^02y*_kDpvXLy-ak%@D z%ZbMdE3M<CQ?;u_qkl5pK;e7q)%Z%2dN1@imBxBhJsyMxwZ3w_bIf)6S!H>%tk82f z6J>h{s-1;N%~f1}lZS6mJ*XSj?CpcAr@xNz{tN+f$PU&&vT;!%=|uLNf_bvS{7E<+ ze@?He5msHaEKkl>ZP~igkZZOS>E!;czW44~EQeNE>pkcwY#^oayv3t8*xtH0mf5r; z+M@eP4~p}D<6{V?Ke((e+_>PlqY+|4e3M&j$Uv~cwpP7MPfya{>2o(1!!+N<_CbHd z{oasav6@34Qe$xCbro{9tk8o9W*@r}60|s8h7cqTR>`BWgCrrm>zJ@i?c4FQG2Zlu z^K{jc5C}8~YseC!j+3a7;i?}OmN9+pX6IFAotg67kX|8ZS_otuV3r@Hod&Z}tdX1n z5tquMw4EgLCJz*_VNEv~f&Fk0@0c6lZP7(Kh0kr%V^<h32tWlVo|wA%$f<gPmQ>sV z+Ju?}I_JmA@DYv|cAXOCTP>AQ!;6fUL!%L;?a@^yW?IMK?0hcU);Q^}?_xS+Hg(oE z4$%M_$}fHL7H412`Pfb>JXEhaU&ZlvWxO36_)4p<6wk98jMs%6{`KObvWTP9%~232 zsSa&J6p;$CvHE5N)v=jV`fDx)#M}!C7{4>6bMWSMPUc}Z-c@_m30<ee*O?{_1}=1< zCUl$_yzv{q^TtwREZF_5b-ZwPzSRLU2jgoKDt<P-zY&6=Jb2EAs)HR>2Vr$Pwv3%x znj;PcA7)R#G4Yg$2GliThC?q*;|_qTyda!@@6!c2DQVpmxcyPy@{=lw5+^S!zvlc= zKJr-Y436pX7w?ZD`Z&#zRJC-^`nQi?i({TK27}&=&;SA--gXqh5<qtqua4weES}fb z)^-f5@OW~~^BW|Pf2*n(=Uj(in1gYKczg_inLf@gQPk&a+G$26M&|RuVjKuc_{Bi% zKts}DxnB#DuGzN+MO{w|d)?3Y9bpX>0;64?dc>qj#?|-Q?YCx)zn!l?p%;H@a4a?$ z6IT-k9fv=icXt@rQBdt{erHw9W6gKgS}d^r_MP@Io0u{j<I7OFfgGi!PJ^mv?P7-U zqS|G~<)dkeoHk~^)x=A(K1p4htx-<6Uh-4t2!m0!h9aiCKLaO!td&&m)3bTtyT|lJ zxdWA-_KTgN<rN9u4`YEOm~?+J^mdaERu#V#J93qww_UI=iNVfm1cGdPU)cRcAI_7S zp`X#tUlwE6p)Gv3TK(bEr5Tw2_A8XMQ}H7y{d1o*g>e;i(K;thPe2VMr#B|o(+92U zYsB3bCt|PinnyR?`qqB&xhBLvYdr6O+p2XRC;M$LPf-S>hw{EZ*fyPy75?s#U&{a3 zEdAkS#;k>)NSeX}<y-0fJAsW%Q|Aa-uaFqu;_lXBVo!ofLceyy34yDtqRL9_%d3Z7 z3h})emhZ)dX-$rm*Ks%riM-II*=%aWs0*r{v~{-qno_4|Wpc^j%8ua=4zFj*9O~P> z&q4W})iM-wIze4P%CfD}?Ah7#V~HtVOwsGP0eJD**s*(16=J74pO5+Ut`_Y=&0!(# zv(Odh5?~wnkS=8R2;koi=w40#?zYr}X?8L`t&2l;P_s_P$vu^(z-2_m$=)I_CD#=o z+%?YE6>@MjXb-GxfY2=icljQfMJ+$oc~uUAu*FB%JP6s%NLh17Fw6y9fGy1bAuAWz z$_|Clk&PKYU_&w2BMDo;QFxC9GDuaX3f$GZ0>$LiKHRHtw-96@G^J(Q4>&T&Rjk%X z3hO2tfaon!9JxaaIah$v>oat?`peNqlk#U*a#c|I(fbXRriuLt6oySxPHhl<0yf}3 zGW&h9O=MksD$hOv#n+xo8gw451GDNvlmFYH`Ga7DhdGG(N!Z#E+j{SOygBAdysy%! zUrE2WvfmhJ+j(u9j!;%Wu|M67%<l=(Q@VgA_FM3R@=rD}4OJJC0fMMZ*Tz7ZeIA$w zF>RHYOnC+&TSZJ9ekX!d4r=L-d58Xg3~0;NQZ?U%WCHGs>9F6P7-{NCq$;O@jFO9Q zq^MeFmPsxHuOVg_w#l@DVj>5U>){}(CIHYVx8al7*WH2|h!j=G`K}q&w8k(w@<*q> zc!7BQPed<t4t}8Iud1QHU&2^+gU&tdyB%m;=-!ee#8M6RD~w=(Kr<ocZelmSnWR3l z(T9l7H4bB;s#y6XPaTU^7fu9qJNxILxG@;f6Lj6^Wwq^j1B?WK-n~p9HA&yI2m;DG zXhtrQJ|cz=&E1C0B@=%cplHidy+Ik2{rV6()vvp59=XC_0nWKdn4!%9UljJIE?CJP zVL>!;$ZV#7Y+d<ubq4Rh;)~I+^;$5=Rld_g7K7L#_XM+nZ8)m)k%O5Y_<zRv+HC$a ziAN4%PTfq*s+-b~<R_C9IWYl@h@><cDO;v`31cBQ=6dGdNDM}k?z;t1zq!yo0^o!E zRk>n8W4nE?dJV-u2I%8G%|Xsng;%>E7B|K`wjkAiLTCYyV!YOW2UwHTPb0pe*F@C? z4uKPRAKnu~?IXvcf%cpSuJ(<*qY;fQQ#fLBo<su-Mhh6#3%RuiNG8yVK}_ri-GI^C ztQOL?hSYEB4Ai}{+V=!l)rB7d=yR{zZ!v&kq9P<nCpcUgLp>7)#nHg-(0}}Zg3j4Y zns0}ZR)~$E48m%{3KRpXco6O&FscMQLXvNvtGK=S>Otw%^9=C?Z=SRQ@FEuU&|9<6 zDMU@&?h^o$_r>x!z0RbbQ6BfYNk%Q0RXMQ~Fj$odLL~l|CImX*hg@wlY(m7`#K($v zPe#EV4jp|K(x$xQ1b(czb6}Yiq_u^_zT15QB+!W+bk=@;?T+^KImpTuDImvwvC?pB zT4Dm$0IrHO0Gyj?cSA1{+|nxVzRG>=?p|#^EGY90GYe2PlK2GZ|Ei*dcKlVUM@`7J z4!PNdV!qsTAIX^KhhDGcfEkSc<5yh^-8MQeU_Yr{+s98=wha#9Epe%m>F`a&OW=}( z<(~pJ!u!9TK_i6SZRfs{cIZFXqY!)LQ<x_c`RK|!cRERd-?un%?{=TS;ilJZ6@ptY zz%x^6n<oD_qtrMFGClw0qd7wd=2T@2^z_17zCG9FP*PjFO75ap0^(Y)k<UQY42<%4 z9K{yLRnz|k*M9rL!#G#Y>NcIlS8b#^VD_cOlbi`4(S&pN;))0gky@_r%atR-n3CJC zY-4)BZCLDXbI*p;^K8U(GE%Isn>`3GAh5A*n@emQ8zHR4t-{90NaFy!Dec;SLS#wY z&RU&Q`CV@-Uv_;upl$5k39wP{PslC`P>|t}5#1?YYxq-FkxQO-3P#$(+KoBhS`;W# zLv{~p%ywQYHZ?o*{Tm&~$`SY%ynv^5tu;UW3Sc}$`~Ao*HUm$?4v=g>IsP6D4%V!E zdZp8`==GUfV$UOD4T8J#{%6F1i`IEo<#`L&=d)xT?tn(TP8g88s?I<1I~lRs0c!!Z zjZn%XpyG^2T{9$a8^Z8)+bVli+4(rDE(-3tfa};@<|BOdL(Yv2_}?Ig+*2z8Eo_jK zukHCTLk_Rut6Gz&C1>N0uOF(ciEj67{?BAAJe=j>4VSJEee_)1NSp6FeGnO&ohfks zS8Pu8%`$?lOpFF`;sDN4;2gKRXMixNT}72ov$k>_eOSe^e=sXm!*nBe2?G3#`s*XV z@{V@;G-XelpG+w*^7<}8Cah~z@Su8p8+L}EMK`zU>V5mdr@BLtqtjv=?K!|Irl1<Y zET&y7v`Q0%{vLPqT@6g}+X`80&s7D`m8YT&sz*@Yr*<S&9!}$ao2B3fU-GCUy<dBd z!@qvpd`*wvXVE~puTK|s`+>^JdxX_-;FZ}012sTsm0OL6=i1;dziM?3N+!|qi^N$0 NpWq(i=KQno{{WLcGW7re literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/30kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/30kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..82cf6c9f79269eeecfa658b51ab241baa3c763cb GIT binary patch literal 117182 zcmdqJcU)6h*FSoYCS65DYE)1W1Qh8aK^#OxMMXfmib@kBy?YQv6r~6PiXu&#G*Nns z6e%LTL~5wgCG?PTayK*Y`%IX5X72sn``^Wne9lhD-g~XR)_2t%+7H?gwC(I^ozoBl z0|Rso{DWwH&?#sO7&0(y{NA$h!^F7po0*A;k%@(wh2{7EtZZ9ZSlL)vShjL(Wn<s? z0Z*J9?3^2ejY<Ca=oV&1MrL+a7S`YY<p1aw?F+Ph>lQ;sZbpWE(3b5CjN2J#H4qAd z7?^+G9s~40KMY$KnV4Bv!8SO+ALMTX+h=41n`Q<(27m1f-iMgBGw;}Y^dt-KrR%Kw z9Cyk+c#*JGOf$EV?{XVK{MZdAe>V1A{JRAN_a8VYaY#~LK~YIrMfKEgTBo(o=$zHR zVqj==)!4-9=B?Y-Hnw)oF0O9w9-dwg9|b%PeDX9XJmO_!RP?LYF^Ng<lT%XD(m#Cq zoR?ovSX5k6RbBJ7wywV6TYE=mS2ylQPw()^=-BwriOH$yg~g@imDM%kI%$J028i(w zvcT^@2>T0N+W}o$HqL-`gD!?G?%+S;b|&V%M_G29yu^Clk$0cmgRMI?UnJyKvWXqL zOyIlW)W*I`Tz+`}!Uk!-Q}+LiF#rEol>LXWKk4d)I2jqh;W2K9&=7^Olm>+s!!t>+ zYRG%KXFv8id7gDfQy90`%-k)8mGU49I};Yq@$!-u<aA$_28A`kIEBoT&IOqA*c2(w zy4A{He((Ve8f}J2)96TN*LDvSqBcQ;vXj;?vW)M%q_O+HGFVF&CQah&jg-s}hM-5= z@koi%B41N0gGmK9n6r-h2{UDEkTEpB&I$J&KwdI*wQ22S(5pc$G8coX;7%ic^VBEk zF%D-MWJZJ1vSs|(qv{a!b?{~eWm@vj=SjxW#2^VMn|%~f7pFl!G)Q&c-oFU!;3*o9 zZuS$<+If-HK7j_+i}oQ!L4^kL=yk?E7`NSU63W*7N`n@KVA4<Qx02qmGD{k?w-Bsg zPf25x3zCTEj;=&4j4Dyx5dVT1-anrwp-fp}8dO(aNS>nv-0kKMfky}XsH=#kpUO9h zL_dWx0Wj0X)=k%grZXZ5)|7x2sw3v7)Q9*j=^oDz4R`b}o}ZF)mlyace!t*;)c1?5 z8yjWn#ZVqO(4d(T_^5f;y%PEnv=bc3y<>0|W-VATR*BS2gFHHHpzJ;^z)-D1>OISG zv-57fvJ`)5?2JDRl7#X%NEaKyuXF1lBk<(D&-S`sv5UeH)EXMps&yM2B-$Sy6OyI6 zqe)w{Z<N4HfJ=&&q+jszb`2qUu-rA`4Ar2J+(MO#&3;yAIh}<ags05rAikU->^cXU zdJp~GP|Kbui)gk0VtJN!GIVa7<Ea|_;udfOuJH0+GgmkD17L@Ib>s{hl)yfk2Bk0O ztg{1&tAZyr<LL)}$72BZ*oRQ_aarywU%>g9Kxe@#$9=_+lZyD2Uvc#YF<I~7`U8DP zdB-~YXANd2Q7JI_GXA#>l3Z8nJ#vs!9lpFY=;Tg@*bVwG4aKc9>(C%eR`8n1kIdhR zl++^;(IocnuMppZ(VSxY6_^@TIKx<H>4cl6L1byjxf4)-$KxQP`3c4WiENE32^yz> zY4;kVXZmT-q^`LZ#1}Ubx(@Yktai$zHIoMIgzH&GC*w$ht*j`pHghlv(d@>qEXI+x zWsem3(vSR<GlHe`!$)+)I;?M5@4u>9v;AH9p|~HULh6=Z@O(8K;1(6PFvU-Gwj95F zk(GxUngO@UOdu2`qS2-I7Ck1mVSVNnT05WksX3kDdr8{nWf*Y1m&jQAPO*EQHNZ#7 z)n{MCS}>ER0qNaKhIDF1G9cnYA3}q2h;5rjxcyl+CM|&qtnK-8a^AYHT3WbjZe6|4 z^5G)OYDU70#s2P4idc+RcfzY$^{<S&Z(Ygp-43`wpOd$an_Acyy*LxdB^=e9sU9D+ zHvgl~xOGqK-Q}l2+OT-7)@|W3t2EZ$jQg#mwLn)apGJxJ!g=v+FH2&0!%WpULyF>g zSdh9d>?A+XmHR>zDd(!pl3RJX(|4p_zvVM-t~#yyynEdFcRVRV&%8!l7>YOT{V$a8 zXhAOTB&9x>R>fFxL}~A@VfDNeLY%q^)3Mc#h(gq5(EXM_?UUlUQDl@M4T?8!p%O8K zEFLaXv#H+bURMrxfArx{xmyy&%MICypC|x!_UO|fb0bnKbIY8$EaLBmU!%gcp>)qh zUJ{HSyJheES}vZ;k{OB8J}2&YM&Q-NM-lsIdLkt)0Rq<B;i*81>_7iy3+dAG<rj{p zjYV9DHMq(AI^i1BqW{$`QUp)&(ghm!W?c{pB^!aq_}D@)f#pKdrct(N5cCV3?}8<< z^}+ZR8YDQD((bDLdO*I<pJT_?fMNlX!P$8LFr$O$HP*#=ZYg^DljsN8BSBC?G7z+> zR#S6}YT>85d4$6QZmB=w{i?U=3~>8%Ht3l^N(Iw3MCw+vqk*Cw$B+^1sM*?+xx4vX zm$L6jzkjzch$$@LmN>Vku%VV~#SWmg;_!UoQarak{jz`CLk;2cf!DU;CU2g(*~(?8 z{5Vs0k;|3_*-gRAyahA}JA)_$jD`}ChX?>1{i`n-`eFL_B1b+coVkAf$g}Y0U%wXP z3-?$lPnnHlJcOtYE#wTU4dcOoUHzxpF$c#~y91+_9?Xp{K3O_=`PthLIeT~$*FRXu z0cw<}1(sv>FXOpKH^152HJ<!4@<di_|K)GfTeNpRcwH<4jp6nhl_>!@X@u887v&jv zR@Jj;kVa`7nSdYGrXQGp-N{gUbt>ki(#IynSk=U{ncrJKLW~Uu`MNf7L4NKOqIM7% zFCHKqF~c^DMMzgW5V3>cv|${@X4A+%Fwsw1=lyh+nA}t}(=O$GyJ!$QX4A5H=;>%` z+l9Z#XLjnjiroB;_`>4y$0|Ga8-?g-+)|!AsV0cM>SoDJ!HhbXtm?57Z~t1~7hBe_ zH*{S8-D@@LUO$CRLb+)$rr;}N*eW~Lo?otNZ~7`k+~4Edr?`X<oebsaHiGj{T?;YX zHice(5=DxJb29fJw2NR<5dkT;J!Wb?8SVHx{CwZ4J`_X}T2<-J+gi5YF{xDC{ik*0 zvwIeM=O?*g)p}~YE1t)`LQY3sAn8^0U9sYKVv*Jjzf^~=-S$&EMlS(b^Bihkx1Lp} zpDFm&9(5(QV8;=a$~jYm??gPJd4vYxc&M*hS=Q*KT$_Gic48+(8!$o#UVJIBCh44Z z7{O2Uy#+$o+AT}ZUlW9xyoUY_$!~4l1n!2>kEJI%Tv>`buX}rZ*ZM6Y`)jkdz=@fZ z%sAjv)C<EnSLC#xEWM1&(+?D?+cZSnirsC!-#6Lca^2ZpBqSE3@g09ejiF(rIBwS0 z6nWr|UK_?%r4s5Wfer`|yZD${8^*v*80COI*BOuX_gr3Y+i}a<{fS@vHl2gQ?6V)Z zbdi&VsFhzdh{P7pv`MJ`E@H>&@v)etUExMeu-s@4g@7S^=)$M=qs~Gj=-d?yi5Zww z{9_=4n@7JS;@MSQslf$t%;jH~kJg8MC{c^&+vBwL;6wdQMAzF}F7lTE+ZKr2&bY|x zxEY{SMud)+QcX-Vgp3b7^`8shc{r7wp;Fj2^TVu~G(h&<=pjqe_IPefdO`Rb5Y-aO zUQES!S8hl~$1b+xOybu#hgOFWgQQKXb+ZQ3ps|DeRPRtKTZW+DCLVlJyULvgP^%|y zO5NC(23fDKPV8<z781Ca?N!3Fg$6a^D2z1dc04CccT%Br&!s^Uj4^~V-l>v@{dO1g z%Wm&Tm@xMPnB+}>B?mU0hh1PWJhm-vg@7e-7)k#Hnhg|YGEAul>~)1+{fw-d3p&Jj z?D_*`#)vNmiX~eKIh4S75*qRAWcYWUjOGm}T`KH!_;v8(YcZY3*ui~U{7#C8EAw@3 z#wI)LBFDz@*rJzt%}zk>f4VkT+~O8y{>RH<usr3%5Pd3Qc%a1QC;I5k>mIy0Z}19B zP0m<C6fvW!WUl|65N`gkZo|?W;~phnM-7w)(urqV!HP~5#NY$uYl=%h^&br0x})rV zH8FR}Qf|=L!WJiM4cm*$)!tk97GSJbq>z4nfuqjrcA9GjYM0&ifn#?)E81&v*BT}k za&8f2N6U|oW`CwZTMNJPFxmD7bZ&c{)Wx({cy9JbEzB5d2h~vD=9O!530+y(njfZ( zNj?8bGmxoJ*bApR{<=}=vS&_K)}1@E4u;>F+m#cvdUH?vNr=AU`-v8~M!;1!KJn3h zPn6P&SzOf=v=1{DyLRk_sAHTLv`9q{uRU8i&yCq(JlU@BmQn6(jjU+AsNS#{KZu`x z@sNJPv0k@x7D7k3^Q~lFyJkt6o-H-mD&59{KlvaGEx3dhW?W4Jfmf9EdMk^_&TAyW zBfebFT{>?k+xg4TvuDpkhkkc`w$OVu-O0CzWxR=RdDiW)-F_;n5|zvHU<Rmk7{AVC z3al)Z%gr@1(N>Tz@cFV$PLx*RyV^r3l?P?oBAQhgm8Z-J1bKc%oN8=mn{g%kyyfR# zZ@h*b3&mYqyrA(9$FaoaXrx$aQK8d<$fA5IKP2<^cJ;b}yGGJ4IwEHDr}13dPD+;< zIq+sZR5X?ozZdX|^KHn9V8|nx4`&DSEWf(D!fT!Wtssg!Q9B$jw-`SJ{ZM;HOjE!F zI!-A@=pOiFVbe9J+}+0z>DVAnxZriImG!9k9G2o;hX4hw1f<Y8J**oc%2#_3`3Y{s znzbJcntV`mZ{DHD(?58qKlWpv@!1bh;S7Kz%!FAKPeOKSl}7Lmwa`(_gofZ15EwXH z07i#SqGv)^6rP&iS7O4S0uk|HI6d<m>XZiaf4mEOR@T<;wFeJ&^pC;pG{^*+OiK)c zzAZ#k9$@D_(I7FiWY_ygnI`*r*6(2JafcpG+CUkDLcp0A$CB&T1(P05+O0jVMEVLx zi5p%*&n2*PZV=0gf{+6T0-DzI_wonuAQF8<gH}K+3$*J1PeS~bAaM4(0V&5P;VxNn zV(j^6)XOxe<WMJM)P`l;-#SKgyjdcpz4(j&<k1(3_kGAeE1a_3(7TC+RV7Ws1l*IH zJ3b9>Jo1Zfa<%vfLTfp_8N&z4N1sTm=?+UDlF7c)7XC~5$&#_^bDohpHP@V&Us*Dl zsrIIg?m<_SJ;pAx$7yoe+rrz`Jd^CKuXgwtr)fJi6_1m3MJD=r9};nSl${GHFBawv zB2E%t51A{ju72CDYWH;OX`dszuc@w(fMKYl#^p7g?x+&PJ^7mXA#6(S{oRXxU;Bi; z2vToU4(rUskOnz)P3>Jj7Z!vlN8Zcb2gQ5cDEmAr=;1t^zbrTyIFzMo+PHe7qd(m> zI9fQ<vzJGu3G$51sh;N_^zg#$tW0cJm0+<j+~YXSFc#`)_B(Ei@lfvpcn<cuUAXXY zgaw=0m~1(7&GcNU#a0KPY8O}>iMZFqe%`d-4;;N}rLjBj5;!)XFAUfrORV#<-i$ey z^B@b;iDvDa8`hn{Sp66{P#`ebGn8O^L%rv~JaD6D033>G2xtATqFT~hWBcQp?ebj5 z>qxFyBPD%0DW{Iz4Cl<TLxrnwlr4q$mnIEez4f`I3u7J9y!-ww(|a8l{c(o8C}Gqw zHK4TPn~ZdJHu(z&hw`Vcb5$yor~_My9i~$m4~qR{d5=ScP9MhXdpwtDlUEn<^Wtxr z9|I!<R7AY2KwQS3STbk%Mesz{VAlSWbh#f>g<0F(3kQxeeq<<k=e<CctSBZd$RF2@ zioPnR2Sq;8y{q|BhfnV6JGOrAqd$K7sl?28{NhQz2c)ocnf!1{gJUBY-<}26Tg)I8 zsP&jE!~FOQIj%r&WO*n}27rN((e+`>I#fx6fFW!Rb|iw2@^HZQ>^ww%<dF@d=0--w zsut)i?=z&l4tdlSY^tuvH0^i|ZUnx6YfSD(fOveZ9{h*}b_hjQa0W8~tLm@b^@7?$ zjqy`u2e||}HK6%>fWG7efX|o|+fDm`aDwiII~yu&<6(rHYV}0{pWLpca#<m1_~Pku z7Hw<r5kWsy5|~G7dXr6aSIwdL|AJ=*epf<8poDBPAk6w@39?|#N$GUY@mosGp}1N5 zyYP5ewq)sfMnt0<zfymZCH7rhy4~T%)SmMym!h`Snlci=(d`l&KAsw)X6-8dxlus( zyxbABo(I$4c?S64AxsUP*#mvDxFdhPDf6fK$R#$+5ig(kB{QWO*`0B_J+fy^bi{39 z7of1kG*wQwcpfVpY$MB{HQewk553K_;Qe(Pr1kODwz<8-Mk4E3BKAXTUt}L4Y#kNi z2=4x#&azV((_eI0Vxo6!9TmUZBkcHzz%Ulh>=QcT{nSD2x5A5xqI*IDTSK&b4X%^5 zk#ClHan(&ymDoHJb6dfbH#^?Df5<7kxBGDTo;!>or#LUN_~QN0LveT^ifo!W<pi#; zGA1^%_ywFN^Il7N>Sg4sBQ0we?CW7`_#v`~m@}$U#x?An_THda-Idt#@`WsmUc&5g z+^0dL(vq=4!bV9jb#`VUTZ)`^@l$V;v+y^)TQ`bswxsg`>&>)6C`cGWb5S&q)=%5* zP3|-?<-S-F6Tdk+6$7<(tM5R*TC$8=a{HWK5E)GW@Zo_|hNH|y8dS=?h01o|GsT*G z$VZC!aOhbm3TYZV?49#@uWjDcZP~Y+kpc`aa(h0<tWVSk2CwF1TiAKMY}#M5CbM+> zZFtSwpXI5mjJSMn*=I{OhM!dO$~*c8wBn+r{If!9{f=U9#r4d5L5a9hjkJgn7~jw5 zAF0{fJCF0-IHNK&k?gXDWyTK0kX*+~eCKQW(ti4DhS&Bcjb9bsj%0L$q-{^(*^lj5 zThtS;+po5K`82#`S>Oho<vITp9(rv=nty`HPgqFOdtyG&aOC;aSY&_A=sdZVHTZt# zATRZenyh>B!P%9OrwS6|!Oe*`i)|GZ?^}E*8Y#eDhkGV25PL??pVD8r7At>VruFHd zfFgfn#q_T^KRNpd>U-GQKCWl}Ym@~ahVNA7iMfxFw+j8@FJDj`J*cqU6#EkX)H3UU zNsK>~;}IkGo$p@ddjTsN#GntTR+jDUTlH!~IH$et=L|(0pDcN#Wsvgb`yq*GC94GC zpoPpheaovvHr#3iH6lk1mG)5PbA0-?DDrsNEulDrk%~)2g)!ak`9;q&Ulbc%R$&qb z$;pzhA4@AfKksi4IKShd<pIsiuU7RJwZ)XP4dhoB_#WCD6_x}fDwOItV>m;PhDil5 zvECU?z3gRV@ZprLdRFTGc~U}BO;aPM!}E{mL#$~cTeB_oI`8HSMR#SnmUg(pDuvpQ zZ)@hJ^`Ei6ef`T+gvJiIYOl=mjN?SaMkd+m8r$9mA^)&@&ZVe85&L7tZ}i);9rkyq z8KgCGjb)1Sp1Bepnm5Lx!pfH``}pwkkHOxVud0PT+1Xaxt2rNSF?PpX`_X_p`<RE3 z=#ps?{1fZ)@mOllXxK5i9ZEag(uL!aAsg)+d&jc}LXC=zE^hf4`w1FyPaE%C5$K7r zUw>QSzU$@NiR}CN-TjoqxsQ7}UUt8J6r!~4A%p2F8no+DM|WD&usM6P#C)=M*5|X& z_{v^!7T*!6>zL9IZq`euPnNHs1#O~ASn^gCojjj*-Lx#KrbhG|MVY~MHF5KC6B?W# zyUtk9+JMv*OdwZ-@*}40QUU>BdSgf<k^_){dP*^xA4H}g%`g)Kvd%M7;Txp_JW`yq z7|*$p4Ohi5?KpfJz<LzE)v#MHJyVYfu6vGO=_9fC#WNo41nF}f#nm2kExz7x?z+bW za$*jP$BaoZzTH^bwDM7~*${|~b|E)PfT)<|JVcMlz%$Q4hTLFd`E-xx5efZcGzda& zWOvDKhwHf~sFjqjkmF0>s+~^(dpnIsN>i8k25ypKhF$RMTl;|b<bvEN{Q$}No(EHa zWgfht+QVf)$+6vq<k~kH%x<JZ=$>65E^TB+3~G!V62UzCKm|c|F`i3ET1mfCmrK3Y zbCnYtA#lgn(IQ}o!vo<iA=cGKU#>pUxnDXj%}=gmhuklo0bxfYWGm$oLHm)<QN`%& z3l4X88HN=-Dtvp~DJkc!eT$Fdi1vbYkgP(rc))>|uYL=Ryina21g*k5C@|rig<w&1 z6|$%BjiE=^oy`4A$Ip&2GwT(T4C9_6+(<LbM3GJ*cC6;%^3lBZB_E<g>dka>xfyPS zDEHjU2$Q>TB4Z4*ZJ;HU7;o8I(R0maEVz6(bdvJb*MbJ+Y0n0eFL}tGZG~-4x+dBS zx}4lGcPfC(Z}<BrnTl_%xg{9IjEK%;Mjv~^?c_`!g#|QaZ%OPU7LAz5jzr!NCGpI@ z2Wmcn>UGJU+Ous0`x>->n%=>OWykOND^FOLV)wind2;RUTFdppa_=kD2kP8DX9?rY zg=A$P>p=bD03B1~Y^&F7bz8r`lF%yxnF!*+)u+Bgm`C_+vhP0~wKwF~|9be2x{F6b zy(M`@p26LiXinbdv$t53f8iI_^Ml<Bze3Zyw+<-Izt{k7aYM^c8gz61@t_<*oCfVc z-=;x)CzciKThwF42XAW#NWS;`_Qg5B1lJ-MJKmj?)&lz;(~<8u)+qKi>V}g}jt33$ z_qH!7FZ{}-UH!3s?v{IUUi5bBan9!nrlQ!Rs9@;&{crH+xa!bQcdxI7HBT@>Q?^1H z(lTY4yP9VS&TCqj7J@Uvmh5o6Pj5kU+(J=u+EsffB#CO^#Xp<y{)a6rP_f^JWU*^d z`nS4m7Ji=L>`M;%2-|}+%V{HiJfUQHd@04c*JY_z2RMwz8lnp1%S6*vH$p{zay9t` zG3NZ)c2h%#lVinlcOo3Wj2j8xD2e-VYSpRzzC7`n(E?Af&vNT>qvfF(0iVy}vnLtd zl-ZLGQisiC=lIF!0Uw5iu0nsFrwQHS#d$j6_8#n<xqD>fJVz?xa1K_~DA?*557c){ zVSanf{kD(SA1ZSlgTGw)aDShl+RSP`ks-y0Z$Tt@;*r`~o5FFQzOwf9fc=(b$+^u= zTS;W2urX2$sqr^UqHRvk7V`t+oF(&tR~|9>{5%sa2@hR*>w7<P(d9+iW%<j8I8!-! ztTcpxSd&kuWKDbv<_Vnpsr6VhR80EA5e<Oj6MYKbWL~*aRq{(`=1zAj<@1`GYR(@G zTW{QriTxb1b5U<Vw5!|Ru~#R%FMq1W(dMG=+mF@zV@l#)KCG5d+iq6y+SeIAZs$fC zAe3~;h>D5x%H4UqXLs0lV-jQCiQ~)hY}$`x<c-Df3oJIWw_naK-n#SYwWes`@uGfj zpQ2`a*-LTy?Xt^DDa5#oG2PU{BQclXN4~5*$?#;)EG5^JXV_j^4n5n4-D!uvT~cA- zzx(Fi(>ILWKi;`H?l*bDPDqc5=&Dtb?wMnjsV9EBU5RsU*QNcHz3+vi#fV<K8iLzr zNVEDJPgb5K?5P#L&@&ZMyquQY>B?3pkdxxOK2W0R91#(h{<DPK65ytoTe+v(ye2eI z@*(ko$Cnl9ZJZ~XE~)QobujE*yj{F++QU%F_6R$R+B`aN_bdoc0i+eNk|$;?Qb)N2 z@h5TnJF;#qZP$^Kq}B;c2bPd=QGb@!g7?JDz5%}I06HuKd@jQlwa5lCR5>n)W@alx z#I$|bf+Zy|g>(?{m&(aL^%Y(eeFI8dTjM#WH?TdFDO^7N2s{oDdQ!?1Opv=#CEJsZ zp84aIoe%)sFAF{UrJcO7NTcb>f9h?1DjO3hs_i(_brTqeXlGCzly(I(6#rhLGt?uk zp-DS%mo!-P(m#kEI!I<2eb)f~Cd=}_RN7+cYHRp|oj9H(0M{lsq(YwtY4Y`7WMy@y zK`1AH`==3C5x4GMx3{YcrBj4sJDG9=bPl4<!mAdqfwSKSlL^>i4Pk}<l)}^DPs=SN z7GN^)AYfo0UwKBJF~4B%ZQ5`n7{w;+#AhJ-#U-A*B50Tf<>y<H*!p4oPf&P4(+{Ao zu0CBo{x7{_PUWvWkj{?<!gX<PnAX1fo*zN|h!`rY!)&#^f0+8l$N5(3$Ik}ux)=5L z)&Cf)KW&V{J@+>HJ}BhRL6yEMJESuv^QA$K<&Je{cSW4o)D8ic6ta|P7G{xm{f3|V zdul9v`^528jZO@5*vEvJksKe=khH5ioG%n(p*vLSCBavTw4n1X9wbqG7L1;*c$lDg zJmM~6j(i%c?lBKcQN=x<R#FnIWHox7U9e2n!H1G(6uuL)b>#b=Bz3&)%h-GPqln+z z73FxIT#6@|d(v{7Lb}>@Ld1wnOcejG+hnzxlD&5?)Sesj-fpVCi;z>*@*}Rw9XWtg zGiJ#c(JkV<r?rcbw`aTD8MDQ!xT+|NqYG}Y9-lb=)g-dyT?X^=6P__Uj<{|1xbWA% zR!SSpRy<|QpHg(<c|OC}Lw73XFK~Q)x37ENN+;*qlKJ~E&hVPGoEPeQruhTwyc$AC z=Gb26(H(ECJk!-gJUw02W}IEc{q}r$(P$Ot^+WY;OwDK8?y-08tH2qH@XTTeC9==Z zLV3%$iBl<4zgbu+)Vw{SznH3?Mah^#1;K=iT>Mp*ygBzpCeb|73f|_&*5JF|U*d}x z_nxl)GSyvi@o{_ij|hzYPS2T7M~<x<x<4HaX*_RVs@yGb&QIXR#jJ<87fq0FB%yG1 zuER%v)E>n#9mgZ>lHtAnNY9h+$8ol)7awn050=5JUx*mnA=EP?rIKSwwxlAm0XFK( zqZ{{cjke;NPhIVL`PlsO*!I?^eH7cpnci9A(n>~Q-TAe{j-*!Bw3%KX)%@|`vL#8) zlHYjl%@WyzitoJWIDr<NP_X1Ax+?HyT(#Ui_v^r;AJ2rIi|=n1iV|3NoHJ{FmNw1r z^<Ht!s6$sMHb*#om*MWolQZV%Rkzqe%&O1s<wYZk#1<9#xqYJ--rBj9JSq0QbR)?2 z*CMfRtwE}u2B~Cmz}&V4pk$gKlI+P4E}-5cuO!1<X?%otYpSqYCCR|p!NGb@lRa;k zvh;4{l=B!2b7=!}nN5A>WW68X9oOBHzLSgvf-J$d-Zq!*`x-reow;o+cyyb-U#iqw zlBnb%HO1cY-obwJ!P)TBOTETQdEPhK84gzPcrEe}&nV0uLHf$7-xiT|DRrGoO{|u< zvyrL;J)BM_i|^{?m_RF~Ej%`?TG5xyHGRL-?>l{%e6|2mKIe=}%Mk`SgFkviQqA2> zulDZmmhmqfymape+QL37@O;O+o$eh&;%VZqjKq;E3^kX`Tj(J|n|`3NeG*<|1*n<5 zFAKLf(-Lno9nsfk(I{-Y7a+v84<{fI$->owjE%x*D4BvE)e!mWWFZUELK~i_0%D*~ zHZ|C&>DEyZ%tCf(^~aNN^8Th}Hno6P0tYm{d#=bceEZi82)x@0s1d-<6fX1Sn@t3b zN1QJSl2$!+H*1&iwc`vbYHtmV{<48TJ#8so`sK4=w$f>*3ndXkeh<#FA-=^e=a%C+ z*`<n+#t!tP5C&B0`6&{c28?g%I$SbCc~5c2rT8Z41?-7vx>Uip^~c2Xpb6|IJp3gY z{RBJ4>I~AeH;VP<9E=cuchuTCwl-_h9ard;sfcrTY7`0=RS`d&RXNRL0)0;`jhih$ zhCBdVUK@t1Lg@#7%1ug$rXt9J4xnFUPk*qmUES7u{;=UTsrTm$qV_Xw<KC*AtxHd2 zJom`I1NLLgN*1z^g2RZuNy)QoN;M6?a`TlD<q*Ed%bLmvf}Qy)8WaHC>*}+?E^gg8 zdJalDh|uZZb?PlhfF06XFb>}Gj_=>^6Mw`kFbPd*hy?Ie(;$00>@qKqL2MHu57Q4A zay&@;Jbn&Pba%F-K20RsnHGp2bu6_#u@FOw21(wJEmb_hgQ6W}x5)CuCB59>%(k0( zC9mJ>Y(;rKX%r**tCEbqBcg?c741pI6@?+Ty9=g(5Z%*rZnC%S&`m0i&~dh_%P<uI zNiaMBa<FY{Oi!OS_4$R21-%jc*Yonba*z7PwAG)FpCA%$I-TAUkj=PiN=+|ACr~UF z3{yvJf-4@3G~G6SRWfFJ3>Eo`XL!#L$#LF7HmybRW95o1SDR(Y-3yE8`Apogk@Vya z%#FYcFS6Pa`x_X3ur*9DmP5YJMlFAw(ph-?`QX$0yp+=&`sd4F1&3d9GrO(cilw;o zoO@tevMU$>=U#$(LdKv+iiqh~!AHmUg{ZOIM!6cuosCxu_d*N^vC+@VEK_Q4bd(vT zn<h+u#GiS%$PyoCfxDZ0Y{1^g>A3Gi`1n)wQ+bBf=vlsz?Qph7-PLZ)sBw0;ig|Jv z*LU3r+>E85N9e_J8uZAYd~3OgZ1$=qm0X+WBjoAsg4;6vQ%5tP@2AQg*Oe@*6x;V> zQ{6xY$KfhJRs4^K!*@_SE0lYt)%V35OR?EwG4SR!i%2Ijr!o^YF_}`~M+6}WGh5rT z?9<-p2lD7Z!<h1vXtCd79z_=|3EUH6y#A$G+oEeRQ?a0+hkPRQ(nNOsmzHtkcZbf* z%FpNhsQq~MHq^i#aAT|5O=k_14P_s-IIl&}<5yiJDaTLR<&^>(Cu|=yyDcX)TI|}; zJJq$EZPW}zu-8YKSn9niY_iua6?uKr>Y8TYK_|z_9@IIbmW)ih>B{IU#Z01GV~eP^ z?K8b&V*)F0{$o!-hnik~m#c?Z*=xgYk$ugkh1QZ4CMN}Mi8}!UIAqW?NVGip%up~O z<$ar$yElgVZdGY_2!q7_C*s!Q*YjMax{I?|5Ym!iQ19ZRv6W9?h%tv0SE@e`Ydj?* z1!?Xe@Xv0$<|2A_LxVJ3=0ultXwcJulmxzhQmK}3G{2{-=;hd^$cebr`}UV{)g|Ty z8P{#C(kwK>jXztI8Oat*wGY2Mu-$aGneerRsVn38`LPdyiFwhQcP%F9*KUV9$?v*% z29E>}9t_^{(joOHlZ*N?Lw|L=O+id@(9;}@L$-{m+|zS6PGr`noiuyAezFDS;drrn zII0`7r=q;Pd~xC$Zimi+)!>TOeU(;}lNUU5_5k5{Xwln9Ep&hE@Lj#VKTf~Jgd3Y3 zDdC#&iQ}%=oV35M*GfFk)$&#s-eLTlOGTV_Qr^+e$7c7g&WRrwJbl5PC)s0$3hcI+ zS$DS>`waid-Q!_qifp9YCF33P?eVdy_*BY*B_W<$H0al6rxU%&1%>Xu03P-m3~5bo zOtQ(bHzfhaq??_@_yUmmp7!(*gN7Q!dh+6COzAh;JAz&3Ilrt&Wir6f0d9%;mfl|S zna9(sgDS}meeWX~k5+G!(>o!-82+!2d#r4epU>Ci@xeB)Z*r(3+1};I<3k&IF7Rdk z3nk;&UvT%Mn(LbM{Tv$fsauKOB$=x7TBTEy$Y-cYx0~L<Erlx0$2#IcC+53<-G|CN z6L9ta6D?dFln6O-{Jin<WcR@LO5HCBY`fKNx((eoctFki0J8TNMnMal60w!l(HM~c z2AHd^4ZW<8ZArh$j0(}R(u%H;{PL1;o41OS<4)i1y?_3&a_l0D0UyW+-I|J9<|+ip z&4KKM=?4sTHlRAOD<6bUFTq*??tHozb94QxJcm97i0pCGKI12;8NPMTJ^PnPcNaW) z&=IueyrI}I=H&t7eFpn`{wzF+e&EMGLOBWAgx-Xbrp%Ka?*lOmYpSEV#Iw7A<d*BZ zZD1_<M^uw;e4l=#!A#dT=h|+h1e&DC50PS!(%Zf9*}qhVY0$!gBQipRj+u)<e9@yk z>s#VT)7b8ODcM@kl#5>Jg0mo}jSrd=<|&Ust_F`hE>#^>I}Uc20k46;EW6o{J!Bp^ zu^$-2^ORtnOQ04~_a3{_fPE3q%?*k-TT1(2;#w$3&Sm&#ui}vtqcrFqED8C7reR@2 z?8ZcKq*=RUQyeIfDS&v;JorldmJ&Q0T)zXo*0+w^Z;p9{9b-d*uG>k*3mfGi`#RJD zm6hs<q~uCr{(P2zvgR4#EKuHcg|n`K5-heGoLdQ~ZL3Oxpi{2w7SJFJ`S+r$x#e^0 z7#9t4h+Y>Qm)Kl?-PEJ?->a{7sD)wB2n$o0a2y)UfD)1AKRTyUs*!YfVCOU>^%RF5 zJLU?=0VFt>T>!h<`zD9<3*YP~xlxM7dFUe=j&K>Cv^`6*iI7V11IOTrT^2LB0vR0} zh1a(NZ@~=I8qF1))s?`3KS!^CS8mHQJOec~78>;6KDDI{o#mp?;=w=PPvs@yKn3e2 zu?5i>MM`rP6|y#!AR(tbaEhDjjUn{aM;j<jL3W*`AI6n}p#DJWrjehr9bh2)AH_Ys zKYDmfz$?nZ_K4=1<qClYeebgSOjqXvsZ`NjVAq@|f-H3_4rLw~fE{CGrEq}AT%I9e zqbzt75XlBS8w(&1ns&8WaY8_)FUXSCP$XVMg-s>Bl|RdSkjqX$$W0F%a*_?SLW23? z^PRdniJQiqkYQi|Ja&S$4HV{BGD-BkEk8EO>6XCp4l~D5y@3q^eRDHKUGNw`I4p~H zc=AAz7u5cyCZ=;o-gb-OOF?OiI6pKyhO%FEjRI763`jbAsykg`0kVOs^mE{rHAK^r zkX6csI@fhLsZ)0Dw}`W)?|o<G?)!}tpZ!n6y#^;RDpo+f<3ZvP8w}jQs-y7$H`HK! zEyy5XK_*AFIl(=_A{MO^-S9}_+M82OUW+{nM#zp>Zv@6J?f?c<2MEhLXCc+uq%oe0 zhj`X?ejOlOy)MF+nox&&GVHnXp0~^)pKbk~Dh=Y6dYc{b1?c(&n(B)B<_F4>o0dcm z?{0-BMbY!4aIj^f-;w+u9o1oVib07ikwNwMS2bvmw*p9$uw4MY5*okG23O^)0T2_7 z0<L!(HZ1$DpFDc_5Dq&*1~M*7G$<ED<}J#QmagQbgde82TgyV;W^>&z%z20%J4%D@ zydhm=nV^UX@=zJ;s1(dX60$v*6?rg<AWFn8k_4mF#kS=E$y)Q%Rh`=Mx+O}37kFC3 zrFiMdcX_t~iP9}pXC$$x1Zo8wO$C|lxOvJW?66+pg6L;QRnsQVV)1*~YWV_8Lm`o` zFaH3zG`oRlv5;#V;kgZZnFqDDfUONBo|Z?ESVPG~{HW1nJUfc+z2bE>-K?)-S|Y#r zt_Fyj5Lk!JeeW5e78VYYC)Qh;@pO#eNhbrDfQroAw!HGQ%~Ir<lj0qFY*F5v5qM}M zdGpyT9H1+zT>Q&>FEXc<V)zz1^3r|M3{GC@6=Hh+?!tMOt_BY*atZ`wX1Mi>jP#7Z zwCRjKPsVeHo_Z|1y|27E&)+?GHHo*7QJ}6d2%O^9+J_+RwE(19h+-G#j~=bXkmjh& z4z0{QblkY2&}GT>RX9fSiJ;-WQ){1Cj;?*4G3^Q%jU%ps*vA(e7SGx8FD!7@swlzD zb3M*E7|UJNrx-A1#VYl1FdwE9w;LYE5X}jssBnp|>*A)xFWRYIh<*Q~F>Pu!Q6<r= zmi)A`UW84o+}?n$*y9{WcsYY#q5@%vrU1iECk4jKpthd##PwO}tGT<fO4?G7To*fU z^7<?D{e^z}mmTn!7~rRQ$9mAOv@L=EBAQ_^@63zh-zvW7`>BDWWY?pkp6~P@!DA~+ z;3lZ(|I{X5e!5+X+^Dhm{lS>;tkMn@Wmdih9DQ+VE0&Ha^b(lU25NV?=@ygjb175$ zo);7S)AJPN<UIGh%ijbD$2Z;a_{$bLTZaN`471!bYY)B<|B<O<Cc{wI7&3-aqQ43f z&tXX?`G3(0P7x0tuJ?M05`N#$L=X$Dc9VNn6y9u-x4be}<U=2I0*P$?D+`JfE&7T6 zbD6GB)g~X^s&e31+QQ;gbfW2cH`X5*{lfr906ZPl5c;<r#OmpGEPJylNGtx(Qq%Cn z6urIa=OG^Qs9SauyC;3l11m2Tx@NSI1FpOH7gmIK)CiW3_Zzw^c_&3_>F_sRiaf}4 z?}U_0YCCr95Qy+CfmKOhho=AKKz7mtrgPm_!RhcsvY!XF9RRZ%-yauPfL}w0m!b4> z5(iwk0x!`>*p_c);Fag?U<>WRYUl0Y_qZkX=(JCNQ%-)9Zd@f*r28h~E8ZlxjGx>s zB-Se=0KGeNFkPVo_ou&qaSI(HCDEg&HE0%=dFsIWBujA3`1yIsGncN07nw1JMvF9L z#L>w>2Dk}x@-mDAdHPnv0*OtUkxBIy6}lSogh|v9qx8Q5fxRlKN{+$;&iB|b9;aUt zMW?4y>Os&z>%5HGDYtIb#`U(tx4Mq-b8Zz_zvsnkLcf0QMzBGD_2#b#X?dmNu)MkY zdA)Om+x2#-6)W*R5948a(Heu>Tr5EU>tWdS*pu>C#te;&yhmcRLar=!-o1S9v_{J* zQ~J#mJJ1yyM*NgPdm}j-+;3Y-n@Q7Svvrq{xf$-;&easSyJ4a|8rfDZhIpC5cq@to zV^nqru%TfJg;Xa#eY$rfgF(xki*4W8ydW`QRy%>6QDS(ei>$g@PIyAhG=8ZTj}XzL z+LQw&g_MOt8dSkUY-Lol1UvzjH{0IWwcXe@YVe?+UCC3|7a{F?mCbm7*GAdvrA=7| zDW-}#;zd?z`fGc-0QoIm(4Z4C==ofP&-7vuX6vUu+aQ74La$mH>PMg70NqkjVDd*e zLmKo>5hOgo*$bkF6}qq!!B{E*uJw~4jv^<dLD@eE-fK4CBIwgJGSW>-47hrFY*AT7 z&G~It98q&QbbZPZScp&%*P7(}h=47Jl5gVM^U=c`?dXZ*I_fIADzUu7p-lF!tGRON znXTu}IUTwGYB`?k+yBk_N<P4K+G83=nxJYqx)$4ya17iXcFCw8*{-)(9DL@E>!>)% z0RNXQB<F%q>jyjoVnNj@`aP85dn|`r0u<tUy@zXGWKGTZ-f|sn+9%W~^rQXi-F@~y z9@g!X3!D6QM$%(Xn4RQ#{gg41RP1gwwcJ-FF1(-LzQjz=I?Eg4D2jn!@gzQVK^ioi zKv)CxUWTh}e9Qrs=nv;0f+!w%k<Ys6DFXb?2WaHCnN?#Y3X%>g&%pU@JZCqQjUFA* zTWeX$0gQj#N(4T*W@@!1MP6ML0HkD(Ug)6eYo@H>oWR%DBS5c*a}}_8zl5|E53U;_ zAQWETwrN5=uEg>dgdZ0IPnr-t!HmvTG>DRw^j}_j!%G1f>MbzkiTB|*2z-SGRf3Zn zPi0I1{^TE*CrxqK0-mqFGQZBN;;XP+-!%Jn7FO|aKYXy9%ectL|99Fi{YmJFC;-Rk z5AYBW$i)u9Vp)DLEr8kIquyl<(Shd~c3IL#fd*Bd8lFcqvrZ_jz9a_b^vWcA4~GV7 zo)+JRW%ZHM7KV4d)tmW8dU^jp)BB1jhNywofo#yOGT>5zoikoIUVS+^J8l>bWWH%W zYdHkiSf^4)xGFIRm^7TH4&3P0bOMeBaq$FV*V#kv=q=_@fc041JNpT<PSpn)z&g<W z@`~PJ%I-siPL0e{+2goiLMzc5z`}=LFUVJX&Mh2M^9l?=gdc2WcJmP>^vod0yTRDB zpEaPnh6a6!qe1&b8xH^<w+l@$gV$|G<&8i{Sw&iCp>kOApb5<$02m_k;J>}%d;^Yz zhxBOB3!YmMaLaTYQ3g%PTa;yi>&-w8VWYw3!}N+?ujPnrU=}*>u+LG#WW~@c_~D=c zBP(@4O>{6H7<#UR1$QJs?=hBW<8uNW;g$bBZS4n(eSjvB7V^XOpegL%xs>veno}V; z!*821;9)de6r%rFitw=d{c_8~)fat5N&h5`VV5i>Xb{It9eP>XM-2#z$}o%=w*8lv z{z>#|^5|QDW^YsD%RFs42EGE7dXuO*6Zi1l?r9cp+u}_4Z!-B$yGl{m=sNrxXa27E z!aw51Es4OGjh*VbiC-e6A{?PKNLnrNf65KTIdyoEGl{3cU4ic(8)(q8|6}T^r3%{M zvF$*y%=p)hfLQ&NRow;?bAbz%=Sw2=3JE#YPGQBrNdv|ge<59cu+FZMi~fcs90cbY z_^AOqv7$%eM<FKH+Dy@eUKBq(d4*^Xq(874PYKZeKT!8(HB*3u4d{N5el&FOz8g!{ z@i~Rd;@2-Dv{dJcjs2n8tf;T4ynWp%z<XL5jU(-<5QT@|60kH#%H|)Xe>k#(2%M8o zK!BY=BptNeLbS9{0cdMKJb?(bfULk`L7E+?&AS8r;W`%;CCX2{XZYKoI|W7fF(D3f z`G<7=cM1MEnHBeU3HY1V{<C7%fPC-&+@8+4-Hx_{pT0Y|#D9^1tq$8;c|MM{Ownrs z4eMbpbh-Z@!0}_lO|G&9(EYz2ahI>r>MP>2;YQ2CA0Af2ZBD~m|4`zCL>Gd$SKB{n z#>>P4`0t7u`gbP$lXA+AVAdJT;1Vpj@T^+?P>-6UE;(cLG{u~_q2Xq~YxpC=F^VCR z+j18A?+5iy$oWn{f68)kX8}m8J_1-9;B8Hj%@GDq`Gh4J#5oZF?4IfQxYb7sb1!*3 zc^+4YVgfj_?{j-tr3r}04|%)&lj5d|Xx#xA@>lze`n$0IgM9@Cd*imcSKZ&0!6<>U zci~sU!YT7^HIY$0R*zlY9H9)v7`I(8M;Y2$-l;kPugCeK1!E<gtEww}H#20b<nfzV znv=cmIlVN9D#aqd_3`+BTkv>tG1bJU!%lK}B(m>Qse$QP@+4JYNo3=aRTckxxJ5UV zJPQY)2mw>5rS?&Tj2bpS_}ro$J;n=Az+#FLV4Q6?T7x5*&8PHfZ4ViEZey+^F3YI4 zk_N07okOP@Gp1$))O4!i>4qk~K|s?L;?W0Ey{r_wm6TxX5h>Sh*<P)vJHNIc;i&9A z8s^Oo{Y=YFrSoJrLT}kKz-5d^t${oXJERAElKTJLw|DLhn0?0^=|Vkfko3Z*_L!5? zh2vHs%wW~cjwUp1|L1Ld;3;i>H$U~o2x0V!(EXNB+4|ArpWjZP2X->FTr$_AcX=;u z@^Qh}0f27;U<a7GVLvoYrlr_P-+0(hQj=5e+KN273A|3vxeyONJ$kBb7}M$Fhi)Z$ z54^L$YXJ8ooBwo0h(gev`J-Ee9u!%LuWj)=GWqW;naG3JIZOaxeFI;BP#RPhT`hR` z4ezw#{L%1%b7>-#OlkEkBFdTb#PhD0^-++I@Ifuab4PU`CxAr-UrzDiYzW;mB=u~8 zmGby5dM4Q|@+<Kna!Luc((ZR?BemS^aSG7@PMx{X`o<M6x&g%31l)IZ;L2oMuj6#g z@c+4G23_CyWa$u0Bmz&(5q_N=QryA_Qf6Q4$j>NEE-sLv<#Y5H`|m!qNoOW@H(b9H z5MzMkF*Iy^)V&(JC|C$GN+iMAndkJ?0!XSAdlOz)#Xm-`Ud*$k$~-PxE$3L(ra=)| zL@Q8O;n1Q%?UVMLdgMGRYRt=1mJ)Igzp{uTT~_x^43cvG&i>~;u59-IloQezmO&=i z5wMi<I2)eH{Sb)(E>Kuk3)M~G@?Y+AMbh6r=TZf!Yn2>fxNaG>Qb&rZ$-@5m9KWTo zj0-84pmrho4^0PIXppHhGW}22xa7cs|9b^|OO6KyITZz(1W;pk!M?z0V#=b1BfLI$ z3D_V+(&r9Q-!sS7i~pI65QmDTam0lO!>=(GB<19#>mkNpbkPH^4I&Tpt4Q)BMBZ9# za%T59)A>kv;AP7CjXaD|RzX1@h&vSSxT!wg@zONX?q#~vf!XQKV2NU<l+G(DZ(}aB zm441$isU2f56=_Dv}a`#ubO$xTMz{@?HfeC&!iFE`V6|-g_JEDUx@p|a&onhv9R90 z^%oHmTfgNtbWuRG=dT02|0DM$Jx=KpJ%>YkEH8?ReXi(?@1i*G%E_5FjM=MHXnDJU zygwOPD>t?Lq#SZ3WKVdYr?`s^s<(!a`Efb<l9hyx*8BC_%jGNGl2azlxB-(1ZkNyJ zLQiBx8-2mOJaks7ul9}0El-0-Z$%@;)4#nej{bZ(a%ieHF&xe2%0nc?Aw_7!-##E` zQfl=#uqVLcO8Hbm&R5G`snNAc;8E=K;L%yQNie%A`*h`sC~rqnhXbb9`}!?8J@>nb zD{VDdYK<aghclagMu%2m3EHwmaX82&Bc~StC;D^Yqm{Tvmng>Vc~S%WE9C6$<Xd=} zFIPEe8i&J*?ZYxMvnvA9zhXHJ8|BbZZsji851iBWBXz4IC3==@51rSl-EOP!z4K+h z?fwkAX(UpOMJ8KITj4oM`l_bm!!^78%IPMTB8&HLt*}imTI@Of%juCdh0<o(=04X$ zgILz#O6mNT9*#OR3iMy_^i0&CxLo2`iC(@&CvkHWy-f9l5#3j<1c!W2Yg1nZchsw@ zXnr{fk3k`iuK6sa6-)RHMHDxhbtX(90>rx2!<bz@nq9LgxkPjp-h*uB-}iN`k?jyQ zrSXGF@6?ipTcew9pK0SZ+bp-wCn9sWxcQnKx2Fs@dVaffmXylOc7giRO1T)8{CT(k zQ(<#=^T#U(C7OC_kG{<wd1)mzb4W!Zd1uZE470m<v2`PnjfVuXo-X<sYp3e)1Z^yF zKdLG&gy6&fkuV?V<4esMeq%ZyH(za`*k##R@p!*3@%@>cev_K{0uQTjo!CobT*ro) zO;7|)Ob=!xAn@6p`)v2?4f&%*1s|R)b>x4(^3YSEyl;BSWv>pV#z{@jK2>q|p(FV{ zS}~XdywmDizF*hmn>I=obQ-t2?5uMrFR~-mwW7qfqON_s=$wpIV1mWf4=zcDM<b`5 zYmZJik3at)p?dd%{KVzfx6z+M^Rb^}RrCl^MX}BREiG3Du(9{^rtyUH^FYvvacLBF z__313ZozYgiQXBdO_~PIDzD^A&sSQX`EI9fw!_e1Y)<M8VFF=0MwTU#M;vff7(U{@ z4!w%bmAzKC?)&Jcn>4DPa%5Ut6SOaBWUiUHA#M}(+fB6X<IACfxhNx}N|^)64>O*U znnlvIW4^h{?oa(Pu%ACehy1O@xqtM+j@o<t+_>f?lg@6@m$#H8mKtNW*<N{x+V?zC zs_?SX#PjP1zqK1t-X&u1VQtXF1KN}wZ-zp@C=!#<vsogw9~786u60D$dDZJE?EZPP zsL(oS)#J-4t}i#Tzf~Q$5`8$-5={{R3gvje=1{hs=ze13Q1QI{83hRk`8o8N1+G@| z&2wM+`_~(eso8Q$lM8-S>AY4qx|;GNv#?V1@OOeNKYN~)h^M}*tdgi{np1mZ?@!ab ztnc$S4LJ`8xT85EA=*#Ae=6JWbvH`VL+fm^KuMQm``Btotg2+j%R@`*?k*$gT@gXS zhl&taB3<#5szJ0TvjZ(xL&T7p!a>Dc;$au8fK7bg^qSY{)U3RFdi!hAZLSQM?-sY# zdhqj#Z0^l_yX4v;2la>tWoL~>gs_}5_T&@V!x<u)RF{EM7dk1rY4tgWqvj9x?wGY> zlD9pq300UBIp6#Ap#c?*614&bkazrSPPbj#v(!T;QxBzj^i0MoxXRr6*8Ro;7mVPa z5v@cjePm71wVjXBI)aT&xX3!>-Afnbhm|Y8nbaOF2yPZkE5MC&ZK};Gkd7{(5Vlf6 zVxK-SG==C~Y0~sabSGi8aO4$+HE3^?u7e!@R9VUA;E`MXN|sve>V%u&Y*sE;JJ(y* zTj*-OmLfG2>5$=b2CBPb!rr{~jCkl^GG{z^)V-siNw}x^WN3YPbhnvh{^ggRH{WLo zeB&=EGw;8fIT&owJawZ@i*HH$35NK;RbjKW|1A~ELz^z5nsh~sg0IC2CH=zIx3WrY ze0LFWtKoV#{4}1#mR(ykPdD&me|Q-fJBK<d=;-#h^P(TwFg^yCcA%Vi_%>=?q9l|W z(XxvMO{=8gTDq2bW~*t?etzJWeexW^Q?(TYt9g+*wD!8_J6&)a_N@}tClGlVs{XsB z|Nm`4c@jN*Oc6VY?ddDSM!UaxKKgw5J#cU*K{Rt1#?K@9H$bkit{)2us<GM{LNtgF ziy|?Hl0llUI~A@{jG3UEZyJ6!heAh*4HWjN2xNQFT_Uxn?8yZ)UBb?{08clRcoMi( z@kuZ~4k^cg0utE{PY8;e4Jcfyq6}VlDEGEvi9mRhKnW0h3dWMU^uL0DSpY-&nIHYv zwWUjl^}gwE`#jMHT9qc$Ci0!T=)e076d;*H5&vM&9}1I};VKRkm01V@b@G*&`$5nb z8>7l+s{vNd6R|~NxBH#v&u^kx7j&mA1D`QFm=fUZ!T>^kwl=WwtDr89r`kD9gD-%9 zYZBrY8P+LZ`byktS+ktG=)OJ98QBK@bW#Gp27LP*?M*x=oQ&t>A!_rUWW8!yeW*~V z?6c^=K*`u>meMA|Ge$tmOF!^q(bH1T;<><Gqzj?cEubM6WGIc2kh*urlq~bHRehM* zp$h97hwVz9#kH7Wfhmh)7LjBDxM66c>i8)#0iLR2|8HU)V*0Op%xXFE1#n~+_*OC{ z>N;4n9j>yuMy*@D>*iCuR5D7)_AinOB@!d3OQ83~nSSe?aFq)@xeGnN27J?xpeg1V zvi)T@cH|D`-0jhc#Tw7PcRelgaRmQ5(0_aya1>4T>I8-IF&+>enrWGCu!l}e#OzUo zXQ)|MAR=6Y*FpR5i6i#$^xu@{CqutrC>@^+nRha@KD)ILMz&WeT)cli9@FBpx{|bs z@XH=_*;VKoy_`(iL{~m+HdI2}9KUz}d=X`-yKn~hM+@@~2pQh1u^o7Ae-iq)b+c1} z(A;&23Y;Cfzx17}H1&?-%w|dWKwn~JF?>e&d}ZN4uI(_MJ8J+*fSpD1gM%ZV=_-70 zuDq<=rep1P1G>m2?kBZskFe#CnJG@xXted*u`lW>3(e6<GhsfLJ}+dp*{(Li&n!Pm z=f$`rufBIi4Kg0SZJ^0``un}=5gwwLdlgJHra^@l9(*wCv5i)=*w!Jd(AVdC_5`_L zPvL`+%bA?H{r!F4-p}=o@8T-Hg8G5w^EpZ2uO@eRj<yI*35pwSORSX1N!PmbX`5MC z%4sM}Wu&aZ`t_jE+cu;gTWFM@m_nWWCM}UKPVJsgYQrZ`K9A-+?bnUQeOK1s8~l@S zFGFd!w@$IHP@up6v&)8KKb_37r|s>Jg%IXv=SDJwQV6Gu$y&ru@Z;{nEYBp5(_9(8 zcgBaWV-BR5^`F1{A^h~i@z-K6^qcoynAaeL0ubNo!%L`*b0#ZzBz?8mxuC``mrwoP zTT|HUFuTP=?TK}MNw~gboh^p%)2l%i11$kphSQm={M{d=yP96+)+}b)i@yj<ZeZWZ z+aGn2_3~Bj74?W=Ds0i3yl^@&VbEeKtie&ZH#qro0~3ZRbmw%tge0ev_P+m%w)YNe zYWvnk!43#WuZoHksnVrLEE^CIBE5ssA<|orKrHksUFk@ZF1-_h0MeyPC!zO*8X(EO z%kO*c7JujLbH96^=l+)!$eMG_Io4X^ea9H@xX-g_X?34Z!6zOM#%ks=Xyj|ENHq|8 zX#p~u;UZbnL5d}D$!P%(3MY!2mx+~>X%?;XD%$J6mf+OMPO;LZiVb)jqo$(6ub90q z#nRPnFA6*~DDGg@gXVjL17<<EXtbbeOLe5-#v{yFM*W?7|JB29$Kx8D-M5@7q$g-1 z6~t02c%NTIVBX=ckAke#cn)o`K>;3pD%W|9fm5}rr`?LAe7vIE*Xx-ObD?_o*$1N@ z$28|~GOkJkLr`i~A)FfapcMZ&U2~}MeC8}9(NL`uujWwcV^bG1(C5u6EMak>vyq=+ zCZa`M?7iUzW*jYsOU2Wsk&N|MTz@yGoK4B+R3%s_t61@|dWR-a@i}hN;A#J(Qd&7L z^mRFbd)<{;S6sUkH2pP)6}K+><O`Z1>zw@br}iE1W1TuT(?j><5Y&At{vsZHt^${C zh&bq_tf@fOXHV2WAHwim3auhX+O(Mt3xAVD*gR>(*_6Ue8^&N1a5-mFoRi_umXl?} zP=e{JJ27af0MZ)ku-<o9p1x#Hc21@i@tQw|d7#?I{wA?ib6i0yA=xPXhP5$&lZ47? zxro`-dq+BnLe+s~NxF-yaj6s(j-~e^eGz%>qhoBlj8NIUgN8VW%}z?@!RA-8g^JM^ z5O34l?N9taoYOA<+Ak8%S!HKCN9o524SN=52%PneM8m0c%RQ5cH7!;8H?&k^IyZN( z%pWiegOOkw%&teij<Z7^^heHhJ?nga6FYvRH2wtGpsu_s54N+jH<=k*XE}OzIK|Mp z2NR;1<fx%N)Ve$Py3cj^xjJnMt8)q(7Zo-~PGrFUg(YTU!QY7I$}!vxlo3^>{wtUm z3RPc0b3snIL+pjfLuIR&N1XS-(?z`Rq#|--t8oTcH}p{}m<*RH$5mn{=_iO)%c*3I z3N3axI2XfJDR$@lrrTW4RZ`2^Pd_Jp0j0yMQ{#P(dPsSGOpU*#exn}R1f*&+1}dlV zU_-vC&a8{wwD4w0cP&3QgYzkhQY!NVyI+AR7vMxqT>CsC$co2}hLV;p_NUo|cafwC zYzKES3nhP>&WMig)8&kWsdWxTvR1B0uo=kQbL@f4rcQ#5WJ@4DXa|G}B0ODr+T`gN zQWrVmFdVVupC@Fa&@H|oWKRiBOmlWgl#-ImlHj__BbkK~4lo3=Xuu3+FqwcVN^4nY z6@QEKg+z^SMqPVUy<!=jCiCaCZ>JR8WVa3i-0G-V7HnV*nv!FoI#n=Wk;D3jc*K)d zwuK?V!RZ#}-I6Ri21RXe@{l_;N(s+1^t|(?rtQaeymG!Bi72*PCd{Z7d?oqtbe{d1 zpT9OElV?&%zHjE5m&Ww$S_JF5uIKg*BgN<o(IL;>SS)WPI<shAnIG5TxCYb7&d!o< zK583|uQs!ftx@om;auK}Vum?&T0t8xIq8hH<)|}c8eI-bxwTn$OIcYvV^oTIrUm3N z(IHh?gd;qeZ%!?pSYwh|3FeN{AClmYP@K{o-k*{@l^E^0Gp;zxzv>vn6|*M)gTg6+ zn~PTG@$)@1280DXz)vhj5R5vQEkmXL^>o1dL4So?K_{#~<LRE@NI(zc?6ESPz-f9f zU+w;N5Sr<YhtoA>lpud6>w~evt3z#)pPcfMM>Jh@MXtBPMP7X0Ecg~)c<=IsP=sVv z*3^bG)Y{i@LW2L3W#kmtdj!m%4dE~7P+#U}%ldHXaedkRdlPpU7#kU$wTWf$?U_2d zRz5lhwsN>W+aNhv@oMuMu5JG<D&>?i>BYuqn>jDMvMrWECB=cmPH##*&Q>v1pT{sq zkMBc@bb(CiEUYsPCPavrXTZxyvKDuQK)ecn-WgQ#vaqfeVK&vb)c<swu(*z}3ARQX zg!%2c$iHOZ=;WAag+~zCD=;~oQI?p4)SSr}IjNV2o)G=8Fv!c(RtEEkpXVc47I`@h z?nE>(91t!^@^jbN=9t$<zc>EUYV?$|*0Jffr}l?^#ha33?J{!)gWEe+!ww!sc8)J< z^|@;zJ!~QY?Z}8Y_CUVX7VsUJG=J?LWGS;>*+Ei#fwbvS{1y2~;n!*&km{!X`?!UL zD!Jt}o2$P1qhST{UxuGMe$H1ZaF6FwQ7ckVaZsU}9aJ!yQElD%o5Xy8#t?P`%hBp| z1!h|Qwo#dKlPL+<NQSyPBcD`J6XC8K3hlLb8H)D2Rs8f9eZM&fviZsT0Xz~0Y!(SB z+iuF3gjtWcvwR-kT=oUR!EK4V#x0zW*SSI(S5eU>7s^DsU)|Q3?0phIm>MC9!>$jy zgK)|R>0vimD~J7h4%4^TQaxwy%cbVv=R{J3`ZB6F7f90LkL!TYaR#A*coFY{>4-X& z#4}<U@<Q2^$6t(9MbWJutx2ZSh1q3Aj<L|WPD>lbY_Cpn^5rME-EK#rYtzFj@RMSF zQz=#Im~a8a*3Wj^{V53755ho;84JuAy)BoSxZH*QI^=p-{3B0!SR+VSEMGnKfrY)Z zM!Hnp70q{{8mfC1f4FaddQ>&5r4Nal_gF5!>-?BKO~_cdyf{^}H(=<5=TRcQwE%o) z_(48V=5G=m2O<!tQCYD)5C6k;T^dme+shFL*-)Gg+><1xSO7w54-APw)b2wC;ESIJ zWE=oi_l#Q%pn@v`@O^rxQ{a5##Xx%H`BPH4`&5-e;T=@4@?<ZYrH$Cg%DJ;%X<`Us z@uJHw>UQ;U?K;WaAIO6bSGoR7eBouq7DxTu@`~fOSh(9*-ATF%Fom2N0*r^~&wC#7 zKd!-lIMA<!H>(!tq>z2;9GjaCIJX7Hf#h+gz$(tQE#p2TLOf_Oe|_#yt<et9weHW; zH;2#U0pO2wxC_4M76`zX4*&-q4a6z_)!AjJTfR<%DX^czic58XDv3uniKz{B9c}}L z;IocA<d3wmOPBvZMbT9QI7RT`?aAX-8e(Ph^!9Q6i<9w3#zCO~FnAyZ6h+WHWI~{1 zK>HLNN2h<26f2$C(!z70B&!OcxORADl9tmFapMKsUZh(ZsOd!GkL}6F(*YSeziYus z-~RFE%r_YQ?&Xy&9z<7-(@J{Ni7w#<bYt6)0Fd`q835n@uPXq+jA9%%(7ifr^AzOM zD2ZPPw}{&Di#v-Z)@uN9YknSrPdb4N^5sAFh~uX+D#N3yUX1zj$>(G*$K%(FC(AV( zpmvU3(psR_J+P8A^-l~6I<pq~K+gKZW`3D0%6mUwor1S(j_alx!WY;N08aFbt&T|o zvHe>Rvy)>m;fkKiLv}#M*SF_?MPo)hDrc!jgg#E^^pZUFB2l$GKaj(Nzr~t}Crl9? zi1efpCb__3-Gn%uECLD7*CJGjep`Q&0L(mj9d&R~rGBDHU8rshY1QOC$=IzJ-t&&3 z9l+RA0FROmi8@^Zq=|8Am5AfRS|IyN4=6Da`;F_3#$RjC@+O`dc4$XRvOVtm02GCd zm|^_w&GwF*j%#qwFG;wkT?Ss@(f|zo0u-nIF?@xMoZq!4kT2GXAGftgzLU80yF6qY z(FG!7lV<o+AkU5eS01|quo44RorGP)!o#cBPW)?ttOrW(AJ^5dmU4rcZ%?fqhkx@D zNqNDJ?GV#JpstJ{R<`H%oG=+z?ME?Q_(0HBEL<h_kC79GRg+tX0Ab0wr!k6``o1ov zq?hoX|NOZOfszEiUYT4V9s`2NL^=myqHhUkCmu*xBWXAb>q`=xu1#!wsE&ou=igbd zuYBWhx%58IP(EO3H2Ls>8N~7&>LK&!Prm_EnIU;5ydMU*i~VMoA=Fg3wr3+dFDn%6 z(%5{yEO|WaEzmExM*2c5JbJ7g^n3bwN+^m`B_>VdR$b1fcL`nR(^WpTt5XSEI|P*i zat{HvFb%s>?d>QVV6&VK0UGV|AQpJoQAPlkBJ}0I`?9bL^zWC~GXW$Zr31g^0`6M% zxl$B-l{S42h^8jo0LYXpbDO|6C}g3Th-_>eL=!y*PyhnpgC6W*htaxTDGMmY^o_qs zUQRB<&kj+bHb3*&Q!HnMM0%Q3a1N7oc916<IJ1)rc}Jr_W?0ZmV2qkgUto-3v>uT) z0tCo7RKi;YPdVU&?l@rm1GB)u|82R<{kE=OPY6X|S|HEANs{3KH@fric=)j}kkrIs z2BfC_-~u(50$Pd>-UB%>n`z>OE=(Pz!B()$cXL+-NI^k|6NMm51RyrHZzz8Yjw&ky z&OhqSZpv9cm}SDZeAiIbrEG%!Mf6%Ma4V2iC;m+$KhAN~4FH;d9m$DEgP2eyhAAP1 z@sg4te0_;UyF3#inoZBm1>1>!T;2X19PrwQDlN~Lp&c-lGq$Z$vLAv6OC2`F<+D4U z3rM_GyYN-qhcA5(3+x91AM6VUHuqs1@dSbYx&cBl5~2{R^)TSo(xw5h6}yK~I0b~o z&WTVuEdnzFybthAC9;3m{29~w_if0Bg4#gkniDF5&60Qpm*rhEl*7Bj8%Yzza2&w* zSP7p9a$G}Te*Of8TyOO2M}w{?zB(YWv{OI07yd@Zt25{S`&tz_u|RDOm2Cxy!`K?M zDCJg^Fv{V*&D)I<^1ZpUk05)t38s!KU)LtWzqxj}gs%*<?Em`}Y5o6bSahv^%!Ft? zZSJ{+Af%TQF90UVH|Z@nYsV?w5&y-spi61V!U1<=a`0idX)0bx^YCm$sQ^aze`H!9 zfcTjY0+BV}Se*n#`3d8t(zVCt8|x|uw+_;2p^n39Ni%4@H1sST<<fKjvzqNrtzvez z{vLU{@LJU5<GnURFQnNyQ<zG+f*L@hYddhS4`^0JZgJbi=W2Fa8E^&{S4Jz}dk599 zIj40k`bHfP5d^iq1&XGxVmwCY0+XMOz;r91K^l~v+)}rf{w5i;IW`%UGT_SlUfUsW zMcrI)TO~}6w<3J5+@doouNq5K!<zKvq~>&488H_pgCm#8GI;ZyO|oNjTz7AG^5s9_ zr><~9&9K%ETw5E{iirT(_3`fR8BO%dZw*JxDUN&9;iFMZ3`;PR{Z9jXOz|4|PpDO% zr(_B!RpzUi-}`yLBk80!zfL<YtE-2hcQRqC{iG(GC~JhPXs7k-W0ms1g%~XrU#??1 znu_W2+Il>z(^8$b&|{m;mGK?Utr+r?*FNmf9{17*o7_5(jdvO;ftjGLpYLGpi1PT{ zQfzE1qwS?(Y9co-6V4bWog|qWp6}_Yx?EK1!pUEtfLuTEEe$#V)5B!2O9NpCpO!GC zK?0R*16NgIAvJ*=#1r%bWesl6OEWoDqF~p2`r(d+9;@h=c8Hf|%zjgy3vi^<&jnPR zA6t-)pi8lRv*7sH<fN^W$Nk>1WeWE+?XVsTFZbty#HApMD{WTre6f_6Vu7p8`4N7L zoIFyS<D&6#xjCCLK?3P~4eFw5Jbk^1K=5{@?h@!hseq)`6VjkV?e&2vol-trFql$B zq#c!~>#Sm5^i|(m*y>44w)BdwM}a!MZ;b}-!KtkM90kk)+k;*SmJ`F&gD&IMMvCMZ zux5YZvUvPU_wQR)R7UR;gqA5-G*4z0n8;Ym#b_S1Dv)!0JU(gzg{Nb*`;5%0adiu3 z=kZVAOlEk=#^ISA`RjH`@?`~fU%_AcOD1h5d$H3BB8lctu8OLEXjv)>1WOtqEa%<; z33Wp8r?2tqxFt;bHzFAp9xBfQz8G;7RBE&Pva)I9_Nm}#M@&qSb1tq}U%Zs75zWlV z;2EjsPhdhvO}-vLdv(G|VXEUqdgwswNnh$#PGU$SXNlba`w5K3MDTmVJL#K|ssT@V zVvOD}*S9l$x+<!0aT<&F<DmHT@}Bm+3Z#G<$U;TWF(s8p#wEq>OYL3<16z0wd}btF z-O2lJlBc-%WNT^r-mkU2Nohjl@lvnjxnx}Pgsn8mM)M3*Deo#i&u5a>YQAL}RxrPa z=QPFLoj*lPn4!J4C{R%xKk;hVoi|nvW*s$#X5l<)W^HSBUyS85*;c*A#>yYbRezmD z{!QW-pX+pY=?&8qn<t`LuVW{8uI#Yz3!WXPumC1An8h{EY1Y(ZmJ=6jOLyF*LOaMl zhB%gpFPAm!3Zc?ia?DE#*&UX_5*Z0cTWu)e2mnt$zkX=}z0)H6{zUJ+JDA$;o|zGD z0XgYvXkT9yYGBgoV?IvKb83~HVA%Zm!&J8DglyeM)6^YD>A6r)C1VhVnn-qx+Tuam zeDl>p5@~VK^6|yE^PRKTBUpiot%Hxth&nYhaKi{!t?C+0i86Gt{vG%}-!U7lOp>^m zf%Q*#kzT5)xA>~xvU);D4tGAE%9vZk{SMk8zxAV(#`<e08E6tqJbQIascO=-jFfx@ z1s)mq6zR1eaTXfgr4@&gZn4GP00rYJqt~tq`kB=>shfvAf2fPqDGhGCIKQPi{2a?_ zWEhAQpfjE_mT2yQ-Z1jbv4Ds-#$S1RLo&uL*==#djLwNDjXxiYL{JfL;1KPf>gq;? z8ttt3R+VjBlRq|;R3?ZRPX+EV#Be8w?=I@vMz)zoo$4FoKtytmQxNoT60}|z+_n$Y zmNfUSk<1&7IFDzl7%R#dm6LLSoKAQ=FrTDI@N8%-x2h&bX|@U~55I~Pd+Gu+!l>{^ z(LzhLaMZr}i1%`Oxibm?8%nvlC$2GLztVHf#873)q9#UxDp7PBy7=VAs<jQnRNP~I z=m2ejPF{%S=qznmqJZVhjBMBGB!6uUo2j!c9>HN4L~XvCGVwTQ+&d*NB=4XbDj?@P zYKKl7vpT3@DTpq-+ggZJ^vBXaNat@GQD;|bD~&Rh87%fVb~k(H$BXrC{se&tWl@E@ zC)>ITKFL8cM%*^(S$VQFAAR%F=eZk));4Glvj`#`W(6q-N2}L?Lgm@hLp)`)pqa2I zs0htzsMF>Vb>0)M(W%D{o2JKi6hh~%>5cAElz-RO`wVl&Ar|JyHmX@yS_cANcLY2b zd&?2z5yn<5Vp%;TmmD0Bx>O{Im8)^iGMRbwQ72y2C^7hQh*kSnT=c0JlnxEJMFaGB z8LV{>cR(SOU+;$mHQhk5k`qHX<L4owR6S+Y?L@a;69aSCaiiqzfYP!yt9TK81<m`R z(Qz5upEHtO-sMY4qHJ@~)6xu6!&%^EXhNizO#2v`d|K>rvGICb!Aq24)9Xl8vMUy4 z8pxihk#9dzU+G@rC*##fDJ-zp3JbW)_mig`LGFRL4$b?<%H&^!*K=EV<lu0_KbnwP zlwznx*<0ghap&vzGzcNn@hTJfQ2ebVwb6LY6O>sbksS5}t1xrazA^&S_^iKr5)~?8 z;`G=kc-!4hu*3m1jMfjE_HHRYUjcYjvTcr%DyrMFqkim0r5$~eD`=qxv=aqTHVQfn zKw_XuNHtoV-*w3;@Tp*ZdH0V2v4<5oBeTZQmG3w>%>$z`J5F%>E6p-bu$-uaVnl>H zq)tdqHV3i=5oa7nQy!K1ekIGSu;a9Dj3hHR?m6@cBz>H6Qs?_>SiCz&H{QN-fmdm! z;Oq22^cS8!KI5;;&l3gcwBqA(Za_NdknB(7Z>7l!bg%fgzl2!TdIcXIV8yab^=~{A z&tbO~>AWzUnP9%EHhM_qf!Xb48p~8oqQWJEBHX7a0Ab4okiUD61Gr;yqM|CX&1ZZ0 zt#FBBm8wyQqfnM^d06*{er)hj_7zg|^%7|Rlx|sV(hAbBk+o@feGH51d4>T8WYrjb z?V&YLb>0=5Rz39a4*!~iEc!A1&~Jd<T(K6Ak(9wIg%CyU8BdN{BFugGXZVdPO>Xp` z@K^sRt%8?T?SGv!HlLlYs&so6{k}Ib+@DX?G|MF)>I<@_bZYYg(eA6MFPP$D^P2O} zKG(Sfx2&!ankV%=qxl3oqvfs{vGjDxQg{dv?FCXkrf~Y-{(`penoCgbNb#M}21<j) zZELHT+iUJjEo;OXg;v5rg%M~|w!A>(c=wkcGG?D=&sHCGKhOF&5^t-mpTeb57S1=6 z5!<fl;OnR@LZ4$8m&veOv$d0pm&7HW%Hkpi&>SI-cu+w)g{i&Y9c(HhXsd5K<K{c= z$iW!tj2OFW{>L90!|&||*`k#Ak8J>E{3@|aHShcXa@IZeB31E1U$s)G)n1LS&vm2+ z!D;uUH}M`hP_Vj;gg-e<D)W)R_;`K%t{T0cyDnWO?PNo{*9F@FSE<5|UcXhmVP!*D zD-9dvL-D9vd!+uBq{Gb*_%S<l&K3H-5(*(6bm8&GFH+-5Vk;R3<8+$)^MP06Lua6H zXsK@BUZ-t-%||$rR-=@0O($;sWfl+LP(vWCK6Jw1(Jc8opXMP@1^k}~0w@Um&#xMR zB!V-j`wzrg+Czv3AL9V*VMhGx1auaozF!c&>enU6fSB}?f+>PORUgACUa>uR;L)NF z!i4#C&h4AXbHPzxhJo~MALFVG;cy)-b$NrDJBaiSFZT|yH6SziH}?K_I00bZ|AJGi z@=+XD{k|9GmsR6X*y~eWa-i0Ri_G7*CE83q{=}$iHhHQjX{vnq?eF1oUjg1B&1YdK z%1Vpq2f_mYGn)GBHFW~N{SVyz3-bQQS9&pja3nxw-*5KhU-0Ap&NUq5P+dkG?Gyp0 zVQ{YF$25P7-lLkEvN#^U``=w*pE0C5?N&e~<msX^53}wE%B;(B^XV!8^87zR;IbV5 z1)S#Z&ruM+pVz3liyc5KJ3Y8Z-I^+Q&K0ySYYYg({zG2jV0V4<RO<c5@5R0K52sK0 z(3s+~rBn{kEFcad05!h{jbjk|WZ<1bpyG|%`oCj6{@+s}4}Ke&JR$(d9Z`Y%ni2J1 z&*3@Y<%tBws9-bPt5@)25B;<Y<AD7-1;`{6qY>0Fb=><RdpfA9=}?jT>0FSfq;uo= ziOx)@c&t#F*lm8}pgW3-0XL~21Awia;h74QS`5Rkw{BB;ug{@Ww7Ga|yB+e@h>CF) zD%yM<#R3xdy9LE}v=pnrh7q=>xeZy2p%cKBasr%BdIP)<(Hez&49IMp*5Ie`{29BH zTW4C_wMQWjS+ya#;HyQ4>ztkn%v{j>T>xitmfw3Lc~+Uz=#Tra*yFP?G{&N6qK{SS z9-FRlATyiK`L&14;<^K8wh4ZQ^kVvxsbvVT^JellC-#q=f4VD`#7YzWzC*ebB&hr! zz?bCJ*yYIPrBZ+mIy4081<pJJ0*`Kpkc%%Y5k968;Vd)5%mYViKwG_kodMZ@Wap<< ze2s0@ybgXIZK-6&D*yoRl)XrK!~cZdzzpD_pvChpfUpszea+eXs3*d49O*0>X2TwG zXU-#sgtuj;pKO!&eDbd<mwyOHAUov@xk}PM2rxH-5TN=SxTP}5xA~KUTF2`xd-B09 z6kH8tCeHzD{vaxY)&0{NGANC}xc#tSqSyI+vj2Pp`ceu5JuO)P7PcgQQjZBBBd-Fw zDk>y-zhqAgP(aF2DZ$-o#V|hc_vbj0Gh#g^TxVo_+)0CeDZcCg%<uwwfzVF0u9sPn zqXq;>m^ikD_ap{^ZWDg@fWQSX_mV;aMDuKqmmimTe&zMeQ2{sL|J{AAMC?qi{wm3r zZQ#U1W+#ht-$(xFIXAxw^ey3UssTu0z_*^}=&t4aors_DUmL14!HG}wKnFiZRY>@Y zF+jT$&R-%CsjfO>I91}qXn>Oj#BaoZopia;1(^O1_&CQpgti)g=HLzaEJo^ND*Z_B zWQ_8kmMXRY;S0!h^LLo-UizD)x(6R&31w?B<;KM>IB=lG-&GD&Z^#e}opRSC{alq+ zrU!1f)B7x1DNJu>xn0YWzC#5u`~6cNIG$z)<&oD8#_@W!Z3tSlCK~1@e>O4R@G5pJ z-z@i0wX>?Ki$`;s3(i-ace&F4J)%~AIP!Ku=3^aMZsNi>bmO+1L>u$wBtYru<!I(K z>^|xe9Niv`sc+hH_uIySTUdqLN`vZc+TcNw(RTHo0a;ISSD&j})~f2i2v#^(y)wtE zqjOof?#)uUo2fTCYGNCRnV|`#A$Zy1-X!h%q8b^zl8z5#r95TQdkkybNhgw|VX09v zMH}@Xn_Ic!)=r}tRtdH8rlk0loEiF*jV-L_<I9?=m{;8$dc5Hpu01SPe3mzFrxl55 z*~trGa?47q5~9(*GV68@Qtgygn~wcu@^@a)$2?{+zY6#N{;30%p8CDQkr$Q7?nh1= zZaKB=>?mqa7j{%!oF#3-<G7Z-%n@j;h32@pC_U?t*x?djDDtJCJ5k(9mpSR4mJSzN zomPZlxt(f!&ul)6YoYa8GX*v>F&Apu)8@xJEM7Q3{prTabHrexwu$<ZMPxsJ;hSaY z-YA<DM%xu-S|tTh<G)JEPlPvX=I7oX&M`LgL+1_yhBn<7fp!c#<gL4tl}E*w@~tNe zOnj4GlDPjBsd~M{B3wB<?sQdzx3ma}>*=`PD6p!1=$WX)#MpH3V1dh{x7zFUK<-&$ zN54pySbbg5Ek%!l;X;+H_&ZJ6{NpF>Pe+`c<NsPWP|$V_x9bo`$2kJQpNWmbFN9q2 zfsk2lOn+3y6prJ`*#3-|npvoyP;(@}#zl?-esMzx9k}{b8$KzbTmTNSj)8b4%-#`E zqmPo2U2xj0IK2+xplhbLpLA*mGr$yvwyFw~;h~c|NDjIUsrvpL^A^L&C;SDxk=J7s zs^@y(vx=Ue{*8!ScxMHC965I)Qqb-^57R*#*Vh;ON65e%4mCAaG?EVe`u9wSXYC+2 zqGK90e-huJopQlpa?(ieS*^D@fe|b{Oo7DfrdBG>X)K+ox>~R@$87rPEcKj}+nLOd z<y)|A0H_UbW`qj2vr2tS50{){l)GDGH_qs3N{$t0s;(!-)sSP;E7lYFESeP{?{6_# zU4L11rCg13yOf)dBF_$WLMv^aqCl63)9K7flM5|r%tQN#%TVx>NP@tAP+8?WS)Y*h zd<q}lge%+ZPd5W~u4E`Ni?%30{IM1x_wFlev<+pkR40GQ7}?j=wO0}GtalC9&hhHw zaa$0B=Q4%VRjZe;qMYMyPr1dDd*rKU8+%`uR*@JNV8sz)^7slc#e8u~_f=D{h|S|u z8JIJMGNPjflc#_&3u}DjTmc<7__3MLv1Y2+KJpIYp1yUt*Uf|W8JA)VbJD|dz6Cwx zWIA$7to60<H=|Peym0X*YNR~-$SXj9nNFWj(mk$G6XPS>V31OqK*Jn;-B2gte#bH$ zFYWB-hMWZ@`Vk~w74J}@;I#RusebivBizSVAf~~7M%dbUc}}HYqOXDsjVQ;^XANxK zQcvakk*5eNpwiAd2wdp9upmAaeq5KEBjawRT$3g+idRGVYN7oy=K<Ya<hW#nO)k!J zw|{n7zlhP3(BAu<#Y*g!@Ez4#AyQX{-S}07Q;B1KtfRzx(>T4(G<Hmb;VcY<*(Ztw zQ)tMV+D8Ykln;I&V+ip{w(>qiT1{MVDMZ?EH?fB9-y=$6DP^#Qau3AO!^SCt#`&c# zGkvv{DW)~{V55d~vS{c)s-<)_lW1mO-qyYHlGRdpOdMn|C(wO?iF^8`Vr;l^&fRX; z!+0xQ<7s@&mJ$k(ej@%Lp2G~hB{D%9ah|Pav<4e`C&lwn_SRQB4oQq}zI@Vu<Rxvp zv^)AKD<r6Yi&8i=O`h=Cj{~O+lm5Ia&p5idACfuRC`aTNbd2psyt^x4UTw=6V?l2| zrP=hMGhUIA?_#eL-(w$p{?CZWPpS4a85r$j^O1z|8S(AYCfaeZVDZkt8d>s!XfJ}N zS9Dqec8N9~%BP<4l1J;>RH50VR=6~uy6{B*z0fRPnHcw`Dg#|1yd3WBe4kre{j*8k z=t4VMlSyOK-1NfLVI#E*g}2E9TKJcWI_#dfuJj|z6|EF(Zh&l1YYW)<AQha`#p1-E zbnV(<>xLoLd8DHRos$z~_R%?I@-Pa6TXBiAFA}DfU%hM2Q-FXwi)O?5c;`_&@YiaB zcd94WcpwKOqQcpFjF@W19JyR_u`kn0(p@8Q>-Er3zU<K~mhMzmYy=nYZmauU9eXWx zA}K(vyh&rhs4bUWj0*R=X=awynQvgvN|o-KXc(D!6{C`Fn>0HkxKyL$t{G%O|6YXO zn~ckk7UqGo0@wv`r~^zEctIT2p_(2$JaBwjHopI<Xc_t}^7F%3zOu*P=kGChf8B(f z7?!4h=8My4aZ2cP9M1|;nRu^j(Qr*hb8gjZaFWcrdUQ-dm4-#+yTzW3d$red>UbAk zq0rv8Ww!x3F(Llq$7y__#^nk5)dZr>_-73j5nWXyj<3#_hkAlV>Im%V9Ep#$Mf7vg z`E`35huf+5hqBWpR)@lGv5Nb3H@@UzV(vU90xxz@qZ%MVK{!qS3^!bbq+x{T>P~nL zN`R(pUD$N|+fITP&|}rG90tTsZvwu8$vDsucgYs;BM_*lW2z|v5N3WP@pJt8*`pt% z&+W~2DFGj>)C&kOs)7GJByk=AiU<F<l-)c(0$eK}M^gE#oRD=KAFz$s0F3-o!Ke+8 zhVr3loB#vuNf^E%KifF6ME-xZsk-z(wW*Q<ew|`=unpShF0v=#&%g-do8aF-hxRKQ zzdr*B?7)?L#{!+C=!nfsz@^wP73TkO_=TjHnjCQ8UjGufU!^oS$V8bPQ$N~=6G*?D z{|YSNxn=-V-E1g5IgI_a6m8=!1;D=xZ4jG)A_JgZ+&<}8JKBVGmg}9-XBK*XYQb7g z3{X{|mkA#LE)=0gWau_IQ+{wAj^}#KgeP*G?$4nNm`)gT3TBnR{A|6!lI;G<_-a(< za@j`Z56~jzuT=5?5};9I2n4aWjyO8_m4WbA)!gxc+35*l!Nh}}G%UxSF^!{w)w57I z@t%46<AnMBMHgK-3MdL)0fKOIxj-Ne`Mb^hWgrWL%oIR!pdcba3a9H=bs>#AT1fnr zO4(h#J6kPy7k!4a^#_-n@V5<j@F%4N!mlg<8bL3juO5+DiW@fpg!Co_gi(nx4mLCb z83LBqCpg!VegJr?^f7?O+JK6MWISIUPyzc-pZfn8T*pC|IF6LGQ6I9};}&4E(`=+_ zOj?HMwao1@174^aftNJ>f4K6VwG-~FY*VFtvsPMW^)=@E_c<N`_JoOFHQU3%cZT5s zs%O&_GN=$l+9nDjoSJargvsqftFbO~*95L6Myq7({<MsKJ6Xq<&`AWn{N?52SI_PI z4;StVIy0{tPON;`RS12erRW=GZ-)^-h8$ytPCQJRcnq}G9y@CW^k)wkzH2;WJvyPv zD==05GVz%8Zb~Jv`R_N?6aXqAp#g}o14ake!$Y!wMg6C&fJ*7iCXAINewkQhgygQr z9J}4+io5Gb_I=UCNaC!79iRpH+t`%Od^QfCCv7S=>OtGZY$%@7j*yh*ainsayHN!` zJHlD@y2}9II6E`@!!S1J%j{SK<l`3?e(ithGa%bZ|Cdlil#dgjElN&O_lLP@{Bfjr z3+OC9S+!LY43vXc?0=H$@(P-KWO~W1tFzcI5Z+QZM<x)|P91_^tWtKg7^#dn4;~W8 zh_t*X$5hcH-n(FDjw-rI{)FVb@(1KQM2g>4;Bf$qS0adS_nU^dP~p!PL1hnbf@$o% zB!?cM5lr^1B`IHJnIh@+Uxj`rf5XvN5r<NxEDDn5Qi@6&J@j@@+!IHbb#V;9mGOJ0 zY_04jceVtctqrOl&KmC;$<ER*CJigj>{sl=BL^1JL%fKbn26NW+!_>gYcRX2p}Z!k zb#SZaLY+~KC>wv9YfW{LxxO|3Ipo#mmn!S>mvK_98m5zw`mL?vfyr<?U@Zh2Zs*j+ zJ7}J0IOQ>CMrS3>>R;7FKD}4dvwSh3PLQ+BlndyfZlQxsL=L<+y)?euj7`hSo3q=+ zncG$|9~ex>k8I5@W!bW1e0{grAb!K7eK7c2WV8~85teSA=`Bok{<QFcu))YqBhb!> z^VwKs-;G_ObnJ6Tu~6r8gT;gibE7Ce18#?$bE?bA0-?PHohME~UtPah)j4Wu7KW}Y zxrH`|#y_p$@RjOg;jP;4@bnsD3>tJUrO@btGRldBl-}L*xhe<+r>g!edUi|qzPDnL zab{?i*7~l$mAVeU=5nRQW4?Gwufqfc#%qfY(7usHWzR}B)t@><<VF#S8Izf&7HN!4 zJ}$@6(_AdGIj!?fv!3=Ual{K@E^oD9fK2D87T^hnJ9>)I4M6+K?`dM=Yub#mKTH`2 zWwJ}@F>0<$ih?cJIVQ`dxhge9^Hr-uGWR(3*NmZ{7N%j_ISP46T;zlE4{^SzVx_;r zkZv0;YXc7a#&%-1dYEUM*~ZB}Mge>8{G}N61`9rp6ndnW>22)+V%>+iSox45C>!zy zucRN-k4h8uJ=7`J_IrpgArs0qa@%`3_?Wi1y;-HOCrsJ(x*#%W{~2L#Y4;?XK1*F> zr72w^`}od|dve(Fg!mGoi4EpOv0~6}%t*)5V!(xY-qJ=L1`XP>H@{uRV29!#EEO^o z&DT^zCuR8u-cDJ%e`-)rIU}r$^Eu_=L4qO;!Tv-RnBTaEFxzS~?Wmk8yS%_?Uftlq zR58f7rmDhMfm37o5flMYeM`e5YxNV{BRDWMaQF@*+!p13I7be$+j(Da(>lOz=f^)- zQf1)BY%<vg3U<F7gC^Ul9A*v45be3p!%*BEDDc9#yM6RNC=lpmmDd42?>A(63y9g` z$&);Da&fe3vdHRs>yPzSJN{Wf!`%aPb(MD!YGlEvbJ)UL?mH$XE=u$%qj0taAjCCS zmL4R39d-*;Q9M%`F4(Aw{oLKzN#q^(U>cQ3zozcac9eA89unSbWB#>EFuVILdw3hi z3`YXW`Qt0DXXPa?{dMl1-d7i0Qn7~>WNF42htlc|*>xMWa|zqR^|3+*t=@NB7_dLd zp-IQESxJ||D@t@wb^SHBkt&o*k+z+dj_pW<2iYmll`iufjy3}4Lg!ZImq!cWKoA)q zkI#pbh58$8Xs(XE-U*fX`F_jmt;4jz+S||3v7(>ysv9aipj;7eOOu;P@f29aw?I|0 z+hI2jmAe7DCeLcpG&0K*riAq@vnqnR(l@3JL0S_kG8(Fa4cqudoXrjLxbFoI3;#ge z@MDLH9m-+V=8zl{poIsC{&+h#yWAE~TbJ_4<&asQJk>k(Z;oRdjHlZLE4^M>e2@c} z`Rupx?4_Ie1;#K(Lb?UvqrCXcY7&Qk<tMHNEPG-aOQ-|6YFLEgHs-H^tLFW53|%x= zxNNV<xg7H@krq4uWRD_C7@+gdQhRBy6Ic>^Sh+TtR~Z^Vqa?WmPI&$Wef(;~{FwR! zKs!-!kfT|<Q0mZdHBbR+?YX~50ez;~q@08m@2TpZR$_I2uyzisTcl9R&85eNL{i-Q zQ*q*iAt0qi@7F!a3#Oca`Z~hErIV9IiIXtXr;*IL4Ze%hiImJ<35p3%S3Z#aMSXL{ zk71R_8iu-&pACCf-YCz7bIUizK|1u*thgGJ0%mgCRWapA$()&nsX3km79C**opeXr z^m*aUfKys1LKl-5(tO*#nF-??)E2xW$A-Pp)8S<Gx>~HM((QX`-j#(qyX{HobCs{I zZ;dwAP{!`%wObQP=?)8j$lt<?<1DZora-GT6u$!>1RN?^t)x3vEFQLI6Qf~XYULu> zIWhK#&Wv+_|Jgd5Wvj|+kEn4Ti>Agm)cEL3oxS#<OM{ALjBB!Szlv%S`Ci!4>o2Es z@32ho@jUIZ$mjVN6SX5eBs6OT({~VFT?Q>09$Z0%;E7?C)OE#FzL;XYv>ekD6L1H- z9MNuBhbzqJDuT&lD>2G8a5p+*wM;WP-aEm^pWM}2KDMMbDB|8&C2;om4fu&WO;*hB zyqBYx7p8|MKg2plpnN4ajIgjYChu2NMIRKLymF?KQ*+U7hk+mRZ=TEN{ZRhmXpRgo zI}e&vns3T$f1q@jimgEcSNqDn=O9_*J-DK*?wy(ZGH2e}20P97#gxW$+Yd@h%z3=J zx@Hs*5ChzLhu+TgN<C&S1m=y}ZwM8<vEJWa!lpL-p7eCVf#TVX=?~}1zsD+C==UK$ z3@UF7b-CKs$VoD$6g-wJ&yD}()w|`^#SW*5s_3a3H`Zuqq54?|aFGGFR_;9Mj~lNW zvuE-_?JF^{+V<mtbnE>&(2jWfGUQ9+Oumxvb<Io}5%<i!QY0b-ROJQKZca*eqIQt! zbZZ<xS@-D-R%M2#+O2X`EUO{VDl%@{Md&lSMm@1sWs-ce19gAGMQq?Ubr4|HLfef1 zQd9Zic(8H$fT=C1KQV_MLaDO$vL@_^$xF1jo2+r;GsRtf#=oRRLd=2)WpXa3s<;}Z zF?lvTeV8_;I#7bFkqdp@0(n1lKs$lBJq#veDEcb<z1cD|VOyl4o4Q=nAghF<)szY+ zjh<tHiD6TSLRhM*g>)ud>-v;w9oA}R^58n9gZM^a&kPq$MkK{ws&P+4y|2vbEY9k- zM;knNrALnOb4fs9N6L#NB$QoM6T<c6Vv{vv+&5EVcK8b=@&wd{gtAZ_PC?(riiWwq zS@lq}KNDk@Hw(xNi-Ww(0@G2y%3{^{oW(9-AJe#Ts-o_mx3xCn>I1A@`v5!s`q-<+ z%K!*KikZ%Bq;XXzZ?&lhE<12OYp5i>#aJ6YLwlrKBUzN3^z!5Mhpd4OLHT=zxL7pB zG*0pas4@%u^x4p!H84NVm>(G{WBlx}hW2G+!l}5mW}Zcd!wO}uW`P6#@m;JCfTr90 zu8iz#Il``IeG(GbFMQg#k1(pWt_tN9Qt41;q$OQuZd34};|xgbHI;D+m1h{kTU_n{ zQ$hK9G_JKK31uyqh%VYQQjq_gn>HaNJ)$uRQxIiS`oKqKnWk^z#*_fVD_zEnKD(nW zIxSl?zugqhWWzKxwA7%x+&o>AC~}NO&60LvO7uXRIqZs5k+&mn^W9e-_pq07Z5`2G zctXi;@=Q&-0Qa<R)HzSRl8Zb#pFD^X4W8ubeC-uwhD@WwHp(Qv&lweBQc-QVf`)v| zl0<Pj4|WO}bvIhnaNO-zWa5ZLU^L7k5H(Rqr(jq71wv8dlVSy)0Aby25XJgyljhVz z&$_qVHEB;XBS8{LW44o0&h46>lS&^?5xRbY#2&LNg2LjERHOOkOn#UKjft(%LDs8F zg^N-t(UVj6zQ%MvQ0#`duy>aiQIqvtH1>N+oRaZEI?w?xolMj~*rdQDJY+weX&?_$ zeIyfO`qa^3@TNDbr9ipZ$D<gQI+)`tOQHjsTdfTzaEY<n%s)VOt&i1x0U{Hv+|NN@ z853(SWE`p@3Ce_Oy}5s$yFWpevt=k>MI&xaSO4|hL5*U=)ccB!Z1Kt?Ii4H5L;9gE zd4|`tmvcbp0Z^w30N8XL0L&Kt%0%ZX0W#463_J(Ks8~0?ly-wh`{4>tP*EZWMSpRB zi@NOTlCnSW1pqK-;Fu<M{G`z7DE&lF_Te88SjWSs$BAYVZnH+~9TP;Q{SLwVecff9 zKdBgg5y067K*s!AqWPQK|4-8Z8d<9imhKykj7l)Sd&2lElAYc1g|qa!0^}_2qTitd z+FvgafT{loa2X*T2hwbQBX#<osB3Fd)w>2p#tAW&mJzUO7V~?T!CJ<t;2ijO%_(9t z9Uyc?PYUEW|AU1G|Aa-55<vcl;|xwW%4(NkeUrPn=s}o*2iT620OC^w+w;I0p2f<% ze;)FG`20p<2L>uwmvWt(d{|81Zz?HD8qafcJ_#sA|7YxR)ol28?kQr^@G*JCL-wdM zsI}NZO1tbwQP$9bbYmU5f1lil<xZs1^()1pe<+fX%>Fs>e=`rMs$^xns&nF`Oo+u( ze6_hJ>MalR{Y?d}KX*i;7zj6B1j3nSmjRl@@Mp#!V0Dzh01iOr8QvBKImJgM%etj~ z>eM*fx={F!T{?U43o2h1D)Vwet3G;})wSGRPR8<dYWIzztIKp~?|)1}>W>PQKc^5O z{IvPUPOSFGXPTC4veWlpSu(Iwy^c1Ku)$>!A4+imf=EBc-T+$o{}2U$vhzQmOCE=k zYzV;~<(N$=zl69N8Z6i@X!=`yd~r3ple-L#q8*2?jKX);fxLJfz$VT{JbBN*2M~Q! z9URd0m5D4dwqwnXZH!*q6Rn6T;=Io(KCo$GMtoZV+))(|847=sKd$LN>k)+W05gZM zt~cR-URFMwS=G=GDNREHo%zP++fHJqp#!h3j5;BE1h54cIi?Ji2p2Mde}DHzdJbT_ zzFPquP{vGNK?BEDv_>MvQqK?2JiHJsgo@tg3px}6ssbKP0Fqi08RTbmCv<tv{HeI~ zs*IiFP<z3>8XH(auV;+N&O^3J9kZ=sPU5@g@VOSH!?9>!!+AkF^BGs?0Ijba1Q35+ z<WDY%YNtwSYSdVJCB(v>cn$xPc_*};*bdxzt85^`sW|Cb@#1`-Vh~umeadtqAqjz+ zf<y>woa$zsf5efX^oeha<w3da`7fV=hmM0C$3E?QB9R>Q`?^V_fQazLU+5n`qQ_+7 zS^PzRcCEtDV5U=`oSRnsg(~|YLm&M2`ALe;G%QdigaJ>gACmCXLwi*d9<9)IY0Ked z9RpHpkrWc3P1@#a0pj<%M*VZ$4;c&J0R-s(?swM!`saJ&qDjRsd$PIdA{Rq0D0<VA zs)ttm9>VtQ0*u-I)8lT;^V64~25Xqf8B-<p=#KMQwHLve44^Y>OQCay*wIrWRAs|| zs8FBc_|GFH6J^qJ$6v#!#TDquZkv4jAPw}@QDCq+Wzqw(HeLZr)0=~5rf}Y^g#)`F zMeroPtKOh)qgBeD?4tUDo=H>duDG5Z?y+2nIJ35fMZ$nAWM@+i&>|)P;4S{yfFA4< zq0*~&bE2I!KGp^;Po-Gg&!F=B*NgRPN#A7x9ke4pmae)Tx)4%}VWg*YP{^V4=qq8E ztSpXMe`77r{?@j@&US`%bIjeEr=P)<YGQ?VEj1MfD@o1XrdLF@QIv)tuFLUYs!s^} z@mRg!B6q71%c{ML4JO8&S7NP~X7&8G8WQh!C>atX@eT`4RCqbe{wyC>dt5{xV6sb- zrqt6GJEU9q$z@5@>DgU-3*@bz!>-O)K+s=tFm@}x61{Nql<cKE!I-AmL)}+I;S<A! zy%a~WTi->4)r()p^XO>hvGlv9cyp>Ih^Q%_j?yZtn1-BAGlhd}q#ctWQ54Xab<f)7 znB}KcMseXq73xvqQ>Y+FYMDY6t0<}7<Y0(tA`0YRRT_x622;kAOrcbiFe}eTB?5k= ztJOzNor2Wk&3*K9G@Pw&HBS9Bh!tguU=Gj|G(iM5-+|I~&>9)yeA;#0W=!k~;f!fR z$6k<ENK($JX0Gr{x73#|8ZF(V2^|h2J_f>_jb<nG@%ta07@#Y+!tZ@da<&)#q?p4) zA+L0$i&w_eMQyivYxc-yNsfO3P!;$jOl~7>%1uxIQZeGSJyeE%hHs?ozM(s0IQ;Ig zN)G+vS`A~}bjnDwS3bZn&H1}qje0m;wJV1`#e&;*XnNdGMox^l)XevK^$}@O4OMO{ zM&E|BiUy1Ls@HCXc(yI_2GtQFVInBA$;1VCILrd2W~PlP4O_sOp?XTGY@0c~i>xOI znZ;aNO@~RwOxhm|v%pJb!QBy8!^^)We)`;$x8V0upgflWMH?5RqLHktq7iFcA}GGZ zR+Tf7<d7yz;d>hk19iAV6Y1V~VCi4p*K(rMsqJv{pcmB9eV3!W`#Aj8mHWf*!dEmV zRlN?~aGjWR6ce5vq%-DWK#FZjY%`;`1!&~=MH2c`&qq9-9u!ONcB)o~+F1np1gVCV z3XT*=S_$4RQn!G23jZwGSx84xQ~6E!G2%SX)bHv$vV82apt3C|P2Kt?YCf-HE9_bQ zPjuRhCj%pjZ>m~;G9BGA-n<#-2YFmuTb3ZG((M(vJVaQjstpNk6fG*!84Tk4wtHof zbp|Vp1P9*`8y;8221R;A7>-)e7FXxw_sG5ccJrQ|xhN^;18@1NG@}I}P9Y=;tN&Wd zAEhX6vvW6JL2$@Lw`sD%aS)b&0LpTM=PH8RroF=Q3I0t@SJiA~Vp1TcDOjzv+t<P~ z)kOkqYnaIRk`?y=ZEz**<yP=S7NC%!wP3cHdASwnA$J4lZ<Dz|kq9X(RmVKyYU9pw zk=yNK5t$Ni5aRCL-0i1T@^qlaaRc282PS$BpAR+PRLk-%U%eqRA`WM5VO76yB9~}K zObKIGSeEQnKw5PSI!P=`etJU9k9BG{3znD1$N`WI?~OL_XcD!Xgm#p%niw0Zn~RWb zm00N}jalhB#I&wr69mGGluLMwF*ZSsYS|mFd4e7Cnrg6=m1C1%>zY2z>T^-CGPs_8 z4kx=a8LXq_^NJ$YGy+TyH4^zYo)?m3n1ZFtlW8oFxIH6pwOuzF9^;Zcq;6ayqFhzO z$iEiVD%QOsqwNw?Dl@VnqoZ?oC@er`gx<nvim$nw9xJg#?)pACCXY<laMUCr;8YAI zh{IyRfJgl9D;_iiV?fPFsgKv-Wd|ipgu#`A9%@t_(he3QR<)7LR#o-&t~`;Dcy9;R z`wLd_oWV+N?djEt@9|crDt1S6mtkCREYO_d5vv28+7I(b-0|Kna!=Fk?XFQ+!pfCJ z+zy>1>O}Zfcu@VNsHi|9O*O_hs!feaBk%_z-mL)qdT3KXC2xD1=JDqb@5#x?DHzRr zr@ioef0G2&Fimb9R?W|dX~`@t?$t~Inim2IcH7*x86SB+J!gAYST_-;n0?QU6H%s$ zY^FeVr?^P)eHpeFAxt`GsDLMC#21h2oFo@`ShOp&TwIRCKsi$HU^@QA^1Q8MNcE)W zpEI&!bGB{?+uSz|`?A(0^EIW6K6_5o6~V*B5ecFsa^j_d7MFtPbTTLpIH=uEtO|Sa z2&hTHj9L!w_dV_(qv+aN8Y#83qMLoN)mH@ZS!{h`tX^7YsbSCz!UbU9=)CtZ!OwX1 zu~*{7PS3GA37<;Vq{gBn%$|nzS=9!vk52UlYTUVfdu3$Hl|!(mXcfUE0b)<TF@d+K zt3-Uo?5#H6Xp$84aB;BX+RB+Obau>5;7<Tq+v;l2yB=$Ch$@@jUsTsZgExQ9(a1|o z;H{f*2y_=uz}CglRAMnVD{o_a3@>Gt5!V;@Xnk?JI_?l_-RYsrr_U~j&fXZyT?p?m zbP1{xw$hyv&sX82UDnX8@Ki-PLY$(4!u>dwMI&Eo$>#YZf3%rDNLA4m;VV|@XNV_f z;5@MF(7xMR%&Vb^bnR$jjV<mY|C%CzJ81*b?O`lFnD-hnr-nl?S@|F|h(hgprrn&{ z@PUuC^>7Qb0nc9%w0BJ9-7j<$6+~gB0$|Fy>uJ|;1gyokL47Dd-L_XxI_5C>3oS(K z`^e58dVXFuU?a$ACqbTO$2`d3k7Z>D|0LrJFh!d)R+dR}^5>eX${Xqv7LXvzQJz!v zD$d53OHH+Q&&G4O<8u^0eTw@+u0wIRhmh4wkK;fKe<PEpfl{D~1C0zTMoNryM@v_H zVqdXT3#Yr?d716PS{_eR&ZJ2n?|vZS$AytFrp*j!S9DDocGL|*4&icS6(r-blZLv7 zRIsM<=Y!>L4`3TXgjl53H;an9;|4je_j#Tq=$KWMYK&%ur`Q&0>&T>p(q<P72PkXj zsOa!^Al~?0u?5lKJr;yRZZKf;!Yh4}5sX6VHpOeRT(?RWhhz8+3^Jhj3U)6I6C-ag zn(u5~F%J!;KTz`$^5HhZ%y|0YH#iUMfZ144@&2&~2aP^7(oWc-wyehAo_3c0laR$b zoBC^=E0tUd?fc}WcO3FYuMqO&F6OMJ@nV_)DfOxeIk8-OR^RdWQ@Rb+tTQPXq`B>~ zB%0T8-p3<SjPK)O<ob&NGLu~^m?n0t4joKnhAH6^F=jf0PJk#R=NE&u*WTko;yoK7 zNo;Dd`hV?hs_Ha(AAWg5sP6SUu?>peoUbhn%8JYihITX1J8@VS4#kyranZ+FFAizw z#%YCHjtwc_Sh<XKbZCpmeC)NhP-412tQ9X2*=E5b6_}@+Kuw;pQD34Xs8VInA=#!L z1GPoX*eT%Bx2Umcd#7;ippItV5pK*%+x6RITem5%4*gVfAL71MC8}r>u+$XgeKp|D z%ew0F=wl#B_To)ULh(EYj+dtcd=B@%{mAd;NTn0|^w0IzGlZUj2L~fhL&S$vZ&LDC zhAw5lph&5{<YHDNe}Ry^EoXv)GnOJ#X~*V}N!4|P_rzE$FNya?N)XTJXLmk!2}FC3 zdAbQsN$M<xqzeUKUR=S`_jHUm-vu76!FUK39J;koju?@@HP_>Q@ohyY`eBPHnmI|C zyp5k<nMG(ZD_;N^YsQ9lbc@&fo<Dz2b9phJqB6@mQ{C<Xo0n^<>f~Tzdr`8@K|0k6 zy9ifkw`h^*a$DO)MV*lcNrmh}H}tIuN%=igul{loiz)}yPv2|J>}g|@_)34f-dU%R zr+^<F$8m(wLj~1a;r`K}F9~bEV~_n-Z*cl3A{qL>ec%(;j<Y_#VHF+#Vz&ScS919{ zH0!q;4pC~;-CNV!a?AhghoU*(4UI}0&hYdc68DjR0asUkC35_3zNBYRY-X^|YCPsC zrP0Ixw*3B2TE7=i4wV&9nFsvj5|CT%*GHn8zh8PxZUi511$41fe-CaCp%m7vX%0mD zuxN0`8_axolffQid%o;n5td;IDe?GZ9P%4>#5%C)3OpUo-T0eCu8&0LGZ4o8jj+zn z!DCVh|IPuiF$4NgDDeb5vVUrH#i7K>T$wXOXK?ylHr1p2GZ>b{u;fWQeD_B3YWn}h z*L%k`m4#cNs3=WDL3&ks7o>v(ML<A$@6wxqfIxsq9C}BoN|jy%D1=^w&=HYdr6ly4 zPy>X_JKmW)<J{kS@4p<#$=+x0bN1Qm`_{MCIdNs$Z$l5Nnz7iDsYpwu85Yx|efhpp ze_25;!Bc@=%pm7q0Il*HcKxL}NC=?df3(tVuntbO8ASEtD`x%-HUmij+PRV)6mbBf z_y@iLu<l=(beG@Y&HzRWr!h&f(|(j7Q2%iSH|HJe$f|gzP4q~~<hKd`9cH%w9|HDA z^fxMJqkZqvt{=+Qzh<23o#*fmyg}nXqsnu2;`d-g5q@?Qw82SqiK8|$Z>=4FU0Sgt zr0Z-h)Q5Wc8FBR$QMDK#5N-(lcg9)&jTpS8QUP+}@TyBlF+P;Pp%SDyCeG;gge)V5 zURP?((9e#IFPMaTw#nn)Yo{`W_7+$j4?$B@b!PwhsBqo$AD7h1(T4Wh&^`wgzDfJ~ zFR5>tVPa?>_5VaR0O9g~KYzN~_)GYEp7j_A(a3D_X8@8FZ-8vB`S9VVo4-z!g#5;` zo|67u9Q`fnASMF$ht{Q!)i%K6{>M4>t@N)Gg|L2jMSv{6|0jW>MV4naGjNp??H2%s zpK?^VuHpwU=n?^G3@*HK!EfyAA4Eg|SNn>^ZaXfp7w||o=r9WO0KSU(lb`{VLLmRk z`jj8w$NVjE4g+rM1BPEAg`P6ttba^Ww-YPtJFN}~6E05xe#ifC&cy+tO?(I*hy~~w zr_}#;kW66suT5&TYv9+#ZFlHTt8E2lYQWT#^$E0tKZte)r+?WR#4^3jLfteWwo9v% zW7aCM&7;m;3r{yQi?S4zxW7QAEy*0a6FC>M3#tIY<Bs<uaT-gDfF1#B_6e%X$cV}~ za=HWmo<98U+{2W(ak3&6g}Lz|vcz%(4p>JC3DCDbm*BvdscvE+xA2^NtnwqiHCo@p zbl1UxbS|BGXN9_lH#q;eo<y*ca^ZoJfT4V_r=`wK35Z?My`Hg->YrdYD@3Z1(QM4K z^jOi$>}{8Me*X^!wTGl1VX)OZfM@LtkZ8CfFxJI0#D8g;yv31jdEEHocwvH@sHo1U zNfnMO|Dc^f{f1Y%*zab}72UQJc8w=xAt}5A-nGuN@BrF$&t%=$<fLeqhzQi!D)4f- z<s`#o$u<E8UOsasa<?mZ{jJ4UPR7g`pH<pDTd{AbuL~J=jWn=LU7?1GvI78IR0$~z zFq^1rb0~0nm|)jQnf6GzA<H#uv6IP~oSLRNGx|vTny-!eQSX{PVy#~-ol!?bwh3a@ zmsP@p1hCgSr+{=EGQ%!OYg||}O>iO?-d)r;YnSbmGZcJ4Kfy9D1w=|clXvIw-_s)^ zYhl+qKSOk;U>SxO5&WPVQ^hN6z|86)bI>;n_Hmk7M(ISJ6+1nqowxU9sm?<r2b_%b zUro4-rAX^%zF8@D<}vVw4&ANDw15f6EV>MzGg5c@+sg^xv7b5U92<lgX7P@D1`X7D zV*QP(E@t0VZu}@!YrC)K!}0lUY3bp(>2NMucvpOR+hf+&2n+h8T7gqR9}dgsJC=df zILE`&)7;$dMf<Y@uPsj?{Np@r>tCIANAVO%EDMb|pX#Mxg&1PEcYZDj-@rQKj4H88 za*9j4Do7!iXED^)6jAm$N22cb@JU*r>zvtRrZ39<Csd$sqx}rt5?0scgweyu>|%`f ziT;><<7mrG0XO&82^0cfRA3xECgME0yerYl@7?Uj_H4;J62&#bHMX+HmV^`934^%s z-?G_Tv6q#q%hGJvW?*?n#5s&9jUAh{@^m;l%IB2Lk<FP{$E)U<a3FfupVn*97=$mc zVbaLZ@iH(uO){ZEv1QHu8KEFQS4|gw3nn{cYfnaqmrL)8B@0j|3C8o4GB7>5>2Nib zG>%E>xdq)=*J#fGj09S%6Ix7cl*Ko}cQ{r$XuzwZ=Zz3++z)Q2fI7L^BG+T&cu~R> zPI$HvKv{xD68~UK?sg4VmAALIPl=f-OQsM>{OX;fi>R;fRM@%t4CogF&NBfHk32KB z*%IA=Wyfd$s1#dn*7!wrd30L6SU`)!_C6&&=5D7&w=Fr#4DHH$(-st-WCY`la%jC! zz-gnQ2w_6!^t3Ke<l;;=2S%us{A+|FJX{vMyC)=o>ve{dtTjiaaBE4YWZd}%gmGA7 zSZgSDNy_m*`<E|mQ8rsLL&I-h`oujUmwk3Yli|xEs6468xSjw>G;6HCeYVAJr(QHe z_b%0=&l5s{kSaTxydNh6`4FJ@Wi2FSQ!!mb5xSsSyVsZqhmS2_Kwm+(Y9JR6VIS?$ z9V5jCYEo$=V?Oeqqr+GX)I!&FAu0S-j+O=NnlPzSHC5TsG?ZhfRTzl4cGGqY5U3<$ zz3uvHNX!w@q!}kTG$%$psznz+QS8a5!t{kMI-HmA+l~7WPtX@=D8%Q&y1!Hdz1Tt9 zWRaQ_AXrre(eQM0u@StJC{6xl;8dOQk1*fRt8)?hNsa|uR`nE!;pxRCq2db=ej<m& zXgR#u(PmaT&NF}7g|>-1`fYu@v=5nV`+XHbcxV+hq6GnQI#d__So0n`cHs~-oPFgo z2G0tyxy*)Guq0p>J1lSh;20Bw(JD1Je3`J^FztVn3rI(*y9M5jle<XzM%n9k*kjv3 z$h5pnLqQc%$RI_URwYhsxRzYnyepRP)9;%v&8wjYnIFvfDaRx^!i|tKbd1f{6YSC} z<go@+g5Wt5E8Bs-tGmKdYC$Xh<F2YYF$s^vIl1-HF+EAhMFN~DMy0dW>MI}_3|2Sz zJbJ7}Gc%nw%5c8dA&jh3jiRKvEt4k5koQoz;_DDWnmcM48V|$yd!oN>C~LS6t6M0a z17vnyrNU<UzFFrx(NDfBzEpW}AfWq&UqI6^VkhQ872IrgneCH9G>u1C3Qs~*Fx)*d z`%yt$mS$#Kh5=S5skyJ*^Ua)5!N<0C@CyOAyWxUyl);>SzH%NoDixGuZw@24xo3e9 z<C|5mnL}BTp*kuq$le_gbFc1)*hfHa;r3(tL?jYPGBlEEQuJb9uqjQ4$5VPS6e1E@ zff|y5REp)hyi0?p$9R>x>c3t(<5OR7k!y*PcYttHUET&uNVPavry|W?8Ow;d3<+p( z@7|LsORCa@z%xrHlE)$hxbpjD>sE5<Y7^o>r119Jpin_MzvAwS-q(WmBf>=&f;)aU z{9oJ_Z<(_<@#|b{=3{m3!p?|2zqFaQ5?@L8no)DV7sru)g?=HjJNUEZC(8IMk9>0! z%}?@|+}I5+^V--T+8C9{Rm_9Y%I|-afXfjwb}@d%3)7pJ?|Ik1_>)#!r~wim#NM1= zdcHQ7Nu~u&Ni0%&w8^TtqJL=t;~s;;AmVZhoM?2dlc3nfK4%>~PDofRGPg0#ZvONJ zd+VgE>K@e%;*rc2lEKW<1H*D>CDl!$!EY0dRsHtVJcn<JTWtLpJPw~vZR{?$J?xs7 zB)6LxQq$*-Ft9gm;p87o6y$TsA}+a5Yj244Wa$K?c@s6uU&UEjj>#D;zi|n4wP5W^ zrS-Dh)Y<a&oU`PJdld7Ia`S3Z6Ai}|wt+-ta;qvKY;#%AkEWoAB5)0oJGPAx%-YLf zC;1BNi&Dc-|6DPRHM%1}#cyV=Le!Vknq08c2$W{bsD%?HjmUFg=T5w^*62lqOjRc{ z%a|T|EqSPPIA4pgwJ>Be$=phOqA4YvD_+ss+bchypG$O*|0zEdn-(i1nX+_9%j#2C zr~&f#e#ALUIA-3&G3(_wjoo89e~2Msva1!DxpAK=%VZ$=9<S1q3gl;s^ss>Jo~!^j z1UX3{OF(U*WpQ1xhV>$-ZN&H;IKOl8I!=07-6J|ZGXN5yfZ=LHs_y4;An-}~k+vxz z-@be+LK^q<+6u(6-(NE~dUPQVF~=ly1uimgv^_*052eLu!f8^9uzZhXW)*V>xa$%r zV?QP?JA_Mvf`Uv;GF2FIZ59PVSG^;`%A*ToLQBU276etfh4fb{cMCIWoOx9iCai|4 zmRMNo45EibE0A=Va(rGo$xh>1ce7lQ?{An4kRNu+kEnUZ344Ua77s^;Y96!&02sCm zB7?QUFrE-$6DYdX%gvsNxm~reQW_UxAzoP2uh%_^xtqjK=wCSJ@??2MJuT{)s4heu z+kwenc8nFfBtz21<c`8n<8CXH3mt;OhO+~%D#;WwJPXqF#$_G}Ud<)b7AERJ&x000 zXl<?8DO7edQY+Z<5w=la;TDh@P4w48oG`qB*K%4nCiO=x@JyQIKj$UkZxCdV9?Yvg zgX|*&fUj+9m&cTAs%dVHB^TE052Wmt)%a=17jHlWkMuC?5e<tJk+4`q51r|c<TBts zbUsjfm{`oI`b2ltGf`7j>bsyshP*l8F<^U1B#9$C-3yAkbj_^{{MsJ0zL7K8#6ZB$ z-2<e$SdV`~-@{z~tvhhKmhy{W52%`fR%AVnJuV5SY|Z_CJ5aa|fWtls6ux!w7x(_r z??+-+5P;h}fl*M-t2g{_D=+1j&b6=pa!cxRwK||}0+Kxuc!zR>ELZ%KQ>$ZOgZga( zs1vA0*W=#40QiZ}4dsUO--`}Dk(2(iE=pho5TmB>`6=r;m7(}c>>~b&Cv*zf-Tz4c zTtZM8^0oco_)h{Li$7DI^ZQZBwNJpcTx0KPKOojR$68%pFHfy3{{86F)mk}zAQrG8 zp8$jt#2qIi!k{aUh=64A(Tz{HIspVidJYsS00k1WfT!OSg+&jLnEb8q;0KYP>wPlg z4o`fA-%0TqkaZna!fl8BmRf!*yDthl+i1`7oIRJG6e51|I4StLZsn8$_XWdT&Y2z0 zwU~pIKMAtk&U9A$0o*=!0MHP)$48R3oURFX+Hu9^_7MfX3W67|0nqUg?O~-+59<NL zU)BZ8ryp5yM^@h(7a4+2weK=Uqy~5|RBsoerSE@-u%5X9Aj&()Jm+wzolmY2w4M=U zu()!bF8T&2QO+j0&fOp+5f?KRfBfTr`%T-+k)aOBIdfX<Gm=#J-(RnRm?~~`Yp<M@ ze_fw!lmUbb8HQO8``Zf%?9aTQ!xFfXzc0WD3Us>vSnNs<)}PrY!>dn$qMv<w%KGn~ zm$k8RY}8AG4u;R8ksH_A4gvOhcFftB(2Aln&n?h|B-GZNQ{5IQl&uD^q5=Lj!LX3l z+1g?XcN#bD&|{z(m!qewRr=}HwZSC3fBmY(&z49w1@ku@i?ap&$KoC4(B7_`{hW0L z=Ec8;CE>4ue<h}U{ii=OJSJ72gI<%ETI=uAE5o0S>{dfpBg;+Xi{466{MDFG_T778 z#uMLftu0-;YH^QGaRY3sGxB!86|Cf1+24I0`QOR75lt|MDG{~o?31M6E?IA^u=?v) zUbhi*7!QR2rkCxXU==xf3QR<QT|_;E@}}23Eu&ZYRD$Womp2;L;FTl~w<Me!E{wqK z?}^y>yP2tLN(4cJ(2jQewUL+d*TCDzl-7wst8Esc1huBHtmpjXSry(-2d?hjGChCM z^_h_G#ZAgZbDR>E5-*2w1vGIy{746FQum#G=(DUzSCChk<qFu6YH}82+k)Kk2SH0o zEVPrqN^m+P+8AcA=ft%=_@0)DkHt-~c_tQ?^9vmhWj-5_dx&}6e#Xam^KLLv!!*Pk z>m78c4ACPmf6V0dtSQsO39#r=W(g=-QsnI$zEzA3hukb@>;?<W-TAQcF2nWIE1CD= zX>zUVf@t*G>ZwP0T?XrFJ(VYS<T1`{xMq*4*wk$zo5p}w_XP9GZM68t88^j3Puym? z#lb~fL!EcfLo|21j|H_4e^*2M<k67)f*{RWuYv4J%gn1PzlYClXEB5|##tuwX&>iY zuXFp3DPX2zAXH9m1eo}&B@6XuBTF*J!%;Za>z5PVhy9!xP=_+}2XWMUEhu*Ky}F$p z!)pRwN9n%##oG)JhPtFT<P)%QesTCvZ7wQZ;!4Uy+P&mpV)kHi3E?x+A;4|~1KrRy zn%2YAN9Xg2bdMBDssULnQ|DRL?(&9)Hiy|)0sC(f+Lr;&@H)MXl$FfawKI3hR<+lB z;?g57uZ&}r_>7}nGLjJOuDk2fP08H6`d*pyg}jnWcyfRg|Hc-1(zpbj)k40^=0jVy zSM@GmSZIPM+tOT1!MSb%?%4}#-@AIL`c|H^*>vTb)>6`QTnNd(yNsh0o}mJ2!`t2T z1XwuGk_i=6a<a&u0mBH&S(W9YFB2R!W7!f-9&poHt(!VsNDmRY3#XWQsdQeN;O0;E zMr;od1Oc%?{QBBKxoLZ3ix~_eoVEn(jfW@_g>j99zkAIr+eK@by7_|r4w=3&hnA4A zfPWzEHOIkNPb<d{Z|>P=@fn+Il8+(8=_W$$3Wpd?HA%-&8k_Vp{A!-TZpt)i@UJ=Q z)Ak<(5Q4)S$hNBZ;?R7ft>aJ0wh^%?UAWAxyBo@I<q~~oWwCX>JH<LOUddJkTP$}j zV~;_E*m@MSdojKV6b7FI9Ajx`bN-NL!--+UB(gcehjg7#wURGxk7y>kJhpu^xyE>$ zqNX-@-`}GXIva5ki2?08V~Czk;@qq~P?uUArf$U%EqayCUS=v>@7}50w`3$MHDn~q zU+<Oe<e=FVT+pSNyO#)hJA##6N-cFp3Q{ct(#GXkLd1fv{UHWLS;`txrq6dhI9tAa zPNlz{=vN-x75?U1nNce`r{@s^0<|9rbrNQQNY+fjDei0zJ9`&h!t!e4OvF~CqPn7S z&b~v3;r4FbCW_Q@EwV_f>-IAc^f9}x#+a(iyAbn{6W;^@|3!}EN81CVE`r_0mxob7 zsSB*ayOm7cHlOw9%L8S+Pws+d@KrIzI^qoPd!AIdD#zNIibfaht)UMSbzWZPwZBlm zsJc3gp*<<P{3O1}<f86*f7;n^DoNGJy_jc=`0h*fXY@1<5ANGOm<xNyC*~C(ABBdV zm|TY7sE|1T2gwlK9^ArRQXB!7T?}QtO|KCTFH`lqK2G739{b@v{Fz*L)N`t{Dnj&` zXV2{tjMnTR@|XK;G~hPzQl0`wJn<(%_3JE6<Z_E5C=yOz>0V10N{JwK7VZB0AtmM2 z81-$s#|9r7yMftcxq*$jc#eJ8nTT_~Y(3I2>$arE7!;M~Zy2%AXA3g#u_uahT|AdC z%zj!x^jP4>_v&7Ofh&h5Q=4U;h8o@UJ`5(|o*LR-ka2hf)ZRsnDOGn}cP(fu!*7y% z;+0kc)4jNFj*&yyFH*7MlA2jOfkw*3HJOe^*-|d?@eIPV7p4Yx-S|9Rg!sgHnzFyO z5l7%j4pGAt;2H#;do1BCM1wpnLL78cwBv=K&(r#={4sQhya$<&`NfDJ*{@><o@E=w z^gz5TaqJD331SqHe-hkoQSr<LpLd$zd<wP}Zbu9?jly?zovYU3N4VcBb+;T^s=B;f zP+V7f5cYjP%O4u&i33#ZE@;3xJq+O)$dZ;oXdq1lEs)y1Zv}nfVq+J*<x1sB+TnjE zwhwKEKj6BY?XmR(Q&=xS$*~AL$zuNSaz+AqaXe14#Mp9SlVL9<ufwrqZaa~tsi8WZ z(M}fTUTLXn?eu=A#8LGwf^s0oEIc=&iVqxNHfLiiugd8p(-P&zIjm{9bH>!Zx>~z# zI{bW5Z1A%bDcw$8EAJXLzqDrNx@MfrVW_^DZmcCs!90J1%{|?`cs|JY%&mG5%s*`> z0tNV+Q)<HUe_}z(=%n^YkK<wbxyZc0xF_2>*+`$PXMTbnX%Bj)1+%1bGfv%Z7XyCO zEDWRV_K(zigIF;yeN9>8TG(9!%dqZN#PjCerNeLRUG13xwa(<CHIlU<c#8;QT{zp* z$K!l5n=XLU2oZX52^1>NgY`yoW#r-1&<-E{tc$kqul*D}7C&51bi0LXDQB8ov$L-M zM){b}|MM5-<p$7<N)MoS*CM|Bi18#Cn-o~KH3ojziKMvYoZ}FchM3jJzA%v=rb`l? ze?F-fB{Y36X^^L!lwHNjMDBZzJU>;GS3VI3a@;g@-aj+1Xrgpb)2VSV{qA@s(@$wm zto_S+QRMtKJ(8AmB$X>-lBctcmEsSt*kVl|K3CG(vaw<{nAM_Qmkqbf2Oi}jmb{F@ zCsM$3Lk@MB6OM;ogJ@KNfBNi`Z!vt&DVxT+BF-oJ0?n|?A^ol~Cbl(o>fwp{9Yznu z0BH%4ie<*i$sk&6+DQiXJ#7rm2N{~QtekOE*Qt#>nx0+ec<Y(^U@1S7>dW}|wXYrw z$^<VPm^h&1Z@}w&J*LOB+Uv6ss_2ubCF8Fnuw$uv7n+|>u4k)fY#K~h$8o-UUb6Z; zw$uNaZrK|OB<&wZi+`Le!;!+lentU71t)&~==cPOQ<z_%z{5fJYEu=$Z#CkBPv;(# zu$e`WQrlT~Bq@q~MNg90dWwSkig{;miLR|`6w(Q~yGK8WS##dnL%vCMPI<LvkEEfx zwmeTm^dQ_i?o;V_tn1PPsb>NL_8Lge$8yZ3(=OV{#SGxcg(6Nlqgt457D%8Ldu1sn z7)TfF;r!6Wi1a6bK)}__y4k%Dm`kN#1zf$+HvQB<)qTY$+*Ou!XD)8;Nk8M4is%i6 zz9i%id>`5)LQX4pV*${*=tOTUaAjZUXlR?7b5xto56L}eSa40K(|Gw=&E7dz(OdGJ zA#z~j^|=uOI_t9Ek=|Or%ZQ}7>6Ct>2DR;c{N`cjto=k!VWpB^iD2!lL$2W1Q}!^O zTsQ^I;R)DQ!7f@@2z=B|2o6N`b~Uq3pPKzx8iA<zxVN!1PKq@P?~=U{-Pdin++9p! zt5?;r<maF8<>e^%rsC0ElpJ|+C?{{P40~xn@;%wdhqY;!xOR(UrRZ|=FmOPS-$G47 zSxzz>*`gt!_nljAkv?_!LbUCEobz{MnLGK02A<T+TDH6s;ao7&$_keOvCQ1v)!`?Z zw-`@80QT!SF?co%XAI<N^SDO~-6_U-)*iNUV|0CIM2V_myLvx+^4d$(o|`|x4b}Tu z_i&G~s7eHKKZ>C^x}s$*Mz_78DfZi2d5(|s?xfGiL;46~PsK019epaXtR1t;RTxIa ziF?gsNcC&w-w%yjwmD`RTf;rrTJTOLLL7<WNvAahiBV)bY3S1q!Z-<Y)-!kL(H*NO zaDH?$?{c-+%4H_gQA)jGEpn%#sL;2nGQnWbV_HguuH3qOIbZWNdqk;>PCobdEOF_H z{HQo1!m>9G)Q$7Yyq%ufnO5v!jX8g9###P?K>G)8H0b4v+S%l5*IRDibn`NI>wE5) zV7mDCZhMk7K1#&Q4zNo6%fsP+0m`IR?6ah2q!FHnQ-2KGn!{YN0`JR#7hE;yoAwQ@ zzqa)Wf3@UyCSMf$Yqt*#*O@Z=<Kr`eI#t%4^zD{DK)F2+@1xZPydbU3y>S5M%q2xR z{R4u=Wnyy2DhXbx{(-*oCxP7*#ebc^36%cEh6Vo@YJK(p9|%_7s>(hq?>RP^m9*vh z7TOk6du8GO1x%Pt>dYB7-Xpo;+i`87>@W0IUO!5L@2^|OTL6sp&%a>j+y8CEVmVy@ z$CA+tilGkBF2e`_viiVPc*U_dzz97Ce3$=UT6l^5K`+h|O^(<>y&uMi+y31~F<O;f zEr|$kNr4ZB|ECckYZ!bbVOObVey0bFKYk6&P_>+|s=9eLkWBpY<Hr8~#d1V?sQVnF z+V|#zeze?zhLxxN-CMvgUX`KZ1L$B6dc;|o&prNw=*r)t2BRP==W4zt`i=mS2$~k3 z0zhysG7(zsF1?d;&hX><;$J|K#SVHn0+m^E`gChi|FxUwszC?W&%fq_>hE7FX8_^C zV9@PV(9u1MwqIcM);?Z-705}(;kINFfBQ_p|1W9W(`R-Aba0~%_}Y`Vg1_P+{n&QA zq9BlZo&2)>yBXp2|9BD%O{oJp*uxxrQ^KkO<7+^!!5WLgKLXAJSnK!9f4<I^0@%*# z(DRM|0qoaZu(EhX))N4l+Z$Gew6BQ#N$@h`T${+~mn0Sl$Pv@5<AMCCj=6<zHXD#v z6&$|w#^*IO5%8I@VlN}`O;v{_W&eEqbZZZYe_Z{?kZ-%Sk`yr0<^YN%fb=neJ&-VE zu8aV}A%Py}NWPy2KmMtTHw7}y!T_x7a|3#s{wD$7wrk=q$%DmT%3+^w4*bedTM<Hg zV;7I-&PnGg{{1}r>1uV0H?XLmEbiAIP&falc72^Euhsj67;E8&Njn(@;-DuKq^8^N z%(35lPzIw_sa(M*t@>p11ri$DFHdQHe0%OF`<3q+4XI7Rgp9j~U8Vn7o4q2}z-PL1 zAcaY%Sx`ATddDlEl_th75A+5Fn9;R|Sk>6)bnL2h%VZ^liwTpMfjz~;<G5R+XI`jF zt+GAUS?w9aS6RE4(cW+28Z(SR3de$$EfC~sCmKiX*6>M~u#oAZ(HN>R^&WH6Prm2W zNMp7zi<bTSPV+Ci`r04k%qQg@xzeN+U}JhlHtR+$;0w8hYGa?KDqdJjN!&y6<<1z3 z3dG*|c}J$2Jsy43UenttXyay$=fyhq>;lOxjy8sefbi<czWoUus-`jg*l3uvTrwrF zX`3yD#XQKa*(T>$i}1ntgBj+RuEjDbjuI%>gYKUBFQ%rrZ6p4U!a;X?ADqz=%VVbA zPMo_;GQW*yL)nB_sEfFAfrYenndzOZRe`6{#ls|Huk*Q37xmzv>l-Yr?GgGDEvD%; zi$90miWdF-(j;zoxVgM9%P^`-m%i!VqY5^DE7}*vK^Jhs8d)#Hir6+|rFUt&50Cz) z`ohQ9?%vg2!JiZP>=LTFIh@}W<_#aU+z_<1Myn(6cd_rw!1?A)*f?+J(m{!0u;VDH zD)kYq(WxYcZf!<@<dxg}5RGk;Q`XJ*XKwFja0ZuIEi@bxEUeU9re{-buZ63(Ok4Y$ z#YRfsM4Fp{rt!nnU*nN?c=Q-3M5*V)-e<KxAO3<Xmq0?qne3&8)O;c1<M|w=nj#|$ zn0odY-PXiJKQ%z<8*_uK6E8K4G4O;ht58_zh4QpKQfr7;n@Odh;1(;>E7r~2(8(P% z%;uaxXs^Rm`7ni=a#h{?vw8?17!#j+A?#x65m{*$_(51qy;bHw`W3rPy{GKXA>qxq zHM6&tFMRWR`VY_X`MKEoZo>nJGS>D&8utt^$pgxj+D~?Z?qTKwUS8W7q|Mx6ncOn) zd9Y^haA)P}2Lak|->|mm00cr_9P0<@KuL{=1+tewl*Ymvy#=EmbLHku!+OdVtn0&Q z3}4r{I?Pv8tu-~?&_#{m<+{<u%UWNDZ1E&B7YbN}`De6ce(5GHgGzMmkj&8DZY{L_ zvS|ysEn4&}brQVbN!8$gvxiofvW-8of&Z<G4X<`#SloQ&y#6w`Mw^Mo6UrJ-I7-7+ zIN)?dIJIBy8ag9d$~~0@#;qp)*<Gi*A?U=I9?ltEsF_?cR;-?`7suzrZt8yPmKsy# zT~B#J907*4*Mhyv6MU^ZfNHyqYMi4EBOEHc$5l7+dM@IpfR4u9_tzEgUrzm8O*MMb zk@sGY>MMvs&I6<O6@`>Uc-*wuZc=SlH_T9r8BUe9B;KR8y!);6Lt)&(zzq&dFNF%$ zSrC%tOVcF$LOtkfdrevw`9oxDeI%SreK^K9b=$RI(d6giusFOfzu0__7SOIxdVcy~ zuAh7;E{|TV<Fo8OmP?~O9`fcw9P7Od?c%@K51XBv(_%gi6?f$?=O1#{5;UmNaf~Nw z4^{^!mlJ(_5l2W67ISU66#FPuf0=IGpll#PvPMlvCpmB4yl9;;v(bL<;*kxWlQYlj zsKxl4A8ho|0USHX+5258RzoczX>K&rc{n}4oDct9d|R(@h%`E@)ca6bf9naQPKu_A z`492^n=W2XZJZ-QN85dGMQ5$d#6&-_-AQ>x+{YF#!%%7&7kKe-0|=Z#-9fZC#*t(H z7qwWk{LT8wbi;Ng+I08!N1Yr89f8DQs&(%<qHkzrhQ&?W^~2u)#tY=~q=3yjZ414v zaKuYF89}*+$UdCy(j}E%U43KVL~3VO!P<C~iOoZERq8Hf={w&j`GHu*q5o9a>x0>3 zTSfZeVdC+`*R!u;mv`^g=17Y9Y~&p!J;!B4%7@Wqk_Y6>oQ*p&yx!DLPoei#oU`Ud zqRP@*>7P{S+Yd6km+`rA3a9ZgUXYO+&dNU09bo)m(`Xi%*AOdHFpxm^?%LN^iG8_E zVefmDr3cU|-R;Di0Je6+--bLHS;rXvz}=J6LMDXQ^?L$~qYuiJ|9WaU8Ngr`Tn;4e zN(={flD;jmvAv{~r_u6vgC<Qi3X9{|un!Aoozr2LaCllomG~LQxFDG#`}0#OSW^$p zLn=x`xw_S-l$3NRvrZwAuc`*QhOtSOJGmw*AL~#~(gzZ=6Fd2|&Qi_!hd~18f>`)+ zyi2YXZCLnyv1LQ~VOj<QX%~6@(efQf!cX(-hAwxl$x6rdPH$i#CSWrQt-DSETpw>0 z-+6~9sY@YD>a=rac#<eXqp>SiG52iV&c-{*cox_aRfsQ!1wcEDeKb@w&_82+Q@;SQ z8yJ<PGa6unuV#D<8otk0kU?+fGw|`jH!?x|eXI^nuvp7ioTo*{8<`<|Ys>PchDc#c zbz8&y+;oo`ybQrK1#(781k=+oZ?BGmn~^HPEmyoti~-$!npumUEbzV5S^tSuaO@Ku zFG|sG)py>vcH#ye6QHE0`XQDBxiZx3k)Emxa(e})llZOVd`@S{yZ}{rzGElU7QBh@ zKj!VQN#!R@3DBfUF?sSJX{AehHF><0*U-DzGC>@)5co`MVGXhasxj)cLoejI`YkuR z4pX{Rl>$@+?Ap2(+``neWRQJ9B$3Wm>p{V2PlWsQMDPwDy&14LFYlE~z7^Y#c(wgt z9^r{p_iwQ%bHS*3dzU-E8gMw^82m$^=4CWV41RaiEMl50vb=P(lGZHooLrQ*AW5TH z-E1TFR@Kd659-cbLxS~zY_5}^A>o8Xjdy;|8%xhUDu`kpCyEH0<ykZEoKTH6E+9Bo z)oFUbU6d2Gz-OP5%1)*0brKk8s#*f)s`9%#QLyVed!iwc(%`LiyTvR{>@a$wc+kXV znGfx*4HFKawwCTq7r9)o4He$;FDm16*LW6#oWFm*t%9ivWy6m&f1ZdhhUS+VvmkBl z{hi+ngsi=fMb|VpYDfBB)o0&xeULzaWko=155eh!X4v=3zO_k)HNj@hk$bytmF`8K z!x<k8vD1;NlM$cDD!e?9tnN{wuEA7AmM@{gyR0{*deyttL_M3`1shep7Bpr!VHxcL zZkq;}X7L_-1N4WMW^z6_5On=4VqhEfCxK(KLwZIj54T}eEzIIVcwwTPR}&LPH;P-n zY!-WCrGVu{<wPcK$aA27rZz5-nZ@bOb;Dl9PDyHS(Ujhrwk0ER7VLbQC^^gQmgdcR ztavci0XiU0!#C$#5*i(iS;c_R##L`YWO#z0scma?8bYFpD+384nch0wm~~600oca- z**{<{4|-x4L}xi-Z>c7#GD^L;(V~cyMeU4cu7<|lQuB<~aVs9A>n$^N_Gvb%aqq*A zp>sCxrGbmPM*0o4Zr;p~D9YVgAHGq2R64q16zWLF$>QSTRnAki*%U7lY{duI#ILfB z7E#2vPnbbl0Qb4Z*^L$-eA(RPIzHw5k1PN2<Ff<M1hAb260yf$|0EDmVAcS3yLaU@ z{=@dQM|zxHF^4v_pWm*OcuV@bnI7MNj(Dy$0(nS+zxcXP^J|xf$Das)WhU!KK`T_i zCfRZm7iLoS8!1<ez~~;b{ft5b5d0-Hvigr<9sMsQHy;)fU<0q8bBu-_QNyBp(OS6R z0wBK%q?|s%UTR-4W|6r_Z8ri^qOL*Jaz3YmK~=xt6u^uHq;-3LugI;m0%nUk3Ew)5 z4~36wUopY+0KZJ$3z*}H!$^lQD!8}q^1xk^3nTD60$Mf(lB2&@((*_ApFi+ig~Q{L z=9KsCNjR@?bcuq`^#D1k9ng9Y#l=zkvSuxSS)Kt!umCPde0vW+3}pLq=s^2`xmlRk zd22T=p!Vd%`*~SaSUeZol^r6r?ed@at3YrkB_YIS3b=^fJz?Q~|Mk=dE6^_w$L?M^ z@E`Z#lycqdI1+_(pQPpkT55+t-R>A(9M~}fX68RZ>VZ~tSVzT!(1JpAT?{dW1KTV9 z&XQ{ztTVD5*|#v7A$}F$1g-jUVcX2S!dViD;z|nBs*A^9;f^*YjCj+Aj6nq#m`sb% zQ|Rt`NUUdi&*jJUrm^mmDi3zPS?9y%7ntltn5~Ox+#W2D6QAqDG1@od%wePYiPUQ5 zg!K?bba`%tt`Meao;L4H6|lY;S{=GexIWut2X9Q}%9dh&A9NVDWF!LcR4+pCjX(yI z9yDv3fCG}rKnbxHcI2|K1o#XbpB@3F%!*0`9$=*fymRVV?6N*J74ui`Iq}BJ9BV+K z>;ZHUC=MX)M1yb;b7({Rw<#5c+rSe(4IPeUJ>7(M*5I`68k*{4f9DLtbu%Khi&=F{ zCw`~%=Ijcp;Gye4!E!Oq2|qdxUB^Q&&Y?ZId2hvD%MLbY8PW*}6}+df?%R7N=Xawi zXXk?A3=@LC6vi5HE-#*un*pa@lKZ~CLUHmY0*3|o#X)H}-ZTkARX6s+OukMDw#c_^ z$ck}4C}vam(#vDT=~~op?Iirxz6%4-Rgd3}UB3kPbmuC&@~HBWaNQebRa@TvO|AJY z{eQ*)^zSXFr=!3WRO9dGQ8s+Nbv!cW9%<wX!6O1{qYHH%;O096h|8ORZbI6>T;sP~ zzjdj}gB(G=mYB5gB(c%q`l@!<;g)OC@0?@53wZ<{0x%fb)$w<s{|<H$z+Gsk>E{fa z*O_h%GZpyK=^O0jkNg6yg|h;U=HT%;7?>46$v$E|?mbWM`b5(H`+stXo2~j~0H;*G z$`Q$-_|}KU)U8V%$MvASs^d@O!@mvu6cqi`Bb+At0kB~INpM#wkU9gbh%k+>xNr8L zXB*;bz3Sd~fH_%w=*uW?IS-jjTPeE)p7Ia~gdT9!Q$#ZFhXN(w)Wy!}D|M{Lhk`@3 zdUt?TDS^WUx*lbHO71@c*RoI34>G(sy432EgM7Dtk5$Z=imAy0*^gPd@r(xkN#N_& zR@ZFkvcAB|5JYMWv8}6)UpIB-6=2YgeQ~HWs?hw0_Fz)7WkIa_b<M|g3q)9AJZsw+ z3draRJ!3RU6jU}dA)_kncVIstm9vJx-_z~T_orx%)xMur#5gV&%y#30<vfZxCqF)j zKIUq?6PiSra&y{<Kcs<I_SwB^W&T{)7mC{rQy~wu5qegQo{6C@k7vgqqn@s*T84!f zv8tlDMclzMu+vpvdLEx@VlO~eXqqD9Qz}kGIu@rEPnA$pGFt+;K<gYdcLyeA+7Cha z(3i!LJ{eUv@x$4q5l^QgqIT1?&<mx-E;Ka3e$Dbu!E5RU;X3T%gA}~qo~lJ!ioHRM zK~ym@9h2#MjhLJ+BMBql+hV#~>4o0}MQ1cmX<uo1K~lOKqOuJ>RL@Zg^eD#}oE#ke z1ZlTbPprH0H{SntJC%6)rlM+Wd_?K?wv~=nk5vV7Q@_`mwVA(BIq0~Nlb&B3HrL)& zk&<=fdh)VrQzUC`Cdf6eJZ!aFnX+rVi?`IU)UpEo!M|U6ESXnX<B5AFTPgQ0`%WPV zk4hAF44s6?sRgQkB=CF8(C&0C#Bf+h_xXO*(WSoWw5mPl%7gCLRZfOK-Q~Zh$E{80 z#qH7jApRH{WPCb&C#XN?3p4@hWHod8<T9h}hVv|Kgq&U5{VDNwYVbpi0}nUBo!aHQ z(pieVOyr*6$Zz`LNqy5OcBuG;5cu3`hIDjma9KD)U`0KPR%`Uil+eB~13y1)bD)z! z_M18Fh3_|1Wz{Nu^Zp=0Bv1`4K_gF1d)`BRmbGp!_WHYCMl9W&kxy|0k7)RuaDQAq zV6L=|f63JmnIHNx&WP2_sQWw9Hx~`PEH%>G$<Bw|`^wtMZsJ57g$#)&?-nGyG+@H# zP#|9QEQbU=bBm1cyC=3RxkR_?$E&VRZ{7HZ*_ma%Gv7T6`E<*73$F{AjKst`lxY_# zx0_r%!!O|JE|c0FcRfxVu@g%gUTd$%_Z>#%)N`F+f^A=-Dt{8)Cj-YCiar{bf2yr| zKUY9=#X#YbB1ZlZ7>e3UDg;w4Rqb%2h8gCuW@hyxM~igeU}K2Hxjrf8!MK};=u~z2 zqt=?t$CQ1atD(mZ>|ep_rdSY$%mQr{@)B~bzViV0bP_%sdEV15FlJ>jr^;JjS7#D> zpm87G9R5*jA#sA$6Y}wq&BaON7}UlpJoRLO665d@H5`6U8)BcKm7|N%NU4MssS-Yb zwPvoVD8J{lJ=l3$tI$`#6V0<acki2&X*<P|)3QDva_#Jl+1+3`NJH1tGvk$}h<Dt0 zQo>WHa+~0C#eM=tOv>>=r+)AE0%{rEl4baFB_bt0pAxmy`{K5|JrB!ee0Y&Ba*3h0 zEFYmmdfRIO<tPs*;5>nlXG{2+EsmK?6{nzZwPYLF6(<&Vm1<M2`}i`pM3-)dD_Az= zb-bSY0hI@5=bU=T1>pMGAuP@uh@>e;RndS`4^dgYVL=^b;0wfp@RYD%rBFd4@5!v9 z&&wYlkk2^$;+3wjd(%06vr&pk#g1H<1$CV#?8u_imW4ZVB3T46T0QM#_a@~;sy6Nv zByB9PH)QiSH}ikwYOHa#ZfZz<cFoLxFPQV){%bAC4Xx>GC!?47pqKk$@*<e^4l6>4 zR3oPCr>L8eF@~n9bZ$;;(c!iVVV<DK(}FjNHftnmDjYilg|DhkrFI-V66@2gtr_(5 zCd7Snc}p~uDRn(&dDJq^LT&andebGNpI?IH`Wp6yzKP6KT3Jf@Dc>%ZS9`s=T<EA4 z95hg{8g<_4uB1z1<a3YDD~@+;B~0}ohpdJBLIkIGSp@;2zBNF}3k6uK(~<-0!#|Js z1oj<!J}#!=+p}kwD*YnL)5DLf-)^^+?&0H?0~XY(LznICPJa?aLTdo^sVWjIsQcWY zDy9O*iVU9|vw}|u)}BesZ=A;!7N!=i<;|H&xTho4VHocBlucdgXO1`4Pkb<bu|X1x z5WOTF^kr|<>J&t!&?Sgrv~9|H8Rm8V=$4@T8+o3pU3IcRo7wKFS$$0hf4h(56|N^z zSPxd5{^;xB2nL})P|&vl>j<;<D`3>qmT`zIba{-q6%L1QiFbF0zPlH_HS<K1#yIGp zX9#YP_UJ=Pb}BS7*Fw{BAibcFzM&~iZ`8EERX0}pEI?^MBvIRnBEA=E9s9kQ0Y60@ zS*k|IH?4A0MNGt}M7Q&MvP+e{31UV~q}W0?j^Vp-MrzH;bzxcvdkB)KM>wJ#4()2L zA9HW9eq~de(<v{M4i-yp_+noJ4+qZ|blTeh6lxXvq(FCjuVE#5R_IG`epe2&JoVOW z<tNB>6v=K_LY%O<DLAZRH$VEg``bokn|{Y~w4vyer0Iv0`lT@;*bbCOc-z%hbWi;S z_a<Jr7EM!LF1G36T{Pdlyep|^;vsZ>EqTgc-5KRk8zq2>+AUJ)Eb!`XYNdEKCCBNy zY@vl5#Q&f<J!P;c$}I=GcF>sa$TN+FUcd^tb_DuPz54wGf?iIEo+)c6ghxN*;@?dn z9WU+lDQmYM$jj$gX!*{Uq%k0p(&*;jGq})t1RZ43dW+EtJ%HSjdDVpw>KRKV+JbM| zv?j)ixO;UNAO;LlNSfT^=)M;Q=!VfvmXfGbX{f0$f#T(P#`om>VGu&J%~pEKV(i`? zP94eYlRfohjB<hXb63c!q$Fi)Y7U@R=d^5j=q<{7=LVK>NjL&8h&|N<)ec7pRe5yP z)t|_`IUavCy=^b>dRctVw0E^7kt2%9JNL0$lucxmFF61PIvYKvfhYfjg#ld&%Zp>} zN)JjavI5&0PFmQR4F-Z?tAUDcPWCN<$xoxTgvQnEd@@K$^g~d`?Okr5-fEmF7Pj06 zXN{O;E-;#n3p)+ZOFbD_FzXi-ei3aZBHQ~iHPOuSC;zjxO}A{ea>BGbN*gL9D%6@8 zh#}oERbG&@Zog7*>PgT^8AU2D&%kb_<JL%=Kuv^;LngC~@$-7IEa#=Q&qCQUc?H$g zrJ)FIgBRPphWUEeOnPUmZ6gpP<qT!{q1#Si)KXnOZKtz57k-%a&Mt%(y{<6fu_q)> zL5_`{JrJ}ce<Gf;vrD<eS(#pU=o}CeHEU?Rs4c6;21ahRJVIV1M1yL$Qcz@<DuyF+ zfv%p;pTIGiBS)^hg{_k`OS9&Kl(`bAKg7`U?hRhmPfYJeJsi9qn-Rp1(MX6F`vc_> zv2X{D*^4RP6b1WoYRHfcItvO3!C2O|=q;bdJ0Z*loh;-getL3vx!oD6>68=33}}T; z;W@|FFgH>jwH7r8zG@OPt?1r&eB*ZfELlJa`K|?IZM;gnCR{tue|PYYgAceW;qT~& z#d3nY<Hb_7g=(1vdGmSW^Lg`&ApVT(cTKVSMgm&G;po>5>s*5+wxU(AhKYQJN@FY6 z$U@8XF1=RMgvG8)mxAgE*QqX*8O_X<WwnRF#p)gHFQHgoR)C{1L-l<0Weaba^8)9% zkMqhsh}Ckv{xcer#Ro%9CxhN!=wId~Dl#b!tA{<cf6R~94+6j_J)R4&`YR2@SRtX& ztU6Q2k=8OP=VnT7>vVa>?3`@+k0X&v%gVkhD=SkItY`q8vRHtpy4vVR#fdAB?ITmV zk_^6S)+-&hg!OEl`PT%@3liPEMkUaD#tpU@XdHll*(okx0iBD3%3$iO-hTBA;-hnU zjdDoa%clc;2+wS(=?a6QOfN0>&##3xkcEM5Y7d!c7;k<y$V*XcaB<0!Ebz});!#XZ z6K%~)wi``ZYqYZmio#reAy?4lB?zVRA0SIkeaJnZMHEV3HM?ZRD#v4y=aE4_{QL-3 z^)Co8<o+Y*a(Dy;doA`K=*2JFEz)aWL{gD&Z1r8Ijg!<fq({khQY#j?j9Z}XrauYT z6_^%(Z%z#QTSv4<6c~b7o12;@mg^fE6Q50I^|PlEtv-5One!X!p&kI+;uV1eCy>tl zq2c@A9`NyB$Vyc>rt&{aNu}i*q$9k2i&)(K(|G#|qbGnefIRP~bOIFUH|Uf9Utks< zO_1^5zwFX<el6kZVaYk{hjuoY?vL$J6cQ-?|KUIP^1#3w#hy1Mz4AD|QByv-8hdmN zZuA?<%Yi}rEVuD(tY_&k1*+eNz(OVBQ}Dh@IC76LRrzP*io&-b8=3SK*WY>TZv}tD zeF^{0ivGAZkvMY3{&RagKRpBWgR6#AwNwp<f0$VPj_@aQe%(~uw3mSimn7v3|3RO1 zI5yxp*k$#Q4;spl+s|<KbEMxKZQR<BBm0v;*a}T?nf_Ly{a>)F@*C{tbK$wh+U=Ao zV>4vW(7E=CtgBg-PR`Cq_P-H@*FoYy$ma=Ak`ACiL322P#()2BiQb(UTKG)f`V%q8 z=>C%_-bC|m_T$rvrXT1kT*Rky5dQ7>m5Kk)0l5B1d32On9_i$EU*#Ed%H#vmcg2J( zJ&mmYf%X&76<QzQb{K_ja5V%F><a=y^}^?C?E?jsPdsjKKX{Jr4tSDJtyBAoX!$u% zAdz7XAm|goWQi8XbL~qp)(mx;AWsKKFv*BjYdJXxR9oD85qe6;PTdXd)To3GUqBbh z@YJov&NA+Ww$zu$dHrIgO)4C*IbVMeDS2EN;WQ)<G|B{1Rx656Qy-eeWxOGRu3Hd= z;CRt0DEueuv6n)%<R&T^k17boba^hiz5gVbJU1c&a(4>=s8Cn|dXj;29R)eIUS%b9 z9R*J!C;0`X*_;ZSvIfGrKbdE15Cjs1%Tt5dJ7qZ1ZzbgOA;c^#5F(rfENd-`ND2gN z1c<`J$Z%rMW3|4)`^1&(HM5Gg`AL=GB+ep#qm8ivBi*R_DR_QBu9yhCLp0gAdYRJ_ zh)F<5wBMG0h*KKF(dRvb%#n$Z*5=Z^vdDZ(!rZP#aOheUJ8MuM?hfH!t|ENw?BPlO zWM63QJX=~E)%J@%&;Z*0i1#^4hyhs#4yhxIfGQ()%$MOVsKb+Cml5TPY5K4B9FE)3 z=$xxq{w~mMpTlLn{QftkF-e54t|NH&q<RTXKi#??eSWA4<Sjg%ebXUEpxbiLqRoc` zpJHBLAIN#4PBGe;6O&UN--<>lLa8@ATq~X5S8h7g3b2UdG3H0-4sYccfjBD$<B12@ z_75$XeW6#N4i+k?)WSDKSiLUabFoxU{vnQ$hi7jyuPjn;a^p!lP+_uWsQ5(UEpmX< zKuUm?`L{ydqH0$d&EE~GNtyiU=8w9tFuPEbw0C{>_TVJb`@KHYp*_Ts_p$)uEEzhb z{cKkd_I%3dp~``B0MD6!|Jqx*FVVn_m5@_I1tG$aw<VNSNWS~ovG&;SwvXYCQPQ~4 z_5aSg)76A<oL~-}bAat4Ure)I!-9%NpPAF~qjI>`4HwC9-!WTnCf04172?jfH@uU2 zb+oteOkZSD!n)%!`8gN_L`gX2pOh7;ewD-M+hH8z;N?X4u1OfaTaM_PYh<VcTY-?M z>Jjr0fmJKoz4gVj?3r6*;WIpL#q1&RSxU0{XdyUtLFrAGJ%QLSMN6css_e`deK)vp zjCMEYe81a$v4RiwI)?}OuR1p0@i7}Ajk+|r_IP~wV|Wesd8$Z*MNa9#Ae|usZ@)hY zDBv0Vb1`?p_7dL+Yd8j1E0z6iz-6aF#2E6pih4i8k{A-VuLI5TB8fNrnd0AU*UPkM zPO<nVxNQ4`c*U|(-WEwZgz_b5k1H3L&l`6{-FX*wlfbY?VSQSgDC76~egNHtdME;G zzZY~-126u45Gm-u%OJHMX<&2rr6tj-0&^HOu<-r+>;h&D|2)Tc35NbLU)z2u7AL9m zCHnki#4c5zoIOz)8HjeV!YUtu&WX4$j}}o1Om04Hl)w_l0o|`ZEQKyJ{s0y_rkv9; zXq@eKK-gMT&}>keNI12&0Ra(VY<BIHF&%Rc9LMZB5Ob}+M7J-i{C=Q73jy9+|7+*g zq;Zv}<+1xILnq0C<ZSHx3tK4^bs+vuD+T_Ke!vh;68nRQ(QM(yp9E&!_^m$)OvnFw z;W^0bRuoEi(?uh1Ry+;!@1yHAKmT##IA{>q15>uKKs%`~$c({B7q+_~bQ(5IXQCyi zX6J&d*NlQ+HsNE=Xa9`q_HAF(>ilB(B09-6=McYm3asN{(8thgEr8TAE0#Oq4+w1q z?orE^)&{J9{$?7UxfUMZv$2(iMi72(8lblRxVJ~wH+nO|(UEXn-oZKy_R$EjdZgzK z(|urQ<W_H&IJ&oMV&U6}t2%;p>vy5+Ox}&A34H!gqO_6Ie0TEu(8XcM2&`iEc`1s5 z4!e)s4bOlgJ!s}06~+0vK*ZgAip^&iZMLK<)wMi41z@Y8^$Kx!_i2*^t5R=^Tx&=` zrp1Y8UF$U6k3R|=?Auuh?tL6RtQ~<ss&ktC;XXRo&p9-7MBz}hoJGS{PkUR)P%Pf0 z1lzt0A1eN;L1~DMaxGIWDzj4b%uNzZ=}BU2`$N1tWX`Piiz>nA`Z-3nLqj5`LD~C* z9T01ba`A;W7S$1TA?@n-Wq5f=OCf%3>y5<uw3&t3oT{4-(R**|_Uz3%YdL4`Z{gIs zJ3CRAVZmRQMLxKIjg`lpi*m%?%=)(2lSulN)z3D021u-=?J`;GQFOiLwM%}GY#ZL8 z7Xo8AiLI{86cO7Rtt^&%3L`qUC-pi(zxuSRTu{t2dJ2@+nR3VA9s`<k^|LEeKd{zH zB_p;6$x0jtPZKRZ%ycA|sdekSi<AgN%PUY3;uIT3cX5wlTc<%R=^HM}!lYn7bqt{q zZBuuFW=Eo6qe)f4(?qA;q^b-;O-$l}ur$ge<TG%yk-9_l%D0-<%1dUtUbmBXc$6n! zDB%uU3vN7pAKVk=Et+D@h5UGUGcyFb40?Oa8j{U|u|l-Ue)UCl$@oQcRHNe?rQdT; zShqShn0@w5om+lgo3XPmS`Z!gLSf;yvb+_*5(&Y)D~#-VvFZKYg);X3X8j;(T>n63 z>K7NvjC!%mM(NZFTv{CVA);cDKEq);J=xWuTd$)NF2_Y9Mb|qsK4=?PO0NdXw6_Fe zPcBU&rOJg6dx^!*<$P}>Bih7qS22cB`C7}1@omiQQ}EXN3;4y3fLFkV)cTN}@=;4E zAqC|y<-RD}yWNB7U<BbY%gr$#Xk-w5QjaC^4>+@yTJYR1E$vA<1jh7WIr9DY#rMR@ z_c92=I6Q}Zg5)t(or_qm9K?{{lG{`S4z%nF=+pbbAWRsMVA<gGp{CyJ-!p?I1jdGC zEapuY3c^L`qt{+^7>@irfw~AsEnWpJeXt_KNtZ(&Vb4A#u!8ke#~>o5V9QauwG6{X z8lFLK&lmM1C$GUMT1tVjr}3nBKWJj;p+Y@i#U$G@o#NDi3dcy_d}t8WmzK(LDsxzm zs2`;A)KDYmq18rOCzEwVxGmztOLvB_fU+#Q0ncvz6{EE(!`r#U-O2_J(50Hx#e7C3 z`?{)+&)h!(P-X~_`=x?z^psQ2;(J*ceLyh_Y}ofmz=OCuHDEvLxc#olR#Q<5irIl* zUGPyAjWoxMr{~K<S+m{;s*|z?Y>z3(Io6~uDClwG80!CryZ4N0s%yJOQB;sBy@T`) zQbLDdp$kawL_vC!CZWbckuF`jO7Buamnc=K(tAm$0)YesB81#$Kkxaz_tAHZ?-}R( zJLCLI24(NH_gZ^jbFO*KS(mIrv*we)MTVE_62@jvJ*dJoc*N@~&4@a~jg;f-?o>wR z2Z=p8S=!egRby?5Vi{4|qc&(#yv!3(7&+?DO{+u?Zso+qTX@;|b@20r`NXb1C=lww z%6TMbx<wVQ2y}kVuv)2;JQO)rcw#U9RaaP-b21fMLFKK}W|EwNGwE9q!*E=#RII`1 zc9lS*ALykZOF!isY`*)mYu=~T9)D~1Xh`^xAN?S%e?4b~bowMYI;1qaCQNC%?8iY< z9mOIvWW`H7QePm~$6Fj3ZA@~Q?VvsN@S^0hS1`gMp%QO~k?&oNvKLJCu)7X8V<}V9 z$Q7ax^ibcmBx=h2S5_-GF7&%qFBdBNDV}}&nCT;}y-4bCS^mq1i7+5{?%am$`8t~d z4K<l|nB>Kpzrn6riEq4>t?zZvWQy_C;WfWdldq*B7WUR<mq!U$nLYaIKeSN8Yw$5O z=T*CHoc{N|usgn8RT;`vgu8k@2+kv070kSC)zru8WhGGV)~SwJTqesP=<`?{O+Lf( zI(;4YfSCem3`ff=6&lR39`1?b$2q8AFQavIK|qXGeX)#Bps9abfrfb7il)Ry2kih) zbX~0--UE&md_z#gC6U5Kr?opJ-&-v<WpZ-9B!^YJ;{j%<aL<U?E565{`s>RR3m(>y zy5$Tchl!Tq7Qdd~D1w!^zs+vC_$K?ad5rnF`Wgd?n}}}eok6o%k->geA>due;>6$+ zXM6MyQQ4=UgA?1D<&Nf6nM3Evqg`Cjx;({nO-w&ZWU^0W!n?#$S0OIYVHO^jmzwS* zT&`Q`_WgV4f@x)?j!z&Ur$n#>B-8FLR6lZ6W5pDa${v1NTI?*~YYSd$57XoMUE$?% zi$-aH&!9ao%Go(FL#68U6UHYNei*N02Vmh~|5ChOCno%aP$}1aDzD_}>KH3gBN5jF zm5^ZCr??q#p)yOeG{9%bxoT8-ZjfBGql7+-{iV+{Gif~4%WHyYZhnx1xySr~|C!8f z^<jD`<@-QA0|`%qVr{5Jd<WL1J{Ap5J)N>%8Kn-`K9t>dY3$mb#JEhz%dT~9m3qDG zQ84|WS)xLzFm@(u_jKJH<ml}_<)Wx!(U7)zKBA=0&j#OQZTX6Lg`oBH3Nyd9KsU5z zg?FsRjrG!&bd`PFmA@xgkH~S|NVvy)1ixv$LZW91eV4B8C~FN}>|Jd({L1x)^)M=e zpHg1`^SES_MO#<%ONlJKmIgPkg@y4P*ALMLTL+hO0NtR8ReyTy&}koIdYP|62P;<( zSPts7R!eOUYnESO`4RZtv*}WILdTmg)Z-m$VPY{QD2S$IiCfB6)`={VyaU*$F;}Bb zEcy|6sio^y3!+xj=k}VB@lh)Q;qUyW>l1t2Jt-{~Ti@K6+`dV&i-WO2l~szw#Oh6o z28;IdU0e88Wq0k3OpJ8;Z-V$X&<tz>o9A7IKzScM*U1nj=a}Ol6<BGIR%F6rn2r4O ztDc<WO_a`{nVD{DEOKY^RhfZqd`VQ4(2M~>9)xk}&Ez5_FuNBvPC{P+Rbk%>4VKtV zNjE%`S)*5+eAPzR_*SlwS8Yw_)<Q{1l3kahm&=h)5`p5i4HlL}V29q=GyNRXv%(|K zs5HHww7dDC1?nUn?da=uIut!O(V5pBx4C$u1NLH-66Oky;ezL_GUD}vU20uf`|F>d z-8;2$mGrDZpIq}0wl;kvm}yy@=6CDb^V3ha-@g0M1W~=Ld(wa@Ogw<EQuk10ltJSS z^~udA&97V^?M!LVq1@YVvEsK(RqPxHn(L@B6?)QoSwJoYJi}J!HWexZOZcJfeo=Z; zoxypI0a;>-d8T>Bex0QsLL<hJ2TU=0&h<S{aXHLCw`7+p&3gv(DyRCp%bNQ}6=2K# zvK9SZ{7*iZ89hobpU&jng*&mr0Ak>)5kS1Q0CgY`A2vT}kFjiw?`FN8lu?qq*x?cX z!ATa#a)tM1ZcgY$%MTxMNi}ygP{zg6hRLtPev|e9!gTPdBg8n&<1$4>2TNt=fm-c0 zOvqf}b=ywe(z`l1!s=(v7nT=k%kw&ko=DkZ3_{gOUWYfFN$bg6kj*;JU3%yE<|^6C zgl%RbiUNI@s0(vO!bsJu!LCV~!A!f?qCpN9;zESprc7gnTzhAtMNb1SvZ(o8!&;ax zRl!|!4=qo)+4s@PazHX!jpt{(({LPVi#o*Z7vHBbq-|Ee<eXzK7kQI2*8H7#V2$t% zr?y7%cF>8_n4xdZ@e9oAe}^l!;I3bY?-p_hPTj^7#-f`{9+$hwJQ&-G9#!>C;2Ql* z4_qpRFmEdA0dYaVFKZ0<h~(v8+?ZV!S{!52$JJO+U;0x%LZx{+smOCuEHj0Oj>3Y3 zC;LJ=j0$UrmPB=oQRQoJH`F&B*Gjk~q-%*?l^hy1908&mkK9EUx>O=YT-Ge&P?)Vc zdJA7$o0~OtJXDN#e<T?`y2}7u@NW4J0ClDaJ}d>42t-v#*v<6;IVF{>L6tqew$+xx zg4K})68}-rdH_*cc&IFdd2QO%)9U!YIeqyFfRqwN*m7X<&6l=NUM5y+pSCkpkMQNb zd0_K&jOfVs%UPdMVV}L?%&(tRX|*=tuTVrss=W>}%od4Pj|>$x4nlH>K8LO?M|>SL zbZ?`CH*2$bc$2?Qis6e0$T@roe;2S<62*9*v%o1kh{#0hKqaW(y{5Jb>qqa=_7VQ< zOk<d?oJGKl4afUp7c66T0*>XnB_`?cY1-SfH2KlJ0#6ZAsg{HMyC%s<-np$8iX&Rc zgT}Je70a94Y5Nv8glid{XedJJRm?&UuR~+>n=(&N#~m%Lda88g!>SqHaA;q9Sr~#| zwTyOdXJQ3a$A(H~2hx%BChwg!s6xx(s_O3j&YcaBzXx}5*Pe~CzZ|QKBRUTGFILd_ zZ?rWk9}9x>ksrT+{{9zlRR6Jc6{iCq1JoEk7f2WoSO3SC7d$hF4M~8Lf>7f}%xl|+ zG$#(LQJ*^+Eix^qH~a>+9Hb3z0HUiuU@YK$F#81Q^P32ey<7$EXQJ|-KyXH)v0~Nr zJpSi`=a!HodBdG6{px~sZL(LU{v+IE#QOji6$*&GCD@L><@Cgk9LD3+E4ccBU<$ub z?b4HHR0;!r?uU5Z5Uxw&G{U(L_C1wcJ2i0pp;<ifKSa(ol7E0<s}=5nm`u8&D<pX~ z!;7Q)jvW3#&rd|$It(c=3*Np&97X}S0sQ9|z~kVrv`+uK9fkIt9;)_+YW#0nHJN*^ z-hd7`c-Z_oRsi%`b20#!`xloMa3NUR|2zk?6ECF!?a7j<fW;^D*!8C`(h@$A)YZ#g zsnPI7{0U;Y{`^7|X#J-bhxK!%Er8Ue%%7fzmSz|~5K(gyycY1Q<{zRzMyt*a$UedW zEN#d38<2_p`*Q%1h1+}BH`YZ$8yV`)bk9)9FOpO^60;u%weZDIw}Y97(zYo_g5@N? zXZf)neKobvI6F~;Y^H||J`xk8H+YGHzU+FWTLg^u^YZ4g>JojKg<qN&%o-V=`(JaG z_wW^-n^XMCA-Z430S!U|MDBM?ntC%PrjN}_^3f!>i9o(=9?1fIRjGf!f&vJeROfi3 z426^3%bjXY3QCf1O*`nn*}uLox(GP6eSy%0ahJGt3FGdTe+NXcXmg#7PhJh8DS7Wn z#JbjVhzfhT>Z#Gnn0Sq@>CP*tlwdEuYjy)4R~l4OPQa3E2(mr!TCN%!d{Xw139mW5 zKeY1mOaCjQV{THb_Fsa`wK1oR7$!7mttR5k1XrV0;)I-T;@w}E{wfGNOII9xq5P{H z>}(jnay5A!;K%TcEuRKTpz&sD`?S$l<-@#0s11Vqh@cj|b#GRLaEYkBF&gM=vmA@e z=TiMol^tv`mC8h-3*aYQu{oQwakT{cy(~X_x1bpV?0scMnmfBULatKlZbyhl^g|ed zw)m<vBsH~8m0RQRm<OohdWOz73Z(>#V!{ZR*az%V#i6w>*f;;-Q!1N)O{jS~ZCtP- zASK2S0V*mdLvkCO^7?9Wn3N--cDnfi$z#j6U~9}6bHsNre5(ZYS?|$glb!nFSh(mH z&1xbc+mwESLY>oPJl;Y+F+vhL+c!Z0I{H1Rdc`q$l3`6v_Oc1=W+&NqUYhHKl|ypB zew3r|)<)x~+>hv@EB(q>JOt;41$@xzeLjYnHn+y@T80e;w6-5dJUk&0WH^EB|1Q3J zAr<kRX_fXwD3ikjqJO&B1=!z6u@Z=LFp@FUSjp3`xJ{rPRdrTiYWN}LNY8_+O&ji| z)qpEwhW%ajxMi%*>7#h7*GQ7yB2aG*pW{$dOOk#{*!#!nYk3YY?%<v2P75y6kXQ!? zJD>a4w{APdm;W9>DdI&pCP)={uLagM5pLiuE;GdfT`<%=G^$m5;&AkK5=26CF(C|p zRg2*mjOM}&t|K9R;aciPZ{RuieI4eIAHB6UCtgSe3OTn<|Ju3TdKB-9b!vY7B_Z{W zHv7w@&wDvdU9E;qAb3gK!Vn?W!-a?4`<uh_D%yxPU?twNS+!gJdD`xuk*P0meThlI z_?=_&nZNBYfni3L(yHdyvWD@>0+MwIZG@lrT||64Bw_1?gss~OC^x*hBK&c*a+FPQ zX^=@K+pBUC=JO<xR2*BMQsWo?j%KL%=JK_QJVpObU?(e4{~3tVLO*pMnl%5kWr|kl zN!(JU&&?MkEbAp!F&fybpQAH<YHIa+A0FKmqlg%#X+AJ+{XQ`BLf#qYh0^9t(&0_G zX_pb<+fQwRUik<-(<L^ETC<E=0G~-?Gl!s5-xs2RWAV4!;1h5dO%LsmG#_)kuPCz! zHF22(we{%d*N~}$53k5`ouW#_y?O3ccJPtsacT+5UP(r&lEJ8UeM*;FS7I^_ikibI zgY*Aa8g1Zy$ZQN~*?2<V@9a?=Oh}EN^zO4VlDr73I`&pzfyIJX!J{u&0Ld<i2T&b+ z<6I=P#<iHqf`1b)!e(jAcZh2B`T$c@HrT)RN!k}SIspYEcMH&F=mD73NdL<}HS3RD z5xReW-XZ!kLd1K9DG9c|vIrQc-g_Z{W5di6n85uA5<DkifdKFck&S&y5s8;Yr#{O2 z2=}%mYWbn1j?=^C7Qb!gZ=)XPTDY<`BdiRPP_`yNWjv#5e1&3C$6XL2`AnkZ=9Sk% zqO-V0$m>;%HsU(eWndL!R2a?56(2ALU-(+N>~5s7trF_(x$o_bE*`ui_!RTt!XMs@ zd})05@;u9A@^LnLd+N3hubCTfu&H#kj-3w68vU#1oF7@JA9#ixIK>Yj{lipk87^xC z$`~^iQZpvu`TMB+99IJ6xtT9#@JlQgZ&|vcm;n`+Rq^_D3G1Yqb-o%2=lp96slE-? z%HNLBT)^G~lenxGUAG$Fv=>NQHkrs4`h3>b<Kx*68Fwbu*p8IVgxt20ww&9$VZ}#C zm*q~8p?J)VfdRnlLQUL5jU2Q6wU7pvx~?%LKJcohX3%<W_nS-Oam~mcZ@V^nyItw4 zlz7xUypgNk2ojV5T`yew1iyo;28q<C!Y7^uZFOWO)_N#v{uCFKuP$E17sYg?vKwVO zO@Fe=WGxV&O6S&>Tsi{m7lh0rM&<L?$>8OH-q;L#(>id^ARtVp1n(W{p?}{R7lX`I zmFdZv^@V1K$v+j87xoBve1yuhiBC5*PpD4p(t5fIFG_Q>CfvR(=rlqh7Rq|gm(ThP z>8$3VGCgMt+p+xcgc>|!KWfY{)x+@`Z0E>EyvNp?rZ7X0^6dfJ`-Yj5a3vYa%o17O zmX$Z!&*i5>INLTX?qA5@EhYh>F(g40E5UW`Yt8Zk&Rd^#M(?vGbQAumz%<j6=W*Yi zN$W*LH{O)=`}Gv=!_+M%{VG+gNaGroZnu%kEUu8e5AB<K@~2`Sn;=gwUw=L1X!XB< zu_TYKpV;!VOGr@ByG|sFvp*NFFi8xN%?LFK{0S0O)M=kIpo`*Hfh^LUQcXwP0c_nN z7)hW2gKH(=U5cTt?z8geTFH|ARgZ^r%trbPLs}m7);UL8a^A=x-b(NMZAqO9(ZT6o zXyUnW@)v?(CO9AP{vmQK8b%)m`Y-^nAX<}6qM=qN?_M0?PodAlE1ytI>ZUS1eXH%9 zknTpSM$*H@4tCXNI?Z}*j|=s|?DedW)WhwRd*toqSqnOX-_NziZjrqu<uo_Hc=#+? zhDVW6?pbmA58Mcb!~%EbxW+{VMVuba;@wc6Evzs2BIJKGQOc_qEX)gDWd=l*+&Z=N zI=*sKZVn0kH!XV_4I(DV3o)}amwLnrz2g~5x(ts|Xpo|=ad{s1jkHtuJ2|NdT~s<c z6-5`sVpygZ3hN>TW`=Rkuw`$2qnMGK_WABfox=Bk`KLrBmF{66WoD)@Mpbdo-7lua zERevsi)h^bIySG>qb7nI!S-n4T!1Y!#-qbWN~2AgN*PPvRj@MpS9rGEe6PKAq91(j z*|SfoSOr-m1K%S2IQQu<k6?ff*iXTbM9I1~2nw8j>CEI{p;1a#Pl;ahmdE$>hR96% zrbL>9?B&}>)U^?VE4OgOKzG;G9#nGoA(<7fMZI-OT(&MQCo|bw^6*JZ!S0Ho@*}`8 zK>5Kg-%|NEyF0}U-l1#M`~GW?1(H*LtUUS&Y8<eCv{)ab|6T{xJs*I?Nq!nWJ05e~ z7=552G19j^-&<{Z5PhraQ^U||sxym|N;BMcL@(8T^j7{so`(RMxz<W(Afv;7#9GeR z!WVM4m${a_u2+#D*GyI8`LI3!snE^neXCcGW{Ax8N1$tWBCB7IuD3+kT*%GIB4u64 z1-esw2ljB^2Xz<;Bl(ADEw`{qGWw8nWoG6(5U?r-rk?wL8b3ulCQ%gRw{z5#{LR^I zy8vmx7SJ%Two0U;zXrhx6(;>kz6JZL-KDmp<Xllkt||{ecv2t^fs))Z2b-M9i5feT zzAHO9Ksgw1MUlqT!V<@z7xZiFWg*6R^=ia2;uc;WYjGOenAH=))uVr=#xafuf7s2b zNsbG&;zTW8IHm0mdm$rjI&3rmY-g;;eLPoGVlfT#fX#F6^%U>}y*`NOc8gv#Prr?R z5OOBF3b54JbN64?5Ax#Zd>+bvKOpYy&?apfO(hZbi+Om#342!^)f1;oVC|1)@)TF^ z-W~LdEH0FNVr~)NdAmfOiOpZ3&0bFRKq}g!$0}^){_6@civzVr2=$nl27}3hZj_2j zMxpGgX!ZN4O|+S?MyN>AExaY>Ah85bff@UfOc}=0(S&VnNge1}@QFSdO5{`(2_@ZZ zNjg2)HfU|m4%pe$j{L~vb5buNmMY8L6^_%m5ZgsuK{!g{YzdT?pE@7pL}k6I1*TEw zt5F}y#fP?|Sb=;o6Vl@2jP+n%nAB!4mEx`1!>@JGt8iEpK^2;1g?WqvjJOObdWzjx z$9h(8>G(fuKEHN4zS51|qxn4%KPkDuolft%nZb$Dc+1SPjOjrU+B`x*%^jGs-dVrh z75QWvA2OW5>DZ&}0}#Cx`hY+4W@pCa6X?^$AhB`2er>*^?hQ$PZ!YApJ!gLKz5Gyp zfvFmPH`(=#wj%n1Di8VR$-T!*$4TW+-{I448Y@OKCW%re=Cdf7Il2F;w~UI)ps<*6 z72`u1#~kMCPH|Mu7Fp1sGnhugWM>dwhcR7OIvQ|^m`NRMc(HYQh-St*!xUvx^O+v> z^tSx~&0A@`XX2>iPcQjeJ%7i4Dm22DC0l%bp5xt8fxB<=YSJdkaokhF>6N(V!SA~D z20gPlD_Uut6lVwiW%h@OJhxMM1x2xfsG60RSVxT?oh)mi`LtXNU)}1K?4W61HJ>0y zY)pv_n*I5%-ggP&PO=0;bBULhf|GgLXf_E`1x(nn82pv$pCRC++QXuWUjx%&UZ*um ziY7*^F@<I1QCd`=WEl%RoU@o;awiWS^=J>)cd<W<4tl3+_UvtE_5R17Rti-fhAE1Q z@>N?2#h07R^K}CXxlwoll)c0dVuqrK@}*_Ff1NPWTtLFVyokB-lUV^%?xJoqrzE9) zBFUR7;S1JV+s3EL7dHbgombT}AB0v_xe30K9cAH#ri^M6Jt<9ie6rmC%s2NE@d4(I z06=kb4Y+CisbpDrN!SVLr^YnSAj&F#Z$tK*D8a+p2%XE+2sXkDtJc?W8DpH06aR<l zF#DX-d?eeYF`ICheyMO%Oa6MnQ`1RD?jp6Psf8f2@2n4am;Db2N;t{2DcmZu?u{B5 zFz?pp!)~fZhC~;IuR(#w`pmXLU?>a2pxrn9Dz``74YyMTTeE2e_;P+5+&)*`u(UNr zMh#dC>mLhi7W=SSk8eh{*@U(D1-Z@t<U{bH4vSzU&t|}MuX<ee=qSV~Om`hjxmgW9 zv&Lnx+7B)0R)?2Z0i2~^Y`*SzZzvz3%A9<nyp9!fHc&^gYyM*lxyraY+TQnhrKXfa z|EZh!Mh^7p1z&aLxEw8>^oJVHg+RZvByCG%#3EOVBw7d4XxE4>+z<X}18vctmI$Oq zb5Q~|TH51oa(mLbg7BPCtW%rxz2T?F3im3BJTt+WzFMzsHF};^S>zk!t1c#d5LNUm z8=QnM*VSYN1+2az#HsPj)+s?<nBkhBDc@TaF%=?yh4qFh{b6;B!uKY94b(=fZ7XKV zgrNvLW7etEbSL+^C^#9?aF7ivS%G%3{Z!+2YggUQxV}HmY$Y+nKur66YiKJ&!7pwz zs3}=+6bMDtN7D}UtX#z=_bFe1rH^{Qr5tieS89BYsTX89x2VL^;i4|w!fbE@C|D8% zZe9i|C@k;E4Hwx6mYX3f+lXFZ<m(}m(BjMF>uBsyZpkNnTV=o#2V%8QBt6mX(c+@L zA)CWFCI@7xHwM!=qJb^Ew3kH|)R9q2NodKvgE_))%utMfE$y1h4WnEK)h?a{ap7fn zb#4M(2;4y2Bz|I7c;2&<ZJ+>*)#|0D1J+n?NYmtq%J3K27*9tPk)$sc9fYq4+Q38) z%PGPw96-`8OYa#5KaNAjzroyV03gy$%E^V+!&q>AOg|R|E;AHH0e!9yF-$e~^7bNi zY$_n8dOur180ETAa+&>$(q^5hZ|IHZfm*L)OOx~~qmZ|TXYZnj$oACs(@qsJ!x6N& z4_NB%nHXWG=iF~DNZyiR#9dAwTz;yBhgRi!(HR|Wv_4N}ZM`T-0w;YQIAz81kHz6V z*6SDye8qoNJqwSQ$@x8LcL@hnkGcBp2Q$>MXJjc$?H@05B#0bHFh5A>utCV#-oxmK z+wncC^fd=OpFMoVgjL6Kp40liPFu2=fsiy!U1oqCWARRYA6I)h`L0^(Q5S~2rb)(; zg{?wrfcCu$!#9v-CiL|pYyABg{;AA4v7D$O&8mhOnbx{NqK&r*jL3Q6I;<Z&FY^d1 zjlY9?=hD&k<BC~xOB_Uk_TDS$JX#{+g%@`SB6q3Lq8CDQVVaFb0(Bp_L*EvOXZ&`C z3|y(&q{{a|C%=RMOtKRaCfFkxO%6hwesws_qWQi#xOhiv><ho9>fUByGJ;Z~i$2VF zT18ldi`!XxUQGcC$pEJeOtBJ;&2VR~Lt3JR@tr%5m<C_5XnbrGzV`Cf6%H-yEzd*m zR|eu}F^$hd@yeo#kKT6JD$7kfgdFFumIQF}H-4T1RoSqykjXA+eAM1;6Qyas%RLar z?Y>1FbuvP2c_AM4%Yzb*Dv1p8#ZLzBJR{|Z!vv#VNa&T}R-Vh9mli#47=Y3)1aCYZ z?!9@hoP_OJXcDgS`N|EfS_P;$b$Rjg=c43>!M3aFy$_#7q`DN^nx-Y*x15+YiRsN; z@eKJ8w;+Tb{P2VffZJ<CidC8C0__q_m+UKxwy|ChCi=uE^ec-C3<oVLxaos_s<Zh6 zJImsq-i)xT>yDBfsvXRT=$x(<mVs!YB7ssPaz#Y1tQ@tA&Bt<E*Ec!mz!^R=xO$MN zzMu`3T`JoJB6w!gBBuKzdM!X%n-^g{lDgW<+J`QdJ2U^zo|I~R&A9x<Lmm>6xAN@A zd+N+xx5vFzz!l$1mhT+%I&di0sZxJ9t&;&PlHmK+t1<8z-LIWG!Qt#{n!^qIw+BC* zrsV~GKODUd-TVJ}moBjYn9NOHs;0NV`zMie4>oPAL=w-vAb%+b^fA81i)v01RC)f3 zN~qK&8U#oHWzBzxN>|S?uqYQh+^Y+%)^Ldt$D{YkCLtT^t2sZb;;|(7Xm9Xd36VAM z+d~$FeefB8!dSsb>FIxnI;bx(u>J<XTPd?g9}e9AY0&L%bAH40IcBc>5R0C=WC&9P z<IjpBsL6mul?!vPd5c)XM{12FX%cwwb|iR%3~@4!$ajB4;<JueP+r&S)fdsHgJ97p z>xU)I(ZkjE)I({D6!0E{K8J#s0BmX8rXB&)8JS5zeT^o;{L(+-zr~ILS9a{#FWX?Q zhZJ)XxlZe#96n}4_+l(6m$APkC-}0oODfEu8#>lU8A#h~z9cdC^<;rc^u@;)s!T}9 ze#18fw>mp>y9>C(6*u3A)p*8dvFrp9TUo5IeVVFsp7L?Z-zv~dwUDOHj{UBx>LK%& zu#w0PFe>z+!3#{4PUElCF1ek_^lc7FdpTGr4v6?#M%+Ol(u~@$HRxY0)`?T|tp%Gc zKH^i@ID}Qi9e_+125v~zrR&wq6s%w$D^=Nz`r;)m%8{m5+D;D?%{i#8XR(Lq>sWb| z*DzC;+%)QQ&OF(D-Y-|o_L4+n0oNs<L85?X8bn$nAz}95ZFpgrTeKzi2j{Bwl!tt% zD;i?dCVbO`^Xat;65hP$wSXYuh!vodVCSs+J6DzComz>4M_=gj^Qcymud^j{xH;u) zG1xSBq-wQL{oF#|-cF@vPdF|6v$dB$LJV5tNK+2K!newJ8_<XQr?nIaf5(RQOKFY| z@Ha&J&EN8q_EX<}nUb@)^PVcIO8}awCs+T@Mv0M+DTZH1Q9%(^T^89C`}QH>xvjUt z+dy!XAAAMyfF0<B9Z+wovmh`ruB*Qm2?T0P5#bh^jgSjOAQKp>G>H7=BX|%K5|D>Y zmiSgS2Orx!YI}Du?jam@0PMJhabYWS{vpCg*TVMdE7Pw4bmh&=y30A(;cEgYVnDA6 z%iplu{>BG%R5s*EK}EtaVqt@n{C!o6Z~;>y^7&(}0IjrttPb~ab@tN|KLUM<=dY6M z{C4Oq{D7+JXOR}XfHmUm37`|E#!dZ~^mYflmwW<>RcBqrWV`=Ev>Zdgf!EEOzEj8R z^;N#O#w@%U)>+WD_tW;$2g-KoHFg2qdg6mZ-0h&3Dk7`R1$EVSI~Y6Lp9pH7vPqYY zC_WFJoP$9+u?GqLTf$Dserx*~vqiUHce{9Ty8mihXaXYR{vq1`tZAbvsbwSjPWGoU zZ|F1Gi=lU3D}Haxg=cmxi(7&p%J9(c9Yq`Fg4b5LNTG2<z#^ts2@fpung~=i)ScX~ z#c!xNjWh*G8|2<yk}Fwm`%c6qLzG%gGTz04bMz-cs|KNzlc{$1*2#yKBTknC^QBjg zpJ!hd`uaFD*W2>yk+$-{vQ21v=<l*Uxeu{Ida*Jn3^B#$?eB~?1$Zgy3}_YU*kp?~ z{a&*5oSr>;&cvk0_UrAaztFVX8W8GpYr{CN#JFjvN>f)QJ%3v%WU9nuLE%E=ZN=f_ z_f~9Db~vW$YmNqDK$4}eb~iHwc=f92$(2dRdnC&FU&HWEjeGh?4F5C<?pT0ku5s+} zJ8>BjM%8X%Mq4hxIF~-)sb{iU^HV8&Ilt!gv-o8nVnJ-ZBX=}sJ)nVFdP_Djme*bT zj$C<NysS?QfeO%)x_c-bHtmT!e(mDt!X)DgY-;Wyt@uK9jIPONQF#+D6$f7^iVWL5 zuS^zO44+){ncv;Mi-BhWlkiPYW=pdY1>?_>yH7aKFF(Pf`=_b0Wtr%{Eq=&%iac~v z`EkDsy~uPf7}rosKk|t_yp&UX+MsHyjALVKler^22E=T=+M&}w@?EkS3ybOGMM>No z@>L+C-*FH%ElRBZoL9VSTw&em@!h1jO?c8wil)RczdJ)ocHJa<ezc4W<-=qR1#4tk zPM?JHnAamZv#jb{rXA$X+aKu5kk6sa9iI&W$$q_L^_p+ryD{8OjV=NTGl^t?mY6B= z#VS9@F=X6foc&}uzY@DWDIoGRv;UVSDZJx_Qt-Ic<;sD9VvSD}>{<j3w5qR*3B#F& zG#@{?^e~%hLO;2U?R|BuX%p%ZU2wi4JfBe0YSSs^U``(H^~}sPZa)A*OihFb2&^xK zBv6l@=c{z~hnkqe*Pwh0!@Q9jAA-v5Zw49#Fpa)?(Bi9PC-I|{&CHBXgDyg{&z|ks z!$u`j%%=>A;Q8{w8Dld^`QhDusrUq&IO}`oXx=TT&CVIpkY+Qxi%BwC1XOR9Pdb%X z@hH+&#f<aeL*dEu4MwI#lT_mjD}R%X($d_-kj|Ox%AYyQaqb~<CD)gm+Kvvyovmmv z+6qp5?6<V0Oiy+ZOkxP<LmZ!0Z#+OK+u&;1fCs~hd_%J#1D^gfmOrs?B|nU8z^!I( z!JYPIozcSTw|Bw0v$0mianr_&Lj>Z8$->5#e#vWloPxMAj7wkrZcbKQZCy1Ja{qa~ zR*Bp8MqD?nd8zn@@wYQJuNjRb(Rk=^$;@5I^;nDxxX<Z$L^^b;+fGRLW1^xix=OZ8 zp|qxEBh5h40NO`zLNWb_d4mhOqH=b7q<nTT-So0cH0xT$vHm@J_rc<AU54CL-4h0- zOz*tnHXjcy>|uffCbEkhMq@it)S32vqIPw(Ie}&VU9q2&ql2DP`qlfbf>d8lR;juK z@cffusxI%tLN4=~sN+a<$2TTqbL$vd^FK~5?Ak=ZQx(@US&Sv693p?aV|#P;<hBF{ zR{QKlf8g)>mf$+pPT|N79T3zDT{11{AnNVXCZ+9?d6(=>&4xtk5)m(#OLo$jczVcT z64==%3CJc+jKftS;lEsrvr!F<K7ipr&j-K4R+ojv`*%pLMfyoI)E|K`VS(LEZkh(g z+@iWvGA6Ij97X%S4$3zbg}N6cO~mVMD2&!kaCH~nYP6m=3t1V>2>EFcr3)RTUpF_Z z8XD1`Ez%#PD-t#dYcNbJ5P7C61NB%}OJ4JdZKkz`0(jvv^YdD{7v6S-FS>h>ypGPQ za)7F|KX~gFd^KO_?QKicqFAj{P>;VHSEH=;cE2Ixu01F2yCX@jeEkHl%^2HB;TWSi zd01<IKB~+Xs(^EKfKQ5Zr<A#|ZtBVKg?879-!FGNWratcn^!qfj?@f`GmOA{@2+Rc zU6YnBVA1Bg1-(7{IRjUbjjVrLmr%l*B-f~;QRP}Fp2zV4dUVtW^4P6~wlPh-j`M40 zE*~Pfm+y{^<Z!27*Yr&gnJ8cXmR16E7pv)}(?8K|NIM-2o7_fu{#rIXO~WmsY*Zuk zlBunsGlvH8DE-gT2+n2aA$@qkvKQL^n*TL<=^>I_=KSxm{AR6BZd0y=`QTUyyjbg9 z1ZluB-90Si<u6JBpP2Lft-L)Krv{JSoG-tXbr;6G5iTiAL78>zAISR{MTb7_Fj<F} zri8z@9&vl(!2yqIy?+ZHCtV7P`Y3|gpUVwvHop2o0o8^UM4I$2j5OC_WBRvdZDxUY z+2PEPN!-m6BPX}3Hot)sCk=K#>+DDBSRt#8*clDQx|s$;M(BN-@Ar%W*|u@I1M<LM z|5zUp0&KR}AJ0Dc?U4M#AHs%{N&aBMaRR&*6U@Z;S&d3}%rY6PD`t8s6e|6Cr~ERh zBA*e4Ze8YEcHhZxH$^<}JYQcQ`<keS;)?&3oUF!#l`9Iz3K~y@fhAw3>9-=98{n_z zy|!;@^WGJEw(C{iJ?3ebV;R&Pxfzdere<;HV%rb!iC+=Mt~5H9Kt0rtPKX@?0s9OF z@tK_27Y|)r9Wp(PNRQ1I&r+A{YzLFZ8kC=|G-AvE!RLLfAh3nKe}R1DX`x?;w8Nk4 z+Ufg;p9;M<4I8#6ebSnAef`@5^&{^uZX`AsgEJKM%LpmxSr4aRn@8lt<~aP2%H6|P z=Hc<O`uOON!yJp|Wb|`mS>LM^PPx}A?t#5~d~ay=T8hjKr}T~H@p8H-4368T=Q%Qj z+pSIIZZ#=3g@%v%^mZ|9vx~-kSMUQ;$4XR~c#?Q;DjI+)oNz(+DGi?0u&Y|zFJ9NJ z%y7^6V4d$=+5XNwHG}%qc~^)08_+6I-x@T)DuR6#0=?fY{UB>%QQx(eUbWlyUP6tx zr}@G|gTAe3NPEMVk!_2@MncAgNSGL6Ld6IR)O#UO**1y(MxQW!1^KQix!Q~yBi_k$ zhCZy~O*BLjWWQ4dP!z?pj%$c{rXKKhSp=)jnhzuRB}GGN2@=?fw)Bu^0w_s4B|y^a zZr`XC$g1z<x0{yDsIVm<7Zoeq3mroxqiv8rq|l;=xHQb6;fzn16Jr&Um~{_hEtl&9 zbDepKe`Afj61}puYhk&9dgRcX^qu70<jWd`W8)}q_n--BUFqjrZgojZog+U5>ndHw zpGtk(%r!6hf}2yRjq+^h65OkQouOmaGu`VSYP~W^DNokgK9^%EY*4_XP*|;*W_11; zx`}K2(#3?EE^^I*b))?sPW;-tAoieJaZ6nqcmkMSE-x$<OM>9TFIR4&bf~jLv~RaQ zJ=(AU=Ys*RgZe@}447QmYyFeF<B9OdWVfm>3?FA}9z-vDo2$NfaIJZ=Eb}HQN@K`t zDPp1ptJQB9!|JLpr!P04g(2kn+=xZ4QvYNV_mZ&Iad_e*wwR-t1jWw;$7f&LKOj~U zJ<44-Oyb2QV@+(a8STBdJGyv=@3WX)s65tUBDuyTPNzcU|K%qnA6H`BY?r1aRi5Xe zFDlQXUtZ@XtXx$#B6O_aTG%G63$SjVpApOqc|T$-MaFxdAR|KH{36pOZz{f9H+?P% z@dbJUig!bU^hb0(=BKL^O&*o`qe#%?*ff-VhCmDo!f79`nB_Th8s%U`Qsl+Ly9nCM zYEPVf?Ohb};BBd|P>`Tsv+r9?sUHCLQ<Dd<Qv&z|D7c(K`1A0aI}0S}=?iUW$k%{9 z2utz!`);->U*0Pxf}j!HKSaO-@H19T!-o}`UAwM1sBYou9)9n2+}h52YHgejwh#r5 z<ir7OX?||~0e7XEH7?h-Yu8}kt8J3Weg>I*9zK*&NwS*zrYM-UP!44}T)Lz?pS`cn z%0<~}gG!DJ%2JByIlN{2^VqJRHkfx#Pe_qCLt$eU5WIA>O4h1CRF_)h&$6y9jrc9L zWDe2wD}JjH`6Hm|YI6)$xvzkA8hwJM-Bk|luzK+J;TyjM<&zpoPJB2n4J-2~#uQsy z#enXm3HBYt5Z&8WSg+%oWzirCI1d8yJgRqjMt3(&4L!w|Q9u-mDbW>l_sd^3a`24x zXu&CO?UtvmI&W!9{F}Bp8a&c51Nay(0)UR*=j^*)6-FC7<T^oL>2Fo`!PUdAbd=eW z1)Ry7rvTcU@QTgU8DUnbJLcD(c1;fO1}U7CO|fR-UjwYbG7zamr_K_Kb?kdnUhbup z!3{M`8Gf4IE2%<}Ht<;q98ZvnmK0zSPbXO_zB`CVVyK{OFBEF+<A`?HP!?}CJ`qMU zybA6ZbpO~)6XYW<xZysBiAd`4J#Gm8hsYA#-KP70cL6&AT1t*0*rd+|4h-n|?l<|I zdjSxZ1ZQ4De`VMXn)PT>g3F*8K!nT#oSWajthwa4{DI7-#s3PYn)!>$_|Y)FkH7Dp z)AgQfG)uX&`O6xbJ^Z>qXbx&aP`?BFg80R&P6PWtAAZc;A{A%uH2Lcjg?E8taAzKX zoZnaeiT(_+2z(?8FmeM_^&dcvk8b>l8mB+sNoI^;{WLI--TV!aTp9JBz4-WdC$RW` z8huRp{9U9C49y`Xm9nH6Hks12aS=jR^e65uTZjC<CU_YpNq99q^!L%HW|XE^-$-O> zAxw{)f#oay49XS*ek4luSA-T3aIyc-7a&DG8nB&Zn)1T0N-tBS9E2qfO3MtCSC9Px z%4_4zfYoX@dl?Eel)leF?hto20b-c{Z5h`#xh^bjI3M*Yg=>&HdzL-K2sr;?#4jqy z1)$=bc~2Gh-*L$1S$IL|f2nF=huc8oT``2Rr&egX09_<c9GoC<kD&OT>UrD_;4XOs zAUWOxHT!BkK^E3c3CJz)G65`@Bi{Au*uSYK3$Q?Sn8@lpjk*B&ad5(-q1x0c&H$Ki z@BM&39V5Vr0?bALgKjkdWY@a<o<txOvj{H%?I8?&K7~Wi_UoNiyjy%{@P*!cG<eLN zXuG^NnQ+Skc20`8yx>~b!rumF+b<f}#VNS|1@|8oZkDw7x+oz{_xjhzl(nC<FmJD9 z|IaZu-~nRcwh5qfv^byU`s=KeR3G800aN)Q(idEXA<gRpp1ynP?3WDVz>WHIsK88T zT_wDd1Pt2-a6fJs#=tf}J_O*5K=U)?P(ShO2K5}1x?cTAmWMacvuY<?e_h-cN+L;z z1XX@u==%7?$H4#gm%Jp-A`oCF6&C%{cAuK$$UZ{ewq)nIB>Z|$K_&`JyFZQxoD3-l zad{0wxJ(A*t9~7eFx*-4<yU+a(;t_}h>KP4%F&I2GMAx3nOZOz(N1}75P>cmw!@A% zJN}2LM(gi$k^%iIy9;O(pLH}7E#hR2w<b0ZZBAGU+r0WzBGl!7+-u^zf1A1mTKsX? zhiMi*<npH~&u+e=Tyd0}@E_A9+7bGXM`rmWbUNe5fM<aer1{|%G4(eF&Hb}6AM2pM zZnom!3P%2XvGB~|d<ubiZ3E0%4ZxIc4q#6`Q|eyR>)({;a#hy$$?^t+t%)vyXYnfz z9El|+XkWd6XX?PK_;p`|#1zO*@$qv>cA-!63~w2Tz_~8M-I;7wRDQb2W;i&;V&Jp@ zNP6tIBkt=G!d^cq&2nK(bPGns+VfAO&R4rk-ma&i;U8T5R^pWDe5_HN#(1IsBTfQL zAYBd%l*9>~_2kYZaKq5a>Fn#QeLIAVUubAH7t2-{e=f=$`GKXsXcI6^t9BHfR~VGG zfamAuc>nzAbF`?0b$p}1+h@-k;AT>zMH5#+*0eoZq+nEKe9NLtK}XGe25on21!wHM ze;VBWBZ8#)<wxk`Y1j;0Ri>{%gmIyyG#~kP#yXUL<l|T05P2>BCi}3{K8YJtPk7{3 zX&CmD>IPPm_tuACkyvQZ{r2g=M|<FSkj>B=v=4|OVMI2<)Yn#4T8~}YwpiLW^VYlh zxi(>I3-jidnFcHSMJ-twO=DLl^}$_DvbWINNu(h2<DMMN59QXoS+N1mjkD`BAE6-S zH{|yGi23QfKAx=m)ZfOXq*}i@dFEUeiDDOHuz^lut5<{ub@py54rIe!1~*CQGf({% zl%8Lb$etTNWjBMc#g85-w4Wg3!d7NJ+nCmo$*${5RvX2AJu*qn<TR=noH#X!QPuPX zQ<PqocPd|4yS48lI0kyqG6S5_tv?I^^IK%*=+VyrG)QfX4Dzs%J}1;7TD0lP(^Nh+ zo1$7(&Fxb$tToV28g-eKtOCJ?YGWvT?ZQkj%f-jwSdb*#I`&D+B<0?>v?2OCJ%VqY zEK8EyZktKpSscZOumbu?nDaOWj6_83_ZJBiQO=&8R-yFbt;7x@et0`gIb5hv=noWF zKS=OQv^pX+B@HJzCBv?wOG=<UkVXt=BJ#6I-zt5volQS$VWNs5NBIx$%$4VH<gRbW z_<phylU3_HOZhEi<N3gGZooG}zc)b0(XZNx)iO$uQ%7NP{GKhGZ*xds$`)09IQrpx zbt<^AmAcoE3YSG`oOCy5qPKOe;zu-NYRStAlhhI>378kVxQK70oi#L|gn=cL6o|mo z%lK8;6tiD*K{F5KU0Waw7m`=kcHUhd@m|>0o(@zdKbHE`oaj{W6TRtLvwx^^+5{I@ z(GhR!$~IP5g+fecYrOv@*_mm!-tGokl$ww6SE9U~v0YikS}NyduLXitdaAxuA9(-z zK_32bnIzY<vZ0$V(O!rE>bQIdTl>HW$jtz2Ekn9DO_wGQKFt=-;%&Hka*<s+PcN>t zr9HH9-CqVVk#$Tzq_rC=)^!p?af2seEFkcFAlOOpvZ<2;n`MSgN~xL?-3iG*!KL`* zZOPCPvm5gdN7%-041fEs!XwP|%yq0KZ}aEGP{Xk16ERbFkg$;c$f&Vzy2Gk`o9j@f z%8=F=Uk#w4Su%?pZuRH5EK9GJ6Q#7K>7FV=KiyTT_fI!1Go&<!S)FEl&?Gxb7H6=a zMqk!gQ-SA|B<J<|2qL&MtY|-su1VG80rv88GyQbodG*JwLv6&Mqf_H$onvnWpK<N5 z*b&2~9+gQyS99T4@Z2g=Fh-3<5PhW>+S5b0HUrX;4R;`fR)BQ6tWYtAsq+jQlJ1g4 zi8Cuwv;!NzeXaXH@)uoPi}(hkBGBNU01~AO(}?fwjCH{NFqN&f>k995)4)^!!1L@` z2X@aHB3thBkCcmLLR?=R8PUne{?HQt>M7U(jRDedW!7P|&^i>N2NDxvo(qCUA!5Qn z0x2bZo-z6j&OzELZ;eo?!F(d7S63c#$C6eSsz&#1fJC};^R1hT3=(`qMJy79CTuh9 zFYJHWrX|>wcpOz-wlHDVk@z0@?#`d6a#P<5W+CI!ZF|2{-x4w7ir6S6i9Dy6EhyNH zLRG>oG+09sf4R<~j0}oVVJVN8;T<^Vdee2=^_z-5&>V{0lRJ-`*rBl@1t|;dqkZ~1 znKGX-4_n09Yo>M!J%|=&u+Ty^$7A9s?RWnn`jX{7lQsDXvs@NahkzTO(yNDkn<r;l zVJJLA%9lGxS#)Y#JPe}%(r8)N*J?jwj0fy-Eg$+odF`WR$av=qu}2zD{L;QY>uui* z)Sj36#Fw(9Ncs^h|1E+P&kInB#P(Qlw@*xg_~c0pCSwHX0p&tWK5faC6-{^Z;%RBm z$TMV>HJLB>i`Hy%2`>6_ch%&@QQj#0p{82Krb6BGk}mq+!AOPq@|E%UEQwft4-b4e ziqYh)FUi$OGe2m!L!we(8@9o;a!{s<*|Y@x@%Lqh(ouqKnF;mbOofg^Zjp%J++-7& zeh8(vdfkKd0podBVex{y1tZ2jxc-eqSw|cLErad1>qU*VautsmHufwRV2NQYRk-N0 zZfmUs*{aVb`a$~l4VtDLGDDrU=1>pJ#d2*n71=pOk`P!P!&nHTk1U6Le+823)?T|> zZt)&aQ!N1ct?M<_Ig!2d%q^8m`lqS#*?cs;3{yU$9fdzsERY=X>!lqS<<qb(J+=Xi z{cAUu;3viKk<yH-I<P>{q_Ts&BjsjWV!Y0lzF$<vw6o|jOU$czK8*bYT|VnrZYJ5J zv5|3V#^zA<I_J~$-*yF6z+P#A43J5SeA&B2FEUXV)Ay+7NAF;KnaTVUR~=-<OrL{? zkU7l!6ke$tSA;H8k}VS+ls@&X+L7JJ)W&Xp8;Yj5<NIwVqDY_+<JjFrdvpRLb8Rlr z%y?4UR|IuX9?Ir{EG;Zpi&u-w5Q~Bab;yLoCWaSHLJ=bamSNgJheympOz%HL%(&H_ zN3N65_Je_*tcInof-I%5ARjVdL)T-D0L!934!%p={{9L>tQpR8_UnP<_v4#d5_uke z^DEM(Tj`m3<7u`v7lVVwIKZV0Pic4qH%4uoDJWRjv|Sa`(*todSEx2+FN&&QQ8uX~ z4V_NQEi<4zHtlr&Fzx<P-+bRa>!pOZ!y9tbE@>UlRIykwKTvynQG*VvQa#(-S4QcL zbQ=)5&YRfwf!<HM2ui#RGEq-sJm7s7$HdC!S^;?@ZST_@;Y@9bIWc#}dl(w_S+eeX zn}w6bSc4Q7<O6Ii{8@WM&Ue1lW&4M(6nNG5Cv<oFcpud_GCExS<yDixDC^~+iDk^D zYC&ECzV(C1Ae-g+(S|;uQR&*^Xcm$WXj`0tJXZeICPTt@hBDk8>laxUTB6E#(3aI< z;=<SDxsH^iQMtP&_CTt$jxMrH$u~pfpynaJg(jxVz&l@Cxc^R>(j%kt8oh<?T%+{E z-)9%T(1G=sFUc|1-Ow21R_(cc#<k3INSv&l_`=Mn)$KUty8%xJ6^;cSJDCf2@fp9I z<HmQ^{k(@D0^UHS@t6)|A$l51{blvKtiH%<&q74S)gF(c<r~e-Z64a32lQmx$xf37 z(cCZTgcC%rkx{sCI@`LuDXo8N6i`$qF?w+1GxB|PGPI-RvTY5V%v?w>LpHA|bA=UD zVH{|uYi_!=40M{(Tkw?_SLNuy`8GB$MuVr0+PA{~)n&#E+lwI#yBq$6Ak>s)v2mAO zE_axdGyhlp+Dph&-2IO=Jn4U@PFLT21ieENnVa0ierr`?8Btgx^JmSj&cW~$H%3rj zCv?;ufeiorkwLtXnuMTUrsQp*WBH2Z$ppt_YohI){{Wk$@lwDj7GYI@i&O{eSFfv* zR24HtZEg>Vd8AuOz><*uf8mZT$T^ARC1CEd_lQK}kvrsw5@@%m3j)e+eFxYdz{RAm z!Cg#ttKO7}WJru}ba~08>@(40BRj4?tM_EwU7#S}0d@_~_F;)c{u!%fOI*4D)$|9v znSx+)2MZ-n{jdY){{<9HEtLO)a7BL(Tb;#v79RzKP6M=McIEVVGWq=~YP448Q+eWH zp<5gsZT<d-f1^dk!9QcOD<OYlh^IO0P&Y)qV+)-aZ!F6vgTvgib#;#G3;>A#_h8Ha zzAo47|HYZ*K~4_9zXYn?cZwPenFUYNCzvT*21$#a`;LafLbCqANb2mH0i4(WA<C-5 zkq|}<{~G<I6Y<x_%>KToX`_c(-m7C5t0hD}<F<!?fwknnrW}#Y-z|sl<M6o7d<o0W z7q3TF%AWi7OAVYMbYXwqhZl;2|MnxBF8dQu7JHFNQVP$kx4Gq9>Gf<S2^yNkzNg$3 z&Hro6|AR=Ntg#^64T7AY1qrV_VrqV2ZF7nerK(?%r)@G(=XbP@N*x;iO%@Pe{UZSE zKZJp~a{ccxFbN<o{r_<on9d(zVCnzg4g)g<HpMrn0V>E=!{+~G7?|O|gTek&7#JZM zNYX?6mM(k^@U?njU_hI+7&43n_ZCL0DPx^xiZC&~N|ADc{ViqMlVM`$(w-Z+Zf;M- z9awFjeGnF(%#<*CxQ<rtMD;lL7p}2!y@b@Gv$|Ea`i8_J7;(WjB0;6GUW6YQEAdKQ zn&NJmh6+>Z@GbJzle#<OVCTa~*5vNwTORTV8d<F$vNun}!FtmmMOqHB^R1ct9#24+ zr}NPTK1~B`D)rKfy;1z4Ip>Er{PL)toD9yrTcOS4$&Hcane;|??EY@DcCB4Z1USFf zUCB6mrr{%kK>t>KDdq$#n=g_fbfLkTzHRJl`YU}|H@(tyv+O(Dh>3stTG_p_iF2Qx zu>~r&v8%4eVG>x?ajZm&e_*w{1?R2y2a^)S3!}})%>8rEzw$4Mj9$sqc2KxC3b#Pr zKv4Hk$2TKxssy>`klVQ#K?FKbH7*9@o>#ve53q9|9()Kc7582risHM?AV|#T$H@p( zjly_IFYK7^I9|pL8BX4t*>1`hnQIxKuTZmGEiXx|e!X+-;-|JRYrM9e_f<jhJ#gbc zL_LKs38FZf8p3p!45l=#_I|BLsv!yuHlEnb@C;M+Ia*lIaV7XQ^fA9S5xK?NIi>;; zdxJigr^oqr`<Ekau2zhwY3(}-ffSpkC%kif_4%1NtgRKAL))ld=7IVM+*%?iie#Eh z<YbjW@y}KXTW^7?3Nn?h5lvA_)|3zW{-J{Vb=Qq${KA@(QGo4ns!e&PIO>wuf-y+a z$5$?~vL~4K+q<Q%rxJr9uit8OzhtK|0f-lFE5zQ4<RzKz0?z4zY@RT)%C06Jrg{19 z*Vs)Qi3TpTL>~zz(RV>o3jHkL#`5y{+wt%A^B;TG#MuZ_UvW;|oXXPXYmVr!#U{V( z62+B0#08?pVyq!Ohp{s=)@q6C`q#x#pBg6u-=OOb0~sJ9R*pG0np0;^_%+|f%ZeS8 z@EPIiXrMOi0&23-)mlwyjp+h4B0*(nCfSV1Gw)m-p~3Nt+y<-dabAYBH5s>OGoYy` z_W&Sq%T8$e42!euE^d>^P~>N6J38tH314WjC~C4mC?n+YMmTjzk{$$oz6#_w%;Ux= zOUv)jW>}5pVj_ByWlZ(DFN}7d3uVzKtm4Dmh&hd^@)-As5XYFuIM`^<f@D+pJbu<l z*juXnrg&6c%R5||#3f+ixWmO32EGu1l6<uQ(?@VcEWs#1pUF6k_T%)|m9M2ZuUuW^ zi<Qxm9W2TIdi0GZlYGwC+7`&TeG=yLUfP|NcZt8<!#Xr}f59TkMY|W9#^Oj<{PO<O zq8mH@5OC&}+U;jBybyBv|KjdF!<y>9ZBeX%2nYyBjnX@U6h$B?(xvyVB3*iyK$I$7 zy3z%a-U$dqB3(d0x^$AzYeEeW;$81P=P$hboPD4B`F`;+F2k=a)|z9^F~=~{MerwT z=*=|uI^Cb~oaiViQ85n`R|4(jU@n1}^-_e%HKOzQM}jND8X;JORMF!#bv-o|MM$#D zWPC_!K2X$F>KKRs*DMVCs-gR13LIW5#VEp@@@sE&6y~>2!ppZw{moLQ1p1#+2Nh2l zCo>Gf0%`H;O<2khh;=bU{WRAFPlC8Yy+#?4MK|QB>*V&Ojl8IdKJQ_gsUQ2Cm`7O? zX{#!`eNcpE<Z3o{V{RWSNr-j`H^U%8@ftQRG`?2qBWcS|gVnzVJZ^n3sdmc+Jwp8} zRYx5$iBd@e?K@A^^AkS{fM>U_Aa_E8+L5^#hD}lqWR_n3gKj>JnzK6Ul3t!bF4v+@ zHpQ>cg12jd`PrH@t-#X;+u#^R+8m^Xs?O=Oooa!&uuqD99zDl&L!PV=_7Blz=<{t# zyKGv#l(bI?4)G+>60?vt*XG|FM<WwkmUlDTtN){G6-nmS7ueUBayTqRk<spXYdePp z|G`^acG()JesruR58|lq@?>alle;aDTl4yFribhAp2JhNwput8K1_d@RAw2XV(L%O zv}d?iJ|Uxt)<e|#v}a%MxEggLzh-b;7q+uzLD!hjGdYoHKqcl{yEFA9eX~xw>I1xv zc$1=^>spmz437Rl7MmJ!r+NhL1a7&PGht-97RYB*wx7wS*qDH|9{Ci}F;Q3dPHtSM z%k{mVBU=|}g6-Xw=3KS26q16!Z$-f1!AYgl=d{GaFZox9wOdZcmx_9^_j}XU+-<iY z!svofhGtt+nSq)(yXEjKrr*eMaRrmweBSX~>{_OSM>P9mjeMq&lGuZ<<vs@boWgS0 zvHTM-{toUTDwC_XWis$vex`T7@I_zmQIq|B|M4M#E5)rnCMsEqt|m?$AC!Oo^r7~R zdka86h(0C`IS?WH0HTFW9!+gO5%k*^zUAPyPIVf#(o<KDc$pNqB3SAuG|Z?h=fNw_ z_5sbT)Z#)y_$>><Mnhp+O&EVYT%6<c&;8BJk=p>4d!F|4{m(B4V>4+!UN=f|l%|I` zN9z-;jozA5PHG-hVI|u&FE~tsHcnhnag@{RQoXadekZfG&oiqxT1cuLiOKJHd@H*i z$0y2HcsHT_XT-6MLDg@ZZf6lsk$b0T25N-)i0!nvX<=DqrqA)Se!<V|kr%$EG1Y<6 z|47HT9OZRA5|DWsC{bo@lGd*9ocD$6{@u0DnbJV_?Sp>A*eCkfj;|aeE6+EDTM)N^ zUh|^BE50R)BZ0z3cB~{L;!zb8b2H^(<C67^VU>fml|M|w6&gkiZtkSa=tvO%d_|pg zctYf>`{);er42LmC}&nxS|K18ccL^bJ{4oA;rBdq^SZ8rcmL&~sUt4)ZiYZottQ$) z+0%q(cDy>~uw9)P$=x~-{Mt4#AdtX?*)yqwk43o^3T1ejep7JfoEF}QQt}rG8hskY z;lcMn`C7I+j>!#G5k%bihlmb;4_yL~1aN@Aam<FdEbE|k>Is|r3tuaEQ{0amAGy_x z3mRM8zi3uP*ZQ{>lx4ou$FPoHAl;QpNcyy`>%66_qEg_Qc%tL3re@EeeDrRC;SbSu z-{23f$;>a^*TmPJWAFRw99ZC&rE2X<dweA~YcmZaec?~nh6~>1YXH2n=OubZz|-^E zx(W9taR4%o63<3D-*n<=>{Q!p%+(A_HQ=%6JlMH1bMTPZ*JQjWd~q&+ib3CsZsPZ7 z;2r#h5ot?*<O%d0w)EI5CEGf0jgB$hqPxKS>A}*nj#AiW^JLg>bNOU)G53dgSBwYK z07t@O=q-o9I{=f|kqlktK$n15j2+?;6gwQ=$_txQhwWw=a`7w}zfAt{opEOPrz9DB z;jVC0^Ic47AQu+e-e=pUYwoMrVnJ<gsXkmV$OQ*pL}s@(UkR1{jBlq3dc;(6q}@f+ zO(F#Ox_AWdsdb!BDpu&s;Qc%~I8)eBZY*Q!USk;PIkT_+=-3F)YHBF)-5Li86lMu3 z2x)tclt|`L&CA!E(turmGE$5x*6<X$rd<;5iTO|r87ku|PHN^jg+u3yKy`>9S+MW$ z{6DgnlL-vcVv&NObKzoBnh2RjSXZL^L6O^~(rVS<=kla-Rhz%RG&7HT^|^E~&MZej z)Jn}Aq*C&{IQu^pTAGOsPY<xuCm3_M8_#@55m4bsQ0Xocj$rK1M}e6fSnrHEL)Lqb z`Z}hkXnlYT$~}pjM4~G9iLSL(ESTAjtl7|(JkQBv=ux*ztZ^RK9y*x&c>>Q1{c0Pw z2;RsLlro#UnWvG#tuv*X7xE&X8=md`+fZ{p`{*iABQzf%1o3|;2hyqku}(7}u6y;5 zS8y=8V&7nH8@yNU-6+fgEw1}R1XR3%>O9fEP0EaEE9MbLWZ+X*z?hm?_aDz+N*d^o zYv|Ka0N94QjsC`^6XXm*TNQ*5{@9$01w)7hULZubB>l&XI_TdYiMH%=BZ>I`v66<( zjRTnp$f?~09^jug_u`H&1L^~f&^rbWb@4#aG2P|(P;-H=kBIi1J2dV1_?dy3)>W^6 z%z~8w+c8?8whTJG;`pKpPXm0n2)sTIU}t{Qn?wf0vCWGWz*G-R=1M790(vch-^Y#G z3j_Z^q$*&St^sPQ7C;^MvB?^LD&Th(`VzqG9>ClMy?}2+Bf$%o+yJ{Ya>vItcmT@X zW{S&&t~kmu2LNN!i9wIZfVPD39_Y&Brby)8zdjNzO|^`tK6N(Oxy|wL&4V8UvPs#P z;5q2P1{hf2wH2qoQq(yVj)WWj+efG2J7A>23oLDU1mo(x7Iye0M^UTGCpPu`XI&6Z z&{h`!g${h4E5Ho`V81#050PwQU^d#U@8$)B$LC(uM=-36%P2l<rg~XAfDep&w2fFk z0Q~^OTkUZ21UX>+fNITHK9L82=l{+oZOjw%n#uH+^*xrJ7b`^QZ!Y7KXU<`C2&CjN zU^YJFGK{wa(Cr+6#Iscpn%Ht1fJjmPMe|lpJy1Nj)DZoR!go^(+DaJ!D9%?Bl<>T> z#6XojD(;Z}C~als62OcPVLc&0pX1|jdMT4;S+t2KCR_T+L=$xa%iQaG<zeSb&c7~$ zG3l#+h;~;cSN|!Y|6Ta_J%DtQfD0QpkExCFeW{e;WC(fYvkX!NQYIuahj>EU5eQQ( z%L3#YMiD2#eL8L{$2^X|eK@y!Lb(8KO_m1v*`YSKQ2bQ0a{bE8$A&7}0F|WcGh)9R z5ubBC8>hYp)Oh#Ofj@yxlfP?s{0MYAxSYRO2x0JhaIb7Z?!oj0Vg%AC`CJbH^Y+<@ zKsx8|F?iN$UF8Vms2$8R=kw+8sb^wHyv6Yvkd!)G;20MI01PGB#~Tj$M4oeJyC8n0 zKVCSJlQ3TUkzI-Du}TKE%i;T3f!Xsy`neqd8W;X^SD6a}zw%BVpx|E<v%&nTK1ESE zEDullG|#W4=v;L<>B8{2{T?yY5sucAxBd`KEMUEz{WO3-t3v-YO4<@R7mlc{e+v&l zohog-)(A&CfwV@2@TrMEfVk`dM?fK&1eFo;5%(>kEIym*7n6n$L~xN`pOTyGtu`iv zSaZ_C)6@$~xVC1alvV~-!07N07ik|%lO6^Z7I8J7b0DF!(}QF;nLAd|Xx45)`O9QM zZ&K0D!f*7IN6cZ#^G|T>^Zb+-A({wG*;sbzg(A&jT+pzFE^<N|_rezq_v4JUNodve zY>9p)B$!Wm^ApvbeL;GYLA*-dq;FJPBMe5!hB~qI#q1}o3rOB=3{zqE;xuOfAlvOA zk`m=@rU>>Ir3HN7=Yx$flo3W-SDYh1G1le_d1oaoRjUrwz{;vsPb8fvcU;=y7<?1k zp7QtdwDewI_cuuz`IfXOPD@L#uc#ZM8|{Z?;;UTF*Vmw_g-9Z~5J*t8B|V(?<hCz` z3-LN*MHpN~_7hT*0alh$!<vpv5|rk*mRaoF^)0*Zy@-rOK0o0V2!8>4o!YL6<FX6} zoN8~3z^yPPoi40RNcBJzIq1;{0c7Mz<uIrYRJbNyOWh2a`^aHhLZ(^E6#nX}tjWTw z#%6L%B3`W?_pJ~YNVa{$#JJ7LJ|J*Fa$<<V!Y)nRW{Nq2y@pha^r~AEv!2QRT-S^| zivBGun;fD7NcE?NL9`3jT4e96`bfqrc{s#Ba&i+$p}aCWFwr(+2HCmS%g(3#^68b+ zDIRPM*Uy?;n(M-p2l<SZI=X4_481ZP+5Ks&2Rp{i_TnYb3E9iOC&(o->DJy8hc8<B z-MUnaMI*@&og&_`gbGHTFP|(j7LwMbEc#(fxydFwWgBxfO5g9p{m_=QgjO&H_+=r- zMd^*ejF(5H!Iwca;-*jvhhvEQ9n<>)&l|&d@4j&S(H*n!eEB1!K`_HW=?(NbG#p9| zG)32=>NnzS>B6MxOUPBnm73s<4bYq2zFWhvj>VDL=k}kg!@N!3@;&5J;<`bjk8lu_ zJb;~6LTKkZM+t%urg6L`lC&IRSqyDupLcrE-}_`}W5J5YKYixW?2>U7lUCij)Af(t z_moKIB+CMOKqO$hfP1L1#5{n00EpSbSg+N5gJA|jq&f3VK~x<cZeCs&kJ2KV(|hYc zE}|qMIuB>!K3df)rg#3lpY_dX@aNqR$&3jZNuTH?ACv2*C8548avHF1f6W&Be3VB| z2X)m(nGHmWLcAXe^}Fs(8mf`;_EY6Q;L#}wk31O3*(iSOqK8yUyPGVaDIg;4j}o3R zm_q8ueWwh~qR05OR8Zree5<L)<@q2@ec_Ve@I4l(bxA`>kG59^w>tnwsQFlA5W~L2 zyL+1-H4|_MG*FJt4zjF0Xu@71kXB%RsbPlOCoST>_*OGO*q+4CF-7Qe4GT=5zV5Px z8DBQoX3$-nmQ4C3&%`n5vk`@?poAEYNb3VqbMMBiV2#*XldJJ15bY5J>=neeERzp- zIp^s#`URO^g~xc)#@d56T~R=H?j9x3oEO)n8B8||<Vvs}2kyUWzj>%*?_w$6l;c6A zos)F%G*7K=_rzLP!Oo1PZDR{$DIW0vrJ%T*T(VjiphQj__PxTPcvtl^pIAf2G@ts8 zimacI(L_<hBW{VLj5M6I60Mb6lB-eamq;V8$N6T8+%y|6zf49qSgB2^=C<{S*^TDw zpV+lsM@wqN*sRF|k(vYO9fB;7B(SG$R*2BojA@2FN2LxU$MB}e^zCZP&g0OY(~qAu z`G0<m<+3;X?7~-;QEa8JDAI&fOh<uYEvOMdlfnSe+9Y>SSW@aST>&aR-8x&(e4N#x zjiok$I=)mJ<#$;PoW{y2vgy4P$OE(|jK@M>I_Uy=y-m(}1Z{n%xo&G?O!>!xH3IQC z%_GcgKGZ!`*S^tT#pQs<CSiy3bRnVpwe@ocn>%dvF$B@myuj;_t2m!x-`)dtOnt0) z1=)I>zqK3E6GK-}urg^D%1ShLXy{$pVt)h9s{7r%PI}{o9+e6WPIR8))=yv6pbjLb zCT$;Hxm86)MOQo8ERdU5;uEi;ss=Wu7EFgFZlPeo@=KMZ4tD1;d%fy}Td-yFB|Sqw z&`t#Gw8r!@UA#XR1-zihK<nh`M(M=^DP7yS7`|~ciF;%Zf3u~HE#}_gP`M#>L%CBm z16{aqgG8L%4Ty8R=4c%~d@m6gUB1h5!{L~N_Z&mFF|pBy1lqb}(Mt0lgACkRM|3i8 zdWtKXsN?Un_hn<isEU|oq18Y>OHw>9++H)%IaPH8qTnuAR=aLnugmzu%8$|3STCOW zc0sCu?dz>>oS!dk2D);${TW{;FUOI?*N(y_liesccZ6uQI=`TckkKC^Dw}MjSCg@n zRFS>d5r?5R-2$C5d%b)$vR;GQB88#$ks^}ONL3-t1nPr?gS#OM^UJFSub0Z61wAx9 zqP=;eDzU+ko0|ypph6sw#9|via2wxuxq+9(I@c6)HQ0Md)B`%NI=j%?eWeC_^f$i) zy3p?lcG)kS;*D97euRErC9wLY>tXl5WqpyBdgZyP{4-4uztfwk@cbe9K+><GdX)ne zH)?8JDEbs#b$>c#*4M>F?C7?eP_}^EEYat8lgckLuOeH1dMHkVP+eMbM}EJs58Loh zD;Nrg)Mbi?v<Jb<(YnKyUS$%Fn&Ew-+tkvstxFHYt+_+m71P^!Ov<i}tQr(OPAs}V zI~eM#S3uI;>bc%J7V4nAfRS-*&5|B$W&`XhE!!=_EN)|q;PsfF%~!|wjy6qJVdhek zHYY|jy?1JMwyf{a_u3`gStOYio`EB3A_E5l$uNX(Ww^ux&&m;Lc`p?B25cV@j#sf_ zjFDSQbrSQlHy5=fyPk0L^NB=dOtlyhxKUSV6N#u!)qqE<Twc+!OW$gY4<b1>T=8=m z;uk4V6}y)~`=DzYUbNe(uE-~`=&?A;F&SJ?K4v0Z+a7Sc>S#$fqQ%zF>Dq967r926 z4OTK)TAbvU+Qe{&cC@v)YE*W0<}FzjUfqN=?V}*gcYt}=K--GAOGM(->KH-bSDDxp zlxSV{X4sbgnBXftO^(WL(P_U=8wNbfF$NF)(ni08q*_^uL0euS>^3zhLz<~EV<n#* z#>vZS8wGzJe{9SmarRu<TQAvVG9zM#tM%5^zt3~F)2CC;)2s87-NbdB+_$%+uB}Z~ z8O`c7s)si<)s2)}7}v?Pmx&cIzal)nsK`?-_2i{z*zKRQCgZ4WJZ<{?;U+mI{2<w! zA1xCMZIx~GnFwT>HBsjn15Hr<7$S4@<LE6>5ZHPdY2c^*WqN?`N21yuvo6Z=x*MyC z@W$l8I*qfCXjDi8%eM8+oYNmIsv0^;8QF~ue%Xh_VFUqJLuMQOyhIz#b$tiJB7;o* z`}#!;{TBT<^YS0GCSUWUHAz@1({Xc8V(;xIKpF<WV8swqbTu6Iw~07D{^(+9P6i5{ z|B1wF@w@=2x{sK3IVBlO4wMc2{V!OOHMs>QQ92+S6|D{bNlq^(WtE-pVhFHv{>ll< z(VvUY|4(e<{1Ni9I7O-F<Uz0Bx5L*~t6D&q{TH3^Y5qsj*Y3YV6VEJak75he>O4x} zSLW`117Ot^NA6DO4l!td1{$A30`PnP!h-)}*j27^C%8O~-PoYC%l%gPhwoi|Q>*$2 zBr%}QnEe~dPN3Cn1MRTXAJ+p#z^Z@2KaHqXpVyvIg=#)D0>nS9wcH=?zU_i}dR@&2 z_Gv2a_z-$}`PWr|TYe11AFCfjV?gJ?!OuZC7Rj?qda|V7tiD>b4aiX93^;vO4~d5W z>)>-p1auAouG-~Xe}a|CN(z3OGOOt5%5G!!EE&z74S1fM14FH2=frDsDAEZu0boJ^ z*D1KOWZEv#H$k^_vOoUwcPEv5@o}m3LzVxwvl2bG1%UC&-*e#4&wX>(se%m?0-YF- zw6>>AV-$MBDl%{a<33xB&VM7Z6RV$xzuM+josSgacbb1{Y)dw8Keau94H!O}w>*0N zhv*G-W8?z;*-iJ~z!)*u@fm^2qi9ySx+IQA;J;3LYvdg05(7{mAe49qypDwK(UqJ0 zHw^e{at0B>=0rEf9kYB=!F5*xKhvDtHx?cWU63ILF#6ur95U#+od%z~4~BrY?gb0l z#$ir#Rnx+cP6KH@4c%n@#H^#XXIonfvpl*o10Ao;J|-<^ee<wa6So&dXsFmJ;ujL8 zSvkO#!D}jCYL#BLEkvafsAp&hfgr+Z8qsjMa64#+0bn7NCj;-<R?}SQKpQ|RuQB#% zq{u5VZ_a-iIrwxc&&HJ$BrkVs#2_2b#yE$^#t{gSVB`&e<Fp(NJ>1i}dXBDcAoQ_t z(%1W!edFg)o6A-D=553UY(PRHr2YwTZ-)c?cAGbV&MdYIAJ766Y6o`9KsYr|%_AH@ zKzE3(xP;4n@^uiiPMz$&>`ZB~cj2vqJutI70B|3;1(1_h@(5JqE(G5$fZwh_WO9zK zZbpbF!<lC}S&>w~Db(8P2B|gy=kFW=BpN6Ia(N$-{g`DmAm{*HF9ulomS=;KYihx; zET4uw>xFrr{eE8i%xmEn@xA}IVdc*`j(hzyvNH*b^G?g$;cFwEVdoE$Tm5BFfah%F z#^b@KCt?>0&ZQ2DL70@4>|M-1tc@WRloQ*ML|vq}Fk7;g);{~iHxH!vHP5XNgn8!( z-R%UQ9P?ZfJ>#Y)1G_123Q)a7fU_Dj<wa$(-n`NM&{^)n>BJh(C7sBh|Jv@jze}~d zlsOJm$i;#5m3fR_S=7uWol)n7ky5llq>V6x(1qJ4dY0#hY@8#7{-6dQP92R2pPl^h zuou53rHRnTq8|p<9M#1sx1?hgh@7;Iv(MJ{Pv+^|*4qI63E&*yHUp20ak{J>4Eg5j zH4fcfWqbvkGKI(7x*qVjJa<1?|5YAvC^#E<8t0F6GT81gkfl)(KsAjE&sSGEZmN=* zx(Os)wv_OjVS6ju=9$o#d%Z^VjdI~*FRo8ly!TWbrUGu{^Rx=-cq^ZZoqhzr1jSj_ zY`1-o=0>k)LfcF>8?p^ke$B3ospoZhIKPA^%x(&CHON{gXGKU&Q{EQ1XQ`;$`&_WA z5yFa#IB_+`9jak0;!9Ro*(#gkG_3L+B@Yfg?CV@n{DpaGWWhetU+pH<8bSvJ9#JKz z)@O8}w*e;;g!A@Iylx||PB;}=5G?%&)l|ZwYaC`y$E15h&4`-+!|hn^#^;|_DQSzo zW^RQf)OPjW0J4(dV2qX%>*O%HV$%ydJU<Wu*R(Iv%&QNBDGQ6MQPQXvul4c5YAZ*` zW)%urY;A2z_^U5-ZXkm_$g2tt`pH_N4QyL(N!^N;U}8*RO$<KJ)zNKN=Tui)znS4O zz!(b|d_AkJHR_I)bwXxAlWZC^sW6$$UIOIGgL(QRYB#1!`rPa7zVh<)Yvl8G-pEME z21_%Y&~#Z+!Gzz+at`51Pt@(kSSdy;;6jakGe6Txx(cS~8xt<qk{7mF`w28z&Av3% ztg&?$*y>TR^W{g`z6s>O*-UjJDB#A{6)WRSgsu|1>eJ%MfY`z2?ibTBuu(u+SoFQ$ z)e`&_?D)pq3DDt*3=aa^1o%81gmZdf$y7%P9Hy&`0b%bBB<kw=Ah~v5u19cB32x+B zktTYW_A)B3MLVu&lHiq3gM|SRitGb^1TGyj*XglN<3NT{d^s+-IVV5pmH0CCSTMH8 zp0)vI=XEiL{9AIHxu4+6s`*Lh@FUF#=^JHlq6_DjwNdu7x?fgRcv{4nzP+3ut9H;( zn<$WV68J-uc5fhe{Oz=MYzYN*icrYv@F$&osjra^V#O~WEL84BSMGDGetwoGk#ADs z>a6zBzbh(JarCW0*nH4~tNoe;u3DhO)E4CvSxX8B>NaGOmcyH!9~~X9Y-Kt`1vpd& z)NE{C>1`c0l@|74?-F<#d#%`6B$#1^Kpog+AybJ{z;bt4+&?YYq(-+igRvHI0F{nR zv42<vmfhVD#6rt@JjRpKIy%m|;P2S*^2Ad|(d|~G%e^7ESH5F5(<Xu3*X1!*D8Jb8 zy<Zk>+Hgzbhj8=S*iN!lVW-}ylCD?Oo9xv6l@S~<?SU^geDFO8O1C&Ns{%tx1{JMz zi=i}+FP{^AnhbDWX59}RohW;%f#Gq(t@r}jF6$$U2gp%g?c`SyLiY-E^ssvR%Er&E zI7ZlYpzs1b&q%5;UsB#Ep8vEUPz1tqnkFp?$R~oyHXwSQF|P-7pb?6zp);d1$;WHn z2{WrM*B?KjHkq7&mq2#?o@rdF{!jwPd7M1<EkG9p!*x;FQ9vdF++l9mVUm*Sn#$Ob z8eY0oB~Mc_wb}^La-ast^2JGA{GqnjZ8H1EWGz3fr*TJ$se!3+jz+K%&l$zBhnZll zs;|a54M7T&%vC=^O7eKG-=ZeD9UN>T6_{VRO8?>ykt!l<%*#MOZB{4t60ZTnWoB9q zke2ecMHwZH2M@~pHO@q|gxgO~H8(vG(r=)zFE(|;M-^199qom%G2a{L&}td%tr5uV zzmb--$cQb_u0_M`k*mY1LZl}=k257kbX63kVTPT}6aZ%cL5gR@9Tm>C<k%hfNR5sM zi5ve+H6fG<eUcuG>NTR)mG)j|E@NY`pno5?|B0j1AP+0IlEs4={|>#0SBTQW*oKQo zMXi(jYxy~qZ*Okog*w%)CL3Fzmim|MW^L?3oIt<LGr#!h)CU53=$6;<x}a!j$)p`m z!@;YmOO3`%Pv8l@2=@@41c?OKxaiO<g$GQJ=Y50auv~el0ZNG42t>&rRpt$PM?bW# z<;WN};e^H<6kVGbcz)UL3-9fEBeC_ANG<8{>iCh8?mEQN`DU43Y+z?nm0n^04Y$Z5 z^$sr7*2uTwm?PMdhx$pGyuvL)M7HlL(n2_5*DUW+XhoR)3;V%*fhWvXQAzyT2eoUO z6pI=)8EdMy(mq7o=Y9TZBjYYc?`t*<UIEjQ8Y*piBD)H$r4R8OAZeU%`j+4=>D{Q_ zKF+RHDeLy!h0R1j)~t*<5~cW}WhMq8f~{#kz8ZygWYU~)*j5an?3$%fr_>|-NSJX# zC3v`3GMU;t&znY7Q8Q3cJ+UyAV3<{TVv&!bJa~=aj*%Ak!MdO+TPUx7DML+VZ>p(Z zB2ex5;$`fxiqu^+w@?2N^}PJ*#_Ycw-(tpQ$Z+xqVvUo>>LQ^Xqyp^2lW1d1-(eUY zbeict8M^$=<hujq>1Vng6q2rOGk59!0!e%~?fVo1>yK7ZhXDR5^-YV6rKG*mE9Jfv zDrC)Tk)FA&T^tEX7<`qH!SZeK08Zb|3PR!%QrNj#t=#Um4=0I;Mz4&tb=@tK665PJ zdTqq3Myr!-CblasZgJCIr$DNf_H*UnhAbamdE65m_S*R^2HpDl@a;Zne3_@?s#uv= zOD>07^;bu~f*osZyLyVqDB%>q^iMxmhllVJuxrzR&Bx)Cr1jA=8Ur2ljH7E1`E-S0 z!KKC#@upOzG?bs9lV$?r1FD=@F%@*3|1<CE;tI(e$kTDSA;#7O*MxOxYwW9!f><Iy zh*ePH<WIyXtGnDBL1_ZCt-YeP<>T}mi-UrLs?}3n94U|htV<_|y!rkbU_5`x&$d_- zEpyTQo<63zsYrnCz$7~5V3nd??CBDU$EwO6og$_@5d*h=dt|hW!bmG!)3acrQ8jc@ z|7vW}Yp|#@kfNjARI6XWGqb$|Cw<>0g4yzu&`jvR>H0fubPa7~ax0RmEG&##H(x-J zo6ID`>Xwy=Fr}=e4}(T&<#1$$L2ZDLf5mlQ+ZHYvO_ZLub~DT?4`*nEjfoi<mvry{ z;%ER*zF0OokS@^H6O$Y*@q?Z_trNT59z)zRM_oG?UdL!r1f?B|ZHysQ33wk=O+4QH z@cez77z(AF@i}Ix)YO$qaakxHGnpE`e~Z8^k7e&jm7=KfaHyxd>o8`b9{N6Z{bv|S z=_W_kX0+YY#7A|0$<4o<uO~Pq-2DKiBk(y?;p!D|#y}GAdLJ^5MkxEV2}0L1rB^R} zS=Yqx5Xk=znZ>hBnet_nHqr643Am+9U?=9n{VY68blY2#O)?TQ@~`OxFR4{<8ma88 z20E6&e1EUDVYq{`cu;PBKX;Bl#yI?T7|Jx!UsNgW6!GyW*tolu;n14lApB}*IVrJq zFj=j441|KVt?cv5FyJj;)ThPfdlc9oe0j#v0I!qh?0`FtE=JIPL^Hh9=X`Uq`5Mq% zI0t!(b31tqxj7g}1YyJF&1b5$zgCKCo+_U*$IA}_b&Cx|^_01(G)>v&f+%Tp>MfGO zDac33q&xBu>pw(S6mh!&*b_8GDyH{)y;Kp#vh5-79+YxwoxW#B<zfGTmv`@CQLMd0 zYeLWvzl!q!lYkSmHXcY~lZ4g(A(FNNut_c=!!1KRsMjOn6nNC!o{Vzz_ZlpF=rs3Z zYrZ1SGBks~{j0^D@1q?96DF=9>pG4f3rc_jQc`Z>VZfx*!~;&BD;ul~r>O)^`8)+C zTsm^%c0Df^+V)B+3pfp0D1jjn1wOr=O$o(p`2t~h;(E8(rp7?qfn)xf4(&%#V|^9o zj98_rA_P(pNVEY=?Cpv2W;4xQVf+<9a$jk$3)YQT?$g9GfCzf8EAaQY+o8t{vaCS( zJdIiYL&QDKi&Z*sz~y~fkqVEsfL^n-KV}K>VXXQ^xV<tNeSrD)(|i3+(AbuWs^4&H zXwZ%8!5oJC{|eT9z@%1yRNQ@Bn@2u!m_VCfYHU@%#L6|ugn&JrWlK}<c1{^6Q9Fu_ z7MISWf1n#96|tkCa-#grid4nipVP~$yhNiAoAy5d8UD{$vaBm7hu|j!*spQ$=R27C z563Me+~4DD`!Z~0WOK{U<4`$9uS7K9I}mrgh4=v!n9nw)__%Bn5#a=_*-M?{ab37O zc~?{_yD*2sArkm+=g^VT8GIm$JC{=_x78eUsa0zq6~C+>#++*Hs{G^oynnn2^bEuN zx|;c@2>L?;P53qkv}OZ60)LV7D+2paMUFqe--m9|Tj(n!y;N_H(})&%%D}iM;)o+O z==2mwUz~x~oa;URB@^Hd{R^-7?R;w#v}^k(n4u*AMpUqYp22UWbLg>e-ExP%5#Stz z6KqNhI+nw|WK`GGACHNNXe=pryOQeuK;`~x#c~YE=Y#=_&Hx?1uIA{gS|+g}81J<{ zI-lYq_5|exe=0d9F$3GP0nbfCjv?@0Z2Z~LjU}w~dcbEQY_8ucv(2No+=wb#-E)AI z$mU#1WmN6l6^p@f0+sfiF%nHMtHnV2LyxR%Z8@gB|7m0@+&JM8DZmmT1Nz)y?xRBv z^{&2YBlgE?+sS6i@-caKm%U^c41CU=?$0tx;34wkHDw+^?I8cB72pgb>#jD+Yz6zK z)#XN3wo@D!UXBjRd%Fd21V;X+3DE7IPpLFE#ZlS64uz-C4T~iBPTp^MEc){<SQp6l z|2<Ehi=k&WKmVUBf6Q_tc`hYlq4+RULPMGLSOE~kE{M+U_c;o^xwa||BrRBhC&aim zz9hXo@jKvCy$n9}0`<I+{D%<J1|(2k137?kMZ)8T##L#c1j3r~hX@d>d|&ST=GrL6 z2OkFBOoXcTlvxr(e^?PFB=>SC$^mnZYk{``+JoT0sRtqVYvZQ$BOq^Rnti-{s^I2H zq*n*Vo=~28SuSgz{Z)=-1|YLsaWw>CvD_!iN8|oxwEx>n#FMCpC-==mb4r5T!Q6hk zeq+(6zm6etSKKXxfuW{=S&9?%$HqB<N8k}T;?%<u&`<oQmB6zZNR!4fAlB>mXzPu# z&V7)(5&%5!E^nQtES!D{<XH>kAA{T}bdaJ9E_=ne<?nbU3k-8$EKA8IuP#m5Rp4BB zKWz>x6@5kN<{U0`ql0?@cB~70-xVj19Ee5$vWdjV?YLPGW*~y8bI8#rzCJEn6EVCg zu&Kp_wHsz9t~X{ia^8IJMCo4Lf2}>@STfXz`KoZt-TkWMJdK--CEKR6u1QWev$nR= zx>aEG`Q_tXZev~{KX&L1X;t%8b(5^bRYjAMSZkaf4=rj%H>A1My4Yk!S~3F05DY-t z0u(t%9LTULwN;N2zUA9xkgnG}?p)rP?pHWD8<4+o^`ndX`)-z;Os@K@Md!=)ym#%W zB_B&S?-J<75;0wxIN|5k$QY~kw8LOFEVe4~>Cnq4`Jv4+m}7U@l_muNkpZrZ7b9&Y zrfQ1~5ko$97XyS*(BEoE&8`3%fWdhKB2(dDiwX<HUi2sNyezTvc*j9%w=Qk4OQxfc zO4a$Dy~T@WcQd}LJJNZ>z6b&-65E7KZTm)iK)~tD5eo`Rb0Yg_jA7$(v5+U?>D^AR zoREo6b{_dZFj0xG9SIVlPrLSn?&1<B@R+>s6LTNTgN&A7b?Pb6a@W^6EaB5S(AZKt z)Kz(?Yc{l4Yt{V;<5y3+_zQJCkY2FQK^0#0p-~^TY??S-M64K<Y@xqlD8|RBpjW^n z<(=ebX8Ci{5`Qxt?GsG6zJjO$b!5L|6&%BZDtupZM{Z0RUtLyH;S5ukaN-@bk^rQ3 zf+mOb>qW(M{Av_WE}?|oPLuHDC-y)tF3}mHj#2A;4Q;Q&%A+g7JXxsQI$!gxNzv7R zGMQSdsjVTGcMBtRxu$SiKg`a$+S*vU^VX3rKqeMLyfc)Viv`<ev)DDuB=oksd~$fd zmUS~&@q{Z@A+tQa)X$J!kmcLwp{DOc_-reYmSt(1t=oY)Sm>rX26}KGOBpUp3ZUID z5I5}AuJ4WNp9!2;t{8ti!O{iCC?-QS<>wPubJ^<>jM?kH`G1&C8P^Q%mso|`y6rJ5 zqz<Q8GE>M0e<>bIFVe|a6{oQ4))4YM(kqg+*NwL3)lF9BDeN?e69!W)KFFv{5_w=6 zf)y{|OEw8v<n6gRqta}zD5@RuNyAxZ(G70J-KRql*l=<g+9D5qftWZUT%)u<xo<an zJ*pi<iI?#{28RHq&wZ?)T!dguog5>3?*!vf_5Kl?f(bLb0tvZKo?@M;VgOj;00Q{G zz{@8nviC$ALW9W+4=aZVVu{-&#=W!He~FWR`d~D%vQA$9=`=06!tEW0QHoz#UiwBn z<=y*obL1c@yeCc=YeQ~pcv>76i)Tj;T;YyvW}RKjx(|=-HLit8(lu%(zS`=e?I@ex zrL0uG+4*ZmA+yw&FmxI(2AxVrQ-;7fvGgd-4s}!HQkq6KZQWZ`#SKcBZ<=TIuxFnj z>(bh+pV*1xj0X8*l>W}o1aZs`GJTWuKE5Ir$IaWln<3$)mN@r$#bdODw`e5u8lJFF zRCHo2XiHC_@W8*HT#^zhiR!<d8vc93#_(N8rCW;<CF9pDYjwTj4st$in2J<#vWBsu zbake~>sF)4<VA4pw(J!k<rFk(b6OoJVP{E&SMfv5@O4Owl;U(o2`$g9X?q<cUOzOo zE7%+tnVjwopfNL_+KA`O;!03Rz7D61X_g4=mF2?JhdBfCDNTrXtRh(A2%$S8UVXy4 zLumDTtp};8R8J3v)@*LEd01brzoB&V;*Ot1AN$9_G_^z|hyviGFd+>$d9kJk_NNtM z<W?PlM3}wTvlUMCp~9ulf9<RFNvcWenwZ-IhFKQV`LVH)F;F*=x^(pr#ky8B*$N|f zm&@-I(9K!-dC;V(GNv;WrN$%u2(#3FTA=zBQS~(i^~=<FrJhc^JfC~AwES5RkKk6p z&g7_^<(~UokQ;F*gMx`(iR}ldS8K*6oeV$TuYH^v<efXqK2333i+!Z-!#)XS3?p!X z{vCnx@Casp6PQC%WxsDU3xia$wLx;S7ssk$%&iki-ZJ6d2fCm5w4A@>XLmq}S53@( zEQG&i%gyA^IMjEUylJCIzx*_Yr=fwNKJ=GrgF&JIwSjr>&FF7VzLKr#mpVc9U2!mg z;M_lVa|=0)XUVlcj>mLGaKMJQE4H?unLi#v6F9p(9pbwkdN`lOc-G|pIKX}we~6T* zDI*MINdcw;Q)p<=LEWst5Z;3|&#~B^W5T{>X4W@Q<#~M*p`S@um?LZ=Ql48<RNDO^ z#}8{zqK%~z&ft6J7sF`ncAm!`pY&B!rLh`V2T9k%-0>!Ed%>5(h@~viQ)=A32oc=R z;WjgrQ7NQ~-0=J80bi+ue$lp+OIAh$`vZ<o-8y;E2|5`GUb2xOfy#ck%(oFqi7lxP zpg(6&wE$<%@g&~Jy)?4z@+ISLq$cGmfqGn85V?7+O;c(sTQGlgf$ohOEYBCM^XN+6 zy9Y+-{@=eyhF`oP?r(%{%AY9Vxkjxpa~*Nv<S5^3ZOn!eX-_7-^R63UNnHvWv{?Bg z6dLH6tYRncUik6kS@%XZU{mW7W_eRuN?Pf&L*nl)W&@COoMHW4GPS7gG!j8Zs}CGs z?-hmjMykkq%aKwmTB1ByX|W!y<xk~9RrS)BbPG5Qq86R|RfSwl3aqucM)zO?%X3uH zSC7>KSoBhyLMqgVHDG*MV<D%_6#7>88)=F*ri%&&dWwoM(fRzG^i_r(7S!100?Yvm zcb7@)+-e#{UJe<saJurrS>s9bDcH<t>!zsL!|&W+D<(A2ZT&2*SZ-XE6UMeP>vpgz zuCHuGOSTAkQZgYR9`zNSMP{2dBN(s$LF`pGOY5QLy-jJ+ZQU7zz<eZ_%#m?68)a_U z=1p&slDG`DcA%%T+nw+$rncmIEUENO&R|k;{;r3mTH7pm>8q61r?lrIXjVs!!~+k* zNK;4pVvY6G=88a8qT?r4zNQcJKcFjzm-6<*mDZ9CC?^_!yI9+uNVz1d!g)}9{n9X7 zooulJt{FTxO0z8+<a-s}lEu}C32T62hOU@q6R%P}V_Yy(oO@2g(`e-;%3jtl*mW$I ziQ0K#_wp^<E@E=(pdIJtBwK{7L5Zi7P=>#{od71oaa$yA(5IEwQ;Re@S~*=`b@bw$ zy5ra0Di$^=>6lcf?@~zMhX@T3M16DHIxHkdE1Ws1zYbAOpwqh}mBm)F?muG_3{48Y zB=Vxm>$8B!$-uo`7s9oD3>kVnI1qRl-f6;=N`;5M+6O%}8uy%t?zQ!}y@R4Ci@2jC z(4D||_sKOD;{(a5-VO_vK6k!^{CA50OC<U>3eDLkNS%CS3-&)uP~GHq+9Q0#^mbTM z+^?4~QZ~@T(yr*{*%#@S@V$3)_Q)2^v!sbAk{WfR_46xH)sXEID*(TR%cIDl9gU}l zk#PNT3y0TV3j73T^NSqlg~dB&+G8zL^5eVhSw5uLy!eMvFRl^EkM*ANvE7$<YO0CH zy5Pe({t&r=_o$3v`KY-g3Kaqhy24gtcf+uj@DseF5_lK-I|9h47g0o52wDuE-2Fq; z&4~kQmM=IFgwIl(&)*Rk_u~jjahkxZ@OA2`e+keG`o(=jTfx~cj4~E6Y6^w_AsT9! zT!DKLil<JO3CaDxE|?GiMDxA|2#GJ@J6`^qN-xKv4#e3vrGdKjZT`4JLx6Nn+hu5l zayhzS25m$f-zb-Qb1hpH_<nx<DTJF4!uPLFJeL{(L_t)3fpBy@4mG><|92;WnCvH` z`I(Dxn#su-$<Mw$5*yeccO<;6fzHwXo`iONw%qT7CacIX8y;MR{UMT@Kx{{@?0r*g z?a~bE-`Tpq7(?VcQ>k~%ICNG8Pr5MjhsYVAYwS^l6Hf9@Jd^<V84W(1ansYf+K;gI zDqiE-RexLXF6W|hr=pTc-s#&i=r0ME6I3IJ1p0#(x}FD>8p)yHKe=QAeDl@ZVaF?+ z)38E)f}nnA)5D-B-WGNiNB0H<Gqh_Ov=7v2rHCd7(?GR!g`M*BQ0ZVP4hW%dLAM)G zKrSP$y|i(JO6hauSG(y{Dvvh`K!)m>qvalXIssQEd<o#AcXXXZ;rl#2FLXfvbD?Aw zRMRlzMG0GT6{C8^4hg=*4fEVjMN=MK%syU2jJ*NsR{z5aiOq}GBqWbL$Gi<y1gg2H z#a^X6DEBy9%ER-*{FfpL-^UOuOp>Qq9g~&DT1k;U!I0v@`5M}JqSxbA=W5<LB+z;> z=rO7MAEJOE=-;u+`GB^L|GM&z^LN0wuuynOH@|Y4XTEX7Wnpc-l5ap#F3$H4(KLX0 z@6Y|`Y;XQuY57<rQU9=)plnYolUmacbjtnK#(U3-_QWO6wsFzxOp1-?66|cNjZ99H zXG@C2m(rbwpY-IY-1@;m;mCSc@cu>o@bB5i{by|2$w9eWflQu*WiP|^-JG|%7L7GX zZ>^hvr_#Wum!AU~`|I>wAnYmesT<)-)xX9wZsue+iM%<aIeGn6N4wc3@vU<AdN?_u zZuxYSP<!FPB}SG%aFUe<_Xp^$@Ie-|yM(fGVN#0FnTFcGHX)YiI8q1Yx}jbvxr0qV zPv=)|*WcuXBJBp)9c{kNArJ94*$?8ek{jFpCtMIC*~=J0XrVgokmGBYj=1X%Rr0TE z*cHjk`acn3?3ueZ=e`PyWQ~a*rKnuM&*V1OvtuvCxHEbdX?O4?t@coBmt4`d0FgJO zyQvlM$CPh6*2KN@b$NR~n`s~JeW5X9D8a$az+GJ&FQ}iHyzRtTo5vtL2&Qz9y#`23 zTVaR~WHHciJQY&Lztsd*5h3mGhmDdSg;=5Pv#CwIdR1;+-*6(EY31d9{F0t-tdhr# zv2<MLlb{Nah*fH>h_JlAp9yXSUnSh~y@z7y3Ul^s+9qBB(;27>o3ZUXQ!B@N@s=B` ziQLq=<;>;yY)rd5!P++${~Mc%e~Z`zijeF|Va*Z{WgyJ6!a`WtQg*c?aTfVwU)0-9 zbMCwG+HzD)-wWfQ)_BwhRl*>KZ0V!g-EFZ(K0gaK?YgLB?aMNadg%%{hN1&`cREG% z&=ls73`0`aO=jlVOY3}}8%%ZDyAm`g)E{s@-keJo=jMFb;OAs}+zTWeW)aYkwD7hH zqQDWt6--^zyr4(t&aAJ}lR?5AquW8d7l}vUADn~M6^-E~n!IVqgDExE-$^9p0f$|{ zaZ`ptAP9OGi|O|&T<Uj8sm=DRD@uTEa&JkKf3MRECQ2#dx`aywGZS_PHcNKe`F8SV z-{bo?z+!=XfT6r;ZCqp^BStnHV3*8?rD8gFTbggisShs=ZRI!C3~moC%uYK@N<T6@ z5#8BxV}wuHG$_>8b&NfU4P3(YotXaPxmv5VQ8N#k;6{%2h2_d}It1Rpe5;6fl_r_m zMlaH0E4?%M*$!JHSYB9nFHhY`OmWRO+MTZlw(o@tihIX!VESS4Lyu?{TbaI2^8G&j ze3IePWfQ$DHl4VwFVoWkYZ`(b4V|K?%le{b5|np~KG+yt`xU)<q8ek^)*nMssz|33 z*oVw;MoSc2Gb`%TFHbK=8?b7l{lV{~24Z#5hHv&LFLprD+r++crek|W(mpQ5Og4-u zl|yrrma}tA@2Hi_$^@61YP@>7yjeCUC1`h)Hd{{kaq|$vDx5i{7i}0K4M;6t@pW(0 z7~XaX6tU;M?z3Z>KUSJDb~rAvGxfMJ<FK&sSwv)RQ<%4{OM~pq70c>~(`Zj<bk;-o z_@^<*6{O`2Ur|B_oYceJ1_qvN3|$QURGn@en{yo4;0l>)Sc<vwd8qe-qw(kPoe~|y z*HJHqeYL6^DND8~+LuYGonNR-zPp&yjnpF|Cc0qBvKNVpo+D4uL9UFcie@y7S7!L- zDZ1-r*A|)NrA4NGMOU;J2#TL_vsENp-Gl4<Db^flc&23<dLMl&5Y@lCrX9_kAHJwD zvaDG4(1aIJC@gIZltM0?rU!B>0mfR{wazg}ekXZkc<^4P!ZTb85+_3298+-b){y^n zM?}ht#P*wTkKU?D{?uI=vIFtc&oIj%6UwOOn|OO5h03ju@rm|&GPWcI>Y^l9@yT1O zYw$NNHQ3gE&X6u@Vy@ahq~dgc;X|GJPWC1cu&{R&oF=+lgRV&y7``3fwY`p=V{)A( zn|LNtF1A#(t59x-u(c)Um}zjzi%DA<KmfN~Rgvw7$l8^Daeb&m0Yi(1xP9#>9nk~9 zq7FsghX`*zA*=y70IpII*au~WT9avpAZmOzjggjg5WP{aUO`7Sob~55SBp8pch&D^ zS4vyAjJS6=RbUL(Q8(Zzs@>Gd#!AUJCNzCqAQkSCE>7h{3U7$B^(ggC)ozMKEh}KZ zMVT3O5hpc6c<=dD!v|AEXxQFezE}G`-0m<?Xgmi3So08sAz-XxDk=m^Iy$E|BGwxc zWh#76?Meu_)0MbM+LR@J&6)>qbHa=U^OVDlo{JE^wPs1#7(t{l#`rr1Nd=oX^VB{T zt)z;X8}TZbrlZuGiaZq6Z`mBxevJ#~TWFXrwp!J1SEAyKOqQz8;J#KBC;Exu@wNQ> z-NhQz_WeT6!bzvCIK^<J@J31DdYuLB*IzE3>0ZpQx8hNzcAhd!28geA<<ehSm8xRU zbdv!D78cpT(x>qp_5!OGsluHyYD!p{FL8w(1s0QYYlAJE3qDkn<YG*h?!emm*k{c@ z{<^QPtYtcVDaDR5^JpIxhZ9bX#rt4J><<tZ;o|d}bVj%rXbr%H`tomRPOHs`jvsps zEJe;UKaI<~;e*VunVPLV>^6H}G|ub93KR)gx8Uh>@jN&{#9zs>DY4D+#qd$&oN~&5 za<pUOG=D*VJ-wx)XEKL!nc&ZAnp+Rq_FeHbEwXnX*YRaSSeT!F`<(QETQz@9n6JLh ztcP!FJrkm4%)?8d>}Y0m-HybijouGu{}h(Q%H{yOHkfbX;P$1c)p6}0J=C<3?_L== zP_<&q-hE(CXB<!x&}M)QL$pz+V7ak^rs}E&%u-d+l;D2KC(lsi@S@Rzm!u%9HTT}O zNY&$cn<^l$g^0)|g_C1w+LuwIv+u=bET4QEzC8q2KwTNUJywu1_R4<UPedVfN#Bct zLeDucQu)Y{aE<IlCvX696>MGP(tLS6jV>P@_ikLrczxF{-oZfXOUf@G-*V4frX@MG z_nz_eyPWq*OD*0%E8CwWbmK<Lp+9Wa2~G986-$J>m`P^d3<2)CR8fmPTVe*TT5lf{ z4_=P3=B+yL-Ja$sRw}EKUwwDQt1$Tt_1#jnBa1!5(P$oILI_tW3aL|?SDci0zh)YY z%!1qgA(96~3h~kwOh9qr`2X@x7!&@eR2n?+^11-U$Dh94bay%01#;(CfzUUZ^;>yh zcQ&1PfWmg|j6ZVvS9PH=4VpNt()BKM>CQi-z1YBe&|ikgZ2~JLIdrGB0dWobgF^T) z9l$Q)`AS0EN2!F1KnQmGpg|IUR0OEaumjYH7-5`McJ$mHEzTdHxCI0At1MqeF1N{; z&O=+aBX;nLSZL6*0LxZ`vDemL(y=s(BhJn?gy|uh$@eDay?5GOpDt{Er^<-8us0is z0Tu=X&#pjKJBC-c>>;m;$?C@O!$a}>nBKcvI{Au_e$mKp%C!x-Xn#J3gKvk5b7%1( z_@Bu1f5o4)3ZASF27S{B+}f>;DkqPktKKX0Poo*|F)#myoMq?u;Aio#2`dZi>)>|U zx?V(1bi1B(9#KXtSl(RlOkYgwg3B3}0G&mPkwCj>pABI^XPC3PvO&e>J$ZcI%ZwY) z_vQX)VYdo0?ucUQ)byVk<nLd^w14B${HnoyHOJr1&H^u$(aFX$si8y*iRPi_i<V*+ zK>x#HiM$bK^GI<bHWpAGwq8G-EHFO~XaPz^!e<iz{bn3Ly<`J~xBRf&H}^Kg)uo0y znM~7v4=JPc;~6UT-u@65J{x9Xzv74tU?T%j{XPA{e+At@Qp&$*Ex}^-U_eZW{$+f0 za3~QWx0=5aQ;&c1><`gf=!)W-2NnN`xBngMcVHF<?ZyP1ihl?$*sJlWx~k4!Cp;tQ zL(jJMIc|>d*bO@V6=>;AtNPd2#(`YKrbggu=#X^otZnjtoow8q+5S2CFgXUxzbobW zi*C#T0rx&%_sIa(qb-<nG*zvFe9v97m&}3TJ7pD{eIP;*kQtcs((FX+kZ2y`EKjeL zq~uVHpG``CtfF*ZM#z*!c9HAj!A1-d2l6dAN4&@2JOP{pQ7K+=d=+>fLbU%LaFYqo zrT4>oF&bk8vXXQL>ibKE@e{uKm#H<8=G<o+9#{e-44NvA4-)^mMcRH5`vI?R)_CYY zRX0v~M=`dsyVhDytk`{E;DKO*KlkY#&xQRCTrfdi60|?m1d^pZ+Q>fqRW5HHW;?pY z!e(<-gTyRY?xtPAX%?E`3qIYkJCW(aW1uGhF<KW1AjyhTPnTtr<W!`Ak*Al+2j1Cf zk(PB6SqNx%0=)f6j<VbZfI)}Eryk(`#=k!v+UYPn-TJG@mHh#K|AU<Ce7rzw7jRNp zK&2CsCOZI>Fr`6+Be4rGKyeHQTyTSaERSuNyHfH<dg+<g&0E5qeq}&2`~RA44)J+9 z_u%e4@PoPm9C@t|Yb7xGK>35nu3_i{nUzaPx!DK)aYw-Q!|uF|L(nde!r4xgqk}*E zr-K@L2(<E-_kZ2I$Y3>g+mFp!3!if9Qn0yCHZlG{^JGQq(%M4=ZZDP4Ah{#f{J$6Y zv@wmwk%zj7i|hN$hTWym|N98n%Ma!VGUz`<u24Q?;D44UK5g1Z^7cY<;5<RtfhZ-? z_J0qgy$sAtCXsM_^Frr3K=oj30O-=4#riYu3@=BwSnq#K>T!L%z*zEkEjd@u8N)4} z{rpj1;}jM~vE-o4zBXpoT7X(`??0!0wn;?G5MaAOzo6rwHHWQ_7$vkKY<>(ElZR)+ zD$Io^%-YYH*ZmTDS#6Xn!1=zvP>b)TYhQ-YSpQwe&21c4_J%QL7-bO$-lW9(w~>`` z_~_abK!aWZ_hmvNi!Y~!n$b2KWumkc+wDGs?}ds4Y|4S&czv69*{=t0RqR&`#^HGD zH#p~oneZZGU_0S3)?4*McwOX)pBMQH773D1QATyM)(t7olUZN$t4OAa?p%4v_SlN| zXmB2OSIyOiNwg#eZ(By>DW)rp120!Y=N`xX=f1c;#{m7oM3@rZ5$`e7M~xZR#=Nie zSSo7G$lCuI@Shv{Lh|}p>fy2B#sFqcZ)n@5uCWf6k1BF1cUs`(&=JZ;4waWaFt~h? zWP!>;<?o(X=;Lfr6``!RarU1f{J4^G-_%D^#1Z>4mYO4CAc{vtWy@1#rO$oyjVlBp zal$7u3`Pu)0hzZ{N6)&GRa9w0mFH%BhQ0DO%TMDB`7@Ip+!CS}FXv8akLraqa}Aj& z)J~a{2%7vqwS9L~lS|ic00EJv(rZ)@6a*|3krGf55Gf+PswgcYy(maPM3gFU02Lu9 z(xgeR5<#j6C{=pzEujWT;+=SoB)s2yzP0XJ_x|@hXr7tbv&+mbzkQ`EqCtYQ9|!BM z;+m5-F?gE-XTSc1*YlwZO-Gt~)_{fS%MFLJGrgy144JMO$_VhJ+T=)Afb=M6?>Rz< zXDu^M+5?I!Pu`*3xb_S3ZV*ES%Apg2enG@Df3%zrl57*Lud;fUY2h3k9HXl1pkkh$ zCR!mh82fc0?ys>o@h)kesAW6*9TdXg+y>Askz*Z%rjkI|I!{OD=lMRAts}1&tf5LO z&HyddwN`$&<f&wsNV|hUyPWs)s=5?YW63a9m#-P0MywAA-lO52s<he_JB#~#=f6LG z6gQ#ecwWCHk0qeo74+eK?eg&LUpEMUL`3q>F2Su@<w_A<5<Bk_uGdK(J5F<VCm9<k z@kcbN7cW`#NZH;l?sAW>csZhPWK~*fV^s65{;je+<k_<`Kd!4PiMAEBZ7~3A<Uw%n z-9jVU0DMPPp!0U;ImK+3S(by=xA$8xOH~Q5J+EuIS~<|CE-ciqey?bzTs%<AB}3+< zTuFs@ehe!}FCIX&(SqM<LP<L7b95#;4d(~a8XkZi947klqfd?8jG_z<^xn(lg;v^w zf|oy9Wd0SgItjRla-chBaw7hbNYMn$>%vWpq=?ymr>mixk`&KXV7s(Z?OlRR2LRh5 z<R>Ffzq#c591nk+<6W)vxku5f_r=TM`iI?{qyb39XW6iSWFZU1k>B$ENnij{R*Q9F zO_HMdy7nJU{$rP^ljsvUflql6)rDGPF%NU$=Lt4iPv=+b)njkE<)?VV{EvzPx{y(W zpj-l7U-|{vrpx#vdha^#J}=w}G}eoz@}qL!(u6pz{g=(OrT817bYyp*r3MAji_j_y z<Pa-l`()xj%2oBxl4v=y5sen}gevIP>uf`*XV#AlCfkLMwAO;cWBU>kak$Kb0#OrG zv^aX=p|fe1d9u(Q?@a^`eH}Hr|240Ar`}J}Hub?D4&eV|t9XZr2S{NKymthiE|a^s z@=ms5GRwu3&wiA8HVG}pWZMn7OLkZ=vLx}rAX?}2qqH`ja|JxuwxJ}Z$Nx>M$C39q zF}yxbDbyZw^k`dR8hukecUkT(e?iXf>1?9=XTv}>2!o2C$-r3+9udDSYfh?3Ns6B9 z*GM}3&vy77>q1O$0LQ0AJAk7teYm(Td;5{}<Y5)T{!$2knq7{>E{iGAdjc!q@;i;l zoll+o1;W-hv+ozg%GC82<W!)uejgcp=$-A?XCG;@>d*=Uw=$y)-qoZzTblzU{@g{) zzwS1Nu(e}(BW)C!aYfLtWgo~>nbN6Tg*$&l&)I@{KAeksVF@tVv0=DCSNC?Wae{&v zz{X8R95ow+uw{-cNhQLj|1*Or_s`EyV*R4u4NUxkG{fdZLvlJmAsaQ(WFk5ZIh3e1 ztiZZHf_3Q=+}X%p+$aVo{+T>Q^c?&#IAugUhYiD8EBZ!qVB=%jn{BH}G(_y5e%m`? z{Qa~9qu`?GIr~(gJdb!gZjXr!Lbw!D%V5OSIso6a<)ryt@-!zsidQOZoj#n{OXCs| zmaLM9C%%x!gX<3Vqsb*QuFu|u>2s?KdQ1eW{TK+Oex}Q2{7jc(8$_A*MPj2z9XSY% z+%}ITLz3|+qhc3VIt+_rI-Jg#HM_HZ_)u4ws$Tr`W|>zC<lrlqR!;*eUjoOHyYU47 z@<-*Rx4xYhd}Gq*#F72w$B|FtbvkmQWHqjYwztsBiom)>RFBc!(R1P~@a9<5*wOHs z->^Y{Bb;}9EL_Wd0`+*mW0w0^;>8PmZEmRpFJa#K=Qp;}x8#O|R>ogYIc}7LRFzT7 zUPMEA>L>3BWr;w?Q{&Oi*57&#@pu^?pxa7`;ZUGih=K_EN?|9W9UY=^4!A&X)S~K+ zm5&ZSqe#@t=h_Rq*X&5Srqr1W-g(cB3LIjstzM<>ua+6rW9+{U3NrU&+Hl_eh^pa6 z9a>p{B1KaY0Gkj;%!eS(m>Xzk<QP^XS2$qnb*Ps)AN&}QH}op6sDEE_LHHrg7~01@ zLru`S5=IEO{mv5;(u6t?69Ry$=D_Q)l>bQ6soW9w1Z>xQIrv%^aR)<@0IG`Oa|@ve zH6+>RHau^NAJ<Hxta!wVTnM?3n0)*TA~Ggg`~xv@2>i~BV@roR3wh&;b_U43o2WDg zN5>}Epe25v!CgDA62he@L@9E6e^wtvG!3mRpczL?Fh%0`8J;nR0rV*z3A`t4dw&w+ zn?GNu#{3Wxy@wn_%$hB_SzP!9(RU!Mf&!CiTSzv7I!ek0oCRZPw}KnN8(=ix(VO=N zYrC-ff#k8<h>tn41h(H8TSfnO7+WrnGyw%bsIX~W>N8+|ljV6L;#MJqn3Lzptqkjx z9sqJh#M%O4ZqN>!U;#9+n8gJeCs7G^l0j@4TABp`XU~L!%nuMqRpJ7{Pl!7|ouHjA zxXckd_<lDi2A{CP3KNud5j}tZ;rF=y<M~%jCP1-rY{@)TgQZK)+%L$E7{rzMg?nCt zksq3X<rAL<8r@_Le8Gi42TW8Ja(xN0c0A|ZZw8Rp)!txiPym;nOC~5|!U^yn7#qMm zq>`8vL7pT11sE<c8!<l#TRUoA1vm(*3jRk?F5V{%Ad!_OF)@+BCNGI)Epqos!;P9w z&>g3hzd`tN7u+<Q5yN>(yvIFW)8hQIQS&b{NPjj<EOB+F$&}X_xNxkBO}~)}oy1fh zJgPVdJQ}blV6?xe_U9s|S1fn1w!i@r0*Lf?YG*l$L4~b5s=)kmzN`n&d$Yu<)Ivq_ z(cBWjF(X12Y<W6CKX-#iVrw;ofDf+5cuOUGJ84^gL?=o>&b1A+eR4CT+n68T!hv>2 z+++hQ@es~~FK8gPXNDUMWlXD>g;pMPqhDQ2>J!|`Yy0H*=xH;-2OL^ZKw7SnGDT;r zcBf%HbRt+(Q?MD%T~D|j_9HBfcaxPOTg3@^{}VXVG$EEplNWnXt6Kog92g;RlT<2! zt+#ClkIi4YSXzoSc+55Jc?I#x{5fqvUpeYyFQV;@<>rD8EuHR95Vc%@t#=_3Jce(9 zSPk+#YWZiXS#RI*!kpN=#{#$aE5C47Vn30?vOB<|@=XHbIGFBJKe_T<EuBXCbH({n zS$+Gg3!g;=2-Yi{pbC0du{-AVT>?UaE`j}5D8W0k-7j6VpPJ$`89Q;GkL~VJeKSAW z_78aSVJ0dqfrys?djiLOi1@RU@Kp4-Gv;=5Qr|QLV(%4(ME7)lr#)$zJdD0P{4|lZ z7;89&3bnL43y(`Ya^XyAjDVub`_sybKU)XqKTUrNa5h-EHNx72bzP9QT%G2?@35^S za4eTLO3@M3j2CxCN^0ZZ-g=7-xDh_B(PjQFykG0n$;qba1pnfznUq_B8<%hGOE>1f z48b4H%H{LAq=^j}NwE2B@@=)wCVSS9`_VvbR;GxGq$UsRsr?L8yodL<S+y67i!F%> zdz+^7pS<l7rFtyp&P^v}+84@;mWqU7SaEJ3>MksZgIhd0W2;KG$8F2-ODy{&*TN=^ zGUBxRU8CfiS2ItpnjfGjRKxiB-ZJ0_M~n~k<2MKwKl+kb-Bb~<n0npl>ctO>hkbs| z&nt0C8hY+ho}9gVNLpS0j@O41i;}t0-BQmhyLgg$v}D(E9Cx>!Vz5i%5O5|=gLYhX zF0ftB%Y02;S683A?_BFrXoHK~VP@LAB!)TBiXFx{+*Tc^^sa;MG8Tx$Yl2M=L*YHO zr$oy?loZEC_FkKXbLZF89`rlt1P|YFU&awMKruNZ#Pi?ei6I^jM^xGs4b<JWw$gPt zCYau|QYZIk6Im&03?1G9Eq$z?P%5#K;kzqEX0dthu1uNEtTId=3Qp@A9-(**SxEoy zoGp$evm*2IQVcQ|<Xz2b^JT^2+?(VRr*iS+LOc5##;_ML4^BMaRqROu4c<8_dWTi` zl3)JyB`Pl==}n?n5>xEIC?+b;2Ftl@)DY1OIbzSpcb9Smwe)c~#;;oCX5S}$6{v|G zv?VSONhpO*iM}UM+8Ud4eo-<{?A`vC-;&*|?CP0$b!a}Z)sSQ}qQnAJ?oXgL(cfu} z$un6BD;1m->hl<6SmdA8E~(yD-qN-**Zz4AHQg$)vvGpzNyb|4)&WyQPYn?}QTvY$ z(KFnL&HJe>=<y@-lsLczJhCYNo%)056Vg6HcR3}AX{nTUXL??jG@T0l{Cp9*!jLrF zD%iIl=EJ)Kk`@I~eUE4q>L+~a*g8;PW}WTs&Yt1SYIs&8>l;w?5StW3(qIrzcXIei z?LXWr)roZh&@HysWr25GE5zsMU}u(WsUrWoV)};G#yx%yN<4tcOUk}ycy4UkTjApQ zMc&#}$klp}$DT6s28MrhkS$dO38%6sXx9Mrqdm7B`+R$M1}mhuP|}K<*S^!jR6G&8 zvXD$-*j6uL!o_?<50QIf%Yz#*ckFCZPZd8qW_6w#h~eo0XR~SY@jy5S(MU5sgWTrs zIk`LHr_r+MvhG_?$7~`wr6)WDp?_^ig46GRAF>`K)vT}=fkpmBJhFJQ-Ow#63ehT! z6}9b(r4{+=chDmd9zjM}j}0VdmV;O;psVMx`=~=<X88;@aSk}I%tZ^y6L++L$!994 z0k;54VE0;!L?uYiASsH>A$fHQNA!I;A$rc?W~i9J?-+-vNXazrtzJ-qqBv~8atfZD zL`jY}*`0D1`-PyCMkvo+PhujDNMFSV^vfR%Ni!R=?uFke$Z}vZL`YslifVwb3NiEs z=Tm;nFGwjY#z~(H6_S})782Y84h;X`G-N*f1;IVdLCoiU_zObj^P9-bMuU_G0pRpR zB|z+mpsg}E31qk>L-sNB@)yU@p;PFMM1W#!G~;`$tnkUeX?;77%X1Z9>w`_Xj<VYL zTezC~5>E;<u=$8}spm@6yQm9r8nWD!AH?fW%(%oB6{7zx;Y!)nIUG0~9dX>bhidFO zsYGpo9>xWU{eld^8oRhZjiR=gK&YY;VBj!)1r*xv&WuF^#Q_6IHi0?wI$%6-l$!^v z4(_HV5MnLM^4nh!J=9XLyEJrNgD{f@Hdza>=F#}v?WN(?3i~nlKQ0_M3IpOcSJWU^ zs6y~lfRn=P3>*Vt6SN#VEx?h>-45D5AbEf?z5?AI1x_38*-UcBOA><#xE;vs_K3;x z{*3aSo<Vk(b3;VQ94Pi=jc=)9z=nV$+*8<uoa4G9eqWE3nJ3wc5;b|iMM{DEO_JgZ zARfff7wPm!)Gr6GII^unN!+MfI9XMfe!`ySuX~~)rQ75!R+1PGfceWt5Lc)rvAqf1 zW-*Yuw>Rhk$qD$3T3H8B;2<KFi6nnZr%EC+mjHRFA}5XfEs1iE^TB2hNDWgBApU{v zT-;;OB&JUrP=eXK9{2~zV-M6@>x&j#i6?U3h~yoB@IvfR=tz*Vb`a5s2sEewn_u=j zM=sn?9Mt)#faE!4u+aoI02gDCkZz>n?QI*SaqNC%zpRy6%<j262~=0(ISBrF1Qh63 zDzFV&d|KfV^*Ps-c<U=3xhD_Di=DM%P*y&ab}jLfJrXBq(u3azU4f3?z@iA30Bf3c z=g&|slm2cp#CN&JVItm8S?<ctb>zneEzvi7YOEw-qtG9S86N075my!l%=>p~SP#yA zl9eKGOi=T{{*-oBrFL1S8>Li3`H0bDAQSEgPy_(Bw`Wgb76dGrj;QvOX>mbV{Xv?I zd1KTLd&bGvVu8i5YvDn`b!7EfjK3gQ)iuj)nucxA91)6+m_e;EMu4s4E>nS6+ds5M zrrE6w8}*&Kak(s9rB%5F_-07tbt4d`@TahA@5nb6iv}&=&qiandiiSdU&!uT5mijd z1KaWQHyq9d$UKPU{@aQHB+Vb{n{}2G@_4hkElc%pLq3lfT9GQjDBy&{po{Ti<}GG) zGU@Syo(`>fnw^O|KGd)z)=n@#$&RleR<THiw2yI@z`XxHnERasY_UsjIE#5z#gBEG zybj^hH6QkeJ*2#%Z8AF_MXZ?{CgK}`)IxIF!^mG!Kz&&vf4G82?{wEVOSxjF&BB>C z&L-qkeG6*XG4X^7gtDm{1=%W%s|57F-+sR4&OT*u>>{$3=1kALX;<Jl61xdtupgmb zBmo3qwW8eZ{jdpQx98o*3{cZ(LOt19<a2M`_!{QHU9iWYt_|JAs9oYp1&p+9(IdCV zhQAr=D*?wc>0d1MI_^ofD4Ooj>j&HRoIEytWP*9#Bu1mwa)k=$Lnp);CEhj?6RVOQ z_0p3Vc{E)O$|{0~ynF6MsTk_g9(i*Jbd1^+mNGsW!bMOXwLS=YnKQSS&cHT5L8uTD zRuQ?_uCFJk!Vm}HCnnkPpZEElKDmdg88X}5zaU;6w&dbu&iFJsb=X+tf#;nljZ?SY zd$bxwHsxHYaNr;)vk$LVBVr&jBp&(?39c$jx3J?5F|sRoc}s=b$|68OIQNqtm{ABZ zg%$)UaUz!NK;OA&Z?XV6VvASe*t6+B(Q9Ymu@SDB^}>;YeOdUY6b;ZDW?gQ-JqGts z>%f&UbL_Xe+2yPMv0mERo3>|a`p&aY>DFi>>q4z^JG%`@<Ta@xchQiq+^`bn>6|@O zl$d!m@hI2Lh>j!SUfZv0_quIl5W9Q)pUMPak9J?MNDw0+?ejD_c?8WS?)d-R$C#uW z+d)nO2|%5mOrdJr&7LbUj5HarC{Pvr5OtC&MtGlrgLVp{QMaE^1*mnAl>+P*Nud67 z;gm=+28qQm6>|EgD^jen^%?@>0kGF8r%6QE%Wh0n4Qd?{_uf{P=c~pV#Z0)qDL51b zpx{XA3#JC7TC)W2owmYey_etM^d_B-ZV6X47%z;}9iZ;zUgLrwJ73SiUtlb8L8;rI z_0<VV7)h-5N*JF+P*RXtK0MpxsC>vt70)>i$asVc2)2;clCjs}M83=ddEf>*%=Tnv ze1Tx+c+Li6#W}w&g)-v5uoH_i1SZp#N`j=l_9`-(>7bmn?q!P(gXp&Bx5W=_)9how ztV;nsx}N|%JW9a1VTs9t0k?Uhf%f($Z2NEz$mb^)aZ{s?g~DuUQ~ZVA+piTW1TB(J zQQ+yaP1-Q3IKTUf&%qfc8{&#2DRn66QTLsnWR_I6?#ecgMtr^3WQ^|RBe(u~b7;#D zh%VU#a<u;!N7r03Iw#VZd*EvR{m4twf=dt55H(O>-dz6lG1sa9SSCu{!|RRu2<)Xb z%O&FF7`ELN{~&jGmO~=dc;V1RkJQPghHk$L_M(3QIc+dn4<TT|neGR$b>VsQ9C&c5 z?Md3VTiM)G;Ikhq{MP4oM~?jUvHs^5>m;HCiXWvsBk124r~RDEh*RhuE$*03)bM^8 zQZE=iWyX6Gqr|UnF6<Aop<5B#bFdgAFc3_I04|cNpy9S&k@|2=PHdkV#a$lcx2^Dp zI<%KmT#)FO^Za>;VJQ9~Z1haG!fg<)gKe)-AV4z0EYTaxvvpu<KB;}mk?mY{CdA+% zmpm#i+7LF%`~y+;r!k+fNfi@d+y;EU<1A1>=%5+Y0C2D&);}<+Y89coGCJ4lZk@P^ ztaSK7<0n0nbA!ObXVopSGY+mcpq}bNLzd-c1MrrDQzkgt{Hd&VFS?s+371h%8Cp1V z&7-QTy1}9-1?-w{2p)LTrU4)wz<!HuAi!<`ms2KgK5fr()d=kE4%c&T8_U$E^hiWT zHYPEekVp@}X4YrO_u)IO;jUSB2cwWSCHoFKHR3E?!tsG|=h}o8h|6Dw#(QQFLAK?c z6gDKoTo%%H(4JefV>UKkKAq=|cbqU~@_&vQ2V`J^XktL!g&Y}K0D{shyD>TaE~(>I zqKE0iKAt|$s{;`B+>s>ertev>(m^i)f;`AL${GG{FzDKs(u_5@T-dHeC$j8#Zc4Tl zmZJY3gBw}Mg42w*BfzRV047FSa^^$5pt`$bT~99`VO=3uXoK2w(1pHx57z@6d_2bv z(Q8ZWl6VJuj&O0BP+GFe)@2}+a?4>f-f>Y(%t)hDc$sN5;1^^r3!KxgxknhGmLmwC zAnxvD7TO3#V#3%4^Q!Kp=&MyfZ@(O^5obD+hzf+<{$Xx|JGw2gc^r5&k$C&P+;=XO zcy}2lRHUu44H{gl;%v`)=iSJziOz6qp18vh{PoYWe{VWf=DRX&(oCSFp&{S?@mY1{ zJ}I<gRcjJAx<iaGWCLm5%XEu{mRtLPn}wR751P-D$Y5=b4Y}UFbf?3?2PHytl7F)4 z^N0?u_P<IQq-~Fpw&+5Oj#vf}#AoucsJb2&ifK**Q9J30T-VupQQ+YC4B9N?6fg(u zHqNz)Rid{d9iykNN1aB9KvshHdbjq@IKw{9#mhuLzuoUpW0lo|0OwX`{0XYJ|4N4n zvNk4+;BYxAI`q1<F@OdpF**MRTs{7W^b_cT^cVbHp9O3RxpMrl9TSFnDuya_D>`=N z7S}3ZhG;xB<o<QDG%~@DAZ-ZbKDp`6uHd`BX<n`=1X?ORy%+SeRGwjdI~XWUGR3CE zn?P>9+1mHcAhl&QTfBy&s>E2n@nB;-Qb6P^ECvE6O<?&ywa|s~5$G~9+a6J4mG!U= z7<I(@yqTBkm0P9nD_03%o!MZ>|5Y4J$>Tpcx94jghQD$ZN^qFma*_>KXo~j#3}lyF z-FA@$i1f&G@{hdsQ<ciL0E8pUI!<mwns#6M_zX3~Rq}t;K~VDcEoFncE0*-vin(<t zWwg&!R+labM$CwmkWt_7LiuM*&p^>OiqH%Wk)(O8yIvKjd#s!pibwKW#;o8MreQCV zm>vetlMCSWz0z@(=w>}?44WsOAvMfZZq0c(d0G6l=hlrBC=J~Ta_Uoteb;9u+i-Vx z<XFTOWZ)6_;U$yWKhjFHj-7qJ1rKrub0X94oo-3k;h^<1a$TqNJ98qZfL!jNWIB;5 z9&pEm7#tic0PDUzup}ykV4QvE#++_?D)G+#I}xrE_pe7HYYhzdP{4Z^{#8V7_wfWI zR};W&o%fQfeRve(8G6e*L*h;0!OTTHEk8_W&nrVqbpOWNpi%r^Rje4H2(fSME64&3 zD#%yVAjs8Y?o%D9ib11vi#sdNFK_S+_%j3vN%Iv97{>LKdj)JHp_wB#XDnpU^i65! zeCPCEa0w7wJ>x~$U^Wi44PSO{jB<o!=ZuKUH)|9W8!4}E>(B%(<c=xaP~ouKH@%Pv zm+ZLwklo^GfxOMQm`#1(7yI&Wqc45(j)jUyB<0=&xKN6AzWdOV-LZXz(Pl&aoGEX_ zDQ%()4MDF3hAQ+_(qc9?{A-6c?WX4q*thZT5@z3NY0Us+!}t>O_7oz)`_w9q<%hhe zXG))BUw9H`Of>dM4)o^++qlJfU^q%)^REbQ6hXwm^D^<&F*c5`BUqPTm?q+|KslgG z601@_zEc?cf@IGZU^8+u@o-&o-{5yzVPfy2VQ_e8v>yiQc?MpPWAnuV+6ArMV5fK7 zX?|AwBW(Dy-V5zCwx62GLv;d|pB)!@u%fj*sl;Z#>mHP{)(~xUp6Y8Xn=RX)e4|~8 z2hQ=p0m^*O?BILcdtRG%Kl!=f68E?E8-|QF?zfIzdqQ>SQblB9485_%DF;y#H8v)` zU|y<ar9=N;Jd7<MO=B0y)d5TP0%6<D@5|yILd$ITBR37VztgG^X=)gXngHGnhqx{7 zNzqJFrIuL=gw6X4Vucrk+Ppydh@SoCQ^4}Fjsy(hil3Ya@OB;TgpJoAwnvC5M>*^j z*_R0N!hrr@TasRn+Cqp9t*Rir?k`CB$<CjDCyOajKa8kB^k!B+9P$GYb)5W54j`TT zvS44{TY0xRXA5)lxG%`Q#Np3<uGky3+mZl>;c7Ens)Av$?SL}KeKy?)$I7Ppoa%AN zk)$*GX_?76{$is3%ZKUGT<KgF4DI4M^v>7`fEidt<?&Hs=lS>xE^yX_&#z@YLs{bm z8kFpjbUuy_-nQ+`XX&GhjVKfviXisB%~dD5B>B$ioY9O|yC+oY75~=h=Z!_9L~(%a zKdyOeJ<Q%|<xmmZ6*i8Kl%L{0BMLU6M{?<gX6Q4UPi<}t>Gkk9mqdAi%Pma-`r_sn z&m|v~F%40<gTv)zF$6o>{Ph-yQ_(k~HxMvs4>SH{Pl3IRCAC`wt+^eyB@&Td?mM?Q zDjKv-`!Sb`EFJCtl~;5+uu|?rNr;$awc}3jk=4(_{ydk>&L}+Xcs+l--O(!YT{uiK zqxv-NOOovP+zHAea!;w$eGR!%wZnal@55z|vJS%4J00A5zZFM3Es%Kee$@EvxmhKC zZxz$>@9y5B8K=avj;oKoNUqUY+UKpuXycW~)z_^Q?9{3=0=@QqpZo7t*dwAS?NY_R zAcY{Kz?qx8v$YL4*T4AGgZF{0N}2c_Aa}6lC{{4jgIEVMmV@xbmg*wW+iX=2LKiF{ zgij5GCtYEtiZbBWyB(?_qDg28+$Y3m*oOV|Jn0!SL-cGnVt})hg;2!-92fSJnHhUt z(;<5htBlv*j#_RpE3YB&6zNnS0bf&AW$tmV_Bek4%0+yh@CgKqzH2(IQIz{wIooUI z_Z~fzkQ6IF9t;|&izB9MU^@%l3M4ctHwxfAqN{7eVO4?m>UDy=EKPBMLG0wXUHwWh z1!dXSMM>r@DsToos>B6uJOO=(wl(BtW3C217AG&M{mk(Ji{>$@_~hc@7=?4DP+9_$ zEkW+bRJVKlmcD^`WCI-+|5S$070f9`w$kX&iu9qqef`qnHdpWy%X6k3eSQin1VV>K zUYu@Kg4I*b<|YAtHr0o#3a-^Cc9h+W!;&wzkK&#7#T107LFe?r_v5L0{9WU(K|}@$ zeJp=GeLh<#UZlQc{~SH%iVOo@bUq^DA+&Co7q=hXhC4@-&R!>`Gk7WO+F@1A01CA= z*~TR1L`6a0W@MrE7cn7CPXqL24iBfCS?i9R%E5q6|5nkji}x(+m$=5gCc`QV!;cRb zA?Gcs;Q%hB2TS+P(!?w7T4zdr*|TKzOjE9QUVxvZfZ`{1oqz0srBcV-|CEc<$G8`| zs=hCamAu2_Q$x?*phbHXGKxF1L+f)7WB%CQLy<3*^Nx9=BcIhN1^*nx7{@{hhIaG; z^SBuMQlHRyQ$PP?82V`4!-zU$-_BS`aHXNk5I2Sac)=MKVq-T-p(oDoOPu;7vvCvK z?~Pe%zK%VIxu=>g*?n)LME8o!+3@{}<LQzVE7M;Pj}ZrPR_@NUUo<H-O>AHAylkdk z>B-BfAaH4H07iKSLN3^Yq5~)^D80srV<^8AI`d6D^~zs6H0SYWETqPn0dz!Z2hKRd z$gVFZNo=$#<_Og_!F^0h1n5=BNYx2|+Kj9&bGU^K8W~>L_@vuiJ=uyruOJHh%+HGP zY!LG#97KR_bqdW_tZRh@sn^^1W>H*<r*Wp(Y*%Yvkzwsq#kMtFHpMGnA3qqUl3L4M zkR6p{evG1$8t&t%^{BotK6*FrFoX5+og_qMC&el<LXpBNZZ!3yB$TVK&Bo=&b2dKZ zuZbhw!nh+F$W^>BenoTv(Pw%s54(e=QpffunVzitcx^DtD(0fo9AXgGTBVmnZ&=0m zNZ7L7T~l$&BX(Hb??XLA@ZOR2#o#h$4DjY@6_@6<%Zq)=J*sG4m*qEsdmBGF+qh`3 zE>p%0AUpFiU%9D8#>8{o;2LbZf6lBs#?>lK*)!GHbV%yG4rkOD2hY$Ir=PSb5Ig3O zl9C~}a%5nRi2&@|oQn<)C80P%aJOC_S1C7F$OdP?v=aEsYa%&=*W+yEw^?2{BUrJI zH-w9d(31l$%0k@d-|1%2)9^eeh|3x9r$L_;HOHIUt-&LtTMg{Ewglytpf4mTx-`90 z2HGA8_Hg(OvkBepvpCGbd1LlE+|b~{n;ZR?ZPZfKX@+FQN*Eqt@pjqo=DxDUYrUko z{oyLV+WBMeEt%j~tf=f(PU_0A^D?YW`N>*hl^0>t+uA!5dbIVP2cbud-qNi+Hd_sz z%U#>~B<<?xc}SP8dVSk4VF1xki(E!dEAhb4Z_Ge6{|REVH<`c^g4{w!5O$=3fTJBg znl6>XT^J`G<|Ol%&VH^%;;l^~4fhM84(=SmKfVK_{--fJ186z;XXqPq%cGuzhQ|~l zNrRtS>Dr{e??H)UM~t2ax(m4<lx!5J;)FS1tD{i-2Am0W6}(lf%_-b3&RKIyjxy~? zc-i#4HXt>B2LS<?zDh;nF>JivaeEO@?eLujG!*%Vb52Ir%X7bjTTSDW7LQ`<6_KFr zqXZD~hEF9si?~1t@Y#?wC5&uzBR3sdWt!BXQ&uTvmyhbmx6HV>$hod(fMyMaV1~1> z<w!jrpgxbff^d`RR`6Up6*FkBr@cjpCTy`rjAGsPU8pr=6i_;Q=qW`Tw7Y~nY4I%i zNPE{g6j9ePT$<-CdHu{vGmSjWI4oOp4{fW-a~<~#3L0qGfo!yP#PG2aV8@)W-BSXS z^sI7Tt*c;HNXxAI+gDKdA7;YmoMYCBt~=#!aQ~^Z)SUZPgQxc-MAA6!QdP7Qb(arf z>nmGP9+ny<^YM<|fl*+aZRSmo`>W_@s?MW#=F3~(icIMOYXKFPd;JYmh8BLmKY^AA z5Rf*Ic5#SR>z__&FtAQye$*wU!N;MAH0WGn7xnh~7Ogf&G#8qVpJAK`yPu0vmO)6S zma3ThmW`e3rvCd&X?fEXO7ZZ9qTz6U+0s(W{qXXBjrWb{?7p*<E$n(9+uEy2@oAud zH?6_)08U1Dq3HvnHbcz6Ea2K3!SD)0>vlONuO#L-1R=sVRG~!8Cm~IQ8Tzt}v`)@! zj^qwf@`{2QufK(*O{)5Mknz_GS92%c>*S0z<W9FdT=B8Q7gp`_y8jEJhB1gwZ@TMw zD6}QB?^QQ1TFo&nmkqezt7UN%Z|5?`m_rrCio<Q!9&jZYD(PEVZ~8p+Z}&Sd!Q@*F z<-uv*ERRVGdjD9)ylJC}UHaCV)Hj?m{w2;EU8Q2lZQBzYSyrPx`82F5^n9)s_SKH1 zj~T}E`I7h=>`-&6k>EEmF$X8<B>6j=QgcKs^m@RGwu@8-SSif?^UG;FhoZU{lX+e# z&bIAbRXeitowgal=u3-J$3zbbf01Bn%9K?0?WPZ036eu7B1FI^M*l+DYi}P1$83Mf zPyHJ_==HXMO2_eBhBiWpcFZl9z74d!QpN<I3xm%;x;;14Z_v5V&S{>L+jxeq0VMkz z!T<~hmMSKTzFA;EaYyk;v56}h?hjl)DObyTcUcA{(qrNp5*%<`qY8A>rQs|tH7svL zUdXmlE$cgmA^?gp&Y&|}+*ib+MXKe^aj_>G1Y<p6h0}69ozT3vpi>AN;HyWO;*+Fy z^f~(8Kgd_VLib$j=U<4*T4V~ur)wPPuXq&en1f{Usvq)}D+;@_lA!!GvYI9j^qBc0 zv6i<8UE6#?^|_C^p$#a;{!DE+WyoScB#S#OzNc*pJ{b%tLnJjNd*wG6eJo3u47gIb zWd-p;-Bof;JQEtdXpmDSJSQz3cfmSjRM%wXG{(%NasRECB{Iz&LgzZVv*)cnx&?|K zOF6@WM#68lL=4934=67v?IW<Y%zAowNE<%9o02_S7|d4kc#M{3BD$67!R%r%q{A|# z$0R`AHN#7Ha@4zK=r->QpW2%Nu%$?BX9<$)NbG~PW)Ny_b2z?UR&rpmzB}|-iDHmY zK}2w+$|EifOU6Of<CQyio^r-nF`xSeNvtS$TgwtHl~>8O{HdZC={#j5-8<o{&M2w| zQ-%5gSkS3WjVk2zDDU{L3t>$!TPv=;h*F$GYR~GxH>FL!8A|`y`cZe`EBk30iU;~% z4$TKPjH|h6ntR;uNaeqERPj<1V<DkZFB0o$66JdT9^cjS%mN1LQ&(hhwp20XI$6ob z!6nW1qt^MIsq*-Ko&-fJ>P{6Sme9><uG|a63}gy$4J7F$a-~RAziRRlj+rOA1pjCx z-GT9SVhhv1bu3#NS=yEoCupei&p9?dwR-~H0dSkXP=5Uw&KFMC)<P_#xm1T(;g1J7 zP5YBT_nm(;Y&yNdAsstcN56@2tvpUU;@|oJfITJbQNYoldGdj1LKQRNaZw)mz^Pia z0jxZZ!}#~BsIUrO<g#xJd7Oz-V)wKT+&rXZe*s0o`z8A8zPSOHfk;3LQ;=X}y(}0O z*fo-Uy8)8M0`CBKAFwyXUc?kZdnTnWdEQ4l$mFR<OcJjE169Q&p{Qa{jx+=6Uq_co z#^`Oo54h%iS*1+z`ppIro=^ga*Z(o0qRikL@o$OL1By&#<wBE=0+g3ZDbqq%RY6xJ z#3~*NYDlS=c0)@Bu-!k~yJ7gMo&~7K4h|;qaCL@qLl)eaxv<C@OcQ%Rmgc?uh#?Vv zMjJCTZBMy@fv;@>#nT?Lg4^A+IAM0g>ZAlHW(8y!Ya{r8NJmv5#GuD*{*z_h89R?d z526QH!v$Mq&Ws#b=hN20XCv-}cng(u74gu^HSS9<UbyQ|N1)*il$r|CF2gW>g?DpU z+8hac)jBCUe5@)2G?;M2Zhj$f2Gt-B;$+gif_c1Z?WAgO3rRQc?>ngd36xOh#Vzt- zT*rsX9*rP^6Zr#l+pB87ZMNJkQl2fUkhbqxc%69gyYF$F7FIObtbz3`$YuAZLQv?w zXEw7gMRE`Z6;C6-tj>V`3v4M~J_AP$%7W$dZAu{&$cJ0MAYTY_7~wC>hjW9)+#j^2 zZqkgH*J5w?PRq`NMA9lDoH#%h&t)I7<(>+0N;F%X_<HQPpcz_uxy~E5Aciie<+cgF zUnS}l{#8Rv`fF47N%4cZFST{g{iFcBk^o4Eba|Y1_;5Xn{?z)(aUFSFdeeF}En73r z9NcvLu+3uz&p_PCP3lKs@0H%$h0dRPcHVD*E5RnT_fnk!;WT!Ayp7f5W}Qp_xZ(#+ ze_Upp4>*}np9BpB4h_#Vqk~jmm<*{Oj7*Vr$hxA<-!%p7QtslJOdr9{b<tsFtS?Vo zg}<({=TQhlVm!RneVNG;UOqTfB-W|c<0*0O$c?~Lwc{YqZWVN!kyqZa#oa{{VjM>0 z9L_!nHrX<`lfN(+>)LSZ^$zpca7`|ySHLJC8hxuusBcEP?~eLZ-*XnXYCY;kVgEPC z`l@sIL?2ggG=2S9ukMb^`JGEGWx>pav6QFQ1^DKnV~*kSDq|oYZw|`pqwOLXyJ7a= z5X-abnPi2hC#aT?{=@V*<`Hc=dl<tJY@9<*pM89>$txC@`)1PLnH7sLC3O*$mOe6A z{|xNK?PICklTR*3eBzSTg&mlxq{9?1f94m<!}vzRPbStoAIpe-%2&N{tQ;CXT*Lt7 zl~;BgGaaTq9@uF>(97QUYE@}Q>(L2{#3L0I`BfcLA0vDk)cpmx8cxN#Vr`_F1bvUS zyHllD*e!Y$%OpC~MykiSe1QZE_s<%N5ri34b^ZG7DugwpO8h5|e0WjHpz3?BPTliS z&QQalL{r2C>1UN6o;a?wHNQAPX|AD<k(!LRXE(Y0EOs+;na253a6`Rw!_`Nrd1Iz< zQy$~O-tiqR?mi<v&oh>hCHH4UqWfD|uh3JbhdmTGlVgdiKeLvJ=)Vvuqci7v>OrwO z+mi=d$yTNQiCalbi}LzonwOQ+Km<d!`0}fR=M>NWRJ5^Jc+h6w*yZk^{#s0^`D!U0 z>qzQmv#j9+ulrWG=&Mp}ufqdD4vvSKwNZUvTlR&Wm|%(G;j;}G*NVRvY=y?9jCrhZ zepA#jlWofYVbEdroRVCN<{Wc7F_sgx{n}s8G*Fd%dcgM&Jhl4}tp2S~__nE$R+&Um zWY3G1C}y@+D2=(655}95c@?6Ec@6pUt^^$7L82CNhFBR+uCd4hpdUMGi?>C>L`-cw zKtt}%(8GJx&V55NbZZlEQ8ES>rN2;{-_z6D1u>U?LGGD;%M%TI%X=r(xzF$PiR?D4 z@)GEuwhh~v0NQ^)aM%2T0KMw-8no2i%}R3jr~c}tz?jhf>h+CENgv1sPa>@K==lOL z*^>xRY0ncwmX!n)AW0FP9aF(XJ#$cg(w|V<)atsntwXDzavxj?Ji(O!j5sU=y4?Ml z!S{WN3_z!s0l%skuFhS*O*s|y<mX(;+2?u@61N$66LEMEORN@vj+_2!35w!rCUr3! zIKL&t0Q4J(f9(E)F6`Nnp6@g0&zQn-ih;*8vWvi*>JmIaG+fIB1aP5%`dM_qAfU|} zVzViUA%Q$8sjLxq-1+9%*7Bhz!rw$#S2*7I##n)SCTwdZj#w98q5`7hHO@AmG6%SO zLCH61U>#bye-e}6PFV4|8&e@aKi_vQ{13{0$>~=C%Ty`BJ6TQ|p-2<Sq#uJj9K8~A zyr9A~LM%b8S|Id0?X4tiPn{xXNo>!>ZtIe8$Es%o(1$Ir?d~79n|@JI)_jgP3QkL! z9)fIUexh^bSKj7g>lIk8`Zc?{Ve0nX9C!T)0d~j&);GLyNjmmq)||9Kob>!DI2BiR zkAe<bNuV@W(p+)bv_kvPYzflZ;d5P&%ULv&YH7<O=m@MozTtx5)3@lJ+K2<QiAU80 z_Lr~-aed~b_TR^{ti;!_U<I1Y+`zxhDbl9KnW0;%l2cM*HFtU)3<SrU@1c94Un72Q zNE|SkL$NAS+i}?O+8C8<KzOo_U-NmmI97__Aq-SWq0j>aUaZ|HpTw7UV`sx$_aQD& zRf|9%(1&R413pR^;TnlUbz^)IdT;D4oJ&p9<D<0qNk5$C1sMn9%TE(eV;_x~BALAc zE|&(YS&QUO9?oY#>uu72`vVKsD#y#!u#+H;&1uzOl<wE^O7f05Id$i$b@c)zq3D|( z5`E)=O<uSJC+<W+r?>#;YKep*_Q+TnG!#+N7Fu<3reze)$Z5N6iV^#i9M&$eslK+s zN&z@HujKhVjAb43GYe6FUybHGd8?llkrr^^E3Lj(G|#9tR_nw6<K-o}BUYk!MnIsX z+P4)^NGL#uYwF_^MrXt|*FXcZoQu-q9%oAC;LYpIbVK$WtCk8ASFK~-q~EC5vZeZ7 zsXm7H-uQ{#d26IR>g{mWG?FhX&*ZTFZC&FDc@MLmp9mgbb}Vy!6-#>+3#@j>oTfun zW%zb}>g?&aH=Kk+fpiV)V^9mzn8Uvy8xJv>Js}H{qGDH9;FiZY%1+702%owl_lEgv z+3+((0QdZ?(lx_J6Cg1pD5f~oy?gdXX#53@H{^^G)C<RnH6KA7@S?hoRYD$GESlF; zQ?v3bcYJQ_^cnJiYpbdVV^fQuo`W&_IA(ak^qyrE%V=^o?ldD~g7P?FVYhLz*u@9v z{`y#c$sY@oc3F1^1nf@pIX_PO8DI(po)Ehb$FM|^h`Jt&gQoP6_wqC+G$O?ZM#H_w zBWnDhWAKo9hui%-(h42T$tKn8rkrO@1s}BCyWciy7FLR(dF3nFpDnx8p;h&wO;9^h zK&@1_Y$Q>J*-ZbZqEK<>2T|kM8oB73#oyJBQtM<X%Z!)xrD3Fww-CzQx;GCuIZj`a zJY4bNpx_xwjw9X&VFw`5H@YgdUG1g36@)H_4_~M5Y2)dQrM7S$h9Fzt7j#u>!r2qj zG}GF+O2aJL)%aYhl>$SSW?-J%uam^Ai=K*Vp8uf2hbgZORX?S75~?LKy)n6-GGJ0y zBjm6+5q_P+AhhxB=eA2xpz<+uEcdYes%bAX<2`350cxb9-2T59Hf@d<{Op!m%FAdL zOMR6#YshmXQTmD8-ITta2Mx4S=W&^@k>l<~T`fiU?r8bwKDGLj+}BqH<YXC_SNUxV zusvx;?}hj%ZyYbHWwPcy^71OhW@E#+5|833a~tzd@wGB0H!f>k+tL2Y<orU8Nol($ z>UTvZbo_L*61S*PYlZ%cvlm8V;+<(j*K@qELbKtckD&7S4kb=EgX!H<v@N-Yg*ePY zSLlkt-N21-F{_&!`>y}$^^_+2rS9=&Yu(dVG01ju)k!ny!Y>Nc;@a?K5LWoz_mZSz z-ytu@)#f7{lrPj4FdeE_>tERbp<8M;U@FLL7P<XY;*e(nVT%mdJP6s%h?=qmP|tZ? zge}bfbxty<g%Jv&B3@=Zz#WRN4vE_Wj>1O=AOobD7H~Hw>Gd1p`!TQm?R}61(D-lD z9>9@NNYQrP6iHIu#0wy5ix5Esjv?j>hzjGqk$5_IdXDc<b>*>!8)Yx9<;W-Hg&x$F zoyPY?lN2^Z8Tp0i1Gobk|6{Y?$C(AyMkcWD=azZnw4_Ys2)gqs@lO74i{^SrR&846 znuj$QzZU5(EB+()=T_EREj0`0ZM|XA2uX|~yOH@lL3&b2OH7|3#~AY#!vLb^DkKdA zQE83$K=16r@PMKanehnhP5_|{Ic<L2^><Cj|EGZVIdTYCNIKBI<L#E)6T^+2F?_?g zhhQ_!;<vaVBQqfQB}xY1S}L;a0RHa~Y?F2+iI!LaQ3odjx%q@3Trz~M|LnR75hW{X zanbL_Y7msbU8QQc)lZW6(Wy#j5Rd<jTLV8_{JW6npBKLayFuq}#@$L5TdH@&2(f6r z<qFL&NO3bR%q6A^+e}az-snX{=IHtzAgfsUAVnUFR^p2RaLfnipqNn@-U$K99q7%w z--1g5VDBE<-x0V%2(dP1_!1!lF~~Z14>lKv|DlycS(@Mqu$3&=2T=(gUA6Pb6|Qn{ zvRcH=P-cTK@_CXMtYi(7Bc>@)yZ(+ZhQijrfL0b#9eaCOa}tA@j#!T60X)lg&n2@> ze_wpt4_LOFB*Z{F6!_SgVDn%o0h2CL+obQbqQt}mfF6Np^cbES22u3-(q*z2zXJi_ zIQ7Dz0q>0>Jhp#G{$@+{6p#<{yK=>l;%{g$Y9c|Ok@tDdyg(LS?SvTK8g<-)RR4ld z0wRSuuamVSQsQO>D{$rC6GQF&kH*au=CuBZ$$0_=xG);R$X<X4o|sIa8itrSh+Idb zw&@MU%(cnil&EdJ3<;OMKZ1gET>G{?0ahixKtO%AJ&k=T!VC$@o|fy2Amtby1WLFW zZ}*)zEUkVvo#Hb;(gd+F2r31mSD@pdiU;8U97?jVqXen8x$=9Pub-4$zd#+C|Mqzc zATMG;1GO~^okG+^>^=c9xn3%Z(CCQm9$|N=oupBPnUvv6fKOh20vCk+p#p*SdmvX^ zwHpy(cd+3?U6aA^+pNc4__WIHSc4zS>>OSuJXGC6qLX)@fCzM;2W-@$jPI-6oP(@v z5xlZ37b~>4riCY9^<b+A{Xl^xy7*qg*(X-Gyv}*!;81Na#3S)}d={{35dJwh|0@XK z+OXHj9#tU5?UJ(#MVvV)ZX#h(tZ&vp*y_K3)vmyPqvIm_gQD?%E~?UPun1S-%N4Zz zcMz|DOA?kR4(<r=e?Ol{qS~Ey&TFyTedoKS!>@htbD||KU2f-o2jM}}7BeP!_X#X+ zdfi;wyX7K0J%O@u5_B?Ym;{-g|MJo7!NYS35?UG>e&0SvU1gG0T)VCWk`RkQaOn;5 z1*n>VksePZF+?1y>8r%F-MbhVVaHtEs=oNTl~4<=eTk6-8yrY9Vcy-iLY#Dvs@?lC zxd1=fxVCHC<K19440orwXTmADW<uF%@uoNRpZMqF7#Ow<gg1^4<JKZpVWUK*xedH2 zZE64tkHBW5+A)>a`L5zs=ZC{;x~?678+m>~c3FVL46Hg-;_jyK5W6Fnoh+nv)cDjI zvRze4R3@kF9@d!cFfP*5KhyM?DhVwAU-$x^*tymm@(Iv*kh1CMT?Q>D?RJoCKwADD z4)#{52)Wi_Rru!2UBRe;a4qky-2cuPaDiH<s$5sTy1WCK{O!<yH_`o)*Oj=2f5stJ z+hN~+K?0$qM<B&%PdjG_u4cHQo90!P3g_k{Ogc%tYYVnxcbE+LYHIea4fsDKhCEU% zyspHFBz<kqhpDqUv|oR@5xiuhoAD-4eobJzd-K1GG2c+8qbppjT;OSxkd7K>)4qp9 zZnh!O`Cqv?!97z4vNAF9kQoDbmPF@>-8ln>N$4!B2+7>av2vpq%=$_vTMfG!v?~zc zXXIZW{*imE!>uuE+Tc`tzK(N~Fj26K$>>4$_|ESPPL*nI)6VtY#SgWtK_k<G8*SO( zR!m|wz*)4rTxgQW1N}K><-YnL-eb#Wtu03ZP*;jfHpm`9eV^jd1SvR$!@UFfUpeDO ztoC`dWrO6VfBCk-ng*BKqLy55@71JxPvlqLBTP;JugoqP$O%Fz*P=T#*9y1&@kO0Q UB$kTnNQ4RS3GNYY=3l-42atUL`Tzg` literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/40kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/40kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..7f9fb606bb2086172633cf0695103f1dfd333a0f GIT binary patch literal 120387 zcmdqJc|6qX|3CbeeNU3CQ&EXfvL_=QNs>y)Ua4$pvSsfrC8bb=5+T{LrR>|-LP>U$ zb*$Ml_A$$Q?#nsf@8^tjKIh!`@4o-L^~mFW&6w-DUa#x*dcM|cXg_E}(ALu@^-e+z z3=Gg^@DHN(K_{RsV93C*@q5e04-@0YZ)PSYMkW?!7M9=tv$C_Xu(GqVu&{Bmv2$$v zfF~|a4z7*C#w34ybPF>hBQpmp3+wNH@_+P;Rt52~Z82fwVPx0?ZQ)~J<YS=KK`01f zVE%o34AB4lFl=FDVrF3l+u#I$P_PwjpOF!4ni=dE{Ix%LA7bKT-nRSjaTfmbS6KJB zY*)DVJc&(0JFi;cLK{Ky$W_-sc8(o_JB5Vz?%OYQKw42rSw&S%{lsrNCv{Khoi@5? zY+`!J%-r_c^&58f4vuc_9(O#wynXIJ2znU&=y6Cy<cp~2n3u0&-zL9HNli=7c>nQJ zenDYTaY<=SZQbYkhQ=>n+dDeDx^X{xdWT0w$Hsq7OioQNEG{jttgaE)NgH%AK#YHo z1%CfQ*k9=419WZKI0M!Vx)`>2g8z(sOw79vvurzlp7n|g{~m>VY}>V;C*@VMOB}gC z5V-2v#<4?Ead_{-25G-j_Wz8q!2eg2{fDqW>FR~J7#YCfG4erZh{9M#gThPTnPgZ! z>>b^60LPpn?>eIejN5H#btjgUaxWV@^DL3`#d#gb^{zY(de#Kvl(I@Y7huXm3#26b zdMks~{(CfN^gB$NMn}1Mw0oftjR_i*le~V8WqkX2t(|vO!CLw-X%gRPs$#W23_aS8 zM@m%|1)5tK%qw}ooDI~Em?<;k%%S;pF1T+W@`9nOO=mlUVI69bxdcoFcbW=Xr9DEA zak|kUOB$4(BNxCC-GHF4fHyNK)6#!FPcoLh4UvL!I7SgoNgCuwgVg7p0*k>89;5N- z?*T$O+t0B&CDEWp@jj$Dq{vtiz0TMN<M>P_p&b3sG-y!-CjG>IE$tmEx1mA1i@*v_ zlypXg5UE6-m}=C*s0#HC5?DCH|L5~0lqD}pgBmJ|$a9pSTit?T@aSM4brsPLQ2Q$N zHbALd2+Xvxb&K_o>C7mC9VMuR>Vo+x^FDD)hSw8B%M<;J_owvSg#|%Mz%RHT_3a$% z#zvWXF_Z_+G-#$2K5W%>yOe$eZ3jnk`v{zkSqoK;S0Q!NAg>O4D5p;cFjS|AdfR5) z(%??7JS9*TI}=EQq@jWh(j`Xl>pXhM2t2vxlau~u?4oESwT=e0>f8Vai4KIvMC7TS zXcAk_)l!%Va7o#Q^b20*(-Khx%UveUP>qYoEmWEKoF@%7)7jWTc*=4P6389Gu5+TP zx6$8BbexFth;|DgmUn48L+8dho~XkwZUIN&0Wa^i^thwB5A0B&ft*Q$k~l`wp^W9+ zbq*kLHSnZ%BK;uXXe{6!#}H~hA=`7M3Y?!gbQ-*J)L#NQu8d##mC$G$oBa-M+}DRx zbgXlH(qeWMmjRP6<A2*A$z!F_D;GJ@;m=Qlj&Em(-=P2eP{KO19u2Z#1+SU^$oic~ zX+shbP2%YO3<=yD%`I_SfvM3&GmH&3uDEF$M3#lzIsx@Jz4jy8A7LDj$kyo6kZ}r_ zcDEUNrk@5)>RahR0tqAG>rns3YA4KFvuMzExRGUaGJz!A%8CMOGl!xO?QZPKVghMv z&PcI8{U|^+GgQVXVnk1(!|uA>-b>nbd~YfaB>W&1QMdep=WF4hJJAUXQ-V}CoAC?h zSb3@8nQ*Jz1VT|Enx21W-DB?Xtk23?XZxc74cAiwFGyQ`OoFcT5*h2?D0k1Z2KlLY z`0a^Y3uW>)CcSyVkU`B%0YsebLugPgv2D``w>R6~yd_wPwY^|Y!B_ufOAB}1^-FhI z-k)Px%}koH-rF5ck%-mlPI_6d`I%8a&V!uT?TicdJAVDBg|)ru^HagxqS4>8G!sMC z=702=weD)Ywfs0l7nZEoxglC^o6g#sdAF6c7VLo)&?=Q&Fp%8(qBNHOnS};dSaBjR z3)0YqofHJRa#w^R<5rVZdObgH`ljrwI03WoH7C`dc8|OLjwi+FnOBHAL&>JS|Ai7> z9mxHSw9I>pnpj)TXx+VatlsCth*OtfI<`6zQHZ7-y5HufQ*t5?ii|R$L5Wr^R3e6u z&C6|JIn^7}>%r+6h&~vua9yfo`Ag2*j}!nqyNqa%l_{x}xn<5u9tpgIU!%hH;dIZ% zK2nSyy5(>FS}vK(mK%xIJtOIIO6cXp2QjA@dLpH500K5T;;BH2oId?!3mLMC6=#p8 zk42u1H@?RFD(N!RV)Xe=lo+1kqYpIf^|~+=PBsOPiSb2X0-J^8O`{y~5a<`Wz#U6s z?}PCxG)Q<XwcSJa)qrAOAm=u=pb{aH@#%R0Fr$O$HP*#M9vOQ2lj#RJBOy>y3J|oZ zRtqcZTG7Wlc|{|Fu4_Kv|7^JF3~+mMH|Uu_%7int#2Qv}Vt}F@#gGx~sO8$DxmyL? z=W}k#zI(GLgy~t*bx9s?Q4<}H%56YvCE@v^r9>Vl`epyNhdRQieXkrO&0jyc<DihK z_TyB;Ic^6U<TwQ{^B2+}><pq5G#XAs?jrzjj4r)k=!fawiyHZ;bn1%1p(hbfKYuR4 z7wxiDow6Lqc!^M*TgaJId&d3$y82IzBhD^qj{8Q>-<um<e6+Ox!jrf#1t)kD*WX(! z0BTgIg*IbOFA{l1H^152HJ<V_>R5Js|Anv9TXeVIdsQL^jp25ima70bX@b|n7Zn+J zS2eR~kXBg&nSdYGr5{**-p){eX)5-G%7<p<c=flZv%a-{fEd5*7wFo=1;x1&h{k?k zym*0d#17jt79(BlK*aWg(}r;r`%NRK;I{#?dhe#QB^0J&n0Bb{*+GLiFq@XmM^DF4 z+s^()K6BE}ROS_QBo>uaJXG7Z*ECE|>$>XXaSdVYr8_n}6wIiz`KloY@y4(9J@MsV zc88A}y?Lc!*BhX;NhmiB#+3X;Oj_l~+6yYwoh)94Nd|g-{g{ySzLTLM!(Mp)u}2Yx z$G*rXK&n{TWKQljgmxEhE+!xq4o57kCSzQFho5h3nnNKZkyW+se75qvF3Dw*o<HrP zp4_(HJwM3<t2a^;J@C9vl?r-_Ldh>{Z%LHAk%+SU@=JZ_@{ItEBlHrGJ<qA(bNxwe z#;L+z?a>$G3%4CotDdtk{zk+j+J|Tmj+gqfm1T`y%5~`nmdCa;v;iZu?|D_J9ZBz` z^9X*TFAfM@YqvZ-f6WnQ@*4U#q@cBR6S$kiJd~a2@L(zKyyENiP3O1BoX_8Ng^tan zW+echqEQsac_1eP<mqKxk$#|5+omOUr^M62_g%Bob&u`s#Uc_RTHo-8G#I{&lqAgh zTOjv5(QCulnlwTKCD<7OVwV^@YtI<G38S3RXF3zHf!@pOZQHKfc|HnA+^V-<lw<Zi zw?1;b2(|Ky29ekknKlX4-$m>wJwBGOv@2b$3so4+r4TTL_g(n3e$;7b1f92nAu$7! zihl@XaP#PwR3eAE2Q{=Xfw|)I^5Mp3?@Kij1$Mcz?Z0odiReZrn?=D=VB3O`8=2== zT{Z)h+K9-}GOD>nrij_T$ANPZ+YhF3FjR|rWWAr&kOj!T6Fp=@;!EVQp%;X|0Z~1n z{P|R@Z}o;`bnIY1$|QN2YiM-{F;3pJS~qJb4I0}oNc9b;vS$hhY~sO3jY~Y~0JVA& zrZmm`X^`Fe>cr0PN5X;^b9_p9x6q&_9EFhv-ALqu=}sz~?zt>PiZPZ@&OcRpzu)m( zLHUhsNfTB90F!(Pu=K#D^Kc9fg~zrgtPrpyPE*;xK(n#ZOr`~OpOe1G%b!s-b0G&9 zk6gK@${1O-uSB|)kV^?pB%zUjPKJNy$!Pw7%K4&B=U@9jypqt1iXYswCE&PZgsMR2 zW^8iAE^=-hj{|y{-|`sb`KN1h@lL|R%>Q^f3^phH7-CLD4iA*t|3n|YcEyW7_cdN= zso4!nh$d#%l+N|P5y8zL)c>;d+N?*#-$e_hg>>TCSFqw!g|YY`#k!KRkNx{Y*|wG6 zttIA7*(eN}Sv%n5?O-QKh5FkIUxUmHi<L62EO0jX+(`GxMD1|o8#r>yyRyA5Z|%#( zLhf~<{Ak6|(VR~-h^^=|FOx%WQ0LZH$z4plMdxOJ)WeM7j!+#nF26#XTjb&bTfsA3 zOq#(*?O>)NQ6HT8_^T$B3*Nce**9;_I-7j`-maRY)0=lPKuY|jz)!T$Wdg3Y>5-rA zJEDwX?Bc4nu+uX$iOWZxi@PNFK#NrL@Y<6V10Kvav&nX)I7Wrjb@Jkg;)cVPf*^kS z#Y_4L$NSvKT?ilHDX^7$<&iCIak|W$O}32%fBfDvwD1yIlyNm31YXg0>#Zze+b@%Z z5BYOLx9Gf`9Ji{WCr_S+5B=`?Y@zpRx>K$b%lY5N@vb{!y93nJrK*<|!3<E@Fn*oe z0$5op_Z^R@w+_Mr!B3a%bE9>N-qasRt==!!7WrL`QFY3SKu{D^#;M15wwYCP%-ekW z_1b6HrAX4F#RnRHe-ukxjzLOP7L_`!i7cuo3c|8(@M$&-+%lDY-Vr%tG>zxpdR(^L z)R{l~zOtEu<n5rBTybH?LLsjd0h}YuyZrLj3cp>(*TQI?x4IE{g~h}n=!eD|V!9G0 z*kwvNQh(n^Yx}N2)$TrqD3>pigtI=ETUifV&0#6N4G2)sYCsB|)5E$EqI`A&k)QBJ ztXcowxY-Xi_xcTbJmbBW=EDGv8Na;%6;1(2!c163^Csn#)o6uo(+D5MOlS#T1c8B@ zHDGl3Bzh)%Md`7{T@@z$2@nw<gfp_vpiXEp|Hr#<Vr6aZUb}a1TmKl$L4(Yp$@I4& z(AR|+%02AdM;atync{KxFw<l|@A^$_BksWcNqZ=BPy{#=<5+UTx^VLSNyoK^)kt5_ zC~?C}=s6E|&I4juaS(FgKtR)KaJygt4<gYAG-w6HvOv4`@g^m12?1xn6OeLr67G^G zzl}F|LcKtPN)L2Grfpcpy{%(Jmusamx{JRAj~{-neAkcsv(h!^4tgiCsHU`en1Fkf zd(-dBYp;UhYuqh<!q8f7Z|3m6iqS{18v4Vs2jp^Ywnh9>eY9kz{*-s5LBk_A_E)xC zR+^JVlV`|9Rj;uN90}UoP7W}ihIg`~-K7pcvvgh8=8|!;zSu-R|9v7ZpR#=+_4&fQ zapZC0t061p)zz<j>W+`uPWm0%d0Bmh1PntpH6g$GWJirK?$PJ0_s^yj-rYJE@VQUa zhamG>?V#RFENPHa-@?h`Q&C}<YSit#Jy4?0)$&iH!d`B}1<S&N!9&^V7EP;HJNh#` zLSsa;ynA`onj!D_+}e4;K`$T7_UgA^R;5_1O?J6VGmM41SpJUN61>#g0G>mAZWJxt zA7R0!HKo|hT(&q<X3gddRP8K_3laB<*w3H-`+=iZZMAmhp9jYV^o0RCWP^2EHk`5I zb{k}2I`&=n+J<#!Fw;B&4ipGX&I~2g$;9v}Fb_QF832b8TB6zitEe{g*4XK&cDo|? z(FT%7_DE@;Uh0V>*CM!b9Z?Z#oaIYlfn~`<m#%**?ZViFecyTay2b4djL|qlezYj+ zhz3yF@l8fLCx=|c$*KCW>r9OrC3@eM66fhO#{CjMS>E9gk&_28dmhfcwa;&e{CV!T ztPjDFLTX|@wjeGOd|NtaQzd*XdoX)%YKFp(siJH?&!U0Dj2{>Z-}o+2r7KGa3yMee zqhl^97(!7G^lxdu&=XL&^oG5k=kSl80cx@H9lv-}ZUZSSTPEM1(&F3*#`&`0M(Y`* z615(iZBmeUHrE5_jXW=<*%&YoGQBd4S%<1=5HN(Tp)N%5QC?2Ck%N~gh&-@o)ZWO* z*wzER<$r=yG$0SULM=3vnWkMX!%e{VZ;j3S01!{0)k_eu#txy#N^W2VU{wP(yPi{9 zsIdX+93YpVpaC?07toj7An+OU631yj5Khp&aC1Y2?Y&Hq6RrLz;FCMHR4*$f51%_( z!J=yiJ|Y~TP6G4DOmDJjp6a=jz+dpp!0$?^43v;v4uo01Y(N(5dvXTdbK;gVD=1;s z=@vZxEJwP`fDzH^#;-J<V~Ky0kl}c+DXqsq?R@msdJ9GZIJzAY!$;G?H0(TNKQ#&I z8z>yo=(#ujjdwr*9>Ub&nZ3}*OF9bHo3nmejhtu49P;r?T(VTDli!}O(<^7jTu;(I zegS&6n6A!sCz00{2iwat=nQ}Pm5<(PQTXl(4bu7Wa_ijgVN<d7Y%!;ywJP}s2zy7R zB!auUtF!z>=5&=FOKi+Gwo%DjJ)$lj2@GQq%zoh`zK@+Xek(esEWRr&xHU}2-}nky z7x`+FpHSN@Q;p3xw{j3peZB3S=lk5E+dB_N?7GPqc7p31i$6X9J(PeKp~$COQI6sI zs$=7$N}j{{a_@9hr(Q(8Jk+vw)~OM;gYP4|h`FO`<=n%*>F<n7G(CtdFP_V@7$(gg z#eEz^s%;o6rR-IN(`IKDa%9Nq=RWo}yNP}^yneO#T1$oiu-;57gu<jDG&e;HY5mCO zWPY=mDew7`gygl+saUA3TXP%o*@k7@hR5&Zg4kfj`}g-;GhO7)(V#M(EmZb>pD1?Z z1Aa2Z`$JE{QAqRPLEqd@yB+eUZpg=RMF}xH&+GXVyFO7T9J-pDW9{hkqIqxKn%vUS zxQM#ApA~7VjJN_{`6o;ECLh)ED?0iIbP{4@0<**G0}f-aC-lrzp~O6>raHt(jQ=Nt z2O3UJZsP)1PpJ(}q`0qPnXyB$B#*ID|M|MU^q+y+5%s;v<CjGFkj!q7wCyQ6{h=M} zfO_O}<K>pBkHcG*g|5Qc-t&*)p;xA)`A3+7q=jU|M^*!04n3V3i|Vf%ohP@lhTiQQ z<fp#YkoQd4Kf5yWSV?L;^!wXuB@W8Ucdg$Sj}&6Bz&#UZi9MqRCyW*@$157hwLTsc zQWlJ=oc=Wzpx_iqeFxh)CG^aHj<y!S2%N||HuoXwdQm{)g|o_|`<0fP<6poZTV|ax zZxavXdc`Vy6S!UdPRN!9F&F`=Rpop8R(;wKu4$jUxkHghCrcmb7^lAec0g)c#WqPa zWFafT$mSA}9k&`ujm*_RrQetPl$fzKnmqpOx=4cYNagwBqS$WFg5sxH&r3`%s4<Cx z<YejR4`r2~p7wtcGT64?W}kM}XWPbex)Q26#)_*80{5Lvi%NsuDwXNEVYtE%Ka&Y! zV!b(<cEQKg`27h7&Fr+j^Q5HYy5=S>=cgag2Uyd^*m7(PJ8u<;#B^nQly!K(YDKya zZ)oSG_n)%6aiwZ1QfnJrvs><I=20SIFPGwanSJ*ck-%rS-O5nGVopcQUK_RLIPdMy zFivmc9?O#CKXox8Jb#Quja48|{^7ypAA`L!pVf<ca&m0>YPlY4G4sS+{_zEM`XMhP z(LKvN^e5K+!;!R}(Pu{#wyA8plOdXr0@>^4I=P(Q7j9Z&dTz^y_>a(#XZm>Oicn9i z(|TN`=Z+U~6FGMay89^y^B(qczUY4SAWUWJeFlq{G-${9j_&m4VJnXBQu8Uk*`H27 z5h#DjRdQ3Tp<_x*^t)jOeX@K7Eo>iM%96jT?CSlv>zYk*Ej6;=G};nws7shnn9$+^ z*>%Rk)-Omy;RJFiq#$zIF*O(frZ0vxB0T^JX{MH-1wmvA(hM`PAnQCM6R}Y$z#}EO zi-}wt*>H6X)3$>*0IWyjTTQwRGqMbs;D)F8l|B+jUn1lFPLMv=Q(o;s*W(*a=B{{6 zAjjsgc+8j-W8B8l7S#_zEr&p4v;(<X3Pi;+_da?|4xV`eGUUb^%V&5!jZEqvqd^dI zHK$9S4{qd{pjJ~pLoP3Xt7ec2_I47Fl%*{R3|u3{4!h&m+4_L@<c?e|dk-o28-OXm zGWT9no#1ky<k;>aa{X&9<~yVV=$;)QE^T5)jO$FD--3DefC_^AVj{PQtcp>mKDTDQ z_bL}QQs}0?i*?Wtrx(IgN^Gc)xlntobFXZEdVoUdHicij1EMab2pi=*LHB{*Vda>d zv(C46m^>?fP!xC6H97Z|Q;VO=i0*=2h`ds*WYE4BFMkV;I$PTp0<FT^C@|rSwQzAv z4YI4~wTV~P&8)plM^BG2GaHtWOcEX=Jji#Li6Way>{!jm6`=W@O5ewXHCpQD@i1Hu zQ|-B(`Ap&LvCJ{d)`6BZVxmoNWzS{%vCxX0&~eIVe`^|)uR9w`KJO)ex)ruR?(x=1 z*!}pnxf4O$0XyG4%2JNA<B?*NFeSQ?8U36HH&U|vlorsG-KFslShQlJI^Ob!sYqt^ z-P7<3)@(@e)}3u5IMtzrGz|COFF$%aP<6tt47=;)$fL`*)>^I%R`_0|-qYmqJ53n> zUPM;)vkNvV3DUDL%dvgM-oW<lrIcYY$V3qLuRiu4!aTrlm4El~u#<_P(dUCVHQl|E z8g0lkiVU7+L@V-EzuhI`f(yT}-tQfs2NYS{y1q|&{`m%QOPbh()1Yhf4+j+pk~C-= z`UVXWIJT_Z*rFLPIe0@$NcvsC*DAMyQe2C0{CIbAdJF7-L{G8fNRvcd^i@~ATrV0F z=<8HkQS_NxxAsHh+;z{C{1`sFajvIH7UI~$s8Hz2-LLScgxc_MPoK|4b&oJ1Qw}0p zvU25FJHF2n+}3n3Ed)1&J;nKGpW%Y`xV5tMw1@6cSTfbvM{qXj-46#?sB*78$$H12 z>~9TQtpmIxIF_7^5cYfNHq)kpctYv&_)@A}ulrKH9&i}Vw8WLj7l;<CcL<dQDYfKd z#8`vV?G`4^$Hz((ZbrIPjhl*IElv1wV%4?%t|IY?=>l)4-*W46lg)uxA-_+Ov&R|l zsB$Flrw&`n&k2&z1AYt(T}6SskCVD3OY-$1oV+-=@^;B7c#l*j;GAu#(Xj0kUa0T7 z(mY??-L?-`?yGVifvYaQzq=<uV`jC0$dKwMupkyX@jzp(P3fp#UwQj_&|aJJl)Ue* zY$USjvoTUEsp&TxqC;-a7OQ>ZT&45D7auVB{X7*T4G*1<^S>Ll=>EL?g5re(Txndq zwpt=UtjQ-+vnRfW@&?cS)On~KE+PB=kQTu4i9V&TaxXooY6WF8b0@o13iz!owC4{$ zTW{KliT@O~ebI10ysO*ErB^SfuVAXq#r~Xr+=tq|v84$w?$=6b@L3kV@^^!eI^H1- z5K6n`#3dy86>dJ<we#6GGZJINv7^h0?79!+6wM^?3oQ2XH(tyxUcdSAm9}{B(c*qz zzvAys^5+wb+U1v*Qi%!YV!NqDhhi_hi+WLioZ-=~SxTM-@351s0(!O&yWJ6gqqNdE zaObt%C$E}$ez<vUJYe#eqlh6B(L<*)!#me9%TV%0y9(Fbj`Mq~d*6x1NDzJawS@U* zNV7(qk5--}?Wz|&+cOnbvYejM>A_wkl$+|mK2WOd78#k4@w1fN5_Cs7uX<OvRb6<n z^nKzzuc{T<tz5^N&ui{zbvEf;yiu}e+RH@7;SdLl#ymQB=PU?M0i+ePk|$=Y(?+?4 z@yBs{JF>4Y@#)D(QyYY)gG<S{=s!zqp}P`hUjtus0R1czd@j=gwa5-KRJrbmc2+Ax z<h0YX1sh6mDrr9wD3hCW;xoJ`{u-3H*b=#>H?TdNDMB&h5IhbLdQ!#$Opv!xCEJyO zp84aI?GOOns)e4tvaY^Zq{(9CKlQc%wT%gsHMX7Vx(19xj2oy9%6fnqN`5cVnHZAR z(4=j+^I9y18Sljp>?gB~zWD<FCfnw}RNCU{YHRrYojBfP0N3U?q|%56X$$n9V`cTE zK`2*%`zH|(u{+(pcj8tT%BBcMwln1g>Fr0IhF7g$0cXDtCKIs3TB1t-DTQaiAD3H5 zEWl*oLBPN<zVd`TV|CWa*W%07P!zkUtAMe1m3tyjWymlMDk!iavG>FHpP=x9rXN6E zU48n7f>pg^t`#r6kj@W<q74bJnbto08;qcSL=F`-VAve)9;CkZbGx4Q;gj*3?nR?L zjX%a3Pnw}{Pkl|l4T=PEQe|(+59y7`Ree!lxoOwgU6~*;wN1!9l`JEkjalShzZ#(V zjv5c&ICgYZs}qA9^fM=BrX+@aN#4;NArOwS)*mYKkrJpzTF?d7_mU}o3#N}(yv$L& zUI`a4hdz$g_E-g{s^gwctEdQ9vzorjDO@J&;ls%@O5cb%dWwCIk~`x1GIt;RAQlj} zqMFE?NAV`}OxkQ!%Fwt%h#ZlNjTZcMgRD_ky8G7I`ZHs`d={EJ2)Q*aKN4y@k$pG~ zGnUK|{bH`$Iy)Hod-xPiSuS3})kIq#Ubyq};jyEi&7(@+WHK*5;vIA3OxWs#i+J^G zrR<C4inpBAV~SoP?<e?5_;%%j1<ucJ_H@tN>g8TuvU>N7E23^K_qpb-X~EzIpD$q~ zD{QaZ=(adp?+gtwZ*LEc88;8ffL&G3n`{$&eyHDyt^4HAJ@)2Z4LD;l-dPNxRQ?HC zB!3w<aUyl<H)|WEy0}9|i)otKl*}nq2uwJ~Em&j2pL<tq63r{C<ZE?g4Zh`Dl~~NU z`($m^RCndMhwa@zA~8<ey=OiiI<ju!`FJ#}$-t>hwOi;+fY8-*+4phJn<4)wLec76 zho8}?6N+;>fmhZ&(|7%Wp|`+~qwG`9KU}jLEQeRCh!}?<)Du&c(j&<Zq++r$HoEG; z)w|b6TXEk{T<Uu9(CWe%U+d#Oio@be?<{d?C9|l(VC|p_sg*T-rq@rsU_7*ZNm{$~ zH{RQ`M2?V>o6kFrp@k=uY`BOXO8l9ZY<AB5+V|kc6OpHqd%ufB3$44%S$=<#J}v0; zPI=9=Lti95S2SXW$<E2+Ggj!;JMl%BRll9fi>4H*EozE$dq&U3Io>IKRN{aBYKX(H zMPlFD7nw#Hq?XMI^EecOl4(I$iZ?@qkY<mfiX3yb*&%+mG|@ZNBx5sYXS-d^PW;bQ zWp}Ek8elNYWnY-f?HjWu8v_JxdhDF^pJXf)W(jrhwZGuh*W~@{)D1J?!&{94(q!UD z;?f5+lzS_B2m7rCXCqE7^_r>V`(EQ<*k8%(v&c(4r8Ij8=_{{|D<<nx8akJnS#5Bq zqtpj_xLl8y+%n8HhgQm3c<otrVlG%|`&TvYIeCzLx)4%5<AzJm6$LqiKYB#ctUN6) z_3rJK3oIHufBOg8+9^BOpySPU&yFF<bjg>dlE_7dy7N{o^bny-KhWZvgcn%>YUb?8 z#_i6s!JAJ<_Vrmei8|~C2(k73F-T0hXtgkNqc9pyrr<}l#6G)P%Y(Ggh9|0o7#oo- zj5lh!4O9fPkP}|};W(VKw|SXeBj}~jKCN%wD~b$X|8)aGZ`c4eLfDz2Wq|_AiIDL~ zgVGRL^%J+UcbHv1%AlqZXJY!74gBe8%ka}LpAEB@O}m~gjT8yEcbXmXFKIcmoXEu? zQ-U;gpeIEzpi(bLk=it1jHByt$qMH`!IO~cpKKVkE3)}~r2yNHiKihG*iCr&OFHHe zc8t{xq-U>|7|uDHB7vT$wRLQL_M|7S$R|q~=jqxc5+SZ8c`&<rn%5lq_O>ixw&DnK z4{&*H7_JGY9|Wj2t03CSAO|{tewj1<-r8YxYp=mUldUrE&KO7UW!lQarkbNqPh=v` z$iD;jL(EDxvXF|yh`&zFcWh3xh`4y|r77hAzQ@Oo$_Rp;`5GD&1l{iHv&Sy7Z5%x( zB?Cn0^zXX%7AC>Y87&xRUqzR9@AgPOU>2H$rnJO@1ZruJlOuMSAIKoK8Bv7k2MoDh zq&;3g2Ppd6ThboCB|BOaN*;D8b2zpTONs$W-VZG`yrF~Q9p%@_io_+uywI$+Yx$+G z-s!QSydO15kOI|7rr!|pqN2+7<dVvwFo&ImQ$UDr8@e?+IdteJmqhBhIW}Zkh=C*+ z9soJmwjHLYPnY`iZ03UD2>!Ey;*Pw-{;_S128k0y!Zp{ETY_>JS1qU+<>(}e^@2&- zh<#|~y^-b{W-m*}ERLX}Uh)p_8X~#OTg#`nD1WG4ao}#VDZO=e5j~%UJ2H}y(t)`e zeD-;E+uQyx3_sYvOfXhJ{!d12ew@%-c=&1m<GcKnlO09|<*<_TFNK+%ws8`vp1f!7 zS(NSw1;DwRpqZ38=#?sF@mcu6(LG@rEH_Xd#tNqsH6nZvV?un)({h{C`l}t~rWqDV z(;x7s?k}<=CRpQcr5qV>GIc%bKM^th82wn0VKrt}V1y6O@oKo#jTtq|=~lB!dB*)s zKN2@%BkUD^u7U<V2qa%$E+$*PtV<);=lh9xd%EMcO#jr=4(j`<cGF`e+cwqV-Plw& zkil`dCO{qk<NokX)b>i%o@vcJu}4zvcUcd-e#IiziOi|ZL{ChnRt6A3NW#qCwk-d+ zH|CxqI@lz(A~i<hx7Y_U#Y;lBMHsJCeb=?_TFg=|EbJj4%Q`=i(^%CqZuaKDsaeJO z{2%onPTzpOa0Fdt)41lQg|esYp_b&g2z&i%s3zqG$hyB&V&{ULLT0z-hQ~-;9(tp` zmb;aji3s=lsS?Y4cRZWyy_1H#x@LP>J9xjV%VZDgjA=_|mg97F%*7HWakltkszdus z@7S2o%Ip8w6VRb%SkUF+B~kv$q+4vycZ(uB=}PnCLf0i-fdL#cZXP7s9DiaW9F+R5 zO~=z0Lw&QVvNMc9YVRXSyYVae?o-_**(?ZY$t0wAana1yFF4GMQ-(V&ke4-)l9`Hp z?;r@yZoTX-etJWLwB6^#m-J}R<Dk?efqqh%j%bXaw}<$J_~xjIgtWU(7jU(uR)v{Y z9Bk9AwIa+uS(ls27f!Vgzu3oTvC~rY^1{@`@q&W*`@qCJZ_U3P8}e(X^Uahu-P=P) zLI?MUZh7IH_LIq7bD5#PHqpK?HYMb7F2*@W&O+hwnXAXL8q<$kK3qTEg7R`XS34Zt zjoDRMQBkotaT&KwZ{KQYW$T`5TgvgX-nqMgaNM`<ZK4)=K6L)3+1{UE)MCzq&54ro z$o$B8OJYto(BEezk@r$Xt2_TNe$Krz!8bYo@TViQyI1EV_YIyr>&ctqHA4k<Tf(xt zTY_Uo@c7R0XO_zBq#LE<9g6LV@#^?A%7P6ckw-k_*Jh^^y~zcIZaoJc_G=7j&2UV* z*`+r%3C3ht9>@3tkolJW_yB{J2E=;&+-6MaH{CsgUFS7eHl#8cW9R_4)M`s_FZtBN z>D58C6z9HoQH+Ocw<;JOlVXhcSI9k5zRAxQX!d&Vkl!~s)RE%ke(2$W4LujCny;c{ z9{CIIe$en(lf9cugFbev(3>O+O@7-9YBKp0HTg#K8@Q!N?fa3AM9_)(=3n=rHqQiH z{r^M@mj<Q6jvX~HTb}G5_*Si7mBhYN<Jz5}yT<pZ+3!L2{_H4dfm0#2vbvZdQosOn zH?*Obm2zz8H<?)}US3w&HBwMf8et!&JUQ<A_4d1`_p8Uwu^0=0jL`L|gk|m`fZUwO zc9?#^&|nX$6FUk(`1As-733+Pe=aXCu*Q4nW02UcJG!R=q_rd1cHMS*fpmAlllxsj zYtCzmJ!5`8Fy5!Izvs^)lIaHl93zzDpiSs?IBCi%#pNy#!)MJ6RQE&<caYrjc(WCZ zrT>U(GR*GMkF=QS`sO^^O;tdX6!|_<0#bTAH$MB9$}kODSa3l`XwVTWF-Rb0ly`kg z0%;oCT_7W051Mk(D_w9l<ht=eE5bbGA;{I>k%wjKqZ&uS?lR#u5SZnB58w!!M~>|U z#?XKgs&^jLLK@y-SH57MC-U%s;?0(_KA5-`4w7@3fjO&q<k%<;x(!Q1{-9}C)C9XR zQ37e!F~tH0N@PkP9<&O*n7E}B&ki?kL$CF%<Mvu%9$?4VQK0K~lJV?DImoF2wLoR1 zx*(}}GMGP~rJ(G2MmQUkcRk?j%b)~{?FQ#o3ToTx(je$mD8CLg2t)q8=xSy26g$RE zgPdd5g~z2f*IzgFX#Mx<t0QV*7&OAdR3;p!7BiqkZ26DQsnl8|10L8u4aq#lp~sGR z0CE5c&X#Avu6Do9CH=yG50Ks{MdQ4T5G@zD98coQmTo4bQ3Aj*cw?6(%r8QwM@Hdw zHsCE-f?A`MlAERqIPj<F74XUpMTRG!rp7{p?%k!fw4t-zm0G+6=liMrBpj$<T_d(2 zTBAr=?xIrmrV=FNnh#EKbG<Q)zWQhnr7Ov=v-HEbG7!}7OWQOGP;~?h<oKhwC-6rP zk2!cnHPi{wUb9&t(4cQ!j-Tl2d?1x7z60!<3q_Epvf)rx!9mzDMpg<Zh|Cokk~YeM zhXIl7z_YOi0-^0#pPe8ARQjwuX$?i<H&NPD(p&knya%~&2ZUVn!Xd}mK`SJfFR{S2 ztCP5C+zFWk2f<^<Sld8hjwOpk-`nzIqnvI79PejVII1tOL7;DLrnn0p69k84-40Lg zEB1lfU)RNUZp-Jh9zGwEzK9Dzb6_ZY)z>IMb;p3DbEJ9FB^DrixW*_KZdpULZ3x+A z+^92M2a`MH=YESkUG~m@R^e{INXhB{G~8=(0i$9I)H@L*9<iao4Xinw2yjCK#@B-k z0v2R))W0WrCRxX$^<us}kh=W(gsabDkCG{}E#4P_v5VV)0o4P-vd&dRbu({D<mM%w z_LyG>2-m2O2&5%7pdJl-ue{?gcP?OGzpYM#cx2*oBCCL|PoSwDsILK_EV*e(^zhDB zcv2iaKMIH1ybU;1@S~&lS%Y%OTb8Jh#=EOpG{{#8q)FJ%0$&M@UuTDF3N!$SiAMw1 zyAAs+=T?9sdiVeiJ3$6AE>ASB5Ju*$%aN9@l%=E}7B^bU!{TzdubSlE$BrGQK{sEM z&aq5TB!qdXj15!@W+55j3uQ&_jUtE&v5O?dD08lDc|f|}>SRr)uA+Xa%HUbv)(9DX zdh*@hY(S!H3)KyITU-jY0*<DE%yz;&<pFlsuxLU2lZ(1Vvv-N)?Hr8)A*P|Qs8<($ z09=~gK(u(sBZ2VL9=*(qT3f)@hZ9dKqDZXaWFmglbTW|xMfYCGx`uxCX9*p#Ujmnc z#LWq;!&d&cO;HOA`^gjQt;~2j#&4&Sfh<5pR$g0v#p&-d<eB4=9lIP*zFd)bXe4Fx z*(>d%E2^CP%X`nWrd47E7CQ1X{L+n&U+fiOdiv(9fqT~%FD!Bb1Z0-D^>d8$j6c8W zj6O{!@`RswD9_hd@jXA#GjuhXzlc$&p(zBMB3u1^koH;t(kw!8ObA4e)?-L>RA%Q^ zW?njOTvY0^;r=WdEB#2=WY3AUk1U7RKFwHk1&t;U*Ffy!kA0TN)$%VaaMP(Q#m#d+ z%-tW)Q`4s$G-k^xbAPY^rW3cTUPln^38c7aNucZ8rp3=Ws-KO2_oFF&YW1z!Tg!U# z<LX8+c8LlnW4dCGTLR(541S3Ugdv6k3_G0^m@R|adhR2SCuJ|^Zpo|Y$~^E`?7YSw zs4DOm`kh{Mz+)1CpH>~~A-~eM1pkX@K7;vZo|pVqS!EQU0gjTxkdAtRlYaz{tt`Qt zprZd{n_|Vub{TS$*5bE&WB#)$+tgH91-{_ui%V=+I;PM|U~U_z-Q{IiPkPR!P8oTh zdmEUMudJZpz3WZECO|m4>5j)=w$Rx+6kKPL?U_}-|GDIkEIms(hK8oFF`NqhRggqZ z8#>AVi&k)ndGT_;Gkhx*@a<G2vB-8Oxo1V`^(J}CFZV#+_faR1sPBJeLCIU|eq!KU zmd9g_$p_bKoH>`au(%c<YrfKr4FpF2Aixm-PlvTc{%r^GhWZ`LzU)e}%0F~8w7fCJ zan}O8B*Pwb%Wq=$q@Mw>@-pFTrW-lnhI4;mMMOuPaK(7PiKmKha<q<~VAJ`i{Y<xy z$;hR(W5*7F2;T-+l_U;m`d<!YJ3U~!HGCGHj(AHB@S?T@V7?>p#|0MP*U;f*IK7-C z02i*%M?4C45Lg*_>3t*AT6eJ4jW6OhkF+73_8D!;$#2q)OQgyS|F`(c*C{RI$9IZI z^oj^UZ%*ycQ0l<_>F=N0LWfAn^yp~^nuX;aJF`B@7G5)ZY9M{;{H2IuOUCdRu`ihk zbTW_$Zo(YD0OLTOzSX2qYLjMUQGLZlE`>c}5_iF<{I5V@FNv#@qp^VVJ@$-8>6b*& z>8Xrn2sF?-FQ;+hPPcl~dfUP4U55m@*o4+^`|z97ub;OOY|vl5`71)&T<kcgXr*aj zc&3QYaEC^T3jfn*yiCtqV{w~{1?Yc0496ZPQo+iYiK(gYNUToS#l_BB7jB=_YB^y+ zznKzex?;mffGTKjB*%dJZA<Ah>4xkMo>FqxBK+IAn}c_LnP`tewpK_WK9(@vmLkO% zoznqq=rg4vs;htz-8<5upykfpq3?8lh=eGsqtNzf2|Uv|R(%~;JRx=(zf_M$i0DyW z%D&Pf%0dwhs^lfMGHTcWo&d|6<7DR1Zsrg@xIe(L^s&eDu=d@mmb}1gqwMz4r7VLK zQ)L739IGt-wLN`+{MOHD&@nmmd>$fTajqD{_OZ_)MCgXd%a$*Vqff7bZYdcs`2(B@ z4SJ&t5+2~}h0()GUD%0GER_J)2gngekz=x;?4Jzpwj6L5_G=y)=_b7mx^!}EQB_UD zEv_qpsJ$G%KIH-|L^z0R%?td*z?Q?w*YNEH=wZ%w^h8PnbroInwxYwiT>h4am1@~3 zwlim358ZvaoXGw4|7Lv^Kj1p;vPd9JP<329N}NVG2W}0!XEu)T87`KDp1SEVDoHZN z|78m)c_7sK0ndO~P<@Ji4`uiso8guqrG#GJ;ri#<Q#1b8Jw}`Nh%|}(Xuou8kJFF) z4SN)xO@2Kk?X~NfqqKoh>KI8Tey4^;-pf*V{!ei)Fw?VciY7RUa`0z7NkCJW1`Q_> z)&RX1;97e>D}W_N!?}nsiWgoKuxoyd0KfAd8u@Kz)l7wgWPr*uaDJQ4I1c5YM@J0T zT9$GF;~%yXfe)^oR%=61)D#B*DcxfjKB)eRDSJ3K_|=t2(Cgt=18m+e5nbi|>!t_@ zh1a)kn$VE@ZAA+rhzo-!&57P%Mz<OoM9EJ6FE733r+^Ig7MSwL_uy*;zDR?r!O4xM zF(v_j@{h}t7C3An?`MCxUk2*<8Z7r$?Y`|rHM~6c?=9ysE(!?#o%Zv85_&8ez%lwg zJOl)Cu|v2-UJy(RVD|T@cNs%;=6!-)miAMkLA57_=MnAfV=AjJh{3tNaw)#U;lbJ` zCAVT({S<UX;T>^?Gyh00|Nm!tUlJt{4bVD}1KL#v+)J@@W(!AaFQnuo48y_9*Q{o3 zh5#EI)EWqvq~-vVhVwOn8{L{gz|kOX-eBxHN7zln#as%o9*etYKVsIYMj!*&0NP(( z(mPB!eTc}3k$Ead0yj)(CHewbc>n7;`J&&Mg(Dh1!9j@VJvQb$e&U3l83cJV7@z*L z4s_ShpsEBKv`4&YAMkOz&;(0(-C<PG6oiyDq=gnLrwuQf@ZAdlLsUNew^!V*!cp*$ zAq{%Ydp#0vnNA?ep(*)`@+@$pCCDLcG}yeKUNP*o8IcdpM&}>&J4~3Y9C``g9~5F_ zr4DF_4;BDJ&z-d3i3Axw#1ifOj)5b*_}{0ke{a19&?MGEzP}zah5b91Qa@00E2U=y z9a0CpOoxlZj2_Am?$^FsZdthWystR<pQQ2GdFu%p#5vP|UY7OK0K%d+3?n9O|K+8B z61}>7`WB$s8`Q*dZwJnS&p@SKztx^exc_G7G>fl8Nf!J!nf#|+r7CT79sZ3oe^-3b z9|_|&L}1LuPV`*EFOkv^&TtwetMT@K$_*vC4S2CrZ%=}|0^dG-p+QgnkEyGbDQtts z_<&+r3a*<1vHB~kx{W91f){KIN+S)62)VVc&q{ui1&lALB3-(-&Y_lv{)#2+2j?36 z@e6ih#gHP1Ld-9>S)d8MC_#AgBGCy*e{e0H5~TZopzhx_EC3RILHC37qlvTct$4DY z-w9l{piw!Yr8ZAu><`suMSV`=@9Rzl-qXrx0%=F3I6NFjz|tTY`+t=F;iwKGa85n~ z0d@nCbjWfG(Z*U0psmyJ1R~S|vI2{R>5iZ_?+NsW`%HASxFGSi$!~+66cpjdge1%z z7}ojUCHUuLcEaB!;BQ*{&x%<G^1c6adph?<JK7O`{AT}>;5h=e_Sx=gg9O%cWuFN& zY=}AA<@tXA#}7?5xysf+_y2mtUH+!4FNsfvn{0}Hc-aoOxel}ap~U-%?gU?-wtv!$ z7jFyUzbk6^-<j}F$|*mBS!b|>OR?a>vwFpSLu#(3^o;4_R4d|!hFkuw;SUH$C?-sI zmb1}+Kd65~&No6vQ#Om+3qfM_0l?ZIUptC?t|)jaAS}@!u8AOE_bdz&Rv#?Pz2Noc zeOM`u3F6GT%j0F6E+nQn<a_6z6gN#w=O)0AzuITi--Z1j>?<(X8@JVc8vd>frb(3D z3%`;UPFQtoh>aSudhPJ#3}+z5-q`_jmZR+yU2Bu@hFs5EFt(z3>iVL$vclM;k6yd@ zJ;mp?>kH%PGA#02A8+8-1+Pcv(#-uj9Ho~>qWV6T8C#qtPf~@J#5OKj)d;?WTlB-p zvv3fK5Hy8aY9B?&s9~%9Pp#Y0WBdRGtfweJW;u?dbvTmcd}^N#U)aD?dn-Ljc}9(u zbYQ*c96I&bF%46orc;%VH#F%r0-CN6uRf6KWu-W-q=wp!$ar+i_v%F7{Ka>Ov%2^2 zGhYtqXL?Q=ohQ2yddr^zE@KR84dhukAVc7jH2&wly<2b4>>K_lcj{r|<mZ0%M_gUc z9<>c)2CHs%G@)syKX2m$PigbJ1!>Pm2%{H8?zV)>H;x|t6gPn$*v`;$-pY{P<vqX2 z#|2*p0KN%;17PZg{m?d_mf;|M<>fd|O-a4wAok!I@H)Nc!n_0w>8ZA7%%G1Sx>e{s z@XkV?0o<b;!IPC?N+CDr4{s5<S8OY}wk6=u<iE3IA|GDoGzWn76?_3gSx7@nt?;ea z{L{+wha(2gq>EKEr8l;Ssb<X+4LmUGqaYvQhgwMFiS9s-0gDR0oZ|iIFuG?*=E(vp z<>4*#Ov;_8&&2!42^G{zd%%H>)N;4i2}BDxbygzl8&|yO29Q8AaNjk7E0bflj?=Tm z|L2w&bY<g{WkWEL2s||x_*G6=Ned%LnSE{`KcO_cyF(^6Ptju>zx&YUomtqOaN~AB zj4_hW@MYtpp0(IT;UbVxA_>pVJf*J|Kr*e^Yw)@{{vmqxT)que?qT_A1?Q?R4T{Vr z+JeFgrw$EjpLF6fB<E96V?N&Ul(5_Ql|>Zkf~No55E-{`9Dm;9%HjA=IU${48DxT8 z081$kbKsf0_fZ(&0zK<$q25ut@R$2sQS^7uxz$1HS}j);ZdgXGG>~HJvax?YCvGV! z=SB)As9i|GeTzXB8f4*yO#jn0E(NgQ|6T##lIw**PDFzy0o0gds6TL;n6jx62*2Mg z0yYGZ_Pa?m^3HYe5q#n<!l`Cs7J2sG@GFcpNi}8ZN|;%dK6>Dlan!zkHEG_YsOyW( zZX8~xIv<D*yhvTYnvXHfE-dT=afi~)JL(U&y|9RKe32ouZ+5yfRI0=^wew<XT<qDl zvQK$SQ37P6;d!Ej?yUUVOO{^q)<mH!r!QjPX3~jw`i#5UMO1B?o=XP83JUd*nW*8O z_2-dNY+v)fbWuRG7pMok|3i1By-pYry@$hlY|e>Ge5&kB?4r2s$jzNLiQTPIWOJjC zyf+0|tFW;7s2X-LY*$3Ex1_s0s<)1i^<g>Xysea;&b##+%M~l#(o^Q&aRcTPJno;) zgdfX}F|ESAIB;5~ul}|Bb#LPbapF;u8DC$N#C*CCH8fTKHUiD=!Am40AjN1T&?zW) zQfBoxuqVLcYQ;1{?q{1`nbEas;8AS%;?-NYMzFjj|9Iu1IDbcShcl+v_sVqzL(f}p zSK8{bHJZfA4`wz0j0vy75_IK>l5mK7W^OM4PV}du2P+8=&Qr|V^JND1Rw_6-Dz@-` zzfj|>Z59D5w-3w7&8`T^{)*=^X;MH(->Godz2}x;6s2DqCDpU!aKJ#Pp3gz)Tjz@c zhrOAO(@2yCi(HP5uF_MK>?LiN`)iJSRWr=bN0sblt8~aHUhFyf%k_aBh0<oz<~i3x zgILz#YT1I89?k|d3iMy__Ds~FxZM+2i9Y_O$8mEM!z|6D5&f5~1m^;8I}3j$Pt?nr z7(oRouR#&7uK8@F6-)RHMU*t1bt6n6Ld1sEgP0wD+Fi4$c|>$J-ivG**!Ov@iTwaI zwduWi@6?jkou)hbeHKky9kTCyIu@17%_Gq4!k0SS<o)&hX;K<9`&sG>Th$U+`sc0w zk44|Rzkj&6U#hvM{%~B*$O~JUnFDH4Dcf_8VVFH7OYEA6?7Sq9^>jDNTszT#C+K2{ zdr>tBVFW+H4}|$(KYwcO@N0_!h51@*<u041%7=UPiSJJ3_M6wu7kb%7=*6EO<32LX zY>pymV|p+nLBUUM-eterXd)ORE`0xZnTz1lmHXaG6@AlF?z{Ccb*>tQPHD<J4;(7! z(TT<E<Db^t^6iSYz_e+Ku<N+v1vk9|`B5Ed9+jmIl@0CV#b@MfgOjW;y?0MGIUF_Z zR)2WHZT#tbDfL@t6(=sV#>IRLFTj3^S2H9;7stB+w6s|nz{cOrpT-jm=7FFS6VfS~ z@Iw{rox*2K-uh;iHESEYsl8MzGpM#Z_03V!a+`_q*qqF3!UV#8ge*@ak2vFMFapFq z9fp;iE4yv4-}N)fFmF;n;li}GChSz&#9TLXRnk8Cw`*vJhZn+y^H8Ry)pGk%?q@zG zeHTmDjs5B&zc;OFV6R}N9{FpFTmR_UZS}VWd2rvC%sacqUtCv_T55{j>TvM|YR}Us znW76S6Hl+~|JrU!dGi)~8*7gy?$f1gdp#6hrA$ml&t{9&zgJ@FxZDxb;M1t5wDae+ z;v&0{Rj;ZO+*Ma|zSiu!7;`Y(22BwH3gvRQ?m&*C_+DbuP|3XFDJ3aq#X0n;1@2bz zwKG-y{p(+jXgF}mk_&&-=)KZ3y_EVWtEgK1;5UN2AV<Efn75IKyo$I*x@&t>?@x>T z>~Hh-UvlpeaEEh8!gL>f`&ho$=T@||m(J-Fq0%nt_OaElcy;N_7YCL!J>5q#x*|hD z4-_LFM7rW9Rg36E<^Wo*fk+^AMT5$D#DnfwA^XI>={28|Y1#R=4fob%*k2s5+9_$L zbMNOx`MhhlcPO+)4H^>n%g>sQh+w&9oXE#?hcm^rsqO<O&URAt(;IUSM$hl>-8SpU zr08%^8>%!fcDw!Y{TEaWO57G0K>qR5x!sO!Ptpz?Pdkw2)iW8d<RN$cYxiqwTquHn zLbMgD_LH|j*LOZh?+7(B=O*iscP^b(99FIVYF>Z1F!Z}{dLeF{dsA&ziF9}Yg|L?q z-u4+0!&8ZF)#l9)#J3Yxi$-2zSVMM4>pLspPn4H_3LUxLuVSOap-H$F!EWn*sdK$$ zy@jskYa>=ikqsL@W30Y2_Sx$=@5uYk=5uC)hdnzAn?-xR9}jP=i0QVpDY)>$``Wu~ zp|66a<yQT-vIaw~zfWCl(-BzGeS{(YZ&lcG?SD(fiqNKusODXfqu^_?!b!idjjgOQ z8{b_7+-kV-4t^R>V$Z2Bo~IiGaNNHDjGc1>6?Ak5I{MI$>=_?|OFK|*B76h2E>#*% zjcnOLgQnHeaV=fTytB15Xs;mf%RYLK;HkPw!nOR!99nl>{Ea@i4I8II^$SK`glqn8 z>HmLQP@Y5&A5q3mVte|^u`!;npN>9Veg_=fNf6B(gz@u8!BvneZ0N^=f@-|3mIw_Z z#G^>e;bf5J>rR7flw&6-2F=4y=1}NpiGiX%HK80Ix=W;XlwEmXrt{eO7U1cI6ORM8 zDlr+xCm<CVP(UI(;t3%Mvq42mHI%_C&K174ERhI*GAIFpPr+DHm(gbsFbiQwKMP|1 zy0&a7vC%&xuFo62uT^D2W1_&Vi~hUcKmn3D90?2s{h=^v8Lr_(QJF;$P$yrRxf=pi z*_&2BSq-vvn}{!#xY6%6Z?K7GebAk<41C6%P)d-SI|B&$+1tRzFM+x^p6cj24ZZ*Z zu1iW>WLT$E^_AYKXU%r&qWktZH)JdL(@81(8u0CNbvN;#XflzDm#E8sob{4L?SUeZ z@=xLe1Epi5*(#d|&l~|QFa5xeMNi8-N#q81k<Nxww}6IRkfAh9MjGB6QL!n&*7RX! zhbryrocUC|OX@MhLQ~d9tfR<6@Ry;Ds^iC~BzUTZ<G+b@n8m;DF}vkZ72wDY@U3Jj z)OE0CJ6vObncA>=>yBT^Qt2omC$Ly1oJfqME`i<`H~Ou2!Zq&j<PP-w8t_d&fToxy z2;Ylt?8r^bnH!@Mi*??8Z+co369|C~p#S(J;3%5v(+LXYW4s_dwA8WKU=N*`NI0Pg zPf)WSKt#9)uYmU7V~3m)>Axv2K#qRFa5_GjFmGpQeR6%_8QDp#Xz{K=BBsS}btQQd z;TOE<va8T#dO4Z2kEy=@-9!a#fAscUgJQ~3chL;+j~3>g5i-16iw}5he-iq)b#u~y z(A;v54xSylyY!8_EbXSt%w|b=PhVnYF?mAxba7!{p2IMnCwl-%g5AUlLPMjT=qr8u zUVTBeP0#MmRp=bMWPr@76T+TLW~R7OW6*YUN2)Z{7QV+M&ph)x|7jts&0)0(eq!@M zHb2%qW%ZpKYLM~Z4P$M_lizOFj_?vCJZoU084W5rd+)tvk3)>I_0|q~rM^D@)5pk# zyNd3OT*%_e>+kRT`fjdod<S>QMbr<hfS(otRZFh*9c>YD5SBbrD_kv?o1t^_;~|A@ z+Z(I4v1*vUI=FQ7>ryPbM{sp|HUA>MLP#fN$Ge2mfn}eg%jjr7kA<U;T}kV~9M=w) z5Aq1y80B?PIbeI6aPGY0>HfIy`cVT0&No~J#i;S+#<uQ*Y&f(%c84LMw|ga55yMtp zfXR+4KPWra#rgVicGrbdt>8A9tF(9Bfq_YJJ|aBK8+dnT$1nIs?sl)tnm79cf0|%R zUSEnP8&m`svOecpExK^}`lUJ9kwPPps;}wEa*0x1Z)!;0%%vqCqgCG+hhB?N*j}<* zJJ2`cD>SXoFqqcvht8ep-Cilxx_q>0KtV`O;`RCbLhoInL(fOz&2^ZMhn*VJ{lBPt z&#0!_c54(Xq9D>cQR!XjO`;-Qdha4NARQzq5|t`dy3(Qo(m_f<YNR7odM`=nHK7Iw zdA{Y@<9i=`_WSPdj5Ed=<D7r2h}?bUp7Wa5ye<-=qH-^(mU<!I5%~?83nci}ln-Gw zZ}r@d(4Rg_0r|l2>0$yb3<qzIGUE0f<u}Ywy3(sbshsUxnGjXbH0V*Pr<Sjt<20P1 zjFFMiRMr5Y>@xX&5t!_;b->}EmRHJ$N)B{eIw>#@GdxPs$zUG`$*ytwKN31{l)HVm z^Q(82{nc|oNY6T`Hh1G^HnEre4z{EwUoq!eBnYoI)Oxom&tg@kCT4K(e)6nZ{55~q zp+2fNoK=wmD!Y}w?x^iB#9t)g`fFy!uYKftz1GzLg#E6#D)!l-sOeEDhtg8flMja> zPwUFQ^R;`pSOzi^lwmZ;xB5SrCq`|*nXih!$<aK>K{z^%dehIKMOV5&EE;@Fof2r3 z7=mJMNGOw0qRn+v-U6KnGpCtPrM_H+_!Ob-ZkE944t62@X#&p5F$Hy$uM;Yqqowq^ zrCq3CH-k^}mHC|7uvI_&Bky-*g|)W^LiI3Q(TX3Oe1AJ~>_z_@_vM&ta}?`lmc<(> zFZ8;5gX1lfv7aP22K?VYAS35UaHFwV5+;B|V(O)9=QhcTrwOX~Ae+)j=S&bzCBlu{ zRZ9DA?~*ndFe?d4(#czrAvrrwW99{^nrSEop}9(<@)QLfpP^G~H3Qo@ueIqi^Dmfp z;pq8UIbT!fB!zlL<+BxPsNh|246SC*0INd6x#Bs~KC-u4{pzVE*(C3um*<mSq-t8D z@EO9<v<Ap$I2&59KxW1HR17By)W^)!M}dS0xVT|#{7-@>ZkM}V-py1(-DjCTU6gR! z;A>i<q4>A@N~;Qs%3+$|+{@`a(v2MG!)9a%U|<5v3(&`cUl-Mrm9*Hpx}anToNou` zG)y8@`|s61;An_9wR^AHLvtu_^=32%lD*kTA7FuRz$P>Y@@SK}q-w$=1N0%Tm$T4? z=CAH&zjG!3Npiw^xYI&nD$M;{67Jx5Nl|it*E|_V89@+1F;Ro)@bN8={UzWV!Ilqk zw}kTC>`oZ3D?3gXH5$)##YF{aC$!35RNx#5U=przsBI4(T`ykM^m@CjE!J-LTASYQ zkzEvn=DeGZYUffRRfhsMW>tm4%sVx@D1%YT9<i;p$y1y$Cb5W<oXfFp*UsJ&&USe! z@YGpywSA{qKSk`zBC}_T#O2)Xerf6Mw6sj!)cC}NG+k^;bFp!&Y;HtpBiqBt&<eJC zv!wa&=QZ-?g%*y&9GHH|31iRkQ)wCAxGtuMg>`I`<6F#emt%2LTFK2jlod|Q%AZjb zxK;X<ttV0b#=7q!viRjg9>rhD>gLrEs2|$gl5p{>8=QanA?s<mhFi{v35hDF$Mq}V zhx`-@TVqBeB9-^}m*moBgt9Ev`(|3Yod$2l-{rq<D;O-gb%Fl@EAv_wnlhp?G0{=7 zc8*fZXyR3Y)(qX=N^Dx6ybTV?mW0MKH5eOTPm(qYdB)D}8CJd!!o{T*WH1f(yLdY0 z$T&M#f!U{gd;A>fm~FA1c{BB%t?F=z1dFS=_RzDbjWJ`v1WOiZ>E~M2WR2{T`$CN- z9}?9J$rO77j83D8bof411UPK$MMtPF7011WL)qTGLbhGmHyl0HdJKZ*FBdr<S8T!V z6krC;+ZyS#X{FxGwN64u-`nqbzXVMtJ{3!#_lx0*tR_@yZ<F^+BC@8|J)jP+%qAoR zKH9}hY5Nar3uL<p6trtC39w|nzx=SaY(B`+KwbwIkrtE_p1);TI^C30=&o(=$~Idk zIa%>+t-Ib1cM?`n&+Y!Y)v#skOEQ02D1DN&bjPIO!A>so)eJMpSiWgrHqUkEn8L%< zxMlb?q`h_s?0R%)q30K~nY9Blaow5miQ*__hGZssZdIheZ0Q7=>3j0ix%z4C4@xSy zjsp)k1{Nkr;Pb>x$lr5>JkO4$7=M+KI(i#DIUa}&G0A#Pf(iA%dSz6N!~GHLh7(l< zXX;{VQpB3_<;8Pkt~X;)vG;C2H}D={d_B%Xd-BRrrLG}G6EWhNQ}Y(}Bz0D1BvZze zZd6joi?J~4lKlI%7gXw2T+o*N*rGm!ia@o$PS6VaFni3X&SiQrHilhJzYntH(J>P3 zRGZJGoEqdyr*5d9ozJi5`jlVaS?Bpd1pn-s6$9*q9vU$;e;7`rfhwZ+6DiQD?oaAR z_hYXV_jXN9ug0$is_qC2HK`UmrgiD>bZ~54fH+Ozb`Qn?*!+Uvc^d1xd3gvUnf0lc z9_c8y>PKWn#xIdEGw2FxE~}77tZ==H(YK*48GXtsvNfBF%bMSc1j6Xe+C>Bt?8w)& z1MAAaNSvnEt8h&Vn<7g`QK;vxm#Q5ZFYcB0_Tz;}H|MY-nAlKp*hKYwb$GG7&ZJh| zWkeAau7Xsn#HX8UvOfRTnU;*|nojXko?tS3T=9`!gp#h6U<qFu$aI@tEbt4qvHy$2 ztzAIn>y)W**jC_Gd^aYH!E=!uDXC2tnvjBU3z5}Ijgs-tQ1@9~XVHHfb=1)LFp*X- z!a5D~$7S*C#eN^D^n&!z=5?n$y?h(@@+K)Gn0p49`C<r$k_GQw10A0HMN+Jd8#^v^ zKZG9}%l#8X2!D~c&fxoeB5ghE|E78m!-yHJSsTMz6G8yC546O4e(aCS`#%8;BWRoq z^~3kGkHa1B#l)#Pu!u#vFAy(0b1|%}2cX4S*%!bH^QaKt*aA0s*nYloTdtl>E(-<R z>2wsx1d#LdOt;NM^ba2!6G8yvWE6Ps)^GLM*~{`j#{cJ~b$tM4U&{Egk=xk=;PGtT zTi}dU0kd@h68Ru)=OyR4jeG#}Y8wIAz!jr?s_ZNKZ@~c&b@&^E{o_IpK!cUo5PjfJ zy!+gE_cZsgPQHF~rcW&M1%MIGpe%DB?DAf-`t)V)4xPj6J7;^n7hM8t7KN43kM-S% z-Oo8#_Uj!Y9j(3kN4$rm;ZM{BKC_}GfJ*zJpmDpvY4%_mOytm<WG>x19e27t_{R!q z|7o`T4`e}3`nKIz3JkeN)U1Qa1ON9A%jG}d*gvM=)AbPdjwrF5N^8f7lNnU?GOH~s z?B(8{$incSBC$Wg1+iJ1;zDupz=t2;5!$IbzwR-fF$v_^ERav++h@Rx?w_;q14wqi zgfkssgoL&@PQrYVy?ry&j*QF2B7bbyvOi-xB=cK;yFe9x#Rh)%X<rn6a$fQKdGnj> zulT^IE5pd;t+`!y>?d;Pe<{OF;Mibi>)k{5qiVciXMmFZm)2Ut9=*!<6eR<1D&f!K z?z8w90l}zAYr+X2Efe@H9d`u?*?vUF=?)TepD9xW*bD#V+&)`3_!ajEIXNnt?fGqz z{#j_}vBMVtYH|Q14!jQ5i)?;<w=f$ECinx4fu+h$!P&OcWH8vbES8F*;vHTeF5kZp z;~haV`=tztk{tYtWO))pJOV6;i8QVv#8)NY?Ib`VM&bxWlK!{f`<RlyD71-wPP@n9 zLQNEgWI5(;YB3O&QwI79e*PCp8Z3mw_KY0d;7r>FRjC%U^eHDs$B*LgNV<k`E}VMa zXQQKw2G*r2<u4M2G0<VxUnJ2WY#Ic%yXgsp$x88n68i?MlYW_4^B0M(g{4mgG_>C$ zq%zGUM~#QYF#CejJ^v<!ByHl2XbocE=3gX|zeAMmB`pUpaHDZpB<Ao<Be%=Jp_mEO zubtT;_a#NDz+>#xjEX?PWqZ9go!8gSrQ5|I;{F_hEclA`q;zfk5_K8d25prp>#;!} zzlY~bv1j*Qe6V;Vpooste39$(5=`KLm8YE2$A(+upFM*e`KtW$11lix@}CDcYSooX zAi$1*wY~lP6b48e?k5tDk%VviNIZb+?M04-KsS)s@o|8{S^J((5IO-JZNp>W)D`v1 zpsV75qV?qZnAksB&~v}MMpKp{{OMfZJeeDyykP&k5s)<?7W>5oZY%}d4dp2DN=V!7 zV_`To5<3h5-l`3NUf+HEgczCIT1t>$h5=S?E-`=XtXTX*AeH2#nlMG+Jun0>WBwxf z2|K!ROk^Ow;XB=j9ocL!ONAosa5?7TjS>Nh0*mDIc$+6=1aMU^0Gfl{4}eYjWdH{Z zl_EO!FA`xu-G^gKj%Hppz6&^^M8|YyU5tI4YK_;dL>?UgV5-rW;PmesT8Cky0gtjh zGlg3)R9P7yY#Z@r=ffg5!YAv}Vq?J6bXCF+0|bV~efDMNOGN(I)5U(-+Gu|yVk1Wt z<3TG}L(#$ZCTqd~I6pw2xPFUy*74TI7jq9sfIk}sbo@&7#w);FZ3t~lWR3;{<`$K( zW?(g713q}*jD%)s1HZTFIrsM=2VOR355<34gL@iHM5fdD<St!TTs2xCRw^D4e>`LO zwl~`A0(=Qdo$$d1obVw)6YT(=O)<nA_)*~>iaF+8;86F=54Jlu)Oe5o|KV)eLc3eQ z<r)v%58%;As`u{C{9)IgvB*<edKhN{ZJ&Al=*)ID-cbtE0uFt$Sd^o}hyI-ZG$2{{ z{~McXC6fl*u@O=G893go3LJI*Dq(ozCs|Bv?cZI1H_yM>Rvm(S69Ig;Mno1&Z$zir z{FDJ(yfBRYzp<@ONP*z43SQ(36ohh&QV_wDw#shhX5*{%5f#7{FF375AiHzUhQ=)w zB)qih_%3rbYnJJGLw&@9o0ti}Bsasa=@{Iu9jY6kGqx!x9<6AQ*}m4btFF;4hr1p9 zZCZ7K1v>Fs4=r<!GK`PO>!tSi9Eu80bs~VjhSKa0?TdSrgLfETH}kBg`QXc>-`BwY z#LuX=Cjk@}L5@<;`SOh*<qv8HN3ydI$vX_L-Oxa@L<W7D{T$QP#q01^ngg2P^CC#i zMQW0xc9%0)Xd@y5g-K?sm;7wZ){%%S$%>Yi$>r+q-PX(dk_GLOA5_cn{aWmt0FEY* zql-wx*%g-4mE@};nw$C4@|ld63kr;~!diaCo+xIojRm{1n}eV0Yv$D*hs7#Ls-Qvi z$c>J#P^}@Ik?qRQ(CR~d*r&WC9lMUZ)v4Z8(cS(`KSLE+GCt;k9o$3wfG?8(-ebr1 zP37gb*&EouNTMX7*|#4BnScK!p11X-zSh6Qmr-!kTU=9)Ne{b`&}(XiRyH<>Op4?A zCGUssWk4G+=hREdT7^O8SsE@YBZm=cJ~i9EjJc|uVin!)oK<T}8}efH<~jPT?YDR~ zd~uWq!22!)fnzvO!wWHl`dCwUjWUN8qUWejQ)dSUcTP*#GOvkw%bgZ@3rxS|s((k3 zn=Ev`hT|9})8*VjAq!<ScT2y;r&eq2o>U{l4|&km%UO~`8d%@49>|OnxsLfBnqwxT z1rlu1rc|Wjd+JG-YfPop$Q~{I^xH_Tbh9Cc5mZoqMAjffHgQoliS0#964<H^uYDp3 z4ML>=Qy5@~QwdREEPX@db2f7f4&+|}(OEaY2n)l+xA#3C@|pS|Xs<EO8QfErl_e(B zvrfzF(Yp+zY?OvI={SxSD~JXtVpC#=+RVaQ>M{hofk5Zro~5<nx0q#}_}i0^x?N0- zMrhpA7)G09)YEFJqG;ZDtFU>>jhd4uc)x>s+*})+f^ZxE5`EHtz0Fn*Z>yVp*WJ^b zJ7)nwOr!n$RFQ4zEvHec1_VRwuDV-BS$SgI>OMsc1`+)5ju=-L;A=KFR7AXnOF?P~ z!NzR+(ve(BQvb)(HwT(t`R)=kt&tZgMN()>KBKGS#umQOmhF`jB-ss#6`F%z4|AlH zx>6G%IbF+)!wHe`feQt0=?MwMI84v>U5}nSAEHt-x%bd1mFeq4kXo-CQhf>|{g%Eg zpCgM5308eAv2=(*QGK8`aO!?o-9G)$$QST(fGDz(DTnKC!3!hin4NX-<$KOA7{-N5 zmKzYSuA;lhKGoJ%SJfeU2_fA<{Gv~5OQ*yz)~)X2hlay}*9o_Axxq!-0haFh<}*-l zbzHq!$W|!Mq)9AJX!zLMWafy$qn~`R%-AqSa+fFdmqzZ1hZFJ!c>c>Ar8OG9v50L^ z!A6&cx!TpbN5~FT#V_lZ#k8X*mmk}bq-=U}%6_e2s?_JoE(dM}AP?EzYhJTbc%1!- z0I{joE%HPofMRHC5A;q^xp6>&7yn$M#-&$Z-xR^JvLEj5mR-+4f*@oDa6@xq7UT5h z&eIn#TFm+*NW)vTveF<ZK-$BnR}o$6tj=uNCyu&;=oZIZo`NU5g`XGfp!hJ@y?P4a zYfolQw`bt@nM{WicqH-~MDZIQ{L12Y$;>{@zWKGLPfQVClNHzz$T+wk%S7x^;EuJ% zk_IE9!MZq!N~2(W9P`$!sgU~A{hg@~3(<i;*%tD;$-N%!Xv(=cM`Mb;52El=6l2Y$ zVeDeKkhZNX2@JGOi&XhUXbJOnz!`9j8fJ-#cpBUjxmcSVwIKmq*w`>wsm+rUd4kUA zCn6v8_yVZqFOo2`lH&QfpyvuV-vK<N&w*4dq{zj^(W}q*TBOemTYVizRj4V74`5PC zg>c%<+q6zFW<)Q|d`y@(!&`aRPiwjXDk1yk<}WXgOimC&D@4nnrAt?Al3HD9n4SnT z-#3*lPh4p)xlQM+-`Z~MhE24nvE|-c-Bml8ai_-|%nuwT^BHw{2V~I%<%T9ZALZ_c zYcQx>(6n*UYxNqdlGH26-4BuOlStzK5Uv~_wPL6Rr@|IuNLwk-!x>Ch=B@>3V0z`W zGUalaIZPffXPFB&LtVEV87kf-E{Rp!eo-#FW$&1fGE9_&YP2YT#~L};Qv!ML&jYzl zRyEOyIMPrF4R^e9W536-54ELb<>kqr+wqS~+|J$kGTv!t_dc&w6+eN48(}rmt!e8y z=I`k@<0#3wgNj#WtI~gUWGT_ORgMT@G)$RaYCwc}LUq1#^j7t#v#F`3{IDX!_hSon z@tW@J4X9K7rsJ`&%N1W#F16~O!n+!bMJJoBmLSZN8~)}s-U7;>>j!uybh{VBo0UsP z9Z97nk6xv^HnZ+{yHP0bM5DSAT(`5d7ofEz95gYd89;RnrI9{9a6x;LdhZyN-=OS! zt)Z)#3A1m((>n&4Y=bSmV~dfgX}Qvd=&ANO@;yKhtsseI56YQvsVynYGaqlWvE{2f z;o6hbKicsxXjbF49At`FStjrAX4|T<zD%UVug@b}W2t6yTTki$hJRI7A-Vt$*Bje2 ztT%69D;6$J?xMOP#qRj==^%adk(29i(Si(Afi*x5dytEZRmV@c2-l!o;8CfKrFl*q z&DE0F78e^@Gy9p~U6qeFrY*CXgHvn|%Tyhzy96UlT`i$5m>Fcd_O$?C>_)9fYoU0# z0%J<sb1Vg|W#6GxO79a}|1yu2R9j89R({um6!QMt8w#0MOT<K*v`Rn>dg9a6i}|eg zroI-XdgVCf=P5h_1XOO6-qjJitX7UOJ))`7>0FP+%j?0TSw<xSG+Kyf<O-#REp%2M z-E$K1xl~HEBM>dayi<q@bzWbkGr<IWL;fC0zZAHy)79Uz&H9OPwR;M_-0kgyi>&LO zQEvC={H}A*Rh2>^l2}%s?{wZ>Fz;9v8APzpw~`pm@^de&Cvpw#Z8IyPz!Xh35W%r? zG+HmG3d4ji@*N~6i}@T?$4lK&A@`O)N|~h3L0eDKZv?2~X<#r2_s4?CHdHh{?>0yy z%~(@`&+f$dBQ2n&nzF3%;h!p5c7V-F&K?i4go7RWY4F!!H&$!m@8qp<S0~qYO)6AB zhf;En9@C4O&fN9QoNRW1ST!Yfu0upC=(&{_TAwUlbr$#Z_0QpA=w)`6Odnb7$>+pq z-StXD6S+v~(G7FGiyv`3<Tf7T>D~NUtOAj~E_#s*i@?3OvgEM?d-f-E-oQbUr_a)0 zt3iuV_Oja7Mz_-%0v&2D(z>FzFAXD*;ix!Vuj%6F`Vx}{zV^^@ROCt3Ta&%zyBg>G zlkdF`PS$6Bl`UAVM01spjfI86>~e+{=;v4hZ`U4ma1j|y`1(k{R=MnNV;sZxGqjsh z9YX`i7!E)oM38f8OoJmV*TqHQQ|)k}`vpbvn~07CTC*p<@836@Conqhw9mB^YJ9K1 zMfGj?g6a<F4x{pYHaW~7k`^aM8X1K}tQmPBD<cNUa+r7+D?b$tJ2JRbmfAaH{6&%@ z>c-QwJQ3jO;~_pmzqm2wYb!wpc2Q59U)M+)Y#IJi%p}cuM6(>+|K#6Yh4cR1hlM}E z{~7TUD$YV7ZT+)Y=o7xX1yrt~^cytHQ6((7Hd;4NUGCSm^f00%+@32tJY~>+XN`9T zz$wvcOz1^7hR$FpHre&3$TBWt=5ExnA?*JMApyAi-@%nLR0U|5f9;uTqjZ4E^BrwU zY)O-{s9dziSO%<_Dj(KAgIt<J>6@+&;<XeDtUJp&C<O&&cz81Ld;b~Q0kHAEfh+^q zfBVRA0e+U082AU|{!d`&o?NQ}^Jzj%v~(J9$xyNoRwsyj;|yr2J{TwZcKsU!>21us znHz57$~-7Tt=3Kl&>Kzt(maFtKrjC_LX~ph5ey;%3Y*TbF)VVAOnbW!$TYj&@!!C^ z^D8Of{##Bm?AjIJjgL3)e|!O(t4)#~dmJ-H`6obC0A00)43>PB=;69)!*Pj+Q-p{0 zrS3)ntRFaE04UwLwNDT^J+FTP=w)|WCXgtW(?sM-Wxzu~Y;S7|G+zMz?;q`G{{gsw zjW`AL8txK%vIvygvezdDf(Zce6GvH!f~`=)=Zt}zD)wriV{;n-s#D5BGZ0x=KtxL; zo;MOe;;A`GE2j`z+A>GecypaOc$RvsvXD*T5H%B>E+Rop@_QQ1*<JLwGh*!4PpX<* zsuxm$RD!b|aE`+oed+M13(9;^jn_*eQx_IZgB-)+as&sHu9g*QP-uxpYRU}{6zh*> znJKK6thD`3pZFJ_2auCzNTwC}pqFR)*)m()z0f4))r1y-d$r*+amr*?*F_<)v#0D6 z#h-fo(LX1o(9$V|o%6%Gq_=Wh&*hPnTcMX{e*lIG6u(oE&XNhBziEcwvaUb$_%>!% zN+?ET1%hNyK6)uM*zO4~#<Ra$?@v0BMdDwsodDN<c2zz%bVNOjmOg?x@W9~hem?DD zr$hHy_y4CZoCk7=&s5c0F52M4CWh$`bDC0(bzQrz_H$Vt6PsN0&mNquwFgj$f3Ret z7;^-UmEy}p$89yK8OZ&scl^BH{?1MKox$@r0|j*b4CyKMCsVtG!XmalimvHTKm6&| zY-|8*X-@K(dPC&dE#Y**=#29I|F0^1{=W;daH#+=n;kf?W86SlDe2#G`2TN8>@DXA zG%fRo1d-S&KNP&hw8*Eh&Xk~kX)D*hSZT@J($qA_-}l1T4$7qm?)(>R5Fg)`T~%Y{ z`P<s(WQa)7f_FJB#Fe5|+CiJ8A}80HM^mK^{3a@vPa7BdmyXgJE#VVW&o|}jHx{4U ze6Ijfc#WG3@@hreR*+)5a0cmk3ocX%BvolrCmX|1l8`qdeUE0+JCZPIRyq<J-gpCa zL!Pt{&xTO0ur$|B9@GeV!_};sV?yhp$ak^uI@v{3A}WjyH;017DBOltv@nOYob<{) zw&YNb)f)Noay<=dTjej*^Ujv_ews-qg1<}|mq;xp_*Tz>h36myubwGYgMSH*i1XDj zuW-X<y9&O1D{vRWK^}KWsI0y@#N^4F8V#RR$+B#h6mP4Q+8o4!!Xw2#M24NkVxMSs zOfaa`I4xmW-lj<_nLAoWKPUjVoV(SXN*w{IEJ-&vQ|~X{2lvMUk^9!tt9U=zV+4<S z$TJD%X+$31LpPIjc|HRzkA`$EDN-ihuD&%jab2uPush)zBzxtC^Ur+A^xE*CR<ph| z@?FI2MM>G<wM>hs<^d~G!=#*6K(-hl@pDgPLZfx=vV=Pe;UVHQE0EmTia|jfyOnVL zb4lx{-*Ydk)%e-lY8R_E+-4@+E6B^IzS_Jl$|t+cu*_TfwG}_mHeOGT9l513JF6}l z)hMCA(JRE6lvKPpd{kfBKFisKk7)GYe=PA>$;mKy`m=Zr^T={|elMfJ+f=XkU|R`Z z<-}W8+DvN<uwk1Q0B3E6gYP(s>XzvH6HsOMu-e$r;zk~q7YY8}Gtqh&o$BF`D9_pM zd!y@xA9S~bsvbJ}Gw~QWxxHdI_yl-mI}F&*&#@Ae@zr?*SDZbNR^9^bFdUHw9M<n{ zY?s)VSA`B**80A#zw%Ux{MX0er$!eqEY~^`UIH>#&A&*pn2U@ULG<25ELps|!Tyi} zuLZBL%81B_B}jEeomyVCi;^j5Ai!p?2L}@D5lfGWzN+KbZeyzlmyqGtk6KaEFqJt0 zM=R?sxOK;ImDU6V;QU%)6G8Lt5wWkqkOl^fR4{4iVr6X0i-Vj4IDPA2`>zCdZ@Y3B zL{3d%r(6+~!g|i{eeZ3k@kTWEq!oq$c#-WZ=7D2y1`xn9W8D(ItY$J}D^pf;*Ss{c z<!@S9at)?XdUBPkc6R;zRx;{0j#Y?Q?Iu|DicZs_R46o!5)%&cxj5qyiF%8Av%4A} zXJ)tc7j}_3#Fy!Il~~=M*ga?EfWBfW-admPT1x?ehx|s7`FeK^9qIVJ(n8eZ;1UIa zKj$j6+hCWSUcjRp$swt*sFFo`1;NH&+k$)f3m;~ht5XIM_3vDv@_3^)?t~sz!2v!F z(rUaXni3QsG|X|Dp&)9xs&IP{l>~3Lz9B9mY$EdIjgh-Bj%wkh!0R^k?puaw&*D=2 z&TUmVl^W&7__z6YPucKwQKlse>m9N{a!G3u#jg6%Tcr>YhN#9w(=Y~`G80w1J&#0Z zDOsJ*vXw+23xrEvEYczp9kq(!_s-GNS=2LFdw6kdAN-EKwzS=JQ^-{4cIMm<Gy0nB zSIKL$!)UpDx2GA0G(I{>$|e)81caSRyrF{O$y2CR3#OWI`xv+ufx{$Ih<pP90^aCi z<t<Ha*N2nnu4#(Yi}{QOHBu>;RfCm+_#gNfdbNSZcuVr2o6!exiCFak2p4mDev<@L zO<En7x}-mqmZ@1-4NE}vv+tJB_hMyYE(b+nK_)Tu3L|-XxmMBq!fC-zvbdbIiZ#6W z@e$?4MxtK%%<14w7>=iXmIE&^uT4*2#$8x#WF8K%$y%!>iZD>M(Py~$(x!S@{G@H- zvO7^ImJ29miYln18^1b&@5Uvd=YCiR%~Jm&=wstM$5*X{2In@}X>siPsY^mUMiEyG zES0%pX5M_zYU8?_^@DC^;po-XBsPr4N}H+H1JaAkD=9IR1w#ik-R|0%V%3N-6$Y0A z-Nv}}g1QPb^A*0+TcXTIMuv$?7Bb3>440U3iH6#RU4=z!X4V^(d3sTwnMd;TWW_#V z6nq~_<i0C>r~O8DyP2hw0;sme(UA!na}V{s7pN(+fz|f)y<^H<lQ{`a<%w6jQC`02 zm*<Szq$3Dt3e;m&LgYoVr+Y6gRr?j*e;Q+M4y$l}Q)F9<AmMwWlHs<H{q8`Dimmu& zsn(D@-TVyo+U$ukHu)n&0^sOeB#MJQD}`66Ca&i3o090M=#a?k@0F54^%WbC!<E|P zkOM#2td!v`p=VjqTjLdFqUEpcxU%EQCzh1Kt={W8IE+9GYVD!4dUT^f!(IXc<L_Rc z;H<E-q$cH3ktK3`-=;i3YUEo#^|bTDilP}tgHj_2mvyuBr>p!1d81(?-?pdpbBrQp zle8Tv&kZYFa+xLh6`)zN4rdY(R~mLjXsV+Zg~8=Y4Fl<F7w?M4_aq-IsaE?(E9^~p zO`+o%oRF6Y?m+q{BWyj4*yC~x84Zv^%~5>^1ZNaUCxV*Ph|L1^hhk#ogdbSbkKrpC zG{dP!*2Jr9CnUs91<uo$#+xq3jz8SV@!m#QWQhCzCdd@~HOw{FQpMZRMerw!yl$*0 z!=x_S!yt58vNkKX9p@fF3q?{XrY3$tFT+B|(i3XcM<=WYgu^xhg!Za`;wF0TFs5Hz z9Vj-QG1&O5W$3KdXA$F7=cc>l>1k0GWvj)1Ee#tV!CNXw?3E&1JKPF<ck1%F<mC@! z;PMK5w3eAffTta>W(Mugz~YLXf8yYTHyx*b)(cJ-l7Kvg^FW{syddYk?+&>4*;@FW zdANV+K|ZWg5<_g5160!z_s%|vpKH-oq9rj7gnPUacwKU;Fn_Fb{&(hM>)A4th8bra z@kj)|VXFzR0m%IZwxay~_>any6jy(zA;tn)|G!=Dp8YO3>IoYIf|@{Ot2~mDpdZMc zeW1z-fNTokXP@#eeEMA|g`*uXBGx{}Tc2JkOfJbi`}FC2rMv*JvMUNeyz-NT<LDVn zyieDg0VBn$$G^*0A=f8?{QNOW%XR=E-mEJ<K1ldI_?BO!<_zzAT%gHhZsB%1Me<ei zvCRO}KxP#JK+7=VDNvJ|54cDE%U_?w7sy&jTCv{6!?uTDA$Ha)X32&A+*!6)pboAB zWgemmVW}N|Tj9{2>jMxgR|%kBC;*a;NB%FP8R{|E@(64jz>m?s!#bCRlk&`<fjyAP zqDG6RNV==$K|^tEzeB{O0HlNi9B^P7L4c<1@8ktG7=h~r1Az!S*_%U|9uHGPQy+aF zDC2L<u}G*U#kD;#Rs&L8cj3g^*v0!yNbEZo<n9{sa34UL_(zDjqkZd>V<g7X7sxAi z`i2a(QbVLaDt}$}-p?-ftBWF$y5SlTMtOP+R5Hz!2EP0Mce(rff3$0eFh8-rF_9ss zmeTX#n`@3bR(8kbW3e?Utkae_A+`7EGVFgIH>pVON@`4;KYI@BimHuV_LKSfSC?FX z*)skN>jyY|q$ZJ0BpkeO%^Q&N|3#8lBK%qwK(Xq3B1Z)9;VQB@jpv=X%ZJoimM>OH z{6XC|@yevm3kBvN{An1mwsiN?wf|}4o&Q{x>Dbm|!MjCzmhZbrY!<6^@kU91o8XZG z%W-B)03q!&PsX>DNL=PtWHa-DePDmZ>8sc8eLz_z!9ciewoN!LJw3GsoX-^j*~-1@ zQ%^d#*D|0p>tI%EmF4)!v?Q%SW3eYYStsW^4@X?vvoS6-koix6{9PseJ`4QJo&%lv z*$Z&VJV3aMy!)zA%t)puKE9CgU8X<a#R&Lp3xQXFW&AG(_3Hbqv1htfI4S6g3XRuv zq#}Dw1#Ezr2C;R^OMm;P^PXQmv)5G4{A>|Idv3^itZMdl1+jn7ZkKBo1i1ud>gQoc zoTva${1#rr4|{k(HiQTpp_rZ($64hRMn0;VbiG;&LEli6N`rrUCuIX0-R$VDLDI-G z0cZI4LYp5&5X0ql=LM|a{zXy-CJ4MNWm{DZV8Ie+yC^g)(l#Vt6pb3?m6`Pf4pD`O zaK01jq<O0_^tyF__b%SwLAprNn$*!O+xD;$DH*%?7fJT?`m%{&Y!J3@#9Po_S~x|m zoxUzoW3E_pcD2xzbJ2~m&5Fs@5jBr<J!~N%@`SZw%}rgZjrh?l9Vv$ONGkbEFQH1Q zyV=(m9p2@Hixs*1-YI>ImqCFqHld@9+hj*`yg6TJ&h(gF&qD29d<dPKW$c)8MLmkp z?7bTHi0Z>fU91`R8^ToUA^4I!9ZHi@{TtpIhH6k&Tdu~rAy8kdzqzXS@zG`1C+I-+ zl%oMX_bd}(WuzDdMT@w9Xwbm)Z>;AMR1mn7Fyc*UoxY29Sjvk`cn;L@0YXzmb9lq% z<r@}@wj0JauAEfjSFMzJ71adaXl<_x%4#t=&=+O!_Gx<a0?~?e6tu)H-Dgp^-Y|Wt zb|f$|G&i^x`jGL8kvd~4tp|d+MJw96aHKFShu>#-Ew7I*pGSp~m)Bq^*C>0n+VKK9 zcT)sa7du&G9zcto*^cxT(r%R+!#O?QX>;NlMt?&FbxSdjb65^sss1LX>srD1aY4Z3 zg#j3$9UOSG1A;2O+%%tnagr$ZHW-wU8ETJ3Rch3!iMW4`&}V+C0-ZKjJb1&b?e(jj zGx5vhF9Jm#;Q{{LX9E4$a!srbRw~3d``g%JwHTwD-k}m42(F+n4$-O1_Rw*EM+|eE z%Q7aFJJ37LttZ2{<9QQ_3iz^O6SEnU0Fkg}2HlkxuSRoii)Ph|R15uFxa#%3m~?W5 z`zMq?i?`<8;_tP7kdFGc+x-e&5v`<^TAOIF-7PZHXzc5NKne{$cg+XEvF#qa)9SsV z^5u*XCeLU>xlJOh&5HT0rf68%ob<h7$eOE?p3Gj)QCH|6AIaBCf^?OZSq8SlLByK@ zj@ViPJ-)_XxMWPWy{vGRUAQiFO67a3#_-1Gq=<-ih=$-MxS#RL2fwL`b6S6qZ04Sr z5QN<)wswCoFaJ=%-@`djKt4BMi&8~72ThaeVgw5BJ-8Jk_kmsY9R<r}_ws34N>&GD z?F)f`Nq>vTq(mbq;MOl82{zl7(c`v|r80E)YUTEIyjQpG@RRR~FTH7L`r`$^@XuO} zn7`vpikI_edjX!TIJi?;j<*5S2x!NS(n(t*{AMY1tnG%02Aa)`_x7*R?h_t^`cRDe zP;s~UxIEHf$VzSgS?7ToKVwfkDFMUXV(;w#*gJsLUxqgS`@_2l@rUVl@wy&~u0<&l zBlDA9$i1(!vFBAn?n-ZQG&eWMmqXK)RIXZe)2|K`8Z*h#FGjN%H?=3eI<l0>*GpgB z^>&9AqJ3bMgkLM*GB|-|5=~GNT5#;Jrgn7?VEXicN$I8BN_}47K#{pc@cUa;%1)h8 zoww9R*1Pvh-v)}}9Y2@0mPQk0#vJkfFVQoOYPC4WH{vI9E^tcAiM8q%0e3B0Ub6MT zo~Hi@;pP<gQd|7VGc9`T7a=c(lOmEK<_k+B6)xfHa_68|+o3l{1MZ@8zMDT{VE#bW z@a;8nyo7Pu|M4j9gI)5IIeVQfx4%d>nob_zb1^`guZhBW=u4D+P9p++q0kCCq>Q6O zPTD99i+ruAa}0$VDkUI#I;lpVWrb_}yq)aEoPMum+{~ROxXET6Wv^i6-^RC-_p?9M zkT#u%rKv>qyV>-BUpx$?A68G>v0yU&({5ZP_+TKHsh<o~T=PJS*gKMAWVj~$On&$d zu2`wr2NRyfz@L~x2f<d%|EwGUf_@C><Sd+s0WL4}mF!9Di;zm)Rmqi1Z=Ai0`(j=D zgwIF2xQov8H+%afuxURS*cGsu#b5EqXm<)Iyoq?LZb04=;&O4YgRZycl6{0m_-(NV z_v(`mJ!@Of#h~tX-u`?V2b=$JT)JV5+ksKwMLH^06r`-L<SY|7@6rzMovJr$bo=vs z`(E`?H#^$y!TITj&%U}>_}AUgSd3*pErz*nip`I0!g)gX+p$8Y{qOelzY-qe9Gg!y z`dr%IZXzojzJH6m*5>cxJg7X7Gu<ze86mcyM145_T_XgCKmIOQK}xQ-7?mZBLNDUP zr_@;s(n9+NQbeOMEW_0cHHU8k_&PquaGYy~UbUX2U6<jKm%lS=Fr8>COAF`)1n)hT z3o$w2F{-*<^jV78**WQYO4IBuB>vTjvL#dlbAFvUEI8m9z*A#O_6534K5KZ_ym@>- zVuKT+s}}b$i;RrpS+S5~z+K#2w7bH&6=M)X7IroWXKkLWftRPsTc;ZD_jDD`5}7Ez z9pQf=JJzL~m(bK;|Ko$3DSd4}Ed+@$?r;xHW+=yN0C%4dd8SKA8FOJAzxIzLHqA7? zyA7LJJ_w*^aT4MRvi+!|DIGG+|B-8oO=Kdr1x$f-oC{~p4V5=Wy}G78y4U-VsWiaG zJ!@*b#qX=efo~`T<Y7O<Y470i7F2n0mn$BP@o7kycf0ZFwCJ0-H79_xvUqpBxu;X> z)K*HFq}!?)#o>a1ehTxjYhq6Ny%0Mc&lv86RvQnm93EyU=~c1x!nR)B7NbzfC>*iL zNUvB+ESKLSAqhl||9qlD98$QBPoivQR5&*QVcx8YR>;X~E3zgVM2}vB2;0}Z$%^9` z|JEckS+4GPD@sf@3H)f~g%*&kn4!|jE{>}Xnw&eigka+_8A7~Dbu#h6XZky2K2A9I zeb?Sp*F(ruR3kgI20S%~QI4ILb3K1_Ip`I}mEBcaZ^);+fn_s6+sWr>_V`+OJfGA= z?=!o%CO@KsX3V;F6<K8z%rPs0Jb?r7^ObD+?N(CQ+@MAVXrvx?F*IQwb~zuJiMO<x zGDBqawy=28-0#7-eq*8OSEgKi`|6ovSUu^-MZDSgv+^Vf`Ygk?8YvmIuNw=M3l_MT zXs>RgBlBZ+0TlSsE`fo<K{}8nE8hOYPoq$-QA7LiT(k6{5H7|p1f<KCPddl0A*i)r zr=|T){`KyIeEbv|KGEL<P$UZMl{Pspqb6`85sIpcT&<q3*VJg=S9eY`&hd1In!jPX z-<4LI8yVn_>Sr5=y66qwsvqhNNtknfen8zE-_!l_;0=@TI^*SQ0er&x{pTXx^mPdS zcpj8B2=CReRgK->sz4hINXQh4xFcu|8p88yM>yjK?^vOV6Ry)ql3ibTCgDA*z>j4J zBWMFPW}zBwW;w(+X!A$k!yX|kHEP5Q)%N`3yPSL(l;J;B_t4ZWo66_051Sr&(k8@P zv15H7H;m>a>o0jGxL8ta%<cH;l{aKe8dd5O`T|*@5c4;p+Z)FQs1MCDIf8cUI?n0N zHct}o(jc5mg8f&}Y*)P0>FhVrnCp*)>6QW>oaRZyUJcMsQy$p#nd+x#^Enu>{4oC0 zXNkAu6Ew$EUEXW5)708w`s;&RiJ*Q;JpUYlw&mbGF1HmF4lg@wk=v$(5HBM}=d@%G z!-P}K8@#oywYvp>6?6BAN}zj3+KJ}i47b}=7{{NUNE0+-jYk4>u_gTvhI{}y#agu$ zH?{<hwtTpz_WH#4AXVoybBz7j;N-Umo&Zpl*_Up?oHvB>(|UOZo)9qPm7_tVZbfay z*v7{8h8;pf+VtU%stV<Us^Un|6v?qGaiWTiToHEBHmTHeq-fA3Y@lfps%*mW5|eej zQDcl$T~fo;Y}eX>Ct`o>um}Fb`YIkK^*POk7losV_sadrBRzQF9aUP%*XKGMWs$|S z^OE;u!26I0WM%|wSOPfF5I{_YL_jS62iRQCEA8qZkAW#EqGIpv7d_(s5li~qGkvc= z4}igEaD?8Ow3a_%p6|<UcdAL4<0`d(eAsn^w@BX3HP1DH)MD5r0Mi4wX#EZG>FeA7 zr)~h{tu+Tq_soY!BpBZ+(m#%2Wwm?aA+x6B0y_ivXt!yAqS%;I04M(n@f<!k_6HoK z?T)>%Dpj>(YHpDnZ)X=BP{s804ym@jMTT|`tW$4_*hmA|U(ud(CsGOd5nmY-iKTcT zKz$_{kjE$h<AoU$TuJ~o;w<_y&uWupehnOB-_t2rh|?IrK?IyST>t?4S@_NS=cB;; zFRvxG1Hc7qQeJbD_ls%!tRzLxCGp&xPX!Xx|JC-GMmDUIdy3dFbab`iPux}PDrHdi zt0-%5U#7kW-M4quoQX3=h3!gl#GiR9vwt@HZ~7sHNK+$dc%)3qzOz*&R6Tu;dc(sg zy`iN4=ZZ)a|093py2_cJj-1kIhqUIJ-4+46C&i}8d1rp?&^=qwP~?wQI{QG^3DkuU zF7tCoYdo;Y`nl9qPR67<wewop%X2!S=O3MrdJ9_+;5mH>KP7X?`}AiQqD52zDm=kp z_zP9j4Y_IQXLfX~*I&e0N;u-Pi1(#HfKAe`(bs@O{=eu6!0-8AKbJg=AXyg<c#vZ~ zrDo&eWoC+T!srFte|SP3*TG!|L!IGV41qndAOtWC)_lKRu(x<G1OXc)wgv{c{mRCa zSU{Mw6YAqucSS4Wi#Vh?#QQfat%+|c0Q#olK3!quFYp3|D}Yo(yx`-t$kPjsz`=8< zwG_}PD<ArdsH=;Sp(26K{NR7pMgq|_gjH3>9+N!)Hs2-Cl$pxu#ZSPmzkMw;#{irj zd!R1LsO2+g=;*TkaP(-#g?_607vqFcaa;Uh2g0R562t^xv^DYR>RC4mBc3z=R9s3f z3y~abE4Wkb7*NpjJpS(XeU?f?>&;>g;#(cqT$9SdXdFOv@q)MKKatM?4q!RRQy=#Q zfwYp?w(F@4^}4Iigqc`VZV<*9w<Fq!ZNSM}VF90>h@U%aX$<Hro&t2$9tE6unu<hC zxkQWTo)~3acmPUP`N+S?bg$g$Lf#jE;c|t5_Nar1#H--H$4w&D3Y1x?0UR)3!^RAj z&x`X+W>+iBOlLX-%ekq=pJ=ci(DlOp{`(}wXUZ6;okjvD_m?E><iJ_Ol1D#cO~!6$ z$<Xwi!`*Zepm^HGN&)ikd5!(oxbM>!z6JQj|Ehvl2maUR7DbcFdAo97;dd{+yQu6> zdrm8&;_oJ$&Q8Fn)4wX;jXwXFH*UI$ot&{!VU26QkoEnN_GdcqnYq1Yc&1{3vC1hT z8}>_`@&qq%p;a<PHuLM)ivUV-C0erEmOtLh0M&Ms=p0WNi~-6L@Mt{T7&y~~3*Jp2 z97gK&Iq_}PI%NyBO7`T>>v`yzOwFzew(Kb1rAp+Pxiu>i0n8#h8mfW9F(HsM3($>I z6fPy_%Zc;Q{qQ|(X)4`T`qTC2|8cO}aIAW47#s_1^Z8F;a)Q)p*#W4+WxddU&T-cd z=9p!DWHSAISD|-ttG^rhoP|YuTcj1Zs7^YzX;8>%jRYtaK?YVQBQ1lnW{S8mzLf`? zv^7R^RBGc%7{LPX*AEE5D>cX`kRG23n`8l$H1z3B^l4d8(R;U-$Rgh@WFBnEe6eGB zo@n^(!(G8EBJ3B=x4{hM9dRzeb-3l!t)nGVV05v%aoCpHtcg9t^A7Lh*K*>X<)3== z$jcb{#iG068LfkTcWe5EO|`u9)uk$LFATnrvP-M3PuK_dA+t-w!tn`hrFjd9jz&;& zasMnW`JLFx!(7Qk^J*b8$X0x1WnJ}M_Y>I_<KyK}0vLUdL%9~)B~IVS5yK%7pJw17 zT0ZrN(=_KhjfMXpy&B`sjGl)Vi?QcH;d9saG~H464qLh-!{>*WhY0ry1k7hl9^}e~ zRVQx=q<!E_r85r=nXkV1bW(Nf=|+DJ<hVVqP<%DVIeAQZ)SY|9ysyM2;b~)glbpG2 z)|1^Z{a+C#$OQqZ)0Y74`&rG}{538pQnXX?T5Jw;7v)F3d}Vc`RP7mv$nz{CUA2|j zYWIGWd$xA?9TaQ7NKd|Q>npQh0lg$MH7$uzISN_BMc(h~UfBg|gPM6@?@8rsj!vAy z9pcZwNG|wV)2zX1e2ZNSaX?eAZ6aQoiWjQ-DvxECmEXCSEjcEMYt?)HzB8Ydw-iX0 zxEN8c+);cQqrghw!LQ@wfQqH3$t;@GQv@OGQWol(=3RTlkc7tNVZ>auS@6SeN*)yw zH9h%DEw_A5$5YXTZQ|clx!xKnvoWz;)NiEgcE^I-QpaKgsUXbmVZL)zrv0wP>t;qt z7mfYiiAQqgERi8!$_gC4-kug^ksljT?BF*Pb^ZWBEnh9>V&ZFe?$S+Yz>q?u5nl&f zh4$9xDYM%_H_>ZMqwXqH5}{E^jLO+OnpS#=wi^}@{b0yR+1FKGAWPg*U4JR|<%!hS zw4%UK`poM%#Op}S6jW){l=+aabgQ--Zawu@YfZ~T+&jk12l_$7=jFZ8B5wl>F(<!; zRN#4dqtI}@4A$_grme<<`NGJdQhdtK`bx^Lrdm($M?R~j52h4$OqK6t%^UR|0Z|ZG z@P1zjnqbz@cS6gNZ9g4wmrL`sVe;|HO&7~w<t$Kl8q$h=cSsPbuR5IB2GPKrwcmkg zD<g$?3=u;<ySZzg){~a2x*Dtl{ftkdn6jVTt&=BTxbE^StzEECpcPf1yW|ngrR9;Y zDP1EVA>F2>`}{C|De}eFcqd|PpF$EljomDV19f3=sd;K;p0P=|%D6$xaO+sIa1?fL z&Cn#AcLZK`Fr>5OmHur@?@%1}6d49^+=0B%suOfaJ2Fav8y|#|WZJ5%%Mj}*FRo`M zJG#`Cl$;#bLT)Wo{4FDjcSp@hm|W-M^I;@b1MmQxoDS@t<Y@&(98{<D7ee1+T9^s7 zLE?UsK3O^{6`67&=hvi8o|^v{$hvMuM)u&DS{r^FIO{6yE_Jc2t3WL1*&c}Pnu8^{ zUGhblD3j+6?W#v{$|9)qjK4Yr+ziNX$1~hkTHrkWjC8iX0#$6yq`<r6<DY8?Jsm|o zd$v!vBQzg3Fc9$TW->%gpSg2g(B>^gT&thhivf(=^*#?@?6`%2lLnQvX1nKsXYSAb z-k-b=9`^RCDVQiYS#~%a6+%x@Rl>Ec^I}(_wcm=hig`!EMg)H4DrfR1dJMa0(S9q4 zE{jiJCeuk=RNI-)UWPakC&AYM>H0EewiHtuk|~dm#khwwk_>P9xHCbBOt_iK7wMT6 z)eN=CaB`f;WQpsh#rS8HbW1X`B?`P@{9G-(30yG?Xt)7A@|y*0LrM$$I+R9t*sYR= zQ#)sR)sM<w+2Q(QKdRbk^_|C4Eo6+Ht=-8BNIN(PIyFD{<MhIOHj=J#hPuCb@-e-U ztFI$h$D{{i&1E?i4pMj;)ASwbAGmvpO|v}10UG%MO8B@EQ)v8lvsqP{RA_O42CBb$ zbuuHQ<uSQC#04?EbVZnk>Q<BnErjguhW4lKiW2soJ337*qMsS{lRo?JbbZMf6aO@d zpw{ZI&!Qiuc3JTROf}`ujmF`HsmrwAXj)FBbG1K?v<B|*r)&)c=jvsc?9^7GB=g1+ z((graiJ2SY<6N-aR_r3DX{92hKTaKvkJpyi{Irs<0bdHE?JuX&qPbug)CSqRcn$rl zMSd3~7jn~>0i`^1BexkIgpv;g;}~K#BucM4OHn=c$@*H{msWItpt3A<=cf>>GxMT_ zf?5a(kDN8Q4OFQ|P{B9M_eW(40y#d*)qpFH|7i$H=$bMzBWr}aG5Kf7S4c?t+fk=Y zS}(<V&I*Q|iH)}Ypnw-R>sXirpw6$g4y~udMzDcVy`zPoNFPlO3tU6UTZngi!qE>U zg_fKtO%8^gY)2)|O6S<6DUmt*_g!MzMLJ9BP^c7d{(}-TPrt}?J*@&=y~M%81g}FM z@3BjXj;2T!!9b0-x#Z8;L%9olT?SgUiXhFom04FS8W^k)vIdzVEaZX^gDidOVJsmb z!(9<y=0dtjfz1Wp*A+8|Z^h>*o#EJoRkOfSS5z8f5xu6siPc;HmUAjbZ@9wk$&W2% z-IKOx@A;8>Dr_mbAtfx37GE{%PTqz)C)gimua}%^RCh0FKEAJOvAH#3T|o7qYl|b% z)i8PikcQm)6yS#oHiF$iAcIpcg(6?MUrx9lWQ*Pt9arHyQM8zzsZ?8Lw2zRu(ZV8V z*V$|uuy3#^?}tLN;KdG9h&_Wu))j>-2`zq-%rS3rEY_d<(I58P=BfA{cu;TJn_7N0 za!6Q86fe3a#Zy5guV9&I96gd2^WJBXduXYezdpCyapQ>NVBu)r8J1vg!O`wt#Uj{> za?xu;d3TLC3W7#GymQqXZ);qO$=^uK(Wg>RyfZw*x437+FJ7n>)H=8r<w*y)r0AoK zTj0^M{oxXzpce<lS)9o@^QvT#(h{nzn?ak`F5WPez8g{zoIm^Ron4~%Nk%*+15P9| z!23jopfI-I|Bjs+=a%3q)CYH;7vJ5eucNr!e)M&ya*V34(U#GnrTU}zZU<+P2B%>6 zzQ~VFjV5NxjNFL*IXWdjf82$(loSSr8_hp7{SQ=91#X<1EWVy$Lwk<+fVYY|uF<xZ zax$nT^E^Jq4>fm*p!y3|$uU+Ltv03m%IH^d$V7|_Wo5U^9sh+G0he~4)JYi%M9*`s z_eDVxiVR_<8BE4TS+u40MK!l)(+{<FB3;c*A+G+$QkRx%xL8{RT9!?HFR5qqY11$x z_)qq{Qp>#$JW9i(o@N+i@aU?cAqK6=T6DKD#!W=t026CEC`*$SSw(~<_gJ%$hs4*c zg4G=ptJ8?Couy5C<)om(YlWY<W>}vnzyBs<Z+m18lz(9QwI{@LkUs3bCnpf;nQ!jD ztKxqy!h;(968b0~@vuv1{*Cq38vCa$o=;&96mH@Z(AqIyaKIYiGp$Ldr=V_w*ED)X z%xjE-^dopOin<l~6+Lf3co09yJBL~aUeAXSHUMLi6u^Q>?j(SqH>e=CZsdjkGS_;y zr8vzeMj8WnQe9aHG2&EB>9W5|bv67!RQS87TVOaeLphT)%tl@7x?VwLt*drIW_E(H z7U8GbuJ|^{*G!U_(<OS9>9V&qg;`}*WE4<tn?k_AKw!8<r!?G!in-j^SvJW~W_E8f z<TTyj&Q5I9e?oJ}3krGNe-kK{3=yg$m^VHZ2SF^7ILh8?>2}XOiRd#|{PPGGya@4O zKY$`Bcj;8l0D)0JsJA>=I=QU(?o(8&fqa%zp9&LLon$rdKfoL+Xd3apF=(rl7%UJ| zQeoCuF)UtFwBeSOY<$7a^BX51Xi-S&`vYD5={GNTruE@bW~&_cR}`%WqF+?_E9!2Y zyD!7}i_})hkT^LAUg07=CD6kD1@TA_78ih`uO(wAE~)^KNdz5YjkzZ!i%jBjHOGkl zsU(F;rf2Zf**>gS#vWaqf{oR}ZW%d;!t+-Ts%}hK%(lj>P!|H&N|p7u@#fiv!Xg07 zeoqQ0Xi8-%@;B@%fmxT=4f~pk2nuC7r3+7RSmZaq_Gd@G7Ii8F|BcRL&medfA{h{f zH-PVBVS9AN5pCF>0f;1}dwyrtj(A%Vx11W|1^H9TMYFSLUC4+urg5<pz{Uq=BmbHT zx+F9lpH>8#fUUBdx{Lih`d{q5XFwC{+BOObf=H3xLFrPZw@4@g0s_)Is7RL%5^7YM z^hH;yf^<UfRl0yk?==a%CNu+ttZ&xd``ycR&iTIc@BBLdGKA!rd1f;6T=#vIhAoDl z3X#X3$pikkFbmoRKBi5^0l76{^;0I|@Q*wbl`C5Yz{&3Z>tyrZL*{<LmU;g@qt6IS zN73row{8ki01|*{{})*DS2PDY74I0B%~^h(XtGM|pSO)5SfhCEcr!V#{CBtxuJ(mq z-U6<*kP$o{fFyI@#pd!t_nO$m(=sHx&{=9Bj9!`!Fwpo>e)wI{h=5AB-e>i1ME#bh z4nWcWe}L=%X92F@7vQysRp1(h6J5u1V<P?S3Yl}6FloETcZN*?3wiUOOEFL2*+cK& zXp>Er-WbXYde68-wtCaj*@g`#wF<$l&pU;%B@e95OEY1Wg_QZIWQrP19KWPoRKFZw zUSVXB>pfs_9p}p4>UJk#pQkt{02;nwtKZV9cg^WTU6E4~%;)qCBV|kB(zg}NW}cWI z`;)%Yx~KO1ZLv`$Xbj|ue(8P#Lx=3WghmCKATlvO%!@v(zqiuA5VoDji|d%=U@T0M zc@DT&0a?}UgO*{>a|<x^X>G;=Vk5T9gSbO#_a~L{CKehJ`6E9vG#;@Yv2OsBVI%22 zOaFdLhtM#Am%InXFH)U~U#u7S5*ybY=~HRO77<Go=wu;Fv*9~na;yc~Z3m<aXAcD| zPWnqEex0|BemFe6cAN3FxN<SD6_;BYb{sEg6HMxJ4)y6jRQ$ypR2Wlpoh%p>oDa!i z2cS(IeVjq>LPwdWHzXrgbikd|_`FaeXIhc(=lsdKc2qKxtUNIZL|erI-Pz-wz|{GT zm8d%)^;hH~{GcPdWzi&F!12(0Q`Y=g{-fOjW$L(n+Oj!Rj3V`R%q`~5a4=QKgY6s= zj04&Ru^b<T5TWS_i1RCSL}zNn$ijq!28FFP;QXu&j7+iziF6w$r0?%Wo<BuK*1Y!0 zXEEganXRFEqDkWWD5GcEFF>QhTF3427kbC}MN?d4vWJ2eKrD5Q=(U^LhL`De>lm@h zw4l2tH+$h0JqD@fDG$^bj11^0UTCH)l(G416tQbg;Dj*pJvQ`hN~mOnNZf(3)vccZ z|G%Y4&46QWP%_i3<Vg?la>zV)RaB$4$UGt)Pv=WDju;!%46J>9b0b3@VSJG`cU22V zUke7Ap`hQ=nU?EN+FZ>U$3q%<O_ObPcd?(BE@JKGR__rJ!HK$|k>Kjt{<2PHh~|og z?rn2t3b+WRjkAf6z@nD7i*2#R$}opA?ei7H+(m4jR3fuK6|HVb2n)uT%yw<0^Pn1~ z-p9r=jddu(r1#2=hM!u*IYZU}%e{4#g3$t1LHe<8n-_H!@*ms|IhrDF6TDL10QH=( zxWiZR_3L(?BfjXVq&>6#dB*MUoL?X_$O|d!r*s}M<2>mkYhy+kfJZtiV~0xZ8AzHy zpc3R4*%xpFdZXsm-P4^wO<F@<V}m?2dF+E=vlepU*wt8!Hv$}a(DA@|l>m3oSxSLr zx()OVl5X7IVKRO?9A&MYcD%yZ>((zDEm*?b=F!&r*fux-Set+AjFPgJuEzwlsJ2}e z91op8R4G=u!XODgDL4?)guj#y=Ow`ZL$UWd6(@unV&hCeB=lv2yJHZ`Hc07sSNDT9 z5#b!+ib}ze@VW)pw)1@^neR?k-!48%esfb>G6AvzMq}6rF@xpS6yZ67sK!VT^_M=u z%gzq~f5W{PW85ETml|Vs-=*wpG^;Y>j4b`naI=YLj}`QBRtDWGYy;!5Rj6!Ure|60 zXXP8j4M|BU%|;qtW!}<kR_@IR_wn?%wK$0%cB#q@?8%hFa>=D%)XH~fi*8@ZPKE0@ zr)=nZp8GT}>zLLvIgJdMAauI{?;m2H3*X!*Hik^is>TNKrCoz3aW16KMY%WCL<?_- z-~B;+lQ-Ta3e_2pr9^%x$nCNgo2U;9b<euA&ZqsBAlr{*W^r(_1urY4p6d45+zA2! z{bY9M)w-POD=kd^Kn}xn8%Lu)F-S!!=BpKNCYx}qR3RhmRTORF7bk)jjTdN%nB!p} zz?Qe?2*cA+yJiZqK}9TT0C%`P<^y`oNr%Sjh{L09HsR)~yCY7X{1Ouq^hy2Cv`JwE z`q|-BvZMoDF!&oImWH5@(Vga7DV(~A<|vI31&7<sTsT_t(xZ$qD0TSdJ&$-h($U-M z61@g}FD@P>rSf})txBru$u#SgK}ub}!ik(zJE0lTC})9IROkD88y4ITHZfoo`$hO2 zHKx-V{iYHbEE;46-}WhMKv{~$2n4eoo8HgSaMk(bKs$Gwa`9sb-;;A#h~h1jsnhOg zLFx!Ga6tSkgC`C(Dz!it;mh1tm&(*VvNa{b86|a{(zpnO$FBHY%7|>#l$Im0jD7H3 z!w6=&(m>up@baK}ouw_m=dZ6D4!pxcvQrjXTI`fr*W{Rd{EtRO@B6O;Xqs*LOJh?@ zn~QZa!W{IyJiPRO8F&`~hEke|k-Vz@={*gYfnfB^Rd>K@pM@?ZL_j6bU#A*gN!Hxa zLBYM0IN*t&;M?-Oz}7EbJiI=fCeq2xZU@kg0M+Equpm$RaPBF$L-+b%$qm$21nmAp zXFoqtXHK0YYTDJbXP{#>4nO|bs-+=IRZ7o|X_Q~|eI2oIb1|=mXfNHBH#RgJ6^q6i zD+dDB+t^m{r93A5kFBX1pOV>188!WLo%}dP&4Y26>}1$|^Sk<GGTsX2dMQUPHWe`@ z)6e<Foc)Mj4x|A}Bhg6~^caxva>^=zpa&iTa5{8qtBq;Q*Ct9(dC?CeJEDL;=6cxE zWk6J7w;p13kpiP(0oR+!Xba<prbb;tE!a+DhW2}l`uzq`x~b1k>{{&|x}qJ^Wrz>U z_icq=W90jQM~V~tV~{Vr4|QIEU?;KOo24_M7dChrv0@=9sxvV_Etn~Cw~3FymAS$c zZ=e--e>SFB)pVxoWQSJfXR1$jlGm?b%n*9RdC-Y(-fHgRY3F_Pok;%Y;!A05Ysjk~ zLIJedvL*c9FzLvkvC<-~`KfRd9qDk#E2-<RpTDj$V%ac~=sWPUqaJn!EC=dfCOJ6J z-H+d52Ql#~hw7<5*G#`Gryc2DvngxM_vVFt3X$TFQC^MlQwl=tJ@m*x7)bt04<ymF z&%Pz~2bmXoP<+91wQj_9vrY>4+U`|&FYzFYeqFN062!nJy<aYGCqpeXpcBm#qn8$# z@PLjx$?4@2Q~K3SYEoEtDn7X>)#rU@IlIHe7s4f_kA)6iq}pa|I?>vyz4Ciznnhaf zWjmFR|DB_zEE_VN+@}WvX(jYIsZPhZN@O*sAXbHcnm7d|jC=p+*^y1uF;nma*+IIg z3iu`6V+&XpV|RuZ^^Ly#%<#5eNU<X~VK`<pL(Q)FeNZ5Sc<ZBng$F4W?n(KraOIk& z>rB^u5HjA-hD~YM9}(C~#^EN0Im-#|xi70lF)7(3=b}t==UUIJPy_uolp#RhnGz(< z2KxfZ*<AS5Yt1=+ChAX?R^lZJa)YrLsNQZO+W>v&(szNZ_}dGPT!~2cg7GY@m5MAO zTk7$Moo@4Qmsv`iFSp+rY1u{jQ!29e?#d<FNC3nz8?aO7J1{ZWc9c0t49L*>?7YH* zwtjccO4QYu{$$qcQBR%c?hV!?G457%?rzPYlFfxu!6?rAmAqm|VeygD$^1;^Lw&cy zq$1vNtZ4Ma<xY`R;(69>q(htp(D0&oH{ziQvotd8FHNJ9;BRV)*LRukPO<&I`_oNF z%5u=q?QY>0jJzt1i5~7lCXVpx7x*!*er)#9noXzosqUT?86NH5feAD9uP~!HMI^4Z z@>l|Y=r17vw1@qewehkMNUy1`kpFGt^Nr6_o$Jh=fH(gU00%R2{<(<<FV2g`6X?`! zQb_&wFMR<Yz9aA#gk<H#on`1Oz;hQjD*agx0F=PWOAK_=xgL*p4q|~*d<gy4dCF-S z{DzGVKyIY$D3NR8v0LFZdWtLqaR4mjrN0hLxV~M+)DYwjd|IY+Zwb1sZ90W#qO@jn z5dd^Gp!?IKvwv?);g10#2mC~&%>@DPb&v?|{q(Sj!S7qo@Xgt1fx%AM)q&<CQ|+Eg zcjqx%==Ps@mp7jgz4$9c0-zTt`PrNu@B$MNS%EYH{@ZHyI#A=ULx*qQY^_fuEPoE1 z5M%i(1MGLeQ7{kZ+r9i-`~mB)Pwd!Jo1aYw!7O|91o!U^cHJm3arsPr9p^fVt)ap1 zyYPaJN@0tS*MZD2*9#M9@~-3HnFM}1T#Q=n+4{})Cb0R$2`BJo%*Ct#lH!6)`r6xk z_%r#{j|5zR$d=_%oKj#h30cqZBiSQU-w6y$qJshjww`_Ht!$^T?#1S6Dw}2Q$w(*v z(Q&Xgqe9_Z*-?V`$xHOiYJGbH0oy_U+3Of&l6FCdF1GHkw()<z-K<0C{^`qNub}BQ z?>)<GXN-KDL&C-S>cm?yY%_Q(GsMvUU%Ow{3GDN$%M3hZ5GcN7r1{l7qV>dmm#Y8l z__WPkDj$oi+zSUF>DC8-)gS0qkE&vK(!K82r4X_2W_DIrQ2m~4i|3Hei#>54N*+$e z`8RG@;dD##d8fvR@HYnk!~-oJR~)W9zI#ttVeRNZ9~kz(nX{kCkN!O^>i?N`CcYbo zZSf0z!~9gFMFb>8|MU4-6)wl~Iq-3>QF*R`A`8*Khie%nxtk&AyhY^g5mH~2yz7#T zhGHXDulsO@_|yN{>FxhH88=n&TrpFOA}?MsM<!2sFU^Sj=Syq|s08i10Bt{zzdEB^ z@|pbRzmLMA<Mu6Cw>xpoMtcJ=A2Wr*sx~i;#)d(h6i)fA)c;&Q+cq_RJ((i0;JU51 z3XIOy%uO?|C3ERbmCANz-s>OF`ER>LiQe6g!At!#6&GDT&+MfDt!(dH14tzAS5a9Z zGnZTathzlm&Q$=L`s)=>{`pAm%c&zvC5pqIh~(hX-8(}y!eVb4(_GS7Ep{;)Q~RB4 zxlyPU9#0mC)?0DG`Bpi@qM^ygPVPZni!y7k=<(GHgE#8?><J*+0>FL?HX0_`e8^ef z;uxFYyjvmlq=uA^z*muiRs5{Npqrh*U4aEtINPg0j(%FB;(qsC`B4pNHD$UPD=}51 zZ)__6E&7vjv|oQG1w?${O$gBx7F_;ASO~k<Zap+^S2vlGRC4~la+7Ck?%jK_h>UxE zL47}0VvwDLkoYs75u&~p-{nP%;QW0LYtE+}-K?9S!<)YnkJXuHr;HheT@VzvHqfxp zSa@V<)--(N*4He{ipdQ({*fX&q{~&M&51~4?I<Hw>bq<e&7NKt!fB|*D}O{ct(;eB zHmrbtKkM_7?AqEExe+hFEAIfL^IO21Ojr+sSzF$;CDH_~uL84No##qgFsI2OY>L0* z4t9*@xv*CiZ*zl(g#><+gR<^+-aWHn)hfr*jA2ECndU5a0&bNc{p*D|b_QMHxbM$} zHa@u?n&sJva6MBJ^nP6PBz4TlFoI{6Z1{1Z76b|55;##C7||bsh8@^j#{W<cxGEQk z$Lvm5O^!T_&d*z^N{;sQ$kO-lTl{1`8S8Hl6QgZ$mesgJ9g9$)8%gs_(=UrEdS9kS zOS9LV;xX+4cQWW6Ak(bp*G#1;?xy$BD^O06wfkPV7DAGXwCRJ+PukQ@DhO5fY>Wj_ zN);j830E-o^ZREO!AfpN#yBCJ-Pfw_UNAAbC50bj-z)HAYlF?Mm_ml2x3F3WEA=(q zgWNSM<voPW9N=u3(kO>3D;n@CvQcFnr<>_Dr=eWZ_DH%H7p;>{()X~;+Oq=7kD_ZW zv2cOGG5ht*?4*{MH$#8oX(qy~ABjO?U7d$1O}C=F*km@%sAOs6__LB1aZ9-j3gWm~ zIg!X$V--H^WX?F2#`d^M*B7l6P}+&qoH6hM=^M0W^#Tt4r77uwP;bfXaOIe1j<m-t zrBOUd)(Ux?j{Vm6X-xz3{*!_c{;K4bprcQ`{#wf>*R^jIQnDyBHk$jbGHmIL(U@FV zi8>hrx0zLwVOe-Se?8o2DC8QtV&J9Yo$)!_t@T`UOhFb{>E9mjbb-EW(TPHgMw%Z* z79=D5!k*WLgOtGYZrGT>y*o2E51a_|M)>N|3@u}FMMl!lPnp=sfDaKuc=a*iS8B_a zkVphsV=tJ6IgSy_oEKHV6r>y&s6AHm?Zw@N#YGj4!K-m86}v{t@3>JM8^$~Mi&Fr5 z|IxyoK4T`LhzfYR8cHh8ox38#F7EK=MUC>SBwyFvH+&67EVRkoWxBZAzfdauIaFiy zP$s90&B#(rs0mum`EoS8-eu7^{rMy;cJ^UP!z#fhs!oPt{dGLiQh5zm;ve=|>~Vv; zh9%KO#+5>R^*`XUD!$r{eh?W|S-yU$4U;52mtXM$Xsu8T`ehYEkQ)gEgXA1m^L4mA z)$?FB7IpUOi^gP`%2Loyi<{^(gOcGV7qjOdQA7u#XxrX=9F0S_kUHEtp~BJ6#u4LR zwChK|K>tBFsIvwXMQ|6EyI>b@3ctg2@wVHl%8KD?wO@DM;Jo&_5^5W$8v_`qL0`+X z*%msF@8F=JLA<Q{0U@pUosClHM3y(ox5L&i5=U&gyHhCrKWxL;UC>(Rr`L&vfY%y3 z#<mwsne8s&4y1zaEx3Iw@q^|st5tG2`MS8-Wz!$fC3erneF*&U#{qY=*TT_3=VvEq zgEK&RP@RoC3ZdRxMH{FSZbo`Kr*+(KNUhj}a5XLR?@SJZI2;S2-dpCi-6zP*Jg7E{ zq@5`WPop3@gFerGGT1d(Tp}}cw@gpdazazgBzq#-snX|)B~oV8JFBDJ`d+>+9%|`0 z1<v2}c<05Ah$}nHsFMHK`n1_rQ2R-DmaVk3$O=uTedV0|x#4UbJLL|T`A`@uQi7Fg z>Zn79Wcu;sUZ>5BGqPA;{5t1Y?>hI3a2NebdErj|>K30Yc<$HQ?d!;|D2g8U_!Z{K zHZ3P~fT?5{nyva(oG*NoZorjna=~&`FoCcu!*sYyLe-54K_|~+u-Vmm<s9@JO^F$K z<>NlTyVotXN?i_y6QCVp>hJrMm1K_n(O+XOr_MSwaHlQAyF`97oFHa>KXA3dF!%1C zcuwHCO{X)PyG~5fJ(V<0Z|Hwf?;PCgH0|qy_2<%--&!hhiArM_Ofxin+%<11pl&(s zF^3%$>oMt{N-8iO@iy$NO^(eMR%g`8E(t`3<w_)l+1ZaDe@gR0En!HFrHmdn=j-{} z>LIw@oD9#w=3n<pUh++qmi4{#yjz*jqe5}OtM6TNLV>T8=aRu2p&&O*9tS^S$Nao9 zMhkUD2uu1TA&vzW7t0nOFsZ(OE^4=FmYGcQz2TQwUd@xJJ6@~It{@?_x_LY17uv=M z)qbA4rpvUGVH^p+R_3$Q=I;*Hxg(?*tYIgZ+wM!<{p1#9(c%z`fAV8N%K=o+x#o3N z2RBw0t(`KnB0hm*f;unmuH2t=wGY-`)pJ^_(Q_+QOa9(6?;@H*gOB<_pfAjGU1<*_ zgg|=~1a)sh03&NuVI%6o=nw>j?@`@%xvuHYpjdp7Ds1bQ25DR6w&I{@(EpkWcC}y( z@73uL4)gy)B(E`F+$S?6>bl%brgJyOYb&~aIWro|ORvmW6niTA(d;GP3(wj#CYfIh z4Le$tYNh5^PRj8d@gjHL7BRf!fBEoqu}IQf(jlCFz^0b|+cG^IiM@{+jR;bqOUtM; z{&jbc<M48Ut`p*#wmGw>FD9MMnAPU`dX!4cimNn9?%~Pm0<#*Lw;QI?b@?d1AQ)Qg zG_$4zhbf4cSgsB}O7XB%DYOub3wUj7*qrmEC_~0(-;>9%rRI&b6dKwGewRbiikj^= z89%BJKHHWQ;_R0a9~IvfA)GR(ZmsnbkGy^3Z53UFBt!^F$>o&r7{iQ0b}w)^L#ZX8 zOe>feGqm<}TgFVSZ@^D(%JjQEG>ZI>Kkz(n)zcCnO}c?Ukh+Qap<oi(rx}}9dUB!` zvZt~0$Y?S-Im<t-A!uoMxf9mCr1BA>on|+`0%m1-!_I6$uZ3?l1o^nhkgk?+<?Gyb zT%e}e9`uw6M)DDZ+anxg=&s<%O)<qyUiu{j0hovc=pBiVyVo~Yw9&NKV7UUqVN0Gn zv!a@+SrZxow;f@Kq(ie$d48!Ib+O{LRaWfpN6`*|%~wJ+_BNm=BGE>G+2(f7nL0|` zI_@<lxm@WvK<E&=oA6Z5g~^_m(&DurmAiSEjhjcAc5^9?0REc$g8G18lH+Z(yIwPj zH{9*D#ChV8PiBmJ?cB1ZBC3b0V$x#CO6|KAvrC<^6D`Ma+9V=-2y2V7iSFQ?$3P&u zz2|an#gd;Ss-lXtMHb9w`nAf62(e`<Z(cd(#fa@vso{K_T<)EDel$1DswiNhS-W6L zX<qcw$=KX5h>4p_knq>nXySn#R(s44@%L>Q!qcC_S>*F?&qRo|?IK+4KRQl#ml~B$ zKp-zmCcdI6vmWSwos4zXbSp6T0Hq^w`S40W1j?KcQO`%-NSA$GbnBCCvH3u;hIfOb zIW@@4CfT>`YXiM=?@yw^46G@-Sj?vTyEFx7@fId7qz5;l0MtLWzS%H`%(kQ@oLBBI z5+f&k%?^d(fn^4uiU^aY`$mTqU*eyfxDm&@_=-I}26^I?G4~P+hk?d|&?xS`04kSG z)X>?e>&0KD)-uD{K5ZGv!O5Fmu}PXgMFvHdyj~;Xy>Cx@S}!+iwxw+G4Yh5_8X2bx z+Uirc@fWN8^z_nCVWE-D{eMDRog9zyb5M$+^@E;`_eFCaxj_GoPfSDPxcXd^vAWj+ z*?*(05K#{8d;F{eqt--^;=JlB*J{+tG2r8Gf8vQMGAjHV#)1BYyNp)XFEhk~wedW0 zjOtcyx9slSnCF7lxK#WP;sR4sUx#~+qW)?b$NhJNXS>3YI!*XpJVf7!u9Gbv{gYBp z|NjEI&bSgBF9vkY-{_W9;NvbX$A|(q0qFdQ{v`iDV3Z8t<(sLyny-g(F)k8N1eE;` z-dcUad&RSud*P?M&fotVCbII2U^Gy9XZ02=O#n1(T-14|X73|9FDSH60VV%4B8&g~ z0JTWPS5tX>(iFAv>fqk#g#Q^Lw~H%||0(+g1c;!U`F#uv9Pur1Jw3B`EhF-3dJMpe z-vDP;Auk~PaafVL;}!H|94ZI;4-Wn|uE?qz`yp9FG1Bu&86}IOtFZYud^5-0=5nri z4tT!-Ea$Pbme}8bV;xAiJY%19ND=?|$)9-7XKj*qog<?)a9vGXHPCGrMf(51Y@h#t z$h~)YZ{>sa#_NVtO$ajm{&g~R|2_NVj(`UM9Z(^uOaX=oe{%sqb{W9%>M9-AB7IW4 ztM%WP+jxIl5YYC`x&Wl}?@WuhW)i$cpmssTivXnMq>X=73t+l`6VdT#e+xY{k+u?f z2LwF)gkJ7~Q}JB?s{KU%9%bk|0YTy(2>}9-eCU14Wjxydh8Cu#ns<-`^^k$<8uuMV zRx6-VLxWWUY!@tYFSh`g@4EmA#VIy|&qgn!5!-kruc63u_RHPQpLu`3d@JAbmtog` z;d{mT-x-1UDL^Fln-+HLyMxZX4`se4D!^d>lGZ!FC0TE?0g6D4|4I`tgZ(4iPn-{^ zH|+#b0=8h{&{_9w0k`VkHh|A|qeroUi_nhM@5TqeY2a^WRW9gaq=8ztWKmD$-1#r0 z(Q<vsR0oI4i5BZf`xMY_pFh_*uj=8KqGWX=JbC~2P$Su!>P8V_8L9>*1(A2wnC$Dp zS0lyMX~U1gLG%tqD@zciz9!s+D3`aD5~o_L*<tqPiJ3H=*M311QUAyknr-+t+3tu) z|7xcCapgphyib!B{vXQup#v{D3S8ZFva{-p+e<Z5V9S2BmbtyUao+WZ1;HqNA?jzL zrcFsU)P0h*OO`9<9}tc4fm-Qtq#B;~gAHSvoKzM++&I)7b4)P2>eCzbuY;5)gnVsi zO%<ZNVNS*Fuf`c37p~r#BLagL?udyIBpplH@>>+TW5qDsD6Kwr($^r+Wk+-Vc1v(Y zbs?n1%C<MHd(>dsXIM%0O7bW(q4wd_=^XZBnB6D0H)&7S6I-FtIB67zV-EW`@Jxcd zn)D?Clo#~on2?>3@&^4y>xF^WB{yk(uWZ#xMTK{`(xgQrj&ZsNg5et%Zd7SE1q*~t z1s>>tCOu<==UN*XHJYxfG`xx@!wSHVYj#Of9op|GiYp3Q6QQoIen|oS5<Q*dZdHT4 zY}MfhhLsFDG|>6eBIVF*Grc6(D(2=lbE~a5VP6X}2kYj*VMkY;Z2waCx+KMc*L&1A zp8s+DRh^^XggG_KKhpe{3hD<tRb`M=4u9iYYvqJ5i#oftBTViqH>z*FBzE9dK2XC8 zt*iAq?<5M5w#0%_KWqp)L@k_f0#iN(%~L#Rwal%>?JDu15B9Cq;&ru=7Ivf@#Qo3w z8dSjC2%CBD0j8g@!X*e2fh#H2`r0FaDbuTQ60&cJN7Ydaiars3Ovx}~#ufe~L2!qv zi@8)4WtL8aDs+u5B2{J5T1{d0^zhP5)%O2#>(nDbXd%$7_-gogsDsr*3aSb5-!$bL zrVfoK*U2d1H7=xT=T-jd@3FUgTwD}Zh&m}Qh{}i~Mm*@xHXnvsW6IV>NwD6LYbG&g z45!R7nFikO2zE-F1v4i#ikeX|4elSw2k%~`Em#<yyrGs+RMenS+pZAyc`{Pwv?7W+ zhtVE~I{3l?(VW@tv!{MFu4b-wiFe$LnWfzrcD|QdQ(nh}Fy>O)1lgjj3Ol`BQH_QZ zt{`0+rh<dEM&pSd!OK_|kmGz}Ub0q_3SD0`^#ek)x9mDWu9%zf(S_Ob@J5tP&m$@u zGKg(AklkBx^c)Q+58RnXT-$VuHC%WyX%a0Ys2LB0)+`R*8@Z<c5e2Htehg^h(BOz5 zGA(+-cO}MIG|a_^U-P+PN!bNQ50sR=-KY0BzvrKtp{}C6EHnIdcnSzXLUNc`Z4FHj zI;FsWfJjce-!k=Kjb@IpQ)%g#^#tif(Nlm618_krqdHG*jiQUtH_z)a3Be9<DDZ3Q zT{J6K5KuvO`By;7_N)KIdj)wv|EewR95<fBU<aAFa3e^xcw7LlPr8S$8@Un8ioVms zena8j;`dw<1tLhqs@|u9=A1zJeD)N762hjFslN7OBV&;3vvPbHjHOK&i$=t7)m*7p z?6l(vcZh}ZV82O#xnEGr%CLpB?K<}5B@a5sWI%G|CcQ2-$VxL6NvvF6z+@y!Rm7Bh zu2)(z>3!vEB~x6ui9pH>Y>p6h<q)Elu?z93sH>hY6_o|;?a|1d^V%Li?|VHXAbqv* zA6uc#)A1X|yPxAbk?y^$TF9cFxgbIW1%+dP)1<_mRvYr&7V<Q~ic^@HhHHiE*%O|y z@+xhz<t*w850IXwir|OUR?&&;3?Duq4PupH&-xC=soc!mYKN{2!ZFM3;+HeNO8Fx( z<%H49T$;4lP_U#uF`E`Sd#aVqIUowTsZP&ywlNT0PeEoe`q|0E?_meb*7dxsOl;-J z@z*CRO;m(b<@yq8s%o6^9YlTPG$XVR_|dS)`p3!M>l>C!=az%&sa6fJVRT^8=4g0G z@(PXZt`}Ui&Mq<q@cQ(VtBRXwchgYwJomk?MrD-c&u<X^;DIJf>^3ME&14h5$`nG6 znMItz!U7!L?LWPIJ1MjkS0Ndh$XKXKEvjV~7^snYN1m*vf5qc|SrTTv2)JA;d*a-` z<r18=>q7~x_vkK{8{gH9NU1l}r`>Y0d0H21agpX>Y59TY$LsN4eZ>-z>Q$kQ@blaU z?{Pz>tafQq8u|PxeF8lkYriyXlcZRUkajZsiqWmdophKYzDk`Ojx1gh=!=1L!^QTr z#B_1@PilLH<#poS!JKXC!=6*9=3f6Dy*fKpk(U>Fi<??$&x*_j8+J>rC+I^)CX-_G z`*8~^GU(g`c2uPb8t`>?DEmYn4%_iEcL_+#;H+;=(ART0m-jzhSh2`-iQ0TGd!s+G zB}~lqsibFTy<pKda1C4Tl@xHdYaBD_ldi@<btWX_!!r&ZOW$y4trz{logAoKBUmVv zWZWDt`@+nP(O}Na6?P;vQm}qoP|eg%^!u0eAJK*xyj@5yEf%i_yOm5;UC-1XA>6|k z*rR-{{CamPFrnJBAf?Z7Y+Jodx*sY&w>8vL4Tu%AMiGZn^(KTpEB7NJuXzGHKgBwJ z7d3S+9lZ^bV4Zxn0i(<1*Uxh1D;c^yRof`iKD0Jdb{bE8sfi+|ml;BST%Rlm8@Atj zVP0uLZJrGoUC_&FE*tCCP=jesmWY%LX_D!GVbV`7V+R2Y@zr<ijJn~zKtl}+sYmlh zuMW((mN+j&x80b35sg5@riFtV8|vqhX?$Y8CKGCxf~U@aMe41@GN<!%6ZV?bw-VY0 zy*SWJD!5+KrPaknJ}}T%d{=DP-Bar7`+9_wi1QyWZ5@x~eth9bFTsSuhbf|>SVDNc zc3eDNe2cmp8V=KDjek9m(<wB~{>7SOfVal*HPJ&l4HirVq3B=7Bp|dP6%tqM6kWDo z7Zfz2HH57#P;0`B+@?NfgpGHf2l3wmM2h*teQp#867PJ{zyfl$6#Ip=20fji6!_Qj z{kmAA#VdhrjKPjxvd5u&lKq*jpk_~Zn}B|=QHiup%ATIjj+%tyi>m1ozIta}a-_=c zp-=u{w`3dOVOXo)$5?l86K)cN6COlnJE+!9opnY&l#bl@abcA^pSU9<_}Nj2mhPGT z$NNrZdGRY|iT5>FbW&k$%<#$uarkUM<LLV%;pgd^t{VGo%9Vwqw*E1!{44j$)sF~P zo>p#xtPQ<reT7okdXPdC255>{p2?t_#UIYVcTMNFXD_dp#~N!V4w5YL8lOxsEN>_T zeZ+sOvQZatKS4})q2GoSD~qxl=pBs=u>Ml$1f`RN3Ft<4D^O3Ao1f?fUd5D+C>?MP zs}m&#7Pfs#@p^K?zR98c<r}i*qcR0w7QZoU(7!b6pu$&R$}hRGZ@9E3tnhl)cIP<j zBnmxGZWdm7_S*P`7PWOeT_IZqGnoz>kiTm{Z9*0n_CSS*e-6^0`eZ6^iwSC`W9Tv& zuKTkRBft|C)L9LU6#*Gtms~gcmF@)eI9(Rh<poPEZ`Qvp&u!<Ba$;x|tS+-Re8nYC zhpk2FVngkKW$YFp-=sZvz|scn^(oxMn80%hc3ax7KcgQl01OIOSy$IX&dAYty&H?+ zjq$`AcZ>e`6f5CquxZBFA^wl=!2F6zEgAk`t4vEX&F}d>DL~R+Q_gyLIjO~5+F!m| z7QBOv6dV$>Or}WR&^PFw&^NR%;630Q^2&Z7u^4N&zd<}`ph=ZtISVS{ubl^y>`!{8 z9|rm2N*AxUaH&6MRgslv#;Zr*(~385N&e0~6yT`G0vO}I18^)v7twgTe|3GoAlxtT zEuk%)mv<}VT19?Web?a`{uWsH?Dq{t))4?p5PDGj8l7pqTw_1Vh2e1ne_`!N1kgpM z`{geHLyj0vfY+&ki{E+&8*cXbMl%I1fPMnp^Pt-tEtmh4SO5IWU9K3IrT1Tfr#gW8 zKf_)dg8`8;EzlPRLf&0oz9spFo?WWH1OVahdT7~Q0G&vIsDa}$1MdOZ>f2gYs$T!1 z7MJIq9YRmJ0iij`@626CV`wyZ{iY`XUdbG9CIAE9=>I1h_b&&#zsb3Zw6OBmISbN( zd>VYWdG03<OypkY0(A(5htSmmpdjR1gbh#y2;{RDhAH?I=fRO!Oc%iMO~(qPPaldP zr;8eEGwh6l1U*IZD4xriSXm#TsDUL~Sa}dLUFUVWyQhDM)+netlJhz-=i_IJ<e&K^ z4|;5LD88hYfa~hnFM#C}4ws9rbian-=yonG7BB-na_lMG+#=z1riy{0H{V&)DzYo$ z23JS{zK#!byKQekaL1QGmJM3rF^&319s$$Pg*#m#WT>qu*sRh7?1lI@a|maYM-hm{ zHg-mOfArBzj!1o=Kcn%aZuTNk?D@3|v;LI3ugkp1*_{%eG__$3PAY9YecWgjurCbY zqX}Tq_X1MC(!EJjZA<)$JB-(nS7CaR8}_4G0{v}2=2w=;jphVE;=IIu_Tx`HIlMvK z#1wQ32fexkobL{V)NxSYx71mLb!Otb8Q3lS>*Q(U4+oOZ#UBrE=FG!J_pc}}(4n|% z5sWeYI{^72kU)3WzC{i%@=Box7X-ljPAwd5E&`HQGZB04DJZhZw@MW*a~VBT-pK&{ zP6Iei8{z8kfuWt8!6$%y;Po{aseYc854;36S0{0jKoKPW%Zk;~ZdI43FV}~W2z4(d zWRv6+5U)809gSuGwFB*L76GvHcjwh>;G%M={Y(t4-3M>=Q(T>P!k;$R)Mz=e3c`&k zs|g<C6Vck||D{~lfbJzjITcxSe;-Q%`rBSS8&{<MecLL9PD+SG+)P>HnT9Ai<kEz~ z>Yx)FIDlKj8RGpm5kL^iZ<ky~G#>ISbGS9w7$S7|^|2YTq53`iZM@RX1@i<f(6$Fe z?z)(%79c(^q5`^CU7CU~{retCPD0!m+$B<Sj%iYdABylt@a6*64Za;z0D9+w9yR{u z*f)R9eu5;rzO+H*|32xGH25Q!1`R=BM10>5{&BlB>N@J=QQG9|f?{A?VC-L~fSIB* z28ja$rH%^l)C@PC_CMczjZs~|Y0Lm|v_@~DI$rzkWPF1i-Gst`ij6N6h8Ii-c-EZ( zRw)Vb(1wJb)kp=7n#rHJQqAXkdx6Ws^2KiO+GwqTh9sW*W;_<&ls^@zsEn%XaA-`C zsxB==-V|ljpYP}34%->E^Ytwn*|6+mzN-=aOq@|(Q3gKN=EfxL<37@fxkuC`P$HSY z8Zv$v-u}Zw#g#qcG)jL{gvakq{O*Cd!YlH3g3*mbU!Nkk?(JXGO?PlXcpo=*v`qUt zG$d$t#t-QGkL#v;a(Rvr8^z@)C#iGNCZ^K+w(WY>ljabVIDEujg6Any%AVCB2hk-D z1Z236WFN@Ps~vX?dt))^MM<QBFuEp<B6L~<QB&%(L8!V?3L9l?*3+xo(9`t!GN_y5 z7wRmhxg_=ON(5uu-60sNKdGrzV6iaD^~UuE*Kh#M1=WTj=UcOPTo0bnGv1@!DaUf7 zW>rujp~YALbcMO7Cii4WP&><=cXH8<_jqzFnro3P57((3P?ge|TyIW2{i7_tLCOr4 z*Y+VI!bgOlZ0P%!=%k`A%&8ITzMS<!!8sO42L`)c331}mAyCN*s>E?s$F8uXZZXtd z?Z^T8(}VrV3OL_-{s0XcFStFWpGvA*Q{=}mSw``OtncdvzohKvlvhQ!b;P$7n1VE? zC0yEVzIBM9*gC(O?JdNeRfg5e?CYO*pEIb!rjZv7JWqr^ZA9EsYsq-PK00T+Wa1K} z3u$4G3Q{e_*lJC{goICZ>o8@OXr8=ro?K5BgS?;TbE2b^reojp5X(k1fAl8DY6uHE zv`vb*2^aZ|Z+tpkb7K*-_TqT@k>Ex==Z6~h)C^+NxN$X;3`}-DB%z;fMQReu>sRFD z(6@4H%I8{VMxHj-#yPqBUR_6;?=7YEK4xV_QZrUvY_)1-?J!6W4jQ12fJEtpZn@<p zxiR&7TGqrZ8n0tg^wV&=o6urZQ4C0+*Z+-O`WmXP=E&)N7u?whHfk2gFLMb><zH^m zFH=+K4_Ta3mh=QH>gsHnWqkew>=oa3x`N|!Z`zG3+zA<1pu>3kLH)f;Aw7?0f;fC# zvh5_9<>~8k>^l6Brb)dPf_jTpQ7@XFY^eE=FH7$yTuC{x->q}e=0&a!u-btHki*xu zO10BLw<~pB@*(vHB9#)`2b(z$Vjd*%nXN@FnDR#Z)7UG14q)$1i0!Q1>K6H+K#4iJ z5_P0&XiRdd-d5m4xuwD{_LDaI1@vFH^+$s_z%_!}ufHhi^Tup?x{_+cu0Rl%zLwm5 zhtDBD{!&ReuyR0&a&LVVgT(ZAaHlZ`?)^#*-h<WM(E2Lmb27{v`QZV6{;N9-U?qzW zsOESQ)1?;A=n_8p0&<9zp^*r0nP<w&9U&X;eI(ZcZoUU?t%V>o$6z)SeQZDEfB0Ng z|8UNqKV+zmzu%Xy=_S|ptmnC*^K3fEX)@zHs3sgt6N9@AMG+x>^#RK0Z?%y0Zvp8& zBRaV5;r<Yo8Lp&D_gYKKg+<O!J&$A7CHTJIy(n|N$4jkYU45k#^cs^4bOdG4(C*xL z9P<PZz`qRrIw=u8=AJ0jrcSU&mi5cn)0HZs;Yz=*>Oxb&h~J2dSs~;)t%D-S9@E}w zh;BUaMhAAA6UBd?WbTo>PW|CQrh{7+Cf$)-a;^}z53Id!f6wweE55DshnzSx@*F?X z3eyJ^VAjCBl{D6n#l8@{nIo)~a5drt!V^D3%sE*hoOEesGkoQqOe0u2p^RyYejIpj z`jp{;J`B_m?+|Z9$Ckp=oG-6F->2i5YU04qP(aUcay-bVs=C{$ly3msM=AAXbncaW z=mV-tsnZ$;n<;d3FwKr`nEz}Xq?^7Z!lOv1?S-6WwMVj%u5vr(>`D?h1g$mc5!mi@ zZ0BFpNA+isg_r4aO*+4M)$LX{Z`+_D_2hAtT?U6yJ~`b(#^nBx`yumS(hkv(pFq&4 z<7(|}|NP<U>fJ%a0X<SU8I{O026}|};J!Xp(4w*Bk}G^i>%6HhJIpJAUp|F`L;B<L z(S9)8X8vj*w}u1LKLC$NW$zba+Fb2wxtLn9aJ5_&9AEq@Eg*<6@Tk5=ZbzA~>mp8^ zBuOl-AdgYeyN(rXGh2J4`z#GS4-op~2+!Uba1MjR+#PBmC$EjA9pVuN^?APDn?Ho5 z8{A60wl~0wpbF}e7$Z9o|9)Y8eSPPwmjyqrfAOhlm*yPTAJ8AOh?+C73=<~Vo0@ez zRh9E`)+tLVor=>?Gxb+`Q8Gl^{B_E5i|=LWlwm%JksXN<Xy9D8^*X=f5mqvEP0)tX z2TJC6;#A`-mj!zx0x~GGupvr2+|=OxZn~ax^25wFDmr(m{#%+XV{>NiJGO_{*?@Eh zrq9l{3#B<dBE`IC6}KF-k2ZB%s}D3idi=-wLE5fNrBDigRlJ=V(XSf*p4~t3h(fqR z1}=;CtJf$<wb3@J(C83aRIP5_E*rtIZ??tL=Ef64#Sxcw5{<2)T!&8+vPl2$_w_Y6 zFGAPczMugYfx97`SWZkhqLUEAtBr|6-?5mM6cTo2Lj-H}!Z^z5&l|KMiHo`<s-z!A z=@-~2_{DkF6SW-Tl72QtI77_6d%S;&>lbEZJ=&3L)LPMb7FXamw4U-hd-P^s2lEec z1(s2nO!)$}G{&je(r3MJTZV?c=IJm8&G)@iG4D$rXiC!EH+-L2!Z2PmJh#0{$?@0C z7>NKV|5T4`x&jRK)YqD0Pb{=ymXG6qP1qx73>%DJHO9uR54w72-F-%~(Al35nIR7e z)o-5Kicv<j=_}MC0*j3W7@|FlESnu(V&arbga_716`W71QQmNe2ppvq=FKC50Ytk4 z0&v?ZXR=OYnVFgGn|NT?5chIL=zc@A%iv9k*N+YUK+_pp*ieEDN^rx{ayDJpF6w|t z|MPB+RMnJVeRDaxetV+v1L35J$8}Qs=}9)G1FU7=&3Vj}Q(rYe287+=x`g&)FfHL8 zui2JZ6Y;q02`vpT?Gp(gXiegJuC-5OogYUDG3Yg2QZq<~yMSH`Ou1#cr5e5OE*JDn z&UZ2?imlY{ZYki?`@)o*Bb=WvqgS9AS-aOz1F?P5G>cW?GJYeKDA8z=PMtSE>U`Vb z4KK;(8(J**+G!7-|IsJ$I##Ysn7C2^osfW&fpnZN_Frzj#cHg<ZfJe@A|;j4)jGun z5YX=g4(@Z{e@Xw@7M{lN^(4k(sFG!bwp9gI88W~Gtb|n16y0<t0l#`<w3WLrC#_Sv zhmKYGFHm@sy>ttn+@o1+>Tk?CY(=AKY!XL6_}|7W&jMtcCo|1u1LaZ{$GwI;QfSNr z+PQ~P7iOff1MF)iWOf)9HqM75Gqi{j{S^8`QHdAEMkO!Gx;yw&A^Q1DK<;6szP9F9 zkGW`Z!y*S+zf{7_)Iw)zy7YjEOoHP%t2>#D_Tgr*LXsiw*u)f%is7c`@DGPB?=sD< zzbLTb=60@RF)OP*aurd8D=@p@G7TSBcaEy+Y$5V`xn4$&B$u>C$N?h$@$n%~)VbJg zL@khR%u|b6k(_QLLRJz%8m~l5+8fZ)5k49t%hxG%=ab(j+Nz!olD@ZiqZT=wIBmuC zycqpSftPiyk#55`A0*6?`WQaSsO&10Wl=MUc;l(pQL)SfdTlbk)ti+`tp;(f<JnTK z;1Dmccw917qCWrNxKD1{PA8<F(tVNZIx{(T3L>&_g}Xg}C6Ak9qYei5<*+dsw>!KL zRA5DuXIVn+pBz?LE)tpA8^3x6Pxt0gZjqX``KC)Z%pJF{XWAV8R94{j!tKGW=xdE@ zV7a~4!hY9h8)St-!u`Gx*SWszKi|@x#G3e323HH2%f{Lx_hHU&JEpmfmP(uTyHyF9 zk0<+qP9|j}t_ix|-{FEEF;Z2}KRM8_o?V}mY}xY2z<GhI{Gc%MTzz~sEXZ(ezmoMm zl2JoRGt1E+)zR2PPv2l8g<GaS^B2v_qE|?seC8E1=<gt8{GV%o71aRs(-&h9rHtze zLi9;@_yW&GHDH3Lx$qBg`4U2Zv~*2<Ijf=w@Ra^WWVLMuEN{%8XADV(V>g%)&x#m8 zuZ-J&XU32GpD|w%{HnDKX3ZR!`H3qoYAH$fd5FOj(+=R@@Ly<WS@gR@|38M$>#VJf z?)QIL7iIRstGxQH65d*<@h+JbPN|Xo>=2-&-~LQ4ex;=cpkx5G9|2#>^gDttcKm$1 z^EX6aG5%VR<o)Xx!2f}OYC-tFP5udN{`b(Uf48x*%GvL3j~_qB(=I)(dwipc@<!0# z5Vh0gEH)hQ*ar#>pGv3xFR*V45<o0`3UL!&(|F~&nDdx)V3V_?LamkJ4)psi3Jg6i z%<;zTZv_m#f1DI;RXlHNp)?C-45B*mivb?@3wb5^1R2`Yf1YBee`X5YaQ|)ZT->`! z-ErgRCtLgTwLbxw_8ZTfY=NAA1`W9UhBs-Tf1muqytkrQ<0#ug!5O`BVF$c6t-8d} zepT;(fZkd4f2aotR)4=3r;o^&EtmK1E-o*Dsv8c*zi*_#HP+b!hG7%{E9iRw1yCT^ zCR1cJ`9IBp!IZ1e{mDa~hzTyAck@=ZcqJqrO8YK}zm+&zg?^VLd?r8sEzfJ62Tfi} zFiL9jm0#3|SsgEgW)!1QKMGtg?pJVV_gi^>Xm|%0asrQ=o=MKvA~=tDIZQY~N384l zUewYA%eAltfb7O=R43eG;Z1VkuCb`is<~jYX69F~CxcirJRjpf@#>+ylTfaOym@Q$ zA*jEtWYc`(m><q}3<B=XB?tlU-eQ&N-cy`T@vmL@rlQJ`&}IU@b}#S%!t1x8r{ua< zJDvUQoacdK_fduIym4+qFKZ@~Zbe&^EET^DARJsDBdUVf!cE?TIP)|<Z(oX)i>q!d ziBp*?9lDI*?qNkS-l+34Usvl*oJC+H*uJV!Y08&y)cMTSy>CGw1~4wC&P>T57W$Dt z<lz_pE!ZXJuk~Li16JGxeG>`pwE}l#a7B(()!r@Bq>Ln-|Bjcqc>0+_ss%GrU;(k; z>h54dJ*G?hMVTUeeCS?+OtzK>*brBtxaQm~n<tpsbNaTaHc4-U?t3t^AXfeSmEbvy z#(Csj)-8RtkfzGpD3SMVDrh1b1zI^!`ohQNhw6BiVmZiI4~hUh1Yc#PL@tJxF5Ri9 z&l`Pn;L<G_R7%{aXjyW~Rdp@!3DbN<ythg&A&s_<IB(hf#B`YEqTGeFIielaEp)uu z)kXnCRM4{@ikwJ}&pM#!&+Vo{WSvbG+`~cY?)e%HRBaR5)ZmY|zp<jNlb~x^Y%&J* z9Wp!j;y*9uqCQjH{H=ghzkmY@Z8zEsu4Jv8(q?nO_0yeo`EQKtK2V4_4am}}pSxfr z5xEQM{mBq*UxN6Fg{cu=ZwV-uLta99R*vJ%VZKUt%*B<c^f&0;#qG<|9)GeWwpa9? zL`H6X{*P2WY<@f6Z}~9p-Sg;(^ukBS#jOomaqB)y;SC7}3$2DI`+SIltCX~87q0qH zF_sU{K^EjoOI`^d<}5L_G@b9RQOfJNm!#dxU-~NR<|wV2E*)giyb8Ln?Yz2g@GYpn z>4Vx!5@jS;uF}#N;nnJ`y%~b2gFg;rT$3Ueykul{rVQ$JZ|v!rYyQz+f%rbm?}k@l zm?XMNtG1|*sVCL9`jIxlsi_fR#17_{CT06{<I8jichKVrH$<d<Q%$PdaWtx!lif2t z^o(VUNE(W|GOKBCs#cFMc>PUF>}iMjx<eXobfw=~!ri%rVLxBz4^?SPq-9M=#(NHl z-?vs;y~}zJJhvRrD;iCu`MS{eZ!&_VkBiU99y_a!^u;nHG7>-gM)>*_d2l$Mf4yJB zpLpma_N&kfBVCNzDfp6z_xf}dX}RCQG4nDpKOPfqd|$0^EyNIiPS4W)_n)i!?;DDw zvw&Vo(i`BA#u-*L^gNmLWd<%iS2_(l#R*w1H{Q-$KxsM59pKY^_JXcz<0SC=XD#3& z7dO;#S5Uch9A!HN?%m*@c)`+`8HL7TYsd71q8)FB7e<87@I0Oj?kTcL(gKh6ZtV)_ z=oNJJ4vq%;+iQHk0e18?(X}V8uv*~j7)MMm-H~Vcy=-J~@kswI@pw@aAWU-%xEZqK z{+fiw;d$1#ueqN!f)6XtV80)>mEZme$}{9)$aoGuMzYZ9vS_}|2+=CfYPs#{pRQ+G zS91Po(o4pMpF&E1zd-L<Em^6v17A0}?kg`_bW>36O%uisZ;EupvT_~!q*j*_<^WGO zUiO}4fpZf;Df4FAny&+}#9H{7%o}~i6Z7m3^+3r5frY{yHO@a4@5qqk9h}gt$;xNG z6!LzC`Lt#-t03YmzOcB<RLjaFB(BqF)#&$Zewaon|LK$JKC1GLpnilz&hnGhn*+Sw zSH^pxnka?D!WHL9vz^O<sC$!V4}|KtrwS9fqHSqJEs_d0lHkwdh+oYeR+#eFKgXJ( z*viVa^G3>fT5Zd1bXFeB!d^`3Z(6++$b<;5rDzevxW5pLl5j4b7+{J?lCDb(cb~#i z4L>~H)|KhyDl+z3&vJdxXW*G^?6;w@d*H%N#FHFj^Bt;&<La`T!$R4%jBF#z;`+QN z%S$GE4U71xE@wGnOQuuq>&~~tJ4?LKnjb4OuIDQiGMbVUSs2#G+z(#UrM7X7RDLg8 zi52pP2a9q}lYO2q*5YpMlC@WFXw0rb#|j)RSGg*r0)f;6zgD<W3YqX#iur}O7l*Uv z4gPk`Px7K%8NZ%1++R*l)r-y(O}z=&@+D(E|3Zfg={-^{y8Giioi2!AX-(8Rle}cy zVX}Xrb5(m=vI@<yDpSl{VO{8(`Ny80&C)_xO(w8pC?s+=s!ilpXgSu_irTEYn$meT zfUGmq$>WggS!p?k$1p?ONs}0(f_3THm6SZ^usA6QT>r4{YgPe7C&PL)N7Qn6d~+kl zdB$Wj7M9<74V4}iD>ZYojYB?_GEtf~d%sZ@svk!JHSAF#i|XkPm#YuXArb4E%zB_4 z9TV<2X;eVmU*zZKS=fi>S%h2V<g;AX&qf|fhKI?8vbGthQv7UfeBhT(>{;JdB1`CL z*hcS#15H$7UEx-8xGk+3o|Vgky7@f1qyaxq=beX%G`){egAC-iG+7*?(MR(&qXSSX ztPw(&80&~RLbh`dq7HIDfcP44qK$Pf%jD}%a$OveCp_W#koa@)hSf*-B+9Lq>igp; z5vxg@m<5({4D3|-!G=V)H_%F@FN5E7?+>Mt-5Rrxf(y){oJ)_EYAEVg*;o39n3TuJ za+|SQv27f1Kz;%u0~8y<mKJ3?L)4kB77KwTfirE-^Lf@MTtnECgIO`Rkxh}2c9|`v zEevuGuK2wwHNWQbn?_IHe;^}lj3hU`Qr}PVDb<)MPLXq-nrQPxX5W00tBhKWuOAVf zSg+0ijNWr*1&3&wMCDRn<4NCOc>Wy4f7B%sDqxrI4A6f;Mo1_vRt5FwSFEp))M)QQ ze7+0!^hTS!Yo@-L&~m<=3*3K0oIi?=A@<WrI<vW7k2?`CM}1Cf?(^=w)q5EP9SqU9 zBb%v;RVhE1;2w8suij!reHvFZSnPrF2u*T-0#h3Dcz>Wrn16`h5EklO?!>bpqm`aI z02$6qEh#$pP2SGb7U^rs+(skRZ`h(4vWh5~R*h0+ej4ru@}CyzKa0IDBg@O!Jfg;* zwQH@HWw2FXEHMeEALv>Ghtb*KpV>s3t5w49@Kp$rXN&(xZc}q&B+9aCNPYQLYPrYp zUc^OY?oMaD`T-IZh$#GmzPUF0zX*Hpc&h%#51c5KmA%~x*<^1w$<E%plB{fU<#J2* zEVB>_*(8^1<%Wxpy|UeFW#4Pwxc9z)=l%WT^QrIe@%#S%yXV2ZXT8pNK3~t#1$cp0 zEGOZB$i~C27A5{%IGCF2vRhM{_+j^@Tu$v>Y1z5rfMHG<y{L=NYp)TQ@Nbq4rH&n4 zx^{2n2M?TI4(5_))DjzU7+`+kvToX<F!$Bsv)P^HX~kc-=9GIP{eJyjlpy`(e#P+w z#pk(a-EwxB22OHCf*f|k7$cd<;)PNV+dxN9;Y!5oMMb=3Z}V7>>DdrxqezQi&sbiO z<f8m<Q9+}M0DZ>vXnPBN2~Yo}p?1!}a}y{fv3>^{h?~Z^#cb5!+U(@(aC|oSkcyug zZfIhlY5wu`ce_@Ldqevs2I11bXFfLGSj_|;DeHRN`$vMiuyZx2FdmJmgvB;4!ApC< z3CcPNs?zNOINC(~x;!>HCFvmi%hYb#nBv2hu)b>6#mnTGjEe^GD=D{9ICS1S&e$$> zop_z=mZm;OX3IXz4*2Y<sMbZMv2#am8e+b}meM9ryrs<2SmrBsETmfQeasem?~Z-9 zPrIr3+s^K*A|GGBN=NwflOhRD{W4Dtm46aIUp(n@lNCEHa-Lb&>wDND19SBIr9zBC z&VGk0Sb?wS^M(dto0>-Rge{A#j7+PA_5EwM&Kt%{AQiXGp(z>M8)njZyb1|oNcZ8H z6+>)kGKm+egv4!hav?8nlENF3e|T3z9u%`;?eDUNX792lUXEjv*az*errk?mpZL9> zL=tp&W{RMiC8*%vV?n(nzR8uznwlj$d?0$@#o4V=o`C`1GFykbn^&Ioe<`#T5aRim z?I#8rQ>9;#<oTg0gFVH#rMl#PBXQTmWDFX{RQnn#OY>Ly+0qO}ck3Hp?w)8c`h<R< zb2MeWgu+=Ts=Dx224mTl*<$4EEvFme_G+PCOx?a-AKiBwBn0A%ttFq|6X!OGi_^|m zvVZFJ>TH-EH>C4^n6BKSXt&5qvEO3-_|zejBvc#UDQckbtaxc`gI5Tv!|{kO$~Lh_ zjIt!L)YK}AH7B70t=u4DMLeq1XK`_|a5pVg>d$YREV0WYu$}lc03@LxYPJG0fKmGt zk4f}pHViAB_l&sG=xA-EBYJV?bNB6suECI-Ki+w)Bn~~+owSqVLB_R{LtZ&dGys{K zki+hJuL9bqD+ui1P%|d9*0p_VEploPqi6Nxs+qm>7yB}4F%h3ym|qbM5!nlRg`{g! z!%CWu1sQmy(g3ghL$X)^+s7W6hK0DweximvioBrFEHlh+0(Z^OcU4(UeP`Z9;sPRK zxFY)V!PwelIY}m+>aG=oWOZ>R7Xxv#aI-zxMuh#qYEw6{HFr+9t!D-m7Gg-2Z2T)j z%BE_G$B5moLdx8%qWNaphR^L$If%ZIp;oiVGY^8N???}<vU$&)pxGxQm<^=Tb&ixo zqaOU~o5-|`esA|CQ!<3<Zk4FAVv9|wezej`omBo!c!eG&ER}%-<dg)1V%w!A;k7X% zznnx9z6)e!);byUCsBS7--Wi`uI~{4rl3usFte!l384#J?k?IVapJkU=rO+62pV4} zjvc+a^Vz2xXgPZTwYa$#d;|%XUm)g_^PAqJs(WYu!y@!1BQ;EICH@XZ3&>}Yz=I6% z90DUa*37_iPwVGlKY!|k!$Ln*SwD|zahMtw3YA<xkYJRzA-qHL_uQ{D=2o17QS(nC zeL&0_E5l3x!92rzGmA&Rx9fTEnel^7*H4=!3j+bs_K&Nw8#m+PmblHkl-y@NMi8bN zS(yb5sD;Lpn&%xtbIYkaRa+K%Pd&ZM<xbL{&kzvY4-UjS^i>64h05DHMc=ogYf#m` z*>K<TYQ%tKr%`dmjM-NX%ZRRg7U9lht++}F4~qgYPN&z2SJ^o#Lbb2j4v(}OS2YhS zg?X38`S=uAwIymzWI<jJ6*OmIj#a<7SS#FA@i5T6@1BYDqQG{csbY>6z$RFom>_ZW zZH-iutZB_rmxL*L6@9pWz)i-2FL$#29Szoh44u!d+S;z=@TQ)W!>9|Gep!20+8g?o zLt@SjHU%16-|rrat9QztJ3Kw#eUT!_z@DMK=;O@T=DP-ckIU|OhA6ny76|GFl(v1# zw!x6cukKGua0Vl$X4kg_bHBgwj#6OMWY6R`!xl=c8L%GYe*fY5P-sn*Bi`Y25r>lC zM^E##q>t%l4N7{o{(*r;;w4-%$N5*#+}wUjK7q-BtG#0C5<y<$4en!*DjkXX2F39b zyS5b$w0-V-JBD&iTF#6T<7E&7G|13ib3)btL@nlK`YbGWAU9p?ODi`#<%jf;k=~=g z^c)<F3!pZ%L1zFXRL^+^?m>PYDi1_^6|h1X@B<zg_gxo>lXeHs-Ir<1<<|>b60pEk z=5%qIB)F}I9`NQgAR6x7mqL+WywekyM0Uye7V@=#u#u5j$WvmAS;p#`;ImUVTCMPK zK*!mk2saRAU&C#n92M?2ztLd*MZK#YmBm32O~ZGe(?DLKpCv7dj9;v2D7pRvA@7RN zZm(+I+>_Bw?}GlPR&!~YZ3j^S4Jt5s)fpk!IBFRAA#acgoWrGf+;bbId}I!&1JJl8 zMKCwKfItOC-{GaQRhI#T3yOf;V4INq%o&d8FlLSzdft;;ynsKLvr<m3zyHPV9@%{< z2kr#7oj$BeHyDmg*jH5!W{&Ca86RqD&X+dj{(KoJsRUL4T08s7YCZ9|bGd?-PNIoj zIc=tn-TqH+HMYem+EU$BQq!Qc20;Gh#aN&fVD%re_FRJdh1zI>U@G^|UkA=YhgE4C z5sMLFFa>v>Va1wmRgQAUszVPPBGU(@Cose}d#Pi{n7bvl=i@XK{3K^y;Y7ZUZ}yi} zy=<D#4F>OYRf@h|3IP1VSRfnr<HgEG&E6-}aTMQA8RC9Cbdsg+Q(a?g-g3Wiy#Ffr zoJv@&VpV=>=DK%vlLVbI_nY5iUhS8r9*);!G27BS56yC&C%@m@gj?dMXl$wN{%%^c zo-o<9z;@fH@bNnf-{lmFGQyzs1c@Jd=kwQuF3aXGIcgeLLqC^Y?^$XIzGwuFN_EL0 z+mHjrwhR@(LLczQ7}q(le`>PLxF@xR!ddROv0!-Q$L#0kw2~jX(NzmA9DKIA9(<kg zQusC^{1HdaF9-LjF9JL5t`qk`jNsbE@5h*r6UXG096(|j(}rl}GDDYQ0F`=$5XIp3 z|0I$a{0VKR6&LxZCSFSpk*};eV+-ke5>{a7ThrhTB62?(kY0iRTp&xd1BSuZX(AMS zC}-EQEzV`oUY~HXH|S*RV*O?S^e(PXl{5X%pC6&(a*T~eu2N7DsDZu`+5JBdy-mwd zX?W3=WT{8}+Yd<+-@j3Dkma`n+?T1AKN6enRd7gJIt4`V(V#yU$bgtSLKJYDuJs2( zBIR7H4GQNvYG)eO>#pVB%lO#pAN@^ng{Q9)`6u<FIQvT#Siht*mY$dc{|kA$L1KA% zZH$sAdHsE5d{yd_f``isY0pHH0dgSM0pOWWfC0!x0A$^NEmHXY+00r!cxf;EIj-tB zR283f6V2{IbD3j>C%)SEkKMh)?d=Y+CTWg@gMeY}`RlK(u%3i(^Y9sEn~r-&nfE5A zT`-dV#@mh>xzzA~aSW55$OCFXgH-DQK4NlE^Z2=)Q@y(*A7br_$+6VCR`wh4^pB4r zfb^$7sfGXr817UOXvWwuoyh*r#}RVJPk<8ax|i?Ss%YYWEmh3qJ4muNm1Q1l&6bvF z@7>Z?+uMBsI^XjPK^qR)-L<TZ%^2aJYURg{(tT~My4Ts0$d@R}YfK%-RoIhK{5*sx zD4eE`4OJYq3^so-yj`e9mAX9GpbV=0(iRNZgaD>hu+#9uTqlUx8~#=Ee)RpEpfNv? zyIIY<VfN+a=^o{;Nt^|V%i}e^X0u9*ii;TIR(3(I)X%lv_}p`Hs3A5c^Ao-leW^$g zh?{S)6-?`B{9dCS@Phlxd5Zf5*tG~07{1>r&U$WzrAp9RgTH17;Z1!0{Xl1e(B?xB z1^i5rPw_s}_s83uaa`8*l3}G3oL6*yMBR9@J(BmR1@zPYn=^bmvf+He7z01c%#O7h zNv-#?rUZ&}7fm)q$o9tyiSN`UAy>hvBrw))v5PkoBW`8<S)cv#0uElLrnJFKj&^2j z=Ytes6cTGywJ@|+9!|DDdpTb3#s_wm?U2>F6Qd$-d1X6^wBpTc9Q#5`mTXnJX?ASx zb(L}ax~wMp9$$UV0ky;KC)5~6sjA(o{xmG3Ry9@3YAJaA_Lh`W`nfEDwvCuy6%0x$ zV0#kNsr&Su_pY6ZzVPY>vFO`{7q^I+s^Y%O`>7FX*zVM`R;!t7JTD*JA$oPGK0N0q zP3L4M9E)ojjRsTrsvXsmbABfK5TFB0LVV3Wk;FMH%HhARIJ4>Ao*vi`I=YwwzHj{k zKYlVoED1ugZRL1pqvoPwXz#jXG`!jRKYXXyJ2Ro8!okp`-Oe$b-R<!>vssL2`NKo; zG0gVhZ<z`1JnKnV{rVfKo$hmfXQ;u%N1Nd4aD_P^pl{$d$_r2D^{t&7j6%*)tz^X( zK~5cV&82QDD9|$2W<HG#3?HFV19P7Bu7q?WXYPtWp^pMFCQUQCze$xCTU3(QI(Qjr z9_gPz)`fd(JR5dm9NQfqAN-Yu?d{7fiJ}cq+y=HbUHAHO62nycIGzjVd}32KS?~=^ zbMK_Ks&N{TuLN!8@{u~kUg5R|)QxahmuPA<jOCbzqW|WU2W@wvOH6z-C|jSbd*VaR ziuHJ5<VwGIQFqoX{RL^=j_U!Jluv6s$Ij5|BU4jZqF$0`0@ZnO{;fCSXRGwi))52^ z-|!Gv>Fnl^m96YsHa`cn{=*dT!eF2b-r8nF?g?T%n8hH>E6Pi<LFdq5J&ES!mP`&= zvwtaM%KK!t<T#RjkHvfa9S}w6bG4A$WlOQbVA+>>YnUu+Z)O>h9mM#_Z*Ay6h9oEV zZ9>jb-k=Vn;+nQ(qWd96G@!ig78$o&O6C(DHq_M<PTTgzW(5YBKFZHh=Ze~M&H5{X zAUm>!Tr?v7dWsT%%58yXmcM)1)r=9(6G_)vGcI5pwU@rTS?XEFFY5J>RZpvnMXpcl zPZD%!48*>_ek6{ndQhfH_dZU|OZkKrX5JEWS;9MuHKU;^{%Xa}YYD$l?!1vp;J71U zf=YRNZotZOUh9^WnIpON5D*S0c)sy_x^CNvdpg)aPi|o0t}vkxpK;@2XCANr?<Z{m zD<pM(pswm)sjKV1D(D*E&T&1=_Y5PlU;)smtMuN0K3K~hkU&cU0_^X=(ss^2WFp&M zY5$X5L~5=*D5U8Jgv`p$l(62UrQ^A?t8-Px|NUHep&fXrL^41x*W)&JC99!<le^VV zUVY<aNHnGo6fvgz0Bh%e$8bCCdSk+gJe?oS_q%Bdf?W;gSAf^02l!C5F(9e_oL9gp zXE0zw5}s(Fb+&AGROAPSLCQ%b#rKl@$Hw)8(pdT2Z1TV?UrELHT9HAUpVs6*rcE}U zc`P`BUWM~F#WZT6jYML2Npl=R4+}r$dQW%{DZ}K1CX!ngXBUUJoD-ZcL#c6zcR8t& zkKU+ywD!Hb@cT{7x8RE}FWQiC=!*DBOOvw(Es@!DQzbo>^S$O3s8KUBJLi#Yvh`{g zYd2f<d1kh4tY`bn<s|N&Ix1m_ZiIwX`ZA!bh0zl9(BqZc?E>R%Y9Zd$HPID7TuP-c zWn)g$tHCh7<_@4G>ZT~=n^{&~J4B!3)Q8fgO@+fvyXuUoX{&KrYx!vg<}_jE*Wdd? ztthW)tTH&VtKV4Jrz`$!$y`2emTpqc)qxlo?4R1gB|_8Ie1u!!Fe+G;lQdq5ef4eG zM3;GySyhoy6?1t-=0hVnhtP}<rbgFFhc9jDL+b)wdB~w7C~>Z*FWPU-LzU|AESS)n z@RS4Ri<+P2gc{O=zv#8BV?xs(@gJxfixlnJ#{68oQ`fiIQr+84&)|N_%Zm&7HV32i zm>sGQ^jNWxgc@H@H;P;MZQcQlq~j-6cd!=*=(>d%O%M8&!@(xVG2i9Mpvsx*n(9xs zfa7aTnBPqJqN7bf)n!VC?>Do%*jUxsMtlj9UM0m@%6Zw+jy;EZZ4Ib>Rh0Tp^1=5X z&sP*3KO!v$2*CsOSH^8qct&zejr@IzAMXna56YLa&KZ`KFIszLy8lCFkU9ny??nqu zqg>~kqZ|ay8LX;3x8UVty+*}3=B09~Mv`nI<B7Sk@Jg%VwY`xOURPX5CkXzm<lF?J zV1@1NN~Sg~uo*e#xfv=O=3zTFzAGQlO?$K-Eq~w;D!<v<pQQKfTNBf++Qx1*uHYmU zJ5_?th0zgi6rhJu)LetgD;)-G$wA`!29FVlN%6<;cYW-M@(a7Z`;UU-e!rI1x*-@) z`P_NuCE7P8TU~kbCb6(xPLD1b+y%pH!joCgjSuhD8$-SfROp4>&dfrajdjt=u-H=c zrG?gnb;BA?cgp?G@BAuYN4kSjpNq*OFFV=OI_(=bhTj!;LCGhFmVTM-rr{0l87<4L zoxcY~iXrBci$SKm!u>MbvoU;^vH-MfWR_Vf0CTbIkxqoRr7lF@!>l|x_5fy!5URYr zSdvQT7JFMRd1UX3A6#UlV6to?BfR8(;8{iH)nNCbpeH4o+t<qSCKXGl`X`*rNkc&A z3-~Fm&WU#0sHy@k8x3T`#GLuONJP_G-^B{-Au9y(Bo*djidY8h?DhQ5+w{czl;`!t zQIU!y!zDgaH>@r-K~=nVp5TI$+@-?N8)6IMylaonC0QYC&a7+-V*|mm)@FS-+YTS- zF@0B1k;zVh%s5?79ECa(Yk-bg(XK@WEb?2pd5`ibkS9B9p}Z75JNK>Dmo?k}B>7Zo zrZ?ooHA_Y5V#fW7BDcAR4SolAptYe`swA){h#mscz)NCbq$>m7<#-yq+1X8Xfk|~q z_s{n8Hs9wxnG%K8UHC3YJig5z1y34%$5lJ_P%zK0M=P;wu+)IZvNqy&RI^}+?3Sgz zk6*?FNOgnL-`qD--Q{?GKozGW*mo$PtO#YUzdW8)+4){fw#3a25-(Y!98hj1olK2h z1CX*vQ%=Mf3lELOXMz`YuIssa?Q-p90z=)zO&k~~rOZK{4aYBfG#EE}C_g>y?A!`n zP19^rD`X-J{z#Ky3tWGmovMCq69lK~+zmv5sDr|_2fFgFwMK3j;lwyU92`H3T-6Kr z_2BN#-f4B26YpFZys3*BpqGj;oWW&xBN+>p6%yrml*I$aQCT^c1~?>-fML8lK9v28 zzM_j|660}dEiw}Cy}Mgt?LJy;I4m6w!|ca_v8Dx)&R-BoL8-GcU9kF(TW1aJ1!!2b zGWdm@p=bZ(-oEO#vxsgfB6IDa%f9UyR%B1tZ5~%fhg3-Vwj%tvS)GnC+Q{A9q26mT z>9^hJrebGqlz0d`|9nu0Gf&SV_mg=q?k=k2>Z?tq5_YEMmV9PyPjHIRd&Ck2j>%+h z!>j&9*0bhC+V69|T3-ZiybWw!-vI><{m*(mVvQ_N7B;i>#F*9tk)6*y?K3q7)RM)a zzKB=hv^x@t7(cVe&oHNqp$!9;C_yL~PXzlc@CrN~wSh=j<H<E{YJFK_{;2fbc|*WY zTRUC9JK@+SA$7B#;4e0K4~#u5#`!98xtv#RVn<ce#f2^wJN_+#4@=0(2c<0z%5yy| z@A=egCQ<3JE)*o;q@p+2r*3i#O3c5G2VsrTYRGS?G!T8m0Fv>wB}iCDJ{@3pkq|$= zWbZX|-!%6-M`>dWGsC;}XTSL*9xtRNuedF;`u%t)){@0*%($kc-Ns!$mM5PO^*E24 z$!xvsV|9gL@jE<y+~O5H%ezSkr;UEoQ$q&}7j7$7`J&^{=H}@b&VUlC*sgOWVT%SK zeF^iE*QG`h(BSr>(nZI`pLWigVrSmlGh4TNh1?pN@B7BwQPN}M6Z*-=ck@#%Cl<Mr zhzrv+<|U1QE+9R6#|ajvoYk=js^D7*r$B*>d;x#KV?BW>Uy1hu&khCCwroFLUqIjY z;;xjGL;KDytx&x>zSoW?VvTLW!9CKUPIOc7C<8-faeZ^Xu7@H9*B~+9G<Va`D+gSj zeX+v7xv;qjg0E1R!jB*B?jjV!2Hy9m4+<;wHF(I0_$~GySb-@9+Y_!~^ej*i$AX84 zae_vo^a9qjNgEj+N;P&9A7b+!ic~Jf-00K6zb*v_oiW*s??MeKJvfo^&|Qrq(e<z6 z*IU{$3sY8mMym#|JxEg)ZSV2B@A~tD8LB`X-;CYHJZr!)((^zi)4QGs`|dUvEXbhJ z9N4EVBNy!z_aEJGwYYiZP2+FawwU-(gxkZVjtY-yE3b09t!L>oy`_V}<(_^ELhx}y zar~;@TDp6D<3JnLRee4w>LiP-5UZBx<o5E1f!rt4e*7od*P7hd<6|sGV`+-7X>c<b zP!-_cq3755H;m+zYBpFD^_t2Y^~!IJC7Hq7e}ve9l3Z2YFut)I(VRa^lsYp-nzVG7 zORSRI`>RUL>37yd%~KJH)jODF;>VLLPs4$<_7P|ZcDUC`1h*7T5`d(dVu@4brCW`5 z5|w2Oi&}m?2HW!W=i+HH^<7V9pI3Jvp1H-BJbfqVx!NufG0DlC4<2u*4m7~UM((YT z7kzFhFdMyrh+G$c^1EtXThpJ~#!>quUX{Ml<Uz`DTOp%@uT$0jHN0^bNpuN#GSI$q z2z_nexr30tw|2dWO&$-Kv9%L^nWkXIdCTpwh+{lak`H%&MUZ`iol8$k%i`m)m8lW- z{rEb(IX9!AZFcfjL|rFRFG=m`Qz@u-cAJv~W9beqsAQ)Cy*XASBD<m;tzbYetU32c zg!J3u6Obk+yV>EfiiDp=`l_l_LO6fdT*^g%r3ue=IF~O{YnZh|X4P?2=WC@LNI^zW z<u@2PTpA(YwK5PWXGBc&r-+}6?BgV!uJX<2^l`GgW{yTc=zXq<N6ED5kB?WLI9*!i zHC{|!n=CS0YVHm{#~m&kRpWd*RlNDSFAY&cG9Qed_FXJLm`wfx;(u{7(%;*!j@dP& z;m%T60LcK>p^aS5|2K)VU16S}H3pBGSebg5pj$jb9hIcTc#lyPozi`e>P6ttNLBMO zJ{LvDHLPgFe4AxbzaCnx?mom|7R==_qaeti>(E!+U_|#1+2kUVKak?C^)iKC{705Z zMW(x1bcFjOOT{TjCiuxJ@pssh3X5PV#;S5HeZ7&kw%%@Vo$)Rh8`hP5mi>~TKiw$Z z8L>bY|9tB}TWL*EOg(cB)}a7503M9gJz(bj9m2o>(@mW=Xn#5D2`?(oZPO97BfMNN zYw&HlCBGaOvu{$5J)0qI&Dk}Jb>0bVqT;W3nRimPG{c2KzVK-mBHY3IO`CL=KvEr= z)AhqU%<jyXz53jrmq3Uke#iRq0@-BUplhmz!5CwPt#M=7Lm9F$p1LG#g$lXT{`n<> z-jrOmi#c8sWAIKgXrNkcEmAZ_g0JIhzYKw2!Ps-9ouAYLVu#9LY<CG#=oz_ibv?a? zX84ViF$j(FE2q+PMJQ+XiQ5Q}{_M;qaihNJoFQd#r2mT6mIiq75i^<41>>I^T~c@h zOe_jaZO2`b`7?%Zhxd-?w}yflrjyQ=$-NqHxS`HK8hTdMb7e0}k)(VI`sszrRu{$9 zrnFfqp%7!$9VcQ#UK@rXC)31F-g1?#HtK@&B02$Ei6`z&<Z+-bz-QOJ6zj~?&Vi4V zq=%Xzni7tyQJ;%X)jfXd_0SpnJKI8e$IVYHh$(`&%>G2!HOT8LfVMXLfJPg<EPNOq z(Xfo9+Eu?1@zWX3n(T$6x5+lMfAGbVO`Nl4z-9=86rxDG3-kw6ZovS;jU5P*7}P`! zV7o96^Y=FHT(p{96oxkGUA^4zr%OifN!Eogrv$@mcZwe3I0x_Lv`0nn-A!t=UV8`Q zzEqo`99-L|ei3R;%#J1$(6qCQP5nbQcQJ9+K}RrK^l1kOOqR)hTALN2PLOTEo8k;C zu*GH2=(hup@o02}1xW{F;!Xj!iLp<PSY$6fIQ($OS>&=SYr>CW#!HtegL%B()qicd zqKJUkv7SnZ?NqJZy}RqTGiMpUJroj=IReQVIyIT9e){yW(6|R{JYU6XmG%r}EDtui z@~t}Cw5*!TP9xiBmHc!<7Q;gCq2b1dZ`YrRc5Eb&HA@t%g#Mh{%1MqK;8`~C*m(0w z=9&P2@4Y+rR50ap5H8eN@l={Yh|kGMiu!=a>J<tGsg5(f{BVCWBRN_Z14kneqkU-I zR*a~75ke$7N(8|9FUZzw?0@C_Y8gKY4D${UXkap6{wyV5kroOTb}EiCT`D2-9>z|i z8aw%9{mDfYL2c))HsykIkr8<ldduY#y|S}O7p}M_-+W`Q?z57b5%z#&**1(pO;pRi z_eJ^jxW0!LEcndViQeUUIkI~_h3F-30K4YJ*7$mE!Ja=rS<jt8|0DVBIBwoM^MS+F zWRLK#w3@J_(p%X<T|biJg7(^u)MIDc27v&r={m0n-l+!BOE`hGqrjJ3(gUAgiNwwt z`A-WX6<Jnl0SEL8#sr~4x+PtJel|o9!%7cWo>Y2(4z2)i|FuD+yHz9P4u94rg$MA8 z0{?on1eo+jw8-54jliCO2$D3+VABBH8?kB>1p)0uSJO%D^rXm!x;qyiK(_bnh(Mf@ zYxUWGT+ny8j{&ZMix+_Sum59pZiZ0;1cR0F*(vypaT>5_|Jm6L7X|wF4#=C%1W7S) z^4@=gq+E1>Z#UEup`}0uSyRowDck>DETnl$5H6nYK`@547L(`F_ZX{ZAhEITOGk4g z5<Rw>%NT!@_%C@;E<_<py0*(j$_0v!Ni6R}Fx0!e=%ZG-)czN{hTG|>5ni8aB!Ti_ zjwWE1CWG9I#3b%~{u!|10s;|$yB@G6?SM~#edp{0I1qbUdEm@<SxmgTVw0(E{@_7G z@TN0eyBgFHZ~y62GTNBOsXEVv!EXLbf1Dbd-*?{0jr?oCc8dVMUu{xw`5hi)%0Fc8 z`^g{%*>YJ!ST7>pLpn2uOS<j~`Hp_l3a(Zd*;ddo-jgGmDS6&`z-V(@^_sSn{qZ1R zTU7^MdTZQ%k5GMp1fHxBi`rx!w0LJHO}W2*s6Oq(e?44p@BwgpJ;}j$<5aG!fSKhc z^k?k-T3x87-4$ytB#<3BM<F@XZ$j=K9Qa;^L?3NrUH{VXMZ&@D!#u64GsLIM>}#&+ z*Q}77P)<FE@9Iwk`HzmPhA9C1Qg`opB4IEnh&%*69N(sc%{9xl#$IamFP$G|%NFZv zh<DiFF7JMb?<A27wKsYYh_MAv1@kAEu&jkPgn5q$(G}lCx>HJOsXZ>dYNvxLV0Kr| z<LpWI=T?v(yK*D*+L}#}nwN7g63&KNibvdb!p~VJoOnGJrb#8cXkDXNa|;ONf&-ac zkVK1#oA9P)OGb^8aNH*jm)<*J;a;Xy3%f-P;o7Uk0{25-GZu5F_|N`ti}ap&)-w5q zGPzJj+)0^al8<U|NtV}JOP|?2J>Geh(p>nfd|lN5nb`u<e*@Tyk;i?=H-$8r_&Q8O zlJ>_5%5<pBE28a?(ITW&uzR1qn@fi~tDj@wvBvklK8pNH+Fsef_+Z7q!`O<=_B?$0 z%jUHccP9Vp@<zg!e8#a`8Zy6U{F^Wu6C{@Y=`delS8)H3H36Y%PXH+-PZ4a~_Z$!I zOa)j0-!p)OgHhqFs+q}uEZ`IVA=7ORmmYOFSoV(p8sMiES_aHZNKgJl)=E#r!g?ya z0GkA7GcYuIDoidR2)FEzrw@Ut7kd2UIgbQ@@dhfkZnRDJ7l?npt;lUH=ja=ST)hGU zs-S<7|8d0>{c(|00&@D<%mKWaR{dB8b7lx4_mKPO<fvi^`wkFWEyR-W;1#pKeAGdl zywxj`%wEqTII&ZSw~ER=6-?(m&cc(62GxEX+}6dU$PTE~U;A)}KaGq-j(CY+GFDBZ ziU7nwcs}eo>Ukcc&5Vuvnc*4yi&IHvl>WiI@=Wh~Ut-vkLmH`#4Sos5+FoBgpL2&V z9++Cfnt(5bBfFeu?X06nqZl=7qD<ep<ctg0wIJ3i95L*6AhENtZuWBf`1GV4Hyz*3 ziyt>gM=|1cbg;zzsC|$@JFZwPzI<q!VeWob4PH;6QPMYng~LYHMdAh70#q(C#kZGT zOt!F;Go)<1-muywXriVW=*mqr5?@+qCRAg31gTN&GOM8%?bK&eu4X#8+SunyIMn{E zc&%^PZIl;^!Hk!h0;WfoL4tJ^R34iWy<86Xwg53sSeMl1^Vn3lF-^ssmjTP-$7)`D z%?(Q(uPYoMQ>?69-9st_vj!`}aL#v#Wdy?zT-tW;qU=aD=@!9k{3!7mb}8=DcnPvC z3nK(FxvALSA)GjTOX8+GI!-$N?iWYm2UQ-dN@qLI7rbpb{`uUwOSiJ?i;1J$E0j4& zS9~8F3ZQiubrG}y)6{R)b{G5(sMrGP_aX+6^=!%NQuqseRS@$oRwRQuCw{axsNfnT zOLW^yw`k!J=D^=gMs9xG2&-7o|HgH(%JNN4ATj$DYBg0P7#EbQcW@}jHh4vLEQ8C_ z85zCyY&AVr#8Zfrgr0@6Bo9n^<v%PjOBTsMa~SzWR$e6y-A;4ZV}Gk^#4}xPR{05A z_g+Z2zd*I*2$=*`D}oqwg65{b%o8g_1zNIZFIs!3c2ct9Zty|BTuQ1PJd~}-)uhOO zPQr+b+K)oTD-bis;m?<Tj2|`rE_rsi>)n?3$+SdfaqeDORrjI^Q?NJmE;a+f%Vr}7 z;)End)MFIW&pnRu)e_!}I$D(9%K)zK^2)#bd})sf87_3M66o|aN_9@`5nbU4bNGy% zj@uOzZ>UVn9Wa>FT?cY><lbj~>>pr#Z3bL6wEaa@k96e=x(-vR6~VF{Eg8#YQ{I)G z4v8NPwMq^7j}fiHf&)Q2!)OvWkfgjP6XVE|XA&)7%w$!C-D;~Cie`~?5#T&3Gmq9g zzc2Qw@|<JRCdVj=&qwc>a&$B)6Q-VBVQc6e>@A}e=<Uy;ck_)NO;Ty*0}V=E4Q8NS z6JL+wy?`5lAUl;`)=zvGM_mc369tKAKf=BK7Gq|5#q9EY-1D-Vy}NSfpoq~%BoiOr z6f1dBf)h-J23NR0PpK}M#g|&ym%|OO{;U~>8<Z^!Z|KR*ms1KnjOWQWvtv%smM1V2 z0saXjwxeAUDua)A^L?VKQatae%v&z=wL7IqVUBghaPdZRagLJr(Ada5{sgV;wInK7 zXJEvIA!#j5mKQaZVcNefl!`1xeb6mt(9uN0h3;SJsS3=b6y94{<10_*jne}sI)~Dt zg|$sf;}alNqDfokrDnw*74r=r^hCzq>u495uKES;R+CilFpMB-o1Tp{qRwki6f~@Z zECWSblJd7Q(yR>A?^6a`626{kv^<4-aDhT%8ikxy&>+5V=ka2|Q(@NMg?#dw3XyN8 zYH4bYm#7L3wbDXpNBYr0N85VL8Aaf6r5l=S?b7(bmEqWQ`;L{=%Uhhbt#NvuzTWRx zO-#9?1tTq#_ngX%rpO{iFKtatolO~t&bhD0xc3{<lyNxfc9_vqGIU&O>}$I>6p(}K zTK7Ada4CvPOSJMXZQT6oQ!B8C@NO54Q4PZ^(pMV`VXCg8x@fi(wTsm<pR;^g6O{jL z4R;s}vy)p9nku~-RE#Mf%LJQ`5;V`H@tUM7-BnNuT<j}?<;qvzE-Pz=*~Y|WU+N{# zfcatW1N)Akw7b>bYoYE@-|HzYt%CiwoBW*XP5~FV&(xs0Qp7wkWC*U9VMe@J4?P`3 z(;T~+H5=WS_hwFm2N%QP6Vewh`h_dEJ1rz&7qrL7$K}2W<A8bz?)>&YmvVH_hBAeO z(J17&eh5=S)|;Cg?(N*npD7AT*^-oAyc>d1vJs-Veq3<1T?Fz<7e|!}<yiJ*wA;)o zU~Ds)K4EK@Y)bGlrYS*5s+WptoANb1%hzLElsRZ(2>o$k7dEMAj8f-B`4OK=2rpKx z4SJ^gLBFgf5i`ctQq`7ZS>`|RT8A@{c1n&Smy>+Fa+U+~yg6;=t!@=d1>yQjSS0LH z=d3@N)7vFqp6pf-F)w8wD&7n@6iLVsGN!U7HUNwvi~+*b4XTgrs*Pa-v-(OvU2YW= zLqt)F+=C^3roR4+dKcHPqS8WB4*EF7XuW0AE)s_eFv`yg&W)hFcqE2CS(z$I6@-&k z;c-5v?w#VLK}1q7$S<l`Am0UL*s_qNtnb-8hPyHuo%q$69M)_7il8ADxZyR5@Y|T$ zZ!kvB+503q+&Y3cyUc6EuEHxTtBP-eb!+&(?((^cb9Y2tu?cFE*-zFzDWQ4@FZoS* zsrUDBE&VTfgcCbH6l2Wf$;*dZ`0@PJt#XV?V(U9jaj}a5PYdlW8`&hHIAqqe@5t!F zOuv^YTWnedd@5X1aJ29-bLcnJ5-K~?mpbu3<>ubf$$^%K)%E@)F$@H#UoXkDKbMzt zG2r0rH>=Myc3-=Ex0snJAqdT_re&wte9nEhBsyAHC*5~eX4&_px2g^rnH(X)X&u#2 z%jUQp;yjzrG{L@g&Efu-rnjv0?E2-tNJo-qszQHoYJg~i{baimM1G@Z8c7YOC)2}t z8S0=8ya4}Fc%WQk(WeFNtPp>rtZ`WJoa7wi+5&&V?a}$)Z+^$!4+!GDJ<$M;Tw<cy zm8<nkCcdnMwCr~+N@`S4d)XV<)`;)y$SD=2xi3pnp1hfpq4c<~P%?mFOzs&(5AYaw z<O>s9;N?JosQUGERF3!Q3AC|ir7P!o!<U)NJe8-d;~%pe(bwMj+<?;Gl2)6qrvw5g z?5<RJcWa-f1#=~?t=WA_%l`Uo{^^)mn!$mpI`~BZ!O112uMAVfeYgB&hw{%%F>%$P zIyoLy(Gnxz=_a_dV)YYQV^sCf(NbT|D`E=>*v3Suv*R_(AflN44pAPvZO5-+t?aTq z78>f&K`eXT9H@9zh01^v#wwibMTv{mt>7%|J<;!^%cP|uOlnHdS2hg%a&WHqqb^<S z^vUCZp3_R`AZ0mp`z@D%_j-RX9gWy%DY@uGyOf8zD6ufeIUaD~6U3JXa%Y06nf!xm zG%LHfpP6-0%4{k>X8h7JuiDMH<z9ac&bF5_p!CqLWuv3u1?&om4KfSptrzL(@PRs^ z66^Jo;5tdZDcdxX{V=@aYA;KdZi_i;fcuR$mfwIX<I|<n&p)}-@@dgH=8|2JS?f}v zZO%7qAxX`J854zRaPA`B2rpx2oml8Sv>lY?CHnrkWb)HlaBGoSDnE|h-G!AkV?8IB zsl={ELQ%-1th}@4LTp2+9emp~?-L-?lVtt{Vupg3xxh>iMa^=^`zpDC845m+WVNVM zc`IuAS=&#|&!U+4eqS}yZM@rKz7~{2pC|^^LD%99W#_oMinv<iTqaeMv0qT*l-WV9 zF@0G~{5trRpobkRs37Cn{SGkW4jOm*!lzcQmS;HRRtamiFFI`0`)RU^T1>&y17g<2 zG-j_{zjOPbv_Y{1$Kv0gB?x*L<0vPoQ3+K|bg?nDt%v;W#b5HL>80;n`NuUq$ln!< zoZo^Us7@Nr?U%R(ysjA@Qq1jCXY2vq$HQZiIZv$CA_kH1V1NDs*=CE!E55P|1znFw zsT|%Rsz}w&E()v6%Vh!0=D@^7PqjYN33IcnnZ@?BMfq6u&h|rMM&V|UT%~~ZF9RSY zjAoB;FP{O9kNq%EF%U4K`Kh<^?)cz!Tj$F!5$a}F@>nRP@9kYNF@%x>cl#V-gRC*V z7l{Gyg;nW26DPHnICx58V#hbU;)6Ol71JjB>!Ka=l@LAOe#Be`SjNgXf<pyZOAu?~ zew-5*R;5+8#W8wtzWRjSQm^UFwai@K{1y4$Q)51@YrR=4`H%h~6SY2k;?Zei#Eap~ zD4PsSR&Wh-TnMrA2=n+_yBb~)1JkZ5jf7NEp+5IaWRz<(=#?QO{4%(Lua9LYxqVDB z^K}Z<`njuqJz@lar~;d2?hyjGwO{q`o(=lCTM4{=E<c*4R_|mRR<;0<-%<?HyXwXm z8xSJu#zE=AbJ2HNW(D^9au*<F0H3(nfhIPJ+(8KI-5cobi{sVMC+XU+F8frYlBg!~ zrWIEHA)7VEoT7fSw0U5jv?g;2lRMUxA77;tef9B$8XsD)2Np-V7Pf*mX6P&B7^Uo) zVLN@5-}>?&vRidNz;(W0bSl&K<3P#H<@##AvFC^XmZG^s<#E0V>I{nxTOj&2jlj~u z5O%%Q)Q4h)t8^AC=?;JnX>Yl`2?sq5m|t3SU<#BQ@L9AMGiKko39kfJdq4#`UVyzR zygCa)?XyC>tP#_|yV&mDt}CO4^o{=8`&00?Fx)A|7&Um8$GoSd${KM^YpqxG8##5} zN=jS0gDW%n_~xP#VB;-IRH@7~Rr`zxiTCT2Ga;iwT%{U=&rVsVuosv%-&}a};np4f z%%SnTXMHv1e-^Y|E^W|D@Xo|sQOK!eog~Lz+I#OOJU+i*r$hX3QkrF8Q|ylFuwh6$ zH|9>BUs)_L@pL|*1*ntS5P%*sBzq#*oyvOi<A(-bi)ggEj#OI6wKlA@G4IhYk|e%| zz3uJeMiWrL8!FMm*l$Y9K4h5Y=Ry>PzVS|cX<g^amW_}O6>80_`+2YFARLu09cL=E zy+eH)#0P+)a_xV5;WEgx0fp-`fb=v(?gNAfAhe_#MQ$R91Q6N|ZbBs$jB(Vw-xRJq z0{~_h?yzh@ikJBw1%Dt{i-teS<jN@Q{~&z4?hfeG;{Ye%*$bGm!`{Ih#Vfe~5zCM1 zhiKp5WF3Iz71+sSGOhn}3)IS;4A8dO#$(^4T0)c84+8Xf7b7cSovxMtkUayP1KXSo z{x{lyDUtNGmlQRbe24Q-U~P5OscOgV*#&az&0d2d!<2@d_YyWL3$c=fudr|66HhWg zm-zpE050(sxl%;~3<5mpbB~Tc$Dxt-c>3-yk<>qkfvJLI*y=T)-5hyFZ7u%y>dkGo zts}0tIPwzB`*KwX4IRrq+{8Oo$|KlXLTup~nDk<T{Qus7dyAaovcH^75r@!$AZeZE z0|lY)!@M8s!GDkzE&qoNeZx4ZxB>ix_3AyCkh+_L|E3N>5a>l6QG)Gn{6l8<LRkd! zZ&3V=+|;v8J7;X(0H6w819JBYh@Nkt3Up0HR$+}v^R(-?-%;b&UntFr76CLK=MpJW z5{N$R#g76<PYy|>bS4o~afQ_Cf6{Xfgq%8TCG4>l*;~oMbs2Bfb8{G4DVy{XSO*Mz zHbFjWt?(a1H!xEaweEaIB}pUzqABwggfoZa>?aqWhbm;Itx6keWfb`zTflgYYQU^| z6G)%ifhB{muk3+60mje%Pk>P*i~R;zc5(hB4A5)n$n!w&Dqb#Pl$tA5b@xWhyi37z zxBtE81GreiOJicN^R~rb8}{p16H^a#SKlOy2;Z7Z<*DnfCJQ{W1}M}2?km9Xc)`vt zBZ=pr6`&4+2cRV<k$`k?WZKO}9Q_^6qKpbL6h?4Gx!&eNIGj(w{yMZ|zbb$hfun3v zv%-PgD`2MY2l9x{`5Xubm@08*?|arc@>3)};_l)T|9qLT7q^9KQvX<;4&gd5rEtUm zJ3j&Uyin@j2gc{hBKVZ*pvw8L19T7SAx8C`^ZEM%3FuH0L5Skx$L1xxk?X%+V}Oz! zCN+Tm-l`wdf0&h%AfDpxw6=S*GX94dS6(;o=KX!L=>l4ouE4%Cf=}muPyW4PX+y_0 zv8A85Z?`ThgeJ}D4XXjSrT?FGyQP3v&gjoph=z}>HF>^3x+7*}-qL`tTXNMeseScW z`d=rT2yp7J0wQSKvz)0(z;kZAq3SHFq_!J9cjqkN_lb$U2G5UHLH@?R**%`o7e(^^ zbz;wUh+H_qSaGPWr|gV`SWs_sL%2L}4H(mDggy(Ju@7ooQqgwR5K2HZ6kkx<#bn7R z+_Pm{2beN&ry3Y7xkHYY0mbaWcQsLnklCp!Usj7SL>d|sxy&ECrUQ=|_xZ+<A)1se zwxkPj=~d^(J-$5aeNfU-|G7D*$IVpsN~k;HS;qvUG&Ze^^3@lOyq;xfHH}kP%%BuU zj9tljwV+UMj#MJF{j5Hf&qFfQwl%npWQ~8>&FyX8{o^$53zdB~t@X@A`DMiA@lt`y z6?xf_pEmRq4}Yz(598zIFj)mxq2Aao>rtahw77LQ!+>8_U}H41KuNw=w1vQ@d?{{w z`Ox$q-``O3f3}=o>?)3!keY{bPPDlKK{D3yN8U#3q*)%A!32Si(P_qu!M>NZKyIOO zkP@M-E3x~Im4gdv%$a?+67iu7Ss&!Fzbn}w&N};RX3L}O-j^PwX5F@ojDN^NGjB8J z?amelRHn{Aym|=CXk%IwyFI|O4)lji+n-}I8fO;iHoMjJR7y{jtjB!m-<f~VNtAAI zx}BRx%+!Zx+GBV^b<#3DB@#0n+<PoMwKEkvW%4=O-Wz)iK>hG<aMmlm-!co(wVmT1 zXCdiE<9kQ+*S2SWu#W!hKj@Z&e^jxrRkBgY+OkZ%LU-TnK@X9wgPtp5g4G#obZOH0 z#O&NOTdx^MSBGgG25oYNdC9z^CCt7xus5lzY*KM~!+0l-VUBOmtKbqVD8`N@xd64q zJ6!%N;@U{f&2e<9W|l!~N4sm10nf)bN-^Jc$h1;V4^;ZrDlbpClDa?)BnGG+cBtT- z*ReO;7dzJhW^V8TW)(d-zrN0yGle%!@VC{Ct{@;j{OYb<bAA5Y0~GuwZBM&P$w;*Z z%6(0xqWOHHYwty5l6GoVKTgyJ|0o^a>(-_X8{Dl2S3~GQo$MqU+eOA2M;*#T4vff< zoM%Z?afzw+ryGyz+Q;Oi7>YE^J_rn$`Q$N`xNDtl?9^gFcp<7d_}o8a@y_Jx><|}Q z<-AdkMd2pgr;mV?e62nyE=cdG*%|o*?|VP))3M&2mK5Fhph<)FRY1TeU-7-?##<*5 z!q}QzG(>JGJ_X4nyF@#$5sW5s>hA8c%1-iWx4|W)8k<7{4hwU(yh3e=A0fu0U^xBm z%()b)7YsM--Mw+nj_*P*5S&?7a>g-hd7PHSK~ziT*OKo**YBF{8?DQ2P1Hebr(gKT zl(l55#<bi{d~j|Z7xB)3Vk2MKml0p8gF{4JZ@}@E`yFaZG)+Gt*7{KNNjvJS6U)D> zz51Q+qTQ`p&Xu1f87FPiB}*EP%+$^l5YjU|&%_Xmvf{hD6?-#(eGsw}E{EOil`26a zXoqE^MVj(>^erqLKEvNDny1{*Hq@7OR<pAdH>T3ESWEKjhx1*2=-C+_vMXE^vFJpG zS1ZF8bvrja$qX&&P^)m7+lpWr-ycO~GxTzn!0n`D`p4kzarzSLG>&(34pV1JPafcg z%5nM|XizUW!OZ>k_L*x5FinxW;H<TD>nmfgAEL2b0zc(}HgMl-1TCprOG=D$vO053 zwyV24*RQuOgMV&d2qej=2o4A}ioy)55O=JVvVLkY&L5OSUH(`avtp2f*;CBosl2IH zyI06?!?)_+0<4Q5VobY80X=^DTmH>SxSBb7?N@>Bv=3B<r#iYS@ZQLK^{p*K<P&(4 z=ryV0Hyr$t<cHA*1&MJG9S-~08=4&1X63ss!uk!Irb!->!5!rl{#o0L-da6O8A=b$ z^9ZfCv9DNqZN${+Zx4vBzjM_O=9XgU2soT7R}Sb3#0a5@jT~lCe7hEvcQdRcN(5P~ zQUnHm1cP2KF+t^ADxHnd@q15$k^@Mc+a~pQacq$uR(i}2z!_H+_OC{>cU;FgOa_B# zV4lvAOYp1`g-*$2Fst{G@6{!b!0oeG0zWGtiG_TbGih(iTxOiVyuwG%k*0pdmd5=< zQIpg*MDiPmj>NM-FeAPtI8)6Y7tlj6;^ydyMnL2E^toG%oF&^en{Nr|J@Kl=sk2G` z;4~o|_wBcnv<-+u(nIv8ThU@Sy9N)Z_51Y>7N?)(*p*Zhm!9>>&yD|fM*TzfF~;TX z#=9QhEX(rfw2V65VJ`ikB9Xw#^J$~%^oSlyj~>&YrMC4<J?#Qj!l7e>Gt<w_79(Ux zXrN2+mjBYs=7z~TanyI4WL#178@iJPuE^x3y-RRe(K3QG(jBXH_zRJ?c<)Jq*5T2H z_S@e>*ay0;j~-dxd_y5?y8437lVCjwrN_3<8af?z^ZFEc2k=eotG-&@e2It~L=~;x zZwZB>6I;lT3e^7I{vN`STU7DA7H{<5;5k=Gqd1C}0#_{^Rt%w1*+`?oqvs_RleY?j zYmh&rdhsP_SE!tWS-DZ(in4#Sb414G(&<l+o?U@ZL1(((ZfrvO{z=XJfxOIP>dL@W zZJ6W>RTp$3m<k`UH>FE3K1swk&}us7Y)Q!-YJ0Cq+1@*4oWH>lB4v<aZ)Ms0TJM~O zK$)_w%bDF%aLtnwiK?8dEAnh-j_J}p+*$jQ7P@w>{4VplyJk@p%_wF|F>=?tcd54O zX@dcEvZ#4|0%mH9DspQU($y<#RN}~EOjA`HNl(d0Yl@|R31z_oiWn(KsouzIV_&pA zJ)NzJNd2tGRH|q%qwcrw8ZtZ`Z}+5nj79W_ucD#hLFK*l@xHWzuEJWvckKi9ii?Dr z<-+)v^Q!}TZi657w`Xx%X0FKOjZ2sgRJe#tpu(N0w53X|s-4|eD;|mJHwva%mg*O8 zmY0Qz$b8WGDS}9W#k$~93eI^p_p$Wo-Jue71p2+`xoBtB*@4|)=^d;O{l%jlc6it* ze=77A#K}spuqkCx3wURJ3^1Wjnmry?LET!X;o|nFGq;oVT)_mNm6QRy_#4_yO;OQW zjCTiA9z?^ww24u@;THDYE}$JM!5%JON<?#sTN^uubdeYv8xBk3*AV9xtR2j|3tR@g zM++~$|G3PdIX>7fBG?5^f{}|waBD5oYO6_bc>BP;2GlqgZe*!wCpAo_%ushQ2YM&3 zx?kv{ta<puj94K#ef#Gg&ya{w4MPR|_nLqiV_=%m>A9890NO*rZLq=!jDUpX8>a|k z0z7S=iWMdPxL)Dnhx-td=WbzHITW4YF<uJ^x04epE4MO3bp{xvq0FZ63%Fj4;LCRQ z1*i^IC+gVHX%3YyJK84a3ix_|)&|?_8g}=52q~NC;Frjz70-VceD#K_DR-YdF57e! z$pG~Y!_dd@Ugzb<c4x+<fBYrADgXTLQg4NkW3ZsH>QaSjox%BfydB$oQBazS3MIlg zKK~jv{4_RVF<%+C{^8a;jOe+&w>7HeP_N`;@71p7>r(YZ-4uu>m=1w3{myyC9Lxjj z(2yIbjRalwt|Ewrvou!wm+BNd50<u8Xp|XV;PClKo<0D(#T0v|t%cQUcwi~j)`(5A z(yFwna7|d<HqcIXsTCK{o11y}Bwzz}wH3J;!TSILV|ioJffmuTF6Y)i`SQU^PI$C@ zcR|Z+(o$KbT4=14b12huo8js)vyhmUUI7h37yq)1poar&UU8DD&S5q7-F_!IRwZRp zhfnIG6YlO@c96MFw<NN*kTRlIrM$5^W#2_hOy+5Nt1Zp{WY#Ej6F>eZw3#HliAPy= zV+5Tl+dj>C@67@3-j{*1hv^yl)n8W^s}Ylk%5ZySk@f%Sb!Ufd$C7?{8vg|u)Kz40 z3B-1{+w7@XEZRG#!@hPXH#Myw*xxVcVDu#b*cK)NIHL{-H3GeiAP$d$tApfTiqKyo z!>0S6yo%&nn?oEPe*$K;B#9K+BogenjN)Te0S6##;f75IleEi$$K-$hRzB(}*p1o@ z=w7|Z`{Y=q#Xre^`wlme1wbX8w15OagAIVKF8?Dl`7b^lx#avu%AbvRp%!{lc_Kty z_{C#wYqE{CZT$Zmnf;mbSM~SKi$EF;wPNz7L?V}eyGFg6YfU;jEu^{ne}ZDVfYzh) zSDQBf>i{K^m_p6hNJCDF|B%@NxUY~dAz|asb2ahTaS{E?^D2dQ4}M52J57pN4voG* zfe29?3jg&NFdv~(`qT0%XYdDryr1siORI1q_6*}1<<BR7W#KT0;Qs#$&=UWmSsa<4 z>8((b#&R^tlYVP3`wS@!`|g|luTw#h_h;fCa5n!QBTow<Via^f>SLh`2fK3s_zgSy z*YgSt_CKfq)4$MhA$5ct0JZPJraJ*5K-{4rh{3slExlxb?e(?L)``6##U4e{>8A1j zJ{ESoEWp=}{*^tAa01eozeZ>B2Q74o@_dN6%pJw#Y_h%I&w&y96$l*s3mt?1;w~C0 zfKe*3P5N34{Gy@XaeKaKx`qEIxz`#2(2wXtL<mQZ+LrNOaGdOcBcO$uM;?zN-|LwD z@%hfhXE{`am(|Ga*Z&V|?-kWlw5|=Ks7Q@S2LYvb1nD3V5fG5xyGjiRNRuEXiu9^f z1pyI|5{mRrq)YE0orK;KYJd>G<^IQ3&c!)b|BZu?fpg6{SF+~wzE3F@s@EXIKNz1s z{HcBQk5Eh+4BXZ~Z4sL(;}(uk1YS`PD9etQ0da%zf65)J;Bzn5?%KL_IS@dC0c^%5 zbZ~iu?f^}V3=HHl<RAcn?Gk@#aXjDywhnwqESOG6R@MlLtcYMgt?`qR2ZaS=Xm4By zcsm}ZMzFC41cl_HKqr@huI2=I<BtLtAah-<1^6(qQ6stsSJkZn+dF{I1>`OO62X5j zJTJ`xEHeV5tH8OF^(L$dmgZgAY!2&e%h=6WeL(gn^rLd{pFpl4<-bvao&-jmz{Br^ z9C7YpwQS++ZYd0G6aZ8v#PRx<KK;o~R9}e2Vp8$-Fa<NO@V`F;{MM^}+<-27^2{11 zgY^+i`sC#d4u94#T6h?CJZ(NXMd<B8`fVK4M9=XcN}}{BeK1EDTvsf=+tnuZELKvw z@9qhUR(P))Yip*a7bl)xsSAJoyawGA&AK&mc5mI1-d~ek8%x(LF)lJ|9&gWlHf1XC zSW~W*?&D7>mS+~&O9NJSt1$zuyEhzCqO54;IGq-%#&PP5(0#SBj4e~UPv2T;3Mr?; za`l+=&s3(^tb`sxC$=d?+_;<u5sn!*rlGFL=!VnPz%SzmPKX;Oif~hNXw1AOl@gQq z(tCbYw(dR-iTJ#|#7{5X_CLmH@nJ;$2+**W&E2Ru!9n(6KWmSLvq?Wedx~T?=&8o+ z#8exEP`W1WY9;MDnKxMAO`$7C_ph4)SqraJ4Zm3lSijRNGB7opql74{NmdK+dE~3+ z+D+)k<DZ-g*?vl-po6E$F+0{2y7219a<LeP8|G@d1r}+>eOoW^bkd?!E>cBU_gUUe zS=E20w<dfYONYY0Me8-o-$BzgGkaKk$IyPK?I0&q^38iukuP9t#>(ew<O?gSct6#% zy1)T>wf^&w<9dT$_B_@ICI1$kvZ*>|han1Is83ZK-ab(O#Ffr(W0d~zrUYd{sMV*i zE1${I`6KGEspv%`bOV?P=T<y9yY4M7Q9cy&4lXC_$)A@SF<Ugt@Ur^ljHQ{m`DNHE zxvvaKQrQ8KEwJxeKVoCXfihV|#<no}+YYL;O`a>HM;YCbD>#=lC7AGbE1~Q1{kn!~ zx@fZLqb@FHxmugpr>t7-cvkc)TfOtD*wR#w*!$Pd`d>9XU*yfx=+M<k+vZh*NKD!H z+RB4o4usFRs_^xTp4O_nWZRm?uS9M3=|<gk6wlJ=hsu<_Ow<2dsz$>tpaC(=GO=td zYZ!6m8mVMbb>0zNc32IBcFVcsk`?B@SGaP+=Zb#H{guRA$CvY)EX3&Dusab-b|Vd1 zU(7Znh6#SWw@#zyy-hQhYR-R`Op*}^)c%c((XpMvH0^*B@?r<wJXsSlRAvegUL@vO zq`}TeqzTPTenH-A+-aDKymIVH9k1w0t^E`4DN^Thti_BU&_cQfHPK_o7Iwp`Ecwu@ z5n^Zj(Xu-4)KWUk-g>x9P<B`CCEG-2Y5%yld-W)BAq7VzzrezVBsstslN5hVZdu4- z{Lr8umtb&WgIW|a;I$OIpEfX1v%7YN0tJ0MHCJq@nS72$$9a}YdC3?&lay{&?n3zQ z<qO;D=8DTCEHzH9ld({oM<5(P5$P21DEqBx^jUMAOAz5~aq`!k#;ROT+qW3e_8U=c z10=jAZw=n=SVPo$H>QB50S*S*A_BZ)z(jZnoI%Za10SBb0)Z7l-FH82;o%q*T#Qoq z#*p>CAubg@of95qe{5J*btm|?;_}3}<dnt1lwGd9U}axJ5lwpoCIOnJ$zY<z_n%!b zq^$;ORZzI@UW0n(v{k3e_pVz;B0J_G9)aL+&1?GTm!eWM#U>~_>+mEd!i;{emlewe z8q!7Fg+3+rKJ}BGpB#2=U56T^PK_{0vYh>*#nSnDbfKPkwFY%ZqtYVuujLMq91E*7 zx*iGl+YM@!U2t)^n=DdTQjB>(%Y+qLXP$KZb>eOZId}Uwf(mzsyl5a{$l-g<P2<NO z%$biSOs!|lXQrpcM9mq-FBcE7v3|$-qY&2vhLTOeL7r}$^P$e{BMpjhL43lH&yF9w zQHC~Rfj|Ez)puxFG_^I)!uAOXYq*Rm)~Cn}s)7;@_oG8G_{rYS$xeBqhVl)k=7Fw+ zJZ8Dn*w7awF+}0l`8?kgR&I{JjovAN``yM4oN3HrUvIXi6PIJuRP75)P096?)1=3G z9$VRHcafo=Sm?t!UbL}y><8pwe7vd7UaZ7O>mL~{1!p%#30L!5kx9ozYB=pmY{9H- z<nLpF;2?JJp%;pUn{)@c-ko4;@oXwnSu&+W_jBS^hmmO01B~2oqN}}BP1V^z46J<h z$9+X}tTYDIyD7mUG+r5k-VG`7EUEfd<Yk**cKvb#%r-(L&P>UuCXQOPLebj`EgTC( zJ>G_DEyf1n?*#N)ksdJ9X<&jwO0zY-&TfdRK;%B0q~xR(D6ZboT|Y1V{>Avmhp~nl z-1~+H=W&8fvN-p_CN}6jo%DGmDEhF&io)r#llt3&oSf{5S9&n}o)@Kxj$IV<Y{qHn zkL@6rm7TN9GOAa%fuz49?{T?H=v-5YIY|sCNVrJOEgzaAZpJJF*>X-g<;U7o8^&&x zi0KMw7r;+GbcqI>e~s@wrwet^ZC?IJ_a>t%%~3lclPkgIM4x@9mWP)YE<2F=xXaJH zw22S-nHqX%BQ5S|-2Jikd1>U;h%^;q!{l*mLobJ+xUcZxwvoa#nUBG`(Zqa7pR@7# zYY1wb&sV>PSWU#WO4chXv^mzOB1$=vujKUff?oo6NYB0=)qhHtj+=X&W!yB#;Twjw ziS7O1w|^8m)Wqp$S%E&PF2TY(11MwL(s{~;{O%zKu3M5irJAXJ?(*;t=qB}<w~c_% zC>zc{-y#1L?bXDFR%tH@O9w})U{f)#w!Ny+BaRxbNVw1Q;RDhn37w8`L}Z1}mnNx% zKnxkRvL3sScRRW3Q5vQ*8h0-n>oRRLh9g~o9|H$Dct-$JRdvL!MUA{|_V|$_ms1eG zs~d-_+qIT>fo2Zfw~NP_fj!?prnnv3$|*+ao4QxUc{gOy=QWzSS0zRHe2&l9UnP6l zp><eDE=1jX*I8M#L}&5VdVzSUegThOOMeqf3`6T(cyOj#B2tS%Mr0|6;aQFmmC;0e z`)NQmM$nHtXZ_}{_40XhNQ(dAL8>MG^on<l$irW5PIL)F6|1s2UL^GdAF2+EsI<|i zg>~5vr7RCj+U0lSRJ&E#IzY$Wiu}PFhTKvuRZ<$VN5NR(XBbOT^#R(objINdP^g5* zI-}BfkI%9h%Ff|=nB>4xv#oO&(r9IoVSz9MkPB5U9%W%C-B7NiIHK|G3Sn{!$2z08 zTq*h)s*?R@u9dt((FHTc979tkZSSk6IAg@$<1x9d0ngH*oCzyp3HcB89rM%-xUV#R zwwV`=<%}Cr<5d<CEpx6K(Zci^y&0`Z4Hhv8u}Uxmj+A!Ko^EuT<0|2*s04Ptu^Ap; zCpj{VWw(3o^=?F26g9iXYd~wz*;+Lxfi9X4s+8>sdtUoCjudWkdB9e9E@tK0?XcB| z2XURZ8C2PoZ{?N9jWj^uz-i%$)fJo~5>S>pFm9}q0=+b#fm3|DVzek-xymV#)Yo}M z)x*X6Cwqcuq0Z#?r!4zNE?szTtdh_Qw_b3?w69VM?1qX5<#(04?XpTMF8#U;3yIm& z%gzax?$~-+{VW%zkXn2vqTMU{sjk$tBZtM7BYq@>>1@iO7In1Zs<>Y)jFxO;C5Hwt zio#KMLQ?ZJE1n`bw`@M!cL_Ok&GidK0puHqyM9Vk5fXp<JO<|tG?yth#=#&th<9<p zI_;|z4w<o0JO2-2Ye)On6s~+f@vtT%(tQ<b;BjJh2K9S_4PO+F8Ud(D+`&5sP9>yt zm2usteVK748BXHklhlv%MXy`Xd_t!hi_EE>&z2&-j|m!{J!uR<5%qU{c`qYDL2-Ry z?>dfuK^QAVg{PUv@$QDsPr>$pCRK~N*LgU;9<MNO&+5E>R&t1#1mMytewD@6)~szu z0L2KKtj#_-0nAmqv$#-k6-BmA?GkZDaVv>ahUdA>u<TG~jQuU-o;*ijyE<i$hCviN zNyQkS9Q>04r;M}SYC(!dU){cYf-d-u9MDz0(*>RZGT#lIA<$~PVjQd{<Mevr)KB~x z$vTb-a4MLDZ33WRP|1U41PcgS%7F7a06xA%5CAEKJcLA@RvSf#IoP`Swx^}cZvq2n z{QhqOwN(d#BG^>`&X@o#-naPYW&BpnusvGX=>qKI7m9BHXdz+Y0#5%loo8^sRf%K~ zUW$>#y(tFITAg1vVt#N{D+l&dcN*UWT){({|M80Y(#(JG2La&DaqfgDz61z*1~2OX z!k6jw3j&=nXLh`T#Qfn-#!rJ30{-_HD_rO|KqV8%Us9~t4%=f%T>~cih3rq(piJx^ zg$<w9DfUl>eY^FadHxmd@DLP&nEiXKfa~0<L>RNkoFyTQ06#qkpiK=dfHffNp^3*g z4&Z|-M~#FRGEPXkfOtfp<NnZe1NhtD1k`{N{~|CL<9P5z<<1+aQ($NT2Y}J=FLvIW zrWFA97k>eSvsJ$<5&Ae&wDjPyH-X28bbnqjlBfwViuwg($I}c>!8)_84*Ot<st;~W z;BFt!@1KE|U@e91D1M8Z;=}fVD$r}=HXX!AeJ)0H0N^8=fla6p0LQDKc>p_Ss3Np5 zS$H6*0`Jdt4(_N;;UNrIRZVUeg*ll%DP<?Gx9x|X>H`&xdDy@f_ya&38A1cSbR&G7 z<bIJF!3yHSwTKt4FC0izf9bZ9O=usy)cJb8*cCvd$3*8I;Qlv)uol-`AW<%RKKBoq zfVe3G2waR0$XGP*qrNm`@g!YD!PWL-6p;tR>sy$qFTe$|oZ(^5aIsju1_1K@*MfbJ z2q+6&zkiIwx1O+~^93tv<@mXeDrew)m&#w5^lMG5TL8Hve^oQrVMxi5-vq0}t|R{` z82z1eu^k|d0gO+J>zN?5=%2AtQ^nXHyZ!QsW&nw4_vAcu4~*3JlLbB?a2W7x$}H}G zBVB@3*hQ=!vHk?WC?8aQZ>W8Gw#|^e;qB-5(g($H7Xt$s!06QV-vs;XlIwV}3p1a% zr$pd6|L;9<ZLH{?yS>@ZHy$;YL9mum{>Ey+90mHDV1~8(jr9D55m_&6!n(s3vd1`8 zNS1P)KKk*li^M&yyN?fmX4Ai2E!2SF6^+1$zsA%E))D_!!I3nL&5Bz6yaXbu93v4F zFTEHu_V$9hg;4U}0ssVr|K3n_raXk#rdGg2ndObw3=?+s=pM*;pBl~1qaPqbzvI-; z3&aN^sx4{ad|9tRZTp(O9>2Yso&&`{Vec^_=Q^`R+=8<$ay$9hHIZOCaWH_1Vh+nM z0V+icG2rT$*t1)Ho(*WN7*F~YG@{KnO}^D&%-X+v{a)K%QDdh7&6jH{3Vi1a*)nm~ zBI=#7S>bKZxYa>)ygiSSc6M#*s;VqrfyFS9f+)GgR)GP+_rqRp29UiDN`zPzuabV0 zE~Hk*Z$rdr<yCZ!FL-*M7VC?@i6FOvx^8dU2|HVI)kmt8rF)&I#yZV3v$GYpFdSuC z44bvIt%&jefcz#P_hUfH3N!fKKI4uNz+GjVn=|FOd~DJfH+MQtDiI+W!tf-=K4}N_ zxYyBdBF0Ng;4z&yGI^UEZMMjjDG`tEK{3aacw7x`+<LFjX!bKj?87Z0o%+j<j0m~7 zWjTNcq~NQtU8ZpM=Y_d^KNj9uB1nPq3O&}!V)^5YT$UE<$bfCVU&t`-vn%z^c<G9U zsYb_4A7a0R55wLTOZJ@xs&YTeGVS_EN(|#yPd@ELh#q|VOM!0u>aj4$iMWH$Jx!dU zQhbHAe7>0!F}>e>Y9E3#^T>lLuOeS1!oD~PB_(~|pi=j?7Yui33sjF(x{<HjA1G~+ z?Z$9df$gA)3qUUQM>=T0Nm5P$N&b2fMU595OE!9kED8-1pBT3rZ5uy+?m#>5$5=4+ zwY*1maxyw;u%3MDW*vxhU1E*|lY&!5NB5q3hneZnNt#Y|kMwy{ii8WS?i-&}6@Cc5 zvHZw}zs=gykY(hI8e83&659@@^mE5dY++DZESs;HzQv*kTAP?BaA1yf=AjlD^SLjG z(HAgZ={;H#zqE~5YIU)<xiPHMWv;aDGcCbD&==-qkltyda;C2PRJX?A=h|f%53M-S zA>Z#{1U@#M8y(;um4B;5A~z(Lrz88jre+dXk>SQz{#8pI-FRsCUdeX8k)Hl7B#R1( z*fY?U5(+k5cDCRSoj-C$6K&NZU5Q~WTK;aRKKavqgHWA&?V>q7^F1$$80Q*9h$KM> zUJlT5&?V5DfZhpKw00lUQN&;XF_ymtd{rw@PTB*mj&%CDEnY8pb3iAN3t@a)wBMHZ z=q&Q3K2d^_z@-lg`b;Uu+tL{Rh23p1#%dwC^*6yA7}bF*A@<wOoG)--S$loUwC}w5 zo8Z_|S+$15@)o=3NyupXtxmV<$`})C;=8Pmp!JKeH-0{60`rp_h|<tbP{^?rsDjB~ zz4<u(9u~5q;nyLZlSl};*Z-b@b~b5sTltD|ZH&s5*rajSkPw-Q@1yyK1~V>MyWPoh zrkbzf6LN{wv<+b-@&3uXpH)K!@`idaP#4zhwY`URI-2?kqt+~@pegm~?$G-tIz`fa zkOB(#qnO;W?+6EGZafLE$3isYz|mW*7Mif#l4k<<Bt<gR4$X;2<XXzo_YNsX3#R=d zp%h+9?zah)TBI=Zp2cWQF1A|H1;{{MI|Ia%f6&U9pv6%N@JX}Hj)h1oK1lFz!=TxY zMc&NS8HI<L)i)ZCf0RsFAALRl)+Ds?n}Du?2Cdf$kYYna&9T1C8PmzS&2%9z5}(!7 zBYdqY=yU4pBerk*Jdc~<sS2n0#9`yo`UrdJ%m8b(NE9v}i6F;H>dWB6nz%3}fvLtd z5yNK&H7Q;d*Ev+xw<s+MuN>brD=h0|6U{c<bjI9LY4HQ=31`0R(90ovbYfK*RRj*v z^^SPu=B5*oFdU!%Dw$somV}K(#s=ZE)J0;RG3vmrF6YQ#jrEVMs#{UK-HB?R8@ffr z3VcH1_A+I8sP*QDLVB1)TU)^PLRo=%^PVZtMQeEIMFn4bn_)5(6I(cAGOJ<l;r~qx zE|7H7+)U0R6~ds5RSbUl_^HC}ne$Sxi$9?Swt8Vc^e!M=S!~y~m|K%)AH;$4O&sGp z^9RVPj)ufAGwm-BwoO)|P9{QMYm{1L+DRJ{y|vIr9kWEp=-f7Nj1_571G7)wW>4-E z)N;TIKUE*3E}ZCM8#i?|(&O_@cA<j8!d`?-?y5;{sJV5EXWj~wSE7Imwcb5;Q`ZTp zxodOYZ);cL9J^l~-T=aIw;Df#hH@6Kk~EBDuZ?<QUg~dXN+yEb%gVD?2Q=>mhH@++ z2dJOnJh3?#C!h-tVk;eNkj`X^CT-t?W+{)&&Fxv+dtKSLco8>sdGAS-->>Fyt`9-$ zj6dl8bL91!(4pHJZg7PnzvozW3``#z=9$`Oym4w6X`OE>s>nGzqw_6?Hm8hguU-Yh z2p5Qd5y-%zzaP+87UJZYG>77fdA#$@NX49n4e%Cw&8T(5WB|o_eWQsq-mt#1Vq9!} zYbRycqBvi`PQr%cM)4)&_m>Y!U~l~(o#=jcigFUZYzL(d3K8=mcQw)Ys0@Le?pn{6 z5VhBH?yg6E_3Oc%mdu!RZr)5qkXo9YfvHCupQb?~jj8z%;Exn#18}QM#WFPwRy9B8 za7xwotbl_Nj5rgFb^Bd>{{)z-B7+1nRh7XK>w)4|ph%T5nfiGd!sy<S&p5X`$~eQL z4`r`5FDwf!3BcsGTTm@rt!{H=-At;}OwNLOsE&AA5u4=g#U1VNs}|oWeLTW(bAl(! zG1z#olaxA&8NBtI;Ea0)$L|_4CxBIeoQFG1NX9+qhxe3o#0d;{-TG;|^>dl>6`Yoz zQJGjfPu>>md&YxPIR65+|4kqZxS<2?68p&I(IiHqP@I|nk?}#Jgqf52sA?{$P|J7o zYco$(sjmboDFt7F4K=X0nRB-nh~EicEs|<CT#h)t)5p|JvN>67%jkH|bXF_HFj;uh zCzcV)wD`*7<BD<b6Hz>C(08m_0%xdxPS|G*y$r&%wNNg{YRbTvQA!3sCzM1A3Jc7! zbazV4#i}l{hJvZ&WuQInEHvnEkww_I4V=jP{69$Z+4`;+9Wxpn>~*@8R(0M|ciEN+ z5xSaHa4oqf>J0WHgB~i`+yut#Hm9j{yt=FP6`G}9I<!@sG&i(dEzde^C>|pfC-ti$ zP%Dn}k~=kDzEVlbAC=T(ssehVBXD<7!|mWcx9+=^<2h+G^G+rJh$|cs_LWUFfYz|l zct@!snU1Z6cyW&`)`{Y|QB5=)IHy*~(MZGsT@pq=itp&Lqk73OS8-q14G81?&q-6X z8Bf<;X(#DtR0QIS-a1rmKaJlZz1;D|zgUv91z8FrfAhIOFKs#@x!g@NU?UNQr_QM7 zB(8=xWPez(muE(=NOt%sD<z>yseTkn(2;DeOCkB@f_aSKhK0*&cXQ?L`{_Gq>hsB2 zJX-fvOXSf`s@|?fuWDj@&eTdmJR_MboD9+FU&WaTTkB|Z=*gd-eoL8nzS}oR=u`F8 zif<lD@}9`<{jBo)J<EIJFT{X&iM5oZ`hr=ZRIYgW{4blL*jGCmk``kEDG-}r8$|q; zhgsYHbT6Df@wx*>AVk)I6J7{4YE9?D(DcK-t!+_)vaJCEBhFqLPHl`j<F1G5>#>tu zVRBFQ5~>3?ZnGI1f6^w%$&y|U5cbn<NH)gMb!ag{WGFu5U{zX<8T&%gP|J!}XNwJQ zho$NYKHLLw+D~N;>)jfnUwPUiJYd+SpP8VTW=g%@eR?*t!^<<(fBZS~RdVfskGzXv z6GEZ|O(C*8gfyk^Oww&N2+ZB4w%4LD&}q})d#RU@Wr2EG_SvC8C<s&Lo?IQoqm4bo zljNMaU?Y*8ZMz^GKb8_B+-}LxI9TzHrBOK8&%%SI5+$NXS{8oOINOJOtTS$%vB2`t zL))}@;MSnSIbuL<!j$GvMCaU{aj!npefz0HjprvjF8047BAZm{%b(Hc+n}j0{h*1( z7@+`g-EI{wv)bmbHYT_<?j>Cu*MIw~?BmJsm^pE!M~@dZO24ud@UayX<Pmrr;&Rii zA$C5E=H@gB>1kUP8b>Y@5Xh^ofYNtedr?=loP#szHQ>_j9rwJ;lO+X*8!DF~mtsBy z>O=wlJwx9xVu)$lat_FC0*+5VJDHmjS^wdJ3LGy`C6GeQxt?DiPxP_R_OQBuQ_`n) zz}HodNXJAgLVL*p$Y7n3<7#wKb@G4?{12M|X!sw1`Ge5bTt4~P6eOv1pGo)lG#<aU zUe^XnBp`nv_We6v1;?j#`TQ*7E6jAwfe`rc{Y8xWNmHKbH$4h0)ylF!!Y?e`eFng4 zYfcxmBEXUR{}^_iYr?rfk;-9wNX}KNrQzd`&c5k&gNs;K>!SFB!s#Dm(u{2Je(f2V zr|wN9K-6oi?f!88ZD*yY*PryK+tab9$FTD&gV*eFT&FM`Al&~$ZvP7u#e0VyFiZY> zOJAP2(YnU6b>Kb-Ysl%neoQp{MjG*dK*C3u`{@bqo+QmFJH2GLGk==6$e!V7h1EC! z`mP75z`u+w<A^0;uipe#AY7l}7mCz>&>ueI5D$&hE1c^8kp071_1=fr<m%z?PT$eh zxHnIK6TF43DZdfDumnK-)ZcyJ&-wc1u5$?+ItVs75n&4fr7#M;VG$WPtK|MS8{PkD zq^(V)aj^=ZV`1H)p!8v{saJDXvT65;{aNLJk-~!2$?HGo-mTF~bpP(T*b7VG35Zv~ zPEYZa9{F>R%iys*0{_|VozV**8~83_1S&jtz?(?e0c|m$g>b#NCNHLD5#emkwBy{- zt7j!#cO`JMO^JQup~0}F`$Ryg;^5jB(u)<4i}jb`p$E5?ENSXSI4#u7@;*5aq;%JI zk@gd@jM@KN+KNi6ldH3^iHeL<;$oIJvORxYR``X4sn(7#MGfWOZL|xo*yo{=@i%9w z@Bys&^Av)Se-0~&gTQ@n_7ye&z<~L36Yn~TEVxBej!neSlj$tGm&B}!59mh?GjME- z^EgZ_9v=Zl-T<1St5LAy1MO=ALEt5l|IiT}4TV1CO+jA`Lh7=E?XHv>ShN!5vH^9O zpz23JIVcoh*4Vuf+e`&8x_>i((FgX6Sh4D!S|?aQgy0xcLWuqPsAdSgc{9;{)dggE zaOtfQ0FPVl0BVf^dO)ACmW8Jzcf~_H0p*7hfhih{^D~FlAbKZM%<&&cu@>ph*4NA4 z<Z178v8vSr`|lDCe3XImPCy?4WZWtWxJ=k4K)5iq`Zp-KmUbnEIdjCbTA26guV)oc zy_N=v?)_iGDkA4k$bs4>;+*`ISFf>yX-Mp=l(ap*R^nN9{=f(8gNC^{&N^-!4t#zl zb}9FQb4dX!I%zFqAHccCTf?d-XSNlIs)$#@Y>C?1hwPW%NXzhRU6>y$I?M^S-vK^5 z<slTUpN3(NW6zs$@I+uW6@lT?MS#5;GUG+1u~6UWl684->3nj7hfp^HFnYeQ+_8VB z>Ohz_@lTgg6gf+%JLa-9TDWK!VJFNWbm{h)zSYGc|H(4Oh5zmR$cPue7RXfSQ~pmw zTaL1VBzn0RB?4z1lZ=0J`%{3su=IBSTuCPCVa?(VH<Mu0hpbcXXDIVI#tN*e6HCMJ z`jPH{j~f?;T9q-3BV1<{D)?!o&584{=A|`+1e@3qn~y!#uc}1nBvi+DZ@Q8<Jbn__ z-50E+({uAN0Yx?nVbF8~-(h(NTsrX<I4Egdg@QGz(6jSxvi|mMtW=!n4mgTIPzYAO z9I|&h*Sr3*%g5g9dX?|JTUwWx*i)WyIC)r=U`1N=r6MDFpO;R=P=R>5Jq!)K8>|cB zo%6bK=(~+nd8&qC!fk$#U?js})g7I-QP*Ep@oF#4C&oq1rvkR6G&FMsq%CF}iH<_C z;`wHNjDzxk=!(AZ(CYf!+_chH=+|ypDehDY|GJ#Yjx6!QGF5R@jkk}j5g#qpYFueH z_z}KiLbw<|U|QV<i<+<cP0%VUJ1eo;_Z__&C7w_{>LNCDq_odYDLn07g`Trep_-gg z_vM_e6BvB+3#+1xT`ux7J<qIUI%i!ZY6k`VCLon(g~pqWdcs++VN>>;O-EXXAnoZ) z_XH2VSgKXMS{G}9Jlj9?kbO=Wdd80@&Ny@T^9HyQxhShn*p%c#Kf(zJv75zaJed&7 zxYU>w=}$D7eX~%q$^2D5P2I1sDX04ArLx^m{o9C<CIPH%NH3OqaxqUY^<A#ChI>l| z_0q}hoGzYjO+HO{&{Rx}w$q#pc0d|gEQfqi&5cpy3t=OPOu%^N7kHs&mU%dPK(F){ ziCZew91}PTmz74Ai-c9stR3J>eved(#K;|q#yqjloV_2$Y%rxZvY1GM*p{6E8^H%d z-JxXNrrcA#bmAlHc(znk#5?`r9oPTb9WNvT&KI}g@JoqLAKZ>npjj*PqdboZxCymh z0EfvLNCxd3WYAezVVydTo-?eDb!4K9?c(}(`hCsb`PloA<4UZl-xsg3kMA;*e}}NZ zv5`kFu&H?g6R%5}g+nAnVKyKF71XqaY@43ad8X@8qn`ewH@)flkee#buCCOAx8ljW zN6c&Y>0uet)uGbC0vz|qsx)(m^}K{RyLk4x+B+tW(@sov>UHvoIEn{QyOj87ImuQ} z5r$5(;gX0}-3<P~j$vqoyO)2$9Y-i{hlj`Vigx^wAEqIPdgCUJ2D^+tZVk8{Gq5Px zx>yW-1tzPCbhdt$*-2&ch{Gr8@sRFaTTxXm+nF*uL;vLvkOl^Hv}YAAFNmJlVnvov z&dyqH3`!nlL{-d->{R-T%JCQ<bY8<l7-?!#77Btc_a)jS+PSfYu1_@<XK@?_D9z?< zXS^2|<ktV5)PJTK=j7m$6|ynzrCP*w*IYq3UX<gl-9vpB>bj$NYm^naqveh956dH7 zzFOsuhVXkG+(2Z(B_0JPo5!<{Z^JvHvPA=>+=V22MQ0xIt`HmKGSi8=CrXweXa*=C z%G-PWhViPZll(rnXbw^`TPk?b6EwEi2E%JqerR}DF5jST!m?D;3qeUk(KJ=H9KQI- zd|OQecCFd_sqGo0;OAIjIlxuex2=gED^diIh6IMNW}S?7p9;)>9vh{z4(B@TX4VHj zpzEXjDX=8cO*_n+>5$~VyJU5vNjP8{FI|rjJlqX!u+O)e>B*Y0!fLhP*)v)h@mbGY zta)Dy&;(Dd{~T6-x!>vJLrn5R$w&6_St*Vw8>fqojatQ|#kNO+C><qs-TaX~1Cg)o zvQWe?yoet`DrQw+WRWhqq>n_qXl5`)pE>;ogv0>-A^_0ZVG$B@jPdOfKnO!_Xw&Tt zJneABS)<X9eWo>+;wh(m&cF`YwdX)8R&|h=M6ukDpLh0&bq~)dG*XfKroW8HoXO0s zC2IK}=E~{jN}R+cIJ(P93foI_@{65R;{gQ;jhqNZhNb{rxZYnWCtzXn+({k8=ayp` zY@+O#$YAuDElXNCo5oUY1OOp!a9uAR6LWm;JS_rp1|nYv$TJ7K6i{#EZfk0!+rr@> zr8qO4(de%3@*MwtX%75A97lw%OX5(9dWQ(@$y}{)R7OQc`v4&}>mk-P+YfBT)Q+?W zFiY*}Q!%#?nwogxz$H;_v?;*iu72Hk#f=&MHF|(pijoiO+MWRlAaBluCL<95Pm>xd zs&%co&@r74=#XT5tIF_3MYEZ?xxr^td^q%&BA4REyO-c{e5k8Y4Q^!ZZ&9vH>ve{~ z0RD*%puv91b(#aZf<aaN#~tKfEzfgM-$xIb=!G5`>V6WkA*Qb^kKvi<GjN`!3GF#G zBn>V9JPtN!MOiaCYDY;w>rW^?t&7*uo19M3O5wHC8CfVbc46pzx*V3IVRW}uQ?ykF zX7YLQ)}v+9DlU%_1=A=u5hFOOt5FKH?rt#SNUIuk#lbua8}zaj3w9qRlv)gZXEJuP zRdGb@C(E>YMMEtqzuB~!f#vq{`^L8Cc91K&d~Dw=(pNGutjN2=u72uYaVmg7t?|B2 z$u1!!^VixtWF^rN6nBZ)xxW<aEn02WqQFt^*z%4f^rZP*tCzbR>({kYo&8;on;8;L z$uV^48{6Lpn;D-O(9jhQTRXMxJAxVIg_^%gh6q*+5aWazoHVo^C(YgMLVcv`k$B5M z@vK~xnBuGOyw8*1F^c)5jF1`Gwn<IaP4WDKxeh89%H@<G>#HS=uj7srC3%%P)4nbH z+(XaP)Oi2Ev;VOBY^Dba%UiQ{<EN3KFT76zg}sVeL*A0l<kl^ERWO{%qmz3Th(aB2 zd+yBVS<ODSwXBqMN0y(!AZh&J^+Q%cj_PqEkn>TVkZsKPwvctTuTR6bL}_K44pvAj z`HyW|LwXzCyTW)0KbeuJdD13UCq}?`g&eG(KA=0y=^NaD-U2&uY|!ca{NBzP^{NZH z0^Lcqf!i`=#%(>SuWGuB^)ALX&HuoYV^-4O8{SFr7G|c9eV@q)o^MGHZ5}+=E&Z`& z@KO5YW$w#?C5DV(oJY%^Pm=DcuGr4WI<N9eRUk)mB542>nP9516`;~4PxO3G;01ii zN9bA9*F`HzO=G`Dj`}gz7>7HI^k3eKVM$_(U(FrR`_!&l@fFE?V&4%<><7cRwl<m} zS3_{lIgYf|N7egZ#^jh>$j7q;_AL2lL&CSm!FQc?Twi>Qd(_hQt~WAyLY^4sinTzy zuP)5D2#2SbVqdI-oPB-ZCig2(swne6p=>L8k3zyZv_wrL*lcjw{7MJ+4Mr<8SWT28 zjYh0%RH{>ETjR3Z`KUig@{$qqHa8Px(%+^$kdt0qrCKPZc3A1A$|1JY&^7NnPGFaD zi?@)ct#8yj#Okfzi$mVyyU{P&DJR=@?pT>bTyS`v?a22l!mVe$qi`LM(fiEIS9(;| zsM;cu?RS``@$6c4u^%7iIO5QicH?zlierEj%N>kR+Ih+yAHiZ<r)YVk{Rh%V_M=U| z?(7d`s_YjB3<=Fg!xp|<-DuFjG#3S2@ngYQ1q+Bt9Zp9BbsC{cjLL)ZGtNa-wiY(C zXjQvjG`)*U+#|jT+i%K(98tdsv;(FQq?JHG_z!vTd9FMQ)UxBWQ)^^(biM_>E-5+G z<8^<=Rj{?g9^`!Mihtn%>6^EldN(`z$FSuX6)Vhf2O>QE4z_cVY0b4Vmewixbw|<b z_lhn;LdABFocBsMv)!(FTbI%pcm!(`&>VcW>a?2nF{dS@AxR(JaDJ#Ar>dfIRWC`h z-aOxrZx*x*13^cEYEnb<7x&C<pJ?zZwPblAUKez0<|yfsMDglH0#7W;Aoc-<Tq!+I zBu)8m0<tWOB0eM|1cCLz0Vn((MldoVfCn}>f(8!nAaDry#M)ft-*Nl`5Hni7Rg<w| zg#|b<OR>dAwUW4#e1IFn{+pmX_9=Q`3xVNdX5^V~o2TfyTB{X_XL>ezOos)S2k71m zN`M7#g9Z9Np&qRnxC~3xT*p@dtmPKMy6+3S;<^hSFD<#>kNyLx|DEgqjrMM8X?}kt z7f%)ogp}Mj!ZXC9z~^KcAQ*ZF>hYT(elr1^btdkoGkCzP*eMJS7Ops_XpxOJUW486 zbXN9-TCT`?y>E8%=E#v-M?P%6eoY~c{}0Uh2O8@$f=a8y@VES))efV92N22dxIpRj zK8VU8dVcDgE2Re4QnkAMSPrgJnK4}_@^gMi+M^S0j`M8G(xB|(#yBAC$skuB+D8Lm z(d!{V4_wX~0B~Ppv5&+NCyT7-=QP96;DP^^dz><cZ(z-O{htO=EvS^Q^xsR*&@qA` z1&6?^z{6yB@(a047bXMuw)5QEY6$`?;9pcX=5Kg3-&Tc~JXPOKkaDMYre|Q*8r3Ee z|GxmG3NrSDV)`7wbPD3XChp~~0o*H;V@e=jD}{Pl4TsIsm-l}bfiK`V%`c;fB_=n3 z39<{2Wm14SUDy^080EUr;QhpgUYk#3Zh=9zVL#3_2;39?SNLxGpVCh)_}^Mo0F1u8 zDf<^O;4z>~@W&+L@6@v{6cAPpFL-vqpYONUrRR8YWjZm^=X!A1)LhA5a?^ob0PjF# z&6XUXJGe~`Ua&f)EEN7X;(xr*$x|Sv3Bh)evSa!mx;WhLhkYSW;lKB9zzdi0g$%(2 z)Lb-$PmftosSL$k9gjSq>0V941kfS5Dxp`nAMx|QB7ocf!e+m@$N$f-1E`l>c&o%= z6L_8Xe)9@<My#-XUs~;eR^A^C$^SC?b(|A04FF!11Ox0P(^|)MakCmZ4M(wa&g1T4 zjyoMg6_;f)-1%iMz<B~Y!wWSZV9zeBO#Z<v%dtX(hMA6%@pB?y{y=2~ogc?+Z)6<* zw<{ohU4jeTL2OO|?5YWng+*srMdQOcbyCR3E;;90Pcs?p=vng%VSiVc`qIN)y!<jC zz=+0e$i!XvnSj4y5WGb043uMn-Mpq8Sof|0xU=}-8=*h6r!MSYt;nWcJHQ@da6MhA zOnz|HGo1)vl1Kv#tUSCy--PM{47;C!uZvxNz?7h)MDPs2{P%&q-pqpCF`xBJ2h>Ti z>af$b`JYCT53V|5W$}uvM_q^<Tf>rfh$Y~Q?nNpPv}FY7G_Hbgz<$!M;sIWmj=9CF z^xFWFOK{-a1OK(Aj)2dM6?+~EIM(jx75x423&jq=`MO-gAB)AtpYP)~8;eQ)e@j@B zp96A~RB^Y*D*7bb!Il1L!O?SB$Y@EuQgm>7kwe^MQ?6TX<5vwn4JWyKVuHTRz1nxr zcYm!eQi`y=LupODI|@bTtmH1h$Z!T2c{nmn#dy?nU2wR2kH_rsXE|@Z8MB7?yA8EI zIY}COs%}@%KOaTe3HW*AiHiW~H5<l$>zR{(<{VA}eH`u?8TpnodJG>95z6{H5Hfwg zqWls5Ib1saXFP9%E#u9-d*_HVMw|-(ZMku5qd4B&&461Yeo8sw?eoE0Fwj(M$vUGB z@BO)Cd$B5`ON?glPh&Pc0@k`|i<boY!Bse-MfvMpShocp9fML(Vx5PMUc!v&=d7Ks zN@6DluH~&|PL5iA)+L-rioNueB*}X{&!T_$nrfVJ`{)Jn3H#Cz>!cxx2hv9yCr7F) z@|M-a29kiXaA-O`MkpV>dZaoir<k=qcNb%mJdaKR2=a}PFTUH#D8g^XVpU0ceamc< z##(PzM0@fEm{Q%jh@DzlD?_){&ls@vTNAr^4gq&RPMJc1nAz2kq^|yWSC{W9xmwik zJJydr?sGO1RIG08mw$S9KOj0_l=WH@p(zkCdS6cV>=Bd>wb~}-r)r%$y{`3)JL;PZ zMS0Qv6v3ss#GJ#%v22M_<?7*{TRLWn?%y2T=lsM^(m>5M2#3x4M3#W7?zudEQ*#tt z=I5G+ZQ?4cuZZwhd%Shnr`TItXIOq$3*yT0J*{f^VX2&NP9SRk)G1Udo@cRF+;y8w z#`v{f0$)d=55kvQ*WG+aepy;oFG{Z-q8sSf)rMT~>rZkfZm8|&D>994?&{a`;`7j5 z398jcLiBaCK1t+{Xyl#Et8b)}jN<7wU@S0*ps(3?Oia;2EGyQ17by{6Jj0crwP}=+ zcD_Vc#{}8Gmopmv!etTqmDGdKgn=FUQuU1KNDsR$xwQ_^4(N~rovhQ>Hh%znKolDC z0eFyhwk|lOBnQgfa}%hZ5(*cbJ&bSLeKEmgbF;8or?b49)%L>^c_tKS>TJPkYa3&& zfn{INx&>=7`i6*kp3zbFs=Cl*O~Uk5Zb2p57b-r@B;xjTe1BGaX(G;N#4K9ox~{{| z6p=l_&KQ7%>vU8&CTE2bp6qNvP{=()ADNwdqbR;i9ft|okKR;P`s5OgFL~*jv|UU~ zP+Fs&GfHvnkS!{_eBup4VS9q~J=8SC#u=%;4d?cWAHMcPvf7)pcaS(uRg&CWfrrI% z9DcSP3hi*aM%5<ZOs7kkW!d=pBUE)N%`QjazO;-uq>rbgu7S0@FwJD7AeX*|^$Qqn z1Q?HzE@-t11I`vLuu0$6d1^lk|2(Xoma}XdUTzeB*HLtCosMp0GF>&eIc|__+NA$z ziPXo0nY)rtaMFLV-IDM8V+{NoRQAXYyIbO?RU7*x#@XIG*hPLU_eav^ip87;O`$}K zg5=J(>S*?qImjc|%P$hzF}XjS5J0Jt2JGxB?ToOoqMh5IO)+}c@GJ`&uiUUNh!gSh zN3MzcS<JU3?LV$xtO%hmu}znNesc)AG(~$(juplXEOf@oUscV+-5zOT+rSH<LrTtr zIp#rr_au+JdL7HU&aj8!U%ody-l1+4sj8vF6etp>i1!#R$a6!Vwd^<BVqX~EgttEo zx}W1ERSYpa&eY9P%gJKe<C&8v8&;dZ$^+lNVIDw5f*xk;w#--q(Qi>MbQ`l*OU;y4 zm8w+}Eyz(x&oKozety33P;AZDVQ^%i<X~G-t%f!wCun^5V^)Ha8>KSO8Z*-sd$OoP z&_jC4=7OqYZ#PF#1)3Q+qsB9zWq}}eE$5f^Zzo^Ncj*{kyJF+HX+oEA>o<WT0&uoO z1T|gqd)_$IAozzO;jP20cP5GFZgE(ujd3yqmCwNJHOL!olHTReP=yV$*QLoFMK#Bx z_d8?`M+r5t@hln6C9N`$iOp|aAGvBx)RZyBs}4aM7`6B1_rCV#_4bOwlBFVB((fXl zm^(dVt*prDURSN1;;rP#u^avR`76@fW?E+$D7V`q9%)hIz+E0Jw~@R(BF$s1yo2x% z#5j9bR7*d;AC%TD5|km%U)d$GNMRTgi8?=SV-2rEgv+yGL)(gAKDpR?+T~a;q^ztK zTgQNQdcQ+<O<Icc$bir;r+FENn>yR#s(p$4NB{%Sr>vZa@PyGfqlI;_&bez-7N3(} zj|QR!v@MJa`k#&zrRmbp?n!ixa=xj^dE&-H!l|V^c-TkP&d8Y&?k8Sox*_9|<;2{d zk!L(3FlgS)78+x`^w3}^A%u(=$g*oLVzRKd7-4hEbkhCRtAC=GeWPy~47uWw)wXnl zf|)_{ZugJ({s9!2NTvi2?Y?K*RIzONtgl{bsdzE*uIC&Zx%&;5TLq%&Vj2{hYmZ2o zEu%QC$fY{O%}tlSY?CSRYR3vP7UYO?a_fH1UY3bZO;hDn>GJbO10M%gmhFnOFh2tn z=$4<E+2QE!0!9XMbjlU#EIe6B+EH2l?uE!)8)rFz;w{lG4h+Zl;5dm^tTnm>S(Sy} zZ-Wua38PgWjN&Yi+pY$K$P6nJWRmRT*`~gHM?DT6v=~Oty+g2kmB=Wl4G6|MYPy7_ zBm+`+jKU5PQI@ygK+6rvYe#<*lzplCUR&?0AH!U3*~~aliYuDF<3J-f8MyG+=^fg? zICa7G61El9*)k9wz+H}cX*TQKK|2*)IMp}9=tF+RFurmN(_vrn_|bcx;<B)(PoF2q z^5f5%4FINO3zFY<Bh3+=t4X0M&QopQBZYW<SGU57Pfa(<7Uq*NX|9M;p~bM!$^4Xp zf!mBisAxi7<`bhFhO;6vs$;phw2x?bpE2sTbf+=uwJPV3iL0Xgzp)>uSdqwsuplI? z-Ga1TIA=Y@K6GXDFoW0xGS$mZc5{x>hS5yB1Esrfv7Y=~tTy?h`6a%x)+@gW6#brK zl7sO#Hs@H;%ZFRzhBEithUP6Nfd`0gjO=8gO`wAzvs|egdBXt7Ju)S+{<a&<p#CN) ztS=@OY1B$DPlgl6kZ+hklB;qbBEHvFjtW&wZoBB|guu$xt#1xUo=U&}Vf$3k885Z} zHoFHMxN<asDsTc7w0QBGS-{#($8$XjHmi@<N?SRSZx)~BXT^Appp0oA*`_V+k)-+% z{aO?av-V)nG%))%vJ}Nu`z<}(@>ET=x_fjwKCy(!{j@=+<;34_R~R+3C=E~LOU_k; zGFIAcE+F~RTQ@}kl~<m1IUlShk<U?`QXOQf?^vUsFLgY34|~G>4$vpIb~aICUGpq9 z>t;JXre8+qMjVbyR_&Wlib2!I=fJ|6)zO}3)5j1Y5~+|ypK5Pcp@|T@c)PP#F4hTk zE5&%!<>17{OdGvCJ^RZ!gvZi^If8#Wf1krkfKlYuO_5|Cq+5Up5QqyL6#cmBq7dW< z3@+jphSRO5Hu9ixSC?Jg`wv^U1(#>cA(-n)THiB`2}3^&?p%399^eOSw){=t3I<_; z=)faG>}?kTKZE>9MO%z)+iTmRxr9ed7OAR~y>PMjA9F&uX0)YL8?dWB21s0d+pXkx zm`U~a=jhU46N?VF#BW;(>@>Ubwx07%*$44MrgPUI3%gg`GRTL!`IbF-t=TQh@}pZP za&>ARdgOqtuNx+;Y9)#2C2{T0Jk$N`a(;qO#ZD}`wtz!3h=l^=08eF>M5l#m3tn+< z%*|P1=j^JN-+0*^j(z6r4k!zKQ<OdR$xIaR(8F`HR+%FNtQgAQV)ctreEVQzU50LY zZu3lLa>*`Yy8k^<YR|*`mAhoq?mprxiPH{<z3YD<1}P4HaxB=rnCu}gWG|dF4{kek zz1Be0j8#0GY-JL7f)Qfsoa_(@mE>F2OGzl<_NlJ=pwm!Wq@zT$!CLb<HWIcZ&3zXB zM=#P>Buoq7L3gcVDgZ^(q&~RntF;9*vpJF%iO$24eiNL&UrR)dZG+1}xHzjQ)+06m zZEq-kHKdP4mKgsgSbu!5mvNjAo2WyaI@${=Q5&v)e2U#XH>f@vIOk6*j{K)YA)qN) zK%9_*&tHOj4V9d*!uW>+0CocH1EDN{cI1*`+x*_;n%@Lou!B41Ua#c;hY}@^ApfA` zgv1Q+9e}Mp{BrTd8`%^<vO%)Ix|>ntefR@B4>l!G1AZgxe?e<flnwjIHH~i^IUy;3 zaP@!W!gwA2gqGkHNBsY+0QIG`KazJHKrwPv72sn4SWUt7S0N1eI`}6=A)tA?SW@eB z2s=-z-X!d_a-RSwt!IJ+9-{z&djaLfKP-by{E_D*)kQ4-k?Y(s0dE3|{xx+AB?6iZ zRO|`C%%9N|O$RS3Q3i=v|G>CtR{X<p#Nl4X>5XDkjsL}0Z=@y<G)ztAj1NvsOu7t7 zN2#9Re~cs6m?Y0J7SXx5*Gj;GPMqi`Txy3sb+S4jPsL-4W7S7r2zX*&><TT$7!MLf zPhZu_EV|%2`G8sLXay)hDbT}q>%i4wfU6>K1NcwS0CU+qGBPdx>MHh&5gI|j5oKfJ zRRI3QIB`yB2V`>aXI|8tpb+21OHQx#0RkYyfsk1-Gat4wW3%!ap0dw3MaHZ7FK`#W zkY{Z7vEl>o0*!c2m<#aOKA;T6pB3`~%p#mxPmu!kYjx6)=q@)psVj!yqidCbC*~w# zH)8k#Z{fi$qknHSBF|*gxV6tLa|sn_TO@zp74<dJG6?|w|M$GW=LLT5aCzW=o1@oM zah5eKSHs@cGp>j28M|_qb;>IE?_Bg6WG{+Mq)N8Po$znVVe>Sc#gTADk6XjP)Cyuq zMJx%3ie8B`&*NUJ1ACBq0@z`md8hy%u>|n(Ecd^`QF&h|CjP&7qJVeY_tsuF#8rgn zsu_HI|L~AT?Jr*;k1+c0-m3hY>NX%T*_PBD*($tKQQr_FZ5_p*B|(y*sCQu<jer27 z_hSR+uf%oV$XfkfYOmmuNsEoTcuPptw%C(`D<7f)AFPya7NL`IZ-HW`KO&951Mzov zdH#-W0YtZiBC9nR#~*tc(eCWI7$huwh^d4-p`1whKkmM$%n5NYm(y*R7*{5`^Y&IC zNV<>}@V+=;J?uP9X)B1zA?8(@Ec!SCnPs)ci2`5t$(zZvudUvIAx=&pMy!_B@U%un zWztM5XMvXZ``Vhs!kmh_roPHz`F>&NBuJ2Z4?ES})M<Gp{AfBaX18UYX(NE46f2$$ zm29mFU>Fz62%e)F5-h5ir<#GBwn?Dd;pK$>d1faPr_pUmbvg5C-046b)`K{3Z}+-9 zlcQ-2VAbxOGvDXT`=-OTIw9+YmyOp?=~i~p4}&4M(N4#%AV25;R;f_PUe)?;!(g(& z!RK4H4AOc@Gs8M+x}R+&lIx`;rcVlHm|LYnX}0|18q7Qstg}srlsfdshL_#7^{QK? z>cvkr&g}g-&QtxYxUv?l-k8o7=X#--pUgocOyuuEUo%OGv%ASp8b8i^s7jYU^dQRY zW^&xaA^L%efS=&9<JN&Gx>iQIAFfmHP%f#+BHjJgDd+z3EMqfM$JenD2Tqb7Dv(#E zYzMu}obQV!3%hdZz8ny2gWRIcNJCtfm&e^7mcIk3vSO8EbpyZMT?v-+vPV9ik}cAu z-;JI-44P3QQ9XA45%vRqUH0M6zB^}~N3SsREug7sJc;6;7#`4zN_e9YiZgn-ckVW( zkWr|bCM}Z5tX@N+<wvL26>r0FooSPb@}8I7-?YaE)d*rw)kABJiQ4^cm(8*E`Qte0 zjM8(61vJ2RU$gr9!hjwWpJ3N;)Tj^7-juVuAB=Gk507cL-sdw;fxdR4vOwvtjlK-3 z^jxF~&O;LUfbDAS&L=xuTpCRSme203NwAh`1$oJWA~T4$#X!NYEJX%!?kVymB?a?E zQ^qaIX;()yTwOWGzLi*Km!>0;)wL=agaV}*p99FDC5tM-atav4(TDRiy!aGOGSw_@ z-mI=1y&8L<UT?;$+-S?$K<7}_2sit<Tpw+lm<h2@lJ!__7XMLO3RIJn0p`(<-QXsE z^l@kt0W?(|<N8KSkX>cW%U`s!U3b&e&l~QQ-`JlfHZ=1X&GAh`+OI^!-5!!f@QL07 ze8Z0jgrnMTX1xJ+7Ucg?$JHdqi<y6{6)d9_S;G3buF6SjmkT&ud;ZjIU-l8)IXEkY zfD-TC?&G`uJe|QGtM*N=RVw{XZ>eWSb(GDboLns@qh9t5C&|Zr#VIXSefO2559*(? zQ-0dEN>MQQBykg37PB+RfhEUtRYxoM9!5)bDH*0S<~VdD@IBPn*Z;gq5+Sy(3D&>? zPq@I3SU`4S$%!_Kk*C3lxzcUkNZqA@Fz&W9lPZ;s_$g9Twfi`E=gLj!HVaR^a3*sj z=B5(IB>BR*RoMV;ks=Zhw2|<hNv^Rn%2^e!dtg^vX}upo=7{zyEx0zeEBSK`?wP2& zk^E$fA=2GK+CEo^f;;2=8|+cDuATV1V-4OYh+u~9_#yA^AyN7Fka5~{2%{>A!etKa zZ!1zU;`%yo3J3^%wcZBsL3@yhtsEpXxHWlAKzu&TlBaU~;AC-@W{Vht%ztDPC1;Z` zWfLB!C8TOiL2G1)7tBIcSqpRr@wKEeIwC5fjdee7i~tR4X=?5;{bdSOQ=Ma5uEY%! z6MQ*xfC4=cs>KwBgpM_j!h3YH3;_Orazze<hh7oDPO@ixW!cr@!Y9AK909frAjBft z_HgnOp0U^0r<4Z58f5(il1#_LQE+<a9ZxeKv3g_t(ADgFoTHJhPscm{A8lVA2<6xI zKN3oztXVRNA`*pU9i?ogp|WpDvP^bDWJJi8C@Ex=WZ(C7vXeA+W#6T-%vc9A)9?7c zPmJe%p7+1sU*?{1-{(HpIp^B1&xNR0?>uC{f4x*7&Uq8*kF;5&wLLmC;H^>C=`G^v z;5dG41}~NTO;3vx`ZemJD&xU0J~xkckpkhu^lA$qAMzJ7oR-*ACQvPcE<n!nO+*~^ z(16krLbX7!N3TJBswyzrDpmB;x`^b<daLm2A=~9EwP*IleT-6jE>EaV1IrxZ&529# zmqhLdy@OEoW`_vtb&3}|Klou9$lL{fUhl7L*2$D#5NT!otiB-dD2gsT{&~;3RK6OJ zU=#8%++sr*NxOC&^kh%Dn68~9>ylqtH6>G8JjS|VY!v$X1E=~qi`H=%mCp;sbN7VI z3&LpmnG&Ww(!1754GWw?DpN#y-g9bcxSG$Ox_QTQ7Sn%yXeL_yiCD_-i?jA$nqZq7 zaQ1xO{PS~#BdpvG>>eU|IQAqL<nh3w<UxHC&x@EU{@9D*A?#P!awq-$B*OeVtIfM% zHYB<)raU;S8nGZBxuVW${%|?f0(6hJQlB(0S7FJPd?xKjwAkzV!JxJZ)$?s}ZD;(X zpFcT2+IGEB56QR!WhdUjHADouDL4x_%-!!Xb+KQf^%xbE6qkwns%0Xdmsgj1j>8Li z$x4ySBYdpxL;To;l!p4v_qOhuO<tuV??lfn#ET+|-x2x8oBRwGX`Or!^#tz-P9p~8 z<If#)4&UU}TXP!-N8ZbgHcS?L5a$whF6owrrl4v)?|J;AxQPR2S71Q}w*4lJ{*UZ) z79EJCBU+y3&{^$5f#{_>8xCA*7Yr}F{Fnhdj(;^aXb64bEtpE!(s|zW`FpVz;n8>_ z!pmdTZ~X$v@0+Q{r{OQ_mksKjL<(}3m|`3ptFw$9UXW?LVfcj#5a@c5lswnR*O`*n zwJLW0hhb*=XnDO+>&TlHM{04c<Pb}ERh^IIw9oK+`C)B8?bjyyx9xA0Kh_kE)Ht{H zDup|_kXvmAw>~Ra^OHu{;1U0s1m4)BThFjp3We`v(D&$Q<YoUh|D42C94;I!)ajCP zMVQs*Vv++bDG784Y*W@Pj~Uksljj?=+t*sx`?xY;KW;uHe5J-#Od!-%8-8jf@AB!b z41h6U!9LD&LYq~qj$<;X5d)A%kxdaHn~M!2oVIAj&MjlK4Y`S_F^kdqAxL{?ca-YQ zI9oe>K=;x~y~v*@L!<^DO;^W*?OyNAO~B%s8XnWk1ZPHJYxMTr>5|HlF}`9?Y*8yI z-A{aVAn5If0@OvM=v$FYB&!ZSi1`mB^HQlQ%`GMdO({nGHdWop{@d}N-VdQ9<Lu|F z;EReZ<LCB|$G>@D7iC^1-gWEF#LWW7X9}ODT918aiI#TXYIgbBr3;T%IS<@kfieW3 z3STx0LK8gXr9eEI{#PNWPp@mz)fMkIA+(O=UuQMHuR>@Tt4yN?{$xJ-acpoOY*NAv zfP@Wf^fft;Bi|uM#r{B|6yx@UiR;Lm*hb`v91%RVu3-#Kh9~{6Z*pipzA%O_ixFu+ z<mvLfv%|*n?LQD&ppQoLR%QFNpxC9JTw5$0@){d#&rdaAnV<{IbreTV^W6an_%D1U zknMV7i)3CV2INw08JZs1%qX@V2a4yVl2y+MZp4uHfz0(2dm`oGVgw6R*vJaoKf!SS zIx}K!_RQE!or2LQvSu-OiKv1{`rUnER;%0l*z$86o<*hG-u?l3u=7FxOGA@ZzIw+S zlk;DW#z&gk7-PagB%Ys%<Om2Be&%+T+!=Ml*||-*b*bd=R`G>f$tvF8FN9R76_$OR z@DjFNt6EnX+10T3m@uxqG94aqWI^rPa`mmtVR<jFeIK0QB!=JLv5&GSiWNe3bY4T= z<3*(%i?P@{!HHq@cjS{G@h@P?CZhKV7_!m?xguvtlFDIMjfW1z!btngfl-7F0muby z56GBXU8nMM%hVsdWQa_<AAbb-GTUowJF=4aaAdtfoicLWPRB-inuTn?=&&`OoY%2> z9r457{_K6ViD-kNm;lJ+E0ciBX~^b_6XYt;l=?CNbNnxpg*-y<zQ-FoI)k%nU6xo< ze~QWGlbV%8MzP%&fbQt|B1Ip4CFZ0wWjh<WjpBZEs*USJa^~K7+AJluJIo|y#5$F_ zh&<Q<%vrER>-w?_D6h2NQKqwN7|C-S_anpn10dv&`67EN6l8YHCe|IoXZMCc8gP>x z*1e*3>CK{(HrItU95qG{lR=AF<SuE=2_xhyPRKss8EB8q+cUO-&uKa%eONxSQ~u+y zRrEhA8!=_P>dFhYeM}C4j@+ii2|O$RvRC(7G;JQv{ZDu|7K+rujuu{1{wjXxK95h( zQdZ8cy##Lr4i|twVMe0Kc(ccB)9KC0Tva${bX;-j^t-jWaBhLIr?5n+uauGM!~?q) zvG&daSAc^3mt8C2H+#v4GU7OyFHHl+<)O2m89ru0VJ7-yfH-+Y&gR-Hu;Nm6?R1_t z0ADZ?2~hcTPAMZKPxgviYF)M9cQ1lr{K;N|q!l5m)dqq;Sy>vo+F1crWZIZRt+!_@ zn*>_*EF3@ifcEAAV}B)9>l9ML1la>dTC(0!Xd>c}TOe!y_834M%mGM+GltPIW4ijT zZt8E(3=f{K!5S)hLzjQT7C$I4QGiC2?>rvaXxlYd+n(mgFC+3@Ch@Q^Ft@G1N+mD> zH$bc+#t9^hK*<}DR7D`nO#nYQA>U=cC>x>4xGX<?SBv$SSfgha0G#-rw@sv@tTpIZ z9t96-0fs4k8{Xn<zl_@3^UHbxG77(_Uw=fcc|~l1-`87`=GLLhH6Xj>l@j|NTfKCC zAE!m{3D1+3TEsWUsQpdcQFO#L_|`8i>fbxfA0(^)HNhL@u`CE7=CsqNzYNV;QwRL# z5e{dsjgS>4{y-d&!ec&vrzbUN)OO%0RkY72S<DvlCdBGr18L8I_fmL8-ejd}!~#bA zufC=_L(ZJ{dlq;vy?g!D@yaAu#?D+4nKVhj6Z4?TYb}j1mf|hh#T1j$5W2{05?UBA zU)cRd>fOZItn%B_!YAlQ<kIdQkrTtN*DU&u(2=P;JO~zJbiNN=uY<^(Y42~0LgVp4 z&jK|=gW`8k`!%}{xuwV0HfH}o_M74b9!t-k$tFA?&%jGejA~i9&D|UhlqQUeJU@2r zaCWuBW`RVZb}`S@<2{wp_enB|Os7amNDHVRy6{n)r&~7RF@tn{)R)?>1}<+od;S<( z8XLc84vqcRaravemh!9I9NVy*$T?tZ##CvSNjPMXaL_?gQ+EPh5!LhVqo;Xv(!BuR zQ|h<<lrGK5>dh<oX!s03nZ3{8Ro6b@gTgBLQUx|$OFE2<27@i`qvqD|Mun-(-?F$R zZ!~{d3QGwag?PYsn^ow}g!QCU27I_Rdd*KSVLGq+@2W^bz7FH0HwRGbdYiq1KNny# z{=naKx<sD+^FjN=bq{o$&|#~IjDeZ@w&kB+cUH%w85?nqSwFbAe1Vhy($|Yj!j2c1 zcy!?Z+MG%MI%gt=Y}he`N*3p(ud<)xG-0QUlyAK@=~8?_O85h@^8z`(h&8U95b`-} zENyE4ca&QiA?FUdv@*0gH?OKV@KWV--UUvdCJ7t-=~=!3*XtW1JkHmU<U^N%ohg9V zn=imCs}js<gFf0M@Zi|;ine$o(|;gdUQa*Ux6i9W!StA}de-Og@p~b)7n%?1E_DR8 zkVP%y)P5eKQ?!jg)3RvXv@=z-`Z$cev>?>^(x`+U{j2b(tkzb&s9x8}@$UPv+ImjY z8t3GD<2Ne3RW3)3OUTLu<%S_{g@(KqqY>D!|9wUD%BQMkujSD9vvtGkT3=U#k(0eX zyg(-3z&nuRDiut1b~bK~4#8?XCxG_^!RC{<2q7ceBj&O!UGS=c8N6E(%6K^~Yi1xT z)7&H3AV<_YLTpQcQ=iitqww_T#@&_;9YhMJE8Mh-iv&+^jkly<v45SiKe}Jzx8s}n zPlcgF*#m`Pk4FG_l%4yRl5@SGYZZD$m0>pP(lO`1<YN%0(EX5-Hy4-rndyw9!nAd- zMP0z7FO&SYP9r<)2~UA4_Pq{>gFDE(<QCM5QS}MrSV8U|$W+f`PE)V9_uu}qxUgAt zM(0Imko^5>n}?fOu^qo|EO~2cI6q6i*{O@HPELQKD6t6psa$WC$5cNOzC`3EB`Hc7 z5XCyqxk3-y%JNhT$7}SlW5$L=!_&I2Y7H2v<$kHjK7Ev5?kcn3um$`h`4kaBaLVv@ z>+v~(*}AF<`jl=Cf5^mgo%)`%HY8ZP`D87FApvzh!Jy|h)02BKP7RW|pFV3vI2?xP zO<2t{OhnKT)*JJG57U-c$J{8!HAW^IYNq$AIyg!HD9k{dj{Nw-Ku5araLv_l-@15! zY!Ny!(*XB-vpF0$icJ;hBB~~3zss_D{NB%aU~nL7kRvZmkJF??x46su6Rr3&M|?r! zA4s_)JghT5ZH!R#-L)$I%$crmDWS%%%+vlMGgXRdX@Uo4#XMoJ$8SVPrqxH|WzJdY z9l8l;<2cZA=Oej<L#61ZMqUQ=@#{|;HmQP&>MB|qwkh-Lb?A^`x$Z?pKB7879dDsa zc>3w5aZz8;S+nbiw?(TVUmMk<h6MsSv)(p22w&B<2xj<J!fZ6yvQ+Y93_8Fv_N<z( zy_%DFuRQ1ruXNwp`Pi;H#gkQP<Q|t(Rj*p?>?G`%n_rooDh=*EGwJb3gt4ZSXtyPR ztT94cnNZ&Zo$bXym+eOKX~J8)tr(tbtC8!OZdQ8Rsqn9Wdh%%7Z&w!V6o04%$}n>u z75w?k)KznXw1p&hpjco);`YC40Pum+MaKul5q*y~uYE?j+qqa-J&by-HX7T*Eb{5V z^N+t6y3+Xz&dcObHw+&heZ2Abdw$SCmBI}W8~Rul3r8hHX+L&OlkpP1K$_%9;<aQW z&Ni4r9L;zhFsB5z4%0Z_*3L}tnz<Q$?3R;<t*cPi)cZ7DXX8%iG#w4s`_XKhhX7}2 zC#Cw(dsK`S2W?&QkZyd`j|m3m1P23LKUCwLV9<^09`^I5hl1I1V`vT3mOL$wo_Bl~ zft+?zWo>`{nlol0Vx0A_q%#Y>oBOiHyho@4RY<V=a*2t-<K`RHXBooj=We+~zk2;? zVdzb;tHwf$?LY<8_$G*B@Wth9E{uGyfc@1fV1_`e$Tm57@9?+FhiazFF_mYu;eYjs zjvcO$$e2@$TA~gmO#|I6+(y?Skkh>5p1Qt>Wqzik4?csut6W%t{kH^y0Hw&e#`2wU z+<|&AQV-M%z8YbP!FJkHtbZUNaRCFOGS!;UT}1;jh!Yzr+Z0^Q4lG-wp{6$8n0Ro- z0?COr8r~U#64$(tNPx}cBS)^}6HQw$MlrK9dQV-t{i?m4PV^dVN1ssLVWht2JS@n{ zAoQjSCZhRBs@cQ-j74vvC%>hZ(WyYlhNfG>&N!)3VjHvo%?sGvzfOPJ)nP)l-<<AR zV6(h+gAu~eHzi3`*YTf7Myuz8a(p7<|CgG5uCM9}eKsB=J+!EQefGp5G55jb19<<A z$72ejBYa*tn*`*vZIN*=-@8?#7`3<la!0P<Jkv)gXk___7lis=9){w?NC)~(?W|IE zLEX(r>zAq`0p=CLO>~P~kdBY<b~Klr5g{%<(%|-Zv(*LI%IQqoetcBnW|$^@%s$9L z?F4tJ`%nHVmQ>O09voy-^eA*o%KY!Q2=^MLnl+UC!|&f5CSZ?!W$DlSrJ3qqy^Pk3 zvXh&MYS@7|jXTeR6d%Wn2_CbZrj+cv4cvOJ?<|-e@jPoJ!m;J-!*uGYw|ALdx6_$i zllZG2?=A%-R0qt&q>tpK4(zemF>FcqRPf5cYjxIF_M?!;??0EKcXk;>bcFb%^&jBw zZnsmrp8;+*B9Vm@ZigY}vo+}1BqE!+2FPXfkg`|5ty@+lwUu~Kpl()jWVH=(u1Fq4 zWcWZdH5*|7ZoEF~d@Y^;Tk1v%PiK4rK`l=V7(jI?k>MNawhBBAfPmNGTTXY52$Bt@ zm)Jm(C}`8R0+O#m4r+jlD+Hu|miBr8<yey>B3$Hs96UQ>>;6cmuWaSt`%}jE-3)aB z#>3e^kW>I_4yViwg|LZ65Pg79G|}7W*4h2sPUrsj<!Rw*l)0db2tS~_M+Af5>UUqx z?FgyehbT#}htQ3CBArMp^v{Cvn0bluvPx0haP5&|N6+#X8L4XceuFf+yOBNm3(m<p zItDL}P1wqb#r^`FA;D3~K8e;qkG@vq!o7I6C2isndbN9gQA*)<y#!FBUU!Av`dO(F z%9f#4xBi>|q?_=goc^CaIB#F*0odqU#r*`$^jRONF0!=8cP3UF=gLSd7f*3-<m4NZ zkDMpp&YdrL^J@Wn;@pA$29Yk9wOIeXku_tSfT<$k0}gA_Q`l1)(!YEM_oVQ)GW9WY zUROL^(!n;$SaOz&_PvhoiDiz+JDcIacqs%eO+@fwqsUPCLlY*q;aw|j*X!1`jeo~} zIw-*9zVP!6{#jVY)|*4(r($fvj(=5AqN{@y!HMi#Gfk!pWjMjPp0W29N_Hwkw-y_? z3iBGg>_3%8$$5ORI+|zl7WHkg0%a?*|E0GCh<|r^oQSlz$V4nA`xWOu(Y)uuPnHK^ z*6fjX-6064;^*8-XZ4ce7V<^%l@i3ECIEqAN8Up6De+9PYAbOK9|l_*@ak+)VuPE3 z;^#6mT4b{^fQ4iy-z!gtTzH~+3(qO2T-HLSA~u+$o1O&!ejKyqzYzkN5CR)6P7{0) zjwZRor$x$JR;6lZ(Mw0Sx7;kT!Tk>8{$?zA1Xy=!>CN6h5RWdKE@YO&diX_O`uUYx z$b3;S^c#?u@H~3}#GqeZD<L_WO)0U1d4M+ufQ(UicVdvhKf(Q@2GPmmBO8qB<Z<M$ zlLgk0Y*fwu@QcRK4SVFuQR4<z@<H%~hv?Pqi1|t1i_U+aLDzKkZB{-q_zxu6rKrPW zC&?gjUlEaAtp`O%)`w1uoGc=8fCFI#UY!n1?)Tr@_eBH;lWR+72zuM#m5qHC;|?2C z#z>I2a3ovSmmZ}722Cy@c?*)C3GcZQqAmmH84y4yky^035AwedE(dKucEJ4smp_nm zv%~;>Ks+PhHh-yELh?#kVte3w7<Jn?C<M5)6r?*~D@RS9>`6a>SZ$|^cY6p#CaVJj zMGVL`kZ}MW60tW2VSDgix)&{H5U+;*K-LULb^$O8sW98m$QzAP$vDkKtU!?tB2vK< zS^;DxMJmGfCeXsG!+uEftieePwxs_6eEAEA;a%X%M;nTt|2+c%n9f@<+c=Y{*wW&H zLWK3tEDM1|f!92E_!dJ9aiamC1~fn%qjwYHQ+B_1emvAx&y|T+cKj7W(9t`=RO>6p zCGu>`ZIMX64zLLrp!QV&@1O;_IF@*b44j`YTY<|Xv-~&U?0SY8ZEnoXQ$Oq@ogZ(; zw(mX_jMnJ^CCkr%HBZ{mMgMq+p7}1ewI)K>FxTrYo}6^-=@qrGd5j`xdD&qsIFN&! zSu)!qSnm!CaUf8p-P;r7<635nYAxygtzS(yDXvznaf@v%hmuJlkTDUxnvtbre;~zx z`+nYi2`i6}LRpfpL^BcG8zIsv7vo(9wP=gjYM+#^laZ%D(M(`O2}oJOOrqCu?Q~|8 zO&+os=*P#O7#^^CKg3D4d?dijWc!<3X9@fwPRNlwC7x3hjUL<vo&>g%y~n`=@4a)e zvVPN9ZrFGr{5c=(<pzlU$5QytARTMikqshf>%s+D!0xi|_d8$Djpi3vAC2uisd4z# zG2kBL4O!S7RrN0sh4vk1A}g(ptk&y+gO9th*gsGQrCn{s_(NHwPUUrYtEM(7#$*^@ z=XuocHfttIToa~m64KXev-)}TIXji9I?K4I?ez3<!*L<|<7}3EI>x?qo#~_<s`$dZ zGsPYjY03`hb)6e8E37JhG5-DcLFy*?3qr1u#~ho#D${cAKcY%o4Fi7t_dY|s`*C7* z3>IsTL6X@eDHtmuu-}N`o{6G$a;R$2Ig8R4_mr7ruQ4l69hRlFIe3MiX(MiD%CnUc zhxH7vXu5!X6eoIea&=Xb>Z`WN$j)SU*AsG|K*4}re8e6UR0fD1tN(m9lC%F{%StBY za=PoA$^iN3<p6qd(%0<ntB2bgNsuF`jXtALec2)>3v##PKab{OO3A==BF9sc3Og$Y z^m|V)-?0y~yEM~ThTd6PAgJ$D0zP{}4z*6V%+|b1&1`E94i2u$BN(}IiQ~<4YVy2| zz7na~i*pyvmS;FfTdcdg$M;f}H2KQKKakZS*xT&i>BIeos+JPTnYOKmj$DCUuF000 z??W$dfQGP=pt;C@J~kH|R<p?X&wVaz(eJ|53!g_N3AVB>=Ke%t;?36QwCE0+6o-P> z40YHXMSo4+C9bn!L(ezata`0M+4OHUU`x<iQ|JGe&09esED)KvZt=li_%^VBlf@=| z0!v=8Xv(vhf`b$N!O6)6yx=lh+RjfiMAJp9C#;WN+`G-F(fG*E*>l`i*6_b@9)^+Q z$aJ8hc>W`4(4*rHhNGrXX={^ehqf2hMP)lr1<YU<K{@-?Um~-`jh9XocGed^KWT9x zydym2n7oq`*NWc3oqeb{1RO=MDBzE(Q#x)HjGm-%B7+>VUsp<hcj8v-*SYG&2X8F# zvy>eVrkhd-cY~Sd1Gabxz4#-MkvXLkJ$c3sB&Pv6`GJ03afefAoAnzunaf8GsAT4r z>E40(7cMKYr)IP4tm7^(@|7$9Ct*%~=auGlzc#0y?mUND{-#BD=$bonXUL?#^J1mq zjRdP1=digBpA>F$iY@BtHcYP9Hf~NY5C`0xDk0izXDq6rKE84E29xFrsI=07?d;vY z+hfgqWgQ=4r`aOE&sC%f5Sz*p8CCu>@1d3eK+g29$kj|_zoI;2Oz8W$)dLfSF3fMK zM8GK=9K;)#?Me*Bg<N^Jby1%jkf+=W{mbSN4mBgQpa9=$@zLDCH1WsQki>S|sv*)2 zAC1`EurfgCQb0wEKpP^H6W-?cp9l^cWe3Nw&Z)r#MLA*tQ5%qiJK`hq7s5E@@0hmh zfinp+27%nc30Ln9ME-c`bNfd-t>u3ilrsrr7aI1Ft8Z_sCWAVf8oj-uvg7($NxJ$x z8N!gu{hrydUBV9Rf=g@fepI4y@&QE$FWZ_(uGyWXXrS;vm>`#H(a3INX=4r`o7s?{ zs7$sy6TSO6abFo4q-qU9SHJy%$j<Ib(mT9;qqH~EF35AA45b&}mwvZ@Gl&~ZfEWU5 z^EbK|!0~_^&k@|o%DTWU57Hb>-a91#BW0&Svl5M}JBVh0?caBrtnw*!0rXGqG~1jU zX>O;Z1I7iF$vm3q)kGd8>(uCZIe>q~|ACakq9KZ)T#Zp=H@hthyX#d4cR4&mPacGB z%@eUv*(J4ROZy{8Yh+idlx=%O3Ybu2e=@LQZtF*vP+Yu*=&nCS_X1_J9Nn9X@cJ@> zwMPz_VU>=v0lk{j^a6NsX;QJ-B;s{;PNUfpEs*@J#Bk@=5S>Ma?bO*3(gZPFJ7bs| z{NogQs|lq3&7}g3ItV0ZM1UiT1zO#&)1`(BMN9-7id+gK`ym1n_iayQ6S{hx{43?Q z`5(v~^g@UmgsmQnTH-7R{0mH?I9m`X@Gsl?NbU|ZN^I8Pnb^uRV7L8+b$dX#O;&P3 zR*q~Q%@T%)yxT_d0*}guZk^ALEkl79YF2@6jsc$u7o=eu79IHo?KATW)mzRrQ+a58 z!6%r6_>j0S-y0~)CxEqM(zn6YOX(-^l`#ZM2_n0c&X1-&z7R>s9j+LnzdZ~Kw9*xp z+uf8`N<314hBW`w$(GVDb}cX^Lqx$hJSvn<3xhr2XZtFc4gqX-CIScf86qOPu6AUJ z%AZUFSREIneR~pb_X3vb{u3=0<RE!PkPc>W`O^QAKLpfhGaM5swrrE)0=OK&WG=`f zz+|88R-pd&{<kk6BFeSsC0>7^3U5;DKC$-DBP+K*fr1=VTgcqDsg#or2usm=Y|s|H zbO@|jjty*u#aIDihBECLdp91kQJZljk?IR=9LT=d)~PSk5rYUih#md;*S<xffMFkL zKXeH?W<nd6Jlh}eOs}LkSRnuO?D2v(QY{p21=tw01Nn;^irvO7hkXQosEe>ZqU{tb z)i*>*pP|A=e%ER7de);{t}WQ!G*Bda4MdbL14D?+1`7qY$Ay0!5x(d4{E{`+t@&tJ zy~vfN(4mNP>#*y1+1I_D%#_JTNgU*-d1Um2Dv^H^^a->eAse%`m5!O7yxN`^V#0To zf&b-{oUZ~_kjyNKAp0?GFyXS0fT{fLeU^9#jf(`y$bcas15DZ-?27<F@@%8tef(i$ zvC{m@Bh!$g1=<M6XhH(jCh;LM=b!HOWbpP%KY+BuXS~*;eUS3mX7dqBbT#~AgXHzM zlg5)geLyeVrLP{GQnTJOw&H+E&vfYvPKWoAgCb|BU&2oo{HCadMgO;{0;l5+@uk|X z=U|V1?MU7V&^>XOk>-)qZkIK7^w>#|jJ?f-L46>M@*?>f#I65Pbc)%J1~1PCQP+iO zBL`$Gu(v6e(#93GK|O%%JF5F@A8MD>c~S$|DySCX_yw24!imrO5(VzBW+#-10UNg& z=m6MQfE)k`+9f@xGyl5^>36i~)W?2J^w}jmF+DGrG_T@Q$Jxa80aR@75;dLo0AN#` zXl%&}TZz)1sm6^<na~QMRJH9b?+KhCDp?%&DXOAWbRjKZu|l_V8bI8cC`5T79L-8q zlxS*<)oaA)yvA_6*<R`<`6md(E|v8aDOKJ(Q~<;6?_Sec)x21DqiYJCTcrOv+&Su; zGouo@D2+nt1^b?ID+AcW-3_l10_iC1lS0ImX3bPRQWwy1JK=n==ATBDJ0}Mb*@c|s z2eQSaYa?VKm6GHU1l1L@P1>eSfPZ8B(f3jxo;Lr5w!<Jqje6fJ3i7`Cmj`6;nQH%G zBWt(%S}z6+oZrZ$`fw_kCw3B1+<}}t3Kq<mV?&D?xwD`C{V=y;V*{omQ;P!QWCB^W zbftb>xbS$Z2To8c%Go>sn}pRS;~oBSq&NXjf<Ymb`|kT>MKCF|mszjNR^Ibu)=bCz zxXa_TD%GY32PzG1E0`#T>?Z_R&dw?Rw|R<ttI+!Mh$cO?w>&HGlc?V)OVYHYBx}Y* z&Z_RnB5Wo5(ZBH#uex=2t|6?!?|jbjqi+t7E*zMNNXyjd!<i8SfW(7N3sJl8F794N z!f9Cj-XeLnb7XccgSF#n{<ZHaYS89hCJNRlxJN;TR8XGxJH>{>8E&3zSq)f8XN|Oz zFJ*2yUVG5JsYeVDMPtWcD||}F9scW_fi&G^rigbAN3fTlbNP=#FPlU=GOc5Jea}%4 z;NSNccFr~Y!rE8v)(inp%V1Mgnbz~1r;{o9SJz6!#(r?7%aMG#)|6W;w<t?xUA_BL zZddkUtwfW^oXal{lGL+5moc${bN$!>Xp<*>`6&<7|2kcrgvSTmT2Ghvd}L|Pf34^9 z!IAOO`sp0X3E86jkdthJByT8*264}K?_?$Fk$67+n=ceG({Gk9BH7QsK;Jf6-6?GG z1$qx92m5z+X7BO%_Y?coc_|xt!kd$0(8Rk+80c*yC@$g`dW9ik6<~YT0b48pL@RQD zXY7Nh8|$6}UKFm_s?lYM?#g;|CTSr5+V2ZrpzX0enG~H_KnqpMl?HnDE}Pd87NXXu zGwcx)`%qX`X$7L60#|4`)oY;9u4WXkFu8)<I0P6}-&asIR1pFh-BvXh%mAFi_oVD} z82v2A(X9H6)3dA+_ioO_x)b>}#nw*&*9wYc3z@|3;yVDJ;WOAZGVt9j|AAx~l*E$A zk<Ocz2{o*Ow)V#HPpqjwe=LI&Zn#D0qZcE{RZ!epEN>oi1WI}gfp4?w|7jrVCH*DB z?=eTCsO&@ouW0G(v$r-*%31a6M@;D`ihI-JM(T#_x$P7^CriqnSKd=sw5(}lVx^j- z^ls@y5R_NU7On$l8EmuX`knVg;aR&+zU<m%M9kZnWQePz9$4ptFY>S)B%n3-fi5z~ zEqcYaCcru<aS(x)$NL7D{2l0*+4kiO=N{m1%X8(@n1f!*8=g`w<Rc`GEufc=V8}%f zXSa;e#f`(rfz#w@u&)mIgpz<`4j9&kiQTSPGX}%=@Ef|!fd{u52gR+a?L($uW9NGn z?t$<WY;y%!Ymxc50r*OhtG}p`lub;HbPZS63S47N7V21=5c9@7ZdgMzT+lD{An;Xf zw;+C%_7FL-1_idn_i`k~Y`Y`I>`wP^O`m$@ZENDZ!O0T>>Di?^P#jDnc2@x6=C&i5 z!Q*$9qZdwZy?o+br^$C|9`(U?x--|@P!xmjS!X5o9hr=MTZyOr@M%c#olU{lr^Tve z&W^&cJ)^aF0Kg9*PeA?EZS*c7R+Ca@-z4xCncTjmdm-<{+W~6orwtGnNj-x-6s26% zZYnxI*hHhl<~)hUu1_J|7#(o`x~2dmDtm2N(IS3gQ^#!2$N>{5!a8tQJVC!qhwaX^ zBw5W{*Hl#h{uL^?*wo}IXy=OQFtMWC<FGNN4rCed@Bl?Zix%z=n>>fah9b|K=-ji_ zWgq4&CU<uBJge~Y!7Utvk<&4NI!*ekp=1L1|8_b(3USN^jGWy~m-f(YVBUUKGGjjQ z%nP2AqZ6E1f)=ePTQ9N}3RG8Tv#kx#aXD$vZgY`!AU@mHXv)F(09|7&T==VC<<t8k z^f5Q8Rg{`DbN)5y?S=N0Ef;xB`8FMt!zUhYLHCwyHO84360WO6UJZ+y3WP7hHoMUj zD^2~1GE||1q#%W^<;e4*<L9O|FZQ)ACEkl%Fpg)Wfw->xA1CWDrC2VSH``ZDLqLu% zgo=d{O`ODeodWI^zp~d@SB$?`pm@%k3Ab1`a^y40LVjrg!}N}QL(!6xpKd9UNeIM3 zU`q@!WZ=W!e~03A)8C}I3kD<`i3(BigicGpmFAg&f_NX-|3!sE)v~*-zYvL?C^B=^ zY)05~af>CgX&GjT?ca|(MSW%t<u=Jl(;pz*8`x64eoNrNQIz<?F&S997VQ+<SISdP zxg71ZGkawAKwj^n+rXzzhqYr5nxBOFf5Dig0tDk-PS#D;LMgLN#3;vqILy^K$LEE0 zd-d(<;o!2R3rYMN+rIUk;eCLqwwL2%{L_J~H-&gwwkgwWy$S4@qNZoA54c0FV_;aY z6{uSNud_f?MNvCCeXde9bvEXLP4BQ-4E5WI!FQK<=p!ik>T#1jAsuzf&6ve~{A6oA zdvJ!WaHEY2+TyOG#tTJXEdZ7Le=we-dzzhzyzdb^g)3||PloWjE^~k5ele~__RF9o zK6S=!IH(9t@osvOALaE0xJofU@lzXSV#D8EHs~QUso4dThYw15F2ukN-07XB%bQ|F z7cd|AA^8lm+;hxZcZN?aBpTq^*uw}6$Ur@L$<PGCTT-B7`;HjYOu<UWlKN-40_zU{ z9LaO^pb3I$2~jhLU@18d5bPAP#aE_^vg9@23O5{+qO=*1-!iQfsJ5=CGR4VByap6g z3i*;!2y7TN(4!j|Ls3bT7ryi>BhO$3LH?DhAE6u`jU44s8?Be=t9!2gVmhwr8SMs| zNTF?y`9ObOAA>VnFAdf>oY|7h6+fIo>WYPYA${^WG;4NfRmARk-HSgE^Qz_}&CV9) z0}2hEPrOo|!)%!#fEW4%OduhZu`bdJ$p%zWu(hg)&b-@ekJ`PxVMU5ZJ^K3>_Dy^% ztdO&O1~p5DSo?e>^Y=(<KYDr7=WB6+rljfz%U=kIMxP74-gcQ6Gcvz(2DLH^)qdQh zUt<b_7EH&C!Wm6$>@w7)+UD~@3~EPDd&*sNjGg(?y2xnD*gx`oE=v-Jba#^=eplGH z+6HlSYXi|NMUWkvZMD&tkAc-Fu+)}3Hc8S<{msOCvdmgzj1*yRy6q9$@+X&p{@}-4 zLE*AJ0ZLXp2OBh-MkHmsd;!hP@lIqAXOb{E4q@AM?-hxNHG-Dpu+<)97Q}h`Mibm3 zF)#}#4dlQI*=cX7F_JbBZhjX?q{`AT&0|AE8uk5~PA1R#73OY9s`=eYK?y7XVWdmZ zm`(S7eq|7^U1n%P+{+Lt1%B<~Joh&pxV45FdidANjZcKAzo%xn8?xtEI`+EjG7B^- zooAIR<DAthiXLz5Ec*0RYwX8|FN!NvZ0=xK{2~+tw)JRs+=zD|o51yRDGT|x^;!wg zXPRwi$Q4{^N;GcO%wYElAQwxPvo&_XyW45sZ@a4cC{j&Fc0X%T84UwhppnbA-`=n$ zYmpk6Rkj`9&Vsn!0YtI%XeBF+to=krX5T7Db0V9$$pd0bQeU;G^eUx+Tc#Dc9<d~) zlH=h(Rt5^$B6M;)0ulnEZOUYML9ld8|D>iM%DZ6`wV*>I;BW`C*?qTNSaQFRJz`rQ z-)jbuZUL|5nQn+)Dp8OWTgj323p8*#|8!xx`&cXM70nDTmZqC2Y*Rfyy=6#g^F)Re zSb#h{Nz>){r_AC4qulR<xKB_G$Q0Uo(LdI`w(U{>gi>@{z-HbH8O9qAWwX6PmTlL? zj`(!Jn5s_(wG+KYr4jppCpJNb>W$c1HCm%Nbj_ht-jy~D7t^@bR~&v~`9ztVr7z2% zmlkcxT*Y|!?aN(K)T}=X18WgM!Q~tb0g64r<BRNAMaf>Mes2mBAGh`$b8Rn($WL#& zEtriWJ?{O2Z+T@t25C2?=~Tk)Dfo0%>I(w4U(8$DXQtj%Aip4wVJqXE+4M^<G2?c+ zLwjpQye=lW;q=sSZoQGo8|#~)DGS-d%%w;zFM9m{FK_5~52L#B43GS-8|;4|RZ&dx z`#eB7K^@BvJDKc!lhbQ5TtXAe8u2Vl-(;y16hHck>~WXsP8L)=dn%e4qBh}tRI|76 zy-J^Ee5*A9abbi0Cfh51#n)6bg*p{kbb9&aQMJEo?<Aa|mp{cgs#>Jf>mGXaeb)U0 zDTk*RsaDz`s{a&uWbdn3+47%NI<)QcKAMGWHpP;wp&PMTx^5JhgQ<``e$@%=o?;Ej zZ71inJkVwNE}^l5$X}ZJJp~iUje|g)HwAXY72C$dedSDGC$#nvsX@AWwh!f1BBLMh zZ6A){0!M78w?jE<&!sOtMFJPfkQZ3JFIS+dz^lpSE4RJJMSkz`sk(DfqV_3qr!-2l ze;N>tItqe77T+&@0`h2lhV0D`Y>zez;D~M-{HLvgsuDK}7Z051m}kiKpJ`onFA>&K zHuk0$;~j(&kBG!)cPW8^rAkQ7tW+o<g%nbNCJdyvcgPC*r$Zg+ITpAcDcQ+yP%dY; zal1<@4~HC`j+m(8wX-rnN9$Pr<Z+CQT(FI)cVMm?GYXcc9xZKqpH*;g+SOtBCONrE zA(eVWY;j()g40c8w)c{GSY_1tu{-WL5`FUAc*I&l;PA{?O5L>PxqiK+BD<ST^fzTK zFVCCG<Pe?k1pZpX7v-Hc`I!jE7m0Zh{EnE;>Qch`2ciic^Cbef&g#T%pFX_R!_Y13 zS|i~4L!322IX(okF)^+>SGIMPc%k!tpPR$}%kEb63vcXXv28yT)Of}#vwIte_G1as zFZ2gm)y7R4g2_d5>}WQ$9nv@U)M`qwYnz6V$lDOf*rL4md>B0S0Din2Mi2xA&nR|m z|8{>H4kJ~`$JgIks9Y}jb|UYg>!@oYBeV{h>)wcA`*AwOV(h1R;I+X(eD8(2A6zqJ zKA%?P5g(41<O?14^B*k&N)K>JfGl|)z_biVIn^Q_84d2DV>w4!lV{t%x7au!o-X<O zsxKhAkPn!`OVGS?MNoejd;Md7%?B8Sn}CIj(5U}{tiKZUoVPSV5YN;ot#`y*vR$C( zb1+p|Sgx6<7Z(;i_8M&q-#i7F=+k{wt!w9Th1Il#nh7)dvX)%4Gw@uCh%UAXQ*lxj z8W9d_h>Z?>pZ<H_F!$^&h-9sj(j?Ou$cH#I9^_YjhRFS<7y8_Xfs8@)h(6>sUZnQ# zEFe;i!8yF0`;cRFxa`2L!NLa*uQ)528RLiJ@UJGA8qgtq7p=y#R+d^Hgo)~UIh;)u zOc0ka(;(L+u;da%a1th@50$D9*~b^yjgFpZyk}NUx7DTul_4yTas>NuA*e6o-)FA5 ziyn*A?&e8bV7Ldmy4Zk-aVK)*WOWlMxv&))frdz;!pmv$<68H(^*74g5oAmubrG>s z8jvEdvA#|>lHi@L1uGl7mACYnclW8(GMWC!h=H=?tY8tL$N6gq`j=Ry1`V4T;a@qc zP2*qmINbJ%Ow+GJaFxYe4dyh+i$4E;aBV`W%|`E{tSiT3%jl{J!)sK*=lGneCaoBJ zA8XORBvg1knYo@uFr4}bl#i5COsz}H3rsV*_GC$;<gWe^f`-?lvS+pF^F5r8{4pP7 zGE4CA=VJG~jLaBKngp25lR{1jf5|m3MU77sng4bogc_F>6{A#2mmf|&h(tvxSC4H_ zD;>YnS8nocy;IZ4g8_f*fl2ZhpHqNhG<%VoMOuSGp^9tBotJhKQ3H-mBN4r^{pT`2 z7!=O>J`n!&0aOYLU&BooJ`lf%IvLIHWc~$n)0#ROFbm!;G7>P2>T62gR!&q)G$BV& zLZ>j7vO#1AUeRTBaovgSL_AQ|JcpWy-s<EH5JfBiN__){NB~UgNi1ya5)k$%;5uI{ z(0A3MQ>o_iH`LBhcmCB!?RgFIGy#~J{{2YI3TnMM>u>&yPC2BGa_no0*<=pnoW}{~ zbcTV!(fDN(24_<-z>o%j-$n{(NT63uC~5;2LEZvxVkh85Q#=Z^tOvQjK-CKOeZ1e3 z{IRgpEV;tY2e1h~K<g!3o`=nB!nY=GQKqgyKuB<R_q>z0s7XIvtcdJq?1Y9{%&ul_ z*5WZluK{HBNVC>{=q|eio}+(_E)@j2;~ufK8*h}=slUQT{cSi%kiP_G_zLt_f^U#t zkvG^>YfwuZu+;|i+w62-ao{?n1Mh>Hg)K&^k)c6K%9+<3J0+?4j@{+KlMs*6JVMDz z?yv<W;27rL8Rp+7$?%J4qOcXpQE-g~dN$YMi@n4qXdm>KteM9tvsd<x2^!?Cp_WO4 zq$LsO5XcNuxcxmvtvuzDutiA<d5~%FKVE{pLZYwk;%05Q?)4OvQeKM_+P?5h+0GSq z9OTRFBdayYXb4Ej+@)sK^)>Bw+MtQJiqw7^elJ>;m)UHLqbfc{X}HkQ>d=V@rs|5! z-^|&TXMm(wnkdV}Jg*kfq+NjTBV3TMw6Hq;^L}`>=b+mITgdv*?K^oLu0L1pZjRk6 zDG6(l4DSG<Lb8`gjSpIT|DsEW;E9_XnAM#khQoDAkA(U<ef1xR=&kfJA&gDLg$CdP zE3yj9Z$!`!C7n3iVR`*9Ndz0w?+&&cm$w@(r_R~uTWktZBkBkDTgjGMHEhu%JO11m zATTiF4s)$rSBN4&V60;HE4x_IFT_s3%a*TNbU$ron_7E(KjD&FeA1_Mvc@&~g|m;z z-hDZOKp7agKB^kHxDvr;Qy%t4&*|8={;IV1=9v9~n~(7(4n!8z7cSoPgcAS{Zoqmv zLNzj$#+62A&B47X^|%nVA8uyuC>~wkdnnD&<FOjQ+aT&;q{RcMvN5I}`ZJ;leP~h# z|2f>#hC5z>tZzN=t1e_^F&I^}-hkooNElyK#`Bb0`rWAQ?CqnrrEY|~nC5Ir5Y16* zFWRLX{LR=WUTh-sI7RLI&zHSghzF^>pZu7rAl@aozENa7ic_J}`vPt*w%{tq{M}MB zA(xWnnWgL;GUxR*z!yFO1D9|_WC(4JW-=zoHIij<Alig=-Oy!O)pa6?)VbyKFRxXX z^q$L_FS1ioiDArpnw;Ppk7R&2L0O3Wc)8K3`D_%PsTTTkY53~>61^C?ZXTAVDzJv5 zXijg>-jSLFmi7d%=VQ`m`DAL-sN->ptGa|Hyu)}-gPlg_%y{x#m+{ZqTR-3qQ_)vk zx~Qw3T;AgJaBf;dlHyj;{nTbf+E3C|;{;ycefxSoSas{0I)DLgGnFB*j6(xAXF=N= zyP1Lt{a*MPAV7GIAh>tW>Kb(3?86UlTLRw)q8Dzcyl^d7sQQP@QE4sYkT>~3wSMBE zn9akn(xGSFLJz$g)|W)U--y$-uHB)NnK;&>*kg+w_erv_artar&2}n>pNXv@(>IVa z)Wy5%f`x*D?QpS`-90&Lemxd~&w=T~KS)1|OzL^-A@DKd;TU%-3rqLUhK9p&Y9EX| z&Yf_oR+k^0Nl5sS$RI_ia!Zwrk&OvBXUb72I?dNY_f6%11bG%3e%%uvb<hfR1C7gE z>ohZpbIcyJv#u3!`Q?nbM98Su>v&y+8|rp8!W65S2R{;Dmj7}PTag0SsIBm?H|!xj zyFJUnYw2&7pgQ@ov(SIVi9iqez2M+lF}unsSXOmAb?{vnwy@<O|3cadIhq#jVwu_C zVh4TCb35~c1>`PAwDEb~Qez*<psPK759Vdfr<qwM<zEiKu?_0bz|}Oti_-uxB)vlX z%dL6~RHLtq*$yMVL)X|R{3vw)L_{?rttzjqYg*jos?O6(7$2wD<&>=%tP(f!zj9pv z+O^I6@LPX5QGn=om?3C#_Ls35K2|0A*`cvRu$LK<R6%>x*AP2<I0J0$toYfC17kl% z<B206=VMYHgfaMLtAl}M83HN!zvS69hA59JSYb9#Z3jvS$QPa&0P?oWd(-4uKoUh7 z3=7QCUm`{T9%|3%_eVX>UoIwr@+r6+VW4D|ygo}ASvpCnty2h`Oj#l7L_bocanp^` zuq&zZ?Z2GWc`Q)t>F^zT>cI8`t3nsPxenW8?gLo}paI;!#O$Y6%0YG3ZmCu_hE%oU zU*xLIutr6cSZfdv1KqU}{%zdHFgAF)nq*VqRijr^?1!B{lw!7{^E*mc?*9=;%Bma1 z#(lKcT@n|N^A+~M06E6w4wN<ElO8$kD^3wcve=d#J3pnsj}H8LF8R)GsGlnDy;@Bo zW0Mjd6-*T4iL{oj?`;(#jei*Jb!(_!cd2UomboNn?`{zV&$<hA0V|*j0Na1$N(ABN zS<p}Js~IS3rm=IsS<yqh%^qXU@lK&eZT!ZB3oj%`yL)A^zi&;gBp>m_NISQn(pMwY zzES@OYSg^>wyCx27V600=PGlzHRl6A;}>pKEs6X>2f=_FCBhpv_8gSuGSxkHfBvB) zOy!la*!Qorw4;~zZ?)4Qwm5w{MmQ7|urb4QgfsxSD=IQ~1LNImbcZ+2sNg}CPfOYu z1Kqe;{i0vF)Hf&Pb4h|fj!5I!gq2ns5y5!meAmQ5B1|y=hp92t3u>!nL%dCDJ?-TS z;atx_5n&T(W^Zx4FyUjLUi@zdM|+w<c%W#4O9Dt1Y#n!~UF0Cj;_arNW?PpWocca| z<KxL&*D(8eiFyU(+L1%@mp^-a#*UXfpZk>G^)U1Oy{Iwzjc2R;3chTZSt#x{BF&XB zPekDIF}D(=s4-u|P{v1`jL{7v1R<ud>QmMr(j=&C!mat*?v02l_YkriZoZPp<V1Qc zuj4Sm6k#flzxMgCo@lki?+?$RUn|$^M{u{^yDQ_5lf%#lTs>*BCL<4W-G0+we;+?@ z>aZnC?&2z`)r8-w!U0t8u`;hxHUSRjBaoKa;>sCQ+|*h{))4mA(A98v=j97Dmu`K# z2`~&7<=yZs_0ZyoMl+^a-C>sEF2T3SInfWUpKJSRCI5&sCzmWr6vhcYSA@>OXt~Gj zvi<EoUrn$}jg-E@rey5r!P!DYOu&B5G)bc&l@@~Gc9PdcZ_W+8P25tydlGZ&{BRy9 zi=3!86~ixlz^m4;pHz3SY>GU3DU3Hn;>SH-#aY5}9Qq4+KkiKuu9hkIQUCnsv<l0# zNa@p4b#{<ttQohrKJL_d9r8IB>Y3O_VLN;Mt7=;vucG;J*@!PFZhIot_yCk+mOcO7 zoE5Y1yG!PS(0d{u2=iN7HTb%EcJiqzoU^{kHHRsUc6F2_<FlDgU(WGE6%``$iiiX2 z-(24^pO1HLDS-vL7)Pm&iwbJV>P#o}g<5z{52~}i(>p7EK!H>p?L0E>*zG37P#l-< zT43bCdxbvjkZ-;Fg#4Wt_x|}gC(fyo<s|FSuc<1a8j4u9&-YY!kr|7rLGcI6Pinyq zp1e3K?jM=nRy?jL{RrMu#YK5VaheIR!m+I6ry#L;gZt5fUz$Q?$JM*J!q59YPSxef zcw0a<N=OB%b#9C)7n<VkN9wDhVlT=)=Uj}1EOa%P3UpuPLK6Ao?yE;qOH7FRPrEHN z#jj<C>*;pC``G!gFvB<UCcT4qLA1~1CbPHWWpNSVZ~CGxJGp-vR2R+6Y**`iaao2h zulKp4<ZN;CXBg90Q$Yv5u(~Oly7*0C;}79&v5!~h%BOmxIxd8177~+q9Ob<FA_tL8 z^{7SEjL8Jimf3nSx#$@-YRllb=i#3x@Wx{}%kCKrN1pE=h&T<LGx4yj2nYaqp*P48 z0HI+I&$_r9_hgX2?(i|SGr8Cu;k3=9PEv9l+9^tdMJH)nq@ai!AUOSmKIF+sI4f+e zp|X{^wEt+MTGR1V>U|-D+Xm1g843OsRB+<_fv*O$f?RJ&JfsMWslRzh`bUgY{M&yH zoq3lmSEu@gIt7^w17-qjV<~1EOreZ23CV1i1KvI-V8$sF*nLd1Z16_>3=EzOAUSns zK!;M~G6@PGFDM6xD34+`4xu*3N51Ll7_V?42%0Z4T!f<4mex+xv@BvelefhMhU^Xg zRtG@rb;OPW7@Qf<NwQ%({IT;3Kf#aT31h@zChnW!$D2=BB#dZ4W`wdZgv%h;U}h7x zH3{Uv0fiCZSpue`cPylZGVv%QKB88Solz_Sf9#5P?FTrYXVa`Mur7hMi8_M>xEtKA zx=^AZJ92qS3}Adv4h(TA_@4x%5+=WeWJT+$FxnaJJv2QmJ6~wFu^)h@(vWpR_q;`J z_37eHR-0Q!az&*}KfA-2FSS7)aWRE^-yRF~v~v}Gfbf{!`W0TYp850hn{nL)&qEdQ z1?O8%=OTCCO?CIZ_El$mvIQQ#FpCb!)Wapxa2_ocMrk<+kUl*VBoG_8FJW^p_Ir}0 zjf;JLWA6FbA(tMe{rluXmala!tX34_dE-3S9t<8fapxC<OnQa&b&#n^WtA?;9=1>h zZ#7)@yKz=O@ldA==J8a%`bRDUPye7#Bdn040oKojy@NArz#Ja<Eo*3Sf28V7&%K-S z#TbT2Vk#-(9xgdM1Ft-)8~G@*(Jk~-E>(H$ou;PjVUZv_dcJkS2*iIdW0=5%qn$+A zbNoVm;;PGu^2~`4s`Z@xxRiP(X77`D9#g)~RrSW?8Sa4c;4%T6vQ@TI8^p~=kzg~y z6f}IQ47dJV^7`{nf%nqM+9D?~G;l`*upMB5vNJ(aPvGN=A#;<tU3P^tA#`Q85+0~M zc*y%j3~Su@4it7vzwtUYj*qAfRk$*KK0?lUdC`wiB$Cjy<xOZEPY4@k&+Q0|NJcXc z^j{hRijyk}Zmz_;xW(-eE5=6DA_R<=a!giMurw-!ma$Ej=MY(2O>?^!&Z^eTb3T*E zr@c^o^C0J}F~{7@790yZFxg{PH_YodIieCO)<4N_FKxl?^SKhOg?m5!0V%aSeD$-9 z!Pfx!`_sM(hw2l=`p|X}5#?;pcsYu@PL&<)Z)N*%O83;M1mz~nwkJXOk}(HgA_BB+ zACn-$i`wlZT}{?RgzaC^vq|ss_<|v=nsJlABaZ@?hE)#hkVkdhmHh6U(?v^sUQu-| zx18%O%DxaY-V^*MphrAHn`C3^M_5fZx_;{&HWUi3wU>cd<x;a!tw+>E1Ps&RQhcSL z&ko{w2TTjQp9Nkz^qCMHa~MJwiHgITv3slHOp|cyjhiw4t7;*w7Oov(5tU^d`d&x< z3B6)<s26=GhDsar2~FPby0MKWwHIGe^&Jy_@?0tpk6C+LO!zsTN;GjBqsc8}Z)F|6 zTE;y8{n$+PC87`&`E+S@ajz)4z+y<gTq^UZWuE`3eAW21#yK)u^FYKAo0tjB@~(t= zN$l+5rK=mvlA!@22?r+}R~t<H#}T&WABz&=`O7XIvfCeZM2Ehf#YgUaI+Ep<@d!3X z)4}QN8?vj!Ws&j^`;?FHIn(7);}Q=_DHzqSUrf>~=)A8szk0;P8(;PAuFlMH+(F{+ z>)^NEJez*kes6r-^PYKur+sHx59n7f_^%_=()aZu^zRjRg?!Q;;m%a6k7~FQxiX%O zv^O&}X~;A_`CxchZR)6-^|wId!z(fZT6B-Ah4H6zq^e%xdYd@*i5sjf=LRcb9yuE+ zgj<+mx#IKtZDM_*o$?P(SSuGBn&gzkJNj5ed@V~OOB<OO510+vNVF(?3cDAX480&x z@N)PM<ot9fEc~%s$QASUQx}Zlm8Q*W4?atTdWZQ)QWcCh^tuiFtW<VOmb^NNDI_M& za8l<^GG%%4la^Pr@nngEl2jjy!mvdK)co0;1|>&4ForV`e)ew{I69UwL%_zlW=|=m zK)>m~EVi9?I1*SSe=AeWb3#N5levuFWY62n7hCf0&*3EP<(>9=yTvJ>!P8#`D|}`} z-TS)WS~pAPb@4Ht`{8IYhh)fIZ6nmKr~+v#e}yKM3uSqVzPM@1Gk)^-GGz%h@AeKH z=#_<9w;9338vr5q8ol10$nf<GzHhK-6HRV~Q?l|4qY<2`>?ti<=Qk?9yW4LfE0lOv z*?@<ULT&)d4<tUKe*J@Vw4EP7QQ0{&KgV5r)=lo+{;v~X4;`!7znp*^O4}nwqA5+G z6iPv@?$+$B&e?JIX_99X<K&U;HrubMzW>)L#{khyQLLgT2Mw^7Y~i>aHP2}m5&M;O zGGGRptVuZl<OgL${@=p$<HYSG^|*-5S(9X^odT9b`t887Tf!0G4HX97P!+OUnt>1H zl@g7M&n2KSl)|v@$Znl_(*Iwg*%R_|;O#Py>mY+M`@1jwi$$`+DG;31B!;U~^ruc_ zWCS6veLL9A8GaNvQIIFwVPswO_JdHHbGFGweIOrS3b=Dk!ta1U+Q>m<Gcybn4)&ee ztzh{@eRI1&1knV=ljulJ<j;8`4!fU)AQbWDyS=;hE55SA+cgfAmf$crY&}Fb_nk2@ z3qwybfSUT44X!C62xXm05=AIllIrJn4KX9g4(A2NeIMO6(uHHukS!EH1|Zv!pj*}< zB^of3<14V=F{F;0pX<nJ$RXC>5D`k)LOV*p5MSYKT=zZ?iYk>hTnf>59F*3fSNIL@ zK=dR)TyYz2+!(fIVIt+CC=C`o47Lisc_2v@3WAs*#{SfYgz11~xk_O?I2H#<ESr7G zN;JDbd{S8kiW1;9up6?m#BhjnA=o-*xF%wd9T{jIiLrBt7nE1lkUbC`DSNJbFWCYD z{!gijBil&IAc&7|*T7r~N06_qo2>%-?OTs+0YzX{iDnP32Gk@d06j@fM?3@qrIJ)1 zw&Sqp_Xbb1{)t8Jv|xj<?ZRcatnPk>xUzzY-1q1sUp@%RAHeexi=2D9345-)A(W7F znVY*|)o!XE+Y4%@14u&wby3=boaAr=f!t0cC`x(^nY-I7`td3M{a3=iJXEu*fHT+u zhl&i0k1VOJM7K7SLR@~e1f4J@XMDzZre1erNi^UVJ{I3`4WdV`2Mj48l59m3qWB1E z#w6w5u2jj`*;73jys35HWi<me@Cdd19o~!#2gO~a5)jFfpCkqmdg0H<?M(GQ7xP^? zL-%b0U2F}Y2$6Z`fZqHG36vvx7{zCyL<Sf`qigV~H<N*kiA-XsnUEgx0N^YM&OXXS za3|Az1$<*ha1z#-hAlahKHJzk$YwW||Nr)f&u$86py<Z*`p=i_fy211@(3pIxc#}x ze)CQTcD)LBT5(g+^Ssx69EQ#|Tc2y9&$amJgvJTh{cC~IYE<IAq41ge&-ot~{}y`x zuL{Hh&YUAV`sJc)x{G_0GoGAU!Oj5kJ@fu;z&V;Z^CtjD<?RtnU{<dWy_~-1irTKu z3p#y~&cbu*LgR6ndiSE<;!9tiY}vtchErw1<H_%V@tprV@AALOlRx=CE{3y!jydsB zMtAjjnQuolBEC)dBlBe5%{A}ec<=xDQvO-}p)L&uM8s+PAI>N#o8>)uhXq4r&6o4* zY=L2FT90reigUT5z8=cDRk?K=YlMfi{(%GMmnPLG#RBU&58#5Kf52jb{TuMGlrR0C z?H`7f)Y@gsdTH;R>$Om&Ro&JQ=-T~=L~s#_>B?aAJapTRZIf8sSs$meG+ybcx^4mw zWwfwG4rgHa%{84J>KZIFhrx>f<5C=Pxbv;Q&yL-|K<>SuGf6Dq$a9vzz`U)12n4i* zyd`?ama}Hoo`=PPJT)wyJl`9I!{ALe?%c1w8{UZ)Shex3;t$J{wwr;zocp&EIM`>a z{OA0SKqRIsLsmtuU;lH{^Jky2-hTS|vfYlaYyIJ=7ZfY-be%PAzg5;X`7~HKvtND< zG`JJVG$f`gL)68RpKDAl);%lLnt3Alyp#Rf{CceUIq>eQZQso{-CksosRRt@o(b-t z6m13%YuqXNdel}1emy_-1;7-nv49of)C?r%q6W*m-rhTQ?Vt6`++mZ~nFW*Q2!C0D zoV9_6X~2{B+P_ktbj^Lb&Xp#e+^xzkGpQcv7}ojl5b1}rfZPA%j}+LgFPm<5L~D(s zM;%|0f6lLK_3*^zD#C!24n<c!-1xUo%{<<G=Jx#Q=Y4)Xz6LZQ7@k2;vdZE|l9$6a zh+R9dT4!Nr9h-qW&|rOB2IsqMobGq!@!q*pR<WIMKCk8e6_`5jB831Fb5Voxo~yd= c);!zRD`PUzXk~)oB#y7^^5NbG>imBb0E>9!qyPW_ literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/50kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/50kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..d9462805de8730213c40a176fadc1f6872b0a414 GIT binary patch literal 124184 zcmdqJc|6qX|3CbeErcY=Iu%8Pl06yeNK&bU?3K!vCR_I2Qc}v2wUm%OTgtwTEtF(8 zS;v|^V;{4;=f0ft{eI3k=X1_||L*(0TaP^6*NnNY>-D-`ujgyMhW3Lt1Z_WaO7|4R zz`y`q1^*ygA9NDh0)`9>8^5<~{4g<Y{AOliVq{`rW?}jLKP%f-7FIS^7M86XTiMt* ze!$Z<4)$#ugN;f4_~;g9Mn-0KRu<OZ|K$JZ7p)57*}BDuk&BUGAGC#sfsu!SRtKRV zh=KX{?J+?A^TV)(k%^gw6>Nh8{6WEXuzf~GuxVznWAN9$;C+aRhk3`|BPUpRFJ5Ea z=d@G)!HdMLVp@6Ce3#k?;zzGL`?Im{;@>SGxc`8J<UuI~MI~hwRkf49X`j+Lt$W7c zvZ0aj6%$kI8#iy+*xK2<xVqhQ_we+3_$c6U;FG68;SrHh(J?Py#lA~QPDxEm&v^gw zQ+`2VQE^FWO>N!h`i90YU)wu6ySi~ddU}UPM#si~PE1ZsFDx!CudJ>S*GU_6F+hxe zkOhAKLD*mD;sJDR**F8%4Z0Y%xP$+UJWR}ckFe}Gagp_!6YoCx2U~Y)y-3WfW)nMl ziNJT=xs837xWe%Mg$>evr|kb3VgCQGDEkj#f6~<pZDV8rhsVeRp&<%m84U_8foGCn zwUA`GXFv8i1@3i5GZ?qm+~Qs=E9F5pb|x%=Bl4m)<a}R_28A`jIK`~e&IOqA*bFJj zzS+uPA@P6)jedto)95G{w{{N{qCP=`a+20Bu#E4#sJZ*T3Rp`ICQafSjg>7VLeQh_ zc%)Q$k*~Rx!L*VK%-KNwh?z1m%p96u-v;*`Kq48s+O&5v=+~hZnM=S_aHlc9McNbe z7>5fDGN(c5IkJB2(G3Xt8hA64GA;Gz^CV;0yC6v@hkX>$5T`*tG)QgU!M_;n;3*o9 z{_ZEBz4HRALm~}o6zxNbgNh6l(CdtSFpkG)63Ws0OoJAMVA4<Q*V5jxaw{6Nw+O7@ zKuKqm50Xsaim65|j4D&_A^wFkynjAVLRoUcG^nAXh&)FLxYNxa0*?;%QCATyKh>|2 z@B9?Y1;9)jTQ^$|n$C<O*iZsms7{!l((e<tWOzJ7G~Lm^xPMB`U0UF$`2B+WQQt1G zZfumP7ejgENP}id;UgAZcT4F<&`xk9caOr^n6+S~IAu~d4f5!)g>w3|0YkNmsCTW# z&ClKIm81B}U}yYkkQ7v~LAuxoew|Af8G$GFeR9zIj9nCtpw`i#R_$BhAkqHtn2;RR z9ZlMrbG;O10$ftEBK?Awc{GI-z;aiKGgQMOatl>DF6UW;)pRy?5S}uhgZOfXu<IOX z>Rt3VBW(ww9HP|%h~-||$<VoRjwkEzi(9}ExWUVN&E4*48~{7yYanORphWi3bSPsv zcby$bTn#*_l|Vo6I~EJL$3BFbkI!~rsRHL`3Y`J39P<@JPAK75e#JK$#%3qOjR*RW zijH;mPnyimqS9dUW&Cd&B)P3LdgLM}JA8R*(21Q4aU1ks9Ex9O)}=vKtl%}%A6dT> zDWy*$qDk!CpCP^nqq!vxD=;;>Xoj)D${9CJgUB+FODCZIwuc0w^%2GaiENE74H~C_ zY4@6-XZmT-q@IN~#1}sjx(@Yktaj40HH!xAgd15#C*w(it*j`pHghlv(dx#oEXI?z z=ZqBl(vSR9GJ~ZJ!bfz)I&5y*?7yN_$Md%0VEhkK5p~Nic)k`6xECG2FvU-Gu^PX0 zft8yYnhCecP9PLzqVdIK%N|p^us#b*?VV5j)SXZBMUu9A83kPHB{J5(RqCE+4e(KR z^Vt`%7R=;nNO~K|kU`B%0YsedLugPgv2D``w?Es~v?WlHwY^|Y-dpcwOABY+%`5j= z-d|u@%}kuJ+}|Ba5sTICPJCIf@tINYjT<?k+YuM&bK>SPGfP|J7pDU`g`>Y`X(R-# z&Hv~#Y2DL$XZdN64lG`;eM`99I-RvQ^L{I7Ezk|ir&%h#a87)CWN9pKn3?*vkm3Yx z7NnsIJIN1p<-QO_+NCC|^k#nE^lh0}Z}?2U*PK#&-aYQ}JDwDyXI>$$3?-ZP{ufHP zwISEHQqu3uYGSQ9qILGyv3gz%Ax>R^>DX#dL?Ifo=zgo84oL}IC^E{31|?XuP>C2q zHaDl4`BZOAuN#NEKl)Ip{7uP{<u5t!K2iYe>@lE07RIDj=9W1NImG`SevJy(htfS4 zdr2~W=$5<vYq?}DTXrN`=d8HXX@Qp$A4D8t=!ulF0tnb>kEa4Da`^O@Eo8_jRGdGS zJ{EC4&hQ5FtHi5Ni^1o6Q6hMXmmbit*Xx2%DA^c1Cd3ti39J^9HjQ#bgP>pN0#_`F ztq;bp&>+FF)OI(WR|5)t{v12D29yYp4A0C1fEgV`udyyBa7okCpF}^%83}?CQ-GjN zwVGL2)(St}%`F@ra8u(E?`Qo@XMo$EyFt$cQYM(8Dblc-69W|O7>0~sN6pus%-t#A zyqI%aCi(5YAf~Xyo8nxa!baL|l{<jeio^3oO9@;K^vnKj4|Rl32VU8Uo4$T_&rUv5 z^~dRk3!HW|$bJf5<}IW_*cn7IU^JA7JVXHC7+i^D=!fawiyHZ;c>3D8!_UH>fBsy8 zFWO_RGG#uF@eraqwvaQawu}=0y82J`qmE8#_6J5UKA0O_e6l2Q>DikQc?WnC*WX*p z18S71g;rw@kqKO*o8Rp18c+Edbv!$+|I*j#Ejl|Nyebia#&CO$%as9~G{I}3iwX?f zs~XufNV6=SOu!H8&<`v=?_{XIG8G%C{GnMXPVL>9tZ%I!AjU5ed|jKkpfGn5QI`P5 ziyH_>?656kG1AozL`(vlHjJa#ZW=iRzVnmOO`gsclb?!V+NH8@7Y$;^Y+5!SJsm@B zJO3B?%t<?2nOD$}P*hU!SarvK;}BiVn<|qh)CI9u?pbkBFr$v9tNQH3Tff%##g%{A z8#-?A_LaI#ub<*3q1-eWQ}h)wYLy#nFQ`y+Fnbvy?(gySV|?QKPKJsMTfzCKZbcX_ z+afPN$zmm=IoZ1q+EuW*n1EE+9W}F<jB)xMe!gwh7z!c@t*UnCZ!O>NlvF0}{?jJv z*<H)M^OIb#S|c^V4bSaRDX*&_ko2<lj#$ZCu_&7_zto1V-ttpFN-qJ~^Bn44H=osJ zoG$#;9(_5kaK~ZQ>NzvRZ$vzzb(jX>xT!B&S=Q*KT!(&OetaiG8!$o#UR0IZkaSNu zj^HQy-T<L%?UtkGuPMSzUPJ$e6tuQ(0(YaB$1)QgZY;%}*StNxY5x|H^ZC1u!10;X zta#v4Gz!BwH{_I`9KDPy&<_-A+cZV)mAKn^CpSCXblcfpEF>1B`3-+qo#D$!N&Kv@ z8S=m#y*7-kNh35+0v!<`b_ubwwv2(BFv<~qwle|i@439*w&SLa`xC!}?Ya`e?6dDV z^^g-qsFhzdh{Tq_v`MJ`E@H>%@v(%ZUGaKdu>5E)g@7Tv@4~0`qs~Ah=)4sSi5Zww z{9_=4n@7JS6WG<<sKJHt%oU%Pk2Hq8FI7+A+vB`d;-SGNq8lBo7WqqoZ3{$hWnN%) z+6+*tBSOc@sHSF_LM8{E`p<>$Je0=HP%Z41^?p`e1|a)x^pF*aCxOd~UJ(8UMD>L7 z7gMp`)f<x0v5V~(llawbL#soGVbZ46x><v1(3k{2)jO2RmMQ4Bi3cCmuW+RU)ar?! z(lGI*K{o5F6T8134GCP#@hausLW7!c6h<0!D`6W<cT%Br&t*Z9jIo4r-l@`u{q`3M z%5UvRoUrf%nB+}>r3N;ghkal$JhnZ4g@7e-7|Z+xnhh0aGR>$59Q1@<{*0=b3p&Vn z^x6Xz#)zr|B~q<~TuNX9361!5GW<JFM)L=hFBWw={*w6cN=!E@ZgAfgzZ2r&Dtw)r zvB@60$gy!ecIahZ^W%{FpRUd2d+`f1|KsH_Se^7?h&dTCJWy);6Mf{yH4on0*LcOH zW*00WnwVKrI@kYJ2seL7@5|C_lOAPXCry+l(urqV!HP~5#^M7M>PpH!_DckB-BEtO zmY6qXB|m6lX@`@ufgQx<>+ddn4KUF!R?N7zz|r7!E8Q&<wacDo;OHIC%J#avwJ#G3 zxi^V&qZP+Sb3W0atwo=?ne2K4I=8<{>SEd}JU9EJ9%c-+hw7+r@+-7Bg)T2_EeO-W zq@DYy706U1?1fVsf7PUX$ul=Q`}XZwN29Ob+f@>^d-G2DNs7MY`-v8~O2E}NJ@L^= zCQ9qaF0N_`I)s^sT|N3j)G6KzTBM?f*PgAM<HGDPnQT{l!zh2IPEIsIRDal<AH+|; zxJf_ZIIml|3!x)i1=g~!+_I(2&Xk#Mm1$$apLh_47F<FLGp?qCz$@Bjy_H2|=T(y6 zVP8(@4xP7?<5D&B?Ai0sq2FDfE%aVZcgjs-Iq$nS-0Sw(Za-Bu$?9bVFauOJj9=$8 z16G#GdCx8Cot+?G;PYkM+-U8hxAg~8t0iRHBEG9Ks!UlB2nzg4IJLOWHj`@hd8<#q zUV9BY6^XmGctPXuk70?+F-VE>qGG2dkwxWXK}gmu9*u^9JH|3EIwEEartzHHPso%T zJMv~fR5FnlzZ>v!+nbQ%!H`D^AI=`;UVeFJh1VwIYhg6kJDqU6{9?io^h5nEF<lW8 z=rpAip?Bb;rES-sN_QVal+zb+!g;T&t*l2Z=CBm+1_UT*H6Vq~>0#XnQ9e6>$WL%1 z)~tVT*zALvd;JzYp7Gv8<FOz6jL&|63a0@iVJ6I@xf65BYBYm)sE3YXCNu>vgTTPW z5->V+5<L^TqWIM8zA_X3B#4L)!5LX+Q71K-|KnXau(GyxuRVCMqkjx$r$MIBWcs@x z=<7lZ<pFl?BMlNWPjS0{glV#$d;K=H5qI$6q%D*=C<L5|aV)uET`=k4r2X3CYNW4d zl(^v~^jrix=K`^;C<r-lAfRbIceh{w4<gY=G-w6HvOv2Ia3>~g2?A%o8<28r67G^C zzl%HfjCzR%l^*PbjN7n``&-9|PB%)Wbryf|pE&YD>Any7XQgw_J@js3QB7&{Fah@@ z_qNZM*B%AMH#l2-1fjLu-pt_x6{AmN)b)mC4$9`-ZVUgV@?^<G?K$^IgSuO8?5}Lu ztTYF+CikGrDjs8(*yFW09qeEpb<ZSwn=2hYCh0oP%_ZYxJ&}oi-iJh7K4s@Z>WhVW z!-x~aS3?#`tE*pm)a;*bJ>_$F_f@qO5-<$a)cE}7Qyn#exF?^p-iJ-eC*Qf?_qk8l ziy-}4^^opNENPHK&&<K?Q&C}vO4QxFeNcke_3}@nf*vlz1<QhifkWA9W=*TtJNh%+ zf@6fUJbSrSn<3A*+}e5mK@Ts?&gyqxRwY?1jrKTAGmM2gng5R4V%*fb0G@-rZWS#& z9AUwxHKkb1Ts1peX1Uc7sM>iJCnD|@v7a~n_X9_-T5ImkzX*;E=nDgO$O`MStUqJH z=`zT|bo{%{jScJ0V4`sp94HW&oEb{6gOUDoU>>;8GXM_7G=;POS5d9#t+B%~t#$>@ zV+|y??2*zw-PDsuZ-j5lwMT`ka+EKH_?IOOUAg(Gv<qVs@_qOHn`U=AFb3lc`O(6t zqv}9u$2S@2oE&l$2ZzeXuCq0&l;{InN*t%t7$wAhvLxdWp;L!2`yS7|v(0aa_<7;C ztPg<^0;(cj)*vq9e^)wZRV8>ldoX){YKHuesiJHi_o9I#j2{>Z-+C`lr7BAZ3kt{d zqGPVe>qAkG^zLXy>hj57dCS(%b>zoSKh@azj$hm<cYzd^Et4NkX>x1?<2>1LqvZ@z ziCT}%HY!LspX&znMvj}(YzP<#8DAU5tV7i_2pGcFU?(E@C^rY($j(jVM;_TSYHeg> ztm}c^@;*Z<8jwd_!DbptOw&$R;U?hwx5nmu0Eoxe>cNj#Vuw&<MHeswu&VwVT`#CD z)L1_?c92VuR|lHE2k1*~0Qih)iT$(>2q)-XxV@pmwjRdF$yQ$!@X764s+Sd$hA*6| zV9~Jw9})CZBY}COr#IO&cePxK|1WrE;CCfd0!qjx3&N~lRv-)ZJt>3kIblng1r$H) za0ea_%aJNO$B1Zl<5wClu*AKM&#*t#l-6@j^<wn)dNW1>IJ#Y8!^hG>)NR~kJ~avG zos&PT-t%Dk8}|SoJcOykGkc&<lynrVH)s8{7`e!XIqc<=uw<@WC$}?xw@1#5sjj$f z+yWG~n69?%UIMo@4z`tJ&>sHsD<8extT6c+4buMba{JugVPlc?Y!Qc{wJNzs2wO*` zID)&sr?dQI=5&=VOKi-Jt)t?1dW4-m5*Wt9nSDY>yq`L%|5kKCNpw$0U~7oBui-Va z4)WD1KfbnEx*D5rYGEgs`g%vQ`}^FYySopC@43wwa&p@R7GJy{dMF+*M3GCkpd82b zRma9fmAruSWs|j4rXr(W9&TAX@6ZU_zz>l<#N1KUa?WAz^kl;l4L4#-<O?|#{lwX0 zxQ~NKwH0Hfq^+`G+U(3ijx;&_!pGib7vZn^H?J4pXvyFM)|+XCP?$J`=A>vMtsi+D zOm8<c<-J%E6TdM!6$`a>YwSQiTd|B=arvBD5E;yP|Nen<rjzUi8dS!$h01o|6UByn z&_|m1aOhbm3TYlZ<emFzuU-DsEx9+_q68RT<n?@tU7x5E3|`I6v9$M!Y~EkDCcAX( zO?cg#pA~7VjJN`Cxo1nZMjuu4D?0iIwBuu>{j)>s{f=O7#`nxrp+wxM#@fUPjPIv& zkJKF;T*mpXpH>~3NO4`mGGm8gNp54MzVmf`=|BCo!s~mJ#;*wTAer4DY1>nD=0iKy z4)w(A*2^tbABVRr3tWe@J?EdoL$8cU^G`4Zi3>^kPb>z$9DY7E7S&%jI!|t84Zhzw z$V+{#F6W*iF}pJIR8ev~`1`vXC3Z?m_buNSj}&6B!95e_i9Ms|P8uv+jZ-)$+xm1+ zK#4!9a{AYtpS(i^H5s;Xi0_&I9Bs*m;X9dieC|Wk%_6^qOXrnFB@~yN<09dYEwhf8 zcL@h`J!0j*@!hRX7O<v43<iK|6}jHNRj)Q=+qBpH+@XkLlckTe4O3r#J19A=Y@H|^ zw2&2VV0DGahFguGM&zoa(jUrxO32tAO&$-sDHLxwQhBksD7M?Zp!j*#ixT5Ys!YNl zIa&JoLs{jg=lx#<&h3z}I-r&H*}Cz9j+jc0p~C6{-$MuEqSAnOie<Vkm~Ej)!lVP3 zSZ|M}UGg$Ee1FnTBRg&XJSj1$uDNNO<MR*bgRJQyTXU@RJMR<-#dKx6m36qmszo}F zZ)xSF_n)@8b**YDLURXPvsd<c<}o5-E1Tkcm2K}AA^)(uE@h}d5r?BDuMOIA9QSvq z8>TmLj%A7Sp1vF&nm@*(%F34~_xRBAkHOxV&uT?IIXTumwc8$TF>%LS{qY5L<}o)T z(KX97_$Su&!_l;!(XgZPJCt|a%MgxFfoyeh9h}Y_2sJJ-zOdy(+(&50J$<}$MW83v zVf{^|`>x106FK(_y89`I@*ekcM0US=6r#NSA%odV8no+TM|XPjum$^f$@vuT>`!N& z@s+>aR&raUp<_x@_`7}veX@K7Eod8E%96jT<m~yh>xNZvEj6OwINBU;sEePEpU~U} zvg?e6tzVFa!U^O`P(j4BeQF>8Om7TnL}~yM&`2#o^Ml9~q#0&nLDqRjI((y4fJaJl z7ZbK^WW&`kOgj$U0<a#9Z#C-H&&bkef*YRWSNcfoeF=;bogjU#tF+pKuE#eT&0X`D zK#tF0@t845#y1;Fn^ivwHXj0!(JthADG(L&+=u8fS$O6d$dDUuET7@=JR-4wj0Qo- z^_(s_9=MTff?7@a3^_#tSM6LX*xM;QQkJ&FH*kX#JM4;I-`WSfCs*Wp*?UOd_Z*l4 zEc4(s)d4OCN{;O=BG<pxWWGl_i0;`1;?gE&#IVlT@g10FAE+S6EhcaZ$tW9i>Tzn+ zd#-N7MhM*Yb+QZ?;_yJYN{J2iF_&tOckY+TPxq5A-68*rdqCL97}-j>NYHuYb3`d7 z=e*;cT}ENWkBZ(Lb56>=<Iv*cG@`R$6C|ftD;{tl^5t)VQRi#>f}mA+2L&dawG=Fl zsX_J>y*Bdbx}CM3>DZYuW@h~ol2QCqgbVo&Gf`wxi5;u?xB@h<L+SgNkVbR8JT8Wt zAu2t0GsEQ1AI}`aY#(SzBPLk&R`y)A9Sg454V|ET_O+xz`8u<~<cl71XIf#~6K?Mu z1YJ+;m^&H3>9;%iNtV(Z8!kykF=L_&nbF6Aa4RLtM{xm7*;^X-h($9ts^cARh_ZNA z-vf1@K#hhJPo3E|f<qlzKwV$rVfnGU{wfnTW!OD0N1j~0v(|ELu)_N?^??SL&l$q_ z_ad^2k4>OKNr0}INsjd^wuY_WUP|g0gG>ZbV)d!-5atnnyIk_eBMwIV2A>bz)^PPm zY_uZJC@{F25G}~tefE}!@-O_tdcL=R;a6mK=jH*W`4=0&EpB8LN`r39KOU4Ph|{1Q z=vy?1@A$G(V~a+d_~0!~0jXrauT?GurMMQsxbg0!^cL9nsIEfC(I&As(bt`Ib3JH~ zzqdnaMbT$Yo!SqLb2r^n@?&^x#<x9BG!w-hK?OtC?tg_p#n*<0x_f;ts(XS7nz9qp zl#wmZ+Vy>w;IgKTX(6~EY$=Y%`t%pH#x0ekrrmUgLXxP4Ui`C($v^C1fy({1B+Ffc zGQTx!xAgN2XJ2wOK-eCnTTL7D;|Zn9<4dVFy{=33y1-#H(G*oAUm}{V-Xl~Nq|}m+ z6JyVvX*V-+JTX=xe>=jdYTQ`(dTIQRldI0{_Z5iGj2F0reU@97o2(AT3ix~ypFP2N zPlY{6f;wz2H^)y#5BM-FbQSq?KTYfwFUi*pckp1}mbXV%-gBff9_MIHjfSnCaYKDK z73X>C?zero_E3fMC|q^<{r!D@>NBeaM21u!z6FusiAU;dZHmWy`pVna1NK{$r{sNi z-bx}HhmDb9Nlm|55$$q&wpbh(-&Q&wc=-{N&(G5_Qt;5lH@^3y7F}PIUsAYqa9i3o zZfi{;AlBqlso4`>gSi9eeri9~3Kf%ie^?XX_(Y%LSJ{_tRMmpAnYmNl$_2a@W?J({ z!q%I1W8yxA>|E3z5bf%AaO%~~=_{D3bF#gl_vS<G{@Bv^$cMF(>OAI!uY6tLWA^t* z1BB8pSy3@@UisUP_v{Y)W<p|YIDTw7flcR;tb&Oceu2eS?pEaN;?3J1UulU39xLwm z_9_1EAa^m|pj~cxDU}$1A-0=ZbU5}>a#Upf35F+oW+{1Q+`|qs^61$<>`r_9t<p+E z|J^tCp1N-0{^9nGalgsq_CoqhL^tiq49{HiEPe4??aJHcc3s?G-J2{NBS!S%)fD8J zA<Y_aJXv{`xTjwDe9u%!$#Qy1ryE<5KyIq<`ar3cOGHF`#?Ml6OTay)yy`vO7ImS4 zQV)p_JgQb?wr@M$d{JXptD{lx;;oW>(;i0Bc8A$n)aTKGyJtao3LveRl{_(HnKsHP zh(Ceb-;sTDiAPsjirOGB9au`nMgLh^3*Hky`x^M71L&|!@VQJo)FK<mQ02NJT3M|O z5z`J~3s#iCRFVYZFP)on@-w_B`WlqDwkB+w-oW-yrf`Lf!|*sj=t*faFhSl%m26K2 zdghN;c0vGjs}_3p%Q$;uktVa1|J2+3R5vD2Qr~g9>jp3mF)pAwDB}iZDEYlaXQWSB zLz8ykE^4yqXS^3ZC_!c!eftIcO}5p4skFt>)z<J5ojC3!0N18Cq|$%}Y4P=6U}bfu zK`3W{`=<~$k$c^}_ui~7luZ$i?qtdf(3L=)fmbbG0cXDtCKIs3n!<|zDTQaiAD3H5 zEWl*oLBPO1zVeJbV{zWW+w9BrU=*9MGoPVom1_c5WzaAUDk!ibvGv3FpP=x9rXN6E zU444`{8hbU&J`~`kj@W<!VU4Snbto0o*O~^h!`qrz-+a<e~9|p$K__)hfjuYyB7`i zHU1cDJY|ByJ@+>LHYnuJL6x~9H>5izTlGbr<+e>{cV)cT)D8jHRI;>aHfE7`{koq< zGBpmqb^O?>W+w(Y<YP+AOi2j&lC-NkoG%n(sW(*SCCOKfw4e(tA0$zH7L1>+c$lKN zJ>oB64u2f0?Xd_<Rl_}>R#q0QW;K45Q@Bjl#fOq-6u%L3bQSuZBz3&$%iMeDgNWao z6_o_;Jc=ioYtm}FVut!PLd1w{Y&8F`TV(aR(!F=i*Pk8p<}uUQMaZpb`4L~^jvT<L zo3Lb#=oN3ftG$bnw}(gmwE5x{Turp)k%fCNA0I#V*)*#3Z6@>b6Yep4j`-~kxbRoM zR?5DZuXxH@Jf-L+aDRfYh3-@;Sm5~lc3=0rwQla!C5z;+ZQ*rmxi2*KO!Egeczp>W zSzvozMt8ii_RLTh@$__4pK);$_uEtTqRBem>xbH%*t$=4-D7W)Yrq+caL-~0rE<^E zLix+MiIb^Qzgb!-*1b7wu$ZQiP05@>1;K<1ocuLbyt(&9Cehq7iryAS*Wf$eRSCt6 zdr#F?O?6jZc--FoBLd^F({twI;iKzD?oUTUn$9_tsdNjR^%J;$A^RcjMKk0ZMJQUG z>+mrcbwF`U$8*cLW_qtb()Z;1ag1&1#fKX<gXQpQ6%k`MgnDMITzWLgj#NxG#70*= zx_<xWXe;jf$tzuvk1Z~Z@w7hequ4FZ^v)8ORx*nk&aEACBDJ!n&-D7J6^sX$FG*>Y z{>FWGmdGAda{EQcakSusqSZE{n<8)K6|3EIzYaY5@l5Es`2O!g(E{sEbLQWlrBCyF zB`d8NcjyVl<qC)IGTJ?PV#Wf!dM~aBv+A>ZdC{06xkXiBZr|wnH}>~RpOpAsydGrt zYmwNu_C>mp2B~Iqz+85Ppk!JQlH$n_E}+q)pe)N=ZE~1*Ynt%AYLcOeqod89W(VFd z6`9>Cspl{l=CUu$<+hDklZ}3Sx7~J6`c5(y3bF*-dD~uc=xg%)b^4Zx;F0YHereKg zNTN~))s=cHdI$S024}-hE%llx=X>8^XOO7m_FCj7o>rVajP#Y)z9}Z_Q5rgznpv%I zXQI>wdbT;AD7mAbYYMHDwQ$?AYR6o%(DJQn+;{2_`Ai|Ca@GZxo+}J;27mO3q*=I| zUFqH5E$d%2c=7HJw53CK;JJ>sJKZ~m#M8xJ8jB;B8R{-tw9rF@4*furXA)jy1*n;` zFB`Wv%L;Eg9nsfk*(7YY7a+v;_s1a-siM`w%#FfmD4BvE)fD;cY$*rQLK~i_B4TJj zHZ$C)={8Ui%tB6R?S~U^%KqkMHuZp)0tYm|d9ElheEruA2)x}2s1d-<6fN@=m`?<a zN1Q7Sl2JQ(CwrI4)ng2*>TisU|FVHUJ#A@T`sK4>wz6sG^Q93&eh<#DA-*LoXO|PU zu}haAO&#b-Aq=S0^HU@@4H)0hb+}}O@}A_1PxVdG57-mYe6f;m>yL@&K@-?bc=$^y z<_UI;)di$yub1f0IT|DW?x?kOY<>2mJFdtpO9|)h+$0n(sw#dcyLy`26#DkAEPl4) zDDnVsd2JZ338f$SsWdAiT1p@XI)HweGyUGuZgqR_xkE<VrIXJZM(=0Z&b3t~M~|M! z1g?>P2kgg~m26}o6^9XhotkgooMsk&`Nm6Q%0YaOmkpH>1UvIJG$;VN+tp`_UEI2H z^c<875TVn*>)czI2s>u9U>v;_oRX9Gi9cc%n1rS@MFRM0X^?|Gc9|E*AhsD%fawPe zxgMl_9zO>tdOKUvp1vd7n-z*5aVoPrz7R`_0ZHBuEj8T1gQ6YfH^~abCH=hMthO8Z zrLU58x1v0sG>MV?)kwzQ5YeKd%J!s^%Aydv-Gx&?i0<mUG&|UJ=p~gz=(^Z9WSWV9 zBp4n5IoP%hrl(Jb`uu$6g8m5p^EriGc}IL>+ZxX$Ob`h-oKI~D$YESHqh^$&6DgJp zMrk9q!Ick2ns1rBEFCjDii&#4J-la#<TP(7m)@fEp?bxRv(2jX&iO_3d=~ELNJdHr z=6c}y7ujv^`oA#zVEZz`SONJy8@2jzQg`9;CyA%`c`2tl49=CqijKeJXLeh^5leOF zKKsC|bXPC{&b<VU#LPjDR1ve!f{%{v3sGmeg>o~LKa-#y?u8f<;$ohcTcy@t?<hCU zFiV{NfIt0kktHGC5_c!%=zxQ<^D*Cv@bRbUrwR<KF|&LlJaCRj!<BB#s7X$@szpi| z=Qq6w+>Di=N9ctL8uZAYd~>;&Z2qz?ja;AaBjoAsirX^%Q&%gX@2Bc*x0P(`RJ-J{ zscs;H<8Y0i8ve(_;oGR4l`1{c8vA08rrPeY9C-bTMWhp%Q=N&Pm`ttoBZ82GnXPSE z?rCq#0|j)TQEWwOjM#6nk7A0K1nvqkUaR`9W7)NsrBqnhLq48$aU!R&s%6~d?ZMNt z3iJ6t>OY*h1$|);xV}~WhKnZ3ma>mplHVfe@vEVll<Ozs`cjc?8|)A?yFE8FM(pa) zTeY>^?bJ*}u-8Y0SmwPeY_j)W8uIFf^;NAv31_Ft9@JUmmdq^s>FSuvB}}4Q<BF+v z?K8b&V*)F$|6@-;hnjvtmz#%J`75Jtk$vCIifp7RO-~5i6n6#&aLBNEkZ5({nUP>X zYI2*lyElgVc2#+I2!rJQC*n5a*YaJbx=XTI5Ym!SQ19ZRiM3B)hzW-@XPQ4ZYXT)R z75Uyl;Gf-o)m8M&h6ZW5&WSGR(x9gSsfm33q%v*c7=BMT(Mxg7Q4{fL_Z=?bYD+B& zGq2fMr(0@<n|!h?H<l}$Y9Ed~z+<-CT=?q3)aCJlg1Cpk#Jp(DzZx6#Yq#U=l(*eG zgGYh~C4#p^I;Q<(a@AO7=&wz%EsRYGdYX%I%#k&de|q-%@vO%56XuWCPqd&soG#Q3 zM|WfPR8~|}EKXd-?a)228eG}BuiBb&;=E_>9v~bKEqj}&MedIsziG7h#~ZYma$$3# zB;7JUa@-M{lkxZUT1nu(Qqk(lJB*)mt&I0h%0Key=<MFrIq?I7r_Q@`r+Cazf!!7} z@9q|3pW#2TdpyisiH&rtbi6~MJt0mFpGH}*A|!B$2L0OXbfP!8pwOKcz{7rxA+70; zNi{q5rY6Fe4D%BhUjQ=S(w`n=&{T(5Ph8lHDgDNKN3iSM=a%)UOokXbz%8}d(%VZu z{djtHP&LJ|FFA_wNbPoc{o|61;r|M`N6R<)`FzbD@9pyYCWksw99$1SKDeRh0#)-> zl+2@l!QBt)Zfi34b7|1WZe@CtWTwGuok2|^pQa|=YJLm16sdkc+K~V{G2i~{K2+zK zfUEzXXyMABWXSPj=S-F-y9d5i>s2MP?N+~WZ|J_^18Vkrki9=Y3R>WliLI<oCWs_3 zz?=<j=w-zmEBZ}lR*IIFRd$UORFsC>zEPSScm8@e`T4`@u?sAQd>|uqb1HtBvj`wJ z2eK2UA22l7g6hPs0uVk$g0%wN`SdR2<@wim4t)#|*>g|lw4an#_|`pl9U_tLE_hPH z3AE<Crr0v(=L6$?8vA?xEIf&R;Kx2fIRV;)UWbyVEK;2A12GJ1ZlJm*u)BifmfPFy zU@Y}VRFh$HpMIptOxHK()^4l}nxx1NkrI&7+r9DGzf^{4(87WfGD3rnT8Kb=F{9k; zTjEL6*zN*pxq8r)i(cu1vmxh=4_XlBDUU&}29G>0QyW!326mSTuYtfU=er+!$UJg< zKQM;pD8afHK`o>q8N2cY`yzph3lwj*l=Z>HwNQ|p%k<A##UsZ@Y0zC*3i1U_!@@?` zjfvt(v-T-wI8Y)}1o5Cn@a2RprFb^DaR+*>ZymSa0`mwv#)bl2x08(LH_AZ{4X6bw zE7b`}&6CFb`78-#&ojc=puFn_XI}*+SZp^qw^C5sR+9ojr+oQMpg|b&??qP&tLNA; zP8#GGvo1I;xw-zjsYmO-S6}T>3&Wrh7N#=cI5e37B_hjzbWWw#A{p?&&S^;cDGoh$ z)D4gWNN_Yi4|cWpbuQ@_{=1*lMkyNSVSs2l!R2@oPqtJuA&ue(j=>YVEM|HcGCn#A zuWtq3f;p%)S}3|`D1!rkj$Q$;+)`k825M?7H0Z&7YD*hB+f}i}gMYrC%1gq53f2u` z3!*uSl;tieW^XD%LeBZ%6gSr!L+GoIwotmF+&W7?j4J~{{eiSiBR>^;z(DptihF#2 z^zfL1S5$%>5Un+<6#@<V)@A>RuFeNisiM2UuD78Ga@4Ijlto|wc8rmg!T}<41%||p zvfvRwBpdK-EP+61+1F>s3jvirFGpHKk$8<1H<k2O{w(i7t~&uCH#~622{zCQ3Fb>E zaPI0PZW?z&Mu7qF*m2f2P?%%MBGLD@{Maa`TLH&A%mPRC1~v%v&CL{d!DIa3uq@l* z$pgh+Q2Xn;*v=jKJeI>3gVGmqerR?KWxv`Q1*q;AkaYGmce=y^WDD0A<iag$h?W&0 zyNnZcw(C$*r`+6c5ogMheP`wG`;C;G`A@^W<~CqdtbuwbfW#v<7`TBoM-l*TsKfYr zkU_wLOpe<3ME69?IJ9oemq(IUU!QdLTI^9YMs~z`BQSPx2QZ+zKv>qd6;WMGn-Vy= ziD%sA*8##c>LGk-i4CYH!=5Y2yycDsZ0mQ`Xb_k5o1BO$pz9N8svGL7A1F(1S`t0H zyA_@kMbD4I!B+454j26Bs10jS3VO#971VftRg(sJD}po$+j-zCq4Dc%a7}?a05Q>M z;Ci=V!*cHUDWHcB;;<8BAmegG!wNxU-m)BN=}K8j{9$&hwLIia4(D~F+=tk)BQ)st zYtjXl35u8?H<hu0O2I57Aw0pX$b(S?Q6_egBpIbIv@H)v)mxmZ>C{osD^(sm&)pg> z%}Y<d>)Q=Tlxd;5An%Gxp;o}rG?3YjpQk*+4(k^!h<<WXGi&xN5x<+GULe3U6cY97 z(hq=3vm1yO2f4))p4+0AxlwBi*!oc7DFqaXHIz)mj~Y)Vu%qbSD_K|9%l<5;E%J-+ zN`R;-fpyrz_pUK&VL^gCvEIszr(^t1IvL0URAl9~<yV~fE=`^}A>Oga4&}Wq0uPO( zY(9I%19U}|3x9d<Mb@-(EZ;&$euhuF;fc$=LQK!!o<HZ>^~D2=oCE=xId1&|BR%6U zZaSk+lL=g*Cm+l4^i_P%_jeCoP2w$L6liD)0;jmO{vk+vEdXg2qS(j#qets8q&X_H zV=FT^9XBp3c3E+L7LJvAB51Vl<l0A;BWs^#%(?<b<B4k^_VLArC2VW?7Z$i^SC-=D zIUnar#BtU1DFuvKvr0c4EP(06?YhTNL~8;mE?VO2y0B^S3-)T~<C1?grBAKCQ+;P% zPkvh6D8eRI;b2Ht>~V=FM9$!ss6ZHED8R7ONrA~SsIBKdaeG$wa_)|tvX1m4x5dsI zy#6YDf1%$YvI8Cy1N^k;SP%M@z9sNqL^BNLoq196TV<7jpE@{7c6~bP`A+>2Jhrj~ zZi0&bk8KJSr`n~-O`40}9*p_UD(_HLVdeXRqc1LP#nLf_UIKI5K<zFs!*bGnE_KSl z^TIp-jC>_|dCxs>3pN45u}yb8{<4M6)}g>UqipxAdWjd}KeBYqWf>ZpLdI~)^jAR= zIIQR-|1VmxO~iwnGg<$gq~EvG5yT?v-Q=DX#n+qUEx+6idEZB!K%&0?l?5g5Ec=Q6 zb6IXr)h8d_ta0R6+QQ;oe7yNuH`X5*{X+mp06ZPh6#BOv#OdpGEPJyl$|(KNR@d~z z6u-IQ=OG^Qs9SCmyC;3l0V^*Zx@NqQ18%tR7gmIK)CpFM_Zzt@dnZL}>+&~UjFMow zdt6#JtsOgd5JdP^z^Wv&L(~6qAUo*+)1~3F;B@#qvY!XF9RTw^zCSLo0KbL~FGK0& zBp$eMg<hgjupQsZz)R0t!InCMwJtp2ce$kW>9o&aQ%-)9Zd@T%X869tSH4bZ89%XG zNUT>#0D5~`B15qQ_ou&qVGA81CDEg&4QLjYed@^iBwKLJ<oP+N(-*IV7n?JN#)y2$ zjHi=<OmGwC#3dL9^7O4ng_4^zBa7-SDs&~}36rQ3M)`jQ0((VNjU0^yobRz^JVw7H zicU|ZHG-gl)_Ga=llQvSn%3J6-RwHdziq3)`du$xQ~LGuHi8ZMt2ci|NUO^ohZHO{ z&gq{m;?duwUZTwVJdB&^MQbc>bFl#ZuZLmZ<3K7{88b3A_8y7V4!OM8dFRsIQ<^O& z&FD8%;z(C)81Yj9?TzFZaKCLSeI{L>&CXp?_C~mGJ7;s??k^MVG064`F~rLp##>V) z8KZMLfDH{(ETTH|8PL5W6%1PLT<!YK<Ohifv)T*nj26Q)U0~JIcE%H8r}0bmc!Y=^ z)u9|HEut(G(V$9hVk@J%72pZ5yg3dgZtW&^(Ss6x_N7nVUWByoRWauVUK?evmkwna zq?jrjh!<F8=&$YR0pz!QL4%IVqUZAvKC=tOn5`fC?1BVt3B7Fj(m4A3I_Q>?29rO+ z8PTA(N+96@&R!5btk{K}2*y$gaJ`=_aTGZ&1IqqM@Lux)S3#fVk&$lFyMQaF#uimn z)m`3n#S^ubL)WLAfQ1MJajj{Aj|kXuDES7yy#PJT(T<)-X`rs6Yu;6KIF`%ZakEe< zJH7SnS?9y|UoIzbe*M2$U)cw^PJ7JaNfT6UC$|!Z5sra7!>*Z)BRu+xCBdg}yN!yI z4Do;2LP{P8wSK@eAQn`cqTfRqzQ<~~B|tI0*L%4BMfTK;?@hPS=6ym<LO<HC+}Y>w z<6*--`LM~ar=>jhgxO1-Ge{jHNyqJ0SI>J{>dO1+O(bS|)<wYxM^Os=j3@DF2-2Y8 zM8X=N_Yz!d>tg}1#9%lV5kzsri+ncCPZ8jEK0qVC&8(UzQ;-Z$c?QmJ(^>nW9Q5dj z{#wgYE@1rQRwD4hwbE*>C<+>)03fA$^g{>LUNL14=LWvI76E!aTxx*L`z55KB(ZLc zfKYgS`=$x?Ip0;ZApE!xc+!;U31)Pup+S`Fr2q2LYhDV-P;Y@LPrMJkM&Qdds2ZHy zcp76O@F)McJZXl*7IJ^~mHl;24PS%h{HoQrv#5rf>*0gtJjO*n{=d_H@lQgJM*}!U zzlVo_KrVI&mdNpgX#vds9`!C`h>qOPu**_DiZrP9<nTPAm3>@!HIf*Z+bf&mJscXS zbxM3YmeogIM;PAqMt|lX>E-?ZOz%sg7@`hZ2Xa8W%7AMrcFttsSnZ{hocLilkokti ztkn=;V}oh~;fmxOVA62D25_TWGYB{u#K|3qU1txut-qK{0oG%2@9am+I@JJV02@I2 z%S(EPDW?w+Iyo{=Wsm2C39UqL01NMby&zxqIlFLF-77Ev5q_|h`JRs`p=Sm`-VVm4 z|EvSuH8iLyo(Am`Z8`va+%7c19A38@RWJr2WesVeh00;YjV65e0KgEH5C82Im+Np8 zJfu&9UU1)xfLo^HiLz)){-PWU+-MGR2pbJH@26Mvd#y&~0<+QihkT9@CM$<t!Vd=p z7+I+U>Y{@Mz|eChF1RBB`j4?hTc6|L2rvKlY3tux?gKQ5w2&XJ2TfuB&ZX23)Z9v` z8GgIe0T1Kh;t+$!(u9Y#$;&MZS6=iLC;gK&hF!Frpg|ln4d`VVA9Wxss>3j1)b?Lq z`X|w=%cpMvn!QC$DEGAE82AiS>h(LVnfQlqcTcl;+m&R&f0N07+EuFJM%UrrIP-VK z7yc1HZbbyfZ0uyu4g3-*4dDo-K{D#^{-@kflG}h6IsNVwxGV7O!xtL#?Ejd$TIs?z zc#H=qmO1~rF%YZ2vZ~u~VlHsO>Rf4rei0$J);X-?HyObAk}A@b2kY#rdFZcLf&@6% zz>i<B6D#@@eiUMQwapAo=tc3vlb4AOK>7n~@st3a{{waZu5Jd9@C&*hq#unOz3;@4 zb$w3aviS|l2`#mGVq<@(HY@6L8gE~BD)63GM&n7lDn;SpHv}vVlD7Rv=^u{jAOh#) zBM@L05J?9uw-Bu?RRP*M3{M~eEg&nfSeR}PYV+<ue>l%ZM~m_k?;8C!=uSZqeoTnN zoc<x5|6PKAPG-mdT>}25wg0S`bs*pSKewlIZ?&WC;iqpUmiR9au(e@(tIx%=mMeKp zpkaN?`7ZbW12}$cw8>Sr1iJs%BkuAwUVTY?Hr!-Y^uxn?xXpQZ>mN!iL3AZ}d$s+O zW<<U#g#WInp?_z>KPji&2xgtZ94^Iz3(sm55A~_J8d5XHPg5<38yar@yM{j^9HkgB z-CNE^|NWr;2|3>i7))6$?kog})kgqp1H5f0a=F6bserIVgSJfs0J~>)E`IgV!dxV` zC->t@QA_|w&V4Qq>vRDTg(2^I|D?ESBHFhBhWyn&qy8@J|6pH%!QQy7?$z*jWiU>p z>|OYkxNy><TU}&SpVecRH%BM~G4|drn4=tRqu^Ydh}Yltq6K3uoTsKId?zbptJJX@ zm%pcY-F1#Mj4s0>zx8qZe_il+av{ysr^8-qc_gauW0|4Z8S*4mU`b@-l2r|VGTfpU zN}h!SP=tUf)KdE>LPiZ+NIbV}N00FW6tJA41eoO5kJjNx=JTn2+B_ix&uuMq#pM{) zSJHv?qI2lfV#m~tftpTLKHboy*9d63LOl9Fs+W~wzmghkGa~KQE!V3Zeft;BVUFtF zBVpd`(9iUoG&)aqBlMO#4P3?;)EdaMutWO5Cu#i8eS4SQfZ4aaQLfY@hDk4c>W?}* zpFd_D!VFg3>}W#M4u9Up2cFXAcMH;9j1WdI3*B!Cm1`V5_UX+8dSE9*%S8))dYAX& zCLb4k9RT<y0Cs?>8}>uXbXuC7^p%_a1T`h~j-AM(8^G)IoD1>b)2FA}mNA1qe&|-F z_rN;~y#{bka`;bGhA0Nzo<Fih=s~fy_}Uh~!;}Bcl8JnHox>CW)>rTa2xUPHF|~qs zUh_^X%^wLLIGZj~&6M8QBBGKtPdw*_Ssw-Y2p`l!0#|egavWGx@Z}Wm&xFuDL(<O{ zSSgS1pl4F<MSUhdL{2KBR@(gzZlspGJx(H;z^StkTHm<hMK^%>nt}VS0bH3Jn{}M7 zIsQMl%%E!<pDY`KiA3P3Il-@TLP}Z~LCWlN1Nj-H+0_*?vU-jlWB=WUHto#9?uHw8 z0%8o2e1<O@A9b(AE(#Wbj1oz3cIG*KwE&WC#omC|)$otes~7UEsIrgCS1UMHb!bpT zHqjasRyee2Q2V6AHhpqF6*cDNDMtypi(gqpkuGWYz6+9e`Nsa|J+2(~|CAHb8J0mN z*a@(d@;C>c$$KA#0WMHjR}1x?;-$ab=Zd1gd(No_QrD`v!f?YfYNde`TbGUf^EqKl zQ8_14I6>_~3Lcsbvd|zi7i9XMu5rnO1^@R7_?BD`4019WGzp-_?1O!Q)5Mfb4M%u= z?hvp+h?LK5qJd|wofrQzS0N5nE0c)x4~Ac1EJ-RUOV>h7s`StUuMDFO^s7p7Cq~^| zY<6MyINkY3cpx%${dzveIJ>a055ygcx9_Pv-VtdQWgnR#ePDLFGgz|3Ikoe0>YLc} zZDpVGmZJE`2E+42F`ZetcUR0k<}HZ=Sq@)BzRjc)@AVmWwF{|OHN6n`hvnt#AroQ! zed{kGB)5Le`_e@L(Vo99@cs|qm-0AiK=d3A?XkKbD)y<eGog#(vMV=t+9-Cfa*@@o zLh}9;WUa!?>Z3}?<&Zt$fu7>7wy54ZLe_`nl#AAqy4uO>x0Wkbx}~N}zvBi>C%9Zc zoee#n9b;UDi#&Kny08AV>rGF?M{h)<#52A|mc)Fz6g4ze|1KQO=EhAV#3RLM#NQzx zcT#%wH?Swb;%bF7Lhfg)Ug^=bYT!}q^x)QAxIr+#BKLIVvM6syQimg^*ZbN{d42ag z?^fFCvelbJ$`55V|BMN(!4h=jh~jXNYi4dQ08aF$qDL$7k1kS7+ViCc_E*X~*ekSf zf4@}YsAUokE42^H%FeC`$oz`iX4E8)j=opns`J1l!yrnpHcGN*$?o7e?Rp+N#c!RF z1$O&0?Wd6_br#tiZ5_quD48o-P7l}Y_p4->UW_W)zqQgXqj<6B)Gy~pHWW&mRh#=< z4-H~jhpS}@T6#Dd&?wM<!QC@ahvIaNXC-?18lS+;QS`Gk5=Zo2wh|l*JZ;Q;72Q!U zYhw82B|Qd(Ji6wykyb3>HxyCac-Dn5g$NKERu5rz`Dk^`rsfgR*?14Kxqsj1wI;TM z)YPW;roB^3n)jOS>Ghd4ZMVz5_vv_4E+-dXvlCD1aFgfPi)Tn_%xveWk=80Du++~x z{U3|IcYptISwgb8r~b&BoRLUt>6wG7k|{fLk7JnK#Y=3Oh-};>ko9ym$Xq+wfG6l+ ziThDC@gW2s{ttxtKp$Uf?(l1~0r~k_OQkNWrpm|r^@z!*bNfx}<_kTn!*$~>j&U9x zW;R6;v@kuGk$}Kwx9_vvZ#3eM5fyxRqRff^`N~62#frY^Dc8Nam^x>5eTOuq-3JdB z^k~Oo4)9KEZ25Lgi*MREMbLTN{*sIC!ThL>G`Gr9yUK?4@#3?x)`5wZSKhlO86An5 zcBwxy;WGaGy`<Wm^9mD}THnNc3@yNZic{4mL>I@o0JOAP8NkNf&!5H<&dmcsC&s5! zG~ma|mb(Sd8ol$*ENj*>bWwe&P<F1`=JYpv4f7pFhGTQmuL%<f+flL{kv!svtHJOQ z_jTx3cCPHTzIorrAj7mt?W7aa+M1w4X%lnZ%yn_w=-+Oj?H*qW70g2!8&}I7NO_p~ zl=NLBT_^Udo811is)7CdnY!e!EiV0|=XccK<>$hEUo!3N7LB~AEV<MayWQ?`Bx>LD zDCwe0$`jA8NqlWLro4TJy^FO)6A$Q6cDx=6tx_T;p=Yy2>fb9ebzJR;Y4B>)Rowma zMsbl%(5gq(NzSV4IbUlIT#h*uYK5i<0EKe8Uw1IaUUWaPX{cmg;k2Tpqrx2e^a5uq z`Nr9*{{HnZN7e1N$&d?w)abs_Fus!dB&(=e^w2kg96x)$wTP#Io1C(!S-Nw3RPRr- z{OoV@wqJ4|5O7CwM?!R-eEV3w-|J4al!x}26oJw%srIqekT^A|%*caF8t$$m8C?-U z!3T>GHzHl}ld4H{AhQE4S4YH<x}rg)JmMi&tblDo-}IW-skH3;yZZa<GHfpoSnL+J z(SGprvRvMcySwDuq6YPe5^}S~BSP41GY;hAI>VVFT2$A8ljl1rdg+b1hoa{tdUwp) zGbz{|(t;{Yi(T%1eE$U%gA%m{29S6BOm4S*+q1NTC(;h4dGt)iDZ0tt{M!B65*Li% zpAoG^s(s|l(Dj{<(mR4pOgYKA<lRf>6^2!+znaz`DGdHDm|ln*=iF4ARU{o*Kp|{p zgm--g#L!ftOSNh9Bhj6N)uNG?7}lV@(Rz;Z_><+OpMpnj_A6UyvuhA;gtJ+@Ug=zK zS#P1M`C5t8QDj1f&l;-jjtzVL#xvrfqv@Q<;1TzZ!e-%~?<YbVD`L9MtqLwhdfrIR z7Wm3vT5i#QCu=a+^83{FHf_EoohKOL|5k;~*Z#LutN?Agh-%suF$%sGE0pvL+t|t~ zz46^ez^#TG@8PHMB(|LT;(5A(AN#{gz}Pu9P(eqxzr7dz$d>UjxU>W1Ccw8)>yo9R z)QFZ{G-z5i9oN#e%spF6gZA?SzwD#u2%f5=C|Jvj%%OGGMc?Xy+puqxsXl>7WT?jP zmj3^@1?5Tf@KGh~B(|ro92?{Q`uXVd<z(RCPJ(FW5R9Kk3a*1(VM9L_6jbAMG=*po zAr3`i4kd#$Uw0Z@qZB(qIoCY=Yz~Ev78@w)Qx(YZqPs+DL)nuDX1a)-ZvmceDDebv zs}ho6d^}Qt0R<$oJ)RI0KO0cAR6`lO=2+ov%@Tp|CV>(l_!NvKbs2mH0kZ&x^s^x5 zuWQSc5*vLp-t>8*540*zs81BQbkTqJ8z?|Bha&#Lpg$BQEyFb&C@QlM0_x-|Gxvj_ zDqG{~XR86$E)#LZVz>HT=Fe@SSr2rlECZi0Czul8;>rL*ezrES@hhM%j;Go?PlGRj zfa?+y78%wlReh!R>RGd0y6C<=&IQ>H{&Z3jzXp8!T%AokD4I;z#!b}WJ;8d#toC4$ zQ28g(fq~Mo(QM^SglCR`mY06u$D*gDpCxdDyGZ9lsarrpF33<CCm{`Qk1AUgU~Bp? zvqP0Ob&fpBo+b5|VSy>jqn1%*0r<<%M%D3SR3bc8!~WmII>hW>_n6&sxC(G&7x-2( zW$HRuvmLIny-ICZy>ri}WT|wNkmFx09ZDodP?tdOiwphMJK-8vcybqdehv7hA3#&g zGlVCy8#{6vbN1Hg#A2Oi-`k!Rg?NI01L!|K1vrYPdUb+A`4~3{56!jBHrPWaCSndK z!ZXyY8xRrB!E2!X_xNFl1p05v^OL1tFqDo@M$9`ITA$rq2qQbF7A@XCmw;*USzSrm zMEE5Sy6h@+m0nIJZDXn*em7D^+a9}n|6DO;sk>+f_(u!#jtCjvtH}erwm%8|+qyYv zKxpo`MhDIg-Cz2~S(bL&X=bw|yr(ZQvlu-ie7d}FAkS_X&y_uZB*HEt1;N2l&-4_( zeXqWx(xz*3?>cmWP25j<)d6A4B{Nf;sWE7qxuaDYstey^l4inuE`D0bYO`Byf}dG^ zkjamAO<7HLK@Bn<x@D-vc<S5T+EFxdAFe8%Xl7M-JS{}gQLd%khc#6%^DItKzgOn% zLf{Jr-eW!=zKWhI2@Ww+x{=-}8=otBaDfK-A*g}Zcu|kO(`|d-O185V_@0rz`QkxX zSn4S#OtmUk*5s#Kw9RGsqugBAoNWfyOa9pz8C|qf+2rzloyFV`%YzGC+`O;u#&BnL zUQu(CQmO6Lf9vs0K3H*AtV2)HLGO>HvAy3$%a4(ddAzTmD(A_$-**2{{BS|`jHT@$ z&qI5>nX1PXvoG)Ym3htHC%;Hozjb=-^3oH7vQ~950yqd16Xi%+KhkU|xnLZiuFw1} z8+K93lUaT34ZY>wCop#>Ir3{>ui59@smc$cE}pW`yqJAFU?q#g&F!XwlX|A0uJ{e< zW7`u?9M?URz?J+#WZF@pmV{I!>Wu_*pDeHF*c(2gS|Frn6TWqjP4r+_@`cO0$Nn$c z-aD+RZv7U;4-pj<L3)+mL6jySQ4kQ2-fIM;3y~(Bs5I%)l`2B$0qGs2OP3l6QW6BE zC)5B*Jj-+L{XX3L?B9N#`#kqQRtU_p=9+7c@s4-A@eiKqeEvN6%rN@M6_<;KJrc^- zFGzv-p1$P;=<pn&%hv-pWCsX?i=X|VOn9eWTSqHfnAwzW?9|777u7O#*}-x){>ukE z87Za4aq3g<x06$*o>UR()zR5hooQf-Rw$Oc$2>jMjkRtj6a~NUt?qMaeCy?2#Rs(% zr9}s?YHrqOM|lU`_e@X}8BV@5WH>`-b9|ZV@<v9AoNgnqgN9`*D6=w$k0xin-4f-w z<o5mDjfS*&1r#HVrc-q-R9?-P$c_sH<H8kTFh6qTR)kn>W&$o_&gpQ>i#Io8SJK+0 z?@|Jg&eg*5D$DUg9RgL^<A{~V@hY5yXFJG~wI@GhHe7VEFn%8ADB-riEf$-Ht*uVX z3bp3(+v$<>Gqp)|R=u{86b-uwD~v;4KGHYui1J*(S2g_n=7C;Jm<7?T`iF32q+YaL zH~el&sbGt&yfcx4m~Pw8R@pp0PKpV$+b-r+ngg~9=Fv!h%$PN<&9@v!PxM=A!z|Rn zkP8F8Fp<`;>byOW%cSlj4DZfgd((AC8YRtcyVJRg+vtt~ut~=JSWm)hX=XxU3F<dU zD?~d?dhf9=Ji%lGvm$8_<-Y7>4(1cs{;QLf^X5E%w6~SrCuDg5LtJfUHv5U`d92y` z8>!YxYTLZ7hv$UMOdS~q6OpyGkcbZIAeF-2avb!N-26e-(p&e<{SsL8y-Vb-LT{ek zXJ!A;?2L;-E3#|X2~}LF-C?H9FWsExb%pb~di8paWeD{TJR!>Bj+5=!WkfPya$Ygo zOd-@l23mtc8K&0e;${`*E|<CtLbb1FfvK^9C~#ND>m1OOq9Bgrld<)AgiTd_9VUxN zbKe;PD_1FS%vrdRxG*46{gB7u(rIe=HC1fw#PdZ8MX?}joH`10y(p}1gm0|3U9h%3 zR1a$eZ-1}<pg!Wsi{SXcW1ANu>DT31bZTzD%F7Hmh7b8g_J%NEQlhA$Th(m}6*9&S zA2=6V^YGSP8P2sk_j&j<HGS~(SYP6e^DZv(USv;mWhfs)WYQFvZl5;Z3SG;!Rlngk zm(Zg>V-sJkwO$###KbynEBmA8Td)ACOxsJZE;;|gW_{b*e8E9Y^J;55-`su~ZeTyV zcPj3w%2O@XdD#V14bN3?%Y5xytM8|d{eO@%d3kva-qzPo@^Vq6!5Nj}A`P)dN8QC1 zx-)hSG5W0xB<en_WUaY3H@oG??H5RRl>`Sroa=K6p~4YRxs0wMH^zzb&J$m)?;pC6 zKAckEY`@Dj&o)e*Aha$aVQ8=Rra0+7t-t+cGT)5gwm!J~QGg|t7wscsb+@VJe3DD& z<Ii=H|5UkOG>>#a!VV*0mi=CVuv*s=v$;lpH|7U4s=W7y?cYRLeX@VZ9cpD5bRTP+ zloY#)ut2R1&WYEl&wXgmrrz`Kk5!aeu5Ps^l__0EO%z@J0uSvTy?JQ)rl6oy*CjJ@ zdnvbhbD0Hc92Am=0c#^R_hYiXdakRLJ2R*D<-3(RpSWcPXRNOzx#mOY_GQ#*2E22f z$Qp*O(?kj73HVn=FIIJQbubOk7hz6zOfjP$cpO`EewZ~)+qFCD^7yB%E3L#pf(oM2 zg2z_rECV$C8oEl*X&8B2rVcZbvOOMRu%#ivG!P@-Pty|s9eO~-4DY#`-)(Ook8qrZ zC+jz*J>052%6_ohtXkb%{$$&>s`(Dd6X7!Ui&E3dy;O`PjdG^ZIV(uQFtd66{-N>s z{6>vine=FROP>x$W1xJO1CCO~@@{~jZAqhzvq5NVFboV4@_1h|U6>t^nzgR<Y_)j3 z!@q>xAJcMZh%>?b{OZ!c%nM(re4MPpHXoPqwa3QaCeiju%u#YFA%`<F%0cvWq~|!y z5XuU5yadSgJjc4y+3zNI&pc0ed5D>hoSlW+iiyG_cP<)5%RIg+>-gq<+><2feN`+& z<Tz3W@wA)A<W_TL!62;W^)}<)r>I%Iu?M!Kk28YXYx3t8h6<7E^%LJZpMBJVu&$4> zmPc=}2;8AG8h@4Z(C6+&m^e+V%}M`^qj`SnTx;?DeUHEi*D|ZRZO{IGDz=gzl6$gt z>wUFWhDrHa_nV_(LM0Q1se;l~bb@sP@_{OJ5Fc@h4nmBAiZdp#2YRWM6B{si0m~!v z(b_ejKg@V_#ckVrz`KLTpMid<z_?~)Mex`z@#tJ_tsCz6)D-}zcSB@}{mqA=&e%-7 zFAg!_ns@sxfV>hs;B`KZqBxCjFF!)Xo2I8<@MDyTtHf1?BQHJN047xJiv{2V(F?wU zT#Io&ESz%p8S;K{zri=-i6cdg6aRCMcrS1!6k|>`2bc-<b5J_{BB_CNLa5FC@@li6 zUvV|XDkg*^J7Z<*Gi0}H5@kfYQ=7!L<En3!zH_`KV$CNW<=3q^l5ZgE?&-X~)<+L8 zq9V4n0dAA2PZQ>Y7_c$@+QQ4Nilj2JRkG$;qXjUfY_W%ZVywgo+O?v=<;%`Gne$;z z0K)}42Hs{DMWFk%kW(PSg81_cXR&YMPnddqi;65kLcQtqejn991LQ|e?c$lUpaK4j z2n--*`PGOo?SR8H^q^#@IDz4ZhEvEW!%@y-H-c=R>_J699i9OQJvagofc!X`r0#!g zUH1a{;a`5w*qp4GVp)&vrMJh15d3V;9cPddT>LuV9JEZB{v9sznEF>lVT5&_dh6WR z?T7^Vbc~G7e{*E~0rxskOa=O&2|2;(5H9LoK>UFt{uN6xa{O_k-UrXR_VGcYGO|Fk zU*|AC`b2YODi*J}s7)f9G8#^WpaTZe9h;eclfOvxvb8_<0A@2f<3zQhBp^KU1ArS~ z&R--j?&LpE5yzPUm0t$vZ#iz1;dBSu2@(r+CTx$1%lmr80`vao*?#71<mcZG_kfZq zcT=TqFN~Yu9NaX&=iPZw@v4c64(LVz<OARm4VX**Psi*SI&AbW5@*T6#UaAXCz&6t zKNO&W`+u$vgWnO^f8=7Mq<<g)<#S6_sUu@Z9cZ%q;ut7!AAa%)i}+S|0_2C^17_k3 z6#jDp1W5BNu*;NdZVa=BAxD00$Nh}`918>hcb&ma(~#c*r@!+-?)}Sc0)0&GzPI7( z?QoOoKt+0ce)nMDU<5J)jRt)u^#GD%uKbp(odLxE2CiNP8T+U*+kBio%$<kqc{TVl z_1)P3=!-KCOZk5mh&i`%6kAC&X}%?SvrUrrnLJlR2d4z6?N1x<bAUdK`EMj|%#Y_} zPRA4Gh;BqWPY!A`rz){jFIqScscY?HH~u*u-3#+{aRB0}Pya=th~PLH{6!MSfys1+ z?rnJh5u-}nmkW+D0LZ(wcrfBB)=;ru(yAwZSQlHu`cyhRle1d!U2zBM;#9|v?ZrI^ z<~^m$ngSJ|<n{s{c0GJ)(V5mAM*Z+NA`rU6aT4DO&%Gg8&O*PCDK3ZLv}!w!4}lm_ zy9plHsKVxeS;%!wI9&m>VN7T7ywAAxqnw*64U>CJFShMuKiyf5btr>&QI|l+<~vpw zQTG`C!SbnR$1PfzE)xzTPPZrW#9qm?8Mp(o)FoF@v4eKG0qpZwT|Z&B<F_gf3C5oS z3OivUU=i|%g}lfDXAOeWjc-O!U%hYInFL8?{Y(dD0Cbicps;dVpd%e!FC@x75^`F7 z3WCIOgeBksCbSLDu(M$!-jytLJ48<^NFV79uD^U|SY>$QuTPFl-0&x7`mUYO#c&ue zR?rkyt`<lpnnbRcdOJFc)p~f2%DRw&`tldthe_*_d3Jz}xwyCq^jak!%|K*f;UHS+ z{rg8IN&j(ZQt8ztfPRXD2+Z>5><%y><NCr2YOe%#_`47yb;qnGF-EON94{>m!Z%k4 zK`BD|iGe?si+aj;?(}!Xfe^&*x?upgotZhq%+BVpO-IdQ60gR;EILqXXIh9vU^@0M z>FksNqO_~sL~6*_Q({a}PbFT8846go{l4E8hl;;QKCEGd0bPY^F7Q3%@|hI{><Dq1 z#E`9DBtSUn^4(OOV;sONfr$?kJHi2GM*|uRCYlCbh(lG*DmWXX#pA%&29K4=+8Is% zf>LeO7(-Dkgp`h-wLwZieBKUVv4%=_Wn0zk^HrOThV^UHmhGwqI=LtL(uvpI#EHQb zpdDcEX8sTD1T5mYq1EXG`h?eD+|#GfV;{@@=pgY^F6oNZ<>iE)aJQH@xtI43+3spL z3dj7pmdmWxuH$kbTY-Z5vfs!k#FRbyA3GfyfqpFiA{l@lUppZ(5MK%s4xq<2Gte&4 zQx533HxB4aM7|E7p4$S*l#u?#eJe#?D5@CP{Eq`IegAp5XwNLA|1|wn`WR>g^a-pw z#UjWJ7ri|49iXAeHt$N+0IzpU9ALb*Z?4D*MO6W>?3HOhLUvEcwb<EplFt*_>o!az z-a82z{~ssG6fn{m+f4dmK`2^=^gLmiV+VK5T^J)pSknFIIJ?(O$yAHSQrk?{Fuhob zU1l09yuJ3HMsv03|F6Xqz#oQ}IOVD+*6Qe|dcD1%ha%E_73fp*s9;|EzpN(g&|PWp z<%d3+$Mg@l9lm;M>mb-uTbArfg4D6~37CyebKc(Vn#%S16Zd4tRTYk0FNGLdy`98q z2CwS4VWrsbZ|>wxW|;W=pC|I&^vF$GK@Hd=DS<x0`fsHLNz?W77CdR21mKnaN(N7k zq3WiZ{jiK4>yESD0d8Cv;8vdGJ5?7$TJ#NGmsO4IcR$3Ad0m?mnt#X!7U4hFzC=0+ za%IBb&BJv7-moEDE|}gAL+F;^tH36b{@~QA{=K-dRUsN}^%2>XqYN2cv$70R1Ii?r z;2=v-s-PP<yZ3nMi8^B|{;rcN74O`F%dAvmMYr-y)6@&PxUyeUNYknDlX&mWRc?y2 z1nE~bVcQC<1v9%(!l!1GtR*+zUaZN^i@ptEYD{>#L2E+eUo{*(8Lk)va#+LkUjZ}p zdGFnsN)hZFxg+eQ7+^#b3!$%=a5<b<TWcoXJON?TNTU_>$8e_-Lu&?|1~El<O3>Nn zG1SJiB{t}6Uj}|vG4Zs^Gtn**i5u;TxDiMtE-Yju!!fd4O4L<%QVW3;<Aqc!Rr8o8 zCP8Zk6#L9>A3nD=N7}-7FWgzI(dnLTm%#BIipQInC&UJ^p>*gr%&qhC%v=~U_}->p zTd;0L$Q;g4f0G)NJcY%7C(9bFzT2IeB$*J=+Sq{c?Qt{dgkE1kRBGqjIdX&n$po{N zQcQdkJG@i1hzM!*@Tsc0sj3bn>3e4Vf#=Nfn8Kq?D{Ssz!(@meuI11HlODM;9%Q%t zvS6VX&8E|><C<qSC)+;%EKxj@J-gV7X76}1vnQ~ar@`roP&Bl-W;3mhl`@Trj(_Ol zz(})t?be9!sc>&^?Zkxcym%mZE=Uf|&fbqbU)A`ih$`KFqHD5e1X1?71kAvsAI^xr znJT0WYF&+IzwHvvz@TIVRw(N=IFi?SnR_k>iaAA-_b#%mE3)ID;xC9i8`ABxxNH<S zsv2jfk69^QOKWJLmwS3Rb6s?$VU~U+Md8Wo!Y1l&c9~oWTp+facsbMqjtqK&i$sZY z6h+rjMf%E_rR(8>VLzMO%WT+2^LSKhC!agUuZS_LM9bPlScFG^Q>~W#pdKK8E@X(K zR`KPjOG8iP6=x0#h2RRDZ?~g)E-I&_$l_j=OUK-#sbU$dV7&~8!@;;?3X_ngdRuwM zH^Lz9*oLjLq97yO4rbA8M)9IwW><O$YtA;9-OR=OJREAvmDIJqz!S^$&B_+3zRfI< z=WDpfOF9tm9ND`h=pb1=EXohwFw7Q$SgSXS_DX4qY5QDGt_hIy%G?kJq(1ksM>GyM zyH{x?-tj6Zc_TFnN)fRivaDpiYzo)MON@#eT^R`u6Gi$3&f2Be5)c4CNN_QSHaHk| zLk-vQ!EdJ@M77k62y!gxM$e6x`~*L4Zpk^Et`&|E;Cr>czJT0D$m}wRQ5FvX!oxWZ zQ$jw}E)IAtb}v%w2MSy9_h#5{BExeM(6<BmqTIP324Veu`Er_ryK5sij|^_BanHS` z%Jkx`)-*Z%uEQQOFX0#Qi)0D<3C^Nai>bDH(81`VNe;xISpow${NGbG)27X%n`YeF zfw5h`_={vRDqDnabl8mr4ZPZGp!n<SJDs_;mED=D<9Jup-P=7LcoQHXzf%D}C>uH* z3M|_QetLUe6XJJdQlpWq5P@9M9$<X==AI2|FJX&P>XE9Dfe%k|x0I@WVI>7PE#uW< z&b3&sX_#NvQOS>SOLF6O28r&+B?_9c`I=W$3}dnxJx8yFIS<kb^~(JsF@;_1PAga! zszoT+ORY9j^#Er>`zyD*8-U+!&ccx!L^8}Fyl{h^*YD{ktimnJt{unb^Ygaj+KDXS zhQSt5R0b2f+2U}iD3-;5@PWuUYlgpx^Ie9}Te+k+0Pqm=ZtbvojoQqLCz|4+l<Cvu z#>k-Z_6K}6uVJLlx@t3^+S)}*klW&{PJc(8g88TEAeN=Y$Q-^*RC{jw`o+~YH!h=K zheM<dJD-X;TY;zA+x#TWH{0$X=odx(_PUV3PTekNjWb!=39s{S6~t1hOxt1)(+l4& zEVw-~)w!kVkRSBMx>b7eQo$~g-$-e2S5WZh_gi6{1`Nz~f@rR}q~uVIz;=hVJ(<$+ zE#W>Bix8KOv+)eCJ)7T(h+c9SF-)%y?fud<?k9&SUyjyf($`;2<H|~1@4D4%aMHR| zVnjfQVvd01%XTJnT)|og1zrzJu2I)g(@5Thon`E@yic3>P5J3w=In$GS9Oz)h#K>j z-pT;CXLIBh10d!FT|dZW+z64JBC>&l^sJ;2Ju~dQ6FwB`3Nk(})!mmZ=hYczH@C&N z7}Y8Ao;-Z|#8;Tp{D>nV1Oz6VoyD7C=u?AHLl*PQi(S4*hq@xs6l=CO-)>GyF@5P8 zBFpekkACvaPUMSP1Lv^+gkOF)`+4k9S1>86GC`z{gVe?RLIaExQaKy*u&^PXrEp54 z=UgLn-+999&coPu!*1M{LMktXpKM>2vWrUc)Y9rtlo2pEOkQo1{_rg+#ZcdU!-5Zn zWp&I{zW%z;@$D#GA(ja)bKs;3_me9l*N&H=V;<D^6PWVB=w)Bh>+Y!V<T-%pOSLxi zD1vYxRBm*L%y{h>r714iqP@LgqWr1%M{$Sxj#J_CPJYU2$=*>1UUZ5gdStgXimG!g zG(;XJisk5$sS46>o>I_)IU%LX&~9qh<HlI`+UIr6bry_aH@;m`7@|*ko11*4IrVL% zcpM7!YLQaG4I9{%%jSJo_2^RwAGWRkwb~0&$xIW|r?qggNsYSkd3X*rvw!^%lqXU6 zB9beyOsJ8n>W~U~RUG*wNUI$e`~f%9uNI|1#vfHKb<ulg%lUhqTvbD$Z)5tC@c~D9 zn&L#Xpi%rIj|3Cp5zgEd&&n75hKDX$21a&~CLX$aE1rc2k?AbvTG(*G(vf0%j|dtb zWEB+6Sgx=JeKMXSohDQ$R-XAuJK{n^O-WP<Yr8v+d7pp8I@7dKqb|fZGTUAU9n`My zML`lt%)~<ORZoa1IF`T3@6;cAj-?oC*;4BAP4k|2k8!<|qFU8j;zTEtcJbt-Axy!( zWI<{n-v?6GO5~l~-(glpfv$AgIEx_88E6M?ltqf27d%W$<MuvoNRqj!M(L%1kAQih z#@K_NLayUAaNKB$#;2n#=h<n-Wrn<p#!5|1d7`oTO5>6rJBvpR<3=IOy0;W2e^%dL z2K^P%yC4E+!C#{9Qm*H4A-v~xEU=ah63RuU^J)}7ztn!TQezP!Z>|qac`{EO{ry<w z+6Tti3YcuEp@&a!LBac}d@a6p!{}z0q}A_w$tjaWu1L{|YW!}|$$Yn8hNQ$XkF%<@ zk)fbwE|Io$5GFg>Yf}VrW`88_Q&qclahZ+j{!n_Vzsy!5MqCAlJ-s>m6<29GB?+Pi zlvX?5s#vYaNPR0cz1I5Lstn;fTU$X*_Rcixj5b$<1^Ar4?~bRKe5VS<-#+CP%e_&L zo5Ru}M(>DYnme_h0f%?+M-UsV2|M;Fj-r#D0_Riw)la#LD1}w6lx`?>xjD$!Zn_Ci z)~NeSCFKKe_3-ZJxbQTdZ?GD0<Vj9;Fs9734dWOM$3h+bMNHJ)gdUb~NyMdlX2T;4 z29v0CwL&=2?xfUOsM4vP=Hxb0DJTAmeIeiNorJAq?0sD&;SLEu6>4HUDR)CpV9ah^ z`Wji;D#ob{{6g1CQ>I~zGHkp8{NxwSsZ9>RI3Q?jFMcA*ajgUM^(%nl)`6VRfBmQx z&=H&gVjz_C#4nN`$YtU&7+X0Q{15)y4><z>1E^wKB~E#2jR8stH;-jfbeLPgi++5% ze}Eu+44~D2gHxV}@^%R$E!ks-Z%ITb)BGgk7|i4kJfC21Knwxl0a_%HsuBhLNt3$> zd?Af30nfEqbwps$i2~zXB!7_*t!Ih=M^*qZ6!y(6NA~zac!0p><xN^U?ncBFf5bl^ zjZP{jTRiN$91I`Bb#u3?JIT`@z*PSMY6f!rE7Vl`*AJ`#apiyJZN@iCp<_V&4Il=0 zIS=sSgue_<0oCbl_hhRw0G4HcPDZs$;U5@veXr~~{Y!0F9_p6x!?Nh#Mu(8{s6hHf z(2v8p6M3?1%<oCZvhKYK7Rvo+V6=fkxqDcEB<jGw4u(<y=cN?lNeBMpCKN?aNa*<4 z9HappW%P=G)(?v&0la+Uit4wbeoz!|>;5OuWpB)-&p>Uyt!KcSIm`vTcLX_Zz!{)0 zu)}Pj_3M^h`WI+!>U%2fdi2+^4;JC^&|`5RcZuT<>LT-BsSCgZ;7=~2lIKr6p700n z^nVB98_<8l#kPLe!GzRy+I91WX#8EQJo;)?u@*`+P@`&cCxq?mY}X!m&E&bj#G~e( z;n#3a)<l*hT0j~M`m^y84l)-JUy8;%Kgyutg1RXmmIdo`i;kJ~M+9}tm}@^yEeq66 zwrMd>-*u77-_F>MH5YdLg9rir!?{(2ewL|CI6e;)BW#9p8oSbiu77pbt9Ykyt7fh^ zZkG0O>eBMR&>JMPXB;@;e=u+^bu&>OX!ZCSM@eVaPi|(OjE~(msbD1kJ9X#pyYriK zQUzEj(DPp;nb2^+21Ez{ssPZ;gaVul{HZY=?7KB}%&ENY74FXqPEM+-RE$4Z@pb%v zaBMaIB=@@f*$0+yemw${3F(KnzQ=e+-$!<!c}YN*4<rx$#~$zlB?yK234ytUORmKg z0i#_ymw*V5l1d_5(EE?yvvRyfWshC@|7`!Pbx-NySt4RmOsWM;{Rt_W<;jyAJd;9_ zPwp$r|MC4*_h>+LdxrH(I7_?As{wkpx=KP&5iv}-vBI5$!g?)P40g9iByE$|M+sQM z_daj*0(#>=I8G@yps=O*@7j?C#an;>`2MfPj%(1*4$H)56K6{>P{Z=J2Oz)~_$&Lj zH;iK#pq&5T(k>Tc@IOE6o;xGJ_f9<{&Hr7?MeiO<J2{ZH8k2CuaGddTBMSq<2U$WJ zJBATz_sHyV-NbuE#OBHaxW*7R68}<%-~-;c$NIZHh9G$$pz;6O^E8eD)WJWM=l;qE zLRJat(2Zm$x4xk-6uTx)@PvGKA`Sg5;X7l{vsBjB0DRN$7s)rkGvs$=LvlKRcl>{9 zz8N0?q}CNnfH$@?0{*O_3%q+i0jP!PGhkwY5<mV+4G{0hkxc&f^3K5a<DvHf(GgH7 zMPu&l1&MIrr^O9-=sbACRH|(Wa?k+Ut~_{uH5xGap{!(rer6%giSJ4sFyOB>90mbr zf`L=_S=_1VL=b@mwVEnjBX9Y0(YZe9ATrVU`osPw*U1yNKiH+s+xFfQvQo7Ar{W5@ zyaNN#`Q+MhjyN2`gWD>zuu=vk92~^xm^4Q%W$H}gKj*)rzJ+aS$~cj}>VK_I>4h)o zU6#oqQxGzsjbRMh^#cuk=q?Z>j8asD-PxV4NWJLaTrsIRqJNlVJZ-){(|j6=h5&^S z&<Ww-F1hdhn+aZ&dluCf;+J~R58^Ft4*jEJgBs#>QrvttEWy3G01-r^0Iv8+g#s~< zyNNAqPwKYK_ypE?J{7B@_F5?@Yc}?Y=Y1iQ$+E?g^l;9VU!9{L60zLtn{#<eN_ZZm zSM~6FQ^T}(Or`;=`|H7-)xJVr`L|TJZ6Knv_wTpv*EdKbn0t{H-?(c95+6}_N;Ep( zg2#vXl4o=akNP2AI%*dP4rbA2C1rzr8W=8YPqfF6PSn)p%z$3EDlCg%58@u!`^GBR zeAAmYTW-ouV9=E=EYvs4{hMKOb-L)Wf3mp()g|2Zo}BYjl3Vl~*T1?Vn6DNUe^p)< zbyQX_=%}Oq#wMfBA*W60EIzv+1CeSU_i9=MIYG4uiBfw2i5f-Zt0ELAoP+s+yRA7f zqP-ojVa+qBCRaCQ^{I0cKPKI2^FKFSa|y@_x1P8EMWPyK#!Z&y?iqd33W;YmNa)rG zH>agZs(BW>EFP1yRvHJ+7_k-=7UoIdzOszCR&hI>2K`aiC3Us53s%x7*i~mf?Q$O` zW}H=8+^KQPutYCkH6u=7^m-cxbeMpZ0RXsro5olti0VK~=|}}rk&mLol`O|}+o4X& z0^1B-jE_n)tpjJ%%*4!XR=XN0sQq$}s^t&s30eD8)cCuY${s4@b-+6g*M?;PV^u10 z(dw<B())y5)P}l9<$Y!!So8aax_D?+dWLQ<@*L-7`y}c9Nzn3a#|9cgV4SvX^87`@ zaGSNgf*npN$xu^RGGu05;O0<p!jG@gxXbLgFT)Ug8;1}Ws|m`y^0J6I=xe!*f{US1 zaBRMuLe^G`s!Yn%<Gc&UhIwL!i|u$VT$IdaC?+0wy*J~AKH&9m_nPgTy}(v}tGx=~ zA}08E$B4V9q6fD)8(NYWlih}6jd|i`xPEkl>^rXdB@i#CW5!T>eybFfm+=BPw<2d6 zKlkoO9Su$G(^8pa@z;GsMwm>|CeiD3f8E{A9Jsb^HSJW9RoOdW|5jatk@ui}zr4tv z79qS+w29Pr^<Ox0I~LFC559?t`TW!7C+0v-w$ZE4s085=TcXWA`Yet?LpQ95HeW71 zb$NJ-+aw9DutJD|I*3Q7%LHUscA;FC-Ht*Sv5NU07FjeCYVUgv_<Hz|rC{g2Y1sF4 zepkJ9dyWP){Ze}at=2m>%Z20s-feXuDMt+fqOr~Wp+Rn_7UMKgbEE)xt3GhfSu^aF z`tlyn+-lznuY7@-n6C>9L9yGYDpPY>B(JHyF)F{Yp)pp$GoSKSbq?dTXZM#7Un<$z z0!kTMDYDtTecYD=T`#QtOl@bot}YCpkp;rIG8cc~@M0XdP_yOjsTxLf0(KmdY*Mr< znuHul)Ywkxn^?|Eliq9M4kaZm%+OeiWwc*%A5s#Ew5F?>fV6^8LvbMErUv3dLpJBB zcgaoDVGl^SO@tHAjbk05hrVhxp@d2W`Me+{40-qsoEN4m__=Vl(sFM`TWW1*VN2cQ zev_T6qc>Dq^IbvG=w}66bvqGOXi4YJmN-Q6^kQupMbqQDS9H-VPEUkcJ&Hf6=zY>9 zA-PIYn#Sy&4FmHP!M-ZHd9jt$$D<c+#D8SC#Ta_-P56LYn+%Od##Y&KgpS-sGC9Du zSz9}`^p{)bLaZGCr%#WS=MAgJCh-ZJ!_VkE*KfyBHX%;nf&+%pMmI4qa(Se}cCCGM z`7+%lqs-bnc4Su}hXdHicpqrEB8AS2=FM1SL&AQ`TOSq~Q76vEhUUqnrFk`$Fs+O{ zq*vNv)2*Kc=2-Eb;M=J5PB!^Yb_twanV-(7aG$wDUJ=#Rb?GDHkD_%arkR;h4dovO zour%-vzOImZqF5j2X(IQAk|!fCm4JQxpr6r`^tDFKKJn9ur%?$YUGeo<9(*M%je=? z=NNnMqqn#pV)u=WiBc1yQV(l4Q2vfrwn`r+j;##P6AB(@Cw*?bk??kAr!R!DGBS-B z#ynmms0yWYnEHSqD8BMoiG5n@qV3tyX19hR%45Xj`93!W$_{3Il+}R;+Zu8e8)m|_ z%biEFg^U2@DNot7ev!V|C5>84C54EUw>6GiDlCV3;`>aHx=nD|M%NG1skE8>jto@F zHxUi@if3=q;wjZ`_l0ql7zqi#_?WJv^ZKMdyX@|09FY7#?HbVDP@q;Y;MClkL6IK! z<T5oqeW*!Yj<jVN<YlUv9g8&n5@xcCgYtmM2Skdr`r3;1_w13fc*kjz^<&VV`EEa{ zXoCl`2_(?>5;OY3XCs$ZI`z_&d(Vf!KFiO>4{ah;$Z>Q@7w=QNc;pfgiwNdml{J1< zMyJssl9m=OH8JB`Cfv8xexl}3;hf~R*BvCGb}CO{z+fD%60r9@Uu}b-<Tcm`9&uQ= zHr+Xy7gd~hY1%bgpf6i?K38F5@vk7~ASuW-zm^_zj_!Gxo_er7^Fp>4YlrQtKv+Cq z^Xb#)WkPk|ynGC4jz4{}`YIK|O`J}!<L}?0SBK4MU8w<FT%|GJ9`Ph{pIWvUWeG(- zzDYr*t0T)Md~ydX6WV%b`MPJ2T2XL;)td67RD~ZZ^siKs2k#YJ?AyPx`}l`q5hxdo z(FNnU#JjcvQL1n(<j}qad!GIFm)f+J#_`HZ$Eoz59NjdtF`+#|yW6LVE<0Zp9YM+n zBOFl-%g>E2)(dCU$P9(j>Q89RdI@UPv4}_Q@E2|p%3if6<<QLx7q5KDH=rOpE%hqV zk{OaqPKsR@s$+HT(#a7*>QL)x4N6X{hbaF}+;BXoI$Kff?{cC4t)Lii>cdL_r@lF8 z8Q@^o!o1vi_KHO4Yz5Df^|M#+uQLB{m&V`qx-7|j*N(_1UeNz`S>y)dRd3o5gdotK zlzI8a*;<?D&f57&^&|c$;YH%~+hK3m4=A1L0Yw08Fi@kb%&`xElYdw6x<}^CP6oLD zSK`QtBbJ0S7x&nHyD2iUO95>w0mZ@reZQz>osZ(5*Ccd#DDW}W{e39mT$y660uYSm z{Hd4#pcyHW=fC{{P5$)r+m-?!lg&dBwYflE3;PSXudSN-7Cj#|y_LDbZB`o2htTfe zH1@@h@t~u%j;<!nzrB5ak^)EGuu32ro!bqhIAr35xqvj{sXB`RDHcZM?%VEhF)tJM z6=v@KT{+<WRbL{ts4p?tgh&L6ZUe|G4LEQsmH`?l6TEB1hZhpwaHYxaLp$wh``uMa z(_;N^>{;<bV|d;G20W4Dbbk?Lngbx_H$zZ_RCzPW29T`{B+&i<Sc=6$fT<Xpd7s=f z!P^%XWy~w|J-ZPUFZ@@t4k?g4k_9APOaaE4BS4QefozgoBS7_E_S;{Ow*t^jlmh=? z8VHte6u-Y3s1lC9wX0Q*=1n1s4Q=5Gz71sMrTzr(;h;N{&~QWGkRAX4AE0c4Qq#Y8 z0baU@#6=9RAs@9r=?!%gGI@zewj6Q6$rF`14hK45B)9+P8MqS+dNAc3^Z7s+r=)yo zo|~MU^rtYGNYh3^gi;YsAefS~9zWja5CA1)k_R0FRK*=yMA}&e^?b{o8O%J*uAm{i z1!dArc@y5V_I|+F|Jwwpo$2As_YnSZn>gE~%?MpmD$(YIuG+F!z_R^6Ht{dy#?CAa zz{u;LWpY`7)EY>xm^#n|R)c`D%I!2@HM|Lq0wgvx2<VS#=nlZ(#CZpB;9qWaY`iY> zJ_isdf8LDgi366qe~oz0>x0GYd8)%jJMXZ@3p@O2lS2X|sGMDc0)Ji#zxnV&rmoCC zNb8oB(<hC@!hW8u&e6c-89+JmXKRxfHM}3NJghq2!<$LIL(g{8dfW~|DVgLd`}z^d z?<L{0mTUe~_)H=O1L%)+_~+GkV86&TZmY-A<sOD4^S=|roIVu(H0m#VP`L<>;5gU6 zi8!V7b3AmKaIejlJE6MTnZM335!}3?LmY1zXv-WnMH-p8^Jev?k_<^o2-#0?<2r%- z=`Nf~K9GRXtjG~`2YcOuP0`J)vJ$@YlzyG1@hLj6zdnhN(~Qr;i+c1P4UJJ%EfF0u zp#`(F^aHCQ+-gV67uHXX^Dy6<d)w*`dWX$}dp^#0vcA#cS-Yef7pr`8z!!4+0<~K? zMpn>K!Qj;pdh7WQIDET^H}EH-c{^uAi|Ts^hliAGdJk)4n6s+EO5D>YC^rALRJo+0 zd@Xfxdy5SD#`@$K=Nv1Jmt2bEn4C6e04`{mSWdlzD5yCW_9f|jnC*qBxm~}`qVg<B zP+nomY1Y{6;+rn&wuGhYL2^w~bz@O-g<}1HiG@=R*O$$u*TJdz535%4c7N111-d%7 z_Vm0Lxf=huT3L~*SM=&+UkAGg@h`k`q}3GP%)w9Zd5sMtL@z8Jb{G?f^p>IND*1s- z^rCfGILF<EF!2yJCsdfu>6qbM(TlHhuN=TtPx}H!Ul#n7)|+3OVb%@Rp0Y-=I7TB` zqMmZrD_^?A`OaKiYQgjw=3)=&Nkyq?>09P2r(!M%3og4W*>X`<JN#m%fOXBXzr|59 z<Um1{LTtnnuWj`fp*g3vUK6Jw#c7<zuwnX0kt@{MkU%gUFETPL8XH7cd1-E#Mv969 z;<Z{}S?*jVPE;2AU0v44W*1hXSz@-7l`!F<*59m#>%Bhst9O0#Pi$*Rp`_=0JgSQB zQ7#TLA$-`cWL^u{>4MC*4<d}PO=;*kWn9jpbKT??y_Mqd=wW>gsY~G<$+hPgjFwo@ zs_Hu0V-V-KRO7ePm&1UmkMRveb<p~8cb}}J<t=M*4KtZo)Mu(ln;cz95JOdz|44F( zQ1!HJYYJ<}a$hYve2yDfT4V!czbgFLUnD)*Ch8dL{35(yEheW41)^L3()nB}s!sS_ z$k+u!i9b`qpidH)GHmKR)w@>#cNTO~G!o?VF1L?nXQmi<YUm_8mOAqlz`c{4t#|Q1 z_(mI*8M4$Q2X~wOa9=)6#q*h#Y8zQeMOErtF$NBaMuJL3cV#Dfm2P|FYtU{KpF$u} z2rQ^O7nz0k!8jzK;vn~Da(grSssQQUMeTPs>`Ce1S^tdP0Wk;Hmlqo^-Rkl@{|FoT zrr4Rh2p@>sIAvPzsP1^J0Kv#~H?Xr{;o;LG*+-GBM#Y-0<v9PX)CIE&5r?#Uy8bR< zSs&hg9Iob86$Xk>h2zvQh(kagAGy`aRvvT@>lo>XB})%)l|YfO?^3|Ei7bJxnNd7x z!hY{1VqPzpfo&-oIh;=i><(862_Zs3wqF1R^77#rVl=Y?R|$6G)&#5tRO_R~FU}3Y zTqX%Q!P)}D$P{e(&5x<(Qm<AmCMguIAFJ)fws0*CKk|(B!;{HcXXMI--6<W>*49lC zIYy%fkBdI1iy$QDVmWr2evy#l?!0>j3!0Q1!X)KTY#42zOHj{p7D|g^dW~}x*>A?W zg2lsy_cUTtO-JNv%I<hQU%W=VLF_hZ7p}+M2TWZ%UWah{#S>RV?WYtu?jGh9{?z}> z?dmvHY0E%8YcXmz?*7PAm6G8`s`M`H@y?P4ULC77-5;SS`>o*xmm+U^S2H-;2Y!o9 zdtuS4{^I1?Nhs2?`(k#!NBzUtXP-AXW9gL2_Bpx;zRL*w^*yDDc1Blg${K8L7o0;! zy4f;^ZX90jV{zdjDOvP9vn=21R(A~v2FjzWK?AL=ZMhLSqJ*r2#aRn<W#oP?pbAG$ zq7m_}D&@-drA}Td7jllSMv=VJ_gj^Jpl6w{ig_f{AL@>>R6EJ;#3?A0l(%OGczGDE z_wA;^OJtn-Bs|QUeQX?E`4-##-z<seOWSlY!PM=)ikI4~DCzd8j>A>8VLMT=`H|rQ z?OHc+8HT9Wg)7>rW=*B54DnEVDjGZ!y_es{vP$G@zUe{>D{i$fcxus<N$n@G?zh_T zOT|~>Udl+=_n#|E#3Xd<T*FmrwFHXO|CBK~F)mX~ulVY0BIxNo_tS!APGdl9I#tnX zAS<rB_{I!q6Hw?Jp5P>~o|@3u$#o9eidInmm`nto1wB{nJ+NGV`osh2a??sCr=p9y z(fsq^$9FK6urC*pkQit!`3oXV2trXf!6>~Kd9?`ZsG|7}FS_g|?Zi1DWpyW6Gj7Q* z70wq;Ja<W*J9{8dO221_)x&dqDgN5Yw53Ri0bD>uO15u2*(+AR)@^&Y{&*Yxy~!{$ zNo^@eeaZN`Y=kXNnM#c=M!(jWgMvxSTx>*0s@OWqQ3FCPN9;5x8Pd*Xu1hU4A^&ug z@f}nfe$)wyPERXw^S3=xq-`93YDp+^9ps5Oi;aKr{*~peiUE?*pI<M2Lmae09^pJn zf*wvN$Tf#C^S_o7zH2@V=D7t=jXUTqN9Zw;s6G4W->!L!l3tJVhI=1w3=3U?_9dKi zI#KKVjCVx`gF6it{c{vB)-ehh(h0t9tX}hk4=1R+@QHivwhC9c@vp~2+qly@HWM+s zNBs+mIzRz4X1q$Fr3Efy3G`yK?zSDPiKmrR@BGMo_3)D{O`qouoM{3*IZrqrJ*=vP zfiBDHhimv{g;1qs8CGg*6tEVocxSy|=4rA$Hms`&Xg6FL=v|=n^DyVwP`ynqLVq=f z`-=J((}2-}W3~YO{EHLboKzK+Wyaw_Rxa$L))VYA>h}@f>mYMps0-2F!Cd}4%`<go zdc0L1TkB8n=Dz);YTuG$nx|`&`YwusW0>cOfJ%UGWUG}Unl^D#r@8(YNwj`<&+}X- z6=B~ZtFAHD#M-BWOi$wd*kyz^cqpI0T@d8yB(!wcbA)lQv^v@>2TOOY4)ypV5E(wH zz0t3iXI7;FiJm=DGX=U>H~6Xj=_^V4@ll?48lT8X(U3VP$_lYLl}m*uE70;Ob<U8g z&n;e;le}ILj*>5-7MbUtD%|^P?%L$}44K?v>8fPTW2@#GAiftQ0Z;nUZ;vytZ8AuO z1{9=9&Zof#cKcInx1Lvyz>`jfPd|b4cV0{4g8jVG0d+N&j#F+BZl-)CpgJ7nw60wc zQc>24avt&0OfxzB8odpq6U^aCXYtg<etY^8JGFCG5>H`m_0w)~Z9UQr2KQ;K6x{De z)9uAPe1f#Qrp=_RI%Fi)&V%zBiCDfL50rQk7b)M79C7dJyYCuIHXK`wJ?`WPH%grz zH=}vL^VhQ*xEd6Q8SjiUD|Q}3wTM%#v)}v@pY?KQLbJc-E5dWl^BjxPs_#qMM|=sN z!8c2u2P|)SgINIPN|9`$ooB$&3(Y3eoe{p0@OnS6Cs%t0en{=Xjj|1Nj^7fK9p_3D zWcTN}HP@e#(3cR}N+Bzkm1>+c`K}}4vWfA+E$6<Y=9YAk6t)gl>vPXS>=Rd#I~!XE zTlxZ@iV6YJqAVAbz+l0%eNGL7R8vHmhBq73sV&-v|Dr8-WQkM@mg?{&2HZ`>Xo=(K zWp*!Zs7GDgg&P*Mgm;TgSh5=<RR>6}nUH6h^mJeVO`<U5l?ahNNSTn-PK%eG77sEB zbOS|7!PSh@5U0|k3+VZz6?D?V3KDIvE`8%z_clbN3nZpvPN;5m2E8EO@=I67O-jY* zq9Iq;(=c;mZW3w8!#>$qr#{{7Y7MsvSeAg$sM#}k)t3-&;MkzidIi%Dq<7aoQA6eA z2Nz#~bk`$C8_K{B=_<v=U^(CeQqU8p$F6}UVXcuPb*V#w$%6?ixS?)s`p>(M6z$Wy zLiRsY3Q89oTcitBk1Lu4c0?7qni5PR+T&Wu(mgKs8xLV6*Yr!<k}D0;ky<K-(T2x% zf~r}zS>H1?U}_qrVJWsm-TwxLDqny~;-M<as04|F@&|mM63Cx>WbKa?1BmquB-F<u zPRbxhxhE#__t>Ckz^ai?;1Glw33Xhf@lT4pYWS){;Pbl2x^M;@3LyN?W<XN=OQP)y z05<<OOlGGwUb$~EH7&*XN}2vqJS*#y$ItGptGGhXg1?<V6MX&!8V)5~Ta&5ZHM6ix zOM3DoE~uW#_9nTGfn~N14EkArj@W)3K<~8Y0OkDugwXGB;2zX19v^^DPdb(@@_Xf& zUleYB_aV$d!<`T$K$-=?i4;K8{{@ms?F4~J*JV5xk@w)Vqt?>5&ZY9-Sjqs>^#5)f zp;-X^%r{4Dn>@Z;bB`6!Dwyx!PbvunFc$76V_5a2Jb&WgPHPi-bpNsi6HmMv+eLWv zA8u_V3;(qrGIg2ic+F?&NVzDxhxmHi=ct$bjIx_527lfWDL7!1Mh0jUz(COPzWLYp zSI=VPX#$;2cu$czmpBNLnvf~)mGiD&?`&B|AbsczL_d2$_Zf(QidFeS(3<yc@&{H2 zt1mG<oZEe&>gn+<8W1p^T^3R@XXC>E(uFwjhwWc>k`1RmP<LLF|0etN2_5UzfJ7@P zM_fMfo(#tWfN7d}0n`cjn@0d#umAqJLMfVLLoDb%3_Pc9<LYT{w(PX5A7=mdF=b*u zU)3K_*a%>4zKgm7Qz7`<3w&FEH1v1Ov<V7$9?Qj7SUNKoB)2B6?cJ(LD(9BvmK@u( z0ux^X+y7$CJ-V{mFQD&N+<<UrxM%Ly<_-d>BS2d?G+PPlR#i{t)wQ(5-=QY)oBt#f z+)LuDX9TUUO*pv(gh!!d9CPMsg!Au#ufKY6XORJTdhCJfFf&$9{UT<57)-^@WRs3j z-#ecuhDzKPiaZnpsHuBEe0yj1{pGWs9LD@-eg&_jlyjDz=q<h3;22ao{5(lw=N?O~ z5qJyEO?;&bUF=jloJj<3xBzHp={@Bl;DZM1Ab3N*3ujg&^j^(qYt>tOD#pZ`ehvSX zaVNT$*b7idKUqM8Q^|8@jhz9i!4@Dp_OIj;2^k%zIoCLGy;I|S()%1~YVU-$nC@0P zkrsadC@42)j(wU?BJnclpK+7O{E@!%9A0d?uvTMkHs3E&%||2oSd;aTZUp+z|0jW; zVSCgGF~CmsMH+f~=%Q)GZxFqH=gH)%k=Z#1i7XPJgxu!O(vE-THR11Z-=jZ6^0a{d z{@k)0sam`zUzjUF7Ij|LpZ1(~bj?3aIGvq<8K=MN|IIvqSNzp%4TGGwR%1=<Bh7Cl z)5)U)otaw-qce3IOw<T<1<)@VRHry$(jMt_xtu~oKoFIr3hgB>t50w405ykH=p0WO zOaMmnDd57rIew-Kq+XpI*ku{QbK<M|4XSP$wF2b8)nfE~j@DoeTS2VPYHi1vxiv2r zX9dW?wg#YlPPp@#8!&`b7OSKbge5-Hd)pYfI+tZ9`~K?l|2WtafK9xB!n2=(<Jx(G zpdD4yw#2asxB>`fd2I0%Fp}VGYSHRd^v^$)de_zXwSnVSuEa%xJVNn0j-n?-kp0%Q zB(O+oc_Jt*HeQRb=+w>jh$+p<(MyE)u8i%_ozEYUeMUlu;=nwFyZ~e>B%sF~WV2e% zPcw33L=&P8qTpioiH?C^D%~Hxxe{M*JHh|p9BEIFJ5Ng>f2blTNDd3fH>=d`r}=tl zk2AX0-;%ycD)ObKYp`Gb+40k77r8+);lP1nW7P*cd-u-JtVM=yOuA5e+^js`a$uVn zG~N1!2RSQNCWdK@=2;!{G-qg*;Gp-KTvgF!&sa{uz?xV)x!U8U@2THs#*{OX4^1&+ z(G_m^OW5mLb*-4_pS~E4!-fRXn0K}gQTnrX!jyWWZ)%n9D5=z4d%$gZB_R~d&@Qk6 zrh<o%;mVd)X426uY!^1Vj)*sMkh?$BXVRFyJ4`t?UgotCty|@yk$Z>iog52~PT7&% zQq!4{#7VjF5n0MKi;Z0^%AA$^C7+TCmx(D0p1-Dcp7|+wmoAgoh6Wykg37i|zuBBG zMVeF@sC<jBBZJcJDfx;TZ`=oD3%~8~eokId=Y4`eJj<QXiFd}dL&Apvmki@>1Jh_a z!@F_jvXzxK4jb0#{E{$>B-lfF)%?OdJ=s|`?&ZkN#cO^PDhYiZv>_nPLTK0ZVom;@ z0R_P#E1?DRe$lU|@@&j2+g5HFOMMg?Yfj@e8Wm%n+dH$qhc_`$yy!0yHrx;}ZHI9s z&gSCX9TYC21*PgGmW#?h&~i<-(Oe&qQIZP-JU4|tzAe{|O<*)@9s;Uuym2v)_=pT0 z@+s3=T~BA=XieIFR3gq@Z}xWcQN5?qOW;=MW3`SpUD0ihJscNA-IhMih=iBoY}aoS z-q~>=?VAZbx^KU7D56&ofwK3#xcELFauMn{SUjDd9k_V>h~O-SF{x<KSYlFACp%Qr zr8cuuvkagrsN4zV$X#uL2yuxXTLF|n=Nx4oRq6Cf=?{(T-Kc3H%Y8|YlFfXry(z;r zo4m{3E99LWp^KM8ZW6yRK(FGhQ1bq6L6D_3AgFKET06&@u5ap+@zi*9n0DJ<^Y~SV z?&al_*nE()PRwGR&ZjXJKM2Ys%A6zW7YP;qI+`B)bb$w}Shk|`coIGzYaWD*-BahC zxRJK47G_~-saie9RhyS69F1{|P~`UWI(*fP>qRBRh@#+E*LFl6V>-h3FWSVYOjg*} zoIavgw3CgxUlopyC3`r}!1-l3Iq*j~58+KaJ7D$Q-z6RfzUn4Pb@?l9kRr~ayP?@t zi}f&`$(<*i4}4bxlwLQR>2jW;%Fv`T)i1THcKva_+|<T+9Ak-Uk>nk|{J~?(6!WCW zMi>+CcHgMp7h>LMkT>R4Zj^txLWt|Zu%dLErL_1J|1bHQW!i>9hGizy8dps6BA?}7 zPSH<-sm+Q!dWMPRZ9|Qn51Hhs6KKp`rs}1-=nTFh6?}Urxl8e4Z5wf-HGcIX%t>6_ z(J5!al!x8y5=}W)^JW_3P-*`Vv{R&(>7Za-QP3$vF%cEBL$`JkpIhi6=aBKFCRDek zB_6`NiHA33jBVX}Bxd`p?Adz>Z>L(kL6M)`q2r_l`e-u>n>J>EX|4V`Hy<Q6?Oxc_ zZgk}kvd<*ObE}Wyn0%;-g4Xqi=3$Iq6!)MaTgV)g5^!&<jIfr(NF}`5gw$4^cX3<h zpwukYBqVx@r--i4D!WSZW}i>|oa401GT3OEb~`~)2YN||s)tFDpCVCPD%Dx(S(sH8 zO-!7&(;dm|ADZv>WOYz6&bv8%dT&vCBDBIbMwAZBaRELh!5VriMar|&`FD&v``mqm zG_Oa0x-(r`HerybEzz^9c6HJ9R4-&2T-P57h*<94M#)43F)W>O(D&!5pa^Px49ufJ zw;CAIj?&X~2g1|PENM2>7V77{G`^IHZ#$~Wg0F*?a@tvN9m^mpCva^?Pc9wq7fB!U z6f%3JX!)(fDQ$pH<(n!(4nq4cO<7K!dj+49Zp)Cx+nJvJmN8u;QsJF&bnu2Ps->w8 z1d)$yN+H;-z-qwvX#<&|YFf=V9iFxG4iY>P@0cEo7_(KC3gO%mwt`O|`28Y5Gep$Q z>Cn#M7`jcEr4W&IJFG6|<}SH*Q`}7rPg*FeVDBPqOD?@rXlxjf)_u+8M_^5g2!7Sw zY41&lGY7Y1q2Yp7En4z}?$nmw_Lnj|!rYifUHB{3b+Ht(Irb=`efX#4XYsMZqjV)x zrKR@;l?rU`BYODtX|as{sI>{t<al<8xPa<>jdY;GUGE|*zzzYlz%P<Ha?ASZoitn# z5cXs5T@}I=JyK25uYkA0S6bDXKPPZ&EWNvZGhQ=_DoWb?d899YFPy@p1=IGOL3&w# zW~D|PLesZk4j#CaA?f%^&_PcmhSQWc+gKVZ&=;hNyPc<oz5NMHMP$Sc={7Y_!6B^{ zrFerWDfwVc)0Sufn!$6l4fK=BeEJ7~NRMmoUHz4v*5k_FF$PyKqqh~{O@*7zTf{+n z)q3g=i2^kf*7ns?PucI-S)2;aKG$;JRdBBwNRNIn$90{4dHb;^UXd?S($OWT3@O>R znigNgQ!v;1KBsyjU#m3eOEg}({dTyZN1e!EmZOE3Zm(hQc>YLutUzsvEf#7Nr!KEu zK^ANsoys`gtKV&0yrx>goGJiy59a>_rtWY6(E|P};9iOmlSi1g)cL+_yZ38|fZ*iy z5;qU$zee0Owb%I@<8>sWU+M9P*ld86rWEv07I#?=AI?bTt^Q;enN*D{ckz6UnhF9r zK5O`*PFwYf&izLG0)_vz{(4pY^P$7eTx$-KllK5U7S#p6Tj+kH$*nC>pIJ#p@ve%@ zl9<<y4=X4g)J0pn+5?gqDZ{(U%4HdE{seIVC_LhXp@%9qmnILG+sY_&t9>GKG$(IF zG9*}m`Dy+0YE{&-TXiRQa|?Idhx|*Vnmp~f)tWcT(q}wUrP0ew4I|=CX(a+3H9q=> zF`nb|N@_pA$SF*9m*#6B{#QLlC#wcJbBa!y^zT2qQfL@%oXUii=+J30T%IuXH5!i< zI<0lBC{o9cg)1myt(TXeuYE)>oCIE~bf_C&_WNdiUs7*?xm7+>q)N+|<$<;t_nwB3 zI=ez;C%feIcTAAEVy?}FlJcOt?U7x#6sRq&g40ORq&A+_-y)52mN$**eRba2Ivw%! zKJXQ0K57>tWQ5R%j5i}*+rK-YOV&^M`8;5xVCI(kW%K5Os@WEvoQDiFR$W_MQE7UD z`gD)&cX#IG4?VxMQv`8!q%WED!k@F*K(q*}C4r@*$+)t?>Kyc%IA!(gd3<=|+nw_d zXV9{UTRiqQoXQOEY%sNKSxt7ri>c23(lg^nF#7DIgxl@|b8|x*em*@@yIJ%MOs`?D zhh1#)1P#OZcc#<$Hzspy%G4{}E`KeRoxbdor<_4u`ctVI0>c&g<jvw)Fgx*;?ev<w zX?Y$+&O~7?9kqs}G0Q0)#7fJl=vY>TSZkc(|Kjew`<mL?ZsAx#s`L&jReG<Hh)Nfb z-a!PE(5r+RrAn7Bz4s=)gLDDuO+pO_NKX(jK*)ZV_ulv3?&m${`2gp?wZf0gx#mi; z<`~zw#@LjknkVeG47Kgg6){gRN9n}`WpZKeURc{QgV3B|?w5L^sO5N{!X+rWrnJYy zCYg`H@uKflk_U<G(RKU#>@>%m>k`p*hXgw`uUiHpa+9WdpcdklxO=LD70Pi^aDVzy zgh6>F__G7a6fK35>085_aB;|LA%q$X^bMV6q?u2F&DqbRNM;O{j7*LF-b=;V?5#&1 zC|et3hZtl(v`)Al_RuXFB8sNL(_-W!_yIMm65fT|QSqC#wS`M_%&c9`<gWouhUWK2 z^_ZijTce(eoO;;kcxuEm1Q(dkPZqr5b}mw<wJDNvEj}uioX)TnM0s;p{R1WPF6@*5 zT#&%>6Q#d8ut?_*G}`Gp;C}o8QrWW0MJv;{IrAs^k6XT6zI)cNMLQ}RQr%hY0YASv z1}GRtKzjcoW{Q6YZWE}PwsYMJlO0V_vJc^*2@Z6h*ExaYYB4JPf5z1O8@g~^{g>U! z%&eXMtanJVSVq*e>(HuwwD|R`56pOz&Huv3rG7lPM@cIusI2qbMZbZ%)E?F8io=|y z%zhoE4Lwh*J6w2dsh~ZZ|0{ZX1Ml#!2b%Z(MwH(c6lNmGMYmf3v4hA%Dw{IMKkz%| zH;B&k8UVb1C+R+$I(Z;F+s$B?_BBpvP1oHMRC4XT?LYV!z=`kC=Gf4}b52|UPXP`w z3Hi>BcZsDM+db9yjxJ;02(BHW2wq^bOO$*@%DVXMrrQ4<xxu?2M+EV>4pLk|eYHUc zT`C_(*ZzqV^|Hc;n*0GME9g~L4z}#^Ka2hBM(N)!DMr8H*qSzgzM=34yb!o#9p>Bg zf`~7!(+!N{bO7DG9{iuX&GOF@yb%EWSsvBE=YWdYcv4IFrmx6#gzm-Sjtg+JRe+m) z{Trj(F(lCu{`ZQ4>VMbVm;44Rb>{>e#F)74WC#;d^$BYv7kHgNrC-@22Et->v;J9Y z#ow5S?Cbx7R^f@6svA*Qcowj^)~^#Sm6$P)Pmmp;d|H|I+x1_c%|dU}T)LTWXz9HE z`w&ph|E;m-sjCzK_yamXu~C@-pmjirP}>cJ*P5SyUl|30Z2vh1bn3s-Vt?XYx<N); zR5r0LK!~R^d`<-L*8G)JOT6++M)Q~9y~ikw1t-f7Sv23Y%ger6gS7xYG{B;p>Yx8I z)&H;hKAYs%h=d(Lo%sDs=LN8|bFWNZg~GpyIpF|4L~MTi%5RCdCEP%4*l{whS>j0a zN*7?857PH>0yY@vKR`{8L}%UQ1z-Yg@B`9~horxx^Wgx$`QJ?3GVi~Q?h`=2iR{0X zRiKiwZ&`l@GG>6Fzr6TIVCy&tz#~;crf1n5Fu$FEsQ#AOm(wq!B+eJIe(Il(<H?(P zeu4xU4GeTf`BMYillm`in0S-MYM(OIn=L*{rUMzSFSH2RG@TNgpHYjmCtOuzHMa#g zZX*9%rm&0Csy0lQhm$MNUj_Q^I+T3dq_^bsqSwdfMJxmV_i=`~p(`Q55`v%gH~aO^ z8>l^e1O|%Md|$mwf7&GTww7@#ML`Fu+|_D~5F1vrE39YKH(q&FeeQ&=?VZHl!Dvti zqQd)UrwkfH@Y{HhOAuwK=6;2dM3a2uThe4Z;&j)x%B#GB3j59Y+9oV-j}Iv^wg>A2 z9a2;7WlTJ3<9wL|>T%x}@+U+-6FE!g9~lo{eBIRKRUC`jbh{g;gk8w0YYgL<X?vPU zkfl5Ueq7)M{Wd>Xx%d^>U>Stva%$;Bb4DLXiC*lcd4!w4uZtY|j!N%C>G#6PWFdyT zD`fuSFxi6zwQ-N>Wb?PP#+%cQOS-IeZ|}<6C58%)++(vZj(hm}jJFc*jf%f(=!rL3 z!6T=?nW1dzrcRn9x=!1Us7sK_I~dhYupVYxLCW4j9pD9FX+kXD<*0PdSsHanQ?wh+ zI7jQ0XhpM-?o*USv=wL&>`Z2G=~n6G7pSMRbC;p;db1dS_Jnsh5RB*4cP^&}Wqw+b znI^V4A(qG2|8d~r(f&6d-OT-GE$=2?#M$uO0rjWEK^|SkA9V1-juv`vp_@fdrg_D< zCWlPvz)eNfc2-SMpLsV-gQB{&rx>kJ%(R$3bj`&l|9c-%kl;3X>LNgo6;3nP!fLC* zOO4pCKmJL*%`k9>91_cXV$dLwC|J*%?-*%@4h?|Y9=>BCKaRTEzYA=qNe&&cH0623 z6o%2NOX6Mo734f{X#<5b*=79^V|kK~xphwOGF2`K!(fUWqt(x%p^r&N^y<}Z<7!I^ zq!Ue7MB=sEtiP@BC>K!d*UFMs^*6tC3mrRJyh#9SQP-`m=d_pS{y=an0=BYNcPr!4 zEDPz?_N@-GzWz)4|11Zhim_NXz;VLXdu2g2la9QHZG0|nB#oy9_rF09ro103sWKe- z)+O#vQ|ekj8&&S{zv-)n;vCqA8>2Wwz{UkoW<Jzu(J8TNH#5)7e%-<pmt8F9JOX;7 zeKlsU+)Dgt_@gqNy`$t0jd_jJ*C?i<zC$`22$ev+6RnBetfqL@8idR*Z{Ks^>9k|{ z!9)>>0&6CNIGI-{Hy;}}-9rsm4BdqkmKFnnu8zg5)OmJ~k?wSo$_g1Te&9gQ1&JCr zfoWV{HaAULXKANyeQ9jyn2Kt<dW~|`j7{Zb*a5g1BDlVSk72#>;exRtt$@^n-*8kb z&3)rOS824dGW2yuGHZ;?COi{WG?DjdS#<0NI5SCrvglDXnO2EHG9S&m3YGi~uF-a= zPL=W~Rra<jaZrf@4E8KxLsviXY0S+XX?Xa4WhaulBUI~x%Py^I@9fF)Q~od8toEbR z)@Omt_}^Ug%Y0TFdk7sopQ82mp-6LjXp49&`r3dnEaJ&@zB1pv_G<A46n~n3T=DC$ zOu{fS13JDh7gMC0JnrUKI-x8<=H&hyyUcgckPv>byeCu6<UW|mB8N%Kz2!~+WGNX- z0ztgny}Am9L0Z>v-)23?@GeI6*6NH2$31<W_51f9;VvRg^4w<<tPrj0gQi(2z)$_e zaxw)hEOj8bT9;cz%z7U>oqt&%JyqJguAKz5!Y~;YLA+(V%Q@o16WVa$fbP<fM<dL; z^X=NKKM8KwJLZkUK@vj*gnq|+G{us6Hq7cm6yd)RmYWjL5-f<Vi0T#jsM-nY1fCN> z(*-@43SMOksS6Dj)wsRAEHHii%M#Vs7u?*@FtHh~OK9mN2zcpnb1;0d6q0o|7y4qo z($@zwOhXD1(rHu4$+fa=amp+h_mgFDYiM{?7^#oU`(DCxfF~B*TK|jSSqO<H(7Not zWO(5Sl^0*UKUId$)nR=&9l4jodA)Q}d&`#;%`lKfbUe&Q2z*f^PKa65rwW7(p|5Gw znDU=|wt9XCZ}@I{t#D!wwG<vl8O*r%JT&OIE7xd%Y9^;SY18He^fJzCL#7~A`Rmyj zPv;@?ql<i3!(nRsuNX4aZf_^Wp(sNZ^>Se{a)q|b2l5uI%^cxFI|~TtGHDN9Hnc?F zwKy&A)fY#l0Kq*?k4I-MjC=jb(f%<$>xS-GH+PJZ;#Zw0yK;9@do^rh8;+H&TJWb1 zmH5_^Xi`29M{sQXpq8Q|Sd>@`c^qCwy4<g?mCUCz6&D}wT8D5@ZmK)cND-}<r2(&! zGNU9H{U1jgghz=<AJ4#{1W5^eS}vz?QK~9+y5G{Y6LR+@M-<1vQYev!sKa*$zK<=@ zoC6J4cR%~2K}a!44`gM+azkkKlp~)xC4z!J?9X?MI686~+zn>CZ_?RE`gLnHCQ4RR z4sF-7Ld45Q+*{pOWn^Y25f`Pv5K~{6CsI?>Y65l}*l0jWl!<KRoZ$P)A%`p6aAd=z z6wqYP7*Usn$JQnCkOji83oB*Db@uW@48~<%ZJ#5u4HeW~ub=8Cr6%TdPF3bLy)hYc zd>PzRltENMH1W-)LyBx7xwNJx{kFU}rLO||RR~(7PrpP<IGxgJN2}HaPAZzNZI|ze zXoyfFebgCauEbAYCizklfpW|Kel%M&)SghDn2V&`-%Edvum#s@n%^EH#u8s91J7!_ zd8~lOm4$5_?b}S<DZV6|)1?H1$s@(EpjwsU0^uV;E4L;QUTYyZ)Ip-VMR9L*g$PH3 z5qNr~%AzH0zgo47HoGBcXtH!i&Beh{F5r%Cyj_XS?7c4)ERW^AB{i5Z1v;T~+x>O- zrYlAymx{{#j}td$j<#FsV`sWLRRqXkmMjV74p2)$gIm+Zs2SVoMCqgA_=M66WnB~O zZia4<r5<=Ph?ADvHjB8z_aSB&MXHK2@8zkQUoq(zKVI<ZBr%2AbwxWJ^6DAzEsq|_ zz^r4fqbaPx@*6f8L}+2^;XG?h<7o-T7@ekuT8Z{$U-yHnPKst-SM&3yF=(D5%%Ah5 zh4OJm6F!i$wDX#k!Y#fC_kjj-$1?8jJTqH1%2Rak<hA`qWAN>c5M7t#Ze-S%SxA&G z9TK2@^v+-PY7jyZmle5tjdio-aXXaeQiTgO&xRXEJmaCXi+f*($^FYn*Rx1<yA_gH z`7@*{C`(3^6-ZOjn#ls<aW%dZjb@fJpRvxX_)WS4-%hyng6~gh^~@$3In4F8V2Y$+ zDWmz9`R3eiy(+JNa^Cl;XFYNl_ypWQH55xPAkcoNk0^zO8qRW5t4R}nC(5#z{Bj6M zpD23&$~Xc)GDIYx6`S3B$6o{3sXeK$09v8zaO}3swBw?e0;&MTaCh=}pGPO|9I-sh z)BGZswK;jKNt0gS(BLW%`EI*qbBUhuzXhc)Z|NIH4}_IF*84=X22a<GDBo?HI^gdn zOsOb38qRArq`k=>OSf?pC)lO9?u4as!`-S_&-!|(U5y#AUMF-SgFWs|t!wDCzwMX0 zuHF$_n8BARk))7lMERnYhw(!`NwIG&rvyDLIL<|v+g%WrGQ8sYEy3hP6@#grU4hL) zrv!h@GOm6#i>Zkr3RYT3EtOxY->dplv_Qcf+AS3RtVkoZ;7Phoe<Ht`lh;HG5HDs< z4>VJtULD>9;#U1H$0i^Z?qXxG|0ZHQykUhI!#!NbwN@R8RT#>O0GoG7V7t7FjRLvW z0qq0kr~z!K1Fiyq*{OSW(Z8SBfPjqMvzv?XIiM!|oulYqXKy5JfoLg$!>I$(0%xj~ zqD2-JkP-08|Ff|c2m4lXcC`GEnP}YfA0T1K+4s&2=SDdCrvOky-qIY$^V?Je@`h=C zRLYnuO80f)D+xP4EY(GPzy1fv(%22KF$@N|_?u+?80q8&HZEIf{<<sQ&Qpc`)Iipl zr$G}5QlLXe(%HH;Ksmpai}M%)fY)O+ptwF;^Zi=K4*>LJMx4#btUoi`xf<wvG^Xw| z%jDjH$7VPd2&j}5kFrUehU0NwjT?%|oY)^uL#@~>Z3T^zY!bJwJNZ9v^iNcKqnBG) z{+##=%(r-`Q#|mG3}*zJ|GfXKQ-qQqZ7E}x7>x0Jj?<`vWZiHb=OuBRP1MP+akjaV z$o%IO93J_p(a9FRkz65Vt*mu4#J_UJ=0m>+{%i93z1K6Sw>WWtCPvf56y&*V1^+Pt zm$qJf=fHkt;Jol~&n~FM9=?9ca=z0!`i5>}@DC7p;VA#;8*rHpXZrB?9h<=u(JP<4 zT;XHl*s|8f*z5R&F-<ZTIw`V+zXe6K{<Sa@|6Tl>;h@$k)`n`=p`gI~T~|xa{(OV_ z@j?0r4W!s=Dm%{Ual9*k4Om&*9mEkq-`ush$Wj3XZpSyQInZF!_$wDK5#(X^=d}NO zRi7pvGWd(#RQ+mr6Z!3g@uyhCf8Qp#>v{y;NBBnLF;zV<^=ohbx)8m?0J&)6fOSV* zZ}hGywMGe0qK<ReuYpH(zRxD^{PSk`e};FF<M8ZQ2s*8((T(9?8HZQ!^$b@vy-7=( ziKW59a+e<aS{nHm!Es(|pc>kPz>>>#0;~~+9p%%%Qb*c1M(RtA@vz+5m1UcGQB%7_ z8O10QGY0O^k|`Iu1GRE4vT|u93l_ViHycK3%r77n!jLT2F?u`3#2kdgcs=yQ?=m;_ zpOG))>%3*Fs;49$a6v?VQNLBiD%`U!0+wfN#3S*pw~A9);c1vuEpy0^bEr!k+Yrb< zm606#cxHa(n|p@+OAB4uCzHM(U&n~VYX+IDh@__mS*p0E=g~G8qxHL4@L^SYe%`t* zHSHOi0*>yxF}%wPZ}y|Dy9_CrqCSsW#-wvmDJ=9XOQ96svLJE6Zk}-Ff-+;Hz7k_f zLs2`!0{PZ<vbKq<TH;L!iWH7<7BovY<_%ZPqY-#v*~S7?P<>|RnblzR0t@doC5M$E zav|fO%Y|;aFK!tn!c^{`Ele}BiVbW}Z`-!$9!uyoJ}YmS6F&-#Hu!qAvRs%>=}v&; zow>%~wHR`+L<J*1e|o}QYg)Y+u?I|ZZ1MWhsjeD{1rAz}M13mQ@am{AotbBlZ3ahz z&D!@175>S{+_mMzJD2HRCY;=EL0Tr`N=Pu(E2IVp>oAF90e1IxYP1N1a^d2Rnv6np z&4ajy4aj${KOOnO!#0G}u?6u$id#=Ir7ufl@A%4gOt<N;RRx*xp%VM%Gi6L4?~A7f zXJ$d^-*dFuK`oB%H5oF=4sVX|R%{M1bf!>xe2*Pw<7W#|P++1{$1lZkr<ya_2?&I- zuiP8VHBo-hrrF0<q@KiTU;YUBvEgICK|mi(rB~I2pseJ#lzwPnrdMzRE8fMRg30zp zT#Q(=w%QNVGIeZ;hy7)3C@vO!x7UzgybvDS(o_nwCvB|a9?Gi#i(7`k4K{QDhxJ4$ zM16Z+Z&QJmrdrV|{eI{GvBoNCpez%Vr6y8{ukwTF3LpgN?%?~_=I3ZPeE-hNfDyh- zue=szvo)pltB)u@8$Pujn1VBa2`}Vuvw&j<KFeBB1enSJg>WJ<66=pz9dY&Ji+z$b zIdANjB3hzHXA#R6a0kxCtbCN(JT_0-)xy$!7=xo7_h*N}dxWuEK#RKS7&Qi3H9aC8 z!ItVbEN{mYNqz6ZM_W%}jq4qjV3m8HZn9g~q7_dIF^U(mSSvKmUKjFZ&9p2DCaw2% zCJ$7gPUaoo@#O;#LTHtHnU9w}vN6H0RP8Oz$R8lZrho?vp9Xejnija%8AmLRV45X* zX}arN&CR0U&L*|e61b~g`<5CtvL%K80h*R&1Rxon3;g<{kef;L+9AS){1wu)=_W#O zy)vokddTV73+B7isjl5qzKPuW6?-K=6wDSTI$xPz2kasR0(}80j+l%y%%hXWmwvL+ z0}xm0^N)Wu@3P=A5zou-e*ytCAo)oLrfr=vqaixF)_4#Aol6ui;6CFRW@HI49b3r8 z-d%0#BBwPba!cB#*2o+mCe@)A0(<#M_l!6f!)YC~N_E?OP7laoRmkScf;pu9GX4x; zsaF1VyYn{x!T!Eu)mleuOU7|p1ayh5x%#Hz^$AsK%#cP9%(^Y|Vl?G~1f#LuH#m!v zvhBDdAs%-J5W5NJ%$O!WTnyV}<GH@9<G?@u<@;p+UQS|K>QRj^*cmML%LPp(!S-lK zSwT!IQ4FO(pcxpv!!cbklp1tswRO6DXA@(RO#JpsF52L!n7x8<g^GcZD9<A*!5J<s zz&)@RY12<-Camq;+oW=Th&&=bx6D}|g3_(J0i;vpp=yyaePuoXPq&jQ5s~z>UwS4; zXa^xS_to)wF)wj>yt1>S(bC;(7J}@%HG_8|!RcH3OBXIMkv0AOYd%H(!$zcGeBUs^ ztHiImI;mbvgSqLPj=?tqO&jW?4{ouy1RJgKyl(qSYjVa#78%fPh3f*^Q#gUTjK|6? ztmp(-l_j8_$JAQ%f$Ed$7E^-&@TF+?to9Sl{kWZ_NBvCJHu-oX#C+b3y#m3I+JXHp zWDEh6h4`2!h7?M?x^Q@VdnC8cWqzA}X}HJ1iLY0j;*8u@+|9`3ZqH#<PAXNh<!Hs% zTL0TaZoaatq``4PlzE(RSLVqRR*9PhQlhCFfob}M>0VX~4=Ra9Fv5idg&uLMNz_qB ziLW&E+F|!yy9JApD&_2h>?(0Zc;XxQ{U!;e&3T)LQCSV6^(FpaCU(rPLtemd8^X+2 zO;TSMWqZkrw417osnq^(*hg$G6GBbz9%Tz~n<}AdJ{^n*MmFvJ0kR?uV-}f&SPPKC zrdIy|1%g?f3U(V1G2y<i);n+8eO%ZcHyb)q^NoJ*m{2D{gu0*j@x8&vBzgBI{##1u zTbPpzE||vYQ^2OPm6*o37QGyk4Y=@anzPL>Y>V(0qUD&HxHR*of^LQB-&TnaeQC3n zyk)+SJn$M)(-`AxenATp=+oZzXTmI4LuCVRW{I_*!&Fqu)~OphpC{=x88|w8i+f@a zptw0$gJ6ftS|qU$^6p9*KA^u{Kqb{|=E3czn3}3f;Tr#Xv%=U%Ha5O`9r^LAEL);2 z%$JJm<zxlT-c;|9s58dPb*4^_ySC&Vu%JSWr_NObuFkrY&dxDX7q@*0Cc*4>mA+3= z%vny>o)t@c<1yM0n+wy7nfCfUGn4GY2E8BA3R5!@{YFBW=4-F^@hkvS#EP-*=3_qf zl^!9xo<3&w&T(yxY4?3`1Y&19zx7i?%9>(JJ?U#JRVZKO^NgHKLngz^C9Dh0K<`YO zW-jcS_5@;7$im4T$C)|0vz<D!DCe5w*gf@PSwukKj&S~hZeD~_paIqZ^BDDby{h{U z(2Z>zb(&&(=Y+3D5hk~PJF$vS;3||nFCkduwe^Kqdwsd{9fhcz@ays+GA<|Tl-xtG z6y@&weWC?)hD9FCK7$uCth7=_`-9zP*c5D6&>GQ7I96@#X@7&<WszAXiBK>BmCcXU zY3JB}fNiUwn=65oN;CHmnmtR{p3b1BNG}p7n|A7riD4#~I?j06gM^1wXscjK{0b$4 z+g@4cDxWe*141v4f|H&_-s(GXwEOa(7~(X<Et+mu4t^KhMQ8;1YOJ->PxYR9O7kbK zs<G;!u;<J5wBdZ)#d+}_yy0_XAC8aH>*AC};_vIZeh&0m*AJaqOOC)oP!}3#)5FjM zita7_rn+#MTU)i$*)4TR%gRcIPXeSq<me{myhi{c?+vW1sRAT)g$j=Jz|v#n;Olmp zyyE_xF`rU(l9Kdh$5q+uT#ea#)l(y5fVdlJg!DTj1iR-zis-rSkSpU4QmW`21&^IR zSMJ!r%>?^+$J}tW?(~Lu2ebRjdcG!7$hjNn*K#N6_Fh}T+0|5BCECTMN4nieRFm!3 zp=oEGlDXctjzVfN)QJ#5O%f-W3U}t+esgV1+9!YVhUui9p5?m<i+u%#gJsaTlEmYM z;h+nnPcM(wfsOZgrM)s&6S-)X(CBCEPaU*+vNfvRpBMUZ(U#u6rJ^tKL;X>p*%`-} z?>J4Yo>H}UzN`Y8sEXx72xszWr_ESIC)pn$`vpJ6p3bXa!(S1PKgE~nCLQbFoxu17 zPD+Z#>r$#jPn0%v-yn<!VU90I4q1(9<v>sK>=Zju0})`69E@u3tl&=SK&bCsE==AF z-$%S=yPD>W!lk?_KOB;-H#V8Z_S}jxWJ{8&bp-sn*4pl^Zg14N02b3CQ<*{u&3TlS z-zF38OcxyRc~#ju{1Bai+-M>cA5bw2(GM-s3pNrO=uWy<0V%Pt<`xM`q?IpO+Z`>i zXM4Ug!mbi5^?0|oOw4=$Qvd4HSjc|4K!mTM2kp3nb<6Z}&!e^urHa_4rxz6#?<sqo zIOK-<BloB@!*PHjvkTg}S_C1)@nQkE9HMra-lpO)Y<#KAfzEp8a8KI`ZTz%fhRaB4 zFim8DauXI__%#pzsJ!O-HpH$fQkD|q1nej@fXzjZ9pG(T=MzORv?()I8^v#!W6b3k zRK_4ur!TxD8I;IR{^UjJW~VUtw$hX}@c2mD0_4e5X9Dyvc)YW}pL#U4YjR5wRE2+J z-%eh%^}cCkMVZ7YqtLPb>hi6%9j`uRorL0P53Z?1Be!t<cDg}@bgR00BhTbcI_={4 zLZnue$X@^@?@wrGiqj~`<D8xgfh#cn47d_isT$RMD-ykHjQbPl^q?m=c<i&*;M*qq ze}lGRbQn4G%CiGmZ<N%YT_R9Zj}v?KYqq~~Oa}h~I)F**e-IqdEWkNE@e2aQpoXM( zoki}0s0Udu<4rwNSg^<Dqa~ORS$jOu@L>4yT@#1D#|YJQm-hHXa!XJa1ldbP?)+9c z&&F^24_emA{2$1Z^iM$QS;FR{I4bQuRpY1TO!{+d_KnQSpSX(o&x=~M$tLt3lChm* zyL)H!>m8pN^FROb^|>5mUL0sRAO7V|_X~$R{{?P$+XRPF8432ToHcP?<{3%J7XB+g zMEd{t{=`}I*EkBu<eL1_U8Qgw<?ug8aL3(ZgK9koMgW#;T(9BxF;-9yg)WPm7BW7J zu`E{xa!$|UMGxM$i(mQ!bZP`z`ai(h9bc;_sVdiHVh}WM$58dIxIfop4yDYh8;^%G z9m56HPg|X*f>!^c7jlpuR&&o^YJo`O6fbVJ0DOQBSWDxSc;Ep5{2v>ETK~e#d0%31 z-U3@D#FSSScA}#SO-h^C7CL_2h&A6oi3&@A+4$Q(uJIQz?*iue-waPJ(|?X1-uT-d zqLRPW6c6`scID*rvl}hHa>yYxe+&I>VV$_gfKv7sy8)_<|MUk4y#=}SU>Ry|+4d#< zJEx=gnj=tiCW8Df){h4Y+uKe+dHO%p1*pOt5B}K_H!pEqUOI#F#D+lj<KZfxo$tBf zprYS1FDs{h*WN$8p=t?K7(N2l54t!Hs^3oBuPptiTzv!BwX=}JJK!0f^<5_Lf!?gc ztgVMczlzoM<3O?cuXM@Mmj9X_=z#Rufd|$Zap$ihzNv$&nE<eCK%IL|3{Wei{IZo( zU5&w@({QbDIb)BAe~xuPdO*MF`tkx`EBC0;?l&s}7B}GMs2%XWR?k`2K;W5N7M>iE zI!(0E6ewHdt~_-FXrZw7$skLzXZO;E>qN@meNpkNx%pL<N8tNUz{irs8dFyA-CHBD z%7aP2d#>69YQa_?#8Kp7;X-LA*%X50tPxyZXp0rTn<&w*%1XTGgr(?N)eYTy3|JCi zCR2aPx0t^4yJ}7YtC<C;PL2!T*<lgmLCVNYnh-8z{c|c;hv5%1DZ%c*uU;&$;oF0} z!x5QEJWkU?Qzy0bm#no5%YTGzG)%A8MNe`$t}VDf)ekGivo^GhURLXx?_bG7^>E?7 zt{F8K*s8ljePVq_c~ZWgLKk9(P8U*a7L;(JtCesHtjmaGOC^21Z|4pA4@ScI-?AjC zOB3{Y+%$_54W;@;p6QY&N=V0sjlgJ-r?qJ56YSmf3|j;blQ0XXX4cbJ0f&ZD$N<m? zuU(U|9OprtGWe65<M$>*e+>hS2y&lujWaYRvH-nVU-<Y{zM;)2j%u=RsSHZ75XjSU zkzyUa+VGvu%Kd%abNM^=!>t;?r<Dcr@(<8eOpy*sqq{<IsSAmztY_j^<DXqpui`dl zb9ocjqTy4bd?OjbG%Fm%8gP`K5?%{`m4ptBIi@JLq0iV@4DFgdTw|f!@f2Fw_LTl2 z9>!?BrP>LWXG1!?Y-<SkL4N(J#8D+ZWXHt5?8T80x=-s{ZUP_P^?0Xcc<avuue}O~ z_OJ5ArYz;?n=BN({tm$-&Jg`7d?Z>lFVZoDBsC(@c7~E|{lp_8)g8Ide2+5yzNTXX z3lLCn>86FsIA*44ny#Bn4Jo)0uatDUeG03ryh?sgj<q@15W|qEmRBY#!ECgm7u*KH zi&>ui2AxBg22a))i&jy3k_)pcRflkws+;1z*_Iy+g&VxE0R&3>jdo5x<*<uSnN+BO zklbqH&us0jucw(8`w45>1YE<1iYH6rSU#9MdE!`>A{leVz<*MDpleD0>C|CeP(+Wk z?ovoKa!GF_)i}+xg7@_l`#1gy4ti@{eI?(N7kX?V^Jh0bkOG7+>q>Nk+2u!HyA?@t z&38Lg>T^;~h1cgMrbWd07Gv8nw|dTIRr_F(sTueaQ7U9bX0$Ebj7@FbQPz*D4ms7s zi$Y=E2L48Z>SYOK(-CDMJ;Srdmv)LXo2`wL^>%h8q8APIovL0lBXv7hZ1O=F(bw*C zJ3q7-5PLnlv(vvLv%r&bH<j*MkEptC?Ay=J74HOoz6Z2l-9n<$PD2|mQ|ei6VjV6^ z6az)8Ksz+!0Gz?)ARWkms!Y9z`j!N(<acyP36Cgf`5@TjuB)^t-hIP)rM3|Ze3_|b zxfTHT)`qaPEMf!9SoaYo5UJi?X((qawrj=37Bj>@pCo4ep@%^PY=7iv@PvHqjKl@W zVHwi*Vp;cHu&q1ON!zQTmDV;d#&o~aJWgxR*YU5u`T88IuVLe51{8zYd0&&>+LtO* z{i<D8qT`$>x;<A$HxnMYGb98k2e>7Na*OWYqKRx%F5MRQepz2S?Bi6pJ13oy?x}7v z;JyaSR9k^<a3*uBFE-mdZnj(YXVqJWMu3I*JHVu3S&_$SOy@V2qIM#DhTlZ`rpzb1 z3(Bm%qM#%hAP%VUnhTI6#XdqGMq_nR7s#y;&KWjTVfBNC91r%s`kF-HkKww?FNw4s z)pFN_Je!@mf2VjUV~vy$lh&<YRs<{SX+&7}^s*_55h@1H-?}5H4~l)S;BCdCa%L;F zLWgS2p|6RH)Jm{~c!O(|=WX}tI5Oh()h|8HaC~c3w7y(uR-rGJ+;!{H^*J<}J}R!c zJF~W_PO03)vn8DPby;-|g+=A&HHwj)tNF~38QdL&fh~?~vQ4wnbivfj)`&TU?c?^x z{>N<8&N~uzge4*>W0D~+`J5*PxzEIhk^q`t;2PEs16c=tcWa9RaQ9&M1gPzpSzFQS zWs<D{_y_h`+U--3r?J}`gSQtAq>>g1;p~-@G+gtV$y%_hZm5CYOe!=>0C+?a#y`0; z)`Kw3nEq&BY-I9bq_1)Qg-2LUY))7>)hF1*oL%Y1OCG#+cNg^n-hpfCx6^f(xHuM( zRG(Kw)Vk4)Jn<VEDQ22=e}JALoeC8!6<L#X)5hIP7D)0=Yz@qeElP$2BNs~)$+&&d zxtHnHB0*9D_+=^?W|oi8RWY)ZxCv&~*^Ya#vOe5hj872;vCy5oEH+og7JtFKiCktV zkyt#tu%BG(UQ!)<EjvbuVyYRGQaOglbk@Lo#v<X&75=2=2(|JrnUt+F{2l_73XLu{ z+rnvfa!`8k)3U8DkuT2%oN@Ng)u|=1;T>1zWErut7%`Sl^ZxkT%d8VlmFs@~Og?(A zqIa(fZJlWlg<EM7vEAD<-EN}<&k3QX238o`NY^j2FpqKMMwr0fmX%N>P$j&*2+I{u z+JR*vX!nyge+&%`+{P!09Ry!cjc!q>tdwpr+Qqw23wsDJT1)FnIgmiR<KtC$Qu@`w z6<kAVWknpR$|jeAbZfK5YnztlqR2g?q8Lrh0)h{VvefD8YREHg^=JVag#;dM188^o z_Twbi^LC@^V0NQ&Si95d+vaJkHfo`drH(qZ45Qt<Lc&{*0jr{ZJYM3=SfdtC_0J-D zy-Jm}uh&QukFb9sE}HhzD*SbY6C!K1C<X$JSP7voZ%h?<TVF+LzAGK_?uYT$9Z$XP zTcYzh8S4f)afZHU*%S&dn*t!U@-^n^j>D*xp2L`yMl2=GKqePDXI$4^zm|SvN7+rR zInz&)mU<@jhJI7{HTutAC<mApO0x~SnEe3KGauvSb@9YxCsP)!*CNX#U-%e#F-G~l zgQYP|rK#nslU4PFU*>j!zFvgu?SrB(x(gJ|=1qOpqHf;qu3?i=$}J8Tl?N{Arp8*4 z_S1R$?63TN*w&B^-XF0%Dc`_QbLrJkIh{||iR{{6k1R_qilU1MCc4JE9Q61LrSol6 zaw}9?0(wTvb)^%z9c;|*wV|sb%InOdQ}Y8he>{}tFIwBbDz!FMU*-bt7Yi{_`25N} z#h^c!X`fMHCoMOA(Q<-MmfBaW33d2sg%B#dxQ!qb2nI`fsQS3KH5nA8ur7fo4g_kH zX_J4j-MVisEEgDxTKNR2^~nO_sAK^DL;Wd_`MO=1DCTKi^i5-~!bXDywx^@D147OG zx51yN$ywt!a159<wCVu7p1&1Uwc6RM=GGOK%f`}yCa&F)_6$3|<XDqoSkSNKkL0s% ziN2{Ex2HxIjSNg~g1lTGagovyf;|;yN!1G1SsyJDPrjF-I&7GKnNh^CBARz|>lL$^ z#_c2D#@<TC{&f^AYp*Sfx9j;UFttEZG=00GN(kQw()owS_t{_#hmb^Wm{II`9pgvW zVCwCOFS931GN=BSQGX(H)33kG2}EZ1eXWbknPk`c@x^v8pvSul%@&QqZvoMwb!VFm zQmx_pA-!V#J?lOo3Fq1;=36MI=r+qWK7G{|rJ}mJh8eI_K3`>7mE7xCQ#lcNR?$h* zWuB!NzU7B;CT(1L2(V&7IgGTcg9d$2aACgP0cj37>>uAXV~Fo_L$q%sW^A|B8?)42 z56cVqI><C0!qA$slwA{+^tj=BISX^g?XMB$p=R8ZMhG8bxS|9Of8ym-+=@o+^yJ!F z_u$so;G#?oehUX$=NI8pDg&EJzEv8#w5d(ECI&3d7`FzQx4TM|RoB8DN~5@4^&;BV z3i3`$rVOp_zUf=#jPO8-TANd-WWai8qI;&|(>Y4}h4P5R%KA0)_DTU!CihGc{YmjB zOcsvtF--`T4COui3?;wOHi<d?q0uyVK%?E%rW!0Hqj>67DGqexwI?UiAxdN8->s7u zSB<d%rQ6Tq=I00SV={99<a9Z-Srl$}Qn{PI#ZjV#hYO$@vc>2AS%r_OB2-XD^Ss+G zlq08^yk=thVMLn!`7&N3lq~mPKvrZ800MxWe0Dg_ZGF$)C0$;O8WE%e^qHb~>@$+Z z63-eYO&U~BNm#m7@#3FF&Xh{ZjV(p$%Y<)fM&6%_yh{V?7E&h*&@7x0!ykAV&Q%rh zARcePe5ayw`4?7qH<SKH7;gjmm+ZZU$Gi)EL=8V*g@4E<DFomY0W$}HOQ;4efNtU( zg7vZ*v;_7|C1lC`5?`O;;f>!71gQRXMtNoNKgbC5%NW3}v+@e=?0o#HCLqII*k(Dp z1z43-x#J#{&p5E+fS9h6gRIZGsUV);H04#lxw~f*?EsiiI_B3Jb8DPqAm;?LeU|?Y z)&!N4GWiXg1M}Rg@BGJ<-R4^6FBE18NX)6?aqa&BzWM?{Q$GPfLYM(0$|Iv4E>Jlj zLxX?5x&A%toPIX=U!C)k=fKdsHh@nfbv-cY1OS}}ds6j$|Mv@&SBwz-gZp`&H9>K2 z;$F~!{qFw(nm=Xvv5t3nZjLH4f)C`IpNzm0l^@;)n&iI1$0AvNZo|8q{mj;I4~%?# zqzZNQy9X$4gHEp%c+4F90lFf~f>9ahs<s2(=k-sT<Zo?1hG|_P^K{$cpfm7}bX>aF z@#;C9QT&CfCg5s#26Vh{0|L9#KR}2Tq+?b=dsU>bNY2?KEiH_(d=OskZAmJm&Xr@* zy^Pf{JXn!j>nvEYXkmw@dQ?+u|9YDC9A1U~Wp*3Q>Iw-gb;+HHdzJ!xqbNW!nZT{9 zUvk9K|I3dh=-P#TV{D>>=-JXo*qGC7bv>WLPrddyVC&El2eq=VixXlSzag-9L3)M` z#9azt^k^bX_xLSTsRctG89aI&;I?lnY_vE`p}|P<xzno~#q$C1RP+NF50kMU*+g0U ze2O?Ya8Ejmur|2KY4{cnesK=(&jFnL+U^~~MTdR+ol6PAqF1H%Qx|b#03gqzg&a-- z7U&kg%hK`TwR@1Qe$tEMPNX4@Gn|KyYwQ(yH||9gnoB#TxWe{#YxuF#q&y%4;0NGS zFa@|mLT!H?LM|^M>(3@0(n~XKERB{C(a>lqMSivNWMh^IG}Sou3&s92;`2|&^2DJI zu_1sWW(610Dh&#~knO?wJ_oKq6-POo#>3VSJ2^^a!EpP@!`m);w!g{Tdx4OTe}+>0 zeG*~-xgzne7v|+GUySF8C9ox4kH5VYQ{a5^n<Sp-UkkzV&xfuAu(X62wzW3Syb4&} zc_RNl_=zis`3*tYWkE5}41xtZ=#K#>M%60dTV=b2Yo#xFNb&pin@WTrLw+bLAKq0q zsl9qs{KD%*Y!FBj|J%pD^)kx>F!2<GuM_|loREJOU0d@Z<4S~8T=xOjo=JBFwV{QK zoD>*s2tgRd0K<*}whkJY*{W#B`Z?+O`lZ^7XV+JL|I^$A3+gFk{%xndIig4zaOsnA z^F&@s!RxU)9Ptn||JylV%b(RvKk{uVekyntWo?2U(Vz8q+CWwVS8B!n0DXeYn;Tqa z`}%<q9&^23IUV7MlSrWjDD?{q2buEN9EJBIZsM1R44-BX@~vyPUVbPF?rK(C^A^y@ z8E3^{wg)^Uul1Dci4e=0s2OYKtz>#jDUPN~6}Gs^b2k4Bc45AUp+Pci=eDCpf(w(m zO&5m2gf>+UE{uxzsDrR?4Xo8^u8TP8jcCroZL$cq12t!!zitUYtSvA1FSAGK`FK$o z?}t2zbMze(y?z(G0Oc)wVme9Z(@AWr1<UF|!;+>HI|C2~agQAL>BRB)OK)ws8cE?@ zKZ=wt>6;vcUA%>AjXIY)7xC+lF<JU3_}1T>$>LjE5jAm~itrY}9`>Q&5zG`8AI~;O zp$buoDrS>u$((gT&=-l)vC#YK;Ux-XT9Mh!+d7d2bW`ayV4$x%U;?9UG$AXy1SQ8P zYN088IM7Vp10)&HdygG9+m0Mmp>o0w?#~~8CP<HuS|PSGW5hft#F%R~Kr7tGs21Q> z+nz1*>G3w(POy)Nd9KuD&Okfx?8Fm^U<fp2o%h|B8eIoY)hR5?YP(x^7711=`+Kb| z!v4LH?d|V^NmGu7dDd-VI$XjfQGoI@I63F@B}FLKF7I8>z^zPemsy@nmK%xjt|68D zLq{&!uJdvpmz;0g+>t5I1*Oa>EQ%D8sH;T%OV9342j$R?imfdcF+;VoH@H<yhSF(j zO=?a%g3;;_e7keGDXfP3#P-Bax9%jL{ehU5e0|+ZkH+{xL%L^#26;E84?hJfrikjU z!Kra#Sn*a&Gtv*w3}d(+LkoMXJ9BpiYk|Dv>Au2$!r;eC7xx8Wi+;r37`L$(nI0oV zZt$%3GkGg%1mt$T2H|!pO|SXQ9vAlI_)0^>u959mv*olX{-aX_!$9;hLYJ6VxyB<g zFERFc!u6~AV(q9&mPl`fytNp_MVBmRs)N8obbZ3slceo%jzFTHElfWK-=*XlRMl-C z;zt{-iN}Zxb$uxHkH4&X`^6c<{ekGoD>_}5-~wwpm4r!+eFfL4Bz0^}Eua{jxV(Gp zJ>pC^!>DeNv|&e~h!^16{!|CKFO<l=TGpSD6B;EEo{tPU717zAC;@jQ-d7Kn(Fw_{ zy>NmluEYBvWH94y_)Y)&hK5+x$qHVNv0Jb_1vT+qorY**m{U$YQNI+?Y%uQ}1zYLQ zIB8|Ful+^)X{ESnbIJ~4_NpE@hU26&;H2t`ZBio(VVid4;{0V^&+KVSaG(PE(P^jk z+m~bupB%`)SNA_^d1z(sht}whk~yuuEbz5hPfM#J{|fb|LdnMGU}%gaqOMb)xA#Q7 z@KYI;+%TM(Ac-tL3sT(}z7|GBvciPf0E(5W7%GqTs%y9rb7rirhf|deO^iU4lYQNk zSAp3(<UJ-mo-%{aHXK)V2yYWp{#2&O{g9F8#i#B&MO1?&txpuA8zRx={M<~TGM?Zy z75*$PZlWH~rw;ybmHTCa2>8L%kYJ*x-%uxaA0-Hh#FdyO=+}i8g{f4CDQhQs`_{NQ zr!ykC_md#28O%(W_zM5QbCS?JSOf7jO=CN|PO|OS+6=0RZFcSvUlO?K0%B>Bu4SEB zL|RLJzRYv4ie{ngv}wlO@TH%%Koj9eCUU2-`hFFIo|~*-twE}Q+cgbF9OOLNRs!62 zxgYZkSNcz8U3<}r8tZ4df>oTUGkpoUZENGPg?a!K2h=tb;a+Yo_AS8^jhd%U!b&7m z8SBtRFX&z29^+HH%K|=G8q5F?4RC3WY-nBsw8v%rD!FVg<BTOa-tt>i({Qnc!>DQM z1Wj*JJ5auzbdO5tXy$dp3&<3&q)8c#)7c)PS8;WTY)(@_NAe$fv>AWT#6FHk)|4{J z_ZcRUk{V_5S9nvgMuu-{mqoODYh@_XA!wmGI(p1H8+6k-QvK5!dUJ4q9t}?2%s{pF zn2}72wGx~6y*@HGU$UL$*xa<k-)q~pZlVr5RrS(?^05wm$oaBY%(!QS$_m9Xqn&!k zZu*L$Nke?EtWnO$-Z9vP*rRZHg%v>Cf0cVg9<*5QwJ9pLqMtQd;p?cO?t0i~m1ZOy zu>iR3(+rquAglITFYbJYpkg)bw{s+-z}93nsOSVl5QXXD2yscI24(*N`HMzbU-+x1 zX$4QBT)_`={3kN;FUw``?9wpv1381n=rW@v%$5;qDNQvSI_6opePpIaxWW}K;wdV= z@8*2EsheQ9k;426A^{;dBJ$t{$`Mi0ZnnCtTsl!}?U)W5ZP$$$aLN49NVAqpq>1eh z$e7zoUT7erZb1KfHL3@hi#jBGR6$=NU3GhrOC?>fwA}XoXamzDZYq-<ZRY~&U0DYW zDi~`Y4!<2YhV~2<5IrM`j!pYOP+mYno98zVV)GqRlEMRr4_Bt0CS8X6lfeKnAQ6@h zEwHu~4Ypi6q_Is6$#C$h*qwwRM0f27)8-6Ql{W5@TZao)gNfuPESmBt`qa>RL%YV~ zov$j~x~e34yGlQtH1k!gs78q@F)K=sAMGDJ=ec8$EhLdN0v-eUx35)gj&*In9IudN z=`Y0%B5a-A_nLK@<J+pJW}5m(`i%A$Fv&6gQO<)>JSg1rU2S(W4$WR|omWJnwsU#f zWZoV;3hpJ-J%iK!dwKL<tp@=Og?fb8%B}Ba_fQ8FNVP|^Pd?76dweK&%&)imlB?i5 z5S*AM)E}Fkl|p%U2yJrs>F})?(PhSo6Xh<PxS-Y0SA)1ktRoM2I(=C<!zo4S@FXz% zT%{Wp)IEDUC}VaXt%>n*C{taBJyLV38n(+bGE9KhGnmGz)ZP#X`dSm@+Iv;o8DXWg z^Ak`=3iO}OB{S1D8~0B+sU?*Vx87pz-&16aaT3(>ZPv9``|PFV>~&o~LYnzL%AQJ6 zrL-_LPSbxjtEHK;+3$M+)RmK~;*7a;_=m~_8XgQYriq;@Gu(h>sw6_Y{TGP!C^NY0 zc86|_lBAxxpV>AQ56`Q_$Gew4A_VG2jJ^uvz5-sJNC;uq8lP)VHyOgFRtf!ZuH}7_ zmhac4^=L`ep*SJKw}|L$N1c_5%a~%U)Md&Y)N=58J2&A9$+l;}ZXbPMzR(z)FC|Xx zk#pCKT<X#RhbOP9imKxvM}h8a-2;l=R5vK|y@`FNeWr=!+0!NKs1!zN@^XB3Q{A_F zI%J=#Jh{+~;yuNW1$(qh6BZY9o2|<bh`v4^#C>_0i;=oiN&P-w1=X|*6EpJ2Vm-hs z^Id;}^}Zz-{Bb&ed)hJlyfnEkPbI--$`SQCLY*E$iluWw2cGJq<*Pz{Wt{Rc(hEvc zmDu|ZRona?OiIwk*t$Y4#Hx}5eHX$+`t03P3iZ<Pds$lo3lY75Lpf03YDmf=bz+|^ z9OqXD=wMRiQWFOU+c8yQ8I_5!3aeWlM05Crm$^#?HBC{L3Z^SM7)wAuh~>33RxPf) z7qX%iF6p?oh__HNyNqlk5_%Eaub>R-m+X4Jd~03fjoJO=E~DvGny?KtXT)Kpm}(lI zQ(tOrccI-`B|pEBM+n`$7e7p7cw-+^#)3nh*hfX3OORmtx((7N)@pC5q?#;#jEgs! z3W!Kc@QUBq&~hjq((*RsVVRU=hAkk)St5n8)+!!?)6Q+<ISO?fT%}E+dQ{bkyZs^w zn@DNb-XX#K-Jt|8XqN&vB$B0(rB5C+d?B~v85zbN@+Rx+`BT^JkKN+~j5W%_8^V(% zEvXxc-(I>#zu6}!?zpiwZ&lqM&O;+u63YJPe%ve%U4&%m%L+6nKY@dMt;ZdC+mwrj z8B=?;mIvI2e)PtdiB8DmB`NEM5vdzzy7CNzfm-TaTKH}#?u*?~y1&#W4Dq4!?2MD| zFwaw2cF?9R=78H^k=j~;wwxg%PqaWINyX*VfnVK_kDZEvtKMqej)xBZ`%Zu2-&o|a zyeqXk^X-?Nc5i)sQ8}-}I_zIP5SeV~{0CbYWd5E0a2@gw*eO2*Sj(gj95qoEa47{$ z!u@_yI;yIFH!-;V??VHri~a{YyZRx^o14n4FFe_z4OkLRZnnVx!L$1Jkuhf^3zq<W zEGPDL{PzhISMBYsRc9Jh+|x5KDdT;9`=R8WnU+8;fIe{;xb*471=w7R{0-E`{04Sy z>A9{t{dR6wXH0lCJB`*GKE@6pE2LegMw4v96`J3GC)dAFpPD?#rKMtjk3OSUaB1jW zyr7OUK7q(M$&C5G*#Uom!no^Gb&i2=+SY^A{=N7f%*+9V?aT}jP2`3QueV~a37x&$ zv5T$j>0UXy5{SD2FhKO6`u`2{%|%!z_2VSVt!#8Y-7-)gS6?5!Vf{O#H1d}K)+62g z<N$KaQEm%L`}gz~P=O498=7C+*@d|Mj}C|CrSw-tDqCgQC;@Cc{1fEV7KHfMb^jaf z62Yl*4Yni166^?5J_(TTvpq-0njHQMNl#$raB{Z*4?{wLVXJqY{vSZwr>9Y0!n;@e zrza_|L#w;1l(nRm7v6Hs?&I#xBj!MW^f|xw3{UreSp&)w22~~Zi?E!!Fs3`N^$k98 zKT5ytL;nq4SI+`)G+8)Y7P@j6VDsLa&RzN_|7xW{e!tcRR9|A009(U9K-_W7x7r?; zcZu{+Z4*T5DolK02^PVTJGkNC3pk89Dw|{|3+WWI48~Y`c;tVd?0S&%p{C0{IDlgD zd89rS;I=E?3=kOm0PhCyFQ*y#+bxNa`afqQ*d`0N8RLZE*B&xab?%#^MOOyJiyQQl zYO<CMMjXW*j+y=dWw<kwqKdj$V$R=&s(ox37qe!zKmB-nLMiW%3PA0~+a^Gwr#H*x zwRjxRh+d_1nR$%wd%sF~-8jOayzblE+@u{(ZraSZu3n;7_JG!C-PIWU?{PNLvXNy( z6JDM~y-DwVQh&hTL5Tbru@Bl!jrE&5la`TV^W}Ww9!zooM{I12ejSsGaa`}++~5cx zbmKZoXIlTrVziZf>W@C`hY%sK4*{oV8V%ITu)9C(d3(7hgDkpUyMowWUvga=sq7Ge z>MheXqpCvM$Ziz0_gWLSwWjUBzRg7g4ga!$?4a`1+1#Wo?`80zm;kW}CVn-he;7h` znL_xWOrE~>`Kv1lv00To-M)mYRkyKnb7R5kG3=*>{7=a~(GV3itutO*ej^#qvpd3x zyVX~KfTB&X57D@^{4wqTzHu6EzgxTzl}&$s|8D7@JyFD1{hap7=0b(mg4FSku(^vq zx2f$^5X$M=Z;lG{*c+EA9xTyDiKl5u4YGyrlZL%jqVZ40Hm^G4`ReCqVL0)kDfgYC zrIlEV#ka6r*FNnE^aEB7kdqmB#p}+x&QDd8xKVv0>-w#jeGjL7uBF6^d)I~$E~E0A zm#H{nSkY-LI)9nMRF1W-p<cw)WQ1jq?t9+G7H2BxXozP4C+q*^SLdAgxoqjj<;R|Q zDK{47W{j)NG&D_Ue!Jb-1hNdM249PU?HJ!u{{6UhFD8k*4tdk3l`~+v;$^x8wWu%7 z@N%E`tOOvsQ4J>f$7LAT&pUcF)Z)(N?`=MQW{Y<rC{5u6{piz-@5>aQEoZr)FlxM@ zM6n1}-Xr@E@V;q~bKFz(ivQ29mXo*le5_>D8LV;|(xXYFJt+6JKebHj#pMf?HPr|Y zrM=-vWQ+9d(`=aT;CoD&?8aXAZZggyQE_Z2st2#|VX=pKm^qnfT2sz+C2xUoTW%XS z{=lO3>ZPLSm5~*!?5us2Bd;bhVL_1mOT0i*Gu=kmTG<kYwO3rcW@*VNmzTZq8ux)@ zzY^UySE-+si#uo;6EDPrvWi*aAwgfIhy5BO*wP1&HR)sBTr6+0DLkSSykbmuEz9B| zvxDh=C)Q^Gw~Eu%#*wv?;@%DdCKM8wIT?X>^&j$W);sR%zSFFRu_OYaJo>=z-S1ym zfXe;-^w~9l&H8VkBu~Z1Nzo;RA)eg@`8dO8qS49>VTWBMa3ljDG5XG!^>Ydy1#+pM z#i-&Q#{L27SQ!OqxgaM%o|EkgUs1z}#Z>Ijq_ST?&rSMib>(zGjO4=J<9KTFE}f`& zyR09$m7l;4DwyT>6Oife$&}lo__^pCt&4W}oUj#J5tp}->yf&L7=>fVIUeWb@yhx` zCcHh(3mJHif&Vm)5OYPm<dnx0t_wkU@<5XB8Ol*CE_tbKe7@d~Z%uaasKY|-t4Zv| z1bR-rJ*LZBV($mabwO!jv~czu7A|h=W6Gc^|J*b;C?tH|GPt&$=n?HpJuX4JZ&{c- zoqI7wfPe>Ae_^yMZPW)}D~MM_&6CGBs)bmbhRGVLWQlLGt5wmr_(izJ)w-R$%z5Rx zwt{HUxT<X71uP2`nq=D{A$_YeUa=<Z!~aLvdxkaf?eE?wA|L|NJBaiyy?5yX(o2Ad zNSEHCAQ7ZUm#!eacj+A@bdcVplY}BYp+-u4X8)h-oc-JTy3RT8GB03et(i5m)_2|a z=UyX%*l|zbT3Ug1o_a_FjKyJwI}D(6Pk(Z{9Y&)V*JNTElT{yeRDHXSX|n6H!lN!g z4UGm<@6duN6h5~El^KH#hvB@bjE%+RM$U6(Vx32p-kV`bvFqZJPFh+eAs)82_NY<y z26Sgpby2x1^{69n1C6Vg#KoxWZL!#?-XDiI(tp^E<KUXnrSVeDVm0@J^f30<T&s&W zCYa7r7c$oj|1$SAoMn&4GrrfK{^A74r;M1>kl~q``Nm6gB?z~Re%Z!sAw6&*^*!Ff zlb1OJXN2O!d=t$mlVM;47@26U?(k8_4l_oPX7c-=Xi-kD&@qUre^z7fSRYtt1{i}4 zt1C^=y5=8QmUBXlI-qqD4Mh8Ui4}I!lbG6j{^a@s6-xKK@Y4c>^(tST484wm)_hO# zGO?w?J17`0lH^e*3(H@wt9KE8kz{!JHoe{;uJv`oZe%PPKd!qTW#M!2)q#yHvMj17 zA)Hs6%HE7F=EB^`q{{SZs+_o$xU;vosZT*ffp!)R;Z(uCf*g7x#y8=fQ(JdL5GnCM zZD95CqV?`DWQIKip1MUg+$5j(oSl$Pi73r}P_Ow#lZ^dXYTV{j;Z+P(-G>(P=kV9w z(VZ5dYHX==tOf~6UOQd1sKG-%FGuGheLy4vcCicu=|B?f`2CwM$?iFvxZkCttW#Jm zy8kL$ZAFux6=PBrJjuf1cbyYO@9_~!uT~0C&eTV3H<re!I4lO*yF%RAK2Z_WsmgZ| z@(Io-5+v}KoW@?ls>u<IVteD!u#p_mRBbmKJ>60pqOaO=E6vV6;+#iUP$5VRT=DMq zie&gzl~p$pBQr_mR&<exx_Nm^ti9&eo~N$HVkHx;&)kJrW|sD}ca?z((d2G(+j`8g zfMAEHEgHAa(!Mf{?3t0){7$oBW;KDvGq<F{HfPXCq7A2r#O9lCXu!rIr-n{~l0&+7 zKo|yueq6xx{$*k-$|LIN@GM5kW<md1Ykhlna~AsvXXqYP1C7h)p#{Q=w+1Fv*QEEH zx@6HieVw2mfJ%j^QJ%)4;hP#~c-gwjsijcrMHu;rg!)h0R0iJrKHo@;p>jLHOlXY< zcDG$%1JhWh+1-ZX&NVmZ^=z59Vsnj`saO?-`;a_1HNM1zh}?VL(~|HaLy;bYEx)cf zzXRc^c9{KPig6D64#9X*l9$i>K>ZL2aD7~%WpFZj8J4uyOmDK%EaT7`G_6go^-LWq z!yR3`a4k@tVjkU`CP|!Y=L5$-I4!v`>qdJVGQjm8{;u7ZF-xe?5AiMaU9Y!@VSucS z9!!HqQx|>Q*;-cQ@*Ps7giHT)>=;k`>5^RO3R%v$^B=t$%=GXh(s=Uvu1Mt_x_c~n zWxhZ$ECzPzRtj;n>6|Hn{Pd8In}HpKg&L<kPW((FA6aChk0^Px^$pb@j2`wrm1i%2 zzT*)P5Gcy`0CifNtcaiGAy<lxQHy)#Ek@Zu%FV{^T#0E)o`(Yxv?OU!3M*1CnlQAP zE|F}8`1DI)Ie|nN6id(3Ul@<Rb;_WCiY3=a`CqDiJ0+$OdnY&d%`Jkbs9NK>3%*LE zwWti)k>Ei;E_KCR69um+(qZqrEH$?6cFD|aVq)L|GCI2koFbwXKN5NWP>1O<^~rv> zF^-re_kUvc(+o?39vlCj&5bcZ4_adUs;$?xSUz=t;hi#cer|@#KYKti`BN(^iH+v` z=?vzjt4U<Z6AJvn!_A7s93KZ1NubUZP=>W(#*Fkn7J7gIbNaOk^rF3?xhZ04>1q$b zw><ZGZ9;6g&kJ{3C(6zO`g-Fhl)y{<ewu~OQv;vk0$!1@lpV9LVt<x4wY*_jQsqfL z&{3Y!nlsf1O#2Uj%KWJ$X;V71AgT{x59mYb8}`dIXk^NH<+{cj#qvvyiu9^X_vTYg zTpGbbzgZ4tfgGlHEIrpOO94Gg5>d`*#~yMmgtbPW&^-x5@I4_fFK0hFeY!NJ2pxaZ zudhxDQ$j9HTWWrNyqLL729kI*F^x#R1S*9RXT+`gxKsE<xJPw<V^gxugE#K(<g15C zT56g3O2CTwS#AHe1a<9S94GxnnhSDFLCJ5$`t_df#p+9odB8Bc4xXzy@21;-)eFn; z8*+Z!(zO_f{pvZ5yJ_yh+EMJ_lpkl&Dir-W2#PU5odUX0x^74Pa4_mKL}KJGj?v7G zBkCHK@%+`^5}i0TnYDA%XZ3O_4vO|3T3ktfuZD)nz*ZaFYdijU%e@orhH~~j?r9g1 z^u{nY=P@<ovipdlk?JKg6Uv49cmxng!eLvFAJsoWhn-RJ%BD|owqP$E5a*psGD%^R zlcz?V6-c#~N6mNY1t8N8anY*q^g%@+xEM~-$XxLTC?{Wj6hDq3>&kMwGwW{S8*TeA zL4Nr4WE!9C6U$cD`fyfLvH^fodf|sk{{(g7>r_QvM)RNR+N}5FEZaOr2T_wb^94lN zH=DFPV<&hON=u>>ai2UO++TYV4Ib?NHNM{mCJ(|xpFZ!_RUB}&yDhLQ{hh#3TtewT zO249l;z`l2qGh(_ebGyp;95Y21QQ2yLb{P={hg{k!8Eg(2*G4HfCScsw-2K4=RRiU z{4P_}+5auwjPu@S9lXM6jkiQU_GQXgc3GVNC=Bw$UWxo<wB~8^vmd1$KItF*+TW^f z7TRDYRxW6NbGb`8+Hxcp7*qDui;LtXnofa&NQFG_i&5`fPupy{c5H!7+DoKfmb7sm zFUt4ZZ$qPs2dSOEXR}B$H%3>n6Vw?(1B$VtYnVXTyZ(spQ@d@ep~`|EyajWeXIFHe zh&46Md=D2v%VirKCB`rTOF$PUTmS+DWUk+cd$=MzJ_&ow1L)5x={1Phu4A`roSwAc zOH!s%E%t1Jn*sm0Y~uaLvYA52$j~mnn>QboZgUj)T$mrWp(DzuwrksA^AiM<m2QSg zbsf!;0-}TR$lb}TroK1Vnz+8sV!<IOLg4+|3@?fFO^6I8n`{`Pzo3+)XLN~WpS7GJ zc4PIszil7Rl=aQS*L-u>DC3+}pLbx}ueK#+@0y{f&3$-8Kil2V`IL{>D@OasAj4am zXY`aSYb!|QWLy?ePWx@0j$gYXA)X<1s_cQ!;Gkg1;p-ink_Da#n$TE#b&?Jz!}5}Y zg~op5jR1xZ-K<ZeUj_O240ZNypy+Mseii(XO<&XoY(31;-~a1%w5G-AXsvc4eI-vL z9p!y^@<qXX7d<9GKL!~e+9cCC81{VLpR7Am9-C+XzRbeKs2%pu6U0-i6*Qd>Oq4YV zPX6%I%qrllV`lonq;jMi>mfq<YfhI6j27-)kM}ZSo8P&8EB&EG4x%I9Rw~qOwXT|8 z5*y@Hd@Oo#hT7@<mm5&_2e8w{ux!2iF6TodUuG4BisoT)`_$R0qhU*1t)in|y{^o! zx;~hB(QJmX*~ymWpM$}0j2Y9XlCW{l&z0M=6w%?*Dm+@8JG3Q4C%gE^;xs5pIu;6E zM%jKVWh2}HK<vfCuf`>(_Q2P(vDMb5qUQW798q+?)VPRW_rZ6_T9CY@r|<hBnR6aY z4p8e252g>2nh9pVF<%fHQ|L9EsS>I>_Km9csB&y>dzQ3jo_T=&`5QgVV4tT_^!*2! z={n*VR;oK<b)z+z7bqZTt#`#2XGyy@Kk_&N6lL;-7NPva!yiZRe3*_Z^;+2m7{|Rn z=9mQIR+M@=TnyDz+%ykRhikjj4Kg5cb2HC37}zcXr=AQm5OP?!%T27L5dX=%_P*gm zryo+G4HcPhd@<8q%=Od0qt*hiIwPh^?k`a`MN1~(MblaGIk{E+ERTLIu{^Zh{Q!VL zx7Z1dD0GHYaO;0n8_diQ7&W0SVW?K4lOCQ;?<Xj|F${JGpV`5gMZNpC%tu<B^bE@j zc)e5X)Z0@~4f%!1COn1-$G1h!($YOW+I&m;6xatn*N#CVm}NBLR23sDW;y@0=(n)b zrOe63^2&;a+==G=f#`Oh++@BUu1Kx!kiqiCI<V*(QfIjW-XZn$SBeAO-^a^*;I28; zL1dUwXN1$Co!~{6mCIpB5@p%r9J^@LUz|uAyag=Rz7~Acjb7(g_vpEB-yJ-q0iRf$ z`}&++LZs?a?}Uq(l4@@YU_p|ha1sXCW{Z}zQE!j3H0bMcMV<EH>hGij&snpDCBQZj z^Q^8m9?Tr1Hsd?`m6FW;L)Xl2E!!Met57WX``{-98mBQt)l<uTOT&kwJ`NyX*S*o~ zY@~SY8CL}6f6-d3yMG8RdKhDN74iTqp1xatCZ4Kv1}9WZ!fQYFCD!kE36`)I>FF6P z?W~9)fx<q>k<<k_0<=aiVE<|15B)*6vqxw)_wBdyI7zK`^j1@)AA`f!*A1U=zPxIY zrkq$z-Ux_>Izy?}AijG%#Hn#5SzbPJuk)o}k_Fp%2YU=n;wKx}%mE>Gu8Ma%%xEIT zA^Gjmh+n#HZy$Nqk%W1_3ni##`R4+75)Vv-(Px&fo!aa&*s<UkzwNlWz`9S$W_wvj zLqrYREw*Qn9=xlcl61alG!TFMmM!ha5~o&;2_6$~@i=gMrO`N9<>1V|qVi;!6M~-{ zkKe@`i{(X+H<xJoW_d3k&^*FVJYpmJ0_$+1NqRdX<TE>ox4(XW|ANFY&}7K1s!nMc z<Y~p|E6sLVxDZ5K*;``G&s|4*cFI56a`$V37qUy##LW*J^SQu!jH)8CP4H!w(y&PB zdJiMM!JmwpvKviIh;1NMM1_yN*t<~5Q`;BHaoxUq557SOnFq!0jJqh3`ei9#Pkv}U z%z4!!tm|3N{mE_)C@ic)`1)kr3Y(joV(4MxOqK@iTQ4h>_LSHkUN5*`^@)m4woFyM z)>#Z1E&Zav4h456?)R&e?cth=if^TGjhmVMV2kkFBzbTA0zY#hILGrnZ~8y#GSyxk zT2*C_!QXHPhq~cPOmS2LK$fI#HFV+{x=w@zbgcjWedk{yw*OrL_M5kqNPq80b-0?* zQ8!S-mZm65mIM*!`o}-dC6Q<+B?7c@q!=1(nDaU+?l<&|ME`oXd!W`YOYd4^7OXep zD6C3ro%n%7<c|FN;armZXe1QQxuCdn+kG7VFJ;g_4{(~1&_9IzfcOpxi0@nms?(L5 zKZ5IB$6m3@Me(TlBZ)qE4ag>&{dZYo5<-Ku>E2+u7I%iiB=Z0np0wg|F`#%GN0R{i zNm;Z6a)>pDwE#QX{Tw4DhO_@yW##^Q9CY(h&N-_4ipWd=ltH|5b&j;yJ9&%dSA#tr zpnW7dAWLES&-Q+hTAD=F+(hPHDPlj&P5tLp)Koan%cy4w78EZNlq4{)-}`3&LH>PI zF0l(=98iVHv;u0sfHtp-=7#&f4spx>GnIL!c0nAp{Oiq8^=Q9Xc@nF^DUTFeNfEH~ z@*mB{*#vB`$fN(^xfYZO{`+_C-F98v|KCezMq^zZ0t|UqkE=~?+{NHKkboaD)scRF z)yvEJ{&luVn+b{XN{ZvHLNPW1Za#g6yOzE~ZT87;{XZ)S)8cmF8(HPI7yAp-F>Xx1 zxPQO1W-r6PEjoSX3!88|C`xajXPjUcY!BJ*?Is1dfcjw>c+FveDaH9+#McL3#dZrf z6ef$TMYDx_dTL_*0%^q+X?jYm)`}W@I=njja{Qm_NwV15ETbha?qV|G#C*Dd?t@re zpByydQm4=H(Jj#`b_++^{*rO>9`^C=C#ds!n5Do))dneL%&7C@Cr9$s=ZTvMWq%;6 z7&8mNgtmxUt^Qg9=|)J@IM`h3-4`QI_)4HMwvZ>)@2mK|`9rsJ4W8>|TTZ|8IiC<o zRUV7Od^Mr$U!0D-apODdMatJAK{hB#D9a6Wqp>qWp0CfcGUsK=Q?hoX^NV*r<J`Eg zE)D=Tr_tv@V*`olqpzIqsIQF|WnCuU2{-t4$7br9;O6;)V24Qns>G^2=~SnyE+Crj z*Y~K%7owAo-kHgwK^G#JM)*3FRSp5<oi0c>+ab`RN|V1_Psw)nRVUYlGlt>qwY>SB zBAtTZ7;)I=MUmyDhTIgR;fZUF4|q7b*MPozy=R^ICJ-LOa_(PM_gMCBU&z%$1f=&u z>$XN*h-%L=A}fFI{#xL!&0X=AcT_gxCDHwXLI+?(Ylka3aG*=@vu#cKxWR8C#^5hC zchDt=dDq&z!9sIl%R*7jgb(S%russcgi=*M<FB6Ol8^!ukY4@h?uX(r?<o*PjeTZ@ zz1yIo{)NmF$5LsjnsPwQI`)KgG3G+E3zJ^<?EAjul}FR+CD!)S0*Y}VBuEMx1#Kc7 z6d+YcAGJypzk2EJPR{}6T_oAQ&Lw#lEPkFaa2x}z3$y&mLZHAwSIs`f#%x{G;r%9N z3-?~hJtXCwNaWL;hRcH-(ijTz{dcrN!npj_8smy&6L2u+XXPGRwyO6fC`m;3L9Jbd z;)h_`s6()YTaAaD_aASG6}z1ca;ciHz@iOsXPdD+!1C?M;HRinPBX+%4-!*&D+;FE zi78VRAE+r&#v4olX~YOLFyDKf7^<}S(C^r4uIL>0KCh~Z-*g^)rUR0Gg!EUXXf#hg zAM?P3u3Z5#UH!(HZ<Te<PX#wxVJW?g(DsaNM^trfuFIH5@g8s5#R9=R*d<{*eT<e4 zch*ttjyF;dUAcVNsIz}hc!hU)OtkIW_Z2E7sliz<<MbbEJagH11Xk;NJOqDpJco~F zZ93k#xQ3Lvw7p5U>+>Jw=*mr0eQ3I61bL1lHNnLDQ%2|$)qz<3dpB?QCyq&kFYPWo z<C?uw2lNyg?zBtxdXOtKdTTMh)IO*<jeq(s$Nik<hBbg2udfY&N{yE%RZw&!$KC-| z2U*~aRi{>9;%U<?5+C=0qRe|<K$v77y_@$tpvRW@J$z)f%rC&>>P1dvviR6)<3w6I z_aT(*w-F}5=)J_&z?mFi8m<5B`twK;iO|2CIIXdp?~tzEOG|Q1ZwoW}qm1TOAqtn0 zL!OL5wgzv4w6K4$zBnU*vRc-f6svTxe%@!&RtCJ(hnSbKEz!+Nc>grSn#?c!!z`;r zmjbZpe7gvMEi=0AeE_5Nn*|@pQ|d*Q^vmPJ@jtxjxCQmeeDn9uEJ!Sf^!ihrJZfei zEk?`^?4mq#V8dC+!LVWF0MSwP`lQ(&%gv*hix<Ft+{EE~q&yAwofG!KwQlpwVS3`9 zL}<HvQa{%XRvp%Y#*}WL>dG&7_a|>I`vs+YF#$g?9ee&4iB=8y*f|SlyzS)6qT64? zXNqba011)gMjjQMyum`?ylyw`D=$K<sMBzot^Z_+c3x`6CuuCqgzlBrfEHIqeW^3O zLj}WNsRetseNlgfFs&V4pYB7nJ7ZW97i85ZQo~;QUNp)zCq_XA?HG5cz>0a`N_VDX z!8+UM)HtTXz0ov<Oi>kkqT_J-II)nF$NMOmf&gMkOYV4HbMHoHrUQ(E4I&Q9v>KT7 z`&E@@8W~JHxmumI%T5YS67NPeU^a&ku7|aMYE?OYoC^bPg>kj8-feTu5kC&sa<^-3 zKlZ{|8a{VJ7m>P{Z8z;HFKzvsYs3Uj(2I>A5>ojhY2z9bwOQlsR2T8`kwROd0k>Ho z$E8RnC}GLCLa)$7lF*>c#!VG|9C0Kk>0G#H!`w9QE_R+Rudrj-9JfYWY>qo1+~|KC zUVJaYOQ0{8j4YnJm1WTf;RwtU2q5G@b)*-VsguT>L#drCpGhnv?V*aZ-ZVX09N|pj z`HM5n`E{y*Je9idsiWZV)<E66cXcf*u>|rx75-gM&^C$rdrJVB*}C+1RmJZ1wCgP= zlz02iwg&I;!!Mk4hMEO_iJl`v(gVtuEp`Jx7X)GYeB-~%8#WQGom*1g&0~<_WL?Rh zNil97KJ~o`g*J}8vw7)gV(C|<>c!N?o8@|$y_I4m>}4=&ZHnX)-o(f!DP=t4;*5Lc z*@5qCAPIvq;w3O$S2%vuo3r+Lodkvz)zW7*0%g$_h0)8eqrA8?jz^n)Hr2a~>;B@D zkEBLwpeMr4NS8|bF6aN^Jd^{1%pkDQ-YLkAad(}Cma0I1A%%v!#U&f(tIzi4RkdW# zPPE!OMf(*57W17g$5I|GTm6;+q$aI1MIC`L&UALIWP=p=tDDIUf(IgeRLQ9|))<a! z$zOx;)Z2n!VTj1u5zD7+QC+5n{V$HQZ?;jeA7(n&CY?X;Ja(8ZxYm|)p@cd;c4q&h zc^k^;n1Vd{{pz=gQP^^HY=B#Pms3+=PTN64yMf;D3N{p#R18L>S$qn&x~EX2Ph_H3 zB=cpUs~$uZIcQqAtLNp@SDaEd>&Ky9`8_3dT1#W7ODK2_TEB3Rh0giGER12X^{RFa zX2XE1F<j4+P1Y`-u3N5~j}|qRUd2vMI6FCHV6`0iv%N>^YJq(ZHpjm8gq*tdgPaWm z^n+z2_AB!Jn-%j3>SlO)ZA)gK<=EIo$=lKvO?HqI)x#K}V}>`HpH*8kH2YGp?AUQq z1UQaa^0p}WUJxlN=qezTeJZ`@>V3iovA0Kp%ygVGvHnGN(e{b2oE!<CerX>;6$c~U zkq#cmO#;rni)0{_SqrtDkZXNoj>2ZAT}aTFqLfR%c=!cYEb1rSA!<`^J1w}Yt^j&t zCvCY*qd`y~o1aA+s43lDsWrwUYm};4p0t_HTcqw2c94<Irmd66aSQ4-*C#FN{XEPw z&}b4-p=?_5?rDNJ{TbKsSle_FBYDc7<58`d@PIK(vA20Uigl8Q!`FN_&XE?kg^KPh z^iGd3d1CGF>COb$U~OUh_HVA0bd25zGCw09m5c4kc;+0SFa!^osK2qmsG$mMP)&*G zj~n-!J=^ZLl?uG^<0Bd(9FpZoI25kz0)_EQ;(n{(;YNCB!C4}J&AIf-Ro69=nfZM! zpyqa5tuJOkG;IIY;j4~jbeF?~gwodyt`ScqpD|2kzhyw5(9&-p*L=qPoJsP>g@^5i zE{o>O(#5g)EPIH1^^qG=GwjQQL={HaXWb6zKHM1{f;{jeI>gVtCfP;t@HjDKd55u? z5W5>~<J%FrvQD-!9-qB*#2S}pcUUm1BW-%faD_?OQd#7;^1<wmS7kGC59L_3OiCW; zmKuMokW?krE`DOX=RIJA)^W`w($(JSjVrh8Ja6p7zOM{;F#VX~=_qFa_wFnSfqcJZ z_4P%_ZR~Nd;0-6LCMK94b0S2#yHwM!Hl^|5P%P85G5%`Dyt6U+THD_NJ4>ehQesNu z0y3@nkwrRImj)jY91BnTD*o~q1adVo_Q+*7htYnTD(W(zY+%(ocJ$S?&7VH5bGppF z*(l7f1%M5D8+=c03l`9a?X}KwLv2kj8hHl{FTAbFywy*l%TUc-b(^849jiydEC`P& z4LJle@3;>Mbp@TNd8KhznY53VQD|HM$EO$Jd@ZvcX+aIUFolaJ-m;3}IZQ!zs45!W z8N;>x=c05RGdrIiCYky0m9A8(Y&d$y?l@N-M=FS7Y7lX*&rvzCz^4S-t8jms`CL#= z)Tw@D1@dJ@?4;vT^7(g;BtAKpwB8AIBblLTQ5Xv8v_^>@yX*~AjI!+hc;tI+aX^1` zL6~K!D^F$pYrJ6l6T!kySy+ncU1f#{wK5w8ifF0sk6!h?2;|t*K>7Bv4$OMGEk?KB zX4hJ+W+xV(8Il7R<fBP><$Pjdn8MN&TE^?0Am(^be3b0sv1T<aN&mTFmb2-`8jXC8 z@u}DY=57x#?t^`Rhfz-1TP*JGv=>!z&b?qOBQRKtzIm}K-|w{?O_JJ4f#G!%Iva@f zsDuRQqG|dLS^5L6y5ky#1pSoD!RyM-O#4OoLl-l0m7jZFKYy7ZJm)qSKuF0W4ppA= zReXpU@%SXe8Sdy&xe9upeSwv=C%0DnGCpkXjXC*z*W36Z56-taOiA7znEw1d3ryx< z{>mc^F`GLVq+J%sp0uB=H1u+&@I!8x1&x7Nm-Cl)jYkHA`oi5{cmnmwUV}q{i+NN# z_iS_h+{u7Q**vw22}7(+ok47?9dx-xXkeTw&6Qt}g@(T!-waRZTBYipXWznrUf6H# zYHFI;0vW&GQ>nbZTl6ogWa=SJyDjCx&L|?}`XMe79I3#5n-^q(%290&JQOedjwYUO zW1V?9!yh~;mrUH!+Ugh|(DLPOW+8=kCHn1)fvF&#dbD68YOr6DS)!vI<rrNPWGW~B zHh)(p`FG^C@=smL-O_<(vxT}p0YV~T(^|N1!``ZJP?#{e_S+C)I1o9skih;msp!$( zrW}gu4mU)V%44~?5CI?)0;KjygNGATM&atN`egAZ<yLh3wK=*n2hb-uvyd)f7Oo}r zCePN1bZp_PmV4qe9#1GNI=2oR>e+e&oTi8{+gcv63QCgNO;ZhJzR+B6IZjgEk-V^? z<7O&LL*3Jc&h3@AMGWKlWnATT9eI3#30M03eQ0@?uLC|wwrolEt=V+jQg2_{nbO9Z zGTc!Sfo*UP_;Fa*yezK-G7XXX#Ojp$*Srtv3ydV;$NdwLIfPwOn3@YejDV|elSKDJ z0f7c$KArCwi1D?nrBg%69>!6|SI!U9CdWjFD)^#o(`>mPdv`N*@Sy?GIvYAZRpH~t zFOSB0_^L)va&>iWwePBl;87JvSjt<r2rY-NCC004)^@?WdCif<DE;0zwvF!obzDe^ z$t1Qn&=J)QPJa=~Q0pb$ruH_EBR-X~DntYnp#wqDjInO9jb*F9TW{d{mr`3+A8&at z=ix!MI6K;?v3~b^L%PJ;`>YW)r*ZFzZtf#=b?=tYh^F<*%yvn11aFv!087{Lgp|aw z>)@&j{c5|<=$cz$7k)TIlqef5|4^OzX-%Xr@0tm(vdK?jX>dc1IJ3pIw02_<ZW)+N z@?cKfdc62aHE)Vps!L7-X{a362A@75<_Uo6ov#!dP4ArZ8?(9NXLoN3cFLr^(!;qc zxQw@SaM*{nAkz+N#fL#z8oKX5d!99b6d53F2(^fq_ZMYHTT{;~UxjbG9nzU{V2yro zvB#Hm2JRg8B8W&AYc7HpZVcco)W1(%x+y%|<(MQ2e4O1;y>6w;y3S=_cB7G#mX>R( zMUg>DAxD`v+);AU7*#~`0Y2L7N1{2vz@S=LV{1s8W436xSmxD=*DjUj4I~3cVQMm7 zx;hx6q@-KbnQt;p-F>v$S9yGd8tdBYq78Jh$Q}y?<y2Vb^Nfb_snRly3?q})B7za` zr1II<TfC{|ftD^=w9}<oLiThsiCodpS2;`2jmt=(b0J(zYRwz_u-i5!^7FaPSf3G3 z^Y?sBe{n)RoYEASQ8cl^JnM^p($hGfB|!e98VVf9M@dagw<-QI>QQV+52^8!H$oDx z<vGI7>u=|p8oe#TKJ0jsXqn(jA6j(RN%li=R)Y*MAt-otUW_)Hxz&d=<vO%5q^=0x zHdUJHkMPCLN66_QmKzg-aIGPSB$#HrE&2N8{^!G3N1!h8;1c>v5}{XH<w~CeV<ER1 z4lK5IKISL0682&yFg3`5v$h4AF`>CGo??38Iph-_@C1_Kiro`!-Kw#?hyKYwY-j1u z6&HJf7{hvnkcyyJm{u?1tifNg{udE1w1o@_v8Ru6?<kQ64=T_lz`&HiN5yh-i@&;0 znC0ck9UHt#>`+b<)qIVgk6XTrf>k=n6w-{vw{{S{(1Pu?VQ)o)<AVGUW#b%OsqUn; z4nANR*Y2k7Ls91{>!lvF0^CqG-56Z2_T!-vmL3NIe5GYDS*VFVz{7w@?d&tFa_0!= zYCYA1={@xhjJ_J(xX8$<D>?8|jIA~X0knq?I)t{T$Ddyb1D0C-%>DBkJRm{@O>_af z&24Z6e|p!~mb8qQ{G!!q&fjt%fa;GDV-gJ(4{UVfff>B!bYbQMN3c*lybO@R;cc2n z>ukX^U#J^}D&YjaxX;qB$$DD^wPzsxH1EPbcg8N{O=(}(%|D9S5D&_msd`_F;zIz2 zeW6W^J*vl{8T*UhW*Q+a*9vkV_=CAuI@lRhkG_N#Ex;0@Ela{VR5$qtKwN{QL?<OD zQdb|9=&t%iR$MPo{fg;X5AObXp~~H0YXA82Qzf?2eXFso!%40F&Z1AvtzM4yj=bbF zu8|H)mHIY5?Pt{=`<epUA{t%o>{!(^H5;^;%s5_246#cchY48qpt@S~_F3$|cg5K@ zbr^q-KT^!_kSDo=TWdoq_X2O&_b(2^_`tgH>>FzH<GUbzxmda{A>1Z7NOw}Nbt=8( zA8TB5oDE5!_JHOFuL}#a$C|WJ@ubtwPxqsfyh>f^E%!VzNy}pi#=;;qrdDHq))zQP zIUIa(@AYR3YV$b-nai$;0;L(|MIlj*#>vBfw9na}!~@z*cW6WxM-v%c!6!nCAGbTJ zOZ{33D->tj`TBTz#nQ#IFCXdfJ5xq4o(3=m6)fYQRBc14Ig6YN_k-CYMEUnOvHSj8 zQI?NZNFtr@1?*eY0XN^gvms(_Z;>r=T1P3`<Pl+*(#FYsWcGU}T$(<5fx*agX|eWV z=GSjjOZ;~7&J^ahJpd+LXAB5+(O70K86_lC@Qq+G%{q+ESYg^HzE%Fuj~XT*U#$V> zUlj=dD~+2_x9<H_#m^PuAWfixpxb;KSaL$;@ZrIKq|xv1fBxT5Y23InfUBOQ;6D=2 zu!O)L8v~_i=owX2G!7r`AlQ3h?=Q}^fCoT&>)NWB`ybHTPAPyX`-RfK34aY3(E&t2 zo`4_K=zqqS;qWQ;vz**%0b<!A8uR{{Q<h7j@UKWNdc~XYD(L=};u))TzvtCIk8oZO z!gV>f#aoicRv$n76)f`h3{c92$*TXwDPF%sLBpMv{_SF?1EV6H*3Xu)SW;Bwe)l7= z(<N!qVr8%~zKe&|x4=_taj)RVK(odMZ+&x#z^Jb-e{ohLu>kQ#<A&3+`_dMug_C0D zbt&&m|8i~uZajT)A+2^_*-0iY?rDuS#t*#@Y-6s9i+MbN?47?s(nim3r5P*#ZjVs9 zsF6cO-h`N8+ayn`v~dn^0<JZJoG?*ETKTS6`3@bel*-A))K8kEuZ$g8;@;}sZemHY z#ip#vpldXrlX^lnLWQH(|B-q2L7u2Lr&;Kb37&~J^QOb0{@F*ui*_$o+&w*4+(AH( zzAzvZ^-G@)lUJQ@I<g$TOsmkY-0uk>+VXEWFvDmH7)^RI#HdfGM6MPuwJOmYDNnND z%6r}GPoH|Q6n9YHF*7u+y{&vIEX`F?<?v6ZI#D-CkS;<oY$;`_`-Av$oWeGwqt!vT zQhP^gOOKCqfadbVMN&b$vny@ipe<99Vx{SDt1VmD>>mPP9K&e^c1(ft?8dxU<|lY- z(`T)RrIEb7dHa@F`P<ws&Kup<(940P4zqd?tLAG64sWMdzn9nxeBBbvX`f|r9#v8Q zNNEyj{c+sWQDzz3<$cRIhhsOUiakjVR$jZGA5tH0`ozx-Ljtg>rT}CBzyVrk;b?fh zX~rRyo+Nx$sL`k#Waovf;;*-YRroJ>YhJ)t<yH$BPn3~~*|S&i$5?p|pw^}fq)5E3 z=}(}ld?iku%btnoW7!+`_CM{HRuF;=a4$)1HoX`JJt0xo(_}=6h+1`0-kEIfn;;){ zm=`5-ROt&vZI*Fy;met%pwbdW2y@0q;|9q|N>J6N?aNTiWx{RGO)0J<_R%2&HWRwu z^RI0$rUK}U$2CR~*65T=;&9w&cBMADn-;^8j{8P;KRIN7OaoBcrq$g3f*yawiW>nm z|Ic$1xBlXWAH=)iBEX<)C%r{M2Wo!p`e(B@S(_OUZ+990aSI9gfoLt?4+2{C7#Q~J z9y?0J|1nNj{yj9REV=J=lgi=OKxPmn5y8X|>g{P@_nCUX>78}#Rp$2y*_f}>1WW2_ z4#p2RY9I7H++a?<Zbq{xqaqKst^tkzg(1d3_Saasc^tlyeZ<^rzX$gg%<$%Ay|y*? zcSZ&j+_RNWH&~*f8{s*%=Q+{X$LqmMT^zG+_8(!#et8fNT~+REc@<4I(bZN{<6lh+ zoE$3b4;}rVh?3J>A77LK@`7+L_>kF;?nmjpSFcUUfn6qLJE6$jIU|dlgRAHsLY?Ap zH*(GGv?Yt&tS|ktH1RCFLQQ_2MGrZ>2F<PHo%>aicY=1MMgWg?>VURuW@?L6qtvO| zqQnI9_z@<O1KG_ea>P&*6V5LPy59SSHi~<$lVT#{k^<*8ec@far|!CVEmY~#NITs9 z6eCaw$k*0;R~>t8s8HDjKtG^Kitw_d-j{I{HEzw0N@e&ka>E_!?S&C^4Czi!z>Og7 zW7nS;BP28i`*@d`9HWbt?Dvn^Xt$QNK`X|eg`rv-brp`*j$Wthyx(ZtEMqh^t9iUG zrSpaL4}hzA#}cjZ6cX8or2`ZU5DNHKXJ_1P<9Lo-_7gOJzR#Q2iPeZ_p$m_`Qe{Xa zdwNR<-o-zCryl~YTZol=k9IU`MW-zJE(OHM@!bo!XkHSFE8#e(3kT(<-!<o={=7RX z9H8<F^r8Rmh|g_mBJ%q$E2cMkyu8A7S&{`_E~xE~TBXCMTBqty8+O%sr`$BIM8kcw z>6lH782V<NZGR8MNvhX$@(koxnP&RF4=W+9H0;xP>bnQargteONu?}4%bN`z=qBuT z1fHlH+4|d30FCuDvzHI?RZwlUGxhAdhTlbCMW*@3Wf*Mzt!8W__ZmohQ<Ng@xI?|o zG^*5Pl({hH<&*&Pj@hg`)2q;a6V;S7^~d+gl352=)gCUZ4t7Dqa&Y`|a3HoftbS;9 z)skOTGtQpBgIOA<4>lrv1xQAXE$&*qjh|uEv=iv%D;G}wfLVaAFX8uqNzdIx^yA;@ ze_8|Tw@YC&yI1LvY?7R7Qd6%1B)?wsqudm_fO7S`^guj!MQKDeC45|Vz_cbN#&FIk zXw3LUz*d5IMmoD`Vy0!|NH*}K@}mRr?AIjFY4(h5O-u+E1nTT*$_|KfuM{R#YF46l z3;Lx&tYw&9AE#ybu}n2P%c90rrN&|Cx96Vn4=J|VO%wg-rSyUIPd4<^XW)m}8D<4k z!_~b|Ysy__wwwdoNuCJVObICG-n}F#t7kvRwhm2|ju`AVz#jq8me9SMJ0CUB0SCiy z-9Y#j(xr>T+JTgbGb#|Sajl)(e66<CKiA=(xTI9e|7f}2{d+HE?5N0hIgcLFPd-5O zJ9Pn?w0DhQ{!r|e%{*CWwp#EYDnj-PGGv*Y)6AAe_>E9)jx-T?+#>xx+T*U>-gc|5 zzOx1?U!Y4+mByNv%{23+ka$kJ7-GRUSQlWwVe&R?B&>8`kX^*n6#kN!UYJ+7w9g1{ z7NpC`(lG2BMXI*n%T&!)6|JtB4aE>e=L&i8>`Uwe=l8Y+i<JvB3N+0a$HMpJYb^3d zoKDpa@#+~WF+yW?N->XDVn<ucgIF=F$iQy;=h&y1R0Q+^#(R%Y;B3qe27WnHJw390 zkZD4phNC0(%2f-IM5TGN5Ht27v0UX<jV9*pwUWi)Z3WyTCd2ruGixoxw&a)1GW#nx zVS(`V&xXSFW30uS=|;_-93lOIL5he~6HCfddQUwg?^HE{+tS&XpmG`63AIY{DRmys zZUCOME1NLxUAcpoGe{U#`rFXAma^`Kk;gE_ODri%+qV?pWC2NDg67%<3GAuTy|@=e zw^_Cr8dP0xuS8Bm`XDI_rlilZ!+(u>(od0DbLP1*f4cWu`alaE-+bCG;}y6g#Dq$2 zXSL#5HuxtXC@8|jArd~W6Di2|pnQ;AAAR>J(+AUKbem%Y<y3R^W*X-jp6>l>(|O&c z`Pw4e;g2O*EpC|v)DBRtUhNzbq9?2|QIaq)t;;*$WqSNzaS>wnqb*iqzV>@I=$nm> z=Ow8_-d4yX846J%c0V&Ri6f$mwa(kxE{@<uW~MfjP{_GQWb?b{rcFy{Hn^Dl8JFzG zl27`N++O^G9lAF)9lM-H+3}VPWf_`Z$aQzxLq;%du90O6p^aPyvpMX!MMqLa+BRF7 zGXAkOgj~EyrEA|tulXWR-#{CBwie?oAHh@#kw#QJFo_CN9#|u<?~1hxxmQ7WoXqD` z-p^Ga>Kfe_89#1I+`2dN0YLvj5DRJ@>7Q7^651u%q6;!khNVvlMf)L3C5kQ<s}7NA zTwU>qaq0ZphUU~)(Punaaif+sYN%y6=|KpZ=E5DF5Elf<7cn7d$)0Qutst|CeHn*> zLKjPg@}*dcv}FCx)S^(Y%?=0nl7>HMXx=)GpRH!5`^|btH?9IP1Pljs#&;kkKTaU} z2;!6%yGFZ4HlQaurFu4N4Bz#$E~H*NqzpHyQ=hzb=DW)`-t7jCZ&N&^2`IiX!|(tQ zFRj@`-*w{OITSZW!nOYG9rFT+7`<jz`xq0lm4Q={0giZ%P*W|ftb*X@ITTSfy<gsx zP5bf~#Bxl~=#iz1d0a1eyf?jEGANyu&S+Gl%qbY8%MN6D<kUezHw81Q(yQW~^fje7 zFP*Kz2U8i62!FGd@zPT1C{h>AVwB^X4@#9GU3ML4TfK}pUk?M<4@S$`6+$wNr;DeB zga8bRa{xX0gzx+$M|^=-DG%uFYtWa;_h0^?ITo{~K0myHBZ&2pJ2w<Na3@Rv5*ijv zkLC)W-$ty%m_<;l6N^XW7u!ciexP;{)s<1s&E(;5DmIhEXGfa$M*voFwdUZqAV>m} zh|=f}CZ82MW>6*V`&IL1*}d75+L<K3Efy0GDQS<mdlKbC`{XIsB7F0#d&!iE{JQ62 zoj%A`y#F}zMzY)-P(w0$vc@BL+*u<6qwJvPb@C0(!Ws-u)#5kOz)wHY4`QInNJwZr z1H%N5H2aD}ad8)IZ<<RLcUeP@+><RwIv#6l?4y?Aj@nkz$ZuvTwx`eUb5YO^NPX2p zc+GK08~iXa@jNN9`NpQ`L2tr?@RD-cs1<V_$<kUfdFz1_q>S3>(~q=N?5iQ&x3oX6 zZY_&p&~dx_=bWqgYo2R(v=5`|&}Wsr)z<_@-VqP<_})$-eHf!nQs61Ek6g!n6Fw@| zclUy06u2>eP&o*t8NVEw-Os;vO(pt|j*LMo`X211UG}|Tj$RGQXspGrS}sN@0O~}C zIaS9Pp!s^Cq(F7kjZYc1dJxbygGn~i%~?KKvD)Lic<pXCV;Ak@u2VT(FZP`vFYwcc zmdsNHR+MFgB#mkDi`z)C!d;lv^vB}%i8OT5K4l4$Z?e`9)*P8rP)sCl{&S&s!KR5h zjL9XX{6%@Wio&>Gxq4D$lV6^SUOe%5mNr1jWuEujQVC<TEM8rY?2s?rlW6NIf?pF= zR4|kty{Q(gEJ)qR7EiQGCHmMntNYZHu{0H>j{Kt0dwkE;^s_UTBh$bwn<odHeJD7h z<K>I6rG0Bh^w``~6B*-r-?%A6((O6j4I5__g3nFG*{*5TwF<lhOFKz={&ZFA-ka+W zOFN@)K4`)shE^y=d%M_C$1!Ihz+9qlQ#U8J->~isEwN@tJ#S_62G9T^1Vi!_8{FGA z>=2{)REaG;xnZ%}Jws=)D)xh{^u-j1B(0@+aFof<8$DF>r!889%Va-*%L<?yaBEYT z&eELm-Ok$8f*DmPm(Xz*SUy0<rl%}g-q_V)8Zs)J+7dpU#p(B5Hpy65U3?Wd--#3p zR1T!gmR&Se<fy4(Z<b}}^6T)V2{6C+dE)vxWCoVaGUb=KN~A|0*IzZ(`Msre*4|u* z6C&7=$QTGyF<5`_BMTENac+V?*GMd@KUYN@QD#T{lbGFoa^)Elk^24<2~s*UHP1ki zQ0coJIu{wYNkO`3t{&{;b_@-g7UJ436Olvzi`aDiP{zkfrCC8oGxu$@j}Q0C^Tg_n z0YYuwg}t}>@pRO#mL{SZ%mZ3(_qGU^<|E>?1ud_~FWp+TueyIL;GmHqKHrwY-9=%g zrX>?JCL;i}xUg)lL?vw3C@F5H&(zOloJzi8t4yLi&<upWzBt0nA#xJBsTg23?C8#; zihKw!B9NGTb<;1Ja41TM{h8MZO$M_HT+zP;Kg}HkKR(1q$H3FlGJvSwfWQl>^fwZh zYWC)Xxho?0O|A)DD6^<823O0R-WvMdoLBR{#FqQIbCoxn$wRH7j?w0q13%*$=OVT^ z^h5|5XZTJ#CWNapx2e1u-QLBGjM~3XI?*0}%MOLUs5y_7m-)8mJRp&@SVWm@*~y>U z_|7jdtE7)~i3Z8l*U76(+Seu5N$n#Dd^#TV)sd<%iD)#rjtcoP)ZAayAc<mqj(BmT zxAg}3IMyz=>S{X((7pXH;y~EsnH%oK-ff|r{L41Kn%HTlNn7H%mc$QN$r;->&}*$5 z8%)lV<~X_M3tk2GkNKL!74m?Ey6+48!XS3QG|U1c4GQ8xNQ)t59)DSWf<^f(cq(qr z3k-()wwJAK2Yk)e;6HfHm^^%FEJt*C6dZNynwLvV8nGsT)_}>5W~st2KMDH&sYVjY zB_433FoukL^LEWbo2;(TEHDdYAAvHjM?>8mTHTgM?W2&4o2IG%4pbDo15(9gAts1j zF0L-3{FpjdEAurupGm7TUCjd!6onft%-2%Ya>#;7^aX;Tqh$+%!|L<RYaz)s79bzK zmmO4Ko%bVi^z$y~YN9?u3(~5W<KSGtm99)PEl1G36nm2FpgJ-3Awt8}C7<|3@ezm} zRu!m0155TvU4OAVlow^fx^*4OoTnzQmU0zvR%fd5WCAlQfCX%W!tBYgD`gz*7rwh9 zU}t1v`?tWEJz^cKax=?0AaS}P%zfC0sYUb|8%q?7eD2^H+7{76&}84&Lat@802&S2 zUYg{GX(PBthL5*`Ju&!l#6K9#gaC~WF`BQ>+Z^hs-84bVW$WZUoSbxL0$2PEL{Y=G z<<FwrUz|!7xK&ZW?j`>82a&%xaFVI+-R9dH7P!U@>yqTH1OU?ec*AEJjk7J-p;PLd zPFe!u54L(}m*Bm*;VC*Milq<$Uw;SI;P^K#X^sC-w&J)#VfGb&ar{}X0nc}w698%t zW^L33zaZVw$yx)w^z@Hc2yM+ckP`qF@wAE?;489Rg6{wG`F9%mhJ*M-cCXCuOX>@E ztm$d7El-+wV4gQZj{tE>5DU5lvyN5qf-bZG9iCBJiVOPZwXJ>8h*6C*w>!X`+|;BW zJ4)~0PFbD%GUNTlNw2}+W5<-J|8K4Doqdyws_MRoPoo_=VpDJ)TJnD1iDv*59Y)Qt z2a1<Hz^ru!U2_vkf$aiv6O>)H{_Fg%OfJWLG&%+A<!?nDp=m90#JxGCRFRg<R6xz+ zj0LEJOwxY<di(#}0YjO+mJV4&dlFcWukI0=mkR1zbacpBQ^$W)^A^;~0R@-fKDM*) zUr(Lq*`2k2b1$uS(J5&q2e2N^gf0A^`|<MJz~yg)ukeL#0VLr53w$*z@F&Gh(SOO) z`E;-pU!lJlyDtG2W0j#$1bl(gWx{_dGo)jHf)&a*i7%_>3q^ed0jE&|YEr*|_AA2g zHv>-R7~o;3#fsf=gaHou{}IPF^5rC(Do}YGe9EQ3`_nPtR+8i5al-{XZj;i`<DI`a zmLFtzw{L*+vUoxlL~nN2QQt=Y;wWta4`0r$OOXFQlH=O=r`u1imk%Tz<#rlzd}hsn z9wQL%zP$&=-X@?6u#a4!R|MU+*DOe-M;I2Yf}r9Gc-yt0l8_aAzh;Tm&TA*D@ab}_ z&++sBZnQ=4Q{Wcx00pv&TbG3YxU4MZ(jZf4oqd=R=|m^U3)v)fo=XxO{TsMV|7<E0 zMhv_om4W--ZFl2@%hlU`LJ#x=^ossqAFo52I<&+*ez!;h=^0y$>%X7#F5#bj3$P$G z0)PmOBmg?giB<m&g-fSnLxAQ(6|ZJ1kaU8-EE(_&goZ#r$3+L;y||A@H3ckc{&_;6 zLG<g`P$2+^If$9Wm;Sf=9k><$?xWI#IF1j0aP^Jqw<f+Wu!Q6I8k+&qTf(2+XC&Zj zz!o)M@E_Mj2cR%+BC4VLwdJW(3B+nucPiwU)!h}mLqurg>oflAZjYP&8%tU7&(jub zRWyfZUNcMG>$!g{oarpRQ-tG7`Cn(QDfx@DkpNuG&TS#oU5LbT<!73|!UKJb4iMm( zU$4!-6Q<1gHm=uU5A=S|f16d1R$^t#ror>f-Vns$149G>k$tcZ*_d%*aBuHS%F^*j zb$-LU;Y9)F%G-e3aHwMp%i_liOH?{+{Xpou%V@DiAR_GZkCUznnJ7WkVH_f%w4Gt~ zQ5Ig>bRWEXS7#JDt^poUH$DydqMv3G_3FPM4sm^nLt)<4@#Q1EsrL6?M)%KQMQ(U8 zT1Y6-Fxp1o2~xjh-tEY}QoM!J>B#MI>xUJBCUt}A(3TUnB+X`>h6-VQftCr9AXT)- z2VWL^jL@L}ZZ#yqD4SN?Tx?85GV^(}(-FJq>Ypx~#aGLeq<5HoXx%xM?nFoj{j3SW zB+HN3e|uRl#=#>_<;R)-tw>5fhc8Cg=5otm+kNz=trz2kz-QPrfn4Jm=r!z{RY>)> zjFT010^ZGLrvd8Hqb+6|wUI5ZQJQ`5-9`ovGUu!G-YoF5ncR5v!~Lq?)9Y^uW`_As zsuz*Y!>5e=&wt-XbiFE`v)KV&u1sB=K(5?n6wM$r-gH8gFHxp7FLt3fBlgr{KhEoZ z7NmG}ZFVGfdV*3#KA{ou%bu^bd@k!et$=jN_j;%#R`d7k2&K_h^9n%?&mUz>pV%5@ z_&~xn&RvgNqqXd(i<3Z_*qJ8-)#!%j{kU!pzkcR^mknUF<5GOvlPzR6DlM|cUbr{? zaoYd(fId*)QM`oDV?FdTT~u3W27b&?OB>X>8Dtw0FG@<Qmy%VaPa!2Ui>Bf>t{|Mr zIo^9wq7ImqObYbZwrXhQ<gF?^mY^3QT^Iwdglg#PuS=xgL8I_MYuWy^8K&pDjZZ|M zD$QT_MDB3!g+zVsEB(n63@{n!D}!)RdNaniWxf-i-g#qUV70%mjFvI>Aob~n(l_}_ z^KS01TV^@G$?5X<urCTeF^8LP3N@qr1t^qJ9uZjPAb)gPl>Pk}w-Sg?udZK3B^P-1 znS!O&r>!5N68*xUh{PoQr&v^_AxS!xa0`maiGtQ$L|&5z5iT_1%{HtC8tKzw_BC3m zhx2|D*I2b%sYyrM>+H8YEORA4dMRl|qZVh;?bna=c7Hr<pYifZL1ZivHSQJ3ULZT} zZkW0KF|O76Sb90NAs?E%Le*<w>ex#@QCE4NoMNn&a=J#PSg^Ym22bN9D>EYlQN$SY z85SM1&RQ!vkAKfG^A6Yc^OYmJ*1`VFVd$a?l1BkaaMTUmBxeyaO(nL}k)`WgQPtC0 z#ElKZ4)OWZG`3>jR|H>YbAQey(`1N62i#EhZr~rxUE2hy&IS{5HX`Ei2e7o?=Y_;v z1tgr<>d?HaTFzpL%PTSV;mlO=p!7f4&i>^4jnUU&;LCasI}SzZuO~nmu=j2(Q2Jrw zP@F}KTQJv+Vl<Z4qtT5|KQ(FmR5#69<=Og<3omSh_TC3-XoFte3aqB*UoKgtnPA=< zxvtwXagW93XOoSqe0>G|S6scv_|EhBJb5O@tqsCODG^r|Rd%MraJ;Q0ZXrtkaA|Lk zb47~SY(BAG(`+j6VyieFk8#k-RB`^!n4`0{h-+$vg4w;`s0S<Zz0z^~neqt=CJ7aC zOf2@+Mk(CJu4Ly?Gg-Vf%P+u27w0A>v~#Ia?MA8mvNIUb(%=y&v!Y{`;=mQKyky<* zxR1etGNb%D`3%r^K}&;dap<LTtA3Xrs^=CN+!^BjS&x2}h6gQc&z;5D8Fi+s%^eEm zH~YM~q?Y6n(`EM_iEDbsVeL)Aq-A<fB&m>M56g;KyncFPaho6~iav!8h9ca25U+J; z!aJlTs>*-0?GZ`Eqd`L_#h^fGYCHZ<wFA2ZCiWESx{7zOV=Tm2a_l_wT@-Xs@!=qI zI6^40Sh{HD5Ue?KcIbZkqREw;^9w-Gw;22OebA#d+nMtuRI~ILoCcr|Z-g_Iw`pl- zVY5|+HT)bSh&dUbG7idCP(yxhQE{_=c0luKHzkCoSI);wve$l*Z&;M~Y=7xd-%Ouv zfhv(rSP4(>UW<AWZ^M>)N}08u@jjH<E2n<Dg9cecdn3DGhZYLC(FiEE84TI6)HZt; zVfG7I_{qXJ<)!h)YkD~yw89_^iUPDy8{J{)G9}Rs9xPxN1(CM;_Qu8-Q=J3r)xG2- z%FHssLw+P5eTpW)vzITU6utyz;rc(aSm0>%U!1;#`}-0xa8kTKm-PQ1dtdz)<=bzI zq5>k)T}p>AN=nFxN(&?1jC72E^dK=vH`0QHbc1w*l2XzjLk<lRGvrY7J<q$(Ij_3U z+2`7S!1=}NLayP?=b3x0d#%s%S8_d6wZB7CIcF4vEP#iK1lV#x=BYcu3kQb87tA_6 z%$h2#!RyF%>ZFC`g{PPSMm+7wkUP0#vP@*Kg9kL=@CHhX-1tB{uF~VcX@T^NY4xJA z+8CjArJp#_tQ2hX(k)@~B(p7Wv9@<Duhx17O}(f%OgSyb_ChjkVHKrAYqTw-V;s{H zGt;X9Kqy$}!KE7Jg*dH;3%2R7lfgJ6^Gzk($Z$Jb>WpSjk;QP!qOq}tjFP!Mo^l}$ zI;aQ9fQOt!U`T&TlcJ|)A@N2SNGG%N`PfQllXg?5cqnLU%w9@0$U?a0t^CxfuDJMv zZ;=F$k5%`cGJ15j@nM3)OkFc*F+O{M0o~A6l#$p=Ur=L#zi3VG!~An0zP*ekzgK?N zv3_$iC7Gn&Ql6+NJ4YJqtrKIYdgDRP#L>Lj2}kRMUeICri(U(7W%pb60ySjUIgtc= zEX+=sw^y8-;L=*`yEy|kN(~YKT-OMnx-0W5(3)OCA*EMm@%Ti%7e}??z&8l@kSZY5 zD7d4>5+oUS@-~=FoBx}dMi9N~XxVXp%{HHAl!J`|t&FbfAj((TTNE3#ydScNZuIs+ z=R9`|J2|&pC@|06oDyCXZA&p{I{cPX6ZST4`0c@5v2<N9Ie%M6)w3YZ9^mq1h*7<5 zJRcp>TfqnqfntZt%1#4!+@7crUlFTR2@}r_gqBt^f0~tpiSI2V9<B*oexMTxC?7>Q zAZD7o+a5M!ID5lIOH|eR_n@Rd;U*i;TfDaFk{i6R_OB0F4E0y^j0NvJx9h^E27Q5x zcRumZz+PLS+iN59?MLo4h#*MkY{>QHJY5Z+zCSK|t{y$K8qWW*z`dqv+~|u3f21R4 zn(jV54f%RvUPQcZfv=)m&m#myy>OfZ)dn3euY}=}nsA)+xf(N2EAX3{b>vr+Hs8z> zrU&Q`c0o)6`Z`&=roq8{t$L$HcUZWzN|gCZ(z1?I1q*7^taT@4$n<OsK%FrC2QA<N zIn1pULq}3Ob?K40s{qZw%EX`Y?q)n}UR?^N?7fxZd$CGqkXP7e?et(92qoOG^Ih!( z3q9Js*2{jyFez?B%)sJZ`p!Y7XwC<fdy3;`VyAKX<o;E?(jTsFqIJJ!h+O6RastYC z@-_@<kTf%p=4~e#ooSb=XP4StGh+Luu)JD2Y0JsQlHZbpqCa0GOxv2#4(_tT65@HG zjJ?pE5O7VxI(d|CHU-KEkFAL78q^itQL=T+$<?{o6Qnaj)=t<`&}hG(E9r#Cm_(C4 z?0mb<QXq{Q`rcaXUi$>~{VYDh-B~>X*?;h^5bMn;BaC(o7Y_I2lve4wAT+ZxNLSz! zHQ}OrBXc)CT|%?#$76{}PdBPOx*?awCYKVmpo-u{Ks~S&<FDIx?JB2@N}&|my{w1A zdVLm)@GP_)m(-JWvdI}tC#usQTc%&Xc=|%C@x3L_4Qucc$0KigbVk%t98&Z$Npms% zxpCEn5`kQeT$N!`<j_6;<?X$>ABD}?u^O0fLdjO2Ua{6OpYGlS_1Yq=h)JGx3si^z z)&!dc4va}AO+lVvL+$k!jo}h4g&YU@h^jC;1<|1yx<eL~@FubMD-oo41J<SUn@yZM zNFQ9(i9!SMljEB4dF1>v3yqhD9rfY|&msaf>0<-@U|oY%gQ<ypiQKoLEd>sG4Gr8d z(LP%4y^E#+l?u0m{oF&NU!+M2v?=Q~oJ`tAV#4GX`=#U2T;&X9MpiT;iAFD07}O*A zv=S|HBD5>1`Lw!TDWwAf&uA7FtemaS3UNv9)Df|bw!kOZaHZ9zIG&U}E`MwCUP-2o z4k31%DebfTK7JIA8xZeJ03jX{myZhUgfgQw?P$+kg;{sfL7mCtN-iR=am(~Av2S(; z#Y!_g;*<yme|qRf;HFp^Owk)VwgoX%c~?PGpRxp#nM+ML8p2iPjbwV$L@2Y6-E4Dg z-YqoUr{wH>IE}xc8|*B(OXd!0r~XmF9T5qp`1sYhH77`tB!8Z-u6vnBg+Lka<uPma zbV%clOm%3KvbuAt#H%9e+chf}?Vd{7Msr6S!#rM`y!{Sju0Dwd0O#fy21PgGxUm&0 zq$i*g$4kx({)yVmo&B1#Mav8Ax#}|$tI5TB-}zbH$3Jd4=~EB)mDUF{UNA^GJ&d$a z9I8n>9LE3-+YT4d6@D@fhd3@-&!MI(EQ`H@1a-dpW@;LeT}H@BS7sciqrA5}BiNKq z?II%%z}ZOfF>r3T0*u6e!t6}uRCu@VqVUH%3In%u+`TsH%Y<DrvYWtIS%7Qb1Vp8$ zJBTROzhOOI%-43`jm^xdCWfzx1Oa$(rG^XHZzKo1vuEey;6KsowNV{NB#^au7yPT~ zA3Sy~04D!|WjAXnmzP}|%?_@|2)|38f86um0@I*Q)&u7H^Lm^=tg@75gblr&ZYPzL z@KuPN-_PaX_|guHRkQq8eKmk}7{=A&xoY3a0|=$rnDbM_)s3mY$Db%|$d%ox2BVgJ z>s{6Ha(BMxo!7{J2T`B<d^;-rdzJv!gQ%tG0B~P|m=LA^lRuGjY5$A4_<MGMFxKxT zzi@4=XQ^ezbm$t%FSrS>p673+JKkTLZBDb6Ir?ii+Tf@CRrnJa)^9MMuT(A`{ON*5 z%1Nl>aqOoXduL6)BG*RLjrRXq@R+|RNA5ovzr&?CF#ZTz)%$)u-k-z8t(i9JPl0N7 ze{vhwe(1_BLC=7TR6oQH@Id~xQ^a0L(_9M?XSJ2yJ9FO!NTk;DSGTUHfBd;)3;*U@ zZniT34Ap(`FBIa4rre;3uwpo(Z)`2%JE8Rawud#7ITOO`2w(&LVmR>A%1CbmAA3id z18h?gga1T4$&X~C$I>07l2Sf1$q)E>c()=L@D{Qg7ylYP>t9QQhy2^~y$GT1D}FrA z@cmw+jQZQN+2+U<mSgVAdsF}59g!n0PQX2W4+Vc)y#G6P@9S$+Knh1DK*FpFEglcS z1Z$-Mfz$mYfN6s1yW;68Eg`UnnYgByHKTdg3<AJRDFJMwLLhy#5lA1s#R`OTj4c8Z zy94T>X{D7I>=D2zl}B9$xwzu#R0OoIJ^})tKb`An+hL_}&sk6U+Vk+-Tmf06CWheh zy#wM`<}r2mwC$gvs-LgtRRYcYMEnA1Ldozyf56-OR|G4+KR}+wgn<{qKbnzC<^Rh{ z`uWzsQiG72hy#K;pbKneldAu=jN<XfVGx(Wi@3&$gYvpY5G}Aw_P{VwfjX*qgB8dM z?0wpuU!bp<KTm+!gG9TA9<{10-_5$p7j($W;ARkLu@tyd#G@5S18W?6aYI`C(IaQE zz)N2&CmN`bUPIbFOzKU8bu-`iCBrdkR#iPu6~!bKGc4VvAyxY5o~^~(0t=^Ra-bME zYiHIrU<C3dH3TGEo}(rUzdBNH=w#fjjCeK6**=r4Ri~A-^hNMJt!)A-Mg9~onT5qg zgPK!?a5cMt(|tZp*Pv~n;yX^^TnD3l+tb9j!*@ng4_TRLi{PYF=9S<tV_Fny%WQgA z!Xmn&Vh>%e=<<Tl!CmCrCu)r~=FQN(L2jySJdSVJ>+~{QMALU0iJJCaymuhBb~Z7j zc6G-u!n)-F@c=DyKCE43_iPLl!pn{Yo&i{+4#yTG`YCh?=Hli>(&&d&xIG79l8PEL zy-`62B9AV<6vFB+XZmN7y*bWghAU%Sp%k<8TdD5NMTYuYQ%VBqF)8aqmgXMG^%jO$ zgJbAvT<1Ls%ZT!2sP{{tB-^!Rfwx%LOUzVq4i>6Vi2()d?8+w!zdUG}@-?pAIxv!j zIZ2%fsZzaeQKq(d?{pR4aVEwRt*uODeG#e=!|tq#1jX@+T&33R^SV^L)AcUN__cR< zm;Jl58huv6nnT*#pL|r?&)n?lhn3UyQ0!_It&nT|+Y(x9-CBYClU>Srk5Ol>c@RC| zJph7W9DADEnc$ks*1>G(VmN^^?W4KpTxsa5^olz=ANoX;%-2eFW$O%ota6a=Km{g? z!FO$aMKRPd5w)H&bns6qm1ye-YxGHpXX%za;c7$V%24Q@jKu@R&hx5(sI6vv6eQ*t zg2eCXMS&tJc5zJKmhGKS0Eu6VszcNJs^~>kJ^P*Y`q&)UY;9Z6WS0BEtF|dya-|sz z<ZH}N{H219MaE0Hi54l=PL*Li__+Fb4U`<qrZo;46TX=vf>+#R+=Y30&$1!>O+=Ww zR?Am#htod(Yj|o?fk{G6#A<%lV_C7u30g3Jcu`(b?79+1dd%=a1>QkBmGd13#~#-O z&CtByykol>u1c-#=NYdee~AuhQtN21f0@Hn=+sQG)5$iBX{Qw1zO!n~H`+{HNWTe` z5GTDkpEtqJq1m;qJv#dSPASn1a(|**_3f5me`vL1;L$JAAcmNjOWP$M86uhCoS_^O zJtO^2#%c-5zCwdJwE#~%@sFc^o%{@0=E)bLmmuKaE&RM3>(bL?5=#q+LtvIJ%P}NI ze74BEhIWu>#1M?4Hobb_jr8<;2kNZX-_4$y-<+<~O|@S|y64ymw05_YF`*&!3Q-fN z#DoLFd;X;N!g25t-AHMnp@N_S!$c|Z{<9)2ofb>$9Pe_BJulCI3NP%k;*+Jf&k`*) zL~!WgQ3+~N=PKP!z3VkbW;i3w?t*XBX?-;zT|$klLM`18c{@jA1#A!UN7OU5Q+S(W z4m+T=H>aa;td{~~do;6J4egCS>aMe`{%bS~gfB?GeD-K~c|Ga+Tg^946+giwEmDPB z&}&DKaKx>4n-n)vqV03${GwbaHe4!+v;abuN<=k(HeO_zc)d&8a9#T=A5BX;ihK8( z8~U*0JhKx_jRh%V6aqyjQUze0=e12O9^@)S;d(!o`bWR#J?~{}sw$#09)v{V22BXC zQQ2^{=@V&;v<E2~s)9*4&u*!AQYyR(HVkgeR8}&*V25n<iKL{3_Loie61)+^AfBO5 zna44V*Hj3vl32HkB%Y0|7pV=T6!ORmr&*-M$FL{Y*7H?fZG6MAz1<j72{!fn_J9kT zf+|)v8J<zkT?tC&<P`m0sM)20e`{OQUu(^Hs!N_cAhTMy-KvcHB)$Er_ENRTcQ94j zgztSpGtfh%U2@WhLaD%17D-YOb7^&!A3M~r=)tpxDxkUVF|~Q8V1R(HBj{!gVWk!s z;y%f}%5?L=U%p$A4O9{4?pz?V6}7c&9Or1``Tig;iFcse)49#~yIv>vM|V%2-Q7&` zY%G1A?=<ul!lpf>O?0G&A4~v;b+Ir_xC+obvMl_i1A^h}>k+>Vwf<6{X!11j#j9bC z2Y3TQ$2vM~_kjGy=iM2+nCTExRUO2QtzP+Y&PZ#us6A1D_~$0M|C8zaH~p894YG;l zf*i}mXLVqb(6Z$5Ji_K@n(J<?jq3WyR}n_jY2)GZ7yUw!kY9It1(x2?%kg0c?`%H* z`7B+jC(n*9HA;8&Z91}ZNXdDsO#79ya!!764{q@6*NHQBcgYc{Gd0`U&fpg1h1$C~ zNLBFnc3RtNN)EM*(^_<oJZM&>8khd!7qu>ujncJwO2Yb{l|+UaZoZ_@jR<5&{sz4b zHvyEEh#H#u0=N{897-yf`EZ;|44Er5bSk}O=<~e)CfSRk6TL~LNacCAjUMPsW|s*; z`&EiBA6x~3anH(!O`k-e%pJ0Q#2#5Qe{YFhx3uY*mnWQBpY<wgR&B{0V(tG2@2*=W z1D5zC4_mTiEd0!i^v*0cp!1|&NHBjiolnA*S(5I)Zk)ubl}%O@`yumF8w&6v6Ycr! z<pv0GmtGLxhXgI7)W9<d>s#Ze&}NM2t$h}&<wiTHnt$*TO`(KXTA_|*G&M}8C?rbx z=vR{)kLHOeJE5ddnI<X2ctnLxPG_G+q8zu5=K0V&y8@VKO{#n?IK;OX!5c31sjgL( zYh|b8_M&LTkW+P^u8<HZ$oC(-h5J2pT9qmSEhW+vRgw=aT;EW$XAxAEI);n45!GQM zmIMSljlYcLMHo*VS5U)f#gl+T{g=`F8k%X9cX0%DjZLXTPMu-)V|x8Vw})uKE3DBn zoKtPQaIcQcTfWz}kqfcQMC9>ZwBm>vj8EbVRTnoVVY$ZaFv0ux=ejtZ)y2ie7NgBt zxVzWk)KRE4UT1lkF=0EgOtw$2K2-t97h@iixw8rftYJ6;>zQ84>7fQ|QVI2POhb5F znNE<T7D~R2P2kEbw{YwvKI-;l5<Tvm%5;~qMD;>$9)7F0L*_<PL&LZ?rzKVWyWlK@ z3xc}pQ;~zCmHu9yC+Xn2K84Vk^qEt1Y<9HnSKu61!;B00d?|^1uwPNeJ>~7RytTAQ z^Km+vmI6R+wwq&$oDE?gvzwE{d9tJW`_?(!#zZGmx9d|G77bh1Gd7c_MveGen<a^; zjd-P$<aO|lZ!lya_tt-?KPerIlq&kQ<D*dPnf7Q|$EB0VvN4irbKHH+cURH5JwzM5 za2lXge-hV(h(cXHU4FwNRQqNdY*?W`T3l>4@#_ag5MOMTHeZ~{sC>r#i2}8pMEXAU zgcV7rwM58Fawlyj6@Yn~GlAN+Na$Ua6-Ch}&knYy^!7ma0@UM7VXH%5f*VxC-<w+D z^?czbTElB2L5l+=dph(tu8J>VD+5n-QIn@(($9-k%du5cx>NVYEo@bja>oWs9*nC! z$Ge_l3_4e|lF=QRY7>P9L2tfk5l0P^%rAlhqy>|jo+QQ*Ie?Ia?j=Iid^LOI!v0xx ze%JkOdhU0XkTT9(KAM)6D7H)04ZfrV@KSnh3&XSSeA~)Sdne{JVTD4~x5;8XkeVm` z3MBD8pR~1eUET(RwqNE%RQU>|ziV_&*wRiv6I)YO>nred0eQsASb90n&$RDk5;w#! zb|tznr6$3iB^hR#^K}%Lg(l2?Q#E4|e3X0D>dln>%XB5ML^oDKGu=p`ra<GNICLcx z<JbWv^R`E4M%dT*sC4?0H%uIbE;rXVNSb`9+dUx?d{JypUbY!pnRr9Js|xZ+am6E~ z14rWRftlT$k_2@V50Km%=s2f|Mm9lBZneg1(u@;vw|rRb=1pBjWzftxog_rcjKmQa z$~=M#qo~>_l8ssK=8x^xlAyOJp`T_$S=FjYoV=b~eNr~FT6D5PcZ&$zvsvLx3`r#T z0j(478YaaJF5Y<~A3~{8N|-x#eBa!4-^zhY*rcqQJ2i5o_ifhM%?VGAB+Hd8CsOXt zHF)^X%=z)r`EI42N6m4OZPTrL#&Uhix>f29(B`)eq(M%NYWJ7WZub=)mRBZZh2{)v z;@=cBsMO9;@5r^2r|cLnQU26bQL0_Ud0WJy#5?N(?rl?tspuwo{?(TZ!QOd7`*z?e zoj&v%%!%nbITbPa0V+z9Bl{+sKBtZ##gjH-4P#?tsIiilmkY<Z>V41r!~x+-i3dun zah@C#ZkNd!>yw8qQ{_TAzK5rp_6OazbosOH;Z?f!r}o>vnY>eJ<_w9PGI~9{{Td04 zW(j6#1-wc~UjBZK_}VpIsrv8Odff9kL__8|VJUJ9<9Hdu@eiI8_=sG;c9nv9{9lQu zRsTC4cAdWf@PY*ZZ>sVQ;QpWLTJ^th8)<a=q#>dOsEX2v+-z~f70+I6;1Yj~Tr<EC z1I$b{@M-+ZZVR1ue*hRh_y_M8C`9|{DYGg77OA9F0q%l7=2RCb%tqa-YrgDwcFhRU z)P7D@F6nnWQyKVtUj3CfH!hIxub+7E8-a{fy#L5}okkepUmYHQzVWZr)%r2;DkXr& zOtvnA^ox<d{c<9By7!mc&q!5|AXhhZp++I$KyRLij{+loN<RUhNH-QDptXN{;(CFR z`U9epiU5FYDSPwk+V6l@nC};9w^IS%ihuB`MhKq#YYuw-5v%;%S6-P{M6kkg=%3NA zude;+i7UH3j8VAsbC3xG%yeaVPDen?dZR#B1Ykf!2q4PHy1mCA@}K^L2mg~Jfr;^> zM#JxZANKGz*rm?_B9GJu2;KOCQ@G^M0=~)qo#o*tQGu1+Z{Ij!{SH`d^dq`-nmAy& z!#ASQB&B_klt7GWIjD>EfF1z8<q6jS1rt$QCJ?C^@0<BApWHd(@?7;C5#=HR5F0<@ zLE#p-shSisc}DkvG|UmeZJ-F+fVy%&5$rhX92Du<^@=N3#|?voYeRo@h!3Ve{%zCV zQ8r=FgE!(ce)Ms>(ISBE_ejsz5$Sja05V#H0DncP9Res>D1E><AFeBKPh%<%es)ue zw3+|Hz$3c5>q18oE48w~TkXl|C9d;~6<zSBk?k%FN9MJEb`^2}Mrjz@I>U7!yD-3U zgm3k;IxVwetcl@|%vCagU~vRkmf_sR0xU4QzsGDe1o#0}mKlxR#l{3su`Eut#+dhu zX+C`Qm-kK=4=+ep5gmotzno|;P;|f|Vt5A}3sf4^Li?=cMASEjmMVDSOWbqWGUohK z-r^^OK#7n4gSRo}IDTpK=fKOY!tu7+fB(`h3vIc&`lCJ;Z{zI^7GUYjbiEt_oebt5 zyasS09>BEyZWR2-DvXUjrHjSJjmt;57A?gt%)POC`8sw><<Bwd0p!I0Qnn;q8%O+} zi3wWC7i~Pr7basCQB3wkTrR!LCD)r4i4fl@z^AikBLuC8Z#>@6C5T^pJv2ZXfq`m` z?i{@Zy~)&{SWTx?Nm?G$%SjV?Q`qQERz1kT5$(zBpQvwsg+vdBdp}w+zPs3kBf&5S zm*pE5i8V#1z>~>d;!|^SJk$R2H6UPu9NA9Z{<>mDK?RHQEc4dG;7U**FYlxHcfpXU zqeZg13Z~=`&Dfos45X^$loO+&sz6JyQZ>bZKq1^APT~DOc=9sh@PTe<HFwW2Is6c1 z-ML7iKVx7pZ0VJa?d*;!Qg~Nsq{^;pi;J*i?=WyrGlDP<h~zKTj14(CYwjFCZ@Ku& z^cSz7t5*vXi;6h1G?RX)uiNV*ZRdFn7LGL1EPSb#tw((;Vj64T=*Xo!%Ww?IPIx%U zNmcUfb{<UrK%1SLNLi^vl-*`Q-9Nt2hZjSD!i8b@Wn-RB7c_+3YmMGRdYMv63v)ev z9k0LvIjH8<XLr5dsM+n=8{*68tv%gtXUyFLt$}uLEukIWJKE;kv9OICaaKj>)R32c z-nMbzh<q;ERsD_kwprw}J@kt>StnXYG-SCfxd#-?0P4CA(B)Q;;!d7VFO$rAB(iv_ zLsJs(pi7$G3l-|j`;&L}q`SH(-Q5>xu;km8f6lv|%L3G?TAChQmA3E3F__y~H0DVZ zj<3gXv`GqVaVzf)q!^2$o9k)my?QbA1Wt=gSfXxN2)3TYAmQz31>Lw)!7e(kTk}== zn+Mx+2ZudB)B{)4iccr9bVPn>0*sW+{*30*t*9kON_g)}avNW^i58E%IpCS^mTbDf zhG?k3$M^}4`qGHF8Yl+Aqp1t3dzL~sDfS>g0p7i~tr-*UNXh*bbj!A#9LH+h1YeW` z+&}{AY<0MiI1gAWXW38}*_@HmRc@IxTCrn6@r9=9oxK356DzDWhV5b{D6^}TyAyX8 zn^=UU>^!LN%nWYhoys54kP4lm4p-sL@n4?F4_+9h*09k|Rccug5~wi)?2$FryXghq zguo?Cu#vaH*b)6DrDp|JwFX470RQ>Zq}yJqs+a2RoUMn)L&G02ro<o1Kdn7~yI0Kc zWU+AxTOREbJ8;v#;`V5|ptXi$a-4hQlNgYQ-Q$Lf<hZK%m}+I-#((e%WoWI_B+}mA zx-KCmmSG8@rYoL=DJ_ypYO$+{XbZZ9CyOe(+JbCS1B*vpi+V&>BwqWDK<hHQK{FmF zWscGR;8C<&_;`I|5dhu^LAo91Q}0ok47QT3;i}YK6t>8+LwrZd`7@B`-Lu?T*bSYv zl(?l_-&}7uKvA-T0q9j!>ZR$0vIv+uV^6ctj+Vja=v60NG4h-ADVac<%qWM`vJ!<p zw_BKUi$C8cP*JYpCqQA=chGNObus&$EKjiC>_5w`l<2(?brEZHWJ=oNE3xf)(Gt#^ z-J+LfBwsr0!6->U&i3Y4W}Rwg*Kptz>s?<8Y^GB61jyB_O$4(aNro_oE2v#qoWqRg zMMo6(95ynL@ZFuC%L+GFWt7(;q|E*UhjUFChId3-XPkB79f)!>tL@c9IdT|fw0&(2 z6Xk}wGdO*zP%%_2{5L<Xjwf;DvJ-2SX5AKHR*sG|vb>|Jc=32Fytqh7%NcIxJ5Fvu zo(N4lZpGI{@BaE}cakkZJ|oUi!uCirpmrqDX)o8G@ZM5*?NU3v9q#6|`Lt_b{U<uZ zPy9b`)SWsx+%ZcM?#$vVV3yUkyq~BihgKfO5$#@x_|6$rbbvx6jblQk#Y-+9GWaIv z!zFtJOj~4qZX1YrFxE_3L>~cM=df$F$SpGZfAC!Hgzk@dn_`8_FZqD;RA9YkJ&gh9 zUinFrtH)`j=*0b8ws~&ga>Zj^@iU_2fw<GRd#pW=2mGAU9>oN6^SN<9Q;$UPD#Ya) zBVmbRvyt(tJtx2HhYt&SKsh}gsI<b3#yiDY9a`yfbU$Q<$pIC~L}%^JtY!&;q<zoZ zh*M5ho5b-XNY`i%yluD}Tzf0_D&_OG%yo3-L^gUtvIW!YLUnELm|np2fov=){P|i` z@e46@Qk04jaE7ZX@RK3`^{(2R98DT}X}o*|S%&)W?n_g1#TOaQ{mg4-%$F>iob5vA z1vN8@>t0u)-y?ewSMB$>RYi5YHcHZmUH41y_SiN}@b=XDJ<Jf}_0q^vLZGgM>{5Uh z0Ir11FYa%jm$i4KQ*@A${F3}Q>8)#xIQdl)#K^I55)2Z1wi>knN#;7SFE(FpD+y{* z@{C05d3TfqvqfIb)Y~ZYr6p+Pxvz*yiR|PEdYZhgYTseO!!8C5VZA65thG1pSlvzI z4qPvigsWV5bFdTe3`v9b&D9F3^XNuOB(&C(==+B1Pu>FQ44l3{#B~50j_+M;IG9|? z*0Xd|h8Mjyl$=!Wu49lm60SmZI6~YDH@=Z9^j%@r(#riT@r*PW3Y?=tq&+S)yzQC* zH=;DWq}!bZq@w5Q^|9u=d}0a0T7O=D(7M_EVK37Ga^Qy0Bb&9KR8=3gSjjOtCkt0u zEwp9W)1~Av(f!+4){aGVit&uCFPjfo-PXb3Si(?C#dTtZ)Y6eV)-_j2{DX$Xi_bmZ zEh6}rpj~AIC{U-dTe-JO?&f}}?Z{S>L$jqw^3-ra*8#N{rGe^+&D0R1wkeaoEqAQ> z4e4jR;G9iUCyC{fl*ulInW92o*u{4jv56YhXOycgQ}q!cCYD#W|EfS9T5VJ<T@s~d zq$5tXrTGoDZz4)VQEnR2eWARlbK=IQnPsV=-q~)i+T*%mAW*3A^O81udjuY%5~GiG z$+yd(tJZWw5gkeOHY*CEl(bDr`0+X!2Q`&yAF4-qM&2IBdaaz{o_IqrAyG1fb|(~a zg2@G247$<s(VQWw)nv8fp1$V64NY-|pI=C6aD?-4edznRl1$vq01CrB@aE0zm}02S zk3sk2_EpC(8BMJVYjkBEL@!$kFi-S)$J(xOlJ_|><PDZMN(kjThD59^2C-j#T*8P| zplME2xwSE^;ag32gKjX|8|pSS&Np#IKQ&AH+z1aSggp9m*JVxH5-#bPFQ*n+>?Qcl zb;2SSY0IN*U$eS2XRw~ytg4OFNk9-`Zq<`Ii8EsE@(Xp17o?lvDg(apmAj$C^^DwU z%AjTAY1@2y$sw+m1|nB=1jx~zUTVI*S|b_8iGT1cV}fwR#_V0d=`5&5fB)#a>V#No z_fDUOC{~GD&`rteW?1U-PE}2#@fJzp?JP14)skMP<qEQ`69ds529u!TZ@J9MxGBY( zKMJiL8X>!>!a4XIB@`KSt}&?dJR4yB2%No!m#udd+)(>L3j|n0^sputT1-lBFl*a% zl^Mkmu0lv7Y|YuEW*%(Lk#zdTiRFxer(98kEjD?!raf?xv4s@PrZRlP5Nil&M*m2^ zAtpmvZzXAY5mDzPS~Dh}Of$WvXyM73B90v3=NAbo!#Rdw34#wxnM{NdsHL6((Mow5 z<PodNTaRZrsmj+_->H6c?tv^fEc!c>k{^_E*=DXkhMU36oXFQR1QTsFzK)dUX|z;6 zwyQ-SSGwIN)L1X#4AzEC6p1To<%qhx1jJP^)%qz{`)9<>QVkR^m1f%)u|te_{hR%Y zmiPP#mjY7zup#JQ9gCEg<i*}H7~`;b)hX$m!smB}$y2i9B-kH}R#kR(l5fi_G4ubx z;rosu?zH%zjM)yqC8f^kynRyJ)+X9akEmf-R(i>2am^xe)ut@1qnO^Pg$%cw$}?=g zL>f+pEm5dW?rPH5Y|0yaG$8ZQ!FQyt&E=uL1h+PMm<8d5CRq6S<H+w{s;3Wo$>2Uc zZH(*u4+r>Edp>Ds+b#%4m2nPH%_@0S*-OZBvsk6Yfm7l29SAD#dqa6CruU(wI|VjF zDl=xbCCa%*TOAI$ng!IlNQKk{a~@tbQIHz=iSNY14eU7D9L2dGehFUjXsSc6j>Blq zht|&g8Da4I)`tA8!yKoNDk+$Iy(Ea}IFX``eHF-!liE7$K89n?79brqQ(xKCd=#`F z<vR0Ev52R5JU93mkI_cU2+xD^>h|<uH*mQqfb~HSqa1f<F#O+G2|)sRBld2X2ju!n z#LumzM|wqva?NgPMcr$Nv$^rq>Jgdz0I#SshE;O8g?7TJGHTo<Awk30!^C7?rEo?p zzAoh0ade|6ZMbWvmpa+{r=4c^SWI0Id^C?H$4#|E@S#Z`Pd~YOfYFw?)Xzf@Ru%XH zJv;gY{0lfO{*9qvDcLQD=M9UEqxl$-_F0;04%>Tp94X&>ncEUse?zvKO8`sXd)&U@ zcttn`pr=0}8$cX_2^CI=CxvQ421#h2N}6ZpIqC`nS^+{pLt+FzF@H+?M~nXlYTI;3 z@wO;VQs}>s81QU8eP_P)3V@gYhU0vY>sJ?<*$9J88+_o=4rIB&Axtl0uv$q-*9;1m zViV=698%C5V`tA{u<|C1y9c;tW<8!q#C`^jpT7tCe>A(rHErMWoYH1$RNC=zN6W{r zy+gBG+U<WpLC7E4k<WkPW3`A5k9V#Sg(@DD4+sV=UpYTJeBWE^>h`B}WaJiLtoh&Y zpB4RS>mR(sE%7a!=-}v6X7S&@(vl%+HE%HK9DYKI)#3b~Mk<N+KPU&*KY;3%&F4EW zFi$cP0$wI9$iv>UTN%AhTw%|&gZ{a^9aHVAAmEe=CA}Qd`F!`&Z%UwK&L$onr&)^p z5u5wfUP(AMCb@p>3+xNJ{?ZRHalS`v%KHiZF$F*gmVd7Ue_poVL;DIgbRc48I^5Eh zG?hWnkLA(uMJ@O5(P&`WF9VkWn#T#CUPR4-8a00cXLV!q9$C5AgSJ7neet&am(~}x z!+**{uF?M9aWQ{Pfoshx0x;|~j@+eaL9wbNhUdY5toGi-;_rDC0rvHu$`C(E$3N%f z4RXFcjLn{AiaToKqJrz8*yVg%;?Pt`5MuQS!6+coxb>MB@yAU6CrW^6)r7ifoYPp@ zurS4bIJLjAkN5`x%cS-1sjaDnp52^BOxI+d6P2_0New`-M-l&0H5Bm+f+#mnFl8;( zUo2jg-morQPR3EpQ{sGCaaXB$<G<;n#1UZM8)hShfyV|&KJ#e0n^R)kmS+(@`f@hM z>MarL^QUwZI+>Sj42zeT7#uDfj3S!?xR6N1>CvlO!-3${+wI4r?df(pf+>Yaxci80 zQ*MyejY@6fPJ#k9fUXIwe*w@$A%M@w%1`9iCm<No2av}b4Ih@VVpUurXIMa}Vi#Qj zlq`7BFpB;~k?6ePKx%Sy?Y*2W(6jqx0O3Oin6)-@aO5P8ICw8$GLpkHK!Y#6jSvm( zgVPE|xL9JWafZD)VU=IutGzx}<z`_09l`)+jTEpK4dK~NK_h`~{)d3X0Q$R863DAs z40G1FYdwhf^-t59*KVsL1j7HXW}l-L&qx6KSo;-;yW1e3It`9-Pfb7I>m-_I=l6fQ zHKJ2+$=Sqxc?rI{5V=;MJ`V)8=C&XAwZ|5-qLVf=4}lZe>CTwavOU|nSY5a~h%NEe zt7G=-eiD-WkUz%9iVlS#4tu~C=REjA|1MNik_gP^bD;T*N5EQ*8uBiuvrv)sNjW^d zb~UrjgRc=j_}6sD{ClW2`03LCKPl=0xa6X=$|C0RH6|TaCrVdz!mU8`g4ga{XhHvM zvbEww<tnp9_2T)jO02okWND3$*d#~8)TKg6-`dR97rdb+C8FD<v&w~5+QWjFo+`x* z<9sZBS8Cajfm?cum69QGiabG)%vTp^mb>mbVrLh{0|xH>o5cOx7`+T{CcnZw>FsPb ze*FtMK5XsCzA$e@f5Tm@<iX+d_tMv$f9eC)bkKAQ2f9E6!z~f6l1zMSVtqbw43elX z?xVd^qjnnJlAMz6<GCif;$O7$%ULDPA#H<jK(RnjYwUE5Fn6D8HMKyU_r*D2x(2|H z|7)o4k5hx*-UuJZuNk+|>7!E*T5cBDCA$N6K^6^7FydXwu~p9X9F9KesnI!z@JE4I zedNr`AoS&v3m70p53L8Xe{*pp3)q;Y(||UXt<$F7up?I5Ut-g3%!jqYOdawm`Sq<W zt<AJFDn!AL_(GW=wl{0WyH{k$ud)$#!^nT|<Z7`JOO8~#0UhT-i9>C9MKfD<l7b<5 zhA&JEFB&wa`zpgptDaJ4TPgxX+R2>gcnW+!5?aF@b_qelzCx?50?^aOh@f}wtwq}= z1oiFXhHA~zsVV~{@b$z}j3Yu)-ZU)#VBtlQM2>>C2PrOi&4jh3i64|^v__vtSA2lb z$wl#sD{seZ+d0oDYfkGvZqQ7yK4ZP5LL0ABiqT6MAA}VPX(!qaY)|YJDZfqUb1hKS zj<mbbyI^@27x*dNBChPh&>R!oxwN?Bn42Gy?M;QD^^@jy9)qhf3!?;Z)oz}JFD=KH z8>>>>ENu4$<;J^`V?$fIo2^KgG?-j)OlZ(95ejk_V3^P?EyVVYpdgTlF{=rNC5oSs z-VHV+h&)hyDRfOVMW-S3+C7`_1^v${<t#888JVkC@KPS4nqbEk-3e5klICA>WQIq1 zGp>x9mu<EQVrr8rO;KkSl^Ig(jw0^r_VU3hCx^QNFZ>O~Zz<*Q2+C|;1tONR$9+c- zHIC7jZsqVtm(=L#lc0&C5->itx;xo<ev3ABw=T-w+$nGN1?rw{!RyLikrGlQM|J8% zY1P*+1sKP$w!3DShBrEb`FGVGp2SDrZ|KqH9%lSjc<2JQ9yaddZHiS-cu<>kY5YwB z60L7V3tEONN3#<@%gzZ+4dTP5#zu)s9vc@($T@2jeQ%FETO+KA*Q4HPueOeqq21P8 zfLkvQhXn_@u!by+wNMuu>M1zd=Sj|q6baf-(sSvr9(u38rW08(znsHDz9Ia4xv(x5 z!0l_N<^V>x%a;x7ah2oYk!ynemUOB=?kzLzAW*))XaDW)hmOr;A;tF1^##w>l%>HB z^EJ)2?X}_OJ?j#mQ$^$Gv)}fyk$>n{xIyMjSh4!X_|8S=&UqUHHDv-TM;>E?SgqZG ziq>Anry`CyN5oPo3wKvc4uaXog@9{C%{}tW?!gncfyeoc2@<K1>)EGKYgQ}VLwitG zUw+@dfADGxI<ZIdtS9axm$n#)UZo0&$qDH#k@|DtUMiQkcs`NcgWV*a&cuU{A~_D` z2u7?Y`U2Ja)t;pnik(OQfHHWCM06QUyvwhUiSV$5E!mb;WLGL?Hzb<fw$7N(WfPNE z31cD3ihlW>*P8;947~U)_nC~my|MV{{SMuQ2h;Yu_AOcqT(mcjeMDsjNovIT23=3J z0#@NUHtCt-WIxQ`f8GHY*qF!#QtS-+_9Bkx%*S`}c4@p?V@(UXeRkg-IM~qia{l;y z`YtGHs5coG=JG&uu<s4`!GsE>q(TiV5^e|{a*=KW@e~a|d(>*v=KD@pNo_Pre&xn$ zYocOJdYM%H<K8RLzQ?_tf}s9tBW>wkx?)r4Bt~Q<Y&D$^mO;&ao2-D7Pi9oE!zITc z(XhdclYvi9)5Bm4aG9pJ@m=MXwg}|IntEcNWJI~xFR99O_!zqpM``HYNe!AzkVWd) zl*tS-TZEQB>~_Bc)H@%`ta04+DuKdX03#Ld8g^DOKpt~9eVK&O2%9CAZYgB+yzot! z!<#o&pLWHZ!UW8Ox*xo;O1V8N@hWDU8&%&4o$>hEw*q4g$8n)q!*-;VXkv0nNfzd} zVavSBH8k#1r|(pRqYPL1R1yrUnI0uJ#F#xiL<F=6UgfmNE)P?~H+tKv)fzD}E8Qiu zL6=aMa(KMbs9VL|&5|1)<g=nR?n$G4A}39O9uL^kA94NUILMeCir*J%5fgsU^_;Gx zqlTT4Q-`8ma=zo(oZhRf|8lG)nLpAqhqkwKCX;AQ@4O+6g<d@`c_Av#gzDj59&dkq zNl=iD#<#k(oG|q=iN{Tq5k`|M!yc%D&i3dG60H5r{oY0LO>tycW9^sG6(H?hG*6|_ z`-9B*lldbXu7)Hv>4t1MCNe`Ot@OR5X}yMUz#=8C7|SAF{Xyu9^>=m$g_Zp+Bf;bg zqf51in+)6`N6oCj&be*4u*Cq0_C}QS!px9|`@xT#?q;5BaYtoynS+pK;j&DD%I`m9 z8er;TRt93|zT#vs-L<&lfAGxwr=H+<u8)oBam2mtP+Uu0Rvj%?y62Wi@Jb$!0Q2J^ zdcDpxCW-wTskKDEdrW1~v$QnNnn*kS9#y$!o`Z^-l_6TtMhtZe!*{F;<ELSIKfQO@ zaOt|Ni2Tjzghy~CtwfM{V99Or+&l#&Uq8S;4j?s^)N+OPymcVKZlrhT;qOT7`VTtb z9HX@`g$vOUS3a{3A2Z48+`s%>fr<CKm~dlQPhMhUG2OJw;Lx^5ZHeWZ=b#g)pKB&5 z)_GGO>#%@y6zb`hs*Pg$cEjR^-g2ZINAL>`S&EAv)!EQZ54MG4f<d9U`~CIhq_vvD z+YdW=#%lFTt>b7E_jbp`;9+!kY2++8n8@h$oo~r*LAhg{+I%|Tsh+-;ci*{M<@ISu z|DcF!w5M0*Qx?;R<TwKja9ZVX0=jJ!K}-XPfPb0w?&|{Oa_%IG3Y}Vp@f_lE4<(hG zJe?U#BZVt>J;xG?>Q=ZZd-f4FU{<)bLP)1%$cb+?hTv;8;CQyvQF5%9pPLctL-5$X z&iKK@nPEI~raTswHTy+Mnnl+fqjFL(>22?Y(L4zP4sRiDqy!bApW7Pi+Na*+)Q%rB zOa9nCR30z2w#~);uxf(oSV0!PrwBFo3UmzZvEGm&+Xj=?wmSD3eHm|2$|fe^e}VPL zF)}PsGAGH^EFF5g@HCq2M>kToHT?6d+){O>vgas|4icCFYb{W;i3V=2GA6@3Y-ye? z7?f*hu$3BA7B$#ufFX=tI9Qh&7XHzYgw*Ee=Snog1ncN!o-YOnD{Xj^&?@IMcjWOA zJ=RRfBQi)=8e2cvdZuRI;TT)fIKdD}0d8~wQ+neMaCW7rv2vb#XrD9>i!2&12`!5( z)2Mm))ALyxpJ{6MRM(Vd(eTdNvocBFg=h+@!VPZ~Ohv~$LIX`2DJ`{3!n#a-9Ma|W z#JtDgs=Thwe?iJnrIP9uPgBf56wAsRvDwv^(q-bQ2SX1s_JQk;6;l6PAlyAH7oNYj zXn^4uQ_V)|tG&t8v@~?9)5}lb-cufa8#$sF&-ao+T>l1#=WvL$X2GRAhC3W50Jqxv zah2OvTd9AkSwJ=JN&<e_=xLrPj+|BHI8Zz=-t{mgKd9y-Tp?X;nkquIBN<VrQRQyN z;zm=BHAB~zy@2|}V$H(eEVjpt{=qZvD5~U2=ow%_X?_nEOJxNOrJF1y(S|uK^t2+Z zZ{Ds00`vy6XHOhpNKP2X8I>tVqeffE5Zvhl){@%41LLb6mKQVt>qu1Ab|O3JFBgj| zg8XudX7P_=a0x`~S<0F=ZcgU$Xrwb4OOT?6-vc&AAQ&;!^<y^LttZ*M*iHxuw_=vf zG5qC~E)S=J_=rvWJK1r4(Z3UzWB8pu{~pI13~3h_@A5JF!TH(54warEW70H8S|v}G z<CIdwa&Kx~UM^byUi1QTN`f?za<D3A_J$n!r3N<36vL&84^%Jdgwl2AV9j;f>b$O? zuaayiHs_R5%F8X|?sGi!+pBm`wl3w9Z8H<BgBU_!c^7xhQI5>s+Kw~7zUm@f;1JZ0 z>LLR}<E?OO$@G~<H`~0H8AfR6iXtjpCyI)%F^bxPv&|*)u;r9vAORz4zRQ#gC~i{i zIU2`5VN*ZFsn)Dm+X~3c208DM4IM_R*`f6=MfG*cbd9vRdHS=xOUPAGd32K-Cspft zf_B1zuebY4nWk-7cL5d2O^G^m*|dKt!Y=0KtnIXt^Cy8ecK8#{_uST2de*coZ?1X7 z(nU@8y^3JzenEUN9ocTR7>VP-xECxNBYGD}_xF#9&m0^bD{x|P2c<o(*a7J{;ccmu znJ~^zaX@s^Di|d&3f@2gsB)&XWSG?MUHV*VRIZI#`aqA0pQ3a$|5=enaj`NiQ9`ON z2i7hnykC_T;CH}~$em;vo5dG>=z5hX&b?q%LyfZrgfw?@Fwb$pnZfN?&r1NA4FFVE zf-etZWE>5EE>dtX_{`i$;r|MtwVjs{DTpP|KX`FZDq!)5;nYm55csn2g!B$>0Jtj5 z8qJQnR7LN6FigO<qw1I;PKfY!pus*2D=ruk(vJ0z2J9Do$E&IC1=gqw(XnIR+k+_& zigTmY6xe?POvS%3=jcEf4(O_1J5KRQIlzy|*ddm_|ATjsGl@W@$gl%dP5RKMfJ$>C z1bimb2nh#Q>vl7f%1%f-A7V8wAR{~M4U^F!7y|hT>-wNQ^LqU|H1*EPnm;nA9+3H2 z(6crE#?`P!tO_GM2G!fcm=3y|i7pc`8(?mKh!G2&zbdxEP>ngLxYqd?KnGn-i`M8G z`_pVEAaTwRq}(q$W#wNp{3T^>25t(Gqkv=P-zfMm;A_ksYJ>(YHlA}Imj^dq-6sud z>762!mAT<1^JYb2>zLZ(PpYFd6S%tj&V-nD!^s08nLmgD-APCLOBL8vW^UWr^N{<& zqwixUuH^7swEio)<AyK5M10t7pKL#(G>&qS^o{VzHsLBNWGj8R+RX1SFHe9!7Y+zT z{-QkoDv4B#_`M|K))<yVAN(1^!5*a#y>vYCdXc0PBLuwvF9O0!_g^`l{PBOyhvD<? zRKBQu_wOrL`kzT8`GtQE|Bs#i`L3e@(EHZuD{t_js6ib_TB>MUSHq5`GArCeNM6NH zIYWV(_V+f$8~n@3)$v!82C2R!mY-+x6N?meY^qzem6+my4Hu3#lU@BslR3XTf;aFt zNvCsCVJ#lEVYqvbAc}IpY{PMo=*d-RapvzO#}{fMy$(E0)0g<b*}V8SKf!kr-Hr|q zyZhytC-&gPduBH6=sX;6@xN?2rl<XY5OR)%UfnE7Dv#H04(OW7fs8@Di<h4<*)u+6 zFFIwbZvT_jvb2Hg;+~KAumbgb>=3`FBvW;C-<7dzvX)9a_?|~q1BV4Q6R9%~e*S;i zc0F*&`=hkc@#GvlLS;f=^-En!WPHzP&u#J~)A#480IBr{vGbJb|C_e{FQzRd)&)b_ z10|C7$?=9@J<HlYm2Wa6h@Yz-yomD@?m~@*E0)FyD)4Ogck+Gpm%Wm?iUu#0AU$@= zE)?O+GGMrHr;dpXIx)T9HsIy>P#WzcpCs+ngW)&P`#v0+FRNzQ?9-lKi=v+bSK~DQ zj1GhvcX(T-zD?rO?7Wy*&!d+;)`*CxDV<}4=rZplB*ax7%;|oU2K8VG0)E)I^d>oJ zM5q_t)DWaxO;2yk-sQB)h@Kmb%(=P_hv103&>JTW6EYk?Jra+u8zW_?$r>N4bubOw zeZ{c3He+vU)7U`8<;g1T`pa$@fA@od6Cl?@-uy%88YHOQ7BO=$y95nvQ9_IDcOj{8 zoLJ8lADHIk102)5U20T*az0SzQ9C#8tQyIuVtI3rb!P0W{@Jp`s?7que{}{7N7M>@ zzrGu5Bf5MTfASVv=CZ;}@M?-H<mDG^779%EBFfU7<K*p`u1@@!-5s$-M<O5UF3lc6 zJzkwzX_GKi3=ys`30j+<S!jo#1Zr8Utw}Q>^FjhDWN2)CsYczH1remJm+rx*I+M@~ zu|6Qv$~dq3VU&TF5`8Lh{M9rH%&fb-BhS?;-I4cF^tPQ{a&@g5d_0n4LnKe_QTl40 zWOY^RS(;DYKY09o=ro0|4d<D&F6nPb7>k_~w$&&K=<+AlxS7rA1rfHQEb!vAJ@xgN zWZ#a(o1%`<GD1MDKE)PuFY6@`nW0$b@)J{OQO|ct9#Vpwqw5blo)H&0z79qbUM`Bs zx4_LQJmUm>q%b<5ncfpG%xPCU(q;Kpd!ZdGiMR1Gc|M#NRq$0ytc_u68WJow#x=$5 z<uM)*>v)nBreAKBs@)ttgGy2Cz-;t5A}N=2JHWRt>BbN!J*?)^X{a=>SbL85Gpymd z96?n6_)(*Un5MB&Xy&fwu=UOKIcHhs;g2sIZuhPAEoaEYtXKmt0Aj4yNj%nNMLpLL zo7tI!qs5j92G%p^#Ad5x_uAk5(yYj)XI2;2Ln5^N_``ROCZ#dL#5f+><I+yjj~K2u zn4fdcaspD{)>u=m?Q=~k#}>TPhEDEsv%UjzO_U5=5|Ub;Lj=2>I7M~IH8L2=iexoi zJWd<WR)}Ps<x7H;U8kpv-852Ng6Orh^3K<m76HZ*N3@Ub#1YBJ2wp-k`9(hVZrQ_@ zrb~Klg4=xFFOna);BO@{L>NBj=jfW7;bpr%SXH%m$9n}w<hkM)(q1#XqX3iyI%law zRRm8V?i{NSbBwfTugJlqe8jAh9<PWe%aMGso?)*4lpx?R;_wQ!giY#P(G6+i@Mgif ze1?Imr7mqFG=MmJ5>8Qz7!60NUyp1%)h6~p-)mCEGW5Z9$NEVU9v>r%huDSYl$=f% zcRry%oycM}FSLI_2^}sy(T6BVpnV%zZa$dlrT_8;)cEy)^@BJ&O{$3;f1+c;TrJlW zvk7+fN30fJkaZSm^z8k-&X03qw(>wVsxrw5qfcqJV+G>3KSVw5*9=^(VDZ#kSLLMZ z84^vIjtM3IhOVbXS({M9%-H3WfUHT40=0^&m};l=cM}D-sZIO0MyKc0N~**!*_WB| zyCl_INt}OR^%d<wB<cMst48;(p?q?8-M;syk!Q%cF+d~AkILweY%hgT^A3dN)33(L zq;<2oa_kH2oQm`um!tZ3((%cd^_6Z!9<eP3%CPx%RqDZH?qK`=BQ&ntJ%eh@P;pwM zf}pMNyfl9SbvYHGqQBY{;W|>+CtbuMEApsnfO$;eD_nOu#;*lhEFOI1NMoQ>`rP)U zB#K4PK>(z&I0O&+R^1v*+_2;!|MTD*3nt)wnl8HBvE%ajx1Ztq(Ii??;&jT?6bOg7 zPp5HfFns~WF;I#?%sPlwni)gz&EZLxlP^Sn_@*JbhL)2SR7f+<4Ukvz#~!r92&{Q( z)s*c(^OB&zMLfCQNC&q?f64t2X;zTGgMD^oV*}RHVbspRD5-K#Z^vf2Dt^~_8`Ce~ zo!#HBT>Nnr!P0z{8xtz?1RL>fkz!wzmBdDd8-0@EgJBS$=T2H!(Wpz-7`F<h)xJ}A z$d!4=MTItP^{W8#6}wMc)^g09%{CGA?nYpXilfN6Lk?+dp`omgXk|m-2LmoRGpqTv zT0hf9CCv|tr4VXt#PSO;rGqpzI%ml@zDOVDdwtyXN<g$Zs2;r+dG6g5Um3?UId|yt zn!P?+RInHud*e>$Dddjyvz#uvP?VE*Y&Xa5AWBV0`3EMgKGpXiqFGIPRHIsD=P~=1 z@JA<VBQ<WxEctxX9nPC#o2Hg@#UJ0rRVYwC9(wSCtHi8GUdtfIL<ae(a97sG7D0W9 zk4m>*R*PBM#aG5S8<$5mk%ovcYjoI%-gmJ%ahf5E6Z%%aBivHN7QkF}Hftb6v}%az z4HMaqlA&Uyk(RIK%uhrVsn7=3O0|l0c77=<b)pV!8NOE+)zYQGa<3hRq-N*h@~yn! z_I`vVMv-_eZvZT+Z6+O7f~%f3LvYGl+`~3+7V?-|@QcEmjT8$6AJcc)1hzd6{0)kq zmzLOW4DHv<TP?cF>Ci4;(uw_A&vq0~D;k$}IA>G$I9bis;eO4mha+bvuX_WVRJ~sA z^<|ziCg1oji9GMNI)*mrb0i2x=VGGkJz-2Q%1xEipT`%ya2PeK*3W-ZaTlG&9ol34 zbFL&bC!imd*f8C#9V{^Ej2p}%><^rO%)894q*X>Y79@F)u2&op+mrT$|0|AgRCFGy zkKI_}R|R)0Fej^}xDLUf_2LF0Vf1-QkpoZ0R7KM$m6%{;p}m~{gS|Hog!*g$#z%^h zCE2&8LPVB|EXhzIB>TQhC0Qn93t2`9MJQ`1qa^E4_I=8}B-yhY`)=%mndx`j-%m{U zbKl>;e$RhTe|gU|?{m&|u5<0@dUfPVWSu&xIx8>Uej67#qv8H2t#qR1r>$1QSWB_T zhYM=@)ZexBZ{4e_<=1=lJ&8bEUL9>+fcm6(gebHDY{cXJYHi+1pJpQPk=3l6=&(Gi zba2y{>(Xi>RY{@MMOhVzmoJX8(Ksi6A;$W$liGYQ<8q$Ki`$$y)#0r<I?Rk`Pzye~ z#NH^`Rf{e&RT2BO(8m%Wf-btNdc-hBg-UhuO-A&p$Ig?LALr9$<Dz_?eTWD(%t9l+ zm6*oc)(<75MQBevV>a&+Yc6i}$BYVics*^EZk1H$5-PxLJ&v|*N>S3Ki!JAovk+!d z8l9CD?$eLr;kcEY!>+xJ=1{s;(g7Rm#mtR564|@PNHWAwZ|XECK1ssMl+w-1fuBvv zq0Lr{_<{Fa%tLkVjp<Pe*?Pujg6_|Q!lZ}J`aBw3Z-FXyh6hW)E^VrHt~1DQR>v4J z_1ax}Rm&Xea$mgNEH%+#OqY|;%xuTp0KL?3a^$5CV#`ac&IuDBjlYZ2H?!^1b`Nm~ zwdtF^sQPii$5L2LbYo}<=OFo`Tm>gqJ1{F_AoEQ>$M9WS`q?{~pNOe^3(dF6KFp>F zs;WuMe#+V=OfA=AEy{2~Rh+3Hne7i_S}PM_s_E0QS-@T{zBGtIx!KZU?upJl$g($> znq1k;df32d8h0vws($E52Z-=Lx1j5mKRK6pZkhJ6e!EBE7|5uUk{a7Jx=)veElNk3 zn%(%4-zxJ;uF=VfX1=r}Mz3%)lgQaVDPvVo7{*oP!siY`4HxQ91>TVBis&;+p+6m? zWI#{DN-N&<(f1yyf0&(ZgSX=h=q~WYHRLyh8NvE_$VS(!u9Yol!7|LtC>v}4KIQ&h z6Y=)rxh9lCxv#m9O84Z?j~g#4H9vp*-sG)m6jxsKfJ0PIg{0NJ95#C{voE@&blkOC zv&`_^$1?gi_3gIMf<LlS%y-sB({+6N8P$%ZYioZ>;Xe2FZBnNGl*7a7tKL%t7Wa*b z4gy7z?QaMKW1Yig5!)rQu(*EIUX7rUhF4}kx9|XcI?N-AeX10!Z1kSz$MfY$?C%p{ zk{C%LA05(;e&-_SEwy2qkPtUy8uDUXbfxV4x%v8-yQ+MNs*;C%Wl&SUew?f;?Mj$1 zoCxjLhRbI+$F2JssBcFUUgUUb=Mg6$l@)K=xFpckxbEn4JXiH}nLQgxk#%_e8#3BS zvfl>yY`c9MjuJAf#YJ{oIsEraPWceSeA0K=imI<T^4AM+-y)s<g@uSk$BsCNjqu|^ zwZUC}4C$jR|DER~&h>CoRJi8Z-;l?#M6XPMQT53g+#GW74E%prp#JY)feJ-k?@D<$ z5v~~>{Wkh`g`!03JRO4cBo8^v@{0^5jN5R7ssQ-jy_luo>9q>ws(Q`9A1jN}6QK}~ z!OwczobCJdD^V1n3ey1;TCFh#k#>@ITvWhaua~gRK_@*esvj6Dw~W~{s~S&IpC=u- zQKzh8l1zMpM*h6yxHDP`J&bH%LCz&3WjmATg?A`HcqHk;@Mi4;ynTmKQG|$oK-uM| zA!onw@*tc`Fx<%c0q8oYu#koHk_JHa&NMFraZ_buG8|l^V@EEPj;1Bihu374b~37b z{9J4^5X<P|r)2pXavK3(qe~#+(PAKwQD0lX6GCWlb)~39{`n$v2%1;Y?#56s`%r@M z0k5||r9gq}dh8gunT6V(#dQ0f`>!jcHqV&7B(?3@{m4-DT<)3U5)WczvR(F<a+$2H z?=)pF>1#J;noEkftYb1=nlE*}MdVpV+DIPD2;^~(C0Vsf(qUwg1akYxwcik*cH|y) zvxR~o3;+6Nx5&<?M@%#*vr+g)ylaZ_i-Tg?dYKhP;1Zk1Z^!_&$?p=(s<oGTG<899 znG<#hZ%~^hvE!4A=p%OWCw1KBBh=jUjJR|-?4+VIz1oMe)B#yd0;9@?Ly%fwkU2hj zEF@vPNYT^D*4>&`r-|9oH5C1}E+zMBtTP29&r;w6sOeCfIl)>;d{?01cthDoZK;+? zDYI1+#eMUW^quopbA|IXjwdf2dTQ@Eq4kDqcvcNU_)7eYxeaF|HJRx7O5(Z;<SRxx z&IfB;HGLR4WA*X0;NqiqSy?oKZx0zn3h7*E3)&jq=O*6{g3(Vo;ZaOLB0sJutRQE8 zkVyweoXGx?Moc-iBa-z>R$VOaq+o(pp2KZDOTOENSRTkDOn*F#c<|0|Nafs7cy3vj z+nMqX`#zgEy(7FF2cNW9_U!i`hD;$pOXh4-wSczZhB>4bRDOLZ#(GCYy}F$s_qi*7 zK~tscf!tJweK)DialR$LN;o!PK>6#LaqLsi8QPe-Nl$3>hl(MtQM0*cc}9~m=7zVj zbPd~5*^*yImPWz#dhTbnBV_Y!?w*y^pQ-zJBJAQzYqmL#RJLKg^&Xcw%^(yL%!cmb z$o*8DBbMavWcz6@(<#kE(+F4i&fU=^hbyy;PRP`Q&m8T>q%vvxrisH{Lqdl;Pg(vG zF_0jPGrdlHuQG4D<NnKLNXVR_%CIL<qO*OcA*4!5I3`?KHo9WK?lhg36H5&*qfh0; z9g24rsxWa9J*gAU2D^s}F>$Pg`ERFuG%Q@5*<`!)I5fh{)B>HDYM)lkoZ)*LW1Cxa z*YckCS*?+a)@y8}BXb}JdkH_c<2VOe{mNMb{A{rs%lSGso0aSdRSy%0CiWViL_V2k zN7`}eTS|PVjZh*b9+$C@h-WSe*-3pyuxl>YZ94zv$erYXy1J;@zJ!Q$gPgJxcE`1& zI)Wz?0=6RE%buNSt(Q&}8hslm6L#?|=mlgL8FQ+mN-d{bNKZRFuZR!+O%gqhX5%Q( zp+QR%uVH_YnD9&+Da-Cv480v=kK#rgpIY$Y%|#ZAtgukVepOcgjFfi1&6xIPxx0Nc zSr1VUE?h8e=Kt6uJYMg}vC6>d+fL%d-`R1o8!jmFBk-p+;$m;LkGG%1(bWg=a$f&3 zBdcTg_yKL<2b=Owr3lq?OQ(!a6`3ZOCZ7!T4q8R^D}Yc)zTtv7R_q{Pb5gnsE|)Z> z7CFi{bQou~QUEZBRzt7OcK0_~(o4j|JL~km#^kwE2z#O}+($3NkC0kU9B-FDM*;<Y zkaAn>Ou6Z(h8kixNcJEC+w5aE)ZX0^Q{Qr!zaX!~{_f_F*Q^Fgg{)5X^uw~yvMMWM zgQJ2mh{PYN%?$jqZnxj-Mk|%va!%`fXT@o_5h`|nj4OY#ABVR**^Ku(r0n)EJNqJ| zqIRJ`j7QLdNdn?^T`2Xfw|4FE=|3=DG?ld(5l%z^p|Ie;bI#l&NTrLQzN6q_SQTG~ z8sRxnS62`35ux4TMZ_6kKd8o?`BGk#_+u3IR^qjs=5wp-XD2H~i0@s`;8Q%8FOSH7 z!45w!bUy*@SR2&BTh<zA`#eQ>ihdLk8n}6&_H5Z{$>W#9Pi-=;TqFrGgq*lsgn!|_ ztf|`dp+hpHaWV0J+x)4#!XwVPeBizg&AB7?e9nzbrWuEC>PT2!I$p4eA~0E#X!3R> zNkBauDp$mr)*wHREX!w(zSDPDcX1pQ)E9*x=pGW5OcW@gO+SD1Sd1;pcyTn3!8LAp z13|JzhSf#c^UR5^Gbx;UXS-5aZdC{@N?w{%>HX1TC#s=ZvE=$2@<Cds@?s#uQhYXs zSK{j=eQNiG?JitIwXVJ;)K*rsfX0p4o<q!XftV1js?p&bmCEq5^%;hRp@s-G?oxhw zM}w<IN)};eWKrvLa5~|{S@-^!74r`<A~@B8vB<~a7tV99tj%Oz<9fks8f_(GU}{W3 z-Lu&99iHc2Q*n*Nm>JGapjvjp>jHC%X>F!l8(YCv6MISC2R*MN8s|n=TiurrZq2Ec zuhiY4ji_olU5W4ijB{VOV>#l;VFy24DQ`Y#yD57n^o|JTx#VSS?)VU-RlkPIR6Vmz zrp&w4zAwsYH&&uqx~`*QoIs+=O!M`aP*0<+TK?V12@RFa&lAz_-gBrHu(@uT#ZNda z*kMA-Z*KFBCP$A+&pmTC`IQx)V)7$emc3vBdsyFfyfR0Q_S4v{4{u@aIu%iTTYYA& zXnZ)Xs0PI@e|m<qwFdUwpmZ~E%@k1rs(5MfW#2;FEge0DvG>GHL_U|DWsX$g8k9gE z6R^FDO`i1D$CZsT)a1PE#xUN)zeyA+!Rgw4R!>D%i5+BhcN!$VQcu3&-|CSp9`a_h z>C?@k?+=qO`NkH#vjz`mW!(l0SvMKaz0y4Rr2YDxXsbKl4*sjtZgfv2hljl5!oscU zuYJC$nHpTPCO(OIa_zP&v-f*P!c-SFw;YOZd>a#vb*nBrKRSY8T@C*A{fznBQE=O^ zUn^_o)98RTYlewdyIFVC=8kS<F8n-JC6pj@j>^)%MbO}5+K6RPvS76+iccV<y5lYX z**oI7&xEd~=ArqGmD(rW&UQv<7~_0XU}17rJoPW-S%>hZRf!xObg_ZnSKJ)9&GXw1 zPsA9Z`6C8(r2Q4SZ=wTYlxd~rO?;0KQ{=3ZNlg|!#qgl}JTB(yEm9U81WLNl%7jmS zDvx6}9x>*}zMwgm9&qo;M~YD+g;3+@e7P&Qg0-cmL+p4%1XkDS!%R18rX1a;dRoKN z5dN4^>``|A7NKLOtzi;5!ff~C;jcX6n>I%<0a?B$hOZ2V6d+0*z|Gpr922i2PFk`V z9<sPn`16KnQW2Zj$zS{>jLJ`?n2<LNt48x~dJFD6)(MIJ5H0f&%OcR?{`^r{g{p;n zNSRsNPh#1T2oH_mW_h#<f7WE?Rc0H*y2d(oTCr~Ii`qMxbuk<}sy#V6*_O9Fg7ZFR zl;(G&unX?Uqn5cwPhe82M-~`rSU36(Mk-OgaC(oo7hOlN^OqSXTE~y76qJSPPd&PZ zC{8^ee%?^t&3##S^w#@jcQb(adTsO~-tsEqxr99%Htap!%MPQyuLo*Ynz?^g9~!JK zZ;w)bC5ED5dwo~`hP;SJP928cmwnnovYW&|`x-vWsE(kDwEfiI_$l<d60fE`;tg-H zN1s8i=etGjYQ&YgV-2|HBpo7fnjFRaQMsY04Tj)y8o4{m7Dh_*oNl!ZoJvpP`;3m( zixku}JF$ZP4Q6qy4`0`FU+rCXqW;<<B*)A0MwaQltaoXf&ZC!>K4$G@wt_7JlEO`w z>{orGYuJ4`Mj!aPJ*l#CU1s-w(8Xq~SKT~2`&MvOS1X22X-BBZ?wvcghNkb^ejWd3 zzH>OX+ACaj22Q_*vJB);`m5(vbeGGpjGAkHLN{H!`s2<I%U8T_#=jmHijX}f4;-?m z<3<D+J`xK(h=+m;KbNV)BnH(Gb1tI{T(*5O1??%J$+73*gJ18hrUvqaeJO_Ci*mRX zz6C@3{zP%D4~NQzFR(c+s~Z<C|42_agAd|SY843KFLKxzT`tr46}`;d2jO-HFGE1Z zfLQii{BW>jS?h6ptWjyFn~3tP`nzjdmBqHHC5g&ne7QHq^MFHZ6rsu&83}I@<4;wW zh~Z`6XE!gdYrVc?m6ecdK0f?t6PfTZwynso_+kx>_qEv0nhe*sDYsCCfnjRe4;_EG zNDDS+4ScNVH8*c=|40lYT`0@TM&s6=s#25Kr~@%ucR(UOPzDc7K1Dc4=6lFVf_x`U za}ZJIH>C7z*X(|E04#<0SJqyg#6C49MLgsSnhan^cIynz34Z{YXKMx?W20(Y_c5`+ z#&g;Muerw90#`oLs}P<Ehhz(Y!k1SqJw$iMDHTzHtymIBuWp^(D3Ky;rGt10?{7#` z_(L$G$IB=p{ci{z61VIDyy?j4|M1z|H=E>GCITo@pg<B{d6^}Uyn!F~?e%ZSgh~zq zm1|ua3fJ~pkg~wLOPtGKy^jBe&ElqoZavqB;Vn@whu2u}pdu&8zZy>X45G`Z70M9e zB&b3NwblM_l?wl9%_X2#wABC)#d(c-V;IZfBX6LFxafk!INMKz>um*G32~SriMYa# ztg+4wPTWi~mmeOq<}-}{>!OgF-rTJw9fMLY`7mOOt)=t#%TejtsEaQ@<miZq+7u5p z#aHC`v=tFclEM6xp*xG=3oTI6QxIGjcB|Dkrw((qIP)9wqVr*PgzrzwbN3isilpn1 zyvER9oIOO!`@r}Y*4^ty3mL`infV4mLG}(3UX!I=r)_x8voHvL72pm3*`sbOe-Uhy zG>Cr80rX?j|LSb!8DsJ~^BW&ziRu`Cq`YU-D{v4xE}XdU<oz3%)4s=<{=n5or*DHR zA%x?&^n`)C6;?rpujh`I9ejnZ7+j=r2P@TpsQi~DEAZs(d%Y70irwnRC3+tN)TH#D z-RcBE%8<P&sO&rP3*Z{j4xR3;{4asslN%Bd($V*nAF!Nsrc>V^rsN8ObafNHj{6Py z-epJbYj)F@r4G$L{uo>8lh<-IpqJ0`Bvt{ImKFRL785;U-}NOUf58X8^WHKNCXykh zcDYAAIdz&M-X1TeguQ`9!}qCc<SPZp{uaKz2wOXo_4nxT7f-so8Rk)I;ethR6aTZp zTZUK6sh=Px=13GE_oGEc7PNrv?Xe*O6qHzS7ot=uz0f+m2kjZPR$d<HrG~yIWFq$6 zOWl8iVJg_4mcCo&+!amrn0n0;)lWWUyvmKzw>78foTJ}k;ad!fYe*tR+5xdYaTMmg zs6uvkFk~FS#_ASep3Y9zT@RCq9)D!PqIfV8Z>YLYa@5}y3V(qwY4x=nE_lhI$H?9= zxS+WTipmljf!|L9@p0NiY0s{2^(T1=5Z8oX_1uYD_X@fZ_ayQu+sU7YIDt&J2Hcd$ z09@L5`Bq@n$w5h55)_^IYa|5_dNb$R>Q1r3>&Ni$=-j7qFQR?;xH}w0P1w-fnbx8t zzbcd+^k)#%a(w=#c)pO?;U8+NVK$UB!N}f4*pxpwjAz3029T}P;Jj%-?8&;!WV?T} z`>84OhWQZH(d9%0@}E};QjmpM^1bn}sa)jn)jV&b=1XBZXK1~<u(vcHLnZ`MiHTz* z4;XR9X6H&h0f*cf|9L0}h{p!IVIl|uA@Z^>D+C&?KR<CJP7lT(2pQ=yp8_`Wl}ONR z4ML7%F80sTbVWZs>uWlgq59&plouxiYx5sQI9PfsGGlHVT^R7*HkPfZr|8I`cke!m z@Z~klv+!QmQonc}B6u)Dfn}QuCqO#F<>HlGpXvK^NIJ33);=iqgNNOX?}hUQmrmH% zJfAk!d=tvaD|$7zNrhz;gHy?&m>~%gbCB4Roh<{-c<ZX3(rCYcr^!tVEOE!JRPU`U zj!Pf9H4-F!$aG!VPtJ72@aq-$hFpI48j1#=xLI@JK*{}1%eDmNFmsD0JTZcU-}r9t zM%v4>=R(=9o!(+RcfMgo{x?Lc&6n5v%CbP9qZ|U;dSbdXFeEiU(<jTw?sE&m;jSWI z!lbfb8Dn(6K)`KHYRNo!6ufA|KgmOL1G8Kh{k|VveqmVAlkfih2Q5wrx|-G)K0<rb zLYV&}2>2)e9M}slfx@{i&-9CMrkixgn`t?UbMv_*o*tE9$Ej`nU~NZ+k+!<!p3Ri) z-AB(3zc^cZ)j}#%A9G1)v4l3)Zj*ugW|NilDQ7zUy?vz=M&n`$Pk<uy!Mt<E>@)9d z`MGBLP)@aPw<fV+3?`6{4{>{Y?1@9R-UCb*0CA}VGCO=4HW$7wfuSSudrV>3UM|R= z^p;s>?z2GO%TwX`u9ls9O+u4)W2J87BTj=h;@Y|6!YUFvjoiTv^B;G4`_(RQe^y%^ z=$6`J?Cf`HQ5k2y74R*_w|y$KU9*X+VmXPGbX~KZ@44?A;tQH_;j}P;q+@v02k+Zq z^*3-nMb(-ILRqK275PdbOv9P0k?GA>n)(L@6n<`rn-9iW7C8%q-lS4>I9*g)7E*(B z2*(Qw)H?PTjrzPRdYR*DiOqrZH7Dam>5eR=1ga}w4|TMrMS42%eNl9vja+!dD16~u z=qbl&(w|c;Su#=}uKw^o*M-bbf;HMVq;^QqiGg!MLOd=aB%O|5AD)<D=rmPkTX6Q4 zPK0V>BmBnoRq-uW4gWeHM>?genHs8}=DQXn!mFX4O}b91U6DGOtpH?Lmh)_)H*~cZ zw)9@*pYvllIhEnF3i_b{gX8H(Z*iPqjTjZ-46!1=Sd>7Q`pqo`@OM#eXi6@k%pVq) zMrE*yHBMBO`&D%_Tq3(gFhXHih13N*jwVTZyLQVT_iex&Tk=*JIoq$9*KUQYOs%Xp zEDIhQ`qgl{@HE%Ej&B9Vyv@uE$80tn2=|r|=lYZzjAT~zcE!U&B@L;|WT`q6Mvu21 zrS^x{$_fNX8g|NEX2)EL?L)A{Xy#TsTShA-43-;SFfG?y<*U4AdZnu-7pdT3Jlf60 z-+B@sqm!<2RV!4vA~nx`HC-(+EP1l6QC0Qq<@D+B_f7ar>BfuFlV8$x%BSlb-W};i zbq%T(3rJDB9Vr%iaf=&Mo;C~f)fa#ba5?syj^yD(zQSpJY3fM)1)Z@P9XUCsT45aM zmT#;ZLnaRx2XAnw|Ii-`la6)Hk5Hw(_;@2EYkGTOp=;<xrm2O}(Tb0`eYbLjG!L#; z%Uw@DDd$|z=a3rhYIX9MlJ{>2p!o!z%QD%Uzkrwoit=D#P}*`&Pe<$(F6FK@41?W} z&tx3JcNv*7+!qsob~qWq9F2bG-^}f<o%!PUl|c{u@-o{^+@riP%=5mD5H~kVbW>kw z_iOg@FCDI4y3CtQM^4*xeXy~Lx_&d<`QxIO`%2%%F^>W)lzxgmJ`P1CZ_OGtin@?~ z);#^H5aWcssa4ZrV&WPK2WRz=#BK-+{`f2>`BHB+O)GgJ{jQUd8@D<-Eaj})%RysZ zhbUW_CMR^Gkn>9xNs|jxYfwgS5rAMyP)-!<%>Tq0Khu)h?B?ip4sM%&0W>6*O+Hlo zTzcTRLQ~l=#526Ck#u?X@il@foZjQwNZ`BVnNpsKgx*2^qF$z3`7ccFm+stH;nFIL z^?vO;6D4DLbnE=Vz>4r{U;fxy6PDEHu4U5R31zO)tm+Xwl!EqI2e^+hqyr=XRu3z0 z>!d*sFXN8U6^D`Ya<7IiH26Dz7V4L-K7EN^QRu?qQ4GgOE91pm$7|0~S+~l`iLo4! z@txI}<LAokTUY_Wy9+HGBo*v$2qQk|YjNYa=Z_1~H;=15OVj%fz>yWNF><!XMAX(g zr>C##Xk2x0b_r1OP#<mW<Jy?O!RPBo;j|t*W1B&u@~1UYjZD=);GM)`TH*`_MIA)G z4_n2vTSiRUq}aqxC`yFAj)`?5Ji>>9LOdv|w_655ZJCs_L9{lh@Iqf5H?60Uc=?!5 zTd1DaPCT92E-g4CEh7W6oj{_=!9saFj&9_46V8qes?BbwJJQ-R+V(xesWTh4oryc> zC|TO{<2vYc$w4u2<e*=kxF!6Q&p(P6G5Di6bgFY&IeP5s+tcsarc2&MN0evJ$ApYJ z$4aD-Vq2ln*7}%y=k1}sP}8QjORR4N1SA`qqV(KUol{yJZFS@GXY~^PgC_5JO6|_D z4T{ZNbu*+tJ-eRt9pj2TmhzXSBRfS1bimA&A!X+Y{}>6yL^}?YL5b^&=NHc(6r+xZ zq$t7WH=(OQ?Jq^D?1^nZSqu%bfnIDg0dz)`Ofjxxw+d2v!G9Ya)AZ%rPF>E{p5~A* zL2&_#LK(UZb}^50`p-Zm!yK8KNT#bPUxN;&wYn&<N9pcKT!}yAv7vO?b1$aKnQ7@< zrb6S6>`GzBecdFV>un91DF7SHyl0EEV}FIs%U<XDZrlJ8Eec4qYYN;2%wP(C3@PZo z4uq6o!?)=BiKf6?mHgFn3R|2KZt`S2G+OaN3_In7WH;GhNu8K+E-;qG5=g1VNB(1R z35h5hC1@7wN2`iUL!{tQKdBl1Gu=4Mcd;w78TM#u-mXdCwlgt9#40fSN7d`}xQ7t1 zh?xWAi_7S8F$%Qqaxg!Amv&z9=(owtJxWnT|MD;;DTpJ#V%B)gV)u5cw3SX)>4PG7 zHcQ}qCO5R)hEh4$`X6<py{G9ZTK)oS%|z6xb<CcZ0Qwrjuk1O{^?JiAd<z)Kn~h0S zWE}>&0`@*f4<DkW?(<&GyL=w=k~j;Q7W}kFwG;oSIRy@15C(X471;wyuBS!J3fxYJ zpSC}%bDVo?_F?(kJDKrh_R6&?%*qLW;Gl0)>Wl5|8XQ-nqlB*J`;wc+5Oc>*URQy~ zjk#5xVQU_>`7`;C{d+*fkfi7iUtbUaI3+>Z!@4m79S+)jIvQnu6tj=wNB21mQiNRI z6x(eQsofd7_vcRv^K3uO4ap+dN`oPb`KKp<zYvbw<AMh!HPe#?I@^>W&c47)e$|2O zkpyYcWdONgN-9BHfgg%JX=HT)q-xeCWX5Mle*Fzuo`MnGK-y61f{zA={3p-`l%bw4 zLERg*Wi#AhC}l1{hAaWvl2+1>8IO@XrPi`Cx^V7<K-fYgQVlY@^3RVCpq?L*75Sk_ z$Rm9yE?tmQ1amV*ZBG%EoLnJ#g|Ouv2BI5$N_+oL1)iZlvwjSnFIeu^Ccdk@G(CL$ zRB<V(HSCUkPM=APrCVx)LY&+eK7_Df&Fjq1nwJFQDi?e+2!i-;xcV{FGnH_8Mtohr zSv%c8A?870*o~$Zj%wa|p{&=1G@lLi`OVqsvObb7_OPYSabkiB@N$Y+qRwO;sczZf zT+V|jn@>e?+!t<yeY|kt^Fi^GPbruwcAS>SHiGdgJ5nB(961R3%T^T;=<*1onRFqp zLDg4D=lic3ahSTkeyYqO75GT0nV}97KFnS)+($Vk@Z47%9|k=$X4XmD*6(1jBSCZU zp<;<P<(3nl(^B8j2LqmGO5VAcb(d?PEj%J?;w!q}r_HkIm<<mPn@QviwDPig-h0IV zuJ^^=8W0JK&s5+k47|~{@EJMrJkwbIQ-;kRxW-S4$XP_>?hX$VYf1XuhWw)-wnT>^ zy1*wCIHEv<RM(-yd`2z6PZPl;p|eoBMu~@kvCM&)D_UbIQlQdI&l2N~uwTeUhGJf! z`>K{(310ok%HakrYMI^UtVRB?aZ%)42=ctSfo6KP;WyL@8*IH6^CmmPPZml^&{;03 zo<l51RhJG{8O^HEZNxj=GxeM>N(tlWWsKsu%hY7)n_(U#w20n7&buv}8sYOs9qI6t zUr&evcnj+kZ>hw7J>2~=hxXo?m`yfAMmu4-FTKwv42wIn3l1e>v4KMzr-A|6A+M3< zx3w=G31&E}8hKG%%Z|yctkriz11X{4A+xmErhX$92ZfQR3|9~5bQ5HkUF1gWoSW@P zI~3ZLk97<uCU1$lzUz24Khz!^VJ~&U!K(2MR&Y|<SSRO%TcfmKiA0p0vQ}DzopyNs zvy>wmij8NbxGrDZDBI`&NyVk!)@oVzg^)4i%lM$6a#Jtd(9$iOL&yZ*p-)Vc#H<*b zQ^7kAFRdt~@Z~=8yP4xMd9@3RJc=0^#q>@hgZgv{c6iv>Wk;5yTBYN@te^8ynzr9g zmeXAscRqNVa^8(!ih20V@OjL6-^;!rn8<;&S^g+ii)2;xjTgFkPDDo{u&?*yN>_P^ zM^&vod*D%<<A?Q6hY1@+NGK^Jw`PtKlxpw2)qI<dwQRY?sCLn|&fZww*lkmEG{-9+ z)WXM(4=9b~&^UD;r7w<&vbG2we>PnwA!Do5+}oxWb&A1Sjb8kz-k8-<w3UFE5iuKP zhvD+=9nOzQSstz{MBd)<#`Vw0o^#LDq>r^?Wfk`5yGB|I)7Q2zwt98ivF|)M{0~bV z3D4{SluIdKlrC?y^wlWl(^)akiH5?>;vAx;DilvYrMIQ9S23C@pEpo9ExK1^UsPrv z_|MTd9(s5YiFVu!z4T6M8zezJI&2`>!%6}>r~6S`w=qq{!3+8Dt%Ih>o<jif1_5MT z<gCpHKN&GLWP`KjZU<yVmN*j&5g_!&QHwyX3SaW0nIRmz(P8!NHza0i_xtaLnj@$! zDiAp}ZzVkyq_qC?7IAM^)!=>sJZjtUvN;=BLuQCD{M)@yV;pkg3F&SwctEbOBDY77 zZ<6R!|NK}G{{}TL9EJ=)uAMToe<TkglCN0mcR-ZoJ<V7eBz-Msiv~=)3ORi>iTuIu z@>`UyvSvEK(E)<@A;V^CciHv`bP0uq@Pp>gJaw-$H#C5RUqm(NzeMTk=Z9|{>__&L zB2O9EfQx664IVk9YaKpJyDRJI+3(J*Mdh~pbCsv6oO*9yD>&pD3mW|1h;#%@Y_CD{ z?wGed<|ATCt_*`)`{?bj%RK`H+Za-_0{1%jJ=cjNe0I6Fft~=ZH-E;If;X69$lEk0 zQ3`Z+F)&9G{hfB5@Soi|-N<0rIHeQl5KU)884lV>ANUat0E`gu?JZ5>VM9kCr~c2@ z%>HFS7M1*~6ez4L1aVopFf_jVg4zL9#a3VqeeOlJzJ+hjYf&HB*K$J0KOY+kpa%vN zGg_IY=%42V=sQCQf|OrA6l)e)fYvqRm`z;U#@z50A(lkqgkW~XB5e`T#iThqr<zg8 z?PFGt_PH?gz!^4yoOCq9pLgyKB>)ua*bn6PEG!y93~VNOgWqEAe)hI#v38*`IscrQ z@A;2`)dd9}9+oPf(oGVQAABDezBlYos^1VYrP;mY-&mgLR(?h+?a~YR2QEvd!*_B) zXC7(H(yt`?;|1P4fK1^#_lDa`9sf+jz&-eMaEI!JzPc}%H_5J+w)IzPAqZ_Vf&Lui z)CznDZ?ogJL?Eeyo;-9AH_}P4w<4`XmtCFv^JliGKvz<r=U^LZ((tb0$VPU~{3ZD6 z6dQ4enWAc6@tPO?dVrbwA-1z|Huln^7xuy_S+}46dV1_0x7MLx;b;2;Kpnu{6;vZ~ z37bT}SS%cl$43%Z2{XfcA7}qKDtze)2l_N$Qsen>H3)V(dueY-pFIlto%#uS;V=Lx zVWwo7ec7a>B*>sRm@7!h_=djWNs6@$%-$QpKqY^nLnZHR<xKfST0@ho8ZO5hCK5zW zkFT#wP&8?q5C2(=;0|3ZVXGE2AgYDj!}F5lKq4S}_@}|3i?7)Iyz&4M_L@)UUUT#v zX<W-9+cRo+BMWe)Gu+D&^lqm4w!iuZc)5f|0k)tPn#_FFRm&VS<aXPC9?ivq7VHB! zFxeu6S~vaIqiM<c?dAPO-Dg(y9A4T>Pqmj|_L+p*U9VgTSVxypo7Af;4a7Z0%C=!+ zW8*A8)_S@0B2UBo4Y?C_eizgJGexD*QlzVwKwJ1h*qiLxjG;ag6|0LWS$54wk6nc* ze#^eR(1Tgs5+f2MC<fd9GxuC@Tt}0ZKlQk<M8}1y=0A@}7HDQ(`ooC3=b<nJOf$rB zdj!*zvQJ!RliIHDvgjJE0ojc2-}KG=sB9>6|I6ts8y()FS0#-ir%&f0vT&W^1Jlbb zU<1bs&3pJ(yy7t%Tw+_RAtYij1p9ZJe3taRucinVOV&QjkHYTi(yP@ydg|;s>L+XR zUl^5cm<O2wQnH@EAt^2eKoL8dj95UWY|JYiTf!;}O7`9g2HcnH*^z(PmL*}dcr3rY zrttY`%L}1xp{eY0P70iBhDY}JP=3%0G`fla@$YH{9_tsF@k34|&|hczYVmA4ZoOuc zvqpU2<_a%U3C|1ai7TOQF!Dp6+Kw4N3l0JtNago53-Z-g;AXHBa`=ljyw9Zmj@;{h z<*d)3A3MZ9e^r4sEt_d?ANK{0-{sPO=?m4pDJ>W@HKd(s7e%dp*P=eE<c{1MGWpNC zm?=(xRN=`4$L&qcaiJEc_=2uZlav~5vxba3@!eCH7!BVWi(-&WvFOA0c(+Fv+i<F+ z?S1?t%j+NWWodkb`jRAi<={oq-a1tFjw9to(9oYIl2pk+dRp+stTp7_{QBXse3#>I zD1^Z&92i(OhLfNBeRzOw=pSi^aQrqrgR$MQUV1d&KS}ttGk8&fo5(V_FP+2p8CC{p zc^Z%|u>e~Cs>!S{wDxsM;+x#QlP_M5u!3V)?NsZ6A|El2pbbdE75)J^jWA37Gp5~U z;8fz2aUj==#Ot^FU;ldLtNZIGmDPV4lmp}_8%%mgmAboN3<LTaYTex;vZF@mWCJ7a zOd*J3pJz5~pRoP=MYr1fe<~azOYgK7V~!yk?vIg5wGPP&e(;lR-LIO>!tDQ@bb!1> zc1D=2(OVMj?hmEBK^_Ro23-_em2B&g0XTwqkQ{PC#$|{3(d@VRH;E=Ie3jY#q3B<o z`<)Vjo_f`V*#X+V$6DbKd87W1X^TK*w!^o_hZ}xUQv<(&!h8Wk@Tw<`ko3R()rwy} zSP<0w!gpWQN_-@#gPsGI;W>AOW?csOmE$wa_z~#N0%0y9yQm7jaxk2@L2{)?1+S!* z1h9rAe-fCyu2FOm*+Ue>VDky4djKTwG2NdLUSEgj9FT+XIRzdTV9Rh=TmYj<5ewnt zh^XwGI`|6E&xOr|Q0FL!{t_M7H|JsE7$H<UbBGK4#|g|%{T3%=J`GrAL0Ui~fFn8w z+^6X?#U_gd40s%hR15=-dqC2G-KA_p*VReWsk(Q5L-a6<!EO+inmN=8M=4kkSVSRt z?q7k$2E22w{4C(MKg~7o<8?_2PRR1%ZAP>ZL^y8uvNm{CHgxBFcKqMLDM;-uMhA$X z{DZGLRep4H(f0)r@jmImUqPmB@|*X5GA3Xv#qgG-Yd{<t?B<srN!I_JpoZvi#uEG; zU~_|@nwv?tll)16TN2Rl(7#$$7Sk+sEHb1(M8GH9$_2n|@ygl8BPZ<&jQ?svd7zBp zD6)Zy0nbKyh6w-bHaq0!?jqj&+nw~*P+%Acuo1n&iAORy{b;7;j{b&-!Ep@4_>yh1 z2R~UFu$T*S2tdJSAYC2+mSa+4H|zaxA3%i3;xh(5<hRNp^MYU#a{f-ft`FE@R*r%_ z%dv&6F_~R~z)==m*tpT)t*XppNfckH5<vd~R<K}2YC;fRAA!N|!~(3%)wJmYO9VcX z9^ygh3KVNjm5?&i7x2umsPF|}?wJ{$yco$wL)#=|17|;}ga!h`LfeqjT+lg^1hNYD z0nGgptcPGX!A$WTQPg8{Wh=MijCc(*Bd2TQTz5L?!KefZ<`n^zNi47sK%oD@1@!}W z)XBa<V>>k-4XGBmGUYoKaO}{!j+Qjd$bl1o!UbT*XcN*XK@B01jr8OT2?H=nc((yK zuq6>$m#wY9ZgKkh&!k}UQ`hNuUrk*0yD}$0Ixd1BJ!RNpz@d?#?mh(rVo&432}wsW zxYwYX9tb34fcZ~HhXO#5FLn`eAAXryt~E@1WSNi!gMdfz3<*q|qzA~HUA&OPBrto0 zUqIU}XGUpJ-B0~wyZs0yvL5=ORzm&FxY;;&4~(3?hMIrDkdlur-*4VESscdU`0n+9 z@L9@Nny2$-O`&*V5UDh0HHjYc-<ArTi9O;=wy5XKF*dcO>;xE`q@_RfNb;K*vc3kj zgql)d#b8f^O8s4X8g!R}kw2sWl$*Xs(W&rXwO*e0Bh-bcUiZsb&gqhErL8M$ixN0# zj0V#OQ2V6*BH2Gz0o6kATyUWkN_yUt#CLB!JMnM(780~ideFV$&n{%>X;G_Ur^kBi z6MZbsUrt_7_O0fqXL<h@Q8P}EM|A#LYQm_bIh7zvMccvZF5g*#f+de{K?S*?3jvDq zS%?YPEPv89f*|>WP&6||L6U{poMBz7epD-4%<fj#%lRM>`&2fPCpUTZC_pdGKfI>D zu5qdQX2%5PbAi#PQ0E9yXL<!vK{}by3;3R#l|lR2eTG*HhP37PNFox7(Nh(VRQdGX zPC6g?#sau$|KuQEcOb`k9f3dJu@$_SMo#i@yviDUo2q{MHzd^TgP(NIGF5Jvw&MWg z2IYZBGV(_LPtf7t&eYFewzBr?QHHT#;M_V+l?M|qxZ}qWg>A@j#$E4)ZA*(1xyMic zewdr*;sYjMrxgSy$OJNL8AwiFxbS$VOA~*iAZPn9Y#dgVvP=dPl}`bhru^A%bU4E` z))Jdd+48%d$2Brqf8FMGT9<73J8%I+&fY2hw{?npD^vM%izGjBusX-rOE9XFC2Cla zlQnZJXWd|U3AUE~=-<}tRlVuXIXGuLo69lE7;~6-;qX*=dX`!b4o(OF8V@=tNa?=6 zxqk~14wK4vmMJss!!sM1%xzC{m3}DSfHrh9kcmctzYJtZ8TonFD>NC(bn|3E*Um{e ztEHcQC8P6D>3-+7At68nWENm+rxbV`|LdB8HYH<;ILBjiiqARyN1%%4(f^97_=%Dc z;NN*{Zr(NY!bTHUb0(js)e8$1ndb8xXHv-JSH~Jz;DwyUJ{O>sH&r`7e(uPo)k-pd zoul~b2vIfrQwakLFex580&DWLA20cV`ae!rJO1%ux8^gYT_2bla-$4=-#?_6-aL~- zz92gkh`O){5WS(qLx{V6e=qi84RZOE(XBA~*2$RFOGwu9VHjQ0^(SLFC5Uw-F~$$r zJ>(MX-^H1O$KzQahxG+XTRD8pX)HA9wn8gZ*A$8ipT?}wg|CAi%hdqLD*(iIa)2^< zFXG1h*8wjGm2Xz-u)=hpW6mb`=PJ!!_zL|Q-<1U}SOV=oHjUcm{7DUb>V3@#?Ckvq zeIY?gwQ7?tF|qggCFRy(#`=6$sW?=>L8D#aWK$SlLv9@f0;;D8gwV=@AtSq{<|2H1 zdiY0jb_R@QhK&(jlX+%_`QqJMQ}OPEQ`=&j{2(BMBHBU5=kkBT#_4v?YygN6K7%Qd zKwN0`Hw0~56i+0*cHXv1{KhO`=V12M#|CthDbd8=bPG4aEQOOQptv`4C%zzup~S}! zO*XKlR+zc?ZgVfGui;N0v(<^nj@6zJDULd)vvvBib)QlAgucAEHw|vMdeDK(Ufy%O zsN{M1T~&FjZ*>gJ6ywqDpfE}fcqG}$Tl(SnYisaDbr8IPZFi~by(0+C*njk6)h;2l zzL`paxJnp;eLfQQWsZ%w3>FShzIZIV#dgNPJ}9seoPchR0WN<V=2f;sDV^y3WnDSW z&xh_%L^f}EO1hAa5!rTj-O^ovduO-Ik)<tKWd9jbG~lblz9B>q#{ttYN$PZ+gVUM3 z)4XYLJn+a)-GI0ar9<!p412!&%3V-Z1KVChR#|2}t_3w@$n|MTB!E3Tv}>j#I}O=P z4NTTI@?7K17ps};5esJAZgVDZT+lRT00i5R>uHpc=?{=&8&GhG?nfz-Y_*-?So<?w zoRj>K-gf5BTO8cMkgk2I1H-{0e18WZZf<*;8N7aPJGwP#Y*tUkwVVHt;#M8lZQSIB zA{+d#eO6%I)5&vh%9p9$e;kyLv(0OIQm9hm{7?w?*JzC%7}7PMPt1C@bTRvcSWix! ziAm%wFxS;FxbWrVn|?~lC$$h42}9$*C`!JoofOnhVPkcU+Y7`)_B~fJ%rF7>)HV1Z z5!oB7@|JJMw)NqEjT|tB!fyim+z0b21Gc}?qLdrn1{NYl_pVZCicO5KgV=X#o4GYP zkHfGGZO9T3;Q?NX7M13HwnqQ1odN3*M<J=bz3W-oQ(xR7JB*ak3aC?Wv>rmjga7}N z+K@~gvj8V&pXt&cxb-hM%t&M|1fC7!K0PwVF^AWp5@G2^RzZR3>I~o6`VHw${)^jO zWXY2N_nNVxLQMkYPwoxV#NMn_R%pn|`Df9)8|^1sDjY>V8=%|whfkty#B>+!)Fqgk z;MJ91Uw;`f5vaKY+wR1W?KEX%cE1uZ)s%{e58)H~NHS6wSPeff;1QkFxYX0Ul63d= zqS;&eLlD=s|K()SlB?x{1^9u=LwMxqVu)A>!Q4swgj2xX!bk_TP5HNX^W;Un8E{M0 z!^b|MEag`ETN&b5x8$ujc&S&C7zDFXAmBk4ODaPV59*OkHzOw9T_7OER78-1J7iMo zjTHA3wB1jZ^M9kl(Ms9h5Pf?R5Ls$dh@^HD>3GFV=F8{emMbKSlGYWLe?RUyBbcqD zFycelcY_>qHpxjh>c`*h-%(N5;k(a>5?^GOf&J8?nqX-nKjq}x@sn!mFP+{0rF+S( z|6{x32K)U6pAi4At?)F^Nq%3Fby75v>uhr|^6?)GakkH&@|tst{QiXYMajyAWZo?; zs)GIDeL*VyZ;6xnFM!JKRKgkA`YiZnJ>Z#w`e&~9xq{VOVRL{LC>sB_vv8<_m!x=U zczrj45<e+gu97wrd%?DQ2p&uMW^5o%nwut^T(0t%JD(5+ytFoa9XMvYU1j!}5zWPO zy19n+MW&rlovjPT^7ccuFnK>M(6au25j>2$=$|^so^RlF28F`!y2SW#`OSAyAiS=t zT;I9EMsJXwW|9-1GBb;T$EO*d`5Q7{ph-42Lx~S^Mtq#bt-Z?=TX3<VA1+%okg2rn zJo3W_B|jHpfCE_~NfoW6X9b-GCsM7c0~P|`r<^^0`FZObce;;E#6uvm@s}VV$Jxvx zQ-d0*b5ildz8TKIYTDl6FAqHq1;MlgDUS!wkxL$+*vWK@pG*ambhR6^zJdZ+q@%gk zxS`loh3$ac#z}?18=LaV6C4}_C19A6>6g@e5Nf#rRP1kvP((8MgCEV>@H1Fmkbk+# z2Pm6I9b0L{R<j~aW!Lp-1|AL1Xg6?U0%OPS3++|MY96;)8TjUSc1Pl~IBh1eBOdY< zpw}OrfgfELwpXtX`wh8M(QvH6+44^Rm0C|9uhi!-I|c}lg}wn}NJx3Si_~I@F+~Jy zqawWhi!NxK?d=UKkZ1Jh>svf9_C3Gsveh#vJOyIo+eG5+lF)wi>XvU)VV;JB%6qG6 z#Kk(_3*FxKS(h@iesBae9~Z3puuZeU5CqMej2+RWH@CIVRF!O5_!4YfHFC!DveLu& zsjtmT^mg=p!_Vi@5;&y0+eN~UD+ktFAP?PI@M9$T5uk6aw|a70Vc)JWRTVupPu57A zWjJxV#6}HE48LQs8xh;_CzSxtmE9HO`W^64lDsHv06vLG&UX0<iaVB_NFaN4(VPdu zvLD_n5EiQg+8nmtg+xP~cYkP(TOtIafzdz;ER&t|mc$aZ37U6q1C3N({8EE`kZ?%# z;I@<bv%V|yIubXY>ZGFh7J)J{NCt*{xGHik63J_DFSk7Cgnd>>V#2Fn$t%3tg<srb z+Hf1S-)J<O6zjn4gdb^{?k21`Ru8+~4UY3QD4b`$T*5J<RS-Q|*Iw}Pi5B+P`>*nA z6fEvw*ySbYj{lb7p}jDo9%LJYex%Vz(ltZa`mZjvB4E!n*iDhjIMWplxm6wqXO|DT zRJ59{Mux#j^=>y*)dR9|+YH-dM2))!yHKkC{H;Y{Is`(2rY^g2dy{YIB}yb3SU7Hg zD6V>dC{`ZLB!%IPUgYa+ol*=3vVn`#FSa7tq(xy^4sI-*YDR8`uShEAcsP=-0fTG_ zI=-6$0f|qZYa}@VuyqW(MOauwX(w!~3gnG}ggcVW>bD!hx;%~S65ILkPUD{|N1YJE zG=cyz9w3=bQ`TCXf3i5)$==L-RU?y=ss2_f%S2bNw+u0T0hHOo0^~H4HC%W;W)<d{ ze*Q6l`v_HoOkix5{NvrLS|0U{DMYsfY<~%pp}+Y+Hrp$B)oxSlm~RJ+q4IRlPlDHo z6yg8?MNO2Uh!NYU#HcldY&f>dxl*O$V(T_~3PVq>o-Da+<;OJOrA3uGUp5-5tJon) z$=sVCScM3BQOZUaAm8<3bcuCNUZNXn)Sb$3ic4GXj<y#>xYwI{2WBe|KpqzTO3QOw zk@gcBPDNav0#DW@zan4<#k{3_r)n(ta`V2>?PSKmCtrDqnf;_bYWA<_AL!}u@HeD4 z)az2R8_w_s&aL}(%GTy~Na|wt(D7oVmKV+PU!{8gKSo1;c$ij~W_sjy++_U?sfb{Z zJK({XuT;(S%U&is*Zj<e45#4Os@hv7hVQbJiSi%(g#QYc8h{&X&z^{61>YERX4L4; zf2Z7|@wV9pkGQZ!bBiUCS3ZhjDqp`0O>LN48c{V{rI&b?Mvk9;M5REX+dYKw9s1tk zRN4u8inSJq%Kwz#9VlDd@t;vRx*PLmL?at4=17&$t$4J7Th7)|06J3*4zzw6<gd8u z*xX;RJ`%e@&Ph37%bt?P%ncx?HH^CQ07lahV9r|rKjNxgUD5&aHlNwP<WEWTPeE*( zHk=b2u~V=)EOL!C+oTlr*P|cJPh1WmC}|r;^6NsGoB&?$t2L+!&~}`Dmv?zwc=oTD zsyk;6;VGyT>;n+eJq!w5sdZAUANxfj7(o)q@`v<CppQnUNZ!1__h_*Mf#~{yf5F?R zC~%>0Z@~q+)@R7g-t>;@R|p$PTL+6vZyg1bjtRfb?oa>&OBNBGnJG{}3tdSCmN3xX z-oa~_UdQU{>-fOU*Anf##-*3-w{$xszu=G~li_0(C+w|_G12-~z1$C9zh1P9t#LeF zjWvBCM>$g5@(!JMchc2y=oTrZ;z}Cju-MXqL>Y&h@JzS#otNbi=dpV3ITw56xRwzc ziGf2?pv(QFhG?JRN`d_?Cz@NbR*DN2GC2gNWjuh*4J&Q8&CNnQ3`_bF&ik;ny|Ng; z`JQ0D-1;>fgwCqP?Vdc)>7whDb^XTY`b(TS{My@K$ky1X%6!Srb;5=Adp&NB2Nm6| zX%=JbW#?LcUAe(MTAtlqOK`v@N`)EqH{TdFuYEx(m}kYXVC<28@%-zlFI-#HOoiVB zOT-s^d3UOHnX-R*v=oLHaP*TvvCj1YFj+X8sfxs7^*Bpq#iH*gzdUdqaZRF!Rzp9# z*R`_zI+JRN?Y$GIG!VGleWCgn=M?FbZ!_|kFWW29g*JzU50(MNhdD3)h8*AqLd%$# zQz;A(8{I{)Imen)W`6!?v~@&0S@HK%T|{&s?=yrJVNT2!K>cB?HIMx@?zbY`_$*xn zNBkFM{S~01-coo0P}3}Bc+6YkCtug67ZfEgKf^`5IOj0fD2$!vHa`%ePYzTxZ=A>F zS5o1>jlpS38b8C&YJRp1?_e3T5GSHBh)`H<e01QujM)Q2Tr)Zli7Ew!aR%&K68+K9 zpr@5*30yJV(C5B%q*g?i$b%DROO*cYc?1fqCY!f&4-!j_%MR=q$iM&Ks<Q&zY<VbQ zIdY7l78Bfa$$AvMw$gn6rHFx-<GD0}MDdGoHBxmV(`URe?xHyWo>Y0jI=aYe%6PKw zF1(a_r$qrOgI^tCd*RE8pj2Fbm$l(8!v0#jlRJHp?k+&rvIQCAcI5Es%6ei-els*2 z1Cc<5mLAGYXg=7|S0|$<K%YwNAk0muK?=OEJ?(Bp0lkhzYg_xZH#Awd4=7hLSp3S2 zg)-%=%^^Z~c&qyRR+uIROd9Aln>Z>h-iCEK>UzCSH>yT(mc(9v!D0L*`uw|rjWNj< zTf<ATu56F3qASKslqg<^o^q-fx2E%ZtVQ(-U*_dArJjyAnfL&Vk5qn!=9Se&hA9IF zl7wkWN8d1B&FfLgv#N}RE{;e3t?y;Bik3B>i{14yh0~kY^BupF9Lz8D_4A!#)aY2j zomnS*h*?QNAxgP;^})pb*QkhVmDnvx1s=VgQuFVd?HW!Vbjv#T%~P<aoC4&dSqt1O z(`&EfE4v2ky|N#R=zmy09Nrz@Cz|!%IDf|PzR<__<Ni;DlyH;z_r))vPDk@P-TB&j z%Z4%<2#XUPBqR_Tl}ZZU)=m^Fhk}ox1o>N~vq5G@v#i7V(xwy3$+y5*^Bk-vc&n1O zKo&6%81=QS1UwK@KJhTDG*I>^5ISGVGji3UR<7jqH_^^ib)N2_^i+a8Nd&H@e;=}S z4Yk>T=3yWyYz(j0=$Ar(^xYp@Nj{szhMe~}c|3!ze_-V8syUsrg%}V>{UB~52`nUl z85V-t!iAG|K$zIc1!Vadft7Xt^K=q@AlJR+r#`vZmuHwh3ppR2OY{X+FJ5s0Hnpv} zGp<8kx&i?y!F}$Dle7Gmai&ln*+<_FeQ7zfj@~9K+dK%}7ndM%^v~#$L7)=!n4SG- zoveP%RTj$cLqP((MKF^{fCI0&MT#VCv8a%jc8c%9Jb?M2W?)ONZ;+rt3fHof9=1zR zo?^evy-Y+rO7{pMDY(NH89-o|cW;<~UnJc$!Ticj2wR>K6ZG6?%dZX>w?T9CKV;3~ zA+KKX`)f=U!pRNPDp7#ABJ3OtnPLcaxGS&q<yz6pB?&TpkY)ToQG&mfL{Igl?W#}% z^;G5J6P72n{WPVsoyoeKK|n>&J~b=UH?)6J1&t+?rS;kJdQmCA%4VS-QT8oJ$Ayek zhKz+XRF-AU9?!Nq3pB;bSV>mv^Gab2szuEM_zM@UEUnM<-V3et9B{jD2iY9d)%()s z+PiLl3wyVy=w+isXd6%!65RyK<)DpsVIBJ5*7SV;jKKsUR8znBScsoflYf7Bce$52 z9y^v05`YUVL+6*?45t}PK6$RqN}ZM{JQv>Q4p@%U+YOgf?d<zKK9!&r@r&z?L}S&B zxq?Ubyq~9l!e||JoNwN_N)QGLW4-m@H5V(I#rQGJlGW>$olhEACN>`5OO$qdoBT0@ zq^3l(c<wRDyC+8g7z6$4BPxMQYvC-mr7vR)o!GzkRiwYW(|Ry)`|+~5BY_F^mGeYK z;z@k<Xur*5xXSDJL#~JPHyqvT(|80apW>$G8J96N-AB_+JRaZRbsIoEcx`zfdd;l0 z2HG25k2yN7zx*lG)0XQkAIZq3f4Vw&ZRrK7V6(QB%_DJi>Dn@Psnye)Rqfq9ly;PL znl2VOI~NIeP#a-CB^~|YtYcx@$S)is4t?iKA{XBRDCLh&87d&&MYx_3WDSbrO1t+3 z+<biAb+(1u#c)BFqSdLD>>Lt@`Ua2-AAp04KPEhgxr1Ra!(Xl=$>Kn^Y0h=afN9;p zi6~s{meaSoQCZY2ie4zNS5S_n|MDay(eEv&r*ncb5qLrKnu&#M)G|XAv=?A|-77MT zz1+#oR9^x15CC3#dv*_hOJw?)==B^cb?%f*RXXKcocy{0zJA$pG^f^Ht$k`VWxm6# zw@T-irsG8PRhJIR3LnKC4iD%04J0vP9n(h%FVObMP)Xp6y8R|<;f2c1chzkz>J|$b zJkuyNaC-(f_0oPSugs`h^DIyx+{X}H`)73nx&VLw%i9ir>OH{=H&~j#@ma9)mkgtn z7IM&=bidLl>1gaWZM;;-Ik%9baYIHD2+bIA>gEkSYMC+iM)@wgxl!L_OIw#uHkB;= zIlK%kwOM|F93d{=6&Eb8T(KJ}w6?!{*@oAU3GaJ&lJ*y|x4^vSL=8j}Yc>??Zf$Ah z{>j8-DB;F?QxDOTPL-;1BU6cqzmn)A@fB`q60x$e0iqUc<sy@(8mYf4AHGPMfrhGk zE=L@(M%~2VvNqb`rU?(T2kdRCgk7ec5z_d~8pF1z0^DGyvuSJLjXN(MiLc6iJu+98 zs;O25y2hJy{eQJxc|6qH`yU~RkTsF1BqEnWlw}lMB&NucwW1<-$X1k$lI%@%OO}i! zTlRf7WsS<%GTAdTOtQ^n8_dl8p80;imvLXezW@FHaz3vaXU=)f`8>~gp7-;94*jwD zl$g}@U_`P3@mWt<@S-PmC*;SRhfnR)lDKSjy?OR<eAIMVJGb;)&LZQ*c8vG+ycTZ+ z^tGgUUaAx1ir5RgV^URifvTbUUvM{OPhFi96e4Op8-h=_7(t&b<;b3xeBYP*wpRI_ zS+f(mHRz<{h9bVi)ryn96Ujk9HMr%}7gzUAD%<N@Jk-DjdL}Gnt&^s8C6K?=xWSFf zYbDWUe`}%;#ZH(FxNP!o#cFfUfc6N1nI3^X%T;9y-Ew@5K)Azq!IqCIAI;q{{`FfD zZLGg$FHsA?7zd^r!hvTQ0jd07_U!DgSigE$S%G9@H(CzZ7fBL&C1+Fj=4c6lB#Io^ zG;mA5E7%JE<JX<P`5il5LH`Rf2-l<zRZcNhrdW}sgRG}@7K4*_N{&6{5xvf??R-_# znQX1D?_NfdPUw}l@C|udz&L<cVF_PbfvpMRKo$bHi1WW@_RVv>&?Xn(?3=DOY>mqA zG#ebJZOhSk)GB0{ndq!%1Nrzre)k?s1pd}gwXICw_W6V;uUBdnmWj@99J-4B2auHC z^ldsZ&E4{+@*&M2c|R<$WBhl)VGYEj#|{T6v%pABOxv;XQ5Jmn(DyLac*MvcTk&hd z_bGgBx)gLcO-VAw<y3S3M>#q^^;^GhOY@3%{pU}4KQ-O&I>o~CuYj|_O>h=41KpoN zQB9A6dp$cG0r{R2ao4o=3(Z_K?y6Y4_IpG8d4jhTr0`<j;`|_P*|4(2?SbvZqSCsc zbCK??)&l5nS3j6LxcIE21%@;0ulg=~?HEX!Gpqlp@EsEh17Q?Y0Bk%g;0T4k>E7M2 z)XJ#epW7*Qc5L7N?KH=F7nj?*cwqOKn2z>z9Jt{+XZ*XGqQcC1Y(T&5C8<Q)(i{1K z?K$JSxbTk6^N(uOK6&c>mM;5MK%Fciue;Rh7EVFV_7b>hFr5%G_Pvc&=;uZew^!*O z58n@hh_4i)!QILj!2o57JT(nxmGr~owmauA{E1?+cQQy8{D}8xoEHN;4aDTb0+&ke ziO$jUX$Q^DVmYK}R;7%_F&?ecnSPnm_{y-EHzmD)<h{NYJHB)E@shN5kO+1PN;Y@P z@uAMr+{h(Zvt%`PY)2H@PQcR+(=tYt<Bw{PaREq^te(Au$)AXq3ZSACvIc&2F@@ig z{->6O2Z0~uphY>G$!n$9pz<R%4BAn*(mX~sdwo}rvX2pk+2P~QnNN)2-fRAHu-Tb1 z>)^3|iqX5bve5)?R!;`yQ^u?BSBV@F^AdoxPgT^B9LN*PwfQ5{W+VF1cfA&lb847< zGKJYd=Cyn&Le0<$RI4NZl;x;UMX&6ujKUW;jDPz)a8v7!cwrGkktR=;4by>6!M01_ z5e31BO#Ng;c8vOY5na1Se&X#kHv(*c)TWMs)H%sUBUFtQO=pH)rK}rWIfykoHd@R$ zOeHisC{gB8DF)3e2aP<gx5ez%h?0s>`Fbr#XNtOyjCsf4Aiqo}H}Z$y8Jx|`slA>P zqkedz2?1G{c9aOPCd;feA;b2fA1kHFBiya^4cEJ$zmO&uxV=M5xYOA1Lr}3P(USO? zn}YK38dry**A!Bzv+Eb$Q<|DZ88Y=`FKhd=9uw!fjL@olk4Zg2;&`6gT7_91w;d~= zd|nA2OY&;3ggx=Li#5P2%3e5SF`0~ubn>4ZHWH4vI;y-wo8IukYYcz8&sT0&MPi9h zsjZ*XnVmU2LCtpwT9@MP4$jVaiceH7q`O3RWd9E8?a->X1<CZ4I|?~mu1LN9#xUH& zUy6KF;%i>OO-Y}uK{qLxit^&}M3ZD#*?4}&Ly*|KDsgA-QI2+9xBitP`7m7CL{ss} z04M0VN_uH_lP_P^@wP<g7;6J`!U@eV@%aSETyKlRp+5b+NSbt_vr!DY3PCY=(s!;c zX*n<2%Cav$t>=%j+@KiKogM+DF9J`uIljVIC!(TX;$lyG-hDG{q?ni2W!Urd^vMIo z{b4$)QxzXFVf-BqvK|MbnkG1#lGcEaKSH@ReQ#-|W}-i~`*@T|87*D%w&s0Y%<z9x zk?aYyTY@h08Rd_sW7jY5^XDDdPq7;(U+*Jf#fpRef+%ys#X)|j0sw&SV^$d`P~T&V z&N{J)d+yRQ_DIX_$*8#N=E+o22U#`F_6b&p#Uh<)QqZ(j08T&H8S&sCTo|_8Quk4? zYH)X}VcWiJ_H7ZvOb2M5fdpS|FoBYTL97P5hy>hA9vzlEBx?b?tl+MJkt6XLnoS1p z*t3usFyJP@R)5BU`W$T4tVu|Yn;Ovkw?mHNa!>m9m{bp+Pa?tK84&M2OA@##8o5A+ zf?6P~KMv9RhF#@Bui?i&Sy|XE?scP@Jk9l%dtvx<dH?(Nd2CMx(_CN~0pKqv6X9;5 zv>VWZN%Z%$7H~S;{6w1iXx9Ti6feJosq(%L`<;@<&Ou0W`B>^{kZV9%gRK*R9oV5g z1|mzqbqq*=w6i82<tCvTtwi~hk|}%61T?0?5BRrDSpx48c$?@W$oW)V2_H)+O;!}S zFrh?WWF~=Z4#~UpKM6>c{Ey}`bX@AAwv!~b$dvcgCh^H4a?2=+8V*<V2)mluYL-|1 z9O#P@)c6d!vzI?Qz<fN?AK{~T!_9AU{d@HLmArw>mw3x$f1cW;(qrw1i;$aRGuRy0 zwuam{w?Kq1%Bfp5o3~OOE_va1K6On9us&Z1bbt*wtGHfE=uE%v>g`_AT68R7#QO_B z$2QG~g|oeLOSNSbsYL(f8^gTzccqme#QRaWZU#HOy3RYpk9o0&A-NzPFZ@V3()0M$ zB(@-Hfzu$;KOEQ!D-&yh4ep)3M0RY!@(%qtWpmkitp4SfYo=Ni*j+KSY&z;1Iinz# zqW8@*=1xqjZ{(XIwwlIEZEXdk3ZWFt>_>tvz<;pg*eA)mduXSAla|9N8!V(~38p~U zRth=DS<U={0S76P4hMRcj9N2D5+OC=)rZJ>Hw!#JLwo~usICP5&{3Ic@=BPhaoC$D z*WNNND(uH{!f(3)-vRdI6e(2g0USRcF+(isMU;^uxT?*PZy4VAL+YK<v|VdFs5`0t z^8Ow?1=Sd-eFlFFrRlXW|A<c^hT66sK>dhMjv5s$>VAUCzz7ZvYK(w`lMfnxRaa_$ zUBWLxNrZNR8iKD9Bi7XlwQ5IJi%ixO(u6-c6!py=HF!TO{#d1C`|%1>Zt*EQu^G}j zd>Xcc_{FhlRO%6N?Dt5eL87#~x|2j;W*z1N`SoNfQf*;WKhyPcM~Ig5WRNybGq}td zgFvBbL>^0tRrG>FeS;rGQe`Y<WRmsTu77?IN~s+82%@=-Yb%Va(BS1=2vr~ZWd(Wn z=Q~BzxB0!p(w7`17@f%7Af$1#P<X_zq3KLXU*X~Mp9k*8Hnp31H9J+mqvgJ)1{0tH zevxgb;+n^V?N@t$Sn=A(g*UpNgxoA*7iL>Qy+?(Na*?xw)S!>KDN;iYWqpsIXz*lG zU&Qf3xMI+W(~hD624shH@=EJkT=0@%#78He?kH4U^{Vy#-NDp;r6%-K9C}xs>s5k@ zRHtP^t9|2%=WMt=@(;q)iYeITR~6I&d^XMAcbv1RTJ)pvsD8EJZ08<Qg9c5Gjd8fD zp`u?AQ|dILRil=-`+9M(Oo>6#a_bC3<iik3z%`CwQq!9}t2#Z!`%`~aP&G0{A(@+S zd#S}f81HtgCapX<NxJ$34}v3Bz+z{!P@v}Pw@4wt)}4+s@$fwQlHsFrTA?O&o1VY{ zFRo&CatgPawr%suiFB*d9%sYZB?0>YN`3ql3(`I^H|>Wp_^iL!b<hXU(G$bI%pQ7( zJ1V@xx?wJO1)1}9Tfdw2wX)ubHy6hw@(i0}Th7ER;tP=OjyCo!d3FbHjE)*k?Dlo} z^u&&L@#LWkT=yE}DTfQy>YtJO+r+jhUtV4)3fINn@v_y9c5;~Bn^ZFBnh^NHvxJ-A zqE}&KUs#!RJJ1Q$QJuq3x3#w$avX70Y1e)ebuA_XdR(RS*(j(^I2j3xzULcp=4zMB zaoZ%_$*Yark5ixlQGu##rTCV9-=TpzJ>LvfeImAumO>I|FCy~i`%BXomI^2g6>e3w zwDPFw^2_Yf1>%=01^lo!B-A7KS94<B3)m6h<D7M8HB+cf72CCaGzNGie=}3A7DgzR zW$d+kSupFaRdHRKqfnf_Rd>2uZL%IM(Hn|P{>Y+HfU)dypHQB$^0=gPG)BoI19Ih} zEqc>bfwYysjV7BnD?P<p*&*w(G^4XxPsK2xtD6kb0?v!;7&+-OFmiulR=QGlb!<>2 z;jF6s_&1bzwrE!S`mxoz&b#hw$XdXp6af)N7P|pFKY*8_zcZ^<=rZ#I&Xgc=;46S& z89|zzk!U>Xs~OMHLFnMw^PXcN899=(#f-dQb%nB64YiT)hX5n-?kf+|{oDA60w-uA z4S%wA{&LE3z;v^aRjf3jA?~W}V&<{4;s{hihcGdO1kEsE{Q<~VRz&_E@I0P&8aSni zsI@8k49~#*Ao}^ajqa1OlL;*QCJTUPc@Pc#o#C5vIgs^9m(x2?1NbOau<3Y)Z;zGw z{|lN;(9#5>%SEn$490@apq)?W8QL-coHe0E8?jbi=i>vA*S6XrBy|M^P6)Y=3YNzh z+JwI#w~_LY2TT~*62t5Wy*6_z!xjhf@zp>$*FO3Z0Mf>|kskzMfH;Vg*<`SMXE$XM zMBLh-6gn5(laX1h;IY}3gRtPuSNb>kD?z8^nH-0@>)>VZSpNg_0e8gSF$zQ6^%n#Y zx4L&i4#LV)NoRqgRoMoZ_cidPf&@X}F5|es&N8`OK5`3683!prNPxTX=yHOY>|2EW zh@*F#W;QW$kR!rBAPV6)7*WL+Ob1K>VP^{V<blM(wYjm*Ao*_4CC-n9rSh4aMGL|M zY8@!$VRH$xrKF?1nzxQRSnw#=QWL0Cq{<e_tRVmpoIpCZ8<y{*hV>JhAEpbf;q-Jl zovB!cE`d>7_){%^Yw1O=GO%?V$!)Yy1OuErQW9p|p0Yl<K(f`8R<{o$ao~OWemHB( zQ;^0jAi)1nRc?!nWeo#-oXLUFh-R&ESjqyd>T=$Z0?_X>UMN|Kz5@rf4-LT(*|}&u z04P;uOJ(A)$F_o}`TxeEO_kPGpld>wY7mhwKQV>_<{NZf&3kFH4e=2M6LI##F-~&> z`UB`MrQGXFA9c%fAH*^=1WDB90*B1S?RjgPuxcOMSLT8`T7a?H<LLK|{+&-SUG)V? z6a$Op(1Qe|q<fH=EB%UT52c--%LhraO)UY<fB*rNlduB})r-1Z%OhE|h37w^1Up7< zCe}aO*jFg!vV{Der0%m2D@HRAU~&xOCQXi|2{>b_ny(h?Pa@peZVa1VaQ0rxMGxIU zFLc5`Afo}fi(cspY6=o*q11kO7#`tZomp|<%n`0n1WbiXT968|7;scbZ;<g!4h2hF zE@c;NSF2CB%uC`Ez7&2XG%4Z>V+d%LWUoLy8u(BC*;@E2NtOs}&6%z|@^-4Ve^>-D zUP9y3`I8wa`WlB^=z)PSZU}U<DSUzRwX|vS$BPj^tj=T)95BM38~a74i6;sXs!BW4 zC!Rfgrisc2%X-|$xX5$TU=>YHUl*Kb++(%?a?U#FskDB@^k^p+Vn;R?ggJY5Oa;Jb zlF-jUR35h31g|>MqW5N9-{G3@uA@&c>j@<VS~&iy*OBhu(t8$(WmUYNxDTZep3j4I z_E>lCW%#$R@>9|`T3|3AD3Xe~SjpvPIqT(TG)ZFeK;Ha}F=llNI*DwIkb`V4oC3Vb z#ph0f@$)JTh=0H$wm=)mR1LW~#x29$X|vRLYtX;Eg45biLh0Q*Y{oU@HG5#^3_*SY z1E>kEWtlPBB5DCPZt3$t$8Fy^h3ePmQV)g5Y99lm#cXbZZkFa*$Z?WIMO8&ChXE(y zI>*DlsCzio4JrRawybgn@_Vh8XmQqDG6`~upOW#5HLRY6pRcL~LXPe_8Y_CCnZ!W{ z@Am#pA^c+_m)Ta8eLkUS)Ff(VB&R_n)!Y1{;}R_co*yg6hHVAj7SA4_o^01H1+#oj z4+p_MZD|^odXc4h7IMoEVTvNDVLwlD4oxid>QpV|!#8#>b5%C>^{tnfQ@8q|H~yA0 zSMN0FIGm+7mgZTAO}Ec#o|;C%q_2GZ2XpKhSiT4H|9qb>j{K-tIZ-l{rr~-J2s-MS z0dq&6*pT(FcQnqX9K!#bDOU>E!Ez~_n?rSBX@cq+BgV#6HJF4+b={J4pHiMD2`y%` zzS?pr>>JxVpT75}qWbxWPTy<owK80iu}Cl&PV|OEP#Y~k|ARK))+xLbccNK7@3dhc zpBMa(wSMHrW;-hkVcCZwIpf9jr-#)Y)#EEY;;`q}2>qZ3^Nkl|%d3)(7w@$!677GN zdo(pXaJ#Yr=ve7j9ed~($C>sK>R<o)cKZiCth~Vz*qtLR5@2bj1xeR^QJl-0tcaFW WjX9ok<yh>Fr2>zQ>4X3LYv5ny`w5!> literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/60kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/60kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..169c775f64166a7bf1d69d6a2a30f10876d8562c GIT binary patch literal 127441 zcmdqJc|6qX|3CbeEqjt=or)rol06yeNRm`S_DZs)$(FshNJ?4CR!T^=Y$>vvETLpy zChJ(UXY6B^_uQ9rzTeLo=X}n&@85m@ck7YI`<gM=b-iBK>-BuC*U)~@hM;X{PU)V4 z7#J9!E8rhQ>w`{0TfmTkVdM9fjUOh)jo-{nOpHt{%q%Rw|7T^}%EHRV%EGdhV=Ei` z#t(Sn<Y4FA7;H@P$49p?Gcq!>v$C-M{wM!Ozi6K!-mP1V8Mzr5_Ci~D85nsPXtfXu zf*6>8-yQ?>KR*mx7@3$^Siv?pz#kND1KVe01e<0CI|hI458j8Ec$v5FIdX!9@4{8q zy)HZC?>$Z4Dz24Z#ecDlAaV4XYako@PJvy5Li_ehN*$0^P*hS@QB^znoAxQ4)4FF2 zFBut|TsAecxo&&I&fdY%&E4aUr<b=+(EZ>CArBvgK8uQuiH&>yBK}Rv+tjr5jLdf* zJ{A;yDk?51t*)v4Qdi&b^;>&KXID4wM^EqY$mrPk&xy&Y>4n9m<(1Vn;yP)AE(VD4 z53<1TKM4B^UA%y<EgNURx<MDi7Ekb>k(Y^i&k>gGCoZsFb>Z79e{bs!t*6QPRczu% zFB15#xwf(Ilu#Jnx3EFl@09&NBP{U$6=nY+>`%ISAx=gHaCnTo5E`N|meHVy5_l#B zRttYi_Z+}Jr@*t$Xb$7{SXkbPXQkZB!Olb`aYSFxhFtH;(V)mi7^j$B+PMHz9+)E~ zIkv3~mXh~q&}cJEnnuUCd9-_>5cLTfl$)}Co@IQ;1<hS|Rlr($FliFsV4`d(8IB%p z$0Mc6i~LQk3}%(wV9t8#2h5bIQP$A>Iw#z>ABkq@YSZ4qU{H%%WG(?y!JQ@omgx`C zV;pWY$btrC<Q@uOkF7`0SHYWElxgWdpC=j1-h@g)x$L8eh6D}rqd{u(PJzW>2anKr zbaQ~9_Kx$cPRTT=L97oc4lOcLK(90Q!8l&yNhnwE3k_NnhDkrM-%5MO%B^Y8o+7Y< z6D5ODK2$1+JFW_~Fse+wg9Lt>;rsJ>63Uhnp+WT(MdUe3@U3ovaCmgEkGhIz1*m?L zdJ~{nE(m7Y*t+?8=yX;L!HyE#LUqCXlzEr5CDZFMqUnkL#q(2o?&5*~CEyp_kNSR| zbz`GUy%@@UXBsq93LmlTx?M^?f_8u-xqTGQ!K{TTB`A}+X^>ZkJ(Sz04H&9jM7?c2 zZlQmtSB?@Wi=7FiLDEp+2I=A>_;qewWCWhv`_W173wBW?idsv9TD5P0gG2|yW5RM& zPc&(3?zK{w32;ftn)C}^=G7Ed0Lxt=&QOht$SqWvgxtsV*3&uIL3qky4&u)n!me|m zskhPJjkTSKa)?$7AeLuo2Sew^Ii9S=FKz)x-~li1vGBN~u^;S^zn+{$gOb@tGoZ}n zymfXUan<moRucUn;8;B19{Uh#J~790<uf=xGw2L><(R)XazY8e@++~yC_d*c+_1k7 zspwc||ES6ADkcLaU&jBoL6XNxgI6AMvcsQ`2A$Z!kg!4jg`vcCW?dR&%?e&K`;q-S zk<tbvBAUeB{RQH`H=0-Cv;tFOi)I+>tzB``G>9w<xpe~SZ+b~0S|4B>kjU29($H}V zn0AjTdZwQSP3l={L;Q&&5$jO@#%d?cTC-`;4!D73bTW}7)XItiYcq$T5Up<P%3>mE zTkc4)Km8~`B`ZwE@Y#s2c!!;>-M-6OwY;w@4kZ2{6;ZeRg6C`C;5)I23sVAAH|z0> z=UI8E5m|8Sp$UYdOf<Rh)~d(MA+pcXN_)q{0Cm^X{L!RsKE}aUdx?y7ua&yzS%dwQ zJ^c1Yt%Wgp8<Ac|Gh|Y;QUMX?`VbnFM{L_P!tKkkH){z|WNj~;llRqo-qONVYkT=F z%e(U|t69l2R{OdmDB|(j-O11EG`=wEz49O@bvxri{7%>&Gq<ugd3rj8OC+{ATO%oS zZT?4}Y3uIRTg#6^bzq4)?HeNHHW{qFS$A7WYat$3e$7&e1$~Ka(WUWxk>={0;l)Wj zEJ%G9c2WT7%3WcKj9Ybfsck|2^iA0pulP-yt52yt=^l6c9Z!nUGcOQ#hLTNt{|hBN z+K~HeX_<HC)$ukQu{!%|S-mfW6Q?f2bZm7bq7aQk=zi;;PAN&;C^E{J1|?axP>C2q z4iA^P#Z+%xuLp-`Ao^g0yscEp^4HuqA1DBJb{o<lOA}HnbIY8i91?g3zea`YBIurr zeWV!Qcgx-UwOlfnb7&-1=d6UwX~E|c??s*B=!ulJ1_;>Th^GQ6a{Bm}Eo90nRGd4O zF&1?$!RR{ki{vX%i{Y0$F`{^ij~>vlm+L}M1la^UCM6Vs39J`VHjQ${LZM&iLU$~Q ztq;bp&>*3)v~~}j7Xu1?fgIbn2A2qujLyshfEgV`udyyBam&!tpF%&#9SMb!Q-PpO zwVGR6)rdUW#Ut`8*jD2{-xq^TXMo$6w?WSYQYMtCDO$gp8wV8a7>0~sM=jPK&fO~H zx{!NQ_U-Gvp-hp<wi4XlBF5StmD_>VO2G3)OG(^L^vnKj54D7k`(HRnn7w>_$3Z?z z^~dS@^IQ%z$Z-l@=KDm0urr8a@Mr`P2|@ti7+#KM=!fawiy8T#c>1dT;m6OOeECv> zFWPORGG#H2@e-yww~(`__KcGMy82J`qs}hrj{8S1+?yL+e7Gce@$sv0c_(-i*WX#m z18S71pRC86qLa8sH^152HJ<u2=6Fs*|HW_9TXc5Zdr=|^jp6o~lq&-`X@u7z78MwH zRyA^HkY-sTnSdYGp&wX&*}+hEc`80y`F)d8g4&xi+232=LyTV~`MWl8L1FGBqAm%H z7Y`7Q_+fj-Vx+4bh?pceZ5T(f-!yUxc@rS3`*u1<Tz)E!X{XBGoivCYvuW7^^mH7x z?c87FGdKNgWqx5tQc+381J&*OOu}_FZB-^us0(2)-?8SVU`CzIRt?yRH-4?}O(_4m zCt}?2^$T^o-T=i-Lb+)$rsywh+$uNLURa^#Wd1x{BGBvGhs5M}oeUM3_CoWIJc=;f z_C-DcQpHNfbBAt2Xm_EeVggd(aMav#GS209`1!t7V<?m)ysFw=u(f=jOG=r9=TEzs z$G5Ha%ujN|Y7NvR4?K@krM#|!V9N8FTjC|J#bfNg{!$ydaw9<fD7^&a%yX#w*gmew zJpJicd+eozPumZxR?V3keJA1(t-~}3$3uPI%Cbf;<vR2Oi{m>O+JF(-|MYXI9ZC0; z^9X*T?-dZb)^0g^{+c1o<TdnfNMUR1CU7^7dmuZ};lWbedDYkJyY_EUxnG)f1dq?8 zWhVlkqCo`4c_60(<mhEwfqtM^)21nUr^M62_idAtt;de`Vqx)6&F}cb>I`2;N)l)N z&5?Va=(S;NbvmJ*65@;iu}g}dwPy_3gi+4uvz<xUK=0-Cw(Yido(}_(w&_ZWu+P5Z z(nC%Zp;ms;AQD>=(<Y(%yNDg5$Hx+ucExM8Ve+GS6at3ut_z>uk2(X5pz~KSBxYbz z@ehCuZXW%TN@7>@poV=)WUlzKe54`rU8#B!|8Cc<l0k->h;DGQUKA(=wk-s?k#(Nc zWivpjjtCzsqnep#37hVJ6gc;6$H8=VhAI({?02*3vH;n4p@*zVyh+^F^n&m=AgUvj zKb?yAt=f=`j-71Bm?W-n4y_I$Mk$+C>t+q3L1U5vRNn|HTb5A3CLVlHzs#KhP^%|# zO2gEj2HCBzPV8zv8XmHk>r=|Jg$6a^D2z1dMiM7XcTy2_&t;)fjPZnWzNylne#i5L z<u|q`Pgn*3O!6hb(gT~$!!aZb9^00<Lco$ZOl1E8%|?ndS?1LJPI|)6f5ueLg&tr$ zdi9<PW7OyUCDN^gJW5Cs35^7FGW<JFMhga%FBEk;|B`(FLR>c{VQ}x3fD;nWRQNkL zW0NCxkz?a{9MH>r7RMpaKV6$kcM=z7{>RH<us-R>5O*?ac%an&C;G_st6qG0FY$^? zO>S61EHSIPbguukFmC>!-q)p<raj93E}AG!q!Z7!f)$(k6ps&9s4Xe`&@UObb$j{U z8e;yGwfvx|l><)B4tA1|ue-hQE!fncSTXbJ0!O{ijSP=0)J{j<fupy)E8A=H*S=0H z<k=GCMk|hu=6<9>TZ_K%Fgf%FcW!%;(#5n#WN!9H9n2Wv2-Q+w6;x<(313>+S{SK= zN!S0N6~a^`;)7Egf6=IX(K|0E=jP2>XX9_p?JCLIz4@mCq{N={|3nL3A>e8nANuLM zCCV7YFRp3{IYpX^Upe|z%q7tWTBM?f*B-Cvb7QufPPQw)Vw68qD<_sDW-x3a0OF@# zJfxp+g3pb-g@_UELYqS`JaVMX&y<;Mm2G3epSTx^7Ft4!Fs^2Rz$?~ny_H3D#}$&$ zVSg^@7M-_~>-Kr*@#7~EL%+K|Tj;%-?o?Z1Ip3RCJnN3w?f_Lasj6iKFauOJj9=$6 z2UeEKb;l#-je`(>$dhIJyjbm`*L4Tdsw5A!MK!B3s!UlD2nqs9IJJb%Hq$EhdFzkA zUiu8X6iIlr_(0?Dj$w(*aY%{sqGG2NkwxWXVR-fpUXA*JTPCtkJECR`r}13dPRN#< zIP>KMDVfSk+zx)u`6~Q)803}8k8^~1mY?5R;j_#9_9>S8jm|T?{9@7&^h5nMF+&j( z;xeTarMLfsm3`NsN_QVajLTOE!a1KSt*l2Z=dcvtdITtF6(EJq>0#XnQNB2V$WLe^ z)~tJH)Z~Ynd-)nYp83v8<3RxXjNd+h3a0@iVJ0kMd6IL>sx`y5t4EAtCNzaEfxy7c z3NSii5<L^KqWH-Ct}+w;B#4L)!kO7;Q71K-|KnXav9h*yuid-1y?+d5r$J`WWX79N z=-WaZ<sNqK0}T?lNcFgTglV#$XZ<F&0e2v1(jLkh6b8=3IF?+$E|d~9>A3cw3h65v zC2n{LJr}^vxj`%|20{)T2xwaMZx;^WK_q&g2CaZt7HHRgp5&x0q2TOy0aA`l!d-IY zHwpTWsTXNb>48qjqz%isuXT**a=lbWXYrT7i6c*y?)s5`R=VciLGL0KRhKpm6L1gn zZu)(F=~Y;KovX!92wKbQ%^KccG5SzeU2j<Sz@glmZO?wGJX|tWd%`nPukMi-|10NE zcDj>!qi5(P6|b?2?1@@jP7W}yx_64B-Q^BH(+nNgrjl{8p6EnBUl0*jK-sa7_H<$1 zDCz|9#gL`a>gqRMHOEI=Px&3*bwzE31PntJHL;-SR7bTC?%|j0cac-_Z*QFs_|hlh zLy&o?dQf*Jo;1jzXYS<jvFKB{O3dy2y-<?RwepXnLSAmeh08*NAwxN8=8db@I{Gs` z!s0}-y?c37n;`FmyqbA|K`$T7j;c3bSEX32jCZ?CGmJ&JSp1IL;yl#b0G`8qZWJv9 zjj&+T8&j=ku9%-Kv)bwmRP7v#3laB%*w2^o`+=iZZ8UckTmZ)g^o0RCWQ}!OHkh&G zavNk}I^L{veZ#slm}(pa2MPoxcZL$?WNh#Rm<Mk341hy%O_7}cRa9$wYwUDPt6hQX zSUt%jXQZ@GH|^xn>(4mz98u3yIm(y91Ito|F57-A?ZViFH}AS@Yks=}V>r%G5G#T@ zst%NPe3OyR%_V>4;86L{b+%fS61#s(iSu+iqonvxmbW-W_|!qn-UoAU><j9nexCm= z`+Z21psJ{k4T#GG-jvQ+e-=8PGnlh4EmQu-R8bDEXVJhB#`g@LUi&Ukr7KGa3kt{d zV&g8$8$dDl^=@fJ>+;KAe$Cd;edNc_0M+>Uj$b^fw}BLvEt7+$G&wecao!xb!D<Gn zM6Ji?7#Aj;%kuzwBgaE&G6D>QOs)=N)}bmI1Pozom<thnl!pUuVCNwUAouMVwKg&` zHg!O6`5q$`^~n9MFmnwhrfHWea3k>jTjTTJ1H|KR^%6j=utO-aq8pe2Sk*v{uBX%% zYJ7kiJIE!-s{_s74fG{17<|U8#BtgWgcEcx+}u!MdoL5@WUD_4_~ec)Rm+Mg!{<*` zu;|!<j|c^*k-$7M)0=FXr&=B*@E1HY@VgQ!0VQNR1j4Le)*uVkoRUfRoV2CP5=xwP zx&@C%=1Q08Ga{PZ_?3q9ED5g@GaU~$ruXQpUWnaRXU<3fN4Haa_*i<lx}AsY$3{Ut zefh)cJ@=-+^9=CALzr4TvlseANk`#&Q}$2Gkqc~?!#;jVOBTwtayt@tdF9TS=}Ooq zEI^Tq8ETw&l6Y)zu)Q3E_VCwV1?X+&pWa@jLE7)1Z=2gQY$CdzBkDA?_F3*e!q!nK zf#B}$?kqo<HT_waB|dKZ)=`ODJt8h22n=J-nEfI~d>=Wh|5kKfNo;p`NNc#ZztL5) z4)V>qAhD)NrV3kNX6Yc5_Hz4M&v$u6w|5<Uw)-Yy_({(5EdKZa^iU#Rm?D>9NjZ+| ztBOyEDR~MP9D1v*G8G;3{BX<KIj08L4h}+g6Z1w@%ejVqGu|4NXm}7?qMypK7$nag z!+jV;s;n6+rR<f3(r0HDa%IRF=Rfo|xrux;u)S7%y(N<$SZ}5k!l&dRG#5n^Y5l<K zWOlQODgWt`xWx6*sd%WZTVp%&#hPW@n%nQxg6Lr8yLb0ovs@0Hr$J@hTc~XNKT_<- z2mEA+K|_xtP)O6@LEpTOdmIX;Zpgjjj1gpbn&0y=etn`=C~P$^*UHf+x@lkS+M%Um zub$Pu`dN{_%7`oUm3zEoZ~Q^EprWIHKszx`CNL+WF5n2(HnC^sGfLEhYNAby!uWsG zzpw7(<TlQK?X>F9M5_B5mKi$~Px2Tm^`Ecp%lH|n^{lQpW&E-TFOt;_lD0iXXWqAC z9Z(N_Zam-e`NQy*Wx;E3j`#c{c<6-*Y5pOmFnJ-x;GyNf*TYYy#$x(wN9W0{tYLRM z2l=Qk)#W@>C1+Pg9w|zVhc&;sUgDsnbl2)#@yI9aRk&y39I<Cq|D@r<l>`O-L#>Yn z1(gJ1DyM(V1;{%^QQyLLPKiD9Ut+EJG5ja9kI%i2u`LQnx_C}$R8n!dDIpsE&@$_c zd6RS?&nsU3JOAyfw}Lh_h`|t0ts>Xkx9Zb|a8CQ&%^Qk3Hd%UK+bHej_XASX$~MU& zp$plGhSryfY`E1ZYE+&&DkJF7$E3_{vE=bcTj4~bk;)6jMe*I9g~d;@pO%<hRAmwY z$;r|$@5?GbKI#7|sJ~s(dcRio7n_FjI^rt1MhdG7{6S78MWw-S6w7qoFq{!bB4vV^ zSZ|J|U-U6CdUw)6BPV^|JSjP)wyBZR`N@0q0oDxBt-00)owo{w<GOM@$~rt?)gqk- zH?;CI`cK>4xcYf2N^?70z30%AtYbvP{!psx6}CNJg##mRyOp6rM4gVBzBFvhb>7#Z zZj{l;HI^;Gcly$^h=MT|RaX9dxd#WAe+>4{d{Hav$<4Llt>L`C#ncmX<;PdlnFl<K zME7j7u%B4>_eaxvMk9~PZ&%)aCsQOb6|&dKb8<PeKf<KM<ouTR2_K*#&y4ZT6~Uf( zr}bBro;#yoP2}D!?Cz%=%zx0!5#9abez@|sAO`d2G-&6Aj_!=6VN3RAsrgjjoR4Q7 z^Ory8EV(IK-!Y{r(rl1PpDbTN3)#n(vJ|W;xq3h9x^7)uLyhV;iM4?1YZK=aCp0-h zcAfE4>sO@y(*$xkv@mMgF)aiDrZ0vxB0T^JYNVB*1wdp9(hM{4AnQCM^K7G3fJaL5 z7LzzPvf*kNrtJrB09cR3w;FdFWM&&M!Szq@D}5yPz9dG;PLMv=Ra)&q*WnwC=dOB9 zAjjvhc+8j-<ExFO&8zN*Sqy>5XeV;56o`sNUJ!ch5Ipl3WXO#+me2Hh5|!LPMuQ;a zT5gvdFWkUAL9L>Efn1`2tEQg@_I3)7l%+564_qh354+>nxAp<=$sM^?_70Nw*9TL8 zW$wMCI>F^Y$+6u<<hqxd%y&o!&^<drT-wNt7}c6MzX9{?1r-Fj#Uw6aS!KgcJuZzp z?^RB0l;BN&7pveQ4ljhelvrOEcd_Pp=RVnji~#x4?ef2P21Hy;kgb#p1fBbSN0j1n z&pF@PX&hO6zv$I5*Oa_lPAz^eBRUIqp>m2f62beUpZ^vTbFQW@6k3J1Q((ebE1}}J zYGilOOJlFDo7wxAj-44}W;Q4x87DqMxRGX<i6Wau>{u<p6{7i^O5eqWH(2Q9b2He6 ztMuH?ij+ThJZlWIZJ;Hcm}K2s*>lByEUaP|bb|85---qm=*)(ZFL=qFX@%`ic)W2E zazC+s?qo1mz^=Csvz1=iaZ53Zn-JZ|jDAjp8>!iTiVJAUp3;Q-ESm8#9dG!;l_j$K z?y38QXw;{A>&&(hoNCd6>IRZQ<;QLZs!Z6GVRt_td3fd4TFceJ3g1iAdm7w+X9(lX zMPwB}yAZ>YU|n<5T$>kc^;^F`mog{@nFylf>LdRl%zgYexwjvVI2j8VemQtk!`&;n z!J0gyz~E_0v?Ooy+fyPYu<#4({m$`eK#}<^+x<%OPd9*D!q_^323?<jFep!uph4Tw zH)s(5@nxlk7L5dn!5f-_(r*L4eReA>#kB|}jCZGGw7~vHbrm{}Hj2NBz2>T$=S718 zeVs}xioS5^)Vyz)v-M0Zh~u>z=X{cEE`~jV3WKiR{RV$btci&5^!ZX$`w$a4<shsn zd#F5nXY(w<ZA}}~LU2RaQk{?W87ydxTPaCTd*}>>r%;W21ZI=p{&0W=EBD!xtac8{ z{#L)uD!}_0`;xOE!gepidfG$)Pbgg;UrMv<bziE}1rDRBrkEo6BGG*H4xzFzwT670 z7_Wb(-Q3vu#8`>^%_x`8<0c~4N)vyaTy<@~t3Z5gvcMDOx7@niXni1F(C?$f><Pv@ zD(oqe)L{#`IRP?yz>i^}t0<7?QF6CLNrCP&Cogu+{N0D-y+<k&an3f>SlH$<57cL? zIL}*qx9$DaAQi5o@aIeK?(PjxpII#=GNk$OFNlUs+*e;~Q#|I^SKhuJywAEkHNV+) zD~W6pIYx>nHU4Hzbja)3V!3~uvvfY>(tRespQq!b;h_t!{O`srx<4(ysBrNBXF4a3 zjixXVYx1eIoQZE?JRx&GwI66jh|9h^tO;;@qEGSLq30e{)xxrwxl`TBg?yIgTJuLD z*Bf_X5<Z6SSTq<A>*{uL>DA5cE1arzu|Kc(>V3_=_|nAapc*N4UW-pJ{N3PVj(11{ zgwn1<V&W2f@;4vs-WB=Xl*Cwn{Md35o6h}13Z~-t1r~d`8_~0iwl_b#&=LzdR^0FF zSKRC*cOlWRU2b_PjhJ{ozMEQfIR4_>nCQ9_3=enDQu57thMi>P(X)Nn9gg@LrIkj3 zyRPp!b<NcC{mtv+0h7lag$<a99@>?e-gy?;1`;>gl{x2jUf5UF`&J}Qoan=+Da1QN znl<Ejxbir8cb&+&o~iJX<&4x$54Iw~yfpvyfl@8EsHnuupQYrM;5$nBRlB<_Ya>FW zgNXOMKCj4b<2>GUL1SmDvvKd@jgr07UdA#GhuK-w=g}d%W<hugAg!2{JTYUHKFTG8 zKY`oVkz>2Wt1BZ-trwgQDJA1#|17PA?M|G134GB3bYvFzT$TfBkqu<1^4t-v>{f=T zX{X2qYf4BONfHT^$;&<Y1zr?;2})dBlQ^e0uswq5nL_4acpM<~q>MS3Ab+DuwmTC& z^T#VYAOO0b7kc)|y82>~M)Q^b)Y}47HzrV0-+sF5Ixr4#ZlF3S>j7pc`MpGEY(QE= zleXh7XtEe&z7snjNoE;+{T2L8j`e@3v?b8h*6@;@IGz*$*Je1R(vSve@%Nu+W%Z;% zC|7{{rw|X(JKeo^Uac;aO%aanV9F2Hl|-F^SFK(EXTJ|76R^XYB8vYhg=fMamRm?H zz+~V-z`#Df@|ZkhdCtk#{Oh$a6q|@EzmeEy_ayGh&|w->SZGaR>xc0_LE!~WKY+Tr z`t%G0KKG8fRy_AYI^Ta1sZV^#wD!ece+2a-YN)6lv(@45LF!9CH{100AB|pjFB<M` z_%YUS$`plr;%oAKP&kl-Dtk+ANO$be=dbcCH|;vRD-*@1whOwak!8ekFpGTa*8()& zQWM}C$B(UQc4Cl&erCk1)THpQDLcEL@kd~+^oGiOr1-0l7IdN2y%dVyg2|&5FEbR6 zSK>v?;SXaqJ(eM9YPcuU%F04jtR^pVKP{7W@e$-1#qY#iU4_1fDIKr+vi2N&FB<S_ zMJ0(RpW;pCp0wVkn5ll15H)frK33q@4YGP|>7HBX>dub&@|tVxB;-}M{79_!ME2v< zO<A%=^olueYwu*_>*19@ZLxS6R~>70WZ};92gi?nF^egEoyENTkY~)1BXOG(?%9i9 zD`j6TR=f{cKBDL*@qC1@M(j{3T;TZfdT;l<jc(qRCCj&woX=|4@}6q!o)!qH_xT!5 zvc&efjc$Ks<DIE4>h0~JKI7&g5wQF7(?**_pC4+s;%h%TbdSA$TMf=wlxG%0D3yDR z7A{!EO`J@d`pwE(vG&zr!^L!s97@&{DikK1=Mt#4=F7V)I*I0yRrIwyx(46!{hU<H zxaU;O=c(?>^AFm)e?(!Nc6iTxIDB;7*z?h7c%!~knM$|d*#N<7=W~K^Pn#hB7(&tN zT!)|Gs1u4~I*~`#J<E6fzJWLYk7I08Pv2j+8!U%cKNB$yL#W3l%B4qB97x4vBW&#F z``7N;j<({OPhRedeqecVjJNesAH`vDrgxUOw31a+ufKNCh1ANLG1Kd(RyZD3z9g+x z`Ww&fSt5IA$<3!7$I(I)iq@P&4@JJL%htQ*e(k^i<FW7)iG9t&v4ZO^a~92yGo}T6 z-YTt`bm$2u<cU1nX}oLl#Ed0+^-e+&X4P-k@}dbvYKyAE+}_c1uN?1`J}mLSa4po~ z*CMfR?W;@!4N}eFfVmw$fs$!qc&azUGeM0W1?5A`Ri=mewx)~RsUjJfIy>9#ZgS#_ zRFU1KlBSQrFqeI0F1K&Uo@@x<zv;1S(tncilMqXogRlKXr@lt-U#D-F3LV*I7?3XW ziX<j|KwYV~qIa<0a&Y$9sij_1<pSU9><p5XJU)v&#M6qihmpSWnpeeSJxYD&QWL8+ z?o5o@Ko6(uiIQ6ed1lZ`SqqOnt9IN)OD+G;4SP==B%k>NshoAgW#ox~oWUPGBI%Z% z=9hc-bsq{W8oY4(2inRhCq%#F^$yRDA&Cr$=Oz-!C5GAymM!!Up+i5=<eh{USpjP1 z?#;pN$+pIuO-J?hSv86{>;VX|?cH%mRJv&OQ`SadG=faQk7|m3akY{IX`u~IR1q;U zB%2#;)O72q2xcKSqUQYxICWpsGMjqvbHV+Z-@R897{2}M1_WPk1=I*)XNs2j3oRx> z$D{O1LuJ)Y-pbi&dgT~{s`@KqlfP`>PfuHhkAC?an5}Hu^;~I`aKODYY>0nJ%h}~5 zPIj3Rq_G1%DU1P?dI5^mrUBzCx(=7@2)>itiD~{R2En_dnl4oGZ~ZaxBy<A12@iis z$34W3vATiu?6neuIcF0j&=a+`j;+g?^u!hUWGmr3T^og;iK$8)%&D5@F@wIpDNCHK zIEvf@TwWW7t0U+K0V++(h?Ww_fexUb=T5(~a#-EgtAEgVo6Os@MzQ;twsCJ&$<?DL zGKqWS-vRppW+ew%NW)>oUZxc|Hl>?CyLA1z3FQF3$H$J!2!fsYY8n&_-R|nM$1ZN& zIC>6BCWz4K-*xT%lngs(wqTrn6<prF-79gQS#T1X(i9Emuc1Lsj@V^BAcNQ@L;<EB zFywiW_Imvspy=&rNq_W)>}dW;;)qL`!|{c9QXEL~zHh1K2^$paD7Pgm5SI+{!?N41 z7nHtutGgBD{jgD-6sSfr`HqMc6;-yUlvEalJM8*21%&9ffm@T4Lx)~UNtCXeV||vn zC`f|g0g!`j+hKb8bf{0xWi1$t;J@fA?94ynAK%uXpEN-vTz5USB{-LH)ts7Hj!vdn zEf}Yd*oRf#8)>>>`n+_^{3t5sInVI!A(G3ym0U)P()+3v2d*~j(p%>i(ev53qa&HA z9hhq&=bq-Yz3KnT@PqB^1Y-r{|9I5;$4T9V2OlLL-Q}a4>M+zVhZUWF$<OSvc_p6a z$#eFedFjqD0GxXW8p&CMUTLD{Uxe--+Z(RVas%aIB!4DJ{h1G9L`aBxQf{4Acdet` zB-1>3`aS-1&>~Axq808|>d^rw6W3$@6VJvUp&uzQtj5jqkMP2|UiFu|F{7rr-Kv(U zkzC*PqHr_TLS7N)D`?RDK(g&}G1=mIZ92KGz)#rQ(;c^E`lqf|aNkeWn;t7UHfauT z$ELc0435Lq0c!XkLBlsuJ1SLrrZx7)A5F90Z8h-n1&e4WGN(EdJ29D789)Rf2{T*U zvfQKIxO)od5aalYv^eqK;_t^5FA3fjX1w~jS;wktF<a@=rylb0><bgQ4WC=aO<x~4 zJ*zNZ@T2binH$ho_TXz<)vvp0qU<SqsU-z1LSDb>t4MhPvhL3n**IaR(AjNy5pm*I zhF+_!<!z&8Aws==D#SA1ospBhchZp;*KMw7g-E)(O!lD8nzUqPJ5E={T`FM`+nP{J zb!eaI9UBu|dHElE0y@+T3cEbK#LHh8cZ=?AHZQW1t~5I#Xe;3g4B(Ja(;(6M#A9Qj z;Iy}G+Md1`>g!eIUEvH;`yNWzjbANrpXx5jVL?bs#-Y87i>5YyA>pPRGF<6_JgiBS ztTd##gCH=w?TWkDnGFrna-S1h(xpL<g42@u`$=WmB5?xV9%2_0nqnpr)9*T6#MP8q ze#*M)V3T2``ONgARk?}Wr>XYg=>5FryDUVmEKFS*FDy(50w(5ZYr&QH&|kZpZ>GNP z-VrtuHYgdkCE7XtCzHFzGDCk&lKrRn)X+zH80XwW=JJouUOS%Mka5D|!TO07l$Xo- zn&H@P%<jsHii*XFE4b~t`&Yv%TlZGkP)?ll&f5)yBgm?^ky_;W!1=pIdw-%~iy1dI zH%7`M>jTFv@j2N*f1i~kp34=j?tH`eIrqv$-;{zQACJ!NS)G&EKX~e#Cr_%^3>DaI zaf|M5arPO36T8MEEtJ?uH%iAl6xx##)bQz)1#3bQw^-<}%}ytJlM4#ndI~)3ml)ET z!I*TDOK(~-jLEb(f$;|*^F8Cy0R~NVi1ozz&6v_}vS$Rl&ZEC<KxHz*&;f3#<(A%F z^63ZDtAnbk&V6rV7?0F!lQ%dn#rW)BA@^wcCO@CQ$?Kg%LEq$1N2-(i;Rgpc^jz@s z{AWtm(ZAsCdv%XB*}Hi(=tH+My-70H;Iql3rjSolQ*Jc9hFgkMn~!!RflkcV|GE#= zc_!fM|0i0wJSY`@{FuJ!@?`hG_bR>5$!xpSuiqKEYjlsA^A2S1&y9i>IAvlhtBWZj z1q?7(eH(gNG1r=YlUbEw<z<y!BZU>E&+K0*O^&;MyZ!b_P}SIZ79)O;5we|1T;?hQ z$jyQ5fawPe_4c4Tv9l0_PtjnlU{8L%^ZEIK)!suNf<<@V(K#I;t@Ui{?%Ph$NOu=J zDd_@Qb6!&H84C)4@ji|HJ%9Erg?<pgK0-MG+Js(4kftnCUG4%gjBKi>x+k%_gXEUS z>uq2x{YO-jX?mA_q{&RzH|NoAq70g($U#U6Na^j``0QUQ!!&4N!37ziK}Rh`A^x~g zp7kw>q-kt-p^RJ|Xv#&ebip~0>&6Ey3G<W(AXkG&9+at#sviTp%YxTHV3yk)z#cx2 z9N!0wp*|%{_X4Pe)W5~9e8oOZ;^qd$n=NI1FmWvcB<HdMb64@m@lhId8<vLrLDR5^ zF?M63MAEEdsyPmn$P__5Xc=}XX-g@d4Q|+uUh7-O?X$$($Bwa~K-cXg<GGD;kW)Qs zfyzpCLDKSNFn>NvK{@k`a1JQ%dcZkXKnWJx4bH6;)V9^6LC`5*ZVNOBL;k(!YH9rh zJH|zWoa5Go#-%pbUpMt={rBptBWht7G{VAECLD(*GoVCt`H#-2v>GH69@sGr$vncL z$BudcasUa=7U#gO_Pop^{lYf~NN<#)abAXqrVCt-C-LS;Hxbe)0pJ+CvCHCSmmrg) zqwxAx;4N5yTBD_+n}#wt@F(aM@X8GZhR2|$#zKSc-KDm)p>y07Tf7A3`>A{+9H?Mj zC$=D(qexlaqGHab5+vkW08Vjpy)m4=`e+YjD9Wv~^uxF^5Y+Ea-!uwPaRdxx|D(9a z|3?px8F)n{%n8w2vtA+4pzmFdAL;6RAeAb%6YQE3MUbOz#i1-ig0W+atP~CqnJX|P zZ<Ga(03z9dXJZ8fLd&r(Cs7!v^f@`w8j8ecthlM9xAJFs4|3lD2)XWsLr$=PR!A^k zQlV>CCvnrb6EY47hR2Sxwt>PNOE!tVx8=u1Io%pK-jS9#sxPoXpl@!bxC<T=0EcDO z4o~hc_JP`8*2Z^kFW|Krz7U$RhzmfoV<`L7)+j)A$AF}>r+d;R79e}L+At4pSwpm} z2{~n4sIy%MQ#$45ev3L&_SSz^{%*iX$(jE&+-q_IqhbTpI|(Env0=astUi(ia6=u& z*MSTI7G!eNnv*?~trF0>abNFCU3q!Z)n~Cs(FEC^;ETZ6#qGd=>H=X|=PaVSnKdSH z@et2=%&!B4YtTdZ)068_4~M;1-tv_@7qYG2R--}OGOu!@J_B8!KvO+X-vU5ca?_IN z;a#opq!@aB6b`d~6L7fjM@LO$y;A5KmYC3nyQ`Ws$X5}hN!ZQ-UkQz0XM?K?)d7f! z#RAv64I7zzD?kA~d;o`?AOjhfBN|l*A@f${NK04hQt}V;8?EKxuX4Gr8RrFI$BxjT zn=eV{StcmrLOfK)dMX98kb>}ru_E_I5k#5TMUrBaIp4NCAYEs9s=8B0L9bMK@ElL; zGZ{X5^4(u=K%#65)eU)5Tne=Uj;4dmcH%tcK6cokXhH0wi<)_pcZtO9T=hahrlIhd z7Z-m3T$<fLv;@c_k?_PGz08AJTfo*u5Kk$fNURZLB7W3lGKn2U_g=}mx?au~ac$9G z{Fj5p%m}Q*mj1U*Pzwu^<calGW;`9^chJc|HlQLqzpbF+OtTDm=7dDYZU>YvXA~Y9 zN!@(*iu>t`D(C<5-qY-9<#_&uj)F|T45Jg5dWD&uygsMz-u2ZBi<|@jnFVhBJR?2h zFKjxakCRE<5howW@%B|T7X*5St)}o5F$&f<hJsVvS{DS;UJF2)g(;4Sf#}gX3~7$a z?A*%CL&uFvie1)RUqs@i9|{@oJ-POQ<;dE{8S}2-(L~}Jh<*IAkx85_|H1+{?aETz zJlBIf$pr4|KBeF>8&;X1!9ti$+^%^YMYJZ6;-V$~uJfA~Kkuk^F5&Hu#*C@eH>z(e z>d23(8bsN|E1Znzial<Lgy<Rk5)}wT90eG5Iw>$+2DSCPhaQj1p3mKqQ`V8W@3Gi< zoi9*@|1b1AMR&ks;((u)9qXaLGPZ>Li)co|d^1l=eyjX!7@!W0lHGugdj3;?1dpvO zA)BD0|3jNX#i@1~a--(r_j_ahv&!35Rap7I;^>P@Td{OZp_jnCHc-3E&$OEKoJ*TB z^gjP4Ftb2OUfz56>%vWdaBR~ZkH2i8vvnw>);PyAyH4_{#E)!Ui$e_cjp1WBW%{ci zNgUR6lK&U2;1u=Z;d*QEMk?U@=_q26%`S4!isH*n@>WppfxPRZP9QPOe`P_*8>@a| z;9R!HBlXGqw$;uYOIui6i;p*5?ZyTIqkj<K2!N*}n!^9Kg9HP;j%8mqMOmdE+UlC# znBrI01H2@{?{~{>V)vw<KCtpK5o;zJIpF&9e__S5j#{CL@qS}ZW#5!oZC!!J3o(*R zw~xylN^i%G9RLx&HLxnl?9lYT9LNrOz;vtsA~gN%4LQJz+75vE4*wq)Sb$$chnErb za*_yKxKBP}F|Y&w%D{8)8(~&DgEelv&u()|8_;Q=;ijDYCf&G9s?79%gRgv<+A@A( zm#}!RupspMv}C4Y2kuXQ|NIs@L`tDYPdm^oeCUxg>%$zOHPa{h(x)$6epYP37!fD> zH7k)$2C~3Sm=hOa9LUqR8h?`7q#4;%Uoqj!;SZU_TrkT2D-hVrVrt}AEZ}^PJ>xO@ zB~f&GDx(n!4YbZ5Qa^d8Tdi@u?VxSfVFAvqg6p?^_{`|n&)*0(=&#=V6(OxJbsSW% z)X+CLTf}RyQ@uo)?@1&N)6>>?+~#5d`d<&jvB!y2xH4vJV&XdzuN{7AvGdl&+ov>J zPMXtiro@@9*f0{H0@@qNao~R2QpQY%0h@!T)S>Io{M)&jLUw(fXpcj-Rfr=#7BJq1 zBE=Y++W~B7q+$`(mEVx=9qBO8a_8>QccvgzT!ht8a7U~-p6NWRp0+EV5I>Dys>35h z^r#MHe`yhAp@;@m@(^1Y)vW<ffaT3~GWBRTb%-653~(%c<nc7TeUFL-5AfP3dwg^# z%OJ&6Sx-FADocNDPY)o!)l(XD{1AFRAK^DYUyRxMq0b>y@P_d7mah$?Pp*M(DH$;N zeVj23daVQ!9^mYS(8G#d*oiPKl>pZT93qY)$7Mm;KLy@nG2kxb*EBNHO?nf2`PA5= zimJNXtFA<%)^f!9lnbyB5g@KLEA$fuTaF-K$F~=vhdJ8O6RGvoRdn^6iVo*;xmzBV zDrKj)o;~Y&`0n%NB(87&H|s0=0oQ4_c_L|os_o)Y;xxiBaBJ8-t6_xKV6i0Z^i7XZ z36c^1FIz~>2cgyvcm~9RYE$%kD8u(y54Qv>CieOc*FDXdn(?>w7;V}s+$j8`{qn87 zPCtU`_sU03emgDgwL8*LTHi2jj3kq=OI<zxd8s?!$5+vq=~*`gV;n^(<O`m}uOUQ( zhLZ_vfZmI6jlG{Gz!JmZJVXe^126L1H9bOr-+2#>{5G>{s!TyLLFE}Zzl~=dhjP)Q zBL-_NOL>6t4_b-92iHokv8E_!hyj3<?lFiMRC~dcGn^Ol;%XG=^>C{OHt(0Pj*{fM z2?9dl^=+FbG~jwu(Siuz!r@6XqBoe)t(pc=a#H@wOE38-AVa+crabgL_!5CH(V!}D za^vZY$-tld<MO0A4*QAci~pft`fB)UEY~-!z8yu?JlsL|mh%}G`33$?`-MLVJsu0- z82t_&0s^_%AygtK0Hy^n`+L;8j3GMnJjO0d`zg|(nv=uxh*r*V<<)3nNM7%uRNvu< z5Uo=Z+pw&D@;V~$&Q}IA|41+2|7Uui6U7mA&^nL{+EoVJOR;mN3&(0MrsgIN!y(Mq zEoZHV02}L7>j{^o<^Yq13p9Wm-I__j(I76K5bQd8_)UYwJPNQLi+g52VAiRIAOlzr z+Fzd2J50HKi15jgc`AD%7ffg+`T|&Z_v<P7lHb{dqv}2(!HCGct;~1)#0Whz2=aO` zA>(H)=&qqbpA%`&Ua`jgz{l-E6D;6$hfxI+5K>l?7Fwtr);wrJvljq{m;(53uee=< zW8fhJ8uXOMHVST;P9z>eQwkR4Sl|W=kVDvLuz5GVV$f?nA{UZ_E;#6SgfLk-^c)Tv z6l7$j4ycO_76L=hmAv4I1RFfS67BttgCo53->0p6XSEm5B-%m_S`VGV{+&x{@2Po} z(lY`MX#-v+!^Po-4`c{IHE)+&7A`;SD^B?*X^gyJH9><oX6n()vVQ77SX75$#JKIh zy!20^S6e{e0yKMrnpE!Xz%lRzsMO0hS~H13uXjze_&Sti!+(>>f7(@=;zrlu-#GJk z#TWUJIBrb@#%%0l&vpC~DIMX6ph2?gZ~mv;P?A@V7d`#v6u2w!{ry)O^!Wdnx*C~J zZSWW`P%I09brT>~e`Qs-(ZpQHg0+5WltB?8uf{d9<TqKs_>#}0%lFpVRrAr`umnkP zt|1@3VkcG%C;}+N>`I$Cn$U|9fF~~zoq+U*)Zi(>I{ydi-mGp8knk(IAEY0Roqca5 zkahh|;&KEG%Ly$t`Ql@Ls5UF=OFCa)cN*}XRz?#^J1fQD;a3DK4U)0{N9iAq=^z5< z<O2|3HxNmOF1HY^tyBTpIt@=Cf-N8`u=pv%5!B{Af&Orvjg1u(Al^3qZP1f~BK(+; zfVl$0JO8@`|D4Q8{JRAFO>6&IF>67-_kV6r=iO*WJHn4%OD+kVCtzzL_f+X8vX(3P zOrT){%(*Vl{{uLFV7$pywgS5U*CX!oH(7m7d_3G}UG&4tX1L9Dc<UcZEJ<`H`1-W{ zlV(J}`2_!6Q6v7&gnv>_xe?4dg9TiQ1s9&xDuN8Cc^c9)CXdoAi5nVj@w<lKCmf|1 zGu>IvLI3@r{s}o>3mQ&YFYfpR607$C)&~39QRMPOz*8Y%i3V{_1OvNguAjJie_<|~ z$D8Ltr5GldBlj-1mraJCsKSu%oqtl?bW!b_07L$2pHY7o_J6Riz+i9OR`;p@yE2$0 zQ}!(UN?tf=*{v=*YQXBX)0ZQHff#>hC(Kcfwo`DeNyZy+K5fC+h~%s3iQLK#-zt6V z`laSnpWCj{MzLjB<hMSaz;6p)56`EY`E@u-FOS6ZeJC?BKSQ3R3NDFmT(YVbcni1a zMUZFVU=$&E3boWeijYymmXc4b+R<Zt00pe3D8Z(=j-$0WlEr*lpEhs!z!Q5*T?six z^_2`@z33b|wfHf06QHJ3m5(+w=_LZ1t`M(2km_ZnIIg6H*^S6}bj$T>$KL$KdzhoD z_ei8KJM=RnH=WLt-3YzqP6L-Q4z&jIEbNd0@JSl}bKl;rH+c3nUyM8Th*8Q@zq+HY zuIG-~gfoLxH#?fpw9}ur@qwqb`Q5_wrz3>XOTu?sBIFuIk9~YKfgaew&~m}jfZpZ3 zu*t^-Uk3ob34k47>W2N$GMkoRCw=2#KS51RyX7Ey|2ptGz30Nc_zmc(wr9+wj~}{~ z={@kyPd)><hq(f$D#H~+Z_XdtB7CpdMq+JCz~RY%XURkXyv|_;0P7q00)(>A`nVdQ zTQB*hmFAB;8#tRGTE&#n&?2gmJx|p4z^spge1sorA&EP-133;XD)@4WcW1)so*|jX z3#^m}x6m`GcVfN}gOHQTsFn7B0~@L3Zm*MwCUEL3h1WN(c+m|Y{wCnQYXDa!*KQrB zYk~jIEi>rq#wW{$U?LHCYA*1L-0+eXMvyZ5Qcr$NX>xamjIE!b$Jl@Oq0Kt8vAf`g z9e@}kq=4b;#z#GCu!}-PAfrSQnw@z<UoC)STCvyRbv670^y>KnYwDo~<*OAOt2#6& zDu-wT3M(AiG^l;jiPL~wKt+xDc*{}3Z{t@MQKX9+{%=BM+`hB_d5<fX{XgY|42ETp z33dT2r98-mXY$|0V1Nr0+0{b5qj>Qz_qk%|@1Aq1fz-8Xo(NpOj9RHD#n<Lw|9no` zQdG``e43zkA%#KagDf=2+zpxjr)ymDV8Q>r0=^~B3xk}D1x*5|F~=}};50GiP@f@u zezyqNP(<4ACehG4&%sCFvAZybs<mm<xqHJeFjgd$)TOK8rl0lD122qX_V=qw^CZXE zE;hNbd!6pQFES9FwtlSuW0LdfQy+*s6mQ;9d$2v)JjO9PQ)d6{bZ3}UiECQtrL<S^ z=i16X<}bzYlMRRGiQ+o5a&InMc+Fc81+$&LihiHTAl~US>S`BOv2J`S5eUo6*FmNt z27A|^MoDe`mjAVj0;0V@UEuv6zANo@(vavq9MNNaUQGOBWoJ?s#cgL^-n4Q29_1qI z8=uJgQjxU^bL$T(;g`a9KMV1eaJNVG))KPcFQ;Cxk<!(EyMAN2Vx?Pp%B&eTU^c<+ z{_$+Y@tio5&$#FVXJq>7Ub@?Q8{K~;79)}QExIJ`<HeYvsk%4M&}<$&L_#7`j79>T zg7YS2R(}I~0xYglNGIfdvF?=_U8@2f#SSkX-G%D}i_3D4RxXM0b)<ASV|snB+R7Vv z-g>jrR-2>VC|Z6nyXj|KL^YP6BS(~gL*29TdI4~vKNj6zNxXl7V%lCHGqA5x-pNs+ zg{S#qwX>G#Ggzs8_|T!*6+ziw37p1_^61z*74ACs+%gSg^lD<HdX^jx=xf*UIw*ec zj4pK8m*qH(#Hh0z%GK6Ue1ej_tmP84=D1HK)9gY_$-b?X4w=P^J*R%T-nXMr+N|3= z=Xz)m%Q{>oTiDXWQIAG}{tKR-iCPqwdm<~*$KT`xZjNG*t&u#U_q>(hT<C3Q?yu;H zdR`qTATQ-LDD2fWpM$hw3BRF;5+<{5gegRjSigD@v(rzjYc?&Ph|a-#ku3uIzN|H} z9iXN)zBB8cTGG7Jct@|#ym6aD&Yh3PWAeDT`I}sL(}o+pzg;*(N@r#}M~${oDS@Sb z-s=BQ)ZE?t{*t6rQ%~KISGgn6HZn5@RHagP<Q>N_drFkpH4@o)NFeL!ZkV-pvK~*+ z!4mhOsuRNregf|a^C5oz)V$%B<^%HcHC9Sp){T`9_URGdp3dtxtDXPkW%Eoo;ldc# z(P3sY6hRBqgBb}9d3^IO+ua6ZfjBXtpc7>-0#8<gycH|@rl;KZ=wfPJ)eW4|m3AFC zT-c)>kJ-;Rt+D0%RW1H$lT;zsamR~px(5nkI?_EVOC2if+sBK~9<m8Zwz~YzJ;nG) z%(PqGkqNi)C-0=xZk<z@xY+tC?n6W&_G5yo0U@?H!406L^~wM?;cme+o}fPu1f7_e zLD7I8C|m6kI&1vKH><2k%g9ajxk8zKmEGy@jv5x*jg7|UWL^>`5VoUaIU;$)8CQ+r zC+_VqsO((XV`F>Q&oI-hQSGD))7qMlQ)we}?aVa^``F*Eqa7Yxj1bC4nV3`^+MgPf z^@!9gnxPZ_%|mWq`saat0$IA`Z!K>9qvy8Q-4@`+H7}WUc8f*ZDoZUj#&2`D6ph;Z zBu1v_qVmL(tCHW^O(?J5U~gmX(Zu~al<hBvB0eh-Q_!<HqIK^SnL4g?#MS#W=qm2| zdA+#EE_BuF^GUAH*K)sA@4pmxFv1#55d;e5a<}$CuA|sKV&hQByuxWkDQAT_^yvkz zR`T_;pZojQzaCY0;FKkQ`cbX>Lc`>8+QaOkDzSs#333AL1vaAIh8}XtV&)mH?J>PS z%?onA&)a{^yGOts$r}mRdHDT9`97apvC>}JXHo@AyQJI4R>Kq2q_d(AENOVUk7Ra5 zg@zp{Mm&gg#ZRgx(TU6sv|Jq#M{0`(mGX%P-LZo9Nqy66KBv-i3T_+htIf2(G+?<) z!cP0%&r5Ro*KhBXZ;Kf;AWF*3nv4izIcJ>6$90CYM75~y11HaQQuHz!@(#w%OZIM` zb!1X-IH(0xniad<{_yTADh?%P0}LSF_?f(J$F|4m2Tr6PNcZZQOi=VVWc#iAr4=p= z!9OP2h*tT@nWO7E?`L#`nVNBtb;-My&M6G5RDCn6JMt;4St#QZZk%gVZB~(VWC4Y+ zl@Z?b84@GXh;CJ8P4~ri5LSyuo?}=;_r&Ts%i~X$mwpTzvF%s3)@IirTz|%9<9@kw zy=A?HuI6hkT1$})A3kfOwktmJ<ty)~AZN2V)4?O29iN&+dYVr}G*rZOTUZxfjP}0% zHb?NAKxw&U|E=u7FstUNYi-*6OF9oR#Q&`dTde(WsaOHpbP?68D{2&cEmj2S7q+35 zRc7P6i-21VH{8Kb<4J6}b;a{^g8=rRi@?}9*Hb}9cc7yW{m7p20l2gS<t4#4Q0r2q z5!9%boiu1#H3QeuwahbHLxc7S0Ke>m_XwV<qbO9vhs>dM*2P}yf!naJl&O9pNOXk8 z@0R}mw*}=%^zcz7>?F3QuN)ia`SQu=ljXO-!JP!r%t07Gj}%@5xx)H>EGVcZ=x7Sl zAVLC)#2i5eX}<1sxLPTGf}-Cv{CEz9jujs$>QfcW^`W~&YDd|f4`#Z6oo@l2ZUpfJ zaI2D1V0<D{fdK_1vLl`lnm8L=v{X$Qyy{%xYr_(S@TGtfAovuFC3P8o0RgihhV-*A z?yqahmJ%EMGhg+2qxZKePpD56x^>Zi_ZuicGDjeRVW2-0CN0C&94IQYFaql2D>HXP zq0javRgYJLZQLdjip6jAyUpuwqFE1grz``XF*l47?B>n@LVmV3u<^^FE{>-<x=w>H zfPib0lNK4)DWCgF@6@s8xOLHedz>4x4gBe(6n+i(_IWy+cu+K%#K}X{;XA>4*}UdJ zk#PA(v4MfovC$mmO@wESfR>kj;K!n;WgaJSfxAfOBB)zHLoUcrnxr80ua7EQ7h<dX zFtbCIcD2sD%HAb)m|?*wtD{yiWI_1r&_>nqLrgL}Rn7k2#5&ykU-y{Pa`-dg$WHLB zWXjZaux2}4ZGVMYzk2JAU&&JGC?PknSSEr<jG``q-WNCet#`uJ?(pPJ^!ys|P2Yp2 zn8yfjbT@Y7Cg$vo(TT-c@4nYPEeeT*z<SVsd<t+BP4(#nh4L{T5FT1+n{Tj(PE5p| zP=v>*Sq~s0T!U9Z`|t6?PD%9NloxP_e!&PjJ{dFbU}$}8yAVlsQY~7%tDl5v@mpO< z*+lq7FS_h1bcJ3{Chg;@f|`w$(e}q~-_<XsEOi&n0RL!V-Wegodo+20*Y+o&e_J;< z9SF@W_t=oxp}R}pxysUSy3A~rgm?5MW)|begpZdN_UAhc<GFJNkYw0Rv@k3z=CPjQ z_vWgLDs8%UcdkL_*(3sFR-F*GJTf!Il^Tb(n>+ehLv^7!E@dXt@50B0>^6thM)<My zd)b0`_te$5Zm2=VgEx${7*Bn_T{GH3+?zK$;js|3nr9FipAcNoD^Qb#DH`A?yPU3z z`Ki12;}e<U>mFBSzkPexC)B3%t@#PsoMJc%((qneX7OH2b)}~sF)f^mY|5IxU@q~5 z^M0`WVW!bn?2F^CCrod6=-LXbE>z_3E6<<0;1rW7>80#17Ea|EHxN-bY9SP7x7_#g zY0nhdr`kClQjn;=;AJG_D62@3Y}(f-Q}?F#`)K(w@-eS>byMZMxp&*{9!wlA%$c#W zALI>k#G9*nT{i#vPC%K@{N3B9N$WRGk6l`NXjs;&E=~X^fnuT@N$*FRtfUr9g4GR} zzvsYiO8K&@FMXlcJbMM_ZoQ5Emfvgs<z|}ly_gH9EHy9WxLk#uwhUOB>Wdgi*L~0x zWVeV+K5_i3E#$E;VBXL{1BF|eW4GR6?;|??>jh^VZ&OCExq9R&!s&%`IeP<>>LpzN zFWTNatf_AO7R4?iBE1u(cT{?fjV{szqzg!w4iY2~mENU)Ql<A^LWx9r6Ob+)LT{3Q zgg`>P>)X#cpSbtkzx&+tJm<fxNY+|&&UY>681Hz;%kkb{NlEv8u0gYT2T<F`Z=uJO z$eH7doNeWkBw)0(QWp%nG=Jz5AGhO%mX!pkWwvSg2eSih@<MWS#En$D^j>UA85D7j z<>}NqJk4=SOUuvUia}Rv(rox&uf~}I^B%^=K89enTP?2zkvouOs~0|vc}0=#MJ1O_ zhZjwcWmwUbp1Bu9(hqP8BCT_}*q0+Pn-~U&fyr3bNKj`CfpZhZus9~{nKs*PZ+}bO zg%c=tsNY<_`X$a-F)`<OS_Y0jY6tK~2j8KPz!w?TwMMVpSy;!&jB>s2M?u15Z1#cv zohQC+Ri@u(X_lqL%aP>%9N@5pR=!2@SKD{L3;j&FKa!8vF{-I`l#X!5FnU^3MCBz! zt}tOZy8UmDwzXd`QM(f&n4rh2C?w|m&7di6oS>d`v>Js}T8^P3`1j%}MElW%vBF36 zItA=sESBlUeFhWqTgvuww?u4*z9yJ(fV>{?)6Ii%6P~g|!EcT_w?Er{fgf~V+6z7` z6Q01Tf9A7ZYf}~GfM_wlwnOyX3Jj*~g_Bku(EC#)cbl=8x?lq*e)w}jA5>26ifdBf zaylicB~lCiT07tg+_b-?nw_TZ&HQlW_^z@m-PI-1;7vK*>}`e1<5u4gj=8fNM<ZXj z!-t-|D_ey`(B7cBPpZ?`F4grcdOR<OAdZVd3EdNNY$uXT?3J!xZ1uLy(-71lQIR!# z7V!S+;vwy*W``yvdf%%^&()~_@-2_mz@|vR)Ly_iLm&w{tgoQXgX!-6n#zD_d^yfH znr7tMj}FsGan^n|(zZYRX25+^>nT+llWQ6Z7Zb5?jYvy)j3H)WG`|qfSEIR`$)oBj z0@u-TWa@rGmO>nISj@#}tg3a~1CBeIv!%T6C8P4=>v4t{57becCMhmmj;q{W!e0oZ zkypzU6JF+Ycs`D+R+RI?j>kg(^>Z&9K7OC}1FR0O&rA+D8+WkrqmhAmDsp-#b@IC_ z6R>Iyjfa@qLWRyR@eDVVY-dYb3>NxgBLg&(J7g{@aE(J5B^qr~x&kM*%Ql7F->++m zcD;P7N$36eWhA}EqO+Dt&sqs(w*vR_rZTxv?plr$D}$tU-QLq(?h0G40UxLaeA56E zzbPA0#PmJ<drDN38=^8{_3K8XQkwO^gQER|!5jD1*47hja`QOX#-Lp25<Sd~B2>v< zh*o`8X}1eq9z>WVZcB>HN5Nt$*z-m|f<!G)H}Ua>$ZrG?2H&o5XM*q`hwyqduM!ck zGkrO>5b_B6MzKluFAg@nF-yzBzL?wEobP$}`)IE1iQ#>tjOKp)Y+zgC{i`%?rpQZ) zgo>2q!h4Eu;Q^Y>wc~Z_yA*0o(OXCAc9S|aaM%55u~5!PwE*sWJ&%MJ@8wdqmKQ7B z!j-71DtS1Tp?|JAB~Rz>4x2v>Jw_~dftWE<W+LZO$Gu!Pb%X5mTbI@ue1%nXbo6+| zHQJ9{HRoQtMePbGfVFTU1&-J^ii3?P(wqsgD79tn`tjORiGh{@FZW*YVK`tkmmBu7 zNwfC+%xYNJ<3z0lxyeqK?+Z)jkt-3pI6v=Fh^;o2=)9&!>Fie3f@mR?T))?C_fB|= z&f|WC^@D5W@>~exrDqs*2rEIOAj;{oxw2#tHjg24r89jw%u*h_nhk^4_|%oLEf@#1 zi*8Ny7Mb*OzMl3S%=R(mFf`S_=Y9A29Lw8#wBs=snYOY}A(78!Sp^j}-FN-h$c2pG z_zKwlIGm~<Pqo!IUFM0Il}}$1g<fVaXZuW3^=$S|ZBc8N!bk-?QR>^Xt<k4|HqGm{ zl*cnKbHrGT98h7+4|rdAz7jW%qMFz<s8r34{?Rq?%JL4PvZv~vBEEOrf9U2wM-AQS z8VcIR4~_=c1pXpnCP>>ZsmHMOE^W)I*KtCe+jn**s_5w^+K&SHJDDr5u!#0(DOIa7 zzhQ>NwD)qfO&@-Mpc)g$=D78QW|dt#Y~N8==VXL-Ty7QTYN^SYoA1w`-l`v&ZFQ~G zaADaRVkr&ZX6BW?t~dNXL&Zz}YMuxc!2%LfI#{PH0Qb=f*gzfSPU<&1&aTEpv&rfX z+ON5Gk4M=x6>%x01bES^>FMSc@#{EQ^6NTiy~c*~&u^L0!|-&F@X^JiP$D(t5$Z63 z9Hrv&0x@wIbG2-sZ)SEgZqr|7Us$MBrOY<9Pj|nY<HrSiyBW*@b`k*3ZwPLuF<!fu zN0%jXJ`K<zZACY|i7d#tHBu&eZ9$E7<?G=aTw&3=7F6XEmMkJa)^afMOE+RZ!Na{= z!dsZ@M(IX(HHu8OlQu~LocF|f2I+0SJ>6MmSwjN++hQ#U4*P<PR$u_O!8Qx;=h<s9 zkL+c3m?o-Fer%`QqbN5gF}LY<c4y-d0e90m=9kub_Xb}+M?5j7!UX%JD&@P*u8fY4 zMheyupLg2*oGIX+0yP2lX7tf%2Hg<oWfw+E*E;ERRka`)lh{ZT>C;@kQO(3InvqP& z=BvXY{MzaVR)6f<{@hBzH_8w2g<oE>k+E6Edtd`1LGjKDL-O{>vtZ@7dGNpOr*)IH z*+d2tzMZCt?8$wZIdO}0+cr7;!$;Whf4n%bW!<@mUX=OPB+4MY-{&-!3HU0=jKY>= zz(2`ANBCbPWkzN|iu{c0@CDc(d*%|<XwjX~sNkVm|7}=mdUM0z-65m(Ek6O`!=!~n zG~n3#iM-<Mwixus{&@iq$DYMIha1T1$;c-Q)Z$XGnkx9xP^7Vfi)jnfSWH2khqwzC z&<Vs9l)$DWFa^XMnRE*v!SXsYhY+L51!Us~nTairevzmt^ZW^Wz-NZ@oJN2BFHhyR zq7qogw*>~`D1I)(?DdazMqtwaxRF2Xks1EHYo$r>5+nF~gyZ^E<&zP-NAucdz_#h1 z9?B$udiD$$1)W*Y(rdgIvgibsX^A8D8pvdP*;|)E=|KqbX!FnDC_rlx-UFDnA^?DJ zWv{d@U-<)&1z%{j5=hOg&G<#aJ%`NjKiWK76%GL2v(WF)IncWD5Wd{SI5I6#vvc|b zJ#!F!HyZr;L>t(R3BrETxZr_o;AHVUDX{XTnTLRnHCOq+E!0n#1yAt1iHVJ`FF;%2 zPIJwx+wt2e3um)D-!6L-c$A6ntN`c-`#VQ=W;$K~`u_8{(yd6bc8i)_aMQxty7Ldw zNRJ6X=XC~wKA#2?g34gqtKgrvO*=_ky<wOmkyB5Xb?u2!2w1Dh%02ncx!bengg#Ix zBxIrk9n24oT#n&5t;@d)&r3CN4*?xM9!{7c@UJMaR}Wj7@~`n3sa&44`!cOrukwk! zNr0J1?Ic3<D+li-{!5-EG4hLKeR`RAY>ojGx%5El%^D~xnJ{%R-PDC-o9{X@>PUTe zB9nOZ(oa+y)<#(b8=6C|EiBz<IE&@=&R%*T4TF0?UY_-l$*S?mg<I#kr8`Mnw4X1a zQ|(~~yKX>s3UHJL7Og({7m30o=&0`(Nfe1FP>Zn%WUhe3)3vqjY{W;o7ZEN6Yoh07 zyWHM-bTbU-1JlX@&`6ohumNP-+q)$Otqc1MzewseP66%X?|~a@2)mG}pO*Nst1>W4 zw8y#oH+;Gg9^M7~d<GzmG96>^tAGzPPNNoijBNm<ZUzLq^Lu|d$2S=w9@&;ZoYpAS z$&HUH9ywRbhFHv01K{FSr942A^!gV`DlCY^%D@6I57}11nPc!@fCm}x`>|9`c9~pM z_jB+7Z9c^5M^57Sg?mMoh4(ML9lWP()bqy>(m{bDyDX-v9;DBsvDb__Z}{=s(n?8v z{#eiU`H3()Z5Bo`|FdqBd?t|+Ii*gFQ0@>RNJxMQO@QeA&o3%C|A)ajidgFs{lNra zvSVfakwL%{rUvsfCq93(K;VE?C!f;Agqq`Cy@DNknLH!XoyHK3hPpMw4Cg&!f|y_x zry-6X|2%t<WPlgx_rYW>l6BXMaG<dE_xUL*mS7uHnF|Jhc8N8Fz`js*bV{!oW{z_Z z`$a-D0~Y-%e8&$k5gSDr5SgODfQdt0_nDwlCfsI9CY;U?orpBP{Fw(BfO9|+Lj7Q5 z0N<2AJV6pFvE<C{=GBmqvJP{mmfMN@!DP@ol^2Pi85`h<Y?H+E!G`T{z#xOW0P-SP zZ^aD~-LDkoS@Kt&y--*8OYQf{`5Gbw?rC!Z9*|fH5XJt>bq<j@fcdZ%IS~TgM54cc z2S~21#uyr$Irg!W=|FckDD2t{{cQ!>%^jIH>8=LAgY!o`>o<?^VB{92u{ybK4cF*Q zf|sMe4DS@fhJd?@1I~5(kRWn;UKbB!2lv~7I}bF*D*PhJ-oyw1niHi=K-f18UIG>a zxzPkw1M~*kK=AEj8}@z&IzS$sc^>}DBCzEFboF&&uevpFJ#Gd=+nw4A3#upk{>IU! z4oKxQpC%wTYM~E-3s_kJ*DS{1WkU(K8EeMQ#pcP5wcR7xTwqK5Kb@{Bg!NM96xSy> zUbAZ<v`4aD4jEKWo^hqTL0|~BbmqlV=<?E>fxW%JM)X`iW0z>=6WfvhG9FgV|0_ZD z6F^>8SVdE<R9G~Kat@KxP7tWnj*MP55eHt6{~1-wNpD`Y(0tfR-WLp28mL@J%Pf}{ zXg<x519{;eLp{-%05f;Pc#F>i<@aW~wY*Gh)N{hMIYwrqqm+#EuFJ<`Eh-7Fg!2y* zxUM#;<y8M7p#UU$9#$TR8sXNlPRlz#0rLct+?kSG%TyO!I@PPw5McYL2)!_@aNWOO z9R=ujy1jjXh?~eisWl+pLZdci!fN!MJE3B!jH58nI8ADwAT`q;T9R?Td(%xvtwt1K z&`T(nFa^%hrJBsn`e{KTOU68N;@A>GH9(a&)h>FP;~J?o^T)?Msf^aIe3inM@O~6Z z_2{AZa{TYf$i(3zwWj<GS<j-yI$R&;=DHQ?UHg;>lu{KkvauEu#J>^zP^@G|m=%!o zxFvC7jGUnFLR+8Z`d3X7cU7Ze%7yFU^>*g=*43h7PbaVS&Mi4#p^QXr`P8YEr}Ij8 z);Zg(s%2|Op_X6QI!}A>6m)`?VL264>fw;>P^e0`wI`p2y>1%kF-9%V-k?Y=?atWB zwpy}mWR_}gq0+q~^$e}R+2ksy8g7oRthgU9W9Ls@J1M^Xnd`^+6C9j*IkJe)bD~UI zA9ye6tgpcnO5VPUa+ykA0w^IyD5W2$TOeJz%ZwbI86jRKp#811j(LFkNi>SNe==o_ zINc^2+^CcZt(uLh`KYhl;9jj1i_zM8bEOT&W;ahg(Q<3ve&S6==(PX4a)=jKV`Ib3 z`A&r(7PZPg_~kjSF?O%c4&4sQiVI~Uk2R;ruy0Rm<oGZPUFJ2JZxQFbU4Z3eocZnm zo-ts$Hnpi`e4701rSEgrl<9We&uJWt<*OOgG8)vJW!E0@9A5T`oeVzLeJLz)nU;r7 zM%zi+y-%Y_J#JDbD#cYpeq|UB4>`s@_~<6DHs!DUh`)dQicwDISf`&O&0<UO*0*%S zt^`Lut#;L}blztL&JN{XC2cgH+cj}|crk(sdaoms3D?|dMun!ULN9cmWD+=t^62DF zTl8SflBtY_f<QrirLQq#%lJ#|#B@l~$YT%C%wuhyq#-j?v?CVSQM`|a{9t9qCXNY0 zt&1GYxN)XjEy<-Z7dM%ljzYye#7{eGH($boAMqwB?JFX*<-fYk9IM|>P#1ZCp1}gb zN&+R`>G?L`%F@0N*24Quj_zc4=$&{4#mxN>y%2MmSJRyVVwA?rp)W_X6KzCn1?`3v zZ}LV4EVPLF&zmt}l#l?^h%yK#kd;Gh4q8uEwow)5x89g`y!p})TYFr_QAf>rcUCU+ zi_fjF2$gDnW=KIp%(APPD3g!#jqqZOSi#fyX3w<^IQgyQnsu!bZGnX&oeaXrQ_Z7a zBsU=e%*yyjWYN7vlYvFOiergJKi3(y)#S!(nG(2+++sMK)AVm2=oT4#AIw@gk^G_= zXtc01g)v?}T<_?o2%W!+gXKFIEkx|qB3b8V98NBEMkbF8T-Zo9a_GN)P=-Lun8QDc zB<<2v(ou<6<2`VbK(GYXGWS!2oLouF#<ekWv{a(IvfN5Fv${pwZIVIuAEsDkl;Rc{ zD%QErVQo|m^X}|*oHly8ocEuJgG6*^RvqnN09I@0>Bu2jx-n{Xhx&QDYo(EfwTD$v z?nOlp!6siW#NGM4@s6A3CQ1|a?^3jZeHE=7GoBOHDr14B*cDnNEzQGaW*a)fLDWta zb*%0~op18Kew&@;!ZlE76wD7WtH1t6J`pEtig0Gl5FL_}@K6_Td)8@CB(85#LBXZi zm-3Wu_<<siH!tsK#M679rHVW>dvlcE6-2c!7g`UW%;*-VldFlduc`r_vVnYq>HHre zxBAL>yW;iuho;;3wY}&waJs0Lbi618*3LA(w}UAWu2@{SzEy7&6QTVo1x#nG;dU{9 z>LvW)D@0=wU7h5}+j@)!S+C&Unmz<qQ0PBwenU_U8JtOu@J2-p813(AvE8kzN>+W} zhvL&FQ#~yp&lT-3vb==Q;1gi^a)~eTqy`&-0mT4CzM4}*-3zrDnW)g8G4EPHI17~H z!X-O)QmS7hT{3B}4JNjWwp7I&gm!LCtxwI64{?@}&*sy==M5PE+>9y82r{^8&%IzH z>#+=4T&i`+H00=h^~cvOd00{|ctfp5sRbgPJ(0CdMukJ))BgP3Lx@kOOhckhp5Wt` z$MFeVd((R#o4nn}&4gw?O7(3k9xL&os@eE@d3{;<2djjg(;@22kI0`s=dY~bwX`^# zl9q{~ByII|Rz=yjlM6gVatVW%*1Lv6LFBIxPh$xj81JZ8Le8b-*7az@Yx73>n~Ln} ztW^z;y-C{aA7-9Bl$x|eNpnIM=%7A0YT#k&PG%FHXyKhDC``26iC_>f19uoXSG=5l zGC_yVX*-xTEc;wG_Q7-}UeH~YN-4IH-$>Gb4;y)!Cr7rJ$&B;X#`!x#6^QJ^wrD6e z<#VZoz8O<XUAnQRW43nE_pAA1rn-Wh#`;>BjS1bpDDSYGO56~-{R<O3O1G2kBBtQ& zVfsB|C$lx_GA@-D@WyzZ#)S9D?;X7;)4#A6#kO`t7i{sqaI`AaDPlUj{WW)GxhMCS z@1VEE!O5_fPq9<rXgE{43%B#~U`NS51zjetE7m@q!4@en8MuBZ12J*t)60>R<K)?O zbt_ZTD!396B%@}sD+v~zfcm1%+hKGB``iah0$>^kcvDn;qDz6@4qUg@4{K{UAsZPY znhb8Sv0E{i{i>qMsp@~#e+W!Tq#`JeRRH_lNXjiXzUY1x1m@CFm{Zx0i__Zm8RM_e zAwz-3^})LQJvaZlt-DT>knwkc#T9}Kpg7jc?5el~SrfUO8EWKQmJgL4^>pHYDC8s- zA+In!vYL~0`-1WO1MJ6%S@vV?sV_Q~w&!F-Zq7kHzWLu(#WZ(-uM<R212WSqIKIQo z%d?aoa?1l_Iio9eNrpC29k2I9|5~<dQRT2tUnT?jUl1+Hc(I0Nm=5Q^8=z<L;6RQ4 znq1kaW0J$*4UrUYli`+vs;<Aj9);F4Aw&}=+a_{!`P=25-4(z4SF-ft>Z1#Ky4Z1! zcZJ7j@yeqp$7fv+b<22U+&a`#aZ%-v<Ok?*T;J%jaBSWN@RT0vhl1N3w@cQQ5lx>F zqvd*ksa1+htsaDTlHQ$O{R>b|DM;eHmv?zu>A`ez>K@i*(-b$2rXiCmXu1$b*0~-? zDqdl0?RzhG7AIw{%v;L}cC~OlOFekQflrjJ{x_%rW@8J+3MEAe$*N8u>)00B+jlct zni@w1J$qK}DzW=8%yjymzoX1QIq<$&J-WZWiKnvxX*Cq;vHhk#SlsWaomX$?m<2#F z=vLPgJK=Tpk@-_R4M~qgrZ~emb=K$<?WRn}`-^#7wL8ak(sJlYyW-rjiR_;z3iD^B ztq1fcbR%iwj|^59%u)VqIe}##S0c#Oa+%XN8<5zOVTU^%TFIi?iPHSI{x(1jqn)2+ zb}t7ca$2oGVh64@*eP=ai~~F9&FC<a(OzT&EVv3yG%i_pV$bPzWrI57?(P>Kv**sJ z_q6t}mu#ZG`o?=NPX-V~@m#{0xBj)YpB$7HK{vHNb(I&dF)u?>%6WmJ70yF^7YzdZ znQ(*cPto<CQ9{1@82V6Wb~|;S*Vu2HLtF?U7p^WmgAJs8_t`>i!?V`}9i+Nu$aLO% zNI{%$Q1p)nH2Jj3ybOiHS>FYqjkiS4O~n`yj5`P=jKLL3c@Fz&W5un=xhW-4{{i1B z{iZeh*G698T(q2KybVJ*&Ou75NGGk)MY{hqLpP<pNNOT3a?C<%UqDwYl2yDk?$G5w zQ5H}>`tQIC0Z0!18*5R~C!eT!j0512Iq~t&ma_ntA`)>I&shsF2llu*45Nb0%ql^s z^3~77$xAPQZM_g41RM6m0lSvq98I8ZY1e(SwB@dzhSagmY#b5BI5)~Llm~1X|G!}t zYs`PZl8FMqycN%0p5HaI9Ma+K!U?=fukFxSaWqVl`%M1ExwPUL=^}wEGI@ju_B;D+ z0AJy=7o&D&ND600<O}+D$gceFUzh<p%s-GQ=nvZEzd_JZ#G|E(DXERouoiK`W4*SO ziZ=Xt<*%|Zr<iq<g8vxZq_|u8G$fdAxQru~GtI*2zC<L;!Fxac%-;k1ZvcJ=_Mf=6 zU=%8XzeTPzThI*-<3jxW0>0*nCI#q{!d+KD&hii2rMraA!>03ZQJb{sT&B9C<Nk2p zt-Fq`uYf>+9g6@M3S<tvOTTe}TPlF=3i7G{PL%xrV@~X_df;^+!`llxzIj5VC%)r5 zJ%k-wY{Sq|fOq*%BZb?rrK&0*aK<em)aIv&Ei_w3@Nj}WMizCWs!(G|$XBgubkCpl z`&8S3`KG~Z-jOFw9bZGs+*x9o<7faCF~EPE<)n&0mmCDW$r_~BOJG5KS_#?9eD#?H z$4oi{d|D+;wUuMbytSjBHJHZb9mI2fr2L3960jxSj8Z51@BShIQUKS$OIOE`>pvC_ zT+rnKJ(9IC#}|RVg-x*A`i^v9>hJd2<saql)yxz|P0_qaTwLZ({^O}4nL1<ES>|$< zAakgj2y;WJM%UPi*|U6cGIVEn;j}}MNAj;KpMO?I```F6^FLW#ecHSgGs+0OtQI*( z&%B+Tk`e{OIt!tW=PVm@uI6_gu*0ACz&s1-;2n)g##(wG6KuVoSb^un00}=(XY^n1 zfCuPSD8O^-n|Vs=SXlmM5Xi6snV^S?v8>Qf0BX<h7?e78=>GHiXI*}Z|KKb~g~glA zDZfk$rMYv)`%NT}<XrKV;;H;}!#RBF&$q-Gmga)2GQcg@Rh&W#h=BqP<<1~7v(0$n zJoyg6q#Z7=hd>D5@7eAIq{(MP;jOq6&;wKC?>3XUg}eWJ{B*tnc@x%SvrKF<us1OW zNJ~*SfHLJhpZ>RvjBOwwvj3L~%t7D$_h+qhXSDjBiDy*&f46<nzR%op1*mY1h&iG^ zPTAN_LxTxW6IcWC>!kAiOV+q{;{5_*Q^jGKT0bU)@J{p8%Y6Gj%iq_dhspw_AOG9Q zr(x&@z#ae7r0#r9GjLK>*mgXOL+2U5W^am|y1T5{T?qJF?RUn@XR+in9QaGfFOpfn zUgYm4h*xNVhxdQAhtod<>U79W0FK^D5BM3p&3yl24A3^ytJlDIN#yvvGNAL3AsPMK z_B#dBO@IOQy(U0Y6}6eO2P6W%Ulz8VVRPo&&&5A4x*Wp6KPnFYCWU!FU9Vt-^)M4> zME1px3JA<Kcm-ISGRC9JytckMcdrgTn2;h7Bs3q@BJsINb}fl4Nh;dzMX1u&+o~8X zM*gxe1+w40S<Hcfpw%=3Wn6YT0RjIGI-|fNuk<7)%oB?-D@+lKH&HFrfEHt`x>^1@ zJ+7m3_0fKt|E%qYpedqsUe7xC8E^i&c42Ov6TI5Y7do^)lv@sq>PN`>D48>A(*89b z%#?Pku|U|?hqu#Vb_DxcwSJ2;@epW%q=vo-rX<KTT|fDX_17EozMBv%ot>nzugw#z z_cB9h#xTbscv_ma7y1aT*`;~YQHHHzX-=~pG{a;*4ZxUZj`X$B>W)#5cAcrF<@>(Q zKabWJA?0jWUGL_M+-}VG|7Lz!yn=e0jd}zDb2u`h8SX4*4&|;l_F;T#1(Uzowawm3 z%@OnhbEowZW0Ns+iSf*)^Q#|LNfPjwSFuvoQubFa`i`w0FEF85)$B(SrHV|IazO&l zLh`RtpWgFUGpW{mHncoXhJw+`arGSRlz)~U&fZW|OLQ<9TNMv)lb24+v(t~<WpwWo z4TwwNtmq|h;H*)aAt^8Y*&;eL%C_oTZnrRbM<8si$;XngHq$#(edpC`?q#Jt#;A(+ z<vSLR*o1c91>TZY;81-c_%wG<fz5wxT5&RH7x7@xxQwE+Qurfh6X(fbrW^T0V$tSF z5uES3hLd-x)j$e3<uN=-lvmF>yQQ0QIRh5es+Seou7jBDykS>YaqqQz5`u_LGEnO^ zgs-fc$=lLE7N|R=^Up`~(3*)qo6Ebzqc`rcZjfNDfj3{`?IN4fUIo~$q6+j8b_he? zwl{-R#M$Qg4>5&=Wus3sLkaRl1oLrWUG>pA0kY3JgC{^kFw(&HhuKN8X-Z{LlVv?K z0<{b9n4JMkY8U9b90w*7`wrOult3RfO(3ia3{5tOEOpT{?FuZTd)Xfto#<!|0Mer; zjC{8}DVA+sTK}Pfv*Q!sp|b%pZehruR(j#>0+=_9rY2lQ(oo$z4c*K=W-ooj0u5L1 z*O?Jg0R;od22348F{%z~M<_@4+pY8#>vk;7enx)g*TH^BaNbbu^cX8deHy_!r}Gsx z`H#RXa0P831|Soyd8KzL^X7wM=rf#t%1b7bASy6UO>BehwsV)q&G%#_&!!pInYr~E zY@ub%DgYCPqi#FdBhWT462s8^eY19;%W~8fc@ba+PK!DrrG3VmV*0UPgRCfxb0=W- ztpc}V;e%zI+@PBf-8Q07FqsQ2ASBR@o>(5LkI|}8P2zif&nKLPwXAB+UAnz;L&FT` z%L2Q))C9-r1hiAm&&qeAAP~P$O#vrzj?mY8R#ooZoV#rAo2$X}u0BucAeklL3J)IA zas!4b!@eP9$+88ZiV}^f3T7e?^R1+78N$&|Hf(Obj?7+?dPo=Hbt{uo&qpndeQndd z>qbs(ag!IHwW)twX3b<&T`!T_j!1_Ag&=&riyhu5)Rj#^$_f4Mt-`haIBRp6mvqe+ zztY_br=l_O@y&9IqVHk~*?9+S8#Mrhg%Uwwn7RYdgV!d%p*b;eH`_cJM@R?(;Z8Lh zIy*np%Gs!TO*M%6+$tTZM0|-u6Z!6ZUe=a3oq<fyO0xG6UA&l!hZ~1LuV7>@{p*)X zHqxBMaS&R`P7vi*CKKWE!gZn`nG;OWDbQ$3;%0Nsr`y(suaCocFQOD*5HeHa%^!hS z?v*-o-}%Zrk$AB*F2S0!iR<e`EVA9p%U25SwYCORbs=vEVSV3U^<B<Su7E;N^jTJ@ zN8CxR6C>}_Qu`L?Hy_fd1FbdV<G&AOxCeB2%h>L6p-yeOux);}s%RrK`@3-L_veT5 z8pM9NFq--U(p$cUPFZ@f;i}{#$Faxm#+)HNFlS8)D1Rl6ei4tnXisT0tzM#0Yz%>E zj3;$c&9|$LyR7fiiN#5A>mnHGxWATB^?$ewi2GYIZP78UMlS8hkPkrZ%*M2w!qary zhW?d&)b|D9b!XMpFmc-lOfDfz6U&+-9FlYr)zj0OLgVc|TI#owR66`^lMiG{=%*07 z+RY9@Y+ax(B2~1^-9Ul1@W|}iNYj)!WV6oGd-3s!<HyD$Smm`T<*1MP>S?Rvck1rm zYg>Ja94~s7*65(9W7eH<Eq9zh(apWXvV^xU*ADNan<uSAv)ki838Os(g}^RA$v`{n zg*cl>zRRbK2ylVyIcx)WHDcrwo;2c)lWvLPt$UU?3z3p@%GC>uEo=~h#h~s$In^xO zdb@Ia%iYns2X5svmOgpGYbxaxHXltV)`n3?gaL$%T5h5wNc9=;lu<!tzCji7a$DdU zr}3cl!2s{9f&AzBMK;3zopdAh%}NG7b*IB&-;dw6GS}3;?eX*%#l2ow)(n0n2P)b+ z$w;(vDXClC9R4xEx5wc~Hp3@mWEvDmrRdAwPtV71&1$I0nt;$o?@=n{UlY$$yWy58 zmnCmvq&iI*e`Ikn!9=Hd#Q$d_Sg{RPwixXj)Fb5)N>lX0LYI}r^p&8aZV@fmMNZzX zID)EJC$$T8o9St45>qKg&weyYW;n2}h1!m4Q#Ut5s&O>FQ-QysVcbilOh+u?egzZf z{m^BfxQQ$9w_i6%r%PMacPk_@F~K_oY1FQH+edgq3j!C~^u8S^OwF<K_wNw@8E%?$ z%4U~ES!6c~X{dTEJS<kkjcl(tk858lotQ9E?&vRxV(-`UO*IwXnhXkBPLT{sXZ5zW zp8Iwy_QJ7GzB%Du(`Q_b4@OZ=#RC6KGFB+zbuNu@gr5Y}^;F_3m~9n4haKuxBeJz9 zXSfKwVZ)Yp5{&hOeAOJE0~xo5W^<+7WIr)D_%h@m5$CsCJ!NyVQzucJKQ4<!gP$QJ zq(pZMqWn}VOZ!_8)8X=t!=o)s9gnw+tLwhJdFw9{N;$n{);AP4X2lbu3v4}daURMT z{YK_#p|8W!mMFW@yx12)97d&YE8`TSXO3(G&D(#GOi!GU>taJN{&`M0Q})BNkW}p? zdGHhX%^70>)4s>rxA3urvU<KGmtcwt0yvlzsyTOT&t=uIN33U8FfaXagq@CfsQOL0 zt~KuF&=0fSueZO<a}p9x5wOL`%vxmN&jot_(P_;XgaC?}j9Fj~*6{{<?Uisg$S%d6 z5Sl~-_l!QzC3R>0Mr?cH{a+;Mm<m=PRxCDjTJ`h;a5^bQB_dI#TdCvC9>$Yc5Cy^) zz08_|$Oy8txPyMS`7LHontNpx(m56)FZD1dt*9$cb-%4TAU@4jr(k`YM%(-*OoREK zZmE;<|8!X+q5WO7GEw*2?@;Vq-`{1Zuy)WsEBpiwR1j8`%bq#-bpF#Aa)lY#YMbo= z>GPC~KMzTk{%+DIfYfYINc>{ppXutyd(IB{1|?o`Og0Cb1ZG@RuXqqhxZd`yIKjcz z9O_7Dze9|P_wN9Tt)CnwerNp-zg-RjHrFiOQ9$ndpQfPoP#56WQpoLD*oMaQF%p9Z zi{{5~ev!O|?Timi{yrEx_e~oZN$j%u@kO3fs0i`>c)x+}*(0rUMr^bIBKZjdaLG5O zn(aqz$bGhe4WK>i1+6O<e;4xj84w?Mn;-514ICUp%9r(kzy57^xN)H@qN7P1p?(qm z_#Ur5o3X3%(o+DuR6GQ<6~IXSQwahIfA9SpVSvq#O!QlT*Tkv)6geh<k2aBQ)gnKI z)b$YY+Esyaq7ob58yG>42COFSKf!vKW{8c~NY-IXRFkmvao8S^8jk{@!yJ(ZTganB zSXa{)?*)3bF(Emyjo7Zfx$uk5@F1bq%^uX>iGPDE*w7MCsh~lm4FeKt|J&d229iki znT!adI6ZMem!3M1%4x8h*nLm5)G1e;3BaK$1#$tr<1+++C}p7e&;ssp-NNyqIsOC* zcqg$N?Ga8YPEXA-<xSxv>$T6#+eJ912iXnpKkt#PRvs140;m=<Kx+UFA)ZR&^fZA= z;5;NC+F21u{q)C`i>J#@D?(olrswvrJ$WuMk_Tb+5&t@I#?=t0h4~+bojm$eLs<n8 zqk|0Oypuk1$JJHgJrGVyKy~ywut8YJ2f%-F2jIHe2o%J?#ti81v%&~mZ|Dg`5dP=F zl16+-iuhLz7xG~d_QVIPmAxDn>fH5&VhH}gf|(lp%Z>2A4}9g16>(NZ`Oz^<@Co-= zlib;#DI^G}ohdW<Tgh-H5_tbS6!?(+R($U#tL8Hx0ICDUbfxWp0J!o!1*ks}@+Jat zN36h2Dg)E{zubfFvjD`}KdVq?DxzKUO>k0UoNIqgN1az^mO8cvRquGFeH1z1DfmyU z0nTavd~O7kXud}9<c?9UiO7pZOt0LZ&a$kx$U9`7y#V-3pQ#(lXKreImrerRuF72# z8u;bv--~bd@v!`TB?2%IVZ$!$!S`v-d7Ozfz%uQhs4IU6bY{w&idg&!u8Y~FTtvQo z^Sn7l$hYGTclj&ZXws$84<ALiqt-56=zbN~^qwK^?Ip{Hne#(YCzC<W21+;$)B=M< znDsK*$Lw(t%e2;eo38xwo8h{g4h@Fvs;YuIr1|mv)=}X^bD#{e$^3Gy3k|^wNH3r2 zs2kd%VIjM<r!phUnucuBb)=l!Thgjug<}o->H8Y3o7@`j-~L7N$kQd%1J{h58LbT& z|KTN1_8_?@M7^e7MJN~H7@>kn|G|E#JZ1XjSa2^SYPlhr+vVqY06ee~G{fSgYSvE< za`g4f9W@0Ri|75sBja%u^p7HlaZ)TTwT*TwKbH+YZZb@k@ViGA@Obw%7S<LO=<CD? z%CDsv`z{V>J|BltFCDKcu(eF=MiP0F@uYe`)-v_RY@W~0t3;Jn2i<GgOnP)fFX@hr zve^RG5{UKyn{h9ZuoGgoXY*mwuHX+tj*Jm?-}jL{PaN35;$==u(&s!QZMYvW3r<WK zT?v)Dgt>wZj9BuU2&#Yt&pR4A3D4Z0q%AufcsNKQymbPqE8jk56R@|9N<6R0S}L)o zngxGuHHI+<G#t@pw{e`}6!Zj(@t;E1z}L*p?e(XrxLS(js2u3yjq_GJ!Uq^tclWw_ z5*c^b;D*mt;=;iBRczA`!i^ibp99jBX5z+u)$}~8qh=gfiiLcO`3EIa%yZWnB{;-- z?)o^3Q1|X`O6f;#j0dUcR78HUaC?>xw#FAHuch<mnTfGjnYp)jeSWU2j*U9aR=5b| z#2s8NKv9Irc(PFe?H1j*OI%(KiGKgwG_b0?@`cUX@TKFcw&G%ie(qHZ!SMmeGPZJ* zAc`@X)I<YW)8$?L15=F7%*H$u#<~gjdeksxr^H65cYX$HSDlyFw&%2SWWe?!W<_@p zV!Jf3R)i5~oy??oSvk_e2|$-gXL0obHA!C|xd#Qa_7Y{Bl|{_A8sUg0{)Ze4;#b!x zLnxgNHK&%BLr-&H&dt6HK+S_luqQ0QBR{9WWRv*hgssZ0L`+gY8N$5S&>1e0uscH4 z`=K+nKxV0&^`t=P2`7IS&4O%#jz*D@h+@g>5vOvy+*xXa<TXQ6*fqN~%C6x)efyxS zfR1)5%$?`YJ&F^v9+tFgB|13kI*8r*o>>NDBp4uYwI~Sx`0)^>J*+M`9Yfzr0T7d~ z<GGVz<xi$FgAuf@!gb{O^WP9Bx!T6_2?^EgCRY*g*=-iy8Sca<8GD$glUUOT?Bg+{ zz2;jmoijpBtFAttv;C&}n*eC6Iz?Pu8#K>{#Jy1`lJrJiap!VHAo8leIF4soxjQpr z+92?!c?c5y(M-dqMCHO(wFdu8sn%oWudzKzJ`x>q@Dpj%90*50*iqyytX5=~3{an6 z#y#*ri?oBO5f2n%*}{tDcl<dpm#ePLnkd5x?O#Q>yo@2wn^w|71pVOh;Xs7%t>Oeh zWUfkHA$@izbi&4TN@@|4!<`~7iFLIcRq27zl>{bdZ5;>g6-3c55+#gCPzEg~<i_w< z(b?uJ!5NGwNBz#>b|sqpBw1Si*a{}M=iwtKQT%#EWABrzJhVG>LuwOMe1DPb8Z3dn z7hsLPSw*0fce&_;4`&vu?N0RJCEpn<-iLAWR;f*FgHk?dP-%))-LFoVU;iN)OyI#N zPIkj0j3!(6LQb6Oqe?c1VcCX|A3yvQ3=34P!tJ<j&OE*4Y2#K`t$xYGI(otIG_fw` zZ6*mqxnKiS3%thg6y!K8tF88!U<)rKe@TR+;d4XnJ7F%o(|E^FzUgc$8&?>sQ@)+G z-5lXtK^5A3Cu_-^k-&mW=jr_HJkypkzSj++c0`iPS=kCodh5&1Gh6X@Qpbx4af;A( z<|NJ+1z+uF30oOM<KNwz*1K~Y&8A}zQ&U8jT)T$w$zhP>{}9!f$1t|0+FWjJdjJv1 z85+hbEJZrglf8{{vJhkw76*HW78a{ft4Y~xH7V?IvnMzVekL0<8x-HfOLlC7swca_ z=j?$>ZdBU*waU@uYah}%I^YH#1F|y3T~!0t=QGIe-tKMl8|`KDTU3E6F2`JHT^5k1 z<Ee{X4OcC#xQNajR{Pcu`s?9JZsCUexl1aySl(%3RZpvk0t8nD>KN=Kx|GO_hKD#$ z_sw(~+>`&(GOjSQs#q|uq`e9UHT@-b^hBwj?w$hHC#JHWBCLf9>V}KDTUQzXg-uZ1 zg#jv$9HH{r?H{6X+loa59NkT7o`O(bJ%H76B^oK+3r%#n1~DKHD|_2%kzMjY67sCb z*1k}xJH`Dd4!SE2=~UZ%PISUhw>sZkVu6cyz1U9^SM@0NeCCKMY4v5Q$uanjXEDY$ zgx93;@avXof6IGNq*I{p#i7{^l}7O)v@!Y1i_V!#Wvb%LPGSrFg|m;tY_V>&^acx` zD}PiG3jHnJK1Az5AEAsjujBLx_C@!V(p^xho{lr`JkFQpbVIR1ZX9y&9xJ%JKM*cn ztQKYgJoR?v7h`Th9%&B4UX3?Z)?sYoebyiWyOqcjyOxIikvoAwN)(<wR(d+nwRY!d zxqTu<d{>6tL|sKNlA?veffT)N-aOF<DaPyLS=Vyh3eCl8hOC%oq^(uUMYPX7WX;hU z`MajjV-d=^#NQC^?3Pei$HTKL{W9%k#l@M`cr^nJ<)sy8$u(qbr~i30r{g2Bo>lrJ ztunO?_B^BE_L7JB><kUM*t#uWhh903EEc)qKG!lO_w2M{Mbj}kjit{#?L1v66``d< zwXqxp*u+j0r?lbqmwT3%=f1q1qhR3SkT$>OFMzwU9I)^RU12KIG3|*_^mQW7?G>|m z@Yhf>y8sRJjsZ!Dm^&|5Y#VN2Hww>9P(Do}-oxoGYqo)Ks&bA?F6XzZOdQCIR9u|J zrgq9#n{1P$;=sbgv1B1v94eE2Z(Gl8$b<wqDNy+jrd;VH3o^z#2`ojPC`XogN(pk( zPy4oWt%!0?{0QSW9^zWDbLyy`tuN$?{jM}>VB@z4zF>VU#L`X{Q^NZUk(L^;66xZ_ z%d6PP)przrl$11vSCBp7fr!LgxD${e2V39MZ0y6a&-n+R$p?-mzAk(k_dc#X=V{ap zZ?iNu?&7D3Qgh1RtPr)Sn#uaXTatCbkj0c$6Ncp^RVq#;=XWWp9QP@>a`jj$FOIng ziMbZ&H${)h@@F-;rbgVPA^+aX^_DF+#^@lE71y=gioC4ahzSa=L9uc?9p=O&C1yEL zihmv~u$D-Ft%&fDa}ki~c=+h1{qxVwVvbDxVkSQlGH5Up@6ZbdI7?>{sC3qbP~HMv zil|pkf6JA+;6tlR7Kww2QdeIehqk=*&GCGVwujKitJCuifw(j{_xf4KtO0gpQf0qv zI?c3v1QufhQyLFwvk<jCEH?D=F^DhIPk6DcOdgW{CR#hQ#w}r1+O=H&dEp>c4!z_~ zjNv%KadGa7R*32()HvVJ)I>IyZqgeA5c2`T#id{3a^kK$JzRm+i|ihtL0B1dbR#%i zPQ74@cy}bwbp{Hq9JgdjgNr`q3bKje+GW36-7~7vKv~JpX&WuMNR)x>w|B9LBQSM| zyGwBN;apx_C!)Sja_d2bpp9U7tCjF*r}T?^!(vYGbt3`>koT240t$tKUDYccbJt95 zOqDy#ZjR1$9LaPHXM(k>4?GJX+UM?eSdA{>_c(e`svb8Jot7{S6|G-IZmfD%{S@dc zlg*RN4o`~8J@Vh#-1VDpvOfV`Ii;3z5&tS+$-m4$+4?Qj1hX3G;I2lMz`83nAI)=l z?}n4Zv!m=0c(?f(JQ#BZteJYz?ssF4hc*hKch?l^LIb~3F8&x4&G>jo3p=wHFE#_v zsGbuMDEd%ax4TgBCp_UVukdj~$!hMLvTNScTI%~?u*%5#R9?|TuVN8-Oa}C90DslG z_}_1V=G<5NCUIiKo0R;Vn<|#QvF!nokvFc$s{qN=-$*3=tmECkq2rHkC{}Llyt;s6 z+{ly2*ovffK_!ySEywtxpB2Z~jA4^)fdAK9Apq}kmH#3cDh8n6_`j++&R|EcF|8{c zz=kIY0O1NHKtYND!O;^^@JNehE-f0_?1C<1`j-J6iPr);al`xo2iqI{+Y9dZXLq1S z#OJ+`LsO+6#&{Ll?2r9jUH9+huCP!81t5Q1c+>NDirMZ$EHItwfE7h1z!)G)h~j1W zTS+ps32)2_B$MR~=ijMYamMy6XVF%fgoFd+hP))uNCoK3{6F0Ww#FVD=1hfG))uq} zC4GH5dxvxR3TtRF>`WZg{n=NB=3LLe&kr)Y2;Gpd{aA5*cfabu*4blJYD>WXcUzfn zm-fyq(7(gRyb0l5f~uXMn2+3){sRs^W`C`#gHL5+4KvT&L_Uz~4tfdXQvgH=G^PB1 zxrwU0P5NopeTS5Uhf?fUd_%}1-{-s=(h<l9Ff$FT=khYpBa`VHV7&dC%Ah%WK-&YP zc&&#*#Y*t@f<n&f>T*sj4qA~l*U!aCtpG;mzj1PL(|@Za8t;$dcoyd!C$C_m@2(eU zd(r0OX#@}>-y~potljy#e|lJ!>*DDF<;$m6fQ|Fcq<WqMorIC61l-%LoBb9AbHgRg zhEL@D{1w;<V9g)!g7+44@Qwhl{3!u+gx0zu`<sC&i@7;HyY(ivY4np1ikBpgYxbUe zrxvjj2-^*2@F`yGoKchJ1wdw)2H1X#!T39V|C4y#Qiulk^z%9;x}Cj5!{`wu`Hc&& z!%I%<a$(=pDDXI5;`9i3gX_vEf#zK5SvwG~VO-Xz0X$q@D5#wy4h2fRz>0Z}{N98- zy<iK3rp;S{GYuv5z&obq#CJ8ovs7b1kacp)+X6d`y|Clh?>XQy&EcunAn~HnGv6)a zAimdvEwn2C9`vWnfO+11IQVerBpkI}K3+%0JSX9(F59r0^teqalGG}rt+C?w+3(X9 z8-sACAwW9)pa@*$1v|M65KsOCs*br^Zl=nDDbT)>TY_DpZ_jPtXHBOy_&ufCzsG!j z{GTQgleYhSEs&V1GR|h}Il6YM>Q?9wJ7DIg5Bq%u(3!Ez3{Vj7V;2rP^qK}o#hJ<E z6_|}ndY0p)zIb|*6#Zl`I5Vpbe|jzhBw>AR%n9iO;H`4$1tfT6U3YAHPxIYcX!bi! z^#-ada^WOB*+4v70^HqC@=W4s%9&x3IG;80u)tZW{7f~xJ<eiW)7z+TRT~?Pm`FY| zw`6)}nnjd>|CxV7e_reHr693t;cKGwHwiNyk+wAF2LBlDn~)uI{9Oldo${{o;?Ud4 zn*M?*$EG6Uc=N$^ATvQJ-#L`fB~9{I>-B8;K7+5k%w%!wxyx!d+@}OiyD!^+e6jzk zy2T<QS&08mqH4=<ph+%KRTRrZyb4D%?Jb(`P%M?CTTXA0t9Km%HFDT_)E1vM)v8tW zc=lbtF<&VmYyQr3GiCBxLc~t;FOr%oZ*NVkU_gPN)X9qKRO|RGKZnj6r*7KDt<3qj zOF&y)w|PzHpWiLq$F3MyFAp)>At?~zl3{iIJsi<|9M6~HbShlGeqlhJQ}vPf@d81S zkn~b(u#xQ&ZfOz3W`A>QVsf|O<C<L#eEgcy%4yEdX0ZNC1*?SbSrMSS=gx&`FRp4Y z%L%f1C+TK#q^D&!E`Kc_NpRvEF@TFXAwLq;`z0|V_Xet1U`fL%K~GGNb7=L`96M#k zHv7^N5)y9Z_3qwU=IwGcGtBFB1cnn54K*k=M+QT6-ImIfmC&<yagrT$#9K+K&cfr7 zPAr2~2PmP7aP68Of606$3nPgml?P#=r)A2!>WgIpZLiHqR~sgOKskJ}kwL=Ft96ns z8Uq9EsvP%7Ih0a}gLje^?BkCx%Wl+y#sC()>ey89UJke}sb-Kf-5_z^*s)<fnoBxE z!YR7--3_Hq&>cBm)=U2Jftapxo=cA?(q4?MKU90Rr3)<wHz!J@c)KI-B_2--=)Vtl zOg>=-7|%RbqgkPkTBujq(d_wTqz^2B+GPrU{Vogn+Tvn+plgfN(zY6{^-e|bGg|S7 zb&6~v9p*LN-KQd`^nwm;Oho%U4a8;eBkJ@aIh6pTnKaMcN7q^l)n&MT?z&i$@rN<& zyz@qWsBEEV7x`Y(Hh%$Eh6(6MnKfXO8m)keE`@p-$|;J$=_&J0yRs{|2HQA3h&3se z^9V2tgx>ED_C8dKXg|q(3w?m@?>G@Pw<B`-DCN0egJX_#Is4rh_=1nWjz~N@pBJig z`CCf}o)T(|hVL9M#?V2<aeIC!O=kP)i5RE6nJr|K<WYSX7mn|>cZXc(`!xo{s^v(n z3&%y9)>AeGA=jVP_L}73kp&RNHn)|utRZ@Tr}(Hcj5x!TK<@O3$VG(HQlFf0P{ChT z8^f(iX%_mCg%;?stu}@V`{0PeB0m2$i6|p4fw4e6LmAyfkc-QC9O<HycL%aQx_N2n zJY+!3oY4r!J<|z@WMn(3XE$2(v&17SZ+qJFs7i~f3dm}(AZ<VVg?0KF69YzTyD&i( zusJwGygb2m)M8W|c^*=sJpnbeU6Plscrj)rAuPxfKF#6gdmYm%K8S~XG_^L2&3h=9 zDT||&jFJ<=`)_5);_Me^nzuR8ff-lP^F_<XfWs0Os%~?PIPQ*}`1-Ez-MRhbe$fvl zW2LYM;GITP3{`mq(2Ll-+fThifgj_Pci2*}eC#P8V4p4&`$Oo3<8y7xxN+9p1?Q<7 z!onmksYsB@$!lriP_j<lC?j<;ddAKIew{=C)%t|ok%)u@7Nd0owR^z-Zl;zE@qzY` zfRt6A7D<ZJ^uLtpA85B1dvU4Hj249ivr}bV`;fJR4o~3HTzL9<Ta#Q)t>Z}n286Py z!@EFapW&R)E{mWr%h~|F;91;W=Ns|JH&8XWT{ISL(r2_&kwo+q4&y>5ZL<rFslRdq zFQ(HGSui|7<=HW<{(Kna0I>lsaakvd-FdU3n?8AUb~;ys`&-u)*J7^^`)~*@MGlu{ zq%ZA7gXsLpaIOAi{-Z6-^`@_vHRu(X#%ojS<JwI~seJk`j<8FtxO;bOS>FeCb#J0s z?EJeF1aX?^kVVb61WgN!XdBuXBCGZs;lrI+H0_rmD}Vnye6*@NnOT*#ZYX0_@&QXs z5)0caXvw0Kdp%o}#1emO;uXdN)2E_qwWxS+*T~zsCNJmqgdK@~3GLS_y`;=RN$MAZ zO7zoJb)3Zut@w&PuyGxhR*a8m*2M$z)ThRRu8}?qEG&-e=z>mmW={7LN$2ni1j{jk zg%iq!+z4W9f__=$ka8m`f6ur7cyHJ?toG2fO*v{g>G9q2pC7(HA|-?O0%kyf5<qj> zcUf|mBHw@1yk=o%GYiU`X)wZFHwvXJ+}<O{BAsZfO&Fa87bA`CkMQSSp0{WB^12i$ zczt;j90sOP;3wGmz!r05%G2%hA?xi;9dI+M;loGde+9Ja4|pP{Jk(~g-}{EzW}wuQ zd;_VZ_Ft-mCu|^e@j8SXXoF5)C+|*wkvQKTs5k|I!|Y~E`_UDH&rP3wBvK)4Tz-Q> z9ap5T?qB@SWlmnMY9?)ZRlnULiHGXAXkgrboKHzTiU01AwQt+_%LP%5R$co{3uC-( z@PXl)0^?GWxD|_qK9gP!Q!TM#cM~tAl;FUh;8RjO;(?71Qq_snyH=AK3FW|Dzzaa1 z;=Jj*oE(9-PB_$3DF0iXq5mzQz3KQN=*B$h*P2b_W-8N!qcY&<MEQtUi?jD$4Okgn z)5di4Wr5C71{<H%>$kW~t~O&9Jke#$`y)HUF%*?DI6q}YJ@<i%k$OFvfjwI5k?i@| zkPc8KR35hu>P}}~B!DRd30Bs{xPa~x!!c*J-P#C8pY+3s5~*>E_j^Nlk~;;{T)MuV zGy1B+oK7*}V47NykS56xFIdP)$K`{rd7e?rD&)xCxY5oN%P5z}MR8k2EB+YK59}sE zw_>u&lx4ndD5cF7tL0BZha;0a8N{VIlM%^?-77wzI9mvxO`2)Y(#~sXKx}Tw6H%BW zDQNv1#oI;e<GTMTFF5=QzeJRQp^{d{ZGN?<dHnt`JQO#NH^E7Jlt9^uQy3a-sW=7g zwhYh;=aoK;oYC4;-Khglz;WZb#<<=$*q60Z_O8^+6|{n?VuFc6#KAWdp+qjI$HWhW zCU>Gsj=jV@2du`>&Rf;(QYkj6Ua+tYl2aeY&3KCcGE#Z5q<b4lFZZaBpo|j$2PsHA z&fpqb1RUBw%XVlvhL3c6#zBHxbzN_(cUHy-sx~0(8RH=yjTtv4{Xq^HA`=L2v{k2( zaLy;?WvTKyzk4&9vBEYJW_?@JKCf81V(0lnmBohJM%9#T$!fk@ZT6Z6S3Q?glpR3| z=Elb**h19OQo>gw6XMrQitWW;ju{;*kS=Ec9$@`~OENLSd2u!jDc|1|Jxk~7O3B^S zDG5)PY3Y;N9QQH>Dhs8*1*zy^e>f)RqZb05)^O6GHqiAg8Rr0nJPV(EM{g$ajn69F zcM%5EV%=5)x6)(h(sIlHANJlWtf}qq7RG`|@4YF#BUPFNk&g5pnlxzw(u0&JN^jDo zOOxISy-1fXT|j|^-V;C!5VFtO@BY7gyU%&fIal9zb?&mrv(}uMb1~N%V~*b#{l|T@ zL#)A$B@lMR>RUO@^%xKdD}(b2b%2~n&F%y;LwH4#k;f*TC`tl0e}&d({P6v0-7rP< zs*L0|28vo30Nw18f-Lu69`{`<LhmTMmFzL3m3Y2N+jW{G(tSFQaAKnsGG6&%OqFIi zO|83k@*#O_DE>u|AhOVOAt(Sj2}Zi5ZpYbnARB2zXf*9L?{+*9Dsyx7n%Y=uO$v<c zhA4@AREbj$nlSv#Yn!j#pdV*nQ+2fM=;(SitfgMIoS|x7DA({tYX1Rtc+#s(uR_2+ zy)L1-&z7;~!$d{De$cm=ngg^g&w|x-a&eU5j!7A>UOwX?u=3o-JXvR@-(w{|tBC}I z-ul!qI;*X)HqR-KU#bU_e7pq1M%XHK$0e?dlC#F^$>OWn>NpKf4X^}t#psB~fbtKX zKniK@*DBxh%Oet3Y3maCQlOmS&>Bg+hetL}@jgT8-bZeSkRrgC$_lnF9QKO#?F)>Z zV>vAQl|9X`ss}4R%YkRJ*{`WC%H(F~Dcr`>qt<`C{v6@}F!3*f+>qM?pr(UdPNWh; zaBAvM=oy4r@W6OkZ0YlhO_d9>FLr_6cfIcN6X0@E^PlF*4$LRql>-7s80w8RM)<78 zXOi6?b`;XUT+Z9TtY1552ftMsF+G10^AY)TSKDItQ5Zm?x8>_g>?`Vp>X#9TbJFwq z1Qc44pNqUqvgXk<g8l<JSeL=7*S9|c5H7U)mVE6fYT>fN<5%9LiL51UwA$SI8=r>r zw~Ue~((z`gLC-UZxPO7$-`rxTReyuG^9kWq+tW2m+xk%-WBU!|3Y{iY=|LJeyQSsb z|1_BJHvmx}hh$+DOjwU<06}+rbpyDoVOG4g^1!_?&E%H7XDtWjGg3Zv0{RaK!m0Xq z7=i3>t<TOgSQUE&6ZfBs7O3(ywBNs>AkFa=&raFs9~=gCb7noGc#Fjn;J_?y0g1rX z3;$q46Rsu6O4Gy=tp#jACQgO2**^$c{P#ZW|5gs*5}sGKd)`F0Y_Zaxq)Jgy*n+FZ z^rtK9?+yJ%(pU=r1I((S*7fbPzGlJ#g1JuFLW}GcWxcNhSP-v8ohm^8;LL>Ia4#eF zPk$A|yq`$u8Ff|k0CH@~S(4PF>`T*$_&_R`tUBE-IlzMu{M-D#7Bt3-@7k;Z-lWdK zbAJy7bt)ncomI)Y2;F5d^AH=pXxgTmkdHX|Nb)MW;kViTZ47Qedq5}D$ygxN=pAg< zL=66cYr1A-+W?sC-ajXs``&t9KBmI^pApr?EuTcGVqUw;M*(C`mDb-Vo3FYx(7ANi z!0ekv(R7Pt;^3lP`0X{)XHK`0|M#euD*;gMxLRLc=v?15@w5oZ`Q#$G^p5r+jcAeQ zSmn_d1*6*(IxwHre{QwcTmbI*f9bw|78m^gknVd8h*UyvVgL>*aq_&NbG9=`@RQlV z!|T8w--r1C1@rz_m61PiPQQs>_gQEDy!r#@3WQ;r>wXSe<W@jGSsSNV+BXNDb0gRB z!`rRlzf7E#oW}y|_=}o7*l}-Ya}bnw@SqwplT&$Y$}mRYXy6$c;s?r*Pw6nS=3k4J zzC($=NLAKyNpGd4ePkUV<GEACwQSt58N!Zk+DD`x5_9*i;_Y2lX9d9hXX2(^+NkQ5 z<c_#o0#jO@8{E#Fx`rO+FwrORm(g{nBwlntBRi;RVy@_aKnw=ktTIpbWN-(I7`0LC zk9{}6w3$3h(t^yE4Fpevn)x@i$u7Lo`QwU%p3GtyFoLZp0(8g{_Gm-Xqhi&$%{Qm; z`xAg_ULsm}E^geGVP;F}%`SHmpxN1bt6?TY48k?^x%-BM4rP!j64L~}UX6GmbT&!) z108aH**iF~aw41M#`d$&2w!g6yhyBQB1vWX5QpcE&Y?UZeDbFUVfZLqS}&H*z*t*I zze1}kz$|d@NU!vJ<#Z$Ers34(bMwBIJVGghTfN^jD1ETap|QKY*>%+Oc3~ApJQ{J5 z<@%exWp*w`HClr&_4AdNq?AFAQKSP<a%-I$YxFI+Vbb>jy8v$+l9KarZk4xMGyQtd zg0b`X1#j96N*s|yn*h#Ki?;%+4WPK6-SL2<Mx{KrOB<UrZRR`CsI$T6AV(3aAIpav zuhp-=Oek#R-r*-S03Nk|Za$NdSVlB-J&ywYq(9R*M=&D7jYV><F~jFPmR;4sldW-7 zCNehk``r}tj{O#G`$~Rbh-{Ics@7vj7rWQyQ;Q%C7U;LsbCcm6)&WcjobAq@TK=zA z?c1EbW~`8@rF;~-Clx^Ly5+q}ETt)17+!3RPvE;Po}(<U>NHbY^r<y9Gt=rc;hXhy z^}IyYUU_DOJjH})C5wpwmneh>ksmu~Qlf5B99kCMhhR1`Hq50YK{>acD$3RNo${sk ze|4Re<6J)`f{gY8TaA8&Op-5mXkJYep110e<hgp|XG&%t@x5bfcrd(l2jTaA$awH_ z)Ufug;fyd_3#{!8S5s@K0&1MH6fmLf<LA9i-gBGWO8tsq8L}CI4=F@A3=J(dX32U` z?8($by<1_8KQiz<cd|Niyq@M$nMm-YdT@U!8E0Cpzx<WzLEROgD<MHY1~eMojiiUn zsPrE0K6Vw9V<ZL#%a;6Pntj@F8lJ9W;3>zYt`{=t=^!4%MwO=xQ3E-I8)MRAF-%{) zzMq&{biu%$UiI60c_%+Ok2C`~lC?FJ1;3~F0=B6i?K8R_M%jc<7?W>Ol+bDyGbyXL z26750IZQ_Md7Wr!08WU{^Z8y@jBFCXe8eZw=N^~nEI>6O;j$~wjv{&EiMth6W3{N| z#@^Z3l&-_5G?CAoQiiL^L!h>Ihm?8(JN9cBiu~1+1eDjz&C2-4oJkc=!D6nJ;|5Zv zbme<|+20EZY2tZGe(C7#xy@17dJYY>ZV2jTx>Hf%d<ol1EHWF5DseHPNt{S8O8@>w zsqRZ`d7YZ33RTqz?sFbAW|<Z~M7e3|A5|<h%+W=EGHT8bwrJZgk4c(ZY^)AZNBF<Z zh9;wnvkX3a&3cd<4f^cy?90GrK7G#)a8WdLohhTaFx(keF#rtfPg(fUo2bCSHowFo zbi&ZDndP0#cP4(3w_WUg;t<PXxMO=$U)G`sy_8-@k#ktnpcZ;2DbNYMuS(v?38EDD z)utsXw%X?0if5*`Gz&RDr`acYjfz*Wk@9v7`Pp-tWmCYuV`tNwy6b5p1;i&~LQNa5 z6;0G&?aF5N-w_=IuoG|NdfkjL{XzYKUo_d`VK~UedU17NSJs)8&PQr#X>%=;SOsY| z!mKdC-tuj%BO&`{(Z;R!o_h{-leB09g1QepCWc1ovPBgJTAj4w`TFE;i^YZQTJBkA z^#?lBHK8X<-r<zgk-dZdpZ0Bdx1=CO+QT!cuS_$=_ew~dq@-rmRf+_%?XgM7q1Y}O za|pw#LGn=7y=mV#_9x-$XT?*9w!qPi*oFZ|(GHC}KktS^`ODL6(w5g)Z=A74cN5Cf zE3Z!ypg-;P4Xm)VUr8LsF4-^jx6M*6?Ve;gz@qH4zC;dqJa>Ri%+{wV&<ZwG6ttfR zGolmt-jyPp^sBV>wbciwoh`jqSK_iAIFA*<FhPr_XvbX}gevLA&y%ulH^s)C5v%Dc zmqV3=#^~a^c6_$AQ^kBn<ufVr)iWJj$1-})S>JTYV5HECS5F`%Lzy|@t?Nc8l^ERI z1o$D_ilw>sR0l{PkUL3ttW<s)sW78(Uy$(&+gQ?2Fmp{3q-20a6fKBqT7`SO!&11g zJot)v2)%7h6!fTaUpKgQe8Y46T>W-_wV+LdtC>TzX5{i{G|%W*^!Whx&5ZB3hYE>! zu<hQ=*igo~Yj}d6SnMIY)G%frs3hx4yNrlEl)pDzY9&<TT&YufT~$pKZpIaLKU0#z z{ibBJ)K|W+Z>6^#_|L3ZQNJQe=Tk&lq<fQN**+FeQmxw;{eW{itq>0ixoLpQ<n7Mx z26G09j-jM35GNY5sTQ0vRQFIU^EuMf`3&T4gH**Dl%Zt=b1#vmWkckV*?fvc6Ly0l zE><!~`I=x<^SRT)p|1|5bDr(IoHSg$>gUv_&-DonR^PwW@jdZ6rhm|Vd`FNhltHv? z4*lzMnl%BI7JaL~jVp>ZR2)Q%M)Weu>QL@Jq;cAP$yJ+5@31KFRR6?TxxdgR@uAww zvGtazF7DB1j^>9nyz_fgYw4t~^CR!ik_G5fodo*r$#t*)dWX?O=~yDKC&T6ZE1l2V zbWa(k4G5Q%y%xwza^F)EIheB8ZPDN5-BPTp$vos<+{E&{bPtrW*<HUM5tA-v;2jHW z&aCRB4SSug_*svgz1sNh4;PMFOeaB}+eBiA`)q2b<D4s%oz}kp;8ir-(;Ilg$o<N< z7|61w<})nO7E7;BanOEnjHN+a%UpNIVD#XpB`yprx#?JeTFqY6;M9wLr9mYvKK2-o zM~aQTQcpzi>2##8yD-G?yqFb+IY4&Y-`12|3Q_HuLC^PYD>f-q_}Ua|oHw1Qm0XjJ za$VTTLLq6iYGGzi_(Mc?x?w}FJH+656xi{Q`^d>S3F3zuv*O3(&J6XPS=N1Wmp<>? zl!RhcOf#2kIRfspn2Q!Tv?3$`rMF2Y@XlNPr)>t5z!8Q@kLhAuc?_>282XH7FkAV; zqfv^6&RwYLOF-j!V2re>4s-hxj%LlPS<~!mD@)M9p3iBt>4$keZIR6+Z+F2b@XgMm zWPd%qDM97}z?HGL`c4J5*1`0E`h~n55%W_{3ngSjnVzt#3{X~GOfYQsD2%9^Tnk=o z#Z+dqZ&N5a$76gkvu@oFr8RfydVunO>*JrLiY(rs-2Elv_sI@+DlB9*5=bA`UZ&ET zVYM%6t036iJGxCDv9*e!N*Ivm0IJinR_~&tXZpU9;+b*1bs!DD50i{x5>-3WM|@{( z3ePmlaOX&Jrl-ft+>2D*AB<V^xVwxYYsfR5arfn{ZD>M;SNSDP`npywRc%J{7&f{K z+L1l&DNMsRRq^Ia@drh-!aVv3SAnf`mJTfxzwZ3zto?#-`{-1lXsWZmW)wZi^qro@ zQo`3%I5;@AU6cb)_flG3g_{w$gF3ymc8_{V_ym2ONA%rKnk9FKORl9;P<I$b3r%jk z?U_hpB-z!^*DvCvpUaQPCwj!IxuhZ?44Dg@5Hcu}9W-JE<>)C>qv?0E{$HKN|5tSu z?XX1L%4aQq;26tZ8DIcW!*&7IxA(_yQ6J2|GFUNZ))Os<!A$$Kx9{H@?zvfJ;`)*D zI?inpQ%`kc;KB<!DTygP+4ut|*X_atn!M*U{8Ri!I$V@eMR(&?XA1~CeF~^Wa$|rU zvUSo6;)mDX;L(pHS7Qm-SHjyC$8nDXO9_bkMjuHZoBB?pnGzl4Nii^>Qd_!PNatc} zHI>C8?{vJI@AxEGi(dZIYw5|`p~>HA8C3@MhhFUj{ioM4>q%P0T{@V?ze*$ib9J*W z!TV>nrCvdEYu@`7IWB0~ILCyGjn(PbqL^0Dc2<aCz<+hWq8sS5{beT3dXQXv+jy(} zJ-m&?1J~OBbbQX5jKaq}JMY2~NOktPu^Iqq5+;=~yXju{8&mLD_p-X{swsX?amH~> z=f<3Rj3kdHV*{EuEwMUfh1|1W@osDay8?2{C)GzQN@Vwh<kyZ5^?_#p&R70Oa{Sk@ zsQzcz8F+3Ub;K_XjPg+smE0yM`S0@=o^Uvwe*>NL8&&2RC@|su)m+;o0a>Pi%Ql|( z%Me&eGN9@~K{4U0*8^C?8*~5Z^v-`z#w}$WH}ovMu#G)qMDncn_j%#}T*Ue|g~0P3 zz+V%{8lKlF`$%%@uU}!_g?~rdoiMJ|Xn&~6$4vfHZHJe7bJH+Z607)H9-vV|#j&IN zsN?hE2!wXK`=53seNcAe*8UHtzBJFTZd(hK?nki)#(kDytq*V);i*~FY}YiuGJD}s zRhWri=(H7XNR)J+j_)(_G2U&4i>p63T|{@GwRs2D#SqY-@(Y-qt8ipcz{?}kC&2<5 zGxwJTN|nflsJnLJhvg@?aPK^^1cm>B;{*_$GTNyqMq?y4k2Va3NGMhnr}b+-_TWwF z^NQhc;Es)PEsdY9+8$`YA=62I1CM802hUY(`pgz;OqnFbBsZky`?VH3jc70Pa~<=P zL9;M{NvPFn{#Y@A_3$#j7CF2lr)o%<(S|{punpm<QF1JwNp>L%*w9GASkJ4dWNL2} zNAAAF0XQPOTFA#ge&;(?eM<R7_!F+PZ69~KO^uwg9>Vu`59EA{cC0Df-77;lTpt=Q z-N|rs`t{%~F)Y5uQ{Y)g!pnxrz58B~wobOj88HG$<@a5zC{e2sLH3+6>Me;vRR!Ui z?S!RZ-ZhF(8v<3ctQr17CP7|2wqHKKFqz(1;q_d=wGAoxFlg|yv(Ok-h9_h)PT#oc zm(-Ay7LRIZuqIDK&mr<~Rj-7_EA;h?dFKkH7i}N>+$+YnMgH8RA6>rU<e91wcG_tT zd?8x`eo)5ZxHcKzI7t-5ZXF-OKkdF2dZiQmu<sS!`yVcuGhjZ(v>BUR$JQ>E7j=bS z2oJC1FNzo~O7ce6^TMrU(a_2tXp{bKCms4l%>YEF`}AGdBNOfEK4qa#1MKmLK%NC1 z@`|N?E=_&6phZq|PspQo_}LO(pPM?2l@v|;_<B7elY4p{pa1nTbMI?TK8sokcYTP1 zgFwkhmjqf+PV6=-j5PdsF31wutj(}dUa&GR_=-B_`KRO%gz>6iT>Ai{5P?Vn$8Ean zzVILoxV8X-Nq}d>&_$+P_g&+hLB%M|^$u)ur1f}Cefre^)B*{OTfs+BzgWNG#*68l zs7Poi0mGzg9C>w1B0iP}(hsJwNG)hr85v8Y>}w%P@UOncyGLCqVmQzlSK6EjuYC#g zXdv7JR%}RMMUASeK4aYf@Vv9G<-2%$piV>3w3Q&N$iA)C-b{f+vEUL9LsfF#g;E`W z##u2Zd<H0cy-&+4&I>Dq=;pQgXr7-nl%_fxmb>qZ!+N7E*s~I;;>dg%iYi#1PV=5M zA~zQRr^!%ON)Vu9c>8K1s%99u3Z4?eh?POy*1``5^KQ@V)v80r`E*_g_!_54z8kui z!>mXX1@_QG$E{DkV{Hy8E8q3AlBu&M-UX2q%^dv<W>LB_PAzxYs7x}q8cvB1bUL&Z z`BKN4yM8}@I`z!7a+NpDSyQAWG*1vuMt`fcHJ_7?bF5H%dP~bo<EwwPvx=_cQHCK} z=baRu;2@&*TdWYtr<<AOxop{=%2kOK-xcZ$<7$;p^=aa2E`{t-_$-HU3P`y83^HFY z35Plb)`TW!xv~;DEy>p*_T$(BwRCiyfAX?eD&Z56DHd}-Kpg&18jd`)dYWPt%)f@$ z7vR>RSBM=4vB>j6eyJ_opI&d9J`_K+v_bxg6(}5TZHkwqsDBy_7jhemKI-m{OmUX$ z7DD<D5lik{&0ud~RJ-RTu2$cgG+#Cq3dl%#uR9lgr`2mP`y{GnGTs@g)-ha297yhL zr9gfEx(Zll{=lIN`N~REgxpHF;)nE(ED9HPA^jth`%$}>Kf+5q7~3qB?I<*PAR1$9 zH+9nKKhPnW<zmy>$4&(b@xo(mlcU`WUdE^wA1oPhQge?Uw^$uYb}sUlkDf4O2s6*Y zF`dtl=oe2nrL}#LvlSYjxO}-a${{1D^RA^>=UG#T&XN~jxwx~;%fy`!q3bZva~+nD znXe&ZD+Flo5=F{ha9VMdD+^HAFzd_jD;ecV)$}X5qd{g!VlIlNN>1c;vgq0|#aS-* z^+zGBSjd;JAw!v53B@~5st#{Nl`7n-JzpuUo-1WaY1&n$IVEXnh>t5}>le+yl#sCC zN7-++H2{TS!;FU|cvBHF10@TRfO|yV5!Bd|mHh*U8PapqIQpTQJ#+8$fGE+DqsEO< zWY*#2S)_oi<V}&SL4JRD9`KA=rtMut>aNm2x=zp2YGLSP#OSS0F3q*hYCc(c4Pdi` zhQ89tPgNc9^gif~lS)i~@-HQk(L4{v6urXCD>-*ZjYj0G4LEh%*lk`jZ#9CW)w%Ke zR?fz{Hm%RaM*1AQV&j7AaYS+SgnYN6_<Br<Rjj9Jrqxon+^(Wm90}N`)sj!UvD^FZ zOg;n5`AQ|d7M%$N((UoDtNz^eQh~uooiMy^@C3A47ps#@LPSQ@+=~PJVEH9y)pV%O zH0S2<58)+A`ka%<lX$x!)`pdKB;lHWM3+1oF*NY%(&_wHX3fAV{tgoS!(#b~H*jOu zKJZzj4%?$q5|*@Ug^H>~Q`-Yi%H`uVk3pTqZbU?{2Yryyb@3Jox8_}tUNK~S$a}v_ zEX%S3*_7uD#f`Rl>?Yu;#n~`gIuT*7Tm;b#W3h-{Ili*O@GW4>5TLt|TLaw`!a;fn zDCLR^*T}@FW`>U?SML(96|gomC~By_)HfHD{*<X=eYVTOqng3tc1oAsz%_A7;NxOg z5}BjMJ6k5>9yCIh&Dc>`xEZ@G{b`TCZ1AM{;g;D#cs8-VtLS)%>fT})_$O1Hl!JcF z(X;KSicvZZ@q#_03S+NrNQUxEg|>d2(n2_P0z?+VhMfYDkR~*Ggn!*VUw<4`DJ-F- z{xQaAPA*k+h(SPKT(ZDzcl)^_4xP!fot#u`e*QOe)9*PUOM0a{2K$n(WbZQsY)<4B zf%gO9rDqo*s8cCC;#gu<W3(PJZ_TKrAD}<AQJgtLZ!)D}SC%(*iGNP-qE<Td7RNM+ zM+j**&xsTHbp*;dh&@>ov16=s@J4jSIy6!bLxhUk4zHB>(t!`R)R>sp(mz(MttCP% zIa!gHDKV&Xw|@9ea}wJ$|2ZI$nk6Iv{_vJ@jr0>j0XboQsks!BhFJHlA4U=dFa14Z z&GYyhQgk-sd6C><QlCBr_IEsbn?uA!)5!a^cTk5=X4<8Q^RD5Lc9Dx=N@qA5`N!-M zf>ho<LgkTI_TzdTA{mM9$dW|6x>hv?#xm_$8!<j5(N|&(1z}R0IVz$GB_>H|Z^MKk zYeozyTsRV3ARHdV_)IuR<`;|k^8RJYsfF^V?;$(m?sl54eo1%y!r{-ax}MotIv%_M zDtFh{9D4#ih*uyLT5tQTZY>09IU;1oy)~1tfo^P%o*0Hz$G+@~;tYSl-AkQ3MwS|v zI<cBE*>R)K207io*|N>UFJ4UIz|-X_Aq5652Uc82ZLCAmCrs71O~O;3c~-S*=`3rf zV5^uoHe)wy4lhh(V;{^KXk-VV=vr*tv^#kfgMC#?z+mS)CexMhrhs=@o6TW*J&7^0 z{5Mjbb0m#CVIIoWvcpJpw@iZ^RtbTBK7@bly;+H@JkljAm$q^Rb~A?-f)N^?^zALf zI2!R){xBoUBbs8AP+cViV97(`<d%eLO0?iL%~t!y3}X*8(rs7h<JuNSHY4R<Ch!V` zajC{3aT2?3mV`3}CL5>Jip6GXn-rU*?eR9vq&IjuzewFUYBgxx02OY>1%dM9BsE!G zjVZhf<sO-kx|bRFGQSXRJeS~WQy&qFwL9FI%%tY+HBrqCdUE|f2zPz*t|i*mQh$@k z|M_X3=OjgNvT}=Aapn)3&{Y7TD93H31b>hz6o^%)xSa|jgRXr9G#dlZZ|&;@5XzyZ zs=(qE#S^q^|NQ(x(-N$$o6}1tUDW+C2S-|LeRjQ^7wC{Q21sBj1jJ^)`dEp-Lz)rT z1_UXA^ZDhK)7HK|GUu>gWqX+No~YS?jOvzZ=Q@RGV+>VnxuOVbMmN%Mb@><k_^<~> z`?wx0?drEegS3BG3*H0A=elimw`Dp|jJ+MRJAWR%vRFuxI6|o2sfy!m*T5oEl@)9P zN>$gO#d0-mssE7gSbD^$0~Pz#eH)UniyyrX3qyQZsCt{tIceMxkhB?d?w;yXrGKI! z8N1CWt+6nRcKi!FsQ!g5+A(<sDmrCVItP8ZNCgqtuxImqk=#eF(7#ZRX^0HRfLk&~ z=bAs~Z-i(TBEqJ1kB@n1(hBcUoENNStzM-P4LSjeXGIj~<^KYQa{q<qj8-=;Gev{7 za6GZ}s+R6|9PZs*<bc+@R{uAS15r|5hj~sS|J+xP`@03*J)sEgmK!}>c%SjElPw<U z6hpu0FJrqXflPL)8?^ryDEE^i!Rca12kfU)R(%6|arqT5a0@U#ctm?z_#cQ%Om)M< zOw|p%@s5Lj`8MgRivLD&t7_a=T+4YE{yH0cgTEmyOaE|sgC}n+UxOar{sX7cRh4^o z;Xb1Kf>i5F=lZrTp85aUK*PF%{cHixL(+zLRZ#z2!hbiB*TWIV_muSl0)#lu|K5f< z_U;`JjF!>6fqwmJ?kj*oKcf~o1-$~hv7>-tn?3Y&3MwP_A9VeBN`YA?HZoaVA;R-Y z5h;zOskZ)WV!>E^4ww38fX@hE4DdCrE%rA!+9)SfnR!4oqHyCx?GK!13)abdE)mh{ z*q)Z{dgzWTVDI+V<$eAGP50jvyp|2tn`#_QHMyPT|6h}#^VjHCIsxvRG%%q0Aq8kA z%<lpq0;FWS(O2o%wuh&sdzycL+`*}yQ2?|663y3M)B_8yfR^Jwz7NfRI=^xMRyd$T z3w-xi76}gZZ?T~!4=sg(Rdam;dbtNm#c})7xg+9V>i=oTI`$E;a|!rQ+_(6FL;ZK` zXKE_Aiv(zW=(^rxSAp3Q@Y$fkJpKdco_XHoHb5TuE<yg$^Y7r4y@0NtvtI6XPZa#~ z@wIFlkN{8cHz`nk{*V2^jT9hM-mi@n^X9O7KeEEt<O$H&qvmT*YM0jp8y!G_{(ZnA zuG$q-QT4BQOfeq7Eo3){9ANUqpbH*5{O)zX9RTNEc4P0NuDBAG7|-iwu-uU71!zPF zoj7=Waxy{IKmgi+xNuOXrBLM@T&s>a2r-Y<;NQ%lRi2kquLMK<``Wa|vHwY{Od%Fn z5R=7KTUW--S&Y1)z>$Pg^CJPxop8_&1VtoY2|8I5!_2LP`)L>FI?PVD8DjUc5C}8M zUm``uSB3XkzntRWjzccy#r9fM>AGKmg|%xg_a?V%iqa$N)<ST~-u4+b2{XRZRlk~g zYu#D4s&*AsWw=e#^nCJ=7R5N&MUA=>2N%A%2uU&@z2@6Hex3j?=?aI>160A5B8yVu zQ?D<>uO)F;=s5=hIx>sTt5BkWj8Fz0+}u_dtL452JLi|Nel*C}Y2NC@<-Mm{D`M0G zy@NG!(-FRkMJ3+Iq4NxM!WwI=odr4!*#+$4)wMSQ;@`sM?-7C0)dIqTkx`=|=Tp^1 z5!-%={SUyx84usTc7f2Y1Nf|q(Mg^GIfP*oi(@;Qm#v|3eKp(MG{0q5Qm=kYys-E@ zAkwg***JM5Ug@<uN7EtK%(dQUi$~Zh`!grq-rmZT;Jw;&Zv&5vZs=-^Zi+S6?y@G= zY$pi;az26p?Hk(TK*tA(Rm!*2A=mJ6Ii2(INe~aIy^a+juh3I86rnvQp~zRBOL1L? zu=l?0JK5{T4+5cR^<WEf+L=L_lhMnM+pu5Lo^XtMvx!UAU+2(>xe?hcvNfq=25jLS zlb&C(^w!QYuOqZjW9gTQW&&Cs<tkb~s(RfB^iBpLxpHZu(uwvKN4_ZnR)W5$SF1y; zFq$%W4T+09S0}1*MQo<3gBMQjEHJ<1mlT5=J0m(oHCnQy!%;6Q>&B^7bWl#v;A2e& zauSZSzFRFIfO&i+gH8&5d^Vs%;S7GBxsY64J^j6O=3eGpG3?gC6z8uzre8!AOifh; zZNuUqoq-Dy)<|C6o-OfIXD#KHlcJfFXRZ16#dHH+JsP5VTIwppjTrfR!0R^NU<U3} z6{FWBQntvD315^*$>A>IerTLybT|vXmw|2{{K46terU1sBwfL}wnVw%83j44Ob+DA zo##tM{&ebd?4ml0k|K%psPetf+nZ<X5(U6NV&&@3V_Iw&XTV&^P?hcIc_{LzEEsvK zzoImc=uvgeov2Tis~Txuw_olxa5l|_2TzH|Muhw#pnE6rHAoKKw_ZbrotD4RfXX|V z0+JyFU9NQHxslq@hg`*_eIB2_U))(dCjMaBUqe()l@D@!L306+ZaC|tw+i3J$*CCV z>*;s58i6MslyN(oIbCOM`Z=F+YyfuCar&2Hj*w`nFB>T?a3@5qe)8pMm_&q+r&K`8 zeA%7ZR1F_KTlUCeEqFHHRA{z+1)o(6ZNEoUQwS~ej?*d?#-Mn&>UJV$R}8|uU6|AU zN6X+>wQ#OcF?Yqgb}eK9H4m?|Kn}<6R&ZxPaB6f9ihTeKOH%i|8Jq^K8-SLyB#$)D zg1-^Qlq8J3kZCKV<sQ*G$&fjYV&OrmhRazN?=q02BTC(TTit9L8IF<(hTVL9rNdXo zSC*U$GWC~r8<k#%JSQ(yne;H6g2j=nfnC8y<Jpy2^Zca@lKe?x;W+E}P7hqy9+<60 z$urFO6i%w7sy3#=xvAYa&%ydv6tPK3f#M<e)6fy?pm2IE0TxDPeJS42+`LYP*?_XL zX@f#N??7o4vCMZn6O?+H+2Gi9?z$^3>=1)VB*>|oG34tKUL5(07nRVup!@KMu$7Vd zF-v?CuR0b}yIcJC^ff*#OB2N%vNB=iG4g1KE6~2Y6w1AZHR6TO&isrKts3698(*A8 z?6|!uRHCEJGE$BFU&{L-yJ{+&4B||l%pM6G6}04yv^M4xCW;=B(5tcEOFZLh$y-ug zTZjNTdqhiu7(;j<uNJIPG<hYec2v`rO}U2z8fKEiL>?3}_}qLa=3|<4mjcgBR$eAV zwF>!uuz875=hX|7ngNQJiaNgxN~T`8O}aS<InY+PSzu$v<$U4tGV2&)6NH?LO8Gz_ zY1LF5|Fu<)s@6;yy+)F|p&diWyth~ELR0oe_DAeIIs=8<ZRZgUBJ6N)>$ug2<!%Ft zF&X>Q>IbCEj)+r#uH=Y|^xjo3>Pi@PwqGet*ZTZ@T3Gf<br(z1Jkv!9ISA55=5+T9 zlc3AZ_YLPebZ*nqdRenyH!-Tc7x$;QE;n~HT#QwseHAX-!FnEr7P*q%g%Z8MxL$!E z`q*ElNRNo0P`Z_Uils%cvhAfx_VaMrxn@(&#82&+%Pybg3T!fBZjh-qUs+?=k^TeS zVO@8Spk5FI<m~`0i2B=J2<@Dlq9%B87i&n#f#5;JtBqtFW_b@z3lRIzr)0CvdI?CX z#->p|=(V-T=hmkz8+PDVaXaPY<><^&=W0z(VYjcLysTkgk7q<YO~zyDEp~i2ph``o zB9yAZ+a?yyma47esIMPm$Y-3AvZ+#3)^a5^qE~m;{Kg&22<bLQ=b>T{D(&|p5Dxp! z#%Xov&?7iI^6;I$*>ZrnzS#4I3}In~1g6zA3TeiQwVFlN^`Qie4T`*rIY>NhVSu)q z6my?63?o?MY8!a>PNal1rzX15$FzxaAZj{Q^MQl86j3r@(VVv<{LTu5HittOj}ekN zD92vOm3t`eJ}o;v<W_sW3)n!Vtw`TObXT1@3)VN}>g^#|DWcBSwMjCtsXHxC8~*~M zenkVE-#v6~1enZ*!)&;6P!Yy4nrVn5scjwEryVy;9`tyKv>59T=<X3Sd43ru)6wKB z3xj`W5u!$HZ94T#?C~!ec>Ji}a-Q*w%SoBdAIoe@7(saF3J%$Lc8Ca6(`7#wnJo$P zs*!2jHXzo{-kt61vDwkks3J(==_5AQmPmEsbLlXIlQ{N=kayGrF;@&QQ1~e%&-C@T zWk_0I|0^YK-R5ZAa1>iDB-O1bjq%e%0ozjw%`p4;XKrvcboV#e{x%3IVj!4pWnI(t z-StN~WoU(Sy}8B1%iI2XN~%ZUvuW@GdzCcc&2)3io-)h0Iob961v(i;Yl_SZ2U0i~ z`<rBZf7UnEpv)1hac7XNhAD}_?ZEwZW!Rk+UdL#}=8Ea}O5>@I>i*K-qzMy<&@<;A zsOpj{BeUh5c}e+4oex=LkYV5TmVZ=E|Im_XH*Ykq<+m7Yrs(+kVLi5cNpg+Ksk3q) zH*;p}<u?I2={;#L&D15UK^>hap2sqYCHf-zM$A&}Tq%a#l<<%{xo&;*dBnEcVPzTf zHLApEQ+YCw>?c_jZ{uFMh!qpKr}6=n_La2aeDKnBJ^?x8Pc3083nzS}A9RUyP{wV( z*}H<+UK!qL`|XKjn=iB0(VT7kG{tD3T-1vlTNR6%FH!B|VAk6kXedI520ePt4!h37 zIKT-#n9xtmrn^}7A3nd**C89_3|kC6SDTkgBMc8Ltv(|8hDZ=CT6Kv2!KVFd4bXGf zMC4H%Vi*yft`;%<=`74@HptEyeEs=R7Xe=3#h~%Hd&?~u4`sgK;}Wn9eZ@|ZIXj-q zp;JHYV%bk>+=5su&GtecwuU?9C#VEg^7nXB4t0;gespq&LO5F9m2oy5et1qT-yYLD zj@@z|%r-~~;Ijgl&?UZID?zPC)W;-wdXXsecSwv|!dj(H)1cxfZ$5Opb{9(=9+OY` zbg_0)OkrdklhUpt?5QzJ>QjeT6Y1i-aOAgAH1T;J>d$PSLqhm!49la|1q=utAW=bS z1ApW~2XFZ5bM;N=g<W@NhW*_JWuAZ|1N#J5+@&p*yI<NtuuoNp!;oO>b=p|m`45-5 z<;_i!G}DoV?eV)r3+5j=i(~Ax+!`hwo|Al5Zp1G}gotCDI#H~V97vD19iUHpOR7;F zHg*sDiA~hn+D$Vj5H`3u9eEw<&zxVpSc|r!Ct%JAQSr!x#)DPgb_B2eAOwawLQcyO zw_}M49G>M-<lJDXDv_e>m~_P5<Pbg9f9y=4CApIUH(VB)Av-&j*N_0HoN41tpC!FH z{TThSrjA2tu$FaViO)}K&Cfm}(j4`f854R3D6(P!=BIK2&uUv;8Y-To6&N|KyV~qO zCyD1WGBPu$QlEgD4)A$mfc@Ukam$@17AmyxnxL4)42<4Ki``J&y{g*wG=ub8p+$eC zg>oCc<QMfP_jB+0FOSf!PXcK6i=_1>5Q0f=Rs07I?md)BR!zt(?GjhigUr6ZCFQiN zlJ6ex8$Pp9vNeAwhZj=bjXy}T<!GQ#KUw|lWb08Tn@C75_rR?CaZX7v^L+f?R70D; zaebhrOUPX6No9R#bf!fjmLsM7Mb|?*g9Nc3gAZcuki`z(&!c&2vSedfnW5!Pf8YcF zwVK|rDaih{QS;U0pR~hG7zTia_kk+zYP^f+FI7-npwDIi)O&-qeJzs-ATyqSiStMM zS5IyNTj;*fv-=iqIMni~z}cFBzz+~(8~*D^7tb3&pf~=K*JE4ouD16T@c+c59!1bE zT+7(bnG1pjqu(_2PB_2W<yUvLl2QX*dF4?6-C=tz_NO7_o*Y0?+$#g^12@ACzd3cn zTHXb&`X4yfctFiO_}j;u{}>R=Uq6HFAAzp{gy`_6l%3}zal)SiYOHhl3v@}bpl8wj zyOaILn++H};M$A{Kx?jG>O4fk1<v<ipt&btob?@`?K*&q`T}0Sb{POH3H5gq(tjW8 z;<~yrayP}Tj8JIYRFAYros|H^aNnSlv8=y#p}jfI01{1vE=XXFIB}j_=h*;G5)YuO zz&$~*`7<yE{nPpIU@ODOnvm(K!mV#4sS76UnA>P5oS*g10N|<Nu>9T1I_Y#$zy@Ft z>>WSx+}Z$00F9RmGjDesTyzcvRk6@*popUc<GTC@jw>{*EhO!{O9VL)v5Bv)33sC* zV;NIeGYQkh`wFV}e=Em~$hmWDiekz0D76}rR@Q8!aMQ71fms7@@YZhuHz8NwuRax~ zPmwgacM%r6lX!IN5^+~zlfES}hgK^pMvXJuem(1ty1|39FvcI?bIohTJ@w+mdO(Ak ztU%S>Z~)pKB)vN8hMQUm`q#FG37GcM<J;gb;ZMSRhF!e{wB%mOvR!Wzey#?#5KzDH zuDwAMuSKDaFxCs;fsV!Ip$e}wf$7Kt4v%*MJC5*ZoE2nDCuT<Ql)kr=k4yITc9X03 zm3$vI=o#>{HL=uTYfv;AxGg=Q8P)Nx?_(!xfz#<g$J2k{ggK&fc`6$VA7yJ2UPM3a z&)1eOfK><&0_KjOpL5VE9B<GPH~|Al9DpKx9rV<7aVhW_IR148V2LNnI8HnM>Had6 z4=gOz*~DxTzrTkZ5&MD`&sk5`@vbkek=2@g-6sqH4*|VoIM}(#dT>R0fqIL*7DgKg zy{JrDQq`0)diUZnInLt&v(h7gXqmRY+*tkc6_4`YO|kyojahNs+pE9-VZi}6E=DnS zUN^~*;^~uI`P9CJKo8)q0+#R=fVC0(Z8WH$|J-?>3SLWHKR-EIHOeInEF-5;q$dA@ z^9l!Wnn(lgV9+UG(lCRS5bFNBHULNK-@Wo#VGL&+=j84P<MbLM9LbN`o?YO!^my03 zfzNt%h}pS$d>$NuLH7W@3+Wi1e+|5rGLCnMV3H<bOJSWiL8F<&yTjWXrvvstdW_4T zErYJFLF?cyDL|*T1KLmcDFLV-R1e-FJeD2L6Q|`#b`Cdobq{AdEQ6ZMZl}Fc@>WWx zP%^Xj85&bt*NvAOCab;6oW^Gu#^CPlr*`U{y(;`gw0tp5rXY+##5*NVDHV&2a{rMu zmj|@i1FR7?ymH=^-G^l;f9>dFwP|;U2Bc7W8Cd&i+dDUUH$6gIZZ&PRoz(k)71xkG zO?$!1n&SOTt`>Kdm`d;pBaqbBLDNjgohY-`sMDBJEh<`a+un2h<*U{B5SoxNAnb6V z*Mr2Y@3x<x<SU)<GiTuqd{<XGO$gXI!y(nqNH@P}m?P}vE#|SVK)hHiJ4Oa+RJDms zCJsBuEF3MhULIna3a*9}<Zfi-$BcZS=QQ@D6X>$n6Hj7<WW0iS^o{K&<jXzfC_9BQ z@M(dy&;4Obnwsq%oc2e_SmGYEIRZ3YBi-+L2fwtf!SJOa)7l22_}GfTVyZ-2IJa`v zd^=m(j$1#4`zS;N=^nOTMG}l>^(K?Iz@9>B**@XrpyB12)V<g@?_CDM2HzsFr>3Z_ zW=}^q8;_66{Ye(u3Qgn!alT^hadkkNP`jUOU1TeqR<c6`sQaZ26<?*<U0O*mi;1yZ zI4p7@n@F1p^=7=g;ivM=F4^^2X}a^UzVpxFRFp71#4$eY7A4-n&+G5UBQq{1B|_=2 z>gs0w7+0Oo4_c4uAbPnv+(Wt+XI!6ljoxZgCY9)mndp^iYpJAs=X4rZdC;$)9Z=R~ zr-)qr4E=VjI1SYH5Cxeb7s7nB3@n0mdKju<2u-OOFf0v$ztI-D_Fl-;T$72HZF7$3 zS@&2`@co*BQjS-}RbA<FHD!!3S5blpf^=FTtk27eFJD^j=F<jT*e6+MIgdkz`hW#G zhyi(2-^_9!?NHL0>GaD_kR|K+dpRV)$2s!G=DV7-sAZb=-BdACd-kbfFB1@~@L$QJ zbr7_Jd8C%EqG+XET9fy%%FNj%%dzKD#hq*_nI;gqMGn{4j!`C$dw$2)w-P<WO@<`w z<Ty1Kj61ldv)p!_R#(((UTJ7q=`A)U>;;v?0|f??l?$bHb0y{!Ibg4ImL)@e@0l_c z(&a#n1WLY+>LLgHYezCfs*HgzyQ^{MjQout5Gw<gXRpFhK93k%jPUzGCQAQo#f^OX zeR<de^Zw|19=~uQ1rAn~>zr=Kgjj1Fd6^v$6_&5FswB3<ywc1PU8rfkBdikJma>qB zbe=yMaHD7&D%tfzjrF%aWU=E&;#ILGLjSnBA0&!yU++{!^r9(7nAzbg6-CfqrFq@E zl-6@Uv(Wjb?)GXrx%1`E+LLI4rv)*x=YyNi0Y4LGk8h*Bt9QBt&<5u(ucOTeZe6(y zVJYb=3+7gihIC=g;pfu*H5{V^9hLLC%N-SUESujn$vsw70wr>`Atrp;bq1B`;yzx0 zq$R52sy0k|iDDr~+gL*+w)k2C9&Xv!nt-$3z&BAphFT2v=M4tOafbI?`N!uoxJxx| zYKzopcNkKu(&_c-T8$V|bMLXT0Aa9SSz$U67>_GeXDi{3#(B5R#<^}sEt2Wu96m;= z4X16N)G9co%P@NsTbr>YYLdyD=D~%Yr!_vvd6g*SM+gtHsjiS_DhU7MH*=Q|q1M@; zh0rama->#?0z3J*+*iD`@5oZ3Y3&i>MnZW&Ceyu^Yh9}vkG)|UGR+_-FIKxCr%{)~ zwKdu=Ix5jsO8A^<lxB)ahbVfomQ;w%j-J<SwSo0uZjBYq-5j|EDDGi_Hfzwx%l_ue zXKtcLTwi@9)lz!AeH=wT<nqk8pHbXVClupT=X?cup-N)(g<sJtRlUbc|I@BlX$7Yd z|A=Q!dPjDW#mcms^vEROO(Y0k;qEc+oA0$2bJsQ8gY%9^IWSPIgOdzJ(#9AHwN$eC zwcoZ^L}gQJ>`6#s%#f>asuhB6lt*6;{nPZcrL9u?scN@RB3a6vfayz-2&VGBkuAq_ z!Q_$Dp3^UGHP2^E%ou#9!5x!S{*>Sjr-RB71%W#O#yw1AqN38(4G7i<pFfL-=o*C= zL7(d_%$Jv4msavocd$cxsT$xM#S{MEM;V--h3Ntu!j+97X_BhL(m#)hc4_i(y2v3B za1gLhY~zoJ(;3u9Llxii4f~f31xGZsbtSrS-+OFNa>1pZS}^0a%`uqwek+6y`O}@b z7x8i?N6yGpF(`iAYxIYH()4hriC`5?miDiN^%b6A8uXLshRdJzV-{u4DYq-Y<OO90 zG5xk&rP{h_Y@LM%t&ZktK8FM?E~vM00p%cR<Ggnr2HtDI`lJ0|+K5JV7&D_nf-3Ut zGB?{nOK4tLb|ju!RWZ6Cz<|K;!fkVdM_0mk@+R857l=9(!O%4!e`51W(cXiAeF3~W z9|0m)XOg*uMA<|Gx}0#;Bq^aoU-h>NraaCzhH8g265Xi%HJzw#$4)*ETF9v344~s+ zir?aaHZSekhCj^o;G;^BzVpyuq?D;FK<}2=18SsM1c_(K4P&EHty05SaH_PWwrB}K znKo^pN|AdpEj9muB;pWL1sKtxC)Z}@Wp9kj3Ec-v@W?~vLSy-ss)!w&%6hd7OZZ&; z^|Fh#U|TB>(BoHzkOuR4L5$8?9-galTNteJ6$gV{vYDd${nj5$>Agprg;I|3M$50e zG$T?y>4mNvjzMn1G$E5Kw9`Ru`Oa=`>mFpzmmHZc`*DF@Cjp<f_{+lL>X$iW-N4SA zkA=Q{lbrje@U^^oNiwU<RfaoKxC%2mNn)krTkzDfd&(jAPIE?z<83)DSV}0#tkm~N zlY<t`!ORRxwI`Cjij{WKI=LbtQ<lzj)sO+z48cl7)yN@T;VwFGS2o?IP8`+RO>Dy% zTR5(t%N8@BpIoIwvTKvQqe{&rEWpR3p&v#!>{XtqT@<{5K1Dr5;Po6Y#+agpVm!{= z_)Rkx&k8PIL<Qc;3V+b9O8lelO2OPX4Pow08FIv%Xy1#!pNKT+V+{)tM+d+?82T#v z*7<>)f$^f<E{5C%?Z?l`ZX@;rP4B6NninjZt!zEK`?xvrLG>{sd=Wd^CXh#Y7z9Ne zK0~Jk1O=8rLQf4B$ONzJ%@(c8m8oh=M;M1I9Zph|>EefVE5ZnZ&HFMzy*hUww!f5- zlRek0eNj-vGHcy%fs;s4vlquhno<5?mv`Vno31X)>GhZLrhE%GNROrQ7?2aP_}r<s zv-@R=>cYM)CqtQ{?+O{3-({z?GQoK&4*7?EW_S135T8Uj(5vFua%xoZXwpaJGKeD^ zE7rNgHy~h5a(%j`m#Hrv;p$VBUxN$Wz57&hN?7HuVFEs+Z&yj=?7ZO~v`^fs&<jc( zbx=ZQBx7@1i)y^)Xt9ziIo&~F>qCm0)J6r4JO{<Cr16>Cht%Fz()%(GV~%}T?+#af zb3NT}lZWw}?|G}bQLapSJ9?M=uvCULM+>p2IfM`26AjM#wYSTD-gewe$hxc+q=F2u zlXY65`RYS#&?iqm3vc)#wyI3l+SSpI<PT8y^`Nf)R=mu;cog-bUOf1DMG4vwF%(_x z11vx;el(eq%^_WPrXA;OM9tmXTQpr4i{l)d1K3YrCMj{KoSglFZ0Pa2{B(Bs7AqMj z7Ysf*Pb|I*qpKKHAD?j^5$#wX%c=6o=a{W>IChW=cspSKo%C(r2Kk_2FM^4$Luu25 z+<;bFO8QwTZ;!ryg+{JWbiYOsv*}cyadCv9U3gO28Vf7h3~4ZAMb?5Gdh1Kfx2^QH z7jdHHs^6A0ak7yW7_4!5iTa>Y9Xd@c1JBW=D~wj|cV-zlJ=FB*6AtTQLywp4HH;Ud zHMQyj%P@ka1Efm=6nnC7ir5?IH$)cu>jpTc+b>L#sh1hT5_W{6y9v%n->l+y@jpS~ zeXgjk1r%V*3bV>%S!eC4Nn3j>GrEc)BVUJbD=DZ~RxGb-zu+wNbT{V>9CG)9>Y4Mx zf&{yGeR-h`D>`TDn`ZX7_9`uJXk<&1rdjK&dfh4SuIGv{jNuH4kJX}?%Deb+rDdon zV}+64612RJIY*DplxtwTg1#N{CGQ?2h`$Zj$*`@Hl4Fs{F*EEh6?$Q~?yuLwS4{&6 zlrn0bXSshOCEeBtdK9Ep%1Q%C)<tPoIlOR($?m!zJ$;GOWgl-@OY%}w%PT}MO_T9k z0RTZhco|bRQYKGQ&s4!id)+DUM9TW44Bns@1lOS#cY&8Z3(&cp^~g+ixz>bvr_O32 zT`!-AI%mDcZ~#Z6=9f|I^el863%$C84kr8tx?LFfRD4*-o_D*x2?|2y`$cuVaC{^- z-Sj&W&c(g@1yaJozJ9&^8+5EZrW#^S`@mHnX9Ja1L8tHzlG0Pxn8}L)yK4X}s@})M z;dn!Thk^eqJatBg9PRC!gs*IEsk7VqbHtmnru@9q2K@(yn()FCE=ZQI%>kN3;@iJE zP+D_vfT+tgtzt7awWttyMy4QjZ?5f6<AV2YL)U;fBGl<t?Em&>^W60KZ5Uh|%?WRQ z%%Xb*o#X`Go8hj1=69srp#4ALL(jIV!vlt#{s%usB9k8&s^29L`${rr{crdm0t3+L z-$5V$6F&82VF@MdWMPbHp)h0g+fKYCauK=bnpoY}yLxitEf%1&@)>XdZud9J1@sR? zVW6kLv=HNvHi(s~w0AQ6jBl#_ReOB`*8%!FL=AZej7PTh&m+(oSEUP1*1x;AjC{)o z$X0?oF0LeBoOZdj{>XML(b%r|h!n<jLO+AfU2vBEg^OAL;SS15KN3Ny3ru%oBvM=n zGd>Gb9CAEEC0ZQ+3!YD*7qE}<0iuf#aD;?;&E9zUudf69noS<Q>X-cGPb%Qn?&Brx zAf+FGw^IM_Bod?l!x&KgWYkpixr)kfjAFj$XJY!9PcfS;kYVF@PNsU)2pEOmb4xk^ z<n_0!LMwj9lgb{kKI&b9SR<9G&#Yl$SPD09EOZ%*wnly=8OeitB&^7x?R<eUfa#t` z`5)?ge8NI0zdwsL0f;_)$yR_6IQ#=ANEmH=o>R2jmKtmFYd(f!`qM5`k|^|+0yA~@ zp*2c;by%{r$t0~lZ^d-nUDEB08Hl^_VIf5Vwm=D&Zz8m6+rCOTu)H|0C7V(!Jf;Rn z9rIlaRt)<q*6Ulz*h>#ojoNkY+1()C8ufMa7}LtejW-2pd;WZMxo^Az#BUt1(4mdi z67KFKImyV!Rshys{zUz0?*lVWp^+e>5GKr{PD^u>*6y?w_~c@x;8$Pf$KFew=H@8B zgaWktdjHlYS16%3&q+4(dMzt>JN-Nabvy_nTEZxxfowV*<nyTer!NHh`KI65^!Rz< zaQI#G+#0X$5_2|Qp>IXjgm;kR7I*eL5O%a@?Ljsc;?e6^d4TS$cDz`amKV4VJC+b8 zwm>JZB@B*&$geX9A5|zbG(2;>k&>8K&EFeDxK=}kdAu+grk%if{z>R5`Da?9l9qL* zTPv@nqWSm7xv}^I#Y@g83ycB^n^iQ)7b^IbmM<7z0Hm=MA{5dq^Q$k87-N#(S>5_c zrM)=wYb|8qYQTGDHxmcxaSN!F8W_5Y!HoO(E@E)6Gk`#3aO!y$T!(ylXWFd4Mm$+* za_i<xydaaJJTy06Jk_B`JP^ZP3K$CU-1@x#59j9B-PrxPh6+1j0(O9HCmi~E9P<1~ ztzx@1y5u>btaqJ>C5DuoC!&g0C@mkeH#Wh<EG@=ahv|0;H@CSnaZX0~m$C98V_Hbo ze#uMu^4gUr{&*R<-yhGJ*IDW4S<wDA-5&|$8IesvHpROMLFGb+N$Ua35AVAb&YoA# z$<ddt&@XGnjlG0c2EJz}z@eYeVOD-pf%f{cXG}{Y`Lgo8Q|%XyWKV+f3~rp$0lnmb zT*>)L)+<VI^A#16Riv7Y{6pybmSOI%{^B=6e)Y8de8U!KFRRUHpWl=nPa@+>b!hOp zZPqxcNTi~rUUVeuHGe8ctp9*s(`=XE6RLD?&c?|9!Pk36H5K&lqCr$Z1f=)gyYyZZ z=_1lQs7UW15G4}ny*H(*^d<rcy+{|3-a8}|r6$w>A)fu7yY7AcpS8~Y#{NKNX3u0Y z^ZcGNnffwAb8IM~hoD5Y%-=4?j$AUQ>C5ytp<=7HuWbT^1IrHUH=2@oBWpllynBtO zkika!(nE@0X`-3U^jk5A$`uS}ue5aC%8KPzA?`+efkWATE&5Ggxr=YhyJ!XLw~I=Z z)w3i+4<TBr{rV%=3MDlIh7>;^`@38kkEtHwS<&Mcyi{fJusP_&1`XiWaVADM@^&&@ z$lzbldl}4}f@n1SW05nmgWV+Bpcc%U0Scfp1NOUrzpwyS`|sm(e5wD2j0#qNpOjqD z7!urDQctybE}5v!7<1HB4&7iJ2T**bf{Q6=0>}qGi_yiYru+qUtc?Pwc(|7uu+#ZM z*Yt2wN!7cw+1%GISJwS>CXb9kOcdhp#tHP)eL7KTZUrZ}wF|(M0I*yB=K<ul_l~6z zkwo<;p8++S<X^UH8K1J`a`ir;RZr>Hv38woVFI30z$+@g+o`JfJe|OKZ#{dhwj|>E zR`4*3W^7?fn^CnDPcyQ$=6fI4>=dzga2I{U>Xf=We#M7luaxZ+>6lQmG~mA?3%>JY zA(^FFm%NZQ5eHISu_vtezcw{%Q*(y`F)BDMYHt>~!Uep5p%z`9A5SRe{?x>`aTj9t zdT8@0<^XHL_PEy(g!jWA4DBUrY`v%wCmc#7f%H2hb<YkMb<d_58)w0MR_Dwbu8QAZ zU9tXvYKzj;Eni3f@pcfXGiQ*pKWpxuOHa>|WV<=q5L}VMnmDog*)e16*58{U8e`Aw z=)fT`B|%$sKrCC!v^#J9O`BBF=)`{J!Ap&6K}FxCMcAj9*TxwE+B@B2^&1B=&u>2C z<Sj6U!)j=<s5dKYA}QqqLS*(lp)Zn`?KE!<W?KC;<`*6&dhoMfgO58+4V8uEhmttk z;qSNUm;M>(l^^bNKqP1!^U~D#y!S@UTX9djcK>M`9*#=j0o#<qdwpS^l~xGe-hxFA z{Y5f;)Le)pKa78STofYXK+x-aM*TXnpYUMTd{Xe^PAIr~P$OkY0^W6EvPk_JH@y*| zOCRMs<V0@(IJ;*__=MXJT^7E#rzW(NTuKYo*5eNP3sOZn%69}t^u28Ilq?PVF;%|r zW7NwxUV6_ppOZ0q3sOPF9o2oU$U|~6Q?g|$Rcsi+voVQ%gqn?bxlTqJJfcF1M9qvQ zIVl>rc~$;?C&_ajWVFLrUcGN$mt%O(!+kw(6qTye;a>FfWwlB?E4kvM4N+RK-Wyip z;XvAGhvvrC$tjnNC)|YD(%lEIc$N{5&D_;)?0yZT0f41S0>e@4sc3w*%D_a43k&nq z&J=tzalv%*_vrcLu!qNOpWd3+CBN#l{e-r-8$-f9CoVH)F+07i%vjd1HF2;!f*#BM zg5vVX`8^u1yVc%K*$>MJ@7QzC_cTb&A3iSWPv(<H9$OcRf3Dm2Cp0Z|O-gB~mg9kC zqH|!}hrWwL@(PWJ&C6i5`!pg^v^TmERo~%X&fJZaGC4|KT8xoJ+F55XkWyC!$&--_ zfIkAc5>kpXTrWoq&Kgb4Ox5p9bKg%nQq>w=PQmz+7|p!dQ*zVjK;cTsQ^ySJGAGX; zY(eH<KTZrUzwMw+f17;zfx34-9VW}C#&#Yz+aYn22!RIP8HilhC$*V(wR9{eDbB4` zOkEyu6*1J}$`p=0H2C;c2+Ct&S9+5Pu~;uiP`(Q#1s5VUqhMaFfHbPWPdNj@nBtf{ zQ<bfp7jQA?ZQ^mTnYw+pu50>2KZPqK^cLmiKs<zHR2Dd`IB)tFn;5ykY4UXRY*xif z`T6-4Y;8BwTqjbWX&%oi{2oI@uvTs7ay|wxniB!`qc8!3oP;;U{PH3R7DKM2L_@QA z{3AxNX%m+-3M^0+jc~i>!t9&}e8&(KVzP((X|F~LD_oP?yw{5RPD8!mIZ*br=go~7 zalKEIA12Pua&s3_uxerS&~8Z5N;JdH07GDxn->*bo3KNPiy5taJcIviLTT@>nA@+k zWZD8L9$%1JJ`Ut^I{Y}v%G=o7&=ziOY0XvJ5HQFXX*4PyyMPHqGxn~Lw3+x-fCJue zSZSpqW;b-zAO8Bdj7Pwh8%oHTGM*glB#36D)W}d|aZ@+mD(9E$@C+JaO8R6YSSbh} zT4_J@@VXKOz30Ki5qCFXvtq@sz@J|H9=k|8|6b|(G4~Gt<0}5qY)C~q<(r!f3)x~r z6Iw;rw;6Lue?hK-c1w<XT`Gi%b{j#}tY(;qs#TX&a<p=Wf;rEZbC0Z_+2My-5*inL zvUtz+oY_Bc-ATE*K(GMyr90yK1S{4MZ44#KsP`R}{{8I4SWl5hE$SI`cO;g>NeS;4 z9n(L0ZqBEq`J)qKa5eU$se{_BL&ihYy1wK6GiE2NR27(dFd?g#Zsa`%7a6gXFrjY_ zO`CUDtan18&d|sLIBUEjor-e-y>mVV#%?1|#74K@1F7_`f9WaO5zaiYaNs`cCB@br z%KHdB=D|HuC^2xqFklFm@WY44s9>_xN~CA9T#d9^uBp+`a<Hpk?9JAJfXnTw;sXZ1 z)a@4BPgJKu4>&9Rg`X#LBJ)(&kQcdWyHs@9vh_}6C0{pyL(e=sEqlrREYH&D9QK8O zwgf<RPC9F&Vmf4PAvTz<5(qy=$-W$Xq&mHC))yEonCw#hZcb;PI6U9pb9ekH!vjxh z1~wYCZ3Qz%bP%wBLsKBCH&qB!Quk48C#f<k<Wa$|(D?-mW;K1SNut+57T=2NTlvAL z{wiZ31L}I-TTl5<?H0n$7Xi*^M5nt~BI~_V5<lIJsD5Sf_jVgMz1byu!tb`Xt=zyP zRTYrbd-8JZ^$*DpUeHSIccPvrMJ+;mk``=x5La$jzH3;%X^%FwyI&CZVKTG^E9wdg zp59&Cc_yUXhBR+MylgCrNn+KZzaC1~%DM*j8Ws}D4J_KUJTwK|E}Jw;g{-MevtqMa z#>O$R4KGu`QAwl96=}a5G>M$(h6*@Kql!(d*y(f^4U1J)p9zoFrwhEeJW@9*MwflR z={!wZ3}CE@SAl61RDjohO#XQQZnQ;ZrgDFW*R};Tz(py|ABQ?~PS?B^mum06J<aM~ zD;fMWKkfPjv`c1R7{}zCT@$Y?4Ib!Qm6>U?`TU1L7*{JbS}Y_s2qj)&S3GQJgwtMF zS6TP!YJJF1ZoC%2P1)7jmI8EnX52(R7p8IJIs=n|NMP(qUKnwmvbK;KO->!KhkPgE zFn=mtSDUx=GvRZqM#@veon9PA@SH7Y1Lk65EgX8Mjm!_NtOA0%SYrYvuttH!!*8jV zALax#{~9NZX@F&$`^Z=P1(o)F=h+KrYMYY%RX;!7<$yLWZxN7UmQ~l#0Zt=t33ZEQ zr_;ZFp&h1^Mx?)5I+KkI=0Ui%J!Px=?Eq8C{ann{LCyIr_B@W<wD60Lu|sS|u=$Wq zYWGZdGcUJ%67hyL%e|X|U<y}&{EOpTm>)yD7wyYru+1!R$(}oCwEU>Ge!QIqc20%D zkB-UF)ad~IdHLbHY>`@ops<%2s<StI9M+md_S;f@wYcn2l^8tL4VLoSSVEnp&tfCx zc`bKFA+H-nVd7lJ9qcO%{Myk5;*6e)rx@<D<owZ+gYmNYbUMOA`I<&BNbB$gX`S|U zIk#cm<6*9a7h_vht3(sRkU%t-Xzz%Pzn)C*TqBSp_HDC+aIw&$xVY}wSL#?fgY{o2 z;sa?cJEj6pQs3nQ%y9NT6I%)TXJ@<Iazoi$Sqe##sctJi0qHf|Z}O&XGJta<<mq4= zKT>E+e55Ifrqa<oo}q89{BfT4ocZi;gyVYI(!Fxit_{EYkJG=EP4#I6ce^G~){nQ@ zY$Q=?3o+bnck`EO^U?P6qWUrHS$E6mSJIJ&IsS(qEM#A*xdIb<3aK6BZZkb_t@&Xg zG!S-n6mP5C963AIN6YFlnNdakWfG<}!%>^48M8^g6m3xRIyr@kB+&b4i!Eg~vk^VE z(HZNH{}ro((wkg)oMn1W8*m|GxVU>nDHeOErc@;CE@F|v8OimrKQ?~H$6F=O$Clj5 zpRekfiSnDN?D%RT4O&R`Ae<3CT-tJ(S5-B({R{ac{)FBVE08ZDmZwAgDm!?LGAco| zYVy1xg1?`#9Bh2SDcf}HH}rgG0p(_aRYI*{IauyZNZv^3Sy`-y_IHoGh`sYsHtm%r zjHDmX-K6E0%KZi5<7mvCgE`yL1&P@AJT-`*6$_PG+Ml|@DtbZX$ZI2Ys>BJa$FD5Z ze!ixV&}J0#ouhySv!I=#uoi{RICj*?WoPZ2<WAf7Hh8FJ)GKkpqSQM}R27qVj_0Ge zUxQeM&wtO+uqL)?u2-aWBetY|RUs{f8`5U@6`n1^4g@WZ+a(oQXwdq-YeXjk^G~HL z46>``X5!Z~>|BfKW^c|iIdam=%1n)S`;0feD@s|MJDGsJG6v!_7c7b!?~p*r>|fq@ z>b}y9f!mSo1<tng?0SQ<EarIJOx?6zEq_;hxcZpMi^V-t>+`LIf?=<vMk`drQLlmt z+HhG>{%y|BseP_HB)t)~$nD!~i~}|?>^r}Py*ptH7g48nlz)7Gcd$)yw8B4WfgP<A zAJH>Uuji77N_5o>k74*av6Mpt-D`A7ac6dkh3Y7cnr$1Ghij@yO7JePwWUwCPlrCI zI|Sf0{G>X1?ZUWU8!WWZ6cx$8Y5Z`ttNP4vTQ^gGb>c*>PuF}wb0tpO?WT5}H3=fs zm+s<S-}By#n$FmG^0{|Kv4FpuoN-;b{BZ`|vje{VbSBQ%1u_Gc1^qUX7{i@z7G{)Q zdj`DQW7T1KbrU^!F#<kH077Co$!@&=f)*0qvm)*0os64N@Ub{$LaYM}Eg4Xo6=WwO z74T#5o^i5%Z66p4#5V8!1yP<Ap|%<lxN#*HJah<9=x2Mmeh@xynjI7LS*{fI*?G=i z&~3zoP?dewKmqxi74dEL+g6`NVOJF9P5?UwNxLtGAd6U(09QVxX_-wA6JK7)Tw%DX z+bL}t0fD_jf^WtqRI1-dEn#onWS;3KrtLle>-U~7@_#p$`1IB3M9qn%sh@1eHWs>` zt1Lr6fXoE0ULXD+Oo6u_dQ8B2wgOH0Hhi9m;YTDbjG0fp$?0UVavd;eaLEMrccMta zu#~4apOgszP$3I#vlI2~Yx08m;@de|iGCf<OgvfuRoDig*0)mB2X-tfj`b+PJ|D23 zS*&2wH{tNvxfB9ow%?k(Wo)q<Ky~fki>nE$GaQY~VP?_YV)0M4K3W<Z^V&YZZ{DGv zFAb9tgy(xGOCMLy$8a_G2C2@=4I;A)Fw>StQTtO?k+}X@t{|IxvyQ2Hy&S@IP9NUN zt_LB?#t=13d+*)=`BcIkT|OYd2v&?fUa&vpEpP7E3ne{}Z9B@d^Tie~+&Xe`iHii@ zc&BSXEmcKcFYw3WFM0pT?l|@&eeqwdANW6BuqYs<Oy^86&G)31CoG$SzHSpu-%k@r zz>@#)XZ=)hRnVIhO+#C2?%F7Aq*=zUFHL=$Zt3FL=kftm%D$f}({>^1!eZ*^Na%L* z;JIKJ)f};Sbfl7bzCim$Xq#HeqHa)-b8VH-#!N9|hv~gu(xO|cW9<P)RcaD8#0d<u zPujD7wZw!WG|#RVSlWy&^FK@3OW0aGhHUvmZpk{4s_x9FgWk3W{<$ESEQfZ>d;!F6 zaw<na_%6c^V{i6i>Yd9UijX)Q72f=WwHKCaaR;DfHQt~)H#Gl!P$hS>JEjHr`882E z$4WCBheDUYSs&Y#h00+e*JC;R6ES+;FvI`(`5>g*cT^+x1Hc~(f&SLW19CA|qkzlf zCICU?VBKgfrjKCn)lUzk{iwtu7U%%Q1?AjwHfWdco6JA3CJ;;eUx<_Vf5OCn-Y|lt zuBF>%IVgXorki;_Y$9N?Z<Y%D7hM@AV6-6!fo|>L@Bpp4Y1TiuRn^f0WX~|s#D}m^ z;cbtd0I|eoz-OrQ{}=Y~_@6lOO!McJu^L;c{2JZ@ie78Z`!7TA742)K05^w!2kVTV zP)&C4KU~ZIkQ#rJ*!&BhRa`aX*%!G??#g?7j|HRaRJHrf@#p5VL9<_*)-c-eF@U4z zb-e-YPWt!ZgM9VBk=NA<%zh^A?UAFq`)x)#<s8(k;%TAs?@a%K{u%IRQjH^=@)m$~ zCSZ5vQ~&uJBnTT<*(C7*>N635q|ll5_%6U@{r32SQr0?c6a>HGcc7W&K|AcijfY-D z>ymOBAG?=|fg@(;6xBsCN}tA+Sjc3#+{P#Wps?;QH6+;LWKW(lO2Q3#;kJk?FLf&` ze=ip*!3b|k-*;zPPs}(sOKejBPSEF@812tiU^PTSLspqfa(UXb>}U7~_e`ebkW5Sr zm;tleFe5aC!GC1eN>gEgaasGq{x;I*ocf@X68b_krsKgR3{VrXO}|ESx1CpV9h*xp zQ2!i#j-P4gGXl~_kj+P(=V8>puDPy)&{}N`skcOs6J8c9T2}>G32PDl1t`4&lEpvS zfpIua*K>!XH|zF~_%4&fg;w5C#+#{K6N8D*vr(p<KxNOgz_1RryGVZS;kusIc|F9m zrOJF|%v#UecZ8=2Fa!s1#8&h6lWpo1gXctQc#Iv=83d(@h!2W_2(w-<Du@Q!e<!-_ zQN@VhumT-YoViv6Y{LA3`hfL&QtycGUY{BCp8s&OsATINFZfGd9N|ZQd?h@BV!ux6 zPJ7WfTV}M$ASx=VXa=^h?F7%B4jn4myvwX1I0<zu2x%;+pGho4ry=&o=e0@Fgxf21 zh}0Exfr<$j1aKVdN+YVV%;=+m4!YXEAT!q`4*c&zTCCMzr+Agu1&b$!Xxrj4mqn4! z9y=Ww>zt+_DiJLtl*z0P*M}3#>F=a%b3^>O%Ww(VV);-z@Fy0<$`HKB3j3CYxG~bJ z!{m4;ca`ZeX$gP5G?oLsU(*4t<3zENm`YTSdE<n#fR(knzmT#+i?z+$PM&vRX|Y!| z=a5OZn~$BZ<Bnq9rR$QyYf7#?)}Y&T2~fNdFl|p1ChPhI)_45Wi)Am()sg4!_QqF} z<Lcx?uNKfwDbmgy>xpT+=2NfgLWLm=vJrX|Vq1$=13W)Fo<G#_ekP_$7c4<^tsgvy z!qke1G=2#^c_7|54MC!raMZ^xx0%R8<>wZm_`!m>VH){*48cZp{>)kC;`zydXcnhO zzj81hXY6Icc@oCK2UUaUDE$2PiRB1;Q?0xAgbe5LA62@RbO~$Mt2Ym<->SpFbxV)d zHMHrtNL2@H&qgfmta%q17AN~W9R7ly!0S^;WnPOZn8c`9&;A8P3m<(uI=!}$8ye<G zyLCvM%l}kt;JW#nBlO-L!`-UcE6=axULM{F4(DY!7sy0NvXX|MDy@j*5yMEwl5xj( zHRkT>wkd`3VUjLm{P_2p)Y=ddM4rVu#mbT*&GBKV@hDUCss^;bq=_N2vSctoQPaK7 zYL|%WVV|doO!yD{c=Tjd&sR){ZI7<Z>>Lk*=Pg_2T@@$7r9gh`*T_9p#(Ib}nu~mZ zE2aPTx1mm1BtiN45fGq9>-)i4w`}S1{%*NIt-_$}59*ekzGUmgKbD=*8!--_DDJB_ zWyDhxgiO^ER6E&r)$9g7@47Qm*FBlpNX~9zlX_>Aj5948G=OG_P>J%Fnew#uQX9H3 zSW=E`8wJWQTtHFkFG&7e$*m{*u-t{GIjBrsC7qQboUO?yY*a;PF3}n~&|7d+u%mka zYb+l=900aA$^NrjsasWK|G(PhHy|@^;C6XQ(s|=&w`JquYby$r)0X~%08+Ry-X}Xf zXqSk}i}zmVTbTXwia2vD$@+Dr!Wxsdj{-q+$fh52xGrN+&f#tGFDVvJw7y+8MkCYu zRh$YwtUZ9bti@ju{3wWMn5}cmXK!(?X1MyTcAGDyt!{)fH#wz`DfPjZ+;Dd4`HF%S zK<op;=wB0H@1Y9zi&1q)`#7$dSFtNzZ}jjFWZoqfaufwJz#0xXC1|{*D;0Bmn8d2$ z7zV75BSo3xO0(8y_Dlk-7R9cOGSXbd%sdtrc&=C@F@p#i1@_XYjrdUAYcp2oDbMpS zdae58hJ#K0{5q5HETNLa@}`b3gi7BCepkz5$U_WgmGh#aEz5D0XJ5ug@;@<j39srJ zqcvU{ZAH<`#&Un?_u=eL_!E2!{k|rljkjoTB1vEya9C>z0PHf^h^4;TKG~1sxNA?p zM&0{DY^!<`UqKJ7(sdAgy<vNT=J+F3b~<8bGAnswq_5iOy($?{^`gz~)9kzrqd9Kz z^HbeEr!tB-CV><8;NcEMj5_KXK>&~=tPq;L^HKm2DN7fK|8W}MYH%Zi_b7-LD*sN` zyB~O-Vo8wRs_x@G8lMa+fN6FqmWpo>O?2~~RX`GqwFgHHb6-s92u!ajO=WS`=?E01 z=XTyHnD`6g9h1eM-;%Y=Kzrs2PS$7}*I3aSEk2IWdGqISZsC5O4sNs3q-XS55=W_s z4t(cGo3nqZ&==qrGkI$eVk?Jmau_S*Y$uwwrzHuX^l0T%+WVBcO1Nfm+iN-HFDz@t zap~7zfN%%H4@H{n(qY+T1I-ZDa_0il4jGJ*?f4n}>CabLeJ#c96~C_%FmV?#%)JzK zy_0m?Z?p|LOjLh3s(b0z3?A<fCqgI?k`+_WM6-u%&lqa!<MQO(Pv2>~<~1Wr`7x2Y zA2Cs<uE<!6^zZ4FE@t!3zUEo8a8SgR)KUo;=81aTzI2_;bs8RHkm6=>e!M(eT!Wia zrkH}Q0cR^JKoP+w;(ofMiKdzhCU%TeG8~e45Q>mJ{1t3%if*lq`jtNPB#qtN!_oDP ztsDwwG#@;%#&{;|25@{UrCU)+QLD2~G_#YI158<S$%{of-#Xv=ehF+*_u{DM@|Da9 zO1kHo@(4|1#|lm}Y-wxH(y99%y`tMpEqs5?={D+zXs)KA7=s9CundBaIx)hm<}=@< z!*nrlBLo?htxLXeOH8ivr;SRNMXN4Bfv5H<RoSb9beGWf&XDQ;dm-2T1_SiAZ_~zD zHHyDhj~yyI>*%jO6Z7z0S<rQCaN(s3zU;v|q=3tHiBlaGjN%1G^B5}0Vlo6^&eLCP z!4=;DO>&zO-KbIDW7|=&UY!UP2Sb1R=y>3#u+FOsAnQ)3)MteSlemfv6k+6hx*HZ% zdKtTXYu*OfHzdlvS@QmpDwR${Cg<^oC4kMv{*yejp!Q9c<WZQs=018Iy0E5(=8bd2 zgdn+5H4*;gJ66t_nK<qlVXm1PhKG@ibPX+PtZN>_Zj_WA>c!V;!K3dqdsG%$pJ2+b zWwACYB#LI0zgryOnMoeo)tPX`+WrE2{klPtmFA2^YL+M6l6=Ll#HEoL*BrsWI_Wz& z-B|cADX69Mq1iT8gxuNEFf=-twF8y#t<qk2y`v+exYnXb<weMmrxZOTJoQo5;AYl) z9}{Pt(2*5Q=jnKRfW7z3X;_Bm+p>{QZnITdIMd5_NdShU{+fyZ$6F0f+It@tWnIiF zh13PW5ixJR#67G2VlY`4om+al;+aILZf2EBQ}-L>K}SvV*WYV+%6H}geZR8so`FS2 zUh#@6dbbfTyxPNa7B#5yu{9ClC45U&H!Bb%*s;5fWdu%l2+cUGQW+RGw{c$T_R^(P zJxI~4EXIc<XW4q-e%%wgWS#C`yT!dv<m(~fbBS1on@<3=oVdpH858Do{Y(u>tbgAP z;Fubq;WZJjrZy(CC8+jMR!gh<P3i089L$(l>eMHAkKe<+kY0=RKcM7i?e^+(9aOvW zET7g}2{QkJ%oC4vwS``WqO0>(X)+n1r%7=7*Ct|BECyO#_XT$p_0~O^dN;hqzsQc! zMtkKKy+sZV6G`Se5H=n#cSw!G+%m;|p$fe?kT;D)B)1xC?#5OQ(%YcgvRZb|=-iE5 zL)OK&<)L4BjJJu8c#YmGLF4DSa-62c03@hnQbPdNKlg7(|5E11{6SgaD2$jZExO9) z-Ll^KpQTfHYMXF1WU5Fp$Z;D{<}z>IRUK=E<@DrJVG3V5A(J8-EaO{PiUS3BYG^XY zAGtly<~iAnb-aEQ9`Qu8NA3j4MRk8~+muBB)n8NN+Ce`7$B1~HYEKFq{t_IJs!h3_ zLeG(6s@3y_v~?zs|7T6Fgb<+Vm+v1V4=*<)x0Fv`E-YDwQv}Af)*DV94%P!lF3x_@ z!c`}sInH0qJZT9oFWv0YGK<QF0MeXmvFx=8pV}VP7y6;){3}<9V1V>-TTyIXe~IzO z6;@ex;!KnX-1xj>qN<G~&<lTgH<PAcfv$M&2VGl>^U-0xY-n_f2Ya&DWr~u*c@BpA znlpHU^}&&{DA?@WZc;N6M`KO*8Lc2W{s+f4BV3e60{@m;)nG=0wr;7Ko9g4u+mdSG zN~!snZ(pKGdsxFj<>KMxkh!vgC)ROcGn^mg_He9_d_4QqD|!tsybM%A4ir^tAWAc5 zb5n3D+8K9<lH!BG@;}2qxD*D>7HY%f2c{3#<l;Y=#Kzv>N3|JtJL(fL1!X9z%j?9Y zdOS8TOX^_^nk;pe67_E#Jkin3x*AQIEM?3?&k9DO)ACu`Eo+DwR#%P7yM6no<9DYr z<P6`G3Yc(g$!Ac#9F*fP-EWp7BPYKGL7t*YyQ46CEp|Ogv@SFg7T~PM-(4UH@5y@` z=1Rm5kEPn4XXG7^as&wN)=9O~b%1oyUK>>fjFL)LJ<?FBO|%mh@Xw#yO#a#8-)n13 zQmpUi{3<m_Gjye@n33wz>l6FiLhg1>6EyUI42|5#!t&ZNo?5BgaWTBC13aV~rw+e% zetN8TZ%Nyy{1JcbhPlv*d!m%JwG~;$LEbj1Afb~;#eO)!LYW0)zmfR~p&z^0-gF(D zna|N4sYKr~Mpd`A8|NW^lgO?874niRZ#%*06LHN!lh9&Z1e3aMcb#ckQHH+rY)ijk ztXUlFfR~7C31+3--ARtb%w{N-k{2Lo>+@7x1gL%^%Z$tEbeD{43_An~?!7UlvK8>I zHX|??HA;k6FbQ`aNB}TgCQe`m+Tb`2^J0Q_D=uQ=O4_fi)s<QnR-9>8pVY48T(S^< zY%IE6#AeObn<86?9_|lRp%lj6LG5gKh3=r9UgT71q}2Q|HNC(wPrObQ=KqGQOMEG0 zI+-)!UZ#_Z>f>^yq4k@=5={!LygZ7UyVCE|vsDni)9vAjK#QjMNb0_QQ<qu4E}5zm zJjNA6r8O|D>CV?(U4GUXu0q~%f3JYLgAe-{b)Hg=RU2n(fx|k{ZxTFSdN@0JC@)g| zR6ryv{NjlJB$B<e<*>wXwMQP+vkm*6@;P_Uji+e0n~Fj=MZM2YTf;Rc&0xpX=y_uK zCPtsWJ73nQZ_~o$siToj2P;8H??i0hWcB@L46+Px6A?g<lK$|t(zsgw%z@CjXR=#I zvfQ-N@F^zcT6xJ5%Y`m!M-L$H)*=NlScyRY_kra$#KOuwL!la)jj)*TfL{h?kWWI8 z1~~)4$kR1o(4rBFtQ!fs1Jd%Ek!LHmL;aJ7#3A<X$Gb*PsywKcs=V7GdLYT5@S2}r zRPl#!;(zR5n!RM9jV!bn2Ny)hTf{(=o_rAtE6t)w(S?pBc1^qN=f(I^G@^}Wi!CIb zgCizTy}%j<l-2afbp5Zjz`;Xnrf9`+P1-1bXOYxH{{|v93t<M0*A1rH0p(Fc6oY=- z1l$bmLaQ)={&X}rg7<pV{IQrRv_)rk&?rjZ$HKR@-%=JQhG<|E>q1G}rTU22tI?{F z9U%30{k^BI@?1|hhyatooWhVE!)gIK%y_Y$jE*r1JqZ&$!H%IhyP(u<c<Tq6{Xn@! z@sZoc0t_R?_};IlfuDHk*M!?uB{A5uSSz)=pD`#L3ajJf9Pxea5X&d+{};rFrA1So zo7`l<f>gqAjN_+nl`8i>)%efUhcfEcm-fz1+3AMV)_CEDJWU@se9CqdZf9@GRML-8 z<`3(W&S%671I(2_h0a$d?bUf_qj@jV9&ybE5SQCwGQpPg9BaZ`VOCF2eUx}UTxdN( z>ppIuHOjUiG=7(5LS{QsIH<2-v7}?ddcj<~EbgbG=*w-Ph7&7G1>M^ZTBI|bG6Ewz zC`x}NFpvt37>(Ev*?Yq(iuteW!dVqPbK;9KcIbR<k8(26dcI8sl@4;F`hClfqJK(2 zco=D)$;I!T7)8iV^bY#H{66olZWmC(Kk=;it#NOoyixiW(|c+0NQ4Sp21^sy4XyL) zZR%ih>m=bozb(+q-e3F85Z@5G()a!NGrtesiOQ5|kjraR7P}PAuTQ^9h>or`m?dI? zE7%>&$u<?>Vn&G7XhdC3RMUI3DJWe(O@@6GrzaS`?*2itao6OzUn4IPx>$(FuesI@ zp2=QIXfs2$R?eTjw;yVpg$I>y`+3?CNhU~0My&Bz&?j1IbJ-6w>~#nR|A10Mh^UjI zmC0>J5DMBJ23tA$9(6?@H!H$YOKYjIafv@RVJDUu->I6}VJ1rxf-+01YkJiCFy$nG zk9=2AdA;RS0@8Zx58@^@E`3K%a*OqSS>qtBa8)6AU}Zb_w3s&*`l?_Nx_%KQdM1jG z$*6I62)}7zrZ}6~jQ1PzHh(V&fMuax&Y8+ADBAd7{<Ve6tW2IKN#M&2L*ad;7}>GO z7L|FUE)`f-NR7Xe5t3x}i_^wg{mo1R+}9%f!;Uwpwh6x6fkkJXOdk}q0x`gZpa5Y? zoDQ0$*^ejvI<zRHu9)Cuh8#8TK5rQKWB|v92|>8kP=J$6v)`6}`gk|_Al@m$VE*0( zbY2GWthU;Xp`e?U!g?^M#Kz@Fh}>GthlSA8pkRZ&CCH2!&3pb3(*q<PjCpM&kq%b= zIo8pu9{F-VAnnJ?X@)bEg`V~4&U)pLO2{irvkyt$z<hkbdE|2)Q9~l!$%D^$suaNk z%JfOyc2vsj7|Zc3p>MrntS^r7Z0}Uzeik%P&(`?+d3<$Mw$37*K$@|>sU1MiHQ{<} zxth^-2@roo`6zcsh9_CAqo19;TW15X@w-&pEOw!lHw+cBjP2^xf81BaF@O-kB3OA$ z9%`(Y92|tmXzw+v_T-M>Z9aL{{p_J{Q0&$4`gwLiUFp7$O8hrtD@<7L2VJ6<Cr8Pz z#QuWt^mF#kYVKfET+qbl-8Y|MZg$b{dRtPL?f~===a~S@{y^$WRi;#0+#Ne3tQThB zn#Yxe$1akU^8Q7jJV>Bn7OlJ0t@T{PC{z^`^!zSspBDQ~G1P&PEPB?JYvz<o)R)Sk zu2X0jvn~bsGFAP)7A1%%*l!cv#5kb392;@-Lbj6#ImKoxN5V_Y?XrP(NIm*uqj;`6 zDb}(yf?I7<sNafrfQ<OK^jP*POqKqsSA5y+9Mz|im3Qyf<#RPYn5hF>@<Ub5vOVjO zyn}J=zV_ni#%3QU2PXjvTDK_2#VUPUzt+=lVZ9B3Es=0HdwX_`94(kOvl;g*>7QJ( zN8!TOU8s)cFMF&G-#ZdsHnbUkPdrq~_EI9n!>_d^Q+$4B5GaH*j`pt^PrK8YAKkLj zSB$6s7{X@)LVA+<tWiH(`mxG8!vjmTY7K0J`J7vrv1!r8B$7=&J=u#*^(k{>u-x^= zq%Msl8H-t|GdCLxu|EeP6+r}2zH3kB)MpC{bC%pvgv+wci$h}I#%Y6>I%ixQi2xth z6B^mU-9S!X7)@mH<7Q`Nu}@ohneue|tNxv5C2}RxFCOR$xlqL}oCGpK3YQ3utGA&v zJjE_Wd%>KM5<+{MxV?a_7|RFCq){%n1NSWIfXO#+hefXLE^wwy>Z-<?JRk~JT|d5y z%zy8UPut5NJP>szC)rxU^4eXk)PLv8sq)OW*TvXudz=;O9A0iN6C)~Gm`k{jX%kLw ztUT$L*sOH<qlOvU5ex(UZ-cxmO>C$~=iZ7+a;20N;P8^H*LV|DdQ9yInB*y%0p$5V z9Wel(GInn-8EuD+D!Jmth4SIc1Fi_9g+P|yy);}087>rFYyLlD1wn%N19rZ1yFfyl zu-EK=(*r>}|8ZlON9kiD0A+QJA3(7e_NN}k@ZuiVLFWJ-H(-ny3ldc6V?D-e0@{j% zf3d*v0o@`Qm{2*D`b??}v`oyPf{mz#?ro`@vfK1|U;X<8dOfhA$FnWfls2-$c7Hxt z{O##~NTCXV@VI2{0tJn5UW5)5*`19*GqhFd?NCw9Yo|*%92u%=uk(SO^95P)LRGLa zfvcBwZqSL1lus}l(D=x}&704}cBoIl{bwZ#hfzUlVtFh(FJ1x_A2Q6W9u?l?yh{Tx z@eCzJbUMA|$2s`;Cp9`4fAk*WsCz|9((4|0_skth7dyL^Y5eGSYozLVjUp-v8)Eh! zQ^sl?&;d5^S`*@oi7D3p>V{Kl)74I|8ehnW)*^dl?8KVzR_|sLN187=VO<VgrA<!l z3Rw>oi(UKX^<NVNCE}ifM$rT2jhs7E?ro0sPr``KTYcE^cb~c84*-byT)$|{ygohV z%eSwlLrW1$bjq!d`n&;8jjvd4%pjVwn>H&AY}6}Ss#tp`qdLVGsYJT&CUD&oz>u-O zn6O{pHuZB-XZz8Km>h3uwIi4nr!1nfY`5)J_?ftq6rzVv313WK?EE0Ll%Tu~Zfkbb ztJ2w#-FhZS)=ztJ>?)%y)!vc0XV8)(L%G~=u+@?;X7&%M8)P`C%!Mg@G`&76nG?Oy z+>oq&zbs0i=gXcYPU+@z2M<=SIrO4`vCXXBie2k97$nf{)8`}koItM>bJA;B@`bv% zZ>TJlto|tB;V_Fl{?eXhg5!|~bLFlKH@krSuMZh)n|_HigWy1%nknE60hn{x<bgDO z+#5k;a^pl#iZtPmAof1UYN2}T?#h5UU#;_v6~&bzrsGG*l>F(d#3P&%H&8dy11i0* zYx<I?t6oXbeCEnQ^s?@b`Uafz$pJUMe!fN7&4%ZrRve@n&$O6O;u6;FRCwc!y<-%E zj<XWPPLF#-QJdwwyab9S>8Q*UaiW6J;e-JS(o)nn)7B*@<|65)3tNUSgL`nmh|7Vl zb>XO>-OPp1DX(jcN;lm3GpXZIui2IQ@Sn^$)+~H?y}h)My%9}-L7iE1GY>rq!$}$0 z0n2q}>?T0U@Pkz6#(%=kTgh%v(EghFKLPn%4K`*5B-<T;b~Gg92co&+22h2BG6eS) zpjs7uSPw*zdn7m-lt$%W5QRgW!SQDE+$(3NIA1oQR}st(?sazq!pX#*{FFnRXM=Sp zDwVR3n~(w~pG1=%)?(44Cj^IvmKuNL2LI4$+`K+LHuHKi23J{6EBG!G27T=n62SUE z>WJ_oAT8^Bs+;s+&8{*hj@X4xn>0U;%X#+NY)C>g9=6-{X_hZE5X#VIg*GIM$%glb zAQ%B2Cy%VKyQsU=h^8rUEg>EQu)p2Ds%piu&mrOHvi5>u?o#l5FTdk!xGyVR2dyPU z8wFpc$viJKPwaj(S=uJNB~%s8`;m$@UF`Y?jdg0fmaI1c)w-`OcP8({1f+rN$>L#- zm$q<T=IEGK$LrieMre*A9%4lXVaqFn@OYWDT`FI0Tf!nm84JXlFd1`-m>gLWX_RsS zVsOaaTD1PUX1MYLXB_>6<j6gG28Ce~m7c3OHIlqv7ZgHf6xNJyjR)`2+Y~0H+>V}9 zJ{Tt>yvc=-p{{i>!&R0p^8Im@RuIK0I2koYL~xjF|N6%3SL`Z3#h!sjIhFL}fNM%s zq2qOBj0v^P-WnFa2qW0rAwNCUhwl1f^{DF4EV&gpb(<@7^6J%;n!Wo6?p6hOOPjJK z&0mnFNJP4z$~cq^NAo+F5v>^`dNjUDqHhkTX)#`XC0YDtiO-ZqsPZ~uURTypWKx{q zj<ppKJ^Rw{odpj?^-~2uaP$d3zm4p0%3)gj`eyoN8f+N`sZ(kHgGq}-HQtG>HY2ia zLsLD>Sbk|5?sAMUrO6<i-R?2V(@E{RHhI)<SSj~7u)E&`m64=;lepG90a0v6i}s6B z|8BIEMJrb;otKxo%t_ZtXE>1`3%i?aWb2Kyk%^!5*meXeXdNuNX3+%m&APutk)*nM z>k184?$I;~p6hBR?8G32)3$Z$yT@TZoBczpjy)e%SOFXn!h-SnqFjKeChoZkjDodZ zm%nLcR(;%H>9r*CH1WC0pl6Lxp}Q{Zbs0#YqJRQz_oILrd%y8}D@GTsU^P=CT(ydP zK0))l`+#A9!+Nz}jEjKfwHs65!;w$-wW=oR(y;>%UVx!--@!54->vIf!;Nifh9=KF z<@=voR|p(lXgBZC2Rrq(DJ6qfdM%LUe3K(+6Nj*_4S?!6oLxc@Av;sGXHc;bzUf;k zZ|*YK9qu$@3XU>`16V{-)$djIDfT%<r7BBT8W}b?{48Qf@BR-lL&GQB)}DsqMD%xC zRKlT@Qb!9tHfXax(J&RVHr_y_O;Ar|DPSAG6&mp5_~~&ExwEyTkK%Eq-gnPrbrx+g z&Bi<o-g*rSmJ;*wTOYdSToui{6NNRaw%N5*iC5(GEyIz2ZwLvOo^ZxkIeVBIiM@R? z!B~{5_el|!;tXc($1!7KHku$N8$k`(vld*@M~|zSQd%`R9xB~y`F=<$PIQ|Ro7Kl8 z{1K(>BY=_KeYqi7Xr!&)?m=Jt)pOFiP8(Lx0@pk)rG9N~v`$7nz}iD!3hx=qs7OC@ zELuitQtB1ctO;N8vRE89s|R)L;b?FZ9UN$~m{SGTn6)~yK3!%N)%IMl<A6rewf)m6 zUXK%<3z-MePY%od7%DHl=)G4hT-cS(1QDW(VTLIEzD{NgSr-clx-^ua&n*HrX=jCs zhR5pZx(gon+?g8jofCd=PrW%!X3{Gm4F0Yl9P986EOL1Svq-y$X)xz8oEZF*Ot?vz z{D`3D)uXc`Jji_%Z?rPQ7`ncvgDdPgy06O1C(z$1NXW|pzbREKo03gyd5|b;ggnwq z^c9V25pJuCh1+{O(9nxfb74A7cR|A}YQZgQk-tOVg;vf_PTNnmVM-5xaxr>HJ3??_ z-Zo}`j5l6_0b`-I&_fMIh*7wDC&<fIm}mPG^Y>e0hkQ!ukBv<@O+AC5sHpS0n-B>5 zx^BV3MHdSjnv0>mLI=k+eyB)NW$Pw=fgHYm(h|C~*epZLsqxLPo{b|fwn8q68f!2c z%<q~l+QTepgnr7xh<41mTTpK0vPwLYSYED4Ju}%;+I;+|F4i<JCB8!|g__#tm5Xir z5fX5ULX=@8HoPJ`2}Im!5i*GuFJYkwaexo@zyX={+&OXcN5+%qRllN-wVH)EQ{09i z%-8G~s~;+`i%6B%or`2@P!^X0sy5mRGMe4;_daftv~_wSUry|L>JR}A-&60t7-x)L zh%1>9V=XB*BZ(@H>O*o$Sxi?N0#zXyhBt1_CgBdx#M-FLM5XkDy&-K`dQeU80R7Y* zD)d4;AA)aN%H>(r`woGeULc`I;A8w#ULh(@qM;HZqpw-88iwz2CBJpk$VE#T&vntf z(TcSGD*a^9b2vg&UivMB9>I?b57Mt5oDcOmY+MN$v_54jL>E~J*WvMtt<c^>4nVlq zj~1@`3hFLma54~2G;fq5IrCA{(Kkh2M5W8Hjm2O|L4BNI+GjWTwR*(P6`l-{q9XIw zPdf=r#s(_|m~o@Amu%q(N7R0833=LqTA9sY(ynop>0DZ6Ky9+9bxRWKJ==Xtv%138 zT(5=v9(CZIb>h(6ME>?6pl7;$i6KJa_pi!CZFKhQQ>pu-B{rO*_J#bRk#h|0=i~ES zdJnIk-r8Qp_j7ody$V>=2A?~<-D<tI9Oj|Iyn7?gq@h9|lRKHq_2r(gk?}#h)}WMr zzG19yPC29Vbo2Tueb)U=WhSGjnLo!B;5T2w3bng^OAWnuGDUoiih&fS$<Pc}{~f-u zOvxRh<8O@XHfwz<@mCROpcoQ*s%NAZc@XH9Pcsu>PLsJPm^a=R#MUgmIUFt?j1lbH zW*baC4WzlC$s%(J#P1V&W@uhySQSr7$aYMqR5=0B1-4*T(vDlh$Z8d{aR_&nohw7S z?Y-|Ujm??(W%_}>4bqOpgj`M8oNQV{J;c&|9u**t4ms4(K{2B8C?1Mx{R?t8hXdiv zwxUz}>ruV9`;(4PvbbwEul@P`Qj5>o8zQMz784_|iW(vI1?~pv<D}lE%FyHGXB3$Z z;iYFfo(~Lt6ErpRiZXWjh90J`9IkOI4=F*jvDQ~2oz#ASxk+pjMef5hZ}^@;dC1I6 z@2hg1qKbigX{j}a#vAgnRQ5ENuQLeCnuk{))*V7~9W1-JTd1Q%e-h$r!~5I^Vc2mU zdW+ZioR}0fka69XFJAT7!d|yBIm)i5Oqpt7h0x#XqsY#Tzux0RZC0a}A1D6At;31; z>oU!}q@R|N;_=h$Zem4|Kr%80X)rAeVOPA!JU4n;yVhSjc;}bc5XZ@+7FP;2b2J}w zriO;uJoR**?jGRW+wUP^R3E#&h~SAutb%)r%6jfsl}6sCAXI$dwsZXJItHRL!WsU{ zx#3ID<9EmXRxO4z+=4vIUi8P`=IjRF2GXH-BH+&6ffVDF`UFw^hJgP7oWWnIO3q}u zn8-%9OGGE7{F$%}UB9Oxg!O==&}9wo6#k|@s5k=S<boLCyjHZep!<fk;<^}L)CMn2 z>pGR*<Zo}VMZ0H1WezCaZ_(M8qNmQ^VLZ_FkI-B`=HQ?nTP9RMl#f&4ZbJ)s!k1}I z$L35g=~@2QZhRJ-G3&81j@i0nX(O=`Hv0Vu5{Q9>HfpjcWoAtG=)iN}q8B-IanRBd zM)lywlh_Yj6cVq%8(CZw-s`DFe1#j#w1}u4n^(g<`J`xv%#4>+R8tU=jrW4uA(2rf z-v*E1x(#Wgj_oEVFSPN3e59s{AAbC04K?u=Wq#dUSR6AX&=~7EqQE~@$~ZDq_|CVl znF~o@6RankhKpbKlo{GZHQ3}BAS~(CnMgS*d$#7iJWQ*Zq`ps<^Bbk}Yc%k<CRmvE z&ZLEf@6BwNY(#xNl^SE-vn=RUSYyP>pri{c*~VX`b!RumBU`7i5>zhy5&lHxO)oCe zR&Fv^>FlrlyM+X!?<|G`Ov4uip$`^=`*GALuU<M)QIFNhpwMGi^-M42pcq3f=G$IO zz5~9Kxk<7`IOBn@yapRb(H(@H<5)4#0XvF64TjF03mnWceS=;s#bnXMdd^-p`I;Fo z`TfW>p}co3wlZ{zC`y39X0n(Qmw<~`{5k4Vu=1@`x65zg`t0$CZ$CAWKdB-b^&Kit ztxR6scFLN)>OL=Dl!<K(aB*>fy<Sby`V(-fSG*67OLkhOjjHax46r<YN0A{gT`OL; zy`_@`i=@b;Xj@Dap6ZzaSJd1thue{x=JOvL_fAI*uaUz@%r>Ipidxa_+tq;^V|bX> zUX_Je8HxofrS`njSsBxDUCPm?nW!<!LGp~uK%U7baZZ_TI|Ud%vI7z{<&&E{tQi_< zjoO-~eK))Smgs58Na!f!$#d|Q853@?RvfLp^e!5?2dm~7q3$jdE5ti>ikH$0?6V|@ zm0F8op`SKHTG0*|qgIp3lxu{$Vt>{XedA3Mg9%c%Y4bN8Q<z&i2VOo8yHo*S;D<Mb z5Pb9$k|%2;Da<nei~suC9cKfV#n%@XM7)b$OhjJa9#ovV#2Bt;<ROAG%+&|dSjT)y z$)|pb)9O$FS~HKS2-sGrtMx>x=YjU{r_PwNl|~w<=F7UL4fMHg8{dzMEi>71SGt+i z>XDTUyTyndz-ax|u5rGUpnSaxPo8{oQr!F>(_qd98!H2{?ZM<#s~6thvRJ{XU>4js zl&*u`#pNs5eju>ZJ|>{Y>y4>N{5z5!wjjs0z3zfz{J5KK0C-7oF*^}ECvZXIpGN?I zfT&KI8d@|-R6TdN!7b=<tx(uRLww3X_VMtF#$H#WLC;q$BiVF?v}P;WpPY2R1%sOl z7y%-v2J6)Zz(-{OoqFJ(@7@$CD!pj&uZf>@9)C$P)0FbzDlK~(3%%CH+F}Yg8WR+s z&iNENun9IuDSrXrh&Rs(iXdEo+?}<X3<BXt$VnpQ**-3D;81>Z-YT23!UGX+TFY0r z13%?!3hlpUN*g>dRwTYS434>R`|_EDEOJ#Ct=X+GoTs*N5iRoO@*9#!F=d}Sohf7} z*Vio%ZL+dVJI5lLe`u9+Jsj%k*zB=1>=1)w+BD60jTytKB5|!X$C7wfYM4C47>Voo z)p?9RbNfowS1q0=avIE6vsp>O%2;j8r!ut)@SI8PIfAgQX$uTu_sjK}OLdF?`a%A^ z!hkaStUsW>@U7r&pgBZ~&}meFK<68(SEf0ZL+BpLT^TN`I!UgdM25|aeu)cGLtuNH z8UVBdz{I#-fFvH(dAXQgUE3p`6O&hqpOrx?Q{V2$2jx@(=p0OW`gqWdDuM2!;4N`G z7i3CnZqU>&i7xI@BkLL94|zrO`F<~^7SU^LEL}L1+{XKJTl^V<Hvg_Ray5^&5Adex zp-sD=IfQ>`$hH;ijUiAZ`N3o+st$TXf)?!cHHSLsG>p;lzI65-OiRTZ!<TXgt7yJ# zx?E8F3#ww>urB`JeCrRusc(aHqVrGV4VD$)Q?oD1+(-jvnqgQ$(^$~9NSkh%OBPwF zl~AztefuQe&2?{y5eXcnu-)}{z%!Bn>zWDw*OkK!+U)=!4gsv!fLlR=vxW0{Fgsk& z?m5|xZr*<uazLVTXmj?yqA=jHN~f}JcSZi0u=D@k{tjGl5F#l4=gR!9jJ{ag>N9Q5 zrEwE4%u_h@5U7hlSka}JHQZw#=p11BIi6ixhHv$6-&Q|r#;GNk+wWtJu{BvoPI7xU z6V_*MSnm7<Wz}E^a3iX~t@{7ode5}`XH<3Pd15Br&qGdSm!FHi@7wPf0KZJbX1INo zi!OkmK83EqhEn1>0QcNSu3P^{`)<sxN4>PVg=-aWC7hs{O^PHv1!dGxmMqi&vUAD` zpgrRZAAq<0fA7N2oE}TZJmOtxoYyDMNUaNHjV*e5<g}^NKbYm5dIj)h71_hJ7yW0| zd7t8~TK<2ysP!LodS>Z<cb8Vu7QwH*L?r-#4d1rAA`rd70`|Vo3Dm9aqE$8}eEx!L z1a)zgpP;{)IxkNCf~pNgBRA%#T*m??azfhrDcPY+;{*!oZ=k3!08|)P2avaUVEif@ zcLB@O&vC$FsKrU*Idubms&-eu*GA!j1!<<r)L#41pDFKLw)K0I7Pxw0d4c6NE(bl@ z`3tiAATO|u1=?lxhR#V~|E!^MhXLmO7O?mVZd@S&dr0nU<6j=XcwgL;aZ=oYgZ!q= zfHy`c)p>K<4tJA;F2p@>gI*DK-dwXHRUcsfi(*z0vD@9PS!B2O*~u$<xD@Yq^z{E6 zv_<ekU<&vF7_jojHR*qJE03iNVhXKu2v;Q=Yq#=2HprfRCJm1L4NTL&LxpyecmZ<` z%zLLj))}AoAM@9}J8g0_p{3@De~P7%-ti^)0ec1SlKy?SfQyM{AmG}X3h+L8a2nsC z8**8=5McOFm8<DWB)!PICF30f(VteoMkV^+J->U0dII1{{M#TfAci$uC{Vc!9>9zf z$o<#10ho&azN50F1nv))`1(fmTVtQ*SR+7hjLj4PknvaNDXHBxK-!-z{2%?I&j!f& zk>8+uwG|l?NhIpkc$G>^8lK9&A>y=3_1XW&Y=5~{#NNe(T|dJ*jVs^A3OB&htkEP> z>dtd>kLlQ-By456Fl~k>@@*zZ+}~s;{MKg-fVHedI9jaG4bV-eJk|}f57mchJvh1s znseRvWg1Q``7XmWsV>>FDcen-K7GpOd;U}Zu+T1R>j=Y{wC}P(w!nDq*?Los<J=V+ z01U()>FMkqUJ-j|OGnYYMGy(lde>{#ZCih*Gbb-J`%wSxFQ~7KtWVF^s)laOS%$(n z&F0a@dl?<tIiMyqtL+f0J1lpnO`J^7qy8|*qpil{Vf@GzOrKs_Q(0uBnP=HMy`Yo3 zH6zEs*5jMiP5N>R@D+=d-61y{D0q;s_pF9TGjn>Y(m=b$Bibjgkk+w=msTS;+b3a* zn`h53yyYk&Ujn_BcsS7eUeG$Cjoaz7a`}5Vs?0I!zMJmSPh^Xkgu0i`LPHXlzdi_; zAWohPj6;Z#WB0IHs4GlP*VWgRMaG!wl^<*al7^DLocJpiT4RqN4(TN8hl8nceDnW{ zu=k8=YU|s*v7#U#y@OJu_g*A6dXwIX(jgRS0uqSQJJOXFmENUyBB2QgNS986^p;Qq zgzR_i=N;$X?t6^qoG%PQMp#*M&9&y7zj<B%%aZ3E)CdDY1Bs0}B+AJFN1CJ-yZpn~ z1P=wr1E@Wcm7Rq(p4kKp%BiJ4*#MF{sG*!I;CCy?MLsNfwF_}ny#gz-`p>$1iTP$8 zO-Yp>Ea~DFHNKi_vOJNrsx66-U0Y}eDow9YkYd^lR6sNMuRY4<nWwglNWP0&NWkon z_N<tCPeZn$yrM70o1(|`%*JbV2WvPMM$e&9z~o-ftB$;z<}4S;tGX>7FUZO;mZRir zH2$eU5%T31ZV<KCj=8Y->FVnSvKU)!Xc{{<es7_LTcGr2ByZ(5{e352yv}9dDSy(S zO9v(PB*_D_{S9;zZ(HWX1eIw}qPDVLZM3x7JTXoglnkL)X;h^&t8-R(WUbEVSwm|e z;wMP`xN#_Y{0;GAF4wRUMq&t&>d&{2m)}07jYo^zDvFj0VmATqBe==9!|2{>@@>h% zUcCmV%-f0Sy6JWYIY<o^T>rq=J1B$<=CJ$6$h+-9o*|Bf8+>N!R%2PlZh+Kd$-i!F zam4lvfdtXYCWeSXIM26{D3^iKjJlKLJRs@tK*e`MRiiXb4XLg}ODnQy7|&;HSfJaF za9WT7TpzGy0g88UQm8g6-p+;X-ngX5&3BGBQeVGGh1umIyUk-?hZ_#LRudgWrMVwm zJQqpX4_!I^<`J4pG#X3-l>ga}hjOC944ZVXM55cA9rk@oFLPH5LYN0H+B0+|ZVQ|9 zuEkSY6~u@(-L|9%hdCoc%;9}N34J&Pkf*p$X|{k@nBbc9r68Hby>a#>Mo4=plP9w9 zs%Hj-|40@ZsGU=ImanyaKkcFS3HCAz;R=dHR1?P|oT}nV3OAHwF`q;Aa4#|2I!$Ir z`{YA6%cvWQiY+PRndjg&0!1J1Y0BPr&ebF7m*~2@o!dtt|BFS1|F(RouwvCpYW@VP zJVf1k)H~aa&4j%U4L`5Vcohz1^9}oER1_J(oSDG4vdI$}kRU>>lX>35FX^y3pfpEu zdor7*_;ItFxw_#|{B69%g`I8zRC-EDYPNHEh#H9`Ge9jxv^{^nWsa|KZ#Wn#?zi_| zSGH&P&?}_$WUOJc{|ZMH#bp-M0C;q9;v`n!@7N?Kd@N?5)L2zhOyWCN!58e9_e*nG z{dNs;z3=if(VDf;yN{{zbIsIH4tFY!igtT0qzK(_SSbA!G;s16N{Una9Bt#fl3Be# zA=jW*U=)>18sLs#;67Nq9?e0)H~;=aTZym`;n5`=w458vhzq=Uj>|$dMs)Bj;S_q_ zSjYM5UNv(%^(y@Ak@v&x*(rGTZY={RJw5$vb(T_d`vm<$U4C^{a@A0j^*z+q;SY#W zfpP)wsI!;O@K}nTo5tR2BUUAU)!eb)+M0*;VaxL?;huQn9^WFBT;|)VG$k)f$_<?Z z`3K_Bvjrk<*6{%&rxPyf`j&e}s3)25FWWFuAUasL^BkN2b;GP1|J;$v&Z5{g)t9S2 zO&N+33v~49iYmO#%V?tP<6|Dogw2RoBnuP<?5K2B8!d6^$=@==vpp4hSv_-7IJ<GO zFSt~!2J%b3RqmgJ0n#rIylnLZ5QGCqdqhIPkd+{z&!gN}y4XUlbT5?zhYL`WRC)3+ zoa=Mum}yeSNV;xLSx?6;7lHz=0HgT`*Iw#>&9Jdy(g$8Yza>4Z+&`Waw(I`QGW8(! z<8!q5YVWe#7A)5v(IvPPDT<hDhJH36{ZU`Ur#`;6mg+IY(BI>wp*W-<+u?>@#Xm&D z-}&bfcj>PP-|i_lzAf*a>Rehy8R8vpp1R;<SfCT!cghf@(kS?;D6-`C&_zng_R?2a zCwn}QYeXO88-Q@O0_kGiQjHNa!JNR8Lt`LtZtw|<8h3-Q>4Zx6m;T%Ag5N}MWDOlw z%_9CbT<sQJDC2aIh?`0ehtNi2M=2iUMR~ZFK7$^2`)=+k=x19FdQqY8Hf9z{U%0KS zTh9}VMnA9^^ywI{k}N4mdx5CV9o~JJlPCUIQk$lF@5wEb_yux``%(MWpO+Kk7R9lM z-G?YL9#kT7fkHiV>D#z-=JVtL+p%4Dw@*!?%BvR0p*un>wc=F+F+$I*Uj*0?Z^|lk z&;DvVPmo|7JZ?HHzIboAyTh+)#oU@=&co0nGYBc5*r>W1oaCRt)49Sa_>k9;FqM0M z@;7oU&lr~tYUnof-5eIKU#c^--B}sBHIC#R@F~$B!Bt#9{VA3`It3En!S4cNdl6>1 zuE9V$G2dT<clRjh37V);+@iZz^h96#6;~qUDF<>)Fu4PHKmx0S@7~AAtPHK=1xMb( zNmnNoHBk`83>{p%hqF{zrhy~{)h}iL8178x480k$n6rfO`5R6)uecM|ceyVf_F?JK zu=rpOYpC{An=+QTE0_gLF%&%IX}Zy%<gH%(*!IR3;*3+V1+x*s1Idf7-fPLp%IvBB zhbQegO#o}5(o4|c;}j8f+VYI|FzL~#r8-NOMNu`I3u*XEN1@sl?hk_fl3rh;E6b;U ze3QG(;u&yR(@&SV5}D#Po-UD7CF`xDe`+~fS{LKxxtb`6uHvm)@P_Ib@zaRSXp=O} zcL~SKtx+K_Gz?uPy7}vidjS`FRH~<FWUYpjGw-C4BWRvaKf&Z}6@eWG%rT`~i?<tu zO7N=f$;=NSk6Y^<5txeM&yF>wJ3^JjA6*d+>F59|@jJbI>1Gtk&y=DsRGs9Nmv#m# z@H}JC`;HZ67S2z)EF^l#8j>76Zl#-<48In);_|e)VQ@cT89DZzHa-B}-A><YE|Va+ zPc?&!nd?di-#tFAn>zAWq=Y=|HsGEZoqJH>>pu4VVm;|a!lwP*Z`dCCH2EI~!tg{T zZhR2V6QgR0De6nSi34eWZPOeQA2GyugRR;c)^#9}VrDelb1qib1gG!vGt4Y#@Hz)+ z<=)MHMg5s;g<&i$yK;OrCfQh1ZGgQ0!L0hCdfwsuX{fj5Nbj90(i9UUn%2?~f=uV6 zrWKSZlMQrXFqcSmo;c5uVw#`@Ih!OS>U_41PP_|xVaSh{UqE(Ci3U(P++(_`Ak22} zxz$AOy$-688|mS$mDi-gLf7gMDoyY6)j7*<KZ`5A8(>|HWppFZIm;;B$I^yRMkKPu z7lI<wO?lF{Em~V3?^p|38m!TNYAAc_R&e0^_%?5A<{DfV+TsFm#)&R&E;5ILC$v|G z%V<BgObEL*f|A_rnif)ZC8Jg-Z;%kFF!y_~UILRuH#Y&)e)q^tNDKJg+62@96&R$d zK22?|)-m+(i)D`o>knOOd*7?+<Fj=a*CCJ_+3Iu?yv;WL?4-TND^Dufq~@1XR%7*x z`YHU93Y?l%NQ9J|nx)6w>Ih)6E?J5Ka*lFO3euRqm(E<P5heW8y=b}n#xS!SbB&N* zLw`R;bn!%$P8!RzG<&Ape$9=tEQ?q<Et%&vqB~txO~-7<rlw|OE+gGw$DY-9Acv*| z)p#VGihu0=JGQng_9+UcUy{j36CdKh7s_}UToSAls#!m#s6VxM?|`dX0G0FPT&=<; zobujKxxrIPv-rUl&OMV1yLVRBQYomaT{+AW+CB6oS~E}x{Iqe>SHiYPwQ80_vS!cz zxix*V)SWJybkF7)PIiUspdTNB`N-K4sjXuo>U^(VUU=9CzR%a+w;0#VJh!N$sgmNx z1!Kh$hp>tGdnBHp&=W_kb&Yoo7ihfl^l_Q$8m`w++9@pDDD_=2LK<k~$Z6E%&u>0n zqK9(k<KR6*ew8@uab1jcq$4QC{Zj<9Q$@YUUEb`o#vcso9KA{17aHMdg-W(xqd4vH z#<(67{1#pUc(gZmGvySVeD?I9J=kJWt}}<HZ*2=T*Mj-b>1*oGtS!>SxDw#flg`AY z)7gZd@GCn&{d%Tz3bMW%MbWmfdT07+dapjxfv<y%4O#BXLThF@Tu8CbVdgZCW)wRM zXH-=L63e=xlao;w(y}1Es(Y4yoSGLHSYogm6MbaO=--uU^g}cN%=kncIsQtc9K}B% z7H?`&HbN}ylG0;XplwtlXBe{@Uc%d_JEV)_E!us@j`WB$_dv2o-mfS`V9qzqr3yOg z4j!ZxD%ZOGWClWp%v3)z6MwUFU=H@rIt*zCpTy!ku_oHM6?7mdk*;ypBi6+D{kAl{ zllr@1l2WSOmb>AKg~s+`uKYg=)B$PipUYn<6jqhW5bfH7HZ<g`xKFc}yhw1jXmry( zY80u`q|O*CQ-1selEd#N9}MWK=H>K5wObEW#Pp3{3*ih1k33;*OXrjo{OiA`EV{@p z<5`<NsEBhp%<2Se;>Q163{M_9nvI%B{85(|Fz|beTwco{5Mak8*qNd@lifqPx82aM zr815kfj~*XhyO1|!Tz606YuybZW3WqJWoPHm{;c-504A~_~*sfzLdim0kXmZoAxEB zlmH9xe-1qA!qd~e>DBZ52AjjNLW^gd=k_C(%m2qJ{U$g9^jpE>*yHm0w5_SoCuP*6 z{Dhwn-&;Es6QcFiZQKOxUkrq3qx4T4SgwoHvH!asBEVWk2=)B_4cf{P*;D)>%V+js zALm-*j!r+_ArZ*?7a9P#!9O(M6S-IG(M9N{>3>0-SORr`!75?cTJ|p@Gk^(vB9Dn# z|MN0T{Ht9A%mH@NK79!V9ZH$Eh@qT(UtSiU#zia#gkQbZ=qEcI1i+I2!V{6<h~L+U z@uWa(l9c8j;6^LO(t}LqMDR7*KFpI-`u4)14?t5seQ93$*U7T~yJ2F1x%L5dETO%R z5H=ZaMe|yH<vL+3^XZkiv&S^<!*U}Y`}+R{Os-{DhJHgF90S>*z&<x{HUG`ATtE2> zUL$u`8VguB*qsBwNZ`>YvU35TAjBWEOz&Uh<P&MI6wnY)VADvTUV@Niy$>ZAPM=aR zNdNwBK<mWbuxzg^;dE2?zuV$p_^<BY_myP)XJu4@{Jfu##3R}G45GcWHvm;@SN2By zs{ufN@}evC|K@+k9k~K2hMt8|?;m?Xzn~5q{TO>6Zt3D4R{&p=0|+$Q0ZMJYumZ{f z%p;CR5jm>*fBgRF#_LRC{JRRo_WMfVR_$wqM^j73-=E(Y03yKTK=i=v@c&0gyZ9pr zPXUT+IaLE>Pp5qQiwL_8y7XlqXl~h5qyW$sAP1e+0~ByxfXMR>hy~VHfVlMW_$`oC znF0tMHvx8L#e7Dxwn0<@CWd{tCCtbim6uLp{O}Q=-4vJx(bnH_TSaJ!v#WqrY8td9 z5L-Fk4Zy`_fZ4$&Oz0oo(6j~EAwZ$0jR?N9f4uOyvH)aP6Peub1m35Db-;4`>O22e zZ*~xHQLn=<laByh|4CLf-ox3O2MCXFW2-M!k?hHxBG~1M-3Z&gCswKf6y$u-tG4`+ zh*20WumKdDX#l<pN5>Cf-(10ea0T4O9;d{EOF{_|&ErVAx)R`bJ)}qv-HK-1d3MBG z(`OwnR3?nn)|*88eeQ*r+$T@1X`7aVPt?r1`>yBPG`gK{v|D9-Jb?P8Vj}`Of9(*H zs^HG+=A8wK8<u*UHAZ7s*H%+A^<KN{X>1>F_gS;GVEsa*;3TG7>W)e!1(xPd1B9AC zz6jv3qhjb1#uU^xdaW~jABKECq6o`d&ggBw*3+_=wmfI5s2o&chV$~n-bxRWXV$#! zU@=o3-je@Zte&gPvVI_4CEeMNYy6FBCn8RX6t}so;1OkgqdBR9CkdUrxbh-*)=<`I z)zIPAuP$4~vNCc8ruG%~n=;Y(3QetPhq2>8W{dnWDXw?!R8!8jNR5+&;5|>8{u{_V z+tYMxPFLm@<}lh3V9UmX-UGtfBD{v$N^gv)Jatv-^c&?*Qxf{iiU=+^`#wf^SoYHo zuLyn=Wqg5ZhAH_)=0M)4d`ybD2Igd#znq&XbzSGQNNR6zWE`#A1EPdJr`-OD^Lv8H z=-RbfpQ_xEY%Mb$r8?>BuW!GQY#qsL*jjTgdY!;qwUUgos&KH|#S38@I~VWZ;;WW6 zrN_7Z#GH+#7wIN<>IK}afi2T9m%EJljrH#izV`7+zw=L+%ul9@i-YrUUI;@KFN+aQ z>_A8frR4rysLpsBt8-wnO%V9WPr{IQ*{qpli+|wtmgM!{vx9=kSD6+)ud<7A%k3#z zU=GnHJCs<7F7~?hP(Z0#fzz~_@-<b|Eb-4pG6?RN=(SY8Xw<iORs~`0vWU<e;Tx0V zXoykP6Ra7!^e~{!SQ96VAiV-rwfSG^E_gX>_kHBbD!CXo3Q!r>kZ}fIh!;gRd(eCO zcx}}eFGD6ef2Q4f$zz@RIXXEnF559W{Cb+!vqkX)rnt2YgU{x0A%5S@BDprlBD`7b zNh&OkoxS5KZlx1JQ5R3Xt~s?A%!aFw$`MdcIi2?0dXw-`s8vy|q1FDw?1EPRDi`Gb zp+2KbeZ10~=7e2sHI_WBZ0>E9TdC8VIKS6^N#YUeFEhoBMpGk*t7PxpeRNcH3$JzA zfPX!^{tjgK7f~pccFET4>f+~e|3fs{&g)FNw~h%aHFfdtH6O0@-DuC$W}zI86&mEt zr7`4udzk~XC6fSlei#V6!2@h}v4p~DpvF8{Idj`|A`JX;nrpIdJU}GP{*F_Nsb+y& z2v53H%#%WC*dqL!;xiP9+!~vIqpT|Z698gz3;QeQXHV6{%@;9rHp}ofb(kWBJyQBc zt~B{Y`zud=$FQ6HIB1~(l5(EVc#75-q{N@ioz%wh8UMcADH~5)k6iE8TR++lgWp#4 z#j<Nn1#@nlBO>1y*G)k6P_myAjWo4t^Ev!tRPWv%&=`QreD};wbFVs?#F<^_;e~LX zei-5tWgwze9V_40+am5vw@BL&GHdd6yo$rZS<|YIqeo#_IM?RDqEyvA`Nv^*Kl4a* zkiAk)pfucf_3XXc_ccCaWiA%h^87LimFppL*JF;^XLMI8GcbX@x^C!rc{#};J^kBN zNCyZ-mO|=jTrz3#?_Fa?f%*>4t}1E?Vai^E&Xq5vqlNoSz8nR#3T1p&-pb%J^W-<+ zwC@Cu^N0TXN>_VEzt?K9v9<G<Qy1vBGx>5q`BI`@|6_TpxL-fcwqGC4)uHr8*k|=e z@V8N@6C6dCgdGFMwEalHxaOenQG{7_Op89nDmuO{B||-?RpCj`2Md9_eed&V2MLqF zI3dM8b9yp>0qsh?M9sBJJfCbMF2{*<tD|qNrD)f35*{!)3tSCoU0kMGXB4}CyK&9i z_T=Sd!5WTsMK=ak>xWz--wGC+!YgAvo=*{|o#>dLC+DtA+89+U`Rmy#Q%`2lxtifl zs1Q!c8qUE6jZK7$$V_OT^&Q<1g3M(xRIkt<(Gx6sS*&=!$VFZ|Rpddqb5V6${O%ZE zs^p@p`!1(i(@5G~Jr+B}k%|I+>hdAe$H=>SMI;h&IlS7<GK`N~+y}EXw2OAF+HuaW zGeM(*iCuySDJ+CK{u|0Z!`?sKOfQ`KRv+V&`Wrhzsg62c#hZP}<yfIM$x?${rspMk z@`mksC-gW0)CltuVi$xJ={r@Dz@|;M8TU(9+X*?0+eCk)2}&GH+=&`f<tkx#blXF+ zF3u>0{X}~l`V`}MqEvesuc&?rOjd47hX<8zyjjJI+3H?!wq+PB&hdXAIq{(f+dq9J zG^=j&`e0J*V}~NFQ$F}6o`)S9^%v1yMT=z+>rmkkPbglYaC>agS={9@c%ZF4X4N6- z`PXO8w7rv2@_bIerX&1Cj4ta4ED&o>T;hd^zax?$03@|nTlzPMgqz3=mVWz@$mLg_ zQGTPFw0`VG6-!j@$ER-booCs`B3IxhE)g90o5pE!Pg09z51PEk3)p=%l4DM4)cI6| zHg@8-Fv9^|XRf?2#C$xleKsY$rF*&T^yWTan~o#(x`w*Q_PoZ6NDN&J^Z4~DbkdlD zhtv4Hmg<OmJ>G%HU=WqdEFU5FExxL{4fneKeYac%zoz#C+Nt{AiF2Q*HrrW!pK&_< z$a%lYdAc#vBT6T)$ZF8T)BU~rb<B6Y6<<I8fv)$DiGbV4qzGy<6-*|wTXw-l7==^R zTag8`Z&LXKSs?DeQZMAKoko9kO6GsQ_i)a_^y~Zbh`p_`JCc>0ihaH7n1n1em=dp< z=95U`G-@%sFamiv+X-=~)fVTE=Du&3PI49hsdiUcuU-I?%d-r1J(REaDwoWo<t@;` zkGB*#2ey{Tzb_MUg!IVv@>QCMtmx9U-58WL2<6Vj>@oR6Rd{Y~PIopNmPthyd>oI< zAssDx@L40(-dwT7AUlIUB)RC$KIsy!MVFL4OgdPmt{St@O}{jI*M-S$HX*M}*Z)*p zcWrTg9<h|Z^22RZqGO89CjGh$Q2JW_@`EC%#N7X2P-DFCr(mX){8^?{vIQg~Osbq} z7_Dx$_l)1rO(orwllcS5aHYb@dyHdTusmL_4ktl>!oTsRqpWbwA8wF7J~&n3^UIgn zqHXhZuG;<k)EO_f$=+SM<{n71Q;Fa3b7X{Bmh^H%@@uaJ-r+$rDL!Sxw1rFq7n!89 zj4&lp!M})PGDxvg@|q$)L|C)~rqU!=8RaL+re4MRLik#~rgM~*8NVuDUJ`WUL%0Na zJfDEsAZVbDIB-?pNy+h$4ESf2``*iEA<S-Gi+e&H-T_*{CP~ljzVA^Q&7?};NlT%! zmxW5)+Xzai$;uMhe9_6n;g8Fg0-Dp$rp=WSR#%!P@>N|e=B)&)_kL*n?5<Y6FKB1} zxf0KfS#0+##EamXS71!IS|jY-)_a$Or)48#;icxYE$YQWF=b{*r759oflA}RZyViT zin03)gaO3W0_-h}A2N{%_t7S!I|&E2oI2`FSo5g+@o8am3cbKNYy4w)+F-z(;fn}+ zhGINN=cQg}s@F$M8Vk*qhExIRVK2R9a<~+CONK~u<?yhkX(McNM}z|RILD#6;buUO zrSyYB1@^cCYX&nZ7K(;&{yLYb)Qy9&G%c2|*vxSGH2S&%4Y-i=7(5>;jO)wa&Lr+a zM7$vjGbdCO`9Ia+Lj_6iw2}HtUT8+`@2$POh~>SWRH}wFNj5v>5)x{0{DHr5K~>a~ zquI46k6T@l!jd-v`COal4|9^^g?5ERSa~Mw(_icsb9K1NJg0kJGw8{zmhxzrdSfK2 zLli@?(~POvvLXl8WX9(C)6#qe{x)+4<1gF&*`*N>X_Ym`q6Et8V&yK^<inqj_QrDs zJ7OLqoV6W0={gv3_RG66$Xe?S<JdCX1-Ld7qAfExo-XU^6R!k`On3S`)LPJeC`qL@ zUBjTM)Vmna^6f>QejHGL*(^}WnNNE_TfJY7xApOZ`P_>9iTr*0133pXw6Rr&ZEY@d z*U!NXo6_-c{(~M==~G&{i-3s}Bf8QY^QKZ?PE`txLjJawf;{2{+&by?Q}0UfG??G; zS`lOwI~mjA6ZrEfye1448}J~dYmu!rV86ocQ*-K##!2potpyHLCU?x*tBrn_Lll&% ztpUe_3Dh3ng#ufA`7>I+y0i_^d0n*a6Pc+S4RME>s~M&oP4yCWPG&ha5sdaui^S`a zh?%~VsLNbM<_eto;L2JO+Ksr^94|IRUQwv-Tw>{xp&Y90A=dnAUtD=jeXTV^&B68B znu0Apa6%YpHr0zjt#J<_H_mAxUsfGbW|jI7G+oEL#i?PMR8?*S9y+g4o~;XUC3x3) zhb{MxclNOw=R+=BCd>Dx60-uW1(FZE+xNLv=>xnv`wDXnGRlofg*(@P<(PR-pHz`? zj>1&WMCv5Jf01!LH@|pEbV*d6vXQr;d6!8Te}BvVuVBgGQ7}md)mFpo?gIYYBz*Ba zK=?sN<C5sOZG`FA_K!?|RICKomG6$)Kn&zP6~%ld%|Jkd=XV)Wp-2f^;q4H=EOdKl z1b$jSwhrlEcUtugp{yOqdO-J7T+MAV^Wj)=vb0AcY`F?luNBOWa}2<wbmj6jL>gh= z#Rv>3eK&9W>Z~@}(RHtJp5{zUWt=BT@b{0~Vv3l?^%FpUa4**5d>Ju-_|W$3`+-cB zO1QiR?Td`MRB-oVi4??}Yb>RH&f5H(VI(gj67LwA2WEbI9>GBc{fo#bHBTqsLO<kp zY5qz-@y_pErtHm<W?66DNsy~ZA{;Xg$h#1+1i7BV%Y-@0iM|uJ)~BoA(_eL`pDfy( zC12r-;Qf(hT6r+{s_EL0)0Ym1Y)%al${B&6z9R>d^yLHBnh0=Mq7c7mysYqOn4wLF zI%g8r10Tr+L>q&SD9!2%&`W3J>I5_pie2k6jH!eJ{!OwBLM#08x`~(-2ne-i7P<5T zo!|OI_IG%<DAbowI(NBFNE@D3Ua2}ZUfKs8Rla^pGK~S_!{LM`_B8>He?@>3Z8-t! z@6TwDvn!Uc7R348O8HiHYS?#@l}ljO_A}gbg2?dP1RpMh*hT@?&F6o<c*HtHqxa~> zD+<88+Iqgsz7MY;;s*Z0+K~h_dX~resqSz7A>%R7Z)&%{h^#m9;bxz%{+aXLa{e#B zD$(%Y_0)<1qiG00)~iAR23Fx}{P#)H@?1jMFK<9>-jaO7PS4k$BM5^Q$M06Enjy!q z%k;N$TfoUn|D6|p-wd=3^xO?iD`l_$vA34PkAXmT?#eH3Nk*`$__yv#fH(GYg_AKX z2K4)y=aKFunbWmI;J{aV6M>IIz~^T`wz-L?rP9A%K4O{kmp|ByA6R^LJ@OT?9OL>} z3gK?x{@G>Z0SIM9R)l{8NTn>N&kR$q48f2TL4Of}z7kaN{6DNY>PI=P9{6+ly>)ZY zdI5KxTJ`+Lp-NVT(>?;~#2sY;KLM4M4A7<4$2`XIkdI&9%Ix`kgc|Ui)aMUUiOw}x zt|u1!t&DnjiYIiPv12OOZ^6FP!nX5Z@)MuPA^&_G1M}fril>k_cM5HrwXBF({3_1> zP+)CboyI>nhvCn)&tdWGn5@mehz>VpHVINcMghIjME?p6-HBP$H$SnA&m*j*z}T~o zSU+L^4wRTz_#6LVJqZ9Lmat+a@&;o<mtZ41AmDP7B+qH4AZuU{tAUzN%+fvCzb}K+ zeoleoK)*>~+W@#SCyFFc2Z0Dd4=zEyiGQB-8eo!42H&0Cu5L*3xD$04U%DShj$hd{ zLZFB{fL!liFirxk>L0qRjcb5<DU9uc0DFl~#OW7>?hCP4wa+WtD12w^zXsRX<X1r8 zjxq?%GJq~L1(+;%!2cprN(qMlZ2|s2C+_{X6ZOycj3`1ycpmt+MG-5!y?2Tip!&n! z3Cy_vb3A|}{pSi)=JMueDn|gjU%&V{;?j9OU26{tx_A)WpGgslf10-h1!FS8eMKl; zyezEDojW92ldX8P#uq(fH*b`GuaH%1`)!dVmECYErtnl;gH@?9%wOQ)iluj#{ZE8Y zbN>Dy&3WsC-NpVHm!0V1Gv47mXI|z0#S^`Rnv_+2=-2pF=@ggStqP{=u;tt(j8+vJ zVLUSg0;h7f!yv*1>uLiX{k&Zqf;@jJ#=0b_-piEAl(nDZDEt1{B!Q1Qu<yJXH8KM} zvBM>LfRKng{w9XwP-hf4a@IW$wX176UeD9qKI&=*(JZboO4n@07w6ShC;E7wiAmKw z;ql1<_XAIJ@SN(2&1JT*A_#+CoVCZQb`4(2ShbDgDVd~l+R?7{PVQ9N5o_0I#sa=F z=A|1RtT<Eu2;js>VP$~j{ah{b6vRRh4<1EO3p>=*`r;;Q#<eUuQA098lesBhHm5A; z2a+GV43DX#Z+l*E98)QQNKkAiT*0`QNn70+aQC@4yIPJK((A9A7Bn<b<YA~ZZ5C)& zq15;G1`lP+^eAzAD*1(>-vq>KRgp!exlEjKmGJRvSofDK3RlQ)k!RCOwpW-h4jH^k z)rDLp;wdklnG!}RH^4VKSRt9Km9<bwIPI+EuX)9WjMrmytpTVr^F{y9;51f4+c#gR zlfYK9^RdOyE;sLMWi{GvfzI4*7`1XEbUL4rUCgr=1K5_bJU(Nh5MtnA(kTIRV!swV z1-_04W98TT2+}wo0`+i83FH;jY%;}68aXgCZ8CYB#6`J9PxV8%A)s3Dxw0dTCRHB; z@pyej;7L4oz1K|@4eth#`?nk-&zB;ltSr>0kAo;w>RQ^XM|a)KFH9%y*M>})+8Cve zjV(&BG`jBfi}zB=?*2u@a{lC%v_MpC>90~#r_tV*HY@rvb)^T3>dr$<X*8_kvDzvk zD~SS;urZHN@xO@j>GTM#%b25Aa!1_8)X1KCLCbsd<3-mC*LjioLPq`8+T%Ing(%o_ zEFwCXSrdX4LB6q{+$;DL5Kmj5`oL_xF2iO1ThiI6V8Q#_w5%VW{X|}{d@|V1^w<F& z&<zNr2)pwVW3UW2@YUWPm9=WJhrr3}Ek4+fS8~Rz?6_4vRuo&9x4JA`<P+*kqiut~ zRR2Q#^wkzLec)t7zcyBHyb|5i*c5FS;%`Tu%z39w0B|RT+*%H`+FdL74D}j2n$xA; zn00`!?2~Lj3h=Vn>4-KdU-}phA=aMq*FU#jo4i-#W3pCzrpxkE_K-=f04fNN#QF7^ zMUWdFL>r!XuUQW_ib$!sHd8MMJ)C(^aQ$~m{g+_vBXjIDS*m<CXSac2SzTUeZy>j# zGNZBvWmn;``$z`)oPN>1UR*N|6U6T%=n@W;>G1d^($yh=6^Vi>W462f#<x%CfNex@ zm2TelbhT>veDG>Pqio9+A#{|~SW7p9o72ZolQ8H5tm<waXtxu4bIBAlRga}d&h90# zm0(G`&nY6%qf%8sCalB2g4_FinFuvu>8`7h>ALlO9nN`;svd5aX@E8Zo(QfX?jn1A zx}v(X0Kw+Yb-o!dn!)pxgjV%?aHlplN))E~tc@LbD6MgucKot)`p|Ms5pt*f@47_5 zUgJ(b3Q#T%_MBwyRaL}3WIf8t;Z*(UD4%Mc);?V2>Y6)dpJ11%nX2|&{H=C36;-uH zGJIb2Ed4=)bG-i>@t)Gs^3(!nUO5ekI2-gT_t;=AzrJ3wwg6~f5t&Hm*!I-m+J~39 z_Ms(=CDyukw=^_lqxkWqo`7_&KqEPST}r=v#bEZJS+7I`#6TEiulM*yx}bXU$|6gI z#{cGK1yuVJ<XjU-Ml#X6580L9wVO@0eDqY}Ok14uNk8N4GMvfBe?G6o*dXLq=gs!R zzFfA}OF&K7e_?_<528S_5o1n6ePj1;Y8Nb+S#Ez5d#~&1S@OYjW58`Ui7TYn{-aj1 zU?a)sbv6Zz?(%#~-_E<`{aEY!xDxb3+rAF2y69c}{fb-GKovNlc~L8iKGx#aZ0$Q@ zTJG-lY4%1As%NP(zoDL}BNuxq?>Dp--Qy)pzRufna`n=?vVH0LF`=myU$j*}_CxTY zM;Yg`nhJRzJ+0NwJaHhqYE#1n=b<4RX3w%)y;LQU5sWR>adrSx5-yTo4I<vzbz9D= zqLB&l?YAFao7%T!3c?!?DspVj(7TROCUadelo#K%P5*9VQi%n&fA-_N@eZRM*SCJQ zuSP~Hs+0BfMUB~@j@6PGck}Ag?98~q;?5jt-0`VxHh0zLE6|hly%ez-1U3w)D_&I_ zgH^|qVPmzhD$OOc-)c1j3pyczG*hc~->E^lUsZnRi+#k;*fpxHHZl5J^i=oSeok>n z)_0TrnR*geksnYM*vi`(IPE^wo`OegjIK1;za9G8CYCc%6!mGBM6{<_CyXX&LnYgy zo_`*zm&co*T`D(WWUrIMcj;Y3m|nV~M22%%vBZUzL-aJS!Eu_$yE-!knKNIa8`Z_> zWNy;%b6(-J$!ZieGP45%bPZTo+`)O4K`p27_c6AenHjOdQrnuOyBvoj7c??-qRAO1 z4sx6lT)bS$;U^N713#{+UJa@kKdGN2+#~#CuSEcOb(Ry=5WS4Ju}Nnlb7D<B>1$!7 za$(UN;&{R0H&*T-K$~J`J5ZaezEBxb@I#qoa4mhQcDV6^&CD5C5CCOsMW`+O&CL{L z+!54@tQFQHz6Dz{fqsnKE#lhTU-|@-(_7ize9J1BwV^JD*V;9MDW?0kY{Wz}>PzPh zS>OV%R+G(@bxvzeJ=m;GFDflZ36&#aXTqLc69qXoC7PmDF|P{bS;oI$pXbRw$#&co zW2t%7(+jT;^E5RL)bQC3yuNDA;?egQn5TuaHzr0QoGw8q)|}EU5JfrXL{Vdl^lRhB z%<$F4%`C5hB*opLZ<Twc9S}|cnhI^gSbZzN$a9^tVt>BMV>q?T*G*$3O6QdTn}!Kt zp5_RJkGA1rzb)RLim$%njIiGE{>^?3<_6$#wzkJugFbWiokR4(lRos#(t9Ze^^KIy z>skOK4C{ftaWHk=dm?ynSL1!{w-8l(X5V0@4QUX)lmIh=LAiYMbXK`W6BVz2ax%X) zEpO`@H0aBsu~EZStt#=&Xm}y<f#$V++pjf!`rm9U<yh>m&-t|lg{pfs{LYr+rpw%} z9A5Neu{TSw>T1F-MLA%Oyh>%AR`@g-6^*nEC%!5n^*b-U@={+NzcddwuQuc~xGk%Z zx=YO94t2)0UnoF{qkTMRp=u4)t#u6!xj%1LuE*=q_NU!fb&57Nw(5L(^>rM%l-j-J z7&L9iEikUeBchS*%D6jT=(B|R27yAJ#cKpD<l&0ZmQ`mL@4555pBOG*F2t!dBC<z2 zU4l`{z;dE95~avY%%?wL&`#!xocfrD9d9$}Ms+1Uq{)j}nJiMlwdrbT(NfF1q+h9I zeiOKGwi&i-)pCN|EKg!{lm}hBP1F?%oDAI#>I1yh%Vx(j36f~tYc+9wLSZ$!6$U>z zAEV3K>`GLm($opN`kz&@N+MI-MN8KWD8oNTWg@3~^~;-C1wh1`CM~~nITCDN1_V-$ z`#!XuwAe+=lqeo#nR4GD`x;<3_&qe>`RlYKo8*T};Xu9G^v`)vl`*AzbN)(mU2sxG z=H=sYD5JofxkmD$l`dav?le_asHmn<c>1IAA+CfUQ6qxy%{ry(bZM|@FTF)OPtrQi z4=7g6XLX~GwfS#+rLJp;6;NwPR-2>!#q0Q-VxXHNBrx1^{Tllfz=;-p2EVPoECxWN z)Bu+J0{+xIh&f*?x5ElV$#mFQ_Zif|x6dq|O>RW|M=-|`|3vp_XbE4bPj+cb@L2G0 zj(KuSS4$J@wQ#<Zafwb`iMO|~BcQ={#^jxp1EEd(kz#nB5EzL+$D+l8iGJ%-?ukZ& zXB>^y7h2xs?}s=Lb3D=XFVuD-)vtJn;`Fd5u+Utw36SG{6pVJqcR>V6H%;ef&0Vct zdAluObPQ>uICZ$Y+<Q>Y`PBQw0W3cGv0Z)z)lgOH57z~3M@;o|51E)}>X|QjklaU- z0oGe5s?9m&s~1iScYdxhR8l?29Mg;x9&@cC$2^F{gj}G=rn~m9;FW&vwmtOCn_sf7 zQI>}xHC+#Tm+Z&U9ZeT@dg@%&AFWN|KWo)7$Epg#CT4ULD8OVodNH~5X)?lrtqL7Z zjda=h&DpkrGY|H@{DxV-BGX~(!r))kSI0^Wq?ta?Q;Fw&xrtimXJ}rLAQA5#e^q4l zq}^SEs!Mi|LQ%-9i&B?VC;#4MONRnp8zZwTg&9HS-uNlGUBTI<DO@4>reZ7BV#s`J z5lz$Fa$9EaQ$swo$=WADPXT;()u)p5qzISv#fkl@FX9evT`vK7LM9x54&vAnxP7$o zrQuFI>wFo>!hD9xO9`UW4E=tFc)gxBDd<ZN%=EV<vigVa7s!)FU5^{93DNn^uNmle z5|9TLY8kJTEN)(XN}_hqyUbeKn|BB~DZDI@T1w32Xn5<==;dq<4It&am672(JZ>HE z;tJcz>)D*U)NfmVnb0$=HwCky&W*S->f={#EvR^<t%^8ZuFEh;PgF2ezFy8xo<1dK z?6LK>rW`b;o%n=7G*=jPXyBT;6-?sI<kJdndE1nj#GM(Iq3r<oI92k&Qk*qEE*?AH zI|j%((Kp+#pN?556Pe;WY1El+bUSrNbxE)DH(4FX5joPnV~?(o3}dqVsW#%S*kIp# zo5gd;ZJN3g_T6Ed(As!dwRXo^ggT*ngfc26b!{#su;J8k&c;(V&Yi<(duYJR&#koq zKQ!{^s`=ljp!o;cMGlh(wdQ3tL|i4A=&E{loafvouvYyCMF{BrX&ik{EcM4iwq&<* z1rr8)(QY812K_ebbFEPB-1yjANd^$U#DR{1rJ94}74QGc0zP6hqgSKE4q8>4-I%rH zSE!UmfxmaUba+AW8-~osh%7aq^Bh-3yp^l^gD0rF6{(|m<O_b6@rxdu^i1<)A0Aak z)Ic2peB=oTN2br1hyXv;|4t3uUe9%lNyocU_a4Rx^vB(SE_9?>{KG*E@xVjm{v50f zw(+2qiD>N)pg^+$lwc`RYYA)g6#oY8H6rE`k!1-qQGM<LJ|JrX=#w8nzqE-QU`UUm zzlcWimx^$sf6@ZWA(|`Wf4n*QbUABEA$&*i@Fy_n+L#2xUj^}A%lhBAL3#{Pw=VU} zrkZ5G+i!=)tI|N9uojm)DF8mOqzga~b%ZXqTnIvVatc1i{6+L*(uHUf@edtxY444e ziRP9cD&J(%x;c>|$8Z)HByh8pf)w`sCIyb35ax7E;Gc$2{pVV=nDbt{IeQ>-OZ76x zztH&o+2=1CS5{bnnp1${?my=`DZ&g$fOJI8Pub6@jircumj2*Gv{Q<9G-m7qJKcMS zfqO^2u-1Q@Eh+!tU%Y>`fQhCuk@rah1&Uri=XWfB(?Q7pTynzhzc`HUe>p7+|7?=N zp^7<N@`F(~8~;UE%Yp4RkD<9u%LONY6T;J<LF|C9(1ob+kA4k!2miz9glMh|E2Atb z#DPKxEz#-oXXRzt@7tC=ca35HG%Q5Z2<Y<vYwURq8mpA(!8A9ha8sG&o64I6J{U@9 z6toVETKhAf$mG%Z$3TzEN<81RqQG;v@Zj;F%L}QDz)xH9^>bUsY85m?Ez*ueNk@`b z;+28PBJzF((7PCbPjBQAD9Jns{(x-<rcC6DdrEjz_CMOGsREnL%=n^6x0_j|YQ`@# zX^nv3J}-V4PSZ#C3<tY7ak{3{i~xjJ^X$ifL`fd#reTfGfG!jXSQZ_Mw=kd>F3os$ z@@hU4;n&N@`;QoCjNy0=rX@T!kwAz6q3%ur$T1Ffdi4B8)wMq|zehIjBEo0ZrbJ_T zNy5o@l8(v{nDh<!A<!L9cYfZ?vBz~09u*N<s*eBewf`LQ)5I|;m~xg?M$_vcoh*V` zh1gn~$XoJ%JLq*KR-nZv5rFXe=d`0`PegdJ)2VaG5=Xgc&X{-;7kSPN7Z}pw3v2{< z3N6(>V)A8O!oSf3U~ASH(`VqGbdLsDD+OSX9OBA-FeYpZaVoMo;4`{Gp)bmNE#*r` z9F7~1el=f~0O1HaBFw+coI2RYg_jfD#9@?6{nX%Rs~!F;5pq^0B)7!*Z<<l2ypm%= zP$HI-K=p{XPzj!BpN%#JwC$A#ZlJErxGJyeFh^l3f15+4jptG3Dvr;K1HKUtPA<*? zP1gq7qgb`9`loegbZIs)pCZ)fyof0FM)V#rpWkdQ^|!UE!3szE{<hwn_MD#?s<s$R zmnM&oxXvO<eEn`<%%$#SE`Zk9BfyQv`{7cFbWkqLgB-NNK6MKA>Rgu+lLh^S_QDQ! z^?~4c)bBda?<pAp&D<(W{UZPA6Odw@%*7L3j4E0w2LLl)h9N_sA)`=(v3qSH&(e9K zCqFmGnA)AOe&vdvkiKmYXR^u0h#hjjGeT1&GH=*sU!K94TvOa^;Fqw=H5W4~$6J3m zZ}NT$9n4;pKH5D<CLhf^8Dsg=MMHgYeyYvDg(@s3quq^tBXU>og4hXmN6`aIflf$7 z1%7XnDsp+_GvtTXv@(9kt{1A`+S1Y}p~G?bxzSn3<|{p)M3=ytN^`9QvVIv(7fc3q zz=A{T_Ge@JIutNlE;81_K<9FNt}VT;T_38JFsL$KDQF+<%5JNAV#Xw%j&&feHC;Nb zRb{;7zKn-0=fi7NJ1J%cEib<c?XCWeTx?6bPt&KBgwxjQs`~>#b)>z<0v`%xZYeg! z_e^Bm71OO%lo2>vFUGrMoJ8Y-R=|<D*Kv<a<{{Mn=xK8xg`!R2rJrzyZNdCt5ZNM} zE{nD6vFn!$gN8s|VfsvVd8dw_b1ATMDby*0r%I4cf%$VIr_mEV(~n*QQk?ptap?BT zhuel}1<u^MS;?Y$@Rc@plNisLRB`-RTzdztN@88`u&*sWt$yBG0YguJzjs}8_WsT0 zRGW;S;OZqjEgLv&=>}A<L>F_Yimi&l)B6>=&;uGcvqFn__tU4zftoiPImFhiE^~&y z2$~oSBtLsyS1l;|6kH7Z>WHVQUGdm0xp)K>!ey)gf>{1jq;%$VC{+0i4$^(z-m@B> zQ0pnb`6jmKI=g+7YaNsAyt2gbSH&lW>Oh%2Wqi@)d)RUg6;8Fs7zh$A!;JSXQej3C zjR&>H@jUsP@uh=Rk{OT^=9{s)E%NcP1@)OtRC7(nAqIj;;$J{7iQ_tGgZmKmpqMs; z3)SFXRVV}<4sKjsJ<&#qSwfn~yw1HQc8#^XdZ2>l39IycP&#9|qf9!MQD};FOqT_g z3rquUVdyDss!c8PDENQ%kt7%KzbY|67m?`4(bDhi<ZtQZ8RyXtYVc_kHSg;Wf6bQY z`S9`Qx5+YV(ce|V=40_@I!1=<b;i$qQhyha<R0jzq-jX5XdV%F?^fWddaZe}u&(`Z za}B7}`0)qH5pw^$Zw)Ch+wXM492a_#d!G-(25B~9{q*P-%A{)NyFP8dDT?qN6rpm; zuvXrK`>_sX&(XFu+rIez>&4?PqF0ZJ+ut-s3gbmEp@iG}g{J;_C)qeiAyjz6M<E(2 zSA^UC)~Ih4AQstto3ygg^`K2fI*0YT?p<9mXn6cHm^}0@c5=OYB(#G8msITBI0eVN z-$XbyChC1nUYIZK9=p;`J@o5Aq)$|7#TsY0a*{D(1VrsG^-{oSxMslZdAzQ@z!ONi zUaW?`JD>N+%&?KZyI9HVoC14%)=?w|oxmm=tk9nsuBDY)&G5#sRR6p!+j6sCSnZ(0 z6jUxFP&!qzcj2x9Qvt>w5`h&kW$>i&QZ4u$^qNpcYzO~_fNvp$DdAI}Mm?e?s-nxH z*XDlKPLkwaTzBvNFlxCpPTFAU;2-QPijL_0D0X^9IqX~iiyqh==tDQQDwOf~euMRv z_?Imic`a>b+N5-(|KhD@6wI11cP&r1DyFGV*cUNmVAOts2UG<8P<&HF5rlpy&lOO2 zkq;6GdrzAztv{+s4Xx=Ctd<$%G${-ohSeeB+6;V)p$u5RXm%7^J$j!O2iHrUR>Pp` zGkOWoZO)|`m$5Qct|V1OF+opi-|Mg3ye|rT&J#$6v2uGPX<7|AQc<62%K8>li*8w* z&Xy>tKlz#cGM}qJ&WrB}FetHI#bqHa1G*4qBSrEvh2*K5lX0v1c_k{A14bptY?Ip9 z0#KRUs75{g_XTsG{LG)&zMZ8DD#F+j5niN%Fpztr@ux35TE<}3V%z-2PX6X=Bp=;n zfqth3hZ0$}6W4oLeWF7SxkYm9`VKI7U!R<=1UU+6u9$SmN)84#Ci}HxJF=Y7q;6QD zZchD%bhU+?bb}hB0UApD`?46cug9<H&JHq6WVZ+_&H`;;U%p+|cK!+1=%c8fhYNuy zB-X=sjV9>=C@mn=56imv>k>tVZIvq_-*Odj^cRM|cy@+lLJ6#R3LF@QHXANM!Ed`v zi9W>&ZwgP1-8woOW47heIVl>Rp|ZMuLDy>_UI#8JXG+}%)9M#8c`RuU7{picmPqI9 z(oIU{WH)CoD8NfmwRaHFuW%bEtZB9idANzLsLMcpo=W}%zhM!#td3XksGg6rLEGvG zA1Y7p!0Q~e`x1p<@Si=^z<n;=WKxZ(7qVYm(T%mLbxKy(pLtmyL7P;0r$+mvgrrH< zB-|)_ug}xhyKu?8-#*Zu>*o-o`sehX87s9;eUjx6*?ZHUq5Rm$w~Cq<95P+;V3bly zWo1Fx;*2RyWm~f`cWTS0%}<6Zzxqr&D=c|4w(M?q_3#*4gaOJh*+!4@m)evH4ZO!( z|Kfru!i-%u*5$!VeWcWN50X;TX2D6EDmx~EyTtK>8o#$kW`V4*Y2UN6&9a7MzcuZK z@`53mA#Qx^Q5<TC^dMNYXQgH*w*ef}HC>`oNtM7aW=N>w(VgpTlXACqB(2-l(SKcD zBqgVXp@<Hq#wCJ~AZq9>+<m&Tn`vbmUl+}1x0rf{CQGem<^u*_x<R;}%`!)(?2^f* zB`q%GCE2Q|u*mcYRLvUnoXdo@J;Z|g<SS0fD*J-GW<gQiOjf(UPsV!`)Ld6uGe^6{ z=FA7#XH3iQTdSz8X8L7pv|5zKGKaO+eaMgUDsL|XW{(gcA9GRuvPx0P168I=<S)J9 zEQ4jX$N?LAf|3ND@w}p&P<JmK$d7XO+6be4{VVMh$cV{F=v~QE6|c}SDmm0p8cWG4 zo;Q(9EA7gx%eMWoklk#Ujfmzvf#+3?#Zvbw-Cs3h^9V0Yld>+bbeEyl@OIPJ@sCs1 z_+VyKqW2_C305XA1qo!5=+?>SwQ}{hHN{zBU_jJ%2lF<dVHB(rxxMhT*u^{rc*U_b zKBSl-G4pMUMygFhXHARmCg_2<m9=@S6;@=I5u2z#aWq1*L56A6NWb3D+Jbcq|1|9j zDNb5WV`Db8Pw!>;y##YdFVBZW#c}?K95{r}^mQ^h?!Yfhf8np;;!&nj0d1C1i??to zrQfUDPRnRQOhGV(axb|Y)O<Nl((icikeSWFIgE}l%|?e4ZmFpK1!4M&C=qHKcmmPp zd|Iy=HYO!%``A&ILpt3_XubaCbz{emfHjW(j>&P%j4r*6fc>!bu#t<DY;otv#{t@G zK=|OFvbvh;A}7H2^vpG5!692A4NFYrc-9!vtgU5e|Ae7jSl+0_%OoH|njxmPNTrZ* zw17b+%{Qtfp$JS5q)>$TZ1&A4TjMm#AWOIKRKW~Z8_yrF<bd_HIW;Cz1v4_HjHj@@ z88wo>N8Y&ZzA}EGPtbqNc&i{M5QR-and}_q!;lS4bsZD+jFJkm?GO5%W3QUKFb$nG zscM3ciVv)}RGQN&o7IfRyf{8)%9agDRfR9rF7+ic^`L{i81M$yGeev@NHV%~65Wbt z%+EYv(4XI53%))*mBI82+|W{Gdct+Me4!HA3I4UzX}%w?__!2E83-)m*l6*M$S8Ap z{*+%}Yy8*dsmbUJXkg#r`fDNgf^_A~6$5fQnW5JvX|7|54Y?emMM~!J$k@}YMr1nz zS+999Z0vH9xZbpQA7c=OTag*@FB1CUJV0F%{o`v=_^q*AjymhBChbm!Azi%<_e+iV zM~lL{+YBGpIrn}kn(3%Oo8m>-WATn&{oW@bQX>y$caPf1XUx|eL%wSb*hW{{rI1M| zHp5TjkWz-RU2I%g7MPBYm0NEtW_5##9(zjFG4FAPFG@MY+Z&Sd>Z>j0k;Nt4sx&zH z<S`SuEE5M5{HQH-X`zVm$pJh|&oZ>?-mOh4ng=h)D?=oOL=Ty+L-f|Z-eG+$=JkTq zqzg`|_!6zlrtOPfVAuQUGe^N?IXfrRJ~TAB!l~9EB<mNkC?fdr%9R2qR8kCbtZOY; zF2~<nNf_l4kQ%@@6)t-)n2|IjM3sD!yr#41eXyWpdgP2_<HuQ{_L<iF@zb|{H@g_0 ze24*dgP(2bR~bt=jeS1W0Hktc+CRTwX>#896zIgWnd=y>wUgC5We%fzl#vw^N|teg zmNjt^1Ib}!cH}DL;__4!LrTIpp%sb<B@#HQs55%EeBZsOE)h9Mqc`_(zRZ^;LedNd zlc;MHzpq~Sfnj2YZ%wHB6!2&H_s(@MvW%IZg2#l9E#j$W_i#?rnp}5wTJ8M5?jS`( zrH6jYsl-QJRem56$4=TNfo(*YL=h-(gTqWF(MJ|J;^&%fxjuSB%qn(qEj8t_tzKfr zSJHII1r8F}R;)!a)2t?fS(mfG3`bjr%}IJ(W4m=`R=wjC9PS^qqS!_^wEcUc*e0FI zTdzvRv{cGzm|rtfFSOHZKq4VwD&EB-9Xjf=l!~aQ??EJh=_L6S>6e$7p>h`55cPM8 zdcnaDaIT66RLP2TYno_GHzTcC21JyMO-s3LDGP!6sKg0O9{MrBnUb$Zg3grMN}xu0 zDqo~?YVwFr9TNXpt4$0YT23qU4$?+v2f&r-?JIUNBx+hch8h+t;G4%HJMv;cq})Q| zo05eA{p`iMoa}YJ;s1}Z_l~FffB(mikTOg5tgJH2&N?JJggCZJcF0!75g|K-kdcu+ zvR6)aNH(GDk?oiV=bU~IukZVXUhntobNl^wo`>^%tm|<-uIv7|uKT5==k!gL&1n$+ z-|bYBSnS?MrLY$`Tt%f%6`wU{aceap_8ab5qNM~X{=}8mgC#Q!?1)zj(JS_}h{uJ- zL0&&&fW>tNVa>pmJOZoOKRP?HHJ^ng2GI+g;(RDG=3wS+K{Nmko4ThWu)4rnAx=li zVgphF5U6KIU|T2M^eI3=0~qfC0FIF`1yDp<xS{$M9~vKI^vSF`+V5{^fr2LrzacS9 z4O1y2@ag+vf*OdRdd4Us#}sO`a8u429})&K4E}o_qtymh&`|Rl<IF31(QGmIBip~s zde9|e$$wtLdNX4&3AY@eUlAMBzai}e<?V=tE_F05Gxq-TBD4TUGyH&7iV3{-$HoFE z)Hr+{sjzE}N`L=LEHK;{PH19v!1&UQ?qd)3@~_d*-HlIQU6-%;4y`FEKkIMw_q{;u z#|q>619NbLo;S6>h!#aPIb}}uV<|K9^-L@0nb>>j5#@KsuO_Ir+r@V0sqBY`3Q43> z-_i;b3))muI#m2*dS1!MgU!XIFi$NTnZTuf3jSf<cx40MYK0yiaAhEglJO7spm(t4 zJ;Tt9D;t$>4;s#Ke2%c_dS@Xil~#CqK>;=rJp<jxjW}3Cd;x)EC(u;xLBT2_$QE9@ z9XE09>FkZs8~kD^*{P(~!QkIs${PHJB!ktP=v6p@E+7$2%$tmr2bEY~n~#MS>b>@5 zD$RpJc-jFBab`~yzkHtbh}4Jwfe6Xuz`qF3U_VU&!Ym>6ll6FlW$7zQ_27E;ww<45 z2LD{=#TN$&khyCGP}ChE#QqF31_N00PoS_=;*RzHHL^@c_{l_Ax|hmnlzkgvfaeL~ zWXS<w_81aUI7Zq8ak`dI)dtsTSqOBIR9;fOJtTNjZC<hc>3OX$(`kQ<SeiEGySo8a z`Ud<nVw*+R<fKI{^}#1)^n!im*9p6*+;VeRq7-L6E=to20#>%ap*_J<-H-;sEC9)R zXR@;f-Dc0X9v@tpM@lSvWk8T=&z=~r?!Vwbe5BMmwayT8n9QWfJ|M61fv*gzocfD# z?=beF#+9LS>QE-*?nH5?<P-oNZU0-#7ynTSywAGwse8hJ)q%=-jG>}zSh^*ii`1-+ z+o{$4`bQCP06CwM0<Faw$u&Rsgo?D_;%3ra7+$Dv`inKdICw-z_dkbDwPUi6{}Vo3 zmU3{ukg29N;-b}a|GHSJ{+m(mqoNJB`M=(PYUzSx+`k3;+8O@|v{&a}2<Lzc+sS88 zIM*r_{)KJ~TTM8<d{PM<Vt5oB8jXab0}Qa$1!hB8A)xLq|HMw04X+R3>0H!2ka~KO zr|Khe4FtG0A=}W;fs_x+V{ad2t~!8>q}bmOkQV#8(9VbOBp<coBuzDyv=HR968;sd z$<vK-!lqT#tV#fU_p(9C!2(9^Aqw|16F(|zh6g&e*R)P%XkGIy@9C9~A1gF!<QrI{ z6bW-vOT{nb=6-F4C_>tb9$|c>=m8f=_p0Ay1RiR>tI)ZfZ=trT{EV>P=;)A5_Dtks z1z1orh2DjTc%o~ZiVydgKf_V1%qz>26K5L{3{UJNOs44*-M^(S<{BF4>30yts+he< zb2a48u~MM|6zL%j%8RxDt^whg-sjMIfNh!RQ1F)<on78k?Q1>>A<3DaW7ayF3WC&+ zSRDB4+yc&jZ|uI|_cd6^Mcd*v#EWgXfKt5)d$|{_oh~y?a(1h`tcql=Iw;-D%rQJX z9JlSNSc!xkZhATkzS(7!oTcY>K_7nDh<$sHpP7_FCiL^?Kpw-r=3u>~kynJNXOuV~ z#61M_P&7sQlv>C}?QSZfs>ck|7R;?>6g6SvJ#Cd4!%iRnwqo(oGx$p~5zBiN7PAHs zC{#3N3%$GuA2Zl}S&7N;7BhBlQ!e$D<WTiH<dcoP!oHlRm>Co0Hck=n`b&4E^{S5c z<rwY>!9P=ff0=yW+kJ^#_#EbP75K&&gGQ=@o!n6qn*;U_yVPQyiLAQ3*g^cdy_+o* zQ3UZk{awj8f|qmN+&J`@CR@FPtd$;?Von)_@4hKU#pL8?-K_vXkr7NqM4vRqj=i#< z&jN{eQ5JZ5aPH@6dOs!<Xgtn!P3rNwjd@!h=L~;>f0h!cMU_t3a!h8u5@63u(@%s3 z_BWB#JsdI^u8LEyic)$+L@(Jjfb2YMm*~4psAFac&6WxuXPK)ucTos%T9flH;GolH z!<$piSf`{Ece;J)O|)ZZdME3<6qfi&^B*@#zp9FT_sG91MSADQ{Ad&~{8}A{95u^s zF^p=w88D1KG-!rW!>#yG94T$kbEt(GSZfg->e~+5*8Z7Gu0G0l&B=aBMO9C3=jEBX zH-Nm`g2tib!pHBd+-=>}m43~3Ah7>81h>uwd96LK$#kPgZLqw6?CxM4Y${LHa5+0p zb4)(LQJpT`xN>B-d^N{^^^IbqZu|Y{9&b@kqK&|ni5ZoMQ7uqv`ICu4_|SZ7|CB=0 z#OkXx7tHg<#_#$v9uAJ#L8K`RLk_K#R~aiGotOIdD%mh*H*WRTAq(~^lNctl2yU5V zFts|AIg@m$N$nu+CEaSG0(Ph*?n`WkWMAeF4L>W!U|BO43h%ob+&Evf;VbVHF3#<f z4P<IcAY1igl;12~%MvZW)_TJ}iZ?1cqAcVM#aPXPX5|)^AOt1*^5ea)ADv=2T@pjz zT+8k)2#TKf$5(dJ4As;K9d&t>mfNbiTkuUv;ZOm69VikCt!a^0^#qH*Ayh5`1@44R zis9;n?rqZ#4D3m5hPfoaWj?M~4O<+-6E~~e@?5sMl0ff^tXEOmwO?6$kNpuhQIedp zfvZ-FQlNfWDA-<vWwasJH6oEUDl3g&S#jYjZ*%dmnCqz64Rc^Dp`{wymS>{n2%oR> zYnvcOm`|WMidIw^;O7M+@PBw}`Zc}QcXymo>Ep>97CIcbkFZ%BD2qEgG8@Eku`F5l zEM-K-IjrBI5E_R0Fo8Y)G~uhGyGR2Q-Ub%oROGJaF>&@s%QSvXb-hUCb>g&VSIVHH zA~gX~tTxQNiWf6C@u<&;p~*t8C`e8{cfZSXO#;uR^_^t7xKqcya-~+Hlmu<|v;h`s z_9XRZ-^ddW$VjK+Of4}sA=h=n@60F=1-gea^ylf^Ps<e*`&cBR>`*(GJ+=1D$tlF{ zr(A-&@951e6hbyadFXP$*@3c*frmB11%elU$P+a;Kb%USg}Dxoa8loSbnl5wp@}sU z*?>32QoogxyHhiHW5TD{PpLAw`f2&utu7T+u&_+&_peK8))hyhRA1P<K_woVqHPAH z@O3?<!38~t1aqrVc<Bk9v%<1%)Mw=`>L+Cu6yN-5p#GuD-Z`%S{MB<g3o<2l97~=g z`CBbk_FC5%eJHZW|Egg;D(7^@Sg+llFYYSA?Ox?vWK=%s(7h(n%XC=c878W4;CATT z%(b>ChGD<Z>Nm#d2pF5KrZx{pCtF@<Ji1^8;a3OSwnmbMTfFJG*QBQWf$2k(^L`PV za(Z3AL)m+3zUf1;aETvL7S|tc6v=;#P(=;fABq`(SQWdN^sWyr8P;O)R?bAWbn}~y z;t?grwuiblGOT$No!q@0YwxECi5A@rrWqqz`7WaMH{fW2q4?><_WB#vOn1lmd%Jhp zvc5Zq5S_Cp`VtkCVR|8=GlUfGsTA}~Tz@>pWrm2Yr|u!rqE#R6zp@&uQbdAs`f_0+ zLqMpr<#PDQ+T51I+}o+w0);Hv;$80c0V~eyIPRAk$FE@CpdB*74dw;ALLR&N%kC7N zLOmr3OH&z$s6EyGhgJ_&^z1$;_&<o~xJN~)rz2{HeY3GF+~i<xMEv;HyP0&ignP+x z+6;zTq0UyVVjl{V-oUmMa8M!YEh|#&88^ra5~i(lbwy}~W0^viM6@+qJVa!pC^D53 zU5elA)Jc`(-nLFy;)a?pPlPd@2bHRd;Zzx7U8|qg1L|a^F*-DbJXh<;dCEVAPb%04 z@z^F&zG-Du{IPl=H|Z1ZG-Bmu*4QF55thQ8MS3H)^b<)BlEBZn&x`$z0zZ9X(0c$x zBKZZ%n(I1!*Oa~~__>hz=@0wc)!`$Zrm^W$Ji=s`I_>knquwVrT|@=XXkdG9NDTLN zAZ&^a40I}khID6If`c4O4DQtJ#vx6nls)eajA^3OvrxGUEj98ne2o}-`CgXT(cci& z`*pqqzIrkNtoO_BRE<vj>SGP!l<!etFdCsUXxO<v1tP^Z{pLbh2yLscjjma5mXDRE zuYEEriTEX95-}rnW7_U=R`ZRnn>5@^9MnPY>69}W1hPynUF-8#{@xMU0Lu&vTNdr` zzgEX{{ZM%`i?%Ow6*kU}vd><YRoj3?Y};zg`p;9v(q(9M(p|sT{PK~j?~(|-3}-L7 zW7CExqpp(WIYVfu-}m4x;P-e^4G1y^JtqkAbg`d0WG0`GdqzPAdnx#qXS-7z&&E6+ zua&YUL66v>Lhq%i!#zJs*X<%|%bY0^^KRJz7ZtYJ0q5>jE*{Z|X1lKV$h1p!ICagy zb<ZpD_ax64-kJ!OVjh?xp4Tf><(jHaXPxori;Wx3f7U<u#%nM`C)OUliG($Mqna9h zdlz=@QSMB!OYvsGtqzi0Ynp_&Fb;6tW~Qv2y4aW=%EB3}5%TUC2NWN<*I+^mGSry4 zJ@Ju_wienO(+W;`-A;IwIyJ5-=5b=ddZSm=e;8Wh8I7&KZXwG2^wy}K+D)P;1ZtK< zgMPfh(bSE*NJkdr+y!qHvC6jMkWL;q@FHKstEe8hN^Vyc$&;oyw#s4Y5&s08ZCK`m zq0iMT-+5VqY_Vbu5Z=_fS828SHBnKPTc*ED`n#=vAm_QuJ_>I=C6Fd<P*9-cpfbcB zkixm?L^m7Xs2kiFQFv93e`(#t;3iHa@Ayx7s&Otu#YQf77M&=0evxG+TK7na-2m!y zxsKC|9*P|T*{j;$l59FSZ8H)<oYLlPve=u!p>cdWSudD`9fmJ#%$xajAj_<V-us0! zlf|}D6qj)h<md>_=yOsOT;J@HSL08=^^GFt*?pJXN7sLDfU1x|&{B>Ug6nwtp3nQs zC2focriy#Z=~K=d8QJJZhN{eso@YlSi01PQ!G&)Z+g6721M4N;;?qW8+i2TL$c#+^ z_4Gur#I1b2u4gXO&(M-KHe7~=#y{1$*M)oSJ}OpTN^foFYCY4Mn;%3&5QVzL?(2fI zogur>IR$KVLKG(t<%gOx^dSYD9W-@647<5~+o3M3TQW9tl;-@jChg-f^^DdC0>Hu_ zVvuMOXe?sHr;U8<NKc~tg-G(Yxab<~<H`Uoe}Rdgbx(h^3mv5J(z@b%R4S#HVhkt) zx^g>dgPK+EhshVTtBP(eTixQ-CTir>`7lE<%;o5&zFdMPpA7YuN}=d`pQMqaLI$H0 zowUkzA1%*2yvw~f{j^MLS65rDT-mXq&Z7LKwML$3-h*Gi^xbP)5lr=0mZ%-{4KlyI zcLIScR-c`z1~@KA<awHjgtyxZzqfaDA^zBQ%ZlZtlAz97|0834vJfok5U9lmKckwX z?8%tgWcg_0!}|~WB6OKe<pW_3&iTln?RfdGGcvvkFs>O3M`>oMw0cAP>uJ#Z?pWN0 zoNkM0_sa>LMz-s=`1!A2T@GW5rycuRS!Q8n`1)ogH4p1+j*gTKEp<j+Y@1y@PCY6< z(*_W00MKXM#fDyye2tG#owZkqhTFpVQpkO?@22N+T+d)Kn9Il#n-*vovH~7zQ3}!I zIuAT^ey6Xox9_zqWN~iX!E^PnV-xX<K`ZiUH?w<Kf=;s;dDGP5P+HpJrhFlDWFym% zbNYFZIGQt{tj)o>y;Rda7^-bq0dG+H4Vg^yzKJp`Y}n|Yf`{$kOgr$V6pFmsu3F_G zAD<SEG*x=wJ|Cq>Qu-wL2PTs0=M4LqsFL=rg_Z~ux5#P)(qnRa;_Oc6I*IO>HJz!| z!F<t&U(&|b6@3PEmssm<>Td48@4Oix`s#r&g<;PA^WEJ&txt&>19o#&RaG$=$<Jna zH^muB1(=jrqm*W&HDFtT7tJqDbGI#P=VYX3P({REujLvs9uImFrNsIP-T$IWL87&{ z)m)U*CAZfti!(^=p3-5Yrj<vrjz)0kg97(PI=0VU*mA_U;HdM&vH@mBwdlq{ap9O8 zfCJ<zF;7kA3{_o6`Ov-~i_#ZBX^?U`P{fhtRBoq@N(*9>AsW*RAVWFx9vtKT!y5p; zVna3jhCE_JU^B$n+{-=GSDJo9SmS00Ft32~dhq&JOaKeYW(azqDJhYKSpvXA5jG*d zQ$vojdY(o~4CJrcVu99HUa(0+4j<&%@1-2T#HI0VP<+_i-5`L5Y>P5dA4>#!SqfZZ zTyzV>MNmTyat|qj_9=w^Gy!>#j7AYbh*^9GEbsw--L6`KaC&iJZ^usTY@{4q$Ugm$ zN;(hR<ug?ThYQO_n7@)jeaOK#q!Wsufxk<X=2<asp05D$b<Wt^`8_y>fx*CwmlOeo zLN6M5IWlp9f8Cw{(MvsY5DN`C3Y-CV4y=qOd>G6_k4^;_^XdAf()bVDm)G<$CchzO z1qa88q0$UHAPJS8={$JXarS3591jGv>8Ky<K@Z4>LDs4TDjh2=!hF=!P}!;CrDZs6 zfK>{|6d;qY%Zo6cS=g6cRfR_!{wI&Aq{3d8bYk6NC8cz99JPIS@cN;}LPZB>yFjf1 zm?^M|m?GiBLRf7!h=a*@x?v2iIbg@*O7GjDCt{SM7w@c^i50||ac$80Wush$xB$XH zXRtN*2(&QO>7YOI%!g|ct6j`kUmyb$E-hd%VwjkryzIm-;j_tCea^Gc(lS~{?4B(L z@opoC_26HgR{$yj0@n(|(94=WqD3ntHrN-X@CnM&sY+F<am8{Ss+BcD?kv1emx7Md zsi3$PhfZK<siDxlpUh(kPz>Hf(9`8$P!t17Ub1{ojwz~fD&5gg?i&te1m;Bnyhqsn zaJsAxgj+FFGq3S&3HA06P#*uG$ld$fg3^H0aL(r*x#F-*V&de%{y&mHOaE<%jIMdv z-zOIP^+t?XOTN5S>@Crqua5(iTQ^WjS(qH5pXxdrE94bPlUzBgyu1aJqeHSDX4LVQ zZm@G)=lU?$aGj;_=?d8w?5SX~kDg~xwK;&fzI|#v<hfB~jV=8>a>Eg>)_|pvH*F4( zXDpGA_-}7sjy9#~4AiKWgLt?08VhZh?5<<pdGor9F?xf*Ug5~8BxTX7Vuc~ojB4Vr zikOhF$adkDYLlPQ^%7HhBCkd&h)qW6v4ngZWRrzHeJBN!kI0IOUlI11mikd;QhMgZ zn?_gL8QjlJT>i<fCna4_2k}ffwDNq83fth=ZAQBKZ4^z1XHC^!6AIzE|Led!bz`L6 zgC{H_s++A?>V6RmXFO5fv$y+ugvf|sc-dYHUzi&iUkh1?+d-MS*j;Y3+7T;;9Ol@< zSmbK3@Tg)(Du>ghsOFUGNQ+>X2?kW27Kj?MuOG}=rh7R&8rJ<LXF;7Sp4BV+Orc&- zqt97)h>jP;6>+loadEPPvoRT}Vw(BQzSP;d+9#oH(hT+|Qg=$^ZNP4|s)<c8dq|S` zbJn4g;h_<2@%;n3#1rXqtU0bY@CN5V_K?GSuwERKg;t#+BUL%HMr}1nvG&>9_O}d; zx*{A%DqlUYX@^dm+Qr62s!QcbR8r~m85oQyNj8TGrwgvFx-RbkV99A_Z{;w<lYb+n z6+Qyrtwp*8*J)%b<+nJHqjrBoG$NFJ73DsRg?MSY)>I~~JuY(}?hL<mrLvBf?Penv zlA~dqci59)I+2Xl-F%v+XnQOs`TLKN7Kck0yk}p3Enw&^?x@q`V#(t#DfvjSow9o! z<u_>`o-h%By@jfr0)E}ijbEs>19)&UU4_+JSv;TKor-BM{-NHCi?u)BZr9%4ls}u~ z#^BI?^{0x+F5K7C%V#>%ztbtGeY*HYVisOb_O#Wt+WwefN#)(W2Zduw;?Qw{Ery8~ zn?I;rOIH~3TC#^0-rv@~a(+uAe@?sqy?p-i{SeRH>;Vd^D%mJ)$qXTH`X#Z5=I&78 znh8Kdy98(4?k1CCN}o}cRTzF;t<uS8qxQJJ?v|Nz4n>6)&sw?|5xwrTm0jUNXbaXS zD&aQ-Y-L+}Tx`Qc8AmXd2^wJQ{K`{XD&E>wF6?_?lWXi~ICnboY>JtvOwP#d*tn=f zQx`{Km=272(QQwJ$^|}I2(K_%X_~R+Qb5Tbf|M15zV$I<DOO}fC7ku@(!xEc<);5Y zVpe=%Okp7hA@2o)#1T!)uCcp3*b7MJS7=#a_f4Q`TSj-*@^Y6dOUA9AC#O4a{V+CE zo|{e3V~CAXa5Xo7q(ZL5nlJ|vj5>(Ub0=O+n-Z75G;bf9Qj+~4EiH3pPDF6bn)7C0 zY1X>qs2B(_U<tC)ZZj{|$PCHieNK{FY*)mi978R*)UOroS(wRo_PyFWtIm-YlRbsz zluG88Qn%1%NRyS3LuyZP<X%vnnT0JTb#y4m!^$kn+VwU6*&2gaycT?BlKGKm$7o{L zs8t^2b}@lO))7Dm7+zH8mZRrsh$INy?o?T3k7~P9R{KnU+{5`9N6OdaJI*2PcWW}( zX}-!N>&_<Wn7jbNrOX>zCa>TneBnh{Vt1_uEmUQT6n}(jUp?jbCF+n}nsSc%NV%6Y zmhq1gS1Z}CMzd-dcIe;Xa^UX43<EUh_J9<(r)=+Ui2VefCqwxL1N73WkR(|X6TyH> z_Ig3#qmMPEHdz(5GPb)iP9pJm4xPmHhP!WZJE}CuA|;r#r{TDdOaoHi%eB5?NK$sn zBfe|eb!~HC&idVZx{@r>#`fDb@grjrb}-n@jR@u`iVd=hgoPJ6(z)+j5AD9za9)R9 zJnyB$P~UeUxLi~|mSsFk?P+BnCDjWgbV}hfGg%UK>+>g|Sf0QCD_armUT4~@GT*ti zNaJxEn`_33xZEIjC$gqi?y6Kf-9>1qCjsU|oj|sY>jZ(P_J=Vmv9bb*8dIx^b*hA3 zi9SK$kKCo5tZI={XCBLK;?RWhODFfbSXses*uvjikThSCH%%U&W{bLYFO<^kf$Vi! zyo<i1BydhK35CgZn$GiYwQ}gxj5qtFMx&yY9Z*xQMI94RJ^|QZDSD^dT_D6e%$ui) zYeu3bvv@FFD>_MbRG!?L^4B-=9F<Xdo{o1Z<zcs!`$7hpT&5y|Hobe2sS{?}p1Ruu zV~o_3KD*3qH0DFvLFP~aWBI4P&ZqXa@mKq7lZirH-Cspb<~wmIF=$bG3xGU(?MW~` z7JCX$Nu<atTM1jo9_!JHz>P62-&G!-wHZ?ji@9<8idYI?6Cq=Z$oRU}@MjbsT;P@_ zf$%eRra7bN>qA(2cl*Xsww8C7mPUu-r>fM_vuSxfKV~hqGmvpdNqtp(cvf-9@*9k6 zUKa$N(Yq@&ikUPN1zc=OLvfOr@2S)eteOey&yol>E{%4K)6bR~=p~Q3;KZ1jk>2&t z7j(tGZ7<;#_VRC-7k$<rBYJxvOU&usOEa1r=#0oJYkJ2I+iR6(*TyxVb(`n~`nEbo zhB)6FptSVeF-qbm8zr%HqKXd}Yu@#?+}C|_*P$;@Gb2-r!1`^qvb)~>cPzJKuI*0* z@xh-!LyaXi;(|RnkZ$rG-DKS)YtdwZb}jj%tts?RYLneR*S$zGd+dAXV!O4uCXHfb zE9(LLbK94`0-hZ*KL9!va#TgD79;sW$}KP5i_daZv1Co&S+EKDz&pk={$gzIPUvHK zQ6qyHvX!_)DNlncB&<2&qM_wSl*wl?wXmsA*9_FyYkU_!RM~h~V!xT-@T@cslM6<E zzNb)bK`txeH4PtqWrDuHS*NgJ&^oNI6PGQ+=P#&^_hS)UMO0JqM+)^B8OpKzyj{Y@ z^TSv8@Q$T+@II$&o7u=3=euk*e-Y)}#81j<H{V=BJ(@F;SMF1f5l)-Cu4GiU*V@E0 z{f>#i-#x^S!{^J>f%G8d0(}&p8O`BcIi<mulHr$r#wfNHm4oP(@_kUZkVuUZQT8xE zzN{+7ESWjh$qa9u3OQ^Qb?rx?lkb<8;kjgI-mPXCFY64)X^h|O&kEmcr(Qi5^7Kkg zCAk<o-rMkbGn@wITP(ylv~<I*h?glO5<(x`17}K?r66?vKfB@rY|Cj@5z}4*q7Qtz zyp*RNyK6iQD&n|c(7O3i>j^KDSnq~Kh_ea(7`#z7^#^r;fn^hmsizw4W+)B|%lFqZ zpfn}NzEcQFTxw%RI6eNs*sjF*+?^syF7c*>O?8zWH&{rmCN$Ck%c$ODO!HMV;F&Qe z4Yv-heA09G6~RUAu)FdXJ1#hH?69pYX(h!~C=F(<Uhha6lw)Sc<e{lIhG#_3EH}^( zd$*HlK9t+y(S0lO;K_eIrt)c=rDRH$cGgG!g^ufalHPlT+Hr3;5Y3Xfjg_$Rt0=29 zlu6_0Tx+}s!-VO8VAkN-<h|g4sbFPF-h^wtFO~S4=p@G0*`qA`x`zRl&`pR6Y=IKH zoZB{`Sc-i;+H5C8BHYDmM~*#*b$ewXQ=Rd~zvGF#tC{xb2*jJuyANIwUWA0HGm}VB z0G@g34b`x&QT?&R5*HH9k@+``e3`eYZojUP*N|_jOlmM4IlvlCH*Yafg(+zVmIu%7 zN|fu@+E#+7IjR-xu+a8gLSozw^hKTC=Q@keOl_=<_cJB9O_|Lk41Zj^U!dt!Aa;Ky z(EpmUVdOhDRmW^0nnO-diMRl^0v~PL?M3xYNjmBDz%9J^rUq+l#;JS5V+xj1C<RqK zx`{Gu*al0-%7(Ky75(njI={Wv?#`<BIP|T}q{@U37CKPGKH$Rq%7nC#mzT|oBiTN* zp202h`&|6nC0gJib3~~M?B@N3L{9f(+bjK{JM{f|pO-h^>DVTk4_J9T4~e~~d{b$Z zv)$^MRFGHulPHtEk#8(q&tmkouMdFOb_y>P7l-h^cJ?A=nQ7UB^mCw?kjF4uU^o=G zlx`>hMg)d5!O<xS|NWIQk=)bGX?Q$*lJ7SpN}}5)8s43dg5rmwvv-uBrijqOmE}B7 z$;(kPAnB@MstBvA1)mD{7J&D_rq;1cWF+v-#*(Suko$<WU>Am}lz9^r@OEeYPRF$f zBL4Y{8XoBGQ{-SwsBoM&Kk7+T3yt2z`kU_doYJ%KFSn~|rd_)CiNR&JE7sZZxN~Hu z`nE@gvM8bjp4|Ed5G*q406_2~74bj5tD_43mspkE>O*!<-N7B|`hJ)7K&RUs?;op& zGSM}BZukv(>#y}25^xIzyiFOCKm^KN0z~9=63(Nq120e%F>a4J2Pzf+{~c{@N?;1{ zj{S?@5Q2J+P9%K`_WX+-_;~}p#n=S<W>tEP>S|!dD<xXXSh;ZrUThGEu7t=t%00{c zGdnO-t!yQe%_gh#*ZPm4SP|}~YULQ(Ezu6novVHGAz>>yd82zj>EXw2#xLv-V7>fe zA;at$YE$;OFUU>XqmmQ|7dckX^0&%Ri#vr{YzjplyO!lAH6uy64srE?)B0p$uf@{c zb!bMR-ljm4-B;k^z0J@wj-nV6=kk*{m>zt@u`lfmx3l~W*}fQvJuKu5hAayu9!jd* zjqPZhV@r@0mJf@1Dg)vJ){ot1j#EVL(hRT@-zT<BVUVZjVRhBVNS1JI3s++b+$dF7 z%CnhZ1;!!{_TU)29=v}UECtT!Z^%hM^vW0?e`HaOE84S8`hTSwMG=2@fCB!&#$=l$ z5sNAu3WjtS4+<`;(Ae79n<}vc>D)1I&?LA#aLRLw9zx9Wx%`HhkfFPDQb~tTysrn# zHC}63xk?^cV-h`8MgT`9rNBK1{!-Y~II)T2hXqkt?~f8Bk5LSb<B6{Y34_#4(Q@g! z<rR6CD<d<xbFMdV`3UU$?E}Q&cxqh&0eS!V7Qpj01GwL<TmNX@4E2`L_5rs2H$-tW z<XJN8uf>JNI1To=Q)7)0lgx)g5VPa4rk^aYYZ=H>o$9pO_E@MHym~{vmy+z-XP(y% z2h1H6h)O|F77!R=UV~6N0Pb9YE>FR?sS5Rd#7$1R1=FuD9oVjZ;(Yif!D6gL@JVz4 z9@c00`XB7<K3B1yhY-K$MKB;7>=;&A1;kXc>U~1u1}NUbCyy0p;*Ax|rtV)*g8DnB z91HT|K@r+_4Y53`4(R^Lq#5T<sK8=K@_Ryb8)9TGhK7v~01hg${gsrxo>YQiYCw2S z`~yC$yyA(1E|kD0Zda4I(x$+woP*xdie7OffoP<q?0Q7(Pl9B-_VkrK<}I-C*Q2Ew z)n5Wet-tu(t#wTN^&a*PvOmc3c-lr#V7b2m?|uy68-Iw@>4d;v$4&f((B`Q-5#7%G z96DPhI`4BM8<cjQ!MZ~+o0g!$4tfKAINNh}7^s4o=^0E5*1Se+!IP>0Z!7+V^t}fN z+WAWKe|qb~e7drtjY78{)`J7H%_Y(jT536W^+8*gF~#g&Dye2Ld}Ix}08F+C_K4CS z@NNLw*Q-MGH`dVsAoFno8&E4YQ+CcQLifdNP>k%R?gLU1mvK+#tr6(@dug)lHPDql zlY`lbFMY?O<6p8=%}-U%c$<jp_A!-|>VG%Ee@x$%=l}QEh8^q$ui~B6KJ-I<%08oi zJ^4QkDWnjfchwJn-6Nnc0)k|{fUTv=fw_D!i-uLXPn&C9Zy<VYU35GUA6lcmCVMJW zUK0~NqGV$@sGLNM(Yj?t=+zVZ$Nu&O#JwH1^XH^v`S@v4OwHWxgoS3aygcrM_LRA< zvt^$Sp_>Tt)8~V?owC@j)d~%g^1m^fUg;A1uTI^6wcrWDm6&_r!^}%II|kTud56X* zgWWGRA-hmaA@+uWA!^}Jc)D{c@Rg^=<HKp))Jhd`ss#F1iCXmjozM8o__Jbz7)mi2 zA?h7PKmeW{2|x&5kz|)fj}V+3r3JDP)&0xGS4Fh??PhBF%NeCC0zC9)9w0jzUdgiL zK{`5Q@XnCRc`*|^2%9yIL<|*2TQ7C74{lpQb;p<X3_iRwj9zW9pq*E_^@#u7-CsJ& zhNUm7^`k@6sXZj$Raku}qIzebzB|0@gA6GD0O~iaH>KdA1$*s0^-|qqwu?}T&Lcv3 z9*3Xf*qLuUdmeJeOp{8J`YSuk>=s+xGAN*K#U$8^zL_=RzN=F;X!_B=Xl-cVs$eKt zhqAfA<x$xum&u9nwaqB^MJCC{=-Yln%GaB-u~$8z$k6(;0|9YaV?R(f$`voBH!!pO z`{7R#7U!zyv@U;2#*3K!SX~p`{ltNWBW1<@`$7v7PxK5=Y~G<Xwy$`-zGsIkBus4G zq}1whrLT=5kHlWIN4}=SUN?n8yR(ggONZfI=7W$HHJlDl&5bSG_*v8|wE|9w0nFm9 z4kd-;H$T#O73kG}sPeiXl~}u5>YOH}E+5FxqPSVJZU>0)q-&^Eu;*h6dGjhucU_Fm z^@lMTbmUW3bBI}O_6H{(^xqxG>Ra>w3Skm1sdQL0Oz|(=A>q5N{!$DUqGL~PpjVNZ zZ!q#`)C#>ATKPQO?4f_`v{I<I@l`#QmMvC(ywRSWvxCkaMz@t#Sf4%6iP^4QFB`LO z>zY$7mlz<pEH%jbVAa@<xfxXIq;t<}8S)lJTKMwpaMc<(*ofQRkDc!RN-ij#WF&%H z+v%pT85(5^QMznDyG~rSS&2U{<mlO39{8plWm1|)pRv;)yPBh~#20)Z4q{2YsgQgm zPsu2BJ|n%U(lZI;?A|=x%u~N8qwOzpxa4wmiY}_|9fP%;{Pz5tEZY66%Tf%Oq#Yi0 zb!2;D<EVL&y@x}3{zsa#d3cT;s&%keN@qvxX3P~!g%`CtxV3u^*Uv2PB{TMLOQ-;r z-k7?Zk})g&OPAD!;zsYgI<cPhNRraMfQh<;nN~UfT86T;u2%++pJJ1b8Bo34Lc&`P zV5=lkJX9ktP%<T4eX9e?p-hr|;o*B}-L|YXAzvdLBfq_v3XsQaE4RNwFIpp75TgW5 zDGY*1c6^};^NAa64aS!$D~BY^tezIYc?#cDI*jR-eJ!RBi3?kss^GGzxb;I{U@R}< zCL-6tv$s)U*#Xe%choHjQ50PlmrrTo=;#kE92QX8Y+y$qI2zCjEw?a+V*=@7Z>w9A zB$_CV?QVvdSgdgBG)=vuSQdNg;7?aoHKeBfQ@J;cL6TQp+Gz?(<({sF$->fF7B9o@ zEs`%?FzLz}@A9zE`ZTy&tKa63!&<!Pz%}+Y_Z5pAwfJtvnW?x|PjDfHPm7W{yoPGJ zTa4;<vEGy7L7L4)ylQ(P_=T;k*M7RZI2O5{=w2=IwB0$)Jy@c4whG7eLX#a_6!D}8 zbzPyEFD${o$Pa3fWYSuH4h1)}VwxcR;U4%^z&O9O)R-?e*LI{&8y3bGGplDtPxX-4 z*l44>#e`5oW}{yb1w+CNk-WanWS5qn*QaD#N-_9p8FW_~=r$siOO5sSnM`({^B42) zCwrV>*=&g3;FX%8yM?9G^P;@oGhaTJHy0stRcE{_$H_6vJNP==-m}2KeK_3%0phG% zE%%E83gjs)50&J}!#G`7GzpiIuH9Bv8O^)>jyHx){-SasrT{etCO`r6x}L(5B6@n* zAIoj&eWR|rBCJfE=$C$-E!<5or(Q6D_i?H8t;l(4(*~o0E4qmrOSQitE6gJT*buj7 zGPJNOGrA`IkYM-jZ%EotB<^nrNmAf%2yfnI=vitKK!d^X4Ku@==q!;!=y|@Qj;--g z&fMUj-ZUHat#9S@n@x#P*X5PD;u2JAjjF|eMcu{Z0++-c&_<QmPN`$$x0g1=c8f;o z+nC6Z>tSYtbtEocyz#bEVJymJiP~l1<J0yZt#pP|S>zZ>a_!w|eS_$60&f-393L?0 zfog)6Q_S|6^Ub&X4aY8uif7#_8_LPz$fcEo9$OL$$H!TP#7u1<2IQpFTpwi6x_$MY zxk(N5mFDqz3z4cya>B}rnC$#SB)NM3=gc(pE+_8JGpxDOO#9ZC+OG?u`7Z{Gi9d9f zfcg+PEAQ$0@+XM-o6?%2igh~8bSE)0uoHvAusaOQ1Mml)0#G%~`M90+(7`N3(0k2E zS>O8>)v3hFz{{}!3?0b;xb{qt>IP?{1T%JD5T|<51mU!;zHCI|G){Q-Z1q;_*O#qW zfuYK}6Qe~+0Nmq=f{U_cbePrg2+dHRVr^Mjxf%95o@Q~pPbJm=-!_HeMjJZN77GlQ z)PxnA*Bd`H+X|#N<vUU<RETjl6P6{88~T$*L}>vSZ<5j214^oNZq=+GoE;f&86fmU z9hSI(|9jSm3o%lY2QY$T6R;4}NVUXlZeur633~5t0kbd}SkqpF$4!cUI!zW*oi8h} zRLL88^Q`M-|H&=w`r~PWbeyirUZ`>`5JnaONmqL>hr<Y)T(!f=#szWG<plm?*Ihel z5HgRp2NV~gh~*#fU#hx;<uhznJ2VNDym%1ubcr?VFMrEn4=z{g1|J%Pz(RMe8~^@x zXx;aP->Q`RNYdMhR_`5%GlkaQLx}j>JSIl`Vb0e?&|DOLlXITbb4S!z?Z#l2*WWfP zPR#o$lYKIoZ8!!eH||)Vi%^fQUmco?(jB=^(0SuC^Yv8HnqZ6n*mxR$uLT7T6#z9Z z*A^Y@Mjz!XG!5J5bY5DlycTtx{pV-Mj<~7={6x+m1_;z)9JWSeD|<=h_#-HZG%U?= zNH><U|ClSduwNQTmry0fkpjnwW1u%0a4UmiN;L2<R*2<<A)`NQDaC!B4Y{=epUcK- zcfph<;i#<?Y)!<RG=03(htL!)a0eYY6Q!D2uZ}MJmvTxD`A8u9i3d8`)+lkTEc0$V zA`{~B?C+neH{&HyEpTA<z(ts$k!$j0(7C_k*dd$-%qUDCAn(}9&OQE^O1l1cw~14< z3@O{to=Vt#tjqZDNsT24|IwZPm@KR1?sw>Bvvz)pmbM_sIT?cwU)1>pY2OiQM}d-2 z_D3YaoXcEMM*;g2*y^H9kkkQ4n#Jt#$hpnIc8Hzm(HT<D$ydjNw}npZj2#e;rIN{D z;-FURA-^FXC)yavc70LIMQq`S_iFk=)gfJ#wf+P775#0I_17=NJUI98bw|fiJ|fKt z-k?w?a%gOw%!wS1z|t>Xe`uN$LA~rPX@FxPq0f_7m}HivPLf~Rxv+omQYRz@`p9JM zT5j7t^^TfFEQO~llAyu<Vj?B7qB<RLB6KnahMx5&R2LZKMyf@#lD9KBsp5UiKypb~ zcs}4Rj-KaR#*!hw=`|YO&N1ImCo+g7Pnyq^b7EhTja2%?=f2r4(#b(J9gW;FOeBei zy$^BWP`DWQ#!SBay0VaEhtL(RWQLNE=#UTxzc>zoTD4W^kBLAyB^_25t<4-<AcP>Y zOu!pD`0y!>Un)8J{O7Rr3qO=qXrdkX>iEl4iP-lwFpl+i`{CAn-{YF0xaenKp6Sq* zNRt*DcQhYs4fg@IU~Y+tqonNPYsD_cQlb?(;tLsj1=QX1o%O7T_**UD2e|ObTISM# zAY{ei6vr#UkgiKpl1XtRo{ZBvedYpI%XW_y(-Ou-l3~8O<cy&rDh!!^0SZ6KUd+Vd zPZoc#ny)f(%`{Mw<7&<1psD&sBG0+B8<UpK8yjT>GQQl4CO-&3vx2%xBp6-7({Cx4 z^D6TuDXMNcJzS87<!Pvos+m-!pYKl+bAFSn@h;B`2OP>Qh{VZ=Mm>ZT34uaQ4V}<{ zRgS@EX0`6!%=Cbny{~7^R=Hnw3}TtS*B~WtjkZOlAPw3~Xe3}xGh~d*rQ?R(S00Bg zxQ63@z84v2e&u#<Xq4_Meh5SK0YEnJfztOa^lnEm!p*&8Cka*#r$dUUtc|ZHPpl5- zWd77`$Y`*2!vD5+c>h{oT^L<j+8M|eZM<@t(tf!Ke%u0DCV1*V&z0AHq~BIfFxuhM zu)w&E+uZ!8n5bSZxU3iL27^Y7y9EQUhoAfN;v7wi{Y6ffq_Z=Ex#FB*9x%=Eei%)Y zyL=MZ)%WY<m3r13;Xd%2FzdKih*<(B>?HP4D)xow(e7aHhtIMA^=j0=AG}uLrTVnS z9{tkxH)Od6e$!|WLi_jD{ztS?>X}+Eij<WQJNVpDc+oUhMK65zBKVyl_5MA4utVk5 zb3hWzY@HF%-0eq!J$O21R_>Kp*(i8b%E7t(Q3zMoh716q2(Shz|4l9b?(a7=AbZ)l zo}^5}7Y$dPjm1s^j4UAqaQrACi=&NAupj&dJOM`<XrAR4*hfBM$1g~qegrQryoIF% z;HbYt`FB(zRvN|(!j@igg{Pj$>O;(42i-O~4~zvu-#;HAYmQ#3U<QJ(9Vwa5&<Uvi z`mzta-n$I)1_Uj+(aAtZgu#VuXAS&{4!@V`pS<(990S8wrV;yOs(|qw4`y;Y@JO0= z0KCA3={&2I<^%8oFbEK91YTi^IvsrUSGzA}N|g0y0lpVoxs2Op;y4WAq7Hc=PDgKe z;?5eG+YYb}-UR@G=`Vpd{F8$osMY%tn(DhGZIa;7k<~}&VF5$dYmzn)040=4Dg|^a zkr)*1UjSd819baF_3AnQ6?;Uwj+L7GE7oU8Y>g*>m2OnnMz{Uic{TzGEo_q+fSDZN z6Cb4+*p4gw<(zzNm|W@Pa5hik-Vd>>^_1FQa5qv(TZ5;hetG~Br6_>NG%1V~!5217 z4pEk8enWsN{!flo4T4yXaww|Q=uXKkSNaUY<oXX~Qm0#UP6pUc#4WJo;6y9hrRUq< z3c+H68;~ACNnfv9wqCv$#Uk$1T@G<}hMnJCp4dl&+MaZ$8kVNV0?RBy1%B{r;tNc~ zpq`9<^V!fw{O#0H*8Pv&pX|K?I<cNWdm$eAh$^3?Y%SIwcSCRdS}>O?Yo`reEA~-X zZ&((?9tBQ;+|v}hPk<1s9lk!5zB-K9+ULWd1#yN^epu;B=uY=R@bt3m?W(F29bei7 zH+guxQ4oROXbqxx1m6A5WN+mj!FkQ^fZb^Yx-$q*a-Dcs0$wJHSpWXPaAcINtT6VY zFUzBIGOrz^sjd}XI&Q$LW)BNz1Kkbq5wDpngw9N>?{#lwoqSy@%AG%oXI}Oy%8#{G z@*1!OYmeL1IG#XApe&FO$x4g^rCrsk_53`e{`56FMoP0Q+J-&^eYu#^&CJ$;V7M!l zKss#Dxe<S_q|JwouQ!dX&I^52VTpZG77{%?&_i%t&JBJ%lJpf}ldT16%pnC%^kf7I znTV~0%NV$Hp*|&i+oUKnC4XCT$HJ0>qp#%jf-(Ml=)QoJTt!R(3x(kCfeV#RZrZcH zGiDa#EbQgz3a>B2kw&GMNHH-{(B-GAU5XD&tDt=MqSG`M7ccu3q23ort-1gI>I-Fm zQ0vUiLb8jRTC>3~pCx*J3@&?A_%od{P32C7tnH_7HVrA8)X<$4#M{E$5(#Yz*92Ii z4PEoN^<PVW0JwYq7PI+_KL`0P!oQF%U>eXZj?iOy$V<R)X=yFO6Zp0k+U6)uPDb!C zm3WD(_K+kFz25>z#aft;Cn=SbOBF0d7y{#_KF?K?TUiksIdXT=hOVTs`GU`dr#9h- zF6(Hl3Se*}fw=vfloKanY~XcP<v&`?%uO|Iud-&hZ?=e^%zq=yHVx>`t7F(IzReu( zW7#&0{pjLEn&&_vLYiB8LmPG(CjqjO{lDdn7j;UvFG~m!i-<`$88(;P;)!!<mq?y3 z!kpepi|9+h5FUXqR|CZ-XMM8Gz%zC2$b=kY`r9{6Q6H01-zB@JlE(gvy1;d7Gg&G? zj2|5i_9)TBp(^UYu2E|H#4XdJ0=tv9g3WuX97)E>Oq-($MOOts@}!-6`!(I!)T)(? z;ojL#l#M4lCZf_9(B;h{_BMJ5^iJ0-DXWuokZk=(EOJTWRr8v{Bbj}5QzP~7PY?^= z_zrik;l9k-F4`wF03}@Ezi!v6|Gl&C!**joephF8?akxn)sBH&UX|#<&*ge~vX0Eh zl9Ecg_E&7H=1F&IwM$Ak&zFT{p|>b-8hec<jvG7~6ht8d{)K%E`>B7Qu+-4Jz{Q0s z$AJRI&zb)fs9%UhChVj!h?~n7_adxpzZX~#8A|oz9W{V*JZI-@X<qIB*r}Fx={)r2 znk8=J|5g`Y|E!+^6PRA`ki0Fr%Fz4)qTK50>n0+h1N&PuSmM^^lQDXAngCa5r9AL> zzl?3T9oUb0j~xE272Zb(OYPn5A%Omi!uSS4bZ?iyhmWKuwkEg@`Pj<h19!!%tEQs( z>GWzhemEE|oNn(ogaVLM&iqO_pc}q^+~TLH>V@i|hXK<Tku<`yuB^;&b_H?b|E0-R zaErG|RSv?4-y9hdZj@S@<>eu2Rk2)_gRumh9X=OalWihSO|0u~3UZMe<76_YdEfQ; z<2@WhlULAL0RSNwag`PFfx5G_09hz}gQIrj<dimoI<zL>H2PM~#dq@g8l=!3l(yX? zz&Js_)hPcFPD=`YM=}8*p|+N`!w__rv&%PkW~>x1^oPm3O?v8?67)l`)wDo+u!Et@ z69&ap(xVoM>Q6<lS{Pac!e@o-vEaf|Xru>6<0p7)24bfj5t+j&ep2A1;jbdN9>8j3 z0`6cHH0J5)fK9Tatm$BI3q3331X>NdpZEME4if@1nBv<%qkuhxi_PX0Y{a2oumDg2 zkp!_iih=HOpTR;?!F)gmhS+RTryd}bpC;{hDxqsdJNb0u8zKi|DSNPk9s)TK*M1fj zikKw<L4|SqbaPyJNbpj`DmXD&3^O5=9!>B~25>yNgXjC!d*EVx_Le;siIw*e=LGie zl>z8XBm7_z1h=0rq^d2D#Y%91_5sq9nlNPvIT}m-f1s*?@9;ss!?Yx6d<U@wbbuXV zxfU+Anin(-*3$)ybZox|U;oJATqgu-pKmYms3LWyUOffS;0z|~BG{KU%07hio=0E? z4SYEe`_<+{p+zf@D{wnp1z&0Pxp`C>Y2ui=wtD>x<}f7<uK&vta=Ku6c^*eAs1eM( z^AjGKN~&|Tj941b$SPtGv3<!X%whcW6XcIO;(?t%Zj1>?!2IDD9e6ct7oPd6g10o$ zQKrDf0{9o>Wo$k3enNqcOVK_N2tH^6HF&hMA%9%p&MX&iRHA)=4f_KAOWsHDDD!<@ z;%J1&a82nyZfVcdkO4EVa~KU|*1XXB^iwLSFBlAQ#GhbH${&wDggqNY=)lwiDAs2% z<<C1+aY8WtTuX>eq8hMKt)SbN3?<#@{<tiqUKlQSH+N5~f12BT4e}J{17Nd|13~68 zpvzcF{Zoc61VFIok9NEa0Xh%`llidt-1YrK%GK30CGMaag(q`ij@qM^%$sLHZb9K~ zA2O7}w#mWSwu9dgP~s@!7h;<vVh1?NAjsQ^ZgpoU!uv^Cd+1GkJozO4=R3LZjYx3M z4&w0P{_4QM+$XNYIO%t$5+P2$w{ds5WK<btYlOE-zbfzD#3)+mSfhTl)87FefdM!t zqz7;)z~zqO65vHgWWndKz<QSc4%``J-kW=8sb573Ub`BnsDZ0EdrNJS>^Z>iUWVv{ z|M$bnqPa}|sFr<Z9nGpgjKO2xWS)XK(~lLH1O2R@@xii!>N|#CjERe?+!N@ED-nl} zC;EIu0M!R`FZ>rh^D-7NQb2+I&?5{TMqAHO;Kb)FCU_@hb$XdvepDr&zeRnEK&bnV zY3@H|2md<VuzJO?%d<k30E30cZiF4uvzNZ)AH=p{p+JQd=AnP#7X6<C#)qC-11HVp zgJ#DvEAJ`oSGc$@jKZG6n2|`1!v(NQ!Tn!((ZM<BEVMD=<YNw~BL;X2t%i4R8jtH` zM0LE#aQ&uxFfegyHI2xy(z_Eo&Du4PtUu;EU)A+sU15N(?e4oK!tAR;zs}Q2+GG`~ z0E2Fm9)2*7=<vC6diH@2cCr+lF%&p`?$1Sc#w=1`p=!SlHByRO9a=0;Pi&wsbf(q* zU=@RJ+w;dj%~4@6nP86I0fTtmAVT;Bnl_UHdmZX<_{{hiW*2+ghaWz56@(gG1{wmS zx<OArWXeHoEve(g29c$MW&$m9v0$lhb~Edbo}T9+GC$}nFMK%!AOhMDaFU$J+@P11 zYH`2dzWoZ1&h>P|jF5MJub~Cj+9!rD#0h#L(aa|wHPd_qZH2n@=hwKNts6xtQ5q>S z_&$|$hM$`3S?7uUb7LS+$Qk>nHuoPB4#<l!)Yumvv4|NMI5~yTGWqFm4E7-8kk1)^ z%x%X1%a8hFYdH(ksU>=uQO^C0QsVv?5IJ`1kpg=)-D;W1J{~aH@UizH6Q^Y9AN$$y zVE+BH3~Qc;AHF^Gr=SdbP8^zCzoUgE2khCtWcy?rIi3b!r?f+V0LNd)7GiX|KU}6w zJuQX$lHZDGlJ7)Ym+sOKFnFmtY4;y_{@~CW28U*9@R9O4wVVGOEHU%N7pZMTmXikY zD(8jaR5!yBT6!iYb8C%S#%Na_c4N4b{us6K2IgmL<@2HE`2p@P&3vJEeQ(Vy*^vKP zoe!M(C+qv)Iz^`_OLy_PbLD|oZj0c9Cy`E(Q3RVpet)P+rPFq@4`9<hrD1tuD|3Gu z%h@<Q?_!9`Rm>p0{|*!#l!^iKrDA`80)_DI5rE12*Rd0x7La*^X0e_}XH!uGJuovv zT+G%^DpAVGJp3tcVuy?@cR!T`Y%aAk={<r)eslaPuapBnQDYbutc>u)&RWVB?Sy{_ z8{kFP_|)feom+6(kK!8jW1F7GXW*JPIfb$<@J*&fU|60@JqJ|c|FO@U>zRBR9oq}b zEnjYOXHrgN8{&pbwgV&hl)z_ArtIS@0rd@V4H^CKsecUiE0P(lsB<YjqI5sAt}CS_ z)U;?|2y>E;mP(8`(Pe+CHTq<xniPXi9;*84Qf#lP6n@cM5NI11YD2Re@L_OGG4R&n zBZur%CBuJgb6ZpOlD@JL`|V}3V9VW=$mgNO1l#Q8HqaL4O`NI&4s1Xf&NukUG6Qa< zlS5TG7}8ffRIbwb%a+%kb|zL^>B5Tu&8G@;M${)AsFq~L-X22iY=R`e!f78-U~c~B z@?$wSqOnG<*~S4>{*)vB9$h`31mwdz1Ovd81yJSB=a$&2AlW`H*tb`-!5WbD!m9z= z0#G3x+j#^$!>~TyqFC<yXkr`(vp!@oyHE>ziP3b3?{Eg#2%tQlSX;iyUK@xa^SN}S ztZD5J=F8)ZyEa%Rll_sv!bd8E*s&2&)GLOM?8dU}YpaJcpQ#hs*fR(iQ%`=zv-XIO zCQ3d2se@k&<Qdx^kd!I*0*3nV2;%C-mTL}jzzJ&%tS;lfv4acD-&&MrB%$npH=5=@ z2hDoIcYcA5*QUD@f<=L@_u&7A0D|>Q1jhNVs~A6(_`3VuXY+A%r5|r%ja3c7KSSlP zz%SkU4JnXjNIJQXu>t#y8Jx$CCWrgKAw$_hjAFx0I$2u%lrP`=dLt`|=^$fi)#|9b zE)lwj^$6@I=8d<@OdsJB%$Vnp2_ymfg&ll3Wrwn5XfXDZSN>1-IFI6%o1=#?0><Y< zap)@te0yvFVoJeSLuQwbFLDY~P7js^WuR0pUmf&#f-cUmUS8p<kC5f@yzc=emwsvu zq#2El&t}lT$%2$eHzr7YVRw#m3Tq>G6U6DzFtRw^KJ?UD-@{KjKAPwGBxJI!MASd% zKiN#Rja)N)M;P&Edyd9@;50lsT7<Co*H5Oxa`C_{>(wgk{y<D<z9PHu=g*T4(hOac zL-5m63Ml?h))gXi3cc#Kj^mrsBkxy&u;zWL>wdc+ij9H&+4Kp1#TjvGtObjj%#?8< zI<yyjv^w{nNy1|wPTMfOKO{W@CA)31rUJko=)nL$&ARuAQVymkzQVM16Jq=;18fmx zW#tcfCsXRg1IT_ua!bK(xH%;G2n4`E54LdzPvKF(U_X((B?Cs+LxUPs&clbnrh(_G zL|dO@DR4sMTv9dye<6MV&=kIt{SSfrmI(9(Fl^RRzQSDe_)(_HB|+<#^+Xyo`}rbY z^K)_iXVgcFeMD<D2R+r5(^8MiZ@*K3MSd98sVDEv&|qP$ei(fS_6y(Xm4?hNpSobs zHaRsBgYj<DJPIn+(W>Q}=xmw{k2nt87t)N9|Ht0Kl>jHq@$u{d`&{(Gn;BJ`)(H%8 zYQwt(?;h$FWQ;|9>dvCc?+!`9MT>9jHDAyA-YrqF)if_xuO2V2*nrN)?EqI8>S#YR zV4MO)Bt!W}mosyX+NZ2^I+Y;`SNFr_N!o6;ZKsk3{QE?lSr11H8o=v*L;9*me+g!R z2`_qXJ#&?q291a-bVB?8*PcI}RSgc3Q#vtkNk<q<Q-SU68wjF(Y4KG&fK+{(0;gKe zG38{lpI#B1>eFX-#fnSqPuE4kL`(o}3G@F~+m{DI+4cR8y~Pp{$rcsaOSZyjvvq4k zmaIu7`@UruLdsecMV6@SBzu;TJxfEDv2P<owi(12Gjsor`+07r-}~Ip``7zd=L*-k z&N<)n-9F#t&LmC_{Zm5oH>!8{qL$glfGDY^PgZ<fTD{MbICghU=(4agJSw}5auayP zcV|cb&UJqNg{qY004*Y>c!8S?yb9<7w<-RkkEi3-P((lt5O>f2dKp}_z<vHZ<GU)d zi2djJd!0#M6^TFUXO%WjU1y@r{EfXb8B@bCpbyC|8(z?8)%t{I$gm%dC{8k8864!} z$c#<rr0MMWFU*HN5a378Zl?XhA=bGHBCuZ9zQU!>4%(^j8&hdnW5iU(LDO?5_O>4K zlM2c)p#HM{F0t4n`xy)6HsF4N#vPj_Z-54`{8J+TxBI90+vVs0R2T-raEm+uh$ZF4 z6`nKnWy;?=+fL_7%(UDrf1@2eAkUk>op=AhUN>Tg!&EHFz>e58i}e1i@%Ce*g3qG4 z0F5=O?*ODJ<1>ot*7g0y5Yt&*G{O3Jlh^ZKlN8_2cdNa1{N(rSc$_Ngd6k9+f*t6n zdy-~;35xkHvtt;&%ibHN)7C0Zu`NzbuCULAH;<nQTYgvP-hHX4?8bSzRs+j>7Klcd z;m3mE8~Ox;rX-aLS+n-QE=guOkeK2LqKlz+f{%#C4P>1WeH;ck=;BU)mhaV|H_FY@ z%5r|1Z8)S}4Lb4GccNbA)SIsD93%C+vE(9~_57RUlu|)Kwk24or9ydiQ01DG^tT~v zCiJ{Iuiz)-lV7@=7Vi$HeJaTB)n%W%^^ms{pB7b?cFch#cR}v4^=eauY<AtF+K{Q% z#jW>*!;OiiX7=B8J^UT-B)C@YPrcq_eyR$0cDpetq`YGKf`qP$;Mf=l<&uk4uk}#p z<M#+u0w`1^bm29{Yq11{gI&QDj3++mwLc%y`lQg5qY_~=XdDe(V`{)nRcO1_&B(t~ zZlI0{{8eP^Cihm-+`=0ilms_NR3bakn(7RDZoUGY4tzK%7)JK8S^#PS_&bnp3b<b$ z0&wQHh2N^uSbPyT5r+p&q>wApB8N2;5j6T2)!rCeE5!P9Mso;(<n6B)kS`&IRFTpB zuO*9)w<bFXV?WFYN5i!GoboMxl)_buT`$G2K66Xcfvn|<j}3(74VlZQ^oKq@dx-fe z>$1kfn^O0Di%Sdagl;N%i@CDZLatgYAxZwN0FXBPVoc>wgzUhQtP%iOde)C3d&}z= zECAJv7x;S%TXKQF$|V#zvtMv~iL?+`SkYj$N*@a>T~AP?6S%JAF|h<n2&M8*h=Iw= z3aW<}5Tngt<iIEhJ3|h9bnvgASa3#+fo<XE0^4%b@+_E5kz8&y<M5)esKsiP5%i4h zAVs^sfEca-?_!(#1Q|n$zL7V64E*8`<aR6Q6}6ZR9A4pi;2;14SO8|w+^I^_<uWz` z4zxapf;y&Q>9jjbAqxJwMw!bp0FI2mGJ_yoKcV0+?iVpEJcQtlqi*|Gl`)=eJ```? z5{mE5Y4-E-wqixt`y=S=P*b3(Y_EB%orF~Wz@l7*%4w$WLCP+}7ba&@a3vPymE9*j ztON6HVlKxYW6evQt{JZFXc8<%HLg5)yABl~ungBDmqlaL??sY}ioSmmCMU1Q^3&wP zPvUFKmNK<e+N7@!-KO6Z=%dNmmL_E0?Dp(ZZ&q+R{xNB4+BvMz8di44x4QW=Dq22# zKt89jO{33{=cZ--fekAf3Thbks7BO3UAjoJWMah6z}%^2Tze8k5%8kE9Gqa8sKRqU zmCRqf9QbqAc<Y@&2l^aM16mF^1b31s%%K}LmR;FnaIWtlY~!6>U;rg!emk!sv{0~5 zprPjf!ZYfTdIYzeJ1$w;%Ya<D8-jwQ(mS!cHf<cc?vS6TT^pkjp+x$gMc=r_8ib9_ zPCw93?JVuDl3bn=y5=Apr!*RB;8h@cqpa8V?64YdXWgavu)A%j_Yl7&F6V`d{fmX~ zK7RiAQZ(XH?EcG@>`Qv`Dbr214!3AeH!5Ea3XoH0NAGm&k_h@M=1z}x$MxOhKvhQ8 zFoim_4kAJAWUVAphts9A?D#yDV*yR>HP3P+Oi(VlA<*CsbSD)9mu*NrauqluAt25% zFOB*sn=XCF#Vyi;T-^sF60FD!c?pGC)KBTOr79ADVa%z;0>^~B?Lc@KVn&q-cm~!P z(^(q;aUb|C9mS#rs3KG`ZrzOY_~_;wg^s(S8s3jg)?!XWr<A}&P6PJxN{PuP0>3E( zj2!HZZbmFglpDG>B}m?|_r%Tc4zrk=B}Qi*YZs$GfR&)C%W4ahS2jBkJ@6edAzUl7 zVTQx?s2#7J(LMKMz&U0l@aB4#BV3T6oJm;GOujYX^26|!w<h0-yZ%Y<@yD7z5{#x{ z5Q4Ovt%KuWRm!o=cw~+X%pS7YvAwM;-D06b^orrJkvS3NYskOQ`3uEJG9_odt*8R+ z9Jk`HmA@nvm>Ime6d&_i&)+!40hnp<z<s!c%)-(n$2{Iqk!(quwo$qDqCz#*IRrP{ z11Hi5#dY$gn{k$1_F_$u)#g`VW)SJd3J0nA5}t2M2lhajOJB>6nSD8AG1O4~KKc6R zHE%Y3CZ!^YvSP%sO512mg2L)|r9`(ohys6xqGp#7tI1PO1MH?P<n$BTXN99r6*$^z zd63jMNWO)!l>H-<ETYYyH;{Pa=7F9rfw)<do@Y*L`y|cymG}YTk854z$CosF@6Q<| zc$-*1_c>nU74>n05gf@At4|Y6f?+ezs8X})2d}1_X&FJnWPLc`RYwpGD-q-3c#95S zho-Z@0VMay)NFVXo<7OppR_(P6oPSDX|0yhoJ2Jj3#9knDj6Qr<{52Q655VQ?`G;q zW1;LPUB*ZEHwm(w+b?gIq3&!W$=zYu@_B`DPi8ot^7Jw&(WGAFPL6_0$pqKQ`l1^O z-5t5x4HkJY>&?FCD5!(WFb0Od|K2*w{&P^pW8%#q7TITql<5ed>D?p3+sUE`1mlmg z@M*yiM9J{4Yi3M|7wRY1f!YM|HE5pTE1Mu(BuTt2-IO|-eCW+HZnTQe2hv?aBOU~x zcfBU$1*m))$~<V8I?^G&9~;Gt{*L^J4P8__Kw?HC9=NcNFjQ8DB{XTBd6l>vOj*-o z`WC1{V3@XgoK)Wpw{=iW>CiZF(~C*mKg1*r7cz`Mt*33a6%~VeTux_OF)Q^fq8R63 z#}BJt<h+Yx4EHzY0DT2?PTSHClCmUtt*0Qg`_FB^9ySX&MVrS1dHyj3T`vBkwP}HT zet5c73s=5T6T0Pd<P%-|>SLG0ERiy^zVR7*BiZ4W!h1c!8b*%y{;>5?t?cqJHSCH> zVHkgX&&7A(x%!=JPt0BXjyB#FctP_{O?rI7@B7cdBUKN;smkSiy}U}Q*$&z2Pew)` znfKhNpm3y)6<W*YR(ok!q_53gcaS0(OdlLf9Y8lGx_za8^<es`&PPceXHi1slF7q2 zfx>8MC#S5QLX{EaTkmXVo~={{s&_LP$}cB+sIJGGThhUAzD~6B)iSq+y}w#uVe-=r z=ER;N{PM&x-<k5!Gn<%SAIc;1#EhKI-#!|VBjyJh-9Cpa7aWaZ$!dGAHEQB2*9%H^ zBc_;20k@ckt~}QhJUXfl555yB+P>f8n?x?McX@rNt9JCNmMBowEPdQS&JqWr4v_+J z1RTN*Xv1pk!1)3S-(QzTU>l&@iv#?eG(AO+(+6JIe>eXuUq60BUC0)gnnD|CYh+RK zs)Qz>!+%G<1jz#Pd3Wv`usmeg#J0db`rHujO(jtk^kwtJNB|}(04$~pSnI%451qzR z;3B}<?h?ek0oEES6tOv!e_o94?c*Vp+i8xKHv2;t54?GF9-CGG1#JRhTa<Xp7H1vc zgt14F3l-~J73w^QUGn(=<H6ZKEr?Cq2q_K6@DKwW0zcM(MG0(7tW>OW(lG6^%LmkR zTlc8*)AJ_#7RS7FI~1nArug=2+Y)ME$0;t*OF@8t>#p9w*^<IgWH*;tiQIH%DB<D~ z6ib9{&*($Lr@9X<u$!NYhO}w$FsUF+$8s%&!JhD=0I5Vk+Nfvx|5o`B$_)#gZeHxU z(%K=(gF6;QDO23rStja07V0@~0Mk)5i}WW%8@RzDMu9ME#F)K`eIcp0gt^cqy1Ph+ zBmZ&~{3a*7a9wpDGY#YBdkUFewQ=4){7vEwbrm%AqsZO;EYc^x@T7T5m|gy<kfb&K z<@q~_Fd&`N3hd#+1epv1rg5ck;e2S`YaJjg;FZe`a?>&qy%($F>+6`KhD?UOmfsR_ zN%i5sl@z49d9z>A(?TJ@%%IYwU<q?pSHu%Yi!OO2gk(+5vMKEk6o6k)AR1O7L=5_! z>4hix+|xHOzlsFVfl9u!(^K%{g$qv7@gfZs584i%yQSX<)gfXwQgDAlTGII861dT{ zl2d?3aJ(yLoMk!d8h3ulB3Wxuc{)hV1C*IPOX)@)Sbr@~_V{vWbm&s`hsxe%cn{An zA$JD9fYjHbG5oe-^Ww<3=a;G@1(0d-3t#bwjqe2ZscN!Fv#E3D$(N%VatcNEwk955 zj@PBu7z2L@Jr>6po}2YVO_oqTten|1b3fRE#xNjx4F8i!2QpcsyiE^x!OK7TX_P7u zw{OfxbmWA|P<S_54$rh<gI{Ub;)2^{TAFHL_d^qS6^OFawHKysmjdt}&Euk#)!igb z>DRa8WlPJ->W72y@uTQGN++lZXiLs4WigvXH&<fn(iSzYnUzO5-`&oFE}a$%Sy301 zBFPg3@uDp-&ot(m3#amX7`9EMx!d`cNL!>lpl3YRC+9%tUO*}I2R2;>T^iA9taxNh zjU1FXre+vQHhhE7!Hqd=)R2n`ensZ_JDKURzi-UHZD*S<D%hybr`ZH(k93`&?C+38 zx{M3ofLA;}D%Jnv+b<@1{EA_qfUiu8m4H_T&Ng&iG<8}@w`1RR*Iae13R|sV-5HV@ zArEh+Us^@T@jr)FaD7pJcx3CI-kbIM6)U~K7E8WjavD(a$u1i~=%t%h_RnX(p5!@o z^1_`Plr@gP7c^_eF@f}i@Tt1baAnLfzs2PN`S^AqLp14mK~TWnWeo`5HlFhq<gMHH z03kq9bS_ZMKOj@idPTQSaMKF<x+p=6_6H^8RP=NQ|DA?ep9B`(-XBpktK^q7-+Wun z!pclP6VkE=ht21cWWux^+8UeP9E6TPzB4)@^T#U`%(SB5^@vH#@V@>gir^#V5Cy2W zld&69G2}48Sn>VX(BP28d_qFShwoxW;|HJcxx~Sgl(AXmVsyHJG8XnMC%?U)x|SHW za?tOI`^7c(N6f&w(!}VG!|y)2h3%CgNvM`44$O{9R2(yvjTj~JC4Ey9$8)XUlY%RH z@g=M+#qr#+h*Ckx(mq_C@BRL<a1wu{3}MYlyxI!Nde}bSI&rQ*h|CvA8+5)pc}$uZ zprO6&a`UI+DVy_4XD?}O=LSIEUo09OayVl?qKVbyTo5y<=VAC^%&b|+Ef{^gN8W3w z`uZ!s(9kWm6AHaVyuRjCt-W?v)kiP!pM{;WoW(p?d^)S~E;Ht$!I!nCWPDM=tR($( zadh_FisHV(b^E&9#GCsy^OP-OH{--ENBSRZR|r>Im!Em_Z*F9L%_DXoc9*#tr9KCm zak2|>6E-8>1p%huo)(*tY!=@LBS$hH6mL-SRuY9Og4V@VY+OLAf9R5dm=g|?`fnob z^4(M!*pfuJY^iNK5HL*2Sn^MwUEV7W1OA^jaiHHri3bLnf1mlak^r-w6B4lz|Ba%s zL`2jQji^DTeMl;8U2}Ko4y+N7IU%GA_nBU4kwdv`=g#xRY4U(s<M*}_1}Z0V#Zzig zl+dz1Jx0OZ?>T*<dkQzqZ+~>yD9ANRmUShOIIu)r9We-);{Q19cx<!5&p4JdOYBEx zwyuWoWjo95VDx`0UHShEB)JmK&(0;ktclvsI(Z;f4oK+`fOewR5u0DrnfE{>6M)I> z{vfBf$(tz5a>~rdJIK*iU-kiAaW`l+h&b4K!j!dG{!=^DH``Y}#m!B1bj8C%LM3J- zWpE~b!34-gpb?;6AUC@K))5KaT1})7Icdx+dJBIcIGf)OUY&)x>MO-7jkX3!^m(aX z*eD~%Ni8N#81*?yt_X2tj1(u(ixPO;Inhb{YS<>l(?up00dF2D*j{*11dkxfOre&L zm<cw*9l-<e%ee8BX)z}Z`#bc(wNJspm4_~>t<wxsTC7Tano+S2e{2R*#C;#KT+`V; zEH@#a(9iT?U~wqV>XW_i<%@(w{DsNFXb(QUj_j`+^eiL>ooA|UNz-tvZBIf2f(`W+ zE{8LEIkn~*W;!dj`ZaYD!WgiC1yx1}D@|$4DmryyW&POm$)m@DeGX4W+P=XSKA`(V zNXAtIT#L2F%rD&`Nvgrmqat4H$&2S6Uzm_wi+@5sRy3dv*`=QTOemPXa9Xl-L_*Z$ zUFD@ZYgH}OZ3YjbCW&+Sr-j-D1TRUlq%SL4eQh;U6iv@(EQ9x<9H7I<JT=_`nYz&$ zz4wmYi|A?Dv|5fI1h&8^;vO598KDt_j#ar~7sA!y5=G3u!?aoiDqxW~vn+rlLS)J` z@C#gY@H=ry<He8i;-f15#>td#$kLVqT)aVF5ga;2aJF1#&}JA7g`9opRHTfqQ4T0v z@Oju*aYMvnw5BuoI%mn@*nyx6D1P`AJkwGpKCzK#SP{BZ`gQiS!;f2W9VOnkQ2dV_ z7NL=d12y}n*}{piFOLby4(TIy&qb5%Pw4hC=y40BGP)yp38)P}eAi0749{1LnJ!0% zLAAoHnA&%feI<QSKKY2JbxL^dNRodx{03gNEzWGnZRW~#5vGi&4W4wi&w)&E85}fN z<zzNVHe}kOyxK0;dC2~*?$;{U5p@+Jx@F>s%KiY{#57~p)WNxkWU~Zz4z=~WKeR{^ zNjTA#5hTR7ytSElHUESE(WZzG*Li%H1|#MIF9i0<!d>wU$fquFz69<YW?TBD9JXC_ zZ<W{68GRouFSl>Qk{VRk_)pPC+46mILQTCvpLkA))b3+_>6cYDJvi=H!EyDJVFxoU z8^Yzic?IE(JiiW|(}%?r$$@dEXOD6(O`hQ=ptw$sZB+a7Y4|yj=7xn=bJ>v{P-*q_ z{a#YWP3Q!t>|1sm!e--|HAh=EBm|GP@}J&FYJKWd;OKO}*EV)Z$-(Zn*JyK~##nWF zF3jcJ4Iaq@8S-;gu8Y^Lcv`;~{0VXVDLZyKr?Yr==!6kFb~ZX@n$dqY=t3#p_^CWQ zBM{H~W`{WLs&^7PZf~Xd7h_fPL=5}OPCY11mJ**lVelw<Lh^^zGdJ|CQsI3J=3d#% zGjof1MUHC@66ZM1Wj?#E<>-~c7Jc67)9Kj8)x@VGZ8ox77hSPxS;9ezaMRD@wf@po zUhhi($UN)>6>H^V9sf1s^Y1Vuv@eJb3r)H(?__;`rfxvf^0I=Kim?*>sF(6u^Wtr2 zCyhbN13K0S;I9l7SfL;?cj{PBvn-Z9#Iq5`F*28XF2^ZlcyxzLX;Jf>s^1J1Aha6X zfCoiQADBj$GSal-o7u?4E@ztx6++$O&a~P?>N6^!Q%u#s=$hLp0J77`9kE6h1Qk1I zQF}p11N7XdC)X8xbne?-$MxVK^Aq#19peB+fxib|8U}Huia|=;V}Tt{xm$FOmoXl8 z_Bkx7jOv{S#dEoU^I@Or1h4@#cQS0LXIDQ&kfU6}QYtIfxcZG%8Ivf7ZE{E3PwK1G zK9P0zUt0$e97-kNTTdfE`Ho{RuQge%(t+2xBF+H7WA`Uo6rm8S%bAUIExl1p?)!MK z6~KquF5v;B6>^Ib3zB(32YDahQtAP_aw_QTZ;?k>5!}n>kVtHe#-TLXY=bsSH=-f1 zDJ4M@^L8sx!-H{*D;z*q&1s~qYdaaTRP(CyE&eO~sGxDOItP{{V?$Hb(o40abgb1* z+?0z)CVqWEyaY%s)mP-pJS`{<<Gq>iZOK`s+)IQ$MoyjoaR|nWlW=F;%;Mm!q;cgs zqKIq2f`Z-q%9mNGmzJ@To$lKCf_vWvjH|uxf)s&9r;m{so^@SuI;pPSR!;Vi=x_B9 zAb$WYIv|FahfO||fCh@@Bl*So%=atIe_j3piJ7kH@!YO;UQ*HgFdp!_f{xpwt)pI9 z03*MS2m)n=T=?cKdBYp6I8-D)_=X8Z36K8q$`*3_2>l^gEyPE#IChBv58HVBxnG4F z@6o70j7dnirMPmh%p^Wms-*EQLL6!{SaaGTm!wDFdS~&@E#=O<B*gjS%QN_eiijza z%eFgV0JMMeAb3n=g?b`cBcHU(ce0b_*yyt%kbs3RDyQ*uO=<gTG`XL6*6O?E__a(q zXE<xC92#19<Dt%P6<f#a+c>rP)ETZi&B8H#`uM9{<O`iPxi1EzyufIHO~q7Aby*n@ zs;8@!CC`mGDNhG4-^_X)cQl#l<3S?&%m>65-5;qfN;NjP43u7Fl+Cx%n(fJuh?&4M zlnFJ^jVV(xEdQK!=DbT&`9_SQ7II9qcTkV1n$j|UDzX{Dsdn7AkYP(kx(Oe9XZfmM zAuwAQ&Z6_>FGRBA{57nZ7lWe;;vZ=|G-lXVrt}g~4a)MyxXtkND#f0Rj*Y5)BhiB` z6FEgPeJY}U*;ZZf&F80+jNISCjw+|KUBZh-{#qHa!7PVaGlc=^<9x;YQ}Y9D!>8J| z&+tPYR@NYK(QFdROMvMR{`eDec**maE<blbM0@hPhA`dwR9QJdu*SgLC`oGqv^%uW ztY|6ou{*y^;%fo?iRH}4)thgMd6r$F;@ChTLTi(NF#g+nykawVpeONV<B<qq*W?)W zql=JcNB{<BGvyOZIz7pvIYkTCEJqi}A3q*LJ70J5UL%BN#&(v7Zcbw-ac7fM@pbPf z$@;>d2FK3Xh^$Bl8VNMrrpQO)u$VGzqYJNzZ?9&_%MZnguF>!6y;=^W-C=Qrdyqd! z)hYPqLb)w`FFHzJ{nV`ZT>472$7AJ{80Y~A;%T8wL0P2B;@~DsI@*E$mgDWOj?b~G z#nsR-cLhun?>$1Vb1Al3_dM~k%5$|V(ZW+Y*hjvjs&2-&2}#3+*#)*)`<8Vdja)nt z%5|xjej)~IpVrius7U<LYc_iABr=7$TW2|2{aMpK^Wa5wk{GQn%m}aAmEFI%{+i=L zz!h#Q6_@)aTz;)^TEzJ{lo4J&-_$!rAx-7}w7kEzkXHu-?Gc&kbn?Vc`=GL<0iJ?$ z(>a_zEejlHP893C3sA~S8%Z2UbaUX|_qw7YPWg(3soe2II#pI}PMYzeh#Kv@E|<G1 z^2N>dQAYx57KQcX#@-~LY)sIfTe2j}lkTUzH+OvGJA7y<A<<z8%P05>vs!46h#o*2 zE1)+`|5%0DiSWF$)9j2|oKZw}`emRnmMM3hz4F}uM*{Yc@+;Rz)?!Q(B7)HnM?$ez ziuZ=gp)osMc4fIGsF-q#`l2%3f~6MV&18ofL{x(=<Us*2z>L(}79JZpH3`TKRADBQ zKU@e~hp%nwLackt()KiH5H0gJkEN-g%1kkFn2vNht&w;#ui7kD>b2Gvi57$oHS0X~ zk~%ddi<*-~1aMe!d?lCBFK~1!X&x1E=@^+;=ixNM?#U`@sR=RvJwwHanLB4{A0YZd zz0U7~=gz?)Y`}II_92NLL9G3dA+L+kxqnpg+LQ_`0yQ#vcZ`w0Ma&<SA}#g|Ije!4 zfi7|>BXw!Z-At-iovEb<u=qd`DJ&5RN?ZLaFkr7H{I)+ME|UNH?8UQ{tB+b_FREbE zHtk`1{92Fk2elytTtHO9I?lpfkVC`MMCie|TVoYH3sTYLJ;dY1Kd$;7kl(-MtbA*o zGK)TYwQr_c!^~#(Q<(B`zt(vJ1l1Hl3R3?Wmfx)zZ)~@h!6HVx11R&`QWpr@8-rYz zi5MtmnT<G$Nb!8x1=2bG4*={+6e}=p?I*|pdvz#Dr_BV4ORP3xAs!*3f71tnpO+!K zyUaYG3jsJ6q;O+`qKetk4#X$(YAe8R0>L*b*d8RfgB){#)BblUE+c@JZLt6!F51Qr z{MjzX?Ddr@fd$gLgPkRT{#=NQ0M10@<m-%3KR_gQF=i9_-Sm}o)`*=XhoYm1wqukL znN|6AV`GfW79C>b9z~-{2O>_DqmtcEg*-#NZ-SKH%h`z5P~da^0sy$f=2AYU;Ur(6 zc$o`=5D)o=ZknBi1h5f-4(4f)^ASXWS#4fDA9P@^f~41o@!>*H|9^o}U9pyapmZk@ zd7L^&r38K&_$mIb>ImWL+(8q8GaSuEeudWky=V&L&JK2oq^g7Rck9q@np@PRPaKS3 zQNUZy3S9uH86xU@1v`-lJN;Xak0A08bEm3#F*Vdr5OJ1kl#3ODzra-@?$7y2{glqi z3wH2d=_=+7|EgekWCvvz0l5v&YSCmkbWPqge}M{61u+BRVaOReCep#3tejS~^_0sN z1neO#fJmbu4{m@}box@Grg?wi&xa!^wXKxU{%CauPXUHMA&Er<CQ6q%nd(8EpJ69_ zKtLYMeF>!d0Xmd2FY{9S{TafwS2!e3?Kemj;>`)pz_=eV!|esaP``uSsC>9APu<=! z=mL*?<b!mrp%d-tOpu2Gc7H-fywldc!P*efAb*Ek0scc}h7?XfLv!a##_c)AuFM_L zXn!nv?uI%SsBHmau(9tDuXn=#sm362tc!J4Rpz>xS<tPD!!M5Vk?pY?V<5LMepL{2 zl@o$+0!WrJ^f*O6ep)HnIN@}`6TOIwYf39iNq~YU7Ox?<<^^XF4Y9i;a35feZYjdr z_o|MEWYd8H7}I5la)2(pNqYv&9kFz}ZRcK!-`6cReD1@gcKgq6Wfcr&zK%$`*!Lij zOK=19<y?<l0~Nh@N8n^^wR*EY_1*dWvO8BnOW)%=xVZoMogcdLMsyE0WN+OSy32}L z*g4b`jzvDd=M-C#7^MlYhSa}?89{8jpZxhjS>ywZ$*}U-T$=j7mc6o64co$s&OlpY zcSm4hY5kr<EAsmbGdvH9B<M9^1wm-%e|}|!=e6whT4gC|IyqWxF{PR9o~sZu$_T)* zQr!bDlO9kFGlI^lXdbj*YgH{ia76VTlu22%+~LAD#|q`4=2jXGM3+#XSTAs!@qdV$ zS!RU@SgFb_#F~OLwA%eh>d&Q3sC7*$Pjzw%HsWCHz{$$Zo1_gUBG$e`J3-~z9in*( z>>X7R5{h7$A_z-r)sI-V)z8*Gu8sNwkfRGor~CKepW7t^Kuye5{Z55a?}FLC_zqnZ z@)8j!>*C+tVd`!DjV7{m@Au!h*(wTQ4I$b613eV_8}v#`|Jq-e>3Q%(*o!mDU!Xc- z>HDacPdx?;UplfZC8rzn-L?5eoDQq9@`@4iKa)j%EPDg7w$tZGlX$+rRv@c8%n_W3 zE#i&^aM1y^MvlTsJ-(sNn|jP3bF0f^%`ez{3%-sjRCO@eCET4e*_-Em(YK_s@S%c# zZ!^t05xn{i_3Nm|H`I@mTBtd&T$iXy(fQ!cxz-)KU^ele?{c5d!-Cqb{PMXNUai*` zg=|i+?+|p?|4z_e0|n}I9r3|)(3S`>8mjH4`fR{0ee}OCOBc;nMR!Zam580d(v!sn zcW(s{mV3l4fzYUl)a?~6Niq54{Pkk%iL{+BvEAK~%-s>#n^rs@Ti)3FuHplEhx7$Q z-o%fnm8I<w8=x)0Jvy}abwt=ajYfCPI*t5T>s71#1>Vp{bw8+v89`!%$DaN93}qk1 zJH+l-1xK-iS4aNStIc{O@AZ}`t=QfZ5B_v$t^GOqK}L|`Kkdf875QuadCCQunk*;& W$TeZU`$*Lxd2a_mj1Bb9q5lVWh0uTi literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/70kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/70kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..8312dee53939bd5b1f0122294f6a1df461940348 GIT binary patch literal 131710 zcmdqJcU)6h*FSoYCS65DYE)1VR21nVK^R0t#0E%LQE6hNcMqb7f)qhO5d@@5v(Q_l zqlk1OHB{*mdPq6Bo0<20Cd@oD_x|qv@8U;3XD4Luz1CjqyXp?@2W<%2cJ{Q+X^4S= z0lEhML9{+d6WRiX3=A8;w`}|{F>d^3W@2JwVqs=s`TajD+g27<HdYpvtsGm~*f)N_ z6DJ2d=f+@Tl0QDWg_)6&nVpq|_4hydKl(-c3~k@K#gLJkkzpUSWjh1ob_QB4gn}Rj z=HIu+0R7Jo!xly+W)@bk4G!=J1>3;(85zN*nZb_1U;BdhA*SujJN6zs#lm~>I_o~i zow5&}Cv6qe_)x`nsf{3h{DzZ18~ZN)-2#I94@gKJl#-KIP*hS@(fm#8wDuXDvzM<J z7#dwQHnF;S>$bIxt(~)rtDC!rr`N+r0gnTpJPnG7d=V8L^YT^f+vJqgwDgS3cOO6H z7Zes1my}l5)YjEEG=BNo-qG3Bjr-BlJ3KNvHvV&Ba%y^EacOyFb&a@A+MtU8V*G<F z@cR$K{zBJwK-ZRyGhp4Ii(!j9_|LeViFxlamK~=qvR-%O-6#8C>rRd5Ngt}%#ExGg z@ZE4~W8Wn%H@tsggS6i%`+r85|Nkq>{zKTGboD}<j11uL7`H=ch{9M#gThMSnPgZc zG==Wjk9|&#XPwa$#_csTcZ+4EJjlV$geP*mxTpm=-It+3;Y~13KD)GY0j4}QMM`pR zwKAAXJfK0N-(k`;I?CC#-2;WFPSBv-<n;?I<2x^^@4l}D*3yMZllVp>MRSQz^k_RC zDOFtLYi?yQspJN8Hc&reri=};hUV8f;l2aN3x=*Xt(^?|wWvkr5-=6qX~b`y{scY7 z;Y@?fXi!G(5kL0m1_XT_yqQIrmiqH~lCkV<kR+7LK8mP`(;y!jq%v>sUkrBe6pcrJ z_Y=_Cd4bhFi3T-__94YVMFw){b;dpzx7~0O%GIr-L5o5#=_mGUY42FMB@NnJ1Xi%8 zWH8DGNhWf~RG}6|6{&8Bf8h-8pU;y}wu~?hYN#k8&rt&IcJqhAql10aRYb#2`K#nx zKlyS2Fw@4?P1l2_v!V#rlz<khBj%^{yTmP-9>IvZJNg&TPpP>}3;YznUvNL_+XdE* zjWYFOD32Uy&`c?O%)IMfDg6lA36A96aX1IF7NQWZNb06R9vwDNZl4xls8$j6p5?fi zo?EXB#s4sN#-9dBK?NJ6i;dvdxpj~ccyiw-d)+$hqHrX&mIk$I-3AAV_J_xWWT@_F z($?G?r7#oVl7c1a7reY(T}Tcrca1nhH7FvtP^IH@gBvWTbFhQ(l-V4_mp6o6=Ri~M zp}!ew*%M_DjTS&G&(cnY&W&@_ti>;G0Y~5pFYh&TbyGV4cF5O2&Z0p{?4ub_=5pRT zJCL|)cv2&ge&BZ^7I2S!2sNLO<G%74oSzAF7QAx8R}49&fM5BQ&}a~wlL9v$=tC+x z*4aO)Gdqb&gUOfizip7@y3**8hiG>A^3tGFI~n3P=)X9Wu+FSQgDhFWYbHOke<xB( zpF~8H*t_c>z6YauCH5;YHM(eqvBA;_H%)`chau-qK>ZyL2}I)~i~|zc8eJMRP65;I zHAc_$)1XORb1jH3VI*uF>fcyR)1)<<2JM6!Sw<%lNP?}bD6lqj2nx~Y#;z<TkhbNH z6#LST{FJgnq%TK|=!kV#-?H9+Rik$Mn~H-8KS)K?Ex+LT8aTi$I$>dopXzKme(3@$ z4>c?cZap%AP!x$q7gH>HOl-sZ%q_HbKJim^I>YyZw9U&f;Ce5SvHp!h_dIKWkD{y3 zzR0x@CQk#>n->h3)T~rM#Q8pi2IUdkHjQxmb8Jjn0_9oT3+80Kbzio$aMj+rdY|Rp z1(wyUq#29--C-25Sgr1)m-T9OjJk2I<iu_VT%gaXTPI8{Y>b|t3FH!v{+_Lt7_>J3 zqtCc?PwU;~r$O4Vc)iwb;c}}C*50i9t)#U;S1g};srZ7P__i0NvAp4?s+^(4i99Sw zLl<_EALz<`A&Rtfb$02k{14N24!?@yGyYzETIE^yxbyFLQjDH?g}5-3Y})%@DB;n9 zT;51Yzca0lwc?1@-e1e=c`=kYbrq&#s~r)As2xG~TmH09PUJ?BQHC@q(Y%F9#1L|L zxJ=EadSiNBIo$oxhr(oUNtP^s$$k5g0$^v)Wg28|L~3PjnKPF`{N3<tRJcBj?zz}Y zlJR}F%$;A$C387PMxwRPi94PVcscQ2#6E_eNGVHzfQ@!|Dv%=kPk-4$=3%*t^CvRK zBG1Pg++=>0bPZ~`T;~=gf~R=t0u6h;E(nE@jlg4Kd=Z$yav^!sC|5KH`h_lV!IIee zVEhUV5*$lwch!D1AlK*5v14mMi2%vq>^uON(LwYY>tZ6eG(G*v^n=`yASfvn2-;Mu zskuds@YCHq!Vv+t)E@EH>2Ep%-2S``dM1!E!Ay0LhSl5{plByBWCS~Ew)SN1ZUNWD z+&hO;-s}rv3QxKv&h05|sO4I@18A){JYTew$Zb!*?BDiKOZar)m94nR>tHuq*(~KB zXBsYW+0r1pDR`N;kOpCA5cz=7Fe3600f2M)>I;T`nEt(}k&p6cuIn8Qj(ApASAs9v zW2H1@HjeQSqB^vYv#2(V692mTPu1fNj_Gy>MlU{?8(n;|BylM?E>zYY-o*8H7P5dE zMQWktnEi`H?$OO}_I8b@{){@A6W@R7>+}}woey4>h(Kewy+-AV08X0VwXj7w2A);5 z92%rvmOv)phqdVk=5;$6>aR}4zEFJMtPrpA_H6dI*7p$O7YV+uO<a(h(?nDyfbrr1 z!Vx=c!&r=TwF4280H+P(C^nl$_JMEx4(p^$=ZMKp#W3ws+P8}av12wZn~$E3p|+j> zi+tv$pR4>((2-bFQt?=M$9|(w9rasElc!V#u~*$Jxha@Y2a{EOcH-?{>-*x%zw8Yg zzx?Kvs&%iQ{3fB?G#Hcj6*6p<8EY@7P_Z|C87l7Y@%3Xu(z{NEicA~9`KPW$7;c*) zFF(m*1;e=`_aL;3U~@46sjxk6YCaj`_&fZ3+p0DcL=sw6?#|y@zTYvqOx*pabyV;@ zi@o!c+^|X`HPIE%V_zw&BPWpjvgWQ>$s4gK>o31lhOXWAQ$0>E0Xg#=s$RE(YckIi z{%ViD5?{FEsB+buslhiQ9?>{TgK#|5m#r*o^ir-(KQKGFlc5b5p##r9ms*o_PCJa? zC;H-m(6x5U(DT;>VJ5Gke?tmdTQ`BbVa(&h6CJKB#hur^J-%uE7MWZ3U0dMfOj>pV z@F^OFVVo;++E0dF#^vY-@-=PhB5oz_w%#et_P1PjwigSD1*w0-A5~@eGE$N->uZWU za7V8VW2@5%4U|9!1c+T??5quA;3kZ6K%eVO#QJ+Kuea^EW$pgNFL9fWgfRQ;J1$-1 zR1s?B7Y!n@B{FRis=tfa33_}iVQH7YQ5zyVnnxjE2=BV^>HVm)&<Og&3WmfCOe+2{ zkipHPUy_OJDz4O!!UX1uy5(by;qOXS6Z!TyZIyU<c@xo%_LhtMrNFiYBDb?HusUuA zDCH5M6J=Br(<~w515f?uB6c21XJ@DqcFle_t9lq9`)>4*C24yiw<WzG{0)fe3FXhH zV!f+2B%@;&+X*J|Yn(%?Lx@50rq#MxLuk;L1V7a~jLMcJ=(mXnA62h%X8_ddNtjYI z_N77A>#GyHzaI|`T+H<<<=H}mns5|G8gx666Q(<<FuLcmAW6npLOJhL>BD}z3kBu3 zcO*@i`vFYyCcshyo6f^7Fa#dkmasy=k~oYG{{@;2<Y%%>sR!(Jg<k%Qs-6ov$awtv z10}}D&j(7RS_yfSz(f)n@#|#xcb<&q4=7$N>U8)e@&1*VPE`EhzAb*I#3PjWIyYmJ z9d?mp<9KY*%e-bMA@@IBn=5V!3p4-Y<uF)k`Y^<3Mh*{@+WbTxyLsJ%H}5rGeyQ0R zONb_BRhQ27zY)UCAJYA@^xC*b(brKOrH*vs*;cTkQ-!hk0J++dvXA`|AzOEp->)Hl zn6i`|G`6tC$ymeo;<EMk7QO};>le#sUSHs7@VcGhnuXeBw|(IFUC+w)+7D}ACKmE; z5oJazPK@S$qCs1W>UfxJdjmSRy-Mz4+ABOa`=cIa46}o3sd4!g8eBqG7Pc0IYh%*& zK57Iq6$yLcRK{O5DPHo-%gMQOXV$^+>-To0B(2^Lr~M>FU-JD#3tS`MYMP$-Xr~aR z^<x)TH3aR$jm54Ve=h2n-~}yG(Zg%OD|+0R9mbRG@^Or^XKQ6d6Gioh&G<q5^oxh| z6OQ+~owpD+!d+l><dtiVl<C<rldXr_Sn#JFgrfzQ(87$X86fbAwq9>#5!rc-BzV-9 z3%X0^?c_Rt9tsYA7B=*|>$8R4tLaX?MJ(ri8^^P5hwb)LR*|e)mIE_DWyAP&E>mD- zsa$TZQEzPp`2wFU+vG)S6}_oHm{uimq%HEhGNaOzIe{R@uYgmD?`$)!VxPDC^y{_P zuw#+9Yl{~&{_X^pxEzC&C@#u(S`b;3Gz&trZ*Ny?7`SV6_<2X<%;jl3*S1rK%Z(g( za~>)f%ZlF%c*z+TdNKs^Nae%X!92?^@2>D#XMQb==6<UkftOuO9D;tRz9DAFV*(wg z6e4vGe6+CX8dU1;V~BG6B2GB(b*+{4nE4!*;@yA%1+4<4&^bM<8zD-aJ&61SH)75D zcLvQqsJYi~(Bql!Jk%chvCsJI2dHocKoVxcESe`Nx2#${WQS_lC}u)k@CpbFoGk#O z!zR%)VJq@aP46o*;Wa@-d<f3WK8Mm&Xa0|OVb99i+P(JR!H)hhn4JchK$977gP^Yq zF_Z_`xsNnR%q-RQ{xPP>exCI^*hbvJhm$r?)}Rn@CdRSkhIPT@hm&?|kE@WrqEX_8 zm(X(&?3^3KvZ5g5z=43KRqtNG03Jl5k7&>eh-HCx9pFhy+!6%Nem5ZH#3bA$Lw*~t z7fiiGgGvu}LPl*^#{I2hM8}(@(%Or^_)i^su5jOn{Ik+2*A2a!SX5owJWRkn$-Cq8 z<+Vpa@lCE4A3<m>uQzM>K*i{j!>YQ&hYudfz0(%)OX<myvC1=^kp@-Qyx3nkN3zrH zO`F_<t|)noU1Cqr;Ig-cx2t+4+gV@j@G;KNc4{seC+mt#^z%L>;_@jw7t)?D%o{|W zBEA|jS6E&Bx?RQY>DJReM|WRSSs?+#P(@A1Z$8~oEr@$km;Ek$N;c*01;4sJVK0L8 zYvn^aGqI#W4qa1w*H1--p-NHrKJ0@My>66$8Wr?#9xhlG91I-FQ88^=z0uL1=^7Fv zobB1mqudO6#^=?{^ACD>VRlx%{jw^_Vqv()ahhQ)%+c(3+!o`Z-UIL);&r=d;o%4i zHoYm;a^{-pxiX8b4nWn;vp5oQuZaD;8NVMmdeusOcm73iY(QTautSzu=VkpFb1vsW z7N(QmwQp`%cLrm%<KRGnz~s(QLhKFop8@m0jh+E;D5fr)^S_E}NpFqqPiVBuah+%& zx#o<N_UWW)9={pEnP-QJQ06FK3iU5b9=dw#Q)w5*I`sSQ`?pN*bzm-!Gvr4LqmHWr zr5)d7q;qr0pE)>`K6ag}R;ENB*izy!oz5sB_LC(AhX|cMgxU9a?yXIJL*&m3zh%D< zj1*87@v;JO8UNeTIm^$2CvygK_NQga{+KGt+3sF6aE$RiL*X0m1*%kK31LC*gl=@q zRat!~>XGhUjTbt6vRB`*^>ZKl@zYN^cD~~mPwG7&g=Nd+hg0et8^QSY9JtY92B}1? z$L1IoB%aT61$raHLuobu41|oX4`bG$DjEa~VQYvZ5qy+~18!vJA@U=SY#22*GBQ^6 zKyP`2k%|W7QCEnmngY|b<2ASm`2MZ2AKnAR<7@TcM=Y>ID6+gWm;qQ-f3>dX)D~*2 zp9(w3CCI7*&EEs`B`*Mc#-zk<+6ROabT8c5P+=PnBSf>+7X^HByOyeD`Q+gXrz=>r zt-(hG{ZvR`9_i^#HqBinkK+Feo*DRE2^D}6vK;|o)-Owt1^b?yN%x$%rOX^kn6<wP zkB8?<mFY1e>fQL2#tSU*ZxS-?4mG9s=qX=}-d1nQNB~E-OKkW=dZ?<k>)}sL0=jy# zM^$?sOn>7U;Dd)SwRmO^^r@1Lg7xO?pXMVM*)T`Fd=i(;6l-O6ChYdeoiWi7w~1eX z!WT1CINcI?tZ=Z641?D2mtXnlZKj1O*J+T}`<L71_6{3~tmlZ>53PNcd4#ZaREi_G z`+GXeHM6Ea>#)Se?ASUgez!;1@gsp@EP~l5Y{dJigX(WZ7ZgPIga)>TYWW&mCu<{L zE%Os<nx(6-`6lMJf@!aJq`1G!E4sJ)P{f`)jG>yG7g&7pe(0eDybwhu!<=#w*H;xA zA64=k&Oef(r8M;->gCavwe$9kur>S;*+a}5RW9cm_RdH#C{c4Iw!C;Q!=j%wdjj`y z5UH|ctdz7-6ilC;S;&<pXI%K$+w3g-RsYtF;+rj*e874$tq=;6hR|FTb)@y<c6*aM z%}gJjFNulY9G!}V+Pc+tAa#~3<Cfe$rx!#9GvB>?;FRTf<N^&U<K9ALJMf8OO+M%& zO?)^M9EL)g2M>AYecEfAKXqFsjx$Pt;rWN2PqFJ0wSpn5dASyLUN4&W*RCB|IuRF9 z8~3v!eU%Yc;4KrpWMlYIIlrQ#e?TiCM%q6otlsY!_EtjA%x9E{E7eGg7>V)yr1wbG z-rjkf@5UMBp@~$NH7qlBD3;_pR_Z%n+n4dvUn8QvH+lT3@OC7t8zgOeiq5`o$J(Nv zc-?-v<@3kkEz1Ho;2h8Sr|{4#Bhvg6OhM8@vi=kEfiFj&O^rqM*N)DUTUkTycMkGW zU#rTvr%KGOj69W>91r>a_GXE#g2H`^cf})x*z0i5#Cc-RsGjEKg=_J0dPiEH4hksn zM^#S$n)8#jkEEu+*7gZK^L5b{d>B5>?2~ivqiz-XC0;tOFe)Lx+#LS`{@60>fO(sE zFwY}a_8Z^5suTe$8pLoJP^~1>+qde~hHy@M-On3}JTY1NNXsDY^|ynP(~4F}!a)n! z370Le64`L8k<`dMRaC~qBcBp8w?&i3!*2;C7>rb2EG~-eb}uM?mi@fM=#ny%Fi1|8 z*1a#Q{Pe8<i-6t^3CjZ-*>zTp7qrEcat-8G7x*698x@rXyp=E0amH|l9SfHZU}C*9 zntsX4$l#r(ty)g{{&`YTa&2=Hr^B=N=!2{oB3pAU^*iqt2*q^exR!Oe!pcS3k8f*y z$ml;~ef#?7sYvx5aP{6J&$3Ps5t}2aPS@D>ei8Byzvo<r3KX$FZv6UkTdu?Y4poDU zCa$q;ao#gmBEs^=Sd>}$KFB;iwESbRccxCIs3$kqYI_amqb<hnm}@`2pw2$#VI;a_ zn}qzty1YN0-ZL70Ty}@z4!2C<gjC2zJI~(n?13<&5~B-S-p7B0hTJp8J68mHV(r)C zD&2Rzh?~g0U(nr8IrQOiFUO1SSC2v!w>@MqeMy6MUF_)2XdX6a|1LS7>YelHY%pK> zOU{xzA`Kl=>cZdkGwGA%D`-KR=u(#aRRt%{r(HKKi)*Nn{YKGda6@gve8Pk}C&;cd z7Pfvt8VV<nt3d^k({^cr05H8Vq!FnBNI)&E1kDd3Q;=qui3M5b8R>|PQUM+*$y-e1 z+{lKjV3>9sx(#4G8sBQzt)H2#&jdF-!>{y_*!vP0B|1U+Tt{KG2VIYEG@QHcF@c<% z!{RYxl8kX1OPf|b3Naf3k<l*XMkx>#v%H7su_N$IFvyS_Y%HJY@hmc_e~bn}$c@}C zneA{R_XM?yQU^J{0Ir%|8ra)uJW`gv#5Zu06g%vKU*FmXyeAjrM%g<^)>jWq0hW32 znraW110~0H7m@2<t24Wi4x)Q@fw;7Z88N6ea(D~o*#{~JGK+~^LWdPEcj|Jf)qAdT zVj~6a_&Qny3~_iM+@-{Z`j|^KCp-5a&d>0ZE!`pei)TRC(FoZ}xk%7{<a10RCilF< z-Cc&^#gB^OPB<m!-L-G=aU9WJunv-uuMrP8@Z#lffl=pc`huWUcn1Y0oU;%tj;TiW z6uma|=(>}=pXtQeF=l4{5|UxUQ-mA&4l_{>rx80=^Kk`eUi;E_F`<oSx*xb1ZiOoK z+{+4=J%2K546|*ZC7qaP*<0Cj&1Nj5VmEY(Qs-+ygYva!L&z6BWX`t2Hm6+Q+6%gz z+A*gYz~#3)<w>?eoHe&3qnHuVnat>8Pq>|$?IXW{rtB?^f5f658`bfaH&jtPyYGRj zPoP>us;BmB8^OL7Eug9|@v!{FJ%6PM>oV+~mm^QE-Cb+BK3L&>h5A5^+vhA{{Cg2u z$;UeIa!G)Wsd28=E4GHM-(E`U7lTX$QDXI}?-1q@ew$3n$7A+}{Fmzv-BEM#NNThs z&&V;j8xzgR+kEzxi1IJ|!g{{5d+t|cdiT}=h56?jz%6cQ8AgL{&OaWMC5Y3Y9q8LM zi0|aGLSu_sy!ha4bpfdqzptO23rcY<g7M?s$r&xM?{OWuj^j;YanU!Nbn-lCkiWNm zX+=>Tmv+tj#<^SWsrfP6t;ac^C7Ft1kD)@K>-WFHpAu@q!rZ;;ifW%=f~IVR)DIsi z&))TYmf*amg=rx;BW$S-C;IdkG{!9yq^4c9heDI7244KLNhv>UVS&p1HYAH(gNJ`> z*k<A98Nt5fa2a8HkYPD(#E&PGE{`vzS@*gu)$0I<(O6wno_vXDy6Q%#EJ&>(pCrcW zoozQYbT~CuB6}y&@$<Nm@Qu=hADXL9?f2z~!A1)_AwJ8k%T1OCV+DLZiO-&5bW>ta zmY@!s$;|PS(E~mV3tdJ2JWrFl#Y^&aBJ4fbIX~<<BI`L)nSgV!qDI43!8}mkE&2KF zwfEcJUw^2?bsYYD<=y>#eyTI81w@84AHD^VkcmgCYi;r;eEQ1U*8}!jmZyIB?zELe zHVPjj#gdwSvn1N)^=vUeFwR*zA9&>vlh4mHF;ei*#W>&lQHw6m%P+}YI>?#M$z!E1 z1jL$rIxT17YY0!^+)u5?8ew9G-yKy4I6l!Q|MkdASE_PB+05MOZp8v#b5o7^W8v#f zyD{;fLU%6e4~TYk+dKB^<n|Rz)jHZ-(2aXvvp=>p;l;xmN!9IUg|B>_;S+Xlqya){ z*AY=MabDRwkN4~j|7J{LY&dyhIgw5K(GfXgG5i9Hjm+&Avx~Rxe0-%L8hE0(-`l77 zyS>cCgv;$R%S&m*gbT6V)S{!Ymr|l$)SqH_vS*g^!IWp%{;({1whz104u89}(!hWB z&Aq2@7`wl}b93Bp@}!-RJ`>SZt1{Cw&n#PC{C2w{=iIJ~`>T3Wgk!{rUcBmp+h<6# zmpPuS1SjpO7e3!J6<V^Kk=p6XRwR&@=DR*ns^J_NnUMLjl-v^FrtqO^Pq%q(SfJEH z;scM*D~Gpno@~CTwyV{_uy^rx$-Ze1LuuQi>@2GD=)m2xAUp+-R?JGCn6XG7<r2i7 z!tL+KxwW)iM_P*7ATS+RO2$S1Sy~I(lQ8=l_@V>o@GS7TEL+qf8^}=QxgZ+ZtqhUV z_TdYbl)yBS1mZ89m#bL^FN(efC9bWBoYNcF9>x?Qmw6N(2M9eWZ3-s%uu&!3lZl@B z<CUEd0Nu|EJ^K$kd1H|#)0O|!+x(O_CQwk_ai;4gFb*-!pgMTi70gibdx_3apR|T1 z?Z91BXVK4mCwfqV%rg4s3;3HH%l}eoi>Irt;Uzk8JjnpAO>ju%Wg4Wx*MEVP)tv^R zoB-~hMqEYQx_jN?Ru{^q2*-CaeF)HzK%IqGEnWd<zYiu8u*2%Y^8YD?XTl$sTSzRx zWZ*%-z&^ebOr9}6Z|`mT<wgjKP1uRgK=iXqB6nrbFbygwuq3hd!}y<|@PeivKwVvZ zy88T|d&itAUV0#%?+b++5?(W{)%og;pngOS6*XYC+TK4zeeL6XEB*Z^gE!ram-jXP z7;8LjjKV$hHu^Rw<j+Apd{<^jXY9!5FS0CmtUJ3a6U3%=2)Lw?rA2cvi@fVM{M1sY z@$l`FCsx%vF~}hw6Jl0sV(6FTUEL9UVHgYDp)xN?zAB^zU10Gbnc}lx^mN6;1jXZ# za0zqt<5*3Pd0?6f?%A}WqF@!P(W~6TWwH)Fj65U%jhL$=*Y_m3Bd#xN@1gf1esL>G zi98=Do@DMx%Wd+Rs@DmTBS&JR`G4IetJaq8y?eg?+?e-vQ?*@$yy})83Dxe%0i3Ea zOV)^PG3Pz4U5vav+hxy~EndY{M_U|QaC`aq<cT_ysM0rC%*#)B#_Tu}w%Ow%Uj14r z`(n1@dBprFMJJKx6MQ{vr$WI3N8Ou!-SbvDdDoWAQ^GkTYS;3ftL>TQ4{Y%I5=t`1 z_BxO5h_mv{R2A{`bXA>kb`|&A^Z9v`Rf5+KmAkREpKQCw-lSB6GZx{Q#Sltmg3&_x z%eV>6w5i`LEahwCj$U3&SIePfO`(Ed!UZn=YD?a{`y!KQp2PCq=Ev9IyWXD@iy8Nx zuK7IGU3uYgd-sn>jQvi}nU6=0uN%5Q9Sv>LvoBNX7C7f8aN|PGL)`Ob$Tx~mv^v+} zb9vMr#W9`0bJ!)zd;O8VC*O|~Y*WwQ-?SbqhgUxnF}6dfU?auS<H@$9VzL1?`tze3 z_iv51;=XHM?RxRp{L<L=)~9_G+r^pQS>n=4R#AiA+95|$D{IC~ua8Q>cu4t@lt$@q zJojda>_H`Wo_Cx?3r@&eauQwTd9$us?w<Q~;L(p@p=aXzzY9eRtUJz`eGkr<=J!fb zSTpL-6^hRjj@V_md-BwbIeOJCz6i7GvwL~bh$6W~S#ECM==nH1x6&siz87x<+5TE2 z_N{%9ZlpoVIUF#zZ6PR`7KEmHGDHZd^~fn6VXiVh%DXjP*sY3WVC>*vy{FlpH(crP zZlyFm42HSv3v;<mWA<dDAKx9<-IKnPjD><MA-3K&m+bqRJb#_JZ7g_f+hxCW={S<8 z)In8+-iqGAe)GZEh|^2G#)|pgH`y5^DtWvXd5CA^XOAL%<u!4|WL-)_=TbAPCGKpL z%0LgN)2WiX`gtbMN?8k!4XaknC36km&yD*|A0nSEgp|%X<1+GuLC)Zh9+7l&chjrA z`@4_$7Y$y#_XBNVpA)Fp@n)xc$B=l2_)8;k<O)OWMe`PVh|s1VsBfQy7g+&n=I+bE z?aj8tn@mUc^;t9t+wKJjvF+VSNJOe=wJ>X=Fd9at;78R(>YOZOKw4<S6O~5{E|X0S zHfp*JR0Ok-8&>oF6r8%hd6`W$;HAI;^>3alatvSpbprx#wgPGduro!=d<A9`LF18n zr9p>PH1Fo@GQM_#L0L7<(C9B4_|wyt=A~ag2WBgqb~;}gDdhLyEF0om(sFJ&k&|7z z1ZnC(PYPi`rJkQ6xoN-{N7vz!9mcE4osj06tRJu^viV{q-_{=!&w?hfoAB_LRLm3X z7^^c#&)z7}pK~xm{M}J&>)867Nq1b4SGEGq-Kj|^LR4A&P)^k}j|uecZCS!>#c|{T z;PToqTpdO~@Kb75L^KpY4s-zhGI#o&h3)FLUcEzx+oV&@8AR`A+Qz+ADOZ=C$VBdu ze+TTxn3Wu4Aq|HSeVvwX*PLz|apmSqBg#R1kC!!-5d=H))ifvoy4TfbgI(OZar7LN zOc0^dzw6Xnm;^gywqP8*<s4H|_K81Y7MO&l)I|dLYG{zX9d?-)$RM^Ek%Q?640#@; zeI7ptD7rga(x1L1+nE-MA9F0TJ-HA|iUCR9_bt^tA%mhF<+sRk#3lU?A=zy=^Gjc) z=xjxKK4}so`KyqOz9FJTMV0NzC6z^?wz~_bfDql&cW$<~?a)mwiPUknYsfMc0ZA}C z0CKQxYfMj{Huc&0tOflMe4U=$t`En2W7`__5+{g+n@*><1mrTVno={%(Mc4G1;g|a zn~=%}Bh9ysUzU!U9!EvJ<Qd*GL~@+BkjZFKcwe<*%hhICdiVSydOjO>d?Yiq19Kzr z{PUc)xBXujez1L+V61?AgGViYXzDCH{v`4AJ}>2T$7Q{8Sl;26?96VfII%Q$o^uaO zOLv6;;M_}4OUfGbNE0!w6MS@HU#Kd}ZIr8l?Ab)s2rtBd5Fhib+%m2HMn}0(rfJgj zd;FP)i!6x=7Pz~q#|P|<oKE;oM2tU0Kb2!xjhW>e*$(G=G+gb*j2h>5E1Rc=bA8i| z#LZX=dW2o5ph1uP$+wn^$!0HW)5-PuK0==EF1RhzKXo($`hF_kab3x=O0!KFo9YHK zI1X3)so;M+9KM6vS*g@Bt+p@rc$&=~i-Fg#SVTIJIpvw?iOIA|KOzW8nAzHvWuErN zJdi^N8pc+n#fbeD`zWS(N#LFk<Mq$qwJo|9vlR*pd&noVFHYn(er_2zesl25tlWJ5 zkNWp#Z$n?$18!_pz3HruvZ3swmgKhxdi-jrBIWrVc6lk!#tGX8&2GyJixImv^hRYZ zZyPlW5$yF*B9?jY3ZLwCOGjSaw7RAdDB<Kd*@HS~)RL8LH(eETrG!azYkV=)wtc2| zY)oL~^?&RM=up!y=yLTCD}QC!Ewb;sX_2*5rO7FQTjEZ@01g>64-zd;1se(mq@}cJ zxqD-%Z&np|hcZa+e<E%@em&o1s=FkI1tBdN2K6p38e91Uh8lB7bEW(9uqINn(va^R z1pe7=*IY!;ZfKB(%be(v4h?!5ke0;PPb$+Aj^X!o6}=SS95s=Ue&7BQuBOzyFzdRl zRfdIngz+bfawD0-srKO)2ezB;HWR+KFm+|TpdkJsFfq?t^RLAQ{o3ttC-qJD&XAFi zL5YwpFC5Z;GP$TNGxXOa+7!m720hKgIOHBNm3?~d#>wo)j8kTh*H5*eJRC373`cik z_Ec6>R4h(h!|l*Huo_a?y06NLa_YQi-X0(v4=s9|s73CN9loix_a|I#G2zDMMoGG6 zedM?+Hh0+H*J~w_=W0c(3-2&~&ZRQJJ30T@r{lAGSLehJ44yvk&XejfLj`tQ%&fax zjD3dx)b8<cGX*x%?b7iMx%R|(6?{5n!IF^3EgJM|v(t&*<bpzXp92s3HHNgNKPJ`e z*qfFFV=~Q7VSE9|e9L%xkU?D)Vm)<XGp6(#?H$3c^XM(>Q<)4fbbwoGzNNR9eCF}= z>Y#F}Ltjc1<FT4;vic__86*A`a*vm9^7HwcJ>J>o_e~CUq}sb2eSC03&jmiuf2L#| z{|oNES9M)Gd_Ru{ee71GH%X>yyjGdiWbzqm^6lm~a7&T$_v0OjpcC`WzwSeMo(Z`6 z|A`i^4oZfeJfUa2JlQ?)txETE65DRon{Gq*4IWT)-hu4>`BBgUr$}sNbu>mKfdS@f zXhSc{=UUQlGOJRwysWZoq@bcS!X{2(a@^_by_9DUtHv&{81R9N(5<P2Wv(KC+#JYG zn0~;}U<0ZXy9z+~^a89E;LfLe;ll_2YR{pM0U~?cw9oiSX+&(@bI<+-(%l75N;rbn zoYxc^#{7I>yw6~N&!0sk(+~XEM<}O2o6zep(v*3s<9#58;mr+Hmqd0Kklb>8vki=; z{)lQajqlTs)S2n}=3Lv26hV^|`5{sQQhK{LKKqx-Fb!H*a70FE&~bASh%aW8XMIZo zX&T#IAT3i5nsU)AU2qQMwDCc6!aU_M$kpJH$7L#`swcqivfwoknB{)=V-KB2PVNWB zP>&L#a}m@+8d9(;U$D;;xw%2{W=mNgOk4{C$+;~5+*Lesa+C($gQXx}&@?P;h~1bd zfi!EEYKj9TGI<aWnulCT+)|2XgBy3C*ZS6R`^_<ruw!f}&~-b>cz&ZCWZ!^Vpt4dO zk+cuem_MH-p`3X}I0uw>UE!Q-pahHU2Ip1^YTGJOAn24WzXdc1L;k(!YHs-qJH|zW z9Aef5$0aw{UpMt={rBpt9cp11G{VAECLD)4GoVCd`H#-2v>GH69@sezNk7G*$Bw%K zasUYqX6M1K_P)*|{lb6uliDan<2)`S>W*+Zp0qtjs+o{Z@dL-;iCq>mxdIs-ABESq z0&l?#)Edp@oz)b<fj>j9fLCtIF$9B}8Ve12aG%=JhR$)3Z}H%t@2B#TaG-*9lh}f& zk0NDxi}E>}N|2CKJ~+kA^~O;8>Z1*mAuqGe(huXxKu~`mebdNK$qq1({g2`v-yc0Z zCg2sN5PL*p&2oi6gT8gyeWI)LfmEvKF0gA(6hVf%6^Akp48V>tvQjueWG=^$v{4p3 z28d(>o{a?%2o1aXoCG1D(&uGJYbX-0q5P(j-pZflJ;-GzAmpY84mrgJS|P!Fi3Ltw zoy1M!PRKAY03JKZ+6D@9EZHRb-j*L5<#bEnc!!(gsNTQ^fxfw!;x2fM9~_oNJ3M)y z*b8cZT^rlEBY(Ta@Wr5vMVud+9Yfi#vPJ=_I|d}3J>8uyu>je?)tB?&mNi7fl8{rz zg*w-DD7jN+?zhOZWhuV1viJQ)O3wbL;a;5+7!@m^-iaXbhz$X5VD+&?fE%hXz8+){ zuppD8@;%8t$s!)D6Z7Sf<h9qDPF{;W@<zyxcy9#8F75yZR0jylI%g5p*`z6vi-&mD zb$%TnT%#_+m!8ysdNS;}lEPc=P{6i+PlX0?OULC#eg?Wefu_2mzWRZ(<fbLj!@FDI zNm2CtC>&z>*6(P+kB*w~28E!vEKxy?_gB?vkheTYldzo!z7iV0&IVT(r~(iZjRvlF z8#X-muAdxw_#h5DK?X7|Lo}!mMCL8Zk(RF1rKBIGw_D3Y<8rxf80J01jvb>xcV3e& zuuM?I1bL{84O9wdAsN{o!iqc?MG!?|7fF&)`a;|CfK<Kt>FQ2xIo(pl!Sg(=5z@T$ z<h#7tfW*TsRA=OEaVgXaIGPSJ+X?fON7!Ngq6N`Ujw+_jo+aY<a#afin1({5US0YD zaA|e}(c&T31i~{L^fC`>Z2?;!Mm#NtBC&>%iTF{Y$wYP(-FqeLs=7IKVp<}<_^t+s znh;or&3*3~p%xY-$P??W%y>G+@1&D~Y(Pc!hqnBRv)`r3GpEEm_SmAlIV17VNb2UZ zmp?#PRJrh%_nv1@E5`CIbmV9HWEh;f(ksOD?9F*Sm#!}!SVR*9WM;Va3yk!Pzqsj) zK20WahiN{R+1^+2J>TCwWHp($h*6-SDF~e6*7}Da?X>`;S%_kn;Ex`y$B^cz%nq&0 zJapW+BHv}nRVN%P^+eEcpXS;}mSbz5W=y*RMiYo@AolUah9`2i{0j@5wJJ+-^IVVf zB;vWN`xFAktXQQV4i><4;&#L1IHECu6c;V=bzRuB_ys$a^YJM^nlh$V-zvW~t0zCL zY7}7;tFSkqEA}`i5MIpSm#9D(Vkp3{(@BBxGN`TRJ#h^#dpUPkMp0Y(k?UgTO<sQ` zzQ53K|DppP69fD-?^qA|m9Zu8Uqmw;=AC(7@>}KS%YLfhDB1PtsOLNVNATFn61WK} z`aibGRh({@CO4@setR(HJFB=uS&5bJ3y!|Hv=vLo6nY8FYXh~r51AH|?sI8Vmpw1M z_0P;#kd^h^^QK@EAe`8A$Kx+s=xiMdtToJW&#sqvF8(81$Lt70LsRG&PLcj9NFs+N zo#g*TD>y|wc(_vZ-%9#@I}=GPvf54VS&@IeN#63yU6FTv)CnZ&`(Ig5^46lC=s%b3 z`c!rD(XDC+j-@RuPQ@piuXkhpfzdw%a0I~9F?FGT+d;g(ZpX4WoBUygA6lyFo|xje zn|>bRp^v&{HnDrsM-Nze>994UjT~^pg}<;OqN7%@V!YqbUC}!^T1$t&>0*=w)4h|@ zN7CD|V+TQmZwahQ5<4{gF9))d9x$C7>IA1F-je-1sO<ol-T3~vzykalI=l>{my-nG z!WDXnM!~jxD+4b*Z--cD57szukGRJzrBA1QmpA3)H|fSzQe~#^TYTl~)Rys6yM@Gh zg#@5CXCyM^J8*yc`xmy*AyP6udRl{K;UiBSSfAtwt{FemlR9(pYDBRaV_1yHm#hRj z8OQ=RVNP9waUf6MYFH?_Ni(vk-l9TRL!U5-I${+6S0J!gMODbrSit!n8^#m#OQPuX zR9Y<v8fcwAqN?fEt<tpKcIZ~uQGU*?0_*p@cunZn|F98k&|kgzD?(ac={O{3uBNAd zu4uddF4Yo6-e=)FOwU_mahr<;=zl#7yB>Q|!OEDSk&*XEtXAli#m>8z?wwX|(KMys zOo;<sv0=nd3A8toW5E5krHq*jeKuQn$s;!-eA~I219yL!Xpcd*Rfr*8W-#80BFPw? z+W~B7xO@@SiSIJqJ5nK_<<7;n?`(dMm@uoIz|LqfJkteMT`ea(A$A(SRF6l9=uvIT zfzl$%LJ<wB<RP{)s#*e`0Lz<eZ|vG`Y#Ti&;b&L+)b)92`(7n89^kc6_IhbkmO+ZC zvVnMk^)UUlJzaqO7SCzW$s_3b4+x*>g<{OskA1d50=I=;wtQ(EeRczMOG$&tAK?sX z&>IDi@Bn8oh#r>j!cK%>sRX#*?+9@eIe8eA{gdInW&<vQKFuQ|-K4hxS5J>EDk-Zv z$8{wTHI~EHryPNW2m^7gNr8_D*m4;8CceD@J<QRLo=9z=uA-~oR&+R&%iMJ}S1LQR z_1rn9qxWAfCvtuLzgb_=2e?jqOcO{GR4qr>68jO3fxE*lS&bvx^%qM*&fIYw6(<?s z|FVVD4<OX~0ndO~P-TjK4`uis%i)#)`Gj8Y;riz}Q!~D|Tt}Pt2{j4*Xuo=QpZ$-A z4f|xnC%>MN^4Jq@C#82eZHy!xzgt!H!^=_^-cNBaFw?Wna)vmHLSP-9#HS`mgNBm` zYk=NMaE*<RIlz+3!+D4xiU(fgvu=Kh0KfAA8u@Kz)mV{&WP-{waDJQ4*$w5QM@RJ6 zT9)zv;~%#Yfe)^cUSmm-QxgRMDb=GNHmLH7DQ7q@@YVH5(Cgt`4Q$>oA#DYTbt43X z!t2{MO{mZHwxR{$$A!X^CPYs#qjNP4qU0q1mzQ4iQb2}!3ru<9edsj;U!g%&;N-^B z8IyoN`N!o+QyjLCr_T4tFFh4}HJ0nEM&Hh&Y98)~50*bLF7omJo%V}=5_&Qkz%lwA zJOl)Cu|u##h967|VD|T@cNs%;;0eYqOZmvtpc>8Lc|;@Uq~hueVqjkHkyP*Dut1H| z;@hySKC;@v@UA%hnSZ30_y04!FNtD^Drg<Z1??&WE~VHx<AoD7mr`>RhT%Zwo945Y zLx7D9$_<38l5>Db!})5!jc&~(;AjvRPat-kJ@k(LVjcxpkHx*SA2I9H%OC^T0NP(( z(mPDKeTb0e$UK!jfeR+I61@Q|y!-W>e8uP7!f{ovzyL(}!B%EBA5lWj41&BFjL-O4 z3%YA)(B}jiv`@6@0Pu0U&;&Dh-F8&Y2!xc?q=gnLhb0f1@ZAFdLsUNew^y8Rz)|p! zJ`H-#b1M>VnNA=cK~wS<Wmw=wGmt~rXs~%Vy`tZ1IU*C7gU&zXbBr)qIrI{KI4Ho# zN*z!Y9V`Hbo-1j=9SP8Xj3wImoCHUB<-bo`|IT6`ph={K{BS*J3j231rM;)-RZ7k9 z+olb87!4PPUVbc1cvzFN+_G@>d0%nzKS^WwMT-d<#4*!=UOw!j3WP;@7)A`+{>w}M zBzm>^^esTMx2cKcp0*qVbwH(FztxyYc=%@bG>f-wNjCg9nf#|+rO9t}9sZ3oe^-3r z9|_}@L}1LuG<$C1mq_UdM;Hw{tortU$_*uX4S10=Z%>1}0^i<$p+Uj_$JEtG7q-D; z+ks-4@vj>JvHB~kx(z1g0v9axN+b1)2zfP5;U&Kv28=KHOuG7Don83@`YV<o0nRn> z;}`72iav!Og_vAxGer}6QT*`a6{0<m{=gbMB|!WCK;6HqngS&Jg6;?DM?(kiyYXZl zA5B~i|K)N*OU(zdu|HIs6;+qc+t-~2yr-4X1k$cbQFu6xfTcmwHvcI7!%-bX;GBE} z0_+ST>7eBnqNRm0KwJCa2}Ga;WCa!rGweWZ-W})<*SY9uQGVh*!`}woDJa5^32~Uq zKeY3|OYqOhoP@tiz~8j?pB1wf<a__;_H^FucC;P*^o_(4{{;fJCVX#|UIJ^mg4YBZ z*2kRha{oVo<Hv@ZTxAQO`+q&+E?=Y7m&D-VCd;B99#+F`PQzROP+|$93&Go~?VmK` z#oI#o?}{4scP9Lka>|Tg))~y;QY^UetWxn%pPHv8HDmNN&78QQ;by;U_#?t`iXoHR zat`|M2lY?L`9|RKl;z^iLXcQ}1h6*1+nOSiCk&nn2un1Gb0PrPJyX4e)kh0+FL*q8 z9#@KD0yuK-b9-222#ClHdAt3S;--se-2oW#SNn|myRiR*eFX-4<F>k2!{3#`D2cLn z;aAdvrg^uj$f!Q6$1ZP<Fa~0*+b)=+9BnP<RFj0)=X~CRu@e5EqAPqiJ9MkmiJMox zr+VFUdSMV<hDCns<MIEx;PK=_x`|JRoz(J3RNu!k1JkqQNvgn-$i^kBYW@_sMK_E* z3kRSG0aK`@_ECh48a9`BX3>rw;{_;SF+~Y5&b1q@#gWYB)B3cwhYmcmG1n27VN_ko z0M?7np;L(+Q#Ar=I#u~}Lz7-3py>+n=mV)<R*Kz9T8Q<Cv}?CauU7P(U)zszRP`PU z_hyHFX5^;Rd9oX!x6B#fGRC0RK%Rvi(g!|C<A3hkJNE|6zTu5>p&m0xe(qC$+{x+u z39C?Mu<B+<6PmXF^EN*4ls3Oxkp6sxFnUGkeoL54<LHS`aTDl)oeV7(&GqSB-iw=j zT<~=O;F|#00j6%)4-J!PX?D_A9`;kz)U>;{B9CqYuhVlb)Pql-o@yJ$O#1ktTan%a z?=18hz&*+3KV2CrA9QE_*cPD&#a7~LTl|hr{yR%1^5Jz3698CW!51Ku1vSLf2;P0o zJFPH(EMnkXhDa4tMq`VJQuaJi&lR&i3i1&?sD(uC=nmv0u&Ch6Dc+q8rF({?gBMsS zkME*qQr)8Jhz}7>Mbt{W-@%R4a<_*jq7IxobD{N(D_(R1h_4yA?`pu6$+cd`>6qdF zbIT06zVXSjA(%)6o|+^4DmS#Gg%PC8>Ke$wlx7zf$k6f`dW`*dAKIid8@n5B+zE&= zK=K*BY<$$c2D>O&1Tsn_!P%K-^wk1Lx)pm9URS|CMz3DTx1=6<T)tYtv8qjjB6EmV zps>QBMT6QW?K$<y`Bc=Hm!}LR^d5d?5k<PB=KD5C+W8y%pZB<O+5b~c$Y59onP5l2 zQp)38c;>^qC=76c!n<0iZt|D@a-S=T{_Z)K3P@cm=Ly3N%czwGQfzGw_Rr_UEk)&A zNZ|yv3n_SLI><tUOr4SGf4asc3l{v}E8tu5JTQo6G-wh)joF3x0;h>7hZ=$K`rIX8 zgAgg7JH*SLdA45s!7f4^%9h5F=N}Be!dQ@$QkSlW8h_SB54<vnI?%5y#gi0uYq8mx z-Q!H>BjJG;Y3n!gF-AFsg?%9IkiX-m@_5G!(<r+anbHSlr#nL=OPta=ucXDro^LDr z^kFHAk9>J}o+ze0EA#fMna8{ZQ6Ss?i^#W`45C|~L07wwl4a9#aer7=wjMGT*59}O zJW_J&*AHL1C?MMN*8$%D(fd*!nwN>5!(ly^7evKARdyzJQJi<><xLyL?o}+Zyj@7% zpNgzim|A{R3cV7#CnC^O+{FgfTT94(znpr}N>WEFW&QSY#Y(r-l*xD8fXM{6%cpZ; zCv#$qKI2{-JS*K-|Jvo2r@^B*(J1lEuP;hsK3$3$nyP;rfo5~%ArcahVl?7!ACNaG zz4{y26JT+bTsk4I&azi}bgc?_6gxe5bQW$B%&y8jUAZF4+mYPifa&$VeoI#0{qEb9 zw%Q!kCXw<(+08#=!m6<ZZ5g6C9OROf*9(9X{i*2DO2VUy6yx@M>4E)~vi5dzEj-^Z zRXb=HN5Bg0!$*$Ht_U3d70+qdB#VxAt8meN;GB6mO1CCTvS-Qmpq^I!c3b&xoi7S( z_h;EnBT=d>M{>2a<)5JrU)6AYxMsIsDbwU)RLTCWmA0A1i#?}*IX$wbP}(fp+~;~| z5X(ATb-19Vhob?F0{s^}JrlJkE|&yWqL;7HDcl@IKU*znME7MY!J)v@+SFIx9rdz0 zhF@0FV^GMWYd!~Q#S(r)5yg#Woe5Kj0I^~95N4N;M%QfG2O>HL??E>6@2gvDVmnAp zYkFtWJGG?l*5sz!XWF#QHplJL$*4RoZoX#6?P<eJo?kDXC8aa7ou|IAQYwL^e%|f> zSoFR7`}->rlFdE!$KrBFURX)b98{J}-I;e1!|X0zV%<b!;~{~pr_1H6HO&S*K^sfl zkE%`xCHU~aC(H->_)_zRUz-ld&evEdbXhi4KHjfOOgWR+Z&Ev7=wTJ16Mu1x>-aFU z35uYB>A{Qy1P0%^&vw7jkUvIL@ZqU4NB(Ck4?X28`lhE`_Ud42omBPh(-n3fJX+AB z6^l8*JFT|m+jR}TX`@s@r*XSW&N>J4qdL-ED@$!F8`{T<&mFM}OtQH8&L!FKSk$z0 z{jmw>@n`QORqmdbo4C{(7xOW!0Q)IkS)UMH9PbR!(sE@08-G848c)!h2ZBya$e^gf zj}<L;3!XE4>z!5BtYP4+{8Fw=ugdz&H#;@69fk&DbJDK~6A0UJvJ8<t;()8h@DcZQ z=vQ{G?6tae-{*3sNt24EBh%WNpnYi*bM4FxahvGhZlY};UkVfafHE?wI&vWOVb)X9 zcaaS3*srcK`_n%U?B~zYA%AUg?jJqBqy8R0H}3nANoTj{i(874OHHxcY_GgP?Ryp_ zU35ut;@NeHukA*ZH*c}`ur_Go0d2~T*F#~S6^O~`*&LDjck)af*E(Vvyc%`ncmKRu zTx1=z>hW2V>+_A=uhj>x#2gB<L{kKSLOI^AJ(z1Jx}VrIR5CAjMqbiEZVr8Bfvc5# z^W5kD{`D`%Rc$#BlM8=T>%3Akx|;SRyQoU^&^Lk%KYPBFi05Tj8AVak45#*}-k+xV zIp5}OzT`b1;Ev^ugla$e_OX1w*WG9-53RGQ0;OG2?PIH<@hVbTFAgrLxx0*Hc0~q- z94tm$iFCzJsyfl0%nr0%6%j*fiv|@w5D&Rv1#A-grq{eqr|0C~)8Aj4X>(=3e7Cr@ z)`Oo{WIo)yw@bDyYEYjjAv0?<B826fu_vF@9?lZcpt=lbp6{gSW;Es<ik_F~-7#y& zBxid_1FAGBcE0!V-4|30O4JG%K;H4QdEItx!RZH2r5{Z9=$VX{cRh0JYxiplTnK^> zCR&M9`N)`}>pLH1bc7h2aFKP$yO++(4J%cBHK{*V81h{(qYyXFwW&5MPdc`MLfFa( zZ~HD2!_tV(RVK}kM0XNai$-2zScCRP>pIBdHOossg^b+lSG3e(S0mhvV6$?$+PU7c z-a=RNwG^qP91a~mXP~k>HvDy*XXHZ%lR4wTW9}V=&B8t3PlYvB#B`fk7F>Gac{3$P z;46P=xq1KH?7<L=?^8G0wD^{^pJ0gpTNO52``=Qr9JJ{os!3PmDEL~eFw!q<V=Jrl z#&;J1w;FDA!%yQ$Y`OKt^K=70_J@~%v2$pkf{t!~J1_c?4dY{QX$Q(ngm0tPB}>Do zkuAGu(6n*}uBB_4XSRk0?dJ!6*+<V2JXKp>u!a|zLu;>#zR?A@VdE63K7q)KFty(; z{r_(Z%9H5f;|kbGY)@Y~Hpcz+v(abEDZs&<1kubP7(b5`+yJ@4hJGw4sK#rn3(+7# zJc`5|Mh0oV?sT|XA$EeI*E}3NheAh-4HWe$3*>syT_Uxn?D+s@x`>@`0iJFc@f2{Y z5|d$k0#bni1thW^o)DBU8&I@VO&PrIP~mOG5{d98gAyS46pSTxU9JNGvjB$lvmoZL zYacEpHu`49^?9NXv?@-hP82wI(SP?FC_plYA^sttKNKb{!_^!pDzgv*>f|dk_k*C% zHbzy!s{vNd6Y<4jxBH#v^)}J03%XO5fzOy5LJ4qoVE`dNTN~K;RZthlQ|+9l!52Wl zwMmJK4C|E7eWh;otU1nIbl)E5jBEpcIw^@?1HOHp_9h+_O(t^k5Vd(vv0gQ;IanlA z{z-ITpmc0BM{yJ3StFq3r62gQ=xOQTL@sa_>3kS<3uwp%8A_vMq~XnRMau$gbsuJS zsM5ODVY{MdNj+v*V9MgSMHE>8{xY;tb^I8W1W#47|2MG?HT~B;=CmCB3^=k2d@GqE zbsenP4p-Y;qc*JGb@M4%Djg-{`WH)w5s8u1CD8lgOuzL`xY`At+=ZTB1HS2d&=eDl zY=6;>9l3)!cYAbVvDUNiO;3wl0>Qrl^dFxF97R*TIzgd)j0c2=W?H5j?4c7AF?$pt z7&Yq(M1*VbI%xkrdDK3U{+sgrj?ga{M#m>Z=A8_!!M7H|$@a=ci}&>sF)co;E6JM( zzvMxeU4^dE%gLloOx45hhKgvL6Zh`x6;qbFi)Mg-v@q|0km0@R+kw~iC!v2^H#Z#! z&0Ux1z}cbuOW(N4((gFVY?g#~^d)8%!(hUvD+>oc*bd{la|Vzk*jc0?BqS<WSN_}g zs!K|3I@WGCpbKo`e$uP<2wNVRnc_r^L0iuq|E#9G@I5AZCfw)Zr-ke`+tnsG*z*11 z{8*RN)f8vcAmgFi1{#c~zul`Dvn1|A&n{RkIIpIb5>rPUIObyYYvztxd|uowxWDVR zl}Mt;81w6`MaRYVFz+vVTEv*IID-!I@g35K%wNxodf;^0_Pmj77bx&OD}D3%gYfXQ z(@>oA0}Im@=j=}^DIbH$9)sOMuh)_#^WSzxt_f9iwBeH|siSZZ<<#T4pK)R}Usv`% zN>>RzYH(me)q+1dHY6oyHl;r@*g@}3bU7vvw#M*X9Z>X_Z|Rk(i=-$NRM<BQRUdUQ zow1hT;P8~!_&H+ldL=>*b?A$5&>Kf~cQ4jQ_fbU6p@heB<b<BAI#DS?`qQD3sJvgd zyZ2XiV6O32jcK0D>5O<~ctY1B=S4k1_MK!?2D^OjA(^>rrde4Blb?=X?bZ?7s~fRX zQljKgB6rGrk!c5s8WK{Gq&pJAqgh_ju{UBwxj;zQI%4Y}o9Mx=lnYmOkNscly>(cW z|Mo77EhW;;sB}w835wDs-5}lF5~C<x(n^iQ&>@{N(j{He%uv!Z<N(8Xp6~CR-~Qs> zXYcEMuXCO2{pbB}o{8tv&#e1i_gX9VrK?(RZ@;Tn<f#K1f`BS><Z9$4x%gasVg|_Y zEDk(U|80@J%l@U_pI~Z?ZI`)?u{l(K;#Ks-*CTt`5(Sa|QhHXrW2UsEVx1U;31@-C zqzTJPEQJChlc+7l6u$+GV(c_XeeXn9JM|u3_S{p!3wLz)-C=o-T$1#XwMP{rU8Ie; z^{X$`VE8SxcyZ8=G_{@46(YRtv?Q@t4Z!pBL#D(FI+~E7#Pm<Q+)TJmtDhg#rz}Xo zsYsM;t7^dFaynQBw7)4jL>LP7z4M}Fny02D4xMIbdot|73`si>G_mi-jRS(YnrVYG zY;M<1!z(&%P~vE2iECw<*5bEX6Xj{Nmh6>uykl(moE8~*qO(yoRq+|`O_+T5JH>qU z%#!V7@2@39LhnNJV`lMAH4I=8?u(ep`d{;Ih^4q0De`r{AW&NJUGpuiRXqX;^Vtf~ zv83tAZ%3IjJ7;GJQ6DV!3Yn$nfCmN5P?#Tb*aZE}rxZ<r^<DmkT&#u8F829AxmtcI zFn7A(-EbbH{CxBN$97R+xG;nHe%k?hyCVufCTR=9opIs9G?)2B@V_8hKEit3^N?=Q z5}66iilAnM^NOv3DGS@)^)|YPj~7@YJ&kR?&z8QSjPXp*WH{HmIjX<)QK+SY*gU&k z{u+nAo()xh{A^8)ODKf6MJB(i6b=4Pvv8TQ{K<Les0bSQ4EK%$$4A%abPQjnRiua| z<U0DMpxSM9nJdysUdCy8WnOt@&c5aPhcbF+T#z0Rh~Lqodo59`K-JBzgSVYo(XLTO zQwe`SW?N`L<++HWt6jTC6he|0$N->=BJDX3>yo;G#vAyawj(S&)k+F!m*?g_stvD+ zKAh_$5uagBQMei1CguJ$=kB6#n(7?frfWEA30Hy@;fYLX%$q^icL}GA*h_NM)=%Kc zr;PmgNK`ot=6ZZ90byfdcVg|TCE#Kz)aY{Gx1@uCH2DEaH+)C1k7){A#i$~UddOYq zY<WR-Pu6C>v{iShKR)`sT56}*O-bg-0BYez>$L6<Q`=>m-0r~}Y69JsZ`CM#URp*| zsw_LdlJ8wFA?}f6S=p2$G{{@eb)u(wVpY4Zy30~w<2C3Ppi;l7i%Q%Sk1C@18Tm6U zrpc}4Ytq_}UyZUER)f!r4i1Oz@vpCMBw6P{nbs!)n2{ygsCz|-lKrq(b=jpoE)-B- z9-M?N5qv*MvzbuOdjl;viXSwSU*3ow!GKT~9g>fyFwb)_-s8}(E$??`Z^sw<z6f|D z(<J_hkwJUH+`O<q?x8wUFxx>t8Q#9&g@25}!roB>!#dli(uBDpFIgNCT)G><L?e;! z)tYN2kCk>w6`NwWPL+J8HLL4g4`v0!nW7cnv+(!6V0+D<N8IJ5j=Ixjpr|O2ZtN0P z!0FgJ$?6<=?kP98!SEQp6blfk1dAmlVTu`?(se{cA{{gC(g_Jg&x@Tw&A~z2)zL0? z`l$1;wm@;y>M<U#;rl8Km3j8MG%<B$1)FtFCk`bk3gs~^x+4orO3Y({UnrKilogqZ zKV+}Bat3t+R42xU$pF%^{mr67EIdBzz(3P^Lp$~?^I815VG(``_qT%t7X4GHPugyq z+=wN-f=I*f`v@lq2V4Gg(Qj(CY@IeNT>ErN#G8OWi1eaEV6e>g<b0li8lqFDqPVWl zSU0}tMcThf)4x@j*cjRUYxUa4@>1Ui)7nI266X2Ko8}z;sSc-)?d<2qXAI?h$_ML8 z=ftY^sU?EoJNvll%Y5Xn$G@PF`S1{^>OH=b<iM7q?%)EQG_Nfkk0RWTwA|v$^*q0g z_Wc=6xM@eOS@FDWO8uK}!75}v-og$R#35^;G7$;9i>f6jzM;;{pX&FYkggM}W85w? zSkX)H0VzBq-xD<={aNE8#tv_gjdg8!LtP!H<)IGS!dnq|mUOUCg8babaD;?dRSRLo z%$-=y&z3JdKfkPZqwgTjx~bY<{)X{B?ahgl^PxB|f1Y%Q5<>;ITkUN^EgnU_YnHlt zGtYa?%cIE-UKIV3VfRg4!S4*T_9_-NZtnj8lB4{_(o{QVvcVPLiki*xP!kB1EOn5X zRNxStpe-!cD9&V7&`6$o1Qmwfak0%Q+k?V=e&bZygqKMY`NqMYe30bTf40aJdV)Xb zqKAx}pD+71^qD7hHSQ5&o-A_8uLUZ_<u17_oDu^ANjZVhtQ9?=pQk1xPLcxlVg#cO zCmxciVEDip&+GVXFOtqhPuJe^V7*Uk!o(cA)(_jUd-hV)lJ|d|<NKEApiAJ*#@yUN z6SK)fjm{tM3hx~%N5j3HZte{|7D&SYgnRHv&;sC!$BLjW<Sx^L@O>l4y9o2Pzd9K7 zL>&1arK?4B)r|Hy5JWUO)0Or4csj)=YYm9To1^#wl)9-;oM=9GcqFRnsy?ooKC>Xt z9e2(su?*T?hDDo*xtY?#k<=|#5$zM}Ud$Y1o9?oFt{W#G3sfX^sWcS>7IzqB>561{ z2minhpg*j~rJUyBz1(XbeYyN1RfcEpJq}W721^|0|6!m(Rw|BlmiDEN%Dvw{0UQlt zQb+ip(~I9YWva$6ePLpnFHT%xEr&N;HoN(H0CWEDl)|rWRa`Yl|GDkAkEOnncD&t| z{`KSa#sGW0caTY=$o8Lj!p=7x`%D+KSAqS&8T(JxyhcToYF>w`Fs<b1MH$xFdv8Ug z=cxnak3_`6u>S~V{;<@ibFc#@d;$T=6L9QM_fnW7pX1p#Z?uDkWY*-5N!W}gRxzs# z$V)KS4LOhA@(N|WoDGUQcq);Kl@oC}KO?$ir-NWv<*@H80IUK2%PDgO48B%3%rYAV z;pGE&Abk;FaiO;F?dLbwoM9tz{1<He8!$}O#a{^v`O~uAq%{J*Yxx_;oVz09A!u7^ zcW6I7pQy}}{Evjm{{InHe9)_i*1b@G3S&+8>aM{=Hbhr0mY{#G4x~-$051{SN`wur zt$arH=Z928x1!6PgU0+Z>E2jB;I}SQcVb)DDkgv9oEYG^{D(PsMvu1?M`fdA+d5o* z+T7tXB+@N{J>C4%y#Gt2b|qai&YyT{^zuU%%^gF-T)wy9Vqnwkr<SXgI|Nl@)PY%} zjmrW5a(G6)bOmeYUY(4|cR*@kd_;Be<8i{!;Tr5VI6bquVTf<o!1U@?wXg-y^Og7y zvTJR?IsR`jZ>X|-DZLrfZ}k0UnCs2DXA<Wc;CA97@bCg`eF^@IYI4>VbZ{GRa+XV1 zO2O|=z&7@l4qcEXAJLHmG7+97pP+URXpM7k*h$VjdMo^^)CH|l13Nnbyfm%47@*}3 za{!G3afrKE1JqdpSLI>fe4r|b2yktwmHdiX4c81|{LvubYPl;5khoIbzj4yRAvhMg z3V_e&5Q1%rThqSUys$?P{HAbIsHI)(+GB#Zcjz|Au6>iS0Jl2<zaFmbxjcaVB~6<( z#asX~H%_b|&M@Fafx<35T~;~M%OejgQNi4;kWWAEcu;p=8>X`m0-$h=5;kb}HxA%x zz{BY-Gra@uwZP6iIV!r+aFLT>V+%L$N!d{Z(`(1MdkTH$2q1oglNL+r#ET6qm)cMM zFG-s4*l(PT*%j=WDe4P;>jQwA`foY-rZtK%s}bK$xKc4eRk%d{_Q;#V;6M%t<{?cg z=5h|}geAKcV;r_~yi&#p2lwpX2vDBh-LnQb>}bJ3)e~AlozL+4rdVAqf_`XZHV(xN zkv@6{#y>jm8FU|3<L1TugV|jCC%fZE(W9aat!2cC_0KoQj~l{u!n!EZj#Yo1fYAW* zw&FeK2Hl4tfBpov$rd22{pYt@05ay^jji-svf3FM_@OEG<?cC_68nz*@)&$(whczc z0LizG3?v_d;gtXkS(|jz1d@hG9WF`HOETN|4M~#OVPPlq<u-rZJa3V3g4III_}Puj z?<Bx3#e4eq{Uu=`0Q;f{4m8E;c>{DnP|wnlu_QAXUN{bT+WqA)kCrM=FDca`Owsm& zzj3f8)AWDtCJ^$2z3Jhp%UL~IeWw^a3?PaGpz9BhF}#=8H7@`!+Cj%pK^MZHz7@rK z;sASesBS+MH?sXZDH`mQRt?;2X$RO{GPwv!EG;bvYpfgJg%Iba5gIEuPtL2SrH_}z zW%w)zL#Eq-4|m-F7b%d|{NFV+1^oNaUM9hQ)dWZb&VCDk5*sL9m(YZRXNYTko`C3r zm^dAcKA?3AzHV-LwHcXS*~~%)`|^;^L$Je)Vtn^9o4z}3toRMNsv_XrfUv-E>kXSm z!j5p&_Dg`9-mAtEyZpSsMiq2cV1#JEKyJIgj-}y=<ZqmuO%x{}K#_$2-<w^5{e8Rv zdgRJs_&1C2CiOi=;DVVuDQ9lQrBj!|g&9lnlh<ssENvQSz~uxWWOGJQ_&@_OfS!n_ zq-ST35&6M-_|<LMq<zi1y*CO1-e~<F%vLulH56=_61=o4MH|HUVDaYx(7v!QL(_7_ z(?1_P+27&=UPs-_1dcnG4b@N}A4KurjLA#t|I)@9m0$&2mgHX2PFRruIq!owB4l}+ zEWdb+>ol-p|FW}U^*5`~8ZU}Xd#fJO3U?&92Q?g3I9|S!Bzm%Ib)k!vgOk^X+O&>A zG?ezqB3||pywM_HYCL3q&rS3xw^yz|PS`i~O$x!I9M7W0{@g0v3#nDV#$l2*>U)~u zKPo@jyFq11GBURU_*9xrigl~TjrGp~g70SECB##0X5~bAl)Hr-A^y#Iu3OSH(&SVt z#EA*ySogMvDp-Im%8{>~I$(w${!@4guNphq3PeLEqXgjCvXuq%5#TY>F5koe%}c6k z3SKtOsT+W1j>((j74AP`43V2%j`#?AGwFrz#H*5q-3AoWDS{%6Q(ojXwXzbt=>pdo zH9864aT1(#Hx4JmI^xiV*oULF713`3s*Lh;%N-bKYMavno>r?CI_){~tj6zJ*EfQz z&ZJ+^Nm-lU#M%!9f^pr88x}bV(h(f}WZCRp4Tb$G{V}?>MJzQsDsv0#8alPp2cXeJ z0caPUCIlUmww7cen_(=<0oKp7Kjss9kW6E*y><)io?7Etfag&rtC7j(p(?qLVqLMM z>4x&|>}R7*hK;88jtZLfexTppiR8~K>#G$=whB1ox2$b}8r@t_x)2YbLEY&bzH6d~ z9rZRCj=-?OO^LTsbg^_w&AT^LWl0z2)91Dg*~)3QsP(a<gtH-^A)eLEOrww7gIFgX zAWeH3TIfp`9fCk#YmjR{Xj~$WXdmYwJc{(|K0DC8GCXr1a2yCIvPP*<*LfelEPC3n zL$o7$p@5yo5?odWs4u$^1UyiA(HZn4P9@OfH%@03ZFAlD-cG4gMOU=Wk5fK5sF6{X ze4Y|>C%44j{q=|RJxBR2@d$8rhO2M=AdOq$JXAqkl&yYnCn2O9N?Xfjd<MOMg*CRy z#UL_dlvxyBaDE@}XqpVFHmEg{eUzusA*;pNU)<4M5`ssb4kg#fe3>idAo0@b#iGO$ zWctY)bYB6+6va~JpNr<yLq9<@4=T<fq~1$DF!ptLg|v?Ha-t^IH=f-bf8k}h>GURQ zo&9ySauI>y=+dwx19n6T`D*{ZgExd>TpPt3x#v|8<|8ZyiWXeDVK=L_$TKpv@hWZX ze6ic`LleQ6sK1wzgWaCF;p_P7fmTIHg3FZOICk71ES^BNZ;2)n65Pt{o7yIcpK3ZD zAm#d~_T4^rZBb2q>&t`PFDbUpF>62A)|o!|sSzt&?}jM^jY5#>kdXSI$7r_|7m{DI z!y)@E+$FuOTu7e?LC(2A+3qcQCtmJ@c9P)Rde+YdBaD(fBXafiB@OQc53(;m)-uyZ z6lp;f4Vt{3M!D()pNg*F)oQ$%O;0MF*q~I$ULvf$V%oU6V>y{)IWmg;i&e`xXPFWU zR5|gVm}Dv*e@SLaesUb~B7QPiRORf++aNM5;7K8cSwg~>YQdqc!oN%@g(~pSZ%#YU zm%=f8C>pp+O`D^Ov!QdMWCqpKiC2Tf7Y?bJ+F8_J=9x^NU)D=<V8^78s-rHv?MpW! zJRuYd{EIW_H(<d0LCZ0E(6{J%JcU;oK0Q<{qMt_?26R=q{;;qJ14P4g4aoZ44_VAn zCqihEm=y@YOjqevkOZ$}R>GW#9=_7jF1}_J`{$#dQ++Z=K9nYMv$>&@q)uJx=%*-~ z7nh%;mNVYSwYkg=bkKCw6`_cf$7xm3=|%R{4q|c<ZBc3|_zG6ZpN|S+XVzl4R$tcQ znz=E#3vZOW6xt*Xx>k2i6ln-m1PCTmin(6S!8r1BQn?o7*~X(zZQi)WNkC%Mh~Ot2 zg4J*I1Erk$2Gj^u6dA_veJPO@+-!%6X>ZESUD$GXLUDD{)1o;vGjco7AVkpn3vslC z^dt+Kx|lVh1sA?uf<NfwXb#x2rTaVtF=Uh!Q|q*9kNj;VKERrEV;5TT1qRqZyWi;o z<Q}t}@WI&6$Z2>_EJn?z#Kd^(Mz^rAfZbz#BN>i|eo{5?no!>;<!AK~P-cryIQbHP zK?`~zsr!ISSwYGsjt*mq4n*uKv=aM*zt7ez;v>7G%nA*b&^?{(`GXNIAHK@0&(0b> zj-@s95Y#kow@i?I%*1)fPyshq>R6)Y9*0ks3?o+%-Kl{@(M~nAoed7@8<lCcd!?`E z>coq(!{dbXS0L2!H;U!41@~U0cvWhYXe9e89;l2bLmgTj##Q>3mYw|jx>X8nvBq(2 z>lxx*GcOrHL<F-<>ml05TV%FscQnX1l*koUM4=qR#CSD@7qW{i3GKu4C2X(OB*;<C z2;O#;C;BNa!9ilE{A9^8$A`fGuZL=#Z%&GmNV!j`iN}IilYGqj<NG1^iwV|N2O2N4 zC9iM7C<ByA<}iR>{R7JdLbiw@HPEku`!b|NDR<^s{cYN)bj#Qwc*^E$r!`}f>C0FA z&$+O<sOgjU$PaR|sIc$fDCBus<m@PexoV=qYHGzyptOT52}QW>IiimeU%6^2P+xG! zDl1pvO`^k=2YS7RZw9cU-)C<IaUoM9N?FHhCnstQ?P8%7FI=3Sep}dwFbcMn9i6qq z4J|sGXR4{=Hdo$dItt-cbt<N(r3yh+6b^c_R0>p}e$0Ii9;PZ>)7|K>j6gNvo^`)d zLXCpRAM9G^tqkNP#kD%*W_+KDCfc58d|<|f7Y%(t6qa_(boq}a77=lvVsnvm@aZlW za=Y{Wj!#~LY6i{KRpT{LB-O^HyEaX7p*oK=4*VjAIjKHX+RV3$TFPVbu!B<fgNS{{ z4h_bz;`&=bJPv{U+nsWqI+gQMC-Su^Q{vXMIr1+C91n0w97!FhtP(A%;Q=7DDPq@j zWw8-e(gr4-mPgveKqrs(!xHuM3`MIN$IZUhJR7aK4tiv3ZWBzQx2OEZ36bj<tG_-1 zL!Y6nJ66^zLNPu_Lf%@_dozQ1_F0U`uCj?b-IzeKC&=0MU3@XV*sh=5UG?EScX1vv z)^l~O&n(`~Z9^1`j7LVFWh)x>r$uWO9ga?sBqv!BTF*KORL7uNT+-Kl7wOxz+YpRu zT)7fXxYJ!LoDJ}YVeKAb<XeII{hA$@CQuIY;;C4H6yK=HXlBh!)Ltb*g|R(urHpsQ zB+d+eDc41lQLNVCuwBv<v0u*1bF>{|O%hJl_TW?Lt3>)rt~MW=;%{g<l<dKrF**?e zqw{tCjiVI0FJF(k6Dq+7*Q#lqa4txZFXQ1c&QC+=kx=c^Cuf@9pBbDcr29mZ-;A8@ z0yNt6uxN}=iTz0{b*fIwT%Nrfm+;bTm7SYiqFmuzD~jp*5=R1kC~KD0M?Xh{W@A!0 zbh^_8cYsP0I(>zy(U`x>Yt!*T3gE@Ho41=9*&Oe|myb@_2xyA=9ybv9C7$crX`Tyt zin(pMB2`m-29&B{NH8&I%yWqg?3$iL+4Gc}85BAtd4s<jHB2anuS?!Bd`A{4K0G^` z$&vB%ti3oJZ}XLNnP4`TDq~g>)L2?8TQM&%?Ep5rvP=~E8^_jkCUR=2`!sctVN$}_ zt=PaJ=<&GVuSXNL*PuUVw=~+^qk{E!R`1I+E@<J#w_k6>cp|}oT@4*yrC6d3den5* z!;GcWV;{PcU*~Y5x#C?}<{(u)l#XO<AND@2le!=9yvY81rs{AvyXIxJ`nP;AKd+=A zz907tlMmnUqm*Q)H9x6)Ena38$mX83(+_kqj|{eT)xSHEw|t4<e1N|$zjJ4x+jxjC z#i9>m+Bu&~D>KriUBTXJU$eg_m}GrMK0%@zv&#_S5tw^U`v{?2EmjoXwfsw?DAdC( z4}lU`E1*`;)aDRd93oXbN?}N{pyIff<F4&QB=^5VA%8Jh{|Zg|q~KQ&JHWDB0lb*p z8Q=*80U!)B;Gb5@xdL;4N%A9mb`nMnFAG+DIxWxAT~d*CZPnw`M&$1SqrQG85P*y0 z2wf~qj1-Vfuy(+t3f-kGxU!b+u5^a6@lm#rOg8<00=2yV6_yxe5d&>UHl@?L#Da(y zS`s@joL|+WV^@rXHcbCUx>{3jJX=XWZlxY@g?9|#1BAs!>r=K9ZK;iw-#C5Xv-?+u zv-7X09rQ0a-jDSP5*7TDaQQb7lt>jt6biFk$yH@RPos!+@e^S9JGh|7yO(uRneLE( zL0m?Y-OY9gDnr?t*p~@zA$B;kk3EKPkBY&659{9ocz|p8-(Xva3KF*SR*2ReLWgBa zIUL8qu#bOdWyI#zb^vhYA9R;mSbOTMXGx)o2d+Goe49caeqRs6gg*!55Ctqf3=<v* z2H@<oB<wj1^Yz5#U%8V1m-NXWJL|<Z+VuQp!6{%Ktc3y0YWtH5cJQbzIs}Mq=?1up zRPBgm74V4;TC>Q0krR2^xgRdpo&DrP?Jh@;+BdY1g$@277;5}8SAl<<l>bp}ulq}9 zc@3QP7Jv)6x}Wm`$O|jyd6qY_%CKZmX^p7p{MjJLs-2P`RJzoDtV1(8XI%AI&_V0C za4N3Jp^48H2sx1kvTt0}W9I%VjGYlc_K;@qAgsNK=)vMuO@FB#M$HT=+hmFCA9l`p zVyPai`#w6&^bbz(hIJzmIY3gpaRK<vN42o4C$D(gfVn4vMQku*G|%H&tyQntyZWz^ zN!Q;06%q0GI>}un%fMIZT|J%DcwbrGo!w`Gag2W1+0;}L78xD~6OgN<%*gG**S_0( z2A8G)*H!dK2MS%>R_^DjN}A3@EN!4N7x<z9Md`?$r~kfvoGe^`-7AG00~HFH%X1pH z#c?H=A5I+OQoQs!2nLY5->}HaS_$Z%I$(p&#Xfri0wlyEQzd_#BISmu-2k~8wsmg3 z2`Z-sudYYa&o5`SzZGrbwE5#%afO!rLa=)^{<pCqfZIP`xhd)NewE?Z<Vjp$Bi~@G zAb0s=Bj8Nd{QoI_{=Z7`v$=txg<bF)*n){#v@Z<M?^T;rl#H6dM81CI+{_WTA-Iu- zpL5(Vct{N2(OK?X&ixb%8xV{8v7q~63iE0zhz2<o=T*365SvX{2PybDS2I38%;*@) zw(?AW;Zq3SHKva^eHBZPP!N%4+)tYmePmplTIeEWD@tZ6%H>|Bg<1aG@P_^An1Gs( z>wUl7`_@l%nfd!8@rrQRDj0=g8A*zkzYe59_1W^8fGE+rB_)${&=0Tz21tbP8%G-% zz?xK~MxCY|BhoJ3Pi&8ZsoEzLFhr_*G*{UkWqPy?l>3&*pv=*^`d=Z^4iQ}NahI3s zEn^R4Ql8iB+jj332T3z|#aqf*N(LfexEP;tFMl=SUldqsluKmBf(#fzXvgyPhweQV zeQSA3Ni)-`HplCiKNHBG(`0i_pl_^fw1Xo_7c1Tc7!qPAng;B?E_RnbZ25STZIllu z+3k@N0r|n4Vkn}?-_9akJ;ByeSFSc9eq!}8i}HQ{sYV+Tw*s8$T)ZSBGm6;|Jt1lj znZ-Sc!~}cQP1Rwg1*W*Qtm~*7olE#t1p7>7_lzVS@23-)r0&gcM6`9Q%%wOh@<-=P z9G&_^Rj*>GkuJ(;<unUl|ITSirs<SlE~v2Rn)m)JiOk(u-{tI828<OP$bUqUrLV~{ z?|t%fP5S5!t^#%P-U)bh`E>;yh+1khd4N1ADe*N`M=pgQWr}M&p;314W}5WO4CKi~ z$i90pe*7uBQI8;kdw%MW>seFvuZr^DIN|X0>F=tctoV1>WeV67Uri3Ar!5{dy_s_c zRJYa;2K}RVJ(5pTDK;8C`FxAI^H}YZ*=5~IhKH$NoPJEADG}Fj^UP*@<q5yrUdlP( ze-Y>#1(({LLoS_oAY&m#=w@|fDOR9ns=~a^_R*x^H)-3oQ0&&prn35M*=3&lfX~eY za&1d|rpQsHf(r-iz*4PRHzef!NyueRE7z=DS~;}PRxEI-V}aoDc!0Q>AYvisUMWyn zLuLZ0Y8-i!#Z#YI>us#Rs<wl!&a3BHub<O{eJ9IUBLd`jLlfH)wol7)dpP9Nl#E5| zbQNCqw{z{@RJ{3i<>7a;-a#ED1eS=sD7Z-J`j=mAnpu^Q+Ni{gx%FUmr@B-Qv?-?( zCuqX2e%#Epg2dcaPZ=t$XWtM>H+G`Eph!|?p!wkvDl)#dUbsTl#P6IIB07;_K7q}L zO-T4%Q0r}BDbdx)^#LO^PlX>#96}AxPSa??)>}jIaFC(ier{GiLDXvSfLgi4i7EAg z(qmo}?>o%%ix=QF4X|~|($8)9UWG*tTCJn$WA#*vomakC7jvlrJY6kx<^gdx5Lq$) z;QifB0a$WN`AL>!0YZB}Jc!qqfj1O#zr_pT{~L!$MuG(Jixxyye5p(9d(fF6N6=p- zo5xNp!k(mA&ylBxW-bSe@RTsAkXF2{dK!vE$pW_^!Eh`7+2?{i{C<y>nnV~`nPg~6 z?G-q_Bsfg=1{lM43h*VI6iHLeb{R#K5=aUtZ{-~q`G^XyF(Fn4?YK4Sxv-zIsC3}{ zUhrgdw)L%AvB;blnxxl7EE8jyFE?~b)1&wAN(+bh78qnG(hTn;F2~XQ+)k@_*ZK&f zfMh5rv!#^0Gu0vh->1V@A$pZHQz1C{MA)fG^ic#fbL!!vxeO8uQ(^O;FkDG4U&zTD zB>6@=Y?gPKuFgaZZMGab={a||mi}ZKDPuh~x@c(9&2%ltPq^~tKF-mC#H&**1v;h# zt=1(5iRSVge7f%yBdr8D?vGqpM0r+U#_C7AQccvv=TG-OZ0Vy4-ZKCUL3<S)m)Uyw z8PX;Cs7ze7wT@ph20_n(t8u96qmod}m%1LQHz30$x0WFMU^&F<JeoHe!x~dUASpDV z#q3Z|v39%0lwe6vW9-y@ZA#cq2Bmv0hklWz+h#dd6w|SaEcpPbN-8!X=@996Ps=r2 zDhN+1P|UMnSIiXCau|u`IDF;dJ4Oqh1+A!-z`@jLilt5y5VHOQ)410!o}+aE2U4}w zCGG?P!{F{)^>vN0zScacq;kR0am~G8Cr}9X9+I*Rj0?mG-*pDPh-lID@he!A<I47& z(?2S?C|P*BXX`}ZDp+kO{mD~KD`Fv;b`ncCKL>>8PnIXz**Artza^?q3E7#2E*w9V zwo{&_)R4Pr8)+hI@m9o$M^!)@)X{o#s`jpK*W&%E)^WjJue*ZW!u~HClx$t}L)zu7 z7uFMr?}yS#d5?46A;Gk+gSt#^<;KMjNb*nkSrI<epj?m6W%nPca$om$vMr;`k>VJ@ zc;v=gi(1p9IB3+}U{3auP0F-UqP&RWC{O=jIT@f-I^o8z8iO~n$<`(9vkD}fb$S*w zD0QdhMmdHCtpJA+&!b(s#dM-_jkd<-B@3W>!wyfwQf-4q66QbC7+U%o4wF!=Bqs*o z3mO8Iay*c73g{a}zPhSti2JD+C|0m!;e}>%P1?{_pskSt-M0UFH;u^b(1wP&Wp_}2 z(K=tuC@Sbd04-9r?1FCq89ArgGU){)^3_3fe1FrBS?Vmf{mDXhoQFbwovI<!!T*Wf zbD8*TmlTmT-w@N;^mYd3%WOfZo9HJU+(qc1#eHoD2*nnICtteKHJ5c-@%LmgOkL$9 zgkReYC=#9?i0~N>fXWznmouCVFEiiwj47z{rg<?c3co)M;%wC>n~m16Yi8?LF+FlD zh``Vx9PcT#`<2@qD+@nr6%(0Pp=sUalu-Vq`l_o`mX$OtS;Fc~k~vDt$V~{vSBMfa zlaXv*9tI#jT<YQpz*JD^_c5PFuK5pgOks6wkLD=-t*hQya1GF98Ml!3lGX9hc)tkd z%tTLmz;)4KE8CzuCJuyVCFpVKny6<JUYu^^$KP5Z1twefKmLm19B?9^e?}Q&74gzJ z`bV}dydXl#j-Cji8kg;RZY*}#A<WL#GUY^V;%8+`!G^<I`$K+AB39YlcqF)ddDm*P z<yw&gq(-K2f~$0|g}un6yq>3#d`?F4Gx)?;u+34uKRD<|ssQC2lcgF}e~TkgK?nj% z)ozgi6aZms)vLdI@y1=ZDJ?dk_ADo{7Fwb>B;)D>vZlKgnMD)(<c9WSd!N5l8N8D0 zTQZk1Ye<`{bI=a695IJ>_TBL=F;BnE3sH4V6M72RiXWEUH~o3F-a0bmGG-DIx;E*# zSyL$F(2J1GT+5RGQ2g<XfFPzx#O>iTpMmutChRyx*2Ayp8H6~9(vH`x<VCqjPqAJf zwQOAjC4U4XhXRN8DFK5l=Q$55KfP>j!B^~}EuLS^!lp>BSpIPMP?meSIm$L7m<eM4 zQ1;l3qkW|Ad4CWg!1l^Y-VE?Xf_f@QFt5<*%e(d};+;Vc5{_H6c|&<iOL=%*>KDIN z^?5j5|GdJ><y=T$wVc#B_L4#tv)x&`!tulPlP#P~BdRuMTya$KROht7hP|1`&c3up zDsXv`W4T4gyy{0eM`UhTM|&o-0Xf@vi_z97lyyKun_Rz9Cj)-53A3Y>L!2QZ*(&;o zCSm|F*X0Ey2W;@mAq&a7)OgN%Tn<zk>_b5??|LqMfWpBBRRK1D62%P&)}02bJg?aT zl>%Y#xU+k6mjLtqT<GUC{ne|HYp?804+sJ6M+Kl`8&OgF^Ag8(0*HwHpZOV=IbmuI zl1Vs!rG0dxnZ|_d!L|Wm?&so38v_7NeVe`vkUA7Hc#C(n8fv-Zf7M>Q{hw;D0jjQ# z8K%d3Qb#PM_Bfnhki3|0;O|l=_8Z%OzXqZ*fRXf~fbwXh*j7qlDE4b5MSolt;*=2q zQD41p{;JyWi%|bK8*X|=^!x~Xd9CoqS0J9~dTR+VHO&?0Cy9SeMaQ&TG4OSsZS1$a zzsBx*bZx2&VNA2g9Bi0FO~y&Y-N1+hLS=Nb!Nb5nVJcYie&fGoIM3+880I&W7%b@G zXbG-Qc}@W>UQ{Uj+0H<n?&)Ym5SP7Pxm`0NwMys&#7BhS0M$n$9AJlAu+w9p;y3zb z?b6w?>BTv0#n_ANS`^ftA`4Va<6Xj=`q;cnI%WB2)lCNs2O^y}kU->oJ|L{<{Hq|6 zA-1v1YUB<8gK<p&nn5ZId-(*d6I6RMizS{%&{46HU6*OM4dbRqel@7(whQKw!9M1^ z;_?!x^^GOw_Q3|~VzCwIX=5Ne<SZ92JT<||hM4OMmnHoS<7OHV*72bN5IH~qt|cfP z!%+Z)b&o9p$*B&=2miToZ6_V<bf>V5>X_9b3m2`OM$5gHv~>sFwxt8A-#B$Dmu%M{ z|6$|<o98UKc_wm2rtKtDs+&|IBB1BMenKYyGCf3t_s78@N`HjZ+=F3BzTsoRM3?6- z$oxKp3e7r8edw>$c*QRVKY`$e*+!0(9;}oZAb%>s{JOsX9|rC&b){eRj3~({0td2G zOa8Z1eohlX<WM8>9!!7&_6(>OKXr8*kX^kX?^S<Bb9#QSpx8vAa7LPjJ);I#{P#O5 zGJp|~()=4o64-QLU5rES)mWK(a#t2%sywxD<`;!S{#L@72Rm~TyEAU@s+*zE)x3;A zg3G@*o7|PxMj?QVs?2ZzVVAHidtEC=Sd`WIp2reHt=iQVuBK$X!}w><>`$U-ea-R` z^*g0s-~4O+E0oWtpX>dV{Upxc1xT2Shtv4Sc2oc3O821*P9X4KcGDhxBRgmeRCg;Z zQYhW9@yI2Nk2O5ss|wQVk6zWT3|W_bP8y-msLkBcX7z~7ibwaDaiu;gh++#uTo&*U zMWi<_*cc#c<>qhYR_q%)tiosSZa`hrC^@o2&*&4pOr_M(m=m$86W+0o0mRKWrO}L5 z7mu+W=li=Ll#(*GH@%yGpxoF*K2_Fo#1ZaNE%=dt+1-VQI7f%S%Y)R}vAAN?6es8r z+WZ0$7a>WrIeS?fa-2E!g&E~syP<EuGzje!GL~23D9&jsYI|CgbxSLD@g@QFs=nzW za{rn{Pvn+0yYSaOHjIL(l(!<P+KK%sS>ohVov;I8&9w5z=dx2n3+&S!YaY2_*;Esr zXIqN)<k<{{qWuBK>;*I*-8P`2eb4oE0qh84uwN7&!H~ks?72a5lSfJvD4B(^vYF<l zlx}7(J^G)9LssD>s;`tNehE{=7|XdKO;2=@wM#J)yepUP9ZImq=C7?S<2A!%5hjS) z&Am=Od<!>PQ0=?ClADPGuGYRQ-mdY3VQ?_<FA$03V{}C)1HpKJ+Uu{IZwkUC7|xwa z>r=cB=T(?Cx!l?w^>c@eQF2Al7%6Y^a!QOD4Io^uW2dlE$oyPN4D+i1;kvQX)=~IA z;SBnjv64SjiK@9)L1waZtcN$_l-2vdNV&kAurh9w<_LAn_lfRN2_B)MqN=^RQdY9A zoh+WSMuJ<Eo5`xi`?W|Z%MvA?c2{rS8?i%duLe+_%ql|}4scP%PZnPtjQCIDPmW$^ z*lC6^s}b1?7W9P`Xf*A^Y}KfJ8NZv>yp$xG#Mos2GNG8-heIw@R}5kopNfgI58UsH zd`CX-*5*tle?v66*T-h5pLZ90!5mm@dLR9wXLc#(bps0T4zeyJ_lzc_HlxnYfljB$ zXH{rCu%SoznjbjmJ9{JxKESdgi9SeJt*GH)lmPOjnchYxs$+IP{J7$_L-hcdaIYv| zEr0X0?q-w1dh11|O#G;@&`iYm{adlEpT_c$L_ManH@*k4*Nm0cmPro7cd_*r9&WFh zoWzt$$^>VOc9WkN_97NH`mMDsR+aC}yNXmVlEWij!&U3<ktDqycP2Y>8yi*-uP3X( z?XvUoUR^?v{l-Dyo1q%SK8NaZ1>%l$kC%ySc1Vk);pMECD0EP2kS27DWJ`PUQN3}G zp;modVUW)wfRdueSfC@2)15(NlPz}0l#O=m-3iPKa!9z>peo$!nsb6G!J<)0*dzJp zDUb454rv&f{8QOrszD>LTLIL_uw|=_9v8xZ7h&4fVak!)s?~>#mJ<VSSNa-Wglbar z;N@Dqs#i@65FE2?1Qh!qdURAbqx?t!E-2ayc7NW8B!zZL-H~8SoXd45^1$z9Oa_zt zy=&H{p8@Ou2^R+6-vz*@=?NLiYVGu`8R`~7p+N9N{nvI0OU7wpe#m2=hQ{#E#LU5W zp`i<VFQ}q*KlVb1Qvg?ciwr?EE}bB|+Dvh>so;bS$ZmjX;Vfy)HE7!{A<bkbVf}Jj z2&vTm8;AI7O+k47;|7|_5`#LP7RgFHlALM+8Fo>fA`R__x?2-E9C$)j1j;tdL^f>Q z8Q4lx*pAW)2p_}Sg!&L9J~F3UIeu$$Ed*2MU`DM?DDtEfS4-xej%>&aC)y9M6JSr# zKHXDU{KnFto3>4{Fh8gs(`;xae9o+JD3w4jFqY483_s$U+~q2ZQed%>vgUe)`eh9E zE}-J8t!vH=8U;+|ja?wiQ8<GrQe`B82=DvK%kh?{UJ}ADf7G35B>IpceteqmciafJ zCUmwsT*zDo%|vwq3R}XzR3NZBk__AxF)ie%jjptz_vEed{C$W(7XJJ|N#eVmJJWo< z$b^K#rnmW&Ka!^7i0~UI2@UEfLB10OZ299EX2Zf0W^WRl#z&>>1}GBUPjeC_4T+DG zkQSsV)}QdS@+#4Cim#G5v_ojdibQIqNh|ahlMUS5vLjs!Xo6;RGaN=E<)mDeO-YQ< z3IWOzPb=n(@D2U;JYx*o-gHB_>(iOkt0Ydn-3%zB`%-Ylorz(o>vXrfk$d~(dToWj zMjJyn7&Paz-<OL;cqe!J4LyE-he~J@L@2fV1w;sTF}7%1y4^~Sj?xU2UH@U?yST`E zZ(**-X^nI})hSViz-HiwVZIl)8wuYb4tYE>SPCC)2>4paVKxhX4;<pcOoUP#?lQJE zG$aegXb4R>en=(ZGMBw=2iNNkND3AiP<SWUQjN4=x?JTPuaM276pu_Y-J72j;(e1< zG?<q*zNqUo0~*FM`r@`r5COqZD^&r;V!mMO&GGYj+rj5UP>#vs{yMytOpyJr7eoV! z5HT++u~?ocNahT>r^6sDIv?$4Rh-wfL%DBzF3m|B>J^dCQxx68OdkH(gY@;=Rg^AB zV?4(@RtZg>s*WADvU~Pu9~(F<wGIAxu{Z%}kqzvnZc5q4+&KxYLmrm~QKL*UdEzBf z`4mruM`=TnS`zXUB|1o6ZXZB|oHC{J$x~87N`3Ei8w3FV>sTiAFmM)?N`0gBCu?XO zE~e|6D`Nvy^^ayEmD>#+>Vo$syQ+6mc^}=K)Oe{%<;$L=)jd{l92uFB%Pz`PU|Hal zWS%n?P-dc=#LU(#spmUyc4Xgw5WR9oi9@d#{U(l(rV5H3<uIAj>oO?K`Fg~B*KCox zJ<p0kTSVvbVs*_xHIDYvs&r`qLFwb?M|l<LQa~;j+LJi66bdYjrbTs6sfEs37ZpOM z!wbfuDWAA**6T*slQKnZB*){;JK|+e+nyQi+HZrcF7ftHTt+eM<<R6kXdZgw`=MzU zQMfV9SdT#^zcF*wb81Um9~)6G77K~K{C)$G56bZ;)-XA|8E+DD_Vte$TQlR4A>;4e z6*V&K1uOb@E%(L^1U7vSe+fW*{o4<^tf|+i*U35E&AuLO_G@jA8y#k(Fb_S}W>+r| zo3xWAx47G+u5HDU<}XA(;0qZ3CCC*xnHZ2wud6%pR_D2JHc(s1-npy{yJUHqGE|5k zrfqXe)6I5foXL`b{5UR3^8QyO&wB(Q`x4kTSWC$*a&T>Pw7{2Wib?8T6!K&Cie02F zf@?4SjFmvuIGvU9zSGa*Z_ZVtSAry~u;f8FH3J3>HhE+-r_MdSF*F5l=buX;vWV~_ z0aa9Se<t2(>esTn8f6A$dRmcbZrL<OpF&CtwNsgnjD~-1-$7(WEQ3e@Wf>?;lJjX5 z+VItg3wMkBbbbCTaX}w`SzE&EeseXpRwMpoYEh~|zl|7-S|J+T9cp~1tNuKIMmWTU zbJl(~r>d9NDpW-4EFoT^|5xvAdep<$J@*_A@v(UE7rNMyRuS}Q5e9d<m3?s-PRP;T zmOZ}Xl-5lsQ&3mi@^L=rBTw{`o9)rEZ6~jLi+}7a2|>`tX~<J%h3V)oyWUBODqBtZ z7cEt=C$ma{*z_>Tm=>i^s0E`mk#kRM3A<Rb#h|}*NpLd0oo<>$vW3W?G+z<fdVwu0 z3?NZRrokJN;C(;_9s{~!$~SFs3?Kd4IMR}&Is_SXN;}>~`q)qpE1yTg{;*uNdFjE$ zbwH7X-#Ac@nrnar`YP7b)orOm(HEQq#j}29b6u0?Jcy1hV904Ko<^EtLV%<~pmnzE zyjO4>AZPyv#wu@$#90?ypaH}L-&8c!!<qOjd*N-}vUhG|<>}O4G2c~DPcU!Gr4~#t z@9NV32`QBuQ1=r3U6_+=`|Ma`<);VCQW$YOkA?as&UG;%+yMHPI(qnw;y=v;+l_bt z$teM-6`~Cw*b=NzlZ0k=A)fP)oasV6S|`Sp=yVvUX0eY}JmNjWNS$uN+JV&4|9IVq z$9BWywBx)y*N6Ku4{ua?ZN=gNwTAmW+(OvZ+4pRc!vs6Qw*RXBD0r<Gm`G;8+c6Bl z>m|T9PBS&`r9_X{|CCoVeISc#{~5G0L4MV3B=YCgLXd?2sT2PCHIUAF+`!zz6v4Ow zYgT6}61VrUo!U}Y=HFoPFSo81<QNG)A}@=?Sp{G1qUop>+DOqW=h5NGnci7-z366! z7x~rv($`O~EXzM5tg&rMZ!A*{1&u_OW66W~q!<|6O&eDF-qPVK9nk!z$e}+wpf`3D zwR`VONJa4>9r2BC9iiRN)xU2Pk&o+uBc)bvxB(?~2yL%P{Q>#^yjlg4GE@Nt!?iDK zQYh+~p;^MQLTs}7p*VeX?hce!;NGP1RoC*>)Y4mP-SNc=;(ZJd0Zvhlc7b34Wo#F) zM89aIE-wVH8T=y!h%WnO6aZXDguxdl4$!e$d|GZXTEpgsmH7L2V&<<G%)h#wOs;$3 zAP)q1B!Nzm>X)^7;1NZl3pCq}%zqFSQ$68M&R$RD7wkqPP-Hj?Bzx2hh(fSAaAJ=L zA=t|_oU*Iwq|L8<GK=iUPjuok$i?^e=`ZcEV`MnG)-0oqogI_<#eC-yLk4!T109jP z$71nt22nkjHvqi_ROOUzZ2E<HwOKOP#gNhtkMDCM8hjUvE;ZdTHpRXJ0z#ImpOKgR z%}sDXPIxK+eaH-uWNoGdOJCP8b_}Yue=JCRX6ctuKAJek@>VR8qvB)=I7rXgr1qC{ z{~q(J8-JvZp0=M2iP=jRf@aRU4?Hqsl)YIwY-TilrGYPaliYEbAb?ac);*hm{A_|< z-T>G-m~~$5n3qU-Zi<SemG(yp3+nGU$6xLZMV9<Mseh0An*BdAcx+ey<8AVOK<XDK z&}4UbU+?2foA_sBze=S3ZXoW;`01^IXXpPaylrEb788;MAuO9*b?c*hEhhd}>zr5< zsABVvxve!yjRKT3!axF+L2$Asc+NoX^5z$y)4^XQUf6jQZ8`ZAd_R1t{w#rc9`{BT zP)S8y2VCg|KEDm<or4BJfA`_-6A5CV$cF%U+T|Cg^H&TX(;Jo2k6W?aGpq9@e6#XB zCJsthCihlxJ8Br?KL>6F3VK8SUVu^<8UGftJx!nT7Ijp3kW*u~KqStFLlK%8>EFFn zL)0})6hMLYve?*`WSTUus$L+Ap%afAmT1)wFXek+XX#pC>DEjfA_R2r?|pa)kX`Qs z!4`I9dDBvkOW_O*Y%4!TB?#(M8W;=aTyhTqd93#gOQhP_WlWFaN)ICUeS3e&QbEOw z!zHqY4I=o`4a8y5+^mfISk#5KRUT!U+G6Ud1?$KqJ94AL^g3D-UKZB23+m7TsIBPD zCOQM5@;IOLPpxfqk8ZugAiA{=-o9w5G|TK<oumaG*{u{w!%t&BJFWLmGe|GUb~)<! zYETpA%Jwnm1q<TR#eY4}UeNYV#vei-o<xsJg3#mY$lb+=LVG6*M<%ByO4Sj2<RlAw z3~sEmcdcBtZ)z}cQ`KeZTF`c?fwR$ZGAJe@kDR5_O}Z?jPa04|oaIoQqt{@X<u>(| zSdtEnLF8zL?W9q^9s78~7-oq~QzdUA!EOiq=`0XTj^WP@MMy9eYv#thFT!ixwb#}a z)H+*X77>+okG3wB`>ar&po0F56N#n6=p!$eB4M_$5HX5+C&a?FWo-Yb(|Y9AQyaCw zc#|F`yf!O>x>3cC&URo=D1l}lD1PT7b{0kmwk4#+l0brW-kj9U!a{34l^tbDDaR@` zSdM*gHU8Y^cB}Zz@#o=M9N&WM7Ipu_l)bSj?35wxw(WYb?W|~a@(reNS-h_j_n)`j zE)BqMMDBkFlP_&a-ba@5^|%pKhns!QJ#bzNwOwh5&RjHnxh_h^hC`L=Jl=b0b7RF? zH_hzv*CE%I<X<Wcsx)nF?MeyiPDA}hWe!hD_w!0&+2|LWw>mINZKBCMd;@lqoy$cU zvBa;kRby_2raX#aAL%@(1BiT%@*4JH)zayj+}+J?H&;Z<b9h`Vn6Q=ESRVsIJHhi? zrg>pw5(?$^Pjt^sAbhn71vOO{k9O-rw=A<Z27x$_j{-(<LS^vx12Bsv{4H>G&u%^H zz5M&0)2{}b)tjj#o3kvR350dOF3ru)r+eItUeqxB(b3D%mGF2ofyptDG@xleLK4p& zhF=4VFsKL>YA%V=7hEFwDb|ak)i;q>ZdYX`cq!@VcwJFqvOkm@XrT#1hK|3W!N`qC za-dV&7jL4H0o_7eq^SZ*DmJ@TMO<Cw-q09(LHY*BVleNk;5I2ElSUKIaqp!IVfPFL zC#O49LnO<OL#6BDWaC5QtUacsK8~YGCn}{5wgZ+^Wrbt;SCmau3}PAdwUA@b$d1vI zSj`iWpK^CtHEOnWN)*giM9URe3OH&xp&DiEN*hG@Xi`K)CpdDE1GN!-q$d#wC&FFa z6w87jw@tp;a@B6@G&H2yIgkC!k?2OuDsvT|EEk`BRG?-soiHVputPGQM4_{Rc!Bg~ zo>Yf>ac~vJPVcE8P<_22E3&Jras&}5>7dtZX!o!#KIuhpGd0cA{?W#>>J$IVd{3gV z)K-3U%yJyjyl;=`R1h8755v10$l!Gm1QlD{CZ+15O%al>c%3HQykJHmU)fiy9XE@A z@)X$}v*JRE@kiE&Vw7$dl+AP%`o@=gvDcCz>r$CW+gt~%$iFLvC$C+%r7tf_q4>xp zi!(ZPrbEfoZT_`ELU~PEi%o7uFg-fc9*;CSXEk{q@<cFj!v<fxjrSMV9B$+=fJh=l z1VC(SdPXlRwUDZ5=_TrNggXw>RK9(a6$CPDO)Vquo%2f6gG-C0V|WcOE2iPh^_|-) z4shPsoul74(dSz3tx*)8-PqFb-x1B~(1t~_KMcta`@!zwP0nK>u>0`kkT}r{3sD3R z{eZnM2b2kI-=n=<?GT4nvOsb7FYpx3CNC`Pymz3adEX1OW8#~`#<4lU{JsV;plMGu z(Sa9qzSRiUov>wNP{-k1faD~$uWa*Oy4HJ7jUnv{OO~~_pI;E}C-ZT@mHl<6U}j72 zX02nEA-HHmgxZHErY4xDHJO%9<~oVWjWt<M_g&U14SkZWtGT)EMK4)|OYU>yp+(F2 z>qx`$O6qqXPeN&&9ZoY!KIbp5*&aM!O3ljAbazWGuviv(LQ&${>FdGsgOBX7#Ia_K z44d`+is!81A^4MPZSd?}%eBw~Rgp-Mv`>*ylz7QTR_l=J(;d(<(c2)g379qPTENTc z8marfYN}Nef)y0Dx-mGDJcJn_$F%d2Mx}7e#w=EfG3x7id|#5?hKE2k!@I>x_khY& zp8{xC_QM${QBEzbbb<H=(=GSM1W|L(Jz7~Ct8q9Nas$hCpX~*UhfuVtQ{wy0ptk|? ziXLpcG#fkA(`gFAC_->C>K?_mCS)kcyB+Rbm*WO5>3Qi?gCv(nz2#h(-n|u`Y4vvg zN{}$8i_JLrHIR10^jiy>8*o^?lcX4{5huEH7dlas$uhA;@#aGb^S9aoB@X$q1(`eP zOq$A7{4He<nHq*G-*s8(i6I9?f}x7XoEp&?b{FN`%_>70)f*lf>p8joc?+{COV2xf zV@Z%JQ4ilD6qWcp5c3Xs>0S>xe&%ma#Q5wNX_nv}ljHi!E693ob!U)99YAP1E<6J4 z&}Kex2t@!9GOWV|uXt9!HNpoWJ0%omYaRQtA=ckp$@6Vh2eHnNLJGTQA4^^PEKVMw z!8tN04r`S4`}_ffZ;J;#B%+qHS=47<hEp1KR{w;9IAvuZvHyeQW<bKCzV-Y$jF1r> zhkPMdd-+jP5WU{fnYI-2U@6<dTgPp-wJ5inLfm8ZtaM#ZeT7u`d(_6WR?ERA-A2Sy z-i~wY^s?>Qun_C|2_f2aQO`j+RX-k9KW+=_NbhRD<(f2YJJt_etLp+GDct*OM=N}) zder04yP6v4r*Y!%HP%#G{lpS<jAmP{SIB|{AY8iS6OijxN7G-S8s!|m83H9rginSQ z^K22tQ$;$OdeM^f6A9@hY*Sej87sb8NfOgoJeflDolaBy(iR7le_PJ_!G2dYYsfJb z?{YPTSmqHWvGgwY02_s!_tZf@L3q?^Zm%Wo8Z5@QXGIrqyF^P>CHK4!qQnlrS#8S9 zgoKrOnlc#K)}1?Nr6vxZ=nK({QB$zU8#C!WN?;0e6iaGu{lSROTZWy75Vq1_o&gL+ z0Y(w!wGqKJ*WJXBi5m;w;r8-wm@0$oo7d}*v<FWq@VTrvs2nH+_kogMEb~-)xh#KU zJn=$-!YkIMB|wNq!3CYM6=nI`1-W{8)%wO}H>h$*z?NddM|KP>8djzP;88QX*OdVR zJH?twjWjx^30iCHqKfphRT>(K?1Q4LJ_Cms$}TjG5oLn)MBxBm*D6)<WbrU5*NYQR z*J9|KPmyl996nHdiKk+!#d#$<1=M1r8mnPFV!A!_hRfJm)RQhLYRge=%)`P)WPXIr zt;uNQ)1<~wKi0Q_dA)g|hmUY+z8=K0Mv7PVqo2UP!QM*9z<EP8P2xy=?KvGTHG$I- zy~CTex1l^LIp{)`GW{6dI_=DyHkgwzlcr9c?x=a~ChoQ=Zq5JT>%GI_TKlhY5~2ms zdx_pf7r_Y8gXley=)E(dOp55`=utw1(My!kndm|E-p%NJhF}D9e)~M<dA}#;d%f@P zKlfbM?EBvL-u9lgKI^mA4I_wP6a`@0?k`N_clYQl1b1cP&!c+Zyl}sl5hUN^%Fm97 zmVH%$JD3QX5wV5DF$R7JyKClr@thnJ<P7k0pEky<8OU-054EkOx`7t+`>w(ixJ)(Y z<saNfDqgOo8q3>5Lc6oF<JXIl;x6UtkB40wdHF`PGf$<jh4iB6<48dV2Llrkmdfe& z#t78ZSIm==SI)C$>I7QS`Dc4lsHt7ud#N?DPjxvAKN+o!N@32{Dn-9pj8q~LnL|`- z8m13mv4ADn@mY}POO01)XC-NNF|>qvjsXoS&H1JY+~ORX6rMwH3_njkbRSah1CG>~ z@f1aLp!#yVw$Q{Wo8{kV#C2ck-!pPU{2_>gOANAvJB@z8;)2KkyQWw`D@VRQ3)5qD z4md<MphXHG5?Zsl>}|DXsgVmQDvs3NJ-WSmwb9f;QMlLnfJIH^PJj&{wQv#CyJfx8 z_}X%J<<9uW>?<ml3^u36tLHBabZr5XN(ZhNLFp5BZxL39qi<D!rX`yfGhnHfA!VXT zfcX7O^|Wf=VelXADQOu$0}1Uy9!B;f#mu>1Pv^<sRO}5Bj~St+3Ut&mBptS8Pt^*c z3|jO-MjM4?eUz7j|5ubngSr2UBI6(HnHEv%r1Jh-yN-u<q}`Eh*&g0;>pQMYS9GQT z{sn~Y7YAebF8>fi0*Sw&zDhPy%TcHeYy?X6m?5epNNqePK|CxKcT(RN(omoHi|8>> zAjW6=2Uxw~_?;B8c7TOCmN@&G&n>G9Ro(f%{zCKe?OLc{&cA^BzthG7f1AFvLb6?J z<rh=*f&G&NW5)pHTW@?cKa=(SU(cHwK$iqp+xynPA>JyTdUvxLPTlP4>r+WwlbE`H zm;tBX*D(8gzSuM=$Z+z|?S4aZdo))9x2d`p@gEQGK>r7?0u%k-Q_x~_SjmZf_YAVy zX@!N`2bS#BJ~y+JAD6YRRcki<fODeIi(@zb{{)uTQ~;ta1?{f^OopH(O)Mhw%Y+;2 zs$r7*hI6dI(}3g$cY=Pg4c3GH*>4<+3UZdvAsc|?IDq{Fv;_rwL1-B>P%YpfFJHUj zm~!eqB9;?MzNy4~M&tO~^&bCi7j6OfF=RuK_a->+hRC&~%CY-_4%DW7q!_s1;lKqS z(|z0zQn@tQ{s+Z=CNa)KCSKw!g#t@gvB>@h_!?XLoKNac6xDrg)`WVsa>m#8-zECS z`fZGWSJnKt{r-(B!O{7h?`gVu^mNJ{MkwMT1o*UMnlJzHri>8KHtoWHJ9{1AVZ@pQ znU%sCbF2UMHxAAJc>lL*{Sz7t&<TM2W?%k3u+IRK2>7e+8`NI^K6*pEb?psgn0i5G zC9d}it2}`i-3x*nU(g5;WB`1383noyv4S+gf6S^|ZNL2!XC1kI(~EUzk;C~d8`$Od zPyn2bzrNUtSiK|#$Q}3%X@GwpI1sA>VCZ9D)2u(?(6Fptzt#riHQASp$pwJeB2g2v zp90}jVrBs%bnyclfQ-^(HXu646yN#~ejVJ8UBepT{Q4_swi1F>F$JB?O=~p*1kiVv zZEP!JsS^Hgw*FOG|6~S_-T4F@ka-r+!TciswSJ@X%H*%8ga7{h4EJ|m|IXh+gK=Ji zI!D8?4=}rEy~mixYfPdb6Es;d%cr894JX7>m~-LD^!%&%+nSso9_cegeUrNCcXdVe zpYz{jyGw>L&Mc6VVR#?U6F*;q<}KohNhWqUeRi7JL!_P8#1T~$t6ojS0DcRE{8y4Y zzo4_xa98qs>h8XZ**+_*s3jqql^I)VU+blN<D1OALSkyW?2qi4O{~OI&h-xOuX)md zhmfETQp1n5r-e+rWc2s5*kas805#3Z$=raykm4(TQpH6LR(Wwrumf|gy#61XO&)yf zPo>SH0t#q19|^9e`T88yr=?n2^vZC30unA_LY|HIj8b0v3^jom^!tUs$(T}3*>m%& zu}(Ob><<kVXn*2a+cwY=Zxlp^@S+lt@ECb2_hJmZuR&k03^StvgUOg=I5j%U&ju<l zS=7WJ>HnzRc%;JBNVbCzq31P4bM~_lhTX-^0F_XGI1R?x<L4-02V5i~oiTQ0VQEPf z&!A$q2KGm0<@~L>$2E4|VvgzTL}J%>P=S4k0F0r9qC6w~w3!s>o=$G&>7r@Q3-CCf zYTj27N?NqCdhbVh6!c2b(mnC8;h4*{LyQ|j7Xn;0MB+mBT5;qx$(;gUx^S4gry*K- zkI``6hG<cbtdUM)rI!hxU4CNil$n!Q>j}ZRhk1IR2b9sbE%Z}Ruv|!)d|iR;K3C2w zC|<Hf!=_;U^6Ihdfjsx8u_2T<IIehZi$2nn^s!OAoMC=^SEx^iNIb*Kozj;j&$?fJ zJ>xg2*pthh`6R=4V+%o=9;TtH5umqztM^o#t1zY9f!6BA;}w$!COQrLPedQJ^mCOp zKFBxA{LZ;e_#?kvjifc(n6Wt8Z$Q#Ci^<3pumB_%f5@GQOb~ySG*<V}7}vb^$7dg< zYDo+XeYNI4+)#rcU*zrKFVG!dSzNWK%Jj1_NH{!lKlC(y5#JNnAYGdIhqx-&7073& zW>y%eZ7uLfTuE7gX;1a0{1t4TV{D6^8#}nCJ(C|vO6;DyD_l?1N%g!DDXMiddmi}U zX#l<<cbI?A3W-;dzs;SUXSu9Ui)6zbMx&)5Zf-tn0eAKE<22R!nUVABMVg-w#1Y?s zx1X$bWKBKq5O-Xqsi{;{??mN?(nuG{2l`zGP#u%1(#frStx7)KVmap<!ok5_a}D;j zcX9@%8GDSQhjerYnhLAYZ3Hs!{kO+~`g`TsBAm)XUAUoKXlqw~j+L~m)~cm%rqw!= z+lg%Jp+XpJT{Lc$6k?~qxefx%`L=*!hNCtrAcLoT-P#oy@X6D?T<1LW)Ox7sBk443 zx%<HEz*fIO^WB5QA@|jH+pH8@b5>olAzxa09!e(%6bLiwPZXxtxu2Am2G_Qj1YiTY zLaF7|ew>7KKl(2AQC^3cmB)`NLX@n`Xd^A(B+J;YV6<Q(XWbwxm79A&it{tZIf$V9 zn0g6(+TCJYwr46nl3}RHpy-pn2#aE0r|AF2$-^}g5Eo3|CAwg$g@X4qqPG+LEZ>nw zuIkMf_Ene<cYSAaOK4RadwiM5sem~-<oy=Lr$+{HectU9$J=zJrS5;yXJAhAJ%|QZ zX>e5xXFZvK-SoZIv`E`Sx;WvVtr-&zt?4tuIxjry+R)$81NTyxv<rGU#J2^;o7idC zL#9s26u*0wzGAVlAN-Otne))S(3bZ{a_zWkrKtP-Nses~E0-4}rnyfsr|co323+Q0 z@O&XB2x>wmf1E{|$}M8bU|u{-P$vh8R^-R<ujSFWvMS!>VCh{=EJA1E_A9}LI=K^l zgGXDk!q9ifg;~7&pti=31%eF1`pFAxvboK`lYem=X}QaK4-*(zxML9**H^S)yj*T( zy=&URR_|&GYwb+l4%UT+yXcRnJG(FSJ$2wMH(%He2mDo?KR2U!Km0sY*0%R=Nd7hW z(1P0s+Lcb=<Q|>lzaTMYy0Vcgp?~g@9{TS5P{i0kB4lXU<w#=7&{MVIOR`B_Jn*Z- za1fjJQGQ;nn#MlGY^Oh2c8Nt}q5@euA|Qn@$k~pH%Z`+)F$+4GjN{Zd*n)ywFrUyF z2%E0Fc`X}aFlV=y`5f3#8|HpTw(>CBuHmH5*5BMfmeT!O%Xj^AZCDT00}4>ywIZfw z9r%y4T#u+;dy9@ZMqne6hm_qWbu|-lGc7ki9taKHmA+6`hY{~^wq_y|51F$alFjlt z$O?M$>Q{SLS)JZ@{)uxhL|>%fi`AY<ovSo0>aoj0e4&ShB|)-m(>w3*RNQp^#z*GU zK-U;@rU0o&cTF?#6LM>5HywVjKGV%Ew#Q;PR;qsXK^cFCKFMuY**_RED1JoVkybY+ zvS~zkQh-U=G!1(}<ukr1aeL2Q$TUR)F70VkOzWm)etbGwzmg#c6_i!0QoT!d|0N=} z2PqJCHc_r-W^8P@(F3VB`r$nLten8WX!ChYqFkw7df9pEsp5UGp+3gG?E1+x+#d4& zq~3-UUMG1-r_mU*T;<Qex<_*8LBEwU-1NtglhBmJk!=kvw=g44FFGRSN;$*{<r&?< z42J7W%kvjFi|-|Cx(nthYJc<)9(;ghuw5oPS=JxZ<~d;IpSwv5p+ReRu@cnOqe1=c zx0T1_9~J62+af#<Qb|s9<S*pnherK{-a;K*<5b0!Vg<vt<lSrtFeJdMY=e~@t@akR zf1WujFIeij@DB4{ow2`rh^aS};|ZI*F55tq#;Honiqw<vZ?p=lZ4}s{KemD#0yAc- z)hX^EFKtb%PJH7vPBe$orC63Y5B=Qx7ql)?Opee@M3Ma)3`YS?83ZxaZ^OU(dD|RH z1?_A-i)VI!9sR5tAmHCuNBMM((g@gCRr4FCzEsu**eZH*ylcgVW;Bq3Cl#-C+9h{c zlk{`vX+nmMr;xrz*_KS+sQ4E?W8ao@9(HzTP8gz<=_)U(MXe4^)yb%n80#O;@$1*j z>C?0!=RYh)o$u9sOg1^pWxBlm{T6;Q;av!aM%_>S5E0BQVlJU_?U)U$8%pmo&fTNP z5nMbanrjw2>Ki04M#0>gKTq6E5w0#WmQ+DRzXfq&!*QWor4D0o&Z6tFEO#AN@BY;S zP74t$bGK$4M7(%s`QAHfQ<&?I?+wuWXLXOaS&-A?gVp%aSp^KDL4#IH6BkCWwudIu zo*zPohmX3=t+lu66p72bb6ie6Nc*2biC&1&SLlk<6!WizcCfbF*y@p(NbVz?RG5tC z%Y3R1NlJ_hV$XAcz6Ja+0X=j|Uml$z8K#y8O;%pE$U>#s+@7u=hv{|3kFuOgUtUn+ zjyNXFlfcPm<v<#tAqxWieXDi39}vgyS0vEXVTvu7_v_Ij{vWw&uJCG?D-TTXqH1+E zm7XJzgLl<*k+(c-ZC-@jsvnnUf?|eL#{&E95w7KWB;eN!c0sHQpo46pyN@@yi;Nqy zlz#j;VB96T%=S6~CANHm<@HokflvFz7K<bO6u1i}*{6iI5`tqB>pNdxNRMs_$w(h> zE|f)@n_10?>9O}%_~OR(XiF5^Fi>x*Q8WrVH>~3m_Rd?Y>5?14;&S6TJ;~ahAVX{@ z5Ct)ndQ5sGk)6nwx===KiYWbW1Dhy+j$9u4DBA)x{SU-H*YORGpigE+$<f=$&DkDp z_=gqzsh>=QKlO;DD}648y;-TvGYiwIZ+B3diAb6C1gr2FOb}cqfLQ*-Su2Ck_=95e zU^C^_F14eNEasu@?T5YHkE|^v1{7M~e50RIk#wp7*bpT}{gdh)f|#G=QH(d+;i8go zwieNt5c6~MJ21qRf>zg~?9wC7DS!I=?;h3p;>h_?sB#E)2p!$kp!F#}89FaSr^C?X z>lsnk-bfZ>QBNtIS9?g;k45B6N1wjWeM|a!7r&F85625Xgf3<Zl?fpm>zee2*E<U? zm-LS4%vS~#D_FP;Qs@Nt|I9V+3Zm7FD>o&G)|=;hSr8csJ2%Q#HV(2UFdy`1idV%q zu&RsmfQ|~JBy9sd5D>-OOZb`%-1n#6zBQ@u3jWmv=m{1!Him1iC;{jYWC4`4e;x1o zuYeRK=1KrY&|QlG@py}na>x!(E8}|G?;{)mQf=(xMz*t~KXHB$mG1pM`b@?c!}s}C z>(8tAyH@ytyB7o#Z)kx}$T)v*z^K@_IiYI-8ag7e4&~2qts_6cH*OPLlK^RTQvI_p z5uTSgz)JvttYh&wPWnL5+7Iw5R@oae+XQ@+Ra5Q=P&g-4vDo&0Z1{A%622cRKHy|f zjUm7eTiyINP-4Lc&V_+h3OHG1$Sgoy?+9DL{1yK_#-aJA3!_}IUS1G5^Bu)RfHjfA z37`gANld398+86a$jAh+8%?i|q--wnmm#zDc|c$c>zhZd=Jzc6ND|L%;V{sTMC@zP zZ7bo`>(C*fgwAw1<%hc(lmrM(RIm3FX2(Zryp$>L=G+rV3uwUw&CM(U9*Osrm~Aq6 zuTMP(6Gikcw^q{vFBOa8@(h(2!l>>`+LI|gT6}+2DJl-S+<|}c>39H~%p`z{D_U@l z+W;NQ_7|-G2xf||<;~|M`MSy6vq)>vw*$1kz$<@9|GMOM_6g7tm+OA1zd7(Hj{M>Y zzzp(Eji>B6-OfR2@GEqB*SkG$3#^L#d+BB!54jdBfo}}`N2u`66xqlLHZ_4r-r?s2 zim-v1>i11EKzSz@=$*JNI+TJ9YTQ)+`y^Vg^9<GWN<WjybbsHkSWH*O3DaclYbF1C z{l;iqUe#t`CFzhUQ#vJ<i%hobpEe_zfgDVlO5WJg)+<JYfF&E|CKB6Hefs%MkPl>3 z`npuU8MK`pX1u!bD@#072gi%mD(`d{E^u_X@%YxQ^&>LuG>=|s6)}+W#|1cK0*Ti+ zN7sMvjo<&-{kLD<i0pqqtgx!hXCL%ZDhvDj5Ql!^YKiXe|HKhewHP>)#Qpa7jO7)m ze4;OXRbGKI1p5|2ibc&Jprhxn6z3(IO(ho7zn7i(_ept4KD)CT|2X-a_Hk2?g1W-+ ztIPi^yBvyo%+cq@cIkeD?{4=i3uo=W=dr(913Fk=A6>{>kNAZ0{kGsg9;yt^HlBI` zqby2$!F4Nm;I_EP_vyO&mg84Rr7L@6cl1iD7xFN?1P7XHqjQ04S>RLTaC%x1=E@v4 z8gn*uqsx=1^LF!&ApQ1>QtB6kajj<MKZs7bo<w?*foS9vq=@x>N@a%Vp#h5vLxDSu z0oHoo+w9N+ip;3NbV|iZwrG!Z#w@E5W0njVk&`%4rowEW)cc;Vx5sP<6sa(vHJh$s z0tCSux3+lR?ghJmfb4>JyKJY+qLd*clXP`qt^{h2KnG5)nY@@bPQ)scGl4Q%?PH@! zkx}aX0OhJU26J-_d-jCS2}CSJG@Ik_XvGKDIx{dqc+^5*xF4L{3gQTMjynmhMK7!{ z!P*}a2?jbH-LCbx7j^KQKa;09;l2;~g4*gg3nO>*m)=84!Ngi?S6UvXsAT^bO?q+5 z0nP^tZz7`}xc4@ExjS1NiGs)TuQ_eaTiq1hw+KlsoCYg!)6o><R7}En`PD2ewo%ve z#Arv7cb(`k&A1OCea4~Hb={^7a%uJh7L>&vrWSBGk?h*GMI~c;+&XbIboH7Kl^Cf= zq>6;lvS<Zo`;XZ*yGngc4!*j0%P_M-L5bAdunjjkS!WCML0bWGzxqnfPD;xV2lRG4 zOu<keKK1g{eLH4mS~BS-)B8c~30@<A^V5Ww@gG&2W08wo12R4UFf;?y00c0H{SKP( zHdTMyl2sM1z%2U%I*YJ;=SPqI-MPdW?)6LBX|mF%oP1@^c}IUsvG{$6N1y!}D_zu! zy~&JL{$5q1O--(>S_^aQqU_qOEk~PMH|*^V3JBTRPYATp3=>^Uw_#CD-M2D<RIj9L zzbQTuv#A{C!R$)D1$aYjs$GaD94*?F7}3CXE3YSD0n`Jb?v}K0?<hD=%c7Fg5wr^b zKspt$*6V#2$VB7P<v3-~XPHfz4I{7$v1^Q7D|%mTF^>t<L3Nv960kFb*s<C4bDLL_ zoXrU<8X<iY@_{<ddLP{oOKPb8LQEsTBsro*BdV{1s=(UM#;%`<NGaG_qGvvUg{lsX zI!}MpS{5&e@cK$k#hJ&j33((a175Qq!AxrxF@AXw&jp(>2y`B@I?@((E4!qso{jP* z_sXQP36^j%kcGJ5$rqB)6wdL<k7q%?pwVOxyGV1)G?5?*AMt8x>U&W7Xh3aOMhm)0 zo$Z;jd|?syWs?EsYV#}hLsRPqiRX9wkg^ier4hZe&=1wTrsPB>=~Az}FpMtu3LdJ> zIkixAkH>8aDOh~%(NvSVPqj0O;mHFGgX@7V7;-cLlB|VJ38PtH`8--)c}t=S{KZn` zmQ{XJq<fD^)NHeV2Dk;B=fRPnzAkCQwixo_D++Q@ulR7UgKI*O5U6+kCGbmt`${e( z)bONKS}!_jDvZa!Y87;IKeFSamw!jgYN=X(fbFsQn%6Z>-mCWpRNq$_ymm~#W1$=E zTcL`up>7j%mKJ?U(^Dz5PibNG{YfSBi6&D%hk6{l`!>mW7)Ajlihv(#+M`MO;e^Mt zYM9t!p%nsjKsy)2Hfw*Rr2$scT0i+k?zNuqdkY=v*{2`2vSbg(MiT4ZQ{0V6@Q>>s zFMX(^oU;qn;aXbDv4_-ul1m9WnkYhM>58czt+0E|lA|t29ImChnzqC9@kJen^ztYk zPAAT^4;mO1a0^JGX{Mc!B?AI}ypd1=e|`fa^}f8w=Pa03|1~C0mU*pQv6d|47F8*~ zm{n|?D*e+Bs#$D;?-({$aMrxfX2Y=$Ng$C8d1Tl-VLfb={)7|r9);s)a8h+dPddX# zZH3M(R5$rTmO1b<Rs88FS9SdOKq4Q8{0bBzfjL7Y((lg-)AYZ))_3MfLVT<rqOd>L zVb>EHQ=xn#Eg*UN{dWK0^2f}l&b3AL0Dm6dc|`@L>H*bx9-5=+OlIVL5#{uz2ta$n zJ+>{5snbiAOduld_Dpb{D<tD~4ym{O%E0wf5_bCWDZbk}Nkr!hzLx3x#0GwgSw5)+ zOdV!ihg!#<e0{n3H8s^J9e?N}u*_DfpCGnt-o_GcQaVnpeHGK(x{5O&i2d>(8f`rv ztl;L=FPSLU^@)6xm<&9S;D^R&$Mdo#RA^&2gb-*TUzk3d9?2}ibp5h^HD|qO?v^}4 zRA2Na)hTOX6G=rlp`qO`5E~is8eV_#4uCmxaI?Cvm^{%pZ7v}yjwLH#M;%mQ<AOW7 zZsLHeV_IaJPE!b%BTD3+&Xx=lt@7rppQABZ+g&!1Y$#oSG(jZXsTy|=LVYcY)Mkr5 z{?ZtK;DN|CuWyRk+3l09dXvsqxla4dQqsZUjn?M@L4xBjoNL3I+%O=y0+V^=at%0~ zDYEU-vGR^@p-j6&Spi4cG0SDATn1RvNBIki!7;Jm{j@8m1hWMVPO;A)Bkgo^W<Ovc zQmLo%-2%lzQoOQ0hQ%gS<p#uJMK=}phs=(n{EhsQ2sIO!rt<1%$1ox<5Y>yF=@E<` zshl5si3vDF;k7Q*%!hA;CSNN0+_x@G#-Jdt1}f(gb{f46r%=4NZ*w<{;W7GsFDv&L zC+g?diVViLGn~=F+V^g0ILyf$aR(F~P`j<u42qHX`r7pnRUGrww?*CTh}=*5l1|5B zJn_WNUcQ_k?-pUz`|~Fl;73?vL@`3|?p`i!8>%l7Wn<PpBk%9_Yd#quhz+!p{URD$ z8nR@M4!VV>hDB!eq&o}j2~9Lz!j^3q-2i1gTyGriFdF?@q@W11`aI7J9r4z!aCgk* zJe@AURKiNfP2WN$^MEIL-nKbeJ2uFA1LpKh=Q7NGZH9D96gQ$=z(1qj$EUuuQ~5~D zUGP*_%ttS?co+{BVAEOmi_PI<Tl<T(va#U;oxw^5pOG|yr1x5>+fb-UeUS5@L=HFc zl)$8Kc>N%>POx~N1WBS%puN#>CBA&AWq0pLcylA}U`gA3HzgMab4CpFs!R$W%X=gD zT^HjaHvG;(4qwd{lz7a!A{JI;k~04woRP%e&WueLQq%GUo-#nb7XSQnOeCTM4j4Q0 z)Nv<dm-bSxs3LnQ8Mrm=Vx%%dR;6gxPV--~K51>_2&oe6>W~`{XqgX5({_Psd58?G zI{Q3Y<{hj$c6~l;1N`1blgmQe+-kQO=PVwS^CLNV)jnwXHE)WTMjP>L+{A6)mEY~B zkkV-y4=L7mM3bAp*Uivsj$rtb1>Q>gF0h$oM~usid)2-8wORtr)>%ymK1QBbquESj z)}Q1V=`Fj+k&ee8R|g{|2sKmi>f@<>1<{*p=|<`S!qBQ~4HR8On_nL3Sv9Ts<MQt> zp1du*l;53;68_ON*GPHjkg)vm=?-+7_}z4)aRxXR=wN&W3ERr~GF{&F{KVNmq&9g% z6zROPJQ;X_vF#b9Y2*Llx&_vp%8%+tY!aAMa32ah>ya@Zq{^-RU~Xib)4pTUvb|l* z%ix_?-}nwIeJzDaLy|9Wo?BrWi>f1!j{%9#apVeLGu3XiSi<U4%W`L*+9RVY+Mh~X zN$v}3ff^I{H(6N|kq)i?GU073YjElX%^+8ieB^Od`hrwMw6ABNxCTR<^jI7Dqt3fK z6MY-KwVd0-LP-o^5iKxS2P}E;9MCaliKnOt+%YwHVD!Ed&+Bo;F)dhkvNw#P1LZvB zDY+PY#WZB@A(<I2!C|djqYe8S)WwPO821lmpZOaCVe~$JeCJr_7T8g9(i>*sA|8+^ zDk|<GVpXc?vRG%@Uf?-%0%2>Ch%PXYcTVekRW_YEBNERTP)x7<;9FM_Yu?viz4Dy? z57V5d{GA2-HW^OTGdA-ueE5xBp|{Ti(4sxj*SeDKww;V*`G`Z}t`iBC2^;IjZl$;A zml;?1wj!S;^WeSZppT*AYK2h9yWGt{)sl99-+PGVw1L^63`Q}$dA;NdbZhN5@Nc0W zi-u^)S)U;YU5tP5TkgZWqpGJ59@-MN2DjQN+Qq!>Io#6duz-b$f!ULah5$?<Jc@lM zxQ(ff5wGIyoy@&cQKpvT9^^E=7*J=bU3GNW>IB2~pvq%0k78^0CcldrR5B`#<Q;>e z8NEN0o~rhVCrTAv`oGJNE9U3g)64vSAUW5~#A)5&PMp43?!Kk)KJZ!PpE!R5lb4vC z6q*J-^naph9v%Pvp*^N2TJlXvAe#c1`CMvn2L5h<vF<Olc>5ZtVE>I=O8z^QDFgtD zf5D=Dj6I8g6GQ4761ybqKvnDCXwm5UsoptFKd1}->t2=goBuO|N=XZg+!_JiM>ZU` za~-cU#WVm?YkU5}=-m)L!+ZWW@Y4G?*kva8FMOOzRw&qJQE;ADEc#EKUy0@Te}gUj zc6%0>Yx2E69Nq3I>{b8wi=pg!2iYEw&A&Q47!-@%$ddm(gZ~P>y$%_E0M7Li6?VLm zInU54G6v9#E69w4eo`p0c>eFh-x-a^O)-f2yrektkQr!=G6DTPLkk2iS+ev2WE0pd zpoahZ9G)0<dhC>y`^XQ+#ADOPDSNKB`|VO;0{}&GC5+>7`8NZwbIJ)o=Ge>G+p0MJ zisBqP+_zZz4@tglV=S5>e=pV*!<AGv0Ngqv+W;G4vG+UL9YeL$x_*`5#~~Qtym@aO zrdL|V%FlasXFV6d)A^M+*8e^H_?G&gI0|&9Rd-@=4$ss9=NV%wO83>ju7$Va-<w}k z0DxJGS!@R&q*ta{1YkAJ8nD*&Bb#44t0M)aBLDmiusJ%nu}U+mXWvcftgC>fvAcTy z+Tgpj{8za-FBaHI@zt|oR}t86IV^rSzh$ggE&Fv40EO>|K-gyq)(E!|NZq}|_M2bB ztmeN$QE^PF-@`Wm%E>MJmx-|p<`Gtf?R)?Z#qsw8*cd}J!S!1Y$bQ}#P4BGpzl;}d zL2H0%<{<k(SC3rG?*p8pzv}dY?*IZRF&eZA8fjfvs{*Yf^)5yMlHo6kX<-L)LI4!w zt2ipBt;w-U=c{Ku#$`By$$xc<tYVw1PpTT4MgPkI>}UOnBY^V*FzmPuMX6tdhXJk! z{<*TH_n$#^DP%1dP}1u`Si%-_<y?pQo5!yS3YN++i9OErtDI{xbBBSqs=Wpu3q3Y7 ze&57hkYH7A0*x%(GYZf^%O*yhcu)<LI{;Q1S|7NBG_gd&OW6}*rtbC0&4<8YRc+=x z_K^e$Dd&xt%>1R^e6YthmTykv;FarN&is^|OXLzl2Gj4-?DaFx(}0k{D2OtaAGX@( zZnC(x+U-fR``#$gq`|dZyImUT*94Im(pb=_;!ui~P-Eo*-oIc@V=j%zW|U*N{3Fyw z=P$iCA@_?z6E(+vewVxvnH&j{k9D#&Th|%UmZmVWkLG3I%609(RzWTH=i$pkibITm zDj&&yJe>-fi}5Tiq1@;6v8$vh#MRPS?eK(iN!zQloB!6<vz}bLL)479gJ+*tWlZJ4 zzS>HcFfW6iCC@@~OMtV_iq2J~rYZ=bM<zSUi4NYy)qaR%_M8r4j37>dGL|muK8V>W zwoshb(kgpC=v%IT@@%v8K!3FO+bRv_6p6nfrx)RI?O2K-F)}Z_rz|9S0~&y5*<C&P z6Nk%P=;W#IHdFKjZG7YrhkfGLly5CIUB%;A?tNCA=`&3(w1%G|&&1)`L*Z}lRL)%q z4`tLneMV~Pp9Fbw4KryRl=Vuw$y;A(0zOf7iYzFykF$(fI*>qTE|43%DY%i<`o~PE z!k0GvZr_b?I>HxpB%FT?d2c&_C)ddVax;OAhHLr-niXCRw$wz~S%l@~gC)8y7P2je zO0}wmH&$(9^l5wE2|f0^+u>d}$Z<ER4L;v&|8&qmo9fZzyOfkfI8R0^S2JbId5VjP zrumA&mUHoqLgp4_aV|n^NuLpX&FmOc9G6Zr2-P%x-WMA_{ZKiVl15-E^(I~~XoNm% zuqBRq_cavW>B)*Qmtv#cvti_#g$14QdsMmW=6R(XS_m0%1vJd;@C5tP3-W0sYl^Vm zi{}?V($VplZ<9>wXb*NIY-)9KukpS(xw5_L^!h;@Qot_Zj^8Bw&DjQ~){KCY0yQ}{ zMTWf<;@J%phwEz}OxekZEG)<x<V!^Bqa&3wxmJ?^=Dc_4HFsa77pb=pySANxrQwaM zKc+1_)eC+ZN}9be;DK6H3C0`A%;9+7!1Jo-gWFxoe4Q}c-sj94ZPw3?(Ywk8sV~Y^ z(ga&eDk+P(3!EkMgsg1&pv7xgF0iT|jh>+Sk&QZuOhWnlavP#yV#9c|XTMUQ{Kaar zE(W=R7imUDC=6ejK|bRjF+YhNK8_EdW4psZXfjyUfHNYyoN3-qLBcR$h15XXbq<K= z9kYwDI>?>jU{LPpOOwInWE=)u&9@Qi-PQQ>;C`i!iL-rgi0kdgfVNl1TORN@b94Mb zB4Jnl!tvq87mp;lY6cADMJL;w+~M+B+j%Yzsv)J!T*uS@F1o<F*IQuma!iwpvgzK4 zaenfXBo1*-nh{X8L=^+Fn!Nl<i>8{WRIs~jGdTnm*pT3Iv@7B&ReH&L*NZ%cm2r~+ z&S-DsP=ZL^nd}wtzHmj<G}*Ycr#;ywGK?<^JIV42&wt3Lt%0^_s6MPl+w|JhA7rJ% zN&Q2qI&(!)4%rCH0z^6H_y`7L%+};iK8}#^^a4B)>?m+Kh6z(Qqx=#*&s#AA=*50W z-ArXGLK=#oo#N7LqXUbs>6i$9bm#6cw+<O|%futQEg1dSFwO8p5;ZJUKj7^tq0Z&T z_>dyX{)G=AXMW|dVDB^64ms3OG5WdVbUh1=2i`BMbbc?9r|)R)?s5t|r0AD?=+-dQ z+{~WlIoYJ%C;zrWnoYV(Ev{5hAZg3_q&fgST`HYw1s#E1QE07}cqLAZ3jdIW3k_qk zdGpWWxHlP-K7kFki**${uLS(rm(>M~N{w=Pia2sguWI9El|`6x$!}8ILf3V0MMI>} z7k#-@HMMQ6wT-CN$PkSM|At(Smb8$3Jg@7>hq7F`N^3X-AFqKj#=Ga&49$!ypP<sE z-o6M0X%-WrLlKi1q`oI(The7+5W4hZ(<wIvO}uigrPg?m?+x)Pvm*7i*w`6c%z1|- z3?6+Js%-7qy<n5+Ulv3K<b1mOrHgrddTZsyiO`>0^R(Ll*^MsVM!*xp*ubr(m{Eic zrBf+VH~=gx<PpMDDmC>BGXGLjam;PPsUYJ}FQiG`#E6hy@U~46sw$|DB=Uaz5R_Nz zL1A(+lML@5cC=l@C>w4p*yt?rE91rq&Bn8yb#`)aN)<hn&o^7iXc#XgP}RO3Sx&4A z#P{fiJh8jX*)_aax*we(UEL4IaKaB(5uU_5v^L~Ym97S8)%I`;n~3^6Y8UBk-6@`^ z!j$KG+U|EHtR47b6wTM~=wC&M7}qM^3mXA)C#^s=Ie^C!Z=W@8J;tvR_l%s<%-npp z)Kj7J9T8{DxQ8v*qlg&#FQ?DsCm*oaMO0;AiI%U_Ft)}w3D>yD;~1>S<e|v5)EX3Z znDFT(O*eJj*K}=fnPgVwQyrEz{C8F6Uzn8e__pD;i8LXU*_~MgU2H^{Z+j3jc`2m3 zb}z;AJ*1`U(0+;ktt=yvB&!}=P4=vv${wM_%>@nHx2RHZ&S(tkGK`Zbrq?8=#6;gv zOFI|Tex4LNZ<9_cY$M^*s&U0C+oOX2aSEFG%4JYi=&4uQ6tBsH(!>1NQiH4<-h)!v z>3kj0<>p{blOA7-PqVp@P6?0$AYTljM$^SY?8z4j^y*>_$G=R->myn<&OmibOAH&X zvEyt>;@OL4T+$DQ*i~?IwX;Jf)gE|aJk?qtxIlnUR>*?qn|e=57yc4w6Yn`oi}{@u z`UnlyiRm@-6~dKZLdSITS?Bnw@3ORL0R*H|UlFu`$vaO*O-FW;lY?vhX4*t$-gWT1 zE=av;Zg2-ZYiX2T@M+R6Y;5K+kG78-UJSmoD*16NFifrn^QlxM((_6QGo<zr+^V0U z9ofZS_^>uhdXgvC)h{t<fMa>Ns6|A&yr-sj+qC^dw}T%l_4KK|>Y-R*&gaQ3t43cf z@?3r$m}#LcUPY??!R$6jV?^!;XnHVnqmFRcLDC|fmieq%v07KGQkQz2an7GeXR>#A zHkC5&#kN3lPJw7T@T6&nAOaKC5<KUJbm8$ZKnXJE{Ms~rts@lFeV)smyR#c`F%wgL zclN^Dl4*Q<o`C~bc)>W6!mi;b2=CemZQ3pRmdycvlPkr-s29m-T~GI%Ipdjs++1(* z9kqtGB>RYUPeKGwW&z=45Elv4*$Nxl@!ikWJK)H*#J(NBeO?Tt(0o6sJxAD;bStxX z$#Pj0f?sdu^;MpN$Tr$S>JI_Z&Yo8n(IF~GwrEDs+crA9ix%OAQeS^$yOv-;^2pH& zU*-LX!5RM~5``(zV6NoPCu^kgGe;S&c!5*_9U+RGd#R;;&n&7OA4z`R+8$+aKIE9t zG;FCiIfPx(QEW}4>F+j1HpLPt2Zd24@X~41L{&$X%ImU>m75zB8+_6NnSp=c%f+}O zc1B5vn}X$JKODGXHjmzaxz-sAqs1ilb=>!xIwOx8281!x;!18(g4TliEta$in}x36 z%3fG|LwDj*7xCc|eJE}an(Sz@N0Aj}62Ar~+C#gbU5BON-leLc)CLxMMdmgOf=aO& z?;b7nskEpEQCHOJP*shlg}9<2Ypb1XEGoWa#YmuHzP6c=@zOsOLBeD?Q0-ClwXG)7 z2;?kySMOEP1Gb?gWXseGJ+ZKnJg1*}acuPg8P26nHnbh2uIjxDPi;uIGL#c&<NYc* zkVt?ADQ}(U2w(c#P&+9plf1Z<X0eAyA!uEGTV{yQk(w`<(WQZ5#4Bx9(%AS1l)$wQ zZ51<GlpgnG{Gz#-V2hbION4XiWcK4!F9J<dQsGWGL>kdO(<7oG$g7?~StI-Uj}#-Q zig5RekyA?=-{jA$LvihDmPE4MbBO(<yU<FgjalwP3&MwdF;L^iM_RTjpGvYjlg8>_ z>B-b!cA>j)QorM<Rhp3d)nGA?%Bqd_npwZ-32pU;_~*~mzKuZ5v!qE*!#!v^v{Df2 z32nA(iSw40=*V8SIxAP1T+a4!5q||mzWn+e3m2c8GQ1e6yCh4BxqAjwLX}N?K`hC7 zL>MT-b(Av1eY%Yw&5E+wVZ=YGR4fmObW5nDOMV*8CZ{tq>ZNU;=cj#|asgKu4&hy^ z2z?3|!y2XW%U)@TZ^G+Z@`M=uZg#c!WvHh=!#vbGH&<?fWqKHBed*qotI;#o?>y`2 zrn*{sGVQ2VUdou{H_fkR7BrUQHI|yok;5$qqn_Ud-Gi)sUaev4I;8y*#{!*qsJ`|c zQpZhUv)k}`D)4o<I0K%8guTb}?bkKkC5b*SWATZ5!tMdTxlOM{AhC*4nC_d{n{2?! z!ZA*Y#qsLVp<>{C*z_a4&7f@4u;r^jcdK<-hF)JFwvh+amlxk5hUw>y->d`I^;$&K z&MZWfUCdH2m1pwK3lEjSy5lj<X16wI*{Nb20TDZs=uIH#7h(1GQ&!{1p|atLl(cit z#wB=F)QwD+&FvFWA_1i9OK*uDld1wbesfhdnSeM0y%mqc!J|QbzN@80NqyDV1cz$m z3Giu4NE@J{Z(i7G^T(Dg-fUyjM#gY0up~f@y$)#B2N)4M6Zks-;tB!H<=+6CawQfW z0QOSL>i{rVF!2KDtx%@vH?>E4UgBCoTK=X%i1W07??W4JLU^&^0{<HE-EIazBTf}A z_VU*(#On6V>DgzzzhGqJ?|}zp3%_|);F#V=!Y|2n0P_VrQ=5NL7YtJX9`<J?0%rRk zPl<k%-u1geKwAL-_0N@V&v4CH<*w4<z(VI;!@kP<UkHZ*V)EL*(gy$(-v6(r02?6m zfF=doK8g*8O+5qNKzzWFN&5ksM5>Z_6evi&@lcHZ57prP6PVd-9M~9P*FSM=_<;|J zj|3zC*9UyJV6ga<MYUslB5qu+9&zw5fNrQe0B!e?U;Tt5bb+Euq6YjwU^@BDeeCF0 zzyyRIbUXp*!F+zT_g=rQKR@?<T2}obfrlOUfIw@%d>MNy1cXXUeE(_|IElj}QPF{* z?eqs5kXngJYTT2cDSvKR*WJ#a;xOLxbb#Xko&JflI*FA6ATtc!wG7e@wxP#3s+@!u zLQxH|gyatFUV>dEw|Cg)A9d!Ep>^K}R)7=r8mB~UbG|?qh@^|F$Sta`9)m?YJDAZ@ zEjx0?6+B=PJv?s_>h1S&-dTM&ncFRsz30`QoB|8Zr>!s0xvQ17E*9}emBHNDe1EQq z@AJ-FuQWds+svP{ovsty{IWq+h|;zK0^D?=mv_Uzh9BZ>FSOXfn$vl5Wm%HKPCu-f ziUD-U)q8An-nJ40Xu%@!8qkjb4LEw3@f&Cf@Ha5N0J>x2Ra9|2!Ky1*=k&`sgb@uD z%QxRespgx!mw=_?1IQ{AaOCXzt*1fh9^eu_2N{iHyV!+v)m`gRn^@@Qj&Ogt?qxzg zD`wNTn9f)yzr2<AYY#s2=3(BUusRk3&`|K=YbWf)6l5C<x%vg^%m4C5((lnw>n9U> z5s|_qhOgg`G~@&CwB#LJkzb<UV{b$;rrf`EMEK#7pNB?XV*u0}mT}FWA#I}R&I!#C z=#plSdc%&am<oiTcSUb}JU5(fNB=fY;&1c2F!J5<{B7)7`>wAyU(J<IQ-Fx){wSLk zV!yo+xSIe;$`ae)8-{=F0qCDw&Jdui!s>zoJ<CS%+oz&p?-NID;3(h#HX+*jz|D6F zv~BDHZZH`(z>PmWdJ`aJ@P_BNCAD~xc9U);r>rO^H#^{OKI=K%b4{sg?6Nt*OT0M; zOgICt6uYq@FMvJM#!^H6+3ccftDAU;txXK1A){9kMgHdH6>FwrttTZW9eL|~L8p%L z_5-}2<c=ANE<zEbWMfKAN&%x{wd|bbWcj6a*+C3Mu>9kel(7JHhUB&|r8e5Vozm3D zoh#d!$>uBQnhJvCJsd)diQruTjm?2y1`B!>xf_(?1yQT7>c0zI2thSp5i7^BbkoN0 zL)_X3))FKC#JMd`R20IEF<mRFnfPf<8zkvYpxF?_s__CG{+4JU-60t%t}T|V{;`gh zJF8iP?i-}$xD!qi!h#7xEG{-3xJBd@%<cXP@m;F->a%N}^5BRaBrCbC=gmh*qG29$ z{Cxw<6vByi3zMt|LMw$mkf*&_%ZE#^(NjWrEhc$(?$MU6CD>6xrsQs0o?~H(35k1< z2kLuXjknijx6+<^2!suh(}>!$c$(<z9x9qN+dBSOIT}l-GDt+TxJi5d{G)GOA_Q6g zHB*{0oday4A5vQ>AX#RVrnX6-w;caaF1b{|JI+&ABHY+z>@1HA)BCwKMH8J{XL~0< zuwwbKeUa+@bZskbu`90RFHsv{6A(YNC(O2hCh=v0=4-)nOUr$8A<xQ!EQSJpN%7D2 z{+#$4^7qv77%zwVW&;|r5)FxntwiTa75^Zf?Bd5&d*k04y$jSPts_qH+bC``|FHWM zr{51a&ZKI<m0aNzA^7fqNW5$2we?{{BQo>Y9XW<wYTS2~%Fz>^h%LnBjuFqNG<L>A ztS3t+F@=Vbvtm?ZyP9lI=w%emN1!wwPCgH1__&THo_T1B`u9Sso7pna+uyR7h0j8O z=jBG849vg8ur;044;r1b+L97k1C7jU^!dPOv^P=CD553tL9pn2^~v-ZIpgYbH=z#Y z!USECGBoFzAQ4-z%peP%>L~NK!t+JLZ<N@PT*maDA)=V~YXjFZF0(QhuOl*$-~H*& zm@qHvQ}m}CT26DC;;Yz&>|WWLudQ&h8pNI@(REeN7m-q#P05F%+?H+<yR$w{Qgxmu zneCZUX}h3ravv31pLZ$s-Yuz>d#9w*8ZR%8wyv)|*z@sqP0u+>PPq~*4d!dzDU&?> zv6MEMa+yaS@^q*v64x|BHoekJkHO?!yo)~2=iQ7DNNe8H*DB_^Np*dwH#b>oQ7NEJ zC1Vn{i39|**YfDJ;foI)_rX4^W|LAZV(!P1`|p_CXwS!!*aaS&YxkzHm-9?OqRqf~ zt96jB)o2si=b{se3{JlsQar27KFK@{B_m{?62{I`je2uAy=h9*7T|hMZ@m$AA-G4k zdJpFLAzhJZ92OsJJ@vV5TDV?nYCDa&@6b~my1Z0K8qXE=M<h;AiXNl;kLGHc8)(S= zD+@iOyC5R3Ycw9q(KO*-9JAW<x}%`b%v>GX&0*Dn5&axNmyAxIF{Ej4$)p-^wok_s zs|(wF`=jPkn#`DgpwC2?|DmF@;EI^OjxQ)cxFOkw3bug#h+q{$T#Hf~L=rm=2}JPH zMD_OX`?<c{1$;}5cBXrI1q5jr(*zBR(gZ$6>u(eoc*hjgP+LhC-F#@{zEU;^Umyb` zu#Br1!*97%nv(mX_u8^w0zK1(Q=G6*?gv{Y!)eK(MZ8IOHHBvH$PNinGX6|l)IK-I zNTHq|_bO6icu_mxFjvT}#%LiaXg$SFE(?*j__DP&Glf_>`elNIi!@-7ntf50-|cp- z0i<;OiE}P`lU5I(??#Ru#IAt|G1ArsEHd3Pxj3^&_(k!K^ubf+1<mp4NSmM9ky*Yz z$)JyRVs&<K-Y+38Hx*%2!{wO9UYi=Wn6pY<r~JI$+2hK`B2aI(yoWkk{*4ViAG!x9 zpA^`)N%K?Ib~C?Jd_;t;M|y*;9K;KG`At)sL+iO2qsKSnjDYfK@8iDF;A_E!M}Py` zmXUW*gwa=e`C;3=mn9PsZ2M+|k~QGe8ovSq<9%cqU>gG^)6g#!_*%>#OiaD5Ytai1 zW81N*bBw@BsM10mT5{hPTUj_$?l}iaWUiUZ!{s*D#p%cDlb;^;cnxuq(Z{lKp!DL} z*hq6$gi*OrXjQ&j$^xlcpT^yo?}>4;cyf`?cD%m#yMB0~bOOh4t9Qd=SViKcs+lo% z%d6MSXwvP-pTkra$1fWBeHssg#JjGz@<uap=A#<T1#uRs92Y?KphFrY8&QaO8ynkC zcRC%^8PKUGG+Mk;E?IaKryemR%MW+Ld-EY`fw9B02Sjvopyq!j59N;D%8(Jfu-mwq z`dqcx&^8Xc%uOE8`!28j(*`lZi+nv#P7wO4gTt)lj|d*>CBW8)r#*);P17jHxwChq zo+;#{+_OSiax0|&rKh_9*Xg1vXJ?S)ADNt_HH|GBc3xgT6vGqFb^!f);u?tfnyMM& z8iY!DIxCgEiw_&AE9cI6b@V9ny7@?i>A+BAM>u;!1+Pp0mfE-5S(_cCA&Qtpbg&8> zO&)$t4qmX+V_wiX_~QqiNrZ#%w(>A#&#kY1cH#`wecBuZQSCrEqns(SuDv0d!PZTa zy2Lp3*S#PbOiT|t1J}qbke5(V(-Qf<Wy|7cKwzpT18-s4bOuu1U%h7)|5~?ii++hX zjyF1WqLOeLDtqNT1NhYnxA+)bl#LnlPk+!@sIWDlO&EQP6~c%jiVv38`Q&X-iBH<5 z71^%MrrHG8THzGC_b5shfuL8p>!`|gjddM41ebEFiP_;)VeEF56vz>BcR#PL@sKnB z8V>^tx>H^h@)T8h-dg<0QoBANvFDE^hH7{BA2_LxojK$aMQj7(?>^1W64<CHikY<@ zZ+oneDr2xCm$+CzS2fk<t#d-T=$r7=JLQ<#?ZNjC?wI}aw>O3Irmi=ike_%v<%$w! zA&%+&I+I709wO}N6Kfh1nf94@kKQSbmjpoS%Wvj3)NV$3(CX|+Mt?qIZF0HM)woYL zms0eDaSQcET$h`4-!JWD%X@v*f8Fi|3{0DNd!9;j@)WC(e#qtcWGXMhV^nJRDQI=B zjh4e`Sypy>GvjM^cb`Gd`Ut}1V^}8^ZyyBn{B|4#R8g<-q^zlRK6fOcM7p~(Y_(hk z1#uXszF824jj}AEMb<2DG0-XuZF2Ia0ftc@VbfR{a4=G#w{`Dz??qR+r6)d^yn6u# z{pst{*r+2?7Vl5YtWG}n^QVlsxH2tC`jY_jTjwUL_aGjL?;v$1FeD_Jl@WCjA^#9z zLvH0VBUiB^JXukXSvS75GB_{!)6r`&P2Vo%q9Q0&g1sv69E?ia?gZSN$kDo^YN($J z?$GwC{IZq3^j-S+@5xfRh$xM4Uu$hLh8Rz>!5&4ueXx^ZC(_lVN0+8lwaLI}Pfe4T zz9?sUdC4efp*~OYXfiALhP+pid9=hHvqU`Tg&8P2>!{QtPwdhK$57;xSMX`YYfhCC z8|@-!AU?Sw(1#{iQmvy3FNljLPKXL-2*^2FiCk+}giwWmYGRG+>Sph23Rg%uG`-su z^1IrYJaG6!$J5i<S7KChO?bm(e^c#fvxB5{8mrjpyUz5a4Hc1J3U*=PwP>nMUvXXL zv3D*69{?T08r9p~d^!C!NiPMU%N?Vv`Rm63Et3~sr6>wsvDCw;_?4VlV&o<ArIu3{ zKE=1{@y>a?ZOYX)`*vE8O#QI}mzC?1k|)*|fWx=t%@Nt2cfpfg0C%5NanXRrOw0^+ zalx7`qkA%Npe==BOumvu9B=SdDXxcLuI0Di=7)EUv|9{HInv<M6uwF=(*u05+BY3} zXVV%MbK;l8Lq<6hNjHI<@(^Usie(z#vr>5}B7<<jb<XHkmwNlC?(tFrQ*x68MsUl$ zKI7`hQkywH8=&Dfgdb%b5ARwuLt+QpoDTd!hrUeOCBvdrl5z9q+C8>QKgyY%nLH>u z?`)nN$I^j_!f3(ky}5L##;$mfCQ3IE87sJ7KIiw?W5C(D$k`%?Z}OXp!qDEY#81?| zZAtwE3olK~KF8m2h`)LjB7@pU2cc3Ho<A|QX>7<Mc@%3rAuI}5lC(yg?3=WJg_4cK z2i!NA5~bN{pKnQV?7lk9yN4k`vh{#s!z9p+{Wom7<6N_CR#}Rl5W|8N!5>9Le$KJ} z7`T5@_|6cI*6@LYA<b0Op7OWxXxS5Du$+HrZRu+w?fDW=%%tX&&ZFlPTNzTv)UZ~! z>yc_=$L2dAsb2I(P4YM62r_?{4i`_R=wbnrU**|aRPjI*&k$vMz0<(Rm+)OfpFAjr zu6IQgO<RZbWWcOGscq1Z!q4bpbZ*qnK2+S|c6HKExJj~NuuC@QBy@~7FynH-{i62) zxGQ5JG#z9ZnO+<E6eMZ=ZOhzXQG)K5zCwnF=2=X^O;Dwp;}6Q#-5k*@7ts_`oy_HD zWH4JuL5Rd`7`~Gtb6Z36l)w3x;7^RmCmL?mqPQ`9Pel}mI2Nt7hP^ij*&m;(h(An# zE5O&v^6FWm*Y%=xP%4Pks58q-lJ1uG(qCq?mKxD}bV<i%N8uB#^@Y)n_9?+034Q~3 zZi$1)kcBG4RNI=SfXd;67ZdTxJC!nmGWL=wDK0c@>fBe`#EwC|B0QC*LcJ=BY8AG| z2H`;uFyK?857cEXIaL)e!{cr~X(ju_2O0ZT%fViri2epz1qpg<2W*3>O+;QAl4*4X zyz>b{w)i(RgLS%;wxnboiM>FKn{A$e%7q@XABp|pdKq`aHS`;B{9jo1_Gi?4sVggz z_3aNN^*X1v4|j9ZVE@9bJ^y5<{F@kY1Q*F3)OSjyx{_QD%Jk&xJ^+8OeEm<niqq}v z|DSpFx-SAvE!w0nWW+U@sG7NazFilWNKO9E3pDH9g?tZK-CG5^Tl)SNE29c=bfk$p z>2;>8?b<ZA#d(L@d8cxUG2{BZ2WWp8aLlAqVs`wUc#(uSyZpt$fNpL;>(9oOsD2+? zf0;9*!JF%z#0CMB0g3gm(9WNq3E}^sb@ksafq)C&?f7X=&lgii_alyso@BoJqM@Xp z`z8R;di+k2OrBL=k^tQ~!0SrFxa8lYK?&;TJ?kCRlJ&Rb?~9G{Q4EPc)D5lT16cn* zzTPvesjcDKMG=uA2ug1%z4vM;f^_M<MnGx=q=Q7F^p11^1?e?JdI#wO0#YNPCJ0DR zkP;xU&w8%!J@2=l^W*%>x+uxYDs#;-$G8U|a(<xXz=~eo`ALHKzcPl=e;txsfS228 zBh)O58+77SEhGBRc@V_@T2S!6wSyU44<Qnmh#-6bQB2y&@Yd?TKi>RmB;)E;@&4B2 zLWApPfZVaSuBc$4Xh-@Uwy}GC1CYlIZzKP;+kF3}is`8nIpN{7!_Td1iY;v?ZUkq$ zbCM>;Z^0UyH~{UU;QG1%SDP}_b9Bex0uR0-sm}UB*7L8QRj;tMw{^@vYUyYVaq?U& zP95X#OaHEPl5NdS2Ydy`9Ds4?C-Xan|G)2`yaHvdR=%Wnw?u23xW0YphVg^7h+jy~ z|CXi#t$`XGpneAhsFp}-6}F9X!W(sff`L3Y&HS#1VRIqNXGCb3I#$Uf1GTvY*mOw2 z-|N-0K42<K6lnSn5d}01x7E*54d>O!BHO1N%%Ug}x|hFx%dr)K*KV2wcGmk64eM)Z z+~?Jst#Rz>ZnWabl-2s3nvQ2C`U3}OJpg;I>{`1?y}q+4<N9a_;?v;$<&XgM^}wP4 zdp&HHQo%E7{(UvyU)QF0(edgW!L_i9RUN?Eg=YB)_`6sO&SqdqZ#4JLzNn$~-WV`1 zSr0mwbKQN=V$x<fa7>Xt@`d^ZcDN65D_HYc`qQanXG@oau~rwZ#)u_k9^on83A=^f z-`PQRjT4&BsKUk_ydo-gDDvlaP^$@zZyEZ7*m-67rS93}XlAS(vc0=Nf_fUxQo_XX zE=UaN5G=MG79pigo#){4$UK9SilX7e4bGNr6?V@6T%Jxdc6>4lD!mpfEPTMpXScDm zYBJ2z8T7wAlkQZU>z-%`F#K-~6x<4vvBIb9eYe`T=9|kSmZL05yz;TXzXm1=j=@lM zLk0XpM4QBYUnCQ?Ix7w{t^pL=0VA-zyE0Z^SY*Z^ehWjIa=gqFVoKxnuFd3+w!?*m zB+l=Y2HDN(=8fsPyB{zvA-ya#9~Cjwvm%&Z@cbufL@>v-l8EvWcoR}wJGmyhH&#LL zokcXRk_RWRYNSnYhm_><z{KvqdxGf#0$aUupx5OPsL%9Mwx=!1Xccx+t1vO(d<10W z+UhGv(^cs;NpSh8Z~Kfe0tACp!`wCY;O_U>?PrpG1yc5qSjeDqV@eVaHg|`Nt+c5! zcW2Y>T5D3BLsTC0lQhf7eiirk)Y1Fh^`n-l6SL?emR8Vr5e!w;a{SSo__dyYA8;a| zEHkQM{jTWq&<&%YSJ^Dzx7#Q@*~^;(E7!&~uoI|PUQQ8LPD}3@4T&avgLeej!2Ma8 z#$Q|O8lqlCs7F8L%8NBK9g!o=7f8$(!ZkMmTHvqTxt?F;@6MBa?j;U9h#JyXifH>n zan^koSwnVz@e%6vBKO_K->-dUD#|_bN#=_hGan_{4W?$9F5R%L<Z|j3NNO&{c`%lA z<Or8&WTaD8DTSGOF)B)ss8tbk@Np%}gH)wH&H~FDbZA2jrFBu#9r-U*UciZb+Ta}O z<CsEOw(u_NWe&9I`=pQoo&8}i`=h$1tb?678VBK4CJUb-36)9C)XA>EEsHqR`oz?} zo!3_{qX>-ZZHX}N4Wk|A*x7`<1V-`4688$<k^lP6dPz?7*W=I=@CdFbpOGF_6=0M8 zz>cX5fG)71wgsqq%^;^H8;-n2H7Vg6kU;!e)Vlibi#Fxo8}FEa<%s`b+t_(Vr<U!= z04E<xC~fq8iLcg@LD*egAceaE=#?tJ{~_wmBe)SK{a?j3K$O7whU1Dj{rbWihp1Ox z%k9Bxud-iHg-Nvl{DPUMb0B$ahrvDDMaw1CQ=}4~t9mBw&2I|U67>yBmFNAhA`e8l z7#)42UT1vPNgfGPiW$SjFugvz`8z<;7E@oYL!o|JcA-JDV(k5_*=D4o4EYG?^*IAf zAfdoyYY8`FZ?8C!vZlzsVKETKsWo)Yaie<}(n=Q^ZA|7!-dDrcE6nP9Jw~9#-^C`J z`e21%cf-hoA1^+gDsD^rjq2q}12t%cxpQTiyK_TH>?VGw7Cr1Mdf)G%On1$WC+-K( zyr;g{ji~&jmvw?3VRX|EJteg+pX~~MoMILX`q1aKWz=O>l1SX)=Tvc(+v!{jRmH<9 z@dbeJHOBWCr#M*lDW5yIwEZ)AT!K*Z*lEaPu-HTY7Zid;MX^|Vr`}F*G8$N)|8wN9 z-Sd7mf7x}+GpogGzOnJlituQinxH;;KUlSe$+7aS1yBD3O%$n-U+DOdbd|c>2EU)G z2(&rF!=&s}vGL(7fdm%_$UAA+@+1(O;&plXVsC{?yL#8(MIi};(iIy}njTH;qD|3v z5oUDBsFbECZInM8lkx!nroZ1B+z*brzJok@%P-9)GkHy~pM+t`zr#x<velVv^NFRk zq*?oMGHIkuk-;5bBuy%BK<ys|(YWJ;B;o;Uv#yiO*-#N-ks@l=gg>U(klu^<4Uigk zve%lrf6M@{*BOLixf1P1+3mGA*lSa&;%qz9brlw#(qz*_nvvh8=Vo-Y?b+$3#@Q3g z^v{gc+3#B$dF1Mtr*)*IX<wdj@<T;4r83WF(o!rUu0_z|ZC>F1oFNH+cLz>$sfxag zU6V><qfdp_rkvL}zFnrNN;wS=slr=m<N9dXUT`w3fuoO_$kyGS9A8<e)KzOcn%#hp zF%6%7D=?43SUR?}$2)jSc{wMCSTAYF?zg0NHaz-JzBe3H3Dp5OOt^62054i$3&R<y z)WRJLnr*GDi>N&fC$IXCrGFnm0u6`s4JGz&Sm$6_PHpf3I8I%xeJMJH*q|sld|j{k zt?nS$ts@*FSXpej6~7n?t)1+$Ava>+q|~zBDZ0v4x)sbaaJIsBl?!EfTWn<wRsiOm z7Xx1wJL;ctTeJqIX&XPb8p3@D^WltqdPS0>MjbUUR~nsBYP39RCX{Q@V4UVPYRy-Y zIU8d83UCmY2KNiBC7OrinSOJT>r`?!($9a~ERm_;_oY%NKwxfYG?_P#I{LFZnMNd6 zRg-a|$BR#bs%DjVn*rFpPF>vAK>O{aLOVTltf+H586u-v^L4VZ6GhsPsrx_=|EtG) z#4fiyQQ?fvTAZ^MpYduK*f5MF7(*SE%bx9uGd?LW49HWNebLe$&0@uwtey)=r)xK0 zO&^#fOLJG#3A$Uu+*CB%m_kla2)Sm%3l5lD@4eZxj!8NerE~YS!^arAdzOY%gleJl zzNek;SPHF2uQ1)x;Zb>PJi<iK9hfA?h8*x%?!i@)!YoVg*km>6t_S(}WVDYD@{b~Q z^o^CtahLs2gE&HH+@zd=P@xX3VUmJ8RKPSz$EZ}_Xvo6Y5KiXEwbPH9ysKlj)5ki? zX<kz*g0OAtXv5CtdbrJ_@)qrEz}xe($Q1AUc8dmVKW>yh3rvFkN*AKRAtAnSSB*Nn zRcY9`{oQo5d5=4WBOwMOl3ES*Q5ft?a^6bU&z;_wXP^N!%aj{w!LNTLd9uP34%q#Z zdT=ajhXaR^nz}I<?}%Ed&?JlJ@dtt-W%1tpIdmm0?vH}vN~7||K5*6_Fq!+m48)um zP`X*qSC&H*%JNu|3T7i&)0(XB`d_8Wo)x8%X{z<}Z+*B!$O{K)3}Gh(@`+{q^4asI zc)G@!=dAxmw6||gPi1(IjfhSVm~a+kYxA5^Xn;k{D<mQy?LKeR2r&uZYxhme$UfvV zvrT?&oLpCGFH&62Y^Jz{DUbGFU1S-&NEt4OvpA(#>)@bTwj}V+G!;<wmFu;%+Jx{R zYbnoDy<TRm$iDN6?Du5$ewJ&c8gjOGb?FV|x~gbOB1TW)Q%N!p%F$zNECX3eoPYNb zB29NiaMQYP&y2pLxysI`F(UmMemr2HnT&;67Erii)3(8PyIB`k@Et=ICYIcBE%Cd1 z#!Iwk3W-@WX=&;#O4s+!>vdT*-9N4u<9#k^p>o)Nh=zJ-0m{f=sT=D1oG?6~hiduG z)Cx+HBUQM<CU%jlQN*{6`=N%M&}dJSaW>W5w>2D{fUM4uzr4IxF{7Tm@7}89X1bTe zW@JlH%NaGL&xGbsFeL^q3-Y4asfWizl<Oo!@;QnfXE<q?RcV-3SDM3(&72v`gB7a$ zXDX#dbpYSfqVmEaraJ-$7*E25Uiq`+cnO1Go@IlSENQ;A0i^1&jYo&-5^};)aMn9F zDEB&}>gE83{v>L`Q_Zwx&a<0|Al99=`g~?Hc)YfwTAl0XSQvRkrbgd0ZQeT*DJ(fo z2%)PYnB(Dl`x`SLqtdXk`F2cjLGSg0?)gq9KS;1h(X^0y(!d9@{NIcYpG&p2VnudK z#JHv&@82K%v)a%Dv@$acE7#{I;GUS__e0QpwOnnjZ>^^pW=dy0omz7#LYtfNSDc^v zkv~<4v~9^@{~<_%2;KR`+Cy?xsC$3hyz11b(wIszM!|~^Z>G4dx<lKw#O>egI)`H! z^IfGZ%yFI?G8=M)Ehsi~5^awg)mB+#l#av>OkZ8e{JC=Z{9N542EnZ#)2QDhf_#o7 zKrme_ws@K~Wu_gO_TgA1uAQ%w727qbljzU)_l>pv{8$q_1%?ic-PYWPtV1T|7wPX$ zKyB6wNOk~7+qG2KFpQc&?NkBP&BK6WHnBR8pqo#0AvQha?v>J00j;_*fMJ+tyM(+J zG~B?#E!qTK>;u=g?5khu64Y=8F(BegpI{{V%^y9w4MMXxm}T4?Ql0QIZ{MhNqvo}O zQvP_Iqe=Uw=da~P$#1I-hr=n!J&j3Q!=lvCu=zyht6jV~z&}!s-qO1vt-a^jNAYoG zZcC&2^S&AVFYynpR=r0XG*7pFhft|e=BP25f3`HBHppdd(D}65P_1v~&Dd8eKa};M zT;9~n^9T`UbXnDA5IrZbDKRN9^_fKP^10NuUR7%w-+ZawkWVT3v`?YYm7R|C2H&iq ze#s_!ceSy6ZzKdut=^80%;#<{=xhGb1DOqAiG}A5j3}s4`g*<KTAJ1<{NOvVVUc)l z#=8#~32vR?vq^g19eYzk?Qy&*ok7(e=}Y=6oRGZj!WpScd2cq7skf=BB2k@W?b5FK z*P=NOTB~5>fV9_wHrUH#+ss@$?!xJHBV=QWra;m)qnNj5qRw%uYChsxYCK+B0twC3 zGM?{EZ{Sa5`=0Z-t9Elf91PVYGYL;D9AVP;@UpGXI4@=_eNZY_F>0LFX$r(#!lCvT zB3OF6UcA@iHNtc;fP2!QCb7;`@E|vV(^<`BJ+>dFzRa->2+5X8tN6n;8wl0I7|`Lz z`g4`Tq1x-hj-C{nNO*whwBxKj-vL+i=ABaKbJVR=rwp}L4SU8hK_atm82$<kOX;B@ zzzUcaCSgT8xy#+}(b-t%rJwe}Z-$N9lLdE?;@?($layB6Ty4@ENDV0qGwm!EKpfQ` zN<2-o>upmgig5~~>xua^4)Ma|{TK1>&qTR=MuY@6-_<v|vEKdW>CCIz9V)!eE``0W z9uuF<D-U=RK$mMfmGPM$?!?bMTFxM1ddOxB!PXMtvIoG#!BuAE8q(sXZaPWQv6~s# z(R!1uFS9)X^7bO;?Unk+9{eU5MOJvdwJVl2{gwdUy)occryD+WX!Ds6dUxQjwyQVg zd^Sx?G?VjDA&_GJ^t`!>@sXMHuM!d2{Tp!n%uv>wn7&wV_zA=tuOV`RVEA@sA(KL% z4xv!68a{nd{UFF!#VHf|E8iwq#2oZhlx=r-)<!i(Wx6(Pnz4!HNy>6HV&v{p5H;h` zXX?Y760B*her<NXN#M1f_meT#_kt0+0NCgj0QBn6n?L9@soXvj`eMJbFy<BKCdv#> zV<aR5XN1eBL=KTTBUX;UG;&S}X12Pu^CBY}bT(TVHGAi^v$LK>37ajCH|k$q9#G;; zq$XPPcnY(ecKaH|Y5M#A!mQv5I}fsy=@d+hnXareT(*boQKkGEiLL_2vl}4l@a$au z!b@d>1U9?BH=xvN6|bo`FY>$Y18Qk;QA+%W1XfJk0JNXQd04f4Z!sE@Jq_ioSiSz) zKGaf-FV@E0jw<zFuI;{<`}BKzzif3!V)ynP5vDt7x*uI;_Jbs(w1r+gn-&^9{0S9B z0<O-WmW!=EVWpk1eg(`T%$=at8sj`TDkN^*7#Mgoz^yJcRb;25q|F|vPT~}JpzO`& zXMlHI=K$7U?wvgOF&I=0$v*nUJ&<)|Z}m$DAE_g&K@X|Om3W!d+4k^#^z*5b9<R2e zxtOu98M8b3d6DLyrou4k9w<9In;a3#aw*K-KSX}L*c6u6b3*!Nl&pTt3(W!nk7D2= z9>+e=`qPh{b}Zw(CcBwp)8#g4I$3PyLnfw~9+KxX7;s`S!!<v?q0){1LMfrl&ZAv9 zhSMziQ9$Kjkl%|lpEgrBdXgqT&M*C+)f{{xxWn|Xe_k;3Cn(1=4-Y6>uUqFY+RfF9 zH111a0<zqSM0AF^7EQ&?1lq`plZhCKcfC;tr!n)_^iZ)poq68)(*vYNXlPz`#wz!~ zU#{@0{$(bXiICDP)z^9K`wKGlcMBxPFXiy-nCzGu0t~l^@hVtbmQb-D>UA(rrTfMi zDo@Pilrr7(7^lg`=<?vG{f&Tb4(jx5Izx7zfXHd7+S-^>=f3=hhzjdv(<k<c&*W^! zy1dbLsmUFg2$`;AoLq_jBv9G7DrNgwUUa$m$BA-cyF0dY63A1n<%J4DA{RTy+PX&8 z(+_iTt1Q42ScBsN4ak4Y7s^9DUneU4&_D}3lm<WMj&a*}5;^U*_1J%(_Mq}%fm1wi z9md#`Ag_6Mwb5gq%(_>42hYU^Zjh)9`6UwFHsI+IRQianKmd9Ro|it(*@?9qgik2j z&X(YNynN$r`Oma|<tSe;V~<11J*dc3-k|l1ruoJarmW2$&3}+{*@}uoZp8giinD{T zxGP9u?dlrCUP~3!zrZk}FO0W&N-w<d)A)VmTo$>LAu*W3F<|Pug~qkYDYG^f5J>-z ze)Dg@R3NyqrPts=*u<Nmypm=7(W1FRQp59l>t{sI#cf&RUH3+?PXGa@C;kwm5bz*+ zbZBOxwJl%5i1q889#MH^S-=-IQi1Tm<1VEO-rEZ%^yhXO0YRBpJk6c4a#p0O@`_Jy zSy2CfRDzp`C<1Q^>#sjYV7|XKX<K0{VWBWtH?~Q++CdOgrCrTmcU()R*MK(n1Sjft z?}Pzsd&*D|5~}QyyCi!mQ^$$=W8NT@=JkliGaW=cGEBTmrval2-m;k~QP6MmJf(;w z{(eRi`@_Lriedz`!O*tjcJt&gBH)sgU$N@9%>2SbPk5^cl>%$(`81^a_PoPPZPo)T z$~Pfd&Pz9*54Yl0nW~!G5rf~2YB%HO`j;8R^uN5!G4)<cCaxfiTg+Z_K~=tX#rK=F z)#oZcB@g*p@o;FhJ%B`CIWom5muO3xBc^?#02cCsE83vWma(kWD&v{>&H&Eru#*nM zCNpibxTv1w;7SGOTR!?~{xIMn?d`X_EpHu}a{t)6&DV49bvw^K=b%+atb9Mg6wRL8 zsAkGN8oj?ISiMHmFXv0DRK-U;zWbj(^-SGsnl9?=_apxhy_Lly<yN@nXFrHe+*tn& z#{LJ=y$(b3AeFbSdJdxi!=duOH;58|yv+ahuD9<Bv*>m=0N3WYy_J(i>KI2(><EZC z{onuoCn?LnabQx1c#UJ_3sT;z<JEP`_KEVh#XF+q?hPLc6Ggs%BV{7W@BaOh)JWZ@ z=idr4$G<m-Z2nu2x6u8v*o#<b+N`^m|16`Z!zb#S+&bGxb<e*<taoy#KOn#aEDFX_ zU*$IbmqO?o9K+6Tsh@a@9mq6!KdDO$n5_JA_d+lU=tRo11w{B$K&E0K0M^<6+9dY= zw=54IzkTrb4X)-S1cc9ejAnGAyu-B476%6g%KzP66;@BTV2f+DpKmz;@yp}Se|-vz zxyD^KPW^178P7<Q;iR;i`V!yRy9a*WZlVL=XnlIMu*pl<Dg|Id{MYLna~?fM6z#y; zguC+beOpEMU%R>R{XLl=z`&eqrhTvCJmVA1%rs!6{4Yt=R~Cjl6TR~H-ZGla{@<5B zZ`hT+|DQ0hU_$MT3UH*QTdsT`+}P_O>U^@sW}(*Jj`Z9w@30aZ@zwmE|Ak}AHhU03 z-`s}b_lGOIw38U=?9h71n0RBAxU$yBZsrMNV)AQuK4M~f<cZ!BJ9XXdA2c7A;REGP zFSc&^BkDT?(5rwB*uvYVcXP3i<AG;mm)i5F=ehpVuQ}X|YjY+U*Vd3j3SEiJ1qo|2 zwcf@k`4zbpj6nw@FH6c-geN}l@&;578x2si%F(xrdE<n)nyh%!dYix3YWTimt-nlm zy9v7&HlW;i*e6VXX^th0SKny-Koi8C@aFrG<}9Jpiy#Ovq{Cm~y^zmmI>9&=iw4oq za$;sO%^#7ETy}qca%|`LWdjsJBg306mkltD7n#{H=08&!AQrbi|3kE5xFtYzIQ``+ z2Uuz+S55&6tgTo2*)uW1<_2GN81F3O8Y>j#w;tR80$<&n!NnNa1O!MObJyG*7_Ntz zKJ3T&^;PT<A>6Ja!+0Rs_5vMvlUloxkkVDFCxeuGme2YtnEu>R6#R^bUot_hv4`=s z29Y2|9(dWLq+-o{3B4KbL$Muk`}9jG!rjiR{F(rc!~zDF=svAiIiCC0hC2Mex2}r6 z-F(M$l?f8|UOP+)Q^XFYTy&T(++%z1sB#7A2RU4FT_ba|<4=Uu^rr%dy%moUH<-T? z75Zwj;4xj<r=mF96={6eI+#IA3^}&NcTAG3{M_Ole&+P&RjGdu!%nVe_P}Cf^j%dq z%u`Q>(ZcV<2N#B<q&OJ5d=MPXJlGwFGe%(qD;@p{Ph)n+&n0JBKLG^3hRsycy}?T^ zFjRN8$T9%_R(8<~7=FbDAb2Xsw{BMDfu2Ru^{klU;4|Ai6LB$F*}Jre%vUjfZvm^j zGV{godeC6cf~v3!btDIEB9hiEHAQ54MP5ez=zX|JxKBJ$KklOeD)iJKW-u-;po@~> z<NGX;;w_HYEi57(z%?h*%y-WK-LT+O%euLOZ_1R<P7yWD$d-J0Xd8={_+Km;tHlqX zG#S<}m=Xn}J7FUpeLU}ecQC;zI<Ac)TZd?HwlH_yV&+Tu`lxX6U>1t{ri51SL*Ls9 zXSE*F7iguQ^YdAP5YY>6_@`K(jz@8*8tseC7Q$2Sw?VLS)b@nAmDERu*S2UKhh*jD zaX(4Ch2>9amzJ3TI^9r6Bt*1H^RMn^BIWxX$y}l~pYq^&&r?+CNjT#Ho#$rGvc9Dk z`4?8F9l0vqHSY&IlSEku3u`Ue{<LMUHztlGucf8G%}U$J=+<GLIH#=|Y86Hc`c`)G z5V5)@XS%R443M8PTXi?L$<j!U-1;hhDW|d6rnAn=VNJB0hi-{`m@LngEXEyZc0SCg zXwdQ|;rd=j#!ZZ!#_D%hGi|fD740D+I8sR{d=sfNN6@6y75e_cQFx%{MFoiJbF3mn z;q)%dq&@nMh-VgkMpJ7XdDY$rk=G%tpMKs}jy>ilJgMx?^Id<#Zqc5+a4fwU#DT-{ zUT&Qu>vru~kpa5e(qqf2{Dd#~j7KDWpV)oQT{?aLg#vU25*uu_z@6iN8U;;%0=Wfh zVEMvUJ*)=SE7-G^xr&9u8er}{DDVCPoG~F==|1-JG5F~AL3R)yY~!#{E9D}YDdzKg zQg&GuO=8V_821w4Y@mQPIJBRgJ<B;q=P1aulJ{_~z<EKKb#tz$qlIxS@jsJGSTBd@ zD^dSL6vOFHpmnw}0YW$Hze)_I<p>t)Jy8#!V0DYHe_J4A*=p5%=XbP0YnaF?er5pK z5Nu&HdrVD@SJ>QqA_!MKGtw@bWh*rnZsw|}9}e=~Y~;TMm#m1_zGZ$!!G8j7+zEtj zzY+c+wxa$QrRV3prID6wmJ3SSp(3+QOqP%Y%j4su*eKQ~<3RtZk|Cp*qz$gx*+-lt ze0S0I_HsJXVfpx?Eqw5_=9OhHtFKo+bQC(caI!*+_9g7fRHqCndCao1$t`LrIlJ!` z8KqgI8#l)x-t3-p_8mwgFfh7xxomlzZl{Qp#y%sw7~ag_tj99rcPXPu$@;#)Y_4zE zgw#30T!g8BBETU0ng}<&-F$r;_qNY=0kxwrcwJfiT*&kH^-T1bfsN(iyHs{<QLlj# zg<|#c!Ruz{eCw0Rg^u2CdVCyi%oM+m^Io4whoE6G*%s!c{p`%~NUa{6MsY>IpzXI_ zFW20a@r6&5udO5%%O0^qg>X3Kdtm|uS$sLkWUnZ@-GZeDGFL$~R#f_vm1Y?#Q#H<& zC>5P-%!R7nvMrK$a-KLvmp&QBw99-KXwl&Zd9H&K-ZT(I@tO!*o84~Kx?~fMq?1WS zZ-=>q{g+C%*`inFZ29M=?SoFQC>KLgE{2J-G&$Z^lld7Zd1<Nc<{KMtc0~NvktpCQ zB%vd-E}c0uP1&hsANeXDrM%Bnqt37TiQl2B6I88Jf)m$?7Ktp?$Y+n-?WeX*k~7M9 zO=#N2a4Xb(s_H2ZV<u=%U5f_WgW3PM4DprC9X`&}t+O&~4CnP@OWc-}N?p<<R_m0M zvCJ~}cMhyuH@FcjiBU=b9*$R2K=QXMU$|&nqXGlYGq7r$f`vm*1-@mvF!f4DU^{wG z!K{wcJrH@2SU34>6W^8+yJ@p?*PPVmD(z>p*9m@<yL63pi<M6ITH-BhwF8bWA+cWY zLy;G4Gi5C_OYME!7X5=~#V>xua`1h(aeHLr`#V#b0HFD9AlINLTk<Ua+XC5*;I5cT zSd`9_K}Alv1>S>31UoRy&_NZ(JGn6zIjhu;8~V-kovy}GZ%eUs<sOaO{dCO!+ZLv6 z#X4q{8U@^L?S7>Ox#^W-!7-=eSkiDMhTippcRlRVU?K=}chS#a7_jV<bRze-v)wfF zfVUN59`X>zt;(O7{v-KD%M(*w6ap1sLk;M*^PQ4aZYZe4(=zvbE^JT2Eo7^DT)y9Z z_t$&T!It%nVWwYW468dyt#e;7vnoBTM>cs<QM3u^Ugc{hLBF@u&j0%D>?_9NPV#O@ z!&gC1!p?7iU9JO*==UpL#sgK{%$<SOcbgmDI7RzM&-3%NrCMY~qe!z{$->d*+%Jwa z1do;O<8Fe?GCIwb8cu;YPr^7)n&)LhREzP({8{#s+&OKI!q?>qwwjnyAtehi1!cc@ zIVoSLWyR#;e8pFMqL~hEBO;-HuDsMbfM0WA4q?ZuBZ&aY0B-JuaXh_LSpqB&4J|R! zcU`ryLGQVKf|Su5R9dO3*?@PVHP1wia?#SZCDRQ$ZK`7{*+IP``UM|zdJmt3%LAAq zuIK`k=HTf?R$eVWXu$d`u2ayxO264!x+{ae`SsKCckkKPC+CaYMV!H6R~gzA-^57* zVon*;fq}6J%nX&qk3rBJG<et`YI$Qap10{J+YWW~l+(WR30HH7YqF~S^4HW+Bc~Uf zTGs*Llc(^jQi5|3E&@Cw)M)`Ydioxf;k}33y(3TZk_1h=vA@q+tRvjNj)y>;Ufmk9 zw6|Pv__%1@PnH8ZcWJvA{n#$oE?w8?fpFFlmK~9wO>B-#YeFzdo5{6^yi9A%)xB7Z zY$c7UuN4V_Q_jojWMEJJj9Mm|a>gb6&SV<IID@4BPl?5JUZDZX)DUiyU))kC8kr2o z=>xLut!^=VgdJYZAxIbza}ba>-`;$ws-?bq8roSi^X-R<ER{G{kwxOidBsb12`qiX z+DImXeB4uz=I#%bwfxsL)XT5@k~MAbN7&n323-GS=fl6ndUliUfa|Xd(Yv3uoo5~| z#rc$~73z3-#-vN9KJsEmNk5*A9e5sg9LJpV*6)-RzkW%JAI2~TSD&Wid(l$(Y>X&n z!mc92fby&6rWid7b+-r)nV&YrCDZl7HF`W736ra@{Uo5Pv0-dzKQHFwfVfVc)rNAu zijfJu!KZq?6=R=ULZG%6gGvyN%;3!9H#nQ2#PDner`P+|U9Xhb`b>QSl&bX^gEY!G zY4jVi9!q4;FF$|wwq_&Ny~-oW>y4$gNL^)cs6`X95mHRD{JBrhQ_L_>;e+W~I5lVC zE%uXXsP0vX5?64~;2Fm~g5X-L5J9_WI~R7!`OD)bI)F4@`}tQrZ%G>gHCYtza`P5c z74?`BWA%sy+$7ouriL=%K4rh5uk*;~m^DVNYfG$np&EL!Qe$2ayVwdqe++0dj?wCc zBnpjGkNz2;x%KSc8|bvf-!h|*uB@b=jH=^`$0`2$juIO5<XYI17MkElZB1R#Eoze1 znb_+TC^!%KLoB{a;Xxb35U>a`%zvFNcd1$D)v5N`G|zA)mD8cs9w~+Oswlr)jb5!+ zPU)r&c0y;TG<nBz+y`zQPuE4+t?+@jTV^|-hPb|Fwq<(MZo`#jaTJbvT;iP;ZjlXO zCy2wQS4leUuukZ+-h#Mpxd!Z#0!IXAceWZ%sA$0BNO*|eKSZ2u?jtn|zxj=Y_x({% zpgpH)$N+DYAG#$Lq`3apyWgJ96&v017Bk7Tt;E(GGoZwuwlXg>)0on99_qOdaGL#Y zbi1vEF9gPMi2~uZdRW3Waj@>G3f>MY*blA`%vl$u8zfoIfB$7yCa`RRg{7>yXZD1? z?PaTsLU3rs`b)R|F%bU)Lj?i3>-_SZ-yn-#z)~mw%0s8r16j%LzoBDPE>*I@&B#?; znx5#Or{O*{A$TPPJVns7G7Ncf#N2cCKnRD-CY76K%dq<teRej<zgKRMmX;9dB%(D{ zR@LWUsBct|O7OWVQo2iEyDFEy(p1F{7Ft2VWU&lMp3ca0yWpNW&UC}}+&=VkcBk(@ zP7|H(y%%Ju7>!Y~?wMAi!y)%{u_mWaro!l<@>j(K-s)Xuo^of!&y$e>x8|+c+~+l; zYK;d=v}o1CEpst1K6u^bbVwH58kanEotA=g4y`g@b3lo)ukoL;r%1zDPhpT~QA6Lw z4=?i-iaQxXb-j0HJm*mlhqS_5((7uug?jEvPsXe^PVVia5flV|>_kDKd$+<2XA_P) zE9vGU+mq)>_JZH<(+^sDY1W%B-n-h>X5lv*D-N$rMt^#cY5w)t?9Ry0cw2=mg9+wL zo@<uYwzDoh$aC@MATB7f?Uk)$W?Y}i7|!ySe)Ho}fef59uMviGghU`M?X$pK<(hjd zzb>_Y7hj+7xaq=A<+b9hd}(}MCBX)Z*y~saz@={prwTmpE=UsZyQAnoHdHmrS|?~S zMr(#}cfalS*SnSVQaj=Zx{Y1!gVF6>b9*Q^dX+k$J-zO%**WR8xBWbX3pHN4uN@t1 z%uI0=jCOvsk^4N_*a6D7auye@!sl7HUZuwjPDa2hz$o|j-4RUB&7EoRk5u<lROSzv zH<99U?;kbO%QhsW(rTx(9Y4!-JTeE0i#Uj{r&pMMay*;&JPc!TqwO@Zb~oYu1u}T+ zDVkvyPGmnyhW;RsUcYJZsWM&;1uGe=REs?ChBFxF3m9ozN$<hw_d}&Bhr&*F?8bGd z^!3G+(?QxeQPE!g+P5*^hDkFp+p~QWCR+olWlYBX$WtSOG~+?@E+Iu`)2d!oqXE;w zk?B%vI0%Nf)Wuo!w)YIcn4wQ$6nI$;7(VZp%J=>s{O!S9nT(yolCQ`b1vkYw1Gy|h zvDs*j1b;+~Om+bc)Iee9{<1F1c;${5OX$nLC8^NG2v+S)AqiD(&oSD}(MbL7`)dU$ zkNYt_aRd%*58A#1bEVj6poH+DDtL6Mm)r(26tLXkbE2_UW9?hZVOvNoObY+1y1$C| z9st@?K{h!1v%ZVfs2UJiC<3pdTiq31$+rLNYt$iU^t2<k(>EsHW%KrX^{(Z<iI%o_ zK1h79<fR1}Z%R4YRHAXB^B9we3xcmy)UA7TGu}ARebmdSC1$vjCQm_rg+r;|;dLur zWU_EuC$~VWH)PN3&UC-u*nRT9m9goA7_O?>nk;rYu5x{#lW@@^H()c*6^;V;@)T4} z>=uE!MxACcEGT~TmXEfBfg)Y_$VS0un#?&1;~D>bSN+y$>Cih~`y%LIFSwT@t)|o~ z@_L1@k21oal7>?W#3XbIx~?flPO<qJ<(Y&kKlmf*!8{y?P+F-55+D@8C2mneznjhC zt@?Ee?ONE4EFiwH2S7LD9sF%QeMK3@fJ2(@=2ytxHw<yYqMKj+7jMK$*T@MC@nj4< zkFvKi<H?m%<LC`e?|p8^XTZ^)o`I%c<;pCBy9SRwIe?FkLF`8NInPHC?{W|{>tZHr zItT`kx=!kbk0~9~&?j*k<7$QaNKSG(PJt$Y*+{Wd`;}7pQPb@UL^M<l@+FBwr)}zC zf#!^Kg3Z`x33{=&RdRBcvWSb)J1-3lZ-V;t_p4hrQ<C!U;JlMhsN=xw%I?Y!7XC1= z#!H7Fglmr>mwbCtmLvq(tmZN9%V%6MKO)9+4e90##{?9L)|b#Yr4J&n8oTs&1n=rx zkfgB*9Bn@GNvj#WSuGZ5nDRL)=KBEcZI8DQ^(lfj@DK?+cj+}<7r;EZn@*DUD1>Ci z+B1WHYmnG6X_II@41bEq8U?AZ+mjDY-c3%($ko17KP>rtwIFqnr`<f8zLAuxg~d}0 ziAZ9{=)dAWwtw`fk1VG@cU7<@%+U!nXM_kYu4W6Z%Zs}81ZPZc*_>8g6*Uzkt~SaP z;+S|k^~7wyNi8d^6=gOjkkAdh;CC94U((p`_(%lVrj8Gz!cy<gVgIW1U}Xm(b_!>D z@3Lpg(>EwbCD<fCd`l#buxGjqgEHc^u`Q=ZxR_q=Nc)G$92CEHW#;Ew?t9$a7Gl;7 zwhyL^;ELr5ap<Sr-S7-_HRt(<Xwdr?H3sqiaUG7dPq3|1(_I*7Cv)F#Hce;EH1st+ zeH{O5XW_E}+$`PqbAETOpue^iSEDvpqvl0+s*9Y^DrcY5*Vn&`%`@dqBH~lHxbL*8 zWxBIlqCnMJsIh0-n1WyBrv-RL^w^c|w`*?5B9nu%SIo1nfDlgBqfhi4I{Q6qc_{9b zm`;*)j`*O{Fz1c9RL&J8XVZjGYDay^<Jy$d2UvrB?ls7=fhoQ}sKN^W_SHW`0iJN% zEQg2kOT=krDifjR-g`+n@HbiTgRqBCIY@=$bf;#m?MSK8TIIu6l}~>;>#M(fQyu|y zr(E;l-(w&M+TaxP+>r8|kGDVUC%Q%%{USeu{gTD#*TEso1$`W}wj-fscJ7BlG`8YC z?03wK3eb<*LoL{Fyr*LLeslrtq&GT+YNUGmNJkGoUPu|3{>@>Q`9yi4e{Hs>LFs)p z)Dhq2bNBP`uf)L9XhR)QW3ubN_rBavp$!{WVoK=)KTvvvxBj^yR68Kf@#5%)JxR^= z_kw1+c|?GpXORam$)%cFx8U%v8^$49ulwz}+Hl|`XaG<j#oe9hMP29O2UdXeH23UF zy2I^Iy*MSb@sn&*aD)0cN|kG7B21VFK>-+hCkJSNR99x#fCb!(JBqjMuYRAtm~UwO z#n{?uZb5zdo{w^3t*H$@V&I)FnZw`1502vh5Zy4y+dV;$;FaBR6sLVxUm79c*f#_1 zX^SN3hHY+hf!0GobmuCpX$;pSU=xBje)y8dgPjK)&2gXdEJ%S!pm`pryV0j*s9_SW zLKF(1CkM42U6sO|S*T;@J-FtMxkP;*IM??Gjp5g%p@lQ>w{=)SOu=5K=x@9;w%4WQ z`j?RXG)5lOX5(__9Dl1~xC`2VJ42Tu`%>bq%cHo}ehUrR@D5W`9F-r*T|}rbT?|Mp zK~AxQ%GsaEZ=M^f@im$|Kl~u3!dbCvJN|k9r}ki1X>3cIkE^q*04)O~#syVlVDHy) zTpKaa9Mm4&1aWeDq>-o9sLf`<?I`n|OYSgI*tQqj-B!5E;rz8b$)UN^^lS2ga;~=` z)eYi0duos&$%y|yL@X0StERKB=q(R#+8BTmnLfVfGb38}qV`#((_j3y!aK*)m}b)v z)Y9m4YGv_Ii!m;ldiwd_-S{-03JA0H&TD+y;&_UwxQ#kno2k$vL!xyM5vjEA>NBMJ zd_i&EA_VX=<yw}$k83hbA34`K;d-15w10TPqPw}9X_$&*$*jIzZ7rh)wUw6cA8!^J zkm#4mm(9Morz_<CAb#O*5G%BJk@N_@38UvJbuZZs<BXOR+WmdK8@Lf?eQ${>#{E{% zu2ns7@GZL<qgQqoI8&!}RpQO=kwvPk9RZZnw{FA?1I)t1F(>j;9cAn<U#XP`Y!x0W z&24(0P0n{E*kDhaDlKK>L`91~-C4-8i)1oYn)XX>Q#}8MV1spsH4<e2)RMr9{|i@< zw$TDsE%aKhLd%cnT;7ob&%Qv0XS+KNV5h|I?tZ|52{C0Cyw~A;#0vjuu_*=sDdg$b z-PG6NO?8&nWWXQ)FL;GWka!sEiv-+3m%`rjq{-bI2*6==YE86N0iZ{J0a%u(m%z%4 zACL+W4xk&u^Iogg!;o!2;3BIXK$9vDava@g1>P&Vsqo+6l`m9Ez&legD-)vNu-y&i z<41ObuP^?+Mf7qQt;e$|-I_kW{E+fjm_*1iK>mn)qVW$=+3Fb(cW^_&hD*RF<FHI^ z6(%q?#%=X@@%ow?TeI795A1eEUAj;cW=iVeZTl(oubs3{*h65q#)q%`zfgd&Ie>_; z9CM9VUe_e>SofSc0E=7H_<6ktH>Q8NHv<QrxvYdyXQ1*ZkC^x`LI*IQ?qUx6mZhb< z$%A)JUad36&u?UzKK;`Xt#XP0VPgpIEw0;T|H5^M_6b3knou`<T&Z>u<XW*)S39HT z=R#(z7PX_PD@Rg@-qr7Gs(h&_+e+99!-urq_iN$e@vHwXZB?Y`FK7|nXG7<a%)IJ! zX?PYvcG}_dh<HaIpzi`wJaR}h?w0`*zOc5)d~`8tkx{AR>EP=JhNMLVZh&EUzmFk1 zJ=kPGv>a4Nk_k`sU00-9g9u#q2Qp{wp_29*I%mF5>uf&#D=yDl4tM!iq~Qxi4;A17 zQjSDrpnBd(FD5B%26wi(=+)?K$!+KhQV%hl9eKzqNq2Q;?HaY`$=+XT-rs1?7q{3I z9pX45Q9hZ2!HJBgmALT5PiNQWrSf9YZOtFFDJx<G`U`ihuNAMpbn_7O+QQF<P@NVH zHjlJk1``Q%`3(9<8ItOi<Npp=mle{L4vto&Q8yeWiH)%<5HIdpC%GJYvQ_WMaz7Gq z`tdIF;cvg>xsm^Fqt*0z)j~uq|C8)liDuJNsFTk+T&TgeuR0Lvt96QA1}&Gc9z9)8 z&7ZwUKD<`s2J#nrge0Puh`|)P8b@jRFI;(;0gjys-@w0v^1vF_5FbkJceCMy&0{JJ zeJxh3grsfPgBw3v1}14oT;?SyTvZ3cvA-*Mc}W4C3!9ZHK~^v^mNZODRgSGS?^uN4 z&r+^>frNnU^}T(T>pY-Z`I^pE9q$IxuCWdd>TlP(x-NwIu{9+nr7^j*<@^%RWERK@ za(PHXl%{pF$={B_630{Lj$WnOmX*DTy800~FC$|p)nNN$kB&3x0sa5`n?3eDYuT$< zy&IRj+u0mUN>AMA8DRHnEtstrZ1V=EgjQ~?(()zV2%MPF<Q#G)p);3V<jQxYmt~>k zqR&pB7Pn~*bH>EPGsyyV?eh=>B(AcQne6h!*}u^SNCZfw1zL0cp7sHle?YNVMn28e z$4+4gPIMh`X&jFSVeXE^hd$B$=+xGN9WAa&E#ca*-;=0T9KGr*eDp+ZM0N`H0Om$b z6)a(;k>kUC)tu4}zHhf(-)G*RPS@30{~g+zYt!&RpUUp>UmJ4OCLa#kPT2ZemnU!& zOI#>k_gTaM2Biqo!QGM-zoXQ5c5evoDxa+VJ9c8<>!q`?XXN3lXK}z<w#y`5g&<$P zx*Zfog={+4@8X`%E?X{bnrq2^tVvmKt7FA^zo=}^!Og)!WJu!W4_M*r$*3Mngn`7w z*1i(5PB&A!LB|tyWt{kOx%L17+hQ&6{RF6%5a6cP&56nATA076`G+Wo!<9^~-6&%- zTUp>V<MnZ|IXr-Ymnn4o(mMvEUJ?vkr31`#dqMO_^1x2x>L_P!J2GPx=NF^>Ac+ql zbekNFWvM~vN(M}#L8aaHj3vxz_d>5}z-RFHh(M=FmLqG}`J=dj5Ep7DWv*B7U%?D^ zxPZZlx@!DppCZq40N*Q2e1OB|gz-a>XGdB98KqHbDyi~AT1h;a@WwEbv(t->v6}z; z!?g%7bzEsKUU%51nj~0I8^SQDW8L~!u#~$+VqQ|m=Thj}_ZxBobPK1EFH-Wz`a#)j zu>p;~zW+H~0YdY1@|WY|8niKewMN)P=lz7TjfhKyU{3UPC0czJz)oIK4=C8@A6}Jp zQ{+hV9f+7qg~+m~Jxo(ejdi;FVXErDxav*xRqk2=8h((C1}>I0(R-yOK^7J(w11U- zppTMiP75+gCR8;UHG9p}mD|MxEb={8SbuuK+>^X9Lvb>2=k>dgZ>K1_<~%fDx!gIL zXZn)+R>O+-w%n1q;IqF#mDp@mwo8)J5?=PwkYHDbS9HY@V}g3UMGfZ7cxMieV_`5Z zxa9E7k1hh9xlbF14u&3cC!VJ^WO5+=d?&tUGzgJcj!K*Ir2FXo_1Mchn+{3{^psmD zbxGOZk^3|gE3vvy$QCczbrkG;UZJN!O=EID3UR{hFE(=uk&LgXlk%a%(Qa0qW9NYU z>Ui|dK_|<)XgJ56nt->oQzsi!$9YdIj|KG}sn4O_eGpxErq|ARPvEPjwxvM9ir7O0 zXAOXm4vO1@n&I>XQ)owEXg%7^4Jcj3(y%kR&R15A=X`2fl<MT8(^4d7QXb3_5W=0S zV(%WvVO%#Cz<&&TfJit=p;Ro*&z0WKGH+MYG6XN{RmHj-oi$FYJZ@pQ?Np+Ji%uep z?n8ky_!b)Z50RU4oF1Bkg<$tJ#j0z1+MChVot?p;&U(K&>9KC`Mg}N_HF2Va7L;;{ zADXoc<lw3G%rG_SU7s!h$(PD}D%{&}nXNgL=3C|^{jrqc%_#l&^(Vo16F^UUC9a7y z8=22RZNd<jZanB%Dv*}=`XEZd;FrS3S1<o`K6n4Q@j1j{Lt(aZqSM#k4x)n7$bdct z6!h(j2|$i-vNO=`)J<^tOe-548LN|Rmi2h-)BDG1V*Ls|)L}f(XIJ?kSP-sb4H<o` zXJMcHj5(~hcvr?Ky~b*gzg1Vx3#GMakokKl+;{Tk`Qm0vtGL?6UvQ)MJ_(NV)NBUI zbV*AvM-s>|2^^I8bp5GLSq$XKFX1NLyKG<lwVLi^sS2yA2`7-TInoMO->u);7lgB> zjx&!_#{bzNum2QIt$G*6@5A%-BldQPrdXj4-g;@en4g!=G-}D2e#s1FVE3Tdf5uoF z@q0oNZO?Nd>$6GyWQ5n;lAN$=QEg6JR%iMJy<a&h5h?%WkRgEGY@C5CR7;lq4fUcU za$P^p9S|E)#)r1p*>;jnCH`3uN9iBgzdf;cm$t>aj`sIaR`967U*LwvF&g2{InY+% zzJ`rBO~rmvrs;kRFu~Rqhk<5f!x^}@KQ+1A<mL_ojjnT9d7g05KSU*}b@d$L>|)zf z;kgG&j61_RbqU|X7_fxLJ7>n;dw(3B#q;E2j1RypVJ?{qBNJ97@|@gN!^u5B*6fCt zk~|>kfSLAA^gIJf{pbBJDGKT=m+fprDq!mij%j+efA;oyjzYc}b8<{Wg$F@`19JRG zSVy^%yMUp^MpL<fr=R-rh`X$GuoS#>a>t7VGf4rp{?X9=WU>PD^?@g&f=3gpoqVO^ zABzE_!l)=#?&lyjQ9sn=ePcs2XJct+;{wnVa1^*68IMF~RpN+GbF%vFa4T>L4?Wf? zt`BailHGDIE=RVCve|tT6JzIc?mY=&28woiBEx8}J|9mqL4Br<_cZ{ky72Kn-!^W= z*49HjJ9&l04g91wM{_Lkg`_y&`;Wnhp_Fj;Tfma`8>l36OP?~T2U8o#m1pWr75rGy z9BHW=nK{1!UyHt8aSmVk6%*L*9Ad=nd89KDyAptbvD@R7ts^kQ1Bl!B{sDS0WsN61 zjMFk0{LN^m`_WIX)`r|oo94^|&pn4kc&fIG%;AF&pCd9e&BDmhDjX}lM5)HMe4DCx zWT9x#((mwwNGE<d4T;2Zm+9=D;DTDmR?;h%!54l%q}GkogHxPTljPUX%(SOEkn{yp z)7P`WqAJ^b(XI&8Sz8x{@zh5&;GO#O`Ec_oq3Z_8_qP@9BH{ybT$S#%wOyLQ2TZK< zf{)K%wz~@D-R$6QNoN_Y8O>uFSh<h!j=czIiBIk+-8Kk9Yag6E(bF8vYBsU9a=(wV zvwz$lz}8o-B7<7icqv@BGW)%d)>*6j5U-32I;8^Iy?O#J0|~siPu7PqLdU~RU>1D- z4%SYO>wZ^xn%)kXFtbe-pQ<`@TP7pFYIG-cf6s$!Qm6<vW+0Sf(cAuWQ%d{_b%ZTW zIr8_6@qwq}@5`43j;Udz9~KPQYMN;kmeHK~fl3asg47d#J3+zSg4Ey}N|y7dKJj|` zqG@4Ms)8$<<?L3n^1jPzs7js>8|X0E1c@I=u66R0x{ol&RUxOn^+;cYUTMr}Jly(q zv6nNc-Ha*r7@d%0;I3mzXz!9-6CGYmiSqGy6NvB$kS;kD^56B3)n;CCR+V~JpQ+bT zZz1%$n3M>Sa6KM(X$e?(&C0sg$5lD*xhn*w_>^xeiOj7>&zQ{@Hg;qQh9K6hUiv_B zbaDL+`}9@ZdE=DMJJS2a*4S>iOcaJq0`jC)=KO>H#}`a$g4AZtk0PiT#U6fmiWrtl zcsNNA!3cZ|o=egy_X@U~sX#R7@#JUw1ZLP*?oIyH9S|YGc;ApawPbX3icR8WQf-np zma5|KZCzH<93SC#`&2aJ^=a#N$rbM@6u*E|vz}hV9`+Z+$mWLS$&^;?u=C@#;`YC% znB*FRKJE$UJG|z)`OKZCHI9aP3VrlD#99k9W_gv~NGA2MGiXgYo?e+6+<Woq>{RLD zOk*s3U)W)hD_b3&SrpA@$++<T$;~*^+IeYmJQ8CT)8FOPmrsgQ{<YcF(iuLjJ+|K* z<W8Ey!buu8gi+%^x1ltvi<p3t)!~BnHOohM_c;_aE~Kj6gRu1zlHLFV`*{nQ-<xV5 z-qTcpuQe{uRmzxTIR7DnE7!l~r8gUX=@atIV*X27C4)0#Nt>PaUq4>Gw)WTY#+e0z z@p|8{e~&>;@|771a5B{QHAyHt?t?&IXTR<;C3-Yj{!Fq|?Q|t?+%?IxWf0b$={HHT z(D&J@RF&>*8Dx%0R+57{VZ*v`oa+YhfS2wZt{$CNqlad|P6HEPln+_hgo9y&fjfWG zd+Lv0Xb~SO>wceb+=Jf1W=DbSoRqS?@_B$|44WmO?lEHMqTSB+k4%v(Y~Q~=P3B!` z(@3(MLo#3H#_Jp!_?W2PrOIxQ5-VP^W>;*I1&=VSPdCO6#W#!FPu^Eyw`?NwTsc6F zHAL$gaiDBRI8ds*se!k?atPxC5Z4RJ)ZO>Ca}lwC6VbH0ZK~$QPk$Rhmg3M#d+AQ` z64~Y>={B3lcy0;(^r&b)Ug2Bu_j)hpZwKrc18^g7R+GJ(se7xvxR;)0riRou&{!RE zzaBbXsW0tPkNMHp!nV;WbddFgA{C^pL`oeM!2h$)abt9;ZYG+VjOq=YVEbrGLtj5d zyrnIus_#KYIaLcfCcc}4K#L1(!N%C)JO{@Q7ag;v*Nt1X4+A9Wb4t~^)m7L-tK*n{ z-AZhnNPpoPp=OIuzXfCWCcw~$o570%MvL27?2KuO)cvK7(HDVfr!UiVBWP<rJUb0@ z6AEA5kL5nkqxl^+VF7q<lX_h3WHA|GqV-cJtM}U)Bc9Jl9Z&DOw&|X~&?cJxlDva1 zikSG=_qXPGCBI9|m50SujubUHf#|9_jGqANnwO^N==mBP>`rg7gS0^YwME&kXjj;I zCXRsW$D|rM516cOX&((#R32>NU)=^<mnu|_`sYSw%L=_*!{qg}pNG`6SxBF?H-M=4 z&|$awF_NEJqHv5${nBIZCglkx{X=rLw%CtLRHQWE1%!9(XD!{#zEAQG+-LI2w&dpm zLJwK+5F32gn%;eM&tO4}kL9XISRn9}57x#}B58X|Q8pzB;;mX318Gs7|A(*ljB2Xu zyM9p=R6wM65b0fd5s83w0qGq?YCu4mM2SS{9qCddU3%|LdI#y!2~|oU0SN&@u6N&O zjPu-H&p7Y-!XRXXz1G@mXRrNR^FL?3$h`=Qp;(Pvhb2q~OaSW&M4UUI!us8KHjg8@ zfSDHn2ok1!ig#w-K!@fow>@qhb8T?87AF0w=?|aO6y}%_+KwJ#zi1ir@4sY=lYFYx zyG9}T3xTRgEwnty<_taR*9vU{gtmwc6GKPe1l3b_Xwkys`oQG@ubdU=(WWV?GwzQ? zCtYK>Lo@2Ep~(09z7$4!ZZQE;YT4AHZv2purm3~Aey4w2J?|7cTkWetJ9nbd$E;%B zbnj>M*7u1O&)}kwF@X-#mElv@<=BLp^Q_seCWv&nOjwXNPFO1>$ACPn^sX9%YFRb; z-Lc4|qDVboC*$%Lj*mj_AXbdzeipI1OnMc_&gAW`QFSP2BSfgd@CLeQ1-8{+<`#P& zmM_T~a(JZ~eWXUflKJz-ab%<RxwXqf4J#?nTeZwMiCrsq24Z0Ab!@1Y9@Gt$g?lzk z1ygk~&zDu)99;8FBMy=I%d`@$7QXNg>;y09HNMb4c6XiWT(4nc-mGm4L)>of%f~;Q zCt1eko-C;TE_>9ThAdlS+N5Mqy@00j?O5E5<J4th`&5dGqxL2hwo9A-F&zE=J9qwJ zcKIpq0PNk}x~yY?tKr|*$An#NpbUpUTv-lDMf`ff&Lwqwx(hE~MiuB}TC&x=Y_%-@ zqkT1>)Z)s*KhgVcq|}8Sw;;we^5*`1Vz!VE9zAP|<ePLoLP8R{q>!WYLr>vfZby;B z)p3eV_T+EovmgfeXP&UOwM&X}e%$g^PaXF2l@iV#n_8fegH0Vs%^i1Gl5Ed0O;P;4 zq^gb?d+%_R=exf29Wlwtm#N7zv|OHPPZ8}y(`h*YNWQl?$gkf5-pVlqAEZ8C`36j} zvQ}Bi&G&;PoF9koFRTCfs4?ap0J_e{i$HbbE&8*$U7IFrzR)Z&!e4&dXp-Y4oKm2K zI$`4w#2pIMXy$a!tOqaL;$aZkgC@2USK7_)7OR<K?<b=Z94YU_?rUseN?89V$D1gu z$AcD|hhW(r&p}=F(#b*RJ%h8=F_gpipKa^NN{(Yoj*dtU;^-#)gvPG7yQIY}0T5Nw zi;ndY(5!(v0g6b#q{eFgf{~y+2d9H}3a$75=>NPWcJ*jZkCW;VbKd=HSFM3gwg67t ziy8J=dDoIYe@`I5%d3sxLG!rG!H{G>Agxr$+JrwikPEMEX*Qx-BJqQyl5!Xk5ct3S z_EA8)+yR1!IAcl>T41EKzg29BlpT1JzAX=6{r`y<Cy4Yn{93qR{V?%;NwwQcHUjs( z`I}i!$7b_ki)=3M?du~|qhHW`W)P`E53Y<q-8&-!_~yf<xXW|c^{t;ouc4;s*ZllU zdfV#OR9oH*Jf0*Igq-MOz|!j<f@s^Qp-?S{8|QovygFr|gxN&v_XSdOKgkgRX?e1O zpxOcpr)a9GI$8UnA%fk{=?(I1c~#5M!)(|bIjTbc{|PdG#sK>-G|l@9Rh6m`c+**P z%}9)dO_!&Dgo#84n!Vo2FzloO3d@wr>tC?rAiSg&@O}J0H4vX9I}u_47j7lLM#1{) z1nc}k4;Bk6zZ0Jpj2{bC$vjbGQ?wlWmm|@wzmV<!KKf$vRtHU*&$S>SQ_<H|4<62V z<Zu4Qzew#g?mw<nGMxv@u;1FIGdIfrZkfjmj=r4!GEofleSpcxd2Qwy{&&TP7V?`w z7~DLL5MV~%NdE6#x80X|2{B%~Qqv-}_oIMIY`MuQtOkAu#9I!f{}8-myIKeCLtyMY zUJ>BrHUNS8R`2z{8Xy^4@3%oxFnK&HpH|yBV#!K`n3%cOQ%-&lD2Vz%o(K5wkUeAi zzc;~N8&NK<6LQ7`lOAnU=Jbbi0M9t+eF1Sim5|L<72y3%jC0NXcYHg+u@Go;O5}2< zb2z`k2Rp1~fU$j*uXYl&<2%5b1nc$|xh71-<6&pt33Dq%df84GfY7jtWMInO9qs&c z-{uPN9-1qr>v?++De2VeJoaPN?(Ub)SZBhl+!hd45g6d#j{tw}Ls$$OD#!xB`znB` z^e@0vnxGZ|m}^)5r;frrd19!P?Or41`OCY3xK%r;>4|!2JXIR(H*@DXV3$??jD^NK zKn5_hZUP;o;eC#=Iu5}2c>x`oz}G80@kJ+GmpDr8P*vS#s?GLZ{3N?C01Q?z;~G9t z1hCm2z)k{+Psz^fTQ>OXIP|wWP@p`DjgIX|<WzEU?$(#eAQR++>Za52DSEel+4I7G z_qwc;9yUk~*xwuB>(%~ll}?<Yf&geitotGH?rM1xdWreNPhyaY5A5F^1tEwUf!0O= zt*ypO+(`V(3*0wwl{re$piIqYD#No$)!;^}??k)WzlQeP{m8slpywK}gG3mIDF~H0 z0+hdO1D4wGYZoJQbm|)+vcT`DTS7Zd44Y4R32#RJ2I^J*J|e7}44CwabihaK0K1sX z3d|b*>E=HKZ(;m>{~DzEnt%~_btMvXW&X>xWxiV^6g`p$F`s&p<!v(KE91ryN$aCM z8IeZ1?N=%_8cZ58Oswz!*6iIA(b7ZI%<{_Aq;q9%>w?W#9-JzwYrR;msidmlc3Y85 zH=mG&SB9R3kcAt^Q6=_K<ssj?mD7*nD=VBO>SIH}cZ~{nY=H2u8Z)lq1U`|QWd$sY zUc;q={<*G_$>if@AZ2+Q#Pmixk@l@NYs*t5clPWJQ@iF62epKituQgwgxtCpzZsJ4 zIR)&%K;R3{yu2@fwpVXl!^<4eMsw-&UVWQm0{tz|rF0AS{c2Sh2VQGWw|T1YKb9I} z)Y{Q{dsJ}55xaKOf^J$0fxthDM+@^j-ro71tobe>x!D0V^f67ux4u?iTiP4<`%(|p z7_rI-=~9#2;8WEpjpevgv3+MUc)m8MNWg1x(tF!_JRc~D)ps{W!NP268Y<unlI>0# zMO{Kp-6rP7@cUKxJG1Onx__h->^}|CY{egOMClHJrB+_hO2<n3e;rwBo%x5r9>joM z(m}zykHZ6m8s^Rjg^Rqs5!wNpYV|*zVywjyz|#_WM(??4yXhH4#Efp5s6}ALS~oi> zTsuiRcwH1g*u)}8q9Ka5C|CKGUjTVFq{7F4#IPwr#$A8Oeo9&4!kEukI~RP*3&_8X znh2Nx{7mI#!KkwUF|0?Q-T^D9o-t%1>dyqFb0yjAcHRhy#w~*=TcJ`l>IW0dS}g=2 z=g+Gzye(j_->yCpoH)^xjiGP6_a!pg7GhwK^ajBvafHwVMJ%QBN%OW=?v0j8k3yd# zz&mC{7Lk?rlD_vT1N7t<s{oBoQC(4Fa8<G`U2u9`$!qpQUY%Il{Miqt-{%VsK$H^4 zVd**{xez!)y1U&@AKlUHX=_`uGKN?h$ryVi>bs@;{n=uULtV_&zLWZ+Zh@Qjfm;4f z*)3$sy6x4z{v#r_7Yh)?sr1)*o_oEXO{DfWpYa5$@kp;*0p<f}T|f~P)$za@Ld)a2 zJClpe^V^uH{~aaaM#$ge3Vtut%kGAGW5-Ew0dp2$`0{)pFn}rG=Vcg@r)VDzc!au* zuF<yfac8ZI(BnXju>(DgjImjmj3&Y3H<dHXi<VYJOZK6r6~=UCn@jFWHC-2B5zVy3 zPX}EP8yD3w*5IxKxr90SnTp21K(CGp{`+pct80m#upm4)cBlu7b9149;93me^62~R zFN{Q-h>EAS(+f0z2A3$M=iN4j9#L0iP8IO4%1sMHwbsd8yTa#*$X*XFuJ(cDMKvUZ zdgDvSNC#VgwlL=)#u=C>1=;G@!j9^W0~hQ6<kS<jO_@AH4FvmiQG)rn4pSO1KikA; zLbsofP+laG1xhDBcS(?w8kSSfnG6yj4ZN>Nvn?7hoGm^RAio~~!tx<>DVHVQk!;XS zL#e(Gd3bvGF~`vseOD!URM7iV%Yk0Y$s#Hx29+QB1*#UvtQ!&vx}p*<cIMvIyz=&t zb8A*n(VXv?JkMx#zUa)gp+&iqvqd2+Plbcg^_E3}<@}oY#q%x{#oGM^=6XTt1-Ert z-exnMPw#Fgs<i<2*(|6lj4Bq4s3eDQY{FtqHb%1<rrg}1OzXjnp+%+37D|0b-=^~f z(Lb~+F8mk-hs|W19TUvtFWK$@>A*^J0ZhMPbP8g><&d4hP*~CPOL!EX(M8?hO6f`G zpYXZMaZd@}T8kCI6wDOE;HP5aTSP~7HcQeNA?(vDPMpTi046r9qC6BTS$^Fy(K|0q zyEs=+S)R4LwwD_Dy4f{P%3xH4fl8hI^Z6T^Rqz@UPL1wxHaDP$t#+b&1o?Ve8SCnR z(6$*+kgIEGslJnLRVPCmE445Dds=nJA#`mtrYXytDxf+d>_M3dT1E|Q2%UAQ*IkY@ zNzm~6-j9B}ou#@6=5tQPSVK;hO9gtS$4(i4X^wmM`oHK-<uZ@&>8CD4D6jOY8g5&Q z7ln0e=I@(aZ*k~#I*FtN@LS`5(1K_JNX?=AXz5@H@;eZJ<MtV-i7WW6#GYN-^f!Zo zk>X>~<%k4No}~F(b=_vEl!C{tGxhX`3Qxc-@IH~x*(5U_IO%*P`<XT^r$YKaOUP+W zR#&rz;P%D6hiM3~e2u6`isD432#%_AJuag2%>|xx6`;?WQ}rOMaf1S<8@V#7OzI{| zxK`dzti@c}!(;nRyxTxxjfxPJSV>7lKo~5Nt%2vz;G1w>nM>+F1k`OnZURru9PXf9 z%b%+^EfT*-m#nOg&bcxa4tkwC^uS@LANr)bO)WvNk-t~7;gQS1;!MJM#$-2o+uP=L zb8*j#yT;HEC=qQCB+rjl<{7MlL<b0M?%VQrr<dz^M<u^72BdIj)enk}jePbE;v{{; z@{6a680#sm$62|Y-uo4;^ucU>IjOoH4UztAHi?<p5{n;v_(_pPpaxrg^}!sR4hyZD zV1$5r9~``uwE)roGGFXSWf?g(JpDPe(|@6^@rXO>{^7flh6!%$d$g80w$FD1PPc|7 zb$+b2u{2nIxX~1`*<j-Rxb|KI6Ng2_?N&m@Q`!$HMw4h*@E;H}<O7Tp5<C1PN-HpW zQv05I>*U<?*9ig~h*=BQQVu)Pvb)3=t^AM)Qpo21`xWUS+B`j#wdI7Ve1%cCK#Q&~ zL@UL_6VHlZ9-#Z<iH6gBLCYJNQy1~mhbiSdjWASt(}gDN6!F(>a+w3b%x6WG-y1q} zori&DtV<sE#<*@yAcN37JqFNcQ|<{GZj!CjMSGXbdg5)OOC-7RL${tYye$4gwBU8< z;Jm1yh7rCl^Bp0NV`GFGpezu{=Y27DeU~Xw7!j=Mv0a!>3=+wzQPeua5HRA#oDChi z-yfgtD!XAHMNyX>a-{`nhPmnn&ckS+Zm6)X6jnBr?_s?2J63_8hw{q)8!So?jzEED zR`g)nsWq)zZja)<1r<40UK2R(+FgG&!GN&bAZMGP4#`?napM$Rf36~d$->{&*?d*< zVRtpBzS^TcCJ7}eTd%%6vL=4O%wsz(RQKzaWHtR|d{VV0HG=3L0?*rbRm*J0bjDPN z?`z%{mevcnbOsFay<&L~FY>}s&5^xEqa0}n{+}_tLmPZ5Gkp&AVE!-N21Q(|_p<Jr zzA|*uOw6L!-^r76V!!f$bv^X}fvw!taV8FhzXPP3;l^m<FrT$Bsuxv@%cHg8><O2? zp*t2q9=8&bL%SH)<wItR(v5$E?6T}IPv!!cA)USO+Y0wx(hc#<a=xiJ4r_&K|1pba z=oiu^K_f;T;CEU~YG8#&@^4m$xy`8Up;W*YMFR8{_H&s?zehN%79LU0l%acD(atUx zOZBWJ;Yp%Yj;Hv9SK{*tH{PhjRYN8H0+ngaZe?nU_ryr;D^*C3K6W4<a@zlaHWjrY zu*PBzRI$jdh1CmjU#};Qq{vi=gk__ZeYg65R;P|hp?VVN?<6ntqj@M_q0Cf#MV#(c zE_lsoiX<EEZWsCSCoSu5B{wIYr%KoPUA3v`$o6m6zNvg#stI}Vl;7xkKg}ytW6yAK zZjvpX$%6w;>*1_7@}5+MMcR`3d0VMJ*Xr0Ja84*Vg4!I287#$8LneA?=ibc$_IIy+ zr?-Pfnn>KcR}G~K^6FdSEq7${>YGwLxK~M{N@3}pj<7|>P0SbU@doHF^wpds8!>j+ zq-Dk(M^Or<60FtsWGVh^*W4OkNU^xEq{>mf#KdU=Yy_z?JZ0*E)vEQdSZv&$51fC7 zU!Ia^%56n=<ZNhb9}CyVD7xv(kR6Q1wA?Ar7ursZU5QyjDsiL<e7$Z4><wX<ShR3f z0T$HVXs~}N6oX~u2k0B?&UWsD5$1Q#wdtE0BeJ4v)I&%{zbtiTaRx&ecJJENS{m{q z1XOdAvow8^i<>0h`=bpq?Wd!^%_10hSNTr0VIX^Y{9QDgNZ2iOn0($>+X4{MY^o3~ z!(*=5ey2=+Yj3_sd+0UKh>=Op&tC5<s8E3p6P{^CP%`V@n&p&x$D~65>&Ebw>hId_ z@jgr98=p9;31Wi@<MqevB-@wq4^e-<n7O(YTAD4ol)Kb?O;OJx`onp5(-<Z`oXBft z82^RLv$JL`a%;YW)fy-XnD6@SR*$6dxdz!_<NS-%FO3iuO#WF71Lq==!$QOCpYP@C zX;9a6SPA7LeGaakTKBrNSa$g4r&9HKcok@lK1$vYF3`BGp``Zo&eH=F=|QM>Hbv=m zWwK^&Pv7?|EwgTI*Slu*Tt1s)Wjv1AjS;x8%|>Fh-{%17U3y$9jecTIbYh755P#C9 zxi3Fr*28gI+uwQWJ3>d_i07VuvN?599^D||w8RZB#fhMA$F^@gbqCR4;l@*SS^maN z)Ar3-9h2gmFZ(d2uOpCibF06VJ?`~qaM+(rsrra^4hRW!XN#k`@YSU}5jZFm<oDef zf42s3>iS5c(U_tlYH2gLW?vhhA15s~CS#oNAU^CtKU169r~0P$s=%Ws+Nx_W8$!3W z1Wn!@T9bry-L_ZdAthJ!kyZ13GmDBxgQ6w=Otwi}nuN9qCfb-oEYxf3)qM}J$T@Yh zWJ9%E##b;emd&-dG=nj2x$i+a5USoXHhP5djS~d=p3wN^sVcvmp1DN9@VwBmwmEKQ zQ|hC&?uJ?@)FS~=C4=jviy3t_?lb9~EHzFj0D-mc-qs?Ij8<sYCFcn)xUFbz=sb`D z88$VCL?$;~>jem5H-F6iL%=Mrjs93~Ci&e$-AV)@^4V_M-8W0IZ&Uu=WlXP<kd(zj zg2lneP<c{u{g+<*lW!qF7HcD7E!YQ$S;Q6qtF!wHSuPmxyxwFHo#(!ks$&8}$YG84 z(_X66540N_e&JT((G?FQz2qkP+329uDC^It)_y?metedZkWL<4QFliWh!qTcS!1b1 zmQgs6vbr{ypkZj$C-|j@wDvIKmN}dOSc?Kxj^_KUAhd5qa-oV()tKO9>i}IEyRR~{ zruF-`-t~sbDq<7^W0&rBN%Q5=z+yW(e?^i+lDBY^)wEkw*WZ=;A}e9X9DlV*#1SDA zBwuMDTp4C&ZD(GtNmIo-TyAO4K6D5!kzm&`;<KGqSBBHk8~52UC+%s{M?&mCm{{OB z+Fuj9Q~+r?_Xg9g-s%Xmn3cG?*o>GXseb^=uV9Z<CrwRYk5%>k62W5FL&BB`RN(5( zoY{m0aI~RC!X(D15cA#S^)7yR=2=PgKZD0SqC#ySJf%Zd95V0F%q={kBV)SI@Q_|) zAhtjqZCWO5oNvJ5gkDY6gU{03IVa^oPEJC<8sogoo;6Y^-m|jGS0eE@s9!mvd+%UN zyEYET@--qQ5o^&OFmM#fIw+iR1aTa)Zl68zVvZF*e0g2LnY_riOq5PP)AQi<6vq(Z z5K|q<(X>M=9Gghejpa|KHaxINftx;M6K?@GI;KikA>GXcT+c70@7j7*u;#?CSJj$Y zKCQxjI5POYtu%ExFDxcxP^#~>9h59*ILoT8e3xI(00R@m|AaHtPb{)+`b8>8VWV^d z#}9g2dgnWB>s2VsRR<`3WEd%$Zr=G^MRIFsh;yFBiVgP=n23KUU{@GWf84*25=?4C zl&0D=V!m7$Jk~6|()bSl=9=HzmwO9Y(ZZQJB*590py4Bg{flw$Zp~TrkX^^HG<{VS z<8)lqdB2C9h9P8A@t*;(0s~#nM)0Won`LYK3&<1=IA)95G>+~NQk-;uU&+2e9z0_{ zqX7uhzc|ak$jZ-K0sk+hp1bv3o}RE<dtmYY9gkG^wTZd^(9!>*G=TT~3q=?G>)j%i z?{GS*f)Tne)bBH9j`sRR2g(V&|Cj*G=)ZgmprWp@%R8OdS8SWl7y{@4-iqv;?fgS! z74xd$GhLYBf!=am;f;6(OG0>R<)$9c^1mtHcS(^8qGi}TK%IVbSA+f<nwjE_1xZ>) zZ_^TzpzRb&C-)=q>D5n<c`M@nI-=U&r|XmK@bUB!c>$o4{d;s=M6lZ1x~W&Pkj-lV zyPJQK;}-x7L4tQ|E{R31asLn;0FC;4P)N&N@k-}5XQ+P&MrU1q4}|2*hGFtn#h5<t zP~W+~vb-sK{;ys$Z~x7VXGQ)sYs9oY+a%V0RWC)PQ1nLs;_(}sMt{2>2>8bT-PgY% z;7t)GfWYdAT%NOCQW;D7=q>O>Q(b9-Nr}X_Z|Swl>^|*m*ZTVue7o=UH#Y`O;@{l| z*L+^DB9(2r(%AJIY4q5=KA!p{{ky{NZ@8$2;}HXBsVwYx_df$9^lxxH`%@(VYORwh zX#Gra=h&cCW|MyNYOMhD*Lirxy#2Rd&h)<~<djqhU1-vQ=W^W`!G@G2Ve9q*_9xL9 z&G^6O!oSYQOQN|_V4tD2@)DB>;6%xuxl2fewqF0&ImO#UCsASJE6Yyw=f(evc7FB) zNGkwp=T-5(EE<2mAfQ=vW;-Ej0BEvOQwvgp{DRN|HqZWyju+5}Z{dK*LG~2jJy$c| zVqoLqg0%74+kE8P%@$n%#1CWw`J*#1{+)w-AkgtWz^<&+PQH;1^X7hfjPnG7rh!kM zO?G~%a0l#eVFLx70A=11$oO`%9?Amz-?%ILwW*p?ldiQB;Nob|24wrCxsm%Fq(G7F zF|fb0fRn-c7LY_8<aK}xxL(zMdcgWVldwi|aHxwj*@$$s<e3co0c?<V7Z2#w^(?Id zK7()+tpjqYpN{SqpgT1h=d<T*M0A7HQ!K=Jg|_*cg)3;PGBSp^{FnuhOdZd!3;rQ+ z@Q8xf#6<)C`+Y)ED=C<@@oCAAQfdjq7tgFVq#X>J83J3xN`(zKUGp9jXBswu&{yQw zzBaph|NZqD%Zk5Ax9%^$4U=Bb{RQlCKb~U>dKb~IKfbf6F^@CY6_k#;m3!BUmfFug z(nME+7pyOKBItEznVhkzvtz0<XI7$hp}fMa(9G>fXp4_ipYOJnsaM&ZTNHzjI<*zp zp%5(3l{4-!s&xc4Jvi59_0cQU9LG4;`ynOk=02+{xDZ`Vb)~T}B^2|$Ih)TY?epqr z&GB_cS1b|Y=*hUt`l+<uNj_4$Po`&ex46{gWu3=TntzR#hOfhd&il-rq{kP&G$yN- zGc$RN^|F=p-HDkwI%2y?oV&7hISi_gvow@M7J;GqhXBjvba;-^GMdL3<={Z*Ed@ao zpl#<4?ck*aElF7$?g`a&y%m4$&f#x53?$mVNoeaCceWz?cvrf2B1mi9hHM%49J`XM zxIs?2m;Pok?gx^=Edh*x<kWT4h2Anf>Khhn!vHy*JPmg_N(Q(mqVQAz5Si)Vgo>e$ zk%Z{WQ)SdZP(1`$;nVJ9b~kU&4-=beT)8tssfyCRotw)UTi^)EkJMm%QYxS;f^tGq zT=794Tvy6_qVo`Iak!@&Zc_6|^SGW)tUC1eM_00t>$4@zhPgmmM++@G&H&F8nXH^E zj|E!3MLte^*>D^C2<oU_kkles=CnXHINc*%&+xibzkVBRjYEfAIPmsK<39H?(?pH8 zX^eWg^Oov$Z5a8grPLK0Kt3c_9fdWzyv#xJ7k@uBNU9p9GUCvGY@jf4-Oxb-g>_;} z3n9DfB3&QVG{pCT)gROhu@uGUQFd(nhqG2g{;@Jwa&LT@$vuW0{u=q*mmFV}_t)+L zRvR8z*>y4|L?iMpf*r8a9#Id}a+MX<D@^!t6wAOFPVn;!TAPR-y0eg_B~Z%72RwNO z1pI;n`wq^!lu$*iKafVqT#M?P4;Aq_5MjiMEwo7%l9MUt-*}ISV9%nCN>WXj65W-b z>c!LyaBxlz7Ok`?Zg?z`Y|w_~V_VjG@S-yctl)Gc?gJ=1K(al#u#&7|MStf)qBNs{ zZeHq5N`#+;-!XHwVqVvFgw~x@v<MT#Pi7SButkGVUbK~UQOf7yVZbAYMMKO$AG9?+ zGtHwdHz!6fC}D-zpw!Ja!%J!1pwr)ow+n^ZdTPX)(Jp-R7#~~7dv8<g%8iZM>&?Xy z-z6dLCA)y^xc9L^U8@h!J8<B8e<Ds|PedYZ%cg#@VC!euC+3)bZv8F`QfhRw;Tb`k z6P5~1hyb?2et?Mf;WSXaBIh}Cw;Hel?;K98SOt8YSN7}0&!^2z?~U?Bo@P$hNSUk8 zK97oE5g2lv?I3`_v{54AQ0Xh>Mcj=lEIh};MXE(QM&b%~XK7!76Q#1=24oLC*vm0G z5`Ht(q<-{JMZEtf;K+B!Q4Md0nvQUOwKq3{)&~oWXQf-8B_tVq;GWWt`n_?OnIDgv z{G(FY(`J=svc9~x=xO9hucbtpw6FQNz&OF%b!|(tg5}__=w3~<gIomYs{#{FV;ah} zxyG^wx`T85SpJ)pqrrbg*9;J?q0UmH1!><aOn5a8-4fjk@yPn)TKr4p));3(j#di) z(@y+71{g30i03;U*eIaJ*oBSC5IjBBf+#N6dZGv?G2<bb<%mHYNNL~tVy#P4Cbf6k zk9T3Hdc|ZE+?x2agC6(l8Xmv{>r%!)hB~yOJ3}Q!2!_@N+n#)M(SLF_yW8@(izE26 zgI3hLF!fiX$T(qjqGk1Gzy>9z44dkT5*|>*%3g`%Sm)b3QMy)Wcerl}PH=7xxPLaZ zHaIV=PiGxvIW~Y}v&8qN-shSf-65iQO9Fc_*Kag_I?7QHtXDds={C-9(Jz)njl82; z5^a=TnA;FlK;O-CX_2`r>nOUF%&SyRs_E07X{V=J@krDqQ`XWpEaZjS>~FnoBVH}? zJBz}GV8!Nhg(p}cv=f45qzirjiNzJzy?~aLeOiaTMVT|(T!X>ru?~lkAY6=jn-eOd z(Ls*Wp98X{E++=$BoturEl*mx)8d75Y(rxr@uXsR?w9;};%U8rYSn-(86ZBP$K$RP z!Sk22Ik&`mz<Cypmjb%Cq&-!93E%6hJnEAyD`j5#n*V*7m~>6<z+52@fpk26HYe1U z(aMx2bd<BoWFOvV=9M25cxRB)<iv(;yLMP6(zHZhW2}*jdMf1k^>)ch=lk+Rub2e2 z3-ZlWVo#p1Oh3|#F5CTic>Q+tw!V)i#dflazJ9WL^SIkgoy$y=yN0<yvMKPD(2jf1 zgx$U3cd=<u>pi%#xnC5l5`8HsRVA2Uz2_(WU|>u4QHukiPC{|2ry3>FG(~mgD4Xay z`4|XgD)mnbAcDl{wP@|7Y#P?hOKR}AE=50lzc%V2GM0F&HMdut!21(%2-FsvTnPkH zJevn@9#7Utxy!-jZF+kSPA9CZdcG`Ed~csQh^s}5GLMb8S%ob@Nf4cjaLiEf(1yS@ z2muRu*b;7Iy43a|rP8miOPFJGFjmSqTQXZ&*qqCwws`OQZcm#*x)Y8nEbE1~oT;W) zdJ+qg#>FEw;mF|pBE9Z?#ZuCu=Qe%`kuAC*LWiU1di9n*B)qW1$aKxa=9gZ6diQXM zEWiBMkb6d(`g)gHcgIe<y$sy7p{Z9&P@rrNSPI`(Lir8YP>#73xU$~G%6{}l)cSc! z|8hU$Q_XY9-KHU-SF(D6pn4OMY-E{oZ_NoRa~<Vdxp?~!&lfNUryPj>vlP#Q4?-Zt z_C@pf#YZRQ6z@Xpm2X`cJHFqxcX(td5VT`c>vt%5#gB8mZU!<O2@O!}b8S4R-5+uy zVUA66zOAKKSup+9_H4|iek9UC*^X0M%Fnn~#Utds`8t~b<?|`*ggG_`s1{g5zsRP- zx}wE5$opN1+x+7Z9%Q(ut+OJB4-@>@_EG~C9k1j=BF29oHR^=esYh;3jy1u9OV?-R z!zh@AAgZECySnk?^V<AT84F`iicg<N4ks<?h+dD#q9!CD%$>yD*ijt;8qH*0!@R2! zO33>z&GbBDi52JXC2>nXi=*>2^X;#T8Z&&p0b7bu>pVX|^Z_IDYs?+8P|;YXc7I^~ z7$G^vp%}WM{QbAIjYoRdpYUV10+UV~sVM_^f-KEU8?04~m2HFk(^+R|2T*k#Y|`sS z&?4n&#jhe)eUdLo6HXkL#%c2+?^S%@M-q%Q_MiekEob!)0Zw4-o<ECjx1T<EF(qtM z!b0nqq`jNz>!OyCqsLnQ=c!i}6`c=lw+AD-0o(V+K3L2e%7mN}!eNGOXk65e>jEl= z<y+j^k;u@`#r4-!HMQ{pb5$1B8t%20xpmI0tKi`uR@sMm@P-08VQ*D=Y&M@xO(I6V z#+L?I1BWgHj`>|WI=b)6-A1?mA;`d4t>04sDbpz51%T>1tFU78Bv*rSoy>>(Q(Ilr zUWLUi`XNSgMg}gvoLTExCJH7-jZLlfp)x~RLcUC{{}3E5><YMk6lx1J-E2}StH}7o z9+?`_t$Q~XVw(c;$JVZUgs{qD7Yea-s#p`J%~Fe}w?HxSejC>xtn>wBc47+Z>S|)P zeY7y%G?VfAq8=W+&M5cIfoMor&*eaf<iP|fHgIss27IpT;Yaw`L-_gYGO_%i!Tr0$ z-#HD<9g~Y88GUk(TtIX<-+VK$i56FE45Iw4x!H=Qy|MF=5yvT)+G1%Vgd}B=dhjqn zy2qU(FL;#JAZ-TYlb-o{G2n2ke1x;!(|v!+MKsafM7s!AxgHjEF&{SFhnf@1|9;wE zE~lSZQlL~eFZeBoHhnjB!Tmvug<(kvZ<Bnf?xM&`tWYt|8D*V?=Ft9GUN<sASa4us z?%Xo{M^<6{bw?9_>x&vfYA{WMmd0D7=MeG7yKP3m^rDBtuv~x~a~=Nq%(WHlGp6th zGO|&T?AVZ+(lCC`SE6xy>WOt!PyK6$2HE6=UrKu3``P4x!a6P}`(dXIquE|VqJ@T3 zZNZB6&Duv_8cuW=Om2Gdm}=1boidobwafab+-uD=1GOlDY?{rys{Q%Lij{Bi@^Vjq zc1l(_qFvDRQGW>+KeE4P=jM&dy*BqJB1K<qMNQxE9Mh;*I9`u*2dDN>S8`9m`&#FO zfFjm%Y*5r=dC{Jx0KSnL{=`rwkrBpH<1!ch(yw|cbmUrTh`ma%Io2V{vpD>1*1nG6 zPBqEmh1zEYAyX^~LN^R*#~rjm9wBEE$vJaR8#ULxe>C|9S<sL$>>6H_oRyz6;p0Fx zd?JWBr8_lOe%Op|+!+71SQ&oSNq9hI;WE7^^+EWvP}#Y@6?ksyc3VfYzr?e-li^CY zdmLX2xM>vJT9UuKUAtk@X9Bo(O?(D9f&wYmAOZa&T`g`Cac!<tpfo$K?J~avvppow zYHJ3PNLg6QLWTbUNu5jUq6%PCHxYVy9P7Jw6DLDQHx1c%O7$GopPH}oCKt~l_e)Oo z<$F)n3FhgxW&UqNOi4k1XsRSoG9Bjd{_k5CmX$oLzCaD5hBS+$CQ3(ND_saz;hll% zu*%-W;#l>J3w^4^Vt7^CRp^3y?N*!(`&vqTP{M|<H<I>C$jRhp1*W52rjoAN)|scV z879+hJaoZq$i|n}=FZX|4y792Nt?%X57B&s{J}(*c`lDoX*QtCoZ|;MEZ?ZELs`&T zn&^oh^?=6*9RjsgsIZW-3ic@+F(PAVYE38EEQxEYc965P<D@P8<shYKX7ATzd(cz- z92@2BmD!1&r;m0{&9U*GZr(-Kdvdok=U?CDGRod(awhdpVXG~R<-D<#h!m8D<;Anz zy%NR=T^F@+pcgu5R~GhK*s_?<O=3JtKXyDw(WMC7Td!;XG|bUrOQ5e#$q?A^>Wc`s zQP08$#8;y}1wVd?wb>aa{rudE!px=o=1l<}9;WYO0t-b~a0<Y8u1y)S;}E^Uyq|5Q zFL_{8&O?7?sd~e>(uPKj49R2jU~k4Way(Rk{N27`X_z6nyIzxLDaCXD!BTl)Ij6q$ z(g5>^;FK?#03UGvRj3k?Nw!ZP|3ybMD3tVesgTmSPSTj2*JQ2m{368m%Ud-iu^YQh z#Pv`lAZ!W;)Ma=cocm<QP2lkjpA6#;D<1K#aKSU7-c+gBNk}Dbj4o?=doq5}EKT?x zc}#tOcMNjy3(sZ))t?cmAEVl!`#hGP{$j(zO@AoQ)pbOc{`SWx!8j7tqbg8Z$h&)c zpLtT*PR?1ezEOzbwIx~ka?RoVJO=ZEyHf2dM>Fo}o^JWaez%cq7u6fYLCpjAw>y`x za&_C9J~`$Eyb}rajHVHWA$%<~9I7RG)}p?AeN*}&d;{6SiAC0p<Y>AduSYhBlFNtu zHp&gG=6zqRLdLiHBtB?ol_!t%xJ>pidlodeJeK!-7+v3GwrUJ9G-0_?#KETjv|1d8 zC_I=tdMMo>%CutK4?aBNv8kiI=PpF*Q1G_#^UJ~bZ{mXsrVSc@<g3->-AE@(^NLMW z8A!=rs(ru#tEIq&9<)Ek162n&?lLMCb>(BH^{iM=d!>xg7S>>PA%o$%?gvwK#UA29 zKM1}Bhh6V!WE^2R`lA)NgH!y+&eA2yb@b{>hJ{oq5*Fo)PtE)*6W!hfApStn0s<T6 zbu}+GD!IkU?&uO_$=y%3RFO--fQLQZlfVX9QdNI)i-Ek>$C)nH)Nydwdfr;&%5ix4 z8R(P3{nQsN&FT9#SPjW1yhi27s8Wu_XBjt33AP!M2wGKdc8<^u%ZcCug*p!c{~_St zaBY}`ZBe)ZmZo$UCcV20I|AY2cVD}5(O_OzI+v~vBiqklff}5htp+a9d_I9--&Gx5 z6F;=Zk`+xJlL}|Ko(j!I_!iUxU`0cqWgxTB*bNM6#49Jjn&6jr$`%O(iU0$HAOK8M z0CY}~X4FJ?9ezOs0A#C)|F|PK0v-jVY%H)6VD`QTQlPx+Cm{#dMvYe!*8*7pg~9<3 z#q0q1tRTLK94v?32H>I@06jnBUw@KI2Ot(NBm@7<gzcyjA1n}CG0?kqa<d8WRDu0r zxAY~TQAh?pt>tlv)xExB_^($liM>^*U*51Jygogvz&8<J?H)Y43;c!HBOf-%y@YR{ zzPMLwR2O$~YY8^r0%JFJCa6&EgPpKu{090}(a}s!^B<+DM=tF5qfg@hF>2VC2X>Gj z7K07|_3Cc{3z|5fpSJ-ZZbJ<8+x*wJn^p3@=RyIMfYI9A^()B1k@+=1?i{||{{RdD zSsbA88Z_3uJO^D;&g)rr2Ew)kc&`27*LPjNf4f<W11Rr9ra0heuI4oGjkpVf<&VJO zl+6h?e*?#^1~i<5=JWUtgMSE=XqHX>BY^$u^-E%@)%$HNc3zF~H`teNjH|x?lMk%i zSg-IfTU;F0L>UZ#z<AiaB;JUNz}p5Dv<90v1jPfU?6q{^<v!~38rgSQ)|t!_>3NnU zn=Ng^L0jSgJG9~@bj4GB1mQn&U;k&nK^yR*y!ev={AAp5{zi6{#ce}9bX^V>>y4H| zrpj*a0iEb3{|JP-R^iof0&3lWrGd@m@3rxIUc&Uh+G99ZTNLzjaW#nV>yZK7Gh&v5 zfaXpBPA;>Zjs8O*M^FzC?+ySaC?p2J|Kl!k3Bz4#U&3O%0h0q2UolAE?e>({k6A_? zetQqN1mPd}A75ODoq!NJ00D(s!kRiq=hdDu&*L7Rubp0zZ^63TGcbS@KM)o$#l~b? zhfWP@d*XCI$WH>ZSFzt%db`PaUQh{97%xpODDPQwJe(jUYYwYT?S66`yT&Xpi7FYN z+HpR!(ty>eWTN{7--+_2?;C=}auQZ$E$x|;ei(D|T?bZ8|GDPwCKJ$@UazaG4`Htd ze!Pyn6R(u-9C<Uh<kQVh1Ox=4&)8Bs={wgm;q{<yp}X>GZU`nDItw7y9LFM`YOsVG zEd9zED{H@OgEte*P!d=8DHc!-wA=tfrSTKypalwlmn+?Z4lVM1FJCxhmm;&ChNL9= zLg`@S%o*?fsnCzW*YVQ4=?-2HDuwk!J9-3WbD-aa<xZ5C_mx82htCab8(fFnE4Ctc zR_{<syx!R=yDIQY+0oj=wU4+xj3(@?<hX9Z(_(El<`45Wt>}8^x?<CEmR&C0y8A=5 zTw6`komUuU8{8M|yqfHoYj`={xy}phcwqU6k&1}UFg9Xe-QW%yv`RFd7fp`Ss(kaX zNrQX(Fh5%2L^H#b8=GeLa)~|y*UK{^apS@R;6+c*armAKHdKKw@v6B@tAA5uuiqE( z1Y(8cDMLRPdQarq%L9mc;Q8-7>;SI+KszWf&4Q!)jM)f0-u&4slW1+X={3Gos4Q`L zH|eVC`oy`yZNzkFM=*ZCfu=XWB))Sf$x>&sgdeJGrP~FHfziO6M55$~2SA_kGVQ3f zD0z`$wU2<shW`z&x}n1#rFl1vHs20C66YutpaJQ2Eo)f>LqcPnbeQ+$hxOW<b7Yz{ zY%CPao;=++oGTX9T9h-0=GVzca-!kY==R)+ij%N!Nb(q?b4*Hbd&2gUcwl0o5%aeC zI$8n{Fay_5z!R)i*BXWItQ+i^Ys@3ULRZ>qm75Lmp82K=f~j-7fwGRhbll@$?iT&m z@9k1gQ!#b33ipA46~s<5>UbTQ92)09v)WoD*?F|x9A(%cej)A0zHr9tHbq#NKRCka zWjbCfrXDcnu?MHe*`l6ca-tB&K?*#O$_=MLWSdhy)(`(cml`6{bBYa8nwPlPFf9u7 zC&|*Zm~WXrntMV75fQoTCik2+ej*F^AKS-Y{s^aVoSy%BT#QXaVF+sOKy5ldO0#{g zP00IpVduTo6=k1Em}>+4A%!K!vthKmSdZA}uWW34aRi9H?X(x-P)A#1y+q7UAjOSE zQpZIvjB`&_$9k*T(#}uw)GOEuiM#%>;BJ%TV8otj0&Rk{qy}tdI&d+1M_WWUn}F)F zc=#50=y-W#6^bzK*X?*d9M3ge{>HkNNa&?>guM8MZe&Y+Va_^l8=I5A$2&m&2*Oa1 z<@E+k%C*%JQHr<EXZuxsRg()C3-|%A=ZWZC&jmanxPTp$wP-j{i68Fcfdy9B<bvgG zRJr@KQbG=5t~D$5tL5(Jirg?MGKJMido^cL&*iU+&zm>{T!61s0z5f>6h=@fZ?Mi5 zmks2-bQbM@2#J{=fXIuNx_GJy7jX@$`=}pAM>s(it&>u9B|Hb&>t+zybBNsLzz-PU zL1`X%>{+7-pkKn>xc=Jd8m_=I_RX1cPvLRnPbm3E#8r&4O7_Nq5hI6gF(~zsmXAm^ zf4*&xpb7goZYkVA-wPfRr-l0>k4I361;&{L#AcJ_&i!Q<CBQEKh?4wFGjGL*>?xOb z35B`M?Sgcy_E4^<Ub{V8{uUz_{<oPN7U%W+;}Q<~mirXfhsiSCv($SfvBEPMPop$L zS63O3J`)sHt{?0fW0o03!Yj&wTlgE(K2OfKRuRU$>n$RT!WT%B!wKHhA+DSAFw~<d zHcD()2aug+)5VwoNng~u?ZN!}rF9o!jnp(-dR&9*_RTMYhx-g{BvEV)<k3*Ne4G+W zH?R&K%F2%t8mwxY%tJMX*QJpfsCY1&#IG){Sjb~2c`je<Js}Bg0-HY=3Vz2d8FGzD z{dm8q&|1sQ+l_z3!}C@ME0004gY9tD!v|^)BmW_gf+P}Kgf!JIO&4zJcq~rqZ$oFc z7F`ZjlH3bO$~lu~D`2#c#Kc|vP3)eUc#-y`ezLp+mrkChVW~6{JXLy^Pfk;_gH@6$ zx=2SJ6DN9rv8iEgyn2ZB@BfE@@*e^_SctiFU$~Fe2fb40qj~K%jpF9&8gUkWR4JJP zWM>sgI^<Ik&jbl3^<xoXgLNsv9N|%`3Rv*w%9FnIckn_BcIgDyminx^bd|&T*Rtgm z3)?3To%OrlQI<`xbU$!Q_f4UaB0m&Ii(@9RA>_RWA6+-%f}oPQ&K-hL#_jX<F}j*9 zGaEGtM6s@|U&}2EYQ``cBDYLvF&WUc1hqH;axyeAMi&(qslbjE*xZeU`WIs>yI~BK z8LBmCqJmc`gVjuSf^_GO{)O2N35yH6b+@QLnfGuUz6(~qW)IFw+3+?I?0HbC6|YId zr!l0psK4u?m8>{4kgho{?zI!u5ewS8Rn06L9xa~PLnsH)F_&q6&HK^1=qay$=%af+ zo5Cjc%g2m$Rw7Q)x=VVRP9A7teJs;PT$G6o8*ClkK{scyVJt}|Vu>CIhLTgSGB%%( zERPXYK3$$Oo+?dS_01+p_KO!<RZG*ShYwk7)UDB<X~Q;HOA#6EL=c=AcU1ABm05LN zhUtQ2?}&pxT=?W^_3#LT=@F$&a6)esze!QRY)dDOItpWj_3%d>birvPjw2~uj4_xN z_w*JCzr{bsqQiOx5WAD2c=tzS%r$N;zQ4A#m;x}Z6AR5aa4~);oxH0+;r_?_x+EDN zb?{6XW7hsFni}~DJ2(xQppp07@8Bc$+;{zW1*vbZZ&(tUWS~Oc2+8#4x$`Hh={4s! z=Wp|AW-@6S2L=Y#c-I|XAEy9em)+LvZ)pL05V#OO^<ICB<{7`-e*1Mv@sr6SeV<}J zz1(Cu;e^ZHJjU`)SeFFZYY%eQln==EGOG5h;TI2Ev?sOdKmXdlvm8dxAs?vX@7FIv zzl;_6vD?R1qf;h)hE&sx)h6!AHQ?$inE4f>sXoHV^|MwTbJEByr3im~17T9t<@((U zjJZrMU$1LRUpNvhq<ntN9K(dPogvbH3fZN}LJwd*&jc{w2eW0dt_2X|ev1i4i$25> z?7{M{k+%|qzOp$rP2hwzY0Bpu$&o^BUV}Wm&@`hAk1YkN9fKd9zJhsl`2vQ~%slzB z7fEgsm+tAtiBo)~@GdqrVWCm1NpB{%@h+ngmo-HZvU!Df#+R=osZ>e4h;Oo23D{DS zM`2<m+P8U?^ezoBHfVfUNgVYat0*=KL!wIssXn{vB!l>is!%t6_?VyA$2asvFyUja zaftLyVOmwUQSA?~{s{^!d5_I4?!+IJ1tSHzzSo&?h07cf9`;#2f5OG6c3wDn@OTJM zeUCe4Hu(w>-%Jft5Z-$iK!`d%%-M`P6cTlpi1MJso+>s@*?oQ#^~Rf%j<NtVWMs#W zUMjvlBb_qzFlv2*1xJKU+-!x>2F!gJZ*`MO1#fJ!)>k+y?#$>UQ&M++WZglg-wvdY zvQT{6VVO$eUMakw7}FUrEXK&J_*L#~UtX?oz1dt_(_~9yDY<VXxwW3pIXybj%jWly zh|~c3oz2(jQ5I4%N&2ZgMo6UfIAtH-%e;H2Xnuav;A1X*&C>7dy9VT%ky$F|(nt~1 z#0!*fe;PUu<B9Fb1Fuoz8NqsBx<!FCzQ*~(L9LW&4<Wswh^^D!-vi*${lk%~X2dDz z*ZJnkajY<&13#BdQ&Wvf9_U9pj^njPV!$1XEe;`YjBj#$aIG?xpy$&O%iia4T<CD5 zg`razCKhE9eAXGl%5<H9C+$vmnCLB4t!->-ncM*`D=z^b*IlV@0uBR`9!E-LLNzX& zgB7O=%><OE6)?P5Koj<_kxQ2A>eWw|SJ=T78`7K-o<xBkwX~}r<~Sv2?7VFBtm)1l z!Kkp4L<mgfBu)=FXe|yK@f$>W>IZx92Tbu5<++QN<RfU0iAU>W(s65IXgY}@d5LT~ zVlMrTdzrSXfju)Ju<x3kGrPp$-d=BuqKj2com(DPsuu9Cogn-5=CO^XeV+dL69{dx zdV12>^zkwgyT&k`PkbjQi8KlCS&fYhBTR!&^Sw&hWF&zYVd)-gb}YgZo!Aeju#aI= z$9JRPJu8nV-ut=)XGCR;jL7H}grY}Zi)9eUGc#F54GyvDh6D&fJO)5i^4jb0JB#~t zp3Xq3ug6wH3TGX7<)_7q#uv2_qd!+zO4*X)ON6)Ia0RGr#DzgJRc(YH{+I+S@f(?I z^QpA+TeV76(rc)S>de=I$6<Y}kFXm3$sarHba{a?2T9`a{&_>RSPq|NS@Sm1wIy?w zeKcubwQSFLtC&~vaJi(Y&z~)(lL=PeK{5!Hv;_*Hbm|(XIyjU)VAu6IDsFPtmSz{8 zFCI1dM<B}<+|6=L5uy9ECjP-<cG$}GwSETN?e76&l=!LFn<g_jK?Ak=X{e+V;)-_a zo4}nqSoPwI*P)O0TOWz0rEK*MjNDF~L{_*99?|a4=_jxcS0OF4QbPkkkko$0zQ(W) z(UE*}>;0PtCbLI>!iC*8!gZ-E%)#-s60|51-)sg}$d<S8o)YwGA1bh!YQhqhV|DsE zM^BS^QoqesRnOR~CCajGx;84Ku98n+;7=TJz!zqNAjG`|BlBPP=mqocBEbfgp~1<P zhUg^9KEvX(H!6N|E`~`6m3|`{#(;5(QvRm!_kO|hqE|2RBXEjx!8SI;AkLxi(_kmL zJZR%Qa%zsGpbfGl{dsXpB4HtN?4g3)=LddZ&Vf9z4Y5x<sX1hN)26>kLIamp>D&60 z#3)EL)c>MD<fG5|<8b%%m4cQ!l@abuw;O4NZ$&2q05K79eI>AeFLaC~{)UAaGIGNO z#}Hg?(TjOYExLl~1<TVKt#<W&`-=mju`;jTiS~DRus*r^fbARr;@-<W*DJ$TpQQF$ zGoWzhj-4BNMT-Ns6xdovx|~rfH&}k8wP9e7j8;zHhifwTUF%thmVe##K_wL5G1<1B z(@?NqLDF6y=o~FCS0^TVdb#jb{%#ZY)!L)#r<T!}xZ)8jXM~v#{Os22E;CY*tJ}AA z%q(eoU93x?1aAm2<9)qrK!Ve--8N~(N+Tx7KGycGK0)Dg{0p2{1!jD9XXOow_aQ(U zVQypXH1e4AM5w3wt@Wied-`t`>V)BPu1;A*XUsnYqzX@Q&(J)99TZwQSXX0Ik~E_^ z_FQuY(b&;|8oHtY*_!sokCS5N*@d<G8}ux@1U08#Xr9^J@3dR{w1`j5b8W#Vio{ZB z2fBLP+q=xpk;EiAxNfPvv8$~HGcGGXvMB3Iv-g@3e;>BBIKhgeyG{;ZafL5j@&wB> z<U+bX-m@4n`T6HhebaQ^T-uu>U)smH{K^zfudLGaUnZ2)3L4Pkc^;0kyr>ZE?bo>C z<vr;DgX!1OF_z^#wCSlWM@T2SQ==+o@l0$o{IxX?oeAxn<aDo2h_o7+F2Uk%aagiT zay6CD<3FgGk8QGf3@W;J`GsjbnLR!sCCKE|Q0GBsEOcF$?+S|4t5$U@x@@Jga+m79 znRcIQGR~PeJ7(`})ts#NjtN}MUCJHzf=ESvd}Ocd4LSrZTzW0V@L07~)y;^wO<Jj@ zryxB9J<DEfdA!o+>2gkg6&8a9LVwAqy4i^G(4g)ym`UVuubfV4!LqVLp5WeFBw)8G z(bTlU9(hN3&{T$;`Dbsz=aZcaD*QdND@!cLx?h(e)}Uy4fsMvR;l4JT=5(6^EA=$e zTqyA4;TS)EW|Na0XTt55v@%J`vK4YMq@>leK-t0c+>*wO<;vo0z4M}WhslUzSxb#D zb&B7;i#ggXb>qG<otM2_JUV53bK73NT=e55aT08jnp3G<Y8nQ;)4j@fk6G^kPxCDS zBOo#xWvm+7pl|U{s&Rv^TQQ{2#7d7No$!&kWd<ZcWpy$nn$ue&)Hu0WOnMZKGK*U} zUI!svQMElbH}M26)2?sLA%Rc*4bapLiHpjF1GmRo%<~O;Yt#>UoSeE#LY|R^ERA5T zH!$Z0S!Y73M;1|0VPd-SCv@*wV$IUxI1@BDPc#ZmP71-HKO7m(EXT9Bw6b+9<EQvK zMvD9e)M~Vp_x7;lh%<5uID@V8aEu37t|UfQRR%Jwqq`Cqn4q^a$*0OF;x(@(`4`tH z)x)Mwt1A|a-HOI+jyPJriXUK}Tk(|J#f7?e9<;*bYB6@+|Aia>ACQgFgG%eV+7+nn zCAg`P8ST0Bzc8C_H~fS!>Usx|NXCF)690YhVr0c8Dj4>v-9SJc`eV|Euu%5W_{>{D z8qmQ;gU)(@I(~^8|362+AG(*?uUTvlt*p&#%vkd)R7fWOFICG&iL5pMAI82rs;PbJ zHXc-vD!ocndhbPARHO????gemG-*Lf6s1U&u5_f=NbkLah;-?M-bttdLVWw&_g(dj z@7_1wKaP-?{My=kuQk_PbDeV>mj=DQhrm48Z&^P9_x=P0syODUAUULRR*JX<4^Fx! zIZ_UfN`wAE<po9k_a&3YIC{=>3W-NJQg$DP^Yn!i`_47ToBW3Pbg@DJ>N^83f^V=l zFo4!t0EG;oyW$Tx3yx}|k;5xbx&B>^t8lAtw;n#LfFzTTfzlIu=m80U8zH=aT~Y^G z!`q$neu9Rw7xMnDhyM*WnhsK38U5qKarwpM3F*KcnZxhE!YmB@(_Q>H@sj_*GPV9V z>(Yc!P^Tv4)TXj%pW}*k&0peH-8amI@15iTUs%ut=BU!5i7w{*lfVnwY(Ywl{sgU$ zIFDlOo4Vgiyl0adEZ$^ze0?nT9^ILbAJ6p$G9q~IbutVs?wu_j&+m-@_{IN5IO~l$ z@vcuF2oNY;rowXdKb&QL-ng>N1jtEf|GAuhl6OJw3#jDHpP<7{iA|gs^@PlGDkCt@ zPUqgC&)!ityutL?of!b+6A>7E+~9q3_-|~N^N$@cPy@s+PO8a}v{I=nVcfL`0slI3 z+^+hcJFAICU;`*|%>dm0z<xC!FZa(a$sH`2!Njl+J6gcz;q?cWc+P_}o2GMrl6FBg ze{3{BaQ-*uYsN=)<(mT1q(oS6ET{f`!t7abQObwLMb}+@`0tH%P}2iU-fZ&H2LS9d zl8_sCjg<fpr`)m);L_YN<x6O}C})P50qN@sgsqCNBDvs5zG28ZATGE+l|dr4gna;5 zTyoU;rWqNQt)2smg<M{UCHiD+Nmb2k=_{8|4c3bTt-_8(uS6&Sz)<_062Q9XfNyVP z;mApxaj+hMP_F=bfsx1E2dKkljAs)$7Mn>CdBKj?lM9vgpQ=&o%?iGH$qmP-xoe(b z0D`|Qp2nY`IAEslY90Y56by(LSm$q{Afc>k5n$3XE(3ng#pC_^bX5B3*t-l1SacK) z7Yae%oB)g}9DaKA<Qf7GK)JelF2b;b?jA#%H(LUy)+PkQI0*wuccPDg{-y~V>4yNH z{B-9#z8A`1DY6XsrzaT4wefQPhP#=D^!tpmF@_1XBH!J#AN?8eDxZZPoe>i%w-){N z;4%OO5BKFl<9E=Qiv!#|zGE}6cJSbrF-Nr*pM-T&1c|c+xqDlM%getI6M#dYzsH(% zMP;2-WA;(@Bg-lnYP2Fyc4!i_&!5h!HDp)U*mMxWPrhWN9Lje1FnGGb%aQda+0-j6 z0Ph5(`NB}nJwwxx%ets*yG?ts$X#X<h6Vk~T44qM;Xd9G)nHr3N3o4h3#?pkdRUYS z0sP04zRM~cKStmA8f<%6c4gYC8|mSg*XCe(^6oionu}pVa$5P5*;~cVEZ2BeVi-VY z`L&mzJ$LAI%SledMCOITF3<9rSFhSxnsBpY4}PiD8qgtER?TFrR4mozN!s4Qo>$V| z-j;rhQI03?x1G)e3l-Mb7!8N$FW;+3n0LjbSM-7?>lF>Iz8TFZ(fsqU|B$xOh5WX@ z?AXp}g|Ci|R6FJh+!>i$iq}9d-T&K3<4=OWkoA}uPc9<DD-ndM)h*;QWXMGvCHm%= z`<$GaNc-ODeqooRSnvIs2sb!QpXDJU<?)@GgW>0M8_`%R4A<W&p~Z!hyf@Aqv2A7c zn|a2V3wefwWWU?-dv_~@O$MKXH7`6mM`H$93s1GXB+^M5RXDnSg7BR9ns50Ue{X!Y zEPLJIl3@bFU*?!M+ns1Vq9F8m;u|tXIzD15Gdez=&G1LjHE#H0U-$)&|5revfeL0| zj>_xsi3(@t8E<Ab-jbvE?y*3ngq)L7=Swh29H(eQI371Cs=dEkR~x{Y6)IlU5`wpW zzkgvNT}hL?{KddKWUO@++i|hzbTE%rZ01f5K@Hb8(J{LV6}G|t&!wYoX)Ot`4=5P1 zIT_WaD&~_9ef`V48+!IB%M5ODDWdMH7qxX}s+6hXc|MrQ&OzxV1dtX;yFR&ujys<W zuObVX7o5aG-Qf9#KRUAJ)JRhbSibW67TK;usitPx1y(OR^13Sa5vp*E{REYf?be|2 z7uP$TnSG4_(Q`5+O%>X!%PU$we_^Ko<lHM{uS1<FDZgBqr7q?GufQs!>@7nA>S;}q zgF^vyLWc4JA4?X6yRn^xu{r4mE~w9#Pe8(vcq{SMak-OEG7nqB_%uQD*WKH-PX<N0 zWbUvgI<eFe)iMC&5P*l5h&+8OM~#8t2#L_NI%t88Ci!+|28J9&@Q#ea+J+R#yCIRw zAkO1_jx^y-H<4Mcl&kf%b+BpPZu|u_2OTQc>w|@h<c})VRMoMJEP?~QwF2%BxjFRr zRKs)VULHJPjkBIftk6VbC&PVZ1`e>EMyd@bAGr@tT;u8cxm7FCR9PB^FugGC2tqIC zgg7o${%_@3+K~o3;H8#uphIsBmg*|T0Y?~t_E8-{c&KyBs<krc?H=bejpv{eIEO1; zJ!7(8@{JdSI#9DK?`b0$=AH*E${+Kdcukuf&%Z62vy0hcFuUwdF9dK{`|Dd1(gWVc zL?O#@pGDp!-J|3UnbN7dxvE5o(loz}_l5b|T|DzO#-zfMW^v5JrH!=61!j!gvN~!P z7ic|6t6iGzB}K%ieXw*(RkPyJj=*w5dHQu8JDcjL;arRWYM~WM)F_J%USzI!YG%aL z7>-po{WUSF9jY#&R$rc^oE<v(6@IUIlvnB<@)^a0Fcr4h2*^GpLN0nr17AFgc#<p_ z1_)qo7TTv|s$xTRBBZltRB~6wb2rEBHPwb9n;EQUZ59=nMT_Hv=(r<PLt|q;r`T~H zJp<d2DtFsWR%XvqS=Z_2adv!@V{w2|`_tMVVD&IIC8Dpy=95X2(b6gn<-j9MqiOhA zL*$0Kk0n#@r018VrF+YPk8?-PcVaAzEa8Qa7XpmF4==OfHVsgs8O%_tmjOd*QO?%< zjme{Zd=;2uUJz`LrLkr%U(j#(dbkv`_9EhI`AuKvb{y-t%$+432<67ePF;Dek>!9O zNo4+vGMk~5a&IrISE&JT@q@88i*c2sSP7c+#f2Lfi=QBMb>rn$IN7t<j(N)3I(St{ z^c7^%mVsKrh2BUMFK<HO2L;i=sJEyd$+opx22mabKL;Y#Eb;MG_3FhWulUWOIdyYx zig2g^_uAP))?}!RUaAY(c}-B4PM!|$Nu=C_Xm+7?XYELC&h8zqD#gZ(6y2CquI|t{ za7Byjg|q{-YN)+s8ovudgyZ)gF$bKOcQfW;7it}H{OG*)?S?8e%_r&<b6@d9AqN-k zs>*?S69X-QgreIvA$e2S<z?V`={ya7h{^Fmw!F(z#{@er-Ll{6=`u(s@`ZRKc^u5_ z$8Xo233w3AJ?vgx3DHQrNye8xFyI|%j_`HCNCWbMK&Ajkk5TG@R<a|O;kygeTg;pz z+5-<v9LZG6Do1i}n$moUkxnU@Tm76Jum=%h@Ai7bqK`J%eS;)>N6SodnF6=pC&0M1 zCI!F4DzF!^t#_zP8Trb3JU@|8Ei-u(I%;fYeYh418z)P!qVUJj&72rh3m4~!<Ays6 zon)fx;SIr}IsxS=&)8G4$UIYG-Qo~djNsujR<|_4yx`8KEJ_lC`OkPJ@&W^yjXl_c z1MNi}boB%=uSPSaj`SFQa4M#=9(&NxxMp#{9)cs9Z!*9;79t>cG9Jk7+G6Xp5xX6W zu}U9l&-zaRYK7AS!c8k9G8MhnLIH;sl1uUw;%h~@hTFzg-y#ay)@ICFQL{?5rAJoW z9k&C7Z>+eP$L9I^VU#YEFp)eYUMKHRZg$;ELeG#Sl-(yKUVMGeIb*9D8!mc6#v{?< zlkIgOsQMI!=LSTs8Qc2xX~`bMUdH+bmM*ameC)Vy+)2B4Gu|CGWhfj&Aj5!jLCf=% zFm0kqZ)I<*sG3GhQ!}h-2se1fRK_|sY!C9x;z-UFhr8q>?a)?))GoCtkLtEnv<noI zI=fB#-Pyzo=O?rqE!p%_*6GKzb^N{2@=G<{>F*#wO9eSPjDg7{2P&c}GUD@QeM>~l z$o#}S(V1_ZHp#<B%3rzO^I7@Cgx#!von=x|y`736hqtL7fv@_?LP&97EKk7H?yhAy zYFVX_aa-DtuM+dTqTaLpvaEcGBj}z?uCAR$<0l4**o;wk&A@2;S9u}6en@As`gxeY zqqN?5l@A@M`~IiZ>Leq4tdGQ3V{x_{E0I;mc}V)nT?{nSp@n!4Yvx;TwH{sUD}p)= z5`|RTRr5Z#Zh=*i?cR`y_7F{$8(5v0xf4i#Q$)oDk|9YJD(UmSoWPpC(rRz4NsmOp zSe0sTqGrvvBAk}HF|V{7xNVm={)H9^_WuA&VOQ&vk(N=n7tWJ9w!5dD2PN10-Z4Zi z_TV8!300<cG0#1>c382lm4<7))HJ-Jr=ukdLL_5W;`<nrgSL0%AJDBZlkNaSw1?h4 z{StnLQt)D;p{VHR8<8$3&ANH#fg4}_khE%P+a>M&<mHEeq``Dg2tsTZs@WL2jH4j( z)9ABtyek;}k=iP9o`vU=Oly~J23ZaMUy6CC>E)%Mf>OgRAcreQ03)4|ADzIBdq8i( zqW3FYmXxRW`WG}q$(^>{*^{<zJQtp&XP}f(coco~O4MHt({}yKPteU~wl+6p2QT@I z5eA~HPBG43!d{)mGecB+YM-!n&k<$1CG!5c@RuLSmdq1`^o0X<lUc-~ddhBUr%=57 zRalW;tWINH{Ct9n7(s1GqduC0B{Rj9*L8ez$yQZN@JH?URPJN0hgDLw+;p$Zhi(vR zG~V6ReP<Jv#+}PTJa*>dE~N3q-e9`92`NkY0HcoF-UqtV86~aJ%UI=Z`dDzrd}W?g zKhTSt9avSxSqo9%zo37h+nWvq7v#QT$d8TqD2Efjnvs%XOWR6EGJ`p>W9$PK;y!0e zg7&k+{1}@$f!Bkpy$5$|gity<=$>{yT0@LY?nc6NO{X&*rbuVv4u$FnZ~tSLp^}9! zo#{4q%aWd*H6*X!#%yo3ka`HbX{ji|W%vtXUySTvAG^~x$`@=kv&LK2PZ-Zd6Y**x zL%WOjsf!8s`mVkweku5BbLb^@k}$i-qM(+`Oi?uVvSej^<+8}P=9E9laUovuz+t&! zHY)(b(sd8zuNl826t`(%`elo*K7MQ2W=LzvP3BSllRPb*%!hgak}yAQdbF*TshFzz zaeAyGsY4638kn1kFw^w*CQ0GSH|xonRg7?3jS>Z+@3i{0-YWVaQuT^Z!&kOwZq|;O za}?op<ntpV*myL<AP}+B*ex>s=`Wi1R#EPXk2>;SYQ?{PRsrdBg!lMguSJXPcQnD< zt0Np8_{tsl?AS{Rhj`>glvoK9iJmvK&u|$5iRoE-nWo`FYb6hhdCu`82S3GWpVYhS zI}F)^8l@A7TGH=tf57{=qSL|hEDm*F3|rL0bSni#>YyavI*>r>6`l#78;h(S?ql6c zab};cf0Y}x{zB2{gUkBK5arXCo9*#+yTM%}CGsTtlC#%5g4WMdRZYkAUfn2tHLRHw zm&4VqZU<BW<%{lP9`4}CedW-R$)7)3By}i^I9jOr2oRdgOf!DkPaE#pPv{?kRtjHX z4KD$I9H6WmXom%XZ}`$(rtjg1O%)K^^$Vf5n}->@1hS{>zSv6*&c%fJZ09Bzu12#a zDJsrTorYIa##Bhe^IkS5x+L8i-$UeVXbt6?P4^I~5Cq*@C;!C2+1O`9c_k;-`QujT za|`8b6@dI&vkWZ0nQa;dSHw8_<@Eva``7ZGB{E^IyimJUcOSYpotiF>J!2(pY9r*n zetn|I`U&o|7=9tKEE9ww9J3n_Yci~rvtsjH_0Sga?W>_CGB*}qr5PH>GWVban8y<& zu65KVjRH9yCzZ9EDQLQB-OWZe=^--0=6-5wB_*O87AcEpO82^g@9(N0RwhwlKz&B@ zEn{G(7J`&fUuj-hY|pcX>hsum+zJ;jwX(?WjSwX)BpsoP4dTG-6&ti!Vms|=QtIJB z8$2Gjn23?)vossa8rAP|hdsNn|6w=b?;AT~0?*EfW{aPYcV3@mo1XiSir>}r*lyCM z%@y|PXpZ{Rs@)PLQL6f*zi1npExz$P8Pi;dx_sRw2=CuvXMf}z0e2>w;q(<v8)!|V z#dzaYRZ`5sJf#aP9orvjO&^`@iqL+bKdgHEj{mu}Fx5FWjM{*wH-D+jFjSONN-*Lw ztUml{oUv-rDS}Z^NL6@c-0fun++yUb@Xlygcn@QeRXK1s<_JcF7wDuuf!SHmFy|2H z2EOtiNwrlR+wAzES`83zxyDa4{JSooSkv#mM2lc@tZXf?MKTIY4IBQGOgL^#k)?wd z+#8StFByyS@N(dM;>hx$kWTw<F^hIr8+HJbg$g?fz;rA#Mlr$`deTYu_}8?URDObp ziaM<LkkC2`=dn-K;c12yLcDulcfR_r15P9Ai?833!vY<qN5@ZIXN+BVZf;0;&$Al@ zddmI!uRsuYKERiw2B0>AAOQN2u>@d`&n;J%<hTYa_Gh{BzlW`9sj8?NmwIz(>&F@! zNwda`&ub13Y_59ylNx%<D3}A`Uw<x3YCl4Nr(j<vk;k>t{Z)?ly)n0x%W8qCsHOYw zm9VTplZ=g@prktF5Kc1>-XZL(1a#qwMegHn4UxhR{Jga>MT!xR9Hp%k$@T`pe}ET# z2TSlz@I`^2pctv9QUL0bvxhGN=;uM!I2`#&js?IO`%tGpL8R-!kTbbD5}OlUOgejs z>s>&V_sex_7O!q7@!QGoTlCZb<+0u5GkmB6P{ph;GDu?{JC?2!V^sd$C7l?a2>Rg7 zq&4s!XY~{Gx&@~!`;Vaj+ES3#-*rdwnjKKA3=Tk?RsnI*eh3w0!wv%!u>_}gfU#wz zEPsGdU{r_${IDBxan8Bg`4c1zlwtxjRaWLnb^u%wgP@+n&$M=!=`Ry;Z1PzOjF@EP z)a@EBG`!=5R2op;K@G>z$1XuGiPOp8s6Ck5Pf+Z3pXjc}P{)Zw&XzXyCt)K!6{eI( zrLuyS-zY{_A|)1}1Ydz;Klqp?<9vZYxh)!)tP&8#{jW`bnN9__MubW+zs-lOuA_2J z(ldW3xfb0bTOy6fA95y|?Qtrn<8xYx%S)BvG`s`q6;^op2ZlB2hDs1egFB+aC8W%6 zL6FAAT?x|u&z2m?8!mJQm$<TL6E<I*SGIiI=+NmGa*LN7%}-}tNv{l>5R8kTEH^MP z-m2V+qW=s4gug+wzhU0rc37`@vu+XE;&!CDZARjD{t!&$9aVfYz?a~}cdFZMbc=ic z7fL94CC^As1OOi;0gm%FHUfg9n4`q`gK?Khh{E|9Ov2;^M8)qQm{gu53y-DXJQTE+ zUjo5A5^FhI247xM!T-P#GYI~He6P7*(p)@hRM&Z;VEC-h)8J}&I4OP|bshk_I=u%- zxMYCd>mbN(j3E*G)(Nsb2PlV7>H>@Ug>2>yEy;49<CoWb3Xi=LDflG3j1F9oL8=`J z;L-2o0m^rp5MYzTN`F9MUrR6L7S9bh{;?g^!C|6$jE{Gtd(JEFGq~&9{9Zl$w`t#J zng@uzcYF}%82Flf)eCc&m(Eye_86a~Jk{QFz|!MoBDn>Aul&j<v*5s%6+C<_5kPtt z3;f5BRic;r0}m?Hd9*(i58J#djJd}Om>kuW3Izb$|8+Gf{hr8`#AW!|4dA|G4g_}( z?Ym2M&A&NQeyf?jPsYHJ(DiNMBZbcex!#|+>2<3=;BVcQ-^QS~dkc=FrnvR=-648) z=d7aU-sUmYm6rcHG&lmjax?uH)pAZ`z-Pu@<c0sfL@_<P`Ao0#o#eFmYbBjM1)F~y zG;#lT6apKZaSp+~2CkJ~n?fy@oHf58@xI8OvxxZqzLkq|FSjJ~3efxQzYgyFPvm>M zs1{9=m~Ybe%u$4%BO)uDiiNiW?^p~VrT$^yuQ`E&zMk0@Ksh2+N&Ao2_pf;-;bY&F zv}}JU<!?~O!`+`)IPQIN?Qgw_dk_HJ@3jIj^$9b3SPM>`52!krDBl2;#<u<hq1Pdo z9^n4E`b`<YFqwfH$D|fEAMfSg^#PDSlqpJMd%);T=YN6Zglik15-2{r*Ah1+aa3G5 zj`G3=L3U%|s-UgEY4LeWfNt_E@Jo;_p0LtUK$7_yAVX0KA2Xo6e@zW|WPky$9uO<` zp#I|z_bYS53REBifU&6I91f{Kbebt4Pu`<1kO^h^ny9|Kit#E(W|OCHRcptd7%o87 zyk#5pH?Qp;>H9l;rI54=U!w^X;pmMY#&rVB0iZ+DLn91F7eiM>-aFhK8FOlM+4!-J z<+IClS8wOLnjTU`qAn(8ZFaA^Tr_{Q_FkRbWTryLVK~C=EOOZM$2B4hXvX5D613x9 zOg4evLzNutd`ce=;JqC@NKrHkPYPrhc1cN2dZM{IpR8kA-_U-bdZNDJ{}DIUQjOm_ zL<w7H1#aPOqH>IWv7HPjktD$(FMN5}Q{e^M25uoaBc0a?khM2M+FmlR52mdVSn`3V z^_>K|(kp8KcgU`Ve99LebA}$ekFSFA%sjbB-lrA8m;+KCH5Dee<T#hYwEg71=|<A8 zChYxaXTQ*EpXrbZm{2PPIwvv5qePH!Ao$w^aJ}>pcRm)wrpaRnF-N2ag497@Tnak< z;;XtHqY*EqaY9Y`sD-0Ad?$-JS?0r|>lY1na$J`g@Ws#RH!An3reM$$OAI6@odm|; zzX!S2SGr;BI9EJf@^xa{uV}$|?nk|S&=LWw;fUdG!mNtJ>I3{K@xjZ1G}rWCe`cLX zGKx8=%CV+Y?*iRawL^y+`G*?Z#zv#zccjOLyU7#ReOcnIr%27z$N~fH#lGmVG5C+@ zWoPO=`1T}DNHC5=-A6ZXkeVxxUPnvA5eGby+N4`-A;D0_mZ$sl{{3)59AgJr;1Psj z1_M=W@Y%MTzIfaeJ_z>~OUv|<nTT>J+p5UELr-o){%DfS!9#FM#sE17U0e^Y3=wU4 zkCR1RmKH5HJVJv5kIeL~N3nYT9Is8G>h^=x`Y{vKjh+$XmOu0cKC<eZSzS=W+kh;O z1L8fjvO68Q5ZY3e7`d~ALC6LNA1~arJ)G-v%bQiX75`2urzt0Ouv``uG%`I`N)V$% zsocdLYYWLZU+);ga9z1f7ImKHS@PN?$+l0t=}<Ggl_(|mzIuAC+l|TdP4RAK^=qJi zS<o)W2iDbN>QLoOTa!U7lz*t4ACedLRj`nXOTUv-Bf>~EM@6-m#rvM5ln2W_MeX?M z)zox>#;7dRHzA}mHT+A3)JLyGn>Z`Q5~=9$Le(14$-Nxud!z0-40>EDD&m`i1yil( zw2vlUc<jnRf0#bFZDbYTQQaJ{`Yer$fh$wkq%m5ghg-(6Y)YO5q`^~wf<^!yr}j5L zJS5p`8McC^-LHvBMX<M~wWCwX1EFlU+w3Icb``Wu?5^mNbnKng?3|(16fuJ++K1@) zv@B=0d_z;yjrzuuL+Q&x6YUJs>gDRY7rlme7nq*(T(|OOR!{>vj{EX(M9KkmCpUxU z>C?4F)&it`infzs9M%u7y2%!0x6?=({Uyj7KG4ewUY2~e1@l-kMZx0j-M4Dhl5u`2 zQ!2ZKVcJ!bjm6Wz?OCw4CTIhuvg|K$J6?}h4otCmXbx{pi7V(=rM4YNqguVupIm~^ zP_~j1|7i_OjM#J63^Rsz!9%98a<@>>uw8yYs~7(*@w8uVs?DvHeI~`t1fHStLAI}n z(ruCWhkSH*dv4Bbq?39erj~Xv-G`cJ^I+sYk)4+_(u~KvY-0CrmBd}jb=juLqye#k zYbw6S{4t$;jBYZ*SH&Pxmgbm4R9a8R0+0^2gHpp{=2!T(Mg1v<kH+}r>CEmVw5?Z1 zYqj3)Wt1L&t#7-PvmR7QHq~<CQ5JPlfsxMKmLowqHq8YGHX3Ew(wqtoy4COPbjTL> z(bv?~h5($M8KROAB{vT*86lF*%d|r#Rw|b&4(^z^xO)Y*No$S9;c-@65_@J{(y}@g zFL8a}YSY0>P}0#ns9+IPyi?8?W-4Z<qla>L)w5D<;+5kLx~1RkqkO5aQ=Dm>%S>qA z@1%EcvK>+lZoiOap8>KV-JO-_pscK|Sa~2rOJhppa|zMHd*OL1Ana^n_t=0q{HroS z3_UyP*La{g%(Y<|vTRdK<g;8mh;3t#cx9PxP36M_g3o$S3K<N%$-SP^u<4S;E5L%@ zqAlCyMA2qFoda+JhXrzeU(E~?62^`s*YdH<ii-NgU7Di&5St_tu9}Rn{!cN=xB=Et z#V9`abItZ4I!M$DEHob@-OhZ2mL}|0Vz3MZ{>m9a{#ow1m$0$QRqorLmOoWzqx)7_ zoxY~19bg}Hcni?Dlz2b<99BXYPkCx;rZ`)W-z`%f7Tj>dNNjIzisjq#JRuUhFK#N7 zYH6+&+SP5CVro!cB0r<&j@EAf-oZV#^)xf+w7D!Kh{8RwB31btoqm2Z`qq*wtCL>b zs*whPT;&3@?|lplYT;qkB#xsbGrdbHyx#b(E!eSXEVqt4xaPp|j-6H5bDA#+oCYsE zi&$u%3pnVGvIDZ1eWGu0_aD7+VO*e>To)U_Adp=>VSCS=Z(u^nh_=p)$?cNTLw7_& zR>l=SvI@(VRJGkHnfjPoerucF(<S)?h)#qsZb?g$YT*+`QT8eJ>N?5syEmZmnsXZG z;-!_Y@%xq-=hv{X8*$cRE{0z{?CFR#c^w8wBvd`Py6si@^U6xJMQ2nsxFgj11>*|T z+qqy$0sc||!dJ1I*clZBxz$L%95%<*sKwrdtZft{RCD&Wbg3{^w~<B0g>kYjIIwSI zdCIeWcjxUCfTAo<wt$?tEg8cU%yS+2&Yv80)gXd7G0#?i2wnmU*pk-AQ&mY)enwu{ zZ{tnFdFQ=ljnQhjayj@BCK}QvD}ltNq7dElS0|52<V{ht^+9it>A~pBbkoKJhc~n{ zw`<8O#cwiBQmFg5v{SI88miqnNbmM%1Rf`{G7oGrws6E~j!pq0Be(@$({XN@m7`<9 zR2T1;>y4G;CC<$%azjjZGB2gt#pkluuUG~xTrl!>TN$kr`>1YF6{(8W*{i4zhf_Tx zjMYW*^yf8L@3YZM@Oj@OJC+WE&9pKt^9&ZD&DGVeg%?3-Hrumc>5jYh9Yn{yIvI7b z2yI=z9DC86Fx|N2Km?bTPR?{*`+g9#5-}xarq)KXyg)g(F~FR+<jB5{<7#kt7qJrh z?c3h-wo0SMUOdANk=z^g*R{K<;Wj`e5QpM;<wqQs($Xis9mJ&S7%x`u+F;tg5Fc)M zwYb0H;hjjePmlGh_ucmjt$dPOzn4_I*MO_iL$S9U@?avJ`%7xF%6%{DPqL6iKJ-rE zY&OAKl@Zp~m5K-BF-uP)i%a$C22A?>-gZK&ih%$cM`601PD``@7}NCXgWWvouqg8S z=NGAS0dq6P@=^&=F3&@SSmm@RUbx<E9c<(Egir@HU&+m3tz#~|Q1p%DmMJhF39Y;x zzcdr^6U2vF=S1({YOVd+@cQu6QeD~0%&_*+&i*HD!@0Qy_eQ%E<LSCvSU2-W+O=Tz zRGh<|1EhIeADIPEUR~fRkuGhFW*eN&SAMAp&oq?tczf_ZS2Id)Mb7jyv}(?b#vNi6 zv-&9$TA}(uk>cKu9@Cb$jdrMm;iq4|%eYLQ>^}{!Ny;rfRMx)T>>#4LP)|_K8~IT$ z;%W@_BNcjBgiWjeZOp|o0^ipf4Q^lH!$Lmy6~fH<Ud^jyjX3SCR_j`ZnOK;!R>yeA zuS=`A1}FTGw^!SdyREQXM6_!^(xYF6T0IS67&VyiP+=y4=&R`T8aV|vGVW!HyO|Q) znUYewm0@%DktWZ|AvP#Tgd;1_f+Eg_M`J?8e-ClDT$Ovme8_C13dh3h%t7f=?HuEJ z?cTRi<~Z9W%eMu=dGga8jEWNL{v&A|)ROfS33pYbYCJdyR52kwq^bFv=iTYo5!uiV z4?7RSK?e^<PS{$+Yby^cR^bm1uDU!x2wi3$ZG*4D!~v>eZeU*9waezt+PW|eBWqWd zLJBKyJjK@`Weh>#a;6!=YHV7-#r8KzhyZJ8h4Sgd@eRvJla>^AWMSkLle!l)1oHXn zMZbqE$(cHfMl_o2B`8}*BNJ?5lzqRgFFQy0lVfEtDobEmtoPVa5%l`>rgjv$9MG|J zTFr*p<RO~cS^Dcd%gsRR=#;xfG=%Vv-W71-+G^d6fiwYi0c!oYB+u#1O`E(1$*O%I zkO>zua;AVuF9FgBO8PE^bE27pgz+01zUA3tU{QMsu$6v{b3(C|hN^3Q;wtU#`h_R# z?V{K24UP`*J8g`c!FZ*iXeK0l_v2QQQ%Q?@RgA1Eo=gnejB+`5u*ZQhfyGyik+1vc z@!j3E9B=-t{J8<y&V$O>A<@8jCCdbB%RYdhC=+A9uzT+(h%Hzi$jNvure7*n)(;^v zdu*mky&ncoY~AB_RprUni{Gg>m}>^Eoo6CjRov@_X?EiA#t|IsW8S$l<xc%48tM-0 z2%e^gp_~ZO1Jdix$0ay)?kK>>GG5qca0F4$*tQ%H0L5OVMA)MDr85cudZAEr=>lE7 zPxE&n^#8LOd>U>IK4Wd6gX}y4V7sy4M+h2(-Q`F4N(}ZXz>c6;_zBX!Me(H*PV%Y; z5WrW;i~9*`Qo}Wk{{)Td+_UHWTqDzg-viw$X_<#_n(n%rOZ^1tIpPk1|GRDr`bU9y zIS;fAen101Uxa_mAk75=NkV1-#QH$pb5R7Kc!bMEWoQZP>r%)Z^pe2f*8OXmIq+WX z8C)~v-$m5__>1bw?7w0{&`*%>r9(^U72MhR_rJ6hsIJUxf)8#0dx3DrJuDt~WWhZU zUpU@N@6}5J@q9o-vBA0L9Jl};#2>}u8N^#aG%WS6if?Ysa}4C1aH7i+!-0FC4WDcS zfI<CgPEaw~Ex!RMFwdQ;7DHyKi-Z;fpjntLUfSnSPCUyt$N_aMu4xGOu4>Fc04Ovk z1mJV?bzt7cTflb#{eOTExC~UPGfV{9V6t%cCBQ(`@O|R7<T)@juPuN>(g0u!0@&Q| zfnL-d0LJ;}8&p@ihd$end^_mL>+k=j`o%mW$>!ub@P+$RE&HK6j=$O<Wsve*;28sy zxfctkUGA^Uvz}SzbpYc3OfS1%%Q*eu_9L+~pap_(Vn8Gnh{@qKqJY{e0A%_NU)E&- zV=IC$_G$|`@ob>w_2V9t-np%#olmZ?TC%W|XyIBXS~eIZF41OW?;tCL|H2yVpWstp zzA1r!7k9o`s`eG%{5;b~Q`kP2+NKb<7#&$vXSxsxS>7W%UxTNDUi<_(0V_Qs55`?& zUAQR$(+r24&bjJ7!B<++H?t?m8Zk5#by5qdYrR|c6ZAz4aejReIAHz6H$OqkOUsvC zIO}>T&{E5<PxSW5re-&#f~Suq83?M$n;*Q11rjp@=wR#{O+ayS`##NoU190C2P5O9 zl!G)+c7hS*4F+*FrpbH1mXi8Mrz7_(UGS$4&?Ay$9HxNJ-OQNr<61(yp00~gC<-L& zP?o<3%x(mFzOvB!{VHT8337QAKzN%sA-^_vl3D@e+48SXo&le1Cnm~|uf%7oOKBH( z2GHgg>dnsp=uIPhk8JfmJ+ly6q7wn;PbCXwORyD<5GNuL{x&}%?c-x;5qOvJ&U<|^ zPx2y_+h&K#=0-*<UY?!552l2=<kc}+%uIFUW$aw_%&?LD@vz;7>AF<pp<@$GQ%pIO zHO4F<$TPXX?nM9QwAs88Q&~6laPl?HOvI0&De!XQuE&KBmJW3})J_(8u!$oZ!%7s| zwlIqV3gQfYrzf&|i7!s|Pm}y|21k}0FvgtGFD$A8roKBW+CF-Vh5*3yhw-6HPq7m) z_GZIL(s#M5xan#*sT?b8S>wA5z#04wbLgB7%E{qtH~GZG=&je^@}XTb(KXWchqAVE zdrLCVPr{}%9tIEbmQArCM7vJ|a&_!Ud6Ic2NcI#4FYSuTW_sUs$|ou1p;f5O!lUuc ze!&P8MOCf%<s08ptS@J}RI@D^La7;>M59Kep|`La7!njmM>8pEtqKV!x4gO@alIwW z+@apb#PohyWwhy3SfWLl>Emq=8>VIxT8H6E<b>3@(*)9K*Rnx5S0O<V$$uM`{Y25F zcTrfP@XJ+Zg6oZxC!4jGu{aVHaBBqNdZ)iocmpQLyE0Y3f1uwayDHjK{X`|<>9GG1 z0ZZt$5XBY|7U3gsSxrQvLaDD%1u8LAbSlA7M7g5wOS2t|?cNI;5duMd1B>kysV{f* zV4BS_cm144C<8LXk){H)&oVi4IBvLM-SY04Q;yd`yc-tc{n4VSb1mfOb{I3{IyuZS z5tG+itMaTs<7EQ3*jZLc5%;kp_ks5M31Yfm<}go8MWZNAw<$a26<NqR?d~)0f-P+< zJ0`Y36S>J!RS!J0?R)e`i}!J}vB13}zrJC#l-M(q@2>URuX=8L?a|eCmWlm<th(ii za|>Fr=t2f7i}5Mg1XIi1PEM8YdesuTnB2(_8Tg{vYHl23ms5YCKG!e$Ms9#bdO*^~ zBZe<)143^Eo76+);G$5cT|&0?B`bG%{1k0Zd7suN(ld1%J<z({7yiYiq{i+LOpS5Y z!aQ4&Cc6eq(g!I^v~;bnY0?q#;#zlc6hWmezY~HbVETHs4I2%Oa*k3ov3*!AK%%o0 zoONv%Eyt>JN(4Cxmxn{SSL19TFMT(=#JD&wG(8$}M<LSZ5Lij)SuQQ<rp0D)4+&xA z#zVRS;6e8$C_LX%ghRXKOV=}0Oh77wE-JoAqe_B%^ht!2VW{zb&~uDt_EtIr-1;Yo z1XG0UPS3H^W?V(fM#OBqY82<<?u<2_HDf!Xm{pE`6#K&HMxy87sPZ~3aC5B!NT|+e z1dd{#%71VkJj^Rr!Y)}N2B9&6hVbQt8ZB2<_^D2OQ>=!HFDccAJ|O48EAa6Y>Z64( zmB3Ypk4&OM7nqL9mcYz*+p@uL-TmZd`*NE<$Ch_6$GqWxIIqU5YFIz$8AMN(@THpt ztgrzk0z@zvk>>FZOGLM<*Uolnwieo%seK}xl*3CzW0d4_?y^2Xd=w8L&sK;ho6^#K z1X1kK<UpSBigBw_C9SSzm(au-D@>b}aCHl+Tnr?bmO~vseqWBf*<a>?i4A17`&f^- zA){xYrE2J*qFdP9q&IGenKpzyta_zaU}3SP)A2o!8``{D<sc9u#~B2ngB5i%SdCX~ zqSdnP{25W>&FQ&0WubT0yLYVXYX!dat*Lo%r>@&lhnYpJzef0j2Y{T&P`kient9NK z6YsS~Dg9tXU3KWVQvAuB#`0ifx6ed$jyPJ0;!Nn<-eTWMh-AY}*5MuJNgcH^Z|m6i zH2q6+ae}=Dp=+Eg5v|=T&#$SpfdcRkHN%-84?U2nixy`L;oP>d+Qy2S@%{XpFYDZV z200pD;PlQPVc>}_`d-1QOzOs%(8^_Q+(ZPiRPIWNDj){$t+SGMy-;(i%`K0X?wi;h zFl8AAvOE;Xd}q80J~h)V6%;65WaCr3RXvI^=IK3lR8&c`so_86x>(Y<Yf1Q-=bCrx z>;okH##T)l-*_W6I@zSm9SsfT^XRG=kr8olba+;z{v2gyqU6AOKr|kED%2x3-gr<; z!l}%WW~W)L=E0t(n8yID&TM|3mDq++voEsAMR9~w*Dd_*5~Ru?ywQWN+z@KCW&Rh? z=XP;?5383YyTeeD^D&9XtGeRA?0LPHL+^w(3#?=WDZ$d)*>)Zk<g1tBYCtmD-k-y< zbGP7|Tvxx7kgA}Q>1O|?fNP8OO45_2=u0u=e$>6Z&`&si?S9!DUv&;94S}S0W$ty^ zNDV6X^3!_<+Ie70Mf(<s7R5v{<KaxXh9##g%Y1vg#Ryu1NvvA2nH|E<+flr#+Na@B zt%H(~p>xnIw`v6A&?=`=6yf7D7^cajm05DEQQ?`Z-;xIgo-;jDvJiH6Sj-`0HA*F6 zo-Vg$?76NwdccMMog-oQmtv>KHNwRtwDc(Z0i-}sC6ourhX|`IA(XYJZHmXL6#TFo zsZ2^TdB1w#6h85N(D_>HA^*sP?SOH)yo}F@+X9onfG;U(djV^Swh5CF6KgKZgWA)| zaVMNFjSzVzC@%)h_s-Adte%WjPk^n$oraYszK39ItHI4({iQUO>!GDteb-|O9vA~o z@8n6WojTiaSC_(E7jB?khAptyzv5x=B&QVJtC%dsCVTU#y4q3Kl}vhM{>xJPxJ~VM zd5SPwtq9I`jqoP2r2^FP#Cwm$sHqO+nvr9N&lL{-cgn_g6ZQ@aOIGVXAvDw28m9j0 zA6)-LL==>!$l{f_2B&I<bfI+G8LV<jGqdcH)&rLl<%91xpu2;gdAa)8<o@W~LU_1S zOvtm`P_xRdF^X{vdKeA#;i*)@Qm3^Kb)aBGClFNJwAfy{2d^_)TCYZL?3j)MZ4;nZ z<MoNJ6i=ykR&lG#$x89zOb$F<Ozq;*;KT;SUQlR0=;q;uR_i*Lot;%SS9$IT>F7%R zc<>cq&-bynFfaK_bq~kOkP_wqAoE#W9dr3goHJI*!^VSVm9EC4I6JBi>HC&Qjid9K zTaF39K~4@YvS_MOutOHtU4}X&PCXoUD`4=rxAky5dn?s>_ZrYKt>7|8#vcd4ye;t+ zdp|M9w<Fply>uEJGo<-O={%qOSb{qzOq!zW)7+=`yy^;o6d91_u<5#_5Fqh2zRY^z ztCid4UL$CSyL<Ur)MSGtRqump*<hh?FyUV2>t50hN%qFIP;3XK4r6%fwn2W5#CYz) z!q-<?tuDoS)W<3it8B&;#>fRCcN6s~v-$mkt%XX1oien6E+#X3YvR1-jb#AY6^tUi z`a+i`S!-Jc3YSV1{35ZxOG2^Bl%%x5jEIMa34*af&;x$<K57!6z0n2%`b=`E7eL0Z z7i|YLPMm2^KabcPU-ak;ie%YBohA%q?c!KA+>+{)PMYr?*+Zu_app>A>6cQn+c^5| zZupTjRt(6<cOhGFnpywr9mKWI)qipZyqo_d4Q$2u_rU4RrY7|<uO6_z1=t^N0aC&j zAgt_Q!U9jZ3`EBQR)(1YNc#s`b>Ir%b5vXRTp?duP(a$S55KCfWqnW+OAp5B+QI+# zH{6ZkJILiC9y&*UtQBgCEmW|a#n%EguluGKa1sMuJvz7359k5kqjVR$@#iG}L2TFq zqlU~yfZ%WeiNG-nkN{zk-+y=u#z*z?7rlebAr?NAl#UUGVDpc6-A*23%8IrG{BpM! zNY?`6ANHox$%wsu1FTnwFb^Q=yP=bD0WAPI0tIvU2}+<I{Ili8|NnZuAY^j%TMKwN zGGEQaC5bRBCEgZ}qPk*~Pjn$9Nj%HVP2yxNR(vdAWY36{CBTNm2^78(dZ@bQ3#3l( z(80HZabN9JQ|+cyRVOuVh8OBec%6)bU&eEbthvVNZ7Jjo(lSoz7*y@o18B^z$l@Pi z8&3xMTUh4;S}KxyM01+hDm;MSbDeHz#ewB_OlS|I-JiXrJfD=m&t&jBg#3=$E$NQ( zoixr?ziNFqbCvGuit9PUrUOSe`~V+(JO_^k`Un3CU^Z~G!+@q53)$tVsUFpp2?vRj zR|%i^;sg8DL|?y%U}Rl<iw$&J_`xuFi3b=`Gq)x&yw`JKYvKGxY4>YM#14rA?o9=J zftoKes?fx|!_C$5t`bw>x1B~#eAc8LZW1-zgBtKL5Lcbw$RPM{%jLwY`ePmywo-i- zipc`dy>Y33_3Z$;!hcPG^N$dT>Pq^vLc56s!Rgug?ieMC;*i0BY|;k>zazy-juLpU z`8KW@e3k_C??s%f0m=3UbnyN9wn_JkIZfS|Q_X7cOqT}M@aIgN_{Y@Ie-a-=uMGYQ z7qfnEyl3T;>jJ^-VTxrAj`|OrSyYX*bpi}PHi!5J0I2Y5Yq!a|0UM_b!!`Bb-i=56 zWAp*Epwx655O_qd(j3Z^{_AYv-0MXdC;@B}ycKd{59<H5P^I68yK9?4>d=uex^X(> zQTXU-#Aj}1t=A^EmyaOvj__X*d7(dWC;9LYKG_Z&EuU%CpAqX;X_cQ%!RE^!o2Oi& zLp9HBr#OgjTwW>Fu9V>ctan2W*q{tCkixI{IqKIDPY>T`3QEtm_pCvgnf~aF?h$T` z9B9wK9Rnx)BSIcMhMrxUgHKkb117@!T6#bea}<WFLmU)vGa6;ml)dE+V4-JhD!}=I z52qmenfJ;5Xz2Xo3<V#04%k`XONJd0IfTn5rJ%6O!xaWlmI7qw6nxkQ6!yg`P3=L} zfvbLj{k2p&0lb$QzMTb^8Y^xgEbquFeB7pSf{Y|H9zI+IXfyzL<3|Yc`=fEQ$M;`@ zxZy<f)7EGL)!xwenY#{xo@r@b$o61S@Qan<6Q8Iv;0I3oGD!YW#P<!uXMAH_<geEm zZT=#I&cA*OBv+0FAc5OD0DZ#Xd?G3xAA6#Cv7zrAMsGdb|EMi0sgbL1|2|U=6_7)j zg%9Bat5gTu)B<xP1CWs<P}Ltmg-4I=%>m{zygo|q;FT|}ObpwN7|41#eBt41uol23 z>d9_7?rVw8`MpG|vG2)7_v2NB#INsL-e=<bZ=+aw0f-uUAAIrl%z)_E8cUbvZ66U3 z7oFmxeV$yc)RFn0(W2zY&UVsIzh{t2{2LGu1#YyM<jyoApoQ5o7#|jJp)!7yyn%2p zF?ien<9|_V;euAD%9mHVD^<i(a83E@O$GKk;&S^_GN#A<R+4vKlIZ<=kH05BR_Ef8 zjT(dA@byNg?_N!#zzp094#GYli*S!nR2gSi^KO(b>Y$4>6IW9h7sv_I47E}ll7rn% ze&VRA#gk=rHhdX{k~nEbgS&U-J17J?O74E^9#S2LSLFbD2mp3m&R3$2__V4nm%(Jr zt@->Qnt-kUuHuq-G#psRVjz^h`I@ibWu}bLqI1;zmGn+=oDeF^7~`N&Q#r<7H(nKz zW5g%At@S)7qc-g!mFXAmkn&Dgtp!9u6da-hi#Z3F&;~uS_kh+K5PSvvaM7>}Mmt`t zw0+J><*3Q-;cO68;0etLXOeal<#TG=#i$E;k`(!_C}J*TnY*L5=&E9l9&LYiU6sDN zj}obhNjwLa!b8(<1BYq1k);$%GCF;dkuO&Y)Bu5U`xpcv-96n*C?Kj8F2q$|x%|pA zi*~n;vu$vRo9$@uCG#zGUPlSha&8r>x&53GP7ieG95rsaP(N=!op@SR-p~G&RZh9a z<KW4cD;-b0V}wt@Gsd*<cadn#psJ!<4|}xbWhA8BKYXllvWnJyxRXx<X!XCXdN7^w z#`Lt)Q34q*M>URhMANou7F9<eFDA=j{3RJMn2L#;sbc>y<zFI7^|IZf?2l%WaAK%+ zsZNv<quxN7y{ec=rWS{Tiuz0OWR-(KzG)Tly`;xKL1Ml_gQ!N9Zm|R3eG+|lSMe-K zMU8k{-3UY7EXnEpB<g4Qy*Z4zXWXMnfrj4D&V_gN_~8&+B0CxR+|ARZh^9}CbES>i zQ}er&KPnOAHg+HQX0MA%s~nJ<EB9SHza@dh?||NzF;Q5W<7j6f4O=b&q$-^9GN$aR zn{U@vc)XvOGP{!UepP3sLKS`QLEQ~5bH@vLpu|gO*+GEphXhcHJ9XTPkWm8e0t8zU z60git*X>5TC^UvO-CQpkie!2izk;+6ipjHHOU=Q1z!f$@cgL`7DB8u{^zfB{z41nA z@#w`C7PX0e2Jwj8Bx?tsi+f15_xkt&WK#EtyoEbE%_L4(%Z!>#uikmpJmPmtT2UxW zm1`hrY%RMkK0c-@`K52mCNls|ljBjRt$J7HMfO~p3uZBV=y(`Ur;}&wbhGJIOjVun z`a2eexG~OWt6Gy<!8Qn3QD;kqXJiXGjtR!oEp^<To=fiz_=JX7-3#i7@Mrj+s7`7U z`K}7F@;@e@nVIFX4Gj#`=K|w(f-9A}eW33p{3S4#xiD!pRO|S)h@6FYVsBk-9IkzR zlT}-1qZ^-1A@gLw%cZO%{x8l<VWIR6v6h*1Bw6bv2qSTlk4emv2&b8=+7&Tjrmr4j z`0f<dN8Ul2!RK_}C2%R}dvCki$LOCR&wbh<$SwF{3A7?&C_(`H0JV<{%0%Ov2hDHs zsH=5JMRXy8E6=R!W1hM<*mgC26}M-;&lfrq<3zgj*kldk#PLnix|E1KU~sx<i2gyJ zs*|G~r<7w&e|>=l$;Cp)E0KY(lJcV6F7X<SJ;Raguu#(~hekyXYJB>7^Fd_M((~;n zE7`Mkb+YNKv*xrE%in-x2M-dU@AT~Q0Zr-ZyAi01rPFS+muss#yB-VIF&5uVhj??1 z(x$RSB*{(UuVbD{2ywH|_8L0+5450+1g125AlEX+aQ9&IWY;k13T3(zM-3sRdok+{ zT?DmNA9%|(nEFdrX}rJl=G0_cdt&f#gl{iQuyU6OfE)s__Jcetasxlxy4ogrTu%Ks zk5Q00NY13clBsC-gIi*-iuxmqPy{3q2A24S(UeN{6?M!>7xo-c$xU)F<IBRBCVa)& zor}6aLuN^q#+^%^ISgkisHHioQmsn83@;E99kbpq$>eg=iTk{-;idtOfTFY^bV|rR z83@Xt)z~x4hGa8QeH{BJ%V5m$xrb1ns2uD<hKyHh=K5V4cNq0@wDMKol4V55!p&yR zZJW*oN*V8BOqe!zzXyqzZo=M62BqlWPdp+|`&c8rS5u?3)on3V363n!d6~`%UGg}Z z-2QmjotySZ4_4T5gq3j3JW3ws?|ad_d@-HkmpbiO^L)n3X`*Vu#K`DHaf!p7_-zUx zMk&V10ypzdOAD70uvd*mzgz+HBGgb9lu+gYYE&6xfHp8i^9Q(-QEt6zPS3ZMV|uG& zGE`$?*p61MFgHG9hMv3<{vv#q=JOZJL0fER2_TmDetR+tTClbHO*rtCgsM(}>Momy zq?+f5vBKV@<FukIHIOxXit9^1GHJdIM^*r&#?^7~4@kMqCCz>a81rHWa^|5l!379P z61Vh1%3Yy@nm<9;M}C4<y8XxD2QtR+DRERDF6)&C?3RzgF3EBfKIXK$d~5!CeRJaD zYE*Z0j<I^-w30K>SEI7Xfj#<jq>-LPBXQfKh}Rt{li_}8%QzV1^1u!`8bQD@<^O2y zFwk^{Tv9skUgbnV9!DYle{_thWtJO)FSUPy>bb_5bROP)Vhyc_glPZatpJU^aq<$- z<GGepPyhe%#Z3LHh=+<y>mPN}e+-~~I|$PLoc_y4$ojSE_isT1AuIT_7eGoUlVPNI zfmpcXb7#yK{Q)b(#mi*_>@Q#CpDhgCe~q&rKAzX|K2v*9K0w!|E`wN=3uvtJ%N3Fv zas|o`z_>HfD}Qjk=LxT0uRHAi`mP%%GEwu}ANmK!+wRv2tuRdqj;ySJ_4NbRmzhCo z918#CH%9&Pz(A&`9&E59t^{y<lXe_Fpk}puO70&h_GeV95nnk-+WxmI^cwt6B@>l( zz!#N`#hp{rWbvx!&2sl=e`EqNBKmFdg8%cb5&vHTH~z03E#2e@w!J(!!l5$ohadm; z<$et*+4QGgNnNqL$W{%1w9s|W+kuORdd<JK3DmzM12{Xk=^%^HbMjKPUngZ|6O?*) z_;#cLVTY$)B-y;^l`I93p|?06j>{v?-vffyu+D(<FWIs^3*S&T9Isktvpc3sqUOH} zqR5ijv+w=ovElLj4p9I~*#GsFC-wv0yxo<9O{IQZ==MJbxl{db2a>o2Kp%SVK(>+a zBbrj<`Y1Yb@wkE;q`t?J<{E<Iga5X3+bi*zNaz{agCqFmmBPedCx*aSaNV6i#u!fN z;tvS6g1ItC>qBk+$H~_E_gPR~p#eg$KiUIMIu{I3Zq{(daIw#|f{vxtUE#m&3}n)R zxk$v-OC08Jsr`BhkftZ^b6haYq@O+K2`wGH55!VpHJ2}`uDEfG4aaWT{!O>0gZJ9~ z2ex%$>q^)?6nr%wr#EPzvIxf<rsL|PR_`-@lFJQG*8!5+!OJn~InA2b%D-Cy{s+Rf zYcU$I{p53fJ$sBaP9A*H*OCMB@c#GLH9N1S(yVjfjQ-W~&ok{dFgd=VOE=u-+IkST z2^e!3jH^c+<`@2YnL)b$?`adK>zGpaV0~3^XE=}f$!ow>2Bv^F1NmHGAcGH-ZL->) z{D2&E>J_K!=!rtk@Bn>wa{Z0J=HDW=o2e&XG-@JKt+zGDDrai<Dlaa8E^#G!5pR2V zowBJsp3({44!A;nPJY3%4Iy{LLKYG9SV8n|ZY=T^e#hHyqc2#VSr#wMnump9a(;r8 z581{n_-+A>QJs=`cXn>}ZnC9z^{iX@obCWDi);Mo(;cx(M3(J&X%<@}!yF>yNS*K4 z=i^Zy;&Wg$vaYI9aNs4oRr!nLd`pFLt7v`-1E5IZ1<E9Hz2ja23s>hiBBJn!oLwf} zJCX%2hmutCYi?+y?lvwhv`68E9P}FnX_<4s<JMa}^<K=g<I|04G)>YlEql4T7847o zEzBJ6FRp|wLPKJ(cgirXr9Vtk+5J=<Jx`U>==j$}GS1dgL<VHio|ixEU%3|RYVlH5 z-|%zo`;0U;cMtB3?GLTTSG}k)@fSMqHV=pcbXp2$n^A^Zi?#YcwS9RYlwJGqNGN3~ zTh^&4A}NuwjTYI`Xt87s$riGO$S6^^CQ1q!B_WJ`U#9Gm#y(|dtc_*tgPG|&^Sn=t z=l4GEf8Ss3dv5oA&biLDoolrpe(H%}=V>{Rpevu5tmS0p-#QlaT2m~t-wWj$3F#TR zpwVZ}3hJy(`+tcYsM2u}_HL@}Mn4%onXJ6hzr&1m=GU0gOSU*W^xi#AhnFq-8rm)< zo9#}}>P;iXgme&pBKImgoA{)Oedz3Q4|9y2KD-*GtK{TZ29l99QOw18TnRT9dXpf( znz-1FiHQWmmr@t6u8bd9(C$3&wOzOUiHxKNzERi5YdUh>$y;IBos>C@cwE|-;lCfZ zD1BBySjwilyH>dQz3IU_FYdT93VzP`wV?2|<Ob_2=mGB+RMtc5n!o({ONofb<!4!f z7b$RcfqMlaFVWL}C_9sY!S8Lm3=J=^F2CoM4D^W%D<i@RSf)Wt2%F{lB@zKoR<!t$ z=}ECe+%}ODF%7ZVexk>CHGNETd)*EzStqwj%Lm1#3^j&r_~NFgd3O#e>i=>(wC`hL z$u)b2{>)!9Qz*%as1|DHkkBh{f1awgZ}x`_JnTN@ucYwTal~>4mRs)l>aM*<`-n<d zrRbda({jsU5F*G+Dzd2PlsCJ&Y|;$B*5RDs8`czJTK+;uG^$N==G(V#TC_qkrdiLl zPA&h0)eSTlOj~-7Q&pxh1AvCdR#a;X`+k0>1*~KaVpn&e)`kbZ8S20I<rq!0B?n<C zt}bIzpAs3xJ33|dM0qI1qXwbh^t+RXWmXwL{zNeh1kljPZ)g6%>JAV*fb*bQl>q`Y zJr)O8vLIq@2KCL*Q;iv(mIUZn9dh?1BGY9h;?!G(wXWX~?{?5UVL)Ac{UBghH!)v} zL#OjCR=1lVa7@(e432*&|BMVDqQMQm0?ra=dEOYC17Y!e1T{kopE(u4I!Wf#Y_|d8 z>=g)e`M-T6Z2x@axSxksXpcAvwPvVf#`g@<X@V&K4QVR@ohU56+={pX7$0aJu{Aa* z<<H9!q}Qk^sb`2FTK@>Ad#Z=Q6gI+zQXy%JS*xsI+Es{&bBXjf0RUpxF2d75^porZ z-Mbts*sij*LFg<h6LN_AikfiUbNI4u5p13o7z9}C*1i&rOY#lgS=96Gw2lsEd2qM` z!<bbL-9^w$Lyy^$_PWL+ErIK=Ve>@9B2OlG--x;sOzb*H8KV90*O)iGr=nh!r~pOK zCUfoc9Im%u4MS}L?Uup&f+9P`9CB~|hBTD`U%;zU@P&Ugn4oPu2lop~pexO=)zX#K zg$RX>FuH;{u-P#pLCn#%??|xIjuvaHpp}N93&5Nwtw4X21~zO9pclPkosnP+ECV&O zO8&BQJu3@yRJvFg5!)rJy-n*ZmK(&^{6t{mEmo%VSazCyd<X=fqs!WeB;wD{hT@sM zy=OmRxfR%-W(DcHLC6w}Iq!?%MIhS*JAzpuwk{I}R>?6`ssIE75)J=ubBoTZ-lOjM zAp>{i=rgn6Nj~wcv`mga-=qyC4u-;iN38vVMLSZ0o2Y)^U5r(>pLw&bJFD@Dr`%#s zzxOUos|gG9R6QtNp&|}}=fTL0VOyAgLqJSX+W-*3^E}O6vw@A}37+ML^-@oTsNQj( zH5stX1(}hjF|$7s+4s_Q%`J8LGYtc;(1W4vTC&}BIhfZ;9@h5tDzy;DE2iQ-S%~p@ zi*=ISy5}sJssn0(u|Yhk^y0Fm1$|7sGcnkwuN5_BXmxgQ8J#tC%3@)hkFw6qP_^0N z)~x8q9nAQ5nf2u(F{kc@I7uaE+<f}u5$7!-J*H5p$D0E{oh!g}8xgZZiR?4QQb-c% z1!aLeIk53F`ui@aQxEww4~iu=o<M3th9=On8$&+WfMCFZ7O?*uP9TR%-2|;<TvGDH zpg2_UiTVvqeZ&0>i=QwXUjze{$N(o!1Ni5^3aTY-Y~^J6$=!y==XBloHjKte9~@a) zl4JOK#cbfuVkFktV#uqtAXBjxa*HHNRR;Eb^gxS2pS!=z?Y#0J>3uaHk4Ex$?`&Mm zpxZMRFC%jxqLIEXD?O{MUp7~Nhol_WD9-n!nKeCMYr#4z6LPclzmMi_z8laOAQ-eX zxz<xZayT_9zpcE-sO#{;b?0!W)8lO=m`x;M@w#5F4scotwZgK%(?HokB(xnLAD=)u zCswKSq;SKOrm{#KXczO}A$mGffqD+OTbBA@uhG9g^>-U<*qltxaA?}ac@A>+3tDL! zhgnz!UBBf(irRn29@+l{YvSB_qTfVl<v)!|5^v(3{ey@!dMFG7(+qQ28^nA~-UP0j zac$=}#mpMLUd2z}zUZ3<FxxTa{tNY$4G*lcYf*<m=bJpo3}VOe-if(puz@3mW;n5V z-&oADpv>w*7?lzV8Tv=}pR|of<7D$$+XvkDo>^UE*RH$w$jxUsK+*VL5S49!zCjRX zaM;Co&>X5@XIAOb{H(H|WaFz~z|ELX^ou`e%M&+TjL&bYDSUd+S~j9JB4wYltD3-~ z;m!>_RPFQq4S_`gbA7d%ux$utgvpf(@(3o*75{1@F4e3E)Ew`<G%w0kA{@dpsuJM| zqbK^5Hq6KofZG;;E5Bo%R;{)H>E5o0ft)KA-NyBn%8@-6GqOtzu0sOz7eI(CnrmYp zHyKWVQt4mvLTh76(*|D~QV+KsLoIyMW7(zdh1eJ}>Cd{j8AKw%ZpOK+t-wbln_XiI zIy;P$Yp$3!e9Ajcqr!w}i;b}u`sf6UK5PSbao2_#4wSUMiyh;M{61BdDn_m^No2nm zIz!!9hsFjuGM)sXr>rlil^oPZ1v#eJu(wl7JMj7LdtWn10V?e6ox5Q{Pxo{^kD!0J zoukW_fk}-0y6x<}sh%<NkM+KjYC;sAzD@3o+(g(jTZ3DrptX_739oaz_lJZJ@&Yof zcCB?s(T_;qD#<kE&zKG?!Q%<zH-ZI25-!~AiTv^0|JsihW}AN*ls^eDtIc*w`nuX( zUDArfMwv+lMndV5kh9%BXxJuTd%6+zA1s!d5z$&#HZRqfT>WXRyt$s@fo?0tfHvs2 z@zhd1CPiBGFP7dVw0WJljlQVkq*UBoJ^2ApdQ7nkiMwepD)@1L0}&r|MrJ|26?X=l z-blbC;fi>Jeip#G8Hs8f9fJqCuc)<On67{`v=@(ojxOg7fM*I+12B8*njj3O)`?jM z(jI54#-!l|a&7_o;|^0VexQ#qWnlqLu^7yzF=XF*>L6ABi=i(#g^PgmUok8iqDniG zN&WG<$Y0GQ0B@oIjcL|>0&lrI#*FNQu1}K*QRt#7i}~$H$}-i1Aq9MrMIMhNQ3I)9 z^4E-_i|B4%LJU?OV!D9ZS&He(cJ%!`KyXI%f#6zU9-zzco6CZUD^Ln8MjT(Fv+6A7 zfqX7(B1gErgy_$*fqioupy0_7SJL|h!9R{-*6UXVAXBus^e1{iA^;L40I%G{;bP;N z0uB-pMJ<L=A2|jkZlf(_4Z5U5ok+Q6`5ST_GZP9rh|z@&5DL-arnC*kQM_En)p+c{ zHwooH`PqLO)9*sr(G`80-j@%NdNYS1KL(#dL)TBBV@ptALJb$8YeT@dCIG3W1#%-k zWBkV_P+g@0<K??nX8c1aj_(q;Z7GG@m4V_1?+GDrp45v0XN<vC%8;z7=YfX|>}HGZ zJ^6ZX`dc~3b^3(<Yg^L$)r8~$44J$pS6JGLS^wj=mIl8FT`U0F-JjI^8(o+Y8Bf5^ zILOTgiQDMP%Q_;_)l~!Y41rW8npF+bLR-XZ+A@Jwl?9IK@8qowun|Bp5a*-#A}Kr5 z1p-(nlz07xfcz>BN^Hp*-A#ZZD_D%IvLk@tWAJ(qSdMXt!!N&o`~Z<UUxk?$37i1_ zc}9Z=TdKZJNq|kr`UC)Uj6kjUKm*9#rCtZj{4Nmck!25C<T6!(SfI>1hu#c_u2!XU zCNg|xjswwtwD9+{EaWF7eaB6s%C=dum@$sB9XbykGGmTQp6m{KY*<tnB9?o2QaJCG ze50X#BBDW{hg!l4fek@h5fg$?0#y!C1$z%hJ_W;(9Y(nszBv}*j8#^1+YcYF;oc+Q z(Mae@12sI<LD>3P0A(r<EDQihc3`R5@mRpIEl)CsI&|;#YZZ8K<+~K{ukZF4F8R7O zAO1Xb4~38VFo%l4Ymi0PWGIZ*6hs~RirPN&gBMy7L(L9cU=w{lsuZ9?5U1`1rGy`G zta1=D5p)^!iMuewNDyES7!o4Lti{E-001P%A?nThA12m|4HMoO#&n7F;6(8l0aTmB zJBTb=G2|UoFnhHh06XT=U+OX6PWfoRb`K@J6!E@RPUrQA>4*>xMh{;@IDHcSma$cP z%sR)4pYglAjqH^=!uTA1Fz*+gNeJ_AO9h9C4dBZ+>tqr3d~Ho$4>H)lo1N*N{1;P1 zeGO_BHLk{s89E4Z2xv?g)GdY4-z2L;JiG5jr&#=`_4T<Or6b84*>lF4aE)#&?L9V) zOQ=my=g9XEDxi9f!m{qWB@>_G62)#Up%b?1w~!~BpikPo`~)%&w1y_|IH!aM<|mYr zrZ4(e^Vjpd+XB>2w2J3Qehi^#k*7#)%TnWp<;|ESP#Ra9ZLGwOkkzb({R=AS6<tUp z*sL&PuvvlB^JEG78_8&HhJr+MQ-Wa~R{tfI?-gyU>y;lkI&MPQNR?jYz0LsNe5Ajm zd#d_U`zR*6!02OyThuW(b~S228lBP$@SYx(L1B_jgx3y*w1OVwj&a4A;}!R`#PmJ) zyY2kK1F&h6avUSu5hJ2NwwSfAhR&pJqXRjTq_JqR#$3Pl8xmpqKHxNNjyd<)6_;L! zCgZjjbl`pQAEU!RXsYFhy`t07OT!p2aBiJ|#+}g+q1X}nzL$E8hz)%DCowk>VuQva zQwxIQ&IEJo8OTq_%HCh^gp)K2vetIMMqpLRb1vj3Vn77L7Wdr9XYksbPbQM%Ja38J ziekBy&tBb6*dI5AT$kjVw>H28EN6p?|FO>FeixYog`|@nI@=r-`$;ycQ>5tH(1SG{ zpS5H#Fbi8m-}}d!eXCcz1o{X!e&zBH?|HR@BD-T8nU<lABU+GyfW(82NiceCZthk_ z!f#yp);f8zZD4XaoxAm6uKM?jn$U(W4m#Edx}(u4$dEF6dcR(1+@J30!;@J{kaN>c zJNW#})w}AqJJt-zL7?a85Nz>)ny|~it{F&EI+S?h!bv#$R3LB=de$uZFRMzxF**SJ z6UPWs9ucz3Uj>`e#e8f+%r(w5o!~#5OwYgC7wH;$(xX^*LFUC3t&R`bAQeF`(JV6S z?DL%zE%e7NZ9YZm3F`k)R~za64$r2;rJe7&8ggG6`oFu&etP9_7X5-8P@t_Rk2u8- zN?~%e3fQ{XlQoFB14fshsba@oEu2E|o_L12X0r4UpH<?xgrK|%0D2ES2m2>GbN0Uf z>w)vqw7k7C>D9p@XyQ#ZEcBWQl!%<bEV3b&KvThL(1|q&*mttrfuNT5<laKy1re%E z+U+)&_RLpDl6rF0f60D^w#0U3(B+b~uz)l5rsTXrf1@uc!Khtr+$kgTF2AJQ7WfCn z&N1_AeSt=MSkO&jWD&8t3ot0$S71Ub3xy2Ql9^`yY66;s{sd#4<lB>3lYV%T`=r(7 z@mMeNfi;<xL%<+|qBuZC2>C6r5jJqpG7SPY!pAUmDzFPJfDYX^ief3$NVhecgfHCU z4$h|W59}C0OFKB}k|)v#GmE5FK#8vjA~}cwDCIr`PBTUPrwom+!e`{8`+RlMiuhU) z>Ef41udW_cvh6lPj_Ru(_hTgvRQEXxI;r}M6qP(Jx6)Fz`BKNh%`g((<_)DP13M%- zX;mLdI=^T!qXUdLu(eK|>u<@DlTIH3c(0U@v9HIIAs%vuV4rtB%OUVl=D@;}s9eI< zT{7!<un%f{WLKa}zXC`8R?Ks>b1B=g+jG~H1+tke8D2E4`pCOeIVpVWv|}ljS^#nL zOdp(G-HqruOpOM3wZlJ*0_-?o8peqo9s~<E<G1ij277~duGjS*w_|h;9fb{@=u)u) zF<h{<MMRZ##{F6l#D!RzU_{i=mBKMGFkV{D^N2N@sphVCoHiBmBp6!|pG;tSfw2v- zl*;%b?G6IJ3<YP2@1+R3)pj6<oDO#ij2(L6=V0cx$}bcO>D+`mP#nyWn>zsU^xTll z;PV^X(FJF<TiE}m&Fs5^kXCOC%Mo=?6y4xk_E`-iQ2*`lA-pc1V}AFcPxXy`-q(kP z8YOObC1G1eYowJJ0`kNZw|Wh;35cbnl*v~Kq6KExt{TYZ?0?<E$oQ}p;x1=+V+%y- zceR6o<q-^D=dw0UVRFK$d@{uZ-O|w&gG8a17gVj|@oV}PTSgATqev@2KYxIE{t33Z z(xPNdKLc}Vqg&?~;4-5lOThMxZ8fu{$8p#YM=PQPSa`rGMUNRC2pc(uAcP@KnCV+N z81VM<7gF2WIv<xk@+Z#hgHb<W0d(q(mcpnc@c%6=hIHbX2OM%XkuL3yXV0|rq+I%R z@R4Ui2M6)|1d<-JG*1_z3JO$LH;eVv-;gfQHh~V?+!bBOj{&g}O2PP@x0;3`B)^K6 zKfE=-8gr@gqFO^n*58Y!ZFGQQsnkpQ*#OzTIeg;oMod@HdR?5EF-hlQ<c094(O~#2 zY^?)Bx6_O-=u?UH5p<w1uo-w-Abf00_Y|&aKG7<2#x$Ot3F5K%KPYQAy;v@ow%At5 zL_!SDgvo@F&0LR*xCU7jzHruFQH{6CQ$6O#L7c4~;QWZPR-W&{a=hVPRkh(4WtmUp zkU*n=!GkS^T85%*zfL#ZPp{Iv#DkJeq$L=H!p0O{D+rB4+X55?{udN>RVr>KD?28( zp{RQ+Cey>89=D#SnwMbbdHzZ6S%a9>T`<aB*f)bLdNj#OGwLB(^{i{?Tot>$2X%aA z-x*ko9`h*AS9&U^-;NgM@hvjDC#P%Hv*$yb%ksY44G+QsKVvOYGokdf&Cp0Mv(04a z$G_7r&^C3zm*Dy0+r!-<CG)aLqN{q$1)IbBgQMD3j+6dZ&U9A_`LJSrhQ&%fz?p*j z#~!x@Lv^q)0zd_Z#{WeNOcivQ)nmuXHBu*IWbM29En*m7<9pwn7Geb*V>bD!u$h~P z6j1vY2QGkvnYtD|GG+=2A8e}O1vSzn>+Ibz);I5JKT{3RV>$W17|)(9>Df|mJ7o?L z^P4P_A)+1&g5Lz64Qo;#rPBkSF`X`h8%{SjL%H|LMq&cR*q?Kws}?f--`!VPA>*m& zJbL1T($j?ueYUrONQx~>&~)&-<Rg2Po?>5nv3=m8FagWP7DjM`3e=P5Z1t_MMfnUm zF{qnDP>7{;PYMKA@BTTEbJv^c2~1Cdac?Mrp7Q{~PA6Le&Qw6D=ejUU^QbjW^l+{% zu|Fn7Z7nFbaZD{(b4B&yC_g`09Vn)B@+Bo7oMHZSPf4P`31D3u0EM!j1eR;Ohw^#X z@s&ocHl1ay?7T3+A*|~Y4a^Q~7>9lS(4RU(@V$2Py<c38tjlE|-<?irkA-}ueDL2j zX|Zcb%1NjC87N>-(ZJc@W^LJ{QtR`;H{~hJfdc|~p??q_0V$7lSC~n@!4L&ou0Xcs zTwA`^;^zk|P~GF*-957n|1G~v$>uTCA{k=m|CK7*DR<@G^UMBU3-fg4G~U@vIG(KY zm+kU%$~cvt@tyxk(_V?H_iL=n98aKmV=;qpb~AgYbS?Sj>739TRfC6pl+^FWj(={N zWp`lj9(X#HDMv(jd7dPHSJ}4I47uysOu|!D2Z6p|yNb)jf?_dTRYmvBl5|slaflo& zvC|%+AT7;l7P0j}Y6&>G?(?{!4sj+ysjA0dy%uARNoe=aAR>Csl?v=EC(VQ*Je%gd z0x6j~AkAS*orp}(`vbgaMw}%FX9A^x8eFD01}Z;Ou8`rDH-SVdFAmq;*GFd3+P>y$ z_PASR>Z+XPqpK+>u^AwY4Cq>n7~IM&e<I?P5tb15JXBsq^h#ll*Q-|Ia_tvZ_}8;_ zpvlqq)O0Un-YlEDU0w!z#TwL3a4VJYPwEv!57)I7e0Zog^yA%U)kOv#x=?PW4Kw0( z$Qm&HoX$j0&l|#)espRV0ez;yVVqhfkfz4uS-BTruNY#sXaTKVI<OPbuonjWI4#U? zX{IV1@W!oitl=rTRtB_e|G%&G7)<(sDbU27X16!~k~zzW$SnB{@dQBexDJ3~<K0A6 z8(98{h(up4#qc8<1gSkT^YUNy7!1o5fLW#qv4WhJznJCiLOl-@vRNqTDxOPod<vhZ zDvN`y<Ddm!4LO!}!0=U|rUWfn1kD>jGhr!BAUb8%-@n!UJD9BlVweiLPsf(?Wlk{G znxA+$GuE-MiTj*xx&T-G<rJRL&Yyl~C~4DVwiH;9GCWDwUHC&rVV+6$_g>-$s5WF2 zV>cTZ>s8f!uN$ux-5j)*^Xv@!r8|mf-_Qkz6&X(db{I$H!6z+b-$4b(ZNL(naE9TP z%yK10yCH1ZrA^s`IgJ=ow~Q-{*uSv9M9C(AtJhbLIc2JBIO5vbc6mnbpZUR6j!!~L z`PhO~J41$Nc?qg=T~MR06pjOeSFT%L@r6i%x_|31dsSBA+nIpU@?0#!X;jy>NYF?8 z;gbAkN7!~5KL!8s8gsGSyd1Xm^fwk`&wXV~TUd5&4W{!wmE=h@)FgU>^x4&wwXl>K zbpPIBgq|<!-2X3Y=yz|E>e6)Y-1bYnpmInQhw?V>J^AX@TtA%7pmWU*FP{;Rz%OXW zb8&oAWK2+fA0V~GTxu|qSN8a!bVjHq-ffR=SN_|JINkUrJCdX9D(hvQ7ow^!8OHPV z%Q9IEb4#PDepOvhIKrxYh<#9_K&{IwY|q=wTRT#AkFql?HbXSb)*gIWL~kowTo0U7 z+eNc^@1aZdG4RY<-33xmssTakr$V;aRq=#uVi7suCdd;<Ok50*qZv8Jlz}e08U2>G zwOnc9wo(p&2~9XMBWT)&_NTu~WPb!~+q;nhfW$Uq+fZ9>16Vf;igu!mMR;h!6RH7( zr$B%b4acQ^ZLz6(34nH8GZ;cQ2vWdts0pUjDe!*ik&fB}oIuv!PXj~j<Kc0tpC~wc zG+WbhLH@24swRjc#secd_Az4RXIgvpb4NRQduQ`g@h%dHoKo@hfov!sg;Y|2CJdyv zU+5y{r%QG91yb-zq+FZmjZ!72)obnYIYh+Z7!qG0;$(XR6RmIaQ|NAF<cvd1jmzHZ zA(Ieg#=+v|x0!iXV;(O3m#N7WDyfVEGPBciW&EB}lU=7R!^@*i3|;riI*C&joO4`G z2<{&rN~s>xJ=SeFU*L4vmG!cs&Dm-5Gg)NUIg)6V@w3u4``ir2yU!AHkfL|7ZI#8O zm3L&bIqYX7Fr8H&cX)W`YA0KVqQ@68j~~amk>}$>A*=Xdjj59L3uM{0TR2ab?PtAg zS!Z53DH580sAviem!rFC$<9Lw3eSvsnly*aYD1_6Q@j`+j1wXt_RvyFh)1)wiPY;* zx!8i7w+FCuj6HM1r7)7XOMo1Tm(cwiQft9yq9J!*=Z*Envqj(b=iKoa^hjifRztJB z>aaXN4yRZT{j>~L?+u>olCAzBFit(---O`w=X*|-ZFQc0Zyi*;L*V3Z$TlIsv~Ezc zDy6*BYrUk0vN)TPCtJQZ+PgSDoDU4pnsIDL+~$ZV!iY>2Km%dCHTMH`Z(|)j#jM>W z1_Ngl1J$6%{1iyya~yRFhMazKEn=M?Ll{cJvn`~31qhg-mly~5+9AM1A8xB?T0TL{ zuVf~D!CSDFG-g{IfoEGI+j;Qj$0?Z@#|T($Y;^G3PrtVH3r=2z$W^JSjc^PtCbI7u ze)6dD2wCt|7xbw=8x`x=DSb!8be1u&EsxAF1n2W}!y$%Pi0I(<-u&Bl&bg^sn9lXb z&Aq^L)M7$$r)-Ba7w4O9hf5pyx*P=!j*g$S(56-=aAlLEh$qb`@5(jq@D9)Ln(WzM zXJt{!vfiu)JwsX;<O}f^aAZ6?_cmkMOL|}Al@6h_88$1>?9Lu|jN1?c2P^9-$@xuC zBnBdfiYR5ujceN8++BC(x;T3ZrJYO|)rJ)K4&mB7DdN}LXKd}A7GJYw+}w7tio^Uz zdJL2+Ymwj>CM;Uj(>>2M+H2gv4*$wuX&(Qq)8(3PWSUX6qd-Z_g%JK5IngKH_AcY) zo9zuxDSGhTw~4O68>=&f96R7zF=ERWa9@x4IjPL|!MIKu$$0cVP(D%)aWu^@%y5hw zI8)_JlH0onNZP*lN*-5zn(pMk7l?g#CZlK${#3@w*TjO|tX^!dWm4!N$<NuA#i(I? zf#ok(QkZE;K_Tj5@xq<a+mWcK^OZxZjB3KyaiwP8R@!u3z1ilj-Zo1fI^Y_l8qHha zX`NQ9l7G=7^!jrrd{ocf`T=BDZ1=H@cQ^7U18z%xcsCOGNK&0RmVf*BDb&GeQCG{) z*voc|(STWqv{Mm)X;iAK`PsTM%rk{@q9hJsPosfn2VT~0duqj%XMa3U)_nT@4h{8S z$OB4!EtX6IOzJ@_Z0Ix)_9$RFpUpG!&||q+DG+FUC0)yH0>|j14tbaWj+%kp2<#$i zr6E(8gQ~VXuvDX83IW`Ab8K~0G?foA<-LFJC$^s6!T1F;HaBw_zzKVR-9{d0NVZh2 zFw`m$NnHnKVpm{AQ{4l!tlQZWiR{6Gx8@!_$Q=ql%#|(awu6x1542v=*=gAL8hm}^ zDt+h*1h@n@vFDAl^_NeF3sn)_>}}9+>&d0ewW>KR*|!H#InbcD9lFUbf#vA$(dD10 zLp(SgoQCTZ^=r=YFn;TQA}(44GkyX39>Q0tFQ}_L8edTJe6Xcj%xm<gfaAb)$O7hr znuN_pYEq$3)Xrz9-))m)Jh1Pk&>Y3_UYd6pRm}@F!vPG#q8r2fbCGNlWHXiZFupu> zF6hy0>(9<7*E$9^z?vaUAHA}5OwfsP8MQzWr_4*ag+j(TBAl&M^>WS^h0n^-$%Bj= z|FIHm6%x4WQ)^Wb20AGhi$$#WUkQMpM!S_c@lnt64lI2^L_<JC&?Yo1be6BQFh9Y^ zm8Evui~2HOe2(T}AH3*akVXs}tPH~=IV#ICe(gou908JI9$%7yeOf7{%RB?$Mv^^g zV{Lo*=dFlJpI*<~4v>|;Yu9sHJ$^1ZT^_P3Dhh9ui)aO+LavL<IQL}v?Xz}$k`HmJ zXVPGl90Aua<_rsP{TkSV>?-#)BMsr>!h(pwWtsV<myoP|N&Ans+UV@2ND+|TUI66; z{5*+S)o%XZVpGW4Q9lG<%QaSM5(@4)iDr)jfq@-%0nOLXk)?pZSi){U?{3376N`tJ zEL^bec-X)*x_tju!fDU=qz|8{+Ul$`NAFYpa9Ol2dp$aX8o{%RNFMvr@K=Ve`@VHo zq`kGoZVz6&KWFAb=0bfI5c!m_pHw~EV>gD>h>T_OVA5Z9@v2W1mSB8D9G}`VhpFk> zm1gXHUsKex7j-An`Zn~uDYgds6IqYhHKITFF~Y}QFkXymWY;rM9lAIhf+|?4#qxP4 z49}jQ6DqZNbg8PX3&-fdSO<4E&ssl8wnQyIYms*ewBW@*TSMgVOFMU;D0wjx{~MD3 z;Som##IJ~m8${Hg_*L5cWQkL;c^CMmZx&lfxEC#q&!e-b{5s2kFT4i_ToR{LAI1{H zVM<b}qbd@Cw~64fYQVK*;7XCI_RQ*DSgtJUI+i(I;G}jjhCSzDaza2nh^KRfa*;*n zlm<tq(Wp6&D(KJo{tLH?3}ci!gt+P}z#a}_`2Bpk2EHV4wIujH9a1=Y;7nB-V?0rH z$$(Tp=Q5mC>!jT_KAb$&Zu+z8>JPZfX!JSvcE*YaXV>|?-RhSSl(;2KH={+tl?R_R z;>2FweEo7dL}UG%)|wtmv-uek*Dy4AZIU=1?lhiPX4C~g0tAQ<r=#E|tu8~SE#Cd` zb08gfNA@N5mF6#JOH}?ivqwP>(dS3KU1^lKD`stXtU}mP&#+x@`i<lq;jfOfG%a6e zIfLKVsM_g381_%Hws-$%SIKiIOO%7BHX|UIKg`{)Le^SE#i75@*2zlAPSlW#<iBHV z_Yca?0<#*C8VG#Iv_Hnn*4oDFqp@*+oaQ?d?_>L2E47pd#}g8MB(lkqDm+u=ViaS7 zj+yh7OOG9BWchY+$4TlWG(yK`E^4PO>Jo;SvD{{15_cEf>tt6Y<v!u&c$$=6W7zt# zfY{gJW`Zr$v<$g-d_np1PC{7<T)V0)u*SHP^7z^$pNLJMQ-a3G^S1oJMOP9l<kyUg zN7>{Ozj#T-wbb4>;e`CgouV^oi_~aljJr)nt-BNStq`dAYYn-{7j1e%q}bG7?#YEt z-0f*a%dx#&Bg)Tv;DlN&Xz)^+_^Gik9qFISj(@&dV~wf{IAgKFh_AEM;Uw>cZO0=k z9n&guO4`Scn_bX<cpB^P8oQ9PK2A^*MEonq4Xj#T%Z<4DhZ6-!e}@^vHW{n&eGT#> zCk&wv_B>sV;mH>DHPp!&&IVgPdi-emj-ele@#Fyz^D&|f+!zNYD?`A^GL+W9_TS~1 zI$M-?1uP#eRMm=-0P;m>9JP|R$$Qh3xj+y_8jJvrr4v#nAcJGe=(h&FPn<2J{DySH zl}J5Blhl<-de729dTpIf;AALDFeW~tl$+LHDh@xFs@yW+rX^&JTKNRufTuoeJ2+Js zz}Hq_YkP4Z3IVYp4?es&|D@W^Gu77Kn4#+UXQfIDf=K~t7`Y1Rr3E^lH-<F*k8$tA zc;KHj<?8b<n7kO}-R<_S7)$fcZzx^a|HF}#Sv^RId+%&8e_Tu{K++ov<QRt+P}YD= z8f4=ir*k7&(`3iSqZIg_o{6V&Z=CwN8FJogeo17nSDQnHkY$7-?G$Uenj|R0?*_X( zYim~AE1JJ$%quy2Sx3P$ZvtJw7U%+3!ROB*Ntcg;#=2iE)+h9soV+fVb&{{~##r*b zQTd`dd<pL^0?E44u{hg}Th=Vfb$noQB|EP?Ks(I2&WIB=XxVVh+|FYi#o7C@!qRiu zZO6~}nX47^QWKabFkrnw`oV^tf?m2D)%U%gzAFm9_`+1?`&VY>!L!@fTUZ>|`Tbi5 z_*7L0G5sv0w4n)kX{o78Sidfl>mqR`dABqD8`Fl^ScWZXW*?Qxe{(&5EJ^$arvi~j zQf;ZuF=P%g-HzW$hN%V-v0sc0pEOtTIKED5I_w(&;a|x@kzshuUccjWlBD-I!}wn= zcb%Df;la`g?g=1RuxZ$(YL<_zIOjC>5N%hqbM$-vrS}J~s$;i{kPY*wRRg<}&wlj& zNEj}9I`tv9{Z7VPtEeH?)yGSsDgiv$NhtA}W10tPn(Ro-#a>O2XT*LDN11ZEnqq1P zND>_3m51zrr%C+0nV{}Vr&m%Mf_;cmxaDFZhb!f!vc3zR18J^2r~Yxbp>*ZRU+<nm zzm~7m3=prr^*TQ%Oby5E@bF>E9Esd1aP3uh&8@j<bC-2RYP&#Dl`i~h1rapC87lED z<`Ls_<AgL$7M72j6GxZJGW!Tu`z}Oyxh=>toxb|*GRzn<tL!<)RRb+V)>&{&8uW7& zwu`?`&WgURbFBHNt@1totZb?@S&}IJR24c2V-_5CLI*m1ypZ6O8mVxJN6qw+H-979 z5fA%0Uax?Glv|5OILYZqU!LlDow%-b^C0%>iT)hwVG_Q^TxM?O-JC|v%0Vp`oBGH- zr^7`;PyVn9P@N<R6EUBu+ljA|h*caR_qwM)rj^;GMJgN~t#*Pe5G(}!jEIL;su52G zP>*HaOFB6lUC>-_eGx56L_2;)2|AM*hI^oVlf1carfm00zBz5#3$>DZN19&O`!ZKu z!%IC>L3A@RQ+FBFZqY)?u|FPf3*aB#RaPc7t?IaA<(tRry(i+`8jE1T?xs;1!_wk< ziuz*-xG-y<v0g3iH-<-#?@*ysM!O9R-|g^}U@MHv^~f{v7CFb7wkx2<3$J`V#;bdJ z%9Ve#Xd%fi>}%@9-;kr^l5GKpItnbf%x@IFv-zMI;^HGhv=#i3;b$x4k<#rba;UH% zryx!@0hT|Mnfwq0Hm?fan|YL`Qr>#uCa83Pdp}y8bH>jas$E3MORe@~Pm!&UyA^4q zfr>q)^pt-#7BbUbYcAGtK>$G(jk~24$#@bk9XRGWQy;&a5n*W1@#cNoo&5BG$jhuQ zetFUUXX`Cq50}ItBVOU6&boSi=+%<W$Y{}Qdv^BBft;?Vs&bQs4Ig0~U(Ll`4un^a zGF8W~fir&JoCD$h(p2eaS5&KPxNbf<N$9SUFD|n8?@%N&JlSEd-E4BfV?xyW4Pl?% zKljg>4iRlS#<6@k0iZ(w6PzE!cS->VkS}JHiUe7uTX@!~O}{6bvX0C9)VAb8FGp7z zlR8MxahONx4=nmgG?9WLuL9@v1J=+72jSeX<=XP5y~W*o>NM+xQyI5~_R<bOvs485 zS5WDL7zk`N*hK^=D6&fx9H#!nAsKO+rUbV9>^t%%S*cp%Gh+%O83v9Cu+{k(>KZpg z34IWf#U=;5c1+BIUn00;pKeL-rTB3eJQ?ENVK5Hb(jyiqP|Ca={os)EbeTz}ivo@$ z-Dm0U649FT%lp4H&SKk=Y2pG)^#gw^gCNfOGJ6mW?BkR#<XW2hW8;Y^=@HulcI0jj z!OO>m8}?f#3}{2fB{H$3vmn-Bd<_Q5rqG1r0I)29qa&zk(nue8lpc?)GUR2KNtoMr z&adhn{D4pWqyacxg3~7I2m(}s5%e&ClErxu3!^e1J(Yf7h<o0D0+5P09?c}H+Es)z zj|*;r>2Af%#3%i*Ewjk3JY3kuZGY87si1iNXGi$n)6I~30vr*3*M`D;oIIp&J9>|; zPegoK$@uy4)v!T=&#togyc3Owvk{wf)7YHXw#xJm4#2_}Zrv)Ey1PgLE~IynT|o%~ zq)#WF0(=9vPTE_=eowNocX!UM%RUj?=ibS&eVbC~f_nSRQd$0-NSx2|?cUvHUZOIP z5#MlJE0vK_QtqDY?Eq!-(<Gwb40As^9_A`*8P5=4#CaB2`g{HBVEKHtux<gub)rQr zc6ZM&MdKT{1}a{4T3uEy#Ii+_Qz=L*Vlp~??);!Z<h{r`&#({K45d}q>+8||QcvbE z(@l62;Qzr6VS^L)w2>8$iAvy(Yb+!x?@fd-tYmE`rqpok^*cBxWPYG+Nvke-Trj9K zq(qE(-WClC<9LETo%VQ+C;f*?h$~O!be?_)w)#Z9BDEjO1i$MD&JM6(#qlTd58%U~ zhVe*tyAvp=$5L`N;kM@OJ0hQD2&Q#!Kvt*1E8l&?bI7VNm2<-<kV<X~vya%NB1!e@ zex#=1gz$de?ABmpGG=d2_vt>MIC-GpmTDri>w?~~GCX8GQqXWQ-$;2GSDi{&3C~z* z7MZ)rJiBA&sK%FR{>LYCnPm$v@8q8}<(nE`hZA5sMmjC3`$Zm&3|tJ8=^hbvR<IWI z|5%REBfcGbhmc?Bzwpui#@8U_TVnw#yJ`|-a2O{fvXtks2w!3Qp^`n_O+4=o85}y4 zaK7HA`N5O9q9K<6vg447)X+&Xyr9KN&cke3O49iSE04l9@6TAul7%4kJ7NzoY1n3Q z_jy-VpUdsYI$SV+z&EP8@v2*mb;)OP`dd;U9?Iz*R<9USGr(=O+WyOMx3NS>mGc>h zZ8jq}!wT{XGN_-0m=YileY|r{q{lqJ<8komT^~u&F}oowk*GL=1+Sk5(L9N`QnwZp zxTG1{WbM%!jw~-(HS*mPNa~WQMm@u!*vjoK@wy`44Pxues!qLN!0nTK@Kio$4!iui zko0pnm2BoY#FSma+r-^}p=9s$_kH7)r^ylw)WgM<g<aB^JnKH?Qu&NMHaUTZay8<Y z>!zqY4LwLs`xv}#X?w!79AR?z{DsxMa$!MI2|Mw3muk%dhaDYC-xnmri<X?)<+MGD zQ=hel%U|j3Cj{43(*Z(^u8Zr@S5%LaXQfKtZ9C6-z>Ot`k(jtsUd5zl<y4YkUfV6r z=_O7xzqyJxH}%Jbi95-^bilK&9Q$sMZoj#>r=8Pc4{=AicNkU91g;>`K5grAG_uNX z5B+duKrlnICaU&a<l-<I;cQ`SR-0jZ@OFQ{=I9<zyKlj!yBE)h>9O3el$<-9C13HJ z*j3NB?f8x5h3pVD>^(OVl?ZEdf<Sz3w|%UCv}^88yxsXiW3#NH_`Ckr$gd@7R0R_= z(;kaH`;(0-AHuC7lcBOF^PcyEnsZ}eu!#Gfq30}H4#}FttBqM!?R=aF^$YixW5^q> z?egsTS$^I#S?<CJHlLh0&d-=V!jb7CN?BM!&rwhAlw){b5Kbt#!6=I6zfr{LjWr%e zK5~9N!`Hfi?E_~Vb!U1ph1_JZEzJFqbeSoZS)tPT$pWUY(9_P!g*Kwwv-l}nd8f1C zX4aztYJ-tU9$D1#(-B|p;L6ZBJ|uK20wd#+47qv51hpxuK-kJ3p~>J*pPpiL+&ty6 zDD`{E`IDM{Ev-b*B@(q_KR}GX0fgL345%2z_H`pw5>C&`We1V`sk|wT>nB#rzk4~a zA<94|B@eJL(#Z{Q@&kd7s0muJFEv_xz`0xm4*Uy9unZlao)WA&>Z$Z*`&azeUHiUl zUr0dorEL)-(ey{56na6e<=Nn;#ov1KVUkZh`v~VLa$n_3hVTEn<QO2j>5^3pm7qb+ za*ce~qNe$skg;F6M}o$o$-49dKz`7B<p1HGA12d+)Z>tAlV-`T8wo6ltTe~6X96d% zhDri!=tZh$+6{mDJ2fWy@?~v?3jbfc*?46oFuQcb3W#7te-B`NHcM4G1e~+F<OnUg znq!IV?7-!<t*i$@T0sI0A^j10d4Q^d{|&i|kc2#-xseSpv=5=yrW}$@a3CIE9+-2@ zBCZ2R+J?g!cW5(%WrFcCEkVQ)G@qleP+X}WbEI50uO%RK{^pxqoB1mNijuS(hjJT0 z3@+<;Fb%jPW)|U?5w_nDr<hfNQ3(iro=Os(D_V}>CoNr@9YlwVfa5Zb1z?u$-GV*` z=-dzp2|@tB+b%UGuoB@#*smB$>*bGs*UW@Sh2UT#Cq2P(dRB2xrk4Ru9*E0Yn;G~X zAPKq{FyOqeQPo@#<pXPbG9{adDdd3R-w+?nqNwq8h~Y`#SEN<wH-#-*o5{PYDu4|S zhb@6$Zp$%*0VgK#u|M>uU|V6C9`e}D>W)meNLZ>Go?4bQFQ2)k+6lxhAE1uKmI@}% z=<n<xsq!+b%%DX8pr?t$DO>IWPCEbq{wG!CF3&(pFYu4ka$rtJ&{rMFqjRi+7K9?e z_4|A`lqf^lfrD->miUh5hdr^?d7Al`FZ!~~+6r`y%RnB&)8frXHOCA>*X7-pHm^a+ z5U`M2-Z<*nogn>T7qHqCxOH}rw%m6>44wobMpRgUlDWv7v9{?}?O^yp+fWOAFgG(C z#aHXEcmhIkCt`#TY?gT&0wg8fhfLk<l79bC^wtZ>03n9SCBPY+fZyT_>;P5niW<vu zUkZ8Q#XJ;mN=^TW^-0z7<Vw6DD7i1bRUKkTtpNZ`h@{$*CFm|e&X}Ci>&1#QPR<Os zdoSzVa$ibE_1r@(e1|t6B0zE%rN|ys^B5sNA$7r@4m+6}eJnh1?g+~_Jf_g@eZWaX z4#-g%|A2Ty%b}pVmPllSvDJBm9C|ep%$~?0gBlO*r1k*LlHlflo($gPm@b2_j*E}L z>e2{BM?Ou~b@lQ%4ds&ARbSE!ML%K?3vDo9#tnjQUUKU(y%oKj&~zpAm*Kh8p9i$C z+5`Xc(YRAtPI5A=Nu$pnK376!f^C)c(8+ck1NCZ&N$Y!OsrPADz;jMN>B;w9(n%54 zb|YU?Ss=94GhzyXk0u`V99ZRHo0ovp5&G@6<sFAhLt2hLyK$Z?-e2G1-@e+{dMv4J zaU{QZ_qUy5iTD?@V4q#qo!hBCjjJ4UNgG#SG7WP=(&<>C<r)d2<>zFfk%XTavr{^l z)k)|WqAFAZvbk|m@M=4cd$Bq%icdp){1&lj6#!Ft#O55gOqbPosmh_-r=XC@NK;Ve z^Ji?b6~f94$T>|AUqA(Hf@S&80C^F)02?v@72O?$wWUhlYQGZ;5?46^W{cTGf>ydq zb%^Y^eqnK8)OHOfyv_E99pU$JavM<o2W;u#4B+=xK2Bf#novAMkz+3TU-qzM8h)v` z3;;Qz<!BVIUd{M+3ZU)%n?U#nBIlbF=Qp2H(yHdYswHuHWW2)oUp}0xtg-9Y%86bR z&QCeh2S{fcRr0_p-%>(=u}?*mj3r&6yHtlbcspH2j>}`4$C!FX7ur>emoniS*h|}$ z4ZL=Eg;8|qg5LfEXO?yX_;3i_*XS<QA;zs9s~PgA(PN&HZyK&)&%rWX5dW2)uk`&Y zTsf87^ZvB`K>+CR=NdGOKD7bsf5&K?aRG$m*kzVPfWZ=pOq)}+qq_v<fckWFic2xE zV+v}y+TRji#B(jC(v!ACBI5>nXHo>_r4=rPe)qI$EIY&^6omkjVM1*{1i5hq(*K|} zcU80Q#hj{<%s8v*&+Z1lv(|;!KsL}xl@1Si(uQ&<&kieCD7-0hiNRi4!*_u%T-zX! zEu@k(%-?R1&D-@k{ph<8f9B&F;KMTi_F<O`IWd<z@D*=geqwGokCoI|0@&F{2LZav j_W`2iozgQIV}%hya*?uWH%~<ESVFsOEFZl2`{(}yq|Rxf literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/80kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/80kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..47caee401f932085e469923a84cde922fbcb2bfa GIT binary patch literal 135723 zcmdqJcU)6h*FSoYCS62CYE)1WR21nVK^R0tMMXfmib@kBy?YQr6a|#3DAJ@!v(Q_l zqew528me>&J*1r6&CL5g6K0;7dw=)-ckv^ivlFuSUTd%QU3G`{gEj<hJ9}E^G{nHb z09^zBAX*=!32gyG28NB_TQ+`}7&m@1GchqTu`si+{QjSnZ7T~a8!HRTR*tP~>>EGe ziIan!b7QbE$sZrx!pz9X%+AWf`um^!AN`_zfq1uWF=XUsWY`OB;bmatWuVnSC<tO; z{(XB4(Et1}Y++<#W?==}-~fM+zYT1kkr8Z~8SEJRwJ&%dV&Y}qzUSB}7QRc@S@$~b zkbUqXajUq-$4dUoZ3KzqH=O+0*mnx-5)|6E|A6E{DLHusMI~hw&EK?6YoF0MtAEA7 z(CDhMiPg<px2<h#?VMd)-P}Dqy&eVxJ_>sLBse@GGAcUe<*V4F<aa5lY3Uj7KYh;2 zFDNW3E~%=nsjaJT`1-BAqqD0U_oJtGcw}^J{O82v)bzsQ((=mc8gZSpK^FtW_y<|w z_aB7)g)Uw|*OrYlVBMgLVT(KX&&bQfyyqCp_EVQwuRHSXm3^>vhsKM<kCklV$1fB3 zZ#cEF@05@m-nXzp+V7P8KO@Zl{}pBbA?#1OdLd3m25@+cybv0qFqYDwuwr;78CD5> zNB8W<J}1Ys&S(nb_L!Nw#j;W!WMgNZCvZew(t@1s%g~_bjWA9=tE6)QraUr5inDLE zGMFEDK!Zk`VbU}@%GtHu1BIwg(4d^;^@}XyJ1(j3x~~M*(uGNr_y!|I^8=yi(RMsi zqPWQ4)XHE|!42lDr+&gr85?8{&98I9efyC}hORcP9SnLks72;tFcsWsBw(KQ7(K?} zOoPm5P<qZ0KlbQ)1brR6nMs+J`tx~`u{0@I63Ss8Mbso{kPi(~nYZ^Z0y}tu#-p44 z1hsZtWVKJEK@DPkNKtU1fgF0Bu@A=a8csqvy0tWDQ5Yuu#C|L39V@e>L3;|p3igzA zM%iG=1n!th)WWDD)eZ44nBn{Lc@oN!5uri#<%Q%qO5ojYflzpKu#dWmX!t3AlT7lH zFB1eaZEW3iJ$O1ZieOC%Y@s@0eoDVj*plJ#6j66a|Kj;6HFtSIfa3QH?niyU$hxsn zrd|vsz<~zMl)%T#yY7|HkDwjkNbVhnvoUKS3UP|0ZW`p#VFTs#X#s|66;kh6j+>o# z>y@GSAI8r3(;z7*e}i=K5&Sy04l)8y?)_}9TZ>&3iJ;cdpjNHh;2_cd@R+a+)g4XR znscKBW&&JNuq6G0mwDBN<-l^+h%;1!LUIdLIxgpFz2$T^b`YL2n}hgshp_7$XzD%m zcS9|Eq70(Z0*K{V+QHDdagLfb_{A;Y2wdUiJ!Y<MYWu+s`RmD<G$@gMG#$!V&Ru5* z5?2LJY9!DP{7%FI?y(P{=Hs*7SH6JrGl9;6S5EkfBc~MbE5G6!3}Un2!43QSkn)ao z_Rs3fPGZtv@@4#Q8zi}|G<f79njOA;H0ab0hPVy-FAc@7GwaYGOIGlj$&akxiImbK z5z!>}?plcd!Dw!={R&KtE}UVkw{*fy(;)I;$hi|xf5+nhqVWmF0f}slE(so|fNA#_ zqi6bQ(4?-p7Q`Pv61EQYZ>*+i(waqscEAlRqm%I@p;lHDSerQng=lnRR~F+*+j2&V zeCbDiN|_<j`r#uw;vLqvtoL2jsNsEEelY$AsgSzm7d&4L2f9VaFH8wgoh`>NUu5N> zhGoL7M<x)8BGKs5JBuC@+vk1e7Fs(V`>8se;g2M3^D+#)-b-Yxd#lhr&l>2X=<2gK zVl9Np(}46gk|BednF5Ho(1*~VTw>d%5pG|$jY&(8JZpRYoUFI*%a#_dnp;=zv%J5^ zvYMGVW3jJ0j3OSZ)t&gVPOX+v_l+w#q1yo$<a6rQ2~!IjqZem_xJ06xv(yrT*XDop z8Mp3ky}SG*SR0n8)4DBEW|hv`n|Z&Lv=-!w<yS9}SU4}SEwUt*@42ZeXJ}CZ4+~P? zg`E@tx^iEbBJEt2RdOru<Mf@wuio$*H&>ljdDcDd{5zf$p=VwpE)2z+_Wl=2c(fpw zw^GvYO{-$9IHI-p)v$VA3MEcmh3VL8M?@iNN6`J2KkbtfxKU)3Aq`3}Z=n(~glrxz zQ?sewm|j;7cYpMuFxgv@#mirFl0H!Y?CjR3LFPuJR_2yDa~Z_n4ZlW(>%!=si@YQm zKXl97`L$d;mwjX;TKk-Y;~Bx16CXtFW9W&LvIGd&V27syDYF0kmn~!*mMgz-B7H34 zLY%=(=2wZ=pcegFw<u9O#Y-1x*z0v6D2!|b9uwjU!335I$(u$wV!_ZabiNCg#MTGn zS7?yXSZceg_NxK8K7WqwTLX&)Nd{-<0l<t7qSsg#6S$@6=})E~<ctJEi77zPrdmzS zEviMH?BWp#54@!oz*noc=?rlDayRIiKuU!&)J5x8b7Fv^oxqS0?5Nq=<GH)}T$gh0 z9Det9Z!pvI#9I>Fo+5@?t`*yX)=I$hg-Z$C_VmmCZ4Whs&--85N|?NU>SimOsr=(i z{Y5TY8e}&GFY^`9AnXhxA2=FDL>?jlaP+T6GW5gr??sJ#l0S3({L!c3&uVLn@rAps zl%~waF&@HHhZb@s)rRrFzpnmM^|*s$n%(}<OAqEo7auPjxcu}@sH{D_iR<qzWC1mb z)B?*f`^W_D(amr6c8#a}j5?Ve*MIrj^cL+M4_+0ELSwi+MrDcsP8#90uthlro>jGM z8l+wtPbT1pwdn`uwL2K<u1>{9Dt>5Eh*L>AoAtf*1H}0C0DspeF38PkBB}>~@!|o( z5j$+dScG)70}(p_P8-HiY&MPTgOdCX>%5!J7MGohVcMy*cP9;E$81_Q4?P`2ZM*On z`OHZ>SMf2wBcZUk{E_nZeMX@=>bI08PpJxFuew=sQ!t|rCaZev#M{5t_r{fd-4iyh z|Mr!tb+4cNCZXIk7?bxEHf)s{YtJuNu{V7gD&g<(?NfZ>`%Z@P3>%^OC$5DUZks|c zKgl8m!?`2(Ahe56QxO3vw>@rZJ{jZqJN$g#sx}l%5?)pA&f8kH&oQ}F!u_Xp)YE$w zd*&y(VU-4If-9cKzCu<<PB8gp^<DAex8hOOUw^3#UAyh4dYoPYvgbKey>30N&Nx%> zt3CQkT*3CE%9V4b2H%NzMB^w8!tqdFwz90zOSv}v!0hA>hBjb?_P_X2VolOH?J$C$ z=z9Z%uC-f+p1&ptGkFdD8<OAJx(VD3V;&uz=x}8z>b&ml@m=e;h@9GHZNZZ>saf&B zr)Us?ajwW|KN)%%m!luZSGTE)x)r<IdcSM3zva54y+~L*Sp7Txs4BzPk>dDSUsL3P zJ9=#xTa`wrrvy15K<pA?XKfgRHer+l`dnuM*57k^y>0s~Yxl=~3EOlIh_KJT=h8(^ z6{1#t(I66A0@Eg;`n!mopvT8zmUj6YH6gO2xfBA1@V*P5){i<1ji5iSU`Wisq~ad| z8QeVjC7Hmk;z|uEh-WUZT|U<E{C$aP0{?EOtp^_JZz8(E-f~f(1lYD9<aXvoR>#c% zr92{hqLgZ4nkj6&|B3%x_>Mzq><pD6u37JARSyGX--RBsB=IJ2Tha@{-+-u&Q1)Uf z*1K{;GCFp$onVr<#yPY)gcu}mTCJNkga(Zr5TJU8QQ0zu{5J96lj>FObbwkt@l$HX zzBI^seRX12^YPH2#T>5^o-H(}5l3O9LAMh)VY-tFqkAq5mSl`2l<`fKJnXl-m|u2# zd*Xz-AHXDU0xUJK={)R$Lg2A&@hb!@iNomdU!d7QekRkDy5C+`_~p;2s=45UjK{A( zP-2YuvcFiWm5@sbN+6*TzfOjK=gDZ^fa0aXPKRFyKD-jwiHaNCyT$L6M7R=v=VolO z!!B}c9FHw}na}Jb<o>5?bHy!wVdj6l90p5GABGssh~a?}o1f@oH?Mo}<-W$tFEu%1 z3DLyNs*<_>x5BvjL%Ls=UK{r)`Z}tk)R9g++X_}}svs60C|6Tl`l<gw$ky#;_p6B? zrz~X$jV)|(GS;xYglyftg>QkzdPVXX*B3bIy>6$wW}<f5@eUln>sirW^KtF##6s>Z zqReRdiP4<TG-zvKEf14zZ(!%PSIJ#Wdqn1Df7HQ@VRldr^-W&62AA-ag{}F|wJ~Yu zKWPLp6^eM_RK{O5Dqi-?&Cb4aXV$^+TXVZoqE_$6(|(d-FZq9>1+Nis)s2sRwBHe> z^<o!SHH7S+8;f5%{zA+#-V0i!qKDU>uAJw_Y&V{4mw&@3d$vYKEI~|f*h~P#PrrCb zKjAp9+qny2Bi#8`M_##ROPQW6HQ9Q&jRk+|!E?0G5?X|DH5~+A(bns&ETTKEk%W%= zazS_Lyqz59FGEkCJ_{TA-Syc*@6~jt+#;6oCB5NUx5IY(DXU0UF3W)#pweOdI+rQ1 zvQ#cN*Qg|0A^xCe%Qm^uT7_@x4yINfIMNo;tjwr1WlkW-2`J!H;yT-mE7|8QKmU5| zHSAa@;o9N_jlVyEB`(Jx#fppaofbqECC&WMtlPY5^#gZ}4!`J#n9-lcb8S0yxXj3b zFZ-c_v8=?sz?YnFLQjT39x41dJD6wr<=quN>x^#&(cDSe;dt4_gdymM>RV#EJSNC- zN+Cjb|0fHZu0f^lK87gAuM&g{Ue{V#kD1S5Dc<!6P|!+13Z2u#x)Gw(+JneXXd~9F zdvDO>gPME&7CoNv-b3w?AN!2YK7a~m03=~1%%XV`b4sh!L$<4ijbbL$g|2|Wz}W&Y zI&2a>6SgA%#Pq%*6J8TU#E0OFtaB($b>{zg7xt{It=(%69&GO)gV|}22{f6W6byY^ zh@m{d&V8am;$|tX_m446_VcXY!8YIyKAg0HG6#i$Gck@O*RKmDKb*8%dsK<^6^;@& zyo8=hVCUQ*mK6gb2Mz=@t>^FM58y#08bE_qKr9QiYd=q7!j@og_PYQnCnn)88FEtG z`KQ#&G^pfYCuG!yW!%>~Ms&PcBCWmnOW@S87Yg@%$UiHba@^3nh=o-pO~VA-<J>zw zUtfFV7v1D)@ezX7a(gp}_m_`8KCG%ceE8szoI7pdzmy&?8LK?w8L3xw&5iw)eIzT* z-n7v@_==Lp*k$&34K90Im{-*^+0OcEhmUc(wo_B_I9XS8qMz>}5tm2Vv5@*=VcsC( z6!F!Nxx(t|H(nLHCtFYZ9Nl$IWrYL`LnSpnujzD0l@RW6ZPxqeQ?l>wUi7Q&6Y(NQ zzg9k^GZRZ1<j^&>cl}&g5ULb)@8e!5!RtoZ=TRXK=i&Tip~0Y`Y!%bS)f*lC8LlBQ zB3YijJjzXwXIyUeyuhG`7iLFg($`f<77N4Oj?)ZdVUA|M<F+^t^&Wud5U<;X3lB$F zuxX7cmNVB(&y`wibpWb%fyI%CdqwQ$OaJ}A(W_SKyYeo9V*~oafE}{LIxp+Zm~%M~ zvM`-&*1ox6-5HG4j)MaQ0+TaC39&cSdj`w{H+lxZp}4w8_WvrXCA~GaKcUes$91Bf z<eEKF(x;QEdHiNLXRaM8T$!V6Db&9-dFbk`&m~<L>(J(1_ivfr>%i!bGvq~!ppL5o zr5)d7q;qn}UpP3FK6Ra|Ql>=j-%{)_oyK@T{3pvh93p)B5N7YAxg?vs`iP$wf6Mw1 z6d|ZA>SYDuGJ&L$Im<6XC$k5$_oZgY{+KGv=5;R|IL7#aq2R6e0#&M_n6MysLN_|* zs;nLq6`*@pBT|Q7_Uc=<e(qyGe)=iL&UgIcNx284uymRHa7vwHBN*q+h8rwqkP6g# zY_?&3!i8K{pf@r+lqLhfK*;F&FlHU9q(Q(CwuU$o!AE&G;0AUcq5u+L!>F;5k+G@+ zddv3|DX&KYx<X9V6qu$RufdJL_iv5;_yHguf2)T8Vu2k(k>#Di48W@Tt98AgwoqgJ zRM<f-K~@!L{%)Wzxq;v_CdGEsJ|LW+d*RN83fp)XA)2keDBzRZwNx(4Cl6mdUCyFy z4L%~|r$PerNKbFFY3?ey6#rlF%)swTr~s6Z?Fb07ep!MnSaWg)-E+d0QgbMN*8VO$ z{yayj^gJV?-i=>rxX2RsHa^4dP-9xpdF4yd+v-di3E=2<iVvSi3stptJ^Z;*Q1`s- zQPrLY)8Bap_~9W;4W8KpeX6)4f4wQ|r}@YwHq22kpM)hd#TuC%@w+^7W=wP>Y~mK6 z=ZonooNfs`Ryf#3hCyri>#scYHq(N4*J+T}hnL&t_6!?|u4jwd53PNX2|(C7DkKox z{oS2qnwisIbXa0zwr?GkxZ5M*_=&(U7S8MwHsbxnLG`!7iwa`9LxWmFwR{b(leLj= zmU;2jP12RvJQH(Uq14yg-?_ifExfnuQ26dUjG>yG7g>Dqe(0fiyf8&3-JEg~*H;-E z7ghWM&O7o>OKB=H>gCavwF~wQur>S;*-gwHRW9Qi_D+9iP^{)kY>9j!!=jfsdjj`q z5UI3etdO)(6iS<&S;&zlr(gWk+vF_rP4Cu?qMI!l{J?rMtq=+lhtOOUb)@wZuf55g zCZ>-smc%7)j!wlwZQW|yky=ZZaZ7HW(+i@58SmdeaLRN%a*+m=a&Mus?f*=%CLi>X zCO#Z`8iqoe1`m1Xe%@o7H+5U)4QG@f!;6nSpJUf2YJ@^ob8{^0yds<S)vO&^I`JmF z=FQLYv{go2zPHTNB^$#}%6a7-{R3L@G1C6oVRe4Tu(#rSX1<_AU8zP|#0ZS<=ko!o z_V&)>{5Q@h4^5=FtYMk4L$M^+u@c|;n!fa({u<$Ry~*QOMR<|SZjiL?DLnh39cznv z>~;I)mM@=%w=4_ZfU`a4pTI+}j7am3G5LuL$$F2?2fiMCHZ>O2Uo$#SZe<O*-#N%f zeXT0vo^oJzW#oyx<akJP(#>L91%>+-?~6tXu-D<9i3`M@(es-63)kZ0&L3%gGAO7Z z5LGe#YtB#BK7#rVwziM&nXiqu;K%T5W}Te-5Ou52FX8e9h0z1@%S~~S@TZnp2TW4J z!Ca46+3)=KD&GlO(I5tWK(&%gZ{Mm{8^Ss5bw76~;>2W0fR;h(>+c68rxmRdMS>Ty z;`J@B64`L85!8rWRaE-JBcBs8wndZ2pWhOWHyEk7R8$z-?VexsEbB$F(Pd>O5s;iL zsr^t|@%dT*SHbh!4_NNk$f~t!xTr0zlw%;by1@U?-l(u7FiE~t#~H&JcI>%yAQS7I z(X`86Mh5RSZPl{V_RW(LlWUq9IUSyTKp$jH7u}j;sn>ZoUpS^K+qJaA6;>|Peso*o zV|xD?>)Y4AOhu?~hpYA+d6s#Ch}axSak|E~=c};)^Lx&vs31}M<HoP`+j1QCb*LJo zH*$?-N${Py5+0T}#-hy1|54`Aq2(Wgy)(5cg*`brR=m}m0b7jSG1q>4MV)=b!$@?= zG70&Kb@^~St!MQ4aoO#P+ubrm;!_|S?Oc1uv-`u0ij6LA`4IOB8gfq`?_3e=iM3yU zQ{lcd^36of{rv8J%At>sdO0GyUj>9JZhOdJ`jQ6iywuU1-ZX5^-Yhwv;+_5Z>{I@- zmz>3SMC&`I)J2;0GU$`#D`+8`=n|H^RRt%{CtWu!i>j#+{YKGdaD7eueEftuC&;cd z7PNjv>I){2tHJpZ({`yr05H8Vq!FnBNKh@c7%c!IQ;=qui3M5b8R_tiQUM+*&RtC4 z+{lKjV3@Wax(#4G8sBQzt(TFd#{}0u!>{y_*!vO~4|Ia`xsJkW54sNDU^sW(V*)uj zhs9&YBpKgqENxmD5Mnk2BBPzijS?U#X1Nd1V@KebryxUau(5oG$FqpU{xKQ^Avbcm zWO(5Q?g?ror519G1g_foRIs<xc%(FKiGScGDR$TezrM8(cuy|Kjnem!tnYa+1z6_6 zYpOk529zAzT}ZBbt<LO5I*9Js3F6X5X2hVz$RP>LvlmnlWEK;+gbyp~cj|Jf)p@RR zVj~3a_&Qny4sm!O+$F^Nx|qw=Cp-5Y&P(@`E!i&ni)TQ@(FoZ}xkS(o@HwUslXJo0 z?oPw!MFE9xPB<m!-nDP>aU9WJunv}yua*ehANlgPpr{MgeZkNwyqy9Q&RGZ*#Z)1? z3tt<0blu6?$8_TC7&Eh8G08Cg3Brvu!%URJsl<-eJX}7S&%We+OlX6d?niEhTcJul z_cEW$UO1UKhS@gIl15Ch?5*gzW-}I2z6&}<sr9v>L3!G<A>>OQGG|+1n^Uey_ChYF zw$Et>a{29g_c%-8jWxF<qqq^#nat>8Pq>|u<s-j<rtB$+3t&-?jp|6^3sscJ>U*H- z6Qow3;;B8`MzF6z3##fJcvyDgp1;zBbt!iD%aO;|?yj|5A1wF2LVcjd?Q@ne-dspl z^05xmFAmf(HO{em#a6%d`%6i^B9Mt79$0<iJA?_qZ<BfV>6pEtfPU?vJ8CW-i4B(I z894@bW1=~Eo6nwNF@c3&SkL!%FZ>Ek@7~(4F#lo$xFrlN!)VaW`A37Y1PL0n9etYy z@t<5)XlPN3lNh|ME-3ZR@7ovW{1RM?P~3QTa(WBwdt67Z<9MU^o9G)(I=LP+$lu$( zq`a_}OS}3*!`v<Rl)M;T>v7I!iKb%MW2g}5`u%V4=lJTdFn6!o!kWjJ;3->S^}|QX zvUWDl5}enxFf9aUge}G4M4#S*#<+!o)U>PiP-rsMz)N5@@!bzwSg>NB4as8X;Njou zw^{gkhO;j@=p$?o(k-Wr1n`8C<?*Fd>t2_oIvwCJ8mo)RlP?oZSKSB|`6<=plf>Bb zXWLB;9ZroE%if7_{4#DNa-$^vhvuqN`+Yg$Q=<i*5TE7N<wnbcv4TFIC1y`Cx+$?I zAD|AK$;=6m(E~mV3tff&JWmq4C5rQO!tFiSIX~_`BI`L)5s!1QqDI43PkEreTk`X~ zHTT;-Tz{y<bsYY3<^BD=eyTI8`9y|PAN~c=kcj}*wKn+^K7D2F>w)_$%ThizJ8dPA zjh>H@Vo8m^SrTn?d$ySGALlHY54sY-<n!}Pj1)X{>5cFGs703-WtZhHALLBq<grp0 z24YP<oti!IErcg%?x)rxjWF@U?~kej9G~cu|90f1D^)qabY|{!w_-k@xv9qdvFGcJ zyD)K|Lw79d4TyDh+dKB^<n-lF)i~N*)P3`zdS7fweB{GwNmX96f>*xI@CiFN(g2~P z>xh`R1fT4kN4s}D|87iTtUq~TIe|?(;E0^DIDUb}M&@?p?BcCEpI&K*1)V7B_x34j zwwJjSuiq}Syp&3ezZlz1Ej$`~`CU|G-6@90yJsmMO?igx56hxw`>;Fg@V84U4E%T9 z+;jSdvHOQRH^==ZPudCVF%ez0Dl$BC&9d|)ZnrCP&h5Okud?@@NQ^kqi%(sMcZM{p z&+&NWY2xlWkqbRjp~cJTDV?rtg@U=MzUu=e8qN_B@fkl$$Sr|x3Lh(XcbnIQ1xY<5 zKJfUma(El($)-zcJ6jzLdlzpP@16EAl(s#}&Z0Vx4%#&f!czcgMXcnB8H==0E+PCW z+`f+NTT8q;(o)oV!Req9GA{bh(pt#w_}SOM7ac%9&jg>#v_&nlfecly3!;(L$`CPa z|9ruc5|m0hfcQ)2=4jT!i(;=qiEC>D=kx})hcSiAWgLaa0YXnon}P{GZdA#3XP{^P zcx49!K=;c+&%VP>-dLp3bmc$wHb3Q!2^3VfpXs^@j6;kws16=>1v3=?UZOM9BdwuH z+i{oFS@bgAiyb^bW*L3^75q)M<$tNP#nIK)@CQ0^JjnpAO>jtsJ`K{~@4v{(>P~}D zP5}2$Bd(%u-MwyaRu@XA2*-CYeGJq&fI17WTD$_zejiLGV29O3<o{C&&wxKIw~$zX z$-skvfqi`CDS5{Hg1xut*Bc=yHW4R&1F<hI3EUOI!!#&A-;%`E595D=!V8*y0Cjcs z>FNo5=^b+_f9ZjAekc&BkAKayR_l9y1ob0gsIVTh)%N}&>T4h8TWKFY8@%ma)Zg3i zW31t{F$(w0+vxkCus;X&@Lic9ov|ZdzRI%PvF_}yh!>yQF6fd<mKMv#Eb^`2@Kbw7 zje~EWJh7_Yi9rtem=H5l5<<Tw@9Yle55rjK4wZUI@>e1)=zNO@$rPUjqbDmKCMX_{ z_{*51pT??t%!5)@aL=X{6@@BUjb7yxER%KcVdNS4@5CG(xxUBA9dG(F_Z<2l>i1?v zDS_uB#goiEX}L{4L-jf#V&q6{w7{?1WYwCIJ$EnEog4G!HC5Y5$gOJm5nttw?8m7Z zvt*9w7IEIw+R4b*!z+8nZ1F0tD%#@Mg4@eSCr{LxM3ubFWL|#EGiJvTzs(*O{_59C z=~uHA&m-nfC^`u|pW*9aI~4L4IBMVS?Vh*N$-TB@{_Z(vc+Fbw3$@+T0zvg&Uqeae z*k0$+?Qg6+GgL)AJzZ62oLwdSc7J)%Xch1EL*;I4&1c*0vA6H4z!{73%wh;7GEdRM zdCRy7&D5#iEG*?~-W=6mOjFCIWKN-iVZuc&fhtSB-20-FXr9CJ-sZ>G;Je;m5{el2 zoUZ;d)m?G%QG54~2#oy>&zVn0kFOiLKN$^eJa1pB)Gc_<Pw>XY?1#7)O^|OCp>TDs z!$*JA9>p;o&vV!%(|bKY&y)Yh3AU*hA8uL?mcgrEh#1=;)KeqHlH<v?q$08bHu_7z zjr+GoTXD^rSGyt~nO`2`ZGF;5v0a?$oh2@<WER$+UpwSTYGqBI>Ge^`9}g*8lF}&o zjpyDhkv+Kh&WnzdXrT#tOHQJzJYVKj%UyH7_6PiUD*Q}hU$bzu;JV|SS@YBMX#uZy z3Ts9ky25d}BH=p?cTJv}F-Nbu#T8;!eReG`8c`&-D9g?59lh|z&aLEevG1iD!M48^ ziG6Edr5k9FayAFdZCe0Jrum^Mo($oFYCUp_N0=*(kMeCz6LG5~85lb_SnqDK=X<Vn zc$ZS@c?^cR^ec0jO+(gXgCGAL*IkpolZ*vIEFreuHka-D8a;oVxos?TY@5Dcn)Dlz znAAa4h2HYs!G80>+3?d#y~c`p-Z$A94pi`XE%Ff0$j=@{`pT-`6p?i)^_@#itd_X5 zQ7QvHoKB~T@9O26Kr5v!JT|OaF_+CXe7`j8J$;CLwg6H(=Zs6w6#+SeKYB#c%-v0| z_U`LG;$Jv;>D~{tg?)C=`Hr_c+&hLO(j{IRNg!7kYA%_#&_jea{Xm^}5?*8lsF|}j z8@DIR5^pjc(bs3uC}O(@AjG!!Cm~U(!qtMzjlyUcnSvix7p--&kO66-4Np`aG0-QQ z8f?^b>!}E4At$W*!znmrU(+(1YT!%3{p#O6SL7JJ{p$t<-);re2x4anm-+L}CW6N! z&X)uqR?)nhz0>&G2?k}=H-<)k*}$Kkwlp98^4Tz3>9o^@k_chH2WQz3-{O{Y%L$z9 z(#1$)2YON%11j|b6v<5k#y4~wE?HrGn%wcJzR7xlyCa$|Rq${9G4U*T0=o$he@VqW z#*VQ%gY@i;V!b&BBgEewwYH9}%bs+{6?$bU;M|=Wg~P>^B@Sg*PV<;R-;+w?XUmTx z4*-|fhT*C(`hlNPlOm#_0CJ!M=$ARu?=5UsxAmSsWVlWG-8qBkeN5Z9w<_i6(i54$ zJ@W5>{Rp#?jVz?%Fk-J$^X!_^OvA6-d}%~Ei0|>TrZR$HXTFLC1w!|_`fRX^TQ`oL zgOULvbozIldJ7U^hm01CgSVXHyLWpf0+<CSp(%CIK>lhPWN(LE<^wW_Z9?Q=`T;|( z2WhXz&jE_=j+V41Nn|_I0*PaerM4#*Vo5O|$@`(DiYH`HtfTA}S&q1*_c0`^?Pgxd zt9LqEQJ#+*#Yz4uB%|+$SYcsBdvb9_VW{n{f+-+G_w<~b>}@-AlZzvCobBo}O+`Tx z3=e=DY}*>s)2B^+b|G^?Zv<a^UT){dW4^I%4d)Xkh=iL?r?&*=Fs_<XGs@736pIDJ zv=N(-iU%W2w~b$xjF}!sMZM%1-aSNeoVSokZ&CPAxnj%JW?6Fg!XkP;3wL}ZBc%g# zBk015?6#!-uM9ufzD_WfL%vT(Eq`e0EIj&r;K_YH%IOaM^JTES!!OyHT~=?zQ{8#a zJuofV83KTF4?!(4bI>DI)U;M8;KbfgRhHW*R|DCz398{<hyfuk=2@9#YTb>FGNTOB z#OV+CGY=P865=gzcT<iJ*c&;W@SO-Be}aA@$FLeR%Rj;k=Xlg#?Z%86=X5KZr#$ES zt{Z`yu@v$MyI4+x0{qFhmW#+{FKg1sb$LF*p6)KVEz>`BGy?m6D&KKk$+k+heK$7M z4P<Z}uJTjC|9Cij2eqR@sb^YkZ|w0@o81-zuV1l<b|Q1iGtm>1sTF=i5Rx#nwJpm$ z>5X|HhYm7~El-UR|1CBkrf5m<o-pI}FU{H(U5i-?1qD6ilUbK0avHw0j2pi_cxF~^ zKJQ1}hqJe#uk3+0wyNHAR!7-T_EL-UT7*1))mM^o{SLdllxO3F?Sp5x<%Y$GUmJR> zvX;Aznu!SY`X~`gy>~vJ>~%{+Ufs01rV(_&$#Jp=b<U_IGs|weGUiG#li1d{BC2is zOz+s3;L7X&*b~s9rkCI4>LFhC%CK8>Z?kEkwN!=4DZyJ3PQU;T88i(NEl)i)6bejz z*QVv}jiJ6>RooTIAi3|cg!TCKJeR5N;%pX#v}73EySQj<<r5TY%puK{=Fh{LK*>x+ znmY&rv)it@h@IWgAPtu}u_YZE^dvAfk-wi*swEO5;OQ!MIj$*cB0lZD{bgKriFrZh zbz7@+3-xg0&lY7yG6hrZ!;$-WO?R1zTw9pBGM=9w_Yjzv7p-~MVuOF}a=4T7wtGj& zNXX!UkS&o8X+N1<)Rr0gs}pPrVpD>j<YF9hj+n|mId|h^RzvzJvq$TvT2LO27psS( zyD_^f%FD|aC$8bP>+D|*sc79>X+=48!83O^5RQiyy^YjD_eT!j)!O^x^;=B1u{lwa zu9=@W?uySH_V@K#N#MC!-s-|PjGuF<i1$v;JNEhb?4H#*iT#78FSzrhc+60N-4-|N z?iOdC5jeGL{JEI|8|ik*c!ykjLYxXdjj~`#NZ=L={<YcZL~n9Ip}Q}Dhy5BuTGJbo zYI5vNO@uKSW~VT|0A#+WKRL*tt_rc9y0{rr`i=ICVApxhFY8g63@~(nTVlSYx0ih8 z(e&z|a*9LWyC}wE)!StCPD(O{|10DkFWcnj^EY|Cx6SLD9O_81cRBj#;D(+HewqJ5 z$vplS-2I^Hx_0<}E)DwBtw?W@Ox5_TGN{SqGt}hUO>g0rLgnV;9SNWl^X<RxLwTMF zxcdKz7OoCThMqie-gtSkd*FMe?w3TiU8*<ThVC0Ypk}`Z+4~Elpao8m*vjf?j7S0l z%vIlpUY5_Xq~By_g;-f>Mb}7vc}cj<8->Ynr*HS(J$qO=c9F$^A7q4XO~o&B6$0eu zKz6|N1BQAVP@UMB55lKNuvVZuzwX74AN{L5hdu?0?sn5Y<0qvNzIFFK`$(j_3!XgS z2wHPqQ*0RX@__L^gZ({!7M@H$@M9mLoC0k^ufs@F<|&T%ffzn-s;9anu)Bcdmh0PX zU@Y}VRFh$RpMIpyOxHK(+HRx>nxx1Nkz$b2+qLo8zf^{4(87WvGD3rnn~OsHF{3=| zTjEL6*zSC3nL5yvi(cu1vmvLA51JF^DUU#|29G={RT))10d|)OuYtfUr`eA^bRIdm z4;aJqln|XupcYd94!iOd`yzpx8x(K0l=i{IwJ?yJ%k<A##Um$2Y0y1b3i1U_!y<;* zjfvt(vvw(_I8Y*!2l1eJ$d!aGC3rTtVLN)QZymSK920;YV?%+i+eyX?8|5JTdej1y zmFkG3ew4=i`78-#&ojc=puFn}XI}#)SZp^qw-Qj>R*?chr)=3Rpg|b&??qR0%V*dz zE*j(zvo16)xw-zjsYmO-S6}T=3&Wrh7N#=cIMkT|C8EoJbWWvKBN_0(j%i5x2@XAW z+!c@mNN_N_0Cu(KbuQ@_zS&P|qZEzv&_~oA;W9jlH(RQSkVf$X$KZ)w7B{&9866*m z*S7+1!3@+I&E=id6v2T%L$82WZp$$|1vNDm8uZ{kwWST6?IPdeAu!)h<s;!h1?wiU z1yLVGN^=+Gvp1C>A*VcWiks_=q4d>98z@~~W}T%U#+8Dget+7gk)M(sU?BS+#XbH% zdU#C0D@q~uh{l@b3V{ZF@3Q+$SLXw%RI#04*PJMV40S6GWgZlW9b;sraDd2Mjv;ZQ zEO-nM$p$<d3m_00c6HhD!a$`j$dJ}hBtAp=O(ngRKg)ZN%ML)uO%EJ$iVd_vg835i zow_=So5r1xVNf7Ec9OLX6y{j6Nc6oeKQ_wgmca3TZjPgR0~-YT=4Ohz;4uMkSQhQ@ z<o+TrsQq<KZ0GhoUW?&N!Rd=QKQudrvQK4=0#tVlNIH9(J6&P{vVp7gbK#aXM8lGh zUCM<z*L5hlQ)ceBh_j{dd}n3v`;8Qz{ZGTaIwvqHRzSTIK;jV_0^Go=V+jB^RAGD_ z$RJ=rCP$??(LK>34y_aOH9+#(YfUGw#U6PhWP6-90%I4q0|Tl9gk_zxkm_vGn83wD zJnK5Y4iK(E7vWD!tVcZ__FQ?#SLTq<wti2A260Qj$%*&^bbSI%bwz#i17*ogOQMH& zwZfBP==o7N#4^e6X#S6m>gV+e!AUGp!43CU)oGBoJV=wUT>!ok8o$m4SLLe$5EF|A zu6G;udCpxwIrQ*B9Cm^XWL$=5P%ebbTa+O!T`5b6KTL18mW95_;ksd%`w%;Jj0W9# zO}fZ3K@k_?p)%G}DVT+1gg1m0c`%9~io`CGB%}1jw&ek-I`h+2o!WA`C5nR=cv{1y z`RK`adAk9Lhg+!5NK#P=)CxG71~S|6^OOMWuwLPU*k?x-(<aYiiF-M!`GQPCp;50c z{{Xl&yMbtNkZU~QnGJfG2er0<tqUWbmP3(P!^lMZsL^BsJBseT;&oNs>{@Xx(O>*m z1I0`Tti$HM_l!^r3kS#(>#fXqI>zsylYuNiMb^i*yz;Zn(&U*_5*@p3QQn*pcxWVL z^V!Sqrz@&l{L6bUvZfVd`4>9!GJMhvPF?90W_tGa!g-gjuO3)L69i;txb=&S^o+l> z>5M*4CUA#oK9b?>D{s#8cMn-j<|||rtZxhkr?|E5AxL{I0BIJc*v0#!N9!=8IV!V5 zD>DxrH?GKcS#s5i#7aFDGTf`V_KD@#+UFV5uE5cF;u?s3e6i0HI9vXO1<qO(CAfL6 zN4W>$xU2dU0>`Xar5_IF!*t?y!{a!jF@Y2nF7bC=+_d;bJCzG@?|w9<Ppu{?Cz;ie zpHw!8vWb`58_*SdoZ|_RGx#Mc5QZ2EFzj?vV7v@!>$#6zpO(IyyDOupEgj&x*m;xB zUy1)O^xH>vz+>WopXMFw!N1bC1pSL>K8N{cUKIaU@kQTH6&xkI9v$`kr~e2ZTUmlO zK}G+kHo5ZC?b75%^~LWG#(ZZLw<{~L@_)tA7ninT>6k(<fw^s<cK0#EV$yvsbxPm! zVv>JGo`S5b=kB-pn*ia&raK;g*+OUQP*9CwwtH6Hffo`#vUJRjFw{4Oj^PyPuYx3S zSkg)UU$lZ#)PslXonDfp-}f^S#6qiG<enAz*PG-mugn#B-$$K5qMHB8g5o5Lexm<e zmg^JM$$(o`4jfBcSe%MZHeK(=`U9hX2;c~Sr(^2E|F(lTJ>8CFZ#MbE3O}?|)jcsq zZ*KZ|NQ4G-%WPuzq|bR^<)y>cj5cz>^%wubitvsaq4M#5Lw7~*<Y+A&fyPTw2bk`i zls=NyjvYG)B793=RT9~u>3=zp9rS?dTwg0R9iBw?^Psi^V0PpG;{prtYv}MYj9yOS zfeTmQB^CwS@~;fM^t>Hnp*>jb%o~1>TS|{k`}8;E<TvTYRZ>NUZxX)ZbxO<lsa?Y2 zy~2Xf+cO6;<U4SG`ui8R&>>PXJ$hP$X5k}G99SP`3#}PHJ1=$S($(-HGsdtO(XW~D zbTW_$Zo-_p4C6qazSXcma+79cQN6{4uZBKm5_7~T{;xn_uZpRVqp^VVJvNLd=$Ay% z>8Z3@Ff`CQe?(Q&ty`sWz3tGguA>5+TLstedGVRhum5o)*r309^H+qlywY(<&Rp%h z-nl|vy`8GXihR$W^Dw<=jm2#)7NGz2FzkBlN%<>dhDJu-Be7bcR~9?(UcPr)y+zZM zelx`mbj5}dKPAxKNR9#b+m_O2()HME-6fCQ4EJs4Y6{x*b)r26*;X!&c$vX?D~cpz zbWR7bq0i+DsZRX*bni%ofR;NK+rG1T!QvvUc7i*i#qmrRS#`CX@PycD{8AkrA)-gM zDf>$bDGP-(sDg*s%BX4ycmgbMj=iyKyRmKb-~m6ok|(Y&LfiK!nehOxjk3o}o3ad2 zOcnLSi>!y~ukGmq<hOW1gH9en&woVtO)nN<wtnif4HmpD{Icb1!|1acpj%2BOdfzU zq(N^LK*9r@y%2g>z6(1Mf~6ARI=>^tQRL)dQ1(xT_m~a12>CRPjC7Nd0<WGPTU1h3 zb$-(oPt;frTc2_S79tG9wI=yKqF~Em<eT{ReDp9!J9;9ep1O*zN-FPgD3iJCYOYjz zX6w0gPDk&*Tu$Kn_J6a!q7QJLcALhNCa7ADuEq8v90PZUT{0U+c=Z;GL(bfB9hD#% z;Qz9Pl#d|P`T@^?SWsn(eh;Pi9?RjDK>7Gy@8P-^*;6yVw_Hb?_6j!&|7gE@cdz}A zhxL19pHF@}BjvICxt-K`{nRm%blfgg)sHVrT=+h}iNs9LI?Ea2C<;NfcoM&w5Dgkm zB&-2?FT>R~KIQ;R^oMg1Arue1$Zy^B1Oa~M12pp6%&M^>1<3%FXW;xcp0gXuL645; zt+g!W0>(dTB?2E@Bdyw!BBv$>08*+)FKkfd6;t+bZqTdi5un$@xeD04U&7i72iA=c z5DKqv+ccpbS5kQkB7h5pCryZ+U`FRE8brxX{x2`R=A(cN^%j`&*!$3H1inIpD#6K( zr!gi1fAWvZlcqRq0Z*;(kzeOk@Kso@ZyJ3&3afayA3j+A$hgQa@ORoT{YmJ_XaL9P z_wW!9$i)t!Vi^H2Er8kIquyl<(SheFc3H|to(5HG4$mVR*(ViOBZ)z|y+=~Khr@z2 zPD^aVviitsi@-bI=*|2iy?p<l>3vBQM^r)UKn`eE8E`4V&KWP9sJ@(%6F&?GG2b+w zwHyL$tXHllT$P*yOd8Hp18#I{1_4KdxOjrF>+GR-^cHg|z<Mn1nf-)Wr|N?YU_EGm zc}edu<@6!Knj`a6_INIs&`R_Mu<-uZ3-T48a|_2+y@CP}kq29u-F(CdJu?XMb}%me zXAS7Cp+R5bY0zG=#{Iy@?LrgG;C0(kIU^8KR*@E3s2r9&XhO3G0EVbM_;0T`-+-gw zAw3%Og6CEQ+%g?cJc6d=Ey}RK4Q3#Ru+d=ietJc(*K$NAC>x!3$mbYgvSR2Z{BTf^ zk(D~2DmIu83_Vxkf;$qZ_Xtb0@i_^O@XCLmw(h;fUO<y*3;E%C@D%p%TuS{w&8?7{ z5wJ}i@Gu%K3e|rkO?X)SZn<UQ>WjXj<bRUJ=a(!dXb{ItJ$m`Dk17xr<zW~xZ2K=S z{gdd`<k7bP&EBRalzG~64AcUZdYz;(6aVn-u4xu;+u|(vZ!-B$yGoVc=sNrxXa27E zB0u8CEs4OGjcNAW#4nN35RNb!bXYa%f65KTx%GI_GfAhxU4ic(zS5wl|Hsr-OBb}k zW4u7I%mmhrfLQ&NRow;?b3qH1=Sw2=3JJN@PS1;fI}8|K{DpM&!8*J0NAx!=;Q%<- zpif`16DxWY0Tg0#t<4lo=tT*@lUIoLK>CBK@svRA{{wYzRy74k_!Zp`(vOA?-go23 zIzF1XYytf;LQC~W@v%Qtn-x`?#@E-K3cRP4(Rk9%3Nd*24FOAoq;39D`iG-Bh`>4d z1O(U_MAE^_EksKTWq`K!!xM;L3&;vA7NpyO+Ppi^AFgxJ(P9F`dxpOax>Hbu9}^NV zmw#yIf0y8&liBfqmw>-%?LRAK4aoQY&+X~l+wEvO_{rM?O9B@O*y`tdD$mEWmMM5m zpkY1Cg)aC112}$UxXD$v0J{IzBkuAwT75};I^1Yk_`}0$xXo#J>mN#dfapT-_G<el z&4^4Yfd8(jVSi`BKPjio2xgtZ3@*Wf3(qR$5A~?IYEm;sPg2c^8yar*yM_l4j#CVo z+?KP^e?O>yLe95>`csyRI|@KzH2`33ptm(eCRYSJ<r9`@5a&c7uzRNG<5vR~<|27K zc^*}WVFEdF?sI!sr3;G64SBo$lj5d{YTW@C@>lze`n$0IgM9@Cd*imcSN-3W!6=ck zXW>`kf~I-5s_3X5tH(}njxYvdtlLhQqYP~==Tx1D*W-NAg0T|$sG=)!H!F0j)QOu{ znp3>)IYk;omtv9M`gr`mEqFY>m}cVBVJEdb64m#q)WGyCd6Fu)B)W0Qs!HG;+@c#s zo`nNZgup4(Qu`=EMh%-EcxKU#9^(TjU@=7rG|sUbt-+DZ=2QE$ctZ!C*_i7{$S|s| zqyy_k=g_Idj;R^}HJz$>vY|<@5zusnc=Ul(FDu1vB{jr)MB24mrdKQa&M)4h9F@Jt zo_n)HKhty4=sekt&|BsVa2aDzYaq|U4(S1(q~SmJ?VWoAXW#NgxloT8B){;fJMQFk z;e=HvGgx)AqX|vh|9Kl9cuJe!%};wVLKwXwe7_}3reXBN=Qk7RfgKDjm(2C(UEWKZ zd|dE#0N|Sd*a4<)*bfbpX=!%SHy-v=)Rfe_wxR(yf!FCd7wW;UM^Cj4V+MWv(5*=C zfp->o4d5Q<2%N46l@Go%e{75JgCZ-5wJm-}C;y!#6M67DhY0|zZ{Q0MN`vcTs)g>p z=9^ZSKNdc4E?u;eDZQaZR4Hqoc-|GWJ__;?KB$ER?&uEWB(SL9%PHQU4W)aAq@OOZ zQXbt!&!o6T)e;{fnu@5EcE5ugspW1DO++0yb>_nB8&|yO1`vM}aNpH{E0bfrj?*#2 z|L2w&bbaHKr9&{02s|}M_*G75aSJ0znbp>lpHiA!Tp&ZsXXr8Z-+gG4&MfRMxM2q% z#sJA<_`2~?_iF5-P$9@Dk%VSvp3zqeAn8`@O?X`e{|LQ$G0&2E<WbpbImfCt4T{Jn zT7kj}hZYTLpS0)HBj-_3V_u#zl+b(ll|>ZkvYKyFu(b1c_CN1&<*@&!oRH423^Kuv zfTfg2Iq=NK_fZ(&0zL0)p}NUm{>y!?DEhnSTq+=St(+?Y*Ds@1>PfLR+1Njy6SfqV zaUlg0)Gj3dq3IwC4Kj5`rvK?0mn>NDf3JXV$@Rb>n$e(105xV8;tQN6rfh0B!sm0B zfDJ~ZeC`nSJ#%fn1fIGGb0}LHM_hO?{0d`1Qc7969%}qW7d`OGAZmZVvJ_8Z)UCxP zXLgS>odF^Pk*Vu9@-Rl(1qFQ|?vTIZrt)Zeq-m60WQO$q+3C&@$zrF}&MT>JVlT9n ze*U-=#ZT5Bo+pZH&&niSHS?IaAPQ#Le--^clTLK&Gw5m;R<dk-A>j|p%GN=~B6@q* zUqnc5{r2%|7X?In{yM<>KYCxvLsOsVIULqwc~MOKb46!D7sYvJZtk>U>>kBJ%i9Iy zeJRLVxvAwRrO+#(yTgM#C0uM!y)}fa56dZ+tR!``-mTwWE??=Enlfp|4VX-DyL>(u zb}~E0=nF3L;92Ruy4NnZJPiWgh($?ce2XlO`FuHQXsRwL9L?s+LnOo_MQFs|J}`Gu zdi6K3C&1!Lxims<t!1zD=vpQ4D0X=8=q%hMm|c~5vT{X?uOqp`0n_V!{g$kr``x6K zwwi3!M$xiESxrA<!m6+YZ5g5j9PE;r+Y5jb{kbq;B|hL1#kf6BdSG9Lti7FF3s3Xq zDhCbYa9E*z_{fpj6~V*5;y4W(Wzo@Y<u2L}oHO*JbgQEzdzNeup4Y15wUz(g8JTap zFVk)siBe@blB1<9{|t5bs)pmkHM@OE877yaiuY};u+1o1>^c3*DZrXSX|rr|pX;GP zEbDOP;rx~!j(Ri-^k4AwOw^#bT;f@YUcN@BaB~#BEVaZD-IuKdhkQ?KQ(t*^)XS<E z0a;0pL1B-s`D~;WOZW{%lrWlgCQKoM#QN1kn4LZvU9+hliRf&+2ieTOuXe4G?I1O^ z@x4j!)RMYeqnmD@Y2!BAY`4!RqjI^p`I{VhQ->Qpzg;>@N@HfbK#jCgDu$(g-tGTX z*xcRx;mQHYrk=WEZ*oQ=t)yoTDodv9$UTW+c9$r&ZX~ktkU-YcML%;*vmQ^-#uE3T zs^UWlJ^~*I^Fcno)ZF3MrUSC`)fNg}mW>sU_URJeoyqMtshKbEunO0SyEMjie3;n; zMbN<XU`7Iip5D37cE7<;AVy5+;i*zbfoCfZJ>|>$rl(x?=wND`RQ2rB6m}gvn%|=p zi`maNt+wU+bq)S$qZA>hal6aTItTNjI?`M#N^C3Y+sBK}9kB{Zw7B}-CE4&;)U<Qm zu?gq#XYVCd?p~0axZL_C=2KWc_H&%F9wE9Y&KaPk<;nmy?tb1ho^XC12s$x7ouURm zQnc75bj~ozJF~P&!@ybjrCjOxO6xP<?bOV+8ybwwNxvpcAZ*9UGDPx-1Fj0gPu$y~ zSJAn$$LiL7AN>rIMios*rnNO8`;tcHnwc9CHqpP`MB6^P947P;Wn@%&WPi%T%qOH~ z(RA(DZ>}=?(!LDr6Ufvde`|5>AHA@>?w$ZQu6fC%vs*0kmZIcRW9&BDE0L(Z&!VIY zFDp(wyMEwXyAkDW680X}22I?rP1*i>DC~;@F&RCZEn4?po~h$nM@+p}gO2>JpErvN zt%FxRzG!lNxsmg&YX6m(Lt&O^iXc!Z$NM!0bL_<S5gUh!=jG1GOFGESq0cOEwUTe1 z`_kXP{`I)3E$3l!!H+7PS87IAQy*s)R*D_^PLL5`&$ANs)OVFp6f;eCYLDvuX_}Y) zectA4?gIkuSnf!u_T%rL%JzBPjh6DzI-4R`(k0bCwi+6zB9$3=a7oSGWhA33A~@t= z5#mauD}GYdiS}f6pyjHFI8swMsPK_^$OS8Clh8N4=5;zPJMW&}zM2f1D+A`cB&@X_ z{JbLb@#ejqvTad=dc*@VvqmGrSk4)H@=5LCOi>N0%Yf#EPKs`NL++vI`2)S%XYH8e zY!7Kb6(&W__ddP<ii$yrSpfscH-0v^+pg_t+QCz42h%)yCgbE?kKFp!{n`Q-g5aML ztwbw*WK7X@odM|`A;u<LWF7LZr3-SyN|oPC>W&qJGz+B{;KsQ&)n?^M#}-fsTPY!_ zPoEf;N_4I?X$lbAL0Byud5K{S-V?3sAdA;5EBPEUa;sm_Qj1-Ua5J3E%H?Y3ddqqX zUCq~0w1#pxboiWs%C6Ywuitn^JajObGafwV-cisb($jn@tf4%n+srcma-`?YciDp9 z1WL-x`|oBAhFCOD-DuO|U($YzA^vYw*lg{8OT}`~ri-X1T@j<;Yq7#ezpxFhtkN6b zT?E`}xWNrSjVH0?)D_Ls4gA<2UIxa_p`Hply8Z3E=tnk;kHDoJC^rGVjarv138O}| z?4&`{%IUb4u4SItY8tdp0QhB}JV)?UZF!+;K4cE9y)O1v7u<$@qe%4$LL$S|ez)}h zzbz<FqKA(wU?;IXeP!4f_t(!xpDn)w4(=p~W)8vlc_jY^$Q9Q2V?jYRPFr1=1`*;= zB<3(ONb_~4!Bq;e6O{8!!%yc>=xFhQ!aile951>{q}G((AHhtQu=6dz(+wk@0&Z18 zGK`N$$}ymTM7F~dg5zfc3zw=WgV!C(y{%Xx5WZwk0tBCev7|2jS`aV`Vn{#pWB$7K z;SyqlZ^oNGPxSs)#R=7keCICu?|uUXNairaKLqrL!lY%miUUPu7Dhmwd}Zc-F!aU7 zsPgG*pq2APT#@+ge&_k~n`qVr-6_k!XUqwq1UkDgfRLZ94Q%`>sEgyNc23ja3n1W{ z#DqnLb;_5%61O_mZ09bzZ;x|Ewt+vLl*F$A-#%A+6Aua}6F7N@+I**2ubNgLEEF#L zEH*GuGB%p6xQX!05zz9|5Bym4wDi*iE^rs=LKt-mXvhT_N~2_?{_Sx^%Y1BAA7*x_ z!n($RSJAV$4l^t`WpUghiYy3!9oncmeu_$jr>fZhn^=dM{_7sITaJDK9N7uJl}wSk z4%Tdkt8A`O>sRl(`4lgej1qGEi=@Md#0csV=zVdf-+Cup<pNLcM9;4Q-}D1$ig}9g zMs{OI?qJT{9-UaM@$7rs(;^p7@UI8`$EN{D(NwQaP$(bc0pX#Umgxq2=)^?a9z}SH znso&t!ZmmuwEvzwYM(&=O?iGt=obv5<C7ut4u;mJw-%n0?Uf4`@1IY=wD_#9ByS@8 zvIkvu6}m<*CzCcYl@FT@711^)?%h9ML|N)CoB{sP!n^}QhWDuR0<Y~)LjSgIP8txJ zyDrf|vqSfnzH^nP-Eo}RED7)FOUx{WPYIu|EbRYiJB;Vf9zYUdXVLtSkf^7+^52^) zFDtd_Si9YTF0x7ZNw3-?Y`J7+iW4;kZ9RAVi<<I6b4>EgbDv9}7qZ%HR~zA{mLCr1 z#k!=dzH>$mG9J2Zpuu?h`@QNhAVqt5W;>E8*Qm*^sAm-iLwiT{h>i}-O)1YR%^EYz z)-xUUXop0F?|bCQ$fB(iJ`kgH=Y9?`t$vW1z}#U;oUe<$@PujM^z)|7=}V>(&o~3# zzuL9Mv6<OZ?_~3*{^{^<GIOKeCQ_KeXG!f(FYEQ+C7q;%jq?bX8MhFK-*Ev-UWyrd zY!_UGf>iq_f~yugo|%N(_nci^Gw*C~Z>C^^U~3Hj)d59+`IcUp+6an5ez|><aMe)< z(-~_S4h~Owjh`d-u2;h4P=~&X1iy7;clTlqxQ`-g4#hu`Bggk-){03H(w+<zN9F#y z-Mz1(19Oe9a!m7Nc4zo2!xOq5*^zYw+4qu->Fn}3a%A$Eozv6bY(_i{<-*T27&=vI z_<MyLtBdMfJJH#z7qmk4)`+PU5)1P5PSxC3<7}r8-6FwTwp~>}^GrhevHy#<_l|0+ zTf0ZGASxo#n}AC1MM4vaigW?#9bQCwlMaH!La)-5szB%vTIdp_cce?G3DR3a2?0Xh zyFK^*&Wq<8-x+s|JMMoeJA3W5_F6k@&SyUJ>AfAkm>nOVv{*#9YlsDRs(sQ|f~xY) z?;eS&0gn?oJzDOgN%zFlWJH1}@jiYevSX;RQ?0u2D^rox+IWmXf_t)&tR~%tDu_?7 zj5)Dz){cj-u-BR(nAj=H{z0&X!S8Ppv~oCH<O)*8sf?`M<o#O022JkFrB(B%al9cd z1FJ8UWN3$c2EIN5phz1z##is`vqbiEZWkNf6o}XBt2^+py(a4yDh(pf<dG6Xny66E z^ol=r6KeEt6Xi@9v9Txm#Fh~rVsHrTbr*Ft%*`<Wa&rejMj}x=vYoY}4hH?QZ=Q&z zVZ)Rf`bd#V4^cS5+AYI}(Y_cpze}dF0|w-8xIao1wT!2fZZi+Pm}yorXH{5ou;Gxo z(yW4A2=~HNwDXTf-|gq3Q=?MXV5y<o$%8|vm%klbyN%Q@bt2fSf&>Qk2w)KZt<LeH zo(e|4PPm09ln+)Cur3=ly}!@JaJ75xxmrkF91)axb03xU4f}f67$Zc$eh)x>b5e(Y zOW0L2_OD1#51*&KGM6SIe)aC%U=NozXSvRW56jr8Fb31Jub`&v2=-gfpi>Rqb|NoU zqhm0CeMP3Z7bOdfiG2a}T-T49mS@_tr0=DlST$<Vt~Cz7J2W~FVP2P#eRxoD4P8BP z$I0K~UZ+Cv$BTMZ6+>dl9B>Ew1qyi%e3V9%2?ikT&RkE1UOi**d963vdFS#6c(RK0 zomk4}PWjp4SsbWen>xjdGn&}1YO>{nItGoS26b|Vg2y?ffhk%`adDp|#g;sJi**a6 zYfz~uYN*6)P7yR@Ip;8KIsZ!rm$U>*rW4D~&_YKLz(*{dDWJ385lC$oHGEiDoGh;m zqd4hPPE0yXl>E2R*I2g_`Z?b#{gvHdq<z_qMT5r$Q;lBj+zrm6!OHrnn~gdXOwsA; z_8@jTlbH=tPIY@*6|$eJh!n<)z3%rbYfkS=^E1`K(q`+z<@8Z;*9KCE{8-k|&zxz) zxTg+<7Mxsgih*qF3q1p;$*Fy($2wvk9ro}a9)0L&gni(i5*#!7kv8Z3jjQ~*+4_p# zz{hLoA$)ZF`}JmuK5=oG;tu!Wi24)lc7r0B!Wm^HifNaCu_o1$={ZjeOB$CG5aH#C zCVE4u_FgS_u4{&yAeW4%tgv<gljn2Cz~=oA(G3j^%S=Ulsxol)Yk~X|feOWb#iyuo zp+YCIna&~$^0%Cgu@~pHKKWQ>UaHz9q5ev{tWB~c0VX2^VTPkYh+Fo5ld#sTJB!>o zm3)`y$aZUiE#5VD<!X1bH{+*b@!TFg)jN@LRUsFf24#^;hVOQ2KCx}^&gLbU7I_=A zN^{zgUB3OA>bb*|Pg)lsc5sjqo3mJVW8N_E8DcY4ioYBmq3vNU7%aYXiU09!Lw)vJ zf%;G;-XRz77PgGCs#CqpMuGJa_WSAh{v`{rNSDoLxSc_?wHl~svdwChk>BhibdWiT zz1qFzF2hb;p75?+_Xa!Z!FJHFO2d@gV~N*Y@kM5ilE~WZ{OR8*{Knjkl2}UxuXw>! zRoq+Cz)CURgktKjG<?}9;9!Z(hzA^t$`9jiY}``{=-u&7&op?j;(by1vumEPQSDKm z%4fS-qLn@%jE#~LV2?Cy9Y(u6^sZrgb9??vqjvbvGvj&b6pk^X3C~feUAoE0_F=u; zefcuywB&&*WtW2H4W8stQ1XN|k0)KsNYACa=0=#u<;85gew`ZMM?3V6gr|1?8l9*s zsH%<KHBWajuJu`-7xz1BpPr|YYJI_v+8j}*(`YAG%P_Ov=0Ek<jUm-6lh_<DUDcrp z11amD4yx=Ahb&YTv?0Qj+V$&4gj^2;E~oMCY&lPMagg`lh@#=NY|b>?!rquw7jv6; z<r%n_i(fjG*1{s%Q-Wygv0GVe)iq5z%As5GLxWCK?k>(?zbB>IO(gE^av_(UIOFSb z%>1I-acMDKao*+AoxXNA63vmlUQwJ>U6swT8=Ct1wjmL67x-z8LM`1&*NzOU)@vK# zHL17E1ZhmWWm97T|Hzo6+oAkx-?cbpvx0R}BP>K4fpqCi$5<`XzF>A`wwg3J)D@Xg zfo<=$w;lI1vfk)|=A#@XCS>?WGI&m*syb;I?)PIW65x8t-)8)P4fmEYT0rZ=JO^F_ zMHw~uTq@%3xA*&|lXCa!qy*eN^VOlp96j}Qr1#)iZhTt(x8v$5pt)|{!!wq|Yn#|^ z+{39F7OiMx><0;xvy5Tr0^WnD{)yAx{As0B=529-FDcwI8o_E!#^J9JO=)pmTEVjN z@8|g^TKMs<Q|jv4UdZI32G<lcMN{(_hqQV6;|JBzH&ze;5w}>wUI%GK#L6=Q`(fLK z_w)B^unG>cTg;P{=r?R<++%2W7YTP{`#o3FFaZzqIhL0;`r<<`jhdfXQe#8kq$}mW zn*B94F%~TdCmMCyAIuc+PqQ}yK4%QEfrj0Ffmhs^Uc9Pa@wVZoUH4EDd$o%DSfC+q z$f&CpIKRcAbh}7VWbh9Z!T!fSav`T_cqjM5M?XRTNR46SP0=8YCWzc25WzdQRm)z2 z9U3g`f)C1l-bw)>2U+j|Is4J+-y~(4=1=_)vbqYmSBU2QOK$63V%@;T{vUJU=cKUn zThsq+`>iOrf~NiL=99I7zgGMC>U@GM8l*S>L>3Ny>BL8d>^m@Gut4m8?CW)4QJQ(} znvyK?Bd29VSD&3F>F$S4*?(9POCtU&todWlK9xi4w-CD@_-q_S9O_yKlNWP7{^o;s z(vi=a7??mz>k`$n$^eIgnXc@U=nd~so-<@n+}=aERHCx9+sQHI8Q<+}0*^BBoi%_u zAiu*i=V0Mq+NN1nBkb4nfiuu31X`bJ?fUrp&opJ&$sPU%kpDo3$=djH2_k>)vDaD5 zfMZ|&P4YqrmT{MTQ+<1AH$9)S%!}?1>*Rp{3NV6=V9|!Bs!&Oy<xcGdg!HP+(&+;9 z&%2ZT9lUovk=Q~>d=IaD#Q5izjFhC&<*q@a0fclPqCfCkw@I?tmSxz)-y}E_61V>{ z29H>;FT^q0soS><S06RCyA4TqNfVFO|J>;RmaCmJZYKE?S&f_pXEBqRn&yhVg%ksm zW;eB5tK2E5nxGAg8cSRbWX<Uj)51B_oqK*TCf)%i!{q4dV$m^*(BT^5CL}$xseVXo z*u?VuRJ8{F^v-93&|dgH_YbT$)mS`xvL4fC)_OVY)#chpawj^FHmV}X@El@g0riM+ z0%^~_ccm7<!%r%~sH@|M)t!ZXH%!S#d}P03gjdNYsKXr=^V~}g^3(U;O0Jc<;WcUy z$2cHf(_%;fS`MB82$gK7xYK1or*;3lQ0$v8R0ACWftT8-ELqhEPE*7m3<5!yt4aW! z3-<Y&Bpnh$Vr{4jM1S_PiH&i~`sbUM^z24mmTU}t=@7dtdgCqG?N!<f-xRGOZ7#sC zhvD64dx+m6HKZls6cD@#5G6>4fp7{GapvXrOCY^Ga_=Sfy--W`rvWlgrmhRax2-_{ zD2`Dl25tXM0zB)klXR6?l0kZ`iPKUCMdunWa*=3g781dg9Yk>c<vep!wf6)KWO4|w z5NTXQh;PclyUG6&r%8_fO|ptyA|6{}zmT`w0Z6L<BMe`+#ZqK7kUL0LswHSjmZ)6$ z@p}LL8~$v<UFKB6*$mNzNP8j1JZ$T5sf+^!>E68*_-tx>#};6-qa_A4aV!!BpHX#< zv4(m#`k;|tN$4+0_p&;1{BiMKLAMY!?%rGjTrVE{<a7Qgb5N9_w}{5s{(OBXS|4r@ z)=8gssJVuN-~kM7BXT0dehY#5`4gBX8-T?2KR;>)Xqo@5Z>8UowT|(?4=ssLw@-)+ z#CLpWhmd2dO$a6iu;Dr|k-rN;RaOGptqFHsz&-@LzW`>H=d$x3lBabbB5<tbc7L2a zZ=PbD$6D6>(WT5*YG9ULfB4V&<q;tO52FToV@Wjf0f>R1?u7$$c`gX5a14mK2PhNn zEmR(zF=$0t;vFUaCLvl(vHm%m*fGJ5mitF;$8~t^tzyV9Ktdz{mwxw<AaZt5_Y{by z?X~}uaH9z7T~e!~3UtJW8ul>?VcJ@0@DP`@YT#rGTfpp6%tbR0Sy<SK=7#Z|=m$c~ zpwaRd$$51wtno_M*gi`jFzF7E{cU$3SPB@N|8EUV0{=cNXGw^)n!qOjg0KegT7U71 zoGuD7O$GOrV!s{4Dd21tj5jQ(Sl{seZf1FIGJ{NZRkAzwApm-g?^@(F_F##9a7nqU z2v|4lL}0n~giT=(2iLTAOMsK!tR_;q{X8W`6?DJ|AZ7^Qa`$^#n&RaDCdpaH3II|R zrEK6h<Pzea<qZ%e=N7~NauZ&sejwaG<q}HDnOSn{Fl2M%BGUg9v05)nn*the!vWN6 z&IpzqXdnhq773ShZ|!hkf^CPNUr|ch)xFwtsUYyR-v5Wu>cXamLSCl4U)Tn-1aaJ% z|G5XWFX_kDxCndr=Y!|#xA?%nqHbma%U#fpap;X$w%Y&FCvWioPZMiIjt2-{(s@5| zAxZ}-`|QP0V#>cOi9d*WH3i(U|1q;-jn}L2Its;>JymyEB-;}_g6a=o1>nU*Ko&`m zIyDLU*$55^RCb|l<Oy|N=y<&xgU%H?px^6=aH~vsnrz|!g_<LTf->#Wm6?pq`4A?( zWaXDI9ORg$18pJPi#H9!8n@ghr?h!Ool&|mw^uS9wC{6Z;lf_BfYD-~?(4_>b(T^i za>YKy(8aUV&TNu<vW%;uIUqe*NiS<6%gROYdFd@V$6u~*vzrGreYcI5*uxrmx-7%A zuq-;Nf_4+jBZm~+57bRdjESR_R<6G?KDaRNL@YQ~+JAn>7&ui&P{6`r?QWMgEWqOu zrkPJ>)FQa*YvCU`L>+Xv`aiaTW;e*Uo$W%bL*&K2thr!utT(5YG~)_3f%*W#BEmHR z(_bZz?oEmpaWaQyu-L$nv*sPK<t%-tf&t7=KRqMX1y37rFm&ow2P!IG*G^Wcqhr$O z({prS?3Ld3TE+>d!OIaJgQES%@6U@4%P9<2A*rC684cs|)jDPVQze&+p3sR=zYktw z8q@dJ=cmC1jp`LyxZ@x!fj%EB$GOk41p}$rDq&_0`?KT@uF2N?eOYFoGG>ljX>Hk_ zg;d`_h|_XvoXP~!V<|iSCLyyx28|fV4oAvyp|q$SQ%u4_M|S|Gdn`Wq$d~(sIN2u< z+8Ao<R-@qa)z)rKaHm&7CChthPOFW`f<Jr_#O0`!V=vD*>dn+lw)F76hN8KwddW92 z!R_to7xr1``xL)|l#{T%FMAS8vArJ5BGV9D)ma6^&JwBI)xsKwg4aUPkciEk^%KJg zZ!qP2?Z>@NZ+ELadbsgYqK1^m=NF>0&*G1#a;(I;Dq}ZKOl5k+wEN8}jOvDpx?K12 zYdn{IQmbmr^peI#wOz`5!2XyihW2FXmfU`iKE`L16-iK?GH2U+`QlKfHwM&glSvZ{ z5ne@Bo8vfIj!1p$Ufvg621$hhabfZ_1R6Y`d?AnPkev^6Su~CN5X93kUNaocb_;tj z&z#zZG@qy!H+GmxNx3gH(b(xCE${V6(0BPo4Eatu84B3A08A!tXcKHE(BIs&BTJxh zGKh7~$UaMSOpda^!PBqlDKMR!)Hef|T&Y(*RhG9qd?xqJI%>aj*ro=4PLtY#pFU<s z7ARs7-EPxU?F+PCb3CoS$oYarR^4YIUnX3g;oM_xxwjN4f4aehELLzvU-VywTRa`H z$%~~rfNhfj656|XkurQ8YO3Q}e#7W5OfACS1r4LvFmXXzOk483f2t%vWwf;5<V|J# zMAL{v@BzJn)~D}_)hagi{I3eJdH~l0+bQN3U#_dxP}0>d(dLslc4z=x&UhQLe`N8x zUlAa|9*BJwbeGt8@;qeD+03!gU6Xc6kaJll(^=8TBAT|Sf2L^+7aOCRrM<`=0<J#l z*q!D<OKn@BU@?shor6woEo|Sg@^xtNjX<S((``{xmYI~9yy1c?hK-R-Ibau${o?9& z36|iJwd^{wj%*}g6}AKwhGG)i=m+!g#iu<@)jxJ=Iw(-X5?AjuCt0Yza7oVptHhtb z-}%Oq2hmM!gSy1)T5m8>xCBdT2XHle>!5-jJ}O7OFdaz3vqz>o)cSbHXH&pC=Zlz? z1sQPF4j;{blC^~QV2af5tc!kjZ@ED*$B1lg0*aLVxW$ESjU2~Di-sj9)|=)WUC7R^ z+%g9X0eC~~wZCdlokwb3dzzZIa|#vojdVr0+D5(Z+mhx(c_JHX>C61}i!`gJD5ZZS zeZ9QC+4m(?C~uWTC$^$+4n!)`-_xf27JD<xKdj&3)JRy($gdM>5G*3a?3JrSTQUNb zjrGCZ%qSW6)YdJ~d4-mv#G1BdSJ#CI!XJRAUvKnxW-*M6E<DFFKb-iEeN$5zo*z1- zzwc6WaH<F`-K5xBv)0j8Q1uiHOAA8}6`d*)q$?}%{+Ok13$CU~5mz`P!PLe|IFUY6 zPDd$tz?*mbYkhR{VE8=;UqMe2+AfuoO<eAzoG~z|Nbw-F8*88xd~yj7LP0{aIL5u! zx4fYd1b1|BZ32rCY3bEHEo*B|-={k%5?L72DrLFnrDb~-C7xgGvv2K`1zt%TL<GwV z`^oPu8K!k>`HU?!2Jo#gN9GkVbIr8h9J{DiCJhnSrh3N=2?%r0)GU|PchrS3SvaL- z9NW0)rRT#0jEh}LK)u41VJqGqM6Uk&YMv~HYij=aT*?V>P)x{m%4<4V_nhc7thppt znM<fNlN=Y2&$F0|y*AWn#aoyIP4OX^4o69og0@{|zig$JsWJ`*q-HAljIji+((HJJ z(ZY24o>*TD!YZ!cD48x>MA$Y8dy0chwA}S8=ni7U1NML_fr<fs!f<o9=M7_9JE`jM znn=5<`o>V{r3P<A>^-tw!>ux&1lmrymNINNI_#YnjA7bubx}A*s99bTgT%k+LUy-_ zIHzRYsk)WU$mVl#M#!y@?m|_%#EPCTmAD{L8n12bjus&g6vx9B<8JsN+K{u4)C=)( zT2fQK^ZcPh(g}vKs63TP4f)X*j5nE?E=fDks_rUK9%cyLP@d$Ww9l3jD4?IU9+a|E z>t9e+<c5v-;Nxyp6DR~1K!ep5w=IpkM_QOeWL|LaBMkhW8OZ9k4jt$f8ni#|DwEMQ z0x0hBWd^>neXVeH%!gJY7)zfCDBW{SC*hedMn|Wfj_xwSs2|(WenqD`_BPsjyiCq~ z7B(PwU0E<$9mU@2#u&(n4^K(4tg(nH^xHGP*Y`JxK{b{X-aMsiul*F4FQuoSA%dg@ zXI0;lOSfMbAWvNmVhb9|zRi7>1GkJ_xa^%?qIF@zu(4+T=J;U@HOm~&wgJSdGEq}7 zSpB65Xomima^!gPbN?3e?-sDm1!m$MycW7Hj9`xKUVPXUR^ag5QJ#6c*)Ffz{HLXs zmyqz})fN4VOpHd?=qFX>P!wIbN21*@q3)IGT8l{*I_)m8Xxp@}Anu$5ucRW2=Lr6l zXuWKtVQglgR+_todvu^!@>0cg7IVJk6TdzYs)$Z>cD0eSoJp%8jNdcq>yztVqRC=( z`u6QJ<C%_LtGbc+0yL{<>pXh{wi3UII%9v_gmoEdIrV*8AXSUCFo$Eu$`e+MR>jmz z=mc)?3C4f=iRSism^{@M$8KiogrFwg3Dm*F;Uo-SYm_&A@$+p%5AEt9>QjuInbBI} z0iUgTQ~BvWTTQ!hqiJPTv)z}pf-U6nt7K8$ZnrFc;!XCAOpg<dt3tNC)q5pMVz>ij zQu}RV?_N%+3iYRBa3(scaM$_CQUb2e;ej$3bu@FJFV<z{LjcM}<XK9$9wNA>G0~*k z>RRJV#xx@6)V1VQRD&JMvhH$4ikM$Bg6>I-icY6q^w|3(6X+n9j$XO}?slJh@_1e% zl7bUGhL`KVj~=?+I#LqV!$vQfH-Aq&*C5%ipGCg`Wo@h*-O{A#b-Q>-AWIh~EKxKG zmF^!xIBHGTsh$-gUT#0!-Q}s6lyfPbbwDme*7yl-gIMYX%gSIY2{_d>UL7h2&gTNX zuUZAm({FAWE*bu7pD&z!rxrhhrJEX(5y3Qm*L?L5RBc%!&p*}dhR&XrpITH7a{-ZI zV?vw!MIv`VtRB)lBY91sUDqbsnwqidXUV>|Nj+~@_UX^b<yc})mo#u8D9admarjuE zj0^PVF#4O4IaqBp$EL3G?Q9SA)k!76!pMtnJHts{CJqLH(5@Ph?FI$mB@wHEhYssK z+l;CnV4rK86XS+QrfS{04I<PSqFo0Q3>PSR$lKMNt0q=r;7xb6EiG54^i2s)EzdMW z`ZPYtzA?#ai$~LA8}UE!7x;gEw5Ro72n_@;P9MCw^fyT_u(RH1IR{W*Q${z7opRO~ z{7vG3pTjcA+s-T#gesg54yQ=}0w_tLQ+CLR7akxBLUXkMc)aZ~RoWt^uOWSGJDWg+ zFwKoI4nqwA6vF|asO%=lAfheKMwb`_CZzsOnt`DpYt-2bzyT?&asLDOP8I<EuBZ3P z^Sfr2!a982IDr_|^(|U!j`}GI|EYh720BnyrbzHFStudup6Fg1fHM4d<Nh~f6u?g4 zfK;WP(Z_{b;+>r#$KJ~S`GEx>)x1^<T%i0E`w{R+iedkM1%=0&6;QBg>9w(l77*d7 ze%mit+v!E+fd>$mxK*=)|IxcCkb61OFO+_yj3b^i!^-55Wc2O-WKaV5v-h!pt^h#@ ze**y!=%Xa!34&0u1wqlD#Ua)j1JwY`tqp|f_izPcfg-1OD3oRky1@}#%?GXE>t2{^ zJwT<u?N@-}<=>QnE(!z1W%6&(n6>F#p%&Hgc(Ui-4QJ~sAP^wOB0we-yCsm%_Ja%D z0s{&#JWMB2A*R)dQOX@61W8FSp%HKt`11o8=bs=o?vIJ~&&0a*-+7f6el(V6$t|=S zCUud7hu8<`o0WwcD4_tg%CX%b)}PaD`<Cm5KD?vP8aoEU%RFw!vn0?0LSyisjTf<# zItu!d*UPMyKtlMQC*>^h)n*qQGwTfUJuhLdsTg14tr`2K!94NM5tO@=wi9h4VD|?{ zaE>D@|Ii~<6L)+WC~epXxohA=52pF)pk4l1PP}@iFlL(eujIug?$kecACl>Fex7B2 zaEOlZ$q09}YHYQggv0Gt7h?~`zg)H`p(OuG1p4>g0SMDSh(k+^7U4a>MZ-P-oKcyx z0Uh+01y$7PgXa_+J@fYVN=lTBtG5Yoo^z~<#D(gAQiUD=yatw8zYgB9xK!K=-(!NE z?=x%goCKiq2U3y#*DK%w3K|OVoCRc`U2`fde?8Qubxp<l;S<Gp*1#_nzcR8shop}k zyZ>zeyb)0G!uiEBCJbt_q-sS9Wq5EVzL`uS$tClZ=BfB{(=`&1@ScB4;GY1NDW`RW z86e5`figfm!eM8D1whE5zTB0a++saZ82Ye7FlCF&`w1|GAN6c@n*KQz-hy0!GMOU3 zD^cbZZvXq`my7j?TaX^xC1RtYgPA2z5%WGkahda8%>3;%V;2nQ@c$(gb2PC0=k@ao z=j8le$>)UrzbnINKVoSC;8a{x+!4cZ+S+CY222PvgVZAirj#F%+Th!Xj|zy5u){L7 zery=woz|JR<>sT?zuRL7d;nyJ{2#NQ`r(@Z>GkhAb{BJ-fRn01HWMKnI(ohk?7GOA zhubgvOCNp<0?*m~ES7w$1C9i=7PEi@$?rOeWOTsd{eLRR85{z%A_Wkmn6lOfepc6J zxpz4ZsI2MTYiNoRIlib2NP%QY#(q14r(wGZ5FiEE45+)JHgo<Bi9kT>!lo-^&T`WT z^lj1YunxQfJN$Ap60i)q0b_#nun=cN_CTiqRe71`?6Z*kbz*lV!D7N|voP>6R($hR zY1>VR>m7P*(f>tdG)IG>lCDtSv*Ps8L*;?OXox@ySs)2kYFizf+m=ld$mRaa+%MHM z_L`d{$D7z`{pE&+pL<H2dtX#-_Krd!B94Rs(x4N3E}E=8?wzb_7;4(3W}BfM7w2N_ zj(e4YL(;udj=gqSP1M>TMo)opVOd!sKDVqnQZBliB5u%WtpAm$XUT&W{U&V<Vhkbf z*KXd9O_trktJ`EBA5U~H-7eA0Fwq#zfpS6zZTk6?bTv0kz(FYpOn<utA9gZkY0z(2 z?u1tATEWcw$oS8x6!+@2K%As6yluRBF-q;E{%CJ7S>THwE+Q^OHb2Ynn9a2DwBXmV zaJoU{!)D!{eJCmgGuO}64u?0^LqO`EzLRnYO98C&4|x(iEDyOU3#17t7CL$wtwUU% z{!OCcH$C2L%j1n4WC@wotF#~+Xlgw5=SbB~G0G5!*C-lmKEB-BQ{K!@g@s)(fGSWa zjeKaf(h*WDQ4`{O{Jp+*CRK3j7kqMcfB2GL2-+~jU)ViisiJ0%*J=jGm`0VvF3BIt zR_dB$i(Zg(R00WZw5d7tBl$cG5!YdayJ!vYvk%>ksgdyD+A;WpH=f!*UO2tEzIRsc ztMC%HSJqKN+eHa)=W4aAc8xHQ?ul*Enl8XaVAvxdj+yMZfU~bHENd-HfM2b<NC@FE z=}sOsdLhtr&c3lLJ*X$j*F~taCdGm2sk?WPpho4ymwInHoH%xvA)<ddtYa}TG0N;m zA<B02sH~R@E9~S@W#QJ@j^9*Z=~~znh9tGq>C49Oj(g?4jvNxcPLs1PBcm~flWffY zvR<gFx8@4iLTZr{B+r`U8HmHkx{geBV=PZQ5b*OWA2uE%$i=x!LZOa{nxRX2i9>ta z^A9#njR~LAy&~Lie7Rzz(UrZevB*ASjlTJDp~kQ?F4BSxqi&D<C94#(=yt<C6vwwE z0^%)`a%2!6t~xUoW@LOBtRTp-5_+XRi*6r6>IZp@35w%RMhQ_5tHYf>lbbqB_FlGg zhS*vrliYsH{Ny2rqE;hGdA}|`eW}c;^*KQd(1UPwMYw@#K2G;jQ^&Z;nkhs`?zX8i z-)gE1A&)@_Stz6DHIgP<hZr5Wl&FFixcC~nKleeCYU1uErNrV=1$=%G;RD1pV+fgh zvWamJGgS7I?1Y0-F7!#wS!!*WY|>~(valh4b+mtxT0ymTRLRS+6Bg7%T=gmCnu%|_ zNaSmZtZEd?&xDOBH1JS8xO7`Kc_4@J<Awp|nz3u1M|{)=&TRVy*T;6^#}H~$Kn4;< zpe4t##^E^6(rQf8Yr{H@x-GDVkvxr6wPRbk*c)T(ICs}4r+2GQIgSIahVm}O=z)`B zHo>$(Qb8kNY9ejihm`CZ_6Ru<sK4k;Gm-9n8*;lW*NhzUa65D2CWFr?)B9~f{Y+C4 zoXX_gvlt=oK^l~KM54;n;X26l+x_R6P@|XjDPpw3K`$eGF4CsR@CYiA9N|4XU1|FZ z^#+{sv3+GSV=K`aB3hsMh6Xo|XER>Ry3yINQjMgX2{v=U5}yw|%qX-ihF=4_sOj5t zY0}YdfXH+TK)*5`W=s_G>+9VslJ(3+*?ngZC$coc@wun>iBk{;0!#UflkcR<qK0nI zxSULj^y(Nhl9f%Qy8Ct%|J`?aG|8e}!?&wwVjnE>bO59h2?0DIPfrLKS;Y9p%HNnC z78*)9dDFSwZ}Rieb9I*$e{SV?1tfX>Z0G0PMsPzWhuhQiZlusuOrS$q|6)3?mm9;z z$cDJRLB-6rvB~^Z5qeJvYQ<Nn<h0QpinpUUx9@zcr!WH7-NN{8^DJrrK|oaZ2g7IB z<!BeXD-8kex5Z42v@Tc7nI=>WxZcXEy2q#TS#HuR;eG?>Ni$DG23@)}u_U~+a1@XP z?wv}JIYIfPd8FIZv`;l8mnkGt>US9fuc8BkEZghlR-iX1z(txM_L^Kq{oH<oJb?zC z=whp1%l!8(0A0F?6P4!u$Y}oW*uF8fvtr_%%>`1phH=fAcz0X=6562p>zhpOrh6*o z+jl=H5v`i)LPu3m`y5oT^sDZ2_lGZMy*V|+-(Lc^TZUwjV-4FWqoquS8lX-u*Iy~H zL4D<654*BCJ(aE5P9yxI&HM6E&=kgBi8cdj>83v*Hdm(Psqq{dE%-Y0yHb3Mi=(+= z$5D~HMCF{h+;=REIHfRMwDJvmx+k1!Utftk`0b*GKLiOl$=ZDg)GBtQ#v8WnZHk&G zcovCMIFk2pSB3Y&A3sk?G~-+0F-Q>+{P<Guh}S*th62-VNlH;Dvn%y`N4@1;HSy@Q z;JNZ$`~2i3`<iX*y&I`rCk;0t$$w#G^4$GyvL^@d>FJ&fpK`1Kf<`vK7f$@+g%9{^ z3N?ed7&V5oD3SNZfJ`do?;<w|&qi8k*V2AjQo=K3huU?UCU-h_J{OoNa;N+-Rf9$k z?altIdA~ZKz}h6w>>V<?`c488d<3q}DkyLSQypZg*%NGX@HwZt6;t=@cbgy69q`?| zVkVMOVPU4e%wIHf@qS>=BSLq_Zdkk%qSB!5OQ15~PH0Jk*KJGtiusjhQQk#7G8ik% zmo=zjyLKbTf%`pjwQrvhmbKPq`20!G52O?>JET<pHgPD8A%rZVh2Jj{i4HjS2Gvnm zTiX>{m^r$0IwS0psqIL+wxGQ|c6)5#ubC#&rNw@Mv}dKsPiMb!_1mk7_{tk~@u}td zMsDC%EFBW9q#43Rrx~scvlxoNqRL{R;T>aThd*^=m<(ZR(h*Ry>-3%I${$Hw2Duqy z9iGJ!1-~PYnZlH@$nEZq1?CwCldcH)>S71tt+AM9!wPtw$K%VMVZ0X{II9~!t58!4 zuRls8x%2@${1_WlhIV6HJF*b})->X+;iil!C9)Db)1U95o8HJG14^t|Qs2J}-9syi zbqcTQ&)v?TZNfAy_4#phu+iX+m(FhC108fhA>VfL2xk3G_Dj93ZJ`}09&SqUCQ|Xk zDPN5aUT;@9Lf|}Y-`G{L(8;2_P3G8SbUVf2uR6(K1$TctuClMstyFS8+E2Azd`x5h zt(CLUx+O(CpM{Q#bNpT&I>Wn$b7j^w3pNcOYMN6|=~gDQu1|ee9r>9hm*4n}8i4W+ z>6kypS}KF`*2mkG^fq-f%`{{O&)ft0%4Czxe&zDQKJ5f5F0qpbjb{mACgRf3si{wG zF!PxOPFG7xW{2&Cx3dgxV#@)seL^fMQ?YmTW$@Gz&-OdioLk#M4MX@rHkCu-&-vP1 zp#hxKs~TOC&$9z}lNm22eEBF)bXr;})8%wj-A%j%{8gB$j_u0do;ES{OYOwWw!;L) zzdQMoM)qIocW3R)@1=LEtT_^s+ZN#b(V=V0#!b)!a;8eyZw;RM`W<OwwL)PvQ8Q;x z9;^$3$W`yg)BACJX1qp4-nD+O+2dW6(H!TKo{jE(N;;0WWvNyrR$m!;>!0)@HHsZH zHQtmv<j>}$ecRa?1^c6Bo9?vRdKKF+LadaepMj*uRy4-qszdCq%tVz*Pm~#einW7_ z1fTLZR)?rn=C$|&2{PDAJAlsV;@N3-4#Z^5DGMXA&~U<YSPqmg?8Rmi-gTe(0@a93 zssil*QOj@0Fa?y3UbY9y4<b-;$2Vur0Q~V7^mB^!{JS3)o;zCZQ2;U$m@j~;HMIVG zOY&+QNVEOFO&=Ep5L)%}NhCGD6K|QP2q8O&O(0J6xp=}3NW=a3ZR#u#ybm&Yd;NTg z)pGfN6?D7u-wL`(0l&_$Jlp{vaF;rg2z<ea5WYcL!8pg&&3|44sUAR2dayvvH5y_I z1JD)6<&vU5-WHOSQC<gN#p~atAl4|155J-;k0~D?K+Y}{UaA1_!^M^oU}&0PCpaLy z`xw+d<z5UNF1$(n1|V3Vu;Rgm$xgI6^E}sk(;OyR0ZO5I4h)cgWB3&^40IHsL8R+5 z|3}gDh!sNMdd)x}vY#F-po|$#=%K~)s)aw>*qGA2oXu{;eO;;CtoZ@{Md1P<mJkx4 zq-lf`Vt)g1bO@9Y$3KNH93NVqo*<UYy=gB*K^^I{*sGa+N<>mcUvxf6Sv>gVZU8|6 z>C>wKtF!>f>#leFuCioGY$&t&L1qasKo)>b0~|&?lfoMW!7pcV#|uk1t5xzDa&CVo zxEs-(&(yi%M!09POE`g@odE^JiBv+q#5aaSA`Cxe4p>ei1w~M)2`+Y2f?ot*vQBfX zr~Lqy3JiE^Wdj@0pmYL%0gx*`x&Sy{?a>YXXXE-V2E?fjNjuF^n|*FU76+Z?o6Tt} zPKMtX_89*rsns~+y^#H1dfvZ&!kwFEp<HCyM$M?X&L}O-{ur1~nB+CfeLQ4$3=*RL zN1o121d;k1IT1p6cH)M~??r1cuW;9euBFDSecAi@GX5R1fj_022(|*0R3(J9i@X1& z;~wC1*Hy=Xm5;jNM4S3j{4Jxu%XknS)Qqm15U5H#28z&6o}UJ^=ikuvXg^{;I=NX; zY@u2>{e+n>qXxM7AGS0U0jeYgK*;jIq=Og|oN|Fd{dWS+P33bpVX{26aC(j2DSsp3 z*prVdiO=;~&o6gV(0Q{*z%}!q$)<enwOI(D$SO1KM>`~JDqYlzk(A+az3I8Y2G=^@ z!g-%ZGLAp5%n=vG;%AkYXx#DSugkyhKkV7b)MKOHmMU=pZh#B#b&`fZrW-&4otu1y zcMWPDQkr6w>g-T33i~6ISZLuKpj%$YNp4FV-S7F%5h?wH-q-f-leemzB;xizKMzTu zmw8^oT@Jto;Kc>Vd!Mu<d5N>)n`I3O?AIM?<5iTU>zW(=wR4ZEsj3hJpyJl6sfnz6 z_;k#DV=P&8vp>*2?wuV>;WAP(-WRr@=pdOclsSIw)ugVLkM$=lw^w^X%M5{n#ib@r zA+iACC(^8gt9Z7Y78l-15(UO;C~UhG!k*RC!zT&w7VPD|v1heab9A;2J83?O7mUb` z=^uUpd<m-{T|kT#->xu0<PLPkKAe2ViK{c|IO&ew9Yvz&Nhh;bx7_CjnRDK!UL1TO zS*c_ja`A4+(lFreo6;O)9Wk`zv)(5f?Gj`ouwL6dBso%+SH5eF?`{w5=U;+Rd6vs| zX_uH}I0}Mf-GjNIp_w<HnYbr722K4el+J@^<PIGtz1-GC6~t{3`BYKUAR+O-zAnRW zElKO5jwvUzDcG(7>o*(DpE|=+Y|i$b@5W!IO4&l#?!KkriD?$XUTP!Ke{0F^2%?_Y z1wBxYAk2hYn69Cst_d6`#Jl8mek04gSBo=y6l=Y&kLi9NbPxYxZ)nB@D|8qZ2J<>K z#MD+hxLe!*uu2hlOpB4IqFk7fpjRuRfhK)?TOsJqO{`qXo^i9ld)t(J$56IgkdN1B z$hVE#pA0a39uHR;EL+J)y!upo*juO-BJ=5@adWSDC*q5{Oc0pH@Y;tD(Hz6QB2Io~ z_WFV4;=aBshOay2^%?rMf>0^1cqaU4#Cs|x`1HQNsHk~W-kfR1U!cVvnNyKab{M6p zzqW6Z^DBc-&FHn)>Q+9A(io2|Sr58`pJR*2pEYgIb3F1{uxm6eOqiS;)=Xkm+i>8t zQHkHuW~_Q;rh?K=_q6j1Lo>AQhFS<THvs|#Ckm~0pOf*;(#)H4t}r>Vn{6d@KjHo_ z@61&_Nnr8PGmq~Z6c9}CTi7PU^y6M*VNnv`$bBuCUtHV$_1~!*7U3r$zZM-lAHti3 zjm7*)8?TiMFBwNyNxU|FI?&0P^yX4YQ2)X;7*Wz*8~*_1T@ZHglfY4E-dp5nsKxx6 z;<3m<gY&Z$S}INLoCJGRy)lOnjaUrswx9nIDaPAONW|&=hvKgSNU{9c1XaFXfg=0F zQHMa){?DC34{jv3_JQ`G9Z5D3xzV|?o@GkGqC4KN`rIS6X!=blWNFv5-{-8WQRAX$ z_%w}*etca{1?s?MzuO|1F3vqr9XS+myNMsudm7cjb~k#u+vdi8S3fs8U#9J`Xo8ZV zzH-cu_;&VOd6__x7CaYbSQ}s9i#FQb@`|#S|LU63CG&nqQJZmAf5>Q6@QZcPFp~*o z8{#tYhb0~1KITJrrNdMj9TX99xb4}_AX&s=mR-XtKUa6L%CzcDt*@%#WeKn_lLAi| z5jp=5JGF&foHNC-rFSOc`;|tQE5->AN?UCLwl8U=Sh+R^eX))%VzE2Ein5+=R;0xW zTJk0PskRbS)kWGD*BZT-uj-X%td?>~LV0VCt@{#=T<n;5m}G=?an8OY)j-Dnek7w{ zHNTM{vR1qlD|XVwUxpbSC`Q>CfLQc6_{9pg3rNYXk8gbcQL@cYWvT3#T_w^jbidul z<iyXByr^8;WLFK|5>xJcAtKN1J|{=A4OKjOk9x&SgGYOCGp4H`-!UTBi9z;FNPFwi zjkH*pi|gHYRC5LKdGSxRNuuSt`O_;JW?R{HG0u>>?(Gm1o?u-VXphNmi@P#EZ)w_T zy(sf_>QG2a%faHtS&NKZI(dCyfnWJw2`JWl1)&-xhWA>x@V=*VbHw2mrima?^~Imw zmZ3px_^;lJyR_>TLXp@0Y90lsw5o~;Dq(9XF{gHqIuZ7r1myuqY`8na;9t!ws0<s& z8Ygsyz~jO_-2{i;29w+SQJNl3Dc5gmzvkf*SXi_^ki>Meq}Y}%@t;9R`%j}mdW#D+ zL8A$oCiihavlKyLP$i2#xXP2nvTJ(Yv`9r_DjK{U20SmUOFB`f{s4uZ$$TQv<NQTq zCO^T*IR3>2qvPPMRvzh<M743RGhekh^AQnLb7h*cikpxP_0z5T*{|atReE~JqT@_X z7&=UpxB82X*G$~DIx(=;-Z$vAdoL#?*eM@7fxhL^Cb^1rlz+a?G}2<D*M3Lv>OSRk zZhHl+J)nskOtY@-IM0BkhvhhZwC`W;wDGs|m!P=0xcokR^kMlXiz<yWPx38y>SJmQ zgs;P@KqvNInPgg3(Pg9w%wK7;NkgE1yBd5E9e1%=s<)yc6!Zc+UNOEg0)3KK_@m5U z)zB!!B(3Ceq1A?Vw2eUql!rey!(PqHks~fAJ10=;M<D3b&0>vBY(f}R5`dCy$hCqt zRJ^f}Gf9Vk{IJ5#Jvg9smnxqmM*mm{6I8TVriGd;!HTpq!}Gu9v(q>+j5vyJ#CW@a z@?M8@_{XYxl#qmom$2_lUFx3|9b7?>Vs&8Zlv<46^2VVKy6$Gh22oKusp1LlZi;;i z!e#eY{ASixBT#ai6v-pqjmZM~Z9i6u6n^UHS4K8h^dlR`G?SJT8}uD`CC76zWiyHt z{fX75rh(jJa1D{~ui0X_5$L#EjuCcw>o{L0x}y55MNYAY-HOjy#n)nKy;<rDh(m1h z_;;nI3aEv+d5UCj895dkv^nJ|jZPIq5XV@aa5?tTsQ;^;>)#VOy3%)k&_(lc*#?og z;|vvMG<4m4>srRsG^ezabnDU@_hqH))*wreORshWB!?=J)@A9EMgH1+jJ9La_p%Nz zP_)pZ;E&iFPZdZKGFJErmzvpR_Q^&I1O#Z^GHQQAmxm58g59Go6%Y1n|Kc3tlAzLX zd)tTgTESV$43S!zV2$%4PDL8$Md|;PAB_`i^EXmIdguQrKGtJM>UNex<pPo?SQwPv zO|?Pan3e6s^*Q;Gchk4J_flrmezA+H!@4vuR^<y{i9b$6!U;TI{i;<lhcl1Se!Jyf z^qFj=^;MBL0jGcz>YSdaSE=;-g?t|q*uTAN8VF+X%iTUpW>gC-66mVYsY&!P8;hz| zt%Jr5xy!TQp-I?FsFUaECD$XP^<_t1xmo}v0y*<@w>FgMoStZ<h=0JPYe>z_uAS)r z+Vu7;c(TtaMC<vf`&0PHv5kIXA>SV6wfks`=2<0>Din*TI@;#@ijV3f(qRsFLa>z2 z)uZ|;-pDC?Sv9omy}Z@wk?6lxn{N<Z9}4;?_!q~8WcgE`t{AmpgW3_e2x+*Ti_8v) zRzpR_d6|;ARN2w$1AQt*d^T4F<%1v~cKiM<V9jAd2snM<NFB(C_r+9A&UB>J1p}%r zOPX27Houy#X5D)(we}>LlNW;-Y#s~T(s`;i@9!UX9Uqm1;?QL*U^eT2U76&1T#Afd zCRA0|&isxEJG3^F9(;hN_vI^X=z8(DWvafhy`EvCqmR_5E<8r@gu*0~Z1cVjB(CN! z<5&OOuKre4s{=SJTOYt=B}CAawt4qStmg?o`wjoNvKMzHFZ%(xRIB-K6akR*2Z~9J zMNF7NngPS91|$g}i2DOwm6Xhz`o)f&f>ja+lB7NI=#G_?b>p<nCY<mh#3#c5grnT2 zy}<Ba;Djf$YYZf3KEJ52gPO7G<*UUdj!W-`bp%Y$0hWS4a+ChVGG=~Zs^97o`jEeB z5;-`XmMi+H-pamC`?c{#fcPY3;SiI3a_b8@<Q!)CPZSA6)7!WJo@5xnwF?tKg2Wsf z-;Z%pDLW3>&J007>0c!xAF=wLgAe}+C13%lGehmB6yhkUeZB{_^5cyn8M4dcmgib+ zH0K~bmRva8$?nllBl!hEQBOfuCm_2UfD*yUp%EGzV#AhNG`KuW@B2mPXD_FR^qQjc zxneZWuN?iC3;0%w)IysEw~UOdGb=Aw)70I#CjGtp1(3M$4}vXoy9@yLe_PCv`~l=( zYsG=WT(Ton{-=SZfzvY?2Sc)v3#F8-Z~83(D7IB|A>iB%0nD-gjV8;VM3SrnrtuJJ z6LJbRElK^4Dt$@|Nf+-Y#{M#}JJ){Ef0|SOaRH?cuN84&fob{BTd`N)&7<0_?-VY2 zjz_MSfIHduF4O~sHA8Divd<x0_H(a2fas{PCz^tvh*T#xO&A?!QD#o!5Ns!T87l*d z`g18bmd63%StrYrW398RhVGAUvn~+c^#9BJZQR>qNo9gF^H-eK=j4oJE2i&E`H&aD zEjpmcCZ45{l$qzh1IQ33x07E2NyJWIvaGRy&rU(3>n0&FDVY>ybF=O};g`C0F6i#? zUQ&xJIfLgxeyCBN;(3Y4QScfU*%^WM!Vn%PM<4{OjmfG_>ki2}*{nR*nl(1RND|Hn z-y3o6df-ZL$jKF8^#l!)7@RLeQF-ng7eA{p)!Gyx?U1Gi%Ldjp@o}$7=5l~J?Bc+F zK>dM8ybi9di95OW7y#0wB({Ky-8mELAYQMDZFHQv)vKOg^<gWm-GK%oIAI{X{0Iox z?@oWY{*P-&veqesA)r$L{2!0DfF9qRF>`nwhlDdSUnNw@^%~muZYMrsRiraKby5Ki zOJYC5X#dmg3xA{+ZNgoibRB7=jSlU|*u;y*=Uy~gttfXo*T4@_$A5^34XrJ6OX52q zxn-eR$7EeL!%(}QJ6pWChg>Xrk>vFcGCM{6f5sK^?~aqe|4l-81O55;=gYREAmz_< z635|!D);X90L6jyv;S#9`TPLftX2RBwug0R?sTrzHG@iR!&;$}8++2fVntb5TlwEy z1@c+W4X??0<Bvx0b{Plp{d35|cO$mDH4Wp3l1)H}Jcsv-D)r9gcf<GIiu0C$e>Nh{ zE&;3~!Zz-oYk0(Ru0Ua(Q4nLoL+(ixZ)N(eJy-ot+nm-g5cHqHy*P2MIHA@*<8NRY z$>i;4r6CygKDx65EIGTx)JftAKcXbu0ul$=$HDes<P~<n$D+bNh#K!u{N0;cgA~vQ zIc%Uz)a}v9*9%S_lp0b~3_!*?lzL@sj%iQ@-(iuKjD!FvK@4xR7;t87KIt0Ll38HV zxv%nzTGjThHl4!#2e-l_2Rijt*?+8V)t$-)ikw9UU9bmVX=Y1%Q%Wz^npRtS_f%#Q zq#9VC*OVC0uy2=YuO~e7IF|E)Hm%?Ekhq?Gu>?HhK-Fz#H$bG_`nY<X5A9qp75q0z zrN=q~W}O(U=bgj{_VK7)?;|A5!F>4?=gIuhmRIl(x+;)J{8$^aK{Z9phK2F>lJ!b+ zWs0_o)cVHyZ(lLJb$)q;qoLd;=!OHcWppV)H%~A+Wx>IXFaPQf|LE(TH#>Fiwhx$a zTeFCUM5aVAz4H2-1R1B<FtxQc(~2BGD!~E-P3Rj~KZgjTRefq^xb9qz@fd_7pU}P# z9k}&6Cgw1|z=l58O1A$pRxn=W8<WvX_MXV?VCkcFlY`BPe3Yhkqt4N~s)qjqo|YkT zohZ}J><*BFU%_JjeM&<bGEKU|-tVf#H8z@!$uiU2==3BW&74uSGUlY^UEK`B;WX|d ztjMBs)Tza$3F|T}<Pbtt?1xao(&at3G@1U)^+BuQipH`DxK5po!@CPb6BCkGdlH2P zic$d&EE<CD4K^z5y9t)AwD~Y6%+x8{?5t`b^1H7%rxiJOM-27sphW$i4j(xU_fP0D z!4$O#X7*Fi#>iK@dq|uaOl<GotE+!GA1m6r^#1B%5vh@l5gjK>c69-eGC>?pQ>sKE zuH&!tF3Iv|N@<MKt2zsNUxZ!ATGpTV;jg50<s#Gu*+*-OaLip|zv2E&G}%4g&)J1P zM!;C-)vLg|^qCZcNDrX2@oO~`ZbYFUxC=%hy&2{{T}NkSE;w_wNVmN$Ob7@%w9_aV zxw+}+Z9*ER%5+n-p@NDgL46<|*?3%kKY?e7959bfG{@^M?oMxNV|_{r?Zw~3s@KJ~ z^&LHp(`kG;_S5{?3l$d{?Y#tP6lY#IyCdVMpcbCHJR9q_IG>26X*-g7Efpeh#?vk3 zlR{+0s_J?NcvrPOmK#&9d~|v%hHB9~`p8X8Nk3NdNGqC65^MJ^=#ro3QhqY&PdH{P z^>tiCppct`tu10?K<v0UarRy>!*m{yn4~gC?QkcBTW5&*A>s<LL!R{mjtMKWO^)gB z_+asEB1qUTvE!%>$>kF{y_2fdP`7Z)Qz}t7d*%HzCu+IA)+z?K33sLyOJy>x&6F15 zoPwdW)Nc$t{^ohPrT+eU39AOL)l&~GFN$ZR$L-JhQm!(}G6vq{v$7C&^mdv|5vEPz z(C{4cll6#p)GgUAvdSq|g6eBFy6f>Cr@nKA;-T1;BW-*McF7R0vDg5oLCq<529f;L z7&AIt_dHm&P&2(I{b_UZt)cit;j_e2`==2HS{>}u>5F7-5F`-Et%S8vzB6c~Y(Lcs zYs@M_-*+l~He5XCSmzuMZEs4Cu#gxl_jxwj@HDm0Qb=3DAG{UM{`L!or^EcxlG4`# zhsm_zj<tibhu){*iwxo|Vfm!BQA2kgFzjO)hqTf}J=z*z@8r3GR8CC#lFRM~&~SJQ zZK5`OOi)mc{fm=<$z(NaRxC`e5=rsgWF|ep3N#zRItJ~V=>{hm+SDujS`>wewU3^Z z1(|$$CZ`hzanhvB!kF!71L@-u)^rREq*n`0$*8r5>qEonUhNnwX+u->qAMmgHJas$ zbW2qG)Lv_#MGtJkGnwYgq?PhG*#G)^RsYbm5HyVEA&YSf;`Gxpid{wJe+w!r#Y>{? zQPW}uA`d@2;O836xhRA;9+iBqR|-^3M}Z?hgBR0QaV9^uP|f26<we*nQ_Vo0d~?Sq zlMir+q&)iKUAed$p1fjAoQYn}+292^tu9yy_%@L`XovyA1aY*Ctpye|Jo}oeL!tfa zmqE0Z6*V>ED>HU0)mJ}5Z^7H;Jf7B$(K%?(mPT@%fN@5csjlo0d4_Sh$C#$JG-0@v zcll?y%grT2F>`aF&g5@xgB0!UwGZP&|0Yp-q3vs~!s(MH{dKSU*>`l6tZ|5+k~f_} z-fS+Zju%}~pT@lKNRc-;j7x{#U^yW!HGU-!64_hy>)`$kc^;&`E^$05eZ}|<|E-fc zE_<s2T`Gl5OpKf@H{DlljZ@=EJrvDK+)r|xKYrm9WHIZPt&JIiqx&;2wd0Ul5rI;^ zXh@B@z2SvVLxOjo2tkdA!-A%dQw#_AXv5z>7RtPY)@m!+MP5ROeF(Z9sDObJf+P@Q z1XU~49QTkqt6JZlm+YI(*-l<X0l`TsO?JoXH<fvB`USOk6e+i7itV!*n?1h-by-&P zL^Zn?;v-KUAVkbYR(_O8L{&a)x9o<1#@)j|X}VcGzeEGd3s-0VMA$u53+e#F=|5v> z49=>Ff__IpaEHe3hgX0b6+ssR4+c-Wx7$YcKMbjf-EqA~A3qp>uVdIH`Fhvm8(H(D zdYvmq(LpZZv1}mJO{1nh4?Jf={;#tHeQHPDBoQ|IPK}|B`)u@m_$VOZRUf~^)E{0X ztweK%Jn7u*rn*k|>hR@~W_Go!cwsSW+^{Ct#zMP@(H9IK?uwgEY)>WL#wdpph1QXX zPVhBTXkHpP)JlweyK1{W(y2x@q0Q)Jr~^)wqnC}7%`Aq0Wnt?BM!6&F0d^q-@D1*~ zq>2$jcSDWwl<luy8cL%36fQ0>A$Q2c-NfeZry8>wDBts;ybDpm*nL3Qus%SMg&k5( z`?krm)L~YtDd4kGC#3Zeu+eexN3KJc>!_8sj!z#uP}~2kpys=axV}8va@|jJ4rJ~+ zN=}D0Kzub;FLzR+tF3MtL8nYIa>RfBe0hrDr&tjse^04GeHX}47pmq)sd#EsoP^%! z63)||SbzETv`567hqtbOn70!ItbYb<kc|RGXzQzSN4e3PDLm9z+KNLlk(-stybYsq zRZe7<6hPG`rt&~@IeG59TmxyZT&-USJn!z-S4_7e)&;h$g+Xtuwl=aL2W^T>{B)Rd z8%IGQwe`f_Z?P)(#M%<f$}*c8^X_u;{$F&x2UHW?-aU+>BE9z}O?n5Zf}((c^xg%e zcL4zj1d(2)D^+Ufy|+kj(wlS=q_+eV0)#x@c<*!X<NenEUCXtY3C^4|XNJky`|SPO zUyoB)rJ>Pl+z80w)CL#}ZQY4zN`xG&F(Sgw6H6T1E}~uFt>zEaxx!<{dT!d(0+skh z9iut1$3FKtF~0-U=65aIo2TUnb|si-8at=AXV99C{=h=aZeB-N>^*0}dfo|w=z8-Q z<!=@)AtW<*AByYl<N^~kD|P(7_1oV3_OOd6<^efCo7fI{>W{=9XucQ#bM2)|4D+x` z98ZO3vFK;pIZXek=A)cBtetbVGh<UGkF1oCRPZjn?wC*%FdaEJD>H4{-n1PpNWLbB zNhtM%T*YPkg=G(DWV`st>LGq|=%lPMrKIXxl$WZ;acG2=EmWKE=p<>U5q$`K+-PY4 zSSl=GbMxiZC@=N&zKe|X2w7pK#)=g`dll!*K;g=2{$m%Lj%1gRxhf9J`aza({m50m z8Lsy<xsRtn>ac_uY3BDJ8^lh}2enBtniG&rse@M?-xA+`Q~i>{F!{%lVe2vSo!3$H zuEU172Xc?Pra&s!3=?ocBFFj3y^Ekb)O0RXj|OO1!VcAV2ASzeSg^R6xi%T}1*sh^ z$fu!B?eY}6=OXyqh?ljfajw_i(O2`PLvq~=$RsikpjN=F;Tz1UAUA{T8;<(wIJ%Do zaiu!=X`Y4fl%Gy!^*Rg6w5nH}-dWuJ&J$8W%&B%=jJB-;>gmt!>fW-TI5Y7^>LWD@ zOGdKkKB<!T&lV{~1E5kN4X?scak7%m+lE`aTtJf&DIfb%+O4vBG4u0r+R0PI=Bh=w zN<mA6emL*vktP`H=$$HxV@~puOJl_#V3D@_g%6|7#d&(tgg(?c8G`cFYzQ&N<=<kr z<VjM2Jzc{3idQD{8k2{aTYHqylYwc4pdX@Gz!l&3nfRM#8~kNe?xeYvejR1_3(KLA z3Zv)s(I$R-iu%>(=bkAaRY}1j@*5CK5;0;jv_0Z$TiuNJ&70n@kDAsvqsQ0od-<M^ zF4_=TbB-mt+BU?FpzKe3ZSJa|prpJ5AYmzk=-3^}>&n55eW7}Tg*0JZgPBc@v3+Q< zq%#K`jYG0+oJ&4ifcO2XzVvXD&SJV@k4NjgOs}-)a8J7B6UX>mS;>-F)Zk7APxbkH zBA^%Gl0Vrf_y?I7p6y*IS^mK&?RMxWRWslh<u=ePHb(}zwho9U<W;!;fru!}ExW;| zRN$)(@TamrP*Vd)++8j;XhAwf{f-@L-WI*m8_D4-Egbd#0~5ydt)JcoBpW{9pDboR zJ{fbra`KAC>}`A)>RRa8;@)#^<GlY_<@LW<G*=Zsfkn+XAWlpu_xeAOt+;0T7jM9> z8)t1QnUsF^;(feZ!w-XH=>Ct(*1B8vulR$v&}9?ln>$|s)ECnFXsXe=FHYJGdiHJd zt_jb?AMmr_&tBk|7lMZ#E@L`pF7fL1#BMY-8*9Rsw$Is<BvZ`+Ec)aJUHU&G3^esW z=>&V=e_*QD)lKSJLD{gsmCM<4*xO;cEe#6np$m#z$%@ARuo+^1G9G~A{(r0rg5h>C zDm4Lt8j8({#eAj0OE13C?(BkjCjY_Vx19cnF8<>&sHg_Y-}kM)!T?;$i_=m69L=$2 z$pO!w@~K!}v;QX$$H(9Tx1b{T*D?4fM^%1nE<yLB)SwILEa0w_0eAhW6b{1;@s?@s zKO-B=Zvc*#|AFlZgg6sAx&If8>-&r@t1GK!jQ4CkOzk<0e>BP<#EBJv4XE}h?f)3@ zshb#p@|t`EzCL%jCH6lV1e-sPM75h{AGEgArn1G`+P_t}UGg9)5J>C(hu#r~px*&9 z1|V!wFO~71?G!9SYCw}g0OZB09{rO=fTjCeqhEmlEChzX!_fdc!5`aLyqSPtKd>7( z-Nac{QtR)s`zy@9z5%IRSiQdw^!@s0BC%J_AC84xtUodb8iCkjV21aR`?td5#sNF| zx3cFX0{lbV9he0F6klARg{@x_0%|Ad4dGjFtbd#dPO5)|6=QjL|CTnbEdz?44)8JY zmKmilFds#pFaz;LTG+dQ+6dnGk28U14f@*&@vpREEXsM58s-V`Qs`PAZ{;}vaR5vj zz!<H&?>wRVeO50ENkBWXD}RviOFYUn=#QNzcisKyZ(Jv?%Ws_TbpdPuP?393PUfZ# zBhkN+jj!5fNn~VZs=4{tjr)!Y<ojo$jXDwOn|wt>BVA{=S4Ii^?6%{TM%u+Y60Z{k zWyb5q8AqJ$jKdT)fGhx2^+k5*qqRiSrfHLgK%l_RokuruF5VMFqt_08^UNX_+Sdl3 zH<ndig}i_@8In$bD$~4E3sov-gAU917T4-aElcI(P&Zv1`|lFI0v49u(#4_qM89Ca zcgM5q%d+ra{H)4}Khnod55)ZQq9?;bICTB*q^nWB8z|2ogH1&E$}ytsi%cC)jU1|7 zVb{D|tkLv#FI2l39G=9HzIZ}S{{+j1@)VP|adOxxYSw@N$26)DIvw)~%?ZHTl3%tp z#Xhxlm|nl-0vV2;mdMr-$Bh@o3%gpscj_WRiX;S$)W?)6_AU+>I7+F(lQ8?!{1B$M z)s@v~?TsdxyYP$X#dI2b@lB0J92G0ak<5yc{@H1-kl1uS7G~QcP7M#AgMKdQIj$ay zas&h>@WHAQl{o+=75AC{GUMI%K{J}ryHM%UoU=v3ZHmHSk>e6#kZ7FupfDP)AJZ*Q zg67`<Vt+xJNc%qe>p)S1u352cUUle#tPPoC8mXc^#dyuvH8Y4+8<~nIoYJ)P_P}c< zhwmu!4eld30>^cFsG}NvHgE5OSAU5k-Mw__eNu}>O*cX7E@<?miYSZ1CvtXYvgI!x zps~gYkQ8#K_p$pERO2Qyy%EZHAW0p`3O~KEi^u=u4J95Fs=2oI=MBwvIowKoa__Ct z^WbFfFes$-M+5Q`Eo>ii6_=;sQTL<0T>W$(@NTc0@awd<+aID;(yg6#bbFC5wx;~O zI^k4}FRa*0Ic4pL-sFXri{sH`DZYHpAMHdE$Ly#fT<vSpA!BZMUWCG>?!Sd-?p+f} z*YDt_;+*l`JLbQTo21ZWu;Uh)enxY;2=x~kc;XU$eCLf~g(gF7T}^WgPwySjw4vbU zL}(Wk(mfu;c&+6ZJuhX0Xv*^kd-;QoL?6btne9=0yKkT4{)pFj?vsBBy_-s`Aue*~ zJPPISzFAFxN{1yR{0y`-faaXNRJ##Cy1Q1o5D1=se(g7JG-Z|D(E8ox+k?ALp2tFv zOxy?wmch+k*^KtQBZ1=L*3zCr8v}JOb7MKhEsEo01LaL^1ZS9E=3R>jtTF^dmI3i= zCo08$G``omroI~R8EA-grdaP=^9*<u;OTR#;`W!$ogX+aw~MG(_71jKH8qK1y!2cv zeE0=7j++tmy*W}yjRaWWJGDhYu~puFi9~jHUp6%ln`dmS>`CoINLS$(uan;iCHB6N zr@+Xdm|@$M8@$<~dek|z^Ws0IK&E9DPraD(ij}mBUA0}GW33EQP%R|zX_qBm=eO%U zdIvmiez~ypU;(l7R@BVKn8u*~OkvkdV<3IsM@?5g(iB5Gm+;^S>r6X6JBQ*W`jI!# zgwY7J;s&}WcQ#e!RAxXgWnWiE^K-f6(m|?*wr88c8<X60#5&FmCz`r<YN928Ft(?c zQo>dvYhAWxWm=<&O53Y}g;OW1d{S+3)=gkK<H616E^;7pqXzR8)m++J*6S>0X*F}g z`m|__?@_sn+mDbZ%bX8XJK9+^*%>-s^saZ1UrRX1HvqG1{ZglQDH(4|?W=GQ?y)Y> zDxQG;wd?3h?%LNOB;Uv8VIC3@TK(i6u?f_<`xPn^0PW(=yKB5i%kYiXX2eAFFLi#m zN&eyKU)-)4Pi|rJlXDNPe3u#;9^joGL0gUQD##m0d#Um+DU2AzrPZQry(<>lsWR1_ zPR=DK3KytsnM8MtAtWmB)-^V~E~?TQzYMR;I9fqlac!Lxo*5^ha=J!}6Ds)CN#s>- zpG?AsbY^@xX@@gEOGAWw)X(<SX9g0~ynrs#W2GYB)c?s}SgLVzFXGAY*+V23sb0(_ zbROh3*!Nlz`z077n%~Q@E-Av@BjxV-%i@>rIugRoEKS|xB}DEfQMg{rv(R~N$vqjp z%i5)c>a#~3F_xkteEG-v+lG=XBlyLJ^imSY+@h$*jc6Cyj9*7T3LPrDG`9?$L`~@5 z6#qPuFhxb!$?_$t6GEaJ%Xytu_&=E9eoHbv5iUJDLT7h5d-93!+JB3a*Xcp}-t{!V zzW7u!m86?l#M?7gBH^g6D$=o$QADe%9#D3)Cg0?d9+g9{*P~3?LmSQ%%UZ;}g~~{E zG>FwH;!wjo7~F64KhT{a<Z~C}uH@A(H*S;b{Q|<7{T*5o7sNCR60RN$$n%3dqqB^w z{$+bwoUUiuoV2dj(vfHcu&)>EuSsRQ0xnA~TTZhJYCW$lfr7eEeK%<<AA+g<4h$Cr z@(?HQ(Nd0nSB?FhSq>k&eO%7>=Q${bu2(fP-R>YipHkJxJ3%AX9?i;HZ3K$QFVRUE zjOxZ1H_nRjzjZc6I!nh$8ui7U`$YTiPz{Spy|H~AD>5vkVY5*k?G0Wm9v#3i1A%g$ z_tFC@_Q@@GmoTZY>r7~~rI}e|<<G^VR}XDOR?PDIDNGIY6Nhj)KTZ7d12x6FzVC$> ziCeCy^e}Cfq#WJZa$Xd$u%$U`=~v|X3yU;pFk=%fIUyt^PwM&H+1d;Jl0({0d045K zW2#b@2%@8x?V}SkQU}5F)0b6Z4U;(3)5-P<M`^=P2>g^cm1?i~O;JvO5x|hnFwFbL zt@lZ8pXk1I&ti_63ZHeF`beqEqyj!K=CX=Oy(l(*H6jKhX@RmI0D>ZWmI&&U?Z0HI zYn-d-I9Mg^pUyoJsS`3DkshZ1$R0-;>KbLsHYV?o@S!cYn>Ymc8ix79$8L3)A_n`K z+ioy<fW}}@r+HQ&YyXkZ=hG2(l~mTmeE;R)IBm+UB@r|mQtcc(50ZdqPSBwJ5&f|k zk<{Z?fH+d+wZ+<+qM##p+>ezC)+9c{WlsuQAvwG27F$W#o-kQ+$+jBT0quq&$NmHM z#^eOH(3xcS&n@d}(4m?Y(@0n>9ORg+K;E;-$?))@NAD=5L8qVfgIdXwYj;<}{rFIe zhgnv`xNu(8tjhzP)Mt|&KKZEXJ|N@=O&DM$>$%&ew-jGpvZ7+kp5Q6jc+D=v_kPZ1 zWL=$mg(mj_);;40;_Jr_M}?^9K^PSTmY!o7;puF!L>yIpG7aB8@7dp97>SEWD;DJ7 zpBBQVe2~TSzTxe=<_M4tT%EaBv0+H8QX%l6cA0b63)7=VxUu~FMO}vtuDps&Dw3KH z$neW-MEj(xBjjjNy}EPTGxh<RglPHcOpV&w2P<a79P>qPO;g9V*U#%>0*q{wZCd9! zXxI&NY1D8-OKDW({JB*gt!BC3WuK|*Fg2^%E8cp2`8tR{IZ*BWX~k%mUs^2EsLhW< z5murhh7>B7)psJ&sdV}nX3{8X@{@&bwp?w$<E%6ywkYg#51JNP{h^E9?^&OG-M!C2 zZAzs@`z9CR4ZNmNMJ=3~;l{2ok8g5T6wlno4zC~ZX^1FOA`al3kw5>!`jEE9f!waF z1l}NhzD-@s)31<>9RpVjIt?=gbvfK=S_9(Ou4#E*;TuuLk!S2&f!JT6wI>l>4?&!B zIB{e<8nZelI<si!@@JHdMPpYgzN}`84IgQ<UEQi4o~By)r1VNF^OpI;I|Sjx5wfN* z`K1_DgyGk0uWQ~OCTc|6M2X|lul}zyHf^Cw&G+j>BtEk)nSXDUiD4ZLIcU$-p{V&> z>?H*=JU-%9S3MpV{4Bu{prl^jKcKm05Ww6pH6+Wt8P7VPCQxb+izK2%lJ^7UU8J_^ z^pF&sCfQuGMG<}0obNj@5dDDEO<H{)?w;IE%>0R9m;i>^&#<Tas9M|s&EamXtCM!i z9kS%mv><Ue#EUD9*REOLrNAxyE#7VU`_PS&ncZZ};u^a-j!J87JU$`M+V;{R>4Wwd z^``i(NWQ*%*|x7lglIgV-a$R6=FR3_cY3tqR1gP9bKZMk_NQjV`~{s-(OVNz$lh5) zn#a<zQs3v|fn@2Ck+Q!0hF3A4$>e+2mnH`4(MmU8WOX-NPjWV|P0c%7qYc|dF-KMG zT=|-CtxP?pPuMh+sEf#1Pe0HHT-6HxVJRgYw~Lah!sO1?q_~B}cMVyon4Mt6igqx( zVut&h$4r<krP*^%oqQc1;YLsKpk~Q=*YW(^+9Dr_AfG=xGj`v<pF-O*Hn%DhbNBi} z{yC;`a^dlYCDiMu=7BjO7Ue%dF!PPCQ4^Rao0#_MQ?XkkzoXs2z09YK%~#DpDpzfl z%pW^nZhx7D{-E~+GDl8;#qx}t|J}ucl>i9pUzU;7uZBUn9)Vo9etS{i;?<Y<tKbEI zdluC%8wU^;OF;D%3cT&qh(-C`&lK}S2q=F1lg%vfEfW=h@(7p_f;aak?}Y(wbcVq= zKtj(+eG`yygIiA51ab$CmV_RxfOpl6X0Z&PZdhIdv!-D1;oQW+KRdIxCbfYpN!+x& z1iarMK}^WpsG;tkds??lm?(k9eljZqXqm45;8_p!l<C9nUszYzS~ym}!*Kw+#8Y3( zUq_t4Ktxn+>I47VeBmYl;6}e>z;?0Q8x!wVyaG5G1DR`G^bk;#G#}&Bv-+o7<l-|k z`lsc1%TXZ10ref02gBXBOAVdBkl)0)PN3^3ZuMWj0Z%+amz@6i3oFO<(h!`y?=bvJ z>{dEVgj`AM2X<$Ryvg(#8}Q4R%LU#|;!8q_8!wa5FGSbh5-{%scg#-Wo(7cQ5%!Kg zmO3%=nMN@r+RG868v)C`6jVU-a(g|M$t?G549atI8mLYyR~#%gaVI2sg_>RoVCdiN zg8uGx%x02$QI{sV;dces|DN5ri=XAEb;%ph+=kbIS+)~OCeA+L^2hpgun4+UekU_X z&;MWDFNXqsetngJwF#1qZyRfU{Q&1j;-PcR-yNT`Bq8%Q&C0#B2NJx!Z>{?SAbLU( zy_f!mr6C1}c|Q|cTSfL~VmFq3Iw$(feI$7_8ROr)WscD-E#RD;#JROK4CFs7pH>~O zJtuh}Ah&UHqysd&@t-X1FGMH*9v0=lhn<e=_Hjr2QvWCq83E)D9^^mAFFa#+IR7qx z+NWQUtNVlj=ikk>P2iDa@Hy?^czFahLX!8LlYg6U)^GYTdbj5O?)2_|ZU(j@mMdzO zR?zA-eMIuC*UG%$-zTxWL&j$ZFdk{^lZLK{Wf(L;PRQ@zCCVO%z%?`(Xs<Af6g!fh zBs}fHWlvJb=Lxra%c8CSIZ~hf;jI4JfMl#90SE3vwfOy~QmQ(RT!mH3?$49vn)8*2 z4;QXQ(H1uqUHp4MvRn|MpU2vM`eG6s{$|)2V#<A6t^6~VoEdk^>y3I*9@h3YwjgxS zFu2~ZH{m;=hMvX{?@IS*x)v6uo2)?}r+BE9u8k}gwItfmvS-&S6}DGs_cC2@;eI$* zx=HLJ2<idf6A)v>(Qb|%bZhPsM^=@DaCUmroV^~{WZ*KZ(BgJ&N5~Gp_DxPh^&(@w zTCjCCrEdx(v#*gibz}qjFoLOxihd8m4ua#%bB$X3v{O(i+@K}y(+k&ui(WK;w%_}N zI9YKiKEBr}MU?&$`3-CxKbEys9s(l&rI#4uO@_0mpv21~*>>L8-5+{RykpOn3@SOe zrgb3^>iU(O(lro`RIynO1JP<8PuH0%?C0}<C2&v6IfE*Xa;|8^E!@wPr&m&5;r@dU zL%_d^1bUD-;v{ZSP%!VbIxnoCxijvm?Hz`D%zd}m<2Svql(r{Q&CwdolPB(&#}4W5 zg5qr9>e!ld$3OQrk{(MaMSk!3xY&F9#n={%?SB87`uJ`M@H&H*qa~3Y7&%0LSF=A% zU01oyVW_iaw&61WT6R>dW|+jEO}+nhh=ve@K+jO-*J|ZxS$X&bp{MY8-SF6COmjoD zlirWHRp|`lWus<<>QZ45z%q($uH&P6zoNH6&w7o9H3^lf>(76#H54ClDAlVdIKO+- zp=Srb+*6?B=E(pU`947s^wWieubuRo$cTuOqG=1`4qu#zqbhGCiSkmE#4@Y*=iJxI zKOD8(KC)=BGua?wV49)TXe)REzC#clVk|M)BvWm{=dq~bnft@3qa<GUhlufTiI$ev zzF+UHrWOWvy-MVrA5u1me=#>TTV5DRYyP5JhxiW3iwB6O{mO`TSV@k#AuI(-S}-ju z0na6S2q~Z7FJ3+nBdyn%bi(EHeHt_9c6}#wsHTI(xJr$9PLh7$W%VO~Nv*G^83=n_ zV1Ldt{MfY3J-bq0N=|9hp>b^FFDwm2?qEk+0^!1l6PzX0I=?2lNL)!D7CSIgdT1Zj zKblsgTBm1=7ej2Kh6hn?m@W7f-N5^XZvCrf@Dijy?%CHaa+E<A>2yOUuTH}}$OdMK zwKwc3SM<2hb9v8W&8(R19)0cO(SC;bL@_Qr+EYnrSPmlspy%Wr-NQ_9-lN%^ZDA4^ z;DsKlO77#u*6Y>;lbfwLt+5iVT#0<@P#Chs!MiO7%gCW<LrK81@i#a_kHrA)HDc{? zyYGSv$5d!WZp4xM7C?9_39l_T{<yclN4?D}6i55K@PXe?Iq?;cFJfhl3T2PvRYSO# zbX*97d!&l}?wKo$e;*{d<`bgD@0)r!T3%>ts8Mq(g&glDom`nznLIqD{H$%Pn_ELg zW~y&6GfiE2iF<6d-9)xLLp#Oz#<}P7Ti5>jZzvh;tZNqmk#Ki~jPl4V4jr;M9v|WF zsro&-<!Yp~BSKZPT(5Sgi}21M`f%ntznQNW@)SPA!SW6EeM85U9rSSM64l@{gl|~m z%_ADu#z3Y`g}JA*0&KosLhT=2-?JMfEPl6RwU<nXD~HN*ZptsQ8KKIr<<TP3Abyx- z*!jYe?+2F#LE@WmMzHajY^BE5MpGgcoH1?Go*?X&yNIFLrN;|z@J7)(Db#fg=iFj0 z=pJU0Du=4B7V66Mn72;|l{0$yZfv#aD0PqELf6#%8LfkCxIlz=`hD4P!||d@6#aQ2 zO7~jMA$_ZZ{>x)%ScRchU7T%Fz+=bnN@=8nG{PFm<C97=p9_pKwx3=1hpGtn0XW8t ztE|ye55g0#w~=QcI&E>5tg^d$$(o_TugbgTsGJ#Fcg(TTg#+t|`LGl5RXo~Bpo%rL zL{fpmpf0~m`j->Wv{BRm5cE{4d_d;C_bZp60|yA}%oxvv0e7FIn?ZgFu#p+G%~KC$ zFbX#^uUC<DEx&hX4`aJbd5NHU_;|Y=x-@g{FonTKnOwucA?#gkGnH_EqR^<FRh0*4 z%)?FCge*L_^B<`!_2(A(yC3Gl<f%+RE;9fg{|hS`OfARlXRz64K&^w)HAR>=P#H)c zjU{pi-rYO37n-0AQL!F<-fo}qh?Z(h(D&LBGZciEt_`Hk=aL6au2X<);g(cRjzC_a z$^zPCj4;dHlVVzJ%Mqc>#zm5J`l7DPwBO@LX&8IL*<i0R4vBvE^fxw2X1nZ74YRZ8 zxFQbr0>1(6q>Bud0d;P3ZV-g}hPgwq-%h_|p%Sm0Ix?$dOuJ%VDf?ZLlXeORj^s=! zPg0iCIMXmsV&&+enPHkAAv>!2%f6g2O4}X`cg0q7F-OHHPYdMq<D}Fxe4FAjFj_R8 zYU(fzPSkEGthPaEUSkDyGvTAyko*|=pouH948ixZ&#Efdnk!6JAOAFYuEjsGg#8@U z$GY16%&kPVOgiMyyrce{`z9UDS%6lW>ac`s5}W$D!!G)e{5w6&;fV+7k~3n=^($s3 zV!^8;gj;>W_@!)d>!Y_2T4EpjPo<heFXi~Hk^V#iPGOYC70=1MQd?WCc;2LoZs}xp zu;$S}T*>l>vLIu2qrUpz!)DGz*f~dgm(2F|P<V=Qk7h4qOB)(R>sueu&g#?oIS+)b z6z)*cCGNFh8VeQXGlC#u9x6VrUgA~gUcUL$s4u>;=qj5;{RIyhquWwdx|<WdmPA3* zU7XWsbEJi_eb=;$T)(5IqoY%p*2pw1{e|)8*^i_g{I`SGTOX>>wiCy-xdGniXbk(L z90^DmNz}Tres|c$3J#@OS;@zD)j9UdkDg~w;tCra^SpOPE*WJe8}<xOlM-dGivY)o z|AlpHKa%OX*Cg85sq%LH^Q6uW2~yY)R(Lp^nsM;cty>?sQ2T0qf<(d;2U97#XFwoP zfn+0BsTe#f#q@)Qc9O2PV?**w40yz5^I{61F(crz?aNkq8nQq42j(2O473)GW}?d= zci$Fp^CZ?^Z2F?=yTSEy={=7{0g}CY{r1w{+ojmtMNy7vQLwG!1OwDLMQl{WzpjTP zR7z&l{709XeJ~KsW_R+QZXvV-7ny5@vWKWwJ4kzc&}@$u<dI|xcT|vkkM+KoR&WPE z^s1n3yOi|Dwnp`H;*7Gc^&Ls#oE+Go!t3}5Ad|$>_oE;3^DBhB&fv5g|LS;FM)Io6 zfTn42gHEg)VB+eu{aK9Uq)xW-pbZx!mD28eMso0s(t>iorKf{aRX-)$VWtwV0md~` zO4B2@#nnAq@}mJLpd(KP5<^uMA6OE10Y9OQ{QLrIGyUh-7703O4*cijG|qw7#;R`g zG56<XUx_q}JHm-S0M5Jw;B`TQ+U&`pY-&STM1Ub`h>L4C4!V%h`<+%LpAdD**f&j< z_59;I-^+!J3ay>%kj?#qq^N6!2<2HfdX1a~#pW5lUyo_OiS|;s;Y+e7v3sv&P8K}8 zLDor^6KF2BZ|r=Xh{y=*YIKJMIGlI~&~DcG|0-`+d5!Dw`UB?i*7KZ~p_lALVM^1X zJS8_?5ok47JWKaTrJ3QiYIG>;tQG%d=3H-fBSo@KI=k6iCEKqo!DtXKJX|?z7XA$e zcHVT>?STmkb!+>@$}yE?n<<(-votuL&Cn#K%ldUN8S+6pL4cMQfmWOWJ-%l2bMNos zem(O8$sB%&c7^BBb;P&`@OLc`@L*YwGLWka@tz5_-~Za7&}9k~RYa=6*Zb5a!ZX4< z3FGt1cMnQO`NxV1)$$#ib;aIAv(H;mYv1?2k(*R!8=8)+Bhapo+-gTzUOx@`CgBUl z_jZprfkeyVc-fLW&I|hO7)`UC_2icuuk{8v5_l{ZI=;zm@h|?~G+yojsAO!Og9*{D zNWs2@XeRo`$>T<MqGj_v6T8|H)53)eF&>UIy)-G>P2<8BHo|pm1A9z|m(e)8Wqz`0 z;*j7hUTzCj&pl2K2M&%gzakDD{ER8B*bGDHK3Y7<o`JsCuS;yWGtTT0_bBOyiXz`J zOY*R*BF^wsNdu2;r=Vq84KZ7dH@&Km2JQ00^kK{9^awd#&@EIy97>Dg)NPw_krmwN z^)GOerfkoQBYqJu*U((k?*8xrD_uEOcW-z=_OzPEjz78)St4TDGbBOGR<eVN3j!7$ zyWKkitn&S26cFUjOX#bG7$3=BrQ})-r1u;0aNACE^goGh{UTI28X3m@?wU+it5c3( z4#A~!X^}r&0gM8y&|63~X~?G?u^K(=6d`22qu7?zl5R?MplMy_>a@m@=oK^JCp$_6 z1;Qw0y0=x=Y&t8eFuP1IIeTkN3eu_CwI8=X>zmb@`~QNaP$9mZ4iW;_H)gIwFYOad z*8hfC^UU#4!lthQ%^JYO?>Jz0{pWMb*cZt!@FG0V7T!<Tm{mHX_!7$j;9DdAP3xZK zzmZtNzZ>$slq-(?jq<?Z+6$)dKfl0gQei&KIOzBr`fB#|0iq={FEsC8Sb2Dx|FkhH z9g{axh2^309&rmu^I0I)-LpKU0G5lZfzg}{!&3YkO&0$D!TZ<0QE{gV+mf8;%zQQg zC4<3TK@GRoF8>XE|3s0d^V-V>tt`0r-gaZJmHnF!C~uy|#SAy?V9Wv0L@mGxU<d!F z5p!6$-sFbiE8?+k`6Ifi;a}qaljt-5|7gJlHAySZ6;0TCxS2SC6u0@i4G2PoO*I(@ zWAU%-o<AEg0Or8A5{?uHRt^XJFu%M3-k?VIt%{mi4#4`<P2M~CH@r>|k-yx9W_yTf z;plF%vQKNVtOQMV5P`$W)Bo<R0W?H~uHuvY>A%zu|AXNxiSf%HwquKY!~!MBe-~f) zag~t=PXgDtNgd{1(M{f6|M$t6UW3o3z|tEIUx?QAyj?}M^t&If{`-EA|2_WYbn@u1 zO7Ov!{7)A1F3r*}L_{YTxvhVt%<fAk{jrV3`%h^OPoJe-`M<+=g86^5Uc-O*TK>$( zz3criS%MUh)>?wmA6roSZ)(mH`rixxR{!fw$@#tVuLi!_T^}-(cybpYO)$@x&xfH! zwg%N7pg)BF!g9$3bUuc^2_|`<=p)q*ru8o@Z8P(?IS&AW=|536SUjf8sGA6&MB`aW z*?%{`5FG=>4R8N9Ble)P3U3o5$Nm=<=(ncA_IJ6+D&XtwL4f-eoM%;k^1tOLOupQ1 z6$DDC3;~5n4l@42;yG|m`WL-{X{|o}LNLNrT_wMfZHZ8EkI8LX|Bm4TiZo$J!Qr+0 z`ShI@T8hV&bna*AnhLRTjkC{Zh9jr4o1!vkS!ovfw0m`Zcx2diS_-1;hzN#vGVCem z=!Et!+zYMK>XPdltTW%bzn-AKNyA`+%x?-hjMfQ*@cdYJEaqRwt0g<%NgPOgMi)1& z!dFq-_nD_XJB7;oX_^nt`5*=tc--z>0EO(8Hw-#D0$gndGy3bQBhgBU*@?x^0^=7v z2-5bylJ(vDoFWrUB?&(W!b9J^$pF8ChQ`6<!`3M4XKd=GVz1)1hcXQp!dlr!Wj`6T zCVy+`i6^Cl*~HoCL_U7jo5M1L)-LF-+{@RG_e*-p*ry~#BEnm>B^z7Li#?T^`kv=& zZt9q@f4C^lQJ#hxae$ZcV%ONwsr>jly{tFfom7aJFik6mnd?onsJd!L>d_H<=NzLz zY4I=h5rDw)gY+>kN%yKE)0$y|6zi6bzH+n+#p%N{$IF4MAHFY(X$Kt&Ssz<?d@FnP zREl590UpzgBtDD+<efA9RPxxavdjg08S0TUhv=t2G#M+mD@fSi3YnA(>3RlFt1&=E zRV1Wq&j_xWDP(Wi!pHa<ogdRl{mSGr+8ek1uI3fSnfD;c&=>E!l!f}6NzAx~Si0#H zh_eu6KG$%hE>`01v#R_u&Pr%W1v{llMIZFTV?l?HXd+a2RD`F)q5S3<%+CJf_Tn8X zQyQ!NnOG}>oVp!PRg0;@8PCl2ixc`Ty~4SPUE+J7Cy1^f+5r;JkybX1aKQ|nEMC=Y zDSe;qk^ylWysT7upH!n(@o-2*Hc)=5xhF8-D~2NaTC-+Sywgy<rnLc)R*@lXV%ZVp zFjTy1=TF!d&V~P?L@yHNo*KMtx=tiVwa-l6A^ZjX6uA@clg;#6!dHG#`pGqA<w<4$ z`(DYasYzXeoKfE!6>@d4fa2r}r~db+(EEO8x~O4zHNJ{FVq$QOqY0&Gf6lM_>{=;T zM7jFGqm79`a3I0E(8+vU?Jo)=Zd3+|FT;hGKvJl3cy(w=E&;H>79on3smT@)=%9XB z4MY-YIIqea@c~6W?R{h?TjLeuSpB})945p>u(Jj=#>W}iR*CaK41#{9<`?E)&gQ3| zwv3262{(5vxzZVSZ%f6ieSWo-I@xFU6T+Y*tgj6*S1PPcu~iCF6}PVO*2`ha&$6sJ z_c_o!poEN<zikVOfq(zmZoBZaKTz@caG6T+vI=8{I(->tL!-x^)!L{arI*KzKtC}% z)v8MjM2&i1)CGlA$Gl^z{bJf<u+?xd!<SB`1Qk=Ky{+DY71?wAQ9AbSr3EykL9YhI zY`a-ahl)P>g)0_5_e-sOk4-=3-RBhvEH3&??5+EGhRod6+iQ;y??j9E-m128g5P~; zn_In(L-U&&$#D4CHOYSlWVkzbEn~dU8cH>&cako?bER6v`z94mv*mO|DLc}M<rbb0 z-1!3KG>QU~tO6P(@lx0&aa;~1QmGUXVb+9t=4eYDORqI8&d<7|ZEfu@wmce8;yV6@ zQr@GRjo#+$q4lx^uw<0Y{PHHHiw$jsS`R2@ulI}SZadGl5lr;JP&WevO|-L&pG2?N zzCg|tX!wo`&Euc7cYlO$S5`FumAf+InDrZ>Arm^88f~q$S!xW1A45e=MFsKstY2IV z1lg{&VzbEt^Xaf0GSnFCU>(bEZF0;?s=kFqAJ>@WbD`3$x%9H52O)U%+^{&%xC&gu zGu`eJL3?CtXAW6g3dB)*n3ogR!XQN_T5a`>nmxxcwCPF~)vg>|D-};4T~n7$sjgRQ zGHukN(CE^Y@&zK!JMFzU<0Ko`Z{DxLKa)Fo^?L;r3$sj@8!a0MXOs35)R}ezal^(Q zo#{Cn3wSSRwT1PvODGQ~IR_(lNMA<T(_X3>#`xiHj%UM(>p&VeWwI}unxObTH%=p9 zqVGyG$|d_cFKp{g?RDuaSoh9)-I;UU@nOdnI-yCz=`hZ(mf?S45mceIeT$uf*pN=b z(;Y1C@O8@0Un{Qc7=v7bH(~Wpl*sHIQZ4vrTtQr%ySa-C=N404_x%Di=Ri-En(~O_ zi|N8Po%v;bsTR~JJQeB+o>3$Yxx$)>89sP?S|JbqLcII(p+uO+rI|1d-FOjgGo5FQ zN<)EDM_g;e5qt59?)KX{r_rnO2(OpvaxnC$_=wZ&7)N9^p7)+=ipNizh~CNSU*EN= zxi{@FwPB?^cwRkPaVFE5ad`2BI*95e(en?8_5SscM}mm!ua+d<V5(h=fF(Iv4w>O6 zJ-<J)cBQU%lvXox!h1V`t(ze_FF2Lr=#vuZCHVU$2G4j?o)qmo57-6)tDH>tc@9h4 zG+Xo%>M7X1U<su!aBLe_WOV$&Kb@5;uHyLwxj&bIf{AZpS4~1U6ETv07bxV1<|uwt z$sE;K9HF1lBPGD+3T<#p41FVgOrJ{hw#B;ERf^C8C@#92W?2vE(Tq}Ic$by-_Ae|l zADJUT<<{BlHY4>VQ+3A9u9x97+ZkYqSFqQuiIMc5h|HkTlD>i)PJW!}*T%E46nYRx zuCW1e3MY>7luH|ja-|D*B|w_t2pbn0@lyW$O6W5`(L4R}GP$)zr=$<1=2I2Br>e1A z8Xl$6Z%WFhL#lZY-X<~U(0gdDn{ruUWXyTbe20A?qJ7{EkfKyM5eh*Tr4_+s*yJOB zOw*m3^5RovI09}1&bG916;K_Mk<OD)C49AI%nCC?TS|@%<bk5B1d&e3K83lHIADaJ zA-zvg2{7-bruo-hHAzD%jNiOk-shizDko0aoJduNc@%a7z0O}E`Y&RkZn?2gq9CdL zf<Y2vl)H*!a^J_ISwZ&m$&S9~2U}m<h0~o_AFlA^m)w{2J>NkHgduUvP+r$YD0kSQ z1ubCT%#96VoCL|AbIepWL^aSfis$MgISv#_0i{#`FPAH5IQ4cnW6$OhS46YKHxaH) z#CM}tC(_=I3RI=X5|KrC9#AnsDan=rogdrh-ZRnLq1wOvaJ9zHqJAt6;1C)ThZj-o zPo=R0yfez`%3&isEFCKiwCyS6F7NW8Q!R8-@=gwd<)cQ=T~OGF0Hd2vATdFZa`{0J z)vPVD5JNuQHTDSN^)}bGb@tfyJM!xSxs-4%nE)#{UELEB(1&Yo(Bp-|8SjZGFhv(X z>XZe}+rJ?8n7&U=;9A$Lm#2`b*4(1(`9d8>g8}K~%i0o$Wzxfx0jRAXkX;Z9W@1OF zSvh+-!iXbqZ3C*zj8<2d2%j0JiJULl+)<1UFmlZnu#1(s=YKdCK9|V6gKrsUfs0~8 ztoN+n1|k^1krvW*lle2t-Cb0qW*r($<)j(NtxFe|l`%TnVzZQ%p}1L<rc;U7BD@BV z*_CoQrPR2Nla5Mh%k{i=NQ(XVYC504JFge>aMuIRDxM}yOvP&{Z@`Tex)W7Cp``CH z?V(#Bsh7o~OpHT2u5Zas!KD|<Vv_aahkit#$-`7&#kKb}@@+(kU#~tY8J@|{UEL_k zyl71qwz|<LDyC~uS(Mc@b@>REB9Ttxm$&N4thu>L--E%PuIf;$_G?;KpFXT8Xl?J9 z&BP`9G?&Tol<$p4N!fT`S&7{P<}7*pYI4w1#7SR!^%5`qq=(xsvtP?}SB?W2nxoe& zO}Umy{N3k1hr??J*NW-um+dY7+HCLV;rB#D%X)Ik0bgwmYU)~f6d_~kJVrFyeQL5k z49R|_%o*thQ**4OiPV*Q&cUA5V|N1+5*@q-So3da85k2sQW*k~CH1%<i!SzXTD{A{ z;P5zaj4GpHY0I^`ze5f2EW*)K&W7Q$GG*GURwOD`A8(ci&KXg-KS-}CRKPtDQ)CP) zQOYVg(>h1=!O42ZBux;O39|f1ypannM0_5{w|Bs_{ksq0c~Z~(g2hWO@%D=7B3s2& z>^%B{z^N8PW&Q6J?u(X|h`EU1UxM@~2_r<s+XE!FDe_)<nUmq81N%T1(9?k0A8!=Y z8Pd-C>FjLdC0R#RA;T)ttMdJ|ehaXboQFu9_paVn1?FZ;i~CfM>P_MdMpV?dQfK-- z8QhZb14=5l3<#rKvu?NC&yDw#fA7~pB~U1mu`)t59cRv-VL3*TybZ?Nim6xMdmChv zaP<f&hVo_1d1X(dl*Xb{6jm<&t1YFoLg<7HM#*F%w-j`=AOoSD+dB6+PwH)(l9efQ zZpvX@K+8CmtSl}KIx?iIc8}$&v-d1~Q!=Jv7IDnAt_z-#ArK|E@JFVf2S&gR<HZu9 z=mL*A-lcsKw-N6g5m{cz9F07oaE-amVVautF<PWq^6qo4${D|AxOqhH1g&4d*RIFY zf-Zs}T}RnAwhB3imLyVo@!IDP^|A^h_rrv`=bq6Lb=MaI+0|`Z{bR)uaC-bbzHF)^ z7k8V?VS$k6t2J3}N`_2jUt>cEL4mTG(Q@=kWKNZI8X{Y+UOJv`TIp=__=fB&CXUVZ z_L&Sbd(<0>4&%@TA)!*uMGR7NQ6ob`Zu}T=v)+)RXFa<soveNSCaW4H130d{Q2szf z7PxV{+8v4AOSk0c32+i9`+mCqf)CZp4~#peByZDZuy`?WSmD*OD$*+Qcx~k10;tgi z`s?2$jSh5UlbH_9CVy9!7_on%J6(u`qY9l2sDfSuEC)VVHtUzo>`5jN(cllC)>ECd zeRfHpd%6IG_!6dL+H-I2XcMec=Cs<>a&wP09aeOyHQU_WL41g-7bI!HC(O2~83|K4 zQyd`m{O|)*rlon<?)$E|>f#X~@~HnggEMHkUkP0U@0lHWTSx<jKv&G!zi1n*O7L9( zc^U)A^F7A8j`tr&%on0!0MFtvJp`_Sa_|~hI|C?~@;amhI=D)H)e<OhLI32gW)XNu zXBpE4a6k%_|FcJNYXv~=ScX^t{=IRAR^7r}UQOQqE&N#CV?M?G&DD5g6e{Li|14g@ z`w?l0jwl8ya)j_!{}GMxg<zj6KUg~9&YxvQY*3t-r#j#TU_pP<pot6XpOPYt(0>vw z9I$hKyBTbNaimPfbWUJG8)pp#H*zoW0KtOA4$yCtec)I?<OUwPx48=t9P?rJr~=Fr z3Fha(iRXhQuYjic9DvLesz#vGDZdFOU&`Ly|NVgCmdVn<@KJ$pU1(Bpk~OVtAopKb zi|5Q|n>aUDmI#Omc(Bm&*BCfe<p~L}Q1l%<5zBnB2kvPNw18tCn*;<%73&-J43d*z zonsgI%pC)qzZ^44b+EhE892||3+nVA9cQC7Z{!zg_oA^bWdZgiOZ?}?6|G6~wVF0i zediLWuCWJ{m^lZgOzSYW+@j9vSdeJmrGkzQ%2Y8Fr=CQT5~g?SC-GtS#srQZ<Z1i7 ztTJSIpSpHjTj%IbrtShxrQyw&4(g3{BEO7PZ$_SZa@o6(5Xp2rukHcKF`J-oXRD6z zYs2QmR9CUf)f&GE_xajJex(b8&ZNJvwAzv!U%NCU3A0b$6+FBqzC?b&+z6r!sAJ3z z1+3Jlgu)e!6yAn-9hr-mtc;RtG7t?x{d*9+pZ+nSd?Cm^;#bCifqMdlpdB#Nv)~;J z`1%Swke44U(ZPBG78?Z(c$DEq#cxO*WvpN(YJlsekw2LR#HCh#%osTV`4!7;=YlWy z!S#poI|IbmKcO&V3}-YiKi7mkSr5iK4#}mPP*UmiXRgM?d0GKbxE1(wSf9a&fgPQG zZ_3}?$Zu**J)x6k+*%zkC!nU*c@g{lwJ$r9%m;H#;QfY10gqi!I+`~Lae@x71P;c8 zw@YJ1T+8)hK(Bx+P{UA+X7aK(B~Fi1TG5j{e?sDE;3NY@{Y=NSN&spu095?Zl=7dQ z5GSO#CGkHWEIzfdo-7bgVNbo2OtO<u<niktpUe}2{}~A8e;&Hhk}pK^#vSd=bM_%? z`_C0WhCP3S#T1NJep3YKBPP&5*%d&L7^hYZ{8c&aVA|>GH>$Dymf@OFl^uXyvHPkD zTCsL=&6J$KcWQ1nQA?-1NTE8utZf{BtEZGR*zr+PyJ)#VDxOZMj;e69YtvzpNz?Ka zd$TR`ANSF@1!cJ5PKnm&Y(PLifEY{sB1}3R?^b0OJ5Koe$o1R1Cg#^S%^KJQdz5KD zwe-LY=OWy}eG}A|7F;(q9e||le(HN*ou8sPyo#l5cKzl}(CH4DsVOXtmikr8TKveG z8j<`9dHdWC&^p7zDLbGRDcC*^yXT7FRFr=;F79-!#9TzSI_gK_8r+LE$;>}?%_OP3 zQ3)s6@=;h}&7=>5{yL8<d$Vg*OxK$InITgkr=)VkoS7i8ZkkPGh?_?CO(@x#PFeD{ zn(}ocmv})b6{z5v5FqVIgXqxmjkT!H*QR?W;3)A$*DpE5_adLxObguUvg7oA(>&2= zW1t}W{&PyyY~hD}a1^+Kado@d2LaiT<upOQ@t>;j*qbqXw*5R}B3vTMNDPr4mMyeQ ziFu{*<mYODMy}E1iFc;+B|m#xLlVt#z8x{XNGeg0@rwspu_S&Q@r~UeT$HURaqmGc zGwK=+iS2j{`M#e~k;C8aYCU+^Y)Hl@ylP|&Obb#^T@Ew+i+!W-kqwb{?CO9^5Hk^{ z<G}28V7q?jT!4q-q#)&F)bDh7MD9RCxE|xkF9pp-%lO;JURKFRgA~W~9AB-9<7tR^ z&z5_=8KB6ceN?I5NHbt|oawVw5eVT%v@4=c<d-{yOHij5+Vc&ax*8odowW;hSF>X% z^wXs1j&WakF(kFS>FJ$OEoq^74V5=Eqo5=mfynPDY;|niWIo04TpxO6k7=u|mV{AV zT>40BSgH~A$NJl<6G(C;RC<M}GVCNGh;fD;5fSI&+Nh3aF1y;#KLNxM2s(XvXzLus zM^jkZNm#2ui~gS0*a%%5+<^2hf0tF+bZ0oYg2XgH36~l1m1i1hW;CXK9wo|-4pqYM zlqsHJovQGOsyn(csF0Ex{(Q^JJyc8U1LA+jqgugWdmr-7jfY~T(#Ia>UW%n4kA}8u zk^3IOpxA~gTHcfuKB99@v!pjiqo@brqp%6@Rq)xLEQI*alqwW5cxoqi>l8_UJWsAv zdcU&ncyVPuW3>NP)KnwbJp}$x*(_K|KbS3qc+;qhZB8CWfH<y(t8;eK6?gh_g>B7v z+mM^Dgt90oJxmgJ{ZfDb;(aoUz9VzGgN5KUC?L-Q<W!FgTbvYdsSFx~tfExmea1%u z7MtVgJMGa%Tkp|`#D2Owi?_0sMV6zj#m2cP#r`tw_76+wDSZ~dR^1FIepP`HrzI6` z#l}%iG;!t+S<j6NGNmd(LQ_Iom6DOOSSKE@(6Z^GC@lzGU7og5)`8V>NIBCxUC$rM z%$uBt-DOUmP8bqY?M5eC&$)-1E6kmsw^R`l!;4QV_bqwUQHC8ES2Hj&trYd4Q{r}2 zpnX3R4uU%2m(2P-^i#y4ba<+-UD|?y$$QuQ`TJN&x?6GGBmHe6g(6K1t}KN9ZtaCA z^1%#+CDg>zxoXf;#&6EBY~2?v(QAPMZ;9x&$cGv7*x%#V#RYerYqJX9)+q0*ac*0W zKgtKb5~BG|+`MHjl_PfQn{w9B_u(IWzP;hhX6Le3nCfSLa`~R-$fMxu8RrB-Ry(*T zcC>X<U9oT_IpuZ55~x(BXL!V*A+yb0_p12;T#&#ooi+p>+fHgJP|DyfOm@}JL%F-b zt>xoyE)gEjIO0=eP`IZdCRZ;#yT6d>jxVdS!6bN-0wP4>_g=h(-tLggVW_z_Z_Gf2 ztZn;JlZhpos&I6uixjXswkfBFXXs0Ed|rXXLTx2F>yet>g2C(LAoHLljrYa!aby%9 zM(X07Tj0_BN|)>r_Dd}OkzrOjZ{yfqOX_fOp2F7?aw$6`HnRmce42xQnyX$spL2PQ zB&vtq=WI_<s7X>W!AVztD8lY+WM}(cAagrPX=7$tSz@NyvQhKUD*(YN_#TRl4)85- zHlz!SFWOutrgbo+dY32CS9I*Yx`EGL&T7I&|7IvMQIUisGO3dRP<oDe;V>}LG0jJ3 zLv+)#xf~$xn%=alrR@!-j%aI$n3Z1<ht;`>_5Gj$T~JDH*7yf9XmAoz6~y&x2wim` zP|>L9hBd)8EuXy+L0n0_K5d9<HiKA!hJ~ZM;1TgPBe+}6dlmaUo0-V1gQttod5rW# ztbekRk<&C|O)b(TmS^w0J&{fIlp^Y3@@P6Z!!9-dM+2eEfX?1t1**PhebHCfasF)O zd(lMhxnknh_bQm4``24dThDCuv#<tdF`Q@*AcAnH9a&V}n;W0;Y-tUp>MW1t=Qe8a zyk)v$Su5E|qSRfssMtA*Qu}=SzBc9aH<}*RTi`nN=4hxBI3kAvWpgcu3K=~d-N<Hp zi3CS-h;W{pJjKQhb$ToI_456*p1xXJJ-@#2{q+r0b;#*4=crBe;B-7QrF7hQg>H1H zt%eV45hM9U{%k|Lb6R%x3RD6~-@Al)s5RlNlbj>7q#e&jZop8MC9GdF_bMw-BTRB; zC$#jbD)EwG=uPZ&R<>#634MeT&&Zqmk`ERtP|4@rNcSiV-6~3^FNnORWp-^2(_LL+ z-855SGm@cZOPjt!U~ZGdI<ib{r$*F#9(@xhD}z{oEucB&ZY`V?)9DEnm)|RA6*a43 ziySW&)2gE$ZQEd3TfTi)PhQsWY#g6F+rz+~;knJ&U4DV0!yWf_eea{Tna^T}e__RN z>m%8AFZxG{xUZ!;Z6pI`_us54d3eQTm9}~*YEZ{GFX?(D$5w!t7NBnU^3m`9!itw= zEbt33iCm_kf*&Z&!t2k9TarxcYP-3WJ{LzayqKo37Am6@8J~Ga{8c{T3NZEd<<g?{ zQT3ZCjWZp_)qAIYGClldX6D8U=V`*rjlar8ScmL<*;pwjQsOIF8{ExKde&ptgi!$- zozC4D+BtF!a|^f)Q8{C%*I4oR#8%_1XBU}0Y4u1FV`d`mNVwrFVyC|v4}EV^?%_H} zyq@|(dZ$lK4Sd&l0-{2HK=v2btKGL}W|7u$bY?F(?7x?=r(am5sp!g2$+8ScDbv|b z;Aj%l7>3blHMr7B4(M(2yUbOktQ0V^jRjfQf&DyAVrg<7z!?^9rS#rMYA(U-BlLK5 z$~F#keVn|sOYh97?ir@4zHy`2v>;05FxDUgiQeR6sL?J!6(vDcBu@8{TCd4?ZBZ}G zoxvhJKJZZ>-t$jI8^rE}ed#kwV|eVfA8YwEp7CiiJ_7)&!VN^09*G0wA3<#akx6$! zzjXg>TVUsQMDa7;IC_nS*Ik63)Ja;nY>h8;Ru}24q)yReMK1v&k`u{$ZhZs6(4e@{ zYGtVK6L?i(l^Ob3x?!CCHEm5(bJF7UbB@%h?H5djzA9?TVSMicIbqG=hUZ<V<w}qe z>Vp+i0pg_R=u!H{5!LZHXTzNF99iJgArbx&wI;=cZT)K*rMHwV$-dt;uj%<FxOeb~ z^tco#9WkfsUJ4fD_-WeP=_lMWiX(FH_O}{>Ctd>V@tXa9K@W#^Lj8<kh&e6=XKE>B zaz#Eq$L{e)>3Ccik3pRD&pG|@ur1>OiajRaA#{Y2AIsanMy<l-qeo%#1PAJZF~8c2 zW{w(Kt1aOBri;f_#SXo-JT|c;lYLh4;s$=>XM<*_1f!cY*Aux1DCo<1L6CR}%HqU$ zK55Tod!A*k(xs?9OLa;_>H4TL8_UoyapT3N(AV0MZbbTkB`s<PM%|+sk;~W^_-;lW zp#kyq-OP+LnD^<J6)%6R10PkKqLcAA@Q1|qo-bM_;hNnfjjP~_)HAxrrWryTBHlCi zVB}C<1w&U8X={`Sfp&PH1}$5-6nl=jra^O^CsDtH_wHtMj#QBU4*mmgFXnmuIL!*f zN&^y)Y}JoW+`J|QAzN=_QVK>VxJ^cKd0iD7f;0zYIX~Iwh-^y|ap%z5{(pSEcQjmk z-1bdGwCKHy-bJq=Bzh3No9Jbf=!1z#^xjMK2%;0c6Fmr`M>krc&k&3lbKZUK^*+xz z=l<jQ!&)<zWp<g_^V`?=x<1!sXcv>Q=0JjrZ858>K|W%(OgEz3Ai~w4p8s=cX+<Xy zr9}0V*epsG$zhJtLj>v}S)yw!b%2iM30IQNkH+(LUTCw*`_tuL$-d6YuTL`CSTzWb z1jNxulY0A>2Tc!&gjvuIDv_EWY;Yo(+-H9MQH$R4A}b}bzl-&Dxi%o+fjpyg-;OiQ z)ufO*KXG?(A{Ep)KSbjpA0wj&`|w-}aZzR~GzIYWXZlSG-BPWTf>JAqdHkwW=k2R> z+`a)*8{nYNCx)C87ha^x(SwCzsB-^WsQ$t+5QsXYB~u9YpN>BHMrNkQW#(Z(@cbKg zuJbE+W}Yop!sPzVvJwx;7Q)|_;6i3tzRrAvaB)B3hO;Bc(zVW2_Po7pa$Imu22mXw z+LYIlsb9#$m{d*ZU9J!+Iakj^OTcCDx<u9%Y@7)(t<E+X*!~57Bxu!Bx;Ksz7~LT0 zxQp;762S$)O)r~(nOCq9?yB3Et(epJ^JtyE&JOL^lAOAd&uQ0&uXee*A6LCyTs-2? z#v3i7MhBy2%Arz-z3vszyU;f(bJoqkk{Z33w$i0#pNRhI5fMmcRl%PuVPhHn_{Fc^ zmz&GlR|Y6kq=g9cDwG#d9@D%@Y3`P7;Z6Y#kc%p~$}<=AC~IwMmVXr&Bz%egD6+hr zH%<L@rTe?%)47tRmfJoe)L&Sd-+w3a|1<+^1{~RyLDgTI?!tBAUv|W<_-is~I;NQ) zZ_o+a7kHBvMrrIM$edQjjw7kT+pfM^1<!9BmEy#kd;+6~O5}x|={jt5l!f)Tn~vMa zM~p?y6db*3Ob2!v>RS196Fy5I$;y=B_Lmmv8P$enP+@Xc7hffN0DFI7@a3)=BjLJ1 zF+VpHTt09OCgzs!idQ1DLO~h<aDT_SZF83cu2hYdm1U#GN4mJjKfc1`0RD`PQX@(k zG5SS`07?$+1jYM<sHBs+&4rUIY@WCNN$g|{5$G~zw2Ky-s5r6hm>W;FTMYwnHn-we znMDRsN6Luu2#F$c@L2g#C9Li+7pmmyVfymoRZK?~{&M=HEulJ<w;b@ne3i=ff@jz3 z#2abwbBFbWbQ?z3+P)H*dr0h9YV~s$EDu{7(0}%o+?-5Nx=&a$h(LI=2$h^OJBVmu zQe@FlEAIezX{s2cXVyEM37G%(cANTnn$IPuDDti`PQqKbl_iSBuZ%Fwu)zIAgQT13 zux|d7abb##U$Z45u5|FK*-XO5Wby2RqwMTZp2d0v&28-*Nn&+CW!cAIZW5Z-ra5SX z90Dign<$23Iny*HCs3{Cf?jrU!{7LA$INuU>*^_(>b5S45VUJBjg&ux>*DQLwIu?U z6AsclVCl1*7>d*In=Hb0SdD+oCGD5v|5J^i@?#-$>I1)nLJ`FQvAyojPsC?i`~J~b z%nJWcknQ_@rGNB?nlq|V=B)SJjfu7}Sv6D!-v}u^b-lTwIG`v3PMo?UbRw27Y{eoO zP$H%QmaHCX=D*6sGgY8PI`s7L$TVtWe_xZsE|4?Hj5Xu(K_~1ViOH1jKLtwv-hhhw z<KyjyLbF<S6Emx7!B=EYW!M%v!wrDf_ZYnk>BEG%;3WJ@XG;E;Zs7(5l)V1+9NcV4 zbninRT`+7KScwqA!T-~~giZS|Er|C&LW~Yj%hXwWa?DUL^mu(dCjGIICO)C~cajCr ze+9cxKvn!FbEos)BjC@%5=PX+!WiF9Va^!vGZjblCgu>FS~obbd5#^90i@ev2CSC5 zB3q!><}qxu4A?TIf6j{`kkMO;cgz~W$kaHv7=0o5`;D<Ph3oilmCGVj8aN*R6h7ts zck@;e;f#O__D%QAt(5ykuSdsvzH_<O&+30wL9P5}zyB*hJ%mwzG&_iw%m5SRd=a5I z;e3TmwL1HcxHW@X!YC8`g#{u4!h0<~^Z!fx3K?uOl@1<~x(*~2^yu>Qk#&?Y2*TTF z{BJ1G`2TSXs4f|`HT-U4i<@Ja*#b<>zVNH$lZ7zs!kSxH0ok+&gDFDRO&9}5;olL$ z?q<L&rqTC5hOD#>g6?NE{o;ev2ZRa6YBOJ0BgHWk9=;gZDh35Yd>|Pwf_o)zD4^{9 z{Y!t%_CG0p-`MXL8AiGGD!~+(s}V>6J~E{fKne#W(W`>egU-wZ)9b}}&e=}~Ole{; zoTtpxeJ3EK#O9b(MXPC6W6_4$q^Fd}Z|1+S3jA0|5#{}?$$#EO>wNC~F6qePe)XAb zMx*468u-*$9#{bl<-x3XIO&)_UdVclyTaf2P`-N29m{yLn&#biAF~bv`RNMZ`2<N| zAG6S*jJJ~Uf2Fy|DJE1uoCykiIFywVl6wJ*QF<84gnrUvZE4!km$d<(Uak@P?$503 zyV7H6i3~{oi1OSS+TY_2Bl6`v&u8BG%xdv7`zjQ9Hlp-!1^pB?jil8>IK@7?a2Fin zpN+8X5Aea_47lUPnXKy-cQx6d??BW?b(7<k^$a-@b$8_*LUxyu0DGPy;4rUqzFC@8 z6ugT(lN2GgLZxpdk4z|$-{lZJsa9oZdgY9rky=zIFaRY2pq4<KYC2Lknd|D4@C))U zv=7VMcbITC-pa%Y98L0I2!_j6T#;7jr$|g*=`??s(05w?Hw1!8TKl2Gp#yT)gNejw z)8d}Gj!$Y`Wx3x!LzZrbedi8xu@GK3Ksa=G^fn$n>F2);c-3<JS(7X>ukzq}<g34C z&4=nG(w|T7-+PS*H7zXy;G9WRCtgW%8XOf;KY_~WFGm0n_Z(O0asgHw(AV7erJf2i zWoqHr@-z9w-|K{TJ+qb_XJW;BN>%?Z7efpwze+`xZcth)b2PWMh+A7tvX0UJD%tzV zlZ$meF0hJG4E?5qU>%bBqgeHM<5?hH4(^)rf@On^p1u|BzfSiDLPbVIE7Z2^AQ@UE ze3G^k#4P>Dqh$W7Zb5;*VuOBFC-K{BSWQR@2O$>ylpeF{vuc#j*FzIp8mZScDK4MC za;AF|R^{+uT@34|4;M-;*0A1ETD09#Ay`H0*va3ArL>Rnd=Hes4!!R0ynM$V;vlcf z=uq66pF|?(PjzDWrE}gStyHwSy-{pD@2x;4XF}jGK(Xo-dPbG)%hen+n`WD-K0Tf| zi1+Dfg+C}3L@trnUOZnXSZ3M%v6~-%bj@+=PF(_faucn%=w9zBs1MIreN6E!T_mf6 zelK>rdL6|vBqi0jzHaeRkgE-c|5Ro~gMQaX_PTEE5GijJwDP37c9D4eF;wH}h~6Z+ z>d7;GhE!i~`v;tADpZfLE$MNJY@f1tSfBKvLq;)M7yu+n-b0FcH})6S8)?*%yhu#T z`%;&k-bcnU`VA1)OsoKEXVn@1WC}115I8$c_k~q})<!+-?HzHnCBIGe8_3KkI|tZd zy(Hj#D{#d6BO8NXd8-M9H8-OoZ=Zv&i%1m2mR{7BY`D62UT&)kx@}pG$F;^B{k)%L zJ;fmD^=QZ6_fPn(7-qPrspvTMBX<G93x3(t`(g1TaQUMEZSNTNGTM>uTRk4HZsvOw z^*ALOH%oF7(*Es&AgbH;Onbts51qXKH~%8tim2b9GJIll$y>kE`_qZ8kY9nNWVs7p z*RLDBsp;ip4Dl5zd8gn7YVfKHxrAoV^-Gfl5uw~5p8m3UXX)43G9e*Qu|f7@TE>}W z%Q4&0O&dIvEkgZ@8_`=1d@PsKuUu|%dyBj!6uEn&X2CA#AMEWNG}m&qv!C1BA5Js9 z9upU9t|mNjj+4IJq^W=r+l+GOcm+|eHm+M*d-8Ge#46)|oj#`-z)SWXxJmsPjB<)C zN5xwpZ5m3BY{Zv1nl|r>y*|3ejR_h|aKY_AjeUx#``GxrJL`w*urQHqka2&}c>QO@ zQPksnutA-GWS(DT7r%GFe()2(_+W8dhSz1-Y@t+$vX4XBNGuKSwC_+Gd}4^(FAEz~ zG}Cn}qbrls@~$*sS}3WhHZ0<==3R>WG^1Gd3GI(mA0{Uqc5S(j=(Y$~FMSfZCa06R z@TX>prZxTfMWU88hfdB9{L)l<t7`R!@p2vzoPmwU2&JLh6WBIQhrc6yxo!sxR=wcH z8)C?utRWk9?{hHq%bV1fi0H)O>QraPchs2MPJXK(jR+k4lN~SQuSc#Evh{VUr+lIo zHFCJFy7I$~rtAen`kJyhRbRqDuU;-^;#=n=CuO|>3)bT@r2TeM(X9q%g`uneBe>H} z8v!s6fjf)BjYTiI)w1KOKw^K|{0p-ml(<7+!j+LFHB;}$>_)6}9Uzk37N7Coyzsf= z<2@aIzqE{U&eDU5s#s}#U+WDMEnim^iZo2&Si53tVCF*qE{b;)`&bkLeSv^jv{*A7 zmhxEQ>1Hy_MhTZ`=%$tPzaB9tlQFKST>4l&p53AIaPi_v&yWsNYJ;h|6*Wf~{u5$5 z*g!+_$R^EiF9yiZ(JajmD41S>ki^knSVY=YYpYrZ(vuz>oBhn)+-kAAk;c#8XJoBE zdQ?b;obMxpYVI&D_chk!jt<QZdcdpc`#WZ9UJ^k#JJjyIx)!rsvx?=}<P7te6s$3? z_San`ZDy{)zaNMviB80K+Mx8_DT(RayLJRCx*5}!<!QeWnq+hXT!&Ap6wdmS$*SO| z9UnTJX(yzQtJK7HE9oXOjpMxcKdqM-NI}1&x}Oaz;bY{X&rxUK?GyQ(guiRY=|8L< zrGPvAE8^CLOFM+K<^-oU+#hJ;`Zy$v(5#Eo%6K}DEEctLcX%q21FgToN-+wecbNpp z=vZLDuyJFN16i3x?smb1c-oyv17h78wMNL^rw9o4L;@HODJVNKI}WJ6?dxCMkU<m{ zS6gZZOZ=c2!EB2%e-ehq>}5K(wi@M9x8<rFZ*}~r=ZyYk&9NOA)B6~ruH5lm0k;k! z|NNF9YaOi)c5nL=|J68gSDR8J-V?Qw_{hm2hO7$T{;nlv@-cGI_Gh@?PdvJD@nnAe z8J*icsx!VPOvV}cnR!6t!ZTD?tS_{LeZa|Qa4#o|@>+z{hGoQzD={zPCt=#4ubnq! zZ0Tx&OYVKJFhvAVynHlYss0XGSmKLhg+~DT#N>E+g8wR2TZo6T{kxjMPe&if*B4AD z%pa}eXlHSdY|%dl5n`B8XYlecq2GE;M^{Vl=naN~N+-zr*YUsJl)MmLT+i2_b&J%u zB0Zs18no1G(XPJ_0SyQDB`EMaWHE>6HFVREZP4#X<@&V=F;z+qrGr$enFueu=mXw8 zle_ArMyQW$;`GD+!eYd%DdHj8VkFLpB}_Y|;}s;g8ME7FPaSOOau28W9wo$VbL%yC zr0zK0NQ+nKC2g;j3vAoa6k5mEQtOOO<Yf{19dezvU+AJ+8^O7XyJaOuNCgkAK3a%* z<d!GvQ0KBywcR27m&w3Pd14`#E~}}Ts=|xXUuv0<D$%k_bp^pn-mNk|S>q$SEDZ<q z;?&fcaE{7;139t~6Q^2VWb`)P2`L;z2qC@28B9GYWa*iCg$l3kXvch=7p`|_b!~N0 z^*~r^@7}Z03Gjf!_;e3~>#-oL+eIU!Sdi=;&sfAXh=qPmQdFoY=1ij46<lYw#@7*d zp{tg;*Vz(Bz-BIjMK(TVLxHR*G?lFX#ULH$2TmqMh3h39P8~i;@8^X_+pLA*-zNut z$ev1~%d(t0`l6tkhIsthrE5lOLc%U*lZ?&v<15}CJb?tO<>w^YQIk+Yq#m()LgTeT zBK@RMnZzE!T)wkPnZ;}0a>82Wu>nceraUcbQ-L(aNJRD^EE3eXc>?wjfJALi5BA<i zIpo$ZY?S#6&e_-;b{3XqXA|8QXayfl^fi(S^M=a{z8rXq|FNDI73&&;Jlh6^_ew%l zQA%Yf`@!rD-uUN;(ZRd|8vLKu+(>KgB4b{$C10vA{d=D+LF_VP0j}3T&EY`senIKx zFB(OK&ZNWT4-9G_bZ=^Z|JsA`yzozH=xBZSm~zr-#gWlOoXW$-_SSC#IXa}|{9OSX zX*ks9g@`<f>Y%Cq;2N-D9rcO(T&UO~`MR+wzU+cLM)g97WKkR!c96tc7P0-%Sndat zL2f>WuB7!sw&}!`Bj4nO+fT;!vTrNdf3U+R+XWI(C8Y1*&_Ut^vxAqeMv*RyiE<gA zQA&<#!U>;IUf?)g|9Nl4Md(yM+o4f`9A@nHY3NW9cCY9!fD)Db7KR6vE(iBH6-_NY zYSQ@7+D_IvOqIqj{<g8%M>ZMvg<Ev!erz*rE3dDy{+$9Yyq*erA2AxYs^5g5K0kPU zm~E2U(VhWvQ~P!NFaX<oAJ_VuzL5a!D~k#=BU0&P;g$uW_H$s9EEMZtlPvseqjvql z3Sw?Au_<}8Yw*g+pq7Gtb(GGKDUthz%bAb#Wbgy3e3a$!ypm%*8F%tF;4Jwyv$DJj z>6qEJRvANg)Ulr@Aivr-LpCH5zqwnNI;04`PdH7cwc~}KqZQdDUys-B80$*XDsk4! z%6AMf<uC5Xby_MGRido>gRVj{x6c)5<f0tM=;n=0*b{?|z~e2vy2hUyf7V8SsvKyM zGZv+?l^drl5=<|DsIb|59oN!F05$1G5dl*dNwj(0K|t8fh=I1tV(TCO?im6Ks?<Hg zISHM8PgZ_jIEVtj77)+hOFY53dY!#JorL!F@=|OI;%+FLcJ?N;?CCj%*LbAy*|!<D zXF5iSMP6`ys~J%jWBMa9m?*F%@}>T5?)nAl&p6}igg{Qqo!3xq?x=rYh}_<Ws}tJ< z$JcS9-7|OWFUHoJZ)Z`kkw5-zBTp=iW?%h1YanD4!Ph2fa29?)YpL3LYs@WJqo^%l z!Ts}rsFzPb)i}X<du}T!b4pEb9rILNzCGW#kZw(eWx%>}>n3|rL(-|9A-v&+6$`mZ zpxgNM^Y70_0tym0d@7kQ^u)>ybiGS>=c4%iDKco7`DTixs-~$9MyhYxtWhDrNxJup z70vlaA`7{;v8fJzjqkGWBD@#&vPO)+oGeUkt8#>1v$%ZS+GS<EEl$GRzIDN!26Vix zeVj5ORH6|{ze7<{A@gKD>4EZa01TnmLu7piIHR1rBKxo|iKPv`qiGQz=k(^G<`tML zdbDztCe!TTr>92|mOw|QX@}s8(lH8tHT?HYS0yOhGR&ln;v7`E7Lvx*fTVASJzN9n zFg%$Z<ZAX&d;OZ(p}Q>sr}-<0w|xp&!NrIBDw2$<d?IO+SnNGbi_6TA>-BP_DVw0> zE)mc^VVwYJfJ)k!A=cZ9^78PwrkZ(xr$uOb^}|J1*XCTOGo^s<R+HDa(~r@3R=;AJ z9~nKQx5BS2f1-Ew7S&P$IU1l@c{B7KrF%3;K6EXeQl-PxNavp5%{}uPM^p4AvUs(7 zgmJcLTm9tXRuD6_l6gHe9Z9pu!h|?!UIM(oJH)KIt)Ig~f1P-sKR6N+n9XR9aWr`_ zw(*nb9xg8aS=1I-b=i+{8P|DO@&6+@$on6(De^*9kwwF(ZVqQ8hlN~H>J~UY(PC3G zStm^MGEtMw<#@xjoQIgOd&6dq#Sv1PrnjC3Q{VEUc?=o<K5_9!BFN3?XQrm=2;uiQ zEzyV)27`2i?lhw_i8Xt=u3Iaf-_={8{A0G6-kT)0JTXlMwW`KnR2s`k*A4W)m<$*U z8rADh$;6!sC)`wO)ffvZuzyx^JPT)$oq;~`s6f9&6n7yVH(DfjO{Lq&-DpSl59yvC z^O&Y4G=8;`A?}E!|H@w8he9GLw>KmG+A+)r!MfSy#9|vyz@vd=J*`DP?B*FZmX>Sd z)~}45Am~N?{RxHHRm&&yaA>s3-N#TFXvks-B7+6LXQnxs3YE)DVg0Dgp18HhmacuN za37NDtXaU_)M%7yvZ8UxXX_wFE)kl%l^ntFb1=LF&4=U}ejmz)vY+go_xznq>q?fW z>TVxD5jDe{>kZ}T>S)TF=EG58+Y;+kW&KTUso?0klW%Q75traG9WrMKtrOO_s&bXo zAC~p?oOS-i<d_O`@K$P^u6k9Hzc1mk-7sIZSSVJYz(RRs>}@d6tEyI7)KtjcN>Nh{ zFS8__oU}k!D}CvGh{PK#uvbSF5FYtR$6xxlEdB1WG!E%FvFr3t)-?^f&o+j4S{%Ta zKPkL`gB7Sqg-lA`sqp-X$khzUtqG(FUM%CPe#TrIBd(J5Is4_@n1Z{L6aPoLx*TOO zD#+Z9`cO|OUL!(eP>J}*LFe9SK_ytTYE3O$8-AxaKqYND%=y|&_-QK5#+paW7=Lr! zJ*FVNcYO}5c&p$)tRtYf71gEKUS79WIR)B4i>aKFLmVBc+-I&6_h}lJC!FlVq}upT z9!@zmG}|3pfaIsXi7xmmIPx3wwO6Wnv^doiwSQWj71~f3>o_02ZH#ljXpbu*@OCEN zg7iI^LLAAD&JKMa)F##S&)}UKdSg$(t6!i+neaL_VcuINcBX*P=yU#Wt_e3Z?1Tt8 z4x<m9TWRSVl<I72LBPUlfA`U%Ms&pXIm&Km8Oj#sRN4H+M+}Zt_kuhf3aPUcg%<sP zDmiQtx%Cn@AoYf(>5g(Er#h;Rv|s&6{FNYZNJJ59Of+6r8s}Q4?`R@=)<$9>q2~6h zm+6R=6di=59SWsGa95VE9dvFEtp^&@2Cx|AS_TD2ehUDy<C>hWR|h>@y?kuMDO7N~ zJIKGS8iEj?^2#B%28iQOZrU`L2e&U5y`b_zyJN0|69N;hW`q1zS;{Wfh4j!ab3(Bv zT^^T(wu$9wcPe$vv;G;3x=RsM9qX%0dAaAAMMA$#8r5f=g0ke_HVRHeA!Qw%!-|<$ zNHTRz8O%C=XwN2^#$I`67F&{9lI!L>l}s?`cUG)shhb)5WPU-ttVg+>zuK-Cdds{% zDYFaCfGk!7Q`JKp8Kx;K)WEK#d6O&fx<?%v69Xw@paNht=z;hNANkN3)#MBFCZ3=K z+unQkWklI`wW#)u^zAFmoIX?y$z6|RKk@t7)SyPDm_aK&UNb>7eptnwYA5=ozB%-i zu75319&)_dl$-=$N`j|H|H5MK<vzd=&vD`&yVFp+l3U%AZb}hTlerVPnNITk`jdXJ zTorSe-NhP`BbAm=nyYDHRjD?<27FDOVEPAT2-{!O0YCv>gL)GxYqPnwCc{WVqmEZ4 zbp0yi<#ehl{8Dkjt;_qtMI+V{D1)B^EX)X<p3Ig3j}6DQja}r}^(5r%-(!h4tUI6| z&PE-Gmg#s!e6(XTQX-%sI|L*w8SrI{&?rT(VHg4%tiK1`TT)(@BKBGnxiFuux#_mC z!amr`j$q;Nq=RVQkPqsEK(2iVT_K9`5m_kkM$wrQc6h1UdGA)Qm@5iKxZ5ilI>^F? zvM!O1Ywicvx@w3EP3Cya)K?1!ha`N*i$c+!t=&=nS$byO_eEsc%LsL#Sd15e*7Nw7 zhx<%6mm4M_<$aX!3giE)978a;^ZIqDtg8}=1UB$ifus@Y48(i^f4KG14a0Gtt5;Yd z?_K_7qO@iga<8?<pV2ADp*aTYy<NL3)%0@uR$v^=6-K=Q@jK)r&P*&X@b*=3_$d2| zJk-V~)a&baymWn=1?0{ZSm|E3DQ&bQ<YQOd_75G8AhOquBoRKrVfb~d{}#2r;{qa& z9*b<l%x<s#PjjxRyKeLq#`C*;p|^D$MBJdue1C4oi+?>PO*>z`nK(SZP}ZL{QMC>g zIw{%ib?jlM-txWH$(3_Wg?*J9f|s6z*UO&(lxk14m23DF_^ck&lHsMEa*)3t=yst^ z3mO;ko&Sz|wE5uZio_tq_^U^4<I`2k*H%n^vK$wsOHksP!E$Rs-bT9L7lIS*_i~cG zcY4K*J^VrODJ9mE)YZ|Q!mkRRj)_%l_A}w>-{jU;qBT(OY(uD{s(l?Lg2SjTY+ouT z_W2zW=EDeBMkTPP+>}WD3luTuUo;;U*|m%6yl&!+v0nhh!cB<4keo+pTU%>9!@v}? zg?`uGtD2{WPdOjnE_wbL5|{kmK2z(Uy$qeGc(2F_1NEdH4Xaij;+Tj_?q%>ynVNp# zh<d$C^2X>TUf$B*j70wIe`&3C-rbtDm29AVoYAj+@Tbg))FVK@r%oMg`WCiHgrS1{ z>oNA<Uh)4s)$w1nkjj4JOntJR+ub-)&yl4hPM!vl<oVY>|3D(uMM?x%&`D9Wm<ZQR zMB*>lZxX%RgT9dl{{r1x^?8u)oU`aNI_uQ8Bx2Z4-i&=9`53nYgL5w_{k-cti~M`? z^Y15EZ9A|Vf?>epz5{sN-A3xNmD|EWP2fqpM+&igssTGhZ@ow4(@kM;#_s?_f~n|w z4wi`J-SQnmi?Qk3V!f4gg$+m-18#R&rL#}K@_!0RqM-1(fDT__d&6lX(4OuHAU81n zHU*|b{~m7uUi5!IefeNB5w=TKbcyKuLu4vsnM=I(=W@sV@H_}9s5<a?gpN#nM4r;( z-~0PkX5~Ag9v%JRj}qqX!pwiSqQ2U7QBJKuxa89+et9w@=ly)gw@=>0ejs)e04^gD zc~-zY2e82R(xQ3)*HfIT1=udFKX5>1VZXTBgXbESBrR8exS!Td3`<m{J<`A6li?^Y z0}RLi*=?*{&%dyCPC)=PV5+22_@Bog?se(lV4f~+UVb&D{inT?7iT#X8xr_Mt}fc& zzixF^FQCyjZ8tgf$y24N4v}~pArIdng98h{ubqzRK>;aGMd@&Q@eHj#c6|yErDxij zefi))PyJzTKxbU`+<OkuF3VWmk^U+C1CS%+Xt0m;FDy^Jh+N#Z2u0pi*Wjoe!W@Z% z(k;dBW!B<_qW%5#3H~8;l1jAw<yISI&A#2<JwrtSk9DP4ZEaSO(pUFTd2nI@9i-j> zv6>!*<+NL)9#^<Ws#U@smaOA7)A#!rw!0XZ>t=+7&{gdgDOLQ0D;xXi6PnA^-Q>y} z$U4dt2#VZaMy%K6ltcQqrRtq*u5}+sP$cKzt4uBx%MAM|eQtZ(=UR^ozV0j<cD)o3 zA*n59by}<=05UY)#ZyMun`O$kVo)0d6^s=P+iK~F0#ITWHASy79+P+NxV{Ybo#MqA z=;Z>w%G8IvXl)?zLku;u-AxTi;*VA-en#s5z_yvW#Yewb67Dt*M3h@~rCn(EHU`Gg z|M(mm{ZjlpS+J=*((+0S)dJt7wkpDh1nXGp6gq{N*J=n>={~icx9j1#az!x)-99lp zRH9cDo+OS)Sr%JeY5tI5I5vH&{uUQY=awI0vDv@Lf)0Vlvt9<&HnPdz8+!L=DGD-p zrFmB`DMEc{5moT<@WDpNfz3V1SJ*1MNz%yS5Rqfhc1JfD88Xr<oMKy_J*EGPh$-}a zJvOrZr1)0rAXH>QVpSxzjo=|e#LQ6Gib&?O6ukA{A4o`nd$&QoxW0#y@oy-%%UXs^ z4F>lu%Z8Wo&Yde{W$LSd%*Z4=>2my)MlUM6^7-c@i$7ki>(?0Dm?Z?$(mSXO;4W_^ z9Tg%~L!Nd>eX@Jy>B+za;$J4&zx_ZG94dL4JaQHfYmBh?#)_}VMPJ7`!@*)**6rgS zzlU?b{QeFVcJ$8UqUP)4BGPzDilbmU5m6jLYxOB5@@Y7TJ4Lylj-&QXIYN57@3_If zTIp>lUF-?S+@s!0!RN+DYR&%V7KKcG4q&tZY?Y?0gcyNCIlK(jnpwtpno(j(A0^=o z?D)!Ok|Xuy%DAH$mg@0B%`EpFQp29^KJ-7cS}405cvD<kD`>I^`mJp#OSTj6jIzZn z{c_R^FwFh|(lB~0bNMxmu8)PcItDTZnP6SH`_72Eh7WF&UY`#6v#yr#7eQ{x``MFp z^f>d*64*XFy2zT<lNRlx`=V?7tCQlL`JdOQpURBRdmCkc+2C6!#1>j_>h}`<#q|O{ zQLyWbb_2hwaO-r>wjT<Z;OhO5`s|^}o+0D~mdrFW|2H|280uq*rZ*lwp6t$P1h4F` zUMIHsWRB=6He+{54|-83Gx=yTz0x|azDRl;T;zF4i+&Wyi#ybr*q1U@l~zsJot}Vg zSqC-8ovh2OMkUc@nWwT1S;m_6zl1Q$lLarWC?T}}!b0&#17;Oh7||x$=kBB5>O?(p ze^nlc@K>v;p}BGeU6xUMu0chkgf@p7hl>+vqhGB3Q9z-)34azze6^wd4(cdLOoUX% z=aYY)<}I&8TAZ$LMqz50Ctq9jLTQ>ubLz#}@x<Ss;Jad&D=YPK9xLuqaA5demsx%H zD+v^Xyq{B=sG$DZnq_>8CI`DdQP&9ejd?5ZJy#BE8a>9oWepuLnSq4E%Lg+Spe7^U z;O!zR(5hyoHvcNfDoEc-*DefDiG<VL**PR$OTix{zJG(mWPukBmHBL8CX|(3W{w-T zq%-G`V!1k$&uMb?YiiZ_b;D4?D7LZYmwJ2{9c+LHIXIXL8-`(lAWbjl?7%Q;h|ln; zYSXu+YufJvD;f2^OsN)$D(Bqq>^0zy=S$y+*z#t#l9-2)7`b}M1qQ8C(XRd8wMog- z+TAm1&j!;pj0s#Ykm-)^0_xzlP#He<*-f~XpS)7hMaxZSn@jiHI}SPvt;*GQb2X|5 z!0~r=3LJqoq=XPwov1T&X%B`UV7X=!ZkLEaF@lok7v+wQt(@Y|V+!r)H*n>vtL7BB z%^>O9atFX}dU1Yki}<k)$y)R<0ju{uE<JI7*!tZfGp2UnO_{P-=q~|kM^}Y5Jw$8C zC$v=q0$3zOziKqg((WULXxnteUuO%ss63=<(_Su#!*|M3W{?~h?0t?M3(`X>B`S)6 zK@`n8Krtp^b2a%D)D7&me@M*TPk{SPY~0x5={_%q=F6~JcJ&y#q91$kKw`m9J%S{Z zS+y1hO_{19&YT6MWg>voYPh~3)S70Ec7}tnUPlw!op-0>;KtQQBnD4V$_T0wDx4VB z64=>3*x_<IfU}odlpfd`yBg~zbP-isS{|7T)_auX(wFc_h<$MM=fKraAXC53fVh3b z1Xko&@&^(9S|LPb!5G%m6$^skF~>E{tKcA3k0BM2OMW{Dk6m0tDAE|)mZ7cFG#hGw z@&jf>T!235{{dA<)X`iktet2%5R7QGWLA-&(cY{1M3Y5(E_C|b*2iWaqUj~XK(8c^ zAd<LZ(lg|*EN|5uxn6v|uSL_@m@U8mro^)ilz2ziUiV3V=zT9ky+yNPd&%)HmHfjR zUG|K=z=&!svA9IJ*}!TOM8=y8TmI$)-I@e1Y=9}U2S1|&dTT+z{J|vGL6qoz@4_Wb zd)tN3j6z1HEhJ~?jGuEV%}PNimXouCB?tfpGdLg5!29r^%BUGcwiTc^O)@?WVOAQH zqfHNFNqn+c8RYHMh&7-pxRh$anL5nr-K}cBW+Als+T~Bh;w8S{aBCbr#R$#3#25P_ z{kEPQa?H08J_cSDRsMT3IT4?B!m7e2^<w&(oWi#^8Bw4S)S`z!jCkcxRH9Sy<02xm zJ=R`8@Gq=kPD`S&nhMUX>bE9+<)7Eo?}}oLeli+(H-9Y1|5zd*><COLpV*@}E<#ur zZuBU(ATUZp;c2l-`0AkTUR)AGNv&zovQZQ(VdeLMD&sfxiw(Nnl>_+;f-gF3xarKN z$@e$dQ2N!VMi42~26_7frM^v4a4jTJpet=Wm#^kD<0Wh(rQICxaFTsEK8T)yY??Gr zXp+*bWyx=E-h(<LC{2~qQ(1J3vDxPlzgAjZO^1Qe4qJ+{m_<yVvk2p_UOc2}?3ou- zwrU{j%Cs%m^2JqS&C5YAFR2f;ttMXV+oplyI)d4P-#m6=P1Js<az(v`TGt)fP&dxC z)IQh#@T}x8*_(N$(<#5vO1oKiR+FQX(*;X6GFtDef<4^Tc}=FtLjP``*+$5vOtr&T zMY;=`ypg!tY;?L-T94wH6^{~?Nyyo!OW+a|^LL#VDOaQVHDJcye8%sGm_P7U)6Z^9 z*R55hAEcK{9n>n56F+JuWku_P9x5ZU;k#K^`iFno<rYgk+`_KFOq`7tH^bpE)+akE zaRHfycJK`3$OdM-kEmM}X=#MST|hI`4)<m{dU%%=giJlHWP3a+*_N{}+3X6wH;`7* zCcvl`cjQ^kl9@TNY(46i^Uae4$DX4d9c*fT%MWEky}Q+f#BVFbkhIuuDG>wV`PRmT zZueG`QG<@K4LV_lk;ms+@vO_`7sI=&&p}?IwUvHp`WK<p-VrW{Nel5JK}6?mt6@I( ztj>C+)~p-hlK$QLaf^apNj)v9IN>TM5Z}I#l0KqD#97)ngqq>f)u58U-BqR3ZA9Xy zG&kIwZ<O@-*GP4x+=gB`Y7j$PKWvS+l^xN|<4PLUO|-MFNHjcmDtvrWU*|Ck=a@6T zug}gH(%k&!-EK@|>=>4N{foQCK8L@sVwEU+Y0M8;sd_oA2Df3%ATyNnmp;;F{Cek^ z;ss%ayjV|>!c~Vh_6>RMqi}EDbGA6r$I2X)nq7ZkF`+r`-s>I1i&xNE4PA&*a0nBI zxD7Em?@@X1SfkR*%foFvVYX!D8HMJ)K#qnp^eZ+f!>?B0su5M@yhR#!0Rip-kWnRD zj2*wNpA9Nf&DC_v29;Tiqk7YIdpnCx$Qsf{813U@3g8zX)mp;>aDM08NYSkcA|I!h z6S`?>&Sg67&h0g7xw-kY$?YX>e@bt(+FYjhB7p=Ac6(*pA>NP6I$HIufbz%*MGGKP z{>ECy0=lAC@5hEKjQn|L^~((snE9!Ks&0P{lZN#Y-lc|eT0v#+B6~SOKW?&2vRKI! znS0Q42a8$0t9lQmDYZF0KkbgpILUGbtw>Y8U*Drlf|(;s`ru%f-T70FuGp}5Zyu^} z1;{6D3U-O5;3=d)etzBxl?a{x3yTEks!WcWgK`7IvNyiUoilmIER3xS5_sV+I^J{E zI8$mNTZRba$_w}@1*5DF_C1~JZSLYR_o1)uYD4i*&O_25n%Y_g5$Cd%6>Xo!yy~Od z_v|liPTt2lq>M57Qcr$%EUNwHPTyT9v&CRuMD)g2vZ`2SMdC;&<lIeK^L)K|Au}&C zv!&ZJ^x5|2ec;_&|3IBKXYZn1D~Vg;@%uRR!l71r$%zQzJhO(TaRPf<tqH_}pFaaU z5|G~^|HROI)<W~QkR6yPI&#Odf|@@4^@z&Xngr#3?2LqWDd2<T<>dY%l1tWQm_EWZ zj7x5$>dF8H=B{P}xrN-7m87Y$;W=f{M+~87o0HF5_dslSB^dlM1kW}(Vu+!B)m`{x zcriyF$s5rmJcfnkWl-wydXPAB%otwd^f_!-yV4~qH$t9Mt+glFhZ))Ju=7NvD}*WK z86Q6^za1QNK|((QbGGN#q6?H62WRI_3XHf~OSR}MFOM4KX<&2_P4R~i)on=y9<mF= zVzrjTb7kWKxfC6>QuZnX!@VxhkV&~*63g$JyPiJxTG+NpHe4hO)Nqp77T?PO{^RZg zT6c5b9~}%x{hSoCu9|VGwnoA(lP+AA9ij>hR3c#xBE+bptCKbaYn-I-wl|_t)^wyT z_@vaNx}I52BdE?HiP4emv}4|56`XlP<8dNjyZfyfV77pP9vg=G6a8ChsNKvlTj5HG z7lm8)pRx#xT(cEb)~rAIZIxF%GzT6TT^*M33vHe9r7NReq_-@gvmn}DAxQj4QFBrg zz?gyjnKtQY3Ll<@F!ozSh#y(_-J5uEYuxNg`F85+h{LkjBolXn@2#?eK1|1`zq8%V ztUIjcNw`mZ2G_LyVx`tcErUHR(Ous}y5atD?VL@Mz8~FQ4-rWs?A4$!H`|}u<PR1g z3*{!IcRg;e>j`w-^6fRZs<!!NN=S^&%VayI6z1>ruD;!+Vn~<KB*^GtrRBe{;G>af zrE-+7p0q%%R5(?wuY%a{`{RKKM=JvCc30+Sh=$JHWRbg8*ej7`JitIOq(tbdgasv5 z*re{Ztk!)H`DPp3qbw;9bS-hc^znFFamzl{9>Ud@KPJ%a#WDEq5Y$$WrrNyH1hVJO z$t(c7jcs0X`XOrX_vY~g=$>0BU4e+*8k<9a8TEFQh_JE$#-TYaZw=vT%PnQ-Okcxh zggcZJ`4`r<UOZZvyRnF<`2=r3WfbleW5d}z_d%nDkH)XjuahsxpVL4=XZOQ7bvA?~ z7-8P(`}XVn1u2+^$3%eSCU2;J_7nVs=8}(lPin=xDLp)13~s}U6p4OqFxj{QFs%|@ zZy9tJ(<&``Br>(?<fbC&=8Ubm#&m1Tv@(8;mmYHd&9=Dz1yMc(!nIgN?d&ASU(!MO zf?&nZ-~~1}rERnOZSCjQ-z~a%fl*{>8eQ1PGzVEXaUUOA|1RDSMvV?#=vFQ{Ox;8a zwj-U2;7@Q&n}f6t@5v`h$=|SPu4v>aE`<oH>?wR3E7OR;H4?fcjfZ)Pgac?Wq{!QD zbtJ=?2BIh#s$6-*P!#iOCd+BI8Jt(}jNOGPJ}>BWi0{7JtIVA-AqLvSyiq0a=Bl_M zY6+42MUmkyEtJ)5gNDJsCEnGfSE-F=CBtPUDvu>Q#EJfty({9qqls(Y{bpVBs67}* zm^ak;z0-{iCAkgIMobtd7N01ylD3zg9;Y)<I{)$RAVh=DdR(X=Uq2CP|4#hI9-dGw zv*RseL9h*8_>;tvXywSz;>J%|v~Xbes#u~*CEr=cdV0NHN9%gX(kr~E$^Tp5L%;f1 zfFLa$U87sMJ*htQCv5F6EPD%`zT*j@FRISDu0}N`KytE%QHeihaI?Lwa5kW|BcY^t zknhAwEwc6iLx#{mk+KfHQP)^HQ*rAYVpzD$DhK2=f-D5V@bG+EC?@1{qd?b(S45d6 z_;GWPqme!aOKVGQk9$k{OS|Dya|$@6df=<dlZdW|7kUaY90>%X`?OE3vCMwtv*HYq z;=c|`w0OVP`!VWKSMyqs+xU`?7HtC4YG>f?oVnCm(M|HU-aCI(p7?;>`O14Yx_oOb z<bD==0z3}Dpp?fXyw<N*iK~XHY8o5U5X!jdXH?&s8u$nP_96f*NvLRGC2ue{&}whv zA!kX@!kJLoWcd{#&XGBS@z`E56Mb1KjPqCuBa9B1fs)#nT1drmt*@^wiMxm@erP=i zsg8_WoPHsj_%<Xx<dNyxeZWTY*+Jdq${&OWTvD?2a7){yuH0<4_wnD?XzmNz7O}pj z@v|xv+j2-ZPt_KrAh1nMjaD=1r@ql6Mvjubrcsm)1q09{<?7jV*I`iJT2`y>b!)>L zp^&1<<v{A6YoY}qf(yFMd@8*xeg*1`14eFeF1;1?oO8p7LlpvPIzA(#n>VGa)9G-Y zIN?w%RJa-{xu$G79vb3XegJUUNTV}9(Ad^tW-HxiYod5PYESl)nCe)Z%$af4UR=(i zr3y#4MMfA&am^uNX8w~ZR}x)C8fi1a-IAZ!H21p->cR&-zpu($VT;M6J!8P%H4q&~ zTXm!Ak)(Qa3bb$#nd={#0);966Fahr5C%bAj$65^Esbw`FS>SI=F^H4N0OUSHc)H? z9-MZlJ`U(GaFt?VMC36W4$;Q5OvLx7ZLKt|X?gEY4V(t33KG507{qSv``B2>J1&!s z2YTE;Z&+<U!k??DB?6CdXw%<!RTEIlEO7v|mIkO)QPfSVX;_xHXi$=zM1#KxBe8BX zmx$Bh(jeR^-?fUWHo7#6_Q9c1#$(L5<Rj%7<L;_86bPOjTc;?X<NXokHf=dy*4`rG z|DeG3qsz$2f;*fd^mKMJKxpTArY?uecxKk)P@%grn2TlKa>*4qZo<$50Cc+r3+FuO z;qIf)J-s%Inv%F>iVW+t<V0HO&UEnjzW4?mD>44fx{|(AAA@=9+SY1_@>!W4l$(s0 z8{E3^X*|3)Fl<jV3867cqY|!wk8`jeYzv(Tt<A80>s#5pN}7kcfLI14dscfROP+ss zsTAa5Zo?HDzj5Mh;>F>F#uV|&H!X|+Q1Pfnytqmev3m1!-d`tRn~AFOvK6cRDH<>5 zJJtavzV|Z&i<7?Yexe--Rfds4y88L{x@47fh9!E-=R5>_;~&F}*sEqE<t~dg=Zd0H z@gofAP*FL+>$koRD^vG<oxau-be3{#$+OS7n-;v^JBljbI>W-OgGeQa{=&k6nzYQ- z`~4tzBNwFj@>|KHIoXH!Ut}bak^4DbwUGTyjjs8Urnr5Vk0F)4yUL&c7I&8b$rA@v zy`@nDAhzO8y~tOz-I4`YLOe1#N4bocGM~iM?-xw>YO0#MYi<|)D8DK~J%LZ$X@9|R zfmi8ml{}-L_xJ~KFrDYquxg$3ZRM?SB}aGT?y$xMUWGdD#inv>C^{O&hmhLoivO-l zzM?|top5b|*Y%80gMk(1s5gM4(BGrhD$ABlb`2-Z_~}%LiPv!=67)qHL>0;gl>t}S z&33ETS&fw`ZdJ0mS1SK-)K$e%U>q$}0)$>tN^3~^P;m3yq{6o^64CDV3j9f5OuI1s zeH8wQV6%AuF_5;ey)Jg77xXF)9v_2HX-ohvjKp&*?Psw{4bda44^demu!oQU9gtp{ zfrqCDzI}5c4#|h5O3W1NgR;Av-^7+Xw8IlI?x%`F_HE5#Vfw)-de`qGu?Vr!uVfM5 zLMc$iNYa7DXg<e)M=`f}DTD|i=d0&;pX*ves`ET3_0M<P1CklqZ_ARDl6pq37?51k zacJ;PJ+-d4(C_NkZ{o#sZ|1D;07b_Y=)62#B#pf$OkL~zc$X`TWrv6Ojz@_Mgf9)9 zMTN4(4{lP`p0f7<Es=arrgH-*yu;JiOcz0T&GUDeO7^j6N1u<ILoA&4%(O|1pyA}n zC_?Bas1_p9f2$V*YNb8FEwMm9TjZM0`XQJbIiXhFxG3IUKaRDV(ud&xQ?vscQCb#% zi4;RWM!k3L>iCXr+}aig5~ffI6U(Q-!dZFy7{jkjdLnSk`va=hq|aSn{3s-)L@4vd z2{ejby+=|2K1qHDq5^Il;4q#+ktia`zN>z_t8DVIz46t@>eFAi)Seve6(#o(3-?k% z4Hgvm_*ox0i7hM2KtP#FsiX4@SksG-vUWgiQGDp`UoUCL!{}8%Hu2qm7lzHOZn5uv z<{73dbRwwQGZ8N@Ap0_<%Sv8q!7lisV6)7Rg{!Ft$je$X(i2LosD9Kq><}PtRem%I zedM-J8hJTMYIZ9W`5R2!vRxJt=#8EW`t=&0ISvuD{Z?4J9JLW3_2*N`tHx0X#Y)ib zt8YUDDiwH)uS1ehRRJ3hkcyR(rD^M{Jv}AKjpH5no({cu9h&A`WM!0|_{?l}$uN2- zYr{RbIBtdaWW3mx@GTzw7M5&v)*tRp;pRK0ja92ykLR<)f)917N(=SIO)DQ!1s*(Q z^hHY|g+9kjGCkFr!aGwuUF6ri+A1oSq<{dGE|XFvSYhV&8l@)FdF?xUEI*Voy~I%s zk^(wBmPjVi9A^;EwPl;2*7v9_KY0y~K8wk;%^`;2lTxW`lQE{GG>iKN6>nd#<Kd-9 zGhG}#rR!yz@l;T%94lLYe8FMIEMNbGwD_uC9AKEY99wKgx72F&cWVN;g)OyjjmK=` z#aHS1{$poTxR9f}i^~u9|7Kye%_{9udH^@U2k1!isugu~m`C5yx>8ED1eWQe?Y<jQ z9iZO)zA4BmIt~a7K9QbL`c3|nejeay`?CN!trR0*ng{z$T^l$0-wOAa*#BU+z@h(C zwSUKZ0uZ$yjE2E>1$gd4itY%&6?LG01G!#en`3}^T?+9i@LH0!gwsfM^jlBGSRme3 zi{<?rcxAI0U{i#^KuV17ZxGq3K=l9m1uqUau!ffwtsN@#Jiu}qM5a%diJ%{?NZ&~T zG^TL0fZ8192|JKA0;8+6uz(7q2zj-?us&^GBVduv)~K*s_4YTyllJEy<PC#&cQ$hm zs^gJ(=qOL6qcSWD;IAi4F~>^R{lFkp2`;wq7giVP9RfDe2*A&?26bA1^S>a;HekY~ zm+^y+wIJAZus#_?8%lFfSpqQ}HLZ508!~AVZ2U;7x+aF#67(}dX_v6?a;C4q?IoVq zPTz_=-~!U&*P#R<Pqr;ylsQFxt5JCxLQx`v29JB4@gV$=pW^nkF^KMntcRrc$rDWO zeE+A$yj|%i2jhqR%ZBN$1Lkt}@P}}o<Bnu5C!Jo)YAimhfv+`b#4*ehv}&b`Aw{&7 zZ3{3;!K8Ms16m2#Z$e5gKKaFr->=xP*}k<5Si7g54y8uHT#?Q@JQ2Orn@5vn%G+L) zX0C>AvCdafP1^A>aB=*$^4yoQ9(hXvq8+}ew~+uc3MCD%k2qGqLtGC^<x0huePNqx zUgct!G330oGyjohUI4^Y#pT6C?XYiP#i8Gn5HI`Q(OiHVpuCHM2FS(rJ~(UIs($9! z!%c~RY4Iw!-Zvv&&U-#j6`c|3SFe%TCmcv&C0rEgi^6Ne-hlR=&MckJ7SGy)vc=mC z_eRR1bO{8<<LH--FyBpc(Smmw-OPx-oxr3}B}kwScDD|7X~=GG=ElaptEW?s@v{i> zZ!;EOrD+}gQbe*M_^>X{fTRpTHNyVNudSo6Ye~|J?8vks=2VhE*k+1%!TKw?Dp8bG zHJis7x7NKbYylhTTVTl5FTyp~oM^e@b-WW&3zqx2@~LY<LAugPXmHYV)Z0>w+`3RS zUu|zg^|r<eH~sVvFAgGJ1E6Xq;u(gU&3bY~?XM_vihX3NCW!_b60WbpP<cqHeWFc9 zH>Ay^d*q|kEv%}`QL3{Qu;y$t=?b8^Mi#qfU71MP$SizlYHE(OkHb$pH`bV;!m6qQ zzQnMwa9{t%o^!=0AZaQqR9(G&syM@sZ+BjZjV8Ul`m<yXSBmNtLmrE-K-@OY51ILw z>*_qYI+A#6(<Fi(95}2L=h+Lo=pI<rxBy4;W+@uBE9r&#3+uP!pC`Z_q7f<;VgKbZ z+ER%ul<q*08%Z}K=mix3`*PkpH?y<+>MsCEd+wC=ps^#%b-}00gStTD<=AgDecH=y zMef19mW~cLsh&}4Ar9^|-)rL)Q_m~Y01xwFEwl0Ywa58|GvyN}oIAkUCul@Gv%7>| zS8qMSkvsk7Rs*Oz@D5$H;X$&*!<`V4NjXw|?zve>OBjJUq1it)Ry7D5siU;7^r??1 zG<ns}XU0=)mJvWGEAUniGCK4}xBw|KYM~ePXu)&8X^y9Wcxco8oMmSsjlOs4zC3&C zhH3yIhez@B1V|S%km8yiI<Lt6y;}snN$?B9fO-f2ksNvKAH%V*AL5@{e_udeoq2ei z^ie4!a}huK$BHI*-k8`O>$XTNrEBXZDMscntF@39F&)(_FkC_$qTAQ0?fQFSLRKOj ziV!@X@S8a_CBk>S;PO{XCCwISf<504#dV<Pe)8((r-@aZX}Z3rK}0@VheentICWUd zz>`Ejvo3qfMgWyMgccupZ^JrXp_^Y$XqeqxPA!)<WSIXs<HKqO-@=e_d}*c6QW2-4 z4b!+J-{^KdF07xb4#NT!j0P?&UWvJSNx9>zw@$=(1G&TtBl&5omR5SgIU$^4s%&A~ z2W-vKDOS(f){aB}bce3qQbM+u;HI$(vbRzwBKTD0CzRXyrhb}oJ>-{L<FHSow)a)c zJ@di65}bx@>_<27lpx=nte>arBu@-?OgeUUfhd3mTHYI0R)o8X8X+aJ8sthGa@v~q z#>;8pierqAAwexa({bb%cj9zFmB6o$Q*SLH0^3wd&1y{uamyB<g{ERd6DeRem$Qif z@Rj7r<nUz8YF&bxb4nGxergWW#Qx;H8|0QQ?hvBYIigl8Q|>Uor>G^(Ct;63i$tis zYeX;W6mU>v7^d}g!TrvYX`x)(r}R6y8C6b)>4h}nr8@?Rnzqg|yt77i1@t~uO;-&C z{L??Cm=-v+U@uJ>X)1xV)i!9DmFy69A0T!{dP!)@_wb9uL#(w9H_pt06qf_J1`a8- z9nva)#6C)+=aM#6wB=tsH+8hJM4G~<M`3ZS)E;OY1gT!bcP?aMN-j&^wvZid8nZQA zyLuJUpJe3n?XhwYxoy`s%f>V|qc&d@-rJi*L8*}VL0wJXxqV#&{YW?$k~=pm-Bm!b z(`FJz@`jNk#}1Xv{BC^hQG6yql?H2*e4e-FPs#Whlf<5BDkJCla<8;wZ*t6~vhz3l z4A9{fzEd76gkj+6Cn7f4<~yxZ011}>nr&Uvr|9;kv^Qe%)iFA2J`Ir4RE*j4RjoC_ zis}E4ulJ0Gs}0}2r6OAN&aHPMdJl;@Vf0>tC`0s!5fem>9z9VLebiv|7G($`I?<U4 zqR$Wv#^l-m^{n@O@B3NneLnhN_TJat``Xua9_R5p=ArXQHA(^ljz^~%W6^iSip#kI zH5i`f#12px&zq)goHG4`fE=(Nd`|m09_;me8bo)3vN7Rmhm>T=hbrJkQDI-lIQzdq zi)b;GYoNx?`uYgMX&^}d@ijYlb2N=02jr0c?aO<<Kqk~Z+dI#4S%RW~MRVOvJS~U7 zm+PcIJ@<Fy-ug7{9kIfUr*DV;6K|RQ=KJwNNfCP7F7+MS)P$7;MO`$Qd99Q(;F1Ax z#2P0$gFhZujDQNJV3WDVMnUZjkqtJx7b&|eY;yUVKl8+3DT0aqonDZMn#U9=#(6dG zsyD|Ip|OvbG)L%t|9p{0?DYNd)AKG>ewvFpe>4jdS@#m?SNtxUx(vC5nIA9|x&++m zbi98jnd{}4ND<L}ooxw3{XK)pM$gi{`OBuJp%|GC5i;EEf+v?rQ7uN{zm2eL0mxWE zD_EZ{$rQgNk2!HKTn*xoIE6b$#U^zsIDUru^rh|0r9*jaBJ3oP9IRRBfMSQ8X^|}5 zDa#03QG!jij`KTOU#{QuzaD?s&f!+)aOpgtt>7W{gp-#q-`5P|-af7Hb%;MfZd3xO zA&dN08QzS;%IT>QjQ7iBuTE>oZptqQnpRLEj31j-#;BCj=OnBrlW+FosY;fRy&26* zc;$p|-gH7Ky$rNuTK_`z^SW2q5JO8(lj>*e>iO5#2I*z24kWl@<kaGVYB^gngTj%~ z=VaCpt<=9nlV~U&bzI%xM*Zl^5C9uuz&fOqPT@({3-97$2U%7-;N#B<{=pc;iB~l1 z)7t7vOFmQSTHYh~a7t6K=f6G}7`|=fmEJX}Y_~q95lmo#319}=Q&L_It2IdHGn%x7 z)YXIN{JJ`irC$u+`J9X*?bR}OdH>{{H}QKFkzNO?Fvp%K69^|I-t0<a4VR0q{Tu+7 zUhIjvbJ$pEz1!Lp@+}uU)%mMAS)%??gn*e4d)0oR;9<|4RRP3ap5%>3PDYM*TC^&J zZ{$EsA<RENFV`n`Um~e+hr^}U%1&5b{Qi%gjUXz`$IQ{C(fz%T$znIN>n#!m*vwg~ zB5TYkEnkZlT@R?l&It{ISzuzg=o-8nRyH41w{T>J*(}8ig{D+Nn|sCUB%Y+v(x{Z2 zYkJ>Dx;|U^0Q>Uo;HFKH?yoR1!cCwJDr~UpCi<*m4sW$y7xOwgdbTbaX0vfRnbcKV zBhxQgU?fWOfx9&!<YKCik3!`B4sn6D$(15umhi9#r@gM^v)ClFwjUB_b46y2rAG~1 zHs>76{q#O6OCr_yW_-7G@%NytYlhBL=7E~08nB#3@NzbI*P+4e_z;X(VdTp$UJu4O z!fl-QV~?x^=KG7tfZ(7v^a$@UGP2ATei}Ic`n!dTPBYtS;+TALr^tki^gJMG&r@Lk zPg+2Vu-BNb7{g_q+#Nk-rGo}GRa#PW%VkYH@iIOqYyxdkot`uwn2K2$+>lo>{Fqvy zKPyn!D5deTOYjQj!w$93!$>5ag73I@KS;1|nUW}Jv@;Vg`nc)-p}4x{9<S5OXT!pk zg1W|<_heD6YOMA!9gO#9XEbLd;P*SFy5*r*&{hgj#8<%f#GD4*fRymL5a-)PRt)+^ zi`;rz%pcm!slh%HUsD!Z26}F)lJ5BKF$iY2%wcy!1+Vnc!@(TozVK~re!eV5%WpdU z8Y4__C#FW7*E;-Ji!WQFn>)RkS($r@xqEUY8>%*f;-m^V?B}BR7tbxkJZQ42(sT#M z__L+0jpH+GQwc%SXhED1y43b0N~E9uF~z&|vSkJL`C@@1lMI%|vT0w7q(V^-Es+&a zIwokK#;5lz9p-h7z)M#C#4UmZHMc6BwaqzBAKZ2ls~_|9{Iz(|SW>=^9hNT9CH~0c zLZg~}<}jx!fE(ZVhPW<x$u5Uf<;BvUBF{Q%`ya&WP1vJc^0fVV)5qe_SCEWHhCjZQ zpFfXT*v*mqszwj<#)Sl<R(uA}RXL|vSW_C2#a>rt1MUqs&9(TP9JxO&f7>RxGJj~U zx7E!N)+^Y32insYM0kh;au}Fl^4RF)9wn$V(w+{>`}^{R#;_N%BCgQWx-p&i-95cu z4RNWIlh=<yY8&6R3@Y2_=NP=jO$m%6zdjH1vHQ3OtW~x*66V(N3E|M#D91vq%nrJd z<<Fk^XU+M+XZdU@LY*p#vu<WizSs<`Ua932(h1FHkg1?Yzr22>_O7QsHUcJu*`lHc zC{Kq#E-q~_*-Cf0luT4WMk*W98!A$tB}4O3_Fbg-e6ZCO(9TX6U2AChy2i}8NEq?K zS;(z2Pi{t>m`?ccHZ<nUAjq?(m--&%NGOsp*=Qs51x7}>V4MuNLhKTnxZi<&8Fn9W zU8F34jaXl0HtxFurGsY>`JdFeS5|k-rxpcuvy6UqA^atB$kQs!tax$Mm{{amlf+=Y z7SMI73G5RqkNPZVtW^r%;oY8PanQ%{w8%c}ckxjf8>{b(e=y1w&7$3qx-_y<-&yT# zmRJ{Fo-l^hH7tJ}KQf<~XKWa)dFRd>9)a7n*Ruk}*B;%VAzR5@M?bpyCO3mx(mwg8 zyq{yr?@8|&7;Yv(jLKt6<C2AS4NMt%`r#T`+|_7(U2N{418tAH1m%*aMK`~l0^;Hm zLRHr1u7Ot_S2FZ1<ON@v&^`;KJnv*{=uQa*Z+g`OzcDDf&%*v5mad)cxU)XmO01S; zrRb!{G1IGN;?yMKk;^mY@Zn2Obawwrz&den5Uv;-g4&Ayw6t?sLdBn3;_l^lJ8M`( zYLPYW*P}Af%YVR|0vTxE<QF6*7bXKhFj?18Z&eCu=z;@VC=af`|Fzpd3d@)q`i<Pc zL(9b_-0Q)8ndW5c+4$-k{O;bh%&Q7CoCwlKtrA;=KqQ+~wqLUu^CtdF4Y8n+p6aQE z=asm(<=T@Aj(TGcYET}YF%d>S0If-L`ZC?`=-al+K3iR7+;e5Sl{d%G!pCH2_9la| zF^`W)%R_9k6iidrgqNv<8lQt>H`WF@DfLkfH^DWFyRTcKU3zkqJaZF*sOZw3qzT(r zelhn9?(Y>!QXb&rfnGD7sbG5!=r<^o1|C4kzAlEv;T=#3N}dNcw)0K$)zV}9TW+)B zPg_Wdg5AC!SCZ7AZ-o0l55F^>=8+RPmsGX-+d4eS8?m>uf8?C(@?Kl{p|tT(8>z9` zWX5`d>FgQ_J`7v9e=XjK8YhDWn9kprLh1hT;@1hCe0Z2a9Ovee^eZJqui|^hNXBx< zSg3O^-X?Ao&6e^&&y?N3eXv{wKBnc@R5Yz;0Qx9mZ<Hc~%2DIERKWEhJGn$1NL`tr zC_xR=6-D{%;eC-&YA_l0N6j5QA=LBT!5W=O1Law#Ws{Unj~>$6P$`(+)JvZ@Rps2l z%lYsF{wud685=T^=Z$UcZ>iTCA{OcI^GLsNNEf<MoMukS4x79ZCoBL=$E0quaUb*w zrLHR9PiQw<y$6#w$zL$BHs-&zD0Iu)6ZF#DlDtv;`t0~0+NWmEPkk2V(G~}gI(GRr zJjFDD6Keg2I?#t^uRv_x!fduF$zW?GNDN`9$d}=(lQ;+pALG>`a!l6xpqX72I{rEZ zDQ4`$j#C?a)y*<1rmPd_C1s*Y-_T|Ph4oDjztHHLDwO_aE6DFkv+X-f$Qkk6AQU^0 zB}GKplx;|7*vYnC)R7<;^hZ}C;{7&LIt~Hh*unRR-WMn>`?)?W6Or%jXNFqT*h|8# z^GwaGReykPX&7cQS}^1b(`}MYHq@EtRcRoE{RkwO!$u7FEFNbAcW^&{-Ccv;1Jk>6 zs9-g#(|TR};EU20_w71~m}o3OWEq-9taM_dqFkQIz`CWe8v0{zP?c%I!5Xk8-vvzK zRLiyq-`|(FMV(`gPqTE*S8tr?^lI(6rB2E4)`R(QC)g@<;ouQHPU6f5%m_6=_4gOZ zOa~6Da^pe=J!9=WEb@yt`mC3Ea%0=TqPHcPhU|W;*y!R!P+@Ob-kc`{f)^vrrj<Fe zD}0_IFil;Db(MC*Ofidet!+}eA#WryS$IQUWu`cZb#*=--u<>pOW*g?U85oPkd8gX zz$iU&YX;J7buwn37fR*EXdt<jak1W+Qo>2%YO6AEe-u|p9b5BpTlu(DtLVE}VzD;8 z4YgL@DkrI$TWpo$2i*`sWf}N0(>Kiwd9%6}*hJ6uo`g%egd!|O(j45=r_v7E98xo9 z<Y4#Mg=T4>P~;uYlP+T$Q3jHh@5fEu*a?UO!s2V;os}g|dv07|iKk-cVsbV|i(HI; zMkCmZZwW>6tF@!0C5CC@M_KT;WzCZUSZ~69ZUW$Oa7&Ux%N@8?;95|j**=y0nHwG2 zEfawh8gi}E99B1Cl#Uum4!rp#tq><t|7c$6Bq@L6N!qKpF2;*t%9Ox&LcbF@ae-z1 zWw?}qw6)!=cH0M*LvQHr2U|S##de#MCG|gBX<$@V9Z<7~hpFi$F*z+CeyW`pZkqNO zD;Ls*`)eo$*bB*qT11ZGx%>U7sD52^z0i`Njruw@U;&RRk1Z$H*Q2h>>8Bw5k>_GU zrblm*_N#v)nI?<ov<7rHt7SlKk=AgwX-`EBKqcm!^q-~ahLo>*<Rlu6@s9c^Wc^v{ zOCOb9bCEiT=L<@f%VJ8?3NCG{`Rr+wuexM7->FLms>2l<ewo;J0K4-ip+edyGCqtj zJI2o$ekajzdRD{Fp!<f{7E4hVt*jP??(!>%)t}sV?P`Cffnq8Ks5b*Qjw8c$Zo$v~ zhw3ocvpBzz9sa@=FE<;g!fMuIiJFnI8JAueId)ivGYD~gtmDhtnEr9X&ZqN!ut)Xm zVmauhOI|=4h}b%Vw%k*HG|TI1taZdc^u+pDQ-;6$Ze}*p*DZE*=!nvfNwi9!&+rEX z^`O<q>$GxpnpR<I&^$xv+M~%*tCW$%963ZvSJ@Xx2N4=ttSi$I*8B2L<Tsfym>$k< zV=X?*+AB7mzcY=U$CM>A`a^ey^_zNUD7wJLw@=}@W@?`j1vZXz^!e(-`b)16yX(U4 zJDzI@wILBZ>v6-G1MYS&k-*Jm--`y_Gg8hmC%KXIuPkQAMeb>L)Q?4mS8<O~F>g_z zD~Ef#;lBy|x!MWFx&15&FFHU$$;`^XOi~otTV%J#o|Xx``xP8dbzBhGrwsloRi3-< zF}eWKnN4Y*_Djg)P4^i6sEOEQ$n$ZNp~Z+xV9u2><8lM8oiZuVPWpSZz7vDS_T!5N zbZ9nB_{oSpQZcPqXw`IAv(|0c`kq6c8pgIRMO7RpQu=$XaVQ2x73k=KQo8%`bm5;@ zh=NuAC|!00^0=Y1J~n6arn+|u$873hDbS+-@ZSaO9@DUO6lcmB*&%@nXL05?)v53K z233J~&FL;L|GC;Lvg51nEPSUuQFrUnaRRR3pW)ai?|(h>#($_SFLZ@z8pv0Bo;U9! z8rtn&&G(e1{CV6<Dewc@(*Kmw@#ExKAj@V?mq$E9N;9H4&}&=?BGjgDr8inuKUIy_ ze$n1s#5tDE)!F=YeccadQHEE!{zQ<3J)D{b*bm7^p+htWF{{6;tC;?<#ymP33!aZw z`$f!nH3ldEEK?O~mP+7voCt|QaNKLt9L_jc@N3a6yGENu`ncyDNr>kuFXprCcjfFU z+LPI7G(HY|Ud|s`7*uB(Qnxw%j$0#WJormAPj&rag1Fe7v&G_oYh&-ubPdckT`Q8r zyJjGfcqVUN4lqwGf>GxK7xbMFlxs&4tI!R*did!*N|DH-a21{nfx)nMg!>_AfD$%b z&OCX0aDnkWvY_MbUn2f`Z)K6v6@zoB&hN(xZqEPwDgb+YUU%pT_ygXvqabpJ$zpxt zRjF5PcR8s#)dR}Mf|zuFr8tUy`bBAqPPaXZuRUDvZpFgR{g>BPZD|8!M!i>UM8Qnk z+=wdRu*bxlrz>HppYAPk4jeH+JuO=15ul2L!vhx@^@m&|502&#ogvtB6nJ1vgWY7X zz1pJXzUJnT$k!WWdFbTMbXym?8`C?h3IHg)B0;Gt(@5n@OHiC|pNt_9amzj8Da7KO zMKV*NQ5*M4>Sz8(dYM0_^Ii?tn)GuXv$tHf5F$M5KarF->Bf6yqDbX(su*T(VD28~ z`wC4juUKnee?BYE0$G;05A<46r(J>Bl9th{g@zsu#}utVib@dRE7K=(6+osia2I`U z;xLWgP}P=93%cKlc?jnC^P3=n8)WMI@VwcO(?6A1<Rtd1!n!vRs_nJltxrC2_B?6* zSBhrM&|W37$5~JF-cv%EtDJi;l_-XO3~ygQ1H5pXBLADum<{AdyaJqI`aMSg(F(B0 zQBL;kv|QskH>?qc#FBw1yT?yk-zY9PAFn&Jg=7oddRqV~#C-JlOSBS8z^S24o9Zse zR>J1{{}M@=Rot>6(26-+eF5S=i1D5pquPyFib{{m@GwQ&!{en}kqEy(^xx+lH+(LL z0Hx?AaFI#>vnlw$oPi459<*VV4W9Zc*&dv<b?mRpu^Leo*5^|7m*^Ge6>!c;YJmOX zm^OjXHAIM-O?t$#_OH`3|I?>z&F0b1={A(T3F`?_7<V{~{|}rIU?KhgAO0>!u?ulD zAO#{`ei_vEV+MFK)9DAlg;VhS);;HrfRBy}H&^&?1K)oSZ(_M;5&BQN9mloFaIO-* zsdwF*?fOx*;{WI0o4N6SKY=H!EYs4z9gJE|V52V|YPTKB34R;rC~Exo9MvvnK~N8J zI6VMjfjnbBQ6B$G$=e1emNcokGTeI-CaCIW>$jtg7kKzTrp2(M?Y~6U;flg2ygFdT z%uTu6v39`Zjs7Kiv<V1;h1VXbFgeQBV)KyZ#AS-D2Or6BTj2_eBE`TSj%AGyApyj@ z4B-Hgkwm8F`nCh%ItBZQO!Yn>QVIjph87_ZZi~;U$5e$q*ChHNF}5Y;rF>-)wxN(s zcncgOOzm>!#-xQDIt6zXNoXtFHUNHh%i)q(;u;S`Et#NO9GE2*%bdL(m57Ww6t-0= zZu}*>+x?FwCKm-n7pMx27llCt06vd%Wp|!9tgwkJB<cfl%gZab*=wb#K5rdOe-*c0 z$Of$H9HL)z24VJ)4DEAq@cylx#r#ws@t4EQ{Y2lsMpP%$12MUoRyv%q4wy(AU|@j9 z@#rU@VxCGYtevIfF0Ld*bAtL(-j%WQ@0rA08BWyw!PSb1m!w3HgcWdc6D3a|yhq?! z-`!1bopE$4Ul*(StdZlzt{arq9LpgV7MF5SUUe_)n84-wK0GTm>&?MD;SZj%tb(An zN!Z3=w)a_aK}xV`Y#rgA%as*wYH5EDt>krcWb1YeNaEfit5h5BiSndUXEw>urZJ7C zaaB@h^HD+1e+Kf3Z@qAd_RI}C6jiNk<AW{k&+%AWilZ#7*?TpY{c0?YMZqcfh88)= zVNJh~i}28B&x;hC5MY#vR3+-3B+%k2IjM2w##5zs+~<$lTiOuQ`~jOK(|VxKE=ncT zcl=ikDXE{Et7WhK=lOW~`ZLywFq}nAq^5f6HI)1lJr^!{>Sbd#e`=E-WH)mt;Zx_$ z5i&a3mZR&I`Lprc;XszFldh94Z<<Hf%dr0rx7x;C;6?b90L&cq1nC>;8*3L7!0qU{ zrg#Iqez#|G-42K=mLO}+Z(PG}c?xapc`h|IC!>DbFu1R}38p@JW<{8=w`{Rah|+$j z?AJ3o1{8wm6$gU!g<4pnTpqBt*j~+-h9V1;V!*(%>_>XVPj@(^3fDKJ+f``a9FkxI zmEgCra(kKV8GIv&A3~2VAT^q_S11a!V%(J%k+PCwSocfAIhwOADumQ5TJz_^Y8LG5 zKF%VqH8SeOjp8Hxy>&-q^^S6c<OG`nc{7*2v&s+Zdewf)`Xs5|m;(y<RMDK2FwJVu z9Qq2Mm`mb>PN?YAxk(h5Esby4{MA`158o(I_WYO?;+U{>zuOT<hB^n9kS)OEcB5%j zf)*d#IY%G|7)3e_m};Qk`Ru)?+_5_QU}33&QxmuDr>3<4zuRNHH>&k65|3>FT~GtB zdtKGz15pE}DM}Bu#_Yr<D!ShVl*!asny|YzyNar%8^b(J1vVjj6)&dd4iFtncWi!2 zJon+sPz13VYh)fv98d%8!T?GU_DosQ1$%QmC{9|5LhHB9Zp(oe`8mdBm(kk$DmNiJ z>>&oJT&G-3fzp+de)@y)T4J58FwXIVlR#p$@Rw-tO2F_;KGRg5cW$1CUZL{yO;SEm zYyX^WgY=a3HV&%+4lbwikJvjw2>^v~GaovgQNysII~7^6B3#S%L%B1{I6b4(UFJ_q zUrKag)A&JTAf_MXkRk()@8-u?#3*ZSRIO3tOi-LLwc|0{%~vW2^Tnjh+%`lT;>6wt zg4U)PzI6?!cW!NsAN><%GutVF2^)%-KU2mTp}b7&=U!y%05aPcW1n?a{wG|zdYVAm z?vc@q5qJC?iZ0DO!6-)8yC^4sSvM*<5}SVJik%-Qj10SXHyShD_qw?THJ-pB+BDIm zLjO|U9(ZOcJ~fLu(@ppDXthU=T~~T11|m|FS_IWv*Xn)nbhiMyazxG&R2yh^@`=gm ziG>NRk4flYIR~o7f*!dx&3msD7izSexU^aw7?mW8X_iXr-$pGspWxxlZusfJ7j>$m z!6I|T23Bu4A(YnshI*9aYb8Z_%auYJ*%FPNnX=`#+t8Om6dNZ$I8avoyrsGm1q`Ma z!j9X<4>nDwjL*!3M1GWa2p)sdN`xv<g0p$4K(W0O1P6+zg|RT_8fg3*`xEnt8VT`J z&k{1R{f55elU9;&sVvb)W}Dr=e=Dv5*28*&6pmx5Z!u`eL1#ur-w8EBW>qU7DV`qq z!o^Z-N_YF-xup0vqYodod{tdat1h&MR^_tR>=TS*9OCQ+(#R@^NH?2XUJtWunBI?n z5=<1?sFbUe5{MDmD2(cUSeKy6jGN=UkAzg<%vQ(kFr}SSyQ&;B+#StXqh`%E0o!pk zhsFY0aaNgMEQ3RxsZPQKksA%;_g&FpE(acilji3(Y33<eDcNsCo7CPa%amsR>d|X& z)7O-Mk23=b;)D3eOd-8$9!}S#P2CDm+Ci<o>5{y|lF3<2J7=Tj?kZt0jN?FtN#<I@ zxN8n?vA*ypU-rsnUr429e@8@1Y^ymd#3jNkjoVed{=+SE0%hp5;!s~02~-McEw{f7 zbcmcscCsXtLOFb5+WC@@$@!v&JQ_Y;Vz$ey-^9w|`GQdqd>dI3^30yK*p!1*pR15v zj+@tc-9kfm)2U(uJ3gu^%BGZh_*o%k@{wb$El=9x7tiJoAa@zqI=_^C7S>}vU``3T zvJIW+A?+rCfv3W}3nO}HCi;tdmDL#W^ez-*9k_9wV_BrMlg@XFu;+##TE!vW`YM~; z4@Dz|yRU=OYtkl0-NHL}+Z%D^f`6j84tOw%d5uP!9zwbbSLs`^m-!C#{V=6|XdXQq z%h#D22U<llTlkoqt_D3jz^?Dg&70$nFkKT6NjUSMhs>pnbt_#rJI(e$z?`^j%j-;7 zFb09Qz<5V;bQR;K7N5)<9la1QvGHu(m%B(zxmVgQ4LPrIHDdj?@9Evnxe#K66T>=x z4ZBZx00R}Ehx*Yeadm;Ld(jZS2r+(EIBL53{iyF#SCZaT*>{^Q532<{m%<Tvzf%4L z)DmFkjobJ7zU3)m^Zs!uB3zeLfj4j9oBHs#e|~Mt;Ifn2Tsbmd@bl+0n`AK7=P!9o zMA6ascXllqaGc<riCI0eFBbkxCMoa9ecft(9a#3Ia9>7}rg&7(znsK?Itg0mX6%<f zpfw3=C^g8p_RK0Nrj*mVj%up0>06Zsf<*3M&h@Y*<8`!^P_45c0hJC~S*Z+Ji>I}& z59vgUl+?*RsCjiV>J!yk_QEiRM+=R;4mXxI!hlsXQJ5ocZy=kr$O^A8(fpe+f&f7` zw2}#bm<Jc!=IgfwdCNViYz)6$>~IDGtnDZ%I9>(=P7y=ozT!Sc33;7xB{d^O>%S!C ze+_<oXFBa3Fkf@3;MK3wIvLSaI1#(;{?Wn|i=383i;Zb$&p^-_%{!MC=ppy?!9H_w zemP>rg)h}<e}8=h`!37n$+bXuBdjnHYM&&|Rh|1;zt!er%l^Tgd-XUMhT<{)l1e?X zT9>ggsukF+@2w6gt;EFfV<KjsZ6x~j+w1ckoCP$6rFZ6{Rt&6@i<5Nb`n72M^5Etb z+4V_OAvkTc#8344+P>6!9pEZa>!+f{Kl?KAlF!{WL8pDPcqY(I%=diI%fNjr%H9s_ zCvhoa8>}l;CQGM%L4|hsTDZje^)f37Q?=e{FBV3*193x%JybeSoi<`IuRPE0*m46| z-t4Clj=ZYy8v4Ks?FXfwyG6i&HZ~G=Rd(DE804vBY36mxl=&<8W}?W*G6EU#c8je| z<m6YHb{t`7jZO8IhZ^F1@MuX5wT+aQ9#!(v3M0p>d4Z5$Y%RM#da}3g((I)24QIV- z4`C%;m1(-y8v89PC}*9jW?1T}1;xyOlP{BylcR#&h`$-zwyGPWXRkfra_B4Dp3_At zNOWTM;-M)I(aWQ(4nn0c6#+#k1i(eMj(kY=kazGh&$PFFDl`pG9B|xqbkq{kYB1w7 z7AtsrC5ES&R)a`Y@2pAz9k;p0Ha1luJ;c8W)GZUINs<`@5t~H?=Z5i?vfrv}<FN`k z%H3vY)gY|N#vvS2h2p5eTv?=l&wkn=S@P3p`^h8s(!Rz!Ypgt8!y+BT?>&YNh*3U~ zYjiR{VQ;Qv@mg5MsJrRK`MNM*<v_B6jLwIr<|$b(kEzrQ@YQ@T@Se$99^fV#=uLpi zeU*p@+HYbjb_t5OAuOfm5gl&NINdU4iogc)qq*hnN=`Y0x^chRu86Pcf=)Xge}v?? z`MvRwqh`P`7ffC!{IGOb9xgM+`HDJ4)G1#-Fh0THV1+=2j*V89LfTWK0=`#K#P+&g z2mpYKJJJ0!URs?tb2Z8`s;+Qjczn*l@La!fv6UIz$RPhU;b3EY(aixzv7ThmtIBDQ z%hu}-lFMqh`!2a+6%(CW9_J#Q?$1r0#QW?YH;T-kS88`;3ONYVuM{;~fHyH2v<@c0 z!3Ab`zch5jEZKJU#6O|2e%}y0c_C@@q@kt*PI<2Wt4}nrS6gg`vT?y-#rk`cw4AvG z`1Zt?-`HVhD%QwvE?gPm>bG6HMv?6fUwr`M6NA)m&PI;H%AIZs3}|T$+Je-w18~G- zHVWthlC3XIHXUW}#zd>mJfAm-+v~XKqBJ>00CU4&t(j<p^pQQyx$DgH4439~4`pmt z>Kx%uuo*fa`!^iP97gY}X+WEkDe6sAhbT3tF4+_`v#s9@+-A~1@aGE}(3YDl%-IiD zeo4~t?LmO|OEHCgmp%OsKSwvrvxSGzg>+gu2Q%l*I~AZ3t)oDxM@LNoUKG{UjLuZ~ zAF9(0_Ah(blzFbWaG<k%pgQc~^V8-mb^<1c&9<5qFP*Da=2KoA%tq~*>x?a1XEwdh zk*9lMQ?&LQ<(ljYamq;8b6~-=?8_9T(Cs)h8N+y!kNW%O1m`3eJzgiB;*ZsNxhExf z+B0Wt65P?@eYM|`>qy1ntQPYkSgJGkR!m`x>V3laswj|0a-{kXF6;8g+M~%A+%dZR z4GmJeAW??VV-UILi@FY?i!VZN8pOlA#{)!FjX)G*32<wMJdptZ3cXU@5NvgBbvfs& zoG1k!r~tE;fjH;fGBpw}_c*4zDXK1E2$fMUU+u->k>_EOu~Q-U&JUhYZk>nusVEus zS<P8SqZCWGm|lFmvVHL8%9ij`t;wwJowCK1=$_FcPJC;`hYELd@%R#?LTj6bvP4_~ zf()yfTyxPjxV4jJfV;8pD}VcUkI0Ja78uYbc!%%0qEmj2C{)k}7X*~>;?11eCtrTZ zqHj+|qB=cW^0eQay*yc+;=9IWX~$)Hk-LIQ|BT1wm;wqR)q%}Au$3UiW^UuTy7{KJ zfTZvvN)MKm<q2zU8|Lb!su20!WagknWt!on+UZK(P_KbBHXmBTat~P(m=zbX);}>0 z?44Py7KW5pX))jH$5cw|mNvc|-%k5hFES)L%sbkqC!$<i@$P%+3*;Lg;>6(xrk}O) z<=cY{yfZQmiZi-~;l0DAUc<;f<MjNG$4#(D11@bc<lA?`OX-CJT|`w#uFOtTAo>QS zFF>(#f{Kh~yB1~;>%^UD<A}3|rDJQMqoMb3YM4fAEMASF=>sB#a%VmOS-zK(NLCIx z>+uZEa4CLB+C038PvZtFcSH$KRZ^);9qk8N{UvIW?)d5LRr}&u)+%cC5q6Z7QFymM z#+c-vWD=PTP8v1$qooja4E<lC!5(H@5Hg4A?P&@d@=Xo&?%ABuyLy$Vht_tzVL|lY zV}{E#+ZYZD7qB3)Pl;fjku1XKx;}WLpz+hr;(2cm`yN4hq7JBi6bGOVd<N2Yz3Gic zRaTJugO)BLKxw4-z_>MRW$^x6{K-(BnvK#AKiVjl>(5lLOJ!?!)!~cPd?8>x|DY79 z%nfEivrbN6%yq_ZVd);eKqq0K*-7x^XdMI7WsfW289z&wpNX;$YYPuDx+<fdZ=0dg z?2$9p@K9xZ5N-%Fx~@5em&D)~XOYdNKGIqBKX}{^s5=*c51J&2#$?gM<9ncg{<&%8 zjPt{E3^}mF7(KDK&gyX;CAiTiP;;~{Mj$dRM2(_vavAt4r;ecPv`qL)Xh`bhNZit( zv%VvYuN&}u)t;Qhh>xKhIJtqjEC)>Ho*byuL-D!@?6t9Azmjviq4|z;j%%B1rc)ag z<ediMp;8i|B?k65YTOq)EG0Bz_UuSg&RyT?1jxDa&v2^aga~O4Du0Q{Z~IHciIEsk z?s$mVh0%kl!J<QsyW@2AdNi3Y%vtC*6<eWZNi3&de#Q&4&3JCKc_=Gm>5A_)u@t}S z!yN=*8rKE-@`+Ib2?#1-Ai5B{`-+1Z^W9uT?4s$)crb-L`+>e!xfddfp(|MdUnp3K z<kB+x80H~y4_e%d2?Z)s9ICX?6U|we0J&^0Onn3XOtY)gh<<ad<Q8?^M_zI3EwiMv zr>P>MJ{0XU*utbvzKtVVOZU(RbEh@l`V1FM`UaP~sE`9~(;3ZyR7<PkxEpe`I<Bpf z>!MLQ`>kmfHDT{2ZKxtHhf=~k-n>$yv|8Sow$$a%e(vLi7o*sb?STZIFdmpZNl#HU z<DsrjxJNO*9rna`)xn@lJFD}hLt}h=ir7q!U;MAA7k~5sw#hzfwiZ5m-Ytc4-;&1* z+}jHFf;|rqb+HVAm}PO&nln{Dg;dLOJh0s(-(YGpsNQ6OD&j&RLQWhErC>^2UEjQQ zLCci^)PEkukl<Xa36VD3qp@6sEDi|HO=x;g42mEA%5r_$zu8wO@Bz-i@@RZ3j2uRa zMWd+>g6nKyUN|2V(4c1V2$L6viCtWU7APg;D~L;o+2yQW-)POVZHh+eD(bCTe-wN2 z@e$8%rzCpi-bsHb2e$mJDl@cWASWoiQ-HUCA&xJZ%#@qt#gu19d8(LeN5+U4SH#lz zM|(&yiR%ZO!NSI&eu*TIM0~e|ZSX4VjB+4KsA>4+fdN(1?)#msXI|1vh4LDy!*?2` zNj8nL&z*DzC&@zx9j)`3hSe91{ERZEGfbanIFE)XsVj~34%<)ot(?2!J&|CZAHuGH zf-clVvhEv@p_0W-8I{ihwfsRl;Ivh-`M$E;VnJT9X=kboK4~UkQ{I8m-oL<Tn)DJV zFlJe)XCXR=O-i{Tq|e(sTRcl2ECg>U*#91XSr12~zaGCG&>wEiC!f;{4+uhOW6uYg z+S2+rR`wZvaoW1~Z9)81qI@-fP`UMfF!QY`&0AdM1tWsI98YTka?uir-Q+k@Z1+ij z*nMfchhfxq?&+SZ^vR35+%1qzp<8jXec(mDFojzs0Z*Ni=49Mj8Gc+dn&4_m@WP&A zY9{VL*2(dLd;8sTH!@wBP7lqk;)<0a=9KR_pp-u`PqO&a9<xazzO~T!IZ0Z^r(TX} z3K{4P|FHkl1Ut&L&+d3F*kv8YxGAr^6z?0{ZI@gVSNT~~MRCpcEZHBf*9o5+G%eaT z8d-iH!$@u3)1Ky^8DyShy$~yMWky(nqw2_ZSf1hhK0&(K5lxM4&C@WGH-XLP22*bJ z@w09@bI+3(17r8IX*K3GXc$m@?I$@)YO#e)+XoaV&P5*7!D?4fm50CkVgRcHm6eCT zb~nl0TRNjOm833?TM9(Sy+IE&WdJ4=y}()ToU#yFUmHM>g`t;fOh#IB3A7aUJe#Gz zpLLrWJxn>J%q?52Mvt~8u~=C>cf}!~PVCRZJi5?Y-ozga`Co14xyj&yIJXVsV|2CF z+WgOw#TG_Enqs1#J!PuAM0x@NAC0*$;W1dSS3?GaDYsWXH%y3#hf8?Mw?hO6J*q1K zDf-7NGd>xiAJp4|wJC)Ao?(|HJ=a&9Xl?vIKqc=Fb=cLJ+F*~QYIw^A_~HhVa1!=g z3sF^=ZskKRcP9M`<;e6cH5a0=U5?iOPg&cLSkrbK5L^D=kTG4Llj3{NA4-R-i@!v3 z<wLFok`683w{B4%_f@PETpa8@VmqY=X0kpC0K2Eo2-HKJ@qoGFUj_Jy+oAtYw%FY5 z3T38SefmR-lq5dc-fQD?AOG|7pD5%1L*D!!>-4`4u31sYNDJ_!-_r%>&K&LxN)FW! z1^ltl{&$7H_+NwZh&hxAsP-T9%=Y}DwM%-|{FX7+bkArRQFa4J1-Vt2U57RT&OAWk z`c^i95O!K|tEfUo;^OXd*n9^7ROGK$`*#f+j#`jmU<t6SB#Ye4qH*&+l$u@*fAD`9 z{&0nnqv=DcQecnr@6qv)!0B&-v#%7O=xewCEpUkB|K}zEC-tw({zP8mNzgcVIK})W z`abLNdno$zZ0uR_>O<DITXZCpE6Zqw^Z#5m+vY0{2H?8Mfp6P2$*crUy#}}%ZXhdu zKP>5?zF(*G+Ryr>xGd^{#Ge8|W7F7Alo9dU{}DdI{xv8!C0K!Uc>{^dbIwazbD5V$ z3j&F>S9%cgyHcCCjXLDFReHKW|GovEDE-^1ZvG`2oyXq-(Br^O{P*QU8s4sdAy;U< z(%lXkZSmQ@KAH-b`&}DEp#2#3o2}>k<S$Xp|Dgbh{Wo50c0w~0W^a%!YX3-m>&T=- z9?gWlS}Rri_nl|kbcb3H9#6dC1k@sr>Hj>CQ?k*FF&TS)%ZM=|l&tNoj?F#X#NAW+ zAOCq4{&PnR@6J^LK-iAD%d>RgF_-C|yM)&28x4M#Q@=BOoDlnCW!a7C9R7bu1aE_Y z^@acc)|%LL|NRFM{h~YP@!e*?%%;)WejrVCamyxbp6d~#U{O5LFT4XFcV+#L(akCl z4lK?t$Xl)htVciHYzG4aI+XX9=yWDbcx$f&qlOP22OzcD$Db%h1dGBS;QfF#1@NDM zFYSG;cRQFZY^b#7`lZh=k=#!=n_xf|8CS~H^R=mlDvRE=W8mdz)(7&vssKyj&BAwT zzsLgq650MGs;C9)%$};;G6w)qpdBxt7qv8~sV(9~%t#_LyUuTQqR3s5YQS3e);nyk z@RS}oJ5^<zq%%`4z^qx8^9oX9qW@xEOMb*KEyFHH%`{YYw?GL~c%T%9^&Bjuk^#D{ zJ+KE+uLt9*Z9QqA22&e+5rRo$HOYn2a&j$l6h0M?Vpx$Ut43EbX_|?bgT+_s9&3%U zgFw*C?dwXyJ)F`ICozE)S7!|HsS^o;KYRIG#SX=}+phF;ZM8*qr@p6Y`Uxz2x>3>{ z0dZ+=c`kCIw%>NekB6!eDc`vYz>{LdtI(#6CdH6$4orDWAZScq23q{=5;mdCVcQPX zrRPtRb$_m#Lqyhi1K1h=B?>19FNMyVUydIn_|(|$sogE>#3DDd!+9r<PDv=b{sbce zJo%R_#p)vT`I<M*+^yG341>E}!m2W`wsHl&1XiX!<0@Up`8H+)nczh|GAg>Mh$!oF zW|R1`Oo)MzpT62)>yT7&9#%XsVq^a)X2c|@7{nZRmRecxzF5w#&SSciGSFSGI<F~l z_EsIPs)jJ;aGyX9u7>GiIR}+GIHOltnt>QmlZ})pv3-Lq-a-?W7aac(CM`>wI)Yg= zJCc`Ita4KxXp3J=t3e6<s+98tW~d?+1J2<r|IMupiNu$MB){#saOovbK;_h(seQS` zE`%798DA=PovJyU3}XFK|KV4GkaNc|zFy$hQNJ1)6j<V)74*yy1o7ZV6mf!#5AzBV z4JQ9hpaIxWud2$QlDBs)w`AA3(7%h33YI8ve$o{3yw%D{XJGQpm>Qm;5lyvkcO?sP zXw2@dTaX<e?51^~fUvwuM{~06w7|=E8E7B9*iS-scu{6IzoO9zA7)8&)i3;gtfeY3 zU_kfX(=f&;Rjbr$F2hAe=HAN-5BXulo^iZ?l1_k0j-KqM!NW}1`Rr`RfXx9bFD7S^ zN@GO5DcUMvB(ap)EL!fJnE(Tprrg}N-pryKZfp{nsrIE?>9_rTOwhqCw9gHw#?-Zi z=ByX@Of5i>gGe0lPm3OIwo8cCrb)+a2XqRNyPEJjpC}JMU%t*l+{LC0zES%+?YWp$ z=vK41vbd{Xy7IvudZ#n(!-w@4E%$l<FaNy#R!5E#0=nfE)glhMx$zn}&Qcr?2#dI7 zHC6o*lpEN@=--(XLey*nEsxO2FIsiI(0#8>!>yh@i_4T-2<7yA9pR~H|52tOTV=Ma zuEtvVto;R+D@|mWCz&}vi<zG9f;+W0kzV^5VEq2rMsTnY!-9AH>w>kK1lv>3SJwDe zKCMY-u1Py>)}Tto*03pTmCO!P=JdWN(bhh+kyVTgW##wkKN|`CMr{lJm@R&tYR0x+ zX&!%;ey*16a0g)W<SO5&4qXHEzHSC<k5})ZtJ4;^NT9=EpY${&g%&5gVvIy07*8q? z?Gf|eXSkv9q%8k%3h@kv{3S~4CcXytJ_|6`4T;z=N@?al`kva&^R-PPUR3*xRFI$- zV-VVk2jkSoE@>N|GwCz4Zbkb_)_q<ASkj!B#*LKlm*Y!WRE*2G$fsYXIw{-1k)pMS zogg;zcL%|=!@<ouSt}IZ(-EZ_0bL&_)CSgwdtAaez>IOBTzCc!u3Ti{JymX%g8CAi z-m#}{jT_C-ot2tq<<0!@_v@fd1QkVp+$XPhJl97e{X?|oWn4}dZd&@rg*{B&5P9TG zKq4P27*eWYlUOs7a(XkyD8sF-n^S5`Z9~yi#6C-?k0$b$nXqxW0&=iPzViKcKBRxa zw44PYtQY{lO~{$a86uD-VTGqo^rjG9x6a(>MXRN+D!9`C1ZrX2^VSDsgZvM(+5-o) zZb+wr8V`tuuiE&-nw$tf8{GlXnYlL5?jGQOvhHU`&d6z*wP!lpw(hrTB|VV8UVWWz z>spRgJJZF4h5xzwA1%}t_m>FE0emU4<p^w31V-rEz`2FwiY<59X=_WPWa*5599Oi{ z314zp^ScqOh<bKeX#ZN%`2GS0tuxaZT;cvY`|XPwHY@k4N`2M3^`_R`bH(TBoe}IB zBXl}WR*!<wS?JNHOM_E|Ip|f!(d|C@JbMvpfp-bs58*F&n?#0@vRljas9)DZ%vwM8 zR`EeQti1|ubU2p}s7x38W|j<(AsY1Xz2nj`A;qAI6}{a=mVC<-4Z|u@{SZAwsfERc z!+;IYLs1}+f;>}f+WZtV7nrf|q(S=A;F3}5H*@0+(jR`|Uuiy>sFLGy&%zt7OH~E% z=9u%Zz(@K%U|(~o{V4rZCYRMqq2}c%geQK*Imfbqly2n#UrFk!{5eS@T`i8}h&7JK zzq(v_#8>^a4&Ld8UL%3Y>H}r<NEwi)%EQB{DKAj}nc+tXvCd76Y*J6+5Bsll-cCvL zxGz7xX%`CaU0%%>Rh1GyqpmV8vaPh83-WsfOVV4ONX~Bb9vNFESYJNC)@p~30Hve? zqs$koT!R_T%zA8Tb>>mCRv{wh)x{>HT9kPLjCz^2ntC2)0*4oJ2b?}vb~v?l^A;>4 zIw%1z`3Y2^d8aNMMzN8^yQerd*AYaXs_q({!<*w?78oW@*Dk>p;6?RC>LR=M=xr#_ z*b?D{>-p+=Wd>7?HN^0D72A~7T-sPyy61H6ke|P@Xy|=^Ql08WIjz!(?eBPB?G+k{ zbF9O;oqfgSu2U^qpn7^$G|(m(gN*ZT1`N<9rPDawWVM+l=|45>!;(E<)OaNB^*mx> zLWu9zCF76@3<O}BRY1KtN6|0EIJIYAlr+xp%-pul?Bj`GflgVLH2Z&wfJ^&xJ-?XE zIH;R-L4N$9FSOaZEXL_5ax$2k$XiFxROxS#t*o*mwCbT(obU=j-sx8PmXkbRR<Ma| ztZt;z%Ga9ptTf3Nsz4gTqpHlIm9zPR&6~z0u9YLT{E4%ACR^DVp>sJ&^MFy|XTJr` z<%;X~<#WaDfoumVYnvxx2Mhytbn$1XEvegIOJu)~36fY2s=eyXk*$rjne3+Z3?ut9 z{#NxChQ;GGLv$H`ZqaVg`Z(qLR2z^R+k}2Vx9)cG15=%nEXn|h@4C42K~CZ@2za4z z$jvqq2=+otM6p=J?IVt8fVrtZE9WVJ5z*S3yvWexdH>5Qg3~>&oJN~z;I{Bk4>5op zSpO{ddV7E9iW@qOa)?v&%)(p`Pi{9(xU@E<G5h%Zio;jg1jYM2RLB!SxsZ$XHTA=j z8R<9L6<nT@KbWojL6=u9aKL4>Cx`@noHj9IgZQ^F4Y$HQdZ3fI0pYFG{tet?(%2a1 z=qh`thh?=Wy|VId>-6XNv!5P6<IN5LR$COL&v$d%?`-!~sEmKJ-^#d8`5wdTs0Yis zH1<35H!THzB0+=b7-RL`icTvzpgnSxX`=fEPGDfZ#oD_Cy+Y)G^Y>zx@Dliv{Ac)8 zBCI^bz597v+S7xZqu#`Mn@yp>Hn3NgAQp;LYv7Ct1heDP(8gU|)PUTfQ}|FVruK-( z>iHKcwzPiU`}*AyD(uEufx?lmw&10E_S~3*V^38YEd5+M{1MZ_uDLpS^Py?dF0Z-P zZm5O17BhJ@DKUnvMH<G6lpJ(KZQiL&c$LkYIpuG@2`4MryxZoX*=jJXL!cXbFnuZc zhQ|dgh75u6Gj!T1c2>@QX-LbkF%ud!%`8FRk&&0v?bCZ`zkOxn(ZeL#Ddc!1ftLfQ z&0-=0muI<~LnZDUcM3o=lO$KX=XX&y3(jA320ErtW===m&T%g959&S=C_+aZNcU@$ z-B48T2+A{fImpIdYfT+K(60*e`+S~}lzllJ>=#JZpih@geGveQR-UMTK%~v-hA9X7 zW*7ka(-|;WtIXF0+mmAAUUl9ML+7eWh}l}7Kt^*hxE(1qU)#rJA1|~Ymtm1$U%)Eo zbwQ|df6)_ZVEN`fdD`{r$iAz4_Rp~R^pnnlJ4=2pF7MNS@RBgt#660;e-M|Lc9+og ztszmIk+KrVuLQ4T2#hgTjU1XWHf}}0vg5b5;76+1xa;XCRA&#>dspn|kL#F^uUL`< zm<1<mgio@#X+N7w+^cf@JZccFXVkBY@|eujHOsKm+4yvk0w8=E0Dx@`z>SJ8#;Mfe z%8}+R?b3!g8y##=!eQ2tc}R~Kf7-E7bfr~-%k`i8+aY?@;!jgs7DRdg)MF<IOSK^v zjc2d;oux*JQ2%7T3f<O^1bK<kc)l|a7WG2=e5C8p-}>jS_Tsk!XTH8tD!>6r1=GeH ztslh&)+IY|;4Oesj3&mrD&P$eN(6CqbT8un=nX)eEs;x6ai-RG`n*zi)1gn^n`_6s z1ashT1L?`^0cT-2n=;FtG+SE-=(rv>tJ*pJNqq;yIT!g<r83A>^H@69TBC)mn>q1W zT}wO?bR}by<UX5?$W1aZ&u@EWtv({;U!nFq&xQBb=~EorkZd`Mip;SAuLX%L@C36O zGkFBnyzMuJEAylv0;{GY3i#~@^D0jIqOGBc8t1>KOZCX6)F77VsnGkHn2rs4xJ|w_ z$c}^E!W7{AAgNbZ)#}w<f>>4lqz#^EF&L4n8!fD8B(2Fqz10@bXPmfn;{6k>z((NO zJ1;!AMwc`CPlbfn3c|BN%v_1YdduC|(uJ0kMq_uE-2L|tyVyEh2RgI11^bvlb40WZ zS-kG5jg>9jxYm9$BX+o^-Bt)GILQ1gd4Z%iyFVUYpa1m&$1c&QB#j%xn&?gh_Ew4J zB05+pOa@wvR%9~bS;nkIzxVP&OEcpK4M(<iwXc8un1cQA(kLS%jY(ACGSjoDoOx3n z3?J@L3J9rpxQ7Tn%(LFwzU(2xLc=JIZ7pIi#_qkWbQUs!#>>B+EEblJ|4_~SS@GC1 zIvx%tBP}-*GJx&Ts)sPEkJJ9pC5}hVj;$sBGwF5Yedy9=C(&R3bnY^+{#m`&)JT8` zXYP3}mpNC&;AaYx`Illm1B;r2k#&~ZfsjCs;q~{v{dL~z#J8!x{c~TPezK5tw}5*- zaD{Axv#$j6s+gnZ?nm@N0Fos+zj_5SKWFo)dwSn1O~KK*o8&Lil((;}tq%6lEqJvO zyY|z0ujg}k1%>vh#a*2jr*tlo%lk@p@8JrD8xu5l52CY$%~IC8xqR;m#B7tF3nZd7 z{oAarX3C$>95Gy&mIkpZ4H~`H5*G@)iL3g0F%-*YP>*|ICyy4?%c!ar*|cOcEh@jK zS1Pe$0zcrfGAw7AM*2IJ+an;OAGO7YHnJo3JFVcb(CMZ(Qhg^$)_|}X{X%pN{AC&) zV|iv1_sM)ZA|lv|7c49)8|0Ocj46+(fyrP!`$C20WT=?H!BrkDj4a~tnkO=x)H0>j zay0u%hq6G0CV0!eCT&%s0si)v=S5~|_Wtz@i}^=*f>jd;tnwnzyd#F;{e`RLW&rEM zHw&_|yoMVQ-%`I3K__E~54g|(0DV=YGj^jq9Ipn<f~>1#UgAFngF!YBh(NA?3LG3` z86M|tXX^C3x*@?wVobc}3+^$}Qe1L$XWh?edtfpmF|US?MC0E5Dn{8E)0Y`%db%Cr z&&PLvuwAPA3EYRyCk*(RtI^sg3C;JL7Dtz}_?JhOYe2!(=14hugG>&0Ct=en#e_v< zg>g}y$Djl=UJ~0gFkGvwf|amtQ%6G<4q=jKJEhaga-TG6*az<I+>b#K+`U(Sfck%d zH`i=cng^nby-!e#gKIbOLX+ZwcHjd!^E27>)wKk9s}--B$&%K*X!2J>ELrlzw}`x5 z@2yFNjw%kt?f(JRn+~hEElxV<5c0h2@|RAdXo8n_!w}sR2wMO28Fke0<TtWyjnd+i zZfgfRm@{J>%&}s}dTqdmd<FWrU+&f99%BL1Y+0e%Y#_;7s3?i0@m;%V-XSN@S@1?& zYUe>c=gh9lAD8$h1)(XuovPZGQ;ku9>0nKUm0y`FU0dw|oFszASYu_mJR{3IdXf>) zxtXsaG>AmMl1bYL#T66jTgrIQCNdKJRMX1btZL2_7KrUI>YBxCW2L?lXt9qyRRx>l z*R-YrLC@P}Ux+?Dw|@%X{LaHwU`0`_p`|m$e}moLakH@5?H~keLLmK1bfspw7s`)~ zNvHra+VN9rv7LN@m5ui9bE&$*GJ9n1$Bw$)lML1<UYq<KkMv-<hB~q<Fk#i2YCqKx z)g{n(VzUHY{IRRg**n+%`WwYcN$LV9AV5|2;=X3^ZS1f6C(44A9pnu|7qM7Ql*0gL zBFDoHTr^gD&^o!NW{p=U0KS{8FI~fC#QR{7j5AAqBU!#U(a||sTJv5d5xzVDdcFCl zyYy}R**WY4Am@)rg07nN#mvsPlJa_j3&8Q?6+;pz<=c>I74z%dWRA%*GscF`q{iDh z{l=MUp8M=>0GoA8RAW2;X${DDCNN(MZ8;~g-O<sJzt!H}mNCpbB`Nx2e;^C!5-!kH zsO<sTvEOU9T>Cm~0?Dt768H$Qp1p{_M8f!o#u>jh1zwHUXOt=^=&p1vc*F~q=zhbs z5FV$6wH98IR0Ao)KKNMPzeIijpUVnCWC30;ytq3GRP@FP5h5RI3jx9wMK+<M@cOpl z-7z|&M@*`Ue~HYz2q%Au^tL^Vu=AHyKIes(7D|uqc;X}o8bC47mg<B))tW#CoE1>I zn!kld5(P>F_$@>1|Dx<YgPLmFu3>DTRFNtzO7BH_jfhgE_pbCJ9VAE~N|i2MsUp3D z^dd-?-a%?eXo8f48X$?^zMh%)zP#U==bicfFxkmY&V81BvX6DFwGK(_+bZyiHSV@C zvt>e5=f*8B{4M|tKWW}2;0@x#KS_h1qH-_qmi&G2nS3jn`}6f?qO0xSmN-v}^YOX2 z_kefE;Q)X4gJu&hu=t3^q1+jCbf*yzh4|v1R7_m^+jYz`$eV=^IQ0bn^dIUvfurs- z>T5F)F1(^1Y`zP4%czkL1ay-)8Q(#H4{4}<eCq||_kkG>z(DOQFTbPbmm4lS@xwrx z0q8&D|G1Y`<enbDPB^N*w7_lx(6o{E<vIBB-n{PPTaK7~{9{SbKTXZm^MU(7N7tG! zx$qJ7*9Inmc5Q)F!H0%w9JCl8#@Ad0`me*!<ZkWE0lxj49<0}unr~#q9`69jkK6L+ zSbWa~2vrsFmu7)rs}n)g0Te3w31h?4I0#Xi{YtD#mb)kWU80UtSi8~HySei&?1#fT zzEy{C9?N+N!(M7$!s0-v%$+|3$2*ccc=3_R$BgGP&pUXMugs?Gqv+k11bqgk@&VkL z<q8jbiA}&5CH!qNCjQsOlvX-w6Xi90Bh(jJE)sl8E<5+%Zep%@svs~vh!Y3yPrzsb zyVS)=Ch(VG3otv2-nBzVlLYejzL5PmJh2@=ON4!J4nMx4*no9sufZ^wW?((SK2^oP zm9EAp9(Hb@fqnqNxSCtxAi@;fP_=2QLzZbX<{jLr{>xRUA9QpJd^!uOBv1mf79F{N z2o#cobAde6fBNhrrbDDA^xn<y=aOnu#M6NOS^s{bV6T%hI4Tql8{Y#b0;-<;f7$e} zeXpIu_Ppo-O)<Vd3I$#}Nbp0BlL7@g)N0X=5&5A(4M0^^kJ3fcWicOIk<=$d$EW9f zF1>|6?v3>dbnaMVsXEu5C19y?2j<cmfr@L-aCK;|#}RyolosQ(-{>N$KI@IXa^J7q z?`1VgjUfyjR=R1DvuUQ}aZ!3j=DI4{ipzusAm9;JQZrDl%3nDG6XFGEg88?N#|#Hj zZbPPh#hSiN!ZjI&tszLspNFq%M$Y*daiUiMTGQD8-)F4A5W;{I+C3pG73yH>OmkH% zx0{TnLSkD-2AYmGx3~>5?lk!D19|)5NAv4wvqipD;0DRFVnG~R38TvShK1`2NjX%< zvfW%t$9$(Yw_*cQ)vSm`qAkY6)~U11-eEl6XMsLBG?%WS^e(GNsEFemOeadVdFRxr z^3AeU^;7cobT-4%MGf+`3bm9=2Yww!z)>1-vfzbu5M>7+<hNQYDl!zSRt9%kWu9)Q zdzAx%)L&WZQF5#tkKU0~Kibi)H;PYibGvKG7RBLr^eVWw^ERF_7~U$>L-Dh1Z7b8Y z5F<1GWJV?KK&W1NyFFL2wzcVAYKv~sAho1SL%Yz{_Z{zPMMw5IH_C6(6z`#6wAuN3 z7z6Ab2d=EaJS7Ivhn>$wrMl2{I?lpJVstE7xBMES*UWd024S9@X}kL-Kh-BlUN@U8 z9Z+C6V9_1)&ek<FkufJA3P|*D-zpg<9cGIv+t$vR3cS*^3X+*J?<ros{fSOXk`pDW zbzG4)sm3(^NcM41u+VoeLhVGOQaQUaqhdXgeEPl;M736>ltEHz%dVB!2An@Y+Fsg9 zT}O^oo5UU~nKB?cj>cqZl5)8CIrXIKT()y?5YtB)yPUTC($Z0Hus4dGRUMtIlsdZ1 zDGo%&U7udtj*wHU`nj7!F%6~h%g3^Jq-!V1JIr-M_^Z+e^z0}|V;j$ICyo>ebPu+V zE0{`Fb>tU2Uv}gwB$u1?___L#DEYW~-Gyw%y(5h+ewY%XNEAY5jk$r=c#Lk^8@0cZ zhMHjXOU(eYquM64cF*B^hWHYeX`Ohn46(Z0J&|i3a%P%K&q)1mzidu3^0fJgZ79d? zpmWLIccF8e&fIe!wWh^nmk!Oceo5zb?mxF!-qkWnox*DDOm`bXRQgMhPI}o4hQInf z^-^W~`hCuAO0m2mo^Mu--CCrrR<!rHkkyP>L6lV!qB_#*HpbZ*ZQWh-EDsWDKEE&M z$5>pKG_-1|VB$`@<4%}@;>c8T&|7Bxj=swgwc#GBh^y@ogYx4FIyf=Nb%bSMTJrkU zuj0v54X(EN{hZ6Gxw$FEXZ1A=4B;dD&h}p3-M626u~&?Y)rjWOVB*l@0}8aW_UO~x z-g0>*Jf+Z`j?5~IM$h7n#V(GD!_A%Yiq-aHqBM!)TlHSbb^IBjKb{)ZS$vb(MsoFc zQehQ<q-kWQGkAeYlZ93W81wA)Tym&VW7Nsgf_sRG)l!B2rz9n@i8z#Y+pEg@8r%E0 zZSHQng;U9oGL*4ix-q$YbH}<_Edh&L(A`I|Oj$FpvKsvHxs|=E54~s&(;TT%NuP@Z zcNg=OE2ps%8?5W<^*rg|qma`yi|d=p)1z_RE7On7w_XZVy`<~44#}<K+NVK_YGG=< z(BcYgn7Zz?d9%nkJhjVf=RB8tkL|Bp>iqIxqPwe+_U=dabt~l;FGf2=x$>}fm|Q@4 zK-4{t(MI6hxB|<qxq9$K6XF3J&V@-9Pal4be?tH12k-S4opLWfK_6MuLyGalmREqk zIu{1_Pd#=#3(BaRJx63hpq)ehpsK0WKV5#ti?iUN<)gK(E#(5n5ZaT1*h;3vMsODx z!{srM5C*#`MiKpofGAiBQf-E|%Fa^+$ZMhEhcu(tUGAEH`8-uoy_N`i9&WNi9qC&m z7c%qXNl&}q+M}#a=A>@v9Kp%f$gghQk|`eUess52B+uMP`qaOe4YY{_*vrv84~-Vh z(jugwjMBcPT*1VC!6p-(ZK5vaq~9B8QY>UEW8$xuocyJ1R3WW3mlm>)WQP+&1yI#z zW*8x^_kfX38U9?0g?lb#_zT8p@j>imDzX-WH>sk0sS+ER#MM1CSs{v2Af6YLQ$+ka z6l#~0NbtMW*Oz^e>Qz#>Zf0RVa(2{r7Un<|o+NQyM++UXmSqe^Gkym=&~4EUiD+1F zE@?XtGWV|YL54#n;*i?e$e*OTPi{yv7VM-4cfAE2_Ms2BaYt9TcdQco8^P?fnZv5r zjihP$Rv_(ANZ(S@bbBVo(>YMJPyLaXwZrQK5iIkXyRmr$7Lq{hD25p4ZSYJkG*m9+ zdLLHE;8{ATzhJ)9Epis0pU2o@P*QR{V{PM<QM|YP86s#M)p-*zA0uvv|LC??eQFM8 zRP-qdNG$LwNizIU+1~8*@%B*F_SkoO2ZhJED3b)tvv%?I{Tl-^4%vY)pt=q?4EhAm zH|4f3R5AMFxUxV(Z&j5&n(aZ;CxHUGYplntDqJJelj7qyb{-9*dd?IuvR?q5h)iF* z_Bu&3RLIS#gDy&=tO5D>y2Xm!@EJr&&YMt_NLV;PIw7I6E;2Hh&Pjn96N*w^$V2CZ zBJIAJZ^o|%+4hO1<fwhl2sqf6I~LrrOMO1X!13V)@7vBvX$caJZ2F2_g@w^#!s*x< z+p6}a6za;sYFRILizsf<D>(PK_j3g=eeQm3N>VLnQ(oO_U873HDto!7S!_^h7lU)A zeBRnrcC=o;mT;j_aSK)ygGSl*f^G`p86gP>aNL8b26NdM0d;v>&8GTH!w^X0pu`XN z3=^8kp_?BH(BZ^g>LJ0txHtta7i(%iW)c;2)}lkpn)W-Hy{}mQc{wFk5j1&Ou2Y2U z?~l)?3trF7&8xo()84YTNwqUzG4+pA5ZeWzbb_?B!>#M^Z6!akybX&T(&$gqIV%m_ zL-aeZzxWyR)Z?#w15KoiIE5!xK)2c{P(5oxy}40Bh$T%!w-fW9&wiI%uFzK&f7NKV zx&5yFLUQ1BEw^!YNX_s)f7h^~qgQbDYR7SgGMX7%A!j<6x4@v-H_YrTUtclxbZUx% z&yBuM=izcZ8JiHNx#EQG{s>lSJ7IM7smYZK1bh}%s18w|DvtKuCO1opE~PU{;Vn}b z{;432HS9!7B>PnX8D!|?jL1GPTDFo$A$y6Tw+hSJlC-*^z*Askpf5XQTD&51q_$P` zJ6w#ap<?3x-J{CQu_*okdRe=tURjSyZ<1F(MQ`_y-@|G(p$U@_Bp?!u&Dbn#THM!o zUeM9WLgs00or>FC=VU66W2MC*8i`@1--D3ut1A-ZZPZ4_n<eMzg<i4WgLWimG5xN^ zNw);A3O_uf_|%}tTeA6{(e)Tag^{;yej|kyyO+ZvH~OqRkn_}{)Pu+wYxZmitqJN0 z=2gNu_RjU%iuhD!OvRJ~w(shdye58v)-UfUi>2`CXI<p5q_{j0PD>6qF(|qeB8A#x zJW#{WxsdQ)X2zZ~GMS?6ASAOHqbliWnsE8ZZrcyNE){mZoY`>OD<z04BE285JsPF$ zWC&(*@>d|37pgpfDk8!3KR;*eB9HLT?zm3{c+>0eZK(!NBn|Li+1-BOw6)#A4PgL9 z<&rmaMo#Z0FL2fsX*#)AZYDCw|1#zp_7%*+P9Bi39w-mh61o}p<lbnfLcneWk3Yil zPRTizn>xkH$$lBme{5SH>U7+2XQT`{w5pcsKNy*$#<-!DMX3@N@MY}l&lkL!tC2F< zQ^}srGVVOhdl&0`ZOU@r>{?)oC~&V8(=bM_gXED(g_ZnOeX0JL)i}wMFb?D2E|B-F z)VSEJ?81Y7wfST{wNKzCp#%j6YbYb?{M{?RY|;K!P*lTj0pq@yJnO1rfz?pw;G*5% zWA*7abZrrQK?mPu#cBtROGQo;m?jm(A(58a@t}H8ya!a=9?{G-^9o9}=H_nlLc;_Z zut9fhAH3j6V6aHMw8eB(r`qr%cmj3}Pn$sQEV(L&uEw%0rk<p=8hwHlVtg58{X*`r zAF)M?IX2ck)o6)w4td}<^<$7!Q5w83j2Pc1LxU8j<Q{Uxiphh&3-3x^)TWMNFTc$s zu`X4NyLVICh1;gCHMXRhE+X$+Vh2=VMW_=`5ybl|;xckU=y8@M?zFmYg-4u*Xecvy zfAjV#fb`J|-axH3h0Q=BLw#gWrms00p!&UQ<^3IO6vpSNy!NRnY>|4UN+jH^DKB<g zJ;Qc2?x;V~JAsEQ@Xl1!XDdCO@+BeZWc+QG4S#?7`*vSnVMFB70Y?s~VUYb5O8wzc z{*gp|TMD$p#MyWN28f^eG*DcTdGiW%P_rpP@$!a1M)2KVmxl{qA|Njxjr(}8s$G@Z z3g+nD(TH$bc^-NA#xY8c3jw<A^kzGHzk}Bm&zjsTacq8Zp02wL&=xJ9&}_>1W%0QB z@pqqb#*g%{r~7Eq_FdcjMAv0aB1eVlL7cSGMhTX#!Ef(OENXks*&}DgUyBOIZ9`@> zsFR!Rj@Wc%BSOT5vz8Kw%Z5=G5#$wl`;PlYXqS8GwdH=pXmz<U9!2jKWpqkfk^;DU zRT!Z_jclKf-&LZD?l(^5X`EH}E1xNk?vZ=46$f_X)+)%;APJ4QuUx=oB$ey+676}x zc;<~O3Kq10WFl315@?)Y_xvsnD+M{x-X=TF0Z{jjc~WCzPQG+1P0yjJu7{7OXcO&% zR!v^+oB8jDI#xn@df+$2tV7^;+eMI;>IY+E(-!E%2%E-f-!?}GtMlevwFeFL9srdb z8OLTJdXGUge#oof*D60?qe>C_n&-3gV*Am~WpUhTpa^qSv~S7!^uvg;5!GiGjzBer z1!%K@#nTE0$m)z2p2kwNd-cJ5hrkNvzMR^6!d<i8^1#wZRw@PjC>16R@8^k8?(Pqr zux*S6mSyOtx3Y{i;wz91Oy_jGqJ<PM^(ZoknaUT{MfA)DyYyq~sm+qp;w&|v;z;74 z`iNlJQP&wHX`Fs?s={;eJNkv@RIz7LF8cW&XU?F}|0t5B^~;UQ0c+Gk;~QL2Ju<6< zYYB81+x`rt-Bp^7BonzKE0TKEgGy+h>6GmIRQO=#P#Tv=niTnM_PftP_n<-mO{lvm z&59gt(Ms4jr>|J-+Bi4Je`aI(MVnuNfd4M(#*4BhLz;0+wJ|Dv?<(IVm^);3%Q4q9 zO*2q4UZ*Z#@ZMwQzTWqV!c7f&BdZ1vp2oC~3Z+}-MxNr>`eZno-q-VWDoh<bWWPth zKu+OcbS?4S58m&OJ}44|@L^&^2kSZr240G0k!BQ&-+%IYQhjhJE7|?GZ%d}(!=S|s z>s~8q&n-VhQ=D{>N7|HUPtcq8no|z?v8+nn@l>AU?n-b#_pCI+h}Sb$)R48q6ZaYB z6y(?~x_||vXg|J;UykzFbfS4#8}8p?*>rodJ&Zl3(Go6gE%nNi14D6E3M9hQeyuX+ z0LisnGIu0exvpf#jj#~e;&&tP)|a7X;qEc*MUcnHu_*IleT^)%;QSCHCELX?AKpO< z@m~jpU|oIk2g)ERPQjd0{0}I}Y)9*|kr}2s5wdKJkPM0Cul$MIEb5^bl-5-?SmPYq z54t_}20^h|ut3=+E_t}%5U=EB%)Is+xvwdi_#;%NIHF2)jj0LrE}uP5>u&iz?`%2G ze8K!TK|kts?X}`NfhO$V3YfU0^9$!rU{siV{bWltQ51V;Tb9r#zd*U9p*3#9Tbb;L z$2W2aZZsJF1rr&oP+S)NA@J2NKUPx*gy`8zV6*>%Zp;#T=Q5s<2|BSmHnEsLTE7`D zwbl4LY972H>IYzrOBYi&eExU9i0mqx!GlTzSL^ynIf>x9T2`#r(#}7;S&E=P1mGIH z3YJg1JNM{D3~md6-Qt{ei2e(y+OJwig~48Y)8|u#exLNcQ6zn7bn2rZ2_SK?;L{!; z{UCPj|Is>m#7=s@dZ`_>x-P3J6YgK6kV^3{UR8h+g1209omNHs-(Xd-8iGrvaHE`8 z_~@)}o-6D4q$=XSxWxns|9h9oliXe}^@>Quxl#2W$MOxvl0sKHQq2LEpu-DX<PjKQ zfE59#luNL3pbmK(!+)WH)W6!f{EJmv!<xJveTViN60r+OF$Ef{{NKhoux<~489QD8 zFaF1(<X_~>ViYj-`Rl`3rM1jC+3-ENV?g2-Ze#pUQG4zinSaecFc<%#lxfifz1ma@ zJE~%XZW|6w*Cp)x?^r#OJ_8m=7+f1bEY&)-(G>!JGl~gzIuVl7e+agxJf^WO-}<8@ zqc~(nD|Q&36V4<{(_aJz@e%%2+1}{}-@gL^@Xh}ZcGzmheS>iENa(f-E*ny0^x-1! z%dczeOhBCly}!Hj-)v$6U-(~;D9xOl9knTlZ?E^@IPl=4AJ%4Z>dOKU&(f<gMEKFi zl(2sn9rs@&V65?sz~`)y0zoH}y%EFPd=&COQ;y#U$nF1*tTynN5kiIU0N4qNE}JDc zivAvwqS4AFOcLj$n+;?Y)_P=n!(()5$71Dg7BK<9#QM)b1B~ncvluJ|sIQGZLzq`S zGMp)FjY?a-s3_0+(7xuiZv^{yU|ltUd-j9nJT4GGl|N@7e%)xV|3i?V+W9*JNERf0 zMWPiFJQ$XSWeJ}Ve^-7J&jUjUOoF!&fZ5B!XEK?8J#Z{3upF&iSS%QKC7vGmc~_=k zY1c@#l6tgN!jT~HMC@AJGiTuLd<c-f#{q`#;jer=C7A~vG5~nmJR^98QNlki2kv^t zi@8FZos78RNH@aFGF77&8Z?H>!f(8JVHgcx?F$T`AaJ^&)zS%2h?ha9BYy~FfMpui z1VHP#kpRozp=1{Yj%L@01CiJA7z@5$J3V|%Pi>ToWo3Y4(Fu5bG#GJr4p>yNu=5k0 zTh%uJI$GbrRSb62*Kd61ZfE$y)|_w*H*q-mUgAl4Co1h%?lFMXobOE#X4?aGNgo&E zTdPn1S+)N*`FZA)#F}!ESyIFMD2*(FQJKg}lfXype{1xn0>F3vFxv@m;wI)DE&3wD zOPtP~OW~{)!r4=gn%T*-Z@Iv_&A-6Lfn5k*_n774iUwfLty%XRQbOuXFjr#d5^9K7 z82`u4hxf*fW?9bW7QVDfgpR02<oc8*v!?pqKN|c{23}O)1peDp;(J-ha9Pu9M%kzi zw?Nfs{ITKmD=gK`42HT)ZH1|6!-fo@uNHkw=d46V=Dj|}ho3wMj9ak)f8wt$CTUYS z(}^_H>(>TQmxV-@($ic@Xdn})?c~In(uvpi5Ry`Aty!q#rY`3aJ_Uzw0~G};xK(S3 zM%`4Tj|}AU#8#$$U8-wHB%LkAo*dG`xz641qpMb;;IMtCfeuvQ0bVO_Vvy`|1%-7| zz#PFO;$!iX19^~0BvB+(7U`NTGc6=H=apGWqZXmjR=(4ireM}k;I((;&T_m9|H+02 z3cI8uKzpwFP$f(uDnp1CBKZUzUyNXc)k4<w=rU|a-HI(uZ!oX5#>+wkDyv>Jy|asB zHqtDmD(pSR8^Hcrm(`PC%tP=%0u%H)%D8{&elR((Z2iADx4w>9XWXY0&twmjI>~Ho zZf-Sk7u3@%zk5tN@r)-v(3R7MxHl<ifB=))E2q?NV!;B%H$5rH@U145v*#>G_9@D9 z4xFm<Z_jC4Ml}yaqNE4NY*EwsTHd`+L~<KaSc^&ev~wC%2fJrxGBP}aCl!aBeMC>F z)+74?X_<BJoAhpN0!#)+vhoCBOYy~PO8Bn-b%<lq6rYA^oijUSpN}*9b+G7p;v&1x zQ@1VCpo|V1OafXI$YwQx_NNiB_pq-Nu_w)6T5D?N_T|({e?8*Q0hv1q%$b|4=ZMD# zRt(hlkqpusx{V%5S%1Mk4D<;=Ecwj{-ZLMzJbRO@;_0C4f1_Ts<U<d|$D6gy@J(e# z#t`lY6w#MYHofvfhH6D41zfenTROxg=36-Ihldan`O}{+ny|ws>jQT8)0Dc2ldKoT zgrjWWvgP{cwUKq<W?$Q@?@ab`_v?9>*5}vF0Tqa2>Rp+Q5q;--KNb()HpJcYLJCps zSUs%y`eB^=s8Hkm0ay5tK*`NzK3ZZ*YUn2xjw=qRD!O?8PC3L!w;5wDQH+2^(vpG0 z#o+fb1-#-T^8y0#MM!!(3bEJlmT;?w8}tQ!N1sw%JJE-cfVC;SkAW`S7es;a=(S>` zv|7O=bO-Zi>@v!p=@Of_B=I>T1sGdiQtu9Jlh@XDCw2AWCmhe-VtmjCaOAR?N+gsE zq3PHSU&s+ehxb>_1O5gYH%MY4IQAXl&Ask5lsqT-lpn%>-`!}T<9845M;??GaTQNb zQU#OyaxQzR%!in)7Z<5hE`rOYT93S^j5aT29DXh@MTjuThv$dt^&#BL4NJ{_y3}tP z-_ab)65*rKtKv*`X@;m!(Cdd*s&&&amfs#nADUq10XrQ9z)}EJ{T+Wt6Re3E66)0y zsP+)7Xjha^7Vp)yRHdcP34{qUzq2(`?BH>9+BhO=-+|XFN0rJ~&i7lBV)dteL3`Cr zKrYY*wbMQwE7Hf%-S0;0`gQ!#5Z=PMw$24_lOVA?zWv5mK^m8hXHZ;&-@*#jU=k5K zCtVVGNR4qiGm`;-%BI-%YIigv#BD``hEk2SH6l&fnZq9nTWC9rn+L?DLRuIiB#4;g zT9M_7nZ`Qb=rhLWA*ZWb2j-^syk*raMi1`(VCQ=H_FCqiC<}9GRC0N`K}xCn=i)n6 zhSY_+TwGRJg~K%TZ3Ah8ifXQx17}5Sy)3tUAuyf@)(BlQ>XIORhEn8aSoZz?Mz(t$ z4e!$!T#D{7rFb=~8O0H&pib<EBP+_TKz$T9Fnr(N6c#0-&iGX8^X$IRyRjcjG_y<l zb7ZK|WB1vT4#q}$lT0oW`oR(YFnT=mE{OEx!WZK%UZ^2;=*Jhpp}~<D=54{+|7(=r ztFGSGQxBm84G;J25J!zgt##frfi&s5WpqZ1)77L2Jh~Y%rv{BWSX84cZ$9Ge&8j^X zR+cs%VC!QYrb@McP|njuG-G@Oy5Fusiitd3)Pqi@$_)Nmnay<H9c|$}HG`YyZodwS z@AWKZMqonu`h#qW<wQIy2c`NA4OMs=_8C)VT)Vw|z7-)CCvzOH%&}bQx|o%K3Ktj! zu#cJx#aJ)2nzB9SGC*zR7k`xpiVOG?+66jtxt-QuCvxR`{ZU2k^?95{5=0hx-WLb! zU4-p}U~c@|`hA<*u_q<f`|ES~LFRgf@CAr{+#;iJCCQi(Uji$MF1H%w5bB3=J&VV@ zE7jUZyMyojs!{X^`n<y;jY@qxRm~NDpeRsO_^Ot$Md#j}Q`XYQ+~E(Uz3-oCzlAd> z2t#dw0+o>fXFmonAIGL2@7pjl-L=XvRY8W8EsQp`F^_SLT3ccr;Iv7<TaVtie+VeK z>^A8;ESPJgAci5)Ddpl=u}wy?WqVy^-OadJ1@nTcCh(jf8QPz!+v@Jt&*kIyH9z-) zDTuTRou}g7Bp33|=0*05Dp%gV;%W6R`mMBktnYO>^LbwvDFhKc<HO|u3U7rL6c82H zAqESds+|sZ(*OP--~Dj8#H|mhArnDLJYsv};oA>P%#(;pt~ELQgAUB#y7VcS$hBr+ z$!XoZC0);EB%RO8jX#jl*)9D2Qf=Y~yR3IJ&}(R-0grc89kdwHD`N;yBv^(?CRE$s zdHudvrCGN`691!$W7Ev9gtH%%NO$NHn<ONEFy`RO+nLc+$nhvB*B6ZW+Ih$+Nwy8n z5lvVV%)B%An`?o+A&E_X!w3n<!!5BXe+}gi%wv7LbVr@O@V%);Q2MOdrp0uMn-*WD zvtClsJ|lN||7bb;L9k@kLiJs*1Zr5X<QS%jj-T8uJPS>YrYcqMV3G3IV5z04{aB&Q zY9iCH9&yI&Cp=LoHLn*>oaLo3C5;!F#?xBV{Q}$^?bqDyt!_h&@M37AY<o8+&ldvX zvE*%ssH9rshY$Eew-dF<gsuaRhwlM1w$^jYDLM1v-8UmvOllmn)%h_xZVC(RZG@2R z_<N0j36>Z;pU|hx?mUe~>w<&<hSxQ7W}rPdYFK4<|D;@${1Y<7rfK2?vw3AuC{P$> zS|uVY`H8u8kHYJL^F2k@gvThM?_}3~oYDU4kIXUCy%LL|Tw!}2^=IaGxntyUZqDfj zM^U<4n?<iJ;{+uNm0hC-riWJ<X^fMypAE~r8S~LJn`%!@ZQ9aRvpn)(TbHu!V_0w} z%+ZYLvvIQDO({dx%zBCawh^J!O|h2?VmLvU>YaJVNdeSKu@y6P`P=UXWrtun!1K1q zm6mds*2bp#L)S~8+L=^e4oShy7Y1utG;HG8UI?KZ%b2)!(+WtB<;0g96V}d#N#iSd zannzBjiLK=!jGH0g(Zn=i*x88?|C<%D{18~H-4E3<_T8b8kydqU45mq9MDfq$vf~Z zB~?G1Z*%+2d%V4lu^gav^37baRdW)HGu~r}Ye%g*GbDWAxS~0^S8z7ZVt)5)fR74O zCgWyMrU?zZF<MJEs<Nxyn!<g?X>cG{g}YVMD|Ii!d($Yjx+32(NP8PP#RNiBM}KVp z0(m|lkhfo`tnarI==74y(5&DkKiP7sI79uSi^b5Ru$iQ!UerL>C|@5cV9~$(77E^N z&ewc!@{R2=YElDCH6C^+$kWYMgi*Iqgh`t7N%YiP8n$xl`t4q3*!NZX>EQeL5zt+? zigp*dwm6EX({i$}rba!eC0Q&qXumuZ?&@G);pcg1m~f4W=z4XZ&=Q{x`mDMV!?-q= zj{K&M?>{<J${bjXj1)SoA7we<Hp~idXliNBQ7!mH+&!T}9c~d&)+y59kM3Lp?{yYK z7CmC=R{1q;pU>(5#@`Jnsy^3szMAPl-kqj&DisegBd<?s)U7SC0lbMz8s4`Z@s*|7 z4m34h<$9Ikk+Igi29AS{PRFjgLz=6*1%^3*?VK`vy4i{pX%W-QBoA$itTk!3qDWms z)sEDBEHNw{%9GQ4U2_l<!L``4)csBUXG`@;we6D(gLa=YHw<4Hrej?NGwp?TG@TR= zqCG-(y{u`dpTD<yN5JNNWqs0s&#j7$%GUdaq!G8np5F2_uA1+(vAzRU0gN|<kf3O5 zx^}$}W*4>=GpA}*9s+%%BliNH;m7gSep%}8cXd8-yb{Y~mID8D?PuuxK5A?@gO|tn z=ug#GK5@-9e^P^fVAz1_CC95<u9Pds+Bw;VNaSdK80dHkp&sR79^bEC_lOOan#J-V zI&V0OSVHB|9HU{uk~6-zCsQLX8EiJNuL~N?-2t!X)dWTa*Pc$PhX^BO-?|6-K(_C9 zQog9QHVL!UgQ9)HlA_NH`M+hAi`85Ar1QloFR86`?q*$9xn)A&36(t`7yl6Ko2bY@ z+WEg?Ci5eU-^Z0qRg<#MLZ3g_9V+1BSMsXdyV%j&?9-4KM;OPn8=~fW;DlJw_2za< z#L6SNU&eD8(8Oi!7XriP%9^$MqCGCgl9ctb>p9Zb51wqZ4iA{6N8SUy8+bao-P|^7 zZft3F*msxXv_dzi*j357egvp<oglQxndAMO(0jsCiIFAQ0u!^Ysow`fC1GUy-vsBn z1%2tGS&gAKCS2L)YIZJ&+PC79ZLv#IWlJnhS$d!5Y$Gzr1;@xD;rkb;^fRX!s4-HL zv-{W-?cP+i{PSk3(EX2#+8p2dHoQgEZ5xE>qs6ULGA+x5!zygOF5+$*mnQU0h8Y(7 zX&Z9l<|_3LmKXae-F_b|GzNR6Y_v$c%yO{S??IGkS<E7cX;6N&v_-7t;k@<b)7`U4 zsZxfeM%A;sM(%|&DF`)g^_COKeHi-9Il{5q84Fr-bM0Pa(sj;Jeus!Tq;+oPUrcIf zeh-N0otp2KJ)@402xneDTISu*0GPO`3M8;D<v#=-u+SW#nQfxA_y&ZVzFEW}p7NUt z@-QMvgTznPE@E+)S&d#UF`Q5>$(}TNnEqC3hcm7T&u0xt<>p!1kn(Dq-)69P5K&V? zxx?XAVvP3}*hsZ{A3fiXJ@wXR&p>rzo{D!~tb=ek8thKiHe~r+urM?^p(Z*;cf;Q! zm2+v^{b1!xqxO=B##1FSV3bK&`;+}qwbIgD`LJ|9y3|P5kIAmIrSc`seVL@vp(G!t z%lxwiO!<{<@M^~DyE3fZd@zYg7oyx0IaNPS4p{7M2(yj-aQGD4TJcr1Ihy7{$9GoC zvVs;5AmoeC#pL}VP}1(P#>(LVz+yAb3xs;_3OnuxUtRu#@+bjXup9tygHKw~@X|O< z>x4#Y6a$p0jrgo|9t1hlFwf?K1G#~dekVVh9xw0y;6k9_SGT6w#?|7+zAF)|D&;@F zl8!iB0UaC5N&g`jJUPTTXuk)15+42IdDPQ_7{_Z@^IFq5O_szJzbfg%E#%|xtx(~E zL3mt7hlTdB5EcNTj#Ntby*)0D^#Pw>fH|1T0>CJwgJ=*wLOZe(<NrUueEP!`{I$6E zLfkcqt`9`^R#b$s;}OP=r6W@3N0sBhKRVQoIx8++87x^;j^J5tw`;x``U4sNpOzH= zt0Cre?4yJ}ic5xI20(+kjRKGyey9Im1E(U$b&-w-p5!hboV7?|F93Kvl<g0}P{Iq; z_+BTPmzjYZ-U}xmyw#!|gJ*m>b54f=I)@s`r346~c9=jQ7wprMi_NuCD|UGu463sf z()&;`m^4(Ty0PIcANLQ;<{ky0!4!by@+ebt?v^!%1el=E#SQrJRxzG50f4yVjq&%B zkzgEYE(HvA0P*=lko-FZlYb=+)txwDRvHijhYQu?$h&3ZOn$-c`no9xLaerA{XTTL z`m-0x?I50X-6m8_;!FK6yreBRthVVro(cN0WeNp^Q^Zqq{IyHR6jV-e@WmnzN=?p< zCJo2gLhOJtLym4tR%w6s(+e(kT!B?>SV7gdq}JAX!(s!-C`~bd?L`0ppPVfKZhcAk z_Xe4QgpXgxUFCj(nf-Fjow|!L9|?L9Mzy9=w>2i3ldEg|-#FbMIv4wH0OxPL;S3Dm ze^9O2Afq#QZ)4}erN&{3lsCN_{e5Qb82~E(e_?ehh=dFBB^<E)6~%wfix&TCTI4{w zWQ6eckZXKxX19CcDgUDq{5M?pd8TuN(F>>xeE1K>2=wW%X_0_Y?if$Vr?!vSeIoS= z3A2Cy9j8g)o$|lIXN30tJLg1GE#QC0qF&DQOUa_+t9bBi2Ep_{7T^DYDF3=)2)0iD za$GOBIqqrADfHvab7i0}_F)H>dg+Fj?%zPrXVRfPIRU_5fgZeOeMwm%^lyuR4!qHf zEW_C>CEOuKcGe(qklkDU{b#ZaKGA<~roS%ZGifK|-)<EiE@wWF9KVh!K&>FxDEJ!t zJsJKp8d&~+P4-(+zRxHj>^InV@R<vMIR5ofwbO6lxa7m{n_RgGLXM-^E#ulHpUE!& zx7KfCU4d?d0Ziy{0CY5KaoG_!Z<f<^5yNqu4^^>0?4PW^E|crcC;K-f>tGZa4%?6? z0`S!nLSWARg2+lwR#?sz+cnK~pPASY1@eU`E9!nfXMHQ<^1odH$r}LVKIr_t2-JU` zr?9jfcwhhR$*Km4^T$CsH>MYP_Z{d#r4_LMj4<`JCx>{2O~7m-4!bLp^w(<wzWNF9 z2ALZ`DG&GZ``54Ht>8Zt?m<i^UI~~pi@C4A_4|O$@xI69Rzv#ZTfR9&0IUt{vcF64 zhNJUp0HgRg7vGw&`Is>UprOCStmEZ@@BPk)J+xTy&5;65)_`69g8wj<e0<9VBa2r8 zoeg#t+8b4ec5VQ>{;SMO9U^0(`t&U@z^JC(#<%<-(6z99o$~+ycLm0AKKL)qtpvR0 zAPg=NfQ*kz%Kr26Gx<RWu=9i%j$cXVE+XeuamAHvnLVx5;iqv5G_A80Cs!WzqxP&6 z3cE+Ui+sK!p9~amcw1$*YYUdap4Hm8Xk*hBTy^mMUyG!7HGRq<>(8g~<9^V&T5aZ) zA#*jVv6_*I@`8#Y!)WElOCi$Nv?o2&Uh4B9U$Jn~Fv}W5dz<$^f_`-wl|5>z)2=hm z3Wy+ckPdpq_S*0zx9l^`MYX;~0ogWr0cS49JIZQm!9Bs#aB`^i%e7IUo^|CKNhL^Y z(pWvYhg<BdF-Cp59`!=Ttw1O4Y?42@+i2N6-XL0OYdLgFa~A(2N3<C|(9Jcwy6ANq zO<sJ)m${-WUFH5cX;*D>>sgv(Q_3A^W4x)|>!bFSy|4KoYFs7QtusEiiFBTYXkud; zP|M_7NyG#cV;o15n6(Wels&`+9Qt}Lk{9{<zxF@BuHp5Lts*&)XfFydxaaB;y0wA< z%H~Gyom{n*>KlrfF8x?FA8w^$T)zJD)2v&*Tgk{TcFO_Rr$i@0QzWc?6R0F{A8{@E zk4D8DS^`b<OABq)TXT{t96bIi8@Xz&E#$T*PlknmR!ESL#C2<B78BEy&Xk(nJu~1n zcFiypOxaQQFV*csGL+<VIi2I>(c`_K2(zaOV2sb&0Q%WjdH^FFqs|Q<ncD}6sCh7z z+^^iUMA~J#mbH^~NV5sXO*+At;p-kDg>9(fy_L0bDyKKG6s{$TTmzrjqtaBnfcknK z#Eo-24=AXk=?Qy;q{^CtAEbAuNh)we%<(Mt&zXjauCU*}(#bATd1y;?wfDMO|GW4) zjH;asZH*j$hW78uWvKTc=#0uCW8Q=E1>w`H)wc1-`_*~PzQ&<1JtP)L`zdAI<J1hX zp<V6rr2a%U&I(R5hS^2MU_U9v!eM{vZwpNvgt&uN;HF^3C|dK6$w{W&kOcs4I*J%A z`k@qDU8+l>mRR}A8tliYGMzZ*$$qWivCym%b#)r5!cXhtv7MB`v|U7@e$OTWx_?9m z!MFHbBq%%w)Y#g@!j`dhCsQfo0I}xEsNL8l_CtT4!e%jg=~XJjDm_klToLyf_!8ky zj4OZ+g>=xtx`o6;Up3CkX_mO$@lF<19pj+=uErR3r|YJ7z=OBKZuPJm`0*UZPK*zb zrAh!(e3>}a$WDa#7^0pVU#9MOw?Y#G82oxEN<=d5u-cyar*r?<>laO+nT7hGd(MJl z%u%2&>&Om;7L0~t8LnC#vVTBlI=#QpGx%!N&d0*c{GFRD+bF5W=5j&2+6Q7>^0idk zulz`pC__UY;}o;Vx-!Ilc4Sfln}1_<V!>9ig5jv3$L{kh#^}pu4iKmi;l%ef+lZ>N zev=^@?uh|q-Eg|-euHWa3gVX3J7enP#1&b*tvcoO(~%8lvVRB`ej{(;vkNd~0=ndN zUtF9^Od+ma3Ovo0<P!tITW1{c&Jvj|d8Q8xygZnm1kj}06&apf&R|}yYu~rP%Aoe~ zbtt-?b04^~#JsWO8?J=yN&ZdKd{bJDAO%Z8<A%7@9)6*Ryti*&Dj^-?J?>grDt+!M zRFUt|q)m5&oKr63XAct({fguL{7@-X@8{qRsp>AQf45P!UWC1j+}CXNXzz1BXicns zeO7%Om%Cl2ak@Tce1~EHsx;6tOO#=dFZu55qa8A%7rZ)?lEceO87F;w>^<#Yl6p~W zWpP?K4mHA6I{>AUm?}fDv?z(%O6y_qgix(gWTpLKLrfhlX5#0<Qr3RzltAf&Cq)8N z{ZrvAn&rE28axT4(-K!%KmHESJagK~1c5j$Hly38mz;~HjG98&W3-jFcjlACB%&BK zN@N`zZm}j}OXT(YK-9sv@#AOy@cY5sJB=S!;^Zq{HPF`wxC>R)eAUW;D&KnKV62^L zQlW?%n=BFJoDP0~)yCzW^oJrkyT`AaL97iLGy3<SiZzXBnrZd3$-$dF8gYe<@v4F$ zUklO&r+DI49&k^LURH-M^m;+*lue8U-JfaIWmVt&yr{-~G^4IAk{n%fk)g#)3(m*h zT0ievW=r$BWf3FLWAEik5kD}SFJrhntu;h#!QJU5&g)sup=A;^U#@wTvQ0-1neT!x zC7g9(a8-S4heS(Qc8rpZALP}>te@r`hk(M^3XkH2u5vY>?dM<YUq=fUfOxD_dp^S~ zFm3h-q3DdUmMcNi;F;H#bW4#Re3`kd>Sg+?;)pf*Rtko<l_O|~Ym{o}4Rcgd9gdL4 zV6x!;H%xG1{)0*d32TT=pJN7yG?&)GNhTtR|A4_c?Y_;m$|9p^jkj+thrXuLnHu}t zv~+lfmbhB;@1{Yye_Fee{gu?G67E-h$N7eOUAtipXG`-H|Jg2Ul2dU&`YUCQTu&0u ztlY^u^$R;69&LhB#ZvF-Vv@4N#aWlxlEviK_Mp?fgZ03wfIt>Lhb+;4tae&Y_b%iW zvl%4%r^(!zSdH&XGwsE)YDziLo|zB>AwzXP7v*BPl$uE`!(SLMAhdxpf7S-lxQH-K z7-HCi6nJ#)=0Q?0|C%u6mze0HcD_~9WSG1EGe^#R_ilgj-ju^*HXCeV>`O6CI)ul5 zo$I=Qs7lfinY`P}`HoRUK1?z-XnWbR?~$dY>Ur8%i)8*JbMs*yKUHw(9xMV*2bBbN zHx>}Ox2LByIGrXU*AB=I+4s#N2mFQOS7ki})!f<AoH=kqiksuY10z#%9`XU{`!QF6 z&Uz3R>ji}#g!OyBY@z-|&f)?~=hoodqBgZRiTx9nxU^j-fxT7QwuW{Sw~iOA0fnjE z7sE#%D~udt`}o1LILw%!_NQ`hsFs@5qjbL1f~kzm*o@eKmKGp^C?~-Ghk&YEI{v!U z8}~19&>o^N2-El?V!3pjx=c~epinutA?pHlyp`Tq$}nASR77)(=SHi%le_WR`I0jR zR=mqlpEjAz*3+t+_)w#CO{4Tsu>GT%&Yh&)N0ZMypY;kd8#)|EG*tHbr%kT(e!ZC{ zyvq@l_?C?gAYkR{JZ5XI;?hKKC&+Pmc2G{piGTimex#(3ce@46e|OpRXRJtoO$PV+ z&pV0!i0_7m{Fcv?TzA0qfK?_aN;2nKO<S|%oE1ymOckBUtN;sMNo<~2$$V*4GO6^Q zStE=7gDdqz)pweI2;O5VfvRvM_882QQ>W?Zl;kbFqM27GR=cr<h5P=}-`t8f;cDX) zXg}BaQO{-<{nGGM6(bXiAW}E+$m{^KLUo<o#-7o+@=?Q~%wn0@ve7x8^twpE5SdCF z<A`VxzYTrpRbpYWtI;7ZA$7CjxypIG10?@DB`>W%`$62}@9SG_9x)w)m=?4dU{S#p z`S@#7-8`(eofT@Izp^YJn;4W4;1H>$mlQ%9D0yXkIg!{#Kg(`XiCaQihq7bB*W6UP zP#8d}sh)JiapXt#XziJpU{zJ2NjZTe_stiZYRtdaI~QY+{hzKRG5Y3~Y{=EHbiEa3 zIz2Se*|FvB)N-%wd*xE;_!oNILx%=VwySM+3C`lD3Y35{B-695+aXG;@Q(7GL5X}q zBtp8BN54M6f(_DPWogu8RXq7xj;&XULxcH^Nui!pz-%EMZ%w|GHr&OiAXVLJo{Z-S zee`rOg`<p1=JV48W~|d3{vlMj4Fg7w6E;>CuW&Ss%;QDtrjXxm#-v_7&9ShNy?t}s z!DjpuV1CBA;uewiaKoBL&I|Q>ExkM8j&m>*+9=n@9x>{^`>?`QQjg<X$`5qoq}+k_ zf}Z*N31#M(YYYLO%T*ODFav-OG%1R?p}nz_bWdF1jp=NT#Jo_BQ=UWI7c#j@QXzlt zr{NYCx&_hEk7MKVd%(`%s9<hP)0HU3rynmIsNB(lK94et%TDp+e)e_Zy5QaGOUA_a zhoy<H*+!q&0h;M%f1c8a_-n(IQe%3lmA9=7%2Wb1+}%DWy(u^eOZa_A-mH~QDwFDL z<M2zrnEQ%B2l7TPIg2Vf?&&U{^h}*jQML5ZRZSsV1+K7jt<3svyQ!BCqB^9tAnnXY z-R#Pu<Et*mOgSqJB#*u12`l|^=v~n55BpsgbUK}#vmV>C;u;H8?o|%X?(XjFLhN5f zII=$;ji|9F4|3*x>0}u5Ssn-X$tgeb4@y$!dz#B{+*<A0#_>AvCzPCuMB1SEcBvX) z1ARZXR@Z9Jz?R0TT$wVKt=^U<Zx>X*jZI^wzz@PhV5baIzZL4i&f^#SG9X-X=gmI^ zyW)j&K@fV6bEh{#KhEo_FPM<9-y1;OS46G*%sn9ThU6u{nSo3@Ps1ub&f_HB67Sbr zU)%(|0dL_Ad*|K00I@CW624jJ=rf4{5KVb20HM@}jobsEt`?s}eLJw<J{$xu1F@fx z8v)HexQ+swWE~4SV+B6gRr+EaV_c6P0UxOa3&Va!dHf+LC66+(0Y`iTK#xMU=^@xE z5dK;LqTrp<tOjab^PHEV>(!@5@I&xP)$3LvW>^^@@(lpa^{FQ?>ICkb4Pc`?1tc>f zrZm-SofjlvoF{lhhe-dQaE*cr_JepGHwy&9;a;;pF`4+s#-M|0KzSSg`FinG=LV14 z9|G$;fb@|#<i8II4x9iRM83DMj^GCPJi#9VD9-8HKhB8zCkYofmtga)u!lx2jfp_0 zo#}CTuD!uKN<i}iQjJ%d4x$3U5}Nt>hse$g3e6K>Aan@*0O2sRN(gL&h6@J;;cmIw z)MA0t9+ZNA0}r~t_{^yZjELepHmiY4Ju`z>P%sA#TLbXdUj4Q4e?r|_K$J~92n@_N zP_oEumoFWqjSaU0VtgOq+6DZ8Z^NR&8#law*2r9+)M0gj-)2ns0{i9qm?;Qon^p{V zL1G4Iv4>#4p0q_HPX6nVVBK+2+}Sa}c6!s^k;6ntM^p6b25|Q0SMc+`*Altt9Xgzk z^`@Q<5e@ELC2T^%;|kd-FQi*jJB_GoZ;O|<eas^Hibf%#zB~r-WQ=eJ|1Ko(121KO zaW`KA<==kcmjPhm7aIlc+`^FhT3z*mrAup6`}7NEBsW2lNMhn#$sd9juGS}HnRrZ9 zWH+GawFbiRu?FrN(fIFkoxd0*acFY|M&C)djTpn1?qh3ThCEdV%$BP>20-X@BAgF+ z?5zZ>Ner-{1$b0Jlem_AV9J$2R|m~y+&A*ke1Z)(b$9p$86-J+E!HSa0E;GudE5;L z;M({!fVG20d*P8lZ9Yq80x#?Te8hVmxp&~3t+f9pi|nTPZTN%lgZq~9|1!fqll-q; zoOfxBi^FG&XQxhS@JEHkF>=JaX8ortTBt*8L?wVG<0IN+2#}pM;?<Xgqre(7NNW|W zBpdP3c*$EP#oq@ZU}^X{;}1jc2;savHk_`5_D4bZ5FOx~zJlKh@`*IH9w`2JctO~l z!J8*NodI}V&Wg9bY`H|(U&+Hf%sTfo0nbU{Z>Z`ps3Sxi95L;bey&@h%IP^FcU;5s znqh4Hbx!=R<MNN1y_ybeS43y#XpjD-@!OC<4a|NKW41fKM>iRNPj*Lu;ox#?a?iG* z$NXs?f^%!LM^=P?lr=k<_#*O*6$sTn?!bZd?06UfBEYI$iMa|P#v=fm907Mh8-RVl zv7f2r2>$8EY^|rdw&Z#z%FIH_WcHlD?!tKLD^BxDet4aX1&+U~{XVz;`C@#jz3*5f z%fkr6bYseX8>fAaHeL3EJ9MP1j!#vyPQ16Ti25o#DAC}sqtcI4(XllryHhFEdOpSU zK7FN}7Xsue3cf96-oH{_{UOL~SIv(oM|4u#N$qiP+q}FLm8Vx=@mq^r7)X>%g&WfA zN8F!HZ%DnZ?6>1Rh`o3E(Ve~ili-*4vQN8a@1I3H*tqWLb=p;>4?GVPV%0*8(dqpc z^(C;TR~c}fsd{=FHyLD~gWAJ@?Iclw+3r4;E>CFQJ$1bL)83&K&47WBVzk01q-!T3 zCSwYAcf1T!bqSc7!W)Bxt*xa)ro<A@=#j@^E*B0DltbjB%R0w`uWx<L(-!XHqTa~k z@GIB&q{a#7?QH94bzT6RTru~pbn-q;51}Wz9OCrPXrx^N-%PaQifCgmaA869-?AJ5 zXS<;S^H?^nH$FYH3Xh;9xa9irdk_#}7E61lL^aN~>?g*OU7O;QqINwTv7U1|C(YR; zQqLnw2?R2C!Uhi&7|=p{U8rM~)=Xtgx132bKi%SLA!=N!ZMMQTd(v&RN3FzCxrTkJ zi*q*G)L@wTyA3<3^+snXh!N1=nIpxwBe0rizY32A5M`!@22TSwd9r7Ra}%BZiVSU| zf6B1vx1Ps8+Gs6Q7-~-_LS#C-wcpPh=Lle2OICJEUcHF_-D`BYSLyR&pJTSd>z%-0 zXKnJUbE#xI=gl7n)giMuQ0@yBR+0W$zn$4q>UD|axThEXv0w5>TFkd%i${IaMsrt# zc`-i8=z+Tq7`b7#{%&zw4Z8OO)A@QDbb1lQ(`l@!;!je7QdPA)3nTlaY<TC~v$%|g z66!HYi#>?3yrNzBZQE}s_qc#k3roz<Fw!GJZ;DKneqWDny8gFosbKqBhim<$ctiU> zlh?3<E$de|IsYQamFY}_2BY!2Ig>OKC^p|Mij7Kz@>XS%5~JFNToW0iD24pIyYvs3 zdvzq}TKj!BApo*WK#za1S{mkzazzFyL&WPi&qKJu6Z=~;4<pzdy%Xd&v-%1WO$!s} zhl8U!oetl@>E~6OF~(>WQ#4ISAyd-MeyOvhC+h>I5A$kN3b=Sh)ib1M%R7;a+(b-% zvV+MgMKv!v1sAQUo!SRfNom2&26$WXXs8y__brG8KU)ue)(>b?In<l^TMLf%1Z0?I zYpD%M?KmP+QtV>@_j5FTwIgvu$wV>eRml^VIO(n@z8m9IK$OyyFA-A#u^Kn4ZEI<a z|3mP+a|+QOZ4x}mC@nn7?zH)MwZ$vq@nf6oxy0z|z4THH%(4YN-y>jch-!*FI5};Y z$BGkvJwM((ll<^QXv)WvBfcA<J0~#Yck|vBf+>Kf6W&0k&|_4St3LbcWotuA_?MQ( z=J#^m{of;$jegia_@KBJY88YebL|C64!hdgu2T@2{CdM#F(>@%>^%6NY@3Uapk_6b z7hHbC!v!goRax<}fR$Dyo+Ht;or2(aq@SKii#Xg7<S6Ls>~0pt1J&fhiu*3E?yRf? zbDVgOwj1=k5NUS5qva=G33Aoa0nk61+^_Ap!Z#4XAZeb8=hRt+F5)jXMPqR}cm}M_ z3|1r`>WcQ*53Eq}$^YIe(dmO^78e4IL~j}Q`paaFo~ejf7AOjwJ-yq1pXKoZjv@xD z?^OYr)@b;KcENlZ>RX@l{RT#|q!+lg`3Bgo*gEmAwIsQ9A&laBBOg^b4Uk#gLTD<? zuWv_JgLH7^(185k3bb=<(HbzW-X1N~S)Lb9f^U*G*+?V5yDgkOdAaWsb@mW-*m>tW zAQr^)0@)xkhiKUC>L{q5O@jKAz6NSTqWg!U7c0B}^y1K2-1Uks1npt1PUG2=&B()+ zI3`l`qw+gPMy2d2yro4g6<-iAK)8%m(^z?P)Hnk_i=?&-$fZPE%3bl~J!y1~DnY#K zp6_}o?A_g6F#pv+#N*ce`OCJga9&J{dPa=ync<g?R_|3=^m*U@YkBLn?Qk&=wX2Ak zd`BTgq;KTc39)i>jZ#6obj?pUb(ZN-&k1=r;x)ete7`bbTm;>LC?SmZfVf^jcA%3^ zPQC;J>ywzvu*zUf=oNas#bf1~*WnkxKxwAZoCGl#^k`)CRvUS|fIjR?h{MxOzx@Ab z`|fzE|MveQl@(et3KeCAtcq}`kR-B>t&)tBofUagp^RiTC`Sp|$sRe`B91M4?|ICF zbKd=4KKCb%`~KYb<M+?^zcb&jb-k|nysm5BuZ&KG-d(SCCUtply9e(N7ncWP(~ku@ zgs>hVg59B&uQDnQz6?HmeV3aCD$v6WZ(Ew~E2R(G*>E0v#h1P`rK&96WpQxzCyn$< znqcb5Hy>{_W*3zVhF7jEM)`zzUL9K)d0sZMWTlfF;90rh=st5g{C&P@O~mlK`0!7y zQTBx<N|AUa7DB`gKL&e&l@4o34JS9NA&bFDt;d1<ElIJ{$3MPHU<-*p#CWs*y{@Ka zVVZjmrauT8MER%ANFdoJR6dmVSvL|TVkY)Z4s<FXu~?>a5)=GZ_e)2m1^uQ*>8l!F zOASs?Pz~rZUb4qJT-7S0#Yi8{JRqbx(L9ZGP9FOF0dC&gT_KsT?e4zoj*Ie%g%~&J z(J_Y~3(rxDt5ukJRPdo**B6TwFx~v!cBvrJcwQmgQT(d6O)Zj7@A^51Sf9o42pax~ zvkH9ooNr-Id&m<)hCp?U6X3$75AMaDj{AJ{BKlr_sQ9JEuC6NEBbN|#ZuW|-)!oBK z9De?+!WWGNSTxs6nzbZd$}*IRB(=U476=%{NI6(voDs-obyU20y^H?)JJ!Hx<e|5> z&H3~4TA!wBL=Fd;ozgfPZnxAO7CtFi(2zLOm-!yWpW*m=N$DdYv#gh^aYp*`z|0ks ziPe?H?q7X+icMwqbf52ro>$jy41dgWkovek(F15I(FB8X<PqfkbQU95mBHM{JoC#w zOX?E^HnDgEh0G(&C);)x%Ue1=47NT|@WS@&VU4D}rlAg=7QrhYNb$041dhH^3<G3= zVRwa8GQ$H@&tJhi&BPT^bi7|tI-Hc8-|?p3K{xD2I$L`ALU;0^*V^x5QOW}PIPC|^ ztxi{otEHTju8yT?+!dn__)(F`s!je*F>_QJVnt15mzr+8I};Y#W)vnf1+z|7LQ5Bk z5&#@fF@S~D(r}g7%(<Xt+YVG|@6l$WW<QP4>nhok;hY5hV$K5>+-3IdQC6J~>UO)Y z#}sg!SC==0&Lhq^LzozeE9=|fiw0&|vx{GHaf<!1`PEk>%mQ|fv*{OGzEZ2bPOK&Y z4I3-Lp3T1z30IKwRY+FsxWN1>P~oV2v1_-Lh$6U3+jUyvCRU+jARX4#v1ZEMis*CI z?F{MbkUnC~g8d5;D(HE1a$Ae&j_r44EInIe1M|Cj?xm;lTN?j#@oupWU%@&4eru=B zaXmfV0q|rQR~+mI`C<vKMd$y*NOY#dN&#vcr+W|oMzq-8NT*D(Yb<|c%(2k%;1Ra` zp<bO~?1ssKhZ4dwJiigbTtpoFo?{t6B9@1c>+J9*RAF!))QaW-=Er}0*8aHBz+n)2 z3-t^CMubZDp~E0tB!(c0Bz|62Mw(&+)264AJ!FoD%7dh*zt#*oGr#Z@gBnl+b1(-Z zJ+x5z70g--JL~WCUjPT<*nj^=fgp0l4&NFPc<!~QDB*r+1&iK+Vi8wcez{?&8WiFm zbi%Fe1FgcH;RoB3V<el~DkH%>ofVijbMx)sc$k5jy(Sy{51$ns@t3qm{>08RgRP{> z{(&8<QzNo+!deekKq-0;-PUF1;%28gKgUZoAMUCJa<G+rFZqpl<D&_pHj)Hjj>ww; zOo^*Bpuk$%Q6e8ODKB7qZAsK^5&z$-EyVa?_AT3bg9;wSJhk|v6)=tWGDKsbH}NXc zwp{h-&HVhR4M*iDD|t(oGkyn3#KLkBiVg~HaXYi~;%;P3$DKkaWRA~ux4k-lrY!$j z1nc638vf;zO``!p(}~HQt35}de>OOo8eGQ|25kxNm1rk;X7-9!$}?Yd3^ZSm2-z}b zv!&@)XFZ>j&>vzL1h!3I3s>j1A*Et;s>bQZVh7Y00(UuFAkja_4jV$QQ3kKiVyheW zVE;17&Tg7ykPSe@EFJKJH`4h15mORT8!{@_U)7Y3oQjk?rx+A!Cl6oBpPQyf!`_)t z9}|x+a`>X{vMmUbo5~$St?bPPeIh!rbN;WYlv)MTZ|CP_gmAskHg`5YOc|=`%(NFc zMviv{udhO+-3`0{%VG~xbpA$c&qFVZ{cZ-A>g)7XtM`9FDZDOV|4iU8v}JO)`6F;& zTE(YSSgdVqO_jNx>s+~4qCs`M1-rGSQ(<k`VPPlWE@33r>BKO!Z#XIe4?!SuwddAU z!K2xPBxU!6F6o9mqfkXrhQpNW{?%z^rF{z&PvAYkN3ofpxMk+v+}ij;kg&&G7N!uZ zo1K$<JU1lnOd?;2fS1_XlQnGs3f#1IH@DWwZwOkW0s6A>5b%FkRqhzxjPQot`W6hl zBUcv!+@eu`9WFA$v9-aK88*iDb8bi=%(m7VyM4UQSpfVpP;0s5K333r@~mPb6C>|; z!I$>yoHaSvEoVY260ni#6UeCnXz56rzSl*Q?P;O(i!)o6^6x*`2#+-H`YL`u%y&2J z)y}8S!32C_OPj^r8rZx}ZW;bc+lM>@%Aj3VYm&HVKoCm1fA{LpTVo|N(B@Ye>GJ@y zwd)h><WLGZ_K^hQLj{0%XkXKcpigNC&@G9OKM)wy+X8ByF|JKxRvTid+L;F#*Y<%1 zGS{X(2*|OoP~W9|dS_M)D(}JbH>?*<IM5?*e#ES}2d@Fw)9R1d=~d1}aPjBD<k;1= zi@oWX_~_kkY(0G|!QHNkD%E0b9>M{KQ?U<1mOLSEd}|0$B0gEok?vC5_rT%w3!`3V zKPQl)hhSGEX~AMcriwTZZ45W;Z3nDiXmE&B0pBZ-8uK`kx_j}hx19PdEbC}4@$cDs zaq4-3Q-29KPFgYvt%Q35yYrBi1kP6kW?GD#yj4|ae0X>@hC#z0>X=22JplxAIykc% z!cl?wsUq~ry(>dm)MmlD-owu$E-&cbVxV{G_269WK+b)TWBfb|rqX1xKHOK`w6!|X zNek7Km}{TjL{YkA#4sHB=OH}3pb~M}LsOWnzUc-Jmd^I4vsryqgnGSY#=TPyOZ<(@ zAM8?L<hjv2J0m1)z8H`7nYH0w+%1-(6F5Uxij))YqjO~*XiM$q+(q=rZckZO!e-^p zx6b)z`R$J*ycMbdC@bpYZ+_VBwme|&94euu&3T-tL3#rkOd_9QGEenp@c0=1uuS@% zZXahf;p~!wauF%B->o>>xk3|@_uRBF|0u_~61!SoZLTS`!%&Gc)*8uaSTZQghK{@! zn{+wFpf};|uC9)(n~I0!=JlVwUHBead3}F{^E?Z5#q`1kRnUAaMMQg5RcEu01;5T` z(2AT_Gd%r<y8XyV^Lvx43k%6ri^lu|`!=4NKMUm7c<RQTs9f{OoF?x_rN@_#L)tk# z{4dLIr1IVL$Oz<e75-(lwm6vXFRk5g^5Tw#1Utu&a>2KJgU`>3q~7gUy={FsCxiNv z>$R);igah}&jekJRrzA$*DVcN^MXQI^PnFGkRMja`%MycqV$)q6)r?0Wjig}u42$$ zwV<I1%Pz6U6oXhmGX0-HH5_Zr5={2DRd1NO$Fk}2K;1byde3RYs~;a-5tFXw&d%2u z6t}p2i|`<n^$?{6&staM^$n`BZWRsPVN%dFji*iiuVw`=o=a&qIp|R{+pd~GWL+|; zUF3&P-8t)=$fCli|K5qyX+gPEG(pnwQk=y3*=t%OY|qbyh8unm25BCi4Pvg0C1S3i z6YtmXhaT%P({qyf?N`2>#Bp8!NQcUy^$AdmFy(*8$Y)9`cDV1Ttk@)UP#pP;;}pRb z>9ZvBaHU<TT^gMjQ22ve^MZj}z|}^D08yK}w5hCSq4sBDxK*i!HhtuKC`eg?(q_!h zm-=3;|3r0qnr3`^OwBZ;+VzD+3HOuY$7~Yx)HDb`HzT>B;-S`(Eu&dw!X~W^o&I{v zD&t(TxLpsGQ5pxg0Bf&U;mBHm$o)`d(#Q1Ydg3An)79uD^A+o^UF)uMZz>#fut8b& zoO1shABHRz#nHQ}P(~FQ^Xy7)N>+?aR%i#Ca<JRnIBV?#s<U4E(1XeJ+d2ZF-CyHB z{YE&RDN@7RR<N~sr=vNz8YN_mk^9T6ZzoL1UTpqUlz9-5D$Tp-6LR$F*|!~^?$bxP zv3j0tqIwF#Ieu+09YO4a2eP%R{9uPw^wFrwHn#Hi+EW2P7tZK3=+iL@)f`QfzlsQ{ znKgHNjO>rAj~hH%$KQ3iutnJH>(@}F%*;@fMU3USwZLaL4(C*K%dvKfHK5GqgDZ`X z6YNtgdN0nW#h-BsV$=>$Z<>wdcHC1g`uyah&|Rs1+81ugS5kBN<MF+xO{dJVzl2*B zYR6C1EUX%uA4y<V6;k{*W`4JMwf#(#R0feJ8ZsX|`|C_+QLJ&qHEq6Dmslys1l|Jv zKuJr@1isqH*r4-#9jXpGq)9j&y(qkrK`Mj~c_0ZxLm(;!%i;xlT60p9Ej6%yOO@GZ zK7~wy%8K}Bsz(iLR(`Ja<nZ+|L|>~lfKM{vQN$A<VGn3%_nNQ+$KjtHqy&JlG#~}f zL>o)bWj?|{5u+ZxC`_Sk?daH8Iu6H5=rSbu4AC1@^$NE(E$XyONG{WB%++2cZoK_u z$^Gc_t~8@JprXSC1cShW&Av)=L*eJiI*}^x6|BOGS@}*!<1JI0Z`7r}CH5^j%o_v} zcw{O~UBeg>FRvQc^FJ5`1z(u1)?JGVAE+M8d4F#0-QBn&P3y9Z1U{^nEQgizxm6P? zX@$Wc*&)S+Y*4_ueC3rdO;Pt~r`nhLS`7bb(PJV9RSxX-nDZV&63$f3(4<b}c(Tv0 zJ`ophN;x1~l|cCD9%MsJ{n*_h+1mbimIX1<i{@0}j73W_L&QQ~U~58=&j*cug~zDq z(Trl8J%G=0!fO&MEVIJ6#eGUS?~PF(4HFfA+|NRNop8oY@4H7u6NKZi)euBI(u$AB z%F=Sn*WyB#9vP1Bvb$L*(>(N=csOdMn6R8awO;kCn6GETxtFWR7eu6#8{$HF4_ahq z3|X>|suq5t-TmfD#Gq;j=NUJ1AKSTQBMo2-v<lzLFUSw8%g@hySrl6Rvtlc(mp`{9 zqikFSuOIAY_5GPN1hGyTpBCnPQB|jMNJkT`@U!b{p);z(=-ZLV_Yo#J>HLdrHmi>w zO-R<xg~##qYS=p0`}&(>sE8|S8{;>}fZ&!1gV&j=xz1ObEbIl{v}%b#4iT-c*{`g* z?w&cemSmT}^UaadJP!ca89|645@GhR9J_!<GD6ewuDQPvs=XZP{C@;=dlFF$k17q` z?;+kK%S6;}msW{+Pg%Ymoels2jDE*k+7@Tp+Rhefq_n>(R(ef}4oulsY##mn8S%^A z((LBI0-ki^AkTz^*B5G-#(Vf~&<JEjv<wJ#DO)lZ8s%EDETJIMla13*qYVKl0>1TS zpss=z1e7<-l0ortXdv?o0N=NA>LvhZcfTmmci|rukOY!=R0Tk_SvP=ASd9m6th-&M znDwBE)_$iMldSVEq&bKB*lLqq*(TSGM7zq^6eBFpC0nw8EAPA0l$sK$=r3ue)jKb? z=ioU?21jF&E!8K%?}qqsjM>_usCp*H`&asB-;Flw$G?mIYzEBDt-~VQyI+ehW;vHt z;PC`4dsXV^@^3xI;S(x<4&g9jecO6->e$jLK&GLXY^uY=q5b#nP#ZIfQ(XIJt-{F@ z4Eyq!$=rGPDf(Kb$JttjfP>dc3<M)gpR5L%ECO{c8fdwXXc3Qgm`4(gTSGY(i|Ite zr+rks8E9@sk9vvl{*w|m=Iu$sH6l|VNZ?#~S=h#KM@0`ECE)aX$%nX0z`=4uaAEp_ zM8cmHGQA#L(aU=I@{8jbU+KGOQ1QeHC~4cYCHv?8fqE)soD1x^>$&h_bVl0cGJ6${ zY|0-;`5$+jIZIW8P9YyjJ`t)uHw1qJhPu22&)=l2r5~7a4r7<hA9~9UVT0w1Vc_`Z zT@x)_+ITWy$hoBo7JiCmk6o>8-YE6rR1o`HdE_M<aF84uo-~@V50}(kaHX8}*JI`< zbvl2pLIb71m-$?x*R9_OZ_v3iUwDfkoTAwt1YCJ6X(&M7p>qN0+ORk1Fz#>lJND0b zlu>vr@hNb`r304qLBdq0Juo7n<&K3`-hRZjz{UJzu5G=0U)q!J*oEca2n0X?Cev+w zVNguFmoaN?=$^AF#JbT!(Qxzn_A;dZXv?Di4)~swzICNj;}f^!V#|Qrg))@H7Qx5t zCC7OunQWgNcHr5k00UoTQ!{nWGi3;mcrU3*zUaSoWu?E*M18kDxjAA~oNz`hzWd|V zPf;!i%9a_4iY<ko!UpKpvwsC~V-tn8U&rh!G(upe(KgV?%QXH%RZ3W{t#7$nea}yf zrlMNnU!4bU0{}rhQ2qa-^PmZ3=$TDQd=<Nfk}%={3}mPtTAxHlAZ+fgM~XgDJ*>W$ z^M&%cS8K?H|I&Q0GP8=fU^}6wo!mdSwh!t$4Tn>-4*&gUfbKr{z~CKb&77nF(B`gB zV7Xl6GH%^}a2%0%9|BD;)+e#`AGcq6T`c-DZ7{kWiW86L*%(`EcQ<6JB6=vpYw!b# zUmjAVSgeKZQ#S5mHi8N$Q|QUuY+itVyYw5uK=?RYNyB5NC7NYdon)AF@)Z~N$-sWv zA>NO1iXzr=`E^Qro|Lt{*Vh_it*=+*ewUgnc5SxZ8S9wS@Pkbzhmn}Ugyv~!Rb_<b zR{EC9wF_cDfr&VH0*BViuHT3}Y)wJUa1khDegZK1G&J!urRZki^r({E0jyu3k=!Mw z?667np%PB~(0P(G{5WSE@nc!SXDC$lTaFq&cY&!;*H{unsoZT>yVhtCW19eows~`+ z4~}GSJ1UR_eq2KkgD;K2dAW;Bt?CqElUA>v{g7g>SDR-X<)6{OGZVdLp>9q9$Y2G4 zjNP5K#HZE(d0zmD7`3S-rZKC6nFe7=E^4C!1u>L7EsbH579YJXuwvVCH!7oUM3K-? zktL`~Z~HNf6k?4degP%!70656BfttQek_aMlsoo106Q$nvjJceG5$YOg^vJX;h?q( z!qW0gQ6MP*rslT%3V3L(<K_=W1rh*;;)xm9moe}QfJ*rD92QwA?h5NLfC3eGpB7MM zGMS3)g(eJV5CC8DRWXHtT=@Q<Xp=vGKJ0N_ZH1`{S&CiXpLVX0lN^B3g3ww=5q&^y z{sH9D33c)}a$v_2W5Mzj5UjHC|5@sO=qk^~=`PHg3jmr_swF0MDiI%BW2btMFO$U) zfcS@{QQ(j#il1*TZEETz-h}8E530^T=B1R{Jn`5P?jZi_oNKPgb=o%YfRw+g*7K{a z6E;7n*c|kWw6n5`Ve}kmr_)B-u74lH@DMzJK6rPigx*<bq#NKkRE)q?O)~)%^O?fn zZ#ejAcFSKU@8_=!m*fG5!#El>^&f@r&4DvytMGj;pq#RCkg{<k8*s?*O?-~aVTzI- zP@$(A3p$6sS2C)|ejjU~SchgkMZq02<`4b4j~%NQ-dN$Ke45rQ2c9L7OLAaB{`puS ztZmljc&oYpQNJsw(xiNZ=V6LpjfOm3>Co7M$p*n<!)cBP12qDoN0{ItqOSp*pK8{Q z8hG}xph*Y)`IVAT*@J+v_LerkKaboTDGZ!7ehf)+;;hMr%K){=+CzOAy0XIeGV^@| zS;}b-UNN_ETZv(K;XfeT;|}uALV-J?OlfOaN(ewyCT#zzc0@Zm<x(=-t0vWZh*#_A z70fxw)zrB!9T4uF$?CK^6^(u|16WrT>8tI8(fL2K5V%-zK*93UTWeF@zMnS>M6!mW z2fZXdryZJU$1bi3lZfJv3RYq06v!F#^^yX>HnI#A3kwwUp~;5J(zD~ZMS+at^X@3r z%2DC9#Q>P(j~Lj_SV`-eK4-Ex#!T8cTpM-qN=`&m+u1Ak<*7v(cz0DWm2Qs^oNEkf zIt^o2=NqV8w%Od=*2nGUdm^Ib0^33ks^5K66^F1}Lb+@WDZ90Ua{I@j1u6jLN;{d_ z&Yo)6U6yR9KwtJT<r9DMOT@ai$<_lm$9Ww9a9-yC&Z`cJxVe3h4|-XB1yWC(&VPQ_ zq3%_P!^8DR#0YQN+}2ti`PRZ7Kn7#)c!_!(0DWo2pmy7F0h@d*bEaPJrB{J>G>=>j zoY_6Ru0wWWg(<?v03m+M-IyWz+#+r5ZjJ|s>Tp;<*{F|pC-+)Ldz;r;i+>(WGJP*p zZ3y62N8mdJN!56*o1K=%)+y*iZb|1A&%JY;FznkVkisP6li=9daT`z8{D(cai3lZ5 z7Z4C+Ol|(YhxNs<GdBmLsT^y|KX2zTohZNnjza6Rn4c&oZCh(WuCH&K+9b?;o}EA( z?{8;cnd)03f)>+kh}rRfrXAM5fq&?H|C*nbpE|E7-wYe^clkqyo427$0ZjB?jYc#` zTYH-?cxQ5yU1yNj24I43C8fzxic@sl{O7A@geU7ZlHKNN#bWcob#(Ip4TPpb-DK)a zHt1gy*D62~X9dD8qL~1?bb#_y?SJv?mhJBxVPTidV*iUuB7A<QOfSkyO5^3&1^)}B z?wxyqZ8d<3K#A4-&c1p3^Qm^ij8R!aedkB3O!T|Ap9)6Y#t@>Ex9GMGZ)o3XdB@<& z0g<<g<CV>U92a8f9|}C(CPhx0Z=fpK4`^;6h9R@OZ($d(x16A*6NXNft`7&@gYK}{ zoOV0#y!%D@lZEKY0u0%$*PJj}I1Fw=`qND|=#04y){D7-o%;nUun3xdiM~1$3n0tM z{0R9@HvqXr(QF+h8N-od@A<1U%BSrqIVYRl)dHow)Ye9MDSbW`V*iYJb8B6o_8U0R zKP^=9>hvck1vLhF)9z~Pz1h5nxNGTKgCS<g#0o#=5B;JO=ZE)qk2lmg(pHZ-8?_wt zH0^Gn;!<#dw$>55bss6-0vzKWWe`LFu3CBhUuotQ^(zmb+ILDmzmA9i7jf3cH6@+= z>g#eyZM?z);nsm>{KN1ha{K3&`m#uwtA)<ii=Ou%&AyFc@bsVE=FdvoMEh<hQj#fn zu(}C%UC(;|l}bB0a2Idq4d&y>N7RD>c;qF0RU>jqB29B^O!qQJoMTEEeL3#rS?lWQ zt4O|S3!qK?^Pqts-Z(6X2I~ao(FfXD{`fdF`pA3xGdhjQXBf025XWbv+c~$lc4h`S z)Fiw<immzddHW^kdGn`(3(C^a1T@DM1Ga<_@2>ZoXi{@>U;XxLbqd427s#Pm#`RI? z{ey@)kn1Q5l%6#6wT8Xy;D1Mp!PW-{1g|o$MUGFs1MRy#452*i&vqrbJ=@U6)N8eP zKccr9$;o6&?%3vd%pMm3gGq)~!GhB2^Kd{?Ra^CufI5KAjM)`i2p*~oO@%>R8d}?c zMan0jtv4cVr4N<?E?hf^zd!jK&_sh>e<Qj%Yk+xn7(hzXH=i^H7qTVl02649ev@yS zYJ<P!mYOW=4koR@PCrlv1Hx;&l;90W3MBpd^HN6QtB8<1h=f3iDc8El-yj6szxPeq zKs_c?x)R^|ZI^SAv+2vA=L}F|_NB8z)konj;RT5r6lzF#jS}iIgBA0yA^2B89CcXI z7RJMhpIhhXH+9E8(hxBS;k*fQzWf=g0@rgHSRYG=3<X{E{fMq=V06w+leM&gVsjyn z{w{%<2z(exCaVfkUbJNHfG*UbG|-J_3NFlDjG@f}&vfeDY3>73*$S{Cn0^xa;7h=z z-OfmQ)2?cW3j)&v09re66M_(THaiJn`%SQpOKMX_^p3rIHdc{W;OvG53O!jdK)x5i ziBA!O&^l^?;C~Frse<1KF1cf=n+Lh0Zs<^v2sqZQDx&=KDzJPm=kn}t#5zslB>B4- z1~#yRyZ&Wu@A+3S@yMob$)yhl{MJtLKrTw?r%ahFFoVI;{os4a>J&zPKG<PODk2>S z+euWl-yX1CLx4Tp1vp(0!eSHI{L>Yz(;jLE{IVf3BiXzXD20at;BQs%)7BuMwQrZ+ zG$fI|kz?Nj*22mm0mi-rwU+`q6g13slHK_p!SrFkWQ|dN2_jJ>%VtRnfVGax1_LEo z0^tnc?g&&XG|cP-;)+e6ifZ1&SqYQ1Js|j=g;}Rb<M0y3rCZJa#4C6VXg^a&^iu+3 z<!Jy|ZOjw+GN`oQM|@QKmtNQMfWien2nw1$W?W;OPkW-;v@~<6RG_QtN~qqU2QNBm z*@lz16PXd5^TFfTCHi1M?QF;a&PHhbDCZO`;oy%LmFSvE<sf!ghOykCr4Ew1yF8@@ zFbpRF1o}8wD5x!f0g~}go-;E<{!QEb<mp0N?#=?5&hwptBws0e!x8dCXf28lAdegl z072$ofHC1gNlp?o?41E)hfv^V2p>3Up{^kG^5fo+YKQmVIhMnKUwKnIm!~575p=MC zr!@7!1?Lx->KgX+5w2#ZuTvw3k)>(l=X3Sz0H8Ws`Fi7h!Ho6052SSjx09$5K=my} zegvm`4%tow0rIC1P$FXPL+OOp8eU2<&1P}ZMYUJ!m5p~IPyKWda$rDX$hTP_0U*k~ zZJ;U4GE>Elkulb3lZ%E*`*Q26XPLsit9e57mIZ@}p1`MQgj#E$0%q@jT`ny|b_Szy z?aR+bESgBA$@}+G?J8vJPeTq3s;%M{W9UrgLjW!v=+ux8=k`mDk6uzU7q2y^Pv7}g zl&O3wg7WIjyNu;T?AB?D7jP22XRuSxk{?j0ZSS;h<jit!@Mnn^ZzX-1)UTi$4vIc( zSKFcA{?){4YvXT{pMo|&FXgBCCHtuyoNPMF`^J@6<n6#A|Arl#%D5Y<3hZ0%TBq%b z*|E$zJX_k6!)mdgb44=_9)^#Lyuj-BlB>E15Z^6T0Qi2uS5Lr)q3zd9*ZdKk4Z=cB z$wTHzHRb`eo9ApAEt?JKgKUpeILXysM8b|Qlh)&-ZpT|L^!?IL(NxS=W|pKn4(Yd$ zE5C@*9TbfuC+|1~gheMhGP|x@XR)`CJCwiRrR45@e_%sy?YTtt1a{#7kS}Qy#0nQJ z@_kn#a;*!KC{0OFWg74lpb1a(lz4Mz5!@8sKpWYnb8Y2+IUeM8-mUTb;_uI`*9g>t zf%Q!3xpExJU#L1rbXi~*s5fmGI^t&vEEz@ZywxMib(a>ew&<6szAK~U6<}LpWtDj} znLy;$Zzt{MT;LqgAdvOrLjX~_Jt3VczYhV1S?=$RMWmmfZZ)4i%Wz>may0qhoEI+J zB(`&@EV5jb@-L1we$N$sb?`oX#+2PN{wtPzV_V5O`0ZTvw}FkqAe-fsWxaiP>e}6& zZ+AOZwX~fg>+*M)0!)^S0RD}qq?+8wXj+=EUE0w0xA@+1a*T_caTrZS#wx>hsLBW< z@|(|ZAZV*yP~_h>xEv{YN-N~*vBV1}Gp)$l1jaDr{<n1l(Yj3+KXacs#gx;_&ojoP z)%@jLkz?LLTsz(XN^@F~Qhe)fMnBRTD*d%Qo$KAmo4_y)az<vkPUe9jr!-ytwpjO1 zlN!2~?R$CEg{s?Qs&~Vm+BL}=63QL;Ul(n{LuR+sNSKjTBh9ehH36)89@R1TFrWf& zFGy`ix56E3eLILGyiDN%-JKUz+@g>HELA3n<UI^op=~y{lcSxNmT{8JeYg^t744yN zz%IDq>~Ztp#MEGd(vr#g-m3NAh@jiR9J}-tYR?Dk{8fSfzu)lAN{m^Y<=4K6w%Wsu zGaV<FS#L3pt6H^f=O$TDz9T<kplOo{)QH0rako>gUcYYWH0%|tI+GN7f^y%d{@|Jd zVX`?mJVX+GQlY64;6pP4HX_hASA|IrY{zc4YjgTM2zb^us2%pepEZNWvF;+gpTxYe z>5;*~*$4-+3L?qi1UP|IaxmFg`;BNz>8kSt_@VqqqPScBhqBKL-H^?qXufHfKs+r~ zm14451yqD!!gZ%$UF=*i{0+ea#OSbS-*O#V=v!33Qi%-R5K!+2gO7AyJHqD?!k#&E zMrk1l!y>!K)plSu7qo?zUNGn`Hx}W>i1rUr`6CvtO-M5WhXk-|+iwz+s)#4ng;!4j zPX&f#6_<1aW_pm*BuB^F4V(XTZ1R#~69@-eRi(Qe026@wv=Oj~7a3E`Bs}<g3>^&A zy{!r+Mtfh2xh6)_>+bsE^<#us6bTNC+B1LzY}2vd2z@U}sn&THqAzkL47%119*R_e zfjejMHzHNtO3EqSH}ytBya3JR-J~HK7IBJP1qaOhn<<VAsE?EM5IG>yCUXa%Y>?|q z6j%T=+SLsvfSeQvNKF=exS>~|Dztjr-!ywAjX`QTRhV#j$z)aqxZIHIEfhama*+59 zMqp8l86nA+t2CbzW)<Xk@JF$PP`*dt3k8H#<JQK{0aX$-a@;xuFR6kp=?n(gIuSIF zkGR{*>k~p_M_+KyT2O|6EWnWu50RgC44u>;>Fo5=*!78elMUv2R>z237gu-w1t!j& z<B>bi6Z^I|qp^9ZR_#D%T4JIAtM1F|*52OV2fZXC1yXiwsuKB95l^;V?NiaMLMEkO zPsN8Klu_<(7?FB=5`X&6p-b^NqI(xq+*hs5xxH3{rcbg0!beg>PaqOrFDyI+g{=@{ z<7t`X#LhYIH;(NF{vK%gGbK+6W`P;GT!DR)mXskOKxezJ3$nDdDm5xWy1MKGHjK78 zxDKW%4}o&&0WFVHCX-8Lps#OJUQ3SD%u4QqNbQxf!&M9i?Cb-ViM*6Y{HKrujEzt} za7P021WL;eihF+^zO?DR>p{LroBV1vUm0O`s8{Z*t&d8)3D@zvI;g)_y?NMj>_$vA z5ZPqNM{n4Bw{OaTG^CoA>TxRe>PJOohccd3aAi!$&zj-~d6sGtc6%$5Md!-(U%Yla z9fclQQy00qDs+QtmzUJT|8=|ex{?X!m2__tP}daiqVT!`7Rr0Wc%d}IKsoo6JLZOn z9)?+#ir_LZ_e@hQBihY+%<pG_2Szk7<jI;kRrrp+y8PtxZB@}K3@dF)eHD&)p|E)L z=g}9A!4q=q^#5ZU_VkhE!DcsDssVmrywqBGg+*iy5;h!Lqy3Ld-#%|b^ufS+oTCCL zaza71q*xP0tVywPi3i1~ac^Aq9m9<CQabpLkY9H41EF->A+)W3O}P}zG+CbC*e7;Z zwxXopJiSFHcn8%FPm&4kwAbXrpR=X6bl(4Mx!}jBobQ$HHP)M;YzL+O_UKsX-`Gy; zzp`=Bn(!fZ(>CD^;8;l4A1aj+qpvtMhFJ#0fEfNCmtj|L2(YvN<m@^!8*{ZhsC_Fw zWh-3k{nLK-`a6a_N;|kKLs~u~6L1GSv<2z3Cjq2s`!cizy$CTIq`T6Z&15Q`-<R>_ z!YL(AIbO=Q|C9Mp@67yVs-JuvO3*j^(&TlZz%6K$zRI2(lGnzPv)b0S?d0GD^4TRv z-sCuQklxUIny^4je?4a|N%TQDwxINO+`!-+x8wD{<q|V$W<DuhDN}C>f6iWR{_~=5 z6Ak?M^Ntfw20ZOBRK0g-9J9{W#zV%W;+vPF>O5y21YN%Edw=d%p7gFV%;&=t&lQ|7 z+t=>%4vr{ytTz}K7-*CAH8s!(+FnnLV5`y`^XO8?-NoaVx!o~b4uOI2NuZ^Y37h6l zsOpo+rvG30=JrduJr8Y5IXlWqK>7z`K#?h3kFv)|jE{-c#|Km|;)`m4Bf_^YdmoZ< zI&MDUxwxCnt=w=@q%O-|ZFr&%am%v_xo0WeXFVb(ZlDVK(mPCjS5oB5O!Qz;@weu3 z&TJ|#4+wh+kM%NEm5f@|Nb&l?xnW#2p_{mI(Lz?1vlByIWNqz2VLz&G^!{rpV|tU9 zIMNI{Fd4~Pc$EifW}p`z$<^?6N#gAgk`*m`uI;FHoB6)7k>`hR-+Z*kovJLjV^IY( z;1bHpY5f#Ay7H^y%z)h?>GvP=R2}=xR{bQXtZmDkbs}Ang#~Y6a}Mu^qh1%JMv3+y z5!4Q97b8w}m}B~*pAQ&(6KafaaiR)7V3>8v4zBu=&IUYUj{xH~1UBqGDc+A>=RFv~ zznD2^g%>3n+a*CowCx_twA;Qu{fO5?K&oRvpt}ud3gC}I1Q+<S4uA)P`j|%V9c9_( z;m<J7moElTuc6}UKpS}1r^k;jq?KB8tnjgM%kydCLR}z!MDoqeSl%b>@(*lCvZ$W% z<=}H|3OLnj1-9sr&t1BOwH5^TJN-U9Bgcni!zsqJv<p+|P+#-V7n5lY-aXFZ&)y9x zkn7jrO)d4C<UZR?tM_w0MEDnWL4?&{QVB8nF_}{lv6<n1Oa}{yDjBmrZ53w#^qOG_ zpjsIPX~pa+=%azE4<bPXyZw}r?NjV94JQcfj8op&bY7uBbdE$tvWMd{1U8e&|9;Jj zNS&jEQUMorf>Lj_t$JhIfTmLbHbsgbY>H@+8DJu|8~3r*?R-Wif!JZ-FtmQX#x}x> zNbWrfTs0%ujjA=aSkz`7%ZXZOHF#k&CIb9j48RM+aR_KlR6vJTwaf0Y;=~VtngsyV z-%cmD>C|FhLQcLWHQtCXgA<{i!;=Vs7SBU)oiSb862)LT%lB1Bt9@qvCr-Bp(F`SM z`Y%jQ7axOLR^YwOn9^vT#`ydfO*#g8slUu^Ts0Wu5DtA=E+usr2ksSG+s9lREhXtz z9rHVVjvXaa;g;?G`Wey^<JWiK^0=qW{LyT0s9WurS1t2~iAmgDg^lwQ98#281eGCo zbeG~wx0i<Rzka8gmHAAmxnhJ@OpKX`^!C5sdHJ?PS$PkgZz;yA9Pbj~gkeK7rl2+b zUIu+mI{W#X7t?exB?*&-+2eX+RnEv*&m5bx5TDl-R224oJ+fZ{^O(8#C`gtRKB%Yn z%a_#pGkx)@%<D7@N}sg9yn!I0A`hCb{1$byfFSV6Rch*L6LEv2(7cMWr7=W)mho}@ zzjBU_Ned42Xcy^O#?wK)Kd7Q9q^Ubk4m_Ve_pV(}D9rs>&|&+vxEnNnqwEwo&YN;f zN#y?0WCy*TQn^=c3f%Vj)bUgLH)7H8^=4Tf5^p_xcxZowV6Gt+JNbLso+Nh|Dc^Rw z&98RYhvT519am=z`eMbi`nIpTHGLiY5bO86xY9_n{p%<SqxDB6OEG&k{ol{XvoVsT z+KE1(;Nrk<#M`761Zszy)qeSxs{t%`7W$4|;*w+A^m;mS0IGcX&SZHOxpX?ks$(Zo z33zR(yrGdPm;!*{P)M>j>QwT;(Y;qG2pZmxS)RwP)1d^7)X3k-?IG`0giB?l-ISb+ zvA{h`FURf!sGDh-+{IcLgo5Q=OqOQ=Q~~W5L*G1fG(f}p)emYA3(6Qf2D&!cgKI2% z09bJMGJsS152h%F9!Iz#1dWv<H>O)A2C5~p*s^kkkKQ;Ru1?KVkFtz`s@b~Wd|Ct! zh#rn+7y@#;SmB|`bnd{wM~}<y)sdD5QhL~Ph=~)CzX-^AM<sl3@VU&CzM7=3(=RSu ztzMN-89e{|_Izr2G{wB(z52F}3`eQ+b3BknZ*&XA-0RhqNTa}lh^47xXDf}BS>}^2 zw!fW<rYB@?s9m;ooNpdjJpI~QU`;<K;ernjyJ*Zx`muKS0)cp7Kv2oZQoKV)B2P(O zw<;vhe8R-g!@U6(B8>Gb`9cG4B;<1Vtb8ZgrEY~v-Djay`cSWc@WA7_Rt!lWJy|V9 z(FM7Wj~8b8xTu_a?=(8i@rl9S7=^wApSQyutvX{p^2uIkupAhAD|9CQeL2|gst4Db z%M0$s2}b->U{lrqRsV8~;5|dY8*vg3<$h;V3vil&2GavlV<Tlw{mh6x-Zi>kH%H1& zN}Y;vAo$nCA#?xfLz)@$(_hL?&R%w%V!b_04~}F%)(ra$NmmWATI4!6ij;Qmre_5} zIR?P1&cN+`Ohwv*g|Ft@pP4l+jho-i%FX`1CjXs#Rbm30Nmbd^7woJbT!IO>BO@Q5 zX`WpWDv}>=C%?)rAH(=s_9*cX!Efkj@-taBi-T6pSG>9_b%kGj3v%k4uQAEyAszJl zjri_uJhH(;&^Mv<xP?#mF&zFS9G>t?q-w$+pU&dh)|Xw08LYcjcB9pa!j^t15y5u* z_;ClSc~Hi45B_qA$zhnj7R^|W1bA8V?8#R-j6yEnB@=ouVm=|DSQ3q$e?mZAww%=$ zJ9k3zxNw^5oGRf5-fyt40v#oW*I9Qn%Tzp)ER*|6>ky8GH9ZcxjidSH!9-w9gByCe za_H<`=mej=G!+r<p(KsQFuo(Y&C``*=_R~l2=#657heTl{XEH_wYoP0IY5;Kg1r;S zxeyamxT(`DxT?>KO|7zLSBL7z<9jov$C3{DX~Gk*(?T3V|J(f3gcKZ>WVtGqm9u_* zkIq>NuG>`U_qA(-pSQ0&Wmmii8L*ylqgj|0yi3J1vae70hLTlo;<xISl-t=shP5BB z1g89|c~d{@ZXY?Cl^n$`MfXj#rWc=j(yRRS{=D7=G2ibpyp&fxjJ_2w#<dUy9U56- zbInk{ku|qfs>S5<5Sw7r#EdQRluV&v>1}Q2$-qMSv4(eT284ui<_wwCbU&e?P@1!i z6$c}3>7MOY!`pX$S-wD2NHgs0Qj0Zo%W=rOiu-Y*&yMIF!;pmT5gK)$IGtCtmyjqX z)HMGxuM~4FK))cPWiYyvOG<(N>N)%m>pauBswq`#W*zmE&IjMcm^9QE<V%=N5*+o# zSdOZNTnowj(r=z1PEi9aSVl{LziEQ{PR7WJ<$0~`s-RX2KREUdr41$YOk_s6=lQ?9 z0kpKDSr8ND2Bt1(D2C_&3}SE$_TT~xqK<R^ogsj?JcU*}QlvoP7!!K=RNmH4`47<E zMIXK7aKO%#pFxhTt8EPHyZ~f)+}(D4kiQ3Un|$z(7!*W@U6I~TqrG=#*6xN|ns2@^ zGvI^Pz%-8BG}beL3SWUE5|jX#HxfB;0jL=mYM^3e>ON4Xx=jDowM4eVuJRDgFDA*| zPB^4KL_EHNStRk07Wl|fEM6cyxJ^LUqec2#4;gSGXQ(V0D@B&p+eo)v$6%QmY@h8g z?=HqIe%VMqdKrjhP)nS{o3ir{o}l#}wY?k`(uGL{PH}3P1Ypa97asnx{kSzc%=%#8 zPn5PC3pD?v6T&TFR;xcjjAbz=+D_(KvQfMYJj>t;XBTP}f$+}pix@yKhbe%m^<Njd zcga&Inp6?c@$q@^D_xQP^Q<H*+wJXThyse!A3O{BpqpLq)YjlIc#SC^h%&#*ToF!Q z-49)rE|F?mYiv97FF(N!IWaX5_2{-@@~P%nLq?I8yx)1=p(KrRfG6*GfbDuew#G{g z+TKp%xDDQM%FFn=o)&BIkZ(`8uA*pxa7OC45ESN36!2AkeMW6gG$_$<ATHMIyW7mm zO_<`JxbS#;u(E#5$PByxRk2TcRw`2h;Xa#~q&r@4e?2F`F2kU!@@}N!IFJ{SXio}4 z*~X13%Os*S!P$B#*#TBeNb06m_<mtTex_>5SSF2Vhp($BC0sUY>ohv8<YUwL@`%OP zIA70*<*J#BK->q(N)b>4`N(^!n(!&*`}9BA?hbG}brzlr`Q=!F@EF6NUoj(n@MM}0 zMX!%NK9T>`$3@jXp?mG4$fVpb?ZSqPsM;~9`kPJK(5aI?E=Ob_S#*2YAjrIoo98NX zSy%GU>QPh?$P2t@ZQN4-W$f|gM>4KyxiAf`pPo@$ZNJBDymgkNQfzhIu7X`j8|Mp$ zS{TA9N?aXRs0n?8=shi|(lXo!3TD-Eu4ZI1en>MPWSp)V>hoFPCp0S-Wd+qAgwBXt zFWs(q=u(dB+!!1SC{nX``9OGKBwBL%wj~<volP;slb?<vy@k)>Hk2&ba!b+!?5iFj ze+9nEwPxx5v3djQ)R3p@^^!Fppy!c;YJt%cvaGJos(K&kR=yYthf8*?Ev}(ZApbjV zLj!8$g^1KlvwdIs{L(zwhah&>d(d)$M>5TN@&!0zprC!mZNtQ1idko+Gbe^i#ZUKp z6He|1(%0)k@N@V8;r+bBO1m1tZ-8-n&Gw|IL2~W;Nd}ssUT}c(CV|D$Q?~s$nsGIm za=WNk``-;{dDpvgK1>Gfj&kv+!JIftN4&<0W!n7#zWY463pF1kC%k)$V@QETlBOF- zxNf~~h9bT5b8#zIUFfy5*RMI3$C5_5NxYP!>BopPc*e3v4?uCdbBi54DQKQ>AVFSG zO9bt>s2hwc=?&Ae5+3^-K(7y*9({M+!zTBSJ&XE`oGpgLOwOq9sU_`IJzDWfs>0{z z+!;2BgjyELkqv&zclf}&7^`e2Jo08nR(`X%32kV5h@bypo80An75T-+Z$+Y`vuzE; zax&Pn4kSM(B6mCPz3(~QnKsCH2f;I+W~)+|nenx-Sy0ec^^<yP5%c~FecaJ@jySdZ z>U$%J#sw{GD(_WFUklUq9$DN!{A84CH_#Uz1Xsot5q|8>#KoHsblfe4Q|t0jHs`W# zGvzNyO1$&X9uyd_(I?nUN(zp3ai1+OWO0kWwR^dzIU(-0QOTg76<o@<6c8+0l7r(~ zxN4~{zkY$Z2jS#$zQAZ{Jus}hH?hU$dZkn6-KQa|TI<lYCnot{+wSD&1lPadYg5ng zI!jlR#u98Ogk-z?(P}Ew`Tf~N8kz-;tJVq2gP(%S9=3!<Io_JoZZ&#yi|>vIZb<G} z`W7qZryN2@TvT{$U)3kk()+7>Vv$AYBmehz=GY5$Zq1~{<rsSG7C-tAo-04#{zy+T z@eeO5eKp3J%DKf@Q)Red`Ez~CvzTh_NCXIIZ|krM=W=;`F&jr%j%Yu%o3^{*X$t@# z4jckNp<n8|0&GeJgu(w1X&-%mNE>51Q4F^&aN$6_FgW5iTIROcu2wV+c#sxQ?x7{7 zRR5hri`q%E#B_l;$qdhXqIK8OZ-o02d1wi=M%~udgSXb+#(tQhLEf`h$TZ$i@q`wK z#REz17b3WgR-Wy>#DLOx0z4#l42cH)Ic6VnYeE{zAIb)@q*}zXQV|0zx7hoHms2}& zcqO8jjqGy(MM^~gOZ>kM`;F5-p_QA>wDY9kkA;A}lIq>&n?d?5rAzm}#**3w=AG&q z&kMM*9Ay8_ByA4FG!=+-VnDnZBucZ8MUpZ$h49u_nhDQlmaec}&zYS;{Hp(StAWZi z#uZl%Grzc+#eN5E7Ve2xpGQj#4!Y;}j*jZMvFBdQ_`%cm1!w_4E5PtUb03t5JV&6# z5n<92@2;G}1fxlqFF@r>z|ZLZPxhzn^Metn&yx>bX3!hl1|1T`sh@x8^~#-6$TdAf ztu}vlm@i#i>Jjdlji&LJf(^;t_v>BwjMtc!Ov*4_P*pMKd^sr6<u~x{V!3)(C6{s< z^OzYWrQPwzkH#spNr9lmQ~-u!xpt0{s5QUD_9|lKw0SXFFo{t$wIfppd$(oY_X%Ej z(51wPZS=y2*EhqasgDw9BaS~Dk|-x&S0?aJVNT2?f_Z<cK-uU3ZT8QbBVjV%5&JgU zaWE&o@3}0CYlO#5baK7Z`MmSHW_ikv;3RQ|4OC|M^8+pcFuQBcqFlSU!PA8?+tW7> z@SPlc%;+fqG_>2cKGDaUr8S-K2IbBgdX_mlH!_s%d^}1YhD3j-9a{<}@MX6YcsRon z1U>UaH8$_D5k<8$>I-QmgLA~gRFx(Nvo@nlAJT&2YtGd&#Rkn{dw9M8YakD<;o#53 z`&FfLxPENjEAXn1by>Zfam3gi6pY}zQ3yoQZ-k=BQz_}kZ3|bQ2JzKe-w}0PNk30| z4_O8o44h6#G$uf0^WERNX+!DqsS$UVx{MvuT^%-z+Gdv%Z9Xa%=DWS!^^Wfz4`(XE zC0dH`e2}qAX-L>_DcP2$%QEbzMte=>sn_?WGovr=YySluftg$nm2)yKVV=<A&$Y|v zG@n#E*K#!~o;F5EUV7g!EP=;NFAhcZc^Qj@RpvyVdX?a8{ZswXr!NQ06IteTL7^uP z&_$D(u&Pdo9dr-j&iy)6{p_70qXO%+h#cnwA_KvsAKK-ra+7eIs=UzJxml~{YfE)h zn8QGhm)mlBQ1KbpgBt_ba(cB==0>J-xo1vtKN|m06GA{q^s5EsdLr=F!2wGFde>LP zo-<v4cXpOBgQ<b&O!|C_Ffd359qc7Yo)P+(yAWr=jf<qZ<TxR>55K3UCt?L7@zi}( z>N*Wez2x04OqpbwG8g_x*k^YBMKyFqM$w`TxBvCzS1h|Z;J$15w)hKHQsH~MR6C^f zQi~W*?9uZ1e&-@SnqQ@G#(CvJ;6m40W0t~*78mr&)6iS);G}-~^Yk-a>R+3<ujCd5 zyNU%(>&S||kkXuy2tL@Q|Eseu9>>{f*VgoXD&L<NROlkF72Rv`@vJV>6?CJ+z^`}3 zBEfM6a7WAS0zb{SrgdMhrf}ivj<T2UTdhO5SPrHiv^q(Tgb&nx<*xRAi+@$JD79)@ z@2;bmoNRTy(ej+W_V=p^d(Ic@)nJbgrT?@ytgEW5MgKUSSJ-63{i;pJg4<H*_`8?C zrmk?ZJ?Oft$>}#Dd?@#2<?V&X1NDz?C?ISI*-qact{6E?DO<c%Jl*Me^Th@BZ&TH? ze<P97@UR4pxJy%Ksnd@~DKCnA@4s|Svm=O3I*tYW`VPI>l@JK<olL-zpqA+adOI*J zJa+P|quVi0-{@1hjarr(T^F<SHknii8Oxz`*lDZ)$@O#)2YbW;`^ZN@HiXBYbK_30 z*>gi{>LG5^7cCUt3O1l6whOSlz)wLT27)~B(~PYnLA8fHm~AXl3bl}C$@u-*@SjcZ z2V(mvnz2m)=S5S2A+CW4G017`CWj&kZ}C9B*9V0I!!KLyJKa5d`i3JWp~*{fQos=y z0oXM-7+w=6AKdH2{C09u+CzE?;^`{w{P1g^+}!uy8eScn*u-$yn*)y$c+q#s>pcJK zXV_sXN4Oup10o*V--Hn5_ZIsp`BDWXurLho7s1)aAsoYX#z3oaXpzJTN?L5n<T)4u zo-I&v;x0MxNV{HXKp=pM8Rr^!LiV<L!powerDR}P>H*6#91ALR&=&|W!iNHoYYVU8 zbpW&49@a~;<6rnA1HTd%4UD*PC8c9fJo%RHWhYO5svw_*uE`+-OIq<n!S|h@2Gpb? z&9Qr47wM@gi}~g&igF5$WJ(k{K3Y=j-)OtvtYR;qChgNxulHs+Oc%L5x7h7@QJ82q zNzg-;BIA)-dkvxzUhr~J9ewY$DShy88^{u3&B{<Uzxg#QKUdFGm!-}of70(U1$%|t z$BEU4J)N$>szn=OHhYB%LtcA1$W)?%<fMSRdnKESBp7{*xm{7$@wD<R3VCnO)+4^3 zp+1gzh?qs1a(2=UVrJ-_l3axc$9%1q*#*yhwe797%HZKJF!!y7wLGgbTs7LY2_NPK zt`=S$lB#IZMfBX}HyvuXWhx`|t&HGPLC|MxeymK5dcu>P`9L`O4cA%&2aP%cvC;n6 zRdbN)x$FVg7sC4|9)23qSPUxdxzZi#dLpwO)GU$0a(am4{mSMJb`#vo*-n*fTo%!W zcq3k#KTgP#0A>TGjNP#;vN!?nQsL~NYnjvOSV7sHs3yiOc8>8D^KzQ$bx>g}s#Ye@ z-nD8#A^L+oOV#^)x789VrfQ-osTfq1Q&Y61)3qp5YU+D#J#)+^1S(KV_!7hDLJBHU zW%h@8Jucx5=@yKQo)2+Ubo(zFp<r6GbX_Z#BV7F}fu*b+l&l6ky91Zf=vEv_3CozL z4p!*{bByv1wy_GYXB-aX9?b~CY8sn-cD=Evj*VQKJE<w2GIA+e)KQMZXHboKsxPOi zs)x3ek*>=!wENkNnSVoQ^1)EtiJ`Bf#bt!9`P}cG67$g!^KW6E&hc}RQbHR{5$BbC zXrsKPZ<)jE>A>JHM?QNET*K}DHbo}4Kj>MZ!t~enfBSKJI8pMBNO!-dc0ExZAN)*O zVd%Zepsl|Uabj7(SMczaf%C__#C}ouBQ~n~t4il637X&8f=hQ3g00i_tu9?Ywx`+S zTCFdFvKm*noE{*{MG(G8a36Z4QnLO@!7QV|qEe~XkeDL#tb~YW9>7(halXCcU-0q4 z<^rmwLIX#Yy`}=0WXsup5ym#I8+hEuYk3M4%s>8R7+~gad(!Z^^VmMezGI$;5kN*7 zni!yu^mSy+MjNrUQGfka657F4?{4Z0(GFWzJrl3R$M;y`oFko<eBDlZJZDoVjlk{3 z=RF)uE5S=-8{O2$-8j%4wI}DXGBv-?9U3fqeJk>LqLA%!ZG3LtD-}qJH724*-TTC| z{rQx?yb0>NBcoFX-J@<McT9+KJFh<zDt7Jt`GtS+1z|VrbP9Zj*3FucvX*tNE4Nw+ zm797+yZelZi~I(*rIi9Lks_jRS)su@7u3dmNBPc&tLyeCWUg?k&|sU;0Wn)!Zii<D zS@$jr?R|JGl$Y|G36pCWDzdlQ6>S>e&2nbL?bnqU^Fm3%=*o<Ar=S~p*5Y-@Yk3{J z@mVLj1clnW>MtNgszwZ3ej|>irlnb@&t|<Hj&4#Ex!M%`mbIhW7J9R&fT{c@RdM3% z_`$b=^~W904(u*fXDn7kvLQO~cc!Ffrh88mG)10tFz@tKcMSCY<v`U|6aufUx4VL( zKu;qPjrza_OYshA-<Q($Oxirvv8v?!br-tvwXs=X-F(a?*R7SdSuCaPRbY(#$xivw zUU8&TBS=UE<($i5AR6)*6$pp#V4mj%w(}kZ)V4So)8TdQ;!|N8Ry1v=-q^hmRqT76 z+vIhYHx;)ns(|PslbeYAooOm5EW(<l2LRz4et7#y*202--~jeZ)*Ru+86fIvOg6^V z_l|6*OeX9QGH>ma0$b=bhe>aUz2+BlA0c}-Q!2a3IX5u;K(rLM1g-vv`3oIzLJv6w zegQHq6&zPq=m(BSz5n^x%zk7~;H}4QIOJ>#W}9Wl(ASXLLz?9Bn!8|FmOF6#i(F&T zke>tfQBRw`YaomFf2_O~>;!q{iopBe(p<K?0f|4H19PhC%xE1hEe1EmlMjNpum8`n zd3(=I(0W}J=|Ni4Rwj%3p3SJT6pk9IW`aNmE~%Cj?Dp%JUF5~3CIq7XkK)+&(d=Mq zt=J7<Ft?k_?NI{y3kSdnwx5O-KamxNYM`P55ibg(87$Gg3TO%1B`9}W@KZcUt_FGM zvYR1f0RS|A*@`1MOK7A{0dzhaP{PtGlfb{Wg3VK*+sP~sC=xcaMI?rT3Gfp*?>9nI zHzJqpO*lelJKX#Qy_L)&$Ii5w@n9?pMmtZ+F&RdOr=^qC{0K*AlclZPBo9L)rayzk zZ9jE@5(MV`)Du8ir}Ok@vl$8V01<=)p*NqHU7Jf;|5tGfP2kV|tEwS_seB5vzzSd# zX*0yBoHQQ8%>!*Gx!8`$F>MyepDN-5?$bYI0q+qsVL5xKsBis1DnCNt?PgpNJSvTI zLnJLSA9ED=z!f>yf!i{Z4N<Wf#RM@)&#`e#TLIfx(N+b%U0*$bhIZT@gzwwe*xFJs ztl)pgpmrx%(MwVv5RWjy6ut~#*8r8!pz179<x2im9HGVbn)n2ipa)lK>5yg%`8&B| z5?~MimAsNiJJ&o5;^TtglVgei$bP~-eVqV}T4n2z$5uhc3nLwXzAzG)K~;|6oi*(m zHW%?`XZTd-uV^$6Gs!)eM3c<sMLRA{2WnHA%rlZA^ViAVcuCQ2LJ6eNV6jgDh{*>m z2ej*(^!T?A5CWG=u?rkefC9Bnsq=_Dz>1jO%*anq0vjYW1%LarxgmDT-B#EII&fy` zmPnASB!h51i$2mQ7xGm(LXH8kwB8Jg#DE~iI}FGtVdIUV+^}he-F~bw;?p4QX7i$! zQw7f(&ICp5yJ7LsO8^ubG6Jj#Fk&%~5kU4DWRgX)|9oitE+-d}X~V-SD!JZ@n<-RV z8{-*9R)VZAxC?}~q8&Uh6VW{XZ$}Ev*6RdE3oI0AepYz@wh1sD@4qp<{_`dKGr+So z<q=Ha?DG7!$5t+rP8T_|2e3~+|M_SZaAgH>zQNL7@gGnh`?tHx|9qbON&a!j*V|LB zmOReR<J$J&W*xh{7jP4c{TuK7KVQl}t3T8aXLV^XotwDaKXt{?QtgEyITMyVUkc2@ zSdH|Z9lmXrcx&LN6AmY2k6#1E?My4x8y25|=ZgLa{M!jEBW%G;R|X^}ms|vf?y-$q zic&+E8$dp1ynnlF{^xW4C+d6U;VfW|w_o*g^SvzLSeF-K?m7!Q&)I9O$7N>Ti|K(c ztBRsx*wR=g1r(nA4vgjPf464>4>x)O+>LV)iRsFaQqd=N^?6@)l88>VM;%|0f6le? zZ>snIeChve|Ik&00V&o*mjlPrtbJ8a-jQLj*;kc*U2aRDgVcVwE0NvHs$2EYG}q?V zZKgFUywe{fq+i--zfliZ-z}-13EYSTN;pFA|5dsFod039mEC;PzNMmf&Mgg?<TQES z44`xGBjP^;iMgmjvUt_)m}pNX<))9DnjBua*=El|1Tsp<A_X!q`21#_UA1UspC5xP z`;SXFA~5FL@?|lxuY_aWUWj>eYa|sn)lCU>5I_n6^fY`+_fAyWY}q9byERp&$P^Xd zTU(DcX++8?w|=dj@lLlRG~(NYKQd3|-2{5_+`l8hk-vEp|E2%YKw>UxFtssT?*4h! z^Jkx#-hTS|a(+zJwdL@X3yKq%C8pl-b4|1PH%CK5nfc{cpt(no3`1frYS7KtRdY>h zPI$4^RG%lB&lk#H+rA%rW?u2`YjpMO$lQxECKHXC9FBP?gVOVCL{Q^OdnK>eMm4Zc zS7*LZ-zyTpgcQ<nM+5Vr%)6ya@5IKREtXyoshSqxd5-f}h&^&XW<;1D_OG{6Z1ytO zbgPXicPBOXdD;V=!gL-U9`0}!aD7z&BMbTP-QKg4M8g!8*t1)zZ>!C=ho>}P*dQmu zD<5wBJ1#7}e)gH$+fP4VR$KTQXu?XQ+=0Y&WeEJp^Kx|rcXmSPw16Y~nI)8gMvLPz zdi$b?)6268@0~jp%ABJ3e5&%Vi@;GD9HAk2FKgQOu;OU9J}HlxAsZx4vQ%9+M+5+H J$xZ$Ln*g*?bwL0C literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/PicturesSOFA/90kPa.png b/examples/python3/tutorial/formation/chiba/PicturesSOFA/90kPa.png new file mode 100644 index 0000000000000000000000000000000000000000..ae55dbb937e67f145b15034f2d25731fd63ae894 GIT binary patch literal 138796 zcmdqJcU)6h*FSoY-bF;DMg;{yM3F8M#6d(vR0O1}s5CLsq<auW6a|#3DAJ@!v(Q^; z0*Xi{QbUz4p@)={yP0|4XTr=gbMNoo|1N&yb9O@Z-fQi(zN_xge$a-Xt*1}worD+| z7@*7GA4KbePC#40kbz<2_m+(xCdQ55%uGy-Of1YSEWiI}WoKhyWoKn!VdG?D=h*lG zPh6ZFTpNRpN&fig7G_39W)4;s*5Ci+|L7O33gTniV#3J7$gl_6!pFeK$3UxtP!Pnx z{QLG8p#S+{*uu!f%)$z`!3qALU@O=@BO}-}GuScsYk%-Q#KgzEZTI2hEd1xMu<mi$ zu5j;p5}SnfhiZWfZ3M|9S6u_yId%x{6cXOMPfB{fjG~gVimICWiQjZi>Yma&ZFJGt z#PpJxx$U*<H|*>k9NpYK?s$56``mvJ^f36*<B*8RsOXs37cb+IQ{JYgrDtTm`}irp zps=X8q_n2C?sI)Z<Cm}P9i3g>xF0>e!y}_(<3A@Rr=}McmzGyn*NE$+4Z0X0#y`jc zzyBcYFLdz%y0&bb0qX``3|l<Ge?~qg=G})`wjDpudc}o*kHS5+?b^?iK2)<y9JxRc zxa!)*u|raEc<;gnX}?qU|BSG}|5ud#hp<2C>V>!%8NlH&@<C{b!dOOw!b{+p6j(j% zE!}ef$DAVXI->=Q+ihueCyteJF9$pGERi$nybk1gSDpqvYl3k~*`=KeFy)~IQj&AM zmBC8t9t|4(4wI(Q(QY2?UMNIkf(GTLte;~U-+o?e=Ur8>mOf0H#5bC%SV@JUN89m8 zsmh{2b1Q>+B@dXhf%*|MWoDc;G{4RT_w7TX7`obYwlf&kp%$4-z*KOjsi0N*BlH-j z8x69gK^eIR12|$D5cC!BW)@{y=FjIz#<JuPX(*Rt6w#EVL4Gtyecmas80_FN8jt=S zAf&VX9II0j4QdqcLyAL+j1|%AjD0YU&twwH)&ER`7DZsvPwdyy-m!8U8nn9ztl&h+ zU{nZ^PUMNLMlFo0Q12jtg){trK2Ji~@}e}Tp`wU9M+v&sEf@xm4)#%35$yoAuhPi@ zO65Xerj4yztcOfzMHB2OK`m4l%um^OiCZ$go*-JD=wG})W#%p{2vP!m!TqRj=U6v3 z%G8UYJaDE#Go|ohtFGIn^do3HIFj2(;2g|asB*jtshb9Qb=X6>eL8@lIz`mmHsh8C zcY5V1fpXZHKpG?i6>N|$F@j&`(L+Yy$vvN(^gm-4MI)(oG^kbQ1~^D`AUq}_PxVBT z*mAFy!c2fm$~L55@G_s4h$2|-GI54#Ttsf6%EsqDX|S2j!4ASxmUECm-Vk=36HUF1 z{$`@%M3hIgTL7`VOWPSbH_q`y9e!~OI06rNdAFs<9nF1UhXM`cEE<%=F`5BoF6XUt z0Ew%CC$$sl2LVUp0QWeCQ1b~no-0-0{LG=#;FY8P63B67{K~I{M&r1gw{YXWKBS^! zo#T@hv#Yo)n0y)k+XhJ<D~(=x$cYYrej0RqJ45^i{pW`g)|vHakPRz%&HP99??lQN zl89&$NB3t);NECniPH*9jVYR8Y_M^~P17K<9OTvssK4nYg=l|-aX=zlV@gBDDPY>& zX6TuI8Z@bIr2`2hjD)X4{Tr*DFmKJKLEGU*meI)sl5i_43arf>ibAxzu`7!Sq^-Fl z#s2i80M)EeS)+&%J&6vx>vnrDY1i?+so0<JgH%M_@(Z4?g@f+IBrHq`Qr&FEFPvlL zrG{t0tp_I%iVD&6{9EfDbBAYrR@OS(9|dT*o)U;6ZS^q;y3$Kztbe22J<l5Cr{dwa zCvq*6$=jIpCW;}Gnw1KOINOKNpgdyRrV(y$j=gzHuo7!~!JLAx{)?6t?z-!j?y|f) z$FiE0G-JKDJDegBr_-JEqF(beqyB3Ta$>hLF4*t*^`jQn_NLEI1#^qWe9zWQ3|X81 z(P!4WtM%6M;}Bg~vR>zgXt`|$Yj4)wR?=Fq2Ub9<RC2*Ua%)s+9RD*54X&`_L|zu8 zp$j`H2z2GH2u0SdCcE@{{)g$CaxY&Cn0>D~ss6Nk-0gQfDMrt{MBEulHtqc{l<?|6 z?r&sd-&xee*>c9{?yY0>J|9M$x&+g))scuoG!LTtZGJkXB=VrhC=(i#Xw^a`VhB0B z+!mHoy|KL>oSuQ`1K|qSrAwB-<R*Wl0NB}OM1!nMNv+H+b5`<5;2r!L6|N7bdoK2o zW_;f*fAiOJ$z0CCkr>@Gk}ju&UQE0fbBd)WQpN@#V51|R3Z%&C(_glbDW_O*_Grdf z<k@)RYs@c`E<-IwpYKGA;VC})K*L_G3q#>#Q}CD=Uj!zwSxDJ5$`ucRexVE8u_X3B z7{5Y;gvZj_J#=3VDE0+%Zet575h59%o(BLkI*49lT}<SWrKdlIevms70wtvaL7Qr| zu(GZdeY}%bG$QD_<^%rEhMUd+w>NKto(ZH(I8#fkVKp}vDB4jB8NrTPu05K&Rlt2d z_om$2H+w>uo+VwE<nb0Y(ebF<2DDZZo-bNT<Z+^3_HTQrBYfKT(m~Sv)ss683R!AD zPBon4cA!CyQ}8l>Aq~RLAWA`_;Y8#<0szP8QWQf!O#fc=$Va79R}2n4iFo??a|ym^ zm#ylQ<v7MmgzDTv&Z62gO8x8VKQ)dxyQDkr8$Ew-Zgla{lGKGKufr6a;7weAXRQFJ zQK1&vj5$Rm@{DeNv$tzJ^=I_4ocR6=U#GX|Zol`kL<}0k?KUk}0dUd;uZ1rvGVrcy z=FlLmvIH^#KdehXu=>26q5jfTT$IZDX61PG<kQ*TTHiyAU!(-OHgQ35?gXMC1&kLj z5RSNEd&Xj<s~w1#6gX`dN3q{DatclkkkflRog<+z70a|kb<YkO#DUqgY(9EAmfCjq zFY=k2ex~w6K}TXyNyS68ZF^0_^t7(4P9E0~#$LK(!$ZN0I-9Q=au9F)THh02{$+Rg zxY3)J8g{(_N}Ggo(_l==U&N$UeyqKqLfy&YMVMru*Vm5;N$)xtDl+Yb=O23%VR-C| zd;+A4l}+Xj-iFZb!p+45q{88dh1F!N%kS{>jZJeXge0=6)}7B*zSkwCOw#kGUG$UN z*1P8?d0_QMYN7|8*QruLPf;l4MeQw#k~b33c3*y}4_&?ypmBs=0&?a#HGHl=sm(l9 z_^UnUVtnDYLu%D?7RKL*ctraU4Z`tKU$nBU(M!25{lN0rc7`@!g!VnJDzzi&opc_- zPxQS8Lf6_YPtRX-gqggC{tYQ;ZQTU!Cb19YCOSM=iaW3PdVSOREi(7>cU_@lGilig zz^7;wg>fFp$pCqJ8CRqqDAl%UiQOsjbnt!K>~!5@dwa2nM2OZm{2>j7FC!%hv;G#y zJx}!7Ft#S0&_D@xMu6BQ#?9I@25-VBXY`rQL~Nk<@_O60>vo=x0us0CNr`gIzT?(M zju)X;e$gNjdm_^&q58Xs9i_*|5|(zQt979Yqj?kphVZTnpWcr;4UM2btYApYz@*|I z0vX&q`X!ynq3%HqElgmp_`H0$@!7jljYNT6u542GjW!Y8=w!1fSPE=gFmfa79IMM_ zfKnR~Ia)?Fx5yGP+xIwdE@JzEbPk4UQIG6*vl?;$*>|FcY)E{GJT~-#@HZf;CzL;* ziu0}Bkc^HU>_?d-FLMp84k5-Vn^x;)4W&V2Qi4?9a4LJ2aKI)WeAKwalL1hxCt*s{ z%%29?t*=h({C*@Xcrn+fly?gaYQj+%Y0!;CE|~75!s(vNLZlhv2<7}!rT6<C&lQy4 z*p@V56#y{FmjKHQY&s9e;81vMYr+ZvOX4(@`wKK1E6rqCQ1?0Mi@f+5T{9Q5pYh0* zd#a3)Rr^Y0S_yfS;6xG{3Fu__cb<&q52&0k>U91k_5P)VUUdB6o-F~#B_mV?IyYmJ zBX*H<<9Hm<%lwwdAkRNtn~Qf67H0m(%VDrN;l~hrB64`3)cz;>@U<&m{CThNN=wad zSV9ajtEP0W|BVQ4{(%0MrB`M>D*i57C@rKD&%S~cpDK*Q2PxK-lzr@%3T4|?ez%tR zVai5f(9GHaCvOKkNh;LeUicbhW>~D0d1ZmK!RJPXM;2;_Bj3Q0Ti%uJbsyHgOf2MG zC(4gj939R5M1$ChKJzj;^agcqeVNk5v|Ds;_D4O;814wwQD5g*Xmg8PTwp7Bri)28 z_^2JsR3z$yQy+iXq;kPKFDK{b%~@xYuix8MlXQANoD7f_e<AP_Ep(ZHt8IGZr~8&D zYZ$k<sx9pF%uM3)k>}zr2|myw6+OK6WW|67v(0R>UFkKW!s$AB@kDXMVM{>}KmFn* z{e<IvZsaY5kMI=O9(?JMBV%#8%$!ZGjRk-F-ZQlD5?YjTH3I}*F?Q>%EMnU)lY|fX zb3?c2yq#RPs-Y)Oo`w(o?)q$@_iDORuM^AplV9_$J7T*7)YPS`mleSbP}wkko!bIf zSt|D(kLY9vVS(VM%l3IOIz?~l_or1$9c+vIuEwZ3Wknz;3M%8&<2&2TsyXIuKK**- zGwf0%>Cxf?jlVmJB`(JzB`S+boz_Ga)e{9_**Ew!8wPHf%02IhoH3flb8kH^S8nRe zpL1W?OhNK?&<n2DVaGxtuT%k?Bh0(};?@ekUFO%q7@lO^2)x2#;t=#h;|(!G2@~ux zr5vfh@1wPS*Pv>5A49au7fHfdpUbVRhppzY6yF8}C}=exh0f_=-3U=WJAuegcq7)V ze`nn6hnjo!20fnn&P(%Q0LP5qUVsXx03=~1EMs_+a?5J8Lbqvzk76dYgfD`?z|9&k zI(!m66TYJK*y64V6aEB<h!4P-*=JBEw3z?nT{y9_wsx=GySJ@>4CbIg=FntDatQQw zA(nCvJNJ<WNm!<O+&#=R+0VOv6WfT}e}B>*${G{_&cryD+^{a3a(~is?O`?2S2Rl8 z@Dh5?gPrq$SXLZ_95@irv>Mzl7{G%_^Z^Z80kJI5u6?{oiCaRz+3y6T9G!%_<jKkL z22ZFLXi(|?PRO(k%ec37jOcQ$R91KKm*DZk&z0}`k$+aY=H5Z?Bo@__HV+eUkMeH% zeR<_oP<)NM#ZMSo%j?Y=-d8dDNKQk4SZ@Ep+?#C?zf>PBnW;bJ9cj?;$cy`xb1*yI z$)d?K<f5wA*aeORZEhzAm`}qy#nJ9kho4!7u4{A2I9Xq8qM!dh5tmQdzL55OVct0M zIPv9>mGbK9S3Y&e$80D44(+_GzCr?qp_-bI-+Z#8Mi}?#bN0JuQwncyoeTKfC+b6x zeWi9lZzhg3$f<AP<ngJfFibW2_J=)CqR-XxPou(KZo>u3!h^v>IqDWot5-YvGd)6M zMYFwodDWUB@A$mhdBH(1AI$dZ<S(nzEY>EwT&5Yu!d)zX$88B->TLkep*}Z?7VeL* zVAGpYZDuZ8oGG(ra|Wt*mc@mLdr9o)&-neo(W|yvJM+(jV*~oafE}{Ix-A>dSaG`z zvM?R{u6u36x-*z*9svgm1SWTe66$1P_!O829`p==LkTU>oc~o+8+vQ(bX2=tk^5)^ z$s=c^v`;VX#F1+eTzQVD2sO^~rLe%Vl%Y%4Kb3Z2?83h9ynEf^b_d32oFP9(6m>)c zDDC(rBb}Q|uHxiW{n&M;MvW4)Z%c{ubULGy#7~yDI7H;+0nDC<bIJDk4Us?3{g(Yc zI8sPW%*PhQWrE42b2e4N$8rX9_NHYj{Fo}r;qxpSIL!E-q416G0#&B6gs`A^R6i#6 zl7b-={XqYgc9fog!lgIt{XB<%{0vZwoA3C=n|d2aVc9bI{*)HyMljBo12<aFAeE@~ zxEzy$#It!GKyT!EDb2=!fspByVaz&IO@n|TYz=iGf{*fY!i^lfL_y?%J)`zUM#i=t z=q>*fq@n?N&=qQ-smwI(av5#{zJF`nhxY*S1X{fW5o_!aimc=YW&l<-P_yefwS^iN zpw0nu2?`oO^LGJ#$qNFXF)wkP_5<Mr-3vE2RM_6j6gkoAj{-iqV@vh2Qp)hTlNBtw zcHkqz0qP_$kL>g&o93yWM+y7|&kX#ogvvk(*$;v+>z574f_+cPq<c=>Qf37u%sSnI z$DifOlo>E0THW}S#&az3ZxS*c4>YCs7^t0(*;;SGNB~E-Lt^-7dYFcthuo(oA$<dd zLmEBzroZtH2*5*_Iy|!%`glo4!FqG{Ppgsh?3hD7eu+z#Ds}SP6Lxy#&Y0^-+Q%<I z&lWS(x$Y$L+Tvh)c?O-~FTe89TP+ITUZFuc?_X@4+dXV5ww@#AG_+PF{{Ug{sFXx- zcXxG`pU9f7(qoB>-NrU5d8<d%<s*S%EP~lDe8l&$v&L^l=aj{Fg$1{U>G&I8A?qSv zZSoUpn`Nu9`Q}y*!fCIzz4d&TS9E*lfrwo<8N*I+on!IG2cU-%@FEoX3@gepTwiru ze00fkIRD^V9o4C*=og1t*3LRL!gla|WEU}SRIQwQ*f-;?afzk}u_fxcJd0t{>`~mu zL8RJ-u~OPzML2zSW+7LWoN?}BZ?l`|SHtU9i?6k03IOZPv_dFM8bWhZw2;=1d`{*! zo0&d5Uy_i#HaZmtwRLN5Lq6NEjN9<|om>zb%zXFmo@<uN!E-dIjAsj#ecvaF9eKZ> zEb;!(lW-K$Jb1u2@6&FF{HYuAueqXy7@mLV`4qQ4Q70U_nwM+s=o8hvw{Gp=($Uuu zb+3O`q^~mK3Vh|CEZLiURLigE=pWEYh?Nb@39k=0jJ=-FGgE~U^PrmQ5F;`Ep9~&o zI61kE3tT;=HZ+myzJ_JS4#kl?#!CI?>-sW&25Lvt_oj?r66Hg(x<S&mr|9(icB}*H zk<X16TdF<|Z&?<)3g>vwKZb{1nv&)pVG5EKQVbti4SYHDbZRWRzixD%+{zkyw{wu6 z`btCIGgWGKW#qAv^myp^<ZC4k%F1`G-xZG(Vz0nG6K9D%qXs987B0st8XRnWJSe0r z7+pF2Yc4>+DU$jYwsT78ng1MPEr1a?k$r6Lef0IBfW!-Dl}DwNmYd_F;Eye{&Y0xH z{drz-3f}~7SHBgqr9livfNE9w-o90zHiT>1=WgCm<k88}2Rg=SufFY<o>s9<5)E0% zPB5~$L}bUUMp7g5G*B7$4}MC_+!{k3e|B9Y!FZ(dd~s1+w`W1|)9mLZrWe$hL_u=0 z^z-|&%1=-GzX%y@ld{>To&DLi@tm%NYOb;3>Vm+1C)1+Rpk$>oJvR(j_~B==K}@VS zN7FC(m>R!3;h>q5zIUFKlv3B+#O3_-J$gTDh8SC}jbZ1l0+HCR9FMXN4_K{8_u&og z4;lTZ>~37Cnu^rg2G{I9_%!P%5wSm*>Ux=d_ZN}CXSdzTP{CqON6cOswdFeR?a(mJ zXyP8rmgGNmF(N#Fj75!A;Dh|b1Is@KduKkY7xm=k+Va(MJ=kLAiMjma3+nVkUPhvO zwt47Jto!>T={=**jwozX*>)#WG$9qT*UfWsIlV93w8Zq>miO@=p&`$V@y->Yo;auV z*Oi_-qFztr-Yw|vryTh3u$MEc`{jc$m96&~EMCx{9p^i`Gn$93IKE5Ir~2l6I{ieT z`~_FZO|gcKDJ{|OhMDxq@)fkOeM~7!{;IO8_v5Z>HpR8n$bQopOSqvfVLo9(iwk7e z84Fv#APt2R$fb~i$Z5y4U;voD7}AK$03@WDR)Q7;kts+s%*27L^Nei7MyUXgl;kZY za&2V8)iF%l4%`5+9)oW+={C&FHe`Yup5j;fNF05Mj8dH-eXggx+JmmgH=4{{@tQ!6 z&0+DFF=@uv8%tYMKM1uP0+G=U<Z3Ap70bN)=&^(F%oC6yH{Mu2)9YzuQvVnYf{?4Z zUGjWzBhLi2n(`TPi2|;gK^oZGNjy@Pz9cYkjTATRj$dc%1KyK6a<%Loq~LD=rU1*_ zdqs7E%Yl+(yNk&6ue6x&koKc{c7V9Fi5W4jGj&b|^Xvf?1o_28ZV@>ZqfUKp&3f-u zE^MUGO@9~bpdn5#gr}6)P#=4t_E_g$x%`X(h0<*bzjy~kT}%-+%6WqB1HZ${vAJiR zZ|yL7R{Wso^-<T9yjxB!el8=r3w9y$O0|+f`=Va_794%Hwl4%)g||^)!WnDf;@BEw zSJ5jIudbWfdzp@&9%E)UEFqaBJVtns?=TZZE{)i+nvW|$^E;Kkiw$eE)c?T4a6L@5 z=XTaJg|o-9#xPq4TGEM$HocWSm+i+wD|SN1DWCnVX;8lIY$*A>m;C8g*#5XjvXij; z@ojS_g17^AzI~Lf{MwF3no+`(=tgGrb0XYG&Gu7TKvQ;?#y?=uii_?@<_}Ym%<j9V z;TNpgkm{{F+eUDzLknpbO5HC%dOJ{c!mbRv>&3{U%eU5At_)WAUZmdB<ncRA82?^G zR`s(BHYy3yvoOoGeaYUy_U(nVVKK-=5T#Zh`ww9r;J3=Z{dm~PM9}E-ft#A{UP+BM z<QYW<Pcxzwd8^;<5^=$WUs&&Vj?V*%EN)%jr#%0B1GptkY{F^KwfTpG3Is_Sv<-cO z1_>NnR&H$3jF%j|p(P~qHsEWOTR|zVML2%EJ0+t9_CKPh*m0yu;&sebSG_zh8Wia3 zR9aE=nOnE^edFA9&(!=_KD%+Qr%4v#*u$t$=*r!%@TY{@@NiF`&qZ~QFd<V8B3g0> z%d>ZUpC!1h>0nw2ZU}p-^U*%T1?_QbWtnLY-J!4)s<DsYY|`5w4zN(=UVD=DjzPKK z8n#*oct>z7IU6DD_cCmzO$G6U(&h1`G`n8+rFuQ!Fq&zJE0He{EmrRkDhpC;$;XIs z2B+ICOq`F8l_=bdbg3FQ6}?)T@Z-d)Yx`YA;uF&a-cY~g*5xLf{c%EmpCo6GGu~0< zNRgrrTguM~lF<Wx3=3UFfxM5Cx+P2U^&*_SIJiFSI;h}1Qkj5rwx!0vwoiDWzUxZ! ze06u*-e0+|%6$Z`y7=zyo&b%R)dC_znxDXeSm?w9jkPwVqketm?dw5%ZOT(We0OCd zkxieCk>W^Azu6ES@_M#d?HlJRoe#eFfXVOYsaP3!==^K{yU~m8&&w|;Uf9o-&c$o1 zB?82nd@?O(;%g{x@Z3+GhuYy1a_<gl0UV#`Q~G-Fg$GrwploLDWVcEIzm<jd{NZQo zO*=91pTf2;8V-nebvwEA>gDzoOx3yApVNQ+zIJb1X+qTfT4@bF%fgrbZtzjZJEQ?Z zY1ct<2}yp1n-6#GeD=+Z#Mp4`=yD>v?t_DhW)k=X7JK;{QL~HJZ+?8KEgpQdxZl^W z_`8$*`2?eO`Q@cFV#2w&Zfen?xC?Kiqw0?{JlZu&`C!32>?Egvp6$bKcf{W)tuzkY zd2RQ}t7e|>Z(bV@m^|hvV#q}F(5cMy&a=!ml)TZd!Zo+!{NC!`x1zBUL?3=FVZIsC ztP$s<l_yEN>P64?Oof#!XQXy|uonsCrTMQ9lxn+0MkZwbEG4%D-BJEfy{p@*E<9M~ zKJlJc)r#C!u4B#THFvZ+oAfT;DA_aZWg_cvh=WCA9v!@M7KEn&(u!Hh6EoK7quj#y z<G8&YIoFr?^kikI4MNkwrDR;ppQW|XT?w<VfG;|LewGD3m*s$3WCt0lJa<GpyOkkw z+UePX4J9~@B!vXZ=H;IF3@?hm0wpfCM6T%#Y!7FOP|Q38j{}6Bl(hg8eAuXx?aD;Y z{PD_m2!L+YLeE|~S6?jBWU=y}dRu_n#stb5+fH>|1I8iN4O9o^JirVkznADt3`uKf z(l*?AEf&MfcjEh{$Sk98zJR~UvH35Rws^YQ8eXas$D0D++8l>e8qpwaf&O!>te!Lo z<qB~BB;p}<r@Qyg>(zy_DZ-KMOdo>uq)?~fRqL0)+3$nN1njVusM3E*;hFHq<rWeP zFd29dFmQ~oJR#3moptiH_;NKA#V+b9U@Ttcp2$-fGE9RC3T#O1{V@I~D7>KQ2T)g6 zpT41BRqvQ<#S1T_^L?RcL&7Vjwa@+rBd8ydLq!c3Hix?hsIUCouBX5MWc;Rk(P&TO zkFmy+W+>cKU(;`cB7vM#xm)r>dSeHxz9_KVwCn7yOput`Cgh$*mKD#zEb^~k4bXf` zjfZa>JG!dXi9rtdnG>^86T`lw?C6dV2*+6K50&{y3sfU5=mP6|DHOj2)5j}b<|tmT zgbSEMAIEBYtb)_jaZjgJRD`QpO<(2~E|c}};p7>mZ^T?Z#lA-=9k2Vcb{}{z7VvsS zHIerN#hc7CX|q)+Q{xIDa^zrKjNq>uWR1Gg-M7xxpBeMzv(Vf@$g64jkx=7_?89l8 zv1E<t7jxa#*}=%)!>4e{a`6(bCdT^k!krfnj~)GN9$oq-i+TAG@0cTJ!d53-#LHhR zWnU~;yboGErsyT|euA%rZ&xl@;Qah%Pxrj7Uf$&;tGCa%BI?%io@?%!77T9i`4UF5 z!uGn2ZhLL(ov9(_?d_p4<K`h5u&e5MlWl^}5A|Ddb)Ou%$KJfH0cR}6JBuNd%0EGi z<S*kUPNYr!W^JQX_xh00V!CDyC2I;50u#=03)a~1=iL>XMDxli`C1)WgKzm(B^ER8 zK3Q8e)m?e+VSD$FNQ~2V@0pK>j;xz_J{}EgGH@zW?G`!{AawOy&VAhTX2?I9P_#PN z;b%1JgyNh|;FWXF@?C#m=q>Q$DErj&_t)$O%i+~3BF13|^~6-A^hk;WshDhxjj4KY z_3ri2R^0a!m%5@JT3s09Ykk~Daaf$`oh2@<WEC|StQ~M6wX$Z+^!lk6jE9yl$!M4U z#(R5~$PrR<^LfWHwD5$I4HwZvi9hR-&Ca=B`yTvwBJxyn?{|?Hp>>xz%kNJzrUiZ8 zDzBM#=!?YXiAL-&**ST9#tOZ9C%y=?>bG-w(Uc;+MNM&T&*<6Lj(18QmH3~(8shM4 zk=VEPMYfR!spW9OJPw7RWLglG>dg=#q}ijWa*(;&><~X&y6By1lChbyv)!&{C;n%u zaywPi3@{kxvM<c#_Kn$-jR68TJ$6p|Pcjw?vxGYM+Fx+$Yx4ee>V}!{;jKmi>9Vg$ z;xhX+lzS_B2m7rCXCqE7^_r>V`(EQ<kgDYMS>z?2Qkp%4^p)4XE+*?!8akJnS#5Bq zqtyp`xLl8y+%n8FhgQm3c<otrVlP-}`&TvYIeCD5x)4%5<A%$~69qYgKYB#ctvoF* z_3rIH7+5rT{`L>FwNp;8LC2fzo*hGy8ImtdC6S8^b?2>G=pjOvexSuS2`{n&)Xd$J zgWH{LgEya!?CY~`5_Q-O5Mt}QW006k(Q0AVMqxCZOu>(8iG6mpmIrB}4Np`FF*YJw z7;n^c8>k3oAve7C{c$*TZ}T#{M$ikPeOlkVR}>k({_6&W-mn2`gs?M3%K`<K6CvY~ z2Bjf#>L+gH>@d50ltE47wTbCpHt?sXEz3{8d=AWBHtl-0G*Tqs-f4Ekzog~Nav~Rp zYzflTfu0n>fJ(g}MS9bK@ikqCOLjQ_37&*B{}jWZU6IY_D+SnoOgs&lz;43BUox?e zuw$%lAU%7v#Bk2p6bbZ1t*vA0b0$4;MLyZeI8WCmkqB`$$pbmn)4b-;x8$;f*@`2` zJ;3F)VYnuoeh{GAtb%AOgB<7p`bF;aJ8Os4t-S^ZOt#9tJ!2fRmuV{xn`*8;J&}n# zBmWNA4>2n_$U+(pBmOEa-?2H}BI4q;7p9c`_#PiSDkBJX=4)tB5Olk%&mOzTwsG{F zluQtz)4%K5TbKkpXSQIReHC5azTG4FfLUk~n$i*r5~!s?PL9}RejtO`W<(LDA28&3 zk@k4~9H8iLZ%KcgOm?&=lsxQG=5TBwjuZ=$yzg6TctZ!pJIb$<6^ToRA40R+uH~1$ ze5=QX@_y7LK?+nSnSMjWi;61SQ%Wj}!W?!MP5~jhZRpnQ<j|p?QWB}>=Gc&BAqJ9Q zcmU*J+jf|qK3(e5vsnv<Blyn-iaS0W_K$08G)SBv60W(P+!B<_xN1SoEJr6%tQSnu zN9;o@?~OFyFndutW^n`+{epLR*AU5N-daARMfrX8iUW6>P3f((i|F}m+>w#Y)DFzm z;Iq$j+LHUfF#KTuGQn5@`9B%8`Ef#T;o&E#$9MTDCp(M`%3&qvUkWojZC^{IdGemQ zXHmK%6aeRLf@V_IpjVoh#b@CMNB4wju-rg-7%QAk)QIpwj0y3vPs?r6>aTW`n`T-h zO~1#Vy1&Shm|%^&m3m~r$<+0z|3t+2WAtN1hSk_vfe}79*Q?=DH)hl<w_D9B^%?g! z{Yc!5jj&hvxe6NeAdq~0xtMJEqAs0WpYJE)?dgu&GW}CeJE-rc+D(s@9NRR9w_{V? zKnBO*ngDhDkNd+nQQIq3d!{w_#2rbq-(@}U>LrU<Co-ot6EiWHRvAD9Aqg{k+p_%Q z-q?GJ=wOq$inLgX-{Ky`7B30i7Gb<n^<CGxYcX57u&{@GEc^UKZevx;xY?Wir)CxB z^MBO8KYauG!Vz?pP2-xI7RsKohgy=~BJB06p_-HzAm{!<iJc2}3Yp!S7al8ddFYM$ zTHaP_79!m1r%EjI-SKR)_f9(U@|x{s?O-Wam&qQ~8Pk@mY{%*9*o!4h;%xE7REPGN z-mx*El~@0<C!j;ku%OGsOQQUxNw?UZ?-oUNGL`1Xg|17w0s}Z?+&oCMIsU{%I4JFH zn~tY1hWchzWoH<J^xj93cH>v_-KV-sa##@3l1WJK;-Z<YUvQWir!04RATMhoB`Xd2 z-a!zY-Fn$w{PczfX}iyfFX_>s$3baH0{x^i9nn}pZx8Vc@y*c_3F&v8F5qfQtqQZQ zIM`-bYekrSvMx83FPv&0j@rj(vC~rY^1{@`@q&W*`@qCJZ_U3P7xHVT^Uc&Z-P=P) zLI<Tnw?sLo|73F4TxRI6O|&nJOAUFPhjGq5Xrb`<%++JrjTy%+AFdy7L3z2Hs~wK% z#_X!BsHj++xQyGTw{JDHvUN|jE#>%G@4Q_=IPP2bHc^W_A3A^2Z0}DnYBA@*=0;0< zWPRkkB{3%#=<l<V$a|@x)t!GBKj&VV;G2?v_|uWu-K%qw`vy;*_2f<UnxO)_En(T+ zEx|D(czoyhGfQQ5(v8yb4#oDwcy)X_Wx<A!$Ri%|YqQgd-sFNpx1IwJ`xS<?W;iC( z?9!W-1Y<HSk7N7+$b8Fqyq`f!17baXZZoFzo9-ULuJal!8&a8!F?4`iYPF@emwf8s z^y;8ms&n7lXvV{}TNMnCNi#<LE94$2-{j{DG<&^s$nTpR>PU5RKlE__hMo&m%~w&f zj{F68-)nfR$=%JPK_9zS=uMJ^CckYaHHCbNnsTH04ct<s_WejlBIv|?^RN3*n`Z*9 z{(qu{OM}v3$Br79El+k2e5=;4N@CxsaqZ5~UE_PyoOd95e|8kKz^M>hSzXK!X<&f4 z8`{vzO1U=lo6M>dFE6X?8Y!qKjj(^MJUQ<A_4eDR_p8Uwu^0=0jL`L|gk|m`fZUwO zc9?#^&|nX$6FUk(_!I@!3i1@tKlkB7V2$_C#~`s?cXUq$$Y@8f?Yiw0g>-kplTt3A zHRlz@o-sck81GZq-}7e?DfEK?juFan&?fXMoHS*X>T(x|;j`ujs(T`bJ4kMMyx9uI zGJixhnPzwCM_SBueRCe|rYfLGihLg_0V%zm8=w74WtavnEVv*eH0X$x7$guo%DcWL zfi#WnE|8V42Ti%?l`c33a^3i#6=9z85aep`$ip)AQH`TucUkZn2+VT72XKVVBgggv zV`xAL)jJPrAq{V_D_^kB6M1+*@n%a|A52^e2g$jtz}!_la%_|a-G*f#f6z26YJ%OE zD1kKVm}-FoB{C%t4_bv@Ox#k6XNMcNq1XD>aeJ*W53pnGDA08~$#{079OTr1TA;F0 zU68a7vY0=grJ<a8MmPtQcRk>o%b)~{?FQ#o3ToTxG9c(wD8CLg2t)q8=xSy26g$RE zgPdd6g~z2g*IzgFX#Mx<t0QV*7&OAdR3;p!7BiqkZ26DQskB-o6CT(;4aq*np~sGR z0CE5c&X#Avu6Do5BmKgE50Kd?MdQ4T5G@zD98coQk!dERQv$#-cw?6(%r8QwM@Hdw zHsCE-f?A`MlAERqIPj<F74XUpMTRG!rp7{p?%k!fw4rm{m0G+6=liMrBpj$<T_d(2 zTBAr=-l9^@rV=FNnh#EKbG<Q)zWQhnWhlw7v-HEbG7!}7OW!mKP;~?h<oKhwC-6rP zk2!cnHPi{wUb9&t(4cQ!j-Tl2d?1x7z60!<3q_Epvf)rx!9mzDMpg<Zh|Cokk~YeM zhXIl7z_YOi0-^0#pOYX0RQjwuX$?i<H&NPD(p&knya%~&2ZUVn!Xd}mK`SJfFR{S2 ztCP5C+zFWk2f<^<Sld8hjwPE!-`nzIqnvI79PejVII1tOL7;DLrnn0p69k84-40Lg zEB1lfU)9BRZp-Jh9zGwEv4{&mb6_ZY)z>IMb;p3DbEJFHB^DrixW*_CZdpULZ3sDK z+^92M2U0ra=YESkUG~<0R^e{INXhB{G~8=(0i$9I)H@L*9<iao4Xinw2yjCK#@B-k z0v2R))W0WrCRxX$^<uv~kiPutgsabDkCG{}E#4P_v5VV)0o4P-vd&dRbu({D<mM%w z_LyG>2-m2O2&5-9pdJl-ue{|icP?OGzpYM#cw}GaMpgk`pFmSRP+tQ;S#r~o=;58M z@T53;eiRP1Ne(zv@S~&lS%Y#&GD~zw<K0y)8sw`4(j@F>fv<$dud~B71sVXv#AAT# z-G+UZdn-T@J-i=>ogf1lmnRxm2qW{><w#3c>Qd4ViyN)wVXt$!ubSlD$BrGQK{sEK z&aq5TB!qdXj15!@W+4UP3uQ&_jUtE&v5O?lD0{ALc|fM#>SRr)uA+Xa%HUbv)(BaC zdh*@hY(S!13)KxtE-r;y0Y}q8W;<b?@&G$*ShOJi$wl3w*}FvYcCJQ&5Ytdt^verB z04~jLAX+@+kwAEAk6z|Qtu0{d!-*#qQ6$!IG7&#&I+@6UqI<7oT|+<TvxJV=FM&%z z;^qX_VJrXJrl^GlDe}a6D>I&s@!RQSARADT{h=+t;`Db}^2~9`j$IBYU#>_zG?Kdc z?3MP>6;;mt<-O<G(<*TS3my5Hei_EcFZPNsJ$-Z5z`g5>7Zy1I0y0b7`Z-2=#-HDG zMxQ1VdBRUTl;`WK_?{o=8M>OnU&JWX&=dkrk*)qdNP8^+X%?Y4CIq5K>oKG`DzkGd zGcO%CE-H1|aDNt!lX)a;vggFwN0!5DpJpt&f<_aFYasUV$39EsYWWuyxam}u;^w&@ z=1Il#)buF_joGrw-XAQ0>BQ}-*AYZ}0x2$966iX&Y4LN8>SyEM{%FdWT1{3<wyY;V zu5J`#m#A<urYrWiB@m)!@Jm!646zho*y*IeY#G$n^B#FTDSI(@OI}4+_JPM@=QaL7 zRe`_I?-bPmk4XT2T6L_4{L0u8{4b*U4CbGCUh-RIl~I5OI7$vfI_d>Z{t-O3vIK8} zivEvniWMi@Wywuii{I{z`Om6sQ&VLX_=2M^F0o<hm_jdsd2OI}_aW1I(sM3t%E<d% za$sh@vVwy5t~Ujn0O9DSJ05@8LTBqxaGgnxXLh~RbIBjsdX@(n8k)k!a4PgyK@vG_ z=p_FyTEQje#moKHFj+d_+o?!mk?l@$&x+EkP4bps?t#4PqfQ{v-~Y;jl4R?CV&Gi1 z$77Aj2iI$yIhVGuxE3F4zS4~i1V;Y=z!3mXhqXlhZ3pp&`W?%@>`HRVKXf#-yfMYE zuLXEXhCS$(-^A`oKLcRpWy9A@H*&xY=l;Tqh>kkpit&CEPZi&k7#%&qrt{HKOt+88 z9!zh?j_n5#z74P{NgUAhzZ}SRdcbsR_$)jfkxUNoqP7EIz9aC*1s34f(BWk`y__Tf z7p~ApJQ{WoSQ&WXeIwLbcd*utFXA?jj3J%&8EwkRZ_<rRq{>YHWPIhT)Ryt%J4GaV zMTDR?r=&8KI&gpb`{%aMAyNuGdfI_z;e(HzSs&#HubDkHkU4e!Qbe&OV|c9Cm#hRj z8OQ=RVUAybaUf6MYEme@Ni(vkzTzU6!X7b+yI@rQS0J#L#MQ|$Sit!nd&Z;mOQPuX zR8}(t8fcwAsBz*>w|dih+kxv{hXlFUgw}8S@SD@G|6wE8puc+aSA?{=*l|G7O4Gpb zOc9^q4vi8O{-@7)nVz@C;Wifw(EoZEjy+DKf|W57Q&ZoOIGwPIi=DSF+&-z*a>9as zGbPS+#fFgpRnXo@js^GImNI5C4A~t#r4L?<@NegC4&M1?qCFPbS|Ne>Si*Q)iZo+P zZU?ZT&y<R&t^!7M@5qFLmOFQczSH?35~8e*Lfc~`@J#1e^>tkFgt%$^Qav6aqDOTp z`$~%_3q>@jl9$-Zs9^(m0xWN?lbJ`mnM2H=RDfgYV~^)y?YmVid4bnP+3llCSq3Sl z$_C;&Ryq1>d-?$Rt)J7NV+Yam9}oeHbHy08k9`gyLN`QSw0vnCeR>siOUZ)CAK*-A z&>Llt@Bn8oj2>3%!cK%@sRXz_;2?1nIVK0n{weTo%K>*`zvhvVZc=j4rITZes%jc; zue%b6+RNeVQ!c<lgoC)&yueQkY&o2K4c}gX9_DOEPoy?bSJ5@e6&=py^0z#!RLf4W zojK!r=<bW<MDDNuH|wkT0oQ4lMFMGps^j8O;xxiJaBJ8-t8s+SaIqxx)J>03Ns=-C zFI!0c079)F@C=9r)u-t9P=@cZ8Ey$uO6c_+u7930HRFHXW3+jXNR!Bq_Di?+IQ_Wa zut(w9<kwR&Ub~(-$`}}>jge&IcWP*Scv0%k|LJuUW_s35(F8|P4*rZM31|w_py4FK z8ld+ATx;)V1+c_uI1dp<@xqG&cFm6w;CJ3bBfrh8nyFBbOi+0S&TrEh$Dv&G=!oH3 z%TgX-{KHlv@WHjyYi%fsn&JQ;WqJ(52i0FP<qYQqzq}F&dOh4~fX(|QqN^;mZi;|V zczx@p2@ScED_RgiTo^oQPV@#dy4BDiN>0judFd5D1!SnVz?4V62VNoYMH*BMPHsG% zF$wsSe_Wolz+nq{Kl>m2WuT6)!E%4q?%Q5e!^?C3-tq^=MFGLT(|-O>LXX7&I7YvN zhk!sXb_kcq3xa6@%>EwrE@Oz!yic&pGJZ-lsP@G0JffX*Ol38S7@XI8Fx7WBJXrgr z<W?-JpMtI^yyLau%s<l0|NoiZ7eom}1GEn0f_9Yw_fqVf*}~D<3#qvY!*DS3HLF>h zA;884wFbf^={dlp;e1WtMz>}Xa5RXUHyFFl5q8sXF^>YQ$KvkUkC=6;5y${GfcBRc z^bS*QA0l#MWS+{Azzq{xiM{|9-u-$`zUX&m;fRJ$a1bJTkB#|`pE#js20`8o#%KJj z1Kl+=s49U5?GbO<2YlQvG{F*HcNkSP1tDb(X`zM6X~T;qeD?yt5S<VI?G?AHa5Ow* zNQ0j9UXO%ZrW1$<(Ukl}c^0_Q666pz8f@N8uNd~)jK~M)pz{y-9VSdx4!wZy4+=4| zQU^4|2Md6q=T2JiM1l+-Vu|*C$G{O@{O{A&zq8&0XcB87-(L@z!v390Y453dl`=De z4rv2kro+WyMh|5P_iNuSw=7(G-dCLRPty48y!8YP;+$zfFU$F90AW!Zh7pst|MJp5 ziC$ekeGAa+4QgV!w*%+EXP{EAlC@_N?!VbN&Eo4&k`4b&CjV(yX-XSihkxVD-xXi< zN5Z%b5g4<v6Ft}POQdv!Gn@v=X(azoxuGPl0WWqc`6Re2@a_E<8uaA<n7Ufo!Zvt} z4=9$U;JPUgtG}|U+jwFwc)`Y?G}5q$kXP&atmHR2!1$6X(xrRr9BLoXU$F!!aIV20 zzhEa;3@L&r#Qbub1)9){5`-r&5}knb2iM{$LAw73>i%8B0wCcRbU#QxnmGI3iYM#& zoxtS?8kG}TYClMf{h`{dsL$#Aecfrmds-PyAnm9WhlgJiurx^4{vV}(IJ$!foRg10 zfZaeO9kSd)w6RtLXzMgQfe5vLtiWPnh9juWdjkF8J`)ooE=as>^4p*%1x5HVAqjH_ zhIRgT3H~{mlkj&5_?y=LvtrhPeDD9<p3b|`j&_6}zmZxJJV(IRKHFVwkic55>@$Ie z4KZiCJpT{i_@T)rSJ@iq{$G!{%inbM1@XynlTFbNFWccZ*I~9llvs-BPVn_<`zOta zN-l)|uBhREXTm=zr~C+Joxu_=#exgZ>J|45sd<_*Gp3KztcV*LZuz^0KOh{Tm@wU0 z&O!hEp#BLt-v}8^*(`1^1c}uL0BeJM?I`kjqTs23utbBnCW3(7voJ_leXuYW#p})c zuu>co#F=}S$ICWDNKA3a_s%~lZn~JxO@JYPwa=)(3;RFVS75L=Zmat={9PGLlPJ3v zekCoOu<F(j8#QG0+TqI?&OnU2vjgTVN82g7)+XT%xt_ORY(+n)>x<sX4r7x!dhO!( zRG-_fQN}T4Smd`p-oUR5UXRYDoBMS*$}EpW_kAogwm40mqzWyGZCtXd5qt}`=!cVM z;UE+tXbQE|K8lc0!&XvHt=rLK`~U^4rzk;YxsIcCIFjXjTAvPI*uYbJD?LehMvavW zV7=%ZI`z0Q4O5_|Q<aZ5H0c!rnywJ9K9K5Vr8usnh1!kCdUVV8>crgq#dnCay7%xi zUk>PJMs7NtC%X}P%bx-+V=QV7<XJc%L*SD%{^!2ETW`?p8~$i_>S5!Q=YI7^TwTu| zwGCqit8R8Qp=qZ-Z{q_`Y4f`U>CZ<9qZdW)wuH+!jvoE=dICMLouTEtl_9;$dw!FT z3%(8jd=mf%z|;-<p=~}b%R&0e%W<5Vns&=U?7=nQb$ZW*c?lTOQ*F<fNgqFStI&Jk zorOLFxJS8yCo990LT=6<-Xe0Z*j93FOTeMYe`m==KD^Fp4gl*b_yUBokcQY=;ajix zr<LaqM+}_F5UXa&XlxNv&7LP3cwp8?K|aC{wUEdY(}5fV78QIs#k<pCbkC6NlLc1F z!&~T?)H~6iiT9BcDyWtAfc+b(<!-MNh!$|_tVGr~u6WT6Ac1D!zH0(kCf9Bqr)P=( z&n+|P%El+lhF~HQcxo>2%iOS%7DkXV``kc&LTPq)hfHjqqQ^LX_o2-@v#~qj#_fO@ zV<ey9%f?4NYq5*MMIfU@5}uuTN?$F2WLvS<;B|HUL-gvod>iV)hvlmkoU6JtC^Cm= z3koZoIy9(#(uvEEoKHoK`FP7y!fxYN7Ez=Nn*PZlvTolv{=CPP%kiIbLI%S!$OO9p zmQo((!ZRP<MPq;q^sK9edPnKPU+!~7)89SkRtKqTwLDR{VHvg3K#Hr&!T$N2xTUC^ z8!4Qib|D4#Ee2U=kcAsE{ZH4p6u^T2dj)(;o)-o=5d)e8P-Bjv{=jKs%ArOe{C>9x z*bqd<?<Ud6JI}#K@QJ$!r<#pf<k@?}FEQ36)zqacVP;kO=z*8U(fj(<WO$RJuP-*c zad@5Td>}dym9~C0A7h$RSl9>R4yBuS)E{n(vWRw!%9PzVJKY&7UE-S7c`@yE+}XCW zPal?|1;|Fj^F#^VS^4BkmR|GLM4@b_FJj+jGKhEjjJw)JRBf7`O9sLU3iXhgsNtUV z=aJHEUq5{5qJU^GP!D+jhwjRFoiHML4~O^IoD-M$RN0x>MRD7amp5$^w_Byi=0+iT zZz{4@VPW%8HSA*8u83f7Nq2ixZyh1~{c`GgTWLL=x9c~SD^|K?rp&+N2FxdT+&`TO zKb8|~T7`?+e_FP${+0W6Z{r8A#iJ!NzebhBe!37nG*zD*foAvMB@z;lVl)!y6qGk9 zyZRg06JT+*Vmcx3vrVt;=vp=KD7Jg?>MdL&SYDEUymC>Tzayo?8Pn@~<+_5Q=dI+G zwz?dRCb9AZ+08#=!)vevU3sD;9O9mp*9(9X{i*1|O2UKl6tnhx*@3;43QmrSExg|^ z)HrLKMZn7K!v_z}t_aEfisv$EQb5Ptsc_f5=ay*{tzR20-LvGd-$19H&q3*1XH<d1 z-YmyyBwB;zV6Kj?(o>Y&C2g1cYmR$WGtJLOm+WP$bjU1T>^b?%^?@CQ(q_}<IoCsj zSk~ccxq_A+&IU9J^k4AyOw^&c-4j@eKK`c1adQ;IY|W$*{THnS=K^m#3x6d~)Qg%} zK?P~AK@qR6`5dGbOZW{%lr)`nBTOMe#D>)am>quFU9)K)i0B-=7uhnf@AFy{`+jO# z(>wFtsU@vDO?UMBESk1D<lOmmEIN;yN1)k-FKxKV`|J7Bq;zKXv(zYC)e>0d=dJ#a zMc=!>zrQFY-P}`u_;v0`l&$Q{el_XT?Rm#A%$|}Zc1=WfUJ}T9x*KJ!ooK)lbg{&} zsG5W@f}h}f!hEowKQ(XomBoO<e66)|mrYaU!@c^%x2N*@&Fkh1y=)`&;?Iw99~ovg zM-j9!J(!W8;3qflvfphq5sVcVzJI*TMeym$eQ%|TzUe9V-FlchR}Dj_bmg7<4;A$2 z#9{XFPit=Zc12rY+B8+zb=>iSo8JEX=#F%c%2J2QhW7E|GY4&hldLbjb5Aij96jw; ze|W-e{OLPs^;>5ZCoZ(Uj{O*3fc+G&W=M!Bj&}oSX|pnbjlY{ejVBn)13@PyWKcBW zhbq=Ph0mBI`(~9jYa6?%y-+MOsJ1)x%~8{Gn~Cw*oa`&Y1j2rVEKeklIOA$C0>nKX zhLxQwyKS%E^)t#eZ&E+u!nC#~>{QysTsL!7(mv+5YiNgu7s7=<piE7x5AI97pY@pZ zT`WU4?yHCV-t?-0y@FYK<gYDm{iA2M)!!E6!F^vc@9Y+jx~?L<)D*YX;bIhO&(mnx zq6;b$Pp?RQZ8xR7NygsB+M|j4bSc|j4TV=J6I0N$Ib!wil$bg$cf>aMH0mks{CTao z$S!2ntLg-I)z#duHTy2c9tgKVQ-pv*x!kSWpX(^Tm)JB^GOu__N!nR)4t;8YyOn(H zOjUpX`j;ab4qS5N!XGtyFEvdsr9H|nsun-+jUX?`k#8&JZR8=ZB5sl4+8*8e(;`3T z+r0gkyn6)P;k=PB-ACU(mhbhs6(i%Nb2?S1v`eOaY&9%iT_!7P|B|Ms`$%S2WJu`# zV#I?;SNx=E5uL~!K+81{38b!QQ27J#fIC*mKCy3l&F5r#PX2Afy>*%P7YD3%O4{k% z`*~6R!?oKx6xyN(4T)0nv!){=Sgsi-@-f}vEHQ1W`@o5_ofQ3y#=HYD^HROrW*wOn z9S&$imFC56w?Dr7f{I0n+X4f~KYlu|+p+CQ`u^kT`_sL8CgYVn4qpG-{mL2_ir}9R zZN;kn<So$koewfPLe0#%$$I3SOJ@~_Rja?6*B>qn{VtqQh#TkLRGU>I9bP~o>}7=H zJ|kjy8quxVy!nCncEW1W$O{Z>$nF?@X9fI;^3qSCBiH*?Y;-s@3D+XnZQU<*uD7hW z(A9ix#Of$=VZ&#P)py1{d-d8o^1ieAoY~-E&yK=o(Vp+e!y7ANyDe=BE<|}>dz&Nl zRj{<&s{dB@V5s%?sjF=|0!zA&FvS0@3R|xIZ>d-j+H?`syeo1Pd@WWu=@+)Kl~s1* zyNiHZ4L9DwPvc4Kx%I{Kbb|nn`xk(*b8eu5j_yE5ANr9!<3n(12g*x?Z=lwtOT(#= zEjwt?v|0wPrE8gYww4C%6$F0SNAD3lRaZ&4mLHiz>#mEx(FeC-U#n34f|00j&EGBk z|8EP*ljz|i%GgP4PhUAU*7McV(WlFAfrC2<qL~9QejX{f3UY-F{a8>?jn~x@p+SUr z6p1;U4AOkv>2Qs5+yup-dHBg33LPUcP}HX;l<PxxiPVm=>jRkSJa)bXc)H=l<G`&- zOo8zUNCgHIkjRdBLP)}FP|;EiW$=n~g|973B*LEpN`T-~FqYJ1^ce)qLKxD|g4n;V zEmulx^v`_V=Z)UisxqN5QQ+1^|J`q(0LdJV1crkCP?)p~*Kne!%pwS=ldsI&4S}lc zO{<@*2HCnz#1~84=y#hp*hI5F=uTM%K4WeuCCJU40fhYQZD8Y<KwTV9b#$EuUjPBu zB_%F0tW&D`O7GOO=D2myeS4f6vK9R4q%?jF`1X0an|M$(naIUU)a5_UddZ@8f00P} zC-H%S(y`GTl}&_ajewSye&ENVr)8fca)Y}_XTzymKtnFbP@1M74R4O9*c4!E`Y^LY zm3DQ`d@9~0^_XFyDeEKF(PSa`%g{#E@ndunJXOQ--^4o1;$Qce({iW^aAXJgRx%ap zI#{zEuCc#NZCJf^$FF3mbd-=ASS%Y(Bt}w~K<|qi{nk6-8h3bd2YP-D_@?hcQ_K^D zFRB|mauajr#^}Uiop;}xo)*OfLSO^vKRyXKil+K>f<pNiF9;7Ubu2d6LnkH@PAI|? z)T{>(5$?e&p#AsQA*V$8Z^{ceNWWk>9iL2?w==XpxxVm>?4(w-c-J5i)8e<flCp{L z3tn{DRp>IkoJ`usR^R__qJp+Rdi$<HF=eT{Xa@L43-ith8Q!hM2fVgF3H{r;x#>V? zZn?(<&ko&P`o>+Be$!=Uvn0HuFEO*2JRy9#xUlbo!!VvFX8=ip-NXt)L!+PQD}DQ3 zeL=NN&+g7u=p4Ibfb6Oh!k$NFrnpjL(ROo3sx;LWzQ?A_Jo7vMX(7AKVYLZ<V)I@u zKh8aM^{pFfknz9`V{OKh-)`5AhZFapXF>X$({3~eH^)6f6>KKZpnwn5*wt6gZB|a( z_Af3}?$ae}_@*7Tx)x%Z?^2!DWw@QVR#gd=I?*68VuxPat~lv-p%wp=ve%y9dlqdZ z0i9K=%G*ED(`^xd!R#2d9OI;8KyHgNKkukV4#n$YpHt#T?Vfm#AFy_=(NHaUXH?S> zt-I4#uQcNGu=Cl&j(VwQ4Vqocmio?`xKxT!<I9b0-3QrlXnX7qLqc!&N}eKyt-1h{ z^Sb<i+*lXqtH(KA7f!W;`(&;%-gWy2CdK)P@Gx)S-JKo3;2U|{y|QZFNCo~h!Ir$b z6hk(s2ry)Q&b3-};q>)Ob8;hvMj};TGg1yFN_Q7`%+Kwz$jaKE{CNCQyWSp|>{;y~ zrWMJL0qPM|o|*XxyfdWLAo&o*V?2v%XCCT5`q}9$_vVy@m!wy^$@AmqY$MeEFWTNa ztf_5#8^sQSqDZeQO}ZdmAU3*y^iHIAkPZ@v(mT?nOYc1pKqS(oOYbG2NR<Q-0txY3 zo_p`v?0xR}ec$uk=l++KvSwLx&W!Pncf8|v8;F&at4)Jvu?hu^NP1WrtrV~RW$EYZ z#B_pp@dK5;@)gcw9w@sh-Wrof6`tu4kz}p@?2$&tNC|xf+X{EJdj`*Vyq!jgfe5F1 z<B+PRdVCL7pEJT8bX6b1kNHj18GGB#<Oa-j%78qi{>ljZIH!EWwV~#4W_41()S+)t zu3Q<rsn6b70$Y`4`DY1E$QD#5A0@?8Y4>XL8LEds;f^7DV@D&Y>SPXsePD;jTLdf` zx*r6+R^-d=8^P}~8Df2ryHFJ6Y;w{v)6D~;=Fv(J%GNP&PI@5O-~QW(PZ=$TG*Yi} z$LYFD2K^K`1aUjNb8k5jeYL^kV>$Jy%3WJczY;$ES&@t`xOY^uWN7zjpPcIr@3<Aj ztxcq9h;{+(^JFFN#QVu<Vm3SrigpC{e&7A>r979ONPmz8UN?0O>u;xZFS0~4?)5`V zq+QDoB~7r7(WYeN%)tRW4ROc9E2Us~EI}mm<^eM63+C;fKAI1YY4b&Xu~)AD62GUU z?^7MG9JWY#bs<eai1^;UAXmqB2dS>5z%|TND2?G+j>zZiaF$yRA~+Sz4#ESBO6OqV z=DI{nFH+J#fx@PUVxjvxto5b({FMOlXQs_+lpD>%?|<nX3eazgNlG79lc4G*?%Mm9 z-0ylG^x>jbZS{~~5^KG!%@P@b6&w39(g1zjappuAdh?RT(?Dyq>+a>i`XmMMyD{Xi z><hEQvRIL;+Zv_IbE=peCCSP`4V~su9k`S(?@4YsBw1}GHa1mMaK*K^RI^ANhD<?H z6bR4fmJ|f9<^D=rEButfE-s9e=)$njv{K=Du;D9b&r#X$@mDODRXiCO?7<|%NH*%^ zQ-e+eIiFn=3DZt|KU;v@>+B{y^~=r-Dx8k!I@FJ@y`Zc+7)ftsqfrOEAu3(jMudgR zU~cOQo3f3S!nNrih-BJ}y)KVxV7N!(+;s4&w0U@#lqNEkWFVQqg<%RwWlI}Adf~D~ z6HY1$F!py|OVDMz)}DZ&+;T!UWWcv<9(t!}qb*Js((LK)7*@jbzx0u2N)6M+Uy#yY zx*h+}SnPe1oSeLfUW^1rj73S@Zh}*UL0|HrQ@{OU=B%3G<4XH}lp{h85tXetZ>%uc zsna>`I2OGYRK#yB+b6ujZ+Am2CF_k#ikO&Go(MY^r)VBhAlLw)(Wp^@A(FxMH>@6e z*YmW!xtyZ@)v)*A=D?#*p2o`;weDw>-et531?=kBMLJ9f9Cd?br6H3qc$LNKyKwaL zc7~NvzLEJh+WpGBJ5+L7KG(z9Zp$aX`lRbqWN2iEmYz(wv>?ln7_aQXUpjs5a@6v2 zVC*yQ8<IcA^d<ygD)+Y@mo4zE7^@D=boASd-i;UJ=6`AVA>`FpO9j@5tvnQY1T2r8 zZm<&GF_zQ-wo8D^`bn~`yFuw7_C0IZfjZIht&u2Oxq8Xzmr^TNl;bIz@-zaEoJ51} zpG_VHFYI8?o-em%R?TeENd5@ph}9bv;fa=;(-}LQ6UB*4^s`OLE%IzQ#k0q6%6unv zPUc{z(0=yn08E82hX(sUisw^9{#vX-X1-7u_K_Z{b1UtE41H2K;2RI_r(Qf!yu*vj z9^h^~Ou<+On`4x{>F_E=l?{OcdFkUcN`iE~k&k;QI^RP3Ul7m(2lfWit?+9h))N&8 z8coRxyRhTT7yHd}waw)gKh0{IC5S9|%9x2oCZ2bZ)0Q+!>P2L&&7KX=8#Ejq>5MFF z*EyDn4$Xh=R%2=OecWz^C6hIhe#>Q6(r9X{85!kQ0Cwhf`BXAdnE5s-W9!+Q_2Mmr zPYJUR`ty+%Ru{c7Z3m}kuUM>logmA!5S=#NY3gGdXJ!$3oKSj}buT^KiVru~c@m@r zWrSLj0E9i);r0|}>4c6+&lEca^g`&&OobUgUq$F1v37*m>zm@%A3jA}#ETv($KLk# zAJb?YsjQz9ui{;fxBsljA7>FDJ}K(u!O2}(_pCFED2W8uArNRV^0Ufv%+bT%mj7;} z9w$7;Lx8b7Vw>TC1ex|oK$e1sG;x6dMT@Bip-yswF$<nVEE6MbD`Ky-P%mM+5*qV; zuz0<?XChizrG4DC)KxoAT<usXzCc7AWzA&DZdbzN+kpQ3n`pYOQwNB~$fMKSS!l{X zIa56My|NB3_m*{X(pmiRGDUe`KF-DIx~#p_qDFSI1j`!+Wx1u;>;?q>&eTfmj&GHX zXf|Cv(^Z>#oJ6)V0=<S$d8qKcIo!-yQrtrKDep_ybmAn>x?4!7mk3K#HnF?kl@{$X zh&FnmGC4VSvz{l~b%C$*in33k+?yQH055A=x<P-yHfys1IRPXAC?iBLk1&Y1(jse% z3K{j77O61rJe59GDe6Sc+N{)vyqJgI)LH%9Ec&gl)H35+jrYe^_7yUmX!J{DQ*TjO z5v{&Gz9wR16RxUV3-UmNy9F4rRWWER*`iP<(t2R4Pm61GHOdS*yn9bI4O02AF!AKe zv|N;gMg%yW<!@%=c@zH^Le?vLLGIFBwB7+_dNz#lH9p;w;IsXA!ya@_H5fp$&lzwT z&0!dS_rlN}B-Cg9>e5)0d91;YGH@GopBj3)4E^|rg?8R#{YTq?>G+y6^ulED$j7$f zWKE|X{1;c3NdRg+?>LNN#PIJbK?~qBVqK<x_%j7y>P*Fu3<puaykkTB{O&@xOU&CT z(BA`1M2>$mQ2%D3Po7a;cn`!Fc%g@s&Nv_rHB}{hmfT`yg-tE#ILnMi+=Q6T9K78{ zPv-kcm!+0LYm4wn(uRaycr@r2-T3zZ3(744I%iF*|9vc9bKz1QxiVBLh6Iif0PxFR z+}S^Xdx;PEYy)8Jxn5K_o>NOE`iEB`3WN)ZdkLL}VDV?5$&|UwC9#(*1{*woWqCii zc#P+iC%iWYJRj(v5Yai;^ff?lC$0h0RvjfMIpPru4ww90hTM9N5lVl1I)7xPsW{Id zfCp%A_U_^N&ki3llhPT@pXDE)i0<MKfL|_^lQa4CgMlc;4vc8&e;WTgNh$>M!=dC6 zzijJ0uaKn-mnfIBz0topxjJYye6R)J1OmZeAf5c5Pbd#ZA|-sY0WN1w^qWXa(`k1} zz$n{j^2{2WM|dK}0-(&_C*M6nASFSEq%6m{-$WJi=O&}<Vg%6!O_#NnX(7XnY}>O* zAeH2?mrI6u77X#Xwb~6hud9530T1T-!y)|n;8GxP&ip_6>ka8`r@><kiB0cFZZ4BJ zyz}`N0Kf`>D%qc*gNXKbf@QGppw%0H+_PXaX#4FF=<ot!eF>?14?~q4NwKLbs5JUS z^t0U6QNLPQBF7QEC3Lzi^kCNo2o(YH&cM29Ncl}9GsSY;_nRo1$m$PGm=CzwWbO9b zJ*D(63LyJXuP?5<!$!ZBfps%2l5i_pnc%<sn+SmZuM>5j=ZKe{YhTCVM{GN>qX*fy zF{ZxPbVN5Lh8|pc8_^A{kvRat$+nNhtpTFQSQQxJ<Om2Jwd&$+E@X)VBmcJ=Jk@IN z%4I`8kl@Fg>yM%?Wr=s&!SVO#Q}AbV1V;kph3Inv@fzov)|j<*^ELqQ8g5c3e4S}v zOi1|EMdYrf14QIz!FU|NujBc{pLYaM>EZgGvwg(M6PmyA!$t>D4AQRDqmE`tY#EL^ zA8vg5_2crXHVFF+NOr)%@pAw@kNz|H%yy4~JV23(UA&4-t(u!3G(|4a+NNdhh}u*< z>Tvd8tSqKWQl@%F#Cz2xUUE|YT;DhF_n<bYE#;3&onF-%Gk4uKHN{KXx^@Pue{Gq% z+^Qgt;1k)(9N7U7ooGNU>(D^v9u!$q15m6cSpMT3AI|?eFnwR{>;nw2z!3QGxnFpJ zvx}NIAS|`t0W3!(!&xF?0|t2p1hvfp=%>FFRfLA`K!3FQOG1=}4l*DQ#?GKSkBx@U z-Cjhog`rrr+r9bSwa4$+KNBebY9P!HN(z8OiG))GzIq3Qq&|y9Y&1iZfZMAB{`US+ zELIj_zIV!>O@Tm<+X4Z&FO`q~wwgdl;&H@}pGybM=)4(#E|m@NUD*HdU$(K})5}H2 z6TtXGt8EtP&l0+mobF>MFl1GU4-JvQ?>NzfIT35ZZN!W+AyU3m052*E!Z%m3Ms|7{ z2-_DJb@3=Vi9Ws`MIkL@3q^{K{wDe{yFxetG_n6{I~Bk`kQj~&I%0zj252nZ03wp2 zJ>XpgJn&jpyPr-n;&=s}=_V3%m73|;_;x@e;`~~+t6z)*g|8E)YLi%_zrLzn6=U?g z8f&RZ@CV_6{T4@Fg@kTUWH0FgTrVbT{Qaex<1-qya4^<R_%{*31lX6v@Et!ubZrc! zOQ4Si0gc!9oLl4P7t?=v1iu8XVXcpp47p_C-AiGWQj5xXzG{<>F+-6m;O<L1!19;P zL(vcz7+46#y0J6!@<`&rtWRXoT#JRbKU`DA9+v!nnX2d&0Wv}_-xb8HzbIbr>6e-{ zpm_(hv`3qX?>|nR=f3x`ZPZMUfsL*=B$#n(E|d6Q#<T_f|7%(0daHG?)N*eH&Eel* zV|Le=0cJ!%l!X^PvNGjA))iyjm?b(tR0|Pj@l4b)lx_9QWfN=#SYcF9>oVtA<)dP? zu+xT2E&#ykczU(Ub7+~wgW3~!8O+vyw==HSrI9BG$C<oB5w#MY(D5osU&~V&hw$nc zKdF4U0!awKn$u*iRKw0Pi6uk^wI!tUE}s=1q(`y(39!5U;ye;K%RJnhu|9G|@3lj3 zZiH~58gN$iGC8ZVUM^5kW~=O-wiW*Tun@Kshd12;`WLTB!FNqjh)@IaPQ(RZ_uu+8 z%>k#M+kpGih72vPKgM{_XCH<;i59@r<46?~n({Jk6wsym9cv>-4=V)sepPtee(1eF zJ7>Zqs@(3h*4IWc*ZCsl=8$;Iqn2VbaSi!!Z!f@y3zXrW?Z|<sjY~<aFgd^YGA_ag zGSq4g@X1r|4DhZu7DWjQF0jB}<Wkc%L@>Mx{;=!p+x{~0PB=<QVv-|2M^VY8#hgy@ zK%+Q4BHpgw$=+sRvc{7DKIJwQ#LH&=U}m+_x1!IaQq4`!sN$|K(8;Gfv7P7~S1(L| zb97L&W2#<hTdYym3mlra{P~ni=GxF!!(X>6?V9VO=WEJ7%U}GKE5)&$;{fN+>ragI zF$x|s5!Gx61;nV}npk-L7U9m>r%w|QZRGG}d$Afj0!^gG=kE??`uz1I$-jwS)z&D7 zJKarFSZxeAwo_y+k5^$W4~z5J>ogYY&}F&Jmy3m$%wz34Btan_-Dq&6yN^cqo`UVt z%YD8I10p&BbFG%}dkWvurpsR#IW=i!;us0jAlUFu4Neuijm#(9j@83PW3=5Lt1xuV z4u`IXDv!7JavnJbk53YtCeJFD6hvG!@OI2gdDZ*6VJiWuu-+ma8Kb)O8WTO7khMEz z;QJyi>Pu$c134vQcIwl`o^5}sl}2BNE)hG66H7@w@$VTwxYVe^$|8~^%Sf&#+H055 zE5RNfmP}O^n<At2BGdyz?t7ThgPs7GoqQWO${7>cDLEPLysR7>n8n#N?mi6s`D1n# z=~LQgjVBs~^lhh-lQsD!n!6muW!#_edaap9lm4vYLW}MC;C!}P@20PG7<uEmQrxgw z-fk~3A#vz<X-P2crkl~cifOUF{$suYbgF>*O4i~m6GracyUj;avZ&aZl%uE#gq;d2 z3emYYGxiiy6=+d62~jSAFttvY0pZxgxnAM9NMeWl2%AD*nh62U0JfRizQdxN@jCI; zr#vfOyJP6%?i7=o*tvqu<5vcd$C%3>AWyzK?fjq*iFVy1Phcy)1=A_?)!#Lcm;In3 zQZ4wN!+y;bFKSL!b%jR4tav<FxO`Jf%OXCuPUV@aQia|^S*fbVabgjjB2>{kIC~=4 z$b(ErsYZB9qc}IcBvLbp)=e(TGN??Vy@8{GW22jjRls4ah`#=TwsLPPIYi<t9q)_d zhsd8*xGzPRP+})avG(oFMPVXee3h_q{wb0YF+3+%+BZR_G3vsRjKQ)y(MN$-S3Tr8 zntv0`T|)gP+P#Cj0g)LcJn$cGzL{Nu6+<y@@m95P75AX*9l0e?(T;naa3OtOm(MEH z{XY&Ws#%qzVAYR+|M`GS?-V3Uj~|a_-C6h{ImHs*blkmU))<UD`Vc}+xp92QV0ugE zZ9GghWwN%z^mUokR$Q&D<LUx!&`86zoqE4zfp^(8$6+$m{$n!2;}sAvhN0bn9}d*} z0AcDDY?=w-H@>7&OWH5&gv=^i#=l7Z`ZM$R+H+oJEl<2KdZzP0N`{k4qr7Co(a*#s zcb=6_Q*GhMB_g_rtE)Q=UY9K*-jn9s-KM$B_;S)Eq~G*cnvlC`a1h6r0&f4ql4pt5 zWYTZlxhE46P34rgh2k^CCyFFAS7hk%CRk^jw6~SSA$Udur-E?~ET<mR!LY=6Z?8PC z4wk}}b6!+d79Z^TQofa<OS-nUVl*hVr}qeA*K}3@p}U!ho<my4i1dH4I^EWZ?3}eq zb<3aK)F>}axA4<>?Cq4h#QNTuGC@#bm4(ZA;t15UNdQdrHsw|(yG45Jy_;b`lBByD z@shELv8}&w$U2nDyVQ|ht$JgFuSjpX9+vi#Av_CR;+yVkd5d_W5X9c&lH=_;tb+d0 zfw<hCkEKEV2o-r8ZK5nKNagN}*y)Uy7!~FY(RUn4S{CB|{G_sgIJMxo(MPGkV0vb< zMC}e8r+Cw7W_t7<$8x%>5+=}IuThjhOVG~L85SDi`Bo$TQkpxpTYB`!O`}V*NL9~w zh1<{SP7imCwmD%!E)=G!nWssjq2Z>L)9Vd7dWUgtOBHzxrp1e6lHs4`mpY_ohq7~D z2ruvp)Edr9545VsFUzma%W@nu7_fo)n35IQzK_YULFm3<Si)K#dONSEg|_fHVgwyf zSvXCMLY;ErnB(N4Eg$5UT)<jTh}e}EHGD8PVP&SSg0A5*2&4tg5?Jp`&OjJ+(;qDG zPH4aFt*d6pz*K9v?MY5a@2;uxX2pHj**7zx>f`Hbii;aX0P}!S<^mps`D}wAlX(Q8 z9l`4snQW4iEs9T7-HYEp*7w!p%MVzjqpQ4^y30##&dX1{|0r|2^~;R9cMCPktr{w> zzEV3tRAoMo*;b53g?+EUBEPA%Z^Cd5@)EU3pO?Nqv+f26%bMRUP|e`h)+{X^z7o;h z=i{d@7cB|1Q!f&*r7uCXRt<7f(L9Px!>f(UkU(TGA&3HO71CXDvaZZKU}#cWOsUlk zQhs!le*NW~l26^sOD_kac@rKwZbgklNY1h#=4jn6O~Wk~X4nlVilZuL&X||}Yv8WS zMs*+HZTUF8o3GuIQ<HjmtM<uFfWvJ6h6S*tE%s&&k;gs#0Jj@@^`|4h6bbuch2t`A ziNZGCWOHEB+4}VdMMz!0lxrl%f|DLsJZ-8uZ{cc@V+CQt8i=2>KqQc{(JWVX@%Kvm zk^R4LMp^emwsh*6;;&uTzt|Nk)HY^o_O-XkGb&u#h@Vwtz_sZ)NkrL$F`Y7xXI^h2 zCet$61uQbF#PesdE8h9;-jP|>f*oe!x}066b-b+oCEDG-Mi7j6s7CfgN#Xvy9KVwm zQl1>QBXhm*zS5hhvZ)fCU|O{(Y)++j_Opf-%={7y<Wat@m%(`4mfJS-HTTw-DH5r- z9zW*TLwsI*XtTX}Kg?)euI5e?(@e84)@>zy;gL4B1Y?Mb4Lr=GEr`XlHQ&ezyqYfE z^&`%MucWp4(a_puYIt$!0WXC}Q?UN*Q_2Ys#4Rj&HwZ?Zg!%?i%%8(b;GZ4K@YP_h zAU-;+r^_~teu^OBTaCZuuyIM5s_!0{7nB;Z-(!z1Lheo^2d)fX#v6>+H`dec3QLoA z=pH)@LuV5V)Er7m&A5!DVySb=ZVlg?WiXu)YVg76*?n~2b9$*Q`(WQhG;d%<LbLTS zselIRKie(5#vl*vcgb*(VdyY?*q2NZOeP?0IFd<^4&l#>$hp3_s%^QWHK8y!w~t&4 zJ+c!j#s?mSpJm`dxEF-JyiR{XOaY(_vI3$wi+we<UJI{o9=}@`tDL6HQ}Wy}w><g4 zA;z}yE2#^ca=cmeZz4tr3o?6#%l+iazwG^1mtJV_<aM|An-yti^|cuOoE6Xvi!7El zOGFvUxJ7eXPbd~i*U!zG?L$q;*0-uthA9u;Vf||EnjY_-YH{s7))cd1Ts!J7<&9c5 zX5s~WrfxvAUsO~!?Xi|`i6BKPQ%3NH*dxXZ$>xLpA}A}(@Q$hAx7bkb2oKw{*Z>L` zJ?wsyqeuOeR%P57Q-TY%ZWzjFj)YN!p&kD746i0!-P#w?q5Ud7B3h!#ma>XYb}Z3S zDgIUXH1t0lFRlN4OM5l@e?l_+b$3dk!+_Hk54fJ3ljnWYLl!!3^CLx@3c?uXGfD_D z2=B)lzMk3KuDsp`z!Qc?GQWv(H!(aw4uD)X;1|!XRp~>_O4D5S2b<XOgh!tX1+$g@ z_)v0y3kCB0O_UA|X6`G(<Dn-4K*9|R7;q84vx8cJukb!*`46YJLX8+}ek5zG5)JPm z5Bs^Oh$K)=Kj@ZssiZ%s`U_&<wg+q_l5ZZ$C)6)Y*Mb2j<6w#TzxhQ+AS@8Aw-h+# zW4VPuPfr75-U5<w|M^x6K;Uo`Aox{+_LBaUqW6E~2^V>Xc7SVLMvCr0?6F~G!M)(% zqsy@$JqdFxLrrS`F+PAmZVbba@#PuF-&YiGhrM&8mG~!oa-<FVvGSX!7kYB*lt4px z&vo_-dSVK6yPXfm0v&P30^JMAQv>|{UA00i_~;3Jbdy>PltS5O^PNBC=JK7m-$d%O zNC3q6H)2rKfmGg=)E?((3d$#Ad!4@;yt)!=C!M5rf(2#+On4!K0Q~q*N>D#ALC;qV z&kC(gIirpZ17jT=peG*k|9ry)KuZ6Hjj{Y~xt&{G_x`uQN++5Ff#ZR2jn@O@KVOtr zCzJWB^mc=zB=e$0{NtLs;B~}k<&JuOsz-S0ZG%;b`(kWdK;;PNKYE}cbA4RzC(RqT zVI2T_)5zhH?bdVzsqG6Fq-o^nh}fEzbgSDIy-gD-eLHS1zaX+e3)2}shdQ0Z4~(yU za6X?ZJjv_NSv{I(EaYuz4OeHVebC0!)~zCN4*3zjP-hex0iZF`Vt@?JZG)xr(=lOR zL9x=Az+^RKGb-_Jws!U5*SYCGl^OnIiTwK!0ql<R*dgK{<@R`#zqPQ^9C?1Cmyc`t z{yi#+S#U_=#7^xzu3~e^>Mv2C@xS$9T&xijre4G%u+zDBfF1hzu^ZZK11JLh4?Xx- z!ok1wfQ)`+24zuv*m@fjd0+D6scEl-)Q=38{fWPWl$WgP@ajM^DMM^7bi-a7aUM-7 zG_v<>Wql7b6kk>3z*RiBAb0cU8#U7>j0=BqzRsT)Ea)IR@WHY32^{<Cs%I>aNnsB@ zJy8Q<4=zUYGSpwjIE<Bi!}R&4m9~O_mHa+#DgyqG)j(u73+>4V{~ClQDXRbV^2rsK ze@p*Vjy580LBCn85Sm|I`NLnA943Z-qxx5APk@d8*XvIgoBpub=UILY{7H7@Nyqfy z{eZ*JX!zh0*`FVZLC67nf`;X%z=6ofl*D<)|GVq`m{9zCwKEU!wn5TgazKA-!{h>) zzg~prz;fLK3LhG0x@0l^A=@JWwEX*&^^+^|UVtJ9a6(UU5ajZUe*#qyM!~16O8~L( z8bB<(aIP+kuCFujRRGFt1SJv4{L%B_0spzxzj*r<+rSq8zbmu=zxucG&vtwzydAuM zITon5>3*T;kA95ExdL!W@N*Z5L^^+I|5V%ieqGvjf-Zo!pD<AYN<DPv>b4yR5=fkJ zLI(bQzlmy`gIbtmGCdqC?I%l6EL8G-wtOv{#l~F>!a~n^YQmSpO&jiB?uGNK>rd;h zljA9lkDkRI!On_dA6v9@BddtLC2f8oD0z?OmYZ(FPel^;A{4TRKJsJp=hmMx4UHvL zO;<7Cz0pPQTa=->b}2fy=WJ#lBBn%0GtG#DlTY$uXkWfaHO`;^N@ZNU=fozM->rv- zSY3NG>|)Q~zuBCiIHYK3(K0&+H!L&G?nWrS1mDK|bO~8zrp@1;Dk4E`w+lra+qN|p z4Xk+4x@o=nvamdERN?4ok8H>+#~yW{cuzC?7j11XZZ^O#Sk~8DWDod^3W;Zq3GT54 zbvl(Yi<oxUgKzqCZ5-(&LrI0niESivMaIQw=&!USe_+swun1oDjfH(1eHbz_T{}RJ zq7@5~^^tc$W=HtbV{T-)+KC>YURh1cpS8DT=BTr0`1W(9$=BQoqa33DGVDnd{wyN! zgV=rGQI{|M+M^)^vwK>$7<XroYGl&GQrHaFg7su{fA-xRlB!f1{j$Qh%eGgBfBp`y zh~eyzVIJCNbfTx|7|r8%5alGNQ5iI=#=fmdj!Unfx3=AWP{31ZfxSVFj9R)OrCz9l zQlmA&rf4MEc<p&6U!3e$Y#w)77o(nhR30tp(U@4@{%zVDQU>K?y(^%Oc3S}lv?$_C zuncWr80Y(?j<-9_nLpmQs1#6Uo$&35Brt5IO=h~0*>y|Q8;dEy3{#%OiOi#o<f5MQ zpFM{b*`8K(CwZ0Xb-3{dmpw1FiJyPL1jB783K~CA6MPvIU&~LYD9$Q!tkxqI-O-mN zaHXG%(`PIxb6(3S&!&K<h~IN{&%Vf<{qTMJk5<;ohbTyenIOLh+ZxG?92Hl0LVod( zP~HRa<{{NrN3}@`irNu*{hGDdNZd2L6qXgI54jB(c+NVL9v~WTLljGxBSh4_LI203 zd#0I+Nw@EIF<n%8!mDZ>+vmFqEn|0wlZTa$hR~e5tT@#TW`OI0382RMAxWj>Wk>PX zkP14Jj!MgFe)g2`=8W&k+~PWo9|~#}VM1Ku4@{gcl3(!F)S9R#r?8*ZpKz+`8ibXV z&nx<pz51rl9z$zw9kal8!9X_rl@g|VuW3cj1P8{ZtgzgM+=B+{HkVMd*w&|wp1l&8 z$bmOTpxEU6zG+(od%HU)CedDavhhty18H=*_9#cZS!+c#FH>BJPoiY}jnSxW!;f0E zWR2NPfo;ZvO~Bh#qnzkR_f<$Bx5hh~8zU&Uy2X8TOC%3J<w?e^{V3BBT<_>}{j@t& zc)|{xMHle00IWGfu0IYWRf!?}Q;^Pp0J82u3j@Zid%<9-t9n=<op^lxIx~<Ya>n(s zyqAnEl`vFB$wvNxeaZ=8zc)jpdKTb+QE#&u5%v>ek8;%2nfmE=1itadwvfva$%qyY zaiGgRc+UHL;Nds5)56494{Qz21n-I|+SzkN>we`yN|S0fG}q|ipO;~cJw7InPMLS- z_Mx8MZagrH?%dJWy41k#7hjYOZIfhUsjdq4KwRH`dx|Yw(jD)bzt2ayQ>RZri7!xl zHhuUO^DUo;W9@eIsFEJ#DL)g2A;@NVdtDnNc#0}hbua1Fu5-_O(CzAUGjmT&25ghN z#_*t9H1L!$dy{K<oihl15<(+b^juQ=;n>lm5ROdZp<u2yEmh$a)$2EH+ao%C`MrD6 zc*qK#>F^Qm_>UrP9EL&saF+=S^Z+xV;!usWArdfKI=W5hX`0EzsuzW}m^DNpsgTvw z&RC}dsj#i7`w}rjUPsQ@DIX6YXRiUH8|vU7WsZKM#u*0N{&p8`EM30RxcC9a!^YyE z@VcqtVb5AlbA&<-nGnxZHL$D^%TQ8?J%*!+I<r_G>!yWKw)bc8abotW{hYSImbw<5 z+EP4uX4$MAUU2i^vS99`+LI+brEx0-UJdOR8_`M$c{&dJO~hc^tg@JC(d-<!2T+N| zEQvYCDlH;r@YNk3qXt;@>C&%v3`XwMRtg}2f6IqODN-stI=b4FwzwB3hDt?jT1EYP zZb}e*rA9)tj<gh*(c8YKsZy;yRR+pp$^B8Wxi((ARI6YIBVub-s%bK-W!I{pRXl$p z_^QMtZ!O114_lD$?S{(kB!vd~Ghtnjh76I=8x3_8cB5E-)FP9p9-C>AU7VWTcbJz> z2TlXbPm<?@68hTBp31JqeOBha7mK*;Pl4q`i3~@vPu7D-wzh2?!JX<Yu71sJJF{w! z&zP!yBID($kAYND3c0wIyGlPsq2>%A3O(<)ERj&!LuEk}IThFt?A<Us_cDYlZQ*sy z<YW5+MJ5xuhIe~%-1)utgJe%$KpACjfg!rF3RnTZ(#^Ewz~x=2CLH4cf9nSubyoK6 z=X*?@Ldq);zbAQ8qfEUm*qCfwaVT6fUQN69{Kf;V!W?$|NMePEIu}R1*O7~D1*Ie_ zhWA={YO8Kns+E4GdGceD4=pcTs7~?(oXJbIlJ5&|i+5|=PNYn}X|(%pJ6WI<<+GY8 zTn4elxDvX6$Xs`<WiEue4#S@cI0w|WF1;?r<=1D~>pOKt-L`ZF3N(0TDvN3&^jX6f zma{gMie20H-UA9Lk9t_@V#Aze*r&TH?9x)gTBKL>1z6K0?ivPtiRtB|B%u2pKG?Z( zqn;6K_QuF5tq_E;x;-+0qZr_C_jalaLBEwoU4*Q<+F!O+t(ceRSJz2zoW9sY`JwqE z{mfp4dGBqhM{-*unZYKtt&%F}rDc|#66R>MSbLs!Lbr_QsAjtky+yz(Lu44gRR2Vy zWxQg}LwVYVq1;McyssTot;VS6^_>)@WSHQ(vt44UB5Z5@57?>fdq3kQ10Yi^^#*4$ zhVT0hqGH*Q^9d|rZPq>oMvf%frAUK(q-r5YzKw2|#4_?(HoQugF0_P9${*Imu0EPf zAHnbKh0Jb8L}YPIO#&RwO!CkjJixJf?T)jLmNM$Mz3f{sn@(+<LSFpU!syc4-HsL4 z1#A*B`<5+%1zWV79onB~ORtg=<e|dnUi0>-)fj)OaT4v&1}ToW{A{xxJ}VA&-4EsC zDVsgZmQr5^W93>dEN7G1w=#{D!<t5=mHK|=hbZH;8<LoIsoCxhjJ3Q(J$vVr<Rx4| z(Le6pY|N>BRw8w6xvcsMBD%7L&$%>TN3h?~$6e%$9crJaxL4a;Cfky#E}kw*?PAgc z%9~5OB+rFhix*@S8=A(yEE-BECvBrOA-yI;{oXTfX!$Tk-DJ$8{sSXp2UQw!RbkuF zp3;d0Zd%A}G7XI}a%<>LL0A&qXs7>Pyj>;zaLV*E&Tj|a0x0TGoUR>#bF$pA3a^;E z;l@r#&zY4jnOJG^9wwI(Du2i`r^aihpL2sP+2v$9SqI!xHP^l;Hx9Bjw$?x&)g9q@ z%Iqa}EB%Lg!925_NYQ?JvEIzoxj^{6j9a@nbBwj&7{VG01BF)<&H#na*p_m!+>0ts zTdRsL+1!1jTa#w2@Os0PxP!}KtqLD63ta%mWTUmcCqPbn%m_TY=i9OVVtL-v;OKUR z3Z6EGZ!zZD+G%1|F<L~Ilb8her`EGLB}rLxc2G@5$bL>s0nhXwBVramIH%k{8-U8+ z$mqveriQ}$@6nl-nZBvIA>oSiRzG^!Dd|CJfmCrbr!<Ha6S32-QtzhR96ec#cu>_5 zJ2nW2z?|W-bD;(s_E~6wrKVHPUzI>v#9mA`{(aAx7f|KcpcY~cxJxcTX7LnIl6uVs zC~Js7#-7}qJ2M253`C}<n9g5)zwpWqynmw+pydF*!FLt4zh4r)83)pL|1UAgWgdiD zqf8>vAB{>E`YC+yPsBE`>r+c7tPKEr@ypa11au%`@b3Eg(yf&;|0)!B^?xc9CkFgF z1N`eJ=#Zn_j)><IS^)nA`W19!_hb97*FXvhFp_T=pqASmLMsh06uY&ulD}OR6IGC3 z2U6PK{wXoBaYO%C4ibDq{`3%fcA@xEHIV#tv9%1Cn$K0IM+twXqGQUX6!<#-HsK49 z<^vRLJiIX3g)*jJWDhXRrK98_=WAp|19?5VInZHXpa>NLRp0ppASNiD{Vffiz=Atm zLh93;QWumiDi%+-Gt;HJI~bA0=B(Fj|HT#}0!pQZ+anIP5XZm%FmYbgFP;1X<4zGP z#sC*8vcQfyi=~d<vrHi6p;_0n<mJOv7ab@PNXz~KgteCnfxq(3Kh>KI2~8E2->(7A z7>Nl0uz*4dXJS|#|N6^W9C7@@4oWp#x@@~`co#jY^BF)_o$>b#_VA}wXJ-HjgK(SA zi{PhAAXH(ei~%XjSzZBTO1z`>ZQf737ECh$?dUrI%vC)DC?No>?Vpb4E&_7UN0$I4 zt$nJ&e>Se|s6&|Q6tz|zwLIY9Ww6y~x!IDoZm-+6v`_n+s6plI!G-MqVdVXrryP0t zCh{fVb_!b6O<HkrmZ!jaLMLs253ta^F=(*z-|~NMA_x>;NC{B#vr}huVJ}LBew_mz zvXK&}^l5(@$itXz;!f@%fJ}jmr84}+#l8Pw;I5!^{erV%WFpDzDN`(j-qHFvj{8#; z7*X}$A&P_(z?q#qzYHkPUr>Ehe?otJdb6n1M6r1089i4940!l~J1VjO1d$AI%VdB> z2i3*f=K+)Y@5G*)^5-7HWMxY6%m%f6;a2>K8y9;bmlMgiRTo2%^CFUf8s}e&P5#_# zqhQJlUn&gyQMU2hau>CtMI|_$Zn`Zo*Q=dx;k<t2HP*lP%<d?X!P_)HLBI3a>&t(h zf7Q#=si%5>q*`KqodI><>qG!G@!WC)@R)N~y7x?gbLlevEX{*_w&Mtnc5Vk_<q<Gp zs|j-i#!kVBf^w8^!J?T$8K@`uG4PvwU#zHi%3Er(`vnT4g+KV>o7R6wG?3owbD>KX zGJ+MiYbJ~#BOGUsbZf_q^-o8DdwZOvI|8ZLfOo(QiZnPIO1G@UD@NQfQ_i&3GE~+R zK8rrfWUTXvrDtWUkVr6VKC9|?=etF<VQ}2Jz@P>wno)TlchQ4GTQrO9sUOW5Vq4dx zIrYX4DS%ssLuZ`mjO1#&7$mzt#>*e17HG$)fA^neq2QHbT^>Oee)nLq+dohm_n?J< zihK&{Me4&f#8dBc?|1V5EVoFd8tH<0QRH0<f0}S)Fkw0dvbs9jDl(0=RvLrw<k`Hk zD?!QEeK4UlHMG&r&zLtHtlgrujN(kzVS9aDfuw2#&)J)c78<r{DxFLZGW)e|$WFVL zA3yctS0n<wGED5E&jI~4B!<%SRXT|_QaVynFX1xXL~hBp)7o-ul}lxEe@H@=b_c(d z%Hy|bulM~z+Re;`=`JcaG=7TAyd;nFEb%Jna=4#bnAm$~@FMysxo=GMhmXy=%^C+q zxn;`tR$@ZG*AacK-Bg|qB3nCRs`E6szM+8kk>Rjl$l?fxvhRRVH@b^dC@gDUYV-E3 z__+Rc|63TEfEBc88A|06$|;X2D-2Y}jvh|s$aZ&JR_N5B@v1YdA1z7uC3`V6a!(&W z;%e%j(wPkd?@|@o0DHR*!iNS<m#6jU;AR6mFUg(BH(Q=ZI<G{t#@KUwRsz;cl#^vF zvOm+iwVK<S&EQlYUr0yQe01Po7F_%B213~Vu~Wo(ZI}0C&Jor+#g~+ny*q&=m&r>o z$2!GuXOv9lsPUIXX}E86H*nrzl;zPax$eOpnX%P1QJ|dJC}6e8#SyE6%}DbP#`O9# zU}a`3V3YNv;w_SFjRyucIVnzs+xL-A3@vDQ5M={>!C!%@1YwHkDP(AjyE7?(Z=(vM zKN)z37deU^7_=%#HSQv>I<7w}o{n3-056g87xmwB!}nuwNN9MA8cxGo9@*2m6l=ma zE+y@HEQrm*b<A2MgJ+IXcG+W+*#*PR!kwA9%;Ik+&X?EHTw!y50vz;r_K?;QGLp(b zm~1`W3n@U1g?5~R!$o+$JXRO0kSU)Hs(H%TaJ;WVnYZ(1snmblE;V~#F^1JSbFf8n z+2F94`=gEg{BZ_rZ!RQb%BU*c)-b701+S?1fS?@bt+t#D4R41!>jq}=keZYi1m+?` zJXrNjH<hC8;yaWQ4GW&f$4<DA-{$^R!#G}yLXQ-D_P|&JfwL}0(&gh&k6)8NA&M39 z)<t%2%{$mj(<Arpb1?-4H{9l>`1$H<{?@A|UDBQG+yC0MG<X4Y^l>!)dBsLm(Pr|f zksU=FM7KBmR-M?M_N6S*AdR7czS8^*-D_3;Ly`i!7goqgA#`Z#PIk0W7IO{eD!fQ7 zXS&nLfh}PFv7>a}g*aq{L;=OFMj7Xf=$pP;`D?opIHhetJW0Zl%UKEDhbB-;n>@T? zr$xPLvzKRP$)@I`MS|uG?NeTVqcYa^ma9QddIkyr;1P^=4t|s&dI8C}!W|b_M#Ux3 zE#&EOKf`#cc}{(OZ9V$%tsml+9|N9mWoLzWf1b%f^bu7|l9aKSLBUHENzESZ_A{$Y z8d;7ixdH=B5O=vSw}wt}mB=Js2`i5wT_!{j*s-yI?XWW_${PNQ^K*!@x4*~Jb!CQH z`KC;5uiK3oWK-f1qxy4Of+hC8jXL)F<CYxJ@3=P>=oIb-h~J&61vrJf*nXUPKYs#_ zfdC|tXGP0Itl>Q{_qTD6p2J%YDwplW_9x|Av~hy`M_^l0w(!fj7l+wQxX==WN7yoy zML15udkd$01GQk-=1JfKGRA6{?r7Hq+;L6b?{~TfS44hDOm}b<_Jm(EYq$YfW4ZL@ z3q2-_bw<0OEYc+-zU~W>;W4h(v)Qvg_Y_YpwxO78iZvAN(HSTT?ObML*GM?hUQ><C zX4jtx7E|e&mJ{KbI9`yIqj1UNdQj3Y>+99EH#6xR?0++*qn0qnLM^4s5^fo@xbg%e zAI3J`I>xBM`)RI4nX+NDJoiqssM&V&BZjN<S$sJD%}M6RXK9X7F33SM&@F>)6(6^J zdwQ4`jq-))#RXEPhAFalU0;w^mwfw**DgCqNfK_LN|%`h_`A7BnxhvaG<EG%IOaSZ zyA=(N>%2yF@Lpl9(M>mXmFaY^b&h9p-^nAMs0yii7OglLY!H(Ti-jL~aCJu&u&c{u z<Zwfh*fpFo%!=CFT<q4B?L(u(+HB?nV^z7U-nBeNWz#}@8nG5><BkP3vt5g26-G4y z60L1q2fVOv)dOP=2e%Xj5^mo<v0sO!#v5k`H89g-bC9HfsKKTTCkzpYQ`1&qQ6K$z zX?A{gZfTfImE_tW2kk`Uz3BnElvP&d7kDnz0B2n$cjAIvMw7XEN%!d5BqlbY+0nI+ zuYREF<e18vylb9|`%M*?+`!fDQ8aygdV!95XJ6*^syI23QeHk?Vy?$U*F5M7Wm&?d zp3?i+md~$9Xjrl3e5KQzP`eZt`1O#=uw%-rl?fY&%noz06Vr9`)>+)*xgkpUsp#<2 ze}otw_tTs&J!PM)CgelSMU>|8H_LjL!c9*ZhV-tt@UUHB9D|2|i&u$K_4Dgj=bBcn z+GDFmo2uRs9>ULZ4t+eJmu$t}P>#2D-KfkRVT0e)zTO<R`sP+$;+4M4Z}YD&zBT>e z-4j2WSW^D1h>GpR&aHh^BPw?^G0!stwq!VG_;ENu$_+_&lP8RsoK7x;^p2FY(x%!> z2gQ7K{oPU?ARwm{n8=twU=jURup$s_LV_{LxfWKAe{5c`tuy=M2qrlZ+%OjlWAM5A z8Z1HF&*fUGMMq_{R+lpGZP+D-pcF=gi!lr8L2LMa7<2axEn14!!H~<D?D0M<0|BgT zT&&cI<&_4{jQgF-;~Jt`@7<K?p0ahQV}8Ul&sSS1dBAgJNO0(_oBmsH4E|nuhlfaP z7$3&m&F#wUP&Y^T?oX?R#3Tq)uDws9j3_)=DPE!^o65T@@NCUGY((6|-KRW1ZS8n@ z*JIFf%+TH~<smATwnQ`Lj-Yoa_pM|S$#J97u~1kdd&p7J-L0-?r5UVhsgiCQL0Sej z{g{;Y3Ywm@pYMH9FW`-1halGev9u{0KITdNq_`9c-mmlg%N^bqYMX}FyzrC&&zVFX zr@h5;3-656!)i;3m1EueMe}^k&C6-`${ljyK9-Gf{H!se+P81%NH9Os_snyZ-}cK6 zYXKD-vaf}Fww4mQ->iINRH!!Y!_#Y*Z+{c%CX8mohTDc`1lm&k1+fdLY4?Tzy0l?g zA<m<a0yaykoCdg+PEv;=JzO@{+m?=!npxDm+sHm9N162FqIy(%M3M-Ne~G^QKEjVe zd0Skp8$?qZbFaNSi8H*6*-o&4TlJ?1w_9JL7Nw6LRyny3t=Q)KK|S^W2-TjqtpS@N zNEvX=vb6y>t&AWtrEZc#C}Jc;gmy5SZ|jAryl1|-vm&vXt*#5iu+RHc1uIp*be8r& zhn1f1Bmrdsr9*)eJm`26(O$ZBoV>^iBMgtS9kAbIEV<&Z9yh)+t}9|d05<UlAiy|v z2`FXz4=evad-8;_J3SA)0WT@F6TBS4o60CI{_X3s+js=P6+G`_aV>HHx25XA0q#Q1 z^_AjFRsZ-rh56p7v*T)QLlYm{w_f@a2cgc_H?s<xB(s%(9~QvRAe@At2N#$Aj~yQQ z2zQYSDl^}<aSecXIZ}CnZ~~O91E%quasN+KUzW&z5ewBGcUnWh-Wzabv^ZE?;#Pgy zCPH(r*~%0Jphqh3GvA_pDyw%AEa#kEgIT8%^BjHof-N^6x30_$$_61t#u&-lhE(6Y zs|e4>{O$mDA>h&cZ+hWuFPeZ&Mhd_@D7xcL96EP9E~-9snT{y>`@*m{Yy<6IPaw3C z69VdMo-oFq>t)#~cQ$FbD(r=c{}K<2sOJyqM=`nZ?Z3qBh)n+e1RnhTlIH^u;59b; zxzw2)&>^2Nm}EgA6bD};idtQ1qDuXHKkS?@14zTaL*M`C2)#+1U(OOoNy!V=fV*Ce zZ>GO-i!=VZ-)uLGk;lJtk_iV^L<JG&Ij8TR4&bB_Hc$!C5Z^wz3ajfL=`JAdfB2P- zHAck@;CQfC0+}}e(y=rFkWk71Y~;U}-!y6*6;b5$VI5nyv}V_ndn0F?J>85ry9D@2 z2&;EIy0)L7-{|KEP1n~zH6GB@tHS_1FzDW_lVfgK^xWRdi_!Hy5$5wdEnEcAXfDvC zqb<uJMIeE29n=7eJtcVxc*0kR+*$>I<<SqF5-D$<#@whFDk@>9ki3?4{~gJF;||t& zZSoysFyTG0!<OovP?hDQL3kgaA!GUda<#ucF*KodA9XB<)G~D%I??{P%Vxg#PRynh zF=rrucKH*~-+<WN3RXhEE9g?&6S`LM^QlfO5lkY!-g%?bMnV$&_fDz>m#8AoB7u$f zT@;Etvbk7qhkZ<V&T`a?D9|Ky0n@g@06N2oKsy?y=uPsDD&(#PfOuntv}c8UExun< zm(?cBj)FGWubts3q5mE-k#iVmmDCN0>i;GxuH<jtHGEa`Wy}gz_c=!2;w78S*JOzu zp0vMiFMPq^yaaXvjs`faJ~;sT-aF&T&8kII<F36$1EsYW2h7EZm|+)YMzo=S%__@Z z<9^4dd&LEy4^Ti`p_!i0zdmTvhefNed#T8nkx~#x?LWAfNo9Smm63B(aH;$pT2a3H zNWHpl3|ZgY5+lJHbxr=w_3UTd(7&day6msY;+3&Ddtm#2N@O`k>s$+S<oA$PsXW9o z+eAE|c=7rDUAJ$a$RfChkNAP}?a2(lRG7&-*N5*{fBaSHVv;3<EmpBUo=Lsyvs8ML z)ni54?LpgfGhBZjq!|16L!e4Qg&3RAYAWAf&J%PYAB2l{yF6js^#=^`HYU(=78v~v zM8bmF>(oAw@>v<=p0w{*juz`pcv8zcs7%%uDKyZPR7trD7JBfVYyWaQ1UOVK^ZhIK zAOpfiWH$(OA#R!&ZkSLt1H2N0C0mS0YhAIKmT%npT7yBgMpW^mH(KR675UFk(=q1V z-@UEdPm882>$S!m9PYe|;p1PBnlaOV=U5@EAvY3maj;&0B}S#gT<Rr+5j^PzY0uIP zn$%1*Tdd&ZdQdhaW-<FE!H>_697UclAC{U;gSjDaqtW)DuR!Td)q_RF@r)H(^<#5R zo58lh?%lys&lXFXIuwX_!~a1;GN00P`RH`Nm4M@1e`5>@vsk>y2iMzKwE77@5sB%6 z7a~^o4nf!Ow?{={nT@fkM})o}d8?;|^GoydZ0$ab3dv^9b*a?U3YWXYF8lO1m-JP= zYvsn~;<Ow|0VQf!|9u_dh6&+J*TpTmpLA$bo7}j?i&Usty$`F1`SzcCWiwybjr5V8 z&h)g+knwcgNdHx&2j|XuRo|?iNURv*TDjW#PEnY5RXf?1o{>^Pc>6>^fe4*unQA4y zYqV10hR#~?hUDSuirAIw)xoyhAENS6-p)YAiARb5Fbf0z$}%EG=6;PNP3N}k_>RY} z^S34BpqxUSQ=gL2XPy_1FHbC=>^tjN-f2GL!aemKZUf(G<=jke75Y5l$S+bBR0IG1 z%P>yr6gSVLqBASraEG6@F@`0B_$c4yCpoVmD3Ji{f@{K6v#ehm7Kt&zYXg%yG~qtZ z776+H^<PoFvf5u%i0O`_nz{#RS5hES+VrP_uwd2DJ?%w3uSm->p&jv?7=s>YvEh8` zy_SgeNlcM#1-#$+2JFoXoqLz9grhCVg7cso+$OAVmgvjj458^UGLPKXlohr%$0IU~ zM_nMjN>ig!M*#0^SB7~d`zGEL*`nhUJ!ly+h!HoEBfT9|K=T%6ZXnoS+U{1g^Jaoe zF5ku=dQ&%XE~C0C%XOdSCSDeOf5tlx8QKMkdMRb@n>+0dmTiQORQ}>>t9ca3q@8y4 zL$8lW=dO2YEn8d&+-MIhsrK|N4C+8miFZN2!uG7h&MfKFCx8`rIWb<L$;#=5Nidwc z-e6f%Dz#X$)<K^Bi+F{$)QeY`vdWO)AjDPw#~aB<tz^w(9>WY+oyB>(Q@8mq$$4(q zhkaJ(Kgnom@+Gvbe(TepB!%6ejfM~yw6NqWh(I8qSk<21#1>==x+5jxTi#z_<216l z|C`8m$!Mt}!xOqcNHKaeDH;whwzAM?*IodBGCLs46YTu{b-cwMH6_fLlsitdCm~^Q ztOb~i8R_-28XEA=NP*D#8!H}=sRu>x%K{5@vTka2>UL^o*JNy%-P7C}uSR#U<w<=} zFC$ZVsSUDyKHK~zQTr4TB*Sr*EAtqyi4hBhnzCH;Hkbo9qfxZ}Y>=l-g8H(By)J&h zF-x(L%#ntKFX}%Uh;(tPtjXV~sPhN#p6N%=G1j|uDDuG82iRX_*n=)lfAY~^<hQU@ zdab&S99#Q8eSSJPmX8d0QV$;4m@LxVQE_Dcw5-UhN;!cB1xbNy(U02@u%fTzGzJ?0 zXcqd}o<M^bXI9{yQVr`3D>T!vfF(~~NhRf>1c`d?SfFX}l(ERc3=`qAS{V^MKSnn= zy?b<1G9(f?=O=_(Hp*|9G=RoAd$?SI>1xK-L{@}7wfEu=P>F^AsO1&7EhWw9uaW*H z@48Mv3aDNqps;|3%guyw2&2SRSXiD19m(mGQty=Da0y#3h|q7n!(1|?B-PmGlq{3D zF_gbT2hjINa@ci(@;67zw@Rl}GfGdZzOu|+>PB4o#ZWafd{lpDVLQz-XdnB$i(<Zw z2*dcQ+sI&0WT2*lYVrHUe&G_vRO9`NI{KRs6SQnh0&wWMjELN@@6mmWh!W;wCJ%cn zS8k^7bbs8c(NSgAG7YKm<bF#Qrw>zVQkqtT;<Fc!rK5;R04TQgCBNbQ14Yw;pur1& z&%p$2R?m3Hz5tj{gSc-0zRIZlwraMb0d-#f_|lWy7Z#CQ2%vaa>n(^KIyUsv*{5H= zOSiTqk7B9LS|dvzz^lh!Kc^Gw{2&;!PV!Q9(eR=E?)*tIj`qhuxB3162MbA-y6UYG zNsm&wM5m@r-xuTl16p~aKS&Fh%-N6b9r~zITlqM0d&?(rSsj!qwaN&OhL9&m)d+uq zacoLzYb$9>VDyacR0KyWW%X&>$eHxqKq9IExHJO9NZ?Q@@gFnT3*nP`j;x@b9qn%q zSsgA>6I?VOe;MEz#uY*{U{~JlEb8#A)u7&a2Hr_yav8lB>(6KdCA$`iK$2j)0GXF3 zqq?fv5r(!^>FO|>-6*>fl7J)j=!>;N+z<O2)i((@n$FT7oH)THZ2D0wrmG>+6j|Y^ z$S0-f_SSKacO564OJZvC&MLvJ-IKdEWq&{P`n7govqE?6F`Ov1-5XVSajf~u<Jj=i z)}mrD{M|Ib*z&M1Q})*A8}6@9-nx9blsM;LO|U9ks=s~#KP*IUEzq`3H#)#Q+F=mH zc*pa|{nK*c&-~qMKbyE@TP=subPOO_zQ_sat=e*JGEe51n|j<IP6x>zCozg}A+2=^ zyn;%^RJxPzQwdUSmQH4hglP+i*s{psP0>~rI0^snlTaqTEqa(gU!C`_P5&wC%{?7< ziYH^L;q*LVs5H@J?Z?aM{9(h{(q}P+fb`?1jqDoeyB15AeD8!O-**mmF@?d%l;%+u z9paKldAuKLQ!Ve*_HySwUd?Q)p8ZWk2eNXW{oF0X48wqS%`vASimiuBCUyq8fl{3L z1+Bpal>Ghlt8Ax1^Rr>h?i@t?GPX=fbJGAE%8qt^kEfxDfzbJ~x9Ip^iH0T9kXrJd z77W<id!x(lxAaqWrVN;futF{gxiuBt)`_8rsM@7^+m~Gzgv7Ip_db|Qli7#!IzGrh zu~_lOjpCO&D>=W3+geJgr>g5G3u!;l_OO{OQN9sU_AUu(8lFTu8ddhc=z8n0sMdvj z7)1o6lx~!e2I&R?Y3Xj2&Jk&eQIIYH0i{N|n;{2AT3T9$o{_E@5FFBP?X%B&w&(j@ z=f7E8*NS=8V$E~k&mHAH4@`2TB?{=%9vB3lJdi94eI2^MLL@Jb#Xaq>#Tu6ftB0Fg zvXBiR!KB#80|ZsLem%4?Wk1K`!zkl3xtv}tiiCRE=ZhZi#X@k`YRE68uine^Z`o3a z?W=hv)Lcr`*QfSMcNF~~Kolpjiz8lUey`qD$##8z+ti2f)JcGbT>Tj^fr?%Z5P5=z zhwBbBki=8Cl53%N``RK3o6FYDzV*oM3_H;B`hrBoC-yY#GK8B*zZN>_NT784LD4Hz zz*-FOt{q(sf)fVIwqiD;4sPd_Sq;cuvqv6GK=#O0Jb3y14(+@`L}Qm<Nj0iNhCej2 z9f)K*Ize8}GIigz`rtq)Q~ol0Dy=ZH-lA|LKZEbXRBQ>Y`W0Lnsl$%xtid%LSe36x zLzYgL#TU--@lkSB%CknzoRtZBrn53{&_{6U2T4P%@ieRW6u00Ef+s7Hxi}d6YbNwa zTOsu$1Qw!Gn~=>Kr>!*W_I3V)=ERemF>#eoSYcIR6jc2K=;En0weA&yfZH4B9g8+T zp`G*nVOXlGsS7u(r6onfyzrq0VndIJsY<B-hS(HfQ<QZ^cvh4Gts}mvJtz-x-P<Z_ z34~VL7QxbK$S1!f$R23aRO8il3lljc^xQjYD1?E+FS#*d!AcO)Q2wRwE4$aXClS^x z24Ne4j<ce>4Qw&yD^clqjVTXFV(hj2vI}md+a3GnvXLcKZi;UA-%VTd53CL-;hi_v zo$uc@S(g%Uo`(!cEnB}Apj=xVCd}@k`KZ@}6f!IOmiS<RPL{3D;LBVQeO>XcD(#MU zNqhx+k%8g)Oc9}I9)?|<nuP*pi5%5Yop+*2sQ-$3*?gf>#NR@IGj!IV;a-zS`gQo3 zTJo74(7+OceIw6xJr{$@&tTO$#M@>??Wcg=k20!C5xVEh`@En%QoQv>1NY~zUR$zY z+qJ_eMAF;biOK^X5-k;LPlhVhC29iEw<Ti78uwF&xoN&Tfjf=~-s)-S+omd@4K8vl z)vxmR8{t&D<xk|P>ZE-O+fs&R)5q+S4Tp)fTm1Y#s&;Ad?Q-Ecnu6jnY$R_oNQa7~ zhYaFZ3(6Y{X#0Z7<QB40XZ9}VFF-f#FGX|{T4Jj$V@|7cSt+NHhno3$x+$J1aq9`o z4~0t$H#uaAJY8(N{s$Db9Us^&woQc3Sb||dqIxT03ud5N!$?#FX{4QRjt=!`?H5VP zs|5W6bO8wbPxMZ?!asPtF<1;FpB6eN{XzSdBWvC|gX$~E!E-%)?f-#C<9b()ZnpeY zy!!Kjm9KB+%t>xu(WsN1FJpZR16#sd&JFyxKdZg}L}Pfaf09ewEB~ClxOVb{H)zX~ zvo4KX$~b49;LeS~hi_!)d1_8)lK~2cOW|;};2$KYhgZJ(R~v)hANaggd;<ESH$mDH zemwFG&*Fb$LVW8&@Yjb6*Bw)5cN&aDuXJ^xwULO8Q}z_eG;5|WJdc0SXZ+Wx{;Mou z`wx`teSVd;Tu?q3_}u;Y$(r9F{kje%?$=+GH&Rv1|3Kp47dt>FDGB8IDidb~h^+|& z^dU9C^z?I;yNO_=W1L29P>7C7b8<0XnGiz#3*F`xnCIJn;3wq`*MCeCvww_7Wevc> z_AWiU9{!D^el#4ItNSl#`V)}Ydruof{<-C9f1u;fMAw7>T~Y}-IRO9UsLpSN5O;~E zh5nMx2JSjJaMu;3@ENbj)-56b0R1=oCg50wAGlsXr!<Kx=s!T+*mrnATTL@_tb6@o zTK8U}_%P!mPMjdz$Bh4*3AiEpUzG@`p8y%qG=0Cdr7n#v(ZR`2>1OHuln|gi{67@P z4Y88T*8ndHbYB{!G5z!T1CA*TAmtzi>T5Ok|EWg6F$APJxRq$Y)L{BoS6h|l@E@OX z{xnBar~K)g!0GvGNB=K>79@M;;sbM!xTIe+XPH}DIDb?iK!FzKN5DXG|0N8$a>h;l zOAvGz1^yuh0^*c@ip|f_t*xAq03s>)6^Wk@j*&kYvn_b_3iQKO^N;RioR>a-DWaAa zfFxiT_<(HPipn3LPcerq7vVtF=N2GRLPCMg6B2;+nX@zIS%w2<lfTQ8aj0goTGx+( z|BlX;u~welU=Bcy1W+X_pv}khe;w7^<}a3NOJO(ZL@dTK^pB0lcp(hHe0bz4L00X; z`7+QJH;_K3CZh2~3qtF5diTKvUMD*@tqXxZ-&n2%u@qgPY_nOmDd7cAXg|D>Y(EF( z0;58+bwNNE`0vkWtNdTqn!CIlzMtTb3wTA|)+XQ%?NUatg(M^`0S#=YELgP*qF{F2 zC|lCc7oHVC>!U~r<>D9eO|w?L$BsA<0m{X0t{c4c4dm9#8Y}~&4U*5cB^56YL4p$J z;N(jTYCItj6ctEi)h<w3^l8SbHnuT`iX9##2KFs&pEA(Rw5mz#QeVO*puo7HLy+4( zhhzb+vxuPutx40T=+U&LVVHQG<-&f<=8I9G<`@GZw$hZR_ulM%VP?@n`yTeP#L}-M z0n>aEyPi}3PL^Dxj|Z-$+qRE~yhkMe?dkPrZ7K5wY4oQACQ|mfJF4j$;t4AiSH-~$ z<!+fyr+w?u(>|h&7Xnq!iKI1aW#1OA#23zv41@UU+Q{Vx=v1G!lM1d1zJ)oU;0dz| zWWgdeTl6}~4h0LY5;bMx{yFkvV>^--3|x7p5e_#`mnNP*5o)%56g|xridpSfP9KO^ z|EO1<;|klU&}i)^EL_dhuISbt6&n_CcKs=@ur=NdlT#q^qJz09RSQyX8o)M3TDjNC zRpttKno{3c-^rbYt<z4VRz()^z-Elf{1Vo5@vev9L@RxB`5=mbM1J92!`ULgL<Co1 zgk#Fu-o$f%1Sar#4&u?Iq+#<q+06B@JW%NTPQhvA_9ZboBl7V6oapz>c8p(H%}RO) zw8cR!OXq?;$Y3--7ez*yYyUZtct>>#wF2FT^f0i@%k+1Wf$xgJdqW(j)T7MXFmkXa ze^XCHAzmi?i?83<RC}n4)w>@<M6-;?D|*&e-q1(&lBnr7VZkM~t`pAma>D@3lNHgZ zw6ccwdM)tSc8@v}HWC=KMKrycOy`k>&wF<=cWs_2cW>M=-X8O4A4q4MM&{u&ylN?| z7*C%K(kKFZZ?(j6N3l3awq1hadX=hKf66u15BcP>R^5?&ZKm=3k$_Jgv8V!+$EXMS z0e$p=J4o|-OtQu)YD-j*DS)?+zPcz63+l`CxY|f6)paOaFkc>EThJxKOJ*`kDI^yr zC0G;*@3VZ==T&O8u=u2g0nrb1sSp#szpJ>z`xZ-wb_4JY(Y4T}I()i@uOxlfpgz1O zlkeO|&pmN@2!Y($n7}6_TH1N`DB))Rs;8q9>N6G`gwmzDbi=TOvo@t8hX$-;=??qy z3EcT_r+UawDq4O0C4p0VmN><!qS$<v5evIJ@XV{BEcpeS0nu_i5E<fW6T~f=nxca^ z+RcBp^czQVBlO<$qiiSg;Rvtb@6u8p#MboCtOB0t#iJ3c617Yrw{+TAp1b9128Nj> zWG?y|{NMzH7+@P-!4-@=k+V13L4@>0tVGGGFukMDF0wHfW^kF{P*vq&BY1Vg$H_qF z$juvtzkd(KLVDc|xg$@gf$j#~bG0R@36}EwMNbOnXk!;ozdcygl4$P)i}!rdE9~x+ z=x0zXEzcPV(<;I?57<1wKF`zM#HMz42l_7Ep)nVz@~~59mq?(eR&W$rvViCOG95Px zNx7}^ttNHoQVE$zGg7K7mS0Cix=&!d5f@RN8NZ4W4AOC2{LpF_RG5U{17W&ULo47$ z5Am-5^rCgQnh8{<(WwzVTXT~3-8L#P(W}z&k2_7{4mzj;rkk&_;0|(R$iy79X*a!N z5{6*Q<_>x@(xRU#T&JnEZO+b_Hl$cJlk-CG!-6J{z=nNl0M8I_Il54u?J7&we@!7V zlpEeQ6D)#~%VnMdIZYpUI!y}D=8L8FiH>gY4}4E|Xw_rXjBj8nl<~f%1VU5ux8`1J zHx8Z73BF7su6W;`^VXs37Go&$%mKaaz~TI19|U*2t0v9{H`f{n%4l%)6Li_Iw5mrD zSJ50&D}B*qG7?tc=}R-aPU;EeM6YXll^9F5H6@r09@0=k*c)U0H8p}_wcRL-*v<_f zVs<&l1IA+mz|lfr{hk*X;Q|5!pW4Iup(a-23LO~GwBdE9yk{n(DVy8G>L&+Y1XTKE zuvge2a$uhUZP=A5nl7FGrY+((PV|X~^wAQN0A9Hwr7+1>sPpxd(0uZ@AJj%vJGK;; za_C&a`Qq6HB*#XjuZ-KMmLl4uB7Y~&qo&WBqj%y-Tkz$h9P(QqStD^Q@Q=PL;hd@I zVu4tS)ucWU{=&9AT}u;sCZe!Q)&Z5}e8Moi>!`e8Q90|NpABg^`0g*5ajPCgdat8o zRktsTCC26vh8c=VqB2unLm}frKt1%@V;Ll{m*dR2>GfYznuy<Sh*$-mg&Z<Zb{ZaD z#P9O<0l<09LDzyZf1SFy>~$K2#lsq|abw<~WLL{Rmd^DwktAaDnNNe~YcsH8+MOMW zp2^B>q|os@xyt-1n}#ZVuIX%7nCx>2f+?SDnB6JERkRN{PWqs={Cd8Vss)pj08>C| zG(Lf1jBH(|_VmmV8M#EP`8Vqe;~t)x5GVKUD4va%h0fdFR_kS%9|9vXx;tr_z|>g7 z{@38RpF}wZLt_YapE#n@X+>YY$({{M75fzHJ(|0RDeN)}{2ON2sf#C<<XBxKS-g!X zdMu+5LIdv}mEvQc9XV}Nh!(U@zn-1vXo;j+UMq=RY#SSuv=0*$&~mD_Lq^5Goj-Qc zj$;%~Q!qKddLVZKycMIj;3P0!6wAK0mLUupW|Afd)k-rLqe|ggcTDm>e9`ljTs;R; zKw~L0c3e7L*^x$_=R6H(GmN*|nk>%F&XcLOZ+%W%SUi=MQPWE+|FEF%J?c`G`+3<= zW>sX*kZ+awOwUC2wq6P0(5vEggGQ;(>x70?JkU)gO-SSS*-nlCe`Hf7@UkIs-Ij|< zt};;Jz5g~pIsX&O(9$vcFi-u_kWm>OZLyUicx^PWF^Od7nr6zdCzL^GE7QGA8^Kz> z!ajEk2)4VhO0{k;w6Rh&lHON|Symvt`Y7uG$Twy~IfLmj6$=QP0HVIR*K-R#wHrdu z%ZKGFZf}mA<|>FAzbvQpcwBU52SuZdF&@L_0ZDyx(r+_*X-tz&%|8qE*&DwwN>D}0 z*56Nm;#tWt&fdUMRFSMpyu|FL#3R7HJ5od?+0pE?T$7*H1}sAfZ_+N)d}Zrv3`u)x z9H^g<hH^?o6?ax-%=E2oMxA$<?pw?9QMsl~Z);_iH|X9?(`CMD`q_w0!t5$p3-${q zQ3r5#HRlSCo{zE?QaAez-&N&bPft-1_)=IRPQBAl>Ai6RZ)}1vH}KE(UU<+?u%T_c zNxUu4hcPc;S~ZQsWo%sx1Gi;6YKt?xj%Ds~b>MnZcpZR%Oc4e_s(|rcW_gV7!o1r{ zGv{XUW`v#P0%C!`?!DTr<nD)U#2`oiWctU2^#Zf8ibnEx0$%j2fue%d6cV68TI}^R z51U{!h0riAYB_NPk(y~Pe_gv}A0_vLol2rsdDqNSF2|`vG7{ap)!Uky_w-#fDWIqz z(Vrbt*A52_J!@71Az1-lT4FtA!*uVvo^MU}f*ZO!p7!h<jc~yn%naVyMe0&Sq*Tc3 zxLZrd7CA(x9bW3ritdBH&{J0xS`+SrE*0~Z7IZ!>@adKz+&x3;!K=n!-5@kD@Y-P_ zVm#Jo!J!516!|l<`D0JW2B9y}!`QXu`za+K_I{cAy((px`T1dqhmjSn(9pb3QiY8> zb(w|<VHosV&>hz~=z7dg?H9B^5_gX9o7@6y`X4113{y6n=-(Hq7-Yvhj}vz#3r`mg zxIkG)bpz=qbH6epI%E8i+f{bt<|<`Y%PZqvFK^bLd5`+adVhqqsAZ6owZF64b(kFX z!nR39W|pu7X_b&VRoXYUO(H5Z`ZVVneip1I(P5?f%__%<xVzKnWX0(lT~$vW`Q#~4 zRp`|yg^uO2-5WxwQsi*+Kso8rB?1BEwoubZu<JfqZ|;L{Y#4A9Ka`9v0E%pz-m4BB zb@B+|8%eQ979!UG-Ot^j)MNKkUF;dTm-m<VJuJdmIKb^Re^#{YWXo3y+|W2*(h>Fo zslid(oOYxkV<nPizZFlXMr7L#feOY3bECkC^7P-tGMXTU6QJr~4<xUfnYD#v!6MsR z_C-2#&s>_LME#McOmE+s=zdXHpirNdRk+X!SWukVzszbEq;^gJr4J&hf70>E{8eFi z7{OO|(+y@WB#-igFW+3$5DG3_{da^+4BmNoSkH;J@q0Eq{R9zs*+|F_z5H&aQZ^e~ zWdo%*VpEC`1Q}o1d<)Y*g>oBa?;MpXBLKgirC~N~=r2FZc&)@G(XWHhm@Buu>Yy+1 z(9JE#Y#TieFK0ja2%qI-37lNz`j55688_`O$Oa@;DEyECoq(=x&DmM`|FQ8HPq7UA zRUCEQvGSL_L+;Nl(HlMbDwH^;p^%p$yl<+n<X6x2ZvIt?*Xw3`MAHVq`>1Qj3gaBN zYo%YdC+OceBQt;%r54?M`34{^--5SPTh9OVwR|SI^H)Dz5`fCS>Ik0yVmYTU5p&0` zTq}8j=Kzl7TV`D;PIdSf_|eI492`KnUIF=Ys}%S1U)YtcAAUrjdycie!mCKHF8Ooo z^UX$CUI037$pc8|vzXItR0Q~k9R36VRd0VL?FJnAcg_JX4B){*0L86yWY+zFeBlpo z%Qt*~H&!CEF0boK|I?B)0CbM4T<%7+0|2x2Ux5UPZ)6UI70$NcIbMi!saXL6CB@V* zJcH`F$D9}R3y?E=F5I}IA3$BC$C>{6;BOq+g(E;m!Z|&Wy5o#1*lqtXKJP1j(92M0 z(S{n(R!(zVZQ9RrME`d`4b!hrESEoR$68nD!+z;eGDM}n_Fk^tEkaANjs>%vx&Fm? zgjzw4N8voOtqPl2p~fpe&NGEWv~j$13Gp~v1jG~K<`Pf7{oi%d46tWu1w+o9SH7A` zJpR9<Hw0TKZ}sW@IIH-wIom2dgZ8H%XE_E$8#oSUufXHtm!<#y0;XW#q6bezZ}ejW znS8TeeSJ(e$o75i`M<Bcyz@T$R<o4C(fD~RatpWfm<{;aac5HkKa^d#NEK!zz;;#~ zS^!hYQVW23<7*$BaRJ@4jg>Uc49?4A&`|p&#86eY>@z9uaO!nn^SbpCEc*UqtB|f0 zMB(6xSeF%epciro*?i2j^7pVL{XOt6MfLEO0-2z3=|=2yIs{a@|K7biQhj2-7Q7x^ zVJ=_%Mw0CBllkUSJ`gpV86(|Ty>ip#oSx%E{>3xEf$GOn-12{4^Thw%jN4VtubG>X z37+FUHuMt*P$n(?w!{V9sXY&b%YjpJm>Q+mXTF0Gr3jo9bsYPNI+1Lbz9F4K*M%)- z>@=O=b9;uU)M@X<xd{cd4$vWY*f+l5-9P(!Gx}$aX^$<*v)=QPIEMzI-#E^y^|Fo& zy21j38-k3{lQ<Jy(75#`6+z%h>jEYSt8v#d*sSLujNK`83Tk`D`JU@pc$Y+zu%)X7 zOem6U)03McUiERgydhsSJMTI!<>+}ye!%#ee^{_xUNA$G7LzzflR7{Di$q=z1)WGS z<5)Ucn9EHn1huHlDOob@zR59Du%|<u8DlkRk!eWUUi#ts%wC6&Lb|LjW&?I?hEBS{ z5j*0h;JBkArSu_dz0o~0d*)!dHhkh(6O*Xh1$twP4|WiYFbp7DRp`N=^kKN&0?*K% zsHzt9^mOF0Ui>jAH{GYl6J~wdpIkE(o8KJSDIO4MP4pDw)SDE3eIH$&RJEfw?_$wk zgA+Mxn$o*$FWN8hjLKYRdWCKvGr7#vlL*Nf75ZSHXbHR7Z&HiRM43$G4r|h+`;{@y zsu<jG@$%H!b$gW|@k+FgzZ>>8xQAsyEq#SJSQ`sPjuY;@mgv1=l~d9t>lHr_O)A6M zslYlcY1g2!0bU@I+Q(F$4k05^Bbhrc=4@%O%_~TxEX}acCtuwvjTfBy4>yXqj7q@1 zN0XtKt&XdU>olVb2%fz&c}6tbyIGCsioSiMm*fynTc6fF4vVaceKu`b)&z_58U5<r z>31E~%>0w_X{t$|dC4?7CggDjO0hjXp*V9;%b<_nt+%deBj*ca#bQnP8HI<bF)f?J zCQf`qR3TD=^C&ZH8j>W)3NT}?UA>snZkVd{Ws;xk6FPgH&F#CnraHMRO854Q0Mhvf z83Q+t`_IhFW*X(#U|MAB^L3YQP5!Eo9B0wO8pkTGW8R}7blT*H{6oR@OKU(9)g>TW zk#5kdd{5=dqH?u(M*1hDp-<1)SgK6P#0$=MRxm2rUAV2AS%QmU)4_1|TC?;pD`1#< zT|6oSa=Sywx<h5Z?d|XXEKSZ_Pw2h1M3mJW`<+04UM))^jVJKcFrJ9f6{M3PU>J}L zUGgniT1~^4O0Z5n6{JZ>7DAhGmkLXl(tPXX;HUn*b`ftPP|0Cm%_#jGm;@7LsXS1E zdu5*dRR{f_YUXzgw<V5*EnLGW8oOk;_}=F8<-Q2>TT_2l)<AKZf{xmETKmzAtz~#B z&oIsRVp=eiV*7k&yJ^zmDpt$w&D?QouA8cVrc#FH`$aVv72+n@jtvE>l8pA**4!`; zkC-)zON#52oCj&laUXP?J%2JatKIK<1bv*q?KOAjIlRt$h|Ymej@aI9wZL7JOF!da z+c59W`}4G?s;s`H`iZ=B78%gYG|h%GTZ-re1=?w_6Te;WG6{Wi0@xWG?eaOG;7Ow{ zo=PBwUe45Dx@5ZgQ4`I5cD-_K7pit>zUENXs|3+4565?}1@|a`0EKHREWa=EO2}#2 z-mM}ILd-(ki(YI=L0XE&E~*<>bGBZvKPN7)XK5s;?I4De!d<kigG}qOeQszw02}%6 z8+1!uQZCb=?Z&A;f`dSQp6o7Z^79*&wK<<FUw)o{Ktp~2XdzZV*;2zDYobWj&VUzC z0v)~W9UE<$2!U!b_1U3Wd*N}8T_uO3hso@%W}jbL&)6U932X}e!UTH<i<@i4myH4N z+3JITV@QsvBv<K0?)YMy2e+n1#qe@A{PUJWCmZJQw$qsjtAbJ9n_OdOy+meB%Cx1| zFH_@%s5;VIMeQs)9|AES-=pX?lVo|$Pv2fJUOq#or=e`)Z5~~fGpvrDCV_8t^1>%h z7y$ZBm)=$Lo9pC&FFxX7m`wDf%t!l#7gt*`5@{_U#;a@;HUbl_oH5WgR#J&|L|*jL z(8oG6^M_5WcTAMDee4sq=&jYT6S_xrC(_c)7}b4`PlLI-=)%44;>D#4He;168e|7N zrnp;R@{Ji_RsN)%AV1yNXRC_8lG(JCYmMWAxH&$Iu@9QIj+mH|)xR*kB$<)51PS&4 z2|wm5t|D6*9-+0`>kZ~zjP+~mp9&(SaCsr0=I;16f0ZE1F{c*jG(8F4B_bRx;-s4j zH(Evc9XdIQ&gi&kEk^OS!IIIP!gi7+z3!uE0pk?Dr*`2*c=3t0d@8bhi@>V0m_ZTY zE6ozVEraa9D!PI1#@ViA`umsn(7XN1Vj-{Rx<aX^#dNW1n<mpFRavP`ZZVT=v;&74 zj|N-q7Qa%`+^H=5)&^~@YfTwCT~>FDR7zFmp|XGW(kT4veY9dt@Kw5k3n&so6iR|X z1Sp>dVspw6t`^Xl#pMS;fj!{xhl;RQvbH3zE<5-(tFt<C3<cig9~i#b>33BuFBEKn zUBe6;pdov^7hJ(AQ)1w|0U`UD3e?UOPF{At6e^<h@ASUf8!g~3upVW-(Aa!@L})=f z0Ve3i%EckMz1JbF;qUBoTsU-{k0m6^6RWi}WL!4jd?>O!0dT*pn++Y6zf#BRsq9>C zF1=V+sK!{4re{fgQcD{Ab!tX$KGM@!UIb$su?J-m>AAk&)(D;1D{P$MfAJx@dM#jC z+??V7KFsz;eJFkC{Yy9KReZ1=T4q%{vS>{=rjr<Ab&Z(S-dkp!VT;A=53>sqTtfJj zp5)QRsikk_(c%rHTzX)tE6}eObmxNYF1Ujo(CHs%siy)`4Kd6S4&Fu1uQVr=8+S~a z89XV+Ch;B;*dy3REDQB~+%FgQakVi|s55YNXZdD#wc65`P?jGp3yN2TWrCQ=#4xX- zSYE2qS8*#9@sMZmWol1k7dSajo4#w-T}*G2s8`4l2`<?tTP4*wx*R7npmT7IwW`<a zeYT^MwWJ|6^{(S2)ZDQ2kc!_xYl{7wyS%hU%`z6$m6)kovsNZHs@6jS<qSJ=E3>Pc z{KinmkIa<h`{B~`G?{PiuGYPy1u-Nu#Z`eUE|M(L0t|4qjF%eNaQ?$cn70RL6@UnL z18nf-#AJruDgt{=g~y6%EB8|9B#;3=n7#4usu8n#<{~yWhBjn|Wuju8vt<o>*Uf1e zBX7MTklknl;RS2Pbzk2HQM!gw)=fjHo6}kLO%n``hrK+B9X*QT1EA4+TV|e8V(0#( z0TXZ2Z>)M}3fq$Lt81;fNVdA&Nztwnq+EA!kZjjfsCp?lITg8n0#l$~PdODX($FhX z@;dL}`5qu?__Dwx4fJf0gG&j@vSR3(z0Q;N;7;RZ$>}VteFE+biL!u)$uk6GUKn9? z;zEi7q6{Y8Io}H;Q4G8yf5P>`nJT{FDW)Fg^}var4j^SHu4h)r<V9VCcM)nmD|A@@ z9(j^!Dly2t-Ba=R2y>X%Bk@X-VQs$nLX~>TK&p-CT823pFoU@~XRy+@V3)vRqSk@L zpMAAZ>Tbj5C6<*V)g!D7<|W>|!6TF(zu48%pIned!pTC}T&de^dvysByM!f{D{dy# z%|oMitSr7;YZ1W$355^!o*LjMOy3<+ynlTaj`U>gxA);7TRAecxqMhOe5hk!(vkha zBFw-=IZZ}e-tfTL3;Y%;SrW-@C%lcUza*s=<I$wee3c+!Nnwy<C7WjuXSQv$QS|Od zm89~#VQ@ws8e>D!j8;p8DYEo2$=GOR$(faW2N^$&aqtW^CCI+}<#6#4Eo1eKC5RY? zEWu|b8o~7IZ6gV;-gF~~&W)LU_9Si#<KA@5l4S_XW#bvjH=@DRhVhrztiz59conTb zVh7L?r*v3fBpDG_ZLLzfCSX^&b*hoqa>)RxEiaWZ=-=6LTo@8|x8mV<)6q|}T;Fh` zp4x`NNrGvEX;xQox0bnJ)0LM_C<1|+OJfgE8$mI&Db*m;B)ax)A60G=pFX1hhH;a+ zvEr>72TkDw`j5@~4^;VsxErfcw-$>We4Xd3*t4^3dEg>R1IAzNKH8h<Jo5E2k2L(a zA*mT?j}fJ!e_xO>)jyT(rc7qI(^wE*V&FSfV!+e!+TcT}PBw-#Jt`&?H-Mqr<^h0Z z`{{mG5RKCWL@w*qFC&KezHOh*zh!R(JsNOKlFd*@KPhWD^iF+<!koUnYDQ}z@qqkm zg)-aatzT^ei2|KHYc9D6lMG#xgcK=bdv8}XRXQQtvwh09cMIJ=)l@3D+tRx(b6`Xk zw$EJ}nr5q5r$mc$sP-F&pVA_@ALjON%rq@1-tmB$O*$lCcse!C3fAP`B7-0_32t40 zyf$~PCzo+j0Mr;%vAf0Rekp$(bLe0n2^Q_)3%cAQ>JtCT)<E8^GUBiQS_;p3t^N$A zUARuWBnoK{w76rcWiHuw;+mb=pne6~TF==q*EYlO_J_D!5G%+!aY+YMigCYS(}|GK zmsBzBMLxp%YbDQisYdeT(vukWG=K)ccRQIbMdm`e1I7oy3_s(xPY7Tieb#6BH?lOe zEb)ZDFH)Wv?0Y)4`75*GG(4HN{$aXWlc1P#O|94x$fTyw>$aDK<x=Py)$KXwOo9m^ zZSfHRX*p+34>Sh2(kE+~?*WWX(2Re}d#f?}dz28DKxHN+b1MIG7??HSesb|}_-`Ek z@#`>NG?>PiSinp91|7FiiH>lVX}vES4ZWY6jyl(_-}<Ou`oON0!rG}?msxB}wg78U zuqsaunFlxGk<Cy_1dq?>3{f_noPxvY3h`@hYmra?1G~E&8E%gSb>Z~Sar7^~>kl}o z0=UnA(E!h}Td7n{x|n}?q5h8>aKQG)h`uTHXORnFJQW+7g@+B&Hvli#;lI33_WuKA z4`3abd|T)~ydknrz8<V@A4$4?Ex2iP`Be9mYCxeIetx%F{6Fl2a%mfr^eX<Xk1RMW zr`j)1<kJAwLko0{1=1PyZrS`z66pR7f&I_qi{l}Nj~Vg*4ZNpQ<O(*K<Xq<Ei(Bw7 zHi7iO!~X|icQ`OX-BRwpcXGcgw^Q@)9YgLz_Od*|>q`pnE9m|N*~_#J+N5}XIG2kQ z*ArEY5W_!HI3F{C{{M%+J)UqQ)gb!wqWqW?BVg_{QTY1|ZQxreqGgZ3>%d@b@ml_Q z4iNS}?e(;k$JmHd(xIth>W&-kfc*#PAdrD}!H?tlZ_Z=u--vz=R|UscUYJ#z<0jL< zKGBy=tVJvM@8NL6vL}}h0?&`Y=5HJ&i=Dstlb6hYkJvYKTfJMY2saM?Alp^Ab*OGx zIWsrs#cfnBz~umLBJ2N$Fo?z3KT%Vi5-_$R_gMMsUU<p>eW<#EKP^KG08xXp3S2Ad z!1jD=Wvrk~;GfT*Z~mw7*p$Y)8o0FkZlLoYTsN11P)9~c9FTw^ymB(?CIFSS1#WXX zpv7=A_rWpM01_^bA=hn5>sCu4B<PG&oU6J^t^8%%g-hI7_a_onx8A#rl75o(HRim# z1T&yId$UO6@*wh6Ar6^Teoa7X4>LR34=NFPX}h+&&#T|Ga2iLVIkB3_KSbxx_GUQE z;d%1c`@hOXZ$$msX6!o|fV!3goE^Ib;0IPqI8^`XElx}OqwMH0lQnSll$VOYx3Pqr zZ(gZ*`62?suOBxnocxP1!YOkHqfS}Qci?0B|9pHS(*{t4cUG$vP)OZh<Hyyf|I`HE z_yEW~{MuM9-|oYAqbqz@E^l2Wf?aKsEaVduy1{R*IcD6UX7(4i8?G|HxlEo}_WZ^v z)~;WAInm~Qe>fqWPiby)g#^C(?l%tfFpl46)Nmk_4V@Hmzpa(1?EBJ=f%VF~5(m#1 z`LcMJ>34~8!Y?u(L>??Pr#H#qM@<$^hPGWTKuCI-9|nNCCtr?=NQ)LXhi7`5z%Sbq zHenWUft`h|U}Ga6NQ5n=ydV~V>aisZW!Syun*LlzBeH$XG_l#4D@mD8XCZ0)@xGG^ zpXv=?x<RV*1vKQEfaO9yz-<tQg=5@$J9%2e4b3kT#AzGbW#SyZ1942?&W{HVdSty- z{aT3XG6K&JyRPxE_kg@!DO)n&7wcT%-A{(+umzXXcAFieH#hei={yhUxo(>sX6g#2 z^qOYL9#FaVCz6sD{@6>=H96JrT-Zucz(+!gqKNdeUj}nWlqL0Qmkum_xWC|Mq8()3 z^iyBY^zhqd?^UY8>M{`ckt=uv)4zBguyTEm7q|VI8$@EI>{|vu|8ccG#@^K2!zV1z z<<-HI21{oQjk+GSt&`Y;UfjdV9~`e9_E-k-#_=<|Kv$@ipLm{VWjTLN)cVAc9kzRq zy4xx8{(D|F>3-O($4c)C0w1NdxMfQu%jvxqPF+CkPh<1o<|IMmaJ%G2b9?TlJ>1F9 zlr)x-oSjRA{h5p`{+ey{U96dMB{q!7B{Hv6+l%Z|V1>)XnZXY$g3TbugjtoAwA8_L zI^$vOl<10ISiw8kRN*4}d8n_dfQBTm1eGT!bhKre`$&wwY_N#e4HVP+GAT};XEqiU zyet(;4=bSec~B&!T^;bv>s^V7VU@P_^F?ku2kFJeBHD{FNL!y6phEU~UTU$_#Tps8 z)4$CbX)ha<s6ME1H&MBa=SvtNzStU^<(f30lPqQ;*d7b67@%05FG|nz;AnkFH^F{X z^JL8W89@n7^iefchJaB`AbJ2<9fKTo1rxfgvFw@Ly%%(=u*ZuhoH1W?(c~814fPDy zcVm5sysVm;pA}60nk^GhuDFFIrHQ9`(Hv&aRudI}vL)L}shZckvkKjw(M>kjP&f-z z@=I@bt%Ru2CtvWpVBfiU(M+`W?O<Ow7H$`Q$TJX*tBR=1vw+CjmrcLRJoWav8g=!3 zwz|ZV9NZaH9B{Z6+2NgsO+r4UNp&_Em(N*~6aQr({>aKY6o>~uA!Kz9UE%hpfYtRT zm$}$zJmA__@JEs129sTVf{AA!s48FIBDXf%%G94?b=w_2qgQ|SZjiodcan;TieXbd zU7vt%ldV6LW+K=QBwvNnCO;*?@0ND>@Y*^tu6R&vwX?Y?UM<A4u539upDIx<vF1S< z9m|VIq*&5B+osz&H34RqdRRB~PupPexd)Rl`DN+$X@g&u5s9RQomxXp^~2;Aw37jj z$@b)9Pb~GxPOkNd+nM%?>&Q<H!#ssje&t~l)r^?}GbDI|VPmh`SI)C!N3aUfN5uRV z%yZwz?`a{Pmq_+Ywv?Ndw>YV3in(6BFn)nCvMf_0l%8?pn#=4pO!7xptO-VU@&!x4 z&}97=-+weT&4>ZB^}`;EraTb;`Cy<V%(CTq?lQF@SE{3OIAftle57E59s1Z9YvH>@ zJ=HBiwl?fikkw7TCGGnG5ScmN`{Mb&i!#jPI=Gp%MUC(Nd$Nu@%_8XX3*_eBXcfS5 z?uVdkBP>X25(ejf4nyuF_<q;E4<xF&?AzQ=sFk{@_w_r2xr25NJSvpm`8N(#4T~1m zv=RZMmT30N9K9H)7$j1D5KoX#Y$j5c_}D?e&I(`qqQHifYslG4j;BS|2_6A~rI!<S zZ0Z);7iPi?wU2o%tV*hooupF!WScDq_lIkJA0#G7W6ft$yVtmT?wJ@@j1xu`m}mxM z@}y}R3mHA9o34^v+ny{V9Li;-QA-$-PIHjFAAi>+b1Yn;S1XI3(-Nc7E1tixa-sTA zpL@FMff9Mw$R{EqrnhfcM4cymLfNq9Yaw>FlVVK9)nP6PWn*o(8nibx{BPFk$`vBo zdnfrC4$mSV>J`2{`kqerd|@Mx;hQw`NTK~b+o6_`niv=}vM8=+I5*o;(`_x=2j&RX zPnl{nwEFgHz4el$*WC7Q!1F%IY&cO&@HE0|P|fMk@btr>WOt=i;It)#L!GD5Rfi|X z#rEobC*zK7V_Nt1IN-<jEwL~U*tMR!4D=<bT2#KE3N|hy*ehsxi#jUlNWqT|KD&_h z2gR4)9=(bS<;RMwjqk;k2AEo))88U<{QFQklb4*UhxZWBzUs2TtD-XaCs7T`s?#6` zLvOyUM=@l}COmFc*g(uLWK<Wwj9EL@2I1;T|Ly@oYm}L8bfhloQQ_#v_4NB=zj4|q z)UNAJVGi@VUlg9hNkhMd-mZOk{6(H=_EN2A`_LW{j@^*Ubm-`|&_Or)?LJC$DN+`C zi&6_8M(o7zF`QP@Bl+M-Tra%5Gn2$w<F7IrHT7SX#HLrZAcQ{@94edCG)}6Wo33U= z%W@>4@qy?$(-M}dZ+&_L(*+hC#5{?tw&sOb#k}`q#i$5%pe*(%{V^Zs7C|TL!l1bx zg-C^lD8PQWR;6V*1G`b;n#+au%^xfaNYT9oNX%ArMep;83rysFl=OLfQ{$nHB9Rt* zz7^2-wHH$HmzA*LFkuQQUqH#sgPF|*+HIRh%zoq8(Qdd@+L>}G_)<hi8i+dTvlqB$ zkefzdia;^H2F4eHEHIHtB~0=tO{}{pE~tWCkkuOOvefdjcCZem){tZNi7E!yQ;}FM ztDhNgnTNf{x^*`rP7^LP<jZ{BJnh4}f?4tw&MFl;`09C73o3+Ux!7+@8lKXQFu8it znxo35Dh{mYvVZJVIj^MTdu^Cz$Y^W_&DU*Aa~LMoej5*n%_Wl!`(oM)<Re&=DbbcU za!>orxHB_QMaA23>QdS0R59}8SQvz5Kl-_2xPMI;x&$Zdqzmm8&y~fD_sYl__L*eN zVcfiy17B)C%wr$)=NqMTqxD@VHE$rGc^355j)CY6Y$Xwx1)$b!yT&7z<**}w-<$AP zJV5S(Z&_pW5&Y)W9+fu%QTEnpayFh*0>?x1PRDeo)L#ko-DOAk-QfA4QwTN-@DgxN ziVc&9hv=HX>g0txFk<CBx5Q1UpL*D53O4d|@iygARqNlYWBg3peXy{{(!}3<NhyfL zkMRM$Wud;7+G3{7oU&$SoopPu)GZpWw&KX1x(YkFKUIlLpJ7j5%CSF=(Mx(`Lle)} z5b-Me*3pg`qc1@lrX;#*lvjg2yCaQD#k!wV1oUL-^FD3G@Hs`y^Di*|zO;Y@$9rb( zYS0Rcws-4lM2ec8Mr9Y$o|R=oPzi$~4MinQS`}B%?8WOOOc0>`>w0n-Sm{cgI#?Py zCVzXf8i<GT#%oT38H0H5Dl#PI70d&CWvL@f_w03|U<xEbo{OXT3*<)V$TEexr>reT zO|NaLu}IK?&Bd>7Ty)N&U}3TCY!E~Vy03!wX~tNy&d^4x`g+lp32q0P?=eD)gpOX5 zp$Ecc+17s5#&tpFUnfRYs4(?tcu;kVPFWR1wK}El(`D`BIXu)AZM9TDYcWW6l7)^h zGh)-K0}OkwIWeFZA6_|@CkhTh723R-%3{+d7@I*B2nZyj#W8RBmi&oh*owW40q%yQ zl=joxR7ypXFj@9x`WzI8ygI_50_6YcLerO5!g)yiox@Om0UD<9g;KJ-(L0;p)%cN= zz3W;>R=u(7i&^@H2$0L*Ubf3bfeEZ!^-+cLJ=%%VY~u>o-#EmO)&2yeU?hY}p2OvQ zE>TtrStY3Xt*9Y|HxOp)<aatb8bl4bt{1FF>`+gR-OJIl9MQR#Zc$Q!bu*m^4QdYo z*4M|K&umsQth{44;4WmhT~?ri`wb<R2H3Z&a)O%hTC8U+6v$uIaLh7x3z~O7q5aVr zUFZ#MYqO*h8eo6FwD;9nb!^xi`w0zMWeNMq%g=l?#zJ_1_UW93$^e4DGJn!z*|L>k zXxTB@{FA!%nC<A`;-eLzT&!YGYd>jR!E3Xf<ju?yg8ocb!B46}8EmoZub^UNfkP6S zJiOSsZMxN5W4=v7<#)B(8#ZH=7}1y059seDFv`|ZvB<iWa(73_JKT}<zcXo;s5w=p zF_FmRfmK7|M*~Hookb-hsTorT?jxo_Ik&tm2R*-c-MX7X-Xi&x?iR60Ntj2KY!JHt z0*N1cN$)c}sv0Cd>3&C+#=?q%ZHRndgO_8B74!&?h(U8AT=2ug)KOo-=v*o&7DCg# zFKpR<maFf4UR71>o~kc?Y|SJyIzIlYY4&Jj4VV4dt>hFFvjt2gC`#6=C$0R2@a#@E zVY4*<O8Vd~RfWmxg-k(f3*Zh8V#f%P?zyne3J&YF?GVR?{KYlp`Pm$nW!*GG?+A6# z94Vu4gI}D2f&AM(y2RM50dxSW?|F4meRCo|^%#a)D?|$Z$|3zhJYN#KlJ2AM`(smV zti8$0SEX==1QC?(Ud<X1AGG?89{es?FBf=yIkzRII`cD~C<w3dMf46Wpa;DlnBy2y zdbsLQCfRMa$$IKfS8#XTdKPYUshqcU&4->X05CndOYQP@CiFv7#%XHtdWwWnVdB<q z&LHa=>Sc9&b$QRy8ic|7GP8&lHC47(G*Sc(`owLSNw$=tqpRybebIRrbCLLp{yQTd zW~v~fV6O~rM<8$UD2Lgxc66%8xQyOtllHi@Jh7A2*ok{CM|mUZjvItJlmjcwZyqe< zhLrPGML%is#+H~-r}COrG-$sR;LovH#bvE@6(}~BAExS2t>HuGZt6CoOCl8PE3|6v z?7nhM&sDg)f{n5a3Rvr$Ve51*X>AV(I}o8YFMOJApEw#0GW(eHybcYI6s+NE<hRwF zdNJ{1#wJ8b6$;n@L9VA7jM|Lh!(j|=aeZdVulgN0l2Y&5z5}o3*;010U60!~0EvM6 zZ06Ra9y~+*WIdT=(H@m{eswL!{G(Mck-*wTTB?FT1F}Z^_&Ncq;J&M3NOZPXuV_(h zp3R-nF|U_byD1wDT1%Su60Q)gLcdZvX2$ojS!l2t$c>OU72UN(8AFnTMir6qPCU>x zd`{{$iLbTjZX5aT98F4;bebK#G5z_d!id5`7LpizSHVRtu+n!oL3Kdwy-Sn7gneV> zSFJ^ncAQBOYYp!QeuErX89!7s;O_}{0Eh^HLs6s}G1UcXQf>nV9qWH_a_$36mLelO z$epHj1B2A|c34)>$>Mclf!6m){a3F-95@3tI;;xMhjfloUpFnhZg7m{s%A69AF$o2 zf-i%&t@eFvfS*lckL%;#IGUTzI8|VPT>WYeP!4aeU)1ydW9<4&TKt!$hxxxkfGX<$ zXh~;yjHg=!{%Wvr-AMt^Jyid-MR{WpP&46};s8C<S8njXvwUs>lBXLB+bl<ffJ3Fm z=US<9=D!Na|ELz{t*KV-10OMGZ9&cnJ`?W%%!PCkFq`<w1IUvU&hO0j*<m@a6%D|1 z0A>5lq=^gXpKfp{+>BZJA{`FImCXOu00Rh{?10!Es?_U_@#}ZcX;VR9Nbdl&lg-~W z6|gVRGY9^98wH$<em3I28onjZfm8DV6Z|7;C~(mqfU`yTQ}qCgzJLCK@`eSXe{jFR zzy4jyo0J!HvLS%2Xa1Ds7=?dzZi_Cl_)k^K<GX-%_&az!p5@mzxVtsP26-)K5fmg< zY;4*+Kyer66t~EC24J&p$g^NI2fFIqfaCc6qRIFHJ07Ner7%yo9gA}&yCa>FE%tNu zoX#TkLQ5YAngZ6H54V9hozveqh?O-@NKr>ke6UE~nUaA4)>7pie#2c!sx_k<KgsrT zR>$!JN)+2?Wz|X+c4+Fx^bPiJWf{)lSD9XYh5^e3qyd>rK1@8b6tZ|FVUihlyu11( zN9{sKj+b1J7pBe0X&$0yOSJ*xpxHVozv?fO4xqqAuPw#J-n}tJi2WP>cQ9HLJn#0! zhEEH)7>Rxhv4~5Acs*aRnDgaT%7G**Q>!Gtc=C%jK}2&-CC7`m>6|QqreDEmbzP<a z&&@T7m{7W^F6|e?y=q1QMFG>=9<q0Pt7um`PUYGONxzkC^c<68S#0$1BY=5{64-G; z0l|CvdOE$!bE;RKwi#lAKHhF(4T}3@7cp#(ha1GViidc|BJ{#tel%efaL);1AFf2z zz?h0JUtbmSv(4Ji@_W==3avH4oSK`PU!<ydd)GCM90@EwUMMhIjG@YjRXzdjD`KXU zu5#q@cY#Mm%)?0++76xC(7ws^M1<p@(9YY#^B#f!;;QEzMFOT6W0U7w{?hwNu>vf; z2pc%4e8E+~vkI!Em6pl-^@q%?eX@qB>8(f4fJjAB5}ZIt3^3`2&s+AL^C5260c4fN zeTe6;sh{c|53MU{Ju>k$DBg=eBUKf@va^gOE${;4aFrGuavQ?<-j$hY7B(L&SE`<T z*2l)%N%!GK4BIh<0FD}QrFhO)NF~)##w8WXaOws2#@ZFVwGtkz1ru+m=sa1Pu3pgC zYR+UT#Z#=_b^jS1B@0aW#@Wmj<T(%#{0O{K1Y~fHV`TNsT~vc4(`k+=K`~0%Au4Vr zw($x-?tpj8f!R0C2DlN*0z7+=>uU(6;J+Wm$XJ|-Z-)X0zGlx_+ESi4_OP|y$1KwC zfE)G{Hv7pge!|zRGXC(peY>Ub&wos@)x0@JV`BQt3WD!ptT^GZ4YmfMz$6^4wt|>D zO~z`uVC<A3J@SlGzV93-pJA*|MrdgK)>Vg#5*Y%$D1Pkm8Pzg$f3WxKZ(>cPmz}Xs zIhGHKk!*;>D&sNQ_{K&uXG3_r{a}?#876yK6YkZ)%2!3Dz+~$Z$T#}=8z;f?+kUY5 zzvXI8)4u<as~KpNwC1W3GV1q#a`JmY$#pB`G44b7i%>FfS0^BL`1Pjoqo8aEMy5}m z9m6PN?JK!o`MEyQzFngrU50M0CE+)YKkZvot6OxTImg3C=Cbet1|<F$$o#^W<~FCj zZFG%t6I7lvb`13totQ+DmIuq7vA?i8<0?f*m_0~Y^LKYr=?Q#Au*s7y5iK-Kn5OUR zG}BZ-+0_1OLeN^b8;-QAmDS2t=2{JIDz=MGb&=qRDo&5lF)U+HCFx*16En%+p904N zN|)7iI2w3!#7eVw-bc^v%^)qEAGEpoC-s`9pUbXySCH4Pj1tFx^oqIpf&I~~v}f|Q zSg+qWw@-qNrVX}&EwTG++H?i?uHIpT)F4L3gG(EMx&HIPu;)Sv7tP{+`wVa(F!Dkf zs|8T5P_*6?ZKVqX@$|2tXDW~D@&siDSqBJ(>GbW$*dTmh%IK)FW=wI6KS~_!QQcmo z;eC~!vFn&I0(!^a04R{xH<n(lx_>IjI%rN?A7rdaeEtD5MxADn_9!u%yH7`FSiRkR z=kgRfbD{xB#;C=?HC*Ry*qGG#6Y<GZ@0IbyW?SlIzDwPx;qLd~R{NyHII-D?EE)!- z%QJ(!Na4>wcp(kf<hq1z*Mb+i8Gy#LTcx_u)_$Q~-u657f=n~<;mR)>&y_6yTA(cf ze-CrP?J|4b`~`S3$0<+NsDwMCU1#ZiBh!!e?hL#5mf66}U8p&-e$|Vp*Hyx$0*248 z0*cxK2!ajJb4drq7@JQh0tc-cJZ!Vx^nom@nBAZHm5aS?539AsqNW5>y9q;_M(5c5 zz#lbQJ)w*Rec#(oL};X@3I-1<js`~uIpj^L3l7>_2DPB$Z_w4%{>V<d_+BqRwnqcc zA0;PfHg1*AxRkq!d{{D@N|T(5OOQ8%8hj`+(4VRHtF*fG!0sazaCdU$&`#ZP`~nKZ zrK!D{3ef`0mfs6f_%U~zE>+J+Bgt}ChdNDDs?0NMdI1#?1)AN49~+K&xS|c4`C)Cc zq6$S{I&So6Iv0P>ryJ7Xi!@~U#7taQC{WJcvIMe*ZiHjhdS2hIK`P*cexu*`ge?4a zJ+;OQqH{4=$<o?T|Irjk@<VA$@&zG{AZu??192Al;#m?9(;47!eFrPEwgN0L+yZx- zlk~?T<kMFB=ZZtrtQz75Bj@d#o2QnR&FN=@oT6VKl-c@id~@^_3hE&wSn&>!UDOwY z4-|8uzD!Psnic8gqvD0Lm{)pw3f={4b9fiF6|0gj62K1D&o`BFA5!#|wwhMyF0@M5 z_8_gej0<cMH0R<X%#{jVRAZwWE*UY@CCHU1defK_epRjYX%B;gal;@scR`OLeLjOq z2i0%-(>~XXxdG)6hHDD!3Q8h^AI5+_S}|#vUNB5luly+|v2SWvJ*P^L#loO`7JtFW z+CO6a=KfAF6<T7z7Vq-jl<04qcrbw&98Z+~pym`zw);!y$$1E@xqi?A585vIscLd+ zI07&=P*M+*XIJ+^QMPx!2cWv8Gv0|kG>+15NV%O>m7g`lSIGDFp<2Qx9a?-7tJ1G* zvDYqRY;RWKlp)0|X=~dv@o6d9))JmU?1+?x6cZOYl!M)w2$kWDwdMrP`~r6Y2J+PS z8J@+Tl&w700<I#bjb}g%sNA8K3Wt+3GX<9DGj_Nqm*^@V?m`4K5_QfP$Q+WI13Hdb zYGlx4hICTatD}56ItMS3%&JlnhRRRo59D=M!OX#CK$0sNSuh#abhXNL!e(p+>ijgp zgE>zqX~a=2*W_sLaneX2kqDoR>P>D=ApReHtb=`yPG9I@Cc`*IluZ8o${yE8hO7bF zVj_9pxv{c0Cr_$zy-%s@@k|i4@1f>UFW8V}LfJ0JoW4ZQHhd1&`X+b)qbYNxk=`h& z!YWo(LuK5}VY|<Hv?y!5JSdaT^thcTX>zs4SqVNV)C=!5kfS}T=v0GeHH<)})H7>T zv_l5^X$3T+yplsA^N_8Fw;9#3uX9|_I?3o_^*gC%do>d@XSk+(;PbURIXvInViO$b zUwKs-L_v*THWs5aIiFuVx)jPf^~vggbm=iG%M!|bjto+1B@f9Q)?pDf6`vATX$f?; zOWQQ#h^Ru@ix9=o^B>}27rG($U?LtUTU^)v-#8kb!XdFg7c|JS$yE~)2dT`0w|bHh zu%uOZOr?VBN?a)0w5Xg`pBGl9TjKUIVv^tHeCRihNir&0b#j<}+4Tz<;-NA57b^|w ztp<ie;0G-RPXF_e?9u>`U-XQso5!5oV6_>btYSZP)D_&z*N$rxNm>0o_HFB;DZ6=t znFo#M$v)^1-&1DNKdDo701wMwEa0g4aAxE{UHBU(W2H=D7z>HHro={|p4Lesd^T;P zAAJl&)d3Mg`enpC;icsvw!da}OmjFDwRNc;7Jsli$yRwiOjbs0!#~maAOPIIObDIu z`~jWeSA`brenZX~*K16g#1yLM{(pSEcQ{-B|2MAHTBTO))!JJrwWY1vMePx!woufn zsGwDQwiK;ddvCEx?b;Qqw#2HPsA>>-|IX)kUHAQcf4+a*|0P%AIys5+I?vZ*YNWcQ zD@=|vTveFEihJMwLlTW-YqAZ*9OYrB`-!)3{zRqO0PXcTgRdWzTVc#VZq=;?E56o- z$c1@fW|ze(&$J>cPYa)XeAIk@e1Tl)TmMRZ^}fh$AT9H&a@J^kY(mUq<z9Zh+p|B7 z8mvYdjz5BbuTiuPR$&{y1DfpOH@=>=um666bY>yeM3cJztZeA>;gC0BqmlJKaL@pZ z(xTTyx7`w|;86dd1XUVYQL_=-H*PRpDnM?KCI|9h_s>*nJ2(wv!$%u;;UscODqp<Z z&NFF3QrM^bl<e{PmaX{8F&<wBDVzuPAoQWPhk!||MuPMVIxpu*`z*TumU9UJG{VwP zJSBriJ0g?ebR#a;jG?xfPbu1DJQ>mz&ceu+pckj?8+bj8G%hNqaIq!Y8M|_Ig;*(E zUaESjv3y89PljgIj8K+-@@|BU#C{NV>#WW@7Q}Mu9d%Lj-hREgW$x${aBsKt=iYsH zDn;vlea>o@KZnhHw_jSDS{KKZv+-_~kGG8&F|y}SN0*&{8_0_qVQ7&O=iRE75A~GH zXg@5_HBJFl!liq5ERT4riDhO)RD5|t|HdmIFE59GPt%K*BPyVte#|+}f4!^8HLh=c z$E<a2$sYP+3vR9k3LWZZ4(IaNkW9k_Q(7IKI?WsuL>b;6;7{ZO53qm7#b%LT-TO{< zUpm{u<dVmohvu|)f&H&GzHL1(Hq$j}3%ivZ)5N8@H-NBJy41H+>5|u<j;s@V$xX@U zs>7^kyUD^Z%zKye^sux~>fKtyeD4}9-W2|<0Y?QZCr?z9AZRW~XABr=(0*<lI&=Ai zXw*z8uFjUY8_U;{BxArua3xaRyfgze@1^VBEO1Tko9vK2Ln=*iSuRq$X}+Y(f#0Kn zHw;4px9{an8qzcgWPUDg*GN57h%=%%e=~bO+b22+oY+%r&@?Zn9eOChyurj;;f|`9 zJy-pCS(o}8j#BHO|8~wP)Ap*HkNo|`s-wj<EhanJ&}vTGKx6-M`?^mIC3SzCsXk^G z>+~jUhz6AEkss_$sLUl-LNAEP(Ar%V-eBcR?W31F&mX0W&?zZQDu{kdcGN4?4=ft4 z*<Iyovz12dTUr=*H%5C7-79#&S8gn1nc=RjvuH+1O()?+Fu;*VtK8#GTL*_oS>WX3 z<yfDxJ0l{voo7xcitJ_gsYvq2WZ?CKw%<RfGct*a!D_#CKg0)N%4KPJ@OC@eGaLp$ zP2`cCylCw<eROQDe9uTq!f2bN>)rX^hK#QUgV8m9TGBn^6~?LlrG>8zp@Sn=SzDWV z&Q%szL9;%%Nv|TeXFr}(Rab%iQvr5Xa6`>aOS-q+!2Nl2Q@lS>#3)fIH6kUs9n+nO zt?fOI%A*1~bEvxZ0F^i%QnZWB^;cbiL3By0!n5!nDD5%^ihD7FoMMLvb&(*_Mk8Qg zVbQ|v#QTH77s;xOL%if$+aJ43%M4KQSAkug@VeYTc{szMcLUrvQn5<2UK`6Tfwg-0 z#xPzkON@<e73?W*3^V<1ab3SK{4r&2WZLT^n<%ExYrwWsO^tIhq>5mU7rH~Fn-QEz z=YXF6X>V|II$6}Ik&u)barAGqr1lX?<4F^}Uc<%m=N}T<-v`mL4HrMNN122j%2$d< zCy(_s1ea@v*{m&^a+cy7w|t42>$P|A>iykZeMXZTRu;X#O;ZaE6k>G^7mO2?e&py% z{O~&q$Plk+GcJw&x~r(0S-!V+9j=asL<7Y(7w&r%f7xk!rC78)N@JEg3&L2y{Pbdn zj=#H_S4rs;$G;7?;FPtxaBGLtSRmN{kDCBaAiF)Ot#bG51D_73_#E?8$&AA=m2k$( z#8&x*O~uRppyPw`4W3vvnhqQ!Ayo&7f1BrqKncW68fzD$Hk&=N(sk_2l02Hz5Sn@Z zAH`_zGaJ2S*m)Z&MX<ff?-qmo?nTmtvOrs`$>QSkm(=n~<yHowvO+Ru#Uqp_vjTiL z&C^j6WA**bDOHcT%~wv_?7-k_PZZj9CDdtHb#11$GZ3Yt*rwv5ioKky1k*whYk6Yp zMz_Ss?%Y`2`D<5-D=<w=ltj08)#UzdnAL!BwSjy|cjLnyHiZdkSf-hf?kCa7&Z{c9 ztKhRrtYJS7b9^i9Hz^8&<eVIhvV|pY8-xL$vTR_ClNgJD{IsIDHP}c|khw9MrZ&Ys zAP$%6Yb7}17|$U1$Cq5crXf~#9z2vyTKKf;g<YJDR<T=R$!Dh|#V?(CO}6@sOM}m! zncX-!=y#u830>i75^R(@sKnGR00sdIfThD6A5PNY&6;c_RUv)7)4GU;9Q~$+_7pda z74zEo3C03Sdj8T;I-0K^X)pB-!r_f{4Ur#G6PZIylF1R6YpaX4^+I$ps;b;0Ael#b zP*?;VS<?0Iar`6K!6AX0L7I%TeUlGr@}CqdmKhm06&-Vwx9%-@XZk{gCtig^pNI;L zyQ&2C{G6mI-wyaq<#Unaro{TjC=J>+Q!J@F3-zsp8dO^c)N_wS>P-93oO|jY6X!t; zp*M(QfHL17$&BBJq&|&)iVrDY_|?sVQjwRf_Ivqp_pdJny!hm+<yS=Vb#+d#^Rkmh zVj_I%@+rP>!(x!eLFxwV{h879%hPHy%+e6I8unoxtR-dtb;2Rk(KA4zvp(_3`Y1Hy z^;Af%sT&ad-k(A%2yt)1&ULKEBdOufu>$E$bD77nnCXBeS_bRK-ob)7KGKNk&qo4> z4sVA!1j=p+UFfm(j?Ggqgk9^jT@Q;*&lSANSL2#2)u2s8kd}?stS!{V8=@rc?9R<w zJUy5Bo|47!<?xU)PKVoSgXWI;-;8GB_?wxAtqfH7S!z6d+Uro%OQ%OeU}Q(6_hP18 z0Oadqvl|A&{$=nH)JwC#BxFbxCS3G$)6Y~Jcf{q*ZLczPx|!zxk>?ap!VfzLfaw7M zuo2*JBlh&j4Z%Zs2utjIZ?HEFu(w(1zgUZxqj-T$s(tNnDbZbfH}mI`JF68tsoT!D zlZf!^B)7PldAR|Y2|6#Tljl<RCzKr&nctS&r^e7eb41VrCh6g@^8Gg}r>|m*(>L5M zpT?Iyi+cTmrZFZugZ-Te{8ei!e%l|yN_d76_Xl0uyI5X~i%3@nTn$x@(?ZP+4|KUc zZf5yE=#1c{T+|SKTFyR=f3RN7@nk+!Xb;4#cGn8uyVRFaUAmup_icBfvq!15WwP1= zdZ}IKYwQtsfJTbSigvkp&EFeWw$u-4ucgnFD{EH9`^I&qrn=LDuOc=xyAubWZ|ie7 zDDb_%uR^kGI`kw_{D#L=tsW({Mp%t*jc8CP53NB%8tWvRLEaqpq}bLt!A`*C&b^pk zi%;m|bZgt@TJI2+FZSXWufGUpRqg&&divw4K*y;WnQYS3n#sHMB2KQ6s@r;^<wSQ- zKC*g$LX8gsUAs+?uYxTZxe&kq$dA(3-PUnbrwd{Nb2|!uD3H%IlQ|&kw@52YJYNwy zYXuzdIoD}~1}}2@yXA2<nrD+e7Jn^h0vxYOeUG8`;u8t>Nwc<h#rG)UX42vXcooCw z;R32d2Ui=3;DHSGfNh{~nC%o@wwJ!olvCAMA2$`(tlw3{!YKaJ_@IK_X7qvb@OiT* zdO|O6CZSP9*`O%ZB+lJ;R>ZfdYpW}*C>14o>9ftv4zn7xn$VZL*E317KaphizR%uX zSll!RhDwt8v?Ij!Jjc2rN9k|H{_}+Oa>YS8`{nDmAE_$MvGlJ+*<Hhru1lDp!v=V$ z7CqjOHNJc?)3h`*qWguKg6}4mrC4P-byCHMx-j3CcU&IhLH7+ji#0wT+vDY}@&M~g zk<}{$w$V~r*^feD<~%wwQkK<2US<U1z>VTY=Qt~hq=%IjJKp`Zc#)RFQJmkm_R>BG z7a^z(&_!iAdX`%+x-~N=tMDgIeeqn^xqhF+N}XiSibHga_V*Aw-p??yu{f&7;i@RG zvj8nzx$B>u`g&fo>Zsk87@U1Y1IrM^Wa#lu?9S$ER>swe1_&FR?u?3{61Xgfdwl>3 zRVtLmPh#>Kak3787+FEbsDDTzU*Maq#JwHj2F66~hb;|$7#ONp7&OmIQMPJx4wh1* z4ahfaS^$`BlaKc56#&sBlK<_=_-|~FXVE$t!1(|;G0YG@Bm12EF`CTdtd(VGl8VJG zYkSadT2;*BQmu~&e*vU#=@FS?*C9y1Q^S2*8WQ#Y0!Sxt&wLi3;U2<sEWbbf2Oxcc z`)K_qbpv!xntXAD1d7b%|KEou%ZolbszJa!kGz~x9t!ztZ@oJ=eC|>DU#IMw%L)XA z9U^Cur;N6V|LY^f5ho_Z*tX(O0?v^m4TINikcQKM%jBfa$$(rl!1Ve{@U6n+p@bGO z3}8Eur35!3Y9?%l7<PFPHke=VR`6d>J2dL*L@Dc|O9>|sYz=eA>E-*~NAzL;Lsujp zT+*K7-V?8+@TN1*$vG-kS9{8r)oGT?VjtXm`r&P%D#@YQKP3OcgiH7TWoLhWW9{GH z{JatR*WHdObZf^ufsZX-L39szJ|~s5vHzE^{T9$m^?zuT!hioJa(Awc!<wyLdT+!H zYDPXINsBnVaip?tZgG|l=z~E3zqK|^lq=l`JEt4~sGbdgqH-VnN{Rf}hpR?XNFy(` zmL~HWT_%;cmvR;c-}u+OX{QBD{iE{)Qa~m4m8SN8&e`a{e*4Tgk|CV6K+@+%E6uvL z?CUs5lqM}36CfIby8q|!psOp;hAmHG*d|@xA1w0XmW9M4#;||AX3?n};1^h>?j88* zWN@iPi!a?IQs_g-zT|&7?MVXuAK!qXQBza2VQVIb_D2-Cb3nrNB9R{Q`WmhOM&b_; zkn@`>Ve?IS7nC*JZ<R+4@u%^`w%U_&u@71ON@I*F(sm!p224FUui;HVXu)~V&K2?) zpjW6!4$6tl_^XY{D0vHOgG6!0MYecx7H!LWs)G~*J`ilGN8WGZ+F!u%1c)FO4YJBD z2f{+!8uUfIJ`VE<VP&sPfr+z#3SFO&>K^YL<RNmkl`yyAvi5lGeE#t|Z~&l&9B3n8 z^<TPGO=@nmJ?U|c=1!a%&gLJIKiz2nwbv`34=`?upkrW5%zm1@aQrB`H}f=Ct`!kC zYM{+7;#KOKANz|%DD@F{4>~#0jslw$EBL<f*GSzsOUA1)9VmHQtvvocb_hM$w=_G8 z2+lh9JmS2{>|G%@nqg6`oJAm6+%BY|j#Lc1jNR_G$RvyOtSVpoQxg>Cddy95#E#eY z(*n95dVc`>c1z)T*gN*5T3C~l#r5uWEpOCYg=Feb)M7@TYur9s^KHApR#mv3^66*g z!lVPL59<lx)oK4>c{JW6RRUU|Z2VTiZs1%-9u-{RVX-eS5V}ntz|~d5d0t>?Z4Uh_ zdHpa&HNxrm5;1^pJY(sc>6G)s7>0v5#0gqwPU2_PcihL{Ws@0ehPKvHVx_`6)p6ty zH6|sMjK$Aw_q9lDWO6qWUeUfG`FRC^Gyrp$#DmammjlJ-@}HdI358JfxWs0>ezU*1 zk!bJ4!l&a8UpO1lBT*DgT2o<l^8_Yy+DJ7vR466!N2YWC1zDOaS9&4_OfNAo+YodZ z*={A^iPd7P5K8$v#MQt%Ab3!7I~9OwF{ndXd`;+G*gqutDA%;d%)f4>sYRso6#Ic# zK=xe0=)owW*pJnDn`u5<)VQ0aipLeEZTEDXB&4S@tj8E=p0?%Q_zy7E4?gt8kVN{g z$oKvA8JDyaS@d#@Q@bV}sDL(*c}3fcMDQGHZFnzc0UZXV0}tt-b8q}<y^D4q`i<Zo zGwM#Zwbau{-(=b}dxYUX*Zd*Iu`YEmT1N1lscl-Lf+ekKrc4L~6=e#B-DiBOjOpSB zHgXCouSz}OKB&iBk6S?KN8IH94rK)Vjm5;9u+lT%_GyV)l`xOWFsSB1HI$CqZaT?V zH2Gj2>oEXoN=_8SX6{jP6(h<s_qN@L+LIbQQi>`+ZhHURM@#16CeMnoEWKTRk2+`l zb1eGjkV_Y@vjREgE!dsBckGI2_{tuHWGZ$d$o;x!AB~Nap85?T0a;%(T9LqJkL~DP zrNR;0D%>tYqGKegtGp0ms$_13;fo<pCbmzWHZn7ei%TDONY#x}#?UP}p3k2_@z-#) zXU12}D)%;MZ{U#{sG}why%i{2qkK8&;jlMTRROGdI4#qP?la%Jv~;MT_JWn|yGsvS zJY@-<=MlE0-#emP4J(MKal5!mb#LDq$VGTNqc3Yu*BV!J{3H@|6e&2qM>%vm&wh)% zmwl*%tm#g+GO#7qU@AA(mwlKx@7PEg6qMeXZ}OrM78%tVKh~9rvzC*RmmgE`7W-ye z`Pt<k5~F^F)dW|AjzpK5b9+%;qaEM4lI3{;0p*z#Gd{Ncm9QQG(E68)l1fZotWrxf zLB2y5a+np34Q&kL{*)d|=MgS@I^){<*2~JWKeeGOMIf<NxYG%OeGJ_5FNbsr@ij|B zb_!U}iIxB#xC&SK&qp7I-A}yYMmREpitAhB=uTw)il@_@ZO80$A0Otig?T{U{X@cn zbWY}i{k6I(Q;{#)Z^^qYm*vTao{dh-k35v@SDq3`?5vEhY*e{+-^{^n(=A<*Y1N9D zgbxndI9>#QYlnm*zSqEQ*T<E$P|0zEoihPsdB!uvs6+39$P`6~T&|CH;0et7b(9RP zl=QLP*#6s-m&{BKJ}_3}4B0}^%AiUGeF8*uGeJm1_sv0e%BvKe@vz(7qPRTT=rKPf z{N5*N1&`^0^0JXcO5+HTf#-$tv>w)ofMKg2#pZcUUZz{@#%bC_^JKgLd9U|-Ko&%B zSmWx{lc>o-U%3oIZoz`B=1XG{o-$UsE-5Fr%KB}&<a%y}QDE0N)Qi6b8cuXFIv0WK zwM<Z=GS(|~BSdf&RvnNdb8FwN=7V@S=Tuc(&7BXdWF&93C;cFDp)2gsu_`Q=+G~@* z4fZ{|Mr2-eCs^eT+4~#Q&^e`&FSo2e)93aOhG!4$7UEQ5_{MO9FGP83^FwJhJjr{d zsMKB11rQp`8-R>3xp8Pp>+vsDRWWQbH(vSPcLhJOvHP+!&bFhg2^nHG^`06M=eD&1 z{#jd|9gx$!k`^jwO9*+Zn3`EWn9cmQ+?H-tg^6DpyK$bFPXu^7?kp+WDc{I|Aqy&y zjGG<^!$$tnGM_6!IZsJ8?N@SSaoK_6VfstwzF>X1F&WLfEmvc6$L$)_^Y!c6rW!(- zc&T0>D+IF6WzlPQA0L9Qy#s9@h-JCB`faxYaWgP`=0U3C;7O9Wd2&{8o~p_Av|igW zQ|bji76;jIeP64hiY-KI&*V=N@9i@{R|VP|W}I3Wt(F!I1LacEoFHn!up{2YoSAzr ziZ;gv>irOeRurHOLB@|_0nUwDE-QzzKa}geb{+O+@h21g5}Wf_uBwl>^biQkpE_GH zMNlV6?0fd1Ew77OiW9>s>}{Tfsf1DxR9VD#80m(dSPo)$7hOFqX1O`7cg{^RJuV6h zN`Ha<v^&u$vLXGc?D<8fwAp&aB~_Y$S=($vo4s|KoO#6VNREh~?_#0~1cXiP%cGF( zy6uq{yLxxli{WfSW2%ZE;YuIQTH_cq&eiX$m<k_fYVs8~(k5T{lpa8mY=~`n7fR{Y zKG0o_t+bx@UpSOqs4l_2{#d@;^r}Z<lquJe=YA!n#Fi1i6N8=Eivb@_JBIg0h}i%L zJK+XSEfJj;ondWuR9?M{q*w9u5I{ytRqr%FL>G4q<F@Rr*3*x+FqTD8($~B1x_lbW z$IkaW0QBEUk%5@xXj(LIpY~{gth(<@mXnnR_$W=3i~r4dJ;FGiA+5w$<>+F5hraho zAS|xjz7@ptBtBcw-pd>_ZT$;1{YCT0KxG~&FSqomaBz7w*Q3X>woDWT=TfxD*UW3m z7fq54D!p8OP^wNJU8$q15Tr-@CzC0pTItUklG<F%y_0tRlqiWWUZ)WPzt@d6#todq z0`LU=qAxVz$8MdmHy$$@Y9vp(B))^j+W-D=Gk7Z~5V+Uwg^?jWDc}ITrl&chLW*P2 zY3o8v&+EGtV*Q{$#PshzuVw&`^MCKC%TvK=KCBXM2n{;*(={2lo!wyfv(P<GGxJSc z9q#+mRJApd0$u!vBsGLN$HvsJlNl0G4dxlvL@?>mQcYEqwO7>K?%Yv=e-i7hs1(&L z7I6@Yj1ZYCwU*7A#0r!i-ox%=s6mvW_dp3wQ{Mb1O}2jM3;h7eqN1n0i(8IX#}t~` z)>;bE69>8W;wYBn(a`HK!~Tozob|96NFB1T<IXf9jBXiU5XOj~?8P3T7TMBA7AKTT zTQeQzEa=xJ8NYdMW-5Aarm<_!I$Z4c1A~JK2aeV*7{p3YoMP#FJ!jEO>FE1mSh9FW z-+f#*oS(*<`Q_j}2Boo-{2a3aQ@aNnVFz6}a${U4HxB~;4g(^=`{}0x4k}|Dc@!cR zwe2RL1@#n4bTMo!g0i=^rHDKYg?$If<n3}6s`jl*8x_smqZ}x=lTWNd`9^T~d5$RA zo(yY(E440#`nr|Sgbd0*?5vBXIOt=?d%9FXwr;a$Q;~J2Kn#~IJ_f_&jsg@~5vhG3 zSL1YUg%+xIL?rS(QNgYKc&IA?L8H~rF3WBaUfVqu+Ee1b6V%oi5qaxQi~2CV%KP!G z(UiM=B8;zR8R2(-485%)(2_-BXf*eq%}5|rd2DcMWpW-%A?9oLE!}HAihWfd3(t+t zU!~Yk%sK@K)Rf<@6X=ZV@nrKViSm&BQpAiJ;?v^4w_w_;Wv>5|qj{$*Oz!F~_7;;0 zv!|iionLxSQxIDQ!?qeaejN~uar%iXjs?Xifqr&$ACtsBAUY#rYN-@=>y|-8*z3LL zxg50bKb4`&XSZs{wU)h#1Rx)kP7>gNi_)tS7pRFu;LM|W_0ZllnsO3)2GM;9<I>{1 zzv=r^1jd@j);t#OBObw<O_VjqY0C%-Q(-P)TzH3LOkTX42PpRS>p(H4?$}CqUi_`f z)|?cv97S@vbDwA1LNN?e8?1?hE^ku8Bk${d;_ZQb@w5zkskTpKM?ImN51IcV0cJHc zpOdQ*LP6X#p=3~o%<us=`5R9xPvcI%N3|hZGZhdi^-5#D{w_%^U#LzHPXGQ^-CN~; zht#L}yO9)p(gtOZ-O~2|+$P0{xGqzMo8&cSJ08rW8u@K`>gx=i=oc3id;C@{NJIKy zk?{?ZBG|QSS`uLkR@=;JFynOQY9;zX4gQL`v3j}tvqDiOz8U<Lrs<6IMl+@6GaCwh zCjA$ngwsRQQEXsOV7ry4Fi;rb=K0d)K3zB;oiU$_PN>EQ5-Lt{*vDih>|rQ5Fd*yV zXb0BfBM<*v-U|xGfH{UYFEt9ld>t{f$=TKH_s$&`O&rQdL{rz`0Zllv$aOBr5K#tS zT>dbl)aEI$Pa!Zu1@rtW^mj@ZPS20D7A09ng`>FUFl$@s`aNmgHet7jqhSqN2Z`&6 zQX5i-d>bCNq?l(Jf7u)VLx)=DcjQ8AcqP1eFZEX3&C71k%laOZ-9Osr&=KP)>2p!g zl`UmOW%F+q<R~NEQaW_}ex+`Cw%Y303g#r2jS6uJQYn(LCyCvPsg5apm-@|6I!cJW z&b|7XnTliC7JG_WB`PbIhXza^WgI=bXTDv@9&E=NP7I?~uPA;0XGQE8Lzbs3K3pVa z+j8m=HD=@LF6WW$bVX;>!&hupw#~9!;7fLbtt@yd!|826&)v;noL$(ZB7ne$9d=#1 z(!Q65YXZ59O^4){5baLS7i&wlDpSk5sLFxT30|usAsw~J8=<fidhb9VQNgW-R1`d5 zy~_{1mJlFCiceV^?V6TcrL0R}!oohvM+&gL8tJF5Bwa<O5FQQhV_lg{#_FW~)3gp> z6d~fbJ;2qbRg3yUl?Kx0NF0z-$4%yw7ZFq}+BSQq+@V%@LS`r4vju2~5fZL(m2%Zr z{5^O-;e`uvB=0)h6X&{K8VfhNREO&VX<XR($Fqo_(0l4=F1o8)VBy34@hR^|JE!O? z{Ro=sZ_`A!#*s>T5`K-p+5UiRoDUCkz7jIJssz+Y-uOaHbd0knU(YJ{JIUirmn{D& zusVOZ@S%87ik1}LXWlpk(vG@V!(_aL4i3=vI%8?Rx5W3qrY(ha=sQ$<)GTalMePZS zs+q|+p!Kw4tU;1)n@)C1{YrmYdJf5UFgyvTpXEgSxdg!wyk3CkW3>f=<lNs{9@`48 zroZ`nmxf}}mR?F196Y|PrQJ5gX9)LU>JTn7%N%hT$9%$qIr37mBW9{QMyqD`zN6wh z9k1H-V(?N4t*)d4aOHP>gRqg$vBskt7POibg9A^pN)O%5BX!DjYh@x-OT-v;n`!KK z?bDP^eoKY_LsGw!pb{cktJZ>}HN!T4Da6<9WwJy99Pi@xv_Thid~s3dUbNG`H!=1k z#{3>Ay9W~9X?U1b6gqQe4#G}i2?o;y+ai36WrMz!QF5=0ULg9C;tz+tpGwKB!~5?M zdR_t_M>xkLPwHD=!mnS|z^zIMPjJ!iLREGbEuz)9Au#0g4sNB!;Qho^e|PL|fmkq9 zWnspX!3#z<>zBUN3~3+=KtZGg!^;QzC^#$5J2HSHsJ5v?@lU)VU9V$0Mr<iCZsmy2 zq2LKh^1BX|-K$n35xKvg57v~?%cw+~5GG?rXir(`&2bMM(?<A|r##vDN=i=6mkUWA zVH}6tMkg}%cehzozaDj+2~2z5zd~W^RX?iVB4N)yN2z<F$*s4e+$3Ycyj1g3`G{p+ z!%p8%kn@$a3Q(A%*fxi-HJ9%&q=$`8CR+<?V@%l6F)IBxpzN~tbc8aVG^Rn~(mx~| zvbS30YGd00$cACks2(L7FCof?h?!e%Ty|&uEhKsayy@n+{PQXG#OBQ#!9qizr895x zJv(mvW2_^35tfW`jcJPU_BvHOTJeNSbN(Pt0`ELs?pOIpL_g8~<@b5)L#&FyKO|@O zlQCLDw|J;Rf5@}sDuuXe>8oRI&K_QZ*$92UW<wu&S$hqkj_ewgR38bSosIvTBjC)m z4~OjQ35HtfIaczcW6OIciAqT}b=z?X);4viKHI7BQJFOt1kyh2Nc|U=u$X=g%qxVb zL8R{IHxngX<_Q(EpPV(b%i1&<qZrc>AgI}(r91pXfJo3_PMNj)B3!9C`$QEn7V6wI z>CJEV(kWZPiU|xIe0<l5E_iM-s`IgD;pCaBw|euOY|xQs$xM^-pA~P|iyWbtx=k+~ zM+@_w9?mG^k=4>mC%7IeR00l~D#d2R9aecFyg97#VDuc4t6*6Yi2;9Eq&SR^**x)Y zf^A(s`$oxc$@BdlN-!e=P&nmT;Q4S28|b69vL##X^x;6L%IycLRmr?VBG1y3CGNzT z0up1-@NZ<GNrHZFP{u8@D90!RSyz!0+ZF}k)=K@80ad3$|Efi384^IHl;B2K$9Oo? zSQ+l2mU%_5XpLzFTp{~GLgDv%&fEi+>_R4E2~86NnMe_&Q-xb*UjLP$87>dF++2gf z@m+ct`Gi^(tulAxx@LVU%1>4rp8QiyiHu6SlVTH$(p7OE#YS+5KyF5?-MdS%(0Tb# zsoa%Qp2+Sycvj;b8)WvmVfpgDrp}`q+t3AvWDy32j`f6_43DA*ol^%=@pgZ;uo?Xl zfqkjVHrk^h`R=J;g@6?OVnQiIT624(g;j`Efv-H*aFJIk@{M8dS_BUxA}qFBU^bv* zUr+h)&8iqUQEj-o`iQNR!C;@a=);&%N!mLX(;E?%m4Mcr7T<AgfX$h+yBLP59A=jj z89rI1i$csSZldTm8})k+PljzrFN6EM6h=B9VW{UtMtx@7Tzt!8`sRA(E5Wp!8tm={ zu;N(L3N*CBzkFQCIIpRoEz1m(&z|=rbaL&socAIrCIERDk9*Shyb1AEkEL&o%0tcM z;YUwmb*bCD80SetP?dqRv9ZL`Ju<@t6^_fNmiT!f_A3Aj8pz|8Sn5kRx5ykC0JjBD z)E@uQRI0p+f0V*j<bjBKye&6$p_rrxbBt4@mT9Ziyea}5UQ1GE-dOQh_;~bCjHlc& zgXWnU`}=3Ooa(KazxNj+AAon~+%24-4Bz+fh)_7D-`Y;`QKN+4X~ILWd#bKPrnGE3 z!D;`?9zV6BDQh)PIMykB+eV8z)R<xZX$&FFLek-p)^4jxdpAo4Q(U?Jk53y1js~yX zr3=~Xbsu!57^RsB$ya7>r*uu9!cuA(uzAt=k@G<#6%89rp<A3{J(#+HEnQKCY?UC< zC$M%)aj|mnf>EuxnP}BhrZ-I<4yx6#KM>ANJzz7&Nt|fdWpC+~aJ2L0>hmemTBmW; zj#|~5Nvw9w-MQ3|EV5M-uHKZcPrvs-Kai@|F$E+CH$iI+gxtaaT4;1KE#77Ds_GAT zX$N;RF|xm<#ZTgMoMNiGc0*PyI%!avmD&N}^f)Fznfr^-p<yN5WJ<HP2(P7wRZ9@} z+-&c{-T3Qgy<2{>fnuXAMWJ&kD=J7(&Gi10Sh>wezK=z@+o6zk)yV;=Xgis9d<f3q zOi)ccT;G?ndpWWDT(=7Qmd~a&p<h=_hPUt2`iHI{1GD6OqYV$=Qd&2(;p?_G@tN7_ zGu_)JIxDO4uQ!n+>#r6J$zi~ol6t3#uaZGEXg9P^qC@@9%sUk-&X^tRPi4+0xhyQ~ zY1#F6>~703QGN39FV}48uZ>#c1i66$keC`)XxxJJj=VQptx=OX$K0N_T~PN-z$1Dr z*(*l(tL2u?58#Wnp&>d}hJGVOyC%ccfrKZ*>$y&r|A-%j8m46JRbnn8`o&ZW8u_wf z)&Y@5!3Ka6xT<^rRAqg#YtMIAMXgp>^+jjByuFQt-f`VeXVxFF8ROEH(MGB~Zy<cD zZ2$a?5mtMsfxGPO=D-)167Hmn<ro;!;9U$`c7I=$5HUDJN4eCoI0$7P@Wn-2wxqX) zK`iS)KBpc)Ums|@Fy+51m$a_ms#wlS=I5Fh=h%!lZrF)SNKH@K4pf8msolqcZ>&*n zS-w<bXMM)Z$7m>(ADwTUD4M34+%VwaYG#(b^Q7}tL!k+yQkwgv(x2{nJsMF?LMMod z$O8+0f<+D*Qra$0me_bW9Nk)RaWg;JL+L9&4?>7IWxjB3?Qls7DiV}v{;@>q`0izP z&E$|_3~mq9*b_a_%{k2nNC8s;<^=2SeWO~n<-*~c6esg<2MgB|KFvhVD&JA5jLs#E zA%b*s`&B{bBVajJlYq9cS5G8{uKlc64<lcw?tb0>P>ivO;b?_Jb+oBLByzClOcjOY zX)28gkfH|${eGaD_e=3Y-VGQ;{nDqcvBRF!@NQ%aSo`DhP=l~eL-LrRfWXJEA$x~g z!K?|Ub@+Ce+kpBWp?qXlSX1U|MFAmPinBtDptj-dI(en9Xr2w-j32E}tMe;Q9Ie#B zG}^fuDW&$$`infTSdo)=-=|S(&X4(2;UG3JRm}doA1`%ig#q^1_>5j9t)65W9sY~Z zOlMDh_~$w0FRV0;l)SGRl)chE$9(c~@eg8nt_27)@SfNm^x)U_s7AjqADU4{5Buxy zz70P1Tgs~rX6c8-nu|GC!nM1=Pa0%1G}jEG6bf!;@hTK1+(^83&+N|4=OiQ~H+`o8 zhp+;^7`+eTA-u+CmEz@}ePF4tvotHxctx=~@o1QJ<Fs}YP?P{(`Rw`rKJ=$N$^8{; z39iLyh{@@Nf_SY|e13-UnW+i9{%=l(-fvy+FULY-$AW7nV}C#i?NDs-WP}P(ml!PO z5wX-c+SWC^k$RkoTjK!SVVXP_z`E1OegPUp)=iZAp#hU3KrxL%F>Z&Bl4spE?uYME z?v&rnbBqJ{hG-y@k0`XSgC6x{*Spd`dM4d}?dGFFzXTF8L%~izlc<93?&+}gY-@qE z1Yi7bjAT}c&G)bI{x{F^p6F2%nTFvGS5YdDu^pP;OwjOoYt#o9aF)zcAp|JD_{;W{ zmIf=e)^;KErzWZ+>@B2WwH${Ec|uEx&t1}ZNEPKL`;6%Ja$}yghp<0oNMMW}Twf>n zqQbD8z-UGS<8s1J5+7|4J8Dnl7D7>LH-V%~#eH_K)WD5VPs_cB<1)igx@-3bUipgT zH41$@zC%P2#X7OOGsYZZ9EM7mZP@Tr-*3Ex&P~GF$FH=41znXJLkDxAH(@nWx7~3X zflLE+nTscP(N0_xn}2T5+kgmsZ+NaqQ;8SexUW>*EZAHXKgYshc;Q5YUe0CE`5|HD zYoH3I;||uP_;urW>ENna2R(m=Lb4kNxuS~i9*8~O7JHTH@oMeoVt=wnzV#SNr!_*O z`5Bg0h?5p>#zrvP$niG#u&cDy@>B9IE#I;xpL8VbhZO(sPj)-yUvJHK)65@m7M)do zSOPn}Yi?d|RruwrwWCvm=dg-4Xty+SlHT36%6N720r$ob+@)f156N;*vm;Z?g4W-r zN9kRPvk@{};dbF~Ifx1VBkp?dnHY`v_K4e`8zS4iU*B_t?#?hN5E)dH+(@%$Lb>;q zLaw&nrm(3EymH7yyBN_8RWc4(bYm@I{FijRy*-)bBD0m63Ij)aEZ@z%)n@x!v+^g# z#UtOR(E58u!+D0$eYiFe8O%2y7jH5{R^{R`Dr}ftQ~Oqn8vUK~qU<ZJ{Qn>8ZYG7- zJOy2l3tgSAZP;wUQo+WLkP76<AH#ZqdO9&csSuF`(4Bd}G}FyO5dL3JuS@(p0e-)# z$y4%TLTsr+F3362PD?!0g^wTWZuqYwJmU0x%?)5DAE<%Or7MbQB$@-bVf^CE`#T+$ z=&-MpbCz7zol`R55Ou$UkA&0d`kTwtM_d|Ag8-7EUlTTY8Mbzdcqi;%kFR+HubnW) z6T60p5wnT5lJC9AkS;(h%ab4m<G8~?7LtvGK*5^-#nqB*cznf55xT;@fzI3k-A07B zI*=Rh8@8rTl*_?z!h-CT?$ZSgbdGl(4NA`giD&Y^YUGIwo_@rzB_c4(6#nb+R~jTc zaB<%Q?W4m^nQN?DWI5XY><>21ZvMtt#z)vE+`sFZ@LCY@U*}5VgUCli&S@W?hFx8& zEcowF05PAg@=sK<)zWXKH{^b(O{p+S^5&B95&Mh<u#8YXYy;@~L%_N!g$FEB|9<+M z+zc?jeV5!Pb`=4{G>{Kh>R996(o(muVw({MHRFF$xNZDO%TO1H{QuV}%U=5qq$mt6 zBmYbxbF_?Y|L5_eo3As;3Gb?r`yXl~|8H2?bMgklb?oum0NdMp`?f93xra`D0>eDK zZ{CLG_(GUFtrvG<icw9wAN@xKPY&<Cb+}Iszg^O%5%}!DK}NBs=qoi%Fl1KtFn~#_ z^uDI!>lTKb#P`|ssO}Nmd~_%eaXF7t_LesV+^8A#hen1;20E?tEhJyJ-Brc${d)-O z-r0TkP^tF@ZC!e9JFt!5Sha%}*<NbBT`d^zgPS<{UUu^=OkM<gLN0#`;7`ldBU|Ea zV;dpy9X(R~N=bNpNk^PUQZ#`N!QZ$=Skh6CG?w2;?DGxtn4I7`ur-ZD%0_gD?E?c` zSih&;Sl3ZDwVMEs3|(Ya?GvB4Ut#v%*FvZ5sOFCYKylN1=5}1*Cu-x>HVlCPB&eQU zMvByZf98bmS{EjQ0QEqRM=<ppix`BJT95DxzQ94$*VCPBz#R(L#V2BtV^$?QaV#-% zR>eWCj+`#)%>t8Dg>~1v3eV{AUutY&6~}0Uwm^aHj1Z^eI}hsZ8E=1e{d)Hla8<P& zIO9C}fWR;{I_zm?Gmu(z)@c2~$~60JU)jJL!-Hw;!{29b>Ssb_;I^3@l=m8(TM*F4 z!lkKsXUTwaBJ0c)i$K2bR>lAAV+QRVf}I|{z8OpUr<NKQeUN%-=WZu9gP>8?n4#(X zi|V}L{_T3?Fee~pIfMK}4*0?5F@F=`ws-p=QrU$+m=&(1?MOEam(<VFPy|Q?v>C$a z#lR{@Sr~h>2_hPOm$qZ~5ho9za{;0zLRmeSFN6m4JYs5!qsLnG;%ntMC!hQJK+K4f znNN8dSq?si;G~RW?dK4uYn~m)gg*M(b;a82_*Vd3_z%fTo+NAT#ElhS&u9JLmX~F9 zyUiN7#{WLzJSBMS^CYeTYl|}l;<FkZT=#*EPJyOMhaPNmfn|h@(tvVMm~;x{tPCLu zorTbV`|}uI*7C<c#ts$-RJzX@j9#V6HIcz;wm`0#Ji;~_UR2Ah`QG<MQiJ)8Llgmw zjYxHc6++kc8pb2*ilYzyl;ExP5^vdJ)Bc{>A!X-{+$S9cvu!aCMQ+4%?#1$#;Jy?j zjIcx1wD4KqE?D|#W7e*B20CBLLm>+vc9~!8W!BV|?aP}>i_`dd7f&)PSQU_($3ZpG zjl<Et?ca^M#L$y*z(1?CEsO`llQj6gf?x||kdWe)F@I)SKJ;KzHNg+{?o|w)m26*{ zG?Lwnx|mhzhgL0~JR0>pOFo*ssqldEGu|~~%umF?-(IO9!CnpGY^1Ntm;xO%%4lq= zJ?5W|5IEL>3o*Qk<QBz<3qE*|C&)ojOdD#tJ7lMe%8{+MZaQ~LwLuvfh>EIA`{Iy` zd!uODID$?Hju9Olci<Hu#qNG9uuLCAFHwBB9O+rmp5s~ccIhWufWjZPmF}5uTFtV0 zunmwK;PHvds{@>?2%wRe|LQBqgO<%EtXHB0AMuMlDWl5$fk&)sk-8%{qSRq^(8|l9 zzO^a+3?eG<s2LmbRY}WV&<=bCIFZ9&g)XX5;kLRXalSM7%-?1+UVju-poJ6dDRyA# zmW=1fwwwhike|euGjWPxYb!17yP~%v@OMF>^I^c~;tZI+O?0~&@ESNKH7cl*?O?uq z--=|fUOMwbw>n$*HworA<`v#$#at*KeTN~nQ;cKu2=T-CZ@8HnW3gd0ZU)D6k3G@O z=PWh+eO#%*>lTFjG2YyOHY;UVFDlm%d@F5y%fQTD>G_t&0ywiEQNc73=4;&7%Ot?# zY&;^R&n2RpdZpTo@3>?lNY1L*V`^^zrfnLc$WK`GH>J7ajcVp4Ol0}2`LXU)P0jrC z>E92U7?w4>ur{L{;_(d=AtMsSF28GUK)LS%Gva&MMDl_5wBn;m$Ks`>y})#qKnps< zS3u4szwb(_5ATEPX4_Z$*KZN}=i5VPL9|3(;tx<`O$W{hFh?o(foKq_%DV6SR@qSm zdAZdNe@VpB{l$rb5;2jN{Edwe1!%dT%G?*pEw_#Pc|5fz$%87MR5P#q^QA(6oAK^U z3bzUiuT(x(v+}j3nhQ5DFiL?;gy}y!VMG%-zR$6zb6a|Q(>fbeRi2=Vsa1p#@~r%s zekC)Gt_OFQi}@$SF!Md21SD4{82k4d5XO9O0soo<$?{!Xs`|J%>SFOw+>1YV_lfXw z{i68yN~9yA$BHjN)O@Yqkb<Co^^wT9iU;>2Z+0@e!ZT+R-mt{}srH@YQnrBAq+^sv z=h~cLxlC8Pmim29e+@Dz8+oAA$dCi^Jd1`JKRQ{^qld1hGb&tRWtMJAqze)Up*-@< zKUUox^v>;@CFkeTo8w8fxfsW?#q)cM4Hr8GKsP#}`9S%bJw9-Q=O%1^Fjruvz+*C= zNZOTb97XoS`z6<UN0&O4SH`9MeXC``W7WsNW|MZGo6F&WT<R8{g+e!@F`+2Mz$aR~ z!p^+23iUc6_5GV&fF<(6j`qI1RK)g0HT-?oC$6dy(H}-;Rw27tFImF((;!F3B*i36 ziHTVMME|#LTxzi}7D7ps|Fy>43AV>Y_jAkQgT7W5&sc}%l|tXdw$4gYqn?&~sGg3J zYGzQXoTXUxF*091J~@i#yk$p+XIVdf$7pA@XD8J%+o|=iWR79Komk|J2r-nVJd9o} ziK9dYl@=o=7sf12Iil88<}Q-grTVzE&NA^5*voJ8AZiu*l4T$_i+Rp?uN&0RFe?XU z0?Wl&RW)t7N|)z~*&zBqWRqAkFXnf@K?2vFKU@*3HJBW~*c@L4n>IvslL$qfN?luB z#Mfh#R&u}c&D6-Q=rCUQ(9`i+zf>`*l8&(42vc=fY#C6|(Yq9r|7I4S;P|A#{dRUr zvP`J~0TmB5@PXHDXL^no6>J7^TCER?2?Liyd>x+pMAmm%P6;7`J{Q4k86<H{NZkS& z5jQAiQ;QWRj1yr7*-W#gqDeI%3@DlqT;$e3;Fywti(qop`<YWGh@4H>gekW0LBqvk zNvGKd3{A1@A^9yMPR^oSpEl~McDtqEQpowv$G4F<d$?*48hRi*?hrigFgK~@nH~7b zd3bf|qe{L?F9?=#P4k-2Zx9L2@&eWwLd~yOG%Mm67G)ea9lYv3x4%rZzu<pmNQXl* zIPPwJiR6^&eUd9`RLk0`YihHiRO2O+BNv@z;+0h@ChtD8m=K@W2uki2BQWA<{`T@D z$-mAVxav+WP2{kfT2+5jZ&M!|S2N6o5_$LT$jT^A=6ml=>dC#iP$fJpGwm$;E8gYk zw;9UuX{(-CY)-msxQ?;lhnKPZPRXz5Vc!_~TEFJ<0`5i9Gs>&4z+E<(8WxSQi1Z|A zq4Cu(y#|v#YVp8i8JK{%WOp_6xY^axf;v3nw?v2R@e8nRTiQL;QIc9<JfpZufj<ED zxCgW}#2*k=xL7qz1{}N+*e8uY*<PGj4034|=AJ5`)15d=jea{A$eQIJ%tacy+Ybas zd&cLFijEhXXY<eV=>(5!=veC$L~4Ut7bRr>At|r7;$}(kd4-|+nQ)_#%Kre{B(o<c zJUifL9N<Um_Di=QNw5eln$kN&3(hT8^7R+}k@G+XvjJ=lXhW5B(3A9g?dgf7uvGmh z8XCCpv$HoZpo4S*%QC`l#V&7$sY)EX6N_RrI6)56dWub|!6w+|avT>yqipe6>KH^X ziM+n$GY>Bt`(3`2XPO5FOm(JdW=<1-hrE9VW3&#T`73T9s!p5CnmlNUA=EPj*xs!^ zVA`zENj+rt5q{Jf6RFMr!qM0YK2|DyDGO)C8?MtX*uf4}f~#QQ{%-d9EUmdvPMh(9 z0gs1eV@|J=gsU9d`}!M}#b08cp75JX)-}qHz&>HWtdV1&!_x+I#_;lyf^vODLCnTD z>x3vOHAQE5ReqKrl&B*8cEg)$-&Ie!$81cbe3CvoKPvp|-n4G@OHD=wEUI7LJV&9* z)UATm%AsPANt(*k-8fGjUCXF}=2$><R2!@gu5u`59-VE?GORK^nY{NJbN_k@n2%H? zZVFF>GlT#`ZQ&4k?>{8B_tccrk4@UTr(ZTHv-%W)ZJv~8jV=hC+<g${N`A7LqA2q{ zik`PSD1J#yRd>Qu*{CTFvx*T+f(a!kX(!wt8G+pme@q@u;|1pjR*6sUt2gm9=;H;~ zjlbVKY}v06F$CqSdhCHZ*~i*ZiGGJwR`YS@Ta-sS?H*;$_hSlUi$qx4O{0H9DC_Zi z1l2gen80QbalR&7P;Fr3Ws+c<W!jaUotfFvq*IdRagtoHMzXmo;`C)g|FdbO(bSol zYJz*&YP5va+?oI8)%KoozG&QSCIM0Z7p0>jC2)1TdKrNu2oOxKI9dUhyj)nBwbef3 zn$FGq>83wv;~h(ycWEU$Y-~sAg8Ux#-6>{eq4dN2?XUfL{1ls>hqYLz9RNjhv*D8a zM`fowwKfb{@n4JqgLAunSLKjoxz7XL20i$@bPlHnnkapxk*cZ3B5aT*@*$~32u7%{ zONU`%9*ul|cmVN=F5at>TbdMw5hvYRn5*~@56YykQKw{oj^b4LFv}B#Y#2;-EXK=k z$j8E+b~k8gm)tWRwlG4|KUxBvy?m8by?5fk-#Zuh+iss|Js1vn_}5`+@(?znaAD;y zHXqi#v!%<#pl>H)V4i>$G1i|<A7R{zkO<ProBC;>gmtemdD85c5Z=4BSHeNVDj(B3 zj54Zxl4xgU46o45_LwcytY)1y71E4YtYq)1jVH1bM~DJ=ppH)he+%n!sij68hnnwG zQ^c`E@zsCnC7uM&H1V=6?&*Ev_AsQW&Efl^lPQ$~zzj@y<pFLmKF@6SNY11DTb5~O z>*vO%;zxmIqG0<M5Xqx8#o=$`u&^P>63@o`TYpO;*D7AC4}|^T&d~X=TLjzO>h1ZC zq3Pw6)i6(17nk*Ym#g_K4*6rIXIj4?3x;Rf`29;A0?*VRa59TEOzhk4jZE_|B~TXT zfug47grPg-XUdgd$OMdT_0NCM?ba*$C?+PJ8^->s=Gv=@z8!@$R?|;84>$MpzVI)n zCLS#5t-#AKN2a>lVDHe!@yqsTTWhOs<|r1@q`~$kKK7KFt(yjNLh<nlpUmJU<&^4+ zRs8P0rhcUc58C<{R+gcEKSCCD8Z7y(c;Tdoci$CMxHaDV1-y8d4@(dAOIBbz8-w-K zXY6*Z_EV?&yd)on02x&*&jbUbSnnu@Zig*t>)YNy9VvQTE!ugqCoJag+U=tN#7yRh z0xP7t_JiOWl_Ia|am&q^9>;0bJs|0iLB$?RJUQZ_!fyllUADTkqL|-?h?bn$3_%%& zEpDl<lXPd#ilawD?+L>_HX2{B&EDcvW#yWUMxQc6_jd&fp~{Q;g3CO%^aMHdYd`gH zl_yqGbOv|IDp1A7MYX~|GT|wiKF03Z#jHd0!_0d|1~Q4-cG<)jyahIT9SD(=-YA|? z5h~ct)JG=#@mSg)W>9u+PKKqelyE%r`FbOOsw^L76bCFZXWi3kw+WosE}&gO^^#}Q zuVBG?(cKOpCu$P?$i7sMhtSNnfjMIOMMRn{Yqr1<P>b<!iSd5$AA$xBjIPQRZvCOA z1allPT-Ud-%`nA5`o?K3a+N)UP1+EbPxhYc-PbvE3~rF$m6w06MSar8Z(?%;meGnU zJv6*j37tVU|Lp}*j2UrWU&!BeGecXHniozxIw&+wW%$EhfJHFzPU+aCqK{08F_K0P zw-Upwwpw2<35<nw&RT!?<gAoIWNCaJy4kJfo+ggk<(erLka8uC*V68w^EhiH$~i6O zTym^G_6=s1#^f7BpnB$ZimfotvGCKB1dG{EvoQ07d}Dtl$n`}+0NxOLG_+v~YN+qR zCC9+!or9{uj~&t*9!o9g(Z4$RUP2cw{qbIqgGplRN*)=$5zz9BVxQ&mb^_-@jx8Kg z0t^JsEkLmtPhX<$kO}n*N0_*jq_Z@y#_JSair93EI2MZ6joQesM81}p?z=E=<9Ri~ zU-Ioh&rX$K-X+7W-i(aBG8;Xy!4dn#)+M?Zy^qtqKYE~R7l4S`n14u|lB0?DTd}LD zw6SoF4X)QT%IMYif+bFQ-<vX?PouzvVw6rvH>Q8{=VyPwo~IP*qNK*R5OoVjygAPR zn#rX?*jmojz%VmM@3CoTJ`;t;i1F56WAiYkZuR%S#a~OQO}e|(=O+xcKQE_B`6N73 zOle+BZeX@P$M|!quh%4C&uF`lTIIX~oN2Td`hd8&b`!2~X$lu=zRDxmlMb!t(YUi% zUw3~K_bZnv+GwUqg10W0uzX|1+p~BX@{E~@!7G>5!4owSe;f)BiU&bLy@{^sbHKV! zdlQfB@0Q3o?B>O77h>Y?`IPNxCwzQX%^3miyZy`uJapMwu>9E*#d0#auur6XkKLXJ zW6!d1$J#obns5Q1vbDv9-Snx2{zizl`IJO)oc19mq0L{LVGSC1lf_S@@2VxtaV^3K z7HAG+x{JV7!~YJdYlmnJT0F#zptx?STNbCKW6YXB$j<v$nG~dhJ7YnADGrM!dFUKk zjZ17fb91bQ`!Xp9w9=bw-BXI$49uIrncf<=T_;YTZ=U{+TfX)g?S^fpC65ULmyXBw z&*U(%e-1GAOVh2dWcU8rbcImzPB|$zkUJL}Fv;J{rNiy?{X@dGwwD>!x5lDT1Kw@W zP+nbH)Mt?En${C2iqMUl`r?pSL|=EC<yg38^jog{d^Z=YW^z!C{R_j<`0!)En0hC? zDnYqY<nG1|*Sq1@*g(`s`@C?L)jJuOKtNvfkd_g=_ge>@%m8!2zz`IkRi3X$@0fqn zPDyEQnfMX2Jtny@aeEnZ6OW<g>In`ekN8u4=l|pGy`q}x+O|=6KoMz5?@{SpkPZ?N z>C#K+NRcWaJxGa4@6x49?;yQ{bZH`?NhgVj^n?<Egt*uH9sJ{Y|1tJA_VGUBAS29` zx#pbrysx%uBats-)dW2fL43#-c{b*vTA*$EJ}`n7eL28=`%4^NEDlF&_4xhJuOL;e z4A(1ppXy7GgKF8a9JtO#Zmt{EiUE!<Abp2m8+yM7JSppyB)(?;<wxAYL!Uaqv@SQO zTLupk4{O}FHclzGU<T{K^b(`Yj5n|IwM5%shkRErHlSiihKn(9!ke;R?MSv$>D(<n zQr9TtruJ-$gRHZXubM;7o*pj?Uv{_>iqxR^8AUq_3~9Tvk8S-9P#_pWd_TE}?*?@F z?sdI4vszwVcAM+1-CUNKiuV?tbRhN7mQ*z~6RW?&{PRkxw((6;15iX$<Dz6=V8o&& z*A3Z%BMXE)AbN3o_aE#~I%JsZktQi`rF_ph1BZ*C_Xjv>b?AoPh-`1v@l5}O=Lh`J z{#u;#D<DVv{SuXMyP;(2#CF*$A=yhyqNRO288V4XE{cZCFv2drc&$}CwL(zqZi2<O zX7F5PK@-4b-#Affj|xj;f1H8#4^gG0jlR2xH5hjArZOGskrG7Luu4AsZlI65uWE<T z47PPO?G3RCq7M9$vY#^+eRw7ozweFUP|;{?(Sa$$Jw@sdT7^bVL^EY`*0c(qNeq#u zj5DkXWm6hfOLbRm1Ir8?V{^A1!wFn6qm)>d6jhM9s~xXAx!deSDkAHSQP7p(#V9^< z$u{7l6eP5!45<#=8P8_`;eP>xjy*UMFe<Va!>c3P`a9rKx6Evn%T~#`>D(fhpzcy1 zWtPJ~G&c|3zSQg<U$Tw%Hpjc5D~2{nUC7H_<)!0;kQ`n{Z3TBy-DKiE3qzVFST)xV z?`xNTkSSoLceRR50i7L$nj?yCpITM7%Lp@|*fcE+TQBp33zBqB#xf=|%&*H03b$}# zF^_sg>7t8RJHwdnMh?KE+bYCdZAw3XtUhTF%wUkQy=&SBqWp|+^;T>w60Fa^?N-48 z8aQ5&2W;;#@At89;UO%=KcFA>0zlMf@odJkul(*ydI)Ynqy8)ge=NHbwES`T>)T-v zIU7UxPGOWSbr0aheQS6_G|LuXr}xuZh}NK}!mxxOqPCA^YXO?v)u#Mq%4}Ailah8M zB|?Mtf3C3k-O0w+`HJQx+I8bE%WMEPw%zY|5_R^K>FwPN3vP3!ol}u}{i3farO^{6 za8-!XV?@nnj4efoG~ph)cfCDE>gsAzR<ys>|Lmj=j}lH1zWddoJrh%AoFo-+o4YgS zUd*$_nF6v^{h_BN!|nWi8fqJ7Ir`ffx~dF9d?l_@fNI3h<&PD$hv@w+D<vTYBS1Cs z$jZtMlEJLT;4PX~!R*TEmQht@TxXHDx0KK*QQUZ^hR?(xngo3{NRVoUpV35PTz+?j z6;_T_L5p|HJA)3(l@*O_wf(_46U6$avMG(ifQr;**qtxq67a3L!E#+8(#HqA7_p(8 z^(=UnHM*2695s1RjlIJVuXjC=aO;PKNK0_KDuBgLvfNV$?Y*)BM0GL)dQq&Y<;@gz z9hyDCRjLj5LT&b0!qw&+PiD)0%rtTsdGz><hoGmvhRt5ysNM_AS*-A_b(0WUv;KCf zyU+T`*-3a<@GZS#0TEFE1I8+JI78xq{j+4X=2AnTsg4CE<ESCjc+<u>2eQ5bE`JTE zD>|lD`suv6e>R%H4a&yHZyO&63$;&`O_DJ&56BKOI16S7YDsq1Sq|rvXCPfR51V^? z=u`yS9&seMyT3?4wT5P6^aeJFue<s<U6=?radqw$HoKo`|M;DR6lJTal>0E>ef!!S zMKLY0X@QyUO9`w}cV?KHeRg3K`ZfH;f3TAV08t>rK)$5>#}kWTZG)>NbAi*m1-mM! znWR-ICm4L!HX2k-3&_m`t}6&MP#=KUjt0kCU`NgLR*L|4KO2oP#flrz@NO?0FE-Wz zaZC&yL*`!>W(V0jYFs2|n>^SU`jM7!EmU$HsYrLF31z)7T2OkpzQ-5_vIMVNx<hzA zYETCf{mjsRRIreH#T5cUQ!R~vVnEcad(15jclWa-T=hBxHP{6816Yhwo^Vp3W<US~ zl`OWtM-%zj!u3~y(+gIWHt_-m^%p__p!H%iR(`a#)(v(mMAMh&DBHiH=d<eTkzwe4 zb2V5*)b62G;BeuOArwtii1y?DC`AR{hKg|k>2~P|@fAJdXnps2fQ3dAZb+E=bF&T; zkK7)X4g}eYudc8t^Y?1-T}?fGdxJ>xiXG<!CJ)iaMI+o*(wn;P42On)y#ZxxzIqV$ z17gv;Fx?hgdFf-NpbjuB;bWjN8`KpQG<9brObW9US0S7E$D~7PBzrn!x1Ip3$(HHz z)<Ac%;j2iEBWr`OX(l3Z5}XT3EUp`nKm-nf@2Db<<4iB^+O&3L(iiMZE0D_$j2{W@ zi-oVag-sMT4ih9g4ZM&vw8X+Z(KCI@F=O}}N?r{B0cY#FVpwdI0{ecpE)3B8>}kJZ z)OosHVzTVcvIf~E^3kxxF@)-2`ca^R>`G{M7<0(;N9$|9iK<sEN5rzo?<=$Dk`oah zK4FG2+>6F$T&KTM;xeyHgM9zc`_&+G0^cl#db@BEt=ozn`_d2xYeM&@A+m;U<ZNEO zXbjc{=!V-KAGvn6XiGTHPiDq8qq1yoD+#z2&}YzmXl8j;$gU_hQTP?LM@8hke`nIW zVReX}VB^P6v8_y5JZql*{>cDQQc0b!bYQzOA0syN!N&GTenwuUhIKthu3O{dpl`?U zE*je9jXl<dy2OM?R*wg>-2PS>F{}4Jp!)8#`jQR)`4wFonmPDKDryB|IH=G;aP2vh zC8ZvLDq@~6@yy}96xc$I3_hDX^pJZfo;-B2CoM82N$hw$7Gk2{MFK4}&Vg%s9&T*R zjxE2mdUwyBR~D@KXr^9JbF`?|)xBy6sqH2GSbxNWK44q_bL10}1T+!*!el6&HIqeH zl9xyQv$kSa`^=lX3x;}p+d}gn;uOw4QFRhnahX4!IVIiWaVEJa40LDUzIv@UmlLbV zAph}KuEASn;l@%!A?N8e?~~+Lpo#Wuyjf00d0HJViFvBIA?>PeHIv6h<+VIV>D|pb zr*SVNl|2^D7F^?)q^>FQkAU$L-n%5>U)hp^&OcGw-f?N?1kL}1AAJl;X{63yDv17m z1<CH;1Y2N5yoOd5%U*17_w*&b=5jI*xbsr~O7oli&x@UZdi)8Of4=|!*&sO$6e*ee zaS^E}<M;NF9d3LFo<+EG$VSM8Z4M9^N?ZYpnH1QP6v2dt=p}5BqXahRb%g^DHrL~o zLrd0_vYZ+(^*O3~eY}sS{T4=W;RF>K&^i3A2yE~rK${ByT>*0PL=ZaL?Jv=KGyw-j znFGcS+IHnDz~sB-e6SOut(bU4N%IXr{g%cW;`=H5=4SyRT+Kprg1wMsrnv!G@evEj zO3&#a=;X%#B#E{1le7b7NgS9GByR?9Yy%F95#cp#R&g@DfA4XuL0*{Dw#-EuP98d^ z>H|OwP@AXPH_6`L8Wjrb>}Q9Kt%1$~mXkcunHY80T7OGm)GH>PCQQyWEhXQ|;cx^^ zm0T?ih%jf%+{b69=!}f&inSE-WP0`D&mkGZ7lS99@#riR9{|MI*ytei?)2rI3^SUx zsZJ)GDZHz#Ii~vI25EMaY5I1m$E7KhO*S?Bv!I|g8^|rgb^ImrhGo|$y%ojFVPs+m zbZ$m&1fnHR$*XMS$#%AMqfj0yL$(&oY`ZyLxrSTB{;{l6+k3U9=d;?Lxd$Dwt?g%q zeWm}OX!#c6bLWG@;t-pq{;k|M>%Zc+4h?_7Pm$|&D;py&RqhodUXHW*%4Nhk4|#lv z3LtIo#did+8&^~+-oWC*_`{}`fFj{ck9Z$w*L`%|r1H0X>@eIFT3*B$2@oqpYXV74 z1II}}*A1<!wtXAWfseR$DYzD>yXUrK>WKX~1{iF~U^_t3>x{S<@=ENd3}fC~VH%^M zUfWxg4wHs^NwK^VNi*>}sA>(B0Es#^Z?tDgpFHDsjy9FK8(Q>9+vp5(@a~EZ3bZ>a za1E%<nEpG!kpqi>-Sli}AlZAPn!rh$iF_<(-8+BQ-@K~8wZ5?;RlV9@z}<Yy@=)B$ zNgtE-m*{zj%+%*RafGR*twekxvr(j*Z=%M)^tXo<vMq%zR&^7(en$xCe4bId2X2#T zC&Rn5?-5f>hH56Fi1}%ITdH?@)nKBAFK@a)*GY{QW1*C+tnO?`y^<xG54jTu*h~N> zpahcZ0wuxUtj_PsG29Rka8S{}5Hbq~es#R?la-fEpBI#7c}sZe=CeGok(&4KE|(Vx zO@R(mDZtj(kxG<=aa%UYentR-Yz`bOWaLn~&~1h*JqS_4eCt#UFluexD6F-)&NX@X zoF^upxd+Hbkcf5quxc?T)z$C~+;TCX<1~cq#cu*R){`I-8%-qJx{3*|-yd_^GT2&o zPi{r1${;%5D^NJlu=do#)q7k)SX3ly^8WrlKy5>t+eY@Ib&lDg<zq-0!1F4432)NS zR)c&j<&macsM0a-<uvbE+(DgkUGD#W?*}iAD>QR<*onXTbD(!Uh$DV-Q7D?<q%LXr zDLY}bNxzUsUC!5MzOrzPO-@(pQ@ZtK1vmb74^M#|q0WeZR4TDz+_dbC|4$&YM5@Xp zxj9l(U?HH6PpjH6HKIz(u(|ol2;10tT}`<61ImXK8=;9UxG{$pLvrXo)=}ixvWzAD z)0(rYh@A<&-wi#^Ty$=J;BG(5!u@=752Hy&ZWcy+UDjiCr6xHC4cpt%!#S5*X$Au5 z*HG7J?$5o47Mtp%MY=eI%fWq@?WAc_X%+fpP|l{aak9;oehd6n`GVI$E89mAdsnCS z*@MXGwaOBndl6maFYn!{G!GOfdHqfOG87r%ecsU}XZhZ!wB!b9x`==@+#5c({W>AH z`@+!2mFrS$S2_2WIpENoe&S+Z@SuP*U(nCeJMp^OL`;_7utKfcC{i$1Rmd>$C;a(2 zO%e=L3v(7@4f|%xF6LLWI_X8aZ1Wp!j+e*ql&{0C+%@y2%l0hn{5v$^gh{RJmqwDh zvuhf=?1Q)Vjj+ME``|+qCd~@q4S0%(4V~`hv?YsXAVATOr8u$Ys#fux58^zqgy%kM z!s1H1TtQ_YgM9c4ytHsBSCV+~>$X}HhABe0#hOnO%@^zCsmS78wt6qzWa;olcawH* zd)vyKx#gPH)V(-W2_28CQDRE<^y^%}pW%=U;Hd7R`3}Lzn%qc?TL0E0v;VcW#=Ens zqaIDS_ltxT1wC$Mw%mR9%G{UzS#MA7twuL2ORV68)A;|iQPW1<FH@a2@GMhu)zT91 z<sZwoIg(D*938J|ID6+!v86;^6kEh<QW0KU84T6+Q);+DuGwK^IBb~lCW*ag15R7U zvJ@$!v%!}+4p7d>&nxi4n3oNQ99!28LomiLc6a&Y@bV?ayTSxcOkhIJuV;km-q!aM z2<L^q#T3hroM*aG?(R`eewyVlVf0b_)e9)ZpaWNOrR>I<mjfQ@^%k|8JHOUGWG%>* zsw*uXRhU;M)qK5Z(A82!M|;m0didkenp}w%a37EFcM0Xg)&RD7!fWPGg)#C9obIMR z+`}$vNvAJon>+4QKPkB7?r^zfkCx)LSs46i_Meo=bMP4WAH2<Xr91l&z$Sn(E!h4> zdro5wIpq4mLurphGGT~9^A}`q7+?<V^Nn*9fr?4G4=IwfG0ZjaNocqYu{o?B%Q5J~ z#JP&RJPDKbW}<iOxshwnXdPX3T@^9hwSb7ZKDaOMAB4tWQ-;0?M%rjD6)!;K2Jh%c zRpB>nY*C<PF%%8Z(~8aEJ9I#aak^=5&Ct2+dsVtO)lJtIA#x>y?nlkC3YaRmo43nG z?N7d(-neXM;`FM7%x}=4k4I->V7F?+INdg>&omXKYH{YToD2S3rZ_jHF4<AqWlbCY z_Rb)Bzd4kUJf=uD<IO_t8(TxJ`qXdUIiPrrZ7HR{rQLL|c21`R=lr{9#7vg~nJ}`L zq2*2&4Gl6Wp?qFrRAGV1tq^`JpOTQ(Ep>?etvR4p>#XxlL=m#3DFv`?$spa=Ej_^q z81?3^tCRDbUi3lEn(pLnZeP(H8<vZQk%|@6^<VgA0IQF%J7Hh?+o&#v0G{9~pUEO# z+W|vnlw^AVqk>MF6`C%NMhq*8+m6c;*FTN;OQd#^k>Q{wn3m=aO2m`k{IAq-SA%b| zu-9vwckwI;%S*{_AvRk^O|NpL3ij8;_gcEF>scpIHz{iT<1B+plQbrppKg}OL*D)+ za=Y4z3ocwaHe^gKM|iuJ{D!BNzSIgYuY3XBdA+q$ka2w@_a`)ocDM@~63WEsl#g() z?C6%d?Nb#xpO+Vu8LP>?gaxz%cHVt=5L|=Id4sv>mm;Qla?WBeOHuNYFHLJ*wS4qz z&c9a9zs_g%sk-f-ivdM~Tf-U~!loCO<Y^8Kka|?hIE%$)e~Ky;T+Hj$mKo{mL8pRI zgFyOl_c5i#Oy2}K`*9m`bo3CX9Bv0GMjy6RAcL-N4SpF^sSMl7R#bhB%_$o;Se@or zIQg-weWOu^I6AYA<uqOak&$T`qx2wbVx<AVBXn_BW8mhQ1iT2+GC8{I{R$Li(l&P} za&+KN;{Qg}tD)trC5cNoi?R93u&O|&f@AiNF>yPfSV3Hg;~lPx!#L_LqF^2#qC>+L za&fC87NX7QYB|qZPiamo)ym-}?vG;Zze#;WUsn&LJhr+JLp*O5tg=Xis^vp{7L%KO z{1$XIM`T!is#`6zLK3UW_}iV7xY08TgXoM9v0FQ`8c6Rm6RmmgCV!!=&&=_2SYro0 zinvNbv#94QHBlRQBsroIyg8q5ewnXViZl8G$>a=7tmm805o1_&e`Cd(G4RnfD-$#L zxwW{G>K_tvpHClVBrkbhI@X7yn1&u(Ze0v(A4khy#1$`zwfsJuKB~K!kA2pasSVu@ zGz%G5Eb9Em6#ODks`*NO-<JIBn2k3VBkN+YW;^2risoAqE!Mf%m*~-7E$z{KJypHi ze)0B;R#GYKKAPH&GCY3gsm--~Tp5dNX-VJoV{T-9%k18v-(R9>F`CMqH4&uaiJ22~ z0)wjD_ZkQpZ;egDf?2h%u85e|)4a|(T|q@`z&1=Q#4HV)G)oZpEgzM^lpGSgb!}@l z*XsVY9PQXFyx+7m;U3U*;?UuIVm@pC&kx0-92Q40!BDa*qTk?uz^|a94{+0%tl^xc zB)qIASzH*Mo2lXN*DkLd?@YhKZe@!(B)Mb<W@kUuX4RqhoQnRPs9-U7tR%e#O*UH+ z5pFrAaD^~2WichQ^7JTc$)zO3Z}U&e2HXg!*<rtnv~5iuq4@zw*y$&fSVBPkn4P3g z^E~sCfUOJ`?&>q(>n>7C6Cm}{I3<JhVHjb#^iqUgGG*ixa-MKH6%edjKtd6nAs{<? zUgdL@1jjWn4+<JIdD0aV=JQtEZ1?(9KW>NU2rJ$F`T2`+5wl^GJu2F3Wg<Pa)op=K zol2d?rUhXto1n^KSOfW?rfc{f>%LY;xDz7TdR<-zkS)mZ4`(HR*r&U_8HY>ywOu`* zt;*a$2E;x|Rn7lVBfejF%zj#UC*;wU1YxL8rU$b*U~Qy@ZckLy_7SuE(iV78<zD}7 z5G5lc{U(Hoj((-7GUHP!e@|Uwt*%OPfrpY5-nYMCW(Wcx4IT|*Atsg5882yZ)nh6c zDr|MK$Ll{<OpL!2EUSKY6>KcL4~-aNk7Mot@)pYaNC84ExW@#&I)KfxVa0(E9Jf*W z&2jGQ3Kkg0ET+ubp`i8xjaS=Anp{pV*P1jw9o;(k$oH%HRX=&^m0)(8cnfNxhzb9! zzI0nKr!07MV|raI)@3t8P*Ek#zL|1NATcBaBT?jPG-6j}C;qVPX`+<CLZ)Dyr<uIg zqoGNvtHo+Lz_FrH?;Fg88&`vw8<P&>#RY9?v`Td^qS}^9{oI+_5`K(rOM=}TlUy#C zFS;}~A40!t4Mf-&*^FOVTjGt;$s@@(L-^2H@0CFNO5zLkjAB%_;5e_1<7W$eaT+;J zZPCwtMOt1fXp5g3N$(4!+?CG4tg{WlIFCI-d{KId-(8~q5^3NnV4vJ{iXRE<ul2U} zeQG2PaN@5Dn62^jjiJ79h~>to4R0`;<&{STMd}+QaItW&rWXYi8LaHh!kI#n*5YOY z@zJQ`2ua^CGMjsjxLbCDh@ZQ^=urkbCUtTf&>Sr(K?}j!vfJNV7zBbdJ@eIilZU|c zAulm}2&Z^7WT5{>AB!#l^tq?d8ptgS`flzb4RUJ}6PA|VWnVHHC(Tm*sP`%c+c+*V z0H{xr2!sDA!I_{ns*7M(y+m-EOk$5*nf0!=Z`InagqgXT=e=I{-^a9?i!L7b+7q}0 zYqbnYKh!ps<6N=r&8zC(E~0>I2X<}M?V*LuIB{2-z0BYt3uy`Q``%l7RG};YUP6Yy zg@Fty(8Pe)EG}%}Ezyr$m6#Tf6b}WQyjn*2-VY<?))#&z`wa|xQAR2j^EmwhQQ;QL zJZTFcEGLVR8g29Rds<58c|qGAR-L?A!n6iyhIy^mLce#;5^8LtA1XeMA6=+OD3hz| z@+&bcvr-h8ko;6;sH0^fWSXpKUnB*b;j?+AJ6ip*VT*+z*w!a7<$(hlcHob3MjVeG zlR~41Qg_>x?scB<^nY*QQcHSvit3IdUoXiaCr&B<a5wv|NlG~i_F@ybbhWe}%#=Xg zR#7{6x<9KU@?+6lmO{ZZRM7efg*rCvR049h-h?MR^^ZAEXRe!PgxC)|(yHOH{TZ4N z{zbfI#U`{337;7XOmp$7fU2l6dhnD-dSQJj6}HrqUz>0}tWhHpxnSwji|n`8W5WC7 zB0M9};ri%nYzhi?$BlN`!g}B6GADAn+uDt3$s#L7VrN=UUOBc&Nl$@}F=@l=dr|nH zQ>UYy=E&1Tv+56~6;s<PbZ?q6l+?wXNl`*F6f%4?aYlreEl!0=?;n)F><r5a)68Gj z3CO>$5UZU4s1#MVTlus~?JSIWf95^>0ac67H~;4E+HP{qhuI|D76bO7nGtJV+jsqx zJ&;n|FJ@bv-q{}IGIQ&7m&IR?cl4#PkY?eTZEJ-Q5AF}yRNb@_g;GBKbl|PxH-Hka zA5jQ<*}q&kT0n=fjZ-}7+8h&Mv}8VKoRIoCyqdj%MQTh6y(}W{)oNU6ET9|dZ$2IZ zFLz_-u5%@4$SqjJ8uSt>Fre60K3dy-CK4@m_xP%rsU6?1U+7u`+la;|&y$nLQJ}aQ zB$e)_LGFnBMmG1x4fKuuYNhNlu2Q|g*O(d#v+a~jO~*8m!6D{+WFpOTANFKoJ+Ub_ z+aIH8d3Hj<r`Uzvxddc-g+Ya0zM4c_`_ZOC#?EC!e4jWP`*PqYN+sjUg5jaAv9(sg zx9-Y)<gV)C`wT5@3RV3Yn_i20dRMy=!$%Ejy>5nKUTC3VZ`_-i0i}nyG(?>R;Rr@; zxob;vE;RXdQ>(GSrG19pK$Rt!ufV=?PBsT(GK!!NRxhfE*+K8DNN(Q7sST-r?q4i8 zhG1yoY7Hlrw>vsk9Q|XtHUbs3n14ClCWeIRQK2{(hpwCly9yIqL#6jeR_c2h`dUdf zg;vZh%_lA(A69BzdwX`d6B*_3V`+!{)i>2PhRk(@Ec)SL@*&Qtn;OltJejsPab6bl zhi3rLP>CrUnQDjJU5&4ZX&UBsSzLF{3U<s)-pqf4D_|KwR?V7L>E_Spr|Jr2cZ^FN z)d%u8v*;*PR`K==U{=K^WWyg1JEe^y_Z%8cO3Qa*8rY31O-2ldzJGbKH+hkVi$(Ip z49h2z9156>Oj3{;QA8Jv=9cbr4F#+m{)BjW_?|9XZMsgsd_2-E*kUy9wlme{WJ+B8 zL5MqMKjDV(Z@z*RlY$lJ#QAM&=J!ewrkjUSm>~qs`*WAG<47=P5BLF<+g<AZm)>4A zW%U`2+p$G)vgL7D*Q^PTBc&PIuQKFoy*(kX`W~Ra6{0v~5StP3J;I7Dx!K<5jUmOQ z@)fy^75=03c1_BLf7Bm7lHQ?xKP*n%pWm@G*b~M?Lip^6PA$K_xWUB4zz}2{ePN2P zF{>F5J5DDUVH^g+B!dXf1>5EfZgL^k7J1)`3}s*HzOP_CcU{OyR5G7WuO5u#-O-A_ z*foeSHr@F$69pzyVsXvF_EE#L)O)(j63?d>el8i>aEl8+<jYm)dFP;dtMMNbVg>q_ zkq*`&>YW&!#Rj0yMPd2lHz&*Dn$%LP2$#f$TWXNFg{7v~?ZHW5jVd>;uEMEP(|Kaj zlpY9~+NaJ1MG?fhE{GkkJR71}`+G%L&o{6HYB)iW{}f?h9=EEhm{OYBF-SH2fqaGB zzG440S)BLid=!~du0O3oq#A*{Hl2GT&eXslEud*Z#{Cb012>(5!q9zjUVbdB3l^`6 ziVU%Sb1q^bS&GszsW7w|(cX-HY(8z5?y6SyO8Wk&evLEsD+Uy$L<<cZ^u@&;Y2T`C zS?uj;%cOYf<*$7av;1V{L7L#02Rn6R`A@3Q2bxnccDS)Ia0^*%$YTuk)hG-NG}%j_ zOGBH>*gseMU)$8aE%5aA%!{Q$)?b^Kft_8n3hy1}$R^B5TmWWZQWzC%EQYt}%7ie_ zx|m#~Q@`Kd&e+G0vnZ4Z)@@B;UpKeRo(xKhuy^W&E*n@ls=t3)W19&=>-VoZJjI2h zbo3B~2ba}u4ns98t&9Hq-MgGRPM(Z`vDA#WO37&-s_FxI2bB>eVbd|wJ~nLQ)sPWm zpXxas?wq``>I#aMJmc03^{I3RmntD&m@nGXHr3uY&(qF`%<$2$TAlnt5vy*bl#5|m z#1N05epX`%^IV;Y;D=<vqH|~EaZ><>_e@?@T16cv)t-T)Ao30P2TGuKTTP)(TMB!D zH-qwzCrFJL&r^)mMzDzNkRm>yVGd~O{?*)eoVA^X;sb;pjq1_GWbE(-04}vnmOMYM z5=2><Ed+A{LoGGsWO@n(wR7|!jv0Tr${XRec=cCZZN;GJwEI16U$(ZqagcKS<LgfZ z@em34+%xo8(s9@r?P1i$@7fyXGq$KF*y*69NbpZGrmN|{L`AId`bVD*mF|Uo?`Kis z*)?<t<H2nIZq5#v_Hr@h`S3=1HuZ6{jd^h8I#ha3)=%@cGi|g_ppY{QsRPFiuO+~- z>+%-R8n6Om9iDI|ehOQ+ZHbPqWzucM<mj+c-tTIseF!r2wc1Sn4@n_@lkTS}rXn`y zNb*(bjeyaLd4Ab?>Nuja<cLBR0vAsCI5|>Loj1?<86BIW?FRLmBQku>NC&z;%U@yb z+v%gP+xZFMsX>pc0Y{hXnOSh1pCoY+dUd3aAEzGVTM4v6Z+t71TC?K=Ojeu1Kgby+ z>G<{uc6Y!3gBm$qpY(+RdC*f!BHcl+8WkP#;^4J~EP&LH9k%38P<t!n0;B6ON7UJD z+RTcUw0F0rYm$DA<{#>}fMbrwHe<nbQn&o|Soa!j)|8pD*c*sQMSYXxPjtM~^~v-q zpgY6z--?Bg>P?<u2iG@vhHfo9A>v%)2Wic@o7>3RhpPRI4^WH9CKiM!=z6d6cIr{W zz6NaWZ32e9qi-J+Ebt1nL1KVhpIS>}vM+31{$DEeeEnTP*yxo4a}oQL61p2N)U*#3 zePn!---Iex!M;kP2)%#?QCX7sV<DrWSzKJye2^hi#3lQv=GxQKFXM{Ab0xTb6tn$_ zUF!0a(1~a44c|aSJMTJ3;<kT(qJG!M15MJVIoLH_Mv)$fP@7BmJdxXSs!JyOeINr; z;43^2#|x$ZkHA&`rY-*dip;e%Knw`~9|5a^+Fzpb%?mUv(rxw$`^ZwPKa~XHZ2x8Q z<hum#Bda{>n?dFO1=|=d_Wu;~|4U>`gP%72MCFBh-U>Sc-kT5*rj9~{b7ok&s%DQE zzw6sQ`HGr)cI-Rkk#%%r|4$M!JO$wEEJ@7tzm5P~79<wwWDV9P8r}URlRG}n9sK5Y z9Z>ybHeCOJ9fuQu8`*!<<GNyhE<k_iOr?n2|7&=bbGI-q-Zhk=g`Bn-C)Wo%k6~Rx z1@+-y`cKaP5)lFLMCCu5|Jw+d-z27UGPDzB;X^DO!_L!kY`S{wpQ^$CLaQvofJW4Z zr?4e}_WfJLs`dXGf{sI-HSYbcU+}pe@2lgJC9-!NzUTjZ-d7pyKj94j{g>zuiT=(1 zbqp+YQ1|C^MWJe&)2AZe$2oVtu9a{pzKH`cs)$Jl;Q)Lw09Y*l{(rZM&R3F1oxlEQ zCU6)3=`!DYtPF(CoBT`k1lZa73$NXXe%Hif$na5~;QcaJ*r2c2HAxnM06VW%MX$*t z6U~oS9=(?NIOr&b$|2fusZS={afki6)qi~jLaF2LE&e4sy9>L*f=Ay9<5UPw07%c8 z?Q*fq_rz^%u<kmA{+}29G9RZ~P7if}@&2;?Lnd~O2U2VG$yBX2lfbAWnm@l_`3eNO zY}jx1{tLi<yG}1@J;br!EjzI@;(%D~U?&gzi5g%i{v|@(YzL&s@qj^iBS8{2NaY1A z6DHsx9PlpxfJgvo?#S3xJbv2G{~fo`*22{@VNb==mMAvwq|n{M|ND`}Mgg=Ce7*py z1BAl=8kbSY0!`cu_W9=+;>(K~PsM;S&KBZ7OIIK~6z7cQ8!M!QIRZjCy)EbH5WOuB zO^CqUSdu>#+u&kX<Ysh_dNA##PGB%0YU$?D3PZGJXH$SHm;23ItQwh&2hISMKL>vg zLvskJ!9fOPZ0@0%!tpwYh;Xe%ucNxOE8Zi_$ZT()nV}g<(=qj7lu$A+U7)Yeb6;Dl zk6w8C>kOE~aXgIuICs>x)nhDHiGJ5&;adZGObhcmdT96O+K{_9_u|tD%itP~;U#gz z{noZNDz7QGQ7K#6>lOe$6XDx}9IAw(kFjPL=kR*TL{0@TJrw-q4P$OiTYZ+yaf!t$ zZ(;C*+?w5A*>!yJUwajvL4>RBIK|nX?TC#-0l+89#C*x5Br@@5iQyd|9besVBBMQd zB{MY6%<5*oZ8?QIxO(QTdOjri;<OLI!8N2=scsdT8<>#r9uEGV%xwhgs)AgcSKN|e zF-SFDK8GCgA(L@jJ%x?02r_^*<f<OC6|``=HHk`ILFg|L^YWfuOo3yk%=5OR)YV5V zRRS#?%UAs^V-mu>Nfl_lQQP+Rp*n!L@x715<&9p1-?XI)5Y^E>V#C+HjC!ofm7{l% zedbcDwTE4VkNY%RsX)1+*y6|9x_G=0wh06_JTV3`3|iSoTtq1G5hge3{Heqy(QAdY z#h9`8Y1*CIHHU`Jvdprk8b9cedXL^O2z1%*4;FAv|G4Oay1s*(#atl9-iC=6#=vOs z%5^}Dg@0j8n|xuiqBU={Xhq3TsF$mBhHtf{{gF5=g?4Z16j%ClKb+#{aZjXP!VLPO z=iMR1=OD*D-4YYQQKKv=`7pTt^-83Ig>Qn_wCuQEAi2yNnA8_5k}uh0EI-YkVOsaK z^cxJbgv(6kQWH>8(GdvwRu_}h;Z|87(@bD~=t^==r3zy^R!9~S9IY`Q!hnb`q!Np6 z@tbYkB(o-;bjbmHQh0_f*CTwRG+%tsYUEC;RYd(Fq2%<sdSbOUhAuIf6X}tvatE(6 zF}``Wq8mrv*BysFV$*!kIt*wuN+om$xwf@PBOkGc|MYUaE*6&T6+$J)NFGx_fA14O z&*p$cv#$vfJf&SPOUE4dPu96p$EChxC@EtLMV^?w<ut)mAeiF&B=L7Jg^?jt)wULU znFZ{*#?7o&w3Gh6JT=_o9=C^8va(a`ndLa`WM94VIz35V@C7ly&YPGoiyd0mGK9-i zOyy<ur9ygh(+%N<?%6=U%sE{G&jg<&j~bbfdN?nR6ZGi`x>q^tcMpjmgAURozHXIn zGmm9V80zZn0-OI2yu@{$KMw3L^P>S<H4kj!cc6Mh00bWy=utLMt@-N4p5+X{npZN( zh$r7R=R2jFF+3S>Q@N*tg5B`zXTXbNT5@0`n@L^Lk%)XTq;Xs0Z__8^4lgVZh5Vh_ z->(gnk4c??WX6@*g<kD7J$oryuz*&;e)0kk0aCx%K1QgF8iwiJc4M>w8k=0UGElsJ zor*x_sJ(mUJtUlzswb<NNyiN*7RE%m(tQJ@^-Or6#TP}<be(xV6CDP|q_;P<Y;b-4 zt|;)jU5TSN*CFPJbN8MG&nd|yYsg=s4spe|V-nfmuoA^hu_60?)P2Fcxdb<@@4i`* z71Pp};6VQ0S&vuKe`aXQ&|Om_rjEIc``divIX9SNwfE_(Pb>K}jjN3AG8jr$y}%fY zyG6>{J4e;XUb!_^7@5nx@fw41K;w~{1I{?EE8VaW5UpP+rc}&55F8~rDMr7%ORFv+ zDU;;kn36jV<J}U@{7dvmZK8@_rGU-gy7K%u76{$_m5k7%zfPL8daqmz9Rx{DYSt`w zh_OF)4ti!d#=7wo-kvYglQQu%N})qx4&WoO!xbUHS9~~=)^#vqCR_w-4Q=BW7Ck3_ zb(G%vDQW|`N27GZY-MwtcA_z})B5DnbQk1>fngP{a|yIKX>bgzStiE5X+f>Z1Gu*_ zD5}V;h~af(y@d7G?*`IoGpy*m22Hm~|DM(HOX3K4aLI0@esAElr{JTw^c~iw3RXpU zf*1>rU;$ij`BZsSOYz+Ck}J$|{ZfhNC5z~z!GqPiQGTD#_}-1$3mBFOevHa3GY~MX zkXtlU7?5W)!7%VyruyddBT#~UuGV^op;zX6S>VrjSo6gY4b$#j_X0r;MImqGV=YD3 zoY1_sLxy4B4%64hrI{y9YFhUL)J_?6d=}1}a?uc=r57E>j58Vz6ZoEMJ=^LbFNu+S z6W@3%OJ$0hk<_4(<m2ZrNBVD%0$gcO8#I%AQ9%a3=tEl!<Mo@|Ouf`fYv)!oc13br zckx1J&ygW%;keN@kKCCoDmAm9>FSUZgGAdn0z9iZQhGrv^&07&%vHue{;lv4x&cLV zAb^H#WhSHP24Nf_ihdq!8rsY|9lg<qOrkd(yR%cJ)H^c`Psc@P`^-7MPO_f#C)>8? z!H5(&KySk+pbZ)r(Pk8Xy$7Bn_+}NozH5TvGs2uxj!c3o{U^q#=R#c_luy69?{3D! zfTOk{x{qW5h|wa9ZPMWFkU}h~8Oaf6g_OIl-u{*HYM51p7Dwfb944n1X6g?zG+9vU zC%_5@qt&kTfKDMrj{%SY*45nvR}#SOvAMo_)x+k&&T9Ma!Fz_JmBEc$A9>)_)wQe3 z>F?V3s9BG^Hk!WO+p-cBE0jnK)7;QBj>~fvbrI@&mS0?P$eowflE8Coy}RK|B@+J# z-Om)4DHJRIBlc<11F_WNPdkThQZuH0b}}}8?DyZ)OH|xW5|8ueEjc&^JAzikutvb? zAA;uthDU`S!}{ZTE47wfVaPh4p`j=wl`TZN4ST_4kbM+2{9r@sc3dO!;S-+tc5;k6 zws=mF1qJL`ZvD%-&oJuYo-H3^d%lNwA>@RSsl3pPI#cbyRE2o+{4B<qCXF%?K^@iy z)xi~bIvG@8Oc<vHz<*#0@kZz10N-a4Yt5T!fzDW4@zSo8<*n6^zurTFSR4~#hPI7< zLXBmR4N?A^tA*J9=EBjy9IEy&dhg#9NVzLq>+pCnLNhf;N`1zt7Qfcj!QD00SGY{m zwJ-;n6m0?vl&0!KJvuQJaf8~+=AFja0=QJwqz3=oPw%iLjS&I<0qM)$JjczVEMZ02 zX`^o|W>bB&C6;uud~qYA)YJ`4i59H_(@w_uGSjMBv?VbKD}J4y2p+Rx{2|YAr&Z8+ z)Xwms1WGS!q>rzoYgTeK+hn@$<7dmVrXp2+2V+h%`^ppM0>h3J>(eknOLLtqg{xk* zJ>)G(3}=yWo5RIk8(d`I#M0+u*{~yb^#rC7qGqbE-cOi=H3xoaAl+LkWKtrraZ73a zRmO+s&XFz*6kd_dK_oPUbf2V5SdK@O>a+;myIZ~}^|P%VVk%>>v1~O?`TZ*=OR-OF z0=3FNa-^Kf40zON#~P;&QquQTS8k-Jn@N$*SXPGGQe^MX1?0lHq3)sE%xU;ok1p5H zacMC!ffXz0?}Dlt%#cxq#}%Z*s|1(QLvwXYJQ=Ka4p1z?QZ>$K1>n_JB-!$!18f>- z@DL2$Q2(-z^?m_&M<!32cH+C#mB&woTH_41Er&N<x;wRPg|&{3*_(7YY;b^FE{HH% zz=+chM$r5?9qps*!bB%HG&e@JcyqMO{WGUbVQn?VpqxCBl3oAt!82bWwXD0{=U_&d zD|v`-DKuCI-G4}o)MJ98hP`~HlL02p;Bx}!++hOkq#e(~ZmUR@syqEv)X*E`9#T;y z{V$P;OiaH6f5?L_no)q&XS9l28WwO_RC<tRF)O?iFY%mLGe0D1ZIbu=GOzlw+gLnR zlbet`DIO$ck>1EsyXu|xvxI!&VVd3w|3n^Q+AHe#!gWKjJ<$CsIj*sQ5%DO5+I3iS zFiNm=54j+Kw3dl3c<?9$_v$%Y6m6@8TLD*QIqmH{J|ilvp5G=|^THN(5LySQBYyxT zJuxQvP^6^V;`eteR~!EClG*-g&eg&VT((7#p0vEF4&ZE}4BPR}R34W_Rkxpt+Q4}e zj9WlABgz^MGSF85w-|4NOcWX%B*5aj2sI*WJ}!D*p6ERtc{7WiShg9Fo_60ck4PZ* z{9ZwjVseF4^2#Y9aG2(xAreO3C*U%JT89~RHFB~fojpE}vxtrSdHNs(i{W}k|9r1l zPh7Fd9NvRMl|?6k9gmY?H^Kz*;02pw<;4(nUqpXwW|n;SQ?H`TZ^1EMj53fU{zF=} z$tW|drc4Iuv++om%M;2;-m%UXzRx8a8Mx#ZN_1OazO+`!@$sbpgqj(j92d}{EfjJS zkOO^kVz-T|$uUOM4)HcXIBfjgA!a>}Rda@Jo*ueUjFGmk<|8L_kq~lo`3x6<L8Gbb z!oNfwwm;^uzTbg6m}m#uIkCqC73!<jvk;<;xlI_-EQDZ4?|czG=8d21b7o8#xt04h zTD+L|v~zOeFOh7B)b*!+*JDtKF)kOm&V&HRiS`g<f=97AwVa&jwWdvF1xs>|v5czF zOiMO#$#Jh8t-a)UNp)z3OyPIEcuuA7VZ6IcHdIl+zIl;v3@)zJ%^xIEH?mdHcxGQ( z+%!~af1sQJ64i#zj3uwCY(*bbAT3>$WT)#bUF7qN<8{1-<b~X-Zp^+%x)gUkbCllo z#s);Kymm}7-|9<JA^TBocY59tEjsY>NA<@%dat+y*Xae{>U8U8s2iju%)FPh?L)=M z4?-&5eZUlO#k-<pZ7H%47~EcmMJwOaM7b-br;7CjY^nb4gN0IZlk4Rr6DTeEZ7tu| z6{sbPu-39kEa<LFp!~}d!RrdWZhpshd*UCX(vJ3z7Fg2HO<yR>89^10kOUxgQ)Rdd zbSQ)DzqJB&>}Z`ko3ym72~kkccqVgK@zt>AeOo!+B))&lQ09S;W-9SsxLnL63LMKc zyh)B%EqAr>PZvQPs)i_R?}8mn)ch=$ZRC!ePo4d_S8r{8%{2RYV#8n3N!g?<I74Tb z5-u?IROoW#`zV@>!Jx*JYCv|{mwQ3WW7GL)(z9wTo6o5hmdVoo=kP2HBii&u)?j#$ zN<AlE5RLUm)LIFt)p{}Tv5g07`Nrj0393ohWFQ)VTm+o8vo~VDFs4rcbJXiAeB!#) zr?f=f3@f)-FTFcSNvlCJ<az9rO1kri7jZ$)mra=8putI@FUH<*?8L)d0M{`k;ox9* z+Z&rWH~6okU+y(ootm>E2jADaJ{Fr@)I5mJH;I)f_4pDZHWwy>yTStZwCE6DjKi>n zf8q&mqcbSd+45$vNoVw($Fqs`*|#qZZpOJJ*zqM=zM3K{#|dq14uRiGFBMV)!c_~~ zC`A#wmu@QqGGWj46|*FsD$V*Uc&LhT8$9}ovt1wQ3^)YAr7)d8#m(5&Zd5<a*@@J= zlH;w=Dy!3?O@Evg|3>R|*m)W085o{N!)o6Hs<M1ocn8(kD)izr^bZgL3o`xFCjj>@ z)0{Vp(<-et9)3!%R3>ZRS)tqV8B@9k0`G=NU6;T-VToa!xhP1|IR`JzE%UvV<S73% zL`^Ui#AHrvm@$>?P6|C+v2x=F4UEDRX=2R88?}@x1>6w!4LUNiAQ`i_Iw&vQ94rX+ zRfQ|Dt32N54XA#evJ(BF_b0+$>E*&yv7{jD-mk|ScE1R`A<i&L!uKo)hypJKz!!`I z6(ufRgvPCY5@mmO#sd*<?O?Vl(bBkGht8;-(6JPcmT|!`o`a`~e}V~fn-pi!ZJde= z=TuB1@(V38-Yyn|WN++Mm7@ViSJSeJgy>=8C|3kSr2f;!vF%$%XSWPTjYi;Q?~+?{ z%2=d-&lPf8m0#N3&@?J;5a{Mt+pQYcE6l&N5rYkzA&+>!{8E$|0!Rbivd<O!8wqup z(+1TG7IT?`X0<|o2sM8P`G#e9PxYd)b9BkLp%qi4(#^fX7T9nhEo=}{vH^ATkTz-j z0Cl$_wOSjeOx+;g&ejkBs(429hv8Y#Usjh<g_s?z&2@TR>ovue-VmH?G33cF9b1$3 z`5j2o*ufkV5Rt<1Re18gCZ|~8LDP$Si5CaE{Y+wgxAC_+=cQ~D+duRqI=ff8T13A+ zci-;~G!&6pes%CX%|c`z-v9ARI%rUnc}>1n<8#pFz~e`#<1w1p6vC24a)Mvz%_U=W z7FMSss{UZfu%$Ul6Mn?}B6SfuvLB?wlC#xgC^FE|lDZr=)zQ-~J%jG_ykXZ!eMi6I z*1qg0CPFUv!ZL09SNeknwmREh=7OCV=1t}k-AB{DyWWbg&7G(tK7TZ`bB9!yn99Ox z>?(~0=Q1?seOnrn_ivY$n4axc>ti$AuBkpj!9$FTuH{g{5y@O=xQgeB1vBG@1dB%7 z5925Lpp+7l$@^L!g5q0*+e={-xLibAH@X{1mSm6aOG93px_5I3>iBG`cD2t<?{QoB zdDk#POXJ85of0aheIE$56r0*ijwsRLnroq)OIuzsJw`C3(0bS(nI%Q5LPz*$iX*Qn zc}zxx-owO__*C81?2!4B46^)PP_z00khBY8Q${asT?}DLrLJ4v^tB>?q-sZ4KMud; z(3tA)AG^)_lsoag#C@bPn_4KlC=*Xvbb|^TpOi@FgFGt;WZJ1j=yxYuzyg2U62gY= zbv?D5lTi5nuk+Ay=cFRQJ9<zn|IO<Xtuk44CJ2kv(^jo>jESAFq;pin?);!!rC~|T zFZsfoA!ZmzBG^U59T5<}#o=r+SJp#Q;V#XnB_d4J)@s~hZ}L2KoJ+BYzNchHU;iGB z^?Kbx-Fa=`qKx=7<!p46OP)km%7-sWx41s227wMAdj+Crl=Xg$A=JbD*SQSa+v7Gz zEy_Rrlg}z!2j9`Z5_+a(<yAP9@NK)qj9Wo<sxR0aM{}qE6d+MJsw)QQ{?O(>z=b2~ z4`EVI1G#W!sqi&*|5;Oz;;dqtgwr3aYRZnCKy>hPdJ2tH9<N_sbU2V`O;nVB7C$^M zJ*aBLLIOS!+{&8P>?yEf)ttK>fGtdc#&0D+b8Kx8>}6Zd05M*XHGNOZ&$U8tUpD95 zu}GaMW;@ZVMg<Av61lkSo%f^79dVuRS0ZkOOd(XLjCW_PpFb}Z8U#6Y5~d%ilZu-w zFfwlQLN!e&PU^Q`x_p5R*7*WT58Lzg{`}CtK&$=6ec=8xhttDW;WYjd5%-aX$Sk$= zG8uNZb}Y4e-5vK}zYwBK=38dm5R(-Qig)MFc7pIqKh4z?L4QRL%YPv(1dk@H(LDV0 z{BTD0n>zw+Hnn*-3tpC#8#eAUpx{acKV9gyITTWNOeIvKnQkC&nj;n{nHbBf;ps(c z65GB}AkC)|-h0(rC05hps-=gHS#qj=Fm$*jU<axCm*^NEow0)d-C~yd9yVo(uE4(q zcFCarGcF60nep28D7GtB1@DImjvCV~d8c!ja-b&uKRxqGlHz)2pz=Mr8%^kd9gLR# zcW)WhtjFB2`pcI%=F-mCb0!3P{{Nw~4gTl)s<0Sl@!S0$V@^t91TX54j8tZ_-D_w6 z`G0*q&{8*7dIW$GvVV!{_wk9qh4bHy?c#a8_*nRM{MXxx(|dt_C}z~+Te&|%CBUax zHwo_nQc2htZWhqaO7&lp+7hmlF`p>=|Al6KwtNylRPA4RWMM?~HKCq(W^xHr2^55K zS%i0!Kq4#n&ph$0F>4k+96%BPjo}%c*?)K4jWMrs;;H0nO>PXFOp-rp4`kUre!@%- zQUCY<Ecq9_@PvIkaQA`?{`tRK|58kN-jj;S>%1OsLNkCDJmFyYPk86QX5qgcT>qwN z>tCY#!3}?KuwQPieh!1*_lB+vj#;R_oZcoS^E~p-yZZ0PruONkp@4n8NrPh|M7U-B z8|295?bu-TIxssNp1g%rdqvm%YZv#OOj*^p|GxkR@PGX(Oo>3MEg#c$aPl>I4Qm(w zLE0$!b(v%o3CqcQ{`EZHg3XPx|C)vGWOCMI?_k^e1Y*Dx8JNd^zm}5APtayJ+1El# zPrJ8Q+fNA>yHD88Ai#D(KGlClZF_b3muRu%-+;;!M!fr9qI(g4i5dW8`nyG^+wTYc zN@9H4nPT_uod#B|=Xoc1UmwGPI{#mjPwn$xai*@oFZ?gW#g*-8{E(J^$B~88TW>Z| z;`NhrybH;jxE<KPAN^l&QYDGI3Gi-OFI@*~0w_)nVn0+7!dr=Y?tbt6&r8*z9nYgj z3BmJ)|GglIzH|dhqE6U;2~0kz^k09!y?rQ2b4g+eTe@#${ePTTKT)I`s1o^v0Wb51 zNkEiV+cl4Y;iD`Gopmq26I=7W1Bj*HV1M?&8NU8-D2SlA11y!2OZ}VM^af9u!+?d8 ztPT6~d-E$q#+na6r{J4}E}0XC>F>lAebm5rj$Jo-?V6j^Y#m=x!d7_+>BI*h8knoz z$|D3fV_X02Ffc%ixN8<0nGnW_G1*RCjm>8Dc+W!5i%pXFF^XbM%P(PB;Tsi;+u-=z z3YScdc{6NkYTzcmY$kQp+uPCK#@OCx^<3+I0a4@EFaJ!$rk&KwbqOsDI(Kf^%1%-M zw*RAx-g(7KB8To$?$)cV>+R0MpJfFM^W_ZV6ON}kO$ud3{N0s2+c&E&Ab2_zl-^hX zS}&0x?AoSuXW<@>XKO!xlgdJKYZBIOKI0#-bgIXl6C!S_=Y%m|U)CCQV%)D9>ri(Q z<q1Di+s7v3yfD6q!;0jy|5#d)=wmM4NxBcCovK`!-Jhj$SPjpyWxicEmm0`qD&YV4 zv4pNvLU^_a{}b5h4ROhcnL+UTO?o9^!kiLu+hX6{J)jd69RfzWo2p%@l?f;N{UvgU zOt}=G(+u5~7&ULfZ6_fGM4tJE##Tci*cX`S!=@Fc15Jd7f(3deifgVXriUV6b`+~W zU9sxM=1EaYr!A-=bL^QHAE}-yN7+Cc{b%U?%j9WUF^Yt##RvZ7`_o810Zl0ufnX)K z#H;C!1>IeD|3Cq$3euNBHzCNij^s!2gJU<sYvh&;hX#VBiv&~hu8T8-295XlVj^D3 zs^nyt8S1KkFTCkjr>BAgT($R%+;uowmc)1CkyN3r+LbLBZ@wSJGNM!8V%>joyN&s% z#Y6}^EvfphsEwqeL&73!dpPXsHr(1-(;l|Mj}|HHoZBZl3oh5q*q|ka(`H}Rc?K={ zxp=aK20-Wpnwzd912*hBAT`2dJK-ywtN+UI$I7Mq_7mQfzSqxI`kWTl+htisR4`0P za8ln*=!+0npeHkOe9MK^wBV4srU*B|!bs&sML+VOfCErBeo*y!U{=&2!E);)_O?1^ zjPj}ZOq@?80%KAq-QIe+a@>+*yD)PyL!NJcYFk?HNV?>y(nh@klPP_n3}0*BzE-|; ziLQ?~Hc8xj`+X|hgny*#b1q_LxG+vSWq)ZJZDfD}?oeFPMWt)YKip5;S$ixJTV|(U z7kg;=XP$7tr#^gMmyEr`X=Rytdj$Qf`%2C{Z2nK#@vs=<*w$+BRRtz+=+N`%n;zwU z0WF4R`S3uDlmF<RdUqT_Cdt%1BD0;!Rnlj5I$C7f0`G(y^2Y@JKYX2cR8w8I?y(}$ zyC4vyccfQ|f^_M<i*yi>9wZW_N|!DmASLwPL5g&xN|#O&KspIEK!|sLXN>#3e)pbp z{$Y$gLbBJIdnJ3X-+bmX2SCJf9II}|JzJ$39u<%(E3_|iu=^T~o6MF3{me{lpSRGb z8ckoRBjzK1oyN7pvo=T6N+_(Z5spqmb-q6lqHv-QqMv>^jx!aCf{GXSNi-C=kY*me z74zF}N{i%i{b^>+KgyXzCCd$-HW@T&V=>%g&Q*qs{g&-AyF1M>ygtGRos8!aRlAh; z<+HTD{C%tYQ+ZD`DtbMejUnU3)@1$(Z}vilA-4)81G0i&BllKhth$t=vH@y$X}jOV zk=rn10e^Q6ovCq^U;q8&55b4iWxl59XKg<>Fzc1?#j}>W>95ZKY67)8heJ}IiAMHf zboqX8rJTw_roLw<z%KQ%Ln!$iq3{#%ZHW1k`oo(?ijwjC?p4c5A77~oAO-kKF(MZH za8~88=rS1^=RoqXY-zNAyga)Ln6ZNsYBk~UfWEG4b>Tkor-J(W>hSGnv5BhbJ!(9W z9G?z`Wb!ET2ttN&ZU}Hl4p9)hP<RJ9R2z+3rk%wNRR|%rEYDb2rttpG$9rX$nG7%K z&5^J8MF^@tCf!T=-P{_k#&UmPyxS(gRfSw)VdJw;=;Ark+hkkrLbyNu?JuZXL5ARP z)S~3=jkd?V=~|XOhZQkhHrseW5|C2F=*#`H5;FmK(Za*?$CUM=vSgB{?<Vz3)dD7l z4^Os03>~Zx^R66ns3cm{5L;8`iWkC$A*2xKm7d3}^QUSDd+-?LWpDGZ(dN&TKmL#{ zqF7iIbLM-d*S6fUGB=B`?#qPD)AzR)y@xpgHxnZ4>6Jj0&GZTR?X8S9Nj%HB!d$+l zGjp#i5nT<Hpn3vhVgDokXzbW~h&rveoF8xbZn2)eF5Yo8v8~0CyH7GeY9PIWI`$le zn>{v0>?X+#I5r&do98kK(uw<|7yt-VE2kl-Ppj5|OG-;WU(5GPLkOJZP4z|9s`l>e zmw$O^#d{!Q6?U{&<SxQveTyt*9nD)!5zPVnaEAb{OaAQVPpiur9c0%I+j746SQGal z?*&bM!I@$>)`Fnb3<AD;+Z=I#TAH2Ywu*`}vti2nuG<~P*v!kPfQ$B1^neyN0K+#B zbOSRG)j<3~Kz<~kVA;8DTVjuzcj(ld4YDUYM%k06ME1M;!(cJ6aR6Vwf(ByQkeZ6C zX)(J&Y>SXH6lr?~aVEB0NU;8eo7FrY_Ez4vkKaE&t5rW-kd3b`Nib3NzQAG4BO&>u z{DH;odFqQRZd?Isme#36gZgjE_WZ&Amnh=C4%Xic_RukUnNQ_ntQ{q0F^{*8bH{kA zWBC=rIpH#tF@+fQ&+{8P6$}Q6B|?r@O`Y~dn9ewH5Jk}U6<T>#B~13h^ETHk6Uc<d z67L@F2S;50_5|+7tA`)Pd_E4)&mkKUcdLy&Yu=FmLaAdTFoCP|Asr%4kFW-nWko9T zxy;j{KQ&l#DG%MpCCkfeDu(q+A9=UXnozd3Y6n}h@XOzaa6|Zjr+0FpU3Z_$BocZF zpp0C*q?_{k@{(kNQ;o%UfBGn?Vdt<r3$M$LJl=QkVh?&ciRC%*-+@N-`DOE4XI6q8 z@jZCa@sV{jdM|7$fjvVh>O5iO3Vyx5cd)XtdQp_2GLMgc9Q&_MSjyT_25cOR63~ua zl&-vcfXecEh}BNa1Jr%#mamoe>vo?O7kZ&GT^K7{CJ9e%>hL(S^37IVcv#<MQg>@Z zvGi<_OpZYbxho-W{F%?zKz0^=7m(0sP}zfH&Q6=#uhQl3V9k(c-B!1zcHx-y-(g~F zsq^!?{F(wla~j9Qh2ddIit^_#<ZZGg6xk^UW#%uEPJteHyVIAHIM&IIn?b`c!pbi{ zUmZQ(Te{j-2`sUGL@Y2p1b{FjgBbV0QdV}|0#7AIp^;^=OGQYXZua(kKM~j0fDBTR zsV+B`qs~{lsU8BicW*8(Jh{Qe0FHq~2ameiY&uBI-%YI~;^Qu!M@L1?rh5(Qf6h!^ z=c=c%0j+x!Dmx<@ZQgx<#3W=EX1b0pQK&HU&gcD=?XDL1X1oWk{JFirrPGn7g;sTP zHYxoWbWI-t3YK#$#{UG>SH&Igm=`r_lR#z6Nfq{d=PEue+%Gd(ZMYs-V7lHY{2?@! zex7r*@6E_no;*`$FPI3@aoGo>4dQ!>-qCx%;U?NI&-={;l_E&9U}pBM$y0$!nDz1W z?7Tr)L26f{%oISUt^y4(mIEK;h*28kq&vh#cLaT<<sN(Z%FSfIkT=d08cryyc6*12 z4vDF7gBqc&<AX#va(c2<kUSC+7p9COBeCVFo%5>8CSE&V@Ame8qq+Ig*uu@h>?*0} zEO@MziHwig(2|3QV`N`B>eO>wiHk>>SL-k_DWlD>C4LsljG>l7lF=cC>9jvx>G|q) z&-Px*8Q=@h$E60p^J&9USyEZyynuaafh$tFOv@x{YSXMde+WMU2oKuG(X)u<_n0y~ zT_GHu_=ljM0$!1t`NgHxx4nIKp6PL$dfijj5l<17`|rM}y(?+ro;&hb$UKd?Dhi^8 z(sayLwrQiJ#3~d`ELjK1nYQN*k7sM^o#ni*GPU2cH5xox{CMCg?GPvK>Pu$%mbwdc zt<%{}1^Kq|t0&?h)Q`$!3%SrUU$!OLx?JXv>z4^xbEu7*Um=$!B8ZckZv22YEfYOW zXvMzw^v;KhkAt0xGW&pv`tTFqi8kpx2<O5jwRuZplwX#h*@da$YG8nE!=pM4$_&*? z+7HS~SBlr(4LzD$XTM5Oe*|3~<WthLf>x?0pWD)WHvgR(`J?_Me$zs@|6I@?H6o`( zqGf7Ltk<A+`Q})F@ezE)Jc&q8%%LixAYam)(#$)IV~<xqpJVt;3>+b29M-0LJAC;e z#v`_29ixs-?XkdU&b5T}oSpuZ>3w+^D*Qy(eOYx6MV!w5K0V)LZ#^6wvr-N2-g7+l zZfnP`Aj~ZvSF}-x?SPoKcf@O*F)AE=Bel*^N37q9&&X>>hlY;E6=;$KvddP<_e2Zk zuq(Ye1OjbuCEg=1-2!#ukQ1X_ZtPPPsAg)SJ;4|r$%IFJ-y+RKBU0MhzZSfyKz4?* zaAQ-mIj0jxHzt^0h=*4dZ+~}hXn(m{uiHa1D@b?Wl!b^*q^-Kg^YwN27xq*EQZa(E z6x-vyUHwV%?XJtOlige|BYF6W=YDWhWN79@*fo>Wqd%*uToc-p6MLi{C*sw{J*d6p z!_32D+}&zes-M}d97cbqM9WaVPAgWutQ%&t!U%Pq!85pk>vBHqo&-i$UAJz?TAvP& z_G<Fl@+W9dOzHTA;Zxc8@T;^sP73Dp4!T?tQ0SUrUJi)iuKLsEqAcA6<4pBE34Y)3 z*ZM+svLOuRy~>wkzI0N<l&$7%&R7vP|BMT}s<NRb)jN2em1^S7xS}5}X<C81bUGcS zQ=L`w<&inpSqvnM=%8`Mv&}R};{=L!mf5EZv}FyZ4;-`chkHo`dEA3t*Xvp+x)ZvX zlBD9qmd|lt<C|sTM8is69G2=OKhn{n<!xY0jEdR_OFC;c&wiBFoM_~c2`jX+?v^u5 zZ(E3PUd`gSvyX?%3GgNqZ)??WqMT>T_!Z%L@aKA7v5dOCGX<!-I;UbbA2N?%(Qhmp zQ-EE5_v8eQ$F^igp5>_+g$oCM%+s}v_>(&=i>R2xQc*YE4bS_j&qNdjQ~nUdiH&%4 zgVA+3Ph=#{Ij{_3Hb2qp(s;V#-q)3A?(If4<itufml^q9O2u@|adC9uP0OCj>V6uA zZqMh_@q&QNO3yrd<1)Qbl<ZemB0&z3ubFBu7kKOY*9YZ7A10p%UW;^V(<YMYkK>ej z6%88U(JhflF39lGIW=S|QA~%^k2x!kIP(H_Zhhd)3pq$l_xWsia|Z=#c)Rfiaf%Ys z**G{wMNYKWW}W}8Zn8_4oO(z^&1Z`eWQ~i*65K7GgcA<)EjEEZpr2_~+GrP_DM98? zB=9#y^V@`MZPMB%-5Ampj(u?MU#i_Q;`!z*SPVvt|Jmx;J4U$82#z}Vf?hhAYBXkC zOjzpj1=^!dHSi66`jRN?YQm5D<o33Pt%p^GN<#A`)NJZRz-4&=sg;f~9x%q=pKyOj zKiN~2MK)_?BQnB7m$0y)B(UaQthl5orh6`$7Q5dlrh5t|@)070ilCXZQWF?mA{5dL zrhGdiv)QNnro$tOUrGs83e2B?E|t}6L%`0rUY$NA9y}`=Z3ImkxH>TSGHCy5R@Rt< z`vzDErE69NcwLs1_0{j)@_Va7j^5Y&_`1+$pn2D#6jAesz~q}2%b<zVp!%aS$ta+2 zY{69pd$HUtMv9W%(pCsRYoa%N0BVC>S#6PLb_pWIf-7JyxR<ly%>q7}tdl(<*0mbu zO>xL8+`{Ha-miwN&o912qB2Zh20SDfV)YLqYzMk4YlqI{kjsf8QYVaif<W<Cyq78x z63+<w13yOjC7N<%8z_&eipUV%Oi?*~f%SCDbESvTu7&hU8e8#?SLktJ1k;^wZA7}g z`cUTVHwZl!DoixBPaj2Gen7be-|;`dk2gsyGhcl^$#mUG_a*Y(W5zx9DEaaDv)+=$ zBJl7a>H*P>OgK0BMo>qQtLS#VOR}jy_^3LhRwu;W$bFx(%}+Z~!Y|t2U9)gf&9$Ef z;{8EtqKM%2vTkIRg2|ZkhvYKD6tfiGk^X}1%j7NHq3Wrv!Fx_G9UXB>+O%4Fl`jV1 zE*U@_8YNT_Gyi1fUP~&mK#+Bv3U5WfX5U)kcLtwh-qF<Jy?YJLmZ5vnhHLV?P?K3X zYIKpYHaWH%*>@r!u^b4x?=++1;x8{uZ904rb1J+r!k!vU!$T+7SQ7^AYcd(B)dXd4 zr~1!;sOlHU>0LfTPy>1pb<*o7#mVPybf)&`Ce$il(Yc1yszSrlV?0ta{1erlD%D2~ zq+iu_I<16(YN~p+gycMBTtO624HBdI!mvVD<L9aK0V$P*ldslOqRqY?JTOYKag0be z$f;AY^zH?wIo%J}O0MGh(ZImXo{<=na$>aZ6`PsHub*gihCu8)CPEstxyE=}r%PX2 zy7-)z>SVK|NKNSU^_fwp-Y3*bc1G+B{j#Ys%-7ytF$<Fs?!gxAMPFJug8_8f6$lPz zp~aR}T40lmo0AM1uz~gvw^u$*spD?Q=H@8Tb`o9Q(y}`G0Cy{n_iI#L=h{dCm@&rs zgHW4()zVcSU}x8sx_$aKs>5zV+W!?dfqkSD!L{sLR+zJ1^7}XqjKDw?;Eh}Phro2o zAyGN7U11&W*{YK8?#H=t;8(YM1U26_YFy7dBe8LfZ=>qni=TF=)+f!(dNm&UnK#)b zYR(^=Jx}7vHVixUEe%vF+~Z7K504T<6-lz&-YY2L8PXW^PV%z%1GIX<0-Za-e+YPy zu8rfcHA+CmXF-2%Jj^oZ62<+6Or@{$kSXb^_g_HYVJ0mawkFMW8419~sF5$%TVXeW zN&yM$i+$KJrA40)o(SN1uR2c_0ogw5I|-+}D1t7`>_wT!S<Z#AtR;P1=d?Mj?GM33 z%RB*}br<ZA4tB8$`&1q^i?+sv<=~q^8{9Wa@}jt}M?`k6-SWh510ST&yuAz61XwFy z{25Tgtw1}Vb4`EC`jDm(V6Omw{TcT3KMx7~#Q<PQ`wa~Ej2-N}gLMSe6Z{Kd`dz5t zg55fImcSp&#La<($w$qmtH7c|T8DRc*W`eYez?`~Uo+d;`G~Q`MHF6e;e)wv$owk| z`CZ_{yGi&Ca(r+@jmdw_(;(*r4Lhc-h$7&-F<|XA3yk$rz+;9mu4BDw8n9S0Blukm z1mG818y98=4AmPbArkPV9l~<q6>4F#Ex^cATY)!&`#^`+nt^kLH{_b)xq)Gk4vd43 z#lMir17{{?1mnUgU_0yJ<A;`guP^>SBJg%w-5DyB<O`snV*bXo=9r_d4HO1-{yqhL z2PAPm5;>SH`YUhibv+$IaezZVKEvUA&OzuhVMx^Mvsj<>)r9414e7$cZ|lrc{&5kL z=tM|P{vr51;W3GG0vP&=Hqenxty3FQ=@3P*(lTL>d7d*rlf<vu<38t|EuR9yJvduA zx+GtNb=O0IjMM`|00770cJ$s!SN$~{O;;JnW73LEk@UEAVIKm|<))oX%mD6f7qH;Q zj=m6EqcgYu5FBkuZvCqe!K3I8!C1jc5q4HoiNMELpDRYke9nRG+G4*|gq&Y77(v(p zjOrJR4Nr6MSDAv(wGmi1IglI!SL0Q1yc%wT+IN3kRrvD`zI(Mm=bdzNVXSBx^auzt z4=~8GE1<{$s|k?U^W#k5FOaMH_sm_>^WK4tJ69v|*U>`#9&_IPD!nU&MVMbdanRPi z)c1jQt#N6tfi^_}sfX5P^KJf59ZlU|#B%sIwz~aT`~Ko1C<vQ^N$Z0VLaCjRV+4zv z^OpTJt7Vf&zWcWsU(KiV?HzB-nDl*p5T%-%tV#Wp{!{h$O7a8>vqK>)yZ_!1Qs@`# zlxe&^hXmrPK66q<3v(G3t59|_eYNN2d#5e4gz7<>YVG}@&B4JD;^Zc$dm>g34{(&o z96J0gm>I{0B&WgB>&^HITtB75C@x@ad`V>jRio6q-5z)M&^WClo8|h}s#9{kk{CK$ zA=-SyUhX$?KRMJ>ckARb*0?QeUUIJA((Lpd)Sg@3YANn8sv0_JyV3KRO@j?7cNQ%I z*!fe&xajw4!DW6ZXUUt|yp1k_Ooc>8#pF8=N<qX>T9hznBmT~7;vm4%rv{5y^`QH; z)xkE2G^Y^HA$eM|AYMD*-R(^~OhxT82dShq)#1yJny-?q##HTbpoLKK6}E^Ygfk9= zk?eaTFeS0f*47rxlRY@9;q3PE>j%}0x4W0WxYFHZp4ap$9>jl#Awf6u(<_Cup40Pr z=Ij1Yt9m29YZjGkVNp4$uEoQ?K3pD;$@#V$ET`COasi%qCFHi@(^Q%W^C*Y&x)d@f z7m3-v5h*b<WR~d|%wm{2^;&No0-hP2U=h|029I3vAar95@*uK<s-<Rpw;n`cX}Yi} z+I8#8TXomy5vd+ekNZ!>MjR<qeT{VXCA-;=$AaC^`n_h0ZyMpKd*V6wiCBogpJX;k zrcM?IaD?C4XAPSXJL0fj>Y+*@^txU^gqMcCtQ&7*_C;x`ocaM8>w!=??Z8s3_zCf2 zS%dLhpt`fKw)1NuUk&&B)t5=K^L^|@-fU0VjfEG6J04^FPh-<gKcbsL?a;=%doV-= zasQF|)*JFTIhgaknzw4xi5HX4TT>q-1zpga6x>Un7GC2orRywyoxWxt5qG!Vu5y}t zR7Pzm)!Sg3N8YIA<$MZ)E@hoZ9oXbLVz@{=9V4?D5p_&CJaNPXxpK5FSSCNpZkjE= z$yl?)jBxNRMnj%Jb&6h{iw1SyZR5D;q$wa75l@Oec!Ir!sEP#F&D0f{YWpG?1jTdi zZkIKwx4!qNdN{@Q9+%EJIs7&Cw|$2Ie%z7LMAxB3<l-Q<L);vvihb*gsG@)bY2N6~ zus>;@5(|v}xC7qT8S-`*rqYNO&ro^q2+0%tS@VnbW7Aj%8P*X)d>T-XU%+_82>EK> zb#gPdY#zT(9Q&9pGXGZFce`xlJVgzGp2-}2V8AnX!g3702_3#*jFyh>qu!pctSPqY zLwx=ER%MSzWWbGYv5rDLz=hJF_T95^;cRm--@u&Q>(Ahrek-QLe6jWn&m#IEp{2gZ z6(d75C!RWW4e{?WL8ksp$hw$Wq7UJsL~$i?RiR}eaJ|}s5}lIRY`S*m{typRpm*u% z&r?iK@k<-}h-6#lyO;wOoHAy%hdj)h3jYYFTMKk7Wb2U$%fs={iuX4+wMY0aO>TRd z4HfmtoeueocR6|hYAh0C%CL+(9Kz%_rFbb|L!3i~1xgRUff#Y5NOF>=#hdf7F^mO` z5@xA6#k}}+TO;{buKYj0vzrJaD636V+WKOD;Jm+W3pU!u=oP~08J(9ef-o8ykLRO} zT{KdLmK>3t%JQtE&HnMywY!z6FLvMxKK2}YS&XHxt4>_3Ca6mc$9*3PnoKn?7=$A8 z4I9Rx?AYl`5$OHenTB{qNc6XAZ0%bz0V8QSP{p>{((g!)<_7v#Wp4wEOy|3~dP(nH z>YLXMC9%J7_u$5sUHajNGr$AdH}K<TRpBRJdBlE*gBllCuzuToEjIB=pVaJKS##^! z7yLa*NLd$Y;`B_3pYk-z2}Yt(tCGF(*8oY!M&zYFgm|y@R(%F}bU8ipT8fw<_1j8W zbBAfYWm^);<vaAljwUHoi<)w&lhPN|2=Z^1-d5<~Z59fwLAJ!t%3UF!3b0-ssehhe zh9i#vJoC<)XhAKTcyBH1<KD>2-dNl4`IQS529*aT;ip)r&yq`Izm{G+uWlMYGUuzW zSjCUg`RF(8<i~aKwSqTRKMRnFjXe5PZsi@D8<oGy5o-dOh8u-hFu$4FewnFTSYqJI zqZ_m^H(0^wp3{wLM~oOFtM+VHOR72q=eFco(DE&>V(k$*#MlIJB3})?%{~tg8{PZQ zkRl{T!+NTfERy~Vgo#&ia?(s0>Nq8IsfF{rL#>cQ^W=(IORBlr%)aX0u%Id!bI`%V z^wC0z90Yp=Sy;u_+)gjXE+8tx*26oCHYqC8Y*y#&nuh%-g&V_iou5$;(7Y&IVV6~5 z><?L2-GM?}k+2wf`d>i3x=?Sd)`ImE&CZ+l>fni;J^BrkeU4ODZ)z28jj=lQ(OiqR zN5V<|Ton^Nh{N+qz$i`Jkp@+|7NwnjxNLzjj`sFQZx*=!6K^)!{IzEn7FufxqX;CC z2Mgz_jl)BWOAxl9JxE?-ucEt0Wihcl#$7WPM}~ZXuO5rjtS;uxbfL6~apu$RfFufr zvXDIL%e#NMr`~@$A6P*}tMs+0S@Qa`;lw10riPE-1w&&$6*QTL#|O`Ntb0&s<h#hg zuh#e4%k>`jmoVoos@)KaBvw0>vUyicNy9;@5fJ#x-D`kN4_kuDA>A@E%BIAYtmZJS zEOguDsQj!qFWKL(Kp2uO9G?rm3|4Va(q~m+`OWpNxf~RR7s7b-A5a3a0NT9{Mo5Ul zc>NCKIQm>p$^WMLLB&2toJob-3`oS}<;U+8uMbN^)NKztln*;@^mdR}eOP6(cVpr% zo{Fxu!r3M7jogw|XF63gUouWf0?VTgh^1z%K(<FDS`1S|=;JFmzozpnBt<XF#V0Y@ zQwl1`DaNI4m`vT%DmN(XE4}K^XdRo6eG5Eu5(&&i6mLt6BLw%vGC}o=_tM`vsz!_n zj-7<Dk@E4<#<F|WGzp-<3umX!@x9BGn4E5KOg0N9C>L2F;R=+o``*a^k=tvvSD1L{ z_Vi)nhqUTC9+ES<!{o05^<@j^U;St37~#qD4rN6POY@7p;}-KvPip(bUOoE0`K_$v zW^e(;(+4wTIk`cjpu13FMEpCM#xVN$6Svzv?wMZ}HXpgj#JI}U$knyIx@koD)nb6h zd70K;nq<xUJT1hxbi?HC+$#sv4|%_djWqszS7mbLmi*z3by`B#{=DLIdH>DvzBW+8 zTW3cGcOkJ}r9=Jh@f?m@;blZ^nl2|CaBlq)4RQu?IdF@aFSAptuIr{YwMykCjC4=_ z0q)7nD>o>YFMMt}R&UH8-0~svlhV5C*|=NWmYKp`)k{NM9}knwwCg%3bcI5E$rV}n z_44_S73s8`Cd!&>3pCe3hz?4zIn_r1xqKo)K>=93AbZj-x?!@nHq9>~&Y-J9;+F)} z=29Bs+M9hVdf-jxJ1Fg{#+BgAZ(aQ0<*oWgqr^Ke4?C88*tDe|@_Dnp%e!tLBlA3U z?=+6>^z~IK?x}6rP6y)*zxcs@iv<hwKDwOM`gnsFt7Wwf;&c!H`%Yi(CK3vG=19Eo z%c>KDO*4?GX)y@07J|+u$2HC84hPctB;b4{^2XB2o~^YTYJhlrBEUbigUK_303#pp z&2*Z7K?Kg|Qb^T?2sL;;-mZoy(TYmpojRX-sAs~j#4DHJc`?Of;9gaNQ}~MQDS;Tt z=FnuxcFXf%_LeGB5SlmCY8t2XkQ3a)vpohaEfKGFZhBcJ$5BKv8tFJLFZkqR)p8+b zzqQ(HFeDO;1rFwKMKq+07HefQBL$Ej+;u{WK8@$Co|}L8Cbb~|fCy`AYz1<}21<mw z?+2?fR}8S_`25q%yueG=Z0om9-1IY7St;ij@AU5Th#^M>5qF#$#xRJ}8Vfpoiv<;K zx7xRwFF@*g-$X>2SSmudBX*mNMcBhl1+Jyr#c{RHS5c6JigAU9-=LR)Rsbk^MBZdH zLrs>$Z@tXZ(=X}sXSi&G-`K}dQ9-`p;x(K=$e0tt>vI|DUa1PXIl0zn+o&*UgNrGQ zA(c*InN}Pjd1N?ih3Tk|FfF%w!S=vx+G#dc7R}c6W;U`-4HLH8Fcg1h2aFDv_=;F{ zm}=lT-ePO4mne-Zj@o6&wx3HgS-au&I}LNtYlq!Ij|cHVeX-L>Fck#W3zUIxE))K& z)XIcwi#5f1)0UgPP0s0PRZ~-NNOhL%H&c-}vBM6W7GNbW6*p(jzzr&)LBh_A>;0h@ zZ+kPAKb@skZ;952yr@psDaZ7AHi{?mK)>y>C@HU44g|~J3z`9%Sqc+Iwb`R{y5)H% zj(22B9-!xdJb|-dG|9|mWrpeR_}y$(-A4(O(t`Jg?e()WTEOJ%$+_{dYNJ(Pwxr;= zn)t^h(#j$+FE^4)O(m94EXKrt2sD1DJBCTqN3<yMM}H_;`}7IPd!*Z?9uA_m;uWnr z;Wf$FA>x-{6{!gGuH61v#Ql=ZP)|(<P7XiLQq*fTZo)j6*lP%rchAk=njI2#9%2*i zqxrP<D5g^DdJTzjjNxP0w~pJ`Sg#I7Y(j2fNj`D3Y+0<tMu5?Lz{8YfHaX9aT(K5> z=UNQ+z6^f8i(VlLT4bTdh&N`TEMd>uu^xyD4xgomub@vpcG;I~8_%+GMa|oN%<poe z5gm1xVEytwQ4usx4|-ZE_ojDq+c5P`*Uc9pt?GD5pgW2u^hW>q!0OAbZhgZC<$FYB z>IN51l^JGmqGD;a{^$7X$o=am>l@yS4xYxuCwCjrLzL<%8K<J*wqbhkAuh0IV6BcJ zU$@vcFIBH`iB|cdbpu%gTHcLb8$H|G$@CQd{Ok_D*yfpq)yjEofpv3zw9mwk=Gb_~ zugbl_W}K;97y()2?_Qy}Hz~{Un6J+@aw1yAgxg0d;RW+b-W4tiNTR&(i#t}YV{Z;s zoAnwgC(v>kE!sS;iiPr^s>mQkm)5J5@AKxZA;Bod{yKjT#)6x7rkVE;ls}4x<^4ic zhYg2>(gBab4twNStTh?fQG2&D!kPrfV1oqFS<Y{HxcfesTo`aKPf&T-;`Qu-Kzq53 z&8@g!IyH&nx>uS#Oe*0>L6+{JTbg6@N+TUkl4^x5C`XXDd6Bf5)z2K>Xf^!N>KTo# zw+9(U+79DNRjP2Wjo%7HWE4kCsa|g@t-vyr#9wkx&$DQccSMUfmDRvfO7~*G93y#} z65SKT7V+)0Lnz9;N^DF%wlFsvoy6_uOeAml`Kg_<5T}_^LaOk_s}+==ycDK%$Dfh^ zVtAQ*hEi_m2mgUUz9#GaP?e@5lYk*g%bx|Y51QMWRj(&P!zdhZzE=gu+9Cd(=;{u3 zoc_eFkVn02;AOOHw2}FhCaQtc+#v2r|KL*W&_UB(1b$NJJCldUSbSU#+E6<Z&y8^? zLxSGPyvio|+BuH=nTyd)aF`XSH<`TNP29M|QTjDCz%KS|@EgTA-(Vv2R4B4GoB8`A zZ$16QqMNHH8;Kg};&v_ibF%w;dIDZTE5&wteToc5;o?Rm+LSIez2m39T<T(-2OF97 z-4n~gLo0t1YUyMt=giphzJ@FAg61zzJF)jK>7d|gF%XH>l1nG8?+EMYh){hebxmum zorWvQ*PGv1;Bm6N`9f&0gmSZSEPD$6`?nxlzzCc(A7yECGDfwyY-u4a<!rY|sUb>h zk@UVLy?uzvON}ccuajmBQYJOF5YAfAp6Ozd=H|^lk+i=%-`?n0l(aVG1u<MN;TbK9 z{#>xX!kX+{!QbgmB=g$+&|o4uN$tL4mw#=Jn3ci}FA?&8^^pHJh^mYOooL`Ui;PFI zyZ(dQOa*b)Pf$2}KV^H|d^neOkKJ=XyvaffU}g_9t1k9eM&C*Pg=+pANHt!F5$jx_ zt7CV5K){~<eSo>+KQI*zpg#|!I+s1J?#!eRcw3`GR$ybh;DkQ}ceCgB!FN<niKj*C zBZf)opUBwez&(ur!@P(7e>?Z4dpgvvG*xBrQhF$${p^kHmJX1i`UgpA|6l2`(~S%O zuCZL=VK%sUtU>C$Pd1fzsg-(dKDp2<ORs=2u==JeS3m5K5OlHxOZajJkgWcjPW^vV z-r}5fYg43lni-e#km_#x^le~dVau@dA52E8-2*ygZn|i~2fNmMA#=r31Rk7UMI3?= zTG8G9Z+xPQHT<dh35V@<ycCY!4>b7r-Ud=@4;JDt&R|zJf8KV)abCc17n&C^ps~Qe zNuBuc_!DNye_k?>Cu+BCw(1#sOpZ0;_%EgLJL%59C?M#sP;WVXA$f**oShu<Jat*w z6=(xt@gfDqmg8dmH<RoB4?i5TOg!~lF#av)6}Z1_(J2X%s9!!mno#h~O-(c*KCNk@ z+O-<pgnRem55arbrt&+Hzd}Is7aHV)=e>L6R>g`Ah0V=I**lYGFbck75gxm2;QD7a zdYDdJD4<lY@&wqexUCK$fT4*x07<WWQcw;`*V4BCsZzpW$FSCcWXHjC$IFH><EN|E z=WqTHyo2pd0Y*Ik2BYzRg}|p?hY;-g0#E5(vaDKL7SGN9Usrp7YUQ7}iUBYZK<f{| zI|$e@U8UJO8IQkX@@jsmGm_PfZiXxN_hl95BMID6N6N@dL>O%CG2u9%6Tkh17?9!r zdr|*|OKB$n8=^HU+SW-9OLg<&bhojL!ImGyql7Hej{k(V{(rW<5fq}{JjGPB)m7W+ zl;3nLMyBDZmZ<STApBJZ!DOXSFX)h=8Gx%PKY?{`o(CK20nBCUO#NHQ^2;nc;C4~t z&lmC?UK4>7pWK@=%E7TRuHZ27czhHXK><AS{EmU09qZg43k9#;?K~Op%yKajOfQ~? z`2BQlEeLbCSz~C~Ls-NL;Nj4wX8;0@0L*F}-iiIqk}E)14Ik}uEMTGI5?6HtoA<1F z9KA!8;`Q5|-0Jw+dnIRJWDhF<z<dv=QP|AKQ<8e%Ap?NkUWvdA4aPw&V9lMwvnm$& z1Y)dZwwvvp+IPh|`#(VH|I)X)M*?)298mU;5IE0R#{k2G?Ueo@Fth&Wq@>z94H)L! zNuMSmo)^Dt>R<S-{Uj9q-%cA;i>*V<z%iYt9$4~A1#{eE%vgl45Gj5%!zvmP`?R3$ z(Q;)1(}ab!f<Vkyq;!g<;2lq5YIfBM29QqB2#l^C@Wz+FiH7x%GeGY5oCZmtr_ZvG zq>TM4YWx)fVOMSbX%uY%QLu)S20urm=A#}K&)+!&FjuJ#Ij9__srw*gnQj(GT?FAh z4Adro%A>PVa!$1(i(Monb%q!^V{O%J0&|+I20kGZxmTN&5>??6)5qX0J{Y6MswU@- z6}mi|v8mC#nSH{IE4{+Q-kI&A1vs5e)I!is&`v~Eb4dENy?xa#=$<e`4l%^gm}6Kk zR-GdB!Qw))0dl%UZ!$wP%AL&Msz@wJ_iNfweAG__7Gl%;DQ1${ND3#&dOWSZleS<C z=T^?hCsObYa5l`TE4eF}%F>S7Gn5+3tgjNlrj_6fu_*M43Dz6w2J2qFHkmhB#eumM zA6d`UF;!9ike>?m<H(5quA%u@xXKfRDf^(ChgMsnsvActTe!)ulDV%p$u);^3YFig zn2n)NBM~bMimoWwecX$wHtj;oEm4tQ=QHR{{T@%o)D+t$-QRt6SH?N~m$Xf{9ePu6 zTdNW`$hmE6QaGHICUolj-MoiVXFNSUQqPurTrjZj%Qpi_62@f9w4zJ5`?DGIi%66O zQ&}mKr>dLHrhY55t;h*5sM8u++wux}Md#~(my<=iqRx8xNQD3(L|v(YQJ;SepjdQl zN3LVxFL*LW+g*sQ&g3~2;AF&}&NM<({V9*<(Mu}s&Kls~$ge@YCgr)dtx1mG%64aq zhBI@SP2fxs#DVna(E^(zehgFf0j0$qL7mzl)JV94sQk3S6xJ6WG`4c1AxlFWW8AL+ zBj1wAnAa#!E5yBMt4+NAl2gMpPotUr5b?u4<;$IfMmxw*D6?_z!JObED(1|Z9OoH` zx(_B*PBk94*p`3XK5d_|7O}$Q>Kh=ZBln_Kn3D3SM2(5w03SU1NKR6{oD+?oXy@)z z){P2X)N}6E962)2aP~HpUe@c_xdipL`N=*&;@lOHWR6zhio02~W+~*QFPIt8MPSF! z?kkr9mzR$kXc<(tA!d*;8Kz&&Q$2$Q%g|2Zj_X^-Nm#;DAB<2;c|+~##(5hhvaIA~ z<Xz2mfvGdjK!|<|0YkC~tzK2Qea`OkAA;L*ZxONn&wlFn()qW-ySHVstN2I!^HjxV z;u!W&^%V2H?5ZTxKiFS6INJzxJPSkiUVZFz(2nlBCC>)Q=?3oQeX{q&XF4Xu!DOF~ zPXdK#0PQr@q6SIohS=wODFsKXQOA;LKEo7!G_{=*7qc-qk7B3!k@(mSdhBhF#t$6z z7{ajo`V$3{Ye(sDMO#nL0GdtIpy2{Pi<QOREAA@#UM6H2V%VNXuSD-|ta6qLA?I&} z*ZS__9B{Fv{1HJ*wgWXa#Ur4?V)*wvkr+o3^caPPXm0w8?LkP4kFameJsdyUTdR?- z-bOE(M>obrXRUbJg*sm^C7}B=uQF4Z6XXc!%2tQ^T0z{iLLJ10lW(4?Y9KD-6A<d3 zf8*>g1C4wom{q`7P7y#Ur&~g8_iUtA1aF%s@m3cD-ql6L$6P4=4h!NBnn{Gj^=@Of zc^tpYZ?&@IP#CX}epP}IYk0BwE*-T+_bR>jU4)UMMajb|nEDM%yO}x$2VIQZE|uDx zfqCpMT4W^#<_vX^p}Y)Fa7{A9!cwnTc=W<lZTM!3J`^V<ZG^LAF;3NZ7Lf(LF>Fs% zckZqi67-<M5+Xc8VHAM5<QOxA4-wIGK(dV|8ppFVY}Nnt(QwVY12lx0QA<{+VC;WC zXY!7~;q_A4g0J?R_o?5kxF(-LG*JB8t(mv|b6Y~cFqXEI0U?`D1?VE3Be*t#b$)g# zE8mC%o&H2y4;;*Ob~ScLVmUCbNb4{$`?$xC8(_B~t*0oparJV~h52CtK_*3#qM=xY zhjUzMIVT@tHvn^<s@`}kcTQg?b>AvEEq=)uC=J=ts8lP0bf4ffJV`$X#L0fhZ#H#X z_2$RxD@^uC_0YwHTKpj}Y963YRs@AssSriP*eEF&a?ndF3*y?6&mB3F;osZWnquK} z0NE)*6oPv3^n*BsAI<T!>ISb39@WIj?)abxL-QHQDp~J6SCXl&Vo{OSoGMXp*G<mV z`#e>2`Y&IJXtO^AIKJp5*gzAb+elnk;j-o2=1kN)M|sn3!iR!@`lg0fzrg?nVW}u> z+265C51iUO5D{If@_bu5P$NuLSROie+TMH!M!Lnhy)m)>IDUP3X`uWE<Y-YU+t2jI zd5}R(ZL!xOxP0eLQ{Nt+ddnox$u(cAIXhtYfTI-?R%WrF;guv-`NP)n)TE-ol(ivM zI-l#7DINDay&%X0?)5UsjG#d0YHs7~#WK9qMPXy5Po@uPy;+WVrtm$(t3ScCl_v@; z!o87F(2`uoTT?~O4Ob+3U%oXT)4{pAv`FQ48J$Qf^hVEJOMPew`x%zgCXR9!8-YrV zV6{Vz9IZd_zD!Y%zFj=kJJqdUWGE*{NV;dE4bn*Goo42pcF_-gnH%mIv#mG|NX$jm z(LQWF*~C}`V(-m_hs;}1P4q$V$Yx#Rk%nDm>Z%}gYH|0AtbMYe`mCyN=e&PEh}7qR zwsRL1;GE|oQ^4n2wPQRZ!JoSO+E#<|Eqev)XYePcRleK^?*2Ti(B;dZ{_167A*^Qo z&d!H5iEI+|Mkaj4vf=on0-zB$HJ$&#Yu1~nQs*}&o|o<iFz%CD94rZS8%V*{;P_Bn zZufPvXSL8LGr?lTMNtBoLETMWxluf9L^TDm@-~qYDKF&}>8&|NT*m}^F1K~lWK&dh zn}<}~&0P=J7Z;-ZHPuH1`Q7Q`r0BBwq{gIdbcTheiZo%)LxjP>CMkN+Wk#>_Q}shW z+jE$cN+TVm`-7Gy&d!@N`Z};S=*wr5zCs_Yc(7rWP8U2!?jFbO^oIB!4I1GPVhd5{ zEz;qmmiL4Q_8*%vHm{M<HC1j*?hA2ds_~uLik@F{q<WVbcN<Oc%4hWU+gn~brdSQc z@4ai}12B4Q2D4xnj@&<QQQO~}h5fVT!s0^LP0)^Gh7$cVcAFoE$pl2#I<uiXRUv~? z6P4s*#kquc6B6CWy^0PB4)TK5k}Z<zGwR*PapS9LcO3(OJ}pCG+`zA@>x|(Gl!91$ zyXizsA^Nz;49@GrXSkNa>-%{!6h7pv>=l}cUO^}==NDO#hvSL9q9xKwRxB5-Tr$>X z>9ZfUB(Bb1!BL`LGr^L(tMrau{oHGJ$Yv^XqB<#Yw3nPvxu$8HZXsmBw82?oB+$)6 zFrQUoN?QWyTwt=Q{4(nH`mMEdHn9A!7eG%aSd`hx?0c9)PK3-@^ugZCg))~}ifCEp z+iI*I7sMAOg=i=FRBN(odNrQe**Q23JJO?scF$}P@nLvQ!1%z)wXDM2<R?y8d`F@K z?;i5Svi>?%W9meI&7EwAFdD7O{UI{7kBKW&=YGyf8-h|YLUTXoc{6Iy>Z4=Tly%%B zVfC%WroZqdgUvZHB4l!1FQmTGep=m{DjTd8DI1BZlG*uHjN+ck=AtMWOg`XO=A))p z7ntg{;m_5wSU=cP!?5BOv4MJ1a(oB@nZ5nJgOerO-dy&H^h(1oQCtl}fXSw#Xz$Af zw}<90cl=4>?)qe`4|IV-tnXF;DwW7(0ZmsWXC3DYu{Uoklk!IddeTh=Dhe(i*Vi0Q zvMvsZmiDw*t}TvD1`RPLcRawldfVqayHQNwv`ZJ3)dKi+_|$!g)73eD--;Uu8?wFE zteE;@Q`Q=^6GV;{jFqTCjYTs0WxkqKnD4(6($dy!@23GtyL%=ond+x_cZfd}Bycar zn3QQurgu8b%stsgs#{%bOY5R+C2J<LPJ2mLw|052F%Zx7dgEydHa`~eIV8-J!8SLp z>aNLi2^-~5Ok13L)*F_ETa3-BhWQNMGLXTPe1*~&?!go_gS0V5|GrL!ph=^~W!|^+ zT^D}w2rxxgiP<)_HO#|=J-93SJlbg-)Ucq6lg{7{wiLaYkQeS!QVErxlz*`EW;qgb zzgM0WLzi$XnX#fFwJ6|L-$nt6CUf1q8FyUw2>T%uN6)iFwaahz3;ek<v0e+xlVTg_ z*`A!RnH6$3_dTOaorcL>L~U~ha+E>vM^jT+2BpZ&my_Sh&u-6AGCm9A8-&`UH2GG6 zI-B~ca7I`k-!J#6j?5yn?I5>d#=bW1Pn;0a#G31>>mT4tLtWBBJc>-?io$y(k;B4< zg~f)Uwlq_0yN+CLOBF_1v+Zl}w*?uEo!Z*0=<RrFTd&dE$!Hq%&l2V2O?58=#LXfr zF+Mp#E=sei`VEtG{a!UazcMw;K*iZgDBG$BJyhBwVrMmrQ;39Eww+#O!sno&Zr6D| z*vnm~@|=TnSt5oMvq-<hpH2#tW)em~3Egbb``x1(-F&3{=1v!HXHL`i1T4Op8tlKV zNn(1XArA_kdtf|@2V;K#hG9YIl<+cVviO2%lfC*t%fLPf%-n#Ot_I%|n?_$#hij>T z(|~SKh6k6|`zD|+TnGo~xPr@EmTzGlzu;bCc~(b+_kF9Fw+jygFGWd=s%*%zn4H*R z&TIPwD!O@CUVGgUsjt00eXbH|BBy1Oq8@JZA@uFO(?IIvZ=IC-(?sVzhOg3m^G2Et zy6C0|>|{^*kszGkS9K!9hmMUwO{=^N#q*MBt)t59Zrx||-s#`IFX!_)qz5bXkH-dN zEIVVMY%oOgK38Mv_H_aGjDAOo=Xab6c;Uohugi_S_WOyts)k|nlgNR-%^*>1nJU(O znUMa%eqr-9q^Y-)Mo#v2i9kcSh$)|%$7yj4b?6=W7ZsOnY9LNAU>o{@>r@_4k;wvE zUcjDvnd@I0Zg~~lL$EDq2S2tE(D@3mraIM@Jd<~j14@7|CHM~Wkskf^*a{3+FPH}U ztXi=cl4S99+9S92{mi|M=JXBU7-5Gy4BrWAr25r%tdm}AQ(<!MB5Llvy5+AxE0)$; zxnIGay(N|(C@XJrD(}77kcc6_{<4l264OZ^oXd_HGNx45{S3F)PvPgkA05M5u)j6J zy~RZ{+ku~j5q1dS)Ub)!oHJ18)y(L~Hd4fTLRAO%Cf%>3ORC{PJ<0YbHTC@}dS8?g zXSuwH`1gQ^8#fN1bGb!`Dm)8}1a{cp>M@^bJ;{NMEc(S>v7w1Zb+ZarA6oakabMZs z``-Bvp)eMwk1kObNuG2QnDp?#fM!kmo@Y7U%N)<TDmb|OelWZb#BMsP6DI=n-nn25 z0%#86HyU6J`~bQO*Tv@kAyCxrvBt^a0S2)i>j^@CaD^T9gD)?*fj}#o{~^d02Dr(% znHLh44qF9^uM_1CT$5m9897)HFs}IYSEmCw@;V0yorrsUnU8n*9RWU<&-z0^@&g0H zhigZ4V*TZ${}B8*S=T^TFp5*w@1@)We+86v|3)$@f?Vfm`0If9?ZIh_B<{TA4?zgq zAA-SnLtun<*mz)sTs<o|*=#1D)c#^kJZDZH3C(EejYh_Ye`EL*yTSk!A-7g6wlfy} z4=iGD1qsxj+FzS;V^gHrw-T|q{&dare>z#*5S~E=8F57lCWWDou(p2)QpI5Z-(_iz z$37G9JV$}9t^kPl7rIHK#ti|^7ckt%K#NQ~6c8MBB>?eMsfGY{eApDSSQ-zcM}%GQ zVo~280@CX3z-SyWJFJ8D2LO_ZKpz83pan68*REopY>)+$&sC<Cs2bV*us3A)@{(rh zFZ>V66lbA*B!s&KSW!IP^YS=9(g${pDt`!4SjzsJun$6YuQGtu_l7JNm6p?;HXjsW z!`xr)1O6Z*k^i_&$eX$K`-_IJiF(;S=-d~fHy-?;1#+|hTpi1?Zj*&x7@7Q|#Vv>r zu$Y`(=}h*{BO>dS5BBsWKNKc;nZxV0C-AoUq}tqlqXsCgJZMs4(1eglx1O=p4@*ne z(#cXehbTbG`PX_<`G>b{$tnE)zvl4bV_SEi0vqzx3PfnOxg$r0G40~APIT&K&Jp?# z!P)N5+gWzlG5ix0{%h4C04M)pT^(hC9!PWR-7Ai>K_+Pui5QZ&qHXRQ8F>Ja`seGS z3sC=Xz-d|zxWJux@7T}-xCl2qfZ)Dl?7F5;9-Hq`VZ=3`(%M9D%vn&0Jd$Er1JEEx zD;Ew2zPc2<R;1%%eMkym#VUV5H>(Lm{xABM3I1?gw#hQM>>%<yT&hb!r1wQo;X7${ zKJCBA-d|s^8zNtiFGIF0{$h{wEd1jJZlaAUpltx_jhp8DGxhQRSlk5OZ)R~}`<**L z%0Inyx+Vazq^;MQq|*>fqTiATtaXD!sp7wWCv<Mx`>_C9vyUVov=ESOp#LZSQ<Ep= z0=GxRD%2I~l(M!<Ro4=wS$cJDkI<(7$0<SojOFKT>)5}2FPa(xrQ5V+R-6gsoU+a7 zWrJR*9qcL@{Kpl4!jSS4LXWrVTm@Z<17^d2Ee7LyU*On4)i;=WY#^;}V|4L%(Ui{Z ztN&#HH~$}NcAt!jMHbEm#-PN@bz>?Dl+*k*X6+VQ;D_k%>n+Onmp40b@%~vD1{dz} zfnSz6D~j{Vg>ST{bg?}sUJXom!Yuy34B}S1G5)E)^~oL}&~}ZetVH#iS><|ggw+q* zWlO|8(ut`fA)lH7{}XD0TwvLNynrsg%6MO9wZ9JtXy=_khqoI6Vy)2J`fme_C-mHa zczX?J4Wyh>f!AD3eM^8$z&T0NmABatAbr=q0hptI{zGsw1>@b=DFCo>z!>1uu5$Q= zbdVd!E#N$XCeFY+0fhar(!Et1Xo3vyyz=o_<IDVVy#dM$d~W=u-O5C5nQ_<3A#f9D z)V$)pQC5)?!9v`LO~8;p#rnfl^>(ah+<bN%%{8KfYqdpsiv}B`ObgZ{e$aTSE>SXn z(2q5idt6}+@wTqPkfnQ}7k^nPd3%Vxa92?wDHrX3N-&$7TrO8<MockLG{)j^s=Hy_ znbLH~%QBW8sBw7GSh@77vhvcUUH9VhQZ{JVni78x5^a`)RO!7hTZbSgu^vM(Gr7#C z79rr{C#IYY?WugOJ0?RGYJu`uQi)T2Zm-LDhF{U{taLj5A-FMsSU8}-#tG3ctW+GI zo+fOi8gKb}6u?`B=`gB^kBHMF57D_~udi1tVZo>Fz_Zl6lRPojz6dxmHI6!etCMUG zIR!>=U`UM2VlrkbXc129PqzHoqj?Ly@YOd9oAU=K*gACpchO)^SD>aCYJADDiRZ*> z7ZtEDwqdwFEcEQZYD+Jyw)Dfx8h@s9bPgK*7%n*6<79y_Apa%*5eExHGLgP95cVt^ zk$TF_j^I`rgq~?_>m};dZFqWTco=&i#|k#?KOSu6qLmx0Jx!^3UD%$?BSY)#rCwmS zRy_XMr6107q>-vuLVtUOKQpZys)ANd!-yhIThPDFG4`op_ElT-GQJxXL3N+@klCEE zWBU&?H2X}#SS7DTrQY{)jh<>#a?OXzPvL}$Msk;2g6{n+NFB09<BIz)wd*qn6OB#p z-r0z|@BeYYFQN6D9Fk2%)(t<YCk7@%G+Q$;GcCB%&3Yn7dGHJDHy4%MYMnS^L)564 zYj4Fiy7~PYu0ZNzo4x^>Yo*n(Tlfhpg3g~%4jW`{fP6_&@2rGh6BSj5b9KtHzI*lg z%V+e|8bWilkxBlE9bCau43&&IVwtgT5}`Gk^<VOm)QbD{yv_^)@DmfKP3gxDgBYpG z8@+1{2y1E;@zRMNy{NU%n=(Oza3xuwc=59{zl_1}H$OkS@*K*%-3USRPRmJp`&Me& zmu-7nn{Lzb(N0g-ZJm9TedOEut}WarfCKFGOpPIZY7cO>+vz06v*X^P$$P5mAd{%7 z7~c^1e2<%5YxoLHA8B)nzXnHPF3V74ezYIUvK0LATP$0K!Ujwjb{pSsMNmD3vt1pF z&d>@gf>f&doMCQ<A<G`~0#zbyWDb@*6Wbg27IvecUCvDLG_{;F^tbGO0$GAR76DGa ztoywgk2@-gJ(Buahm06E(#eY5zJ2TxlcbXT!P{FJ$^Y^E4lTiQ9oKFP+{`qb_R?w8 zCpl@Oj1UyS!JsVR6=OLW?K0t}lD!1>AM@rtMh9fW`lVWr$|R-6h|(3>?@jeya_i<R zhdt+zws~}%mnPDy`x)pns+AQmQKUOnv=3vJqr{jSp-ED+g|Q)YwPU3wRuKK(PVx@w zg^r?p^{6yrZ_3Fkftw-+#xZpj{l5ljAa<$G%&dg3@}NQ(MN8}OY8*9;d`E_(USylG z;k0OdS!;;I3A%IVMbt9=N7ckMrKe+qQMHU1W_tWxQsCA#2YxzLFEme$sB9?HE_3CU z(~@V#zM0kixxZ#&0}+;M4V7f|z8*&1rc*P=?s;JD=e^6A)(;ELp%luUz~92Dw9kqK z7`Zl=Z!~4I*F3SE!?)`Ub&kGdrgo>TeaZ&Tz|2_2b-h-Cxe=ARP_3now<Vh!#{rO> zFFBvXp?p6+857TmAq<ye$hu><VmxHYTbFZyZjk1PG~i-T)`v40ngy*%yU0B&)uIfw ze+t+<<l95L=y5{Yb4?Z<n0%-P<{(!7{(RnCbcJaDo6(Tstpo~2VG%Pm_e@%SP;+cD zye)1!wAi|6=f^{=COWA{#;US|6RXBfCz<i=!f*ltGiaZh*!WiO6t;)DZtI0~1_v<d z$?)sZeY!3QC448hb3Z1n&X+ao{y?^;wpoVPz*2HXYYg0<xapR^FK+1A9rgSuglA(K z{Y&Oo8-IJm4EMykW>=v72;;{R6?#C(!c!{#sKJ)|NIQEcby|)beR+DlZOVt75X#$t zt{kI(Y7awlA2eV*IZ|RI>V|GA{~y-AI;`n-k9&ZCqJT(AP60tdKssfh(h@2qsiJgu z4@C@8L_k3q3P=wrX(kOK9g}Y9t^wPg_vSfAnCG15y{`AV-v9V*?047q{>JB9-ZO8k zcQk}Knsib!88o`8T`xp8SArw}XAIMXAk*i{F$9a33tx_0+sO=BTIh4-7k)5rd#dU6 z<f8ndQVlt!epV$FI$5j6hc~{f-@~`aQLn;lM#BcazFTdqmZPfd^5eIZLT|k&%#pT5 zP&d7tKEYk)HDa}s;_!?+PRjQA{dE=F(lv>?mxbkTw_p_b9+7!Qp_kmYd<d$a^9=fG z%^WY<e}4LUv3j+ZHi^Zl)_QW!oZd(x`DFwTxdh!L8}|ogcJI3z#a2iYmK}2eol<Ya z<y0I?UCf$}$V~>p=dQ+R7B%FF2fVVnK3n(txOM5~9t>Zmx__~aDqLFifhoIC$Vb!n zxc8M6Ss2%9kiL_e)<1_okD(d!hu*DPlb+SiX{-(P&Z*1U|D0fRF6!x>e8-pAq&4qn zOsTQlPkr?s?~7oMuQtT^ewx)cqgu3cm*gi){`AwTEX?PQ2F10TbNB2GhaXvw)4uFy zpVq9S^>$VYos^^LDs&937lVaVF|55RE$QQ^$X`=_o<m_YP@ztDV){C>O6Lu6brD+r zAD@&T-PXBinxKr!4-j8anj9akSs_*&&+@;fT!g3xWu%=Sxn_7f&FeK^p6~kE>}nhH zkb~v1LnMXNajv1pUj-CJc{<+bU%a1TQjZtOA|;F7F&2nV44J!d$;{VykbL~Bgv9C& zrO|WO_Y9Qdsk#=rHowH2V`$5~Y~Ezu$~vi-dMEw^sb;3Lt4=0YseJ&b=#np&w|@on zG-qsF35L=}L{6CSN*0k~Jniqh+%bM4bu-Sj)zKqLm9kL$!P3qrJ8rhT3Wv8|xmBWm zFwDzw4MC&TnVM0CX8yhe+7U%hWPfF9_^gv<v9EvL)#mV5jio7JWNqf8ceO&XvK=4| z#)NZ%*jA1oQ=Ty|9)BTb_$z8WA)M@|k?phjn)xnY-C;|+%$GCt!!tvTe4sdCDT`3w z+=%2_S`C~^^%M4ZWp4nhajnl@;>S;vPAvij+oeJ0PS?7M3=UpS3~10%iCd!H$UJW~ z^zmhjiCRhKe9FYc#L#=r@5#l2mw8Q_#n$GMwbc|mT7`!;NVP~_Ha=RB{pK6WcKhr+ z=H-1`#oNiGA*L-1LxM^=&Qw<nd?a6Vf3We34!g?jYsR9U+K&lsfKfjL#?1E9y9FwR z-j|mIICM>N?Oq!Xy-r}3jTU+I@*Hn|dZfxK`mvwFB$V3JYe7gL5;-_;cy$xLkiB*B z<^JU_zYI16<8^f$ngt-FU#Q<=WVT<g#znxbu9}T`KEpFENOSEeh3&)@8^(ns^>9Sn zeaQ|mY<%R<Tq!^@{jP*UyrKH>A{PE}2$S$Fe)QSm=KjgjB1(>51AH1fw6-FuwC7X< z^|*yKS*Br^WZ7e|sdX_nQ>GXEJ%pSzQ+Nl*%08qDhQ>FKs1^qx`#SK_lND)lt2+%8 z1{G~IwQ3dV6R4kgG}>-?mo&AgO+%;CPBh%ncJhk~HIC5PeIy8KMT44=Bw9gw92(ar z$jUu4f_;T7kzNzOSfo}OhORm2j)inKu>ElP-ah^8;%nhx$5*oM)}KK6lQXn+qeYE% zpt7x3#(3{c*(xGf)EDPl=VN!;bg)4dA#L?5#J+X9G~%Z+&Fd@2t!fk)B_=UkT~+4| zY(X<H%fhwr$fqe0%d=Jz*FXxVQQ-Oa54AXoN{yaHTymfhc2HHBd=+HCE{IDPMB4Ee zBB;D%w1aMrZnx4J_hk=UT&YPY;a`z`5i1eP9jm?o7rvJH>72_7GzPlmGk!Bad#<-I z)l0PvWcf-xYGoLlj?X%I>GLG_hxfYT$*qDbBeY}K?q`xvTIJ^(r*7~_!i)OSZqxkW zJp27qXl>6nAH|o9TRF_VU$%H3_~-Dx4{=r>*kRUMV#x_;g|Te;3$Ij5r=o)|yzZK; z*YM0Xl#ll-_B{Q<;iIm1@$(SVhz`W=Jg33CPq~v>IOs(2lF}%h?4324I_B7S<Mc-D z$NT5Y*eY&WiMR90&gN;HQMUD9zjRDr;`DIb<MEhcRYw*C2QCHld>f?-Xsx=~BYS7^ zr<)1iov)}e1`)5X>+0pDH2pXDEo~Y4o^glV5a>vzWx3JCz?HWvIO&O{&zG^kZU7}K zY{}YhH56ks3~rt3m|GlqDEt>B<Ge+QJY7Qu=egiddSS1+$ltCBXhcuH$((eSjnQRx zvJrpNH5CTEY~&IrsuQ2lZV`WbN)I*f_1!x-K(>9u*z}G%d3dhYe2fskT8>X*L-wUA zA6*+4{a?w9lDhAEY%X@C>BnU3YjrU#Z%v_>Wz}6LG568Pr3c;ZFQ~$8ohg5Owy>rE zoCBBaT9!$tt{t1~bde1GvPuo4*V3IFgI7mSz+Q-hkk0zi(-jJ3EKw<STwf!+ewCb2 zW!+u>Sl|t@N_tAF@<Z{yu8eYZz!lsVlocwXZ1ed9d0lxw|Hz5%MZFtFb)70o=Fu&+ z#uv?AF~uvLY;b<RQM4OjIbr0M+0`=p7vv1DfIHh%OkB;UuF>rGZ?aRy5}*H=^5Y(V zGkHa7;u&uuZ@BdBAkFyC$;_VGd*vUY9&Y2wp~(`Y`aiE_&rA7eHNpqlC!a6TrmH)z zk=H9;o<8@1Q{xV4E{oQWQf{qx*QtdPtj9gVh~fbBc5}1_u?;)8X)1*j6In$EI2yO( zxEAPk1)|4N3_-E3x8_0yi#mJ{xM#RWaz;~7)clcME|><%n}#9zQ*$$h32<L~l(?5J z-L2c+Y3Tvoh;;)u*gj9diN7E{w(8k?9k?{u)R$TKwkDSLFGzY{+}*8bEVu#o(Dkdb z3wUKo#NI9pcPW_emQmvUZ>{(u)QISS+vtK3Zc-zOxZIu*ufQ<6RSl1E78|retsg%y zeNST3iF-l4M%GBe4DTF41`veiqO}8tQJ_zdC-v1@to;kZ6*ozadjV|Qy;rj_6TM5Y z0&47QvoPp32Y@Z-uYb}z8#$h9@E2rGWpf>|lL1GUq4sPn`4#E(X5QYzEZ}sD_uFxN zACRGqX7f3y5%`?(5`;c?47Ga_hI4}b&{MR<2;#2+YucE4gN~@DQ<0A7dfn(cF@S&E z;hX1;-96;E0ir_RxDSB0j}(*Xkc`dTT?$aQvIahTEs5|UP$nK2;}m1i6-18b*54`N z5H;|Lj6Ww{L40&;8PTL0pOXS_;vU3TcJERY$dkIT^MRLdj@~#(d3WDx^2)_u@Af~~ z0Xm`&igeoKx5f~=q^h7nA36BU@MrelN$|W{dl=XrMPEIH{_$jPsqGdV7hAk=lo$?i z?Exw1c3yuZe@`Er-}$?+g&`2?uWka8))5ntyO5!S(XJbIWd8-B10_=@XAyhM9pq3j zHfcB%f2|L-wT{?3jhra)CwvN&?BCQdygOpBxqJ6+v);)b+MD=qeW+O$3EY}VcpBD6 z5o{=WSLY2;J^Y@n*(PNI9)pZj@3Fh=hOt`_n2a#!AP*lT)%uvjJAqXI^Gb-^o0DhL z+WrM7Sm7*ur3_Xq3cAz*0`N!EgS9Md>l-3JIg0*d_6mV;g*|-eo(cQOjK+~z`~|7v z`?&fX`&b{8`rOD-gG`{lh~@5)wSq2&dhO4KMUA{UdJT*UN-pNVKO@vv%tx3APKj7* zh2o!F0qD0I+yS8Fo1pOTK9V;CGK*Df$x)#5Q9t=CyxEyi@|YfMo2&?Q-RnoKgme)E z?#Z+2AAM0dzAy8EM|<BijYNT=MxyD8u&=(>pE=;||FlN;0c5f{JWa#$k=yGQj{BTS z&F1mA3jlrqAab=~04<gqhX6Qd|H5_wdMk%_p_bjxhx|oKmq2dLba#-_y~3zZ)}J?C zH4C4k;kx8_Oy%qqB9wri4A|T(_zs|5WLv4wTWQI8)3(opbET_^=e;~@tGFMk^S05w zp?foVQ8bN-t9N4P;a7XnZmqA4{bs9oaxr|GrJzcL59|s2VI$hDopRP?_=CPquiH=A zN*7m-Y++?bUKuWxs5oW+*AfE;qPO1cR*a4}V(HZ<H6N#|L+ju{dwK<*aly$2Prl=q zJAN7;@4x?n!CK(l#W3A??x$H#2PhuK?`|iTgUYR{@P%kNr`h$_GyS8~W0S$(9#~R1 z_bSKF$!wVLeDXx!C@OyF`<}Aa+wr-#I4ytkov<sp@d?qtUMEB&t`1;!r=}TRPkT5` z=NAtRcw!k?#u&p22PsJ=92dJErCvoo1$bmVvr@7^vTwSL5Z~_Y-7^}tbeAsDa8;CC zd-Pgz_4ct@n583z7q+N8hNADc*=rBl;%8sbDt&Fyx13||7`yi9dw#RIyQ9A&-;LCG z;TyKGY;4D#uWyHJTRFGWbf(OG&lNQ+ik}-)x1KKOT2ORUJ1aH5K94!YZ}Y}lH<ejH z^w-!&O#uPk`0&bv9ec0-N|v3EYTCH^avZYi_(5RTOx@^HL?NR31vqGW|9BaH*aUTm z+rEi~2!9*TiL|@JhK5E1Ex%q&6_*G1as<CU-V-RT_4Cd*yhyj)g@pjVpj)ebIpeNr zt+otV<CV7u)>(W@DN_dwQ#wsFyUrEIOPu<F6@IdN7WSlf8$@7|Y~ujpd_R|I;pHTp z%y@o;Y0czA{`_le1r1zEUyV6QUB0w32d!wxY`xYGB+JyL3l>=a4-ZO==-=E<rBdru z&EoII#J>NoYQm@9yusa#g-1%VT=`ycvCYMSJ}gsKm)Cjwj866tud9@j&3nG@&S49n zKVIR~&=A+WV!Ge}l+AV>bEjImG31^>%Uqdmeb<S|rkl<M;X@IUGf`Xg8%mY?xBaMB zi)&iBcWOsYmqeR{sMu}k*lX4en5u3&mrV@~_iJ*zX(F=qYK+aO?1^Q8R-+sRG5q?^ zwj3#j{4V3dmX|-5R5-JzP1;{qJ3%o>rzA9>;3QFyXAwSP)qPLtC(`6X<fLu;;N*5z z&!(!ML?%}4*{|;tRw;>~CfvPzxo?w}?_Zs`bykK<*9kg(`GhWKXidci-}vRLs*~wz zcd{hS#%=o>-6nc>k;5pyenbq8)sO3kumD?@*$YsJYH!*`Ek#Hu^o>*DRGI+r@uyMb z$Mk+M^bFbg6#q1Cmi#$rVkm=|wwE<KQ;4EpVCM~~YfRQ~oE$W2G9{vD%1a10(#?<M zR!xav7P6a_E#P3%%^HSTv_F+&#@royobLBv4O*Kp%q%JJsHCexIioQX6Ri?5LjP=F z1XfVgqfc`@r{_Y2VCjv}LI*NtY$f1fPh#=ys|MEburQc;%R-Lf_lCYkU9>&c>(j}c zV81#1x68W5c~tX}LgyCAt`{=z2nL$18VL4BDy+t|Ka;gi_li^PbQ@G180msjSPvv7 z!{HZWCd$Ge1uuP9&b#k*>g(f**>}cQJ`8SWR-K#D{erKFalcr!a;ZAUZaHJ4)P)Zu z34&UQk$fSRn}0!QZ@1)Oyr<SbhU6&azyCa~m;8B#dzW73!PU>u5z{W0<lDib!;-#C z)f$b9IqEtX-8Ijpc(;Jloql}dOw4C{?s{qVX&7Qe^=VppOMmE12v;kSziZQzXM1Wr zS;@1_-20$Mj(!9y+%3j-U$oHoq(|k~ZZTDkkWQXpXM9OC^Ch#*;0<$LVG`H%(J=Vf z7gzy2TvV^4Xf&+sYX()(#}@YTbemW-&4{UY)SC#V$)KAC*)`#bk3M9z*r_qxosJoq z-UVD1bE$pNY-|BWIcG*3z~=Sqe3C)A+5B@|T0@(i^=px(cFQUeXU~@kNAf3|3;R!i zZUb+t&W)?lr-cR^bVr+&>r}>e>T9Md!mNFBQt1ZmtCdxtv~{wybq1H+?YPy$>+Y`_ z+*R{p*2z>XK8wAbYcgT0_W694)_`ufbp9Kg%g{X27HU}5*qYYTrAZB_$y$3TXVvrS zJ%+5$Ln8}#o+nMmpE5cZ6$-TzKb7E@$(jkWDS5=t6}3FOgl7q8gHiE+TurMP<hQ8R z=&HCEdrj*MW=6ZqZc^{%=h&`E)$V1k#Gi!=S0qk27ZBxh`u{-0%YjutN%G3758&^r zFiXZ#t@a_f-#Hb#-mM(|5xcXaAzjpRGkq;4WP<)mGadK2AWEXgkJ~@^J;0R&$oW}3 zH|;DkdC;idu{D=-GoC8uA+wC6{kwsaUIGF)i$l-EL9#R(6iyLen>g;_^)B+|yPM8* znfFU$;wmyO-MNkNAF-74KjX91n*VwyGP6}upE}{!+f$~O_P=Zk(x`=IJWIWMCr#~i zkao_kme=fkvdwqi*hs&R;m*{obnKBt+2sbs!iu1eu~aDbT>BMSg$ce^vYF~Ky&_Or zYe1be`;}pKl<|))<5Ho424=5VZ_5(pSZj-jd!zd34Usj+dO4o8$QS%Y2u8065Smb- zAwJM4u*KJys9Rk8l7DIZ)KnC!c0HX+X$_ZECUH8++y_tm$%K7B(6*s|rbZnoTUIn9 zqlV3nu!zfU9z}gI?APiVR-3-AmRx&qMwz$_$)xh;gzajCOs-j|tD#rft?64&f)mQ~ z9rP=aTW^Z()7Kl8(Xhk{-&N=ftYWKhww}5kh3F-JLr?=QHdstA)!;joLyoGVT9JB# zyX8g2J5L4at@bRJ9s#3Ver+cZn1IwTs#sS&pZUqUR|+;r$Hpg~Uo$p0v~~Yl@tS6; ze<;Y}`i&>T#aE0MiEb+KX!owi0XMb{VgP!pGh5X01lF{VpP@m$PsB=sxNSngBP2Sz z+vw?QH}_NGDnBy0;;h&oCRBJ7S5V@=&ft3SMRVx3g7>;&6quK)7wByZE9<Rh3%izw zk^6`q$x~&Cw3m~gX4yo<hyJp?tHJd_*>}HfaJVpsZZT>JQHWmbUZb60T;g0KZyY(j zCQ&=s%459Nkdtoh319tMAp=F&i%sP#?VDnSr<pX*5{o<`nka!|%n@OuoAel8P_#S< zL_d7V9^k7D=G`3olv3CYJV?#ZyCDtJk`*@>+QL@Er<QJumwR^aC@UldGy~!5W;^Mf z>Ggbkh{pSoCkjMVn)9&2o30N4AS$r}{Q5fTAfUpO<se*PgPIB6#DX6bTo?PUdlW-) z<<Ce59}wx_vxdM?f#3l6>YA71Uy$g9g0<Ym{YihLZQa%4XMh>fVTjdJ*V<pClH(b2 zpVw)!w_hi^eaDZ}lii3x@j(*>0|nQ$(M$T-fP%OSR(J5<Ekog(!{hS}+0Lx1JFz&# zI%<VImJE4o%UCzP2M;1a;-Wy}3Q#BJI;pWj?G2856xf4EglZ6mVsHz@61c7<;GdwV z;j61&wjdyaK0(pG<s}}_NgxWZvf+;ehNPSge5?sXA|&^staAI!Cy*Iy*HuBs6i4F5 zW9%fWVZsThkVNR?Acb+9^d+i(!I%(-@Q@M~6OS?mJ<!Z%wcS(%=%1qpfiHrT;645_ z+gX1>q9(fW&Bej6Etc-AZwsuV&QSg56<<w2!%y~DSN)54be(Cq`aZCITEN)g1!>Ba z@Y<_h?fB>LXDEzUg#<Xl&HwsjYphUjs08uL40943O{B!Y)ab^qH2f)GSMXlFt@U$d zlCNBPew12;>lJ+5>F*`ejs7>Ol)!rh_dk93r$~};!T<URGE@uqUe^7QIc4f-SQQIb zo)W_i$1qct@2{kw>!*<dB_9s^sjwc-FX)fy)#8~J8sM8USTS%w_2VeKR`P#+l1uvO zA45YbkpayJ1~GrdmBL})@u80V^t-f^<j=l1U4j2PuLC^c5dk9b4*l^JJUcZde7&X= zMFDT365L4uFqv5D|I1ou#%F4;8Uavc<>fl4Bm;kP&)=*@ug~Yv=Y%y{r5*<d3;a-* z#lR~=la}*!PB*8PzR|poGPO2t4+n?BNsV&?c1-xCJ2^6!R1N1A_hfd&Qo~!WEZ<I5 z@@o?gsZ=Q}{WR&zYqMRsqcr*t_L3XBRHs)0p66Cgnd-hmSl%newxLNTZ1}@NgENO9 z{W0XwJT+uzD=O(+iC@rpnG{y1Bby9)9|5~=!cP!#Lgcvbstm$K!eBeY(7|{Z?$~`` zWiEt#3Y2cOz_;J-zL5W=RMp}YWmNLR_ov~nkiPpQhT#A0MtAB}$0K*C260Bfj1~LY zK~9f*oCEI=cif*y&FkD!xBcnhaQUIiWX#>+xM0Xsv`Mf+2E0jp5??tAejrK&{fEUu zJWxmTh_xrbds(IX(E@HD&1BENdNYYi@Mr?iBeS^ZQ=rJAn1*y$1B+3@&n}e--6*Cn zI**&g1doQ9+REKMISfYwOIt)Youmjq1T2DCa6~%>(#r_njQQ85bKC8r0*nu%!h(V! z_)qzKf8;z$<t|d%;vW~lN9hhX9@!THsb8JywCdxx&urqKvR3C+b5a{Sg};Z_g&%D# zD42=A<_t#zsHG!5?~k$X25^%b8Nl-4U9z7>EMxvY*~n?*EjM;jz|nFs<oH&3CbPqp zUOYTqlN>stRxg(UfA-zwB9$<jLdEOfubh0y8t{BQC->0Sch_nFSQJ1}%y6Vxu}M_u zqe<!Z<z{bP6)<9xo92GEy%^5IHU1cuB=%j8FyHa`5yWuo@PNw=FOt0K-VE35!=KDb zU^*lDOFydLOZV6rt#K2cqYV!LtnXZT?%sCv0g2Rhkb7H$;EgEI>;$iS;kvCTN8go4 z+BeKOJ&R!NL3m#t+~!51t;2$O<xn~5-9^Ms2lBefGt1s(HVz9i&Ev*F@^n^dxWq}k z7Yw&<wSTn{y9(b2d4PAusdtHUK_tkGVNBe(o`IXY>f1{rLqgRHhH`$;jegk5M|o<b zV<U8JhaBe$Yb!f^J-orDd#I)(!--RhuT3iH6z?SvNexaaks9DC@pA3XAifHU-xVb) z8iQjn;0tH?J7h%ZC~200?5}&;bY}${ymNr)_}6Tc$O*F-J2ybYZz7Pg{uHfi=9dSg zRNe}0=m$$(oh5nm39;=PxeLDEX-;0;fo@cTtjTD3h6))19HV53n902FoHxfKZEWmW zk{}aL1UYtFYkyXoWL^e^*^I-NO00`k{d<8o%i?KmFP_QZ=KeOkXhjnIzehNQ+#bbW zo%{>p1m_(O_`N)_A*0sgkBMRe#_)nRkk}B*e-CtP2F&YfG=7hcs9^y}G-i-3j%>)( z9d==Q*t^Uw`R>hkr)yKpS%+&$BGWe-7u+RQ#_z+Wr;py>>vcDljafA2$%ocjR`x=o zG)0l$r+&0akQqO)-Ovs=8ai)#rdZY@=js$cMI7<vGZi~x;RIvo?L0>H0er6v)t7g8 zL}I05MOW0FELeoI!m*Y)5I4~~vKZJ*K790A<nQA-HF~7M=<81O-7O4%^~Lp9M$P-g ztsnls>53?3;S3PE*#`<l{=11$oP?K8Mb_adnP#oF*PBtuDy(*^VD#7Yjn@R8xKY#2 z`&1#)t>jpP?ijTf8yVEBsTG(S?y{S0`v`v#-c9r+=3K9ira)^7&n8y-i0vgN8c$x- zPj*X{<U)4o-+5YWe<8(m$zwRhywe0Y)TkFhz?vdxXoqK!p~jos!UgSf!#f=?kAZg8 z2AEi!j{gG$(9Z%}utEDg^w^%iAglI*_?wnX`hP(<>(g-2juh~Di8TGk=%Rp*5y@3} zq@S%o&X{f1oLh_IDQjlkl!2TSj~!b7P_?i5*31{DWA6BV`$4Dj^ORJpS7ZM&Y$gbx zh1`j3k{wU{<EAtnC3Rc#XoJdJ6Etk%U3@;ixr6^rJ)*yN&ept5=HD8{t$I<83uKS> zlQF@9hg7@p5)GRYaR(t?gS%+U-?T;FxS;)Guc#&Eroy`y=e=Y*NdNH?_G0ef<(=Ub zqkA+tysfLXm!&VO@{!to)s3JY5rhAxD59+&2P_w$ooH&@TeR}wKy8>-Ltjihy}&Wa z3rfE6kh=eUM_3X`_jh17@I@Wyt7A#`Y!R|{O*b7UuiE+^jSxKv+a-zITShhYA^yES zJ+sh$i>_<es@vbEQMmXpL#EUJ2d^S+C+JmHN=;dR*{6q^%P#Ze!!O^UmyiWVLlD*q z=t=zdEx%<WTsPoflbxyh_#06f_H&@5&p&W1$oG}*W$IKX_z^o>e(mKEIVz~NLILro zYybD9Nd7${Nho1efUNjB5xFdvIoi{f500Bsiy0l#zx*j=ZO!O9Q4k&osgKN4Rln&# ztk283i~r2=X{T(7M+RfKNqOe~aR;d!L2BGOZ79C75&yI|+{jc|4{__|$J=A_M7$zx zzp^6>hT!ewKoQY^2$xZVQ0f*mmgFypMYiDK7Y>+<XXUzQ!r%3So4%qA`kMVOZql-r zi+w_iuVMrO$Ywe#eeE%=wc4v!GwpYRrzR<l(T6l1$YjV)f8d{h0&S>+Ipa4u+km^q z@tWU(=|XsnykEg7qV;&lLi%U#Rd_o{TBr(U|1DZ*Y*6bb%RnHlHEfgC_^QX=`#iY> zmzNx`?S~-LcM8#rN4$%){2%*-xe>$jasY#ky;hP*5Hl(4ufZhuIpiWq^xAXmvxI{d zVSQ<#K))0o-D<TJ2&9<vqf#kAkmC)3=Fsbw2(~U#3bd(7$LkQ4M$cO{Z;2lC43pv- zFq#6Jsf52)S~e#O80}FcWgtcGswZ<hbfX!S`baM~2sI`27sM`MPn%r-_Y3H-@~WK< zF7Ro@7JWV1dIHE>z<|-PdA`sj;?z7a=Fh)V_N7AzA0W%?|DHVvnis1!hBwwBRuD5L zOHTUGwKbmoncWVOgP72zLSdyyd%$omD;k1-ymK9##?@k+GrdFLDa0LP#KCgK|AH(F zt|RkH1;K$f*@G3v16v331C%x<`Mj#Y(O?JNwa1a#KirG2TUEw-wE{MSO3EpNfDOFw zH5Kh>AC0xg20QdIM!+XW265Z?Yk^V+VWnafOhD+m0#A<7ZpeJTzlKZIDKI`b2_!$Z z-dzU*-k3TetohtE8cVVpQm#{>2vi#x#11*|q&3_Eo-}b_S)6Bq?=2&K=(|VH+Xi>T zr#OM#Ytp?NvYZZ<E(%@&Djt(LZsp+DK6ir<c*D^ZW_t+z;4JV`KQsb^Uj_xDX-vL? zm7WWA+#5rE599|w0&@r6u?rI`yHu)wS8nDg;8Q0o9}T+2!JeF8wkv_HA2_@?N<-!j z9AM}A;R|2^9l)hD_3yWkQAfNKG6IAPzE+#D{d81BTAtJvb2%zYjvD*rzdeP&e@+Ue zrNsq1x3A{npYnwx8~<<~Lg?jUz!s=G?qRfW$94XA(k6HPO+;i`8Au}h?j9O$OoH3k zN;-CMb|qaW@XcRm@L;nj@}lQ$zD9xRCphlyXif39LICNPQiIFc<m31WKFd+I_eWJ} zNZY|1(pObE)uPGqrhiwG2Kx^stSl`LM$M*Xdwm<t1Mc2p5z2sFdOsEg#ALq}N#eop z&8xY>^=?9UJz;xi(6_+v<NmBKO?N;6A17YJzc@%O0>5GJUi+FdHqb%tCE$NK5a&(c zg}mDdNR;0ecrXDw{z$O|=>9(nOFMbO*LDOCbktjDXM0OfRi?nOK~-M$qSORpn?-PU zBNUGdfsFGNcEF}60eKq-YaM<(wN;+*LhSCuv++*))l8&3G#KI`s()g8VRRQ8hsQI^ z4f}!u8n1!Cu9asbjIZv+Jh+G~jESGW5Y_T!m}6>dOYGy}TftxiG1fWoFa7ZL_hvhb zdeou)*~|CUm4t|&MllU0`lpj5e=5-`HU-r^rcgVpormK>MnSb{AEUoxzyVtsUiFrU zZYzHJot~_dr!~TV!FN&IY-5HIw@*h@L%>(`H4f*{wszx|p*6RWL7&71okN(t<V;Bt zr48THefJeCULBMVp@ceA0%WHdzA~Ofg#v|8NDnS1yhoqWkeR-|Zm;lkyG)q~_WPoW zEPHP+?pX`o55$zC9t29N#Wvz$z@kNFVHdvcQ^sL;>p_K)df{Jfo&2e8MPW27r>~s~ z3W4M)Iw20nNM1stHg*MZSW%*3G^sOCN6)~k;2&gue=OEt{m7z&Q!M4i8zyd{IeFHr z^utGkM*iMH?PJnV?BgZW!iy~TMq7P}EAwcY>rS&-mnbr)AaXJKzh8GS%7ud%cuLek zQE{Dsqk}Y&cy>QzK}8k$;4W*yqZH%Bs=xCu%8yn8y`K+uMiRC1GwBrK7`!oTbZc;r zVi4(Azu4#bDmD4+oBG$BG73_1F;Pb+w!Cn%5!5ZU2MYRm1K8oZa}eaw-dq!_yB~Eu zUdq|IZzY{#=KJ4cQQ1}_))`@2^{BVV%zRm0I*)k$1Y7315u5PN@HEyveF=im=Hp(V zrpR6KWB3Q9&_fF9Z6%(VnACs5G~=mcUdr~8Jm_Z!nfw3VNpgC?E}N7_@#Se7^uxMF zgX$`apWTYW@7{lKT>iMESfhX04jz61ocXgrnX-SN95Ri6g={Q8$S)Ae5RW>e^KkdU zheIj^H-Vr~zYgkfW0C3xWu?z`OF~$l>)w6KoAnCP3h~hSr<>;oZo>Iy*pL?Pn4Z0R zBJ(qr5A0G0=NH>jHkGL5s*kUI1Z+iT_-LLy>xDl{`xnU_erF6y2MjN+e2VD&p?1I7 zpshnwOIDj){U6A*d@^@SZ*&E=iS#JOvT7_CpRE10bh5a0HxJ!ceDqQ<AVCNSeV6~? zO)2oxXZ46Ti0wRf)8bZ{P~jwb#6=R*kZ}U0qCA)jpIJBC$5@eMuSsA7k+5Mi+;M$2 zLsRyW#7To^EH4vpJn-bqJBLlnL#7d2dYwIeY%pksFn&;KKkcU-YNkzaf18(YU)^Al z=e3MgZ!9AyBY)Z>(Tcd2zUJs8BM(WXgWU6PVUa;F9h1!dyY$Bf6ua@>fMZ%AR}M!! zT2&xt7i@|a@KMt_Z17#Ah+bJ)s7^@;-#dCei-Suj(v^iHB%D9wO4=a>&-+OolaLk_ zF|Ns%8jf>6hIqRpO4QV8GWvTh7mw~E!~%q(DBOmlfzjNd_m%J6nrmg^M^=xB2X`PB z%w-g05)%3N2yQ+>UxV5serJ!7!AUH^>~PD&34WsqP~Xp1B#2MtsNbyR))Cdt$O2hT z5bI)&$rml?W-z)zBlMma+{LpFl1Nv=0pTIADH7*REgYroo1+m;SBEx+7OvDfi!_C? zxX7HL{_e{R^s4_k<fJHk_ap!T(ceK>P<cp3hT%Ycnz1^4p-l@(%p>{ZGFoDdg!}5N zh1m?nm*%c#@X8$ic@aWT(rQ4T5onXAhTv#5NZLUx(A_`4oI_ye4MbmJG7_^Ngf9ge z<OSEiyWp0<7T)3Ah@OMrk*xsRcyeMASC6+Slb(?U01lK9x-7UM*4aTs7@J~yJ0A<g z!nr#@LDS#sAm=#<0vZMGiYA*;9MGX`3y>nUsCDLIAbs|j7iS^q%izUbW_wekO+7Je zqgWpxmy8p3nIU7dKzHS<1pgT6^%rCa`n`mA1yJ1N2yBOZJ&F7v$f_Qw1c$ImB^-ZU zAGY<gR}I3Kvl@qe%n7g|)CU*cK8!kE9_T$)pbDSp!ApNt9EhHOBOzb01P_4}BdZd7 zgNPmdy*^4uFBY7A`#$KoK=SE8li_PHTPFi)Pc7JRmzZ8m3toP7yB{8fyd6kUIgZ+; z0{p209+fHPTMJ)j1=9wz=9FiP0YPe~=b>xkAXE(0r9+=I>H7%G13+77U`%vqI2A$; zwA|6__zd_k-Mk%aJ`UHZnM6zg^?UTzEg;sJfDMFP!p;)sfH$&v2E(Sv8TWx6{*k#W zdz27^mnU_VlK?t)7;LK+n08{_e-;BgTL?5NM-1c25RP^aecgEHcS@xwL{BRWC|Xpo z1uzt+VegR{-a*cHaE`#!18?#eogdvhfov#QA$SO+2m+BYuk0Ifz9{??8y~_aE0Skm z`yfc1+}NHz(Z9fE(t{0s@rOw)O^~M81JS=f?zjs9cOBTM9pTPfKfR3b@>k&BKnr$x zW;(C}SN4N7zBk)ihHY|Z+w}iO<vSvR-r4#vf`<cx7SOYDIDG0fXo!N^JE_laqDA;5 zPip0*kH6mG4+W80HtjjoAR@HMhdLQhFQq&ih*FfN-!j`J1$cKM0&E0(c{pKmU((5q zg@FnY*;{6kx)10el8|orI0uMoI|pV9sx{_#0@8E&Tc>kpg8(q<=|Lfzq#*otEMHQ$ zTcwQlmyqr4POjJ+!<=7T8cKPOj8$?h=bj*r#2g22h{Pywn(dJ_?t!8Q#-9SE!aepD zlu_b_4;#)tdBUmr?y65O45Lz%yLTKm1*=J0J8XYVI(qbRQHAtN<Y2Qn@`*?Ib~5aK z#Cv@y!tU6hk3<dZ6WD%n82azNDsaUE{{%c2)BF7*$;mpEcsd&Ol#7p3Tv*eb$SZ;I zQ=<s{6bgWA;^}h%H`xT20Q6M}c6B52#Gm1}#Xq6mrC!Y{qg?7MfN%5Pz9VXM(k|c~ z8#R3>L1%4w7J#-z&Z0IcBe(wUa02aw&$56NeleF2$d8`QR+wh@bX8uV!RME*tfB9N z;%9(UieQK54q^e%86oy&aEi`<jGQ)TTULRlspa3umkEA!&gI0Ep1-;|IFB#jJahr4 zLxUy!<BEw9NBduz;f{MCWhjbr%B&-L{0&?NzDNuv8n*$iCmPFTh{hd*u0zL_kN(t2 zPogT<>?&N?Kbz}#xl8qte3y*nWq%t-f|C?@4kqsFxHrK&3<3P}>EV9&ahLmhCeKrv zf7ZMotV6@Rc`PiksGCr?l|N0m`yl1~=p@uaAak-;S$&oY+OryX-2Btqf0|296vD<2 z_w{-;bZt@s=YfCnb(V0I1%66dN%gd|^ZY-uZv?|$oHEbtE6zI7aOIg`t5F~@^EA8( z9t=JD^Y*7e@xqfWA8auF^8n&qZvlsVb|x|hl(;+GU0ZSjJvR`Tbw^*>RAqerX$@l5 zw;8hNI+3>(+Z39heMP)S%5I<(;)skRkN(WKCC@A#|0~DUlfGgH*~}G!OrcVc<S2s? zY_f~ABlanfBMW74A(P%e_qh`!0pml#t^Wy3&9$sI+T_gmbA7kI^X~_qfZV%HxU0AS zg*J2$UZ^q_N*;}>{E+qKX0BL+T9u{ud7RP4;e<V_AdW{w^q-g5-&MP!ON`-5x8;?Z z5Q>IMG9@iDpA3*$%}@kDHgfE9j7}9l;389qWspY9Cmtw3c;@tZ<FgOY{OmLOVOkuj zMR)g4kwgIVKJz~iivx~xNLT;0UNY(z-#W~L3!V6Xq&`i6g`RCR%gD|>+TbETcYNj` zZU!II_Q%R|y#kgejVf)g>Rp$;CR`2utiZaqCHB$~e-g~M0NgGTY(2z*@Q|$t=W)PK z`1HH8-72MxaB{s5;;)FSlr}Y!>@ouZK)@hV2-RbG#y=QqYzt_xkjqh2QfU#Ps>^ko zoLBRB_5eZ+Odz!w=f{J8dXXfDaM1r+JSicWxbjc1SqYJ7`;pA@<^PSVbda_mZN#5M z$L1dq_1U!ly0`no$jf<rO*2v!oLoI90xlL1MToondAS*i(nsc`-^4PzSBKD@%om## zCW2*%^`OsBpmwP>fIfLl`xyM_cKvzLq|K-ms7fEA4GXV%Gu#eY=@B4mWS{B<p=3uA z;toJuo&YE;Hwf_W96Rkl7HZ)YiRa=w(b?FK?HaLYpJ)(5&)Wukk#*nU56A^B8j!(% z#Krz(Xq4^LCR#Zom7jBX5NGO)IX6!oXPTV1HOJH781awu@Tf_HgA{;Q*@!LBZ|wr| z(|_FauX$<x)`oV)d+wn9g0F{4rIG>39<5;!VN5w>21dx-|9D7MgjgHc8m3NfipNQW zt+nu`ypXTGB+0ps3_Y5HabhG8NVaBsy8t}Xca~=bI;MXM&`w!)d)#}K$4xjU#7bfw z4s$%SQytpS1QY^O!~-B^<1a{#JnILKcyjFH9Mr<AOdyq>&!UC^A_U*c65lXGbqSc= zEcnUsbV;KnIuf|Vdh`JsI}wq$z=&G|B%h3@Wi#&++@Ay+FMr|yhWJ-1ey#<EW>xDN z259zP$@Rr&f<w%>l<oG_X|S1T4b+cKSunmiwf1T4vavftjA5!gKT0I4Cjw<(|B=9- z2RKzgC=LKOK>8VG*hHg(P52965r3C}z1v^~&irQ~)39-&zN-&_-V58?gx8p7`_u!k zD|~AfXjGu)V%I1Lbzi4%MJuHK7~!=H(t~856ZVD+awFk2P$2bP%=UNxg7hU(X%giA z14cAX-3c!R5Dws=I?NFtY{#?iWXy%sXjj9$2A@$v>^qIqu-wv(*=9S9z&wn^+;opL zK&?dLD}l}#gqJUdZME-(Of1;6m{#>UM5|Z+eDHS3KPxDr(pDXR8ppVQfU~vZiy$uU z{E^sz+5<CU7p?Wja-*>PDFeyIb@`6r>PRzA&M0~2!lS+42QveA`{*E&sE~)^c|o1v zR1BNPHP|20N~@PPOum$fhfH5Y77)$>dUW9F#BE2y*_AQzT#sl%S~tJAx3+lGj({eq z@_!8YCywq(up@<TIN|O(kE~1^wFW&dT9$kFoFtQ|EJ7Aw1Uq}{kM#zgBZS;%iqzv) zvtL@L1fJ0y8L|A~`W~*9^&i83sc;20#`fq+@jAUS!HV@ZGpIva>a$M0kiRsItw;nw zxYQmWNZTMFdQdTGPjKe~fP4@*8%Xo2B{sMn=j`~4FEd+1t!A)Re00Fj@JpPN)(BfI z`CpLUyWnEHU0~0Hk3w-ika+@3>I?jc0=M`h%KdYOxnuml)C<)<HD)!x3a5b7e=2Lo zT;DWXRtM%FY_I1(NY7FOaF1{l&Qt3bUs?7$KcUpSH+EiKP8h#E7uVFpL?82e*#~Fd zL9Vapf;gHAA^8)%li2G67FoA#me~obu8UExjlVSGX28{nBRp_GbOZ@TnYn~J@uPf= zAvtxZ`SSp%40-DI)t2bT-;$^j|M{8`B@znj%B(T{ZzyW4N#~<Acqo#ar0q(!UYC8d z=}dQ+o@IUeV>}zicY>~a(K6A<dwhdql;=k>*FE56nx^jt4Hy*w7>NdFniTTKgm3o> zOsy7XJxYaeM)@^tkWIdy1b(IK|GW>LM;T0R%s>p)=vRt4N0FThFl#|e;jjJo-N!Nl z?r911c=Fv4AXNzHM0bmi1%Ap1ZZ&6fBdkW`7oY~7JqpOsr&6t>OAkFd56BRq^fvO4 z9$qeYi`T%{p6aL0bMj(Z*rHGVlkBCW3B@;G>L0^vB-9$3JQehJ$oGDAK1xDPN#`M) z7t(h$ItYgPgZ;R>|D8<*eECls4Yoq@7(g?9C94r(wa%*EGdQqD!$2wN|LbKaCdj)o zu1CMvViW$QAwAf#KIY2m8_h%V7~ER|MoW@~yj~AqXHNk6P{%U}=y5CAJms#}lTI;v zMT1rW&qX_`6So>WC?LPA{x1v&b_|%Ihgn;$WvNqD4Dakjla4tgntKO152->sbRCa& z9^&qPnAZiA$fIe^|9YbwdMrqvX<tqj#W%g*-v&P~&$>n5_s8W+{^MRe`m+aUZO`J^ zYUP(6(Nqp)XQmCR@xmwYq)fuIo?js768iG@HC+QloKc9g*f1+M;ne<lKS5?&fEw~; zW}X!C;FgIc;dLYAhT7y3fHIm4(fBGrve)Q`^lpOo&YQDP?XP!bn@%^g&om7sbHZK# zP4!6HxNRRc6V>rJ{8O9AG-37mw$rNTi_Pm3D`#tVZktJ2o!1{o|3EaEkt>WujTbLn zr>@<<<acR8gWc#Y|1``ZmW(I{Ugj!)7Frlt?awzJkZPad<vhA5QA*52b<<A9vLsh9 z*KLh_Nns2MUFoQB9Ak{uw7~UbofB5Zqx1Ikcmvu7s3V_mr_~6u7@2%C_KuCSwEGgY zu$e?j-EUUs^EpJI>qL9MUZ3^n7n_$WDJ{I(8w}gSi=OqmzpK5n`#|xmj+ugK_3Grd zUl;bocuNj{ku`T|<yRqfN#kSfJXT0rV+@o3c&oyo(HdLK=R|6duL6J9m}FX-L`7AK z0+oD*pj$uwf=F-Qox$*Y^3q#TFSIUVQ<$vN=RaW#%Uk4Y_!|;)f}=&Svm{iYjVt9S z2`Cp--?$%&ZFO^R^Mc~#1YkpEzig9}hzSwCzSKvUTD*K3zASeO=n4l7V5`^w*X~6D zp4@@9G;V)Z0n3EFT)fOMx)Vq9GMNPxm~jrF$@e8exiUoQ<!LpYjj0c#-vfDjfD3O< z5a;4JW%DCe|J7t`QIu=93yo4*ij8=m!1{n3`_Gc|s=F$Z?Wqv&UV4XxYrTs|=C=8o z8}E*jaXk0ryvoavUtutySNMvTRfbNId?b*AARcQhivUUtJjhKXrw96Nlg$jioH;{p z>%dI}d;@56T>w=T*O;vziv(V5_hy2SD@gYNY84N>a&Q1K7{fEN)dmS4Abh^xMi(65 z!)6NxVwGc#Tg9;DgIx&$yK*X*AUH~YQgD|9KKKZ)RH_Ey-FXH;Hz`N_8eS>AcZCwn z$z>Ebi46z75P)-CPlq=?1yz}VB?Q7B_&p7uW4(YnWDLM51+khAqJxF_Q||%h=yoRq z02!HPJBreQ6kAa6qXPXWTa^&6tcELBhX#U}9=uR3GQZ|E*E3O3RxbD)R&*8hxNv4Q z?d7I5(!4Mxw$IiBI3($Ufa9%ri4BzA#@s~?8e5$y{esdHYCPW@{#>`++0@>2dV+eu za(oB$&4fn!kuBXb+o5edCtQz5qv!6@1hnocM+ElDoxzL@Y<H%xKV;;w`$Fs+X#?rO z#rfUJw34<+dXOOg>ZgX&n#8s7FKGjLvL+M5mJRW>3(P&^Q=B%uVZ4I(NPPtZL9pNw zPqis+We1~v?A?{6iVURqq$Ag=+~*QX%dy~<XDdUP(7ISXkMk&ZS3YbP^`nJ&$hhsh z11Ru55LwWDp<Ig|hboFWcB-;2Q52{SdCLvgJ6NMnJx_h#^p6%P|G!Yt()N>Hp1O_< zhSpC;ck&fx0=0<6Uz9xXrA!m+Q%@Ob<Wyu0u)g!;{_b;m*Tx=gQX4{~)MhBw)9KZP zq9|2XhijM0`l8bZ<_g}~Ln$rH&a2ksKeX%$l-&*~c2An$*1v6FVxSgXe_r|N$D!lf z>CA0w4@8QxAJdJ$|M*SrUDELdlvasc%s2f2gp>b8A}auUPlypj>1MV8UH-gp?j8pI z%cclIPk^r)`x6#`>mWNoJXssV0g>`B;(Q}<C$gBo`Z<DMOQIHr;IkSA0IfahBGTKA zK6>aO>No(mqbALEkMZFA1o2OLTlDV`K4}yE5gt^qKu~v0oBaL(>g-PluOcUP0e3M$ z<9t<tHWWWTOX7xUnCMA(lz$C)V=sF*(jivggL~Zm6u#4+?Tf<f#~q~frq7bN;%P$> zyQ`7-eKBb-7fO4w9R8Mu?(k_kVp7+bqmpWYBEZHWF9g2dIoL{+Y1}?P#>)zEdSsnD z{)VlDvOS8|$Kor9=3wo_dM3AKFG#FsW|wnDoDsg-dK(iyVc^H-%oFIx$W&1D)y}vr ze7||Lr#P($;yaDQeU391NcER)JS7zOT1l2SV(XXBOi%!SKzGOB5LOi9*PJ@2hS$r< zXgjakcr*QKR-+iO)Z}2tywq=@4K>7d!yRaP7=)%AnD+G1Q1(q&Xq6O(W*mXBpw#9M zG5lEeT=OkgL;@Lc)U0ciJXF?C1s4aiLOe6P8NZw}_CjEB+@z~D&BVK$JcH!De$2p6 zRQQlc!&(cAw>7JJNgk}P@(CJLgUDT_y-`)TCh#sp{gEq;QncPzkrXNXIo|+TedWI( z$Cg&fq9=xZ%`jOL3s%1(Rb4MzHHq&&W#Er^PxXeV7Gu6mh3TItKi0G8Cv*8qQ~9eA z=>`K|5^yASg8hyY)HUnS21EYg!kbRTL?lY^vFjmQ&`?;>PQ4?&7jn8nY=Q}(KurDo z{7X)9+D<2~w)!|OR<C{CnH-KyUbUR~8L4fZ-M{3J66WxT^|XJZwiU^AJ7A#4K;@l= z`3dT0@yFr|JI_f7#h#qbH8=6Z3db!0O1be7SSjc9O9L9@7~;N-o|Uy7*OwAMIelsS zl=I$$3fl%~QSp*<8m8d(m+m4Hd81l?UU{;&D#uwLW98luRr_hL>es`9Tn1{_sH;)^ zOFpSNK`kG~oP6})fwGq-Rw4{nu;=jf9Rt3xVXZGTRZcD>%5(<^``yPBuNnUOfz_=_ zyldAPoY`(a9dm4>fy{Q!?5Asu2b45`%obHB@nY%8kV#F;1Fo|_)OY0nf_SHs%)r?F zh}Q&bHSSr-i4-NaO(&n>l@5xzTAd9#rZ2%}_O$k=^Z`s+`1PIn+RhkR^jfj}*E`<# z-jy3P@;)60T5cKqgI|U`L$06no+c_~KHmSw5`R@Rk!~17<)^~JAic}vgggF&y|a0W zmyxgOHNW!EyF|^q*CkrIqXu&39bLru&f1&n3(rPz@`($77Aa30vM9~r{ne=XWaVal zafPi)lF)@Z0f~yR@h{YBkS-{rqhrOKJM5%!p%VOE&(z1=08{^J?0oBJL#SJsuMyAz zwH(k_-s+l^B@1+TZ}N!6;xDa{E^67@j<=LdJ-I3Bd?VF>;gkd|*4QKaswRxaHctF& z_bi&-{(W|r$hwN>5bT^4NoM?xdTHXGDpHWBiuYzqVFj1Km9(x;eaLKg$+WL8+M?86 zQ&zYbIh@^J+v_$`?0v&0{^820dYw12ubdQBs#yEN8pyh*Zl^e0mSmc1g}9(rg9hO3 zn~0sJbn39>b8_-|*J!7YmCn%jn$7L_*!>z==18Fhnp&<*32;QdgpI=50>$Cuk|0h7 zaU6t|7bs(S7-1XZP~5gH70CEU*J|6UiCGJnFpoK2Ogb$x0PHnitzCRHewRKO5MdMh zAigA|SpF>NcJzDTv|dn|2^V>cSXZIk_dRW*?MI|Kz-rb((AzIyp<f2tyECx;<Y)ji zViAea6oAjv!1fpW*yxBlYV8uQXni#ndRpT_s;R){+TMo%M%2|bfX@K3_X{yQ3SCJ$ z1v?}i(4O8)>_%T>`@X`!^|dg6IS{#JDg{>P>$o$xO92TwWR{|Eg2BJcCQ&`1)Tl6M zR4aLLEy+8fV`|D{W&t4M)Yc$IstZ2Kk&Y3;Uz@>~6mQV?YLh{+=e7|WI3C>kC1~yH z>~Z%ONM@zLhn%NK5@9(Gy@E6#cW4Gz4bb6-gya0V$VzBv8p`>>w$&%|>DW_Vlnrph zgri*zB8*@m9PuKs^w_)caDaSPDLMcdHolhgL-{+yMUS-)zoHKpC>Hu}Y{2Rd5rMH7 zHMo`8>^6%g`SFnA%842JHhp`5i#2h80~B0OIyHK@nfe(4-=!fPSXWPX77Z@Pdre*R zH9#o0_Z7*}_%U|+Igjt4-9KE@{gDdfgq*Rb*t<2xdh4X&<}oueCA)09slm%p#qBZ? z*{$;I`<XVe(gF!`IT=Hj^|sgEaYvOM2#Wa8z<?|G?z{mT6tx^%f<NyNDk@{Xn3%?i zN=n<;c@G_Fi(-{^b#|&cjduSUry4bGRQQlI{&L2BM5@2@z9#59tQAp3k8#lIkJbS- z>u(#8xRSk-RAuu(wx)QnuE|5Cuo}2`a4WN5pPTXc(y<o~b{|c;jjea&tipU=NfB36 zwcm_xq$+sh7Gu_|^3kL|(yTpxYYKzfxAr@}I*gB+$dS19`uj2`Q-XexNVe42t5Gde zz8sL;>xv<{-g~DGde+a#p0#s!T|^!km|4}jjM*Ydg*chA;-1J!VB)LY`Lw82k2#b_ zFTK8OS37I_4imI5gxMMQ3#k(A%;o2FeTrzIWbr@iZ2DnMWV;GeI<Z1KWHKAT8F%xG z>RUs@fiZh|ujXajUf}YEhl$`j2gq_(Z6}7DN42&&FXRj=NeKIQBevhXQrJnNj>R)$ zsWH)$JY`zXOxdFKte)Vq8Bb1AdEou<y5J49mjZean`%JECMNYQUX&PLK#+TlHkvXa za1IFGnt;qUSgMyp(Y|Q_x^J((xAJRF`th#uzAK^y9kh`kl#X)({xpEckF~O>8_1>W z`*KE2VX^b;Gd@92ymm5C)Uu!hLZtK{Mx@4vw%wVPd-^Glr0zM_MDmf$(X)7d&=o2t z!_XM3QyFiYAgN|_VhNj{uIY2nGdCS(E=Xm7ZwI=4K=Ho3?RKVMk;=xy*I~40KI8#{ z_kIaegY0HC!ifE@ua26?v95(zY<t==H%|lM!TE&JoZzNb)#9=?WvIi=j)}q|16Ydn z68lIQ2gy0O=c)H|5kJr^bVR^Wtq`rW_9!CnzN<_NS-ACj17tVgd*F<$ITO!7j)|XE zkDa}MTPtHtO3~E)iISpMr)z~A9OFLUv`ot}>ie;jt!#hHW&%!K&03uREf>!!3Hlj$ z0?U`swY<1!humyYH|n;g<8vgfqmpRmdC$7hJxE9N8O4Y!B6~e^do{JCW+%9!PU_t5 zi)u3XFy~r^qnxn9<&C*GJbmJT`hu$i{a|>`Sw#nbDh*30y;sPdaBLMzS%kXxcJnDA zfd+QVw?tPx-R9;D^qoMJSk#vge~!r?U+fE-u&<f*UIj$Jh~(K!T9@Pe<&wE}Br@Gu zqJ=(qygSe3-z$gcN<uH&6}?5;CvPN&xWBo4?-cQR)-z7@$;gIRv+-q%!)Z5VYp(e{ zf6Zcz^UB~{9Vz1aHS|+D#$DgyEQLXsD+UBj{K1L?F$2?@o%h~5@3gv0e3g*)YdD!6 z@`Z<KrA@@t4e)9ZXX1FsmHvzEzVb31)w`9c`kNu8mNqUZA97bdEft^^YZT*r)7I%N z0<RG2u(vdFn#a@d_0LFS?z76U(jpQL!akmd0EPalL?>*MMjjMR`e%vuF<*-@Z9As+ zt)a*?5HTe0H}G3BN9>p934Dqk==M+?sqKS52fq29n(U(ZC~9AI2F~JvgN@+$2pvnu z%#Jj5;4JyAoIh8DxScjD4t+ZpNAp6LJf4k8l{3s0zXik@fm}-iHH|2m0mKJD+-rvO z7fGlOr$qPK$_ZmnRdi~JPhL{#EV*Y3&eo#<3$VF!ERi72*;bwj{!b%2Do<o=sgk|j zei7>8_o+HUM}i3leDuFHE<N_he|9F7__4XVX?!11I`-U&REy~sXrTyVn`ZW4Ac>BQ z?a+~w4L|z4XKq5qpN1@&zr0*tTqNVHDACVZc9At$@Z@WLa)bE(N6-o#S?0EqlEh`t z($bhjW&5^87uBt7YK$h(3TD2W?azW`ov24(cL9R#PXWn6&Y^u!ArHD1IW~AoF0rb< zcQF4(4|;=r*f+#CGi+-(X4!}{c!F9a_CH&QX|boIC~RA)5Uvv}Z_wESRc#6^A|Jl% zS1I~4uFh<auB|-B3Q-5koyRz8uF;9Fz38$H-tCwFHgx<P!UwVhHy0cLy?q-iUG~3$ zY<JnKWT~nCFW;@ix7Y-A+j`jb=Jt!po=?K6V?M0vE0soEeAM%BpO_3!oT|cJ(&{WH zh%58E4|_h-QN@JeQ(N6Fxt8Nf=l!tV2|^;bwE;5jv7QrJ&)6@R(HYKfe9%~?{8s*Q zwZ5Ru6)j5C@27z=nE?M|%3skT*2*w0TRPbM=7yR|=~&Qc$Ts|^(YWOc(RR9F(Cdlq zO{}4POmy~b<MU=$5>qU{5SQXO@f7y%0thx#cmTuQ`8y3s-n+M=7oJe@#bL@pc>|)g zxVjt~;Afh(O}5St&#$+d^v&H-T?EF!GA#djNDlV?+CpRE#lq^4>EZ@|9U+ok{X|Rx zp5hJ?h$K{J+&ER_xuS~K=Q-6}1`WazuV%FZG{bDbTo0oPIyhHBSFsX;p2R6nmajpW zu8O1IFO0BOq20?XZH&^RkjthP@@W)zUp6ktv&}?Qad-u7cVb$`|4(gK9u8&O#YZZN zlA>%GWi2Av*FhgDNy?J_eMz!s32B%?i;3(JCZn?CwI$0SnHF1%ov|g%FbJ73_GRAh z9`ARVab0hJe*fK%<$mtv+~<DI`JLZ68z%=o2J~O2@|4dNe0J`8D>EMRNof&UkGpTb zlfw3CLvr{N+_=2Wv#cqxx%{BSWcVwNI1^Si*kicMn&vWT3FI=mPASYmIp+<g`|&_s zWp-NqG|<4q>V|}ZqUvc{UD{I18KdV<O;^qxm*kFUH@M4rnQaip3JShK-)9``3gy$K z$PU<*b*p%kpOF~-Ug?=B9O6#&juPHkyX;M2y-L16uWwxVl^q2QKI5Ae%G(@ti0C<l z)U<ITY#hg5)ruzQUzOz4h?v&*haJVa@oB3Dg%8zXYxf&*yeeGJv)-dX3Ts2JUS`$Q z4GeS+$!-2qcqJxrhk-(jmGU^b#XaHNx_;JAwhJ|#{S*&x%>mT$#FJwWSlDpbjv|}& zO9C<3EESyrmy+GRS(|jtkKN*nS$BDq@N3QPU5uz^1<l`+`;IyL&=@8~<nqqy<a~nr zSLH65G8FfzS<xSy#Jjw)(ZrafHDjl`3VelfscUKDB3h~JwfZkdoT%4eo4F)5O)C2E zE>nSd+sXh*xoD?J3lI)?o6qZc7f7?|ks!@Zr5ZH)uxe3tj`j!T*QG^908iaLKM&Ly zksEO5*YK8iz0{2E_`iPkCn{PSCqKD$@Wcn>*<|11Ce<mbkfnkT<xT(GIa%5Hbd-4c zle9eorcIJ!%IfWG4bPPOcp67mjOu1a<)6YcEB!E6<8=gUPuY3fze};L?y#0HMO9#u zoMPC#gXc8<7mGAigLtfGe009z^)p`wchTZw>0-jtXl>4F^a^3|G?WC%BPxREPA~9H z0HV@h?ZCW{*rv3YFwZ}8QJ(YW0%jF0GhTE}CAMAfd}p>;%7A@T3hbj3h}q|+CRyhR z4{5#FR7XoeJ=M>A#B#_VrZyOI#2|3e%p(9p7btGr3N4n-19o9VB2De!NFoOdYGf-Y z<_6tdhWO9U=h6)!fYWGS0VCBzsz@_Jk%0DNXhG+?D5Cg*{)jzT4OAj}d=kLn!H>Sv zt$|q@0w4*s#!$xVGuh$%K&J!yYLlUqpAlh<*i+K&<$N$t*uIWWO>1S<3`a&=fzc-6 zmfAqF{A_~U3Jd726802e9$UZ3LLAU7e%?M3Ms#gpt=h@yHvs&oW4ypnWY-!3<`{6E zz|%loTcBPr6Ptu&{%xU1e(}o}2p{UHKSbG0o|>H)l~dg~*|;uw7(pGA1N?1PuScK2 z6bP*}IPmq>f_ST~H)rk-_$L|(KSH+a%56SUg8WW&WnR~Z%-p9E1k)faj@04%^&X!z zatXi++o;Ef8}euF|D;PPegv2IK2>zTpxIk!D1^IGdm&x1<NJlq)?<Nw$v4!*@LY_c zF%Ju3+3o-MtOF%FSmFswGHH_di2Xyu_#Y5(2h||TanlbxWv*Ivc@)Ze;;-R%E7%kT zKOaUK`q<yB4*7u%$Pn%H*8VmS7F9IrJS-IJleP+bkHD(L_!sXxJ5r1i=Izwfi!<Q% zlDMdVJk7C#UGfJ~Beu73F?>09?W~;}C~sFak{)7cWF(Wm^rpYyd}DIo$Q#%bXvwra zPkDE!6nt-oY=>$~iGMOg<=Ta(%L@bbw`eLGRd9F2NY%O;x$~pC!$bW#X8{sB&7UpY z3<A+!7|!5X4kMV{vlor3Q@77k?W!T(!kVgxWw3iJ08;z@;>MwUnxKYU9adYIvK!^Y z6Zg&B;fwfn{^7h|`+)HvNp7?ylZx}!?I?EWWC70#G(~6W<kfGVIh!MTcWt;o?Su{I z%(XfR*~>4Ry1cSAkRSK54<YN;`@;DChInK6;aA(!KjH;Wx6fk<Hg^pLvmAaUPEJd) zf&=8_eMp~xdjvgDW4U8JCB-qQu_W+#O%HI9hNrsY1)kMME^EC!{UAW6!Q%4=Q7!54 z4KzsFv*9u#l$O7I_fwl~`b4|)n(aN$hG{47uAY>i!iQ?Q<Vdx5o06KP)h_2oqubb? z2PM|8F3prsmh@gnd|d3mjy<kn<ya>6S6x<VQ_yr(@oSp$`YAH>F<demE`dNTR`1J+ ziK?x4HtzUSFK5_<4;-)Bd?KQ+l^_l%Vhe=y;v>B`Ev%o6;%omS=X>qW$xGLw1683< z{BQ^0P6RIQpz$lq>4YepddP*5D1B~K<3<tAMTjF(o3boVe*2!rL*D(89HuQg;Eqp= zi)&=@A3FGE1PPf_poX{;S|e#3U7^CuLs!V5dE8bWUTO02ODQmEF2~adf%;`XN<Vc3 z`&dTP^=03e&TC&Q4Lbf%C+;#S*<GQnM(aF0B&cZ)jVh`UsW@`H&oR9z<+xqdC!wWA zzzKuZ^&G+X*JBqw?&hW#l!wbyoW5Rhj+)Usi1}D0=tJ0dX5AHQ?Khb7EaX_mIm~f` z_*>b2A2hv$EAwB&jXf>REJ{1?1xkGI%uLYR`}|tCccWjq3Bk=MeZzOM@RxYPP|Jgx z;(=x&=Nxy+>MV+c@~}wc<_Bevy4)6nFQSgtzTha%P$`w!TSKg6fjv9#k{^_YKc#Ug z-6TW7N8nvnocdUJ7{`&pw$RxHB^~Q#cTS5mAG1dq#M>yogln&^Xrs+rXTDAuRhCEH zyEriLS?GmqA%EQ0u#AUdk07&__4Z=jB<veufnLI}0f+XF0B$M%UoA#1B?az-PFIs{ zj1^2eij;LVJ=p`k8kH|nW4ONgtXL|+8m8Ry)7{q!CGJR;#YbOJd`U70@D&^)X|}si ziZ7L%yQsc1$H*^I=$oqU=_J<K_}B)dGW=R~%iFsukzQpvk?7P#Op*{$BtR%^p;!!2 z8(RJY*6^nUQqiL1SwOzX_1mAMl?hz@Q??Ycap%#GtJ-(ga*(Gd3R@W;(cs=<(y)*L zW@<`-5=Flv>7`LZ_h4aT^0zEdt{s-mtUC97*~U%jWY%T++9)~Hby|P;ZPX1R(dc;W z*vxz;=U!<)#*M{%bs}ZAGgNkSbdl-B+NEyLi?wS**nkx?qX7&Z*vecAJ?ldigDeTW zXAFIwW6Moc+R?QFy8%;4ZJ8M|S)y|(vCMY|u>6(~)D0*|)UjhTFu=lOb!n4fX}j?* zB1k_b*H0wX_KvO-pGbz^W{r5pMdHhB3jt>k<FY<4Tg8PERhK!S=&d^PJ$(02I<^DQ zcz-+LGxOW{D&tP%!iLo2KYi_9o+_bQ>7nCli1T?kM*lj3hqsXUZJ@lZLnO#u-~)oa zq{|rWl_VBAp1i;GBj6=EtWFHIluOGo+5o0y$~kg@w8`W6e<0W{4-unE-ZX%}D)qIo zm;$xin1x&T3><JL8HqwzJ^(@r#PTk{#e^yJZ-Xbd%zq4kKdnLh;u_Q8q9ezTKz#YA z68O@vdu)~;49eF&C_+q?{FMY@!k9<%nYb&UuoFPfnuCZmSSG+TVO@A}&t;|u2=5lk zTp+N;Txny|r!yQZqj94EO!iD!5g3!srvO3>ZU#gViP~mEc$q0GW^POXG*aUvAZ;J( zf)PI=R);~t<UK`)-xi*wX-b0kb8RASHzD-7)IQt*Ut!fJx_bXfa;3A&M}2(#ffsJ- zEkb=JpD7nb+b(O+rTQ#0Ma8O?2e>PQ9A;H$_uMZa_mVd8L_WmSL)tg@oFbP7;Qa<k zbSn|l4M=%9b~!|r8>(8BTqt@_HM?VD4f6tFJ#iCKfB|<)lMtfkHqD?sU$Ox)#|B*( zM8s$Ax1a|i&@0u&&EUFm^M~vn`}|;jg79uj0I|UQ)W)_CtlvLGm7*P+mA7;_=rB8X zA)?8CidG9<Nh`Ft%><^tf^19LK%Cl^-AGZ2&N<QqlCg!Dc9#+nD|>*C-<}BE7j6xp zJQGtghN4jBC*X0X#}C8`fT<pXO^qPt4;NWiW41ja_qLIX*B@rC!f42D%r-<7sj(L< zzx2;-NfZJFK=uYu6RaNu7x!@K9E}#JFS{(}k>Grp6{)3N_BUkat;x!`<S48G5O-(; z;0GDLp=a0KG2Q-svr2osUifo}I-flRX!n2{)0={zcECV*$$coJ2?UVz&`&re_f+9~ znE})n&X~}0zcnvFD*U{{MF9%}s{kk#8WRU79-k>f#`#})@O4u9A}i>?#b)r&-izWx z>+`Wx*ofg)3!H`Ak;;~Mu{Yo2K6J5+QP(NfxPbr+wZ)_f@fd8`1{Ua1%~233->nre zrevquKM-D6qwEmY*a1YAYwh4HE!c1cLw>o{0s|?{a_#JMlefDtVJ;|kLTwTtRsY^+ z=Z)@}ockkY@HYp}u=y;|H}w)KV83P)$a+QNK{(n069IVPK-*M@ZEMhWiq`dIJ_Vja zspgR3&6x)-4(6^?6X&2r!>tyWTI<hhkEOJGJ*Mir;=f8c`o(_9{~Pj~PHn2iyMpb} z$tf(UVPZ)_z9ADYkf*>|2Z)jy>=;cEvDGrw;TIOYUw(&}(R-gmxC0u2P8?8rwt)f$ zpO)x)>oSNiVcIoU;5UouJntLG2H}#+NL^?w1Y1$OHOg({HL|ZXwlPtzc%Q$A)p?nZ zf4;zE+6cEY2_+#u(xs*j7&;m8G?(?0EwQ=HPI>x)3VCK?aarRzKps_q;k>o~Orju_ z2{H&*^c?Qci5#x+$c$5ukF_SnFjkp)Ww!}NXHKcxtG}EQk!-p&#oq`;k5=Af%8_8O z#MQeJ^uF++hcVeamv=JFpQ#BZz8DpFI5nryRn_s!d2u!&^isaVze@(*Fmfcso}>}w z$ZMgM1!Gf_thfo%rr}BeLt{J(kqUTUFs3$$t}@w|*S=1wTB&*e7G4|d(j#1+#}M9j zuqRtDy3#XlZ2f5(|G#C1tcHND<(a!<ZUe1nEsIflkjwkMCHtz{-a8Y93x%`)ewy7h z-dX%0;cfg4_laH1jFV4b-<0VV#%ljorq!n`GFiqxzn_N^!L7$wZpN^Iy41*X4Lo8= zwQZO<eBLVQpkH|C6Rxde0sf7tcV65}d;Ofrc&nBIE0yb+!~_%iP)eDWgsG_yaaxXH z>;Bb2>b-9sd4lUh%lR3Mbt^;QfP8UniDJ2?GOVPoVTwdmo|#*j#MlOd<#l5m5Jt;X zhX;OE-3`B^zn9lJNnY-K13T!q{x|&=P9&e1>_-QdzIme4$9`w*9Ieb$NATa5VrO7l e_PcI0zWwEc1PODQ-Dh-#%Yi>|+u?@(-S=PLCy_(| literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/actuator_v1.py b/examples/python3/tutorial/formation/chiba/actuator_v1.py new file mode 100644 index 00000000..981c0ee2 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/actuator_v1.py @@ -0,0 +1,132 @@ +import Sofa +from fingerController import FingerController # for keyboard controlling +from loopstest_function_param3 import looptest # algorithm for generating the fiber loops +import gmsh + +from useful.header import addHeader, addSolverNode + + +def createScene(root_node): + addHeader(root_node, isConstrained=True) + + root_node.gravity.value = [-9810, 0, 0] + # root_node.addObject('FreeMotionAnimationLoop') + # root_node.addObject('GenericConstraintSolver', tolerance=1e-9, maxIterations=50000) + root_node.addObject('EulerImplicitSolver', name='odesolver', rayleighStiffness=0.01, rayleighMass=0.01) + + finger = root_node.addChild('finger') + finger.addObject('SparseLDLSolver') + finger.addObject('MeshGmshLoader', name='loader', filename='data/mesh/act23mmwithconnector.msh', + rotation=[90, 0, -90], translation=[22.5, 0, 0]) + + finger.addObject('MeshTopology', src='@loader', name='container') + finger.addObject('MechanicalObject', name='tetras', template='Vec3', showObject=False, showObjectScale=1) + + youngModulus = 263.8 + poissonRatio = 0.49 + mu_ = youngModulus / (2 * (1 + poissonRatio)) + k0_ = youngModulus / (3 * (1 - 2 * poissonRatio)) + finger.addObject('TetrahedronHyperelasticityFEMForceField', materialName="NeoHookean", + ParameterSet=str(mu_) + " " + str(k0_)) + finger.addObject('UniformMass', totalMass=0.0008) + finger.addObject('BoxROI', name='boxROISubTopo', box=[23, -10, -8, 26, 10, 8], strict=False, drawBoxes=True) + finger.addObject('BoxROI', name='boxROISubTopo2', box=[0, -10, -4, 28, 10, -2], strict=False, drawBoxes=True) + finger.addObject('BoxROI', name='boxROI', box=[-2, -10, -20, 2, 10, 20], drawBoxes=True) + finger.addObject('RestShapeSpringsForceField', points='@boxROI.indices', stiffness=1e12, angularStiffness=1e12) + finger.addObject('LinearSolverConstraintCorrection') + # Plastic Part + modelSubTopo = finger.addChild('modelSubTopo') + modelSubTopo.addObject('MeshTopology', position='@loader.position', tetrahedra='@boxROISubTopo.tetrahedraInROI', + name='container') + modelSubTopo.addObject('TetrahedronFEMForceField', template='Vec3', name='FEM', method='large', poissonRatio=0.3, + youngModulus=4400000) + + + # Parameters for the fiber reinforcement + num_loops = 8 # number of loops + loop_distance = 3 # Distance between fiber loops + loops_data, spring_data, indices1, indices2, lengths = looptest(loop_distance, num_loops) + + # print('-------------------------loops_data-------------------') + # print(loops_data) + # print('-------------------------spring_data-------------------') + # print(spring_data) + # print('-------------------------indices1-------------------') + # print(indices1) + # print('-------------------------indices2-------------------') + # print(indices2) + # print('-------------------------lengths-------------------') + # print(lengths) + + # nbDOFs = 10 + Ks = 1e7 # spring stinffness + Kd = 5 + position = [[i * loop_distance + 1, 0, -4] for i in range(num_loops)] + print("Positions: ", position) + edges = [[i, i + 1] for i in range(num_loops - 1)] + print("edges: ", edges) + + # Hitching (transversal fiber) + hitching = finger.addChild("hitching") # fiber string that crosses the actuator transversally + hitching.addObject("MechanicalObject", template="Vec3", name="DOF", + position=[[i * loop_distance + 1, 0, -4] for i in range(num_loops)], + showObject=True, showObjectScale=1) + hitching.addObject('MeshTopology', name='lines', + lines=[[i, i + 1] for i in range(num_loops - 1)]) + hitching.addObject("StiffSpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1, + stiffness=Ks, damping=Kd, indices1=[0, 1, 2, 3, 4, 5, 6], indices2=[1, 2, 3, 4, 5, 6, 7], + lengths=loop_distance) + hitching.addObject('BarycentricMapping', name='mapping') + hitching.addObject('UniformMass', totalMass=0.0008) + + return root_node + + # Mapping + + # hitching.addObject("FixedConstraint", name="FixedConstraint", indices=[0]) + + # finger.addObject('MechanicalMatrixMapper', template="Vec3,Vec3", + # nodeToParse=hitching.getLinkPath(), # where to find the forces to map + # object1=finger.tetras.getLinkPath()) # in case of multi-mapping, here you can give the second parent + + # Fiber Loops + + for k in range(0, loopnum): + fiber = finger.addChild("fiber" + str(k)) + fiber.addObject("MechanicalObject", template="Vec3", name="DOF", + position=loops[k], + showObject=True, showObjectScale=1) + fiber.addObject('MeshTopology', name='lines', lines=[[i, i + 1] for i in range(loopnum)]) + + # fiber.addObject("FixedConstraint", name="FixedConstragetLinkPathint", indices=[0]) + fiber.addObject("StiffSpringForceField", template="Vec3d", name="springs", showArrowSize=0.5, drawMode=1, + stiffness=Ks, damping=Kd, indices1=indices1, indices2=indices2, lengths=lengths) + + # Mapping + + fiber.addObject('BarycentricMapping', name='mapping') + # finger.addObject("MechanicalMatrixMapper", template="Vec3,Vec3",name="MechanicalMatrixMapper"+str(k), + # nodeToParse=fiber.getLinkPath(), + # object1=finger.tetras.getLinkPath(), + # object2=hitching.DOF.getLinkPath()) + + # Air Chamber(cavity) + + tracker = finger.addChild("tracker") # trackers for measuring bending angle + tracker.addObject("MechanicalObject", template="Vec3", name="DOF", + position=[[29, 0, -4], [31, 0, -4]], + showObject=True, showObjectScale=1, drawMode=1) + tracker.addObject("MeshTopology", name="points", points=[[29, 0, 0], [31, 0, 0]]) + tracker.addObject('BarycentricMapping', name='mapping') + + # air Pressure Cavity. Note: 0.1=10kPa + cavity = finger.addChild('cavity') + cavity.addObject('MeshSTLLoader', name='cavityLoader', filename='data/mesh/CHAMBER20mm-075mm.stl', + rotation=[90, 0, 90]) + cavity.addObject('MeshTopology', src='@cavityLoader', name='cavityMesh') + cavity.addObject('MechanicalObject', name='cavity') + cavity.addObject('SurfacePressureConstraint', name='SurfacePressureConstraint', template='Vec3', value=0, + triangles='@cavityMesh.triangles', valueType='pressure') + cavity.addObject('BarycentricMapping', name='mapping') + + rootNode.addObject(FingerController(rootNode)) diff --git a/examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm-075mm.stl b/examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm-075mm.stl new file mode 100644 index 00000000..386638b4 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm-075mm.stl @@ -0,0 +1,24222 @@ +solid Created by Gmsh +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995834 4.833333333333327 + vertex 5.5 -1.371237540587628 5.574074074074068 + vertex 5.5 -1.398051880323649 4.833333333333327 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995839 5.574074074074068 + vertex 5.5 -1.371237540587628 5.574074074074068 + vertex 5.5 -0.6415002990995834 4.833333333333327 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995808 12.24074074074071 + vertex 5.5 -1.353752970690163 12.18700972484257 + vertex 5.5 -0.6505691609439761 11.60886399377859 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.358499700900416 6.31481481481481 + vertex 5.5 -0.6287624594123741 7.055555555555548 + vertex 5.5 -1.358499700900418 7.055555555555548 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.358499700900416 6.31481481481481 + vertex 5.5 -0.5551839111767312 6.314814814814809 + vertex 5.5 -0.6287624594123741 7.055555555555548 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.353752970690163 12.18700972484257 + vertex 5.5 -1.32975519511809 11.43515874407667 + vertex 5.5 -0.6505691609439761 11.60886399377859 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 18.53703703703703 + vertex 5.5 -0.7297372414880464 18.53703703703698 + vertex 5.5 0 17.79629629629628 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 17.79629629629628 + vertex 5.5 -0.7297372414880464 18.53703703703698 + vertex 5.5 -0.7460951207516832 17.80824075471289 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900418 12.98148148148145 + vertex 5.5 -1.353752970690163 12.18700972484257 + vertex 5.5 -0.6415002990995808 12.24074074074071 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.314287720233775 8.531369398876958 + vertex 5.5 -1.395086979222342 7.796001229753178 + vertex 5.5 -0.6415002990995808 7.796296296296289 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6415002990995808 7.796296296296289 + vertex 5.5 -0.5206648722608377 8.514130710649287 + vertex 5.5 -1.314287720233775 8.531369398876958 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6415002990995808 12.24074074074071 + vertex 5.5 -0.5775061330896927 12.98148148148145 + vertex 5.5 -1.358499700900418 12.98148148148145 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995808 7.796296296296289 + vertex 5.5 -1.395086979222342 7.796001229753178 + vertex 5.5 -1.358499700900418 7.055555555555548 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900418 7.055555555555548 + vertex 5.5 -0.6287624594123741 7.055555555555548 + vertex 5.5 -0.6415002990995808 7.796296296296289 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6475363419708325 9.168913783999146 + vertex 5.5 -1.324198814932662 9.334897455958121 + vertex 5.5 -1.314287720233775 8.531369398876958 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900417 4.092592592592589 + vertex 5.5 -1.483478221254913 3.361605706171768 + vertex 5.5 -0.6737875462150171 3.355237303356756 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6737875462150171 3.355237303356756 + vertex 5.5 -0.6042921995806961 4.092768844753402 + vertex 5.5 -1.358499700900417 4.092592592592589 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.314287720233775 8.531369398876958 + vertex 5.5 -0.5206648722608377 8.514130710649287 + vertex 5.5 -0.6475363419708325 9.168913783999146 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6415002990995863 15.20370370370367 + vertex 5.5 -0.5206648722608387 15.92153811805669 + vertex 5.5 -1.314287720233773 15.93877680628435 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6475363419708347 16.57632119140656 + vertex 5.5 -1.324695901138387 16.74295517276821 + vertex 5.5 -1.314287720233773 15.93877680628435 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.314287720233773 15.93877680628435 + vertex 5.5 -1.395086979222341 15.20340863716056 + vertex 5.5 -0.6415002990995863 15.20370370370367 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900416 6.31481481481481 + vertex 5.5 -1.371237540587628 5.574074074074068 + vertex 5.5 -0.6415002990995839 5.574074074074068 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6415002990995839 5.574074074074068 + vertex 5.5 -0.5551839111767312 6.314814814814809 + vertex 5.5 -1.358499700900416 6.31481481481481 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900417 4.092592592592589 + vertex 5.5 -0.6042921995806961 4.092768844753402 + vertex 5.5 -0.6415002990995834 4.833333333333327 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995834 4.833333333333327 + vertex 5.5 -1.398051880323649 4.833333333333327 + vertex 5.5 -1.358499700900417 4.092592592592589 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900414 14.46296296296293 + vertex 5.5 -1.422493866910307 13.72222222222219 + vertex 5.5 -0.6415002990995839 13.72222222222219 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995839 13.72222222222219 + vertex 5.5 -1.422493866910307 13.72222222222219 + vertex 5.5 -1.358499700900418 12.98148148148145 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.358499700900418 12.98148148148145 + vertex 5.5 -0.5775061330896927 12.98148148148145 + vertex 5.5 -0.6415002990995839 13.72222222222219 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6415002990995839 13.72222222222219 + vertex 5.5 -0.5775061330896931 14.46296296296293 + vertex 5.5 -1.358499700900414 14.46296296296293 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.314287720233773 15.93877680628435 + vertex 5.5 -0.5206648722608387 15.92153811805669 + vertex 5.5 -0.6475363419708347 16.57632119140656 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995863 15.20370370370367 + vertex 5.5 -1.395086979222341 15.20340863716056 + vertex 5.5 -1.358499700900414 14.46296296296293 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900414 14.46296296296293 + vertex 5.5 -0.5775061330896931 14.46296296296293 + vertex 5.5 -0.6415002990995863 15.20370370370367 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6737875462150171 3.355237303356756 + vertex 5.5 -1.385103859159129 2.6564949312058 + vertex 5.5 -0.5887211424549268 2.55129450012744 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.5842425113063302 20.46093950786474 + vertex 5.5 -1.38510385915909 20.34350506879417 + vertex 5.5 -0.6469157593234742 19.7181667445964 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.324198814932662 9.334897455958121 + vertex 5.5 -0.5412048538155803 9.844801711518864 + vertex 5.5 -1.329271032003867 10.0458315134311 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.333446556131944 10.72648366536412 + vertex 5.5 -0.5412048538155728 10.93297606625889 + vertex 5.5 -1.32975519511809 11.43515874407667 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.324695901138387 16.74295517276821 + vertex 5.5 -0.5412048538155885 17.2522091189263 + vertex 5.5 -1.333446556131948 17.45870151982104 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.333446556131948 18.87463181351226 + vertex 5.5 -0.5412048538156079 19.08112421440701 + vertex 5.5 -1.317778504738353 19.55228735626768 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.483478221254913 3.361605706171768 + vertex 5.5 -1.385103859159129 2.6564949312058 + vertex 5.5 -0.6737875462150171 3.355237303356756 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6469157593234742 19.7181667445964 + vertex 5.5 -1.38510385915909 20.34350506879417 + vertex 5.5 -1.317778504738353 19.55228735626768 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6475363419708325 9.168913783999146 + vertex 5.5 -0.5412048538155803 9.844801711518864 + vertex 5.5 -1.324198814932662 9.334897455958121 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.32975519511809 11.43515874407667 + vertex 5.5 -0.5412048538155728 10.93297606625889 + vertex 5.5 -0.6505691609439761 11.60886399377859 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6475363419708347 16.57632119140656 + vertex 5.5 -0.5412048538155885 17.2522091189263 + vertex 5.5 -1.324695901138387 16.74295517276821 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.317778504738353 19.55228735626768 + vertex 5.5 -0.5412048538156079 19.08112421440701 + vertex 5.5 -0.6469157593234742 19.7181667445964 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 18.53703703703703 + vertex 5.5 -1.333446556131948 18.87463181351226 + vertex 5.5 -2 19.27777777777777 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 17.79629629629628 + vertex 5.5 -1.333446556131948 17.45870151982104 + vertex 5.5 -1.358499700900414 18.16666666666666 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 20.01851851851852 + vertex 5.5 -0.6469157593234742 19.7181667445964 + vertex 5.5 0 19.27777777777777 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 17.79629629629628 + vertex 5.5 -1.358499700900414 18.16666666666666 + vertex 5.5 -2 18.53703703703703 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 10.38888888888887 + vertex 5.5 -1.329271032003867 10.0458315134311 + vertex 5.5 -1.333446556131944 10.72648366536412 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 17.05555555555554 + vertex 5.5 -1.333446556131948 17.45870151982104 + vertex 5.5 -2 17.79629629629628 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 15.57407407407405 + vertex 5.5 -1.314287720233773 15.93877680628435 + vertex 5.5 -2 16.3148148148148 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 11.87037037037035 + vertex 5.5 -0.6505691609439761 11.60886399377859 + vertex 5.5 0 11.12962962962961 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 6.68518518518518 + vertex 5.5 -1.358499700900418 7.055555555555548 + vertex 5.5 -2 7.42592592592592 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 5.203703703703698 + vertex 5.5 -0.6415002990995839 5.574074074074068 + vertex 5.5 -0.6415002990995834 4.833333333333327 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 3.722222222222218 + vertex 5.5 -1.358499700900417 4.092592592592589 + vertex 5.5 -2 4.462962962962957 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 5.203703703703698 + vertex 5.5 -0.6415002990995834 4.833333333333327 + vertex 5.5 0 4.462962962962957 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995808 12.24074074074071 + vertex 5.5 -0.6505691609439761 11.60886399377859 + vertex 5.5 0 11.87037037037035 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 3.722222222222218 + vertex 5.5 -0.6737875462150171 3.355237303356756 + vertex 5.5 0 2.98148148148148 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 15.57407407407405 + vertex 5.5 -0.6415002990995863 15.20370370370367 + vertex 5.5 0 14.83333333333331 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 5.944444444444438 + vertex 5.5 -0.6415002990995839 5.574074074074068 + vertex 5.5 0 5.203703703703698 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 8.166666666666657 + vertex 5.5 -0.6415002990995808 7.796296296296289 + vertex 5.5 0 7.42592592592592 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 12.61111111111108 + vertex 5.5 -0.6415002990995808 12.24074074074071 + vertex 5.5 0 11.87037037037035 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 17.05555555555554 + vertex 5.5 -0.6475363419708347 16.57632119140656 + vertex 5.5 0 16.3148148148148 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900416 6.31481481481481 + vertex 5.5 -1.358499700900418 7.055555555555548 + vertex 5.5 -2 6.68518518518518 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 8.166666666666657 + vertex 5.5 -1.314287720233775 8.531369398876958 + vertex 5.5 -2 8.907407407407394 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 9.648148148148133 + vertex 5.5 -1.329271032003867 10.0458315134311 + vertex 5.5 -2 10.38888888888887 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 5.944444444444438 + vertex 5.5 -1.358499700900416 6.31481481481481 + vertex 5.5 -2 6.68518518518518 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 9.648148148148133 + vertex 5.5 -0.6475363419708325 9.168913783999146 + vertex 5.5 0 8.907407407407394 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 14.09259259259256 + vertex 5.5 -0.6415002990995839 13.72222222222219 + vertex 5.5 0 13.35185185185182 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 10.38888888888887 + vertex 5.5 -1.333446556131944 10.72648366536412 + vertex 5.5 -2 11.12962962962961 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 12.61111111111108 + vertex 5.5 -1.358499700900418 12.98148148148145 + vertex 5.5 -2 13.35185185185182 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 14.09259259259256 + vertex 5.5 -1.358499700900414 14.46296296296293 + vertex 5.5 -2 14.83333333333331 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.358499700900414 18.16666666666666 + vertex 5.5 -1.333446556131948 18.87463181351226 + vertex 5.5 -2 18.53703703703703 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.7490254591533927 10.38779636909237 + vertex 5.5 -0.5412048538155728 10.93297606625889 + vertex 5.5 -1.333446556131944 10.72648366536412 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.329271032003867 10.0458315134311 + vertex 5.5 -0.5412048538155803 9.844801711518864 + vertex 5.5 -0.7490254591533927 10.38779636909237 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.333446556131948 17.45870151982104 + vertex 5.5 -0.5412048538155885 17.2522091189263 + vertex 5.5 -0.7460951207516832 17.80824075471289 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.7297372414880464 18.53703703703698 + vertex 5.5 -0.5412048538156079 19.08112421440701 + vertex 5.5 -1.333446556131948 18.87463181351226 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.333446556131948 18.87463181351226 + vertex 5.5 -1.317778504738353 19.55228735626768 + vertex 5.5 -2 19.27777777777777 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 15.57407407407405 + vertex 5.5 -0.5206648722608387 15.92153811805669 + vertex 5.5 -0.6415002990995863 15.20370370370367 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6475363419708347 16.57632119140656 + vertex 5.5 -0.5206648722608387 15.92153811805669 + vertex 5.5 0 16.3148148148148 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 12.61111111111108 + vertex 5.5 -1.353752970690163 12.18700972484257 + vertex 5.5 -1.358499700900418 12.98148148148145 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 15.57407407407405 + vertex 5.5 -1.395086979222341 15.20340863716056 + vertex 5.5 -1.314287720233773 15.93877680628435 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 8.166666666666657 + vertex 5.5 -0.5206648722608377 8.514130710649287 + vertex 5.5 -0.6415002990995808 7.796296296296289 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 8.166666666666657 + vertex 5.5 -1.395086979222342 7.796001229753178 + vertex 5.5 -1.314287720233775 8.531369398876958 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 12.61111111111108 + vertex 5.5 -0.5775061330896927 12.98148148148145 + vertex 5.5 -0.6415002990995808 12.24074074074071 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.314287720233773 15.93877680628435 + vertex 5.5 -1.324695901138387 16.74295517276821 + vertex 5.5 -2 16.3148148148148 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900418 7.055555555555548 + vertex 5.5 -1.395086979222342 7.796001229753178 + vertex 5.5 -2 7.42592592592592 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995808 7.796296296296289 + vertex 5.5 -0.6287624594123741 7.055555555555548 + vertex 5.5 0 7.42592592592592 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 14.09259259259256 + vertex 5.5 -0.5775061330896931 14.46296296296293 + vertex 5.5 -0.6415002990995839 13.72222222222219 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 9.648148148148133 + vertex 5.5 -1.324198814932662 9.334897455958121 + vertex 5.5 -1.329271032003867 10.0458315134311 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995863 15.20370370370367 + vertex 5.5 -0.5775061330896931 14.46296296296293 + vertex 5.5 0 14.83333333333331 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 14.09259259259256 + vertex 5.5 -1.422493866910307 13.72222222222219 + vertex 5.5 -1.358499700900414 14.46296296296293 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 3.722222222222218 + vertex 5.5 -1.483478221254913 3.361605706171768 + vertex 5.5 -1.358499700900417 4.092592592592589 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995839 13.72222222222219 + vertex 5.5 -0.5775061330896927 12.98148148148145 + vertex 5.5 0 13.35185185185182 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 3.722222222222218 + vertex 5.5 -0.6042921995806961 4.092768844753402 + vertex 5.5 -0.6737875462150171 3.355237303356756 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900414 14.46296296296293 + vertex 5.5 -1.395086979222341 15.20340863716056 + vertex 5.5 -2 14.83333333333331 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 5.944444444444438 + vertex 5.5 -0.5551839111767312 6.314814814814809 + vertex 5.5 -0.6415002990995839 5.574074074074068 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 5.944444444444438 + vertex 5.5 -1.371237540587628 5.574074074074068 + vertex 5.5 -1.358499700900416 6.31481481481481 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900418 12.98148148148145 + vertex 5.5 -1.422493866910307 13.72222222222219 + vertex 5.5 -2 13.35185185185182 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6415002990995834 4.833333333333327 + vertex 5.5 -0.6042921995806961 4.092768844753402 + vertex 5.5 0 4.462962962962957 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900417 4.092592592592589 + vertex 5.5 -1.398051880323649 4.833333333333327 + vertex 5.5 -2 4.462962962962957 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6475363419708325 9.168913783999146 + vertex 5.5 -0.5206648722608377 8.514130710649287 + vertex 5.5 0 8.907407407407394 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.314287720233775 8.531369398876958 + vertex 5.5 -1.324198814932662 9.334897455958121 + vertex 5.5 -2 8.907407407407394 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.333446556131944 10.72648366536412 + vertex 5.5 -1.32975519511809 11.43515874407667 + vertex 5.5 -2 11.12962962962961 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 17.05555555555554 + vertex 5.5 -1.324695901138387 16.74295517276821 + vertex 5.5 -1.333446556131948 17.45870151982104 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.5887211424549268 2.55129450012744 + vertex 5.5 -1.385103859159129 2.6564949312058 + vertex 5.5 -1.000000000000001 2.077350269189625 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.000000000000001 20.92264973081037 + vertex 5.5 -1.38510385915909 20.34350506879417 + vertex 5.5 -0.5842425113063302 20.46093950786474 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 19.27777777777777 + vertex 5.5 -1.317778504738353 19.55228735626768 + vertex 5.5 -2 20.01851851851852 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.329271032003867 10.0458315134311 + vertex 5.5 -0.7490254591533927 10.38779636909237 + vertex 5.5 -1.333446556131944 10.72648366536412 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 11.87037037037035 + vertex 5.5 -1.32975519511809 11.43515874407667 + vertex 5.5 -1.353752970690163 12.18700972484257 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 13.35185185185182 + vertex 5.5 -1.422493866910307 13.72222222222219 + vertex 5.5 -2 14.09259259259256 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 16.3148148148148 + vertex 5.5 -0.5206648722608387 15.92153811805669 + vertex 5.5 0 15.57407407407405 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 11.87037037037035 + vertex 5.5 -1.353752970690163 12.18700972484257 + vertex 5.5 -2 12.61111111111108 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 7.42592592592592 + vertex 5.5 -1.395086979222342 7.796001229753178 + vertex 5.5 -2 8.166666666666657 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 14.83333333333331 + vertex 5.5 -0.5775061330896931 14.46296296296293 + vertex 5.5 0 14.09259259259256 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 11.12962962962961 + vertex 5.5 -1.32975519511809 11.43515874407667 + vertex 5.5 -2 11.87037037037035 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 7.42592592592592 + vertex 5.5 -0.6287624594123741 7.055555555555548 + vertex 5.5 0 6.68518518518518 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 13.35185185185182 + vertex 5.5 -0.5775061330896927 12.98148148148145 + vertex 5.5 0 12.61111111111108 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 8.907407407407394 + vertex 5.5 -0.5206648722608377 8.514130710649287 + vertex 5.5 0 8.166666666666657 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 8.907407407407394 + vertex 5.5 -1.324198814932662 9.334897455958121 + vertex 5.5 -2 9.648148148148133 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 2.98148148148148 + vertex 5.5 -1.483478221254913 3.361605706171768 + vertex 5.5 -2 3.722222222222218 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 14.83333333333331 + vertex 5.5 -1.395086979222341 15.20340863716056 + vertex 5.5 -2 15.57407407407405 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 4.462962962962957 + vertex 5.5 -0.6042921995806961 4.092768844753402 + vertex 5.5 0 3.722222222222218 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.398051880323649 4.833333333333327 + vertex 5.5 -1.371237540587628 5.574074074074068 + vertex 5.5 -2 5.203703703703698 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 4.462962962962957 + vertex 5.5 -1.398051880323649 4.833333333333327 + vertex 5.5 -2 5.203703703703698 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -1.333446556131948 17.45870151982104 + vertex 5.5 -0.7460951207516832 17.80824075471289 + vertex 5.5 -1.358499700900414 18.16666666666666 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 16.3148148148148 + vertex 5.5 -1.324695901138387 16.74295517276821 + vertex 5.5 -2 17.05555555555554 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6287624594123741 7.055555555555548 + vertex 5.5 -0.5551839111767312 6.314814814814809 + vertex 5.5 0 6.68518518518518 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 6.68518518518518 + vertex 5.5 -0.5551839111767312 6.314814814814809 + vertex 5.5 0 5.944444444444438 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 5.203703703703698 + vertex 5.5 -1.371237540587628 5.574074074074068 + vertex 5.5 -2 5.944444444444438 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.358499700900414 18.16666666666666 + vertex 5.5 -0.7297372414880464 18.53703703703698 + vertex 5.5 -1.333446556131948 18.87463181351226 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.7460951207516832 17.80824075471289 + vertex 5.5 -0.7297372414880464 18.53703703703698 + vertex 5.5 -1.358499700900414 18.16666666666666 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 20.75925925925926 + vertex 5.5 -0.5842425113063302 20.46093950786474 + vertex 5.5 0 20.01851851851852 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 2.98148148148148 + vertex 5.5 -0.5887211424549268 2.55129450012744 + vertex 5.5 0 2.24074074074074 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 20.01851851851852 + vertex 5.5 -1.38510385915909 20.34350506879417 + vertex 5.5 -2 20.75925925925926 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 2.24074074074074 + vertex 5.5 -1.385103859159129 2.6564949312058 + vertex 5.5 -2 2.98148148148148 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6666666666666667 1.5 + vertex 5.5 -1.000000000000001 2.077350269189625 + vertex 5.5 -1.333333333333336 1.5 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.333333333333336 21.5 + vertex 5.5 -1.000000000000001 20.92264973081037 + vertex 5.5 -0.6666666666666667 21.5 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 20.01851851851852 + vertex 5.5 -0.5842425113063302 20.46093950786474 + vertex 5.5 -0.6469157593234742 19.7181667445964 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6737875462150171 3.355237303356756 + vertex 5.5 -0.5887211424549268 2.55129450012744 + vertex 5.5 0 2.98148148148148 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.317778504738353 19.55228735626768 + vertex 5.5 -1.38510385915909 20.34350506879417 + vertex 5.5 -2 20.01851851851852 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 2.98148148148148 + vertex 5.5 -1.385103859159129 2.6564949312058 + vertex 5.5 -1.483478221254913 3.361605706171768 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 19.27777777777777 + vertex 5.5 -0.5412048538156079 19.08112421440701 + vertex 5.5 0 18.53703703703703 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 10.38888888888887 + vertex 5.5 -0.5412048538155803 9.844801711518864 + vertex 5.5 0 9.648148148148133 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 17.79629629629628 + vertex 5.5 -0.5412048538155885 17.2522091189263 + vertex 5.5 0 17.05555555555554 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 11.12962962962961 + vertex 5.5 -0.5412048538155728 10.93297606625889 + vertex 5.5 0 10.38888888888887 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -0.7490254591533927 10.38779636909237 + vertex 5.5 -0.5412048538155803 9.844801711518864 + vertex 5.5 0 10.38888888888887 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 10.38888888888887 + vertex 5.5 -0.5412048538155728 10.93297606625889 + vertex 5.5 -0.7490254591533927 10.38779636909237 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 18.53703703703703 + vertex 5.5 -0.5412048538156079 19.08112421440701 + vertex 5.5 -0.7297372414880464 18.53703703703698 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.7460951207516832 17.80824075471289 + vertex 5.5 -0.5412048538155885 17.2522091189263 + vertex 5.5 0 17.79629629629628 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 21.5 + vertex 5.5 -0.4501818355945997 21.02856969958687 + vertex 5.5 0 20.75925925925926 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 20.75925925925926 + vertex 5.5 -1.526564550644583 21.00353772520975 + vertex 5.5 -2 21.5 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -2 1.5 + vertex 5.5 -1.526564550644588 1.996462274790242 + vertex 5.5 -2 2.24074074074074 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 2.24074074074074 + vertex 5.5 -0.4734354493554138 1.996462274790242 + vertex 5.5 0 1.5 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -0.6666666666666667 21.5 + vertex 5.5 -0.4501818355945997 21.02856969958687 + vertex 5.5 0 21.5 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 21.5 + vertex 5.5 -1.526564550644583 21.00353772520975 + vertex 5.5 -1.333333333333336 21.5 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 1.5 + vertex 5.5 -0.4734354493554138 1.996462274790242 + vertex 5.5 -0.6666666666666667 1.5 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.333333333333336 1.5 + vertex 5.5 -1.526564550644588 1.996462274790242 + vertex 5.5 -2 1.5 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 20.75925925925926 + vertex 5.5 -0.4501818355945997 21.02856969958687 + vertex 5.5 -0.5842425113063302 20.46093950786474 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.5887211424549268 2.55129450012744 + vertex 5.5 -0.4734354493554138 1.996462274790242 + vertex 5.5 0 2.24074074074074 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.38510385915909 20.34350506879417 + vertex 5.5 -1.526564550644583 21.00353772520975 + vertex 5.5 -2 20.75925925925926 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -2 2.24074074074074 + vertex 5.5 -1.526564550644588 1.996462274790242 + vertex 5.5 -1.385103859159129 2.6564949312058 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.5842425113063302 20.46093950786474 + vertex 5.5 -0.4501818355945997 21.02856969958687 + vertex 5.5 -1.000000000000001 20.92264973081037 + endloop +endfacet +facet normal 1 -0 0 + outer loop + vertex 5.5 -1.000000000000001 2.077350269189625 + vertex 5.5 -0.4734354493554138 1.996462274790242 + vertex 5.5 -0.5887211424549268 2.55129450012744 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.000000000000001 20.92264973081037 + vertex 5.5 -1.526564550644583 21.00353772520975 + vertex 5.5 -1.38510385915909 20.34350506879417 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.385103859159129 2.6564949312058 + vertex 5.5 -1.526564550644588 1.996462274790242 + vertex 5.5 -1.000000000000001 2.077350269189625 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 17.05555555555554 + vertex 5.5 -0.5412048538155885 17.2522091189263 + vertex 5.5 -0.6475363419708347 16.57632119140656 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6469157593234742 19.7181667445964 + vertex 5.5 -0.5412048538156079 19.08112421440701 + vertex 5.5 0 19.27777777777777 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 0 9.648148148148133 + vertex 5.5 -0.5412048538155803 9.844801711518864 + vertex 5.5 -0.6475363419708325 9.168913783999146 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -0.6505691609439761 11.60886399377859 + vertex 5.5 -0.5412048538155728 10.93297606625889 + vertex 5.5 0 11.12962962962961 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.333333333333336 21.5 + vertex 5.5 -1.526564550644583 21.00353772520975 + vertex 5.5 -1.000000000000001 20.92264973081037 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.000000000000001 20.92264973081037 + vertex 5.5 -0.4501818355945997 21.02856969958687 + vertex 5.5 -0.6666666666666667 21.5 + endloop +endfacet +facet normal 1 0 0 + outer loop + vertex 5.5 -1.000000000000001 2.077350269189625 + vertex 5.5 -1.526564550644588 1.996462274790242 + vertex 5.5 -1.333333333333336 1.5 + endloop +endfacet +facet normal 1 0 -0 + outer loop + vertex 5.5 -0.6666666666666667 1.5 + vertex 5.5 -0.4734354493554138 1.996462274790242 + vertex 5.5 -1.000000000000001 2.077350269189625 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.363899056731139 14.4948538895986 + vertex -5.5 -1.480680260039985 15.18717556264309 + vertex -5.5 -0.6870385854396153 15.19803606554362 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995855 14.46296296296293 + vertex -5.5 -1.363899056731139 14.4948538895986 + vertex -5.5 -0.6870385854396153 15.19803606554362 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.646247029309835 13.66849120632406 + vertex -5.5 -0.6702448048819056 12.91664022555816 + vertex -5.5 -1.34943083905602 13.0903454752601 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900419 13.72222222222224 + vertex -5.5 -0.646247029309835 13.66849120632406 + vertex -5.5 -1.34943083905602 13.0903454752601 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.489211461299444 10.72451589785935 + vertex -5.5 -0.7968723843076638 10.73319652055624 + vertex -5.5 -1.330608655261263 10.01722652108445 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.7968723843076638 10.73319652055624 + vertex -5.5 -0.5905144024334588 10.01572721891267 + vertex -5.5 -1.330608655261263 10.01722652108445 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.330608655261263 10.01722652108445 + vertex -5.5 -0.5905144024334588 10.01572721891267 + vertex -5.5 -0.6415002990995808 9.277777777777768 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6415002990995808 9.277777777777768 + vertex -5.5 -1.395936673882247 9.277710514271241 + vertex -5.5 -1.330608655261263 10.01722652108445 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900414 8.537037037037063 + vertex -5.5 -0.5283000598199152 8.537037037037035 + vertex -5.5 -0.6415002990995808 7.796296296296282 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995808 7.796296296296282 + vertex -5.5 -1.471699940180082 7.796296296296312 + vertex -5.5 -1.358499700900414 8.537037037037063 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6870385854396153 15.19803606554362 + vertex -5.5 -1.480680260039985 15.18717556264309 + vertex -5.5 -1.352463658029169 15.83558045066583 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.352463658029169 15.83558045066583 + vertex -5.5 -0.6759590785998856 16.00156412262479 + vertex -5.5 -0.6870385854396153 15.19803606554362 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.326212453784984 19.64476269664324 + vertex -5.5 -0.5284304737528064 19.63993188190802 + vertex -5.5 -0.7010437741381724 18.91509534780636 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995834 4.833333333333336 + vertex -5.5 -1.397388727486945 4.833333333333343 + vertex -5.5 -1.358499700900413 5.574074074074103 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900414 7.055555555555575 + vertex -5.5 -0.6026112725130404 7.055555555555559 + vertex -5.5 -0.6415002990995839 6.314814814814811 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900413 5.574074074074103 + vertex -5.5 -0.5283000598199161 5.574074074074076 + vertex -5.5 -0.6415002990995834 4.833333333333336 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995839 6.314814814814811 + vertex -5.5 -1.407849202246686 6.314814814814827 + vertex -5.5 -1.358499700900414 7.055555555555575 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900416 4.092592592592595 + vertex -5.5 -0.6042921995806911 4.092768844753408 + vertex -5.5 -0.6737875462150147 3.355237303356752 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.7010437741381724 18.91509534780636 + vertex -5.5 -1.475943977190465 18.93004070394194 + vertex -5.5 -1.326212453784984 19.64476269664324 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6737875462150147 3.355237303356752 + vertex -5.5 -1.483478221254904 3.36160570617178 + vertex -5.5 -1.358499700900416 4.092592592592595 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.6415002990995834 4.833333333333336 + vertex -5.5 -0.6042921995806911 4.092768844753408 + vertex -5.5 -1.358499700900416 4.092592592592595 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900416 4.092592592592595 + vertex -5.5 -1.397388727486945 4.833333333333343 + vertex -5.5 -0.6415002990995834 4.833333333333336 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.352463658029166 18.27553066044528 + vertex -5.5 -1.475943977190465 18.93004070394194 + vertex -5.5 -0.7010437741381724 18.91509534780636 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.7010437741381724 18.91509534780636 + vertex -5.5 -0.6771292767630352 18.10913719125492 + vertex -5.5 -1.352463658029166 18.27553066044528 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.6415002990995808 7.796296296296282 + vertex -5.5 -0.6026112725130404 7.055555555555559 + vertex -5.5 -1.358499700900414 7.055555555555575 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900414 7.055555555555575 + vertex -5.5 -1.471699940180082 7.796296296296312 + vertex -5.5 -0.6415002990995808 7.796296296296282 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.6415002990995808 9.277777777777768 + vertex -5.5 -0.5283000598199152 8.537037037037035 + vertex -5.5 -1.358499700900414 8.537037037037063 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900414 8.537037037037063 + vertex -5.5 -1.395936673882247 9.277710514271241 + vertex -5.5 -0.6415002990995808 9.277777777777768 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.6415002990995839 6.314814814814811 + vertex -5.5 -0.5283000598199161 5.574074074074076 + vertex -5.5 -1.358499700900413 5.574074074074103 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900413 5.574074074074103 + vertex -5.5 -1.407849202246686 6.314814814814827 + vertex -5.5 -0.6415002990995839 6.314814814814811 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995855 14.46296296296293 + vertex -5.5 -0.646247029309835 13.66849120632406 + vertex -5.5 -1.358499700900419 13.72222222222224 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900419 13.72222222222224 + vertex -5.5 -1.363899056731139 14.4948538895986 + vertex -5.5 -0.6415002990995855 14.46296296296293 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.411278857545075 20.44870549987256 + vertex -5.5 -0.6148961408408751 20.34350506879419 + vertex -5.5 -1.326212453784984 19.64476269664324 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.5887211424549225 2.551294500127447 + vertex -5.5 -1.38510385915909 2.656494931205827 + vertex -5.5 -0.6737875462150147 3.355237303356752 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.7968723843076638 10.73319652055624 + vertex -5.5 -1.425693620269907 11.32000307309633 + vertex -5.5 -0.6707289679961359 11.52731299491258 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6759590785998856 16.00156412262479 + vertex -5.5 -1.458795146184429 16.51146837818554 + vertex -5.5 -0.6707289679961349 16.71249818009777 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6665534438680538 17.39315033203079 + vertex -5.5 -1.458795146184413 17.59964273292556 + vertex -5.5 -0.6771292767630352 18.10913719125492 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6665534438680526 12.2079651468456 + vertex -5.5 -1.458795146184407 12.41445754774038 + vertex -5.5 -0.6702448048819056 12.91664022555816 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.326212453784984 19.64476269664324 + vertex -5.5 -0.6148961408408751 20.34350506879419 + vertex -5.5 -0.5284304737528064 19.63993188190802 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6737875462150147 3.355237303356752 + vertex -5.5 -1.38510385915909 2.656494931205827 + vertex -5.5 -1.483478221254904 3.36160570617178 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.489211461299444 10.72451589785935 + vertex -5.5 -1.425693620269907 11.32000307309633 + vertex -5.5 -0.7968723843076638 10.73319652055624 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.352463658029169 15.83558045066583 + vertex -5.5 -1.458795146184429 16.51146837818554 + vertex -5.5 -0.6759590785998856 16.00156412262479 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6771292767630352 18.10913719125492 + vertex -5.5 -1.458795146184413 17.59964273292556 + vertex -5.5 -1.352463658029166 18.27553066044528 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6702448048819056 12.91664022555816 + vertex -5.5 -1.458795146184407 12.41445754774038 + vertex -5.5 -1.34943083905602 13.0903454752601 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 14.83333333333331 + vertex -5.5 -0.6415002990995855 14.46296296296293 + vertex -5.5 -0.6870385854396153 15.19803606554362 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 17.05555555555554 + vertex -5.5 -0.6707289679961349 16.71249818009777 + vertex -5.5 -0.6665534438680538 17.39315033203079 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 17.05555555555554 + vertex -5.5 -0.6665534438680538 17.39315033203079 + vertex -5.5 0 17.79629629629628 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 10.38888888888892 + vertex -5.5 -1.330608655261263 10.01722652108445 + vertex -5.5 -2 9.648148148148179 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 11.87037037037035 + vertex -5.5 -0.6707289679961359 11.52731299491258 + vertex -5.5 -0.6665534438680526 12.2079651468456 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 5.944444444444462 + vertex -5.5 -1.358499700900413 5.574074074074103 + vertex -5.5 -2 5.203703703703717 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 13.35185185185187 + vertex -5.5 -1.34943083905602 13.0903454752601 + vertex -5.5 -2 12.61111111111113 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 14.83333333333331 + vertex -5.5 -0.6870385854396153 15.19803606554362 + vertex -5.5 0 15.57407407407405 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 16.31481481481482 + vertex -5.5 -1.352463658029169 15.83558045066583 + vertex -5.5 -2 15.57407407407408 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 7.425925925925949 + vertex -5.5 -1.358499700900414 7.055555555555575 + vertex -5.5 -2 6.685185185185206 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 4.462962962962957 + vertex -5.5 -0.6415002990995834 4.833333333333336 + vertex -5.5 0 5.203703703703698 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 16.3148148148148 + vertex -5.5 -0.6707289679961349 16.71249818009777 + vertex -5.5 0 17.05555555555554 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 2.98148148148148 + vertex -5.5 -0.6737875462150147 3.355237303356752 + vertex -5.5 0 3.722222222222218 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 11.12962962962961 + vertex -5.5 -0.6707289679961359 11.52731299491258 + vertex -5.5 0 11.87037037037035 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 11.87037037037035 + vertex -5.5 -0.6665534438680526 12.2079651468456 + vertex -5.5 0 12.61111111111108 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 18.53703703703703 + vertex -5.5 -0.7010437741381724 18.91509534780636 + vertex -5.5 0 19.27777777777777 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 18.53703703703704 + vertex -5.5 -1.352463658029166 18.27553066044528 + vertex -5.5 -2 17.7962962962963 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 4.462962962962973 + vertex -5.5 -1.358499700900416 4.092592592592595 + vertex -5.5 -2 3.722222222222232 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 11.12962962962965 + vertex -5.5 -1.489211461299444 10.72451589785935 + vertex -5.5 -2 10.38888888888892 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 5.944444444444438 + vertex -5.5 -0.6415002990995839 6.314814814814811 + vertex -5.5 0 6.68518518518518 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -1.489211461299444 10.72451589785935 + vertex -5.5 -1.330608655261263 10.01722652108445 + vertex -5.5 -2 10.38888888888892 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 7.42592592592592 + vertex -5.5 -0.6415002990995808 7.796296296296282 + vertex -5.5 0 8.166666666666657 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 8.907407407407437 + vertex -5.5 -1.358499700900414 8.537037037037063 + vertex -5.5 -2 8.166666666666694 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 14.09259259259256 + vertex -5.5 -0.6415002990995855 14.46296296296293 + vertex -5.5 0 14.83333333333331 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 8.907407407407394 + vertex -5.5 -0.6415002990995808 9.277777777777768 + vertex -5.5 0 9.648148148148133 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 14.09259259259261 + vertex -5.5 -1.358499700900419 13.72222222222224 + vertex -5.5 -2 13.35185185185187 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -1.358499700900419 13.72222222222224 + vertex -5.5 -1.34943083905602 13.0903454752601 + vertex -5.5 -2 13.35185185185187 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 20.01851851851852 + vertex -5.5 -1.326212453784984 19.64476269664324 + vertex -5.5 -2 19.27777777777778 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6707289679961359 11.52731299491258 + vertex -5.5 -1.425693620269907 11.32000307309633 + vertex -5.5 -1.250974540846606 11.86927785057386 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.250974540846606 11.86927785057386 + vertex -5.5 -1.458795146184407 12.41445754774038 + vertex -5.5 -0.6665534438680526 12.2079651468456 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6707289679961349 16.71249818009777 + vertex -5.5 -1.458795146184429 16.51146837818554 + vertex -5.5 -1.250974540846606 17.05446303575905 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.250974540846606 17.05446303575905 + vertex -5.5 -1.458795146184413 17.59964273292556 + vertex -5.5 -0.6665534438680538 17.39315033203079 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900413 5.574074074074103 + vertex -5.5 -1.397388727486945 4.833333333333343 + vertex -5.5 -2 5.203703703703717 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 5.944444444444438 + vertex -5.5 -0.5283000598199161 5.574074074074076 + vertex -5.5 -0.6415002990995839 6.314814814814811 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 7.425925925925949 + vertex -5.5 -1.471699940180082 7.796296296296312 + vertex -5.5 -1.358499700900414 7.055555555555575 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.330608655261263 10.01722652108445 + vertex -5.5 -1.395936673882247 9.277710514271241 + vertex -5.5 -2 9.648148148148179 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995808 7.796296296296282 + vertex -5.5 -0.5283000598199152 8.537037037037035 + vertex -5.5 0 8.166666666666657 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 4.462962962962973 + vertex -5.5 -1.397388727486945 4.833333333333343 + vertex -5.5 -1.358499700900416 4.092592592592595 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6737875462150147 3.355237303356752 + vertex -5.5 -0.6042921995806911 4.092768844753408 + vertex -5.5 0 3.722222222222218 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 8.907407407407437 + vertex -5.5 -1.395936673882247 9.277710514271241 + vertex -5.5 -1.358499700900414 8.537037037037063 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6665534438680526 12.2079651468456 + vertex -5.5 -0.6702448048819056 12.91664022555816 + vertex -5.5 0 12.61111111111108 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900414 7.055555555555575 + vertex -5.5 -1.407849202246686 6.314814814814827 + vertex -5.5 -2 6.685185185185206 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995839 6.314814814814811 + vertex -5.5 -0.6026112725130404 7.055555555555559 + vertex -5.5 0 6.68518518518518 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.326212453784984 19.64476269664324 + vertex -5.5 -1.475943977190465 18.93004070394194 + vertex -5.5 -2 19.27777777777778 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.7010437741381724 18.91509534780636 + vertex -5.5 -0.5284304737528064 19.63993188190802 + vertex -5.5 0 19.27777777777777 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.352463658029169 15.83558045066583 + vertex -5.5 -1.480680260039985 15.18717556264309 + vertex -5.5 -2 15.57407407407408 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 4.462962962962957 + vertex -5.5 -0.6042921995806911 4.092768844753408 + vertex -5.5 -0.6415002990995834 4.833333333333336 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 8.907407407407394 + vertex -5.5 -0.5283000598199152 8.537037037037035 + vertex -5.5 -0.6415002990995808 9.277777777777768 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 18.53703703703704 + vertex -5.5 -1.475943977190465 18.93004070394194 + vertex -5.5 -1.352463658029166 18.27553066044528 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900414 8.537037037037063 + vertex -5.5 -1.471699940180082 7.796296296296312 + vertex -5.5 -2 8.166666666666694 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 16.3148148148148 + vertex -5.5 -0.6759590785998856 16.00156412262479 + vertex -5.5 -0.6707289679961349 16.71249818009777 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6665534438680538 17.39315033203079 + vertex -5.5 -0.6771292767630352 18.10913719125492 + vertex -5.5 0 17.79629629629628 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6870385854396153 15.19803606554362 + vertex -5.5 -0.6759590785998856 16.00156412262479 + vertex -5.5 0 15.57407407407405 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 18.53703703703703 + vertex -5.5 -0.6771292767630352 18.10913719125492 + vertex -5.5 -0.7010437741381724 18.91509534780636 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 14.09259259259256 + vertex -5.5 -0.646247029309835 13.66849120632406 + vertex -5.5 -0.6415002990995855 14.46296296296293 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 14.09259259259261 + vertex -5.5 -1.363899056731139 14.4948538895986 + vertex -5.5 -1.358499700900419 13.72222222222224 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.358499700900416 4.092592592592595 + vertex -5.5 -1.483478221254904 3.36160570617178 + vertex -5.5 -2 3.722222222222232 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 11.12962962962961 + vertex -5.5 -0.7968723843076638 10.73319652055624 + vertex -5.5 -0.6707289679961359 11.52731299491258 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995808 9.277777777777768 + vertex -5.5 -0.5905144024334588 10.01572721891267 + vertex -5.5 0 9.648148148148133 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 7.42592592592592 + vertex -5.5 -0.6026112725130404 7.055555555555559 + vertex -5.5 -0.6415002990995808 7.796296296296282 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 5.944444444444462 + vertex -5.5 -1.407849202246686 6.314814814814827 + vertex -5.5 -1.358499700900413 5.574074074074103 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6415002990995834 4.833333333333336 + vertex -5.5 -0.5283000598199161 5.574074074074076 + vertex -5.5 0 5.203703703703698 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -1.000000000000001 20.92264973081037 + vertex -5.5 -0.6148961408408751 20.34350506879419 + vertex -5.5 -1.411278857545075 20.44870549987256 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.000000000000001 2.077350269189626 + vertex -5.5 -1.38510385915909 2.656494931205827 + vertex -5.5 -0.5887211424549225 2.551294500127447 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 10.38888888888887 + vertex -5.5 -0.5905144024334588 10.01572721891267 + vertex -5.5 -0.7968723843076638 10.73319652055624 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 3.722222222222232 + vertex -5.5 -1.483478221254904 3.36160570617178 + vertex -5.5 -2 2.981481481481485 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 5.203703703703717 + vertex -5.5 -1.397388727486945 4.833333333333343 + vertex -5.5 -2 4.462962962962973 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 8.166666666666694 + vertex -5.5 -1.471699940180082 7.796296296296312 + vertex -5.5 -2 7.425925925925949 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 9.648148148148179 + vertex -5.5 -1.395936673882247 9.277710514271241 + vertex -5.5 -2 8.907407407407437 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6707289679961359 11.52731299491258 + vertex -5.5 -1.250974540846606 11.86927785057386 + vertex -5.5 -0.6665534438680526 12.2079651468456 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 19.27777777777777 + vertex -5.5 -0.5284304737528064 19.63993188190802 + vertex -5.5 0 20.01851851851852 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6707289679961349 16.71249818009777 + vertex -5.5 -1.250974540846606 17.05446303575905 + vertex -5.5 -0.6665534438680538 17.39315033203079 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 10.38888888888887 + vertex -5.5 -0.7968723843076638 10.73319652055624 + vertex -5.5 0 11.12962962962961 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 13.35185185185182 + vertex -5.5 -0.646247029309835 13.66849120632406 + vertex -5.5 0 14.09259259259256 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 17.79629629629628 + vertex -5.5 -0.6771292767630352 18.10913719125492 + vertex -5.5 0 18.53703703703703 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 14.83333333333334 + vertex -5.5 -1.480680260039985 15.18717556264309 + vertex -5.5 -1.363899056731139 14.4948538895986 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 13.35185185185182 + vertex -5.5 -0.6702448048819056 12.91664022555816 + vertex -5.5 -0.646247029309835 13.66849120632406 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 8.166666666666657 + vertex -5.5 -0.5283000598199152 8.537037037037035 + vertex -5.5 0 8.907407407407394 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 9.648148148148133 + vertex -5.5 -0.5905144024334588 10.01572721891267 + vertex -5.5 0 10.38888888888887 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 19.27777777777778 + vertex -5.5 -1.475943977190465 18.93004070394194 + vertex -5.5 -2 18.53703703703704 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 14.83333333333334 + vertex -5.5 -1.363899056731139 14.4948538895986 + vertex -5.5 -2 14.09259259259261 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 15.57407407407408 + vertex -5.5 -1.480680260039985 15.18717556264309 + vertex -5.5 -2 14.83333333333334 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 12.61111111111108 + vertex -5.5 -0.6702448048819056 12.91664022555816 + vertex -5.5 0 13.35185185185182 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 15.57407407407405 + vertex -5.5 -0.6759590785998856 16.00156412262479 + vertex -5.5 0 16.3148148148148 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 6.685185185185206 + vertex -5.5 -1.407849202246686 6.314814814814827 + vertex -5.5 -2 5.944444444444462 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 6.68518518518518 + vertex -5.5 -0.6026112725130404 7.055555555555559 + vertex -5.5 0 7.42592592592592 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 3.722222222222218 + vertex -5.5 -0.6042921995806911 4.092768844753408 + vertex -5.5 0 4.462962962962957 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 5.203703703703698 + vertex -5.5 -0.5283000598199161 5.574074074074076 + vertex -5.5 0 5.944444444444438 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 20.75925925925926 + vertex -5.5 -1.411278857545075 20.44870549987256 + vertex -5.5 -2 20.01851851851852 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 2.24074074074074 + vertex -5.5 -0.5887211424549225 2.551294500127447 + vertex -5.5 0 2.98148148148148 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 2.981481481481485 + vertex -5.5 -1.38510385915909 2.656494931205827 + vertex -5.5 -2 2.240740740740744 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 20.01851851851852 + vertex -5.5 -0.6148961408408751 20.34350506879419 + vertex -5.5 0 20.75925925925926 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.333333333333336 1.5 + vertex -5.5 -1.000000000000001 2.077350269189626 + vertex -5.5 -0.6666666666666667 1.5 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -0.6666666666666667 21.5 + vertex -5.5 -1.000000000000001 20.92264973081037 + vertex -5.5 -1.333333333333336 21.5 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 20.01851851851852 + vertex -5.5 -1.411278857545075 20.44870549987256 + vertex -5.5 -1.326212453784984 19.64476269664324 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 2.98148148148148 + vertex -5.5 -0.5887211424549225 2.551294500127447 + vertex -5.5 -0.6737875462150147 3.355237303356752 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -1.483478221254904 3.36160570617178 + vertex -5.5 -1.38510385915909 2.656494931205827 + vertex -5.5 -2 2.981481481481485 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.5284304737528064 19.63993188190802 + vertex -5.5 -0.6148961408408751 20.34350506879419 + vertex -5.5 0 20.01851851851852 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 12.61111111111113 + vertex -5.5 -1.458795146184407 12.41445754774038 + vertex -5.5 -2 11.87037037037039 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 17.7962962962963 + vertex -5.5 -1.458795146184413 17.59964273292556 + vertex -5.5 -2 17.05555555555556 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 11.87037037037039 + vertex -5.5 -1.425693620269907 11.32000307309633 + vertex -5.5 -2 11.12962962962965 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 17.05555555555556 + vertex -5.5 -1.458795146184429 16.51146837818554 + vertex -5.5 -2 16.31481481481482 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 11.87037037037039 + vertex -5.5 -1.458795146184407 12.41445754774038 + vertex -5.5 -1.250974540846606 11.86927785057386 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 17.05555555555556 + vertex -5.5 -1.458795146184413 17.59964273292556 + vertex -5.5 -1.250974540846606 17.05446303575905 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -1.250974540846606 11.86927785057386 + vertex -5.5 -1.425693620269907 11.32000307309633 + vertex -5.5 -2 11.87037037037039 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -1.250974540846606 17.05446303575905 + vertex -5.5 -1.458795146184429 16.51146837818554 + vertex -5.5 -2 17.05555555555556 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 1.5 + vertex -5.5 -0.473435449355429 1.99646227479024 + vertex -5.5 0 2.24074074074074 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 2.240740740740744 + vertex -5.5 -1.526564550644583 1.996462274790247 + vertex -5.5 -2 1.5 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 0 20.75925925925926 + vertex -5.5 -0.4734354493554129 21.00353772520976 + vertex -5.5 0 21.5 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 21.5 + vertex -5.5 -1.526564550644588 21.00353772520976 + vertex -5.5 -2 20.75925925925926 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 1.5 + vertex -5.5 -1.526564550644583 1.996462274790247 + vertex -5.5 -1.333333333333336 1.5 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6666666666666667 1.5 + vertex -5.5 -0.473435449355429 1.99646227479024 + vertex -5.5 0 1.5 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 21.5 + vertex -5.5 -0.4734354493554129 21.00353772520976 + vertex -5.5 -0.6666666666666667 21.5 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -1.333333333333336 21.5 + vertex -5.5 -1.526564550644588 21.00353772520976 + vertex -5.5 -2 21.5 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 20.75925925925926 + vertex -5.5 -1.526564550644588 21.00353772520976 + vertex -5.5 -1.411278857545075 20.44870549987256 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 0 2.24074074074074 + vertex -5.5 -0.473435449355429 1.99646227479024 + vertex -5.5 -0.5887211424549225 2.551294500127447 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.38510385915909 2.656494931205827 + vertex -5.5 -1.526564550644583 1.996462274790247 + vertex -5.5 -2 2.240740740740744 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -0.6148961408408751 20.34350506879419 + vertex -5.5 -0.4734354493554129 21.00353772520976 + vertex -5.5 0 20.75925925925926 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.411278857545075 20.44870549987256 + vertex -5.5 -1.526564550644588 21.00353772520976 + vertex -5.5 -1.000000000000001 20.92264973081037 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.5887211424549225 2.551294500127447 + vertex -5.5 -0.473435449355429 1.99646227479024 + vertex -5.5 -1.000000000000001 2.077350269189626 + endloop +endfacet +facet normal -1 -0 0 + outer loop + vertex -5.5 -1.000000000000001 2.077350269189626 + vertex -5.5 -1.526564550644583 1.996462274790247 + vertex -5.5 -1.38510385915909 2.656494931205827 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.000000000000001 20.92264973081037 + vertex -5.5 -0.4734354493554129 21.00353772520976 + vertex -5.5 -0.6148961408408751 20.34350506879419 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.34943083905602 13.0903454752601 + vertex -5.5 -1.458795146184407 12.41445754774038 + vertex -5.5 -2 12.61111111111113 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.352463658029166 18.27553066044528 + vertex -5.5 -1.458795146184413 17.59964273292556 + vertex -5.5 -2 17.7962962962963 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 16.31481481481482 + vertex -5.5 -1.458795146184429 16.51146837818554 + vertex -5.5 -1.352463658029169 15.83558045066583 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -2 11.12962962962965 + vertex -5.5 -1.425693620269907 11.32000307309633 + vertex -5.5 -1.489211461299444 10.72451589785935 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.000000000000001 20.92264973081037 + vertex -5.5 -1.526564550644588 21.00353772520976 + vertex -5.5 -1.333333333333336 21.5 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.333333333333336 1.5 + vertex -5.5 -1.526564550644583 1.996462274790247 + vertex -5.5 -1.000000000000001 2.077350269189626 + endloop +endfacet +facet normal -1 0 0 + outer loop + vertex -5.5 -1.000000000000001 2.077350269189626 + vertex -5.5 -0.473435449355429 1.99646227479024 + vertex -5.5 -0.6666666666666667 1.5 + endloop +endfacet +facet normal -1 0 -0 + outer loop + vertex -5.5 -0.6666666666666667 21.5 + vertex -5.5 -0.4734354493554129 21.00353772520976 + vertex -5.5 -1.000000000000001 20.92264973081037 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 5.5 -2 17.05555555555554 + vertex 4.655673760136614 -2 16.96466929801385 + vertex 4.744074395475103 -2 16.33170939209035 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 17.05555555555554 + vertex 4.744074395475103 -2 16.33170939209035 + vertex 5.5 -2 16.3148148148148 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.215348947555784 -2 12.57974608201392 + vertex 4.216054417227187 -2 13.35154556175128 + vertex 3.464668476437278 -2 12.62973158487211 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.216054417227187 -2 13.35154556175128 + vertex 3.485196779318045 -2 13.40279373126819 + vertex 3.464668476437278 -2 12.62973158487211 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.460916694941177 -2 3.018947459590255 + vertex 2.841901196153207 -2 2.644686495885514 + vertex 3.568127706497573 -2 2.217660997012953 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.206582833496469 -2 10.35562052434043 + vertex 4.077237994376535 -2 11.0510968086548 + vertex 3.465598520979608 -2 10.40825210954239 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.706195793300307 -2 6.262360537487246 + vertex 3.947182784469494 -2 6.247925982435459 + vertex 4.110486200275591 -2 5.661411558946233 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.077237994376535 -2 11.0510968086548 + vertex 3.389269686093905 -2 11.0434416288251 + vertex 3.465598520979608 -2 10.40825210954239 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.17389398326439 -2 8.848934738026195 + vertex 4.195814199447445 -2 9.590974077315817 + vertex 3.482481059799262 -2 9.029779793154106 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.532384274596081 -2 6.709175634538488 + vertex 4.211091610502407 -2 6.720319745154439 + vertex 4.085163247467821 -2 7.352501298640743 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.195814199447445 -2 9.590974077315817 + vertex 3.482519183485939 -2 9.698778212469655 + vertex 3.482481059799262 -2 9.029779793154106 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.085163247467821 -2 7.352501298640743 + vertex 3.36872271763415 -2 7.293849202134684 + vertex 3.532384274596081 -2 6.709175634538488 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.716472977865604 -2 20.13191285697176 + vertex -1.437299705222897 -2 20.87516284506514 + vertex -2.143283607768725 -2 20.83849238848145 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.112611094014032 -2 3.432801665914139 + vertex 4.837852652952281 -2 3.301747240107742 + vertex 4.858499700900417 -2 4.092592592592588 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.199305772116119 -2 15.33013572378729 + vertex 4.918821107332354 -2 15.78024179549353 + vertex 4.137906133270736 -2 15.9931810658391 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858499700900417 -2 4.092592592592588 + vertex 4.121197460527009 -2 4.162961800361108 + vertex 4.112611094014032 -2 3.432801665914139 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.726672676383709 -2 20.83844788109646 + vertex -4.405426047799934 -2 20.88547754159565 + vertex -4.163256974208401 -2 20.13493404822575 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.518478270762881 -2 14.20097805827304 + vertex 4.199825762598869 -2 14.66546628030377 + vertex 3.522482822207098 -2 14.91581723933913 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.942690586882144 -2 11.51273307229485 + vertex 3.562200465473438 -2 12.06310768263945 + vertex 2.880470240504621 -2 12.28961005685342 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.157032824947297 -2 2.876268055139592 + vertex -4.404546516961016 -2 2.116118090915069 + vertex -3.725708524847097 -2 2.163541749977668 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.518478270762881 -2 14.20097805827304 + vertex 3.485196779318045 -2 13.40279373126819 + vertex 4.212841511831785 -2 14.04539977235522 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858499700900416 -2 5.574074074074068 + vertex 4.706195793300307 -2 6.262360537487246 + vertex 4.110486200275591 -2 5.661411558946233 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.17389398326439 -2 8.848934738026195 + vertex 3.426996701041404 -2 8.351024862087794 + vertex 4.161330733573104 -2 8.122630508642821 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.212841511831785 -2 14.04539977235522 + vertex 3.485196779318045 -2 13.40279373126819 + vertex 4.216054417227187 -2 13.35154556175128 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.465598520979608 -2 10.40825210954239 + vertex 3.482519183485939 -2 9.698778212469655 + vertex 4.206582833496469 -2 10.35562052434043 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.206582833496469 -2 10.35562052434043 + vertex 3.482519183485939 -2 9.698778212469655 + vertex 4.195814199447445 -2 9.590974077315817 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.837852652952281 -2 3.301747240107742 + vertex 4.162755411472946 -2 2.759371800359368 + vertex 4.874071970659501 -2 2.574806147906303 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.121197460527009 -2 4.162961800361108 + vertex 4.787889134207287 -2 4.821432434524037 + vertex 4.076553335617876 -2 4.914212848582235 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.870582047868353 -2 15.09106547965763 + vertex 4.918821107332354 -2 15.78024179549353 + vertex 4.199305772116119 -2 15.33013572378729 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858499700900417 -2 4.092592592592588 + vertex 4.787889134207287 -2 4.821432434524037 + vertex 4.121197460527009 -2 4.162961800361108 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.212841511831785 -2 14.04539977235522 + vertex 4.199825762598869 -2 14.66546628030377 + vertex 3.518478270762881 -2 14.20097805827304 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.112611094014032 -2 3.432801665914139 + vertex 4.162755411472946 -2 2.759371800359368 + vertex 4.837852652952281 -2 3.301747240107742 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.653422321959101 -2 11.49668106748853 + vertex 3.562200465473438 -2 12.06310768263945 + vertex 2.942690586882144 -2 11.51273307229485 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.163256974208401 -2 20.13493404822575 + vertex -3.469012145433474 -2 20.27171639072729 + vertex -3.726672676383709 -2 20.83844788109646 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.482481059799262 -2 9.029779793154106 + vertex 3.426996701041404 -2 8.351024862087794 + vertex 4.17389398326439 -2 8.848934738026195 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.143283607768725 -2 20.83849238848145 + vertex -2.407514177605579 -2 20.2710850041902 + vertex -1.716472977865604 -2 20.13191285697176 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.562175811593016 -2 20.80826400883117 + vertex 2.842012940993464 -2 20.40449675698339 + vertex 3.450126181270477 -2 20.02186022077733 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.725708524847097 -2 2.163541749977668 + vertex -3.472825915922042 -2 2.745571680351766 + vertex -4.157032824947297 -2 2.876268055139592 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.0208654791378333 -2 20.83956576945508 + vertex -0.6699669427066424 -2 20.89718328590129 + vertex -0.3517984009234065 -2 20.14117242918954 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.0208654791378333 -2 20.83956576945508 + vertex 0.8138538323647302 -2 20.78809710159216 + vertex 0.3666666666666538 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.841901196153207 -2 2.644686495885514 + vertex 2.894573521270469 -2 2.005347401248558 + vertex 3.568127706497573 -2 2.217660997012953 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.3666666666666831 -2 1.5 + vertex 0.8127467008934494 -2 2.207667147874593 + vertex 0.003832493913557831 -2 2.100914919519724 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 3.562175811593016 -2 20.80826400883117 + vertex 2.933333333333329 -2 21.01692359780342 + vertex 2.842012940993464 -2 20.40449675698339 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.100000000000015 -2 1.5 + vertex 0.8127467008934494 -2 2.207667147874593 + vertex 0.3666666666666831 -2 1.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.211091610502407 -2 6.720319745154439 + vertex 3.947182784469494 -2 6.247925982435459 + vertex 4.706195793300307 -2 6.262360537487246 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.3666666666666538 -2 21.5 + vertex 0.8138538323647302 -2 20.78809710159216 + vertex 1.09999999999999 -2 21.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.184539364180798 -2 3.019234986705463 + vertex 1.528722449664777 -2 2.638884480328281 + vertex 2.19617203703488 -2 2.164389513344334 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.19617203703488 -2 2.164389513344334 + vertex 2.841901196153207 -2 2.644686495885514 + vertex 2.184539364180798 -2 3.019234986705463 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3517984009234065 -2 20.14117242918954 + vertex -0.6699669427066424 -2 20.89718328590129 + vertex -1.028753845297412 -2 20.34124811214607 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3517984009234065 -2 20.14117242918954 + vertex 0.3310048212655636 -2 20.28022422492675 + vertex 0.0208654791378333 -2 20.83956576945508 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.191479158001644 -2 20.84385449502374 + vertex 1.528258704114727 -2 20.38121451545302 + vertex 2.176315255311612 -2 20.03980165486242 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.934242593271455 -2 2.25495040931872 + vertex -2.348118176010836 -2 2.75223995238126 + vertex -2.927963870571831 -2 3.030785662201998 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.927963870571831 -2 3.030785662201998 + vertex -3.472825915922042 -2 2.745571680351766 + vertex -2.934242593271455 -2 2.25495040931872 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.568127706497573 -2 2.217660997012953 + vertex 4.162755411472946 -2 2.759371800359368 + vertex 3.460916694941177 -2 3.018947459590255 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.0208654791378333 -2 20.83956576945508 + vertex 0.3310048212655636 -2 20.28022422492675 + vertex 0.8138538323647302 -2 20.78809710159216 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.028753845297412 -2 20.34124811214607 + vertex -1.437299705222897 -2 20.87516284506514 + vertex -1.716472977865604 -2 20.13191285697176 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.176315255311612 -2 20.03980165486242 + vertex 2.842012940993464 -2 20.40449675698339 + vertex 2.191479158001644 -2 20.84385449502374 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.163256974208401 -2 20.13493404822575 + vertex -4.405426047799934 -2 20.88547754159565 + vertex -4.879793185278873 -2 20.38464438613695 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.437299705222897 -2 20.87516284506514 + vertex -0.6699669427066424 -2 20.89718328590129 + vertex -1.100000000000015 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.528722449664777 -2 2.638884480328281 + vertex 1.543851635481636 -2 3.385237964523963 + vertex 0.9112001278467288 -2 3.017183334678748 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.8795934270297 -2 2.615567192513602 + vertex -4.404546516961016 -2 2.116118090915069 + vertex -4.157032824947297 -2 2.876268055139592 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936485214511291 -2 20.74314212984447 + vertex -3.469012145433474 -2 20.27171639072729 + vertex -2.93912235862163 -2 19.99464574380434 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.93912235862163 -2 19.99464574380434 + vertex -2.407514177605579 -2 20.2710850041902 + vertex -2.936485214511291 -2 20.74314212984447 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.184539364180798 -2 3.019234986705463 + vertex 1.543851635481636 -2 3.385237964523963 + vertex 1.528722449664777 -2 2.638884480328281 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.8127467008934494 -2 2.207667147874593 + vertex 0.2348591938782687 -2 2.715163559101713 + vertex 0.003832493913557831 -2 2.100914919519724 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.110486200275591 -2 5.661411558946233 + vertex 3.448492090142694 -2 5.250232971015224 + vertex 4.076553335617876 -2 4.914212848582235 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.9112001278467288 -2 3.017183334678748 + vertex 0.8127467008934494 -2 2.207667147874593 + vertex 1.528722449664777 -2 2.638884480328281 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.450126181270477 -2 20.02186022077733 + vertex 4.041626538302982 -2 20.31140730480241 + vertex 3.562175811593016 -2 20.80826400883117 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.167576414659461 -2 2.088616667700339 + vertex -2.348118176010836 -2 2.75223995238126 + vertex -2.934242593271455 -2 2.25495040931872 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.853983791777436 -2 17.46298864682942 + vertex 4.655673760136614 -2 16.96466929801385 + vertex 5.5 -2 17.05555555555554 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.028753845297412 -2 20.34124811214607 + vertex -0.6699669427066424 -2 20.89718328590129 + vertex -1.437299705222897 -2 20.87516284506514 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.137906133270736 -2 15.9931810658391 + vertex 4.918821107332354 -2 15.78024179549353 + vertex 4.744074395475103 -2 16.33170939209035 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.576676627398162 -2 7.779376729527785 + vertex 3.36872271763415 -2 7.293849202134684 + vertex 4.085163247467821 -2 7.352501298640743 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.210490532425202 -2 3.738913142095867 + vertex -4.157032824947297 -2 2.876268055139592 + vertex -3.557504597528008 -2 3.394518219884866 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.856684746805584 -2 3.356652359229182 + vertex -4.157032824947297 -2 2.876268055139592 + vertex -4.210490532425202 -2 3.738913142095867 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.522482822207098 -2 14.91581723933913 + vertex 4.199825762598869 -2 14.66546628030377 + vertex 4.199305772116119 -2 15.33013572378729 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.653422321959101 -2 11.49668106748853 + vertex 3.389269686093905 -2 11.0434416288251 + vertex 4.077237994376535 -2 11.0510968086548 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.812532127091464 -2 19.65217639478334 + vertex 2.842012940993464 -2 20.40449675698339 + vertex 2.176315255311612 -2 20.03980165486242 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 3.450126181270477 -2 20.02186022077733 + vertex 2.842012940993464 -2 20.40449675698339 + vertex 2.812532127091464 -2 19.65217639478334 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.880470240504621 -2 12.28961005685342 + vertex 3.562200465473438 -2 12.06310768263945 + vertex 3.464668476437278 -2 12.62973158487211 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.161330733573104 -2 8.122630508642821 + vertex 3.426996701041404 -2 8.351024862087794 + vertex 3.576676627398162 -2 7.779376729527785 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.934242593271455 -2 2.25495040931872 + vertex -3.472825915922042 -2 2.745571680351766 + vertex -3.725708524847097 -2 2.163541749977668 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.855053374775501 -2 4.84131556842358 + vertex -4.851864159626067 -2 5.586500667836441 + vertex -5.5 -2 5.203703703703717 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.209009251719478 -2 5.223245738263447 + vertex -4.851864159626067 -2 5.586500667836441 + vertex -4.855053374775501 -2 4.84131556842358 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.210490532425202 -2 3.738913142095867 + vertex -4.854580471963713 -2 4.101585275261201 + vertex -4.856684746805584 -2 3.356652359229182 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.726672676383709 -2 20.83844788109646 + vertex -3.469012145433474 -2 20.27171639072729 + vertex -2.936485214511291 -2 20.74314212984447 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.191479158001644 -2 20.84385449502374 + vertex 1.480298472225957 -2 21.00228949787716 + vertex 1.528258704114727 -2 20.38121451545302 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.854580471963713 -2 4.101585275261201 + vertex -4.208972798762589 -2 4.482363263387334 + vertex -4.855053374775501 -2 4.84131556842358 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.210490532425202 -2 3.738913142095867 + vertex -4.208972798762589 -2 4.482363263387334 + vertex -4.854580471963713 -2 4.101585275261201 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 5.944444444444462 + vertex -4.854100442035756 -2 6.32387803528496 + vertex -5.5 -2 6.685185185185206 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.112611094014032 -2 3.432801665914139 + vertex 4.121197460527009 -2 4.162961800361108 + vertex 3.463331557016295 -2 3.757543544245052 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.463331557016295 -2 3.757543544245052 + vertex 4.121197460527009 -2 4.162961800361108 + vertex 3.462425096906818 -2 4.496226693199438 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.836742182517218 -2 13.00553687726588 + vertex 3.485196779318045 -2 13.40279373126819 + vertex 2.82287889280243 -2 13.74009365728223 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.302206729260642 -2 19.647231901849 + vertex -1.668074116135068 -2 19.3012169147081 + vertex -1.716472977865604 -2 20.13191285697176 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82679663843258 -2 9.297354238277073 + vertex 3.482519183485939 -2 9.698778212469655 + vertex 2.826562603555422 -2 10.03778041601883 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 5.203703703703717 + vertex -4.851864159626067 -2 5.586500667836441 + vertex -5.5 -2 5.944444444444462 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.855053374775501 -2 4.84131556842358 + vertex -4.208972798762589 -2 4.482363263387334 + vertex -4.209009251719478 -2 5.223245738263447 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936485214511291 -2 20.74314212984447 + vertex -2.407514177605579 -2 20.2710850041902 + vertex -2.143283607768725 -2 20.83849238848145 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3673592852575696 -2 3.754963435869593 + vertex -1.016136515624617 -2 3.403823044063341 + vertex -0.3680149090001792 -2 3.06536071564342 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.212127115652919 -2 7.441346717776255 + vertex -4.857776399823164 -2 7.800662819528365 + vertex -4.854290590709602 -2 7.063614504077036 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.299852627534937 -2 18.90894251101097 + vertex -1.668074116135068 -2 19.3012169147081 + vertex -2.302206729260642 -2 19.647231901849 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -0.3673592852575696 -2 3.754963435869593 + vertex -1.011373743608711 -2 4.126304381733572 + vertex -1.016136515624617 -2 3.403823044063341 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.010978521253866 -2 4.86052685404085 + vertex -1.011373743608711 -2 4.126304381733572 + vertex -0.3706777379366633 -2 4.49175823877602 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.19617203703488 -2 2.164389513344334 + vertex 2.894573521270469 -2 2.005347401248558 + vertex 2.841901196153207 -2 2.644686495885514 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.213339441084396 -2 8.923744763240448 + vertex -4.211133059312831 -2 9.664172439558234 + vertex -4.859025766115733 -2 9.280652951284694 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.859025766115733 -2 9.280652951284694 + vertex -4.211133059312831 -2 9.664172439558234 + vertex -4.858499700900419 -2 10.01851851851855 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -0.3706777379366633 -2 4.49175823877602 + vertex -1.011373743608711 -2 4.126304381733572 + vertex -0.3673592852575696 -2 3.754963435869593 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.21512821818804 -2 11.14017985693962 + vertex -4.212099464206894 -2 11.88583119197091 + vertex -4.857371180699295 -2 11.50433517481844 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.854290590709602 -2 7.063614504077036 + vertex -4.210009374814977 -2 6.700367524307542 + vertex -4.212127115652919 -2 7.441346717776255 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.857371180699295 -2 11.50433517481844 + vertex -4.212099464206894 -2 11.88583119197091 + vertex -4.858499700900419 -2 12.24074074074076 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.692097972637046 -2 3.077348409045236 + vertex -1.74883458901402 -2 2.529533409221695 + vertex -1.078142303503325 -2 2.674263965434937 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.016136515624617 -2 3.403823044063341 + vertex -1.078142303503325 -2 2.674263965434937 + vertex -0.3680149090001792 -2 3.06536071564342 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858262682337108 -2 8.538487430234987 + vertex -4.211295871605629 -2 8.181800934136941 + vertex -4.213339441084396 -2 8.923744763240448 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.692097972637046 -2 3.077348409045236 + vertex -1.078142303503325 -2 2.674263965434937 + vertex -1.016136515624617 -2 3.403823044063341 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.216057034610309 -2 13.36202290232499 + vertex -4.215605853511458 -2 14.10321060824816 + vertex -4.857691379326242 -2 13.72637819811415 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.857691379326242 -2 13.72637819811415 + vertex -4.215605853511458 -2 14.10321060824816 + vertex -4.858499700900419 -2 14.46296296296297 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.121197460527009 -2 4.162961800361108 + vertex 4.076553335617876 -2 4.914212848582235 + vertex 3.462425096906818 -2 4.496226693199438 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.211133059312831 -2 9.664172439558234 + vertex -4.213919187107948 -2 10.40043495237732 + vertex -4.858499700900419 -2 10.01851851851855 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 10.01851851851855 + vertex -4.213919187107948 -2 10.40043495237732 + vertex -4.858499700900418 -2 10.75925925925928 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82287889280243 -2 13.74009365728223 + vertex 3.485196779318045 -2 13.40279373126819 + vertex 3.518478270762881 -2 14.20097805827304 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.464668476437278 -2 12.62973158487211 + vertex 3.485196779318045 -2 13.40279373126819 + vertex 2.836742182517218 -2 13.00553687726588 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.213339441084396 -2 8.923744763240448 + vertex -4.859025766115733 -2 9.280652951284694 + vertex -4.858262682337108 -2 8.538487430234987 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.461038152320298 -2 17.80933948973989 + vertex 2.81837767774294 -2 17.43790224669241 + vertex 3.459242902665586 -2 17.0664914438087 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.212127115652919 -2 7.441346717776255 + vertex -4.211295871605629 -2 8.181800934136941 + vertex -4.857776399823164 -2 7.800662819528365 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.857776399823164 -2 7.800662819528365 + vertex -4.211295871605629 -2 8.181800934136941 + vertex -4.858262682337108 -2 8.538487430234987 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.482481059799262 -2 9.029779793154106 + vertex 3.482519183485939 -2 9.698778212469655 + vertex 2.82679663843258 -2 9.297354238277073 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.816046427378849 -2 18.17726903057125 + vertex 2.81837767774294 -2 17.43790224669241 + vertex 3.461038152320298 -2 17.80933948973989 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858921784583877 -2 17.42644889903684 + vertex -4.217241391147802 -2 17.06005415907445 + vertex -4.218284649586943 -2 17.79834270098642 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.826562603555422 -2 10.03778041601883 + vertex 3.482519183485939 -2 9.698778212469655 + vertex 3.465598520979608 -2 10.40825210954239 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.212099464206894 -2 11.88583119197091 + vertex -4.215677787774949 -2 12.62062645531099 + vertex -4.858499700900419 -2 12.24074074074076 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 12.24074074074076 + vertex -4.215677787774949 -2 12.62062645531099 + vertex -4.858499700900418 -2 12.9814814814815 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.660634787301892 -2 18.54075855300827 + vertex -1.019622954582061 -2 18.17249424625552 + vertex -1.016913363682256 -2 18.91113701755697 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.217241391147802 -2 17.06005415907445 + vertex -3.577418856687067 -2 17.43210191226107 + vertex -4.218284649586943 -2 17.79834270098642 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.216933704909376 -2 15.58411418009348 + vertex -4.860656951472551 -2 15.94818091204004 + vertex -4.858499700900418 -2 15.20370370370371 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.896712455689519 -2 19.28037270279553 + vertex 1.536645401435883 -2 19.65049039780268 + vertex 0.9055373745915964 -2 19.99946401750414 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 14.46296296296297 + vertex -4.216481903738938 -2 14.84237989301814 + vertex -4.858499700900418 -2 15.20370370370371 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.851864159626067 -2 5.586500667836441 + vertex -4.854100442035756 -2 6.32387803528496 + vertex -5.5 -2 5.944444444444462 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900418 -2 10.75925925925928 + vertex -4.213919187107948 -2 10.40043495237732 + vertex -4.21512821818804 -2 11.14017985693962 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.21512821818804 -2 11.14017985693962 + vertex -4.857371180699295 -2 11.50433517481844 + vertex -4.858499700900418 -2 10.75925925925928 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 14.46296296296297 + vertex -4.215605853511458 -2 14.10321060824816 + vertex -4.216481903738938 -2 14.84237989301814 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.016913363682256 -2 18.91113701755697 + vertex -1.668074116135068 -2 19.3012169147081 + vertex -1.660634787301892 -2 18.54075855300827 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3706777379366633 -2 4.49175823877602 + vertex -0.3714376792019939 -2 5.229676695716471 + vertex -1.010978521253866 -2 4.86052685404085 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.176315255311612 -2 20.03980165486242 + vertex 1.528258704114727 -2 20.38121451545302 + vertex 1.536645401435883 -2 19.65049039780268 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.819802103800889 -2 16.69942089983242 + vertex 2.179344469681174 -2 16.32918499547299 + vertex 2.821179313344073 -2 15.9603879965617 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.660634787301892 -2 18.54075855300827 + vertex -1.668074116135068 -2 19.3012169147081 + vertex -2.299852627534937 -2 18.90894251101097 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.177872523023615 -2 17.06825030927862 + vertex 2.179344469681174 -2 16.32918499547299 + vertex 2.819802103800889 -2 16.69942089983242 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3751518171424401 -2 11.14736947415786 + vertex 0.2646862774917507 -2 10.77704715318259 + vertex 0.2641422182702875 -2 11.51762814211468 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.218284649586943 -2 17.79834270098642 + vertex -4.859141812786931 -2 18.16743965320988 + vertex -4.858921784583877 -2 17.42644889903684 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.862637361884998 -2 19.64719714547201 + vertex -4.163256974208401 -2 20.13493404822575 + vertex -4.879793185278873 -2 20.38464438613695 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.536645401435883 -2 19.65049039780268 + vertex 1.528258704114727 -2 20.38121451545302 + vertex 0.9055373745915964 -2 19.99946401750414 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.933219101096931 -2 11.14588787169219 + vertex -2.293288036902054 -2 10.77608571143553 + vertex -2.293774322911373 -2 11.51846628468102 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.896712455689519 -2 19.28037270279553 + vertex 1.535793096979505 -2 18.91306988439083 + vertex 1.536645401435883 -2 19.65049039780268 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.010978521253866 -2 4.86052685404085 + vertex -1.650598693335845 -2 4.491615851896663 + vertex -1.011373743608711 -2 4.126304381733572 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.216057034610309 -2 13.36202290232499 + vertex -4.857691379326242 -2 13.72637819811415 + vertex -4.858499700900418 -2 12.9814814814815 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900418 -2 12.9814814814815 + vertex -4.215677787774949 -2 12.62062645531099 + vertex -4.216057034610309 -2 13.36202290232499 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 20.01851851851852 + vertex -4.862637361884998 -2 19.64719714547201 + vertex -4.879793185278873 -2 20.38464438613695 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900418 -2 15.20370370370371 + vertex -4.860656951472551 -2 15.94818091204004 + vertex -5.5 -2 15.57407407407408 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.019622954582061 -2 18.17249424625552 + vertex -0.3796622136127862 -2 18.54169448313185 + vertex -1.016913363682256 -2 18.91113701755697 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.461038152320298 -2 17.80933948973989 + vertex 4.100793025011158 -2 18.17905243801717 + vertex 3.453012982194295 -2 18.54804954286075 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 2.98148148148148 + vertex 4.837852652952281 -2 3.301747240107742 + vertex 4.874071970659501 -2 2.574806147906303 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858499700900416 -2 20.38888888888889 + vertex 4.858733561059807 -2 19.64774309047021 + vertex 5.5 -2 20.01851851851852 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3808217490844628 -2 17.80411876256203 + vertex -0.3796622136127862 -2 18.54169448313185 + vertex -1.019622954582061 -2 18.17249424625552 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.94001939355516 -2 19.27790681089119 + vertex -2.93912235862163 -2 19.99464574380434 + vertex -3.57952350344234 -2 19.64741215066542 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9112001278467288 -2 3.017183334678748 + vertex 1.543851635481636 -2 3.385237964523963 + vertex 0.9081003544979743 -2 3.755848508110088 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.94001939355516 -2 19.27790681089119 + vertex -3.57952350344234 -2 19.64741215066542 + vertex -3.579065017001963 -2 18.90863581015581 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.453012982194295 -2 18.54804954286075 + vertex 4.100793025011158 -2 18.17905243801717 + vertex 4.090847999373175 -2 18.91688194045436 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.8795934270297 -2 2.615567192513602 + vertex -4.157032824947297 -2 2.876268055139592 + vertex -4.856684746805584 -2 3.356652359229182 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.94001939355516 -2 19.27790681089119 + vertex -2.299852627534937 -2 18.90894251101097 + vertex -2.302206729260642 -2 19.647231901849 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.856684746805584 -2 3.356652359229182 + vertex -4.854580471963713 -2 4.101585275261201 + vertex -5.5 -2 3.722222222222232 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.716472977865604 -2 20.13191285697176 + vertex -1.668074116135068 -2 19.3012169147081 + vertex -1.012364211165075 -2 19.66731864785164 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.650478580992964 -2 5.228725669162287 + vertex -1.650598693335845 -2 4.491615851896663 + vertex -1.010978521253866 -2 4.86052685404085 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9081003544979743 -2 3.755848508110088 + vertex 1.543851635481636 -2 3.385237964523963 + vertex 1.546076671149374 -2 4.124348986542191 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 2.981481481481485 + vertex -4.8795934270297 -2 2.615567192513602 + vertex -4.856684746805584 -2 3.356652359229182 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.365583445851182 -2 20.88478511069381 + vertex 4.041626538302982 -2 20.31140730480241 + vertex 4.858499700900416 -2 20.38888888888889 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3714376792019939 -2 5.229676695716471 + vertex 0.2683114217292001 -2 4.861199062825149 + vertex 0.2675336108434639 -2 5.598911732970858 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 3.459242902665586 -2 17.0664914438087 + vertex 2.81837767774294 -2 17.43790224669241 + vertex 2.819802103800889 -2 16.69942089983242 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.174596731070372 -2 19.28256664957802 + vertex 1.535793096979505 -2 18.91306988439083 + vertex 2.175300563759365 -2 18.54488978749554 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858921784583877 -2 17.42644889903684 + vertex -4.859141812786931 -2 18.16743965320988 + vertex -5.5 -2 17.7962962962963 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.93909773043681 -2 18.53984166838779 + vertex -2.299852627534937 -2 18.90894251101097 + vertex -2.94001939355516 -2 19.27790681089119 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900418 -2 15.20370370370371 + vertex -4.216481903738938 -2 14.84237989301814 + vertex -4.216933704909376 -2 15.58411418009348 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.528258704114727 -2 20.38121451545302 + vertex 0.8138538323647302 -2 20.78809710159216 + vertex 0.9055373745915964 -2 19.99946401750414 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.854290590709602 -2 7.063614504077036 + vertex -4.857776399823164 -2 7.800662819528365 + vertex -5.5 -2 7.425925925925949 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.175300563759365 -2 18.54488978749554 + vertex 1.535793096979505 -2 18.91306988439083 + vertex 1.536525565386907 -2 18.17497431780669 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.219405200955131 -2 19.27773497154104 + vertex -4.163256974208401 -2 20.13493404822575 + vertex -4.862637361884998 -2 19.64719714547201 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3706777379366633 -2 4.49175823877602 + vertex 0.2683114217292001 -2 4.861199062825149 + vertex -0.3714376792019939 -2 5.229676695716471 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.011374699255595 -2 5.598251001051494 + vertex -0.3714376792019939 -2 5.229676695716471 + vertex -0.3722523798284423 -2 5.967729299340974 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.012364211165075 -2 19.66731864785164 + vertex -1.668074116135068 -2 19.3012169147081 + vertex -1.016913363682256 -2 18.91113701755697 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.85904341510472 -2 18.90779394030641 + vertex -4.219405200955131 -2 19.27773497154104 + vertex -4.862637361884998 -2 19.64719714547201 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.926829710656151 -2 3.751805738528547 + vertex -2.927963870571831 -2 3.030785662201998 + vertex -2.298332905758358 -2 3.40159593333896 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.461038152320298 -2 17.80933948973989 + vertex 3.453012982194295 -2 18.54804954286075 + vertex 2.816046427378849 -2 18.17726903057125 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.219405200955131 -2 19.27773497154104 + vertex -3.57952350344234 -2 19.64741215066542 + vertex -4.163256974208401 -2 20.13493404822575 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 4.462962962962957 + vertex 4.787889134207287 -2 4.821432434524037 + vertex 4.858499700900417 -2 4.092592592592588 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.880508352128135 -2 18.90845629198527 + vertex 4.881498999364475 -2 18.16944240249155 + vertex 5.5 -2 18.53703703703703 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.010978521253866 -2 4.86052685404085 + vertex -0.3714376792019939 -2 5.229676695716471 + vertex -1.011374699255595 -2 5.598251001051494 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822557155252714 -2 3.387632755075639 + vertex 2.841901196153207 -2 2.644686495885514 + vertex 3.460916694941177 -2 3.018947459590255 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.579065017001963 -2 18.90863581015581 + vertex -3.57952350344234 -2 19.64741215066542 + vertex -4.219405200955131 -2 19.27773497154104 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.659883570574173 -2 17.80266468206202 + vertex -1.019622954582061 -2 18.17249424625552 + vertex -1.660634787301892 -2 18.54075855300827 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.536525565386907 -2 18.17497431780669 + vertex 1.535793096979505 -2 18.91306988439083 + vertex 0.8971018465118702 -2 18.54311123645736 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 20.01851851851852 + vertex -4.879793185278873 -2 20.38464438613695 + vertex -5.5 -2 20.75925925925926 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 2.98148148148148 + vertex 4.874071970659501 -2 2.574806147906303 + vertex 5.5 -2 2.24074074074074 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 20.75925925925926 + vertex 4.858499700900416 -2 20.38888888888889 + vertex 5.5 -2 20.01851851851852 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.860656951472551 -2 15.94818091204004 + vertex -4.217715539572408 -2 16.32123053081938 + vertex -4.858499700900416 -2 16.68518518518519 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.812532127091464 -2 19.65217639478334 + vertex 2.176315255311612 -2 20.03980165486242 + vertex 2.174596731070372 -2 19.28256664957802 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3722523798284423 -2 5.967729299340974 + vertex -0.3714376792019939 -2 5.229676695716471 + vertex 0.2675336108434639 -2 5.598911732970858 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.85904341510472 -2 18.90779394030641 + vertex -4.862637361884998 -2 19.64719714547201 + vertex -5.5 -2 19.27777777777778 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.926829710656151 -2 3.751805738528547 + vertex -2.298332905758358 -2 3.40159593333896 + vertex -2.288701402339894 -2 4.121267389307008 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.94001939355516 -2 19.27790681089119 + vertex -2.302206729260642 -2 19.647231901849 + vertex -2.93912235862163 -2 19.99464574380434 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.184470845550166 -2 3.755927490778999 + vertex 2.184539364180798 -2 3.019234986705463 + vertex 2.822557155252714 -2 3.387632755075639 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.536645401435883 -2 19.65049039780268 + vertex 1.535793096979505 -2 18.91306988439083 + vertex 2.174596731070372 -2 19.28256664957802 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858499700900417 -2 4.092592592592588 + vertex 4.837852652952281 -2 3.301747240107742 + vertex 5.5 -2 3.722222222222218 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 19.27777777777777 + vertex 4.858733561059807 -2 19.64774309047021 + vertex 4.880508352128135 -2 18.90845629198527 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.813820309881157 -2 18.91498790393246 + vertex 2.174596731070372 -2 19.28256664957802 + vertex 2.175300563759365 -2 18.54488978749554 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8971018465118702 -2 18.54311123645736 + vertex 1.535793096979505 -2 18.91306988439083 + vertex 0.896712455689519 -2 19.28037270279553 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 2.240740740740744 + vertex -4.8795934270297 -2 2.615567192513602 + vertex -5.5 -2 2.981481481481485 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.557504597528008 -2 3.394518219884866 + vertex -2.927963870571831 -2 3.030785662201998 + vertex -2.926829710656151 -2 3.751805738528547 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.813820309881157 -2 18.91498790393246 + vertex 2.812532127091464 -2 19.65217639478334 + vertex 2.174596731070372 -2 19.28256664957802 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.896712455689519 -2 19.28037270279553 + vertex 0.2665658211570644 -2 19.63282180689279 + vertex 0.2582962276091168 -2 18.91107228975501 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.896712455689519 -2 19.28037270279553 + vertex 0.9055373745915964 -2 19.99946401750414 + vertex 0.2665658211570644 -2 19.63282180689279 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858284764645067 -2 11.499944635773 + vertex 4.216602219501706 -2 11.87014423231384 + vertex 4.077237994376535 -2 11.0510968086548 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858351974257875 -2 13.72219595896676 + vertex 4.212841511831785 -2 14.04539977235522 + vertex 4.216054417227187 -2 13.35154556175128 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.821179313344073 -2 15.9603879965617 + vertex 2.179344469681174 -2 16.32918499547299 + vertex 2.180386143728376 -2 15.58998824863726 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8971018465118702 -2 18.54311123645736 + vertex 0.896712455689519 -2 19.28037270279553 + vertex 0.2582962276091168 -2 18.91107228975501 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.8971018465118702 -2 18.54311123645736 + vertex 0.2582962276091168 -2 18.91107228975501 + vertex 0.2586041205171401 -2 18.17353338690858 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.184539364180798 -2 3.019234986705463 + vertex 2.841901196153207 -2 2.644686495885514 + vertex 2.822557155252714 -2 3.387632755075639 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.93909773043681 -2 18.53984166838779 + vertex -2.94001939355516 -2 19.27790681089119 + vertex -3.579065017001963 -2 18.90863581015581 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 13.35185185185182 + vertex 4.857984469430814 -2 12.97618307852928 + vertex 5.5 -2 12.61111111111108 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9075480807427621 -2 4.492742427723907 + vertex 0.9081003544979743 -2 3.755848508110088 + vertex 1.546076671149374 -2 4.124348986542191 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858094016112133 -2 10.01830399001033 + vertex 4.206582833496469 -2 10.35562052434043 + vertex 4.195814199447445 -2 9.590974077315817 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.012076034282102 -2 6.33670297379202 + vertex -0.3722523798284423 -2 5.967729299340974 + vertex -0.3726607962426137 -2 6.706414694889876 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.927736629004366 -2 4.48943194994477 + vertex -2.288701402339894 -2 4.121267389307008 + vertex -2.289306234888224 -2 4.859074588876906 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.298332905758358 -2 3.40159593333896 + vertex -1.692097972637046 -2 3.077348409045236 + vertex -1.65230458775249 -2 3.756097892537539 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2773268266497083 -2 3.39941422257154 + vertex 0.9112001278467288 -2 3.017183334678748 + vertex 0.9081003544979743 -2 3.755848508110088 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 2.981481481481485 + vertex -4.856684746805584 -2 3.356652359229182 + vertex -5.5 -2 3.722222222222232 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.218601027446049 -2 18.53871904559627 + vertex -3.579065017001963 -2 18.90863581015581 + vertex -4.219405200955131 -2 19.27773497154104 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9069696294211652 -2 5.230288165873072 + vertex 0.9075480807427621 -2 4.492742427723907 + vertex 1.545725985940266 -2 4.861627066226085 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.85904341510472 -2 18.90779394030641 + vertex -4.859141812786931 -2 18.16743965320988 + vertex -4.218601027446049 -2 18.53871904559627 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.01284178372355 -2 7.075690784543413 + vertex -0.3726607962426137 -2 6.706414694889876 + vertex -0.372734229130202 -2 7.445730111745736 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.546076671149374 -2 4.124348986542191 + vertex 1.543851635481636 -2 3.385237964523963 + vertex 2.184470845550166 -2 3.755927490778999 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9075480807427621 -2 4.492742427723907 + vertex 1.546076671149374 -2 4.124348986542191 + vertex 1.545725985940266 -2 4.861627066226085 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -0.3808217490844628 -2 17.80411876256203 + vertex -1.019622954582061 -2 18.17249424625552 + vertex -1.020053807512184 -2 17.43409147419257 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.660634787301892 -2 18.54075855300827 + vertex -2.299852627534937 -2 18.90894251101097 + vertex -2.29950114659557 -2 18.17116677590457 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 18.53703703703704 + vertex -4.85904341510472 -2 18.90779394030641 + vertex -5.5 -2 19.27777777777778 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 5.944444444444438 + vertex 4.706195793300307 -2 6.262360537487246 + vertex 4.858499700900416 -2 5.574074074074068 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.218601027446049 -2 18.53871904559627 + vertex -4.859141812786931 -2 18.16743965320988 + vertex -4.218284649586943 -2 17.79834270098642 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.650478580992964 -2 5.228725669162287 + vertex -1.010978521253866 -2 4.86052685404085 + vertex -1.011374699255595 -2 5.598251001051494 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 11.12962962962961 + vertex 4.856505763897609 -2 10.75359339055225 + vertex 5.5 -2 10.38888888888887 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -0.3517984009234065 -2 20.14117242918954 + vertex -1.028753845297412 -2 20.34124811214607 + vertex -1.012364211165075 -2 19.66731864785164 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.927736629004366 -2 4.48943194994477 + vertex -2.926829710656151 -2 3.751805738528547 + vertex -2.288701402339894 -2 4.121267389307008 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.85904341510472 -2 18.90779394030641 + vertex -4.218601027446049 -2 18.53871904559627 + vertex -4.219405200955131 -2 19.27773497154104 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900416 -2 16.68518518518519 + vertex -4.217241391147802 -2 17.06005415907445 + vertex -4.858921784583877 -2 17.42644889903684 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.2665658211570644 -2 19.63282180689279 + vertex -0.3517984009234065 -2 20.14117242918954 + vertex -0.3780717967151275 -2 19.27660998370631 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 19.27777777777778 + vertex -4.862637361884998 -2 19.64719714547201 + vertex -5.5 -2 20.01851851851852 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858094016112133 -2 10.01830399001033 + vertex 4.195814199447445 -2 9.590974077315817 + vertex 4.849563117537802 -2 9.266648949177124 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.213339441084396 -2 8.923744763240448 + vertex -4.211295871605629 -2 8.181800934136941 + vertex -3.571807950105613 -2 8.553763073372794 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 3.722222222222218 + vertex 4.837852652952281 -2 3.301747240107742 + vertex 5.5 -2 2.98148148148148 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 20.01851851851852 + vertex 4.858733561059807 -2 19.64774309047021 + vertex 5.5 -2 19.27777777777777 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.659883570574173 -2 17.80266468206202 + vertex -1.660634787301892 -2 18.54075855300827 + vertex -2.29950114659557 -2 18.17116677590457 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.012076034282102 -2 6.33670297379202 + vertex -1.011374699255595 -2 5.598251001051494 + vertex -0.3722523798284423 -2 5.967729299340974 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 12.61111111111108 + vertex 4.857984469430814 -2 12.97618307852928 + vertex 4.858151477544044 -2 12.24064790548082 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.013651613078049 -2 7.815339836865478 + vertex -0.372734229130202 -2 7.445730111745736 + vertex -0.3730686086577459 -2 8.185727970766493 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 9.648148148148133 + vertex 4.849563117537802 -2 9.266648949177124 + vertex 5.5 -2 8.907407407407394 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2699326265064667 -2 4.123817115890558 + vertex 0.2773268266497083 -2 3.39941422257154 + vertex 0.9081003544979743 -2 3.755848508110088 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2589630319562187 -2 17.43538646129365 + vertex 0.2586041205171401 -2 18.17353338690858 + vertex -0.3808217490844628 -2 17.80411876256203 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.298332905758358 -2 3.40159593333896 + vertex -1.65230458775249 -2 3.756097892537539 + vertex -2.288701402339894 -2 4.121267389307008 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 17.79629629629628 + vertex 4.881498999364475 -2 18.16944240249155 + vertex 4.853983791777436 -2 17.46298864682942 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858499700900416 -2 5.574074074074068 + vertex 4.787889134207287 -2 4.821432434524037 + vertex 5.5 -2 5.203703703703698 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.65230458775249 -2 3.756097892537539 + vertex -1.650598693335845 -2 4.491615851896663 + vertex -2.288701402339894 -2 4.121267389307008 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.29950114659557 -2 18.17116677590457 + vertex -2.299852627534937 -2 18.90894251101097 + vertex -2.93909773043681 -2 18.53984166838779 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 4.462962962962957 + vertex 4.858499700900417 -2 4.092592592592588 + vertex 5.5 -2 3.722222222222218 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 19.27777777777777 + vertex 4.880508352128135 -2 18.90845629198527 + vertex 5.5 -2 18.53703703703703 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858284764645067 -2 11.499944635773 + vertex 4.077237994376535 -2 11.0510968086548 + vertex 4.856505763897609 -2 10.75359339055225 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.01284178372355 -2 7.075690784543413 + vertex -1.012076034282102 -2 6.33670297379202 + vertex -0.3726607962426137 -2 6.706414694889876 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858351974257875 -2 13.72219595896676 + vertex 4.216054417227187 -2 13.35154556175128 + vertex 4.857984469430814 -2 12.97618307852928 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.372734229130202 -2 7.445730111745736 + vertex 0.2666883617078354 -2 7.076125879193936 + vertex 0.2671505761328858 -2 7.815840390950871 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.184470845550166 -2 3.755927490778999 + vertex 1.543851635481636 -2 3.385237964523963 + vertex 2.184539364180798 -2 3.019234986705463 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.176315255311612 -2 20.03980165486242 + vertex 1.536645401435883 -2 19.65049039780268 + vertex 2.174596731070372 -2 19.28256664957802 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858094016112133 -2 10.01830399001033 + vertex 4.849563117537802 -2 9.266648949177124 + vertex 5.5 -2 9.648148148148133 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8978041598760911 -2 17.80513101507281 + vertex 0.8971018465118702 -2 18.54311123645736 + vertex 0.2586041205171401 -2 18.17353338690858 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.020053807512184 -2 17.43409147419257 + vertex -1.019622954582061 -2 18.17249424625552 + vertex -1.659883570574173 -2 17.80266468206202 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -0.3673592852575696 -2 3.754963435869593 + vertex -0.3680149090001792 -2 3.06536071564342 + vertex 0.2773268266497083 -2 3.39941422257154 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.011373743608711 -2 4.126304381733572 + vertex -1.650598693335845 -2 4.491615851896663 + vertex -1.65230458775249 -2 3.756097892537539 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 12.61111111111108 + vertex 4.858151477544044 -2 12.24064790548082 + vertex 5.5 -2 11.87037037037035 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900416 -2 16.68518518518519 + vertex -4.858921784583877 -2 17.42644889903684 + vertex -5.5 -2 17.05555555555556 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.013651613078049 -2 7.815339836865478 + vertex -1.01284178372355 -2 7.075690784543413 + vertex -0.372734229130202 -2 7.445730111745736 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.451560276391819 -2 19.28475070461192 + vertex 3.450126181270477 -2 20.02186022077733 + vertex 2.812532127091464 -2 19.65217639478334 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 4.462962962962973 + vertex -4.855053374775501 -2 4.84131556842358 + vertex -5.5 -2 5.203703703703717 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858351974257875 -2 13.72219595896676 + vertex 4.857984469430814 -2 12.97618307852928 + vertex 5.5 -2 13.35185185185182 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.819802103800889 -2 16.69942089983242 + vertex 2.81837767774294 -2 17.43790224669241 + vertex 2.177872523023615 -2 17.06825030927862 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.833182674131795 -2 7.046769943574702 + vertex 4.211091610502407 -2 6.720319745154439 + vertex 4.706195793300307 -2 6.262360537487246 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.289306234888224 -2 4.859074588876906 + vertex -1.650598693335845 -2 4.491615851896663 + vertex -1.650478580992964 -2 5.228725669162287 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 17.79629629629628 + vertex 4.853983791777436 -2 17.46298864682942 + vertex 5.5 -2 17.05555555555554 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 5.944444444444438 + vertex 4.858499700900416 -2 5.574074074074068 + vertex 5.5 -2 5.203703703703698 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822557155252714 -2 3.387632755075639 + vertex 3.460916694941177 -2 3.018947459590255 + vertex 3.463331557016295 -2 3.757543544245052 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.816046427378849 -2 18.17726903057125 + vertex 2.813820309881157 -2 18.91498790393246 + vertex 2.175300563759365 -2 18.54488978749554 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.540447376670603 -2 15.21980574900389 + vertex 1.540578471458792 -2 14.47984021110212 + vertex 2.181372868958385 -2 14.85027248055754 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.085163247467821 -2 7.352501298640743 + vertex 4.211091610502407 -2 6.720319745154439 + vertex 4.833182674131795 -2 7.046769943574702 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858494848371596 -2 7.796160416183852 + vertex 4.085163247467821 -2 7.352501298640743 + vertex 4.833182674131795 -2 7.046769943574702 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.185232814302425 -2 5.968730859613472 + vertex 2.182554547454119 -2 5.230533569883978 + vertex 2.812214953593998 -2 5.599116113034341 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.692097972637046 -2 3.077348409045236 + vertex -1.016136515624617 -2 3.403823044063341 + vertex -1.65230458775249 -2 3.756097892537539 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 8.907407407407394 + vertex 4.849563117537802 -2 9.266648949177124 + vertex 4.849062863316313 -2 8.529553442219953 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.115961526634615 -2 17.43426003489867 + vertex 3.461038152320298 -2 17.80933948973989 + vertex 3.459242902665586 -2 17.0664914438087 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.65101878611046 -2 5.966826581804315 + vertex -1.650478580992964 -2 5.228725669162287 + vertex -1.011374699255595 -2 5.598251001051494 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3801064849407917 -2 17.06537813209188 + vertex -0.3808217490844628 -2 17.80411876256203 + vertex -1.020053807512184 -2 17.43409147419257 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.176263957268402 -2 17.80664230692357 + vertex 2.175300563759365 -2 18.54488978749554 + vertex 1.536525565386907 -2 18.17497431780669 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9069696294211652 -2 5.230288165873072 + vertex 1.545725985940266 -2 4.861627066226085 + vertex 1.545624187113257 -2 5.599501849506099 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.9075480807427621 -2 4.492742427723907 + vertex 0.2699326265064667 -2 4.123817115890558 + vertex 0.9081003544979743 -2 3.755848508110088 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 5.203703703703698 + vertex 4.787889134207287 -2 4.821432434524037 + vertex 5.5 -2 4.462962962962957 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 18.53703703703703 + vertex 4.881498999364475 -2 18.16944240249155 + vertex 5.5 -2 17.79629629629628 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.459242902665586 -2 17.0664914438087 + vertex 2.819802103800889 -2 16.69942089983242 + vertex 3.462242831536008 -2 16.330904223054 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.578321844044858 -2 18.1702037050324 + vertex -2.93909773043681 -2 18.53984166838779 + vertex -3.579065017001963 -2 18.90863581015581 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 14.83333333333331 + vertex 4.875264150806977 -2 14.4094014084103 + vertex 5.5 -2 14.09259259259256 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.566045361185739 -2 4.119718267295393 + vertex -3.557504597528008 -2 3.394518219884866 + vertex -2.926829710656151 -2 3.751805738528547 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3722523798284423 -2 5.967729299340974 + vertex 0.2675336108434639 -2 5.598911732970858 + vertex 0.2669669974803863 -2 6.337218674499295 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2675336108434639 -2 5.598911732970858 + vertex 0.9069696294211652 -2 5.230288165873072 + vertex 0.9063840879461926 -2 5.968317219257086 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.201768225106574 -2 11.88690768266759 + vertex 1.548263848345031 -2 12.25974285150989 + vertex 1.544644799008981 -2 11.51710820666931 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.014337786730955 -2 8.555368182545857 + vertex -1.013651613078049 -2 7.815339836865478 + vertex -0.3730686086577459 -2 8.185727970766493 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.184470845550166 -2 3.755927490778999 + vertex 2.822557155252714 -2 3.387632755075639 + vertex 2.822556644375143 -2 4.124490635138393 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.014337786730955 -2 8.555368182545857 + vertex -0.3730686086577459 -2 8.185727970766493 + vertex -0.3733364363707275 -2 8.925891850741099 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858284764645067 -2 11.499944635773 + vertex 4.856505763897609 -2 10.75359339055225 + vertex 5.5 -2 11.12962962962961 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 10.38888888888887 + vertex 4.856505763897609 -2 10.75359339055225 + vertex 4.858094016112133 -2 10.01830399001033 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2665658211570644 -2 19.63282180689279 + vertex -0.3780717967151275 -2 19.27660998370631 + vertex 0.2582962276091168 -2 18.91107228975501 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 8.907407407407394 + vertex 4.849062863316313 -2 8.529553442219953 + vertex 5.5 -2 8.166666666666657 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.822119455895671 -2 15.2206284001408 + vertex 2.180386143728376 -2 15.58998824863726 + vertex 2.181372868958385 -2 14.85027248055754 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 3.462242831536008 -2 16.330904223054 + vertex 2.819802103800889 -2 16.69942089983242 + vertex 2.821179313344073 -2 15.9603879965617 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 16.31481481481482 + vertex -4.858499700900416 -2 16.68518518518519 + vertex -5.5 -2 17.05555555555556 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.546076671149374 -2 4.124348986542191 + vertex 2.184470845550166 -2 3.755927490778999 + vertex 2.184215443647103 -2 4.492955698672738 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.181372868958385 -2 14.85027248055754 + vertex 1.540578471458792 -2 14.47984021110212 + vertex 2.181821400268289 -2 14.11008914350445 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.09173318766436 -2 16.67721812266799 + vertex 3.459242902665586 -2 17.0664914438087 + vertex 3.462242831536008 -2 16.330904223054 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.372734229130202 -2 7.445730111745736 + vertex 0.2671505761328858 -2 7.815840390950871 + vertex -0.3730686086577459 -2 8.185727970766493 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 17.05555555555556 + vertex -4.858921784583877 -2 17.42644889903684 + vertex -5.5 -2 17.7962962962963 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 11.87037037037035 + vertex 4.858151477544044 -2 12.24064790548082 + vertex 4.858284764645067 -2 11.499944635773 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.216602219501706 -2 11.87014423231384 + vertex 3.653422321959101 -2 11.49668106748853 + vertex 4.077237994376535 -2 11.0510968086548 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2675336108434639 -2 5.598911732970858 + vertex 0.2683114217292001 -2 4.861199062825149 + vertex 0.9069696294211652 -2 5.230288165873072 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 6.68518518518518 + vertex 4.706195793300307 -2 6.262360537487246 + vertex 5.5 -2 5.944444444444438 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822119455895671 -2 15.2206284001408 + vertex 2.821179313344073 -2 15.9603879965617 + vertex 2.180386143728376 -2 15.58998824863726 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3517984009234065 -2 20.14117242918954 + vertex -1.012364211165075 -2 19.66731864785164 + vertex -0.3780717967151275 -2 19.27660998370631 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936008509214679 -2 14.84857666890852 + vertex -2.936690955264944 -2 15.58819721247742 + vertex -3.576030909554856 -2 15.21816507115986 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 6.685185185185206 + vertex -4.854290590709602 -2 7.063614504077036 + vertex -5.5 -2 7.425925925925949 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.013651613078049 -2 7.815339836865478 + vertex -1.654746267724451 -2 8.184879985401814 + vertex -1.653828429200071 -2 7.44475907091302 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858494848371596 -2 7.796160416183852 + vertex 4.833182674131795 -2 7.046769943574702 + vertex 5.5 -2 7.42592592592592 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.2699326265064667 -2 4.123817115890558 + vertex -0.3673592852575696 -2 3.754963435869593 + vertex 0.2773268266497083 -2 3.39941422257154 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3730686086577459 -2 8.185727970766493 + vertex 0.2671505761328858 -2 7.815840390950871 + vertex 0.2675047632069562 -2 8.556216284841577 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.161330733573104 -2 8.122630508642821 + vertex 3.576676627398162 -2 7.779376729527785 + vertex 4.085163247467821 -2 7.352501298640743 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858284764645067 -2 11.499944635773 + vertex 4.858151477544044 -2 12.24064790548082 + vertex 4.216602219501706 -2 11.87014423231384 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.09173318766436 -2 16.67721812266799 + vertex 4.115961526634615 -2 17.43426003489867 + vertex 3.459242902665586 -2 17.0664914438087 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3801064849407917 -2 17.06537813209188 + vertex 0.2589630319562187 -2 17.43538646129365 + vertex -0.3808217490844628 -2 17.80411876256203 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.935308886475556 -2 14.10836185815992 + vertex -2.936008509214679 -2 14.84857666890852 + vertex -3.575835566622261 -2 14.47797604271785 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.028753845297412 -2 20.34124811214607 + vertex -1.716472977865604 -2 20.13191285697176 + vertex -1.012364211165075 -2 19.66731864785164 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.014337786730955 -2 8.555368182545857 + vertex -1.654746267724451 -2 8.184879985401814 + vertex -1.013651613078049 -2 7.815339836865478 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.936690955264944 -2 15.58819721247742 + vertex -3.576255991129901 -2 15.95640675516809 + vertex -3.576030909554856 -2 15.21816507115986 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 6.68518518518518 + vertex 4.833182674131795 -2 7.046769943574702 + vertex 4.706195793300307 -2 6.262360537487246 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3722523798284423 -2 5.967729299340974 + vertex 0.2669669974803863 -2 6.337218674499295 + vertex -0.3726607962426137 -2 6.706414694889876 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.180386143728376 -2 15.58998824863726 + vertex 1.539167618242686 -2 15.95899815352942 + vertex 1.540447376670603 -2 15.21980574900389 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858351974257875 -2 13.72219595896676 + vertex 4.875264150806977 -2 14.4094014084103 + vertex 4.212841511831785 -2 14.04539977235522 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.935308886475556 -2 14.10836185815992 + vertex -2.296560192048382 -2 14.4787322337115 + vertex -2.936008509214679 -2 14.84857666890852 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.181821400268289 -2 14.11008914350445 + vertex 1.540578471458792 -2 14.47984021110212 + vertex 1.541321577020518 -2 13.73968876156753 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822533908502859 -2 14.48043622728941 + vertex 2.822119455895671 -2 15.2206284001408 + vertex 2.181372868958385 -2 14.85027248055754 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.180386143728376 -2 15.58998824863726 + vertex 1.540447376670603 -2 15.21980574900389 + vertex 2.181372868958385 -2 14.85027248055754 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.218601027446049 -2 18.53871904559627 + vertex -3.578321844044858 -2 18.1702037050324 + vertex -3.579065017001963 -2 18.90863581015581 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.870582047868353 -2 15.09106547965763 + vertex 4.875264150806977 -2 14.4094014084103 + vertex 5.5 -2 14.83333333333331 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 14.09259259259256 + vertex 4.875264150806977 -2 14.4094014084103 + vertex 4.858351974257875 -2 13.72219595896676 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.822533908502859 -2 14.48043622728941 + vertex 2.181372868958385 -2 14.85027248055754 + vertex 2.181821400268289 -2 14.11008914350445 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.935281513827058 -2 13.36791463067939 + vertex -2.935308886475556 -2 14.10836185815992 + vertex -3.575103169386946 -2 13.73759135621609 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.2586041205171401 -2 18.17353338690858 + vertex -0.3796622136127862 -2 18.54169448313185 + vertex -0.3808217490844628 -2 17.80411876256203 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.288701402339894 -2 4.121267389307008 + vertex -1.650598693335845 -2 4.491615851896663 + vertex -2.289306234888224 -2 4.859074588876906 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.194840589487079 -2 12.6340074235671 + vertex 1.548263848345031 -2 12.25974285150989 + vertex 2.201768225106574 -2 11.88690768266759 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.289818850739709 -2 5.597134858359751 + vertex -2.289306234888224 -2 4.859074588876906 + vertex -1.650478580992964 -2 5.228725669162287 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3730686086577459 -2 8.185727970766493 + vertex 0.2675047632069562 -2 8.556216284841577 + vertex -0.3733364363707275 -2 8.925891850741099 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.93854539660131 -2 17.80165228789176 + vertex -2.29950114659557 -2 18.17116677590457 + vertex -2.93909773043681 -2 18.53984166838779 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858094016112133 -2 10.01830399001033 + vertex 4.856505763897609 -2 10.75359339055225 + vertex 4.206582833496469 -2 10.35562052434043 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.181821400268289 -2 14.11008914350445 + vertex 1.541321577020518 -2 13.73968876156753 + vertex 2.183420200239241 -2 13.37028029371495 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3737856382635328 -2 9.66627206159394 + vertex 0.2669591324310077 -2 9.296440423959986 + vertex 0.2655151456524666 -2 10.03621174168124 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 8.166666666666694 + vertex -4.858262682337108 -2 8.538487430234987 + vertex -5.5 -2 8.907407407407437 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2589630319562187 -2 17.43538646129365 + vertex 0.8978041598760911 -2 17.80513101507281 + vertex 0.2586041205171401 -2 18.17353338690858 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858494848371596 -2 7.796160416183852 + vertex 4.161330733573104 -2 8.122630508642821 + vertex 4.085163247467821 -2 7.352501298640743 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.936008509214679 -2 14.84857666890852 + vertex -3.576030909554856 -2 15.21816507115986 + vertex -3.575835566622261 -2 14.47797604271785 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.9075480807427621 -2 4.492742427723907 + vertex 0.2683114217292001 -2 4.861199062825149 + vertex 0.2699326265064667 -2 4.123817115890558 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.017604372424323 -2 14.4781092538168 + vertex -1.657503037368121 -2 14.84862210189439 + vertex -1.657005748105574 -2 14.10863196733877 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.82287889280243 -2 13.74009365728223 + vertex 2.181821400268289 -2 14.11008914350445 + vertex 2.183420200239241 -2 13.37028029371495 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 8.166666666666657 + vertex 4.849062863316313 -2 8.529553442219953 + vertex 4.858494848371596 -2 7.796160416183852 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.935308886475556 -2 14.10836185815992 + vertex -3.575835566622261 -2 14.47797604271785 + vertex -3.575103169386946 -2 13.73759135621609 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 14.83333333333334 + vertex -4.858499700900418 -2 15.20370370370371 + vertex -5.5 -2 15.57407407407408 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 14.46296296296297 + vertex -4.858499700900418 -2 15.20370370370371 + vertex -5.5 -2 14.83333333333334 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858151477544044 -2 12.24064790548082 + vertex 4.215348947555784 -2 12.57974608201392 + vertex 4.216602219501706 -2 11.87014423231384 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.934268742123706 -2 12.6273540928905 + vertex -2.935281513827058 -2 13.36791463067939 + vertex -3.574595658136062 -2 12.99710602982787 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.836742182517218 -2 13.00553687726588 + vertex 2.183420200239241 -2 13.37028029371495 + vertex 2.194840589487079 -2 12.6340074235671 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.183605746592189 -2 9.667274480950523 + vertex 1.541963627420545 -2 10.03723710428692 + vertex 1.542467984840711 -2 9.29678151908432 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.183443792349406 -2 10.40773240863229 + vertex 1.541963627420545 -2 10.03723710428692 + vertex 2.183605746592189 -2 9.667274480950523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.933457838749669 -2 11.8870692343648 + vertex -2.294798722082105 -2 12.25814924190241 + vertex -2.934268742123706 -2 12.6273540928905 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.196371620835734 -2 8.184302070812972 + vertex 1.546927139036397 -2 8.555854635114024 + vertex 1.546065482251067 -2 7.815243539277521 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.185104942443486 -2 6.707720985192397 + vertex 1.544564088479184 -2 7.07714010847899 + vertex 1.545532470823523 -2 6.337800945684743 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.541632467723097 -2 10.77769188745804 + vertex 1.541963627420545 -2 10.03723710428692 + vertex 2.183443792349406 -2 10.40773240863229 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.880470240504621 -2 12.28961005685342 + vertex 2.194840589487079 -2 12.6340074235671 + vertex 2.201768225106574 -2 11.88690768266759 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.014335245614432 -2 9.295231348231319 + vertex -1.014337786730955 -2 8.555368182545857 + vertex -0.3733364363707275 -2 8.925891850741099 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.012076034282102 -2 6.33670297379202 + vertex -1.65101878611046 -2 5.966826581804315 + vertex -1.011374699255595 -2 5.598251001051494 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.849062863316313 -2 8.529553442219953 + vertex 4.17389398326439 -2 8.848934738026195 + vertex 4.161330733573104 -2 8.122630508642821 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.183420200239241 -2 13.37028029371495 + vertex 1.543602769126001 -2 13.0006143682726 + vertex 2.194840589487079 -2 12.6340074235671 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82287889280243 -2 13.74009365728223 + vertex 2.822533908502859 -2 14.48043622728941 + vertex 2.181821400268289 -2 14.11008914350445 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.856505763897609 -2 10.75359339055225 + vertex 4.077237994376535 -2 11.0510968086548 + vertex 4.206582833496469 -2 10.35562052434043 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.298947996151707 -2 17.43305243895607 + vertex -1.659883570574173 -2 17.80266468206202 + vertex -2.29950114659557 -2 18.17116677590457 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.014335245614432 -2 9.295231348231319 + vertex -0.3733364363707275 -2 8.925891850741099 + vertex -0.3737856382635328 -2 9.66627206159394 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.933457838749669 -2 11.8870692343648 + vertex -2.934268742123706 -2 12.6273540928905 + vertex -3.574315167895597 -2 12.25657638551989 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.201768225106574 -2 11.88690768266759 + vertex 1.544644799008981 -2 11.51710820666931 + vertex 2.180008197240448 -2 11.14323735393523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.543602769126001 -2 13.0006143682726 + vertex 1.548263848345031 -2 12.25974285150989 + vertex 2.194840589487079 -2 12.6340074235671 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.541321577020518 -2 13.73968876156753 + vertex 0.9020817508314349 -2 13.37014429011399 + vertex 1.543602769126001 -2 13.0006143682726 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.180008197240448 -2 11.14323735393523 + vertex 1.541632467723097 -2 10.77769188745804 + vertex 2.183443792349406 -2 10.40773240863229 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 7.42592592592592 + vertex 4.833182674131795 -2 7.046769943574702 + vertex 5.5 -2 6.68518518518518 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3726607962426137 -2 6.706414694889876 + vertex 0.2666883617078354 -2 7.076125879193936 + vertex -0.372734229130202 -2 7.445730111745736 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.933219101096931 -2 11.14588787169219 + vertex -2.933457838749669 -2 11.8870692343648 + vertex -3.573556398640321 -2 11.5159427770449 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.857984469430814 -2 12.97618307852928 + vertex 4.216054417227187 -2 13.35154556175128 + vertex 4.215348947555784 -2 12.57974608201392 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.016110616181929 -2 12.25809403538951 + vertex -1.656052021671596 -2 12.62807046985316 + vertex -1.654833933336664 -2 11.88758380001475 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.935281513827058 -2 13.36791463067939 + vertex -3.575103169386946 -2 13.73759135621609 + vertex -3.574595658136062 -2 12.99710602982787 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 12.61111111111113 + vertex -4.858499700900418 -2 12.9814814814815 + vertex -5.5 -2 13.35185185185187 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 12.24074074074076 + vertex -4.858499700900418 -2 12.9814814814815 + vertex -5.5 -2 12.61111111111113 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.014349597196187 -2 10.03571453406039 + vertex -1.014335245614432 -2 9.295231348231319 + vertex -0.3737856382635328 -2 9.66627206159394 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.544644799008981 -2 11.51710820666931 + vertex 1.541632467723097 -2 10.77769188745804 + vertex 2.180008197240448 -2 11.14323735393523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.880470240504621 -2 12.28961005685342 + vertex 2.836742182517218 -2 13.00553687726588 + vertex 2.194840589487079 -2 12.6340074235671 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.541321577020518 -2 13.73968876156753 + vertex 1.543602769126001 -2 13.0006143682726 + vertex 2.183420200239241 -2 13.37028029371495 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 10.38888888888892 + vertex -4.858499700900418 -2 10.75925925925928 + vertex -5.5 -2 11.12962962962965 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900419 -2 10.01851851851855 + vertex -4.858499700900418 -2 10.75925925925928 + vertex -5.5 -2 10.38888888888892 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9030491369272273 -2 12.63007468708392 + vertex 0.9044505518129392 -2 11.88904062794034 + vertex 1.548263848345031 -2 12.25974285150989 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.544644799008981 -2 11.51710820666931 + vertex 0.9037758590567562 -2 11.14751413629097 + vertex 1.541632467723097 -2 10.77769188745804 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.462650155081207 -2 15.59090371298797 + vertex 3.462242831536008 -2 16.330904223054 + vertex 2.821179313344073 -2 15.9603879965617 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.836742182517218 -2 13.00553687726588 + vertex 2.82287889280243 -2 13.74009365728223 + vertex 2.183420200239241 -2 13.37028029371495 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.942690586882144 -2 11.51273307229485 + vertex 2.201768225106574 -2 11.88690768266759 + vertex 2.180008197240448 -2 11.14323735393523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.932061770091924 -2 9.665124186191072 + vertex -2.29305276278285 -2 10.03456254762132 + vertex -2.932416393902854 -2 10.40506856825943 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.014335245614432 -2 9.295231348231319 + vertex -1.654945538210082 -2 8.924891123316154 + vertex -1.014337786730955 -2 8.555368182545857 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3737856382635328 -2 9.66627206159394 + vertex 0.2655151456524666 -2 10.03621174168124 + vertex -0.3746676392718538 -2 10.4063799512949 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.014349597196187 -2 10.03571453406039 + vertex -0.3737856382635328 -2 9.66627206159394 + vertex -0.3746676392718538 -2 10.4063799512949 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858151477544044 -2 12.24064790548082 + vertex 4.857984469430814 -2 12.97618307852928 + vertex 4.215348947555784 -2 12.57974608201392 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 8.166666666666657 + vertex 4.858494848371596 -2 7.796160416183852 + vertex 5.5 -2 7.42592592592592 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 10.38888888888887 + vertex 4.858094016112133 -2 10.01830399001033 + vertex 5.5 -2 9.648148148148133 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 11.87037037037035 + vertex 4.858284764645067 -2 11.499944635773 + vertex 5.5 -2 11.12962962962961 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 14.09259259259261 + vertex -4.858499700900419 -2 14.46296296296297 + vertex -5.5 -2 14.83333333333334 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 15.57407407407405 + vertex 4.870582047868353 -2 15.09106547965763 + vertex 5.5 -2 14.83333333333331 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 14.09259259259256 + vertex 4.858351974257875 -2 13.72219595896676 + vertex 5.5 -2 13.35185185185182 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 11.87037037037039 + vertex -4.858499700900419 -2 12.24074074074076 + vertex -5.5 -2 12.61111111111113 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 9.648148148148179 + vertex -4.858499700900419 -2 10.01851851851855 + vertex -5.5 -2 10.38888888888892 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.933457838749669 -2 11.8870692343648 + vertex -3.574315167895597 -2 12.25657638551989 + vertex -3.573556398640321 -2 11.5159427770449 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.932416393902854 -2 10.40506856825943 + vertex -2.933219101096931 -2 11.14588787169219 + vertex -3.573122554230794 -2 10.77535438049067 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.934268742123706 -2 12.6273540928905 + vertex -3.574595658136062 -2 12.99710602982787 + vertex -3.574315167895597 -2 12.25657638551989 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.185822392903936 -2 8.926589046837421 + vertex 1.546927139036397 -2 8.555854635114024 + vertex 2.196371620835734 -2 8.184302070812972 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.942690586882144 -2 11.51273307229485 + vertex 2.880470240504621 -2 12.28961005685342 + vertex 2.201768225106574 -2 11.88690768266759 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -0.3780717967151275 -2 19.27660998370631 + vertex -0.3796622136127862 -2 18.54169448313185 + vertex 0.2582962276091168 -2 18.91107228975501 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.015223229097348 -2 10.77672264183186 + vertex -1.014349597196187 -2 10.03571453406039 + vertex -0.3746676392718538 -2 10.4063799512949 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.849563117537802 -2 9.266648949177124 + vertex 4.195814199447445 -2 9.590974077315817 + vertex 4.17389398326439 -2 8.848934738026195 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.807399006272134 -2 10.74844508614493 + vertex 2.180008197240448 -2 11.14323735393523 + vertex 2.183443792349406 -2 10.40773240863229 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3733364363707275 -2 8.925891850741099 + vertex 0.2669591324310077 -2 9.296440423959986 + vertex -0.3737856382635328 -2 9.66627206159394 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2699326265064667 -2 4.123817115890558 + vertex 0.2683114217292001 -2 4.861199062825149 + vertex -0.3706777379366633 -2 4.49175823877602 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 3.722222222222232 + vertex -4.854580471963713 -2 4.101585275261201 + vertex -5.5 -2 4.462962962962973 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.137906133270736 -2 15.9931810658391 + vertex 4.09173318766436 -2 16.67721812266799 + vertex 3.462242831536008 -2 16.330904223054 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.933219101096931 -2 11.14588787169219 + vertex -3.573556398640321 -2 11.5159427770449 + vertex -3.573122554230794 -2 10.77535438049067 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.183605746592189 -2 9.667274480950523 + vertex 1.542467984840711 -2 9.29678151908432 + vertex 2.185822392903936 -2 8.926589046837421 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.013651613078049 -2 7.815339836865478 + vertex -1.653828429200071 -2 7.44475907091302 + vertex -1.01284178372355 -2 7.075690784543413 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.015223229097348 -2 10.77672264183186 + vertex -0.3746676392718538 -2 10.4063799512949 + vertex -0.3751518171424401 -2 11.14736947415786 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.807399006272134 -2 10.74844508614493 + vertex 2.942690586882144 -2 11.51273307229485 + vertex 2.180008197240448 -2 11.14323735393523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858494848371596 -2 7.796160416183852 + vertex 4.849062863316313 -2 8.529553442219953 + vertex 4.161330733573104 -2 8.122630508642821 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.849062863316313 -2 8.529553442219953 + vertex 4.849563117537802 -2 9.266648949177124 + vertex 4.17389398326439 -2 8.848934738026195 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.015805467510334 -2 11.51730017583935 + vertex -1.654202488256953 -2 11.14650870766094 + vertex -1.015223229097348 -2 10.77672264183186 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.826562603555422 -2 10.03778041601883 + vertex 2.183443792349406 -2 10.40773240863229 + vertex 2.183605746592189 -2 9.667274480950523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.928586644196474 -2 5.227460072678477 + vertex -2.927736629004366 -2 4.48943194994477 + vertex -2.289306234888224 -2 4.859074588876906 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.932061770091924 -2 9.665124186191072 + vertex -2.932416393902854 -2 10.40506856825943 + vertex -3.573011778277769 -2 10.03490946631051 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.015805467510334 -2 11.51730017583935 + vertex -1.015223229097348 -2 10.77672264183186 + vertex -0.3751518171424401 -2 11.14736947415786 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.826562603555422 -2 10.03778041601883 + vertex 2.807399006272134 -2 10.74844508614493 + vertex 2.183443792349406 -2 10.40773240863229 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.573556398640321 -2 11.5159427770449 + vertex -4.21512821818804 -2 11.14017985693962 + vertex -3.573122554230794 -2 10.77535438049067 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3758325625919503 -2 11.88829022912528 + vertex 0.2629865536171161 -2 12.25924761449043 + vertex -0.3766763580637025 -2 12.62819035942791 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.578321844044858 -2 18.1702037050324 + vertex -2.93854539660131 -2 17.80165228789176 + vertex -2.93909773043681 -2 18.53984166838779 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.654945538210082 -2 8.924891123316154 + vertex -1.654746267724451 -2 8.184879985401814 + vertex -1.014337786730955 -2 8.555368182545857 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.932416393902854 -2 10.40506856825943 + vertex -3.573122554230794 -2 10.77535438049067 + vertex -3.573011778277769 -2 10.03490946631051 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.546076671149374 -2 4.124348986542191 + vertex 2.184215443647103 -2 4.492955698672738 + vertex 1.545725985940266 -2 4.861627066226085 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 18.53703703703704 + vertex -4.859141812786931 -2 18.16743965320988 + vertex -4.85904341510472 -2 18.90779394030641 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82287889280243 -2 13.74009365728223 + vertex 3.518478270762881 -2 14.20097805827304 + vertex 2.822533908502859 -2 14.48043622728941 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822119455895671 -2 15.2206284001408 + vertex 3.462650155081207 -2 15.59090371298797 + vertex 2.821179313344073 -2 15.9603879965617 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.575103169386946 -2 13.73759135621609 + vertex -4.216057034610309 -2 13.36202290232499 + vertex -3.574595658136062 -2 12.99710602982787 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.015805467510334 -2 11.51730017583935 + vertex -0.3751518171424401 -2 11.14736947415786 + vertex -0.3758325625919503 -2 11.88829022912528 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.880470240504621 -2 12.28961005685342 + vertex 3.464668476437278 -2 12.62973158487211 + vertex 2.836742182517218 -2 13.00553687726588 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.826562603555422 -2 10.03778041601883 + vertex 3.465598520979608 -2 10.40825210954239 + vertex 2.807399006272134 -2 10.74844508614493 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8978041598760911 -2 17.80513101507281 + vertex 1.536525565386907 -2 18.17497431780669 + vertex 0.8971018465118702 -2 18.54311123645736 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3801064849407917 -2 17.06537813209188 + vertex 0.2598502869479086 -2 16.69668717560763 + vertex 0.2589630319562187 -2 17.43538646129365 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.196371620835734 -2 8.184302070812972 + vertex 1.546065482251067 -2 7.815243539277521 + vertex 2.18153235290545 -2 7.44215962233644 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3786352136969205 -2 15.58732630756997 + vertex 0.2616713673019718 -2 15.21837293427887 + vertex 0.2611954692988795 -2 15.95761504188607 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.542467984840711 -2 9.29678151908432 + vertex 1.546927139036397 -2 8.555854635114024 + vertex 2.185822392903936 -2 8.926589046837421 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.185232814302425 -2 5.968730859613472 + vertex 2.812214953593998 -2 5.599116113034341 + vertex 2.815981112413922 -2 6.338245174195091 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9069696294211652 -2 5.230288165873072 + vertex 1.545624187113257 -2 5.599501849506099 + vertex 0.9063840879461926 -2 5.968317219257086 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.016110616181929 -2 12.25809403538951 + vertex -1.015805467510334 -2 11.51730017583935 + vertex -0.3758325625919503 -2 11.88829022912528 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.18153235290545 -2 7.44215962233644 + vertex 1.544564088479184 -2 7.07714010847899 + vertex 2.185104942443486 -2 6.707720985192397 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.932061770091924 -2 9.665124186191072 + vertex -3.573011778277769 -2 10.03490946631051 + vertex -3.572024714500107 -2 9.294398673700472 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.813820309881157 -2 18.91498790393246 + vertex 3.451560276391819 -2 19.28475070461192 + vertex 2.812532127091464 -2 19.65217639478334 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2675336108434639 -2 5.598911732970858 + vertex 0.9063840879461926 -2 5.968317219257086 + vertex 0.2669669974803863 -2 6.337218674499295 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.931366460525708 -2 8.924672563442744 + vertex -2.932061770091924 -2 9.665124186191072 + vertex -3.572024714500107 -2 9.294398673700472 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82679663843258 -2 9.297354238277073 + vertex 2.826562603555422 -2 10.03778041601883 + vertex 2.183605746592189 -2 9.667274480950523 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.016110616181929 -2 12.25809403538951 + vertex -0.3758325625919503 -2 11.88829022912528 + vertex -0.3766763580637025 -2 12.62819035942791 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3774731583634351 -2 14.10858624217519 + vertex 0.2621501162915151 -2 14.47918298650684 + vertex -0.3780284691315897 -2 14.84793992907052 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82495189991042 -2 8.55714936857806 + vertex 3.482481059799262 -2 9.029779793154106 + vertex 2.82679663843258 -2 9.297354238277073 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.576255991129901 -2 15.95640675516809 + vertex -4.216933704909376 -2 15.58411418009348 + vertex -3.576030909554856 -2 15.21816507115986 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.012076034282102 -2 6.33670297379202 + vertex -1.652223002598351 -2 6.705412755708672 + vertex -1.65101878611046 -2 5.966826581804315 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.572024714500107 -2 9.294398673700472 + vertex -4.213339441084396 -2 8.923744763240448 + vertex -3.571807950105613 -2 8.553763073372794 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.017139898840178 -2 12.9982754305505 + vertex -1.016110616181929 -2 12.25809403538951 + vertex -0.3766763580637025 -2 12.62819035942791 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.019083154061386 -2 15.95650508483111 + vertex -1.658586945552809 -2 15.58744135521406 + vertex -1.018444238152855 -2 15.21764129910152 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3780284691315897 -2 14.84793992907052 + vertex 0.2616713673019718 -2 15.21837293427887 + vertex -0.3786352136969205 -2 15.58732630756997 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.017404658776929 -2 13.73786746955996 + vertex -1.657207383403859 -2 13.36815951755871 + vertex -1.017139898840178 -2 12.9982754305505 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.176263957268402 -2 17.80664230692357 + vertex 2.816046427378849 -2 18.17726903057125 + vertex 2.175300563759365 -2 18.54488978749554 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.82679663843258 -2 9.297354238277073 + vertex 2.183605746592189 -2 9.667274480950523 + vertex 2.185822392903936 -2 8.926589046837421 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.017139898840178 -2 12.9982754305505 + vertex -0.3766763580637025 -2 12.62819035942791 + vertex -0.3773902298450702 -2 13.36861719265928 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2675047632069562 -2 8.556216284841577 + vertex 0.2669591324310077 -2 9.296440423959986 + vertex -0.3733364363707275 -2 8.925891850741099 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 17.7962962962963 + vertex -4.859141812786931 -2 18.16743965320988 + vertex -5.5 -2 18.53703703703704 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.017404658776929 -2 13.73786746955996 + vertex -1.017139898840178 -2 12.9982754305505 + vertex -0.3773902298450702 -2 13.36861719265928 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 4.462962962962973 + vertex -4.854580471963713 -2 4.101585275261201 + vertex -4.855053374775501 -2 4.84131556842358 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2641422182702875 -2 11.51762814211468 + vertex 0.2646862774917507 -2 10.77704715318259 + vertex 0.9037758590567562 -2 11.14751413629097 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.017404658776929 -2 13.73786746955996 + vertex -0.3773902298450702 -2 13.36861719265928 + vertex -0.3774731583634351 -2 14.10858624217519 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82495189991042 -2 8.55714936857806 + vertex 2.82679663843258 -2 9.297354238277073 + vertex 2.185822392903936 -2 8.926589046837421 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.931366460525708 -2 8.924672563442744 + vertex -3.572024714500107 -2 9.294398673700472 + vertex -3.571807950105613 -2 8.553763073372794 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.93854539660131 -2 17.80165228789176 + vertex -2.298947996151707 -2 17.43305243895607 + vertex -2.29950114659557 -2 18.17116677590457 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3786352136969205 -2 15.58732630756997 + vertex 0.2611954692988795 -2 15.95761504188607 + vertex -0.379347168317705 -2 16.32651775590352 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.462650155081207 -2 15.59090371298797 + vertex 4.137906133270736 -2 15.9931810658391 + vertex 3.462242831536008 -2 16.330904223054 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.659306952361946 -2 17.0643366164128 + vertex -1.020053807512184 -2 17.43409147419257 + vertex -1.659883570574173 -2 17.80266468206202 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.82495189991042 -2 8.55714936857806 + vertex 2.185822392903936 -2 8.926589046837421 + vertex 2.196371620835734 -2 8.184302070812972 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.65101878611046 -2 5.966826581804315 + vertex -2.289818850739709 -2 5.597134858359751 + vertex -1.650478580992964 -2 5.228725669162287 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 2.179344469681174 -2 16.32918499547299 + vertex 1.539167618242686 -2 15.95899815352942 + vertex 2.180386143728376 -2 15.58998824863726 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.931659578289811 -2 8.184142773686492 + vertex -2.931366460525708 -2 8.924672563442744 + vertex -3.571807950105613 -2 8.553763073372794 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.927736629004366 -2 4.48943194994477 + vertex -3.566045361185739 -2 4.119718267295393 + vertex -2.926829710656151 -2 3.751805738528547 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.653828429200071 -2 7.44475907091302 + vertex -1.652223002598351 -2 6.705412755708672 + vertex -1.01284178372355 -2 7.075690784543413 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.01284178372355 -2 7.075690784543413 + vertex -1.652223002598351 -2 6.705412755708672 + vertex -1.012076034282102 -2 6.33670297379202 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.017604372424323 -2 14.4781092538168 + vertex -1.017404658776929 -2 13.73786746955996 + vertex -0.3774731583634351 -2 14.10858624217519 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2611954692988795 -2 15.95761504188607 + vertex 0.2598502869479086 -2 16.69668717560763 + vertex -0.379347168317705 -2 16.32651775590352 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.9069696294211652 -2 5.230288165873072 + vertex 0.2683114217292001 -2 4.861199062825149 + vertex 0.9075480807427621 -2 4.492742427723907 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.137906133270736 -2 15.9931810658391 + vertex 4.744074395475103 -2 16.33170939209035 + vertex 4.09173318766436 -2 16.67721812266799 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.019481218622897 -2 16.6954608729413 + vertex -0.3801064849407917 -2 17.06537813209188 + vertex -1.020053807512184 -2 17.43409147419257 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.016913363682256 -2 18.91113701755697 + vertex -0.3796622136127862 -2 18.54169448313185 + vertex -0.3780717967151275 -2 19.27660998370631 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.017604372424323 -2 14.4781092538168 + vertex -0.3774731583634351 -2 14.10858624217519 + vertex -0.3780284691315897 -2 14.84793992907052 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822119455895671 -2 15.2206284001408 + vertex 3.522482822207098 -2 14.91581723933913 + vertex 3.462650155081207 -2 15.59090371298797 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.018444238152855 -2 15.21764129910152 + vertex -1.017604372424323 -2 14.4781092538168 + vertex -0.3780284691315897 -2 14.84793992907052 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.379347168317705 -2 16.32651775590352 + vertex 0.2598502869479086 -2 16.69668717560763 + vertex -0.3801064849407917 -2 17.06537813209188 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822533908502859 -2 14.48043622728941 + vertex 3.522482822207098 -2 14.91581723933913 + vertex 2.822119455895671 -2 15.2206284001408 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.518478270762881 -2 14.20097805827304 + vertex 3.522482822207098 -2 14.91581723933913 + vertex 2.822533908502859 -2 14.48043622728941 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.016136515624617 -2 3.403823044063341 + vertex -1.011373743608711 -2 4.126304381733572 + vertex -1.65230458775249 -2 3.756097892537539 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.018444238152855 -2 15.21764129910152 + vertex -0.3780284691315897 -2 14.84793992907052 + vertex -0.3786352136969205 -2 15.58732630756997 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2621501162915151 -2 14.47918298650684 + vertex 0.2616713673019718 -2 15.21837293427887 + vertex -0.3780284691315897 -2 14.84793992907052 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.571095512473512 -2 7.813724840775315 + vertex -4.212127115652919 -2 7.441346717776255 + vertex -3.570329684939122 -2 7.074272975303291 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.90123830670875 -2 7.806428172584075 + vertex 2.82495189991042 -2 8.55714936857806 + vertex 2.196371620835734 -2 8.184302070812972 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.209009251719478 -2 5.223245738263447 + vertex -3.567582490873732 -2 4.857204469194036 + vertex -3.568862881360346 -2 5.595925390348749 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.931659578289811 -2 8.184142773686492 + vertex -3.571807950105613 -2 8.553763073372794 + vertex -3.571095512473512 -2 7.813724840775315 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.208438527063897 -2 5.963155885859062 + vertex -4.209009251719478 -2 5.223245738263447 + vertex -3.568862881360346 -2 5.595925390348749 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.019481218622897 -2 16.6954608729413 + vertex -0.379347168317705 -2 16.32651775590352 + vertex -0.3801064849407917 -2 17.06537813209188 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.298947996151707 -2 17.43305243895607 + vertex -1.659306952361946 -2 17.0643366164128 + vertex -1.659883570574173 -2 17.80266468206202 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.930931160526439 -2 7.44415012737228 + vertex -2.931659578289811 -2 8.184142773686492 + vertex -3.571095512473512 -2 7.813724840775315 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.545624187113257 -2 5.599501849506099 + vertex 2.182554547454119 -2 5.230533569883978 + vertex 2.185232814302425 -2 5.968730859613472 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3773902298450702 -2 13.36861719265928 + vertex 0.2619063412532773 -2 12.99885071109408 + vertex 0.2621797376126783 -2 13.7391008740004 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.546065482251067 -2 7.815243539277521 + vertex 1.544564088479184 -2 7.07714010847899 + vertex 2.18153235290545 -2 7.44215962233644 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822557155252714 -2 3.387632755075639 + vertex 3.463331557016295 -2 3.757543544245052 + vertex 2.822556644375143 -2 4.124490635138393 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.293774322911373 -2 11.51846628468102 + vertex -2.293288036902054 -2 10.77608571143553 + vertex -1.654202488256953 -2 11.14650870766094 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.019481218622897 -2 16.6954608729413 + vertex -1.019083154061386 -2 15.95650508483111 + vertex -0.379347168317705 -2 16.32651775590352 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.929531178456435 -2 5.965875378129123 + vertex -2.930232502934852 -2 6.704696743476191 + vertex -3.569567353810506 -2 6.334929572314016 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.462650155081207 -2 15.59090371298797 + vertex 4.199305772116119 -2 15.33013572378729 + vertex 4.137906133270736 -2 15.9931810658391 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.90123830670875 -2 7.806428172584075 + vertex 2.196371620835734 -2 8.184302070812972 + vertex 2.18153235290545 -2 7.44215962233644 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.019083154061386 -2 15.95650508483111 + vertex -1.018444238152855 -2 15.21764129910152 + vertex -0.3786352136969205 -2 15.58732630756997 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.184470845550166 -2 3.755927490778999 + vertex 2.822556644375143 -2 4.124490635138393 + vertex 2.184215443647103 -2 4.492955698672738 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 2.806455387130034 -2 7.0476518507815 + vertex 2.18153235290545 -2 7.44215962233644 + vertex 2.185104942443486 -2 6.707720985192397 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.019083154061386 -2 15.95650508483111 + vertex -1.658761451313555 -2 16.32606118587461 + vertex -1.658586945552809 -2 15.58744135521406 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.815981112413922 -2 6.338245174195091 + vertex 3.532384274596081 -2 6.709175634538488 + vertex 2.806455387130034 -2 7.0476518507815 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.462650155081207 -2 15.59090371298797 + vertex 3.522482822207098 -2 14.91581723933913 + vertex 4.199305772116119 -2 15.33013572378729 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.930931160526439 -2 7.44415012737228 + vertex -3.571095512473512 -2 7.813724840775315 + vertex -3.570329684939122 -2 7.074272975303291 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.019083154061386 -2 15.95650508483111 + vertex -0.3786352136969205 -2 15.58732630756997 + vertex -0.379347168317705 -2 16.32651775590352 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.659306952361946 -2 17.0643366164128 + vertex -1.658761451313555 -2 16.32606118587461 + vertex -1.019481218622897 -2 16.6954608729413 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.930232502934852 -2 6.704696743476191 + vertex -2.930931160526439 -2 7.44415012737228 + vertex -3.570329684939122 -2 7.074272975303291 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.659306952361946 -2 17.0643366164128 + vertex -1.019481218622897 -2 16.6954608729413 + vertex -1.020053807512184 -2 17.43409147419257 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.289818850739709 -2 5.597134858359751 + vertex -2.928586644196474 -2 5.227460072678477 + vertex -2.289306234888224 -2 4.859074588876906 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.2582962276091168 -2 18.91107228975501 + vertex -0.3796622136127862 -2 18.54169448313185 + vertex 0.2586041205171401 -2 18.17353338690858 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.537387511094098 -2 17.43664012471537 + vertex 1.538184117266838 -2 16.6980286242731 + vertex 2.177872523023615 -2 17.06825030927862 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.2699326265064667 -2 4.123817115890558 + vertex -0.3706777379366633 -2 4.49175823877602 + vertex -0.3673592852575696 -2 3.754963435869593 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.460916694941177 -2 3.018947459590255 + vertex 4.112611094014032 -2 3.432801665914139 + vertex 3.463331557016295 -2 3.757543544245052 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.545725985940266 -2 4.861627066226085 + vertex 2.182554547454119 -2 5.230533569883978 + vertex 1.545624187113257 -2 5.599501849506099 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.806455387130034 -2 7.0476518507815 + vertex 2.90123830670875 -2 7.806428172584075 + vertex 2.18153235290545 -2 7.44215962233644 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.185232814302425 -2 5.968730859613472 + vertex 2.815981112413922 -2 6.338245174195091 + vertex 2.185104942443486 -2 6.707720985192397 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.537387511094098 -2 17.43664012471537 + vertex 2.176263957268402 -2 17.80664230692357 + vertex 1.536525565386907 -2 18.17497431780669 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.815981112413922 -2 6.338245174195091 + vertex 2.806455387130034 -2 7.0476518507815 + vertex 2.185104942443486 -2 6.707720985192397 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.218601027446049 -2 18.53871904559627 + vertex -4.218284649586943 -2 17.79834270098642 + vertex -3.578321844044858 -2 18.1702037050324 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.545624187113257 -2 5.599501849506099 + vertex 2.185232814302425 -2 5.968730859613472 + vertex 1.545532470823523 -2 6.337800945684743 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.930232502934852 -2 6.704696743476191 + vertex -3.570329684939122 -2 7.074272975303291 + vertex -3.569567353810506 -2 6.334929572314016 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.537387511094098 -2 17.43664012471537 + vertex 2.177872523023615 -2 17.06825030927862 + vertex 2.176263957268402 -2 17.80664230692357 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2669669974803863 -2 6.337218674499295 + vertex 0.2666883617078354 -2 7.076125879193936 + vertex -0.3726607962426137 -2 6.706414694889876 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.019481218622897 -2 16.6954608729413 + vertex -1.658761451313555 -2 16.32606118587461 + vertex -1.019083154061386 -2 15.95650508483111 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.929531178456435 -2 5.965875378129123 + vertex -3.569567353810506 -2 6.334929572314016 + vertex -3.568862881360346 -2 5.595925390348749 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.566666666666677 -2 21.5 + vertex -2.143283607768725 -2 20.83849238848145 + vertex -1.833333333333345 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.3666666666666831 -2 1.5 + vertex 0.003832493913557831 -2 2.100914919519724 + vertex -0.3666666666666538 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3666666666666831 -2 21.5 + vertex 0.0208654791378333 -2 20.83956576945508 + vertex 0.3666666666666538 -2 21.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.012364211165075 -2 19.66731864785164 + vertex -1.016913363682256 -2 18.91113701755697 + vertex -0.3780717967151275 -2 19.27660998370631 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.569567353810506 -2 6.334929572314016 + vertex -4.208438527063897 -2 5.963155885859062 + vertex -3.568862881360346 -2 5.595925390348749 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.185232814302425 -2 5.968730859613472 + vertex 2.185104942443486 -2 6.707720985192397 + vertex 1.545532470823523 -2 6.337800945684743 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.93854539660131 -2 17.80165228789176 + vertex -2.937604350828722 -2 17.06405012681465 + vertex -2.298947996151707 -2 17.43305243895607 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.929531178456435 -2 5.965875378129123 + vertex -3.568862881360346 -2 5.595925390348749 + vertex -2.928586644196474 -2 5.227460072678477 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.545624187113257 -2 5.599501849506099 + vertex 1.545532470823523 -2 6.337800945684743 + vertex 0.9063840879461926 -2 5.968317219257086 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.833333333333327 -2 21.5 + vertex 2.191479158001644 -2 20.84385449502374 + vertex 2.566666666666663 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.566666666666677 -2 1.5 + vertex 2.19617203703488 -2 2.164389513344334 + vertex 1.833333333333345 -2 1.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.928586644196474 -2 5.227460072678477 + vertex -3.567582490873732 -2 4.857204469194036 + vertex -2.927736629004366 -2 4.48943194994477 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8978041598760911 -2 17.80513101507281 + vertex 1.537387511094098 -2 17.43664012471537 + vertex 1.536525565386907 -2 18.17497431780669 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.451560276391819 -2 19.28475070461192 + vertex 4.04244324160653 -2 19.64710479876006 + vertex 3.450126181270477 -2 20.02186022077733 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.289818850739709 -2 5.597134858359751 + vertex -2.929531178456435 -2 5.965875378129123 + vertex -2.928586644196474 -2 5.227460072678477 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.014349597196187 -2 10.03571453406039 + vertex -1.653063152461363 -2 10.40602028869827 + vertex -1.653879319330478 -2 9.665289938033174 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.566045361185739 -2 4.119718267295393 + vertex -4.210490532425202 -2 3.738913142095867 + vertex -3.557504597528008 -2 3.394518219884866 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.300000000000008 -2 21.5 + vertex -2.936485214511291 -2 20.74314212984447 + vertex -2.566666666666677 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2598502869479086 -2 16.69668717560763 + vertex 0.8985878540850494 -2 17.06665959501147 + vertex 0.2589630319562187 -2 17.43538646129365 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.833333333333327 -2 1.5 + vertex -2.167576414659461 -2 2.088616667700339 + vertex -2.566666666666663 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.538184117266838 -2 16.6980286242731 + vertex 2.179344469681174 -2 16.32918499547299 + vertex 2.177872523023615 -2 17.06825030927862 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.568862881360346 -2 5.595925390348749 + vertex -3.567582490873732 -2 4.857204469194036 + vertex -2.928586644196474 -2 5.227460072678477 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.927736629004366 -2 4.48943194994477 + vertex -3.567582490873732 -2 4.857204469194036 + vertex -3.566045361185739 -2 4.119718267295393 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.184215443647103 -2 4.492955698672738 + vertex 2.182554547454119 -2 5.230533569883978 + vertex 1.545725985940266 -2 4.861627066226085 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.544564088479184 -2 7.07714010847899 + vertex 0.9059229234557202 -2 6.706979342847852 + vertex 1.545532470823523 -2 6.337800945684743 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.033333333333339 -2 21.5 + vertex -3.726672676383709 -2 20.83844788109646 + vertex -3.300000000000008 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.578321844044858 -2 18.1702037050324 + vertex -3.577418856687067 -2 17.43210191226107 + vertex -2.93854539660131 -2 17.80165228789176 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.177872523023615 -2 17.06825030927862 + vertex 2.81837767774294 -2 17.43790224669241 + vertex 2.176263957268402 -2 17.80664230692357 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.033333333333339 -2 1.5 + vertex 3.568127706497573 -2 2.217660997012953 + vertex 3.300000000000008 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.299999999999997 -2 21.5 + vertex 3.562175811593016 -2 20.80826400883117 + vertex 4.033333333333331 -2 21.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.537387511094098 -2 17.43664012471537 + vertex 0.8985878540850494 -2 17.06665959501147 + vertex 1.538184117266838 -2 16.6980286242731 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2598502869479086 -2 16.69668717560763 + vertex 0.8993938462757792 -2 16.32800498524945 + vertex 0.8985878540850494 -2 17.06665959501147 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.298947996151707 -2 17.43305243895607 + vertex -2.298184202148266 -2 16.69520593289531 + vertex -1.659306952361946 -2 17.0643366164128 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.816046427378849 -2 18.17726903057125 + vertex 3.453012982194295 -2 18.54804954286075 + vertex 2.813820309881157 -2 18.91498790393246 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.538184117266838 -2 16.6980286242731 + vertex 1.539167618242686 -2 15.95899815352942 + vertex 2.179344469681174 -2 16.32918499547299 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.566666666666663 -2 1.5 + vertex -2.934242593271455 -2 2.25495040931872 + vertex -3.299999999999997 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.929531178456435 -2 5.965875378129123 + vertex -2.290609693464181 -2 6.335397328141654 + vertex -2.930232502934852 -2 6.704696743476191 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.659306952361946 -2 17.0643366164128 + vertex -2.298184202148266 -2 16.69520593289531 + vertex -1.658761451313555 -2 16.32606118587461 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.463331557016295 -2 3.757543544245052 + vertex 3.462425096906818 -2 4.496226693199438 + vertex 2.822556644375143 -2 4.124490635138393 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.182554547454119 -2 5.230533569883978 + vertex 2.819993447812174 -2 4.861821755936887 + vertex 2.812214953593998 -2 5.599116113034341 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 7.425925925925949 + vertex -4.857776399823164 -2 7.800662819528365 + vertex -5.5 -2 8.166666666666694 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2589630319562187 -2 17.43538646129365 + vertex 0.8985878540850494 -2 17.06665959501147 + vertex 0.8978041598760911 -2 17.80513101507281 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.652223002598351 -2 6.705412755708672 + vertex -2.290609693464181 -2 6.335397328141654 + vertex -1.65101878611046 -2 5.966826581804315 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8985878540850494 -2 17.06665959501147 + vertex 0.8993938462757792 -2 16.32800498524945 + vertex 1.538184117266838 -2 16.6980286242731 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.208438527063897 -2 5.963155885859062 + vertex -4.851864159626067 -2 5.586500667836441 + vertex -4.209009251719478 -2 5.223245738263447 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.218284649586943 -2 17.79834270098642 + vertex -3.577418856687067 -2 17.43210191226107 + vertex -3.578321844044858 -2 18.1702037050324 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.937604350828722 -2 17.06405012681465 + vertex -2.298184202148266 -2 16.69520593289531 + vertex -2.298947996151707 -2 17.43305243895607 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9063840879461926 -2 5.968317219257086 + vertex 0.9059229234557202 -2 6.706979342847852 + vertex 0.2669669974803863 -2 6.337218674499295 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8978041598760911 -2 17.80513101507281 + vertex 0.8985878540850494 -2 17.06665959501147 + vertex 1.537387511094098 -2 17.43664012471537 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.212127115652919 -2 7.441346717776255 + vertex -4.210009374814977 -2 6.700367524307542 + vertex -3.570329684939122 -2 7.074272975303291 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.93854539660131 -2 17.80165228789176 + vertex -3.577418856687067 -2 17.43210191226107 + vertex -2.937604350828722 -2 17.06405012681465 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.545532470823523 -2 6.337800945684743 + vertex 0.9059229234557202 -2 6.706979342847852 + vertex 0.9063840879461926 -2 5.968317219257086 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.299999999999997 -2 1.5 + vertex -3.725708524847097 -2 2.163541749977668 + vertex -4.033333333333331 -2 1.5 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.541321577020518 -2 13.73968876156753 + vertex 0.9019915256673547 -2 14.10944513363794 + vertex 0.9020817508314349 -2 13.37014429011399 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858262682337108 -2 8.538487430234987 + vertex -4.859025766115733 -2 9.280652951284694 + vertex -5.5 -2 8.907407407407437 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.569567353810506 -2 6.334929572314016 + vertex -4.210009374814977 -2 6.700367524307542 + vertex -4.208438527063897 -2 5.963155885859062 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.65101878611046 -2 5.966826581804315 + vertex -2.290609693464181 -2 6.335397328141654 + vertex -2.289818850739709 -2 5.597134858359751 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.566666666666677 -2 21.5 + vertex -2.936485214511291 -2 20.74314212984447 + vertex -2.143283607768725 -2 20.83849238848145 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 6.685185185185206 + vertex -4.854100442035756 -2 6.32387803528496 + vertex -4.854290590709602 -2 7.063614504077036 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2669669974803863 -2 6.337218674499295 + vertex 0.9059229234557202 -2 6.706979342847852 + vertex 0.2666883617078354 -2 7.076125879193936 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.176263957268402 -2 17.80664230692357 + vertex 2.81837767774294 -2 17.43790224669241 + vertex 2.816046427378849 -2 18.17726903057125 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2621501162915151 -2 14.47918298650684 + vertex 0.9019915256673547 -2 14.10944513363794 + vertex 0.9014106653126999 -2 14.84948437361024 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.289818850739709 -2 5.597134858359751 + vertex -2.290609693464181 -2 6.335397328141654 + vertex -2.929531178456435 -2 5.965875378129123 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 9.648148148148179 + vertex -4.859025766115733 -2 9.280652951284694 + vertex -4.858499700900419 -2 10.01851851851855 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.078142303503325 -2 2.674263965434937 + vertex -1.74883458901402 -2 2.529533409221695 + vertex -1.458238078259432 -2 2.055198051546707 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.017404658776929 -2 13.73786746955996 + vertex -1.657005748105574 -2 14.10863196733877 + vertex -1.657207383403859 -2 13.36815951755871 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.571807950105613 -2 8.553763073372794 + vertex -4.211295871605629 -2 8.181800934136941 + vertex -3.571095512473512 -2 7.813724840775315 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.451560276391819 -2 19.28475070461192 + vertex 4.090847999373175 -2 18.91688194045436 + vertex 4.04244324160653 -2 19.64710479876006 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.296560192048382 -2 14.4787322337115 + vertex -2.297184786416162 -2 15.21830717087623 + vertex -2.936008509214679 -2 14.84857666890852 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2629865536171161 -2 12.25924761449043 + vertex 0.9044505518129392 -2 11.88904062794034 + vertex 0.9030491369272273 -2 12.63007468708392 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2629865536171161 -2 12.25924761449043 + vertex 0.2619063412532773 -2 12.99885071109408 + vertex -0.3766763580637025 -2 12.62819035942791 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.544644799008981 -2 11.51710820666931 + vertex 0.9044505518129392 -2 11.88904062794034 + vertex 0.9037758590567562 -2 11.14751413629097 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3773902298450702 -2 13.36861719265928 + vertex 0.2621797376126783 -2 13.7391008740004 + vertex -0.3774731583634351 -2 14.10858624217519 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.935308886475556 -2 14.10836185815992 + vertex -2.296314174206497 -2 13.73830655589307 + vertex -2.296560192048382 -2 14.4787322337115 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.115961526634615 -2 17.43426003489867 + vertex 4.100793025011158 -2 18.17905243801717 + vertex 3.461038152320298 -2 17.80933948973989 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.657005748105574 -2 14.10863196733877 + vertex -1.657503037368121 -2 14.84862210189439 + vertex -2.296560192048382 -2 14.4787322337115 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.822556644375143 -2 4.124490635138393 + vertex 2.819993447812174 -2 4.861821755936887 + vertex 2.184215443647103 -2 4.492955698672738 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.726672676383709 -2 20.83844788109646 + vertex -2.936485214511291 -2 20.74314212984447 + vertex -3.300000000000008 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2666883617078354 -2 7.076125879193936 + vertex 0.905819969722834 -2 7.445945337647904 + vertex 0.2671505761328858 -2 7.815840390950871 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.572024714500107 -2 9.294398673700472 + vertex -4.211133059312831 -2 9.664172439558234 + vertex -4.213339441084396 -2 8.923744763240448 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.2621797376126783 -2 13.7391008740004 + vertex 0.2619063412532773 -2 12.99885071109408 + vertex 0.9020817508314349 -2 13.37014429011399 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.567582490873732 -2 4.857204469194036 + vertex -4.208972798762589 -2 4.482363263387334 + vertex -3.566045361185739 -2 4.119718267295393 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.167576414659461 -2 2.088616667700339 + vertex -2.934242593271455 -2 2.25495040931872 + vertex -2.566666666666663 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8993938462757792 -2 16.32800498524945 + vertex 0.9005392632235447 -2 15.58878052464804 + vertex 1.539167618242686 -2 15.95899815352942 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.570329684939122 -2 7.074272975303291 + vertex -4.210009374814977 -2 6.700367524307542 + vertex -3.569567353810506 -2 6.334929572314016 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.21512821818804 -2 11.14017985693962 + vertex -4.213919187107948 -2 10.40043495237732 + vertex -3.573122554230794 -2 10.77535438049067 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2611954692988795 -2 15.95761504188607 + vertex 0.8993938462757792 -2 16.32800498524945 + vertex 0.2598502869479086 -2 16.69668717560763 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.544564088479184 -2 7.07714010847899 + vertex 0.905819969722834 -2 7.445945337647904 + vertex 0.9059229234557202 -2 6.706979342847852 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.296560192048382 -2 14.4787322337115 + vertex -1.657503037368121 -2 14.84862210189439 + vertex -2.297184786416162 -2 15.21830717087623 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.546065482251067 -2 7.815243539277521 + vertex 0.9055326313318334 -2 8.185955823557885 + vertex 0.905819969722834 -2 7.445945337647904 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.543602769126001 -2 13.0006143682726 + vertex 0.9030491369272273 -2 12.63007468708392 + vertex 1.548263848345031 -2 12.25974285150989 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2621501162915151 -2 14.47918298650684 + vertex 0.9014106653126999 -2 14.84948437361024 + vertex 0.2616713673019718 -2 15.21837293427887 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.290609693464181 -2 6.335397328141654 + vertex -2.2914199112036 -2 7.074204631513616 + vertex -2.930232502934852 -2 6.704696743476191 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900418 -2 10.75925925925928 + vertex -4.857371180699295 -2 11.50433517481844 + vertex -5.5 -2 11.12962962962965 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.184215443647103 -2 4.492955698672738 + vertex 2.819993447812174 -2 4.861821755936887 + vertex 2.182554547454119 -2 5.230533569883978 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 3.462425096906818 -2 4.496226693199438 + vertex 2.819993447812174 -2 4.861821755936887 + vertex 2.822556644375143 -2 4.124490635138393 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 11.87037037037039 + vertex -4.857371180699295 -2 11.50433517481844 + vertex -4.858499700900419 -2 12.24074074074076 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.932061770091924 -2 9.665124186191072 + vertex -2.293529619717956 -2 9.295319786271589 + vertex -2.29305276278285 -2 10.03456254762132 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.209009251719478 -2 5.223245738263447 + vertex -4.208972798762589 -2 4.482363263387334 + vertex -3.567582490873732 -2 4.857204469194036 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9059229234557202 -2 6.706979342847852 + vertex 0.905819969722834 -2 7.445945337647904 + vertex 0.2666883617078354 -2 7.076125879193936 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.813820309881157 -2 18.91498790393246 + vertex 3.453012982194295 -2 18.54804954286075 + vertex 3.451560276391819 -2 19.28475070461192 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.015805467510334 -2 11.51730017583935 + vertex -1.654833933336664 -2 11.88758380001475 + vertex -1.654202488256953 -2 11.14650870766094 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2611954692988795 -2 15.95761504188607 + vertex 0.9005392632235447 -2 15.58878052464804 + vertex 0.8993938462757792 -2 16.32800498524945 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.930232502934852 -2 6.704696743476191 + vertex -2.2914199112036 -2 7.074204631513616 + vertex -2.930931160526439 -2 7.44415012737228 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.538184117266838 -2 16.6980286242731 + vertex 0.8993938462757792 -2 16.32800498524945 + vertex 1.539167618242686 -2 15.95899815352942 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.294798722082105 -2 12.25814924190241 + vertex -2.296221576184843 -2 12.99816079370306 + vertex -2.934268742123706 -2 12.6273540928905 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936690955264944 -2 15.58819721247742 + vertex -2.937020546194905 -2 16.32635623317659 + vertex -3.576255991129901 -2 15.95640675516809 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.654833933336664 -2 11.88758380001475 + vertex -1.656052021671596 -2 12.62807046985316 + vertex -2.294798722082105 -2 12.25814924190241 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2616713673019718 -2 15.21837293427887 + vertex 0.9005392632235447 -2 15.58878052464804 + vertex 0.2611954692988795 -2 15.95761504188607 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.652223002598351 -2 6.705412755708672 + vertex -2.2914199112036 -2 7.074204631513616 + vertex -2.290609693464181 -2 6.335397328141654 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.658761451313555 -2 16.32606118587461 + vertex -2.297912436752781 -2 15.95707789834004 + vertex -1.658586945552809 -2 15.58744135521406 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3746676392718538 -2 10.4063799512949 + vertex 0.2646862774917507 -2 10.77704715318259 + vertex -0.3751518171424401 -2 11.14736947415786 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.937020546194905 -2 16.32635623317659 + vertex -3.576705497874402 -2 16.69344199335506 + vertex -3.576255991129901 -2 15.95640675516809 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.573556398640321 -2 11.5159427770449 + vertex -4.212099464206894 -2 11.88583119197091 + vertex -4.21512821818804 -2 11.14017985693962 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9014106653126999 -2 14.84948437361024 + vertex 0.9019915256673547 -2 14.10944513363794 + vertex 1.540578471458792 -2 14.47984021110212 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.566045361185739 -2 4.119718267295393 + vertex -4.208972798762589 -2 4.482363263387334 + vertex -4.210490532425202 -2 3.738913142095867 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.018444238152855 -2 15.21764129910152 + vertex -1.657503037368121 -2 14.84862210189439 + vertex -1.017604372424323 -2 14.4781092538168 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.540447376670603 -2 15.21980574900389 + vertex 0.9014106653126999 -2 14.84948437361024 + vertex 1.540578471458792 -2 14.47984021110212 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.932416393902854 -2 10.40506856825943 + vertex -2.293288036902054 -2 10.77608571143553 + vertex -2.933219101096931 -2 11.14588787169219 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.2914199112036 -2 7.074204631513616 + vertex -2.29234907452298 -2 7.814079405451854 + vertex -2.930931160526439 -2 7.44415012737228 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9037758590567562 -2 11.14751413629097 + vertex 0.9045038983852878 -2 10.40717947355589 + vertex 1.541632467723097 -2 10.77769188745804 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.905819969722834 -2 7.445945337647904 + vertex 0.9055326313318334 -2 8.185955823557885 + vertex 0.2671505761328858 -2 7.815840390950871 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3751518171424401 -2 11.14736947415786 + vertex 0.2641422182702875 -2 11.51762814211468 + vertex -0.3758325625919503 -2 11.88829022912528 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 8.166666666666694 + vertex -4.857776399823164 -2 7.800662819528365 + vertex -4.858262682337108 -2 8.538487430234987 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.216933704909376 -2 15.58411418009348 + vertex -4.217715539572408 -2 16.32123053081938 + vertex -4.860656951472551 -2 15.94818091204004 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.654202488256953 -2 11.14650870766094 + vertex -1.653063152461363 -2 10.40602028869827 + vertex -1.015223229097348 -2 10.77672264183186 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900418 -2 12.9814814814815 + vertex -4.857691379326242 -2 13.72637819811415 + vertex -5.5 -2 13.35185185185187 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 15.57407407407408 + vertex -4.860656951472551 -2 15.94818091204004 + vertex -5.5 -2 16.31481481481482 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 14.09259259259261 + vertex -4.857691379326242 -2 13.72637819811415 + vertex -4.858499700900419 -2 14.46296296296297 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.017139898840178 -2 12.9982754305505 + vertex -1.656052021671596 -2 12.62807046985316 + vertex -1.016110616181929 -2 12.25809403538951 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.216057034610309 -2 13.36202290232499 + vertex -4.215677787774949 -2 12.62062645531099 + vertex -3.574595658136062 -2 12.99710602982787 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.014349597196187 -2 10.03571453406039 + vertex -1.653879319330478 -2 9.665289938033174 + vertex -1.014335245614432 -2 9.295231348231319 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.546065482251067 -2 7.815243539277521 + vertex 0.905819969722834 -2 7.445945337647904 + vertex 1.544564088479184 -2 7.07714010847899 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.299999999999997 -2 1.5 + vertex -2.934242593271455 -2 2.25495040931872 + vertex -3.725708524847097 -2 2.163541749977668 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.539167618242686 -2 15.95899815352942 + vertex 0.9005392632235447 -2 15.58878052464804 + vertex 1.540447376670603 -2 15.21980574900389 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.451560276391819 -2 19.28475070461192 + vertex 3.453012982194295 -2 18.54804954286075 + vertex 4.090847999373175 -2 18.91688194045436 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.653879319330478 -2 9.665289938033174 + vertex -1.653063152461363 -2 10.40602028869827 + vertex -2.29305276278285 -2 10.03456254762132 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.933219101096931 -2 11.14588787169219 + vertex -2.293774322911373 -2 11.51846628468102 + vertex -2.933457838749669 -2 11.8870692343648 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.575103169386946 -2 13.73759135621609 + vertex -4.215605853511458 -2 14.10321060824816 + vertex -4.216057034610309 -2 13.36202290232499 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.216933704909376 -2 15.58411418009348 + vertex -4.216481903738938 -2 14.84237989301814 + vertex -3.576030909554856 -2 15.21816507115986 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.653828429200071 -2 7.44475907091302 + vertex -2.2914199112036 -2 7.074204631513616 + vertex -1.652223002598351 -2 6.705412755708672 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.571095512473512 -2 7.813724840775315 + vertex -4.211295871605629 -2 8.181800934136941 + vertex -4.212127115652919 -2 7.441346717776255 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.540578471458792 -2 14.47984021110212 + vertex 0.9019915256673547 -2 14.10944513363794 + vertex 1.541321577020518 -2 13.73968876156753 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9005392632235447 -2 15.58878052464804 + vertex 0.9014106653126999 -2 14.84948437361024 + vertex 1.540447376670603 -2 15.21980574900389 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.217241391147802 -2 17.06005415907445 + vertex -3.576705497874402 -2 16.69344199335506 + vertex -3.577418856687067 -2 17.43210191226107 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.29234907452298 -2 7.814079405451854 + vertex -2.293099423165164 -2 8.554664272928441 + vertex -2.931659578289811 -2 8.184142773686492 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.935281513827058 -2 13.36791463067939 + vertex -2.296314174206497 -2 13.73830655589307 + vertex -2.935308886475556 -2 14.10836185815992 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.9019915256673547 -2 14.10944513363794 + vertex 0.2621797376126783 -2 13.7391008740004 + vertex 0.9020817508314349 -2 13.37014429011399 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.017604372424323 -2 14.4781092538168 + vertex -1.657005748105574 -2 14.10863196733877 + vertex -1.017404658776929 -2 13.73786746955996 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.935281513827058 -2 13.36791463067939 + vertex -2.296221576184843 -2 12.99816079370306 + vertex -2.296314174206497 -2 13.73830655589307 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.930931160526439 -2 7.44415012737228 + vertex -2.29234907452298 -2 7.814079405451854 + vertex -2.931659578289811 -2 8.184142773686492 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2616713673019718 -2 15.21837293427887 + vertex 0.9014106653126999 -2 14.84948437361024 + vertex 0.9005392632235447 -2 15.58878052464804 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.653828429200071 -2 7.44475907091302 + vertex -2.29234907452298 -2 7.814079405451854 + vertex -2.2914199112036 -2 7.074204631513616 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2671505761328858 -2 7.815840390950871 + vertex 0.9055326313318334 -2 8.185955823557885 + vertex 0.2675047632069562 -2 8.556216284841577 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 8.907407407407437 + vertex -4.859025766115733 -2 9.280652951284694 + vertex -5.5 -2 9.648148148148179 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.297912436752781 -2 15.95707789834004 + vertex -2.297184786416162 -2 15.21830717087623 + vertex -1.658586945552809 -2 15.58744135521406 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3774731583634351 -2 14.10858624217519 + vertex 0.2621797376126783 -2 13.7391008740004 + vertex 0.2621501162915151 -2 14.47918298650684 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.937604350828722 -2 17.06405012681465 + vertex -2.937020546194905 -2 16.32635623317659 + vertex -2.298184202148266 -2 16.69520593289531 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.296560192048382 -2 14.4787322337115 + vertex -2.296314174206497 -2 13.73830655589307 + vertex -1.657005748105574 -2 14.10863196733877 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.298184202148266 -2 16.69520593289531 + vertex -2.297912436752781 -2 15.95707789834004 + vertex -1.658761451313555 -2 16.32606118587461 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.296314174206497 -2 13.73830655589307 + vertex -2.296221576184843 -2 12.99816079370306 + vertex -1.657207383403859 -2 13.36815951755871 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.657005748105574 -2 14.10863196733877 + vertex -2.296314174206497 -2 13.73830655589307 + vertex -1.657207383403859 -2 13.36815951755871 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3766763580637025 -2 12.62819035942791 + vertex 0.2619063412532773 -2 12.99885071109408 + vertex -0.3773902298450702 -2 13.36861719265928 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.546927139036397 -2 8.555854635114024 + vertex 0.9055326313318334 -2 8.185955823557885 + vertex 1.546065482251067 -2 7.815243539277521 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.931366460525708 -2 8.924672563442744 + vertex -2.293099423165164 -2 8.554664272928441 + vertex -2.293529619717956 -2 9.295319786271589 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.654746267724451 -2 8.184879985401814 + vertex -2.29234907452298 -2 7.814079405451854 + vertex -1.653828429200071 -2 7.44475907091302 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.573011778277769 -2 10.03490946631051 + vertex -4.211133059312831 -2 9.664172439558234 + vertex -3.572024714500107 -2 9.294398673700472 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.933457838749669 -2 11.8870692343648 + vertex -2.293774322911373 -2 11.51846628468102 + vertex -2.294798722082105 -2 12.25814924190241 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.548263848345031 -2 12.25974285150989 + vertex 0.9044505518129392 -2 11.88904062794034 + vertex 1.544644799008981 -2 11.51710820666931 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.654746267724451 -2 8.184879985401814 + vertex -2.293099423165164 -2 8.554664272928441 + vertex -2.29234907452298 -2 7.814079405451854 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.294798722082105 -2 12.25814924190241 + vertex -1.656052021671596 -2 12.62807046985316 + vertex -2.296221576184843 -2 12.99816079370306 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936008509214679 -2 14.84857666890852 + vertex -2.297184786416162 -2 15.21830717087623 + vertex -2.936690955264944 -2 15.58819721247742 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9020817508314349 -2 13.37014429011399 + vertex 0.9030491369272273 -2 12.63007468708392 + vertex 1.543602769126001 -2 13.0006143682726 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.573011778277769 -2 10.03490946631051 + vertex -4.213919187107948 -2 10.40043495237732 + vertex -4.211133059312831 -2 9.664172439558234 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3758325625919503 -2 11.88829022912528 + vertex 0.2641422182702875 -2 11.51762814211468 + vertex 0.2629865536171161 -2 12.25924761449043 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.297184786416162 -2 15.21830717087623 + vertex -1.657503037368121 -2 14.84862210189439 + vertex -1.658586945552809 -2 15.58744135521406 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2629865536171161 -2 12.25924761449043 + vertex 0.9030491369272273 -2 12.63007468708392 + vertex 0.2619063412532773 -2 12.99885071109408 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.546927139036397 -2 8.555854635114024 + vertex 0.9053027220551045 -2 8.926255811114023 + vertex 0.9055326313318334 -2 8.185955823557885 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.573122554230794 -2 10.77535438049067 + vertex -4.213919187107948 -2 10.40043495237732 + vertex -3.573011778277769 -2 10.03490946631051 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9055326313318334 -2 8.185955823557885 + vertex 0.9053027220551045 -2 8.926255811114023 + vertex 0.2675047632069562 -2 8.556216284841577 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9044505518129392 -2 11.88904062794034 + vertex 0.2641422182702875 -2 11.51762814211468 + vertex 0.9037758590567562 -2 11.14751413629097 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.293529619717956 -2 9.295319786271589 + vertex -2.293099423165164 -2 8.554664272928441 + vertex -1.654945538210082 -2 8.924891123316154 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.014335245614432 -2 9.295231348231319 + vertex -1.653879319330478 -2 9.665289938033174 + vertex -1.654945538210082 -2 8.924891123316154 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.931659578289811 -2 8.184142773686492 + vertex -2.293099423165164 -2 8.554664272928441 + vertex -2.931366460525708 -2 8.924672563442744 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2669591324310077 -2 9.296440423959986 + vertex 0.9049177395366502 -2 9.666575219465681 + vertex 0.2655151456524666 -2 10.03621174168124 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.658586945552809 -2 15.58744135521406 + vertex -1.657503037368121 -2 14.84862210189439 + vertex -1.018444238152855 -2 15.21764129910152 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.937020546194905 -2 16.32635623317659 + vertex -2.297912436752781 -2 15.95707789834004 + vertex -2.298184202148266 -2 16.69520593289531 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.016110616181929 -2 12.25809403538951 + vertex -1.654833933336664 -2 11.88758380001475 + vertex -1.015805467510334 -2 11.51730017583935 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9049177395366502 -2 9.666575219465681 + vertex 0.9045038983852878 -2 10.40717947355589 + vertex 0.2655151456524666 -2 10.03621174168124 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2646862774917507 -2 10.77704715318259 + vertex 0.9045038983852878 -2 10.40717947355589 + vertex 0.9037758590567562 -2 11.14751413629097 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 11.12962962962965 + vertex -4.857371180699295 -2 11.50433517481844 + vertex -5.5 -2 11.87037037037039 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.576705497874402 -2 16.69344199335506 + vertex -4.217715539572408 -2 16.32123053081938 + vertex -3.576255991129901 -2 15.95640675516809 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2675047632069562 -2 8.556216284841577 + vertex 0.9053027220551045 -2 8.926255811114023 + vertex 0.2669591324310077 -2 9.296440423959986 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.931366460525708 -2 8.924672563442744 + vertex -2.293529619717956 -2 9.295319786271589 + vertex -2.932061770091924 -2 9.665124186191072 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.654833933336664 -2 11.88758380001475 + vertex -2.293774322911373 -2 11.51846628468102 + vertex -1.654202488256953 -2 11.14650870766094 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9053027220551045 -2 8.926255811114023 + vertex 0.9049177395366502 -2 9.666575219465681 + vertex 0.2669591324310077 -2 9.296440423959986 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.293529619717956 -2 9.295319786271589 + vertex -1.653879319330478 -2 9.665289938033174 + vertex -2.29305276278285 -2 10.03456254762132 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.858499700900416 -2 16.68518518518519 + vertex -4.217715539572408 -2 16.32123053081938 + vertex -4.217241391147802 -2 17.06005415907445 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2621501162915151 -2 14.47918298650684 + vertex 0.2621797376126783 -2 13.7391008740004 + vertex 0.9019915256673547 -2 14.10944513363794 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936690955264944 -2 15.58819721247742 + vertex -2.297184786416162 -2 15.21830717087623 + vertex -2.297912436752781 -2 15.95707789834004 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.654945538210082 -2 8.924891123316154 + vertex -2.293099423165164 -2 8.554664272928441 + vertex -1.654746267724451 -2 8.184879985401814 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.654202488256953 -2 11.14650870766094 + vertex -2.293288036902054 -2 10.77608571143553 + vertex -1.653063152461363 -2 10.40602028869827 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.574315167895597 -2 12.25657638551989 + vertex -4.212099464206894 -2 11.88583119197091 + vertex -3.573556398640321 -2 11.5159427770449 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.937604350828722 -2 17.06405012681465 + vertex -3.576705497874402 -2 16.69344199335506 + vertex -2.937020546194905 -2 16.32635623317659 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.542467984840711 -2 9.29678151908432 + vertex 0.9053027220551045 -2 8.926255811114023 + vertex 1.546927139036397 -2 8.555854635114024 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.934268742123706 -2 12.6273540928905 + vertex -2.296221576184843 -2 12.99816079370306 + vertex -2.935281513827058 -2 13.36791463067939 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.541963627420545 -2 10.03723710428692 + vertex 0.9045038983852878 -2 10.40717947355589 + vertex 0.9049177395366502 -2 9.666575219465681 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.541963627420545 -2 10.03723710428692 + vertex 0.9049177395366502 -2 9.666575219465681 + vertex 1.542467984840711 -2 9.29678151908432 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 1.542467984840711 -2 9.29678151908432 + vertex 0.9049177395366502 -2 9.666575219465681 + vertex 0.9053027220551045 -2 8.926255811114023 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2655151456524666 -2 10.03621174168124 + vertex 0.2646862774917507 -2 10.77704715318259 + vertex -0.3746676392718538 -2 10.4063799512949 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 16.31481481481482 + vertex -4.860656951472551 -2 15.94818091204004 + vertex -4.858499700900416 -2 16.68518518518519 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.574315167895597 -2 12.25657638551989 + vertex -4.215677787774949 -2 12.62062645531099 + vertex -4.212099464206894 -2 11.88583119197091 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.936690955264944 -2 15.58819721247742 + vertex -2.297912436752781 -2 15.95707789834004 + vertex -2.937020546194905 -2 16.32635623317659 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -1.015223229097348 -2 10.77672264183186 + vertex -1.653063152461363 -2 10.40602028869827 + vertex -1.014349597196187 -2 10.03571453406039 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.657207383403859 -2 13.36815951755871 + vertex -1.656052021671596 -2 12.62807046985316 + vertex -1.017139898840178 -2 12.9982754305505 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.541632467723097 -2 10.77769188745804 + vertex 0.9045038983852878 -2 10.40717947355589 + vertex 1.541963627420545 -2 10.03723710428692 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.574595658136062 -2 12.99710602982787 + vertex -4.215677787774949 -2 12.62062645531099 + vertex -3.574315167895597 -2 12.25657638551989 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.29305276278285 -2 10.03456254762132 + vertex -2.293288036902054 -2 10.77608571143553 + vertex -2.932416393902854 -2 10.40506856825943 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 13.35185185185187 + vertex -4.857691379326242 -2 13.72637819811415 + vertex -5.5 -2 14.09259259259261 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.576030909554856 -2 15.21816507115986 + vertex -4.216481903738938 -2 14.84237989301814 + vertex -3.575835566622261 -2 14.47797604271785 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -3.575835566622261 -2 14.47797604271785 + vertex -4.215605853511458 -2 14.10321060824816 + vertex -3.575103169386946 -2 13.73759135621609 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.216481903738938 -2 14.84237989301814 + vertex -4.215605853511458 -2 14.10321060824816 + vertex -3.575835566622261 -2 14.47797604271785 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2619063412532773 -2 12.99885071109408 + vertex 0.9030491369272273 -2 12.63007468708392 + vertex 0.9020817508314349 -2 13.37014429011399 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.294798722082105 -2 12.25814924190241 + vertex -2.293774322911373 -2 11.51846628468102 + vertex -1.654833933336664 -2 11.88758380001475 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2629865536171161 -2 12.25924761449043 + vertex 0.2641422182702875 -2 11.51762814211468 + vertex 0.9044505518129392 -2 11.88904062794034 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.577418856687067 -2 17.43210191226107 + vertex -3.576705497874402 -2 16.69344199335506 + vertex -2.937604350828722 -2 17.06405012681465 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.217241391147802 -2 17.06005415907445 + vertex -4.217715539572408 -2 16.32123053081938 + vertex -3.576705497874402 -2 16.69344199335506 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.296221576184843 -2 12.99816079370306 + vertex -1.656052021671596 -2 12.62807046985316 + vertex -1.657207383403859 -2 13.36815951755871 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.654945538210082 -2 8.924891123316154 + vertex -1.653879319330478 -2 9.665289938033174 + vertex -2.293529619717956 -2 9.295319786271589 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.210009374814977 -2 6.700367524307542 + vertex -4.854100442035756 -2 6.32387803528496 + vertex -4.208438527063897 -2 5.963155885859062 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2655151456524666 -2 10.03621174168124 + vertex 0.9045038983852878 -2 10.40717947355589 + vertex 0.2646862774917507 -2 10.77704715318259 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.653063152461363 -2 10.40602028869827 + vertex -2.293288036902054 -2 10.77608571143553 + vertex -2.29305276278285 -2 10.03456254762132 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.076553335617876 -2 4.914212848582235 + vertex 3.448492090142694 -2 5.250232971015224 + vertex 3.462425096906818 -2 4.496226693199438 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.854290590709602 -2 7.063614504077036 + vertex -4.854100442035756 -2 6.32387803528496 + vertex -4.210009374814977 -2 6.700367524307542 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.874071970659501 -2 2.574806147906303 + vertex 4.162755411472946 -2 2.759371800359368 + vertex 4.36558344585119 -2 2.115214889306188 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -3.576255991129901 -2 15.95640675516809 + vertex -4.217715539572408 -2 16.32123053081938 + vertex -4.216933704909376 -2 15.58411418009348 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.462425096906818 -2 4.496226693199438 + vertex 3.448492090142694 -2 5.250232971015224 + vertex 2.819993447812174 -2 4.861821755936887 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.819993447812174 -2 4.861821755936887 + vertex 3.448492090142694 -2 5.250232971015224 + vertex 2.812214953593998 -2 5.599116113034341 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.208438527063897 -2 5.963155885859062 + vertex -4.854100442035756 -2 6.32387803528496 + vertex -4.851864159626067 -2 5.586500667836441 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.09999999999999 -2 1.5 + vertex -1.458238078259432 -2 2.055198051546707 + vertex -1.833333333333327 -2 1.5 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.110486200275591 -2 5.661411558946233 + vertex 3.409279506649708 -2 5.968608856392206 + vertex 3.448492090142694 -2 5.250232971015224 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.076553335617876 -2 4.914212848582235 + vertex 4.458357092750293 -2 5.242782729031642 + vertex 4.110486200275591 -2 5.661411558946233 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.110486200275591 -2 5.661411558946233 + vertex 4.458357092750293 -2 5.242782729031642 + vertex 4.858499700900416 -2 5.574074074074068 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.833333333333345 -2 21.5 + vertex -1.437299705222897 -2 20.87516284506514 + vertex -1.100000000000015 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.766666666666669 -2 21.5 + vertex -4.405426047799934 -2 20.88547754159565 + vertex -4.033333333333339 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.033333333333331 -2 21.5 + vertex 4.365583445851182 -2 20.88478511069381 + vertex 4.766666666666666 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.766666666666669 -2 1.5 + vertex 4.36558344585119 -2 2.115214889306188 + vertex 4.033333333333339 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.033333333333331 -2 1.5 + vertex -4.404546516961016 -2 2.116118090915069 + vertex -4.766666666666666 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.041626538302982 -2 20.31140730480241 + vertex 4.47165551143669 -2 19.95897091405205 + vertex 4.858499700900416 -2 20.38888888888889 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.157032824947297 -2 2.876268055139592 + vertex -3.472825915922042 -2 2.745571680351766 + vertex -3.557504597528008 -2 3.394518219884866 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.09999999999999 -2 1.5 + vertex -0.7333333333333218 -2 2.047299604942785 + vertex -1.458238078259432 -2 2.055198051546707 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.833333333333327 -2 1.5 + vertex -1.458238078259432 -2 2.055198051546707 + vertex -2.167576414659461 -2 2.088616667700339 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.815981112413922 -2 6.338245174195091 + vertex 3.409279506649708 -2 5.968608856392206 + vertex 3.532384274596081 -2 6.709175634538488 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.528722449664777 -2 2.638884480328281 + vertex 1.486329693465689 -2 1.994046019256764 + vertex 2.19617203703488 -2 2.164389513344334 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.448492090142694 -2 5.250232971015224 + vertex 3.409279506649708 -2 5.968608856392206 + vertex 2.812214953593998 -2 5.599116113034341 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3680149090001792 -2 3.06536071564342 + vertex 0.2348591938782687 -2 2.715163559101713 + vertex 0.2773268266497083 -2 3.39941422257154 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -1.716472977865604 -2 20.13191285697176 + vertex -2.407514177605579 -2 20.2710850041902 + vertex -2.302206729260642 -2 19.647231901849 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.458238078259432 -2 2.055198051546707 + vertex -0.7333333333333218 -2 2.047299604942785 + vertex -1.078142303503325 -2 2.674263965434937 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.003832493913557831 -2 2.100914919519724 + vertex -0.7333333333333218 -2 2.047299604942785 + vertex -0.3666666666666538 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.100000000000015 -2 1.5 + vertex 1.486329693465689 -2 1.994046019256764 + vertex 0.8127467008934494 -2 2.207667147874593 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.9112001278467288 -2 3.017183334678748 + vertex 0.2348591938782687 -2 2.715163559101713 + vertex 0.8127467008934494 -2 2.207667147874593 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2665658211570644 -2 19.63282180689279 + vertex 0.3310048212655636 -2 20.28022422492675 + vertex -0.3517984009234065 -2 20.14117242918954 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.8138538323647302 -2 20.78809710159216 + vertex 0.3310048212655636 -2 20.28022422492675 + vertex 0.9055373745915964 -2 19.99946401750414 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.100000000000015 -2 21.5 + vertex -0.6699669427066424 -2 20.89718328590129 + vertex -0.3666666666666831 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.842012940993464 -2 20.40449675698339 + vertex 2.933333333333329 -2 21.01692359780342 + vertex 2.191479158001644 -2 20.84385449502374 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.143283607768725 -2 20.83849238848145 + vertex -1.437299705222897 -2 20.87516284506514 + vertex -1.833333333333345 -2 21.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.033333333333339 -2 21.5 + vertex -4.405426047799934 -2 20.88547754159565 + vertex -3.726672676383709 -2 20.83844788109646 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.562175811593016 -2 20.80826400883117 + vertex 4.365583445851182 -2 20.88478511069381 + vertex 4.033333333333331 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.033333333333339 -2 1.5 + vertex 4.36558344585119 -2 2.115214889306188 + vertex 3.568127706497573 -2 2.217660997012953 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.725708524847097 -2 2.163541749977668 + vertex -4.404546516961016 -2 2.116118090915069 + vertex -4.033333333333331 -2 1.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -2.298332905758358 -2 3.40159593333896 + vertex -2.348118176010836 -2 2.75223995238126 + vertex -1.692097972637046 -2 3.077348409045236 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.566666666666677 -2 1.5 + vertex 2.894573521270469 -2 2.005347401248558 + vertex 2.19617203703488 -2 2.164389513344334 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.568127706497573 -2 2.217660997012953 + vertex 2.894573521270469 -2 2.005347401248558 + vertex 3.300000000000008 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.744074395475103 -2 16.33170939209035 + vertex 4.918821107332354 -2 15.78024179549353 + vertex 5.5 -2 16.3148148148148 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.57952350344234 -2 19.64741215066542 + vertex -3.469012145433474 -2 20.27171639072729 + vertex -4.163256974208401 -2 20.13493404822575 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.199305772116119 -2 15.33013572378729 + vertex 4.199825762598869 -2 14.66546628030377 + vertex 4.870582047868353 -2 15.09106547965763 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.115961526634615 -2 17.43426003489867 + vertex 4.655673760136614 -2 16.96466929801385 + vertex 4.853983791777436 -2 17.46298864682942 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.576676627398162 -2 7.779376729527785 + vertex 3.426996701041404 -2 8.351024862087794 + vertex 2.90123830670875 -2 7.806428172584075 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.464668476437278 -2 12.62973158487211 + vertex 3.562200465473438 -2 12.06310768263945 + vertex 4.215348947555784 -2 12.57974608201392 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 1.833333333333327 -2 21.5 + vertex 1.480298472225957 -2 21.00228949787716 + vertex 2.191479158001644 -2 20.84385449502374 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 20.75925925925926 + vertex -4.958455695605603 -2 20.95650076827917 + vertex -5.5 -2 21.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 21.5 + vertex 4.968788439014086 -2 20.96953853470181 + vertex 5.5 -2 20.75925925925926 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 2.24074074074074 + vertex 4.969599156931578 -2 2.028571369337921 + vertex 5.5 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 1.5 + vertex -4.958455695605594 -2 2.043499231720833 + vertex -5.5 -2 2.240740740740744 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.942690586882144 -2 11.51273307229485 + vertex 3.389269686093905 -2 11.0434416288251 + vertex 3.653422321959101 -2 11.49668106748853 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 21.5 + vertex -4.958455695605603 -2 20.95650076827917 + vertex -4.766666666666669 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 5.5 -2 1.5 + vertex 4.969599156931578 -2 2.028571369337921 + vertex 4.766666666666669 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.766666666666666 -2 21.5 + vertex 4.968788439014086 -2 20.96953853470181 + vertex 5.5 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.766666666666666 -2 1.5 + vertex -4.958455695605594 -2 2.043499231720833 + vertex -5.5 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.90123830670875 -2 7.806428172584075 + vertex 3.36872271763415 -2 7.293849202134684 + vertex 3.576676627398162 -2 7.779376729527785 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.191479158001644 -2 20.84385449502374 + vertex 2.933333333333329 -2 21.01692359780342 + vertex 2.566666666666663 -2 21.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 3.299999999999997 -2 21.5 + vertex 2.933333333333329 -2 21.01692359780342 + vertex 3.562175811593016 -2 20.80826400883117 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.812214953593998 -2 5.599116113034341 + vertex 3.409279506649708 -2 5.968608856392206 + vertex 2.815981112413922 -2 6.338245174195091 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.19617203703488 -2 2.164389513344334 + vertex 1.486329693465689 -2 1.994046019256764 + vertex 1.833333333333345 -2 1.5 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.870582047868353 -2 15.09106547965763 + vertex 4.199825762598869 -2 14.66546628030377 + vertex 4.875264150806977 -2 14.4094014084103 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 5.5 -2 16.3148148148148 + vertex 4.918821107332354 -2 15.78024179549353 + vertex 5.5 -2 15.57407407407405 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.90123830670875 -2 7.806428172584075 + vertex 3.426996701041404 -2 8.351024862087794 + vertex 2.82495189991042 -2 8.55714936857806 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.215348947555784 -2 12.57974608201392 + vertex 3.562200465473438 -2 12.06310768263945 + vertex 4.216602219501706 -2 11.87014423231384 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.09173318766436 -2 16.67721812266799 + vertex 4.655673760136614 -2 16.96466929801385 + vertex 4.115961526634615 -2 17.43426003489867 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.807399006272134 -2 10.74844508614493 + vertex 3.389269686093905 -2 11.0434416288251 + vertex 2.942690586882144 -2 11.51273307229485 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.806455387130034 -2 7.0476518507815 + vertex 3.36872271763415 -2 7.293849202134684 + vertex 2.90123830670875 -2 7.806428172584075 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -0.3680149090001792 -2 3.06536071564342 + vertex -0.4134064153154973 -2 2.481641226637574 + vertex 0.2348591938782687 -2 2.715163559101713 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.460916694941177 -2 3.018947459590255 + vertex 4.162755411472946 -2 2.759371800359368 + vertex 4.112611094014032 -2 3.432801665914139 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 0.2773268266497083 -2 3.39941422257154 + vertex 0.2348591938782687 -2 2.715163559101713 + vertex 0.9112001278467288 -2 3.017183334678748 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.36558344585119 -2 2.115214889306188 + vertex 4.162755411472946 -2 2.759371800359368 + vertex 3.568127706497573 -2 2.217660997012953 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8138538323647302 -2 20.78809710159216 + vertex 1.480298472225957 -2 21.00228949787716 + vertex 1.09999999999999 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.3666666666666538 -2 1.5 + vertex -0.7333333333333218 -2 2.047299604942785 + vertex -1.09999999999999 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.04244324160653 -2 19.64710479876006 + vertex 4.041626538302982 -2 20.31140730480241 + vertex 3.450126181270477 -2 20.02186022077733 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.8127467008934494 -2 2.207667147874593 + vertex 1.486329693465689 -2 1.994046019256764 + vertex 1.528722449664777 -2 2.638884480328281 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -0.3666666666666831 -2 21.5 + vertex -0.6699669427066424 -2 20.89718328590129 + vertex 0.0208654791378333 -2 20.83956576945508 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.9055373745915964 -2 19.99946401750414 + vertex 0.3310048212655636 -2 20.28022422492675 + vertex 0.2665658211570644 -2 19.63282180689279 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 0.2348591938782687 -2 2.715163559101713 + vertex -0.4134064153154973 -2 2.481641226637574 + vertex 0.003832493913557831 -2 2.100914919519724 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.300000000000008 -2 1.5 + vertex 2.894573521270469 -2 2.005347401248558 + vertex 2.566666666666677 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.562175811593016 -2 20.80826400883117 + vertex 4.041626538302982 -2 20.31140730480241 + vertex 4.365583445851182 -2 20.88478511069381 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.927963870571831 -2 3.030785662201998 + vertex -2.348118176010836 -2 2.75223995238126 + vertex -2.298332905758358 -2 3.40159593333896 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -3.557504597528008 -2 3.394518219884866 + vertex -3.472825915922042 -2 2.745571680351766 + vertex -2.927963870571831 -2 3.030785662201998 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.787889134207287 -2 4.821432434524037 + vertex 4.458357092750293 -2 5.242782729031642 + vertex 4.076553335617876 -2 4.914212848582235 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.528258704114727 -2 20.38121451545302 + vertex 1.480298472225957 -2 21.00228949787716 + vertex 0.8138538323647302 -2 20.78809710159216 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.302206729260642 -2 19.647231901849 + vertex -2.407514177605579 -2 20.2710850041902 + vertex -2.93912235862163 -2 19.99464574380434 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -2.93912235862163 -2 19.99464574380434 + vertex -3.469012145433474 -2 20.27171639072729 + vertex -3.57952350344234 -2 19.64741215066542 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.09999999999999 -2 21.5 + vertex 1.480298472225957 -2 21.00228949787716 + vertex 1.833333333333327 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.532384274596081 -2 6.709175634538488 + vertex 3.947182784469494 -2 6.247925982435459 + vertex 4.211091610502407 -2 6.720319745154439 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.566666666666663 -2 21.5 + vertex 2.933333333333329 -2 21.01692359780342 + vertex 3.299999999999997 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.409279506649708 -2 5.968608856392206 + vertex 3.947182784469494 -2 6.247925982435459 + vertex 3.532384274596081 -2 6.709175634538488 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 1.833333333333345 -2 1.5 + vertex 1.486329693465689 -2 1.994046019256764 + vertex 1.100000000000015 -2 1.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858499700900416 -2 5.574074074074068 + vertex 4.458357092750293 -2 5.242782729031642 + vertex 4.787889134207287 -2 4.821432434524037 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.766666666666669 -2 21.5 + vertex -4.958455695605603 -2 20.95650076827917 + vertex -4.405426047799934 -2 20.88547754159565 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.365583445851182 -2 20.88478511069381 + vertex 4.968788439014086 -2 20.96953853470181 + vertex 4.766666666666666 -2 21.5 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.766666666666669 -2 1.5 + vertex 4.969599156931578 -2 2.028571369337921 + vertex 4.36558344585119 -2 2.115214889306188 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.404546516961016 -2 2.116118090915069 + vertex -4.958455695605594 -2 2.043499231720833 + vertex -4.766666666666666 -2 1.5 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.853983791777436 -2 17.46298864682942 + vertex 4.473680827429788 -2 17.81087864922232 + vertex 4.115961526634615 -2 17.43426003489867 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 2.82495189991042 -2 8.55714936857806 + vertex 3.426996701041404 -2 8.351024862087794 + vertex 3.482481059799262 -2 9.029779793154106 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.216602219501706 -2 11.87014423231384 + vertex 3.562200465473438 -2 12.06310768263945 + vertex 3.653422321959101 -2 11.49668106748853 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.875264150806977 -2 14.4094014084103 + vertex 4.199825762598869 -2 14.66546628030377 + vertex 4.212841511831785 -2 14.04539977235522 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 15.57407407407405 + vertex 4.918821107332354 -2 15.78024179549353 + vertex 4.870582047868353 -2 15.09106547965763 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.078142303503325 -2 2.674263965434937 + vertex -0.4134064153154973 -2 2.481641226637574 + vertex -0.3680149090001792 -2 3.06536071564342 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -4.879793185278873 -2 20.38464438613695 + vertex -4.958455695605603 -2 20.95650076827917 + vertex -5.5 -2 20.75925925925926 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 5.5 -2 20.75925925925926 + vertex 4.968788439014086 -2 20.96953853470181 + vertex 4.858499700900416 -2 20.38888888888889 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.874071970659501 -2 2.574806147906303 + vertex 4.969599156931578 -2 2.028571369337921 + vertex 5.5 -2 2.24074074074074 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -5.5 -2 2.240740740740744 + vertex -4.958455695605594 -2 2.043499231720833 + vertex -4.8795934270297 -2 2.615567192513602 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.348118176010836 -2 2.75223995238126 + vertex -1.74883458901402 -2 2.529533409221695 + vertex -1.692097972637046 -2 3.077348409045236 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.744074395475103 -2 16.33170939209035 + vertex 4.655673760136614 -2 16.96466929801385 + vertex 4.09173318766436 -2 16.67721812266799 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.465598520979608 -2 10.40825210954239 + vertex 3.389269686093905 -2 11.0434416288251 + vertex 2.807399006272134 -2 10.74844508614493 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 3.532384274596081 -2 6.709175634538488 + vertex 3.36872271763415 -2 7.293849202134684 + vertex 2.806455387130034 -2 7.0476518507815 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 0.003832493913557831 -2 2.100914919519724 + vertex -0.4134064153154973 -2 2.481641226637574 + vertex -0.7333333333333218 -2 2.047299604942785 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.483005193418757 -2 18.54466177502444 + vertex 4.473680827429788 -2 17.81087864922232 + vertex 4.881498999364475 -2 18.16944240249155 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.100793025011158 -2 18.17905243801717 + vertex 4.473680827429788 -2 17.81087864922232 + vertex 4.483005193418757 -2 18.54466177502444 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858499700900416 -2 20.38888888888889 + vertex 4.47165551143669 -2 19.95897091405205 + vertex 4.858733561059807 -2 19.64774309047021 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.880508352128135 -2 18.90845629198527 + vertex 4.483005193418757 -2 18.54466177502444 + vertex 4.881498999364475 -2 18.16944240249155 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex 4.858733561059807 -2 19.64774309047021 + vertex 4.470701957205813 -2 19.28325892797596 + vertex 4.880508352128135 -2 18.90845629198527 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.881498999364475 -2 18.16944240249155 + vertex 4.473680827429788 -2 17.81087864922232 + vertex 4.853983791777436 -2 17.46298864682942 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.090847999373175 -2 18.91688194045436 + vertex 4.470701957205813 -2 19.28325892797596 + vertex 4.04244324160653 -2 19.64710479876006 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.100793025011158 -2 18.17905243801717 + vertex 4.483005193418757 -2 18.54466177502444 + vertex 4.090847999373175 -2 18.91688194045436 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.115961526634615 -2 17.43426003489867 + vertex 4.473680827429788 -2 17.81087864922232 + vertex 4.100793025011158 -2 18.17905243801717 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.470701957205813 -2 19.28325892797596 + vertex 4.483005193418757 -2 18.54466177502444 + vertex 4.880508352128135 -2 18.90845629198527 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.090847999373175 -2 18.91688194045436 + vertex 4.483005193418757 -2 18.54466177502444 + vertex 4.470701957205813 -2 19.28325892797596 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.470701957205813 -2 19.28325892797596 + vertex 4.47165551143669 -2 19.95897091405205 + vertex 4.04244324160653 -2 19.64710479876006 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex 4.858733561059807 -2 19.64774309047021 + vertex 4.47165551143669 -2 19.95897091405205 + vertex 4.470701957205813 -2 19.28325892797596 + endloop +endfacet +facet normal -0 -1 0 + outer loop + vertex -4.405426047799934 -2 20.88547754159565 + vertex -4.958455695605603 -2 20.95650076827917 + vertex -4.879793185278873 -2 20.38464438613695 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.858499700900416 -2 20.38888888888889 + vertex 4.968788439014086 -2 20.96953853470181 + vertex 4.365583445851182 -2 20.88478511069381 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.36558344585119 -2 2.115214889306188 + vertex 4.969599156931578 -2 2.028571369337921 + vertex 4.874071970659501 -2 2.574806147906303 + endloop +endfacet +facet normal 0 -1 -0 + outer loop + vertex -4.8795934270297 -2 2.615567192513602 + vertex -4.958455695605594 -2 2.043499231720833 + vertex -4.404546516961016 -2 2.116118090915069 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -1.458238078259432 -2 2.055198051546707 + vertex -1.74883458901402 -2 2.529533409221695 + vertex -2.167576414659461 -2 2.088616667700339 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.110486200275591 -2 5.661411558946233 + vertex 3.947182784469494 -2 6.247925982435459 + vertex 3.409279506649708 -2 5.968608856392206 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -0.7333333333333218 -2 2.047299604942785 + vertex -0.4134064153154973 -2 2.481641226637574 + vertex -1.078142303503325 -2 2.674263965434937 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex 4.04244324160653 -2 19.64710479876006 + vertex 4.47165551143669 -2 19.95897091405205 + vertex 4.041626538302982 -2 20.31140730480241 + endloop +endfacet +facet normal 0 -1 0 + outer loop + vertex -2.167576414659461 -2 2.088616667700339 + vertex -1.74883458901402 -2 2.529533409221695 + vertex -2.348118176010836 -2 2.75223995238126 + endloop +endfacet +facet normal -0.00511044 0.999985 0.00210245 + outer loop + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + vertex 0.3070111775077362 5.491424599945383 20.04433390229711 + vertex -0.3783033396193837 5.486974264859716 20.49523979426701 + endloop +endfacet +facet normal 0.956908 0.290379 -0.0027551 + outer loop + vertex 5.141986732089285 1.951915071671345 12.03190553294616 + vertex 5.354099104705792 1.258420747202078 12.61111111111141 + vertex 5.362589343990837 1.221734638829532 11.69335974927695 + endloop +endfacet +facet normal -0.864514 0.502583 0.00499871 + outer loop + vertex -4.578874889937365 3.046950072170709 20.49484434252649 + vertex -4.896125033036498 2.505585692183236 20.05737357636656 + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + endloop +endfacet +facet normal 0.985166 0.171591 0.00225474 + outer loop + vertex 5.362589343990837 1.221734638829532 11.69335974927695 + vertex 5.354099104705792 1.258420747202078 12.61111111111141 + vertex 5.462588851477699 0.6404084944092698 12.24074074074071 + endloop +endfacet +facet normal 0.994888 0.0947517 -0.0349256 + outer loop + vertex 5.417922838555951 0.9466319852264811 20.24864700637255 + vertex 5.471007922370094 0.5639790008179997 20.72270400351366 + vertex 5.5 0 20.01851851851852 + endloop +endfacet +facet normal 0.983242 0.182281 -0.00306043 + outer loop + vertex 5.321881441977558 1.388372398722644 18.99144459566703 + vertex 5.330076268660247 1.356571771144032 19.73017849541023 + vertex 5.462588851477741 0.6404084944089157 19.64814814814814 + endloop +endfacet +facet normal 0.996359 0.0780478 0.0343103 + outer loop + vertex 5.462588851477741 0.6404084944089157 19.64814814814814 + vertex 5.417922838555951 0.9466319852264811 20.24864700637255 + vertex 5.5 0 20.01851851851852 + endloop +endfacet +facet normal 0.982387 0.186841 0.00231642 + outer loop + vertex 5.462588851477741 0.6404084944089157 19.64814814814814 + vertex 5.459634833976192 0.6651221539189293 18.90754991733586 + vertex 5.321881441977558 1.388372398722644 18.99144459566703 + endloop +endfacet +facet normal 0.499892 0.865944 0.0157658 + outer loop + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + vertex 2.432132975136189 4.933024345293179 20.87677123430906 + vertex 3.05563628160782 4.573082867663993 20.87706280989174 + endloop +endfacet +facet normal 0.954866 0.297037 0.000301487 + outer loop + vertex 5.140219477149498 1.956564265934789 9.09286486955698 + vertex 5.343671221410812 1.301989968266224 9.635307021455539 + vertex 5.342620843612703 1.306293428520213 8.722112600728778 + endloop +endfacet +facet normal 0.98444 0.175723 -0.000304225 + outer loop + vertex 5.342620843612703 1.306293428520213 8.722112600728778 + vertex 5.343671221410812 1.301989968266224 9.635307021455539 + vertex 5.464329314634285 0.6253839950209801 9.258668456006923 + endloop +endfacet +facet normal 0.244783 0.969473 0.0142788 + outer loop + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + vertex 1.578298002103966 5.268678716391296 20.02401911919812 + vertex 1.001653684937865 5.408020885263887 20.44872268839708 + endloop +endfacet +facet normal 0.997807 0.0653997 0.0102349 + outer loop + vertex 5.5 0 21.5 + vertex 5.471007922370094 0.5639790008179997 20.72270400351366 + vertex 5.452946737555957 0.7178940572102823 21.5 + endloop +endfacet +facet normal -0.997473 0.0710428 0 + outer loop + vertex -5.5 0 2.98148148148148 + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + vertex -5.5 0 2.24074074074074 + endloop +endfacet +facet normal 0.98343 0.181163 -0.00668728 + outer loop + vertex 5.347696406214424 1.285357205978686 16.79025874800341 + vertex 5.458193291725775 0.6768500499813518 16.55505310407936 + vertex 5.328246086204495 1.363742514130318 16.05340787814411 + endloop +endfacet +facet normal 0.954273 0.298935 0.0012057 + outer loop + vertex 5.141258461214585 1.95383249921518 6.159492910637925 + vertex 5.339527180018263 1.318881910500791 6.662341264607266 + vertex 5.335404501278465 1.335462020327605 5.814529487406688 + endloop +endfacet +facet normal 0.984595 0.174841 -0.00190643 + outer loop + vertex 5.462588851477742 0.6404084944089036 18.16666666666666 + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + vertex 5.459634833976192 0.6651221539189293 18.90754991733586 + endloop +endfacet +facet normal 0.983834 0.179078 -0.00128199 + outer loop + vertex 5.335404501278465 1.335462020327605 5.814529487406688 + vertex 5.339527180018263 1.318881910500791 6.662341264607266 + vertex 5.462642959302149 0.6399467940279513 6.305711372119314 + endloop +endfacet +facet normal 0.982491 0.186095 0.00892232 + outer loop + vertex 5.459634833976192 0.6651221539189293 18.90754991733586 + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + vertex 5.321881441977558 1.388372398722644 18.99144459566703 + endloop +endfacet +facet normal 0.98143 0.191818 -0.000329017 + outer loop + vertex 5.45199573013907 0.7250810703261731 15.20311570077771 + vertex 5.324109977345409 1.379801778927347 15.43526584087152 + vertex 5.45147922627175 0.7289542136016242 15.92048612597993 + endloop +endfacet +facet normal 0.983468 0.181074 0.00163835 + outer loop + vertex 5.462642959302149 0.6399467940279513 6.305711372119314 + vertex 5.459976604308243 0.6623107128883186 5.434561843950101 + vertex 5.335404501278465 1.335462020327605 5.814529487406688 + endloop +endfacet +facet normal 0.998473 0.0552457 -0 + outer loop + vertex 5.5 0 17.05555555555554 + vertex 5.466427009523622 0.6067748755103708 17.19140785290995 + vertex 5.5 0 17.79629629629628 + endloop +endfacet +facet normal 0.998248 0.0591407 -0.00153713 + outer loop + vertex 5.5 0 5.944444444444438 + vertex 5.459976604308243 0.6623107128883186 5.434561843950101 + vertex 5.462642959302149 0.6399467940279513 6.305711372119314 + endloop +endfacet +facet normal 0.924172 0.381656 0.0156695 + outer loop + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + vertex 4.937890359975085 2.422238384813751 20.87762820958706 + vertex 5.208115712223082 1.767917059167386 20.87706280989174 + endloop +endfacet +facet normal 0.99616 0.0829754 0.0279445 + outer loop + vertex 5.466427009523622 0.6067748755103708 17.19140785290995 + vertex 5.430619032632266 0.8708483923233669 17.68377109348667 + vertex 5.5 0 17.79629629629628 + endloop +endfacet +facet normal -0.801279 0.598287 -0.00210112 + outer loop + vertex -4.585867558739597 3.036415441552708 19.74358804414167 + vertex -4.203565089212222 3.546835285258711 19.28997812941705 + vertex -4.601993462768863 3.011919017608647 18.91804789924629 + endloop +endfacet +facet normal -0.980655 0.195064 0.0162815 + outer loop + vertex -5.312592044589875 1.423504748063864 21.5 + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + vertex -5.452946737555957 0.7178940572102843 21.5 + endloop +endfacet +facet normal 0.998681 0.0513385 -0 + outer loop + vertex 5.5 0 20.75925925925926 + vertex 5.471007922370094 0.5639790008179997 20.72270400351366 + vertex 5.5 0 21.5 + endloop +endfacet +facet normal -0.0038711 0.999985 0.00398608 + outer loop + vertex -0.3783033396193837 5.486974264859716 20.49523979426701 + vertex 0.3070111775077362 5.491424599945383 20.04433390229711 + vertex -0.3289149400880707 5.490156187412783 19.74495734050066 + endloop +endfacet +facet normal 0.956195 0.292732 -0.000536766 + outer loop + vertex 5.353286605756722 1.261872622979704 14.09259610146606 + vertex 5.140471256908808 1.955902670608734 13.48086883335942 + vertex 5.14260411224237 1.950287913295847 14.21826185107064 + endloop +endfacet +facet normal 0.955852 0.293848 0.00084892 + outer loop + vertex 5.351088640648471 1.271161028321311 13.35230399535177 + vertex 5.140471256908808 1.955902670608734 13.48086883335942 + vertex 5.353286605756722 1.261872622979704 14.09259610146606 + endloop +endfacet +facet normal 0.956082 0.293099 0.000371626 + outer loop + vertex 5.141115229323106 1.95420935388766 14.9559015917752 + vertex 5.352885295866843 1.263573903375872 14.83390153907896 + vertex 5.14260411224237 1.950287913295847 14.21826185107064 + endloop +endfacet +facet normal 0.956214 0.292668 -0.000154014 + outer loop + vertex 5.352885295866843 1.263573903375872 14.83390153907896 + vertex 5.353286605756722 1.261872622979704 14.09259610146606 + vertex 5.14260411224237 1.950287913295847 14.21826185107064 + endloop +endfacet +facet normal 0.545612 0.837942 -0.0127154 + outer loop + vertex 3.05563628160782 4.573082867663993 20.87706280989174 + vertex 3.24533634122458 4.440472050618836 20.27797987500447 + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + endloop +endfacet +facet normal 0.981862 0.189528 0.00517348 + outer loop + vertex 5.328246086204495 1.363742514130318 16.05340787814411 + vertex 5.458193291725775 0.6768500499813518 16.55505310407936 + vertex 5.45147922627175 0.7289542136016242 15.92048612597993 + endloop +endfacet +facet normal 0.956765 0.290806 -0.00575876 + outer loop + vertex 5.168137311619096 1.88158356929756 11.27368581568632 + vertex 5.34724229625872 1.287245052467388 11.01738851026113 + vertex 5.143658139205531 1.947506340678945 10.53566889730253 + endloop +endfacet +facet normal 0.61141 0.791037 -0.0209272 + outer loop + vertex 3.348187859547973 4.363443371601787 21.5 + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + vertex 3.05563628160782 4.573082867663993 20.87706280989174 + endloop +endfacet +facet normal -0.121954 0.992533 0.00248809 + outer loop + vertex -0.9924759007625094 5.409712708305834 19.31055568031545 + vertex -0.3289149400880707 5.490156187412783 19.74495734050066 + vertex -0.3621874643355 5.488061610503131 18.94966241806066 + endloop +endfacet +facet normal -0.988356 0.151719 -0.0115936 + outer loop + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + vertex -5.472807214829338 0.5462427933730074 20.94680099274967 + vertex -5.452946737555957 0.7178940572102843 21.5 + endloop +endfacet +facet normal -0.796983 0.603971 0.00613777 + outer loop + vertex -4.20510078902244 3.545014436382855 20.01829885998822 + vertex -4.578874889937365 3.046950072170709 20.49484434252649 + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + endloop +endfacet +facet normal 0.981608 0.190899 -0.0016086 + outer loop + vertex 5.45147922627175 0.7289542136016242 15.92048612597993 + vertex 5.324109977345409 1.379801778927347 15.43526584087152 + vertex 5.328246086204495 1.363742514130318 16.05340787814411 + endloop +endfacet +facet normal 0.956492 0.291758 -0.0009518 + outer loop + vertex 5.145654811298226 1.942224642764944 12.74763160945074 + vertex 5.354099104705792 1.258420747202078 12.61111111111141 + vertex 5.141986732089285 1.951915071671345 12.03190553294616 + endloop +endfacet +facet normal 0.956482 0.291791 -0.00113066 + outer loop + vertex 5.351088640648471 1.271161028321311 13.35230399535177 + vertex 5.354099104705792 1.258420747202078 12.61111111111141 + vertex 5.145654811298226 1.942224642764944 12.74763160945074 + endloop +endfacet +facet normal 0.955874 0.293774 0.00127731 + outer loop + vertex 5.145654811298226 1.942224642764944 12.74763160945074 + vertex 5.140471256908808 1.955902670608734 13.48086883335942 + vertex 5.351088640648471 1.271161028321311 13.35230399535177 + endloop +endfacet +facet normal -0.863103 0.505026 0.000951913 + outer loop + vertex -4.585867558739597 3.036415441552708 19.74358804414167 + vertex -4.896125033036498 2.505585692183236 20.05737357636656 + vertex -4.578874889937365 3.046950072170709 20.49484434252649 + endloop +endfacet +facet normal 0.90282 0.429871 -0.0112994 + outer loop + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + vertex 4.839878840573146 2.612579722912267 20.28782012505717 + vertex 4.937890359975085 2.422238384813751 20.87762820958706 + endloop +endfacet +facet normal 0.607902 0.793833 -0.0168628 + outer loop + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + vertex 3.619021558537723 4.141579766084337 2.117809182156318 + vertex 3.056057912944187 4.572801114495492 2.123228765692188 + endloop +endfacet +facet normal 0.957653 0.287893 -0.00425932 + outer loop + vertex 5.171106296982572 1.873408568707635 7.60218979976907 + vertex 5.351612161616004 1.268955188981735 7.330746350623435 + vertex 5.153439736913926 1.921473101033819 6.878842079210223 + endloop +endfacet +facet normal 0.955648 0.294506 -0.00182738 + outer loop + vertex 5.343671221410812 1.301989968266224 9.635307021455539 + vertex 5.151436855319887 1.926836351549336 9.806356433593624 + vertex 5.338145514410095 1.324463086304552 10.36741450328788 + endloop +endfacet +facet normal 0.954706 0.297546 0.00174976 + outer loop + vertex 5.338145514410095 1.324463086304552 10.36741450328788 + vertex 5.151436855319887 1.926836351549336 9.806356433593624 + vertex 5.143658139205531 1.947506340678945 10.53566889730253 + endloop +endfacet +facet normal -0.128753 0.991656 0.00638578 + outer loop + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + vertex -0.3783033396193837 5.486974264859716 20.49523979426701 + vertex -0.983224731892634 5.411401770945737 20.03428894565108 + endloop +endfacet +facet normal 0.998045 0.0625068 -0 + outer loop + vertex 5.5 0 4.462962962962957 + vertex 5.45702188206679 0.6862304122116961 4.750840592067621 + vertex 5.5 0 5.203703703703698 + endloop +endfacet +facet normal 0.985697 0.168526 -0.00109677 + outer loop + vertex 5.462588851477699 0.6404084944092698 12.24074074074071 + vertex 5.464321032236196 0.6254563587182973 11.49999999999998 + vertex 5.362589343990837 1.221734638829532 11.69335974927695 + endloop +endfacet +facet normal 0.120394 0.992724 -0.0020616 + outer loop + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + vertex 1.001653684937865 5.408020885263887 20.44872268839708 + vertex 0.3070111775077362 5.491424599945383 20.04433390229711 + endloop +endfacet +facet normal 0.98424 0.176838 0.000626676 + outer loop + vertex 5.462588851477699 0.6404084944092698 7.796296296296289 + vertex 5.343411944396419 1.303053641444466 7.983999811632167 + vertex 5.463459558418405 0.6329373219573643 8.537037037037026 + endloop +endfacet +facet normal 0.98429 0.176561 0.000279973 + outer loop + vertex 5.463459558418405 0.6329373219573643 8.537037037037026 + vertex 5.343411944396419 1.303053641444466 7.983999811632167 + vertex 5.342620843612703 1.306293428520213 8.722112600728778 + endloop +endfacet +facet normal -0.983405 0.181407 -0.00247106 + outer loop + vertex -5.336450873075671 1.331274607002596 3.871193572221433 + vertex -5.329642713413715 1.358274106120005 3.143864560230363 + vertex -5.46258885147774 0.6404084944089274 3.351851851851849 + endloop +endfacet +facet normal 0.792616 0.609699 0.00523492 + outer loop + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + vertex 4.533873164080951 3.113517967191868 20.0724298361627 + vertex 4.151017607888463 3.608192458697283 20.42672570575831 + endloop +endfacet +facet normal -0.997786 0.0653681 -0.0122418 + outer loop + vertex -5.46258885147774 0.6404084944089274 3.351851851851849 + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + vertex -5.5 0 2.98148148148148 + endloop +endfacet +facet normal 0.984308 0.17646 0.000660656 + outer loop + vertex 5.464329314634285 0.6253839950209801 9.258668456006923 + vertex 5.463459558418405 0.6329373219573643 8.537037037037026 + vertex 5.342620843612703 1.306293428520213 8.722112600728778 + endloop +endfacet +facet normal -0.260096 0.965436 -0.0168509 + outer loop + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + vertex -1.086182840163288 5.391679407915015 2.117161111770399 + vertex -1.767917059167402 5.208115712223076 2.122937190108266 + endloop +endfacet +facet normal -0.983563 0.180561 -0.00130695 + outer loop + vertex -5.46258885147774 0.6404084944089274 3.351851851851849 + vertex -5.460790787961493 0.6555638566264151 4.092472815228255 + vertex -5.336450873075671 1.331274607002596 3.871193572221433 + endloop +endfacet +facet normal 0.256114 0.966609 -0.00850075 + outer loop + vertex 1.001653684937865 5.408020885263887 20.44872268839708 + vertex 1.072996771088712 5.394319042217766 21.04016115450814 + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + endloop +endfacet +facet normal 0.342262 0.939557 -0.00949453 + outer loop + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + vertex 2.131499096350572 5.070178655851951 20.32286341520533 + vertex 1.578298002103966 5.268678716391296 20.02401911919812 + endloop +endfacet +facet normal 0.955575 0.294734 -0.00274315 + outer loop + vertex 5.140219477149498 1.956564265934789 9.09286486955698 + vertex 5.151436855319887 1.926836351549336 9.806356433593624 + vertex 5.343671221410812 1.301989968266224 9.635307021455539 + endloop +endfacet +facet normal -0.723654 0.690142 -0.00544386 + outer loop + vertex -3.764535802277208 4.009771838069231 20.37321112384092 + vertex -4.20510078902244 3.545014436382855 20.01829885998822 + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + endloop +endfacet +facet normal -0.99794 0.0597391 0.0233793 + outer loop + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + vertex -5.471754212788627 0.556691867041289 2.02393833416575 + vertex -5.5 0 2.24074074074074 + endloop +endfacet +facet normal -0.982659 0.185394 -0.0030583 + outer loop + vertex -5.455499441625426 0.6982305080878859 7.053492151481383 + vertex -5.331206571821438 1.35212295615743 6.756020103499217 + vertex -5.459939312520691 0.6626180676612138 6.321235945707285 + endloop +endfacet +facet normal 0.659259 0.751741 0.0162302 + outer loop + vertex 3.889087296526017 3.889087296526005 21.5 + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + vertex 3.348187859547973 4.363443371601787 21.5 + endloop +endfacet +facet normal 0.98399 0.178224 -0.00011321 + outer loop + vertex 5.462588851477747 0.6404084944088623 4.092592592592588 + vertex 5.462745257056555 0.6390729664960926 3.349526788074936 + vertex 5.339962456935814 1.317118429950786 3.589736816026074 + endloop +endfacet +facet normal 0.998179 0.0603199 -0 + outer loop + vertex 5.5 0 5.203703703703698 + vertex 5.459976604308243 0.6623107128883186 5.434561843950101 + vertex 5.5 0 5.944444444444438 + endloop +endfacet +facet normal -0.239044 0.970992 -0.0057812 + outer loop + vertex -0.983224731892634 5.411401770945737 20.03428894565108 + vertex -1.608551244610577 5.259521165796537 20.38119086934289 + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + endloop +endfacet +facet normal 0.955184 0.296 -0.00285951 + outer loop + vertex 5.141258461214585 1.95383249921518 6.159492910637925 + vertex 5.153439736913926 1.921473101033819 6.878842079210223 + vertex 5.339527180018263 1.318881910500791 6.662341264607266 + endloop +endfacet +facet normal 0.383165 0.923517 -0.0173239 + outer loop + vertex 2.432587796204499 4.93280007842979 2.122937190108265 + vertex 1.772743246953266 5.20647494763795 2.117973314103827 + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + endloop +endfacet +facet normal -0.864877 0.50198 0.00199894 + outer loop + vertex -4.601993462768863 3.011919017608647 18.91804789924629 + vertex -4.904911767396387 2.488340924000661 19.3376449252274 + vertex -4.585867558739597 3.036415441552708 19.74358804414167 + endloop +endfacet +facet normal -0.983148 0.18281 -0.000403143 + outer loop + vertex -5.33375297905039 1.342042904854793 5.3475778539808 + vertex -5.332602887399606 1.346605526981597 4.611820020301286 + vertex -5.460052036612598 0.6616885653255702 4.838555684658132 + endloop +endfacet +facet normal 0.982993 0.183645 0.000123938 + outer loop + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + vertex 5.462745257056555 0.6390729664960926 3.349526788074936 + vertex 5.462588851477906 0.6404084944075038 2.61111111111111 + endloop +endfacet +facet normal -0.983209 0.182485 4.69726e-05 + outer loop + vertex -5.460052036612598 0.6616885653255702 4.838555684658132 + vertex -5.460118703792913 0.6611382158753166 5.581173766959984 + vertex -5.33375297905039 1.342042904854793 5.3475778539808 + endloop +endfacet +facet normal -0.983155 0.182771 -0.0005269 + outer loop + vertex -5.332602887399606 1.346605526981597 4.611820020301286 + vertex -5.460790787961493 0.6555638566264151 4.092472815228255 + vertex -5.460052036612598 0.6616885653255702 4.838555684658132 + endloop +endfacet +facet normal 0.983954 0.17842 0.000158181 + outer loop + vertex 5.339962456935814 1.317118429950786 3.589736816026074 + vertex 5.339523148522663 1.318898232006785 4.314904814500256 + vertex 5.462588851477747 0.6404084944088623 4.092592592592588 + endloop +endfacet +facet normal 0.983669 0.179915 -0.00504982 + outer loop + vertex 5.339962456935814 1.317118429950786 3.589736816026074 + vertex 5.462745257056555 0.6390729664960926 3.349526788074936 + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + endloop +endfacet +facet normal 0.965006 0.26179 -0.0151589 + outer loop + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + vertex 5.388402417417908 1.102324538402753 2.105178344957057 + vertex 5.207331238571131 1.770226361740569 2.112773058852293 + endloop +endfacet +facet normal 0.123871 0.992235 -0.0112001 + outer loop + vertex 0.3484132606717201 5.488953288176909 2.493006867666852 + vertex 0.9376243172597151 5.419488964808698 2.855592952321005 + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + endloop +endfacet +facet normal -0.800466 0.599378 -0.000189339 + outer loop + vertex -4.20510078902244 3.545014436382855 20.01829885998822 + vertex -4.203565089212222 3.546835285258711 19.28997812941705 + vertex -4.585867558739597 3.036415441552708 19.74358804414167 + endloop +endfacet +facet normal -0.917779 0.397063 -0.00487777 + outer loop + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + vertex -4.896125033036498 2.505585692183236 20.05737357636656 + vertex -5.169860313545367 1.876844249912228 20.38100790963064 + endloop +endfacet +facet normal -0.983408 0.181404 0.00135433 + outer loop + vertex -5.336450873075671 1.331274607002596 3.871193572221433 + vertex -5.460790787961493 0.6555638566264151 4.092472815228255 + vertex -5.332602887399606 1.346605526981597 4.611820020301286 + endloop +endfacet +facet normal -0.00331625 0.999991 -0.00249495 + outer loop + vertex -0.3621874643355 5.488061610503131 18.94966241806066 + vertex -0.3289149400880707 5.490156187412783 19.74495734050066 + vertex 0.3112636309729526 5.491185204674263 19.3064763842535 + endloop +endfacet +facet normal -0.98475 0.173976 -0.000339767 + outer loop + vertex -5.463300394916927 0.6343096995163731 11.50709967217639 + vertex -5.350499757292488 1.27363744731891 11.93984222403835 + vertex -5.349418226983903 1.278172379928623 11.12731726119114 + endloop +endfacet +facet normal 0.954847 0.297077 0.00364722 + outer loop + vertex 5.143658139205531 1.947506340678945 10.53566889730253 + vertex 5.34724229625872 1.287245052467388 11.01738851026113 + vertex 5.338145514410095 1.324463086304552 10.36741450328788 + endloop +endfacet +facet normal -0.499195 0.86631 -0.0176585 + outer loop + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + vertex -2.43213297513447 4.933024345294026 2.123228765692299 + vertex -3.049579275765538 4.577124232618265 2.117940666612885 + endloop +endfacet +facet normal -0.983458 0.18109 -0.00415487 + outer loop + vertex -5.33375297905039 1.342042904854793 5.3475778539808 + vertex -5.460118703792913 0.6611382158753166 5.581173766959984 + vertex -5.345708653247237 1.2935992403359 6.066073096927131 + endloop +endfacet +facet normal -0.957472 0.288525 0.000312873 + outer loop + vertex -5.165673575632222 1.88833696940324 10.75291307090809 + vertex -5.349418226983903 1.278172379928623 11.12731726119114 + vertex -5.164172210296571 1.892439003614285 11.56467286409568 + endloop +endfacet +facet normal -0.984013 0.178095 -0.000117599 + outer loop + vertex -5.460118703792913 0.6611382158753166 5.581173766959984 + vertex -5.459939312520691 0.6626180676612138 6.321235945707285 + vertex -5.345708653247237 1.2935992403359 6.066073096927131 + endloop +endfacet +facet normal -0.119842 0.992793 -0.000785107 + outer loop + vertex -0.983224731892634 5.411401770945737 20.03428894565108 + vertex -0.3289149400880707 5.490156187412783 19.74495734050066 + vertex -0.9924759007625094 5.409712708305834 19.31055568031545 + endloop +endfacet +facet normal 0.116739 0.993153 0.00430431 + outer loop + vertex 1.001653684937865 5.408020885263887 20.44872268839708 + vertex 0.9465461948198692 5.417937827353875 19.65513716806774 + vertex 0.3070111775077362 5.491424599945383 20.04433390229711 + endloop +endfacet +facet normal -0.957477 0.28851 0.000335783 + outer loop + vertex -5.349418226983903 1.278172379928623 11.12731726119114 + vertex -5.350499757292488 1.27363744731891 11.93984222403835 + vertex -5.164172210296571 1.892439003614285 11.56467286409568 + endloop +endfacet +facet normal 0.232122 0.972679 -0.00396384 + outer loop + vertex 1.578298002103966 5.268678716391296 20.02401911919812 + vertex 0.9465461948198692 5.417937827353875 19.65513716806774 + vertex 1.001653684937865 5.408020885263887 20.44872268839708 + endloop +endfacet +facet normal 0.651189 0.758783 0.0141905 + outer loop + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + vertex 3.799593247494868 3.976567760467738 2.654917871642895 + vertex 3.619021558537723 4.141579766084337 2.117809182156318 + endloop +endfacet +facet normal 0.998681 0.0513385 -0 + outer loop + vertex 5.5 0 20.01851851851852 + vertex 5.471007922370094 0.5639790008179997 20.72270400351366 + vertex 5.5 0 20.75925925925926 + endloop +endfacet +facet normal 0.955936 0.293537 0.00464218 + outer loop + vertex 5.153439736913926 1.921473101033819 6.878842079210223 + vertex 5.351612161616004 1.268955188981735 7.330746350623435 + vertex 5.339527180018263 1.318881910500791 6.662341264607266 + endloop +endfacet +facet normal 0.998131 0.0610757 -0.00217674 + outer loop + vertex 5.5 0 5.203703703703698 + vertex 5.45702188206679 0.6862304122116961 4.750840592067621 + vertex 5.459976604308243 0.6623107128883186 5.434561843950101 + endloop +endfacet +facet normal 0.437953 0.898871 -0.0151277 + outer loop + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + vertex 2.131499096350572 5.070178655851951 20.32286341520533 + vertex 2.432132975136189 4.933024345293179 20.87677123430906 + endloop +endfacet +facet normal -0.923414 0.383478 -0.0158267 + outer loop + vertex -5.202761293209437 1.783612885656994 2.097099159738966 + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + vertex -4.93725623361463 2.423530664884083 2.111219890696505 + endloop +endfacet +facet normal -0.984592 0.174851 -0.00220713 + outer loop + vertex -5.463457015218254 0.6329592742526507 14.46853726531237 + vertex -5.350973674996689 1.271644891269743 14.88756196999887 + vertex -5.344337296030745 1.299253195591523 14.11425982063323 + endloop +endfacet +facet normal -0.865419 0.501044 -0.0021242 + outer loop + vertex -4.909025451291431 2.480215538733068 11.95064759781068 + vertex -4.587803823660058 3.033489092713233 11.58495038277631 + vertex -4.921676533348395 2.455015295489565 11.16072658817533 + endloop +endfacet +facet normal 0.863746 0.503859 -0.00830577 + outer loop + vertex 4.57176427209746 3.057608778175061 2.493642932651824 + vertex 4.887805760937779 2.521776128712354 2.854314542228816 + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + endloop +endfacet +facet normal -0.918022 0.396525 0.00184418 + outer loop + vertex -5.169773438355334 1.877083534655736 18.9201977983028 + vertex -4.904911767396387 2.488340924000661 19.3376449252274 + vertex -4.915818579230525 2.466724081872958 18.55622870078207 + endloop +endfacet +facet normal -0.864666 0.502347 0.000525192 + outer loop + vertex -4.918778118388804 2.460817307737309 8.165314093629673 + vertex -4.571761310004581 3.057613207118456 8.650358816856777 + vertex -4.575185892217977 3.052486535867045 7.915867117626163 + endloop +endfacet +facet normal -0.208399 0.977946 0.0138682 + outer loop + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + vertex -0.8586654316901362 5.432558667554396 2.653402613207058 + vertex -1.086182840163288 5.391679407915015 2.117161111770399 + endloop +endfacet +facet normal -0.864151 0.503232 -0.000931639 + outer loop + vertex -4.913838183546919 2.47066677354845 8.903493668018529 + vertex -4.571761310004581 3.057613207118456 8.650358816856777 + vertex -4.918778118388804 2.460817307737309 8.165314093629673 + endloop +endfacet +facet normal -0.865988 0.500063 0.00169311 + outer loop + vertex -4.911652466281053 2.475009101089377 10.38261171957252 + vertex -4.921676533348395 2.455015295489565 11.16072658817533 + vertex -4.59137142082812 3.028086603121313 10.84686772092755 + endloop +endfacet +facet normal -0.864532 0.502578 -0.000300624 + outer loop + vertex -4.911652466281053 2.475009101089377 10.38261171957252 + vertex -4.580458097205558 3.044569529464557 10.11690366370986 + vertex -4.913313387114148 2.471710250010081 9.64411804727896 + endloop +endfacet +facet normal -0.864623 0.502422 -4.79836e-05 + outer loop + vertex -4.913313387114148 2.471710250010081 9.64411804727896 + vertex -4.580458097205558 3.044569529464557 10.11690366370986 + vertex -4.580135555157919 3.045054727977522 9.385342259607349 + endloop +endfacet +facet normal -0.918399 0.395655 -0.000300753 + outer loop + vertex -5.164172210296571 1.892439003614285 11.56467286409568 + vertex -4.921676533348395 2.455015295489565 11.16072658817533 + vertex -5.165673575632222 1.88833696940324 10.75291307090809 + endloop +endfacet +facet normal -0.711405 0.702695 -0.0110465 + outer loop + vertex -3.722911157666007 4.048448160977975 2.818116375233727 + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + vertex -4.142727898941744 3.617707223550536 2.454219851588245 + endloop +endfacet +facet normal -0.00276543 0.999994 -0.00209892 + outer loop + vertex -0.3783033396193837 5.486974264859716 20.49523979426701 + vertex -0.3597172107657781 5.48822407781232 21.06620305504513 + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + endloop +endfacet +facet normal -0.956887 0.290451 0.00215777 + outer loop + vertex -5.344337296030745 1.299253195591523 14.11425982063323 + vertex -5.350973674996689 1.271644891269743 14.88756196999887 + vertex -5.159487311214056 1.905174712571303 14.52663788554383 + endloop +endfacet +facet normal 0.795331 0.606138 -0.00677265 + outer loop + vertex 4.187714980302149 3.56553547784242 2.852014943758265 + vertex 4.57176427209746 3.057608778175061 2.493642932651824 + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + endloop +endfacet +facet normal -0.983607 0.180247 0.00538541 + outer loop + vertex -5.459939312520691 0.6626180676612138 6.321235945707285 + vertex -5.331206571821438 1.35212295615743 6.756020103499217 + vertex -5.345708653247237 1.2935992403359 6.066073096927131 + endloop +endfacet +facet normal 0.951627 0.306978 0.0130704 + outer loop + vertex 5.207331238571131 1.770226361740569 2.112773058852293 + vertex 5.1359082938614 1.967853144176588 2.671362177826976 + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + endloop +endfacet +facet normal -0.86421 0.503129 -0.00124978 + outer loop + vertex -4.580135555157919 3.045054727977522 9.385342259607349 + vertex -4.571761310004581 3.057613207118456 8.650358816856777 + vertex -4.913838183546919 2.47066677354845 8.903493668018529 + endloop +endfacet +facet normal -0.864632 0.502406 -9.51803e-05 + outer loop + vertex -4.913838183546919 2.47066677354845 8.903493668018529 + vertex -4.913313387114148 2.471710250010081 9.64411804727896 + vertex -4.580135555157919 3.045054727977522 9.385342259607349 + endloop +endfacet +facet normal -0.865599 0.500736 0.0011565 + outer loop + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + vertex -4.573082867663999 3.055636281607812 21.0690550638699 + vertex -4.578874889937365 3.046950072170709 20.49484434252649 + endloop +endfacet +facet normal 0.996693 0.0755387 -0.0299381 + outer loop + vertex 5.5 0 17.79629629629628 + vertex 5.430619032632266 0.8708483923233669 17.68377109348667 + vertex 5.462588851477742 0.6404084944089036 18.16666666666666 + endloop +endfacet +facet normal 0.130174 0.99149 0.00133186 + outer loop + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + vertex 0.3597172107657752 5.48822407781232 1.931031098542516 + vertex 0.3484132606717201 5.488953288176909 2.493006867666852 + endloop +endfacet +facet normal -0.904308 0.426642 0.0142605 + outer loop + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + vertex -4.839134342495119 2.613958457069342 2.63629885568169 + vertex -4.93725623361463 2.423530664884083 2.111219890696505 + endloop +endfacet +facet normal -0.984571 0.174974 -0.00187923 + outer loop + vertex -5.461533276369314 0.6493491134287154 13.7223915162698 + vertex -5.348365566948149 1.282569983386249 13.39022568509564 + vertex -5.464240887080524 0.6261561530141311 12.98148148148145 + endloop +endfacet +facet normal -0.866175 0.499739 -0.00173476 + outer loop + vertex -4.915818579230525 2.466724081872958 18.55622870078207 + vertex -4.904911767396387 2.488340924000661 19.3376449252274 + vertex -4.601993462768863 3.011919017608647 18.91804789924629 + endloop +endfacet +facet normal 0.337184 0.941439 -0.000546541 + outer loop + vertex 1.558182631274909 5.274662727378235 3.941249219772481 + vertex 2.148095142858107 5.063169684814978 3.577663568096047 + vertex 1.551714848063318 5.276569058611839 3.234735469707145 + endloop +endfacet +facet normal -0.917437 0.39788 -0.000510377 + outer loop + vertex -5.167666710260322 1.882875665482789 19.64864303455607 + vertex -4.904911767396387 2.488340924000661 19.3376449252274 + vertex -5.169773438355334 1.877083534655736 18.9201977983028 + endloop +endfacet +facet normal -0.866264 0.499585 0.000530398 + outer loop + vertex -4.921676533348395 2.455015295489565 11.16072658817533 + vertex -4.587803823660058 3.033489092713233 11.58495038277631 + vertex -4.59137142082812 3.028086603121313 10.84686772092755 + endloop +endfacet +facet normal 0.614769 0.78845 0.0201388 + outer loop + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + vertex 3.24533634122458 4.440472050618836 20.27797987500447 + vertex 3.05563628160782 4.573082867663993 20.87706280989174 + endloop +endfacet +facet normal -0.552252 0.833677 -0.0010007 + outer loop + vertex -3.300431501637465 4.399676340709515 17.83016257702401 + vertex -3.29025226001403 4.407293961772072 18.55877352661438 + vertex -2.769452990619945 4.751855441061548 18.19930691019432 + endloop +endfacet +facet normal -0.917788 0.397066 0.00203164 + outer loop + vertex -4.909025451291431 2.480215538733068 11.95064759781068 + vertex -4.921676533348395 2.455015295489565 11.16072658817533 + vertex -5.164172210296571 1.892439003614285 11.56467286409568 + endloop +endfacet +facet normal -0.551559 0.834136 0.000443549 + outer loop + vertex -2.769452990619945 4.751855441061548 18.19930691019432 + vertex -3.29025226001403 4.407293961772072 18.55877352661438 + vertex -2.764583419145227 4.754690160103736 18.92372716072775 + endloop +endfacet +facet normal -0.728524 0.685018 0.00184208 + outer loop + vertex -4.220875575088082 3.526217432267168 18.55545174289028 + vertex -3.770575664540913 4.004092800869112 18.93615773712017 + vertex -3.787528484899666 3.988060678584723 18.19338036402895 + endloop +endfacet +facet normal -0.984732 0.174076 -0.000492027 + outer loop + vertex -5.462588851477786 0.6404084944085295 12.24074074074071 + vertex -5.350499757292488 1.27363744731891 11.93984222403835 + vertex -5.463300394916927 0.6343096995163731 11.50709967217639 + endloop +endfacet +facet normal 0.793673 0.608339 0.00257518 + outer loop + vertex 4.151017607888463 3.608192458697283 20.42672570575831 + vertex 4.13511894113438 3.626401983050373 21.02504478767688 + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + endloop +endfacet +facet normal -0.864792 0.502127 -0.00159081 + outer loop + vertex -4.59137142082812 3.028086603121313 10.84686772092755 + vertex -4.580458097205558 3.044569529464557 10.11690366370986 + vertex -4.911652466281053 2.475009101089377 10.38261171957252 + endloop +endfacet +facet normal 0.00112275 0.999991 -0.00411884 + outer loop + vertex -0.3116778562646466 5.491161708956882 2.849244344490732 + vertex 0.3484132606717201 5.488953288176909 2.493006867666852 + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + endloop +endfacet +facet normal -0.800266 0.599644 -0.00095977 + outer loop + vertex -4.20510078902244 3.545014436382855 20.01829885998822 + vertex -4.585867558739597 3.036415441552708 19.74358804414167 + vertex -4.578874889937365 3.046950072170709 20.49484434252649 + endloop +endfacet +facet normal 0.536837 0.843686 0.000667719 + outer loop + vertex 3.219421791503083 4.459296281746155 19.68454339005858 + vertex 3.21270192299947 4.464140046409332 18.96695942887282 + vertex 2.679298557411213 4.803265476762053 19.31909555152663 + endloop +endfacet +facet normal 0.538709 0.842486 -0.00322923 + outer loop + vertex 2.679298557411213 4.803265476762053 19.31909555152663 + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + vertex 3.219421791503083 4.459296281746155 19.68454339005858 + endloop +endfacet +facet normal 0.982666 0.184212 -0.0208463 + outer loop + vertex 5.330076268660247 1.356571771144032 19.73017849541023 + vertex 5.417922838555951 0.9466319852264811 20.24864700637255 + vertex 5.462588851477741 0.6404084944089157 19.64814814814814 + endloop +endfacet +facet normal -0.12114 0.992628 -0.0037645 + outer loop + vertex -0.3783033396193837 5.486974264859716 20.49523979426701 + vertex -0.3289149400880707 5.490156187412783 19.74495734050066 + vertex -0.983224731892634 5.411401770945737 20.03428894565108 + endloop +endfacet +facet normal 0.443114 0.896465 -7.9029e-05 + outer loop + vertex 2.721769633243516 4.779327365179483 3.944197539972951 + vertex 2.144565988556506 5.064665509263831 4.3035861781698 + vertex 2.720921121897517 4.779810482478564 4.666845165150066 + endloop +endfacet +facet normal 0.536548 0.84387 5.3123e-05 + outer loop + vertex 2.679298557411213 4.803265476762053 19.31909555152663 + vertex 3.21270192299947 4.464140046409332 18.96695942887282 + vertex 2.679885196006852 4.802938198251494 18.5928712167449 + endloop +endfacet +facet normal -0.802704 0.596374 0.00217724 + outer loop + vertex -4.203565089212222 3.546835285258711 19.28997812941705 + vertex -4.220875575088082 3.526217432267168 18.55545174289028 + vertex -4.601993462768863 3.011919017608647 18.91804789924629 + endloop +endfacet +facet normal 0.442844 0.896597 -0.00196618 + outer loop + vertex 2.725396144507114 4.777260287602693 3.226181988385524 + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + vertex 2.148095142858107 5.063169684814978 3.577663568096047 + endloop +endfacet +facet normal 0.536654 0.843802 -0.000159045 + outer loop + vertex 3.21270192299947 4.464140046409332 18.96695942887282 + vertex 3.214343495057338 4.462958200093585 18.23579293570337 + vertex 2.679885196006852 4.802938198251494 18.5928712167449 + endloop +endfacet +facet normal -0.984685 0.17434 -0.000779357 + outer loop + vertex -5.462288539552118 0.642964937362526 16.6854252851455 + vertex -5.349945281483502 1.275964531298738 16.34425104958763 + vertex -5.463422928156496 0.6332534311742012 15.94624735955442 + endloop +endfacet +facet normal 0.335963 0.941873 0.00184734 + outer loop + vertex 2.148095142858107 5.063169684814978 3.577663568096047 + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + vertex 1.551714848063318 5.276569058611839 3.234735469707145 + endloop +endfacet +facet normal 0.327936 0.9447 -0.00026107 + outer loop + vertex 1.502711983249084 5.290733096216402 19.30996315390948 + vertex 2.097043851292467 5.084526240049947 19.68886074002475 + vertex 2.100144231072024 5.083246424156013 18.95220948434659 + endloop +endfacet +facet normal 0.327862 0.944593 0.0158355 + outer loop + vertex 1.772743246953266 5.20647494763795 2.117973314103827 + vertex 1.511780695860853 5.288148932057651 2.649115272515396 + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + endloop +endfacet +facet normal 0.998164 0.0605769 -0 + outer loop + vertex 5.5 0 18.53703703703703 + vertex 5.459634833976192 0.6651221539189293 18.90754991733586 + vertex 5.5 0 19.27777777777777 + endloop +endfacet +facet normal -0.984919 0.173013 0.00113228 + outer loop + vertex -5.462588851477786 0.6404084944085295 12.24074074074071 + vertex -5.464240887080524 0.6261561530141311 12.98148148148145 + vertex -5.351863082258487 1.267896505539267 12.6753219338857 + endloop +endfacet +facet normal -0.918047 0.396467 -0.00163945 + outer loop + vertex -5.165673575632222 1.88833696940324 10.75291307090809 + vertex -4.921676533348395 2.455015295489565 11.16072658817533 + vertex -4.911652466281053 2.475009101089377 10.38261171957252 + endloop +endfacet +facet normal -0.235617 0.971846 2.67174e-05 + outer loop + vertex -1.60330531894182 5.261122699030396 17.45467039924617 + vertex -1.603634914426853 5.261022244890358 18.20203651395213 + vertex -0.9839543072603515 5.411269159931319 17.84228907674125 + endloop +endfacet +facet normal 0.337319 0.94139 -0.000299902 + outer loop + vertex 1.558182631274909 5.274662727378235 3.941249219772481 + vertex 2.144565988556506 5.064665509263831 4.3035861781698 + vertex 2.148095142858107 5.063169684814978 3.577663568096047 + endloop +endfacet +facet normal -0.98473 0.174087 -0.000466474 + outer loop + vertex -5.351863082258487 1.267896505539267 12.6753219338857 + vertex -5.350499757292488 1.27363744731891 11.93984222403835 + vertex -5.462588851477786 0.6404084944085295 12.24074074074071 + endloop +endfacet +facet normal -0.984776 0.173828 -0.00059842 + outer loop + vertex -5.462588851477785 0.6404084944085344 15.20370370370368 + vertex -5.350973674996689 1.271644891269743 14.88756196999887 + vertex -5.463457015218254 0.6329592742526507 14.46853726531237 + endloop +endfacet +facet normal 0.983685 0.178883 0.0190795 + outer loop + vertex 5.462588851477906 0.6404084944075038 2.61111111111111 + vertex 5.388402417417908 1.102324538402753 2.105178344957057 + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + endloop +endfacet +facet normal 0.115388 0.99332 -0.000459498 + outer loop + vertex 0.3103090457671292 5.491239231368006 5.391732547173166 + vertex 0.315996693737555 5.490914868175151 6.118810656870219 + vertex 0.9539730636607033 5.416635061900498 5.751691864852545 + endloop +endfacet +facet normal -0.552648 0.833415 -0.000182276 + outer loop + vertex -2.769452990619945 4.751855441061548 18.19930691019432 + vertex -2.767469228871303 4.753011052717054 17.46845059441797 + vertex -3.300431501637465 4.399676340709515 17.83016257702401 + endloop +endfacet +facet normal -0.982654 0.185128 0.0108528 + outer loop + vertex -5.329642713413715 1.358274106120005 3.143864560230363 + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + vertex -5.46258885147774 0.6404084944089274 3.351851851851849 + endloop +endfacet +facet normal 0.33661 0.941643 0.00111842 + outer loop + vertex 2.144565988556506 5.064665509263831 4.3035861781698 + vertex 1.545322340430237 5.278444739141182 4.668058894735688 + vertex 2.15734721088084 5.05923442940774 5.029478211222619 + endloop +endfacet +facet normal 0.984338 0.176167 0.00666325 + outer loop + vertex 5.466427009523622 0.6067748755103708 17.19140785290995 + vertex 5.458193291725775 0.6768500499813518 16.55505310407936 + vertex 5.347696406214424 1.285357205978686 16.79025874800341 + endloop +endfacet +facet normal -0.551275 0.834323 -0.000143596 + outer loop + vertex -2.764583419145227 4.754690160103736 18.92372716072775 + vertex -3.29025226001403 4.407293961772072 18.55877352661438 + vertex -3.288785535624673 4.408388560536143 19.2877628911882 + endloop +endfacet +facet normal -0.452415 0.891807 0.000529441 + outer loop + vertex -2.203868660299036 5.039143074784812 17.10367686674364 + vertex -2.767469228871303 4.753011052717054 17.46845059441797 + vertex -2.197700735824538 5.041836121469666 17.83800695130835 + endloop +endfacet +facet normal -0.792636 0.609677 -0.00472979 + outer loop + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + vertex -4.54305039848295 3.100111784572277 2.822942061993703 + vertex -4.142727898941744 3.617707223550536 2.454219851588245 + endloop +endfacet +facet normal -0.957774 0.287522 0.00032881 + outer loop + vertex -5.351430836992411 1.269719652870942 17.80587799198893 + vertex -5.166641334823746 1.885687491948415 17.44774793172886 + vertex -5.350454380830277 1.273828056942577 17.05762700172786 + endloop +endfacet +facet normal -0.00183686 0.999998 -0.000335032 + outer loop + vertex -0.3289149400880707 5.490156187412783 19.74495734050066 + vertex 0.3070111775077362 5.491424599945383 20.04433390229711 + vertex 0.3112636309729526 5.491185204674263 19.3064763842535 + endloop +endfacet +facet normal -0.984736 0.174056 -0.000329381 + outer loop + vertex -5.351430836992411 1.269719652870942 17.80587799198893 + vertex -5.350454380830277 1.273828056942577 17.05762700172786 + vertex -5.462690840943001 0.6395379396700769 17.42612912729039 + endloop +endfacet +facet normal -0.551933 0.833719 0.0167973 + outer loop + vertex -3.049579275765538 4.577124232618265 2.117940666612885 + vertex -3.287161039918808 4.409600015606847 2.626292319656475 + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + endloop +endfacet +facet normal -0.956547 0.291577 0.000351077 + outer loop + vertex -5.159487311214056 1.905174712571303 14.52663788554383 + vertex -5.161035683133057 1.900976243256948 13.79485434302383 + vertex -5.344337296030745 1.299253195591523 14.11425982063323 + endloop +endfacet +facet normal 0.443308 0.896369 0.000308148 + outer loop + vertex 2.148095142858107 5.063169684814978 3.577663568096047 + vertex 2.144565988556506 5.064665509263831 4.3035861781698 + vertex 2.721769633243516 4.779327365179483 3.944197539972951 + endloop +endfacet +facet normal -0.452236 0.891898 0.000182743 + outer loop + vertex -2.197700735824538 5.041836121469666 17.83800695130835 + vertex -2.767469228871303 4.753011052717054 17.46845059441797 + vertex -2.769452990619945 4.751855441061548 18.19930691019432 + endloop +endfacet +facet normal -0.726939 0.686699 -0.00214369 + outer loop + vertex -4.203565089212222 3.546835285258711 19.28997812941705 + vertex -3.770575664540913 4.004092800869112 18.93615773712017 + vertex -4.220875575088082 3.526217432267168 18.55545174289028 + endloop +endfacet +facet normal -0.998216 0.0597032 0 + outer loop + vertex -5.5 0 4.462962962962957 + vertex -5.460790787961493 0.6555638566264151 4.092472815228255 + vertex -5.5 0 3.722222222222218 + endloop +endfacet +facet normal 0.998228 0.0594691 -0.00199715 + outer loop + vertex 5.5 0 19.27777777777777 + vertex 5.459634833976192 0.6651221539189293 18.90754991733586 + vertex 5.462588851477741 0.6404084944089157 19.64814814814814 + endloop +endfacet +facet normal 0.443634 0.896207 -0.00110597 + outer loop + vertex 2.720921121897517 4.779810482478564 4.666845165150066 + vertex 2.144565988556506 5.064665509263831 4.3035861781698 + vertex 2.15734721088084 5.05923442940774 5.029478211222619 + endloop +endfacet +facet normal 0.630327 0.77633 -0.000207922 + outer loop + vertex 3.214343495057338 4.462958200093585 18.23579293570337 + vertex 3.706682292000083 4.063312243253404 18.60767167829646 + vertex 3.708637154518411 4.061528093726003 17.8723667800185 + endloop +endfacet +facet normal 0.998228 0.0594687 0.00199639 + outer loop + vertex 5.462588851477742 0.6404084944089036 18.16666666666666 + vertex 5.459634833976192 0.6651221539189293 18.90754991733586 + vertex 5.5 0 18.53703703703703 + endloop +endfacet +facet normal -0.346136 0.938184 -2.65469e-05 + outer loop + vertex -2.197700735824538 5.041836121469666 17.83800695130835 + vertex -1.603634914426853 5.261022244890358 18.20203651395213 + vertex -1.60330531894182 5.261122699030396 17.45467039924617 + endloop +endfacet +facet normal -0.984857 0.173367 0.000564286 + outer loop + vertex -5.462588851477785 0.6404084944085344 15.20370370370368 + vertex -5.463422928156496 0.6332534311742012 15.94624735955442 + vertex -5.351961835250633 1.267479591165347 15.6259277296983 + endloop +endfacet +facet normal 0.338057 0.941124 -0.00164676 + outer loop + vertex 2.15734721088084 5.05923442940774 5.029478211222619 + vertex 1.545322340430237 5.278444739141182 4.668058894735688 + vertex 1.564944612513594 5.272660463159435 5.390523919726905 + endloop +endfacet +facet normal 0.435103 0.900381 0.000266967 + outer loop + vertex 2.100144231072024 5.083246424156013 18.95220948434659 + vertex 2.097043851292467 5.084526240049947 19.68886074002475 + vertex 2.679298557411213 4.803265476762053 19.31909555152663 + endloop +endfacet +facet normal -0.333063 0.942877 -0.00720525 + outer loop + vertex -1.549281538959688 5.277284028080988 3.565126421480367 + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + vertex -2.150872866283984 5.061990311437125 3.200430427666638 + endloop +endfacet +facet normal 0.228343 0.973579 -0.00182549 + outer loop + vertex 1.564944612513594 5.272660463159435 5.390523919726905 + vertex 0.9315810629179355 5.420531037012212 5.028583438976002 + vertex 0.9539730636607033 5.416635061900498 5.751691864852545 + endloop +endfacet +facet normal 0.641133 0.767409 0.00566287 + outer loop + vertex 3.259958712102899 4.429748209027733 3.581471263481195 + vertex 3.753167914507547 4.02041423307488 3.213151815948938 + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + endloop +endfacet +facet normal 0.854174 0.519971 -0.00421947 + outer loop + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + vertex 4.839878840573146 2.612579722912267 20.28782012505717 + vertex 4.533873164080951 3.113517967191868 20.0724298361627 + endloop +endfacet +facet normal 0.638327 0.769765 -0.000711536 + outer loop + vertex 3.746583584735469 4.026550812120806 3.945041764355005 + vertex 3.753167914507547 4.02041423307488 3.213151815948938 + vertex 3.259958712102899 4.429748209027733 3.581471263481195 + endloop +endfacet +facet normal 0.115205 0.993341 -0.000782351 + outer loop + vertex 0.315996693737555 5.490914868175151 6.118810656870219 + vertex 0.9442376295085446 5.41834064073311 6.483655795020083 + vertex 0.9539730636607033 5.416635061900498 5.751691864852545 + endloop +endfacet +facet normal -0.984753 0.173955 -0.000336578 + outer loop + vertex -5.351961835250633 1.267479591165347 15.6259277296983 + vertex -5.350973674996689 1.271644891269743 14.88756196999887 + vertex -5.462588851477785 0.6404084944085344 15.20370370370368 + endloop +endfacet +facet normal 0.226461 0.974019 0.00164756 + outer loop + vertex 1.564944612513594 5.272660463159435 5.390523919726905 + vertex 1.545322340430237 5.278444739141182 4.668058894735688 + vertex 0.9315810629179355 5.420531037012212 5.028583438976002 + endloop +endfacet +facet normal -0.718513 0.695513 -0.000949654 + outer loop + vertex -3.722911157666007 4.048448160977975 2.818116375233727 + vertex -4.16358638277272 3.593681737882416 3.170864763690249 + vertex -3.731787377688215 4.040267685157373 3.542647078583606 + endloop +endfacet +facet normal 0.63016 0.776466 0.00015973 + outer loop + vertex 3.21270192299947 4.464140046409332 18.96695942887282 + vertex 3.706682292000083 4.063312243253404 18.60767167829646 + vertex 3.214343495057338 4.462958200093585 18.23579293570337 + endloop +endfacet +facet normal -0.236727 0.971576 0.000188681 + outer loop + vertex -0.9912954322035247 5.409929146124968 16.38022546614373 + vertex -1.609463548531972 5.259242063828863 16.73470020974355 + vertex -0.9889336480867522 5.410361377919393 17.11772481178466 + endloop +endfacet +facet normal -0.720059 0.693913 0.000360086 + outer loop + vertex -3.734579928635062 4.037686559979134 4.271956172220666 + vertex -4.171455162931281 3.58454485585743 3.896746863015228 + vertex -4.174460453283732 3.581044529738519 4.632501134632069 + endloop +endfacet +facet normal -0.984908 0.173075 0.00126606 + outer loop + vertex -5.464240887080524 0.6261561530141311 12.98148148148145 + vertex -5.348365566948149 1.282569983386249 13.39022568509564 + vertex -5.351863082258487 1.267896505539267 12.6753219338857 + endloop +endfacet +facet normal 0.722508 0.691362 0.000703153 + outer loop + vertex 4.18473781379371 3.569029199909275 3.579980119828232 + vertex 3.753167914507547 4.02041423307488 3.213151815948938 + vertex 3.746583584735469 4.026550812120806 3.945041764355005 + endloop +endfacet +facet normal 0.9821 0.188057 0.0106471 + outer loop + vertex 5.352885295866843 1.263573903375872 14.83390153907896 + vertex 5.324109977345409 1.379801778927347 15.43526584087152 + vertex 5.45199573013907 0.7250810703261731 15.20311570077771 + endloop +endfacet +facet normal -0.859198 0.511642 -0.00069366 + outer loop + vertex -4.557314361194889 3.079104709691896 4.262217895531347 + vertex -4.55240678248791 3.086355858736654 3.531903144838723 + vertex -4.880564471515911 2.53576229946275 3.886044622293257 + endloop +endfacet +facet normal 0.865988 0.500064 0.000275906 + outer loop + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + vertex 4.573082867663997 3.055636281607814 1.92999455336682 + vertex 4.57176427209746 3.057608778175061 2.493642932651824 + endloop +endfacet +facet normal -0.998256 0.0590189 0.00121584 + outer loop + vertex -5.5 0 3.722222222222218 + vertex -5.460790787961493 0.6555638566264151 4.092472815228255 + vertex -5.46258885147774 0.6404084944089274 3.351851851851849 + endloop +endfacet +facet normal -0.984769 0.173866 -4.13696e-06 + outer loop + vertex -5.462690840943001 0.6395379396700769 17.42612912729039 + vertex -5.462684705259381 0.6395903461788828 18.16809101137283 + vertex -5.351430836992411 1.269719652870942 17.80587799198893 + endloop +endfacet +facet normal -0.998199 0.0599825 0.000495985 + outer loop + vertex -5.460052036612598 0.6616885653255702 4.838555684658132 + vertex -5.460790787961493 0.6555638566264151 4.092472815228255 + vertex -5.5 0 4.462962962962957 + endloop +endfacet +facet normal -0.794613 0.607115 0.000688273 + outer loop + vertex -4.557314361194889 3.079104709691896 4.262217895531347 + vertex -4.171455162931281 3.58454485585743 3.896746863015228 + vertex -4.55240678248791 3.086355858736654 3.531903144838723 + endloop +endfacet +facet normal -0.347199 0.937791 8.13207e-05 + outer loop + vertex -2.203868660299036 5.039143074784812 17.10367686674364 + vertex -1.609463548531972 5.259242063828863 16.73470020974355 + vertex -2.202922862387096 5.03955661366873 16.37282938396807 + endloop +endfacet +facet normal -0.719302 0.694697 0.000946895 + outer loop + vertex -3.731787377688215 4.040267685157373 3.542647078583606 + vertex -4.16358638277272 3.593681737882416 3.170864763690249 + vertex -4.171455162931281 3.58454485585743 3.896746863015228 + endloop +endfacet +facet normal 0.536688 0.843781 -8.7618e-05 + outer loop + vertex 2.679885196006852 4.802938198251494 18.5928712167449 + vertex 3.214343495057338 4.462958200093585 18.23579293570337 + vertex 2.678916879983762 4.803478359495134 17.86350278336204 + endloop +endfacet +facet normal -0.336837 0.941563 -0.000204322 + outer loop + vertex -2.150872866283984 5.061990311437125 3.200430427666638 + vertex -2.148518953838601 5.062989858275077 3.926012546223322 + vertex -1.549281538959688 5.277284028080988 3.565126421480367 + endloop +endfacet +facet normal 0.114131 0.993464 0.00181839 + outer loop + vertex 0.9539730636607033 5.416635061900498 5.751691864852545 + vertex 0.9315810629179355 5.420531037012212 5.028583438976002 + vertex 0.3103090457671292 5.491239231368006 5.391732547173166 + endloop +endfacet +facet normal -0.707395 0.706817 0.00138712 + outer loop + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + vertex -4.135091253779056 3.626433554185152 1.902145778937794 + vertex -4.142727898941744 3.617707223550536 2.454219851588245 + endloop +endfacet +facet normal 0.630621 0.776091 -6.96075e-05 + outer loop + vertex 3.709288892712822 4.060932886714244 17.14061865087743 + vertex 3.216302611646152 4.461546537952747 17.503573412454 + vertex 3.708637154518411 4.061528093726003 17.8723667800185 + endloop +endfacet +facet normal 0.722119 0.691769 -0.000273027 + outer loop + vertex 3.746583584735469 4.026550812120806 3.945041764355005 + vertex 4.18248952255274 3.571663673099212 4.308525434406096 + vertex 4.18473781379371 3.569029199909275 3.579980119828232 + endloop +endfacet +facet normal -0.859529 0.511087 0.000391799 + outer loop + vertex -4.880564471515911 2.53576229946275 3.886044622293257 + vertex -4.882873685769934 2.531312815282918 4.624276344327242 + vertex -4.557314361194889 3.079104709691896 4.262217895531347 + endloop +endfacet +facet normal -0.000565521 1 5.37411e-05 + outer loop + vertex -0.3225429946578834 5.490534219599867 6.48242493412219 + vertex 0.315996693737555 5.490914868175151 6.118810656870219 + vertex -0.3218670607994322 5.490573885776635 5.751440049854351 + endloop +endfacet +facet normal -0.719786 0.694196 -0.000299233 + outer loop + vertex -3.734579928635062 4.037686559979134 4.271956172220666 + vertex -3.731787377688215 4.040267685157373 3.542647078583606 + vertex -4.171455162931281 3.58454485585743 3.896746863015228 + endloop +endfacet +facet normal 0.228226 0.973608 -0.000647322 + outer loop + vertex 1.565967758461246 5.272356681737292 6.118716452020724 + vertex 0.9442376295085446 5.41834064073311 6.483655795020083 + vertex 1.558061537370548 5.274698498091292 6.85344604553776 + endloop +endfacet +facet normal 0.630503 0.776186 0.000190539 + outer loop + vertex 3.708637154518411 4.061528093726003 17.8723667800185 + vertex 3.216302611646152 4.461546537952747 17.503573412454 + vertex 3.214343495057338 4.462958200093585 18.23579293570337 + endloop +endfacet +facet normal -0.443186 0.89643 -0.00048256 + outer loop + vertex -2.154141002807604 5.060600412996767 4.650566298183991 + vertex -2.148518953838601 5.062989858275077 3.926012546223322 + vertex -2.715775427328977 4.782736019091594 4.282403839769607 + endloop +endfacet +facet normal 0.998144 0.0607457 0.00421293 + outer loop + vertex 5.462588851477747 0.6404084944088623 4.092592592592588 + vertex 5.45702188206679 0.6862304122116961 4.750840592067621 + vertex 5.5 0 4.462962962962957 + endloop +endfacet +facet normal 0.536739 0.843748 -0.00019059 + outer loop + vertex 3.214343495057338 4.462958200093585 18.23579293570337 + vertex 3.216302611646152 4.461546537952747 17.503573412454 + vertex 2.678916879983762 4.803478359495134 17.86350278336204 + endloop +endfacet +facet normal -0.641157 0.76741 -0.000206773 + outer loop + vertex -3.278777122892307 4.415837471918327 11.23609377014295 + vertex -3.276621723325886 4.417437049039737 10.48929820463972 + vertex -3.763344481104095 4.010889965648939 10.86304173914669 + endloop +endfacet +facet normal -0.912677 0.408681 -0.000391675 + outer loop + vertex -5.141032723106988 1.954426396655335 4.249564237577 + vertex -4.882873685769934 2.531312815282918 4.624276344327242 + vertex -4.880564471515911 2.53576229946275 3.886044622293257 + endloop +endfacet +facet normal -0.984666 0.174448 0.000485783 + outer loop + vertex -5.349418226983903 1.278172379928623 11.12731726119114 + vertex -5.462588851477657 0.6404084944096309 10.75925925925924 + vertex -5.463300394916927 0.6343096995163731 11.50709967217639 + endloop +endfacet +facet normal -0.443142 0.896451 -0.000396216 + outer loop + vertex -2.715775427328977 4.782736019091594 4.282403839769607 + vertex -2.148518953838601 5.062989858275077 3.926012546223322 + vertex -2.720098218800375 4.780278828695982 3.557694086819801 + endloop +endfacet +facet normal 0.436782 0.89956 0.00353586 + outer loop + vertex 2.679298557411213 4.803265476762053 19.31909555152663 + vertex 2.097043851292467 5.084526240049947 19.68886074002475 + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + endloop +endfacet +facet normal -0.959733 0.280758 0.00935624 + outer loop + vertex -5.353166631539835 1.262381485513969 20.01659691907136 + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + vertex -5.169860313545367 1.876844249912228 20.38100790963064 + endloop +endfacet +facet normal -0.11605 0.993243 6.70145e-05 + outer loop + vertex -0.9523018227384239 5.416929133596735 6.843717633780066 + vertex -0.3225429946578834 5.490534219599867 6.48242493412219 + vertex -0.9514647961173107 5.417076217088831 6.113238048924342 + endloop +endfacet +facet normal -0.982692 0.185213 -0.00347051 + outer loop + vertex -5.340910767784621 1.313267745192231 7.430202142616896 + vertex -5.331206571821438 1.35212295615743 6.756020103499217 + vertex -5.455499441625426 0.6982305080878859 7.053492151481383 + endloop +endfacet +facet normal -0.79498 0.606636 -0.000361154 + outer loop + vertex -4.174460453283732 3.581044529738519 4.632501134632069 + vertex -4.171455162931281 3.58454485585743 3.896746863015228 + vertex -4.557314361194889 3.079104709691896 4.262217895531347 + endloop +endfacet +facet normal -0.998184 0.0602383 -4.49679e-05 + outer loop + vertex -5.5 0 5.203703703703698 + vertex -5.460118703792913 0.6611382158753166 5.581173766959984 + vertex -5.460052036612598 0.6616885653255702 4.838555684658132 + endloop +endfacet +facet normal -0.998177 0.060348 0 + outer loop + vertex -5.5 0 6.68518518518518 + vertex -5.459939312520691 0.6626180676612138 6.321235945707285 + vertex -5.5 0 5.944444444444438 + endloop +endfacet +facet normal -0.717178 0.696886 0.00248909 + outer loop + vertex -3.722911157666007 4.048448160977975 2.818116375233727 + vertex -4.142727898941744 3.617707223550536 2.454219851588245 + vertex -4.16358638277272 3.593681737882416 3.170864763690249 + endloop +endfacet +facet normal -0.000795088 1 0.000452338 + outer loop + vertex -0.3218670607994322 5.490573885776635 5.751440049854351 + vertex 0.315996693737555 5.490914868175151 6.118810656870219 + vertex 0.3103090457671292 5.491239231368006 5.391732547173166 + endloop +endfacet +facet normal -0.11598 0.993252 -5.3348e-05 + outer loop + vertex -0.9514647961173107 5.417076217088831 6.113238048924342 + vertex -0.3225429946578834 5.490534219599867 6.48242493412219 + vertex -0.3218670607994322 5.490573885776635 5.751440049854351 + endloop +endfacet +facet normal -0.443646 0.896202 0.000392521 + outer loop + vertex -2.715775427328977 4.782736019091594 4.282403839769607 + vertex -2.720122581376576 4.780264965698579 5.010933649980581 + vertex -2.154141002807604 5.060600412996767 4.650566298183991 + endloop +endfacet +facet normal 0.338626 0.940921 0.000644851 + outer loop + vertex 1.558061537370548 5.274698498091292 6.85344604553776 + vertex 2.15678241110269 5.059475232784332 6.489597573843957 + vertex 1.565967758461246 5.272356681737292 6.118716452020724 + endloop +endfacet +facet normal -0.998182 0.0602792 0.000121423 + outer loop + vertex -5.5 0 5.944444444444438 + vertex -5.459939312520691 0.6626180676612138 6.321235945707285 + vertex -5.460118703792913 0.6611382158753166 5.581173766959984 + endloop +endfacet +facet normal 0.630768 0.775971 0.000262642 + outer loop + vertex 3.219014690661195 4.459590162930603 16.77024877340427 + vertex 3.216302611646152 4.461546537952747 17.503573412454 + vertex 3.709288892712822 4.060932886714244 17.14061865087743 + endloop +endfacet +facet normal -0.984824 0.173556 0.000181472 + outer loop + vertex -5.462964695849923 0.6371944223683722 19.64769863209551 + vertex -5.351943193941354 1.267558301943077 19.28010984818169 + vertex -5.462696518159603 0.6394894451724384 18.90815128244343 + endloop +endfacet +facet normal -0.957839 0.287304 0.000843718 + outer loop + vertex -5.350981125896581 1.271613538107609 10.38839257368468 + vertex -5.165673575632222 1.88833696940324 10.75291307090809 + vertex -5.16934903317279 1.878251999396124 10.01446444154432 + endloop +endfacet +facet normal -0.958032 0.28666 0.000423487 + outer loop + vertex -5.351943193941354 1.267558301943077 19.28010984818169 + vertex -5.353166631539835 1.262381485513969 20.01659691907136 + vertex -5.167666710260322 1.882875665482789 19.64864303455607 + endloop +endfacet +facet normal -0.543612 0.839336 0.000305785 + outer loop + vertex -2.720122581376576 4.780264965698579 5.010933649980581 + vertex -3.248170387885879 4.438399388435125 4.641195007400434 + vertex -3.251307770456957 4.436101642407015 5.370668124934424 + endloop +endfacet +facet normal -0.998186 0.0602127 0 + outer loop + vertex -5.5 0 5.944444444444438 + vertex -5.460118703792913 0.6611382158753166 5.581173766959984 + vertex -5.5 0 5.203703703703698 + endloop +endfacet +facet normal 0.229019 0.973422 0.000777837 + outer loop + vertex 0.9539730636607033 5.416635061900498 5.751691864852545 + vertex 0.9442376295085446 5.41834064073311 6.483655795020083 + vertex 1.565967758461246 5.272356681737292 6.118716452020724 + endloop +endfacet +facet normal -0.958185 0.28615 -0.00051339 + outer loop + vertex -5.353166631539835 1.262381485513969 20.01659691907136 + vertex -5.169860313545367 1.876844249912228 20.38100790963064 + vertex -5.167666710260322 1.882875665482789 19.64864303455607 + endloop +endfacet +facet normal 0.791217 0.611536 0.000263215 + outer loop + vertex 4.53775637602756 3.107855703185272 18.6123197078087 + vertex 4.152367342007283 3.606639080505752 18.24163162079938 + vertex 4.150161524325208 3.609177097623594 18.97560217998252 + endloop +endfacet +facet normal 0.113981 0.993483 -0.000503663 + outer loop + vertex 0.9379299192986701 5.419436083808387 7.216973568687898 + vertex 0.9442376295085446 5.41834064073311 6.483655795020083 + vertex 0.3105968174089972 5.491222961874286 6.849704176150293 + endloop +endfacet +facet normal -0.543267 0.83956 -0.000394037 + outer loop + vertex -2.715775427328977 4.782736019091594 4.282403839769607 + vertex -3.248170387885879 4.438399388435125 4.641195007400434 + vertex -2.720122581376576 4.780264965698579 5.010933649980581 + endloop +endfacet +facet normal -0.443453 0.896298 0.000203915 + outer loop + vertex -2.720098218800375 4.780278828695982 3.557694086819801 + vertex -2.148518953838601 5.062989858275077 3.926012546223322 + vertex -2.150872866283984 5.061990311437125 3.200430427666638 + endloop +endfacet +facet normal -0.998309 0.0581296 -0.000181618 + outer loop + vertex -5.5 0 19.27777777777777 + vertex -5.462964695849923 0.6371944223683722 19.64769863209551 + vertex -5.462696518159603 0.6394894451724384 18.90815128244343 + endloop +endfacet +facet normal 0.998302 0.0582574 0.000105422 + outer loop + vertex 5.5 0 3.722222222222218 + vertex 5.462745257056555 0.6390729664960926 3.349526788074936 + vertex 5.462588851477747 0.6404084944088623 4.092592592592588 + endloop +endfacet +facet normal -0.984844 0.173442 0.000716042 + outer loop + vertex -5.463422928156496 0.6332534311742012 15.94624735955442 + vertex -5.349945281483502 1.275964531298738 16.34425104958763 + vertex -5.351961835250633 1.267479591165347 15.6259277296983 + endloop +endfacet +facet normal 0.854895 0.518801 0.000262031 + outer loop + vertex 4.53580408311559 3.110704312465578 19.34349241566083 + vertex 4.533873164080951 3.113517967191868 20.0724298361627 + vertex 4.854264491803782 2.58575254879754 19.70841037355992 + endloop +endfacet +facet normal -0.985759 0.16799 -0.00767516 + outer loop + vertex -5.464008635492013 0.6281796170433402 20.37153635718997 + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + vertex -5.353166631539835 1.262381485513969 20.01659691907136 + endloop +endfacet +facet normal -0.984884 0.173216 -0.000418519 + outer loop + vertex -5.462964695849923 0.6371944223683722 19.64769863209551 + vertex -5.353166631539835 1.262381485513969 20.01659691907136 + vertex -5.351943193941354 1.267558301943077 19.28010984818169 + endloop +endfacet +facet normal 0.855476 0.51784 -0.00162755 + outer loop + vertex 4.53580408311559 3.110704312465578 19.34349241566083 + vertex 4.854264491803782 2.58575254879754 19.70841037355992 + vertex 4.864019593170021 2.56735533132018 18.98242990710356 + endloop +endfacet +facet normal 0.338034 0.941134 -0.000456586 + outer loop + vertex 2.151434623773428 5.061751580197203 7.222461682940452 + vertex 2.15678241110269 5.059475232784332 6.489597573843957 + vertex 1.558061537370548 5.274698498091292 6.85344604553776 + endloop +endfacet +facet normal 0.721556 0.692356 -0.00024467 + outer loop + vertex 4.18248952255274 3.571663673099212 4.308525434406096 + vertex 3.742433202854696 4.030408629676492 4.672797414005285 + vertex 4.180478332843585 3.574017474583094 5.038000552588223 + endloop +endfacet +facet normal 0.219768 0.975552 -0.000184249 + outer loop + vertex 1.505039275104873 5.29007152885401 18.58306770502023 + vertex 0.9098219135290052 5.424225666918958 18.93447455121602 + vertex 1.502711983249084 5.290733096216402 19.30996315390948 + endloop +endfacet +facet normal -0.955211 0.295814 -0.00818837 + outer loop + vertex -5.167592017862487 1.883080650668979 7.796888109715192 + vertex -5.134331014646105 1.971964764402015 7.127875330178659 + vertex -5.340910767784621 1.313267745192231 7.430202142616896 + endloop +endfacet +facet normal -0.229463 0.973317 -6.69524e-05 + outer loop + vertex -0.9514647961173107 5.417076217088831 6.113238048924342 + vertex -1.568027322643233 5.271744522968113 6.474271455702275 + vertex -0.9523018227384239 5.416929133596735 6.843717633780066 + endloop +endfacet +facet normal 0.796521 0.60461 -0.000228173 + outer loop + vertex 4.565564594631563 3.066858316298087 3.945112498922813 + vertex 4.18248952255274 3.571663673099212 4.308525434406096 + vertex 4.563949237429648 3.069261695940139 4.674562988651441 + endloop +endfacet +facet normal 0.790711 0.61219 -0.000301666 + outer loop + vertex 4.151017607888463 3.608192458697283 20.42672570575831 + vertex 4.533873164080951 3.113517967191868 20.0724298361627 + vertex 4.148507192168058 3.611078519851084 19.70342773220382 + endloop +endfacet +facet normal 0.114512 0.993422 0.000427261 + outer loop + vertex 0.3105968174089972 5.491222961874286 6.849704176150293 + vertex 0.9442376295085446 5.41834064073311 6.483655795020083 + vertex 0.315996693737555 5.490914868175151 6.118810656870219 + endloop +endfacet +facet normal 0.791381 0.611323 -0.000193337 + outer loop + vertex 4.539148916185716 3.105821488220152 17.8802646915997 + vertex 4.152367342007283 3.606639080505752 18.24163162079938 + vertex 4.53775637602756 3.107855703185272 18.6123197078087 + endloop +endfacet +facet normal -0.957989 0.286803 -4.18726e-05 + outer loop + vertex -5.351105589102382 1.271089679872062 9.64781585087977 + vertex -5.350981125896581 1.271613538107609 10.38839257368468 + vertex -5.16934903317279 1.878251999396124 10.01446444154432 + endloop +endfacet +facet normal -0.346422 0.938079 -0.000530534 + outer loop + vertex -2.197700735824538 5.041836121469666 17.83800695130835 + vertex -1.60330531894182 5.261122699030396 17.45467039924617 + vertex -2.203868660299036 5.039143074784812 17.10367686674364 + endloop +endfacet +facet normal -0.984776 0.173829 7.9811e-06 + outer loop + vertex -5.35151881279618 1.26934880796752 18.54320227256124 + vertex -5.462684705259381 0.6395903461788828 18.16809101137283 + vertex -5.462696518159603 0.6394894451724384 18.90815128244343 + endloop +endfacet +facet normal 0.336576 0.941656 0.00105545 + outer loop + vertex 1.558182631274909 5.274662727378235 3.941249219772481 + vertex 1.545322340430237 5.278444739141182 4.668058894735688 + vertex 2.144565988556506 5.064665509263831 4.3035861781698 + endloop +endfacet +facet normal 0.790699 0.612205 -0.000268555 + outer loop + vertex 4.148507192168058 3.611078519851084 19.70342773220382 + vertex 4.533873164080951 3.113517967191868 20.0724298361627 + vertex 4.53580408311559 3.110704312465578 19.34349241566083 + endloop +endfacet +facet normal -0.794032 0.607875 -0.000956054 + outer loop + vertex -4.171455162931281 3.58454485585743 3.896746863015228 + vertex -4.16358638277272 3.593681737882416 3.170864763690249 + vertex -4.55240678248791 3.086355858736654 3.531903144838723 + endloop +endfacet +facet normal -0.338208 0.941071 -0.000296427 + outer loop + vertex -1.561840781710691 5.273580697456458 5.017848521761371 + vertex -1.558235160707119 5.274647209428898 4.289890961578397 + vertex -2.154141002807604 5.060600412996767 4.650566298183991 + endloop +endfacet +facet normal -0.22955 0.973297 8.67619e-05 + outer loop + vertex -0.9523018227384239 5.416929133596735 6.843717633780066 + vertex -1.568027322643233 5.271744522968113 6.474271455702275 + vertex -1.56908345876859 5.271430270753735 7.20529155895101 + endloop +endfacet +facet normal -0.957908 0.287074 3.68478e-05 + outer loop + vertex -5.350996320403336 1.271549597550153 8.905278694477291 + vertex -5.351105589102382 1.271089679872062 9.64781585087977 + vertex -5.168278527335533 1.881195647422789 9.272684386469603 + endloop +endfacet +facet normal 0.334816 0.942283 0.000331362 + outer loop + vertex 2.13807510768009 5.067409084918917 12.35499137436904 + vertex 1.540798081005442 5.279767160923855 11.98214227948561 + vertex 1.536716324117605 5.280956631065102 12.72398985022994 + endloop +endfacet +facet normal -0.984999 0.17256 0.000728498 + outer loop + vertex -5.464008635492013 0.6281796170433402 20.37153635718997 + vertex -5.353166631539835 1.262381485513969 20.01659691907136 + vertex -5.462964695849923 0.6371944223683722 19.64769863209551 + endloop +endfacet +facet normal -0.235839 0.971792 0.000403208 + outer loop + vertex -0.9839543072603515 5.411269159931319 17.84228907674125 + vertex -0.9889336480867522 5.410361377919393 17.11772481178466 + vertex -1.60330531894182 5.261122699030396 17.45467039924617 + endloop +endfacet +facet normal 0.227569 0.973762 0.000502836 + outer loop + vertex 1.558061537370548 5.274698498091292 6.85344604553776 + vertex 0.9442376295085446 5.41834064073311 6.483655795020083 + vertex 0.9379299192986701 5.419436083808387 7.216973568687898 + endloop +endfacet +facet normal -0.984772 0.173851 -3.00604e-05 + outer loop + vertex -5.351430836992411 1.269719652870942 17.80587799198893 + vertex -5.462684705259381 0.6395903461788828 18.16809101137283 + vertex -5.35151881279618 1.26934880796752 18.54320227256124 + endloop +endfacet +facet normal -0.346961 0.93788 0.000517875 + outer loop + vertex -1.60330531894182 5.261122699030396 17.45467039924617 + vertex -1.609463548531972 5.259242063828863 16.73470020974355 + vertex -2.203868660299036 5.039143074784812 17.10367686674364 + endloop +endfacet +facet normal 0.715748 0.698359 0.000208365 + outer loop + vertex 3.708637154518411 4.061528093726003 17.8723667800185 + vertex 3.706682292000083 4.063312243253404 18.60767167829646 + vertex 4.152367342007283 3.606639080505752 18.24163162079938 + endloop +endfacet +facet normal -0.998071 0.062009 0.00303584 + outer loop + vertex -5.455499441625426 0.6982305080878859 7.053492151481383 + vertex -5.459939312520691 0.6626180676612138 6.321235945707285 + vertex -5.5 0 6.68518518518518 + endloop +endfacet +facet normal 0.106098 0.994356 -0.0002396 + outer loop + vertex 0.8975897917409533 5.426263223044237 16.75547133290806 + vertex 0.2690620830480533 5.493414748174931 17.11771016924891 + vertex 0.8945770936974713 5.426760711827249 17.4860158572045 + endloop +endfacet +facet normal 0.796695 0.604381 0.000273116 + outer loop + vertex 4.18473781379371 3.569029199909275 3.579980119828232 + vertex 4.18248952255274 3.571663673099212 4.308525434406096 + vertex 4.565564594631563 3.066858316298087 3.945112498922813 + endloop +endfacet +facet normal -0.80335 0.595508 0.000269665 + outer loop + vertex -4.601993462768863 3.011919017608647 18.91804789924629 + vertex -4.220875575088082 3.526217432267168 18.55545174289028 + vertex -4.600131190995158 3.014762515627636 18.18651027564389 + endloop +endfacet +facet normal 0.721831 0.692069 0.000447951 + outer loop + vertex 3.746583584735469 4.026550812120806 3.945041764355005 + vertex 3.742433202854696 4.030408629676492 4.672797414005285 + vertex 4.18248952255274 3.571663673099212 4.308525434406096 + endloop +endfacet +facet normal -0.984671 0.174421 0.000534486 + outer loop + vertex -5.350981125896581 1.271613538107609 10.38839257368468 + vertex -5.462588851477657 0.6404084944096309 10.75925925925924 + vertex -5.349418226983903 1.278172379928623 11.12731726119114 + endloop +endfacet +facet normal 0.796356 0.604828 0.000243979 + outer loop + vertex 4.563949237429648 3.069261695940139 4.674562988651441 + vertex 4.18248952255274 3.571663673099212 4.308525434406096 + vertex 4.180478332843585 3.574017474583094 5.038000552588223 + endloop +endfacet +facet normal -0.345206 0.938527 4.90433e-05 + outer loop + vertex -2.191088185537281 5.044713328148483 12.70458421599213 + vertex -2.191670631422892 5.044460312397986 13.44675804175767 + vertex -1.599638590842117 5.262238723080571 13.07511200794479 + endloop +endfacet +facet normal -0.552658 0.833408 -0.000203127 + outer loop + vertex -3.300431501637465 4.399676340709515 17.83016257702401 + vertex -2.767469228871303 4.753011052717054 17.46845059441797 + vertex -3.302472647521388 4.398144428321229 17.09833579472796 + endloop +endfacet +facet normal -0.998303 0.0582411 4.1418e-06 + outer loop + vertex -5.5 0 17.79629629629628 + vertex -5.462684705259381 0.6395903461788828 18.16809101137283 + vertex -5.462690840943001 0.6395379396700769 17.42612912729039 + endloop +endfacet +facet normal -0.337122 0.941461 -0.000739559 + outer loop + vertex -1.549281538959688 5.277284028080988 3.565126421480367 + vertex -2.148518953838601 5.062989858275077 3.926012546223322 + vertex -1.558235160707119 5.274647209428898 4.289890961578397 + endloop +endfacet +facet normal -0.912826 0.408349 0.000221547 + outer loop + vertex -5.142036710810895 1.951783406188575 4.984386788694756 + vertex -4.882873685769934 2.531312815282918 4.624276344327242 + vertex -5.141032723106988 1.954426396655335 4.249564237577 + endloop +endfacet +facet normal -0.998363 0.0572009 0 + outer loop + vertex -5.5 0 20.75925925925926 + vertex -5.464008635492013 0.6281796170433402 20.37153635718997 + vertex -5.5 0 20.01851851851852 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 2.24074074074074 + vertex 5.462588851477906 0.6404084944075038 2.61111111111111 + vertex 5.5 0 2.98148148148148 + endloop +endfacet +facet normal -0.998339 0.0576055 -0.000722404 + outer loop + vertex -5.464008635492013 0.6281796170433402 20.37153635718997 + vertex -5.462964695849923 0.6371944223683722 19.64769863209551 + vertex -5.5 0 20.01851851851852 + endloop +endfacet +facet normal 0.998302 0.0582571 -0.000106087 + outer loop + vertex 5.462588851477906 0.6404084944075038 2.61111111111111 + vertex 5.462745257056555 0.6390729664960926 3.349526788074936 + vertex 5.5 0 2.98148148148148 + endloop +endfacet +facet normal -0.236316 0.971676 -0.0005168 + outer loop + vertex -0.9889336480867522 5.410361377919393 17.11772481178466 + vertex -1.609463548531972 5.259242063828863 16.73470020974355 + vertex -1.60330531894182 5.261122699030396 17.45467039924617 + endloop +endfacet +facet normal 0.219083 0.975705 -0.00140268 + outer loop + vertex 0.8921580186759523 5.427158931679834 18.21595266617183 + vertex 0.9098219135290052 5.424225666918958 18.93447455121602 + vertex 1.505039275104873 5.29007152885401 18.58306770502023 + endloop +endfacet +facet normal -0.9983 0.0582876 6.36598e-05 + outer loop + vertex -5.462581065098198 0.6404749075729896 10.01827514135803 + vertex -5.462675335659052 0.6396703660341518 9.276591032760054 + vertex -5.5 0 9.648148148148133 + endloop +endfacet +facet normal -0.912043 0.410087 -0.00247461 + outer loop + vertex -4.880564471515911 2.53576229946275 3.886044622293257 + vertex -4.866831821449069 2.562020300803789 3.176153595264171 + vertex -5.141451880835366 1.953323464522575 3.518268699072249 + endloop +endfacet +facet normal -0.984742 0.174022 -3.71233e-05 + outer loop + vertex -5.462675335659052 0.6396703660341518 9.276591032760054 + vertex -5.351105589102382 1.271089679872062 9.64781585087977 + vertex -5.350996320403336 1.271549597550153 8.905278694477291 + endloop +endfacet +facet normal -0.958044 0.286622 0.000491709 + outer loop + vertex -5.351943193941354 1.267558301943077 19.28010984818169 + vertex -5.167666710260322 1.882875665482789 19.64864303455607 + vertex -5.169773438355334 1.877083534655736 18.9201977983028 + endloop +endfacet +facet normal -0.912608 0.408836 -9.35222e-05 + outer loop + vertex -5.141032723106988 1.954426396655335 4.249564237577 + vertex -4.880564471515911 2.53576229946275 3.886044622293257 + vertex -5.141451880835366 1.953323464522575 3.518268699072249 + endloop +endfacet +facet normal 0.636338 0.77141 -0.000496074 + outer loop + vertex 3.248991982273831 4.437798001162329 10.15424391506147 + vertex 3.741330192435993 4.031432548259596 9.789771699872459 + vertex 3.243972728227046 4.44146833136511 9.423277641259309 + endloop +endfacet +facet normal -0.113999 0.99348 0.00119771 + outer loop + vertex -0.3167705464569702 5.490870279008361 3.573177574017768 + vertex -0.9278248657095747 5.421175243300202 3.223427943000292 + vertex -0.9426077132371609 5.418624428666911 3.932243735809454 + endloop +endfacet +facet normal -0.635582 0.772033 0.000298666 + outer loop + vertex -3.734579928635062 4.037686559979134 4.271956172220666 + vertex -3.24670894030754 4.439468555686265 3.913368189062605 + vertex -3.731787377688215 4.040267685157373 3.542647078583606 + endloop +endfacet +facet normal 0.105815 0.994386 0.000247151 + outer loop + vertex 0.8945770936974713 5.426760711827249 17.4860158572045 + vertex 0.2690620830480533 5.493414748174931 17.11771016924891 + vertex 0.265914278229262 5.493568020570403 17.84873078791945 + endloop +endfacet +facet normal -0.228342 0.973581 0.000295374 + outer loop + vertex -0.9475918392256525 5.417755043025934 4.657831776499254 + vertex -1.558235160707119 5.274647209428898 4.289890961578397 + vertex -1.561840781710691 5.273580697456458 5.017848521761371 + endloop +endfacet +facet normal -0.727471 0.686139 9.86618e-05 + outer loop + vertex -4.212012044866582 3.536800041548692 14.17214472345561 + vertex -4.212819464422161 3.535838254245488 14.90743681953956 + vertex -3.776397186416806 3.998602792279227 14.54124771470269 + endloop +endfacet +facet normal 0.907387 0.420245 -0.00658191 + outer loop + vertex 5.126158116024035 1.99311388774473 19.3527997429786 + vertex 4.854264491803782 2.58575254879754 19.70841037355992 + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + endloop +endfacet +facet normal -0.553001 0.83318 0.00051268 + outer loop + vertex -3.302472647521388 4.398144428321229 17.09833579472796 + vertex -2.767469228871303 4.753011052717054 17.46845059441797 + vertex -2.773056990794739 4.749753143670145 16.73580144231683 + endloop +endfacet +facet normal 0.950921 0.309334 0.00793336 + outer loop + vertex 5.126158116024035 1.99311388774473 19.3527997429786 + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + vertex 5.330076268660247 1.356571771144032 19.73017849541023 + endloop +endfacet +facet normal 0.983953 0.17843 -6.29821e-06 + outer loop + vertex 5.462642959302149 0.6399467940279513 6.305711372119314 + vertex 5.339527180018263 1.318881910500791 6.662341264607266 + vertex 5.462634190338693 0.6400216422455829 7.056229042449417 + endloop +endfacet +facet normal 0.856036 0.516917 0.000271809 + outer loop + vertex 4.53775637602756 3.107855703185272 18.6123197078087 + vertex 4.53580408311559 3.110704312465578 19.34349241566083 + vertex 4.864019593170021 2.56735533132018 18.98242990710356 + endloop +endfacet +facet normal -0.00117132 0.999999 0.000143942 + outer loop + vertex 0.3105968174089972 5.491222961874286 6.849704176150293 + vertex -0.3225429946578834 5.490534219599867 6.48242493412219 + vertex -0.3243621561378968 5.490427050026763 7.212153317015694 + endloop +endfacet +facet normal -0.45295 0.891536 -0.000509883 + outer loop + vertex -2.773056990794739 4.749753143670145 16.73580144231683 + vertex -2.767469228871303 4.753011052717054 17.46845059441797 + vertex -2.203868660299036 5.039143074784812 17.10367686674364 + endloop +endfacet +facet normal -0.984676 0.174395 0.000272057 + outer loop + vertex -5.462690840943001 0.6395379396700769 17.42612912729039 + vertex -5.350454380830277 1.273828056942577 17.05762700172786 + vertex -5.462288539552118 0.642964937362526 16.6854252851455 + endloop +endfacet +facet normal -0.954198 0.299175 9.57066e-05 + outer loop + vertex -5.141032723106988 1.954426396655335 4.249564237577 + vertex -5.141451880835366 1.953323464522575 3.518268699072249 + vertex -5.336450873075671 1.331274607002596 3.871193572221433 + endloop +endfacet +facet normal 0.537138 0.843494 -0.000263771 + outer loop + vertex 3.219014690661195 4.459590162930603 16.77024877340427 + vertex 2.680946204045271 4.802346036159332 17.13226512573994 + vertex 3.216302611646152 4.461546537952747 17.503573412454 + endloop +endfacet +facet normal 0.909288 0.416164 0.00167213 + outer loop + vertex 4.864019593170021 2.56735533132018 18.98242990710356 + vertex 4.854264491803782 2.58575254879754 19.70841037355992 + vertex 5.126158116024035 1.99311388774473 19.3527997429786 + endloop +endfacet +facet normal -0.114874 0.99338 -0.000347757 + outer loop + vertex -0.3211802337802007 5.490614105674236 4.298053992840217 + vertex -0.3167705464569702 5.490870279008361 3.573177574017768 + vertex -0.9426077132371609 5.418624428666911 3.932243735809454 + endloop +endfacet +facet normal -0.9581 0.286434 0.0001442 + outer loop + vertex -5.351943193941354 1.267558301943077 19.28010984818169 + vertex -5.169773438355334 1.877083534655736 18.9201977983028 + vertex -5.35151881279618 1.26934880796752 18.54320227256124 + endloop +endfacet +facet normal -0.957956 0.286915 -0.000243899 + outer loop + vertex -5.351105589102382 1.271089679872062 9.64781585087977 + vertex -5.16934903317279 1.878251999396124 10.01446444154432 + vertex -5.168278527335533 1.881195647422789 9.272684386469603 + endloop +endfacet +facet normal -0.984739 0.174038 -6.36236e-05 + outer loop + vertex -5.462581065098198 0.6404749075729896 10.01827514135803 + vertex -5.351105589102382 1.271089679872062 9.64781585087977 + vertex -5.462675335659052 0.6396703660341518 9.276591032760054 + endloop +endfacet +facet normal -0.33779 0.941221 0.00048295 + outer loop + vertex -1.558235160707119 5.274647209428898 4.289890961578397 + vertex -2.148518953838601 5.062989858275077 3.926012546223322 + vertex -2.154141002807604 5.060600412996767 4.650566298183991 + endloop +endfacet +facet normal -0.984791 0.173743 -0.000144982 + outer loop + vertex -5.351943193941354 1.267558301943077 19.28010984818169 + vertex -5.35151881279618 1.26934880796752 18.54320227256124 + vertex -5.462696518159603 0.6394894451724384 18.90815128244343 + endloop +endfacet +facet normal 0.9983 0.0582795 5.85189e-06 + outer loop + vertex 5.462642959302149 0.6399467940279513 6.305711372119314 + vertex 5.462634190338693 0.6400216422455829 7.056229042449417 + vertex 5.5 0 6.68518518518518 + endloop +endfacet +facet normal 0.537508 0.843259 0.000508332 + outer loop + vertex 2.686581987151288 4.7991954769851 16.39939846347043 + vertex 2.680946204045271 4.802346036159332 17.13226512573994 + vertex 3.219014690661195 4.459590162930603 16.77024877340427 + endloop +endfacet +facet normal -0.000839695 1 -0.000427734 + outer loop + vertex 0.3105968174089972 5.491222961874286 6.849704176150293 + vertex 0.315996693737555 5.490914868175151 6.118810656870219 + vertex -0.3225429946578834 5.490534219599867 6.48242493412219 + endloop +endfacet +facet normal 0.542788 0.83987 -0.000150679 + outer loop + vertex 3.248991982273831 4.437798001162329 10.15424391506147 + vertex 2.710732184049698 4.785596203855603 9.784975356056796 + vertex 2.712385502007586 4.784659328363833 10.5186368901123 + endloop +endfacet +facet normal -0.998293 0.0583957 -0.000272029 + outer loop + vertex -5.5 0 17.05555555555554 + vertex -5.462690840943001 0.6395379396700769 17.42612912729039 + vertex -5.462288539552118 0.642964937362526 16.6854252851455 + endloop +endfacet +facet normal 0.721476 0.69244 -4.22433e-05 + outer loop + vertex 4.180478332843585 3.574017474583094 5.038000552588223 + vertex 3.742433202854696 4.030408629676492 4.672797414005285 + vertex 3.742825607793919 4.03004422676006 5.401516095877726 + endloop +endfacet +facet normal -0.236921 0.971529 2.38879e-05 + outer loop + vertex -1.610314611093768 5.258981541448679 16.01007290764218 + vertex -0.9912954322035247 5.409929146124968 16.38022546614373 + vertex -0.9915929150321402 5.409874628016629 15.64704678609304 + endloop +endfacet +facet normal -0.858328 0.513097 0.00237471 + outer loop + vertex -4.880564471515911 2.53576229946275 3.886044622293257 + vertex -4.55240678248791 3.086355858736654 3.531903144838723 + vertex -4.866831821449069 2.562020300803789 3.176153595264171 + endloop +endfacet +facet normal -0.347111 0.937824 -0.000272712 + outer loop + vertex -1.605294890156283 5.260515974278391 19.65749372610342 + vertex -2.204987976597974 5.038653393820454 19.99453580293805 + vertex -1.608551244610577 5.259521165796537 20.38119086934289 + endloop +endfacet +facet normal 0.714055 0.700079 0.00370811 + outer loop + vertex 3.706797571246544 4.063207078872638 20.06301800731393 + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + vertex 4.151017607888463 3.608192458697283 20.42672570575831 + endloop +endfacet +facet normal 0.860859 0.508844 0.000212771 + outer loop + vertex 4.887524974198084 2.522320286282061 3.581719537648792 + vertex 4.567069689884858 3.064616525396779 3.216855658998866 + vertex 4.565564594631563 3.066858316298087 3.945112498922813 + endloop +endfacet +facet normal -0.113099 0.993584 -0.00039564 + outer loop + vertex -0.3167705464569702 5.490870279008361 3.573177574017768 + vertex -0.3116778562646466 5.491161708956882 2.849244344490732 + vertex -0.9278248657095747 5.421175243300202 3.223427943000292 + endloop +endfacet +facet normal 0.720439 0.693518 0.000533082 + outer loop + vertex 3.734233119467835 4.03800730676277 9.061319687521875 + vertex 4.179409421351509 3.575267387024115 9.429207426964693 + vertex 4.175055378160717 3.580350903094733 8.700074265015786 + endloop +endfacet +facet normal 0.790861 0.611995 0.000198792 + outer loop + vertex 4.150161524325208 3.609177097623594 18.97560217998252 + vertex 4.148507192168058 3.611078519851084 19.70342773220382 + vertex 4.53580408311559 3.110704312465578 19.34349241566083 + endloop +endfacet +facet normal -0.998318 0.0579773 0.000591455 + outer loop + vertex -5.462588851477785 0.6404084944085344 15.20370370370368 + vertex -5.463457015218254 0.6329592742526507 14.46853726531237 + vertex -5.5 0 14.83333333333331 + endloop +endfacet +facet normal -0.635556 0.772055 0.000241384 + outer loop + vertex -3.24670894030754 4.439468555686265 3.913368189062605 + vertex -3.249137396094532 4.437691537421236 3.203031802015037 + vertex -3.731787377688215 4.040267685157373 3.542647078583606 + endloop +endfacet +facet normal 0.856349 0.516397 0.000194028 + outer loop + vertex 4.539148916185716 3.105821488220152 17.8802646915997 + vertex 4.53775637602756 3.107855703185272 18.6123197078087 + vertex 4.865749673179342 2.564074904903351 18.25038236144107 + endloop +endfacet +facet normal -0.998302 0.0582508 0 + outer loop + vertex -5.5 0 9.648148148148133 + vertex -5.462675335659052 0.6396703660341518 9.276591032760054 + vertex -5.5 0 8.907407407407394 + endloop +endfacet +facet normal -0.917867 0.396887 -0.000851794 + outer loop + vertex -5.165673575632222 1.88833696940324 10.75291307090809 + vertex -4.911652466281053 2.475009101089377 10.38261171957252 + vertex -5.16934903317279 1.878251999396124 10.01446444154432 + endloop +endfacet +facet normal -0.801874 0.597494 -9.899e-05 + outer loop + vertex -4.593365995810843 3.025060136349137 14.53883673513825 + vertex -4.212819464422161 3.535838254245488 14.90743681953956 + vertex -4.212012044866582 3.536800041548692 14.17214472345561 + endloop +endfacet +facet normal -0.957282 0.28914 0.00316093 + outer loop + vertex -5.167592017862487 1.883080650668979 7.796888109715192 + vertex -5.340910767784621 1.313267745192231 7.430202142616896 + vertex -5.350685539569706 1.27285673060233 8.166452634993886 + endloop +endfacet +facet normal -0.984663 0.174467 0.000437895 + outer loop + vertex -5.462604141102114 0.640278062730595 8.536680095263456 + vertex -5.350685539569706 1.27285673060233 8.166452634993886 + vertex -5.461951509962761 0.6458217268066476 7.795483946606308 + endloop +endfacet +facet normal -0.643265 0.765636 -0.00343587 + outer loop + vertex -3.764535802277208 4.009771838069231 20.37321112384092 + vertex -3.318372368152656 4.386160601970809 20.71529429688674 + vertex -3.283048353747241 4.412662858972746 20.00757501231982 + endloop +endfacet +facet normal 0.797064 0.603894 0.000361494 + outer loop + vertex 4.567069689884858 3.064616525396779 3.216855658998866 + vertex 4.187714980302149 3.56553547784242 2.852014943758265 + vertex 4.18473781379371 3.569029199909275 3.579980119828232 + endloop +endfacet +facet normal -0.00139695 0.999999 -0.000251329 + outer loop + vertex 0.3105968174089972 5.491222961874286 6.849704176150293 + vertex -0.3243621561378968 5.490427050026763 7.212153317015694 + vertex 0.3074141288358063 5.491402057161006 7.579986864874797 + endloop +endfacet +facet normal -0.122808 0.99243 -0.000188357 + outer loop + vertex -0.9912954322035247 5.409929146124968 16.38022546614373 + vertex -0.9889336480867522 5.410361377919393 17.11772481178466 + vertex -0.3585134827399036 5.488302841743858 16.74886969383951 + endloop +endfacet +facet normal 0.860662 0.509176 0.000228298 + outer loop + vertex 4.886861798041292 2.523604914966807 4.311007271835738 + vertex 4.565564594631563 3.066858316298087 3.945112498922813 + vertex 4.563949237429648 3.069261695940139 4.674562988651441 + endloop +endfacet +facet normal 0.984367 0.176127 -0.00105394 + outer loop + vertex 5.464329314634285 0.6253839950209801 9.258668456006923 + vertex 5.343671221410812 1.301989968266224 9.635307021455539 + vertex 5.462846126101227 0.6382101554666896 10.01681138663804 + endloop +endfacet +facet normal -0.984268 0.176651 -0.00337161 + outer loop + vertex -5.350685539569706 1.27285673060233 8.166452634993886 + vertex -5.340910767784621 1.313267745192231 7.430202142616896 + vertex -5.461951509962761 0.6458217268066476 7.795483946606308 + endloop +endfacet +facet normal -0.866598 0.499008 -0.000266442 + outer loop + vertex -4.915818579230525 2.466724081872958 18.55622870078207 + vertex -4.601993462768863 3.011919017608647 18.91804789924629 + vertex -4.600131190995158 3.014762515627636 18.18651027564389 + endloop +endfacet +facet normal 0.791029 0.611778 -0.000271339 + outer loop + vertex 4.53775637602756 3.107855703185272 18.6123197078087 + vertex 4.150161524325208 3.609177097623594 18.97560217998252 + vertex 4.53580408311559 3.110704312465578 19.34349241566083 + endloop +endfacet +facet normal 0.861144 0.508361 0.000664039 + outer loop + vertex 4.567069689884858 3.064616525396779 3.216855658998866 + vertex 4.887805760937779 2.521776128712354 2.854314542228816 + vertex 4.57176427209746 3.057608778175061 2.493642932651824 + endloop +endfacet +facet normal -0.998298 0.0583182 0 + outer loop + vertex -5.5 0 3.722222222222218 + vertex -5.46258885147774 0.6404084944089274 3.351851851851849 + vertex -5.5 0 2.98148148148148 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 19.27777777777777 + vertex 5.462588851477741 0.6404084944089157 19.64814814814814 + vertex 5.5 0 20.01851851851852 + endloop +endfacet +facet normal -0.00342868 0.999994 0.000198929 + outer loop + vertex -0.3379244407656741 5.489609009058223 10.87394205312694 + vertex 0.2990237685235045 5.491865328452437 10.5099348930492 + vertex -0.3354015807467305 5.489763727122743 10.13967599684736 + endloop +endfacet +facet normal -0.643778 0.76521 -0.00182301 + outer loop + vertex -3.787528484899666 3.988060678584723 18.19338036402895 + vertex -3.770575664540913 4.004092800869112 18.93615773712017 + vertex -3.29025226001403 4.407293961772072 18.55877352661438 + endloop +endfacet +facet normal -0.116169 0.993229 -0.000143734 + outer loop + vertex -0.3243621561378968 5.490427050026763 7.212153317015694 + vertex -0.3225429946578834 5.490534219599867 6.48242493412219 + vertex -0.9523018227384239 5.416929133596735 6.843717633780066 + endloop +endfacet +facet normal 0.797426 0.603416 -0.000670628 + outer loop + vertex 4.567069689884858 3.064616525396779 3.216855658998866 + vertex 4.57176427209746 3.057608778175061 2.493642932651824 + vertex 4.187714980302149 3.56553547784242 2.852014943758265 + endloop +endfacet +facet normal 0.998342 0.0575534 0.000979419 + outer loop + vertex 5.464329314634285 0.6253839950209801 9.258668456006923 + vertex 5.462846126101227 0.6382101554666896 10.01681138663804 + vertex 5.5 0 9.648148148148133 + endloop +endfacet +facet normal 0.791435 0.611253 -3.87574e-05 + outer loop + vertex 4.152044140509771 3.607011152638494 17.50983287464635 + vertex 4.152367342007283 3.606639080505752 18.24163162079938 + vertex 4.539148916185716 3.105821488220152 17.8802646915997 + endloop +endfacet +facet normal -0.229685 0.973265 -0.000155766 + outer loop + vertex -0.9542500341208148 5.416586274802648 7.574184692568961 + vertex -0.9523018227384239 5.416929133596735 6.843717633780066 + vertex -1.56908345876859 5.271430270753735 7.20529155895101 + endloop +endfacet +facet normal 0.106251 0.994339 2.90481e-05 + outer loop + vertex 0.2694315000299995 5.493396642041387 16.38625459166656 + vertex 0.2690620830480533 5.493414748174931 17.11771016924891 + vertex 0.8975897917409533 5.426263223044237 16.75547133290806 + endloop +endfacet +facet normal 0.715829 0.698276 6.95789e-05 + outer loop + vertex 3.709288892712822 4.060932886714244 17.14061865087743 + vertex 3.708637154518411 4.061528093726003 17.8723667800185 + vertex 4.152044140509771 3.607011152638494 17.50983287464635 + endloop +endfacet +facet normal -0.116343 0.993209 0.000155887 + outer loop + vertex -0.9542500341208148 5.416586274802648 7.574184692568961 + vertex -0.3243621561378968 5.490427050026763 7.212153317015694 + vertex -0.9523018227384239 5.416929133596735 6.843717633780066 + endloop +endfacet +facet normal -0.339969 0.940437 0.00023378 + outer loop + vertex -2.16572987526206 5.055651699573199 7.567235143067204 + vertex -1.56908345876859 5.271430270753735 7.20529155895101 + vertex -2.163001353030806 5.056819667220386 6.836694798394829 + endloop +endfacet +facet normal -0.635264 0.772295 0.000937154 + outer loop + vertex -3.249137396094532 4.437691537421236 3.203031802015037 + vertex -3.722911157666007 4.048448160977975 2.818116375233727 + vertex -3.731787377688215 4.040267685157373 3.542647078583606 + endloop +endfacet +facet normal 0.715422 0.698693 0.000304805 + outer loop + vertex 3.706797571246544 4.063207078872638 20.06301800731393 + vertex 4.151017607888463 3.608192458697283 20.42672570575831 + vertex 4.148507192168058 3.611078519851084 19.70342773220382 + endloop +endfacet +facet normal 0.218826 0.975764 0.000192877 + outer loop + vertex 0.8945770936974713 5.426760711827249 17.4860158572045 + vertex 0.8921580186759523 5.427158931679834 18.21595266617183 + vertex 1.50976148259572 5.288725769565896 17.85447942085971 + endloop +endfacet +facet normal 0.715423 0.698692 0.000307173 + outer loop + vertex 3.709674271489997 4.060580845081792 19.33662734180532 + vertex 3.706797571246544 4.063207078872638 20.06301800731393 + vertex 4.148507192168058 3.611078519851084 19.70342773220382 + endloop +endfacet +facet normal 0.226541 0.974002 0.000231145 + outer loop + vertex 1.551714848063318 5.276569058611839 3.234735469707145 + vertex 0.9376243172597151 5.419488964808698 2.855592952321005 + vertex 0.9347541321142854 5.419984752053761 3.579453427105974 + endloop +endfacet +facet normal 0.856206 0.516634 -0.000291611 + outer loop + vertex 4.53775637602756 3.107855703185272 18.6123197078087 + vertex 4.864019593170021 2.56735533132018 18.98242990710356 + vertex 4.865749673179342 2.564074904903351 18.25038236144107 + endloop +endfacet +facet normal -0.720344 0.693617 -0.000361501 + outer loop + vertex -3.737953839354024 4.034563309065618 5.002338780429589 + vertex -3.734579928635062 4.037686559979134 4.271956172220666 + vertex -4.174460453283732 3.581044529738519 4.632501134632069 + endloop +endfacet +facet normal -0.00325617 0.999995 -9.66692e-05 + outer loop + vertex -0.3354015807467305 5.489763727122743 10.13967599684736 + vertex 0.2990237685235045 5.491865328452437 10.5099348930492 + vertex 0.3002524704688126 5.491798289629489 9.775064600251866 + endloop +endfacet +facet normal -0.998284 0.0585603 -0.000441007 + outer loop + vertex -5.462604141102114 0.640278062730595 8.536680095263456 + vertex -5.461951509962761 0.6458217268066476 7.795483946606308 + vertex -5.5 0 8.166666666666657 + endloop +endfacet +facet normal 0.115437 0.993311 0.00271169 + outer loop + vertex 0.3132164573217003 5.491074161843277 3.214441762681023 + vertex 0.9376243172597151 5.419488964808698 2.855592952321005 + vertex 0.3484132606717201 5.488953288176909 2.493006867666852 + endloop +endfacet +facet normal 0.439603 0.898192 0.00034397 + outer loop + vertex 2.699519646977631 4.791930057459288 13.46159641120867 + vertex 2.130062841592538 5.07078221686425 13.09066671338084 + vertex 2.126027404577531 5.072475478007294 13.82654127353561 + endloop +endfacet +facet normal 0.998027 0.0623651 0.00727405 + outer loop + vertex 5.462786065058352 0.6387240463645399 14.46303530577151 + vertex 5.45199573013907 0.7250810703261731 15.20311570077771 + vertex 5.5 0 14.83333333333331 + endloop +endfacet +facet normal 0.328177 0.944616 0.000191 + outer loop + vertex 1.505039275104873 5.29007152885401 18.58306770502023 + vertex 1.502711983249084 5.290733096216402 19.30996315390948 + vertex 2.100144231072024 5.083246424156013 18.95220948434659 + endloop +endfacet +facet normal -0.918357 0.395752 0.000357785 + outer loop + vertex -5.169773438355334 1.877083534655736 18.9201977983028 + vertex -4.915818579230525 2.466724081872958 18.55622870078207 + vertex -5.168219743892152 1.88135713750562 18.18109287916363 + endloop +endfacet +facet normal -0.235876 0.971783 0.000274481 + outer loop + vertex -1.605294890156283 5.260515974278391 19.65749372610342 + vertex -1.608551244610577 5.259521165796537 20.38119086934289 + vertex -0.983224731892634 5.411401770945737 20.03428894565108 + endloop +endfacet +facet normal 0.637276 0.770635 0.000149515 + outer loop + vertex 3.742825607793919 4.03004422676006 5.401516095877726 + vertex 3.25639733700985 4.432366905335698 5.035373969090404 + vertex 3.254868386254646 4.43348979790865 5.764558595360597 + endloop +endfacet +facet normal -0.236149 0.971717 0.000750777 + outer loop + vertex -1.605294890156283 5.260515974278391 19.65749372610342 + vertex -0.983224731892634 5.411401770945737 20.03428894565108 + vertex -0.9924759007625094 5.409712708305834 19.31055568031545 + endloop +endfacet +facet normal -0.339793 0.9405 -8.66102e-05 + outer loop + vertex -1.56908345876859 5.271430270753735 7.20529155895101 + vertex -1.568027322643233 5.271744522968113 6.474271455702275 + vertex -2.163001353030806 5.056819667220386 6.836694798394829 + endloop +endfacet +facet normal 0.984063 0.17781 0.00196924 + outer loop + vertex 5.462846126101227 0.6382101554666896 10.01681138663804 + vertex 5.343671221410812 1.301989968266224 9.635307021455539 + vertex 5.338145514410095 1.324463086304552 10.36741450328788 + endloop +endfacet +facet normal -0.998303 0.0582342 0 + outer loop + vertex -5.5 0 19.27777777777777 + vertex -5.462696518159603 0.6394894451724384 18.90815128244343 + vertex -5.5 0 18.53703703703703 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 3.722222222222218 + vertex 5.462588851477747 0.6404084944088623 4.092592592592588 + vertex 5.5 0 4.462962962962957 + endloop +endfacet +facet normal 0.219394 0.975636 0.000240369 + outer loop + vertex 0.8975897917409533 5.426263223044237 16.75547133290806 + vertex 0.8945770936974713 5.426760711827249 17.4860158572045 + vertex 1.513274589194329 5.287721628234483 17.1239828427341 + endloop +endfacet +facet normal 0.218503 0.975836 -0.000386257 + outer loop + vertex 0.8921580186759523 5.427158931679834 18.21595266617183 + vertex 1.505039275104873 5.29007152885401 18.58306770502023 + vertex 1.50976148259572 5.288725769565896 17.85447942085971 + endloop +endfacet +facet normal 0.544205 0.838952 7.81175e-05 + outer loop + vertex 3.254896381159889 4.433469245174963 4.308344229599244 + vertex 2.721769633243516 4.779327365179483 3.944197539972951 + vertex 2.720921121897517 4.779810482478564 4.666845165150066 + endloop +endfacet +facet normal -0.953852 0.30027 0.00221795 + outer loop + vertex -5.141451880835366 1.953323464522575 3.518268699072249 + vertex -5.329642713413715 1.358274106120005 3.143864560230363 + vertex -5.336450873075671 1.331274607002596 3.871193572221433 + endloop +endfacet +facet normal 0.715816 0.698288 3.88914e-05 + outer loop + vertex 3.708637154518411 4.061528093726003 17.8723667800185 + vertex 4.152367342007283 3.606639080505752 18.24163162079938 + vertex 4.152044140509771 3.607011152638494 17.50983287464635 + endloop +endfacet +facet normal -0.645001 0.764181 0.00102164 + outer loop + vertex -3.787528484899666 3.988060678584723 18.19338036402895 + vertex -3.29025226001403 4.407293961772072 18.55877352661438 + vertex -3.300431501637465 4.399676340709515 17.83016257702401 + endloop +endfacet +facet normal 0.544882 0.838513 0.000338081 + outer loop + vertex 3.259958712102899 4.429748209027733 3.581471263481195 + vertex 2.725396144507114 4.777260287602693 3.226181988385524 + vertex 2.721769633243516 4.779327365179483 3.944197539972951 + endloop +endfacet +facet normal -0.229904 0.973213 0.000230017 + outer loop + vertex -1.571882198856097 5.270596394424384 7.936098640024214 + vertex -0.9542500341208148 5.416586274802648 7.574184692568961 + vertex -1.56908345876859 5.271430270753735 7.20529155895101 + endloop +endfacet +facet normal -0.00403172 0.999992 0.000269415 + outer loop + vertex -0.3413497722383799 5.489397082830937 11.60929215863323 + vertex 0.2953835508501084 5.492062322833489 11.24521763091109 + vertex -0.3379244407656741 5.489609009058223 10.87394205312694 + endloop +endfacet +facet normal 0.443888 0.896082 0.000455781 + outer loop + vertex 2.720623379131812 4.779979961142243 6.858957268139787 + vertex 2.15678241110269 5.059475232784332 6.489597573843957 + vertex 2.151434623773428 5.061751580197203 7.222461682940452 + endloop +endfacet +facet normal 0.548051 0.83642 -0.00647787 + outer loop + vertex 3.259958712102899 4.429748209027733 3.581471263481195 + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + vertex 2.725396144507114 4.777260287602693 3.226181988385524 + endloop +endfacet +facet normal 0.2191 0.975702 -0.000287505 + outer loop + vertex 0.8945770936974713 5.426760711827249 17.4860158572045 + vertex 1.50976148259572 5.288725769565896 17.85447942085971 + vertex 1.513274589194329 5.287721628234483 17.1239828427341 + endloop +endfacet +facet normal 0.796865 0.604157 -0.000212885 + outer loop + vertex 4.567069689884858 3.064616525396779 3.216855658998866 + vertex 4.18473781379371 3.569029199909275 3.579980119828232 + vertex 4.565564594631563 3.066858316298087 3.945112498922813 + endloop +endfacet +facet normal 0.984806 0.173659 -6.49794e-05 + outer loop + vertex 5.463174314802662 0.635394685278737 12.98255000771282 + vertex 5.351088640648471 1.271161028321311 13.35230399535177 + vertex 5.463079625775358 0.6362083011389977 13.72188479775475 + endloop +endfacet +facet normal -0.00671714 0.99997 0.00392407 + outer loop + vertex -0.3621874643355 5.488061610503131 18.94966241806066 + vertex 0.3112636309729526 5.491185204674263 19.3064763842535 + vertex 0.262683298397841 5.493723462711136 18.57649404746713 + endloop +endfacet +facet normal -0.5443 0.838889 0.00158906 + outer loop + vertex -2.720098218800375 4.780278828695982 3.557694086819801 + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + vertex -3.249137396094532 4.437691537421236 3.203031802015037 + endloop +endfacet +facet normal 0.636928 0.770923 0.000254282 + outer loop + vertex 3.741065371887834 4.031678296102225 6.132109706259876 + vertex 3.254868386254646 4.43348979790865 5.764558595360597 + vertex 3.252261650712191 4.4354023667878 6.495472300639344 + endloop +endfacet +facet normal 0.860763 0.509006 -0.000113873 + outer loop + vertex 4.886861798041292 2.523604914966807 4.311007271835738 + vertex 4.887524974198084 2.522320286282061 3.581719537648792 + vertex 4.565564594631563 3.066858316298087 3.945112498922813 + endloop +endfacet +facet normal -0.543902 0.839149 -0.000301689 + outer loop + vertex -2.723449466112852 4.778370329466902 5.738895837883269 + vertex -2.720122581376576 4.780264965698579 5.010933649980581 + vertex -3.251307770456957 4.436101642407015 5.370668124934424 + endloop +endfacet +facet normal -0.953789 0.300478 -0.000222409 + outer loop + vertex -5.142036710810895 1.951783406188575 4.984386788694756 + vertex -5.141032723106988 1.954426396655335 4.249564237577 + vertex -5.332602887399606 1.346605526981597 4.611820020301286 + endloop +endfacet +facet normal -0.953696 0.300752 0.00360574 + outer loop + vertex -5.134331014646105 1.971964764402015 7.127875330178659 + vertex -5.331206571821438 1.35212295615743 6.756020103499217 + vertex -5.340910767784621 1.313267745192231 7.430202142616896 + endloop +endfacet +facet normal -0.998303 0.0582389 -7.99461e-06 + outer loop + vertex -5.462696518159603 0.6394894451724384 18.90815128244343 + vertex -5.462684705259381 0.6395903461788828 18.16809101137283 + vertex -5.5 0 18.53703703703703 + endloop +endfacet +facet normal 0.715558 0.698553 -0.000265065 + outer loop + vertex 4.152367342007283 3.606639080505752 18.24163162079938 + vertex 3.706682292000083 4.063312243253404 18.60767167829646 + vertex 4.150161524325208 3.609177097623594 18.97560217998252 + endloop +endfacet +facet normal 0.54456 0.838722 -0.000517315 + outer loop + vertex 3.25639733700985 4.432366905335698 5.035373969090404 + vertex 2.720921121897517 4.779810482478564 4.666845165150066 + vertex 2.72660673659052 4.776569449299277 5.397223163237941 + endloop +endfacet +facet normal 0.544483 0.838771 -0.000501799 + outer loop + vertex 3.254896381159889 4.433469245174963 4.308344229599244 + vertex 3.259958712102899 4.429748209027733 3.581471263481195 + vertex 2.721769633243516 4.779327365179483 3.944197539972951 + endloop +endfacet +facet normal -0.00370596 0.999993 -0.000286262 + outer loop + vertex 0.2953835508501084 5.492062322833489 11.24521763091109 + vertex 0.2990237685235045 5.491865328452437 10.5099348930492 + vertex -0.3379244407656741 5.489609009058223 10.87394205312694 + endloop +endfacet +facet normal -0.00830269 0.999965 -0.000330946 + outer loop + vertex -0.3627338163641405 5.488025526404365 16.01682901906203 + vertex -0.3585134827399036 5.488302841743858 16.74886969383951 + vertex 0.2694315000299995 5.493396642041387 16.38625459166656 + endloop +endfacet +facet normal -0.958015 0.286719 -0.000356025 + outer loop + vertex -5.169773438355334 1.877083534655736 18.9201977983028 + vertex -5.168219743892152 1.88135713750562 18.18109287916363 + vertex -5.35151881279618 1.26934880796752 18.54320227256124 + endloop +endfacet +facet normal 0.544238 0.838931 0.000148426 + outer loop + vertex 3.25639733700985 4.432366905335698 5.035373969090404 + vertex 3.254896381159889 4.433469245174963 4.308344229599244 + vertex 2.720921121897517 4.779810482478564 4.666845165150066 + endloop +endfacet +facet normal -0.116788 0.993157 0.000245366 + outer loop + vertex -0.3267336320428044 5.490286434576261 7.942507020545281 + vertex -0.9542500341208148 5.416586274802648 7.574184692568961 + vertex -0.9573168647443093 5.416045090328931 8.304983976598086 + endloop +endfacet +facet normal 0.722939 0.690911 -0.000359278 + outer loop + vertex 4.187714980302149 3.56553547784242 2.852014943758265 + vertex 3.753167914507547 4.02041423307488 3.213151815948938 + vertex 4.18473781379371 3.569029199909275 3.579980119828232 + endloop +endfacet +facet normal -0.00827942 0.999966 0.000228358 + outer loop + vertex -0.3585134827399036 5.488302841743858 16.74886969383951 + vertex -0.3614443539624955 5.488110601927464 17.48441322012165 + vertex 0.2690620830480533 5.493414748174931 17.11771016924891 + endloop +endfacet +facet normal -0.445119 0.895472 -0.000265005 + outer loop + vertex -2.163001353030806 5.056819667220386 6.836694798394829 + vertex -2.15990204534286 5.058144240185696 6.106736787693633 + vertex -2.7268006282093 4.776458765026383 6.4682204653972 + endloop +endfacet +facet normal -0.957615 0.28805 -0.000531335 + outer loop + vertex -5.350981125896581 1.271613538107609 10.38839257368468 + vertex -5.349418226983903 1.278172379928623 11.12731726119114 + vertex -5.165673575632222 1.88833696940324 10.75291307090809 + endloop +endfacet +facet normal -0.444505 0.895776 -0.00031351 + outer loop + vertex -2.15990204534286 5.058144240185696 6.106736787693633 + vertex -2.156242545109333 5.05970533595193 5.378616593031186 + vertex -2.723449466112852 4.778370329466902 5.738895837883269 + endloop +endfacet +facet normal -0.729336 0.684156 9.25893e-06 + outer loop + vertex -4.221761821939877 3.525156325443014 17.82343063942983 + vertex -3.787528484899666 3.988060678584723 18.19338036402895 + vertex -3.787613740678036 3.987979708000899 17.46072148755751 + endloop +endfacet +facet normal -0.983535 0.180667 0.0042085 + outer loop + vertex -5.461951509962761 0.6458217268066476 7.795483946606308 + vertex -5.340910767784621 1.313267745192231 7.430202142616896 + vertex -5.455499441625426 0.6982305080878859 7.053492151481383 + endloop +endfacet +facet normal -0.116537 0.993186 -0.000187181 + outer loop + vertex -0.3267336320428044 5.490286434576261 7.942507020545281 + vertex -0.3243621561378968 5.490427050026763 7.212153317015694 + vertex -0.9542500341208148 5.416586274802648 7.574184692568961 + endloop +endfacet +facet normal -0.998314 0.0580436 -0.000476503 + outer loop + vertex -5.463300394916927 0.6343096995163731 11.50709967217639 + vertex -5.462588851477657 0.6404084944096309 10.75925925925924 + vertex -5.5 0 11.12962962962961 + endloop +endfacet +facet normal -0.729289 0.684206 -0.000108857 + outer loop + vertex -4.221761821939877 3.525156325443014 17.82343063942983 + vertex -4.220875575088082 3.526217432267168 18.55545174289028 + vertex -3.787528484899666 3.988060678584723 18.19338036402895 + endloop +endfacet +facet normal 0.105304 0.99444 0.000255108 + outer loop + vertex 0.265914278229262 5.493568020570403 17.84873078791945 + vertex 0.262683298397841 5.493723462711136 18.57649404746713 + vertex 0.8921580186759523 5.427158931679834 18.21595266617183 + endloop +endfacet +facet normal 0.998323 0.0578972 6.41443e-05 + outer loop + vertex 5.463174314802662 0.635394685278737 12.98255000771282 + vertex 5.463079625775358 0.6362083011389977 13.72188479775475 + vertex 5.5 0 13.35185185185182 + endloop +endfacet +facet normal 0.637127 0.770759 -0.00018886 + outer loop + vertex 3.741065371887834 4.031678296102225 6.132109706259876 + vertex 3.742825607793919 4.03004422676006 5.401516095877726 + vertex 3.254868386254646 4.43348979790865 5.764558595360597 + endloop +endfacet +facet normal -0.00165225 0.999999 0.000187165 + outer loop + vertex 0.3074141288358063 5.491402057161006 7.579986864874797 + vertex -0.3243621561378968 5.490427050026763 7.212153317015694 + vertex -0.3267336320428044 5.490286434576261 7.942507020545281 + endloop +endfacet +facet normal -0.543436 0.83945 -0.000242149 + outer loop + vertex -3.24670894030754 4.439468555686265 3.913368189062605 + vertex -2.720098218800375 4.780278828695982 3.557694086819801 + vertex -3.249137396094532 4.437691537421236 3.203031802015037 + endloop +endfacet +facet normal 0.998299 0.0583005 3.06838e-05 + outer loop + vertex 5.5 0 7.42592592592592 + vertex 5.462634190338693 0.6400216422455829 7.056229042449417 + vertex 5.462588851477699 0.6404084944092698 7.796296296296289 + endloop +endfacet +facet normal -0.998303 0.0582387 0 + outer loop + vertex -5.5 0 17.79629629629628 + vertex -5.462690840943001 0.6395379396700769 17.42612912729039 + vertex -5.5 0 17.05555555555554 + endloop +endfacet +facet normal 0.113466 0.993542 0.000293559 + outer loop + vertex 0.9347541321142854 5.419984752053761 3.579453427105974 + vertex 0.3132164573217003 5.491074161843277 3.214441762681023 + vertex 0.30949445038025 5.491285203409474 3.938797738407567 + endloop +endfacet +facet normal -0.984267 0.176681 0.00134331 + outer loop + vertex -5.463457015218254 0.6329592742526507 14.46853726531237 + vertex -5.344337296030745 1.299253195591523 14.11425982063323 + vertex -5.461533276369314 0.6493491134287154 13.7223915162698 + endloop +endfacet +facet normal -0.803294 0.595582 0.000109205 + outer loop + vertex -4.600131190995158 3.014762515627636 18.18651027564389 + vertex -4.220875575088082 3.526217432267168 18.55545174289028 + vertex -4.221761821939877 3.525156325443014 17.82343063942983 + endloop +endfacet +facet normal 0.113769 0.993507 -0.000229369 + outer loop + vertex 0.9347541321142854 5.419984752053761 3.579453427105974 + vertex 0.9376243172597151 5.419488964808698 2.855592952321005 + vertex 0.3132164573217003 5.491074161843277 3.214441762681023 + endloop +endfacet +facet normal -0.451606 0.892217 -0.000933374 + outer loop + vertex -2.75983315162458 4.757448998696038 19.64732542503119 + vertex -2.204987976597974 5.038653393820454 19.99453580293805 + vertex -2.194459938233373 5.043247523123249 19.29217846862717 + endloop +endfacet +facet normal 0.00180664 0.999994 -0.00285164 + outer loop + vertex 0.3132164573217003 5.491074161843277 3.214441762681023 + vertex 0.3484132606717201 5.488953288176909 2.493006867666852 + vertex -0.3116778562646466 5.491161708956882 2.849244344490732 + endloop +endfacet +facet normal -0.998315 0.0580245 0 + outer loop + vertex -5.5 0 20.01851851851852 + vertex -5.462964695849923 0.6371944223683722 19.64769863209551 + vertex -5.5 0 19.27777777777777 + endloop +endfacet +facet normal 0.998305 0.0581962 -0 + outer loop + vertex 5.5 0 2.98148148148148 + vertex 5.462745257056555 0.6390729664960926 3.349526788074936 + vertex 5.5 0 3.722222222222218 + endloop +endfacet +facet normal -0.445708 0.895178 -0.000233504 + outer loop + vertex -2.16572987526206 5.055651699573199 7.567235143067204 + vertex -2.163001353030806 5.056819667220386 6.836694798394829 + vertex -2.730331237033483 4.774441468494426 7.198626627347451 + endloop +endfacet +facet normal -0.00920084 0.999958 -0.000235072 + outer loop + vertex -0.3652328073833823 5.487859782867165 18.21031711504795 + vertex -0.3621874643355 5.488061610503131 18.94966241806066 + vertex 0.262683298397841 5.493723462711136 18.57649404746713 + endloop +endfacet +facet normal -0.998183 0.060263 0 + outer loop + vertex -5.5 0 5.203703703703698 + vertex -5.460052036612598 0.6616885653255702 4.838555684658132 + vertex -5.5 0 4.462962962962957 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 17.79629629629628 + vertex 5.462588851477742 0.6404084944089036 18.16666666666666 + vertex 5.5 0 18.53703703703703 + endloop +endfacet +facet normal -0.123316 0.992367 7.3191e-05 + outer loop + vertex -0.9915550309688018 5.409881571768504 18.57253006430009 + vertex -0.9924759007625094 5.409712708305834 19.31055568031545 + vertex -0.3621874643355 5.488061610503131 18.94966241806066 + endloop +endfacet +facet normal 0.715629 0.698481 -0.000198151 + outer loop + vertex 4.150161524325208 3.609177097623594 18.97560217998252 + vertex 3.709674271489997 4.060580845081792 19.33662734180532 + vertex 4.148507192168058 3.611078519851084 19.70342773220382 + endloop +endfacet +facet normal -0.00812825 0.999967 -2.88579e-05 + outer loop + vertex -0.3585134827399036 5.488302841743858 16.74886969383951 + vertex 0.2690620830480533 5.493414748174931 17.11771016924891 + vertex 0.2694315000299995 5.493396642041387 16.38625459166656 + endloop +endfacet +facet normal -0.866514 0.499152 1.89048e-05 + outer loop + vertex -4.915818579230525 2.466724081872958 18.55622870078207 + vertex -4.600131190995158 3.014762515627636 18.18651027564389 + vertex -4.915709720630987 2.466941009123246 17.81820394054487 + endloop +endfacet +facet normal -0.118823 0.992915 -0.000199045 + outer loop + vertex -0.3379244407656741 5.489609009058223 10.87394205312694 + vertex -0.3354015807467305 5.489763727122743 10.13967599684736 + vertex -0.9682168451676494 5.414107141600875 10.50375290328457 + endloop +endfacet +facet normal -0.641774 0.766894 -8.57561e-05 + outer loop + vertex -3.765326991561123 4.009028890719206 19.65026233461441 + vertex -3.764535802277208 4.009771838069231 20.37321112384092 + vertex -3.283048353747241 4.412662858972746 20.00757501231982 + endloop +endfacet +facet normal -0.118247 0.992984 -0.000191034 + outer loop + vertex -0.3354015807467305 5.489763727122743 10.13967599684736 + vertex -0.3329773372250535 5.48991130100428 9.406191867178279 + vertex -0.9643705449208908 5.414793574282309 9.769856747733114 + endloop +endfacet +facet normal -0.115307 0.99333 0.000398133 + outer loop + vertex -0.3211802337802007 5.490614105674236 4.298053992840217 + vertex -0.9426077132371609 5.418624428666911 3.932243735809454 + vertex -0.9475918392256525 5.417755043025934 4.657831776499254 + endloop +endfacet +facet normal -0.340218 0.940347 -0.00022995 + outer loop + vertex -1.571882198856097 5.270596394424384 7.936098640024214 + vertex -1.56908345876859 5.271430270753735 7.20529155895101 + vertex -2.16572987526206 5.055651699573199 7.567235143067204 + endloop +endfacet +facet normal -0.64545 0.763803 -9.3048e-06 + outer loop + vertex -3.787528484899666 3.988060678584723 18.19338036402895 + vertex -3.300431501637465 4.399676340709515 17.83016257702401 + vertex -3.787613740678036 3.987979708000899 17.46072148755751 + endloop +endfacet +facet normal -0.865968 0.5001 0.000276552 + outer loop + vertex -4.914848247313041 2.46865686272595 15.6405238496727 + vertex -4.595606947051128 3.021654644100713 15.27457467989483 + vertex -4.913268007066149 2.471800455283604 14.90405506725276 + endloop +endfacet +facet normal -0.117671 0.993053 -0.000239028 + outer loop + vertex -0.3329773372250535 5.48991130100428 9.406191867178279 + vertex -0.3299439089030948 5.490094445178311 8.673741095686063 + vertex -0.9607923148651225 5.415429634636214 9.036838586275445 + endloop +endfacet +facet normal -0.444828 0.895616 0.000303482 + outer loop + vertex -2.15990204534286 5.058144240185696 6.106736787693633 + vertex -2.723449466112852 4.778370329466902 5.738895837883269 + vertex -2.7268006282093 4.776458765026383 6.4682204653972 + endloop +endfacet +facet normal -0.55052 0.834822 -0.000569382 + outer loop + vertex -3.288785535624673 4.408388560536143 19.2877628911882 + vertex -3.283048353747241 4.412662858972746 20.00757501231982 + vertex -2.75983315162458 4.757448998696038 19.64732542503119 + endloop +endfacet +facet normal -0.998292 0.0584017 -0.00129098 + outer loop + vertex -5.5 0 14.09259259259256 + vertex -5.463457015218254 0.6329592742526507 14.46853726531237 + vertex -5.461533276369314 0.6493491134287154 13.7223915162698 + endloop +endfacet +facet normal -0.236547 0.97162 6.13529e-06 + outer loop + vertex -1.605220724567375 5.260538606019291 18.93286370157931 + vertex -1.605294890156283 5.260515974278391 19.65749372610342 + vertex -0.9924759007625094 5.409712708305834 19.31055568031545 + endloop +endfacet +facet normal -0.11707 0.993124 -0.000253215 + outer loop + vertex -0.3299439089030948 5.490094445178311 8.673741095686063 + vertex -0.3267336320428044 5.490286434576261 7.942507020545281 + vertex -0.9573168647443093 5.416045090328931 8.304983976598086 + endloop +endfacet +facet normal -0.998284 0.0585518 0 + outer loop + vertex -5.5 0 17.05555555555554 + vertex -5.462288539552118 0.642964937362526 16.6854252851455 + vertex -5.5 0 16.3148148148148 + endloop +endfacet +facet normal 0.998301 0.058276 -0 + outer loop + vertex 5.5 0 5.944444444444438 + vertex 5.462642959302149 0.6399467940279513 6.305711372119314 + vertex 5.5 0 6.68518518518518 + endloop +endfacet +facet normal -0.338721 0.940887 -0.000287107 + outer loop + vertex -1.565338836542403 5.272543440011858 5.745524669891359 + vertex -1.561840781710691 5.273580697456458 5.017848521761371 + vertex -2.156242545109333 5.05970533595193 5.378616593031186 + endloop +endfacet +facet normal -0.34651 0.938046 0.000941728 + outer loop + vertex -2.194459938233373 5.043247523123249 19.29217846862717 + vertex -2.204987976597974 5.038653393820454 19.99453580293805 + vertex -1.605294890156283 5.260515974278391 19.65749372610342 + endloop +endfacet +facet normal 0.113545 0.993533 0.000251191 + outer loop + vertex 0.9379299192986701 5.419436083808387 7.216973568687898 + vertex 0.3105968174089972 5.491222961874286 6.849704176150293 + vertex 0.3074141288358063 5.491402057161006 7.579986864874797 + endloop +endfacet +facet normal 0.860936 0.508714 -4.82281e-05 + outer loop + vertex 4.887524974198084 2.522320286282061 3.581719537648792 + vertex 4.887805760937779 2.521776128712354 2.854314542228816 + vertex 4.567069689884858 3.064616525396779 3.216855658998866 + endloop +endfacet +facet normal -0.33847 0.940977 0.000179849 + outer loop + vertex -1.561840781710691 5.273580697456458 5.017848521761371 + vertex -2.154141002807604 5.060600412996767 4.650566298183991 + vertex -2.156242545109333 5.05970533595193 5.378616593031186 + endloop +endfacet +facet normal 0.328428 0.944529 -0.000261598 + outer loop + vertex 1.505039275104873 5.29007152885401 18.58306770502023 + vertex 2.100144231072024 5.083246424156013 18.95220948434659 + vertex 2.103215541586377 5.081976425135158 18.22266410324536 + endloop +endfacet +facet normal -0.00832115 0.999965 -0.000299347 + outer loop + vertex -0.3627338163641405 5.488025526404365 16.01682901906203 + vertex 0.2694315000299995 5.493396642041387 16.38625459166656 + vertex 0.2732321874398657 5.493208913899673 15.65350056583433 + endloop +endfacet +facet normal -0.95789 0.287135 0.000105072 + outer loop + vertex -5.350996320403336 1.271549597550153 8.905278694477291 + vertex -5.168346033474785 1.881010174950005 8.536010542375871 + vertex -5.350685539569706 1.27285673060233 8.166452634993886 + endloop +endfacet +facet normal -0.957844 0.28729 -0.000172369 + outer loop + vertex -5.168346033474785 1.881010174950005 8.536010542375871 + vertex -5.167592017862487 1.883080650668979 7.796888109715192 + vertex -5.350685539569706 1.27285673060233 8.166452634993886 + endloop +endfacet +facet normal 0.983871 0.178878 -0.000188713 + outer loop + vertex 5.462846126101227 0.6382101554666896 10.01681138663804 + vertex 5.338145514410095 1.324463086304552 10.36741450328788 + vertex 5.462588851477699 0.6404084944092698 10.75925925925924 + endloop +endfacet +facet normal 0.435267 0.900301 -5.41218e-05 + outer loop + vertex 2.100144231072024 5.083246424156013 18.95220948434659 + vertex 2.679298557411213 4.803265476762053 19.31909555152663 + vertex 2.679885196006852 4.802938198251494 18.5928712167449 + endloop +endfacet +facet normal -0.445425 0.895319 0.000319689 + outer loop + vertex -2.163001353030806 5.056819667220386 6.836694798394829 + vertex -2.7268006282093 4.776458765026383 6.4682204653972 + vertex -2.730331237033483 4.774441468494426 7.198626627347451 + endloop +endfacet +facet normal -0.117378 0.993087 0.000277732 + outer loop + vertex -0.3299439089030948 5.490094445178311 8.673741095686063 + vertex -0.9573168647443093 5.416045090328931 8.304983976598086 + vertex -0.9607923148651225 5.415429634636214 9.036838586275445 + endloop +endfacet +facet normal 0.544737 0.838607 -0.000149193 + outer loop + vertex 3.25639733700985 4.432366905335698 5.035373969090404 + vertex 2.72660673659052 4.776569449299277 5.397223163237941 + vertex 3.254868386254646 4.43348979790865 5.764558595360597 + endloop +endfacet +facet normal -0.984728 0.174098 4.23451e-05 + outer loop + vertex -5.462581065098198 0.6404749075729896 10.01827514135803 + vertex -5.350981125896581 1.271613538107609 10.38839257368468 + vertex -5.351105589102382 1.271089679872062 9.64781585087977 + endloop +endfacet +facet normal -0.230168 0.973151 -0.000245253 + outer loop + vertex -0.9573168647443093 5.416045090328931 8.304983976598086 + vertex -0.9542500341208148 5.416586274802648 7.574184692568961 + vertex -1.571882198856097 5.270596394424384 7.936098640024214 + endloop +endfacet +facet normal -0.117976 0.993016 0.000285768 + outer loop + vertex -0.3329773372250535 5.48991130100428 9.406191867178279 + vertex -0.9607923148651225 5.415429634636214 9.036838586275445 + vertex -0.9643705449208908 5.414793574282309 9.769856747733114 + endloop +endfacet +facet normal -0.123312 0.992368 -2.37581e-05 + outer loop + vertex -0.9915929150321402 5.409874628016629 15.64704678609304 + vertex -0.9912954322035247 5.409929146124968 16.38022546614373 + vertex -0.3627338163641405 5.488025526404365 16.01682901906203 + endloop +endfacet +facet normal 0.630829 0.775922 -0.000307063 + outer loop + vertex 3.709674271489997 4.060580845081792 19.33662734180532 + vertex 3.219421791503083 4.459296281746155 19.68454339005858 + vertex 3.706797571246544 4.063207078872638 20.06301800731393 + endloop +endfacet +facet normal -0.45317 0.891424 -8.20534e-05 + outer loop + vertex -2.773056990794739 4.749753143670145 16.73580144231683 + vertex -2.203868660299036 5.039143074784812 17.10367686674364 + vertex -2.202922862387096 5.03955661366873 16.37282938396807 + endloop +endfacet +facet normal -0.984725 0.174119 5.25836e-06 + outer loop + vertex -5.462581065098198 0.6404749075729896 10.01827514135803 + vertex -5.462588851477657 0.6404084944096309 10.75925925925924 + vertex -5.350981125896581 1.271613538107609 10.38839257368468 + endloop +endfacet +facet normal -0.998298 0.0583212 -5.26304e-06 + outer loop + vertex -5.5 0 10.38888888888887 + vertex -5.462588851477657 0.6404084944096309 10.75925925925924 + vertex -5.462581065098198 0.6404749075729896 10.01827514135803 + endloop +endfacet +facet normal 0.223514 0.974701 -0.000333019 + outer loop + vertex 1.536716324117605 5.280956631065102 12.72398985022994 + vertex 1.540798081005442 5.279767160923855 11.98214227948561 + vertex 0.9157185103458564 5.423233316925427 12.35095009251186 + endloop +endfacet +facet normal -0.645543 0.763724 0.000201809 + outer loop + vertex -3.787613740678036 3.987979708000899 17.46072148755751 + vertex -3.300431501637465 4.399676340709515 17.83016257702401 + vertex -3.302472647521388 4.398144428321229 17.09833579472796 + endloop +endfacet +facet normal -9.4776e-05 1 0.000401898 + outer loop + vertex 0.3132164573217003 5.491074161843277 3.214441762681023 + vertex -0.3116778562646466 5.491161708956882 2.849244344490732 + vertex -0.3167705464569702 5.490870279008361 3.573177574017768 + endloop +endfacet +facet normal -0.118536 0.99295 0.000307495 + outer loop + vertex -0.3354015807467305 5.489763727122743 10.13967599684736 + vertex -0.9643705449208908 5.414793574282309 9.769856747733114 + vertex -0.9682168451676494 5.414107141600875 10.50375290328457 + endloop +endfacet +facet normal -0.801775 0.597625 0.000187078 + outer loop + vertex -4.593365995810843 3.025060136349137 14.53883673513825 + vertex -4.212012044866582 3.536800041548692 14.17214472345561 + vertex -4.592056601583848 3.027047434027125 13.80214175608399 + endloop +endfacet +facet normal -0.998298 0.0583182 0 + outer loop + vertex -5.5 0 15.57407407407405 + vertex -5.462588851477785 0.6404084944085344 15.20370370370368 + vertex -5.5 0 14.83333333333331 + endloop +endfacet +facet normal 0.544534 0.838739 0.000265439 + outer loop + vertex 2.72660673659052 4.776569449299277 5.397223163237941 + vertex 2.723674939990226 4.778241812766411 6.127289020167175 + vertex 3.254868386254646 4.43348979790865 5.764558595360597 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 7.42592592592592 + vertex 5.462588851477699 0.6404084944092698 7.796296296296289 + vertex 5.5 0 8.166666666666657 + endloop +endfacet +facet normal -0.99811 0.0612927 -0.00434992 + outer loop + vertex -5.5 0 7.42592592592592 + vertex -5.461951509962761 0.6458217268066476 7.795483946606308 + vertex -5.455499441625426 0.6982305080878859 7.053492151481383 + endloop +endfacet +facet normal 0.997803 0.0662445 0.000360755 + outer loop + vertex 5.5 0 15.57407407407405 + vertex 5.45199573013907 0.7250810703261731 15.20311570077771 + vertex 5.45147922627175 0.7289542136016242 15.92048612597993 + endloop +endfacet +facet normal -0.802019 0.597298 0.000321866 + outer loop + vertex -4.595606947051128 3.021654644100713 15.27457467989483 + vertex -4.212819464422161 3.535838254245488 14.90743681953956 + vertex -4.593365995810843 3.025060136349137 14.53883673513825 + endloop +endfacet +facet normal -0.119448 0.99284 -0.000270267 + outer loop + vertex -0.3413497722383799 5.489397082830937 11.60929215863323 + vertex -0.3379244407656741 5.489609009058223 10.87394205312694 + vertex -0.9721075192870968 5.413409920830445 11.23866444627867 + endloop +endfacet +facet normal 0.105983 0.994367 0.00145391 + outer loop + vertex 0.262683298397841 5.493723462711136 18.57649404746713 + vertex 0.9098219135290052 5.424225666918958 18.93447455121602 + vertex 0.8921580186759523 5.427158931679834 18.21595266617183 + endloop +endfacet +facet normal 0.998311 0.0580904 -0.000395278 + outer loop + vertex 5.5 0 12.61111111111108 + vertex 5.462588851477699 0.6404084944092698 12.24074074074071 + vertex 5.463174314802662 0.635394685278737 12.98255000771282 + endloop +endfacet +facet normal -0.984718 0.174158 -0.000106091 + outer loop + vertex -5.462604141102114 0.640278062730595 8.536680095263456 + vertex -5.350996320403336 1.271549597550153 8.905278694477291 + vertex -5.350685539569706 1.27285673060233 8.166452634993886 + endloop +endfacet +facet normal 0.998304 0.0582182 0.000173554 + outer loop + vertex 5.5 0 10.38888888888887 + vertex 5.462846126101227 0.6382101554666896 10.01681138663804 + vertex 5.462588851477699 0.6404084944092698 10.75925925925924 + endloop +endfacet +facet normal 0.544025 0.839069 0.00027567 + outer loop + vertex 3.252261650712191 4.4354023667878 6.495472300639344 + vertex 2.723674939990226 4.778241812766411 6.127289020167175 + vertex 2.720623379131812 4.779979961142243 6.858957268139787 + endloop +endfacet +facet normal -0.222354 0.974947 0.00615415 + outer loop + vertex -0.9278248657095747 5.421175243300202 3.223427943000292 + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + vertex -1.549281538959688 5.277284028080988 3.565126421480367 + endloop +endfacet +facet normal 0.226711 0.973962 0.000552537 + outer loop + vertex 1.558182631274909 5.274662727378235 3.941249219772481 + vertex 1.551714848063318 5.276569058611839 3.234735469707145 + vertex 0.9347541321142854 5.419984752053761 3.579453427105974 + endloop +endfacet +facet normal -0.865794 0.500401 -0.000320886 + outer loop + vertex -4.913268007066149 2.471800455283604 14.90405506725276 + vertex -4.595606947051128 3.021654644100713 15.27457467989483 + vertex -4.593365995810843 3.025060136349137 14.53883673513825 + endloop +endfacet +facet normal -0.000865783 1 0.000348136 + outer loop + vertex 0.30949445038025 5.491285203409474 3.938797738407567 + vertex -0.3167705464569702 5.490870279008361 3.573177574017768 + vertex -0.3211802337802007 5.490614105674236 4.298053992840217 + endloop +endfacet +facet normal 0.716001 0.698099 -0.000353878 + outer loop + vertex 3.709288892712822 4.060932886714244 17.14061865087743 + vertex 4.152044140509771 3.607011152638494 17.50983287464635 + vertex 4.154980888345557 3.603627868895894 16.77750589539072 + endloop +endfacet +facet normal 0.536917 0.843635 0.000183677 + outer loop + vertex 3.216302611646152 4.461546537952747 17.503573412454 + vertex 2.680946204045271 4.802346036159332 17.13226512573994 + vertex 2.678916879983762 4.803478359495134 17.86350278336204 + endloop +endfacet +facet normal 0.113142 0.993579 -0.000277033 + outer loop + vertex 0.9312865324749462 5.420581647243291 4.304029951946054 + vertex 0.9347541321142854 5.419984752053761 3.579453427105974 + vertex 0.30949445038025 5.491285203409474 3.938797738407567 + endloop +endfacet +facet normal -0.918125 0.396291 -1.56406e-05 + outer loop + vertex -5.168278527335533 1.881195647422789 9.272684386469603 + vertex -4.913838183546919 2.47066677354845 8.903493668018529 + vertex -5.168346033474785 1.881010174950005 8.536010542375871 + endloop +endfacet +facet normal 0.106459 0.994317 -0.000328904 + outer loop + vertex 0.2694315000299995 5.493396642041387 16.38625459166656 + vertex 0.8975897917409533 5.426263223044237 16.75547133290806 + vertex 0.9017122864072585 5.425579688157036 16.02342662257618 + endloop +endfacet +facet normal -0.344025 0.93896 0.000227265 + outer loop + vertex -2.185024418165879 5.047342696114349 11.23106540038434 + vertex -2.18769581975002 5.046185390990732 11.96868542169703 + vertex -1.591618912029431 5.264669907873641 11.60353579911821 + endloop +endfacet +facet normal -0.22865 0.973509 -0.000259019 + outer loop + vertex -0.9508328157075984 5.417187181238392 5.38454323787805 + vertex -0.9475918392256525 5.417755043025934 4.657831776499254 + vertex -1.561840781710691 5.273580697456458 5.017848521761371 + endloop +endfacet +facet normal -0.115686 0.993286 -0.00026931 + outer loop + vertex -0.3245943420598152 5.490413328074924 5.02410660243334 + vertex -0.3211802337802007 5.490614105674236 4.298053992840217 + vertex -0.9475918392256525 5.417755043025934 4.657831776499254 + endloop +endfacet +facet normal -0.99825 0.0591352 0 + outer loop + vertex -5.5 0 14.09259259259256 + vertex -5.461533276369314 0.6493491134287154 13.7223915162698 + vertex -5.5 0 13.35185185185182 + endloop +endfacet +facet normal 0.219749 0.975556 -0.000381867 + outer loop + vertex 0.8975897917409533 5.426263223044237 16.75547133290806 + vertex 1.513274589194329 5.287721628234483 17.1239828427341 + vertex 1.517935936642233 5.286385390060969 16.39270319811148 + endloop +endfacet +facet normal 0.631117 0.775688 -0.000504408 + outer loop + vertex 3.219014690661195 4.459590162930603 16.77024877340427 + vertex 3.709288892712822 4.060932886714244 17.14061865087743 + vertex 3.71401833700239 4.056607917017615 16.40709822925858 + endloop +endfacet +facet normal 0.998377 0.0569455 -0 + outer loop + vertex 5.5 0 8.907407407407394 + vertex 5.464329314634285 0.6253839950209801 9.258668456006923 + vertex 5.5 0 9.648148148148133 + endloop +endfacet +facet normal -0.997975 0.0636043 0 + outer loop + vertex -5.5 0 7.42592592592592 + vertex -5.455499441625426 0.6982305080878859 7.053492151481383 + vertex -5.5 0 6.68518518518518 + endloop +endfacet +facet normal 0.997792 0.0664152 -0 + outer loop + vertex 5.5 0 15.57407407407405 + vertex 5.45147922627175 0.7289542136016242 15.92048612597993 + vertex 5.5 0 16.3148148148148 + endloop +endfacet +facet normal -0.444393 0.89583 -0.00166357 + outer loop + vertex -2.720098218800375 4.780278828695982 3.557694086819801 + vertex -2.150872866283984 5.061990311437125 3.200430427666638 + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + endloop +endfacet +facet normal -0.119119 0.99288 0.000311337 + outer loop + vertex -0.3379244407656741 5.489609009058223 10.87394205312694 + vertex -0.9682168451676494 5.414107141600875 10.50375290328457 + vertex -0.9721075192870968 5.413409920830445 11.23866444627867 + endloop +endfacet +facet normal -0.00124137 0.999999 -0.000311214 + outer loop + vertex 0.3055515148459051 5.491506011266433 4.66402990365856 + vertex 0.30949445038025 5.491285203409474 3.938797738407567 + vertex -0.3211802337802007 5.490614105674236 4.298053992840217 + endloop +endfacet +facet normal -0.226203 0.974079 -0.00121221 + outer loop + vertex -0.9278248657095747 5.421175243300202 3.223427943000292 + vertex -1.549281538959688 5.277284028080988 3.565126421480367 + vertex -0.9426077132371609 5.418624428666911 3.932243735809454 + endloop +endfacet +facet normal -0.91827 0.395956 -1.90616e-05 + outer loop + vertex -4.915818579230525 2.466724081872958 18.55622870078207 + vertex -4.915709720630987 2.466941009123246 17.81820394054487 + vertex -5.168219743892152 1.88135713750562 18.18109287916363 + endloop +endfacet +facet normal 0.439921 0.898037 -0.000259905 + outer loop + vertex 2.702402812701651 4.790304691551698 12.72565874458753 + vertex 2.130062841592538 5.07078221686425 13.09066671338084 + vertex 2.699519646977631 4.791930057459288 13.46159641120867 + endloop +endfacet +facet normal -0.636297 0.771444 -0.000306693 + outer loop + vertex -3.251307770456957 4.436101642407015 5.370668124934424 + vertex -3.248170387885879 4.438399388435125 4.641195007400434 + vertex -3.737953839354024 4.034563309065618 5.002338780429589 + endloop +endfacet +facet normal 0.913185 0.407544 4.7624e-05 + outer loop + vertex 5.141289816700485 1.953749989300548 3.23223805190901 + vertex 4.887805760937779 2.521776128712354 2.854314542228816 + vertex 4.887524974198084 2.522320286282061 3.581719537648792 + endloop +endfacet +facet normal 0.444472 0.895793 0.000515074 + outer loop + vertex 2.720921121897517 4.779810482478564 4.666845165150066 + vertex 2.15734721088084 5.05923442940774 5.029478211222619 + vertex 2.72660673659052 4.776569449299277 5.397223163237941 + endloop +endfacet +facet normal -0.33905 0.940768 0.000312962 + outer loop + vertex -2.15990204534286 5.058144240185696 6.106736787693633 + vertex -1.565338836542403 5.272543440011858 5.745524669891359 + vertex -2.156242545109333 5.05970533595193 5.378616593031186 + endloop +endfacet +facet normal -0.451359 0.892342 -0.000439131 + outer loop + vertex -2.764583419145227 4.754690160103736 18.92372716072775 + vertex -2.75983315162458 4.757448998696038 19.64732542503119 + vertex -2.194459938233373 5.043247523123249 19.29217846862717 + endloop +endfacet +facet normal 0.909784 0.415082 -0.000356228 + outer loop + vertex 4.864019593170021 2.56735533132018 18.98242990710356 + vertex 5.126158116024035 1.99311388774473 19.3527997429786 + vertex 5.127797107729225 1.988893366162147 18.62086574692994 + endloop +endfacet +facet normal -0.227946 0.973674 -0.000399141 + outer loop + vertex -0.9426077132371609 5.418624428666911 3.932243735809454 + vertex -1.558235160707119 5.274647209428898 4.289890961578397 + vertex -0.9475918392256525 5.417755043025934 4.657831776499254 + endloop +endfacet +facet normal -0.998314 0.0580382 0.00048577 + outer loop + vertex -5.462588851477786 0.6404084944085295 12.24074074074071 + vertex -5.463300394916927 0.6343096995163731 11.50709967217639 + vertex -5.5 0 11.87037037037035 + endloop +endfacet +facet normal 0.105564 0.994412 -0.000192657 + outer loop + vertex 0.8945770936974713 5.426760711827249 17.4860158572045 + vertex 0.265914278229262 5.493568020570403 17.84873078791945 + vertex 0.8921580186759523 5.427158931679834 18.21595266617183 + endloop +endfacet +facet normal -0.914562 0.404362 0.00825413 + outer loop + vertex -5.167592017862487 1.883080650668979 7.796888109715192 + vertex -4.888301959121175 2.520814145559345 7.500407855524626 + vertex -5.134331014646105 1.971964764402015 7.127875330178659 + endloop +endfacet +facet normal 0.998314 0.0580496 0.000198378 + outer loop + vertex 5.5 0 14.09259259259256 + vertex 5.463079625775358 0.6362083011389977 13.72188479775475 + vertex 5.462786065058352 0.6387240463645399 14.46303530577151 + endloop +endfacet +facet normal 0.44364 0.896205 -0.000339349 + outer loop + vertex 2.725396144507114 4.777260287602693 3.226181988385524 + vertex 2.148095142858107 5.063169684814978 3.577663568096047 + vertex 2.721769633243516 4.779327365179483 3.944197539972951 + endloop +endfacet +facet normal -0.917776 0.397098 -0.000274272 + outer loop + vertex -5.164834411129698 1.890630980813162 15.27016150908249 + vertex -4.914848247313041 2.46865686272595 15.6405238496727 + vertex -4.913268007066149 2.471800455283604 14.90405506725276 + endloop +endfacet +facet normal 0.721149 0.692779 -0.000217195 + outer loop + vertex 4.181216983490701 3.573153304431385 10.15965879864028 + vertex 3.739001783202773 4.033592154049103 10.5248633300495 + vertex 4.179424357135561 3.57524992734522 10.89515204038594 + endloop +endfacet +facet normal -0.998298 0.0583182 0 + outer loop + vertex -5.5 0 12.61111111111108 + vertex -5.462588851477786 0.6404084944085295 12.24074074074071 + vertex -5.5 0 11.87037037037035 + endloop +endfacet +facet normal -0.9983 0.0582785 -4.81922e-05 + outer loop + vertex -5.5 0 8.907407407407394 + vertex -5.462675335659052 0.6396703660341518 9.276591032760054 + vertex -5.462604141102114 0.640278062730595 8.536680095263456 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 10.38888888888887 + vertex 5.462588851477699 0.6404084944092698 10.75925925925924 + vertex 5.5 0 11.12962962962961 + endloop +endfacet +facet normal 0.333091 0.942895 -0.000342995 + outer loop + vertex 2.126027404577531 5.072475478007294 13.82654127353561 + vertex 2.130062841592538 5.07078221686425 13.09066671338084 + vertex 1.529835967906667 5.282953900167885 13.45699023934335 + endloop +endfacet +facet normal -0.998299 0.0583063 0 + outer loop + vertex -5.5 0 8.907407407407394 + vertex -5.462604141102114 0.640278062730595 8.536680095263456 + vertex -5.5 0 8.166666666666657 + endloop +endfacet +facet normal 0.9983 0.0582829 -0 + outer loop + vertex 5.5 0 6.68518518518518 + vertex 5.462634190338693 0.6400216422455829 7.056229042449417 + vertex 5.5 0 7.42592592592592 + endloop +endfacet +facet normal -0.726903 0.68674 -0.000273127 + outer loop + vertex -4.210023668379002 3.539166669102856 13.43680883328707 + vertex -3.773762374263558 4.0010895444357 13.80744932381539 + vertex -3.771238043156938 4.00346894853024 13.07185087542922 + endloop +endfacet +facet normal 0.998307 0.0581643 -0 + outer loop + vertex 5.5 0 14.09259259259256 + vertex 5.462786065058352 0.6387240463645399 14.46303530577151 + vertex 5.5 0 14.83333333333331 + endloop +endfacet +facet normal 0.335725 0.94196 0.000111805 + outer loop + vertex 2.141708837930507 5.065874381933523 10.14863544349151 + vertex 1.545831401814297 5.278295679209799 9.777932328509017 + vertex 1.544463263469689 5.278696167406546 10.51201805553148 + endloop +endfacet +facet normal 0.444524 0.895767 0.000214435 + outer loop + vertex 2.159295580663456 5.058403166546462 5.758176769272027 + vertex 2.15678241110269 5.059475232784332 6.489597573843957 + vertex 2.723674939990226 4.778241812766411 6.127289020167175 + endloop +endfacet +facet normal 0.440946 0.897533 -0.000344784 + outer loop + vertex 2.706256529158432 4.788128611303936 11.98948039066311 + vertex 2.13807510768009 5.067409084918917 12.35499137436904 + vertex 2.702402812701651 4.790304691551698 12.72565874458753 + endloop +endfacet +facet normal -0.998302 0.0582435 0 + outer loop + vertex -5.5 0 18.53703703703703 + vertex -5.462684705259381 0.6395903461788828 18.16809101137283 + vertex -5.5 0 17.79629629629628 + endloop +endfacet +facet normal -0.803236 0.595661 0.000280868 + outer loop + vertex -4.600131190995158 3.014762515627636 18.18651027564389 + vertex -4.221761821939877 3.525156325443014 17.82343063942983 + vertex -4.598174290006761 3.01774637746793 17.45478701894501 + endloop +endfacet +facet normal -0.549756 0.835325 -0.00018764 + outer loop + vertex -2.755486671513457 4.75996777332701 13.07827609719789 + vertex -2.753396472126791 4.761177151427969 12.33816155070207 + vertex -3.282870743564781 4.412794996489914 12.70690887131546 + endloop +endfacet +facet normal -0.998338 0.0576376 0 + outer loop + vertex -5.5 0 14.83333333333331 + vertex -5.463457015218254 0.6329592742526507 14.46853726531237 + vertex -5.5 0 14.09259259259256 + endloop +endfacet +facet normal -0.339337 0.940665 -0.00022064 + outer loop + vertex -2.15990204534286 5.058144240185696 6.106736787693633 + vertex -1.568027322643233 5.271744522968113 6.474271455702275 + vertex -1.565338836542403 5.272543440011858 5.745524669891359 + endloop +endfacet +facet normal -0.957905 0.287086 1.54994e-05 + outer loop + vertex -5.350996320403336 1.271549597550153 8.905278694477291 + vertex -5.168278527335533 1.881195647422789 9.272684386469603 + vertex -5.168346033474785 1.881010174950005 8.536010542375871 + endloop +endfacet +facet normal -0.64292 0.765933 -0.000381805 + outer loop + vertex -3.773762374263558 4.0010895444357 13.80744932381539 + vertex -3.288483294202905 4.408614025263315 14.17660159336728 + vertex -3.284598920282779 4.411508804578905 13.44289205746733 + endloop +endfacet +facet normal -0.123192 0.992383 -0.000230503 + outer loop + vertex -0.9915929150321402 5.409874628016629 15.64704678609304 + vertex -0.3627338163641405 5.488025526404365 16.01682901906203 + vertex -0.3598129782511795 5.488217800040557 15.28358645969896 + endloop +endfacet +facet normal -0.953964 0.29992 -0.00125192 + outer loop + vertex -5.141032723106988 1.954426396655335 4.249564237577 + vertex -5.336450873075671 1.331274607002596 3.871193572221433 + vertex -5.332602887399606 1.346605526981597 4.611820020301286 + endloop +endfacet +facet normal -0.34429 0.938863 -0.000263516 + outer loop + vertex -1.591618912029431 5.264669907873641 11.60353579911821 + vertex -2.18769581975002 5.046185390990732 11.96868542169703 + vertex -1.594841589980115 5.263694548781274 12.33900123544736 + endloop +endfacet +facet normal -0.726461 0.687208 -0.000291696 + outer loop + vertex -4.207775377435437 3.54183940531584 12.70082873519072 + vertex -3.771238043156938 4.00346894853024 13.07185087542922 + vertex -3.768538806172715 4.00600989344389 12.33569936112557 + endloop +endfacet +facet normal 0.436423 0.899741 0.000266058 + outer loop + vertex 2.113350427269168 5.077770177111329 16.76176094383523 + vertex 2.110225258263429 5.079069733660589 17.49329836618297 + vertex 2.680946204045271 4.802346036159332 17.13226512573994 + endloop +endfacet +facet normal -0.865317 0.501224 -0.000185911 + outer loop + vertex -4.910007904730391 2.478270036837204 14.16861485224099 + vertex -4.593365995810843 3.025060136349137 14.53883673513825 + vertex -4.592056601583848 3.027047434027125 13.80214175608399 + endloop +endfacet +facet normal 0.54379 0.839221 -0.000212991 + outer loop + vertex 3.250073991176871 4.4370056402799 7.22730766149194 + vertex 3.252261650712191 4.4354023667878 6.495472300639344 + vertex 2.720623379131812 4.779979961142243 6.858957268139787 + endloop +endfacet +facet normal 0.44106 0.897478 -0.000125482 + outer loop + vertex 2.136595684821637 5.068033038527035 11.61759465937531 + vertex 2.13807510768009 5.067409084918917 12.35499137436904 + vertex 2.706256529158432 4.788128611303936 11.98948039066311 + endloop +endfacet +facet normal -0.998298 0.0583243 0 + outer loop + vertex -5.5 0 10.38888888888887 + vertex -5.462581065098198 0.6404749075729896 10.01827514135803 + vertex -5.5 0 9.648148148148133 + endloop +endfacet +facet normal -0.00918958 0.999958 -0.000254378 + outer loop + vertex 0.265914278229262 5.493568020570403 17.84873078791945 + vertex -0.3652328073833823 5.487859782867165 18.21031711504795 + vertex 0.262683298397841 5.493723462711136 18.57649404746713 + endloop +endfacet +facet normal 0.44202 0.897005 2.40981e-06 + outer loop + vertex 2.712385502007586 4.784659328363833 10.5186368901123 + vertex 2.141708837930507 5.065874381933523 10.14863544349151 + vertex 2.141680680654499 5.065886285943584 10.88235392453209 + endloop +endfacet +facet normal 0.635713 0.771925 0.000303604 + outer loop + vertex 3.736454861613151 4.035951568976943 11.26022638988133 + vertex 3.246224851423652 4.439822543075285 10.8892865042854 + vertex 3.243111424954422 4.442097284541402 11.6248340143204 + endloop +endfacet +facet normal -0.000490972 1 -0.000293873 + outer loop + vertex 0.3132164573217003 5.491074161843277 3.214441762681023 + vertex -0.3167705464569702 5.490870279008361 3.573177574017768 + vertex 0.30949445038025 5.491285203409474 3.938797738407567 + endloop +endfacet +facet normal 0.444776 0.895642 -0.00026552 + outer loop + vertex 2.159295580663456 5.058403166546462 5.758176769272027 + vertex 2.723674939990226 4.778241812766411 6.127289020167175 + vertex 2.72660673659052 4.776569449299277 5.397223163237941 + endloop +endfacet +facet normal -0.548737 0.835995 0.000206874 + outer loop + vertex -2.748401568742806 4.764062217995487 10.8602147235481 + vertex -3.276621723325886 4.417437049039737 10.48929820463972 + vertex -3.278777122892307 4.415837471918327 11.23609377014295 + endloop +endfacet +facet normal 0.635177 0.772367 0.000306577 + outer loop + vertex 3.733692718472325 4.03850698699739 11.99605576310998 + vertex 3.243111424954422 4.442097284541402 11.6248340143204 + vertex 3.2399646392556 4.444392999766484 12.3608043102248 + endloop +endfacet +facet normal 0.99831 0.0581173 -0 + outer loop + vertex 5.5 0 9.648148148148133 + vertex 5.462846126101227 0.6382101554666896 10.01681138663804 + vertex 5.5 0 10.38888888888887 + endloop +endfacet +facet normal -0.123108 0.992393 0.000333795 + outer loop + vertex -0.3627338163641405 5.488025526404365 16.01682901906203 + vertex -0.9912954322035247 5.409929146124968 16.38022546614373 + vertex -0.3585134827399036 5.488302841743858 16.74886969383951 + endloop +endfacet +facet normal -0.123413 0.992355 0.000237439 + outer loop + vertex -0.3652328073833823 5.487859782867165 18.21031711504795 + vertex -0.9915550309688018 5.409881571768504 18.57253006430009 + vertex -0.3621874643355 5.488061610503131 18.94966241806066 + endloop +endfacet +facet normal 0.108849 0.994051 -0.00378742 + outer loop + vertex 0.3112636309729526 5.491185204674263 19.3064763842535 + vertex 0.9098219135290052 5.424225666918958 18.93447455121602 + vertex 0.262683298397841 5.493723462711136 18.57649404746713 + endloop +endfacet +facet normal -0.00424809 0.999991 -0.000109002 + outer loop + vertex 0.2939996045947215 5.49213658174104 11.98041007769864 + vertex 0.2953835508501084 5.492062322833489 11.24521763091109 + vertex -0.3413497722383799 5.489397082830937 11.60929215863323 + endloop +endfacet +facet normal -0.726688 0.686968 0.00027484 + outer loop + vertex -4.207775377435437 3.54183940531584 12.70082873519072 + vertex -4.210023668379002 3.539166669102856 13.43680883328707 + vertex -3.771238043156938 4.00346894853024 13.07185087542922 + endloop +endfacet +facet normal 0.541297 0.840832 0.000348132 + outer loop + vertex 3.2399646392556 4.444392999766484 12.3608043102248 + vertex 2.706256529158432 4.788128611303936 11.98948039066311 + vertex 2.702402812701651 4.790304691551698 12.72565874458753 + endloop +endfacet +facet normal -0.643218 0.765683 0.000285238 + outer loop + vertex -3.773762374263558 4.0010895444357 13.80744932381539 + vertex -3.776397186416806 3.998602792279227 14.54124771470269 + vertex -3.288483294202905 4.408614025263315 14.17660159336728 + endloop +endfacet +facet normal -0.642436 0.76634 -0.000169273 + outer loop + vertex -3.284598920282779 4.411508804578905 13.44289205746733 + vertex -3.282870743564781 4.412794996489914 12.70690887131546 + vertex -3.771238043156938 4.00346894853024 13.07185087542922 + endloop +endfacet +facet normal 0.998325 0.0578601 -0 + outer loop + vertex 5.5 0 12.61111111111108 + vertex 5.463174314802662 0.635394685278737 12.98255000771282 + vertex 5.5 0 13.35185185185182 + endloop +endfacet +facet normal -0.998298 0.0583182 0 + outer loop + vertex -5.5 0 11.12962962962961 + vertex -5.462588851477657 0.6404084944096309 10.75925925925924 + vertex -5.5 0 10.38888888888887 + endloop +endfacet +facet normal -0.727317 0.686301 -0.000285751 + outer loop + vertex -3.773762374263558 4.0010895444357 13.80744932381539 + vertex -4.212012044866582 3.536800041548692 14.17214472345561 + vertex -3.776397186416806 3.998602792279227 14.54124771470269 + endloop +endfacet +facet normal -0.635775 0.771874 -0.00014274 + outer loop + vertex -3.734579928635062 4.037686559979134 4.271956172220666 + vertex -3.248170387885879 4.438399388435125 4.641195007400434 + vertex -3.24670894030754 4.439468555686265 3.913368189062605 + endloop +endfacet +facet normal 0.998298 0.0583182 -0 + outer loop + vertex 5.5 0 11.87037037037035 + vertex 5.462588851477699 0.6404084944092698 12.24074074074071 + vertex 5.5 0 12.61111111111108 + endloop +endfacet +facet normal -0.642009 0.766697 -0.000210031 + outer loop + vertex -3.768538806172715 4.00600989344389 12.33569936112557 + vertex -3.282870743564781 4.412794996489914 12.70690887131546 + vertex -3.280719718076403 4.414394424088619 11.97035238303435 + endloop +endfacet +facet normal 0.796235 0.604987 -0.000103433 + outer loop + vertex 4.563216686645465 3.070350708098406 5.405036775612206 + vertex 4.563949237429648 3.069261695940139 4.674562988651441 + vertex 4.180478332843585 3.574017474583094 5.038000552588223 + endloop +endfacet +facet normal 0.227038 0.973886 -0.00045253 + outer loop + vertex 1.552549114769935 5.276323648737546 7.585291971265814 + vertex 1.558061537370548 5.274698498091292 6.85344604553776 + vertex 0.9379299192986701 5.419436083808387 7.216973568687898 + endloop +endfacet +facet normal 0.796477 0.604669 0.000217573 + outer loop + vertex 4.566179940187244 3.065942066287558 10.52991912852155 + vertex 4.181216983490701 3.573153304431385 10.15965879864028 + vertex 4.179424357135561 3.57524992734522 10.89515204038594 + endloop +endfacet +facet normal -0.998269 0.0588129 0 + outer loop + vertex -5.5 0 8.166666666666657 + vertex -5.461951509962761 0.6458217268066476 7.795483946606308 + vertex -5.5 0 7.42592592592592 + endloop +endfacet +facet normal 0.997816 0.0660608 -0 + outer loop + vertex 5.5 0 14.83333333333331 + vertex 5.45199573013907 0.7250810703261731 15.20311570077771 + vertex 5.5 0 15.57407407407405 + endloop +endfacet +facet normal 0.537987 0.842953 -0.000460314 + outer loop + vertex 2.686581987151288 4.7991954769851 16.39939846347043 + vertex 3.219014690661195 4.459590162930603 16.77024877340427 + vertex 3.223761391834297 4.456160060917762 16.03651162530636 + endloop +endfacet +facet normal -0.228961 0.973436 0.000286921 + outer loop + vertex -1.565338836542403 5.272543440011858 5.745524669891359 + vertex -0.9508328157075984 5.417187181238392 5.38454323787805 + vertex -1.561840781710691 5.273580697456458 5.017848521761371 + endloop +endfacet +facet normal -0.642634 0.766174 0.000272998 + outer loop + vertex -3.773762374263558 4.0010895444357 13.80744932381539 + vertex -3.284598920282779 4.411508804578905 13.44289205746733 + vertex -3.771238043156938 4.00346894853024 13.07185087542922 + endloop +endfacet +facet normal 0.721335 0.692587 0.000250102 + outer loop + vertex 4.181216983490701 3.573153304431385 10.15965879864028 + vertex 3.741330192435993 4.031432548259596 9.789771699872459 + vertex 3.739001783202773 4.033592154049103 10.5248633300495 + endloop +endfacet +facet normal 0.11326 0.993565 -0.00025064 + outer loop + vertex 0.9347925745220471 5.419978121968616 7.947965626364867 + vertex 0.9379299192986701 5.419436083808387 7.216973568687898 + vertex 0.3074141288358063 5.491402057161006 7.579986864874797 + endloop +endfacet +facet normal -0.119765 0.992802 0.000276417 + outer loop + vertex -0.3413497722383799 5.489397082830937 11.60929215863323 + vertex -0.9721075192870968 5.413409920830445 11.23866444627867 + vertex -0.9755631203259217 5.412788246205457 11.97429163264967 + endloop +endfacet +facet normal -0.00188509 0.999998 -0.000220147 + outer loop + vertex 0.3046216084273119 5.491557672981243 8.310771337383457 + vertex 0.3074141288358063 5.491402057161006 7.579986864874797 + vertex -0.3267336320428044 5.490286434576261 7.942507020545281 + endloop +endfacet +facet normal 0.541619 0.840624 -0.000306366 + outer loop + vertex 3.243111424954422 4.442097284541402 11.6248340143204 + vertex 2.706256529158432 4.788128611303936 11.98948039066311 + vertex 3.2399646392556 4.444392999766484 12.3608043102248 + endloop +endfacet +facet normal 0.335663 0.941982 -2.40146e-06 + outer loop + vertex 2.141708837930507 5.065874381933523 10.14863544349151 + vertex 1.544463263469689 5.278696167406546 10.51201805553148 + vertex 2.141680680654499 5.065886285943584 10.88235392453209 + endloop +endfacet +facet normal 0.542731 0.839907 -0.000270216 + outer loop + vertex 3.246224851423652 4.439822543075285 10.8892865042854 + vertex 3.248991982273831 4.437798001162329 10.15424391506147 + vertex 2.712385502007586 4.784659328363833 10.5186368901123 + endloop +endfacet +facet normal -0.639619 0.768692 -0.000247459 + outer loop + vertex -3.756191792225918 4.017589229875878 8.657180996278033 + vertex -3.269152095501428 4.422967847099797 9.026767284026866 + vertex -3.266622743135714 4.42483625166271 8.292931250592922 + endloop +endfacet +facet normal 0.636212 0.771514 0.000270081 + outer loop + vertex 3.246224851423652 4.439822543075285 10.8892865042854 + vertex 3.739001783202773 4.033592154049103 10.5248633300495 + vertex 3.248991982273831 4.437798001162329 10.15424391506147 + endloop +endfacet +facet normal 0.721469 0.692447 -5.96018e-05 + outer loop + vertex 4.1799857098378 3.574593608447229 5.768349711835589 + vertex 4.180478332843585 3.574017474583094 5.038000552588223 + vertex 3.742825607793919 4.03004422676006 5.401516095877726 + endloop +endfacet +facet normal -0.230476 0.973078 0.000297656 + outer loop + vertex -0.9573168647443093 5.416045090328931 8.304983976598086 + vertex -1.571882198856097 5.270596394424384 7.936098640024214 + vertex -1.57550572332861 5.269514371909312 8.667668761794854 + endloop +endfacet +facet normal 0.720287 0.693676 0.000147415 + outer loop + vertex 3.735609022597694 4.036734476069326 8.327927643449971 + vertex 3.734233119467835 4.03800730676277 9.061319687521875 + vertex 4.175055378160717 3.580350903094733 8.700074265015786 + endloop +endfacet +facet normal 0.542474 0.840073 0.000253319 + outer loop + vertex 3.246224851423652 4.439822543075285 10.8892865042854 + vertex 2.712385502007586 4.784659328363833 10.5186368901123 + vertex 2.709588604720712 4.786243787477574 11.25361401691623 + endloop +endfacet +facet normal 0.54191 0.840436 0.000301157 + outer loop + vertex 2.709588604720712 4.786243787477574 11.25361401691623 + vertex 2.706256529158432 4.788128611303936 11.98948039066311 + vertex 3.243111424954422 4.442097284541402 11.6248340143204 + endloop +endfacet +facet normal -0.641788 0.766882 0.00029146 + outer loop + vertex -3.768538806172715 4.00600989344389 12.33569936112557 + vertex -3.280719718076403 4.414394424088619 11.97035238303435 + vertex -3.765826944842038 4.008559270049738 11.59929669367751 + endloop +endfacet +facet normal -0.729237 0.684261 0.000262689 + outer loop + vertex -4.221761821939877 3.525156325443014 17.82343063942983 + vertex -3.787613740678036 3.987979708000899 17.46072148755751 + vertex -4.219621040588515 3.527718564996746 17.09213177742202 + endloop +endfacet +facet normal -0.550237 0.835008 0.000381399 + outer loop + vertex -3.288483294202905 4.408614025263315 14.17660159336728 + vertex -2.755934067944267 4.75970875297472 13.81361629833644 + vertex -3.284598920282779 4.411508804578905 13.44289205746733 + endloop +endfacet +facet normal 0.636447 0.771321 -0.000250092 + outer loop + vertex 3.739001783202773 4.033592154049103 10.5248633300495 + vertex 3.741330192435993 4.031432548259596 9.789771699872459 + vertex 3.248991982273831 4.437798001162329 10.15424391506147 + endloop +endfacet +facet normal -0.340505 0.940243 0.00029219 + outer loop + vertex -1.571882198856097 5.270596394424384 7.936098640024214 + vertex -2.16572987526206 5.055651699573199 7.567235143067204 + vertex -2.169140817674367 5.054189164752243 8.298592900015723 + endloop +endfacet +facet normal -0.446015 0.895026 0.000353202 + outer loop + vertex -2.16572987526206 5.055651699573199 7.567235143067204 + vertex -2.730331237033483 4.774441468494426 7.198626627347451 + vertex -2.734226069823106 4.772212044649702 7.929762223762901 + endloop +endfacet +facet normal 0.542207 0.840245 -0.000303471 + outer loop + vertex 3.246224851423652 4.439822543075285 10.8892865042854 + vertex 2.709588604720712 4.786243787477574 11.25361401691623 + vertex 3.243111424954422 4.442097284541402 11.6248340143204 + endloop +endfacet +facet normal -0.0080186 0.999968 0.000230274 + outer loop + vertex -0.3627338163641405 5.488025526404365 16.01682901906203 + vertex 0.2732321874398657 5.493208913899673 15.65350056583433 + vertex -0.3598129782511795 5.488217800040557 15.28358645969896 + endloop +endfacet +facet normal 0.636735 0.771083 -0.000181757 + outer loop + vertex 3.739370883373951 4.033249979430375 6.863618889679024 + vertex 3.741065371887834 4.031678296102225 6.132109706259876 + vertex 3.252261650712191 4.4354023667878 6.495472300639344 + endloop +endfacet +facet normal 0.795964 0.605344 2.4646e-05 + outer loop + vertex 4.562386486476917 3.071584208191729 6.867102472469194 + vertex 4.178772325094146 3.576012004318116 6.499676398532498 + vertex 4.178568741894685 3.576249889096212 7.231759319986232 + endloop +endfacet +facet normal -0.645497 0.763763 0.000307461 + outer loop + vertex -3.787613740678036 3.987979708000899 17.46072148755751 + vertex -3.302472647521388 4.398144428321229 17.09833579472796 + vertex -3.784781376700859 3.990667855206488 16.72949380097899 + endloop +endfacet +facet normal 0.99832 0.0579344 -0 + outer loop + vertex 5.5 0 13.35185185185182 + vertex 5.463079625775358 0.6362083011389977 13.72188479775475 + vertex 5.5 0 14.09259259259256 + endloop +endfacet +facet normal 0.328776 0.944408 0.000386504 + outer loop + vertex 1.505039275104873 5.29007152885401 18.58306770502023 + vertex 2.103215541586377 5.081976425135158 18.22266410324536 + vertex 1.50976148259572 5.288725769565896 17.85447942085971 + endloop +endfacet +facet normal -0.236501 0.971631 -7.27801e-05 + outer loop + vertex -0.9915550309688018 5.409881571768504 18.57253006430009 + vertex -1.605220724567375 5.260538606019291 18.93286370157931 + vertex -0.9924759007625094 5.409712708305834 19.31055568031545 + endloop +endfacet +facet normal -0.99833 0.057761 0 + outer loop + vertex -5.5 0 11.87037037037035 + vertex -5.463300394916927 0.6343096995163731 11.50709967217639 + vertex -5.5 0 11.12962962962961 + endloop +endfacet +facet normal 0.544285 0.8389 -0.000253995 + outer loop + vertex 3.254868386254646 4.43348979790865 5.764558595360597 + vertex 2.723674939990226 4.778241812766411 6.127289020167175 + vertex 3.252261650712191 4.4354023667878 6.495472300639344 + endloop +endfacet +facet normal 0.791543 0.611113 -0.000341993 + outer loop + vertex 4.152044140509771 3.607011152638494 17.50983287464635 + vertex 4.539148916185716 3.105821488220152 17.8802646915997 + vertex 4.541597390389772 3.102240020308682 17.14747746590255 + endloop +endfacet +facet normal -0.234591 0.972094 0.000393777 + outer loop + vertex -0.9789182018068283 5.412182476060031 12.71018137601641 + vertex -1.594841589980115 5.263694548781274 12.33900123544736 + vertex -1.599638590842117 5.262238723080571 13.07511200794479 + endloop +endfacet +facet normal 0.437982 0.898984 0.000239502 + outer loop + vertex 2.690311348957866 4.797105882265734 15.6661138397711 + vertex 2.120872707858986 5.074632888895402 15.29577543723218 + vertex 2.11806254387618 5.07580644432279 16.02976623207586 + endloop +endfacet +facet normal -0.233919 0.972256 0.000264396 + outer loop + vertex -0.9755631203259217 5.412788246205457 11.97429163264967 + vertex -1.591618912029431 5.264669907873641 11.60353579911821 + vertex -1.594841589980115 5.263694548781274 12.33900123544736 + endloop +endfacet +facet normal 0.441889 0.89707 -0.000252322 + outer loop + vertex 2.712385502007586 4.784659328363833 10.5186368901123 + vertex 2.141680680654499 5.065886285943584 10.88235392453209 + vertex 2.709588604720712 4.786243787477574 11.25361401691623 + endloop +endfacet +facet normal 0.443476 0.896286 -0.000347771 + outer loop + vertex 2.716777995166491 4.782166593185472 7.590795854324413 + vertex 2.720623379131812 4.779979961142243 6.858957268139787 + vertex 2.151434623773428 5.061751580197203 7.222461682940452 + endloop +endfacet +facet normal -0.120078 0.992764 -0.000276213 + outer loop + vertex -0.3448527004242826 5.489178136571092 12.34518875272993 + vertex -0.3413497722383799 5.489397082830937 11.60929215863323 + vertex -0.9755631203259217 5.412788246205457 11.97429163264967 + endloop +endfacet +facet normal -0.72711 0.686521 0.000243387 + outer loop + vertex -4.210023668379002 3.539166669102856 13.43680883328707 + vertex -4.212012044866582 3.536800041548692 14.17214472345561 + vertex -3.773762374263558 4.0010895444357 13.80744932381539 + endloop +endfacet +facet normal -0.865539 0.500842 0.000569033 + outer loop + vertex -4.910007904730391 2.478270036837204 14.16861485224099 + vertex -4.913268007066149 2.471800455283604 14.90405506725276 + vertex -4.593365995810843 3.025060136349137 14.53883673513825 + endloop +endfacet +facet normal -0.00447311 0.99999 0.000276228 + outer loop + vertex -0.3448527004242826 5.489178136571092 12.34518875272993 + vertex 0.2939996045947215 5.49213658174104 11.98041007769864 + vertex -0.3413497722383799 5.489397082830937 11.60929215863323 + endloop +endfacet +facet normal -0.115992 0.99325 0.00025884 + outer loop + vertex -0.9508328157075984 5.417187181238392 5.38454323787805 + vertex -0.3245943420598152 5.490413328074924 5.02410660243334 + vertex -0.9475918392256525 5.417755043025934 4.657831776499254 + endloop +endfacet +facet normal 0.54099 0.841029 -0.000290946 + outer loop + vertex 3.2399646392556 4.444392999766484 12.3608043102248 + vertex 2.702402812701651 4.790304691551698 12.72565874458753 + vertex 3.23697700145235 4.446569452068476 13.09694371569185 + endloop +endfacet +facet normal -0.642234 0.766509 0.000290859 + outer loop + vertex -3.771238043156938 4.00346894853024 13.07185087542922 + vertex -3.282870743564781 4.412794996489914 12.70690887131546 + vertex -3.768538806172715 4.00600989344389 12.33569936112557 + endloop +endfacet +facet normal -0.345993 0.938237 -6.10912e-06 + outer loop + vertex -1.605220724567375 5.260538606019291 18.93286370157931 + vertex -2.194459938233373 5.043247523123249 19.29217846862717 + vertex -1.605294890156283 5.260515974278391 19.65749372610342 + endloop +endfacet +facet normal -0.866427 0.499304 -0.000281061 + outer loop + vertex -4.600131190995158 3.014762515627636 18.18651027564389 + vertex -4.598174290006761 3.01774637746793 17.45478701894501 + vertex -4.915709720630987 2.466941009123246 17.81820394054487 + endloop +endfacet +facet normal -0.00309118 0.999995 0.000190978 + outer loop + vertex -0.3354015807467305 5.489763727122743 10.13967599684736 + vertex 0.3002524704688126 5.491798289629489 9.775064600251866 + vertex -0.3329773372250535 5.48991130100428 9.406191867178279 + endloop +endfacet +facet normal -0.444191 0.895932 0.000301791 + outer loop + vertex -2.156242545109333 5.05970533595193 5.378616593031186 + vertex -2.720122581376576 4.780264965698579 5.010933649980581 + vertex -2.723449466112852 4.778370329466902 5.738895837883269 + endloop +endfacet +facet normal -0.235087 0.971974 -3.0812e-05 + outer loop + vertex -1.599638590842117 5.262238723080571 13.07511200794479 + vertex -1.599262890242996 5.262352915558935 13.81085552389677 + vertex -0.9821963228066395 5.411588526806627 13.44532190637029 + endloop +endfacet +facet normal 0.226859 0.973927 0.000283372 + outer loop + vertex 0.9312865324749462 5.420581647243291 4.304029951946054 + vertex 1.558182631274909 5.274662727378235 3.941249219772481 + vertex 0.9347541321142854 5.419984752053761 3.579453427105974 + endloop +endfacet +facet normal -0.720606 0.693345 0.000282154 + outer loop + vertex -3.737953839354024 4.034563309065618 5.002338780429589 + vertex -4.174460453283732 3.581044529738519 4.632501134632069 + vertex -4.176799564904809 3.578315999826034 5.36342896831726 + endloop +endfacet +facet normal 0.635449 0.772143 -0.000296192 + outer loop + vertex 3.733692718472325 4.03850698699739 11.99605576310998 + vertex 3.736454861613151 4.035951568976943 11.26022638988133 + vertex 3.243111424954422 4.442097284541402 11.6248340143204 + endloop +endfacet +facet normal -0.795179 0.606375 0.00019854 + outer loop + vertex -4.174460453283732 3.581044529738519 4.632501134632069 + vertex -4.557314361194889 3.079104709691896 4.262217895531347 + vertex -4.558730071149369 3.077008309770787 4.994878305694187 + endloop +endfacet +facet normal -0.917925 0.396755 0.000361591 + outer loop + vertex -5.164834411129698 1.890630980813162 15.27016150908249 + vertex -5.166420226055012 1.886293203033316 16.0040728052201 + vertex -4.914848247313041 2.46865686272595 15.6405238496727 + endloop +endfacet +facet normal 0.435428 0.900223 0.000265991 + outer loop + vertex 2.100144231072024 5.083246424156013 18.95220948434659 + vertex 2.679885196006852 4.802938198251494 18.5928712167449 + vertex 2.103215541586377 5.081976425135158 18.22266410324536 + endloop +endfacet +facet normal 0.112801 0.993618 0.000310754 + outer loop + vertex 0.3055515148459051 5.491506011266433 4.66402990365856 + vertex 0.9312865324749462 5.420581647243291 4.304029951946054 + vertex 0.30949445038025 5.491285203409474 3.938797738407567 + endloop +endfacet +facet normal 0.339103 0.940749 -0.000213722 + outer loop + vertex 1.565967758461246 5.272356681737292 6.118716452020724 + vertex 2.15678241110269 5.059475232784332 6.489597573843957 + vertex 2.159295580663456 5.058403166546462 5.758176769272027 + endloop +endfacet +facet normal 0.637324 0.770596 4.21534e-05 + outer loop + vertex 3.742825607793919 4.03004422676006 5.401516095877726 + vertex 3.742433202854696 4.030408629676492 4.672797414005285 + vertex 3.25639733700985 4.432366905335698 5.035373969090404 + endloop +endfacet +facet normal 0.111047 0.993815 0.000108656 + outer loop + vertex 0.2939996045947215 5.49213658174104 11.98041007769864 + vertex 0.9247966696185814 5.421692643433634 11.61532331063718 + vertex 0.2953835508501084 5.492062322833489 11.24521763091109 + endloop +endfacet +facet normal -0.00158024 0.999999 0.000269102 + outer loop + vertex -0.3245943420598152 5.490413328074924 5.02410660243334 + vertex 0.3055515148459051 5.491506011266433 4.66402990365856 + vertex -0.3211802337802007 5.490614105674236 4.298053992840217 + endloop +endfacet +facet normal -0.726237 0.687444 0.000277963 + outer loop + vertex -4.20549953808906 3.544541385727172 11.96453594073424 + vertex -4.207775377435437 3.54183940531584 12.70082873519072 + vertex -3.768538806172715 4.00600989344389 12.33569936112557 + endloop +endfacet +facet normal 0.634642 0.772807 0.000290845 + outer loop + vertex 3.730881864473303 4.041103873119845 12.73213419285154 + vertex 3.2399646392556 4.444392999766484 12.3608043102248 + vertex 3.23697700145235 4.446569452068476 13.09694371569185 + endloop +endfacet +facet normal -0.636536 0.771247 0.000224843 + outer loop + vertex -3.251307770456957 4.436101642407015 5.370668124934424 + vertex -3.737953839354024 4.034563309065618 5.002338780429589 + vertex -3.740045600494774 4.032624319995564 5.731546243898735 + endloop +endfacet +facet normal -0.544216 0.838945 0.000338449 + outer loop + vertex -2.723449466112852 4.778370329466902 5.738895837883269 + vertex -3.251307770456957 4.436101642407015 5.370668124934424 + vertex -3.254775613716721 4.433557905830818 6.09986861334725 + endloop +endfacet +facet normal 0.796422 0.604742 0.000375514 + outer loop + vertex 4.566179940187244 3.065942066287558 10.52991912852155 + vertex 4.563512583583712 3.069910894386531 9.795523476206014 + vertex 4.181216983490701 3.573153304431385 10.15965879864028 + endloop +endfacet +facet normal -0.234956 0.972006 -0.000262388 + outer loop + vertex -0.9789182018068283 5.412182476060031 12.71018137601641 + vertex -1.599638590842117 5.262238723080571 13.07511200794479 + vertex -0.9821963228066395 5.411588526806627 13.44532190637029 + endloop +endfacet +facet normal 0.106816 0.994279 0.000299308 + outer loop + vertex 0.2694315000299995 5.493396642041387 16.38625459166656 + vertex 0.9017122864072585 5.425579688157036 16.02342662257618 + vertex 0.2732321874398657 5.493208913899673 15.65350056583433 + endloop +endfacet +facet normal 0.634909 0.772587 -0.000301169 + outer loop + vertex 3.730881864473303 4.041103873119845 12.73213419285154 + vertex 3.733692718472325 4.03850698699739 11.99605576310998 + vertex 3.2399646392556 4.444392999766484 12.3608043102248 + endloop +endfacet +facet normal 0.635973 0.771711 -0.000273352 + outer loop + vertex 3.736454861613151 4.035951568976943 11.26022638988133 + vertex 3.739001783202773 4.033592154049103 10.5248633300495 + vertex 3.246224851423652 4.439822543075285 10.8892865042854 + endloop +endfacet +facet normal -0.549931 0.83521 0.000168296 + outer loop + vertex -2.755486671513457 4.75996777332701 13.07827609719789 + vertex -3.282870743564781 4.412794996489914 12.70690887131546 + vertex -3.284598920282779 4.411508804578905 13.44289205746733 + endloop +endfacet +facet normal -0.229303 0.973355 0.000221137 + outer loop + vertex -1.565338836542403 5.272543440011858 5.745524669891359 + vertex -1.568027322643233 5.271744522968113 6.474271455702275 + vertex -0.9514647961173107 5.417076217088831 6.113238048924342 + endloop +endfacet +facet normal -0.339604 0.940568 0.000264829 + outer loop + vertex -2.163001353030806 5.056819667220386 6.836694798394829 + vertex -1.568027322643233 5.271744522968113 6.474271455702275 + vertex -2.15990204534286 5.058144240185696 6.106736787693633 + endloop +endfacet +facet normal -0.725777 0.68793 8.73237e-05 + outer loop + vertex -3.765326991561123 4.009028890719206 19.65026233461441 + vertex -4.20510078902244 3.545014436382855 20.01829885998822 + vertex -3.764535802277208 4.009771838069231 20.37321112384092 + endloop +endfacet +facet normal -0.00216111 0.999998 0.000253067 + outer loop + vertex -0.3299439089030948 5.490094445178311 8.673741095686063 + vertex 0.3046216084273119 5.491557672981243 8.310771337383457 + vertex -0.3267336320428044 5.490286434576261 7.942507020545281 + endloop +endfacet +facet normal -0.233611 0.97233 -0.000275676 + outer loop + vertex -0.9721075192870968 5.413409920830445 11.23866444627867 + vertex -1.591618912029431 5.264669907873641 11.60353579911821 + vertex -0.9755631203259217 5.412788246205457 11.97429163264967 + endloop +endfacet +facet normal -0.640305 0.768121 0.000352159 + outer loop + vertex -3.760953233344837 4.01313228994423 10.12705573614122 + vertex -3.272316987094792 4.420626826137992 9.760825036399151 + vertex -3.757675615326284 4.016201435434015 9.392158036646613 + endloop +endfacet +facet normal 0.332541 0.943089 -0.000161376 + outer loop + vertex 2.126027404577531 5.072475478007294 13.82654127353561 + vertex 1.526772267661226 5.283840122742228 14.19155595219776 + vertex 2.124130725649839 5.073270016503192 14.56145281446745 + endloop +endfacet +facet normal 0.109921 0.99394 0.000393503 + outer loop + vertex 0.2939996045947215 5.49213658174104 11.98041007769864 + vertex 0.2889348960300206 5.492405358843802 12.71628545687114 + vertex 0.9157185103458564 5.423233316925427 12.35095009251186 + endloop +endfacet +facet normal -0.801626 0.597826 -0.000243564 + outer loop + vertex -4.592056601583848 3.027047434027125 13.80214175608399 + vertex -4.212012044866582 3.536800041548692 14.17214472345561 + vertex -4.210023668379002 3.539166669102856 13.43680883328707 + endloop +endfacet +facet normal -0.957692 0.287796 -0.000139546 + outer loop + vertex -5.166641334823746 1.885687491948415 17.44774793172886 + vertex -5.166046937107233 1.887315300527439 16.72559648960204 + vertex -5.350454380830277 1.273828056942577 17.05762700172786 + endloop +endfacet +facet normal -0.726008 0.687686 -0.000292857 + outer loop + vertex -4.20549953808906 3.544541385727172 11.96453594073424 + vertex -3.768538806172715 4.00600989344389 12.33569936112557 + vertex -3.765826944842038 4.008559270049738 11.59929669367751 + endloop +endfacet +facet normal -0.639801 0.76854 0.000159493 + outer loop + vertex -3.757675615326284 4.016201435434015 9.392158036646613 + vertex -3.269152095501428 4.422967847099797 9.026767284026866 + vertex -3.756191792225918 4.017589229875878 8.657180996278033 + endloop +endfacet +facet normal -0.550995 0.834508 0.000435466 + outer loop + vertex -2.764583419145227 4.754690160103736 18.92372716072775 + vertex -3.288785535624673 4.408388560536143 19.2877628911882 + vertex -2.75983315162458 4.757448998696038 19.64732542503119 + endloop +endfacet +facet normal -0.642057 0.766657 0.000564981 + outer loop + vertex -3.288785535624673 4.408388560536143 19.2877628911882 + vertex -3.765326991561123 4.009028890719206 19.65026233461441 + vertex -3.283048353747241 4.412662858972746 20.00757501231982 + endloop +endfacet +facet normal -0.00636339 0.99998 -0.000356881 + outer loop + vertex 0.2800449050422982 5.492865814050062 14.18619827858576 + vertex 0.2845863738601849 5.492632392197125 13.45117311754784 + vertex -0.3522236674785046 5.488710093279476 13.81558093640346 + endloop +endfacet +facet normal 0.339036 0.940773 0.000166685 + outer loop + vertex 2.15734721088084 5.05923442940774 5.029478211222619 + vertex 1.564944612513594 5.272660463159435 5.390523919726905 + vertex 2.159295580663456 5.058403166546462 5.758176769272027 + endloop +endfacet +facet normal 0.436193 0.899853 -0.000182905 + outer loop + vertex 2.680946204045271 4.802346036159332 17.13226512573994 + vertex 2.110225258263429 5.079069733660589 17.49329836618297 + vertex 2.678916879983762 4.803478359495134 17.86350278336204 + endloop +endfacet +facet normal 0.860323 0.509749 0.000303465 + outer loop + vertex 4.562176563648654 3.071895994674128 12.00313638980624 + vertex 4.560022727424994 3.075092311682288 12.74020235260279 + vertex 4.886513843818911 2.524278600742425 12.37504345209598 + endloop +endfacet +facet normal 0.637791 0.770209 0.000499031 + outer loop + vertex 3.254896381159889 4.433469245174963 4.308344229599244 + vertex 3.746583584735469 4.026550812120806 3.945041764355005 + vertex 3.259958712102899 4.429748209027733 3.581471263481195 + endloop +endfacet +facet normal 0.793757 0.608235 0.000572861 + outer loop + vertex 4.166942054625144 3.589790232506126 14.57600157407444 + vertex 4.162202925068889 3.595283967998631 15.30957942587535 + vertex 4.552133984799601 3.086758199864788 14.94713570478919 + endloop +endfacet +facet normal 0.438821 0.898574 -0.000293885 + outer loop + vertex 2.69645959363408 4.793652642807855 14.19739360155101 + vertex 2.124130725649839 5.073270016503192 14.56145281446745 + vertex 2.693199767364561 4.795484856932349 14.93203417297265 + endloop +endfacet +facet normal -0.00525251 0.999986 0.000274317 + outer loop + vertex -0.3483378758125438 5.488958072737885 13.08066832146781 + vertex 0.2889348960300206 5.492405358843802 12.71628545687114 + vertex -0.3448527004242826 5.489178136571092 12.34518875272993 + endloop +endfacet +facet normal 0.229413 0.973329 8.37089e-05 + outer loop + vertex 1.564944612513594 5.272660463159435 5.390523919726905 + vertex 0.9539730636607033 5.416635061900498 5.751691864852545 + vertex 1.565967758461246 5.272356681737292 6.118716452020724 + endloop +endfacet +facet normal -0.235203 0.971946 -0.000237832 + outer loop + vertex -0.9821963228066395 5.411588526806627 13.44532190637029 + vertex -1.599262890242996 5.262352915558935 13.81085552389677 + vertex -0.9851812348334736 5.411045918723292 14.17976752853854 + endloop +endfacet +facet normal -0.553107 0.83311 0.000290027 + outer loop + vertex -3.302472647521388 4.398144428321229 17.09833579472796 + vertex -2.773056990794739 4.749753143670145 16.73580144231683 + vertex -3.299526998621698 4.400354711312088 16.36685317911597 + endloop +endfacet +facet normal -0.00485846 0.999988 -0.000398682 + outer loop + vertex -0.3448527004242826 5.489178136571092 12.34518875272993 + vertex 0.2889348960300206 5.492405358843802 12.71628545687114 + vertex 0.2939996045947215 5.49213658174104 11.98041007769864 + endloop +endfacet +facet normal 0.858484 0.51284 0.000711013 + outer loop + vertex 4.552133984799601 3.086758199864788 14.94713570478919 + vertex 4.547089916440817 3.094183784425586 15.68146541042857 + vertex 4.877746635599592 2.541178419335578 15.31515588422337 + endloop +endfacet +facet normal 0.441152 0.897432 -0.000301072 + outer loop + vertex 2.136595684821637 5.068033038527035 11.61759465937531 + vertex 2.706256529158432 4.788128611303936 11.98948039066311 + vertex 2.709588604720712 4.786243787477574 11.25361401691623 + endloop +endfacet +facet normal 0.438244 0.898856 -0.00026051 + outer loop + vertex 2.693199767364561 4.795484856932349 14.93203417297265 + vertex 2.120872707858986 5.074632888895402 15.29577543723218 + vertex 2.690311348957866 4.797105882265734 15.6661138397711 + endloop +endfacet +facet normal 0.220144 0.975467 0.00032891 + outer loop + vertex 0.8975897917409533 5.426263223044237 16.75547133290806 + vertex 1.517935936642233 5.286385390060969 16.39270319811148 + vertex 0.9017122864072585 5.425579688157036 16.02342662257618 + endloop +endfacet +facet normal -0.443939 0.896057 -0.000179818 + outer loop + vertex -2.154141002807604 5.060600412996767 4.650566298183991 + vertex -2.720122581376576 4.780264965698579 5.010933649980581 + vertex -2.156242545109333 5.05970533595193 5.378616593031186 + endloop +endfacet +facet normal 0.540719 0.841203 0.000260511 + outer loop + vertex 2.702402812701651 4.790304691551698 12.72565874458753 + vertex 2.699519646977631 4.791930057459288 13.46159641120867 + vertex 3.23697700145235 4.446569452068476 13.09694371569185 + endloop +endfacet +facet normal -0.917062 0.398744 -5.60869e-05 + outer loop + vertex -4.909352147307213 2.479568812057867 12.69452805020423 + vertex -4.909025451291431 2.480215538733068 11.95064759781068 + vertex -5.161756596738037 1.899017860903723 12.32305457307666 + endloop +endfacet +facet normal 0.794135 0.607742 -0.000487082 + outer loop + vertex 4.166942054625144 3.589790232506126 14.57600157407444 + vertex 4.552133984799601 3.086758199864788 14.94713570478919 + vertex 4.555605928058299 3.081631812569451 14.21147262318354 + endloop +endfacet +facet normal 0.718793 0.695224 -0.00032232 + outer loop + vertex 3.725143434257081 4.046394246018468 14.20400374184834 + vertex 4.166942054625144 3.589790232506126 14.57600157407444 + vertex 4.169614102858932 3.586686246835636 13.83973113987994 + endloop +endfacet +facet normal 0.33045 0.943823 0.000381758 + outer loop + vertex 1.513274589194329 5.287721628234483 17.1239828427341 + vertex 2.113350427269168 5.077770177111329 16.76176094383523 + vertex 1.517935936642233 5.286385390060969 16.39270319811148 + endloop +endfacet +facet normal 0.110575 0.993868 -0.000716954 + outer loop + vertex 0.2939996045947215 5.49213658174104 11.98041007769864 + vertex 0.9157185103458564 5.423233316925427 12.35095009251186 + vertex 0.9247966696185814 5.421692643433634 11.61532331063718 + endloop +endfacet +facet normal -0.232302 0.972644 -0.00030774 + outer loop + vertex -0.9643705449208908 5.414793574282309 9.769856747733114 + vertex -1.584780954026627 5.266732319736257 10.13313319191941 + vertex -0.9682168451676494 5.414107141600875 10.50375290328457 + endloop +endfacet +facet normal -0.230796 0.973002 -0.00027776 + outer loop + vertex -0.9573168647443093 5.416045090328931 8.304983976598086 + vertex -1.57550572332861 5.269514371909312 8.667668761794854 + vertex -0.9607923148651225 5.415429634636214 9.036838586275445 + endloop +endfacet +facet normal -0.725535 0.688186 -0.000267791 + outer loop + vertex -4.202917943979592 3.547602113565494 11.22823847805601 + vertex -3.765826944842038 4.008559270049738 11.59929669367751 + vertex -3.763344481104095 4.010889965648939 10.86304173914669 + endloop +endfacet +facet normal 0.631543 0.775341 0.000460992 + outer loop + vertex 3.219014690661195 4.459590162930603 16.77024877340427 + vertex 3.71401833700239 4.056607917017615 16.40709822925858 + vertex 3.223761391834297 4.456160060917762 16.03651162530636 + endloop +endfacet +facet normal 0.716341 0.69775 0.000504623 + outer loop + vertex 3.709288892712822 4.060932886714244 17.14061865087743 + vertex 4.154980888345557 3.603627868895894 16.77750589539072 + vertex 3.71401833700239 4.056607917017615 16.40709822925858 + endloop +endfacet +facet normal 0.720951 0.692986 0.00027356 + outer loop + vertex 4.179424357135561 3.57524992734522 10.89515204038594 + vertex 3.739001783202773 4.033592154049103 10.5248633300495 + vertex 3.736454861613151 4.035951568976943 11.26022638988133 + endloop +endfacet +facet normal 0.441528 0.897247 0.000433873 + outer loop + vertex 2.141680680654499 5.065886285943584 10.88235392453209 + vertex 2.136595684821637 5.068033038527035 11.61759465937531 + vertex 2.709588604720712 4.786243787477574 11.25361401691623 + endloop +endfacet +facet normal -0.803047 0.595916 -0.000262913 + outer loop + vertex -4.221761821939877 3.525156325443014 17.82343063942983 + vertex -4.219621040588515 3.527718564996746 17.09213177742202 + vertex -4.598174290006761 3.01774637746793 17.45478701894501 + endloop +endfacet +facet normal 0.860571 0.50933 -8.36411e-05 + outer loop + vertex 4.886374773580517 2.524547795569723 5.041732577290214 + vertex 4.886861798041292 2.523604914966807 4.311007271835738 + vertex 4.563949237429648 3.069261695940139 4.674562988651441 + endloop +endfacet +facet normal -0.23335 0.972393 0.000194112 + outer loop + vertex -1.589254029909478 5.265384281172314 10.86784499063469 + vertex -1.591618912029431 5.264669907873641 11.60353579911821 + vertex -0.9721075192870968 5.413409920830445 11.23866444627867 + endloop +endfacet +facet normal -0.343792 0.939046 -0.000193286 + outer loop + vertex -2.185024418165879 5.047342696114349 11.23106540038434 + vertex -1.591618912029431 5.264669907873641 11.60353579911821 + vertex -1.589254029909478 5.265384281172314 10.86784499063469 + endloop +endfacet +facet normal -0.452989 0.891516 0.000274799 + outer loop + vertex -2.773056990794739 4.749753143670145 16.73580144231683 + vertex -2.202922862387096 5.03955661366873 16.37282938396807 + vertex -2.77006097467527 4.751501046677892 16.00392148952702 + endloop +endfacet +facet normal -0.233063 0.972462 -0.000311263 + outer loop + vertex -0.9682168451676494 5.414107141600875 10.50375290328457 + vertex -1.589254029909478 5.265384281172314 10.86784499063469 + vertex -0.9721075192870968 5.413409920830445 11.23866444627867 + endloop +endfacet +facet normal 0.332764 0.94301 0.000250177 + outer loop + vertex 2.126027404577531 5.072475478007294 13.82654127353561 + vertex 1.529835967906667 5.282953900167885 13.45699023934335 + vertex 1.526772267661226 5.283840122742228 14.19155595219776 + endloop +endfacet +facet normal -0.550031 0.835144 -4.04747e-05 + outer loop + vertex -2.755934067944267 4.75970875297472 13.81361629833644 + vertex -2.755486671513457 4.75996777332701 13.07827609719789 + vertex -3.284598920282779 4.411508804578905 13.44289205746733 + endloop +endfacet +facet normal -0.801457 0.598053 0.000250168 + outer loop + vertex -4.590306397789944 3.029700839094301 13.06598312625897 + vertex -4.592056601583848 3.027047434027125 13.80214175608399 + vertex -4.210023668379002 3.539166669102856 13.43680883328707 + endloop +endfacet +facet normal 0.720446 0.693511 -0.000243122 + outer loop + vertex 4.177069149615913 3.578001302309292 7.965218399827975 + vertex 3.735609022597694 4.036734476069326 8.327927643449971 + vertex 4.175055378160717 3.580350903094733 8.700074265015786 + endloop +endfacet +facet normal 0.439055 0.89846 0.000161769 + outer loop + vertex 2.69645959363408 4.793652642807855 14.19739360155101 + vertex 2.126027404577531 5.072475478007294 13.82654127353561 + vertex 2.124130725649839 5.073270016503192 14.56145281446745 + endloop +endfacet +facet normal -0.347234 0.937778 -4.95541e-06 + outer loop + vertex -2.202922862387096 5.03955661366873 16.37282938396807 + vertex -1.610314611093768 5.258981541448679 16.01007290764218 + vertex -2.202980720697034 5.039531321882738 15.64075789320135 + endloop +endfacet +facet normal -0.729009 0.684504 -0.00030739 + outer loop + vertex -3.787613740678036 3.987979708000899 17.46072148755751 + vertex -3.784781376700859 3.990667855206488 16.72949380097899 + vertex -4.219621040588515 3.527718564996746 17.09213177742202 + endloop +endfacet +facet normal 0.718512 0.695514 0.000368078 + outer loop + vertex 3.725143434257081 4.046394246018468 14.20400374184834 + vertex 3.721708589489778 4.049553700708018 14.93898835038859 + vertex 4.166942054625144 3.589790232506126 14.57600157407444 + endloop +endfacet +facet normal -0.984733 0.174071 4.8215e-05 + outer loop + vertex -5.462604141102114 0.640278062730595 8.536680095263456 + vertex -5.462675335659052 0.6396703660341518 9.276591032760054 + vertex -5.350996320403336 1.271549597550153 8.905278694477291 + endloop +endfacet +facet normal 0.440404 0.897799 0.00067997 + outer loop + vertex 2.13807510768009 5.067409084918917 12.35499137436904 + vertex 2.130062841592538 5.07078221686425 13.09066671338084 + vertex 2.702402812701651 4.790304691551698 12.72565874458753 + endloop +endfacet +facet normal -0.0059842 0.999982 0.00030578 + outer loop + vertex -0.3522236674785046 5.488710093279476 13.81558093640346 + vertex 0.2845863738601849 5.492632392197125 13.45117311754784 + vertex -0.3483378758125438 5.488958072737885 13.08066832146781 + endloop +endfacet +facet normal 0.720729 0.693217 -0.000288688 + outer loop + vertex 4.177038937288492 3.578036572811383 11.63127327229928 + vertex 4.179424357135561 3.57524992734522 10.89515204038594 + vertex 3.736454861613151 4.035951568976943 11.26022638988133 + endloop +endfacet +facet normal -0.543134 0.839646 0.000392827 + outer loop + vertex -3.24670894030754 4.439468555686265 3.913368189062605 + vertex -2.715775427328977 4.782736019091594 4.282403839769607 + vertex -2.720098218800375 4.780278828695982 3.557694086819801 + endloop +endfacet +facet normal 0.439285 0.898348 -0.000276224 + outer loop + vertex 2.69645959363408 4.793652642807855 14.19739360155101 + vertex 2.699519646977631 4.791930057459288 13.46159641120867 + vertex 2.126027404577531 5.072475478007294 13.82654127353561 + endloop +endfacet +facet normal -0.724775 0.688986 -0.000255692 + outer loop + vertex -4.197232969911694 3.554326292883965 10.49321336546519 + vertex -3.763344481104095 4.010889965648939 10.86304173914669 + vertex -3.760953233344837 4.01313228994423 10.12705573614122 + endloop +endfacet +facet normal -0.543012 0.839725 0.000143198 + outer loop + vertex -3.24670894030754 4.439468555686265 3.913368189062605 + vertex -3.248170387885879 4.438399388435125 4.641195007400434 + vertex -2.715775427328977 4.782736019091594 4.282403839769607 + endloop +endfacet +facet normal 0.634112 0.773241 0.000299739 + outer loop + vertex 3.728098583680958 4.043671716442376 13.46825646244697 + vertex 3.23697700145235 4.446569452068476 13.09694371569185 + vertex 3.233897126492125 4.448809883021073 13.83288720962454 + endloop +endfacet +facet normal 0.856528 0.516101 -0.000396419 + outer loop + vertex 4.539148916185716 3.105821488220152 17.8802646915997 + vertex 4.865749673179342 2.564074904903351 18.25038236144107 + vertex 4.868094338385164 2.559620579809108 17.51729407791064 + endloop +endfacet +facet normal 0.795973 0.605333 4.90798e-05 + outer loop + vertex 4.562735033130303 3.071066429995517 7.600486548182634 + vertex 4.562386486476917 3.071584208191729 6.867102472469194 + vertex 4.178568741894685 3.576249889096212 7.231759319986232 + endloop +endfacet +facet normal 0.796306 0.604894 -0.000278377 + outer loop + vertex 4.564207626536311 3.068877440020662 11.26642348942379 + vertex 4.566179940187244 3.065942066287558 10.52991912852155 + vertex 4.179424357135561 3.57524992734522 10.89515204038594 + endloop +endfacet +facet normal -0.234215 0.972185 -0.000267553 + outer loop + vertex -0.9755631203259217 5.412788246205457 11.97429163264967 + vertex -1.594841589980115 5.263694548781274 12.33900123544736 + vertex -0.9789182018068283 5.412182476060031 12.71018137601641 + endloop +endfacet +facet normal -0.723252 0.690584 0.00043422 + outer loop + vertex -3.753172034506454 4.020410386937966 7.923594727606659 + vertex -4.187648423468353 3.565613647245452 7.553553388071339 + vertex -4.191236072447158 3.561395819761926 8.285876008499198 + endloop +endfacet +facet normal 0.436832 0.899543 -0.000507832 + outer loop + vertex 2.113350427269168 5.077770177111329 16.76176094383523 + vertex 2.680946204045271 4.802346036159332 17.13226512573994 + vertex 2.686581987151288 4.7991954769851 16.39939846347043 + endloop +endfacet +facet normal 0.9127 0.408631 -0.000330132 + outer loop + vertex 4.880890562096091 2.535134576475439 14.58315638407505 + vertex 5.141115229323106 1.95420935388766 14.9559015917752 + vertex 5.14260411224237 1.950287913295847 14.21826185107064 + endloop +endfacet +facet normal -0.449105 0.893479 -0.000242009 + outer loop + vertex -2.182188084779327 5.048569615509638 10.49727345085342 + vertex -2.748401568742806 4.764062217995487 10.8602147235481 + vertex -2.185024418165879 5.047342696114349 11.23106540038434 + endloop +endfacet +facet normal 0.540167 0.841558 0.000276277 + outer loop + vertex 3.233897126492125 4.448809883021073 13.83288720962454 + vertex 2.699519646977631 4.791930057459288 13.46159641120867 + vertex 2.69645959363408 4.793652642807855 14.19739360155101 + endloop +endfacet +facet normal -0.725769 0.687938 0.000315024 + outer loop + vertex -4.202917943979592 3.547602113565494 11.22823847805601 + vertex -4.20549953808906 3.544541385727172 11.96453594073424 + vertex -3.765826944842038 4.008559270049738 11.59929669367751 + endloop +endfacet +facet normal -0.800845 0.598872 -0.000277679 + outer loop + vertex -4.20549953808906 3.544541385727172 11.96453594073424 + vertex -4.587900685810118 3.033342594753031 12.32887917960164 + vertex -4.207775377435437 3.54183940531584 12.70082873519072 + endloop +endfacet +facet normal 0.913331 0.407217 0.000686409 + outer loop + vertex 5.144340037657432 1.945704390948104 3.946742345627829 + vertex 5.141289816700485 1.953749989300548 3.23223805190901 + vertex 4.887524974198084 2.522320286282061 3.581719537648792 + endloop +endfacet +facet normal 0.54045 0.841376 -0.000299651 + outer loop + vertex 3.23697700145235 4.446569452068476 13.09694371569185 + vertex 2.699519646977631 4.791930057459288 13.46159641120867 + vertex 3.233897126492125 4.448809883021073 13.83288720962454 + endloop +endfacet +facet normal 0.543515 0.839399 0.000347844 + outer loop + vertex 2.716777995166491 4.782166593185472 7.590795854324413 + vertex 3.250073991176871 4.4370056402799 7.22730766149194 + vertex 2.720623379131812 4.779979961142243 6.858957268139787 + endloop +endfacet +facet normal -0.640008 0.768368 -0.000308956 + outer loop + vertex -3.272316987094792 4.420626826137992 9.760825036399151 + vertex -3.269152095501428 4.422967847099797 9.026767284026866 + vertex -3.757675615326284 4.016201435434015 9.392158036646613 + endloop +endfacet +facet normal -0.00775148 0.99997 -0.000226887 + outer loop + vertex 0.2732321874398657 5.493208913899673 15.65350056583433 + vertex 0.2761128175058328 5.493064874185357 14.9202532219283 + vertex -0.3598129782511795 5.488217800040557 15.28358645969896 + endloop +endfacet +facet normal -0.801274 0.598298 -0.000275011 + outer loop + vertex -4.207775377435437 3.54183940531584 12.70082873519072 + vertex -4.590306397789944 3.029700839094301 13.06598312625897 + vertex -4.210023668379002 3.539166669102856 13.43680883328707 + endloop +endfacet +facet normal 0.226638 0.973979 0.000250493 + outer loop + vertex 0.9347925745220471 5.419978121968616 7.947965626364867 + vertex 1.552549114769935 5.276323648737546 7.585291971265814 + vertex 0.9379299192986701 5.419436083808387 7.216973568687898 + endloop +endfacet +facet normal 0.795679 0.605718 0.000243748 + outer loop + vertex 4.177069149615913 3.578001302309292 7.965218399827975 + vertex 4.175055378160717 3.580350903094733 8.700074265015786 + vertex 4.561739448136046 3.072545070022481 8.334534675596213 + endloop +endfacet +facet normal -0.00674395 0.999977 0.000292375 + outer loop + vertex -0.3559398938203805 5.488470350834296 14.5498265854421 + vertex 0.2800449050422982 5.492865814050062 14.18619827858576 + vertex -0.3522236674785046 5.488710093279476 13.81558093640346 + endloop +endfacet +facet normal -0.917174 0.398486 -0.000535408 + outer loop + vertex -4.909025451291431 2.480215538733068 11.95064759781068 + vertex -5.164172210296571 1.892439003614285 11.56467286409568 + vertex -5.161756596738037 1.899017860903723 12.32305457307666 + endloop +endfacet +facet normal -0.00290109 0.999996 -0.000135344 + outer loop + vertex 0.3002524704688126 5.491798289629489 9.775064600251866 + vertex 0.3019705202645296 5.491704089341592 9.042234105602269 + vertex -0.3329773372250535 5.48991130100428 9.406191867178279 + endloop +endfacet +facet normal -0.232686 0.972552 0.000367783 + outer loop + vertex -0.9682168451676494 5.414107141600875 10.50375290328457 + vertex -1.584780954026627 5.266732319736257 10.13313319191941 + vertex -1.589254029909478 5.265384281172314 10.86784499063469 + endloop +endfacet +facet normal 0.337533 0.941314 0.000452074 + outer loop + vertex 1.552549114769935 5.276323648737546 7.585291971265814 + vertex 2.151434623773428 5.061751580197203 7.222461682940452 + vertex 1.558061537370548 5.274698498091292 6.85344604553776 + endloop +endfacet +facet normal 0.911103 0.412179 0.000439495 + outer loop + vertex 5.133866670985064 1.973173333630053 16.41890538970767 + vertex 4.872777661995054 2.55069360307388 16.04778589539585 + vertex 4.870184922199945 2.555640589671465 16.78318931728384 + endloop +endfacet +facet normal -0.865207 0.501415 0.000195444 + outer loop + vertex -4.908877155372405 2.480509035150433 13.43011541263371 + vertex -4.910007904730391 2.478270036837204 14.16861485224099 + vertex -4.592056601583848 3.027047434027125 13.80214175608399 + endloop +endfacet +facet normal 0.112987 0.993596 0.000220173 + outer loop + vertex 0.3046216084273119 5.491557672981243 8.310771337383457 + vertex 0.9347925745220471 5.419978121968616 7.947965626364867 + vertex 0.3074141288358063 5.491402057161006 7.579986864874797 + endloop +endfacet +facet normal -0.725157 0.688583 0.000690663 + outer loop + vertex -4.197232969911694 3.554326292883965 10.49321336546519 + vertex -4.202917943979592 3.547602113565494 11.22823847805601 + vertex -3.763344481104095 4.010889965648939 10.86304173914669 + endloop +endfacet +facet normal -0.342303 0.939589 -0.000442558 + outer loop + vertex -1.584780954026627 5.266732319736257 10.13313319191941 + vertex -1.579382700414764 5.268353659885654 9.40001846000073 + vertex -2.177046150527109 5.050789053056473 9.763260881829368 + endloop +endfacet +facet normal 0.330102 0.943945 -0.00026668 + outer loop + vertex 1.513274589194329 5.287721628234483 17.1239828427341 + vertex 2.110225258263429 5.079069733660589 17.49329836618297 + vertex 2.113350427269168 5.077770177111329 16.76176094383523 + endloop +endfacet +facet normal -0.00560496 0.999984 -0.000342097 + outer loop + vertex -0.3483378758125438 5.488958072737885 13.08066832146781 + vertex 0.2845863738601849 5.492632392197125 13.45117311754784 + vertex 0.2889348960300206 5.492405358843802 12.71628545687114 + endloop +endfacet +facet normal 0.637241 0.770665 -0.000147085 + outer loop + vertex 3.25639733700985 4.432366905335698 5.035373969090404 + vertex 3.742433202854696 4.030408629676492 4.672797414005285 + vertex 3.254896381159889 4.433469245174963 4.308344229599244 + endloop +endfacet +facet normal 0.111695 0.993743 -0.000168137 + outer loop + vertex 0.2990237685235045 5.491865328452437 10.5099348930492 + vertex 0.9265167379228637 5.421398964690643 10.87934931410019 + vertex 0.9286399982135676 5.421035671688382 10.14267071378961 + endloop +endfacet +facet normal 0.634382 0.77302 -0.000297955 + outer loop + vertex 3.728098583680958 4.043671716442376 13.46825646244697 + vertex 3.730881864473303 4.041103873119845 12.73213419285154 + vertex 3.23697700145235 4.446569452068476 13.09694371569185 + endloop +endfacet +facet normal 0.721369 0.692551 0.000189027 + outer loop + vertex 3.741065371887834 4.031678296102225 6.132109706259876 + vertex 4.1799857098378 3.574593608447229 5.768349711835589 + vertex 3.742825607793919 4.03004422676006 5.401516095877726 + endloop +endfacet +facet normal -0.340821 0.940128 -0.000297626 + outer loop + vertex -1.571882198856097 5.270596394424384 7.936098640024214 + vertex -2.169140817674367 5.054189164752243 8.298592900015723 + vertex -1.57550572332861 5.269514371909312 8.667668761794854 + endloop +endfacet +facet normal -0.00708785 0.999975 -0.000309139 + outer loop + vertex -0.3559398938203805 5.488470350834296 14.5498265854421 + vertex 0.2761128175058328 5.493064874185357 14.9202532219283 + vertex 0.2800449050422982 5.492865814050062 14.18619827858576 + endloop +endfacet +facet normal -0.00268656 0.999996 0.000238916 + outer loop + vertex -0.3329773372250535 5.48991130100428 9.406191867178279 + vertex 0.3019705202645296 5.491704089341592 9.042234105602269 + vertex -0.3299439089030948 5.490094445178311 8.673741095686063 + endloop +endfacet +facet normal -0.544523 0.838746 -0.000303664 + outer loop + vertex -2.723449466112852 4.778370329466902 5.738895837883269 + vertex -3.254775613716721 4.433557905830818 6.09986861334725 + vertex -2.7268006282093 4.776458765026383 6.4682204653972 + endloop +endfacet +facet normal -0.235548 0.971863 0.000369494 + outer loop + vertex -1.599262890242996 5.262352915558935 13.81085552389677 + vertex -1.603762649021274 5.260983307862159 14.5447323978708 + vertex -0.9851812348334736 5.411045918723292 14.17976752853854 + endloop +endfacet +facet normal -0.64523 0.763988 -0.000289813 + outer loop + vertex -3.302472647521388 4.398144428321229 17.09833579472796 + vertex -3.299526998621698 4.400354711312088 16.36685317911597 + vertex -3.784781376700859 3.990667855206488 16.72949380097899 + endloop +endfacet +facet normal 0.795495 0.60596 -0.000303192 + outer loop + vertex 4.562176563648654 3.071895994674128 12.00313638980624 + vertex 4.174610919538479 3.580869122220205 12.36750866252201 + vertex 4.560022727424994 3.075092311682288 12.74020235260279 + endloop +endfacet +facet normal 0.329321 0.944218 -0.000597926 + outer loop + vertex 2.103215541586377 5.081976425135158 18.22266410324536 + vertex 2.110225258263429 5.079069733660589 17.49329836618297 + vertex 1.50976148259572 5.288725769565896 17.85447942085971 + endloop +endfacet +facet normal 0.444273 0.895892 -0.000275353 + outer loop + vertex 2.723674939990226 4.778241812766411 6.127289020167175 + vertex 2.15678241110269 5.059475232784332 6.489597573843957 + vertex 2.720623379131812 4.779979961142243 6.858957268139787 + endloop +endfacet +facet normal 0.914804 0.403855 -0.00591004 + outer loop + vertex 5.141986732089285 1.951915071671345 12.03190553294616 + vertex 5.168137311619096 1.88158356929756 11.27368581568632 + vertex 4.888228129415757 2.52095730919596 11.63790476013536 + endloop +endfacet +facet normal 0.438521 0.898721 0.000277624 + outer loop + vertex 2.124130725649839 5.073270016503192 14.56145281446745 + vertex 2.120872707858986 5.074632888895402 15.29577543723218 + vertex 2.693199767364561 4.795484856932349 14.93203417297265 + endloop +endfacet +facet normal 0.794415 0.607375 0.000322478 + outer loop + vertex 4.166942054625144 3.589790232506126 14.57600157407444 + vertex 4.555605928058299 3.081631812569451 14.21147262318354 + vertex 4.169614102858932 3.586686246835636 13.83973113987994 + endloop +endfacet +facet normal -0.446344 0.894861 -0.000292182 + outer loop + vertex -2.16572987526206 5.055651699573199 7.567235143067204 + vertex -2.734226069823106 4.772212044649702 7.929762223762901 + vertex -2.169140817674367 5.054189164752243 8.298592900015723 + endloop +endfacet +facet normal -0.91744 0.397872 0.00118476 + outer loop + vertex -5.159487311214056 1.905174712571303 14.52663788554383 + vertex -5.164834411129698 1.890630980813162 15.27016150908249 + vertex -4.913268007066149 2.471800455283604 14.90405506725276 + endloop +endfacet +facet normal 0.914934 0.403556 -0.00624426 + outer loop + vertex 5.144868400325386 1.944306854211367 8.339749905384522 + vertex 5.171106296982572 1.873408568707635 7.60218979976907 + vertex 4.886627134838323 2.524059279228959 7.969673719830597 + endloop +endfacet +facet normal -0.724272 0.689514 -0.000350617 + outer loop + vertex -4.194572795966226 3.557465257643436 9.755144478608651 + vertex -3.760953233344837 4.01313228994423 10.12705573614122 + vertex -3.757675615326284 4.016201435434015 9.392158036646613 + endloop +endfacet +facet normal -0.343223 0.939254 -0.000366279 + outer loop + vertex -1.584780954026627 5.266732319736257 10.13313319191941 + vertex -2.182188084779327 5.048569615509638 10.49727345085342 + vertex -1.589254029909478 5.265384281172314 10.86784499063469 + endloop +endfacet +facet normal 0.720492 0.693463 0.000296283 + outer loop + vertex 3.733692718472325 4.03850698699739 11.99605576310998 + vertex 4.177038937288492 3.578036572811383 11.63127327229928 + vertex 3.736454861613151 4.035951568976943 11.26022638988133 + endloop +endfacet +facet normal 0.444826 0.895617 -0.000167685 + outer loop + vertex 2.15734721088084 5.05923442940774 5.029478211222619 + vertex 2.159295580663456 5.058403166546462 5.758176769272027 + vertex 2.72660673659052 4.776569449299277 5.397223163237941 + endloop +endfacet +facet normal -0.236771 0.971566 0.000296013 + outer loop + vertex -1.610314611093768 5.258981541448679 16.01007290764218 + vertex -0.9915929150321402 5.409874628016629 15.64704678609304 + vertex -1.606721372021948 5.260080458765618 15.27734419918179 + endloop +endfacet +facet normal -0.638154 0.769909 -0.000475662 + outer loop + vertex -3.263341203312671 4.427256960100894 7.561026034291711 + vertex -3.258463897029156 4.430847890839582 6.829869678627511 + vertex -3.747237355031224 4.025942399620068 7.192426533269128 + endloop +endfacet +facet normal -0.00242539 0.999997 -0.000208959 + outer loop + vertex -0.3299439089030948 5.490094445178311 8.673741095686063 + vertex 0.3019705202645296 5.491704089341592 9.042234105602269 + vertex 0.3046216084273119 5.491557672981243 8.310771337383457 + endloop +endfacet +facet normal 0.913351 0.407173 0.000831934 + outer loop + vertex 4.886513843818911 2.524278600742425 12.37504345209598 + vertex 5.145654811298226 1.942224642764944 12.74763160945074 + vertex 5.141986732089285 1.951915071671345 12.03190553294616 + endloop +endfacet +facet normal -0.120394 0.992726 0.00026829 + outer loop + vertex -0.3448527004242826 5.489178136571092 12.34518875272993 + vertex -0.9755631203259217 5.412788246205457 11.97429163264967 + vertex -0.9789182018068283 5.412182476060031 12.71018137601641 + endloop +endfacet +facet normal -0.236165 0.971713 0.000243736 + outer loop + vertex -0.9882235632298347 5.410491122724196 14.91371131694453 + vertex -1.603762649021274 5.260983307862159 14.5447323978708 + vertex -1.606721372021948 5.260080458765618 15.27734419918179 + endloop +endfacet +facet normal -0.122575 0.992459 -0.000305411 + outer loop + vertex -0.3598129782511795 5.488217800040557 15.28358645969896 + vertex -0.3559398938203805 5.488470350834296 14.5498265854421 + vertex -0.9882235632298347 5.410491122724196 14.91371131694453 + endloop +endfacet +facet normal -0.122909 0.992418 0.000269588 + outer loop + vertex -0.9915929150321402 5.409874628016629 15.64704678609304 + vertex -0.3598129782511795 5.488217800040557 15.28358645969896 + vertex -0.9882235632298347 5.410491122724196 14.91371131694453 + endloop +endfacet +facet normal 0.71558 0.698531 -0.000319684 + outer loop + vertex 4.150161524325208 3.609177097623594 18.97560217998252 + vertex 3.706682292000083 4.063312243253404 18.60767167829646 + vertex 3.709674271489997 4.060580845081792 19.33662734180532 + endloop +endfacet +facet normal -0.122264 0.992498 0.000243433 + outer loop + vertex -0.3559398938203805 5.488470350834296 14.5498265854421 + vertex -0.9851812348334736 5.411045918723292 14.17976752853854 + vertex -0.9882235632298347 5.410491122724196 14.91371131694453 + endloop +endfacet +facet normal -0.120702 0.992689 -0.000274941 + outer loop + vertex -0.3483378758125438 5.488958072737885 13.08066832146781 + vertex -0.3448527004242826 5.489178136571092 12.34518875272993 + vertex -0.9789182018068283 5.412182476060031 12.71018137601641 + endloop +endfacet +facet normal 0.633558 0.773695 0.000307376 + outer loop + vertex 3.230739827492712 4.451103252796138 14.56802161736779 + vertex 3.725143434257081 4.046394246018468 14.20400374184834 + vertex 3.233897126492125 4.448809883021073 13.83288720962454 + endloop +endfacet +facet normal -0.723989 0.689811 -0.000159128 + outer loop + vertex -4.193745453649838 3.558440539055181 9.021971072896772 + vertex -3.757675615326284 4.016201435434015 9.392158036646613 + vertex -3.756191792225918 4.017589229875878 8.657180996278033 + endloop +endfacet +facet normal 0.637375 0.770554 -0.000449747 + outer loop + vertex 3.254896381159889 4.433469245174963 4.308344229599244 + vertex 3.742433202854696 4.030408629676492 4.672797414005285 + vertex 3.746583584735469 4.026550812120806 3.945041764355005 + endloop +endfacet +facet normal -0.801062 0.598581 0.00034291 + outer loop + vertex -4.207775377435437 3.54183940531584 12.70082873519072 + vertex -4.587900685810118 3.033342594753031 12.32887917960164 + vertex -4.590306397789944 3.029700839094301 13.06598312625897 + endloop +endfacet +facet normal 0.859154 0.511716 0.00048892 + outer loop + vertex 4.552133984799601 3.086758199864788 14.94713570478919 + vertex 4.880890562096091 2.535134576475439 14.58315638407505 + vertex 4.555605928058299 3.081631812569451 14.21147262318354 + endloop +endfacet +facet normal -0.229149 0.973391 -5.05093e-05 + outer loop + vertex -1.565338836542403 5.272543440011858 5.745524669891359 + vertex -0.9514647961173107 5.417076217088831 6.113238048924342 + vertex -0.9508328157075984 5.417187181238392 5.38454323787805 + endloop +endfacet +facet normal 0.632944 0.774198 0.000332138 + outer loop + vertex 3.227326122210681 4.453579021517028 15.30250162188575 + vertex 3.721708589489778 4.049553700708018 14.93898835038859 + vertex 3.230739827492712 4.451103252796138 14.56802161736779 + endloop +endfacet +facet normal 0.860929 0.508726 -0.000377669 + outer loop + vertex 4.566179940187244 3.065942066287558 10.52991912852155 + vertex 4.889422945144919 2.518639168974068 10.16456083156197 + vertex 4.563512583583712 3.069910894386531 9.795523476206014 + endloop +endfacet +facet normal 0.339173 0.940724 -8.41112e-05 + outer loop + vertex 1.564944612513594 5.272660463159435 5.390523919726905 + vertex 1.565967758461246 5.272356681737292 6.118716452020724 + vertex 2.159295580663456 5.058403166546462 5.758176769272027 + endloop +endfacet +facet normal 0.538998 0.842307 0.000260804 + outer loop + vertex 3.227326122210681 4.453579021517028 15.30250162188575 + vertex 2.693199767364561 4.795484856932349 14.93203417297265 + vertex 2.690311348957866 4.797105882265734 15.6661138397711 + endloop +endfacet +facet normal 0.539591 0.841927 0.000294539 + outer loop + vertex 3.230739827492712 4.451103252796138 14.56802161736779 + vertex 2.69645959363408 4.793652642807855 14.19739360155101 + vertex 2.693199767364561 4.795484856932349 14.93203417297265 + endloop +endfacet +facet normal 0.860501 0.509449 -0.000294224 + outer loop + vertex 4.562176563648654 3.071895994674128 12.00313638980624 + vertex 4.886513843818911 2.524278600742425 12.37504345209598 + vertex 4.888228129415757 2.52095730919596 11.63790476013536 + endloop +endfacet +facet normal 0.63384 0.773464 -0.000316261 + outer loop + vertex 3.725143434257081 4.046394246018468 14.20400374184834 + vertex 3.728098583680958 4.043671716442376 13.46825646244697 + vertex 3.233897126492125 4.448809883021073 13.83288720962454 + endloop +endfacet +facet normal 0.636558 0.771229 0.000213272 + outer loop + vertex 3.250073991176871 4.4370056402799 7.22730766149194 + vertex 3.739370883373951 4.033249979430375 6.863618889679024 + vertex 3.252261650712191 4.4354023667878 6.495472300639344 + endloop +endfacet +facet normal 0.44258 0.896729 0.000217947 + outer loop + vertex 2.147311820790399 5.063501944730922 7.953930933554343 + vertex 2.144762513208912 5.064582288988283 8.685740321988948 + vertex 2.714267863431721 4.783591743192745 8.323089629866299 + endloop +endfacet +facet normal -0.724545 0.689227 0.000319812 + outer loop + vertex -4.194572795966226 3.557465257643436 9.755144478608651 + vertex -4.197232969911694 3.554326292883965 10.49321336546519 + vertex -3.760953233344837 4.01313228994423 10.12705573614122 + endloop +endfacet +facet normal 0.555471 0.831321 -0.0188916 + outer loop + vertex 2.749999999999995 4.763139720814415 1.5 + vertex 3.056057912944187 4.572801114495492 2.123228765692188 + vertex 3.348187859547956 4.363443371601799 1.5 + endloop +endfacet +facet normal 0.795907 0.605419 -0.000286345 + outer loop + vertex 4.177038937288492 3.578036572811383 11.63127327229928 + vertex 4.562176563648654 3.071895994674128 12.00313638980624 + vertex 4.564207626536311 3.068877440020662 11.26642348942379 + endloop +endfacet +facet normal -0.860343 0.509716 -0.000337135 + outer loop + vertex -4.885748956934826 2.525758723593816 6.089672494525414 + vertex -4.56346141485871 3.069986956828276 6.457894800006025 + vertex -4.561073522989203 3.073533523143494 5.726248478629312 + endloop +endfacet +facet normal 0.796105 0.605158 0.000288927 + outer loop + vertex 4.177038937288492 3.578036572811383 11.63127327229928 + vertex 4.564207626536311 3.068877440020662 11.26642348942379 + vertex 4.179424357135561 3.57524992734522 10.89515204038594 + endloop +endfacet +facet normal -0.343558 0.939131 0.000242294 + outer loop + vertex -2.182188084779327 5.048569615509638 10.49727345085342 + vertex -2.185024418165879 5.047342696114349 11.23106540038434 + vertex -1.589254029909478 5.265384281172314 10.86784499063469 + endloop +endfacet +facet normal 0.539886 0.841738 -0.0003072 + outer loop + vertex 3.230739827492712 4.451103252796138 14.56802161736779 + vertex 3.233897126492125 4.448809883021073 13.83288720962454 + vertex 2.69645959363408 4.793652642807855 14.19739360155101 + endloop +endfacet +facet normal -0.227321 0.97382 0.000734637 + outer loop + vertex -1.549281538959688 5.277284028080988 3.565126421480367 + vertex -1.558235160707119 5.274647209428898 4.289890961578397 + vertex -0.9426077132371609 5.418624428666911 3.932243735809454 + endloop +endfacet +facet normal 0.951868 0.306496 0.00263473 + outer loop + vertex 5.126158116024035 1.99311388774473 19.3527997429786 + vertex 5.330076268660247 1.356571771144032 19.73017849541023 + vertex 5.321881441977558 1.388372398722644 18.99144459566703 + endloop +endfacet +facet normal 0.719046 0.694962 0.000316459 + outer loop + vertex 3.725143434257081 4.046394246018468 14.20400374184834 + vertex 4.169614102858932 3.586686246835636 13.83973113987994 + vertex 3.728098583680958 4.043671716442376 13.46825646244697 + endloop +endfacet +facet normal -0.545961 0.83781 -0.000353689 + outer loop + vertex -2.730331237033483 4.774441468494426 7.198626627347451 + vertex -3.263341203312671 4.427256960100894 7.561026034291711 + vertex -2.734226069823106 4.772212044649702 7.929762223762901 + endloop +endfacet +facet normal -0.00744768 0.999972 0.000304866 + outer loop + vertex -0.3598129782511795 5.488217800040557 15.28358645969896 + vertex 0.2761128175058328 5.493064874185357 14.9202532219283 + vertex -0.3559398938203805 5.488470350834296 14.5498265854421 + endloop +endfacet +facet normal 0.85931 0.511455 -3.13388e-05 + outer loop + vertex 4.880890562096091 2.535134576475439 14.58315638407505 + vertex 4.881074385750622 2.534780629713188 13.84712727035636 + vertex 4.555605928058299 3.081631812569451 14.21147262318354 + endloop +endfacet +facet normal -0.121013 0.992651 0.000262383 + outer loop + vertex -0.3483378758125438 5.488958072737885 13.08066832146781 + vertex -0.9789182018068283 5.412182476060031 12.71018137601641 + vertex -0.9821963228066395 5.411588526806627 13.44532190637029 + endloop +endfacet +facet normal -0.800624 0.599167 -0.000711027 + outer loop + vertex -4.197232969911694 3.554326292883965 10.49321336546519 + vertex -4.59137142082812 3.028086603121313 10.84686772092755 + vertex -4.202917943979592 3.547602113565494 11.22823847805601 + endloop +endfacet +facet normal -0.636003 0.771686 0.000361934 + outer loop + vertex -3.737953839354024 4.034563309065618 5.002338780429589 + vertex -3.248170387885879 4.438399388435125 4.641195007400434 + vertex -3.734579928635062 4.037686559979134 4.271956172220666 + endloop +endfacet +facet normal 0.542488 0.840064 0.000189887 + outer loop + vertex 2.712164933028665 4.784784360454462 9.054788706823091 + vertex 3.244296841629572 4.441231586327422 8.69153930796214 + vertex 2.714267863431721 4.783591743192745 8.323089629866299 + endloop +endfacet +facet normal -0.195055 0.980607 -0.0190507 + outer loop + vertex -1.423504748063876 5.312592044589873 1.5 + vertex -1.086182840163288 5.391679407915015 2.117161111770399 + vertex -0.7178940572102954 5.452946737555956 1.5 + endloop +endfacet +facet normal -0.347075 0.937837 -0.000295494 + outer loop + vertex -1.610314611093768 5.258981541448679 16.01007290764218 + vertex -1.606721372021948 5.260080458765618 15.27734419918179 + vertex -2.202980720697034 5.039531321882738 15.64075789320135 + endloop +endfacet +facet normal 0.86067 0.509164 0.000286591 + outer loop + vertex 4.562176563648654 3.071895994674128 12.00313638980624 + vertex 4.888228129415757 2.52095730919596 11.63790476013536 + vertex 4.564207626536311 3.068877440020662 11.26642348942379 + endloop +endfacet +facet normal 0.720017 0.693956 0.000301243 + outer loop + vertex 3.730881864473303 4.041103873119845 12.73213419285154 + vertex 4.174610919538479 3.580869122220205 12.36750866252201 + vertex 3.733692718472325 4.03850698699739 11.99605576310998 + endloop +endfacet +facet normal -0.121336 0.992611 -0.000306619 + outer loop + vertex -0.3522236674785046 5.488710093279476 13.81558093640346 + vertex -0.3483378758125438 5.488958072737885 13.08066832146781 + vertex -0.9821963228066395 5.411588526806627 13.44532190637029 + endloop +endfacet +facet normal -0.798135 0.602478 -0.00044008 + outer loop + vertex -4.187648423468353 3.565613647245452 7.553553388071339 + vertex -4.575185892217977 3.052486535867045 7.915867117626163 + vertex -4.191236072447158 3.561395819761926 8.285876008499198 + endloop +endfacet +facet normal -0.552833 0.833292 -0.000272974 + outer loop + vertex -2.773056990794739 4.749753143670145 16.73580144231683 + vertex -2.77006097467527 4.751501046677892 16.00392148952702 + vertex -3.299526998621698 4.400354711312088 16.36685317911597 + endloop +endfacet +facet normal -0.231471 0.972842 -0.000285762 + outer loop + vertex -0.9607923148651225 5.415429634636214 9.036838586275445 + vertex -1.579382700414764 5.268353659885654 9.40001846000073 + vertex -0.9643705449208908 5.414793574282309 9.769856747733114 + endloop +endfacet +facet normal -0.865076 0.501641 -0.000248589 + outer loop + vertex -4.590306397789944 3.029700839094301 13.06598312625897 + vertex -4.908877155372405 2.480509035150433 13.43011541263371 + vertex -4.592056601583848 3.027047434027125 13.80214175608399 + endloop +endfacet +facet normal 0.958073 0.286453 0.00647241 + outer loop + vertex 5.141986732089285 1.951915071671345 12.03190553294616 + vertex 5.362589343990837 1.221734638829532 11.69335974927695 + vertex 5.168137311619096 1.88158356929756 11.27368581568632 + endloop +endfacet +facet normal -0.91718 0.398472 0.000450069 + outer loop + vertex -4.909352147307213 2.479568812057867 12.69452805020423 + vertex -5.161756596738037 1.899017860903723 12.32305457307666 + vertex -5.1637250567763 1.89365877021722 13.05630710917101 + endloop +endfacet +facet normal -0.45285 0.891587 4.98763e-06 + outer loop + vertex -2.202922862387096 5.03955661366873 16.37282938396807 + vertex -2.202980720697034 5.039531321882738 15.64075789320135 + vertex -2.77006097467527 4.751501046677892 16.00392148952702 + endloop +endfacet +facet normal 0.912784 0.408443 3.15535e-05 + outer loop + vertex 4.880890562096091 2.535134576475439 14.58315638407505 + vertex 5.14260411224237 1.950287913295847 14.21826185107064 + vertex 4.881074385750622 2.534780629713188 13.84712727035636 + endloop +endfacet +facet normal -0.23645 0.971644 -0.000269548 + outer loop + vertex -0.9915929150321402 5.409874628016629 15.64704678609304 + vertex -0.9882235632298347 5.410491122724196 14.91371131694453 + vertex -1.606721372021948 5.260080458765618 15.27734419918179 + endloop +endfacet +facet normal -0.231886 0.972743 0.000443818 + outer loop + vertex -0.9643705449208908 5.414793574282309 9.769856747733114 + vertex -1.579382700414764 5.268353659885654 9.40001846000073 + vertex -1.584780954026627 5.266732319736257 10.13313319191941 + endloop +endfacet +facet normal 0.861625 0.507545 0.000284532 + outer loop + vertex 4.564207626536311 3.068877440020662 11.26642348942379 + vertex 4.8960469875539 2.505738193759351 10.90676180332706 + vertex 4.566179940187244 3.065942066287558 10.52991912852155 + endloop +endfacet +facet normal 0.791785 0.6108 0.000353342 + outer loop + vertex 4.152044140509771 3.607011152638494 17.50983287464635 + vertex 4.541597390389772 3.102240020308682 17.14747746590255 + vertex 4.154980888345557 3.603627868895894 16.77750589539072 + endloop +endfacet +facet normal -0.121953 0.992536 -0.000293162 + outer loop + vertex -0.3559398938203805 5.488470350834296 14.5498265854421 + vertex -0.3522236674785046 5.488710093279476 13.81558093640346 + vertex -0.9851812348334736 5.411045918723292 14.17976752853854 + endloop +endfacet +facet normal 0.91323 0.407445 0.000287996 + outer loop + vertex 4.886513843818911 2.524278600742425 12.37504345209598 + vertex 5.141986732089285 1.951915071671345 12.03190553294616 + vertex 4.888228129415757 2.52095730919596 11.63790476013536 + endloop +endfacet +facet normal 0.442371 0.896832 -0.000190383 + outer loop + vertex 2.144762513208912 5.064582288988283 8.685740321988948 + vertex 2.712164933028665 4.784784360454462 9.054788706823091 + vertex 2.714267863431721 4.783591743192745 8.323089629866299 + endloop +endfacet +facet normal -0.3468 0.937939 0.000216537 + outer loop + vertex -1.606721372021948 5.260080458765618 15.27734419918179 + vertex -2.200460361911674 5.040632321014452 14.90827765617079 + vertex -2.202980720697034 5.039531321882738 15.64075789320135 + endloop +endfacet +facet normal -0.121652 0.992573 0.000238899 + outer loop + vertex -0.3522236674785046 5.488710093279476 13.81558093640346 + vertex -0.9821963228066395 5.411588526806627 13.44532190637029 + vertex -0.9851812348334736 5.411045918723292 14.17976752853854 + endloop +endfacet +facet normal 0.953886 0.300137 0.00437883 + outer loop + vertex 5.339962456935814 1.317118429950786 3.589736816026074 + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + vertex 5.141289816700485 1.953749989300548 3.23223805190901 + endloop +endfacet +facet normal 0.107376 0.994218 0.000226531 + outer loop + vertex 0.9045204571974303 5.425112233171896 15.29074663247052 + vertex 0.2761128175058328 5.493064874185357 14.9202532219283 + vertex 0.2732321874398657 5.493208913899673 15.65350056583433 + endloop +endfacet +facet normal -0.865028 0.501724 -8.27241e-05 + outer loop + vertex -4.590306397789944 3.029700839094301 13.06598312625897 + vertex -4.909352147307213 2.479568812057867 12.69452805020423 + vertex -4.908877155372405 2.480509035150433 13.43011541263371 + endloop +endfacet +facet normal -0.451465 0.892289 -0.000233299 + outer loop + vertex -2.19179224282514 5.044407474053969 18.56624767881553 + vertex -2.764583419145227 4.754690160103736 18.92372716072775 + vertex -2.194459938233373 5.043247523123249 19.29217846862717 + endloop +endfacet +facet normal -0.917017 0.398848 -0.000556391 + outer loop + vertex -4.910007904730391 2.478270036837204 14.16861485224099 + vertex -5.159487311214056 1.905174712571303 14.52663788554383 + vertex -4.913268007066149 2.471800455283604 14.90405506725276 + endloop +endfacet +facet normal -0.799024 0.601299 -0.000101792 + outer loop + vertex -4.193745453649838 3.558440539055181 9.021971072896772 + vertex -4.580135555157919 3.045054727977522 9.385342259607349 + vertex -4.194572795966226 3.557465257643436 9.755144478608651 + endloop +endfacet +facet normal -0.231135 0.972922 0.000318396 + outer loop + vertex -1.57550572332861 5.269514371909312 8.667668761794854 + vertex -1.579382700414764 5.268353659885654 9.40001846000073 + vertex -0.9607923148651225 5.415429634636214 9.036838586275445 + endloop +endfacet +facet normal 0.630674 0.776047 -0.000667601 + outer loop + vertex 3.709674271489997 4.060580845081792 19.33662734180532 + vertex 3.21270192299947 4.464140046409332 18.96695942887282 + vertex 3.219421791503083 4.459296281746155 19.68454339005858 + endloop +endfacet +facet normal 0.437298 0.899317 0.000402433 + outer loop + vertex 2.113350427269168 5.077770177111329 16.76176094383523 + vertex 2.686581987151288 4.7991954769851 16.39939846347043 + vertex 2.11806254387618 5.07580644432279 16.02976623207586 + endloop +endfacet +facet normal 0.796178 0.605062 5.97231e-05 + outer loop + vertex 4.1799857098378 3.574593608447229 5.768349711835589 + vertex 4.563216686645465 3.070350708098406 5.405036775612206 + vertex 4.180478332843585 3.574017474583094 5.038000552588223 + endloop +endfacet +facet normal 0.909937 0.414747 0.000291944 + outer loop + vertex 4.864019593170021 2.56735533132018 18.98242990710356 + vertex 5.127797107729225 1.988893366162147 18.62086574692994 + vertex 4.865749673179342 2.564074904903351 18.25038236144107 + endloop +endfacet +facet normal -0.957952 0.286928 3.0013e-05 + outer loop + vertex -5.168219743892152 1.88135713750562 18.18109287916363 + vertex -5.351430836992411 1.269719652870942 17.80587799198893 + vertex -5.35151881279618 1.26934880796752 18.54320227256124 + endloop +endfacet +facet normal 0.63326 0.773939 -0.000367454 + outer loop + vertex 3.230739827492712 4.451103252796138 14.56802161736779 + vertex 3.721708589489778 4.049553700708018 14.93898835038859 + vertex 3.725143434257081 4.046394246018468 14.20400374184834 + endloop +endfacet +facet normal -0.724094 0.689701 0.000100358 + outer loop + vertex -4.193745453649838 3.558440539055181 9.021971072896772 + vertex -4.194572795966226 3.557465257643436 9.755144478608651 + vertex -3.757675615326284 4.016201435434015 9.392158036646613 + endloop +endfacet +facet normal 0.953629 0.300891 -0.00751606 + outer loop + vertex 5.132070992332079 1.977839055551192 17.15416962617216 + vertex 5.325937770498046 1.372729712937804 17.5273430786013 + vertex 5.347696406214424 1.285357205978686 16.79025874800341 + endloop +endfacet +facet normal -0.957576 0.288182 -0.000464447 + outer loop + vertex -5.161756596738037 1.899017860903723 12.32305457307666 + vertex -5.351863082258487 1.267896505539267 12.6753219338857 + vertex -5.1637250567763 1.89365877021722 13.05630710917101 + endloop +endfacet +facet normal -0.116016 0.993247 0.000215769 + outer loop + vertex -0.9508328157075984 5.417187181238392 5.38454323787805 + vertex -0.3218670607994322 5.490573885776635 5.751440049854351 + vertex -0.3245943420598152 5.490413328074924 5.02410660243334 + endloop +endfacet +facet normal -0.34188 0.939743 0.000345664 + outer loop + vertex -2.177046150527109 5.050789053056473 9.763260881829368 + vertex -1.579382700414764 5.268353659885654 9.40001846000073 + vertex -2.173007520207733 5.052527913541956 9.030310479700152 + endloop +endfacet +facet normal 0.53929 0.84212 -0.000332097 + outer loop + vertex 3.227326122210681 4.453579021517028 15.30250162188575 + vertex 3.230739827492712 4.451103252796138 14.56802161736779 + vertex 2.693199767364561 4.795484856932349 14.93203417297265 + endloop +endfacet +facet normal 0.916367 0.400338 0.00146641 + outer loop + vertex 5.168137311619096 1.88158356929756 11.27368581568632 + vertex 4.8960469875539 2.505738193759351 10.90676180332706 + vertex 4.888228129415757 2.52095730919596 11.63790476013536 + endloop +endfacet +facet normal -0.00151886 0.999999 0.000376535 + outer loop + vertex -0.3245943420598152 5.490413328074924 5.02410660243334 + vertex 0.3103090457671292 5.491239231368006 5.391732547173166 + vertex 0.3055515148459051 5.491506011266433 4.66402990365856 + endloop +endfacet +facet normal -0.917263 0.398281 8.32251e-05 + outer loop + vertex -4.909352147307213 2.479568812057867 12.69452805020423 + vertex -5.1637250567763 1.89365877021722 13.05630710917101 + vertex -4.908877155372405 2.480509035150433 13.43011541263371 + endloop +endfacet +facet normal -0.91303 0.407892 0.000373841 + outer loop + vertex -4.883662415257973 2.529790784590034 5.356721595552531 + vertex -5.142036710810895 1.951783406188575 4.984386788694756 + vertex -5.143721801250042 1.947338191312701 5.718996921926565 + endloop +endfacet +facet normal 0.719535 0.694456 0.000298065 + outer loop + vertex 3.728098583680958 4.043671716442376 13.46825646244697 + vertex 4.172111394146111 3.583781036117609 13.10364066277435 + vertex 3.730881864473303 4.041103873119845 12.73213419285154 + endloop +endfacet +facet normal 0.720258 0.693706 -0.000293596 + outer loop + vertex 3.733692718472325 4.03850698699739 11.99605576310998 + vertex 4.174610919538479 3.580869122220205 12.36750866252201 + vertex 4.177038937288492 3.578036572811383 11.63127327229928 + endloop +endfacet +facet normal 0.53837 0.842709 0.000336644 + outer loop + vertex 2.686581987151288 4.7991954769851 16.39939846347043 + vertex 3.223761391834297 4.456160060917762 16.03651162530636 + vertex 2.690311348957866 4.797105882265734 15.6661138397711 + endloop +endfacet +facet normal -0.44221 0.896713 -0.0188916 + outer loop + vertex -2.750000000000011 4.763139720814406 1.5 + vertex -2.43213297513447 4.933024345294026 2.123228765692299 + vertex -2.104758878008006 5.081337428812073 1.5 + endloop +endfacet +facet normal 0.44221 0.896713 0.0188916 + outer loop + vertex 2.75000000000001 4.763139720814406 21.5 + vertex 2.432132975136189 4.933024345293179 20.87677123430906 + vertex 2.104758878008006 5.081337428812073 21.5 + endloop +endfacet +facet normal -0.0653914 0.997681 -0.0189005 + outer loop + vertex -0.7178940572102954 5.452946737555956 1.5 + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + vertex -1.13279746910902e-14 5.5 1.5 + endloop +endfacet +facet normal -0.346549 0.938032 -0.000243567 + outer loop + vertex -1.606721372021948 5.260080458765618 15.27734419918179 + vertex -1.603762649021274 5.260983307862159 14.5447323978708 + vertex -2.200460361911674 5.040632321014452 14.90827765617079 + endloop +endfacet +facet normal 0.538706 0.842494 -0.000346271 + outer loop + vertex 3.223761391834297 4.456160060917762 16.03651162530636 + vertex 3.227326122210681 4.453579021517028 15.30250162188575 + vertex 2.690311348957866 4.797105882265734 15.6661138397711 + endloop +endfacet +facet normal 0.0653909 0.997673 0.019319 + outer loop + vertex 0.7178940572102935 5.452946737555956 21.5 + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + vertex 1.078026285860484e-14 5.5 21.5 + endloop +endfacet +facet normal -0.235889 0.97178 -0.000243224 + outer loop + vertex -0.9851812348334736 5.411045918723292 14.17976752853854 + vertex -1.603762649021274 5.260983307862159 14.5447323978708 + vertex -0.9882235632298347 5.410491122724196 14.91371131694453 + endloop +endfacet +facet normal -0.957807 0.28741 -0.000370867 + outer loop + vertex -5.164834411129698 1.890630980813162 15.27016150908249 + vertex -5.351961835250633 1.267479591165347 15.6259277296983 + vertex -5.166420226055012 1.886293203033316 16.0040728052201 + endloop +endfacet +facet normal 0.632608 0.774472 -0.000428194 + outer loop + vertex 3.227326122210681 4.453579021517028 15.30250162188575 + vertex 3.717701953384411 4.053232313327443 15.67311796467917 + vertex 3.721708589489778 4.049553700708018 14.93898835038859 + endloop +endfacet +facet normal 0.195055 0.98061 -0.0189005 + outer loop + vertex 0.717894057210274 5.452946737555958 1.5 + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + vertex 1.423504748063855 5.312592044589878 1.5 + endloop +endfacet +facet normal 0.10712 0.994246 -0.000223773 + outer loop + vertex 0.9017122864072585 5.425579688157036 16.02342662257618 + vertex 0.9045204571974303 5.425112233171896 15.29074663247052 + vertex 0.2732321874398657 5.493208913899673 15.65350056583433 + endloop +endfacet +facet normal -0.195055 0.98061 0.0189005 + outer loop + vertex -0.7178940572102771 5.452946737555958 21.5 + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + vertex -1.423504748063857 5.312592044589877 21.5 + endloop +endfacet +facet normal -0.953893 0.300146 0.000370216 + outer loop + vertex -5.142036710810895 1.951783406188575 4.984386788694756 + vertex -5.332602887399606 1.346605526981597 4.611820020301286 + vertex -5.33375297905039 1.342042904854793 5.3475778539808 + endloop +endfacet +facet normal 0.321381 0.946758 -0.0190484 + outer loop + vertex 1.423504748063855 5.312592044589878 1.5 + vertex 1.772743246953266 5.20647494763795 2.117973314103827 + vertex 2.104758878007986 5.081337428812081 1.5 + endloop +endfacet +facet normal 0.719297 0.694702 -0.000301542 + outer loop + vertex 4.169614102858932 3.586686246835636 13.83973113987994 + vertex 4.172111394146111 3.583781036117609 13.10364066277435 + vertex 3.728098583680958 4.043671716442376 13.46825646244697 + endloop +endfacet +facet normal -0.44221 0.896713 0.0189005 + outer loop + vertex -2.104758878007986 5.081337428812081 21.5 + vertex -2.432587796204501 4.932800078429788 20.87706280989174 + vertex -2.749999999999996 4.763139720814415 21.5 + endloop +endfacet +facet normal 0.44221 0.896713 -0.0189005 + outer loop + vertex 2.104758878007986 5.081337428812081 1.5 + vertex 2.432587796204499 4.93280007842979 2.122937190108265 + vertex 2.749999999999995 4.763139720814415 1.5 + endloop +endfacet +facet normal 0.329796 0.944052 0.00028836 + outer loop + vertex 1.50976148259572 5.288725769565896 17.85447942085971 + vertex 2.110225258263429 5.079069733660589 17.49329836618297 + vertex 1.513274589194329 5.287721628234483 17.1239828427341 + endloop +endfacet +facet normal 0.861582 0.507618 -5.10889e-05 + outer loop + vertex 4.562735033130303 3.071066429995517 7.600486548182634 + vertex 4.897747251928272 2.502413206532659 7.241119007269643 + vertex 4.562386486476917 3.071584208191729 6.867102472469194 + endloop +endfacet +facet normal 0.913178 0.40756 -0.000996317 + outer loop + vertex 4.885815967138671 2.525629096928687 8.70404526328716 + vertex 5.140219477149498 1.956564265934789 9.09286486955698 + vertex 5.144868400325386 1.944306854211367 8.339749905384522 + endloop +endfacet +facet normal -0.723806 0.690004 0.000302746 + outer loop + vertex -4.191236072447158 3.561395819761926 8.285876008499198 + vertex -4.193745453649838 3.558440539055181 9.021971072896772 + vertex -3.756191792225918 4.017589229875878 8.657180996278033 + endloop +endfacet +facet normal 0.44311 0.896467 0.000352317 + outer loop + vertex 2.147311820790399 5.063501944730922 7.953930933554343 + vertex 2.716777995166491 4.782166593185472 7.590795854324413 + vertex 2.151434623773428 5.061751580197203 7.222461682940452 + endloop +endfacet +facet normal 0.861161 0.50833 -0.00137187 + outer loop + vertex 4.888228129415757 2.52095730919596 11.63790476013536 + vertex 4.8960469875539 2.505738193759351 10.90676180332706 + vertex 4.564207626536311 3.068877440020662 11.26642348942379 + endloop +endfacet +facet normal 0.861372 0.507973 0.00114199 + outer loop + vertex 4.566179940187244 3.065942066287558 10.52991912852155 + vertex 4.8960469875539 2.505738193759351 10.90676180332706 + vertex 4.889422945144919 2.518639168974068 10.16456083156197 + endloop +endfacet +facet normal 0.111189 0.993799 -0.000136696 + outer loop + vertex 0.9247966696185814 5.421692643433634 11.61532331063718 + vertex 0.9265167379228637 5.421398964690643 10.87934931410019 + vertex 0.2953835508501084 5.492062322833489 11.24521763091109 + endloop +endfacet +facet normal 0.721021 0.692914 -2.46501e-05 + outer loop + vertex 4.178568741894685 3.576249889096212 7.231759319986232 + vertex 4.178772325094146 3.576012004318116 6.499676398532498 + vertex 3.739370883373951 4.033249979430375 6.863618889679024 + endloop +endfacet +facet normal 0.437686 0.899128 -0.000336192 + outer loop + vertex 2.686581987151288 4.7991954769851 16.39939846347043 + vertex 2.690311348957866 4.797105882265734 15.6661138397711 + vertex 2.11806254387618 5.07580644432279 16.02976623207586 + endloop +endfacet +facet normal 0.720956 0.69298 -0.000769443 + outer loop + vertex 3.741330192435993 4.031432548259596 9.789771699872459 + vertex 4.179409421351509 3.575267387024115 9.429207426964693 + vertex 3.734233119467835 4.03800730676277 9.061319687521875 + endloop +endfacet +facet normal -0.123204 0.992381 0.000603328 + outer loop + vertex -0.3652328073833823 5.487859782867165 18.21031711504795 + vertex -0.9839543072603515 5.411269159931319 17.84228907674125 + vertex -0.9915550309688018 5.409881571768504 18.57253006430009 + endloop +endfacet +facet normal 0.719778 0.694204 -0.000302062 + outer loop + vertex 3.730881864473303 4.041103873119845 12.73213419285154 + vertex 4.172111394146111 3.583781036117609 13.10364066277435 + vertex 4.174610919538479 3.580869122220205 12.36750866252201 + endloop +endfacet +facet normal 0.954989 0.296639 0.0010671 + outer loop + vertex 5.140219477149498 1.956564265934789 9.09286486955698 + vertex 5.342620843612703 1.306293428520213 8.722112600728778 + vertex 5.144868400325386 1.944306854211367 8.339749905384522 + endloop +endfacet +facet normal 0.954298 0.298857 0.000151159 + outer loop + vertex 5.335404501278465 1.335462020327605 5.814529487406688 + vertex 5.334915080859414 1.337415821657123 5.04147674123994 + vertex 5.144454421942084 1.945401938047904 5.408865316838218 + endloop +endfacet +facet normal 0.72095 0.692987 0.000149746 + outer loop + vertex 3.737977261791252 4.03454160845214 7.595859945622948 + vertex 4.178568741894685 3.576249889096212 7.231759319986232 + vertex 3.739370883373951 4.033249979430375 6.863618889679024 + endloop +endfacet +facet normal 0.795701 0.605689 0.000293837 + outer loop + vertex 4.177038937288492 3.578036572811383 11.63127327229928 + vertex 4.174610919538479 3.580869122220205 12.36750866252201 + vertex 4.562176563648654 3.071895994674128 12.00313638980624 + endloop +endfacet +facet normal -0.55258 0.83346 0.000258731 + outer loop + vertex -2.77006097467527 4.751501046677892 16.00392148952702 + vertex -3.296898100005449 4.402324717485122 15.63542294950113 + vertex -3.299526998621698 4.400354711312088 16.36685317911597 + endloop +endfacet +facet normal -0.800745 0.599005 1.36991e-05 + outer loop + vertex -4.20549953808906 3.544541385727172 11.96453594073424 + vertex -4.587803823660058 3.033489092713233 11.58495038277631 + vertex -4.587900685810118 3.033342594753031 12.32887917960164 + endloop +endfacet +facet normal 0.721103 0.692828 0.000181807 + outer loop + vertex 3.739370883373951 4.033249979430375 6.863618889679024 + vertex 4.178772325094146 3.576012004318116 6.499676398532498 + vertex 3.741065371887834 4.031678296102225 6.132109706259876 + endloop +endfacet +facet normal 0.330883 0.943672 -0.000401588 + outer loop + vertex 2.113350427269168 5.077770177111329 16.76176094383523 + vertex 2.11806254387618 5.07580644432279 16.02976623207586 + vertex 1.517935936642233 5.286385390060969 16.39270319811148 + endloop +endfacet +facet normal 0.631931 0.775025 -0.000392907 + outer loop + vertex 3.71401833700239 4.056607917017615 16.40709822925858 + vertex 3.717701953384411 4.053232313327443 15.67311796467917 + vertex 3.223761391834297 4.456160060917762 16.03651162530636 + endloop +endfacet +facet normal -0.723551 0.690271 -0.00032387 + outer loop + vertex -3.753172034506454 4.020410386937966 7.923594727606659 + vertex -4.191236072447158 3.561395819761926 8.285876008499198 + vertex -3.756191792225918 4.017589229875878 8.657180996278033 + endloop +endfacet +facet normal 0.860348 0.509707 -0.00013925 + outer loop + vertex 4.561739448136046 3.072545070022481 8.334534675596213 + vertex 4.885815967138671 2.525629096928687 8.70404526328716 + vertex 4.886627134838323 2.524059279228959 7.969673719830597 + endloop +endfacet +facet normal 0.952241 0.305347 0.000429803 + outer loop + vertex 5.132070992332079 1.977839055551192 17.15416962617216 + vertex 5.130113828406416 1.982910009958412 17.88774139512327 + vertex 5.325937770498046 1.372729712937804 17.5273430786013 + endloop +endfacet +facet normal 0.916687 0.3996 0.00211914 + outer loop + vertex 5.171106296982572 1.873408568707635 7.60218979976907 + vertex 4.897747251928272 2.502413206532659 7.241119007269643 + vertex 4.886627134838323 2.524059279228959 7.969673719830597 + endloop +endfacet +facet normal -0.800627 0.599163 -0.000316477 + outer loop + vertex -4.202917943979592 3.547602113565494 11.22823847805601 + vertex -4.587803823660058 3.033489092713233 11.58495038277631 + vertex -4.20549953808906 3.544541385727172 11.96453594073424 + endloop +endfacet +facet normal -0.864837 0.502053 5.66654e-05 + outer loop + vertex -4.909352147307213 2.479568812057867 12.69452805020423 + vertex -4.587900685810118 3.033342594753031 12.32887917960164 + vertex -4.909025451291431 2.480215538733068 11.95064759781068 + endloop +endfacet +facet normal 0.112734 0.993625 -0.000224898 + outer loop + vertex 0.3046216084273119 5.491557672981243 8.310771337383457 + vertex 0.9319764162669196 5.420463076114648 8.678901954799057 + vertex 0.9347925745220471 5.419978121968616 7.947965626364867 + endloop +endfacet +facet normal 0.442813 0.896614 -0.000227083 + outer loop + vertex 2.147311820790399 5.063501944730922 7.953930933554343 + vertex 2.714267863431721 4.783591743192745 8.323089629866299 + vertex 2.716777995166491 4.782166593185472 7.590795854324413 + endloop +endfacet +facet normal 0.795926 0.605394 0.0001817 + outer loop + vertex 4.177069149615913 3.578001302309292 7.965218399827975 + vertex 4.562735033130303 3.071066429995517 7.600486548182634 + vertex 4.178568741894685 3.576249889096212 7.231759319986232 + endloop +endfacet +facet normal 0.795814 0.605541 -0.000140421 + outer loop + vertex 4.177069149615913 3.578001302309292 7.965218399827975 + vertex 4.561739448136046 3.072545070022481 8.334534675596213 + vertex 4.562735033130303 3.071066429995517 7.600486548182634 + endloop +endfacet +facet normal 0.720819 0.693123 -0.000181347 + outer loop + vertex 3.737977261791252 4.03454160845214 7.595859945622948 + vertex 4.177069149615913 3.578001302309292 7.965218399827975 + vertex 4.178568741894685 3.576249889096212 7.231759319986232 + endloop +endfacet +facet normal -0.321382 0.946761 -0.0189005 + outer loop + vertex -2.104758878008006 5.081337428812073 1.5 + vertex -1.767917059167402 5.208115712223076 2.122937190108266 + vertex -1.423504748063876 5.312592044589873 1.5 + endloop +endfacet +facet normal 0.321386 0.946774 0.0181632 + outer loop + vertex 2.104758878008006 5.081337428812073 21.5 + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + vertex 1.423504748063873 5.312592044589874 21.5 + endloop +endfacet +facet normal -0.864952 0.501855 -0.000343493 + outer loop + vertex -4.590306397789944 3.029700839094301 13.06598312625897 + vertex -4.587900685810118 3.033342594753031 12.32887917960164 + vertex -4.909352147307213 2.479568812057867 12.69452805020423 + endloop +endfacet +facet normal -0.636784 0.771042 -0.000338642 + outer loop + vertex -3.251307770456957 4.436101642407015 5.370668124934424 + vertex -3.740045600494774 4.032624319995564 5.731546243898735 + vertex -3.254775613716721 4.433557905830818 6.09986861334725 + endloop +endfacet +facet normal 0.860429 0.50957 0.000140537 + outer loop + vertex 4.561739448136046 3.072545070022481 8.334534675596213 + vertex 4.886627134838323 2.524059279228959 7.969673719830597 + vertex 4.562735033130303 3.071066429995517 7.600486548182634 + endloop +endfacet +facet normal 0.716725 0.697355 -0.000434779 + outer loop + vertex 4.154980888345557 3.603627868895894 16.77750589539072 + vertex 4.158599706489312 3.599451136102142 16.04387387159694 + vertex 3.71401833700239 4.056607917017615 16.40709822925858 + endloop +endfacet +facet normal 0.337101 0.941468 -0.000352869 + outer loop + vertex 1.552549114769935 5.276323648737546 7.585291971265814 + vertex 2.147311820790399 5.063501944730922 7.953930933554343 + vertex 2.151434623773428 5.061751580197203 7.222461682940452 + endloop +endfacet +facet normal -0.720806 0.693137 -0.000224587 + outer loop + vertex -3.737953839354024 4.034563309065618 5.002338780429589 + vertex -4.176799564904809 3.578315999826034 5.36342896831726 + vertex -3.740045600494774 4.032624319995564 5.731546243898735 + endloop +endfacet +facet normal 0.632257 0.774758 0.000346241 + outer loop + vertex 3.223761391834297 4.456160060917762 16.03651162530636 + vertex 3.717701953384411 4.053232313327443 15.67311796467917 + vertex 3.227326122210681 4.453579021517028 15.30250162188575 + endloop +endfacet +facet normal 0.913443 0.406967 0.000139019 + outer loop + vertex 4.885815967138671 2.525629096928687 8.70404526328716 + vertex 5.144868400325386 1.944306854211367 8.339749905384522 + vertex 4.886627134838323 2.524059279228959 7.969673719830597 + endloop +endfacet +facet normal 0.953857 0.300184 0.00675468 + outer loop + vertex 5.347696406214424 1.285357205978686 16.79025874800341 + vertex 5.328246086204495 1.363742514130318 16.05340787814411 + vertex 5.133866670985064 1.973173333630053 16.41890538970767 + endloop +endfacet +facet normal -0.800693 0.599074 -0.000514769 + outer loop + vertex -4.59137142082812 3.028086603121313 10.84686772092755 + vertex -4.587803823660058 3.033489092713233 11.58495038277631 + vertex -4.202917943979592 3.547602113565494 11.22823847805601 + endloop +endfacet +facet normal -0.639367 0.768901 0.000325057 + outer loop + vertex -3.753172034506454 4.020410386937966 7.923594727606659 + vertex -3.756191792225918 4.017589229875878 8.657180996278033 + vertex -3.266622743135714 4.42483625166271 8.292931250592922 + endloop +endfacet +facet normal -0.345867 0.938283 0.00022825 + outer loop + vertex -1.605220724567375 5.260538606019291 18.93286370157931 + vertex -2.19179224282514 5.044407474053969 18.56624767881553 + vertex -2.194459938233373 5.043247523123249 19.29217846862717 + endloop +endfacet +facet normal -0.45272 0.891653 0.000259501 + outer loop + vertex -2.202980720697034 5.039531321882738 15.64075789320135 + vertex -2.767215262778732 4.753158916914565 15.27200435617937 + vertex -2.77006097467527 4.751501046677892 16.00392148952702 + endloop +endfacet +facet normal 0.332344 0.943158 0.000195033 + outer loop + vertex 1.526772267661226 5.283840122742228 14.19155595219776 + vertex 1.524385328890073 5.284529247630738 14.92646702562929 + vertex 2.124130725649839 5.073270016503192 14.56145281446745 + endloop +endfacet +facet normal -0.728775 0.684753 0.000290752 + outer loop + vertex -3.784781376700859 3.990667855206488 16.72949380097899 + vertex -4.217254729821125 3.530547060131242 16.36191638614252 + vertex -4.219621040588515 3.527718564996746 17.09213177742202 + endloop +endfacet +facet normal -0.860535 0.509391 0.0003112 + outer loop + vertex -4.885748956934826 2.525758723593816 6.089672494525414 + vertex -4.887553899212895 2.522264237206092 6.818608522622353 + vertex -4.56346141485871 3.069986956828276 6.457894800006025 + endloop +endfacet +facet normal 0.630231 0.776408 0.000322435 + outer loop + vertex 3.709674271489997 4.060580845081792 19.33662734180532 + vertex 3.706682292000083 4.063312243253404 18.60767167829646 + vertex 3.21270192299947 4.464140046409332 18.96695942887282 + endloop +endfacet +facet normal 0.112483 0.993654 0.000208779 + outer loop + vertex 0.3046216084273119 5.491557672981243 8.310771337383457 + vertex 0.3019705202645296 5.491704089341592 9.042234105602269 + vertex 0.9319764162669196 5.420463076114648 8.678901954799057 + endloop +endfacet +facet normal -0.115921 0.993258 5.07154e-05 + outer loop + vertex -0.9514647961173107 5.417076217088831 6.113238048924342 + vertex -0.3218670607994322 5.490573885776635 5.751440049854351 + vertex -0.9508328157075984 5.417187181238392 5.38454323787805 + endloop +endfacet +facet normal -0.341167 0.940003 0.000331262 + outer loop + vertex -2.169140817674367 5.054189164752243 8.298592900015723 + vertex -2.173007520207733 5.052527913541956 9.030310479700152 + vertex -1.57550572332861 5.269514371909312 8.667668761794854 + endloop +endfacet +facet normal 0.79528 0.606242 0.000302255 + outer loop + vertex 4.174610919538479 3.580869122220205 12.36750866252201 + vertex 4.172111394146111 3.583781036117609 13.10364066277435 + vertex 4.560022727424994 3.075092311682288 12.74020235260279 + endloop +endfacet +facet normal -0.639077 0.769143 -0.000321471 + outer loop + vertex -3.263341203312671 4.427256960100894 7.561026034291711 + vertex -3.753172034506454 4.020410386937966 7.923594727606659 + vertex -3.266622743135714 4.42483625166271 8.292931250592922 + endloop +endfacet +facet normal 0.499944 0.865851 0.0189227 + outer loop + vertex 2.432587796204499 4.93280007842979 2.122937190108265 + vertex 3.056057912944187 4.572801114495492 2.123228765692188 + vertex 2.749999999999995 4.763139720814415 1.5 + endloop +endfacet +facet normal -0.452473 0.891778 -0.000216452 + outer loop + vertex -2.200460361911674 5.040632321014452 14.90827765617079 + vertex -2.767215262778732 4.753158916914565 15.27200435617937 + vertex -2.202980720697034 5.039531321882738 15.64075789320135 + endloop +endfacet +facet normal -0.795345 0.606156 -0.000282499 + outer loop + vertex -4.174460453283732 3.581044529738519 4.632501134632069 + vertex -4.558730071149369 3.077008309770787 4.994878305694187 + vertex -4.176799564904809 3.578315999826034 5.36342896831726 + endloop +endfacet +facet normal 0.856745 0.515741 0.000341993 + outer loop + vertex 4.539148916185716 3.105821488220152 17.8802646915997 + vertex 4.868094338385164 2.559620579809108 17.51729407791064 + vertex 4.541597390389772 3.102240020308682 17.14747746590255 + endloop +endfacet +facet normal -0.555469 0.831319 -0.0190455 + outer loop + vertex -3.348187859547972 4.363443371601787 1.5 + vertex -3.049579275765538 4.577124232618265 2.117940666612885 + vertex -2.750000000000011 4.763139720814406 1.5 + endloop +endfacet +facet normal 0.555471 0.831321 0.0189005 + outer loop + vertex 3.348187859547973 4.363443371601787 21.5 + vertex 3.05563628160782 4.573082867663993 20.87706280989174 + vertex 2.75000000000001 4.763139720814406 21.5 + endloop +endfacet +facet normal -0.722816 0.69104 -0.000638484 + outer loop + vertex -3.753172034506454 4.020410386937966 7.923594727606659 + vertex -3.747237355031224 4.025942399620068 7.192426533269128 + vertex -4.187648423468353 3.565613647245452 7.553553388071339 + endloop +endfacet +facet normal -0.545565 0.838068 0.000476721 + outer loop + vertex -2.730331237033483 4.774441468494426 7.198626627347451 + vertex -3.258463897029156 4.430847890839582 6.829869678627511 + vertex -3.263341203312671 4.427256960100894 7.561026034291711 + endloop +endfacet +facet normal 0.542741 0.8399 -0.000325586 + outer loop + vertex 3.244296841629572 4.441231586327422 8.69153930796214 + vertex 3.247641787598908 4.438786187623974 7.959160003535738 + vertex 2.714267863431721 4.783591743192745 8.323089629866299 + endloop +endfacet +facet normal 0.913466 0.406915 0.000113885 + outer loop + vertex 4.886861798041292 2.523604914966807 4.311007271835738 + vertex 5.144340037657432 1.945704390948104 3.946742345627829 + vertex 4.887524974198084 2.522320286282061 3.581719537648792 + endloop +endfacet +facet normal -0.545174 0.838323 -0.000319893 + outer loop + vertex -2.7268006282093 4.776458765026383 6.4682204653972 + vertex -3.258463897029156 4.430847890839582 6.829869678627511 + vertex -2.730331237033483 4.774441468494426 7.198626627347451 + endloop +endfacet +facet normal -0.00117557 0.999999 -0.00021634 + outer loop + vertex -0.3245943420598152 5.490413328074924 5.02410660243334 + vertex -0.3218670607994322 5.490573885776635 5.751440049854351 + vertex 0.3103090457671292 5.491239231368006 5.391732547173166 + endloop +endfacet +facet normal 0.43578 0.900053 0.000601229 + outer loop + vertex 2.678916879983762 4.803478359495134 17.86350278336204 + vertex 2.110225258263429 5.079069733660589 17.49329836618297 + vertex 2.103215541586377 5.081976425135158 18.22266410324536 + endloop +endfacet +facet normal 0.910907 0.412612 -0.000393649 + outer loop + vertex 5.132070992332079 1.977839055551192 17.15416962617216 + vertex 5.133866670985064 1.973173333630053 16.41890538970767 + vertex 4.870184922199945 2.555640589671465 16.78318931728384 + endloop +endfacet +facet normal 0.225104 0.974335 0.000168303 + outer loop + vertex 0.9286399982135676 5.421035671688382 10.14267071378961 + vertex 0.9265167379228637 5.421398964690643 10.87934931410019 + vertex 1.544463263469689 5.278696167406546 10.51201805553148 + endloop +endfacet +facet normal 0.435521 0.900179 8.84602e-05 + outer loop + vertex 2.679885196006852 4.802938198251494 18.5928712167449 + vertex 2.678916879983762 4.803478359495134 17.86350278336204 + vertex 2.103215541586377 5.081976425135158 18.22266410324536 + endloop +endfacet +facet normal 0.717733 0.696318 0.000428008 + outer loop + vertex 3.721708589489778 4.049553700708018 14.93898835038859 + vertex 3.717701953384411 4.053232313327443 15.67311796467917 + vertex 4.162202925068889 3.595283967998631 15.30957942587535 + endloop +endfacet +facet normal -0.791902 0.610643 -0.00257713 + outer loop + vertex -4.142727898941744 3.617707223550536 2.454219851588245 + vertex -4.54305039848295 3.100111784572277 2.822942061993703 + vertex -4.16358638277272 3.593681737882416 3.170864763690249 + endloop +endfacet +facet normal 0.984182 0.176974 0.00807474 + outer loop + vertex 5.325937770498046 1.372729712937804 17.5273430786013 + vertex 5.466427009523622 0.6067748755103708 17.19140785290995 + vertex 5.347696406214424 1.285357205978686 16.79025874800341 + endloop +endfacet +facet normal 0.636397 0.771361 -0.000149426 + outer loop + vertex 3.250073991176871 4.4370056402799 7.22730766149194 + vertex 3.737977261791252 4.03454160845214 7.595859945622948 + vertex 3.739370883373951 4.033249979430375 6.863618889679024 + endloop +endfacet +facet normal -0.452068 0.891983 0.000518283 + outer loop + vertex -2.19179224282514 5.044407474053969 18.56624767881553 + vertex -2.197700735824538 5.041836121469666 17.83800695130835 + vertex -2.769452990619945 4.751855441061548 18.19930691019432 + endloop +endfacet +facet normal 0.543234 0.839581 -0.000237287 + outer loop + vertex 2.716777995166491 4.782166593185472 7.590795854324413 + vertex 3.247641787598908 4.438786187623974 7.959160003535738 + vertex 3.250073991176871 4.4370056402799 7.22730766149194 + endloop +endfacet +facet normal 0.95485 0.297087 0.000446749 + outer loop + vertex 5.132070992332079 1.977839055551192 17.15416962617216 + vertex 5.347696406214424 1.285357205978686 16.79025874800341 + vertex 5.133866670985064 1.973173333630053 16.41890538970767 + endloop +endfacet +facet normal 0.860516 0.509424 0.000103498 + outer loop + vertex 4.563216686645465 3.070350708098406 5.405036775612206 + vertex 4.886374773580517 2.524547795569723 5.041732577290214 + vertex 4.563949237429648 3.069261695940139 4.674562988651441 + endloop +endfacet +facet normal -0.751703 0.659226 0.0190659 + outer loop + vertex -3.889087296526007 3.889087296526016 21.5 + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + vertex -4.363443371601792 3.348187859547965 21.5 + endloop +endfacet +facet normal 0.751706 0.659228 -0.0189005 + outer loop + vertex 3.889087296526007 3.889087296526015 1.5 + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + vertex 4.36344337160179 3.348187859547969 1.5 + endloop +endfacet +facet normal -0.866258 0.499596 0.000309478 + outer loop + vertex -4.598174290006761 3.01774637746793 17.45478701894501 + vertex -4.913948422163426 2.470447510941608 17.08763577686084 + vertex -4.915709720630987 2.466941009123246 17.81820394054487 + endloop +endfacet +facet normal -0.546291 0.837595 0.000320939 + outer loop + vertex -3.263341203312671 4.427256960100894 7.561026034291711 + vertex -3.266622743135714 4.42483625166271 8.292931250592922 + vertex -2.734226069823106 4.772212044649702 7.929762223762901 + endloop +endfacet +facet normal -0.451575 0.892233 -0.000455884 + outer loop + vertex -2.19179224282514 5.044407474053969 18.56624767881553 + vertex -2.769452990619945 4.751855441061548 18.19930691019432 + vertex -2.764583419145227 4.754690160103736 18.92372716072775 + endloop +endfacet +facet normal -0.259812 0.965486 0.0182812 + outer loop + vertex -1.767917059167402 5.208115712223076 2.122937190108266 + vertex -1.086182840163288 5.391679407915015 2.117161111770399 + vertex -1.423504748063876 5.312592044589873 1.5 + endloop +endfacet +facet normal 0.659226 0.751703 -0.0190432 + outer loop + vertex 3.348187859547956 4.363443371601799 1.5 + vertex 3.619021558537723 4.141579766084337 2.117809182156318 + vertex 3.889087296526007 3.889087296526015 1.5 + endloop +endfacet +facet normal 0.331546 0.943439 -0.000239074 + outer loop + vertex 2.120872707858986 5.074632888895402 15.29577543723218 + vertex 1.521470269542577 5.285369260411048 15.66062752795276 + vertex 2.11806254387618 5.07580644432279 16.02976623207586 + endloop +endfacet +facet normal -0.8597 0.510798 -0.000199613 + outer loop + vertex -4.557314361194889 3.079104709691896 4.262217895531347 + vertex -4.882873685769934 2.531312815282918 4.624276344327242 + vertex -4.558730071149369 3.077008309770787 4.994878305694187 + endloop +endfacet +facet normal 0.543007 0.839728 0.000227067 + outer loop + vertex 2.714267863431721 4.783591743192745 8.323089629866299 + vertex 3.247641787598908 4.438786187623974 7.959160003535738 + vertex 2.716777995166491 4.782166593185472 7.590795854324413 + endloop +endfacet +facet normal 0.717054 0.697017 0.00039306 + outer loop + vertex 4.158599706489312 3.599451136102142 16.04387387159694 + vertex 3.717701953384411 4.053232313327443 15.67311796467917 + vertex 3.71401833700239 4.056607917017615 16.40709822925858 + endloop +endfacet +facet normal -0.546827 0.837246 0.000246915 + outer loop + vertex -3.269152095501428 4.422967847099797 9.026767284026866 + vertex -2.737208876594117 4.770501814892683 8.661078706061058 + vertex -3.266622743135714 4.42483625166271 8.292931250592922 + endloop +endfacet +facet normal -0.552328 0.833627 -0.000259214 + outer loop + vertex -2.77006097467527 4.751501046677892 16.00392148952702 + vertex -2.767215262778732 4.753158916914565 15.27200435617937 + vertex -3.296898100005449 4.402324717485122 15.63542294950113 + endloop +endfacet +facet normal -0.63777 0.770227 0.000397611 + outer loop + vertex -3.747237355031224 4.025942399620068 7.192426533269128 + vertex -3.258463897029156 4.430847890839582 6.829869678627511 + vertex -3.743532901726796 4.029387225582689 6.461285849362103 + endloop +endfacet +facet normal 0.336554 0.941664 -0.000217737 + outer loop + vertex 2.147311820790399 5.063501944730922 7.953930933554343 + vertex 1.549903933452239 5.277101268411407 8.316110728967431 + vertex 2.144762513208912 5.064582288988283 8.685740321988948 + endloop +endfacet +facet normal -0.544849 0.838534 0.000360112 + outer loop + vertex -3.254775613716721 4.433557905830818 6.09986861334725 + vertex -3.258463897029156 4.430847890839582 6.829869678627511 + vertex -2.7268006282093 4.776458765026383 6.4682204653972 + endloop +endfacet +facet normal 0.717392 0.69667 -0.000433371 + outer loop + vertex 4.162202925068889 3.595283967998631 15.30957942587535 + vertex 3.717701953384411 4.053232313327443 15.67311796467917 + vertex 4.158599706489312 3.599451136102142 16.04387387159694 + endloop +endfacet +facet normal 0.79479 0.606884 0.000301183 + outer loop + vertex 4.557195678728257 3.07928036167227 13.47556976892733 + vertex 4.172111394146111 3.583781036117609 13.10364066277435 + vertex 4.169614102858932 3.586686246835636 13.83973113987994 + endloop +endfacet +facet normal -0.341515 0.939876 -0.000318318 + outer loop + vertex -2.173007520207733 5.052527913541956 9.030310479700152 + vertex -1.579382700414764 5.268353659885654 9.40001846000073 + vertex -1.57550572332861 5.269514371909312 8.667668761794854 + endloop +endfacet +facet normal 0.542476 0.840071 0.0004932 + outer loop + vertex 3.243972728227046 4.44146833136511 9.423277641259309 + vertex 2.710732184049698 4.785596203855603 9.784975356056796 + vertex 3.248991982273831 4.437798001162329 10.15424391506147 + endloop +endfacet +facet normal -0.954803 0.297211 0.00415129 + outer loop + vertex -5.33375297905039 1.342042904854793 5.3475778539808 + vertex -5.345708653247237 1.2935992403359 6.066073096927131 + vertex -5.143721801250042 1.947338191312701 5.718996921926565 + endloop +endfacet +facet normal -0.95402 0.299742 -0.000374608 + outer loop + vertex -5.142036710810895 1.951783406188575 4.984386788694756 + vertex -5.33375297905039 1.342042904854793 5.3475778539808 + vertex -5.143721801250042 1.947338191312701 5.718996921926565 + endloop +endfacet +facet normal 0.913424 0.407008 0.000523292 + outer loop + vertex 4.886513843818911 2.524278600742425 12.37504345209598 + vertex 4.88347787458356 2.530147001352456 13.11008610585002 + vertex 5.145654811298226 1.942224642764944 12.74763160945074 + endloop +endfacet +facet normal 0.910726 0.41301 0.000354408 + outer loop + vertex 4.868094338385164 2.559620579809108 17.51729407791064 + vertex 5.132070992332079 1.977839055551192 17.15416962617216 + vertex 4.870184922199945 2.555640589671465 16.78318931728384 + endloop +endfacet +facet normal 0.220497 0.975388 -0.00028933 + outer loop + vertex 1.517935936642233 5.286385390060969 16.39270319811148 + vertex 1.521470269542577 5.285369260411048 15.66062752795276 + vertex 0.9017122864072585 5.425579688157036 16.02342662257618 + endloop +endfacet +facet normal 0.859384 0.51133 0.000222638 + outer loop + vertex 4.881074385750622 2.534780629713188 13.84712727035636 + vertex 4.557195678728257 3.07928036167227 13.47556976892733 + vertex 4.555605928058299 3.081631812569451 14.21147262318354 + endloop +endfacet +facet normal -0.796031 0.605256 0.000335882 + outer loop + vertex -4.56346141485871 3.069986956828276 6.457894800006025 + vertex -4.179585281389481 3.575061800247992 6.092775715699338 + vertex -4.561073522989203 3.073533523143494 5.726248478629312 + endloop +endfacet +facet normal 0.858028 0.513602 -0.000851038 + outer loop + vertex 4.877746635599592 2.541178419335578 15.31515588422337 + vertex 4.547089916440817 3.094183784425586 15.68146541042857 + vertex 4.872777661995054 2.55069360307388 16.04778589539585 + endloop +endfacet +facet normal 0.721235 0.69269 -0.00014682 + outer loop + vertex 3.741065371887834 4.031678296102225 6.132109706259876 + vertex 4.178772325094146 3.576012004318116 6.499676398532498 + vertex 4.1799857098378 3.574593608447229 5.768349711835589 + endloop +endfacet +facet normal 0.861051 0.508516 -0.00196606 + outer loop + vertex 4.886627134838323 2.524059279228959 7.969673719830597 + vertex 4.897747251928272 2.502413206532659 7.241119007269643 + vertex 4.562735033130303 3.071066429995517 7.600486548182634 + endloop +endfacet +facet normal 0.226378 0.97404 -0.000217047 + outer loop + vertex 0.9347925745220471 5.419978121968616 7.947965626364867 + vertex 1.549903933452239 5.277101268411407 8.316110728967431 + vertex 1.552549114769935 5.276323648737546 7.585291971265814 + endloop +endfacet +facet normal -0.860141 0.510057 0.00035727 + outer loop + vertex -4.883662415257973 2.529790784590034 5.356721595552531 + vertex -4.885748956934826 2.525758723593816 6.089672494525414 + vertex -4.561073522989203 3.073533523143494 5.726248478629312 + endloop +endfacet +facet normal -0.450459 0.892797 -4.91479e-05 + outer loop + vertex -2.755486671513457 4.75996777332701 13.07827609719789 + vertex -2.191670631422892 5.044460312397986 13.44675804175767 + vertex -2.191088185537281 5.044713328148483 12.70458421599213 + endloop +endfacet +facet normal -0.236388 0.971659 0.000130078 + outer loop + vertex -0.9915550309688018 5.409881571768504 18.57253006430009 + vertex -1.603634914426853 5.261022244890358 18.20203651395213 + vertex -1.605220724567375 5.260538606019291 18.93286370157931 + endloop +endfacet +facet normal 0.331255 0.943541 0.000289595 + outer loop + vertex 2.11806254387618 5.07580644432279 16.02976623207586 + vertex 1.521470269542577 5.285369260411048 15.66062752795276 + vertex 1.517935936642233 5.286385390060969 16.39270319811148 + endloop +endfacet +facet normal 0.220782 0.975323 0.000223939 + outer loop + vertex 0.9017122864072585 5.425579688157036 16.02342662257618 + vertex 1.521470269542577 5.285369260411048 15.66062752795276 + vertex 0.9045204571974303 5.425112233171896 15.29074663247052 + endloop +endfacet +facet normal -0.644975 0.764203 0.000294986 + outer loop + vertex -3.299526998621698 4.400354711312088 16.36685317911597 + vertex -3.782065424490064 3.993241931673661 15.99930350686742 + vertex -3.784781376700859 3.990667855206488 16.72949380097899 + endloop +endfacet +facet normal -0.864816 0.502089 -1.37284e-05 + outer loop + vertex -4.587900685810118 3.033342594753031 12.32887917960164 + vertex -4.587803823660058 3.033489092713233 11.58495038277631 + vertex -4.909025451291431 2.480215538733068 11.95064759781068 + endloop +endfacet +facet normal 0.718141 0.695897 -0.000572143 + outer loop + vertex 3.721708589489778 4.049553700708018 14.93898835038859 + vertex 4.162202925068889 3.595283967998631 15.30957942587535 + vertex 4.166942054625144 3.589790232506126 14.57600157407444 + endloop +endfacet +facet normal 0.259346 0.965593 0.019244 + outer loop + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + vertex 1.772743246953266 5.20647494763795 2.117973314103827 + vertex 1.423504748063855 5.312592044589878 1.5 + endloop +endfacet +facet normal 0.910343 0.413855 0.000396956 + outer loop + vertex 4.865749673179342 2.564074904903351 18.25038236144107 + vertex 5.130113828406416 1.982910009958412 17.88774139512327 + vertex 4.868094338385164 2.559620579809108 17.51729407791064 + endloop +endfacet +facet normal 0.382924 0.92359 0.0187081 + outer loop + vertex 2.104758878007986 5.081337428812081 1.5 + vertex 1.772743246953266 5.20647494763795 2.117973314103827 + vertex 2.432587796204499 4.93280007842979 2.122937190108265 + endloop +endfacet +facet normal -0.9132 0.407512 -0.00035789 + outer loop + vertex -4.883662415257973 2.529790784590034 5.356721595552531 + vertex -5.143721801250042 1.947338191312701 5.718996921926565 + vertex -4.885748956934826 2.525758723593816 6.089672494525414 + endloop +endfacet +facet normal -0.49942 0.86616 0.0186156 + outer loop + vertex -3.049579275765538 4.577124232618265 2.117940666612885 + vertex -2.43213297513447 4.933024345294026 2.123228765692299 + vertex -2.750000000000011 4.763139720814406 1.5 + endloop +endfacet +facet normal -0.725736 0.687973 0.000189728 + outer loop + vertex -3.765326991561123 4.009028890719206 19.65026233461441 + vertex -4.203565089212222 3.546835285258711 19.28997812941705 + vertex -4.20510078902244 3.545014436382855 20.01829885998822 + endloop +endfacet +facet normal 0.499877 0.86589 -0.0189227 + outer loop + vertex 3.05563628160782 4.573082867663993 20.87706280989174 + vertex 2.432132975136189 4.933024345293179 20.87677123430906 + vertex 2.75000000000001 4.763139720814406 21.5 + endloop +endfacet +facet normal 0.856954 0.515393 -0.000353796 + outer loop + vertex 4.868094338385164 2.559620579809108 17.51729407791064 + vertex 4.870184922199945 2.555640589671465 16.78318931728384 + vertex 4.541597390389772 3.102240020308682 17.14747746590255 + endloop +endfacet +facet normal -0.912908 0.408165 -0.000134888 + outer loop + vertex -4.883662415257973 2.529790784590034 5.356721595552531 + vertex -4.882873685769934 2.531312815282918 4.624276344327242 + vertex -5.142036710810895 1.951783406188575 4.984386788694756 + endloop +endfacet +facet normal 0.954193 0.29919 0.000702373 + outer loop + vertex 5.141258461214585 1.95383249921518 6.159492910637925 + vertex 5.335404501278465 1.335462020327605 5.814529487406688 + vertex 5.144454421942084 1.945401938047904 5.408865316838218 + endloop +endfacet +facet normal -0.345671 0.938356 -0.00012909 + outer loop + vertex -1.605220724567375 5.260538606019291 18.93286370157931 + vertex -1.603634914426853 5.261022244890358 18.20203651395213 + vertex -2.19179224282514 5.044407474053969 18.56624767881553 + endloop +endfacet +facet normal 0.95428 0.298913 4.90612e-05 + outer loop + vertex 5.334915080859414 1.337415821657123 5.04147674123994 + vertex 5.14467353538835 1.944822412014715 4.67778006254769 + vertex 5.144454421942084 1.945401938047904 5.408865316838218 + endloop +endfacet +facet normal 0.636223 0.771505 0.000237376 + outer loop + vertex 3.250073991176871 4.4370056402799 7.22730766149194 + vertex 3.247641787598908 4.438786187623974 7.959160003535738 + vertex 3.737977261791252 4.03454160845214 7.595859945622948 + endloop +endfacet +facet normal 0.857411 0.514633 -0.000438996 + outer loop + vertex 4.872777661995054 2.55069360307388 16.04778589539585 + vertex 4.544253903008611 3.0983473764236 16.41429103446064 + vertex 4.870184922199945 2.555640589671465 16.78318931728384 + endloop +endfacet +facet normal -0.859935 0.510403 -0.000330444 + outer loop + vertex -4.558730071149369 3.077008309770787 4.994878305694187 + vertex -4.883662415257973 2.529790784590034 5.356721595552531 + vertex -4.561073522989203 3.073533523143494 5.726248478629312 + endloop +endfacet +facet normal 0.913193 0.407526 -0.000688953 + outer loop + vertex 4.885654423310991 2.52594157810147 5.773025074018642 + vertex 5.141258461214585 1.95383249921518 6.159492910637925 + vertex 5.144454421942084 1.945401938047904 5.408865316838218 + endloop +endfacet +facet normal 0.226127 0.974098 0.000224939 + outer loop + vertex 0.9319764162669196 5.420463076114648 8.678901954799057 + vertex 1.549903933452239 5.277101268411407 8.316110728967431 + vertex 0.9347925745220471 5.419978121968616 7.947965626364867 + endloop +endfacet +facet normal 0.635782 0.771869 0.000772408 + outer loop + vertex 3.741330192435993 4.031432548259596 9.789771699872459 + vertex 3.734233119467835 4.03800730676277 9.061319687521875 + vertex 3.243972728227046 4.44146833136511 9.423277641259309 + endloop +endfacet +facet normal 0.331805 0.943348 0.000238104 + outer loop + vertex 2.120872707858986 5.074632888895402 15.29577543723218 + vertex 1.524385328890073 5.284529247630738 14.92646702562929 + vertex 1.521470269542577 5.285369260411048 15.66062752795276 + endloop +endfacet +facet normal -0.637105 0.770777 0.000374514 + outer loop + vertex -3.740045600494774 4.032624319995564 5.731546243898735 + vertex -3.743532901726796 4.029387225582689 6.461285849362103 + vertex -3.254775613716721 4.433557905830818 6.09986861334725 + endloop +endfacet +facet normal 0.998318 0.0579789 -0.000588697 + outer loop + vertex 5.462588851477699 0.6404084944092698 7.796296296296289 + vertex 5.463459558418405 0.6329373219573643 8.537037037037026 + vertex 5.5 0 8.166666666666657 + endloop +endfacet +facet normal -0.802836 0.5962 0.000355586 + outer loop + vertex -4.219621040588515 3.527718564996746 17.09213177742202 + vertex -4.595698850376898 3.021514864541369 16.72529260868694 + vertex -4.598174290006761 3.01774637746793 17.45478701894501 + endloop +endfacet +facet normal 0.336788 0.941581 0.000217117 + outer loop + vertex 1.552549114769935 5.276323648737546 7.585291971265814 + vertex 1.549903933452239 5.277101268411407 8.316110728967431 + vertex 2.147311820790399 5.063501944730922 7.953930933554343 + endloop +endfacet +facet normal 0.951474 0.30773 0.000356149 + outer loop + vertex 5.126158116024035 1.99311388774473 19.3527997429786 + vertex 5.321881441977558 1.388372398722644 18.99144459566703 + vertex 5.127797107729225 1.988893366162147 18.62086574692994 + endloop +endfacet +facet normal -0.342789 0.939412 0.000439184 + outer loop + vertex -1.584780954026627 5.266732319736257 10.13313319191941 + vertex -2.177046150527109 5.050789053056473 9.763260881829368 + vertex -2.182188084779327 5.048569615509638 10.49727345085342 + endloop +endfacet +facet normal 0.913455 0.40694 8.37229e-05 + outer loop + vertex 4.886374773580517 2.524547795569723 5.041732577290214 + vertex 5.14467353538835 1.944822412014715 4.67778006254769 + vertex 4.886861798041292 2.523604914966807 4.311007271835738 + endloop +endfacet +facet normal -0.795562 0.605872 0.000329399 + outer loop + vertex -4.558730071149369 3.077008309770787 4.994878305694187 + vertex -4.561073522989203 3.073533523143494 5.726248478629312 + vertex -4.176799564904809 3.578315999826034 5.36342896831726 + endloop +endfacet +facet normal 0.111847 0.993725 9.63548e-05 + outer loop + vertex 0.2990237685235045 5.491865328452437 10.5099348930492 + vertex 0.9286399982135676 5.421035671688382 10.14267071378961 + vertex 0.3002524704688126 5.491798289629489 9.775064600251866 + endloop +endfacet +facet normal -0.831321 0.555471 -0.0189005 + outer loop + vertex -4.763139720814414 2.749999999999997 1.5 + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + vertex -4.363443371601797 3.348187859547959 1.5 + endloop +endfacet +facet normal 0.831321 0.555471 0.0189005 + outer loop + vertex 4.763139720814415 2.749999999999996 21.5 + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + vertex 4.363443371601798 3.348187859547958 21.5 + endloop +endfacet +facet normal 0.983288 0.182057 -0.000162392 + outer loop + vertex 5.335404501278465 1.335462020327605 5.814529487406688 + vertex 5.459976604308243 0.6623107128883186 5.434561843950101 + vertex 5.334915080859414 1.337415821657123 5.04147674123994 + endloop +endfacet +facet normal -0.918183 0.396155 0.000363028 + outer loop + vertex -4.915709720630987 2.466941009123246 17.81820394054487 + vertex -5.166641334823746 1.885687491948415 17.44774793172886 + vertex -5.168219743892152 1.88135713750562 18.18109287916363 + endloop +endfacet +facet normal 0.608099 0.793647 0.0184325 + outer loop + vertex 3.056057912944187 4.572801114495492 2.123228765692188 + vertex 3.619021558537723 4.141579766084337 2.117809182156318 + vertex 3.348187859547956 4.363443371601799 1.5 + endloop +endfacet +facet normal 0.998358 0.0572835 -0.000603698 + outer loop + vertex 5.5 0 8.907407407407394 + vertex 5.463459558418405 0.6329373219573643 8.537037037037026 + vertex 5.464329314634285 0.6253839950209801 9.258668456006923 + endloop +endfacet +facet normal 0.859574 0.511011 -0.000409557 + outer loop + vertex 4.881074385750622 2.534780629713188 13.84712727035636 + vertex 4.88347787458356 2.530147001352456 13.11008610585002 + vertex 4.557195678728257 3.07928036167227 13.47556976892733 + endloop +endfacet +facet normal -0.644729 0.764411 -0.000258443 + outer loop + vertex -3.296898100005449 4.402324717485122 15.63542294950113 + vertex -3.782065424490064 3.993241931673661 15.99930350686742 + vertex -3.299526998621698 4.400354711312088 16.36685317911597 + endloop +endfacet +facet normal -0.344594 0.938752 0.000289321 + outer loop + vertex -2.18769581975002 5.046185390990732 11.96868542169703 + vertex -2.191088185537281 5.044713328148483 12.70458421599213 + vertex -1.594841589980115 5.263694548781274 12.33900123544736 + endloop +endfacet +facet normal -0.446639 0.894714 0.00027065 + outer loop + vertex -2.734226069823106 4.772212044649702 7.929762223762901 + vertex -2.737208876594117 4.770501814892683 8.661078706061058 + vertex -2.169140817674367 5.054189164752243 8.298592900015723 + endloop +endfacet +facet normal 0.910542 0.413416 -0.000428493 + outer loop + vertex 4.868094338385164 2.559620579809108 17.51729407791064 + vertex 5.130113828406416 1.982910009958412 17.88774139512327 + vertex 5.132070992332079 1.977839055551192 17.15416962617216 + endloop +endfacet +facet normal 0.221046 0.975263 -0.000238192 + outer loop + vertex 1.521470269542577 5.285369260411048 15.66062752795276 + vertex 1.524385328890073 5.284529247630738 14.92646702562929 + vertex 0.9045204571974303 5.425112233171896 15.29074663247052 + endloop +endfacet +facet normal -0.728542 0.685001 -0.000295045 + outer loop + vertex -3.784781376700859 3.990667855206488 16.72949380097899 + vertex -3.782065424490064 3.993241931673661 15.99930350686742 + vertex -4.217254729821125 3.530547060131242 16.36191638614252 + endloop +endfacet +facet normal -0.131866 0.991072 0.0196956 + outer loop + vertex -0.7178940572102954 5.452946737555956 1.5 + vertex -1.086182840163288 5.391679407915015 2.117161111770399 + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + endloop +endfacet +facet normal 0.913383 0.407101 0.000123815 + outer loop + vertex 4.885654423310991 2.52594157810147 5.773025074018642 + vertex 5.144454421942084 1.945401938047904 5.408865316838218 + vertex 4.886374773580517 2.524547795569723 5.041732577290214 + endloop +endfacet +facet normal 0.794609 0.607122 -0.000223381 + outer loop + vertex 4.555605928058299 3.081631812569451 14.21147262318354 + vertex 4.557195678728257 3.07928036167227 13.47556976892733 + vertex 4.169614102858932 3.586686246835636 13.83973113987994 + endloop +endfacet +facet normal 0.795039 0.606558 -0.000398008 + outer loop + vertex 4.560022727424994 3.075092311682288 12.74020235260279 + vertex 4.172111394146111 3.583781036117609 13.10364066277435 + vertex 4.557195678728257 3.07928036167227 13.47556976892733 + endloop +endfacet +facet normal 0.91013 0.414322 -0.000505392 + outer loop + vertex 5.127797107729225 1.988893366162147 18.62086574692994 + vertex 5.130113828406416 1.982910009958412 17.88774139512327 + vertex 4.865749673179342 2.564074904903351 18.25038236144107 + endloop +endfacet +facet normal -0.89671 0.442208 0.0190606 + outer loop + vertex -4.763139720814412 2.750000000000003 21.5 + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + vertex -5.081337428812076 2.104758878007997 21.5 + endloop +endfacet +facet normal 0.896713 0.44221 -0.0189005 + outer loop + vertex 4.763139720814412 2.750000000000002 1.5 + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + vertex 5.081337428812076 2.104758878007996 1.5 + endloop +endfacet +facet normal -0.549306 0.835621 -0.000317875 + outer loop + vertex -2.753396472126791 4.761177151427969 12.33816155070207 + vertex -2.749851836277788 4.763225260106819 11.59683773054415 + vertex -3.280719718076403 4.414394424088619 11.97035238303435 + endloop +endfacet +facet normal -0.917022 0.398791 -0.00604767 + outer loop + vertex -4.918778118388804 2.460817307737309 8.165314093629673 + vertex -4.888301959121175 2.520814145559345 7.500407855524626 + vertex -5.167592017862487 1.883080650668979 7.796888109715192 + endloop +endfacet +facet normal -0.913863 0.406023 -0.000316392 + outer loop + vertex -4.885748956934826 2.525758723593816 6.089672494525414 + vertex -5.148581317488049 1.934453519010737 6.435756342408597 + vertex -4.887553899212895 2.522264237206092 6.818608522622353 + endloop +endfacet +facet normal -0.345877 0.93828 -0.000506754 + outer loop + vertex -2.19179224282514 5.044407474053969 18.56624767881553 + vertex -1.603634914426853 5.261022244890358 18.20203651395213 + vertex -2.197700735824538 5.041836121469666 17.83800695130835 + endloop +endfacet +facet normal 0.954713 0.297528 -0.000725385 + outer loop + vertex 5.144340037657432 1.945704390948104 3.946742345627829 + vertex 5.339962456935814 1.317118429950786 3.589736816026074 + vertex 5.141289816700485 1.953749989300548 3.23223805190901 + endloop +endfacet +facet normal -0.446946 0.894561 -0.000330887 + outer loop + vertex -2.169140817674367 5.054189164752243 8.298592900015723 + vertex -2.737208876594117 4.770501814892683 8.661078706061058 + vertex -2.173007520207733 5.052527913541956 9.030310479700152 + endloop +endfacet +facet normal 0.792323 0.610101 0.000434885 + outer loop + vertex 4.154980888345557 3.603627868895894 16.77750589539072 + vertex 4.544253903008611 3.0983473764236 16.41429103446064 + vertex 4.158599706489312 3.599451136102142 16.04387387159694 + endloop +endfacet +facet normal 0.112866 0.99361 -0.000373628 + outer loop + vertex 0.3103090457671292 5.491239231368006 5.391732547173166 + vertex 0.9315810629179355 5.420531037012212 5.028583438976002 + vertex 0.3055515148459051 5.491506011266433 4.66402990365856 + endloop +endfacet +facet normal -0.896707 0.442207 -0.0192475 + outer loop + vertex -5.081337428812079 2.104758878007991 1.5 + vertex -4.93725623361463 2.423530664884083 2.111219890696505 + vertex -4.763139720814414 2.749999999999997 1.5 + endloop +endfacet +facet normal 0.335621 0.941997 7.42733e-05 + outer loop + vertex 1.544463263469689 5.278696167406546 10.51201805553148 + vertex 1.543555395607163 5.278961710477924 11.24658623127648 + vertex 2.141680680654499 5.065886285943584 10.88235392453209 + endloop +endfacet +facet normal 0.112061 0.993701 0.000134982 + outer loop + vertex 0.3002524704688126 5.491798289629489 9.775064600251866 + vertex 0.9295193028246007 5.420884970710637 9.409696694040264 + vertex 0.3019705202645296 5.491704089341592 9.042234105602269 + endloop +endfacet +facet normal -0.546575 0.83741 -0.000270967 + outer loop + vertex -3.266622743135714 4.42483625166271 8.292931250592922 + vertex -2.737208876594117 4.770501814892683 8.661078706061058 + vertex -2.734226069823106 4.772212044649702 7.929762223762901 + endloop +endfacet +facet normal 0.860449 0.509536 -0.000123558 + outer loop + vertex 4.563216686645465 3.070350708098406 5.405036775612206 + vertex 4.885654423310991 2.52594157810147 5.773025074018642 + vertex 4.886374773580517 2.524547795569723 5.041732577290214 + endloop +endfacet +facet normal -0.802612 0.596501 -0.000290365 + outer loop + vertex -4.217254729821125 3.530547060131242 16.36191638614252 + vertex -4.595698850376898 3.021514864541369 16.72529260868694 + vertex -4.219621040588515 3.527718564996746 17.09213177742202 + endloop +endfacet +facet normal -0.235966 0.971761 -0.000609533 + outer loop + vertex -0.9839543072603515 5.411269159931319 17.84228907674125 + vertex -1.603634914426853 5.261022244890358 18.20203651395213 + vertex -0.9915550309688018 5.409881571768504 18.57253006430009 + endloop +endfacet +facet normal -0.641371 0.767231 0.000266213 + outer loop + vertex -3.765826944842038 4.008559270049738 11.59929669367751 + vertex -3.278777122892307 4.415837471918327 11.23609377014295 + vertex -3.763344481104095 4.010889965648939 10.86304173914669 + endloop +endfacet +facet normal 0.796214 0.605015 -0.000219256 + outer loop + vertex 4.563512583583712 3.069910894386531 9.795523476206014 + vertex 4.179409421351509 3.575267387024115 9.429207426964693 + vertex 4.181216983490701 3.573153304431385 10.15965879864028 + endloop +endfacet +facet normal 0.85981 0.510614 0.000397415 + outer loop + vertex 4.557195678728257 3.07928036167227 13.47556976892733 + vertex 4.88347787458356 2.530147001352456 13.11008610585002 + vertex 4.560022727424994 3.075092311682288 12.74020235260279 + endloop +endfacet +facet normal 0.946755 0.32138 -0.019213 + outer loop + vertex 5.081337428812076 2.104758878007996 1.5 + vertex 5.207331238571131 1.770226361740569 2.112773058852293 + vertex 5.312592044589874 1.423504748063868 1.5 + endloop +endfacet +facet normal -0.955611 0.294629 -0.00118256 + outer loop + vertex -5.345708653247237 1.2935992403359 6.066073096927131 + vertex -5.148581317488049 1.934453519010737 6.435756342408597 + vertex -5.143721801250042 1.947338191312701 5.718996921926565 + endloop +endfacet +facet normal -0.957885 0.287151 -0.000366086 + outer loop + vertex -5.168219743892152 1.88135713750562 18.18109287916363 + vertex -5.166641334823746 1.885687491948415 17.44774793172886 + vertex -5.351430836992411 1.269719652870942 17.80587799198893 + endloop +endfacet +facet normal -0.382566 0.923736 0.0188695 + outer loop + vertex -2.104758878008006 5.081337428812073 1.5 + vertex -2.43213297513447 4.933024345294026 2.123228765692299 + vertex -1.767917059167402 5.208115712223076 2.122937190108266 + endloop +endfacet +facet normal 0.382663 0.923696 -0.0188089 + outer loop + vertex 2.104758878008006 5.081337428812073 21.5 + vertex 2.432132975136189 4.933024345293179 20.87677123430906 + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + endloop +endfacet +facet normal 0.860083 0.510154 -0.000520513 + outer loop + vertex 4.560022727424994 3.075092311682288 12.74020235260279 + vertex 4.88347787458356 2.530147001352456 13.11008610585002 + vertex 4.886513843818911 2.524278600742425 12.37504345209598 + endloop +endfacet +facet normal 0.79599 0.60531 -4.81514e-05 + outer loop + vertex 4.562386486476917 3.071584208191729 6.867102472469194 + vertex 4.562727893440858 3.071077037525557 6.135263660355504 + vertex 4.178772325094146 3.576012004318116 6.499676398532498 + endloop +endfacet +facet normal -0.637428 0.77051 -0.000360167 + outer loop + vertex -3.743532901726796 4.029387225582689 6.461285849362103 + vertex -3.258463897029156 4.430847890839582 6.829869678627511 + vertex -3.254775613716721 4.433557905830818 6.09986861334725 + endloop +endfacet +facet normal -0.00855557 0.999963 -0.000246502 + outer loop + vertex 0.2690620830480533 5.493414748174931 17.11771016924891 + vertex -0.3614443539624955 5.488110601927464 17.48441322012165 + vertex 0.265914278229262 5.493568020570403 17.84873078791945 + endloop +endfacet +facet normal -0.913551 0.406723 0.00111764 + outer loop + vertex -5.143721801250042 1.947338191312701 5.718996921926565 + vertex -5.148581317488049 1.934453519010737 6.435756342408597 + vertex -4.885748956934826 2.525758723593816 6.089672494525414 + endloop +endfacet +facet normal 0.793317 0.608809 -0.000707066 + outer loop + vertex 4.162202925068889 3.595283967998631 15.30957942587535 + vertex 4.547089916440817 3.094183784425586 15.68146541042857 + vertex 4.552133984799601 3.086758199864788 14.94713570478919 + endloop +endfacet +facet normal 0.334264 0.942479 -0.000680858 + outer loop + vertex 2.13807510768009 5.067409084918917 12.35499137436904 + vertex 1.536716324117605 5.280956631065102 12.72398985022994 + vertex 2.130062841592538 5.07078221686425 13.09066671338084 + endloop +endfacet +facet normal 0.896713 0.44221 0.0188982 + outer loop + vertex 5.081337428812079 2.104758878007991 21.5 + vertex 4.937890359975085 2.422238384813751 20.87762820958706 + vertex 4.763139720814415 2.749999999999996 21.5 + endloop +endfacet +facet normal -0.638657 0.769492 0.000638178 + outer loop + vertex -3.263341203312671 4.427256960100894 7.561026034291711 + vertex -3.747237355031224 4.025942399620068 7.192426533269128 + vertex -3.753172034506454 4.020410386937966 7.923594727606659 + endloop +endfacet +facet normal 0.792043 0.610465 -0.000371323 + outer loop + vertex 4.541597390389772 3.102240020308682 17.14747746590255 + vertex 4.544253903008611 3.0983473764236 16.41429103446064 + vertex 4.154980888345557 3.603627868895894 16.77750589539072 + endloop +endfacet +facet normal 0.112638 0.993636 2.36185e-05 + outer loop + vertex 0.3055515148459051 5.491506011266433 4.66402990365856 + vertex 0.9315810629179355 5.420531037012212 5.028583438976002 + vertex 0.9312865324749462 5.420581647243291 4.304029951946054 + endloop +endfacet +facet normal 0.225263 0.974298 -0.000111708 + outer loop + vertex 1.545831401814297 5.278295679209799 9.777932328509017 + vertex 0.9286399982135676 5.421035671688382 10.14267071378961 + vertex 1.544463263469689 5.278696167406546 10.51201805553148 + endloop +endfacet +facet normal -0.918027 0.396517 -0.000310077 + outer loop + vertex -4.913948422163426 2.470447510941608 17.08763577686084 + vertex -5.166641334823746 1.885687491948415 17.44774793172886 + vertex -4.915709720630987 2.466941009123246 17.81820394054487 + endloop +endfacet +facet normal 0.225365 0.974274 7.00442e-05 + outer loop + vertex 0.9295193028246007 5.420884970710637 9.409696694040264 + vertex 0.9286399982135676 5.421035671688382 10.14267071378961 + vertex 1.545831401814297 5.278295679209799 9.777932328509017 + endloop +endfacet +facet normal -0.866065 0.499931 -0.000356285 + outer loop + vertex -4.598174290006761 3.01774637746793 17.45478701894501 + vertex -4.595698850376898 3.021514864541369 16.72529260868694 + vertex -4.913948422163426 2.470447510941608 17.08763577686084 + endloop +endfacet +facet normal 0.913457 0.406935 7.42407e-05 + outer loop + vertex 4.886861798041292 2.523604914966807 4.311007271835738 + vertex 5.14467353538835 1.944822412014715 4.67778006254769 + vertex 5.144340037657432 1.945704390948104 3.946742345627829 + endloop +endfacet +facet normal -0.122677 0.992447 -0.000297326 + outer loop + vertex -0.3652328073833823 5.487859782867165 18.21031711504795 + vertex -0.3614443539624955 5.488110601927464 17.48441322012165 + vertex -0.9839543072603515 5.411269159931319 17.84228907674125 + endloop +endfacet +facet normal 0.913424 0.40701 -4.88718e-05 + outer loop + vertex 5.144454421942084 1.945401938047904 5.408865316838218 + vertex 5.14467353538835 1.944822412014715 4.67778006254769 + vertex 4.886374773580517 2.524547795569723 5.041732577290214 + endloop +endfacet +facet normal 0.720643 0.693307 0.000254519 + outer loop + vertex 3.737977261791252 4.03454160845214 7.595859945622948 + vertex 3.735609022597694 4.036734476069326 8.327927643449971 + vertex 4.177069149615913 3.578001302309292 7.965218399827975 + endloop +endfacet +facet normal 0.226117 0.974099 -0.00106784 + outer loop + vertex 0.9312865324749462 5.420581647243291 4.304029951946054 + vertex 1.545322340430237 5.278444739141182 4.668058894735688 + vertex 1.558182631274909 5.274662727378235 3.941249219772481 + endloop +endfacet +facet normal 0.108285 0.99412 -0.000278316 + outer loop + vertex 0.9073369128292557 5.424641898468273 14.55789481624371 + vertex 0.9108469727899998 5.424053631017976 13.82232051003361 + vertex 0.2800449050422982 5.492865814050062 14.18619827858576 + endloop +endfacet +facet normal 0.912491 0.409096 0.00054138 + outer loop + vertex 4.880890562096091 2.535134576475439 14.58315638407505 + vertex 4.877746635599592 2.541178419335578 15.31515588422337 + vertex 5.141115229323106 1.95420935388766 14.9559015917752 + endloop +endfacet +facet normal -0.8598 0.51063 0.000135225 + outer loop + vertex -4.558730071149369 3.077008309770787 4.994878305694187 + vertex -4.882873685769934 2.531312815282918 4.624276344327242 + vertex -4.883662415257973 2.529790784590034 5.356721595552531 + endloop +endfacet +facet normal 0.112252 0.99368 -0.000196241 + outer loop + vertex 0.3019705202645296 5.491704089341592 9.042234105602269 + vertex 0.9295193028246007 5.420884970710637 9.409696694040264 + vertex 0.9319764162669196 5.420463076114648 8.678901954799057 + endloop +endfacet +facet normal 0.984874 0.173272 -0.000750101 + outer loop + vertex 5.351088640648471 1.271161028321311 13.35230399535177 + vertex 5.353286605756722 1.261872622979704 14.09259610146606 + vertex 5.463079625775358 0.6362083011389977 13.72188479775475 + endloop +endfacet +facet normal 0.109645 0.993971 -8.5128e-05 + outer loop + vertex 0.2889348960300206 5.492405358843802 12.71628545687114 + vertex 0.9146392260707148 5.42341544472971 13.08738556493957 + vertex 0.9157185103458564 5.423233316925427 12.35095009251186 + endloop +endfacet +facet normal 0.332089 0.943248 -0.000277229 + outer loop + vertex 2.124130725649839 5.073270016503192 14.56145281446745 + vertex 1.524385328890073 5.284529247630738 14.92646702562929 + vertex 2.120872707858986 5.074632888895402 15.29577543723218 + endloop +endfacet +facet normal 0.857167 0.515038 0.000371281 + outer loop + vertex 4.870184922199945 2.555640589671465 16.78318931728384 + vertex 4.544253903008611 3.0983473764236 16.41429103446064 + vertex 4.541597390389772 3.102240020308682 17.14747746590255 + endloop +endfacet +facet normal 0.706245 0.707699 0.0194943 + outer loop + vertex 3.889087296526007 3.889087296526015 1.5 + vertex 3.619021558537723 4.141579766084337 2.117809182156318 + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + endloop +endfacet +facet normal -0.917969 0.396652 0.000165817 + outer loop + vertex -5.166420226055012 1.886293203033316 16.0040728052201 + vertex -4.913917191599206 2.470509630441817 16.36286586361541 + vertex -4.914848247313041 2.46865686272595 15.6405238496727 + endloop +endfacet +facet normal -0.918324 0.395829 0.000863958 + outer loop + vertex -4.913838183546919 2.47066677354845 8.903493668018529 + vertex -4.918778118388804 2.460817307737309 8.165314093629673 + vertex -5.168346033474785 1.881010174950005 8.536010542375871 + endloop +endfacet +facet normal -0.00887245 0.999961 0.000299208 + outer loop + vertex 0.265914278229262 5.493568020570403 17.84873078791945 + vertex -0.3614443539624955 5.488110601927464 17.48441322012165 + vertex -0.3652328073833823 5.487859782867165 18.21031711504795 + endloop +endfacet +facet normal -0.946747 0.321377 -0.0196762 + outer loop + vertex -5.312592044589876 1.423504748063862 1.5 + vertex -5.202761293209437 1.783612885656994 2.097099159738966 + vertex -5.081337428812079 2.104758878007991 1.5 + endloop +endfacet +facet normal 0.946761 0.321382 0.0189005 + outer loop + vertex 5.312592044589876 1.423504748063862 21.5 + vertex 5.208115712223082 1.767917059167386 20.87706280989174 + vertex 5.081337428812079 2.104758878007991 21.5 + endloop +endfacet +facet normal 0.796133 0.605121 -6.89823e-05 + outer loop + vertex 4.1799857098378 3.574593608447229 5.768349711835589 + vertex 4.562727893440858 3.071077037525557 6.135263660355504 + vertex 4.563216686645465 3.070350708098406 5.405036775612206 + endloop +endfacet +facet normal 0.335888 0.941902 -0.000183197 + outer loop + vertex 2.141708837930507 5.065874381933523 10.14863544349151 + vertex 2.143854083748615 5.064966896989 9.41608988622334 + vertex 1.545831401814297 5.278295679209799 9.777932328509017 + endloop +endfacet +facet normal 0.911335 0.411665 -0.00052378 + outer loop + vertex 5.133866670985064 1.973173333630053 16.41890538970767 + vertex 5.136237431772161 1.966993910631783 15.68711310633112 + vertex 4.872777661995054 2.55069360307388 16.04778589539585 + endloop +endfacet +facet normal 0.111431 0.993772 0.000285421 + outer loop + vertex 0.2953835508501084 5.492062322833489 11.24521763091109 + vertex 0.9265167379228637 5.421398964690643 10.87934931410019 + vertex 0.2990237685235045 5.491865328452437 10.5099348930492 + endloop +endfacet +facet normal 0.22553 0.974236 -2.36272e-05 + outer loop + vertex 0.9315810629179355 5.420531037012212 5.028583438976002 + vertex 1.545322340430237 5.278444739141182 4.668058894735688 + vertex 0.9312865324749462 5.420581647243291 4.304029951946054 + endloop +endfacet +facet normal 0.225476 0.974249 -0.000125721 + outer loop + vertex 1.545831401814297 5.278295679209799 9.777932328509017 + vertex 1.547363522133949 5.277846732368156 9.046718844641275 + vertex 0.9295193028246007 5.420884970710637 9.409696694040264 + endloop +endfacet +facet normal 0.441943 0.897043 0.000149585 + outer loop + vertex 2.712385502007586 4.784659328363833 10.5186368901123 + vertex 2.710732184049698 4.785596203855603 9.784975356056796 + vertex 2.141708837930507 5.065874381933523 10.14863544349151 + endloop +endfacet +facet normal 0.225885 0.974154 -0.000208531 + outer loop + vertex 0.9319764162669196 5.420463076114648 8.678901954799057 + vertex 1.547363522133949 5.277846732368156 9.046718844641275 + vertex 1.549903933452239 5.277101268411407 8.316110728967431 + endloop +endfacet +facet normal 0.542381 0.840132 -3.15743e-05 + outer loop + vertex 2.712164933028665 4.784784360454462 9.054788706823091 + vertex 3.243972728227046 4.44146833136511 9.423277641259309 + vertex 3.244296841629572 4.441231586327422 8.69153930796214 + endloop +endfacet +facet normal -0.918125 0.396291 0.000294694 + outer loop + vertex -4.911652466281053 2.475009101089377 10.38261171957252 + vertex -4.913313387114148 2.471710250010081 9.64411804727896 + vertex -5.16934903317279 1.878251999396124 10.01446444154432 + endloop +endfacet +facet normal -0.795793 0.605568 -0.000337583 + outer loop + vertex -4.561073522989203 3.073533523143494 5.726248478629312 + vertex -4.179585281389481 3.575061800247992 6.092775715699338 + vertex -4.176799564904809 3.578315999826034 5.36342896831726 + endloop +endfacet +facet normal -0.547455 0.836835 0.000308441 + outer loop + vertex -3.272316987094792 4.420626826137992 9.760825036399151 + vertex -2.741300165584849 4.768151990254136 9.392493992010372 + vertex -3.269152095501428 4.422967847099797 9.026767284026866 + endloop +endfacet +facet normal 0.796058 0.605221 0.000146968 + outer loop + vertex 4.178772325094146 3.576012004318116 6.499676398532498 + vertex 4.562727893440858 3.071077037525557 6.135263660355504 + vertex 4.1799857098378 3.574593608447229 5.768349711835589 + endloop +endfacet +facet normal -0.721034 0.6929 0.000337615 + outer loop + vertex -4.176799564904809 3.578315999826034 5.36342896831726 + vertex -4.179585281389481 3.575061800247992 6.092775715699338 + vertex -3.740045600494774 4.032624319995564 5.731546243898735 + endloop +endfacet +facet normal -0.721315 0.692607 -0.000374663 + outer loop + vertex -3.740045600494774 4.032624319995564 5.731546243898735 + vertex -4.179585281389481 3.575061800247992 6.092775715699338 + vertex -3.743532901726796 4.029387225582689 6.461285849362103 + endloop +endfacet +facet normal -0.866127 0.499823 -0.000279745 + outer loop + vertex -4.914848247313041 2.46865686272595 15.6405238496727 + vertex -4.597528200520561 3.018730601663252 15.99861064446014 + vertex -4.595606947051128 3.021654644100713 15.27457467989483 + endloop +endfacet +facet normal 0.793308 0.60882 -0.000274714 + outer loop + vertex 4.57176427209746 3.057608778175061 2.493642932651824 + vertex 4.573082867663997 3.055636281607814 1.92999455336682 + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + endloop +endfacet +facet normal 0.224848 0.974394 0.000136683 + outer loop + vertex 0.9247966696185814 5.421692643433634 11.61532331063718 + vertex 1.543555395607163 5.278961710477924 11.24658623127648 + vertex 0.9265167379228637 5.421398964690643 10.87934931410019 + endloop +endfacet +facet normal -0.450334 0.89286 0.000187156 + outer loop + vertex -2.191088185537281 5.044713328148483 12.70458421599213 + vertex -2.753396472126791 4.761177151427969 12.33816155070207 + vertex -2.755486671513457 4.75996777332701 13.07827609719789 + endloop +endfacet +facet normal 0.860392 0.509632 6.90103e-05 + outer loop + vertex 4.563216686645465 3.070350708098406 5.405036775612206 + vertex 4.562727893440858 3.071077037525557 6.135263660355504 + vertex 4.885654423310991 2.52594157810147 5.773025074018642 + endloop +endfacet +facet normal 0.336319 0.941748 0.000208524 + outer loop + vertex 1.549903933452239 5.277101268411407 8.316110728967431 + vertex 1.547363522133949 5.277846732368156 9.046718844641275 + vertex 2.144762513208912 5.064582288988283 8.685740321988948 + endloop +endfacet +facet normal 0.107941 0.994157 0.00030861 + outer loop + vertex 0.2761128175058328 5.493064874185357 14.9202532219283 + vertex 0.9073369128292557 5.424641898468273 14.55789481624371 + vertex 0.2800449050422982 5.492865814050062 14.18619827858576 + endloop +endfacet +facet normal 0.635745 0.771899 0.000326243 + outer loop + vertex 3.244296841629572 4.441231586327422 8.69153930796214 + vertex 3.735609022597694 4.036734476069326 8.327927643449971 + vertex 3.247641787598908 4.438786187623974 7.959160003535738 + endloop +endfacet +facet normal -0.802315 0.596901 -0.000542681 + outer loop + vertex -4.595606947051128 3.021654644100713 15.27457467989483 + vertex -4.217191461647667 3.530622632880213 15.63439694126637 + vertex -4.212819464422161 3.535838254245488 14.90743681953956 + endloop +endfacet +facet normal 0.221543 0.975151 -0.000194841 + outer loop + vertex 1.526772267661226 5.283840122742228 14.19155595219776 + vertex 0.9073369128292557 5.424641898468273 14.55789481624371 + vertex 1.524385328890073 5.284529247630738 14.92646702562929 + endloop +endfacet +facet normal -0.727616 0.685985 -0.000268363 + outer loop + vertex -4.212819464422161 3.535838254245488 14.90743681953956 + vertex -3.77886316789521 3.996272407922785 15.27040476235519 + vertex -3.776397186416806 3.998602792279227 14.54124771470269 + endloop +endfacet +facet normal 0.111943 0.993715 -7.00185e-05 + outer loop + vertex 0.3002524704688126 5.491798289629489 9.775064600251866 + vertex 0.9286399982135676 5.421035671688382 10.14267071378961 + vertex 0.9295193028246007 5.420884970710637 9.409696694040264 + endloop +endfacet +facet normal 0.795632 0.60578 0.000108417 + outer loop + vertex 4.175055378160717 3.580350903094733 8.700074265015786 + vertex 4.562500283604454 3.07141517254006 9.064348170825244 + vertex 4.561739448136046 3.072545070022481 8.334534675596213 + endloop +endfacet +facet normal 0.224967 0.974366 -7.41878e-05 + outer loop + vertex 0.9265167379228637 5.421398964690643 10.87934931410019 + vertex 1.543555395607163 5.278961710477924 11.24658623127648 + vertex 1.544463263469689 5.278696167406546 10.51201805553148 + endloop +endfacet +facet normal -0.722324 0.691554 0.000616587 + outer loop + vertex -3.747237355031224 4.025942399620068 7.192426533269128 + vertex -4.182554933290917 3.571587074397573 6.8208155119836 + vertex -4.187648423468353 3.565613647245452 7.553553388071339 + endloop +endfacet +facet normal 0.221809 0.97509 0.000278626 + outer loop + vertex 1.526772267661226 5.283840122742228 14.19155595219776 + vertex 0.9108469727899998 5.424053631017976 13.82232051003361 + vertex 0.9073369128292557 5.424641898468273 14.55789481624371 + endloop +endfacet +facet normal 0.636007 0.771684 -0.000254053 + outer loop + vertex 3.247641787598908 4.438786187623974 7.959160003535738 + vertex 3.735609022597694 4.036734476069326 8.327927643449971 + vertex 3.737977261791252 4.03454160845214 7.595859945622948 + endloop +endfacet +facet normal 0.107639 0.99419 -0.000224387 + outer loop + vertex 0.9045204571974303 5.425112233171896 15.29074663247052 + vertex 0.9073369128292557 5.424641898468273 14.55789481624371 + vertex 0.2761128175058328 5.493064874185357 14.9202532219283 + endloop +endfacet +facet normal 0.957816 0.287366 -0.00297654 + outer loop + vertex 5.343411944396419 1.303053641444466 7.983999811632167 + vertex 5.351612161616004 1.268955188981735 7.330746350623435 + vertex 5.171106296982572 1.873408568707635 7.60218979976907 + endloop +endfacet +facet normal 0.336054 0.941843 0.000125869 + outer loop + vertex 1.545831401814297 5.278295679209799 9.777932328509017 + vertex 2.143854083748615 5.064966896989 9.41608988622334 + vertex 1.547363522133949 5.277846732368156 9.046718844641275 + endloop +endfacet +facet normal 0.225656 0.974207 0.000196292 + outer loop + vertex 0.9295193028246007 5.420884970710637 9.409696694040264 + vertex 1.547363522133949 5.277846732368156 9.046718844641275 + vertex 0.9319764162669196 5.420463076114648 8.678901954799057 + endloop +endfacet +facet normal 0.955217 0.295905 -0.000275021 + outer loop + vertex 5.342620843612703 1.306293428520213 8.722112600728778 + vertex 5.343411944396419 1.303053641444466 7.983999811632167 + vertex 5.144868400325386 1.944306854211367 8.339749905384522 + endloop +endfacet +facet normal 0.44196 0.897035 0.000183017 + outer loop + vertex 2.141708837930507 5.065874381933523 10.14863544349151 + vertex 2.710732184049698 4.785596203855603 9.784975356056796 + vertex 2.143854083748615 5.064966896989 9.41608988622334 + endloop +endfacet +facet normal 0.923732 0.382572 0.0189274 + outer loop + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + vertex 5.207331238571131 1.770226361740569 2.112773058852293 + vertex 5.081337428812076 2.104758878007996 1.5 + endloop +endfacet +facet normal 0.984914 0.173044 0.00102594 + outer loop + vertex 5.463174314802662 0.635394685278737 12.98255000771282 + vertex 5.354099104705792 1.258420747202078 12.61111111111141 + vertex 5.351088640648471 1.271161028321311 13.35230399535177 + endloop +endfacet +facet normal -0.344962 0.938616 -0.000391683 + outer loop + vertex -1.594841589980115 5.263694548781274 12.33900123544736 + vertex -2.191088185537281 5.044713328148483 12.70458421599213 + vertex -1.599638590842117 5.262238723080571 13.07511200794479 + endloop +endfacet +facet normal -0.347193 0.937794 7.06116e-05 + outer loop + vertex -2.202922862387096 5.03955661366873 16.37282938396807 + vertex -1.609463548531972 5.259242063828863 16.73470020974355 + vertex -1.610314611093768 5.258981541448679 16.01007290764218 + endloop +endfacet +facet normal 0.954787 0.29729 0.000590872 + outer loop + vertex 5.127797107729225 1.988893366162147 18.62086574692994 + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + vertex 5.130113828406416 1.982910009958412 17.88774139512327 + endloop +endfacet +facet normal -0.449301 0.893381 0.000130482 + outer loop + vertex -2.748401568742806 4.764062217995487 10.8602147235481 + vertex -2.749851836277788 4.763225260106819 11.59683773054415 + vertex -2.185024418165879 5.047342696114349 11.23106540038434 + endloop +endfacet +facet normal 0.336166 0.941803 -7.78288e-05 + outer loop + vertex 1.547363522133949 5.277846732368156 9.046718844641275 + vertex 2.143854083748615 5.064966896989 9.41608988622334 + vertex 2.144762513208912 5.064582288988283 8.685740321988948 + endloop +endfacet +facet normal 0.866392 0.498984 -0.0195143 + outer loop + vertex 4.763139720814415 2.749999999999996 21.5 + vertex 4.937890359975085 2.422238384813751 20.87762820958706 + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + endloop +endfacet +facet normal 0.857658 0.514221 0.000397531 + outer loop + vertex 4.872777661995054 2.55069360307388 16.04778589539585 + vertex 4.547089916440817 3.094183784425586 15.68146541042857 + vertex 4.544253903008611 3.0983473764236 16.41429103446064 + endloop +endfacet +facet normal 0.953588 0.300995 0.00852938 + outer loop + vertex 5.130113828406416 1.982910009958412 17.88774139512327 + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + vertex 5.325937770498046 1.372729712937804 17.5273430786013 + endloop +endfacet +facet normal -0.122833 0.992427 -0.000230064 + outer loop + vertex -0.3585134827399036 5.488302841743858 16.74886969383951 + vertex -0.9889336480867522 5.410361377919393 17.11772481178466 + vertex -0.3614443539624955 5.488110601927464 17.48441322012165 + endloop +endfacet +facet normal 0.792621 0.609715 -0.000396714 + outer loop + vertex 4.544253903008611 3.0983473764236 16.41429103446064 + vertex 4.547089916440817 3.094183784425586 15.68146541042857 + vertex 4.158599706489312 3.599451136102142 16.04387387159694 + endloop +endfacet +facet normal 0.914855 0.403778 -0.00179232 + outer loop + vertex 4.897747251928272 2.502413206532659 7.241119007269643 + vertex 5.153439736913926 1.921473101033819 6.878842079210223 + vertex 4.887482158996987 2.5224032479931 6.504905294554623 + endloop +endfacet +facet normal -0.345216 0.938523 3.06159e-05 + outer loop + vertex -1.599638590842117 5.262238723080571 13.07511200794479 + vertex -2.191670631422892 5.044460312397986 13.44675804175767 + vertex -1.599262890242996 5.262352915558935 13.81085552389677 + endloop +endfacet +facet normal 0.44223 0.896902 7.77429e-05 + outer loop + vertex 2.144762513208912 5.064582288988283 8.685740321988948 + vertex 2.143854083748615 5.064966896989 9.41608988622334 + vertex 2.712164933028665 4.784784360454462 9.054788706823091 + endloop +endfacet +facet normal 0.635536 0.772071 -0.000147641 + outer loop + vertex 3.244296841629572 4.441231586327422 8.69153930796214 + vertex 3.734233119467835 4.03800730676277 9.061319687521875 + vertex 3.735609022597694 4.036734476069326 8.327927643449971 + endloop +endfacet +facet normal -0.448756 0.893654 0.000440492 + outer loop + vertex -2.182188084779327 5.048569615509638 10.49727345085342 + vertex -2.743506408130021 4.766882900654211 10.12470652105002 + vertex -2.748401568742806 4.764062217995487 10.8602147235481 + endloop +endfacet +facet normal 0.861048 0.508521 0.00180196 + outer loop + vertex 4.897747251928272 2.502413206532659 7.241119007269643 + vertex 4.887482158996987 2.5224032479931 6.504905294554623 + vertex 4.562386486476917 3.071584208191729 6.867102472469194 + endloop +endfacet +facet normal -0.866474 0.498836 0.0196119 + outer loop + vertex -4.763139720814414 2.749999999999997 1.5 + vertex -4.93725623361463 2.423530664884083 2.111219890696505 + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + endloop +endfacet +facet normal -0.952009 0.305972 -0.00776984 + outer loop + vertex -5.141451880835366 1.953323464522575 3.518268699072249 + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + vertex -5.329642713413715 1.358274106120005 3.143864560230363 + endloop +endfacet +facet normal 0.792908 0.609341 0.000432788 + outer loop + vertex 4.158599706489312 3.599451136102142 16.04387387159694 + vertex 4.547089916440817 3.094183784425586 15.68146541042857 + vertex 4.162202925068889 3.595283967998631 15.30957942587535 + endloop +endfacet +facet normal 0.221305 0.975205 0.000224632 + outer loop + vertex 1.524385328890073 5.284529247630738 14.92646702562929 + vertex 0.9073369128292557 5.424641898468273 14.55789481624371 + vertex 0.9045204571974303 5.425112233171896 15.29074663247052 + endloop +endfacet +facet normal 0.860542 0.509379 4.84441e-05 + outer loop + vertex 4.562386486476917 3.071584208191729 6.867102472469194 + vertex 4.887482158996987 2.5224032479931 6.504905294554623 + vertex 4.562727893440858 3.071077037525557 6.135263660355504 + endloop +endfacet +facet normal 0.335348 0.942094 -0.000431425 + outer loop + vertex 2.141680680654499 5.065886285943584 10.88235392453209 + vertex 1.543555395607163 5.278961710477924 11.24658623127648 + vertex 2.136595684821637 5.068033038527035 11.61759465937531 + endloop +endfacet +facet normal 0.860464 0.509511 0.000314422 + outer loop + vertex 4.562727893440858 3.071077037525557 6.135263660355504 + vertex 4.887482158996987 2.5224032479931 6.504905294554623 + vertex 4.885654423310991 2.52594157810147 5.773025074018642 + endloop +endfacet +facet normal -0.640947 0.767585 0.000256133 + outer loop + vertex -3.763344481104095 4.010889965648939 10.86304173914669 + vertex -3.276621723325886 4.417437049039737 10.48929820463972 + vertex -3.760953233344837 4.01313228994423 10.12705573614122 + endloop +endfacet +facet normal -0.797023 0.603949 -0.000616839 + outer loop + vertex -4.182554933290917 3.571587074397573 6.8208155119836 + vertex -4.567633014570769 3.063776859401342 7.184723364159598 + vertex -4.187648423468353 3.565613647245452 7.553553388071339 + endloop +endfacet +facet normal 0.98422 0.176838 -0.00628466 + outer loop + vertex 5.462786065058352 0.6387240463645399 14.46303530577151 + vertex 5.352885295866843 1.263573903375872 14.83390153907896 + vertex 5.45199573013907 0.7250810703261731 15.20311570077771 + endloop +endfacet +facet normal -0.345798 0.938309 -0.000369126 + outer loop + vertex -1.599262890242996 5.262352915558935 13.81085552389677 + vertex -2.195947574048251 5.042599949632293 14.17997266974335 + vertex -1.603762649021274 5.260983307862159 14.5447323978708 + endloop +endfacet +facet normal -0.641571 0.767063 -0.000189857 + outer loop + vertex -3.280719718076403 4.414394424088619 11.97035238303435 + vertex -3.278777122892307 4.415837471918327 11.23609377014295 + vertex -3.765826944842038 4.008559270049738 11.59929669367751 + endloop +endfacet +facet normal -0.998309 0.0580947 0.0018297 + outer loop + vertex -5.461533276369314 0.6493491134287154 13.7223915162698 + vertex -5.464240887080524 0.6261561530141311 12.98148148148145 + vertex -5.5 0 13.35185185185182 + endloop +endfacet +facet normal 0.442124 0.896954 -0.000129738 + outer loop + vertex 2.143854083748615 5.064966896989 9.41608988622334 + vertex 2.710732184049698 4.785596203855603 9.784975356056796 + vertex 2.712164933028665 4.784784360454462 9.054788706823091 + endloop +endfacet +facet normal -0.923644 0.382826 0.0180716 + outer loop + vertex -5.202761293209437 1.783612885656994 2.097099159738966 + vertex -4.93725623361463 2.423530664884083 2.111219890696505 + vertex -5.081337428812079 2.104758878007991 1.5 + endloop +endfacet +facet normal 0.95322 0.302124 -0.00964149 + outer loop + vertex 5.321881441977558 1.388372398722644 18.99144459566703 + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + vertex 5.127797107729225 1.988893366162147 18.62086574692994 + endloop +endfacet +facet normal -0.998335 0.0576745 -0.00111684 + outer loop + vertex -5.5 0 12.61111111111108 + vertex -5.464240887080524 0.6261561530141311 12.98148148148145 + vertex -5.462588851477786 0.6404084944085295 12.24074074074071 + endloop +endfacet +facet normal 0.224106 0.974564 0.000724534 + outer loop + vertex 0.9157185103458564 5.423233316925427 12.35095009251186 + vertex 1.540798081005442 5.279767160923855 11.98214227948561 + vertex 0.9247966696185814 5.421692643433634 11.61532331063718 + endloop +endfacet +facet normal 0.858856 0.512217 -0.000540412 + outer loop + vertex 4.552133984799601 3.086758199864788 14.94713570478919 + vertex 4.877746635599592 2.541178419335578 15.31515588422337 + vertex 4.880890562096091 2.535134576475439 14.58315638407505 + endloop +endfacet +facet normal -0.547702 0.836674 -0.000200146 + outer loop + vertex -3.272316987094792 4.420626826137992 9.760825036399151 + vertex -2.743506408130021 4.766882900654211 10.12470652105002 + vertex -2.741300165584849 4.768151990254136 9.392493992010372 + endloop +endfacet +facet normal -0.99831 0.0581103 0.000768601 + outer loop + vertex -5.462288539552118 0.642964937362526 16.6854252851455 + vertex -5.463422928156496 0.6332534311742012 15.94624735955442 + vertex -5.5 0 16.3148148148148 + endloop +endfacet +facet normal 0.911652 0.410962 0.00084571 + outer loop + vertex 4.872777661995054 2.55069360307388 16.04778589539585 + vertex 5.136237431772161 1.966993910631783 15.68711310633112 + vertex 4.877746635599592 2.541178419335578 15.31515588422337 + endloop +endfacet +facet normal -0.608158 0.793577 0.0194665 + outer loop + vertex -3.348187859547972 4.363443371601787 1.5 + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + vertex -3.049579275765538 4.577124232618265 2.117940666612885 + endloop +endfacet +facet normal 0.108646 0.99408 0.000355598 + outer loop + vertex 0.2800449050422982 5.492865814050062 14.18619827858576 + vertex 0.9108469727899998 5.424053631017976 13.82232051003361 + vertex 0.2845863738601849 5.492632392197125 13.45117311754784 + endloop +endfacet +facet normal -0.998317 0.057994 -0.000562556 + outer loop + vertex -5.5 0 15.57407407407405 + vertex -5.463422928156496 0.6332534311742012 15.94624735955442 + vertex -5.462588851477785 0.6404084944085344 15.20370370370368 + endloop +endfacet +facet normal 0.22211 0.975021 -0.000249952 + outer loop + vertex 1.529835967906667 5.282953900167885 13.45699023934335 + vertex 0.9108469727899998 5.424053631017976 13.82232051003361 + vertex 1.526772267661226 5.283840122742228 14.19155595219776 + endloop +endfacet +facet normal -0.447313 0.894377 0.000371255 + outer loop + vertex -2.737208876594117 4.770501814892683 8.661078706061058 + vertex -2.741300165584849 4.768151990254136 9.392493992010372 + vertex -2.173007520207733 5.052527913541956 9.030310479700152 + endloop +endfacet +facet normal 0.91268 0.408676 0.000471935 + outer loop + vertex 5.14260411224237 1.950287913295847 14.21826185107064 + vertex 5.140471256908808 1.955902670608734 13.48086883335942 + vertex 4.881074385750622 2.534780629713188 13.84712727035636 + endloop +endfacet +facet normal -0.447679 0.894194 -0.000345356 + outer loop + vertex -2.173007520207733 5.052527913541956 9.030310479700152 + vertex -2.741300165584849 4.768151990254136 9.392493992010372 + vertex -2.177046150527109 5.050789053056473 9.763260881829368 + endloop +endfacet +facet normal 0.448297 0.89368 0.0191301 + outer loop + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + vertex 2.750048563129589 4.763111682548383 2.61068253831418 + vertex 2.432587796204499 4.93280007842979 2.122937190108265 + endloop +endfacet +facet normal -0.643529 0.765421 -0.000426154 + outer loop + vertex -3.776397186416806 3.998602792279227 14.54124771470269 + vertex -3.292803668559807 4.405388064667978 14.90654265782822 + vertex -3.288483294202905 4.408614025263315 14.17660159336728 + endloop +endfacet +facet normal 0.998337 0.0576432 -0.001171 + outer loop + vertex 5.462588851477699 0.6404084944092698 10.75925925925924 + vertex 5.464321032236196 0.6254563587182973 11.49999999999998 + vertex 5.5 0 11.12962962962961 + endloop +endfacet +facet normal 0.92412 0.381664 -0.0183038 + outer loop + vertex 5.208115712223082 1.767917059167386 20.87706280989174 + vertex 4.937890359975085 2.422238384813751 20.87762820958706 + vertex 5.081337428812079 2.104758878007991 21.5 + endloop +endfacet +facet normal 0.984896 0.173146 0.000135812 + outer loop + vertex 5.462786065058352 0.6387240463645399 14.46303530577151 + vertex 5.353286605756722 1.261872622979704 14.09259610146606 + vertex 5.352885295866843 1.263573903375872 14.83390153907896 + endloop +endfacet +facet normal -0.550679 0.834717 -0.000547225 + outer loop + vertex -3.288483294202905 4.408614025263315 14.17660159336728 + vertex -2.761926079215587 4.75623425967948 14.54357724341185 + vertex -2.755934067944267 4.75970875297472 13.81361629833644 + endloop +endfacet +facet normal -0.802593 0.596527 0.000279386 + outer loop + vertex -4.595606947051128 3.021654644100713 15.27457467989483 + vertex -4.597528200520561 3.018730601663252 15.99861064446014 + vertex -4.217191461647667 3.530622632880213 15.63439694126637 + endloop +endfacet +facet normal -0.449772 0.893144 0.000316971 + outer loop + vertex -2.18769581975002 5.046185390990732 11.96868542169703 + vertex -2.749851836277788 4.763225260106819 11.59683773054415 + vertex -2.753396472126791 4.761177151427969 12.33816155070207 + endloop +endfacet +facet normal 0.998337 0.0576432 0.001171 + outer loop + vertex 5.5 0 11.87037037037035 + vertex 5.464321032236196 0.6254563587182973 11.49999999999998 + vertex 5.462588851477699 0.6404084944092698 12.24074074074071 + endloop +endfacet +facet normal -0.547125 0.837051 -0.00037123 + outer loop + vertex -3.269152095501428 4.422967847099797 9.026767284026866 + vertex -2.741300165584849 4.768151990254136 9.392493992010372 + vertex -2.737208876594117 4.770501814892683 8.661078706061058 + endloop +endfacet +facet normal 0.954793 0.297271 -7.69246e-05 + outer loop + vertex 5.14467353538835 1.944822412014715 4.67778006254769 + vertex 5.339523148522663 1.318898232006785 4.314904814500256 + vertex 5.144340037657432 1.945704390948104 3.946742345627829 + endloop +endfacet +facet normal -0.798586 0.60188 0.00118525 + outer loop + vertex -4.193745453649838 3.558440539055181 9.021971072896772 + vertex -4.571761310004581 3.057613207118456 8.650358816856777 + vertex -4.580135555157919 3.045054727977522 9.385342259607349 + endloop +endfacet +facet normal -0.917913 0.396783 -8.71822e-05 + outer loop + vertex -5.166420226055012 1.886293203033316 16.0040728052201 + vertex -5.166046937107233 1.887315300527439 16.72559648960204 + vertex -4.913917191599206 2.470509630441817 16.36286586361541 + endloop +endfacet +facet normal -0.548418 0.836205 -0.000443128 + outer loop + vertex -2.743506408130021 4.766882900654211 10.12470652105002 + vertex -3.276621723325886 4.417437049039737 10.48929820463972 + vertex -2.748401568742806 4.764062217995487 10.8602147235481 + endloop +endfacet +facet normal -0.549563 0.835452 0.000209246 + outer loop + vertex -3.282870743564781 4.412794996489914 12.70690887131546 + vertex -2.753396472126791 4.761177151427969 12.33816155070207 + vertex -3.280719718076403 4.414394424088619 11.97035238303435 + endloop +endfacet +facet normal 0.954806 0.297231 -0.00015108 + outer loop + vertex 5.144340037657432 1.945704390948104 3.946742345627829 + vertex 5.339523148522663 1.318898232006785 4.314904814500256 + vertex 5.339962456935814 1.317118429950786 3.589736816026074 + endloop +endfacet +facet normal 0.10903 0.994038 -0.000300585 + outer loop + vertex 0.9108469727899998 5.424053631017976 13.82232051003361 + vertex 0.9146392260707148 5.42341544472971 13.08738556493957 + vertex 0.2845863738601849 5.492632392197125 13.45117311754784 + endloop +endfacet +facet normal 0.22242 0.974951 0.000301076 + outer loop + vertex 1.529835967906667 5.282953900167885 13.45699023934335 + vertex 0.9146392260707148 5.42341544472971 13.08738556493957 + vertex 0.9108469727899998 5.424053631017976 13.82232051003361 + endloop +endfacet +facet normal -0.79812 0.602499 -0.000484124 + outer loop + vertex -4.575185892217977 3.052486535867045 7.915867117626163 + vertex -4.571761310004581 3.057613207118456 8.650358816856777 + vertex -4.191236072447158 3.561395819761926 8.285876008499198 + endloop +endfacet +facet normal 0.954551 0.298045 -0.00154209 + outer loop + vertex 5.334915080859414 1.337415821657123 5.04147674123994 + vertex 5.339523148522663 1.318898232006785 4.314904814500256 + vertex 5.14467353538835 1.944822412014715 4.67778006254769 + endloop +endfacet +facet normal -0.95743 0.288664 0.000478486 + outer loop + vertex -5.161756596738037 1.899017860903723 12.32305457307666 + vertex -5.350499757292488 1.27363744731891 11.93984222403835 + vertex -5.351863082258487 1.267896505539267 12.6753219338857 + endloop +endfacet +facet normal 0.998338 0.0576356 -0 + outer loop + vertex 5.5 0 8.166666666666657 + vertex 5.463459558418405 0.6329373219573643 8.537037037037026 + vertex 5.5 0 8.907407407407394 + endloop +endfacet +facet normal 0.956159 0.292788 0.00586999 + outer loop + vertex 5.144868400325386 1.944306854211367 8.339749905384522 + vertex 5.343411944396419 1.303053641444466 7.983999811632167 + vertex 5.171106296982572 1.873408568707635 7.60218979976907 + endloop +endfacet +facet normal -0.552012 0.833836 0.000403567 + outer loop + vertex -2.767215262778732 4.753158916914565 15.27200435617937 + vertex -3.292803668559807 4.405388064667978 14.90654265782822 + vertex -3.296898100005449 4.402324717485122 15.63542294950113 + endloop +endfacet +facet normal 0.334984 0.942224 0.000223968 + outer loop + vertex 1.543555395607163 5.278961710477924 11.24658623127648 + vertex 1.540798081005442 5.279767160923855 11.98214227948561 + vertex 2.136595684821637 5.068033038527035 11.61759465937531 + endloop +endfacet +facet normal 0.913795 0.406165 0.00279705 + outer loop + vertex 4.887482158996987 2.5224032479931 6.504905294554623 + vertex 5.153439736913926 1.921473101033819 6.878842079210223 + vertex 5.141258461214585 1.95383249921518 6.159492910637925 + endloop +endfacet +facet normal 0.796088 0.605181 0.000142895 + outer loop + vertex 4.563512583583712 3.069910894386531 9.795523476206014 + vertex 4.562500283604454 3.07141517254006 9.064348170825244 + vertex 4.179409421351509 3.575267387024115 9.429207426964693 + endloop +endfacet +facet normal 0.952804 0.303585 0.00052322 + outer loop + vertex 5.328246086204495 1.363742514130318 16.05340787814411 + vertex 5.136237431772161 1.966993910631783 15.68711310633112 + vertex 5.133866670985064 1.973173333630053 16.41890538970767 + endloop +endfacet +facet normal 0.224643 0.974441 -0.000224935 + outer loop + vertex 0.9247966696185814 5.421692643433634 11.61532331063718 + vertex 1.540798081005442 5.279767160923855 11.98214227948561 + vertex 1.543555395607163 5.278961710477924 11.24658623127648 + endloop +endfacet +facet normal 0.912119 0.409924 -0.00108253 + outer loop + vertex 4.877746635599592 2.541178419335578 15.31515588422337 + vertex 5.136237431772161 1.966993910631783 15.68711310633112 + vertex 5.141115229323106 1.95420935388766 14.9559015917752 + endloop +endfacet +facet normal 0.913098 0.407741 -0.000309041 + outer loop + vertex 4.885654423310991 2.52594157810147 5.773025074018642 + vertex 4.887482158996987 2.5224032479931 6.504905294554623 + vertex 5.141258461214585 1.95383249921518 6.159492910637925 + endloop +endfacet +facet normal -0.644131 0.764916 -0.000403559 + outer loop + vertex -3.292803668559807 4.405388064667978 14.90654265782822 + vertex -3.77886316789521 3.996272407922785 15.27040476235519 + vertex -3.296898100005449 4.402324717485122 15.63542294950113 + endloop +endfacet +facet normal 0.109396 0.993998 0.000340243 + outer loop + vertex 0.2845863738601849 5.492632392197125 13.45117311754784 + vertex 0.9146392260707148 5.42341544472971 13.08738556493957 + vertex 0.2889348960300206 5.492405358843802 12.71628545687114 + endloop +endfacet +facet normal 0.542302 0.840183 0.000129947 + outer loop + vertex 2.712164933028665 4.784784360454462 9.054788706823091 + vertex 2.710732184049698 4.785596203855603 9.784975356056796 + vertex 3.243972728227046 4.44146833136511 9.423277641259309 + endloop +endfacet +facet normal -0.796273 0.604937 -0.000360782 + outer loop + vertex -4.56346141485871 3.069986956828276 6.457894800006025 + vertex -4.182554933290917 3.571587074397573 6.8208155119836 + vertex -4.179585281389481 3.575061800247992 6.092775715699338 + endloop +endfacet +facet normal 0.721347 0.692574 0.000219424 + outer loop + vertex 4.181216983490701 3.573153304431385 10.15965879864028 + vertex 4.179409421351509 3.575267387024115 9.429207426964693 + vertex 3.741330192435993 4.031432548259596 9.789771699872459 + endloop +endfacet +facet normal -0.72191 0.691987 -0.000397336 + outer loop + vertex -3.743532901726796 4.029387225582689 6.461285849362103 + vertex -4.182554933290917 3.571587074397573 6.8208155119836 + vertex -3.747237355031224 4.025942399620068 7.192426533269128 + endloop +endfacet +facet normal -0.452116 0.891959 0.000482898 + outer loop + vertex -2.200460361911674 5.040632321014452 14.90827765617079 + vertex -2.761926079215587 4.75623425967948 14.54357724341185 + vertex -2.767215262778732 4.753158916914565 15.27200435617937 + endloop +endfacet +facet normal -0.643836 0.765163 0.00026803 + outer loop + vertex -3.776397186416806 3.998602792279227 14.54124771470269 + vertex -3.77886316789521 3.996272407922785 15.27040476235519 + vertex -3.292803668559807 4.405388064667978 14.90654265782822 + endloop +endfacet +facet normal 0.795853 0.60549 -0.000530983 + outer loop + vertex 4.179409421351509 3.575267387024115 9.429207426964693 + vertex 4.562500283604454 3.07141517254006 9.064348170825244 + vertex 4.175055378160717 3.580350903094733 8.700074265015786 + endloop +endfacet +facet normal -0.644463 0.764635 0.000347746 + outer loop + vertex -3.296898100005449 4.402324717485122 15.63542294950113 + vertex -3.77886316789521 3.996272407922785 15.27040476235519 + vertex -3.782065424490064 3.993241931673661 15.99930350686742 + endloop +endfacet +facet normal 0.33493 0.942243 0.000125322 + outer loop + vertex 2.136595684821637 5.068033038527035 11.61759465937531 + vertex 1.540798081005442 5.279767160923855 11.98214227948561 + vertex 2.13807510768009 5.067409084918917 12.35499137436904 + endloop +endfacet +facet normal 0.916234 0.400621 0.00424275 + outer loop + vertex 5.171106296982572 1.873408568707635 7.60218979976907 + vertex 5.153439736913926 1.921473101033819 6.878842079210223 + vertex 4.897747251928272 2.502413206532659 7.241119007269643 + endloop +endfacet +facet normal -0.551583 0.83412 -0.000483537 + outer loop + vertex -2.767215262778732 4.753158916914565 15.27200435617937 + vertex -2.761926079215587 4.75623425967948 14.54357724341185 + vertex -3.292803668559807 4.405388064667978 14.90654265782822 + endloop +endfacet +facet normal -0.451189 0.892428 0.000544152 + outer loop + vertex -2.761926079215587 4.75623425967948 14.54357724341185 + vertex -2.195947574048251 5.042599949632293 14.17997266974335 + vertex -2.755934067944267 4.75970875297472 13.81361629833644 + endloop +endfacet +facet normal -0.9181 0.396348 9.21328e-05 + outer loop + vertex -5.168278527335533 1.881195647422789 9.272684386469603 + vertex -4.913313387114148 2.471710250010081 9.64411804727896 + vertex -4.913838183546919 2.47066677354845 8.903493668018529 + endloop +endfacet +facet normal -0.721613 0.692297 0.000360699 + outer loop + vertex -4.179585281389481 3.575061800247992 6.092775715699338 + vertex -4.182554933290917 3.571587074397573 6.8208155119836 + vertex -3.743532901726796 4.029387225582689 6.461285849362103 + endloop +endfacet +facet normal -0.79762 0.603159 0.00107438 + outer loop + vertex -4.187648423468353 3.565613647245452 7.553553388071339 + vertex -4.567633014570769 3.063776859401342 7.184723364159598 + vertex -4.575185892217977 3.052486535867045 7.915867117626163 + endloop +endfacet +facet normal -0.447965 0.894051 0.000199821 + outer loop + vertex -2.741300165584849 4.768151990254136 9.392493992010372 + vertex -2.743506408130021 4.766882900654211 10.12470652105002 + vertex -2.177046150527109 5.050789053056473 9.763260881829368 + endloop +endfacet +facet normal -0.957695 0.287783 0.000341766 + outer loop + vertex -5.164834411129698 1.890630980813162 15.27016150908249 + vertex -5.350973674996689 1.271644891269743 14.88756196999887 + vertex -5.351961835250633 1.267479591165347 15.6259277296983 + endloop +endfacet +facet normal -0.548904 0.835885 -0.000130944 + outer loop + vertex -3.278777122892307 4.415837471918327 11.23609377014295 + vertex -2.749851836277788 4.763225260106819 11.59683773054415 + vertex -2.748401568742806 4.764062217995487 10.8602147235481 + endloop +endfacet +facet normal -0.659225 0.751703 -0.0191079 + outer loop + vertex -3.889087296526017 3.889087296526005 1.5 + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + vertex -3.348187859547972 4.363443371601787 1.5 + endloop +endfacet +facet normal -0.450087 0.892985 -0.000288532 + outer loop + vertex -2.18769581975002 5.046185390990732 11.96868542169703 + vertex -2.753396472126791 4.761177151427969 12.33816155070207 + vertex -2.191088185537281 5.044713328148483 12.70458421599213 + endloop +endfacet +facet normal -0.91697 0.398957 -0.000348733 + outer loop + vertex -4.910007904730391 2.478270036837204 14.16861485224099 + vertex -5.161035683133057 1.900976243256948 13.79485434302383 + vertex -5.159487311214056 1.905174712571303 14.52663788554383 + endloop +endfacet +facet normal -0.86616 0.499768 -0.000165449 + outer loop + vertex -4.914848247313041 2.46865686272595 15.6405238496727 + vertex -4.913917191599206 2.470509630441817 16.36286586361541 + vertex -4.597528200520561 3.018730601663252 15.99861064446014 + endloop +endfacet +facet normal 0.860339 0.509723 -0.000107755 + outer loop + vertex 4.561739448136046 3.072545070022481 8.334534675596213 + vertex 4.562500283604454 3.07141517254006 9.064348170825244 + vertex 4.885815967138671 2.525629096928687 8.70404526328716 + endloop +endfacet +facet normal -0.796605 0.604499 0.000592825 + outer loop + vertex -4.56346141485871 3.069986956828276 6.457894800006025 + vertex -4.567633014570769 3.063776859401342 7.184723364159598 + vertex -4.182554933290917 3.571587074397573 6.8208155119836 + endloop +endfacet +facet normal -0.345397 0.938456 0.000366365 + outer loop + vertex -1.599262890242996 5.262352915558935 13.81085552389677 + vertex -2.191670631422892 5.044460312397986 13.44675804175767 + vertex -2.195947574048251 5.042599949632293 14.17997266974335 + endloop +endfacet +facet normal -0.122735 0.992439 -0.000399938 + outer loop + vertex -0.3614443539624955 5.488110601927464 17.48441322012165 + vertex -0.9889336480867522 5.410361377919393 17.11772481178466 + vertex -0.9839543072603515 5.411269159931319 17.84228907674125 + endloop +endfacet +facet normal -0.917102 0.398653 -0.000610256 + outer loop + vertex -5.1637250567763 1.89365877021722 13.05630710917101 + vertex -5.161035683133057 1.900976243256948 13.79485434302383 + vertex -4.908877155372405 2.480509035150433 13.43011541263371 + endloop +endfacet +facet normal -0.451666 0.892187 -0.000388268 + outer loop + vertex -2.200460361911674 5.040632321014452 14.90827765617079 + vertex -2.195947574048251 5.042599949632293 14.17997266974335 + vertex -2.761926079215587 4.75623425967948 14.54357724341185 + endloop +endfacet +facet normal 0.635456 0.772137 3.16507e-05 + outer loop + vertex 3.243972728227046 4.44146833136511 9.423277641259309 + vertex 3.734233119467835 4.03800730676277 9.061319687521875 + vertex 3.244296841629572 4.441231586327422 8.69153930796214 + endloop +endfacet +facet normal 0.98493 0.172954 -0.000196954 + outer loop + vertex 5.463079625775358 0.6362083011389977 13.72188479775475 + vertex 5.353286605756722 1.261872622979704 14.09259610146606 + vertex 5.462786065058352 0.6387240463645399 14.46303530577151 + endloop +endfacet +facet normal 0.913039 0.40787 -0.00115389 + outer loop + vertex 4.88347787458356 2.530147001352456 13.11008610585002 + vertex 5.140471256908808 1.955902670608734 13.48086883335942 + vertex 5.145654811298226 1.942224642764944 12.74763160945074 + endloop +endfacet +facet normal -0.918485 0.395455 0.000170781 + outer loop + vertex -5.168346033474785 1.881010174950005 8.536010542375871 + vertex -4.918778118388804 2.460817307737309 8.165314093629673 + vertex -5.167592017862487 1.883080650668979 7.796888109715192 + endloop +endfacet +facet normal -0.551151 0.834406 0.000425489 + outer loop + vertex -3.292803668559807 4.405388064667978 14.90654265782822 + vertex -2.761926079215587 4.75623425967948 14.54357724341185 + vertex -3.288483294202905 4.408614025263315 14.17660159336728 + endloop +endfacet +facet normal 0.223274 0.974756 8.61533e-05 + outer loop + vertex 0.9146392260707148 5.42341544472971 13.08738556493957 + vertex 1.536716324117605 5.280956631065102 12.72398985022994 + vertex 0.9157185103458564 5.423233316925427 12.35095009251186 + endloop +endfacet +facet normal 0.860684 0.50914 0.000457099 + outer loop + vertex 4.889422945144919 2.518639168974068 10.16456083156197 + vertex 4.886781835408656 2.523759753447228 9.43401035841212 + vertex 4.563512583583712 3.069910894386531 9.795523476206014 + endloop +endfacet +facet normal -0.346209 0.938157 0.000389364 + outer loop + vertex -1.603762649021274 5.260983307862159 14.5447323978708 + vertex -2.195947574048251 5.042599949632293 14.17997266974335 + vertex -2.200460361911674 5.040632321014452 14.90827765617079 + endloop +endfacet +facet normal 0.333582 0.942721 0.000562474 + outer loop + vertex 2.130062841592538 5.07078221686425 13.09066671338084 + vertex 1.536716324117605 5.280956631065102 12.72398985022994 + vertex 1.529835967906667 5.282953900167885 13.45699023934335 + endloop +endfacet +facet normal -0.79988 0.600158 0.00159324 + outer loop + vertex -4.197232969911694 3.554326292883965 10.49321336546519 + vertex -4.580458097205558 3.044569529464557 10.11690366370986 + vertex -4.59137142082812 3.028086603121313 10.84686772092755 + endloop +endfacet +facet normal -0.799076 0.60123 4.64492e-05 + outer loop + vertex -4.580135555157919 3.045054727977522 9.385342259607349 + vertex -4.580458097205558 3.044569529464557 10.11690366370986 + vertex -4.194572795966226 3.557465257643436 9.755144478608651 + endloop +endfacet +facet normal -0.727934 0.685647 0.00054136 + outer loop + vertex -4.212819464422161 3.535838254245488 14.90743681953956 + vertex -4.217191461647667 3.530622632880213 15.63439694126637 + vertex -3.77886316789521 3.996272407922785 15.27040476235519 + endloop +endfacet +facet normal 0.915465 0.40236 0.00557558 + outer loop + vertex 5.168137311619096 1.88158356929756 11.27368581568632 + vertex 5.143658139205531 1.947506340678945 10.53566889730253 + vertex 4.8960469875539 2.505738193759351 10.90676180332706 + endloop +endfacet +facet normal -0.857224 0.514943 -0.00132165 + outer loop + vertex -4.55240678248791 3.086355858736654 3.531903144838723 + vertex -4.54305039848295 3.100111784572277 2.822942061993703 + vertex -4.866831821449069 2.562020300803789 3.176153595264171 + endloop +endfacet +facet normal -0.549057 0.835785 0.000189964 + outer loop + vertex -3.280719718076403 4.414394424088619 11.97035238303435 + vertex -2.749851836277788 4.763225260106819 11.59683773054415 + vertex -3.278777122892307 4.415837471918327 11.23609377014295 + endloop +endfacet +facet normal 0.331142 0.943562 -0.00590994 + outer loop + vertex 1.502711983249084 5.290733096216402 19.30996315390948 + vertex 1.578298002103966 5.268678716391296 20.02401911919812 + vertex 2.097043851292467 5.084526240049947 19.68886074002475 + endloop +endfacet +facet normal -0.450506 0.892774 4.03785e-05 + outer loop + vertex -2.755934067944267 4.75970875297472 13.81361629833644 + vertex -2.191670631422892 5.044460312397986 13.44675804175767 + vertex -2.755486671513457 4.75996777332701 13.07827609719789 + endloop +endfacet +facet normal -0.642873 0.765973 0.000143328 + outer loop + vertex -3.29025226001403 4.407293961772072 18.55877352661438 + vertex -3.770575664540913 4.004092800869112 18.93615773712017 + vertex -3.288785535624673 4.408388560536143 19.2877628911882 + endloop +endfacet +facet normal -0.728282 0.685277 -0.000350433 + outer loop + vertex -3.77886316789521 3.996272407922785 15.27040476235519 + vertex -4.217191461647667 3.530622632880213 15.63439694126637 + vertex -3.782065424490064 3.993241931673661 15.99930350686742 + endloop +endfacet +facet normal -0.449485 0.893288 -0.000226334 + outer loop + vertex -2.185024418165879 5.047342696114349 11.23106540038434 + vertex -2.749851836277788 4.763225260106819 11.59683773054415 + vertex -2.18769581975002 5.046185390990732 11.96868542169703 + endloop +endfacet +facet normal -0.44829 0.893888 -0.000437525 + outer loop + vertex -2.177046150527109 5.050789053056473 9.763260881829368 + vertex -2.743506408130021 4.766882900654211 10.12470652105002 + vertex -2.182188084779327 5.048569615509638 10.49727345085342 + endloop +endfacet +facet normal -0.728423 0.685127 7.82239e-06 + outer loop + vertex -3.782065424490064 3.993241931673661 15.99930350686742 + vertex -4.217191461647667 3.530622632880213 15.63439694126637 + vertex -4.217254729821125 3.530547060131242 16.36191638614252 + endloop +endfacet +facet normal 0.86051 0.509434 -0.00014328 + outer loop + vertex 4.563512583583712 3.069910894386531 9.795523476206014 + vertex 4.886781835408656 2.523759753447228 9.43401035841212 + vertex 4.562500283604454 3.07141517254006 9.064348170825244 + endloop +endfacet +facet normal -0.640648 0.767835 -0.000423622 + outer loop + vertex -3.760953233344837 4.01313228994423 10.12705573614122 + vertex -3.276621723325886 4.417437049039737 10.48929820463972 + vertex -3.272316987094792 4.420626826137992 9.760825036399151 + endloop +endfacet +facet normal -0.236868 0.971542 -7.10976e-05 + outer loop + vertex -1.610314611093768 5.258981541448679 16.01007290764218 + vertex -1.609463548531972 5.259242063828863 16.73470020974355 + vertex -0.9912954322035247 5.409929146124968 16.38022546614373 + endloop +endfacet +facet normal 0.860418 0.509589 0.00016651 + outer loop + vertex 4.562500283604454 3.07141517254006 9.064348170825244 + vertex 4.886781835408656 2.523759753447228 9.43401035841212 + vertex 4.885815967138671 2.525629096928687 8.70404526328716 + endloop +endfacet +facet normal -0.548003 0.836477 0.000424405 + outer loop + vertex -3.272316987094792 4.420626826137992 9.760825036399151 + vertex -3.276621723325886 4.417437049039737 10.48929820463972 + vertex -2.743506408130021 4.766882900654211 10.12470652105002 + endloop +endfacet +facet normal 0.958162 0.286165 0.00597933 + outer loop + vertex 5.362589343990837 1.221734638829532 11.69335974927695 + vertex 5.34724229625872 1.287245052467388 11.01738851026113 + vertex 5.168137311619096 1.88158356929756 11.27368581568632 + endloop +endfacet +facet normal -0.642566 0.76623 -0.000573533 + outer loop + vertex -3.288785535624673 4.408388560536143 19.2877628911882 + vertex -3.770575664540913 4.004092800869112 18.93615773712017 + vertex -3.765326991561123 4.009028890719206 19.65026233461441 + endloop +endfacet +facet normal -0.860796 0.508951 -0.000591971 + outer loop + vertex -4.887553899212895 2.522264237206092 6.818608522622353 + vertex -4.567633014570769 3.063776859401342 7.184723364159598 + vertex -4.56346141485871 3.069986956828276 6.457894800006025 + endloop +endfacet +facet normal -0.450715 0.892668 -0.000364146 + outer loop + vertex -2.195947574048251 5.042599949632293 14.17997266974335 + vertex -2.191670631422892 5.044460312397986 13.44675804175767 + vertex -2.755934067944267 4.75970875297472 13.81361629833644 + endloop +endfacet +facet normal -0.802691 0.596395 -7.85348e-06 + outer loop + vertex -4.217191461647667 3.530622632880213 15.63439694126637 + vertex -4.597528200520561 3.018730601663252 15.99861064446014 + vertex -4.217254729821125 3.530547060131242 16.36191638614252 + endloop +endfacet +facet normal -0.798056 0.602583 -0.000301355 + outer loop + vertex -4.191236072447158 3.561395819761926 8.285876008499198 + vertex -4.571761310004581 3.057613207118456 8.650358816856777 + vertex -4.193745453649838 3.558440539055181 9.021971072896772 + endloop +endfacet +facet normal 0.912664 0.40871 0.000406717 + outer loop + vertex 4.881074385750622 2.534780629713188 13.84712727035636 + vertex 5.140471256908808 1.955902670608734 13.48086883335942 + vertex 4.88347787458356 2.530147001352456 13.11008610585002 + endloop +endfacet +facet normal 0.984979 0.172676 0.000389715 + outer loop + vertex 5.462588851477699 0.6404084944092698 12.24074074074071 + vertex 5.354099104705792 1.258420747202078 12.61111111111141 + vertex 5.463174314802662 0.635394685278737 12.98255000771282 + endloop +endfacet +facet normal -0.802603 0.596513 -0.000265048 + outer loop + vertex -4.217254729821125 3.530547060131242 16.36191638614252 + vertex -4.597528200520561 3.018730601663252 15.99861064446014 + vertex -4.595698850376898 3.021514864541369 16.72529260868694 + endloop +endfacet +facet normal -0.957442 0.288627 0.000545868 + outer loop + vertex -5.164172210296571 1.892439003614285 11.56467286409568 + vertex -5.350499757292488 1.27363744731891 11.93984222403835 + vertex -5.161756596738037 1.899017860903723 12.32305457307666 + endloop +endfacet +facet normal 0.222913 0.974838 -0.000563833 + outer loop + vertex 1.529835967906667 5.282953900167885 13.45699023934335 + vertex 1.536716324117605 5.280956631065102 12.72398985022994 + vertex 0.9146392260707148 5.42341544472971 13.08738556493957 + endloop +endfacet +facet normal -0.957164 0.289544 0.000616671 + outer loop + vertex -5.1637250567763 1.89365877021722 13.05630710917101 + vertex -5.348365566948149 1.282569983386249 13.39022568509564 + vertex -5.161035683133057 1.900976243256948 13.79485434302383 + endloop +endfacet +facet normal -0.957644 0.287954 0.000178967 + outer loop + vertex -5.166046937107233 1.887315300527439 16.72559648960204 + vertex -5.349945281483502 1.275964531298738 16.34425104958763 + vertex -5.350454380830277 1.273828056942577 17.05762700172786 + endloop +endfacet +facet normal 0.912966 0.408035 -0.000163086 + outer loop + vertex 4.885815967138671 2.525629096928687 8.70404526328716 + vertex 4.886781835408656 2.523759753447228 9.43401035841212 + vertex 5.140219477149498 1.956564265934789 9.09286486955698 + endloop +endfacet +facet normal -0.998373 0.057016 0 + outer loop + vertex -5.5 0 13.35185185185182 + vertex -5.464240887080524 0.6261561530141311 12.98148148148145 + vertex -5.5 0 12.61111111111108 + endloop +endfacet +facet normal -0.984274 0.176645 0.0014059 + outer loop + vertex -5.344337296030745 1.299253195591523 14.11425982063323 + vertex -5.348365566948149 1.282569983386249 13.39022568509564 + vertex -5.461533276369314 0.6493491134287154 13.7223915162698 + endloop +endfacet +facet normal 0.998377 0.0569521 -0 + outer loop + vertex 5.5 0 11.12962962962961 + vertex 5.464321032236196 0.6254563587182973 11.49999999999998 + vertex 5.5 0 11.87037037037035 + endloop +endfacet +facet normal -0.98463 0.174653 -0.000179615 + outer loop + vertex -5.350454380830277 1.273828056942577 17.05762700172786 + vertex -5.349945281483502 1.275964531298738 16.34425104958763 + vertex -5.462288539552118 0.642964937362526 16.6854252851455 + endloop +endfacet +facet normal -0.918136 0.396266 0.000247509 + outer loop + vertex -5.16934903317279 1.878251999396124 10.01446444154432 + vertex -4.913313387114148 2.471710250010081 9.64411804727896 + vertex -5.168278527335533 1.881195647422789 9.272684386469603 + endloop +endfacet +facet normal 0.914285 0.405071 -0.000466121 + outer loop + vertex 4.889422945144919 2.518639168974068 10.16456083156197 + vertex 5.151436855319887 1.926836351549336 9.806356433593624 + vertex 4.886781835408656 2.523759753447228 9.43401035841212 + endloop +endfacet +facet normal -0.957425 0.288679 -0.00123867 + outer loop + vertex -5.159487311214056 1.905174712571303 14.52663788554383 + vertex -5.350973674996689 1.271644891269743 14.88756196999887 + vertex -5.164834411129698 1.890630980813162 15.27016150908249 + endloop +endfacet +facet normal -0.866036 0.499982 0.000264492 + outer loop + vertex -4.597528200520561 3.018730601663252 15.99861064446014 + vertex -4.913917191599206 2.470509630441817 16.36286586361541 + vertex -4.595698850376898 3.021514864541369 16.72529260868694 + endloop +endfacet +facet normal -0.917006 0.398873 -0.000194758 + outer loop + vertex -4.908877155372405 2.480509035150433 13.43011541263371 + vertex -5.161035683133057 1.900976243256948 13.79485434302383 + vertex -4.910007904730391 2.478270036837204 14.16861485224099 + endloop +endfacet +facet normal -0.998336 0.0576644 0 + outer loop + vertex -5.5 0 16.3148148148148 + vertex -5.463422928156496 0.6332534311742012 15.94624735955442 + vertex -5.5 0 15.57407407407405 + endloop +endfacet +facet normal 0.946805 0.321497 -0.0141773 + outer loop + vertex 5.208115712223082 1.767917059167386 20.87706280989174 + vertex 5.292980130030065 1.494778024693604 20.35063719267036 + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + endloop +endfacet +facet normal -0.865962 0.50011 5.54945e-06 + outer loop + vertex -4.595698850376898 3.021514864541369 16.72529260868694 + vertex -4.913917191599206 2.470509630441817 16.36286586361541 + vertex -4.913948422163426 2.470447510941608 17.08763577686084 + endloop +endfacet +facet normal -0.91 0.414548 0.00710298 + outer loop + vertex -4.866831821449069 2.562020300803789 3.176153595264171 + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + vertex -5.141451880835366 1.953323464522575 3.518268699072249 + endloop +endfacet +facet normal 0.913839 0.406075 -0.00109747 + outer loop + vertex 4.8960469875539 2.505738193759351 10.90676180332706 + vertex 5.143658139205531 1.947506340678945 10.53566889730253 + vertex 4.889422945144919 2.518639168974068 10.16456083156197 + endloop +endfacet +facet normal -0.917894 0.396826 -5.54072e-06 + outer loop + vertex -4.913917191599206 2.470509630441817 16.36286586361541 + vertex -5.166046937107233 1.887315300527439 16.72559648960204 + vertex -4.913948422163426 2.470447510941608 17.08763577686084 + endloop +endfacet +facet normal -0.799201 0.601063 -0.000324222 + outer loop + vertex -4.194572795966226 3.557465257643436 9.755144478608651 + vertex -4.580458097205558 3.044569529464557 10.11690366370986 + vertex -4.197232969911694 3.554326292883965 10.49321336546519 + endloop +endfacet +facet normal 0.913996 0.40572 -0.00175031 + outer loop + vertex 5.143658139205531 1.947506340678945 10.53566889730253 + vertex 5.151436855319887 1.926836351549336 9.806356433593624 + vertex 4.889422945144919 2.518639168974068 10.16456083156197 + endloop +endfacet +facet normal -0.917927 0.39675 0.000138779 + outer loop + vertex -4.913948422163426 2.470447510941608 17.08763577686084 + vertex -5.166046937107233 1.887315300527439 16.72559648960204 + vertex -5.166641334823746 1.885687491948415 17.44774793172886 + endloop +endfacet +facet normal 0.114358 0.99344 0.000336753 + outer loop + vertex 0.3070111775077362 5.491424599945383 20.04433390229711 + vertex 0.9465461948198692 5.417937827353875 19.65513716806774 + vertex 0.3112636309729526 5.491185204674263 19.3064763842535 + endloop +endfacet +facet normal -0.441546 0.897171 0.0109595 + outer loop + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + vertex -2.109161857118958 5.079511419464918 20.51052818313118 + vertex -2.204987976597974 5.038653393820454 19.99453580293805 + endloop +endfacet +facet normal -0.957628 0.288006 8.74559e-05 + outer loop + vertex -5.166420226055012 1.886293203033316 16.0040728052201 + vertex -5.349945281483502 1.275964531298738 16.34425104958763 + vertex -5.166046937107233 1.887315300527439 16.72559648960204 + endloop +endfacet +facet normal 0.913577 0.406658 0.00258048 + outer loop + vertex 4.886781835408656 2.523759753447228 9.43401035841212 + vertex 5.151436855319887 1.926836351549336 9.806356433593624 + vertex 5.140219477149498 1.956564265934789 9.09286486955698 + endloop +endfacet +facet normal -0.956802 0.290738 -0.00137589 + outer loop + vertex -5.161035683133057 1.900976243256948 13.79485434302383 + vertex -5.348365566948149 1.282569983386249 13.39022568509564 + vertex -5.344337296030745 1.299253195591523 14.11425982063323 + endloop +endfacet +facet normal -0.725888 0.687813 0.000580931 + outer loop + vertex -3.765326991561123 4.009028890719206 19.65026233461441 + vertex -3.770575664540913 4.004092800869112 18.93615773712017 + vertex -4.203565089212222 3.546835285258711 19.28997812941705 + endloop +endfacet +facet normal 0.980602 0.195054 -0.0193205 + outer loop + vertex 5.312592044589874 1.423504748063868 1.5 + vertex 5.388402417417908 1.102324538402753 2.105178344957057 + vertex 5.452946737555957 0.7178940572102837 1.5 + endloop +endfacet +facet normal 0.112962 0.993595 0.00291277 + outer loop + vertex 0.3112636309729526 5.491185204674263 19.3064763842535 + vertex 0.9465461948198692 5.417937827353875 19.65513716806774 + vertex 0.9098219135290052 5.424225666918958 18.93447455121602 + endloop +endfacet +facet normal -0.547983 0.83648 0.00397285 + outer loop + vertex -3.318372368152656 4.386160601970809 20.71529429688674 + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + vertex -3.283048353747241 4.412662858972746 20.00757501231982 + endloop +endfacet +facet normal -0.450087 0.892976 -0.00397552 + outer loop + vertex -2.75983315162458 4.757448998696038 19.64732542503119 + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + vertex -2.204987976597974 5.038653393820454 19.99453580293805 + endloop +endfacet +facet normal -0.000347992 0.999999 -0.00130458 + outer loop + vertex 0.3484132606717201 5.488953288176909 2.493006867666852 + vertex 0.3597172107657752 5.48822407781232 1.931031098542516 + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + endloop +endfacet +facet normal -0.917033 0.398809 0.00164 + outer loop + vertex -5.167666710260322 1.882875665482789 19.64864303455607 + vertex -4.896125033036498 2.505585692183236 20.05737357636656 + vertex -4.904911767396387 2.488340924000661 19.3376449252274 + endloop +endfacet +facet normal -0.793241 0.608907 0.00134593 + outer loop + vertex -4.16358638277272 3.593681737882416 3.170864763690249 + vertex -4.54305039848295 3.100111784572277 2.822942061993703 + vertex -4.55240678248791 3.086355858736654 3.531903144838723 + endloop +endfacet +facet normal -0.91677 0.399414 0.000543449 + outer loop + vertex -5.169860313545367 1.876844249912228 20.38100790963064 + vertex -4.896125033036498 2.505585692183236 20.05737357636656 + vertex -5.167666710260322 1.882875665482789 19.64864303455607 + endloop +endfacet +facet normal 0.983694 0.179799 -0.00419683 + outer loop + vertex 5.339523148522663 1.318898232006785 4.314904814500256 + vertex 5.45702188206679 0.6862304122116961 4.750840592067621 + vertex 5.462588851477747 0.6404084944088623 4.092592592592588 + endloop +endfacet +facet normal -0.436777 0.899346 0.0200856 + outer loop + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + vertex -2.104344891793729 5.081508887759781 2.602739678337935 + vertex -2.43213297513447 4.933024345294026 2.123228765692299 + endloop +endfacet +facet normal -0.566226 0.824247 0.00234778 + outer loop + vertex -3.348187859547959 4.363443371601797 21.5 + vertex -2.892047726267587 4.678253942336872 20.98740566256392 + vertex -3.318372368152656 4.386160601970809 20.71529429688674 + endloop +endfacet +facet normal 0.54266 0.839947 0.00294652 + outer loop + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + vertex 3.24533634122458 4.440472050618836 20.27797987500447 + vertex 3.219421791503083 4.459296281746155 19.68454339005858 + endloop +endfacet +facet normal -0.258551 0.965853 0.0166844 + outer loop + vertex -1.608551244610577 5.259521165796537 20.38119086934289 + vertex -1.78001861476601 5.203992095601847 20.93858895746985 + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + endloop +endfacet +facet normal -0.957751 0.287599 -0.000708468 + outer loop + vertex -5.351961835250633 1.267479591165347 15.6259277296983 + vertex -5.349945281483502 1.275964531298738 16.34425104958763 + vertex -5.166420226055012 1.886293203033316 16.0040728052201 + endloop +endfacet +facet normal 0.126795 0.991899 0.00768452 + outer loop + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + vertex 1.072996771088712 5.394319042217766 21.04016115450814 + vertex 1.001653684937865 5.408020885263887 20.44872268839708 + endloop +endfacet +facet normal -0.863742 0.503933 -0.00152937 + outer loop + vertex -4.904911767396387 2.488340924000661 19.3376449252274 + vertex -4.896125033036498 2.505585692183236 20.05737357636656 + vertex -4.585867558739597 3.036415441552708 19.74358804414167 + endloop +endfacet +facet normal -0.794575 0.607165 -0.0011699 + outer loop + vertex -4.578874889937365 3.046950072170709 20.49484434252649 + vertex -4.573082867663999 3.055636281607812 21.0690550638699 + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + endloop +endfacet +facet normal 0.443358 0.89634 -0.00284664 + outer loop + vertex 2.725396144507114 4.777260287602693 3.226181988385524 + vertex 2.750048563129589 4.763111682548383 2.61068253831418 + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + endloop +endfacet +facet normal -0.644065 0.764967 -0.00232594 + outer loop + vertex -3.318372368152656 4.386160601970809 20.71529429688674 + vertex -3.748758334197043 4.024526177301897 20.95523197930691 + vertex -3.348187859547959 4.363443371601797 21.5 + endloop +endfacet +facet normal -0.131072 0.991371 0.00209663 + outer loop + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + vertex -0.3597172107657781 5.48822407781232 21.06620305504513 + vertex -0.3783033396193837 5.486974264859716 20.49523979426701 + endloop +endfacet +facet normal -0.434521 0.900367 -0.02303 + outer loop + vertex -2.432587796204501 4.932800078429788 20.87706280989174 + vertex -2.109161857118958 5.079511419464918 20.51052818313118 + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + endloop +endfacet +facet normal 0.984554 0.175078 0.0012317 + outer loop + vertex 5.462588851477699 0.6404084944092698 10.75925925925924 + vertex 5.34724229625872 1.287245052467388 11.01738851026113 + vertex 5.464321032236196 0.6254563587182973 11.49999999999998 + endloop +endfacet +facet normal 0.226552 0.97398 0.00610082 + outer loop + vertex 1.502711983249084 5.290733096216402 19.30996315390948 + vertex 0.9465461948198692 5.417937827353875 19.65513716806774 + vertex 1.578298002103966 5.268678716391296 20.02401911919812 + endloop +endfacet +facet normal -0.921564 0.388164 0.00700399 + outer loop + vertex -5.169860313545367 1.876844249912228 20.38100790963064 + vertex -5.194608072678547 1.807220786529104 20.9833334078545 + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + endloop +endfacet +facet normal 0.982994 0.183632 0.00155426 + outer loop + vertex 5.334915080859414 1.337415821657123 5.04147674123994 + vertex 5.45702188206679 0.6862304122116961 4.750840592067621 + vertex 5.339523148522663 1.318898232006785 4.314904814500256 + endloop +endfacet +facet normal -0.793604 0.608433 -0.00136049 + outer loop + vertex -4.142727898941744 3.617707223550536 2.454219851588245 + vertex -4.135091253779056 3.626433554185152 1.902145778937794 + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + endloop +endfacet +facet normal 0.984772 0.17385 -3.05453e-05 + outer loop + vertex 5.462634190338693 0.6400216422455829 7.056229042449417 + vertex 5.351612161616004 1.268955188981735 7.330746350623435 + vertex 5.462588851477699 0.6404084944092698 7.796296296296289 + endloop +endfacet +facet normal 0.647767 0.761815 -0.0059654 + outer loop + vertex 3.753167914507547 4.02041423307488 3.213151815948938 + vertex 3.799593247494868 3.976567760467738 2.654917871642895 + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + endloop +endfacet +facet normal 0.998367 0.0567333 -0.0066703 + outer loop + vertex 5.5 0 17.05555555555554 + vertex 5.458193291725775 0.6768500499813518 16.55505310407936 + vertex 5.466427009523622 0.6067748755103708 17.19140785290995 + endloop +endfacet +facet normal -0.998763 0.0497199 0 + outer loop + vertex -5.5 0 21.5 + vertex -5.472807214829338 0.5462427933730074 20.94680099274967 + vertex -5.5 0 20.75925925925926 + endloop +endfacet +facet normal -0.997739 0.0653952 0.0155286 + outer loop + vertex -5.452946737555957 0.7178940572102843 21.5 + vertex -5.472807214829338 0.5462427933730074 20.94680099274967 + vertex -5.5 0 21.5 + endloop +endfacet +facet normal -0.957445 0.288614 -0.00123975 + outer loop + vertex -5.351863082258487 1.267896505539267 12.6753219338857 + vertex -5.348365566948149 1.282569983386249 13.39022568509564 + vertex -5.1637250567763 1.89365877021722 13.05630710917101 + endloop +endfacet +facet normal 0.963213 0.268419 -0.0131409 + outer loop + vertex 5.312592044589876 1.423504748063862 21.5 + vertex 5.370087155850409 1.188345041884078 20.9108902288276 + vertex 5.208115712223082 1.767917059167386 20.87706280989174 + endloop +endfacet +facet normal 0.965058 0.261428 0.017853 + outer loop + vertex 5.207331238571131 1.770226361740569 2.112773058852293 + vertex 5.388402417417908 1.102324538402753 2.105178344957057 + vertex 5.312592044589874 1.423504748063868 1.5 + endloop +endfacet +facet normal -0.96516 0.26088 0.0201966 + outer loop + vertex -5.312592044589876 1.423504748063862 1.5 + vertex -5.389615255505637 1.0963792216295 2.044677887217381 + vertex -5.202761293209437 1.783612885656994 2.097099159738966 + endloop +endfacet +facet normal 0.9988 0.0489813 -0 + outer loop + vertex 5.5 0 1.5 + vertex 5.473609142205703 0.5381477105425145 2.044517851335947 + vertex 5.5 0 2.24074074074074 + endloop +endfacet +facet normal 0.997727 0.0653945 -0.0162731 + outer loop + vertex 5.452946737555957 0.7178940572102837 1.5 + vertex 5.473609142205703 0.5381477105425145 2.044517851335947 + vertex 5.5 0 1.5 + endloop +endfacet +facet normal 0.632052 0.774919 -0.00317407 + outer loop + vertex 3.706797571246544 4.063207078872638 20.06301800731393 + vertex 3.24533634122458 4.440472050618836 20.27797987500447 + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + endloop +endfacet +facet normal 0.98436 0.176142 0.00316234 + outer loop + vertex 5.462588851477699 0.6404084944092698 7.796296296296289 + vertex 5.351612161616004 1.268955188981735 7.330746350623435 + vertex 5.343411944396419 1.303053641444466 7.983999811632167 + endloop +endfacet +facet normal 0.98542 0.170035 -0.00589409 + outer loop + vertex 5.464321032236196 0.6254563587182973 11.49999999999998 + vertex 5.34724229625872 1.287245052467388 11.01738851026113 + vertex 5.362589343990837 1.221734638829532 11.69335974927695 + endloop +endfacet +facet normal -0.261555 0.964969 -0.0205689 + outer loop + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + vertex -1.78001861476601 5.203992095601847 20.93858895746985 + vertex -1.423504748063857 5.312592044589877 21.5 + endloop +endfacet +facet normal -0.382143 0.923904 -0.0191944 + outer loop + vertex -2.104758878007986 5.081337428812081 21.5 + vertex -1.78001861476601 5.203992095601847 20.93858895746985 + vertex -2.432587796204501 4.932800078429788 20.87706280989174 + endloop +endfacet +facet normal -0.861314 0.508073 -0.0010519 + outer loop + vertex -4.567633014570769 3.063776859401342 7.184723364159598 + vertex -4.888301959121175 2.520814145559345 7.500407855524626 + vertex -4.575185892217977 3.052486535867045 7.915867117626163 + endloop +endfacet +facet normal 0.98488 0.172394 0.0170636 + outer loop + vertex 5.462588851477742 0.6404084944089036 18.16666666666666 + vertex 5.430619032632266 0.8708483923233669 17.68377109348667 + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + endloop +endfacet +facet normal 0.904269 0.426954 0.00268294 + outer loop + vertex 4.854264491803782 2.58575254879754 19.70841037355992 + vertex 4.839878840573146 2.612579722912267 20.28782012505717 + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + endloop +endfacet +facet normal -0.987752 0.155871 0.00709365 + outer loop + vertex -5.464008635492013 0.6281796170433402 20.37153635718997 + vertex -5.472807214829338 0.5462427933730074 20.94680099274967 + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + endloop +endfacet +facet normal -0.863666 0.50403 0.00589406 + outer loop + vertex -4.575185892217977 3.052486535867045 7.915867117626163 + vertex -4.888301959121175 2.520814145559345 7.500407855524626 + vertex -4.918778118388804 2.460817307737309 8.165314093629673 + endloop +endfacet +facet normal 0.998098 0.0616491 -0 + outer loop + vertex 5.5 0 16.3148148148148 + vertex 5.458193291725775 0.6768500499813518 16.55505310407936 + vertex 5.5 0 17.05555555555554 + endloop +endfacet +facet normal 0.331928 0.943296 -0.00398213 + outer loop + vertex 2.124213978274041 5.073235158604929 2.788845339764787 + vertex 1.511780695860853 5.288148932057651 2.649115272515396 + vertex 1.551714848063318 5.276569058611839 3.234735469707145 + endloop +endfacet +facet normal -0.906118 0.422985 -0.0057944 + outer loop + vertex -4.866831821449069 2.562020300803789 3.176153595264171 + vertex -4.839134342495119 2.613958457069342 2.63629885568169 + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + endloop +endfacet +facet normal 0.866416 0.49903 0.0170688 + outer loop + vertex 4.937890359975085 2.422238384813751 20.87762820958706 + vertex 4.839878840573146 2.612579722912267 20.28782012505717 + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + endloop +endfacet +facet normal 0.549197 0.835486 0.0185811 + outer loop + vertex 3.056057912944187 4.572801114495492 2.123228765692188 + vertex 2.750048563129589 4.763111682548383 2.61068253831418 + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + endloop +endfacet +facet normal 0.221325 0.975196 -0.00276985 + outer loop + vertex 0.9098219135290052 5.424225666918958 18.93447455121602 + vertex 0.9465461948198692 5.417937827353875 19.65513716806774 + vertex 1.502711983249084 5.290733096216402 19.30996315390948 + endloop +endfacet +facet normal -0.548148 0.83637 0.00435724 + outer loop + vertex -3.283048353747241 4.412662858972746 20.00757501231982 + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + vertex -2.75983315162458 4.757448998696038 19.64732542503119 + endloop +endfacet +facet normal 0.952633 0.304119 -0.00149335 + outer loop + vertex 5.325260662794209 1.375354090151543 2.800753329925892 + vertex 5.1359082938614 1.967853144176588 2.671362177826976 + vertex 5.141289816700485 1.953749989300548 3.23223805190901 + endloop +endfacet +facet normal 0.44094 0.897529 -0.00365194 + outer loop + vertex 2.097043851292467 5.084526240049947 19.68886074002475 + vertex 2.131499096350572 5.070178655851951 20.32286341520533 + vertex 2.720493268386848 4.780054013989993 20.1355866987175 + endloop +endfacet +facet normal -0.547958 0.836493 -0.00461732 + outer loop + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + vertex -3.287161039918808 4.409600015606847 2.626292319656475 + vertex -3.249137396094532 4.437691537421236 3.203031802015037 + endloop +endfacet +facet normal 0.790478 0.612115 -0.0214467 + outer loop + vertex 4.573082867664001 3.055636281607808 20.87706280989174 + vertex 4.13511894113438 3.626401983050373 21.02504478767688 + vertex 4.363443371601798 3.348187859547958 21.5 + endloop +endfacet +facet normal -0.212679 0.977102 -0.0062909 + outer loop + vertex -0.9278248657095747 5.421175243300202 3.223427943000292 + vertex -0.8586654316901362 5.432558667554396 2.653402613207058 + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + endloop +endfacet +facet normal 0.986705 0.162262 -0.00920307 + outer loop + vertex 5.452946737555957 0.7178940572102823 21.5 + vertex 5.471007922370094 0.5639790008179997 20.72270400351366 + vertex 5.370087155850409 1.188345041884078 20.9108902288276 + endloop +endfacet +facet normal 0.962757 0.269943 0.0151433 + outer loop + vertex 5.370087155850409 1.188345041884078 20.9108902288276 + vertex 5.292980130030065 1.494778024693604 20.35063719267036 + vertex 5.208115712223082 1.767917059167386 20.87706280989174 + endloop +endfacet +facet normal 0.132899 0.990846 -0.0236999 + outer loop + vertex 0.7178940572102935 5.452946737555956 21.5 + vertex 1.072996771088712 5.394319042217766 21.04016115450814 + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + endloop +endfacet +facet normal 0.252912 0.967264 -0.0208685 + outer loop + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + vertex 1.072996771088712 5.394319042217766 21.04016115450814 + vertex 1.423504748063873 5.312592044589874 21.5 + endloop +endfacet +facet normal -0.555497 0.83136 0.0162632 + outer loop + vertex -2.749999999999996 4.763139720814415 21.5 + vertex -2.892047726267587 4.678253942336872 20.98740566256392 + vertex -3.348187859547959 4.363443371601797 21.5 + endloop +endfacet +facet normal -0.00745452 0.999753 -0.0209579 + outer loop + vertex 0.3350879141233212 5.489782881845919 20.89342764300288 + vertex -0.3597172107657781 5.48822407781232 21.06620305504513 + vertex 1.078026285860484e-14 5.5 21.5 + endloop +endfacet +facet normal -0.124684 0.991946 -0.0222815 + outer loop + vertex -0.7178940572102771 5.452946737555958 21.5 + vertex -0.3597172107657781 5.48822407781232 21.06620305504513 + vertex -1.072996771088696 5.394319042217769 20.87706280989174 + endloop +endfacet +facet normal 0.00595907 0.999733 0.0223399 + outer loop + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + vertex 0.3597172107657752 5.48822407781232 1.931031098542516 + vertex -1.13279746910902e-14 5.5 1.5 + endloop +endfacet +facet normal 0.124583 0.991958 0.0223399 + outer loop + vertex 0.717894057210274 5.452946737555958 1.5 + vertex 0.3597172107657752 5.48822407781232 1.931031098542516 + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + endloop +endfacet +facet normal -0.797598 0.602816 -0.0212244 + outer loop + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + vertex -4.573082867663999 3.055636281607812 21.0690550638699 + vertex -4.363443371601792 3.348187859547965 21.5 + endloop +endfacet +facet normal 0.796792 0.60384 0.0223619 + outer loop + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + vertex 4.573082867663997 3.055636281607814 1.92999455336682 + vertex 4.36344337160179 3.348187859547969 1.5 + endloop +endfacet +facet normal -0.862383 0.505796 -0.0216087 + outer loop + vertex -4.763139720814412 2.750000000000003 21.5 + vertex -4.573082867663999 3.055636281607812 21.0690550638699 + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + endloop +endfacet +facet normal 0.862795 0.50506 0.0223619 + outer loop + vertex 4.763139720814412 2.750000000000002 1.5 + vertex 4.573082867663997 3.055636281607814 1.92999455336682 + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + endloop +endfacet +facet normal 0.979251 0.202578 -0.00536497 + outer loop + vertex 5.349734657419031 1.276847326507629 18.25045753221189 + vertex 5.430619032632266 0.8708483923233669 17.68377109348667 + vertex 5.325937770498046 1.372729712937804 17.5273430786013 + endloop +endfacet +facet normal -0.788831 0.614181 0.0229713 + outer loop + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + vertex -4.135091253779056 3.626433554185152 1.902145778937794 + vertex -4.363443371601797 3.348187859547959 1.5 + endloop +endfacet +facet normal 0.955442 0.294962 -0.0112905 + outer loop + vertex 5.141115229323106 1.95420935388766 14.9559015917752 + vertex 5.324109977345409 1.379801778927347 15.43526584087152 + vertex 5.352885295866843 1.263573903375872 14.83390153907896 + endloop +endfacet +facet normal 0.952566 0.304331 0.00103347 + outer loop + vertex 5.136237431772161 1.966993910631783 15.68711310633112 + vertex 5.324109977345409 1.379801778927347 15.43526584087152 + vertex 5.141115229323106 1.95420935388766 14.9559015917752 + endloop +endfacet +facet normal -0.961797 0.273254 -0.0166928 + outer loop + vertex -5.312592044589875 1.423504748063864 21.5 + vertex -5.194608072678547 1.807220786529104 20.9833334078545 + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + endloop +endfacet +facet normal 0.336281 0.941757 0.0030367 + outer loop + vertex 1.578298002103966 5.268678716391296 20.02401911919812 + vertex 2.131499096350572 5.070178655851951 20.32286341520533 + vertex 2.097043851292467 5.084526240049947 19.68886074002475 + endloop +endfacet +facet normal -0.711762 0.70204 0.023119 + outer loop + vertex -3.889087296526017 3.889087296526005 1.5 + vertex -4.135091253779056 3.626433554185152 1.902145778937794 + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + endloop +endfacet +facet normal -0.65925 0.75173 0.0170746 + outer loop + vertex -3.348187859547959 4.363443371601797 21.5 + vertex -3.748758334197043 4.024526177301897 20.95523197930691 + vertex -3.889087296526007 3.889087296526016 21.5 + endloop +endfacet +facet normal -0.998715 0.0506735 0 + outer loop + vertex -5.5 0 2.24074074074074 + vertex -5.471754212788627 0.556691867041289 2.02393833416575 + vertex -5.5 0 1.5 + endloop +endfacet +facet normal -0.913137 0.407639 -0.00329213 + outer loop + vertex -5.148581317488049 1.934453519010737 6.435756342408597 + vertex -5.134331014646105 1.971964764402015 7.127875330178659 + vertex -4.887553899212895 2.522264237206092 6.818608522622353 + endloop +endfacet +facet normal -0.91248 0.40912 -0.000131018 + outer loop + vertex -5.134331014646105 1.971964764402015 7.127875330178659 + vertex -4.888301959121175 2.520814145559345 7.500407855524626 + vertex -4.887553899212895 2.522264237206092 6.818608522622353 + endloop +endfacet +facet normal -0.442364 0.896821 -0.00514918 + outer loop + vertex -2.150872866283984 5.061990311437125 3.200430427666638 + vertex -2.104344891793729 5.081508887759781 2.602739678337935 + vertex -2.739328359261481 4.769285076418247 2.774564735238041 + endloop +endfacet +facet normal 0.71497 0.698967 -0.0162182 + outer loop + vertex 3.889087296526017 3.889087296526005 21.5 + vertex 4.13511894113438 3.626401983050373 21.02504478767688 + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + endloop +endfacet +facet normal -0.954962 0.296685 -0.00509342 + outer loop + vertex -5.345708653247237 1.2935992403359 6.066073096927131 + vertex -5.331206571821438 1.35212295615743 6.756020103499217 + vertex -5.148581317488049 1.934453519010737 6.435756342408597 + endloop +endfacet +facet normal -0.953649 0.300904 0.00332672 + outer loop + vertex -5.148581317488049 1.934453519010737 6.435756342408597 + vertex -5.331206571821438 1.35212295615743 6.756020103499217 + vertex -5.134331014646105 1.971964764402015 7.127875330178659 + endloop +endfacet +facet normal -0.997736 0.0653951 -0.0156947 + outer loop + vertex -5.5 0 1.5 + vertex -5.471754212788627 0.556691867041289 2.02393833416575 + vertex -5.452946737555957 0.7178940572102825 1.5 + endloop +endfacet +facet normal -0.861012 0.508585 0.000137001 + outer loop + vertex -4.887553899212895 2.522264237206092 6.818608522622353 + vertex -4.888301959121175 2.520814145559345 7.500407855524626 + vertex -4.567633014570769 3.063776859401342 7.184723364159598 + endloop +endfacet +facet normal -0.107624 0.994187 0.00309735 + outer loop + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + vertex -0.8586654316901362 5.432558667554396 2.653402613207058 + vertex -0.3116778562646466 5.491161708956882 2.849244344490732 + endloop +endfacet +facet normal -0.329469 0.943993 0.0180775 + outer loop + vertex -1.767917059167402 5.208115712223076 2.122937190108266 + vertex -2.104344891793729 5.081508887759781 2.602739678337935 + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + endloop +endfacet +facet normal -0.131558 0.991112 -0.0197376 + outer loop + vertex -1.086182840163288 5.391679407915015 2.117161111770399 + vertex -0.8586654316901362 5.432558667554396 2.653402613207058 + vertex -0.3597172107657976 5.488224077812318 2.122937190108267 + endloop +endfacet +facet normal 0.983042 0.183368 0.0021668 + outer loop + vertex 5.459976604308243 0.6623107128883186 5.434561843950101 + vertex 5.45702188206679 0.6862304122116961 4.750840592067621 + vertex 5.334915080859414 1.337415821657123 5.04147674123994 + endloop +endfacet +facet normal 0.980629 0.195059 0.0178427 + outer loop + vertex 5.452946737555957 0.7178940572102823 21.5 + vertex 5.370087155850409 1.188345041884078 20.9108902288276 + vertex 5.312592044589876 1.423504748063862 21.5 + endloop +endfacet +facet normal 0.725858 0.687826 0.0050588 + outer loop + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + vertex 3.799593247494868 3.976567760467738 2.654917871642895 + vertex 4.187714980302149 3.56553547784242 2.852014943758265 + endloop +endfacet +facet normal -0.922885 0.3846 -0.019156 + outer loop + vertex -4.927169266073214 2.443972795156185 20.88306788392188 + vertex -5.194608072678547 1.807220786529104 20.9833334078545 + vertex -5.081337428812076 2.104758878007997 21.5 + endloop +endfacet +facet normal 0.225806 0.974137 0.0082562 + outer loop + vertex 0.9376243172597151 5.419488964808698 2.855592952321005 + vertex 1.511780695860853 5.288148932057651 2.649115272515396 + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + endloop +endfacet +facet normal -0.980558 0.195045 -0.02152 + outer loop + vertex -5.452946737555957 0.7178940572102825 1.5 + vertex -5.389615255505637 1.0963792216295 2.044677887217381 + vertex -5.312592044589876 1.423504748063862 1.5 + endloop +endfacet +facet normal 0.913425 0.406955 0.00656751 + outer loop + vertex 4.887805760937779 2.521776128712354 2.854314542228816 + vertex 5.1359082938614 1.967853144176588 2.671362177826976 + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + endloop +endfacet +facet normal 0.381353 0.924171 0.0218566 + outer loop + vertex 2.432132975136189 4.933024345293179 20.87677123430906 + vertex 2.131499096350572 5.070178655851951 20.32286341520533 + vertex 1.762221326863038 5.210045680716155 20.8519498900513 + endloop +endfacet +facet normal 0.706433 0.707493 -0.0201391 + outer loop + vertex 3.619021558537723 4.141579766084337 2.117809182156318 + vertex 3.799593247494868 3.976567760467738 2.654917871642895 + vertex 4.135118941134372 3.626401983050384 2.122937190108265 + endloop +endfacet +facet normal 0.984413 0.17581 -0.00466636 + outer loop + vertex 5.339527180018263 1.318881910500791 6.662341264607266 + vertex 5.351612161616004 1.268955188981735 7.330746350623435 + vertex 5.462634190338693 0.6400216422455829 7.056229042449417 + endloop +endfacet +facet normal 0.552781 0.833321 0.00298464 + outer loop + vertex 3.325866532158372 4.380480773872754 2.79611785871209 + vertex 2.750048563129589 4.763111682548383 2.61068253831418 + vertex 2.725396144507114 4.777260287602693 3.226181988385524 + endloop +endfacet +facet normal 0.974465 0.224249 -0.0114606 + outer loop + vertex 5.417922838555951 0.9466319852264811 20.24864700637255 + vertex 5.292980130030065 1.494778024693604 20.35063719267036 + vertex 5.370087155850409 1.188345041884078 20.9108902288276 + endloop +endfacet +facet normal -0.326281 0.945257 0.00546915 + outer loop + vertex -1.462545165044713 5.301977144443791 2.787068339613679 + vertex -2.104344891793729 5.081508887759781 2.602739678337935 + vertex -2.150872866283984 5.061990311437125 3.200430427666638 + endloop +endfacet +facet normal -0.946691 0.321358 0.0224825 + outer loop + vertex -5.081337428812076 2.104758878007997 21.5 + vertex -5.194608072678547 1.807220786529104 20.9833334078545 + vertex -5.312592044589875 1.423504748063864 21.5 + endloop +endfacet +facet normal 0.711708 0.702471 -0.00246765 + outer loop + vertex 3.673087139750667 4.093706250306472 20.79634919387151 + vertex 4.13511894113438 3.626401983050373 21.02504478767688 + vertex 4.151017607888463 3.608192458697283 20.42672570575831 + endloop +endfacet +facet normal 0.92356 0.383058 -0.0174354 + outer loop + vertex 4.932800078429784 2.432587796204511 2.122937190108266 + vertex 5.1359082938614 1.967853144176588 2.671362177826976 + vertex 5.207331238571131 1.770226361740569 2.112773058852293 + endloop +endfacet +facet normal -0.321369 0.946722 0.0209445 + outer loop + vertex -1.423504748063857 5.312592044589877 21.5 + vertex -1.78001861476601 5.203992095601847 20.93858895746985 + vertex -2.104758878007986 5.081337428812081 21.5 + endloop +endfacet +facet normal 0.259068 0.965626 -0.0211986 + outer loop + vertex 1.072996771088698 5.394319042217769 2.122937190108266 + vertex 1.511780695860853 5.288148932057651 2.649115272515396 + vertex 1.772743246953266 5.20647494763795 2.117973314103827 + endloop +endfacet +facet normal 0.984211 0.176962 -0.00364166 + outer loop + vertex 5.338145514410095 1.324463086304552 10.36741450328788 + vertex 5.34724229625872 1.287245052467388 11.01738851026113 + vertex 5.462588851477699 0.6404084944092698 10.75925925925924 + endloop +endfacet +facet normal 0.97532 0.220605 0.00917333 + outer loop + vertex 5.330076268660247 1.356571771144032 19.73017849541023 + vertex 5.292980130030065 1.494778024693604 20.35063719267036 + vertex 5.417922838555951 0.9466319852264811 20.24864700637255 + endloop +endfacet +facet normal 0.632095 0.774885 -0.00302279 + outer loop + vertex 3.219421791503083 4.459296281746155 19.68454339005858 + vertex 3.24533634122458 4.440472050618836 20.27797987500447 + vertex 3.706797571246544 4.063207078872638 20.06301800731393 + endloop +endfacet +facet normal -0.950043 0.312088 0.00442868 + outer loop + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + vertex -5.31955841476328 1.397246675401727 2.560762479036771 + vertex -5.329642713413715 1.358274106120005 3.143864560230363 + endloop +endfacet +facet normal -0.718973 0.695035 0.0018707 + outer loop + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + vertex -3.748758334197043 4.024526177301897 20.95523197930691 + vertex -3.764535802277208 4.009771838069231 20.37321112384092 + endloop +endfacet +facet normal -0.557108 0.830237 -0.0183664 + outer loop + vertex -3.318372368152656 4.386160601970809 20.71529429688674 + vertex -2.892047726267587 4.678253942336872 20.98740566256392 + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + endloop +endfacet +facet normal -0.866169 0.49938 -0.0192462 + outer loop + vertex -4.93725623361463 2.423530664884083 2.111219890696505 + vertex -4.839134342495119 2.613958457069342 2.63629885568169 + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + endloop +endfacet +facet normal -0.962485 0.271211 -0.00819612 + outer loop + vertex -5.37875730118799 1.148464146117276 20.80997592215802 + vertex -5.194608072678547 1.807220786529104 20.9833334078545 + vertex -5.169860313545367 1.876844249912228 20.38100790963064 + endloop +endfacet +facet normal -0.608036 0.793586 -0.0226487 + outer loop + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + vertex -3.287161039918808 4.409600015606847 2.626292319656475 + vertex -3.049579275765538 4.577124232618265 2.117940666612885 + endloop +endfacet +facet normal 0.946873 0.32126 -0.0149482 + outer loop + vertex 5.090096078474033 2.083487919788177 20.15150386285141 + vertex 5.292980130030065 1.494778024693604 20.35063719267036 + vertex 5.330076268660247 1.356571771144032 19.73017849541023 + endloop +endfacet +facet normal 0.997965 0.063537 -0.00534201 + outer loop + vertex 5.45147922627175 0.7289542136016242 15.92048612597993 + vertex 5.458193291725775 0.6768500499813518 16.55505310407936 + vertex 5.5 0 16.3148148148148 + endloop +endfacet +facet normal 0.853925 0.520389 -0.00289311 + outer loop + vertex 4.533873164080951 3.113517967191868 20.0724298361627 + vertex 4.839878840573146 2.612579722912267 20.28782012505717 + vertex 4.854264491803782 2.58575254879754 19.70841037355992 + endloop +endfacet +facet normal -0.636062 0.771598 0.00782003 + outer loop + vertex -3.722911157666007 4.048448160977975 2.818116375233727 + vertex -3.287161039918808 4.409600015606847 2.626292319656475 + vertex -3.626401983050387 4.135118941134368 2.116174497036629 + endloop +endfacet +facet normal 0.499902 0.865744 -0.0241777 + outer loop + vertex 2.432587796204499 4.93280007842979 2.122937190108265 + vertex 2.750048563129589 4.763111682548383 2.61068253831418 + vertex 3.056057912944187 4.572801114495492 2.123228765692188 + endloop +endfacet +facet normal -0.717745 0.696206 -0.011798 + outer loop + vertex -3.889087296526007 3.889087296526016 21.5 + vertex -3.748758334197043 4.024526177301897 20.95523197930691 + vertex -4.14743289693693 3.612312329437385 20.88414001174677 + endloop +endfacet +facet normal -0.951112 0.308359 0.0173665 + outer loop + vertex -5.202761293209437 1.783612885656994 2.097099159738966 + vertex -5.31955841476328 1.397246675401727 2.560762479036771 + vertex -5.106468007692754 2.043033158421663 2.76454520219463 + endloop +endfacet +facet normal 0.952627 0.304139 0.00152728 + outer loop + vertex 5.328246086204495 1.363742514130318 16.05340787814411 + vertex 5.324109977345409 1.379801778927347 15.43526584087152 + vertex 5.136237431772161 1.966993910631783 15.68711310633112 + endloop +endfacet +facet normal -0.854692 0.519122 0.00368616 + outer loop + vertex -4.573082867664001 3.055636281607808 2.122937190108265 + vertex -4.839134342495119 2.613958457069342 2.63629885568169 + vertex -4.54305039848295 3.100111784572277 2.822942061993703 + endloop +endfacet +facet normal 0.751609 0.659143 0.0247861 + outer loop + vertex 4.363443371601798 3.348187859547958 21.5 + vertex 4.13511894113438 3.626401983050373 21.02504478767688 + vertex 3.889087296526017 3.889087296526005 21.5 + endloop +endfacet +facet normal -0.382535 0.923616 -0.0245088 + outer loop + vertex -2.43213297513447 4.933024345294026 2.123228765692299 + vertex -2.104344891793729 5.081508887759781 2.602739678337935 + vertex -1.767917059167402 5.208115712223076 2.122937190108266 + endloop +endfacet +facet normal 0.224348 0.974501 0.00397091 + outer loop + vertex 1.551714848063318 5.276569058611839 3.234735469707145 + vertex 1.511780695860853 5.288148932057651 2.649115272515396 + vertex 0.9376243172597151 5.419488964808698 2.855592952321005 + endloop +endfacet +facet normal -0.964268 0.26393 -0.0229697 + outer loop + vertex -5.389615255505637 1.0963792216295 2.044677887217381 + vertex -5.31955841476328 1.397246675401727 2.560762479036771 + vertex -5.202761293209437 1.783612885656994 2.097099159738966 + endloop +endfacet +facet normal -0.643939 0.765074 -0.00193882 + outer loop + vertex -3.764535802277208 4.009771838069231 20.37321112384092 + vertex -3.748758334197043 4.024526177301897 20.95523197930691 + vertex -3.318372368152656 4.386160601970809 20.71529429688674 + endloop +endfacet +facet normal -0.98022 0.197874 -0.00372693 + outer loop + vertex -5.329642713413715 1.358274106120005 3.143864560230363 + vertex -5.31955841476328 1.397246675401727 2.560762479036771 + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + endloop +endfacet +facet normal 0.195026 0.980464 0.0256004 + outer loop + vertex 1.423504748063873 5.312592044589874 21.5 + vertex 1.072996771088712 5.394319042217766 21.04016115450814 + vertex 0.7178940572102935 5.452946737555956 21.5 + endloop +endfacet +facet normal 0.912822 0.408355 0.00150964 + outer loop + vertex 5.141289816700485 1.953749989300548 3.23223805190901 + vertex 5.1359082938614 1.967853144176588 2.671362177826976 + vertex 4.887805760937779 2.521776128712354 2.854314542228816 + endloop +endfacet +facet normal -0.636957 0.770886 0.0044458 + outer loop + vertex -3.249137396094532 4.437691537421236 3.203031802015037 + vertex -3.287161039918808 4.409600015606847 2.626292319656475 + vertex -3.722911157666007 4.048448160977975 2.818116375233727 + endloop +endfacet +facet normal 0.725558 0.688133 0.00629139 + outer loop + vertex 4.187714980302149 3.56553547784242 2.852014943758265 + vertex 3.799593247494868 3.976567760467738 2.654917871642895 + vertex 3.753167914507547 4.02041423307488 3.213151815948938 + endloop +endfacet +facet normal -0.108876 0.994033 0.00664124 + outer loop + vertex -0.3116778562646466 5.491161708956882 2.849244344490732 + vertex -0.8586654316901362 5.432558667554396 2.653402613207058 + vertex -0.9278248657095747 5.421175243300202 3.223427943000292 + endloop +endfacet +facet normal -0.998596 0.0523933 -0.00781082 + outer loop + vertex -5.5 0 20.75925925925926 + vertex -5.472807214829338 0.5462427933730074 20.94680099274967 + vertex -5.464008635492013 0.6281796170433402 20.37153635718997 + endloop +endfacet +facet normal 0.998567 0.0525908 0.00993044 + outer loop + vertex 5.5 0 2.24074074074074 + vertex 5.473609142205703 0.5381477105425145 2.044517851335947 + vertex 5.462588851477906 0.6404084944075038 2.61111111111111 + endloop +endfacet +facet normal -0.482709 0.875721 0.0102049 + outer loop + vertex -2.714495705447152 4.783462455701828 20.35757567904595 + vertex -2.892047726267587 4.678253942336872 20.98740566256392 + vertex -2.432587796204501 4.932800078429788 20.87706280989174 + endloop +endfacet +facet normal -0.065379 0.997491 0.0271362 + outer loop + vertex 1.078026285860484e-14 5.5 21.5 + vertex -0.3597172107657781 5.48822407781232 21.06620305504513 + vertex -0.7178940572102771 5.452946737555958 21.5 + endloop +endfacet +facet normal -0.855078 0.518464 0.00601009 + outer loop + vertex -4.54305039848295 3.100111784572277 2.822942061993703 + vertex -4.839134342495119 2.613958457069342 2.63629885568169 + vertex -4.866831821449069 2.562020300803789 3.176153595264171 + endloop +endfacet +facet normal 0.0653787 0.997487 -0.0273102 + outer loop + vertex -1.13279746910902e-14 5.5 1.5 + vertex 0.3597172107657752 5.48822407781232 1.931031098542516 + vertex 0.717894057210274 5.452946737555958 1.5 + endloop +endfacet +facet normal -0.385896 0.922099 0.0285745 + outer loop + vertex -1.78001861476601 5.203992095601847 20.93858895746985 + vertex -2.109161857118958 5.079511419464918 20.51052818313118 + vertex -2.432587796204501 4.932800078429788 20.87706280989174 + endloop +endfacet +facet normal -0.831159 0.555363 0.0273156 + outer loop + vertex -4.363443371601792 3.348187859547965 21.5 + vertex -4.573082867663999 3.055636281607812 21.0690550638699 + vertex -4.763139720814412 2.750000000000003 21.5 + endloop +endfacet +facet normal 0.831158 0.555362 -0.0273759 + outer loop + vertex 4.36344337160179 3.348187859547969 1.5 + vertex 4.573082867663997 3.055636281607814 1.92999455336682 + vertex 4.763139720814412 2.750000000000002 1.5 + endloop +endfacet +facet normal 0.988903 0.14813 0.0113727 + outer loop + vertex 5.388402417417908 1.102324538402753 2.105178344957057 + vertex 5.473609142205703 0.5381477105425145 2.044517851335947 + vertex 5.452946737555957 0.7178940572102837 1.5 + endloop +endfacet +facet normal -0.988489 0.150876 -0.0111931 + outer loop + vertex -5.389615255505637 1.0963792216295 2.044677887217381 + vertex -5.471754212788627 0.556691867041289 2.02393833416575 + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + endloop +endfacet +facet normal -0.751518 0.659063 -0.0292702 + outer loop + vertex -4.363443371601797 3.348187859547959 1.5 + vertex -4.135091253779056 3.626433554185152 1.902145778937794 + vertex -3.889087296526017 3.889087296526005 1.5 + endloop +endfacet +facet normal -0.340893 0.940036 -0.0111272 + outer loop + vertex -2.204987976597974 5.038653393820454 19.99453580293805 + vertex -2.109161857118958 5.079511419464918 20.51052818313118 + vertex -1.608551244610577 5.259521165796537 20.38119086934289 + endloop +endfacet +facet normal -0.486403 0.873678 -0.00989156 + outer loop + vertex -2.432587796204501 4.932800078429788 20.87706280989174 + vertex -2.892047726267587 4.678253942336872 20.98740566256392 + vertex -2.749999999999996 4.763139720814415 21.5 + endloop +endfacet +facet normal 0.980402 0.194242 -0.0328783 + outer loop + vertex 5.325937770498046 1.372729712937804 17.5273430786013 + vertex 5.430619032632266 0.8708483923233669 17.68377109348667 + vertex 5.466427009523622 0.6067748755103708 17.19140785290995 + endloop +endfacet +facet normal 0.988631 0.150158 -0.00787205 + outer loop + vertex 5.462588851477906 0.6404084944075038 2.61111111111111 + vertex 5.473609142205703 0.5381477105425145 2.044517851335947 + vertex 5.388402417417908 1.102324538402753 2.105178344957057 + endloop +endfacet +facet normal -0.979721 0.199679 0.016585 + outer loop + vertex -5.444482131580981 0.7794961955618559 2.618728082093755 + vertex -5.31955841476328 1.397246675401727 2.560762479036771 + vertex -5.389615255505637 1.0963792216295 2.044677887217381 + endloop +endfacet +facet normal -0.98862 0.150055 0.0106801 + outer loop + vertex -5.452946737555957 0.7178940572102825 1.5 + vertex -5.471754212788627 0.556691867041289 2.02393833416575 + vertex -5.389615255505637 1.0963792216295 2.044677887217381 + endloop +endfacet +facet normal 0.987769 0.155232 0.0146909 + outer loop + vertex 5.370087155850409 1.188345041884078 20.9108902288276 + vertex 5.471007922370094 0.5639790008179997 20.72270400351366 + vertex 5.417922838555951 0.9466319852264811 20.24864700637255 + endloop +endfacet +facet normal -0.340915 0.940027 -0.0112255 + outer loop + vertex -1.608551244610577 5.259521165796537 20.38119086934289 + vertex -2.109161857118958 5.079511419464918 20.51052818313118 + vertex -1.78001861476601 5.203992095601847 20.93858895746985 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.452946737555957 0.7178940572102837 1.5 + vertex 4.69127103704674 0.9511412400559269 1.5 + vertex 5.312592044589874 1.423504748063868 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.992602807386213 0.5784873467077816 1.5 + vertex -4.30075581703243 -0.1407896738922965 1.5 + vertex -4.854257856795574 0.3474859625031357 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.854257856795574 0.3474859625031357 1.5 + vertex -4.533919615543224 0.9096756578804275 1.5 + vertex -3.992602807386213 0.5784873467077816 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.877559064420447 0.3196921111679707 1.5 + vertex 4.69127103704674 0.9511412400559269 1.5 + vertex 5.452946737555957 0.7178940572102837 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 5.312592044589874 1.423504748063868 1.5 + vertex 4.69127103704674 0.9511412400559269 1.5 + vertex 4.592403655874934 1.584446114812592 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 4.877559064420447 0.3196921111679707 1.5 + vertex 4.348549180927965 -0.1262957942898617 1.5 + vertex 4.080077303764824 0.5494644464517151 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.939220674837048 1.707170458185183 1.5 + vertex 3.546351029634341 2.331835435566113 1.5 + vertex 4.38127154442434 2.198199387204508 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -3.076702677749195 3.053971750049437 1.5 + vertex -3.497903111842934 2.385066827802327 1.5 + vertex -3.700871888778946 3.170742721706044 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.065361452539194 2.682531394733724 1.5 + vertex -3.497903111842934 2.385066827802327 1.5 + vertex -3.938709611886719 1.837609013922011 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.080077303764824 0.5494644464517151 1.5 + vertex 4.69127103704674 0.9511412400559269 1.5 + vertex 4.877559064420447 0.3196921111679707 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -3.700871888778946 3.170742721706044 1.5 + vertex -3.497903111842934 2.385066827802327 1.5 + vertex -4.065361452539194 2.682531394733724 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.38127154442434 2.198199387204508 1.5 + vertex 3.546351029634341 2.331835435566113 1.5 + vertex 4.030340816201242 2.762411925844113 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.938709611886719 1.837609013922011 1.5 + vertex -4.497880547870021 2.180785379967064 1.5 + vertex -4.065361452539194 2.682531394733724 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.4337140373662665 4.235895607879137 1.5 + vertex 0.9527312490134241 4.84511117665047 1.5 + vertex 1.141688308026424 4.219048976441587 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 4.030340816201242 2.762411925844113 1.5 + vertex 3.546351029634341 2.331835435566113 1.5 + vertex 3.225877023298945 3.002037394799067 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.2903242422441917 4.866212300447543 1.5 + vertex 0.9527312490134241 4.84511117665047 1.5 + vertex 0.4337140373662665 4.235895607879137 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -3.637342861146872 -1.349080118297037 1.5 + vertex -4.381156996247915 -1.354110193305761 1.5 + vertex -3.938723634516724 -0.7037976734235176 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.637342861146872 -1.349080118297037 1.5 + vertex -3.938723634516724 -0.7037976734235176 1.5 + vertex -3.250140632039959 -0.688428408781637 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3203822717665369 4.335102417777374 1.5 + vertex -0.9520750409854828 4.87123153491677 1.5 + vertex -0.3344962908973508 4.979339141727255 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -3.250140632039959 -0.688428408781637 1.5 + vertex -2.919292116093352 -1.345368670807211 1.5 + vertex -3.637342861146872 -1.349080118297037 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.118265021975916 4.222117942277324 1.5 + vertex -0.9520750409854828 4.87123153491677 1.5 + vertex -0.3203822717665369 4.335102417777374 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.225877023298945 3.002037394799067 1.5 + vertex 3.757790900719538 3.340427280609457 1.5 + vertex 4.030340816201242 2.762411925844113 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 0.2903242422441917 4.866212300447543 1.5 + vertex 0.4337140373662665 4.235895607879137 1.5 + vertex -0.3203822717665369 4.335102417777374 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.919292116093352 -1.345368670807211 1.5 + vertex -2.537536482016807 -0.7050924467300033 1.5 + vertex -2.193237827357454 -1.353006190838093 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.2623267067475 1.756376831501149 1.5 + vertex 2.567062035605037 1.791390380062656 1.5 + vertex 2.930332249235315 2.416335828844156 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.381156996247915 -1.354110193305761 1.5 + vertex -4.502137055787425 -0.7050064017157527 1.5 + vertex -3.938723634516724 -0.7037976734235176 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.932112967069701 1.146338233818285 1.5 + vertex 2.567062035605037 1.791390380062656 1.5 + vertex 3.2623267067475 1.756376831501149 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.209067678422399 1.155230350742405 1.5 + vertex 2.567062035605037 1.791390380062656 1.5 + vertex 2.932112967069701 1.146338233818285 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.250140632039959 -0.688428408781637 1.5 + vertex -2.537536482016807 -0.7050924467300033 1.5 + vertex -2.919292116093352 -1.345368670807211 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.815879637236696 -0.7108883506313082 1.5 + vertex -1.443006186045382 -0.08298995768770645 1.5 + vertex -1.093972907176562 -0.726490257139405 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3203822717665369 4.335102417777374 1.5 + vertex -0.3344962908973508 4.979339141727255 1.5 + vertex 0.2903242422441917 4.866212300447543 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.637342861146872 -1.349080118297037 1.5 + vertex -2.919292116093352 -1.345368670807211 1.5 + vertex -3.299999999999997 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.299999999999997 -2 1.5 + vertex -2.919292116093352 -1.345368670807211 1.5 + vertex -2.566666666666663 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.5 0 1.5 + vertex 4.877559064420447 0.3196921111679707 1.5 + vertex 5.452946737555957 0.7178940572102837 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -5.452946737555957 0.7178940572102825 1.5 + vertex -4.854257856795574 0.3474859625031357 1.5 + vertex -5.5 0 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.165563740279156 -0.07157834277515596 1.5 + vertex -1.443006186045382 -0.08298995768770645 1.5 + vertex -1.815879637236696 -0.7108883506313082 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.0003284348192958335 -0.09770912216422634 1.5 + vertex 0.3829917800432805 0.5366394047221337 1.5 + vertex 0.7414784667060733 -0.09723348127734832 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.933844498505923 -0.1103681062979049 1.5 + vertex 3.652110134630465 -0.1155549484835552 1.5 + vertex 3.293697875390585 -0.7388106768635812 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 2.933844498505923 -0.1103681062979049 1.5 + vertex 3.293697875390585 -0.7388106768635812 1.5 + vertex 2.567670435016825 -0.7355155016236967 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.36969470928905 -0.7306577997026023 1.5 + vertex 0.0003284348192958335 -0.09770912216422634 1.5 + vertex 0.7414784667060733 -0.09723348127734832 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 3.9732539505543 -0.7318262072921322 1.5 + vertex 4.372143036323215 -1.373069696241233 1.5 + vertex 3.656152982131824 -1.371806223167343 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.566666666666663 -2 1.5 + vertex -2.919292116093352 -1.345368670807211 1.5 + vertex -2.193237827357454 -1.353006190838093 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.300000000000008 -2 1.5 + vertex 2.931623005398146 -1.369004018290946 1.5 + vertex 3.656152982131824 -1.371806223167343 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 2.932112967069701 1.146338233818285 1.5 + vertex 2.571942814969939 0.5199357777095184 1.5 + vertex 2.209067678422399 1.155230350742405 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.193237827357454 -1.353006190838093 1.5 + vertex -2.537536482016807 -0.7050924467300033 1.5 + vertex -1.815879637236696 -0.7108883506313082 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.7185542750926248 -0.08933274599124186 1.5 + vertex -0.345943276534375 0.5400465827345018 1.5 + vertex 0.0003284348192958335 -0.09770912216422634 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.069336346600583 0.5464552392209603 1.5 + vertex -0.345943276534375 0.5400465827345018 1.5 + vertex -0.7185542750926248 -0.08933274599124186 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.293697875390585 -0.7388106768635812 1.5 + vertex 3.9732539505543 -0.7318262072921322 1.5 + vertex 3.656152982131824 -1.371806223167343 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.6746532451845126 3.667631670872276 1.5 + vertex -0.3203822717665369 4.335102417777374 1.5 + vertex 0.0387167892632739 3.662594332895794 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 3.652110134630465 -0.1155549484835552 1.5 + vertex 3.9732539505543 -0.7318262072921322 1.5 + vertex 3.293697875390585 -0.7388106768635812 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.931623005398146 -1.369004018290946 1.5 + vertex 3.293697875390585 -0.7388106768635812 1.5 + vertex 3.656152982131824 -1.371806223167343 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 0.0387167892632739 3.662594332895794 1.5 + vertex -0.324026347066608 3.048450480034041 1.5 + vertex -0.6746532451845126 3.667631670872276 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 0.7414784667060733 -0.09723348127734832 1.5 + vertex 1.104605458116279 -0.7312649881863611 1.5 + vertex 0.36969470928905 -0.7306577997026023 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -0.6746532451845126 3.667631670872276 1.5 + vertex -0.324026347066608 3.048450480034041 1.5 + vertex -1.051447744215863 3.051817158557229 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.051447744215863 3.051817158557229 1.5 + vertex -0.324026347066608 3.048450480034041 1.5 + vertex -0.6927295915942052 2.430212992084215 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.300000000000008 -2 1.5 + vertex 3.656152982131824 -1.371806223167343 1.5 + vertex 4.033333333333339 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.033333333333331 -2 1.5 + vertex -3.637342861146872 -1.349080118297037 1.5 + vertex -3.299999999999997 -2 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 2.209067678422399 1.155230350742405 1.5 + vertex 2.571942814969939 0.5199357777095184 1.5 + vertex 1.842230588939065 0.5294478755585779 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.567670435016825 -0.7355155016236967 1.5 + vertex 3.293697875390585 -0.7388106768635812 1.5 + vertex 2.931623005398146 -1.369004018290946 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.36969470928905 -0.7306577997026023 1.5 + vertex 1.104605458116279 -0.7312649881863611 1.5 + vertex 0.7357268796779435 -1.363510057891919 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -3.250140632039959 -0.688428408781637 1.5 + vertex -3.938723634516724 -0.7037976734235176 1.5 + vertex -3.594777678583022 -0.06022377001656176 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.0003284348192958335 -0.09770912216422634 1.5 + vertex -0.345943276534375 0.5400465827345018 1.5 + vertex 0.3829917800432805 0.5366394047221337 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.193237827357454 -1.353006190838093 1.5 + vertex -1.815879637236696 -0.7108883506313082 1.5 + vertex -1.463378559907324 -1.362196829349745 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.235547415738327 0.562387091241233 1.5 + vertex -3.992602807386213 0.5784873467077816 1.5 + vertex -3.561583637826033 1.200837332544602 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.594777678583022 -0.06022377001656176 1.5 + vertex -3.992602807386213 0.5784873467077816 1.5 + vertex -3.235547415738327 0.562387091241233 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.298500074197025 0.5096628011174569 1.5 + vertex 4.080077303764824 0.5494644464517151 1.5 + vertex 3.652110134630465 -0.1155549484835552 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.20451367619216 -0.1030147290686352 1.5 + vertex 2.933844498505923 -0.1103681062979049 1.5 + vertex 2.567670435016825 -0.7355155016236967 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.881104939094225 -0.06128471654661727 1.5 + vertex -3.594777678583022 -0.06022377001656176 1.5 + vertex -3.235547415738327 0.562387091241233 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.933844498505923 -0.1103681062979049 1.5 + vertex 3.298500074197025 0.5096628011174569 1.5 + vertex 3.652110134630465 -0.1155549484835552 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.200789878856348 -1.365822432420879 1.5 + vertex 2.931623005398146 -1.369004018290946 1.5 + vertex 2.566666666666677 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.193237827357454 -1.353006190838093 1.5 + vertex -1.463378559907324 -1.362196829349745 1.5 + vertex -1.833333333333327 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.566666666666677 -2 1.5 + vertex 2.931623005398146 -1.369004018290946 1.5 + vertex 3.300000000000008 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.058674549617588 1.804256508179345 1.5 + vertex -1.417660819527751 2.431434306868582 1.5 + vertex -0.6927295915942052 2.430212992084215 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.6927295915942052 2.430212992084215 1.5 + vertex -1.417660819527751 2.431434306868582 1.5 + vertex -1.051447744215863 3.051817158557229 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.515082459438828 0.5589425212431252 1.5 + vertex -3.235547415738327 0.562387091241233 1.5 + vertex -2.872683694795263 1.185667820811309 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.465704938437498e-14 -1.364914703891412 1.5 + vertex 0.7357268796779435 -1.363510057891919 1.5 + vertex 0.3666666666666831 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.933844498505923 -0.1103681062979049 1.5 + vertex 2.571942814969939 0.5199357777095184 1.5 + vertex 3.298500074197025 0.5096628011174569 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -0.324026347066608 3.048450480034041 1.5 + vertex 0.03517957411658745 2.426381474066759 1.5 + vertex -0.6927295915942052 2.430212992084215 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.465704938437498e-14 -1.364914703891412 1.5 + vertex 0.36969470928905 -0.7306577997026023 1.5 + vertex 0.7357268796779435 -1.363510057891919 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -3.594777678583022 -0.06022377001656176 1.5 + vertex -4.30075581703243 -0.1407896738922965 1.5 + vertex -3.992602807386213 0.5784873467077816 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.480578271695581 1.163377739725285 1.5 + vertex 1.843365012587537 1.792316515686391 1.5 + vertex 2.209067678422399 1.155230350742405 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.508311237319839 1.81064297932574 1.5 + vertex -3.208050856029835 1.804690896254801 1.5 + vertex -2.867298633115758 2.439559922802162 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.833333333333327 -2 1.5 + vertex -1.463378559907324 -1.362196829349745 1.5 + vertex -1.09999999999999 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.100000000000015 -2 1.5 + vertex 0.7357268796779435 -1.363510057891919 1.5 + vertex 1.468777335234927 -1.365233902211956 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.200789878856348 -1.365822432420879 1.5 + vertex 2.567670435016825 -0.7355155016236967 1.5 + vertex 2.931623005398146 -1.369004018290946 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.7320942707248586 -1.364787257859086 1.5 + vertex -1.093972907176562 -0.726490257139405 1.5 + vertex -0.3651319963090849 -0.7309445264696603 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.209067678422399 1.155230350742405 1.5 + vertex 1.843365012587537 1.792316515686391 1.5 + vertex 2.567062035605037 1.791390380062656 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.235547415738327 0.562387091241233 1.5 + vertex -3.561583637826033 1.200837332544602 1.5 + vertex -2.872683694795263 1.185667820811309 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.6927295915942052 2.430212992084215 1.5 + vertex 0.03517957411658745 2.426381474066759 1.5 + vertex -0.3321123128468585 1.800460332479551 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.149558517617187 1.182611589819572 1.5 + vertex -2.872683694795263 1.185667820811309 1.5 + vertex -2.508311237319839 1.81064297932574 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.298500074197025 0.5096628011174569 1.5 + vertex 2.571942814969939 0.5199357777095184 1.5 + vertex 2.932112967069701 1.146338233818285 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.100000000000015 -2 1.5 + vertex 1.468777335234927 -1.365233902211956 1.5 + vertex 1.833333333333345 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.3666666666666831 -2 1.5 + vertex 0.7357268796779435 -1.363510057891919 1.5 + vertex 1.100000000000015 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.093972907176562 -0.726490257139405 1.5 + vertex -1.443006186045382 -0.08298995768770645 1.5 + vertex -0.7185542750926248 -0.08933274599124186 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7357268796779435 -1.363510057891919 1.5 + vertex 1.104605458116279 -0.7312649881863611 1.5 + vertex 1.468777335234927 -1.365233902211956 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.465704938437498e-14 -1.364914703891412 1.5 + vertex -0.7320942707248586 -1.364787257859086 1.5 + vertex -0.3651319963090849 -0.7309445264696603 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3651319963090849 -0.7309445264696603 1.5 + vertex 0.0003284348192958335 -0.09770912216422634 1.5 + vertex 0.36969470928905 -0.7306577997026023 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.149558517617187 1.182611589819572 1.5 + vertex -2.508311237319839 1.81064297932574 1.5 + vertex -1.784362077976356 1.807698257491351 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.465704938437498e-14 -1.364914703891412 1.5 + vertex -0.3651319963090849 -0.7309445264696603 1.5 + vertex 0.36969470928905 -0.7306577997026023 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.515082459438828 0.5589425212431252 1.5 + vertex -2.881104939094225 -0.06128471654661727 1.5 + vertex -3.235547415738327 0.562387091241233 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.124222169178418 3.048943347935247 1.5 + vertex 1.45482787875139 3.64880628028241 1.5 + vertex 1.847777614877195 3.043580312578945 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.784362077976356 1.807698257491351 1.5 + vertex -1.417660819527751 2.431434306868582 1.5 + vertex -1.058674549617588 1.804256508179345 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.474921274802654 -0.09873933204190921 1.5 + vertex 1.842230588939065 0.5294478755585779 1.5 + vertex 2.20451367619216 -0.1030147290686352 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.463378559907324 -1.362196829349745 1.5 + vertex -1.815879637236696 -0.7108883506313082 1.5 + vertex -1.093972907176562 -0.726490257139405 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.480578271695581 1.163377739725285 1.5 + vertex 2.209067678422399 1.155230350742405 1.5 + vertex 1.842230588939065 0.5294478755585779 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.424381194657823 1.178078596433584 1.5 + vertex -2.149558517617187 1.182611589819572 1.5 + vertex -1.784362077976356 1.807698257491351 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7594894626402174 2.423403541695613 1.5 + vertex 1.124222169178418 3.048943347935247 1.5 + vertex 1.483690994980252 2.420612065177356 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.114096768781593 0.5342475133086584 1.5 + vertex 1.480578271695581 1.163377739725285 1.5 + vertex 1.842230588939065 0.5294478755585779 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7533807358995799 1.16648708721384 1.5 + vertex 1.119090380431053 1.793951732296135 1.5 + vertex 1.480578271695581 1.163377739725285 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.837034082987028 -0.7322153559924343 1.5 + vertex 1.104605458116279 -0.7312649881863611 1.5 + vertex 1.474921274802654 -0.09873933204190921 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.124222169178418 3.048943347935247 1.5 + vertex 1.847777614877195 3.043580312578945 1.5 + vertex 1.483690994980252 2.420612065177356 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.058674549617588 1.804256508179345 1.5 + vertex -0.6927295915942052 2.430212992084215 1.5 + vertex -0.3321123128468585 1.800460332479551 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7652120942042574 3.661745440225192 1.5 + vertex 1.141688308026424 4.219048976441587 1.5 + vertex 1.45482787875139 3.64880628028241 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.3936718193787542 1.79695234025199 1.5 + vertex 0.7594894626402174 2.423403541695613 1.5 + vertex 1.119090380431053 1.793951732296135 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.837034082987028 -0.7322153559924343 1.5 + vertex 2.20451367619216 -0.1030147290686352 1.5 + vertex 2.567670435016825 -0.7355155016236967 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.508311237319839 1.81064297932574 1.5 + vertex -2.867298633115758 2.439559922802162 1.5 + vertex -2.143981252395323 2.436389610939944 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 1.474921274802654 -0.09873933204190921 1.5 + vertex 1.104605458116279 -0.7312649881863611 1.5 + vertex 0.7414784667060733 -0.09723348127734832 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.4007761352150716 3.052065251727972 1.5 + vertex 0.7652120942042574 3.661745440225192 1.5 + vertex 1.124222169178418 3.048943347935247 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7594894626402174 2.423403541695613 1.5 + vertex 1.483690994980252 2.420612065177356 1.5 + vertex 1.119090380431053 1.793951732296135 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7652120942042574 3.661745440225192 1.5 + vertex 1.45482787875139 3.64880628028241 1.5 + vertex 1.124222169178418 3.048943347935247 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.469745241963482 3.04465005287059 1.5 + vertex -2.14368761686899 3.703602060025339 1.5 + vertex -1.774769701367173 3.058231313959407 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.837034082987028 -0.7322153559924343 1.5 + vertex 1.474921274802654 -0.09873933204190921 1.5 + vertex 2.20451367619216 -0.1030147290686352 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7533807358995799 1.16648708721384 1.5 + vertex 0.3936718193787542 1.79695234025199 1.5 + vertex 1.119090380431053 1.793951732296135 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.867298633115758 2.439559922802162 1.5 + vertex -2.469745241963482 3.04465005287059 1.5 + vertex -2.143981252395323 2.436389610939944 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.474921274802654 -0.09873933204190921 1.5 + vertex 1.114096768781593 0.5342475133086584 1.5 + vertex 1.842230588939065 0.5294478755585779 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3666666666666538 -2 1.5 + vertex -0.7320942707248586 -1.364787257859086 1.5 + vertex 1.465704938437498e-14 -1.364914703891412 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.114096768781593 0.5342475133086584 1.5 + vertex 0.7533807358995799 1.16648708721384 1.5 + vertex 1.480578271695581 1.163377739725285 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.847777614877195 3.043580312578945 1.5 + vertex 2.5222688176319 3.012170694087664 1.5 + vertex 2.207597520252746 2.418532568299296 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7594894626402174 2.423403541695613 1.5 + vertex 0.4007761352150716 3.052065251727972 1.5 + vertex 1.124222169178418 3.048943347935247 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.4007761352150716 3.052065251727972 1.5 + vertex 0.0387167892632739 3.662594332895794 1.5 + vertex 0.7652120942042574 3.661745440225192 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.833333333333345 -2 1.5 + vertex 2.200789878856348 -1.365822432420879 1.5 + vertex 2.566666666666677 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3651319963090849 -0.7309445264696603 1.5 + vertex -0.7185542750926248 -0.08933274599124186 1.5 + vertex 0.0003284348192958335 -0.09770912216422634 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.566666666666663 -2 1.5 + vertex -2.193237827357454 -1.353006190838093 1.5 + vertex -1.833333333333327 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.872683694795263 1.185667820811309 1.5 + vertex -3.208050856029835 1.804690896254801 1.5 + vertex -2.508311237319839 1.81064297932574 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.4007761352150716 3.052065251727972 1.5 + vertex 0.03517957411658745 2.426381474066759 1.5 + vertex -0.324026347066608 3.048450480034041 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7594894626402174 2.423403541695613 1.5 + vertex 0.03517957411658745 2.426381474066759 1.5 + vertex 0.4007761352150716 3.052065251727972 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.508311237319839 1.81064297932574 1.5 + vertex -2.143981252395323 2.436389610939944 1.5 + vertex -1.784362077976356 1.807698257491351 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3666666666666538 -2 1.5 + vertex 1.465704938437498e-14 -1.364914703891412 1.5 + vertex 0.3666666666666831 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.14368761686899 3.703602060025339 1.5 + vertex -1.403555134995218 3.647926557913302 1.5 + vertex -1.774769701367173 3.058231313959407 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.881104939094225 -0.06128471654661727 1.5 + vertex -3.250140632039959 -0.688428408781637 1.5 + vertex -3.594777678583022 -0.06022377001656176 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.424381194657823 1.178078596433584 1.5 + vertex -1.784362077976356 1.807698257491351 1.5 + vertex -1.058674549617588 1.804256508179345 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.09999999999999 -2 1.5 + vertex -1.463378559907324 -1.362196829349745 1.5 + vertex -0.7320942707248586 -1.364787257859086 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.09999999999999 -2 1.5 + vertex -0.7320942707248586 -1.364787257859086 1.5 + vertex -0.3666666666666538 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3321123128468585 1.800460332479551 1.5 + vertex 0.03517957411658745 2.426381474066759 1.5 + vertex 0.3936718193787542 1.79695234025199 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.6985093609911215 1.174015816774994 1.5 + vertex -1.058674549617588 1.804256508179345 1.5 + vertex -0.3321123128468585 1.800460332479551 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.469745241963482 3.04465005287059 1.5 + vertex -1.774769701367173 3.058231313959407 1.5 + vertex -2.143981252395323 2.436389610939944 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.02742010861550306 1.170210903844389 1.5 + vertex -0.3321123128468585 1.800460332479551 1.5 + vertex 0.3936718193787542 1.79695234025199 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 2.5222688176319 3.012170694087664 1.5 + vertex 2.930332249235315 2.416335828844156 1.5 + vertex 2.207597520252746 2.418532568299296 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 1.847777614877195 3.043580312578945 1.5 + vertex 2.207597520252746 2.418532568299296 1.5 + vertex 1.483690994980252 2.420612065177356 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.833333333333345 -2 1.5 + vertex 1.468777335234927 -1.365233902211956 1.5 + vertex 2.200789878856348 -1.365822432420879 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.7320942707248586 -1.364787257859086 1.5 + vertex -1.463378559907324 -1.362196829349745 1.5 + vertex -1.093972907176562 -0.726490257139405 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.149558517617187 1.182611589819572 1.5 + vertex -2.515082459438828 0.5589425212431252 1.5 + vertex -2.872683694795263 1.185667820811309 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.403555134995218 3.647926557913302 1.5 + vertex -0.6746532451845126 3.667631670872276 1.5 + vertex -1.051447744215863 3.051817158557229 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.119090380431053 1.793951732296135 1.5 + vertex 1.843365012587537 1.792316515686391 1.5 + vertex 1.480578271695581 1.163377739725285 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.3936718193787542 1.79695234025199 1.5 + vertex 0.03517957411658745 2.426381474066759 1.5 + vertex 0.7594894626402174 2.423403541695613 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 0.4007761352150716 3.052065251727972 1.5 + vertex -0.324026347066608 3.048450480034041 1.5 + vertex 0.0387167892632739 3.662594332895794 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.093972907176562 -0.726490257139405 1.5 + vertex -0.7185542750926248 -0.08933274599124186 1.5 + vertex -0.3651319963090849 -0.7309445264696603 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.6985093609911215 1.174015816774994 1.5 + vertex -1.424381194657823 1.178078596433584 1.5 + vertex -1.058674549617588 1.804256508179345 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 2.207597520252746 2.418532568299296 1.5 + vertex 1.843365012587537 1.792316515686391 1.5 + vertex 1.483690994980252 2.420612065177356 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7533807358995799 1.16648708721384 1.5 + vertex 0.02742010861550306 1.170210903844389 1.5 + vertex 0.3936718193787542 1.79695234025199 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.02742010861550306 1.170210903844389 1.5 + vertex -0.6985093609911215 1.174015816774994 1.5 + vertex -0.3321123128468585 1.800460332479551 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.468777335234927 -1.365233902211956 1.5 + vertex 1.104605458116279 -0.7312649881863611 1.5 + vertex 1.837034082987028 -0.7322153559924343 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -1.403555134995218 3.647926557913302 1.5 + vertex -1.051447744215863 3.051817158557229 1.5 + vertex -1.774769701367173 3.058231313959407 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 4.080077303764824 0.5494644464517151 1.5 + vertex 4.348549180927965 -0.1262957942898617 1.5 + vertex 3.652110134630465 -0.1155549484835552 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 2.749999999999995 4.763139720814415 1.5 + vertex 2.177810132972474 4.418444552674964 1.5 + vertex 2.104758878007986 5.081337428812081 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.474921274802654 -0.09873933204190921 1.5 + vertex 0.7414784667060733 -0.09723348127734832 1.5 + vertex 1.114096768781593 0.5342475133086584 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.423504748063876 5.312592044589873 1.5 + vertex -1.57355755923579 4.685036403620216 1.5 + vertex -2.104758878008006 5.081337428812073 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.842230588939065 0.5294478755585779 1.5 + vertex 2.571942814969939 0.5199357777095184 1.5 + vertex 2.20451367619216 -0.1030147290686352 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 3.889087296526007 3.889087296526015 1.5 + vertex 3.280205995969707 3.70041192633012 1.5 + vertex 3.348187859547956 4.363443371601799 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.567062035605037 1.791390380062656 1.5 + vertex 1.843365012587537 1.792316515686391 1.5 + vertex 2.207597520252746 2.418532568299296 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 0.717894057210274 5.452946737555958 1.5 + vertex 0.2903242422441917 4.866212300447543 1.5 + vertex -1.13279746910902e-14 5.5 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.763139720814412 2.750000000000002 1.5 + vertex 4.030340816201242 2.762411925844113 1.5 + vertex 4.36344337160179 3.348187859547969 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -4.363443371601797 3.348187859547959 1.5 + vertex -4.065361452539194 2.682531394733724 1.5 + vertex -4.763139720814414 2.749999999999997 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.143981252395323 2.436389610939944 1.5 + vertex -1.417660819527751 2.431434306868582 1.5 + vertex -1.784362077976356 1.807698257491351 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -3.348187859547972 4.363443371601787 1.5 + vertex -3.252827146736721 3.704408250309965 1.5 + vertex -3.889087296526017 3.889087296526005 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 1.483690994980252 2.420612065177356 1.5 + vertex 1.843365012587537 1.792316515686391 1.5 + vertex 1.119090380431053 1.793951732296135 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 2.930332249235315 2.416335828844156 1.5 + vertex 2.567062035605037 1.791390380062656 1.5 + vertex 2.207597520252746 2.418532568299296 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.114096768781593 0.5342475133086584 1.5 + vertex 0.3829917800432805 0.5366394047221337 1.5 + vertex 0.7533807358995799 1.16648708721384 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.200789878856348 -1.365822432420879 1.5 + vertex 1.468777335234927 -1.365233902211956 1.5 + vertex 1.837034082987028 -0.7322153559924343 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.20451367619216 -0.1030147290686352 1.5 + vertex 2.571942814969939 0.5199357777095184 1.5 + vertex 2.933844498505923 -0.1103681062979049 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -1.774769701367173 3.058231313959407 1.5 + vertex -1.417660819527751 2.431434306868582 1.5 + vertex -2.143981252395323 2.436389610939944 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 0.7533807358995799 1.16648708721384 1.5 + vertex 0.3829917800432805 0.5366394047221337 1.5 + vertex 0.02742010861550306 1.170210903844389 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -2.149558517617187 1.182611589819572 1.5 + vertex -1.794730209886672 0.5538947111899133 1.5 + vertex -2.515082459438828 0.5589425212431252 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.312592044589874 1.423504748063868 1.5 + vertex 4.592403655874934 1.584446114812592 1.5 + vertex 5.081337428812076 2.104758878007996 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -5.081337428812079 2.104758878007991 1.5 + vertex -4.640854525297701 1.529027613171597 1.5 + vertex -5.312592044589876 1.423504748063862 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7414784667060733 -0.09723348127734832 1.5 + vertex 0.3829917800432805 0.5366394047221337 1.5 + vertex 1.114096768781593 0.5342475133086584 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.200789878856348 -1.365822432420879 1.5 + vertex 1.837034082987028 -0.7322153559924343 1.5 + vertex 2.567670435016825 -0.7355155016236967 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -1.051447744215863 3.051817158557229 1.5 + vertex -1.417660819527751 2.431434306868582 1.5 + vertex -1.774769701367173 3.058231313959407 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -0.6985093609911215 1.174015816774994 1.5 + vertex -1.069336346600583 0.5464552392209603 1.5 + vertex -1.424381194657823 1.178078596433584 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.561583637826033 1.200837332544602 1.5 + vertex -3.208050856029835 1.804690896254801 1.5 + vertex -2.872683694795263 1.185667820811309 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -1.424381194657823 1.178078596433584 1.5 + vertex -1.794730209886672 0.5538947111899133 1.5 + vertex -2.149558517617187 1.182611589819572 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.298500074197025 0.5096628011174569 1.5 + vertex 3.629650195061862 1.147700606358877 1.5 + vertex 4.080077303764824 0.5494644464517151 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 0.02742010861550306 1.170210903844389 1.5 + vertex -0.345943276534375 0.5400465827345018 1.5 + vertex -0.6985093609911215 1.174015816774994 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.515082459438828 0.5589425212431252 1.5 + vertex -1.794730209886672 0.5538947111899133 1.5 + vertex -2.165563740279156 -0.07157834277515596 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.3829917800432805 0.5366394047221337 1.5 + vertex -0.345943276534375 0.5400465827345018 1.5 + vertex 0.02742010861550306 1.170210903844389 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.069336346600583 0.5464552392209603 1.5 + vertex -1.794730209886672 0.5538947111899133 1.5 + vertex -1.424381194657823 1.178078596433584 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.14368761686899 3.703602060025339 1.5 + vertex -2.750000000000009 4.11566584733009 1.5 + vertex -2.189271177275879 4.439402784072247 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -0.6985093609911215 1.174015816774994 1.5 + vertex -0.345943276534375 0.5400465827345018 1.5 + vertex -1.069336346600583 0.5464552392209603 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -2.515082459438828 0.5589425212431252 1.5 + vertex -2.165563740279156 -0.07157834277515596 1.5 + vertex -2.881104939094225 -0.06128471654661727 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.932112967069701 1.146338233818285 1.5 + vertex 3.2623267067475 1.756376831501149 1.5 + vertex 3.629650195061862 1.147700606358877 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.45482787875139 3.64880628028241 1.5 + vertex 2.174143711780794 3.693244847157455 1.5 + vertex 1.847777614877195 3.043580312578945 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.938723634516724 -0.7037976734235176 1.5 + vertex -4.30075581703243 -0.1407896738922965 1.5 + vertex -3.594777678583022 -0.06022377001656176 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.815879637236696 -0.7108883506313082 1.5 + vertex -2.537536482016807 -0.7050924467300033 1.5 + vertex -2.165563740279156 -0.07157834277515596 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.298500074197025 0.5096628011174569 1.5 + vertex 2.932112967069701 1.146338233818285 1.5 + vertex 3.629650195061862 1.147700606358877 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.033333333333339 -2 1.5 + vertex 4.372143036323215 -1.373069696241233 1.5 + vertex 4.766666666666669 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.766666666666666 -2 1.5 + vertex -4.381156996247915 -1.354110193305761 1.5 + vertex -4.033333333333331 -2 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -1.069336346600583 0.5464552392209603 1.5 + vertex -1.443006186045382 -0.08298995768770645 1.5 + vertex -1.794730209886672 0.5538947111899133 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.652110134630465 -0.1155549484835552 1.5 + vertex 4.348549180927965 -0.1262957942898617 1.5 + vertex 3.9732539505543 -0.7318262072921322 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.7185542750926248 -0.08933274599124186 1.5 + vertex -1.443006186045382 -0.08298995768770645 1.5 + vertex -1.069336346600583 0.5464552392209603 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.9732539505543 -0.7318262072921322 1.5 + vertex 4.533826812817276 -0.6477019363006411 1.5 + vertex 4.372143036323215 -1.373069696241233 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.5 -1.333333333333336 1.5 + vertex 4.974567456280938 -0.9827921125773349 1.5 + vertex 5.5 -0.6666666666666667 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.5 -0.6666666666666667 1.5 + vertex -4.963973537538942 -0.987067885825776 1.5 + vertex -5.5 -1.333333333333336 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.854257856795574 0.3474859625031357 1.5 + vertex -4.926075293601114 -0.3392665821314123 1.5 + vertex -5.5 0 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.165563740279156 -0.07157834277515596 1.5 + vertex -2.537536482016807 -0.7050924467300033 1.5 + vertex -2.881104939094225 -0.06128471654661727 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.847777614877195 3.043580312578945 1.5 + vertex 2.174143711780794 3.693244847157455 1.5 + vertex 2.5222688176319 3.012170694087664 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.561583637826033 1.200837332544602 1.5 + vertex -3.938709611886719 1.837609013922011 1.5 + vertex -3.208050856029835 1.804690896254801 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -1.794730209886672 0.5538947111899133 1.5 + vertex -1.443006186045382 -0.08298995768770645 1.5 + vertex -2.165563740279156 -0.07157834277515596 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.403555134995218 3.647926557913302 1.5 + vertex -1.723998423743612 4.121593549051743 1.5 + vertex -1.118265021975916 4.222117942277324 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.5 0 1.5 + vertex -4.926075293601114 -0.3392665821314123 1.5 + vertex -5.5 -0.6666666666666667 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -2.881104939094225 -0.06128471654661727 1.5 + vertex -2.537536482016807 -0.7050924467300033 1.5 + vertex -3.250140632039959 -0.688428408781637 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -4.30075581703243 -0.1407896738922965 1.5 + vertex -4.926075293601114 -0.3392665821314123 1.5 + vertex -4.854257856795574 0.3474859625031357 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.403555134995218 3.647926557913302 1.5 + vertex -1.118265021975916 4.222117942277324 1.5 + vertex -0.6746532451845126 3.667631670872276 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.656152982131824 -1.371806223167343 1.5 + vertex 4.372143036323215 -1.373069696241233 1.5 + vertex 4.033333333333339 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.033333333333331 -2 1.5 + vertex -4.381156996247915 -1.354110193305761 1.5 + vertex -3.637342861146872 -1.349080118297037 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.372143036323215 -1.373069696241233 1.5 + vertex 4.533826812817276 -0.6477019363006411 1.5 + vertex 4.974567456280938 -0.9827921125773349 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 5.5 0 1.5 + vertex 4.954580468034143 -0.3396358356818832 1.5 + vertex 4.877559064420447 0.3196921111679707 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.3203822717665369 4.335102417777374 1.5 + vertex 0.4337140373662665 4.235895607879137 1.5 + vertex 0.0387167892632739 3.662594332895794 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.5 -0.6666666666666667 1.5 + vertex -4.926075293601114 -0.3392665821314123 1.5 + vertex -4.963973537538942 -0.987067885825776 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.7652120942042574 3.661745440225192 1.5 + vertex 0.4337140373662665 4.235895607879137 1.5 + vertex 1.141688308026424 4.219048976441587 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.974567456280938 -0.9827921125773349 1.5 + vertex 4.954580468034143 -0.3396358356818832 1.5 + vertex 5.5 -0.6666666666666667 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -1.118265021975916 4.222117942277324 1.5 + vertex -1.723998423743612 4.121593549051743 1.5 + vertex -1.57355755923579 4.685036403620216 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.5 -0.6666666666666667 1.5 + vertex 4.954580468034143 -0.3396358356818832 1.5 + vertex 5.5 0 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.963973537538942 -0.987067885825776 1.5 + vertex -4.502137055787425 -0.7050064017157527 1.5 + vertex -4.381156996247915 -1.354110193305761 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.45482787875139 3.64880628028241 1.5 + vertex 1.691187166672089 4.148810338763331 1.5 + vertex 2.174143711780794 3.693244847157455 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.938709611886719 1.837609013922011 1.5 + vertex -3.497903111842934 2.385066827802327 1.5 + vertex -3.208050856029835 1.804690896254801 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 4.877559064420447 0.3196921111679707 1.5 + vertex 4.954580468034143 -0.3396358356818832 1.5 + vertex 4.348549180927965 -0.1262957942898617 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 2.177810132972474 4.418444552674964 1.5 + vertex 2.742911005948948 4.089626300890396 1.5 + vertex 2.174143711780794 3.693244847157455 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.174143711780794 3.693244847157455 1.5 + vertex 1.691187166672089 4.148810338763331 1.5 + vertex 2.177810132972474 4.418444552674964 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.992602807386213 0.5784873467077816 1.5 + vertex -4.135355791928076 1.253132303242682 1.5 + vertex -3.561583637826033 1.200837332544602 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.6746532451845126 3.667631670872276 1.5 + vertex -1.118265021975916 4.222117942277324 1.5 + vertex -0.3203822717665369 4.335102417777374 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.2623267067475 1.756376831501149 1.5 + vertex 3.546351029634341 2.331835435566113 1.5 + vertex 3.939220674837048 1.707170458185183 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.766666666666669 -2 1.5 + vertex 5.013764158893561 -1.531516112227202 1.5 + vertex 5.5 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.5 -2 1.5 + vertex -5.004481582892931 -1.524929741182224 1.5 + vertex -4.766666666666666 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.930332249235315 2.416335828844156 1.5 + vertex 3.546351029634341 2.331835435566113 1.5 + vertex 3.2623267067475 1.756376831501149 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.629650195061862 1.147700606358877 1.5 + vertex 4.186524573317082 1.187984573172859 1.5 + vertex 4.080077303764824 0.5494644464517151 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.5222688176319 3.012170694087664 1.5 + vertex 3.225877023298945 3.002037394799067 1.5 + vertex 2.930332249235315 2.416335828844156 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 3.225877023298945 3.002037394799067 1.5 + vertex 3.546351029634341 2.331835435566113 1.5 + vertex 2.930332249235315 2.416335828844156 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.2623267067475 1.756376831501149 1.5 + vertex 3.939220674837048 1.707170458185183 1.5 + vertex 3.629650195061862 1.147700606358877 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.5 -2 1.5 + vertex 5.013764158893561 -1.531516112227202 1.5 + vertex 5.5 -1.333333333333336 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.5 -1.333333333333336 1.5 + vertex -5.004481582892931 -1.524929741182224 1.5 + vertex -5.5 -2 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 3.348187859547956 4.363443371601799 1.5 + vertex 2.742911005948948 4.089626300890396 1.5 + vertex 2.749999999999995 4.763139720814415 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.104758878008006 5.081337428812073 1.5 + vertex -2.189271177275879 4.439402784072247 1.5 + vertex -2.750000000000011 4.763139720814406 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -2.750000000000011 4.763139720814406 1.5 + vertex -2.750000000000009 4.11566584733009 1.5 + vertex -3.348187859547972 4.363443371601787 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -3.889087296526017 3.889087296526005 1.5 + vertex -3.700871888778946 3.170742721706044 1.5 + vertex -4.363443371601797 3.348187859547959 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 5.081337428812076 2.104758878007996 1.5 + vertex 4.38127154442434 2.198199387204508 1.5 + vertex 4.763139720814412 2.750000000000002 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.749999999999995 4.763139720814415 1.5 + vertex 2.742911005948948 4.089626300890396 1.5 + vertex 2.177810132972474 4.418444552674964 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -1.57355755923579 4.685036403620216 1.5 + vertex -2.189271177275879 4.439402784072247 1.5 + vertex -2.104758878008006 5.081337428812073 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.280205995969707 3.70041192633012 1.5 + vertex 2.742911005948948 4.089626300890396 1.5 + vertex 3.348187859547956 4.363443371601799 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.348187859547972 4.363443371601787 1.5 + vertex -2.750000000000009 4.11566584733009 1.5 + vertex -3.252827146736721 3.704408250309965 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.363443371601797 3.348187859547959 1.5 + vertex -3.700871888778946 3.170742721706044 1.5 + vertex -4.065361452539194 2.682531394733724 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -3.252827146736721 3.704408250309965 1.5 + vertex -3.700871888778946 3.170742721706044 1.5 + vertex -3.889087296526017 3.889087296526005 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 4.763139720814412 2.750000000000002 1.5 + vertex 4.38127154442434 2.198199387204508 1.5 + vertex 4.030340816201242 2.762411925844113 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.592403655874934 1.584446114812592 1.5 + vertex 4.38127154442434 2.198199387204508 1.5 + vertex 5.081337428812076 2.104758878007996 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.0387167892632739 3.662594332895794 1.5 + vertex 0.4337140373662665 4.235895607879137 1.5 + vertex 0.7652120942042574 3.661745440225192 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.533919615543224 0.9096756578804275 1.5 + vertex -4.135355791928076 1.253132303242682 1.5 + vertex -3.992602807386213 0.5784873467077816 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 0.2903242422441917 4.866212300447543 1.5 + vertex -0.3344962908973508 4.979339141727255 1.5 + vertex -1.13279746910902e-14 5.5 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -4.065361452539194 2.682531394733724 1.5 + vertex -4.497880547870021 2.180785379967064 1.5 + vertex -4.763139720814414 2.749999999999997 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.081337428812079 2.104758878007991 1.5 + vertex -4.497880547870021 2.180785379967064 1.5 + vertex -4.640854525297701 1.529027613171597 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.13279746910902e-14 5.5 1.5 + vertex -0.3344962908973508 4.979339141727255 1.5 + vertex -0.7178940572102954 5.452946737555956 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.177810132972474 4.418444552674964 1.5 + vertex 1.588974763327302 4.698394709324237 1.5 + vertex 2.104758878007986 5.081337428812081 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -4.763139720814414 2.749999999999997 1.5 + vertex -4.497880547870021 2.180785379967064 1.5 + vertex -5.081337428812079 2.104758878007991 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.080077303764824 0.5494644464517151 1.5 + vertex 4.186524573317082 1.187984573172859 1.5 + vertex 4.69127103704674 0.9511412400559269 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.867298633115758 2.439559922802162 1.5 + vertex -3.497903111842934 2.385066827802327 1.5 + vertex -3.076702677749195 3.053971750049437 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -1.423504748063876 5.312592044589873 1.5 + vertex -0.9520750409854828 4.87123153491677 1.5 + vertex -1.57355755923579 4.685036403620216 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 0.717894057210274 5.452946737555958 1.5 + vertex 0.9527312490134241 4.84511117665047 1.5 + vertex 0.2903242422441917 4.866212300447543 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.208050856029835 1.804690896254801 1.5 + vertex -3.497903111842934 2.385066827802327 1.5 + vertex -2.867298633115758 2.439559922802162 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.640854525297701 1.529027613171597 1.5 + vertex -4.497880547870021 2.180785379967064 1.5 + vertex -3.938709611886719 1.837609013922011 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.867298633115758 2.439559922802162 1.5 + vertex -3.076702677749195 3.053971750049437 1.5 + vertex -2.469745241963482 3.04465005287059 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.889087296526007 3.889087296526015 1.5 + vertex 3.757790900719538 3.340427280609457 1.5 + vertex 3.280205995969707 3.70041192633012 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.030340816201242 2.762411925844113 1.5 + vertex 3.757790900719538 3.340427280609457 1.5 + vertex 4.36344337160179 3.348187859547969 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.372143036323215 -1.373069696241233 1.5 + vertex 5.013764158893561 -1.531516112227202 1.5 + vertex 4.766666666666669 -2 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.766666666666666 -2 1.5 + vertex -5.004481582892931 -1.524929741182224 1.5 + vertex -4.381156996247915 -1.354110193305761 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 2.104758878007986 5.081337428812081 1.5 + vertex 1.588974763327302 4.698394709324237 1.5 + vertex 1.423504748063855 5.312592044589878 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.640854525297701 1.529027613171597 1.5 + vertex -5.012691359437782 0.9968593824494634 1.5 + vertex -5.312592044589876 1.423504748063862 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -5.452946737555957 0.7178940572102825 1.5 + vertex -5.012691359437782 0.9968593824494634 1.5 + vertex -4.854257856795574 0.3474859625031357 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 4.974567456280938 -0.9827921125773349 1.5 + vertex 5.013764158893561 -1.531516112227202 1.5 + vertex 4.372143036323215 -1.373069696241233 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -4.381156996247915 -1.354110193305761 1.5 + vertex -5.004481582892931 -1.524929741182224 1.5 + vertex -4.963973537538942 -0.987067885825776 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.939220674837048 1.707170458185183 1.5 + vertex 4.38127154442434 2.198199387204508 1.5 + vertex 4.592403655874934 1.584446114812592 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 3.225877023298945 3.002037394799067 1.5 + vertex 2.738886295336481 3.523065267343544 1.5 + vertex 3.280205995969707 3.70041192633012 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -0.7178940572102954 5.452946737555956 1.5 + vertex -0.9520750409854828 4.87123153491677 1.5 + vertex -1.423504748063876 5.312592044589873 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.5222688176319 3.012170694087664 1.5 + vertex 2.738886295336481 3.523065267343544 1.5 + vertex 3.225877023298945 3.002037394799067 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 1.423504748063855 5.312592044589878 1.5 + vertex 0.9527312490134241 4.84511117665047 1.5 + vertex 0.717894057210274 5.452946737555958 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.252827146736721 3.704408250309965 1.5 + vertex -2.695995150692301 3.559379717266014 1.5 + vertex -3.076702677749195 3.053971750049437 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 4.36344337160179 3.348187859547969 1.5 + vertex 3.757790900719538 3.340427280609457 1.5 + vertex 3.889087296526007 3.889087296526015 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.189271177275879 4.439402784072247 1.5 + vertex -1.723998423743612 4.121593549051743 1.5 + vertex -2.14368761686899 3.703602060025339 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.854257856795574 0.3474859625031357 1.5 + vertex -5.012691359437782 0.9968593824494634 1.5 + vertex -4.533919615543224 0.9096756578804275 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -3.938723634516724 -0.7037976734235176 1.5 + vertex -4.502137055787425 -0.7050064017157527 1.5 + vertex -4.30075581703243 -0.1407896738922965 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.30075581703243 -0.1407896738922965 1.5 + vertex -4.502137055787425 -0.7050064017157527 1.5 + vertex -4.926075293601114 -0.3392665821314123 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.076702677749195 3.053971750049437 1.5 + vertex -2.695995150692301 3.559379717266014 1.5 + vertex -2.469745241963482 3.04465005287059 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.189271177275879 4.439402784072247 1.5 + vertex -2.750000000000009 4.11566584733009 1.5 + vertex -2.750000000000011 4.763139720814406 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.533919615543224 0.9096756578804275 1.5 + vertex -5.012691359437782 0.9968593824494634 1.5 + vertex -4.640854525297701 1.529027613171597 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -2.14368761686899 3.703602060025339 1.5 + vertex -2.695995150692301 3.559379717266014 1.5 + vertex -2.750000000000009 4.11566584733009 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.57355755923579 4.685036403620216 1.5 + vertex -0.9520750409854828 4.87123153491677 1.5 + vertex -1.118265021975916 4.222117942277324 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -3.252827146736721 3.704408250309965 1.5 + vertex -3.076702677749195 3.053971750049437 1.5 + vertex -3.700871888778946 3.170742721706044 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 3.280205995969707 3.70041192633012 1.5 + vertex 3.757790900719538 3.340427280609457 1.5 + vertex 3.225877023298945 3.002037394799067 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex -0.3344962908973508 4.979339141727255 1.5 + vertex -0.9520750409854828 4.87123153491677 1.5 + vertex -0.7178940572102954 5.452946737555956 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.588974763327302 4.698394709324237 1.5 + vertex 0.9527312490134241 4.84511117665047 1.5 + vertex 1.423504748063855 5.312592044589878 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.141688308026424 4.219048976441587 1.5 + vertex 0.9527312490134241 4.84511117665047 1.5 + vertex 1.588974763327302 4.698394709324237 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.14368761686899 3.703602060025339 1.5 + vertex -1.723998423743612 4.121593549051743 1.5 + vertex -1.403555134995218 3.647926557913302 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -2.469745241963482 3.04465005287059 1.5 + vertex -2.695995150692301 3.559379717266014 1.5 + vertex -2.14368761686899 3.703602060025339 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 4.348549180927965 -0.1262957942898617 1.5 + vertex 4.533826812817276 -0.6477019363006411 1.5 + vertex 3.9732539505543 -0.7318262072921322 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 1.141688308026424 4.219048976441587 1.5 + vertex 1.691187166672089 4.148810338763331 1.5 + vertex 1.45482787875139 3.64880628028241 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.561583637826033 1.200837332544602 1.5 + vertex -4.135355791928076 1.253132303242682 1.5 + vertex -3.938709611886719 1.837609013922011 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -3.938709611886719 1.837609013922011 1.5 + vertex -4.135355791928076 1.253132303242682 1.5 + vertex -4.640854525297701 1.529027613171597 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -5.312592044589876 1.423504748063862 1.5 + vertex -5.012691359437782 0.9968593824494634 1.5 + vertex -5.452946737555957 0.7178940572102825 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 5.5 -1.333333333333336 1.5 + vertex 5.013764158893561 -1.531516112227202 1.5 + vertex 4.974567456280938 -0.9827921125773349 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.963973537538942 -0.987067885825776 1.5 + vertex -5.004481582892931 -1.524929741182224 1.5 + vertex -5.5 -1.333333333333336 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.742911005948948 4.089626300890396 1.5 + vertex 2.738886295336481 3.523065267343544 1.5 + vertex 2.174143711780794 3.693244847157455 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -4.926075293601114 -0.3392665821314123 1.5 + vertex -4.502137055787425 -0.7050064017157527 1.5 + vertex -4.963973537538942 -0.987067885825776 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.974567456280938 -0.9827921125773349 1.5 + vertex 4.533826812817276 -0.6477019363006411 1.5 + vertex 4.954580468034143 -0.3396358356818832 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 2.174143711780794 3.693244847157455 1.5 + vertex 2.738886295336481 3.523065267343544 1.5 + vertex 2.5222688176319 3.012170694087664 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -4.640854525297701 1.529027613171597 1.5 + vertex -4.135355791928076 1.253132303242682 1.5 + vertex -4.533919615543224 0.9096756578804275 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 4.954580468034143 -0.3396358356818832 1.5 + vertex 4.533826812817276 -0.6477019363006411 1.5 + vertex 4.348549180927965 -0.1262957942898617 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex 4.69127103704674 0.9511412400559269 1.5 + vertex 4.186524573317082 1.187984573172859 1.5 + vertex 4.592403655874934 1.584446114812592 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 3.280205995969707 3.70041192633012 1.5 + vertex 2.738886295336481 3.523065267343544 1.5 + vertex 2.742911005948948 4.089626300890396 1.5 + endloop +endfacet +facet normal 0 0 -1 + outer loop + vertex -1.57355755923579 4.685036403620216 1.5 + vertex -1.723998423743612 4.121593549051743 1.5 + vertex -2.189271177275879 4.439402784072247 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex -2.750000000000009 4.11566584733009 1.5 + vertex -2.695995150692301 3.559379717266014 1.5 + vertex -3.252827146736721 3.704408250309965 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 4.592403655874934 1.584446114812592 1.5 + vertex 4.186524573317082 1.187984573172859 1.5 + vertex 3.939220674837048 1.707170458185183 1.5 + endloop +endfacet +facet normal -0 0 -1 + outer loop + vertex 2.177810132972474 4.418444552674964 1.5 + vertex 1.691187166672089 4.148810338763331 1.5 + vertex 1.588974763327302 4.698394709324237 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 3.939220674837048 1.707170458185183 1.5 + vertex 4.186524573317082 1.187984573172859 1.5 + vertex 3.629650195061862 1.147700606358877 1.5 + endloop +endfacet +facet normal 0 -0 -1 + outer loop + vertex 1.588974763327302 4.698394709324237 1.5 + vertex 1.691187166672089 4.148810338763331 1.5 + vertex 1.141688308026424 4.219048976441587 1.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.452946737555957 0.7178940572102823 21.5 + vertex 5.312592044589876 1.423504748063862 21.5 + vertex 4.585155055551279 0.9206986467201828 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.312592044589875 1.423504748063864 21.5 + vertex -5.452946737555957 0.7178940572102843 21.5 + vertex -4.69130155165728 0.9510560801816688 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.851795212957035 0.3136504576734964 21.5 + vertex 3.95607084917357 0.5694139263736586 21.5 + vertex 4.294397132808166 -0.1476737307457339 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 3.95607084917357 0.5694139263736586 21.5 + vertex 4.851795212957035 0.3136504576734964 21.5 + vertex 4.585155055551279 0.9206986467201828 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 4.851795212957035 0.3136504576734964 21.5 + vertex 5.452946737555957 0.7178940572102823 21.5 + vertex 4.585155055551279 0.9206986467201828 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.312592044589876 1.423504748063862 21.5 + vertex 4.57664415675873 1.616911069653527 21.5 + vertex 4.585155055551279 0.9206986467201828 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -5.452946737555957 0.7178940572102843 21.5 + vertex -4.877559064420448 0.3196921111679707 21.5 + vertex -4.69130155165728 0.9510560801816688 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.592403655874935 1.584446114812588 21.5 + vertex -5.312592044589875 1.423504748063864 21.5 + vertex -4.69130155165728 0.9510560801816688 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.080333626493353 0.5487491035079626 21.5 + vertex -4.877559064420448 0.3196921111679707 21.5 + vertex -4.349689637699501 -0.1295132896712743 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -4.381272568689584 2.198196544719015 21.5 + vertex -3.939232720196334 1.707137030555781 21.5 + vertex -3.546351029634339 2.331835435566118 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.700778955016418 3.171162424982228 21.5 + vertex 3.076600308961155 3.054443667699625 21.5 + vertex 3.491373889216018 2.418229010193856 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 3.927950274508524 1.880549173906596 21.5 + vertex 4.065334361405515 2.682654285971688 21.5 + vertex 3.491373889216018 2.418229010193856 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.877559064420448 0.3196921111679707 21.5 + vertex -4.080333626493353 0.5487491035079626 21.5 + vertex -4.69130155165728 0.9510560801816688 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.030340816201242 2.762411925844111 21.5 + vertex -4.381272568689584 2.198196544719015 21.5 + vertex -3.546351029634339 2.331835435566118 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.065334361405515 2.682654285971688 21.5 + vertex 3.700778955016418 3.171162424982228 21.5 + vertex 3.491373889216018 2.418229010193856 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.065334361405515 2.682654285971688 21.5 + vertex 3.927950274508524 1.880549173906596 21.5 + vertex 4.482881188459852 2.20697468150796 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.141756343751128 4.219078366244001 21.5 + vertex -0.433737444740777 4.235884502737899 21.5 + vertex -0.9527252825573536 4.84504087071608 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.225877023298942 3.002037394799064 21.5 + vertex -4.030340816201242 2.762411925844111 21.5 + vertex -3.546351029634339 2.331835435566118 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -0.433737444740777 4.235884502737899 21.5 + vertex -0.2903224774583585 4.866202495597054 21.5 + vertex -0.9527252825573536 4.84504087071608 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.938849291627158 -0.7035546146220737 21.5 + vertex 3.637341001405353 -1.349083275249484 21.5 + vertex 4.381165749274791 -1.354092706347899 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.250178876801736 -0.6883211458698835 21.5 + vertex 3.637341001405353 -1.349083275249484 21.5 + vertex 3.938849291627158 -0.7035546146220737 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3344959061109473 4.979339280507027 21.5 + vertex 0.3203755464932684 4.335103306945019 21.5 + vertex 0.9520749167050213 4.87123425426997 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.637341001405353 -1.349083275249484 21.5 + vertex 3.250178876801736 -0.6883211458698835 21.5 + vertex 2.919203952883906 -1.345410824862665 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.3203755464932684 4.335103306945019 21.5 + vertex 1.118262403643518 4.222118878480422 21.5 + vertex 0.9520749167050213 4.87123425426997 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.030340816201242 2.762411925844111 21.5 + vertex -3.225877023298942 3.002037394799064 21.5 + vertex -3.757790900719538 3.340427280609455 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3203755464932684 4.335103306945019 21.5 + vertex -0.2903224774583585 4.866202495597054 21.5 + vertex -0.433737444740777 4.235884502737899 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.192818607269999 -1.353240476912664 21.5 + vertex 2.919203952883906 -1.345410824862665 21.5 + vertex 2.537367542003185 -0.7051667814373728 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.930332249235313 2.416335828844155 21.5 + vertex -3.262340651152442 1.756338215678496 21.5 + vertex -2.567062035605035 1.791390380062655 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.938849291627158 -0.7035546146220737 21.5 + vertex 4.381165749274791 -1.354092706347899 21.5 + vertex 4.500892095088886 -0.7063311033856396 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -3.262340651152442 1.756338215678496 21.5 + vertex -2.932138305748578 1.146268488836126 21.5 + vertex -2.567062035605035 1.791390380062655 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 2.919203952883906 -1.345410824862665 21.5 + vertex 3.250178876801736 -0.6883211458698835 21.5 + vertex 2.537367542003185 -0.7051667814373728 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.932138305748578 1.146268488836126 21.5 + vertex -2.209067738968753 1.155230187581915 21.5 + vertex -2.567062035605035 1.791390380062655 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.093308855737858 -0.7267213589704995 21.5 + vertex 1.815393450381904 -0.7111437594340928 21.5 + vertex 1.442714337457756 -0.08312031228002326 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.2903224774583585 4.866202495597054 21.5 + vertex 0.3203755464932684 4.335103306945019 21.5 + vertex 0.3344959061109473 4.979339280507027 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 3.299999999999997 -2 21.5 + vertex 3.637341001405353 -1.349083275249484 21.5 + vertex 2.919203952883906 -1.345410824862665 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.566666666666663 -2 21.5 + vertex 3.299999999999997 -2 21.5 + vertex 2.919203952883906 -1.345410824862665 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.452946737555957 0.7178940572102843 21.5 + vertex -5.5 0 21.5 + vertex -4.877559064420448 0.3196921111679707 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.5 0 21.5 + vertex 5.452946737555957 0.7178940572102823 21.5 + vertex 4.851795212957035 0.3136504576734964 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 1.815393450381904 -0.7111437594340928 21.5 + vertex 2.165378219990663 -0.07175024280788911 21.5 + vertex 1.442714337457756 -0.08312031228002326 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.7414788728394006 -0.09717752935253277 21.5 + vertex -0.0003284348192944384 -0.0977091221641091 21.5 + vertex -0.3830235741399194 0.5366644331615591 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -3.29406767269576 -0.7398072077418893 21.5 + vertex -2.933846202610533 -0.1103726985240749 21.5 + vertex -3.652670293182509 -0.1170884969296826 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.29406767269576 -0.7398072077418893 21.5 + vertex -3.652670293182509 -0.1170884969296826 21.5 + vertex -3.973779619446876 -0.7328053431432462 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.56767899517021 -0.7355385695505063 21.5 + vertex -2.933846202610533 -0.1103726985240749 21.5 + vertex -3.29406767269576 -0.7398072077418893 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.7414788728394006 -0.09717752935253277 21.5 + vertex -0.3698539599991226 -0.7306166050531608 21.5 + vertex -0.0003284348192944384 -0.0977091221641091 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 2.192818607269999 -1.353240476912664 21.5 + vertex 2.566666666666663 -2 21.5 + vertex 2.919203952883906 -1.345410824862665 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -3.656461147653646 -1.372636668532488 21.5 + vertex -3.300000000000008 -2 21.5 + vertex -2.931674366318449 -1.369142425851804 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.209067738968753 1.155230187581915 21.5 + vertex -2.932138305748578 1.146268488836126 21.5 + vertex -2.571942814969939 0.519935777709521 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 1.815393450381904 -0.7111437594340928 21.5 + vertex 2.192818607269999 -1.353240476912664 21.5 + vertex 2.537367542003185 -0.7051667814373728 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.0003284348192944384 -0.0977091221641091 21.5 + vertex 0.7182956924189055 -0.08943793981447623 21.5 + vertex 0.3458814719110396 0.5400512253409957 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 0.7182956924189055 -0.08943793981447623 21.5 + vertex 1.069260257467189 0.5464686057282293 21.5 + vertex 0.3458814719110396 0.5400512253409957 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.03877143035215522 3.662593140451773 21.5 + vertex 0.6746429829520909 3.667626241535941 21.5 + vertex 0.3203755464932684 4.335103306945019 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.656461147653646 -1.372636668532488 21.5 + vertex -2.931674366318449 -1.369142425851804 21.5 + vertex -3.29406767269576 -0.7398072077418893 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.6746429829520909 3.667626241535941 21.5 + vertex -0.03877143035215522 3.662593140451773 21.5 + vertex 0.3240099576525266 3.048440257297984 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -3.656461147653646 -1.372636668532488 21.5 + vertex -3.29406767269576 -0.7398072077418893 21.5 + vertex -3.973779619446876 -0.7328053431432462 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 3.236693544835511 0.5634082118962884 21.5 + vertex 3.595497694612638 -0.05886226124304361 21.5 + vertex 3.95607084917357 0.5694139263736586 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.3698539599991226 -0.7306166050531608 21.5 + vertex -0.7414788728394006 -0.09717752935253277 21.5 + vertex -1.104632430868294 -0.7312497760535948 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.05144846570144 3.051775440361086 21.5 + vertex 0.6746429829520909 3.667626241535941 21.5 + vertex 0.3240099576525266 3.048440257297984 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 0.6927293742293714 2.430177632206291 21.5 + vertex 1.05144846570144 3.051775440361086 21.5 + vertex 0.3240099576525266 3.048440257297984 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.95607084917357 0.5694139263736586 21.5 + vertex 3.595497694612638 -0.05886226124304361 21.5 + vertex 4.294397132808166 -0.1476737307457339 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.656461147653646 -1.372636668532488 21.5 + vertex -3.973779619446876 -0.7328053431432462 21.5 + vertex -4.37221496357463 -1.373106480595391 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.033333333333339 -2 21.5 + vertex -3.300000000000008 -2 21.5 + vertex -3.656461147653646 -1.372636668532488 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.299999999999997 -2 21.5 + vertex 4.033333333333331 -2 21.5 + vertex 3.637341001405353 -1.349083275249484 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.842230952217181 0.5294468965956347 21.5 + vertex -2.209067738968753 1.155230187581915 21.5 + vertex -2.571942814969939 0.519935777709521 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.931674366318449 -1.369142425851804 21.5 + vertex -2.56767899517021 -0.7355385695505063 21.5 + vertex -3.29406767269576 -0.7398072077418893 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.462296853356563 -1.362765086356661 21.5 + vertex 2.192818607269999 -1.353240476912664 21.5 + vertex 1.815393450381904 -0.7111437594340928 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -0.7357268796779431 -1.363510057891918 21.5 + vertex -0.3698539599991226 -0.7306166050531608 21.5 + vertex -1.104632430868294 -0.7312497760535948 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.595497694612638 -0.05886226124304361 21.5 + vertex 3.250178876801736 -0.6883211458698835 21.5 + vertex 3.938849291627158 -0.7035546146220737 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.3830235741399194 0.5366644331615591 21.5 + vertex -0.0003284348192944384 -0.0977091221641091 21.5 + vertex 0.3458814719110396 0.5400512253409957 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 1.833333333333327 -2 21.5 + vertex 2.192818607269999 -1.353240476912664 21.5 + vertex 1.462296853356563 -1.362765086356661 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -3.652670293182509 -0.1170884969296826 21.5 + vertex -3.298593717973138 0.5094064443387398 21.5 + vertex -4.080333626493353 0.5487491035079626 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.56767899517021 -0.7355385695505063 21.5 + vertex -2.20451534066643 -0.1030192144988487 21.5 + vertex -2.933846202610533 -0.1103726985240749 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.236693544835511 0.5634082118962884 21.5 + vertex 2.881232144690902 -0.06113423873704216 21.5 + vertex 3.595497694612638 -0.05886226124304361 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.652670293182509 -0.1170884969296826 21.5 + vertex -2.933846202610533 -0.1103726985240749 21.5 + vertex -3.298593717973138 0.5094064443387398 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.566666666666677 -2 21.5 + vertex -2.200789878856349 -1.365822432420879 21.5 + vertex -2.931674366318449 -1.369142425851804 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.562320624145101 1.202481060232584 21.5 + vertex 3.236693544835511 0.5634082118962884 21.5 + vertex 3.95607084917357 0.5694139263736586 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.300000000000008 -2 21.5 + vertex -2.566666666666677 -2 21.5 + vertex -2.931674366318449 -1.369142425851804 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.05144846570144 3.051775440361086 21.5 + vertex 0.6927293742293714 2.430177632206291 21.5 + vertex 1.417659435571495 2.431414775981395 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.6927293742293714 2.430177632206291 21.5 + vertex 1.058674082092304 1.804225378348518 21.5 + vertex 1.417659435571495 2.431414775981395 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.872603783248366 1.18627598293638 21.5 + vertex 2.515068376510828 0.5590417123785598 21.5 + vertex 3.236693544835511 0.5634082118962884 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -0.3666666666666831 -2 21.5 + vertex -0.0009550981271251128 -1.364723487919695 21.5 + vertex -0.7357268796779431 -1.363510057891918 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -3.298593717973138 0.5094064443387398 21.5 + vertex -2.933846202610533 -0.1103726985240749 21.5 + vertex -2.571942814969939 0.519935777709521 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.6927293742293714 2.430177632206291 21.5 + vertex 0.3240099576525266 3.048440257297984 21.5 + vertex -0.03517957411658879 2.426381474066758 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.7357268796779431 -1.363510057891918 21.5 + vertex -0.0009550981271251128 -1.364723487919695 21.5 + vertex -0.3698539599991226 -0.7306166050531608 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.209067738968753 1.155230187581915 21.5 + vertex -1.480578271695582 1.163377739725285 21.5 + vertex -1.843365012587536 1.792316515686392 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.09999999999999 -2 21.5 + vertex 1.833333333333327 -2 21.5 + vertex 1.462296853356563 -1.362765086356661 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.468777573016966 -1.3652345429877 21.5 + vertex -1.100000000000015 -2 21.5 + vertex -0.7357268796779431 -1.363510057891918 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.931674366318449 -1.369142425851804 21.5 + vertex -2.200789878856349 -1.365822432420879 21.5 + vertex -2.56767899517021 -0.7355385695505063 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -2.567062035605035 1.791390380062655 21.5 + vertex -2.209067738968753 1.155230187581915 21.5 + vertex -1.843365012587536 1.792316515686392 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 2.872603783248366 1.18627598293638 21.5 + vertex 3.236693544835511 0.5634082118962884 21.5 + vertex 3.562320624145101 1.202481060232584 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 0.3321055711695467 1.800474544420946 21.5 + vertex 0.6927293742293714 2.430177632206291 21.5 + vertex -0.03517957411658879 2.426381474066758 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.508243432297509 1.811161058545494 21.5 + vertex 2.149559208878152 1.182603946683908 21.5 + vertex 2.872603783248366 1.18627598293638 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.932138305748578 1.146268488836126 21.5 + vertex -3.298593717973138 0.5094064443387398 21.5 + vertex -2.571942814969939 0.519935777709521 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.652670293182509 -0.1170884969296826 21.5 + vertex -4.080333626493353 0.5487491035079626 21.5 + vertex -4.349689637699501 -0.1295132896712743 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.833333333333345 -2 21.5 + vertex -1.100000000000015 -2 21.5 + vertex -1.468777573016966 -1.3652345429877 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.100000000000015 -2 21.5 + vertex -0.3666666666666831 -2 21.5 + vertex -0.7357268796779431 -1.363510057891918 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.7182956924189055 -0.08943793981447623 21.5 + vertex 1.093308855737858 -0.7267213589704995 21.5 + vertex 1.442714337457756 -0.08312031228002326 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.455025852178601 3.648821126939371 21.5 + vertex -0.765502698122782 3.661708532968327 21.5 + vertex -1.141756343751128 4.219078366244001 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.508243432297509 1.811161058545494 21.5 + vertex 2.872603783248366 1.18627598293638 21.5 + vertex 3.20803536070862 1.805619974416543 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.468777573016966 -1.3652345429877 21.5 + vertex -0.7357268796779431 -1.363510057891918 21.5 + vertex -1.104632430868294 -0.7312497760535948 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.3698539599991226 -0.7306166050531608 21.5 + vertex 0.364529527710049 -0.7312386100132455 21.5 + vertex -0.0003284348192944384 -0.0977091221641091 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3666666666666538 -2 21.5 + vertex 1.09999999999999 -2 21.5 + vertex 0.7315090795513615 -1.364804648857788 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 1.784362640076655 1.807659438405761 21.5 + vertex 2.149559208878152 1.182603946683908 21.5 + vertex 2.508243432297509 1.811161058545494 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.3698539599991226 -0.7306166050531608 21.5 + vertex -0.0009550981271251128 -1.364723487919695 21.5 + vertex 0.364529527710049 -0.7312386100132455 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.236693544835511 0.5634082118962884 21.5 + vertex 2.515068376510828 0.5590417123785598 21.5 + vertex 2.881232144690902 -0.06113423873704216 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.124417814192195 3.049079603007134 21.5 + vertex -0.765502698122782 3.661708532968327 21.5 + vertex -1.455025852178601 3.648821126939371 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.872603783248366 1.18627598293638 21.5 + vertex 3.562320624145101 1.202481060232584 21.5 + vertex 3.20803536070862 1.805619974416543 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 1.093308855737858 -0.7267213589704995 21.5 + vertex 1.462296853356563 -1.362765086356661 21.5 + vertex 1.815393450381904 -0.7111437594340928 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.20451534066643 -0.1030192144988487 21.5 + vertex -1.474921789997072 -0.09874072038935555 21.5 + vertex -1.842230952217181 0.5294468965956347 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.867303180212432 2.439562575974977 21.5 + vertex 2.508243432297509 1.811161058545494 21.5 + vertex 3.20803536070862 1.805619974416543 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.842230952217181 0.5294468965956347 21.5 + vertex -1.480578271695582 1.163377739725285 21.5 + vertex -2.209067738968753 1.155230187581915 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.058674082092304 1.804225378348518 21.5 + vertex 1.784362640076655 1.807659438405761 21.5 + vertex 1.417659435571495 2.431414775981395 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.784362640076655 1.807659438405761 21.5 + vertex 1.424381115798011 1.178073588603486 21.5 + vertex 2.149559208878152 1.182603946683908 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.847955632052608 3.043560626390439 21.5 + vertex -1.124417814192195 3.049079603007134 21.5 + vertex -1.455025852178601 3.648821126939371 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.364529527710049 -0.7312386100132455 21.5 + vertex 0.7315090795513615 -1.364804648857788 21.5 + vertex 1.093308855737858 -0.7267213589704995 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.483697480222967 2.420610379027217 21.5 + vertex -0.759497441329994 2.423401467252223 21.5 + vertex -1.124417814192195 3.049079603007134 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.842230952217181 0.5294468965956347 21.5 + vertex -1.114097168792748 0.5342953322494912 21.5 + vertex -1.480578271695582 1.163377739725285 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.480578271695582 1.163377739725285 21.5 + vertex -0.753566332498671 1.166438832469177 21.5 + vertex -1.119121313197568 1.793943689838691 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.474921789997072 -0.09874072038935555 21.5 + vertex -1.83703550967926 -0.7322192006469028 21.5 + vertex -1.104632430868294 -0.7312497760535948 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.483697480222967 2.420610379027217 21.5 + vertex -1.124417814192195 3.049079603007134 21.5 + vertex -1.847955632052608 3.043560626390439 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3321055711695467 1.800474544420946 21.5 + vertex 1.058674082092304 1.804225378348518 21.5 + vertex 0.6927293742293714 2.430177632206291 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.7315090795513615 -1.364804648857788 21.5 + vertex 1.09999999999999 -2 21.5 + vertex 1.462296853356563 -1.362765086356661 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.119121313197568 1.793943689838691 21.5 + vertex -0.3937079076063562 1.796942957384971 21.5 + vertex -0.759497441329994 2.423401467252223 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.56767899517021 -0.7355385695505063 21.5 + vertex -1.83703550967926 -0.7322192006469028 21.5 + vertex -2.20451534066643 -0.1030192144988487 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 2.14397238962456 2.436439266417713 21.5 + vertex 2.508243432297509 1.811161058545494 21.5 + vertex 2.867303180212432 2.439562575974977 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.7414788728394006 -0.09717752935253277 21.5 + vertex -1.474921789997072 -0.09874072038935555 21.5 + vertex -1.104632430868294 -0.7312497760535948 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.124417814192195 3.049079603007134 21.5 + vertex -0.4008100724989979 3.052087615166054 21.5 + vertex -0.765502698122782 3.661708532968327 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.119121313197568 1.793943689838691 21.5 + vertex -0.759497441329994 2.423401467252223 21.5 + vertex -1.483697480222967 2.420610379027217 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 1.77476966170464 3.058211500149 21.5 + vertex 2.469746722367153 3.044661712432676 21.5 + vertex 2.143688462981651 3.703606637301787 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -2.20451534066643 -0.1030192144988487 21.5 + vertex -1.83703550967926 -0.7322192006469028 21.5 + vertex -1.474921789997072 -0.09874072038935555 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.119121313197568 1.793943689838691 21.5 + vertex -0.753566332498671 1.166438832469177 21.5 + vertex -0.3937079076063562 1.796942957384971 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.14397238962456 2.436439266417713 21.5 + vertex 2.867303180212432 2.439562575974977 21.5 + vertex 2.469746722367153 3.044661712432676 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.842230952217181 0.5294468965956347 21.5 + vertex -1.474921789997072 -0.09874072038935555 21.5 + vertex -1.114097168792748 0.5342953322494912 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.480578271695582 1.163377739725285 21.5 + vertex -1.114097168792748 0.5342953322494912 21.5 + vertex -0.753566332498671 1.166438832469177 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.207597520252746 2.418532568299296 21.5 + vertex -1.847955632052608 3.043560626390439 21.5 + vertex -2.522298487161135 3.012167413056245 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.124417814192195 3.049079603007134 21.5 + vertex -0.759497441329994 2.423401467252223 21.5 + vertex -0.4008100724989979 3.052087615166054 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.765502698122782 3.661708532968327 21.5 + vertex -0.4008100724989979 3.052087615166054 21.5 + vertex -0.03877143035215522 3.662593140451773 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.566666666666677 -2 21.5 + vertex -1.833333333333345 -2 21.5 + vertex -2.200789878856349 -1.365822432420879 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.833333333333327 -2 21.5 + vertex 2.566666666666663 -2 21.5 + vertex 2.192818607269999 -1.353240476912664 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3240099576525266 3.048440257297984 21.5 + vertex -0.4008100724989979 3.052087615166054 21.5 + vertex -0.03517957411658879 2.426381474066758 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.4008100724989979 3.052087615166054 21.5 + vertex -0.759497441329994 2.423401467252223 21.5 + vertex -0.03517957411658879 2.426381474066758 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.784362640076655 1.807659438405761 21.5 + vertex 2.508243432297509 1.811161058545494 21.5 + vertex 2.14397238962456 2.436439266417713 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.3666666666666831 -2 21.5 + vertex 0.3666666666666538 -2 21.5 + vertex -0.0009550981271251128 -1.364723487919695 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 1.77476966170464 3.058211500149 21.5 + vertex 2.143688462981651 3.703606637301787 21.5 + vertex 1.403555195493685 3.647927471976819 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.595497694612638 -0.05886226124304361 21.5 + vertex 2.881232144690902 -0.06113423873704216 21.5 + vertex 3.250178876801736 -0.6883211458698835 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 1.058674082092304 1.804225378348518 21.5 + vertex 1.424381115798011 1.178073588603486 21.5 + vertex 1.784362640076655 1.807659438405761 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.0003284348192944384 -0.0977091221641091 21.5 + vertex 0.364529527710049 -0.7312386100132455 21.5 + vertex 0.7182956924189055 -0.08943793981447623 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.3937079076063562 1.796942957384971 21.5 + vertex 0.3321055711695467 1.800474544420946 21.5 + vertex -0.03517957411658879 2.426381474066758 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.3321055711695467 1.800474544420946 21.5 + vertex 0.6985093609911199 1.174015816774994 21.5 + vertex 1.058674082092304 1.804225378348518 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 2.14397238962456 2.436439266417713 21.5 + vertex 2.469746722367153 3.044661712432676 21.5 + vertex 1.77476966170464 3.058211500149 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.3937079076063562 1.796942957384971 21.5 + vertex -0.02742447045176344 1.170305558359778 21.5 + vertex 0.3321055711695467 1.800474544420946 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.207597520252746 2.418532568299296 21.5 + vertex -2.522298487161135 3.012167413056245 21.5 + vertex -2.930332249235313 2.416335828844155 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.0009550981271251128 -1.364723487919695 21.5 + vertex 0.3666666666666538 -2 21.5 + vertex 0.7315090795513615 -1.364804648857788 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.483697480222967 2.420610379027217 21.5 + vertex -1.847955632052608 3.043560626390439 21.5 + vertex -2.207597520252746 2.418532568299296 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -2.200789878856349 -1.365822432420879 21.5 + vertex -1.833333333333345 -2 21.5 + vertex -1.468777573016966 -1.3652345429877 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.872603783248366 1.18627598293638 21.5 + vertex 2.149559208878152 1.182603946683908 21.5 + vertex 2.515068376510828 0.5590417123785598 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.093308855737858 -0.7267213589704995 21.5 + vertex 0.7315090795513615 -1.364804648857788 21.5 + vertex 1.462296853356563 -1.362765086356661 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 1.05144846570144 3.051775440361086 21.5 + vertex 1.403555195493685 3.647927471976819 21.5 + vertex 0.6746429829520909 3.667626241535941 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.480578271695582 1.163377739725285 21.5 + vertex -1.119121313197568 1.793943689838691 21.5 + vertex -1.843365012587536 1.792316515686392 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.364529527710049 -0.7312386100132455 21.5 + vertex -0.0009550981271251128 -1.364723487919695 21.5 + vertex 0.7315090795513615 -1.364804648857788 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -0.759497441329994 2.423401467252223 21.5 + vertex -0.3937079076063562 1.796942957384971 21.5 + vertex -0.03517957411658879 2.426381474066758 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.03877143035215522 3.662593140451773 21.5 + vertex -0.4008100724989979 3.052087615166054 21.5 + vertex 0.3240099576525266 3.048440257297984 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.058674082092304 1.804225378348518 21.5 + vertex 0.6985093609911199 1.174015816774994 21.5 + vertex 1.424381115798011 1.178073588603486 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.483697480222967 2.420610379027217 21.5 + vertex -2.207597520252746 2.418532568299296 21.5 + vertex -1.843365012587536 1.792316515686392 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.3937079076063562 1.796942957384971 21.5 + vertex -0.753566332498671 1.166438832469177 21.5 + vertex -0.02742447045176344 1.170305558359778 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3321055711695467 1.800474544420946 21.5 + vertex -0.02742447045176344 1.170305558359778 21.5 + vertex 0.6985093609911199 1.174015816774994 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.83703550967926 -0.7322192006469028 21.5 + vertex -1.468777573016966 -1.3652345429877 21.5 + vertex -1.104632430868294 -0.7312497760535948 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.77476966170464 3.058211500149 21.5 + vertex 1.403555195493685 3.647927471976819 21.5 + vertex 1.05144846570144 3.051775440361086 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.364529527710049 -0.7312386100132455 21.5 + vertex 1.093308855737858 -0.7267213589704995 21.5 + vertex 0.7182956924189055 -0.08943793981447623 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.104758878007986 5.081337428812081 21.5 + vertex -2.749999999999996 4.763139720814415 21.5 + vertex -2.177802216173823 4.4185051541547 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.114097168792748 0.5342953322494912 21.5 + vertex -1.474921789997072 -0.09874072038935555 21.5 + vertex -0.7414788728394006 -0.09717752935253277 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.104758878008006 5.081337428812073 21.5 + vertex 1.423504748063873 5.312592044589874 21.5 + vertex 1.573557187374463 4.685038720206226 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.20451534066643 -0.1030192144988487 21.5 + vertex -1.842230952217181 0.5294468965956347 21.5 + vertex -2.571942814969939 0.519935777709521 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.348187859547959 4.363443371601797 21.5 + vertex -3.889087296526007 3.889087296526016 21.5 + vertex -3.280205995969707 3.700411926330119 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.207597520252746 2.418532568299296 21.5 + vertex -2.567062035605035 1.791390380062655 21.5 + vertex -1.843365012587536 1.792316515686392 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.078026285860484e-14 5.5 21.5 + vertex -0.7178940572102771 5.452946737555958 21.5 + vertex -0.2903224774583585 4.866202495597054 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.363443371601792 3.348187859547965 21.5 + vertex -4.763139720814412 2.750000000000003 21.5 + vertex -4.030340816201242 2.762411925844111 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.763139720814415 2.749999999999996 21.5 + vertex 4.363443371601798 3.348187859547958 21.5 + vertex 4.065334361405515 2.682654285971688 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.889087296526017 3.889087296526005 21.5 + vertex 3.348187859547973 4.363443371601787 21.5 + vertex 3.252828056633699 3.704409334124365 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.119121313197568 1.793943689838691 21.5 + vertex -1.483697480222967 2.420610379027217 21.5 + vertex -1.843365012587536 1.792316515686392 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.207597520252746 2.418532568299296 21.5 + vertex -2.930332249235313 2.416335828844155 21.5 + vertex -2.567062035605035 1.791390380062655 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 1.784362640076655 1.807659438405761 21.5 + vertex 2.14397238962456 2.436439266417713 21.5 + vertex 1.417659435571495 2.431414775981395 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.14397238962456 2.436439266417713 21.5 + vertex 1.77476966170464 3.058211500149 21.5 + vertex 1.417659435571495 2.431414775981395 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.83703550967926 -0.7322192006469028 21.5 + vertex -2.200789878856349 -1.365822432420879 21.5 + vertex -1.468777573016966 -1.3652345429877 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.933846202610533 -0.1103726985240749 21.5 + vertex -2.20451534066643 -0.1030192144988487 21.5 + vertex -2.571942814969939 0.519935777709521 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.77476966170464 3.058211500149 21.5 + vertex 1.05144846570144 3.051775440361086 21.5 + vertex 1.417659435571495 2.431414775981395 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.114097168792748 0.5342953322494912 21.5 + vertex -0.7414788728394006 -0.09717752935253277 21.5 + vertex -0.3830235741399194 0.5366644331615591 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.753566332498671 1.166438832469177 21.5 + vertex -1.114097168792748 0.5342953322494912 21.5 + vertex -0.3830235741399194 0.5366644331615591 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.515068376510828 0.5590417123785598 21.5 + vertex 2.149559208878152 1.182603946683908 21.5 + vertex 1.794649548750019 0.5538628216185861 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.081337428812076 2.104758878007997 21.5 + vertex -5.312592044589875 1.423504748063864 21.5 + vertex -4.592403655874935 1.584446114812588 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.312592044589876 1.423504748063862 21.5 + vertex 5.081337428812079 2.104758878007991 21.5 + vertex 4.57664415675873 1.616911069653527 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -2.56767899517021 -0.7355385695505063 21.5 + vertex -2.200789878856349 -1.365822432420879 21.5 + vertex -1.83703550967926 -0.7322192006469028 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.424381115798011 1.178073588603486 21.5 + vertex 0.6985093609911199 1.174015816774994 21.5 + vertex 1.069260257467189 0.5464686057282293 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.02742447045176344 1.170305558359778 21.5 + vertex -0.753566332498671 1.166438832469177 21.5 + vertex -0.3830235741399194 0.5366644331615591 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.149559208878152 1.182603946683908 21.5 + vertex 1.424381115798011 1.178073588603486 21.5 + vertex 1.794649548750019 0.5538628216185861 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -4.080333626493353 0.5487491035079626 21.5 + vertex -3.298593717973138 0.5094064443387398 21.5 + vertex -3.629708522812641 1.147538656405129 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.6985093609911199 1.174015816774994 21.5 + vertex -0.02742447045176344 1.170305558359778 21.5 + vertex 0.3458814719110396 0.5400512253409957 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 2.165378219990663 -0.07175024280788911 21.5 + vertex 2.515068376510828 0.5590417123785598 21.5 + vertex 1.794649548750019 0.5538628216185861 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.424381115798011 1.178073588603486 21.5 + vertex 1.069260257467189 0.5464686057282293 21.5 + vertex 1.794649548750019 0.5538628216185861 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.189271177275878 4.439402784072247 21.5 + vertex 2.143688462981651 3.703606637301787 21.5 + vertex 2.75000000000001 4.11566584733009 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.069260257467189 0.5464686057282293 21.5 + vertex 0.6985093609911199 1.174015816774994 21.5 + vertex 0.3458814719110396 0.5400512253409957 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.02742447045176344 1.170305558359778 21.5 + vertex -0.3830235741399194 0.5366644331615591 21.5 + vertex 0.3458814719110396 0.5400512253409957 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.881232144690902 -0.06113423873704216 21.5 + vertex 2.515068376510828 0.5590417123785598 21.5 + vertex 2.165378219990663 -0.07175024280788911 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -3.629708522812641 1.147538656405129 21.5 + vertex -2.932138305748578 1.146268488836126 21.5 + vertex -3.262340651152442 1.756338215678496 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -3.973779619446876 -0.7328053431432462 21.5 + vertex -3.652670293182509 -0.1170884969296826 21.5 + vertex -4.349689637699501 -0.1295132896712743 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.595497694612638 -0.05886226124304361 21.5 + vertex 3.938849291627158 -0.7035546146220737 21.5 + vertex 4.294397132808166 -0.1476737307457339 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.165378219990663 -0.07175024280788911 21.5 + vertex 1.815393450381904 -0.7111437594340928 21.5 + vertex 2.537367542003185 -0.7051667814373728 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.847955632052608 3.043560626390439 21.5 + vertex -1.455025852178601 3.648821126939371 21.5 + vertex -2.174171594369703 3.693264160956475 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.629708522812641 1.147538656405129 21.5 + vertex -3.298593717973138 0.5094064443387398 21.5 + vertex -2.932138305748578 1.146268488836126 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.766666666666669 -2 21.5 + vertex -4.033333333333339 -2 21.5 + vertex -4.37221496357463 -1.373106480595391 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.033333333333331 -2 21.5 + vertex 4.766666666666666 -2 21.5 + vertex 4.381165749274791 -1.354092706347899 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.794649548750019 0.5538628216185861 21.5 + vertex 1.069260257467189 0.5464686057282293 21.5 + vertex 1.442714337457756 -0.08312031228002326 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.069260257467189 0.5464686057282293 21.5 + vertex 0.7182956924189055 -0.08943793981447623 21.5 + vertex 1.442714337457756 -0.08312031228002326 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.5 -0.6666666666666667 21.5 + vertex -5.5 -1.333333333333336 21.5 + vertex -4.974892396764925 -0.98267491174995 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 5.5 -1.333333333333336 21.5 + vertex 5.5 -0.6666666666666667 21.5 + vertex 4.963973008133202 -0.98706788308108 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.881232144690902 -0.06113423873704216 21.5 + vertex 2.165378219990663 -0.07175024280788911 21.5 + vertex 2.537367542003185 -0.7051667814373728 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.5 0 21.5 + vertex 4.851795212957035 0.3136504576734964 21.5 + vertex 4.926075293601113 -0.3392665821314127 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 3.20803536070862 1.805619974416543 21.5 + vertex 3.562320624145101 1.202481060232584 21.5 + vertex 3.927950274508524 1.880549173906596 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -4.37221496357463 -1.373106480595391 21.5 + vertex -3.973779619446876 -0.7328053431432462 21.5 + vertex -4.534602248022153 -0.646998731336331 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.522298487161135 3.012167413056245 21.5 + vertex -1.847955632052608 3.043560626390439 21.5 + vertex -2.174171594369703 3.693264160956475 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.165378219990663 -0.07175024280788911 21.5 + vertex 1.794649548750019 0.5538628216185861 21.5 + vertex 1.442714337457756 -0.08312031228002326 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.118262403643518 4.222118878480422 21.5 + vertex 1.403555195493685 3.647927471976819 21.5 + vertex 1.72399861236322 4.121595938720846 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.250178876801736 -0.6883211458698835 21.5 + vertex 2.881232144690902 -0.06113423873704216 21.5 + vertex 2.537367542003185 -0.7051667814373728 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 5.5 -0.6666666666666667 21.5 + vertex 5.5 0 21.5 + vertex 4.926075293601113 -0.3392665821314127 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.851795212957035 0.3136504576734964 21.5 + vertex 4.294397132808166 -0.1476737307457339 21.5 + vertex 4.926075293601113 -0.3392665821314127 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 0.6746429829520909 3.667626241535941 21.5 + vertex 1.403555195493685 3.647927471976819 21.5 + vertex 1.118262403643518 4.222118878480422 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -4.974892396764925 -0.98267491174995 21.5 + vertex -4.37221496357463 -1.373106480595391 21.5 + vertex -4.534602248022153 -0.646998731336331 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -4.033333333333339 -2 21.5 + vertex -3.656461147653646 -1.372636668532488 21.5 + vertex -4.37221496357463 -1.373106480595391 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.637341001405353 -1.349083275249484 21.5 + vertex 4.033333333333331 -2 21.5 + vertex 4.381165749274791 -1.354092706347899 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.877559064420448 0.3196921111679707 21.5 + vertex -5.5 0 21.5 + vertex -4.955614474544942 -0.3423606707700895 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -0.03877143035215522 3.662593140451773 21.5 + vertex 0.3203755464932684 4.335103306945019 21.5 + vertex -0.433737444740777 4.235884502737899 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 4.963973008133202 -0.98706788308108 21.5 + vertex 5.5 -0.6666666666666667 21.5 + vertex 4.926075293601113 -0.3392665821314127 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.141756343751128 4.219078366244001 21.5 + vertex -0.765502698122782 3.661708532968327 21.5 + vertex -0.433737444740777 4.235884502737899 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -5.5 -0.6666666666666667 21.5 + vertex -4.974892396764925 -0.98267491174995 21.5 + vertex -4.955614474544942 -0.3423606707700895 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.573557187374463 4.685038720206226 21.5 + vertex 1.118262403643518 4.222118878480422 21.5 + vertex 1.72399861236322 4.121595938720846 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.5 0 21.5 + vertex -5.5 -0.6666666666666667 21.5 + vertex -4.955614474544942 -0.3423606707700895 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.381165749274791 -1.354092706347899 21.5 + vertex 4.963973008133202 -0.98706788308108 21.5 + vertex 4.500892095088886 -0.7063311033856396 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.20803536070862 1.805619974416543 21.5 + vertex 3.927950274508524 1.880549173906596 21.5 + vertex 3.491373889216018 2.418229010193856 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -2.174171594369703 3.693264160956475 21.5 + vertex -1.455025852178601 3.648821126939371 21.5 + vertex -1.69119665659864 4.14888377723177 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.349689637699501 -0.1295132896712743 21.5 + vertex -4.877559064420448 0.3196921111679707 21.5 + vertex -4.955614474544942 -0.3423606707700895 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.174171594369703 3.693264160956475 21.5 + vertex -2.177802216173823 4.4185051541547 21.5 + vertex -2.742913382828742 4.089635814614057 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.177802216173823 4.4185051541547 21.5 + vertex -2.174171594369703 3.693264160956475 21.5 + vertex -1.69119665659864 4.14888377723177 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.3203755464932684 4.335103306945019 21.5 + vertex 0.6746429829520909 3.667626241535941 21.5 + vertex 1.118262403643518 4.222118878480422 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.939232720196334 1.707137030555781 21.5 + vertex -3.262340651152442 1.756338215678496 21.5 + vertex -3.546351029634339 2.331835435566118 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.5 -2 21.5 + vertex -4.766666666666669 -2 21.5 + vertex -5.013804655601255 -1.531507906464627 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.766666666666666 -2 21.5 + vertex 5.5 -2 21.5 + vertex 5.004481582892931 -1.524929741182224 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -3.262340651152442 1.756338215678496 21.5 + vertex -2.930332249235313 2.416335828844155 21.5 + vertex -3.546351029634339 2.331835435566118 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 3.562320624145101 1.202481060232584 21.5 + vertex 3.95607084917357 0.5694139263736586 21.5 + vertex 4.137269388399436 1.274873980711341 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -4.080333626493353 0.5487491035079626 21.5 + vertex -3.629708522812641 1.147538656405129 21.5 + vertex -4.186596015406908 1.187785397092626 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.930332249235313 2.416335828844155 21.5 + vertex -2.522298487161135 3.012167413056245 21.5 + vertex -3.225877023298942 3.002037394799064 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.930332249235313 2.416335828844155 21.5 + vertex -3.225877023298942 3.002037394799064 21.5 + vertex -3.546351029634339 2.331835435566118 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -3.629708522812641 1.147538656405129 21.5 + vertex -3.262340651152442 1.756338215678496 21.5 + vertex -3.939232720196334 1.707137030555781 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -5.5 -1.333333333333336 21.5 + vertex -5.5 -2 21.5 + vertex -5.013804655601255 -1.531507906464627 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 5.5 -2 21.5 + vertex 5.5 -1.333333333333336 21.5 + vertex 5.004481582892931 -1.524929741182224 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.749999999999996 4.763139720814415 21.5 + vertex -3.348187859547959 4.363443371601797 21.5 + vertex -2.742913382828742 4.089635814614057 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.75000000000001 4.763139720814406 21.5 + vertex 2.104758878008006 5.081337428812073 21.5 + vertex 2.189271177275878 4.439402784072247 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.348187859547973 4.363443371601787 21.5 + vertex 2.75000000000001 4.763139720814406 21.5 + vertex 2.75000000000001 4.11566584733009 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.363443371601798 3.348187859547958 21.5 + vertex 3.889087296526017 3.889087296526005 21.5 + vertex 3.700778955016418 3.171162424982228 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.763139720814412 2.750000000000003 21.5 + vertex -5.081337428812076 2.104758878007997 21.5 + vertex -4.381272568689584 2.198196544719015 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.177802216173823 4.4185051541547 21.5 + vertex -2.749999999999996 4.763139720814415 21.5 + vertex -2.742913382828742 4.089635814614057 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.104758878008006 5.081337428812073 21.5 + vertex 1.573557187374463 4.685038720206226 21.5 + vertex 2.189271177275878 4.439402784072247 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.348187859547959 4.363443371601797 21.5 + vertex -3.280205995969707 3.700411926330119 21.5 + vertex -2.742913382828742 4.089635814614057 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 3.252828056633699 3.704409334124365 21.5 + vertex 3.348187859547973 4.363443371601787 21.5 + vertex 2.75000000000001 4.11566584733009 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 4.065334361405515 2.682654285971688 21.5 + vertex 4.363443371601798 3.348187859547958 21.5 + vertex 3.700778955016418 3.171162424982228 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.030340816201242 2.762411925844111 21.5 + vertex -4.763139720814412 2.750000000000003 21.5 + vertex -4.381272568689584 2.198196544719015 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.889087296526017 3.889087296526005 21.5 + vertex 3.252828056633699 3.704409334124365 21.5 + vertex 3.700778955016418 3.171162424982228 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -5.081337428812076 2.104758878007997 21.5 + vertex -4.592403655874935 1.584446114812588 21.5 + vertex -4.381272568689584 2.198196544719015 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.765502698122782 3.661708532968327 21.5 + vertex -0.03877143035215522 3.662593140451773 21.5 + vertex -0.433737444740777 4.235884502737899 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.078026285860484e-14 5.5 21.5 + vertex -0.2903224774583585 4.866202495597054 21.5 + vertex 0.3344959061109473 4.979339280507027 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.763139720814415 2.749999999999996 21.5 + vertex 4.065334361405515 2.682654285971688 21.5 + vertex 4.482881188459852 2.20697468150796 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 4.57664415675873 1.616911069653527 21.5 + vertex 5.081337428812079 2.104758878007991 21.5 + vertex 4.482881188459852 2.20697468150796 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.7178940572102935 5.452946737555956 21.5 + vertex 1.078026285860484e-14 5.5 21.5 + vertex 0.3344959061109473 4.979339280507027 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.104758878007986 5.081337428812081 21.5 + vertex -2.177802216173823 4.4185051541547 21.5 + vertex -1.589004205794794 4.698511038237923 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.081337428812079 2.104758878007991 21.5 + vertex 4.763139720814415 2.749999999999996 21.5 + vertex 4.482881188459852 2.20697468150796 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -4.69130155165728 0.9510560801816688 21.5 + vertex -4.080333626493353 0.5487491035079626 21.5 + vertex -4.186596015406908 1.187785397092626 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.95607084917357 0.5694139263736586 21.5 + vertex 4.585155055551279 0.9206986467201828 21.5 + vertex 4.137269388399436 1.274873980711341 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.573557187374463 4.685038720206226 21.5 + vertex 1.423504748063873 5.312592044589874 21.5 + vertex 0.9520749167050213 4.87123425426997 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.2903224774583585 4.866202495597054 21.5 + vertex -0.7178940572102771 5.452946737555958 21.5 + vertex -0.9527252825573536 4.84504087071608 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 3.927950274508524 1.880549173906596 21.5 + vertex 4.57664415675873 1.616911069653527 21.5 + vertex 4.482881188459852 2.20697468150796 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex 2.469746722367153 3.044661712432676 21.5 + vertex 2.867303180212432 2.439562575974977 21.5 + vertex 3.076600308961155 3.054443667699625 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.076600308961155 3.054443667699625 21.5 + vertex 2.867303180212432 2.439562575974977 21.5 + vertex 3.491373889216018 2.418229010193856 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.280205995969707 3.700411926330119 21.5 + vertex -3.889087296526007 3.889087296526016 21.5 + vertex -3.757790900719538 3.340427280609455 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.363443371601792 3.348187859547965 21.5 + vertex -4.030340816201242 2.762411925844111 21.5 + vertex -3.757790900719538 3.340427280609455 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.867303180212432 2.439562575974977 21.5 + vertex 3.20803536070862 1.805619974416543 21.5 + vertex 3.491373889216018 2.418229010193856 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -4.766666666666669 -2 21.5 + vertex -4.37221496357463 -1.373106480595391 21.5 + vertex -5.013804655601255 -1.531507906464627 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.381165749274791 -1.354092706347899 21.5 + vertex 4.766666666666666 -2 21.5 + vertex 5.004481582892931 -1.524929741182224 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.423504748063857 5.312592044589877 21.5 + vertex -2.104758878007986 5.081337428812081 21.5 + vertex -1.589004205794794 4.698511038237923 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.37221496357463 -1.373106480595391 21.5 + vertex -4.974892396764925 -0.98267491174995 21.5 + vertex -5.013804655601255 -1.531507906464627 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.963973008133202 -0.98706788308108 21.5 + vertex 4.381165749274791 -1.354092706347899 21.5 + vertex 5.004481582892931 -1.524929741182224 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.592403655874935 1.584446114812588 21.5 + vertex -3.939232720196334 1.707137030555781 21.5 + vertex -4.381272568689584 2.198196544719015 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.280205995969707 3.700411926330119 21.5 + vertex -3.225877023298942 3.002037394799064 21.5 + vertex -2.738890663339244 3.523067129332701 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.423504748063873 5.312592044589874 21.5 + vertex 0.7178940572102935 5.452946737555956 21.5 + vertex 0.9520749167050213 4.87123425426997 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.225877023298942 3.002037394799064 21.5 + vertex -2.522298487161135 3.012167413056245 21.5 + vertex -2.738890663339244 3.523067129332701 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -0.7178940572102771 5.452946737555958 21.5 + vertex -1.423504748063857 5.312592044589877 21.5 + vertex -0.9527252825573536 4.84504087071608 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 3.076600308961155 3.054443667699625 21.5 + vertex 3.252828056633699 3.704409334124365 21.5 + vertex 2.6959906786969 3.559418129430805 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.889087296526007 3.889087296526016 21.5 + vertex -4.363443371601792 3.348187859547965 21.5 + vertex -3.757790900719538 3.340427280609455 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 2.143688462981651 3.703606637301787 21.5 + vertex 2.189271177275878 4.439402784072247 21.5 + vertex 1.72399861236322 4.121595938720846 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.294397132808166 -0.1476737307457339 21.5 + vertex 3.938849291627158 -0.7035546146220737 21.5 + vertex 4.500892095088886 -0.7063311033856396 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.926075293601113 -0.3392665821314127 21.5 + vertex 4.294397132808166 -0.1476737307457339 21.5 + vertex 4.500892095088886 -0.7063311033856396 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.469746722367153 3.044661712432676 21.5 + vertex 3.076600308961155 3.054443667699625 21.5 + vertex 2.6959906786969 3.559418129430805 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.75000000000001 4.763139720814406 21.5 + vertex 2.189271177275878 4.439402784072247 21.5 + vertex 2.75000000000001 4.11566584733009 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.75000000000001 4.11566584733009 21.5 + vertex 2.143688462981651 3.703606637301787 21.5 + vertex 2.6959906786969 3.559418129430805 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex 1.118262403643518 4.222118878480422 21.5 + vertex 1.573557187374463 4.685038720206226 21.5 + vertex 0.9520749167050213 4.87123425426997 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.700778955016418 3.171162424982228 21.5 + vertex 3.252828056633699 3.704409334124365 21.5 + vertex 3.076600308961155 3.054443667699625 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.225877023298942 3.002037394799064 21.5 + vertex -3.280205995969707 3.700411926330119 21.5 + vertex -3.757790900719538 3.340427280609455 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 0.7178940572102935 5.452946737555956 21.5 + vertex 0.3344959061109473 4.979339280507027 21.5 + vertex 0.9520749167050213 4.87123425426997 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.423504748063857 5.312592044589877 21.5 + vertex -1.589004205794794 4.698511038237923 21.5 + vertex -0.9527252825573536 4.84504087071608 21.5 + endloop +endfacet +facet normal -0 0 1 + outer loop + vertex -1.589004205794794 4.698511038237923 21.5 + vertex -1.141756343751128 4.219078366244001 21.5 + vertex -0.9527252825573536 4.84504087071608 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 1.403555195493685 3.647927471976819 21.5 + vertex 2.143688462981651 3.703606637301787 21.5 + vertex 1.72399861236322 4.121595938720846 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.143688462981651 3.703606637301787 21.5 + vertex 2.469746722367153 3.044661712432676 21.5 + vertex 2.6959906786969 3.559418129430805 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.973779619446876 -0.7328053431432462 21.5 + vertex -4.349689637699501 -0.1295132896712743 21.5 + vertex -4.534602248022153 -0.646998731336331 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.927950274508524 1.880549173906596 21.5 + vertex 3.562320624145101 1.202481060232584 21.5 + vertex 4.137269388399436 1.274873980711341 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -1.455025852178601 3.648821126939371 21.5 + vertex -1.141756343751128 4.219078366244001 21.5 + vertex -1.69119665659864 4.14888377723177 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.57664415675873 1.616911069653527 21.5 + vertex 3.927950274508524 1.880549173906596 21.5 + vertex 4.137269388399436 1.274873980711341 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.974892396764925 -0.98267491174995 21.5 + vertex -5.5 -1.333333333333336 21.5 + vertex -5.013804655601255 -1.531507906464627 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 5.5 -1.333333333333336 21.5 + vertex 4.963973008133202 -0.98706788308108 21.5 + vertex 5.004481582892931 -1.524929741182224 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.174171594369703 3.693264160956475 21.5 + vertex -2.742913382828742 4.089635814614057 21.5 + vertex -2.738890663339244 3.523067129332701 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.963973008133202 -0.98706788308108 21.5 + vertex 4.926075293601113 -0.3392665821314127 21.5 + vertex 4.500892095088886 -0.7063311033856396 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.955614474544942 -0.3423606707700895 21.5 + vertex -4.974892396764925 -0.98267491174995 21.5 + vertex -4.534602248022153 -0.646998731336331 21.5 + endloop +endfacet +facet normal 0 -0 1 + outer loop + vertex -2.522298487161135 3.012167413056245 21.5 + vertex -2.174171594369703 3.693264160956475 21.5 + vertex -2.738890663339244 3.523067129332701 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 4.585155055551279 0.9206986467201828 21.5 + vertex 4.57664415675873 1.616911069653527 21.5 + vertex 4.137269388399436 1.274873980711341 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.349689637699501 -0.1295132896712743 21.5 + vertex -4.955614474544942 -0.3423606707700895 21.5 + vertex -4.534602248022153 -0.646998731336331 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -4.592403655874935 1.584446114812588 21.5 + vertex -4.69130155165728 0.9510560801816688 21.5 + vertex -4.186596015406908 1.187785397092626 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -2.742913382828742 4.089635814614057 21.5 + vertex -3.280205995969707 3.700411926330119 21.5 + vertex -2.738890663339244 3.523067129332701 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 2.189271177275878 4.439402784072247 21.5 + vertex 1.573557187374463 4.685038720206226 21.5 + vertex 1.72399861236322 4.121595938720846 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex 3.252828056633699 3.704409334124365 21.5 + vertex 2.75000000000001 4.11566584733009 21.5 + vertex 2.6959906786969 3.559418129430805 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.939232720196334 1.707137030555781 21.5 + vertex -4.592403655874935 1.584446114812588 21.5 + vertex -4.186596015406908 1.187785397092626 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.589004205794794 4.698511038237923 21.5 + vertex -2.177802216173823 4.4185051541547 21.5 + vertex -1.69119665659864 4.14888377723177 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -3.629708522812641 1.147538656405129 21.5 + vertex -3.939232720196334 1.707137030555781 21.5 + vertex -4.186596015406908 1.187785397092626 21.5 + endloop +endfacet +facet normal 0 0 1 + outer loop + vertex -1.141756343751128 4.219078366244001 21.5 + vertex -1.589004205794794 4.698511038237923 21.5 + vertex -1.69119665659864 4.14888377723177 21.5 + endloop +endfacet +endsolid Created by Gmsh diff --git a/examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm.stp b/examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm.stp new file mode 100644 index 00000000..a378e7ad --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/data/mesh/CHAMBER20mm.stp @@ -0,0 +1,287 @@ +ISO-10303-21; +HEADER; +/* Generated by software containing ST-Developer + * from STEP Tools, Inc. (www.steptools.com) + */ + +FILE_DESCRIPTION( +/* description */ (''), +/* implementation_level */ '2;1'); + +FILE_NAME( +/* name */ 'CHAMBER20mm.stp', +/* time_stamp */ '2023-05-04T18:22:43+09:00', +/* author */ ('pablo'), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v19.2', +/* originating_system */ 'Autodesk Inventor 2023', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#13),#194); +#11=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#201,#12); +#12=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#14),#193); +#13=STYLED_ITEM('',(#210),#14); +#14=MANIFOLD_SOLID_BREP('Solid1',#105); +#15=CIRCLE('',#132,5.5); +#16=CIRCLE('',#133,5.5); +#17=CYLINDRICAL_SURFACE('',#131,5.5); +#18=FACE_OUTER_BOUND('',#24,.T.); +#19=FACE_OUTER_BOUND('',#25,.T.); +#20=FACE_OUTER_BOUND('',#26,.T.); +#21=FACE_OUTER_BOUND('',#27,.T.); +#22=FACE_OUTER_BOUND('',#28,.T.); +#23=FACE_OUTER_BOUND('',#29,.T.); +#24=EDGE_LOOP('',(#70,#71,#72,#73)); +#25=EDGE_LOOP('',(#74,#75,#76,#77)); +#26=EDGE_LOOP('',(#78,#79,#80,#81)); +#27=EDGE_LOOP('',(#82,#83,#84,#85)); +#28=EDGE_LOOP('',(#86,#87,#88,#89)); +#29=EDGE_LOOP('',(#90,#91,#92,#93)); +#30=LINE('',#168,#40); +#31=LINE('',#170,#41); +#32=LINE('',#172,#42); +#33=LINE('',#173,#43); +#34=LINE('',#177,#44); +#35=LINE('',#179,#45); +#36=LINE('',#181,#46); +#37=LINE('',#182,#47); +#38=LINE('',#184,#48); +#39=LINE('',#185,#49); +#40=VECTOR('',#140,10.); +#41=VECTOR('',#141,10.); +#42=VECTOR('',#142,10.); +#43=VECTOR('',#143,10.); +#44=VECTOR('',#146,10.); +#45=VECTOR('',#147,10.); +#46=VECTOR('',#148,10.); +#47=VECTOR('',#149,10.); +#48=VECTOR('',#152,10.); +#49=VECTOR('',#153,10.); +#50=VERTEX_POINT('',#166); +#51=VERTEX_POINT('',#167); +#52=VERTEX_POINT('',#169); +#53=VERTEX_POINT('',#171); +#54=VERTEX_POINT('',#175); +#55=VERTEX_POINT('',#176); +#56=VERTEX_POINT('',#178); +#57=VERTEX_POINT('',#180); +#58=EDGE_CURVE('',#50,#51,#30,.T.); +#59=EDGE_CURVE('',#51,#52,#31,.T.); +#60=EDGE_CURVE('',#53,#52,#32,.T.); +#61=EDGE_CURVE('',#50,#53,#33,.T.); +#62=EDGE_CURVE('',#54,#55,#34,.T.); +#63=EDGE_CURVE('',#54,#56,#35,.T.); +#64=EDGE_CURVE('',#57,#56,#36,.T.); +#65=EDGE_CURVE('',#55,#57,#37,.T.); +#66=EDGE_CURVE('',#52,#57,#38,.T.); +#67=EDGE_CURVE('',#56,#53,#39,.T.); +#68=EDGE_CURVE('',#54,#50,#15,.T.); +#69=EDGE_CURVE('',#51,#55,#16,.T.); +#70=ORIENTED_EDGE('',*,*,#58,.T.); +#71=ORIENTED_EDGE('',*,*,#59,.T.); +#72=ORIENTED_EDGE('',*,*,#60,.F.); +#73=ORIENTED_EDGE('',*,*,#61,.F.); +#74=ORIENTED_EDGE('',*,*,#62,.F.); +#75=ORIENTED_EDGE('',*,*,#63,.T.); +#76=ORIENTED_EDGE('',*,*,#64,.F.); +#77=ORIENTED_EDGE('',*,*,#65,.F.); +#78=ORIENTED_EDGE('',*,*,#66,.T.); +#79=ORIENTED_EDGE('',*,*,#64,.T.); +#80=ORIENTED_EDGE('',*,*,#67,.T.); +#81=ORIENTED_EDGE('',*,*,#60,.T.); +#82=ORIENTED_EDGE('',*,*,#68,.F.); +#83=ORIENTED_EDGE('',*,*,#62,.T.); +#84=ORIENTED_EDGE('',*,*,#69,.F.); +#85=ORIENTED_EDGE('',*,*,#58,.F.); +#86=ORIENTED_EDGE('',*,*,#68,.T.); +#87=ORIENTED_EDGE('',*,*,#61,.T.); +#88=ORIENTED_EDGE('',*,*,#67,.F.); +#89=ORIENTED_EDGE('',*,*,#63,.F.); +#90=ORIENTED_EDGE('',*,*,#69,.T.); +#91=ORIENTED_EDGE('',*,*,#65,.T.); +#92=ORIENTED_EDGE('',*,*,#66,.F.); +#93=ORIENTED_EDGE('',*,*,#59,.F.); +#94=PLANE('',#128); +#95=PLANE('',#129); +#96=PLANE('',#130); +#97=PLANE('',#134); +#98=PLANE('',#135); +#99=ADVANCED_FACE('',(#18),#94,.T.); +#100=ADVANCED_FACE('',(#19),#95,.T.); +#101=ADVANCED_FACE('',(#20),#96,.T.); +#102=ADVANCED_FACE('',(#21),#17,.T.); +#103=ADVANCED_FACE('',(#22),#97,.T.); +#104=ADVANCED_FACE('',(#23),#98,.F.); +#105=CLOSED_SHELL('',(#99,#100,#101,#102,#103,#104)); +#106=DERIVED_UNIT_ELEMENT(#109,1.); +#107=DERIVED_UNIT_ELEMENT(#196,-3.); +#108=DIMENSIONAL_EXPONENTS(0.,1.,0.,0.,0.,0.,0.); +#109=( +CONVERSION_BASED_UNIT('gram',#111) +MASS_UNIT() +NAMED_UNIT(#108) +); +#110=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT(.KILO.,.GRAM.) +); +#111=MASS_MEASURE_WITH_UNIT(MASS_MEASURE(0.001),#110); +#112=DERIVED_UNIT((#106,#107)); +#113=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(1.),#112); +#114=PROPERTY_DEFINITION_REPRESENTATION(#119,#116); +#115=PROPERTY_DEFINITION_REPRESENTATION(#120,#117); +#116=REPRESENTATION('material name',(#118),#193); +#117=REPRESENTATION('density',(#113),#193); +#118=DESCRIPTIVE_REPRESENTATION_ITEM('Generic','Generic'); +#119=PROPERTY_DEFINITION('material property','material name',#203); +#120=PROPERTY_DEFINITION('material property','density of part',#203); +#121=DATE_TIME_ROLE('creation_date'); +#122=APPLIED_DATE_AND_TIME_ASSIGNMENT(#123,#121,(#203)); +#123=DATE_AND_TIME(#124,#125); +#124=CALENDAR_DATE(2022,21,4); +#125=LOCAL_TIME(0,0,0.,#126); +#126=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.); +#127=AXIS2_PLACEMENT_3D('',#164,#136,#137); +#128=AXIS2_PLACEMENT_3D('',#165,#138,#139); +#129=AXIS2_PLACEMENT_3D('',#174,#144,#145); +#130=AXIS2_PLACEMENT_3D('',#183,#150,#151); +#131=AXIS2_PLACEMENT_3D('',#186,#154,#155); +#132=AXIS2_PLACEMENT_3D('',#187,#156,#157); +#133=AXIS2_PLACEMENT_3D('',#188,#158,#159); +#134=AXIS2_PLACEMENT_3D('',#189,#160,#161); +#135=AXIS2_PLACEMENT_3D('',#190,#162,#163); +#136=DIRECTION('axis',(0.,0.,1.)); +#137=DIRECTION('refdir',(1.,0.,0.)); +#138=DIRECTION('center_axis',(1.,0.,0.)); +#139=DIRECTION('ref_axis',(0.,0.,1.)); +#140=DIRECTION('',(0.,0.,1.)); +#141=DIRECTION('',(0.,-1.,0.)); +#142=DIRECTION('',(0.,0.,1.)); +#143=DIRECTION('',(0.,-1.,0.)); +#144=DIRECTION('center_axis',(-1.,0.,0.)); +#145=DIRECTION('ref_axis',(0.,0.,-1.)); +#146=DIRECTION('',(0.,0.,1.)); +#147=DIRECTION('',(0.,-1.,0.)); +#148=DIRECTION('',(0.,0.,-1.)); +#149=DIRECTION('',(0.,-1.,0.)); +#150=DIRECTION('center_axis',(0.,-1.,0.)); +#151=DIRECTION('ref_axis',(0.,0.,-1.)); +#152=DIRECTION('',(-1.,0.,0.)); +#153=DIRECTION('',(1.,0.,0.)); +#154=DIRECTION('center_axis',(0.,0.,1.)); +#155=DIRECTION('ref_axis',(-1.,0.,0.)); +#156=DIRECTION('center_axis',(0.,0.,-1.)); +#157=DIRECTION('ref_axis',(-1.,0.,0.)); +#158=DIRECTION('center_axis',(0.,0.,1.)); +#159=DIRECTION('ref_axis',(-1.,0.,0.)); +#160=DIRECTION('center_axis',(0.,0.,-1.)); +#161=DIRECTION('ref_axis',(-1.,0.,0.)); +#162=DIRECTION('center_axis',(0.,0.,-1.)); +#163=DIRECTION('ref_axis',(-1.,0.,0.)); +#164=CARTESIAN_POINT('',(0.,0.,0.)); +#165=CARTESIAN_POINT('Origin',(5.5,0.,1.5)); +#166=CARTESIAN_POINT('',(5.5,0.,1.5)); +#167=CARTESIAN_POINT('',(5.5,0.,21.5)); +#168=CARTESIAN_POINT('',(5.5,0.,1.5)); +#169=CARTESIAN_POINT('',(5.5,-2.,21.5)); +#170=CARTESIAN_POINT('',(5.5,0.,21.5)); +#171=CARTESIAN_POINT('',(5.5,-2.,1.5)); +#172=CARTESIAN_POINT('',(5.5,-2.,1.5)); +#173=CARTESIAN_POINT('',(5.5,0.,1.5)); +#174=CARTESIAN_POINT('Origin',(-5.5,0.,21.5)); +#175=CARTESIAN_POINT('',(-5.5,0.,1.5)); +#176=CARTESIAN_POINT('',(-5.5,0.,21.5)); +#177=CARTESIAN_POINT('',(-5.5,0.,1.5)); +#178=CARTESIAN_POINT('',(-5.5,-2.,1.5)); +#179=CARTESIAN_POINT('',(-5.5,0.,1.5)); +#180=CARTESIAN_POINT('',(-5.5,-2.,21.5)); +#181=CARTESIAN_POINT('',(-5.5,-2.,21.5)); +#182=CARTESIAN_POINT('',(-5.5,0.,21.5)); +#183=CARTESIAN_POINT('Origin',(0.,-2.,11.5)); +#184=CARTESIAN_POINT('',(5.5,-2.,21.5)); +#185=CARTESIAN_POINT('',(-5.5,-2.,1.5)); +#186=CARTESIAN_POINT('Origin',(0.,0.,1.5)); +#187=CARTESIAN_POINT('Origin',(0.,0.,1.5)); +#188=CARTESIAN_POINT('Origin',(0.,0.,21.5)); +#189=CARTESIAN_POINT('Origin',(0.,2.75,1.5)); +#190=CARTESIAN_POINT('Origin',(0.,2.75,21.5)); +#191=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#195, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#192=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#195, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#193=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#191)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#195,#197,#198)) +REPRESENTATION_CONTEXT('','3D') +); +#194=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#192)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#195,#197,#198)) +REPRESENTATION_CONTEXT('','3D') +); +#195=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#196=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.CENTI.,.METRE.) +); +#197=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#198=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#199=SHAPE_DEFINITION_REPRESENTATION(#200,#201); +#200=PRODUCT_DEFINITION_SHAPE('',$,#203); +#201=SHAPE_REPRESENTATION('',(#127),#193); +#202=PRODUCT_DEFINITION_CONTEXT('part definition',#207,'design'); +#203=PRODUCT_DEFINITION('CHAMBER','CHAMBER',#204,#202); +#204=PRODUCT_DEFINITION_FORMATION('',$,#209); +#205=PRODUCT_RELATED_PRODUCT_CATEGORY('CHAMBER','CHAMBER',(#209)); +#206=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#207); +#207=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#208=PRODUCT_CONTEXT('part definition',#207,'mechanical'); +#209=PRODUCT('CHAMBER','CHAMBER',$,(#208)); +#210=PRESENTATION_STYLE_ASSIGNMENT((#211)); +#211=SURFACE_STYLE_USAGE(.BOTH.,#214); +#212=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#218,(#213)); +#213=SURFACE_STYLE_TRANSPARENT(0.); +#214=SURFACE_SIDE_STYLE('',(#215,#212)); +#215=SURFACE_STYLE_FILL_AREA(#216); +#216=FILL_AREA_STYLE('',(#217)); +#217=FILL_AREA_STYLE_COLOUR('',#218); +#218=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137); +ENDSEC; +END-ISO-10303-21; +//+ +SetFactory("OpenCASCADE"); +//+ +Rotate {{0, 1, 0}, {0, 0, 0}, Pi/2} { + Volume{1}; +} +//+ +Rotate {{1, 0, 0}, {0, 0, 0}, Pi/2} { + Volume{1}; +} diff --git a/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.msh b/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.msh new file mode 100644 index 00000000..d0df36ca --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.msh @@ -0,0 +1,29361 @@ +$MeshFormat +4.1 0 8 +$EndMeshFormat +$Entities +32 52 25 2 +1 5.5 2 -1 0 +2 7.5 1.94289029309402e-15 -1 0 +3 7.5 1.94289029309402e-15 -3 0 +4 5.5 2 -3 0 +5 -7.5 0 -1 0 +6 -5.5 2 -1 0 +7 7.5 -2 -3 0 +8 7.5 1.90758359496969e-15 0 0 +9 7.5 -2 0 0 +10 5.5 -4 -3 0 +11 -5.5 -4 -3 0 +12 -7.5 -2 -3 0 +13 -7.5 0 -3 0 +14 -5.5 2 -3 0 +15 -7.5 0 0 0 +16 5.5 -4 0 0 +17 -5.5 -4 0 0 +18 -7.5 -2 0 0 +19 7.5 -2 23 0 +20 5.5 -4 23 0 +21 -5.5 -4 23 0 +22 -7.5 -2 23 0 +23 -7.5 0 23 0 +24 7.5 1.94289029309402e-15 23 0 +25 -5.5 -2 21.5 0 +26 5.5 -2 21.5 0 +27 5.5 -2 1.5 0 +28 -5.5 -2 1.5 0 +29 5.5 7.12393107467807e-16 21.5 0 +30 5.5 7.12393107467807e-16 1.5 0 +31 -5.5 -7.12393107467807e-16 1.5 0 +32 -5.5 -7.12393107467807e-16 21.5 0 +1 5.4999999 -9.999999828202988e-08 -1.0000001 7.5000001 2.000000099999999 -0.9999999000000001 0 2 1 -2 +2 7.4999999 -9.99999980571097e-08 -3.0000001 7.5000001 1.000000019428903e-07 -0.9999999000000002 0 2 2 -3 +3 5.4999999 -9.999999828202988e-08 -3.0000001 7.5000001 2.000000099999999 -2.9999999 0 2 4 -3 +4 5.4999999 1.9999999 -3.0000001 5.5000001 2.0000001 -0.9999999000000002 0 2 1 -4 +5 -7.5000001 -9.999999983634211e-08 -1.0000001 7.5000001 7.5000001 -0.9999999000000001 0 2 5 -2 +6 -7.5000001 -9.999999994736442e-08 -1.0000001 -5.4999999 2.000000099999999 -0.9999999000000001 0 2 5 -6 +7 -5.5000001 1.9999999 -1.0000001 5.5000001 2.0000001 -0.9999999000000001 0 2 6 -1 +8 7.4999999 -2.0000001 -3.0000001 7.5000001 1.000000019457659e-07 -2.9999999 0 2 3 -7 +9 7.4999999 -9.99999980571097e-08 -1.0000001 7.5000001 1.000000019428903e-07 9.999999994736442e-08 0 2 8 -2 +10 7.4999999 -2.0000001 -1.000000001110223e-07 7.5000001 1.000000020567882e-07 1.000000001110223e-07 0 2 8 -9 +11 7.4999999 -2.0000001 -3.0000001 7.5000001 -1.9999999 1.000000000583867e-07 0 2 9 -7 +12 5.4999999 -4.0000001 -3.0000001 7.5000001 -1.9999999 -2.9999999 0 2 7 -10 +13 -5.5000001 -4.0000001 -3.0000001 5.5000001 -3.9999999 -2.9999999 0 2 10 -11 +14 -7.5000001 -4.0000001 -3.0000001 -5.4999999 -1.9999999 -2.9999999 0 2 11 -12 +15 -7.5000001 -2.0000001 -3.0000001 -7.4999999 9.999999994736442e-08 -2.9999999 0 2 12 -13 +16 -7.5000001 -9.999999994736442e-08 -3.0000001 -5.4999999 2.000000099999999 -2.9999999 0 2 13 -14 +17 -5.5000001 1.9999999 -3.0000001 5.5000001 2.0000001 -2.9999999 0 2 14 -4 +18 -5.5000001 1.9999999 -3.0000001 -5.4999999 2.0000001 -0.9999999000000002 0 2 6 -14 +19 -7.500000100000001 -1.00000001612699e-07 -1.000000016011864e-07 7.500000100000001 7.500000100000001 1.000000016011864e-07 0 2 15 -8 +20 -7.5000001 -1e-07 -1.0000001 -7.4999999 1e-07 9.999999994736442e-08 0 2 15 -5 +21 -7.5000001 -1e-07 -3.0000001 -7.4999999 1e-07 -0.9999999000000002 0 2 5 -13 +22 5.4999999 -4.0000001 -1.000000004440892e-07 7.5000001 -1.999999899999999 1.000000004440892e-07 0 2 9 -16 +23 5.4999999 -4.0000001 -3.0000001 5.5000001 -3.9999999 1.000000000583867e-07 0 2 16 -10 +24 -5.500000100000001 -4.000000100000001 -1.000000008881784e-07 5.500000100000001 -3.999999899999999 1.000000008881784e-07 0 2 16 -17 +25 -5.5000001 -4.0000001 -3.0000001 -5.4999999 -3.9999999 1.000000000583867e-07 0 2 17 -11 +26 -7.5000001 -4.0000001 -1.000000004440892e-07 -5.4999999 -1.999999899999999 1.000000004440892e-07 0 2 17 -18 +27 -7.5000001 -2.0000001 -3.0000001 -7.4999999 -1.9999999 1.000000000583867e-07 0 2 18 -12 +28 -7.5000001 -2.0000001 -1e-07 -7.4999999 9.999999994736442e-08 1e-07 0 2 18 -15 +29 7.4999999 -2.0000001 -9.99999993922529e-08 7.5000001 -1.9999999 23.0000001 0 2 9 -19 +30 5.4999999 -4.0000001 22.9999999 7.5000001 -1.9999999 23.0000001 0 2 20 -19 +31 5.4999999 -4.0000001 -9.99999993922529e-08 5.5000001 -3.9999999 23.0000001 0 2 16 -20 +32 -5.5000001 -4.0000001 22.9999999 5.5000001 -3.9999999 23.0000001 0 2 21 -20 +33 -5.5000001 -4.0000001 -9.99999993922529e-08 -5.4999999 -3.9999999 23.0000001 0 2 17 -21 +34 -7.5000001 -4.0000001 22.9999999 -5.4999999 -1.9999999 23.0000001 0 2 22 -21 +35 -7.5000001 -2.0000001 -9.99999993922529e-08 -7.4999999 -1.9999999 23.0000001 0 2 18 -22 +36 -7.5000001 -2.0000001 22.9999999 -7.4999999 9.999999994736442e-08 23.0000001 0 2 23 -22 +37 -7.5000001 -1e-07 -9.99999993922529e-08 -7.4999999 1e-07 23.0000001 0 2 15 -23 +38 -7.5000001 -1.000000007245205e-07 22.9999999 7.5000001 7.5000001 23.0000001 0 2 24 -23 +39 7.4999999 -9.99999981630298e-08 -9.99999993922529e-08 7.5000001 1.000000018369702e-07 23.0000001 0 2 8 -24 +40 7.4999999 -2.0000001 22.9999999 7.5000001 1.000000017237213e-07 23.0000001 0 2 19 -24 +41 -5.5000001 -2.0000001 21.4999999 5.5000001 -1.999999899999999 21.5000001 0 2 25 -26 +42 5.4999999 -2.0000001 1.499999900000001 5.5000001 -1.9999999 21.5000001 0 2 26 -27 +43 -5.5000001 -2.0000001 1.4999999 5.5000001 -1.999999899999999 1.5000001 0 2 27 -28 +44 -5.5000001 -2.0000001 1.499999900000001 -5.4999999 -1.9999999 21.5000001 0 2 25 -28 +45 5.4999999 -2.0000001 21.4999999 5.5000001 1.000000008355428e-07 21.5000001 0 2 26 -29 +46 5.4999999 -9.999999928760689e-08 1.499999900000001 5.5000001 1.000000007123931e-07 21.5000001 0 2 29 -30 +47 5.4999999 -2.0000001 1.4999999 5.5000001 1.000000008355428e-07 1.5000001 0 2 30 -27 +48 -5.5000001 -1.000000011686097e-07 1.4999999 5.5000001 5.5000001 1.5000001 0 2 31 -30 +49 -5.5000001 -1.000000007123931e-07 1.499999900000001 -5.4999999 9.999999928760689e-08 21.5000001 0 2 32 -31 +50 -5.5000001 -9.999999983634211e-08 21.4999999 5.5000001 5.5000001 21.5000001 0 2 29 -32 +51 -5.5000001 -2.0000001 21.4999999 -5.4999999 9.99999993922529e-08 21.5000001 0 2 32 -25 +52 -5.5000001 -2.0000001 1.4999999 -5.4999999 9.99999993922529e-08 1.5000001 0 2 28 -31 +1 5.4999999 -9.999999828202988e-08 -3.0000001 7.5000001 2.000000099999999 -0.9999999000000002 0 4 1 2 -3 -4 +2 -7.5000001 -9.999999983634211e-08 -1.0000001 7.5000001 7.5000001 -0.9999999000000001 0 4 5 -1 -7 -6 +3 7.4999999 -2.0000001 -3.0000001 7.5000001 1.000000020567882e-07 1.000000000583867e-07 0 5 -8 -2 -9 10 11 +4 -7.5000001 -4.0000001 -3.0000001 7.5000001 2.0000001 -2.9999999 0 8 8 12 13 14 15 16 17 3 +5 -5.5000001 1.9999999 -3.0000001 5.5000001 2.0000001 -0.9999999000000002 0 4 7 4 -17 -18 +6 -7.5000001 -9.999999983634211e-08 -1.0000001 7.5000001 7.5000001 9.999999994736442e-08 0 4 19 9 -5 -20 +7 -7.5000001 -9.999999994736442e-08 -3.0000001 -5.4999999 2.000000099999999 -0.9999999000000002 0 4 6 18 -16 -21 +8 5.4999999 -4.0000001 -3.0000001 7.5000001 -1.9999999 1.000000000583867e-07 0 4 -12 -11 22 23 +9 -5.500000100000001 -4.000000100000001 -3.000000100000001 5.500000100000001 -3.999999899999999 1.000000009465651e-07 0 4 -13 -23 24 25 +10 -7.5000001 -4.0000001 -3.0000001 -5.4999999 -1.9999999 1.000000000583867e-07 0 4 -14 -25 26 27 +11 -7.5000001 -2.0000001 -3.0000001 -7.4999999 9.999999994736442e-08 1.000000000583867e-07 0 5 21 -15 -27 28 20 +12 -7.500000100000001 -4.000000100000001 -1.000000016011864e-07 7.500000100000001 7.500000100000001 1.000000016011864e-07 0 6 22 24 26 28 19 10 +13 5.4999999 -4.0000001 -9.99999993922529e-08 7.5000001 -1.9999999 23.0000001 0 4 -22 29 -30 -31 +14 -5.500000100000001 -4.000000100000001 -1.000000011686097e-07 5.500000100000001 -3.999999899999999 23.0000001 0 4 -24 31 -32 -33 +15 -7.5000001 -4.0000001 -9.99999993922529e-08 -5.4999999 -1.9999999 23.0000001 0 4 -26 33 -34 -35 +16 -7.5000001 -2.0000001 -9.99999993922529e-08 -7.4999999 9.999999994736442e-08 23.0000001 0 4 -28 35 -36 -37 +17 -7.5000001 -1.000000007245205e-07 -9.99999993922529e-08 7.5000001 7.5000001 23.0000001 0 4 -19 37 -38 -39 +18 7.4999999 -2.0000001 -9.99999993922529e-08 7.5000001 1.000000020567882e-07 23.0000001 0 4 -10 39 -40 -29 +19 -7.5000001 -4.0000001 22.9999999 7.5000001 7.5000001 23.0000001 0 6 40 38 36 34 32 30 +20 -5.5000001 -2.0000001 1.499999900000001 5.5000001 -1.999999899999999 21.5000001 0 4 44 -43 -42 -41 +21 5.4999999 -2.0000001 1.499999900000001 5.5000001 1.000000008355428e-07 21.5000001 0 4 42 -47 -46 -45 +22 -5.5000001 -1.000000011686097e-07 1.499999900000001 5.5000001 5.5000001 21.5000001 0 4 46 -48 -49 -50 +23 -5.5000001 -2.0000001 1.499999900000001 -5.4999999 9.99999993922529e-08 21.5000001 0 4 49 -52 -44 -51 +24 -5.5000001 -2.0000001 21.4999999 5.5000001 5.5000001 21.5000001 0 4 41 45 50 51 +25 -5.5000001 -2.0000001 1.4999999 5.5000001 5.5000001 1.5000001 0 4 -52 -43 -47 -48 +1 -7.500000100000001 -4.000000100000001 -1.000000011686097e-07 7.500000100000001 7.500000100000001 23.0000001 0 14 13 14 15 16 17 18 19 12 -20 -21 -22 -23 -24 25 +2 -7.500000100000001 -4.000000100000001 -3.000000100000002 7.500000100000001 7.500000100000001 1.00000001612699e-07 0 12 1 2 3 4 5 6 7 8 9 10 11 -12 +$EndEntities +$Nodes +111 3872 1 3872 +0 1 0 1 +1 +5.5 2 -1 +0 2 0 1 +2 +7.5 1.94289029309402e-15 -1 +0 3 0 1 +3 +7.5 1.94289029309402e-15 -3 +0 4 0 1 +4 +5.5 2 -3 +0 5 0 1 +5 +-7.5 0 -1 +0 6 0 1 +6 +-5.5 2 -1 +0 7 0 1 +7 +7.5 -2 -3 +0 8 0 1 +8 +7.5 1.90758359496969e-15 0 +0 9 0 1 +9 +7.5 -2 0 +0 10 0 1 +10 +5.5 -4 -3 +0 11 0 1 +11 +-5.5 -4 -3 +0 12 0 1 +12 +-7.5 -2 -3 +0 13 0 1 +13 +-7.5 0 -3 +0 14 0 1 +14 +-5.5 2 -3 +0 15 0 1 +15 +-7.5 0 0 +0 16 0 1 +16 +5.5 -4 0 +0 17 0 1 +17 +-5.5 -4 0 +0 18 0 1 +18 +-7.5 -2 0 +0 19 0 1 +19 +7.5 -2 23 +0 20 0 1 +20 +5.5 -4 23 +0 21 0 1 +21 +-5.5 -4 23 +0 22 0 1 +22 +-7.5 -2 23 +0 23 0 1 +23 +-7.5 0 23 +0 24 0 1 +24 +7.5 1.94289029309402e-15 23 +0 25 0 1 +25 +-5.5 -2 21.5 +0 26 0 1 +26 +5.5 -2 21.5 +0 27 0 1 +27 +5.5 -2 1.5 +0 28 0 1 +28 +-5.5 -2 1.5 +0 29 0 1 +29 +5.5 7.12393107467807e-16 21.5 +0 30 0 1 +30 +5.5 7.12393107467807e-16 1.5 +0 31 0 1 +31 +-5.5 -7.12393107467807e-16 1.5 +0 32 0 1 +32 +-5.5 -7.12393107467807e-16 21.5 +1 1 0 3 +33 +34 +35 +6.265366864730179 1.847759065022573 -1 +6.914213562373094 1.414213562373095 -1 +7.347759065022573 0.7653668647301807 -1 +1 2 0 1 +36 +7.5 1.94289029309402e-15 -2 +1 3 0 3 +37 +38 +39 +6.265366864730179 1.847759065022573 -3 +6.914213562373094 1.414213562373095 -3 +7.347759065022573 0.7653668647301807 -3 +1 4 0 1 +40 +5.5 2 -2 +1 5 0 23 +41 +42 +43 +44 +45 +46 +47 +48 +49 +50 +51 +52 +53 +54 +55 +56 +57 +58 +59 +60 +61 +62 +63 +-7.435836460303578 0.9789464416503854 -1 +-7.244443697168014 1.941142838268903 -1 +-6.929096493834653 2.870125742738169 -1 +-6.495190528383293 3.749999999999995 -1 +-5.950150052184268 4.5657107175654 -1 +-5.303300858899112 5.303300858899101 -1 +-4.56571071756541 5.950150052184259 -1 +-3.750000000000007 6.495190528383286 -1 +-2.870125742738183 6.929096493834646 -1 +-1.94114283826892 7.244443697168008 -1 +-0.9789464416504061 7.435836460303575 -1 +-2.377391089981168e-14 7.5 -1 +0.9789464416503589 7.435836460303582 -1 +1.941142838268874 7.244443697168021 -1 +2.870125742738141 6.929096493834664 -1 +3.749999999999964 6.49519052838331 -1 +4.565710717565373 5.950150052184288 -1 +5.303300858899083 5.30330085889913 -1 +5.950150052184249 4.565710717565425 -1 +6.495190528383278 3.75000000000002 -1 +6.929096493834644 2.870125742738189 -1 +7.244443697168009 1.941142838268917 -1 +7.435836460303578 0.9789464416503899 -1 +1 6 0 3 +64 +65 +66 +-7.347759065022573 0.7653668647301795 -1 +-6.914213562373095 1.414213562373095 -1 +-6.265366864730179 1.847759065022573 -1 +1 7 0 10 +67 +68 +69 +70 +71 +72 +73 +74 +75 +76 +-4.5 2 -1 +-3.5 2 -1 +-2.5 2 -1 +-1.5 2 -1 +-0.5 2 -1 +0.5 2 -1 +1.5 2 -1 +2.5 2 -1 +3.5 2 -1 +4.5 2 -1 +1 8 0 1 +77 +7.5 -0.999999999999999 -3 +1 9 0 0 +1 10 0 1 +78 +7.5 -0.999999999999999 0 +1 11 0 2 +79 +80 +7.5 -2 -1 +7.5 -2 -2 +1 12 0 3 +81 +82 +83 +7.347759065022574 -2.76536686473018 -3 +6.914213562373095 -3.414213562373095 -3 +6.265366864730179 -3.847759065022573 -3 +1 13 0 10 +84 +85 +86 +87 +88 +89 +90 +91 +92 +93 +4.5 -4 -3 +3.5 -4 -3 +2.5 -4 -3 +1.5 -4 -3 +0.5 -4 -3 +-0.5 -4 -3 +-1.5 -4 -3 +-2.5 -4 -3 +-3.5 -4 -3 +-4.5 -4 -3 +1 14 0 3 +94 +95 +96 +-6.265366864730179 -3.847759065022573 -3 +-6.914213562373095 -3.414213562373095 -3 +-7.347759065022574 -2.76536686473018 -3 +1 15 0 1 +97 +-7.5 -1 -3 +1 16 0 3 +98 +99 +100 +-7.347759065022573 0.7653668647301795 -3 +-6.914213562373095 1.414213562373095 -3 +-6.265366864730179 1.847759065022573 -3 +1 17 0 10 +101 +102 +103 +104 +105 +106 +107 +108 +109 +110 +-4.5 2 -3 +-3.5 2 -3 +-2.5 2 -3 +-1.5 2 -3 +-0.5 2 -3 +0.5 2 -3 +1.5 2 -3 +2.5 2 -3 +3.5 2 -3 +4.5 2 -3 +1 18 0 1 +111 +-5.5 2 -2 +1 19 0 23 +112 +113 +114 +115 +116 +117 +118 +119 +120 +121 +122 +123 +124 +125 +126 +127 +128 +129 +130 +131 +132 +133 +134 +-7.435836460303578 0.9789464416503854 0 +-7.244443697168014 1.941142838268903 0 +-6.929096493834653 2.870125742738169 0 +-6.495190528383293 3.749999999999995 0 +-5.950150052184268 4.5657107175654 0 +-5.303300858899112 5.303300858899101 0 +-4.56571071756541 5.950150052184259 0 +-3.750000000000007 6.495190528383286 0 +-2.870125742738183 6.929096493834646 0 +-1.94114283826892 7.244443697168008 0 +-0.9789464416504061 7.435836460303575 0 +-2.377391089981168e-14 7.5 0 +0.9789464416503589 7.435836460303582 0 +1.941142838268874 7.244443697168021 0 +2.870125742738141 6.929096493834664 0 +3.749999999999964 6.49519052838331 0 +4.565710717565373 5.950150052184288 0 +5.303300858899083 5.30330085889913 0 +5.950150052184249 4.565710717565425 0 +6.495190528383278 3.75000000000002 0 +6.929096493834644 2.870125742738189 0 +7.244443697168009 1.941142838268917 0 +7.435836460303578 0.9789464416503899 0 +1 20 0 0 +1 21 0 1 +135 +-7.5 0 -2 +1 22 0 3 +136 +137 +138 +7.347759065022574 -2.76536686473018 0 +6.914213562373095 -3.414213562373095 0 +6.265366864730179 -3.847759065022573 0 +1 23 0 2 +139 +140 +5.5 -4 -1 +5.5 -4 -2 +1 24 0 10 +141 +142 +143 +144 +145 +146 +147 +148 +149 +150 +4.5 -4 0 +3.5 -4 0 +2.5 -4 0 +1.5 -4 0 +0.5 -4 0 +-0.5 -4 0 +-1.5 -4 0 +-2.5 -4 0 +-3.5 -4 0 +-4.5 -4 0 +1 25 0 2 +151 +152 +-5.5 -4 -1 +-5.5 -4 -2 +1 26 0 3 +153 +154 +155 +-6.265366864730179 -3.847759065022573 0 +-6.914213562373095 -3.414213562373095 0 +-7.347759065022574 -2.76536686473018 0 +1 27 0 2 +156 +157 +-7.5 -2 -1 +-7.5 -2 -2 +1 28 0 1 +158 +-7.5 -1 0 +1 29 0 22 +159 +160 +161 +162 +163 +164 +165 +166 +167 +168 +169 +170 +171 +172 +173 +174 +175 +176 +177 +178 +179 +180 +7.5 -2 1 +7.5 -2 2 +7.5 -2 3 +7.5 -2 4 +7.5 -2 5 +7.5 -2 6 +7.5 -2 7 +7.5 -2 8 +7.5 -2 9 +7.5 -2 10 +7.5 -2 11 +7.5 -2 12 +7.5 -2 13 +7.5 -2 14 +7.5 -2 15 +7.5 -2 16 +7.5 -2 17 +7.5 -2 18 +7.5 -2 19 +7.5 -2 20 +7.5 -2 21 +7.5 -2 22 +1 30 0 3 +181 +182 +183 +6.265366864730179 -3.847759065022573 23 +6.914213562373095 -3.414213562373095 23 +7.347759065022574 -2.76536686473018 23 +1 31 0 22 +184 +185 +186 +187 +188 +189 +190 +191 +192 +193 +194 +195 +196 +197 +198 +199 +200 +201 +202 +203 +204 +205 +5.5 -4 1 +5.5 -4 2 +5.5 -4 3 +5.5 -4 4 +5.5 -4 5 +5.5 -4 6 +5.5 -4 7 +5.5 -4 8 +5.5 -4 9 +5.5 -4 10 +5.5 -4 11 +5.5 -4 12 +5.5 -4 13 +5.5 -4 14 +5.5 -4 15 +5.5 -4 16 +5.5 -4 17 +5.5 -4 18 +5.5 -4 19 +5.5 -4 20 +5.5 -4 21 +5.5 -4 22 +1 32 0 10 +206 +207 +208 +209 +210 +211 +212 +213 +214 +215 +-4.5 -4 23 +-3.5 -4 23 +-2.5 -4 23 +-1.5 -4 23 +-0.5 -4 23 +0.5 -4 23 +1.5 -4 23 +2.5 -4 23 +3.5 -4 23 +4.5 -4 23 +1 33 0 22 +216 +217 +218 +219 +220 +221 +222 +223 +224 +225 +226 +227 +228 +229 +230 +231 +232 +233 +234 +235 +236 +237 +-5.5 -4 1 +-5.5 -4 2 +-5.5 -4 3 +-5.5 -4 4 +-5.5 -4 5 +-5.5 -4 6 +-5.5 -4 7 +-5.5 -4 8 +-5.5 -4 9 +-5.5 -4 10 +-5.5 -4 11 +-5.5 -4 12 +-5.5 -4 13 +-5.5 -4 14 +-5.5 -4 15 +-5.5 -4 16 +-5.5 -4 17 +-5.5 -4 18 +-5.5 -4 19 +-5.5 -4 20 +-5.5 -4 21 +-5.5 -4 22 +1 34 0 3 +238 +239 +240 +-7.347759065022574 -2.76536686473018 23 +-6.914213562373095 -3.414213562373095 23 +-6.265366864730179 -3.847759065022573 23 +1 35 0 22 +241 +242 +243 +244 +245 +246 +247 +248 +249 +250 +251 +252 +253 +254 +255 +256 +257 +258 +259 +260 +261 +262 +-7.5 -2 1 +-7.5 -2 2 +-7.5 -2 3 +-7.5 -2 4 +-7.5 -2 5 +-7.5 -2 6 +-7.5 -2 7 +-7.5 -2 8 +-7.5 -2 9 +-7.5 -2 10 +-7.5 -2 11 +-7.5 -2 12 +-7.5 -2 13 +-7.5 -2 14 +-7.5 -2 15 +-7.5 -2 16 +-7.5 -2 17 +-7.5 -2 18 +-7.5 -2 19 +-7.5 -2 20 +-7.5 -2 21 +-7.5 -2 22 +1 36 0 1 +263 +-7.5 -1 23 +1 37 0 22 +264 +265 +266 +267 +268 +269 +270 +271 +272 +273 +274 +275 +276 +277 +278 +279 +280 +281 +282 +283 +284 +285 +-7.5 0 1 +-7.5 0 2 +-7.5 0 3 +-7.5 0 4 +-7.5 0 5 +-7.5 0 6 +-7.5 0 7 +-7.5 0 8 +-7.5 0 9 +-7.5 0 10 +-7.5 0 11 +-7.5 0 12 +-7.5 0 13 +-7.5 0 14 +-7.5 0 15 +-7.5 0 16 +-7.5 0 17 +-7.5 0 18 +-7.5 0 19 +-7.5 0 20 +-7.5 0 21 +-7.5 0 22 +1 38 0 23 +286 +287 +288 +289 +290 +291 +292 +293 +294 +295 +296 +297 +298 +299 +300 +301 +302 +303 +304 +305 +306 +307 +308 +7.435836460303578 0.9789464416503871 23 +7.244443697168013 1.941142838268904 23 +6.929096493834652 2.87012574273817 23 +6.495190528383292 3.749999999999996 23 +5.950150052184267 4.565710717565402 23 +5.303300858899111 5.303300858899102 23 +4.565710717565408 5.95015005218426 23 +3.750000000000005 6.495190528383287 23 +2.870125742738181 6.929096493834647 23 +1.941142838268918 7.244443697168009 23 +0.9789464416504043 7.435836460303575 23 +2.193694070109065e-14 7.5 23 +-0.9789464416503607 7.435836460303582 23 +-1.941142838268876 7.24444369716802 23 +-2.870125742738142 6.929096493834663 23 +-3.749999999999965 6.49519052838331 23 +-4.565710717565375 5.950150052184287 23 +-5.303300858899084 5.303300858899129 23 +-5.95015005218425 4.565710717565423 23 +-6.495190528383279 3.750000000000018 23 +-6.929096493834645 2.870125742738188 23 +-7.24444369716801 1.941142838268915 23 +-7.435836460303578 0.9789464416503881 23 +1 39 0 22 +309 +310 +311 +312 +313 +314 +315 +316 +317 +318 +319 +320 +321 +322 +323 +324 +325 +326 +327 +328 +329 +330 +7.5 1.83697019872103e-15 1 +7.5 1.83697019872103e-15 2 +7.5 1.83697019872103e-15 3 +7.5 1.83697019872103e-15 4 +7.5 1.83697019872103e-15 5 +7.5 1.83697019872103e-15 6 +7.5 1.83697019872103e-15 7 +7.5 1.83697019872103e-15 8 +7.5 1.83697019872103e-15 9 +7.5 1.83697019872103e-15 10 +7.5 1.83697019872103e-15 11 +7.5 1.83697019872103e-15 12 +7.5 1.83697019872103e-15 13 +7.5 1.83697019872103e-15 14 +7.5 1.83697019872103e-15 15 +7.5 1.83697019872103e-15 16 +7.5 1.83697019872103e-15 17 +7.5 1.83697019872103e-15 18 +7.5 1.83697019872103e-15 19 +7.5 1.83697019872103e-15 20 +7.5 1.83697019872103e-15 21 +7.5 1.83697019872103e-15 22 +1 40 0 1 +331 +7.5 -0.9999999999999991 23 +1 41 0 10 +332 +333 +334 +335 +336 +337 +338 +339 +340 +341 +-4.5 -2 21.5 +-3.5 -2 21.5 +-2.5 -2 21.5 +-1.5 -2 21.5 +-0.5 -1.999999999999999 21.5 +0.5 -1.999999999999999 21.5 +1.5 -1.999999999999999 21.5 +2.5 -1.999999999999999 21.5 +3.5 -1.999999999999999 21.5 +4.5 -1.999999999999999 21.5 +1 42 0 19 +342 +343 +344 +345 +346 +347 +348 +349 +350 +351 +352 +353 +354 +355 +356 +357 +358 +359 +360 +5.5 -2 20.5 +5.5 -2 19.5 +5.5 -2 18.5 +5.5 -2 17.5 +5.5 -2 16.5 +5.5 -2 15.5 +5.5 -2 14.5 +5.5 -2 13.5 +5.5 -2 12.5 +5.5 -2 11.5 +5.5 -2 10.5 +5.5 -2 9.5 +5.5 -2 8.5 +5.5 -2 7.5 +5.5 -2 6.5 +5.5 -2 5.5 +5.5 -2 4.5 +5.5 -2 3.5 +5.5 -2 2.5 +1 43 0 10 +361 +362 +363 +364 +365 +366 +367 +368 +369 +370 +4.5 -1.999999999999999 1.5 +3.5 -1.999999999999999 1.5 +2.5 -1.999999999999999 1.5 +1.5 -1.999999999999999 1.5 +0.5 -1.999999999999999 1.5 +-0.5 -1.999999999999999 1.5 +-1.5 -2 1.5 +-2.5 -2 1.5 +-3.5 -2 1.5 +-4.5 -2 1.5 +1 44 0 19 +371 +372 +373 +374 +375 +376 +377 +378 +379 +380 +381 +382 +383 +384 +385 +386 +387 +388 +389 +-5.5 -2 20.5 +-5.5 -2 19.5 +-5.5 -2 18.5 +-5.5 -2 17.5 +-5.5 -2 16.5 +-5.5 -2 15.5 +-5.5 -2 14.5 +-5.5 -2 13.5 +-5.5 -2 12.5 +-5.5 -2 11.5 +-5.5 -2 10.5 +-5.5 -2 9.5 +-5.5 -2 8.5 +-5.5 -2 7.5 +-5.5 -2 6.5 +-5.5 -2 5.5 +-5.5 -2 4.5 +-5.5 -2 3.5 +-5.5 -2 2.5 +1 45 0 1 +390 +5.5 -0.9999999999999996 21.5 +1 46 0 19 +391 +392 +393 +394 +395 +396 +397 +398 +399 +400 +401 +402 +403 +404 +405 +406 +407 +408 +409 +5.5 7.12393107467807e-16 20.5 +5.5 7.12393107467807e-16 19.5 +5.5 7.12393107467807e-16 18.5 +5.5 7.12393107467807e-16 17.5 +5.5 7.12393107467807e-16 16.5 +5.5 7.12393107467807e-16 15.5 +5.5 7.12393107467807e-16 14.5 +5.5 7.12393107467807e-16 13.5 +5.5 7.12393107467807e-16 12.5 +5.5 7.12393107467807e-16 11.5 +5.5 7.12393107467807e-16 10.5 +5.5 7.12393107467807e-16 9.5 +5.5 7.12393107467807e-16 8.5 +5.5 7.12393107467807e-16 7.5 +5.5 7.12393107467807e-16 6.5 +5.5 7.12393107467807e-16 5.5 +5.5 7.12393107467807e-16 4.5 +5.5 7.12393107467807e-16 3.5 +5.5 7.12393107467807e-16 2.5 +1 47 0 1 +410 +5.5 -0.9999999999999993 1.5 +1 48 0 17 +411 +412 +413 +414 +415 +416 +417 +418 +419 +420 +421 +422 +423 +424 +425 +426 +427 +-5.416442641567144 0.9550649771681169 1.5 +-5.168309414322496 1.881110788291179 1.5 +-4.76313972081441 2.750000000000004 1.5 +-4.213244437154375 3.535331853275971 1.5 +-3.53533185327596 4.213244437154383 1.5 +-2.749999999999994 4.763139720814416 1.5 +-1.881110788291173 5.168309414322498 1.5 +-0.9550649771681126 5.416442641567145 1.5 +3.162287958979422e-15 5.5 1.5 +0.9550649771681189 5.416442641567144 1.5 +1.881110788291179 5.168309414322496 1.5 +2.750000000000004 4.76313972081441 1.5 +3.535331853275965 4.213244437154381 1.5 +4.213244437154381 3.535331853275964 1.5 +4.763139720814413 2.749999999999999 1.5 +5.168309414322496 1.881110788291178 1.5 +5.416442641567144 0.9550649771681178 1.5 +1 49 0 19 +428 +429 +430 +431 +432 +433 +434 +435 +436 +437 +438 +439 +440 +441 +442 +443 +444 +445 +446 +-5.5 -7.12393107467807e-16 20.5 +-5.5 -7.12393107467807e-16 19.5 +-5.5 -7.12393107467807e-16 18.5 +-5.5 -7.12393107467807e-16 17.5 +-5.5 -7.12393107467807e-16 16.5 +-5.5 -7.12393107467807e-16 15.5 +-5.5 -7.12393107467807e-16 14.5 +-5.5 -7.12393107467807e-16 13.5 +-5.5 -7.12393107467807e-16 12.5 +-5.5 -7.12393107467807e-16 11.5 +-5.5 -7.12393107467807e-16 10.5 +-5.5 -7.12393107467807e-16 9.5 +-5.5 -7.12393107467807e-16 8.5 +-5.5 -7.12393107467807e-16 7.5 +-5.5 -7.12393107467807e-16 6.5 +-5.5 -7.12393107467807e-16 5.5 +-5.5 -7.12393107467807e-16 4.5 +-5.5 -7.12393107467807e-16 3.5 +-5.5 -7.12393107467807e-16 2.5 +1 50 0 17 +447 +448 +449 +450 +451 +452 +453 +454 +455 +456 +457 +458 +459 +460 +461 +462 +463 +5.416442641567144 0.9550649771681187 21.5 +5.168309414322495 1.881110788291181 21.5 +4.763139720814411 2.750000000000004 21.5 +4.213244437154374 3.535331853275971 21.5 +3.535331853275961 4.213244437154385 21.5 +2.749999999999992 4.763139720814417 21.5 +1.88111078829117 5.168309414322499 21.5 +0.9550649771681095 5.416442641567145 21.5 +-7.703098322692686e-15 5.5 21.5 +-0.9550649771681246 5.416442641567143 21.5 +-1.881110788291188 5.168309414322493 21.5 +-2.75000000000001 4.763139720814407 21.5 +-3.535331853275974 4.213244437154372 21.5 +-4.213244437154385 3.535331853275959 21.5 +-4.763139720814417 2.749999999999993 21.5 +-5.168309414322498 1.881110788291171 21.5 +-5.416442641567144 0.9550649771681134 21.5 +1 51 0 1 +464 +-5.5 -1 21.5 +1 52 0 1 +465 +-5.5 -1 1.5 +2 1 0 11 +466 +467 +468 +469 +470 +471 +472 +473 +474 +475 +476 +5.993966946542607 1.938039384461361 -1.604012461581574 +5.993966441725533 1.938039513128929 -2.39598942627009 +6.412678859682176 1.779611558483829 -2.000003564804927 +7.279604776974938 0.9126920826697147 -1.999998059249307 +7.438036215037865 0.4939793813528109 -2.395984756754485 +7.438036287333087 0.4939790977158687 -1.604014180890706 +6.914207695165375 1.414219429556473 -2.000001249131358 +6.718155557771239 1.586220992507362 -2.500009988171947 +7.086206646469948 1.218174238233005 -2.499994381026735 +7.086206646469948 1.218174238233005 -1.499994381026735 +6.718155557771239 1.586220992507362 -1.500009988171948 +2 2 0 65 +477 +478 +479 +480 +481 +482 +483 +484 +485 +486 +487 +488 +489 +490 +491 +492 +493 +494 +495 +496 +497 +498 +499 +500 +501 +502 +503 +504 +505 +506 +507 +508 +509 +510 +511 +512 +513 +514 +515 +516 +517 +518 +519 +520 +521 +522 +523 +524 +525 +526 +527 +528 +529 +530 +531 +532 +533 +534 +535 +536 +537 +538 +539 +540 +541 +0.1870664633872618 4.758059080523301 -1 +-2.369345890650797 4.311003284088413 -1 +2.662930480922575 4.37608523479463 -1 +-4.019417253347428 3.832279341251795 -1 +4.334942210804627 3.845673741822411 -1 +-1.066461977060845 5.742829375120323 -1 +-0.8496781371805937 3.600354626523754 -1 +1.662193044923468 5.649255575230907 -1 +1.324702040000504 3.558426212972511 -1 +-5.240401876635328 3.30560096425743 -1 +0.3593184614292127 6.150913847807928 -1 +-3.457659281976864 5.134880719114745 -1 +-2.643757035060575 3.492138379570638 -1 +5.49112722867743 3.213068458690616 -1 +-2.336145296968308 5.776661999868085 -1 +3.830359194536645 4.732139124118929 -1 +3.176198888485325 3.328821847416095 -1 +2.804407754639676 5.83168187320377 -1 +0.2290547598993492 3.140805984570031 -1 +-0.7441191184133842 4.636932319680064 -1 +-1.871138905093526 2.896611564756064 -1 +1.68074123511266 4.593027003913253 -1 +-6.013943867599792 2.765847013628514 -1 +-4.875957580172419 4.222600784901871 -1 +2.117961875054624 2.890453613081717 -1 +6.056980986081564 2.647467829677785 -1 +-4.006517483907203 2.829382351440003 -1 +-0.4480311868962615 6.512585141751194 -1 +1.229709082526649 6.493509829829802 -1 +-3.218286205778173 4.257694099162171 -1 +4.03355826990608 2.782726238955847 -1 +-4.317091082471712 5.151774801005287 -1 +5.149556235036135 4.535645231312082 -1 +-1.68455352410657 6.388350152102527 -1 +2.120151158499825 6.416286692385744 -1 +3.484493897097131 4.13122585299617 -1 +-0.1669656622255587 5.520329727764123 -1 +1.011482075305637 2.734121778037613 -1 +-0.05501226635026034 4.042580268733856 -1 +-0.9572026824871958 2.738480748713855 -1 +0.8369784389401864 5.34243858878324 -1 +-1.807591208175401 4.907705890161268 -1 +-1.695146791523505 3.946613544361446 -1 +-5.000000000000001 2.579191874685807 -1 +5.000000000000001 2.570838709504947 -1 +-3.150846400594976 5.923858934523436 -1 +2.348977020872908 5.090849013105187 -1 +2.192506903915138 3.749362782435641 -1 +3.766980691330971 5.504536997524381 -1 +0.7595021600971397 4.237152056534319 -1 +6.718085786945426 2.280482831788152 -1 +-6.718085786945432 2.280482831788134 -1 +4.544385583732699 5.016813890092549 -1 +-5.744816002748919 3.813371987491606 -1 +-2.697144820185085 5.083113096625321 -1 +5.525661012896702 3.905875626402956 -1 +0.432026237847072 6.841270702035318 -1 +-3.004641586911992 2.709507666576991 -1 +-3.848261496521793 5.731171007042203 -1 +3.149691506566651 4.944419682623844 -1 +-4.526878182943733 3.347795362038982 -1 +3.017061590662538 2.54925554187537 -1 +-3.838107588379367 4.552782617864981 -1 +4.877057744456968 3.263636555075355 -1 +-3.378523913001074 3.424200367600319 -1 +2 3 0 5 +542 +543 +544 +545 +546 +7.5 -0.999999999999999 -1.5 +7.5 -0.7272230320699693 -0.6998906705539358 +7.5 -1.272776967930028 -2.300109329446064 +7.5 -1.345444606413993 -0.6399781341107871 +7.5 -0.6545553935860047 -2.360021865889213 +2 4 0 102 +547 +548 +549 +550 +551 +552 +553 +554 +555 +556 +557 +558 +559 +560 +561 +562 +563 +564 +565 +566 +567 +568 +569 +570 +571 +572 +573 +574 +575 +576 +577 +578 +579 +580 +581 +582 +583 +584 +585 +586 +587 +588 +589 +590 +591 +592 +593 +594 +595 +596 +597 +598 +599 +600 +601 +602 +603 +604 +605 +606 +607 +608 +609 +610 +611 +612 +613 +614 +615 +616 +617 +618 +619 +620 +621 +622 +623 +624 +625 +626 +627 +628 +629 +630 +631 +632 +633 +634 +635 +636 +637 +638 +639 +640 +641 +642 +643 +644 +645 +646 +647 +648 +4 -1 -3 +0.1680248073548498 -1.118416106764829 -3 +-4 -1 -3 +5.582830103784402 0.05534530592537101 -3 +-5.582830103784402 0.05534530592537434 -3 +5.5828301037844 -2.055345305925375 -3 +-5.5828301037844 -2.055345305925375 -3 +2 -1.875 -3 +-2.033620359047142 -1.79131912775754 -3 +-2.035898056649567 0.07674516867458658 -3 +2.213333317868425 -0.1258533873162507 -3 +4.101779747627276 -2.439273566114484 -3 +-4.101779747627275 -2.439273566114484 -3 +-4.106695559775863 0.4602366129288615 -3 +4.106695559775862 0.4602366129288611 -3 +-0.6460845862450996 -2.511246244746922 -3 +-0.4492643720861318 0.4799744654831883 -3 +0.8284516776848457 -2.639936478365773 -3 +-6.236973300455533 -1.005328908622273 -3 +6.236973300455533 -1.005328908622273 -3 +0.7271855163894341 0.6810928116033921 -3 +-3.147076911711295 -2.813522715310799 -3 +2.982593592526808 -2.754458812522487 -3 +1.239478326612903 -0.8901209677419354 -3 +2.786404713172182 -1.153827858643246 -3 +-1.280270519985158 -0.9097347106856666 -3 +-2.782476925306105 -0.9459458347306425 -3 +3.0871198022459 0.9588847551704744 -3 +-2.990710833520377 0.8995730809295659 -3 +5.590223628448567 1.066397395798067 -3 +-5.590223628448567 1.066397395798067 -3 +5.594417742649044 -3.069428840312664 -3 +-5.594417742649044 -3.069428840312664 -3 +5.385768157369249 -1.005155152420452 -3 +-5.385768157369247 -1.005155152420451 -3 +6.616812748377478 0.166352148242104 -3 +6.616812748377478 -2.166352148242103 -3 +-6.616812748377478 0.1663521482421038 -3 +-6.616812748377477 -2.166352148242103 -3 +-1.538932989442117 -2.907249671898838 -3 +1.975089339371452 -2.92859563764582 -3 +-3.242963602324762 -1.850896887933162 -3 +3.303834430553925 -1.807180144412722 -3 +-1.416452267750508 0.9598448125777745 -3 +1.753305325058858 1.004626921027766 -3 +3.364516627706975 -0.1919276009994859 -3 +-3.318221291405232 -0.1333994500557305 -3 +-4.697714990354206 -0.208174058949992 -3 +4.697714990354206 -0.2081740589499933 -3 +0.6851656491581183 -1.683096754604819 -3 +-4.783610378634976 -3.21856518310117 -3 +-4.77953654742585 1.218522338969869 -3 +4.783610378634976 -3.21856518310117 -3 +4.779536547425849 1.218522338969869 -3 +0.3935362353222988 -0.1905479777091583 -3 +-4.681322794384339 -1.779357452069106 -3 +4.681322794384339 -1.779357452069106 -3 +0.04893483027923328 -3.171377117656336 -3 +0.0929437356183799 1.310790690235033 -3 +6.891398059349909 -0.4999999999999986 -3 +-6.891398059349911 -0.5 -3 +-6.871228261470318 -1.471345432672708 -3 +6.871228261470319 -1.471345432672707 -3 +-0.5982066934524424 -1.55194774072227 -3 +6.386900014489461 -2.886410964434332 -3 +-6.386900014489461 -2.886410964434331 -3 +-6.386200995456049 0.8859057236818988 -3 +6.386200995456049 0.8859057236818986 -3 +3.811330619798176 -3.317330367616131 -3 +-3.975388588144418 1.315666406565659 -3 +3.994670381889522 1.327528741413841 -3 +-3.838744506328924 -3.327174351414183 -3 +-0.4954200030225923 -0.5329028792978815 -3 +-2.174657908147468 1.21362859412003 -3 +-0.8239683440504862 -3.294274357611175 -3 +-1.135461043898791 0.01478537135040026 -3 +1.966313309299417 -1.13852778651589 -3 +-2.023618903747852 -0.9486665344549814 -3 +-2.276582236264769 -3.266298988243721 -3 +1 -3.401056794828369 -3 +-1.252439943101577 -2.095616567720035 -3 +6.139923109972079 -0.3779299482593397 -3 +-6.139923109972077 -0.377929948259339 -3 +-6.138408855693019 -1.634747761738849 -3 +6.138408855693021 -1.634747761738851 -3 +4.967522314718799 0.4836654837276293 -3 +-4.967522314718799 0.4836654837276306 -3 +-0.7291862218077846 1.29104565521029 -3 +0.0810476141299175 -2.112670073810158 -3 +1 1.433421024164321 -3 +-4.978517256174404 -2.489476540347122 -3 +4.978517256174404 -2.489476540347122 -3 +1.265367744250384 0.09583947997276243 -3 +1.29860224593449 -2.080383435251538 -3 +-4.006516536084094 -1.767381976529188 -3 +4.008077852644046 -1.710766573812865 -3 +-4.020054649754012 -0.2405260823385119 -3 +4.018385873832429 -0.2624141636563462 -3 +2.976429954254738 -3.444946031508771 -3 +-3 -3.491684643958649 -3 +-2.218661454237505 -2.549226914263168 -3 +2.66615653819693 -2.114840573885567 -3 +2 5 0 13 +649 +650 +651 +652 +653 +654 +655 +656 +657 +658 +659 +660 +661 +0 2 -2 +-4.07015306122449 2 -2.006377551020408 +-2 2 -2 +2 2 -2 +4.070153061224488 2 -1.968112244897959 +-3.011692176870748 2 -2.001062925170068 +-1 2 -2 +1 2 -2 +3.011692176870747 2 -1.99468537414966 +4.789444661663083 2 -2.26460913394929 +-4.789444661663083 2 -1.734062762964411 +4.871919544577516 2 -1.64654427576945 +-4.871919544577515 2 -2.348088062796964 +2 6 0 24 +662 +663 +664 +665 +666 +667 +668 +669 +670 +671 +672 +673 +674 +675 +676 +677 +678 +679 +680 +681 +682 +683 +684 +685 +3.317165176642475 6.726545561495179 -0.5 +2.41079598977368 7.101975971213303 -0.5 +1.463177415120932 7.355889603024234 -0.5 +0.4905234692260471 7.483941924289528 -0.5 +4.166776747646981 6.236022092269113 -0.5 +-0.4905234692260945 7.483941924289526 -0.5 +-1.463177415120979 7.355889603024225 -0.5 +-2.410795989773724 7.101975971213289 -0.5 +-3.317165176642519 6.726545561495158 -0.5 +-4.166776747647022 6.236022092269085 -0.5 +-4.945093613250522 5.638798556092325 -0.5 +-5.638798556092335 4.945093613250512 -0.5 +-6.236022092269094 4.166776747647011 -0.5 +-6.726545561495165 3.317165176642504 -0.5 +-7.101975971213293 2.410795989773708 -0.5 +-7.355889603024229 1.46317741512096 -0.5 +-7.483941924289526 0.4905234692260723 -0.5 +4.945093613250489 5.638798556092355 -0.5 +5.63879855609231 4.94509361325054 -0.5 +6.236022092269075 4.166776747647038 -0.5 +6.726545561495153 3.317165176642528 -0.5 +7.101975971213288 2.410795989773725 -0.5 +7.355889603024226 1.463177415120971 -0.5 +7.483941924289526 0.4905234692260767 -0.5 +2 7 0 11 +686 +687 +688 +689 +690 +691 +692 +693 +694 +695 +696 +-7.438039384461361 0.4939669465426079 -1.604012461581574 +-7.438039513128929 0.4939664417255333 -2.39598942627009 +-7.279611558483828 0.9126788596821767 -2.000003564804928 +-6.412692082669713 1.779604776974939 -1.999998059249307 +-5.993979381352809 1.938036215037865 -2.395984756754486 +-5.993979097715867 1.938036287333087 -1.604014180890706 +-6.914219429556474 1.414207695165374 -2.000001249131357 +-7.086220992507362 1.21815555777124 -2.500009988171948 +-6.718174238233004 1.586206646469948 -2.499994381026735 +-6.718174238233004 1.586206646469948 -1.499994381026735 +-7.086220992507362 1.21815555777124 -1.500009988171948 +2 8 0 9 +697 +698 +699 +700 +701 +702 +703 +704 +705 +7.341656363735328 -2.779937073047029 -2.250319501925922 +6.910055516735094 -3.418359418386231 -2.519900209691041 +6.267265774908892 -3.846971367036711 -2.251710135514521 +6.894811167296099 -3.433353343591904 -1.607713803922431 +6.309707639294851 -3.82876284380112 -1.379027954094484 +7.323168302993022 -2.822227060465384 -1.379723552247083 +7.343739922432291 -2.774998773179268 -0.5420657148294609 +6.275000852600464 -3.843739048365726 -0.5420676628435301 +6.914214913381477 -3.414212211363423 -0.7789361270829958 +2 9 0 34 +706 +707 +708 +709 +710 +711 +712 +713 +714 +715 +716 +717 +718 +719 +720 +721 +722 +723 +724 +725 +726 +727 +728 +729 +730 +731 +732 +733 +734 +735 +736 +737 +738 +739 +4 -4 -1.5 +-4.030705005520186 -4 -1.5 +2.095588235294117 -4 -1.489583333333333 +-1 -4 -1.5 +0.5 -4 -1.5 +-2.5 -4 -1.5 +3 -4 -2 +3 -4 -0.9375 +-0.25 -4 -2.083333333333333 +-3.25 -4 -2.083333333333333 +-3.25 -4 -0.9166666666666666 +1.210595349250812 -4 -2.072516506602641 +-1.787792894935752 -4 -2.080020319816238 +-0.25 -4 -0.9166666666666666 +1.218981761800931 -4 -0.9220861084958765 +-1.790547479114743 -4 -0.9197382068953437 +4.625 -4 -2.125 +-4.625 -4 -2.125 +-4.625 -4 -0.875 +4.625 -4 -0.875 +2.061236716908986 -4 -2.312419967987195 +2.043571581542666 -4 -0.6765559708917135 +-1.00755857898715 -4 -2.332670730629914 +-1.008109495822949 -4 -0.667280974712402 +3.84375 -4 -2.28125 +3.901785714285714 -4 -0.6785714285714286 +0.4876724499323544 -4 -2.188544614274281 +-2.512039736529532 -4 -2.189884580919566 +0.4891700236020178 -4 -0.8104915669933113 +-2.512531626561495 -4 -0.810072298850359 +-3.955514116209542 -4 -2.365646258503402 +-3.955514116209542 -4 -0.6343537414965986 +4.947744987207711 -4 -1.5 +-4.949343540181481 -4 -1.5 +2 10 0 9 +740 +741 +742 +743 +744 +745 +746 +747 +748 +-6.91003003356416 -3.418384751908682 -0.4800907253791463 +-6.267216032287268 -3.846992030248474 -0.7482763635295313 +-7.341637756682094 -2.779981008206573 -0.7496735903581735 +-6.894713385906114 -3.433448489194608 -1.392248213528774 +-6.309498687810462 -3.828855345409565 -1.620954262330252 +-7.32311804870467 -2.822338482917635 -1.620256108836653 +-7.343836396064782 -2.774769220185492 -2.45797683963225 +-6.274852704870818 -3.843801314066778 -2.457960240523925 +-6.913718383369125 -3.414708568053571 -2.221186025411704 +2 11 0 5 +749 +750 +751 +752 +753 +-7.5 -1 -1.5 +-7.5 -1.272776967930029 -2.300109329446064 +-7.5 -0.7272230320699709 -0.6998906705539358 +-7.5 -0.6545553935860058 -2.360021865889213 +-7.5 -1.345444606413994 -0.6399781341107871 +2 12 0 182 +754 +755 +756 +757 +758 +759 +760 +761 +762 +763 +764 +765 +766 +767 +768 +769 +770 +771 +772 +773 +774 +775 +776 +777 +778 +779 +780 +781 +782 +783 +784 +785 +786 +787 +788 +789 +790 +791 +792 +793 +794 +795 +796 +797 +798 +799 +800 +801 +802 +803 +804 +805 +806 +807 +808 +809 +810 +811 +812 +813 +814 +815 +816 +817 +818 +819 +820 +821 +822 +823 +824 +825 +826 +827 +828 +829 +830 +831 +832 +833 +834 +835 +836 +837 +838 +839 +840 +841 +842 +843 +844 +845 +846 +847 +848 +849 +850 +851 +852 +853 +854 +855 +856 +857 +858 +859 +860 +861 +862 +863 +864 +865 +866 +867 +868 +869 +870 +871 +872 +873 +874 +875 +876 +877 +878 +879 +880 +881 +882 +883 +884 +885 +886 +887 +888 +889 +890 +891 +892 +893 +894 +895 +896 +897 +898 +899 +900 +901 +902 +903 +904 +905 +906 +907 +908 +909 +910 +911 +912 +913 +914 +915 +916 +917 +918 +919 +920 +921 +922 +923 +924 +925 +926 +927 +928 +929 +930 +931 +932 +933 +934 +935 +0.1301889832017972 1.832594838063375 0 +-3.432664547395953 -0.005449284577116353 0 +3.537550715069913 0.08407582708841677 0 +-2.806798976259789 3.200540829432687 0 +3.150500324607642 3.080966895810911 0 +-0.6241760758070013 -1.138139072431871 0 +-0.2886416802904622 4.587644192792917 0 +-5.163546008855617 -1.663546008855617 0 +4.978112716221158 -1.627463740026777 0 +1.638200311388426 -1.561271288254505 0 +-4.781277195225842 1.954021428546473 0 +4.917436269873053 1.777431335630769 0 +1.999737849900684 5.160724559849697 0 +-3.134763569463329 -2.006829489394582 0 +-1.815667943821952 1.320726280295869 0 +2.05863730969147 1.239522055914014 0 +-5.701604820134682 0.1369700548937121 0 +-2.241272146287453 5.080564993816331 0 +5.77957611002333 0.02087131136300924 0 +3.324292098145806 -2.084562424760274 0 +1.279783306694851 3.305154989775993 0 +0.7443985880669836 0.04712323235730143 0 +-1.019388591713864 3.139909467850984 0 +-4.476274232281495 3.657938526358817 0 +4.694377003069913 3.550075902766019 0 +3.576797163455748 4.721078038759276 0 +0.1906827289498684 -2.441496097035845 0 +-1.618655838116212 -2.408901548408036 0 +0.6344133166524883 5.955206786196074 0 +-5.915586564582008 -2.650035203591058 0 +-1.954378961906882 -0.2230004400785532 0 +-0.9831690486637763 5.953558071550939 0 +-3.316425546497365 1.771421784879381 0 +5.922526904152388 -2.647766749799385 0 +-0.6366410307619145 0.4187863174905175 0 +-6.330293296657951 -1.374681797688581 0 +-3.58452149769246 4.833761210385703 0 +3.461726192079953 1.616843957899504 0 +2.15559003404963 -0.2244948193923277 0 +6.356746822981361 -1.440123210477508 0 +-4.397657669358982 -2.696863892751749 0 +-6.010335692529925 1.4646963109547 0 +6.146759574307818 1.322000253495753 0 +4.638062348776621 -3.005219250253539 0 +2.18123426074374 -2.629736170055301 0 +-4.606513706921477 -0.5514140676891106 0 +4.636342718293964 -0.8254292457711179 0 +-5.519410525348565 2.965404550858586 0 +-4.478163851902117 0.9117041470468858 0 +5.904429128098725 2.819539292640211 0 +4.581072468644535 0.7832493265263643 0 +0.5688053154642322 -1.070036451306887 0 +2.862773054480998 5.584493710691346 0 +-1.393503808874927 4.19204626754724 0 +-2.254766438042159 -1.258022423477425 0 +2.935969522102539 -1.23265118821486 0 +0.06544211347633255 3.53589385144661 0 +0.6853439014138095 4.31798232174698 0 +1.962089129361656 2.188622142356385 0 +1.730028294970011 6.005433223582527 0 +2.173541078042712 3.838436303362273 0 +-6.596068027622552 -0.5607221576473531 0 +-3.889994892646375 -1.499088116587052 0 +6.63883111530307 -0.6190633293265453 0 +-1.993487310821689 2.444266333648922 0 +-0.9139631639099606 2.101374071648812 0 +-1.995719627254441 6.117935340308165 0 +-3.858801392730971 2.672614524884998 0 +0.9996503150566819 1.097389188200618 0 +4.214114837518975 -1.53370256672034 0 +1.097546505263441 -3.076127826249699 0 +-5.064706203663379 -3.214248197829207 0 +-2.544967123081932 -2.876968171890732 0 +4.104362917354348 2.522862800945842 0 +4.52714188622738 4.490125123771167 0 +-0.7851318543128949 -3.016381969969165 0 +-2.856855440885519 0.8534608313345367 0 +-3.044274377882692 5.714031722896447 0 +-5.500427286156741 -0.8477006371618705 0 +2.987100583199961 0.7681535151773532 0 +-2.792799509843951 4.233197899348329 0 +-6.471546818560826 0.6248079143190726 0 +-3.22714717233608 -0.9793147708501255 0 +1.023532633907625 2.230987310638348 0 +3.807335470468255 -3.067945424364257 0 +5.597476335762296 -0.9231198628648052 0 +-0.3418508210840764 6.56688583351043 0 +6.554495903332595 0.5333696705199005 0 +-4.58052460083688 4.689410845266046 0 +-6.644018268027164 -2.158115373276576 0 +3.79057313828091 3.706386565310673 0 +6.656078639667447 -2.371056903560235 0 +-0.1469225247385051 -0.3241556738616271 0 +5.5510986457835 3.670793406078032 0 +-0.6842254454380641 -2.040167968550325 0 +-2.015765071046145 3.596156498197567 0 +-0.2486592881211816 2.597400989835324 0 +1.382761028067258 -0.6460314765818347 0 +2.495471143410406 -1.784221726359719 0 +-3.648036066690328 3.837223975709525 0 +-3.436920620247855 -3.015838491871027 0 +-5.426579760348786 3.658668397318988 0 +-6.280133971501167 2.272737874157771 0 +3.765254695033476 5.528455339491872 0 +-1.290390815088548 5.091453953709309 0 +6.429903637825865 2.06903806805631 0 +-0.2497133456555315 5.51903953494382 0 +5.43547896521434 -3.250995810466693 0 +0.1305722358709394 0.8212623695701413 0 +1.643159484269452 0.4566248905730901 0 +2.925008106076378 -3.232067556934969 0 +-1.076589012674492 -0.2647258170790074 0 +-5.320869689627472 1.01519191926134 0 +5.445700523455518 0.8964857890239449 0 +2.530846579735276 4.572097284240542 0 +-1.420494415088497 0.5179989937550604 0 +-5.153990006472585 -2.366304215520628 0 +-3.722121472705628 0.8723887394023722 0 +0.1075753495813033 -3.271584329950449 0 +1.13151162452833 6.681610879324534 0 +1.168977991648704 5.121026036324854 0 +2.84710535229308 2.245028560873719 0 +-5.772621201057512 -3.370559330467213 0 +-1.288270136307382 6.674927907174983 0 +1.019873148831534 -2.128127606595947 0 +3.840246852302101 0.7894541253586608 0 +3.70320453016391 -0.8611437150605523 0 +-1.80346490271665 -3.222657239292451 0 +-1.413641156000678 -1.622819192058742 0 +4.166858833216137 -2.314177506497192 0 +-5.818055085359397 -1.943378175081577 0 +-3.839115066033972 5.612221301325715 0 +-0.6590229918507302 3.863873444909437 0 +-0.7543342224182644 1.168790478470629 0 +6.258322067804889 -3.135456585553667 0 +-2.305338518395531 -2.094404813623519 0 +-4.781801657570309 2.885180985601372 0 +-6.496291893487516 -2.988342710939028 0 +-2.714581368558815 -0.255559899066764 0 +-2.849130602466123 2.38098989755921 0 +0.493407730134189 2.800033816863435 0 +5.815437281347593 -1.930735082821505 0 +5.139203491433489 2.705700079902202 0 +2.20020994048155 -0.9931412595509284 0 +2.960460250585549 3.83974052864636 0 +5.203531762904726 -2.452223231749342 0 +-6.710413577411138 1.424819248502738 0 +5.663516984421391 1.893497741352336 0 +-4.046937756764009 1.670775250342371 0 +-4.936222604224968 0.1167109662449604 0 +-1.515313547499126 -0.8905451117051859 0 +0.3728488559991253 5.025042873574898 0 +-5.520691446214227 2.023037787486784 0 +-4.524210687552515 -1.929740365210663 0 +-2.572469471773052 1.689866808642451 0 +4.205676745002126 1.552410602933323 0 +-3.968170883953531 -0.6838146791038842 0 +2 -3.4375112159409 0 +2.485104185850116 6.29797422401759 0 +-6.981090753390805 -1.458522380470665 0 +7.056378544358156 -1.5 0 +2.839432598234039 -0.2867602441513615 0 +4.433276462638696 5.230979687257792 0 +4.949015418309571 0.02215201146017209 0 +1.597558224183402 4.288208211454055 0 +-2.919029224661149 4.99715983428454 0 +0.4442670041765457 6.924759953496672 0 +-6.196788722015292 3.085205655499528 0 +2.395579906930914 3.082991570137606 0 +2.76348029821979 1.523859756510349 0 +1.510977347004358 1.689130174277341 0 +-4.135215929166628 -3.380610931273105 0 +6.81351059662588 1.361486016990477 0 +-2.088612228762647 4.366978191357243 0 +-3.861589763516 -2.190451607468654 0 +-2.152395626052333 0.4427251532480296 0 +-4.189159936597349 0.07762741733093481 0 +5.27429051324589 4.36172957633528 0 +-4.694235497317424 -1.203042999761907 0 +4.268354409816118 -0.06800847747299699 0 +0.005396177810134154 -1.706460006925216 0 +2.336784001888911 0.3906090796241535 0 +2 13 0 71 +936 +937 +938 +939 +940 +941 +942 +943 +944 +945 +946 +947 +948 +949 +950 +951 +952 +953 +954 +955 +956 +957 +958 +959 +960 +961 +962 +963 +964 +965 +966 +967 +968 +969 +970 +971 +972 +973 +974 +975 +976 +977 +978 +979 +980 +981 +982 +983 +984 +985 +986 +987 +988 +989 +990 +991 +992 +993 +994 +995 +996 +997 +998 +999 +1000 +1001 +1002 +1003 +1004 +1005 +1006 +7.344716553263265 -2.772671235465964 21.520560458002 +6.944938285925997 -3.382806331293446 22.06232907637581 +7.348874829601803 -2.762667597623568 22.4316280228058 +6.988682308183162 -3.335599110999424 21.24266383432041 +6.27546341420787 -3.843544546037625 1.47967842140395 +6.882810675706266 -3.444934128309239 0.9376840695534332 +6.262941029665901 -3.84876201422799 0.5684175003719544 +6.835619733217383 -3.488663806317708 1.757429665726642 +6.287915994062637 -3.838256888005669 2.390225932501985 +6.896975052796805 -3.431244459155516 2.589068444861339 +7.347680498153554 -2.765556514401801 20.60817891741421 +6.939841487511165 -3.388112564182616 20.40964073249848 +6.296788923781222 -3.834428360808773 22.47478087273897 +7.334431291274422 -2.796782177005269 0.5252259187451491 +7.372318372591293 -2.703152836627353 19.70508728241875 +6.915735334454236 -3.412690151016051 19.50662077713207 +6.296830584257496 -3.834410264905824 20.23615610310974 +6.230674054788309 -3.861750634660617 3.284901277747576 +6.914049404456643 -3.414377701236771 3.499876497866137 +7.334646020341652 -2.796287623942843 2.764622628564833 +7.35207561390955 -2.754861523964205 18.7480811603826 +6.914213562373095 -3.414213562373095 18.5 +6.260266808027412 -3.849863341063823 19.25127713367977 +6.255498755713967 -3.851815765705284 4.252533851391895 +6.914213562373095 -3.414213562373095 4.5 +7.349707114007974 -2.760646825003755 3.749879823876241 +6.256090069068653 -3.851574413156479 18.25239036023227 +6.914213562373095 -3.414213562373095 17.5 +7.351817857897414 -2.755493627486183 17.74738803504506 +7.351817710741661 -2.755493988184892 16.74738790677836 +6.914213562373095 -3.414213562373095 16.5 +6.255568428208345 -3.851787339381812 17.25257749630502 +7.351817710741635 -2.755493988184956 15.74738790677846 +6.914213562373095 -3.414213562373095 15.5 +6.255503284361859 -3.851813918113384 16.25260691821395 +7.351817710741422 -2.755493988185477 14.74738790677919 +6.914213562373095 -3.414213562373095 14.5 +6.255495149103609 -3.851817237116264 15.25261134142513 +7.351817710739725 -2.755493988189637 13.74738790678478 +6.914213562373096 -3.414213562373094 13.5 +6.31941796101297 -3.824432570737912 21.11636270228621 +6.25549413316191 -3.85181765159476 14.25261198630508 +6.255494006289799 -3.851817703355324 13.25261207826074 +6.914213562373095 -3.414213562373095 12.5 +7.351817710726134 -2.75549398822295 12.74738790682673 +7.351817710617298 -2.755493988489722 11.74738790714027 +6.914213562373095 -3.414213562373095 11.5 +6.255493990445848 -3.851817709819249 12.25261209115464 +7.351817709745786 -2.755493990625915 10.74738790946959 +6.914213562373095 -3.414213562373095 10.5 +6.255493988467236 -3.851817710626472 11.252612092939 +7.351817702767067 -2.755494007731697 9.747387926653154 +6.914213562373095 -3.414213562373095 9.5 +6.255493988220143 -3.851817710727279 10.25261209318333 +7.351817646884236 -2.755494144708039 8.747388052356959 +6.914213562373095 -3.414213562373095 8.5 +6.255493988189286 -3.851817710739868 9.252612093216495 +6.255493988185433 -3.85181771074144 8.252612093220966 +6.914213562373095 -3.414213562373095 7.5 +7.351817199396189 -2.755495241560433 7.747388962605266 +7.351813616062157 -2.755504024719127 6.747395471314904 +6.914213562373095 -3.414213562373095 6.5 +6.255493988184951 -3.851817710741637 7.252612093221566 +6.25549398818489 -3.851817710741662 6.252612093221643 +6.914213562373094 -3.414213562373096 5.499999999999999 +7.351784920433125 -2.755574356669472 5.747441273608233 +7.351555027649303 -2.756137540125201 4.747757001214274 +6.255493627486183 -3.851817857897414 5.252611964954944 +6.429060397600735 -3.771114558014236 21.80312340282575 +7.271249497298284 -2.928803110632483 1.19689068240426 +7.32532626364126 -2.817425245060021 1.88319986184455 +2 14 0 302 +1007 +1008 +1009 +1010 +1011 +1012 +1013 +1014 +1015 +1016 +1017 +1018 +1019 +1020 +1021 +1022 +1023 +1024 +1025 +1026 +1027 +1028 +1029 +1030 +1031 +1032 +1033 +1034 +1035 +1036 +1037 +1038 +1039 +1040 +1041 +1042 +1043 +1044 +1045 +1046 +1047 +1048 +1049 +1050 +1051 +1052 +1053 +1054 +1055 +1056 +1057 +1058 +1059 +1060 +1061 +1062 +1063 +1064 +1065 +1066 +1067 +1068 +1069 +1070 +1071 +1072 +1073 +1074 +1075 +1076 +1077 +1078 +1079 +1080 +1081 +1082 +1083 +1084 +1085 +1086 +1087 +1088 +1089 +1090 +1091 +1092 +1093 +1094 +1095 +1096 +1097 +1098 +1099 +1100 +1101 +1102 +1103 +1104 +1105 +1106 +1107 +1108 +1109 +1110 +1111 +1112 +1113 +1114 +1115 +1116 +1117 +1118 +1119 +1120 +1121 +1122 +1123 +1124 +1125 +1126 +1127 +1128 +1129 +1130 +1131 +1132 +1133 +1134 +1135 +1136 +1137 +1138 +1139 +1140 +1141 +1142 +1143 +1144 +1145 +1146 +1147 +1148 +1149 +1150 +1151 +1152 +1153 +1154 +1155 +1156 +1157 +1158 +1159 +1160 +1161 +1162 +1163 +1164 +1165 +1166 +1167 +1168 +1169 +1170 +1171 +1172 +1173 +1174 +1175 +1176 +1177 +1178 +1179 +1180 +1181 +1182 +1183 +1184 +1185 +1186 +1187 +1188 +1189 +1190 +1191 +1192 +1193 +1194 +1195 +1196 +1197 +1198 +1199 +1200 +1201 +1202 +1203 +1204 +1205 +1206 +1207 +1208 +1209 +1210 +1211 +1212 +1213 +1214 +1215 +1216 +1217 +1218 +1219 +1220 +1221 +1222 +1223 +1224 +1225 +1226 +1227 +1228 +1229 +1230 +1231 +1232 +1233 +1234 +1235 +1236 +1237 +1238 +1239 +1240 +1241 +1242 +1243 +1244 +1245 +1246 +1247 +1248 +1249 +1250 +1251 +1252 +1253 +1254 +1255 +1256 +1257 +1258 +1259 +1260 +1261 +1262 +1263 +1264 +1265 +1266 +1267 +1268 +1269 +1270 +1271 +1272 +1273 +1274 +1275 +1276 +1277 +1278 +1279 +1280 +1281 +1282 +1283 +1284 +1285 +1286 +1287 +1288 +1289 +1290 +1291 +1292 +1293 +1294 +1295 +1296 +1297 +1298 +1299 +1300 +1301 +1302 +1303 +1304 +1305 +1306 +1307 +1308 +0.1865762641040005 -4 5.493725981911054 +-0.04536342773729896 -4 11.53843375950134 +0.02725071428533532 -4 17.36136779808201 +2.066723179388088 -4 8.372025681910808 +1.93034311267867 -4 14.44672884941673 +-1.884573037189869 -4 8.538407347636005 +-2.030735702172216 -4 14.65606304151075 +-2.28125 -4 3.21875 +2.28125 -4 19.78125 +2.370541106256629 -4 3.185046901911537 +-2.347319474311035 -4 19.83118477169928 +2.7577880623358 -4 11.57795222632267 +-2.780168379904285 -4 11.64928943428522 +-2.791131522523026 -4 17.14293781891639 +2.790176931156427 -4 17.04269872200421 +-2.77538339991491 -4 5.900047863019823 +2.783129701062428 -4 5.885872191544754 +0 -4 20.62105582524272 +0 -4 2.378944174757282 +0.0242975477616767 -4 13.73476366116381 +0.01618422915651863 -4 7.730231443527164 +3.508673789104519 -4 9.582306732838127 +3.644120056007944 -4 13.46178474070389 +-3.473362388350984 -4 9.567721923275574 +-3.601503182605189 -4 13.4441229748909 +0.4580583464687269 -4 9.601834100500273 +-0.3135056407584598 -4 15.55845009790471 +3.710516693181624 -4 7.729863828693002 +-3.521314213103071 -4 7.661963165494396 +-3.702462552307205 -4 15.27439123563031 +3.527159008246734 -4 15.31688354328285 +3.508669894564974 -4 1.713346469796298 +-3.508669894564976 -4 1.713346469796298 +3.508669894564974 -4 21.2866535302037 +-3.508669894564988 -4 21.2866535302037 +-1.204462831143405 -4 10.46733795300768 +-3.748658323252471 -4 18.70979324370409 +3.833963928779754 -4 18.69338832055072 +3.845955377138624 -4 4.291313802602773 +-3.807448119532369 -4 4.368626265393137 +-1.442735474509611 -4 12.65311930760095 +1.423504750232713 -4 12.77543646107558 +1.433210885652789 -4 16.18262198671975 +0.7207220873786442 -4 19.06052791262136 +-0.7207220873786406 -4 3.939472087378641 +-1.797686658559304 -4 18.35980495724996 +1.590811757995639 -4 4.772920402660047 +1.649372969293383 -4 1.687616157303373 +-1.649372969293391 -4 21.31238384269663 +-1.54788540294531 -4 1.69256422258609 +1.547885402945315 -4 21.30743577741391 +-1.349399346809163 -4 6.701313679528596 +1.262529321994885 -4 6.568353994490358 +1.854381611916805 -4 10.13888765955988 +-1.422109081866419 -4 16.8064886107137 +1.576361643122632 -4 17.80750816646965 +-1.998796181615374 -4 4.656983678680966 +-0.8900710083349592 -4 19.52054761517575 +0.8900710083349601 -4 3.479452384824247 +4.087331351360707 -4 12.01744882728869 +-4.183280336788893 -4 12.07696780238698 +-4.158426547603101 -4 16.79879220195264 +-4.151949403841657 -4 6.20846650238445 +4.158701269996554 -4 6.20024546237363 +4.158701269996556 -4 16.79975453762637 +1.503193235873823 -4 11.41075319530777 +-2.322373927498123 -4 15.81342243075002 +4.062762669080154 -4 19.69195929330755 +4.064761243806633 -4 3.305491060551356 +-4.058343367538924 -4 3.318376471016416 +-4.048545068158946 -4 19.69469344716645 +-2.432508753020671 -4 7.24615404734617 +2.295963574171768 -4 7.261301240381851 +-0.8321906424132441 -4 8.621592272401433 +0.8284463896614795 -4 14.60073715655145 +4.290485906834361 -4 10.66552925887101 +-4.296850684362301 -4 10.66137156569962 +-1.328032457712268 -4 11.51275157771197 +2.459855937540536 -4 18.53466012183382 +4.082073859862108 -4 8.595679652040122 +4.10926053141576 -4 14.47559365613438 +-4.04465487972343 -4 8.581932073246595 +-4.131374976525377 -4 14.46556797722345 +0 -4 1.136927769051897 +0 -4 21.86307223094811 +2.44112390313335 -4 15.65324493946491 +2.606540391764238 -4 1.226673582247674 +-2.589625797372895 -4 1.227498259794793 +2.589625797372896 -4 21.7725017402052 +-2.60654039176425 -4 21.77332641775233 +-1.1514748127657 -4 2.82233940982039 +1.104912682899737 -4 20.17661327040889 +-2.486087385575458 -4 9.462357030803485 +0.8948550575268186 -4 8.573284080684362 +-0.786621470082336 -4 14.49999999999999 +3.037515106976079 -4 14.36771589030303 +3.098547114526065 -4 8.618131591486515 +-3.027211362422011 -4 8.633007116958556 +-3.098547114526061 -4 14.38186840851349 +-1.244760533992028 -4 5.419906818620641 +-0.3505434211581617 -4 12.59938838344006 +-1.085906627558141 -4 7.759908674098363 +-2.691343397785372 -4 18.1475650585586 +2.683199967828633 -4 4.279287471276884 +2.636354795032489 -4 12.70682021121315 +-2.626813344968178 -4 12.64573402823452 +0.2306390332584316 -4 4.306370061043233 +-0.200869522021077 -4 18.59006774462256 +-4.377415050561075 -4 17.76542912175554 +-4.407719635661203 -4 5.209652128706516 +4.380998952918887 -4 5.23411143023637 +4.380553028290795 -4 17.76531968935494 +4.398304981842875 -4 21.89830498184288 +-4.398304981842873 -4 21.89830498184287 +4.398304981842879 -4 1.101695018157122 +-4.398304981842878 -4 1.101695018157122 +-0.09177479131291388 -4 10.59520032081969 +0.3025185008117344 -4 16.45924132310431 +-0.1805703811112771 -4 6.579310820125112 +1.068636236918278 -4 13.73813369565416 +0.7393092014993963 -4 10.51757872194997 +1.179649722690845 -4 7.583636139526324 +-1.355340275171049 -4 15.38958107930834 +2.855865685095003 -4 10.49332031277534 +-2.570565595398903 -4 20.81983499954683 +2.573330075392411 -4 2.182097342549692 +-2.551886383192638 -4 2.178779337079551 +2.550995861213666 -4 20.81944123755689 +0.5930119998920453 -4 12.23729593777127 +-2.869231715925954 -4 10.51569053514004 +-2.361819713515859 -4 13.58491871805709 +2.552251603462409 -4 13.66789096492056 +-4.461202126147715 -4 12.9182934217786 +4.488027323852869 -4 12.94815772708393 +-4.555409806525028 -4 9.643775759223089 +4.555409806525029 -4 9.643775759223093 +1.034236438992034 -4 5.591684770697702 +-4.641828086801576 -4 7.577690669441514 +-4.669161600679746 -4 15.42066182561917 +4.664952725599251 -4 7.586022122706017 +4.649016907907288 -4 15.42602080383993 +-0.9959180988910941 -4 22.11446057217274 +0.994881219121921 -4 22.10504973280776 +-0.9948812191219183 -4 0.8949502671922405 +0.995918098891087 -4 0.885539427827269 +3.25993753310931 -4 3.542192818638164 +-3.238879589209064 -4 3.497594443866893 +3.228126066876921 -4 19.49227211234549 +-3.247342560967303 -4 19.53928216772206 +2.517742049733856 -4 9.438259696015511 +-0.9560790367953071 -4 20.44885511275581 +0.9560790367953045 -4 2.55114488724419 +1.40220563187247 -4 9.302989282507145 +-2.897585937467595 -4 4.962676536351132 +4.525728025695154 -4 2.283317046664068 +-4.525155001028395 -4 2.284467529741306 +-4.524280152869471 -4 20.71669942723931 +4.525549581523144 -4 20.71645530635905 +-1.439154185184831 -4 13.73579177947813 +-3.250061743629446 -4 16.26848298471451 +3.250634881718041 -4 6.737321651505198 +-3.272291677033006 -4 6.683528608295212 +3.273046024961578 -4 16.30089171710881 +-1.501029434674269 -4 9.442183674258017 +1.568068481285161 -4 19.20335510420853 +3.203682586548078 -4 17.801797525255 +3.342011866055845 -4 5.164629516888079 +1.913039518265919 -4 17.03420385896946 +-3.418671959216576 -4 17.75871493576471 +-4.602500071569427 -4 19.09688268693863 +4.56351829691509 -4 19.05473643893846 +-4.563518296915089 -4 3.945263561061537 +4.56351829691509 -4 3.945263561061538 +-0.02872928398866303 -4 3.312370616762315 +0.02872928398866659 -4 19.68762938323768 +-2.054044049553236 -4 11.06662111020766 +-1.943168530662218 -4 17.43168930874907 +-0.9820514309965374 -4 17.67355108039233 +1.910882872439147 -4 5.615157943231168 +3.505845415569475 -4 0.912313203042579 +-3.505845415569476 -4 0.9123132030425788 +3.505845415569482 -4 22.08768679695742 +-3.505845415569486 -4 22.08768679695743 +0.6661302790932968 -4 18.11812326733599 +-1.619459777575614 -4 3.835633733752106 +0.6507495627313507 -4 21.24206402809542 +-0.650749562731348 -4 1.75793597190459 +1.634690809202866 -4 15.23356517640978 +-1.928067721998053 -4 5.94395706853989 +-2.033852444944871 -4 11.99440083838124 +0.6330605465084354 -4 15.4773316369484 +-3.581861592805569 -4 5.566201373314819 +-1.687429712035624 -4 19.15365926255173 +1.68377990998792 -4 3.872693088758129 +-0.5140669479258859 -4 9.592920400331256 +2.006252598984986 -4 11.96997223501821 +0.9864185902052833 -4 17.16051106678019 +-1.850366291989747 -4 22.24003416652434 +1.826478483888026 -4 22.23699745008537 +-1.826478483888025 -4 0.7630025499146248 +1.850366291989741 -4 0.7599658334756633 +-0.5556987616981983 -4 4.89647079595915 +4.675470076647692 -4 11.39418812686776 +-4.69008632849857 -4 11.40209688142874 +-2.671504224018421 -4 4.10940236170366 +-0.7202740209959586 -4 21.2719655167632 +0.7202740209959551 -4 1.728034483236802 +2.098544235192429 -4 10.96451171644945 +2.300628070277253 -4 6.413601404230666 +3.649070075323976 -4 11.23991893629815 +-3.605578911192005 -4 11.31273206257136 +-1.823411110832593 -4 20.48536146153407 +1.824763990462912 -4 2.515584186930499 +-0.767347688893679 -4 16.47363531368168 +0.5416429739069955 -4 6.996620396163404 +-2.840878270670499 -4 15.16835652017355 +-2.226173569123266 -4 16.58829806001835 +2.388623323326718 -4 17.64417367890642 +3.335229970516036 -4 20.35017514315173 +-3.335229970516077 -4 20.35017514315173 +3.352940615300342 -4 2.668808244786894 +-3.33522997051604 -4 2.649824856848271 +1.856008320285071 -4 20.53974475636432 +-2.603023408411925 -4 19.01791535507565 +2.495794944093609 -4 5.136765188068777 +-3.482971964567748 -4 12.47557224483328 +3.289253422703778 -4 12.11637245252306 +-1.854742909908675 -4 2.434666049355047 +-4.696863742514978 -4 13.72133072898216 +4.70475168018136 -4 13.73092268732037 +4.787101725216058 -4 6.599126098764652 +4.784445755600732 -4 16.40288105565967 +-4.782122307723966 -4 6.599107696555704 +-4.787757417330567 -4 16.40182750334392 +2.887972892228994 -4 7.827643184026702 +-2.582070465539529 -4 8.021362422428192 +-0.7338944796410685 -4 13.33707598733617 +0.5688829235773269 -4 6.245939192677526 +2.370119452634012 -4 16.44273224485343 +0.5517814227293103 -4 13.01700362782098 +-0.003256267490225895 -4 14.80125287156841 +0.04494171809264813 -4 8.826618151657819 +-1.227887468451971 -4 4.549693422878301 +-0.6043012402093906 -4 5.947826499003289 +4.796813899918464 -4 12.26360673934324 +-4.822360495533828 -4 12.26938840179791 +-0.6499230315805153 -4 7.192691154319808 +-2.35153017975516 -4 6.495000253345939 +-0.6534315346029747 -4 11.16311726862941 +4.948080467228328 -4 10.5 +-4.948080467228328 -4 10.5 +1.04197396374143 -4 4.267614468442578 +-1.058281450416586 -4 18.72105834137256 +-4.833989366133427 -4 4.592782829686333 +-4.831380421593358 -4 18.41219671048233 +4.834602994562411 -4 4.590031207379974 +4.833955484515201 -4 18.40914274320024 +3.587296022290509 -4 10.41462134943852 +-2.238155041920947 -4 5.351803058687796 +2.557982882556875 -4 14.92305199349563 +4.078473793342576 -4 16.04928633150353 +4.092414573247538 -4 7.000360534257661 +-4.075591921727358 -4 6.966529040820426 +-4.092120299620603 -4 16.00085921175568 +-1.618668908510507 -4 16.21428509889442 +-0.663662550608124 -4 11.8760052867527 +-1.866258770470004 -4 7.779881304739014 +-1.540546406945663 -4 19.86208256939026 +1.542681581387315 -4 3.142359234016395 +-3.619119909930212 -4 10.39383288358159 +-4.906898934265526 -4 22.40689893426552 +4.906898934265516 -4 22.40689893426552 +4.906898934265529 -4 0.5931010657344711 +-4.906898934265529 -4 0.5931010657344707 +1.868960746519098 -4 13.46813587013469 +0.8145681091302022 -4 4.906636404927236 +4.860487278397278 -4 8.565095506793847 +-4.848378554610007 -4 8.56067970038224 +4.919604779875373 -4 14.51893387818496 +-4.942397013756707 -4 14.51097556447192 +3.539868501942395 -4 17.11110129874455 +3.555485192056437 -4 5.879276193240797 +1.160618888306488 -4 9.969414651470894 +4.990612758932784 -4 21.5 +4.990612758932796 -4 1.5 +-4.990612758932797 -4 1.5 +-4.990612758932799 -4 21.5 +0.772060798521693 -4 11.30488414155735 +1.337186385891156 -4 18.50510722552311 +-3.566475689636442 -4 17.11286513355452 +4.851710714528711 -4 17.19798913017088 +4.852153842277769 -4 5.802216337545642 +-4.851696280472521 -4 17.19771677937246 +-4.844250124691609 -4 5.797357308072884 +-4.835065058519569 -4 19.70165511226888 +4.830366109503679 -4 19.69263020772101 +4.830801513283376 -4 3.306814333655392 +-4.829403333096481 -4 3.309621512363852 +1.262891525848173 -4 11.9920724154328 +1.434940722720826 -4 10.71184458690173 +-2.047412621749941 -4 10.21067184983665 +3.760133306720846 -4 12.64649567070175 +2 15 0 71 +1309 +1310 +1311 +1312 +1313 +1314 +1315 +1316 +1317 +1318 +1319 +1320 +1321 +1322 +1323 +1324 +1325 +1326 +1327 +1328 +1329 +1330 +1331 +1332 +1333 +1334 +1335 +1336 +1337 +1338 +1339 +1340 +1341 +1342 +1343 +1344 +1345 +1346 +1347 +1348 +1349 +1350 +1351 +1352 +1353 +1354 +1355 +1356 +1357 +1358 +1359 +1360 +1361 +1362 +1363 +1364 +1365 +1366 +1367 +1368 +1369 +1370 +1371 +1372 +1373 +1374 +1375 +1376 +1377 +1378 +1379 +-6.272671235465964 -3.844716553263265 21.520560458002 +-6.882806331293447 -3.444938285925996 22.06232907637581 +-6.262667597623569 -3.848874829601803 22.43162802280579 +-6.835599110999424 -3.488682308183162 21.24266383432041 +-7.343544546037625 -2.77546341420787 1.47967842140395 +-6.944934128309239 -3.382810675706266 0.937684069553433 +-7.34876201422799 -2.762941029665901 0.5684175003719543 +-6.988663806317708 -3.335619733217383 1.757429665726642 +-7.338256888005668 -2.787915994062637 2.390225932501985 +-6.931244459155517 -3.396975052796805 2.589068444861339 +-6.265556514401801 -3.847680498153554 20.60817891741421 +-6.888112564182615 -3.439841487511166 20.40964073249847 +-7.334428360808772 -2.796788923781223 22.47478087273897 +-6.296782177005269 -3.834431291274422 0.5252259187451491 +-6.203152836627353 -3.872318372591293 19.70508728241875 +-6.91269015101605 -3.415735334454236 19.50662077713207 +-7.334410264905824 -2.796830584257497 20.23615610310973 +-7.361750634660617 -2.730674054788309 3.284901277747576 +-6.914377701236772 -3.414049404456643 3.499876497866137 +-6.296287623942844 -3.834646020341652 2.764622628564833 +-6.254861523964204 -3.85207561390955 18.74808116038261 +-6.914213562373095 -3.414213562373095 18.5 +-7.349863341063823 -2.760266808027411 19.25127713367977 +-7.351815765705284 -2.755498755713967 4.252533851391894 +-6.914213562373095 -3.414213562373095 4.5 +-6.260646825003754 -3.849707114007974 3.749879823876241 +-6.255493627486183 -3.851817857897414 17.74738803504505 +-6.914213562373095 -3.414213562373095 17.5 +-7.351574413156479 -2.756090069068653 18.25239036023226 +-7.351787339381812 -2.755568428208345 17.25257749630501 +-6.914213562373095 -3.414213562373095 16.5 +-6.255493988184893 -3.851817710741661 16.74738790677836 +-6.255493988184956 -3.851817710741635 15.74738790677846 +-6.914213562373095 -3.414213562373095 15.5 +-7.351813918113384 -2.755503284361859 16.25260691821395 +-6.255493988185476 -3.851817710741423 14.7473879067792 +-6.914213562373095 -3.414213562373095 14.5 +-7.351817237116265 -2.755495149103609 15.25261134142513 +-6.255493988189636 -3.851817710739725 13.74738790678478 +-6.914213562373095 -3.414213562373095 13.5 +-7.324432570737912 -2.819417961012969 21.11636270228621 +-7.35181765159476 -2.755494133161911 14.25261198630508 +-7.351817703355324 -2.755494006289801 13.25261207826074 +-6.914213562373095 -3.414213562373095 12.5 +-6.255493988222952 -3.851817710726134 12.74738790682673 +-6.255493988489722 -3.851817710617298 11.74738790714027 +-6.914213562373095 -3.414213562373095 11.5 +-7.351817709819249 -2.755493990445848 12.25261209115464 +-6.255493990625913 -3.851817709745787 10.7473879094696 +-6.914213562373095 -3.414213562373095 10.5 +-7.351817710626472 -2.755493988467235 11.25261209293899 +-6.255494007731696 -3.851817702767068 9.747387926653156 +-6.914213562373095 -3.414213562373095 9.5 +-7.351817710727279 -2.755493988220144 10.25261209318333 +-7.351817710739868 -2.755493988189286 9.252612093216497 +-6.914213562373095 -3.414213562373095 8.5 +-6.255494144708039 -3.851817646884236 8.747388052356959 +-6.255495241560433 -3.851817199396188 7.747388962605265 +-6.914213562373095 -3.414213562373095 7.499999999999999 +-7.35181771074144 -2.755493988185433 8.252612093220966 +-7.351817710741637 -2.755493988184952 7.252612093221565 +-6.914213562373095 -3.414213562373095 6.5 +-6.255504024719127 -3.851813616062157 6.747395471314904 +-6.255574356669472 -3.851784920433125 5.747441273608235 +-6.914213562373095 -3.414213562373095 5.5 +-7.351817710741662 -2.755493988184892 6.252612093221644 +-7.351817857897414 -2.755493627486183 5.252611964954943 +-6.2561375401252 -3.851555027649303 4.747757001214274 +-7.271114558014236 -2.929060397600735 21.80312340282575 +-6.428803110632483 -3.771249497298284 1.19689068240426 +-6.317425245060022 -3.82532626364126 1.883199861844549 +2 16 0 25 +1380 +1381 +1382 +1383 +1384 +1385 +1386 +1387 +1388 +1389 +1390 +1391 +1392 +1393 +1394 +1395 +1396 +1397 +1398 +1399 +1400 +1401 +1402 +1403 +1404 +-7.5 -1.020833333333333 2.486111111111111 +-7.5 -1 8.5 +-7.5 -1 10.5 +-7.5 -1 12.5 +-7.5 -1 14.5 +-7.5 -1 16.5 +-7.5 -1 18.5 +-7.5 -1.020833333333333 20.51388888888889 +-7.5 -1 4.5 +-7.5 -1 6.5 +-7.5 -0.9853670634920642 21.60292658730158 +-7.5 -0.9853670634920635 1.397073412698413 +-7.5 -1.003472222222222 3.497685185185185 +-7.5 -1 5.5 +-7.5 -1 7.5 +-7.5 -1 9.5 +-7.5 -1 11.5 +-7.5 -1 13.5 +-7.5 -1 15.5 +-7.5 -1 17.5 +-7.5 -1.003472222222222 19.50231481481481 +-7.5 -1.297502941895906 22.3207963943595 +-7.5 -1.297502941895903 0.6792036056405069 +-7.5 -0.6361441277538373 22.39336915611032 +-7.5 -0.6361441277538364 0.6066308438896869 +2 17 0 680 +1405 +1406 +1407 +1408 +1409 +1410 +1411 +1412 +1413 +1414 +1415 +1416 +1417 +1418 +1419 +1420 +1421 +1422 +1423 +1424 +1425 +1426 +1427 +1428 +1429 +1430 +1431 +1432 +1433 +1434 +1435 +1436 +1437 +1438 +1439 +1440 +1441 +1442 +1443 +1444 +1445 +1446 +1447 +1448 +1449 +1450 +1451 +1452 +1453 +1454 +1455 +1456 +1457 +1458 +1459 +1460 +1461 +1462 +1463 +1464 +1465 +1466 +1467 +1468 +1469 +1470 +1471 +1472 +1473 +1474 +1475 +1476 +1477 +1478 +1479 +1480 +1481 +1482 +1483 +1484 +1485 +1486 +1487 +1488 +1489 +1490 +1491 +1492 +1493 +1494 +1495 +1496 +1497 +1498 +1499 +1500 +1501 +1502 +1503 +1504 +1505 +1506 +1507 +1508 +1509 +1510 +1511 +1512 +1513 +1514 +1515 +1516 +1517 +1518 +1519 +1520 +1521 +1522 +1523 +1524 +1525 +1526 +1527 +1528 +1529 +1530 +1531 +1532 +1533 +1534 +1535 +1536 +1537 +1538 +1539 +1540 +1541 +1542 +1543 +1544 +1545 +1546 +1547 +1548 +1549 +1550 +1551 +1552 +1553 +1554 +1555 +1556 +1557 +1558 +1559 +1560 +1561 +1562 +1563 +1564 +1565 +1566 +1567 +1568 +1569 +1570 +1571 +1572 +1573 +1574 +1575 +1576 +1577 +1578 +1579 +1580 +1581 +1582 +1583 +1584 +1585 +1586 +1587 +1588 +1589 +1590 +1591 +1592 +1593 +1594 +1595 +1596 +1597 +1598 +1599 +1600 +1601 +1602 +1603 +1604 +1605 +1606 +1607 +1608 +1609 +1610 +1611 +1612 +1613 +1614 +1615 +1616 +1617 +1618 +1619 +1620 +1621 +1622 +1623 +1624 +1625 +1626 +1627 +1628 +1629 +1630 +1631 +1632 +1633 +1634 +1635 +1636 +1637 +1638 +1639 +1640 +1641 +1642 +1643 +1644 +1645 +1646 +1647 +1648 +1649 +1650 +1651 +1652 +1653 +1654 +1655 +1656 +1657 +1658 +1659 +1660 +1661 +1662 +1663 +1664 +1665 +1666 +1667 +1668 +1669 +1670 +1671 +1672 +1673 +1674 +1675 +1676 +1677 +1678 +1679 +1680 +1681 +1682 +1683 +1684 +1685 +1686 +1687 +1688 +1689 +1690 +1691 +1692 +1693 +1694 +1695 +1696 +1697 +1698 +1699 +1700 +1701 +1702 +1703 +1704 +1705 +1706 +1707 +1708 +1709 +1710 +1711 +1712 +1713 +1714 +1715 +1716 +1717 +1718 +1719 +1720 +1721 +1722 +1723 +1724 +1725 +1726 +1727 +1728 +1729 +1730 +1731 +1732 +1733 +1734 +1735 +1736 +1737 +1738 +1739 +1740 +1741 +1742 +1743 +1744 +1745 +1746 +1747 +1748 +1749 +1750 +1751 +1752 +1753 +1754 +1755 +1756 +1757 +1758 +1759 +1760 +1761 +1762 +1763 +1764 +1765 +1766 +1767 +1768 +1769 +1770 +1771 +1772 +1773 +1774 +1775 +1776 +1777 +1778 +1779 +1780 +1781 +1782 +1783 +1784 +1785 +1786 +1787 +1788 +1789 +1790 +1791 +1792 +1793 +1794 +1795 +1796 +1797 +1798 +1799 +1800 +1801 +1802 +1803 +1804 +1805 +1806 +1807 +1808 +1809 +1810 +1811 +1812 +1813 +1814 +1815 +1816 +1817 +1818 +1819 +1820 +1821 +1822 +1823 +1824 +1825 +1826 +1827 +1828 +1829 +1830 +1831 +1832 +1833 +1834 +1835 +1836 +1837 +1838 +1839 +1840 +1841 +1842 +1843 +1844 +1845 +1846 +1847 +1848 +1849 +1850 +1851 +1852 +1853 +1854 +1855 +1856 +1857 +1858 +1859 +1860 +1861 +1862 +1863 +1864 +1865 +1866 +1867 +1868 +1869 +1870 +1871 +1872 +1873 +1874 +1875 +1876 +1877 +1878 +1879 +1880 +1881 +1882 +1883 +1884 +1885 +1886 +1887 +1888 +1889 +1890 +1891 +1892 +1893 +1894 +1895 +1896 +1897 +1898 +1899 +1900 +1901 +1902 +1903 +1904 +1905 +1906 +1907 +1908 +1909 +1910 +1911 +1912 +1913 +1914 +1915 +1916 +1917 +1918 +1919 +1920 +1921 +1922 +1923 +1924 +1925 +1926 +1927 +1928 +1929 +1930 +1931 +1932 +1933 +1934 +1935 +1936 +1937 +1938 +1939 +1940 +1941 +1942 +1943 +1944 +1945 +1946 +1947 +1948 +1949 +1950 +1951 +1952 +1953 +1954 +1955 +1956 +1957 +1958 +1959 +1960 +1961 +1962 +1963 +1964 +1965 +1966 +1967 +1968 +1969 +1970 +1971 +1972 +1973 +1974 +1975 +1976 +1977 +1978 +1979 +1980 +1981 +1982 +1983 +1984 +1985 +1986 +1987 +1988 +1989 +1990 +1991 +1992 +1993 +1994 +1995 +1996 +1997 +1998 +1999 +2000 +2001 +2002 +2003 +2004 +2005 +2006 +2007 +2008 +2009 +2010 +2011 +2012 +2013 +2014 +2015 +2016 +2017 +2018 +2019 +2020 +2021 +2022 +2023 +2024 +2025 +2026 +2027 +2028 +2029 +2030 +2031 +2032 +2033 +2034 +2035 +2036 +2037 +2038 +2039 +2040 +2041 +2042 +2043 +2044 +2045 +2046 +2047 +2048 +2049 +2050 +2051 +2052 +2053 +2054 +2055 +2056 +2057 +2058 +2059 +2060 +2061 +2062 +2063 +2064 +2065 +2066 +2067 +2068 +2069 +2070 +2071 +2072 +2073 +2074 +2075 +2076 +2077 +2078 +2079 +2080 +2081 +2082 +2083 +2084 +7.31170962758546 1.670000695171744 1.270436050623043 +7.12806335996742 2.332533544515483 0.7171260539616384 +7.340400400817165 1.539000310488341 0.5797971301806203 +-7.311711512499126 1.669992442494203 21.7295641380454 +-7.128071056609953 2.332510023969772 22.28289235132401 +-7.340400452900076 1.539000062074189 22.42020322852229 +7.458602554181516 0.7869230831262809 7.441373036822786 +7.411255747476749 1.150342664379996 8.244991252951298 +7.465452638258875 0.719038876496683 9.139975591713789 +-7.128449438092588 2.331353385601907 13.55580353079888 +-6.786022645589165 3.193727704979095 13.23673880807499 +-6.933456459015525 2.859577159465347 14.11011011428075 +-6.528451988335437 3.691790166843055 13.98041210479813 +-3.78251669176241 6.476308167199794 4.265952235563582 +-4.62392347429512 5.905025969787309 3.820541234042727 +-3.857055754283449 6.432194097533822 3.428148786502095 +-4.279373086857741 6.159299147100882 2.869184249210557 +5.768877103361068 4.792708729551215 0.8592827736988353 +6.356715907704142 3.980221459760891 0.9101022083218114 +5.945458246831004 4.571818701041108 1.650265542878604 +6.30419578399609 4.062894967513426 2.109606951540851 +-5.797439838909923 4.758118463659778 22.14890510534371 +-6.35896889533226 3.976621001327233 22.09333076700698 +-5.920024502407889 4.60470519044273 21.26059091454255 +-6.395680417922755 3.917304174020625 20.99225273134387 +-7.463021282167663 0.7438503491378714 5.189358935434769 +-7.412827642631373 1.140169435057875 5.829586866712043 +-6.561915757702284 3.631977641563678 18.21375660131377 +-6.898270681730609 2.943443833603067 17.5147750294565 +-6.613969124454027 3.536299254979538 17.06412047660842 +-6.254309355326357 4.139277048939489 17.45101500756917 +-4.10337647034669 6.277921753463095 19.78091243878665 +-4.490272769169056 6.007283117887725 20.64148047671657 +-4.795134260463544 5.766861141394749 19.95425222359711 +-3.747817465285456 6.496450126561528 20.78056757699874 +5.76653899032631 4.795521668499312 21.52776841258841 +6.289846417617609 4.085074300766503 22.04256411688382 +5.762862379741369 4.799939290466251 22.33630612184281 +6.241949295359045 4.157892374048027 21.04769322668908 +-5.712053757767715 4.860292364495342 0.8538133138548752 +-5.908549532406573 4.619420139270519 1.627908344747639 +-6.263224380108916 4.125775122859858 0.9552775439169796 +5.311912856618846 5.294674853443544 22.08037138349413 +-6.320136042010922 4.038054037587229 2.117438697190372 +7.434539870523244 0.9887451206454784 5.398483649263922 +7.360569672380827 1.439449234265525 6.138811203805863 +7.208541237934568 2.070491057936922 5.50916960551693 +6.697851859779438 3.374726724410307 20.37304882965807 +7.065300006427804 2.516254323229524 20.52528196666069 +6.682747132031654 3.404539729438137 21.24668553660585 +7.21189068932946 2.058793988033539 6.541134792171001 +-6.759040589979313 3.250441555083261 21.27764471073125 +-7.069190771087937 2.505302744573025 20.55239277626927 +-6.734229512507794 3.30153795569111 20.41287260185448 +-7.209957588805523 2.065553574135919 5.675070820661544 +-6.962293922461213 2.788631086619322 4.93442476926338 +-6.924417208679355 2.88139659195766 5.904361562594389 +-6.590332169816193 3.580156685326186 5.154160072417598 +-6.010693600187032 4.485706459931438 18.26637838285541 +-6.726021501257692 3.318227654127911 2.612226188933001 +-7.051366865338712 2.555039203300667 2.451899977293147 +-6.699669068761198 3.371117673574221 1.73291441967205 +0.7830990432938592 7.459005020000472 10.45025198242721 +0.9007551082172431 7.445712876214106 11.27270699723846 +0.01040880166186909 7.499992777119719 10.94578320933899 +-6.987576075910754 2.724661553910811 18.34688127659424 +-7.190790274054073 2.131322414504517 17.53976174693831 +6.731799126991207 3.306490664411505 1.74195486286187 +7.072025750439722 2.497288886996753 2.450697395585965 +6.682362953244883 3.405293726112379 2.564712471135113 +7.456495125898144 0.8066476538472258 17.42804069480152 +7.386415853984921 1.300331047080015 18.05447385036212 +7.278852561979291 1.807845508047498 17.18033568286938 +1.943430971862012 7.243830206293317 18.37923954607869 +1.092144417510581 7.420055294355998 18.80062613918051 +1.428013888058747 7.362796774019458 17.79201706493938 +5.050013865794878 5.545030203279281 21.31895677361607 +5.729484979285848 4.839731590918844 20.72838167450788 +-6.466610205476724 3.799072577672646 19.91835919001021 +-6.759201933746094 3.250106031938507 19.08982242449275 +-6.275012701839803 4.107823705047374 19.07850558668697 +-6.885213666179285 2.973858229818294 19.78560681691314 +-0.07812405411439996 7.499593097773287 10.26379577828285 +0.2650010262094246 7.495316834938197 11.65698276108499 +7.340247020274921 1.539731691349226 2.751139039602654 +7.281730014874771 1.796220473792645 2.030017037053731 +7.432166585722454 1.006429253385776 1.90243142089409 +7.41544258445997 1.123036631894819 21.0217055871491 +7.270201908738061 1.842325760060216 20.96836796968691 +7.353229150712746 1.47648943684278 20.26950071340337 +-7.339049581946479 1.545429142255059 20.24853116264805 +-7.281730779120887 1.796217375598935 20.96998418734517 +-7.432166863329483 1.006427203342194 21.09756975720687 +6.157217569332983 4.282367546567814 19.21483378771169 +6.047846640237997 4.435487686395034 18.26236513883586 +6.482312467608576 3.772217527169716 18.66114556970541 +-7.415442531834142 1.123036979384585 1.978294658195593 +-7.270201198725652 1.842328561915082 2.031633260292497 +-7.333638615342229 1.570905681306585 2.758324883753678 +5.585910941380813 5.004757631989997 19.05407142513884 +-7.318139674274342 1.641594257973581 9.983020739785452 +-7.06151662820939 2.526852371928819 10.3960513657946 +-7.311997275141215 1.668740797226291 10.85978353348947 +-5.739364537463477 4.828011464993289 19.16309387705861 +1.764072238589145 7.289584977009259 19.25438636661924 +-6.626752428710327 3.512285900746376 8.490864281390696 +-7.020638710988922 2.63830098543813 8.365096083416663 +-6.77296494468639 3.221326723269357 7.664174358898915 +-7.106325718178813 2.397943866555339 9.687090278179424 +-7.453360550412826 0.8351146661086756 9.290981806245691 +-7.450063233042514 0.8640357768449851 8.320293767469677 +-7.320027994663338 1.633153439620729 9.08703864973231 +-7.268084533785591 1.850661289849305 8.347047781254846 +-7.03616061531752 2.596621611913174 4.09242596186788 +-7.323093162037898 1.619353741501152 3.830679201560196 +-7.174480237298858 2.185596789119193 3.275562150597539 +-0.1021400003091028 7.499304462437624 3.128791720596308 +-0.8890567358780328 7.447118779795976 2.60500455082434 +-0.1543270229032204 7.498412043226341 2.284924977888457 +7.182416292865857 2.159374028734967 3.24854276321453 +7.318050579077464 1.641991389156471 3.787038648514414 +7.069938659269743 2.503191433782711 4.051523070219632 +-7.167547620413781 2.20822578308939 19.81360504655238 +-7.083686172595203 2.464019116846198 19.06538441358922 +7.357162376479851 1.45676414223764 19.37325333185841 +7.209594428643193 2.066820789153481 19.75755583448922 +-7.289397060604368 1.764848575048974 19.24716842649794 +-7.466627156051812 0.7067382206373291 3.42681372858272 +-7.472586978745777 0.6406589147737382 2.618615913804001 +2.305916974954249 7.136718216702818 0.8205205032852685 +3.148744913733974 6.807011493176314 0.8685788096972644 +2.917937902189509 6.909098233414104 1.556115044097159 +-7.473951373545405 0.6245405238083026 20.39114924338906 +-7.451797284996669 0.8489506601188768 19.59595493426193 +6.689332842645693 3.391581654671119 22.12362748195843 +7.027433023423304 2.620149824208456 21.45519780971107 +7.059203153152466 2.533308280198501 22.29041649917536 +-1.157626862657288 7.410121459655992 3.213280597676521 +-7.05372172681211 2.548530910289064 21.45605204194466 +-6.822646178006561 3.114722961955438 22.09814163863808 +7.469483286426458 0.6758841866738668 19.55111046173061 +7.472587869903622 0.6406485203052052 20.38139128306536 +-6.689454067653643 3.391342547834431 0.8762614885738927 +-7.030607579171742 2.611619625384382 1.535730608912431 +-7.059633976550287 2.532107445812044 0.7065088743786879 +2.65100674340805 7.01585085691002 6.311732402047132 +3.093417706850747 6.832332463437524 7.005951376594398 +2.305112361557938 7.136978142084561 7.002745701824248 +7.053720885390002 2.548533239142248 1.543949771948631 +6.822626588601944 3.114765871217578 0.9020809303646561 +7.473950508092847 0.6245508806964252 2.608857681332026 +7.44022182728618 0.9450392376903152 3.445225445030955 +3.54723542106303 6.60811023421642 6.198118787591731 +-7.25684598048555 1.894250885049476 15.38464151214587 +-6.929312255016185 2.869604793779542 15.19422791113734 +-7.003625191539276 2.683138866409347 15.90421736491034 +-7.244872459470754 1.939541968095096 14.38080969543815 +-5.700945839629799 4.873316789785748 17.13370754972437 +-5.151529176657494 5.450848295636797 16.47750218273632 +-5.092660067059671 5.505888978300942 17.54240585761028 +-5.783872957454507 4.774600885103009 15.8381509406949 +3.456313242935861 6.656117394300238 22.25930765204652 +4.059222219551388 6.306561263660276 22.43501474170104 +-3.227275567366655 6.77013237775143 6.730776893833712 +-3.81126496613625 6.459431813859672 7.193363676683044 +-3.936155514118629 6.38409584582449 5.985944194391196 +7.456146197676189 0.8098665809125096 14.28699735480751 +-5.125920359672269 5.474937485149701 15.66652647869306 +-4.387566570392119 6.08270166869768 16.05350611784062 +-5.386892430237729 5.218370430033447 20.37335312709812 +-5.156885421987369 5.445781187717165 19.19086865207361 +-7.417948793139731 1.106361470025415 14.90571963835019 +-7.445667208556388 0.9011325204586222 14.16085085712976 +-7.464075618960068 0.7331951680459043 22.02281077896331 +7.464075613582286 0.7331952227928359 0.9771892759721967 +-1.753342985003437 7.292173090165869 22.14404178366116 +-2.43385754680514 7.094105823982305 21.53406572291671 +-1.648576031860466 7.316570034324499 21.32923590357652 +-2.342896260083097 7.124664000111768 20.75955964298387 +1.48459682538577 7.35159657938699 21.2127212359551 +2.386271709742195 7.110253675311737 21.50228357561341 +1.720482760975554 7.299995826655377 22.11112014472987 +2.266103478031458 7.149459771678818 20.76662176868467 +-7.282658765025205 1.792451202181399 1.148396780537362 +7.282026348508951 1.795018735172816 21.84995948452815 +7.447683334937886 0.88431495661246 21.79147270432702 +4.751029726753452 5.803250514625835 22.1994056534821 +-7.447683299046544 0.8843152588885776 1.208527327411743 +-2.644298591461953 7.018381933123356 22.25109190130682 +2.616476579676598 7.028801484464037 22.26135945364801 +6.633981179925171 3.498613111562729 4.300229842819722 +6.102934963129052 4.359378950701234 4.292529476966398 +6.309845698622405 4.054114855252172 3.196983584710261 +5.651487564863291 4.930587014159226 3.474304959737999 +6.444263512424098 3.836856497504099 8.234857468174541 +6.888703841974598 2.965764551943463 8.012253933489532 +6.730646803476695 3.308835687496276 8.92582668191177 +7.058012929739022 2.53662245587253 8.952434700162884 +-6.323663839065751 4.032527203937031 3.251525524098232 +-6.13202346168983 4.318366388495246 4.363076547739415 +-6.645359914561034 3.476951481678364 4.267950669197175 +-5.833417386219738 4.713941195873075 3.487124242040274 +7.435855435061958 0.9788023032561467 16.74002738799339 +7.475588647461008 0.6046274670837465 16.04107631787745 +0.4960968292888759 7.483574542688108 21.83107553498352 +-4.442282417861042 6.042857512796629 6.813865785063569 +-3.800349005837639 6.465860146479265 8.159050114524904 +-4.41792165377185 6.060690411259579 7.785441815352882 +7.380788697043373 1.331900225090752 22.41379857312922 +-7.380788670759552 1.331900370743789 0.5862014571532116 +-7.472366663281052 0.6432234833135374 0.6057494847667401 +7.472366663362757 0.6432234823643673 22.39425051592321 +-0.6652464027617586 7.470438221658254 21.87804687321848 +0.749654381170195 7.462440506214595 20.61868818126235 +-0.8658139122375683 7.449856795226059 20.65199387079226 +6.643301297254479 3.480883203139249 16.95759888280377 +6.964809769177547 2.782341617984572 17.51483664434304 +6.569800565894408 3.617695471480915 17.83412446503537 +7.047790520738952 2.564887673131548 16.66175900863706 +-5.99639361375154 4.504804505076745 19.79491594267973 +-6.994462312463602 2.706934975119704 16.74441441981922 +-6.624893582024916 3.515790811018922 14.8793738264248 +-6.122702621092155 4.331571610128506 14.71504970666754 +-6.421119609943991 3.875464224424311 15.54615969991376 +6.455258992138613 3.818328344238298 15.39279715152487 +6.118665611318526 4.337272315276975 14.71139796286652 +6.663019966057039 3.442987791428436 14.71841042888347 +-1.290906306446217 7.388068821280524 5.429713246442358 +-0.3108665981055507 7.493554694414547 5.445263948197481 +-0.7905671025690107 7.458217190209443 6.187914044184195 +-5.439899475514921 5.163089549513207 18.26199060390228 +-2.919131600760064 6.908593973989497 1.679311950985203 +-3.888725602061939 6.413097004713713 1.850742694491962 +-3.374940091952942 6.697744349833657 0.8940257903904711 +5.65619063183584 4.925191116731663 17.62377524810243 +5.522209267670759 5.0749586012155 18.32502940747498 +6.21614406915931 4.196373781189606 17.31274071787279 +-7.147209559493249 2.2731906019268 8.994583074596088 +3.792270462791635 6.470601574586254 0.6057773668650694 +4.464471497225353 6.026482742899245 1.029406060758423 +0.04732718760579575 7.499850674334345 6.232057399972456 +7.369593193497249 1.392514331114411 9.799564808749244 +7.307053807333652 1.690255796242327 8.9510493250355 +-3.095767269812156 6.831268184690145 16.81455088030286 +-2.92492435417478 6.906143462335201 15.92104869280481 +-2.39562169652122 7.107108883868094 16.50639709319088 +4.57379936141617 5.943934673388414 20.55374411969368 +4.183318502730139 6.224937453879811 21.50391095187057 +5.223201624831955 5.382208170105726 20.48199889254509 +-3.58231116442879 6.589161306358257 15.99538757118164 +-4.810052536021905 5.75442391562433 21.39870378300364 +-4.034717221681473 6.322266756557092 21.51841446241272 +1.483834936146228 7.351750395808601 0.902015587837271 +1.251202088456932 7.394896438344556 1.729412117129912 +0.5292779497771033 7.481301013318455 1.575492621115383 +-7.380137841213635 1.335501944845663 16.08718636559132 +-7.45669972124569 0.8047541656769733 15.63615316693804 +-7.223587215158394 2.017371494048681 16.22368270776325 +-0.4202147392658674 7.488218718286995 1.404635393296629 +-1.418154790482083 7.364702097860627 0.9278863575569297 +-0.5428913704688501 7.480325458151568 0.7071267532650181 +-1.152875423801496 7.410862180421016 1.867106243472118 +-7.470421686722366 0.6654320570487662 13.34803578597392 +4.901329697420869 5.676880058375397 1.892800602041905 +4.986301621021967 5.602392002010721 3.119632924020363 +4.188198896865523 6.221654924559415 2.569710607801329 +3.76579974812657 6.486042881218861 1.538199599417845 +-1.834042017180173 7.272296052775745 2.60403614941145 +-2.627055643732359 7.024854350428481 2.613927008843421 +-2.02776195872247 7.22067735318218 1.737977591576445 +-2.198216642313554 7.170623654428931 3.58526682784984 +-4.692966202063568 5.850304968656681 1.428310280907101 +-4.248748616634687 6.180463994931516 0.861405594298145 +2.750356051287007 6.977502532507526 18.38697072608161 +3.358798525805188 6.705853596899421 17.55327404234718 +3.611172754542899 6.573388117009907 18.46395217838555 +4.210600891611827 6.206515941456823 17.60831138051863 +-4.617142211181866 5.910329754059636 2.298645307306287 +-3.666890822354694 6.542469846849194 18.25324186355756 +-3.372158230113209 6.699145383635121 17.52309626426864 +-2.942874187454932 6.898513717954867 18.26969979078798 +-4.24334020499399 6.184178514942915 17.60282999142195 +7.065756412904456 2.514972427979986 7.184908842170493 +7.307314794282042 1.689127140645964 7.459021306513503 +6.939200997489114 2.845608812968865 6.237376235892395 +3.282227317045102 6.743662494464185 21.50791796996703 +-3.272066308823996 6.748598526409681 21.57288706282516 +-0.4099664533369261 7.488786784729442 6.93968346834487 +-1.397872233510004 7.36857877875929 6.899149180092368 +-1.86148227341639 7.265320622364614 6.14199806057607 +3.801280273851584 6.465312697745317 6.888820220926783 +3.621683503269405 6.567602957102861 7.542767299745811 +1.915761088678349 7.251197104692849 7.70798688344146 +1.431313048403695 7.362156135091765 6.967802600711694 +1.820458535382712 7.275708262495978 6.303601538294271 +2.356212723926975 7.120271174583495 8.434987876815054 +1.47594607528399 7.353338233948836 8.371797157634262 +1.875344105096081 7.261754917888746 9.045617405319749 +-7.446164945454747 0.8970103706651852 11.4328407455331 +-7.454785618223561 0.8222964102604092 10.33866604217054 +7.099397295934943 2.418379216432281 15.89081420936823 +6.720171046790226 3.330060224963261 16.13661686918501 +6.856011547910895 3.040576533309506 15.32134745906699 +-6.727816032037073 3.314587672556713 16.1429763694288 +-0.6014762591818732 7.475842849447852 9.708837532855691 +0.4253641045996052 7.487927976317493 9.612142742205315 +6.854923574661037 3.04302855483749 14.14252766827756 +6.797558649355582 3.16910025221215 13.25304134967048 +7.099803046717828 2.417187766354993 13.83873452264003 +-0.02328910753721509 7.499963841077511 8.986031620756593 +-7.363997637253436 1.421808284729631 6.640549718471899 +-7.462867155684344 0.7453950741773565 6.592509668298166 +1.718994561451422 7.300346409431571 4.079078861428027 +1.352313840097075 7.377075794505699 4.860519827479813 +0.9094853065459804 7.444651534973075 4.036875250027024 +0.4211081817876455 7.488168527699647 4.836398003151742 +1.018961899805533 7.430458710385563 6.290864801906444 +0.4710244347119197 7.485194451843206 6.946080224440217 +0.9425461328713697 7.440538071094672 7.625525085947222 +1.13217435665603 7.414052955444175 5.564709917327801 +1.789082783922448 7.283486994034678 5.537133568560901 +2.136363756858101 7.189294116836725 4.852639342663823 +0.432715728332762 7.487506734451292 5.59433561061763 +7.301704202098906 1.713217950247773 10.68326607665312 +7.460429111251442 0.7694137222535211 10.31220302469874 +7.457983975093508 0.7927641687465696 11.26290771361647 +6.241011084264841 4.159300499613296 16.28209034701745 +-6.187358142382068 4.238702539445099 16.43483195513578 +-4.609500633252009 5.91629139850712 19.17261590388661 +-4.803163333612005 5.760175517347125 18.26028246024842 +-6.868799795200303 3.011575895350519 6.804581089712133 +-6.489630052936678 3.759614578121151 6.086585991140011 +-5.400606477495019 5.204176176422052 21.4540901384402 +-6.052270370771483 4.429449554863631 20.46267059837448 +4.998307065542789 5.591683689064057 19.71693609191722 +5.634305044453473 4.950212789976423 19.85059887456505 +-6.909642737985689 2.916648287572848 9.201139233076457 +-7.333455084021501 1.571762237311737 7.578249232346554 +-7.46520958933852 0.7215578890485483 7.391628704501915 +-5.388264858822233 5.216953307360669 4.347127155900743 +4.376927167485729 6.090361940847633 19.64045331931275 +4.312401586949243 6.136219728210329 18.62435075554754 +4.952329952012578 5.632444233758474 18.82238382106809 +3.712484608035306 6.516706072480249 19.48312959632391 +5.153277618210397 5.449195334143544 9.527685409042183 +5.239586390622026 5.366258888202139 10.36296150321025 +4.764592553034007 5.792120320191293 10.00371305374967 +7.218510283518182 2.035462917063894 18.85012039118476 +6.932077836338546 2.862917545257619 19.54704255932423 +6.864100049374217 3.022272408665517 18.58725489105431 +3.023582374795575 6.863523120295112 19.24128882374989 +5.744000524819896 4.82249499438504 9.737562421930726 +4.579141353647126 5.939820238300041 11.77990476280237 +5.175931979059506 5.427681655011572 11.26878166425545 +5.065036867823549 5.531311013456774 12.10897618613336 +-5.093156320249296 5.505429928489205 14.25092489348482 +-4.73481553046811 5.816487074896497 15.12208588833829 +-5.465386953022779 5.136102165429381 14.90353273567516 +7.180108769288292 2.167034393171774 9.725459592875135 +6.817476956762733 3.12602110421685 5.3719264120868 +5.508933567327198 5.089366458683796 4.49567915427831 +4.740617349423632 5.811759384759804 4.142715490741776 +4.350940666621301 6.10895370055634 3.472503327827286 +-3.416234361737636 6.676776376791651 2.618737319310029 +7.444951023882086 0.9070304581418821 4.28642782126048 +-7.444734073529049 0.9088094269072949 18.75400672757503 +7.324471419271106 1.613108312631461 16.1446341469393 +7.422543434864433 1.07510416125644 15.20412375437487 +-7.459615142642694 0.7772656712191945 4.280859705728153 +-5.101481101532913 5.497716850721083 22.21909219245738 +-4.278180637660907 6.160127468773947 22.25331101852477 +7.194088650627796 2.120162372769674 8.150284307552733 +-7.154374682589076 2.250538358066458 6.70514218386959 +-2.450372477566472 7.088418351168668 0.8759515041776392 +-4.398220198627032 6.075002805298874 14.48662932237489 +5.604402869249247 4.984041380160362 11.79043490179291 +3.262763140362367 6.753101264596341 8.769726451087784 +2.640696333385026 7.01973809161331 9.377315573760647 +-3.046495182118367 6.853383624555799 20.99151528704166 +6.44063068270385 3.842951523115239 7.404712113092675 +5.971106130701763 4.538269667604144 7.656204731547633 +-4.779815143333834 5.779564619896258 5.999760533568719 +-4.548712767397185 5.963154547696869 4.947871620272696 +3.864146518360658 6.427936813989477 4.306284698474689 +5.010735366922661 5.580549353125589 4.918069096770786 +4.408952863170607 6.067218032207157 4.979966374639389 +4.290773355703096 6.151362776652697 6.474620849588004 +4.132716153027558 6.258646594792288 5.745726741199254 +4.852217612012806 5.718914603810126 5.843249968055932 +-0.5229026875272235 7.481749312786202 12.97554762857093 +-0.3328043744770867 7.492612444823829 13.9853852545022 +-1.193759438517857 7.404386429877194 13.3835760838959 +2.999901094640965 6.873906707424239 20.90999043860304 +-5.394103663304731 5.210916010599525 1.581716661875997 +2.529012395756167 7.060743325041043 2.279776729923217 +2.067171627268658 7.209493842386958 1.573304520234988 +0.1368132360392077 7.498752038735812 13.35395822010003 +-1.810623851487668 7.278161942992473 13.80479069176837 +-1.83767148455694 7.271379753172453 12.76017646239714 +5.402472940879037 5.202238568450106 1.560676769904279 +7.462326721719658 0.7507861868126942 6.476556768864493 +7.380312552778902 1.334536107901986 6.889559981167197 +-2.622966528951748 7.026382183456777 13.18089412222916 +1.4104146229812 7.366188335311607 9.691508661422198 +0.9704824461393776 7.436945866532533 9.013414459192472 +4.547761857654015 5.963879784676021 13.78837578477376 +4.471816005255918 6.021034928908568 14.8371348890309 +3.865627594814346 6.427046234329565 14.36743035181656 +3.955932432860636 6.371859900110903 13.25610786659818 +5.486688375433378 5.113340461076715 5.557195733513748 +4.672537888057907 5.866633590455717 12.78361931631488 +-1.551903965038635 7.337683155008627 17.87089518447054 +-0.9195906943126783 7.44341003538926 18.22879582090557 +-1.532181574017131 7.341826722569962 19.0390217083042 +-0.503615984829981 7.483072292836929 18.99311078186907 +-0.9218397669246544 7.443131830359873 19.67544456569401 +-7.43036461453128 1.019647828969111 17.63345590893714 +3.776401186528556 6.479876085110402 20.55597775016165 +-4.148811233304477 6.247988904472109 18.7196243452894 +7.446000545087392 0.8983740215290397 18.73590168092883 +-7.098147729896664 2.422044344053765 7.630859831323318 +-5.995935516436629 4.50541421877432 6.17575354421922 +-6.461061289481781 3.808501938237661 6.920435128713756 +5.308391620827375 5.298205205532315 8.77297876847804 +4.670667229857878 5.868123007225712 8.247413653907756 +5.201359314630646 5.403319468632687 7.660826533485353 +6.703703854920202 3.363087067788763 6.928348694805982 +6.565479859686369 3.625530886925756 6.113685661493435 +6.124211192352644 4.329438447589088 6.381277215058851 +2.380367454004541 7.112232475384642 19.01912138594947 +2.382489718944747 7.111521830039094 19.74883031895048 +1.653714418620354 7.31541035223911 20.17590142828383 +-2.461732345064232 7.08448119916092 19.73092709048615 +-2.505013149731453 7.069293396066717 18.96857604946048 +-1.72006574486851 7.300094097566821 20.17662715440142 +0.4920185545373865 7.483843781239086 8.292431238417381 +-5.060620035653381 5.535352279190873 0.7753221388317707 +4.556438543152365 5.957253377394279 9.149015748682451 +6.841631845107414 3.072795745898532 3.25867753090324 +5.078490205570772 5.518961608121742 0.8450567294821052 +7.284694607355936 1.784159319556229 4.732586757165573 +6.987467702503901 2.724939468403815 4.801031401083245 +-7.307757741017643 1.687209767218265 4.829667111270841 +-6.877944588635613 2.990631745243483 3.315830668369518 +-7.26634436284743 1.85748205927147 18.32844035371459 +7.272140061054519 1.834660440628172 15.32788555503215 +5.69197238682927 4.883794666811158 2.480032073112339 +-5.126301900466707 5.47458024192462 3.148644060410753 +-5.332399237747365 5.274041938520335 12.33016370839875 +-5.225567151965723 5.379911517887337 11.32584922397308 +-4.638898659321592 5.893268976429324 11.87186353908487 +4.993111848310199 5.596323263560129 17.74059551414082 +3.403708353881415 6.68317061294397 2.305375573287024 +2.933770761981171 6.902390101707119 2.879455654091895 +6.591313778063965 3.578349155561002 19.42593081320188 +6.230019681588391 4.175746013231801 20.13140617345591 +6.41328499433237 3.888415561828655 13.21918364444453 +6.754663372731022 3.259527990535742 12.45188759592473 +6.163045695629994 4.273975637925022 12.37765909223995 +-5.149379877642532 5.452878769579441 2.235133108173936 +-5.755740074186073 4.808477534356222 2.542898459451804 +3.673729104025029 6.538632461779716 3.198317933769652 +-2.994248324903213 6.876370915593072 7.697735418464208 +-2.446211327950283 7.089855438512672 6.841728895600873 +-2.916888183094495 6.909541470121132 5.983882556216425 +-5.825000681590835 4.72433773765872 11.91632516961752 +-0.1246561526634004 7.498963984685028 18.09234146638332 +0.3216546406500967 7.493099378237837 19.01169821756783 +3.056705762605116 6.848835658771254 4.779469437130979 +3.728142757291586 6.507760873084865 5.216040438086407 +3.077981658053504 6.839300323328857 3.749473000157043 +-3.543042472101609 6.610359297412216 22.27402950935741 +-6.822171183252107 3.115763204482099 12.43495742005239 +-7.07813281720142 2.479926575940566 12.02911260291699 +-6.764236168445946 3.239615572485062 11.62531184000794 +-7.054515014441098 2.546334210394447 11.26255888327246 +-6.696548004550144 3.37731325505282 10.76874188631237 +7.069563071207446 2.504251980576224 14.80638362908643 +-7.459836459926448 0.7751386915591536 16.6358769714222 +-7.308572730888543 1.683675930015146 16.82087289495878 +0.6589328113173605 7.470997761354865 18.08775440809303 +-6.14864056017599 4.294673359146034 13.44146070333906 +6.004815233566467 4.493572522028336 13.82616927211001 +5.554475020316993 5.03962372094133 14.54607499864536 +6.460875221741101 3.808817581493224 13.97278358355833 +5.258906059837002 5.347327094335043 3.753777189332264 +-3.571530300824902 6.59501109250694 5.139886864336987 +-2.79835305440273 6.958392068783916 4.595083150047919 +-3.080727415578818 6.83806395048343 3.496395909778899 +-6.211179203026957 4.203718937784187 5.342803774023547 +-5.803695281600014 4.750486404394159 5.169224581485051 +-3.20238256415226 6.781942635618027 20.19210197783115 +3.032017164355632 6.85980115710746 20.15984404281102 +6.394832580504781 3.918688079869915 5.271075175291076 +-1.986928556125345 7.232020112862909 7.592246245499457 +5.929749761582189 4.592174622661466 5.189434506716468 +7.321302230675921 1.627431610575321 14.47140459537009 +7.328005366701738 1.596977565775589 13.55059534046713 +-1.638325263555957 7.31887220347468 16.98062249445515 +-0.7061087451150725 7.466686710989823 17.23736044987671 +-1.572938927502206 7.333202788028449 8.295607836115227 +-2.42427538086525 7.097386059510264 8.27303316446266 +-0.005711522049052569 7.499997825234077 19.94303531753232 +0.9995918082716714 7.433089278142445 19.60153092987752 +-2.21616831588039 7.165095812038236 9.077869542831651 +-0.517996100363262 7.482090619606827 8.280480069359477 +-0.002963935921015091 7.499999414338901 7.618650902485116 +4.559412296111097 5.954977708948282 16.80932336066884 +3.868787108476325 6.425144847339038 16.78451065160196 +4.296367415692284 6.147456956285062 15.9127755012306 +5.301380006632642 5.305221015685933 13.54028368547921 +-1.62433132081709 7.321990696539611 9.76519552560131 +-1.77865045651793 7.286041624471313 10.62461882561865 +-2.302676826038926 7.137764316284427 10.1016592631057 +7.085900469784026 2.457644102044581 11.20197277457991 +7.025041613730214 2.62655483958717 10.46372111977006 +5.43056881072581 5.17290270466902 6.63437804985926 +5.823614267368304 4.726046642269238 16.80828459398151 +-5.341495137260365 5.264829503281551 5.528810652104625 +-5.448463543247636 5.15405132084474 6.636965549455338 +5.243219966655391 5.36270867950761 16.82425534749418 +-0.9647529068011554 7.437691296956248 10.61609490278779 +-3.118616524322285 6.820867318327193 10.48045256009403 +-2.864941439016268 6.931241631266897 9.617196884287148 +-6.021284965974996 4.471479325516722 7.217353071013118 +-3.528341446033536 6.618217784283165 9.840307931160989 +-2.189550611888816 7.173274574277588 5.372810766689051 +-1.733022622422112 7.297029024895899 4.608211762659139 +1.67119433639249 7.311436896397975 2.37460314670366 +6.537173538413827 3.676324540714822 11.72060034191943 +6.854721479268552 3.043483767273015 11.62852947302006 +6.661194380483814 3.446518449886908 10.77248461240687 +-3.599968605748904 6.579530837196699 12.99596070620605 +-3.128211563131878 6.816472138598383 13.81270495155611 +-3.944287642085536 6.379074775897468 13.72708911458227 +-6.384681634215968 3.935205258903951 12.38236717488108 +-3.504146063197512 6.631060274780902 14.48471953488922 +2.438779023821197 7.092415447008849 5.573609481847817 +3.10873593270303 6.825376246092301 5.623105136732632 +1.689470622378946 7.307235388032774 10.6861545943713 +2.199253406215348 7.170305743498683 10.04655278156517 +2.905690060153999 6.914258114528431 10.37196150670976 +3.401468000602022 6.684311141836567 9.801356942157716 +-0.4527765635812547 7.486320416831727 12.11654363590866 +0.1327899396483101 7.498824363320439 12.47216713924372 +-1.191349660414398 7.404774539891847 12.33475671946627 +1.999962406194574 7.228426548966823 16.03327857963828 +2.649324796273689 7.016486166440392 15.75460641187656 +2.476981266961847 7.079164061039982 16.53780912423166 +2.134201528227073 7.189936288793749 15.31636767321123 +2.448423670559277 7.089091728102059 12.21641555847511 +1.756252918161364 7.291472806467133 12.59966256594666 +1.713968514274328 7.30152805459763 11.73359898431607 +0.998566587071722 7.433227076524968 12.29130656178885 +3.106487118507684 6.826400060247409 11.79974140657813 +3.083788840990515 6.836683873354272 12.70482345700817 +3.87666949832786 6.42039201301092 12.06641975691184 +-1.666712996957817 7.312459763019 11.56843137955715 +-2.459829999255312 7.085141944574125 12.08828933275659 +-3.149243380801889 6.806780893232533 12.30044379240342 +-3.195556406251446 6.785161697002168 11.4928157022688 +-3.953606527361749 6.373303337108833 12.0189809342942 +2.2383466953576 7.158198381672704 14.42057960282596 +3.207029549546129 6.779746416226639 13.83720648401713 +3.10447283017526 6.827316342949374 15.02196837973717 +7.092625517354149 2.438168015247677 12.90959740010303 +7.34139116027414 1.534267197019058 12.62885156445017 +7.462682705936234 0.7472394733418846 13.310779293323 +4.366383800752804 6.097925262294011 1.699229539459063 +1.596613862279903 7.328084618423538 14.02220109546732 +0.6724881351565328 7.469789803473301 13.95900547639999 +1.378657336022618 7.372198040600308 13.24963396183764 +1.283110413742825 7.389426748141206 14.83001541757496 +0.7269315384517697 7.464688241206336 13.13455833052901 +2.536894240994985 7.057915245311924 11.08004502847232 +-1.077543676912512 7.422189678548095 8.984878135371613 +-0.966509467731799 7.437463240163597 7.597182982708012 +-1.023493785266711 7.429835830724689 16.42174074850122 +-1.84828509426113 7.26868916726614 16.2042964966003 +-1.180847065962774 7.406456656648111 15.67491764900548 +-3.402654886700049 6.683707034424555 19.19461130850475 +5.57568259245388 5.016150279667345 16.09471223072389 +-1.616034902008999 7.323826267429394 14.89075652758549 +-0.5217114617755144 7.48183247277377 15.0846922606486 +-1.037198409178238 7.42793507376028 14.27684585434711 +-2.4444914327212 7.090448620175782 14.40026717869025 +2.225364084764673 7.162245087278115 3.263078201863584 +0.2167687350512204 7.496866766556832 17.18943856551297 +0.7233671578859036 7.465034491205788 16.58987118129638 +0.8696766890006314 7.449406852670144 17.3345252872463 +1.495634051992494 7.349359072907005 16.79500113313382 +-4.695537735443684 5.848241220659797 9.703202527472587 +-5.243643680117991 5.36229437423559 10.24536146743014 +-5.162244172502037 5.440701710576382 9.120835129462096 +-5.687231980678604 4.889314103015526 9.658994404529411 +-3.984922499926119 6.353769957244484 9.175917108271678 +-4.149000852178067 6.247862988944754 10.2693587551798 +0.292686966526191 7.494286779916131 14.62682721878774 +0.4193469868082295 7.488267363326102 15.33648018766087 +-0.1245022597658324 7.498966541285085 16.15876992060409 +-6.557718788682412 3.63955001182312 9.439719877266691 +-6.176869979371633 4.253971939016227 9.103062496190544 +-6.221279588487797 4.188756412333509 10.25012077975923 +-6.791688456165002 3.181661187869482 9.987458794802491 +3.918689185846961 6.394831902773213 8.309486035934787 +3.942441632861623 6.380215824835346 9.190687983969571 +2.300642153802902 7.138420391105104 13.33963097672213 +-3.711492265977727 6.517271297068085 10.89678242076235 +-2.529227596814122 7.0606662407675 11.1041832061193 +-4.249552122421563 6.179911549433567 11.19688173365806 +-4.719705556182204 5.82875453788739 10.75635414073137 +-7.282342094273767 1.793737333604994 11.61235357025443 +-7.326176772197891 1.605345415325963 12.28695259608757 +0.2991725872153392 7.494030675348139 0.774487169307024 +4.127118462889556 6.262339274845794 10.15683419623123 +4.150254334297623 6.247030411374976 11.15196886223772 +3.479082175749748 6.6442446684616 10.93558127015896 +4.720114644590861 5.828423263792608 10.84846795594971 +-3.087227380043871 6.835131827836786 8.803593620190645 +-4.556822280044429 5.956959854497149 8.620210264879168 +-5.720005764284649 4.850931256630049 8.637315458034202 +-5.142693053717362 5.459185667775663 8.206864310972708 +-6.109633319098375 4.349986288043097 8.181404108971504 +6.212295874824417 4.202068533905596 10.46754073164504 +6.179834701174843 4.24966387684429 11.31314143463249 +5.731286438338573 4.837598139750384 10.83703903551344 +-6.271883576821325 4.112599712930854 11.24078963307725 +-5.711861041813408 4.860518844631121 10.77798488781408 +1.080490214432453 7.421761306894456 3.251255982404093 +-5.013633431264916 5.577945842055371 7.335628442993513 +-5.578367164412837 5.013164647106723 7.713801308785221 +6.827166437216903 3.104802479794659 9.772789966701163 +-7.457457597823398 0.7977005557639192 12.42008960153221 +5.861371606412203 4.679136981489731 15.40252993136075 +5.123032694235686 5.477639638913118 15.29313439202211 +4.9495605481016 5.634878027133879 14.390483285413 +7.458609826647739 0.7868541502932996 12.36487776800383 +5.019595369465558 5.572581298360745 16.0059145679578 +5.997247407574035 4.503667786631972 8.796133864668445 +-4.589436714833923 5.931869068053881 16.89560968274761 +-2.184215683470953 7.174900824964727 18.32320131500353 +-2.379836653557287 7.112410105047743 17.44350692140258 +2.35670046846051 7.120109753505069 17.45352777894985 +-6.427620436822481 3.864672757186819 7.798711252656826 +4.81447275835313 5.750726220146078 6.87227947768937 +7.129710846992488 2.327492908319519 12.09996329155887 +-7.123469903006238 2.346524353371239 12.83261698279186 +-0.06524689699631533 7.499716184125393 21.01130270872673 +5.897340089892689 4.633722031385191 13.12178278978829 +7.15629318577864 2.24443040417345 18.07701501244921 +7.347749042755904 1.503523862357929 11.60279535928366 +0.6799337152152765 7.469115753749807 2.426642885451327 +-5.766867633794495 4.795126452377819 14.03766204560491 +-5.356536117054527 5.249525771599793 13.26506549579339 +-3.924137914335768 6.391489781676298 15.24247087655715 +-7.344739722170928 1.518156254660407 13.27624939523803 +-3.889933269082506 6.412364553118069 16.79365762875939 +-5.85392075509215 4.688455160615419 12.72993821729179 +3.078987096575113 6.83884774352551 16.83870975366448 +3.378028530421025 6.69618721719021 15.99491308239339 +-0.7187773886138602 7.465477818975651 11.44813088400591 +-3.066208375504418 6.844586634559208 15.16618684897574 +-2.231669580283263 7.160282877403541 15.53900651116086 +-0.6204954111608566 7.474288290180431 4.633630694499611 +-1.266295144351072 7.392326873684151 3.970448601072762 +-0.4453758705796007 7.486764343420024 3.733920657533361 +3.891368846840963 6.411493468594944 15.32360951015216 +2.570012533879794 7.045923330245708 4.164947800861388 +6.379028353266963 3.944362720163574 9.683534107819689 +-4.945769850940327 5.638205439812361 6.730107736870107 +4.340132154139352 6.116637383775966 7.447814295147681 +5.476285022696173 5.124480690781612 12.64467382769209 +1.126778105338006 7.414874988921317 15.88127991875842 +-2.890102848008178 6.920787926814043 5.3112535773929 +0.2138212315781756 7.496951412469364 3.946755116653398 +5.653488528707163 4.928292549735306 8.247207855958312 +-4.525722584209161 5.980621630798855 12.8215956843108 +6.447209951841147 3.831903422175523 8.900324613621544 +2.924390118257947 6.906369700228571 7.851833223350096 +-4.618585431813195 5.909202028111996 13.66530551441999 +2 18 0 25 +2085 +2086 +2087 +2088 +2089 +2090 +2091 +2092 +2093 +2094 +2095 +2096 +2097 +2098 +2099 +2100 +2101 +2102 +2103 +2104 +2105 +2106 +2107 +2108 +2109 +7.5 -1.03188775510204 1.42984693877551 +7.5 -0.9999999999999991 3.5 +7.5 -0.9999999999999991 5.5 +7.5 -0.9999999999999991 7.5 +7.5 -0.9999999999999991 9.5 +7.5 -0.9999999999999991 11.5 +7.5 -0.9999999999999991 13.5 +7.5 -0.9999999999999991 15.5 +7.5 -0.9999999999999991 17.5 +7.5 -0.9999999999999982 19.5 +7.5 -1.031887755102038 21.57015306122449 +7.5 -1.005314625850339 20.51169217687075 +7.5 -1.005314625850339 2.488307823129252 +7.5 -0.9999999999999991 4.5 +7.5 -0.9999999999999993 6.5 +7.5 -0.9999999999999993 8.499999999999998 +7.5 -0.9999999999999993 10.5 +7.5 -0.9999999999999993 12.5 +7.5 -0.9999999999999993 14.5 +7.5 -0.9999999999999993 16.5 +7.5 -0.9999999999999991 18.5 +7.5 -0.7353908660507087 0.7105553383369174 +7.5 -0.7353908660507069 22.28944466166308 +7.5 -1.35345572423055 0.6280804554224856 +7.5 -1.353455724230549 22.37191954457752 +2 19 0 182 +2110 +2111 +2112 +2113 +2114 +2115 +2116 +2117 +2118 +2119 +2120 +2121 +2122 +2123 +2124 +2125 +2126 +2127 +2128 +2129 +2130 +2131 +2132 +2133 +2134 +2135 +2136 +2137 +2138 +2139 +2140 +2141 +2142 +2143 +2144 +2145 +2146 +2147 +2148 +2149 +2150 +2151 +2152 +2153 +2154 +2155 +2156 +2157 +2158 +2159 +2160 +2161 +2162 +2163 +2164 +2165 +2166 +2167 +2168 +2169 +2170 +2171 +2172 +2173 +2174 +2175 +2176 +2177 +2178 +2179 +2180 +2181 +2182 +2183 +2184 +2185 +2186 +2187 +2188 +2189 +2190 +2191 +2192 +2193 +2194 +2195 +2196 +2197 +2198 +2199 +2200 +2201 +2202 +2203 +2204 +2205 +2206 +2207 +2208 +2209 +2210 +2211 +2212 +2213 +2214 +2215 +2216 +2217 +2218 +2219 +2220 +2221 +2222 +2223 +2224 +2225 +2226 +2227 +2228 +2229 +2230 +2231 +2232 +2233 +2234 +2235 +2236 +2237 +2238 +2239 +2240 +2241 +2242 +2243 +2244 +2245 +2246 +2247 +2248 +2249 +2250 +2251 +2252 +2253 +2254 +2255 +2256 +2257 +2258 +2259 +2260 +2261 +2262 +2263 +2264 +2265 +2266 +2267 +2268 +2269 +2270 +2271 +2272 +2273 +2274 +2275 +2276 +2277 +2278 +2279 +2280 +2281 +2282 +2283 +2284 +2285 +2286 +2287 +2288 +2289 +2290 +2291 +0.1301889832018032 1.832594838063379 23 +-3.432664547395952 -0.00544928457710725 23 +3.537550715069915 0.08407582708841366 23 +-2.80679897625977 3.200540829432708 23 +3.150500324607647 3.080966895810907 23 +-0.6241760758069982 -1.138139072431871 23 +-0.2886416802904335 4.58764419279292 23 +-5.163546008855615 -1.663546008855614 23 +4.97811271622116 -1.62746374002678 23 +1.638200311388427 -1.561271288254504 23 +-4.781277195225828 1.95402142854649 23 +4.917436269873056 1.777431335630766 23 +1.999737849900705 5.160724559849696 23 +-3.134763569463326 -2.00682948939458 23 +-1.815667943821948 1.32072628029588 23 +2.058637309691473 1.239522055914013 23 +-5.701604820134675 0.1369700548937232 23 +-2.241272146287418 5.080564993816347 23 +5.77957611002333 0.02087131136300568 23 +3.324292098145807 -2.084562424760275 23 +1.279783306694859 3.305154989775997 23 +0.7443985880669867 0.04712323235730187 23 +-1.019388591713848 3.139909467850994 23 +-4.476274232281479 3.657938526358835 23 +4.694377003069922 3.55007590276601 23 +3.576797163455762 4.72107803875927 23 +0.1906827289498701 -2.441496097035845 23 +-1.61865583811621 -2.408901548408036 23 +0.6344133166525168 5.955206786196072 23 +-5.915586564582006 -2.650035203591056 23 +-1.954378961906878 -0.2230004400785468 23 +-0.9831690486637368 5.953558071550945 23 +-3.316425546497356 1.771421784879409 23 +5.92252690415239 -2.647766749799386 23 +-0.6366410307619104 0.4187863174905204 23 +-6.330293296657946 -1.374681797688576 23 +-3.584521497692433 4.833761210385719 23 +3.461726192079957 1.616843957899501 23 +2.155590034049632 -0.2244948193923277 23 +6.356746822981361 -1.440123210477509 23 +-4.39765766935898 -2.696863892751748 23 +-6.010335692529914 1.464696310954716 23 +6.146759574307818 1.322000253495747 23 +4.638062348776621 -3.005219250253538 23 +2.18123426074374 -2.629736170055301 23 +-4.606513706921477 -0.5514140676891079 23 +4.636342718293966 -0.8254292457711214 23 +-5.519410525348552 2.965404550858607 23 +-4.478163851902108 0.9117041470469031 23 +5.904429128098732 2.8195392926402 23 +4.581072468644537 0.7832493265263605 23 +0.5688053154642345 -1.070036451306887 23 +2.862773054481021 5.584493710691341 23 +-1.393503808874899 4.192046267547251 23 +-2.254766438042155 -1.258022423477422 23 +2.935969522102541 -1.23265118821486 23 +0.06544211347635015 3.535893851446616 23 +0.6853439014138308 4.317982321746984 23 +1.962089129361659 2.188622142356387 23 +1.730028294970038 6.005433223582522 23 +2.173541078042718 3.83843630336227 23 +-6.596068027622548 -0.5607221576473482 23 +-3.889994892646373 -1.499088116587051 23 +6.638831115303072 -0.6190633293265475 23 +-1.993487310821676 2.444266333648934 23 +-0.9139631639099509 2.101374071648819 23 +-1.995719627254403 6.117935340308178 23 +-3.858801392730958 2.672614524885021 23 +0.9996503150566862 1.097389188200617 23 +4.214114837518977 -1.533702566720344 23 +1.097546505263442 -3.076127826249699 23 +-5.064706203663378 -3.214248197829207 23 +-2.54496712308193 -2.876968171890731 23 +4.104362917354352 2.522862800945838 23 +4.527141886227392 4.490125123771155 23 +-0.7851318543128935 -3.016381969969165 23 +-2.856855440885527 0.8534608313345518 23 +-3.044274377882658 5.714031722896463 23 +-5.500427286156738 -0.8477006371618638 23 +2.987100583199964 0.7681535151773519 23 +-2.792799509843921 4.233197899348349 23 +-6.471546818560821 0.6248079143190794 23 +-3.227147172336076 -0.9793147708501229 23 +1.023532633907625 2.230987310638355 23 +3.807335470468254 -3.067945424364256 23 +5.597476335762297 -0.9231198628648074 23 +-0.3418508210840385 6.566885833510432 23 +6.554495903332596 0.5333696705198969 23 +-4.580524600836856 4.689410845266069 23 +-6.644018268027161 -2.158115373276575 23 +3.790573138280918 3.706386565310668 23 +6.656078639667447 -2.371056903560235 23 +-0.1469225247385021 -0.3241556738616271 23 +5.551098645783513 3.670793406078013 23 +-0.6842254454380616 -2.040167968550323 23 +-2.015765071046122 3.596156498197582 23 +-0.2486592881211667 2.597400989835329 23 +1.38276102806726 -0.6460314765818342 23 +2.495471143410407 -1.784221726359719 23 +-3.648036066690307 3.837223975709549 23 +-3.436920620247854 -3.015838491871027 23 +-5.42657976034877 3.65866839731901 23 +-6.280133971501158 2.272737874157786 23 +3.765254695033498 5.528455339491869 23 +-1.290390815088513 5.09145395370932 23 +6.429903637825869 2.069038068056301 23 +-0.2497133456554992 5.519039534943821 23 +5.435478965214344 -3.250995810466693 23 +0.1305722358709443 0.821262369570142 23 +1.643159484269455 0.4566248905730901 23 +2.925008106076378 -3.232067556934969 23 +-1.076589012674488 -0.2647258170790039 23 +-5.320869689627463 1.015191919261352 23 +5.445700523455519 0.8964857890239406 23 +2.530846579735291 4.57209728424054 23 +-1.420494415088495 0.5179989937550675 23 +-5.153990006472582 -2.366304215520626 23 +-3.722121472705622 0.8723887394023894 23 +0.1075753495813045 -3.271584329950448 23 +1.131511624528363 6.681610879324531 23 +1.168977991648729 5.121026036324854 23 +2.847105352293081 2.245028560873715 23 +-5.772621201057512 -3.370559330467212 23 +-1.288270136307341 6.674927907174991 23 +1.019873148831536 -2.128127606595947 23 +3.840246852302103 0.7894541253586573 23 +3.703204530163913 -0.861143715060555 23 +-1.803464902716649 -3.22265723929245 23 +-1.413641156000675 -1.622819192058742 23 +4.166858833216137 -2.314177506497192 23 +-5.818055085359394 -1.943378175081572 23 +-3.83911506603394 5.612221301325736 23 +-0.6590229918507076 3.863873444909445 23 +-0.7543342224182592 1.168790478470635 23 +6.258322067804891 -3.135456585553667 23 +-2.305338518395528 -2.094404813623515 23 +-4.781801657570298 2.885180985601395 23 +-6.496291893487515 -2.988342710939026 23 +-2.714581368558814 -0.2555598990667582 23 +-2.84913060246611 2.380989897559232 23 +0.4934077301341976 2.800033816863442 23 +5.815437281347594 -1.930735082821506 23 +5.139203491433494 2.705700079902193 23 +2.200209940481552 -0.9931412595509275 23 +2.960460250585558 3.839740528646353 23 +5.203531762904728 -2.452223231749343 23 +-6.710413577411133 1.424819248502746 23 +5.663516984421396 1.893497741352332 23 +-4.046937756763996 1.670775250342402 23 +-4.936222604224961 0.1167109662449686 23 +-1.515313547499122 -0.8905451117051841 23 +0.3728488559991537 5.025042873574898 23 +-5.520691446214217 2.023037787486799 23 +-4.524210687552514 -1.929740365210661 23 +-2.572469471773043 1.689866808642474 23 +4.205676745002129 1.552410602933319 23 +-3.96817088395353 -0.6838146791038824 23 +2 -3.4375112159409 23 +2.485104185850137 6.297974224017587 23 +-6.981090753390805 -1.458522380470663 23 +7.056378544358155 -1.5 23 +2.839432598234041 -0.2867602441513628 23 +4.433276462638706 5.230979687257776 23 +4.94901541830957 0.0221520114601681 23 +1.597558224183421 4.288208211454061 23 +-2.919029224661116 4.997159834284552 23 +0.4442670041765798 6.924759953496671 23 +-6.196788722015283 3.085205655499548 23 +2.39557990693092 3.082991570137604 23 +2.763480298219793 1.523859756510346 23 +1.510977347004361 1.689130174277343 23 +-4.135215929166628 -3.380610931273105 23 +6.813510596625878 1.361486016990471 23 +-2.088612228762617 4.366978191357259 23 +-3.861589763515998 -2.190451607468653 23 +-2.152395626052332 0.442725153248039 23 +-4.189159936597346 0.07762741733093925 23 +5.274290513245902 4.361729576335261 23 +-4.694235497317422 -1.203042999761905 23 +4.268354409816119 -0.0680084774730032 23 +0.00539617781013745 -1.706460006925217 23 +2.336784001888913 0.3906090796241528 23 +2 20 0 262 +2292 +2293 +2294 +2295 +2296 +2297 +2298 +2299 +2300 +2301 +2302 +2303 +2304 +2305 +2306 +2307 +2308 +2309 +2310 +2311 +2312 +2313 +2314 +2315 +2316 +2317 +2318 +2319 +2320 +2321 +2322 +2323 +2324 +2325 +2326 +2327 +2328 +2329 +2330 +2331 +2332 +2333 +2334 +2335 +2336 +2337 +2338 +2339 +2340 +2341 +2342 +2343 +2344 +2345 +2346 +2347 +2348 +2349 +2350 +2351 +2352 +2353 +2354 +2355 +2356 +2357 +2358 +2359 +2360 +2361 +2362 +2363 +2364 +2365 +2366 +2367 +2368 +2369 +2370 +2371 +2372 +2373 +2374 +2375 +2376 +2377 +2378 +2379 +2380 +2381 +2382 +2383 +2384 +2385 +2386 +2387 +2388 +2389 +2390 +2391 +2392 +2393 +2394 +2395 +2396 +2397 +2398 +2399 +2400 +2401 +2402 +2403 +2404 +2405 +2406 +2407 +2408 +2409 +2410 +2411 +2412 +2413 +2414 +2415 +2416 +2417 +2418 +2419 +2420 +2421 +2422 +2423 +2424 +2425 +2426 +2427 +2428 +2429 +2430 +2431 +2432 +2433 +2434 +2435 +2436 +2437 +2438 +2439 +2440 +2441 +2442 +2443 +2444 +2445 +2446 +2447 +2448 +2449 +2450 +2451 +2452 +2453 +2454 +2455 +2456 +2457 +2458 +2459 +2460 +2461 +2462 +2463 +2464 +2465 +2466 +2467 +2468 +2469 +2470 +2471 +2472 +2473 +2474 +2475 +2476 +2477 +2478 +2479 +2480 +2481 +2482 +2483 +2484 +2485 +2486 +2487 +2488 +2489 +2490 +2491 +2492 +2493 +2494 +2495 +2496 +2497 +2498 +2499 +2500 +2501 +2502 +2503 +2504 +2505 +2506 +2507 +2508 +2509 +2510 +2511 +2512 +2513 +2514 +2515 +2516 +2517 +2518 +2519 +2520 +2521 +2522 +2523 +2524 +2525 +2526 +2527 +2528 +2529 +2530 +2531 +2532 +2533 +2534 +2535 +2536 +2537 +2538 +2539 +2540 +2541 +2542 +2543 +2544 +2545 +2546 +2547 +2548 +2549 +2550 +2551 +2552 +2553 +-0.1865762641040005 -2.000000000000001 16.00627401808894 +0 -2.000000000000001 10 +1.146268209805598 -2 5.852185452941882 +1.932106662011714 -2 13.11928119684676 +-2.013065949378513 -2.000000000000001 12.98662270017578 +-2.033964768339769 -2.000000000000001 7.174722490347492 +2.28125 -2 18.28125 +-2.370541106256629 -2.000000000000001 18.31495309808846 +2.605279195057702 -2 8.433240816976767 +-1.241028468462053 -2.000000000000001 4.374783206398554 +-2.757193767389408 -2.000000000000001 10.00006335331666 +2.77538339991491 -2 15.59995213698018 +-2.783129701062428 -2.000000000000001 15.61412780845525 +2.985730088495575 -2 4.014269911504428 +3.054742693297788 -2 10.79616246296426 +0 -2.000000000000001 19.12105582524272 +-0.0765301124811133 -2.000000000000001 7.691580334026867 +-3.296815229315806 -2.000000000000001 5.364295001132589 +3.078761433961718 -2 6.436886866234282 +0.8012536422474295 -2 3.691880810390835 +-0.001902850297474501 -2.000000000000001 13.90102607744517 +-3.689106584517253 -2.000000000000001 11.97298747963796 +-3.016796363092507 -2.000000000000001 3.410589060630496 +0.3011988855911145 -2.000000000000001 11.98078686740864 +-3.602028573890941 -2.000000000000001 8.333357396850808 +3.605617634932939 -2 13.85538090508228 +-3.710516693181624 -2.000000000000001 13.770136171307 +-3.508669894564974 -2.000000000000001 19.7866535302037 +3.508669894564976 -2 19.7866535302037 +-1.467575769745764 -2.000000000000001 11.28933161682972 +3.807448119532369 -2 17.13137373460686 +-3.845955377138624 -2.000000000000001 17.20868619739723 +-0.5981805327960767 -2.000000000000001 5.977971049766662 +-1.343774227356338 -2.000000000000001 8.846790390203392 +0.7207220873786406 -2 17.56052791262136 +-1.590811757995639 -2.000000000000001 16.72707959733995 +-1.649372969293383 -2.000000000000001 19.81238384269663 +1.54788540294531 -2 19.80743577741391 +1.823900653394102 -2 9.889427113073324 +1.323061482260883 -2 14.94191038333954 +-1.433912847407107 -2.000000000000001 14.80378233763635 +3.874554712586284 -2 12.27532992337308 +3.868713860907892 -2 9.404241914151353 +3.964537517331878 -2 7.817234572026283 +-3.887016669446032 -2.000000000000001 6.798976816605045 +-0.5496522834455133 -2.000000000000001 3.046364853899398 +1.743139205274306 -2 7.250956475500651 +4.037400253426991 -2 2.984916656404597 +4.043018909788485 -2 5.108693392650483 +1.784013784652239 -2 11.50186497769748 +2.180468809489246 -2 2.930448329989662 +1.998796181615374 -2 16.84301632131903 +-0.8900710083349601 -2.000000000000001 18.02054761517575 +-4.137596178561774 -2.000000000000001 10.48048110233633 +-4.158701269996554 -2.000000000000001 15.29975453762637 +4.216869229794367 -2 15.30550438489434 +2.457019594518446 -2 5.296289506022877 +-4.091692833481508 -2.000000000000001 4.236162389217494 +-1.837313226634802 -2.000000000000001 5.617146118736297 +-0.2769068252740201 -2.000000000000001 4.89694293991559 +1.175823898767274 -2 8.635925469092477 +4.058343367538924 -2 18.18162352898359 +-4.064761243806633 -2.000000000000001 18.19450893944864 +-3.87389422127896 -2.000000000000001 2.862121759973505 +-2.011284998863244 -2.000000000000001 2.858416708166875 +2.40246130460209 -2 14.09965253770062 +-2.343056860270408 -2.000000000000001 14.32209936405576 +-0.6809984370008602 -2.000000000000001 12.76086304915419 +4.627616155071631 -2 10.96645752494049 +-4.147317900323124 -2.000000000000001 12.96966955062742 +0 -2.000000000000001 20.3630722309481 +-4.254933876286451 -2.000000000000001 9.376414478233105 +1.623533028105346 -2 4.24278693506157 +-1.20546666717904 -2.000000000000001 10.04598828940951 +-2.606540391764238 -2.000000000000001 20.27332641775233 +2.589625797372895 -2 20.27250174020521 +1.1514748127657 -2 18.67766059017961 +-2.56637102951187 -2.000000000000001 4.471366333066022 +-2.531435472729745 -2.000000000000001 8.893135334372147 +-2.683806656481801 -2.000000000000001 11.19846383420438 +0.7951990491102103 -2 13.08305749652089 +0.5410369380631863 -2 10.78823861634934 +0.3656491809566438 -2 6.650530196866683 +-0.8778732833646155 -2.000000000000001 7.173568110497348 +2.726620909816249 -2 12.13974768168135 +-3.139703992229631 -2.000000000000001 12.893448395596 +-0.2285030303166815 -2.000000000000001 8.884312390857126 +1.282367392514566 -2 16.09295091642602 +4.589202228848388 -2 4.052727230447083 +4.46670787761663 -2 6.871272011303372 +-0.9896778371998103 -2.000000000000001 13.52722262093648 +-4.521798531141789 -2.000000000000001 5.881987928600438 +1.085661811105037 -2 2.581558094697904 +-2.683199967828633 -2.000000000000001 17.22071252872312 +-2.951712524327236 -2.000000000000001 6.332950281545813 +2.577528460226452 -2 7.376634470553832 +2.782348179135041 -2 9.594657760236206 +-0.2306390332584316 -2.000000000000001 17.19362993895677 +4.407719635661203 -2 16.29034787129348 +-4.380998952918887 -2.000000000000001 16.26588856976363 +2.151680669146609 -2 6.364093831488967 +4.398304981842878 -2 20.39830498184288 +-4.398304981842879 -2.000000000000001 20.39830498184288 +3.055490131958766 -2 2.396562624265165 +-0.3974192900477309 -2.000000000000001 11.00766662094185 +4.468583974951652 -2 13.15826133869453 +0.1868482987073481 -2.000000000000001 14.92918959475451 +1.42654838740677 -2 13.90846685355164 +-4.468346750503285 -2.000000000000001 7.687119362638718 +-2.573330075392411 -2.000000000000001 19.31790265745031 +2.551886383192638 -2 19.32122066292045 +-2.985996511890672 -2.000000000000001 2.3176451484462 +-3.056238706750225 -2.000000000000001 7.417990531355104 +2.965504200613432 -2 13.13073972813945 +-4.488027323852867 -2.000000000000001 11.44815772708393 +-1.054639239636345 -2.000000000000001 15.89309336407929 +-4.671610280748336 -2.000000000000001 13.92064616328047 +0.7773864054125914 -2 4.821994342649862 +-2.038411800045096 -2.000000000000001 12.00427312627231 +-0.995918098891087 -2.000000000000001 20.61446057217273 +0.9948812191219183 -2 20.60504973280776 +-3.25993753310931 -2.000000000000001 17.95780718136184 +3.238879589209064 -2 18.00240555613311 +4.390387401445203 -2 8.585404552366967 +4.618142124462682 -2 10.05069681666658 +4.530678335235614 -2 14.31476240413611 +-0.9560790367953045 -2.000000000000001 18.94885511275581 +2.897585937467595 -2 16.53732346364887 +4.525155001028395 -2 19.21553247025869 +-4.525728025695154 -2.000000000000001 19.21668295333593 +-0.4744277628847984 -2.000000000000001 3.860593350175403 +-3.232946588653625 -2.000000000000001 14.74844536358904 +3.293489513232413 -2 14.80566329347281 +0.009698861107086287 -2.000000000000001 2.314168288677301 +0.8164621500228781 -2 9.514971608981337 +-1.978473688681108 -2.000000000000001 3.813759460589097 +-3.342011866055845 -2.000000000000001 16.33537048311192 +4.724504392361546 -2 5.857423529042279 +-0.7975614494666248 -2.000000000000001 8.114704947014859 +-1.979283930502985 -2.000000000000001 8.12408853801902 +4.563518296915089 -2 17.55473643893846 +-4.56351829691509 -2.000000000000001 17.55473643893846 +0.02872928398866303 -2.000000000000001 18.18762938323768 +-1.280519103843368 -2.000000000000001 6.315248814105439 +0.1783379747583833 -2.000000000000001 5.817045199236667 +2.170526865265966 -2 10.69368113102602 +3.468260502203156 -2 8.618972186741122 +-3.351959604312443 -2.000000000000001 9.30892312694311 +-1.925677416064739 -2.000000000000001 15.74584715747374 +-1.973393443347822 -2.000000000000001 9.578049442996589 +-1.140398097190907 -2.000000000000001 5.304663797251102 +3.505845415569476 -2 20.58768679695742 +-3.505845415569475 -2.000000000000001 20.58768679695742 +4.704654088588915 -2 11.99427820851364 +-0.7327680178549967 -2.000000000000001 11.85429763566914 +1.619459777575614 -2 17.6643662662479 +-2.002059285955935 -2.000000000000001 10.46474415299315 +0.650749562731348 -2 19.74206402809541 +1.370583462313899 -2 12.32502894590852 +1.915952968929917 -2 15.56877895192888 +3.582349990256756 -2 15.93652209486943 +-1.68377990998792 -2.000000000000001 17.62730691124187 +-1.10477828552709 -2.000000000000001 2.405481475669575 +3.766831899999841 -2 10.27998212502848 +1.826478483888025 -2 20.73699745008538 +-1.850366291989741 -2.000000000000001 20.74003416652434 +0.5601757686651672 -2 16.6050598867845 +-4.702664722064787 -2.000000000000001 4.778558396378894 +3.196271075210551 -2 4.823417518156869 +-4.720191399124726 -2.000000000000001 3.516521873425383 +1.877470313704653 -2 9.050963646641648 +2.671504224018421 -2 17.39059763829634 +-4.813176512579737 -2.000000000000001 10.06622374724943 +-0.7202740209959551 -2.000000000000001 19.7719655167632 +-2.277333838679795 -2.000000000000001 15.04968435667911 +-4.655036991412796 -2.000000000000001 8.603534379053162 +4.659725387181753 -2 2.340274612818245 +-1.824763990462912 -2.000000000000001 18.9844158130695 +3.612082343071899 -2 11.40536145302907 +-3.384485722252197 -2.000000000000001 10.56853396770258 +-0.5416429739069955 -2.000000000000001 14.5033796038366 +-3.41549723075361 -2.000000000000001 4.297953931558371 +-4.784245144814005 -2.000000000000001 6.919814213855449 +1.795976171558739 -2 8.089018645449009 +0.940332778481876 -2 7.630336968732861 +-3.352940615300342 -2.000000000000001 18.8311917552131 +3.33522997051604 -2 18.85017514315173 +4.764326559278742 -2 7.854782227139324 +4.871345106199684 -2 5.003768830427969 +3.175067636094211 -2 3.323069503015326 +0.1799816711203892 -2.000000000000001 3.149141761525918 +0.7270830350408071 -2 14.19435938747323 +3.50764219081414 -2 7.13612570063653 +-2.497908450325836 -2.000000000000001 16.34337839774621 +1.854742909908675 -2 19.06533395064495 +-3.827642910422798 -2.000000000000001 3.592230352940884 +-1.226607581310633 -2.000000000000001 3.393233175816484 +3.307096836329948 -2 5.62608816873988 +-4.742028537486757 -2.000000000000001 12.21280953780205 +2.3276964830617 -2 3.761644335190134 +-2.791862670213163 -2.000000000000001 12.15824319475781 +-4.788211317740906 -2.000000000000001 14.9019852822331 +1.213543407759267 -2 6.683801252934311 +-2.826662430705749 -2.000000000000001 13.67829223509512 +2.023441745812905 -2 2.13596850029051 +1.67418105210729 -2 5.216737770982405 +4.91500264377414 -2 15.06815217091498 +4.857265573891427 -2 3.075583699933986 +3.950523154513502 -2 2.1443507786976 +-4.682347603400613 -2.000000000000001 2.324143360944031 +1.578339612522127 -2 3.458581510504761 +-0.6059846052694198 -2.000000000000001 15.22714378367914 +-1.378001259911316 -2.000000000000001 12.43926102718732 +3.671115031977367 -2 4.051182368696466 +2.629585497198473 -2 11.32970888511465 +-3.691478497232556 -2.000000000000001 5.999169020269644 +0.01862536756168076 -2.000000000000001 13.09023713015464 +-0.6734667903391731 -2.000000000000001 9.472489475203268 +1.236304241549872 -2 16.95318426067976 +0.4752685344413656 -2 8.475188386469213 +-3.963419186111457 -2.000000000000001 5.036553304250354 +3.728565130771077 -2 13.10492797382234 +1.030270921048405 -2 11.53723490708341 +-3.908447667314048 -2.000000000000001 2.100782053872749 +0.6148238697281236 -2 15.61154065073505 +-4.796813899918464 -2.000000000000001 10.76360673934325 +2.342069733788042 -2 15.00319146068441 +3.224649573126666 -2 7.876441549386907 +-1.876823607337504 -2.000000000000001 4.876230030284926 +-2.451224191407043 -2.000000000000001 5.49300002642893 +-1.04197396374143 -2.000000000000001 17.23238553155742 +-2.660623131127707 -2.000000000000001 8.023443442892507 +4.833989366133427 -2 16.90721717031367 +-4.834602994562411 -2.000000000000001 16.90996879262003 +-3.753407675147621 -2.000000000000001 7.559361026862419 +2.377405220249818 -2 4.559190996153049 +2.240756277171396 -2 16.15080854901786 +-3.577233829760454 -2.000000000000001 9.94688320570636 +4.77904588962002 -2 9.269225598966162 +-4.088299293151387 -2.000000000000001 14.49441412755636 +-2.005313400472772 -2.000000000000001 2.049635297633593 +-1.866258770470001 -2.000000000000001 13.72011869526099 +-1.542681581387315 -2.000000000000001 18.3576407659836 +-1.388250367816052 -2.000000000000001 7.741642578246388 +1.421158031348455 -2 10.61700237517617 +4.906898934265529 -2 20.90689893426553 +-4.906898934265529 -2.000000000000001 20.90689893426553 +-2.110946762910443 -2.000000000000001 6.186613546232794 +3.933889865121732 -2 6.1675540894694 +-0.8145681091302022 -2.000000000000001 16.59336359507277 +-4.948882360576921 -2.000000000000001 13.01052298486836 +2.738401621844568 -2 5.954308805534193 +-3.552958293047237 -2.000000000000001 15.61869052320124 +4.990612758932797 -2 20 +-4.990612758932796 -2.000000000000001 20 +-4.852312355495604 -2.000000000000001 15.69794243116832 +-0.3815193127950245 -2.000000000000001 6.604323950749944 +4.829403333096481 -2 18.19037848763615 +-4.830801513283376 -2.000000000000001 18.19318566634461 +0.2242391581872782 -2.000000000000001 4.146867697191034 +4.856785131976734 -2 15.72497905821067 +-3.786655425502522 -2.000000000000001 11.15748726659756 +2 21 0 22 +2554 +2555 +2556 +2557 +2558 +2559 +2560 +2561 +2562 +2563 +2564 +2565 +2566 +2567 +2568 +2569 +2570 +2571 +2572 +2573 +2574 +2575 +5.5 -0.9936224489795915 20.07015306122449 +5.5 -0.9999999999999997 18 +5.5 -0.9999999999999997 16 +5.5 -0.9999999999999997 14 +5.5 -0.9999999999999997 12 +5.5 -0.9999999999999997 10 +5.5 -0.9999999999999997 8 +5.5 -0.9999999999999997 6 +5.5 -1.020833333333333 3.986111111111114 +5.5 -0.9853670634920629 2.897073412698415 +5.5 -0.9999999999999994 17 +5.5 -0.9999999999999994 11 +5.5 -0.9999999999999994 9 +5.5 -0.9999999999999994 7 +5.5 -1.003472222222222 4.997685185185187 +5.5 -0.9989370748299315 19.01169217687075 +5.5 -0.9999999999999994 15 +5.5 -0.9999999999999994 13 +5.5 -1.265937237035589 20.78944466166308 +5.5 -1.297502941895906 2.179203605640502 +5.5 -0.6361441277538346 2.106630843889686 +5.5 -0.6519119372030359 20.87191954457752 +2 22 0 425 +2576 +2577 +2578 +2579 +2580 +2581 +2582 +2583 +2584 +2585 +2586 +2587 +2588 +2589 +2590 +2591 +2592 +2593 +2594 +2595 +2596 +2597 +2598 +2599 +2600 +2601 +2602 +2603 +2604 +2605 +2606 +2607 +2608 +2609 +2610 +2611 +2612 +2613 +2614 +2615 +2616 +2617 +2618 +2619 +2620 +2621 +2622 +2623 +2624 +2625 +2626 +2627 +2628 +2629 +2630 +2631 +2632 +2633 +2634 +2635 +2636 +2637 +2638 +2639 +2640 +2641 +2642 +2643 +2644 +2645 +2646 +2647 +2648 +2649 +2650 +2651 +2652 +2653 +2654 +2655 +2656 +2657 +2658 +2659 +2660 +2661 +2662 +2663 +2664 +2665 +2666 +2667 +2668 +2669 +2670 +2671 +2672 +2673 +2674 +2675 +2676 +2677 +2678 +2679 +2680 +2681 +2682 +2683 +2684 +2685 +2686 +2687 +2688 +2689 +2690 +2691 +2692 +2693 +2694 +2695 +2696 +2697 +2698 +2699 +2700 +2701 +2702 +2703 +2704 +2705 +2706 +2707 +2708 +2709 +2710 +2711 +2712 +2713 +2714 +2715 +2716 +2717 +2718 +2719 +2720 +2721 +2722 +2723 +2724 +2725 +2726 +2727 +2728 +2729 +2730 +2731 +2732 +2733 +2734 +2735 +2736 +2737 +2738 +2739 +2740 +2741 +2742 +2743 +2744 +2745 +2746 +2747 +2748 +2749 +2750 +2751 +2752 +2753 +2754 +2755 +2756 +2757 +2758 +2759 +2760 +2761 +2762 +2763 +2764 +2765 +2766 +2767 +2768 +2769 +2770 +2771 +2772 +2773 +2774 +2775 +2776 +2777 +2778 +2779 +2780 +2781 +2782 +2783 +2784 +2785 +2786 +2787 +2788 +2789 +2790 +2791 +2792 +2793 +2794 +2795 +2796 +2797 +2798 +2799 +2800 +2801 +2802 +2803 +2804 +2805 +2806 +2807 +2808 +2809 +2810 +2811 +2812 +2813 +2814 +2815 +2816 +2817 +2818 +2819 +2820 +2821 +2822 +2823 +2824 +2825 +2826 +2827 +2828 +2829 +2830 +2831 +2832 +2833 +2834 +2835 +2836 +2837 +2838 +2839 +2840 +2841 +2842 +2843 +2844 +2845 +2846 +2847 +2848 +2849 +2850 +2851 +2852 +2853 +2854 +2855 +2856 +2857 +2858 +2859 +2860 +2861 +2862 +2863 +2864 +2865 +2866 +2867 +2868 +2869 +2870 +2871 +2872 +2873 +2874 +2875 +2876 +2877 +2878 +2879 +2880 +2881 +2882 +2883 +2884 +2885 +2886 +2887 +2888 +2889 +2890 +2891 +2892 +2893 +2894 +2895 +2896 +2897 +2898 +2899 +2900 +2901 +2902 +2903 +2904 +2905 +2906 +2907 +2908 +2909 +2910 +2911 +2912 +2913 +2914 +2915 +2916 +2917 +2918 +2919 +2920 +2921 +2922 +2923 +2924 +2925 +2926 +2927 +2928 +2929 +2930 +2931 +2932 +2933 +2934 +2935 +2936 +2937 +2938 +2939 +2940 +2941 +2942 +2943 +2944 +2945 +2946 +2947 +2948 +2949 +2950 +2951 +2952 +2953 +2954 +2955 +2956 +2957 +2958 +2959 +2960 +2961 +2962 +2963 +2964 +2965 +2966 +2967 +2968 +2969 +2970 +2971 +2972 +2973 +2974 +2975 +2976 +2977 +2978 +2979 +2980 +2981 +2982 +2983 +2984 +2985 +2986 +2987 +2988 +2989 +2990 +2991 +2992 +2993 +2994 +2995 +2996 +2997 +2998 +2999 +3000 +-5.361303795110196 1.227363685521539 18.38313873365965 +-5.428267523298314 0.8853878785621518 19.18480652017754 +-5.467776455437735 0.5944919119388857 18.20447811058106 +-5.207845341521944 1.76871334556739 19.99295694179597 +-5.423524875319108 0.9139901130728091 20.1210869783365 +-5.217002877114529 1.74151686187034 18.97401890566335 +-5.466146130142384 0.6092999950184108 2.968793403477545 +-5.31308581274045 1.421660700186986 2.922151527396952 +-5.448145933075399 0.7534626015363912 3.695684797181844 +-5.433751196575617 0.8510863256527201 4.368770302418415 +-5.277735545110002 1.54774271630734 3.946334680211709 +5.428267523298312 0.8853878785621625 3.815193479822462 +5.207845341521939 1.768713345567407 3.007043058204037 +5.423524875319107 0.9139901130728222 2.878913021663504 +5.466146130142383 0.6092999950184215 20.03120659652246 +5.313085812740447 1.421660700186997 20.07784847260304 +5.448145933075399 0.753462601536397 19.30431520281816 +5.217002877114525 1.741516861870357 4.02598109433665 +5.433751196575616 0.8510863256527259 18.63122969758158 +5.277735545110002 1.547742716307341 19.05366531978829 +5.361303795110192 1.227363685521554 4.616861266340351 +5.467776455437734 0.5944919119388939 4.795521889418936 +-4.494318175755014 3.170347636313424 18.90294475827345 +-4.878145595996243 2.54041247522178 19.45771012975483 +-4.935946567576726 2.426196917405413 18.71500123654146 +-4.340130750873029 3.378352418757746 19.82464240927159 +-2.788039212380489 4.740974303898808 20.49651314941001 +-2.045990560448315 5.105283794908604 20.83984109654306 +4.494318175755005 3.170347636313439 4.097055241726554 +4.878145595996235 2.540412475221798 3.542289870245174 +4.935946567576718 2.426196917405431 4.284998763458542 +4.340130750873015 3.378352418757766 3.175357590728407 +2.788039212380474 4.740974303898816 2.503486850589994 +2.045990560448299 5.10528379490861 2.160158903456946 +5.301169772294203 1.465468882410758 17.38420304970668 +5.159064035473734 1.906320612562711 18.10939622048037 +5.049770868049879 2.179406841366424 17.36049414962777 +2.850785516321195 4.703511660444066 19.75324663661861 +3.400342744854388 4.322923688606603 20.2759202330048 +2.802807540448903 4.732258434532372 20.54942126419504 +3.512195040731914 4.232550767073935 19.60380450722662 +-2.850785516321205 4.70351166044406 3.246753363381394 +-3.400342744854402 4.322923688606592 2.724079766995203 +-2.802807540448918 4.732258434532363 2.450578735804964 +-3.512195040731927 4.232550767073922 3.396195492773376 +-0.7540973003054051 5.448058118419085 7.102686029169295 +0.3429047598772523 5.489300167202877 6.885794285830741 +-0.115090637759076 5.498795699523688 7.821103323868222 +-0.369929956808792 5.487545154898996 6.261953854359927 +0.7540948419940621 5.44805845868764 15.89731790960661 +-0.3429047598772753 5.489300167202875 16.11420571416926 +0.1150905607912277 5.498795701134636 15.17889719817842 +0.3698913461935267 5.487547757606411 16.73805098511889 +-5.213815696625728 1.751035659722317 14.24160479686956 +-4.859011523581539 2.576821106266752 14.0767541025898 +-5.043588488596732 2.193676174300696 15.05107346198208 +-4.545539583868026 3.096460865486417 14.79238519139494 +-4.771301410129611 2.735814842728794 4.934780611044861 +-4.912643719956117 2.473040978385865 4.068890224930357 +-4.555097049524811 3.082383958790722 4.226924791268534 +-5.159064035473737 1.906320612562703 4.89060377951963 +4.771301410129609 2.7358148427288 18.06521938895514 +4.912643719956116 2.473040978385868 18.93110977506964 +4.555097049524809 3.082383958790725 18.77307520873146 +5.213815696625726 1.751035659722322 8.758395203130442 +4.859011523581533 2.576821106266763 8.923245897410203 +5.043588488596732 2.193676174300697 7.948926538017918 +4.545539583868015 3.096460865486434 8.207614808605062 +-5.433440885306541 0.8530651475000431 12.12477659776911 +-5.245439130680139 1.653894895792834 11.89930997752898 +-5.314699755144787 1.415615241746124 12.70277568872579 +-5.087321418017382 2.090253762054171 12.4989135575376 +5.43344088530654 0.8530651475000514 10.87522340223089 +5.245439130680134 1.653894895792851 11.10069002247102 +5.314699755144785 1.415615241746134 10.29722431127421 +5.087321418017376 2.090253762054185 10.50108644246239 +-4.001512514039487 3.773313875095124 14.63634619754511 +-3.580356334617748 4.175050720310181 15.29530198866876 +-4.219116434269526 3.528322053622204 15.48689891655911 +-5.193480216014499 1.810459401882846 13.44053296345828 +4.001512514039474 3.773313875095138 8.363653802454898 +3.580356334617738 4.175050720310191 7.70469801133124 +4.219116434269513 3.528322053622218 7.513101083440898 +-4.77800665200288 2.724087449663875 13.14343899781896 +5.193480216014496 1.810459401882854 9.55946703654172 +-5.204782757162582 1.777705389186597 9.390175923317505 +-5.237647821647322 1.67840558161401 8.452435548469184 +-4.969208409752168 2.357322163058823 8.810862147774035 +-5.301169772294204 1.46546888241075 5.615796950293326 +-5.049770868049882 2.179406841366415 5.639505850372231 +4.778006652002873 2.724087449663887 9.856561002181037 +5.204782757162578 1.777705389186609 13.60982407668249 +5.237647821647322 1.678405581614011 14.54756445153082 +4.969208409752166 2.357322163058827 14.18913785222597 +-5.464639789967308 0.6226652117358564 12.88744280146626 +-1.775370308048793 5.205579724612691 11.794525575825 +-2.591479492291532 4.851209544127363 11.15424818594269 +-1.707473180723192 5.22824400129824 10.90792569320777 +5.464639789967308 0.6226652117358622 10.11255719853375 +-4.97957827439679 2.335337279528481 15.88671484872479 +-5.296934862807235 1.480702893620895 15.26449045321922 +-5.225701485200701 1.715238755267379 16.30759441413182 +4.979578274396787 2.335337279528488 7.11328515127521 +5.296934862807233 1.480702893620903 7.735509546780786 +5.225701485200699 1.715238755267385 6.692405585868176 +-4.802499207640867 2.680671811432507 18.05498086541317 +-5.172127434138395 1.870587556099147 18.11102908177984 +4.802499207640859 2.680671811432522 4.945019134586826 +5.17212743413839 1.870587556099164 4.888970918220163 +-4.255254537606632 3.484653328550513 18.02386868845646 +-3.895503216668155 3.882660774382442 19.02205922489565 +-4.669559631658818 2.906064838640452 17.33672908395073 +4.25525453760662 3.484653328550527 4.976131311543536 +3.89550321666814 3.882660774382456 3.977940775104358 +4.669559631658806 2.906064838640473 5.663270916049278 +1.640662268317116 5.249593062449749 18.74657061835253 +1.634941213695721 5.251377650460797 19.4817064232031 +0.9104903990210873 5.424113497456559 19.42877874289107 +0.7219145580576084 5.4524159205681 18.35705863048389 +1.865477768828831 5.173972622077295 17.73430431484681 +-1.640662268317123 5.249593062449748 4.253429381647479 +-1.634941213695738 5.251377650460793 3.518293576796907 +-0.9104903990211002 5.424113497456557 3.571221257108931 +-0.7226545540524227 5.4523178920077 4.643196206547476 +-1.865477768828848 5.17397262207729 5.26569568515319 +-0.9366120768684221 5.419663994886051 19.17755949311842 +-1.546463005826574 5.278110663069678 19.50429749745594 +-1.676291566669699 5.238324787898518 18.70641964346027 +-0.8222697977160526 5.438186497331992 18.34209362019161 +-5.363484461530894 1.217799010886712 4.941793117772502 +-5.472834708178332 0.5459672672959321 5.097978092177268 +-1.781166576375658 5.203599295411035 17.6987915734174 +0.9342468254205083 5.420072219923984 3.822191587510265 +1.546463005826557 5.278110663069683 3.495702502544063 +1.676291566669678 5.238324787898524 4.293580356539735 +5.363484461530892 1.21779901088672 18.05820688222749 +5.472834708178332 0.545967267295938 17.90202190782273 +0.8208550325312147 5.438400225762 4.657335625157518 +-0.7859852672793378 5.443549132654157 10.71205179174809 +1.327085645106138e-10 5.5 11.50000000001812 +-0.9377092533995143 5.419474269344668 11.64510014341506 +1.780950670206428 5.203673194032391 5.301043671963722 +-4.399854365664474 3.300194170188061 2.610825787559175 +-4.929435823414491 2.43939797139333 3.122973012266154 +-4.69049046841095 2.872159321093805 2.197842911041263 +-3.192453127986108 4.478642989300634 19.11373963630526 +-2.582161023746767 4.85617590779443 18.3982851526486 +-2.42037693276906 4.938803043584493 19.26759282060931 +-2.831647701981051 4.715057930912985 19.8066776097191 +4.399854365664475 3.300194170188062 20.38917421244082 +4.929435823414487 2.43939797139334 19.87702698773385 +4.690490468410946 2.872159321093812 20.80215708895874 +3.192453127986089 4.478642989300647 3.886260363694738 +2.582138351711418 4.856187963065375 4.601701982932696 +2.420376932769044 4.9388030435845 3.732407179390691 +2.831647701981036 4.715057930912993 3.193322390280901 +-5.44127123839819 0.8016029629315379 7.917539218432049 +-5.422194964437627 0.9218469328620883 9.057260800354705 +-4.911928045456085 2.474462138781268 7.073394092759639 +-4.92101258101846 2.456345899391621 7.877981368156377 +-5.237437925787009 1.679060443679105 7.484678131320846 +5.44127123839819 0.8016029629315461 15.08246078156795 +5.422194964437625 0.9218469328620988 13.9427391996453 +4.911928045456085 2.474462138781269 15.92660590724036 +4.921012581018458 2.456345899391628 15.12201863184363 +5.237437925787009 1.679060443679108 15.51532186867916 +4.466424791770556 3.209524821442785 19.54185340409909 +-5.442121104228683 0.795812721002112 14.37064463833493 +-5.469311552685181 0.5801992241156572 15.09665616340107 +1.775370306945622 5.205579724988928 11.20547442658006 +2.591479495748875 4.851209542280476 11.84575181541694 +1.707473178392327 5.228244002059468 12.09207432047845 +-4.466424791770562 3.209524821442777 3.458146595900899 +-4.826118976347402 2.637911224082324 10.31710369441998 +-5.139876651236302 1.95746468935608 11.02526963841465 +-5.180603981260187 1.846981967792617 10.16279594158224 +-2.199933287348407 5.040862379714054 20.03438984160673 +5.442121104228681 0.7958127210021225 8.62935536166507 +5.469311552685181 0.5801992241156581 7.903343836598935 +2.199933287348386 5.040862379714063 2.965610158393272 +-2.644726557335276 4.822387524548966 17.61930726134104 +2.149138791264634 5.062726780686627 20.05409766705739 +2.644655568795496 4.822426455887013 5.380668681843616 +-2.149138791264646 5.062726780686623 2.945902332942602 +1.979179391696229 5.13155424169763 20.89108115701188 +-1.979247275341475 5.131528059267858 2.108894885256756 +-5.417614790903308 0.9483933663758476 17.48605144250538 +-5.386699343969148 1.110617025658416 16.73448911637549 +-5.430303928502604 0.8728111159289784 15.96415930371723 +5.417614790903307 0.9483933663758533 5.513948557494617 +5.386699343969146 1.110617025658429 6.265510883624509 +5.430303928502602 0.8728111159289864 7.035840696282776 +-5.138825279413841 1.96022313721098 17.27652090621796 +5.138825279413835 1.960223137210997 5.723479093782034 +-3.543109146119543 4.206706262467589 19.93612283565784 +-4.015431698365302 3.758498140981734 20.78548722046718 +3.543109146119529 4.206706262467603 3.063877164342156 +4.015431698365281 3.758498140981756 2.214512779532825 +-5.465902601949482 0.6114807813839099 20.87543048227543 +-5.33784568411352 1.325670944311091 20.78925282336682 +-5.448754189154243 0.7490512573743426 2.218695290381728 +5.465902601949481 0.611480781383918 2.124569517724563 +-5.273782011305781 1.56116088127635 2.06603200461679 +5.448754189154243 0.7490512573743509 20.78130470961827 +5.337845684113518 1.325670944311103 2.210747176633177 +5.273782011305779 1.561160881276358 20.93396799538321 +-5.035042545807403 2.213220857011181 2.206410452068766 +5.0350425458074 2.213220857011188 20.79358954793124 +-5.074137270931943 2.122058188584689 20.77420172025494 +-4.835717359491212 2.620274340429898 20.19621011551713 +-4.557743248489675 3.078469827827905 20.79723383463638 +5.074137270931937 2.122058188584705 2.22579827974506 +4.835717359491201 2.620274340429918 2.803789884482871 +4.55774324848967 3.078469827827914 2.202766165363617 +-2.435229573752302 4.931496418240835 3.778145894065762 +-2.562425871528081 4.866618297434426 4.588533249013338 +-3.178610162629266 4.488478298268797 3.948142884069746 +-3.484058399830772 4.255741658814435 4.95128256276103 +-2.797185184773201 4.735583917753472 5.44399365750709 +2.435229573752286 4.931496418240842 19.22185410593424 +2.56242587152807 4.866618297434432 18.41146675098666 +3.178610162629255 4.488478298268804 19.05185711593025 +-4.074664716300815 3.694199162163999 17.16257654695239 +-3.861866293006886 3.916119091005437 16.1292773714897 +-3.533145732416824 4.215077844299531 16.89902729236401 +-4.439144924956037 3.247151418587846 16.43422087563973 +-3.022113477567022 4.595305226936265 17.06960886564975 +-3.481825507675691 4.257568688124587 17.96021709836375 +4.074664716300803 3.694199162164013 5.837423453047609 +3.861866293006875 3.916119091005449 6.8707226285103 +3.533145732416811 4.215077844299543 6.100972707635986 +4.439144924956032 3.247151418587854 6.565779124360272 +3.022113477567003 4.595305226936278 5.930391134350252 +3.481825507675681 4.257568688124596 5.039782901636247 +3.484058399830758 4.255741658814447 18.04871743723897 +2.797185184773181 4.735583917753482 17.55600634249291 +-4.158614593634544 3.59943393627523 5.002847197232633 +-3.949888851060788 3.827319958439024 3.984903098198085 +-3.249564810681655 4.43737856635869 6.037580621044704 +-3.852016280820812 3.925808269935173 6.807751068073271 +-4.063747650769527 3.706204936436348 5.841337581163511 +-4.472595179053435 3.200920549515087 6.573887925076644 +0.7859852672793151 5.443549132654161 12.28794820825191 +0.9377092523604245 5.419474269524457 11.35489985763449 +3.249564810681637 4.437378566358703 16.9624193789553 +3.852016280820801 3.925808269935184 16.19224893192673 +4.063747650769514 3.706204936436361 17.1586624188365 +4.472595179053428 3.200920549515097 16.42611207492336 +-4.591931475586732 3.02723724268777 8.551267297547705 +-4.664737158055415 2.913799451962521 5.678308261919339 +4.158614593634535 3.599433936275239 17.99715280276737 +3.949888851060776 3.827319958439035 19.01509690180191 +4.664737158055411 2.913799451962527 17.32169173808066 +1.32419993511273 5.33821079874591 20.37287923456716 +-1.324502810566022 5.33813565814908 2.627133581551124 +4.591931475586729 3.027237242687776 14.4487327024523 +1.004748278872888 5.407446800117591 2.089805072702639 +-1.005446149399391 5.407317083421125 20.91052888501753 +-1.440264290279096 5.30807298123781 20.42383452484559 +1.440264290279079 5.308072981237815 2.576165475154415 +-4.639681991537795 2.953531956387111 11.05269867192088 +0.491863173548624 5.477962268810062 20.431200730718 +-0.2496902892026854 5.494329327541068 20.46899264575377 +-0.8175601110633616 5.438896530069134 19.9881430981539 +-0.03525038058337917 5.499887036173446 19.37290484245268 +0.2477656290382111 5.494416456100438 2.531666444634901 +0.8153424688471531 5.439229417711136 3.01228235522634 +0.02863733275642845 5.499925445237653 3.627357620877515 +-0.4921850773087469 5.477933355716788 2.568632365500484 +-3.447222580167911 4.285633731757823 10.39885346202038 +-3.429015848222841 4.300215147249796 11.61241415705099 +-4.053531462906093 3.717375778587685 11.26174415947728 +-4.215852927071331 3.53222084492237 10.16937628088714 +3.44722258016789 4.285633731757842 12.60114653797962 +3.429015848222824 4.300215147249811 11.38758584294901 +4.053531462906081 3.717375778587696 11.73825584052272 +4.215852927071321 3.532220844922379 12.83062371911286 +4.639681991537787 2.953531956387124 11.94730132807912 +4.826118976347396 2.637911224082335 12.68289630558002 +5.139876651236298 1.957464689356092 11.97473036158535 +5.180603981260183 1.846981967792632 12.83720405841776 +4.017434606072284 3.756357169643593 19.91064327234491 +-4.017434606072293 3.756357169643584 3.089356727655087 +-4.321361946451588 3.402327281106294 13.83386504846433 +4.321361946451572 3.402327281106313 9.166134951535668 +0.9284234795453108 5.421072757547991 13.46624313321312 +0.0412765883610488 5.499845110842056 13.09486940850116 +-0.1559563496105452 5.497788429633879 12.21958723913959 +3.289545940928765 4.407821174063109 20.93875899443165 +-3.571991099008029 4.182209892940264 7.754568362470549 +-4.388426564995498 3.315375134678097 7.540432173086204 +-3.152869691912828 4.506596576776927 6.945628202545436 +-3.32839118914382 4.378562788407835 20.82038985886574 +3.571991099008019 4.182209892940273 15.24543163752945 +4.388426564995489 3.315375134678111 15.4595678269138 +3.152869691912817 4.506596576776934 16.05437179745457 +-3.289545940928775 4.407821174063102 2.061241005568352 +-4.08438384027794 3.683450643795357 8.297839776210886 +3.32839118914381 4.378562788407842 2.179610141134262 +4.084383840277932 3.683450643795365 14.70216022378912 +1.254349923869309 5.355054273159989 8.576429444878533 +0.7252461451114403 5.451973773689763 9.280911472841597 +0.4585599985133675 5.480850547840492 8.405727494581962 +-0.928423527756701 5.421072749291215 9.533756926820679 +-0.04127664334333907 5.499845110429412 9.905130586835151 +-4.686433048017346 2.878774962801164 15.56005691472387 +-3.111272901417611 4.53541408615624 16.0801574790901 +4.68643304801734 2.878774962801176 7.439943085276131 +3.111272901417588 4.535414086156256 6.919842520909899 +1.735529716727699 5.218997662612532 9.590234433517535 +-5.433955433351505 0.8497813532607418 6.891402728744598 +0.1559563496105173 5.49778842963388 10.78041276086041 +-5.263165909714519 1.596585295816965 6.490034249027357 +-4.912600392716472 2.473127045155983 6.356473050096961 +5.263165909714516 1.596585295816973 16.50996575097264 +4.912600392716469 2.473127045155989 16.64352694990304 +5.433955433351506 0.8497813532607377 16.10859727125541 +-5.441826599650597 0.7978240779365002 5.888935467695891 +5.441826599650595 0.7978240779365083 17.11106453230411 +-4.935531498073775 2.427041168073098 16.64912992570766 +4.935531498073773 2.427041168073103 6.350870074292342 +-3.03969602357026 4.583693716239246 9.508728973072008 +-3.702991182345094 4.066676321453981 9.533677361438926 +3.910394401200441 3.867662811965418 20.76156169923431 +-3.910394401200449 3.86766281196541 2.238438300765687 +-2.398795895353341 4.94932098902829 6.176980688914073 +-2.299804211181909 4.996088529062506 16.79709113575021 +-2.105599172931436 5.080989285852751 15.81053632039669 +-1.32909969624588 5.336992973336119 16.57357721956814 +2.299804211181893 4.996088529062514 6.202908864249796 +2.105599172931425 5.080989285852756 7.189463679603309 +1.329099696245863 5.336992973336123 6.426422780431867 +-1.55090698724352 5.276806564288597 6.317432835663737 +-2.40780027515449 4.944946696878134 7.025845933768979 +1.550906987243494 5.276806564288605 16.68256716433626 +2.407800275154474 4.944946696878141 15.97415406623103 +2.398795895353325 4.949320989028297 16.82301931108593 +3.039696023570237 4.583693716239261 13.49127102692799 +3.702991182345077 4.066676321453997 13.46632263856108 +2.046362283491491 5.105134807691516 8.845470555562366 +-0.3444890957065592 5.489200967621724 8.849223456487019 +-1.254349923965578 5.35505427313744 14.42357055615959 +-0.7252461563390387 5.451973772196218 13.71908853224996 +-0.4585599985133905 5.480850547840491 14.59427250541804 +0.3444890957065314 5.489200967621726 14.15077654351298 +-4.949112167377467 2.39922669931716 11.71804010933407 +-4.630816937597108 2.967412086391734 12.35142935383622 +4.949112167377455 2.399226699317182 11.28195989066593 +4.630816937597096 2.967412086391752 10.64857064616378 +0.06528672017163339 5.499612499455687 5.410474363719128 +0.03422213607720265 5.499893530369685 4.667123379742886 +-4.109455985262739 3.655457769580749 13.00994058756568 +-0.8717106560275744 5.430480690709431 5.540865093086822 +4.109455985262723 3.655457769580765 9.990059412434316 +-2.561904166988001 4.866892955384319 12.81855549725508 +-3.378787473804722 4.339792069542077 12.47832914663485 +-2.587510382483893 4.853327726471607 12.01824491151476 +-0.06558704829416881 5.49960892601429 17.58951449014758 +-0.03574806645719491 5.499883823840698 18.33276269639073 +0.8715671812424814 5.430503719599226 17.45923067618997 +-1.806860738800379 5.19473332044887 12.48731595457009 +-0.9457136268117743 5.418083216051828 12.65757840932783 +-1.735529720926152 5.218997661216376 13.40976556690679 +2.561904166199617 4.866892955799321 10.18144450244963 +3.378787473804708 4.339792069542088 10.52167085336515 +2.587510382483882 4.853327726471613 10.98175508848524 +1.806860738800362 5.194733320448876 10.5126840454299 +0.9457136268117518 5.418083216051832 10.34242159067217 +0.9920465769188316 5.409791455243319 5.515384189752837 +-2.498340038899254 4.899826226513842 10.27489412223077 +-0.9921545275372081 5.409771658165197 17.48439885075484 +-2.264665722059224 5.012114241248893 9.448640110368592 +-2.736414957460573 4.770957260402366 7.843164289853711 +-3.419514827219041 4.307774175421588 8.687645303354484 +2.498340038899234 4.899826226513852 12.72510587776923 +2.736414957460557 4.770957260402375 15.15683571014629 +3.419514827219031 4.307774175421595 14.31235469664552 +-1.597521175515078 5.262881919042163 10.00487646628097 +2.264665722059199 5.012114241248905 13.55135988963141 +-1.578476841944133 5.268625139393206 9.160076709609283 +-1.187466033201157 5.370281595968084 8.31517720355578 +1.597521146848455 5.262881927743772 12.99512357613568 +-2.083314005604659 5.090167261893412 8.490656990599749 +3.40747188387166 4.317306493709257 8.44876825269734 +3.766108476228947 4.008294767763029 9.124317668093461 +-3.407471883871677 4.317306493709244 14.55123174730266 +-3.766108476228962 4.008294767763015 13.87568233190654 +1.578476775126563 5.268625159411708 13.83992341459337 +1.18746580336895 5.370281646788121 14.68482318233048 +2.083314005604638 5.09016726189342 14.50934300940025 +-5.399283218199558 1.047731229690433 13.55974464617205 +-1.656271111337996 5.244689314511128 7.475761926949648 +5.399283218199557 1.047731229690437 9.440255353827947 +1.656271111337974 5.244689314511135 15.52423807305035 +-4.162885609046146 3.594493483927395 9.130747402292295 +0.6406979974985328 5.462554903705899 6.218483503488628 +4.162885609046135 3.594493483927407 13.86925259770771 +-0.6406979974985507 5.462554903705898 16.78151649651137 +-3.257384838787947 4.431641232324027 13.23557754317976 +3.257384838787929 4.43164123232404 9.764422456820236 +-2.679975435912344 4.802887846171972 15.00130710864878 +-2.720408336780179 4.780102350491766 8.752525399017902 +2.679975435912329 4.80288784617198 7.998692891351217 +2.720408336780164 4.780102350491774 14.2474746009821 +-5.421845168297653 0.9239020353952039 9.919943061450343 +4.454768798144608 3.225683641505665 11.28165606202981 +4.063761597796212 3.706189643862922 10.86854899556782 +-4.454768798144615 3.225683641505654 11.7183439379702 +5.421845168297651 0.923902035395217 13.08005693854966 +-4.06376159779623 3.706189643862904 12.13145100443218 +1.065167941874369 5.395870389066357 7.564614111201578 +-2.046362283491507 5.10513480769151 14.15452944443763 +1.876358319489216 5.17003669782755 7.98248994141513 +-1.876358319489238 5.170036697827543 15.01751005858487 +-1.065167941874382 5.395870389066355 15.43538588879842 +-5.412234380959519 0.9786311897542064 10.75242096299579 +5.41223438095952 0.9786311897542 12.24757903700421 +-2.954991403121212 4.638752613308855 14.047897089439 +-2.490726467523424 4.903700813057245 13.50197144228889 +2.954991403121189 4.63875261330887 8.952102910561001 +2.490726467523404 4.903700813057255 9.498028557711118 +-4.754717202157414 2.764536910136736 9.523734615631978 +4.754717202157408 2.764536910136747 13.47626538436802 +-5.395314428054079 1.067980441034144 11.43468038892057 +5.395314428054077 1.067980441034154 11.56531961107943 +2 23 0 22 +3001 +3002 +3003 +3004 +3005 +3006 +3007 +3008 +3009 +3010 +3011 +3012 +3013 +3014 +3015 +3016 +3017 +3018 +3019 +3020 +3021 +3022 +-5.5 -0.9936224489795922 20.07015306122449 +-5.5 -1 18 +-5.5 -1 16 +-5.5 -1 14 +-5.5 -1 12 +-5.5 -1 10 +-5.5 -1 8 +-5.5 -1 5.999999999999998 +-5.5 -1.020833333333334 3.986111111111114 +-5.5 -0.9853670634920637 2.897073412698415 +-5.5 -1 7 +-5.5 -1 17 +-5.5 -1 11 +-5.5 -1 9 +-5.5 -0.9989370748299322 19.01169217687075 +-5.5 -1 15 +-5.5 -1 13 +-5.5 -1.003472222222223 4.997685185185187 +-5.5 -1.265937237035589 20.78944466166308 +-5.5 -1.297502941895907 2.179203605640502 +-5.5 -0.6361441277538358 2.106630843889683 +-5.5 -0.6519119372030366 20.87191954457752 +2 24 0 83 +3023 +3024 +3025 +3026 +3027 +3028 +3029 +3030 +3031 +3032 +3033 +3034 +3035 +3036 +3037 +3038 +3039 +3040 +3041 +3042 +3043 +3044 +3045 +3046 +3047 +3048 +3049 +3050 +3051 +3052 +3053 +3054 +3055 +3056 +3057 +3058 +3059 +3060 +3061 +3062 +3063 +3064 +3065 +3066 +3067 +3068 +3069 +3070 +3071 +3072 +3073 +3074 +3075 +3076 +3077 +3078 +3079 +3080 +3081 +3082 +3083 +3084 +3085 +3086 +3087 +3088 +3089 +3090 +3091 +3092 +3093 +3094 +3095 +3096 +3097 +3098 +3099 +3100 +3101 +3102 +3103 +3104 +3105 +0.1439532840925022 1.80878576453042 21.5 +-2.533161482887466 0.8350035708821166 21.5 +2.684322237132989 0.6441573625671098 21.5 +-1.918366297722667 2.89955865619795 21.5 +1.935116538353918 2.929904805623085 21.5 +-0.617869995007903 -0.03916839444712394 21.5 +0.2472506510228067 3.771052494620041 21.5 +1.113330204155869 -0.1887615654617705 21.5 +-3.865026801267733 -0.4068519821161627 21.5 +3.901683002334315 -0.4016830023343139 21.5 +-3.239524454636067 2.268339443350867 21.5 +3.351194658661583 2.122298028889592 21.5 +-2.103033122770671 -0.5953951559390851 21.5 +-1.258887492264591 1.491974252590312 21.5 +-4.002495010525853 1.119840610884734 21.5 +1.499694252081707 1.402342659810033 21.5 +-1.043399833946081 4.046024269154534 21.5 +4.059863104852562 1.041728335706647 21.5 +2.45092391888182 -0.8095624370668268 21.5 +1.611934761348407 3.842764520064432 21.5 +-0.5234666198822816 2.610575137599044 21.5 +-0.04123432550086029 -1.06968775303969 21.5 +-2.775147978458253 3.333915772280314 21.5 +0.2147396738385572 0.6281200393520823 21.5 +3.061288995848315 3.187792915955594 21.5 +0.863213214616759 2.618578055416359 21.5 +-2.234043691868044 1.918838354680513 21.5 +-1.176007540292 -1.039512206799138 21.5 +-2.950940836083221 -1.100329433126529 21.5 +-1.959149078930375 4.044237836787815 21.5 +-0.3962909449104949 4.501078806400608 21.5 +-1.534639452218501 0.5980667188967357 21.5 +2.361129400514856 1.966370682845035 21.5 +-4.545726189125036 0.4083972719553892 21.5 +-4.510881612119873 -1.010881612119873 21.5 +1.7661586605078 0.491736475806924 21.5 +-4.155506273726497 2.021477424269289 21.5 +0.9961051974688708 -1.031448082945225 21.5 +-2.852267589593362 -0.0721809400600848 21.5 +2.458843512909465 3.900148354739967 21.5 +3.224373051385558 -1.111211604540067 21.5 +4.18484590657354 1.871881902034688 21.5 +4.56654125562869 0.428987530221737 21.5 +0.9089345858468978 4.5076863255452 21.5 +4.564651995100757 -1.064651995100756 21.5 +-0.6068910310193687 1.050755836463714 21.5 +3.026430624893441 -0.1384805059387606 21.5 +-3.209866393016597 1.416274631411276 21.5 +3.917297409126773 2.718599012353065 21.5 +-3.578383241346312 2.998557775871118 21.5 +3.181374181376283 1.352019897837816 21.5 +1.82997353075549 -1.279600907336413 21.5 +0.7427646616450956 1.255495957211302 21.5 +-3.50142391106934 0.5500805271595448 21.5 +-1.286735708208257 2.346999788807161 21.5 +-2 -1.372327526528876 21.5 +-0.4681841744855959 3.522798061612887 21.5 +-2.558792632772208 2.605653024540222 21.5 +0.9562156929200928 3.430740919962814 21.5 +-4.705969106259688 1.271584658782091 21.5 +4.706198991711053 1.251821566685136 21.5 +-3.789536440981713 -1.284785973121533 21.5 +1.500293911740944 2.166103958689187 21.5 +-1.259466439669865 4.69087211840762 21.5 +-0.6487255254236866 1.839747208338568 21.5 +0.3445237997854418 -0.1578503630528214 21.5 +-1.469915338764568 -0.2000066176391921 21.5 +-4.870877507233682 -0.3737745143724838 21.5 +3.570035734369713 0.487788269676706 21.5 +-2.754907227666153 4.088634441759227 21.5 +-2.14493228607493 0.1308123743158385 21.5 +4.806575250612752 -0.4074694934426661 21.5 +-1.905397148775103 1.223676909823373 21.5 +0.170844406331769 2.914459318507769 21.5 +-1.198055929802206 3.308120984650691 21.5 +2.326134795768562 -0.07382862426031389 21.5 +0.9793182088135892 0.5488564407750043 21.5 +3.914764033650883 -1.369979155009714 21.5 +2.703787506548134 2.547625035864811 21.5 +1.922164729679186 4.436409667097303 21.5 +2.250281782406491 1.205070038228412 21.5 +0.9499838648354016 1.85026127913146 21.5 +1.747104384589735 -0.4819108568772705 21.5 +2 25 0 83 +3106 +3107 +3108 +3109 +3110 +3111 +3112 +3113 +3114 +3115 +3116 +3117 +3118 +3119 +3120 +3121 +3122 +3123 +3124 +3125 +3126 +3127 +3128 +3129 +3130 +3131 +3132 +3133 +3134 +3135 +3136 +3137 +3138 +3139 +3140 +3141 +3142 +3143 +3144 +3145 +3146 +3147 +3148 +3149 +3150 +3151 +3152 +3153 +3154 +3155 +3156 +3157 +3158 +3159 +3160 +3161 +3162 +3163 +3164 +3165 +3166 +3167 +3168 +3169 +3170 +3171 +3172 +3173 +3174 +3175 +3176 +3177 +3178 +3179 +3180 +3181 +3182 +3183 +3184 +3185 +3186 +3187 +3188 +-0.1439532840925046 1.80878576453042 1.5 +2.533161482887464 0.8350035708821185 1.5 +-2.68432223713299 0.6441573625671102 1.5 +1.918366297722664 2.899558656197952 1.5 +-1.935116538353916 2.929904805623087 1.5 +0.6178699950079013 -0.03916839444712372 1.5 +-0.2472506510228053 3.771052494620043 1.5 +-1.113330204155871 -0.1887615654617714 1.5 +3.865026801267732 -0.4068519821161605 1.5 +-3.901683002334316 -0.4016830023343148 1.5 +3.239524454636064 2.26833944335087 1.5 +-3.35119465866158 2.122298028889593 1.5 +2.10303312277067 -0.5953951559390842 1.5 +1.258887492264589 1.491974252590313 1.5 +4.002495010525851 1.119840610884737 1.5 +-1.49969425208171 1.402342659810035 1.5 +1.043399833946082 4.046024269154537 1.5 +-4.059863104852562 1.041728335706647 1.5 +-2.450923918881821 -0.8095624370668268 1.5 +-1.611934761348404 3.842764520064434 1.5 +0.5234666198822816 2.610575137599046 1.5 +0.04123432550085952 -1.06968775303969 1.5 +2.775147978458249 3.333915772280316 1.5 +-0.2147396738385594 0.628120039352082 1.5 +-3.061288995848312 3.187792915955594 1.5 +-0.8632132146167584 2.618578055416361 1.5 +2.234043691868042 1.918838354680516 1.5 +1.176007540292 -1.039512206799138 1.5 +2.95094083608322 -1.100329433126528 1.5 +1.959149078930372 4.044237836787819 1.5 +0.3962909449104934 4.50107880640061 1.5 +1.534639452218499 0.5980667188967366 1.5 +-2.361129400514856 1.966370682845037 1.5 +4.545726189125034 0.4083972719553921 1.5 +4.510881612119873 -1.010881612119871 1.5 +-1.7661586605078 0.4917364758069251 1.5 +4.155506273726495 2.021477424269294 1.5 +-0.9961051974688717 -1.031448082945225 1.5 +2.852267589593361 -0.07218094006008324 1.5 +-2.458843512909463 3.900148354739967 1.5 +-3.224373051385558 -1.111211604540067 1.5 +-4.184845906573538 1.871881902034687 1.5 +-4.56654125562869 0.4289875302217359 1.5 +-0.9089345858468981 4.507686325545201 1.5 +-4.564651995100758 -1.064651995100757 1.5 +0.6068910310193665 1.050755836463714 1.5 +-3.026430624893441 -0.1384805059387606 1.5 +3.209866393016595 1.416274631411279 1.5 +-3.917297409126772 2.718599012353065 1.5 +3.578383241346308 2.998557775871123 1.5 +-3.181374181376285 1.352019897837817 1.5 +-1.829973530755491 -1.279600907336413 1.5 +-0.7427646616450975 1.255495957211302 1.5 +3.501423911069339 0.5500805271595475 1.5 +1.286735708208256 2.346999788807163 1.5 +2 -1.372327526528877 1.5 +0.4681841744855973 3.522798061612888 1.5 +2.558792632772205 2.605653024540224 1.5 +-0.9562156929200916 3.430740919962816 1.5 +4.705969106259688 1.271584658782096 1.5 +-4.706198991711053 1.251821566685134 1.5 +3.789536440981713 -1.284785973121531 1.5 +-1.500293911740944 2.166103958689188 1.5 +1.25946643966986 4.690872118407624 1.5 +0.6487255254236843 1.839747208338569 1.5 +-0.3445237997854431 -0.1578503630528214 1.5 +1.469915338764566 -0.2000066176391921 1.5 +4.87087750723368 -0.3737745143724807 1.5 +-3.570035734369713 0.487788269676706 1.5 +2.754907227666147 4.088634441759231 1.5 +2.144932286074928 0.1308123743158396 1.5 +-4.806575250612752 -0.4074694934426675 1.5 +1.905397148775101 1.223676909823375 1.5 +-0.1708444063317693 2.91445931850777 1.5 +1.198055929802208 3.308120984650696 1.5 +-2.326134795768563 -0.07382862426031345 1.5 +-0.9793182088135901 0.5488564407750036 1.5 +-3.914764033650882 -1.369979155009715 1.5 +-2.703787506548133 2.547625035864812 1.5 +-1.922164729679186 4.436409667097303 1.5 +-2.250281782406494 1.205070038228414 1.5 +-0.9499838648354029 1.850261279131461 1.5 +-1.747104384589736 -0.4819108568772705 1.5 +3 1 0 593 +3189 +3190 +3191 +3192 +3193 +3194 +3195 +3196 +3197 +3198 +3199 +3200 +3201 +3202 +3203 +3204 +3205 +3206 +3207 +3208 +3209 +3210 +3211 +3212 +3213 +3214 +3215 +3216 +3217 +3218 +3219 +3220 +3221 +3222 +3223 +3224 +3225 +3226 +3227 +3228 +3229 +3230 +3231 +3232 +3233 +3234 +3235 +3236 +3237 +3238 +3239 +3240 +3241 +3242 +3243 +3244 +3245 +3246 +3247 +3248 +3249 +3250 +3251 +3252 +3253 +3254 +3255 +3256 +3257 +3258 +3259 +3260 +3261 +3262 +3263 +3264 +3265 +3266 +3267 +3268 +3269 +3270 +3271 +3272 +3273 +3274 +3275 +3276 +3277 +3278 +3279 +3280 +3281 +3282 +3283 +3284 +3285 +3286 +3287 +3288 +3289 +3290 +3291 +3292 +3293 +3294 +3295 +3296 +3297 +3298 +3299 +3300 +3301 +3302 +3303 +3304 +3305 +3306 +3307 +3308 +3309 +3310 +3311 +3312 +3313 +3314 +3315 +3316 +3317 +3318 +3319 +3320 +3321 +3322 +3323 +3324 +3325 +3326 +3327 +3328 +3329 +3330 +3331 +3332 +3333 +3334 +3335 +3336 +3337 +3338 +3339 +3340 +3341 +3342 +3343 +3344 +3345 +3346 +3347 +3348 +3349 +3350 +3351 +3352 +3353 +3354 +3355 +3356 +3357 +3358 +3359 +3360 +3361 +3362 +3363 +3364 +3365 +3366 +3367 +3368 +3369 +3370 +3371 +3372 +3373 +3374 +3375 +3376 +3377 +3378 +3379 +3380 +3381 +3382 +3383 +3384 +3385 +3386 +3387 +3388 +3389 +3390 +3391 +3392 +3393 +3394 +3395 +3396 +3397 +3398 +3399 +3400 +3401 +3402 +3403 +3404 +3405 +3406 +3407 +3408 +3409 +3410 +3411 +3412 +3413 +3414 +3415 +3416 +3417 +3418 +3419 +3420 +3421 +3422 +3423 +3424 +3425 +3426 +3427 +3428 +3429 +3430 +3431 +3432 +3433 +3434 +3435 +3436 +3437 +3438 +3439 +3440 +3441 +3442 +3443 +3444 +3445 +3446 +3447 +3448 +3449 +3450 +3451 +3452 +3453 +3454 +3455 +3456 +3457 +3458 +3459 +3460 +3461 +3462 +3463 +3464 +3465 +3466 +3467 +3468 +3469 +3470 +3471 +3472 +3473 +3474 +3475 +3476 +3477 +3478 +3479 +3480 +3481 +3482 +3483 +3484 +3485 +3486 +3487 +3488 +3489 +3490 +3491 +3492 +3493 +3494 +3495 +3496 +3497 +3498 +3499 +3500 +3501 +3502 +3503 +3504 +3505 +3506 +3507 +3508 +3509 +3510 +3511 +3512 +3513 +3514 +3515 +3516 +3517 +3518 +3519 +3520 +3521 +3522 +3523 +3524 +3525 +3526 +3527 +3528 +3529 +3530 +3531 +3532 +3533 +3534 +3535 +3536 +3537 +3538 +3539 +3540 +3541 +3542 +3543 +3544 +3545 +3546 +3547 +3548 +3549 +3550 +3551 +3552 +3553 +3554 +3555 +3556 +3557 +3558 +3559 +3560 +3561 +3562 +3563 +3564 +3565 +3566 +3567 +3568 +3569 +3570 +3571 +3572 +3573 +3574 +3575 +3576 +3577 +3578 +3579 +3580 +3581 +3582 +3583 +3584 +3585 +3586 +3587 +3588 +3589 +3590 +3591 +3592 +3593 +3594 +3595 +3596 +3597 +3598 +3599 +3600 +3601 +3602 +3603 +3604 +3605 +3606 +3607 +3608 +3609 +3610 +3611 +3612 +3613 +3614 +3615 +3616 +3617 +3618 +3619 +3620 +3621 +3622 +3623 +3624 +3625 +3626 +3627 +3628 +3629 +3630 +3631 +3632 +3633 +3634 +3635 +3636 +3637 +3638 +3639 +3640 +3641 +3642 +3643 +3644 +3645 +3646 +3647 +3648 +3649 +3650 +3651 +3652 +3653 +3654 +3655 +3656 +3657 +3658 +3659 +3660 +3661 +3662 +3663 +3664 +3665 +3666 +3667 +3668 +3669 +3670 +3671 +3672 +3673 +3674 +3675 +3676 +3677 +3678 +3679 +3680 +3681 +3682 +3683 +3684 +3685 +3686 +3687 +3688 +3689 +3690 +3691 +3692 +3693 +3694 +3695 +3696 +3697 +3698 +3699 +3700 +3701 +3702 +3703 +3704 +3705 +3706 +3707 +3708 +3709 +3710 +3711 +3712 +3713 +3714 +3715 +3716 +3717 +3718 +3719 +3720 +3721 +3722 +3723 +3724 +3725 +3726 +3727 +3728 +3729 +3730 +3731 +3732 +3733 +3734 +3735 +3736 +3737 +3738 +3739 +3740 +3741 +3742 +3743 +3744 +3745 +3746 +3747 +3748 +3749 +3750 +3751 +3752 +3753 +3754 +3755 +3756 +3757 +3758 +3759 +3760 +3761 +3762 +3763 +3764 +3765 +3766 +3767 +3768 +3769 +3770 +3771 +3772 +3773 +3774 +3775 +3776 +3777 +3778 +3779 +3780 +3781 +4.416760790217863 4.69153462558244 20.27802019075534 +3.586501304838669 5.39585444643722 20.1726353881781 +1.511324087791689 6.30027995659032 5.094684884818157 +-6.066459866011453 2.331422268137796 8.812311745955997 +3.156007349324941 -2.994616820330564 6.021089682799359 +2.173946275046188 6.117497393448624 2.727699582738596 +6.200211077028412 1.728918814963522 1.056514553143503 +2.331084465244665 6.019927311295758 19.12041037339447 +-1.498739750112398 -3.008963300469472 18.75428058334835 +-1.329026126124358 6.385093723997846 19.62655022194959 +1.176425357159715 -2.997062144367761 11.08987705701061 +5.950633027556892 -2.938771334131371 1.023230422829063 +-3.769824250528282 5.319191880784034 3.39999107913857 +6.479660622715258 -1.487326427342448 21.85670465445407 +2.773205216505086 -3.002212381155575 3.584521476417732 +-1.419904965250311 -2.979157636616568 20.2926598247937 +-6.206397974424689 1.780978082587843 21.93360672002756 +3.00500814186827 5.732831869644344 7.144345928455468 +-4.218674687470353 4.903214275560462 2.315499676165759 +4.140731267399888 5.068005155653079 19.29192161239823 +6.401164009959735 1.187760482006591 10.30212541915703 +1.318555685297358 6.342410788450699 3.373677525397777 +-0.2981977506688522 6.513096241167445 12.55636058796615 +-2.927208098419312 5.817027717235699 19.71828741552023 +-6.419547448213802 -2.438071939894022 1.023292967765858 +-6.417518011299144 1.133353583047872 20.68871282013491 +6.417286079249862 1.133522847282562 2.309539773905956 +6.294431713781179 1.582430265205023 6.995812894179311 +-5.984741968029089 2.526185946685358 12.04876983384205 +4.411781267769788 4.731769258744115 9.959283750269224 +2.915519405171228 5.756327346503523 20.999671797432 +2.281202764538405 6.035168327483619 3.824391556185372 +-6.215014346707792 1.889021437958733 19.38870622130688 +-5.929113546546565 2.603112180528284 20.16653989716587 +-6.466063492599517 0.8491031584556187 4.742097484004571 +4.841673002784556 -2.97636065253242 1.092576815852461 +-1.418779105059751 -3.032557014641596 17.33899688833913 +4.014071883127453 5.198433438401205 21.16148321070952 +2.820077973370543 5.846114557172937 1.865198281831075 +5.928686606271422 2.621923348435275 13.68704984425239 +6.297813402826166 -2.531973322643152 22.00409298026007 +-3.574892878686653 -3.017098212974016 7.136063260596768 +6.481387501087708 -1.460756797434115 1.136485736707804 +-4.09946620413699 5.038073920081382 7.074795399113751 +6.372453588874135 1.213975692949989 19.82262474785893 +0.7910610912902336 -3.003834127979865 6.629836195600541 +2.167715696428056 6.154134614592911 20.27621419424316 +2.722504260568743 -3.00415324574658 16.08349711455594 +3.383900681125013 5.57719574369377 21.97392449084545 +-6.242621352743779 1.621332351381592 7.968300007631881 +-6.262961628348154 1.708730707148261 1.581856711041531 +6.173126446850976 1.739184496429499 21.96497918777965 +6.321658628035594 1.35773295920242 20.88047337508421 +5.001437498733385 4.075660927391013 8.043989723285447 +5.385969285445203 3.542673397515869 8.926386796349197 +-4.995583970073051 4.123847014121102 2.067620374722345 +0.6022380630768254 6.413994002912362 5.686548299942825 +-6.475325335336539 -1.334764423321807 1.09689967995057 +6.473270713679766 -0.4999999999999994 21.3666076187359 +-2.163951717382438 6.093352210369098 9.575119159314848 +1.349962706284383 6.333285961844303 18.66853340782511 +5.623918668112584 3.182497182297708 7.919186004397351 +-5.867708911842186 2.572061417160952 1.052343505039774 +-4.596051177473502 -2.966160845771131 14.42722069424778 +-4.384038032889824 4.815033831568557 14.77056444321857 +-5.071623406480251 4.008165890577501 14.41853403140917 +-6.319777427604268 1.51565130914816 15.83226571475365 +5.241072272386468 3.793790396924913 16.96573881116192 +4.493653732966883 -3.026302067995052 14.88577309372032 +1.669717130271051 6.231469164439657 1.124033878134686 +5.561044813595266 3.32634068819392 11.3203962887942 +3.765471491701947 -3.018707263863317 16.4622696804644 +0.4955861751981695 6.456149423141952 17.66473646336716 +-6.434588155909337 0.9705913869127858 2.625382066913154 +-6.226837233583129 1.792389254218062 11.23820909294781 +0.4084058200975466 6.47169617352894 7.427727817994212 +6.463181560475832 0.5299769597298395 18.39127855858647 +6.385109942982083 1.231778902002133 17.52485036023536 +1.929818508316391 -3.032005683594366 2.939727993063327 +2.350201106036887 -3.016861986788425 17.18374338390187 +0.7184762323208743 -2.972991982178257 10.0655790465897 +3.126418907167513 5.742518985976949 5.696218977225105 +0.413144917443897 6.467352047968626 13.35137686440992 +-3.015882382061183 5.768715048000779 21.15178443024493 +-3.12865120582822 5.667366937040732 9.259986313628902 +-3.987457551019426 -2.931657168498859 1.044069308079775 +5.792081916831513 2.878667325275694 5.772077407388368 +5.963825480348145 2.565906943190685 3.844103727327348 +-2.346358373447856 6.060352556715654 3.8823132750901 +-2.34919766678581 -3.006843995917845 5.873221706994642 +-4.580080794694735 -2.992830499342779 10.40963810370457 +3.272372399427355 5.616571037131719 3.628239130636282 +0.801978218142292 6.411656488995017 10.85037500244335 +5.033226252206946 4.102842126474441 18.6448322220474 +1.002409294008516 -3.036150164737603 16.5768040876686 +5.037559936122312 -2.988700424828036 21.96164677523313 +6.087768438415784 2.214744213926966 10.05852301337974 +-0.2623949225624345 6.492604954150115 10.63504754665944 +-1.295566164111538 6.358437483411751 10.2282426421297 +-5.659342139641423 3.194107977145846 19.03559373522712 +4.19753386326572 4.950935068510689 3.62984185208751 +-5.496196654279968 -2.941266013882021 22.06988558146298 +-5.922424480318186 -2.91576529172122 21.06405057286625 +-6.374396026151471 1.158841330538115 12.59543159941704 +2.061240725392212 -3.012345162932043 15.23492643938479 +-4.990506462165793 -3.018881724312545 20.45730337364785 +-6.505908578461888 -0.5000000000000006 21.3666076187359 +-4.032770466808724 -3.039521073734002 3.884220017271909 +-2.946081018924281 5.749188027646872 14.05972561837671 +6.44261181372412 -0.4999999999999993 1.612536483806776 +5.944504046953448 2.591400367455659 2.733154709561063 +6.480205121941961 0.473481170260964 6.984312038840209 +-5.496196654279969 -2.941266013882021 0.9245671770027318 +2.721138951338516 -2.96960256665324 4.894912994898246 +6.307345873939155 1.428649828032016 15.71966776022897 +6.042845704682733 2.32584009391664 15.14747094444758 +-2.041767181152203 -2.988128687817135 16.2074394306537 +-0.9378504492197448 -2.967431294256052 4.812359041186726 +-0.4282245100163575 -2.964439406084237 20.87116741264234 +6.289332381404806 1.567940016727529 4.14982108086672 +3.507795518989906 5.461014917885554 1.080150133830931 +3.728603352864079 5.358230779510091 2.112207126701394 +-6.472595470153537 -1.519522064280119 21.87740474837261 +5.166947816499761 3.957582988747668 19.94467216629595 +-3.987457551019424 -2.93165716849886 21.95593069192023 +-4.598068500743448 -3.036082056568114 15.92700533412154 +-0.01341898992800206 6.49720440055571 8.467419290061557 +-2.274613040635711 -2.99825424657931 11.53553101532758 +-2.810113941196115 5.845148532958436 5.63339586488319 +3.081209656119448 5.718016760187624 9.070318206478674 +-5.396782458659119 3.583203223207575 20.14887170189965 +3.150093791112332 5.669828856696676 13.72679588605819 +-2.792287431284404 5.877251697151905 16.32641021419291 +-3.700132976051244 5.34230514473102 16.63568970833374 +4.079719204431965 -2.989498670081719 6.596505423126132 +-3.762017401915767 5.332584543023772 15.5286497245236 +5.605748323271276 3.292267699060853 19.07914644178118 +4.307772187394652 4.89010361237162 11.65430666433816 +-6.260027244922713 1.695774153030144 9.688524398632644 +2.088252690135628 6.104645226041935 16.1171865823837 +-1.778454852572264 6.17249508393353 15.89073297000882 +-1.140750022396593 6.407494418405673 16.71841209946679 +1.598642467589612 6.275798903202388 17.57681788386556 +1.257855169155991 -2.982636960754714 3.899477794801736 +-0.5393106328518356 -3.021043330278927 7.728876808156514 +-1.483392493170066 6.326702450241085 3.200827621315508 +-0.7022688851438351 6.434783555891284 3.984002517985644 +-6.136667256443778 2.1694758977129 5.369530170992089 +-4.531089652297958 -2.974158969427984 13.32385021015091 +-2.977245759388363 5.722491534019982 2.809340023156946 +4.572427680724854 4.583595190371614 14.22711654064735 +4.595317937635151 4.535007867586568 1.12955661955987 +0.5936814573421758 6.485553665189603 11.92240797593861 +5.037559936122308 -3.027940052055521 20.46164677523314 +6.026810710945588 2.346611373486477 11.46514868172539 +-0.3996054298539419 6.450817333102099 5.057937146756006 +0.4793456367415234 6.476971976911884 4.376904869881318 +-1.496366420295933 6.305879263260973 5.229645134481454 +-1.453218568386387 -3.000928190504176 21.97259684029952 +-2.171894127228712 -3.000404249194502 21.11791221984987 +-2.489760412638613 5.990688924772221 18.7151222247669 +6.207274973485699 1.816083573126957 18.4448342354601 +5.88798936802943 2.726183326076068 17.86976403478807 +-6.530660756517321 -0.3391871686285662 1.561618915900121 +2.142418535303408 6.121030742786184 5.961602219209452 +-2.108874524990795 6.1548174145697 20.34052849353375 +4.438910344140444 -2.965526525034938 18.62309906027829 +5.040619913446299 -3.005991695089531 17.67896639516774 +-6.465202677659253 0.4257015503852212 6.985816323634056 +6.340717962408465 -2.531135324649481 20.92391853032714 +5.540279337924209 3.263957125987611 6.7994716025863 +1.390443264098344 -3.02245528602464 20.79856418921337 +-4.984022399804418 -3.027584266013931 17.75386766549509 +-5.034195211906481 -2.966002034464379 18.89044920169681 +-6.432284770257975 0.5627519979680236 21.62440329072271 +5.432264117022592 3.473096157143911 15.90311361817724 +6.067630222737418 2.116812248631465 17.00079458268218 +-3.471332762856055 -3.017247167109992 4.877467567592401 +-4.799158113086872 -2.986789826197572 1.712180856543652 +6.049888539431784 -2.831123770601871 2.090611856628475 +5.051400745979447 4.039554805586219 1.994047457941057 +6.43959938016495 0.159903148321028 20.0083975206598 +5.084016477783795 3.98652809727035 10.47562834466729 +3.078803090924868 -2.992670018485516 7.396444171015348 +5.164954247659763 3.629502814026615 1.004602441355531 +3.257541051325195 5.538582686421647 18.9480304792495 +1.580454236835268 6.332002955823975 13.55159605946398 +-5.303199607277022 3.812460080521028 15.49749403998363 +2.220415701130657 -3.02312987769889 11.4826643516193 +-1.706833911753847 -3.041124861176659 10.6046863514581 +-0.9572927926626651 -2.973759783883376 11.40245359923476 +-0.5783742420056026 -2.976973395230251 10.29286955197 +-0.9679007503912856 -3.046362527340365 9.257956795365748 +-1.500338766409821 -2.989173598532403 8.284850230964627 +5.164898243062638 3.916987427847904 21.96948543450516 +4.699517501283549 -3.03852091984822 15.93736015500161 +-2.60313582001776 5.896716567497281 15.28227726001949 +2.686842615036953 5.91559740909027 18.07590618007049 +1.237655777425257 6.428843299738929 6.524091789890113 +-2.898767304585876 -3.01531756574211 17.66089864313905 +-4.477591896489306 4.57712956479017 3.512157947153067 +-5.002828552719786 4.120742773976996 4.42531006965643 +-5.142089407867877 3.915574907613464 5.518662111787767 +-3.903551540430354 5.203552964418162 19.63116099067534 +-5.522168251236867 3.366926178401549 6.370227550118821 +-4.956278421766254 4.15336597833982 6.968921489780755 +-4.602092524590206 4.560814487551903 7.914183322802621 +-5.712467679654104 3.131652253467981 7.419508166985049 +6.398535029268722 0.6513465421006404 16.59334982323637 +-6.437755961439741 0.6533631291249253 1.603530926718083 +-0.668568204191637 6.458742581679915 17.74075469473262 +-1.456200779600147 6.356109263391597 18.52088688498911 +6.269459253104159 1.68358447587309 13.13728921950266 +5.0435414270305 -2.994737588985936 3.771049644056256 +-5.571651740977041 3.362377018084718 3.789028397221654 +2.025226560151365 6.159959950169936 7.479720775336345 +4.384058128078085 4.753802380754076 8.620924834260336 +1.898444814259478 -3.035652273649585 6.835251129042219 +5.499582274700963 3.327692665495433 4.443939224455282 +6.422248938019058 0.5618739764180728 1.386303448006369 +-6.233905573303145 1.730680512874447 13.81120145459616 +-6.417288850651553 0.6985982901187603 13.56734911365143 +-6.510624533087932 0.4753362484593116 14.67097036842937 +4.265209774116945 4.916700652954421 16.51049145149704 +-0.02702252340594068 6.548042938004389 18.61036432895623 +-2.057428694233754 -3.026883692084315 9.221343611522698 +4.9236485967461 4.149366946736986 6.958619555145204 +-5.642386751348727 3.26141488945424 16.41071252078732 +-5.78329497875586 2.860360123275314 17.44703413854029 +0.6335514906855187 -2.982785536496662 5.342425106079388 +-6.056612310089383 2.125760641584352 2.562418798967379 +-3.229135292328837 5.638441829756357 6.666157259534229 +-5.59048240532016 3.37076858072736 2.660925184031946 +4.499147708217293 4.598092120559361 4.66653958299788 +3.623176810892895 5.315981937589813 4.66230450399639 +4.014235558512685 5.092025341183508 13.46676517040045 +-5.952104129121352 2.41458542034538 6.646989788992648 +-6.201092581039742 1.911335314590057 16.88679644810725 +-4.44172451388482 -2.95419305346749 6.444618742581486 +1.038374296824369 6.376687196427991 8.291380609464868 +4.425939061343732 4.685744507610925 2.602178536391281 +6.271100623138264 1.74116642519719 14.22130509174065 +5.591080226453871 3.272106239052945 14.84117782026804 +1.454396235013943 -3.024140645606765 21.89550215233719 +-3.724799120467098 5.23738441269972 8.118331124058864 +-2.843939561691405 5.905616564746103 8.214136060595076 +-0.7343656523831823 -3.046172455227111 6.64181428153977 +-5.604325472166727 3.334895416116358 8.875111772646349 +5.09452066733984 -2.989799241677328 6.168248057913681 +4.411140780935084 -2.970339522989295 4.692758978036224 +1.017030705017785 -2.993447539312605 15.50020443880728 +1.296470121147352 -2.996092160926713 14.41187959823332 +-5.887140662768873 2.734140073040462 14.52382564947391 +-5.535237712199914 3.341998402996196 13.68579011473276 +-5.948368242992657 2.515670759090635 13.12752738950233 +-2.329717482249129 6.087437974760293 10.65339352679665 +-0.7568065223816725 -2.99711101668772 3.476092462583118 +5.015782099126154 4.103162829315085 3.828487457373706 +5.957032080501479 2.527803824469223 9.009524659215755 +6.287769765269221 1.586560782433337 8.515418045656954 +6.501591159370028 0.4931019984920804 8.346769990671131 +-5.02597979880563 -3.002839299564416 11.79460099485789 +6.447792971172627 -0.3946544482045506 19.03053114283195 +-2.201700647512089 -2.974216824272951 19.56112917541799 +1.636369246233666 6.307849405986965 12.15997317251262 +-4.901595741674172 4.31442259747951 16.46743190732527 +-5.150871368079562 3.913425051976953 17.49077343352604 +-1.441047511634605 -2.995317882248883 1.020367844663058 +3.923319619963491 -2.989967527505417 1.683695329842443 +-3.41709951105071 5.421321381326876 1.927819055505925 +2.445303414767361 5.962978244251632 10.01922089600635 +-4.535874080579545 4.610882877174265 1.157807320965988 +-3.179588842838188 -3.003602175606213 10.16429697078538 +2.67392013065896 5.898819183111987 12.25231671283333 +6.521638527713167 -1.545180998765892 20.42208349431307 +6.501664066221988 -1.503328132443973 19.28438761998319 +2.491334459382355 5.949503856498755 4.865731989607174 +5.126719390304729 -2.973143362815856 10.14257345126342 +0.09414848899434611 -3.001238854609443 11.14209994351183 +5.004508741259379 -2.99519685372813 12.76921258508748 +-6.556848762446343 0.09952412507063271 20.49203704530177 +-3.515799447479148 5.424418670353274 18.05589065205332 +-4.074297300719202 5.067875398738278 9.189720906633964 +2 -2.997861438427633 1.277986561060401 +-0.6326919621397804 -3.056781976252901 18.09391037200002 +-3.922741886042976 5.085252154876911 13.82106889903087 +0.8449390639023109 6.454678382490386 14.37403792637134 +-1.756911113713073 6.312640743140435 8.598663414057295 +-3.081037559927839 -3.018162792012944 8.126029667765026 +3.727854585641886 5.276074037034805 7.873233944442765 +-1.154138015469616 6.366695127509728 6.336361972249975 +-6.452523693297067 0.4049745738929508 15.9459020762833 +-6.498255177232782 -0.5060025295903705 15.25697929106887 +-6.506316277839305 -0.5126325556786107 14.13122984693553 +-6.497879702272696 -1.495759404545392 14.69988260238252 +-6.509700640897194 -1.480598718205614 15.83070593577722 +-6.493996618329488 -1.487993236658976 13.57901333341733 +-6.511804830205899 -0.5236096604117995 13.01287749683726 +-6.498135555017654 -1.496271110035308 12.46030542420303 +-6.51424686688864 -0.5284937337772796 11.88889859560096 +-6.505709541918117 -1.511419083836235 11.32938258394462 +-6.502099727165488 -0.535615605655386 10.75839890866195 +-6.489701145632236 -1.520597708735528 10.19447683633001 +-6.477839297395064 -0.5443214052098708 9.631824927189891 +-6.491971772230123 -1.516056455539754 9.073872687892081 +-6.476111422071932 -0.5477771558561346 8.512453018183177 +-6.440920210643728 0.4195383974177513 9.069213643389478 +-6.49103684159239 -1.517926316815221 7.954745673364253 +-6.424752810704593 -0.5691739841626607 7.42544338493199 +-6.487196309863896 -1.525607380272209 6.822357601274751 +-6.490099659802365 -0.5198006803952688 6.290729126459575 +-6.49059685382538 -1.481193707650761 5.689121183026438 +-6.489704657441209 -0.4815900260047591 5.160690669785027 +-6.509955460324012 0.4824554200556109 5.796839731694565 +-6.313970584141088 1.480855555389347 6.20285100232275 +3.611354403923 5.355314971032232 17.93299838514885 +6.30122469976582 1.592853911997183 5.898941156640901 +6.475755626578426 0.4701788457938718 5.846977493686295 +5.04565245609334 -3.027675672456536 2.639297310173856 +-6.45902950896072 0.4606502609201297 17.08611803584288 +4.181494697774194 -3.009359804475234 11.18914625627955 +0.5470162565829434 -3.012345197445605 13.56620640492176 +-4.274611109374373 4.857240089077858 18.6404277072609 +-2.635768984827372 5.908813673646634 17.64140518847084 +-6.407628032421565 -2.544309816582327 22.11388981461604 +-5.128464172800078 3.958425905630469 12.31541667669675 +0.7899274502330954 6.452884457746953 9.745737459859839 +-6.459917850518926 1.0933439261845 18.27062552604219 +-2.256709153389059 -2.984158097255351 2.452191880032796 +5.795572765162332 2.777915731776054 21.89896164980955 +3.762928416840561 5.222881872085534 6.384449245246339 +5.346383986897837 3.664081445572257 12.88736487130614 +3.05477561899615 5.796878944369665 17.07870341192459 +6.465295676566998 0.6328824364306996 12.8364954790149 +6.497149666593474 -0.505700666813051 12.7385986663739 +6.450745549500977 0.4189322286876062 13.94701780199609 +-4.459070445802082 4.711539867734166 11.81104832748976 +-5.948473306844746 2.588232700404169 10.50140569448557 +-0.6302115331617023 6.502012965414754 7.24252678179232 +-0.220396222568245 -2.98500957722888 16.59951450463595 +-3.560866878441581 5.393610717250573 4.509769370853828 +-0.2326663309119488 6.544965702674065 14.51590278421637 +3.490849320694824 5.463439996794617 10.6572908025174 +2.619770161955274 5.951902754399183 11.14395467513305 +-1.690577719490888 6.264879290779961 1.174566286128479 +-0.5841284173729011 6.425474900087544 1.085903585334923 +-2.720440326653672 5.826397697889105 1.150621786762826 +-1.966365220608544 6.250123650072489 2.227881921611188 +0.5515671020471974 6.416759252969432 1.035622649881071 +4.767981165754785 4.353202338435237 15.67537936497232 +3.725991103177063 -2.99244222737713 17.73820069956966 +-6.274234094965414 1.606935248107151 3.500047049010381 +-6.484710091596752 0.4448096265935961 19.18884036638701 +-6.452842139473233 -0.5996167426130444 19.61321794701307 +-6.495181573989544 -1.497661653015023 20.30156932750923 +-6.528748089433319 -0.4425038211333631 18.50699239430098 +-6.507773258754768 -1.482990187709022 18.92465099024561 +-6.460879984432497 -0.6071550862788165 17.40648006227001 +-6.453421437075064 -1.61885709612506 16.93631425169974 +1.337819567340975 6.421102652859315 15.36586495142633 +-4.002182291863512 -3.039189168373597 2.486490163271379 +-3.143261129513531 -2.978938671637553 1.818784214275178 +6.489549771100686 -0.5209004577986278 5.287127128486781 +6.506375543731826 -1.512751087463651 4.724497825072698 +6.501574768946072 -1.496850462107857 5.852148713072616 +6.5103485294162 -0.5328677320485316 4.153020625189894 +6.505467010175703 -1.510934020351407 3.601776256629029 +6.539777491771176 -1.582755260638314 2.484123824899415 +6.503890473461326 -0.4793332798671895 2.745131095007594 +6.465368249111592 0.8507719819020603 11.75064772488358 +1.09658053847381 -2.954628707469988 1.965596750564351 +2.105715654907688 -2.952298965586847 5.780267908380234 +2.032328154550326 6.181086683817188 9.032026549222087 +-5.004332113836062 4.060705997027487 18.55435353727064 +-4.713139548904391 4.419966724208772 19.5829000262684 +6.442281437362205 0.5155140334855894 3.228631762872193 +0.8317856446383602 6.467187853365901 2.07111813470135 +2.863686976195948 -2.974948315903547 1.944925950997522 +3.267122885755296 -2.963404319594407 11.78046964184534 +3.339006362982281 -3.007494774947473 12.88049685876424 +6.517797746403504 -0.5355954928070068 8.821190985614015 +6.494662197744137 -1.510675604511727 8.228648790976546 +6.492927408858437 -0.5141451822831263 7.687851025194871 +6.514195225705792 -1.528390451411584 9.35605011152489 +6.512552178417601 -1.474895643164798 7.105966133124388 +6.535933259385876 -0.5718665187717504 9.942832477840753 +6.528541649692185 -1.55708329938437 10.47570815012425 +6.54657108919419 -0.6024373254990099 11.06371564322324 +6.538444300829039 -1.58886067481068 11.59622279668384 +6.172679857881933 -2.741533704491162 6 +0.6177877964675935 -3.019058245993425 2.97846023596348 +5.15042464954178 -3.015262700514838 11.68894919794065 +1.360586036423644 6.44561329155909 19.69744578956399 +1.151565844454873 -2.967784705610783 18.05166557867416 +-3.71939062871535 -3.031388162017427 9.051867268088508 +-4.175723847520691 -3.046902058815872 8.053928435377355 +6.185752672772511 -2.728460889600584 12 +-3.653750807518803 5.274745650986222 21.93991452434303 +4.456195133293838 4.693648852894709 21.97091799689309 +-4.544698947897526 4.581813522360831 21.85552725912612 +-5.311223705739475 3.753014036814962 21.70803526668831 +-5.784439787521876 2.793358289901554 21.94958237285324 +-4.372018017382146 4.846999474170659 20.75424494180736 +6.204009849493093 -2.710203712880002 10 +-6.206737432669101 -2.707476129703993 17 +6.51311208074696 -0.4737758385060801 16.69755167701216 +6.493936123916932 -1.512127752166137 16.22574449566773 +6.458520854471015 -0.5933721465180677 15.58408341788406 +6.461081234621528 -0.5778375307569432 14.46213916135319 +6.472763691370041 -1.554472617259919 15.00972577668143 +6.478382693638556 -1.543234612722887 13.88480410472989 +6.433656529312923 0.3499906010466001 15.03600602630567 +6.26911271957804 -2.652266151889273 15 +6.482536690631184 -1.382516156272137 17.31985323747526 +6.46136952700683 -0.4699821431706023 17.93338518873174 +-2.285946331776282 6.088187288565837 21.86463603272093 +-4.789345047979285 -2.963498801042074 5.382165488376508 +-0.2588536507774954 6.476394513448419 9.513293745584129 +4.913560887597674 4.069401683463108 20.94703641413437 +-0.5133866528828781 -2.978344518486712 19.27692994793995 +6.532245890389544 0.3982824163508518 4.710903671708 +1.093122230825422 6.327220560935834 16.57925327717446 +0.3019152076252597 6.470608992559197 15.79578968477777 +-0.08937351607533628 6.562350488032711 16.78161101546666 +6.327857385190539 -2.58391532817792 16.08939406328523 +-1.313752501841172 -2.910579650147723 5.784355093760341 +-6.455971324322178 0.4118055864968597 10.16313247529918 +-4.973544948063719 4.208791271833096 13.35822338044224 +-4.550427682964396 4.686811577216083 6.072929065597235 +-3.770743956923373 5.30209817594536 5.590122715610963 +-5.013951262020418 -2.962568091071449 7.368027557127609 +-6.398632207447948 0.7197819418724838 11.20382689969145 +1.696033994783467 6.253380375975553 21.28821758128159 +-3.495944546792261 -2.968293885180234 14.2711105071384 +-3.169859147045629 -2.97159382970746 15.31015413139184 +-5.984363626863482 2.324307641801167 4.287293623695452 +-0.07582361954517403 -2.937021738627854 15.43405048281452 +-0.2047297802965518 -3.025996551549886 14.35536926556756 +3.995315902217596 -3.012626004685358 21.53164057227002 +-1.239288775698295 6.354074200321563 21.96513672242185 +5.211130895033738 3.86750263437289 5.903499520172001 +-0.0381669019204967 -3.01822179851512 1.777504865615887 +-3.852451612430442 5.154642567500478 10.97923860025248 +-3.578213257251067 5.33680093455799 12.03139019645181 +-2.729240886273273 5.83094102482778 11.61072301803872 +-2.570545205127601 5.958119826064819 12.69048835258211 +-1.580916616122223 6.296567260215508 12.16764077848422 +-1.497060622341446 6.318512255917672 13.29520882178153 +5.438860249837997 3.3629190524748 3.224235191928024 +6.424039222433358 0.5620306060088116 21.61483737824713 +6.554901983216734 -0.5259662081420284 6.62503771059006 +-3.774403353705813 -2.966762946835003 16.66791782010687 +-0.570542146174113 6.49431435704607 2.176032606663807 +-6.33356669130466 -2.548900418171652 15.9317022730708 +4.221120847374827 -3.009332087960886 13.56275297446594 +5.197247839953854 -2.950530176818297 14.05212070727319 +-5.140857852115436 3.931532271916935 11.206205539067 +0.4520699645743307 -3.046781385104967 20.15006394120473 +2.325192582609821 6.037199921721978 15.03503912204257 +3.149648670378785 5.682200831857388 15.65800194050038 +3.598300766194637 5.341032220596136 14.69464828587898 +4.351819604036818 -3.02031505967484 8.104661307197036 +5.064153762301105 -3.026297358080705 7.26690242651927 +-4.745035487502097 4.34919136465762 9.651379157061799 +-6.37095186436831 -2.554284421018965 14.85502724826938 +-6.547890305631463 -0.6048844166274849 4.040231166745029 +-6.550401112781986 -1.58654475538124 4.57691048923752 +-6.529532754107771 -1.561103684314302 3.457401877732852 +-6.543491655621962 -0.5779917100783217 2.92013352943037 +-6.542445874492502 -1.513898200081361 2.375834140653345 +-6.472488539537425 0.5926660512155695 8.028244444846152 +0.5807152090858489 -3.032232473958535 7.982806119238715 +1.675096774943591 -3.076142239082862 7.909255325694392 +-2.425222139115699 6.083561648820432 7.234259060737958 +-5.580401792586787 3.38666584421028 1.618371509765486 +-0.7530025091513839 6.388948029072299 15.73206064590831 +-3.417385126193707 -3.048534955683218 6.062399503871231 +-4.082693241483818 -2.947773340974777 12.33327608443741 +-3.47250836845006 -2.962281256829529 13.20622259561109 +-4.257473267364748 4.808763621541375 12.85048540669936 +-6.091981649819036 -2.804971563081361 19.97596209907002 +-3.920196532635605 -3.047329186797933 20.83011630802004 +4.655853405794566 4.559623328250118 17.45077663716079 +5.80870423778914 2.749452100974271 1.08702398757145 +-4.143728820175992 -2.902285138953743 19.75905346428699 +-3.127539991720638 -2.953157901485165 20.10876238631544 +-3.1445052569513 -3.047848308066685 19.02687934511113 +-1.926328743489807 -2.95446789124532 4.344868465796333 +6.270480344119184 1.712157868999643 3.138602986471993 +6.422402039068575 0.911595952006739 9.297677583516496 +-1.253872769888934 6.400279167998879 14.3143276391609 +-4.361229347757411 4.783170422557531 17.25868905272177 +6.378460427267139 -2.453181959590942 11.00410539555003 +-3.248188385920912 5.699864972987125 10.30779201139753 +-6.33096879181931 -2.550313258977917 2.091065083059727 +-6.397814830034579 -0.5686968214257024 16.35249291586799 +-1.023412642388217 -3.064877253831097 15.90392711261142 +-1.810953023280064 -3.009775759604762 15.11748040282724 +0.9396928431814917 -2.977734341136408 12.14675740203408 +1.958366902504199 -3.06726590710568 12.54886641262059 +6.076698848117381 2.183791818284816 20.2165412523001 +-6.475406444938274 0.4305144820632019 3.748591091321906 +6.312328017774566 -2.54963174325396 4.948118703211381 +6.104247893121942 -2.830623482547468 3.922151066670323 +3.847282883274349 -3.035637940141134 3.763016550445965 +3.615919977675657 -2.953132061897554 2.714815802809599 +-3.895605680300745 -3.078816662494211 18.11017788774659 +0.9584758412199684 -3.001702937214808 9.003736436333288 +1.902733323129704 -3.054121193405047 9.572481380703247 +-3.36745774755471 -2.949295830058715 11.5049791781314 +4.540335856197618 4.562436339682503 12.66972306035011 +5.111462847837248 4.059800046305321 11.93530495342673 +5.653865816727156 3.336032177650431 20.67654272080592 +-5.245651203652937 -3.021445002749945 16.7443454389588 +-1.30912292178642 -2.929903785542927 14.09957214947386 +-1.098869787649517 -3.044289067509081 2.063470194247549 +6.062086711015095 2.25518254692688 7.752788443459301 +-3.117089523006677 -3.017052986577256 3.089528999639191 +-6.312184243801038 -2.602029318572058 7.930986674814858 +-6.166088130184404 -2.789918548545636 9 +-6.300930986374333 -2.578722068482836 10.05454104280908 +5.221648133468189 3.734557993751617 13.9486744407591 +-5.117601163504609 -3.012359584795536 3.700561660817856 +-6.158924986932415 -2.773538579769943 3.999919423975043 +-5.885352671143986 -2.887847008430184 2.986662586585146 +-6.317590167559411 -2.533066026376398 5.039814602446776 +-0.6835274691231908 6.431066869753128 11.58895562305937 +5.133829233716933 -2.967680903031352 8.879276387874592 +4.07381948845221 -3.058960923337488 9.171774315690897 +6.189240626777729 -2.724972935595365 8.916599286977505 +5.191184123689088 -3.028208967118784 19.39381967103333 +6.193594660305848 -2.72299195787097 19.00335600770189 +6.093338100681808 -2.821849823489345 17.91745674745503 +5.776518402702255 -2.965994326564346 16.91349230879967 +4.162526823338673 -2.898753881270714 19.79076233876639 +-6.090370001628306 -2.788892685893825 12 +-5.741095491047788 -2.932983233165686 10.98805667346083 +-6.36322079629464 -2.430503403181384 12.97759288919312 +4.476953919940185 4.701628398610383 5.74969865911355 +0.2850810730660739 6.476051578006087 3.024482013768164 +-4.875320840664652 -3.000200198131406 9.149138242566965 +5.972281112167964 2.631682326138931 16.12152432897943 +0.6766476284926526 -2.981912322574619 0.9805231423131873 +-5.327740151124056 -2.981758230906349 15.1770329236254 +-0.1539144735648433 6.51579549994784 6.350435270054849 +-2.414065940447137 -3.08154423026133 14.21318721883077 +6.512618712296733 -1.608682959336693 12.69952515081307 +6.326106831878053 -2.611196058449571 13.06908543581934 +-0.5173870391636588 6.436880341814387 21.07267184221362 +-0.3229929755530021 6.46968523324484 20.01063774073513 +0.6099655028394838 6.423404547871671 21.03511044758676 +0.6683381860513682 6.465282136039678 22.08274124313759 +-6.202415671864122 2.090379262065556 18.03601366119928 +-5.28656701852949 3.599699329792167 10.19608133442887 +6.344074797753587 2.037870868961669 1.965167172571172 +-6.325621636287997 -2.556786301217986 18.94140212498163 +-5.986109463717945 -2.876577612053905 18.00682520802153 +-6.377606037161015 -2.579097401154711 6.872876326285938 +-6.130545867321553 2.356505367519163 21.11673612370054 +-5.906045755484246 -2.869034247514113 5.962943448791157 +2.349123724117635 -3.072473186445074 20.31775354710732 +2.194179103549052 -3.046517454291696 19.2181663841476 +2.934999676797 -3.063517903778669 21.24743288189704 +2.815082103658988 -2.946356846206141 18.33077256154001 +-2.886042763075773 -2.950102416171275 21.95512000229853 +6.330608129447661 -2.546345438714166 7.058454468350516 +5.875739272467967 -2.923426440359056 7.930634415885733 +5.724112371138675 2.931765789994026 12.26236639099646 +1.083544020819441 -2.961467952717094 19.23626237406741 +0.2678388157478407 -2.932845840338508 18.5950021780918 +-5.447886892672739 -3.018445532240214 8.296969721414735 +-5.266096149396832 3.80205098655293 8.038747239775182 +-5.752454793533429 -2.954676092825763 14.06870437130305 +2.514579497266598 6.095127223025279 21.8709049456727 +2.640429228563536 -3.066661103179661 8.368815369845395 +6.000250668644597 2.557999977169067 4.845635805764451 +6.384030821657551 -2.46568773568852 2.997171182731045 +6.006049572046829 -2.870336084081896 20.00794112089204 +-3.382375646722896 5.438260185046505 13.029031238409 +3.65635231424056 5.380358687361333 12.43846183382546 +3.209057108252591 -3.006887784750636 13.95990471084328 +2.153154579856913 -3.007789390991796 13.76453481145674 +3.089021467246012 -3.091011626590285 15.0056581433184 +5.632025523856935 3.118373322503098 10.30274947082164 +-0.3090150427103782 -3.054221148358047 5.717934404534191 +-6.18921344177012 1.796532777164835 14.84390196593458 +-5.994626510709118 2.505805008178251 15.61389135336028 +4.181310856605728 -3.015455030248791 12.19373622538136 +1.754909531392111 6.168873064040457 10.70429399377144 +0.05232696430558484 -2.981067402116469 4.471040908922925 +4.12435311980771 -3.123443111976278 10.18283182695908 +3.237045893546845 -3.05433466356524 10.73662738455201 +-0.1974766404590132 -2.966762514951824 12.21548556065154 +3 2 0 91 +3782 +3783 +3784 +3785 +3786 +3787 +3788 +3789 +3790 +3791 +3792 +3793 +3794 +3795 +3796 +3797 +3798 +3799 +3800 +3801 +3802 +3803 +3804 +3805 +3806 +3807 +3808 +3809 +3810 +3811 +3812 +3813 +3814 +3815 +3816 +3817 +3818 +3819 +3820 +3821 +3822 +3823 +3824 +3825 +3826 +3827 +3828 +3829 +3830 +3831 +3832 +3833 +3834 +3835 +3836 +3837 +3838 +3839 +3840 +3841 +3842 +3843 +3844 +3845 +3846 +3847 +3848 +3849 +3850 +3851 +3852 +3853 +3854 +3855 +3856 +3857 +3858 +3859 +3860 +3861 +3862 +3863 +3864 +3865 +3866 +3867 +3868 +3869 +3870 +3871 +3872 +-4.111997512092879 -1.854474509209267 -1.473854449074376 +-4.150618647766361 -0.3239762138986614 -1.476873329078804 +-5.366742587563161 0.5667079782158881 -1.547094662230705 +6.043312251568322 0.5794080043133488 -1.958037497922868 +4.377822339821406 -0.4829269778248886 -1.498946647443545 +4.31559277727408 -2.030763388558585 -1.515753006992612 +-5.479988971756379 -2.546484434932533 -1.48718385115567 +-1.061417755571286 0.208853146818394 -1.46977291798887 +-2.664009577502994 0.2791739757878122 -1.512131608832968 +5.912232645762329 -1.276902659625972 -1.4924958321793 +-5.947183806198558 -1.06406321608239 -1.474028480822573 +3.014316493891519 0.226551559244128 -1.439436040376437 +2.496358920318281 -1.333248807033819 -1.485490179426743 +-0.4309677583348573 -2.041138542186669 -1.533856017261099 +-1.720832485717562 -1.189203503633725 -1.503017129908256 +-2.660519548309562 -2.442108734749144 -1.500112208895778 +0.9320133726894306 -1.270836950526961 -1.509775168558428 +5.574165879658625 -2.633074197054362 -1.359957872018731 +1.488894373069963 0.1519910355013585 -1.489419606798412 +-3.042504045684368 -1.061452429999425 -1.324454919223121 +1.664844218510916 -2.571630574763671 -1.582026359585311 +4.700238693860225 0.7319588137379376 -1.767541859486351 +3.052657699411494 -2.598254444178284 -1.621950564540612 +0.2045497970764133 -0.1631709411191277 -1.677906906603781 +0.5114363782889219 -2.798004346279319 -1.154981102322936 +-4.87805427544867 -1.107349939427055 -1.11080796396761 +-3.95077097253148 -2.917575806595046 -1.044880597212014 +-1.440585612699735 -2.805693416585548 -1.27160190666224 +-6.275835126140565 0.7758350082101392 -1.712686451711388 +-3.739904305773559 0.8127123025977889 -1.231664323034862 +-5.149993873643559 -0.450593741281768 -1.98975869836389 +-4.52519955759888 -2.725441262614654 -2.018028466962583 +-0.6432287670216581 -0.9459805065419205 -1.908182443943114 +-4.71166350699528 -2.331860430547016 -0.8694564295465321 +5.431628997890761 -0.3224074783431473 -1.048806012957948 +-5.042595605678873 -1.703166013539071 -1.990363620985259 +4.111485715160188 0.3892737678556042 -0.9489315566633945 +6.492083428254423 -0.4730108641903765 -1.964520111779069 +-3.924145134914958 -1.082876370926116 -0.9068579781364748 +-6.382161559861933 -2.019525163395538 -1.081083914184964 +0.6088495623683503 0.9559580062522939 -1.570575218815825 +3.356615972370033 -0.73774058979945 -1.979723357375127 +-3.519980833515743 -2.451474067066299 -2.093836134392709 +-6.103543976545931 -0.06744400078902077 -1.013249802390161 +2.20563736631728 0.8176627577929098 -0.9989246239615202 +-4.557558877162766 0.3499273638206075 -2.096035350913712 +-0.04895155831168375 -1.143252898795575 -0.9729379194392397 +4.011213740498333 -2.963820682559613 -1.988945471023772 +1.943658236407695 -0.6224157671909833 -0.9472248962419988 +-1.821305575422583 0.8193175743676087 -0.9725605357989719 +4.933123175757314 -1.285630589902802 -1.027608021638238 +3.63227229076587 0.9704769178699033 -2.002977168017648 +3.508655511347629 -1.437360554697207 -0.9668153954035897 +0.5641777895218363 -2.152527609288749 -2.02751315386262 +4.791445846774745 -1.268530907346402 -2.077864801864276 +1.743447999360189 -0.7609862091835011 -1.992065590602397 +-0.428163814488275 0.9721978672368561 -1.976288462727184 +-2.842192460049465 -3.112369026783851 -2.145558171102559 +5.176303335744744 -0.1274200756668586 -2.007808935657541 +6.41089121492018 -2.169084229731829 -1.913831859864311 +-0.4470038675131313 -3.09805806213837 -1.487864439939994 +2.385158634855566 -2.203337557927795 -0.938503034181576 +-1.828139586754132 0.7005151154248759 -2.041171576967449 +-0.4133909559490948 0.8380559624164583 -0.9356682525290627 +-1.006885633919657 -0.7802821265155772 -0.8866633554625521 +-1.896377736517973 -0.262064541087625 -1.057465505559632 +-4.975631258820861 -0.1313423643305588 -0.9600772408304205 +-6.473003973296406 -0.2911440569105605 -1.989494475855385 +-3.32514918866825 -0.1936114333400261 -0.9589803782412178 +-3.289512757017487 -0.337206109287367 -1.91284749105146 +-2.268912708949611 -0.5077072989470914 -2.081094153392074 +2.568592945607734 1.030939145151544 -1.977940803525509 +-5.487353473423513 -1.791751383613933 -0.8787555335270598 +6.099634416514322 0.8974163232478931 -0.8740631384568284 +6.54466286870062 -0.08239375840972427 -0.9731822198955611 +-2.515620615779764 -1.573297633154209 -2.084720132568832 +-6.031419245087762 -1.900544866880485 -2.032324219805801 +-3.801940659731509 -1.081532248814877 -1.788807248104936 +-2.367814288193683 -1.681437409761003 -0.9133278692495626 +-3.286977146781755 -1.924882424672925 -0.9986762648285769 +5.448188644953604 1.196925562409419 -1.467160673446022 +5.051534308000906 0.5392967180548549 -0.9027874251319398 +3.876073255649894 0.05317191133596505 -2.109802501998711 +3.641871494269577 -1.656093441146041 -2.103865179750414 +-5.925507610276161 0.880417047610899 -0.7936022350687544 +6.271908194425104 -2.036258857428638 -0.9092257159149538 +4.213630947704668 -2.916488934461276 -0.9580710178391775 +5.090452076563218 -2.193909969610254 -2.080300014766828 +0.8519914009314544 -0.4275004836144733 -0.9141086515142063 +-1.234382620014502 -1.875516085610068 -0.9549889768255808 +-1.369521219680876 -2.043555728986307 -1.965130899358881 +$EndNodes +$Elements +111 21266 1 21266 +0 1 15 1 +1 1 +0 2 15 1 +2 2 +0 3 15 1 +3 3 +0 4 15 1 +4 4 +0 5 15 1 +5 5 +0 6 15 1 +6 6 +0 7 15 1 +7 7 +0 8 15 1 +8 8 +0 9 15 1 +9 9 +0 10 15 1 +10 10 +0 11 15 1 +11 11 +0 12 15 1 +12 12 +0 13 15 1 +13 13 +0 14 15 1 +14 14 +0 15 15 1 +15 15 +0 16 15 1 +16 16 +0 17 15 1 +17 17 +0 18 15 1 +18 18 +0 19 15 1 +19 19 +0 20 15 1 +20 20 +0 21 15 1 +21 21 +0 22 15 1 +22 22 +0 23 15 1 +23 23 +0 24 15 1 +24 24 +0 25 15 1 +25 25 +0 26 15 1 +26 26 +0 27 15 1 +27 27 +0 28 15 1 +28 28 +0 29 15 1 +29 29 +0 30 15 1 +30 30 +0 31 15 1 +31 31 +0 32 15 1 +32 32 +1 1 1 4 +33 1 33 +34 33 34 +35 34 35 +36 35 2 +1 2 1 2 +37 2 36 +38 36 3 +1 3 1 4 +39 4 37 +40 37 38 +41 38 39 +42 39 3 +1 4 1 2 +43 1 40 +44 40 4 +1 5 1 24 +45 5 41 +46 41 42 +47 42 43 +48 43 44 +49 44 45 +50 45 46 +51 46 47 +52 47 48 +53 48 49 +54 49 50 +55 50 51 +56 51 52 +57 52 53 +58 53 54 +59 54 55 +60 55 56 +61 56 57 +62 57 58 +63 58 59 +64 59 60 +65 60 61 +66 61 62 +67 62 63 +68 63 2 +1 6 1 4 +69 5 64 +70 64 65 +71 65 66 +72 66 6 +1 7 1 11 +73 6 67 +74 67 68 +75 68 69 +76 69 70 +77 70 71 +78 71 72 +79 72 73 +80 73 74 +81 74 75 +82 75 76 +83 76 1 +1 8 1 2 +84 3 77 +85 77 7 +1 9 1 1 +86 8 2 +1 10 1 2 +87 8 78 +88 78 9 +1 11 1 3 +89 9 79 +90 79 80 +91 80 7 +1 12 1 4 +92 7 81 +93 81 82 +94 82 83 +95 83 10 +1 13 1 11 +96 10 84 +97 84 85 +98 85 86 +99 86 87 +100 87 88 +101 88 89 +102 89 90 +103 90 91 +104 91 92 +105 92 93 +106 93 11 +1 14 1 4 +107 11 94 +108 94 95 +109 95 96 +110 96 12 +1 15 1 2 +111 12 97 +112 97 13 +1 16 1 4 +113 13 98 +114 98 99 +115 99 100 +116 100 14 +1 17 1 11 +117 14 101 +118 101 102 +119 102 103 +120 103 104 +121 104 105 +122 105 106 +123 106 107 +124 107 108 +125 108 109 +126 109 110 +127 110 4 +1 18 1 2 +128 6 111 +129 111 14 +1 19 1 24 +130 15 112 +131 112 113 +132 113 114 +133 114 115 +134 115 116 +135 116 117 +136 117 118 +137 118 119 +138 119 120 +139 120 121 +140 121 122 +141 122 123 +142 123 124 +143 124 125 +144 125 126 +145 126 127 +146 127 128 +147 128 129 +148 129 130 +149 130 131 +150 131 132 +151 132 133 +152 133 134 +153 134 8 +1 20 1 1 +154 15 5 +1 21 1 2 +155 5 135 +156 135 13 +1 22 1 4 +157 9 136 +158 136 137 +159 137 138 +160 138 16 +1 23 1 3 +161 16 139 +162 139 140 +163 140 10 +1 24 1 11 +164 16 141 +165 141 142 +166 142 143 +167 143 144 +168 144 145 +169 145 146 +170 146 147 +171 147 148 +172 148 149 +173 149 150 +174 150 17 +1 25 1 3 +175 17 151 +176 151 152 +177 152 11 +1 26 1 4 +178 17 153 +179 153 154 +180 154 155 +181 155 18 +1 27 1 3 +182 18 156 +183 156 157 +184 157 12 +1 28 1 2 +185 18 158 +186 158 15 +1 29 1 23 +187 9 159 +188 159 160 +189 160 161 +190 161 162 +191 162 163 +192 163 164 +193 164 165 +194 165 166 +195 166 167 +196 167 168 +197 168 169 +198 169 170 +199 170 171 +200 171 172 +201 172 173 +202 173 174 +203 174 175 +204 175 176 +205 176 177 +206 177 178 +207 178 179 +208 179 180 +209 180 19 +1 30 1 4 +210 20 181 +211 181 182 +212 182 183 +213 183 19 +1 31 1 23 +214 16 184 +215 184 185 +216 185 186 +217 186 187 +218 187 188 +219 188 189 +220 189 190 +221 190 191 +222 191 192 +223 192 193 +224 193 194 +225 194 195 +226 195 196 +227 196 197 +228 197 198 +229 198 199 +230 199 200 +231 200 201 +232 201 202 +233 202 203 +234 203 204 +235 204 205 +236 205 20 +1 32 1 11 +237 21 206 +238 206 207 +239 207 208 +240 208 209 +241 209 210 +242 210 211 +243 211 212 +244 212 213 +245 213 214 +246 214 215 +247 215 20 +1 33 1 23 +248 17 216 +249 216 217 +250 217 218 +251 218 219 +252 219 220 +253 220 221 +254 221 222 +255 222 223 +256 223 224 +257 224 225 +258 225 226 +259 226 227 +260 227 228 +261 228 229 +262 229 230 +263 230 231 +264 231 232 +265 232 233 +266 233 234 +267 234 235 +268 235 236 +269 236 237 +270 237 21 +1 34 1 4 +271 22 238 +272 238 239 +273 239 240 +274 240 21 +1 35 1 23 +275 18 241 +276 241 242 +277 242 243 +278 243 244 +279 244 245 +280 245 246 +281 246 247 +282 247 248 +283 248 249 +284 249 250 +285 250 251 +286 251 252 +287 252 253 +288 253 254 +289 254 255 +290 255 256 +291 256 257 +292 257 258 +293 258 259 +294 259 260 +295 260 261 +296 261 262 +297 262 22 +1 36 1 2 +298 23 263 +299 263 22 +1 37 1 23 +300 15 264 +301 264 265 +302 265 266 +303 266 267 +304 267 268 +305 268 269 +306 269 270 +307 270 271 +308 271 272 +309 272 273 +310 273 274 +311 274 275 +312 275 276 +313 276 277 +314 277 278 +315 278 279 +316 279 280 +317 280 281 +318 281 282 +319 282 283 +320 283 284 +321 284 285 +322 285 23 +1 38 1 24 +323 24 286 +324 286 287 +325 287 288 +326 288 289 +327 289 290 +328 290 291 +329 291 292 +330 292 293 +331 293 294 +332 294 295 +333 295 296 +334 296 297 +335 297 298 +336 298 299 +337 299 300 +338 300 301 +339 301 302 +340 302 303 +341 303 304 +342 304 305 +343 305 306 +344 306 307 +345 307 308 +346 308 23 +1 39 1 23 +347 8 309 +348 309 310 +349 310 311 +350 311 312 +351 312 313 +352 313 314 +353 314 315 +354 315 316 +355 316 317 +356 317 318 +357 318 319 +358 319 320 +359 320 321 +360 321 322 +361 322 323 +362 323 324 +363 324 325 +364 325 326 +365 326 327 +366 327 328 +367 328 329 +368 329 330 +369 330 24 +1 40 1 2 +370 19 331 +371 331 24 +1 41 1 11 +372 25 332 +373 332 333 +374 333 334 +375 334 335 +376 335 336 +377 336 337 +378 337 338 +379 338 339 +380 339 340 +381 340 341 +382 341 26 +1 42 1 20 +383 26 342 +384 342 343 +385 343 344 +386 344 345 +387 345 346 +388 346 347 +389 347 348 +390 348 349 +391 349 350 +392 350 351 +393 351 352 +394 352 353 +395 353 354 +396 354 355 +397 355 356 +398 356 357 +399 357 358 +400 358 359 +401 359 360 +402 360 27 +1 43 1 11 +403 27 361 +404 361 362 +405 362 363 +406 363 364 +407 364 365 +408 365 366 +409 366 367 +410 367 368 +411 368 369 +412 369 370 +413 370 28 +1 44 1 20 +414 25 371 +415 371 372 +416 372 373 +417 373 374 +418 374 375 +419 375 376 +420 376 377 +421 377 378 +422 378 379 +423 379 380 +424 380 381 +425 381 382 +426 382 383 +427 383 384 +428 384 385 +429 385 386 +430 386 387 +431 387 388 +432 388 389 +433 389 28 +1 45 1 2 +434 26 390 +435 390 29 +1 46 1 20 +436 29 391 +437 391 392 +438 392 393 +439 393 394 +440 394 395 +441 395 396 +442 396 397 +443 397 398 +444 398 399 +445 399 400 +446 400 401 +447 401 402 +448 402 403 +449 403 404 +450 404 405 +451 405 406 +452 406 407 +453 407 408 +454 408 409 +455 409 30 +1 47 1 2 +456 30 410 +457 410 27 +1 48 1 18 +458 31 411 +459 411 412 +460 412 413 +461 413 414 +462 414 415 +463 415 416 +464 416 417 +465 417 418 +466 418 419 +467 419 420 +468 420 421 +469 421 422 +470 422 423 +471 423 424 +472 424 425 +473 425 426 +474 426 427 +475 427 30 +1 49 1 20 +476 32 428 +477 428 429 +478 429 430 +479 430 431 +480 431 432 +481 432 433 +482 433 434 +483 434 435 +484 435 436 +485 436 437 +486 437 438 +487 438 439 +488 439 440 +489 440 441 +490 441 442 +491 442 443 +492 443 444 +493 444 445 +494 445 446 +495 446 31 +1 50 1 18 +496 29 447 +497 447 448 +498 448 449 +499 449 450 +500 450 451 +501 451 452 +502 452 453 +503 453 454 +504 454 455 +505 455 456 +506 456 457 +507 457 458 +508 458 459 +509 459 460 +510 460 461 +511 461 462 +512 462 463 +513 463 32 +1 51 1 2 +514 32 464 +515 464 25 +1 52 1 2 +516 28 465 +517 465 31 +2 1 2 32 +518 33 466 1 +519 466 40 1 +520 471 35 2 +521 36 471 2 +522 470 36 3 +523 39 470 3 +524 467 37 4 +525 40 467 4 +526 34 476 33 +527 468 466 33 +528 476 468 33 +529 475 34 35 +530 475 476 34 +531 471 469 35 +532 469 475 35 +533 471 36 470 +534 473 38 37 +535 467 468 37 +536 468 473 37 +537 38 474 39 +538 473 474 38 +539 469 470 39 +540 474 469 39 +541 467 40 466 +542 466 468 467 +543 473 468 472 +544 468 476 472 +545 470 469 471 +546 469 474 472 +547 475 469 472 +548 472 474 473 +549 472 476 475 +2 2 2 171 +550 1 502 33 +551 76 521 1 +552 1 521 502 +553 2 35 63 +554 5 41 64 +555 66 499 6 +556 6 520 67 +557 499 520 6 +558 33 527 34 +559 502 527 33 +560 63 35 34 +561 34 62 63 +562 34 527 62 +563 65 41 42 +564 64 41 65 +565 43 528 42 +566 42 528 65 +567 44 499 43 +568 499 528 43 +569 45 530 44 +570 44 530 499 +571 46 500 45 +572 500 530 45 +573 47 508 46 +574 46 508 500 +575 48 535 47 +576 47 535 508 +577 49 522 48 +578 522 535 48 +579 50 510 49 +580 49 510 491 +581 491 522 49 +582 51 510 50 +583 52 504 51 +584 504 510 51 +585 53 533 52 +586 52 533 504 +587 54 505 53 +588 505 533 53 +589 55 511 54 +590 54 511 505 +591 56 494 55 +592 494 511 55 +593 57 525 56 +594 56 525 494 +595 58 529 57 +596 57 529 525 +597 59 509 58 +598 509 529 58 +599 60 532 59 +600 59 532 509 +601 61 502 60 +602 60 502 490 +603 490 532 60 +604 62 527 61 +605 61 527 502 +606 65 528 66 +607 66 528 499 +608 67 503 68 +609 67 520 503 +610 68 534 69 +611 503 534 68 +612 69 497 70 +613 69 534 497 +614 70 516 71 +615 497 516 70 +616 71 495 72 +617 71 516 495 +618 72 514 73 +619 495 514 72 +620 73 501 74 +621 73 514 501 +622 74 538 75 +623 501 538 74 +624 75 507 76 +625 75 538 507 +626 507 521 76 +627 496 513 477 +628 477 515 496 +629 513 517 477 +630 477 526 515 +631 517 526 477 +632 489 506 478 +633 478 519 489 +634 506 531 478 +635 518 519 478 +636 478 531 518 +637 479 512 493 +638 493 524 479 +639 498 523 479 +640 479 524 498 +641 479 536 512 +642 523 536 479 +643 480 537 500 +644 500 539 480 +645 503 537 480 +646 480 541 503 +647 480 539 506 +648 506 541 480 +649 481 512 492 +650 492 529 481 +651 481 507 493 +652 493 512 481 +653 481 540 507 +654 481 529 509 +655 509 532 481 +656 532 540 481 +657 491 510 482 +658 482 518 491 +659 482 513 496 +660 496 518 482 +661 482 510 504 +662 504 513 482 +663 483 515 495 +664 495 516 483 +665 496 515 483 +666 483 519 496 +667 483 516 497 +668 497 519 483 +669 484 511 494 +670 494 523 484 +671 498 517 484 +672 484 523 498 +673 505 511 484 +674 484 517 505 +675 485 514 495 +676 495 526 485 +677 498 524 485 +678 485 526 498 +679 501 514 485 +680 485 524 501 +681 486 520 499 +682 499 530 486 +683 486 530 500 +684 500 537 486 +685 486 537 520 +686 487 513 504 +687 504 533 487 +688 505 517 487 +689 487 533 505 +690 487 517 513 +691 488 531 506 +692 506 539 488 +693 508 535 488 +694 488 539 508 +695 522 531 488 +696 488 535 522 +697 489 519 497 +698 497 534 489 +699 489 541 506 +700 534 541 489 +701 502 521 490 +702 521 540 490 +703 490 540 532 +704 518 531 491 +705 491 531 522 +706 512 536 492 +707 525 529 492 +708 492 536 525 +709 501 524 493 +710 493 538 501 +711 507 538 493 +712 494 536 523 +713 525 536 494 +714 515 526 495 +715 496 519 518 +716 498 526 517 +717 508 539 500 +718 520 537 503 +719 503 541 534 +720 507 540 521 +2 3 2 18 +721 8 543 2 +722 2 542 36 +723 2 543 542 +724 36 546 3 +725 3 546 77 +726 77 544 7 +727 7 544 80 +728 78 543 8 +729 9 545 78 +730 79 545 9 +731 542 546 36 +732 77 546 544 +733 78 545 543 +734 80 542 79 +735 542 545 79 +736 80 544 542 +737 543 545 542 +738 544 546 542 +2 4 2 244 +739 3 582 39 +740 77 606 3 +741 3 606 582 +742 37 576 4 +743 4 600 110 +744 576 600 4 +745 7 609 77 +746 81 583 7 +747 583 609 7 +748 10 578 83 +749 84 599 10 +750 10 599 578 +751 11 597 93 +752 94 579 11 +753 579 597 11 +754 12 585 96 +755 97 608 12 +756 12 608 585 +757 13 607 97 +758 98 584 13 +759 584 607 13 +760 14 577 100 +761 101 598 14 +762 14 598 577 +763 38 614 37 +764 37 614 576 +765 39 614 38 +766 582 614 39 +767 77 609 606 +768 82 611 81 +769 81 611 583 +770 83 611 82 +771 578 611 83 +772 85 615 84 +773 84 615 599 +774 86 645 85 +775 85 645 615 +776 87 587 86 +777 587 645 86 +778 88 626 87 +779 87 626 587 +780 89 604 88 +781 604 626 88 +782 90 621 89 +783 89 621 604 +784 91 625 90 +785 586 621 90 +786 90 625 586 +787 92 646 91 +788 91 646 625 +789 93 618 92 +790 618 646 92 +791 597 618 93 +792 95 612 94 +793 94 612 579 +794 96 612 95 +795 585 612 96 +796 607 608 97 +797 99 613 98 +798 98 613 584 +799 100 613 99 +800 577 613 100 +801 102 616 101 +802 101 616 598 +803 103 575 102 +804 575 616 102 +805 104 620 103 +806 103 620 575 +807 105 634 104 +808 590 620 104 +809 104 634 590 +810 106 605 105 +811 605 634 105 +812 107 636 106 +813 106 636 605 +814 108 591 107 +815 591 636 107 +816 109 574 108 +817 574 591 108 +818 110 617 109 +819 109 617 574 +820 600 617 110 +821 547 589 571 +822 571 592 547 +823 547 595 580 +824 580 603 547 +825 547 642 589 +826 592 644 547 +827 547 644 595 +828 603 642 547 +829 570 596 548 +830 548 601 570 +831 596 635 548 +832 548 619 601 +833 610 619 548 +834 548 635 610 +835 573 588 549 +836 549 593 573 +837 581 594 549 +838 549 602 581 +839 588 641 549 +840 549 643 593 +841 594 643 549 +842 549 641 602 +843 576 614 550 +844 550 632 576 +845 580 595 550 +846 550 628 580 +847 550 614 582 +848 582 628 550 +849 595 632 550 +850 551 613 577 +851 577 633 551 +852 551 594 581 +853 581 629 551 +854 584 613 551 +855 551 629 584 +856 551 633 594 +857 552 611 578 +858 578 638 552 +859 552 603 580 +860 580 631 552 +861 583 611 552 +862 552 631 583 +863 552 638 603 +864 579 612 553 +865 553 637 579 +866 581 602 553 +867 553 630 581 +868 553 612 585 +869 585 630 553 +870 602 637 553 +871 554 623 571 +872 571 648 554 +873 587 640 554 +874 554 648 587 +875 554 640 623 +876 555 624 572 +877 572 627 555 +878 555 588 573 +879 573 624 555 +880 555 647 588 +881 627 647 555 +882 556 622 572 +883 572 624 556 +884 573 593 556 +885 556 624 573 +886 556 593 575 +887 575 620 556 +888 556 620 590 +889 590 622 556 +890 557 623 570 +891 570 639 557 +892 557 592 571 +893 571 623 557 +894 557 591 574 +895 574 592 557 +896 557 639 591 +897 569 589 558 +898 558 615 569 +899 589 642 558 +900 599 615 558 +901 558 638 599 +902 603 638 558 +903 558 642 603 +904 559 588 568 +905 568 618 559 +906 559 641 588 +907 559 618 597 +908 597 637 559 +909 559 637 602 +910 602 641 559 +911 575 593 560 +912 560 616 575 +913 593 643 560 +914 594 633 560 +915 560 643 594 +916 598 616 560 +917 560 633 598 +918 561 592 574 +919 574 617 561 +920 561 644 592 +921 561 632 595 +922 595 644 561 +923 561 617 600 +924 600 632 561 +925 562 621 586 +926 586 627 562 +927 604 621 562 +928 562 635 604 +929 562 627 610 +930 610 635 562 +931 567 601 563 +932 563 605 567 +933 563 622 590 +934 590 634 563 +935 601 619 563 +936 563 634 605 +937 619 622 563 +938 587 626 564 +939 564 640 587 +940 564 635 596 +941 596 640 564 +942 564 626 604 +943 604 635 564 +944 565 629 581 +945 581 630 565 +946 565 608 607 +947 607 629 565 +948 565 630 608 +949 580 628 566 +950 566 631 580 +951 606 609 566 +952 566 628 606 +953 609 631 566 +954 567 636 591 +955 591 639 567 +956 567 639 601 +957 605 636 567 +958 588 647 568 +959 568 646 618 +960 625 646 568 +961 568 647 625 +962 569 645 587 +963 587 648 569 +964 569 648 589 +965 615 645 569 +966 570 640 596 +967 601 639 570 +968 623 640 570 +969 589 648 571 +970 572 619 610 +971 610 627 572 +972 572 622 619 +973 576 632 600 +974 598 633 577 +975 599 638 578 +976 579 637 597 +977 606 628 582 +978 583 631 609 +979 584 629 607 +980 608 630 585 +981 625 647 586 +982 586 647 627 +2 5 2 50 +983 40 660 1 +984 1 660 76 +985 4 658 40 +986 110 658 4 +987 67 659 6 +988 6 659 111 +989 14 661 101 +990 111 661 14 +991 658 660 40 +992 68 650 67 +993 650 659 67 +994 69 654 68 +995 68 654 650 +996 70 651 69 +997 651 654 69 +998 71 655 70 +999 70 655 651 +1000 72 649 71 +1001 649 655 71 +1002 73 656 72 +1003 72 656 649 +1004 74 652 73 +1005 652 656 73 +1006 75 657 74 +1007 74 657 652 +1008 76 653 75 +1009 653 657 75 +1010 76 660 653 +1011 101 650 102 +1012 101 661 650 +1013 102 654 103 +1014 650 654 102 +1015 103 651 104 +1016 103 654 651 +1017 104 655 105 +1018 651 655 104 +1019 105 649 106 +1020 105 655 649 +1021 106 656 107 +1022 649 656 106 +1023 107 652 108 +1024 107 656 652 +1025 108 657 109 +1026 652 657 108 +1027 109 653 110 +1028 109 657 653 +1029 653 658 110 +1030 659 661 111 +1031 650 661 659 +1032 653 660 658 +2 6 2 96 +1033 2 685 8 +1034 685 2 63 +1035 678 5 15 +1036 5 678 41 +1037 685 134 8 +1038 112 678 15 +1039 41 677 42 +1040 677 41 678 +1041 42 676 43 +1042 42 677 676 +1043 675 44 43 +1044 675 43 676 +1045 44 674 45 +1046 44 675 674 +1047 45 673 46 +1048 45 674 673 +1049 672 47 46 +1050 672 46 673 +1051 671 48 47 +1052 47 672 671 +1053 48 670 49 +1054 48 671 670 +1055 669 50 49 +1056 669 49 670 +1057 50 668 51 +1058 50 669 668 +1059 667 52 51 +1060 667 51 668 +1061 52 665 53 +1062 52 667 665 +1063 53 664 54 +1064 53 665 664 +1065 663 55 54 +1066 663 54 664 +1067 55 662 56 +1068 55 663 662 +1069 666 57 56 +1070 666 56 662 +1071 679 58 57 +1072 57 666 679 +1073 58 680 59 +1074 58 679 680 +1075 59 681 60 +1076 59 680 681 +1077 682 61 60 +1078 682 60 681 +1079 61 683 62 +1080 61 682 683 +1081 62 684 63 +1082 62 683 684 +1083 63 684 685 +1084 113 677 112 +1085 677 678 112 +1086 114 676 113 +1087 676 677 113 +1088 675 114 115 +1089 675 676 114 +1090 116 674 115 +1091 674 675 115 +1092 117 673 116 +1093 673 674 116 +1094 672 117 118 +1095 672 673 117 +1096 671 118 119 +1097 671 672 118 +1098 120 670 119 +1099 670 671 119 +1100 669 120 121 +1101 669 670 120 +1102 122 668 121 +1103 668 669 121 +1104 667 122 123 +1105 667 668 122 +1106 124 665 123 +1107 665 667 123 +1108 125 664 124 +1109 664 665 124 +1110 663 125 126 +1111 663 664 125 +1112 127 662 126 +1113 662 663 126 +1114 666 127 128 +1115 666 662 127 +1116 679 128 129 +1117 679 666 128 +1118 130 680 129 +1119 680 679 129 +1120 131 681 130 +1121 681 680 130 +1122 682 131 132 +1123 682 681 131 +1124 133 683 132 +1125 683 682 132 +1126 134 684 133 +1127 684 683 133 +1128 685 684 134 +2 7 2 32 +1129 64 686 5 +1130 686 135 5 +1131 691 66 6 +1132 111 691 6 +1133 687 98 13 +1134 135 687 13 +1135 100 690 14 +1136 690 111 14 +1137 65 696 64 +1138 688 686 64 +1139 696 688 64 +1140 695 65 66 +1141 695 696 65 +1142 691 689 66 +1143 689 695 66 +1144 693 99 98 +1145 687 688 98 +1146 688 693 98 +1147 99 694 100 +1148 693 694 99 +1149 689 690 100 +1150 694 689 100 +1151 691 111 690 +1152 687 135 686 +1153 686 688 687 +1154 693 688 692 +1155 688 696 692 +1156 690 689 691 +1157 689 694 692 +1158 695 689 692 +1159 692 694 693 +1160 692 696 695 +2 8 2 30 +1161 7 80 697 +1162 81 7 697 +1163 703 79 9 +1164 136 703 9 +1165 10 83 699 +1166 140 10 699 +1167 704 138 16 +1168 139 704 16 +1169 702 80 79 +1170 702 79 703 +1171 697 80 702 +1172 81 698 82 +1173 697 698 81 +1174 698 83 82 +1175 698 699 83 +1176 137 703 136 +1177 704 137 138 +1178 137 705 703 +1179 705 137 704 +1180 140 701 139 +1181 139 701 704 +1182 140 699 701 +1183 700 698 697 +1184 702 700 697 +1185 698 700 699 +1186 700 701 699 +1187 700 705 701 +1188 705 700 702 +1189 705 704 701 +1190 703 705 702 +2 9 2 94 +1191 10 722 84 +1192 140 722 10 +1193 93 723 11 +1194 11 723 152 +1195 16 725 139 +1196 141 725 16 +1197 17 724 150 +1198 151 724 17 +1199 84 730 85 +1200 722 730 84 +1201 85 712 86 +1202 85 730 712 +1203 86 726 87 +1204 712 726 86 +1205 87 717 88 +1206 87 726 717 +1207 88 714 89 +1208 88 732 714 +1209 717 732 88 +1210 89 728 90 +1211 714 728 89 +1212 90 718 91 +1213 90 728 718 +1214 91 715 92 +1215 91 733 715 +1216 718 733 91 +1217 92 736 93 +1218 715 736 92 +1219 93 736 723 +1220 139 738 140 +1221 725 738 139 +1222 140 738 722 +1223 142 731 141 +1224 141 731 725 +1225 143 713 142 +1226 713 731 142 +1227 144 727 143 +1228 143 727 713 +1229 145 720 144 +1230 720 727 144 +1231 146 719 145 +1232 719 734 145 +1233 145 734 720 +1234 147 729 146 +1235 146 729 719 +1236 148 721 147 +1237 721 729 147 +1238 149 716 148 +1239 716 735 148 +1240 148 735 721 +1241 150 737 149 +1242 149 737 716 +1243 724 737 150 +1244 152 739 151 +1245 151 739 724 +1246 723 739 152 +1247 706 713 712 +1248 712 730 706 +1249 706 731 713 +1250 706 730 722 +1251 722 738 706 +1252 725 731 706 +1253 706 738 725 +1254 715 716 707 +1255 707 736 715 +1256 716 737 707 +1257 723 736 707 +1258 707 739 723 +1259 707 737 724 +1260 724 739 707 +1261 712 713 708 +1262 708 726 712 +1263 713 727 708 +1264 708 720 717 +1265 717 726 708 +1266 708 727 720 +1267 714 719 709 +1268 709 728 714 +1269 709 721 718 +1270 718 728 709 +1271 719 729 709 +1272 709 729 721 +1273 710 719 714 +1274 714 732 710 +1275 717 720 710 +1276 710 732 717 +1277 710 734 719 +1278 720 734 710 +1279 711 716 715 +1280 715 733 711 +1281 711 735 716 +1282 718 721 711 +1283 711 733 718 +1284 721 735 711 +2 10 2 30 +1285 747 94 11 +1286 152 747 11 +1287 96 746 12 +1288 746 157 12 +1289 151 17 741 +1290 17 153 741 +1291 155 18 742 +1292 18 156 742 +1293 747 95 94 +1294 95 746 96 +1295 95 748 746 +1296 748 95 747 +1297 151 744 152 +1298 151 741 744 +1299 152 744 747 +1300 740 153 154 +1301 740 741 153 +1302 155 740 154 +1303 742 740 155 +1304 745 156 157 +1305 742 156 745 +1306 745 157 746 +1307 740 743 741 +1308 743 740 742 +1309 743 744 741 +1310 745 743 742 +1311 743 748 744 +1312 748 743 745 +1313 748 747 744 +1314 746 748 745 +2 11 2 18 +1315 5 751 15 +1316 135 749 5 +1317 749 751 5 +1318 12 750 97 +1319 157 750 12 +1320 97 752 13 +1321 13 752 135 +1322 15 751 158 +1323 18 753 156 +1324 158 753 18 +1325 750 752 97 +1326 135 752 749 +1327 156 749 157 +1328 156 753 749 +1329 749 750 157 +1330 751 753 158 +1331 749 752 750 +1332 749 753 751 +2 12 2 409 +1333 78 8 817 +1334 8 134 841 +1335 817 8 841 +1336 9 78 914 +1337 136 9 845 +1338 845 9 914 +1339 112 15 835 +1340 15 158 815 +1341 15 815 835 +1342 16 138 861 +1343 141 16 861 +1344 17 150 825 +1345 153 17 876 +1346 17 825 876 +1347 18 155 843 +1348 158 18 913 +1349 18 843 913 +1350 78 817 914 +1351 113 112 900 +1352 112 835 900 +1353 114 113 856 +1354 856 113 900 +1355 115 114 921 +1356 114 856 921 +1357 116 115 855 +1358 855 115 921 +1359 117 116 842 +1360 842 116 855 +1361 118 117 842 +1362 119 118 885 +1363 118 842 885 +1364 120 119 831 +1365 831 119 885 +1366 121 120 820 +1367 820 120 831 +1368 122 121 877 +1369 121 820 877 +1370 123 122 840 +1371 840 122 877 +1372 124 123 920 +1373 123 840 920 +1374 125 124 873 +1375 873 124 920 +1376 126 125 912 +1377 813 125 873 +1378 125 813 912 +1379 127 126 912 +1380 128 127 857 +1381 127 806 857 +1382 806 127 912 +1383 129 128 916 +1384 128 857 916 +1385 130 129 931 +1386 828 129 916 +1387 129 828 931 +1388 131 130 847 +1389 847 130 931 +1390 132 131 803 +1391 803 131 847 +1392 133 132 859 +1393 132 803 859 +1394 134 133 926 +1395 133 859 926 +1396 841 134 926 +1397 137 136 845 +1398 138 137 888 +1399 137 845 888 +1400 861 138 888 +1401 142 141 838 +1402 141 797 838 +1403 797 141 861 +1404 143 142 864 +1405 142 838 864 +1406 144 143 911 +1407 143 864 911 +1408 145 144 824 +1409 824 144 911 +1410 146 145 872 +1411 145 824 872 +1412 147 146 829 +1413 829 146 872 +1414 148 147 881 +1415 147 829 881 +1416 149 148 854 +1417 148 826 854 +1418 826 148 881 +1419 150 149 925 +1420 149 854 925 +1421 825 150 925 +1422 154 153 891 +1423 153 876 891 +1424 155 154 891 +1425 843 155 891 +1426 815 158 913 +1427 819 754 850 +1428 754 819 887 +1429 754 822 837 +1430 822 754 862 +1431 754 837 894 +1432 850 754 894 +1433 862 754 887 +1434 755 830 871 +1435 830 755 892 +1436 755 836 892 +1437 836 755 910 +1438 755 871 930 +1439 910 755 930 +1440 833 756 879 +1441 756 833 915 +1442 879 756 933 +1443 880 756 915 +1444 756 880 933 +1445 757 818 849 +1446 818 757 893 +1447 821 757 853 +1448 757 821 893 +1449 834 757 849 +1450 757 834 853 +1451 758 827 844 +1452 827 758 875 +1453 758 844 898 +1454 875 758 922 +1455 758 898 922 +1456 759 805 846 +1457 805 759 934 +1458 759 846 865 +1459 848 759 882 +1460 759 848 934 +1461 759 865 904 +1462 882 759 904 +1463 807 760 858 +1464 760 807 886 +1465 760 810 811 +1466 810 760 886 +1467 760 811 905 +1468 858 760 860 +1469 860 760 905 +1470 761 832 884 +1471 832 761 932 +1472 870 761 884 +1473 761 870 907 +1474 761 907 932 +1475 762 800 823 +1476 800 762 839 +1477 762 823 883 +1478 839 762 895 +1479 762 883 899 +1480 895 762 899 +1481 763 798 852 +1482 798 763 878 +1483 805 763 851 +1484 763 805 878 +1485 851 763 897 +1486 763 852 897 +1487 802 764 866 +1488 764 802 902 +1489 764 821 890 +1490 821 764 902 +1491 866 764 906 +1492 764 890 906 +1493 765 804 867 +1494 804 765 909 +1495 827 765 896 +1496 765 827 909 +1497 765 867 901 +1498 896 765 901 +1499 766 806 813 +1500 806 766 868 +1501 766 813 874 +1502 868 766 918 +1503 766 874 918 +1504 767 808 836 +1505 808 767 889 +1506 816 767 836 +1507 767 816 928 +1508 826 767 854 +1509 767 826 889 +1510 854 767 928 +1511 818 768 819 +1512 768 818 908 +1513 819 768 887 +1514 830 768 908 +1515 768 830 929 +1516 768 869 887 +1517 869 768 929 +1518 812 769 923 +1519 769 812 924 +1520 769 822 863 +1521 822 769 924 +1522 769 833 923 +1523 833 769 935 +1524 769 863 935 +1525 770 815 832 +1526 815 770 835 +1527 770 832 903 +1528 835 770 866 +1529 866 770 903 +1530 771 820 831 +1531 820 771 858 +1532 771 831 919 +1533 834 771 919 +1534 771 834 927 +1535 858 771 927 +1536 817 772 839 +1537 772 817 841 +1538 839 772 917 +1539 772 841 867 +1540 772 867 917 +1541 798 773 852 +1542 773 798 864 +1543 773 809 852 +1544 809 773 880 +1545 773 823 880 +1546 823 773 883 +1547 838 773 864 +1548 773 838 883 +1549 810 774 811 +1550 774 810 894 +1551 811 774 918 +1552 812 774 837 +1553 774 812 922 +1554 774 814 918 +1555 814 774 922 +1556 837 774 894 +1557 805 775 846 +1558 775 805 851 +1559 775 822 862 +1560 822 775 863 +1561 846 775 862 +1562 775 851 863 +1563 776 807 849 +1564 807 776 886 +1565 810 776 850 +1566 776 810 886 +1567 776 818 819 +1568 818 776 849 +1569 776 819 850 +1570 777 821 853 +1571 821 777 890 +1572 842 777 853 +1573 777 842 855 +1574 777 855 890 +1575 827 778 844 +1576 778 827 896 +1577 778 828 844 +1578 828 778 931 +1579 847 778 896 +1580 778 847 931 +1581 806 779 857 +1582 779 806 868 +1583 828 779 844 +1584 779 828 916 +1585 844 779 898 +1586 857 779 916 +1587 779 868 898 +1588 824 780 872 +1589 780 824 878 +1590 829 780 848 +1591 780 829 872 +1592 848 780 934 +1593 780 878 934 +1594 781 826 881 +1595 826 781 889 +1596 781 829 848 +1597 829 781 881 +1598 781 848 882 +1599 781 882 889 +1600 782 813 873 +1601 813 782 874 +1602 782 840 860 +1603 840 782 920 +1604 782 860 905 +1605 782 873 920 +1606 874 782 905 +1607 783 825 870 +1608 825 783 876 +1609 843 783 884 +1610 783 843 891 +1611 783 870 884 +1612 876 783 891 +1613 808 784 892 +1614 784 808 904 +1615 784 865 869 +1616 865 784 904 +1617 784 869 929 +1618 892 784 929 +1619 785 820 858 +1620 820 785 877 +1621 840 785 860 +1622 785 840 877 +1623 785 858 860 +1624 821 786 893 +1625 786 821 902 +1626 830 786 871 +1627 786 830 908 +1628 871 786 902 +1629 893 786 908 +1630 845 787 888 +1631 787 845 895 +1632 787 861 888 +1633 861 787 899 +1634 787 895 899 +1635 788 846 862 +1636 846 788 865 +1637 788 862 887 +1638 865 788 869 +1639 869 788 887 +1640 815 789 832 +1641 789 815 913 +1642 832 789 884 +1643 789 843 884 +1644 843 789 913 +1645 790 831 885 +1646 831 790 919 +1647 834 790 853 +1648 790 834 919 +1649 790 842 853 +1650 842 790 885 +1651 791 827 875 +1652 827 791 909 +1653 791 833 879 +1654 833 791 923 +1655 791 875 923 +1656 791 879 909 +1657 851 792 863 +1658 792 851 897 +1659 863 792 935 +1660 792 897 915 +1661 792 915 935 +1662 793 817 839 +1663 817 793 914 +1664 793 839 895 +1665 845 793 895 +1666 793 845 914 +1667 825 794 870 +1668 794 825 925 +1669 854 794 925 +1670 794 854 928 +1671 870 794 907 +1672 907 794 928 +1673 795 835 866 +1674 835 795 900 +1675 795 856 900 +1676 856 795 906 +1677 795 866 906 +1678 841 796 867 +1679 796 841 926 +1680 796 859 901 +1681 859 796 926 +1682 867 796 901 +1683 838 797 883 +1684 797 861 899 +1685 883 797 899 +1686 824 798 878 +1687 798 824 911 +1688 864 798 911 +1689 832 799 903 +1690 799 832 932 +1691 903 799 930 +1692 799 910 930 +1693 910 799 932 +1694 823 800 880 +1695 800 839 917 +1696 880 800 933 +1697 800 917 933 +1698 855 801 890 +1699 801 855 921 +1700 801 856 906 +1701 856 801 921 +1702 890 801 906 +1703 802 866 903 +1704 802 871 902 +1705 871 802 930 +1706 802 903 930 +1707 803 847 896 +1708 859 803 901 +1709 803 896 901 +1710 867 804 917 +1711 879 804 909 +1712 804 879 933 +1713 917 804 933 +1714 878 805 934 +1715 813 806 912 +1716 849 807 927 +1717 807 858 927 +1718 836 808 892 +1719 882 808 889 +1720 808 882 904 +1721 852 809 897 +1722 809 880 915 +1723 897 809 915 +1724 810 850 894 +1725 811 874 905 +1726 874 811 918 +1727 812 837 924 +1728 812 875 922 +1729 875 812 923 +1730 868 814 898 +1731 814 868 918 +1732 898 814 922 +1733 816 836 910 +1734 816 907 928 +1735 907 816 932 +1736 816 910 932 +1737 818 893 908 +1738 837 822 924 +1739 830 892 929 +1740 915 833 935 +1741 834 849 927 +2 13 2 194 +1742 949 136 9 +1743 159 949 9 +1744 138 942 16 +1745 942 184 16 +1746 938 180 19 +1747 183 938 19 +1748 948 181 20 +1749 205 948 20 +1750 949 137 136 +1751 137 942 138 +1752 942 137 941 +1753 137 949 941 +1754 1006 159 160 +1755 949 159 1005 +1756 1005 159 1006 +1757 955 160 161 +1758 1006 160 955 +1759 961 161 162 +1760 955 161 961 +1761 1002 162 163 +1762 961 162 1002 +1763 1001 163 164 +1764 1002 163 1001 +1765 996 164 165 +1766 1001 164 996 +1767 995 165 166 +1768 996 165 995 +1769 990 166 167 +1770 995 166 990 +1771 987 167 168 +1772 990 167 987 +1773 984 168 169 +1774 987 168 984 +1775 981 169 170 +1776 984 169 981 +1777 980 170 171 +1778 981 170 980 +1779 974 171 172 +1780 980 171 974 +1781 971 172 173 +1782 974 172 971 +1783 968 173 174 +1784 971 173 968 +1785 965 174 175 +1786 968 174 965 +1787 964 175 176 +1788 965 175 964 +1789 956 176 177 +1790 964 176 956 +1791 950 177 178 +1792 956 177 950 +1793 946 178 179 +1794 950 178 946 +1795 180 936 179 +1796 179 936 946 +1797 180 938 936 +1798 948 182 181 +1799 182 938 183 +1800 938 182 937 +1801 182 948 937 +1802 184 940 185 +1803 184 942 940 +1804 944 186 185 +1805 185 940 944 +1806 953 187 186 +1807 953 186 944 +1808 959 188 187 +1809 959 187 953 +1810 1003 189 188 +1811 1003 188 959 +1812 999 190 189 +1813 999 189 1003 +1814 998 191 190 +1815 998 190 999 +1816 993 192 191 +1817 993 191 998 +1818 992 193 192 +1819 992 192 993 +1820 989 194 193 +1821 989 193 992 +1822 986 195 194 +1823 986 194 989 +1824 983 196 195 +1825 983 195 986 +1826 978 197 196 +1827 978 196 983 +1828 977 198 197 +1829 977 197 978 +1830 973 199 198 +1831 973 198 977 +1832 970 200 199 +1833 970 199 973 +1834 967 201 200 +1835 967 200 970 +1836 962 202 201 +1837 962 201 967 +1838 958 203 202 +1839 958 202 962 +1840 952 204 203 +1841 952 203 958 +1842 976 205 204 +1843 976 204 952 +1844 948 205 1004 +1845 1004 205 976 +1846 936 938 937 +1847 937 939 936 +1848 936 939 946 +1849 939 937 1004 +1850 948 1004 937 +1851 947 946 939 +1852 976 947 939 +1853 976 939 1004 +1854 940 942 941 +1855 941 943 940 +1856 940 943 944 +1857 943 941 1005 +1858 949 1005 941 +1859 945 944 943 +1860 1006 945 943 +1861 1006 943 1005 +1862 944 945 953 +1863 953 945 954 +1864 945 955 954 +1865 955 945 1006 +1866 946 947 950 +1867 950 947 951 +1868 947 952 951 +1869 952 947 976 +1870 950 951 956 +1871 958 951 952 +1872 956 951 957 +1873 951 958 957 +1874 953 954 959 +1875 961 954 955 +1876 959 954 960 +1877 954 961 960 +1878 956 957 964 +1879 962 957 958 +1880 962 963 957 +1881 963 964 957 +1882 959 960 1003 +1883 1002 960 961 +1884 1002 1000 960 +1885 1000 1003 960 +1886 967 963 962 +1887 964 963 965 +1888 965 963 966 +1889 963 967 966 +1890 965 966 968 +1891 970 966 967 +1892 968 966 969 +1893 966 970 969 +1894 968 969 971 +1895 973 969 970 +1896 971 969 972 +1897 969 973 972 +1898 971 972 974 +1899 977 972 973 +1900 974 972 975 +1901 972 977 975 +1902 974 975 980 +1903 978 975 977 +1904 978 979 975 +1905 979 980 975 +1906 983 979 978 +1907 980 979 981 +1908 981 979 982 +1909 979 983 982 +1910 981 982 984 +1911 986 982 983 +1912 984 982 985 +1913 982 986 985 +1914 984 985 987 +1915 989 985 986 +1916 987 985 988 +1917 985 989 988 +1918 987 988 990 +1919 992 988 989 +1920 990 988 991 +1921 988 992 991 +1922 990 991 995 +1923 993 991 992 +1924 993 994 991 +1925 994 995 991 +1926 998 994 993 +1927 995 994 996 +1928 996 994 997 +1929 994 998 997 +1930 996 997 1001 +1931 999 997 998 +1932 999 1000 997 +1933 1000 1001 997 +1934 1003 1000 999 +1935 1001 1000 1002 +2 14 2 670 +1936 16 1279 141 +1937 184 1279 16 +1938 150 1280 17 +1939 17 1280 216 +1940 20 1278 205 +1941 215 1278 20 +1942 21 1277 206 +1943 237 1277 21 +1944 141 1186 142 +1945 1121 1186 141 +1946 141 1279 1121 +1947 142 1186 143 +1948 143 1207 144 +1949 143 1186 1093 +1950 1093 1207 143 +1951 144 1151 145 +1952 144 1207 1151 +1953 145 1090 146 +1954 145 1151 1090 +1955 146 1150 147 +1956 1090 1150 146 +1957 147 1206 148 +1958 1150 1206 147 +1959 148 1187 149 +1960 1094 1187 148 +1961 148 1206 1094 +1962 149 1187 150 +1963 150 1187 1122 +1964 1122 1280 150 +1965 185 1291 184 +1966 184 1291 1279 +1967 186 1161 185 +1968 1161 1291 185 +1969 187 1303 186 +1970 186 1303 1161 +1971 188 1262 187 +1972 187 1262 1179 +1973 1179 1303 187 +1974 189 1298 188 +1975 1117 1262 188 +1976 188 1298 1117 +1977 190 1237 189 +1978 1237 1298 189 +1979 191 1146 190 +1980 1146 1237 190 +1981 192 1283 191 +1982 191 1283 1146 +1983 193 1142 192 +1984 1142 1283 192 +1985 194 1256 193 +1986 193 1256 1142 +1987 195 1209 194 +1988 1209 1256 194 +1989 196 1251 195 +1990 195 1251 1209 +1991 197 1236 196 +1992 196 1236 1140 +1993 1140 1251 196 +1994 198 1285 197 +1995 197 1285 1236 +1996 199 1147 198 +1997 1147 1285 198 +1998 200 1238 199 +1999 199 1238 1147 +2000 201 1297 200 +2001 200 1297 1238 +2002 202 1263 201 +2003 201 1263 1118 +2004 1118 1297 201 +2005 203 1302 202 +2006 1177 1263 202 +2007 202 1302 1177 +2008 204 1164 203 +2009 1164 1302 203 +2010 205 1290 204 +2011 204 1290 1164 +2012 1278 1290 205 +2013 206 1189 207 +2014 1120 1189 206 +2015 206 1277 1120 +2016 207 1189 208 +2017 208 1204 209 +2018 208 1189 1096 +2019 1096 1204 208 +2020 209 1148 210 +2021 209 1204 1148 +2022 210 1091 211 +2023 210 1148 1091 +2024 211 1149 212 +2025 1091 1149 211 +2026 212 1205 213 +2027 1149 1205 212 +2028 213 1188 214 +2029 1095 1188 213 +2030 213 1205 1095 +2031 214 1188 215 +2032 215 1188 1119 +2033 1119 1278 215 +2034 216 1292 217 +2035 1280 1292 216 +2036 217 1162 218 +2037 217 1292 1162 +2038 218 1304 219 +2039 1162 1304 218 +2040 219 1260 220 +2041 1178 1260 219 +2042 219 1304 1178 +2043 220 1300 221 +2044 220 1260 1116 +2045 1116 1300 220 +2046 221 1239 222 +2047 221 1300 1239 +2048 222 1144 223 +2049 222 1239 1144 +2050 223 1284 224 +2051 1144 1284 223 +2052 224 1141 225 +2053 224 1284 1141 +2054 225 1257 226 +2055 1141 1257 225 +2056 226 1210 227 +2057 226 1257 1210 +2058 227 1252 228 +2059 1210 1252 227 +2060 228 1235 229 +2061 1139 1235 228 +2062 228 1252 1139 +2063 229 1286 230 +2064 1235 1286 229 +2065 230 1145 231 +2066 230 1286 1145 +2067 231 1240 232 +2068 1145 1240 231 +2069 232 1299 233 +2070 1240 1299 232 +2071 233 1261 234 +2072 1115 1261 233 +2073 233 1299 1115 +2074 234 1301 235 +2075 234 1261 1176 +2076 1176 1301 234 +2077 235 1163 236 +2078 235 1301 1163 +2079 236 1293 237 +2080 1163 1293 236 +2081 237 1293 1277 +2082 1007 1208 1113 +2083 1113 1282 1007 +2084 1007 1244 1125 +2085 1125 1250 1007 +2086 1143 1244 1007 +2087 1007 1282 1143 +2088 1007 1250 1208 +2089 1008 1135 1107 +2090 1107 1272 1008 +2091 1008 1255 1123 +2092 1123 1294 1008 +2093 1008 1294 1135 +2094 1008 1272 1255 +2095 1114 1184 1009 +2096 1009 1190 1114 +2097 1124 1203 1009 +2098 1009 1220 1124 +2099 1184 1220 1009 +2100 1009 1203 1190 +2101 1010 1128 1079 +2102 1079 1241 1010 +2103 1100 1128 1010 +2104 1010 1159 1100 +2105 1103 1156 1010 +2106 1010 1241 1103 +2107 1156 1159 1010 +2108 1081 1126 1011 +2109 1011 1194 1081 +2110 1011 1138 1102 +2111 1102 1266 1011 +2112 1126 1281 1011 +2113 1011 1281 1138 +2114 1011 1266 1194 +2115 1012 1108 1080 +2116 1080 1170 1012 +2117 1099 1104 1012 +2118 1012 1170 1099 +2119 1104 1242 1012 +2120 1012 1273 1108 +2121 1242 1273 1012 +2122 1013 1129 1073 +2123 1073 1222 1013 +2124 1101 1129 1013 +2125 1013 1165 1101 +2126 1105 1137 1013 +2127 1013 1222 1105 +2128 1137 1165 1013 +2129 1097 1191 1014 +2130 1014 1234 1097 +2131 1014 1228 1133 +2132 1133 1234 1014 +2133 1014 1211 1153 +2134 1153 1228 1014 +2135 1191 1211 1014 +2136 1085 1154 1015 +2137 1015 1171 1085 +2138 1098 1171 1015 +2139 1015 1229 1098 +2140 1015 1225 1134 +2141 1134 1229 1015 +2142 1154 1225 1015 +2143 1016 1152 1110 +2144 1110 1200 1016 +2145 1016 1219 1132 +2146 1132 1227 1016 +2147 1016 1227 1152 +2148 1200 1275 1016 +2149 1016 1275 1219 +2150 1017 1218 1131 +2151 1131 1226 1017 +2152 1017 1226 1155 +2153 1155 1230 1017 +2154 1017 1230 1199 +2155 1199 1274 1017 +2156 1017 1274 1218 +2157 1111 1202 1018 +2158 1018 1233 1111 +2159 1018 1214 1130 +2160 1130 1216 1018 +2161 1202 1214 1018 +2162 1216 1233 1018 +2163 1019 1196 1112 +2164 1112 1232 1019 +2165 1136 1182 1019 +2166 1019 1217 1136 +2167 1182 1196 1019 +2168 1019 1232 1217 +2169 1109 1175 1020 +2170 1020 1183 1109 +2171 1166 1223 1020 +2172 1020 1296 1166 +2173 1175 1296 1020 +2174 1020 1223 1183 +2175 1021 1245 1169 +2176 1169 1287 1021 +2177 1172 1224 1021 +2178 1021 1287 1172 +2179 1021 1224 1174 +2180 1174 1245 1021 +2181 1022 1198 1160 +2182 1160 1265 1022 +2183 1168 1198 1022 +2184 1022 1254 1168 +2185 1195 1254 1022 +2186 1022 1265 1195 +2187 1167 1215 1023 +2188 1023 1288 1167 +2189 1023 1231 1173 +2190 1173 1288 1023 +2191 1023 1215 1185 +2192 1185 1231 1023 +2193 1024 1192 1091 +2194 1091 1212 1024 +2195 1024 1181 1098 +2196 1098 1192 1024 +2197 1157 1181 1024 +2198 1024 1212 1157 +2199 1025 1193 1090 +2200 1090 1213 1025 +2201 1025 1180 1097 +2202 1097 1193 1025 +2203 1158 1180 1025 +2204 1025 1213 1158 +2205 1026 1126 1081 +2206 1081 1247 1026 +2207 1101 1243 1026 +2208 1026 1247 1101 +2209 1026 1243 1107 +2210 1107 1246 1026 +2211 1026 1246 1126 +2212 1080 1108 1027 +2213 1027 1248 1080 +2214 1027 1128 1100 +2215 1100 1248 1027 +2216 1108 1253 1027 +2217 1125 1221 1027 +2218 1027 1253 1125 +2219 1027 1221 1128 +2220 1028 1103 1086 +2221 1086 1142 1028 +2222 1028 1156 1103 +2223 1130 1156 1028 +2224 1028 1264 1130 +2225 1142 1264 1028 +2226 1087 1102 1029 +2227 1029 1236 1087 +2228 1102 1138 1029 +2229 1029 1138 1111 +2230 1111 1308 1029 +2231 1140 1236 1029 +2232 1029 1308 1140 +2233 1088 1104 1030 +2234 1030 1141 1088 +2235 1030 1104 1099 +2236 1099 1136 1030 +2237 1136 1276 1030 +2238 1030 1276 1141 +2239 1031 1105 1089 +2240 1089 1235 1031 +2241 1031 1137 1105 +2242 1112 1137 1031 +2243 1031 1232 1112 +2244 1139 1232 1031 +2245 1031 1235 1139 +2246 1100 1159 1032 +2247 1032 1248 1100 +2248 1032 1127 1123 +2249 1123 1201 1032 +2250 1032 1289 1127 +2251 1159 1289 1032 +2252 1201 1248 1032 +2253 1033 1129 1101 +2254 1101 1247 1033 +2255 1033 1197 1124 +2256 1124 1220 1033 +2257 1033 1220 1129 +2258 1033 1247 1197 +2259 1086 1103 1034 +2260 1034 1146 1086 +2261 1103 1241 1034 +2262 1034 1268 1146 +2263 1034 1241 1167 +2264 1167 1268 1034 +2265 1035 1168 1078 +2266 1078 1242 1035 +2267 1035 1104 1088 +2268 1088 1144 1035 +2269 1035 1242 1104 +2270 1144 1269 1035 +2271 1035 1269 1168 +2272 1089 1105 1036 +2273 1036 1145 1089 +2274 1105 1222 1036 +2275 1036 1270 1145 +2276 1036 1222 1166 +2277 1166 1270 1036 +2278 1037 1102 1087 +2279 1087 1147 1037 +2280 1037 1169 1092 +2281 1092 1266 1037 +2282 1037 1266 1102 +2283 1147 1267 1037 +2284 1037 1267 1169 +2285 1038 1132 1093 +2286 1093 1186 1038 +2287 1121 1161 1038 +2288 1038 1186 1121 +2289 1038 1227 1132 +2290 1161 1227 1038 +2291 1094 1133 1039 +2292 1039 1187 1094 +2293 1039 1162 1122 +2294 1122 1187 1039 +2295 1133 1228 1039 +2296 1039 1228 1162 +2297 1095 1134 1040 +2298 1040 1188 1095 +2299 1040 1164 1119 +2300 1119 1188 1040 +2301 1134 1225 1040 +2302 1040 1225 1164 +2303 1041 1131 1096 +2304 1096 1189 1041 +2305 1120 1163 1041 +2306 1041 1189 1120 +2307 1041 1226 1131 +2308 1163 1226 1041 +2309 1084 1182 1042 +2310 1042 1255 1084 +2311 1042 1201 1123 +2312 1123 1255 1042 +2313 1170 1201 1042 +2314 1042 1307 1170 +2315 1182 1307 1042 +2316 1043 1155 1077 +2317 1077 1176 1043 +2318 1043 1175 1109 +2319 1109 1230 1043 +2320 1115 1175 1043 +2321 1043 1261 1115 +2322 1043 1230 1155 +2323 1176 1261 1043 +2324 1074 1154 1044 +2325 1044 1177 1074 +2326 1044 1154 1085 +2327 1085 1172 1044 +2328 1044 1172 1118 +2329 1118 1263 1044 +2330 1044 1263 1177 +2331 1045 1152 1075 +2332 1075 1179 1045 +2333 1110 1152 1045 +2334 1045 1173 1110 +2335 1117 1173 1045 +2336 1045 1262 1117 +2337 1179 1262 1045 +2338 1076 1153 1046 +2339 1046 1178 1076 +2340 1046 1198 1116 +2341 1116 1260 1046 +2342 1153 1211 1046 +2343 1160 1198 1046 +2344 1046 1211 1160 +2345 1046 1260 1178 +2346 1047 1196 1084 +2347 1084 1272 1047 +2348 1107 1243 1047 +2349 1047 1272 1107 +2350 1047 1137 1112 +2351 1112 1196 1047 +2352 1047 1165 1137 +2353 1047 1243 1165 +2354 1048 1202 1111 +2355 1111 1281 1048 +2356 1126 1246 1048 +2357 1048 1281 1126 +2358 1048 1246 1135 +2359 1135 1305 1048 +2360 1048 1305 1202 +2361 1049 1194 1092 +2362 1092 1245 1049 +2363 1124 1197 1049 +2364 1049 1203 1124 +2365 1174 1203 1049 +2366 1049 1245 1174 +2367 1049 1197 1194 +2368 1050 1171 1098 +2369 1098 1181 1050 +2370 1050 1181 1114 +2371 1114 1190 1050 +2372 1050 1295 1171 +2373 1190 1295 1050 +2374 1097 1180 1051 +2375 1051 1191 1097 +2376 1051 1180 1113 +2377 1113 1208 1051 +2378 1051 1249 1191 +2379 1208 1249 1051 +2380 1109 1183 1052 +2381 1052 1230 1109 +2382 1183 1184 1052 +2383 1184 1259 1052 +2384 1199 1230 1052 +2385 1052 1259 1199 +2386 1053 1200 1110 +2387 1110 1231 1053 +2388 1053 1185 1143 +2389 1143 1282 1053 +2390 1053 1231 1185 +2391 1053 1258 1200 +2392 1053 1282 1258 +2393 1093 1132 1054 +2394 1054 1207 1093 +2395 1132 1219 1054 +2396 1151 1207 1054 +2397 1054 1213 1151 +2398 1158 1213 1054 +2399 1054 1219 1158 +2400 1096 1131 1055 +2401 1055 1204 1096 +2402 1131 1218 1055 +2403 1148 1204 1055 +2404 1055 1212 1148 +2405 1157 1212 1055 +2406 1055 1218 1157 +2407 1056 1133 1094 +2408 1094 1206 1056 +2409 1056 1193 1097 +2410 1097 1234 1056 +2411 1056 1234 1133 +2412 1150 1193 1056 +2413 1056 1206 1150 +2414 1057 1134 1095 +2415 1095 1205 1057 +2416 1057 1192 1098 +2417 1098 1229 1057 +2418 1057 1229 1134 +2419 1149 1192 1057 +2420 1057 1205 1149 +2421 1078 1254 1058 +2422 1058 1273 1078 +2423 1058 1195 1106 +2424 1106 1250 1058 +2425 1058 1253 1108 +2426 1108 1273 1058 +2427 1058 1250 1125 +2428 1125 1253 1058 +2429 1058 1254 1195 +2430 1079 1128 1059 +2431 1059 1215 1079 +2432 1128 1221 1059 +2433 1143 1185 1059 +2434 1059 1244 1143 +2435 1185 1215 1059 +2436 1221 1244 1059 +2437 1060 1156 1130 +2438 1130 1214 1060 +2439 1060 1159 1156 +2440 1060 1289 1159 +2441 1214 1306 1060 +2442 1060 1306 1289 +2443 1061 1184 1183 +2444 1183 1223 1061 +2445 1061 1220 1184 +2446 1061 1271 1220 +2447 1223 1271 1061 +2448 1062 1224 1085 +2449 1085 1295 1062 +2450 1062 1203 1174 +2451 1174 1224 1062 +2452 1190 1203 1062 +2453 1062 1295 1190 +2454 1063 1249 1106 +2455 1106 1265 1063 +2456 1160 1211 1063 +2457 1063 1265 1160 +2458 1063 1211 1191 +2459 1191 1249 1063 +2460 1114 1181 1064 +2461 1064 1259 1114 +2462 1064 1181 1157 +2463 1157 1274 1064 +2464 1199 1259 1064 +2465 1064 1274 1199 +2466 1113 1180 1065 +2467 1065 1258 1113 +2468 1065 1180 1158 +2469 1158 1275 1065 +2470 1200 1258 1065 +2471 1065 1275 1200 +2472 1066 1251 1140 +2473 1140 1308 1066 +2474 1066 1216 1209 +2475 1209 1251 1066 +2476 1066 1233 1216 +2477 1066 1308 1233 +2478 1067 1232 1139 +2479 1139 1252 1067 +2480 1210 1217 1067 +2481 1067 1252 1210 +2482 1217 1232 1067 +2483 1068 1296 1115 +2484 1115 1299 1068 +2485 1068 1270 1166 +2486 1166 1296 1068 +2487 1240 1270 1068 +2488 1068 1299 1240 +2489 1116 1198 1069 +2490 1069 1300 1116 +2491 1069 1198 1168 +2492 1168 1269 1069 +2493 1069 1269 1239 +2494 1239 1300 1069 +2495 1070 1288 1117 +2496 1117 1298 1070 +2497 1070 1268 1167 +2498 1167 1288 1070 +2499 1237 1268 1070 +2500 1070 1298 1237 +2501 1118 1287 1071 +2502 1071 1297 1118 +2503 1169 1267 1071 +2504 1071 1287 1169 +2505 1071 1267 1238 +2506 1238 1297 1071 +2507 1072 1214 1202 +2508 1202 1305 1072 +2509 1072 1306 1214 +2510 1072 1305 1294 +2511 1294 1306 1072 +2512 1129 1271 1073 +2513 1166 1222 1073 +2514 1073 1223 1166 +2515 1073 1271 1223 +2516 1074 1225 1154 +2517 1164 1225 1074 +2518 1074 1302 1164 +2519 1177 1302 1074 +2520 1152 1227 1075 +2521 1075 1227 1161 +2522 1161 1303 1075 +2523 1075 1303 1179 +2524 1076 1228 1153 +2525 1162 1228 1076 +2526 1076 1304 1162 +2527 1178 1304 1076 +2528 1155 1226 1077 +2529 1077 1226 1163 +2530 1163 1301 1077 +2531 1077 1301 1176 +2532 1168 1254 1078 +2533 1078 1273 1242 +2534 1079 1215 1167 +2535 1167 1241 1079 +2536 1080 1201 1170 +2537 1080 1248 1201 +2538 1194 1197 1081 +2539 1197 1247 1081 +2540 1142 1256 1082 +2541 1082 1264 1142 +2542 1209 1216 1082 +2543 1082 1256 1209 +2544 1216 1264 1082 +2545 1083 1257 1141 +2546 1141 1276 1083 +2547 1083 1217 1210 +2548 1210 1257 1083 +2549 1083 1276 1217 +2550 1084 1196 1182 +2551 1255 1272 1084 +2552 1171 1295 1085 +2553 1085 1224 1172 +2554 1086 1283 1142 +2555 1146 1283 1086 +2556 1087 1285 1147 +2557 1236 1285 1087 +2558 1141 1284 1088 +2559 1088 1284 1144 +2560 1145 1286 1089 +2561 1089 1286 1235 +2562 1090 1193 1150 +2563 1151 1213 1090 +2564 1148 1212 1091 +2565 1091 1192 1149 +2566 1169 1245 1092 +2567 1194 1266 1092 +2568 1099 1307 1136 +2569 1170 1307 1099 +2570 1165 1243 1101 +2571 1195 1265 1106 +2572 1106 1249 1208 +2573 1208 1250 1106 +2574 1135 1246 1107 +2575 1173 1231 1110 +2576 1138 1281 1111 +2577 1233 1308 1111 +2578 1258 1282 1113 +2579 1114 1259 1184 +2580 1115 1296 1175 +2581 1117 1288 1173 +2582 1172 1287 1118 +2583 1164 1290 1119 +2584 1119 1290 1278 +2585 1120 1293 1163 +2586 1277 1293 1120 +2587 1121 1291 1161 +2588 1279 1291 1121 +2589 1162 1292 1122 +2590 1122 1292 1280 +2591 1127 1294 1123 +2592 1125 1244 1221 +2593 1289 1306 1127 +2594 1127 1306 1294 +2595 1220 1271 1129 +2596 1130 1264 1216 +2597 1294 1305 1135 +2598 1136 1307 1182 +2599 1217 1276 1136 +2600 1239 1269 1144 +2601 1145 1270 1240 +2602 1146 1268 1237 +2603 1238 1267 1147 +2604 1218 1274 1157 +2605 1219 1275 1158 +2 15 2 194 +2606 1322 153 17 +2607 216 1322 17 +2608 155 1315 18 +2609 1315 241 18 +2610 1311 237 21 +2611 240 1311 21 +2612 1321 238 22 +2613 262 1321 22 +2614 1322 154 153 +2615 154 1315 155 +2616 1315 154 1314 +2617 154 1322 1314 +2618 1379 216 217 +2619 1322 216 1378 +2620 1378 216 1379 +2621 1328 217 218 +2622 1379 217 1328 +2623 1334 218 219 +2624 1328 218 1334 +2625 1376 219 220 +2626 1334 219 1376 +2627 1372 220 221 +2628 1376 220 1372 +2629 1371 221 222 +2630 1372 221 1371 +2631 1366 222 223 +2632 1371 222 1366 +2633 1365 223 224 +2634 1366 223 1365 +2635 1360 224 225 +2636 1365 224 1360 +2637 1357 225 226 +2638 1360 225 1357 +2639 1354 226 227 +2640 1357 226 1354 +2641 1353 227 228 +2642 1354 227 1353 +2643 1347 228 229 +2644 1353 228 1347 +2645 1344 229 230 +2646 1347 229 1344 +2647 1341 230 231 +2648 1344 230 1341 +2649 1340 231 232 +2650 1341 231 1340 +2651 1335 232 233 +2652 1340 232 1335 +2653 1329 233 234 +2654 1335 233 1329 +2655 1323 234 235 +2656 1329 234 1323 +2657 1319 235 236 +2658 1323 235 1319 +2659 237 1309 236 +2660 236 1309 1319 +2661 237 1311 1309 +2662 1321 239 238 +2663 239 1311 240 +2664 1311 239 1310 +2665 239 1321 1310 +2666 241 1313 242 +2667 241 1315 1313 +2668 1317 243 242 +2669 242 1313 1317 +2670 1326 244 243 +2671 1326 243 1317 +2672 1332 245 244 +2673 1332 244 1326 +2674 1375 246 245 +2675 1375 245 1332 +2676 1374 247 246 +2677 1374 246 1375 +2678 1369 248 247 +2679 1369 247 1374 +2680 1368 249 248 +2681 1368 248 1369 +2682 1363 250 249 +2683 1363 249 1368 +2684 1362 251 250 +2685 1362 250 1363 +2686 1359 252 251 +2687 1359 251 1362 +2688 1356 253 252 +2689 1356 252 1359 +2690 1351 254 253 +2691 1351 253 1356 +2692 1350 255 254 +2693 1350 254 1351 +2694 1346 256 255 +2695 1346 255 1350 +2696 1343 257 256 +2697 1343 256 1346 +2698 1338 258 257 +2699 1338 257 1343 +2700 1337 259 258 +2701 1337 258 1338 +2702 1331 260 259 +2703 1331 259 1337 +2704 1325 261 260 +2705 1325 260 1331 +2706 1349 262 261 +2707 1349 261 1325 +2708 1321 262 1377 +2709 1377 262 1349 +2710 1309 1311 1310 +2711 1310 1312 1309 +2712 1309 1312 1319 +2713 1312 1310 1377 +2714 1321 1377 1310 +2715 1320 1319 1312 +2716 1349 1320 1312 +2717 1349 1312 1377 +2718 1313 1315 1314 +2719 1314 1316 1313 +2720 1313 1316 1317 +2721 1316 1314 1378 +2722 1322 1378 1314 +2723 1318 1317 1316 +2724 1379 1318 1316 +2725 1379 1316 1378 +2726 1317 1318 1326 +2727 1326 1318 1327 +2728 1318 1328 1327 +2729 1328 1318 1379 +2730 1319 1320 1323 +2731 1323 1320 1324 +2732 1320 1325 1324 +2733 1325 1320 1349 +2734 1323 1324 1329 +2735 1331 1324 1325 +2736 1329 1324 1330 +2737 1324 1331 1330 +2738 1326 1327 1332 +2739 1334 1327 1328 +2740 1332 1327 1333 +2741 1327 1334 1333 +2742 1329 1330 1335 +2743 1337 1330 1331 +2744 1335 1330 1336 +2745 1330 1337 1336 +2746 1332 1333 1375 +2747 1376 1333 1334 +2748 1375 1333 1373 +2749 1333 1376 1373 +2750 1335 1336 1340 +2751 1338 1336 1337 +2752 1338 1339 1336 +2753 1339 1340 1336 +2754 1343 1339 1338 +2755 1340 1339 1341 +2756 1341 1339 1342 +2757 1339 1343 1342 +2758 1341 1342 1344 +2759 1346 1342 1343 +2760 1344 1342 1345 +2761 1342 1346 1345 +2762 1344 1345 1347 +2763 1350 1345 1346 +2764 1347 1345 1348 +2765 1345 1350 1348 +2766 1347 1348 1353 +2767 1351 1348 1350 +2768 1351 1352 1348 +2769 1352 1353 1348 +2770 1356 1352 1351 +2771 1353 1352 1354 +2772 1354 1352 1355 +2773 1352 1356 1355 +2774 1354 1355 1357 +2775 1359 1355 1356 +2776 1357 1355 1358 +2777 1355 1359 1358 +2778 1357 1358 1360 +2779 1362 1358 1359 +2780 1360 1358 1361 +2781 1358 1362 1361 +2782 1360 1361 1365 +2783 1363 1361 1362 +2784 1363 1364 1361 +2785 1364 1365 1361 +2786 1368 1364 1363 +2787 1365 1364 1366 +2788 1366 1364 1367 +2789 1364 1368 1367 +2790 1366 1367 1371 +2791 1369 1367 1368 +2792 1369 1370 1367 +2793 1370 1371 1367 +2794 1374 1370 1369 +2795 1371 1370 1372 +2796 1372 1370 1373 +2797 1370 1374 1373 +2798 1372 1373 1376 +2799 1375 1373 1374 +2 16 2 98 +2800 158 1404 15 +2801 15 1404 264 +2802 18 1402 158 +2803 241 1402 18 +2804 22 1401 262 +2805 263 1401 22 +2806 23 1403 263 +2807 285 1403 23 +2808 1402 1404 158 +2809 242 1391 241 +2810 1391 1402 241 +2811 243 1380 242 +2812 1380 1391 242 +2813 244 1392 243 +2814 243 1392 1380 +2815 245 1388 244 +2816 1388 1392 244 +2817 246 1393 245 +2818 245 1393 1388 +2819 247 1389 246 +2820 1389 1393 246 +2821 248 1394 247 +2822 247 1394 1389 +2823 249 1381 248 +2824 1381 1394 248 +2825 250 1395 249 +2826 249 1395 1381 +2827 251 1382 250 +2828 1382 1395 250 +2829 252 1396 251 +2830 251 1396 1382 +2831 253 1383 252 +2832 1383 1396 252 +2833 254 1397 253 +2834 253 1397 1383 +2835 255 1384 254 +2836 1384 1397 254 +2837 256 1398 255 +2838 255 1398 1384 +2839 257 1385 256 +2840 1385 1398 256 +2841 258 1399 257 +2842 257 1399 1385 +2843 259 1386 258 +2844 1386 1399 258 +2845 260 1400 259 +2846 259 1400 1386 +2847 261 1387 260 +2848 1387 1400 260 +2849 262 1390 261 +2850 261 1390 1387 +2851 262 1401 1390 +2852 263 1403 1401 +2853 264 1391 265 +2854 264 1404 1391 +2855 265 1380 266 +2856 265 1391 1380 +2857 266 1392 267 +2858 1380 1392 266 +2859 267 1388 268 +2860 267 1392 1388 +2861 268 1393 269 +2862 1388 1393 268 +2863 269 1389 270 +2864 269 1393 1389 +2865 270 1394 271 +2866 1389 1394 270 +2867 271 1381 272 +2868 271 1394 1381 +2869 272 1395 273 +2870 1381 1395 272 +2871 273 1382 274 +2872 273 1395 1382 +2873 274 1396 275 +2874 1382 1396 274 +2875 275 1383 276 +2876 275 1396 1383 +2877 276 1397 277 +2878 1383 1397 276 +2879 277 1384 278 +2880 277 1397 1384 +2881 278 1398 279 +2882 1384 1398 278 +2883 279 1385 280 +2884 279 1398 1385 +2885 280 1399 281 +2886 1385 1399 280 +2887 281 1386 282 +2888 281 1399 1386 +2889 282 1400 283 +2890 1386 1400 282 +2891 283 1387 284 +2892 283 1400 1387 +2893 284 1390 285 +2894 1387 1390 284 +2895 1390 1403 285 +2896 1401 1403 1390 +2897 1391 1404 1402 +2 17 2 1452 +2898 8 134 1579 +2899 8 1579 309 +2900 1615 112 15 +2901 264 1615 15 +2902 23 1578 285 +2903 23 308 1578 +2904 1616 286 24 +2905 330 1616 24 +2906 112 1614 113 +2907 112 1615 1614 +2908 113 1549 114 +2909 1588 1549 113 +2910 113 1614 1588 +2911 114 1547 115 +2912 114 1549 1547 +2913 115 1446 116 +2914 115 1547 1446 +2915 116 1444 117 +2916 116 1446 1444 +2917 1841 118 117 +2918 117 1444 1841 +2919 1677 119 118 +2920 1841 1677 118 +2921 119 1638 120 +2922 1677 1638 119 +2923 1778 121 120 +2924 1778 120 1638 +2925 121 1664 122 +2926 121 1778 1664 +2927 122 1665 123 +2928 122 1664 1665 +2929 2018 124 123 +2930 2018 123 1665 +2931 124 1657 125 +2932 1657 124 2018 +2933 125 1534 126 +2934 1657 1534 125 +2935 126 1643 127 +2936 126 1534 1535 +2937 1535 1643 126 +2938 1643 128 127 +2939 128 1844 129 +2940 1643 1644 128 +2941 1644 1844 128 +2942 1422 130 129 +2943 1422 129 1844 +2944 1423 131 130 +2945 1423 130 1422 +2946 1554 132 131 +2947 1423 1554 131 +2948 1406 133 132 +2949 1554 1406 132 +2950 1407 134 133 +2951 1406 1407 133 +2952 1579 134 1407 +2953 265 1592 264 +2954 1592 1615 264 +2955 266 1533 265 +2956 1533 1501 265 +2957 1592 265 1501 +2958 1532 266 267 +2959 1533 266 1532 +2960 268 1773 267 +2961 1532 267 1773 +2962 269 1430 268 +2963 1773 268 1430 +2964 270 1716 269 +2965 269 1431 1430 +2966 1716 1431 269 +2967 271 1743 270 +2968 1716 270 1743 +2969 272 1515 271 +2970 1743 271 1515 +2971 273 1514 272 +2972 1514 1515 272 +2973 274 1704 273 +2974 1704 1514 273 +2975 275 1703 274 +2976 1703 1704 274 +2977 2037 275 276 +2978 2037 1703 275 +2979 277 1667 276 +2980 276 1667 2037 +2981 278 1577 277 +2982 277 1577 1667 +2983 1661 278 279 +2984 1576 1577 278 +2985 1661 1576 278 +2986 1883 279 280 +2987 1883 1661 279 +2988 281 1821 280 +2989 1821 1883 280 +2990 1770 281 282 +2991 281 1770 1821 +2992 283 1538 282 +2993 282 1538 1770 +2994 1537 283 284 +2995 283 1537 1538 +2996 1578 284 285 +2997 1497 1537 284 +2998 284 1578 1497 +2999 286 1613 287 +3000 286 1616 1613 +3001 287 1541 288 +3002 1589 1541 287 +3003 287 1613 1589 +3004 288 1539 289 +3005 288 1541 1539 +3006 289 1441 290 +3007 289 1539 1441 +3008 290 1442 291 +3009 290 1441 1442 +3010 291 1591 292 +3011 1447 291 1442 +3012 1447 1591 291 +3013 292 1567 293 +3014 1591 1567 292 +3015 293 1566 294 +3016 293 1567 1566 +3017 1594 295 294 +3018 1594 294 1566 +3019 1586 296 295 +3020 1594 1586 295 +3021 1609 297 296 +3022 1586 1609 296 +3023 297 1617 298 +3024 1609 1617 297 +3025 298 1580 299 +3026 1617 1580 298 +3027 299 1593 300 +3028 1580 1593 299 +3029 300 1876 301 +3030 300 1593 1876 +3031 301 1775 302 +3032 1876 1775 301 +3033 302 1774 303 +3034 1775 1774 302 +3035 1426 304 303 +3036 1426 303 1774 +3037 1427 305 304 +3038 1427 304 1426 +3039 1544 306 305 +3040 1427 1544 305 +3041 1409 307 306 +3042 1544 1409 306 +3043 1410 308 307 +3044 1409 1410 307 +3045 1578 308 1410 +3046 1579 310 309 +3047 1555 311 310 +3048 1491 1555 310 +3049 310 1579 1491 +3050 311 1556 312 +3051 311 1555 1556 +3052 1769 313 312 +3053 312 1556 1769 +3054 313 1449 314 +3055 313 1769 1449 +3056 1805 315 314 +3057 1449 1805 314 +3058 1411 316 315 +3059 315 1805 1411 +3060 316 1413 317 +3061 1411 1412 316 +3062 316 1412 1413 +3063 1413 318 317 +3064 1729 319 318 +3065 1413 1729 318 +3066 319 1730 320 +3067 1729 1730 319 +3068 2041 321 320 +3069 1730 2041 320 +3070 1972 322 321 +3071 1972 321 2041 +3072 1571 323 322 +3073 1972 1571 322 +3074 323 1608 324 +3075 1571 1772 323 +3076 323 1772 1608 +3077 1608 325 324 +3078 325 1475 326 +3079 1607 1475 325 +3080 1607 325 1608 +3081 1824 327 326 +3082 1476 326 1475 +3083 326 1476 1824 +3084 1545 328 327 +3085 1545 327 1824 +3086 328 1546 329 +3087 1546 328 1545 +3088 329 1590 330 +3089 1546 1492 329 +3090 1590 329 1492 +3091 1590 1616 330 +3092 1405 1407 1406 +3093 1405 1406 1553 +3094 1579 1407 1405 +3095 1491 1405 1490 +3096 1405 1553 1490 +3097 1491 1579 1405 +3098 1406 1554 1553 +3099 1408 1410 1409 +3100 1408 1409 1543 +3101 1578 1410 1408 +3102 1497 1408 1496 +3103 1408 1543 1496 +3104 1497 1578 1408 +3105 1409 1544 1543 +3106 1688 1412 1411 +3107 1411 1806 1688 +3108 1806 1411 1805 +3109 1413 1412 1647 +3110 1647 1412 1776 +3111 1412 1688 1776 +3112 1413 1647 1646 +3113 1413 1646 1729 +3114 1414 1416 1415 +3115 1415 2051 1414 +3116 1414 1561 1416 +3117 2060 1561 1414 +3118 2051 2060 1414 +3119 1415 1416 1417 +3120 1886 1415 1417 +3121 1940 1877 1415 +3122 1877 2051 1415 +3123 1886 1940 1415 +3124 1417 1416 1626 +3125 1559 1416 1561 +3126 1559 1626 1416 +3127 1627 1417 1626 +3128 1627 1886 1417 +3129 1418 1420 1419 +3130 1418 1419 1787 +3131 1418 1893 1420 +3132 1418 1787 1891 +3133 1891 1892 1418 +3134 1418 1892 1893 +3135 1419 1420 1421 +3136 1421 1852 1419 +3137 1787 1419 1744 +3138 1419 1852 1744 +3139 1421 1420 1768 +3140 1768 1420 1893 +3141 1682 1421 1637 +3142 1768 1637 1421 +3143 1682 1852 1421 +3144 1422 1424 1423 +3145 1422 1804 1424 +3146 1844 1804 1422 +3147 1423 1424 1425 +3148 1472 1423 1425 +3149 1423 1472 1554 +3150 1424 1851 1425 +3151 1424 1804 1851 +3152 1472 1425 1474 +3153 1425 1597 1474 +3154 1425 1851 1597 +3155 1426 1428 1427 +3156 1426 1737 1428 +3157 1774 1737 1426 +3158 1427 1428 1429 +3159 1456 1427 1429 +3160 1427 1456 1544 +3161 1428 1738 1429 +3162 1428 1737 1574 +3163 1428 1574 1738 +3164 1456 1429 1458 +3165 1429 1483 1458 +3166 1429 1738 1483 +3167 1847 1430 1431 +3168 1430 1847 1773 +3169 1431 1715 1459 +3170 1847 1431 1459 +3171 1715 1431 1716 +3172 1432 1434 1433 +3173 1433 1470 1432 +3174 1435 1434 1432 +3175 1463 1435 1432 +3176 1485 1463 1432 +3177 1484 1432 1470 +3178 1484 1485 1432 +3179 1433 1434 1625 +3180 1433 1471 1470 +3181 1433 1625 1471 +3182 1732 1434 1435 +3183 1625 1434 1708 +3184 1732 1708 1434 +3185 1463 1562 1435 +3186 1435 1562 1732 +3187 1436 1438 1437 +3188 1436 1437 1439 +3189 1733 1438 1436 +3190 1436 1439 1896 +3191 1733 1436 1823 +3192 1985 1823 1436 +3193 1896 1985 1436 +3194 1574 1437 1438 +3195 1437 1656 1439 +3196 1655 1437 1574 +3197 1655 1656 1437 +3198 1438 1575 1574 +3199 1733 1575 1438 +3200 1439 1656 1691 +3201 1691 1783 1439 +3202 1896 1439 1783 +3203 1440 1442 1441 +3204 1440 1441 1443 +3205 1447 1442 1440 +3206 1482 1440 1443 +3207 1440 1481 1447 +3208 1440 1482 1481 +3209 1443 1441 1454 +3210 1441 1539 1454 +3211 1443 1454 1452 +3212 1860 1443 1452 +3213 1482 1443 1860 +3214 1444 1446 1445 +3215 1798 1444 1445 +3216 1798 1841 1444 +3217 1445 1446 1448 +3218 1865 1445 1448 +3219 1798 1445 1865 +3220 1448 1446 1466 +3221 1446 1547 1466 +3222 1591 1447 1481 +3223 1448 1466 1464 +3224 1603 1448 1464 +3225 1865 1448 1603 +3226 1449 1451 1450 +3227 1449 1450 1805 +3228 1449 1845 1451 +3229 1769 1845 1449 +3230 1450 1451 1455 +3231 1806 1450 1455 +3232 1805 1450 1806 +3233 1689 1455 1451 +3234 1764 1689 1451 +3235 1846 1764 1451 +3236 1451 1845 1846 +3237 1452 1454 1453 +3238 1452 1453 1753 +3239 1452 1753 1859 +3240 1859 1860 1452 +3241 1454 1540 1453 +3242 1493 1494 1453 +3243 1493 1453 1540 +3244 1494 1530 1453 +3245 1453 1530 1753 +3246 1539 1540 1454 +3247 1687 1688 1455 +3248 1687 1455 1689 +3249 1806 1455 1688 +3250 1456 1458 1457 +3251 1543 1456 1457 +3252 1543 1544 1456 +3253 1457 1458 1486 +3254 1527 1457 1486 +3255 1495 1496 1457 +3256 1527 1495 1457 +3257 1457 1496 1543 +3258 1483 1486 1458 +3259 1459 1461 1460 +3260 1847 1459 1460 +3261 1777 1461 1459 +3262 1715 1777 1459 +3263 1460 1461 1462 +3264 1462 1605 1460 +3265 1605 1518 1460 +3266 1460 1518 1847 +3267 1461 1736 1462 +3268 1735 1736 1461 +3269 1777 1735 1461 +3270 1604 1605 1462 +3271 1604 1462 1894 +3272 1894 1462 1736 +3273 1463 1485 1508 +3274 1463 1508 1635 +3275 1463 1635 1562 +3276 1464 1466 1465 +3277 1464 1465 1848 +3278 1848 1603 1464 +3279 1466 1548 1465 +3280 1502 1503 1465 +3281 1502 1465 1548 +3282 1503 1520 1465 +3283 1465 1520 1848 +3284 1547 1548 1466 +3285 1467 1469 1468 +3286 1944 1467 1468 +3287 1469 1467 1487 +3288 1467 1710 1487 +3289 1808 1710 1467 +3290 1944 1808 1467 +3291 1469 1488 1468 +3292 1468 1488 1958 +3293 1944 1468 1957 +3294 1958 1957 1468 +3295 1926 1469 1487 +3296 1488 1469 2065 +3297 1469 1926 2065 +3298 1471 1849 1470 +3299 1484 1470 1528 +3300 1528 1470 1849 +3301 1471 1625 1884 +3302 1821 1849 1471 +3303 1884 1821 1471 +3304 1472 1474 1473 +3305 1553 1472 1473 +3306 1553 1554 1472 +3307 1473 1474 1843 +3308 1489 1490 1473 +3309 1524 1489 1473 +3310 1473 1490 1553 +3311 1524 1473 1843 +3312 1597 1843 1474 +3313 1475 1477 1476 +3314 1475 1607 1477 +3315 1476 1477 2054 +3316 1824 1476 1752 +3317 1476 2054 1752 +3318 1607 1771 1477 +3319 1623 1621 1477 +3320 2054 1477 1621 +3321 1623 1477 1771 +3322 1478 1480 1479 +3323 1478 1479 1509 +3324 1478 2047 1480 +3325 1478 1509 1834 +3326 1834 1678 1478 +3327 1478 1678 2047 +3328 1479 1480 1885 +3329 1479 1908 1509 +3330 1479 1885 1872 +3331 1908 1479 1872 +3332 1994 1885 1480 +3333 1995 1994 1480 +3334 1480 2047 1995 +3335 1481 1482 1653 +3336 1591 1481 1652 +3337 1651 1652 1481 +3338 1651 1481 1653 +3339 1653 1482 1740 +3340 1860 1740 1482 +3341 1483 1485 1484 +3342 1483 1484 1486 +3343 1485 1483 1624 +3344 1624 1483 1738 +3345 1528 1486 1484 +3346 1508 1485 1624 +3347 1527 1486 1528 +3348 1709 1487 1710 +3349 1709 1926 1487 +3350 1488 1948 1949 +3351 1948 1488 2065 +3352 1488 1949 1958 +3353 1489 1491 1490 +3354 1555 1491 1489 +3355 1524 1525 1489 +3356 1556 1489 1525 +3357 1489 1556 1555 +3358 1492 1494 1493 +3359 1589 1492 1493 +3360 1492 1546 1494 +3361 1590 1492 1589 +3362 1540 1589 1493 +3363 1529 1530 1494 +3364 1494 1545 1529 +3365 1545 1494 1546 +3366 1495 1497 1496 +3367 1537 1497 1495 +3368 1527 1531 1495 +3369 1538 1495 1531 +3370 1495 1538 1537 +3371 1498 1500 1499 +3372 1498 1499 1504 +3373 1498 1859 1500 +3374 1498 1504 1740 +3375 1740 1860 1498 +3376 1498 1860 1859 +3377 1622 1499 1500 +3378 1504 1499 1640 +3379 1641 1499 1622 +3380 1639 1640 1499 +3381 1639 1499 1641 +3382 1500 1754 1622 +3383 1859 1754 1500 +3384 1501 1503 1502 +3385 1588 1501 1502 +3386 1501 1533 1503 +3387 1592 1501 1588 +3388 1548 1588 1502 +3389 1519 1520 1503 +3390 1503 1532 1519 +3391 1532 1503 1533 +3392 1747 1504 1640 +3393 1739 1740 1504 +3394 1504 1747 1739 +3395 1505 1507 1506 +3396 1505 1506 1513 +3397 1704 1507 1505 +3398 1516 1505 1513 +3399 1516 1514 1505 +3400 1505 1514 1704 +3401 1506 1507 1880 +3402 1513 1506 2008 +3403 1881 1506 1880 +3404 2008 1506 1881 +3405 1703 1507 1704 +3406 1703 2016 1507 +3407 2016 1880 1507 +3408 1574 1575 1508 +3409 1508 1624 1574 +3410 1508 1575 1635 +3411 1834 1509 1835 +3412 1835 1509 1836 +3413 1509 1908 1836 +3414 1510 1512 1511 +3415 1510 1511 1741 +3416 1510 2048 1512 +3417 2005 1510 1741 +3418 2006 1510 2005 +3419 2006 2027 1510 +3420 2027 2048 1510 +3421 1512 1825 1511 +3422 1517 1642 1511 +3423 1511 1825 1517 +3424 1511 1642 1741 +3425 1512 1735 1825 +3426 1735 1512 1827 +3427 2048 1827 1512 +3428 1516 1513 1642 +3429 1513 1741 1642 +3430 2008 1741 1513 +3431 1514 1516 1515 +3432 1515 1516 1517 +3433 1742 1515 1517 +3434 1515 1742 1743 +3435 1517 1516 1642 +3436 1742 1517 1825 +3437 1518 1520 1519 +3438 1847 1518 1519 +3439 1848 1520 1518 +3440 1848 1518 1605 +3441 1773 1519 1532 +3442 1773 1847 1519 +3443 1521 1523 1522 +3444 1521 1522 1542 +3445 1523 1521 2056 +3446 2070 1521 1542 +3447 2033 2056 1521 +3448 1521 2079 2033 +3449 1521 2070 2079 +3450 1666 1522 1523 +3451 1542 1522 1672 +3452 1522 1666 1672 +3453 1523 1659 1663 +3454 1659 1523 2056 +3455 1523 1663 1666 +3456 1524 1526 1525 +3457 1524 1843 1526 +3458 1526 1845 1525 +3459 1525 1769 1556 +3460 1845 1769 1525 +3461 1526 1843 1595 +3462 1526 1595 1846 +3463 1526 1846 1845 +3464 1527 1528 1531 +3465 1528 1849 1531 +3466 1529 1752 1530 +3467 1824 1529 1545 +3468 1529 1824 1752 +3469 1752 1753 1530 +3470 1531 1770 1538 +3471 1849 1770 1531 +3472 1534 1536 1535 +3473 1800 1536 1534 +3474 1800 1534 1657 +3475 1535 1536 1671 +3476 1535 1671 1643 +3477 1671 1536 1857 +3478 1536 1800 1799 +3479 1536 1799 1857 +3480 1539 1541 1540 +3481 1541 1589 1540 +3482 1672 1675 1542 +3483 2069 1542 1675 +3484 2070 1542 2069 +3485 1547 1549 1548 +3486 1549 1588 1548 +3487 1550 1552 1551 +3488 1550 1551 1557 +3489 1550 1699 1552 +3490 1943 1550 1557 +3491 1699 1550 1942 +3492 1942 1550 1943 +3493 2083 1551 1552 +3494 1551 1695 1557 +3495 1551 1696 1695 +3496 1551 2083 1696 +3497 1697 1552 1698 +3498 2083 1552 1697 +3499 1698 1552 1699 +3500 1557 1695 1791 +3501 1792 1557 1791 +3502 1557 1792 1874 +3503 1943 1557 1874 +3504 1558 1560 1559 +3505 1558 1559 1561 +3506 1560 1558 1662 +3507 1561 1576 1558 +3508 1576 1661 1558 +3509 1558 1661 1660 +3510 1558 1660 1662 +3511 1559 1560 1708 +3512 1628 1626 1559 +3513 1559 1708 1628 +3514 1625 1560 1662 +3515 1708 1560 1625 +3516 1577 1576 1561 +3517 1561 2060 1577 +3518 1562 1564 1563 +3519 1562 1563 1565 +3520 1562 1635 1564 +3521 1565 1732 1562 +3522 1563 1564 2044 +3523 1563 1572 1565 +3524 1563 1573 1572 +3525 2044 1573 1563 +3526 1564 1635 1734 +3527 1564 1734 1686 +3528 2044 1564 1686 +3529 1565 1572 1762 +3530 1627 1628 1565 +3531 1627 1565 1762 +3532 1732 1565 1628 +3533 1652 1566 1567 +3534 1594 1566 1690 +3535 1690 1566 1652 +3536 1591 1652 1567 +3537 1568 1570 1569 +3538 1569 1867 1568 +3539 1568 1869 1570 +3540 1867 1868 1568 +3541 1868 1869 1568 +3542 1569 1570 1610 +3543 1612 1569 1610 +3544 1611 1569 1612 +3545 1867 1569 1611 +3546 1786 1610 1570 +3547 1786 1570 1787 +3548 1787 1570 1891 +3549 1570 1869 1891 +3550 1772 1571 1901 +3551 1901 1571 1902 +3552 1972 1902 1571 +3553 1573 1761 1572 +3554 1762 1572 1761 +3555 1654 2059 1573 +3556 2061 1654 1573 +3557 1761 1573 2059 +3558 1573 2044 2061 +3559 1738 1574 1624 +3560 1737 1655 1574 +3561 1575 1734 1635 +3562 1733 1734 1575 +3563 2060 1667 1577 +3564 1580 1582 1581 +3565 1580 1581 1593 +3566 1582 1580 1617 +3567 1581 1582 1583 +3568 1581 1583 1783 +3569 1581 1691 1593 +3570 1691 1581 1783 +3571 1582 1839 1583 +3572 1617 1619 1582 +3573 1839 1582 1619 +3574 1896 1783 1583 +3575 1839 1837 1583 +3576 1896 1583 1837 +3577 1584 1586 1585 +3578 1584 1585 1587 +3579 1586 1584 1609 +3580 1836 1584 1587 +3581 1618 1609 1584 +3582 1584 1836 1618 +3583 1585 1586 1594 +3584 1587 1585 1797 +3585 1690 1585 1594 +3586 1585 1690 1797 +3587 1797 1897 1587 +3588 1835 1836 1587 +3589 1587 1897 1835 +3590 1614 1592 1588 +3591 1613 1590 1589 +3592 1590 1613 1616 +3593 1592 1614 1615 +3594 1593 1691 1876 +3595 1595 1597 1596 +3596 1596 1898 1595 +3597 1597 1595 1843 +3598 1595 1764 1846 +3599 1898 1764 1595 +3600 1596 1597 1598 +3601 1765 1596 1598 +3602 1900 1596 1765 +3603 1596 1900 1898 +3604 1598 1597 1851 +3605 1851 1669 1598 +3606 1669 1890 1598 +3607 1890 1765 1598 +3608 1599 1601 1600 +3609 1784 1599 1600 +3610 2082 1601 1599 +3611 1784 1785 1599 +3612 1599 1785 2043 +3613 2043 2082 1599 +3614 1600 1601 1602 +3615 1602 1776 1600 +3616 1687 1600 1776 +3617 1687 1831 1600 +3618 1784 1600 1831 +3619 1602 1601 2036 +3620 2036 1601 2073 +3621 1601 2082 2073 +3622 1763 1647 1602 +3623 1647 1776 1602 +3624 1602 2036 1763 +3625 1603 1605 1604 +3626 1603 1604 1606 +3627 1605 1603 1848 +3628 1603 1606 1865 +3629 1604 1744 1606 +3630 1604 1895 1744 +3631 1894 1895 1604 +3632 1606 1744 1852 +3633 1852 1865 1606 +3634 1607 1608 1771 +3635 1771 1608 1772 +3636 2052 1617 1609 +3637 2052 1609 1618 +3638 1612 1610 2034 +3639 2074 1610 1786 +3640 1610 2074 2034 +3641 1612 2024 1611 +3642 1867 1611 2023 +3643 2023 1611 2000 +3644 2000 1611 2024 +3645 1612 2026 2024 +3646 1612 2034 2026 +3647 1617 2052 1619 +3648 1908 1618 1836 +3649 1907 1618 1908 +3650 1907 2052 1618 +3651 1619 1820 1839 +3652 1619 1907 1820 +3653 2052 1907 1619 +3654 1620 1622 1621 +3655 1620 1621 1623 +3656 1620 1641 1622 +3657 1620 1623 1706 +3658 1620 1731 1641 +3659 1706 1731 1620 +3660 1754 1621 1622 +3661 1754 2054 1621 +3662 1705 1706 1623 +3663 1705 1623 1771 +3664 1884 1625 1662 +3665 1626 1628 1627 +3666 1762 2057 1627 +3667 2057 1886 1627 +3668 1708 1732 1628 +3669 1629 1631 1630 +3670 1630 2038 1629 +3671 1631 1629 1707 +3672 1706 1707 1629 +3673 1731 1706 1629 +3674 1731 1629 2038 +3675 1889 1630 1631 +3676 1887 1888 1630 +3677 1887 1630 1889 +3678 2038 1630 1888 +3679 1631 1707 1882 +3680 1631 1882 1711 +3681 1711 1889 1631 +3682 1632 1634 1633 +3683 1633 2068 1632 +3684 1694 1634 1632 +3685 1694 1632 1931 +3686 1632 1932 1931 +3687 1632 2068 1932 +3688 1633 1634 1645 +3689 1645 1727 1633 +3690 1727 1720 1633 +3691 2068 1633 1720 +3692 1645 1634 1692 +3693 1692 1634 1693 +3694 1693 1634 1694 +3695 1636 1638 1637 +3696 1636 1637 1768 +3697 1778 1638 1636 +3698 1674 1636 1673 +3699 1673 1636 1768 +3700 1778 1636 1674 +3701 1638 1677 1637 +3702 1637 1677 1676 +3703 1637 1676 1682 +3704 1639 1856 1640 +3705 1639 1641 1922 +3706 1639 1925 1856 +3707 1922 1925 1639 +3708 1856 1747 1640 +3709 1922 1641 1731 +3710 1643 1671 1644 +3711 1668 1844 1644 +3712 1973 1668 1644 +3713 1671 1973 1644 +3714 1692 1722 1645 +3715 1645 1722 1721 +3716 1721 1727 1645 +3717 1646 1647 1763 +3718 1728 1729 1646 +3719 1763 1728 1646 +3720 1648 1650 1649 +3721 1648 1649 1654 +3722 1648 2046 1650 +3723 1648 1654 2061 +3724 2046 1648 1684 +3725 1684 1648 2061 +3726 2067 1649 1650 +3727 1654 1649 2066 +3728 1649 2067 2066 +3729 1903 1983 1650 +3730 1650 2046 1903 +3731 1983 2067 1650 +3732 1652 1651 1822 +3733 1651 1653 1739 +3734 1745 1651 1739 +3735 1822 1651 1745 +3736 1652 1822 1690 +3737 1653 1740 1739 +3738 1654 2066 2059 +3739 1655 1775 1656 +3740 1737 1774 1655 +3741 1655 1774 1775 +3742 1656 1876 1691 +3743 1656 1775 1876 +3744 1657 1659 1658 +3745 1657 1658 1800 +3746 2018 1659 1657 +3747 1659 2056 1658 +3748 1658 1933 1800 +3749 1658 2056 1933 +3750 1659 2018 1663 +3751 1661 1883 1660 +3752 1662 1660 1884 +3753 1660 1883 1884 +3754 1663 1665 1664 +3755 1663 1664 1666 +3756 1663 2018 1665 +3757 1664 1674 1666 +3758 1674 1664 1778 +3759 1666 1674 1672 +3760 1667 2060 2037 +3761 1668 1670 1669 +3762 1668 1669 1851 +3763 1668 1973 1670 +3764 1804 1844 1668 +3765 1851 1804 1668 +3766 1767 1669 1670 +3767 1766 1669 1767 +3768 1890 1669 1766 +3769 1671 1857 1670 +3770 1973 1671 1670 +3771 1866 1767 1670 +3772 1866 1670 1857 +3773 1672 1674 1673 +3774 1672 1673 1675 +3775 1675 1673 1893 +3776 1768 1893 1673 +3777 1892 1675 1893 +3778 1675 1892 1932 +3779 1932 2069 1675 +3780 1841 1676 1677 +3781 1676 1864 1682 +3782 1841 1798 1676 +3783 1676 1798 1864 +3784 1678 1680 1679 +3785 1679 2047 1678 +3786 1755 1680 1678 +3787 1755 1678 1834 +3788 1679 1680 1681 +3789 1681 1913 1679 +3790 2063 1679 1913 +3791 2063 2047 1679 +3792 1681 1680 1746 +3793 1748 1746 1680 +3794 1748 1680 1755 +3795 1746 1856 1681 +3796 1856 1912 1681 +3797 1681 1912 1913 +3798 1682 1864 1852 +3799 1683 1685 1684 +3800 1683 1684 1686 +3801 1683 1985 1685 +3802 1683 1686 1823 +3803 1985 1683 1823 +3804 2046 1684 1685 +3805 2061 1686 1684 +3806 1685 1985 1838 +3807 1685 1838 2045 +3808 1685 2045 2046 +3809 1734 1823 1686 +3810 2044 1686 2061 +3811 1776 1688 1687 +3812 1831 1687 1689 +3813 1764 1832 1689 +3814 1689 1832 1831 +3815 1797 1690 1822 +3816 1693 1981 1692 +3817 1911 1722 1692 +3818 1692 1981 1911 +3819 1868 1693 1694 +3820 1868 1899 1693 +3821 1981 1693 1899 +3822 1868 1694 1869 +3823 1931 1869 1694 +3824 2075 1695 1696 +3825 1695 2075 1791 +3826 2075 1696 2009 +3827 1696 2083 2009 +3828 1698 1723 1697 +3829 1697 1701 1700 +3830 1700 2083 1697 +3831 1723 1701 1697 +3832 1698 1699 1721 +3833 1721 1722 1698 +3834 1698 1722 1723 +3835 1721 1699 1724 +3836 1699 1725 1724 +3837 1725 1699 1942 +3838 1700 1701 1702 +3839 1782 1700 1702 +3840 1781 1700 1782 +3841 2083 1700 1781 +3842 1702 1701 1809 +3843 1840 1701 1723 +3844 1809 1701 1840 +3845 1782 1702 1945 +3846 1808 1702 1809 +3847 1702 1808 1945 +3848 1703 2017 2016 +3849 2037 2017 1703 +3850 1705 1707 1706 +3851 1707 1705 1882 +3852 1850 1705 1771 +3853 1882 1705 1850 +3854 1709 1710 1714 +3855 1709 1714 1980 +3856 1709 1916 1926 +3857 1980 1916 1709 +3858 1714 1710 1809 +3859 1808 1809 1710 +3860 1711 1713 1712 +3861 1711 1712 1889 +3862 1711 1882 1713 +3863 1713 1970 1712 +3864 1861 1712 1862 +3865 1712 1861 1889 +3866 1970 1862 1712 +3867 1901 1713 1882 +3868 1901 1902 1713 +3869 1902 1970 1713 +3870 1840 1714 1809 +3871 1840 1910 1714 +3872 1714 1910 1980 +3873 1743 1715 1716 +3874 1715 1743 1742 +3875 1777 1715 1742 +3876 1717 1719 1718 +3877 1718 1726 1717 +3878 2033 1719 1717 +3879 1726 2072 1717 +3880 2033 1717 1991 +3881 2072 1991 1717 +3882 1718 1719 1720 +3883 1718 1720 1724 +3884 1724 1725 1718 +3885 1718 1725 1726 +3886 1720 1719 2079 +3887 1719 2033 2079 +3888 1720 1727 1724 +3889 1720 2079 2068 +3890 1721 1724 1727 +3891 1723 1722 1911 +3892 1840 1723 1911 +3893 1726 1725 1942 +3894 1726 1942 1873 +3895 1873 2072 1726 +3896 1728 1730 1729 +3897 2055 1730 1728 +3898 1920 1728 1763 +3899 1728 1920 1919 +3900 1919 2055 1728 +3901 2055 2041 1730 +3902 1731 1986 1922 +3903 1731 2038 1986 +3904 1733 1823 1734 +3905 1736 1735 1827 +3906 1735 1777 1825 +3907 1736 1827 1826 +3908 1736 1826 1894 +3909 1747 1745 1739 +3910 1741 2008 2005 +3911 1777 1742 1825 +3912 1923 1787 1744 +3913 1744 1895 1923 +3914 1745 1747 1746 +3915 1748 1745 1746 +3916 1745 1748 1822 +3917 1746 1747 1856 +3918 1755 1897 1748 +3919 1822 1748 1897 +3920 1749 1751 1750 +3921 1749 1750 1756 +3922 1749 1842 1751 +3923 1749 1756 1828 +3924 1749 1828 1842 +3925 2022 1750 1751 +3926 1756 1750 2030 +3927 1758 1750 2022 +3928 2030 1750 1758 +3929 1751 1842 2019 +3930 2022 1751 2019 +3931 1752 1754 1753 +3932 2054 1754 1752 +3933 1859 1753 1754 +3934 1835 1755 1834 +3935 1835 1897 1755 +3936 2043 1828 1756 +3937 2028 1756 2030 +3938 1756 2028 2073 +3939 2073 2043 1756 +3940 1757 1759 1758 +3941 1758 2022 1757 +3942 1815 1759 1757 +3943 1815 1757 1961 +3944 2020 1961 1757 +3945 2022 2020 1757 +3946 1758 1759 1780 +3947 1758 1780 2030 +3948 1780 1759 2076 +3949 1759 1815 2076 +3950 1760 1762 1761 +3951 1760 1761 1779 +3952 1762 1760 2057 +3953 1760 1779 2084 +3954 1760 2058 2057 +3955 2058 1760 2084 +3956 1779 1761 2059 +3957 1763 2036 1920 +3958 1764 1898 1832 +3959 1789 1765 1766 +3960 1765 1890 1766 +3961 1765 1789 1814 +3962 1900 1765 1814 +3963 1766 1767 1788 +3964 1766 1788 1790 +3965 1790 1789 1766 +3966 1767 1866 1788 +3967 1770 1849 1821 +3968 1772 1850 1771 +3969 1772 1901 1850 +3970 1941 1939 1779 +3971 2084 1779 1939 +3972 1779 2059 1941 +3973 2029 1780 1863 +3974 2076 1863 1780 +3975 1780 2029 2030 +3976 1782 1947 1781 +3977 2010 1781 1947 +3978 2009 1781 2010 +3979 2083 1781 2009 +3980 1945 1946 1782 +3981 1782 1946 1947 +3982 1784 1833 1785 +3983 1833 1784 1831 +3984 1921 1830 1785 +3985 1830 2080 1785 +3986 1921 1785 1833 +3987 2080 2043 1785 +3988 1786 1787 1923 +3989 1924 1786 1923 +3990 1924 2074 1786 +3991 1790 1788 1874 +3992 1875 1788 1866 +3993 1873 1874 1788 +3994 1873 1788 1875 +3995 1793 1789 1790 +3996 1793 1814 1789 +3997 1792 1793 1790 +3998 1792 1790 1874 +3999 1791 1793 1792 +4000 1793 1791 2049 +4001 2075 2049 1791 +4002 1793 1921 1814 +4003 1793 2049 1921 +4004 1794 1796 1795 +4005 1794 1795 1801 +4006 1794 1950 1796 +4007 1794 1801 1949 +4008 1794 1949 1948 +4009 1794 1948 1950 +4010 1989 1795 1796 +4011 1795 1975 1801 +4012 1795 2002 1975 +4013 1988 1795 1989 +4014 1988 2002 1795 +4015 1796 1803 1802 +4016 1802 1989 1796 +4017 1950 1803 1796 +4018 1822 1897 1797 +4019 1798 1865 1864 +4020 1933 1799 1800 +4021 1858 1857 1799 +4022 1799 1991 1858 +4023 1933 1991 1799 +4024 1801 1978 1949 +4025 1975 1978 1801 +4026 1802 1803 1807 +4027 1802 1807 1990 +4028 1802 1987 1989 +4029 1802 1990 1987 +4030 1807 1803 1963 +4031 1962 1803 1950 +4032 1962 1963 1803 +4033 1938 1807 1937 +4034 1807 1964 1937 +4035 1807 1938 1990 +4036 1964 1807 1963 +4037 1944 1945 1808 +4038 1810 1812 1811 +4039 1811 2040 1810 +4040 1812 1810 1813 +4041 1810 1815 1813 +4042 1815 1810 1915 +4043 2040 1915 1810 +4044 2071 1811 1812 +4045 2039 1811 1914 +4046 1811 2071 1914 +4047 2039 2040 1811 +4048 1968 1812 1813 +4049 1968 1969 1812 +4050 2071 1812 1969 +4051 1813 1815 1961 +4052 1961 1960 1813 +4053 1813 1960 1968 +4054 1833 1900 1814 +4055 1833 1814 1921 +4056 2076 1815 1915 +4057 1816 1818 1817 +4058 1816 1817 1904 +4059 2045 1818 1816 +4060 1903 1816 1904 +4061 2046 1816 1903 +4062 2046 2045 1816 +4063 1817 1818 1819 +4064 1871 1817 1819 +4065 1871 1904 1817 +4066 1818 1820 1819 +4067 1820 1818 1839 +4068 1818 1838 1837 +4069 1818 1837 1839 +4070 1818 2045 1838 +4071 1907 1819 1820 +4072 1819 1872 1871 +4073 1907 1872 1819 +4074 1883 1821 1884 +4075 1826 1827 1929 +4076 1826 1895 1894 +4077 1895 1826 1923 +4078 1923 1826 1924 +4079 1929 1924 1826 +4080 1827 2048 1929 +4081 1828 1830 1829 +4082 1842 1828 1829 +4083 2080 1830 1828 +4084 2043 2080 1828 +4085 2075 1829 1830 +4086 1842 1829 2009 +4087 1829 2075 2009 +4088 1921 2049 1830 +4089 2049 2075 1830 +4090 1832 1833 1831 +4091 1833 1832 1898 +4092 1900 1833 1898 +4093 1985 1837 1838 +4094 1896 1837 1985 +4095 1840 1911 1910 +4096 2010 1842 2009 +4097 1842 2010 2019 +4098 1901 1882 1850 +4099 1852 1864 1865 +4100 1853 1855 1854 +4101 1853 1854 1870 +4102 1853 2081 1855 +4103 1870 2062 1853 +4104 2062 2058 1853 +4105 2081 1853 2058 +4106 2015 1854 1855 +4107 1870 1854 2032 +4108 1997 1854 2015 +4109 1997 2032 1854 +4110 1966 2014 1855 +4111 1855 2081 1966 +4112 2014 2015 1855 +4113 1856 1925 1912 +4114 1866 1857 1858 +4115 1858 1875 1866 +4116 1858 1991 1875 +4117 1863 1861 1862 +4118 2053 1861 1863 +4119 1861 1887 1889 +4120 2053 1887 1861 +4121 1934 1863 1862 +4122 1934 1862 1935 +4123 2050 1935 1862 +4124 2050 1862 1970 +4125 1863 1934 2029 +4126 2053 1863 2076 +4127 1868 1867 1899 +4128 1867 1906 1899 +4129 1906 1867 2023 +4130 1869 2078 1891 +4131 2078 1869 1931 +4132 1870 2031 1940 +4133 1940 2062 1870 +4134 2031 1870 2032 +4135 1871 1872 1885 +4136 1871 1885 1992 +4137 1992 1904 1871 +4138 1872 1907 1908 +4139 1873 1943 1874 +4140 2072 1873 1875 +4141 1943 1873 1942 +4142 1991 2072 1875 +4143 1877 1879 1878 +4144 1877 1878 2051 +4145 1877 1940 1879 +4146 1878 1879 1880 +4147 1880 2016 1878 +4148 2016 2017 1878 +4149 2017 2051 1878 +4150 1879 1881 1880 +4151 1881 1879 2031 +4152 1879 1940 2031 +4153 2007 2008 1881 +4154 2031 2007 1881 +4155 1885 1994 1992 +4156 2062 1940 1886 +4157 1886 2057 2058 +4158 2058 2062 1886 +4159 1887 1915 1888 +4160 2053 1915 1887 +4161 1915 2040 1888 +4162 1888 2039 2038 +4163 2039 1888 2040 +4164 2078 1892 1891 +4165 1931 1932 1892 +4166 1892 2078 1931 +4167 1905 1899 1906 +4168 1905 1981 1899 +4169 1902 1971 1970 +4170 1902 1972 1971 +4171 1982 1903 1904 +4172 1982 1983 1903 +4173 2004 1982 1904 +4174 2004 1904 1992 +4175 1905 1906 1909 +4176 1905 1909 1980 +4177 1905 1980 1910 +4178 1905 1910 1981 +4179 1909 1906 2023 +4180 1916 1909 1918 +4181 1909 1916 1980 +4182 1909 1928 1918 +4183 1928 1909 2023 +4184 1981 1910 1911 +4185 1912 1914 1913 +4186 2042 1914 1912 +4187 1912 1925 2042 +4188 2064 1913 1914 +4189 2064 2063 1913 +4190 1914 2042 2039 +4191 2071 2064 1914 +4192 1915 2053 2076 +4193 1916 1918 1917 +4194 1916 1917 1926 +4195 2013 1917 1918 +4196 1926 1917 1962 +4197 1917 2013 1962 +4198 1918 1928 1927 +4199 1927 2013 1918 +4200 1920 1936 1919 +4201 1936 1935 1919 +4202 1935 2050 1919 +4203 2055 1919 2050 +4204 2036 1936 1920 +4205 1986 1925 1922 +4206 2035 1924 1929 +4207 1924 2035 2034 +4208 2074 1924 2034 +4209 2042 1925 1986 +4210 2065 1926 1962 +4211 1927 1928 1930 +4212 1927 1930 2012 +4213 1927 2012 1965 +4214 1927 1965 2013 +4215 1930 1928 2023 +4216 2027 2035 1929 +4217 2027 1929 2048 +4218 2000 2001 1930 +4219 2000 1930 2023 +4220 1930 2001 2012 +4221 2069 1932 2068 +4222 1991 1933 2033 +4223 2056 2033 1933 +4224 1934 1935 1936 +4225 1934 1936 2029 +4226 2028 2029 1936 +4227 2028 1936 2073 +4228 1936 2036 2073 +4229 1937 1939 1938 +4230 2081 1939 1937 +4231 1964 1966 1937 +4232 2081 1937 1966 +4233 1938 1939 1941 +4234 1938 1941 1990 +4235 2081 2084 1939 +4236 1941 2066 1990 +4237 2066 1941 2059 +4238 1944 1979 1945 +4239 1944 1957 1979 +4240 1979 1946 1945 +4241 1947 1946 2021 +4242 1946 1979 2021 +4243 2010 1947 2019 +4244 2019 1947 2021 +4245 1950 1948 2065 +4246 1978 1958 1949 +4247 1950 2065 1962 +4248 1951 1953 1952 +4249 1951 1952 1954 +4250 1951 1995 1953 +4251 1951 1954 2077 +4252 1995 1951 2077 +4253 2064 1952 1953 +4254 1954 1952 1969 +4255 1952 2064 1969 +4256 2047 1953 1995 +4257 2047 2063 1953 +4258 2063 2064 1953 +4259 1954 1969 1967 +4260 1954 1967 1977 +4261 2077 1954 1977 +4262 1955 1957 1956 +4263 1956 2011 1955 +4264 1979 1957 1955 +4265 1955 1960 1959 +4266 1959 1979 1955 +4267 2011 1960 1955 +4268 1956 1957 1958 +4269 1956 1958 1976 +4270 2011 1956 1976 +4271 1958 1978 1976 +4272 1959 1960 1961 +4273 1959 1961 2021 +4274 1979 1959 2021 +4275 1968 1960 2011 +4276 1961 2020 2021 +4277 1962 2013 1963 +4278 1964 1963 1965 +4279 2013 1965 1963 +4280 1964 1965 1966 +4281 1966 1965 2012 +4282 2014 1966 2012 +4283 1967 1969 1968 +4284 1968 2011 1967 +4285 1974 1977 1967 +4286 2011 1974 1967 +4287 2064 2071 1969 +4288 1970 1971 2050 +4289 2041 1971 1972 +4290 1971 2041 2055 +4291 2055 2050 1971 +4292 1974 1976 1975 +4293 1974 1975 1977 +4294 1974 2011 1976 +4295 1976 1978 1975 +4296 1977 1975 2002 +4297 2003 1977 2002 +4298 1977 2003 2077 +4299 1982 1984 1983 +4300 1982 2004 1984 +4301 2067 1983 1984 +4302 1984 1988 1987 +4303 1987 2067 1984 +4304 2004 1988 1984 +4305 2038 2039 1986 +4306 2042 1986 2039 +4307 1987 1988 1989 +4308 2067 1987 1990 +4309 2002 1988 2003 +4310 2003 1988 2004 +4311 2066 2067 1990 +4312 1993 1992 1994 +4313 1993 2004 1992 +4314 1993 1994 1995 +4315 1993 1995 2077 +4316 2004 1993 2077 +4317 1996 1998 1997 +4318 1997 2015 1996 +4319 2024 1998 1996 +4320 2000 1996 2001 +4321 2000 2024 1996 +4322 2015 2001 1996 +4323 1997 1998 1999 +4324 1997 1999 2032 +4325 1999 1998 2025 +4326 2026 1998 2024 +4327 2025 1998 2026 +4328 2006 2007 1999 +4329 2006 1999 2025 +4330 1999 2007 2032 +4331 2012 2001 2014 +4332 2014 2001 2015 +4333 2003 2004 2077 +4334 2005 2007 2006 +4335 2007 2005 2008 +4336 2006 2025 2027 +4337 2031 2032 2007 +4338 2037 2060 2017 +4339 2060 2051 2017 +4340 2019 2021 2020 +4341 2019 2020 2022 +4342 2026 2035 2025 +4343 2035 2027 2025 +4344 2035 2026 2034 +4345 2028 2030 2029 +4346 2082 2043 2073 +4347 2084 2081 2058 +4348 2068 2070 2069 +4349 2070 2068 2079 +2 18 2 98 +4350 8 2106 78 +4351 309 2106 8 +4352 78 2108 9 +4353 9 2108 159 +4354 180 2109 19 +4355 19 2109 331 +4356 24 2107 330 +4357 331 2107 24 +4358 2106 2108 78 +4359 159 2085 160 +4360 159 2108 2085 +4361 160 2097 161 +4362 2085 2097 160 +4363 161 2086 162 +4364 161 2097 2086 +4365 162 2098 163 +4366 2086 2098 162 +4367 163 2087 164 +4368 163 2098 2087 +4369 164 2099 165 +4370 2087 2099 164 +4371 165 2088 166 +4372 165 2099 2088 +4373 166 2100 167 +4374 2088 2100 166 +4375 167 2089 168 +4376 167 2100 2089 +4377 168 2101 169 +4378 2089 2101 168 +4379 169 2090 170 +4380 169 2101 2090 +4381 170 2102 171 +4382 2090 2102 170 +4383 171 2091 172 +4384 171 2102 2091 +4385 172 2103 173 +4386 2091 2103 172 +4387 173 2092 174 +4388 173 2103 2092 +4389 174 2104 175 +4390 2092 2104 174 +4391 175 2093 176 +4392 175 2104 2093 +4393 176 2105 177 +4394 2093 2105 176 +4395 177 2094 178 +4396 177 2105 2094 +4397 178 2096 179 +4398 2094 2096 178 +4399 179 2095 180 +4400 179 2096 2095 +4401 2095 2109 180 +4402 310 2085 309 +4403 2085 2106 309 +4404 311 2097 310 +4405 310 2097 2085 +4406 312 2086 311 +4407 2086 2097 311 +4408 313 2098 312 +4409 312 2098 2086 +4410 314 2087 313 +4411 2087 2098 313 +4412 315 2099 314 +4413 314 2099 2087 +4414 316 2088 315 +4415 2088 2099 315 +4416 317 2100 316 +4417 316 2100 2088 +4418 318 2089 317 +4419 2089 2100 317 +4420 319 2101 318 +4421 318 2101 2089 +4422 320 2090 319 +4423 2090 2101 319 +4424 321 2102 320 +4425 320 2102 2090 +4426 322 2091 321 +4427 2091 2102 321 +4428 323 2103 322 +4429 322 2103 2091 +4430 324 2092 323 +4431 2092 2103 323 +4432 325 2104 324 +4433 324 2104 2092 +4434 326 2093 325 +4435 2093 2104 325 +4436 327 2105 326 +4437 326 2105 2093 +4438 328 2094 327 +4439 2094 2105 327 +4440 329 2096 328 +4441 328 2096 2094 +4442 330 2095 329 +4443 2095 2096 329 +4444 330 2107 2095 +4445 331 2109 2107 +4446 2085 2108 2106 +4447 2107 2109 2095 +2 19 2 409 +4448 19 2201 183 +4449 331 2270 19 +4450 19 2270 2201 +4451 181 2217 20 +4452 20 2217 215 +4453 206 2181 21 +4454 21 2232 240 +4455 2181 2232 21 +4456 238 2199 22 +4457 22 2269 263 +4458 2199 2269 22 +4459 263 2171 23 +4460 23 2191 308 +4461 2171 2191 23 +4462 286 2197 24 +4463 24 2173 331 +4464 24 2197 2173 +4465 182 2244 181 +4466 181 2244 2217 +4467 183 2201 182 +4468 2201 2244 182 +4469 207 2281 206 +4470 206 2281 2181 +4471 208 2210 207 +4472 2210 2281 207 +4473 209 2237 208 +4474 2182 2210 208 +4475 208 2237 2182 +4476 210 2185 209 +4477 2185 2237 209 +4478 211 2228 210 +4479 210 2228 2185 +4480 212 2180 211 +4481 2180 2228 211 +4482 213 2267 212 +4483 212 2267 2180 +4484 214 2220 213 +4485 2220 2267 213 +4486 215 2194 214 +4487 2194 2220 214 +4488 2153 2194 215 +4489 215 2217 2153 +4490 239 2247 238 +4491 238 2247 2199 +4492 240 2247 239 +4493 2232 2247 240 +4494 263 2269 2171 +4495 287 2282 286 +4496 286 2282 2197 +4497 288 2215 287 +4498 2215 2282 287 +4499 289 2159 288 +4500 2159 2215 288 +4501 290 2203 289 +4502 289 2203 2159 +4503 291 2287 290 +4504 290 2287 2203 +4505 292 2272 291 +4506 291 2272 2184 +4507 2184 2287 291 +4508 293 2213 292 +4509 2213 2272 292 +4510 294 2268 293 +4511 2162 2213 293 +4512 293 2268 2162 +4513 295 2268 294 +4514 296 2229 295 +4515 295 2229 2169 +4516 2169 2268 295 +4517 297 2276 296 +4518 296 2276 2229 +4519 298 2196 297 +4520 2196 2276 297 +4521 299 2233 298 +4522 298 2233 2196 +4523 300 2176 299 +4524 2176 2233 299 +4525 301 2187 300 +4526 300 2187 2176 +4527 302 2241 301 +4528 301 2241 2187 +4529 303 2198 302 +4530 2198 2241 302 +4531 304 2198 303 +4532 305 2211 304 +4533 304 2211 2198 +4534 306 2277 305 +4535 305 2277 2211 +4536 307 2212 306 +4537 2212 2277 306 +4538 308 2256 307 +4539 307 2256 2212 +4540 2191 2256 308 +4541 2173 2270 331 +4542 2110 2206 2175 +4543 2175 2243 2110 +4544 2178 2193 2110 +4545 2110 2218 2178 +4546 2193 2250 2110 +4547 2110 2250 2206 +4548 2110 2243 2218 +4549 2186 2227 2111 +4550 2111 2248 2186 +4551 2192 2248 2111 +4552 2111 2266 2192 +4553 2227 2286 2111 +4554 2111 2286 2266 +4555 2112 2235 2189 +4556 2189 2271 2112 +4557 2112 2289 2235 +4558 2112 2271 2236 +4559 2236 2289 2112 +4560 2174 2205 2113 +4561 2113 2249 2174 +4562 2113 2209 2177 +4563 2177 2249 2113 +4564 2113 2205 2190 +4565 2190 2209 2113 +4566 2183 2200 2114 +4567 2114 2231 2183 +4568 2200 2254 2114 +4569 2114 2278 2231 +4570 2254 2278 2114 +4571 2161 2202 2115 +4572 2115 2290 2161 +4573 2202 2221 2115 +4574 2115 2238 2204 +4575 2204 2290 2115 +4576 2221 2260 2115 +4577 2115 2260 2238 +4578 2116 2214 2163 +4579 2163 2242 2116 +4580 2166 2167 2116 +4581 2116 2242 2166 +4582 2167 2261 2116 +4583 2116 2216 2214 +4584 2116 2261 2216 +4585 2188 2240 2117 +4586 2117 2288 2188 +4587 2117 2240 2226 +4588 2226 2263 2117 +4589 2263 2288 2117 +4590 2156 2179 2118 +4591 2118 2195 2156 +4592 2179 2239 2118 +4593 2118 2251 2195 +4594 2239 2255 2118 +4595 2118 2255 2251 +4596 2154 2208 2119 +4597 2119 2234 2154 +4598 2119 2207 2161 +4599 2161 2234 2119 +4600 2119 2253 2207 +4601 2208 2253 2119 +4602 2120 2222 2158 +4603 2158 2258 2120 +4604 2177 2246 2120 +4605 2120 2258 2177 +4606 2120 2262 2222 +4607 2246 2262 2120 +4608 2160 2223 2121 +4609 2121 2265 2160 +4610 2121 2252 2183 +4611 2183 2265 2121 +4612 2223 2257 2121 +4613 2121 2257 2252 +4614 2162 2169 2122 +4615 2122 2224 2162 +4616 2169 2230 2122 +4617 2122 2274 2224 +4618 2230 2274 2122 +4619 2164 2192 2123 +4620 2123 2245 2164 +4621 2123 2192 2172 +4622 2172 2284 2123 +4623 2123 2210 2182 +4624 2182 2245 2123 +4625 2123 2284 2210 +4626 2124 2175 2174 +4627 2174 2264 2124 +4628 2124 2243 2175 +4629 2124 2264 2186 +4630 2186 2285 2124 +4631 2225 2243 2124 +4632 2124 2285 2225 +4633 2125 2279 2168 +4634 2168 2280 2125 +4635 2178 2219 2125 +4636 2125 2280 2178 +4637 2189 2279 2125 +4638 2125 2291 2189 +4639 2219 2291 2125 +4640 2171 2188 2126 +4641 2126 2191 2171 +4642 2188 2259 2126 +4643 2126 2222 2191 +4644 2126 2259 2222 +4645 2176 2187 2127 +4646 2127 2214 2176 +4647 2187 2275 2127 +4648 2127 2275 2190 +4649 2190 2283 2127 +4650 2127 2283 2214 +4651 2128 2195 2173 +4652 2173 2197 2128 +4653 2128 2273 2195 +4654 2197 2223 2128 +4655 2223 2273 2128 +4656 2129 2208 2154 +4657 2154 2220 2129 +4658 2165 2208 2129 +4659 2129 2236 2165 +4660 2179 2236 2129 +4661 2129 2239 2179 +4662 2129 2220 2194 +4663 2194 2239 2129 +4664 2130 2167 2166 +4665 2166 2250 2130 +4666 2130 2274 2167 +4667 2130 2193 2168 +4668 2168 2278 2130 +4669 2170 2274 2130 +4670 2130 2278 2170 +4671 2130 2250 2193 +4672 2131 2202 2161 +4673 2161 2207 2131 +4674 2178 2218 2131 +4675 2131 2219 2178 +4676 2131 2218 2202 +4677 2207 2219 2131 +4678 2163 2205 2132 +4679 2132 2242 2163 +4680 2132 2206 2166 +4681 2166 2242 2132 +4682 2174 2175 2132 +4683 2132 2205 2174 +4684 2175 2206 2132 +4685 2177 2209 2133 +4686 2133 2246 2177 +4687 2133 2209 2198 +4688 2198 2211 2133 +4689 2211 2246 2133 +4690 2134 2200 2183 +4691 2183 2252 2134 +4692 2184 2200 2134 +4693 2134 2287 2184 +4694 2134 2252 2203 +4695 2203 2287 2134 +4696 2135 2213 2162 +4697 2162 2224 2135 +4698 2135 2200 2184 +4699 2184 2272 2135 +4700 2135 2254 2200 +4701 2135 2272 2213 +4702 2224 2254 2135 +4703 2136 2228 2180 +4704 2180 2234 2136 +4705 2136 2204 2185 +4706 2185 2228 2136 +4707 2136 2290 2204 +4708 2234 2290 2136 +4709 2182 2237 2137 +4710 2137 2245 2182 +4711 2185 2204 2137 +4712 2137 2237 2185 +4713 2204 2238 2137 +4714 2238 2245 2137 +4715 2169 2229 2138 +4716 2138 2230 2169 +4717 2196 2216 2138 +4718 2138 2276 2196 +4719 2216 2261 2138 +4720 2229 2276 2138 +4721 2138 2261 2230 +4722 2181 2226 2139 +4723 2139 2232 2181 +4724 2139 2240 2199 +4725 2199 2247 2139 +4726 2226 2240 2139 +4727 2139 2247 2232 +4728 2140 2248 2164 +4729 2164 2260 2140 +4730 2221 2225 2140 +4731 2140 2260 2221 +4732 2225 2285 2140 +4733 2140 2285 2248 +4734 2176 2214 2141 +4735 2141 2233 2176 +4736 2141 2216 2196 +4737 2196 2233 2141 +4738 2214 2216 2141 +4739 2142 2249 2177 +4740 2177 2258 2142 +4741 2142 2227 2186 +4742 2186 2264 2142 +4743 2142 2258 2227 +4744 2142 2264 2249 +4745 2143 2244 2201 +4746 2201 2251 2143 +4747 2217 2244 2143 +4748 2143 2255 2217 +4749 2251 2255 2143 +4750 2202 2218 2144 +4751 2144 2221 2202 +4752 2218 2243 2144 +4753 2144 2225 2221 +4754 2144 2243 2225 +4755 2145 2188 2171 +4756 2171 2269 2145 +4757 2145 2240 2188 +4758 2199 2240 2145 +4759 2145 2269 2199 +4760 2187 2241 2146 +4761 2146 2275 2187 +4762 2146 2209 2190 +4763 2190 2275 2146 +4764 2198 2209 2146 +4765 2146 2241 2198 +4766 2183 2231 2147 +4767 2147 2265 2183 +4768 2189 2235 2147 +4769 2147 2279 2189 +4770 2231 2279 2147 +4771 2235 2265 2147 +4772 2148 2219 2207 +4773 2207 2253 2148 +4774 2148 2291 2219 +4775 2253 2271 2148 +4776 2271 2291 2148 +4777 2173 2195 2149 +4778 2149 2270 2173 +4779 2195 2251 2149 +4780 2149 2251 2201 +4781 2201 2270 2149 +4782 2150 2226 2181 +4783 2181 2281 2150 +4784 2150 2281 2210 +4785 2210 2284 2150 +4786 2150 2263 2226 +4787 2150 2284 2263 +4788 2191 2222 2151 +4789 2151 2256 2191 +4790 2212 2256 2151 +4791 2151 2262 2212 +4792 2222 2262 2151 +4793 2152 2223 2197 +4794 2197 2282 2152 +4795 2215 2257 2152 +4796 2152 2282 2215 +4797 2152 2257 2223 +4798 2153 2239 2194 +4799 2217 2255 2153 +4800 2153 2255 2239 +4801 2154 2234 2180 +4802 2180 2267 2154 +4803 2154 2267 2220 +4804 2155 2259 2188 +4805 2188 2288 2155 +4806 2155 2286 2259 +4807 2266 2286 2155 +4808 2155 2288 2266 +4809 2156 2236 2179 +4810 2195 2273 2156 +4811 2156 2289 2236 +4812 2273 2289 2156 +4813 2157 2246 2211 +4814 2211 2277 2157 +4815 2212 2262 2157 +4816 2157 2277 2212 +4817 2157 2262 2246 +4818 2222 2259 2158 +4819 2227 2258 2158 +4820 2158 2286 2227 +4821 2259 2286 2158 +4822 2203 2252 2159 +4823 2159 2257 2215 +4824 2252 2257 2159 +4825 2160 2273 2223 +4826 2160 2265 2235 +4827 2235 2289 2160 +4828 2160 2289 2273 +4829 2161 2290 2234 +4830 2162 2268 2169 +4831 2163 2283 2205 +4832 2214 2283 2163 +4833 2164 2248 2192 +4834 2164 2245 2238 +4835 2238 2260 2164 +4836 2165 2253 2208 +4837 2236 2271 2165 +4838 2165 2271 2253 +4839 2206 2250 2166 +4840 2230 2261 2167 +4841 2167 2274 2230 +4842 2193 2280 2168 +4843 2231 2278 2168 +4844 2168 2279 2231 +4845 2170 2254 2224 +4846 2224 2274 2170 +4847 2170 2278 2254 +4848 2192 2266 2172 +4849 2263 2284 2172 +4850 2172 2288 2263 +4851 2266 2288 2172 +4852 2249 2264 2174 +4853 2178 2280 2193 +4854 2248 2285 2186 +4855 2189 2291 2271 +4856 2205 2283 2190 +2 20 2 584 +4857 25 332 2538 +4858 371 25 2538 +4859 341 26 2537 +4860 26 342 2537 +4861 360 27 2468 +4862 27 361 2468 +4863 370 28 2501 +4864 28 389 2501 +4865 332 333 2444 +4866 2394 332 2444 +4867 332 2394 2538 +4868 333 334 2444 +4869 334 335 2457 +4870 334 2366 2444 +4871 2366 334 2457 +4872 335 336 2411 +4873 335 2411 2457 +4874 336 337 2362 +4875 336 2362 2411 +4876 337 338 2412 +4877 2362 337 2412 +4878 338 339 2456 +4879 2412 338 2456 +4880 339 340 2443 +4881 2367 339 2443 +4882 339 2367 2456 +4883 340 341 2443 +4884 341 2393 2443 +4885 2393 341 2537 +4886 342 343 2545 +4887 2537 342 2545 +4888 343 344 2420 +4889 343 2420 2545 +4890 344 345 2549 +4891 2420 344 2549 +4892 345 346 2524 +4893 2432 345 2524 +4894 345 2432 2549 +4895 346 347 2552 +4896 346 2390 2524 +4897 2390 346 2552 +4898 347 348 2498 +4899 347 2498 2552 +4900 348 349 2417 +4901 348 2417 2498 +4902 349 350 2397 +4903 349 2397 2417 +4904 350 351 2445 +4905 2397 350 2445 +4906 351 352 2360 +4907 351 2360 2445 +4908 352 353 2416 +4909 2360 352 2416 +4910 353 354 2530 +4911 2416 353 2530 +4912 354 355 2479 +4913 2415 354 2479 +4914 354 2415 2530 +4915 355 356 2381 +4916 355 2381 2479 +4917 356 357 2429 +4918 2381 356 2429 +4919 357 358 2480 +4920 2429 357 2480 +4921 358 359 2380 +4922 358 2380 2480 +4923 359 360 2499 +4924 2380 359 2499 +4925 360 2468 2499 +4926 361 362 2500 +4927 2468 361 2500 +4928 362 363 2395 +4929 362 2395 2500 +4930 363 364 2496 +4931 2395 363 2496 +4932 364 365 2384 +4933 364 2384 2496 +4934 365 366 2425 +4935 2384 365 2425 +4936 366 367 2454 +4937 2425 366 2454 +4938 367 368 2532 +4939 2454 367 2532 +4940 368 369 2403 +4941 368 2403 2532 +4942 369 370 2515 +4943 2403 369 2515 +4944 370 2501 2515 +4945 372 371 2546 +4946 371 2538 2546 +4947 373 372 2421 +4948 2421 372 2546 +4949 374 373 2550 +4950 373 2421 2550 +4951 375 374 2525 +4952 374 2433 2525 +4953 2433 374 2550 +4954 376 375 2547 +4955 2391 375 2525 +4956 375 2391 2547 +4957 377 376 2493 +4958 2493 376 2547 +4959 378 377 2408 +4960 2408 377 2493 +4961 379 378 2542 +4962 378 2408 2542 +4963 380 379 2490 +4964 2490 379 2542 +4965 381 380 2517 +4966 2406 380 2490 +4967 380 2406 2517 +4968 382 381 2464 +4969 2464 381 2517 +4970 383 382 2467 +4971 2363 382 2464 +4972 382 2363 2467 +4973 384 383 2400 +4974 2400 383 2467 +4975 385 384 2474 +4976 384 2400 2474 +4977 386 385 2383 +4978 2383 385 2474 +4979 387 386 2459 +4980 386 2383 2459 +4981 388 387 2461 +4982 387 2459 2461 +4983 389 388 2461 +4984 389 2461 2501 +4985 2292 2389 2458 +4986 2389 2292 2541 +4987 2292 2398 2503 +4988 2398 2292 2516 +4989 2407 2292 2503 +4990 2292 2407 2541 +4991 2292 2458 2516 +4992 2293 2365 2396 +4993 2365 2293 2509 +4994 2373 2293 2396 +4995 2293 2373 2426 +4996 2378 2293 2426 +4997 2293 2378 2509 +4998 2374 2294 2436 +4999 2294 2374 2494 +5000 2392 2294 2494 +5001 2294 2392 2497 +5002 2294 2409 2436 +5003 2409 2294 2497 +5004 2357 2295 2399 +5005 2295 2357 2405 +5006 2295 2372 2399 +5007 2372 2295 2450 +5008 2376 2295 2405 +5009 2295 2376 2450 +5010 2377 2296 2492 +5011 2296 2377 2495 +5012 2296 2382 2504 +5013 2382 2296 2533 +5014 2296 2410 2492 +5015 2410 2296 2504 +5016 2296 2495 2533 +5017 2297 2375 2435 +5018 2375 2297 2535 +5019 2297 2386 2404 +5020 2386 2297 2539 +5021 2297 2404 2523 +5022 2431 2297 2523 +5023 2297 2431 2535 +5024 2297 2435 2539 +5025 2368 2298 2447 +5026 2298 2368 2486 +5027 2298 2402 2478 +5028 2402 2298 2486 +5029 2298 2414 2463 +5030 2414 2298 2478 +5031 2447 2298 2463 +5032 2299 2385 2413 +5033 2385 2299 2453 +5034 2299 2401 2469 +5035 2401 2299 2477 +5036 2299 2413 2477 +5037 2453 2299 2534 +5038 2299 2469 2534 +5039 2300 2387 2475 +5040 2387 2300 2519 +5041 2300 2388 2438 +5042 2388 2300 2462 +5043 2300 2438 2519 +5044 2462 2300 2475 +5045 2301 2351 2422 +5046 2351 2301 2442 +5047 2301 2422 2488 +5048 2427 2301 2488 +5049 2301 2427 2520 +5050 2442 2301 2520 +5051 2302 2370 2439 +5052 2370 2302 2441 +5053 2302 2371 2448 +5054 2371 2302 2471 +5055 2302 2439 2529 +5056 2441 2302 2448 +5057 2471 2302 2529 +5058 2303 2419 2452 +5059 2419 2303 2528 +5060 2424 2303 2452 +5061 2303 2424 2518 +5062 2451 2303 2518 +5063 2303 2451 2528 +5064 2423 2304 2466 +5065 2304 2423 2544 +5066 2304 2428 2485 +5067 2428 2304 2544 +5068 2304 2440 2466 +5069 2440 2304 2485 +5070 2305 2460 2505 +5071 2460 2305 2527 +5072 2305 2481 2491 +5073 2481 2305 2505 +5074 2305 2491 2527 +5075 2306 2388 2437 +5076 2388 2306 2455 +5077 2306 2437 2506 +5078 2455 2306 2470 +5079 2470 2306 2506 +5080 2307 2362 2449 +5081 2362 2307 2465 +5082 2307 2368 2434 +5083 2368 2307 2449 +5084 2418 2307 2434 +5085 2307 2418 2465 +5086 2374 2308 2476 +5087 2308 2374 2548 +5088 2308 2375 2430 +5089 2375 2308 2548 +5090 2378 2308 2430 +5091 2308 2378 2511 +5092 2476 2308 2511 +5093 2309 2369 2473 +5094 2369 2309 2521 +5095 2386 2309 2507 +5096 2309 2386 2521 +5097 2309 2473 2512 +5098 2507 2309 2512 +5099 2387 2310 2392 +5100 2310 2387 2484 +5101 2392 2310 2543 +5102 2310 2484 2540 +5103 2489 2310 2540 +5104 2310 2489 2543 +5105 2364 2311 2409 +5106 2311 2364 2502 +5107 2311 2384 2482 +5108 2384 2311 2502 +5109 2409 2311 2551 +5110 2311 2482 2551 +5111 2372 2312 2483 +5112 2312 2372 2508 +5113 2312 2382 2472 +5114 2382 2312 2508 +5115 2398 2312 2472 +5116 2312 2398 2483 +5117 2313 2361 2377 +5118 2361 2313 2490 +5119 2371 2313 2492 +5120 2313 2371 2553 +5121 2313 2377 2492 +5122 2313 2406 2490 +5123 2406 2313 2553 +5124 2355 2314 2403 +5125 2314 2355 2487 +5126 2314 2356 2403 +5127 2356 2314 2427 +5128 2314 2369 2427 +5129 2369 2314 2473 +5130 2473 2314 2487 +5131 2359 2315 2446 +5132 2315 2359 2508 +5133 2315 2372 2450 +5134 2372 2315 2508 +5135 2315 2373 2396 +5136 2373 2315 2514 +5137 2315 2396 2446 +5138 2315 2450 2514 +5139 2316 2363 2439 +5140 2363 2316 2467 +5141 2370 2316 2439 +5142 2316 2370 2523 +5143 2316 2400 2467 +5144 2400 2316 2526 +5145 2404 2316 2523 +5146 2316 2404 2526 +5147 2357 2317 2405 +5148 2317 2357 2424 +5149 2397 2317 2417 +5150 2317 2397 2513 +5151 2405 2317 2513 +5152 2417 2317 2424 +5153 2361 2318 2377 +5154 2318 2361 2408 +5155 2377 2318 2495 +5156 2318 2408 2531 +5157 2318 2423 2495 +5158 2423 2318 2531 +5159 2319 2366 2401 +5160 2366 2319 2444 +5161 2394 2319 2421 +5162 2319 2394 2444 +5163 2319 2401 2477 +5164 2421 2319 2477 +5165 2367 2320 2402 +5166 2320 2367 2443 +5167 2320 2393 2420 +5168 2393 2320 2443 +5169 2402 2320 2478 +5170 2320 2420 2478 +5171 2365 2321 2396 +5172 2321 2365 2448 +5173 2321 2371 2410 +5174 2371 2321 2448 +5175 2396 2321 2446 +5176 2321 2410 2504 +5177 2446 2321 2504 +5178 2353 2322 2414 +5179 2322 2353 2432 +5180 2322 2390 2452 +5181 2390 2322 2524 +5182 2414 2322 2463 +5183 2419 2322 2452 +5184 2322 2419 2463 +5185 2322 2432 2524 +5186 2323 2354 2413 +5187 2354 2323 2433 +5188 2385 2323 2413 +5189 2323 2385 2428 +5190 2391 2323 2428 +5191 2323 2391 2525 +5192 2433 2323 2525 +5193 2351 2324 2436 +5194 2324 2351 2442 +5195 2435 2324 2442 +5196 2324 2435 2548 +5197 2436 2324 2548 +5198 2365 2325 2441 +5199 2325 2365 2509 +5200 2370 2325 2431 +5201 2325 2370 2441 +5202 2325 2378 2430 +5203 2378 2325 2509 +5204 2325 2430 2535 +5205 2431 2325 2535 +5206 2368 2326 2434 +5207 2326 2368 2447 +5208 2326 2389 2434 +5209 2389 2326 2458 +5210 2326 2447 2510 +5211 2458 2326 2510 +5212 2327 2385 2453 +5213 2385 2327 2485 +5214 2327 2407 2440 +5215 2407 2327 2541 +5216 2327 2440 2485 +5217 2327 2453 2522 +5218 2327 2522 2541 +5219 2366 2328 2401 +5220 2328 2366 2457 +5221 2401 2328 2469 +5222 2411 2328 2457 +5223 2328 2411 2465 +5224 2418 2328 2465 +5225 2328 2418 2469 +5226 2329 2367 2402 +5227 2367 2329 2456 +5228 2329 2368 2449 +5229 2368 2329 2486 +5230 2329 2402 2486 +5231 2412 2329 2449 +5232 2329 2412 2456 +5233 2388 2330 2437 +5234 2330 2388 2462 +5235 2426 2330 2462 +5236 2330 2426 2536 +5237 2437 2330 2536 +5238 2331 2357 2399 +5239 2357 2331 2518 +5240 2331 2379 2451 +5241 2379 2331 2516 +5242 2398 2331 2483 +5243 2331 2398 2516 +5244 2331 2399 2483 +5245 2331 2451 2518 +5246 2332 2358 2466 +5247 2358 2332 2533 +5248 2382 2332 2472 +5249 2332 2382 2533 +5250 2407 2332 2440 +5251 2332 2407 2503 +5252 2440 2332 2466 +5253 2472 2332 2503 +5254 2333 2376 2405 +5255 2376 2333 2470 +5256 2333 2397 2445 +5257 2397 2333 2513 +5258 2333 2405 2513 +5259 2333 2445 2470 +5260 2388 2334 2438 +5261 2334 2388 2455 +5262 2334 2415 2438 +5263 2415 2334 2530 +5264 2416 2334 2455 +5265 2334 2416 2530 +5266 2381 2335 2479 +5267 2335 2381 2484 +5268 2415 2335 2438 +5269 2335 2415 2479 +5270 2438 2335 2519 +5271 2335 2484 2519 +5272 2336 2383 2474 +5273 2383 2336 2507 +5274 2386 2336 2404 +5275 2336 2386 2507 +5276 2400 2336 2474 +5277 2336 2400 2526 +5278 2404 2336 2526 +5279 2337 2422 2482 +5280 2422 2337 2488 +5281 2337 2425 2454 +5282 2425 2337 2482 +5283 2337 2454 2488 +5284 2338 2387 2392 +5285 2387 2338 2475 +5286 2338 2392 2494 +5287 2475 2338 2476 +5288 2476 2338 2494 +5289 2339 2380 2499 +5290 2380 2339 2505 +5291 2339 2395 2481 +5292 2395 2339 2500 +5293 2468 2339 2499 +5294 2339 2468 2500 +5295 2339 2481 2505 +5296 2380 2340 2480 +5297 2340 2380 2505 +5298 2340 2429 2480 +5299 2429 2340 2540 +5300 2340 2460 2489 +5301 2460 2340 2505 +5302 2340 2489 2540 +5303 2376 2341 2450 +5304 2341 2376 2506 +5305 2437 2341 2506 +5306 2341 2437 2536 +5307 2450 2341 2514 +5308 2514 2341 2536 +5309 2384 2342 2496 +5310 2342 2384 2502 +5311 2395 2342 2481 +5312 2342 2395 2496 +5313 2481 2342 2491 +5314 2491 2342 2502 +5315 2343 2379 2510 +5316 2379 2343 2528 +5317 2419 2343 2463 +5318 2343 2419 2528 +5319 2343 2447 2463 +5320 2447 2343 2510 +5321 2389 2344 2434 +5322 2344 2389 2522 +5323 2344 2418 2434 +5324 2418 2344 2534 +5325 2453 2344 2522 +5326 2344 2453 2534 +5327 2345 2363 2464 +5328 2363 2345 2529 +5329 2406 2345 2517 +5330 2345 2406 2553 +5331 2345 2464 2517 +5332 2345 2471 2529 +5333 2471 2345 2553 +5334 2346 2391 2544 +5335 2391 2346 2547 +5336 2346 2423 2531 +5337 2423 2346 2544 +5338 2493 2346 2531 +5339 2346 2493 2547 +5340 2390 2347 2452 +5341 2347 2390 2552 +5342 2347 2417 2424 +5343 2417 2347 2498 +5344 2347 2424 2452 +5345 2498 2347 2552 +5346 2392 2348 2497 +5347 2348 2392 2543 +5348 2460 2348 2489 +5349 2348 2460 2527 +5350 2489 2348 2543 +5351 2497 2348 2527 +5352 2459 2349 2461 +5353 2349 2459 2512 +5354 2461 2349 2487 +5355 2349 2473 2487 +5356 2473 2349 2512 +5357 2350 2435 2442 +5358 2435 2350 2539 +5359 2350 2442 2520 +5360 2350 2520 2521 +5361 2350 2521 2539 +5362 2409 2351 2436 +5363 2351 2409 2551 +5364 2422 2351 2551 +5365 2352 2426 2462 +5366 2426 2352 2511 +5367 2352 2462 2475 +5368 2352 2475 2476 +5369 2352 2476 2511 +5370 2353 2414 2478 +5371 2420 2353 2478 +5372 2353 2420 2549 +5373 2432 2353 2549 +5374 2413 2354 2477 +5375 2354 2421 2477 +5376 2421 2354 2550 +5377 2354 2433 2550 +5378 2355 2403 2515 +5379 2355 2461 2487 +5380 2461 2355 2501 +5381 2501 2355 2515 +5382 2403 2356 2532 +5383 2356 2427 2488 +5384 2454 2356 2488 +5385 2356 2454 2532 +5386 2424 2357 2518 +5387 2358 2423 2466 +5388 2423 2358 2495 +5389 2495 2358 2533 +5390 2382 2359 2504 +5391 2359 2382 2508 +5392 2359 2446 2504 +5393 2360 2416 2455 +5394 2445 2360 2470 +5395 2360 2455 2470 +5396 2408 2361 2542 +5397 2361 2490 2542 +5398 2411 2362 2465 +5399 2362 2412 2449 +5400 2439 2363 2529 +5401 2364 2409 2497 +5402 2364 2491 2502 +5403 2491 2364 2527 +5404 2364 2497 2527 +5405 2365 2441 2448 +5406 2427 2369 2520 +5407 2520 2369 2521 +5408 2370 2431 2523 +5409 2410 2371 2492 +5410 2371 2471 2553 +5411 2399 2372 2483 +5412 2426 2373 2536 +5413 2373 2514 2536 +5414 2374 2436 2548 +5415 2374 2476 2494 +5416 2430 2375 2535 +5417 2435 2375 2548 +5418 2376 2470 2506 +5419 2378 2426 2511 +5420 2451 2379 2528 +5421 2379 2458 2510 +5422 2458 2379 2516 +5423 2381 2429 2540 +5424 2484 2381 2540 +5425 2459 2383 2512 +5426 2383 2507 2512 +5427 2384 2425 2482 +5428 2428 2385 2485 +5429 2521 2386 2539 +5430 2484 2387 2519 +5431 2522 2389 2541 +5432 2391 2428 2544 +5433 2420 2393 2545 +5434 2393 2537 2545 +5435 2394 2421 2546 +5436 2538 2394 2546 +5437 2398 2472 2503 +5438 2408 2493 2531 +5439 2469 2418 2534 +5440 2482 2422 2551 +2 21 2 86 +5441 342 26 2572 +5442 26 390 2572 +5443 27 360 2573 +5444 410 27 2573 +5445 390 29 2575 +5446 29 391 2575 +5447 409 30 2574 +5448 30 410 2574 +5449 343 342 2554 +5450 2554 342 2572 +5451 344 343 2569 +5452 343 2554 2569 +5453 345 344 2555 +5454 2555 344 2569 +5455 346 345 2564 +5456 345 2555 2564 +5457 347 346 2556 +5458 2556 346 2564 +5459 348 347 2570 +5460 347 2556 2570 +5461 349 348 2557 +5462 2557 348 2570 +5463 350 349 2571 +5464 349 2557 2571 +5465 351 350 2558 +5466 2558 350 2571 +5467 352 351 2565 +5468 351 2558 2565 +5469 353 352 2559 +5470 2559 352 2565 +5471 354 353 2566 +5472 353 2559 2566 +5473 355 354 2560 +5474 2560 354 2566 +5475 356 355 2567 +5476 355 2560 2567 +5477 357 356 2561 +5478 2561 356 2567 +5479 358 357 2568 +5480 357 2561 2568 +5481 359 358 2562 +5482 2562 358 2568 +5483 360 359 2563 +5484 359 2562 2563 +5485 360 2563 2573 +5486 2572 390 2575 +5487 391 392 2554 +5488 391 2554 2575 +5489 392 393 2569 +5490 2554 392 2569 +5491 393 394 2555 +5492 393 2555 2569 +5493 394 395 2564 +5494 2555 394 2564 +5495 395 396 2556 +5496 395 2556 2564 +5497 396 397 2570 +5498 2556 396 2570 +5499 397 398 2557 +5500 397 2557 2570 +5501 398 399 2571 +5502 2557 398 2571 +5503 399 400 2558 +5504 399 2558 2571 +5505 400 401 2565 +5506 2558 400 2565 +5507 401 402 2559 +5508 401 2559 2565 +5509 402 403 2566 +5510 2559 402 2566 +5511 403 404 2560 +5512 403 2560 2566 +5513 404 405 2567 +5514 2560 404 2567 +5515 405 406 2561 +5516 405 2561 2567 +5517 406 407 2568 +5518 2561 406 2568 +5519 407 408 2562 +5520 407 2562 2568 +5521 408 409 2563 +5522 2562 408 2563 +5523 2563 409 2574 +5524 410 2573 2574 +5525 2554 2572 2575 +5526 2573 2563 2574 +2 22 2 924 +5527 2779 391 29 +5528 447 2779 29 +5529 30 409 2777 +5530 30 2777 427 +5531 411 2776 31 +5532 2776 446 31 +5533 32 428 2774 +5534 32 2774 463 +5535 392 391 2590 +5536 2590 391 2779 +5537 392 2592 393 +5538 2590 2592 392 +5539 2712 394 393 +5540 2592 2594 393 +5541 2712 393 2594 +5542 2894 395 394 +5543 2712 2894 394 +5544 396 395 2892 +5545 2894 2892 395 +5546 397 396 2737 +5547 2737 396 2892 +5548 2738 398 397 +5549 2737 2738 397 +5550 399 398 2984 +5551 2738 2984 398 +5552 400 399 2992 +5553 399 2984 2992 +5554 2648 401 400 +5555 400 3000 2648 +5556 400 2992 3000 +5557 2674 402 401 +5558 2674 401 2648 +5559 402 2753 403 +5560 2968 402 2674 +5561 2968 2753 402 +5562 2754 404 403 +5563 403 2753 2754 +5564 2767 405 404 +5565 2767 404 2754 +5566 406 405 2765 +5567 405 2766 2765 +5568 405 2767 2766 +5569 407 406 2597 +5570 406 2765 2597 +5571 407 2587 408 +5572 2587 407 2597 +5573 2589 409 408 +5574 408 2587 2589 +5575 2777 409 2589 +5576 411 412 2778 +5577 411 2778 2776 +5578 2782 412 413 +5579 2778 412 2782 +5580 2720 413 414 +5581 413 2720 2782 +5582 2900 414 415 +5583 2718 2720 414 +5584 2718 414 2900 +5585 2872 415 416 +5586 2900 415 2872 +5587 2761 416 417 +5588 2619 416 2761 +5589 2872 416 2619 +5590 2761 417 418 +5591 2844 418 419 +5592 2761 418 2830 +5593 418 2844 2830 +5594 419 420 2832 +5595 419 2832 2841 +5596 2844 419 2841 +5597 2832 420 421 +5598 2609 421 422 +5599 2609 2832 421 +5600 422 423 2874 +5601 2608 2609 422 +5602 2608 422 2874 +5603 423 424 2773 +5604 2874 423 2773 +5605 424 425 2789 +5606 2773 424 2789 +5607 425 426 2787 +5608 2787 2789 425 +5609 2780 426 427 +5610 2787 426 2780 +5611 2777 2780 427 +5612 2580 428 429 +5613 2774 428 2580 +5614 430 2577 429 +5615 429 2577 2580 +5616 430 431 2578 +5617 2577 430 2578 +5618 431 432 2762 +5619 431 2762 2578 +5620 2764 432 433 +5621 432 2763 2762 +5622 432 2764 2763 +5623 2744 433 434 +5624 2764 433 2744 +5625 435 2743 434 +5626 434 2743 2744 +5627 2670 435 436 +5628 2966 435 2670 +5629 2966 2743 435 +5630 2644 436 437 +5631 2670 436 2644 +5632 437 438 2991 +5633 437 2999 2644 +5634 437 2991 2999 +5635 438 439 2980 +5636 438 2980 2991 +5637 2733 439 440 +5638 2733 2980 439 +5639 440 441 2732 +5640 2732 2733 440 +5641 441 442 2886 +5642 2732 441 2886 +5643 2893 442 443 +5644 2893 2886 442 +5645 2706 443 444 +5646 2706 2893 443 +5647 445 2584 444 +5648 2584 2585 444 +5649 2706 444 2585 +5650 445 446 2582 +5651 2582 2584 445 +5652 2582 446 2776 +5653 447 448 2781 +5654 447 2781 2779 +5655 2783 448 449 +5656 2781 448 2783 +5657 2727 449 450 +5658 449 2727 2783 +5659 2899 450 451 +5660 2725 2727 450 +5661 2725 450 2899 +5662 2864 451 452 +5663 2899 451 2864 +5664 2760 452 453 +5665 2615 452 2760 +5666 2864 452 2615 +5667 2760 453 454 +5668 2837 454 455 +5669 2760 454 2829 +5670 454 2837 2829 +5671 455 456 2833 +5672 455 2833 2838 +5673 2837 455 2838 +5674 2833 456 457 +5675 2603 457 458 +5676 2603 2833 457 +5677 458 459 2868 +5678 2602 2603 458 +5679 2602 458 2868 +5680 459 460 2771 +5681 2868 459 2771 +5682 460 461 2786 +5683 2771 460 2786 +5684 461 462 2784 +5685 2784 2786 461 +5686 2775 462 463 +5687 2784 462 2775 +5688 2774 2775 463 +5689 2576 2577 2578 +5690 2581 2577 2576 +5691 2762 2576 2578 +5692 2576 2682 2581 +5693 2682 2576 2762 +5694 2577 2579 2580 +5695 2581 2579 2577 +5696 2580 2579 2775 +5697 2579 2581 2599 +5698 2579 2599 2785 +5699 2775 2579 2784 +5700 2784 2579 2785 +5701 2775 2774 2580 +5702 2581 2600 2599 +5703 2600 2581 2682 +5704 2582 2583 2584 +5705 2582 2776 2583 +5706 2584 2583 2586 +5707 2583 2719 2586 +5708 2719 2583 2782 +5709 2778 2583 2776 +5710 2583 2778 2782 +5711 2585 2584 2586 +5712 2585 2586 2705 +5713 2585 2705 2706 +5714 2636 2586 2634 +5715 2719 2634 2586 +5716 2586 2636 2705 +5717 2587 2588 2589 +5718 2593 2588 2587 +5719 2593 2587 2596 +5720 2596 2587 2597 +5721 2589 2588 2780 +5722 2588 2593 2605 +5723 2588 2605 2788 +5724 2780 2588 2787 +5725 2787 2588 2788 +5726 2780 2777 2589 +5727 2590 2591 2592 +5728 2590 2779 2591 +5729 2592 2591 2595 +5730 2591 2726 2595 +5731 2726 2591 2783 +5732 2781 2591 2779 +5733 2591 2781 2783 +5734 2594 2592 2595 +5735 2596 2684 2593 +5736 2593 2606 2605 +5737 2606 2593 2684 +5738 2594 2595 2711 +5739 2594 2711 2712 +5740 2611 2595 2638 +5741 2595 2611 2711 +5742 2726 2638 2595 +5743 2765 2596 2597 +5744 2684 2596 2765 +5745 2598 2599 2600 +5746 2598 2601 2599 +5747 2598 2600 2681 +5748 2686 2601 2598 +5749 2681 2685 2598 +5750 2685 2686 2598 +5751 2601 2785 2599 +5752 2600 2682 2681 +5753 2601 2686 2770 +5754 2601 2770 2771 +5755 2786 2601 2771 +5756 2785 2601 2786 +5757 2602 2752 2603 +5758 2602 2724 2752 +5759 2602 2770 2724 +5760 2770 2602 2868 +5761 2834 2603 2752 +5762 2834 2833 2603 +5763 2604 2605 2606 +5764 2604 2607 2605 +5765 2604 2606 2683 +5766 2689 2607 2604 +5767 2683 2688 2604 +5768 2688 2689 2604 +5769 2607 2788 2605 +5770 2606 2684 2683 +5771 2607 2689 2772 +5772 2607 2772 2773 +5773 2789 2607 2773 +5774 2788 2607 2789 +5775 2608 2755 2609 +5776 2608 2731 2755 +5777 2608 2772 2731 +5778 2772 2608 2874 +5779 2835 2609 2755 +5780 2835 2832 2609 +5781 2610 2611 2612 +5782 2610 2711 2611 +5783 2890 2610 2612 +5784 2711 2610 2894 +5785 2610 2890 2894 +5786 2612 2611 2637 +5787 2637 2611 2638 +5788 2637 2828 2612 +5789 2891 2612 2828 +5790 2890 2612 2891 +5791 2613 2614 2615 +5792 2613 2616 2614 +5793 2757 2613 2615 +5794 2797 2616 2613 +5795 2613 2757 2795 +5796 2613 2795 2797 +5797 2615 2614 2864 +5798 2857 2614 2616 +5799 2614 2857 2899 +5800 2614 2899 2864 +5801 2760 2757 2615 +5802 2616 2797 2827 +5803 2857 2616 2827 +5804 2617 2618 2619 +5805 2617 2620 2618 +5806 2759 2617 2619 +5807 2792 2620 2617 +5808 2617 2759 2790 +5809 2617 2790 2792 +5810 2619 2618 2872 +5811 2858 2618 2620 +5812 2618 2858 2900 +5813 2618 2900 2872 +5814 2761 2759 2619 +5815 2620 2792 2813 +5816 2858 2620 2813 +5817 2621 2622 2623 +5818 2621 2624 2622 +5819 2956 2621 2623 +5820 2624 2621 2908 +5821 2967 2908 2621 +5822 2967 2621 2956 +5823 2986 2623 2622 +5824 2971 2622 2624 +5825 2907 2622 2971 +5826 2622 2907 2986 +5827 2916 2623 2878 +5828 2878 2623 2986 +5829 2956 2623 2916 +5830 2908 2928 2624 +5831 2624 2928 2925 +5832 2971 2624 2925 +5833 2625 2626 2627 +5834 2625 2628 2626 +5835 2964 2625 2627 +5836 2628 2625 2910 +5837 2969 2910 2625 +5838 2969 2625 2964 +5839 2990 2627 2626 +5840 2973 2626 2628 +5841 2904 2626 2973 +5842 2626 2904 2990 +5843 2920 2627 2919 +5844 2919 2627 2990 +5845 2964 2627 2920 +5846 2910 2935 2628 +5847 2628 2935 2933 +5848 2973 2628 2933 +5849 2629 2630 2631 +5850 2630 2629 2655 +5851 2629 2631 2676 +5852 2966 2655 2629 +5853 2629 2676 2743 +5854 2629 2743 2966 +5855 2630 2632 2631 +5856 2630 2859 2632 +5857 2655 2659 2630 +5858 2859 2630 2659 +5859 2881 2631 2632 +5860 2675 2676 2631 +5861 2881 2675 2631 +5862 2652 2654 2632 +5863 2632 2859 2652 +5864 2881 2632 2654 +5865 2633 2634 2635 +5866 2633 2636 2634 +5867 2635 2812 2633 +5868 2665 2636 2633 +5869 2633 2825 2665 +5870 2825 2633 2812 +5871 2748 2635 2634 +5872 2719 2748 2634 +5873 2635 2748 2813 +5874 2635 2813 2812 +5875 2664 2636 2665 +5876 2664 2705 2636 +5877 2637 2638 2639 +5878 2639 2826 2637 +5879 2828 2637 2826 +5880 2742 2639 2638 +5881 2726 2742 2638 +5882 2639 2742 2827 +5883 2639 2827 2826 +5884 2640 2641 2642 +5885 2641 2640 2660 +5886 2640 2642 2679 +5887 2968 2660 2640 +5888 2640 2679 2753 +5889 2640 2753 2968 +5890 2641 2643 2642 +5891 2641 2860 2643 +5892 2660 2666 2641 +5893 2860 2641 2666 +5894 2883 2642 2643 +5895 2678 2679 2642 +5896 2883 2678 2642 +5897 2656 2658 2643 +5898 2643 2860 2656 +5899 2883 2643 2658 +5900 2644 2645 2646 +5901 2644 2999 2645 +5902 2670 2644 2646 +5903 2645 2647 2646 +5904 2647 2645 2921 +5905 2645 2750 2921 +5906 2750 2645 2999 +5907 2647 2655 2646 +5908 2966 2646 2655 +5909 2670 2646 2966 +5910 2647 2659 2655 +5911 2647 2922 2659 +5912 2921 2922 2647 +5913 2648 2649 2650 +5914 2648 3000 2649 +5915 2674 2648 2650 +5916 2649 2651 2650 +5917 2651 2649 2923 +5918 2649 2855 2923 +5919 2855 2649 3000 +5920 2651 2660 2650 +5921 2968 2650 2660 +5922 2674 2650 2968 +5923 2651 2666 2660 +5924 2651 2924 2666 +5925 2923 2924 2651 +5926 2652 2653 2654 +5927 2652 2961 2653 +5928 2652 2859 2962 +5929 2652 2962 2961 +5930 2654 2653 2799 +5931 2653 2882 2799 +5932 2653 2976 2882 +5933 2976 2653 2961 +5934 2801 2654 2799 +5935 2881 2654 2801 +5936 2656 2657 2658 +5937 2656 2959 2657 +5938 2656 2860 2960 +5939 2656 2960 2959 +5940 2658 2657 2805 +5941 2657 2884 2805 +5942 2657 2978 2884 +5943 2978 2657 2959 +5944 2807 2658 2805 +5945 2883 2658 2807 +5946 2859 2659 2927 +5947 2927 2659 2922 +5948 2661 2662 2663 +5949 2733 2662 2661 +5950 2661 2663 2997 +5951 2980 2733 2661 +5952 2661 2751 2980 +5953 2751 2661 2997 +5954 2735 2663 2662 +5955 2733 2732 2662 +5956 2732 2736 2662 +5957 2736 2735 2662 +5958 2735 2824 2663 +5959 2824 2997 2663 +5960 2888 2664 2665 +5961 2705 2664 2893 +5962 2664 2888 2893 +5963 2889 2665 2825 +5964 2888 2665 2889 +5965 2860 2666 2929 +5966 2929 2666 2924 +5967 2667 2668 2669 +5968 2738 2668 2667 +5969 2667 2669 2998 +5970 2984 2738 2667 +5971 2667 2856 2984 +5972 2856 2667 2998 +5973 2740 2669 2668 +5974 2738 2737 2668 +5975 2737 2741 2668 +5976 2741 2740 2668 +5977 2740 2831 2669 +5978 2831 2998 2669 +5979 2671 2672 2673 +5980 2932 2672 2671 +5981 2671 2673 2716 +5982 2716 2937 2671 +5983 2932 2671 2936 +5984 2936 2671 2937 +5985 2673 2672 2945 +5986 2846 2845 2672 +5987 2945 2672 2845 +5988 2846 2672 2932 +5989 2714 2716 2673 +5990 2673 2953 2714 +5991 2953 2673 2945 +5992 2675 2677 2676 +5993 2675 2895 2677 +5994 2881 2801 2675 +5995 2801 2895 2675 +5996 2764 2676 2677 +5997 2743 2676 2744 +5998 2744 2676 2764 +5999 2677 2763 2764 +6000 2677 2768 2763 +6001 2895 2768 2677 +6002 2678 2680 2679 +6003 2678 2896 2680 +6004 2883 2807 2678 +6005 2807 2896 2678 +6006 2767 2679 2680 +6007 2753 2679 2754 +6008 2754 2679 2767 +6009 2680 2766 2767 +6010 2680 2769 2766 +6011 2896 2769 2680 +6012 2681 2682 2768 +6013 2685 2681 2687 +6014 2768 2687 2681 +6015 2768 2682 2762 +6016 2683 2684 2769 +6017 2688 2683 2690 +6018 2769 2690 2683 +6019 2769 2684 2765 +6020 2803 2686 2685 +6021 2687 2798 2685 +6022 2685 2798 2803 +6023 2686 2721 2770 +6024 2686 2803 2721 +6025 2687 2768 2895 +6026 2798 2687 2801 +6027 2895 2801 2687 +6028 2809 2689 2688 +6029 2690 2804 2688 +6030 2688 2804 2809 +6031 2689 2728 2772 +6032 2689 2809 2728 +6033 2690 2769 2896 +6034 2804 2690 2807 +6035 2896 2807 2690 +6036 2691 2692 2693 +6037 2691 2795 2692 +6038 2693 2694 2691 +6039 2691 2694 2695 +6040 2796 2691 2695 +6041 2795 2691 2796 +6042 2693 2692 2829 +6043 2692 2795 2757 +6044 2692 2757 2829 +6045 2693 2840 2694 +6046 2829 2837 2693 +6047 2837 2840 2693 +6048 2695 2694 2935 +6049 2694 2840 2934 +6050 2933 2694 2934 +6051 2933 2935 2694 +6052 2695 2811 2796 +6053 2912 2811 2695 +6054 2695 2910 2912 +6055 2935 2910 2695 +6056 2696 2697 2698 +6057 2696 2790 2697 +6058 2698 2699 2696 +6059 2696 2699 2700 +6060 2791 2696 2700 +6061 2790 2696 2791 +6062 2698 2697 2830 +6063 2697 2790 2759 +6064 2697 2759 2830 +6065 2698 2843 2699 +6066 2830 2844 2698 +6067 2844 2843 2698 +6068 2700 2699 2928 +6069 2699 2843 2926 +6070 2925 2699 2926 +6071 2925 2928 2699 +6072 2700 2794 2791 +6073 2901 2794 2700 +6074 2700 2908 2901 +6075 2928 2908 2700 +6076 2701 2702 2703 +6077 2839 2702 2701 +6078 2703 2704 2701 +6079 2704 2840 2701 +6080 2839 2701 2840 +6081 2702 2723 2703 +6082 2752 2723 2702 +6083 2834 2752 2702 +6084 2702 2839 2834 +6085 2707 2704 2703 +6086 2707 2703 2722 +6087 2722 2703 2723 +6088 2946 2704 2707 +6089 2934 2840 2704 +6090 2704 2933 2934 +6091 2704 2946 2933 +6092 2706 2705 2893 +6093 2722 2756 2707 +6094 2707 2756 2902 +6095 2902 2904 2707 +6096 2707 2904 2946 +6097 2708 2709 2710 +6098 2842 2709 2708 +6099 2710 2713 2708 +6100 2713 2843 2708 +6101 2842 2708 2843 +6102 2709 2730 2710 +6103 2755 2730 2709 +6104 2835 2755 2709 +6105 2709 2842 2835 +6106 2717 2713 2710 +6107 2717 2710 2729 +6108 2729 2710 2730 +6109 2712 2711 2894 +6110 2944 2713 2717 +6111 2926 2843 2713 +6112 2713 2925 2926 +6113 2713 2944 2925 +6114 2714 2715 2716 +6115 2887 2715 2714 +6116 2714 2879 2880 +6117 2714 2953 2879 +6118 2714 2880 2887 +6119 2863 2716 2715 +6120 2818 2715 2819 +6121 2863 2715 2818 +6122 2887 2819 2715 +6123 2863 2937 2716 +6124 2729 2758 2717 +6125 2717 2758 2905 +6126 2905 2907 2717 +6127 2717 2907 2944 +6128 2718 2719 2720 +6129 2718 2748 2719 +6130 2858 2748 2718 +6131 2900 2858 2718 +6132 2719 2782 2720 +6133 2721 2722 2723 +6134 2721 2803 2722 +6135 2721 2723 2724 +6136 2724 2770 2721 +6137 2803 2756 2722 +6138 2723 2752 2724 +6139 2725 2726 2727 +6140 2725 2742 2726 +6141 2857 2742 2725 +6142 2899 2857 2725 +6143 2726 2783 2727 +6144 2728 2729 2730 +6145 2728 2809 2729 +6146 2728 2730 2731 +6147 2731 2772 2728 +6148 2809 2758 2729 +6149 2730 2755 2731 +6150 2886 2736 2732 +6151 2734 2735 2736 +6152 2734 2866 2735 +6153 2736 2888 2734 +6154 2817 2866 2734 +6155 2889 2817 2734 +6156 2888 2889 2734 +6157 2824 2735 2866 +6158 2888 2736 2886 +6159 2892 2741 2737 +6160 2739 2740 2741 +6161 2739 2870 2740 +6162 2741 2890 2739 +6163 2823 2870 2739 +6164 2891 2823 2739 +6165 2890 2891 2739 +6166 2831 2740 2870 +6167 2890 2741 2892 +6168 2857 2827 2742 +6169 2745 2746 2747 +6170 2941 2746 2745 +6171 2745 2747 2819 +6172 2819 2943 2745 +6173 2941 2745 2942 +6174 2942 2745 2943 +6175 2747 2746 2950 +6176 2850 2849 2746 +6177 2950 2746 2849 +6178 2850 2746 2941 +6179 2818 2819 2747 +6180 2747 2957 2818 +6181 2957 2747 2950 +6182 2858 2813 2748 +6183 2749 2750 2751 +6184 2750 2749 2836 +6185 2997 2749 2751 +6186 2848 2836 2749 +6187 2848 2749 2997 +6188 2751 2750 2991 +6189 2836 2921 2750 +6190 2999 2991 2750 +6191 2991 2980 2751 +6192 2802 2756 2803 +6193 2802 2902 2756 +6194 2757 2760 2829 +6195 2808 2758 2809 +6196 2808 2905 2758 +6197 2759 2761 2830 +6198 2768 2762 2763 +6199 2769 2765 2766 +6200 2770 2868 2771 +6201 2772 2874 2773 +6202 2786 2784 2785 +6203 2789 2787 2788 +6204 2790 2791 2792 +6205 2791 2793 2792 +6206 2791 2794 2793 +6207 2792 2793 2813 +6208 2793 2794 2814 +6209 2812 2813 2793 +6210 2793 2816 2812 +6211 2793 2814 2816 +6212 2794 2901 2814 +6213 2795 2796 2797 +6214 2796 2810 2797 +6215 2796 2811 2810 +6216 2797 2810 2827 +6217 2798 2799 2800 +6218 2798 2801 2799 +6219 2798 2800 2803 +6220 2882 2800 2799 +6221 2800 2802 2803 +6222 2802 2800 2882 +6223 2882 2902 2802 +6224 2804 2805 2806 +6225 2804 2807 2805 +6226 2804 2806 2809 +6227 2884 2806 2805 +6228 2806 2808 2809 +6229 2808 2806 2884 +6230 2884 2905 2808 +6231 2810 2811 2820 +6232 2810 2820 2822 +6233 2810 2822 2826 +6234 2826 2827 2810 +6235 2811 2912 2820 +6236 2812 2816 2825 +6237 2814 2815 2816 +6238 2815 2814 2867 +6239 2814 2901 2867 +6240 2815 2817 2816 +6241 2815 2866 2817 +6242 2815 2865 2866 +6243 2815 2867 2865 +6244 2817 2825 2816 +6245 2825 2817 2889 +6246 2818 2861 2862 +6247 2818 2957 2861 +6248 2818 2862 2863 +6249 2887 2943 2819 +6250 2820 2821 2822 +6251 2821 2820 2871 +6252 2820 2912 2871 +6253 2821 2823 2822 +6254 2821 2870 2823 +6255 2821 2869 2870 +6256 2821 2871 2869 +6257 2823 2828 2822 +6258 2826 2822 2828 +6259 2828 2823 2891 +6260 2824 2866 2873 +6261 2824 2873 2970 +6262 2970 2997 2824 +6263 2831 2870 2875 +6264 2831 2875 2972 +6265 2972 2998 2831 +6266 2832 2835 2842 +6267 2842 2841 2832 +6268 2833 2834 2839 +6269 2839 2838 2833 +6270 2836 2848 2847 +6271 2847 2983 2836 +6272 2921 2836 2983 +6273 2837 2838 2840 +6274 2838 2839 2840 +6275 2841 2842 2843 +6276 2844 2841 2843 +6277 2845 2846 2847 +6278 2847 2848 2845 +6279 2845 2848 2898 +6280 2897 2845 2898 +6281 2845 2897 2945 +6282 2847 2846 2985 +6283 2932 2931 2846 +6284 2846 2931 2985 +6285 2983 2847 2985 +6286 2848 2970 2898 +6287 2970 2848 2997 +6288 2849 2850 2851 +6289 2851 2852 2849 +6290 2849 2852 2914 +6291 2913 2849 2914 +6292 2849 2913 2950 +6293 2851 2850 2982 +6294 2941 2940 2850 +6295 2850 2940 2982 +6296 2853 2852 2851 +6297 2851 2981 2853 +6298 2981 2851 2982 +6299 2852 2853 2854 +6300 2852 2854 2998 +6301 2852 2972 2914 +6302 2972 2852 2998 +6303 2855 2854 2853 +6304 2853 2923 2855 +6305 2923 2853 2981 +6306 2854 2855 2856 +6307 2998 2854 2856 +6308 2856 2855 2992 +6309 3000 2992 2855 +6310 2992 2984 2856 +6311 2962 2859 2927 +6312 2960 2860 2929 +6313 2920 2862 2861 +6314 2964 2920 2861 +6315 2957 2963 2861 +6316 2963 2964 2861 +6317 2862 2937 2863 +6318 2918 2862 2920 +6319 2862 2918 2937 +6320 2866 2865 2873 +6321 2867 2948 2865 +6322 2949 2873 2865 +6323 2865 2948 2949 +6324 2909 2867 2901 +6325 2909 2948 2867 +6326 2870 2869 2875 +6327 2871 2951 2869 +6328 2952 2875 2869 +6329 2869 2951 2952 +6330 2911 2871 2912 +6331 2911 2951 2871 +6332 2970 2873 2949 +6333 2972 2875 2952 +6334 2876 2877 2878 +6335 2877 2876 2885 +6336 2878 2986 2876 +6337 2915 2885 2876 +6338 2915 2876 2988 +6339 2988 2876 2986 +6340 2877 2916 2878 +6341 2877 2880 2916 +6342 2880 2877 2943 +6343 2877 2885 2943 +6344 2916 2880 2879 +6345 2956 2916 2879 +6346 2953 2955 2879 +6347 2955 2956 2879 +6348 2880 2943 2887 +6349 2902 2882 2903 +6350 2882 2976 2903 +6351 2905 2884 2906 +6352 2884 2978 2906 +6353 2885 2915 2996 +6354 2939 2942 2885 +6355 2996 2939 2885 +6356 2942 2943 2885 +6357 2888 2886 2893 +6358 2890 2892 2894 +6359 2949 2897 2898 +6360 2947 2945 2897 +6361 2897 2977 2947 +6362 2897 2949 2977 +6363 2898 2970 2949 +6364 2908 2909 2901 +6365 2902 2903 2904 +6366 2990 2904 2903 +6367 2976 2989 2903 +6368 2990 2903 2989 +6369 2973 2946 2904 +6370 2905 2906 2907 +6371 2986 2907 2906 +6372 2978 2988 2906 +6373 2986 2906 2988 +6374 2971 2944 2907 +6375 2909 2908 2967 +6376 2967 2948 2909 +6377 2910 2911 2912 +6378 2911 2910 2969 +6379 2969 2951 2911 +6380 2952 2913 2914 +6381 2954 2950 2913 +6382 2913 2952 2979 +6383 2913 2979 2954 +6384 2914 2972 2952 +6385 2978 2915 2988 +6386 2915 2978 2995 +6387 2915 2995 2996 +6388 2917 2918 2919 +6389 2918 2917 2938 +6390 2919 2990 2917 +6391 2987 2938 2917 +6392 2987 2917 2989 +6393 2989 2917 2990 +6394 2918 2920 2919 +6395 2918 2938 2937 +6396 2922 2921 2983 +6397 2985 2927 2922 +6398 2922 2983 2985 +6399 2924 2923 2981 +6400 2982 2929 2924 +6401 2924 2981 2982 +6402 2944 2971 2925 +6403 2927 2931 2974 +6404 2931 2927 2985 +6405 2962 2927 2974 +6406 2929 2940 2975 +6407 2940 2929 2982 +6408 2960 2929 2975 +6409 2930 2931 2932 +6410 2974 2931 2930 +6411 2936 2930 2932 +6412 2930 2936 2938 +6413 2994 2930 2938 +6414 2974 2930 2994 +6415 2946 2973 2933 +6416 2936 2937 2938 +6417 2938 2987 2994 +6418 2939 2940 2941 +6419 2975 2940 2939 +6420 2942 2939 2941 +6421 2975 2939 2996 +6422 2947 2953 2945 +6423 2955 2953 2947 +6424 2947 2958 2955 +6425 2958 2947 2977 +6426 2949 2948 2977 +6427 2967 2958 2948 +6428 2977 2948 2958 +6429 2954 2957 2950 +6430 2952 2951 2979 +6431 2969 2965 2951 +6432 2979 2951 2965 +6433 2963 2957 2954 +6434 2954 2965 2963 +6435 2965 2954 2979 +6436 2956 2955 2958 +6437 2956 2958 2967 +6438 2960 2995 2959 +6439 2959 2995 2978 +6440 2960 2975 2995 +6441 2962 2993 2961 +6442 2961 2993 2976 +6443 2962 2974 2993 +6444 2964 2963 2965 +6445 2964 2965 2969 +6446 2994 2993 2974 +6447 2996 2995 2975 +6448 2976 2987 2989 +6449 2987 2976 2993 +6450 2987 2993 2994 +2 23 2 86 +6451 25 371 3019 +6452 464 25 3019 +6453 389 28 3020 +6454 28 465 3020 +6455 31 446 3021 +6456 465 31 3021 +6457 428 32 3022 +6458 32 464 3022 +6459 371 372 3001 +6460 371 3001 3019 +6461 372 373 3015 +6462 3001 372 3015 +6463 373 374 3002 +6464 373 3002 3015 +6465 374 375 3012 +6466 3002 374 3012 +6467 375 376 3003 +6468 375 3003 3012 +6469 376 377 3016 +6470 3003 376 3016 +6471 377 378 3004 +6472 377 3004 3016 +6473 378 379 3017 +6474 3004 378 3017 +6475 379 380 3005 +6476 379 3005 3017 +6477 380 381 3013 +6478 3005 380 3013 +6479 381 382 3006 +6480 381 3006 3013 +6481 382 383 3014 +6482 3006 382 3014 +6483 383 384 3007 +6484 383 3007 3014 +6485 384 385 3011 +6486 3007 384 3011 +6487 385 386 3008 +6488 385 3008 3011 +6489 386 387 3018 +6490 3008 386 3018 +6491 387 388 3009 +6492 387 3009 3018 +6493 388 389 3010 +6494 3009 388 3010 +6495 3010 389 3020 +6496 429 428 3001 +6497 3001 428 3022 +6498 430 429 3015 +6499 429 3001 3015 +6500 431 430 3002 +6501 3002 430 3015 +6502 432 431 3012 +6503 431 3002 3012 +6504 433 432 3003 +6505 3003 432 3012 +6506 434 433 3016 +6507 433 3003 3016 +6508 435 434 3004 +6509 3004 434 3016 +6510 436 435 3017 +6511 435 3004 3017 +6512 437 436 3005 +6513 3005 436 3017 +6514 438 437 3013 +6515 437 3005 3013 +6516 439 438 3006 +6517 3006 438 3013 +6518 440 439 3014 +6519 439 3006 3014 +6520 441 440 3007 +6521 3007 440 3014 +6522 442 441 3011 +6523 441 3007 3011 +6524 443 442 3008 +6525 3008 442 3011 +6526 444 443 3018 +6527 443 3008 3018 +6528 445 444 3009 +6529 3009 444 3018 +6530 446 445 3010 +6531 445 3009 3010 +6532 446 3010 3021 +6533 464 3019 3022 +6534 3020 465 3021 +6535 3019 3001 3022 +6536 3010 3020 3021 +2 24 2 197 +6537 332 25 3057 +6538 25 464 3057 +6539 26 341 3067 +6540 390 26 3067 +6541 29 390 3094 +6542 447 29 3065 +6543 3065 29 3094 +6544 32 463 3056 +6545 464 32 3090 +6546 32 3056 3090 +6547 333 332 3084 +6548 332 3057 3084 +6549 334 333 3051 +6550 3051 333 3084 +6551 335 334 3078 +6552 334 3051 3078 +6553 336 335 3050 +6554 3050 335 3078 +6555 337 336 3044 +6556 3044 336 3050 +6557 338 337 3060 +6558 337 3044 3060 +6559 339 338 3074 +6560 338 3060 3074 +6561 340 339 3063 +6562 339 3041 3063 +6563 3041 339 3074 +6564 341 340 3100 +6565 340 3063 3100 +6566 3067 341 3100 +6567 390 3067 3094 +6568 448 447 3083 +6569 447 3065 3083 +6570 449 448 3064 +6571 3064 448 3083 +6572 450 449 3071 +6573 449 3064 3071 +6574 451 450 3047 +6575 3047 450 3071 +6576 452 451 3062 +6577 451 3047 3062 +6578 453 452 3102 +6579 452 3062 3102 +6580 454 453 3066 +6581 3066 453 3102 +6582 455 454 3066 +6583 456 455 3053 +6584 3053 455 3066 +6585 457 456 3086 +6586 456 3053 3086 +6587 458 457 3052 +6588 3052 457 3086 +6589 459 458 3092 +6590 458 3052 3092 +6591 460 459 3072 +6592 459 3045 3072 +6593 3045 459 3092 +6594 461 460 3072 +6595 462 461 3059 +6596 3059 461 3072 +6597 463 462 3082 +6598 462 3059 3082 +6599 3056 463 3082 +6600 3057 464 3090 +6601 3043 3023 3087 +6602 3023 3043 3096 +6603 3023 3046 3068 +6604 3046 3023 3075 +6605 3048 3023 3096 +6606 3023 3048 3104 +6607 3023 3068 3087 +6608 3075 3023 3104 +6609 3049 3024 3070 +6610 3024 3049 3095 +6611 3024 3054 3093 +6612 3054 3024 3095 +6613 3024 3061 3076 +6614 3061 3024 3093 +6615 3070 3024 3076 +6616 3058 3025 3098 +6617 3025 3058 3103 +6618 3069 3025 3091 +6619 3025 3069 3098 +6620 3025 3073 3091 +6621 3073 3025 3103 +6622 3026 3045 3052 +6623 3045 3026 3080 +6624 3049 3026 3077 +6625 3026 3049 3080 +6626 3026 3052 3097 +6627 3077 3026 3097 +6628 3027 3042 3062 +6629 3042 3027 3081 +6630 3047 3027 3062 +6631 3027 3047 3101 +6632 3027 3048 3081 +6633 3048 3027 3085 +6634 3027 3055 3085 +6635 3055 3027 3101 +6636 3028 3044 3050 +6637 3044 3028 3088 +6638 3046 3028 3068 +6639 3028 3046 3088 +6640 3028 3050 3089 +6641 3028 3054 3068 +6642 3054 3028 3089 +6643 3029 3053 3066 +6644 3053 3029 3079 +6645 3029 3066 3081 +6646 3079 3029 3096 +6647 3029 3081 3096 +6648 3058 3030 3099 +6649 3030 3058 3105 +6650 3030 3060 3088 +6651 3060 3030 3105 +6652 3030 3088 3099 +6653 3051 3031 3061 +6654 3031 3051 3084 +6655 3031 3056 3076 +6656 3056 3031 3090 +6657 3057 3031 3084 +6658 3031 3057 3090 +6659 3061 3031 3076 +6660 3032 3063 3069 +6661 3063 3032 3100 +6662 3065 3032 3091 +6663 3032 3065 3094 +6664 3067 3032 3094 +6665 3032 3067 3100 +6666 3032 3069 3091 +6667 3033 3049 3070 +6668 3049 3033 3080 +6669 3059 3033 3070 +6670 3033 3059 3072 +6671 3033 3072 3080 +6672 3034 3047 3071 +6673 3047 3034 3101 +6674 3055 3034 3073 +6675 3034 3055 3101 +6676 3064 3034 3071 +6677 3034 3064 3073 +6678 3035 3050 3078 +6679 3050 3035 3089 +6680 3035 3051 3061 +6681 3051 3035 3078 +6682 3035 3061 3093 +6683 3089 3035 3093 +6684 3036 3049 3077 +6685 3049 3036 3095 +6686 3054 3036 3068 +6687 3036 3054 3095 +6688 3068 3036 3087 +6689 3036 3077 3087 +6690 3056 3037 3076 +6691 3037 3056 3082 +6692 3037 3059 3070 +6693 3059 3037 3082 +6694 3037 3070 3076 +6695 3055 3038 3085 +6696 3038 3055 3103 +6697 3038 3058 3099 +6698 3058 3038 3103 +6699 3075 3038 3099 +6700 3038 3075 3104 +6701 3085 3038 3104 +6702 3039 3052 3086 +6703 3052 3039 3097 +6704 3039 3053 3079 +6705 3053 3039 3086 +6706 3039 3079 3097 +6707 3064 3040 3073 +6708 3040 3064 3083 +6709 3065 3040 3083 +6710 3040 3065 3091 +6711 3073 3040 3091 +6712 3063 3041 3069 +6713 3069 3041 3098 +6714 3041 3074 3105 +6715 3098 3041 3105 +6716 3062 3042 3102 +6717 3066 3042 3081 +6718 3042 3066 3102 +6719 3077 3043 3087 +6720 3043 3077 3097 +6721 3043 3079 3096 +6722 3079 3043 3097 +6723 3060 3044 3088 +6724 3052 3045 3092 +6725 3072 3045 3080 +6726 3046 3075 3099 +6727 3088 3046 3099 +6728 3081 3048 3096 +6729 3048 3085 3104 +6730 3054 3089 3093 +6731 3055 3073 3103 +6732 3058 3098 3105 +6733 3074 3060 3105 +2 25 2 197 +6734 27 3140 361 +6735 410 3140 27 +6736 370 3150 28 +6737 28 3150 465 +6738 30 3173 410 +6739 427 3139 30 +6740 3139 3173 30 +6741 31 3148 411 +6742 465 3177 31 +6743 31 3177 3148 +6744 361 3167 362 +6745 3140 3167 361 +6746 362 3134 363 +6747 362 3167 3134 +6748 363 3161 364 +6749 3134 3161 363 +6750 364 3133 365 +6751 364 3161 3133 +6752 365 3127 366 +6753 365 3133 3127 +6754 366 3143 367 +6755 3127 3143 366 +6756 367 3157 368 +6757 3143 3157 367 +6758 368 3146 369 +6759 3124 3146 368 +6760 368 3157 3124 +6761 369 3183 370 +6762 3146 3183 369 +6763 370 3183 3150 +6764 410 3173 3140 +6765 411 3166 412 +6766 3148 3166 411 +6767 412 3147 413 +6768 412 3166 3147 +6769 413 3154 414 +6770 3147 3154 413 +6771 414 3130 415 +6772 414 3154 3130 +6773 415 3145 416 +6774 3130 3145 415 +6775 416 3185 417 +6776 3145 3185 416 +6777 417 3149 418 +6778 417 3185 3149 +6779 418 3149 419 +6780 419 3136 420 +6781 419 3149 3136 +6782 420 3169 421 +6783 3136 3169 420 +6784 421 3135 422 +6785 421 3169 3135 +6786 422 3175 423 +6787 3135 3175 422 +6788 423 3155 424 +6789 3128 3155 423 +6790 423 3175 3128 +6791 424 3155 425 +6792 425 3142 426 +6793 425 3155 3142 +6794 426 3165 427 +6795 3142 3165 426 +6796 427 3165 3139 +6797 3150 3177 465 +6798 3106 3170 3126 +6799 3126 3179 3106 +6800 3129 3151 3106 +6801 3106 3158 3129 +6802 3106 3179 3131 +6803 3131 3187 3106 +6804 3151 3170 3106 +6805 3106 3187 3158 +6806 3107 3153 3132 +6807 3132 3178 3107 +6808 3137 3176 3107 +6809 3107 3178 3137 +6810 3144 3159 3107 +6811 3107 3176 3144 +6812 3107 3159 3153 +6813 3108 3181 3141 +6814 3141 3186 3108 +6815 3108 3174 3152 +6816 3152 3181 3108 +6817 3156 3174 3108 +6818 3108 3186 3156 +6819 3128 3135 3109 +6820 3109 3163 3128 +6821 3109 3160 3132 +6822 3132 3163 3109 +6823 3135 3180 3109 +6824 3109 3180 3160 +6825 3125 3145 3110 +6826 3110 3164 3125 +6827 3110 3145 3130 +6828 3130 3184 3110 +6829 3131 3164 3110 +6830 3110 3168 3131 +6831 3138 3168 3110 +6832 3110 3184 3138 +6833 3127 3133 3111 +6834 3111 3171 3127 +6835 3111 3151 3129 +6836 3129 3171 3111 +6837 3133 3172 3111 +6838 3137 3151 3111 +6839 3111 3172 3137 +6840 3136 3149 3112 +6841 3112 3162 3136 +6842 3149 3164 3112 +6843 3112 3179 3162 +6844 3164 3179 3112 +6845 3113 3182 3141 +6846 3141 3188 3113 +6847 3143 3171 3113 +6848 3113 3188 3143 +6849 3171 3182 3113 +6850 3114 3144 3134 +6851 3134 3167 3114 +6852 3139 3159 3114 +6853 3114 3173 3139 +6854 3114 3167 3140 +6855 3140 3173 3114 +6856 3114 3159 3144 +6857 3146 3152 3115 +6858 3115 3183 3146 +6859 3115 3174 3148 +6860 3148 3177 3115 +6861 3115 3177 3150 +6862 3150 3183 3115 +6863 3152 3174 3115 +6864 3132 3153 3116 +6865 3116 3163 3132 +6866 3116 3153 3142 +6867 3142 3155 3116 +6868 3155 3163 3116 +6869 3130 3154 3117 +6870 3117 3184 3130 +6871 3117 3156 3138 +6872 3138 3184 3117 +6873 3117 3154 3147 +6874 3147 3156 3117 +6875 3133 3161 3118 +6876 3118 3172 3133 +6877 3134 3144 3118 +6878 3118 3161 3134 +6879 3144 3176 3118 +6880 3118 3176 3172 +6881 3132 3160 3119 +6882 3119 3178 3132 +6883 3119 3151 3137 +6884 3137 3178 3119 +6885 3119 3170 3151 +6886 3160 3170 3119 +6887 3120 3159 3139 +6888 3139 3165 3120 +6889 3142 3153 3120 +6890 3120 3165 3142 +6891 3153 3159 3120 +6892 3121 3168 3138 +6893 3138 3186 3121 +6894 3141 3182 3121 +6895 3121 3186 3141 +6896 3121 3182 3158 +6897 3158 3187 3121 +6898 3121 3187 3168 +6899 3135 3169 3122 +6900 3122 3180 3135 +6901 3136 3162 3122 +6902 3122 3169 3136 +6903 3162 3180 3122 +6904 3123 3156 3147 +6905 3147 3166 3123 +6906 3123 3166 3148 +6907 3148 3174 3123 +6908 3123 3174 3156 +6909 3124 3152 3146 +6910 3124 3181 3152 +6911 3157 3188 3124 +6912 3124 3188 3181 +6913 3125 3185 3145 +6914 3125 3164 3149 +6915 3149 3185 3125 +6916 3126 3170 3160 +6917 3160 3180 3126 +6918 3162 3179 3126 +6919 3126 3180 3162 +6920 3127 3171 3143 +6921 3128 3175 3135 +6922 3128 3163 3155 +6923 3158 3182 3129 +6924 3129 3182 3171 +6925 3131 3179 3164 +6926 3168 3187 3131 +6927 3172 3176 3137 +6928 3156 3186 3138 +6929 3181 3188 3141 +6930 3143 3188 3157 +3 1 4 12046 +6931 2988 3318 3404 3561 +6932 2793 3529 3390 3618 +6933 258 374 3545 3745 +6934 1923 3617 3390 3618 +6935 258 3545 374 3547 +6936 3723 3749 2320 3750 +6937 1293 3294 3290 3313 +6938 3337 3726 228 3761 +6939 3473 3528 2326 3582 +6940 3445 3517 1191 3676 +6941 2492 3316 3667 3698 +6942 1154 3750 3723 3752 +6943 1214 3697 3377 3780 +6944 1787 3390 3529 3618 +6945 3330 3400 2046 3512 +6946 3211 3271 1796 3636 +6947 790 3458 416 3535 +6948 258 3547 374 3745 +6949 228 3337 379 3726 +6950 2049 3415 3478 3519 +6951 2946 3399 3330 3400 +6952 2757 3190 2613 3196 +6953 3723 3750 2478 3752 +6954 3631 3645 1997 3652 +6955 864 3457 362 3566 +6956 358 3438 3402 3691 +6957 188 3402 3438 3691 +6958 1304 3711 3549 3713 +6959 379 3337 228 3450 +6960 3321 3330 1650 3512 +6961 2825 3391 3336 3393 +6962 2793 3390 3617 3618 +6963 379 3450 228 3724 +6964 3473 3582 2326 3758 +6965 790 3458 885 3460 +6966 2633 3391 3390 3403 +6967 379 3724 228 3726 +6968 2633 1462 3391 3403 +6969 258 3546 3545 3547 +6970 2848 3645 3631 3652 +6971 1879 3217 3526 3645 +6972 357 3438 2480 3691 +6973 1058 2297 3382 3435 +6974 2508 3510 2359 3781 +6975 357 188 3438 3691 +6976 790 415 3458 3460 +6977 1053 3302 3332 3560 +6978 1009 3528 3473 3582 +6979 1154 3749 3723 3750 +6980 1243 2359 3510 3781 +6981 1795 3271 3530 3636 +6982 357 188 3437 3438 +6983 907 870 370 761 +6984 1899 3527 3476 3662 +6985 2954 3375 3320 3462 +6986 3333 3381 1248 3660 +6987 790 416 919 3535 +6988 363 3472 864 3566 +6989 2297 3435 3278 3614 +6990 2633 1462 3403 3624 +6991 977 3644 3601 3736 +6992 3317 3479 1869 3662 +6993 1028 3779 3717 3780 +6994 1499 3282 3256 3351 +6995 1753 3325 3350 3689 +6996 2388 3697 1156 3780 +6997 2297 1078 3230 3278 +6998 363 864 362 3566 +6999 1425 3299 3369 3672 +7000 3545 3546 3002 3547 +7001 401 3209 3558 3576 +7002 188 357 3437 3691 +7003 2296 3667 1137 3734 +7004 319 3558 3209 3576 +7005 2480 3438 358 3691 +7006 337 2228 1091 3432 +7007 3402 3691 188 3692 +7008 1747 3208 3504 3671 +7009 2633 3336 2825 3391 +7010 2369 3676 3366 3706 +7011 3602 965 3721 3722 +7012 2497 3332 3302 3560 +7013 2633 1462 3336 3391 +7014 220 3605 3711 3712 +7015 199 3601 3384 3613 +7016 3336 3391 1462 3393 +7017 3294 3313 1293 3670 +7018 885 3458 790 3535 +7019 1091 336 3307 3347 +7020 2388 1028 3717 3780 +7021 1032 3381 3269 3696 +7022 1747 3282 3208 3671 +7023 176 344 3464 3602 +7024 2978 3318 3206 3404 +7025 3206 3318 2083 3404 +7026 2978 2988 3318 3404 +7027 3605 3712 220 3714 +7028 378 3726 3337 3761 +7029 2039 3538 3412 3649 +7030 1058 3278 2297 3435 +7031 885 3458 1677 3460 +7032 1112 3667 3316 3698 +7033 3257 3384 198 3601 +7034 770 3352 31 3398 +7035 1795 1796 3271 3636 +7036 3390 3391 1462 3403 +7037 3256 3282 2637 3351 +7038 3464 3602 2555 3603 +7039 2050 3401 3343 3558 +7040 425 3369 3299 3672 +7041 1112 1047 1196 3316 +7042 2429 3437 3323 3438 +7043 1689 3275 3216 3359 +7044 2105 3602 3464 3603 +7045 1897 3196 3190 3235 +7046 1614 900 3239 3398 +7047 2633 3336 1462 3624 +7048 1795 3636 3530 3679 +7049 2388 1156 3697 3763 +7050 416 790 415 3458 +7051 2148 3058 2291 3098 +7052 2228 337 2136 3432 +7053 3602 3613 965 3722 +7054 3305 3388 2485 3640 +7055 1211 3366 3676 3706 +7056 974 3601 3599 3736 +7057 1872 3413 3581 3738 +7058 401 3574 3209 3576 +7059 2983 2921 3514 3645 +7060 3098 2148 3058 3105 +7061 1009 3582 3473 3758 +7062 3209 3574 1729 3576 +7063 31 3246 465 3352 +7064 3545 3744 258 3745 +7065 2291 3025 3069 3098 +7066 3190 3196 2757 3235 +7067 2613 3196 3190 3374 +7068 358 3691 3402 3692 +7069 3308 3505 2596 3609 +7070 3320 3375 2011 3462 +7071 826 3456 368 3550 +7072 795 3239 900 3398 +7073 225 3709 3279 3729 +7074 176 3464 344 3720 +7075 2337 3630 3445 3704 +7076 1868 1869 3479 3662 +7077 176 3720 344 3721 +7078 1530 3350 3233 3689 +7079 2503 3626 3625 3686 +7080 2504 2296 1047 3703 +7081 3653 3726 3485 3761 +7082 176 344 3602 3721 +7083 2918 3530 3271 3636 +7084 977 3601 972 3736 +7085 2707 3400 3330 3512 +7086 3217 3514 2921 3645 +7087 3269 3381 2378 3696 +7088 3216 3275 2680 3359 +7089 2326 3528 3283 3582 +7090 1687 3359 3216 3705 +7091 3601 3644 348 3736 +7092 1254 3230 1078 3278 +7093 374 3545 3002 3547 +7094 2388 3717 3779 3780 +7095 373 3545 374 3745 +7096 2019 3318 3218 3531 +7097 2356 2488 2427 3517 +7098 1005 3231 3200 3368 +7099 2410 2504 2296 3316 +7100 458 3586 2275 3604 +7101 3319 3589 2771 3591 +7102 3444 3635 2673 3715 +7103 2046 1650 3330 3512 +7104 2378 3381 3333 3660 +7105 448 3518 3240 3689 +7106 199 198 3384 3601 +7107 348 3599 3601 3736 +7108 3412 3538 2869 3649 +7109 1078 3382 2297 3477 +7110 1857 3280 3227 3310 +7111 2297 3230 1078 3477 +7112 261 3311 3291 3543 +7113 3339 3431 1630 3538 +7114 2297 2404 3230 3477 +7115 1108 3382 3333 3435 +7116 2503 3626 3686 3703 +7117 826 1094 3456 3550 +7118 3208 3282 2810 3671 +7119 3236 3283 2528 3293 +7120 3208 2810 3504 3671 +7121 870 370 794 907 +7122 448 3240 3241 3689 +7123 2674 3209 3574 3678 +7124 3287 3444 2673 3715 +7125 2757 2613 2795 3196 +7126 1857 3194 3227 3280 +7127 1214 1130 3697 3780 +7128 3253 3324 1572 3454 +7129 1028 2388 1156 3780 +7130 2535 3333 3382 3435 +7131 2136 336 337 2228 +7132 2340 3323 3193 3438 +7133 2707 2946 3330 3400 +7134 2575 3370 3247 3463 +7135 2503 3625 3685 3686 +7136 2473 2369 3366 3706 +7137 188 3437 3578 3691 +7138 32 464 2188 3295 +7139 2504 1047 2296 3316 +7140 1162 3549 3367 3713 +7141 795 411 3239 3398 +7142 1630 3431 3339 3710 +7143 3517 3676 2427 3706 +7144 3319 3589 1429 3747 +7145 1047 2359 2504 3703 +7146 3476 3527 2967 3662 +7147 3283 3528 1009 3582 +7148 1914 3412 3648 3649 +7149 2105 176 3464 3602 +7150 1014 1191 3517 3676 +7151 2891 3256 3365 3730 +7152 1058 3278 3435 3614 +7153 1787 1923 3390 3618 +7154 2908 3479 3317 3662 +7155 2891 3256 3351 3365 +7156 2799 3324 3253 3454 +7157 1996 3471 3631 3652 +7158 1032 1248 3381 3696 +7159 2595 3350 3325 3689 +7160 1747 1640 3282 3671 +7161 1511 1512 3192 3238 +7162 2875 3431 3339 3538 +7163 2535 3382 2297 3435 +7164 2478 3723 2320 3750 +7165 2649 3209 3343 3558 +7166 1540 3240 3518 3689 +7167 2296 1047 1112 3316 +7168 3412 2869 3648 3649 +7169 3321 3329 1650 3330 +7170 3323 3437 1117 3438 +7171 3089 3093 2140 2225 +7172 1091 337 336 2228 +7173 1968 3375 3320 3647 +7174 1687 1689 3216 3359 +7175 368 369 826 3550 +7176 1758 3218 1750 3371 +7177 31 815 465 3246 +7178 2377 2492 2296 3667 +7179 1872 3581 1908 3738 +7180 3445 3517 2488 3704 +7181 1243 2359 1047 3703 +7182 2957 3375 2954 3462 +7183 2083 3318 3206 3478 +7184 3218 3318 1842 3405 +7185 401 3209 2648 3558 +7186 2918 3530 3636 3679 +7187 2378 1248 3381 3660 +7188 2961 3324 3297 3474 +7189 1606 3244 3389 3421 +7190 2789 3299 425 3369 +7191 258 3593 3547 3745 +7192 2083 3404 3318 3561 +7193 1795 1796 3636 3679 +7194 1756 3243 3218 3405 +7195 2875 3339 3431 3710 +7196 448 3241 2781 3689 +7197 378 379 3337 3726 +7198 3256 1620 3365 3730 +7199 769 924 822 3178 +7200 2504 1047 3316 3379 +7201 1620 3351 3256 3365 +7202 366 3630 829 3731 +7203 1758 3326 3218 3371 +7204 378 379 2542 3337 +7205 1530 1753 3350 3689 +7206 362 864 838 3457 +7207 1540 3241 3240 3689 +7208 3485 3653 1350 3726 +7209 2378 1248 3660 3696 +7210 1304 3549 218 3713 +7211 2049 3415 1830 3478 +7212 1997 3631 1854 3645 +7213 2847 3631 2848 3645 +7214 347 3384 3257 3601 +7215 2519 3372 3650 3763 +7216 815 3246 31 3352 +7217 258 1399 3545 3546 +7218 3119 822 924 3178 +7219 2501 3549 3711 3713 +7220 2478 3355 3723 3752 +7221 3292 3486 2037 3488 +7222 3390 3391 2812 3617 +7223 1845 3505 3308 3609 +7224 2602 3272 3392 3591 +7225 1254 3230 3278 3665 +7226 1854 3631 3525 3645 +7227 1500 3325 1499 3351 +7228 2501 3367 3549 3713 +7229 2654 3253 3376 3454 +7230 1149 1091 2228 3432 +7231 2297 3278 2539 3614 +7232 3038 2280 3055 3085 +7233 3723 3749 1225 3751 +7234 770 835 3352 3398 +7235 357 3437 2480 3438 +7236 1800 3258 3194 3565 +7237 264 3352 835 3398 +7238 1248 2378 3381 3696 +7239 1940 3514 3217 3645 +7240 3266 3397 1475 3603 +7241 2918 3271 3211 3636 +7242 336 2185 1091 2228 +7243 225 3279 3709 3725 +7244 1350 3726 3653 3761 +7245 897 852 809 3161 +7246 3214 3221 1527 3222 +7247 3203 3302 2527 3332 +7248 2987 3297 3385 3679 +7249 1748 3190 1897 3196 +7250 885 1677 3458 3535 +7251 2491 3203 2527 3332 +7252 3377 3697 2437 3780 +7253 1060 1214 1130 3697 +7254 972 3601 974 3736 +7255 3197 3225 1052 3388 +7256 3123 871 3174 930 +7257 1512 3192 3238 3396 +7258 1091 2185 336 3347 +7259 2359 2382 2504 3703 +7260 3170 3119 822 924 +7261 964 3602 965 3721 +7262 1507 3615 3327 3620 +7263 3218 3243 2860 3405 +7264 1606 3389 3403 3421 +7265 1830 3415 3242 3478 +7266 1962 3635 3444 3715 +7267 3270 3423 1792 3727 +7268 2297 3382 2431 3477 +7269 1507 3327 3263 3620 +7270 2963 3320 2954 3375 +7271 2280 3038 3104 3085 +7272 1425 1472 3299 3672 +7273 1359 3709 3489 3725 +7274 319 3209 1729 3576 +7275 1582 3628 3354 3737 +7276 3089 3093 2225 3054 +7277 2975 3318 3218 3405 +7278 333 3670 3348 3753 +7279 3270 1792 3519 3727 +7280 320 3523 3558 3576 +7281 337 1091 336 3307 +7282 461 3589 3319 3747 +7283 1572 3376 3253 3454 +7284 3370 3451 2094 3463 +7285 3108 3181 892 929 +7286 2432 3260 3356 3539 +7287 1744 3390 3389 3529 +7288 3206 3318 2978 3478 +7289 1221 3333 3234 3435 +7290 1399 3546 258 3547 +7291 458 2275 2127 3604 +7292 2326 3473 2389 3528 +7293 935 3144 3176 792 +7294 194 3466 3580 3681 +7295 2521 3278 3366 3676 +7296 2992 3343 3401 3558 +7297 3218 3318 2975 3531 +7298 1047 3379 2504 3781 +7299 347 3384 3601 3613 +7300 1200 3302 3203 3332 +7301 2340 2429 3323 3438 +7302 347 3257 2498 3601 +7303 2296 1112 1137 3667 +7304 792 3176 863 3172 +7305 1730 3209 319 3558 +7306 2657 3242 3415 3478 +7307 2613 2795 3196 3374 +7308 411 412 795 3239 +7309 202 3356 3719 3721 +7310 1047 2359 1243 3781 +7311 2473 3366 3296 3706 +7312 2025 3395 3652 3760 +7313 387 3711 3605 3712 +7314 1245 3268 3236 3283 +7315 3212 3272 1439 3392 +7316 2731 3280 3289 3310 +7317 319 1729 3574 3576 +7318 912 1535 3227 3309 +7319 2126 32 3295 3363 +7320 1173 3302 3193 3438 +7321 1325 3543 3291 3669 +7322 2793 3390 2812 3617 +7323 1014 3676 3517 3706 +7324 973 3601 199 3613 +7325 1868 1869 1694 3479 +7326 2654 2799 3253 3454 +7327 3025 2291 3058 3098 +7328 3265 3266 1475 3603 +7329 204 3342 3284 3358 +7330 2094 3463 3451 3464 +7331 2296 2495 3667 3734 +7332 337 1192 3307 3360 +7333 3297 3324 1779 3474 +7334 2297 3230 2386 3278 +7335 2748 3403 3389 3421 +7336 3479 3527 1693 3662 +7337 2291 3069 2271 3098 +7338 2299 3225 3197 3388 +7339 3269 3380 2293 3381 +7340 387 3712 3605 3714 +7341 2989 2987 3385 3679 +7342 2595 3325 2638 3689 +7343 2110 2178 3075 3104 +7344 2524 3356 3260 3384 +7345 199 973 198 3601 +7346 2555 3464 344 3602 +7347 3279 3450 1210 3698 +7348 436 3488 3292 3620 +7349 935 769 863 3178 +7350 1960 3320 2011 3462 +7351 1728 3343 3209 3558 +7352 2860 3243 3218 3371 +7353 1225 3627 3723 3751 +7354 2786 3319 3222 3747 +7355 370 870 794 3301 +7356 829 3456 1150 3630 +7357 357 3578 3437 3691 +7358 1044 3723 3355 3752 +7359 792 3118 3176 3172 +7360 2285 2140 3093 2225 +7361 3238 3327 1516 3495 +7362 2406 3450 3279 3698 +7363 3216 3275 1689 3505 +7364 912 3227 1535 3258 +7365 2680 3275 2896 3359 +7366 3257 3601 198 3644 +7367 194 3592 3466 3681 +7368 2989 3385 3329 3679 +7369 935 769 3178 3107 +7370 2019 1842 3218 3318 +7371 2665 2825 3336 3393 +7372 1499 3325 3282 3351 +7373 829 366 3456 3630 +7374 2638 3325 2595 3350 +7375 2291 3025 2189 3069 +7376 30 410 839 3298 +7377 1688 3216 1411 3449 +7378 2833 3354 3628 3737 +7379 2754 3216 3448 3449 +7380 3121 3158 887 3187 +7381 1933 1800 3194 3565 +7382 2460 3438 3302 3693 +7383 2491 2527 2364 3332 +7384 337 1192 3360 3432 +7385 2922 3217 3443 3514 +7386 795 3239 412 3251 +7387 3190 3196 1748 3374 +7388 1857 1866 3280 3310 +7389 2674 3209 401 3574 +7390 3132 3119 924 3178 +7391 822 837 3170 924 +7392 2195 3202 390 3247 +7393 1913 3412 3521 3648 +7394 436 3486 3292 3488 +7395 2524 2432 3260 3356 +7396 1888 3339 1630 3538 +7397 2680 3275 3216 3505 +7398 1529 3265 3233 3350 +7399 1108 1058 3382 3435 +7400 1500 1499 1622 3351 +7401 769 3132 924 3178 +7402 2185 336 2136 2228 +7403 2437 3377 3199 3697 +7404 2039 3412 1914 3649 +7405 3238 3357 1742 3503 +7406 977 972 975 3736 +7407 879 933 3159 756 +7408 357 2480 358 3691 +7409 2988 2915 3318 3561 +7410 2696 3335 3277 3346 +7411 1196 3316 1047 3379 +7412 1892 3317 3277 3346 +7413 790 834 919 416 +7414 1192 3307 3360 3646 +7415 1688 3448 3216 3449 +7416 2193 2280 3104 3085 +7417 1538 3221 3214 3541 +7418 2299 3388 3197 3675 +7419 2510 3283 3268 3582 +7420 2987 3636 3297 3679 +7421 3178 3137 935 3107 +7422 815 832 465 3246 +7423 176 177 3464 3720 +7424 1091 1192 337 3432 +7425 3148 3123 3174 930 +7426 2020 3531 3326 3768 +7427 1173 3193 1288 3438 +7428 1996 3631 1997 3652 +7429 1799 3194 1800 3227 +7430 2410 2296 2492 3316 +7431 3108 3181 929 3141 +7432 2385 2485 3388 3640 +7433 863 3137 935 3178 +7434 2340 2540 3193 3323 +7435 2187 2275 3586 3604 +7436 2443 3749 3723 3751 +7437 869 784 3113 3141 +7438 228 3724 1353 3726 +7439 2670 3410 3292 3486 +7440 3343 3401 2050 3756 +7441 2602 2868 3272 3591 +7442 2435 3435 2297 3614 +7443 3234 3333 1221 3660 +7444 1399 1386 3545 3546 +7445 1848 3419 3403 3624 +7446 1273 3382 1078 3477 +7447 2848 3631 2845 3652 +7448 3191 3210 2708 3345 +7449 31 465 815 832 +7450 3325 3689 1859 3701 +7451 1800 3227 3194 3258 +7452 3187 3158 887 3106 +7453 3277 3317 1892 3529 +7454 3299 3369 2789 3637 +7455 2886 3357 3238 3503 +7456 3218 3243 1756 3371 +7457 2296 3703 2533 3734 +7458 332 2172 2288 2263 +7459 2359 1047 2504 3781 +7460 2961 3253 3324 3474 +7461 780 366 829 3731 +7462 3241 3370 1546 3638 +7463 3168 3187 3121 819 +7464 458 2275 2146 2190 +7465 1787 3390 1744 3529 +7466 1437 3392 3272 3591 +7467 421 3227 806 3258 +7468 2578 3516 3508 3544 +7469 1091 337 1192 3307 +7470 3216 3300 1411 3449 +7471 1790 1792 3423 3727 +7472 2983 2921 2922 3514 +7473 2042 3412 2039 3538 +7474 2340 3193 2489 3302 +7475 400 3558 3523 3576 +7476 3152 3181 892 3108 +7477 1990 3385 3297 3679 +7478 3277 3335 1932 3346 +7479 1457 3214 1527 3222 +7480 795 835 411 3398 +7481 2602 3272 3212 3392 +7482 2833 3354 3604 3628 +7483 2460 2340 2489 3302 +7484 3193 3302 2340 3438 +7485 448 3083 447 2121 +7486 3227 3280 2608 3310 +7487 2178 2280 3038 3104 +7488 448 2257 447 3240 +7489 458 2146 2275 3586 +7490 3329 3385 1987 3679 +7491 3252 3314 1036 3623 +7492 1823 3212 3392 3470 +7493 1940 3443 3217 3514 +7494 883 3224 361 3457 +7495 1971 3401 2050 3558 +7496 1899 1693 3527 3662 +7497 2754 3300 3216 3449 +7498 2710 2708 3191 3210 +7499 1758 2022 1750 3218 +7500 3238 3425 2736 3503 +7501 2025 3652 3436 3760 +7502 1091 3307 1212 3347 +7503 2078 3317 1892 3346 +7504 1495 3214 1538 3221 +7505 2554 3451 3370 3463 +7506 2297 2431 2523 3477 +7507 1511 1825 1512 3238 +7508 2379 2528 3283 3293 +7509 2488 3517 2356 3704 +7510 3197 3388 1109 3675 +7511 2538 3290 3291 3294 +7512 2921 3217 2922 3514 +7513 3544 3545 1386 3546 +7514 964 175 965 3602 +7515 1359 3489 3724 3725 +7516 461 3319 2786 3747 +7517 1005 1006 3231 3368 +7518 2337 2425 3630 3704 +7519 1094 3517 3456 3550 +7520 202 3719 3720 3721 +7521 1910 1905 1981 3527 +7522 1444 3460 1445 3663 +7523 1103 1028 3717 3763 +7524 3296 3366 1211 3706 +7525 3091 2112 2289 2235 +7526 2633 2665 2825 3336 +7527 2128 3247 29 3638 +7528 3442 3443 1940 3514 +7529 1961 3532 3531 3768 +7530 770 815 31 3352 +7531 461 2786 3319 3589 +7532 2148 2291 2271 3098 +7533 790 919 831 3535 +7534 30 839 772 3298 +7535 816 928 369 3183 +7536 2069 3277 3334 3335 +7537 2997 3436 3192 3526 +7538 2059 1779 3297 3324 +7539 1996 3631 3471 3682 +7540 868 779 422 3175 +7541 3297 3636 1990 3679 +7542 2554 3370 2575 3463 +7543 3456 3517 368 3550 +7544 2716 2673 3635 3715 +7545 3038 2280 2125 3055 +7546 1676 1677 3458 3460 +7547 448 2783 3518 3689 +7548 2225 3093 2285 3054 +7549 2637 3256 2826 3282 +7550 2644 436 3292 3620 +7551 3028 3089 2221 2225 +7552 2791 3317 3277 3529 +7553 795 900 835 3398 +7554 2022 3218 1758 3326 +7555 2857 3208 3189 3312 +7556 3451 3463 2554 3464 +7557 3628 3737 1617 3740 +7558 1445 3460 3244 3663 +7559 275 2037 3486 3488 +7560 218 3549 1162 3713 +7561 1839 3354 3198 3737 +7562 2956 3476 3315 3527 +7563 3113 865 784 869 +7564 373 3744 3545 3745 +7565 1160 3366 3278 3676 +7566 868 898 779 3175 +7567 788 869 865 3182 +7568 3589 3590 1429 3747 +7569 3218 3326 2982 3371 +7570 1219 3472 3267 3566 +7571 3362 3673 1176 3695 +7572 2970 3652 3395 3760 +7573 3222 3319 1429 3747 +7574 883 361 362 3457 +7575 220 3605 1260 3711 +7576 839 410 3231 3298 +7577 2995 3318 2975 3405 +7578 2096 3247 3370 3463 +7579 460 3589 3588 3591 +7580 1563 3324 3322 3454 +7581 2055 3343 1728 3558 +7582 1425 3369 3299 3637 +7583 770 31 411 3398 +7584 2059 3324 3297 3385 +7585 1777 3425 3238 3503 +7586 887 3158 3121 3182 +7587 362 363 773 864 +7588 2649 3000 3209 3558 +7589 1823 3349 3212 3470 +7590 1037 3260 3257 3771 +7591 3177 3115 799 930 +7592 1923 3391 3390 3617 +7593 194 989 3592 3681 +7594 806 3227 421 3309 +7595 2346 3314 3252 3623 +7596 194 989 3466 3592 +7597 2228 2136 2180 3432 +7598 2435 2297 2539 3614 +7599 2718 3389 3244 3421 +7600 1258 1282 3332 3778 +7601 1070 1117 1288 3323 +7602 1512 3238 1825 3396 +7603 3024 3061 3093 2285 +7604 2954 2963 2965 3320 +7605 1131 3670 3348 3674 +7606 1756 3218 1749 3405 +7607 2144 3028 2221 2225 +7608 2128 2173 3247 3638 +7609 1454 3689 3518 3701 +7610 2916 3315 3476 3606 +7611 3139 879 933 3159 +7612 2340 2429 2540 3323 +7613 1507 1505 3327 3615 +7614 337 3360 3307 3646 +7615 2235 2289 3091 3065 +7616 3242 3405 1830 3478 +7617 1968 1967 3375 3647 +7618 2733 3327 3238 3495 +7619 3322 3324 2799 3454 +7620 929 3186 3108 3141 +7621 855 3460 1444 3663 +7622 465 832 761 3246 +7623 2886 3238 2736 3503 +7624 2178 2280 3104 2193 +7625 3288 3417 1432 3455 +7626 346 3613 3602 3722 +7627 1753 3325 1754 3350 +7628 2504 2382 2296 3703 +7629 1095 3432 2154 3751 +7630 3079 3039 3097 2242 +7631 856 1549 900 3239 +7632 2020 1961 3531 3768 +7633 1186 3457 864 3566 +7634 2855 3401 3343 3756 +7635 325 1475 3397 3603 +7636 3256 3282 1639 3671 +7637 3407 3422 2688 3629 +7638 264 815 835 3352 +7639 2379 2451 2528 3293 +7640 1938 1990 3297 3636 +7641 770 835 815 3352 +7642 1741 3327 3192 3526 +7643 1252 228 3337 3450 +7644 928 370 907 3274 +7645 3249 3413 2693 3581 +7646 1604 3390 1462 3403 +7647 3369 3373 1425 3672 +7648 3279 3709 382 3729 +7649 2148 2219 3058 3105 +7650 1865 1606 3244 3389 +7651 2718 2748 2858 3389 +7652 1865 3244 1606 3421 +7653 3041 2253 2208 2165 +7654 1297 3384 3356 3722 +7655 394 3397 3266 3603 +7656 1263 3356 3355 3719 +7657 2378 3269 2293 3381 +7658 1071 3356 3260 3539 +7659 2083 2009 3318 3478 +7660 1037 3257 3260 3384 +7661 1166 3305 3623 3640 +7662 222 3619 3427 3748 +7663 3074 3041 2253 2208 +7664 345 3602 3721 3722 +7665 2155 2188 3090 2288 +7666 995 3718 3570 3755 +7667 222 3427 1239 3748 +7668 3039 2163 3097 2242 +7669 2681 3417 3288 3455 +7670 2282 3240 1613 3638 +7671 3056 2286 3076 2227 +7672 2735 3238 3192 3396 +7673 1997 1854 2032 3645 +7674 2126 3295 2171 3363 +7675 826 369 368 767 +7676 1071 1297 1238 3384 +7677 1905 3476 1899 3527 +7678 784 3188 3113 3141 +7679 1614 835 900 3398 +7680 3308 3505 1845 3764 +7681 175 965 3602 3613 +7682 1091 1212 1148 3347 +7683 2519 3650 2438 3763 +7684 3268 3283 1174 3582 +7685 2786 2771 3319 3589 +7686 1723 3264 1698 3404 +7687 2718 2858 3244 3389 +7688 772 30 3298 3408 +7689 3267 3472 1219 3559 +7690 332 3290 3294 3313 +7691 3414 3461 2439 3583 +7692 772 3298 817 3408 +7693 322 3524 3523 3597 +7694 3054 2225 2144 3068 +7695 2542 3337 379 3450 +7696 1293 3291 3290 3294 +7697 2681 3455 3288 3562 +7698 2596 3308 2684 3505 +7699 1980 3476 3315 3606 +7700 3038 3075 2178 3104 +7701 2529 3461 3279 3583 +7702 1049 3283 3236 3293 +7703 3141 869 3121 3182 +7704 1214 1060 1306 3199 +7705 1238 3384 1297 3722 +7706 2659 3443 3442 3514 +7707 2701 3413 3198 3738 +7708 202 201 3356 3721 +7709 3253 1779 3324 3474 +7710 2908 3346 3317 3479 +7711 1103 3717 3650 3763 +7712 1260 3605 3296 3711 +7713 2263 2117 332 2226 +7714 2582 3262 3657 3690 +7715 2019 2010 1842 3318 +7716 2288 2117 332 2263 +7717 2020 3531 1961 3532 +7718 886 3112 3164 810 +7719 2521 3366 2369 3676 +7720 2289 3094 2156 3032 +7721 2039 2042 1914 3412 +7722 175 3602 3595 3613 +7723 370 369 928 3183 +7724 1747 3504 1856 3671 +7725 1110 3203 1200 3302 +7726 3288 3455 1432 3562 +7727 426 427 901 3195 +7728 2163 3039 2116 2242 +7729 1938 3297 1807 3636 +7730 1224 3268 1062 3752 +7731 1210 1083 3279 3698 +7732 1563 1572 3324 3454 +7733 3137 935 3107 3176 +7734 2855 2992 3343 3401 +7735 3118 3176 3144 792 +7736 865 3113 3188 904 +7737 2019 1842 1751 3218 +7738 3113 865 869 3182 +7739 1263 202 3356 3719 +7740 2243 2144 2225 3068 +7741 1376 220 3712 3714 +7742 3087 2243 3068 2110 +7743 461 3590 3589 3747 +7744 2265 3083 2160 3040 +7745 1881 3645 3526 3742 +7746 3076 3037 3056 2227 +7747 2039 3339 3538 3649 +7748 2152 3240 2282 3638 +7749 3463 3464 950 3766 +7750 217 3367 3683 3713 +7751 999 3578 3437 3754 +7752 3218 3326 2022 3531 +7753 1900 3422 3407 3629 +7754 1976 3375 3271 3453 +7755 3225 3305 1223 3388 +7756 339 340 2129 3751 +7757 2264 3024 3049 3095 +7758 926 3195 796 3408 +7759 2731 3289 2772 3310 +7760 2649 3343 3000 3558 +7761 3282 3325 2637 3351 +7762 409 3408 3215 3557 +7763 2053 3699 3520 3710 +7764 188 3578 1003 3691 +7765 2653 3253 2799 3324 +7766 3445 3579 1025 3630 +7767 2961 2976 3297 3324 +7768 2032 1997 3645 3652 +7769 2443 3723 3627 3751 +7770 801 3251 413 3663 +7771 1973 3310 3309 3340 +7772 3069 2189 2291 2271 +7773 2602 3392 2868 3591 +7774 1660 3255 1884 3508 +7775 455 3737 3628 3740 +7776 448 2781 2783 3689 +7777 929 3181 784 3141 +7778 1245 3236 1049 3283 +7779 3212 2721 3392 3470 +7780 926 1407 3195 3408 +7781 2719 3403 3419 3624 +7782 1953 3331 3328 3521 +7783 972 974 975 3736 +7784 2649 3000 2648 3209 +7785 2094 2096 3370 3463 +7786 1845 1449 3505 3609 +7787 1522 1542 3641 3728 +7788 2195 29 390 3094 +7789 2454 3445 2488 3704 +7790 2173 2195 2128 3247 +7791 1825 3396 3238 3425 +7792 190 3437 3651 3754 +7793 3121 869 887 3182 +7794 3277 3317 2700 3346 +7795 883 362 838 3457 +7796 258 1338 3593 3745 +7797 2967 3527 3479 3662 +7798 1095 2267 2154 3432 +7799 2710 3210 3191 3220 +7800 3030 3058 2219 3105 +7801 370 794 3274 3301 +7802 755 836 3115 910 +7803 2664 3336 3223 3503 +7804 2188 464 3090 2288 +7805 3215 3557 1555 3564 +7806 409 2777 3215 3408 +7807 3212 3349 2721 3470 +7808 956 3720 176 3721 +7809 258 1399 1386 3545 +7810 3188 784 3181 3141 +7811 2061 3470 3322 3512 +7812 2869 2871 3412 3648 +7813 856 900 795 3239 +7814 2296 1112 1047 1137 +7815 1530 1753 1752 3350 +7816 3023 2110 3075 3104 +7817 1723 3264 3404 3428 +7818 3234 3333 2374 3435 +7819 3166 3123 802 902 +7820 2447 2510 3268 3582 +7821 2173 3202 2195 3247 +7822 2670 3292 436 3486 +7823 863 935 3176 792 +7824 217 3367 3301 3683 +7825 3356 3384 2524 3722 +7826 260 3543 3669 3744 +7827 422 421 3227 3309 +7828 795 412 906 3251 +7829 2043 3243 1756 3405 +7830 2891 3256 2828 3351 +7831 390 2156 2195 3094 +7832 2718 2748 3389 3421 +7833 3141 3113 869 3182 +7834 199 3613 3384 3722 +7835 3518 3689 2783 3701 +7836 2295 3510 3688 3770 +7837 2970 3395 2873 3760 +7838 2386 3278 3230 3665 +7839 2723 2721 3212 3349 +7840 855 414 3460 3663 +7841 1437 1439 3272 3392 +7842 1499 1639 3256 3282 +7843 3445 3630 1025 3704 +7844 2701 3400 3198 3413 +7845 3264 3387 1698 3404 +7846 1060 1289 1306 3269 +7847 3091 2189 3025 3069 +7848 1516 3238 3495 3659 +7849 335 2137 2245 3347 +7850 3378 3414 1307 3461 +7851 1143 3418 3234 3560 +7852 1032 1248 1201 3381 +7853 1117 3323 1070 3437 +7854 1156 3697 1130 3780 +7855 228 3726 1353 3761 +7856 222 3746 3619 3748 +7857 3214 3221 2580 3541 +7858 2340 3302 2460 3438 +7859 3095 2264 3024 2124 +7860 1540 3518 1454 3689 +7861 3087 3043 2206 3023 +7862 772 427 30 3408 +7863 2845 3631 3471 3652 +7864 1495 1527 3214 3221 +7865 218 1304 1162 3549 +7866 465 932 761 832 +7867 2117 464 2188 2288 +7868 421 766 868 918 +7869 2771 3589 460 3591 +7870 1535 3227 1536 3258 +7871 3143 3113 3171 865 +7872 3061 2248 3093 2285 +7873 1878 3263 3217 3292 +7874 3395 3471 1998 3652 +7875 864 3472 1093 3566 +7876 1605 3403 1462 3624 +7877 3025 2125 2291 2189 +7878 3204 3307 335 3347 +7879 234 3669 3362 3744 +7880 1374 3714 3500 3748 +7881 260 3545 3543 3744 +7882 1091 1148 2185 3347 +7883 2657 3405 3242 3478 +7884 221 1239 3427 3748 +7885 3078 2245 335 2238 +7886 1452 1859 3689 3701 +7887 3375 3453 2011 3462 +7888 381 3709 3279 3725 +7889 2746 3531 3532 3768 +7890 3115 910 799 930 +7891 2784 2786 3222 3747 +7892 1883 1660 1884 3508 +7893 1848 3403 3419 3421 +7894 219 220 3711 3712 +7895 3178 769 923 3107 +7896 2189 3091 2112 3069 +7897 447 3065 2160 3083 +7898 1349 3291 1325 3543 +7899 431 2578 3508 3544 +7900 2320 3749 2402 3750 +7901 420 905 874 3169 +7902 2557 3523 3597 3599 +7903 1052 3225 1183 3388 +7904 780 829 872 3731 +7905 3123 3156 871 902 +7906 325 3397 3594 3603 +7907 2314 3676 2369 3706 +7908 2684 3505 3308 3764 +7909 2379 3293 3283 3439 +7910 3326 3531 2850 3768 +7911 882 889 367 3157 +7912 2025 3395 1998 3652 +7913 1530 1752 3233 3350 +7914 1374 3500 3746 3748 +7915 2833 3198 2834 3354 +7916 1450 1806 3216 3300 +7917 2702 3198 3349 3354 +7918 3132 769 923 3178 +7919 2219 3058 2291 2148 +7920 848 882 366 3143 +7921 3303 3430 1772 3600 +7922 3152 755 836 3115 +7923 1160 3278 1265 3676 +7924 3361 3640 2433 3695 +7925 1173 1288 1117 3438 +7926 2053 1915 3699 3710 +7927 915 3118 792 897 +7928 2112 3091 2289 3032 +7929 3382 3414 2431 3477 +7930 251 3489 1359 3709 +7931 25 3291 3311 3543 +7932 3002 3545 3544 3546 +7933 864 363 798 3472 +7934 995 3570 3754 3755 +7935 1618 3738 3581 3739 +7936 1582 3354 1839 3737 +7937 2228 2180 1149 3432 +7938 3198 3354 2833 3737 +7939 1781 2083 3318 3561 +7940 2069 1932 3277 3335 +7941 1551 1550 3353 3404 +7942 894 3180 3126 3160 +7943 1132 3472 1219 3566 +7944 2755 2731 2608 3280 +7945 1894 1462 1604 3391 +7946 1125 3333 1221 3435 +7947 2702 3349 3212 3354 +7948 1154 3723 1044 3752 +7949 809 3134 897 3161 +7950 1777 3238 1742 3503 +7951 1183 3225 1223 3388 +7952 1973 3309 1644 3340 +7953 2879 3476 3287 3606 +7954 766 3169 874 918 +7955 3191 3210 1717 3220 +7956 1254 1168 3230 3665 +7957 1265 3278 3614 3676 +7958 319 1729 318 3574 +7959 1037 3260 1267 3384 +7960 2674 3574 402 3678 +7961 3189 3208 1740 3312 +7962 1048 3688 3510 3770 +7963 2997 3436 3526 3742 +7964 2388 3717 2334 3779 +7965 349 348 3644 3736 +7966 3450 3666 1210 3698 +7967 3079 2242 2166 3029 +7968 1108 1058 1273 3382 +7969 2473 2314 2369 3706 +7970 3339 3699 1915 3710 +7971 3292 3410 276 3486 +7972 194 3580 986 3681 +7973 1715 1742 3357 3503 +7974 3209 3285 2649 3343 +7975 3547 3593 374 3745 +7976 3120 804 909 3165 +7977 3056 2158 2286 2227 +7978 1551 3353 3206 3404 +7979 1239 3427 222 3619 +7980 1462 3390 1604 3391 +7981 3091 2235 3065 3040 +7982 3469 3542 3022 3543 +7983 1510 3192 1512 3396 +7984 2242 3079 3053 3029 +7985 1614 1615 835 3398 +7986 1270 3623 3314 3640 +7987 2970 3471 3395 3652 +7988 1848 3540 3419 3624 +7989 1060 1306 3199 3269 +7990 3037 2258 2227 3070 +7991 1648 3321 1650 3512 +7992 220 3605 3714 3748 +7993 1516 3238 3192 3327 +7994 1717 3210 3191 3345 +7995 1125 1221 3234 3435 +7996 2158 3056 3037 2227 +7997 401 3558 400 3576 +7998 3268 3582 1062 3752 +7999 2922 3443 2659 3514 +8000 2472 3626 2503 3703 +8001 773 852 363 809 +8002 3137 863 935 3176 +8003 2868 3586 3272 3591 +8004 794 907 370 3274 +8005 411 866 795 412 +8006 2129 2194 2220 3627 +8007 3119 3160 3132 924 +8008 258 3744 1337 3745 +8009 204 3284 976 3358 +8010 1763 3285 3448 3678 +8011 3143 3113 865 904 +8012 2869 3538 3339 3649 +8013 2871 3521 3412 3648 +8014 2839 3198 3737 3738 +8015 3028 3089 2225 3054 +8016 2140 2221 3089 2225 +8017 3295 3469 3022 3543 +8018 1420 3277 3201 3338 +8019 421 806 766 3258 +8020 817 772 839 3298 +8021 3056 3082 463 2158 +8022 930 799 3177 903 +8023 770 411 835 3398 +8024 2172 3084 2266 2192 +8025 2970 3436 3652 3760 +8026 999 3437 190 3754 +8027 3115 3177 3148 930 +8028 3031 2286 3090 2155 +8029 1053 3302 1200 3332 +8030 2013 3633 3444 3635 +8031 2225 2144 3028 3054 +8032 373 3002 374 3545 +8033 1687 1831 1689 3359 +8034 1961 3462 3532 3768 +8035 2305 3302 3203 3693 +8036 2790 3277 3201 3529 +8037 3113 3143 3188 904 +8038 3159 933 3114 756 +8039 770 31 815 832 +8040 425 3373 3369 3672 +8041 3095 2285 3024 3054 +8042 409 3298 3408 3557 +8043 2664 3223 2893 3503 +8044 3178 923 3132 3107 +8045 912 806 3227 3258 +8046 2110 3068 3087 3023 +8047 2582 3262 446 3657 +8048 3025 3103 2125 2189 +8049 1203 1174 3283 3582 +8050 276 2037 3292 3486 +8051 1842 3405 3318 3478 +8052 3188 3157 808 904 +8053 1203 3283 1009 3582 +8054 362 363 3134 809 +8055 352 3580 3466 3681 +8056 2297 2404 2386 3230 +8057 1572 1762 3253 3376 +8058 2219 2148 2207 3105 +8059 2844 3334 3335 3728 +8060 3144 3107 935 3176 +8061 2196 3628 1617 3740 +8062 427 426 765 3165 +8063 3288 3562 1485 3563 +8064 1528 1470 1484 3288 +8065 2463 3268 3260 3539 +8066 839 3231 817 3298 +8067 1636 3338 3458 3536 +8068 1744 1787 1923 3390 +8069 830 3186 3108 929 +8070 1636 3458 3535 3536 +8071 1461 3336 1462 3393 +8072 194 986 989 3681 +8073 1034 3650 3372 3763 +8074 2833 3354 457 3604 +8075 829 1150 1090 3630 +8076 1072 1305 3377 3687 +8077 348 349 3599 3736 +8078 188 187 3402 3692 +8079 2661 3192 3327 3526 +8080 1956 1976 1958 3453 +8081 1410 3205 2256 3363 +8082 176 956 177 3720 +8083 1097 3517 3445 3704 +8084 2754 3216 2679 3448 +8085 2848 2847 2845 3631 +8086 1812 3647 3320 3649 +8087 1504 3208 3282 3312 +8088 221 222 1239 3748 +8089 2091 3597 3523 3599 +8090 3201 3277 1418 3529 +8091 3031 2286 2155 2266 +8092 3525 3631 2847 3645 +8093 423 422 779 3175 +8094 3183 369 816 3146 +8095 1112 1232 3667 3698 +8096 2765 2596 3505 3609 +8097 1274 3204 3197 3452 +8098 1366 3707 3619 3746 +8099 185 3368 3224 3507 +8100 2173 330 3247 3638 +8101 1910 3315 1980 3476 +8102 1055 3307 3204 3347 +8103 1687 1831 3359 3705 +8104 322 3523 2091 3597 +8105 2168 3055 2280 3085 +8106 3523 3576 2090 3577 +8107 2982 3371 3326 3700 +8108 1103 1156 1028 3763 +8109 2993 2961 3297 3474 +8110 1922 3412 3256 3671 +8111 851 897 3118 3161 +8112 3581 3738 2837 3739 +8113 3024 2285 3095 2124 +8114 3262 3352 446 3657 +8115 974 172 3599 3601 +8116 2223 447 3083 2121 +8117 2454 2488 2356 3704 +8118 1614 1592 1615 3398 +8119 3120 879 3139 3159 +8120 1458 3222 1429 3747 +8121 3204 3347 335 3348 +8122 889 781 367 3456 +8123 3118 792 851 3172 +8124 3320 3647 2979 3649 +8125 1684 3470 2061 3512 +8126 3255 3426 1884 3508 +8127 3035 2260 3089 2140 +8128 3166 3123 902 3147 +8129 1588 900 1549 3239 +8130 423 779 898 3175 +8131 1211 1153 3296 3706 +8132 3302 3438 1045 3693 +8133 3445 3579 2482 3778 +8134 817 3298 309 3408 +8135 887 3121 3187 819 +8136 2492 3667 3666 3698 +8137 1901 3303 1850 3430 +8138 464 2188 2240 2117 +8139 2438 3717 2388 3763 +8140 344 3719 3356 3721 +8141 261 3291 1349 3543 +8142 3464 3720 950 3766 +8143 2844 3641 3334 3728 +8144 883 838 3224 3457 +8145 1418 3201 1420 3277 +8146 2356 3517 2427 3706 +8147 3238 3396 2736 3425 +8148 3095 2285 3054 2124 +8149 2771 3563 3319 3591 +8150 3058 2178 3038 3099 +8151 3523 3524 398 3597 +8152 2585 3223 2705 3624 +8153 1912 3412 3504 3521 +8154 1986 3256 1922 3412 +8155 2664 2705 3223 3336 +8156 2192 3031 2111 3061 +8157 447 2257 2223 3240 +8158 2137 335 2204 3347 +8159 2020 3326 1757 3768 +8160 3581 3621 1836 3739 +8161 2653 2654 2799 3253 +8162 1457 1495 1527 3214 +8163 2661 2997 3192 3526 +8164 332 3290 2538 3294 +8165 3108 892 3152 830 +8166 455 3628 2196 3740 +8167 3158 887 3106 862 +8168 2569 3451 3464 3603 +8169 3233 3265 1545 3370 +8170 2453 3225 2299 3388 +8171 3037 2258 3082 2158 +8172 1747 1856 1640 3671 +8173 766 421 3169 918 +8174 1529 1824 3265 3350 +8175 1116 3366 3296 3605 +8176 3166 3148 411 866 +8177 761 832 884 3246 +8178 1067 1210 3666 3698 +8179 1101 3686 3626 3703 +8180 3084 333 3051 2192 +8181 3000 2648 3209 3558 +8182 377 3653 3485 3761 +8183 2235 3091 3073 3040 +8184 866 411 3166 412 +8185 1436 3212 1439 3392 +8186 332 2263 2226 2150 +8187 834 771 919 416 +8188 2438 3650 3717 3763 +8189 864 773 362 838 +8190 2660 3448 3285 3678 +8191 2205 2190 3092 2113 +8192 800 933 3114 3173 +8193 1095 1205 2267 3432 +8194 1728 3285 3209 3343 +8195 29 2195 2273 3094 +8196 3130 3117 893 3184 +8197 3183 907 370 3150 +8198 3194 3258 2832 3565 +8199 2775 3222 3214 3747 +8200 2733 3192 3238 3327 +8201 2970 2873 3395 3471 +8202 977 978 3644 3736 +8203 2818 3271 3375 3453 +8204 865 3188 3113 784 +8205 3058 3038 2125 3103 +8206 2525 2433 3361 3640 +8207 854 369 826 767 +8208 1878 3217 2051 3292 +8209 2265 2235 2147 3040 +8210 2110 3087 2206 3023 +8211 329 1546 3370 3638 +8212 1225 3723 1154 3749 +8213 3121 768 3138 3168 +8214 2190 3092 2283 2205 +8215 3285 3447 1763 3448 +8216 3032 3091 2289 3065 +8217 1970 2050 3401 3756 +8218 2038 1630 3431 3538 +8219 346 3595 3602 3613 +8220 2940 3326 3218 3531 +8221 3508 3516 281 3544 +8222 2207 3030 2219 3105 +8223 2957 3453 3375 3462 +8224 2166 2242 2116 3029 +8225 1466 3419 3251 3663 +8226 2172 332 2284 2263 +8227 2209 3092 2190 2113 +8228 1888 1630 2038 3538 +8229 1922 1925 3412 3671 +8230 2940 2982 3218 3326 +8231 3186 929 768 3141 +8232 1262 188 3402 3438 +8233 2260 2221 3089 2140 +8234 2286 2111 3076 2227 +8235 809 3134 362 3167 +8236 2406 3666 3450 3698 +8237 3131 3168 3110 776 +8238 1673 3334 3277 3338 +8239 2499 3507 3402 3693 +8240 2293 3380 2509 3381 +8241 264 835 1615 3398 +8242 792 935 3144 915 +8243 3263 3292 2016 3620 +8244 912 3227 806 3309 +8245 3069 2112 2189 2271 +8246 3050 2260 2221 3089 +8247 1323 3669 234 3744 +8248 822 3119 3137 3178 +8249 1723 1698 1697 3404 +8250 251 3491 3489 3709 +8251 3368 3507 953 3765 +8252 3049 3077 2124 3036 +8253 1064 3197 1274 3204 +8254 3360 3749 2456 3751 +8255 1282 3418 3332 3778 +8256 2505 3438 2460 3693 +8257 1967 3475 3375 3647 +8258 3079 2206 3043 3096 +8259 2434 3473 2326 3758 +8260 3153 879 3120 3159 +8261 1036 3252 1145 3314 +8262 1670 3289 3280 3310 +8263 3348 3670 2444 3674 +8264 1265 3614 1063 3676 +8265 3150 932 761 465 +8266 2117 3057 464 2288 +8267 1232 3666 3667 3698 +8268 3103 3038 2125 3055 +8269 3150 816 932 910 +8270 3334 3338 1673 3536 +8271 755 3174 871 930 +8272 2273 2195 2156 3094 +8273 1282 1053 1258 3332 +8274 1688 1412 3448 3449 +8275 1987 3329 2067 3385 +8276 2553 2406 3279 3698 +8277 3174 755 3115 930 +8278 1758 1750 2030 3371 +8279 990 3570 995 3718 +8280 185 3224 1291 3507 +8281 1103 3650 1034 3763 +8282 410 839 800 3173 +8283 414 855 413 3663 +8284 2537 3342 3284 3627 +8285 2148 3098 3041 3105 +8286 2432 2322 3260 3539 +8287 2638 3325 2726 3689 +8288 332 3313 3294 3670 +8289 1630 3339 1888 3710 +8290 1618 1908 3581 3738 +8291 1243 3510 1107 3781 +8292 2929 2860 3218 3371 +8293 458 2127 2275 2190 +8294 897 915 3134 809 +8295 2832 2835 2609 3194 +8296 3252 1036 3622 3623 +8297 869 929 784 3141 +8298 3065 2273 29 447 +8299 904 808 3188 784 +8300 227 228 3450 3724 +8301 2826 3282 3256 3671 +8302 1412 1688 1411 3449 +8303 265 3262 1533 3657 +8304 1756 1749 1828 3405 +8305 3139 804 879 3120 +8306 1970 3401 3228 3756 +8307 2660 3447 3285 3448 +8308 2498 3257 347 3384 +8309 2833 3604 457 3628 +8310 3134 3118 915 897 +8311 2263 2284 2150 3313 +8312 928 907 794 3274 +8313 3510 3687 2372 3688 +8314 2910 3328 3331 3521 +8315 265 3352 3262 3657 +8316 3325 3350 2638 3351 +8317 1916 3287 3248 3476 +8318 3466 3592 992 3716 +8319 3092 2283 458 2190 +8320 882 808 889 3157 +8321 2192 3031 2266 2111 +8322 3263 3327 2991 3620 +8323 3297 3634 1807 3636 +8324 3582 3750 2486 3757 +8325 2047 3331 1953 3521 +8326 381 3489 3709 3725 +8327 28 370 870 761 +8328 1348 3726 1350 3761 +8329 2885 3515 3459 3561 +8330 2289 2235 2160 3065 +8331 1912 3504 3412 3671 +8332 882 366 367 848 +8333 3284 3342 1290 3627 +8334 2485 2304 3305 3623 +8335 1903 2046 1650 3330 +8336 2828 2826 2637 3256 +8337 2885 3459 3515 3777 +8338 3192 3396 1510 3436 +8339 3376 3441 2881 3775 +8340 2938 3634 3297 3636 +8341 422 806 421 3309 +8342 2558 3576 3523 3577 +8343 1901 1772 3430 3600 +8344 3151 754 3170 822 +8345 756 3114 3144 915 +8346 1099 3461 3414 3583 +8347 2378 2293 2509 3381 +8348 1326 3656 3712 3713 +8349 1913 1914 3412 3648 +8350 3279 3461 1030 3583 +8351 370 928 369 3274 +8352 2171 3295 285 3363 +8353 222 1371 3746 3748 +8354 2295 2399 3510 3770 +8355 2061 3322 3321 3512 +8356 2251 390 2195 3202 +8357 1419 1744 3389 3529 +8358 1048 3510 1281 3770 +8359 30 839 410 3173 +8360 449 448 2121 3064 +8361 410 895 839 3231 +8362 3169 905 874 811 +8363 1132 1219 3267 3566 +8364 3358 3463 950 3766 +8365 867 901 427 3195 +8366 310 3215 3408 3557 +8367 3327 3615 2991 3620 +8368 1016 3267 3203 3566 +8369 909 879 804 3120 +8370 3552 162 3691 3692 +8371 1055 1212 3307 3347 +8372 3279 3461 2553 3698 +8373 3115 3148 3174 930 +8374 2714 3287 2673 3715 +8375 1043 1176 3673 3695 +8376 1755 1748 1897 3196 +8377 3031 2266 3084 2192 +8378 795 856 3239 3251 +8379 2259 3090 2286 2155 +8380 3306 3445 1249 3676 +8381 1933 1800 1799 3194 +8382 3283 3293 1049 3439 +8383 254 1350 3485 3653 +8384 2478 2320 2402 3750 +8385 1754 3350 3325 3351 +8386 1981 1905 1899 3527 +8387 2557 3523 398 3597 +8388 3277 3334 2759 3338 +8389 1109 3197 1052 3388 +8390 1771 3365 3303 3397 +8391 427 917 30 3139 +8392 1760 3474 3253 3616 +8393 930 3177 3148 903 +8394 3552 3555 162 3692 +8395 2154 3432 339 3751 +8396 1996 2001 3631 3682 +8397 2857 2827 3208 3312 +8398 1555 3215 310 3557 +8399 1614 900 1588 3239 +8400 1218 3348 3204 3452 +8401 895 410 839 762 +8402 2251 390 2118 2195 +8403 2124 3095 3049 3036 +8404 2607 3369 3429 3637 +8405 2252 449 448 2121 +8406 340 2239 2129 3627 +8407 2508 3510 2312 3626 +8408 3598 3599 172 3601 +8409 963 3721 965 3722 +8410 1821 3508 3426 3516 +8411 933 804 879 3139 +8412 3233 3350 2595 3689 +8413 368 826 889 3456 +8414 867 427 772 3408 +8415 2516 3283 2458 3528 +8416 1723 3404 1697 3428 +8417 3139 427 804 3165 +8418 344 3720 3719 3721 +8419 3038 2280 2178 2125 +8420 851 792 863 3172 +8421 2810 3208 2827 3282 +8422 421 766 874 3258 +8423 2111 2248 2192 3061 +8424 1549 3239 856 3251 +8425 1823 1985 3212 3349 +8426 830 3108 892 929 +8427 3266 3365 1477 3397 +8428 2607 3429 3446 3637 +8429 3404 3428 2988 3561 +8430 366 829 848 780 +8431 837 754 3170 3126 +8432 2444 3348 333 3670 +8433 1242 3382 1273 3477 +8434 2696 3334 3277 3335 +8435 919 416 771 3535 +8436 882 367 366 3143 +8437 2759 3338 3334 3536 +8438 2220 1095 2154 3751 +8439 3115 3146 3183 910 +8440 2516 3283 3528 3625 +8441 2299 3197 3452 3675 +8442 3190 2757 3219 3235 +8443 2050 3343 2055 3558 +8444 2252 2257 448 3518 +8445 1783 3272 3354 3604 +8446 3023 2206 2250 3096 +8447 933 3114 3139 3159 +8448 1548 3239 3251 3419 +8449 1218 1017 3348 3452 +8450 1116 3296 1260 3605 +8451 254 3485 1350 3726 +8452 201 1263 202 3356 +8453 3466 3509 1256 3580 +8454 1779 1941 2059 3297 +8455 2223 447 2160 3083 +8456 2551 2482 3579 3778 +8457 1772 3303 1901 3430 +8458 3093 3024 2285 3054 +8459 1461 3336 3393 3425 +8460 848 882 3143 759 +8461 2989 3329 2990 3679 +8462 2271 2148 3098 3041 +8463 2175 3043 2206 3087 +8464 249 3496 3493 3707 +8465 2735 3396 3192 3436 +8466 3300 3505 1450 3506 +8467 1978 3271 1949 3341 +8468 1900 3407 3422 3446 +8469 1054 1219 3472 3559 +8470 869 768 929 3141 +8471 3272 3586 1437 3591 +8472 394 3594 3397 3603 +8473 1450 3300 3216 3505 +8474 1941 2059 3297 3385 +8475 2845 3471 3631 3682 +8476 2443 2320 3723 3749 +8477 1126 1281 3510 3770 +8478 3093 3035 3089 2140 +8479 1268 3323 1034 3650 +8480 3361 3640 1299 3702 +8481 3201 3277 2790 3338 +8482 3099 3058 2219 3030 +8483 3333 3381 2430 3382 +8484 3332 3579 1065 3778 +8485 869 788 887 3182 +8486 2008 3327 1741 3526 +8487 3318 3405 2995 3478 +8488 3060 3030 3088 2161 +8489 2193 3085 3048 2130 +8490 1289 3269 1060 3697 +8491 2119 3074 2253 2208 +8492 381 382 3279 3709 +8493 2156 2118 390 2195 +8494 800 839 410 762 +8495 882 3157 3143 904 +8496 1450 1805 1806 3300 +8497 909 879 3120 791 +8498 2719 3419 3540 3624 +8499 2512 3605 3366 3665 +8500 2206 2175 3087 2110 +8501 324 3596 3397 3600 +8502 1819 3198 3400 3413 +8503 2837 3581 2693 3738 +8504 768 869 3121 3141 +8505 1987 3385 1990 3679 +8506 1164 3627 3342 3723 +8507 2463 2419 3260 3268 +8508 2187 2127 2275 3604 +8509 2525 3640 3361 3702 +8510 2375 3333 2535 3435 +8511 2512 2507 3605 3665 +8512 3043 2206 3079 2132 +8513 164 3573 3553 3754 +8514 1404 815 264 3352 +8515 3104 2110 2178 2193 +8516 2915 2978 2988 3318 +8517 833 3159 3144 756 +8518 1545 3370 3265 3451 +8519 3342 3627 2393 3723 +8520 3105 2253 2207 3074 +8521 1282 1053 3332 3418 +8522 361 883 899 3224 +8523 2637 2828 3256 3351 +8524 2258 3059 3037 3082 +8525 1897 3190 3219 3235 +8526 935 833 3144 915 +8527 818 3110 3168 776 +8528 3039 3053 2116 2242 +8529 835 411 866 795 +8530 855 801 413 3663 +8531 3569 3574 317 3678 +8532 1404 3246 815 3352 +8533 346 3602 345 3722 +8534 2207 2148 2253 3105 +8535 3223 3336 1459 3503 +8536 1060 3269 3199 3697 +8537 829 366 848 3456 +8538 1055 3347 3204 3348 +8539 2235 2160 3065 3040 +8540 2265 2160 3083 2121 +8541 2242 3053 2116 3029 +8542 1859 3325 1753 3689 +8543 2782 3251 3419 3663 +8544 2235 3073 2147 3040 +8545 431 3544 3508 3546 +8546 1190 3582 1009 3758 +8547 412 413 764 3251 +8548 791 879 3120 3153 +8549 2551 3445 2482 3778 +8550 1021 3260 3236 3268 +8551 2245 3347 2182 3753 +8552 2314 2427 3676 3706 +8553 2051 3292 3217 3443 +8554 2832 3194 2609 3258 +8555 176 3602 964 3721 +8556 3355 3356 344 3719 +8557 1767 3280 1670 3289 +8558 339 2129 2220 3751 +8559 855 1444 1446 3663 +8560 2078 1931 3317 3346 +8561 3296 3605 2459 3711 +8562 3167 361 362 823 +8563 3553 3578 164 3754 +8564 1510 1511 1512 3192 +8565 411 3148 31 903 +8566 1891 1892 3317 3529 +8567 2746 3532 3462 3768 +8568 1504 1740 3208 3312 +8569 367 848 366 3456 +8570 1987 3664 3329 3679 +8571 3040 2265 3083 3064 +8572 767 816 369 3146 +8573 1390 3295 3311 3543 +8574 902 3156 871 786 +8575 3032 2289 3094 3065 +8576 2398 3440 3439 3626 +8577 2967 3476 2956 3527 +8578 874 421 3169 766 +8579 2664 2705 2893 3223 +8580 2137 335 2238 2204 +8581 950 3463 178 3464 +8582 2735 2736 3238 3396 +8583 2477 3675 3673 3695 +8584 2569 3464 2555 3603 +8585 1557 3270 3206 3353 +8586 2719 3419 3403 3421 +8587 1183 1223 1020 3388 +8588 1048 1281 3688 3770 +8589 1872 1908 1907 3738 +8590 1730 1729 319 3209 +8591 776 886 3164 810 +8592 2612 2891 3351 3365 +8593 2731 2608 3280 3310 +8594 367 781 848 3456 +8595 836 3146 3152 3115 +8596 3430 3524 1571 3600 +8597 2888 2736 3425 3503 +8598 3137 863 3176 3172 +8599 258 1337 1338 3745 +8600 2592 3265 3233 3370 +8601 2013 3444 1962 3635 +8602 401 2648 400 3558 +8603 2125 2219 3058 2291 +8604 3180 3162 894 3126 +8605 2131 3088 3030 2161 +8606 2972 3699 3339 3710 +8607 3749 3750 1098 3757 +8608 823 361 362 883 +8609 1738 3319 1574 3591 +8610 910 3115 755 930 +8611 3073 2189 3091 2235 +8612 3048 3085 3027 2130 +8613 1704 3615 1507 3620 +8614 382 2464 3279 3729 +8615 1432 3417 3288 3741 +8616 1772 1850 1901 3303 +8617 3166 3148 866 802 +8618 3058 3038 2219 2125 +8619 2839 3198 2833 3737 +8620 983 3585 3468 3736 +8621 3135 421 868 918 +8622 1847 3223 3540 3624 +8623 1507 1704 1505 3615 +8624 974 971 172 3601 +8625 926 796 841 3408 +8626 1538 3214 3469 3541 +8627 2827 3282 3208 3312 +8628 1760 3253 3254 3616 +8629 3168 3131 819 776 +8630 2238 2245 335 2137 +8631 412 3166 866 764 +8632 3023 2206 2110 2250 +8633 185 3200 3224 3368 +8634 456 2141 2216 3628 +8635 2129 3063 2165 3100 +8636 1117 1070 1298 3437 +8637 3031 2286 2111 3076 +8638 2160 2235 2265 3040 +8639 2197 2152 2282 3638 +8640 3134 3144 3114 915 +8641 2398 3439 3625 3626 +8642 2046 3400 2045 3512 +8643 2043 1756 1828 3405 +8644 1149 1192 1091 3432 +8645 2787 425 3299 3672 +8646 381 382 2464 3279 +8647 254 3485 3483 3653 +8648 1164 1225 3627 3723 +8649 2833 2839 2834 3198 +8650 1976 1956 3375 3453 +8651 3095 3049 2264 2124 +8652 2455 2388 3779 3780 +8653 3241 2779 3370 3638 +8654 457 3604 2214 3628 +8655 3106 3129 3158 862 +8656 363 362 773 809 +8657 3256 3364 1620 3730 +8658 3050 2260 3089 3035 +8659 391 3247 3370 3638 +8660 1277 3290 2181 3313 +8661 3217 3263 2645 3292 +8662 959 188 3691 3692 +8663 759 3143 3171 865 +8664 3142 909 3120 791 +8665 446 3352 3262 3398 +8666 3075 3038 2178 3099 +8667 1429 3222 1458 3319 +8668 992 3716 3592 3718 +8669 2248 2140 3093 2285 +8670 1702 3515 3428 3561 +8671 825 1280 3274 3301 +8672 2196 2216 2141 3628 +8673 2105 3464 3451 3603 +8674 2335 3372 3323 3650 +8675 1276 3461 3279 3698 +8676 901 896 426 3672 +8677 3056 463 32 2259 +8678 427 804 867 3139 +8679 276 275 2037 3486 +8680 2960 3218 2860 3405 +8681 3183 816 3150 910 +8682 2532 3517 3456 3704 +8683 3083 3065 2160 3040 +8684 3360 3749 1098 3757 +8685 3188 865 904 784 +8686 2124 3077 2175 3036 +8687 2524 2432 2322 3260 +8688 335 3204 2411 3307 +8689 1215 3372 3193 3406 +8690 3138 768 818 3168 +8691 944 953 3368 3507 +8692 2124 3054 3095 3036 +8693 2046 1648 1650 3512 +8694 1908 1872 1479 3581 +8695 892 755 3152 830 +8696 1910 1980 1905 3476 +8697 3225 2541 3528 3685 +8698 1763 3448 1647 3678 +8699 463 32 2126 3363 +8700 2006 3436 2025 3652 +8701 1920 3285 3343 3772 +8702 2197 2282 1613 3638 +8703 414 777 855 3460 +8704 814 868 3135 3175 +8705 2227 2258 2142 3070 +8706 935 833 3107 3144 +8707 1702 1809 3428 3515 +8708 3120 3139 804 3165 +8709 1492 3241 1546 3638 +8710 1028 1156 1130 3780 +8711 1901 3430 1571 3600 +8712 2008 1513 1741 3327 +8713 792 3144 3118 915 +8714 1062 3268 1174 3582 +8715 1790 1793 1792 3727 +8716 3117 908 893 3138 +8717 3228 3304 1711 3431 +8718 809 362 773 3167 +8719 2154 2220 2267 1095 +8720 836 3146 3115 910 +8721 902 3123 3156 3147 +8722 881 826 1206 3456 +8723 2410 2504 3316 3379 +8724 409 3557 3215 3564 +8725 2298 2486 3582 3750 +8726 1777 1825 3238 3425 +8727 2462 3697 3661 3763 +8728 1506 3263 1507 3327 +8729 2286 3056 3031 3090 +8730 2147 2265 3040 3064 +8731 3118 792 897 851 +8732 332 2150 2226 3290 +8733 3510 3687 1246 3781 +8734 1297 3356 1071 3539 +8735 3223 3502 2893 3503 +8736 1516 3495 1515 3659 +8737 2723 2722 2721 3349 +8738 1606 3389 3390 3403 +8739 3184 3117 893 3138 +8740 2302 3414 3378 3461 +8741 1055 1212 3204 3307 +8742 2954 3320 2950 3462 +8743 2188 464 2240 3311 +8744 3126 837 894 3160 +8745 2142 3033 2249 2264 +8746 2485 2428 2304 3623 +8747 363 364 852 798 +8748 2279 2125 3103 2189 +8749 3198 3413 1819 3738 +8750 1881 2031 3645 3742 +8751 3041 2253 2148 3105 +8752 2043 3242 3243 3405 +8753 1516 1515 3238 3659 +8754 2286 3031 3056 3076 +8755 1536 3227 1800 3258 +8756 1986 3256 3412 3538 +8757 368 3456 2532 3517 +8758 2298 3582 3268 3752 +8759 1210 1217 1083 3698 +8760 3284 3342 26 3358 +8761 3168 3121 768 819 +8762 1374 246 3500 3714 +8763 3058 2219 2178 3099 +8764 3360 3432 1057 3751 +8765 1517 1642 1516 3192 +8766 2522 3225 2541 3528 +8767 1173 1045 3302 3438 +8768 3291 3543 371 3669 +8769 1771 1477 3365 3397 +8770 772 817 841 3408 +8771 1970 3228 1712 3756 +8772 3193 3372 2310 3406 +8773 3316 3378 1136 3461 +8774 2252 448 449 3518 +8775 1938 1807 1990 3636 +8776 2870 3431 2875 3538 +8777 756 3144 833 915 +8778 2128 2197 2173 3638 +8779 1656 1437 3272 3586 +8780 2744 3411 3255 3774 +8781 3135 868 422 3175 +8782 335 336 2238 2204 +8783 378 3485 3726 3761 +8784 1958 1978 1949 3341 +8785 3120 909 3142 3165 +8786 415 834 790 416 +8787 2140 3093 3035 2248 +8788 2465 3307 3204 3608 +8789 1801 1795 1794 3271 +8790 3217 3292 2646 3443 +8791 202 3720 962 3721 +8792 1443 3518 3383 3701 +8793 2014 3632 3631 3633 +8794 427 765 867 3165 +8795 1967 3548 3475 3647 +8796 412 866 795 906 +8797 902 802 3166 764 +8798 2389 3225 2522 3528 +8799 1626 3441 3376 3775 +8800 3024 2186 3061 2285 +8801 460 2246 2133 3589 +8802 898 814 3128 3175 +8803 2721 3349 2722 3470 +8804 2160 2223 3083 2121 +8805 895 787 845 3200 +8806 2252 449 3383 3518 +8807 1548 3251 1466 3419 +8808 2248 3093 3035 3061 +8809 2379 2451 3293 3439 +8810 2160 3065 447 2223 +8811 320 2090 3523 3576 +8812 770 411 31 903 +8813 3049 2249 3033 2264 +8814 2649 3209 2650 3285 +8815 1876 3586 3272 3604 +8816 399 3523 400 3558 +8817 3052 2283 458 3092 +8818 2895 3426 3416 3775 +8819 2646 3217 2645 3292 +8820 2083 1700 3404 3561 +8821 830 3156 3186 908 +8822 2219 2178 3038 3058 +8823 2462 3696 3661 3697 +8824 1451 1845 3505 3764 +8825 2248 3061 2186 2285 +8826 3153 833 879 3159 +8827 412 3251 3239 3419 +8828 2836 2921 2983 3645 +8829 3207 3244 2858 3389 +8830 1823 1683 3349 3470 +8831 1347 1353 3726 3761 +8832 2553 3461 2471 3698 +8833 1196 1084 3316 3379 +8834 2522 3225 2389 3473 +8835 1230 3197 1109 3675 +8836 2737 3430 3303 3600 +8837 3170 754 837 822 +8838 2121 3083 2265 3064 +8839 1858 3220 3194 3280 +8840 1736 1461 1462 3393 +8841 826 1094 1206 3456 +8842 946 3358 950 3766 +8843 3296 3549 1304 3711 +8844 1199 1274 3197 3452 +8845 2962 3253 3474 3616 +8846 3092 3052 2283 2205 +8847 854 1094 826 3550 +8848 822 3137 3151 775 +8849 895 3200 845 3231 +8850 2258 3037 3059 3070 +8851 775 863 3137 3172 +8852 2665 3393 3336 3425 +8853 2551 2422 3445 3778 +8854 1457 3214 3222 3747 +8855 2429 2480 3437 3438 +8856 2437 3697 2388 3780 +8857 417 3533 771 3535 +8858 1968 2011 3320 3375 +8859 2938 3297 2987 3636 +8860 1268 3323 3650 3651 +8861 2818 3341 3271 3453 +8862 2989 2917 2987 3679 +8863 2111 3061 3076 2186 +8864 2962 3254 3253 3616 +8865 2939 3318 3459 3531 +8866 1522 1521 1542 3728 +8867 1104 3414 3477 3583 +8868 2192 3051 3031 3061 +8869 3054 2144 3028 3068 +8870 3135 3169 421 918 +8871 2061 3321 1648 3512 +8872 3047 3101 3034 2114 +8873 2298 3750 3582 3752 +8874 839 30 917 3173 +8875 816 767 836 3146 +8876 754 894 850 3126 +8877 1940 1877 3217 3443 +8878 3082 2222 463 2158 +8879 2820 3504 3412 3521 +8880 2786 2785 3222 3319 +8881 2888 2886 2736 3503 +8882 1693 1868 3479 3662 +8883 2633 3390 2635 3403 +8884 3019 3311 3295 3543 +8885 767 808 836 3146 +8886 786 908 893 3117 +8887 3053 3039 3079 2242 +8888 399 3522 3523 3558 +8889 1248 3333 1080 3381 +8890 1131 1218 1017 3348 +8891 3526 3645 2836 3742 +8892 2236 3069 2112 3032 +8893 2503 3686 2332 3703 +8894 2032 3652 3645 3742 +8895 1048 3687 3510 3688 +8896 2174 3049 3077 2124 +8897 2959 2995 3405 3478 +8898 1143 1053 3418 3560 +8899 2891 3364 3256 3730 +8900 2901 3317 3420 3662 +8901 3045 2205 3092 2113 +8902 3091 2112 3069 3032 +8903 458 459 3092 2190 +8904 2700 3277 2791 3317 +8905 2171 1403 3295 3311 +8906 2142 3033 2264 3070 +8907 889 367 368 3456 +8908 396 3397 3596 3600 +8909 1783 3354 1583 3604 +8910 447 2273 29 2223 +8911 1466 3421 3419 3663 +8912 2548 2374 3333 3435 +8913 3289 3310 1670 3429 +8914 3294 3362 2546 3673 +8915 3188 3143 3157 904 +8916 3223 3501 268 3654 +8917 1186 838 864 3457 +8918 185 3200 1291 3224 +8919 2209 3045 3092 2113 +8920 3036 2124 2225 2243 +8921 2172 2266 3057 2288 +8922 1449 3506 3505 3609 +8923 2245 3078 2164 2238 +8924 1016 1132 3267 3566 +8925 1781 2083 2009 3318 +8926 2121 448 3083 3064 +8927 1703 2016 3292 3620 +8928 883 762 361 899 +8929 1252 3450 3337 3666 +8930 3361 1115 3640 3695 +8931 2598 3562 3288 3563 +8932 2516 3439 3283 3625 +8933 437 3488 436 3620 +8934 3303 3304 1850 3430 +8935 887 3158 3129 862 +8936 1686 3322 2061 3470 +8937 1783 1583 1581 3604 +8938 1551 1552 1550 3404 +8939 1789 3423 3422 3727 +8940 2078 1892 1931 3346 +8941 2224 3102 2274 2122 +8942 3090 2286 3056 2259 +8943 1986 1922 1925 3412 +8944 252 3489 3487 3724 +8945 3174 3156 871 3123 +8946 463 2126 2222 3363 +8947 3097 3079 2242 2132 +8948 1034 3323 3372 3650 +8949 3439 3440 1081 3626 +8950 2421 3673 3362 3695 +8951 2726 3689 3325 3701 +8952 2767 3216 2754 3300 +8953 2271 3069 2112 2236 +8954 908 3156 3186 3138 +8955 3312 3325 1860 3701 +8956 2112 3091 2189 2235 +8957 1456 1429 3590 3747 +8958 366 848 3143 759 +8959 1836 3581 3235 3621 +8960 3063 2236 2165 3100 +8961 1614 3239 1588 3398 +8962 2592 3265 3370 3451 +8963 768 869 887 3121 +8964 3078 2164 2260 3035 +8965 1056 3456 1094 3517 +8966 868 814 898 3175 +8967 415 3145 3130 834 +8968 2163 3052 3039 3097 +8969 887 3187 3106 819 +8970 1027 1221 3333 3660 +8971 447 3065 2273 2223 +8972 2519 3372 2335 3650 +8973 336 2204 335 3347 +8974 1516 1515 1517 3238 +8975 320 3523 3522 3558 +8976 3170 3106 754 3151 +8977 3075 2218 2110 3023 +8978 3255 3411 2744 3480 +8979 2295 3510 2372 3688 +8980 217 3301 1379 3683 +8981 2370 3414 2439 3583 +8982 1425 3299 1474 3637 +8983 819 818 3168 776 +8984 2976 3297 3324 3385 +8985 2259 463 32 2126 +8986 2370 3477 3414 3583 +8987 3050 3078 2238 2260 +8988 2705 3223 3336 3624 +8989 3051 333 2123 2192 +8990 2469 2299 3197 3452 +8991 193 3466 992 3716 +8992 2063 2047 1953 3521 +8993 2280 2125 3055 2168 +8994 2409 3332 2497 3418 +8995 368 367 889 3157 +8996 1202 1072 1305 3377 +8997 2582 3657 445 3690 +8998 260 3669 1331 3744 +8999 2496 3267 3472 3566 +9000 909 765 3142 3165 +9001 2163 3097 2242 2132 +9002 2855 2856 3401 3756 +9003 892 755 836 3152 +9004 3000 3343 2992 3558 +9005 3060 2207 3030 2161 +9006 1717 1726 3191 3220 +9007 3170 754 3106 3126 +9008 811 3169 3122 918 +9009 336 2238 2204 2115 +9010 1620 1641 3256 3351 +9011 2520 3614 3278 3676 +9012 1663 3534 3537 3641 +9013 3348 3452 1017 3674 +9014 2965 2979 3320 3647 +9015 344 345 3602 3721 +9016 917 800 839 3173 +9017 1790 3423 1789 3727 +9018 2805 3519 3415 3727 +9019 936 3229 3202 3358 +9020 2529 3279 2363 3583 +9021 329 3370 3247 3638 +9022 1446 1444 1445 3663 +9023 784 892 3181 929 +9024 3294 3362 235 3669 +9025 3090 32 464 2188 +9026 2881 3376 2632 3441 +9027 2302 2441 3378 3414 +9028 2496 3472 3267 3559 +9029 781 882 367 848 +9030 2329 3749 3360 3757 +9031 2222 462 463 3205 +9032 1837 3349 3198 3354 +9033 983 3468 196 3736 +9034 3174 755 871 830 +9035 2375 2535 2297 3435 +9036 3262 3352 265 3398 +9037 3645 3652 2848 3742 +9038 3439 1081 3625 3626 +9039 2788 3299 2789 3637 +9040 811 3122 3162 774 +9041 2294 3234 3418 3560 +9042 1869 3420 3317 3662 +9043 1538 3214 1537 3469 +9044 867 917 427 3139 +9045 364 878 3472 3731 +9046 1047 1165 1243 3703 +9047 310 3408 3298 3557 +9048 252 1359 3489 3724 +9049 2129 340 3063 3100 +9050 2901 2908 3317 3662 +9051 2323 2433 3640 3695 +9052 1947 3459 3318 3531 +9053 3212 3272 2752 3354 +9054 376 3702 3642 3732 +9055 2225 3054 2124 3036 +9056 3543 372 3669 3744 +9057 3223 3654 267 3690 +9058 347 2498 348 3601 +9059 2844 3334 2698 3335 +9060 246 1374 3500 3746 +9061 2772 3310 3289 3429 +9062 1034 3323 1268 3372 +9063 3228 3520 1712 3756 +9064 3440 3510 2399 3770 +9065 3001 3022 3542 3543 +9066 2482 3445 2337 3579 +9067 3543 3545 372 3744 +9068 2222 2191 2151 3363 +9069 2371 3378 3316 3461 +9070 3166 3123 3148 802 +9071 3416 3426 1625 3775 +9072 3314 3623 2544 3640 +9073 2110 2193 3048 2250 +9074 1203 1062 1174 3582 +9075 1323 234 1329 3744 +9076 3319 3563 1574 3591 +9077 1875 3220 3280 3465 +9078 1486 3222 3221 3288 +9079 2580 3469 3214 3541 +9080 2737 3524 3430 3600 +9081 1513 3327 2008 3526 +9082 1378 3301 3213 3683 +9083 3124 3188 784 3181 +9084 2131 3099 2219 3030 +9085 420 421 874 3258 +9086 2430 3333 2378 3381 +9087 2792 3389 2813 3529 +9088 831 885 790 3535 +9089 452 2224 2135 3237 +9090 882 367 889 781 +9091 2051 3409 3292 3443 +9092 460 461 2246 3589 +9093 2121 448 2252 2257 +9094 897 3134 3118 3161 +9095 3243 3371 2666 3772 +9096 3248 3287 2879 3476 +9097 1303 3402 3507 3693 +9098 2385 2428 2485 3640 +9099 1859 1860 3325 3701 +9100 1072 3377 3199 3687 +9101 2069 3277 1675 3334 +9102 864 363 773 798 +9103 2784 461 2786 3747 +9104 3121 3186 768 3141 +9105 2835 3210 3194 3565 +9106 2207 2131 3030 2161 +9107 1276 3279 1083 3698 +9108 768 908 3186 3138 +9109 3315 3428 1809 3515 +9110 3164 3112 3179 810 +9111 3293 1266 3770 3771 +9112 1842 1829 3405 3478 +9113 2370 2431 3414 3477 +9114 1865 3244 3207 3389 +9115 2558 400 3523 3576 +9116 3164 776 3110 3125 +9117 1700 3428 3404 3561 +9118 32 3090 2259 2188 +9119 2218 2178 3075 2110 +9120 2441 2448 2302 3378 +9121 3103 2125 2279 3055 +9122 2891 2828 2612 3351 +9123 3027 3042 2170 3062 +9124 887 3158 3182 3129 +9125 1036 3314 1270 3623 +9126 1432 3288 1470 3741 +9127 3147 902 3166 764 +9128 1086 3650 1103 3717 +9129 2617 3201 2790 3338 +9130 2239 3284 2153 3627 +9131 1996 2015 1997 3631 +9132 198 3601 977 3644 +9133 3444 3633 2671 3635 +9134 3170 3119 3151 822 +9135 2156 2273 3094 2289 +9136 1569 3433 3420 3434 +9137 2690 3275 3407 3629 +9138 3090 2259 2188 2155 +9139 1242 1273 1078 3477 +9140 1403 285 2171 3295 +9141 2243 3087 2175 2110 +9142 1227 3566 3203 3694 +9143 2222 462 3082 463 +9144 763 897 851 3161 +9145 2657 2884 3478 3519 +9146 3384 3613 346 3722 +9147 2326 2458 3283 3528 +9148 3135 3128 814 3175 +9149 1917 3287 1926 3715 +9150 2746 2850 3531 3768 +9151 1132 1054 1219 3472 +9152 2809 3423 2808 3727 +9153 2422 2482 2551 3445 +9154 1499 1639 1641 3256 +9155 2264 3033 3049 3070 +9156 1191 1249 3445 3676 +9157 2169 3621 454 3740 +9158 2489 2340 2540 3193 +9159 1012 3414 3382 3477 +9160 1136 3316 3461 3698 +9161 337 2412 3360 3646 +9162 2821 3412 3256 3538 +9163 2404 2297 2523 3477 +9164 1517 3192 1516 3238 +9165 1472 3299 3672 3743 +9166 3483 3485 377 3653 +9167 1811 2039 1914 3649 +9168 1725 3245 3191 3387 +9169 1085 3582 3750 3752 +9170 3079 2206 3096 2166 +9171 2343 3268 2510 3283 +9172 2716 2714 2673 3715 +9173 369 928 816 767 +9174 1534 1535 1536 3258 +9175 1957 3453 3281 3777 +9176 1425 1472 1474 3299 +9177 804 765 909 3165 +9178 1546 3241 3233 3370 +9179 1618 1907 1908 3738 +9180 427 867 804 3165 +9181 918 3135 3122 774 +9182 3031 2286 2266 2111 +9183 2227 3076 3037 3070 +9184 886 760 3112 810 +9185 2345 2471 2553 3461 +9186 1668 3310 1973 3340 +9187 3122 3180 3162 774 +9188 2916 3476 2879 3606 +9189 2666 3243 2860 3371 +9190 2274 3042 2130 2167 +9191 3172 3137 775 3111 +9192 3156 908 3117 3138 +9193 2787 3672 3299 3743 +9194 2993 2961 2976 3297 +9195 3128 423 898 3175 +9196 2705 2706 2893 3223 +9197 390 3067 2156 3094 +9198 3203 3566 2395 3694 +9199 1075 3693 3507 3694 +9200 3054 2285 2225 2124 +9201 1812 1969 3320 3647 +9202 3520 3699 2852 3710 +9203 2858 3207 2900 3244 +9204 3057 3090 464 2288 +9205 1536 1799 1800 3227 +9206 1619 1839 3198 3737 +9207 1358 3709 1359 3725 +9208 2829 3621 3581 3739 +9209 2296 2495 2377 3667 +9210 3172 851 3133 3111 +9211 391 3370 2779 3638 +9212 458 2127 457 3604 +9213 1068 1299 3640 3702 +9214 3056 3037 3082 2158 +9215 2668 3304 3303 3430 +9216 1610 3420 3232 3618 +9217 2205 3092 3052 3045 +9218 3263 3327 1506 3526 +9219 3137 3151 775 3111 +9220 998 999 190 3754 +9221 2040 3339 2039 3649 +9222 2345 2553 3279 3461 +9223 224 3708 1360 3729 +9224 236 3291 1293 3294 +9225 2685 3562 3511 3680 +9226 3661 3696 1010 3697 +9227 3197 1230 3452 3675 +9228 841 817 309 3408 +9229 3489 380 3724 3725 +9230 3034 2183 3071 2114 +9231 894 774 3180 3160 +9232 3089 2221 3050 3028 +9233 2188 2145 2171 3311 +9234 1307 3414 1099 3461 +9235 234 3362 1329 3744 +9236 2713 3191 2708 3345 +9237 1563 1573 3322 3324 +9238 3598 3601 968 3613 +9239 2173 2197 330 3638 +9240 219 1376 220 3712 +9241 3075 3046 2218 3023 +9242 2208 2119 338 2154 +9243 2893 3223 2706 3502 +9244 1531 3516 3221 3541 +9245 3125 776 3110 849 +9246 3169 420 905 3136 +9247 2660 2968 3448 3678 +9248 3360 1134 3749 3751 +9249 1531 1495 1538 3221 +9250 3156 908 786 3117 +9251 1971 3522 3401 3558 +9252 2632 3376 3254 3441 +9253 977 975 978 3736 +9254 378 377 3485 3761 +9255 1014 1211 3676 3706 +9256 3037 2258 2158 2227 +9257 1837 3212 3349 3354 +9258 220 1260 219 3711 +9259 1658 3258 1800 3565 +9260 2914 3339 2972 3699 +9261 2245 334 3347 3753 +9262 964 965 963 3721 +9263 2786 2785 2784 3222 +9264 221 3427 3605 3748 +9265 3427 3619 385 3748 +9266 1711 3304 3228 3430 +9267 2733 3192 2662 3238 +9268 3117 821 3154 3130 +9269 1644 3309 916 3340 +9270 3090 3057 2155 2288 +9271 802 3123 871 902 +9272 2260 3050 3078 3035 +9273 2273 3094 2289 3065 +9274 2196 455 2216 3628 +9275 1552 3353 1550 3404 +9276 2338 2476 3234 3406 +9277 1272 3379 1047 3781 +9278 370 3301 3274 3367 +9279 917 867 804 3139 +9280 453 3621 2169 3762 +9281 2501 389 3367 3713 +9282 1717 2072 1726 3220 +9283 1805 3300 1450 3506 +9284 2220 2154 339 3751 +9285 2204 2185 336 2136 +9286 317 3574 318 3678 +9287 1715 1777 1742 3503 +9288 2317 3643 3257 3769 +9289 824 3472 878 3731 +9290 246 3500 3498 3746 +9291 1105 3667 3622 3734 +9292 3303 3397 2892 3600 +9293 850 3106 754 3126 +9294 846 759 3171 865 +9295 3580 3585 986 3681 +9296 1616 2197 1613 3638 +9297 2782 3251 412 3419 +9298 2463 3260 2322 3539 +9299 1471 3516 3426 3741 +9300 791 833 879 3153 +9301 1740 3189 1739 3208 +9302 1531 3221 1538 3541 +9303 771 3533 820 3535 +9304 1293 3313 1120 3670 +9305 1906 3476 3434 3662 +9306 2673 3444 2671 3635 +9307 2844 3335 2698 3728 +9308 2250 3048 3023 3096 +9309 874 782 420 3258 +9310 2521 2520 3278 3676 +9311 3048 3023 2110 2250 +9312 2283 457 3086 3052 +9313 281 3508 3544 3546 +9314 336 335 2238 3050 +9315 929 830 3186 768 +9316 897 763 852 3161 +9317 992 3466 193 3592 +9318 3304 1707 3431 3730 +9319 3078 2164 2238 2260 +9320 3106 3187 3131 819 +9321 1455 3216 1689 3505 +9322 3122 3169 3135 918 +9323 3134 3118 3144 915 +9324 413 855 890 801 +9325 812 3132 3160 924 +9326 2748 3390 3389 3403 +9327 194 3466 1256 3580 +9328 3191 3220 1726 3465 +9329 1181 3608 3307 3646 +9330 2129 2239 2194 3627 +9331 765 901 896 426 +9332 3130 821 3154 853 +9333 1847 3336 3223 3624 +9334 2221 2115 3050 3028 +9335 2434 2389 2326 3473 +9336 2820 3412 2871 3521 +9337 1188 2220 3627 3751 +9338 1955 2011 3453 3462 +9339 2975 3318 2939 3531 +9340 2224 3102 2122 453 +9341 164 165 3573 3754 +9342 2763 3426 3255 3508 +9343 2172 332 333 2284 +9344 2208 339 3041 2165 +9345 2388 2334 2455 3779 +9346 2162 3237 452 3762 +9347 871 3156 3174 830 +9348 2343 2379 2528 3283 +9349 28 870 370 3301 +9350 3489 3491 381 3709 +9351 2786 460 2771 3589 +9352 2038 3431 3364 3538 +9353 1659 3537 3565 3641 +9354 3156 3108 3174 830 +9355 3328 3331 1953 3610 +9356 3156 3186 3108 830 +9357 926 1579 1407 3408 +9358 3121 768 3186 3138 +9359 3047 3034 3071 2114 +9360 2179 340 2129 3100 +9361 363 852 773 798 +9362 2557 2571 3523 3599 +9363 1131 3348 1017 3674 +9364 2439 3414 2302 3461 +9365 3673 3675 1043 3695 +9366 775 851 3172 3111 +9367 2425 2482 2337 3579 +9368 1053 1110 1200 3302 +9369 1478 3249 3331 3386 +9370 2174 3077 2175 2124 +9371 2218 3068 2243 2110 +9372 779 868 422 3309 +9373 1243 1026 3510 3626 +9374 2579 3214 2775 3222 +9375 1793 3519 1792 3727 +9376 3296 3366 2459 3605 +9377 2189 3025 3073 3091 +9378 391 3247 2575 3370 +9379 3171 846 865 788 +9380 3180 3122 3135 774 +9381 26 390 2118 2251 +9382 2129 2165 2236 3100 +9383 426 3142 765 3165 +9384 765 804 867 3165 +9385 1717 3191 1718 3345 +9386 932 3150 910 799 +9387 2003 3530 3475 3611 +9388 1725 1724 3191 3245 +9389 995 990 166 3570 +9390 2876 2988 3428 3561 +9391 893 818 757 3184 +9392 3126 3170 837 3160 +9393 3187 3168 3131 819 +9394 2733 3495 3238 3659 +9395 894 3162 3179 3126 +9396 3036 3087 2175 2243 +9397 868 422 421 3135 +9398 1629 3431 1707 3730 +9399 2918 2862 3211 3271 +9400 2281 1277 2181 3313 +9401 825 1280 925 3274 +9402 266 1533 3262 3657 +9403 243 1326 1317 3683 +9404 3133 851 3118 3161 +9405 3035 3051 2164 2248 +9406 2047 3386 3331 3521 +9407 3570 3573 166 3754 +9408 2520 2350 3278 3614 +9409 1912 1913 3412 3521 +9410 1619 3737 3198 3738 +9411 755 3152 3174 3115 +9412 2132 3079 2242 2166 +9413 1186 864 1093 3566 +9414 3092 459 3045 2209 +9415 1120 1293 3290 3313 +9416 1340 1341 3642 3702 +9417 1196 1047 1084 3379 +9418 3110 757 818 3184 +9419 2254 3062 2224 452 +9420 1418 3277 1892 3529 +9421 2499 2339 3507 3693 +9422 1466 1464 3419 3421 +9423 390 2251 26 3202 +9424 2696 3277 2700 3346 +9425 2820 3412 3504 3671 +9426 2735 2662 3192 3238 +9427 2096 3247 329 3370 +9428 1620 1622 1641 3351 +9429 1725 1724 3245 3387 +9430 336 2185 2204 3347 +9431 339 3432 3360 3751 +9432 1969 3647 1812 3649 +9433 1899 3476 1906 3662 +9434 1684 1686 2061 3470 +9435 3166 412 3147 764 +9436 1166 3623 1270 3640 +9437 414 3154 413 890 +9438 1519 1847 3223 3540 +9439 2231 3034 3101 2114 +9440 2102 3523 2090 3577 +9441 3197 3225 2534 3473 +9442 2615 3190 2757 3219 +9443 459 458 2146 2190 +9444 776 886 807 3164 +9445 3102 3066 2274 2230 +9446 2775 3214 3205 3747 +9447 259 3545 260 3744 +9448 3067 2118 390 2156 +9449 2618 3207 3201 3458 +9450 1242 1012 3382 3477 +9451 3322 3454 2799 3680 +9452 322 321 3523 3524 +9453 2328 3204 3197 3608 +9454 826 781 889 3456 +9455 2073 3371 3243 3772 +9456 867 841 796 3408 +9457 1751 2019 3218 3531 +9458 2957 2818 3375 3453 +9459 1256 3509 1209 3580 +9460 3288 3319 2601 3563 +9461 2223 2152 2197 3638 +9462 1347 228 1353 3761 +9463 1059 1143 3234 3560 +9464 376 3314 3702 3732 +9465 2146 458 459 3586 +9466 372 2546 3294 3362 +9467 3104 2193 3085 3048 +9468 764 413 890 3251 +9469 3619 3707 1366 3759 +9470 2501 3549 2461 3711 +9471 1962 2013 1917 3444 +9472 3179 3106 850 3126 +9473 25 371 3291 3543 +9474 1519 1847 3540 3624 +9475 3322 3470 2802 3512 +9476 2579 3221 3214 3222 +9477 1900 1596 3407 3446 +9478 948 2217 2244 3229 +9479 3420 3433 2948 3434 +9480 188 959 187 3692 +9481 2378 3660 2511 3696 +9482 2644 437 436 3620 +9483 839 917 30 772 +9484 3051 2192 2248 3061 +9485 2957 2954 2950 3462 +9486 457 2127 2214 3604 +9487 3661 3697 1010 3763 +9488 3082 2258 2120 2158 +9489 2701 2840 3413 3738 +9490 234 235 3362 3669 +9491 3023 3043 2206 3096 +9492 3507 3693 2339 3694 +9493 2128 29 2195 2273 +9494 2750 3217 2921 3526 +9495 2491 3267 3203 3332 +9496 2501 3711 389 3713 +9497 2143 2255 3229 3284 +9498 367 882 3157 3143 +9499 1725 3191 3353 3387 +9500 2618 3201 3338 3458 +9501 2492 2377 3666 3667 +9502 3171 846 788 3129 +9503 2787 425 2789 3299 +9504 3069 2271 3098 3041 +9505 953 186 3402 3507 +9506 1780 3326 1758 3700 +9507 998 190 3651 3754 +9508 382 3709 3708 3729 +9509 1676 3458 3207 3460 +9510 1291 3224 1161 3507 +9511 1410 1408 3205 3363 +9512 2484 3323 2335 3372 +9513 3244 3460 414 3663 +9514 1971 2050 2055 3558 +9515 1168 1078 1254 3230 +9516 1269 3584 3230 3619 +9517 1199 1274 1064 3197 +9518 3117 893 821 3130 +9519 2990 3329 3664 3679 +9520 334 335 2245 3347 +9521 2120 462 3082 2222 +9522 2214 3604 2176 3628 +9523 903 411 3148 866 +9524 2258 3059 2142 3070 +9525 3124 892 836 3152 +9526 3292 3409 2646 3443 +9527 1151 3472 1207 3731 +9528 2170 3042 2274 3102 +9529 3049 3024 2264 3070 +9530 3159 833 879 756 +9531 866 770 411 835 +9532 3203 3302 1110 3693 +9533 3065 2160 2273 2223 +9534 2678 2680 2896 3359 +9535 2960 2975 3218 3405 +9536 1851 1598 3446 3637 +9537 2148 2271 2253 3041 +9538 3047 3071 2200 2114 +9539 756 880 3114 915 +9540 2045 3400 3349 3512 +9541 3062 2254 451 452 +9542 1760 3254 2057 3616 +9543 2735 3192 2663 3436 +9544 2245 2137 2182 3347 +9545 933 3114 3173 3139 +9546 2476 3406 2338 3661 +9547 1099 3414 1104 3583 +9548 970 973 199 3613 +9549 2061 1648 1684 3512 +9550 2244 2217 2143 3229 +9551 2284 333 2172 2123 +9552 923 3116 3132 3153 +9553 2271 2253 3041 2165 +9554 1842 3318 2009 3478 +9555 1780 1758 2030 3700 +9556 1113 1065 3579 3778 +9557 3182 788 887 3129 +9558 808 767 368 3146 +9559 3144 3159 3114 756 +9560 1431 3223 1459 3503 +9561 1993 1994 3261 3610 +9562 2222 463 3056 2259 +9563 461 2246 2177 460 +9564 2660 3285 2968 3678 +9565 2349 2459 3296 3366 +9566 1419 3389 3201 3529 +9567 1668 1973 1644 3340 +9568 3059 2142 2177 2258 +9569 2072 1726 3220 3465 +9570 372 3362 3294 3669 +9571 1446 1547 921 3251 +9572 1893 3277 1420 3338 +9573 791 3120 3142 3153 +9574 1602 1763 3447 3448 +9575 2243 3036 3087 3068 +9576 2895 2677 3426 3775 +9577 2372 3687 3510 3781 +9578 3234 3406 2476 3661 +9579 3130 3154 414 853 +9580 2875 3431 2831 3710 +9581 3081 2130 3042 2167 +9582 1157 3204 3307 3608 +9583 1067 1217 1210 3698 +9584 3061 2111 2248 2186 +9585 2189 3073 2147 2235 +9586 2120 3059 2258 3082 +9587 1407 1405 3195 3408 +9588 2263 332 2284 3313 +9589 917 933 800 3173 +9590 775 851 863 3172 +9591 1171 1098 3750 3757 +9592 1884 3426 1821 3508 +9593 1512 3396 1825 3425 +9594 1993 3261 1994 3612 +9595 2115 2221 2202 3028 +9596 3056 463 2222 2158 +9597 808 3157 3188 3124 +9598 2669 3304 3228 3431 +9599 3084 2266 3057 2172 +9600 3040 3073 2147 3064 +9601 2249 3072 3080 3033 +9602 459 3092 2190 2209 +9603 1719 3210 3345 3728 +9604 821 414 3154 853 +9605 944 3368 953 3765 +9606 425 765 896 426 +9607 1112 3316 1019 3698 +9608 1069 3605 3427 3665 +9609 2618 3338 2619 3458 +9610 3060 3105 2207 3074 +9611 883 362 773 838 +9612 2219 3038 2178 2125 +9613 996 164 3578 3754 +9614 2257 3240 448 3518 +9615 2188 2240 2145 3311 +9616 2832 2609 421 3258 +9617 3223 3540 2585 3690 +9618 2598 3288 2601 3563 +9619 2761 3535 3458 3536 +9620 2468 3457 3224 3507 +9621 3184 893 818 3138 +9622 2094 2096 328 3370 +9623 2246 2177 460 2133 +9624 1565 3376 1572 3454 +9625 1193 1150 3456 3630 +9626 2132 2206 3079 2166 +9627 402 3574 3569 3678 +9628 385 3619 3746 3748 +9629 1429 3319 1738 3589 +9630 2881 3441 2631 3775 +9631 3086 2214 457 2283 +9632 1875 3280 1788 3465 +9633 1563 1572 1573 3324 +9634 1834 1478 1678 3196 +9635 3206 3353 2906 3404 +9636 1180 3579 3445 3778 +9637 2910 3331 2912 3521 +9638 1781 1700 2083 3561 +9639 2826 2810 3282 3671 +9640 1340 3642 3593 3702 +9641 1858 1875 3220 3280 +9642 1441 3383 1443 3518 +9643 247 3496 3707 3746 +9644 2763 3255 3480 3508 +9645 3059 2142 3033 2177 +9646 1714 3315 1809 3515 +9647 3035 2164 2260 2140 +9648 808 368 889 3157 +9649 1718 3191 3245 3345 +9650 1823 3470 3392 3511 +9651 364 763 852 798 +9652 2657 2805 2884 3519 +9653 3254 3376 1627 3441 +9654 2691 3331 3249 3386 +9655 220 3714 1376 3748 +9656 3068 2144 3028 3046 +9657 908 3186 830 768 +9658 846 788 3129 862 +9659 3042 2130 3027 2170 +9660 786 821 902 3117 +9661 389 3683 3367 3713 +9662 1577 3411 3409 3774 +9663 1141 3279 1030 3583 +9664 1305 3377 3687 3688 +9665 267 3223 268 3654 +9666 333 3348 334 3753 +9667 2006 3436 3652 3742 +9668 2982 2981 3371 3700 +9669 2916 3315 2956 3476 +9670 1390 3311 261 3543 +9671 865 759 3143 904 +9672 1963 3633 2013 3635 +9673 31 3148 3177 903 +9674 3253 3254 2654 3376 +9675 1841 885 1677 3460 +9676 339 3041 3074 2208 +9677 771 417 858 3533 +9678 460 2133 3588 3589 +9679 1821 3426 1471 3516 +9680 2111 3076 2227 2186 +9681 3511 3562 1635 3680 +9682 3272 3586 458 3604 +9683 1458 1429 1456 3747 +9684 2127 458 457 2283 +9685 1326 1317 3683 3713 +9686 2616 3189 2857 3208 +9687 2539 2297 2386 3278 +9688 2461 3549 3296 3711 +9689 2597 2596 2765 3609 +9690 3235 3581 2829 3621 +9691 1107 3510 1246 3781 +9692 2165 2208 339 2129 +9693 3213 3246 242 3683 +9694 2761 3458 3338 3536 +9695 995 3570 166 3754 +9696 1742 3357 3238 3659 +9697 3145 3185 3125 927 +9698 2426 3269 2378 3696 +9699 2150 3290 332 3313 +9700 1705 3303 3365 3730 +9701 462 2222 2262 3205 +9702 874 766 813 3258 +9703 2602 2752 3212 3272 +9704 1253 3333 1125 3435 +9705 3199 3269 2536 3697 +9706 450 2183 3071 449 +9707 2329 3750 3749 3757 +9708 3378 3381 1170 3414 +9709 1947 3318 2019 3531 +9710 1451 3505 3275 3764 +9711 1387 3469 3295 3543 +9712 3335 3344 2068 3346 +9713 834 3130 415 853 +9714 425 3142 765 426 +9715 452 2135 451 3237 +9716 1631 1711 3304 3431 +9717 202 962 201 3721 +9718 2835 3194 2832 3565 +9719 3246 3658 242 3683 +9720 3087 2175 3077 3036 +9721 2551 3579 2311 3778 +9722 424 425 778 3373 +9723 1363 3708 3493 3709 +9724 1018 3567 3377 3688 +9725 449 2252 2183 2121 +9726 3516 3541 281 3544 +9727 225 224 1360 3729 +9728 3149 886 760 3112 +9729 1048 1126 1281 3510 +9730 3455 1635 3562 3680 +9731 1986 3364 3256 3538 +9732 2110 2218 3068 3023 +9733 757 3130 3145 834 +9734 3168 768 818 819 +9735 1851 1598 3429 3446 +9736 2922 3217 2647 3443 +9737 769 935 833 3107 +9738 1106 3614 3306 3676 +9739 1204 2237 3347 3753 +9740 2248 3035 3051 3061 +9741 3303 3365 2890 3397 +9742 1601 3243 2082 3250 +9743 3217 3263 1880 3526 +9744 2121 2183 449 3064 +9745 2537 2393 3342 3627 +9746 784 892 3124 3181 +9747 3030 2219 2131 2207 +9748 2576 3516 3221 3741 +9749 1912 3504 1681 3521 +9750 1437 1436 1439 3392 +9751 2702 3349 3198 3400 +9752 2240 25 464 2117 +9753 2167 3053 2116 2261 +9754 1933 1658 1800 3565 +9755 1126 3510 3440 3770 +9756 899 787 895 3200 +9757 2960 2995 2975 3405 +9758 2374 3234 3435 3773 +9759 2338 3234 2494 3406 +9760 1769 3308 3564 3609 +9761 1768 1636 3338 3458 +9762 1067 1210 3450 3666 +9763 1751 3218 2022 3531 +9764 320 3558 319 3576 +9765 3046 3068 2144 2218 +9766 836 3146 3124 3152 +9767 2582 446 445 3657 +9768 1979 3532 3453 3777 +9769 2134 2252 449 3383 +9770 1452 1859 1753 3689 +9771 1960 1968 2011 3320 +9772 456 2214 3086 3053 +9773 3223 1431 3502 3503 +9774 936 3202 179 3358 +9775 2017 1703 2016 3292 +9776 774 894 837 3160 +9777 1016 3203 1227 3566 +9778 2821 3256 2823 3538 +9779 1469 3286 3281 3341 +9780 1244 3234 3418 3773 +9781 2710 2708 2713 3191 +9782 3305 3623 2304 3686 +9783 1121 3224 838 3457 +9784 3228 3304 2669 3430 +9785 2538 3290 25 3291 +9786 2120 461 462 3590 +9787 2151 2191 3205 3363 +9788 2654 3253 2652 3254 +9789 1390 1387 3295 3543 +9790 2264 3024 2186 3070 +9791 2262 2120 462 3590 +9792 3063 2271 3041 2165 +9793 2919 3664 3530 3679 +9794 3225 3473 1184 3528 +9795 2536 2437 3199 3697 +9796 3198 3349 1838 3400 +9797 2845 2897 3471 3682 +9798 800 410 3140 762 +9799 1187 854 3274 3550 +9800 3076 2227 2186 3070 +9801 1514 3495 3327 3615 +9802 3236 3260 2419 3268 +9803 1230 1052 1109 3197 +9804 1763 3209 3285 3678 +9805 3105 3041 2253 3074 +9806 2782 3419 3421 3663 +9807 261 1349 1325 3543 +9808 3157 882 808 904 +9809 1481 3189 1653 3607 +9810 3194 3210 1933 3565 +9811 818 908 768 3138 +9812 3081 3029 2166 2167 +9813 3196 3249 1678 3386 +9814 3103 2279 3073 3055 +9815 987 3592 3572 3718 +9816 1857 1670 1866 3310 +9817 2759 3277 2697 3334 +9818 779 916 3309 3340 +9819 3650 2479 3716 3755 +9820 456 457 2214 3628 +9821 1662 3255 1560 3426 +9822 2860 3243 3242 3405 +9823 3554 3564 408 3609 +9824 3223 3501 2706 3502 +9825 3061 3076 2186 3024 +9826 1257 3279 225 3725 +9827 1582 1839 1619 3737 +9828 187 1262 188 3402 +9829 324 3594 3397 3596 +9830 1160 1211 3366 3676 +9831 1253 1108 3333 3435 +9832 1878 2051 2017 3292 +9833 1423 1425 3373 3672 +9834 3051 3031 3084 2192 +9835 1006 159 1005 3231 +9836 2055 1919 1728 3343 +9837 2255 2251 2143 3229 +9838 3383 3518 449 3701 +9839 2289 2156 2236 3032 +9840 1957 3341 3281 3453 +9841 2633 3403 2634 3624 +9842 1496 3205 1408 3214 +9843 1410 2256 1578 3363 +9844 2975 2996 2939 3318 +9845 2833 457 456 3628 +9846 2123 2164 3051 2192 +9847 2054 3266 3350 3365 +9848 3456 3517 1056 3704 +9849 2073 3243 3447 3772 +9850 3067 2156 3094 3032 +9851 970 3613 199 3722 +9852 1459 3223 1847 3336 +9853 2054 3350 3351 3365 +9854 2468 361 3224 3457 +9855 1160 1022 3278 3665 +9856 1876 3272 1691 3604 +9857 2532 3456 367 3704 +9858 1876 2187 3586 3604 +9859 3077 2132 3097 3026 +9860 3094 2273 29 3065 +9861 2708 3345 3210 3728 +9862 1666 3536 3533 3641 +9863 880 3134 3114 915 +9864 420 3258 782 3537 +9865 2274 2170 3102 2224 +9866 2311 3579 3332 3778 +9867 2175 3077 3043 3087 +9868 802 866 3166 764 +9869 3554 3555 2563 3557 +9870 1545 3265 327 3451 +9871 3069 2271 3063 2236 +9872 948 2217 3229 3284 +9873 3257 3769 1087 3771 +9874 1529 1530 1752 3233 +9875 1167 3193 1215 3372 +9876 3159 3107 833 3144 +9877 754 837 894 3126 +9878 191 3650 3716 3755 +9879 822 863 3137 775 +9880 3428 3515 2877 3561 +9881 1986 1731 1922 3256 +9882 1163 3294 1293 3670 +9883 362 773 3167 823 +9884 2014 3631 2012 3633 +9885 2364 2497 2409 3332 +9886 352 351 3580 3681 +9887 2972 2852 3699 3710 +9888 2949 3395 2873 3471 +9889 2685 3455 3562 3680 +9890 2349 2512 2459 3366 +9891 1269 3230 3427 3619 +9892 1902 3430 3401 3524 +9893 27 410 895 762 +9894 2238 335 3078 3050 +9895 2999 3292 3263 3620 +9896 2003 3475 3548 3611 +9897 2602 3212 2724 3392 +9898 184 1291 185 3200 +9899 2611 3350 2610 3365 +9900 1303 3507 1075 3693 +9901 3102 2224 452 453 +9902 821 3147 902 3117 +9903 1693 1899 1868 3662 +9904 2463 2419 2322 3260 +9905 2769 3275 2680 3505 +9906 3283 3439 1124 3625 +9907 910 3150 3115 799 +9908 991 3718 995 3755 +9909 1968 3320 1969 3647 +9910 396 2892 3397 3600 +9911 2914 3424 3339 3699 +9912 905 874 782 420 +9913 444 3501 3223 3654 +9914 814 3128 3135 3109 +9915 2775 463 3205 3214 +9916 266 3657 3262 3690 +9917 2122 453 2230 2169 +9918 3034 3073 2279 3055 +9919 2818 3271 2861 3375 +9920 2015 1854 1997 3631 +9921 2513 3643 3568 3776 +9922 2421 2477 3673 3695 +9923 814 3128 3109 922 +9924 3205 3214 1496 3747 +9925 3154 414 821 890 +9926 894 3179 850 3126 +9927 3112 3149 886 3164 +9928 813 766 806 3258 +9929 1478 1678 3249 3386 +9930 1714 3315 3515 3606 +9931 27 895 410 3231 +9932 2298 2447 3268 3582 +9933 2192 2164 3051 2248 +9934 1576 3255 3411 3774 +9935 808 3188 784 3124 +9936 3197 3204 2328 3452 +9937 2216 455 2196 3740 +9938 1949 3271 3211 3341 +9939 311 3557 3554 3564 +9940 412 764 906 3251 +9941 1030 3279 1276 3461 +9942 1586 3621 2169 3740 +9943 2382 2508 2312 3626 +9944 968 174 3598 3613 +9945 3234 2476 3660 3661 +9946 2690 3407 2688 3629 +9947 2493 3252 2346 3314 +9948 2264 2186 3024 2124 +9949 905 3169 3136 811 +9950 811 874 3169 918 +9951 2389 3473 3225 3528 +9952 1861 1712 3228 3520 +9953 3110 3130 757 3184 +9954 385 3746 3500 3748 +9955 1788 3280 3423 3465 +9956 2191 2171 285 3363 +9957 1602 1647 1763 3448 +9958 2115 3050 2260 2221 +9959 2107 3202 2173 3247 +9960 801 890 413 3251 +9961 1129 3685 1101 3686 +9962 1902 3401 3522 3524 +9963 2234 2136 337 3432 +9964 1661 3411 3255 3480 +9965 366 3456 3630 3704 +9966 823 762 361 883 +9967 3595 3598 174 3613 +9968 347 346 3384 3613 +9969 2360 3509 3466 3580 +9970 3118 851 3133 3172 +9971 778 3340 424 3373 +9972 2894 3365 3266 3397 +9973 2310 3372 2387 3406 +9974 1675 2069 1932 3277 +9975 2295 2399 2372 3510 +9976 2610 3350 3266 3365 +9977 412 413 3147 764 +9978 2956 3315 2623 3527 +9979 903 770 411 866 +9980 326 3265 1475 3603 +9981 915 880 3134 809 +9982 3180 3162 774 894 +9983 2755 3194 3220 3280 +9984 774 814 3135 3109 +9985 3340 3369 1804 3429 +9986 276 2037 1667 3410 +9987 917 933 3173 3139 +9988 1037 3236 3260 3771 +9989 2994 3297 2938 3634 +9990 1355 1359 3724 3725 +9991 225 3709 1360 3725 +9992 227 1353 228 3724 +9993 254 1350 1351 3726 +9994 3224 3457 1161 3507 +9995 771 834 927 416 +9996 1856 3504 1912 3671 +9997 1718 3245 1720 3345 +9998 2011 3375 1956 3453 +9999 385 3605 3427 3748 +10000 3042 2274 3066 2167 +10001 1625 3416 3417 3426 +10002 1861 1712 3520 3756 +10003 2179 341 340 3100 +10004 2541 3225 2327 3685 +10005 1634 3479 3344 3733 +10006 1290 3284 204 3342 +10007 1823 1683 1985 3349 +10008 1869 1568 3420 3662 +10009 2527 3203 2305 3302 +10010 2040 3424 3339 3649 +10011 2800 3322 2799 3680 +10012 191 3651 3650 3755 +10013 343 3464 3463 3766 +10014 3145 3185 927 416 +10015 2572 3247 3202 3463 +10016 177 2105 176 3464 +10017 2702 3212 2752 3354 +10018 1932 1892 3277 3346 +10019 1118 3356 1297 3539 +10020 1688 3216 3448 3705 +10021 1604 1462 1605 3403 +10022 775 862 846 3111 +10023 3084 332 333 2172 +10024 1408 3214 3205 3363 +10025 359 3402 3507 3765 +10026 2590 3233 2779 3370 +10027 3033 2142 3059 3070 +10028 2948 3420 3434 3662 +10029 409 30 2777 3408 +10030 1563 3454 3322 3680 +10031 1161 3224 1291 3457 +10032 1820 3198 1819 3738 +10033 221 3427 1300 3605 +10034 1990 1987 2067 3385 +10035 1318 3683 1317 3713 +10036 3200 3231 27 3368 +10037 1134 3360 1057 3751 +10038 3422 3629 1900 3727 +10039 2115 336 2238 3050 +10040 834 3145 927 416 +10041 1058 1195 3278 3614 +10042 456 2216 455 3628 +10043 1280 3301 1292 3367 +10044 228 1252 227 3450 +10045 1378 3213 1316 3683 +10046 3283 1124 3528 3625 +10047 431 430 2578 3544 +10048 1811 2040 2039 3649 +10049 1608 3397 3303 3600 +10050 2668 3303 2737 3430 +10051 232 3702 3593 3745 +10052 1428 1738 1574 3591 +10053 2835 2842 3210 3565 +10054 247 3498 3496 3746 +10055 2064 3521 3328 3648 +10056 3068 2243 2144 2218 +10057 3149 807 886 3164 +10058 1356 3724 3487 3726 +10059 2607 3429 3289 3446 +10060 1879 3217 1880 3526 +10061 3154 3147 821 3117 +10062 2135 451 3237 3587 +10063 1506 1507 1505 3327 +10064 1120 3290 1277 3313 +10065 2283 458 457 3052 +10066 1047 1243 1107 3781 +10067 851 775 805 3111 +10068 2856 3228 3401 3756 +10069 1557 1695 3206 3519 +10070 1116 1046 3296 3366 +10071 1663 3537 1659 3641 +10072 791 3116 923 3153 +10073 1305 1202 3377 3688 +10074 809 773 880 3167 +10075 3252 3314 2493 3732 +10076 1875 1788 1873 3465 +10077 2107 2173 330 3247 +10078 1756 3243 2073 3371 +10079 1169 3236 1021 3260 +10080 3281 3453 2819 3777 +10081 936 180 3202 3229 +10082 250 1363 3493 3709 +10083 1844 1644 916 3340 +10084 3530 3664 1988 3679 +10085 2867 3420 3232 3433 +10086 3171 846 3129 3111 +10087 1005 3200 943 3368 +10088 1001 3578 3553 3691 +10089 896 425 426 3672 +10090 195 3580 3468 3585 +10091 3164 807 776 3125 +10092 949 888 941 3200 +10093 1610 3232 1786 3618 +10094 1304 3296 1076 3549 +10095 3060 338 3074 2119 +10096 3395 3433 2026 3471 +10097 964 956 176 3721 +10098 3248 3444 1928 3682 +10099 884 832 789 3246 +10100 2150 2181 3290 3313 +10101 1709 3287 1916 3606 +10102 2603 2752 3272 3354 +10103 1254 1058 1195 3278 +10104 1950 3635 3211 3636 +10105 1695 2075 3206 3519 +10106 276 3292 2037 3410 +10107 444 3654 3223 3690 +10108 780 365 366 3731 +10109 2049 3478 2075 3519 +10110 892 3124 3181 3152 +10111 1516 3192 1642 3327 +10112 3097 3043 2132 3077 +10113 1193 3630 3456 3704 +10114 1247 3625 1081 3626 +10115 2236 3063 3069 3032 +10116 825 3274 794 3301 +10117 901 426 3195 3672 +10118 1014 1097 1234 3517 +10119 2621 3479 2967 3527 +10120 368 826 767 889 +10121 978 983 196 3736 +10122 2465 2362 3307 3608 +10123 2738 3430 2737 3524 +10124 3077 2132 3026 2174 +10125 1861 3520 3228 3710 +10126 3086 2283 3052 2163 +10127 1529 3233 1752 3350 +10128 421 420 874 3169 +10129 2595 2638 2726 3689 +10130 1584 1836 3621 3739 +10131 2127 458 2283 2190 +10132 167 3572 3570 3718 +10133 1198 3366 3605 3665 +10134 1341 3653 3642 3732 +10135 2516 2458 2292 3528 +10136 3334 3536 1672 3641 +10137 1118 1297 1071 3539 +10138 1705 3303 1771 3365 +10139 3079 3097 3043 2132 +10140 2478 3539 3355 3752 +10141 2633 2636 3336 3624 +10142 3182 3171 788 3129 +10143 2757 2615 2613 3190 +10144 2186 2227 2142 3070 +10145 1488 1469 3281 3341 +10146 1898 3407 3275 3629 +10147 2170 3062 3102 2224 +10148 3136 3162 3112 810 +10149 3397 3594 395 3596 +10150 2756 2802 3470 3512 +10151 1670 3280 1866 3310 +10152 453 454 2169 3621 +10153 3059 2120 462 3082 +10154 1632 3344 1634 3479 +10155 3066 3081 3042 2167 +10156 754 3106 887 862 +10157 1889 3228 1711 3431 +10158 3135 3180 774 3109 +10159 2344 2534 3225 3473 +10160 2126 2171 2191 3363 +10161 1387 3542 3469 3543 +10162 1405 3215 3195 3408 +10163 324 3397 1608 3600 +10164 2516 3528 2292 3625 +10165 1200 3203 3267 3332 +10166 3197 3204 1064 3608 +10167 1136 3378 1307 3461 +10168 2222 463 2259 2126 +10169 944 186 953 3507 +10170 798 363 364 3472 +10171 2723 3212 2702 3349 +10172 1719 3210 1717 3345 +10173 1160 3278 3366 3665 +10174 3191 2944 3353 3387 +10175 2459 3366 2512 3605 +10176 2424 3769 3257 3771 +10177 338 3060 2234 2119 +10178 2278 3027 2170 3062 +10179 2504 3379 2446 3781 +10180 1990 3636 1802 3679 +10181 369 368 767 3146 +10182 771 858 820 3533 +10183 3133 851 805 3111 +10184 3029 2166 3096 3081 +10185 759 882 3143 904 +10186 3257 3643 1087 3769 +10187 2073 2082 1601 3243 +10188 1795 1989 1796 3679 +10189 3650 3651 2479 3755 +10190 3434 3476 2967 3662 +10191 1677 1637 3458 3535 +10192 1301 3362 3294 3673 +10193 1478 3196 1834 3249 +10194 2665 2889 3393 3425 +10195 2222 3056 2158 2259 +10196 27 3368 3231 3556 +10197 2688 3422 3407 3446 +10198 2898 2845 3471 3652 +10199 235 3294 1301 3362 +10200 834 415 3145 416 +10201 2576 3221 2581 3741 +10202 1626 1627 3376 3441 +10203 1632 3346 3344 3479 +10204 817 2106 309 3298 +10205 1085 1062 3582 3752 +10206 2465 3204 2328 3608 +10207 2003 2002 3475 3530 +10208 2188 2259 32 2126 +10209 2179 2129 2236 3100 +10210 1620 3364 1706 3730 +10211 1106 1063 3614 3676 +10212 1837 1838 3198 3349 +10213 192 193 992 3716 +10214 3069 2271 3041 3063 +10215 3229 3284 26 3358 +10216 2877 3428 3315 3515 +10217 3378 3380 1042 3381 +10218 2205 3052 2163 3097 +10219 832 770 31 903 +10220 3177 3115 3150 799 +10221 3105 2207 3030 3060 +10222 2855 2992 3000 3343 +10223 3135 868 814 918 +10224 1948 3341 3211 3715 +10225 2168 2280 2193 3085 +10226 2383 3605 2507 3665 +10227 2186 2142 2264 3070 +10228 2950 3462 3320 3768 +10229 3150 3115 3183 910 +10230 1722 1721 3387 3733 +10231 1229 3360 1134 3749 +10232 2996 2939 3318 3459 +10233 3029 3053 2116 2167 +10234 1291 3200 184 3224 +10235 3171 3143 759 3127 +10236 1678 3196 1478 3249 +10237 1944 3515 1808 3777 +10238 3131 3106 819 850 +10239 1207 3472 824 3731 +10240 2208 338 339 2154 +10241 1927 1928 3444 3682 +10242 2164 3078 3051 3035 +10243 2191 2256 3205 3363 +10244 2338 2476 2494 3234 +10245 2895 3417 3416 3426 +10246 2285 3024 2186 2124 +10247 339 3360 2456 3751 +10248 3074 2253 2207 2119 +10249 2655 3409 3441 3443 +10250 817 3231 2106 3298 +10251 3151 862 775 3111 +10252 827 778 424 425 +10253 1998 3395 2026 3471 +10254 1463 1432 3455 3562 +10255 933 800 3114 880 +10256 341 2239 340 3627 +10257 3071 2200 450 3047 +10258 3321 3322 2902 3512 +10259 2585 2705 2586 3624 +10260 232 3361 3702 3745 +10261 2637 3282 2639 3325 +10262 862 3129 846 3111 +10263 1488 3341 1948 3715 +10264 2263 2150 332 3313 +10265 3130 893 757 3184 +10266 2214 456 2216 2116 +10267 1485 3562 1508 3563 +10268 1362 251 1359 3709 +10269 2469 2401 2299 3452 +10270 1348 1351 1350 3726 +10271 2222 2126 2191 3363 +10272 2882 3324 3321 3385 +10273 1102 3770 1266 3771 +10274 3388 3675 2413 3695 +10275 2657 3242 2658 3415 +10276 3080 3049 2249 3033 +10277 2360 3466 352 3580 +10278 1011 3293 1266 3770 +10279 1098 3360 1229 3749 +10280 3031 2111 3061 3076 +10281 359 3692 3402 3765 +10282 1325 3291 1320 3669 +10283 1762 3254 3253 3376 +10284 3151 862 822 775 +10285 2266 2155 3057 2288 +10286 464 3295 3019 3311 +10287 1102 3769 3770 3771 +10288 1736 1462 3391 3393 +10289 3080 2113 3072 2249 +10290 2273 2128 29 2223 +10291 2369 2314 2427 3676 +10292 1113 3332 1065 3778 +10293 1164 1290 3342 3627 +10294 3392 3470 2721 3511 +10295 1061 3305 3225 3685 +10296 1920 3343 1936 3772 +10297 2683 2690 3275 3407 +10298 2202 2218 2131 3088 +10299 2405 3688 3568 3770 +10300 2177 3072 461 460 +10301 2236 2271 3063 2165 +10302 2082 3243 1599 3250 +10303 3238 3357 2732 3659 +10304 2169 3621 1586 3762 +10305 3106 3131 3179 850 +10306 2698 3334 2696 3335 +10307 231 3702 3314 3732 +10308 976 205 1004 3284 +10309 757 3130 834 853 +10310 1736 1462 1894 3391 +10311 1030 3461 1099 3583 +10312 3039 3086 3052 2163 +10313 358 3555 3552 3692 +10314 2250 3096 2166 3081 +10315 1777 1825 1742 3238 +10316 3042 2170 3062 3102 +10317 3547 3593 1343 3642 +10318 3151 3106 754 862 +10319 2600 2581 2599 3288 +10320 3055 2168 3101 3027 +10321 2860 3242 2656 3405 +10322 25 3311 3291 3513 +10323 1265 1106 1063 3614 +10324 1379 3301 1378 3683 +10325 1016 1227 1132 3566 +10326 1552 3387 3353 3404 +10327 1620 3256 1731 3364 +10328 2452 3260 3236 3771 +10329 2252 3383 2203 3518 +10330 1995 1953 3331 3610 +10331 2659 3514 3442 3616 +10332 1626 3376 1628 3775 +10333 1326 1318 1317 3713 +10334 2476 2374 3234 3660 +10335 376 375 3642 3702 +10336 3140 410 800 3173 +10337 2140 3035 2164 2248 +10338 406 3551 3506 3639 +10339 3426 3508 2762 3516 +10340 2153 3284 1119 3627 +10341 1505 1514 3327 3615 +10342 2246 2120 3059 2177 +10343 2702 2703 3349 3400 +10344 902 3147 821 764 +10345 3307 3608 2362 3646 +10346 2176 2214 2127 3604 +10347 2741 3303 2668 3304 +10348 1786 3232 3617 3618 +10349 1045 1110 3302 3693 +10350 810 3162 3179 894 +10351 3231 3298 2573 3556 +10352 396 3397 395 3596 +10353 2887 3286 3281 3515 +10354 918 814 3135 774 +10355 1569 3434 3420 3662 +10356 1187 1094 854 3550 +10357 2299 2413 3388 3675 +10358 1689 1455 1687 3216 +10359 818 3110 3184 3138 +10360 1453 1540 1454 3689 +10361 1307 3378 1170 3414 +10362 2986 3387 3264 3404 +10363 2731 2772 2608 3310 +10364 2245 335 334 3078 +10365 3071 2183 2200 2114 +10366 1646 3209 1763 3678 +10367 3505 3506 2765 3609 +10368 1885 3261 3249 3413 +10369 2095 3202 3247 3463 +10370 1036 1089 3252 3622 +10371 3189 3226 2899 3607 +10372 3121 887 768 819 +10373 3150 761 28 465 +10374 28 370 761 3150 +10375 830 871 3156 786 +10376 2457 3204 335 3348 +10377 3273 3471 2897 3682 +10378 1089 3337 3252 3622 +10379 1734 3470 3511 3680 +10380 234 1323 235 3669 +10381 2512 2507 2383 3605 +10382 2519 2335 2438 3650 +10383 1994 3331 3261 3610 +10384 1246 3687 1135 3781 +10385 1160 1265 1063 3676 +10386 3074 2207 3060 2119 +10387 1950 3211 1796 3636 +10388 1097 3445 1025 3704 +10389 2168 3101 3027 2278 +10390 2668 2669 3304 3430 +10391 1141 3279 3583 3729 +10392 1722 3387 3264 3733 +10393 3019 3295 3022 3543 +10394 1959 1961 3462 3532 +10395 1360 3709 1357 3725 +10396 2371 3461 3316 3698 +10397 2131 2218 3046 3088 +10398 2346 2544 3314 3623 +10399 321 2091 322 3523 +10400 1143 1185 1053 3560 +10401 2368 3582 2486 3757 +10402 1172 1021 3268 3539 +10403 1714 1809 1710 3515 +10404 3383 449 3607 3701 +10405 2792 3201 3389 3529 +10406 2132 2205 3097 3026 +10407 3274 3367 1039 3549 +10408 2251 2195 2149 3202 +10409 2611 2638 3350 3351 +10410 3254 3441 1627 3442 +10411 972 971 974 3601 +10412 3153 3132 923 3107 +10413 1673 3277 1893 3338 +10414 2234 2180 2136 3432 +10415 2337 3445 2454 3704 +10416 1895 3390 1923 3391 +10417 2490 2542 379 3450 +10418 898 423 3128 844 +10419 1374 1375 246 3714 +10420 1938 3297 1937 3634 +10421 3099 2131 3088 3030 +10422 3056 32 3090 2259 +10423 1405 3195 3215 3743 +10424 2968 3285 3209 3678 +10425 3523 3577 2102 3735 +10426 173 968 3598 3601 +10427 2020 1757 1961 3768 +10428 1452 3689 1454 3701 +10429 889 767 368 808 +10430 3066 3102 453 2230 +10431 924 812 3132 769 +10432 1462 3336 1460 3624 +10433 1329 3744 3362 3745 +10434 2239 340 2129 2179 +10435 2299 3452 2401 3675 +10436 908 830 3156 786 +10437 2146 3586 459 3588 +10438 250 3493 3491 3709 +10439 3164 3179 776 810 +10440 3360 3646 2329 3757 +10441 1225 1040 3627 3751 +10442 1116 1046 1260 3296 +10443 460 2177 2209 2133 +10444 1601 2082 1599 3250 +10445 850 776 3179 810 +10446 2387 3406 3372 3661 +10447 3242 3250 2883 3415 +10448 195 3468 983 3585 +10449 2732 3238 2886 3357 +10450 1957 1979 3453 3777 +10451 3125 807 776 849 +10452 1136 3316 1182 3378 +10453 1569 3232 3420 3433 +10454 3484 3642 255 3653 +10455 1295 1085 3582 3750 +10456 2688 3629 3422 3727 +10457 3737 3739 1609 3740 +10458 2502 3267 2491 3332 +10459 1487 1467 3286 3515 +10460 3323 2381 3650 3651 +10461 2999 2644 3292 3620 +10462 460 2133 2209 3588 +10463 1295 3750 3582 3757 +10464 3391 3393 2817 3394 +10465 1688 1806 1411 3216 +10466 2218 3099 2178 2131 +10467 332 3057 2117 2288 +10468 3148 903 866 802 +10469 2601 3319 2771 3563 +10470 1719 1717 1718 3345 +10471 2283 3086 2214 2163 +10472 2383 3427 3605 3665 +10473 2151 2262 2222 3205 +10474 1624 1738 3319 3563 +10475 1629 3364 3431 3730 +10476 1901 1571 1772 3600 +10477 2928 3344 3479 3733 +10478 1481 3226 3189 3607 +10479 451 2899 3226 3607 +10480 1326 3656 244 3712 +10481 244 3656 3655 3712 +10482 3127 805 846 3111 +10483 1033 3625 1101 3685 +10484 841 867 772 3408 +10485 2128 2223 2197 3638 +10486 452 2162 2224 3237 +10487 2581 3221 2599 3288 +10488 188 1003 959 3691 +10489 2557 2571 398 3523 +10490 1572 1565 1762 3376 +10491 3191 3245 2944 3387 +10492 2726 3325 3312 3701 +10493 3043 2132 3077 2175 +10494 1768 3338 1636 3536 +10495 2674 401 402 3574 +10496 1625 1708 3416 3775 +10497 2797 3374 3208 3504 +10498 2014 1966 3632 3633 +10499 1268 3650 1146 3651 +10500 961 3692 3555 3765 +10501 1797 3235 3219 3621 +10502 1004 3229 939 3358 +10503 2788 2787 2789 3299 +10504 366 848 759 934 +10505 199 3384 1238 3722 +10506 1411 3216 1806 3300 +10507 252 3487 1356 3724 +10508 2370 2523 2431 3477 +10509 2026 1998 2025 3395 +10510 2896 2680 2769 3275 +10511 2115 3044 3050 3028 +10512 859 3195 1406 3672 +10513 1249 3306 1051 3445 +10514 2958 3273 3248 3434 +10515 1103 1086 1034 3650 +10516 793 839 895 3231 +10517 366 848 934 780 +10518 1810 3424 2040 3649 +10519 2239 341 340 2179 +10520 1944 3281 3515 3777 +10521 2554 391 2575 3370 +10522 918 3122 811 774 +10523 3142 3116 827 791 +10524 422 868 806 3309 +10525 2587 3564 3308 3609 +10526 1842 2009 1829 3478 +10527 2577 2580 3221 3541 +10528 423 779 3309 3340 +10529 1882 3304 1711 3430 +10530 2337 2454 2425 3704 +10531 337 338 3060 2234 +10532 2647 3217 2646 3443 +10533 3173 30 917 3139 +10534 1560 3426 3255 3775 +10535 2365 3381 3378 3414 +10536 2548 2374 2308 3333 +10537 1226 3670 1131 3674 +10538 3250 3359 2883 3415 +10539 2834 2603 2833 3354 +10540 3299 3677 2780 3743 +10541 2352 3661 2462 3696 +10542 1246 3510 1048 3687 +10543 1609 2276 2196 3740 +10544 3145 3110 757 849 +10545 1697 3404 1700 3428 +10546 1432 3417 1435 3455 +10547 1914 3648 2071 3649 +10548 2249 3033 2142 2177 +10549 2079 3335 2070 3728 +10550 3498 3500 385 3746 +10551 1749 3218 1842 3405 +10552 1170 3378 1042 3381 +10553 1607 1477 1771 3397 +10554 893 757 821 3130 +10555 1015 1098 3749 3750 +10556 1534 912 1535 3258 +10557 2286 2158 3056 2259 +10558 2116 456 2216 3053 +10559 1203 1009 1190 3582 +10560 266 265 1533 3657 +10561 2603 3354 3272 3604 +10562 1340 231 1341 3702 +10563 1379 217 3683 3713 +10564 3475 3548 2964 3647 +10565 961 162 3555 3692 +10566 1493 3240 1540 3241 +10567 3148 930 903 802 +10568 2390 2524 3260 3384 +10569 790 853 415 3460 +10570 2116 2166 3029 2167 +10571 389 3656 3658 3713 +10572 3062 3102 2224 452 +10573 818 3110 3138 3168 +10574 3279 3450 2517 3725 +10575 461 2120 3059 2246 +10576 1125 1027 1221 3333 +10577 2443 2393 3627 3723 +10578 2143 3229 2217 3284 +10579 2670 435 3410 3486 +10580 1519 3540 3223 3690 +10581 2483 3440 2398 3626 +10582 423 3340 3310 3429 +10583 3044 2115 2202 3028 +10584 2170 2254 2278 3062 +10585 2958 3434 3248 3476 +10586 381 380 3489 3725 +10587 833 923 769 3107 +10588 2240 464 25 3311 +10589 2222 3082 2120 2158 +10590 1115 1296 3640 3695 +10591 1893 1418 1420 3277 +10592 1819 3413 1872 3738 +10593 3289 3429 1598 3446 +10594 3125 3145 927 849 +10595 851 3133 763 3161 +10596 3033 2249 3072 2177 +10597 3328 3521 2911 3648 +10598 3101 3027 2278 3047 +10599 458 3272 2868 3586 +10600 1728 3209 1730 3558 +10601 2515 3367 3274 3549 +10602 2695 2912 3331 3521 +10603 2582 3540 3262 3690 +10604 2558 3577 3523 3735 +10605 2698 3335 2843 3728 +10606 1972 1902 3522 3524 +10607 3232 3420 2814 3618 +10608 908 818 893 3138 +10609 2453 2385 3225 3388 +10610 2194 2239 2153 3627 +10611 1969 3648 3647 3649 +10612 776 3179 3131 850 +10613 2854 3520 3228 3756 +10614 2970 2824 3436 3760 +10615 1109 1052 1183 3388 +10616 2632 3441 3254 3442 +10617 2651 3343 3285 3772 +10618 2218 3046 3068 3023 +10619 812 3160 837 924 +10620 179 3358 3202 3463 +10621 1759 3326 3699 3768 +10622 827 778 844 424 +10623 2669 3431 3228 3710 +10624 163 1001 3553 3691 +10625 1085 1224 1062 3752 +10626 844 424 778 3340 +10627 1006 3556 3368 3765 +10628 1157 3307 1181 3608 +10629 1934 3700 3259 3756 +10630 984 3575 3592 3681 +10631 1438 3563 3392 3591 +10632 2989 2990 2917 3679 +10633 355 3754 3570 3755 +10634 2326 3283 2510 3582 +10635 1889 1861 3228 3710 +10636 1052 3225 3197 3473 +10637 1807 3297 1938 3634 +10638 2411 335 2457 3204 +10639 259 260 1331 3744 +10640 167 3570 990 3718 +10641 1731 3256 1986 3364 +10642 808 836 3146 3124 +10643 2120 2246 461 3590 +10644 3059 461 2246 2177 +10645 3273 3433 1611 3434 +10646 2073 3447 2036 3772 +10647 2387 3661 3372 3763 +10648 1435 3417 3416 3455 +10649 798 364 878 3472 +10650 2508 2372 3510 3781 +10651 2075 3478 3206 3519 +10652 2079 3345 3335 3728 +10653 3129 3106 3151 862 +10654 1231 3302 1053 3560 +10655 2209 3072 2177 460 +10656 2363 3583 3279 3729 +10657 3049 2174 2249 2264 +10658 1932 3335 2068 3346 +10659 805 775 846 3111 +10660 423 424 844 3340 +10661 809 880 3134 3167 +10662 1151 1207 824 3731 +10663 167 987 3572 3718 +10664 791 3142 3116 3153 +10665 2992 3401 3522 3558 +10666 2167 3066 3053 2261 +10667 3221 3222 2599 3288 +10668 1797 3621 3219 3762 +10669 2592 3370 392 3451 +10670 1069 1198 3605 3665 +10671 1260 3296 1178 3711 +10672 1955 3462 3453 3532 +10673 1996 2001 2015 3631 +10674 1373 3714 1374 3748 +10675 2515 3549 3274 3550 +10676 2520 3306 3614 3676 +10677 1234 3517 1097 3704 +10678 2792 2813 2793 3529 +10679 875 3116 3132 923 +10680 2750 3263 3217 3526 +10681 1504 1740 1739 3208 +10682 2997 2663 2661 3192 +10683 3234 3406 1059 3560 +10684 891 3213 1322 3301 +10685 1987 1988 3664 3679 +10686 1181 3646 3757 3758 +10687 312 3564 3554 3609 +10688 2902 3322 2802 3512 +10689 2531 3622 2423 3623 +10690 1602 3448 3447 3705 +10691 180 179 936 3202 +10692 2221 2202 3028 2144 +10693 453 2169 2122 3762 +10694 1289 3696 3269 3697 +10695 1817 1819 3400 3413 +10696 2775 2784 3222 3747 +10697 2651 2649 3285 3343 +10698 402 3569 3449 3678 +10699 2751 3327 3263 3526 +10700 2679 2754 2767 3216 +10701 891 1314 1322 3213 +10702 2982 3326 2851 3700 +10703 2666 3447 3243 3772 +10704 265 1533 3262 3398 +10705 3146 368 808 3124 +10706 786 893 821 3117 +10707 1633 1634 3344 3733 +10708 2735 3396 3436 3760 +10709 2910 2912 3328 3521 +10710 923 833 3153 3107 +10711 2631 2881 2632 3441 +10712 844 3155 827 424 +10713 1057 3432 1095 3751 +10714 1139 1252 228 3337 +10715 247 3707 1369 3746 +10716 1018 3377 1202 3688 +10717 1560 1625 3426 3775 +10718 1457 1496 3214 3747 +10719 2472 2503 2332 3703 +10720 1244 3234 1143 3418 +10721 3160 774 3180 3109 +10722 2134 3383 450 3587 +10723 1974 3375 1967 3475 +10724 2890 3365 2894 3397 +10725 3553 3573 356 3754 +10726 460 2209 459 3588 +10727 2466 3686 3623 3734 +10728 2438 2334 2388 3717 +10729 3553 356 3578 3754 +10730 1841 1677 1676 3460 +10731 899 27 361 3224 +10732 2697 3277 2696 3334 +10733 1046 1211 3296 3366 +10734 2569 344 2555 3464 +10735 1557 3206 3270 3519 +10736 1238 1297 200 3722 +10737 3632 3634 1966 3767 +10738 1614 1588 1592 3398 +10739 2881 3416 3376 3775 +10740 464 25 3057 2117 +10741 2894 2712 394 3266 +10742 2447 2510 2343 3268 +10743 1454 3518 1443 3701 +10744 1886 3442 3514 3616 +10745 867 796 901 3195 +10746 2987 2938 3636 3679 +10747 3228 3431 1889 3710 +10748 2256 2151 2191 3205 +10749 1816 2045 2046 3400 +10750 386 3714 3605 3748 +10751 3122 3162 3136 811 +10752 3410 3482 277 3486 +10753 2986 3404 3264 3428 +10754 2663 3192 2997 3436 +10755 2630 2655 3441 3443 +10756 1244 1125 3234 3773 +10757 341 3284 2239 3627 +10758 1957 3281 1944 3777 +10759 2651 2923 3343 3772 +10760 1661 1576 3255 3411 +10761 1181 3608 3646 3758 +10762 1348 1347 3726 3761 +10763 3310 3340 1668 3429 +10764 2488 3445 2301 3676 +10765 1451 1689 3275 3505 +10766 3522 3523 321 3524 +10767 1606 3403 1603 3421 +10768 774 814 3109 922 +10769 3127 366 759 934 +10770 274 3488 3490 3620 +10771 2629 2655 3409 3441 +10772 3185 927 417 858 +10773 3047 2278 3101 2114 +10774 1714 3515 1710 3606 +10775 3060 3088 3044 2161 +10776 2289 2236 2112 3032 +10777 3201 3207 1421 3458 +10778 2211 1426 3588 3589 +10779 3224 3368 27 3507 +10780 2335 3323 2381 3650 +10781 2247 2232 1311 3513 +10782 1666 3533 3534 3641 +10783 422 423 779 3309 +10784 876 891 1322 3301 +10785 3110 3131 776 3164 +10786 2521 2369 2520 3676 +10787 2314 2356 2427 3706 +10788 2365 3378 2441 3414 +10789 2967 3479 2908 3662 +10790 2955 3248 2879 3476 +10791 387 2459 3605 3711 +10792 2009 1842 2010 3318 +10793 2378 3333 2511 3660 +10794 1416 3442 3441 3443 +10795 2673 2671 2716 3635 +10796 248 247 3496 3707 +10797 1423 1472 1425 3672 +10798 765 896 827 425 +10799 3332 3418 2409 3778 +10800 2766 3505 3300 3506 +10801 1915 3339 3424 3699 +10802 362 773 823 883 +10803 409 3298 30 3408 +10804 2205 3052 3097 3026 +10805 3001 3543 3542 3545 +10806 2091 3599 3523 3735 +10807 3297 1937 3634 3767 +10808 980 3735 3585 3736 +10809 2357 3293 3770 3771 +10810 2246 3589 461 3590 +10811 2885 3515 2943 3777 +10812 2951 2979 3647 3649 +10813 2699 3335 2696 3346 +10814 2911 3521 2871 3648 +10815 1607 3266 1477 3397 +10816 3232 2814 3617 3618 +10817 1931 1869 2078 3317 +10818 3021 3657 3352 3658 +10819 2229 1586 2169 3740 +10820 1419 1787 1744 3529 +10821 3167 773 880 823 +10822 2183 450 2134 449 +10823 3388 3640 1296 3695 +10824 2183 2200 450 3071 +10825 3057 332 2172 2288 +10826 1887 1915 2053 3710 +10827 1275 3332 3267 3579 +10828 2345 3279 2529 3461 +10829 1703 3292 2037 3620 +10830 2154 2234 338 3432 +10831 3256 3364 2823 3538 +10832 3136 3112 760 810 +10833 1654 3321 3324 3385 +10834 2305 2527 2491 3203 +10835 2183 2265 2147 3064 +10836 418 3533 3536 3641 +10837 3097 2163 2205 2132 +10838 3171 759 846 3127 +10839 3216 3300 2766 3505 +10840 456 2214 2141 3628 +10841 2102 320 2090 3523 +10842 164 996 165 3754 +10843 807 3125 3185 927 +10844 2218 3046 3099 2131 +10845 1478 3331 1678 3386 +10846 2132 3043 2206 2175 +10847 1025 3445 1180 3579 +10848 1993 3610 3261 3612 +10849 2296 2533 2495 3734 +10850 2572 390 3202 3247 +10851 2355 2487 3296 3706 +10852 2078 1891 1892 3317 +10853 754 3151 862 822 +10854 1797 1585 3621 3762 +10855 1794 1796 1950 3211 +10856 3060 2161 2234 2119 +10857 2130 3042 2274 2170 +10858 2012 3633 3631 3682 +10859 3281 3341 2819 3453 +10860 1889 1711 1631 3431 +10861 1943 1557 1550 3353 +10862 2723 2752 2702 3212 +10863 1113 3579 1180 3778 +10864 419 905 782 420 +10865 1468 3281 1957 3341 +10866 2893 3502 3357 3503 +10867 225 1360 1357 3725 +10868 1650 3329 1983 3330 +10869 759 3143 366 3127 +10870 2127 457 2214 2283 +10871 2691 3249 3196 3386 +10872 1319 3291 3294 3669 +10873 1417 1627 3441 3442 +10874 170 3585 980 3735 +10875 2611 3351 3350 3365 +10876 2374 3435 2548 3773 +10877 2383 2507 3427 3665 +10878 326 1475 325 3603 +10879 252 1356 1359 3724 +10880 3523 3599 2571 3735 +10881 2977 3273 3433 3471 +10882 1068 3640 3314 3702 +10883 2094 3370 328 3451 +10884 1325 260 3543 3669 +10885 341 2537 3284 3627 +10886 356 3651 3437 3754 +10887 1335 232 3593 3745 +10888 416 417 771 3535 +10889 1276 1083 1217 3698 +10890 2970 2949 2873 3471 +10891 3211 3271 2818 3341 +10892 394 2894 3266 3397 +10893 2161 337 3060 2234 +10894 2817 3394 3393 3396 +10895 2877 3515 3315 3606 +10896 2020 2022 3326 3531 +10897 352 3466 3592 3681 +10898 410 2573 3231 3298 +10899 2572 2575 3247 3463 +10900 29 3247 391 3638 +10901 376 3314 375 3702 +10902 1847 1459 1431 3223 +10903 762 27 361 899 +10904 2138 2169 454 3740 +10905 401 2674 2648 3209 +10906 2802 3470 3322 3680 +10907 2147 3073 2279 3034 +10908 1125 1253 1027 3333 +10909 1362 3491 251 3709 +10910 418 785 858 3533 +10911 805 3127 3133 3111 +10912 1541 3240 2215 3518 +10913 1054 3559 3472 3731 +10914 2521 3278 2309 3366 +10915 2797 3208 2810 3504 +10916 1124 3439 1197 3625 +10917 1940 3442 1415 3443 +10918 2154 339 2129 2220 +10919 3355 3539 1044 3752 +10920 2517 3279 2406 3450 +10921 3145 3125 3110 849 +10922 1768 1673 3338 3536 +10923 194 1256 1209 3580 +10924 2907 3353 3387 3404 +10925 1943 3270 1557 3353 +10926 1405 3215 1490 3743 +10927 1144 3584 1269 3619 +10928 3281 3286 1467 3515 +10929 341 2255 2239 3284 +10930 2473 3296 2314 3706 +10931 1917 1926 1962 3715 +10932 333 3313 3670 3753 +10933 2704 3400 2701 3413 +10934 1010 3696 1159 3697 +10935 2822 3256 2821 3412 +10936 1702 1808 3515 3561 +10937 1955 1960 2011 3462 +10938 1675 3277 1673 3334 +10939 1049 3236 1092 3293 +10940 2252 2183 2134 449 +10941 3099 2219 2178 2131 +10942 444 2706 3223 3501 +10943 2715 3341 3286 3715 +10944 1725 3353 1699 3387 +10945 2602 2603 2752 3272 +10946 1111 3568 3688 3770 +10947 1166 3305 1073 3623 +10948 3034 2279 2231 3055 +10949 824 1207 911 3472 +10950 2160 2273 2289 3065 +10951 1669 3289 1670 3429 +10952 380 3487 3489 3724 +10953 3206 3270 2905 3353 +10954 408 3554 2563 3557 +10955 991 990 995 3718 +10956 1890 3422 3289 3446 +10957 2307 3757 3646 3758 +10958 2707 2946 2904 3330 +10959 3096 2250 3048 3081 +10960 1760 2058 3474 3616 +10961 1968 1967 2011 3375 +10962 3457 3507 2468 3694 +10963 2551 2482 2311 3579 +10964 2238 2115 3050 2260 +10965 175 964 176 3602 +10966 1832 3275 1689 3359 +10967 862 3151 3129 3111 +10968 2750 2921 2836 3526 +10969 2121 2265 2183 3064 +10970 2173 2149 2195 3202 +10971 2964 2965 2963 3647 +10972 2466 2304 3623 3686 +10973 2563 3554 2562 3555 +10974 2367 2402 2320 3749 +10975 846 3171 3127 3111 +10976 2307 3646 3608 3758 +10977 1325 1331 260 3669 +10978 3133 365 805 878 +10979 1874 1788 3423 3465 +10980 933 917 804 3139 +10981 927 3185 807 858 +10982 354 3570 3718 3755 +10983 3047 2278 2254 3062 +10984 1092 1049 1245 3236 +10985 1897 3190 1822 3219 +10986 3049 2174 2264 2124 +10987 1969 1968 1812 3320 +10988 1408 1497 3214 3363 +10989 3088 2131 2202 2161 +10990 2775 3205 462 3747 +10991 1405 1491 3215 3408 +10992 866 412 764 906 +10993 1218 3204 1274 3452 +10994 788 887 3129 862 +10995 454 2230 453 2169 +10996 2314 3296 2487 3706 +10997 3155 827 424 425 +10998 1959 3462 1955 3532 +10999 1487 3515 3286 3606 +11000 1376 3714 1372 3748 +11001 1285 3257 198 3644 +11002 159 1006 160 3231 +11003 3245 3387 1721 3733 +11004 3281 3286 2715 3341 +11005 2074 1786 3232 3617 +11006 1390 261 1387 3543 +11007 3088 2202 3044 2161 +11008 2132 3077 2175 2174 +11009 1891 1418 1892 3529 +11010 833 3153 3107 3159 +11011 1735 1512 1825 3425 +11012 2261 2230 454 2138 +11013 346 2524 3384 3722 +11014 2231 3034 3055 3101 +11015 2683 2688 2690 3407 +11016 2837 2693 2840 3738 +11017 1176 1261 3362 3695 +11018 1658 3537 3258 3565 +11019 778 425 896 3373 +11020 3155 3116 758 827 +11021 1074 1177 3355 3723 +11022 1882 1850 3304 3430 +11023 2984 3522 3401 3524 +11024 3114 3140 800 3173 +11025 2875 3339 2869 3538 +11026 940 3200 185 3368 +11027 2803 2685 3511 3680 +11028 1885 3249 1479 3413 +11029 3055 2168 3027 3085 +11030 1031 3667 1105 3734 +11031 2183 3071 449 3064 +11032 2758 3270 2808 3423 +11033 1955 2011 1956 3453 +11034 2616 2613 3190 3208 +11035 1940 1886 3442 3514 +11036 1481 3587 3226 3607 +11037 757 3130 3110 3145 +11038 311 3554 312 3564 +11039 2920 3271 2918 3530 +11040 2432 3356 3355 3539 +11041 1862 1970 1712 3756 +11042 3201 1421 3338 3458 +11043 3142 765 827 425 +11044 1654 3324 2059 3385 +11045 1624 1485 1508 3563 +11046 457 3354 2603 3604 +11047 343 3720 3464 3766 +11048 1451 3275 1764 3764 +11049 1068 3314 1240 3702 +11050 3737 3738 2052 3739 +11051 1344 3653 1341 3732 +11052 2130 2278 3027 2170 +11053 2584 2585 3540 3690 +11054 1748 3196 1755 3374 +11055 3066 2274 3042 3102 +11056 1611 3273 2000 3433 +11057 329 1492 1546 3638 +11058 3109 3160 774 812 +11059 1256 3509 3466 3779 +11060 2200 3047 2254 451 +11061 810 774 3162 894 +11062 1571 3430 1902 3524 +11063 1597 3369 1425 3637 +11064 1884 1471 1821 3426 +11065 1985 1823 3212 3392 +11066 168 3575 3572 3592 +11067 1128 3234 3660 3661 +11068 177 950 3464 3720 +11069 2561 3551 406 3639 +11070 2177 2120 3059 2258 +11071 317 3449 3569 3678 +11072 2655 2646 3409 3443 +11073 998 3754 3651 3755 +11074 3259 3371 2981 3700 +11075 1848 3419 1464 3421 +11076 3248 3434 2023 3476 +11077 1719 3345 2079 3728 +11078 2034 3232 1612 3395 +11079 1211 1153 1046 3296 +11080 1347 1353 1348 3726 +11081 1623 1705 1771 3365 +11082 1329 3362 234 3745 +11083 1776 3448 1602 3705 +11084 3106 819 850 754 +11085 429 3469 2580 3541 +11086 1577 3410 3409 3411 +11087 2029 3371 3259 3700 +11088 3160 837 774 812 +11089 2000 3433 3273 3471 +11090 764 890 906 3251 +11091 2262 2246 2120 3590 +11092 1188 2220 2194 3627 +11093 1204 2182 2237 3753 +11094 2475 2462 3661 3763 +11095 311 2086 3554 3557 +11096 3475 2627 3548 3611 +11097 1852 1865 3207 3389 +11098 2416 3717 3466 3779 +11099 2473 2487 2314 3296 +11100 2249 2113 3072 2177 +11101 2426 2293 2378 3269 +11102 1990 1807 1802 3636 +11103 1169 1037 3236 3260 +11104 170 3577 3585 3735 +11105 2462 2388 3697 3763 +11106 1306 1289 1127 3269 +11107 2887 2880 3286 3515 +11108 1985 3212 1436 3392 +11109 3179 850 810 894 +11110 1618 3581 1836 3739 +11111 2024 2026 3433 3471 +11112 1969 2071 3648 3649 +11113 3053 3029 3066 2167 +11114 1115 1296 1068 3640 +11115 2592 2594 2595 3350 +11116 1424 1425 3369 3373 +11117 1467 1944 3281 3515 +11118 2060 3292 2051 3409 +11119 2615 3219 2864 3226 +11120 3204 3348 2366 3452 +11121 2317 3257 2424 3769 +11122 1403 1390 3295 3311 +11123 1111 3568 3567 3688 +11124 3234 1125 3435 3773 +11125 2310 3193 3323 3372 +11126 860 785 418 3534 +11127 3252 3337 1235 3761 +11128 389 3658 3683 3713 +11129 2478 3750 2402 3752 +11130 3163 3155 3116 758 +11131 2645 2646 2647 3217 +11132 1743 3357 1742 3659 +11133 1747 3208 1746 3504 +11134 3064 2147 2183 3034 +11135 2747 3453 3462 3532 +11136 2991 3327 2980 3615 +11137 2284 332 333 3313 +11138 1632 1633 1634 3344 +11139 2899 3189 2864 3226 +11140 3062 2170 2254 2224 +11141 25 3311 3019 3543 +11142 2301 3445 3306 3676 +11143 358 3552 3691 3692 +11144 1152 3203 1110 3693 +11145 2538 332 3294 3670 +11146 3243 3250 1601 3447 +11147 3026 2132 2205 2174 +11148 2822 3256 3412 3671 +11149 338 3360 339 3432 +11150 2681 2682 2600 3741 +11151 3233 3241 2779 3370 +11152 1797 1587 3235 3621 +11153 2321 3379 3378 3380 +11154 3157 808 368 3124 +11155 2117 25 332 2226 +11156 1835 1509 1834 3581 +11157 2778 3239 3262 3419 +11158 949 845 888 3200 +11159 1912 1913 1914 3412 +11160 2616 2857 2827 3208 +11161 173 968 174 3598 +11162 3267 3332 2502 3579 +11163 1345 1350 3653 3761 +11164 330 2197 1616 3638 +11165 1686 3322 3470 3680 +11166 1547 3251 1446 3663 +11167 2799 3322 2882 3324 +11168 974 3599 171 3736 +11169 1818 1819 3198 3400 +11170 1556 3564 3308 3677 +11171 1848 1520 3419 3540 +11172 198 3257 1147 3384 +11173 2697 2696 2698 3334 +11174 2620 3201 2618 3389 +11175 819 3106 887 754 +11176 2543 2348 2489 3193 +11177 1946 3459 1947 3531 +11178 1979 1955 3453 3532 +11179 275 1703 2037 3620 +11180 26 3284 2537 3342 +11181 1555 1491 310 3215 +11182 2355 3296 2461 3549 +11183 1983 3330 3329 3664 +11184 2990 3664 2919 3679 +11185 2213 2135 3237 3587 +11186 3407 3446 1596 3637 +11187 259 258 3545 3744 +11188 3080 3026 2113 2174 +11189 2349 3296 2459 3711 +11190 281 3516 1770 3541 +11191 415 834 853 790 +11192 2609 3194 2755 3227 +11193 1432 1470 3417 3741 +11194 2183 3071 3064 3034 +11195 2194 2153 1119 3627 +11196 3280 3289 1766 3423 +11197 3259 3343 2923 3772 +11198 798 878 824 3472 +11199 1054 3472 1151 3731 +11200 3162 811 774 810 +11201 2366 3452 3348 3674 +11202 2957 2818 2861 3375 +11203 3142 827 765 909 +11204 3336 3425 1461 3503 +11205 2465 2411 3204 3307 +11206 3063 3041 339 2165 +11207 328 2096 329 3370 +11208 457 2833 2603 3354 +11209 909 3142 827 791 +11210 2214 456 2116 3053 +11211 818 3110 776 849 +11212 836 808 892 3124 +11213 3475 3530 2627 3611 +11214 978 197 977 3644 +11215 451 3226 3587 3607 +11216 1098 3646 3360 3757 +11217 2435 2375 2297 3435 +11218 2650 3209 2968 3285 +11219 407 3554 408 3609 +11220 1952 3328 3647 3648 +11221 2054 3351 1621 3365 +11222 2929 2666 2860 3371 +11223 1617 3737 1609 3740 +11224 1977 3475 1967 3548 +11225 3164 3149 807 3125 +11226 2610 3266 2894 3365 +11227 927 771 417 858 +11228 2530 3716 3466 3717 +11229 1322 1314 1378 3213 +11230 220 1376 1372 3748 +11231 2134 449 450 3383 +11232 3062 2254 3047 451 +11233 408 3564 2587 3609 +11234 1849 3221 3516 3741 +11235 1343 256 3547 3642 +11236 1709 1916 1980 3606 +11237 1835 1834 3196 3581 +11238 1666 1672 3536 3641 +11239 1500 1754 3325 3351 +11240 1718 1724 1720 3245 +11241 2155 3057 3031 2266 +11242 1089 1145 1036 3252 +11243 3225 3305 2327 3685 +11244 459 2209 2146 3588 +11245 1545 327 3370 3451 +11246 1293 1277 1120 3290 +11247 2181 2150 2281 3313 +11248 925 794 825 3274 +11249 1271 3305 1061 3685 +11250 1874 3423 3270 3465 +11251 1416 3441 3409 3443 +11252 2326 2389 2458 3528 +11253 2773 3369 3340 3429 +11254 2661 2751 2997 3526 +11255 2500 3457 2468 3694 +11256 465 3352 3246 3658 +11257 243 1317 3658 3683 +11258 1190 1009 3473 3758 +11259 985 3592 989 3681 +11260 367 2532 368 3456 +11261 3151 3119 3137 822 +11262 2561 3573 3553 3639 +11263 3248 3273 2947 3682 +11264 2166 3096 3079 3029 +11265 2169 454 2230 2138 +11266 2074 1786 1610 3232 +11267 364 365 3133 878 +11268 2816 3391 2817 3394 +11269 2392 3193 2310 3406 +11270 2085 3298 3231 3556 +11271 2341 3687 3377 3688 +11272 875 3116 923 791 +11273 443 2706 3501 3502 +11274 2021 3531 2020 3532 +11275 2893 3357 2886 3503 +11276 2888 3336 2664 3503 +11277 1355 1358 1359 3725 +11278 2440 3305 2304 3686 +11279 2239 2255 341 2118 +11280 427 2780 3215 3743 +11281 462 2120 2262 2222 +11282 1342 3642 1341 3653 +11283 2309 3366 3278 3665 +11284 805 3133 878 763 +11285 2967 3434 2958 3476 +11286 336 335 3307 3347 +11287 2531 2423 2346 3623 +11288 1620 1731 1706 3364 +11289 1695 1791 2075 3519 +11290 2308 2511 3333 3660 +11291 1732 3416 3454 3455 +11292 1924 2074 2034 3232 +11293 2131 3046 3099 3088 +11294 1191 1249 1051 3445 +11295 1502 3262 3239 3419 +11296 3162 3179 3112 810 +11297 1428 1429 1738 3589 +11298 858 418 760 860 +11299 895 27 3200 3231 +11300 3551 3553 2087 3639 +11301 762 361 3140 823 +11302 3296 3549 2355 3706 +11303 1835 3196 1897 3235 +11304 414 777 821 890 +11305 2054 1477 3266 3365 +11306 423 844 779 3340 +11307 2746 3531 2941 3532 +11308 1770 3516 1531 3541 +11309 3034 2231 2183 2114 +11310 3357 3502 1716 3503 +11311 878 3133 364 763 +11312 2383 3427 385 3605 +11313 1310 1311 1309 3290 +11314 1483 3222 1486 3288 +11315 3076 2186 3024 3070 +11316 2693 3249 2694 3413 +11317 1494 3233 1546 3241 +11318 2323 3640 3388 3695 +11319 1702 1808 1809 3515 +11320 2695 3331 3386 3521 +11321 2696 2791 2700 3277 +11322 2530 3466 2416 3717 +11323 1538 1495 1537 3214 +11324 3064 3073 2147 3034 +11325 1754 1752 1753 3350 +11326 2980 3327 3495 3615 +11327 1611 3433 1569 3434 +11328 2661 3327 2751 3526 +11329 2772 3289 2607 3429 +11330 2580 3214 2579 3221 +11331 1198 3366 1116 3605 +11332 3401 3430 2738 3524 +11333 2034 3394 3232 3395 +11334 3155 3128 423 844 +11335 3207 3458 415 3460 +11336 1215 3406 3193 3560 +11337 3393 3394 1929 3396 +11338 354 3716 2479 3755 +11339 3320 3424 2913 3768 +11340 275 3488 274 3620 +11341 2668 2741 2737 3303 +11342 1031 3622 1105 3667 +11343 1504 3208 1747 3282 +11344 1735 3396 1512 3425 +11345 3568 1138 3769 3770 +11346 923 833 791 3153 +11347 1890 3289 1598 3446 +11348 3096 2206 2250 2166 +11349 2790 2791 3277 3529 +11350 834 3145 757 849 +11351 761 870 28 884 +11352 348 3599 3598 3601 +11353 1133 3517 1094 3550 +11354 1236 3257 1285 3644 +11355 2421 3362 2354 3695 +11356 1145 3314 3252 3732 +11357 2905 3270 3206 3519 +11358 1252 3337 1139 3666 +11359 1093 911 1207 3472 +11360 3036 2175 2124 2243 +11361 204 205 976 3284 +11362 2615 2864 3190 3226 +11363 1876 1656 1691 3272 +11364 1309 1312 1310 3513 +11365 1655 1437 3586 3591 +11366 1734 1686 3470 3680 +11367 1254 3278 1022 3665 +11368 2113 3045 2205 3026 +11369 3320 3424 1810 3649 +11370 162 1002 3552 3691 +11371 3409 3411 2743 3774 +11372 2632 2630 3441 3442 +11373 2710 3220 3191 3465 +11374 2129 2208 339 2154 +11375 1343 3547 257 3593 +11376 2764 3255 2744 3480 +11377 2021 2020 1961 3532 +11378 337 3307 2362 3646 +11379 1128 3406 3234 3661 +11380 1113 1065 1180 3579 +11381 785 3533 418 3534 +11382 1157 3204 1212 3307 +11383 2141 456 2216 2214 +11384 1705 3365 1623 3730 +11385 3162 3136 811 810 +11386 1107 1243 1026 3510 +11387 197 978 196 3644 +11388 233 234 3362 3745 +11389 1345 1348 1350 3761 +11390 28 3301 3367 3683 +11391 1722 1645 1721 3733 +11392 3128 814 898 922 +11393 1851 3369 1597 3637 +11394 1005 949 941 3200 +11395 1481 1653 3189 3226 +11396 2463 3268 3539 3752 +11397 2614 3189 2616 3190 +11398 874 813 782 3258 +11399 3426 3516 2762 3741 +11400 2763 3255 2764 3480 +11401 1659 3565 1523 3641 +11402 1529 1752 1824 3350 +11403 2518 3293 2357 3771 +11404 2790 3201 2792 3529 +11405 165 166 3573 3754 +11406 2966 2646 3292 3409 +11407 1811 1914 2071 3649 +11408 2350 2521 2520 3278 +11409 1836 3235 1587 3621 +11410 1556 1769 3308 3564 +11411 1554 859 1406 3672 +11412 1457 1496 1495 3214 +11413 3484 3547 256 3642 +11414 3483 3484 255 3653 +11415 3026 2113 3045 3080 +11416 3130 757 821 853 +11417 1616 1613 1590 3638 +11418 2659 2922 2647 3443 +11419 1638 1677 831 3535 +11420 1098 1229 1015 3749 +11421 839 793 817 3231 +11422 1817 3400 3399 3413 +11423 3250 3359 1831 3705 +11424 451 2135 2200 3587 +11425 1677 1638 1637 3535 +11426 2805 2806 3519 3727 +11427 1767 1670 1669 3289 +11428 3114 933 880 756 +11429 2958 2947 3248 3273 +11430 3309 3310 423 3340 +11431 462 3205 2262 3590 +11432 353 3592 3466 3716 +11433 1944 1808 1945 3777 +11434 1728 1730 2055 3558 +11435 926 841 1579 3408 +11436 3716 3718 993 3755 +11437 1015 1171 1098 3750 +11438 386 387 3605 3714 +11439 3055 2125 2279 2168 +11440 3021 3352 3020 3658 +11441 3314 3640 2391 3702 +11442 2950 3320 2913 3768 +11443 905 860 760 419 +11444 1406 3195 1553 3672 +11445 2023 3248 3273 3434 +11446 2483 3510 3440 3626 +11447 2787 426 3672 3743 +11448 1239 1300 221 3427 +11449 2095 179 3202 3463 +11450 2629 2630 2655 3441 +11451 2498 347 2552 3384 +11452 2006 3652 1999 3742 +11453 1516 3327 1514 3495 +11454 2036 3447 3285 3772 +11455 984 3575 168 3592 +11456 860 418 760 419 +11457 2231 3101 2278 2114 +11458 2907 2906 3353 3404 +11459 3029 3081 3066 2167 +11460 2870 3364 3431 3538 +11461 2816 3391 3394 3617 +11462 934 365 366 780 +11463 2205 2113 3026 2174 +11464 427 3215 3195 3743 +11465 1701 3428 1700 3561 +11466 2370 2302 2439 3414 +11467 1073 3623 3305 3686 +11468 2064 1913 3521 3648 +11469 2223 2257 2152 3240 +11470 3116 875 758 827 +11471 1646 1763 1647 3678 +11472 1134 1229 1057 3360 +11473 370 3274 2515 3367 +11474 2937 2918 3211 3636 +11475 1785 3250 3242 3415 +11476 349 3644 3468 3736 +11477 1309 1310 3290 3513 +11478 2660 2640 3447 3448 +11479 2113 3072 3045 3080 +11480 2006 2005 3436 3742 +11481 465 3020 3352 3658 +11482 2582 2584 3540 3690 +11483 840 3534 860 3537 +11484 2855 2856 2992 3401 +11485 1030 1141 1276 3279 +11486 776 3131 3179 3164 +11487 1212 1157 1055 3204 +11488 1768 1636 1673 3536 +11489 1332 3712 3655 3714 +11490 250 1363 249 3493 +11491 356 3437 3578 3754 +11492 386 3605 385 3748 +11493 2864 3189 2614 3226 +11494 3440 3510 1081 3626 +11495 1767 1766 3280 3289 +11496 1258 3332 1113 3778 +11497 1896 1783 3272 3354 +11498 2900 3244 3207 3460 +11499 334 2123 2164 3051 +11500 2030 3371 2029 3700 +11501 3275 3505 2769 3764 +11502 1912 1681 1913 3521 +11503 2868 3392 2770 3591 +11504 384 3619 3707 3746 +11505 1525 1556 3308 3677 +11506 1688 3448 1776 3705 +11507 1856 1681 1912 3504 +11508 3052 2205 3045 3026 +11509 2073 3243 1601 3447 +11510 1876 1656 3272 3586 +11511 2513 2397 3643 3776 +11512 163 3553 3552 3691 +11513 3297 3634 2994 3767 +11514 1296 3388 1020 3640 +11515 1346 255 3642 3653 +11516 3190 3208 2613 3374 +11517 2906 3206 2905 3353 +11518 2408 3337 3252 3761 +11519 2774 32 3363 3469 +11520 3080 3049 2174 2249 +11521 398 3523 3522 3524 +11522 1874 1873 1788 3465 +11523 760 807 886 3149 +11524 2141 2214 2176 3628 +11525 1495 1531 1527 3221 +11526 1992 1993 1994 3612 +11527 1008 3687 3467 3781 +11528 2525 2323 2433 3640 +11529 1995 3331 1994 3610 +11530 2093 3602 2105 3603 +11531 220 221 3605 3748 +11532 1019 3316 1136 3698 +11533 1574 3319 1738 3563 +11534 3349 3400 2707 3512 +11535 986 985 989 3681 +11536 2052 1609 3737 3739 +11537 3189 3190 1739 3208 +11538 1161 3507 3457 3694 +11539 185 940 184 3200 +11540 1935 3343 2050 3756 +11541 1258 1065 1113 3332 +11542 2755 3220 2730 3280 +11543 2329 3360 2412 3646 +11544 2880 3287 3286 3606 +11545 1835 1755 1897 3196 +11546 2123 2245 334 2164 +11547 1269 3427 1239 3619 +11548 3027 2278 3047 3062 +11549 1236 3643 3257 3644 +11550 2370 2439 3477 3583 +11551 1719 2033 3210 3728 +11552 417 418 858 3533 +11553 1253 1058 1108 3435 +11554 1528 3221 1849 3741 +11555 2679 3448 3216 3705 +11556 1697 1700 1701 3428 +11557 2676 2744 3255 3774 +11558 1977 2003 3475 3548 +11559 1793 1790 1789 3727 +11560 2115 2204 336 2290 +11561 1496 1408 1497 3214 +11562 2885 2877 3515 3561 +11563 2212 3205 1409 3590 +11564 372 3294 2546 3669 +11565 1373 1375 1374 3714 +11566 462 2120 3059 461 +11567 2664 2888 2665 3336 +11568 1639 3282 1640 3671 +11569 2940 2850 2982 3326 +11570 1172 1287 1021 3539 +11571 1232 1112 1019 3698 +11572 1322 3213 1378 3301 +11573 1887 3339 1915 3710 +11574 1523 3641 3565 3728 +11575 3349 3470 1683 3512 +11576 312 1769 3564 3609 +11577 2778 3239 2776 3262 +11578 2203 3383 1441 3518 +11579 2710 2709 2708 3210 +11580 1635 3455 1564 3680 +11581 875 3163 3116 758 +11582 1107 1026 1246 3510 +11583 2182 3347 2237 3753 +11584 3599 3735 171 3736 +11585 333 2444 334 3348 +11586 2618 3207 2858 3389 +11587 2290 2204 336 2136 +11588 1122 1280 1292 3367 +11589 1405 1491 1490 3215 +11590 3169 3122 3136 811 +11591 1599 3243 3242 3250 +11592 1018 1111 3567 3688 +11593 2279 3073 2147 2189 +11594 1732 1435 3416 3455 +11595 1009 1184 3473 3528 +11596 1951 3548 3328 3610 +11597 2991 3263 2751 3327 +11598 2086 3556 3555 3557 +11599 2550 3362 3361 3695 +11600 2086 3555 3554 3557 +11601 2039 3339 1888 3538 +11602 3313 1041 3670 3753 +11603 1633 3344 3245 3733 +11604 3321 3322 1654 3324 +11605 3240 3241 1589 3638 +11606 965 3613 966 3722 +11607 1633 3245 1727 3733 +11608 1612 3395 3232 3433 +11609 260 1400 3543 3545 +11610 376 2547 375 3314 +11611 1656 1655 1437 3586 +11612 1937 1966 3634 3767 +11613 1441 1443 1454 3518 +11614 1404 1391 3246 3352 +11615 248 1369 247 3707 +11616 3081 2166 2250 2130 +11617 1755 3196 1680 3374 +11618 1080 3381 3333 3382 +11619 2867 2948 3420 3433 +11620 3559 3579 2425 3630 +11621 1583 1839 1582 3354 +11622 2357 3770 3769 3771 +11623 2210 3313 2284 3753 +11624 3530 3611 1988 3664 +11625 779 806 868 3309 +11626 3077 3026 3049 2174 +11627 892 808 784 3124 +11628 1859 1452 1860 3701 +11629 2366 3348 2444 3674 +11630 2823 3256 2891 3364 +11631 3221 3516 2577 3541 +11632 1769 1845 3308 3609 +11633 414 415 853 3460 +11634 1896 3272 3212 3354 +11635 2344 2534 2453 3225 +11636 1577 3409 1561 3774 +11637 168 3572 987 3592 +11638 2630 3441 3442 3443 +11639 2735 2736 2662 3238 +11640 1309 3291 1312 3513 +11641 2466 3623 2423 3734 +11642 3554 3557 408 3564 +11643 1768 1637 1636 3458 +11644 2421 2354 2477 3695 +11645 2729 3423 3280 3465 +11646 843 3213 789 3246 +11647 2810 2827 2826 3282 +11648 2700 3317 2908 3346 +11649 2681 3288 2598 3562 +11650 1040 1164 1225 3627 +11651 2962 2652 3253 3254 +11652 2499 3402 2380 3693 +11653 2475 3661 2387 3763 +11654 3592 3716 353 3718 +11655 3110 818 757 849 +11656 1759 3326 1780 3699 +11657 2965 2951 2979 3647 +11658 423 3155 844 424 +11659 282 281 3541 3544 +11660 1685 2045 3349 3512 +11661 807 3125 927 849 +11662 1133 1056 1094 3517 +11663 3568 3643 2513 3769 +11664 1262 1117 188 3438 +11665 2830 3536 3334 3641 +11666 2161 3044 337 2290 +11667 3027 3081 2130 3042 +11668 2525 2391 3640 3702 +11669 3453 3532 2745 3777 +11670 241 242 3213 3246 +11671 2310 3323 2484 3372 +11672 2232 3290 1311 3513 +11673 1443 3383 3607 3701 +11674 2729 3280 3220 3465 +11675 2118 390 26 3067 +11676 276 3410 277 3486 +11677 2882 3321 2903 3385 +11678 2617 2792 2790 3201 +11679 3001 372 3543 3545 +11680 419 420 782 3537 +11681 1911 3315 1910 3527 +11682 1123 3269 1032 3380 +11683 1467 1808 1944 3515 +11684 2179 2118 3067 2156 +11685 3060 3044 337 2161 +11686 2648 2650 2649 3209 +11687 2515 3274 369 3550 +11688 3081 3048 3027 2130 +11689 3114 3134 880 3167 +11690 1220 3225 3528 3685 +11691 872 829 1150 1090 +11692 1846 3308 1845 3764 +11693 2392 2543 3193 3560 +11694 400 399 2558 3523 +11695 256 255 3484 3642 +11696 1235 3252 1089 3337 +11697 244 3655 1332 3712 +11698 1926 3287 3286 3715 +11699 3205 3214 463 3363 +11700 2649 2650 2651 3285 +11701 2671 3444 2673 3633 +11702 1069 1198 1116 3605 +11703 2156 3067 2236 3032 +11704 1034 3372 1241 3763 +11705 1172 3539 3268 3752 +11706 2313 2492 3666 3698 +11707 2038 1629 3364 3431 +11708 2114 2200 3047 2254 +11709 2862 2818 3211 3271 +11710 2161 3060 2207 2119 +11711 3215 2780 3677 3743 +11712 419 3565 3537 3641 +11713 1282 1143 1053 3418 +11714 2174 2113 3080 2249 +11715 2526 3230 3477 3584 +11716 1463 3288 1432 3562 +11717 977 198 973 3601 +11718 2997 3526 2749 3742 +11719 1148 1091 2185 2228 +11720 1903 1650 1983 3330 +11721 1821 281 3508 3516 +11722 2914 2972 2852 3699 +11723 2928 3344 3346 3479 +11724 2616 3190 3189 3208 +11725 262 261 3311 3513 +11726 2019 1947 2010 3318 +11727 1008 1135 3687 3781 +11728 1718 3191 1724 3245 +11729 2338 3406 2387 3661 +11730 2820 3504 2810 3671 +11731 1826 3394 3391 3617 +11732 3116 875 827 791 +11733 2049 3519 1793 3727 +11734 1480 3249 1885 3261 +11735 1569 1612 3232 3433 +11736 2592 2595 3233 3350 +11737 2876 3428 2877 3561 +11738 1543 3205 1496 3747 +11739 2154 338 339 3432 +11740 1858 1866 1875 3280 +11741 1668 3340 1804 3429 +11742 2395 2481 3203 3694 +11743 1900 3407 1898 3629 +11744 2130 3081 2166 2167 +11745 2682 2581 2600 3741 +11746 2775 463 462 3205 +11747 3264 3315 1911 3527 +11748 963 965 966 3722 +11749 2211 3588 2133 3589 +11750 1591 3237 3226 3587 +11751 310 3215 1491 3408 +11752 2095 3247 2096 3463 +11753 834 927 3145 849 +11754 1226 1041 1131 3670 +11755 2782 413 3251 3663 +11756 3274 3549 1039 3550 +11757 1258 1113 1282 3778 +11758 1319 3291 236 3294 +11759 2417 3257 2317 3643 +11760 2146 459 2190 2209 +11761 2476 2308 2374 3660 +11762 2576 2577 3221 3516 +11763 3252 3337 2318 3622 +11764 1541 2215 2159 3518 +11765 1166 1036 1270 3623 +11766 365 3630 366 3731 +11767 1773 1519 3223 3690 +11768 3286 3287 1709 3606 +11769 2074 3232 1924 3617 +11770 1407 1579 1405 3408 +11771 1970 1862 2050 3756 +11772 1432 1484 1470 3288 +11773 2719 2634 3403 3624 +11774 402 403 3449 3569 +11775 1727 1720 3245 3344 +11776 1795 3530 1989 3679 +11777 2812 3391 2816 3617 +11778 339 338 2456 3360 +11779 450 451 2200 3587 +11780 191 3650 1283 3716 +11781 828 779 844 3340 +11782 1440 3587 1481 3607 +11783 2114 3047 2278 2254 +11784 3127 805 365 934 +11785 3081 2250 3048 2130 +11786 1359 1358 1362 3709 +11787 2382 2533 2296 3703 +11788 2512 3366 2309 3665 +11789 2480 357 2429 3437 +11790 450 2200 2134 3587 +11791 3101 2168 2231 2278 +11792 885 831 1677 3535 +11793 2658 3242 2883 3415 +11794 2226 2150 2181 3290 +11795 2479 3650 2381 3651 +11796 3045 2209 3072 2113 +11797 1618 2052 3738 3739 +11798 1223 3225 1061 3305 +11799 2366 3204 2457 3348 +11800 2365 2441 3381 3414 +11801 1987 1984 3329 3664 +11802 1797 1585 1587 3621 +11803 3409 3410 2743 3411 +11804 1999 3652 2032 3742 +11805 3306 3445 2422 3778 +11806 2014 2012 1966 3633 +11807 3072 2209 459 460 +11808 883 838 797 3224 +11809 3275 3359 1832 3629 +11810 2963 2954 2957 3375 +11811 2790 3277 2759 3338 +11812 1286 3732 3252 3761 +11813 2620 2618 2858 3389 +11814 461 3059 3072 2177 +11815 3140 800 762 823 +11816 2869 3412 2821 3538 +11817 1625 1560 1708 3775 +11818 1534 1536 1800 3258 +11819 2512 2309 2507 3665 +11820 3021 465 3020 3352 +11821 1031 3337 1089 3622 +11822 2670 436 435 3486 +11823 3066 2261 2230 454 +11824 2666 3285 3447 3772 +11825 1109 3675 3388 3695 +11826 1292 3301 217 3367 +11827 2793 2812 2816 3617 +11828 2231 3055 2168 3101 +11829 1849 3221 1531 3516 +11830 1075 3507 1161 3694 +11831 1628 3376 3416 3775 +11832 1733 1823 3392 3511 +11833 441 3497 3494 3659 +11834 2033 3565 3210 3728 +11835 337 2362 2412 3646 +11836 1195 1265 3278 3614 +11837 2428 2544 3623 3640 +11838 337 338 2234 3432 +11839 449 3518 2783 3701 +11840 2844 2698 2843 3728 +11841 3264 3387 2622 3733 +11842 2543 2310 2392 3193 +11843 455 2216 456 3053 +11844 188 1298 189 3437 +11845 2348 3193 2543 3560 +11846 3057 332 3084 2172 +11847 1061 3225 1220 3685 +11848 459 3586 2868 3591 +11849 2044 3322 1686 3680 +11850 187 953 3402 3692 +11851 2829 3581 2837 3739 +11852 857 779 916 3309 +11853 3009 3656 3654 3657 +11854 3167 3140 361 823 +11855 3127 365 805 3133 +11856 3303 2890 3365 3730 +11857 271 3497 3357 3659 +11858 825 794 870 3301 +11859 1830 3405 1829 3478 +11860 2462 2352 2475 3661 +11861 176 2105 2093 3602 +11862 3028 2202 3044 3088 +11863 2224 2162 2135 3237 +11864 2400 3427 3230 3619 +11865 1454 1452 1453 3689 +11866 223 3619 1366 3759 +11867 2328 3197 2418 3608 +11868 1636 3535 3533 3536 +11869 2117 2240 25 2226 +11870 2878 3315 2877 3428 +11871 3201 3207 2618 3389 +11872 1706 1629 1707 3730 +11873 1287 1169 1021 3260 +11874 2392 3193 3406 3560 +11875 797 838 1121 3224 +11876 944 953 945 3765 +11877 2358 3703 3686 3734 +11878 1739 3189 1651 3190 +11879 2842 3210 3565 3728 +11880 2656 3242 2657 3405 +11881 2882 2976 3324 3385 +11882 1338 1336 3593 3745 +11883 1496 1543 1408 3205 +11884 2153 2239 2255 3284 +11885 2970 2873 2824 3760 +11886 1757 3326 1759 3768 +11887 452 2864 3219 3226 +11888 2026 2034 1612 3395 +11889 2559 3575 3574 3576 +11890 2660 2968 2640 3448 +11891 454 455 2261 2138 +11892 2778 412 3239 3419 +11893 1309 3290 3291 3513 +11894 1674 3533 1666 3536 +11895 1863 3700 1934 3756 +11896 1680 1755 1678 3196 +11897 1309 3290 237 3291 +11898 414 853 777 3460 +11899 1327 1326 3712 3713 +11900 1128 3234 1221 3660 +11901 2757 3196 2692 3235 +11902 2787 3299 2780 3743 +11903 241 843 913 3246 +11904 2701 2702 3198 3400 +11905 1819 1872 1907 3738 +11906 2357 3293 3440 3770 +11907 2214 457 456 3086 +11908 1325 1349 1320 3291 +11909 3057 3031 3090 2155 +11910 1933 3210 2033 3565 +11911 860 3534 419 3537 +11912 2541 2522 2327 3225 +11913 1881 3526 2008 3742 +11914 3474 3616 2058 3668 +11915 1424 3369 3340 3373 +11916 2875 2870 2831 3431 +11917 266 3654 3657 3690 +11918 1079 3372 1215 3406 +11919 1899 1693 1981 3527 +11920 3262 3540 1532 3690 +11921 2661 3192 2733 3327 +11922 1666 1522 1672 3641 +11923 1468 1944 1957 3281 +11924 434 3411 3410 3482 +11925 2123 334 333 3051 +11926 3623 3686 1222 3734 +11927 2330 2388 2437 3697 +11928 1085 1062 1295 3582 +11929 1114 1190 3473 3758 +11930 2888 3425 3336 3503 +11931 3033 3072 3059 2177 +11932 2544 2391 3314 3640 +11933 2734 2736 3396 3425 +11934 2701 3198 2839 3738 +11935 2607 3289 2689 3446 +11936 1975 3271 3375 3475 +11937 2193 3048 2250 2130 +11938 1985 1436 1823 3392 +11939 2936 3635 3634 3636 +11940 196 3468 1236 3644 +11941 1992 1994 3261 3612 +11942 2215 3240 2257 3518 +11943 1857 1858 1799 3194 +11944 864 911 1093 3472 +11945 451 2254 2200 2135 +11946 2604 2688 3407 3446 +11947 236 1309 237 3291 +11948 1853 3616 3514 3668 +11949 2051 1414 3409 3443 +11950 1734 3511 1564 3680 +11951 2436 3418 3234 3773 +11952 1662 1560 1625 3426 +11953 2371 2471 3461 3698 +11954 2789 3369 2607 3637 +11955 1988 3530 2003 3611 +11956 760 905 419 3136 +11957 2355 2487 2461 3296 +11958 2662 2733 2661 3192 +11959 372 3362 3669 3744 +11960 2977 3433 3273 3434 +11961 1608 3303 1772 3600 +11962 2754 404 3300 3449 +11963 2911 2912 2871 3521 +11964 1311 3290 1310 3513 +11965 2910 2695 2912 3331 +11966 2047 1678 3331 3386 +11967 2075 2049 1830 3478 +11968 2500 3566 3457 3694 +11969 163 1001 164 3553 +11970 356 3553 2561 3573 +11971 3067 2236 2179 2156 +11972 3473 2434 3608 3758 +11973 3276 3407 1595 3637 +11974 1289 1159 3696 3697 +11975 2368 2298 2486 3582 +11976 2514 3467 3199 3687 +11977 26 3229 2255 3284 +11978 2236 2179 3100 3067 +11979 1220 3225 1184 3528 +11980 3245 3344 1720 3345 +11981 1268 3323 1167 3372 +11982 2738 2984 3401 3524 +11983 1864 3207 1865 3244 +11984 3078 334 2245 2164 +11985 388 3712 3656 3713 +11986 778 827 896 425 +11987 241 3213 843 3246 +11988 785 820 858 3533 +11989 2330 2536 3269 3697 +11990 1846 1845 1451 3764 +11991 1602 3447 1600 3705 +11992 1366 1367 3707 3746 +11993 3047 2200 450 451 +11994 3131 819 776 850 +11995 815 789 832 3246 +11996 1557 1791 1695 3519 +11997 1175 3388 1296 3695 +11998 2466 2440 2304 3686 +11999 2962 3616 3474 3668 +12000 1940 1415 1877 3443 +12001 2684 2769 3505 3764 +12002 232 233 3361 3745 +12003 1632 2068 3344 3346 +12004 2562 2563 408 3554 +12005 1626 1417 1627 3441 +12006 1679 3386 2047 3521 +12007 2392 3406 2494 3560 +12008 2890 2892 3303 3397 +12009 1410 1578 1408 3363 +12010 2468 3224 27 3507 +12011 2794 3317 3529 3618 +12012 2341 3199 3377 3687 +12013 459 3045 2209 3072 +12014 3567 3568 2376 3688 +12015 1157 1064 3204 3608 +12016 2337 2488 2454 3445 +12017 3044 2115 336 2290 +12018 2821 2822 2823 3256 +12019 2635 2634 2633 3403 +12020 2910 3331 3328 3610 +12021 1725 1699 1724 3387 +12022 2615 3190 3219 3226 +12023 3155 3163 3128 758 +12024 2231 2147 2279 3034 +12025 2297 2535 2431 3382 +12026 2550 2354 3362 3695 +12027 392 3370 2554 3451 +12028 2770 2868 2602 3392 +12029 1937 1966 1964 3634 +12030 3127 365 366 934 +12031 1939 3297 1779 3474 +12032 2890 2610 2894 3365 +12033 2164 3078 334 3051 +12034 1156 1060 1130 3697 +12035 3480 3508 280 3684 +12036 2024 3433 2000 3471 +12037 777 414 821 853 +12038 355 3573 3570 3754 +12039 1439 3212 1896 3272 +12040 2365 3380 3378 3381 +12041 1326 244 1332 3712 +12042 2710 2709 3210 3220 +12043 249 1363 1368 3708 +12044 1916 3248 1909 3476 +12045 3067 3100 2236 3032 +12046 1635 1564 3511 3680 +12047 3202 3358 26 3463 +12048 2614 2864 2899 3189 +12049 1979 1959 1955 3532 +12050 160 3556 1006 3765 +12051 3249 3261 1480 3331 +12052 801 906 890 3251 +12053 1511 1642 1517 3192 +12054 944 945 3368 3765 +12055 1275 1065 3332 3579 +12056 1082 3509 1256 3779 +12057 1433 3417 1470 3741 +12058 2325 2430 3381 3382 +12059 2729 2730 3220 3280 +12060 2960 2959 2995 3405 +12061 3409 3441 1416 3774 +12062 2068 3344 3335 3345 +12063 1680 3374 3196 3386 +12064 2971 3387 3245 3733 +12065 1689 1764 1451 3275 +12066 3496 3498 384 3746 +12067 2616 2797 2613 3208 +12068 2854 3228 2856 3756 +12069 2266 3057 3031 3084 +12070 916 1644 857 3309 +12071 1017 1218 1274 3452 +12072 1122 1039 3274 3367 +12073 2782 413 412 3251 +12074 423 2773 3340 3429 +12075 1487 1710 3515 3606 +12076 811 3136 760 810 +12077 2733 3238 2732 3659 +12078 1699 3353 1552 3387 +12079 2119 2234 338 2154 +12080 2469 3197 2328 3452 +12081 1830 3242 2080 3405 +12082 1867 1906 3434 3662 +12083 1722 1698 3264 3387 +12084 1751 1842 1749 3218 +12085 922 3128 3163 758 +12086 2478 2353 3355 3539 +12087 1801 1949 1978 3271 +12088 2191 1578 2256 3363 +12089 3063 2236 3100 3032 +12090 1727 3245 1633 3344 +12091 1466 1465 1548 3419 +12092 2663 2735 2662 3192 +12093 403 402 3449 3678 +12094 3300 3449 404 3571 +12095 3660 3661 2352 3696 +12096 2719 3540 2586 3624 +12097 455 2216 2261 2138 +12098 905 782 860 419 +12099 3596 3597 2092 3598 +12100 195 196 983 3468 +12101 2818 2863 3211 3341 +12102 1131 1096 3348 3753 +12103 2708 3210 2842 3728 +12104 2505 2340 2460 3438 +12105 164 2099 3553 3573 +12106 1025 3579 3559 3630 +12107 180 2201 2270 3202 +12108 2864 2614 3190 3226 +12109 3298 3556 2097 3557 +12110 3066 455 3053 2261 +12111 1959 2021 1961 3532 +12112 3185 3149 807 858 +12113 795 906 856 3251 +12114 3496 384 3707 3746 +12115 1912 3412 1925 3671 +12116 1338 1337 1336 3745 +12117 2773 2607 3369 3429 +12118 2850 3326 2940 3531 +12119 845 793 895 3231 +12120 1736 1461 3393 3425 +12121 1278 1119 2153 3284 +12122 2246 2262 2157 3590 +12123 3155 3116 827 3142 +12124 3189 3190 2614 3226 +12125 1882 1901 1850 3430 +12126 3222 3288 1483 3319 +12127 353 3572 3575 3592 +12128 3195 3215 427 3408 +12129 1902 1571 1901 3430 +12130 418 3536 2830 3641 +12131 2073 1601 2036 3447 +12132 2137 2204 2185 3347 +12133 1111 1138 3568 3770 +12134 2501 2461 389 3711 +12135 1788 3280 1766 3423 +12136 3140 410 27 762 +12137 2261 2167 3066 2230 +12138 1982 3612 3330 3664 +12139 1777 1461 3425 3503 +12140 1636 3458 1637 3535 +12141 1533 1532 266 3262 +12142 1192 1024 3307 3646 +12143 225 3279 1141 3729 +12144 3250 3447 2642 3705 +12145 1853 2062 3514 3616 +12146 1439 1656 1437 3272 +12147 1869 1868 1568 3662 +12148 2949 3433 3395 3471 +12149 769 812 3132 923 +12150 200 199 1238 3722 +12151 2995 2978 3318 3478 +12152 1610 1570 3420 3618 +12153 1826 3393 3391 3394 +12154 1313 3213 242 3683 +12155 1504 1747 1640 3282 +12156 1809 3315 1840 3428 +12157 1434 3416 1435 3417 +12158 1059 1185 1143 3560 +12159 2424 3257 2347 3771 +12160 2357 3293 2518 3440 +12161 1773 3223 267 3690 +12162 2183 2147 2231 3034 +12163 1027 3333 1248 3660 +12164 415 3130 414 853 +12165 2948 2909 3420 3662 +12166 345 2555 344 3602 +12167 2808 3519 2806 3727 +12168 2805 3415 2804 3727 +12169 2660 2650 2968 3285 +12170 351 2360 352 3580 +12171 2353 2432 3355 3539 +12172 2385 2327 2453 3225 +12173 249 3493 1363 3708 +12174 763 3133 364 3161 +12175 2996 3459 3318 3561 +12176 944 3368 185 3507 +12177 3524 3597 322 3600 +12178 2303 2452 3236 3771 +12179 2282 1589 1613 3240 +12180 2618 2900 2858 3207 +12181 2804 3415 3629 3727 +12182 813 806 912 3258 +12183 2025 3436 2006 3760 +12184 873 782 3258 3537 +12185 2521 2309 2369 3366 +12186 1214 1306 1072 3199 +12187 172 171 974 3599 +12188 2708 2843 3345 3728 +12189 1181 3307 1024 3646 +12190 2413 2323 3388 3695 +12191 1155 3673 3674 3675 +12192 1669 1598 1890 3289 +12193 259 1337 258 3744 +12194 2691 2695 3331 3386 +12195 2392 2310 2387 3406 +12196 2200 450 2134 2183 +12197 2270 2173 2109 3202 +12198 2987 2917 2938 3679 +12199 934 805 365 878 +12200 1975 3271 1976 3375 +12201 2955 2958 3248 3476 +12202 2465 2328 2418 3608 +12203 2633 2636 2665 3336 +12204 2633 2812 3390 3391 +12205 2911 3328 2912 3521 +12206 1129 1033 1101 3685 +12207 2901 3420 3317 3618 +12208 3125 3149 807 3185 +12209 2637 3325 2638 3351 +12210 2735 3436 2824 3760 +12211 785 877 3533 3534 +12212 1102 1011 1266 3770 +12213 2410 3316 2321 3379 +12214 993 191 3716 3755 +12215 3193 3302 1023 3560 +12216 2536 2330 2437 3697 +12217 347 3598 3595 3613 +12218 2043 3242 1599 3243 +12219 3275 3407 1898 3764 +12220 2742 3282 2827 3312 +12221 3140 27 361 762 +12222 268 3501 3223 3502 +12223 2012 3444 3633 3682 +12224 1851 1597 1598 3637 +12225 1759 3699 1815 3768 +12226 2216 2196 2138 3740 +12227 2814 2793 3617 3618 +12228 1507 3263 2016 3620 +12229 2567 3573 2561 3639 +12230 2866 3394 2817 3396 +12231 3021 446 3352 3657 +12232 2255 26 2251 3229 +12233 2945 3248 2947 3682 +12234 2927 3514 2659 3616 +12235 1011 3440 3293 3770 +12236 3044 336 2115 3050 +12237 1342 1341 1344 3653 +12238 2118 2255 26 2251 +12239 2389 2522 2541 3528 +12240 1600 3447 3250 3705 +12241 2203 1441 1539 3518 +12242 1181 3757 1050 3758 +12243 3466 3509 2360 3779 +12244 2705 3336 2636 3624 +12245 1417 3441 1416 3442 +12246 1193 1090 1150 3630 +12247 3226 3237 451 3587 +12248 2034 1924 3232 3394 +12249 3372 3661 1079 3763 +12250 229 3252 1235 3761 +12251 222 221 1371 3748 +12252 2888 2665 3336 3425 +12253 2287 1447 1442 3587 +12254 1285 1236 1087 3257 +12255 29 391 2779 3638 +12256 2374 2436 3234 3773 +12257 3271 3475 1975 3530 +12258 314 3551 2087 3639 +12259 1600 1601 3250 3447 +12260 2213 2272 2135 3587 +12261 1121 1279 797 3224 +12262 1120 1277 2281 3313 +12263 1121 838 1186 3457 +12264 2588 2780 3299 3677 +12265 3015 3001 3542 3545 +12266 337 2161 2290 2234 +12267 1314 1316 1378 3213 +12268 3270 3353 1943 3465 +12269 2839 3737 2838 3738 +12270 1621 3351 1620 3365 +12271 1122 925 1280 3274 +12272 2085 2097 3298 3556 +12273 1005 943 1006 3368 +12274 2610 2711 3266 3350 +12275 1378 1316 1379 3683 +12276 387 3655 3656 3712 +12277 388 389 3711 3713 +12278 378 3337 2408 3761 +12279 1478 2047 1678 3331 +12280 2971 2622 3387 3733 +12281 2342 3267 2496 3566 +12282 1052 1184 3225 3473 +12283 1268 1237 3323 3651 +12284 3570 3572 354 3718 +12285 1775 2241 1774 3586 +12286 2572 3202 26 3463 +12287 3622 3667 2495 3734 +12288 1155 3674 3452 3675 +12289 2387 3372 2519 3763 +12290 1034 1241 1103 3763 +12291 2026 3395 1612 3433 +12292 1969 1812 2071 3649 +12293 2737 3303 2892 3600 +12294 1929 3396 3394 3760 +12295 419 3537 3534 3641 +12296 2282 2215 1589 3240 +12297 2759 3334 2830 3536 +12298 2742 2827 2857 3312 +12299 201 3356 3721 3722 +12300 1466 1464 1465 3419 +12301 2201 3202 180 3229 +12302 1963 2013 1962 3635 +12303 2982 2851 2981 3700 +12304 976 1004 939 3358 +12305 2034 2035 3394 3395 +12306 1974 1967 1977 3475 +12307 1855 3525 3632 3668 +12308 1214 3199 1072 3377 +12309 1843 3276 1595 3637 +12310 1231 1023 3302 3560 +12311 1055 1204 3347 3348 +12312 1025 3559 1213 3630 +12313 2776 446 3262 3398 +12314 1555 3557 311 3564 +12315 1650 3321 1649 3329 +12316 1983 1984 1982 3330 +12317 2609 2755 2608 3227 +12318 1812 3320 1810 3649 +12319 3372 3406 1079 3661 +12320 2745 2819 3453 3777 +12321 3542 3543 1400 3545 +12322 3416 3417 2687 3455 +12323 1152 1110 1045 3693 +12324 3149 3185 417 858 +12325 1567 1591 2213 3237 +12326 1424 1423 1425 3373 +12327 2226 25 332 3290 +12328 1486 1527 3221 3222 +12329 1177 3719 3355 3723 +12330 2209 3072 2113 2177 +12331 870 28 884 3301 +12332 1503 3262 1502 3419 +12333 2274 3066 2167 2230 +12334 1890 1765 3422 3446 +12335 235 1301 234 3362 +12336 386 3500 3714 3748 +12337 2755 3194 2709 3220 +12338 901 3195 859 3672 +12339 1788 1767 1766 3280 +12340 2925 3344 3245 3345 +12341 407 408 2587 3609 +12342 842 1444 855 3460 +12343 1702 1945 1808 3561 +12344 28 3658 3246 3683 +12345 2421 2546 3362 3673 +12346 3109 3132 3160 812 +12347 1484 1483 1486 3288 +12348 1169 1267 1037 3260 +12349 1963 3634 3633 3635 +12350 2771 2770 3563 3591 +12351 3259 1936 3343 3772 +12352 1827 3393 1929 3396 +12353 2479 2335 2381 3650 +12354 3493 3494 3014 3496 +12355 1354 3724 3450 3725 +12356 164 3553 1001 3578 +12357 2561 3553 3551 3639 +12358 2318 2531 3252 3622 +12359 1397 3486 3485 3487 +12360 1505 1704 1514 3615 +12361 1615 264 15 835 +12362 2107 2109 2173 3202 +12363 1999 2006 2025 3652 +12364 3565 3641 2841 3728 +12365 1272 1084 1047 3379 +12366 1876 1593 2187 3604 +12367 1031 3337 3622 3667 +12368 1671 3227 1535 3309 +12369 1077 1043 1176 3673 +12370 2316 3477 2439 3583 +12371 2874 423 3310 3429 +12372 195 986 3580 3585 +12373 1255 3380 3379 3467 +12374 1224 1172 3268 3752 +12375 2743 3411 2744 3774 +12376 1617 1609 2196 3740 +12377 165 995 166 3754 +12378 896 3373 425 3672 +12379 342 343 3463 3766 +12380 1886 3514 2062 3616 +12381 233 1329 234 3745 +12382 3383 3587 1440 3607 +12383 2765 2596 2684 3505 +12384 2719 3419 2583 3540 +12385 1493 1494 3241 3689 +12386 2086 312 311 3554 +12387 2642 3250 2641 3447 +12388 2529 2345 2363 3279 +12389 418 858 785 860 +12390 1563 3322 2044 3680 +12391 2179 2239 341 2118 +12392 2692 3235 3196 3581 +12393 1319 3294 235 3669 +12394 2429 2340 2480 3438 +12395 1451 1845 1449 3505 +12396 2701 2703 2702 3400 +12397 1306 1127 3199 3269 +12398 1750 2022 1751 3218 +12399 1039 3367 1162 3549 +12400 1481 1653 1482 3607 +12401 948 205 2217 3284 +12402 1597 3446 1598 3637 +12403 2293 3380 3269 3467 +12404 2952 3320 2979 3649 +12405 442 3357 2893 3502 +12406 167 990 987 3718 +12407 1349 1312 3291 3513 +12408 1031 1137 3667 3734 +12409 2928 2624 3344 3733 +12410 2134 2200 2184 3587 +12411 2740 3304 2669 3431 +12412 1975 3375 1974 3475 +12413 2198 1774 3586 3588 +12414 230 3732 1286 3761 +12415 3517 3550 1133 3706 +12416 1087 3257 1236 3643 +12417 1633 1727 1645 3733 +12418 1625 3416 1434 3417 +12419 760 3149 3112 3136 +12420 829 848 781 3456 +12421 926 1407 859 3195 +12422 1814 3422 1900 3727 +12423 1301 1176 3362 3673 +12424 383 3493 3707 3708 +12425 2669 2831 3431 3710 +12426 829 1150 146 872 +12427 1416 3409 1414 3443 +12428 2801 3454 3416 3455 +12429 2740 3364 2739 3730 +12430 2534 2469 2299 3197 +12431 2216 2138 455 3740 +12432 1142 3466 193 3716 +12433 1861 1862 1712 3756 +12434 1532 266 3262 3690 +12435 1602 1600 1776 3705 +12436 1597 3407 1596 3637 +12437 1891 3529 3317 3618 +12438 2666 2641 3243 3447 +12439 1874 3270 1943 3465 +12440 3246 3352 1391 3658 +12441 2998 3228 2854 3520 +12442 3654 3655 1388 3656 +12443 3132 3163 3116 875 +12444 257 1343 256 3547 +12445 876 783 891 3301 +12446 1030 1099 1104 3583 +12447 1993 3611 3610 3612 +12448 2898 2845 2897 3471 +12449 2038 3364 1986 3538 +12450 2613 3208 2797 3374 +12451 1766 3289 1890 3422 +12452 3133 805 851 763 +12453 2977 2897 3273 3471 +12454 2184 3383 2134 3587 +12455 2169 1586 1594 3762 +12456 2463 3539 2414 3752 +12457 247 246 3498 3746 +12458 267 1773 268 3223 +12459 418 3534 3533 3641 +12460 2863 2862 2818 3211 +12461 2395 2481 2342 3203 +12462 1055 3204 1218 3348 +12463 1519 3540 1518 3624 +12464 2724 3212 2721 3392 +12465 3568 3643 1308 3776 +12466 1199 3197 1230 3452 +12467 1943 3353 1942 3465 +12468 2134 2203 2252 3383 +12469 1185 1231 1053 3560 +12470 3520 3699 2076 3700 +12471 1952 2064 3328 3648 +12472 256 1346 255 3642 +12473 1988 1989 3530 3679 +12474 759 805 3127 934 +12475 2363 3279 2464 3729 +12476 2791 2794 3317 3529 +12477 376 2547 3314 3732 +12478 456 2833 3628 3737 +12479 1519 1518 1847 3624 +12480 3211 3341 2863 3715 +12481 763 364 878 798 +12482 2497 2294 3418 3560 +12483 3494 3496 1394 3497 +12484 2493 3314 2547 3732 +12485 2958 2947 2955 3248 +12486 2466 2423 2358 3734 +12487 1294 3467 1008 3687 +12488 2774 3363 3214 3469 +12489 2723 2721 2724 3212 +12490 2772 2874 2608 3310 +12491 1983 1984 3330 3664 +12492 2085 3231 160 3556 +12493 3211 3635 2937 3636 +12494 1179 3402 1303 3693 +12495 2439 3461 2529 3583 +12496 423 898 779 844 +12497 2594 3265 2711 3350 +12498 2746 2850 2941 3531 +12499 1852 1865 1864 3207 +12500 1018 1202 1111 3688 +12501 2522 2344 3225 3473 +12502 27 2468 361 3224 +12503 941 943 1005 3200 +12504 2872 3207 2618 3458 +12505 2988 3404 2986 3428 +12506 1127 3199 3269 3467 +12507 376 3484 3483 3653 +12508 1818 3198 1838 3400 +12509 1995 1953 2047 3331 +12510 1498 1860 3312 3325 +12511 1722 3264 1692 3733 +12512 2579 2775 2784 3222 +12513 222 1366 223 3619 +12514 1148 2185 210 2228 +12515 2115 3044 2161 2290 +12516 2437 2388 2306 3780 +12517 2707 3349 2703 3400 +12518 805 846 759 3127 +12519 3018 3501 3654 3655 +12520 3468 3643 1236 3644 +12521 336 337 2290 2136 +12522 3255 3426 2677 3775 +12523 396 3596 3597 3600 +12524 1820 1619 3198 3738 +12525 1214 3377 1018 3780 +12526 1339 3593 1340 3642 +12527 1400 3544 3542 3545 +12528 2858 2900 2718 3244 +12529 2405 3568 3769 3770 +12530 3206 3478 2884 3519 +12531 2907 3353 2944 3387 +12532 3005 3487 3486 3488 +12533 1463 1432 1435 3455 +12534 1623 1771 1477 3365 +12535 2872 2618 2619 3458 +12536 1589 3241 1492 3638 +12537 420 419 905 3136 +12538 1482 3607 3312 3701 +12539 2343 2510 2379 3283 +12540 342 26 3342 3358 +12541 2432 2549 3355 3356 +12542 1651 3189 1653 3226 +12543 2038 1630 1629 3431 +12544 3490 3615 274 3620 +12545 2727 3607 449 3701 +12546 883 797 899 3224 +12547 2244 938 937 3229 +12548 2474 3427 2400 3619 +12549 2437 2506 3377 3780 +12550 2149 2251 3202 3229 +12551 1140 1308 3643 3776 +12552 2747 2745 3453 3532 +12553 1584 3739 3621 3740 +12554 1016 1200 3203 3267 +12555 1680 3196 1678 3386 +12556 1928 1927 1930 3682 +12557 1173 1045 1110 3302 +12558 3214 3363 1497 3469 +12559 996 164 1001 3578 +12560 1134 1057 1095 3751 +12561 1743 1715 1742 3357 +12562 881 781 826 3456 +12563 2627 3611 3530 3664 +12564 1557 1695 1551 3206 +12565 981 3585 3577 3681 +12566 779 828 916 3340 +12567 2245 2123 334 3753 +12568 1768 3338 1421 3458 +12569 2115 3044 2202 2161 +12570 3295 3363 32 3469 +12571 3282 3312 2742 3325 +12572 334 2123 333 3753 +12573 3485 3487 378 3726 +12574 812 3109 3163 922 +12575 1665 1664 877 3534 +12576 198 1147 199 3384 +12577 380 379 3487 3724 +12578 161 961 3555 3765 +12579 1136 1182 1307 3378 +12580 2939 3531 3459 3532 +12581 1276 1136 3461 3698 +12582 3286 3287 2714 3715 +12583 2977 3433 2949 3471 +12584 2378 2308 2511 3333 +12585 1052 3197 1259 3473 +12586 2099 2087 3553 3639 +12587 2657 2658 2805 3415 +12588 2383 385 386 3605 +12589 3379 3467 2446 3781 +12590 198 977 197 3644 +12591 1539 2159 2203 3518 +12592 2692 3196 3249 3581 +12593 1504 3282 1498 3312 +12594 233 3362 3361 3745 +12595 1532 3262 1503 3540 +12596 1991 3194 1858 3220 +12597 2666 3285 2660 3447 +12598 253 1356 3487 3726 +12599 2952 2913 2979 3320 +12600 2742 3312 2726 3325 +12601 1814 1900 3629 3727 +12602 26 2255 341 3284 +12603 1167 3323 3193 3372 +12604 2827 2810 2797 3208 +12605 362 3457 2500 3566 +12606 2063 1679 2047 3521 +12607 2307 2449 3646 3757 +12608 3269 3380 1123 3467 +12609 3514 3525 2985 3645 +12610 2384 3267 2502 3579 +12611 1881 1879 1880 3526 +12612 872 1150 146 1090 +12613 2556 3596 3595 3598 +12614 2928 3479 2624 3733 +12615 2033 2056 3565 3728 +12616 251 1362 250 3491 +12617 2820 2871 2912 3521 +12618 2675 2895 3416 3775 +12619 1702 1809 1701 3428 +12620 1163 1293 1120 3670 +12621 429 3469 3541 3542 +12622 2090 3576 3575 3577 +12623 952 204 976 3766 +12624 1188 1095 2220 3751 +12625 386 385 3500 3748 +12626 1424 3340 1422 3373 +12627 1748 1822 1897 3190 +12628 885 1841 842 3460 +12629 2079 2068 3335 3345 +12630 1010 3697 1156 3763 +12631 1649 3329 3321 3385 +12632 947 946 950 3766 +12633 1111 1233 3567 3568 +12634 1921 3629 3415 3727 +12635 2612 2611 2610 3365 +12636 760 3149 418 858 +12637 383 3493 3496 3707 +12638 2318 3252 2408 3337 +12639 2599 3288 3222 3319 +12640 337 3360 338 3432 +12641 2569 3451 2554 3464 +12642 1140 3643 3468 3776 +12643 3318 3459 1782 3561 +12644 1789 1766 3422 3423 +12645 1857 3194 1799 3227 +12646 2182 2137 2237 3347 +12647 3466 3716 1142 3717 +12648 2278 3027 2168 2130 +12649 1109 3388 1175 3695 +12650 347 3601 3598 3613 +12651 437 3490 3488 3620 +12652 1170 1307 1042 3378 +12653 3211 3635 1950 3715 +12654 2372 3687 2450 3688 +12655 2255 26 341 2118 +12656 2086 2097 3556 3557 +12657 1403 1401 1390 3311 +12658 999 997 3578 3754 +12659 2755 2730 2731 3280 +12660 2492 2377 2313 3666 +12661 2610 2611 2711 3350 +12662 232 1335 233 3745 +12663 1018 1111 1233 3567 +12664 812 774 3109 922 +12665 1516 1514 1515 3495 +12666 445 3009 3654 3657 +12667 2048 1510 1512 3396 +12668 2690 3359 3275 3629 +12669 3634 3635 1803 3636 +12670 2367 2320 2443 3749 +12671 2672 3631 3633 3682 +12672 1974 1975 1976 3375 +12673 2572 2554 2575 3463 +12674 2675 2677 2895 3775 +12675 1659 1523 1663 3641 +12676 2051 3217 1877 3443 +12677 31 3352 446 3398 +12678 827 758 3155 844 +12679 250 3491 1362 3709 +12680 2890 3303 2741 3730 +12681 271 3494 3497 3659 +12682 332 25 2538 3290 +12683 2952 3424 3320 3649 +12684 2639 2637 2826 3282 +12685 1617 2196 1609 2276 +12686 2054 1621 1477 3365 +12687 1657 3258 1658 3537 +12688 899 895 27 3200 +12689 1255 1042 3379 3380 +12690 898 3128 922 758 +12691 1932 1931 1892 3346 +12692 226 1257 225 3725 +12693 969 3601 973 3613 +12694 2012 3444 1965 3633 +12695 2602 2724 2770 3392 +12696 2749 3526 2836 3742 +12697 2522 2389 2344 3473 +12698 1294 1008 1135 3687 +12699 1664 3533 877 3534 +12700 3149 760 418 419 +12701 1783 1581 1691 3604 +12702 1695 2075 1696 3206 +12703 1734 1564 1686 3680 +12704 1160 1198 1022 3665 +12705 314 3506 3551 3639 +12706 1037 3257 1087 3771 +12707 884 789 843 3213 +12708 2301 2422 3306 3445 +12709 1795 3271 1975 3530 +12710 1884 1660 1662 3255 +12711 1703 2017 2037 3292 +12712 415 2900 3207 3460 +12713 1487 1710 1467 3515 +12714 359 3507 360 3765 +12715 1983 3329 1984 3664 +12716 2408 2318 2531 3252 +12717 2336 3230 2400 3427 +12718 2557 3597 3598 3599 +12719 3393 3396 1735 3425 +12720 210 1091 1148 2228 +12721 2793 2813 2812 3390 +12722 1433 1432 1470 3417 +12723 1042 3380 1201 3381 +12724 3270 3423 2758 3465 +12725 1624 1574 1738 3563 +12726 366 3630 2425 3704 +12727 1664 121 877 3533 +12728 1673 1675 1893 3277 +12729 1489 3215 3564 3677 +12730 2601 3288 2599 3319 +12731 371 25 3019 3543 +12732 1482 3312 1860 3701 +12733 3361 3362 1261 3695 +12734 1021 3236 1245 3268 +12735 1023 3193 1173 3302 +12736 1158 3267 1219 3559 +12737 3492 3493 1395 3494 +12738 937 948 2244 3229 +12739 1010 3661 1100 3696 +12740 2413 3675 2477 3695 +12741 2423 3623 3622 3734 +12742 440 441 3494 3659 +12743 1349 1377 1312 3513 +12744 3575 3577 351 3681 +12745 1498 3312 3282 3325 +12746 1780 3699 3326 3700 +12747 1076 3549 3296 3706 +12748 782 860 419 3537 +12749 1837 3212 1838 3349 +12750 3002 3546 3012 3547 +12751 1727 1633 1720 3344 +12752 1783 1691 3272 3604 +12753 1254 1022 1168 3665 +12754 762 895 27 899 +12755 1555 1489 3215 3564 +12756 847 1423 3373 3672 +12757 1131 1041 1096 3753 +12758 2559 2565 3575 3576 +12759 1393 3501 3500 3655 +12760 1506 3327 1513 3526 +12761 1920 2036 3285 3772 +12762 787 888 845 3200 +12763 2690 2896 3275 3359 +12764 914 793 845 3231 +12765 1548 3239 1549 3251 +12766 2502 2491 2364 3332 +12767 3422 3423 2809 3727 +12768 1244 3418 1007 3773 +12769 1538 3469 283 3541 +12770 2925 2926 3344 3345 +12771 174 3595 2092 3598 +12772 2644 436 2670 3292 +12773 1158 1275 3267 3579 +12774 2261 3066 455 454 +12775 1101 3625 1247 3626 +12776 1460 3336 1847 3624 +12777 237 1277 1293 3290 +12778 1874 1943 1873 3465 +12779 166 990 167 3570 +12780 2983 3514 2985 3645 +12781 2210 2284 2123 3753 +12782 859 1407 1406 3195 +12783 2778 3262 2583 3419 +12784 1798 1676 3207 3460 +12785 2877 3315 2916 3606 +12786 1540 3240 1541 3518 +12787 2945 3444 3248 3682 +12788 2774 428 32 3469 +12789 1761 3253 1779 3324 +12790 2024 1611 2000 3433 +12791 2506 3567 3377 3780 +12792 2287 1442 3383 3587 +12793 1344 3653 3732 3761 +12794 2794 2901 3317 3618 +12795 1736 3393 1735 3425 +12796 2887 3281 2943 3515 +12797 1152 3203 3693 3694 +12798 2041 320 3522 3558 +12799 3707 3708 1365 3759 +12800 2299 2477 2413 3675 +12801 1503 3419 1520 3540 +12802 1244 1059 1143 3234 +12803 1685 3349 1683 3512 +12804 2728 3422 3289 3423 +12805 283 3469 1387 3542 +12806 2715 3281 2887 3286 +12807 1906 2023 3434 3476 +12808 1632 1932 2068 3346 +12809 1051 3445 3306 3778 +12810 1488 1948 2065 3715 +12811 1882 1631 1711 3304 +12812 28 3246 3213 3683 +12813 899 3200 27 3224 +12814 1881 2007 2031 3742 +12815 3207 3244 1798 3460 +12816 320 1730 319 3558 +12817 1701 1702 3428 3561 +12818 1791 1557 1792 3519 +12819 3549 3550 2403 3706 +12820 2397 3643 3468 3644 +12821 1698 3387 1552 3404 +12822 1052 1230 1199 3197 +12823 1500 1498 1499 3325 +12824 3410 3411 277 3482 +12825 1992 3261 3399 3612 +12826 1459 3336 1461 3503 +12827 3497 3498 1389 3499 +12828 2960 2929 2860 3218 +12829 2295 3688 2405 3770 +12830 2215 2257 2159 3518 +12831 1554 803 859 3672 +12832 1366 1371 1367 3746 +12833 3163 875 922 758 +12834 2681 2685 3455 3562 +12835 2230 453 3066 454 +12836 1573 1654 3322 3324 +12837 1620 1623 3365 3730 +12838 1102 1087 3769 3771 +12839 1928 3248 1918 3444 +12840 3026 3080 3049 2174 +12841 2665 2889 2825 3393 +12842 1157 1181 1064 3608 +12843 2462 2300 2388 3763 +12844 2681 3417 2682 3741 +12845 2138 454 455 3740 +12846 1761 1572 3253 3324 +12847 2776 3262 3239 3398 +12848 1277 237 2232 3290 +12849 2758 2808 2809 3423 +12850 3208 3374 1746 3504 +12851 1557 3270 1792 3519 +12852 2803 3470 2802 3680 +12853 1895 1744 1923 3390 +12854 1831 1832 1689 3359 +12855 1851 1425 1597 3369 +12856 360 3507 3368 3765 +12857 3546 3547 1385 3684 +12858 1946 1947 2021 3531 +12859 1992 3261 1871 3399 +12860 2874 3310 2772 3429 +12861 1762 1760 3253 3254 +12862 3004 3485 3482 3486 +12863 1711 3228 1713 3430 +12864 314 3300 3506 3639 +12865 3357 3499 269 3502 +12866 2641 3250 3243 3447 +12867 1523 3565 2056 3728 +12868 266 267 3654 3690 +12869 264 1615 1592 3398 +12870 262 1377 1349 3513 +12871 2775 2579 2580 3214 +12872 1848 1518 3540 3624 +12873 2226 2240 25 3290 +12874 2149 3202 2201 3229 +12875 2251 26 3202 3229 +12876 1077 3673 1155 3675 +12877 1848 3403 1605 3624 +12878 380 2517 3450 3725 +12879 2318 3622 3337 3667 +12880 1544 2212 1409 3590 +12881 282 281 1770 3541 +12882 800 3140 880 823 +12883 2918 2862 2937 3211 +12884 2565 351 3575 3577 +12885 2400 3230 3584 3619 +12886 1653 1740 1482 3189 +12887 2756 2902 2802 3512 +12888 2547 2493 2346 3314 +12889 2998 3228 3520 3710 +12890 1272 1047 1107 3781 +12891 2427 2488 2301 3676 +12892 1669 1598 3289 3429 +12893 1009 3283 1124 3528 +12894 1469 1488 2065 3715 +12895 2980 3327 2733 3495 +12896 2520 3306 2442 3614 +12897 2966 3409 3292 3410 +12898 2049 1921 1830 3415 +12899 2778 2782 412 3419 +12900 2402 3749 2329 3750 +12901 351 3585 3580 3681 +12902 1139 3666 3337 3667 +12903 1433 3426 3417 3741 +12904 189 190 999 3437 +12905 1183 1061 1223 3225 +12906 1846 1526 3308 3764 +12907 2893 442 2886 3357 +12908 1569 1867 3434 3662 +12909 1716 3357 269 3502 +12910 1480 3261 1994 3331 +12911 1071 3260 1287 3539 +12912 1409 2256 1410 3205 +12913 2580 2774 3214 3469 +12914 1201 1123 1032 3380 +12915 2549 344 3355 3356 +12916 1110 1053 1231 3302 +12917 2050 1919 2055 3343 +12918 2880 3286 3515 3606 +12919 1381 3493 249 3496 +12920 1136 1307 1099 3461 +12921 2323 2385 3388 3640 +12922 827 3155 3142 425 +12923 980 170 981 3585 +12924 1084 3378 3316 3379 +12925 255 254 3483 3653 +12926 1822 3219 3190 3226 +12927 1354 3450 227 3725 +12928 1558 3255 1576 3774 +12929 354 355 3570 3755 +12930 2149 2270 2201 3202 +12931 2843 3335 3345 3728 +12932 397 3524 2737 3600 +12933 194 989 193 3466 +12934 955 160 1006 3765 +12935 1751 2022 2019 3531 +12936 2196 1617 297 2276 +12937 1584 1618 1836 3739 +12938 334 3348 3347 3753 +12939 1270 1036 1145 3314 +12940 1550 1552 1699 3353 +12941 2469 2418 2328 3197 +12942 2814 2815 3232 3617 +12943 1190 1295 3582 3758 +12944 1907 1618 2052 3738 +12945 2951 3648 2869 3649 +12946 1528 1531 1849 3221 +12947 2029 3259 1934 3700 +12948 271 270 3357 3497 +12949 3264 3527 1692 3733 +12950 3622 3623 1105 3734 +12951 1043 3673 1077 3675 +12952 800 3140 3114 880 +12953 1414 2060 2051 3409 +12954 2801 3416 2687 3455 +12955 2966 2655 2646 3409 +12956 1868 1694 1693 3479 +12957 1685 2046 2045 3512 +12958 1324 3669 1323 3744 +12959 2567 356 2561 3573 +12960 2420 2478 3355 3723 +12961 2378 2430 2308 3333 +12962 3205 1543 3590 3747 +12963 947 3358 946 3766 +12964 2838 3738 3737 3739 +12965 2020 2022 1757 3326 +12966 1848 1518 1520 3540 +12967 2489 3193 2348 3302 +12968 2952 2913 3320 3424 +12969 2735 2663 2824 3436 +12970 2898 3471 2970 3652 +12971 3232 3394 2815 3395 +12972 1980 3315 1714 3606 +12973 1865 1606 1603 3421 +12974 3057 25 332 2117 +12975 1988 1987 1989 3679 +12976 790 885 842 3460 +12977 3381 3382 1012 3414 +12978 1667 277 276 3410 +12979 1666 3533 1664 3534 +12980 1160 1022 1265 3278 +12981 2985 3525 3514 3668 +12982 1760 2057 2058 3616 +12983 384 385 3619 3746 +12984 335 2411 336 3307 +12985 2321 3378 2365 3380 +12986 325 3594 2093 3603 +12987 2734 2817 3393 3396 +12988 3021 3020 3010 3658 +12989 1979 1955 1957 3453 +12990 271 3494 1394 3497 +12991 2076 3520 2053 3699 +12992 435 3482 3410 3486 +12993 201 3721 967 3722 +12994 2954 2965 2979 3320 +12995 2478 2414 3539 3752 +12996 1488 3281 1468 3341 +12997 2921 2750 2645 3217 +12998 416 3458 2761 3535 +12999 279 3480 280 3684 +13000 1031 1235 1089 3337 +13001 2580 429 428 3469 +13002 1021 1224 1172 3268 +13003 2627 3530 2919 3664 +13004 2294 2392 2494 3560 +13005 1032 3269 1289 3696 +13006 1411 3300 316 3449 +13007 1732 3416 3376 3454 +13008 820 3533 1778 3535 +13009 2736 2886 2732 3238 +13010 1554 1406 1553 3672 +13011 1762 2057 1760 3254 +13012 2103 2092 3597 3598 +13013 2528 3236 2419 3268 +13014 316 3449 3300 3571 +13015 3584 3619 1144 3759 +13016 376 3642 3484 3653 +13017 1078 3230 1035 3477 +13018 2957 2747 3453 3462 +13019 253 1397 3485 3487 +13020 1194 1049 3293 3439 +13021 847 803 1423 3672 +13022 1706 3364 1629 3730 +13023 2103 172 3598 3599 +13024 1511 3192 1517 3238 +13025 261 1325 260 3543 +13026 3195 1553 3672 3743 +13027 319 3574 2101 3576 +13028 1068 1240 1299 3702 +13029 2456 3360 2329 3749 +13030 1341 1339 1340 3642 +13031 1662 1884 3255 3426 +13032 1935 2050 1862 3756 +13033 1498 1859 1860 3325 +13034 1277 2232 2181 3290 +13035 2714 3286 2880 3287 +13036 2944 3245 2971 3387 +13037 2951 3647 3648 3649 +13038 1488 1469 1468 3281 +13039 2792 3201 2620 3389 +13040 439 3494 3492 3495 +13041 1786 3617 1923 3618 +13042 346 2552 347 3384 +13043 1455 1450 1806 3216 +13044 1575 3562 3511 3563 +13045 1300 3427 1069 3605 +13046 2416 3466 2360 3779 +13047 452 3226 3219 3237 +13048 3289 3422 1766 3423 +13049 378 3485 3017 3487 +13050 1723 1722 1698 3264 +13051 2268 2169 1594 3762 +13052 1924 3232 3394 3617 +13053 455 3739 3737 3740 +13054 2564 3602 3594 3603 +13055 844 778 828 3340 +13056 1483 3288 1485 3319 +13057 2089 3574 3572 3575 +13058 3259 3343 1935 3756 +13059 1389 270 3497 3499 +13060 1564 3455 1562 3680 +13061 3492 3495 273 3615 +13062 2388 2300 2438 3763 +13063 2643 3242 2860 3243 +13064 1934 3259 1935 3756 +13065 2937 3635 3211 3715 +13066 1933 2033 2056 3565 +13067 2772 2689 2607 3289 +13068 28 884 3213 3246 +13069 1640 1639 1499 3282 +13070 1833 3359 1784 3415 +13071 2939 3459 2942 3532 +13072 1952 3647 1969 3648 +13073 1677 1637 1676 3458 +13074 2640 3447 3448 3705 +13075 2967 2956 2621 3527 +13076 3136 760 905 811 +13077 3109 3163 3132 812 +13078 2835 2832 2842 3565 +13079 1146 3650 191 3651 +13080 1067 3666 1232 3698 +13081 1404 1402 815 3246 +13082 1160 3366 1198 3665 +13083 1234 1056 3517 3704 +13084 1530 3233 1494 3689 +13085 1007 3418 1282 3778 +13086 2601 2598 2599 3288 +13087 2526 2400 3230 3584 +13088 999 998 997 3754 +13089 2595 2591 3233 3689 +13090 2396 3379 2321 3380 +13091 876 1280 825 3301 +13092 2471 2345 2529 3461 +13093 1415 3442 1416 3443 +13094 2269 2171 2145 3311 +13095 1295 1171 3750 3757 +13096 271 3357 1743 3659 +13097 2862 2918 2920 3271 +13098 3167 880 3140 823 +13099 1286 3252 229 3761 +13100 2669 3228 2998 3710 +13101 388 3656 389 3713 +13102 1463 1485 3288 3562 +13103 2196 2233 1617 3628 +13104 2566 3572 3569 3574 +13105 1396 3488 3487 3489 +13106 1655 3586 3588 3591 +13107 3468 3585 350 3736 +13108 2735 2734 2736 3396 +13109 2619 3338 2761 3458 +13110 385 3427 2474 3619 +13111 2406 2345 2553 3279 +13112 2809 2808 2806 3727 +13113 1654 2059 2066 3385 +13114 2930 3634 3632 3767 +13115 1023 1173 1231 3302 +13116 1002 163 3552 3691 +13117 2476 2352 3660 3661 +13118 1524 3276 1843 3677 +13119 3021 3010 3657 3658 +13120 2023 3273 1611 3434 +13121 1296 1020 1166 3640 +13122 1968 1969 1967 3647 +13123 1597 1595 3407 3637 +13124 957 3720 956 3721 +13125 320 321 3522 3523 +13126 2813 3389 2748 3390 +13127 1340 1335 232 3593 +13128 1715 3357 1716 3503 +13129 3015 372 3001 3545 +13130 782 840 860 3537 +13131 2581 2576 2577 3221 +13132 1676 1864 1798 3207 +13133 1179 3438 3402 3693 +13134 164 165 2099 3573 +13135 2702 2834 3198 3354 +13136 1532 3540 1519 3690 +13137 2678 3359 3250 3705 +13138 1421 3207 1682 3458 +13139 227 3450 1354 3724 +13140 2860 2643 2656 3242 +13141 1747 1746 1856 3504 +13142 2349 2461 3296 3711 +13143 280 3480 1883 3508 +13144 1208 3306 3773 3778 +13145 1503 3262 3419 3540 +13146 1605 1462 1460 3624 +13147 1676 1682 3207 3458 +13148 1158 3267 3559 3579 +13149 1571 3524 322 3600 +13150 170 3577 981 3585 +13151 2335 2484 2381 3323 +13152 1940 2062 1886 3514 +13153 2355 2461 2501 3549 +13154 828 931 1844 3340 +13155 2615 452 2864 3219 +13156 2804 3629 2688 3727 +13157 336 337 3044 2290 +13158 2749 2997 2751 3526 +13159 2901 2814 3420 3618 +13160 1922 3256 1639 3671 +13161 1268 1034 1146 3650 +13162 405 406 3506 3639 +13163 3005 3486 436 3488 +13164 1819 1820 1818 3198 +13165 2400 3619 3584 3759 +13166 1269 3230 1168 3665 +13167 2431 3382 2325 3414 +13168 1813 3424 3320 3768 +13169 3392 3563 2770 3591 +13170 429 3542 3541 3544 +13171 1031 1105 1137 3734 +13172 914 845 159 3231 +13173 395 396 2892 3397 +13174 1366 3707 1365 3759 +13175 1878 1877 2051 3217 +13176 347 2556 3595 3598 +13177 2500 2395 3566 3694 +13178 2871 2821 2869 3412 +13179 3002 3544 431 3546 +13180 1741 3192 1510 3436 +13181 1838 3212 1985 3349 +13182 3109 3128 3163 922 +13183 1844 931 1422 3340 +13184 283 3541 3469 3542 +13185 2936 3634 2938 3636 +13186 2962 2859 3254 3616 +13187 2527 2305 2460 3302 +13188 2068 1932 2069 3335 +13189 2973 3330 3399 3612 +13190 1219 1158 1275 3267 +13191 364 365 878 3731 +13192 2773 424 3340 3369 +13193 919 771 831 3535 +13194 2882 3322 3321 3324 +13195 1720 1724 1727 3245 +13196 3009 3010 3656 3657 +13197 1801 1975 1795 3271 +13198 2574 3298 409 3557 +13199 1531 1538 1770 3541 +13200 2640 2642 3447 3705 +13201 989 992 193 3592 +13202 824 911 798 3472 +13203 1388 3655 244 3656 +13204 3196 3235 1835 3581 +13205 342 3463 3358 3766 +13206 1160 1063 1211 3676 +13207 1736 1735 1461 3425 +13208 208 2182 1204 3753 +13209 2049 2075 1791 3519 +13210 433 2744 3411 3480 +13211 2048 3396 1929 3760 +13212 358 359 3555 3692 +13213 242 3246 1391 3658 +13214 1877 1879 1940 3217 +13215 873 2018 920 3537 +13216 2198 2211 1426 3588 +13217 2857 2899 2725 3189 +13218 3245 3344 2925 3733 +13219 2691 2694 3249 3331 +13220 180 2270 2109 3202 +13221 2803 3511 3470 3680 +13222 1438 1574 3563 3591 +13223 1852 3207 3201 3389 +13224 1769 1449 1845 3609 +13225 1406 1554 132 859 +13226 1763 3285 2036 3447 +13227 2970 2848 3652 3742 +13228 1501 3239 1502 3262 +13229 3342 3719 2545 3766 +13230 2766 3216 2767 3300 +13231 2711 3265 3266 3350 +13232 2779 2590 2591 3233 +13233 1927 1928 1918 3444 +13234 1059 3406 1215 3560 +13235 2712 3265 393 3603 +13236 3219 3226 1652 3237 +13237 2901 3420 2909 3662 +13238 2921 2647 2922 3217 +13239 1696 3206 2075 3478 +13240 1538 1537 283 3469 +13241 1638 120 1778 3535 +13242 1038 3457 1186 3566 +13243 1539 1541 2159 3518 +13244 2012 1927 1965 3444 +13245 2345 2406 2517 3279 +13246 3418 3773 2351 3778 +13247 120 820 1778 3535 +13248 1854 3525 1870 3645 +13249 162 1002 163 3552 +13250 1540 1493 1589 3240 +13251 1167 1215 1079 3372 +13252 1489 3564 1556 3677 +13253 2305 3203 2481 3693 +13254 272 3492 1395 3494 +13255 2617 2790 2759 3338 +13256 1541 1589 2215 3240 +13257 1798 3244 1445 3460 +13258 1177 1263 3355 3719 +13259 1145 3252 1286 3732 +13260 3377 3567 2376 3688 +13261 2882 2903 2976 3385 +13262 1824 327 1545 3265 +13263 1853 3514 3525 3668 +13264 257 1399 258 3547 +13265 1859 1754 1753 3325 +13266 3236 3293 2303 3771 +13267 396 3596 2570 3597 +13268 1563 1573 2044 3322 +13269 2403 3517 2356 3706 +13270 2023 3248 1928 3273 +13271 435 434 3410 3482 +13272 2564 3594 394 3603 +13273 1948 3211 1950 3715 +13274 1850 3303 1705 3304 +13275 1017 3452 1155 3674 +13276 2593 3308 3276 3764 +13277 2336 2526 2400 3230 +13278 2613 2614 2616 3190 +13279 2038 1731 1986 3364 +13280 789 3213 884 3246 +13281 1960 3462 1961 3768 +13282 1421 3201 1852 3207 +13283 1836 1587 1584 3621 +13284 2499 2380 2339 3693 +13285 1275 1200 3267 3332 +13286 2750 2645 3217 3263 +13287 3003 3484 3547 3684 +13288 2467 3584 3583 3729 +13289 366 367 3456 3704 +13290 1422 3340 931 3373 +13291 404 3300 3571 3639 +13292 204 1290 205 3284 +13293 2184 1447 2287 3587 +13294 1404 264 1391 3352 +13295 3276 3299 1843 3677 +13296 1545 1546 3233 3370 +13297 1127 3269 1123 3467 +13298 3007 3014 3494 3496 +13299 245 3655 3500 3714 +13300 1589 3240 1493 3241 +13301 192 993 191 3716 +13302 2860 2656 2960 3405 +13303 2653 2652 2654 3253 +13304 1397 1383 3486 3487 +13305 433 3480 3411 3481 +13306 2624 2925 3344 3733 +13307 860 418 419 3534 +13308 353 3572 2559 3575 +13309 783 3213 891 3301 +13310 1965 1966 2012 3633 +13311 1902 3401 1971 3522 +13312 2820 2811 3504 3521 +13313 1472 3672 1553 3743 +13314 3335 3344 2926 3345 +13315 2338 2387 2475 3661 +13316 1515 3495 272 3659 +13317 1318 1326 1327 3713 +13318 2027 1510 2048 3760 +13319 2683 3407 3275 3764 +13320 1977 2003 2002 3475 +13321 1082 1209 1256 3509 +13322 3303 3304 2741 3730 +13323 2812 2635 2633 3390 +13324 3553 3578 357 3691 +13325 1851 1804 3369 3429 +13326 323 2092 3596 3597 +13327 2326 2458 2510 3283 +13328 2905 3206 2884 3519 +13329 242 1313 241 3213 +13330 3189 3312 1482 3607 +13331 1942 3353 3191 3465 +13332 224 3708 3729 3759 +13333 1398 3481 279 3684 +13334 3567 3568 1233 3776 +13335 1121 1291 3224 3457 +13336 1737 1428 1574 3591 +13337 3472 3559 364 3731 +13338 1831 1600 3250 3705 +13339 2149 2173 2270 3202 +13340 2528 2419 2343 3268 +13341 1482 3189 1740 3312 +13342 3594 3602 2093 3603 +13343 1379 1328 217 3713 +13344 359 3556 3555 3765 +13345 1269 1239 1144 3619 +13346 1848 1603 3403 3421 +13347 946 3358 179 3463 +13348 1701 1700 1702 3561 +13349 2205 3052 2283 2163 +13350 2404 2526 3230 3477 +13351 1750 3218 1756 3371 +13352 3233 3241 1494 3689 +13353 2090 3575 169 3577 +13354 438 3615 3490 3620 +13355 2007 1881 2008 3742 +13356 1654 3321 2061 3322 +13357 2307 2362 3608 3646 +13358 1383 275 3486 3488 +13359 1811 1810 2040 3649 +13360 1636 3533 1674 3536 +13361 3267 2384 3559 3579 +13362 1422 931 847 3373 +13363 1073 1222 3623 3686 +13364 1653 3189 1482 3607 +13365 2937 3211 2863 3715 +13366 1413 317 318 3678 +13367 3352 3657 1380 3658 +13368 3520 3700 1863 3756 +13369 1438 3392 1437 3591 +13370 1665 877 840 3534 +13371 1745 3208 3190 3374 +13372 2782 3421 2720 3663 +13373 1507 2016 1703 3620 +13374 994 995 3754 3755 +13375 395 3397 394 3594 +13376 3011 3496 3497 3498 +13377 456 3628 455 3737 +13378 984 168 987 3592 +13379 1527 1528 1486 3221 +13380 2403 3549 2515 3550 +13381 1334 3712 3711 3713 +13382 1043 3675 1109 3695 +13383 177 956 950 3720 +13384 1294 3199 3467 3687 +13385 201 200 3356 3722 +13386 1024 1181 1157 3307 +13387 2618 2620 2617 3201 +13388 1652 3226 1591 3237 +13389 2052 1609 1617 3737 +13390 235 1319 236 3294 +13391 1984 1987 1988 3664 +13392 1717 1726 1718 3191 +13393 1101 3626 1243 3703 +13394 1809 1714 1840 3315 +13395 2474 2336 2400 3427 +13396 2191 285 1578 3363 +13397 1797 1897 3219 3235 +13398 2149 2201 2251 3229 +13399 1778 3533 1636 3535 +13400 1972 3522 321 3524 +13401 3411 3480 278 3481 +13402 3482 3483 1384 3485 +13403 1720 3344 2068 3345 +13404 459 3588 3586 3591 +13405 1467 3281 1469 3286 +13406 2410 2321 2504 3379 +13407 2681 2600 2598 3288 +13408 2703 2723 2702 3349 +13409 185 1291 1161 3507 +13410 1845 1846 1526 3308 +13411 2657 2656 2658 3242 +13412 3552 3553 357 3691 +13413 2867 2814 3232 3420 +13414 1709 3286 1926 3287 +13415 2715 2863 3341 3715 +13416 1332 3655 245 3714 +13417 2903 3321 2902 3329 +13418 1898 3275 1832 3629 +13419 1170 1042 1201 3381 +13420 2334 3717 2416 3779 +13421 3149 760 419 3136 +13422 1447 3383 1442 3587 +13423 2927 2922 2659 3514 +13424 1774 2241 2198 3586 +13425 1818 1817 1819 3400 +13426 2757 2795 2692 3196 +13427 1267 1071 1238 3384 +13428 2593 3276 2606 3764 +13429 2118 341 2179 3067 +13430 1392 266 3654 3657 +13431 2361 3337 2542 3666 +13432 202 958 962 3720 +13433 2635 3390 2748 3403 +13434 2358 3622 2495 3734 +13435 353 3572 3592 3718 +13436 3001 3019 3022 3543 +13437 1705 3304 3303 3730 +13438 2709 3194 2835 3210 +13439 1719 2079 2033 3728 +13440 1957 1944 1979 3777 +13441 1566 1567 2213 3237 +13442 2778 411 2776 3239 +13443 1284 3729 3584 3759 +13444 1264 3779 1028 3780 +13445 2104 3595 3594 3596 +13446 1392 3654 1388 3656 +13447 1338 1343 257 3593 +13448 1649 3321 1654 3385 +13449 1035 3230 1269 3584 +13450 2256 1409 2212 3205 +13451 171 3599 2091 3735 +13452 161 3555 2086 3556 +13453 2711 3265 2712 3266 +13454 1930 2000 3273 3682 +13455 1597 1596 3446 3637 +13456 2076 2053 1915 3699 +13457 2977 3273 2958 3434 +13458 1526 3308 3276 3677 +13459 196 1236 197 3644 +13460 3491 3492 3006 3493 +13461 27 3224 3200 3368 +13462 342 26 2537 3342 +13463 2669 2667 3228 3430 +13464 2397 3468 3643 3776 +13465 2355 3549 2403 3706 +13466 2557 3598 348 3599 +13467 256 3484 1385 3547 +13468 2054 3350 1754 3351 +13469 1866 1670 1767 3280 +13470 1267 3260 1071 3384 +13471 2040 1915 3339 3424 +13472 2622 3527 3264 3733 +13473 1726 1942 3191 3465 +13474 1329 1324 1323 3744 +13475 3018 3501 444 3654 +13476 2095 2096 179 3463 +13477 2996 3318 2915 3561 +13478 1644 1844 1668 3340 +13479 389 28 3367 3683 +13480 2612 3351 2611 3365 +13481 3215 3677 1489 3743 +13482 1381 1394 3494 3496 +13483 121 820 877 3533 +13484 353 3575 352 3592 +13485 2942 3459 2885 3777 +13486 1864 1798 3207 3244 +13487 3595 3596 2092 3598 +13488 247 1374 246 3746 +13489 1982 3330 1984 3664 +13490 3459 3532 1946 3777 +13491 1467 1469 1487 3286 +13492 2070 2079 2068 3335 +13493 1933 3194 1991 3210 +13494 1855 3525 1854 3631 +13495 2341 2514 3199 3687 +13496 1069 1269 1168 3665 +13497 2785 2599 3222 3319 +13498 937 939 1004 3229 +13499 342 3358 3342 3766 +13500 2899 2864 451 3226 +13501 2027 2025 2006 3760 +13502 1613 2282 287 1589 +13503 2879 2916 2956 3476 +13504 803 901 859 3672 +13505 3378 3379 1042 3380 +13506 282 3542 1400 3544 +13507 2895 2768 3417 3426 +13508 252 1359 251 3489 +13509 1066 3509 3567 3776 +13510 2423 3622 2358 3734 +13511 1234 1056 1133 3517 +13512 1524 1843 3299 3677 +13513 2869 3339 2952 3649 +13514 2563 3555 3556 3557 +13515 1019 1182 1136 3316 +13516 3259 3371 2028 3772 +13517 2644 2646 2645 3292 +13518 2956 2955 2879 3476 +13519 1161 3457 1038 3694 +13520 1972 1571 1902 3524 +13521 253 1356 252 3487 +13522 3013 3489 3488 3490 +13523 1888 3339 1887 3710 +13524 2375 2548 3333 3435 +13525 2317 2513 3643 3769 +13526 1995 1480 1994 3331 +13527 1394 3496 247 3498 +13528 2973 3399 2933 3612 +13529 226 227 3450 3725 +13530 1170 3381 1012 3414 +13531 1889 3431 1630 3710 +13532 969 973 970 3613 +13533 386 3500 3018 3655 +13534 1941 2066 2059 3385 +13535 2545 3719 3342 3723 +13536 397 396 3597 3600 +13537 2006 2007 2005 3742 +13538 2632 2654 2652 3254 +13539 2084 1760 2058 3474 +13540 3500 3655 386 3714 +13541 2583 3262 2582 3540 +13542 1372 1376 1373 3714 +13543 2537 341 2393 3627 +13544 1569 1611 1612 3433 +13545 1302 3719 1177 3723 +13546 457 2603 3272 3604 +13547 1214 1018 1130 3780 +13548 2339 2468 3507 3694 +13549 1711 1713 1882 3430 +13550 1386 3544 1400 3545 +13551 2398 2331 3439 3440 +13552 2366 2328 2457 3204 +13553 2989 2987 2976 3385 +13554 192 1142 193 3716 +13555 1398 3484 3481 3684 +13556 1208 3773 1007 3778 +13557 262 1349 261 3513 +13558 1154 1015 3749 3750 +13559 220 1372 221 3748 +13560 3017 3486 3005 3487 +13561 1372 3714 1373 3748 +13562 2627 2964 3475 3548 +13563 419 2841 3565 3641 +13564 1526 3276 1524 3677 +13565 429 3015 3542 3544 +13566 260 259 1400 3545 +13567 3474 3668 2081 3767 +13568 2726 3312 2725 3701 +13569 27 3231 2573 3556 +13570 2963 3375 2861 3475 +13571 444 443 2706 3501 +13572 2084 3474 2058 3668 +13573 2905 2808 3270 3519 +13574 1051 1180 3445 3778 +13575 379 378 3487 3726 +13576 2585 444 3223 3690 +13577 1600 1601 1599 3250 +13578 187 953 186 3402 +13579 2329 3646 2449 3757 +13580 229 1286 1235 3252 +13581 277 3482 1397 3486 +13582 960 3691 1002 3692 +13583 3022 3019 464 3295 +13584 2958 2977 2947 3273 +13585 780 934 365 878 +13586 2880 2887 2943 3515 +13587 1380 3657 3656 3658 +13588 1855 3631 2014 3632 +13589 2996 2885 3459 3561 +13590 3269 3696 2426 3697 +13591 1804 3340 1424 3369 +13592 1822 1652 3219 3226 +13593 2879 3287 2880 3606 +13594 1431 1716 3502 3503 +13595 2704 3399 3400 3413 +13596 1728 1763 3209 3285 +13597 3552 3554 2098 3555 +13598 3007 3494 441 3497 +13599 1116 1300 1069 3605 +13600 1125 1221 1244 3234 +13601 2622 3264 2986 3387 +13602 2654 3254 2632 3376 +13603 2200 2135 2184 3587 +13604 1970 2050 1971 3401 +13605 3493 3708 382 3709 +13606 350 3585 3577 3735 +13607 3308 3564 2587 3677 +13608 1947 1782 3318 3459 +13609 451 450 2899 3607 +13610 1443 3383 1440 3607 +13611 2675 3416 2881 3775 +13612 2496 3267 2384 3559 +13613 2560 3571 3570 3573 +13614 2987 3297 2976 3385 +13615 2467 3584 3729 3759 +13616 2440 3685 3305 3686 +13617 1867 1899 1906 3662 +13618 396 2737 2892 3600 +13619 445 3657 3654 3690 +13620 1155 3673 1077 3674 +13621 380 3487 3005 3489 +13622 2104 3594 324 3596 +13623 3583 3584 1088 3729 +13624 2272 1447 2184 3587 +13625 1232 3666 1139 3667 +13626 3449 3569 403 3571 +13627 2697 2759 2790 3277 +13628 2007 2008 2005 3742 +13629 2839 2833 2838 3737 +13630 2279 2231 3055 2168 +13631 1704 274 3615 3620 +13632 3528 3625 1033 3685 +13633 1396 3487 252 3489 +13634 3328 3548 2625 3610 +13635 3525 3631 1855 3632 +13636 2938 2994 2987 3297 +13637 161 961 162 3555 +13638 1556 1769 1525 3308 +13639 2546 3294 371 3669 +13640 1606 3390 1604 3403 +13641 1007 3773 3418 3778 +13642 2294 3234 2436 3418 +13643 1447 1440 3383 3587 +13644 1637 1768 1421 3458 +13645 1179 1303 1075 3693 +13646 442 3497 3357 3499 +13647 2907 3387 2986 3404 +13648 195 983 986 3585 +13649 1789 1790 1766 3423 +13650 2857 3189 2725 3312 +13651 790 842 853 3460 +13652 1526 1524 3308 3677 +13653 3239 3262 1501 3398 +13654 1176 1043 1261 3695 +13655 1855 3632 2081 3668 +13656 1129 3305 1271 3685 +13657 1610 1786 1570 3618 +13658 2672 3631 3632 3633 +13659 2099 3553 3573 3639 +13660 951 950 3720 3766 +13661 1664 1778 121 3533 +13662 2073 2028 3371 3772 +13663 1519 1532 1503 3540 +13664 1436 1896 1439 3212 +13665 979 3585 983 3736 +13666 1297 3356 200 3722 +13667 1380 1391 3352 3658 +13668 1215 3193 1023 3560 +13669 360 27 3368 3507 +13670 2759 2697 2830 3334 +13671 1763 2036 1602 3447 +13672 1112 1196 1019 3316 +13673 2939 2941 3531 3532 +13674 2934 3261 3399 3413 +13675 1317 242 3658 3683 +13676 2731 3280 2728 3289 +13677 1826 1929 3393 3394 +13678 2311 2502 3332 3579 +13679 414 3244 2900 3460 +13680 3014 3492 439 3494 +13681 1840 3315 3264 3428 +13682 2659 3442 2859 3616 +13683 2406 2313 3666 3698 +13684 1365 3707 1364 3708 +13685 2136 337 2290 2234 +13686 1870 3525 3514 3645 +13687 312 1769 1556 3564 +13688 1034 1268 1167 3372 +13689 2453 2299 2385 3388 +13690 1382 3490 3491 3492 +13691 986 3585 982 3681 +13692 2793 2816 2814 3617 +13693 1257 1141 225 3279 +13694 2090 2101 3575 3576 +13695 1353 3724 1352 3726 +13696 1393 1388 3501 3655 +13697 1114 1190 1009 3473 +13698 1580 3604 1581 3628 +13699 2717 3353 3270 3465 +13700 1270 3314 1068 3640 +13701 366 2425 2454 3704 +13702 2563 3555 359 3556 +13703 1478 1834 1509 3249 +13704 1735 3393 1827 3396 +13705 1631 3304 1707 3431 +13706 994 991 995 3755 +13707 2315 3467 2514 3687 +13708 2588 2780 2787 3299 +13709 387 3656 388 3712 +13710 2835 2709 2755 3194 +13711 3481 3482 3016 3483 +13712 2524 2322 2390 3260 +13713 2713 3245 3191 3345 +13714 1777 1459 1461 3503 +13715 1926 2065 1962 3715 +13716 798 911 864 3472 +13717 365 780 878 3731 +13718 2520 2442 2350 3614 +13719 2920 3475 3271 3530 +13720 931 3340 828 3373 +13721 2256 308 1410 1578 +13722 1182 3316 1084 3378 +13723 1213 3630 3559 3731 +13724 1498 3282 1499 3325 +13725 2911 3647 3328 3648 +13726 1564 1734 1635 3511 +13727 326 3451 3265 3603 +13728 1311 1310 2247 3513 +13729 1651 3190 3189 3226 +13730 884 3213 783 3301 +13731 1126 1048 1246 3510 +13732 3357 3497 270 3499 +13733 1043 1109 1175 3695 +13734 2952 3339 3424 3649 +13735 1081 3510 1026 3626 +13736 3002 3012 374 3547 +13737 2012 1927 3444 3682 +13738 840 2018 1665 3534 +13739 2067 2066 1990 3385 +13740 2133 2246 2211 3589 +13741 428 3295 32 3469 +13742 3376 3416 2801 3454 +13743 2798 3455 2685 3680 +13744 817 793 914 3231 +13745 1107 1246 1135 3781 +13746 2515 370 369 3274 +13747 1164 1074 1225 3723 +13748 1609 297 1617 2276 +13749 913 1402 241 3246 +13750 323 322 3597 3600 +13751 2252 2203 2159 3518 +13752 1537 3214 1497 3469 +13753 230 1286 229 3761 +13754 2034 2035 1924 3394 +13755 1033 3528 1124 3625 +13756 2594 2712 2711 3265 +13757 384 3496 3011 3498 +13758 1180 1025 1097 3445 +13759 873 3258 1657 3537 +13760 1111 3688 1281 3770 +13761 2328 3204 2366 3452 +13762 1668 1670 3310 3429 +13763 2776 3239 411 3398 +13764 2671 3633 3634 3635 +13765 1154 1085 3750 3752 +13766 3355 3356 1118 3539 +13767 1237 3437 3323 3651 +13768 2384 2425 3559 3579 +13769 1505 1514 1516 3327 +13770 2325 2430 2378 3381 +13771 1395 3491 250 3493 +13772 1284 3584 1144 3759 +13773 168 2089 3572 3575 +13774 2932 3632 2930 3634 +13775 1381 1395 3493 3494 +13776 1218 1055 1157 3204 +13777 1951 2077 3548 3610 +13778 2418 3473 2434 3608 +13779 2316 2370 2439 3477 +13780 2353 2432 2549 3355 +13781 1843 1474 3299 3637 +13782 2330 3269 2426 3697 +13783 410 2574 2573 3298 +13784 2317 2417 2424 3257 +13785 2794 2814 2901 3618 +13786 2325 3381 2441 3414 +13787 1074 1177 1044 3355 +13788 2018 3534 840 3537 +13789 2006 1999 2007 3742 +13790 275 274 1703 3620 +13791 351 352 3575 3681 +13792 3018 3500 3501 3655 +13793 1480 1479 1885 3249 +13794 2702 2752 2834 3354 +13795 3292 3409 2060 3410 +13796 2376 3568 2405 3688 +13797 2557 3597 2570 3598 +13798 1971 2041 3522 3558 +13799 2027 2006 3436 3760 +13800 2592 3233 2590 3370 +13801 2932 3633 3632 3634 +13802 3569 3570 2100 3572 +13803 1713 3228 1970 3401 +13804 842 855 777 3460 +13805 1904 1903 3330 3399 +13806 3018 3654 3009 3655 +13807 1759 1780 2076 3699 +13808 1980 1916 1909 3476 +13809 2966 2646 2670 3292 +13810 2733 440 3495 3659 +13811 1206 1094 1056 3456 +13812 884 28 3213 3301 +13813 228 1347 229 3761 +13814 1975 1978 1976 3271 +13815 1739 3190 1745 3208 +13816 1394 1389 3497 3498 +13817 1004 948 937 3229 +13818 812 875 3132 923 +13819 124 2018 920 873 +13820 2374 2548 2436 3773 +13821 2565 3576 2558 3577 +13822 3297 3474 1939 3767 +13823 1163 1301 3294 3673 +13824 964 957 956 3721 +13825 3508 3546 280 3684 +13826 1798 1445 1444 3460 +13827 2329 2412 2449 3646 +13828 2764 2676 2744 3255 +13829 325 3397 324 3594 +13830 1589 2282 287 2215 +13831 314 2087 2099 3639 +13832 1194 3439 3293 3440 +13833 2300 2475 2387 3763 +13834 2307 3608 2434 3758 +13835 1909 3248 2023 3476 +13836 3022 3295 428 3469 +13837 2568 3552 3551 3553 +13838 2027 3436 1510 3760 +13839 1455 1450 3216 3505 +13840 1046 1178 1260 3296 +13841 1449 1450 3505 3506 +13842 1465 3239 1548 3419 +13843 2387 2519 2300 3763 +13844 1384 3483 254 3485 +13845 1054 1207 1151 3472 +13846 2173 24 330 2197 +13847 405 2561 406 3639 +13848 1514 273 3495 3615 +13849 404 3571 2567 3639 +13850 3100 2179 341 3067 +13851 2226 2139 2240 3290 +13852 1679 3504 3386 3521 +13853 1105 3622 1036 3623 +13854 1033 1247 1101 3625 +13855 2939 2942 2941 3532 +13856 268 3501 1388 3654 +13857 3457 3566 1038 3694 +13858 1501 3262 1533 3398 +13859 32 428 3022 3295 +13860 3484 1385 3547 3684 +13861 2103 3597 2091 3599 +13862 3551 3552 2568 3554 +13863 1865 1852 1606 3389 +13864 2699 3344 3335 3346 +13865 1880 3263 1506 3526 +13866 1725 3191 1942 3353 +13867 177 950 178 3464 +13868 1625 3417 1433 3426 +13869 1863 3520 2076 3700 +13870 1382 3490 3489 3491 +13871 2518 2303 3293 3771 +13872 248 1381 249 3496 +13873 3276 3308 2593 3677 +13874 2901 2909 2908 3662 +13875 417 3533 3535 3536 +13876 362 2500 2395 3566 +13877 415 3207 2872 3458 +13878 2669 2668 2667 3430 +13879 2244 2201 938 3229 +13880 1276 1217 1136 3698 +13881 2176 2187 1593 3604 +13882 2146 2209 2198 3588 +13883 2832 3258 420 3565 +13884 2949 2970 2898 3471 +13885 2107 2095 3202 3247 +13886 255 1350 254 3653 +13887 2692 3196 2691 3249 +13888 2672 3633 3444 3682 +13889 2594 2592 393 3265 +13890 435 3004 3482 3486 +13891 1853 3525 1855 3668 +13892 1945 1782 3459 3561 +13893 2053 2076 1863 3520 +13894 1500 1622 1754 3351 +13895 2538 3294 2394 3670 +13896 1163 3294 3670 3673 +13897 1389 3499 3498 3500 +13898 2597 3506 406 3609 +13899 1815 1757 1759 3768 +13900 1382 273 3490 3492 +13901 1399 1385 3546 3547 +13902 2623 2956 2916 3315 +13903 2840 2693 2694 3413 +13904 2566 3569 402 3574 +13905 1389 3498 246 3500 +13906 1781 3318 1782 3561 +13907 2778 2776 2583 3262 +13908 815 15 264 835 +13909 1485 1432 1463 3288 +13910 191 190 3651 3755 +13911 2692 3249 2693 3581 +13912 1152 1227 3203 3694 +13913 2694 3249 3261 3413 +13914 2761 3338 2759 3536 +13915 1843 3299 3276 3637 +13916 3149 760 807 858 +13917 1911 3264 1840 3315 +13918 1950 1803 3635 3636 +13919 2465 2307 2362 3608 +13920 1440 1442 1447 3383 +13921 2442 3306 2351 3773 +13922 3448 3449 1412 3678 +13923 1021 1169 1245 3236 +13924 2928 3346 2908 3479 +13925 1402 913 815 3246 +13926 1902 1971 1972 3522 +13927 3276 3308 1526 3764 +13928 3004 3017 3485 3486 +13929 1981 1911 1910 3527 +13930 2348 3302 3193 3560 +13931 1912 1925 1856 3671 +13932 938 2201 180 3229 +13933 403 3449 2753 3678 +13934 1918 3248 3287 3444 +13935 843 789 913 3246 +13936 1483 1458 3222 3319 +13937 2844 2830 3334 3641 +13938 2032 1999 1997 3652 +13939 2654 3376 2801 3454 +13940 3481 3483 3016 3484 +13941 1166 1223 1073 3305 +13942 2040 1810 1915 3424 +13943 2580 428 2774 3469 +13944 1918 3287 1917 3444 +13945 2994 2993 3297 3767 +13946 1122 1162 1039 3367 +13947 384 3707 3619 3759 +13948 870 884 783 3301 +13949 1008 3467 3379 3781 +13950 272 273 3492 3495 +13951 1937 3297 1939 3767 +13952 2526 3477 2316 3584 +13953 371 3543 372 3669 +13954 2245 2182 2123 3753 +13955 1379 3683 1328 3713 +13956 1924 3394 1826 3617 +13957 1616 330 24 2197 +13958 2961 3253 2653 3324 +13959 1379 216 1378 3301 +13960 3015 3544 3002 3545 +13961 178 3463 2094 3464 +13962 1880 3217 1878 3263 +13963 1555 1556 1489 3564 +13964 1982 2004 3612 3664 +13965 3008 3500 3499 3501 +13966 2565 3575 3576 3577 +13967 2709 3194 3210 3220 +13968 2817 3391 2825 3393 +13969 377 3483 3004 3485 +13970 169 981 3577 3681 +13971 1426 1737 3588 3589 +13972 1953 1952 2064 3328 +13973 1586 3621 1585 3762 +13974 452 451 3226 3237 +13975 2441 2365 2448 3378 +13976 2560 3569 3570 3571 +13977 1996 1998 3471 3652 +13978 438 3492 3490 3615 +13979 2091 3523 2102 3735 +13980 1634 3527 3479 3733 +13981 3306 2351 3773 3778 +13982 352 2565 351 3575 +13983 279 3481 3480 3684 +13984 2081 3668 3632 3767 +13985 1003 960 959 3691 +13986 268 3223 1430 3502 +13987 1003 189 999 3578 +13988 217 1292 216 3301 +13989 2738 2668 2737 3430 +13990 2560 403 3569 3571 +13991 270 269 3357 3499 +13992 3264 3315 2878 3428 +13993 3466 3717 1142 3779 +13994 1374 3746 1370 3748 +13995 2639 3282 2742 3325 +13996 2621 2908 2967 3479 +13997 1647 3448 1412 3678 +13998 880 3140 3114 3167 +13999 2822 2826 3256 3671 +14000 1590 1589 1492 3638 +14001 1935 3259 1936 3343 +14002 2442 3614 3306 3773 +14003 318 2101 319 3574 +14004 2967 2948 3434 3662 +14005 1502 3239 1465 3419 +14006 397 2738 2737 3524 +14007 1729 3209 1646 3678 +14008 2415 3650 2479 3716 +14009 2966 3292 2670 3410 +14010 2579 2599 3221 3222 +14011 1443 3607 1482 3701 +14012 989 193 3466 3592 +14013 1226 3673 3670 3674 +14014 1490 3215 1489 3743 +14015 3008 3498 3499 3500 +14016 2626 3330 3612 3664 +14017 2422 2351 3306 3778 +14018 2367 3749 2443 3751 +14019 148 1206 826 1094 +14020 3489 3490 3013 3491 +14021 1884 1821 1883 3508 +14022 354 3570 2566 3572 +14023 2331 2518 3293 3440 +14024 1430 3223 1431 3502 +14025 2786 2771 2601 3319 +14026 961 960 1002 3692 +14027 253 1383 1397 3487 +14028 2733 2662 2732 3238 +14029 262 2269 2199 3311 +14030 2905 3270 2758 3353 +14031 1680 3386 1679 3504 +14032 1415 1417 1416 3442 +14033 1255 1123 3380 3467 +14034 2315 2446 3467 3781 +14035 875 3132 3163 812 +14036 2424 2347 2452 3771 +14037 2100 3570 3569 3571 +14038 1382 3489 251 3491 +14039 1672 3334 1673 3536 +14040 1493 1453 1494 3689 +14041 3228 3401 1713 3430 +14042 1744 1606 3389 3390 +14043 1159 1010 1100 3696 +14044 1803 3634 1963 3635 +14045 2734 2866 2817 3396 +14046 2866 2815 3394 3395 +14047 2023 2000 1611 3273 +14048 343 2554 3463 3464 +14049 3016 3483 376 3484 +14050 2401 3452 3674 3675 +14051 1154 1074 1044 3723 +14052 3016 3481 434 3482 +14053 451 3587 450 3607 +14054 168 167 987 3572 +14055 2973 3330 2946 3399 +14056 2975 2995 2996 3318 +14057 1824 1476 3265 3350 +14058 1220 1061 1184 3225 +14059 1649 1654 2066 3385 +14060 3163 875 812 922 +14061 2191 23 285 2171 +14062 1766 1890 1765 3422 +14063 1487 3286 1709 3606 +14064 378 3017 379 3487 +14065 2993 3474 3297 3767 +14066 1639 1922 1641 3256 +14067 2753 2754 3448 3449 +14068 1195 1106 1265 3614 +14069 3499 3500 1393 3501 +14070 1158 3559 1025 3579 +14071 387 3655 3009 3656 +14072 1840 3264 1723 3428 +14073 2089 317 3569 3574 +14074 1535 1671 1536 3227 +14075 2940 3218 2975 3531 +14076 186 944 185 3507 +14077 2515 2403 2355 3549 +14078 232 1340 3593 3702 +14079 1641 1731 1620 3256 +14080 1385 280 3546 3684 +14081 447 3241 3240 3638 +14082 162 3552 2098 3555 +14083 197 1285 198 3644 +14084 1473 3299 1472 3743 +14085 2668 2669 2740 3304 +14086 1871 3399 3261 3413 +14087 1469 2065 3286 3715 +14088 1259 3473 3197 3608 +14089 2624 2925 2928 3344 +14090 2458 2516 2379 3283 +14091 274 3488 1396 3490 +14092 998 3651 190 3755 +14093 2342 2496 2395 3566 +14094 166 3570 2088 3573 +14095 1483 1429 1458 3319 +14096 2876 2988 2986 3428 +14097 2687 3417 2681 3455 +14098 1423 803 1554 3672 +14099 2035 3394 3395 3760 +14100 1820 1619 1839 3198 +14101 2333 2513 3568 3776 +14102 357 3552 2568 3553 +14103 1203 1124 1009 3283 +14104 2866 3394 3396 3760 +14105 1692 1722 1911 3264 +14106 2566 3570 3569 3572 +14107 955 1006 3368 3765 +14108 1649 2067 3329 3385 +14109 1440 1481 1482 3607 +14110 2892 2890 2894 3397 +14111 958 3720 3719 3766 +14112 381 3489 3013 3491 +14113 1130 1264 1028 3780 +14114 2105 3451 326 3603 +14115 1074 3355 1044 3723 +14116 2366 334 2444 3348 +14117 1885 1479 1872 3413 +14118 2504 2446 2359 3781 +14119 959 3691 960 3692 +14120 2464 2363 2345 3279 +14121 1443 1482 1860 3701 +14122 1779 1939 1941 3297 +14123 2176 3604 1580 3628 +14124 1861 1712 1889 3228 +14125 1164 3342 1302 3723 +14126 2240 3290 2139 3513 +14127 2346 2544 2391 3314 +14128 2602 2868 458 3272 +14129 201 967 200 3722 +14130 3490 3492 273 3615 +14131 426 3195 3672 3743 +14132 2671 3634 2936 3635 +14133 2570 3596 2556 3598 +14134 1055 1096 1204 3348 +14135 1634 1692 3527 3733 +14136 2379 3283 2516 3439 +14137 445 3010 3009 3657 +14138 30 409 2574 3298 +14139 1486 1457 1527 3222 +14140 1398 3483 3481 3484 +14141 1597 1425 1474 3637 +14142 1559 1416 3441 3774 +14143 1066 3509 1216 3567 +14144 388 389 2461 3711 +14145 2094 3451 2105 3464 +14146 2104 3595 175 3602 +14147 2895 2687 3416 3417 +14148 2380 3402 358 3438 +14149 340 2443 3627 3751 +14150 1999 2032 2007 3742 +14151 2452 2390 3260 3384 +14152 395 3594 2556 3596 +14153 1013 3686 1101 3703 +14154 2566 2559 3572 3574 +14155 2118 26 341 3067 +14156 2572 2575 390 3247 +14157 2341 2450 3687 3688 +14158 2576 2762 3516 3741 +14159 1921 2049 1793 3727 +14160 1692 3264 1911 3527 +14161 1991 1858 1875 3220 +14162 2985 3514 2927 3668 +14163 921 1549 856 3251 +14164 3491 3493 382 3709 +14165 3499 3501 269 3502 +14166 443 3501 3499 3502 +14167 1734 3470 1823 3511 +14168 315 3300 314 3639 +14169 255 3483 1398 3484 +14170 167 2100 3570 3572 +14171 2087 3552 163 3553 +14172 2408 3252 377 3761 +14173 1366 1364 1365 3707 +14174 2878 2916 2877 3315 +14175 375 3547 3484 3642 +14176 1883 280 279 3480 +14177 1846 1451 1764 3764 +14178 2085 2106 3231 3298 +14179 1745 3190 1748 3374 +14180 2287 1442 2203 3383 +14181 2478 2414 2353 3539 +14182 270 1743 271 3357 +14183 2098 3552 3551 3554 +14184 327 328 3370 3451 +14185 939 3229 936 3358 +14186 2349 2459 2461 3711 +14187 1628 3416 1708 3775 +14188 1211 1191 1014 3676 +14189 2103 3598 3597 3599 +14190 2853 3700 3520 3756 +14191 2064 1914 1913 3648 +14192 1521 2079 2070 3728 +14193 2923 3343 3259 3756 +14194 1562 1564 1635 3455 +14195 439 440 3494 3495 +14196 2475 2300 2462 3763 +14197 2447 2326 2510 3582 +14198 2906 2905 2907 3353 +14199 1447 1481 1440 3587 +14200 2590 2779 391 3370 +14201 2717 2758 3270 3353 +14202 2029 2028 3259 3371 +14203 3551 3552 2087 3553 +14204 1777 1735 1825 3425 +14205 173 2103 172 3598 +14206 2605 3407 3276 3637 +14207 1381 1394 271 3494 +14208 272 3492 3494 3495 +14209 1392 1388 244 3656 +14210 438 3006 3490 3492 +14211 2852 2998 3520 3710 +14212 1105 3623 1222 3734 +14213 1492 1494 1546 3241 +14214 2101 3574 2089 3575 +14215 2024 1998 2026 3471 +14216 1213 1025 1158 3559 +14217 2637 2638 2611 3351 +14218 1807 1938 1937 3634 +14219 1728 1920 1763 3285 +14220 360 3556 359 3765 +14221 2623 3315 3264 3527 +14222 1938 1939 1937 3297 +14223 3487 3724 379 3726 +14224 442 3499 3357 3502 +14225 1688 1412 1776 3448 +14226 1586 1584 3621 3740 +14227 2562 3552 358 3555 +14228 314 3300 1805 3506 +14229 1717 3210 1991 3220 +14230 3392 3511 2686 3563 +14231 3009 3655 3654 3656 +14232 2762 3508 2578 3516 +14233 313 3551 3506 3609 +14234 1155 3452 1230 3675 +14235 2538 3291 371 3294 +14236 2292 3528 2541 3685 +14237 1630 1888 1887 3710 +14238 1687 3216 1688 3705 +14239 434 3481 3411 3482 +14240 2988 2876 2915 3561 +14241 1393 3500 245 3655 +14242 3261 3331 2935 3610 +14243 1394 3497 3496 3498 +14244 2684 3308 2593 3764 +14245 2481 3693 3203 3694 +14246 2995 2959 2978 3478 +14247 1930 2001 2000 3682 +14248 952 3358 947 3766 +14249 1037 1092 3236 3771 +14250 1018 3377 3567 3780 +14251 1745 1739 1651 3190 +14252 873 782 813 3258 +14253 1344 3732 230 3761 +14254 262 3311 2199 3513 +14255 803 132 1554 859 +14256 3002 430 431 3544 +14257 2806 2805 2804 3727 +14258 381 3279 2517 3725 +14259 2302 2371 2471 3461 +14260 2484 2335 2519 3372 +14261 1088 3583 3477 3584 +14262 3003 3484 375 3547 +14263 1380 3352 265 3657 +14264 1608 1771 3303 3397 +14265 269 3499 1393 3501 +14266 271 1515 272 3659 +14267 1960 1961 1813 3768 +14268 450 3383 449 3607 +14269 2725 3189 2899 3607 +14270 1779 3253 1760 3474 +14271 2607 2789 2773 3369 +14272 1303 1161 1075 3507 +14273 2977 2949 2897 3471 +14274 189 3437 999 3578 +14275 1438 1575 3392 3563 +14276 3258 3537 420 3565 +14277 1117 1045 1173 3438 +14278 1724 1721 3245 3387 +14279 1220 1184 1009 3528 +14280 2719 2586 2634 3624 +14281 3468 3580 350 3585 +14282 2102 3577 170 3735 +14283 2559 3572 3574 3575 +14284 1723 1697 1701 3428 +14285 452 3237 3219 3762 +14286 1383 3487 1396 3488 +14287 881 148 1206 826 +14288 407 3551 2568 3554 +14289 2801 3376 2881 3416 +14290 2689 3422 2688 3446 +14291 976 3358 952 3766 +14292 2407 3685 2440 3686 +14293 2422 2337 2482 3445 +14294 396 2570 397 3597 +14295 27 360 3368 3556 +14296 1377 1310 1312 3513 +14297 1873 1943 1942 3465 +14298 1177 202 1263 3719 +14299 1724 1699 1721 3387 +14300 3008 3499 443 3501 +14301 2490 2361 2542 3666 +14302 1388 3654 3501 3655 +14303 3255 3774 1558 3775 +14304 1312 1320 1349 3291 +14305 841 309 1579 3408 +14306 243 1317 242 3658 +14307 1627 3254 1762 3376 +14308 342 26 3358 3463 +14309 2415 2438 3650 3717 +14310 979 983 978 3736 +14311 1561 3409 1416 3774 +14312 2606 3276 2605 3407 +14313 436 3005 3017 3486 +14314 1993 1995 1994 3610 +14315 2240 2199 3311 3513 +14316 429 3541 430 3544 +14317 2025 2035 3395 3760 +14318 1194 1049 1092 3293 +14319 3593 3642 375 3702 +14320 2770 2601 2771 3563 +14321 1954 3548 1967 3647 +14322 2768 3426 2762 3741 +14323 1068 1270 1240 3314 +14324 1059 3234 1128 3406 +14325 1843 1595 1597 3637 +14326 2820 2822 3412 3671 +14327 269 1716 270 3357 +14328 1384 3482 3481 3483 +14329 2869 2951 2871 3648 +14330 3517 2403 3550 3706 +14331 861 1279 184 3224 +14332 831 120 1638 3535 +14333 2815 3394 3232 3617 +14334 1228 1133 3550 3706 +14335 1690 3219 1652 3237 +14336 2550 2354 2421 3362 +14337 284 1497 3363 3469 +14338 2874 2773 423 3429 +14339 1373 1374 1370 3748 +14340 2334 2530 2416 3717 +14341 2779 3233 2591 3241 +14342 1655 3586 1774 3588 +14343 448 2783 449 3518 +14344 2073 1756 2043 3243 +14345 2084 3474 2081 3767 +14346 202 3719 958 3720 +14347 828 129 1844 931 +14348 2729 2758 3423 3465 +14349 313 2098 3551 3554 +14350 1999 2025 1998 3652 +14351 1741 1511 1510 3192 +14352 404 3449 403 3571 +14353 1929 3394 2035 3760 +14354 1965 2013 1963 3633 +14355 2493 2531 2346 3252 +14356 323 2103 2092 3597 +14357 1910 1714 1980 3315 +14358 1815 1915 3424 3699 +14359 278 3411 1661 3480 +14360 2776 31 446 3398 +14361 953 3692 954 3765 +14362 3003 3547 3012 3684 +14363 2728 2809 3422 3423 +14364 1100 3661 3660 3696 +14365 1178 3296 1304 3711 +14366 2558 3523 2571 3735 +14367 397 398 3524 3597 +14368 1680 3374 3386 3504 +14369 2198 2133 2211 3588 +14370 2240 3311 25 3513 +14371 2517 2406 380 3450 +14372 1140 1236 3468 3643 +14373 1184 1052 1259 3473 +14374 1241 3372 1079 3763 +14375 2651 2923 2649 3343 +14376 2796 3374 2797 3504 +14377 1089 1286 1145 3252 +14378 2917 2990 2919 3679 +14379 1596 1597 1595 3407 +14380 1778 820 121 3533 +14381 2611 2638 2595 3350 +14382 2466 2358 3686 3734 +14383 1395 3492 3491 3493 +14384 428 3469 429 3542 +14385 353 354 3572 3718 +14386 2799 2800 2882 3322 +14387 1415 1940 1886 3442 +14388 1732 3454 1562 3455 +14389 1920 1919 1936 3343 +14390 3342 3719 1302 3723 +14391 2211 2277 1427 3590 +14392 1624 1483 1485 3319 +14393 2942 2885 2943 3777 +14394 1190 1050 1295 3758 +14395 2815 2816 3394 3617 +14396 2391 375 3314 3702 +14397 2586 2719 2583 3540 +14398 1722 1721 1698 3387 +14399 226 1354 227 3725 +14400 253 3487 3485 3726 +14401 1915 1887 1888 3339 +14402 1694 3346 1632 3479 +14403 324 323 3596 3600 +14404 399 3522 398 3523 +14405 311 1555 310 3557 +14406 313 3554 3551 3609 +14407 1163 3670 1077 3673 +14408 2837 3738 2838 3739 +14409 284 3295 1387 3469 +14410 1380 3656 243 3658 +14411 1283 3716 3650 3717 +14412 1008 1255 3379 3467 +14413 2564 3595 3594 3602 +14414 1152 3693 1075 3694 +14415 2783 3689 2726 3701 +14416 1012 1273 1242 3382 +14417 2751 3263 2750 3526 +14418 169 3575 984 3681 +14419 2240 25 3290 3513 +14420 3541 3542 282 3544 +14421 3000 2649 2855 3343 +14422 438 3490 437 3620 +14423 1433 1471 3426 3741 +14424 377 3252 3732 3761 +14425 3011 3497 442 3499 +14426 1547 1549 921 3251 +14427 2101 169 2090 3575 +14428 2717 3270 2758 3465 +14429 2747 3462 2746 3532 +14430 29 2575 391 3247 +14431 1830 1785 3242 3415 +14432 1208 1051 3306 3778 +14433 2018 840 920 3537 +14434 1863 2029 1934 3700 +14435 1474 1472 1473 3299 +14436 2452 2347 2390 3384 +14437 1129 3305 3685 3686 +14438 174 2092 173 3598 +14439 861 184 3200 3224 +14440 2945 2953 3248 3444 +14441 1651 1739 1653 3189 +14442 1209 3580 3509 3776 +14443 2722 3470 3349 3512 +14444 1564 2044 1686 3680 +14445 1742 3238 1515 3659 +14446 2455 3779 3509 3780 +14447 2937 3635 2936 3636 +14448 1560 3255 1558 3775 +14449 1277 237 21 2232 +14450 2088 3570 3571 3573 +14451 2028 1756 2073 3371 +14452 327 2094 328 3451 +14453 267 1392 266 3654 +14454 394 2712 393 3603 +14455 2762 3426 2763 3508 +14456 1185 1059 1215 3560 +14457 2108 914 159 3231 +14458 2465 2362 2411 3307 +14459 2792 2620 2813 3389 +14460 1210 1083 1257 3279 +14461 2403 2356 2314 3706 +14462 1120 3313 1041 3670 +14463 2486 3750 2329 3757 +14464 346 3595 2564 3602 +14465 2919 3530 2918 3679 +14466 2563 2573 2574 3557 +14467 2081 3632 1966 3767 +14468 2816 2817 2815 3394 +14469 3594 3595 2104 3602 +14470 1096 208 1204 3753 +14471 2604 3446 3407 3637 +14472 338 337 2412 3360 +14473 221 1300 220 3605 +14474 1043 1077 1155 3675 +14475 2211 1427 3589 3590 +14476 2063 2064 1913 3521 +14477 178 946 179 3463 +14478 2847 2985 3525 3645 +14479 1394 1389 270 3497 +14480 1975 3475 2002 3530 +14481 2104 2092 3595 3596 +14482 2840 2701 2839 3738 +14483 2937 2863 2716 3715 +14484 2845 3631 2945 3682 +14485 1964 3633 1963 3634 +14486 398 3522 2984 3524 +14487 2962 2927 3616 3668 +14488 2476 2475 2352 3661 +14489 3254 3442 1886 3616 +14490 1573 1654 2061 3322 +14491 796 926 859 3195 +14492 2079 1720 2068 3345 +14493 2083 1551 3206 3404 +14494 1683 3470 1684 3512 +14495 384 3619 2400 3759 +14496 454 3621 2829 3739 +14497 1887 3520 1861 3710 +14498 2007 3645 2031 3742 +14499 1383 275 276 3486 +14500 2807 3359 2690 3629 +14501 1489 3677 1473 3743 +14502 3487 3488 3005 3489 +14503 831 820 120 3535 +14504 1398 1385 3484 3684 +14505 2349 3296 2473 3366 +14506 2672 2945 3631 3682 +14507 3329 3330 2904 3664 +14508 2626 3330 2973 3612 +14509 1476 3266 3265 3350 +14510 2937 2716 3635 3715 +14511 1381 272 1395 3494 +14512 1179 1262 3402 3438 +14513 407 3551 3554 3609 +14514 1952 3328 1954 3647 +14515 1014 3517 1133 3706 +14516 1033 1124 1197 3625 +14517 1876 1691 1593 3604 +14518 2084 1939 3474 3767 +14519 2674 2968 2650 3209 +14520 458 2868 459 3586 +14521 2146 2198 3586 3588 +14522 3149 417 418 858 +14523 2558 350 3577 3735 +14524 2604 3407 2605 3637 +14525 2604 2689 2688 3446 +14526 1078 1035 1242 3477 +14527 3506 3551 406 3609 +14528 2479 3651 355 3755 +14529 1925 1922 1639 3671 +14530 1830 1829 2075 3478 +14531 1192 3360 1098 3646 +14532 1524 1525 3308 3677 +14533 1761 1779 2059 3324 +14534 1838 3349 2045 3400 +14535 1119 3284 1290 3627 +14536 2787 426 425 3672 +14537 342 2572 26 3463 +14538 1470 1528 1849 3741 +14539 1357 3709 1358 3725 +14540 2628 3261 3610 3612 +14541 1102 1138 1011 3770 +14542 1397 3482 1384 3485 +14543 1313 1316 3213 3683 +14544 2809 2688 3422 3727 +14545 3006 3491 3490 3492 +14546 2578 2577 3516 3541 +14547 1359 1356 1355 3724 +14548 2341 3377 2376 3688 +14549 2710 2729 3220 3465 +14550 1987 1984 2067 3329 +14551 2774 463 3214 3363 +14552 360 2563 359 3556 +14553 916 828 1844 3340 +14554 1833 1832 3359 3629 +14555 1308 1233 3568 3776 +14556 385 3498 3008 3500 +14557 1634 1693 3479 3527 +14558 1194 1081 3439 3440 +14559 3007 440 441 3494 +14560 3488 3489 1396 3490 +14561 3014 383 3493 3496 +14562 2927 3514 3616 3668 +14563 2562 3554 3552 3555 +14564 1629 1631 1707 3431 +14565 2547 2391 375 3314 +14566 3013 3005 3488 3489 +14567 2799 2882 2653 3324 +14568 2159 2257 2252 3518 +14569 2287 2184 291 1447 +14570 1826 3391 1923 3617 +14571 281 280 3508 3546 +14572 2694 3261 3249 3331 +14573 1392 3656 1380 3657 +14574 2038 2039 1888 3538 +14575 2839 2702 2834 3198 +14576 2919 2920 2918 3530 +14577 1422 1424 1804 3340 +14578 1815 3699 3424 3768 +14579 1294 3199 1127 3467 +14580 2527 2348 2497 3302 +14581 283 282 3541 3542 +14582 1663 3534 2018 3537 +14583 1740 1653 1739 3189 +14584 353 2559 352 3575 +14585 237 1309 1311 3290 +14586 264 265 3352 3398 +14587 2544 2304 2428 3623 +14588 453 3219 3621 3762 +14589 1886 2057 3254 3616 +14590 1029 3568 1138 3769 +14591 1315 843 241 3213 +14592 1252 1067 3450 3666 +14593 1950 1796 1803 3636 +14594 2360 3509 2455 3779 +14595 1857 3227 1671 3310 +14596 3004 3483 3482 3485 +14597 1988 3611 2004 3664 +14598 2420 3355 344 3719 +14599 2039 2040 1888 3339 +14600 219 1334 1376 3712 +14601 1251 3580 1209 3776 +14602 2081 3474 2084 3668 +14603 1292 1280 216 3301 +14604 1331 3669 1324 3744 +14605 348 2557 2570 3598 +14606 2358 2332 3686 3703 +14607 208 2237 1204 2182 +14608 1880 1507 1506 3263 +14609 938 182 2244 937 +14610 1381 3494 3493 3496 +14611 2589 3215 2780 3677 +14612 1358 1357 1360 3709 +14613 1848 1464 1603 3421 +14614 3594 3595 2556 3596 +14615 2103 322 2091 3597 +14616 1014 1153 1211 3706 +14617 1000 1003 3578 3691 +14618 1029 1087 3643 3769 +14619 1382 3491 1395 3492 +14620 1705 1707 3304 3730 +14621 2323 2428 2385 3640 +14622 1740 1504 1498 3312 +14623 2233 2176 1580 3628 +14624 3230 3427 2336 3665 +14625 1589 1493 1492 3241 +14626 1661 3255 1660 3480 +14627 1577 2060 3409 3410 +14628 1400 3542 1387 3543 +14629 2505 2305 2481 3693 +14630 231 3314 1145 3732 +14631 2832 421 420 3258 +14632 2690 2807 2896 3359 +14633 3467 3687 2315 3781 +14634 1067 1232 1217 3698 +14635 3014 3006 3492 3493 +14636 216 1379 217 3301 +14637 2710 2729 2730 3220 +14638 2852 3520 2853 3700 +14639 161 2086 2097 3556 +14640 323 3597 3596 3600 +14641 2847 2983 2985 3645 +14642 2496 3472 363 3566 +14643 2679 3216 2680 3705 +14644 2685 2686 3511 3562 +14645 1920 1936 2036 3772 +14646 2708 2842 2843 3728 +14647 2970 2997 2848 3742 +14648 1419 3201 1418 3529 +14649 2097 310 3298 3557 +14650 1742 1517 1515 3238 +14651 778 828 3340 3373 +14652 1635 3511 1575 3562 +14653 1055 1148 1212 3347 +14654 2122 2169 2162 3762 +14655 125 1657 873 3258 +14656 441 3357 3497 3659 +14657 2088 3573 3571 3639 +14658 2358 2423 2495 3622 +14659 1807 3634 1803 3636 +14660 1887 2053 3520 3710 +14661 2143 2217 2255 3284 +14662 2560 3570 355 3573 +14663 3411 3481 278 3482 +14664 2968 3209 2674 3678 +14665 2923 2924 3259 3772 +14666 2530 353 3466 3716 +14667 3011 3496 3007 3497 +14668 2455 2306 2388 3780 +14669 2030 2029 1780 3700 +14670 1985 1838 1837 3212 +14671 1617 3628 1582 3737 +14672 349 2397 3468 3644 +14673 1965 3444 2013 3633 +14674 2641 2643 3243 3250 +14675 2704 3399 2946 3400 +14676 1431 1430 1847 3223 +14677 2240 2199 2145 3311 +14678 326 327 3265 3451 +14679 1502 1548 1465 3239 +14680 2725 3312 3189 3607 +14681 2962 2859 2652 3254 +14682 429 430 3015 3544 +14683 1820 1819 1907 3738 +14684 1113 1007 1282 3778 +14685 945 955 3368 3765 +14686 1102 3769 1138 3770 +14687 1853 2058 3616 3668 +14688 2176 1593 1580 3604 +14689 1403 1390 285 3295 +14690 2319 3673 2477 3675 +14691 360 3368 3556 3765 +14692 1141 3583 1088 3729 +14693 1032 1289 1159 3696 +14694 2015 2014 1855 3631 +14695 1434 1732 1435 3416 +14696 1787 1786 1923 3618 +14697 1634 1692 1693 3527 +14698 2933 3399 3261 3612 +14699 2292 2503 3625 3685 +14700 2061 1686 2044 3322 +14701 2277 2212 1544 3590 +14702 2262 3205 2212 3590 +14703 1623 1621 1620 3365 +14704 2692 2829 3235 3581 +14705 3323 3437 2381 3651 +14706 1328 3683 1318 3713 +14707 334 335 3347 3348 +14708 2691 3196 2796 3386 +14709 2842 3565 2841 3728 +14710 1077 3670 1226 3673 +14711 2934 3261 2933 3399 +14712 315 3571 3300 3639 +14713 2730 2755 2709 3220 +14714 1418 1893 1892 3277 +14715 1447 2184 291 2272 +14716 2571 3599 349 3735 +14717 375 3593 3547 3642 +14718 1541 2159 288 1539 +14719 2599 2581 2579 3221 +14720 3480 3481 433 3684 +14721 1398 279 1385 3684 +14722 2811 3386 3504 3521 +14723 2828 2891 2823 3256 +14724 988 3592 987 3718 +14725 847 1423 1422 3373 +14726 2463 2298 3268 3752 +14727 427 3215 2777 3408 +14728 1952 1969 2064 3648 +14729 1376 3712 1333 3714 +14730 1188 2194 1119 3627 +14731 2560 2567 3571 3573 +14732 1886 3254 1627 3442 +14733 1945 3459 1946 3777 +14734 2883 3242 2643 3250 +14735 2943 2885 2877 3515 +14736 2992 3522 399 3558 +14737 274 3490 273 3615 +14738 1224 1174 1062 3268 +14739 1607 1475 3266 3397 +14740 2203 1442 1441 3383 +14741 2467 2400 3584 3759 +14742 287 1589 2215 1541 +14743 1569 3232 1610 3420 +14744 2401 3674 2319 3675 +14745 1016 1132 1219 3267 +14746 439 2980 3495 3615 +14747 225 1357 226 3725 +14748 2857 2616 2614 3189 +14749 1892 1675 1932 3277 +14750 1783 1439 1896 3272 +14751 3016 3482 3004 3483 +14752 2402 2367 2329 3749 +14753 2743 3410 434 3411 +14754 462 3590 461 3747 +14755 1453 1530 1494 3689 +14756 2152 2215 2282 3240 +14757 1217 1019 1136 3698 +14758 1698 1552 1697 3404 +14759 940 943 3200 3368 +14760 2015 1855 1854 3631 +14761 2086 2098 3554 3555 +14762 1569 1612 1610 3232 +14763 2489 2348 2460 3302 +14764 323 1571 322 3600 +14765 1979 1946 3532 3777 +14766 2728 2689 3289 3422 +14767 2437 2306 2506 3780 +14768 3362 3744 373 3745 +14769 1580 1617 2233 3628 +14770 2496 364 3472 3559 +14771 2018 873 1657 3537 +14772 1672 1674 1666 3536 +14773 1986 3412 2042 3538 +14774 1070 3323 1237 3437 +14775 2382 3626 2472 3703 +14776 359 3555 3692 3765 +14777 1420 3201 1421 3338 +14778 2295 2372 2450 3688 +14779 1703 1704 1507 3620 +14780 3013 3488 437 3490 +14781 2563 3556 2573 3557 +14782 1849 3516 1471 3741 +14783 2541 2327 2407 3685 +14784 216 1280 876 3301 +14785 1146 1283 191 3650 +14786 2619 2761 416 3458 +14787 2725 2726 2742 3312 +14788 193 1256 194 3466 +14789 1733 1823 1436 3392 +14790 3417 3426 2768 3741 +14791 1625 1708 1434 3416 +14792 1248 1100 3660 3696 +14793 1822 3190 1651 3226 +14794 191 998 190 3755 +14795 2233 1617 298 2196 +14796 2024 2026 1612 3433 +14797 113 900 856 1549 +14798 125 873 813 3258 +14799 2436 2351 3418 3773 +14800 433 3411 434 3481 +14801 1353 1352 1348 3726 +14802 1268 1146 1237 3651 +14803 1460 1847 1518 3624 +14804 1016 1152 1227 3203 +14805 2425 365 3559 3630 +14806 219 3711 1334 3712 +14807 2566 2560 3569 3570 +14808 457 3272 458 3604 +14809 2626 3612 3611 3664 +14810 1248 1027 1080 3333 +14811 276 277 1397 3486 +14812 256 1385 257 3547 +14813 2398 3439 2516 3625 +14814 2902 3321 2882 3322 +14815 3219 3235 2760 3621 +14816 2629 3441 3409 3774 +14817 349 3735 3599 3736 +14818 2005 1741 1510 3436 +14819 1037 1092 1169 3236 +14820 1636 1637 1638 3535 +14821 2344 2453 2522 3225 +14822 1386 282 1400 3544 +14823 2431 2325 2370 3414 +14824 329 1546 328 3370 +14825 2828 2822 2826 3256 +14826 900 113 1588 1549 +14827 1393 3499 1389 3500 +14828 3276 3299 2605 3637 +14829 2943 3515 3281 3777 +14830 452 451 2864 3226 +14831 231 1240 3314 3702 +14832 1504 1739 1747 3208 +14833 1083 1276 1141 3279 +14834 2704 2701 2840 3413 +14835 2556 3594 2564 3595 +14836 1719 1718 1720 3345 +14837 2544 2428 2391 3640 +14838 1957 1958 3341 3453 +14839 2682 2576 2581 3741 +14840 1674 1636 1778 3533 +14841 1284 1088 3584 3729 +14842 1153 1076 3296 3706 +14843 1478 3249 1480 3331 +14844 2926 2843 3335 3345 +14845 1311 2232 237 3290 +14846 3361 3362 373 3745 +14847 2088 3570 2100 3571 +14848 2760 3219 2757 3235 +14849 347 2570 2556 3598 +14850 1859 1500 1754 3325 +14851 2380 358 2480 3438 +14852 3650 3716 2415 3717 +14853 8 309 841 817 +14854 1830 2080 1828 3405 +14855 2310 3193 2540 3323 +14856 3213 3301 28 3683 +14857 1539 2159 289 2203 +14858 2676 3255 2677 3775 +14859 3011 3498 3497 3499 +14860 2602 2752 2724 3212 +14861 1853 2058 2062 3616 +14862 3014 439 440 3494 +14863 2375 2548 2308 3333 +14864 1869 1570 3317 3420 +14865 1271 1129 1073 3305 +14866 1889 1712 1711 3228 +14867 2971 3245 2624 3733 +14868 2865 3232 2815 3395 +14869 2293 3269 2373 3467 +14870 3316 3378 2321 3379 +14871 3017 3485 3486 3487 +14872 2569 392 2554 3451 +14873 2803 2721 3470 3511 +14874 2621 2956 2623 3527 +14875 2907 2944 2971 3387 +14876 360 2468 27 3507 +14877 1237 190 3437 3651 +14878 2683 3275 2769 3764 +14879 230 1344 1341 3732 +14880 2319 3674 3673 3675 +14881 2681 2598 2685 3562 +14882 2309 3278 2386 3665 +14883 2715 2819 3281 3341 +14884 2087 3551 2098 3552 +14885 1167 1023 1215 3193 +14886 3003 3481 3016 3484 +14887 1406 1405 1553 3195 +14888 1678 1755 1834 3196 +14889 2497 3302 2348 3560 +14890 2418 3197 3473 3608 +14891 1479 3249 1509 3581 +14892 2597 407 2587 3609 +14893 2441 2302 2370 3414 +14894 1945 1702 1782 3561 +14895 356 355 3651 3754 +14896 2666 2660 2641 3447 +14897 1927 2013 1965 3444 +14898 1163 1077 1301 3673 +14899 1611 1569 1867 3434 +14900 315 2088 3571 3639 +14901 1111 1281 1138 3770 +14902 2097 2085 160 3556 +14903 1205 2180 2267 3432 +14904 2462 2426 3696 3697 +14905 2390 346 2524 3384 +14906 2630 3442 2659 3443 +14907 1593 300 1876 2187 +14908 1743 1716 1715 3357 +14909 1397 3482 3485 3486 +14910 1121 1279 141 797 +14911 215 1278 1119 2153 +14912 1114 3608 1181 3758 +14913 2961 2962 3253 3474 +14914 1679 1681 3504 3521 +14915 2562 2568 3552 3554 +14916 1384 3481 1398 3483 +14917 1080 1012 3381 3382 +14918 1575 3511 3392 3563 +14919 2852 3699 3520 3700 +14920 2719 2782 3419 3421 +14921 1996 1997 1998 3652 +14922 3009 3018 444 3654 +14923 2850 2849 3326 3768 +14924 418 3533 417 3536 +14925 1272 1008 3379 3781 +14926 1013 1222 3686 3734 +14927 1764 3275 1898 3764 +14928 2396 2321 2365 3380 +14929 1880 1878 2016 3263 +14930 1506 1513 2008 3526 +14931 161 3555 3556 3765 +14932 2996 2915 2885 3561 +14933 342 3342 2545 3766 +14934 2498 3257 2417 3644 +14935 1582 1580 1581 3628 +14936 449 2783 2727 3701 +14937 1954 3328 3548 3647 +14938 2905 2884 2808 3519 +14939 2463 2322 2414 3539 +14940 1330 1337 3744 3745 +14941 2695 3386 2811 3521 +14942 376 3642 3653 3732 +14943 345 3356 2524 3722 +14944 2763 3480 432 3508 +14945 15 264 1404 815 +14946 1717 1991 2072 3220 +14947 1212 1091 1024 3307 +14948 2176 2127 2187 3604 +14949 423 2773 424 3340 +14950 2588 3276 2593 3677 +14951 2684 2593 2606 3764 +14952 945 953 954 3765 +14953 2633 2634 2636 3624 +14954 2953 3287 3248 3444 +14955 2342 3203 2491 3267 +14956 2002 2003 1988 3530 +14957 941 949 137 888 +14958 2159 288 2215 1541 +14959 2796 3196 2795 3374 +14960 1314 891 1315 3213 +14961 2638 2637 2639 3325 +14962 2853 3259 3700 3756 +14963 2561 2568 3551 3553 +14964 2980 2991 2751 3327 +14965 1473 1524 3299 3677 +14966 1991 3210 3194 3220 +14967 173 971 968 3601 +14968 2640 2642 2641 3447 +14969 196 1140 1236 3468 +14970 2953 2673 3287 3444 +14971 129 1422 1844 931 +14972 3010 3656 3657 3658 +14973 2944 3191 2713 3245 +14974 1121 1161 1291 3457 +14975 3542 3544 3015 3545 +14976 2720 3421 3244 3663 +14977 1383 3486 3487 3488 +14978 2628 3610 3611 3612 +14979 316 3300 315 3571 +14980 2976 2961 2653 3324 +14981 125 1534 1657 3258 +14982 1288 3193 1167 3323 +14983 1200 1110 1016 3203 +14984 2377 2361 3666 3667 +14985 2381 3437 356 3651 +14986 1916 1918 3248 3287 +14987 2733 2732 440 3659 +14988 1609 3739 1584 3740 +14989 2920 2627 3475 3530 +14990 1132 1093 3472 3566 +14991 2567 3571 3573 3639 +14992 168 984 169 3575 +14993 1707 1631 1882 3304 +14994 2982 2929 3218 3371 +14995 2490 3450 2406 3666 +14996 1618 1908 1836 3581 +14997 2032 3645 2007 3742 +14998 1926 3286 2065 3715 +14999 1384 278 3481 3482 +15000 2396 2446 3379 3467 +15001 1382 1396 3489 3490 +15002 217 1328 218 3713 +15003 1886 2057 1627 3254 +15004 777 853 842 3460 +15005 936 939 937 3229 +15006 2978 2915 2995 3318 +15007 3006 3013 3490 3491 +15008 901 803 896 3672 +15009 2507 2336 3427 3665 +15010 3494 3495 440 3659 +15011 1044 3539 1172 3752 +15012 1785 1599 3242 3250 +15013 359 3402 2499 3507 +15014 417 3535 2761 3536 +15015 252 1396 1383 3487 +15016 247 1394 248 3496 +15017 3018 3500 3008 3501 +15018 1503 1465 1520 3419 +15019 3011 3008 3498 3499 +15020 382 3491 3006 3493 +15021 2804 3415 2807 3629 +15022 1800 1658 1657 3258 +15023 2089 3569 2100 3572 +15024 2848 2836 3645 3742 +15025 1127 1032 1123 3269 +15026 125 813 1534 3258 +15027 2923 2651 2924 3772 +15028 2333 2397 2513 3776 +15029 1658 1659 3537 3565 +15030 2591 2781 3241 3689 +15031 847 131 1423 803 +15032 2323 2354 2433 3695 +15033 223 1144 3619 3759 +15034 2891 3365 2890 3730 +15035 2849 2913 3424 3768 +15036 2341 3199 2437 3377 +15037 31 3021 446 3352 +15038 2082 2043 1599 3243 +15039 1776 1687 1688 3705 +15040 2970 2824 2997 3436 +15041 2386 2309 2521 3278 +15042 326 2105 327 3451 +15043 1324 1331 1325 3669 +15044 1149 2180 1205 3432 +15045 168 2101 2089 3575 +15046 2201 19 180 2270 +15047 2686 3562 2598 3563 +15048 2927 2659 2859 3616 +15049 1834 1755 1835 3196 +15050 2398 2483 2331 3440 +15051 1791 1792 1793 3519 +15052 1418 1419 1420 3201 +15053 403 2753 402 3678 +15054 278 3480 279 3481 +15055 379 3005 380 3487 +15056 265 1501 1533 3398 +15057 2823 3364 2870 3538 +15058 2564 2555 3602 3603 +15059 2986 3264 2878 3428 +15060 1099 1012 1104 3414 +15061 2950 2954 2913 3320 +15062 268 269 3501 3502 +15063 1797 1897 1822 3219 +15064 330 329 3247 3638 +15065 433 3481 3003 3684 +15066 1941 1938 1990 3297 +15067 1773 1532 1519 3690 +15068 2515 2501 3367 3549 +15069 1016 1275 1200 3267 +15070 1115 1175 1296 3695 +15071 2417 2347 2424 3257 +15072 2399 2357 3440 3770 +15073 2089 3569 3572 3574 +15074 1545 1546 1494 3233 +15075 900 113 1614 1588 +15076 2104 324 2092 3596 +15077 2774 463 2775 3214 +15078 1818 1837 1838 3198 +15079 2904 2903 2902 3329 +15080 1066 3567 1233 3776 +15081 1526 1524 1525 3308 +15082 444 2706 2585 3223 +15083 170 980 171 3735 +15084 3326 3699 2851 3700 +15085 2301 2488 2422 3445 +15086 1676 1637 1682 3458 +15087 241 1391 242 3246 +15088 2595 2726 2591 3689 +15089 3326 2849 3699 3768 +15090 2597 2765 3506 3609 +15091 1490 1489 1473 3743 +15092 435 3017 3004 3486 +15093 2623 3264 2622 3527 +15094 2820 2810 2822 3671 +15095 2171 23 285 1403 +15096 2052 3737 1619 3738 +15097 1540 1541 1539 3518 +15098 2766 3300 405 3506 +15099 2777 427 2780 3215 +15100 1728 1763 1646 3209 +15101 195 986 194 3580 +15102 343 2545 3719 3766 +15103 2942 3532 3459 3777 +15104 2608 422 3227 3310 +15105 1887 2053 1861 3520 +15106 2845 2898 2848 3652 +15107 2385 2413 2323 3388 +15108 1826 1736 3391 3393 +15109 2885 2876 2877 3561 +15110 2621 3527 2622 3733 +15111 2738 3401 2667 3430 +15112 2864 2614 2615 3190 +15113 2162 1566 2213 3237 +15114 1156 1010 1159 3697 +15115 2776 446 2582 3262 +15116 2717 3191 2944 3353 +15117 321 2041 320 3522 +15118 2467 2316 3583 3584 +15119 2483 2399 3440 3510 +15120 2739 3364 2891 3730 +15121 2583 2582 2584 3540 +15122 1787 3529 1891 3618 +15123 1549 1548 1588 3239 +15124 1486 1483 1458 3222 +15125 1968 1960 1813 3320 +15126 443 3499 442 3502 +15127 1058 3435 1250 3614 +15128 824 144 911 1207 +15129 3481 3484 3003 3684 +15130 1460 1462 1461 3336 +15131 899 861 3200 3224 +15132 322 1972 321 3524 +15133 2640 3448 2679 3705 +15134 2747 2745 2819 3453 +15135 403 404 2754 3449 +15136 2625 3548 2627 3611 +15137 441 3357 442 3497 +15138 1144 1035 1269 3584 +15139 1826 1736 1894 3391 +15140 1079 3661 1010 3763 +15141 2476 2374 2494 3234 +15142 3257 3643 2417 3644 +15143 350 351 3577 3585 +15144 1712 1970 1713 3228 +15145 2861 3375 3271 3475 +15146 1886 1627 1417 3442 +15147 3010 389 3656 3658 +15148 1699 1725 1942 3353 +15149 1780 2076 3699 3700 +15150 1261 3361 233 3362 +15151 2552 346 2390 3384 +15152 1503 1502 1465 3419 +15153 2852 2972 2998 3710 +15154 2065 1948 1950 3715 +15155 2749 2750 2836 3526 +15156 843 1315 891 3213 +15157 1906 1909 2023 3476 +15158 1904 1816 1903 3399 +15159 144 824 1151 1207 +15160 1553 3195 1405 3743 +15161 3011 384 3007 3496 +15162 2930 2994 3634 3767 +15163 422 3309 3227 3310 +15164 2587 2593 3308 3677 +15165 1650 1649 2067 3329 +15166 1570 3317 3420 3618 +15167 2077 3610 1993 3611 +15168 2948 2958 2967 3434 +15169 1084 1255 1042 3379 +15170 314 3506 313 3551 +15171 1095 1057 1205 3432 +15172 1183 1052 1184 3225 +15173 1566 3237 2162 3762 +15174 3014 3493 3492 3494 +15175 2629 3409 2743 3774 +15176 28 3301 370 3367 +15177 2794 3529 2793 3618 +15178 1081 3440 1126 3510 +15179 2269 2145 2199 3311 +15180 1013 3703 1165 3734 +15181 2707 2722 3349 3512 +15182 2698 2696 2699 3335 +15183 1223 1061 1271 3305 +15184 1547 921 115 1446 +15185 1781 1782 1700 3561 +15186 2093 3594 2104 3602 +15187 1906 1899 1905 3476 +15188 1155 1017 1230 3452 +15189 3276 3407 2606 3764 +15190 3548 3610 2077 3611 +15191 1539 1441 1454 3518 +15192 2973 2946 2933 3399 +15193 1084 1042 3378 3379 +15194 1525 1489 1556 3677 +15195 1228 3550 3549 3706 +15196 2978 2884 3206 3478 +15197 2583 3419 3262 3540 +15198 2327 3305 2407 3685 +15199 415 414 2900 3460 +15200 2157 2277 2211 3590 +15201 1850 1705 1882 3304 +15202 1071 1287 1118 3539 +15203 2406 2553 2313 3698 +15204 356 357 3553 3578 +15205 2651 3285 2666 3772 +15206 1725 1726 1942 3191 +15207 3402 3438 2380 3693 +15208 1607 325 1475 3397 +15209 2429 2381 3323 3437 +15210 1726 1873 1942 3465 +15211 861 787 899 3200 +15212 2307 2449 2362 3646 +15213 1826 1929 1827 3393 +15214 3196 3374 2796 3386 +15215 2865 2867 3232 3433 +15216 2631 2632 2630 3441 +15217 2049 1791 1793 3519 +15218 1812 1810 1811 3649 +15219 1091 1192 1024 3307 +15220 2818 2819 3341 3453 +15221 397 2557 398 3597 +15222 372 2421 2546 3362 +15223 1637 1421 1682 3458 +15224 1921 1814 3629 3727 +15225 1163 236 1293 3294 +15226 985 986 982 3681 +15227 1360 3708 1361 3709 +15228 2879 2714 2880 3287 +15229 2535 3333 2430 3382 +15230 2339 2500 2468 3694 +15231 2426 2378 2511 3696 +15232 1682 1421 1852 3207 +15233 2992 3401 2984 3522 +15234 2731 2728 2772 3289 +15235 936 938 180 3229 +15236 2391 2525 375 3702 +15237 1468 1957 1958 3341 +15238 1560 1662 1558 3255 +15239 2948 3433 2977 3434 +15240 2293 2396 3380 3467 +15241 1558 1660 1661 3255 +15242 1831 1687 1600 3705 +15243 1481 1651 1653 3226 +15244 2468 2500 361 3457 +15245 2753 2754 2679 3448 +15246 2875 2972 3339 3710 +15247 1463 3455 1635 3562 +15248 2961 2962 2652 3253 +15249 318 1729 1413 3678 +15250 1661 1576 1558 3255 +15251 1355 1357 1358 3725 +15252 1992 3399 1904 3612 +15253 268 1388 267 3654 +15254 1164 1302 1074 3723 +15255 2415 2479 354 3716 +15256 244 1326 243 3656 +15257 877 820 785 3533 +15258 2787 2780 426 3743 +15259 1586 1585 1594 3762 +15260 1898 3407 1595 3764 +15261 454 3621 3739 3740 +15262 2803 2798 2685 3680 +15263 371 3294 3291 3669 +15264 1354 1355 3724 3725 +15265 21 2181 1277 2232 +15266 2704 2840 2934 3413 +15267 1458 1457 3222 3747 +15268 2072 1873 1726 3465 +15269 432 3546 3508 3684 +15270 2324 2442 2351 3773 +15271 1142 3716 1283 3717 +15272 2572 390 26 3202 +15273 2719 3403 2748 3421 +15274 424 3369 425 3373 +15275 1680 1679 1681 3504 +15276 2795 2796 2691 3196 +15277 1675 1673 1672 3334 +15278 1728 1729 1730 3209 +15279 1668 1669 1670 3429 +15280 1732 1562 1435 3455 +15281 1451 1455 1689 3505 +15282 1161 1038 1227 3694 +15283 958 3719 203 3766 +15284 2740 2870 3364 3431 +15285 2981 3259 2924 3371 +15286 1066 1209 3509 3776 +15287 1135 1246 1048 3687 +15288 2358 2533 3703 3734 +15289 1353 227 1354 3724 +15290 3686 3703 1013 3734 +15291 1314 1313 1316 3213 +15292 1774 1655 1775 3586 +15293 313 3506 1449 3609 +15294 249 1395 250 3493 +15295 2643 2883 2658 3242 +15296 2813 2748 2635 3390 +15297 1551 1696 2083 3206 +15298 2909 2867 2948 3420 +15299 2559 2566 402 3574 +15300 2931 3525 2985 3668 +15301 1011 1194 3293 3440 +15302 439 3492 438 3615 +15303 2407 3305 2440 3685 +15304 1411 315 316 3300 +15305 1750 1756 2030 3371 +15306 1192 1057 3360 3432 +15307 2880 3515 2877 3606 +15308 383 3729 3708 3759 +15309 432 2763 2764 3480 +15310 1448 3244 1865 3421 +15311 2624 2971 2925 3245 +15312 1259 1199 1064 3197 +15313 1225 1074 1154 3723 +15314 1789 3422 1814 3727 +15315 2967 2958 2956 3476 +15316 211 1149 2228 2180 +15317 2209 2133 2198 3588 +15318 2350 2539 3278 3614 +15319 3468 3580 1251 3776 +15320 1620 1706 1623 3730 +15321 1400 283 1387 3542 +15322 2485 2304 2440 3305 +15323 1805 314 315 3300 +15324 2728 3289 3280 3423 +15325 1756 1750 1749 3218 +15326 2589 3564 3215 3677 +15327 2588 3299 3276 3677 +15328 453 452 3219 3762 +15329 1179 1045 3438 3693 +15330 272 1514 273 3495 +15331 1407 926 134 1579 +15332 1876 2241 1775 3586 +15333 2386 3230 2336 3665 +15334 2606 2605 2604 3407 +15335 1104 3477 1088 3583 +15336 1817 3399 1871 3413 +15337 434 433 2744 3411 +15338 2416 2360 2455 3779 +15339 1833 1784 1785 3415 +15340 2676 2743 2744 3774 +15341 1954 3328 1951 3548 +15342 3242 3243 2643 3250 +15343 1441 1539 289 2203 +15344 2802 3322 2800 3680 +15345 2846 2847 3525 3631 +15346 2784 462 461 3747 +15347 1902 1713 3401 3430 +15348 1876 2187 2241 3586 +15349 1397 1384 254 3485 +15350 2842 2709 2835 3210 +15351 2720 3244 414 3663 +15352 2945 2953 2947 3248 +15353 3359 3415 1833 3629 +15354 2298 2402 3750 3752 +15355 391 2554 392 3370 +15356 1147 198 1285 3257 +15357 1828 1749 1842 3405 +15358 2641 2642 2643 3250 +15359 2626 2904 3330 3664 +15360 2814 2815 2867 3232 +15361 1937 2081 1966 3767 +15362 2589 2587 3564 3677 +15363 310 309 3298 3408 +15364 2923 3259 2853 3756 +15365 2883 3359 2807 3415 +15366 2897 2845 2945 3682 +15367 2292 3625 3528 3685 +15368 940 185 944 3368 +15369 3454 3455 2798 3680 +15370 195 1251 3468 3580 +15371 2667 3401 3228 3430 +15372 1733 1734 1823 3511 +15373 284 285 3295 3363 +15374 2018 124 1657 873 +15375 1360 224 1365 3708 +15376 1733 3392 1575 3511 +15377 284 3363 3295 3469 +15378 1652 1591 1567 3237 +15379 2715 3286 2714 3715 +15380 2630 2659 2655 3443 +15381 1427 2277 1544 3590 +15382 2692 2691 2693 3249 +15383 1051 1113 1180 3778 +15384 2032 1854 1870 3645 +15385 2931 3632 3525 3668 +15386 980 171 3735 3736 +15387 911 143 1093 1207 +15388 1928 2023 1909 3248 +15389 2154 2180 2234 3432 +15390 407 406 3551 3609 +15391 1250 3614 3435 3773 +15392 1591 3226 1481 3587 +15393 1025 3630 1193 3704 +15394 2605 3276 2588 3299 +15395 316 3569 3449 3571 +15396 1831 3250 1784 3359 +15397 2615 2757 2760 3219 +15398 1088 3477 1035 3584 +15399 243 1380 1392 3656 +15400 2081 1853 1855 3668 +15401 2628 3261 2935 3610 +15402 1077 3673 1226 3674 +15403 778 931 828 3373 +15404 1370 3746 1371 3748 +15405 169 3577 3575 3681 +15406 1139 228 1235 3337 +15407 2310 2540 2484 3323 +15408 2855 3343 2923 3756 +15409 2959 3405 2657 3478 +15410 423 3309 422 3310 +15411 2862 2861 2818 3271 +15412 1964 1966 1965 3633 +15413 2455 3509 2470 3780 +15414 328 1545 327 3370 +15415 2735 2866 3396 3760 +15416 1364 3707 1368 3708 +15417 258 1386 259 3545 +15418 1962 1950 3635 3715 +15419 408 3557 409 3564 +15420 2525 3361 374 3702 +15421 1904 1992 1871 3399 +15422 2089 318 317 3574 +15423 2402 2486 2298 3750 +15424 1813 1810 3320 3424 +15425 3014 3007 383 3496 +15426 1233 1066 1216 3567 +15427 2707 2704 2946 3400 +15428 445 3654 444 3690 +15429 1926 1709 1487 3286 +15430 1301 1176 234 3362 +15431 1983 2067 1984 3329 +15432 1519 1847 1773 3223 +15433 2004 1988 2003 3611 +15434 377 376 3483 3653 +15435 1305 3687 1048 3688 +15436 1053 1200 1258 3332 +15437 1947 1782 1781 3318 +15438 2138 2229 2169 3740 +15439 377 3004 378 3485 +15440 1225 3749 1134 3751 +15441 1795 1975 2002 3530 +15442 1456 3590 1543 3747 +15443 1848 1520 1465 3419 +15444 319 2090 320 3576 +15445 1506 1505 1513 3327 +15446 2666 2651 2660 3285 +15447 209 1148 1204 3347 +15448 2004 3611 3612 3664 +15449 941 888 942 3200 +15450 1659 2056 1523 3565 +15451 2445 3509 3580 3776 +15452 234 1261 233 3362 +15453 2422 2351 2301 3306 +15454 1038 1186 1093 3566 +15455 2798 3454 2801 3455 +15456 2686 2770 3392 3563 +15457 387 3009 388 3656 +15458 1066 1251 1209 3776 +15459 169 981 170 3577 +15460 1896 1583 1783 3354 +15461 1406 1407 1405 3195 +15462 2669 2998 2831 3710 +15463 2696 2790 2791 3277 +15464 2570 3597 3596 3598 +15465 1977 1967 1954 3548 +15466 1150 147 1206 3456 +15467 2423 2544 2346 3623 +15468 377 3252 2493 3732 +15469 250 1362 1363 3709 +15470 1162 1304 1076 3549 +15471 1871 3261 1885 3413 +15472 1139 3337 1031 3667 +15473 3574 3575 2101 3576 +15474 2859 3442 3254 3616 +15475 2402 2329 2486 3750 +15476 2303 2424 2452 3771 +15477 1562 3455 3454 3680 +15478 2446 2504 2321 3379 +15479 785 860 840 3534 +15480 1473 3677 3299 3743 +15481 1409 1408 1543 3205 +15482 1092 3293 3236 3771 +15483 2924 2666 3371 3772 +15484 1575 1508 3562 3563 +15485 1012 1170 1080 3381 +15486 1780 1759 1758 3326 +15487 1518 1848 1605 3624 +15488 130 1422 931 847 +15489 2517 381 2464 3279 +15490 1345 1347 1348 3761 +15491 2312 3510 2483 3626 +15492 343 2554 342 3463 +15493 2303 2451 2518 3293 +15494 1345 3653 1344 3761 +15495 2631 3441 3774 3775 +15496 1663 1666 3534 3641 +15497 1442 2287 291 1447 +15498 2442 2324 3614 3773 +15499 2325 2365 2441 3381 +15500 1091 211 1149 2228 +15501 2888 2889 2665 3425 +15502 2910 3328 2625 3610 +15503 1830 1785 2080 3242 +15504 2311 2384 2502 3579 +15505 171 172 2091 3599 +15506 2624 3245 2925 3733 +15507 2021 1947 2019 3531 +15508 2187 2275 2146 3586 +15509 1008 1255 1272 3379 +15510 2445 2470 3509 3776 +15511 2001 2012 2014 3631 +15512 1064 1259 3197 3608 +15513 1985 1683 1685 3349 +15514 464 3019 25 3311 +15515 1423 131 1554 803 +15516 1205 1149 212 2180 +15517 3012 3003 375 3547 +15518 2851 3326 2849 3699 +15519 1352 3724 1356 3726 +15520 916 129 1844 828 +15521 2413 2354 2323 3695 +15522 2237 209 1204 3347 +15523 1164 1119 1290 3627 +15524 1294 1135 1305 3687 +15525 2869 2875 2952 3339 +15526 992 3592 988 3718 +15527 223 1284 1144 3759 +15528 2910 2935 3331 3610 +15529 2418 2434 2307 3608 +15530 1056 1193 3456 3704 +15531 2325 3382 3381 3414 +15532 1704 1703 274 3620 +15533 3227 3309 1671 3310 +15534 1220 3528 1033 3685 +15535 2743 3409 2966 3410 +15536 141 1121 797 838 +15537 2299 2401 2477 3675 +15538 2194 215 1119 2153 +15539 1935 1936 1919 3343 +15540 2198 1426 1774 3588 +15541 1392 3654 3656 3657 +15542 300 1593 2176 2187 +15543 2691 2695 2694 3331 +15544 377 3732 3653 3761 +15545 1936 3259 2028 3772 +15546 2331 2357 2518 3440 +15547 996 3578 997 3754 +15548 3012 3547 3546 3684 +15549 1951 1954 1952 3328 +15550 2734 3396 3393 3425 +15551 1648 1649 1650 3321 +15552 368 3517 2403 3550 +15553 771 820 831 3535 +15554 1827 1735 1736 3393 +15555 2732 3357 441 3659 +15556 2351 2409 3418 3778 +15557 1227 1038 3566 3694 +15558 2094 178 2096 3463 +15559 2584 2585 2586 3540 +15560 1664 1666 1674 3533 +15561 2298 2447 2463 3268 +15562 1469 1467 1468 3281 +15563 212 2267 1205 2180 +15564 2069 3334 1542 3335 +15565 3585 3735 350 3736 +15566 2082 2073 2043 3243 +15567 2502 2342 2491 3267 +15568 2825 2817 2816 3391 +15569 2558 2565 400 3576 +15570 1824 1752 1476 3350 +15571 2468 2499 2339 3507 +15572 2902 2882 2802 3322 +15573 789 815 913 3246 +15574 2866 2865 2815 3395 +15575 2043 1785 1599 3242 +15576 245 1332 244 3655 +15577 1626 1627 1628 3376 +15578 976 947 952 3358 +15579 1445 3244 1448 3663 +15580 1118 3355 1263 3356 +15581 2306 3567 2506 3780 +15582 2420 3719 2545 3723 +15583 2462 2330 2426 3697 +15584 2184 2287 3383 3587 +15585 418 2830 2844 3641 +15586 2969 2625 3328 3548 +15587 2272 1591 1447 3587 +15588 2530 2415 3716 3717 +15589 2957 2950 2747 3462 +15590 1831 1600 1784 3250 +15591 1074 1302 1177 3723 +15592 1099 1307 1170 3414 +15593 2694 2935 3261 3331 +15594 1825 1511 1517 3238 +15595 1409 1410 1408 3205 +15596 2412 2329 2456 3360 +15597 395 2556 396 3596 +15598 2509 3380 2365 3381 +15599 1106 3306 3614 3773 +15600 2763 2677 3255 3426 +15601 1629 1731 2038 3364 +15602 1448 3244 3421 3663 +15603 2754 404 2767 3300 +15604 1536 1857 1799 3227 +15605 2717 2905 2758 3353 +15606 951 947 950 3766 +15607 3477 3583 2316 3584 +15608 2439 2529 2363 3583 +15609 312 3554 313 3609 +15610 2511 3660 2352 3696 +15611 1718 1725 1724 3191 +15612 147 881 1206 3456 +15613 1869 1568 1570 3420 +15614 2809 2804 2688 3727 +15615 2241 1774 302 1775 +15616 317 1413 3449 3678 +15617 387 3655 3712 3714 +15618 2751 2991 2750 3263 +15619 1361 3708 1363 3709 +15620 262 1401 2269 3311 +15621 2086 162 2098 3555 +15622 2953 2879 3248 3287 +15623 2952 3339 2914 3424 +15624 1821 1770 281 3516 +15625 262 2199 1321 3513 +15626 1648 2061 1654 3321 +15627 1911 1723 1840 3264 +15628 2707 2722 2703 3349 +15629 2576 2578 2577 3516 +15630 1382 1395 273 3492 +15631 3340 3369 424 3373 +15632 1797 3219 1690 3762 +15633 1971 2055 2041 3558 +15634 1827 1929 2048 3396 +15635 1851 1668 1804 3429 +15636 1579 1491 1405 3408 +15637 1073 3305 1129 3686 +15638 1007 1244 1143 3418 +15639 1665 2018 1663 3534 +15640 1046 1160 1211 3366 +15641 1722 1692 1645 3733 +15642 26 3202 3229 3358 +15643 2591 3241 3233 3689 +15644 1600 1602 1601 3447 +15645 1690 1822 1652 3219 +15646 2470 3567 3509 3776 +15647 277 3410 1577 3411 +15648 122 877 1665 1664 +15649 1036 1105 1089 3622 +15650 1761 1573 1572 3324 +15651 2047 1679 1678 3386 +15652 2357 3769 2424 3771 +15653 941 940 943 3200 +15654 2890 2741 2739 3730 +15655 2374 2436 2294 3234 +15656 977 973 972 3601 +15657 1090 145 872 3731 +15658 2856 2854 2998 3228 +15659 2088 2099 3573 3639 +15660 1821 1471 1849 3516 +15661 2564 394 2555 3603 +15662 990 988 987 3718 +15663 2796 2797 2810 3504 +15664 1102 1037 1087 3771 +15665 2445 3509 2360 3580 +15666 277 3411 278 3482 +15667 1936 1935 1934 3259 +15668 1070 1237 1298 3437 +15669 355 3651 3754 3755 +15670 2614 2899 2857 3189 +15671 1059 1221 1128 3234 +15672 2003 3548 2077 3611 +15673 352 3592 3575 3681 +15674 1431 1715 1716 3503 +15675 1843 1524 1526 3276 +15676 1213 1090 3630 3731 +15677 2004 3611 1993 3612 +15678 1393 245 1388 3655 +15679 378 2542 2408 3337 +15680 1771 1772 1608 3303 +15681 1426 1428 1737 3589 +15682 1247 1081 1026 3626 +15683 2727 2726 2725 3701 +15684 230 1341 231 3732 +15685 1333 3712 1332 3714 +15686 1000 3578 1001 3691 +15687 1018 3567 1216 3780 +15688 1876 1775 1656 3586 +15689 1994 1480 1885 3261 +15690 2878 3264 2623 3315 +15691 2951 3647 2911 3648 +15692 2298 2368 2447 3582 +15693 2930 2994 2938 3634 +15694 170 2102 2090 3577 +15695 2799 2654 2801 3454 +15696 1673 1893 1768 3338 +15697 1659 1657 1658 3537 +15698 2784 2775 462 3747 +15699 1436 1437 1438 3392 +15700 2684 2596 2593 3308 +15701 1889 1887 1861 3710 +15702 166 2088 165 3573 +15703 2801 2654 2881 3376 +15704 1569 3420 1568 3662 +15705 343 344 3464 3720 +15706 229 1344 230 3761 +15707 1802 3636 1796 3679 +15708 1319 1320 3291 3669 +15709 2837 2829 2693 3581 +15710 857 1643 806 3309 +15711 439 3495 3492 3615 +15712 2990 3329 2904 3664 +15713 2969 3328 2911 3647 +15714 1621 2054 1754 3351 +15715 2084 2081 1939 3767 +15716 2964 2963 2861 3475 +15717 450 3587 3383 3607 +15718 3265 3451 393 3603 +15719 2420 2320 2478 3723 +15720 2852 2851 3699 3700 +15721 1244 1007 1125 3773 +15722 280 1399 1385 3546 +15723 1449 1450 1451 3505 +15724 1684 1683 1686 3470 +15725 2880 2877 2916 3606 +15726 2196 2141 2233 3628 +15727 2710 3191 2717 3465 +15728 979 980 3585 3736 +15729 1329 1330 3744 3745 +15730 1979 1945 1946 3777 +15731 2803 2802 2800 3680 +15732 2060 2017 2051 3292 +15733 2788 2605 3299 3637 +15734 1101 1243 1165 3703 +15735 1028 1086 1103 3717 +15736 2790 2792 2791 3529 +15737 2705 2636 2586 3624 +15738 1326 1332 1327 3712 +15739 1476 2054 3266 3350 +15740 1330 1336 1337 3745 +15741 861 797 1279 3224 +15742 1002 1001 163 3691 +15743 2394 3670 3294 3673 +15744 1396 274 275 3488 +15745 2445 3468 2397 3776 +15746 3007 3496 3494 3497 +15747 1889 1631 1630 3431 +15748 1699 1552 1698 3387 +15749 2805 2807 2804 3415 +15750 994 3754 998 3755 +15751 1365 3708 224 3759 +15752 1537 1497 284 3469 +15753 1676 1682 1864 3207 +15754 3016 434 3004 3482 +15755 2866 3395 3394 3760 +15756 1745 1746 3208 3374 +15757 2042 1986 1925 3412 +15758 1249 1208 1051 3306 +15759 1628 3376 1732 3416 +15760 394 395 2894 3397 +15761 1408 1578 1497 3363 +15762 2576 2682 2762 3741 +15763 1513 1516 1642 3327 +15764 2647 2646 2655 3443 +15765 2803 2685 2686 3511 +15766 1114 3473 1259 3608 +15767 1766 1765 1789 3422 +15768 1904 3330 1982 3612 +15769 1093 1054 1132 3472 +15770 354 2479 355 3755 +15771 2782 2720 413 3663 +15772 316 2100 3569 3571 +15773 2990 2627 2919 3664 +15774 2525 2391 2323 3640 +15775 1770 1849 1531 3516 +15776 2968 2674 402 3678 +15777 1216 3567 3509 3780 +15778 354 2566 353 3572 +15779 2292 2407 2503 3685 +15780 842 1841 1444 3460 +15781 877 840 122 1665 +15782 1809 1840 1701 3428 +15783 2626 2628 3611 3612 +15784 2728 3280 2729 3423 +15785 2368 3757 2307 3758 +15786 2625 3610 3548 3611 +15787 2046 1684 1648 3512 +15788 2373 3199 2514 3467 +15789 2849 2950 2913 3768 +15790 2417 3643 2397 3644 +15791 2292 2541 2407 3685 +15792 3424 3699 2849 3768 +15793 349 3468 350 3736 +15794 1862 1863 1934 3756 +15795 3289 3422 2689 3446 +15796 2025 2027 2035 3760 +15797 2472 2382 2312 3626 +15798 916 1644 128 857 +15799 1150 1056 1193 3456 +15800 1174 1049 1203 3283 +15801 2339 3693 2481 3694 +15802 180 2095 179 3202 +15803 2311 2364 2409 3332 +15804 1202 1214 1072 3377 +15805 386 3018 387 3655 +15806 1260 1178 219 3711 +15807 1973 1671 3309 3310 +15808 2318 3337 2361 3667 +15809 1304 1178 1076 3296 +15810 2769 2765 2684 3505 +15811 1559 3774 3441 3775 +15812 1466 1448 3421 3663 +15813 1566 293 2213 1567 +15814 1196 1084 1182 3316 +15815 1480 1478 1479 3249 +15816 2241 2146 2198 3586 +15817 24 330 2107 2173 +15818 1222 1166 1073 3623 +15819 2300 2519 2438 3763 +15820 2974 2962 3474 3668 +15821 2973 2626 2904 3330 +15822 378 2408 377 3761 +15823 3205 3590 462 3747 +15824 2687 2801 2895 3416 +15825 1035 1078 1168 3230 +15826 1424 1422 1423 3373 +15827 1843 1597 1474 3637 +15828 370 2515 2501 3367 +15829 1633 1645 1634 3733 +15830 2924 3371 3259 3772 +15831 2349 2473 2512 3366 +15832 332 333 3313 3670 +15833 926 133 859 1407 +15834 2373 3269 3199 3467 +15835 1441 1440 1443 3383 +15836 1622 1620 1621 3351 +15837 1661 1660 1883 3480 +15838 2883 3250 2678 3359 +15839 3577 3585 351 3681 +15840 387 386 3655 3714 +15841 2672 3444 2945 3682 +15842 1364 1368 1363 3708 +15843 955 1006 945 3368 +15844 2022 1758 1757 3326 +15845 1090 1151 145 3731 +15846 1095 213 2267 1205 +15847 2001 2012 3631 3682 +15848 184 942 861 3200 +15849 1559 1558 3774 3775 +15850 2640 2679 2642 3705 +15851 1918 1917 2013 3444 +15852 1880 1506 1881 3526 +15853 1274 1157 1064 3204 +15854 3219 3237 1690 3762 +15855 1379 1318 1328 3683 +15856 2577 429 2580 3541 +15857 133 1406 859 1407 +15858 1140 3468 1251 3776 +15859 1054 1158 1219 3559 +15860 2906 2907 2986 3404 +15861 351 2558 350 3577 +15862 1208 3306 1106 3773 +15863 2779 3241 447 3638 +15864 1649 2066 2067 3385 +15865 1343 3593 1339 3642 +15866 441 2732 2886 3357 +15867 1608 1607 1771 3397 +15868 2048 1929 2027 3760 +15869 2982 2929 2940 3218 +15870 1255 1123 1042 3380 +15871 1976 1956 2011 3375 +15872 1511 1741 1642 3192 +15873 360 359 2499 3507 +15874 2344 2434 2418 3473 +15875 1709 1926 1916 3287 +15876 1155 1077 1226 3674 +15877 1147 1087 1037 3257 +15878 2739 2823 2891 3364 +15879 813 912 1534 3258 +15880 271 1394 270 3497 +15881 308 2256 2191 1578 +15882 967 963 966 3722 +15883 2622 2986 2907 3387 +15884 1199 1017 1274 3452 +15885 1035 3477 3230 3584 +15886 1748 1755 1680 3374 +15887 1933 1799 1991 3194 +15888 1815 3424 1813 3768 +15889 190 189 1237 3437 +15890 3015 3002 373 3545 +15891 970 966 3613 3722 +15892 1404 1391 1402 3246 +15893 2495 3622 2318 3667 +15894 2728 2809 2689 3422 +15895 1524 1843 1473 3299 +15896 357 358 3552 3691 +15897 2585 2584 444 3690 +15898 2203 2287 290 1442 +15899 1573 2059 1654 3324 +15900 2211 1427 1426 3589 +15901 1705 1707 1882 3304 +15902 345 346 2564 3602 +15903 1079 3406 1128 3661 +15904 2734 3393 2889 3425 +15905 405 3506 3300 3639 +15906 2396 2315 2446 3467 +15907 1559 1561 1416 3774 +15908 1385 279 280 3684 +15909 2757 2692 2829 3235 +15910 1261 1115 3361 3695 +15911 2676 3774 3255 3775 +15912 2944 2713 2925 3245 +15913 1643 857 1644 3309 +15914 164 2087 163 3553 +15915 1435 1432 1434 3417 +15916 2715 2887 2714 3286 +15917 2561 357 2568 3553 +15918 1565 1732 3376 3454 +15919 2748 2813 2858 3389 +15920 2747 2746 2745 3532 +15921 962 3720 957 3721 +15922 1828 1829 1830 3405 +15923 2301 3306 2520 3676 +15924 232 231 1340 3702 +15925 397 3597 3524 3600 +15926 2033 1933 1991 3210 +15927 438 439 3006 3492 +15928 1632 2068 1633 3344 +15929 1520 1518 1519 3540 +15930 1375 1332 245 3714 +15931 415 2900 2872 3207 +15932 2672 3631 2846 3632 +15933 324 1608 323 3600 +15934 1232 1139 1031 3667 +15935 1608 1772 323 3600 +15936 1813 1810 1812 3320 +15937 1080 3333 1108 3382 +15938 1086 1283 3650 3717 +15939 1904 3399 3330 3612 +15940 410 2573 27 3231 +15941 2924 2666 2929 3371 +15942 2933 3261 2628 3612 +15943 2930 3632 2931 3767 +15944 1476 1475 3265 3266 +15945 2256 2212 2151 3205 +15946 1409 2212 307 2256 +15947 2452 2419 3236 3260 +15948 1580 1617 298 2233 +15949 2518 2357 2424 3771 +15950 344 2420 2549 3355 +15951 27 2573 360 3556 +15952 1903 1983 1982 3330 +15953 2566 2560 403 3569 +15954 1779 1760 2084 3474 +15955 1001 997 996 3578 +15956 2686 3392 2721 3511 +15957 1797 1690 1585 3762 +15958 1070 1288 1167 3323 +15959 346 347 3595 3613 +15960 1301 1077 1176 3673 +15961 841 134 926 1579 +15962 1575 1733 1438 3392 +15963 200 970 199 3722 +15964 3003 3016 376 3484 +15965 167 2089 2100 3572 +15966 2067 1983 1650 3329 +15967 1097 1025 1193 3704 +15968 2387 2310 2484 3372 +15969 843 18 241 913 +15970 1113 1208 1007 3778 +15971 224 225 1141 3729 +15972 1833 3415 1921 3629 +15973 372 373 3362 3744 +15974 1271 1061 1220 3685 +15975 2467 3583 2363 3729 +15976 2331 3293 2451 3439 +15977 2304 2423 2466 3623 +15978 782 920 840 3537 +15979 2629 2631 3441 3774 +15980 1433 1625 1434 3417 +15981 1479 1509 1908 3581 +15982 2772 2607 2773 3429 +15983 187 959 953 3692 +15984 400 2648 3000 3558 +15985 2369 2309 2473 3366 +15986 1857 1671 1670 3310 +15987 2550 373 3361 3362 +15988 246 1389 247 3498 +15989 2762 431 2578 3508 +15990 2788 2789 2607 3637 +15991 1154 1044 1085 3752 +15992 1164 1290 204 3342 +15993 864 143 1093 911 +15994 441 442 3011 3497 +15995 2052 1619 1907 3738 +15996 2895 2677 2768 3426 +15997 171 2091 2102 3735 +15998 2333 3568 3567 3776 +15999 2827 2742 2639 3282 +16000 2715 2819 2887 3281 +16001 1228 3549 1076 3706 +16002 404 405 3300 3639 +16003 2383 2474 385 3427 +16004 2700 2901 2908 3317 +16005 380 3013 381 3489 +16006 1586 2229 296 3740 +16007 2841 3641 2844 3728 +16008 2357 2331 2399 3440 +16009 2656 2657 2959 3405 +16010 311 312 1556 3564 +16011 3337 3666 2361 3667 +16012 1663 2018 1659 3537 +16013 2212 306 1544 1409 +16014 424 2789 425 3369 +16015 2865 3395 2949 3433 +16016 2642 2678 3250 3705 +16017 2220 213 2267 1095 +16018 1840 1723 1701 3428 +16019 2989 2903 3329 3385 +16020 1964 1965 1963 3633 +16021 2592 2590 392 3370 +16022 1114 3473 3608 3758 +16023 2955 2953 2879 3248 +16024 1890 1598 1765 3446 +16025 2525 2433 374 3361 +16026 1963 1803 1807 3634 +16027 1898 1900 1596 3407 +16028 2404 2316 2526 3477 +16029 2085 309 2106 3298 +16030 1922 1731 1641 3256 +16031 2355 2314 2487 3706 +16032 242 1391 1380 3658 +16033 1721 1727 1724 3245 +16034 2405 2333 2513 3568 +16035 1610 1612 2034 3232 +16036 1989 1802 1796 3679 +16037 1120 1041 1163 3670 +16038 2093 2104 175 3602 +16039 1399 257 1385 3547 +16040 2477 2319 2421 3673 +16041 187 1179 1262 3402 +16042 2908 2909 2967 3662 +16043 1112 1031 1137 3667 +16044 1410 1409 307 2256 +16045 1241 1079 1010 3763 +16046 2796 3386 3374 3504 +16047 1848 1465 1464 3419 +16048 1466 3251 1547 3663 +16049 2856 3228 2667 3401 +16050 2720 414 413 3663 +16051 2937 2936 2938 3636 +16052 1485 1483 1484 3288 +16053 2727 450 449 3607 +16054 431 3508 432 3546 +16055 2251 2201 2143 3229 +16056 1473 1489 1524 3677 +16057 1109 1183 1020 3388 +16058 1930 2023 1928 3273 +16059 914 9 159 845 +16060 2105 2094 327 3451 +16061 2443 341 340 3627 +16062 1685 1683 1684 3512 +16063 1503 1532 1533 3262 +16064 1446 921 115 855 +16065 2684 2683 2769 3764 +16066 2785 2601 2599 3319 +16067 3001 428 429 3542 +16068 2620 2792 2617 3201 +16069 1252 1067 1210 3450 +16070 195 1251 196 3468 +16071 1669 1851 1598 3429 +16072 2560 355 2567 3573 +16073 2633 2825 2812 3391 +16074 2860 2666 2641 3243 +16075 1950 1948 1794 3211 +16076 2068 1720 1633 3344 +16077 405 2766 2767 3300 +16078 1226 1131 1017 3674 +16079 1815 2076 1915 3699 +16080 1668 1844 1804 3340 +16081 1853 3514 1870 3525 +16082 2509 2365 2325 3381 +16083 325 1608 324 3397 +16084 984 3592 985 3681 +16085 1058 1106 1195 3614 +16086 354 3718 3716 3755 +16087 2679 2680 2678 3705 +16088 2967 2909 2948 3662 +16089 1393 1389 246 3500 +16090 2797 2616 2827 3208 +16091 1887 1889 1630 3710 +16092 2476 2338 2475 3661 +16093 1382 1396 251 3489 +16094 954 3692 961 3765 +16095 3312 3607 2725 3701 +16096 1666 1664 1663 3534 +16097 3021 3010 446 3657 +16098 1547 1548 1549 3251 +16099 1413 1729 1646 3678 +16100 2498 2417 348 3644 +16101 3018 3008 443 3501 +16102 967 3721 963 3722 +16103 2658 2883 2807 3415 +16104 938 19 180 2201 +16105 2992 399 400 3558 +16106 2505 2380 3438 3693 +16107 395 394 2564 3594 +16108 2043 2080 1785 3242 +16109 1081 1126 1026 3510 +16110 1420 1421 1768 3338 +16111 255 1398 256 3484 +16112 938 936 937 3229 +16113 1878 1880 1879 3217 +16114 1264 3509 3779 3780 +16115 1167 1268 1070 3323 +16116 250 1382 251 3491 +16117 2097 310 2085 3298 +16118 2753 3448 2968 3678 +16119 2324 3435 3614 3773 +16120 2768 2762 2682 3741 +16121 2546 2394 3294 3673 +16122 423 422 2874 3310 +16123 2481 2491 2342 3203 +16124 2077 1951 1995 3610 +16125 2931 3632 3668 3767 +16126 2420 3355 3719 3723 +16127 2704 2934 3399 3413 +16128 1050 1114 1181 3758 +16129 435 434 2743 3410 +16130 1354 1357 1355 3725 +16131 1652 1822 1651 3226 +16132 325 2093 326 3603 +16133 1291 184 1279 3224 +16134 1680 1746 3374 3504 +16135 3379 3380 2396 3467 +16136 203 3719 3342 3766 +16137 1841 885 118 1677 +16138 453 3219 2760 3621 +16139 269 1393 268 3501 +16140 2562 407 2568 3554 +16141 2738 398 2984 3524 +16142 1837 1896 3212 3354 +16143 345 344 3356 3721 +16144 2608 2874 422 3310 +16145 2821 2823 2870 3538 +16146 176 2093 175 3602 +16147 1626 1559 3441 3775 +16148 2545 3342 2393 3723 +16149 208 2210 2182 3753 +16150 359 2562 358 3555 +16151 981 979 980 3585 +16152 1514 1704 273 3615 +16153 1013 1129 1101 3686 +16154 1772 1771 1850 3303 +16155 2850 2746 2849 3768 +16156 2465 2411 2328 3204 +16157 2680 3216 2766 3505 +16158 3670 3673 2444 3674 +16159 376 375 3484 3642 +16160 2672 2945 2845 3631 +16161 2981 2853 3259 3700 +16162 2853 3520 2854 3756 +16163 2096 2095 329 3247 +16164 2694 2934 2840 3413 +16165 1551 1695 1696 3206 +16166 1327 3712 1334 3713 +16167 1814 1765 1900 3422 +16168 1835 3235 1836 3581 +16169 1487 1709 1710 3606 +16170 2830 418 2761 3536 +16171 1816 3399 1817 3400 +16172 2035 2026 2025 3395 +16173 1368 1369 248 3707 +16174 1502 1501 1588 3239 +16175 1335 3593 1336 3745 +16176 3559 3630 365 3731 +16177 1062 1203 1190 3582 +16178 1252 1139 1067 3666 +16179 2695 2811 2912 3521 +16180 1322 216 876 3301 +16181 1449 1805 1450 3506 +16182 2403 368 2532 3517 +16183 1789 1765 1814 3422 +16184 3511 3562 2686 3563 +16185 2354 2413 2477 3695 +16186 1746 1681 1856 3504 +16187 2445 3580 3468 3776 +16188 1041 3313 1189 3753 +16189 2269 22 262 2199 +16190 313 312 2098 3554 +16191 2560 404 403 3571 +16192 2779 2591 2781 3241 +16193 1962 2065 1950 3715 +16194 1562 3454 1563 3680 +16195 2029 2030 2028 3371 +16196 379 380 3450 3724 +16197 1384 1398 255 3483 +16198 2675 2881 2631 3775 +16199 1466 1448 1464 3421 +16200 382 3006 3014 3493 +16201 1101 1026 1243 3626 +16202 946 936 179 3358 +16203 2368 3582 3757 3758 +16204 2532 367 2454 3704 +16205 2759 2761 2619 3338 +16206 1529 1545 1494 3233 +16207 1923 1826 1895 3391 +16208 2565 2558 351 3577 +16209 1118 1044 3355 3539 +16210 283 1400 282 3542 +16211 1524 1489 1525 3677 +16212 1980 1714 1709 3606 +16213 1299 232 3361 3702 +16214 2203 290 1441 1442 +16215 1145 1286 230 3732 +16216 1625 1433 1471 3426 +16217 376 3016 377 3483 +16218 1744 1606 1852 3389 +16219 1719 2033 1717 3210 +16220 2277 2157 2212 3590 +16221 1411 1806 1805 3300 +16222 1416 1414 1415 3443 +16223 372 2546 371 3669 +16224 1924 1826 1923 3617 +16225 1232 1019 1217 3698 +16226 2357 2405 3769 3770 +16227 1075 1161 1227 3694 +16228 3013 3005 437 3488 +16229 1931 1632 1694 3346 +16230 1503 1520 1519 3540 +16231 1194 1081 1197 3439 +16232 1228 1014 1133 3706 +16233 2969 3548 3328 3647 +16234 2456 2329 2367 3749 +16235 2107 330 2095 3247 +16236 2336 2386 2404 3230 +16237 1029 1308 3568 3643 +16238 2054 1752 1754 3350 +16239 1911 1840 1910 3315 +16240 1643 1671 1535 3309 +16241 2438 2335 2415 3650 +16242 381 3013 3006 3491 +16243 1706 1731 1629 3364 +16244 2868 2770 2771 3591 +16245 969 968 3601 3613 +16246 2487 2473 2349 3296 +16247 1705 1706 1707 3730 +16248 2728 2730 2729 3280 +16249 1122 1292 1162 3367 +16250 1030 1136 1099 3461 +16251 982 3585 981 3681 +16252 266 1380 265 3657 +16253 418 417 2761 3536 +16254 1483 1738 1429 3319 +16255 785 840 877 3534 +16256 1614 1615 112 835 +16257 2578 430 2577 3541 +16258 1373 1376 1333 3714 +16259 1275 1065 1200 3332 +16260 3232 3395 2865 3433 +16261 2331 2516 2398 3439 +16262 2807 3415 3359 3629 +16263 2836 2847 2848 3645 +16264 2673 3444 2672 3633 +16265 779 857 806 3309 +16266 2229 295 2169 1586 +16267 2891 2890 2739 3730 +16268 2470 3509 3567 3780 +16269 384 2400 383 3759 +16270 2700 2908 2928 3346 +16271 2627 2625 2964 3548 +16272 1029 1102 1087 3769 +16273 2439 2302 2529 3461 +16274 385 384 3498 3746 +16275 2991 3615 438 3620 +16276 2796 2811 3386 3504 +16277 2607 3446 2604 3637 +16278 1457 1543 1496 3747 +16279 175 2104 174 3595 +16280 366 2454 367 3704 +16281 1761 1572 1762 3253 +16282 2626 3611 2627 3664 +16283 177 2094 2105 3464 +16284 1303 3402 186 3507 +16285 2407 2327 2440 3305 +16286 2401 3452 2366 3674 +16287 2914 2849 3424 3699 +16288 358 2568 357 3552 +16289 2420 2478 2353 3355 +16290 2334 2416 2455 3779 +16291 2496 2342 2384 3267 +16292 167 2100 166 3570 +16293 2686 2598 2601 3563 +16294 1013 1101 1165 3703 +16295 1686 1823 1734 3470 +16296 1105 1036 1222 3623 +16297 980 974 171 3736 +16298 292 2213 1567 1591 +16299 231 1145 230 3732 +16300 2267 2180 2154 3432 +16301 2157 2262 2212 3590 +16302 306 1544 2277 2212 +16303 2830 2698 2844 3334 +16304 343 3719 344 3720 +16305 1563 2044 1564 3680 +16306 2907 2717 2944 3353 +16307 1944 1468 1467 3281 +16308 2779 447 29 3638 +16309 373 374 3361 3745 +16310 1400 1387 260 3543 +16311 1256 3466 1142 3779 +16312 1295 1171 1085 3750 +16313 1158 1065 1275 3579 +16314 2822 2821 2820 3412 +16315 443 3008 442 3499 +16316 2389 2434 2344 3473 +16317 1382 273 274 3490 +16318 1608 325 1607 3397 +16319 1634 1694 1632 3479 +16320 1759 2076 1815 3699 +16321 956 951 950 3720 +16322 1818 1838 2045 3400 +16323 2191 285 23 1578 +16324 1580 299 2176 2233 +16325 365 2384 2425 3559 +16326 2538 2394 332 3670 +16327 1790 1788 1766 3423 +16328 1103 1010 1156 3763 +16329 2930 2938 2936 3634 +16330 2753 3449 3448 3678 +16331 2722 2803 2721 3470 +16332 2587 2588 2593 3677 +16333 1473 1472 1553 3743 +16334 2798 2801 2687 3455 +16335 432 3012 3546 3684 +16336 2509 2325 2378 3381 +16337 1743 1742 1515 3659 +16338 420 3537 419 3565 +16339 2735 2824 2866 3760 +16340 455 2838 3737 3739 +16341 2605 2593 2588 3276 +16342 2093 325 2104 3594 +16343 1438 1574 1575 3563 +16344 2176 1593 299 1580 +16345 264 1592 265 3398 +16346 1100 1128 3660 3661 +16347 2087 2098 163 3552 +16348 2324 2548 3435 3773 +16349 2091 321 2102 3523 +16350 1995 2047 1480 3331 +16351 2556 2564 346 3595 +16352 2347 2552 2390 3384 +16353 1598 1597 1596 3446 +16354 1958 1949 1488 3341 +16355 359 358 3402 3692 +16356 114 856 921 1549 +16357 984 987 985 3592 +16358 1111 1138 1029 3568 +16359 2636 2705 2664 3336 +16360 2566 354 2560 3570 +16361 1419 1852 3201 3389 +16362 2606 3407 2683 3764 +16363 2803 2756 2802 3470 +16364 3011 3008 385 3498 +16365 2717 3191 3353 3465 +16366 317 3449 316 3569 +16367 1139 1232 1067 3666 +16368 2027 1929 2035 3760 +16369 2138 2196 2276 3740 +16370 2494 2374 2294 3234 +16371 2994 2974 2993 3767 +16372 1704 274 273 3615 +16373 2108 2106 78 914 +16374 1833 1898 1832 3629 +16375 2855 2923 2853 3756 +16376 2229 2276 296 3740 +16377 279 278 1661 3480 +16378 2685 2687 2681 3455 +16379 388 3010 389 3656 +16380 1393 269 1389 3499 +16381 2407 2440 2332 3686 +16382 2624 2621 2622 3733 +16383 1475 1477 1607 3266 +16384 2980 2733 439 3495 +16385 2376 3567 2333 3568 +16386 2974 3474 2993 3767 +16387 1448 1865 1603 3421 +16388 1544 1543 1456 3590 +16389 2865 2873 2949 3395 +16390 1029 3643 3568 3769 +16391 313 2098 2087 3551 +16392 2571 399 398 3523 +16393 315 2099 2088 3639 +16394 2711 2712 2894 3266 +16395 1339 1343 1338 3593 +16396 416 415 2872 3458 +16397 2107 2095 2109 3202 +16398 433 434 3016 3481 +16399 1201 1248 1080 3381 +16400 2810 2820 2811 3504 +16401 2376 2405 2295 3688 +16402 380 3450 3724 3725 +16403 942 888 861 3200 +16404 1663 1664 1665 3534 +16405 1577 2060 1561 3409 +16406 227 1210 226 3450 +16407 1336 1335 1340 3593 +16408 938 2244 182 2201 +16409 1036 1166 1222 3623 +16410 2443 2393 341 3627 +16411 1313 242 1317 3683 +16412 259 1331 1337 3744 +16413 1166 1270 1068 3640 +16414 395 2564 2556 3594 +16415 385 3008 386 3500 +16416 2476 2352 2511 3660 +16417 345 3721 3356 3722 +16418 417 416 2761 3535 +16419 2577 2580 2579 3221 +16420 1308 1066 1233 3776 +16421 2694 3261 2934 3413 +16422 2007 2032 2031 3645 +16423 174 2104 2092 3595 +16424 320 2102 321 3523 +16425 2100 2088 166 3570 +16426 383 382 3708 3729 +16427 1603 1605 1848 3403 +16428 438 3006 3013 3490 +16429 1570 1891 3317 3618 +16430 1718 1726 1725 3191 +16431 2873 3395 2866 3760 +16432 2861 3271 2920 3475 +16433 2070 2069 1542 3335 +16434 1541 1540 1589 3240 +16435 2764 2744 433 3480 +16436 2818 2747 2819 3453 +16437 2682 3417 2768 3741 +16438 994 997 998 3754 +16439 859 901 796 3195 +16440 1000 960 1003 3691 +16441 992 989 988 3592 +16442 281 280 1821 3508 +16443 1319 235 1323 3669 +16444 1104 1035 1088 3477 +16445 1145 231 1240 3314 +16446 3321 3329 2903 3385 +16447 273 1395 272 3492 +16448 2718 3244 2720 3421 +16449 1626 1628 1559 3775 +16450 2540 2429 2381 3323 +16451 377 2408 2493 3252 +16452 2184 2135 2272 3587 +16453 1790 1874 1788 3423 +16454 364 3559 365 3731 +16455 2734 2817 2889 3393 +16456 1966 1855 2014 3632 +16457 2097 2086 311 3557 +16458 2618 2872 2900 3207 +16459 357 356 3437 3578 +16460 1345 1342 1344 3653 +16461 2753 2640 2968 3448 +16462 1152 1075 1227 3694 +16463 993 3718 991 3755 +16464 343 2569 2554 3464 +16465 1942 1943 1550 3353 +16466 843 241 18 1315 +16467 1342 1339 1341 3642 +16468 2854 2853 2852 3520 +16469 250 1395 1382 3491 +16470 445 3009 444 3654 +16471 1321 2247 1310 3513 +16472 2143 2201 2244 3229 +16473 1231 1185 1023 3560 +16474 3015 430 3002 3544 +16475 1992 1885 1871 3261 +16476 2074 1924 1786 3617 +16477 2856 2998 2667 3228 +16478 2371 3316 2492 3698 +16479 1163 1226 1077 3670 +16480 371 3001 372 3543 +16481 446 3010 445 3657 +16482 2559 2565 352 3575 +16483 1284 1141 1088 3729 +16484 2973 2933 2628 3612 +16485 1384 277 278 3482 +16486 2135 2162 2213 3237 +16487 2387 2338 2392 3406 +16488 1394 247 1389 3498 +16489 2814 2816 2815 3617 +16490 1294 1127 1123 3467 +16491 404 2567 405 3639 +16492 1372 1371 221 3748 +16493 3003 433 3016 3481 +16494 3021 31 465 3352 +16495 2982 2850 2851 3326 +16496 1945 1979 1944 3777 +16497 2103 2091 172 3599 +16498 2351 2409 2436 3418 +16499 2878 2986 2623 3264 +16500 2355 2403 2314 3706 +16501 2568 407 406 3551 +16502 1768 1893 1420 3338 +16503 2081 2084 2058 3668 +16504 2582 2583 2776 3262 +16505 174 968 965 3613 +16506 1581 1580 1593 3604 +16507 1135 1048 1305 3687 +16508 1419 1744 1852 3389 +16509 2837 454 2829 3739 +16510 2103 173 2092 3598 +16511 245 1393 246 3500 +16512 1619 1617 1582 3737 +16513 2707 2703 2704 3400 +16514 201 962 967 3721 +16515 2692 2693 2829 3581 +16516 2316 2523 2370 3477 +16517 2083 1552 1551 3404 +16518 1027 1128 1221 3660 +16519 377 376 3653 3732 +16520 2571 2558 399 3523 +16521 1806 1688 1455 3216 +16522 1773 1430 268 3223 +16523 1957 1956 1958 3453 +16524 2672 3632 2932 3633 +16525 1490 1553 1405 3743 +16526 191 1283 192 3716 +16527 2386 2336 2507 3665 +16528 1998 1997 1999 3652 +16529 2875 2831 2972 3710 +16530 1595 3407 3276 3764 +16531 1764 1898 1595 3764 +16532 1023 1288 1173 3193 +16533 130 1422 847 1423 +16534 1021 1245 1174 3268 +16535 2020 2019 2022 3531 +16536 1058 1250 1106 3614 +16537 2760 3235 2829 3621 +16538 1201 1042 1123 3380 +16539 996 995 165 3754 +16540 1264 3509 1082 3779 +16541 2990 2904 2626 3664 +16542 1569 1568 1867 3662 +16543 284 1387 283 3469 +16544 1665 840 123 2018 +16545 1555 1489 1491 3215 +16546 1559 1560 1558 3775 +16547 1382 274 1396 3490 +16548 2083 1700 1697 3404 +16549 353 2566 2559 3572 +16550 2842 2832 2841 3565 +16551 1797 1587 1897 3235 +16552 2342 2502 2384 3267 +16553 1671 1973 1670 3310 +16554 382 2363 2464 3729 +16555 2846 3631 3525 3632 +16556 272 1381 271 3494 +16557 2153 2217 1278 3284 +16558 1860 1740 1498 3312 +16559 1837 3198 1839 3354 +16560 1696 2075 2009 3478 +16561 1711 1712 1713 3228 +16562 1977 2077 2003 3548 +16563 1737 1655 3588 3591 +16564 2727 2783 2726 3701 +16565 1330 1324 1329 3744 +16566 2993 2976 2987 3297 +16567 159 160 2085 3231 +16568 1497 1537 1495 3214 +16569 962 958 957 3720 +16570 958 951 3720 3766 +16571 1141 1030 1088 3583 +16572 1553 1472 1554 3672 +16573 8 309 817 2106 +16574 1769 1845 1525 3308 +16575 2761 2759 2830 3536 +16576 1393 1388 268 3501 +16577 2851 2852 2853 3700 +16578 145 1151 824 3731 +16579 254 1384 255 3483 +16580 2041 1730 320 3558 +16581 2741 2890 2892 3303 +16582 2835 2755 2609 3194 +16583 939 947 976 3358 +16584 2358 2332 2466 3686 +16585 2984 2667 2738 3401 +16586 1039 3549 1228 3550 +16587 177 178 2094 3464 +16588 2199 22 262 1321 +16589 2705 2585 2706 3223 +16590 1538 283 282 3541 +16591 2957 2747 2818 3453 +16592 432 3508 3480 3684 +16593 2448 2365 2321 3378 +16594 1492 329 1590 3638 +16595 347 348 3598 3601 +16596 261 1390 262 3311 +16597 2331 3293 3439 3440 +16598 1313 1317 1316 3683 +16599 1380 1391 265 3352 +16600 2562 2568 358 3552 +16601 940 944 943 3368 +16602 1427 1544 1456 3590 +16603 2014 2015 2001 3631 +16604 2361 2313 2377 3666 +16605 350 3580 351 3585 +16606 208 1189 2210 3753 +16607 2882 2902 2903 3321 +16608 352 2360 2416 3466 +16609 1885 1992 1994 3261 +16610 145 824 872 3731 +16611 1346 256 1343 3642 +16612 1423 1554 1472 3672 +16613 2360 2470 2455 3509 +16614 939 936 946 3358 +16615 2341 2376 2450 3688 +16616 387 2461 2459 3711 +16617 347 2556 346 3595 +16618 1449 313 314 3506 +16619 3013 380 3005 3489 +16620 2905 2906 2884 3206 +16621 163 2098 162 3552 +16622 1776 1647 1602 3448 +16623 355 356 3573 3754 +16624 2505 2339 2380 3693 +16625 323 1772 1571 3600 +16626 1467 1710 1808 3515 +16627 1434 1432 1433 3417 +16628 2613 2615 2614 3190 +16629 2084 1939 1779 3474 +16630 1591 1652 1481 3226 +16631 2385 2299 2413 3388 +16632 1220 1124 1033 3528 +16633 1300 1116 220 3605 +16634 2984 398 399 3522 +16635 1856 1639 1640 3671 +16636 1312 1319 1320 3291 +16637 2557 349 2571 3599 +16638 1830 1921 1785 3415 +16639 1413 1412 3449 3678 +16640 2483 2372 2399 3510 +16641 1974 2011 1967 3375 +16642 270 1389 269 3499 +16643 2722 2756 3470 3512 +16644 324 323 2092 3596 +16645 1751 1749 1750 3218 +16646 3016 3004 377 3483 +16647 1606 1604 1603 3403 +16648 1521 2033 2079 3728 +16649 1635 1575 1508 3562 +16650 2680 2766 2769 3505 +16651 2865 2948 2867 3433 +16652 1006 943 945 3368 +16653 2700 2791 2794 3317 +16654 2974 2927 2962 3668 +16655 1131 1055 1218 3348 +16656 1745 1748 1746 3374 +16657 2688 2804 2690 3629 +16658 1189 208 1096 3753 +16659 982 986 983 3585 +16660 1249 1191 1063 3676 +16661 1008 1107 1135 3781 +16662 1379 1316 1318 3683 +16663 2588 2589 2780 3677 +16664 1042 1182 1084 3378 +16665 1685 1684 2046 3512 +16666 1266 3293 1092 3771 +16667 2361 2318 2408 3337 +16668 2950 2746 3462 3768 +16669 2675 2801 2881 3416 +16670 1916 1918 1909 3248 +16671 2429 356 2381 3437 +16672 778 896 847 3373 +16673 2006 1510 2027 3436 +16674 1216 3509 1264 3780 +16675 1627 1762 1565 3376 +16676 1029 1140 1308 3643 +16677 2559 402 401 3574 +16678 843 891 783 3213 +16679 2932 2931 2930 3632 +16680 2035 1929 1924 3394 +16681 353 2416 2530 3466 +16682 2631 3774 2676 3775 +16683 409 408 2563 3557 +16684 1937 1939 2081 3767 +16685 2650 2648 2674 3209 +16686 2324 2436 2548 3773 +16687 203 958 202 3719 +16688 2495 2533 2358 3734 +16689 1547 114 921 1549 +16690 1902 1713 1970 3401 +16691 2969 2964 3548 3647 +16692 1413 1647 1412 3678 +16693 1225 1154 1015 3749 +16694 2426 2330 2536 3269 +16695 1260 220 1116 3605 +16696 2699 2926 3335 3344 +16697 1581 1593 1691 3604 +16698 1478 1480 2047 3331 +16699 376 375 3003 3484 +16700 1194 1197 1049 3439 +16701 1494 1530 1529 3233 +16702 2695 2935 2694 3331 +16703 2162 2169 2268 3762 +16704 2370 2325 2441 3414 +16705 2213 292 2272 1591 +16706 1032 1127 1289 3269 +16707 1175 1020 1296 3388 +16708 2778 412 411 3239 +16709 1039 1187 3274 3550 +16710 1342 1346 3642 3653 +16711 387 2459 386 3605 +16712 2065 1926 1469 3286 +16713 1401 1403 263 2269 +16714 1635 1463 1562 3455 +16715 336 2362 337 3307 +16716 1192 1149 1057 3432 +16717 2765 406 2597 3506 +16718 2875 2869 2870 3538 +16719 2884 2805 2806 3519 +16720 1815 1915 1810 3424 +16721 3011 442 3008 3499 +16722 353 352 3466 3592 +16723 2078 1869 1891 3317 +16724 1179 1045 1262 3438 +16725 207 208 1189 2210 +16726 854 149 148 1187 +16727 1515 1514 272 3495 +16728 223 1366 1365 3759 +16729 2108 2085 2106 3231 +16730 1577 277 1667 3410 +16731 357 2561 356 3553 +16732 3009 3010 388 3656 +16733 1586 1609 1584 3740 +16734 1871 1885 1872 3413 +16735 1501 1502 1503 3262 +16736 117 842 1841 1444 +16737 343 2420 344 3719 +16738 2558 2571 350 3735 +16739 2759 2619 2617 3338 +16740 2676 2677 2675 3775 +16741 1347 1345 1344 3761 +16742 1458 1456 1457 3747 +16743 400 2565 401 3576 +16744 2028 1936 2029 3259 +16745 2470 2360 2445 3509 +16746 2520 2301 2442 3306 +16747 1982 1984 2004 3664 +16748 2561 2568 406 3551 +16749 1144 1239 222 3619 +16750 402 2566 403 3569 +16751 2567 404 2560 3571 +16752 369 2403 2515 3550 +16753 330 1616 1590 3638 +16754 1819 1817 1871 3413 +16755 2714 2953 2673 3287 +16756 2740 2669 2831 3431 +16757 1461 1735 1777 3425 +16758 1561 1414 1416 3409 +16759 1381 1395 249 3493 +16760 112 1614 835 900 +16761 1486 1458 1457 3222 +16762 323 322 2103 3597 +16763 2312 2483 2398 3626 +16764 460 2786 461 3589 +16765 1563 1565 1572 3454 +16766 2034 2074 1610 3232 +16767 2199 2247 1321 3513 +16768 1381 248 1394 3496 +16769 2384 2482 2425 3579 +16770 2099 2087 164 3553 +16771 2612 2828 2637 3351 +16772 1360 1361 1358 3709 +16773 1485 1484 1432 3288 +16774 251 1396 252 3489 +16775 2791 2793 2794 3529 +16776 2487 2349 2461 3296 +16777 1140 1251 1066 3776 +16778 407 2597 406 3609 +16779 254 253 1397 3485 +16780 1209 1216 1066 3509 +16781 1579 310 1491 3408 +16782 2907 2971 2622 3387 +16783 2604 2688 2683 3407 +16784 116 855 842 1444 +16785 2740 2870 2739 3364 +16786 2198 303 1774 1426 +16787 2591 2783 2781 3689 +16788 380 381 2517 3725 +16789 1638 1778 1636 3535 +16790 1566 2162 2268 3762 +16791 375 374 3593 3702 +16792 32 3022 464 3295 +16793 999 1000 1003 3578 +16794 3008 3018 386 3500 +16795 2968 402 2753 3678 +16796 1231 1173 1110 3302 +16797 2788 2605 2588 3299 +16798 1679 1913 1681 3521 +16799 1611 2024 1612 3433 +16800 2740 2831 2870 3431 +16801 2763 2677 2764 3255 +16802 1208 1113 1051 3778 +16803 1370 1371 1372 3748 +16804 2801 2675 2895 3416 +16805 825 876 17 1280 +16806 2945 2673 2953 3444 +16807 1300 1239 1069 3427 +16808 2774 32 463 3363 +16809 1294 1072 1306 3199 +16810 443 2893 2706 3502 +16811 2734 2888 2736 3425 +16812 1842 1829 1828 3405 +16813 1662 1625 1884 3426 +16814 443 442 2893 3502 +16815 1864 1865 1798 3244 +16816 1826 1924 1929 3394 +16817 2696 2700 2699 3346 +16818 2341 2450 2514 3687 +16819 1548 1547 1466 3251 +16820 2336 2404 2526 3230 +16821 1398 1385 256 3484 +16822 1239 1269 1069 3427 +16823 1934 1935 1862 3756 +16824 314 313 2087 3551 +16825 1623 1477 1621 3365 +16826 2937 2862 2863 3211 +16827 1601 1602 2036 3447 +16828 1367 1371 1370 3746 +16829 355 2381 356 3651 +16830 2623 2622 2621 3527 +16831 1835 1587 1836 3235 +16832 1226 1017 1155 3674 +16833 2769 2683 2690 3275 +16834 1482 1443 1440 3607 +16835 2054 1477 1476 3266 +16836 1192 1098 1024 3646 +16837 1882 1713 1901 3430 +16838 284 1497 1578 3363 +16839 2241 302 1774 2198 +16840 192 1283 1142 3716 +16841 171 2102 170 3735 +16842 2888 2893 2886 3503 +16843 233 1299 232 3361 +16844 284 1390 1387 3295 +16845 1018 1216 1130 3780 +16846 1975 1801 1978 3271 +16847 1851 1669 1668 3429 +16848 223 1144 222 3619 +16849 966 969 970 3613 +16850 2506 2376 3377 3567 +16851 2307 2368 2449 3757 +16852 354 353 3716 3718 +16853 1106 3614 1250 3773 +16854 277 1384 1397 3482 +16855 2876 2878 2877 3428 +16856 2999 437 2644 3620 +16857 1864 1682 1852 3207 +16858 1779 1761 1760 3253 +16859 2820 2912 2811 3521 +16860 252 1383 253 3487 +16861 340 339 2443 3751 +16862 2213 2162 293 1566 +16863 2752 2603 2834 3354 +16864 1771 1705 1850 3303 +16865 2422 2551 2351 3778 +16866 1498 1504 1499 3282 +16867 1011 1081 1194 3440 +16868 325 324 2104 3594 +16869 350 3468 2445 3580 +16870 1758 1759 1757 3326 +16871 2894 2610 2711 3266 +16872 2724 2752 2723 3212 +16873 2819 2943 3281 3777 +16874 385 2474 384 3619 +16875 1945 1782 1946 3459 +16876 343 342 2545 3766 +16877 2691 2692 2795 3196 +16878 1628 1708 1559 3775 +16879 2846 2845 2847 3631 +16880 2233 2141 2176 3628 +16881 2563 2562 359 3555 +16882 1191 1051 1097 3445 +16883 236 1319 1309 3291 +16884 2936 2932 2930 3634 +16885 2042 1912 1914 3412 +16886 2562 408 407 3554 +16887 2030 1756 2028 3371 +16888 2920 2627 2964 3475 +16889 2086 2098 312 3554 +16890 1658 1933 2056 3565 +16891 1356 1352 1355 3724 +16892 237 21 2232 1311 +16893 2016 1507 1880 3263 +16894 1040 1188 3627 3751 +16895 1915 1888 2040 3339 +16896 2315 2373 2514 3467 +16897 2100 2089 317 3569 +16898 1780 1863 2076 3700 +16899 1942 1550 1699 3353 +16900 162 2086 161 3555 +16901 1787 1419 1418 3529 +16902 330 1590 329 3638 +16903 2489 2540 2310 3193 +16904 2581 2577 2579 3221 +16905 2467 383 2400 3759 +16906 1648 1654 1649 3321 +16907 373 372 3545 3744 +16908 1370 1372 1373 3748 +16909 994 993 991 3755 +16910 2061 2044 1573 3322 +16911 3017 3005 379 3487 +16912 281 1399 280 3546 +16913 1361 1363 1362 3709 +16914 2976 2653 2882 3324 +16915 1416 1417 1626 3441 +16916 1860 1482 1740 3312 +16917 1063 1191 1211 3676 +16918 2701 2702 2839 3198 +16919 2742 2726 2638 3325 +16920 393 2712 2594 3265 +16921 1509 1479 1478 3249 +16922 1322 1378 216 3301 +16923 1822 1690 1797 3219 +16924 2305 2491 2481 3203 +16925 2152 2257 2215 3240 +16926 1530 1453 1753 3689 +16927 1909 1918 1928 3248 +16928 1098 1171 1050 3757 +16929 1875 2072 1991 3220 +16930 2940 2975 2939 3531 +16931 2073 2036 1936 3772 +16932 3004 3017 378 3485 +16933 992 991 993 3718 +16934 2625 2910 2969 3328 +16935 1905 1980 1909 3476 +16936 167 168 2089 3572 +16937 2892 2737 2741 3303 +16938 1002 1000 1001 3691 +16939 253 1351 1356 3726 +16940 1121 1038 1161 3457 +16941 1960 1959 1961 3462 +16942 2866 2873 2865 3395 +16943 2951 2969 2911 3647 +16944 2719 2748 2718 3421 +16945 1453 1452 1753 3689 +16946 1622 1621 1754 3351 +16947 2714 2887 2880 3286 +16948 2071 1812 1811 3649 +16949 2481 2339 2505 3693 +16950 388 3711 3712 3713 +16951 2437 2341 2536 3199 +16952 329 2095 330 3247 +16953 345 2564 2555 3602 +16954 1947 1946 1782 3459 +16955 2184 2287 2134 3383 +16956 3719 3720 343 3766 +16957 374 2550 373 3361 +16958 1761 2059 1573 3324 +16959 1235 1031 1139 3337 +16960 431 432 3012 3546 +16961 2212 2262 2151 3205 +16962 2697 2790 2696 3277 +16963 1685 2045 1838 3349 +16964 963 957 964 3721 +16965 2293 2373 2396 3467 +16966 438 3013 437 3490 +16967 2881 2654 2632 3376 +16968 389 3658 28 3683 +16969 2463 2447 2343 3268 +16970 1858 1991 1799 3194 +16971 1723 1911 1722 3264 +16972 2662 2661 2663 3192 +16973 2978 2657 2884 3478 +16974 2709 2710 2730 3220 +16975 1369 3707 1367 3746 +16976 1586 296 1609 3740 +16977 344 2569 343 3464 +16978 1164 1040 1119 3627 +16979 1070 1268 1237 3323 +16980 1867 1906 2023 3434 +16981 2992 2856 2984 3401 +16982 383 382 3493 3708 +16983 2088 2099 165 3573 +16984 1692 1911 1981 3527 +16985 1333 1332 1375 3714 +16986 259 1386 1400 3545 +16987 1609 296 2276 3740 +16988 278 1398 1384 3481 +16989 2518 2424 2303 3771 +16990 427 2777 30 3408 +16991 861 888 787 3200 +16992 2467 2316 2363 3583 +16993 3018 443 444 3501 +16994 1305 1048 1202 3688 +16995 2846 3525 2931 3632 +16996 2713 2708 2843 3345 +16997 1250 1208 1106 3773 +16998 1655 1656 1775 3586 +16999 1383 1396 275 3488 +17000 2281 1189 1120 3313 +17001 1031 1089 1105 3622 +17002 1224 1021 1174 3268 +17003 2524 345 2432 3356 +17004 2721 2686 2770 3392 +17005 1599 1784 1600 3250 +17006 1122 1187 925 3274 +17007 2592 2591 2590 3233 +17008 1085 1044 1172 3752 +17009 387 3018 3009 3655 +17010 940 942 184 3200 +17011 949 159 9 845 +17012 2850 2940 2941 3531 +17013 434 435 3004 3482 +17014 2647 2921 2645 3217 +17015 2676 2629 2743 3774 +17016 1988 2004 1984 3664 +17017 2401 2469 2328 3452 +17018 1833 1832 1831 3359 +17019 2979 2913 2954 3320 +17020 2795 2613 2797 3374 +17021 187 186 1303 3402 +17022 278 279 1398 3481 +17023 2350 2435 2539 3614 +17024 2371 2553 2471 3698 +17025 2445 2333 2470 3776 +17026 1445 1865 1448 3244 +17027 388 3711 387 3712 +17028 2639 2826 2827 3282 +17029 1421 1419 1852 3201 +17030 382 381 3491 3709 +17031 1683 1823 1686 3470 +17032 1540 1539 1454 3518 +17033 2070 2068 2069 3335 +17034 169 984 981 3681 +17035 375 374 3547 3593 +17036 2716 2715 2714 3715 +17037 1788 1875 1866 3280 +17038 309 2085 310 3298 +17039 2734 2735 2866 3396 +17040 2727 2725 3607 3701 +17041 2966 2743 2629 3409 +17042 384 3011 385 3498 +17043 1354 226 1357 3725 +17044 1315 1313 1314 3213 +17045 422 2609 2608 3227 +17046 419 3534 418 3641 +17047 1159 1289 1060 3697 +17048 2699 2928 3344 3346 +17049 2041 1972 1971 3522 +17050 345 2524 346 3722 +17051 1943 1874 1557 3270 +17052 1744 1604 1606 3390 +17053 1397 1383 276 3486 +17054 1364 1366 1367 3707 +17055 355 2560 354 3570 +17056 884 843 783 3213 +17057 360 2573 2563 3556 +17058 2352 2462 2426 3696 +17059 2452 2322 2419 3260 +17060 1854 1853 1870 3525 +17061 2849 2851 2850 3326 +17062 1916 1917 1918 3287 +17063 1446 1445 1448 3663 +17064 1918 2013 1927 3444 +17065 436 3017 435 3486 +17066 3014 3006 439 3492 +17067 1688 1687 1455 3216 +17068 194 1209 195 3580 +17069 1213 1151 1090 3731 +17070 2069 1675 1542 3334 +17071 2589 408 409 3564 +17072 338 2412 2456 3360 +17073 1403 2171 263 2269 +17074 2640 2753 2679 3448 +17075 2906 2978 2884 3206 +17076 1564 1562 1563 3680 +17077 968 971 969 3601 +17078 2318 2495 2423 3622 +17079 1886 1417 1415 3442 +17080 1902 1901 1713 3430 +17081 2018 840 123 920 +17082 1820 1907 1619 3738 +17083 2051 1877 1415 3443 +17084 2602 458 2603 3272 +17085 1855 1966 2081 3632 +17086 2375 2430 2535 3333 +17087 1127 1294 1306 3199 +17088 2642 2678 2883 3250 +17089 2181 2139 2226 3290 +17090 1309 1319 1312 3291 +17091 31 2776 411 3398 +17092 1133 1014 1234 3517 +17093 2294 2409 2497 3418 +17094 2589 2777 2780 3215 +17095 217 1162 1292 3367 +17096 1112 1232 1031 3667 +17097 970 967 966 3722 +17098 2600 2599 2598 3288 +17099 2351 2436 2324 3773 +17100 2580 2774 2775 3214 +17101 2915 2996 2995 3318 +17102 2469 2534 2418 3197 +17103 1512 1735 1827 3396 +17104 2395 2496 363 3566 +17105 2867 2901 2814 3420 +17106 1774 1426 1737 3588 +17107 260 1387 261 3543 +17108 1455 1451 1450 3505 +17109 1798 1865 1445 3244 +17110 2931 2985 2927 3668 +17111 2952 2914 2913 3424 +17112 1216 1082 1264 3509 +17113 2367 2443 339 3751 +17114 2543 2489 2310 3193 +17115 2392 2348 2543 3560 +17116 1354 1352 1353 3724 +17117 2435 2324 3435 3614 +17118 2982 2981 2924 3371 +17119 356 2567 355 3573 +17120 2452 2419 2303 3236 +17121 2401 2319 2477 3675 +17122 1352 1351 1348 3726 +17123 2380 2340 2505 3438 +17124 899 797 861 3224 +17125 1334 1333 1376 3712 +17126 1488 1468 1958 3341 +17127 2000 1996 2024 3471 +17128 161 955 961 3765 +17129 2077 1993 2004 3611 +17130 349 2417 2397 3644 +17131 2920 2919 2627 3530 +17132 2606 2593 2605 3276 +17133 28 389 3020 3658 +17134 1845 1526 1525 3308 +17135 224 3729 1284 3759 +17136 1561 1558 1576 3774 +17137 2989 2903 2990 3329 +17138 344 2549 345 3356 +17139 2643 2860 2641 3243 +17140 1141 1257 1083 3279 +17141 1896 1985 1837 3212 +17142 2981 2923 2924 3259 +17143 954 960 961 3692 +17144 1110 1152 1016 3203 +17145 1029 1087 1236 3643 +17146 2639 2742 2638 3325 +17147 1100 1027 1248 3660 +17148 2767 2680 2679 3216 +17149 1055 1204 1148 3347 +17150 2631 2630 2629 3441 +17151 2316 2439 2363 3583 +17152 1975 1974 1977 3475 +17153 783 825 870 3301 +17154 1230 1109 1043 3675 +17155 341 2537 26 3284 +17156 1327 1334 1328 3713 +17157 2035 2034 2026 3395 +17158 1329 233 1335 3745 +17159 1748 1745 1822 3190 +17160 1426 2198 304 2211 +17161 1046 1116 1198 3366 +17162 1714 1710 1709 3606 +17163 2292 2389 2541 3528 +17164 2722 2723 2703 3349 +17165 284 1578 285 3363 +17166 2591 2592 2595 3233 +17167 845 137 949 888 +17168 1351 1352 1356 3726 +17169 2366 2457 334 3348 +17170 2764 2677 2676 3255 +17171 2071 2064 1969 3648 +17172 2584 2582 445 3690 +17173 2612 2890 2891 3365 +17174 1781 2010 1947 3318 +17175 2818 2715 2863 3341 +17176 1577 1667 2060 3410 +17177 2695 2691 2796 3386 +17178 2395 363 362 3566 +17179 2741 2668 2740 3304 +17180 2977 2897 2947 3273 +17181 2002 1975 1977 3475 +17182 1302 3342 203 3719 +17183 1948 1949 1794 3211 +17184 1717 2033 1991 3210 +17185 361 2500 362 3457 +17186 2603 458 457 3272 +17187 1418 1891 1787 3529 +17188 1767 1788 1866 3280 +17189 1140 196 1251 3468 +17190 978 975 979 3736 +17191 3007 3014 440 3494 +17192 1971 1902 1970 3401 +17193 1059 1128 1079 3406 +17194 1897 1587 1835 3235 +17195 1534 125 912 813 +17196 2338 2494 2392 3406 +17197 437 3005 436 3488 +17198 1814 1833 1921 3629 +17199 1785 1784 1599 3250 +17200 268 1430 269 3502 +17201 1780 2029 1863 3700 +17202 842 885 118 1841 +17203 2813 2635 2812 3390 +17204 2810 2826 2822 3671 +17205 1521 1523 2056 3728 +17206 1496 1497 1495 3214 +17207 1545 328 1546 3370 +17208 2628 3610 2625 3611 +17209 2270 19 180 2109 +17210 390 2575 29 3247 +17211 1838 1985 1685 3349 +17212 1374 247 1369 3746 +17213 1274 1218 1157 3204 +17214 1609 1618 1584 3739 +17215 2888 2664 2893 3503 +17216 856 801 921 3251 +17217 1808 1710 1809 3515 +17218 1490 1491 1489 3215 +17219 400 3000 2992 3558 +17220 2632 2652 2859 3254 +17221 2913 2914 2849 3424 +17222 265 1391 264 3352 +17223 2036 1763 1920 3285 +17224 3474 2974 3668 3767 +17225 1674 1778 1664 3533 +17226 2444 3670 2394 3673 +17227 201 200 1297 3356 +17228 348 2570 347 3598 +17229 1346 1350 255 3653 +17230 2719 2720 2782 3421 +17231 1033 1197 1247 3625 +17232 1659 2018 1657 3537 +17233 1032 1100 1248 3696 +17234 2493 2408 2531 3252 +17235 2960 2975 2929 3218 +17236 380 2490 379 3450 +17237 2510 2458 2379 3283 +17238 231 232 1240 3702 +17239 2927 2985 2922 3514 +17240 1459 1847 1460 3336 +17241 169 2101 168 3575 +17242 1630 1631 1629 3431 +17243 179 2096 178 3463 +17244 2962 2927 2859 3616 +17245 1234 1097 1056 3704 +17246 2545 342 2537 3342 +17247 2411 2457 2328 3204 +17248 1802 1987 1990 3679 +17249 332 2444 333 3670 +17250 2379 2331 2451 3439 +17251 2458 2389 2292 3528 +17252 1315 241 1313 3213 +17253 278 1576 1661 3411 +17254 2415 2334 2438 3717 +17255 1785 1921 1833 3415 +17256 1798 1841 1676 3460 +17257 1765 1598 1596 3446 +17258 1328 1318 1327 3713 +17259 1476 1475 326 3265 +17260 2462 2388 2330 3697 +17261 2840 2838 2837 3738 +17262 2817 2825 2889 3393 +17263 1100 1010 1128 3661 +17264 1877 1878 1879 3217 +17265 2607 2604 2605 3637 +17266 1153 1228 1076 3706 +17267 316 2088 2100 3571 +17268 243 1392 244 3656 +17269 1557 1874 1792 3270 +17270 1250 3435 1125 3773 +17271 1868 1899 1867 3662 +17272 1883 279 1661 3480 +17273 2052 1618 1609 3739 +17274 1054 1213 1158 3559 +17275 1716 269 1431 3502 +17276 1930 2000 2023 3273 +17277 1673 1636 1674 3536 +17278 2346 2391 2547 3314 +17279 1839 1837 1818 3198 +17280 1591 1481 1447 3587 +17281 1189 3313 2210 3753 +17282 1080 1027 1108 3333 +17283 1241 1034 1167 3372 +17284 2952 2972 2914 3339 +17285 2969 2951 2965 3647 +17286 1627 2057 1762 3254 +17287 2358 2533 2332 3703 +17288 439 438 2980 3615 +17289 1073 1013 1222 3686 +17290 1536 1671 1857 3227 +17291 170 2090 169 3577 +17292 2861 2920 2964 3475 +17293 2191 23 308 1578 +17294 1018 1233 1216 3567 +17295 1142 3717 1028 3779 +17296 1227 1038 1132 3566 +17297 843 155 891 1315 +17298 394 393 2555 3603 +17299 2097 311 310 3557 +17300 25 3291 3290 3513 +17301 2574 409 2563 3557 +17302 447 2779 2781 3241 +17303 2530 2334 2415 3717 +17304 2343 2419 2463 3268 +17305 1556 1555 311 3564 +17306 1086 1142 1283 3717 +17307 2333 3567 2470 3776 +17308 1057 1229 1098 3360 +17309 3012 3002 431 3546 +17310 2966 435 2743 3410 +17311 1308 1140 1066 3776 +17312 2895 2768 2687 3417 +17313 266 1532 267 3690 +17314 2470 3567 2306 3780 +17315 2101 318 2089 3574 +17316 1644 1643 128 857 +17317 2353 2322 2432 3539 +17318 1360 1365 1361 3708 +17319 941 942 940 3200 +17320 1169 1071 1267 3260 +17321 2479 2381 355 3651 +17322 1904 1903 1982 3330 +17323 349 350 3735 3736 +17324 1147 1238 199 3384 +17325 2056 2033 1521 3728 +17326 1870 2031 2032 3645 +17327 1258 1200 1065 3332 +17328 2622 2971 2624 3733 +17329 1807 1964 1963 3634 +17330 2659 2647 2655 3443 +17331 2626 2627 2990 3664 +17332 2556 2570 396 3596 +17333 2538 371 2546 3294 +17334 2298 2478 2402 3752 +17335 310 1579 309 3408 +17336 2081 2058 1853 3668 +17337 354 2530 2415 3716 +17338 873 920 782 3537 +17339 2570 2557 397 3597 +17340 1215 1023 1185 3560 +17341 2643 2642 2883 3250 +17342 2748 2634 2635 3403 +17343 432 3480 433 3684 +17344 1640 1499 1504 3282 +17345 1781 2009 2010 3318 +17346 1776 1600 1687 3705 +17347 2237 2137 2185 3347 +17348 1804 1844 1422 3340 +17349 2093 2105 326 3603 +17350 1037 1266 1092 3771 +17351 1804 1424 1851 3369 +17352 2932 2672 2846 3632 +17353 958 203 952 3766 +17354 1559 1558 1561 3774 +17355 2748 2719 2634 3403 +17356 2109 2095 180 3202 +17357 2445 2397 2333 3776 +17358 2100 317 316 3569 +17359 984 982 981 3681 +17360 2486 2329 2368 3757 +17361 2327 2522 2453 3225 +17362 1319 1323 1320 3669 +17363 1680 1681 1746 3504 +17364 2589 2588 2587 3677 +17365 2852 2851 2849 3699 +17366 384 383 3496 3707 +17367 322 1571 1972 3524 +17368 2210 2123 2182 3753 +17369 2841 2832 419 3565 +17370 2938 2918 2937 3636 +17371 131 132 1554 803 +17372 2490 2406 2313 3666 +17373 1531 1528 1527 3221 +17374 1643 126 912 1535 +17375 2626 2973 2628 3612 +17376 2671 2936 2937 3635 +17377 1987 1802 1989 3679 +17378 1798 1444 1841 3460 +17379 1501 265 1592 3398 +17380 2715 2818 2819 3341 +17381 2542 2361 2408 3337 +17382 1832 1764 1689 3275 +17383 2073 1936 2028 3772 +17384 1278 2217 205 3284 +17385 1414 1561 2060 3409 +17386 1402 1391 241 3246 +17387 1769 313 1449 3609 +17388 2681 2768 2682 3417 +17389 1566 1690 3237 3762 +17390 876 216 17 1280 +17391 280 1883 1821 3508 +17392 2232 2139 2181 3290 +17393 2537 2393 2545 3342 +17394 319 2101 2090 3576 +17395 2869 2821 2870 3538 +17396 1985 1896 1436 3212 +17397 1783 1691 1439 3272 +17398 2670 2646 2644 3292 +17399 372 3015 373 3545 +17400 419 2844 2841 3641 +17401 2868 2771 459 3591 +17402 1442 1440 1441 3383 +17403 381 3006 382 3491 +17404 2373 2536 3199 3269 +17405 1261 1043 1115 3695 +17406 2106 817 78 914 +17407 1250 1125 1007 3773 +17408 244 1388 245 3655 +17409 2985 2931 2846 3525 +17410 187 1303 1179 3402 +17411 2935 2628 2933 3261 +17412 2945 2672 2673 3444 +17413 982 984 985 3681 +17414 1733 1575 1734 3511 +17415 2966 2670 435 3410 +17416 1081 1011 1126 3440 +17417 1145 1240 1270 3314 +17418 2806 2804 2809 3727 +17419 1570 1787 1891 3618 +17420 2003 2077 2004 3611 +17421 2319 2444 3673 3674 +17422 1822 1745 1651 3190 +17423 2445 2360 351 3580 +17424 2306 2470 2506 3567 +17425 190 1146 191 3651 +17426 2948 2977 2958 3434 +17427 1256 193 1142 3466 +17428 2293 2365 2509 3380 +17429 2859 2659 2630 3442 +17430 1392 267 1388 3654 +17431 2650 2660 2651 3285 +17432 2532 2356 2403 3517 +17433 2383 2507 2336 3427 +17434 1235 1286 1089 3252 +17435 1760 1761 1762 3253 +17436 1322 891 154 1314 +17437 315 314 2099 3639 +17438 2832 420 419 3565 +17439 881 829 781 3456 +17440 928 794 854 3274 +17441 2284 2210 2150 3313 +17442 3001 429 3015 3542 +17443 1045 1117 1262 3438 +17444 2750 2999 2645 3263 +17445 2713 2843 2926 3345 +17446 350 2571 349 3735 +17447 371 2538 25 3291 +17448 1904 1982 2004 3612 +17449 1825 1517 1742 3238 +17450 1439 1691 1656 3272 +17451 2159 289 288 1539 +17452 1832 1898 1764 3275 +17453 2843 2841 2844 3728 +17454 2877 2880 2943 3515 +17455 1815 1813 1961 3768 +17456 1188 214 215 2194 +17457 1392 1380 266 3657 +17458 2668 2738 2667 3430 +17459 2384 2311 2482 3579 +17460 1679 1680 1678 3386 +17461 1320 1324 1325 3669 +17462 876 825 783 3301 +17463 855 116 1446 1444 +17464 2351 2551 2409 3778 +17465 1644 1973 1671 3309 +17466 1466 1547 1446 3663 +17467 1509 1835 1836 3581 +17468 2318 2423 2531 3622 +17469 2986 2988 2906 3404 +17470 161 2097 160 3556 +17471 993 994 998 3755 +17472 2981 2853 2923 3259 +17473 1516 1513 1505 3327 +17474 2484 2519 2387 3372 +17475 2518 2451 2331 3293 +17476 2496 2384 364 3559 +17477 352 2416 353 3466 +17478 239 1311 1310 2247 +17479 2904 2946 2973 3330 +17480 1184 1114 1009 3473 +17481 1435 1562 1463 3455 +17482 972 973 969 3601 +17483 1090 1025 1213 3630 +17484 1935 1919 2050 3343 +17485 2496 364 363 3472 +17486 454 2760 2829 3621 +17487 2042 1925 1912 3412 +17488 1096 1055 1131 3348 +17489 2051 1415 1414 3443 +17490 1952 1953 1951 3328 +17491 2401 2366 2319 3674 +17492 1017 1199 1230 3452 +17493 239 1310 1321 2247 +17494 2950 2849 2746 3768 +17495 1961 1757 1815 3768 +17496 2912 2911 2910 3328 +17497 2624 2928 2908 3479 +17498 2490 380 2406 3450 +17499 1428 1427 1429 3589 +17500 1558 1662 1660 3255 +17501 2567 2561 405 3639 +17502 185 1161 186 3507 +17503 454 3739 455 3740 +17504 1132 1038 1093 3566 +17505 2699 2700 2928 3346 +17506 1680 1746 1748 3374 +17507 2622 2623 2986 3264 +17508 998 191 993 3755 +17509 2574 410 30 3298 +17510 314 1805 1449 3506 +17511 801 856 906 3251 +17512 3010 3020 389 3658 +17513 235 236 1163 3294 +17514 2977 2948 2949 3433 +17515 375 374 3012 3547 +17516 938 182 183 2201 +17517 234 1176 1261 3362 +17518 1969 1952 1954 3647 +17519 2791 2792 2793 3529 +17520 2669 2667 2998 3228 +17521 1894 1895 1826 3391 +17522 1574 1624 1508 3563 +17523 1569 1610 1570 3420 +17524 1329 1335 1330 3745 +17525 1203 1049 1124 3283 +17526 1619 2052 1617 3737 +17527 2745 3532 2942 3777 +17528 1314 891 154 1315 +17529 2980 2661 2733 3327 +17530 2866 2815 2817 3394 +17531 2765 3505 2766 3506 +17532 2709 2842 2708 3210 +17533 1328 1334 218 3713 +17534 1988 1989 1795 3530 +17535 374 2433 2550 3361 +17536 2294 2436 2409 3418 +17537 841 309 8 1579 +17538 1337 1331 1330 3744 +17539 414 2718 2900 3244 +17540 2952 2875 2972 3339 +17541 2874 2772 2773 3429 +17542 1008 1123 1255 3467 +17543 1412 1647 1776 3448 +17544 1898 1596 1595 3407 +17545 1870 1853 2062 3514 +17546 1177 1302 202 3719 +17547 1438 1733 1436 3392 +17548 1476 1752 2054 3350 +17549 2328 2366 2401 3452 +17550 995 996 994 3754 +17551 2662 2736 2732 3238 +17552 1327 1332 1333 3712 +17553 282 1386 281 3544 +17554 1167 1288 1023 3193 +17555 1566 1652 1567 3237 +17556 1022 1254 1195 3278 +17557 2991 438 437 3620 +17558 285 1390 284 3295 +17559 2713 2717 2710 3191 +17560 2455 2470 2306 3780 +17561 2999 3263 2991 3620 +17562 1917 1916 1926 3287 +17563 2636 2664 2665 3336 +17564 854 925 1187 3274 +17565 1189 2281 2210 3313 +17566 2442 2301 2351 3306 +17567 1675 1892 1893 3277 +17568 1000 997 1001 3578 +17569 1837 1583 1896 3354 +17570 2658 2656 2643 3242 +17571 2579 2785 2599 3222 +17572 440 2732 441 3659 +17573 357 356 2429 3437 +17574 1973 1668 1670 3310 +17575 1016 1219 1275 3267 +17576 441 2886 442 3357 +17577 2809 2729 2758 3423 +17578 2820 2821 2871 3412 +17579 1595 1846 1764 3764 +17580 1014 1228 1153 3706 +17581 2809 2688 2689 3422 +17582 1114 1050 1190 3758 +17583 2029 1936 1934 3259 +17584 1169 1092 1245 3236 +17585 2663 2997 2824 3436 +17586 1111 1308 1233 3568 +17587 2268 1594 1566 3762 +17588 1011 1194 1266 3293 +17589 229 1347 1344 3761 +17590 937 182 2244 948 +17591 1121 141 1186 838 +17592 1119 1188 215 2194 +17593 375 2525 374 3702 +17594 2814 2794 2793 3618 +17595 2863 2715 2716 3715 +17596 1411 316 1412 3449 +17597 1278 1290 1119 3284 +17598 2295 2450 2376 3688 +17599 1694 1634 1693 3479 +17600 1172 1118 1287 3539 +17601 842 117 116 1444 +17602 2528 2303 2419 3236 +17603 2515 2355 2501 3549 +17604 988 990 991 3718 +17605 1669 1890 1766 3289 +17606 1236 1285 197 3644 +17607 342 2554 2572 3463 +17608 3011 3007 441 3497 +17609 1605 1603 1604 3403 +17610 1076 1046 1153 3296 +17611 1708 1628 1732 3416 +17612 939 946 947 3358 +17613 1367 1369 1368 3707 +17614 2704 2703 2701 3400 +17615 1064 1114 1259 3608 +17616 2641 2660 2640 3447 +17617 1051 1180 1097 3445 +17618 1333 1375 1373 3714 +17619 1675 1672 1542 3334 +17620 2595 2594 2711 3350 +17621 2876 2885 2915 3561 +17622 1566 1690 1652 3237 +17623 1346 1343 1342 3642 +17624 1088 1035 1144 3584 +17625 445 444 2584 3690 +17626 2810 2811 2796 3504 +17627 2745 2942 2943 3777 +17628 128 1844 1644 916 +17629 1663 1523 1666 3641 +17630 1285 1087 1147 3257 +17631 1867 2023 1611 3434 +17632 2371 2321 2410 3316 +17633 2376 2341 2506 3377 +17634 2955 2956 2958 3476 +17635 2828 2823 2822 3256 +17636 383 3708 3707 3759 +17637 195 1209 1251 3580 +17638 2062 1940 1870 3514 +17639 1826 1827 1736 3393 +17640 1471 1884 1625 3426 +17641 1154 1085 1015 3750 +17642 1777 1715 1459 3503 +17643 1904 1871 1817 3399 +17644 2484 2540 2381 3323 +17645 1937 1964 1807 3634 +17646 316 315 2088 3571 +17647 982 979 981 3585 +17648 1121 1291 1279 3224 +17649 2769 2690 2896 3275 +17650 2684 2606 2683 3764 +17651 392 2569 393 3451 +17652 2071 1914 2064 3648 +17653 778 847 931 3373 +17654 2317 2513 2397 3643 +17655 2538 2546 2394 3294 +17656 1099 1170 1012 3414 +17657 954 961 955 3765 +17658 1118 1172 1044 3539 +17659 1813 1815 1810 3424 +17660 1022 1195 1265 3278 +17661 1192 1057 1098 3360 +17662 2615 2760 452 3219 +17663 2843 2699 2926 3335 +17664 1427 2211 305 2277 +17665 1932 1632 1931 3346 +17666 1196 1182 1019 3316 +17667 1010 1079 1128 3661 +17668 2961 2993 2962 3474 +17669 1818 1816 1817 3400 +17670 1013 1165 1137 3734 +17671 2055 1730 2041 3558 +17672 2077 1995 1993 3610 +17673 2910 2628 2935 3610 +17674 780 872 824 3731 +17675 1330 1335 1336 3745 +17676 1697 1552 2083 3404 +17677 2583 2782 2778 3419 +17678 2473 2309 2512 3366 +17679 2919 2918 2917 3679 +17680 1657 1534 1800 3258 +17681 1224 1085 1172 3752 +17682 943 944 945 3368 +17683 1363 1361 1364 3708 +17684 2942 2745 2941 3532 +17685 957 951 956 3720 +17686 1294 1123 1008 3467 +17687 1317 1318 1316 3683 +17688 1208 1250 1007 3773 +17689 1002 960 1000 3691 +17690 2939 2885 2942 3459 +17691 2294 2497 2392 3560 +17692 2856 2855 2854 3756 +17693 2854 2852 2998 3520 +17694 2845 2846 2672 3631 +17695 223 1365 224 3759 +17696 2440 2327 2485 3305 +17697 1039 1094 1187 3550 +17698 2720 2718 414 3244 +17699 1013 1105 1222 3734 +17700 1039 1162 1228 3549 +17701 2681 2687 2768 3417 +17702 1502 1588 1548 3239 +17703 2991 2980 438 3615 +17704 2801 2798 2799 3454 +17705 1104 1088 1030 3583 +17706 1321 2199 238 2247 +17707 2803 2686 2721 3511 +17708 2785 2786 2601 3319 +17709 1910 1840 1714 3315 +17710 1986 2042 2039 3538 +17711 1518 1605 1460 3624 +17712 1827 2048 1512 3396 +17713 2309 2386 2507 3665 +17714 2941 2940 2939 3531 +17715 831 120 119 1638 +17716 2925 2971 2944 3245 +17717 2695 2910 2935 3331 +17718 1895 1604 1744 3390 +17719 2762 2578 2576 3516 +17720 1793 1789 1814 3727 +17721 1118 201 1297 3356 +17722 1981 1693 1692 3527 +17723 1182 1042 1307 3378 +17724 1186 141 142 838 +17725 2463 2414 2298 3752 +17726 1133 1094 1039 3550 +17727 1595 1843 1526 3276 +17728 963 967 962 3721 +17729 242 1380 243 3658 +17730 2526 2316 2400 3584 +17731 1147 1267 1238 3384 +17732 455 2837 2838 3739 +17733 2337 2422 2488 3445 +17734 2577 430 429 3541 +17735 2870 2823 2739 3364 +17736 2535 2430 2325 3382 +17737 2873 2866 2824 3760 +17738 336 2411 2362 3307 +17739 2293 2396 2365 3380 +17740 2848 2749 2836 3742 +17741 2452 2390 2322 3260 +17742 2710 2717 2729 3465 +17743 2405 2376 2333 3568 +17744 988 985 987 3592 +17745 1818 1820 1839 3198 +17746 1129 1271 1220 3685 +17747 2707 2756 2722 3512 +17748 2929 2975 2940 3218 +17749 1438 1437 1574 3591 +17750 1522 1666 1523 3641 +17751 1586 1584 1585 3621 +17752 1068 1296 1166 3640 +17753 1816 1818 2045 3400 +17754 2803 2800 2798 3680 +17755 1336 1339 1338 3593 +17756 2923 2855 2649 3343 +17757 2272 291 1447 1591 +17758 383 3707 384 3759 +17759 2038 1986 2039 3538 +17760 2949 2898 2897 3471 +17761 219 1178 1304 3711 +17762 1340 1339 1336 3593 +17763 958 952 951 3766 +17764 1118 1263 201 3356 +17765 2993 2987 2994 3297 +17766 966 965 968 3613 +17767 2652 2653 2961 3253 +17768 349 2557 348 3599 +17769 985 988 989 3592 +17770 2996 2885 2939 3459 +17771 1925 1639 1856 3671 +17772 358 2380 359 3402 +17773 350 2397 2445 3468 +17774 2717 2907 2905 3353 +17775 2546 2421 2394 3673 +17776 2467 3729 383 3759 +17777 992 988 991 3718 +17778 1046 1198 1160 3366 +17779 2738 397 398 3524 +17780 954 953 959 3692 +17781 2383 2459 2512 3605 +17782 1241 1167 1079 3372 +17783 2809 2728 2729 3423 +17784 1237 1146 190 3651 +17785 2686 2601 2770 3563 +17786 2978 2959 2657 3478 +17787 1646 1647 1413 3678 +17788 975 974 980 3736 +17789 2937 2716 2671 3635 +17790 1056 1150 1206 3456 +17791 1732 1434 1708 3416 +17792 2394 2444 332 3670 +17793 2844 419 418 3641 +17794 1162 1076 1228 3549 +17795 994 996 997 3754 +17796 2782 2583 2719 3419 +17797 2312 2372 2483 3510 +17798 1311 240 2232 2247 +17799 1362 1358 1361 3709 +17800 2017 2060 2037 3292 +17801 2539 2386 2521 3278 +17802 1354 1355 1352 3724 +17803 1086 1146 1034 3650 +17804 2480 2340 2380 3438 +17805 2383 2336 2474 3427 +17806 1515 271 1743 3659 +17807 1498 1500 1859 3325 +17808 1330 1331 1324 3744 +17809 1044 1263 1118 3355 +17810 1634 1645 1692 3733 +17811 1950 1803 1962 3635 +17812 343 2545 2420 3719 +17813 970 200 967 3722 +17814 2694 2693 2691 3249 +17815 2498 2347 2417 3257 +17816 2395 2500 2339 3694 +17817 2631 2676 2675 3775 +17818 1786 1787 1570 3618 +17819 1027 1100 1128 3660 +17820 1487 1469 1926 3286 +17821 1342 1343 1339 3642 +17822 2890 2612 2610 3365 +17823 2316 2404 2523 3477 +17824 1108 1027 1253 3333 +17825 957 958 951 3720 +17826 2432 345 2549 3356 +17827 1463 1508 1485 3562 +17828 2019 2020 2021 3531 +17829 1287 1071 1169 3260 +17830 979 982 983 3585 +17831 1039 1228 1133 3550 +17832 2982 2924 2929 3371 +17833 2947 2953 2955 3248 +17834 399 2992 2984 3522 +17835 2348 2527 2460 3302 +17836 1225 1015 1134 3749 +17837 913 18 241 1402 +17838 1769 312 313 3609 +17839 439 2733 440 3495 +17840 1871 1872 1819 3413 +17841 1411 1805 315 3300 +17842 321 1972 2041 3522 +17843 2931 3668 2974 3767 +17844 1080 1108 1012 3382 +17845 1111 1048 1281 3688 +17846 2685 2598 2686 3562 +17847 1802 1807 1803 3636 +17848 1584 1587 1585 3621 +17849 2726 2783 2591 3689 +17850 2888 2734 2889 3425 +17851 2391 2428 2323 3640 +17852 1855 1853 1854 3525 +17853 297 298 1617 2196 +17854 1155 1230 1043 3675 +17855 2642 2679 2678 3705 +17856 2629 2676 2631 3774 +17857 2698 2830 2697 3334 +17858 841 8 134 1579 +17859 1115 1299 233 3361 +17860 1700 1782 1702 3561 +17861 2187 2146 2241 3586 +17862 2951 2952 2979 3649 +17863 327 1824 326 3265 +17864 2894 395 2892 3397 +17865 1000 999 997 3578 +17866 406 2765 405 3506 +17867 388 2461 387 3711 +17868 2384 365 364 3559 +17869 2637 2611 2612 3351 +17870 1705 1623 1706 3730 +17871 1244 1221 1059 3234 +17872 2914 2852 2849 3699 +17873 1209 1082 1216 3509 +17874 2671 2673 2672 3633 +17875 2308 2476 2511 3660 +17876 1141 1284 224 3729 +17877 2719 2718 2720 3421 +17878 1803 1963 1962 3635 +17879 1202 1018 1214 3377 +17880 2728 2731 2730 3280 +17881 942 941 137 888 +17882 1256 1142 1082 3779 +17883 1029 1138 1102 3769 +17884 383 3007 384 3496 +17885 2606 2604 2683 3407 +17886 1891 1869 1570 3317 +17887 2628 2625 2626 3611 +17888 2953 2714 2879 3287 +17889 2903 2904 2990 3329 +17890 28 2501 389 3367 +17891 1466 1446 1448 3663 +17892 1833 1831 1784 3359 +17893 1448 1603 1464 3421 +17894 2325 2431 2535 3382 +17895 1843 1474 1473 3299 +17896 2446 2315 2359 3781 +17897 2765 2766 405 3506 +17898 1308 1111 1029 3568 +17899 2768 2763 2762 3426 +17900 1898 1833 1900 3629 +17901 1729 1728 1646 3209 +17902 1652 1651 1481 3226 +17903 2985 2983 2922 3514 +17904 1626 1559 1416 3441 +17905 377 2493 376 3732 +17906 350 349 2397 3468 +17907 1198 1168 1022 3665 +17908 1471 1433 1470 3741 +17909 1979 2021 1959 3532 +17910 368 2403 369 3550 +17911 1282 1007 1143 3418 +17912 2420 2545 2393 3723 +17913 1058 1253 1125 3435 +17914 432 433 3003 3684 +17915 326 1824 1476 3265 +17916 2287 2203 2134 3383 +17917 2053 1863 1861 3520 +17918 1734 1575 1635 3511 +17919 1508 1575 1574 3563 +17920 2521 2350 2539 3278 +17921 1413 316 317 3449 +17922 1220 1009 1124 3528 +17923 2819 2745 2943 3777 +17924 2377 2318 2361 3667 +17925 416 2872 2619 3458 +17926 2312 2398 2472 3626 +17927 1272 1107 1008 3781 +17928 1064 1181 1114 3608 +17929 2508 2359 2315 3781 +17930 1158 1180 1065 3579 +17931 120 121 1778 820 +17932 2075 1829 2009 3478 +17933 2969 2964 2625 3548 +17934 1106 1208 1249 3306 +17935 1998 2024 1996 3471 +17936 2807 2678 2896 3359 +17937 2756 2803 2722 3470 +17938 382 2467 2363 3729 +17939 1142 1086 1028 3717 +17940 2656 2959 2960 3405 +17941 2981 2851 2853 3700 +17942 376 2493 2547 3732 +17943 304 303 2198 1426 +17944 1720 2079 1719 3345 +17945 334 2457 335 3348 +17946 2108 9 159 914 +17947 1183 1184 1061 3225 +17948 2883 2678 2807 3359 +17949 969 966 968 3613 +17950 1093 1207 1054 3472 +17951 1342 1345 1346 3653 +17952 262 1321 1377 3513 +17953 1210 227 1252 3450 +17954 2362 2449 2412 3646 +17955 1849 1770 1821 3516 +17956 945 954 955 3765 +17957 454 453 2760 3621 +17958 1088 1144 1284 3584 +17959 971 972 969 3601 +17960 1563 1562 1565 3454 +17961 421 2609 422 3227 +17962 2680 2767 2766 3216 +17963 1401 22 262 2269 +17964 2853 2854 2855 3756 +17965 1364 1367 1368 3707 +17966 1225 1134 1040 3751 +17967 1452 1443 1860 3701 +17968 963 962 957 3721 +17969 1163 1301 235 3294 +17970 1969 1954 1967 3647 +17971 1565 1562 1732 3454 +17972 1988 1795 2002 3530 +17973 278 277 1577 3411 +17974 780 824 878 3731 +17975 28 370 2501 3367 +17976 1420 1419 1421 3201 +17977 1168 1198 1069 3665 +17978 1059 1079 1215 3406 +17979 1941 1939 1938 3297 +17980 371 3019 3001 3543 +17981 1164 203 1302 3342 +17982 1968 1813 1812 3320 +17983 1140 1029 1236 3643 +17984 1786 1924 1923 3617 +17985 1441 289 290 2203 +17986 1816 1904 1817 3399 +17987 1617 1580 1582 3628 +17988 2933 2946 2704 3399 +17989 353 2530 354 3716 +17990 1104 1242 1035 3477 +17991 1430 1773 1847 3223 +17992 2368 2326 2447 3582 +17993 431 2762 432 3508 +17994 1226 1163 1041 3670 +17995 1290 1278 205 3284 +17996 2707 2902 2756 3512 +17997 2011 1974 1976 3375 +17998 1431 1459 1715 3503 +17999 2503 2398 2292 3625 +18000 1886 2062 2058 3616 +18001 2887 2819 2943 3281 +18002 1333 1334 1327 3712 +18003 1886 2058 2057 3616 +18004 2005 1510 2006 3436 +18005 1628 1565 1732 3376 +18006 1013 1073 1129 3686 +18007 2357 2295 2405 3770 +18008 1568 1569 1570 3420 +18009 2414 2322 2353 3539 +18010 1954 1951 2077 3548 +18011 2394 2421 2319 3673 +18012 203 1164 204 3342 +18013 1323 1324 1320 3669 +18014 2459 2383 386 3605 +18015 2604 2607 2689 3446 +18016 2085 2108 159 3231 +18017 1533 1501 1503 3262 +18018 1032 1159 1100 3696 +18019 1052 1199 1259 3197 +18020 1737 1574 1655 3591 +18021 1833 1814 1900 3629 +18022 2329 2449 2368 3757 +18023 1992 2004 1993 3612 +18024 1425 1851 1424 3369 +18025 2763 432 2762 3508 +18026 2373 2426 2536 3269 +18027 1168 1269 1035 3230 +18028 1193 1056 1097 3704 +18029 1175 1115 1043 3695 +18030 1413 1412 316 3449 +18031 2368 2307 2434 3758 +18032 1430 1431 269 3502 +18033 2357 2405 2317 3769 +18034 949 136 137 845 +18035 2430 2375 2308 3333 +18036 1111 1202 1048 3688 +18037 2699 2843 2698 3335 +18038 2426 2511 2352 3696 +18039 1346 1345 1350 3653 +18040 2812 2825 2816 3391 +18041 2395 2339 2481 3694 +18042 1237 189 1298 3437 +18043 1149 211 212 2180 +18044 954 959 960 3692 +18045 1560 1559 1708 3775 +18046 1457 1456 1543 3747 +18047 1161 1303 186 3507 +18048 2695 2796 2811 3386 +18049 2804 2807 2690 3629 +18050 2396 2373 2315 3467 +18051 2909 2901 2867 3420 +18052 1159 1060 1156 3697 +18053 2763 2768 2677 3426 +18054 1909 1906 1905 3476 +18055 2420 2393 2320 3723 +18056 2380 2499 359 3402 +18057 2969 2965 2964 3647 +18058 1390 1401 262 3311 +18059 857 1643 127 806 +18060 2240 2139 2199 3513 +18061 979 975 980 3736 +18062 2931 2927 2974 3668 +18063 1492 1493 1494 3241 +18064 1743 270 1716 3357 +18065 1960 1955 1959 3462 +18066 391 392 2590 3370 +18067 2624 2908 2621 3479 +18068 2550 2421 373 3362 +18069 2969 2910 2911 3328 +18070 2490 2313 2361 3666 +18071 1109 1020 1175 3388 +18072 2713 2944 2717 3191 +18073 1188 2220 214 2194 +18074 1146 1086 1283 3650 +18075 2382 2472 2332 3703 +18076 1876 300 301 2187 +18077 2371 2410 2492 3316 +18078 205 20 948 2217 +18079 2372 2315 2450 3687 +18080 350 2445 351 3580 +18081 373 2421 372 3362 +18082 2724 2721 2770 3392 +18083 2934 2933 2704 3399 +18084 1179 1075 1045 3693 +18085 1921 1793 1814 3727 +18086 1138 1281 1011 3770 +18087 2506 2341 2437 3377 +18088 2199 238 22 1321 +18089 2685 2798 2687 3455 +18090 145 144 824 1151 +18091 2808 2758 2905 3270 +18092 2651 2666 2924 3772 +18093 2991 437 2999 3620 +18094 2999 2750 2991 3263 +18095 2920 2861 2862 3271 +18096 1045 1075 1152 3693 +18097 2298 2414 2478 3752 +18098 1674 1672 1673 3536 +18099 1361 1365 1364 3708 +18100 307 306 2212 1409 +18101 2694 2933 2934 3261 +18102 1370 1369 1367 3746 +18103 1026 1126 1246 3510 +18104 2746 2941 2745 3532 +18105 1299 1240 232 3702 +18106 2876 2986 2878 3428 +18107 2371 2492 2313 3698 +18108 1220 1033 1129 3685 +18109 2304 2544 2423 3623 +18110 1184 1259 1114 3473 +18111 1767 1669 1766 3289 +18112 2742 2857 2725 3312 +18113 1170 1201 1080 3381 +18114 2377 2495 2318 3667 +18115 2292 2398 2516 3625 +18116 1594 1585 1690 3762 +18117 453 452 2760 3219 +18118 2331 2379 2516 3439 +18119 925 854 794 3274 +18120 2281 2150 2210 3313 +18121 840 123 122 1665 +18122 1374 1369 1370 3746 +18123 2302 2471 2529 3461 +18124 2427 2301 2520 3676 +18125 2586 2636 2634 3624 +18126 2629 2655 2966 3409 +18127 2350 2442 2435 3614 +18128 2838 2840 2839 3738 +18129 2760 2757 2829 3235 +18130 1568 1868 1867 3662 +18131 2508 2372 2312 3510 +18132 404 405 2767 3300 +18133 2848 2997 2749 3742 +18134 2841 2843 2842 3728 +18135 1150 146 147 829 +18136 2371 2313 2553 3698 +18137 1544 1427 305 2277 +18138 2880 2916 2879 3606 +18139 2425 366 365 3630 +18140 1205 1057 1149 3432 +18141 2348 2392 2497 3560 +18142 2972 2831 2998 3710 +18143 301 2241 1876 2187 +18144 2858 2813 2620 3389 +18145 2694 2935 2933 3261 +18146 408 2589 2587 3564 +18147 912 127 1643 806 +18148 2077 1977 1954 3548 +18149 2980 2751 2661 3327 +18150 872 146 145 1090 +18151 1091 210 211 2228 +18152 1177 1263 1044 3355 +18153 1658 2056 1659 3565 +18154 1576 278 1577 3411 +18155 2004 1992 1904 3612 +18156 1459 1460 1461 3336 +18157 1737 1655 1774 3588 +18158 1266 1194 1092 3293 +18159 952 947 951 3766 +18160 1428 1426 1427 3589 +18161 1627 1565 1628 3376 +18162 2593 2596 2587 3308 +18163 2502 2364 2311 3332 +18164 2397 2417 2317 3643 +18165 2211 304 1426 1427 +18166 2951 2869 2952 3649 +18167 1115 233 1261 3361 +18168 1770 1538 282 3541 +18169 1679 2063 1913 3521 +18170 2898 2970 2848 3652 +18171 1158 1025 1180 3579 +18172 2984 2856 2667 3401 +18173 2021 1979 1946 3532 +18174 1157 1212 1024 3307 +18175 2549 2420 2353 3355 +18176 2717 2758 2729 3465 +18177 210 209 2185 1148 +18178 2317 2424 2357 3769 +18179 1747 1745 1746 3208 +18180 2867 2815 2865 3232 +18181 2962 2993 2974 3474 +18182 1108 1273 1012 3382 +18183 1046 1076 1178 3296 +18184 424 2773 2789 3369 +18185 299 300 1593 2176 +18186 2882 2800 2802 3322 +18187 382 3014 383 3493 +18188 1956 1957 1955 3453 +18189 2536 2341 2514 3199 +18190 383 2467 382 3729 +18191 2916 2878 2623 3315 +18192 2788 2607 2605 3637 +18193 864 1186 142 838 +18194 450 2725 2899 3607 +18195 2435 2548 2375 3435 +18196 16 184 942 861 +18197 1041 1120 1189 3313 +18198 1122 1039 1187 3274 +18199 1050 1171 1295 3757 +18200 2711 2611 2595 3350 +18201 1881 1506 2008 3526 +18202 891 153 876 1322 +18203 2217 2153 2255 3284 +18204 1041 1189 1096 3753 +18205 2335 2479 2415 3650 +18206 1247 1026 1101 3626 +18207 206 2281 1120 1277 +18208 854 925 149 1187 +18209 1189 2281 207 2210 +18210 1583 1837 1839 3354 +18211 15 112 1615 835 +18212 2435 2324 2548 3435 +18213 2625 2627 2626 3611 +18214 925 150 1122 1280 +18215 1775 301 2241 1876 +18216 2700 2794 2901 3317 +18217 1671 1643 1644 3309 +18218 2699 2928 2925 3344 +18219 1058 1125 1250 3435 +18220 2466 2332 2440 3686 +18221 2861 2963 2957 3375 +18222 224 1284 223 3759 +18223 1908 1509 1836 3581 +18224 1062 1190 1295 3582 +18225 1624 1738 1483 3319 +18226 1796 1802 1803 3636 +18227 348 2417 349 3644 +18228 2586 2583 2584 3540 +18229 2846 2847 2985 3525 +18230 2247 2199 2139 3513 +18231 1038 1121 1186 3457 +18232 1574 1437 1655 3591 +18233 1090 1193 1025 3630 +18234 1030 1276 1136 3461 +18235 2932 2846 2931 3632 +18236 450 2727 2725 3607 +18237 1721 1699 1698 3387 +18238 1849 1471 1470 3741 +18239 150 149 925 1187 +18240 2281 207 206 1189 +18241 1747 1739 1745 3208 +18242 2747 2950 2746 3462 +18243 2319 2444 2394 3673 +18244 2464 2345 2517 3279 +18245 2382 2332 2533 3703 +18246 1476 1477 1475 3266 +18247 1084 1272 1255 3379 +18248 2744 2743 434 3411 +18249 213 2220 1188 1095 +18250 132 133 1406 859 +18251 2467 2400 2316 3584 +18252 2373 2293 2426 3269 +18253 1643 126 127 912 +18254 2751 2750 2749 3526 +18255 1181 1024 1098 3646 +18256 1102 1266 1037 3771 +18257 432 2764 433 3480 +18258 1171 1015 1085 3750 +18259 294 1566 2268 1594 +18260 2588 2787 2788 3299 +18261 1773 267 1532 3690 +18262 202 1302 203 3719 +18263 1040 1095 1188 3751 +18264 2579 2784 2785 3222 +18265 2807 2805 2658 3415 +18266 1186 143 1093 864 +18267 2910 2625 2628 3610 +18268 949 9 136 845 +18269 2427 2520 2369 3676 +18270 455 454 2837 3739 +18271 843 18 155 1315 +18272 397 2737 396 3600 +18273 1616 24 286 2197 +18274 2989 2976 2903 3385 +18275 2281 206 2181 1277 +18276 150 925 825 1280 +18277 2838 2833 455 3737 +18278 1377 1321 1310 3513 +18279 938 183 19 2201 +18280 1229 1134 1015 3749 +18281 2753 403 2754 3449 +18282 1566 2162 293 2268 +18283 1264 1142 1028 3779 +18284 2399 2295 2357 3770 +18285 2930 2931 2974 3767 +18286 293 294 1566 2268 +18287 1105 1013 1137 3734 +18288 2320 2393 2443 3723 +18289 1264 1082 1142 3779 +18290 2499 2468 360 3507 +18291 432 3003 3012 3684 +18292 1073 1223 1271 3305 +18293 2506 2470 2376 3567 +18294 456 455 2833 3737 +18295 2948 2865 2949 3433 +18296 2138 2276 2229 3740 +18297 2012 1930 1927 3682 +18298 2796 2795 2797 3374 +18299 126 912 1535 1534 +18300 2765 2769 2766 3505 +18301 118 117 842 1841 +18302 2107 331 24 2173 +18303 847 131 130 1423 +18304 1278 20 205 2217 +18305 1566 1594 1690 3762 +18306 861 942 138 888 +18307 1134 1095 1040 3751 +18308 2994 2930 2974 3767 +18309 214 213 2220 1188 +18310 877 122 121 1664 +18311 2911 2871 2951 3648 +18312 1443 1452 1454 3701 +18313 1279 184 16 861 +18314 2396 2446 2321 3379 +18315 2847 2836 2983 3645 +18316 181 2244 948 2217 +18317 2435 2442 2324 3614 +18318 2699 2925 2926 3344 +18319 239 240 1311 2247 +18320 2689 2772 2728 3289 +18321 1120 2281 206 1189 +18322 1122 150 925 1187 +18323 17 216 876 1322 +18324 1103 1241 1010 3763 +18325 302 303 1774 2198 +18326 1553 1490 1473 3743 +18327 2307 2465 2418 3608 +18328 1186 142 143 864 +18329 2514 2373 2536 3199 +18330 2884 2806 2808 3519 +18331 2483 2399 2331 3440 +18332 1609 296 297 2276 +18333 2470 2333 2376 3567 +18334 1508 1463 1635 3562 +18335 1216 1264 1130 3780 +18336 305 306 1544 2277 +18337 1930 2012 2001 3682 +18338 2474 2400 384 3619 +18339 2450 2315 2514 3687 +18340 891 155 154 1315 +18341 114 113 856 1549 +18342 2672 2932 2671 3633 +18343 115 116 1446 855 +18344 817 78 8 2106 +18345 298 299 1580 2233 +18346 1404 158 15 815 +18347 1537 284 283 3469 +18348 2153 215 1278 2217 +18349 861 141 1279 797 +18350 948 20 181 2217 +18351 2171 263 23 1403 +18352 921 115 114 1547 +18353 292 291 2272 1591 +18354 1188 1119 1040 3627 +18355 124 125 1657 873 +18356 2215 288 287 1541 +18357 129 130 1422 931 +18358 305 304 2211 1427 +18359 891 154 153 1322 +18360 128 129 1844 916 +18361 2232 21 240 1311 +18362 215 20 1278 2217 +18363 238 239 1321 2247 +18364 1401 263 22 2269 +18365 2108 78 9 914 +18366 2270 331 19 2109 +18367 127 128 1643 857 +18368 2229 296 295 1586 +18369 293 292 2213 1567 +18370 2268 295 294 1594 +18371 2319 2366 2444 3674 +18372 926 134 133 1407 +18373 942 138 16 861 +18374 2018 123 124 920 +18375 307 308 1410 2256 +18376 913 158 18 1402 +18377 912 126 125 1534 +18378 1206 147 148 881 +18379 209 208 2237 1204 +18380 885 119 118 1677 +18381 206 21 2181 1277 +18382 2287 291 290 1442 +18383 942 137 138 888 +18384 2282 287 286 1613 +18385 16 141 1279 861 +18386 1614 112 113 900 +18387 876 153 17 1322 +18388 144 143 911 1207 +18389 213 212 2267 1205 +18390 182 181 2244 948 +18391 825 17 150 1280 +18392 302 301 2241 1775 +18393 3763 1028 2388 1156 +18394 3763 2388 1028 3717 +18395 3278 1078 1058 2297 +18396 3278 1058 1078 1254 +18397 1796 3271 1794 1795 +18398 1794 3271 1796 3211 +18399 3697 1214 3199 1060 +18400 3697 3199 1214 3377 +18401 3645 2921 3526 2836 +18402 3645 3526 2921 3217 +18403 3676 2488 3517 2427 +18404 3676 3517 2488 3445 +18405 3478 1696 2083 2009 +18406 3478 2083 1696 3206 +18407 3476 1910 3527 1905 +18408 3476 3527 1910 3315 +18409 3316 3667 2296 2492 +18410 2296 3667 3316 1112 +18411 3479 1869 3346 3317 +18412 3479 3346 1869 1694 +18413 1931 3346 1869 3317 +18414 1931 1869 3346 1694 +18415 3630 2337 3579 2425 +18416 3630 3579 2337 3445 +18417 907 3183 928 816 +18418 928 3183 907 370 +18419 1334 3713 219 218 +18420 1334 219 3713 3711 +18421 1304 219 3713 218 +18422 1304 3713 219 3711 +18423 3637 3429 1851 3369 +18424 3637 1851 3429 3446 +18425 1191 3517 1097 1014 +18426 1097 3517 1191 3445 +18427 3686 3625 1101 3626 +18428 3686 1101 3625 3685 +18429 3332 3560 3418 1053 +18430 3418 3560 3332 2497 +18431 3170 924 3160 3119 +18432 3160 924 3170 837 +18433 1243 2359 3626 3510 +18434 2508 2359 3626 2382 +18435 2508 3626 2359 3510 +18436 3728 3334 1542 3641 +18437 3728 1542 3334 3335 +18438 3731 829 1090 3630 +18439 3731 1090 829 872 +18440 3123 930 802 871 +18441 802 930 3123 3148 +18442 3751 2129 3627 340 +18443 3751 3627 2129 2220 +18444 1604 3391 1895 1894 +18445 1895 3391 1604 3390 +18446 3356 1071 3384 1297 +18447 3356 3384 1071 3260 +18448 2485 3388 3225 2385 +18449 3225 3388 2485 3305 +18450 3225 2327 2485 2385 +18451 2485 2327 3225 3305 +18452 29 2195 3247 2128 +18453 3247 2195 29 390 +18454 3438 1288 3323 3193 +18455 3438 3323 1288 1117 +18456 3382 1078 1058 1273 +18457 3382 1058 1078 2297 +18458 3295 2188 3311 464 +18459 3295 3311 2188 2171 +18460 3025 2125 3058 2291 +18461 3025 3058 2125 3103 +18462 2527 3332 2497 2364 +18463 2497 3332 2527 3302 +18464 3645 1879 1940 2031 +18465 3645 1940 1879 3217 +18466 761 3246 28 465 +18467 28 3246 761 884 +18468 3182 865 3171 3113 +18469 3182 3171 865 788 +18470 1162 3713 217 218 +18471 217 3713 1162 3367 +18472 3508 1660 3480 1883 +18473 3508 3480 1660 3255 +18474 3647 2963 3320 2965 +18475 3647 3320 2963 3375 +18476 3645 1881 1879 2031 +18477 3645 1879 1881 3526 +18478 3550 854 369 826 +18479 3550 369 854 3274 +18480 3640 2485 3623 2428 +18481 3640 3623 2485 3305 +18482 3645 1940 1870 2031 +18483 3645 1870 1940 3514 +18484 3436 1741 2008 2005 +18485 3703 2359 3626 1243 +18486 3703 3626 2359 2382 +18487 3727 3270 2808 3519 +18488 3727 2808 3270 3423 +18489 3295 2126 2188 32 +18490 3295 2188 2126 2171 +18491 3488 2037 3620 275 +18492 3488 3620 2037 3292 +18493 3200 949 3231 1005 +18494 3200 3231 949 845 +18495 159 3231 949 1005 +18496 159 949 3231 845 +18497 3741 1528 3288 1470 +18498 3741 3288 1528 3221 +18499 3152 830 3174 3108 +18500 3174 830 3152 755 +18501 3225 2534 2299 3197 +18502 3225 2299 2534 2453 +18503 3436 2008 3742 2005 +18504 3436 3742 2008 3526 +18505 3353 1551 1557 1550 +18506 3353 1557 1551 3206 +18507 3529 2813 3390 3389 +18508 3529 3390 2813 2793 +18509 2189 3103 3073 3025 +18510 2189 3073 3103 2279 +18511 460 3591 459 2771 +18512 459 3591 460 3588 +18513 3150 907 761 932 +18514 3150 761 907 370 +18515 3371 1758 3700 2030 +18516 3371 3700 1758 3326 +18517 3574 1729 3678 3209 +18518 3574 3678 1729 318 +18519 3288 2581 3741 2600 +18520 3288 3741 2581 3221 +18521 1326 3713 243 3656 +18522 1326 243 3713 3683 +18523 3658 243 3713 3656 +18524 3658 3713 243 3683 +18525 3280 1858 1857 3194 +18526 3280 1857 1858 1866 +18527 2223 3240 3638 447 +18528 3638 3240 2223 2152 +18529 3519 2657 3415 3478 +18530 3519 3415 2657 2805 +18531 809 363 3161 852 +18532 809 3161 363 3134 +18533 3741 2681 3288 2600 +18534 3741 3288 2681 3417 +18535 3288 1528 1486 1484 +18536 3288 1486 1528 3221 +18537 2192 333 2172 3084 +18538 2192 2172 333 2123 +18539 369 854 928 767 +18540 928 854 369 3274 +18541 3195 867 3408 427 +18542 3195 3408 867 796 +18543 3309 912 1643 806 +18544 3309 1643 912 1535 +18545 832 799 465 932 +18546 3150 465 799 932 +18547 3150 799 465 3177 +18548 863 3178 822 3137 +18549 822 3178 863 769 +18550 3350 2592 3265 3233 +18551 3350 3265 2592 2594 +18552 3715 1917 3444 1962 +18553 3715 3444 1917 3287 +18554 1223 3388 3640 1020 +18555 3640 3388 1223 3305 +18556 3640 1166 1223 1020 +18557 1223 1166 3640 3305 +18558 1741 3526 3436 2008 +18559 3436 3526 1741 3192 +18560 1032 3380 3381 1201 +18561 3381 3380 1032 3269 +18562 3578 188 189 3437 +18563 3578 189 188 1003 +18564 2121 447 2257 2223 +18565 2121 2257 447 448 +18566 3283 1245 1174 1049 +18567 3283 1174 1245 3268 +18568 3265 1529 1545 1824 +18569 3265 1545 1529 3233 +18570 2254 452 2135 451 +18571 2135 452 2254 2224 +18572 1360 3729 3709 225 +18573 3709 3729 1360 3708 +18574 29 2223 3638 447 +18575 3638 2223 29 2128 +18576 3513 261 3291 1349 +18577 3513 3291 261 3311 +18578 3644 2498 3601 348 +18579 3644 3601 2498 3257 +18580 3539 1021 3260 1287 +18581 3539 3260 1021 3268 +18582 2130 3085 2168 2193 +18583 2130 2168 3085 3027 +18584 3413 1479 3581 3249 +18585 3413 3581 1479 1872 +18586 3102 2230 2122 453 +18587 2122 2230 3102 2274 +18588 3765 3402 953 3692 +18589 3765 953 3402 3507 +18590 3327 1741 1642 1513 +18591 3327 1642 1741 3192 +18592 3104 2110 3048 3023 +18593 3048 2110 3104 2193 +18594 3268 2528 3283 2343 +18595 3268 3283 2528 3236 +18596 2460 3693 2305 2505 +18597 2305 3693 2460 3302 +18598 3258 2609 3227 3194 +18599 3258 3227 2609 421 +18600 427 772 917 867 +18601 427 917 772 30 +18602 3068 2225 3036 3054 +18603 3068 3036 2225 2243 +18604 3746 222 1366 1371 +18605 3746 1366 222 3619 +18606 427 765 901 867 +18607 427 901 765 426 +18608 3728 1522 1523 3641 +18609 3728 1523 1522 1521 +18610 364 852 3161 363 +18611 3161 852 364 763 +18612 1299 3640 1115 1068 +18613 1115 3640 1299 3361 +18614 3384 1037 1147 1267 +18615 3384 1147 1037 3257 +18616 3463 946 950 178 +18617 3463 950 946 3358 +18618 3707 249 3708 3493 +18619 3707 3708 249 1368 +18620 3146 816 910 836 +18621 3146 910 816 3183 +18622 3753 2284 333 3313 +18623 3753 333 2284 2123 +18624 1542 3641 1672 1522 +18625 1672 3641 1542 3334 +18626 3738 2693 3413 3581 +18627 3738 3413 2693 2840 +18628 816 3150 907 3183 +18629 907 3150 816 932 +18630 3404 2978 2906 3206 +18631 3404 2906 2978 2988 +18632 3351 1641 1499 1622 +18633 3351 1499 1641 3256 +18634 3624 2585 3540 2586 +18635 3624 3540 2585 3223 +18636 3702 1341 3732 231 +18637 3702 3732 1341 3642 +18638 868 421 806 766 +18639 868 806 421 422 +18640 3753 1131 3670 3348 +18641 3753 3670 1131 1041 +18642 2016 3292 1878 2017 +18643 1878 3292 2016 3263 +18644 3227 2755 3280 3194 +18645 3227 3280 2755 2608 +18646 3453 3341 1976 1958 +18647 3453 1976 3341 3271 +18648 1978 1976 3341 1958 +18649 1978 3341 1976 3271 +18650 2356 3704 2532 2454 +18651 2532 3704 2356 3517 +18652 3410 2037 2060 3292 +18653 3410 2060 2037 1667 +18654 2129 3063 339 2165 +18655 2129 339 3063 340 +18656 453 3762 2162 452 +18657 2162 3762 453 2122 +18658 2162 2224 453 452 +18659 453 2224 2162 2122 +18660 248 3707 249 1368 +18661 249 3707 248 3496 +18662 3446 1900 1765 3422 +18663 3446 1765 1900 1596 +18664 3437 1117 188 1298 +18665 3437 188 1117 3438 +18666 902 3117 3156 786 +18667 3156 3117 902 3147 +18668 1485 3319 3563 1624 +18669 3563 3319 1485 3288 +18670 3777 1808 3459 3515 +18671 3777 3459 1808 1945 +18672 3561 3459 1808 3515 +18673 3561 1808 3459 1945 +18674 3384 2452 3257 3260 +18675 3384 3257 2452 2347 +18676 3771 3257 2452 3260 +18677 3771 2452 3257 2347 +18678 3341 1469 3715 1488 +18679 3341 3715 1469 3286 +18680 3727 2049 3415 1921 +18681 3727 3415 2049 3519 +18682 3477 1012 1104 1242 +18683 3477 1104 1012 3414 +18684 1953 3521 2064 2063 +18685 2064 3521 1953 3328 +18686 3022 3542 428 3001 +18687 428 3542 3022 3469 +18688 3405 2080 2043 3242 +18689 3405 2043 2080 1828 +18690 3623 2531 3252 2346 +18691 3623 3252 2531 3622 +18692 3587 2213 1591 3237 +18693 3587 1591 2213 2272 +18694 890 3154 764 821 +18695 890 764 3154 413 +18696 3147 764 3154 821 +18697 3147 3154 764 413 +18698 3205 2222 3363 463 +18699 3205 3363 2222 2151 +18700 196 3736 3644 978 +18701 3644 3736 196 3468 +18702 3606 1916 3476 3287 +18703 3606 3476 1916 1980 +18704 1002 3692 162 961 +18705 162 3692 1002 3691 +18706 927 417 416 3185 +18707 416 417 927 771 +18708 3768 1960 3320 1813 +18709 3768 3320 1960 3462 +18710 3687 1072 1294 3199 +18711 3687 1294 1072 1305 +18712 1738 3589 3591 1428 +18713 3591 3589 1738 3319 +18714 3284 1004 948 205 +18715 3284 948 1004 3229 +18716 3676 1106 1249 3306 +18717 3676 1249 1106 1063 +18718 3544 2578 3541 430 +18719 3544 3541 2578 3516 +18720 3358 204 3766 976 +18721 3358 3766 204 3342 +18722 3705 2680 3359 3216 +18723 3705 3359 2680 2678 +18724 3378 2302 2371 2448 +18725 3378 2371 2302 3461 +18726 3581 1834 3249 1509 +18727 3581 3249 1834 3196 +18728 338 2208 3074 2119 +18729 3074 2208 338 339 +18730 3338 2618 2617 3201 +18731 3338 2617 2618 2619 +18732 2494 3560 3234 2294 +18733 3234 3560 2494 3406 +18734 3053 2214 3039 2116 +18735 3053 3039 2214 3086 +18736 2163 3039 2214 2116 +18737 2163 2214 3039 3086 +18738 3660 2374 3333 2308 +18739 3660 3333 2374 3234 +18740 3556 1006 3231 160 +18741 3556 3231 1006 3368 +18742 844 3128 758 3155 +18743 844 758 3128 898 +18744 3292 2999 2645 2644 +18745 3292 2645 2999 3263 +18746 3343 1920 1728 3285 +18747 3343 1728 1920 1919 +18748 414 890 855 777 +18749 855 890 414 413 +18750 3028 3088 2144 2202 +18751 3028 2144 3088 3046 +18752 2218 2144 3088 2202 +18753 2218 3088 2144 3046 +18754 3385 1941 1990 3297 +18755 3385 1990 1941 2066 +18756 2799 3680 2798 2800 +18757 2798 3680 2799 3454 +18758 3682 1996 3273 3471 +18759 2000 3273 1996 3471 +18760 3241 448 447 3240 +18761 3241 447 448 2781 +18762 3557 2573 3298 3556 +18763 3557 3298 2573 2574 +18764 3358 1004 3284 976 +18765 3358 3284 1004 3229 +18766 3367 1280 3274 1122 +18767 3367 3274 1280 3301 +18768 1792 3423 1874 1790 +18769 1874 3423 1792 3270 +18770 3725 1257 3450 226 +18771 3725 3450 1257 3279 +18772 1210 3450 1257 226 +18773 1210 1257 3450 3279 +18774 3099 2218 3075 3046 +18775 3075 2218 3099 2178 +18776 2296 3734 1047 3703 +18777 2296 1047 3734 1137 +18778 1165 1047 3734 3703 +18779 1165 3734 1047 1137 +18780 3291 1293 237 236 +18781 3291 237 1293 3290 +18782 3663 801 1446 855 +18783 3663 1446 801 3251 +18784 921 1446 801 855 +18785 921 801 1446 3251 +18786 3625 1081 1197 1247 +18787 3625 1197 1081 3439 +18788 2542 3666 3450 2490 +18789 3450 3666 2542 3337 +18790 3731 1054 1213 1151 +18791 3731 1213 1054 3559 +18792 3215 409 2589 2777 +18793 3215 2589 409 3564 +18794 3465 1875 2072 1873 +18795 3465 2072 1875 3220 +18796 3566 2342 3203 2395 +18797 3566 3203 2342 3267 +18798 3613 175 174 3595 +18799 3613 174 175 965 +18800 3341 1948 1949 1488 +18801 3341 1949 1948 3211 +18802 3634 1966 3633 3632 +18803 3634 3633 1966 1964 +18804 3714 246 245 1375 +18805 3714 245 246 3500 +18806 3682 2000 1996 2001 +18807 3682 1996 2000 3273 +18808 1235 3761 228 229 +18809 228 3761 1235 3337 +18810 3765 160 161 955 +18811 3765 161 160 3556 +18812 2070 3728 1542 1521 +18813 1542 3728 2070 3335 +18814 3743 427 426 3195 +18815 3743 426 427 2780 +18816 3665 1269 3427 1069 +18817 3665 3427 1269 3230 +18818 3774 1577 1576 1561 +18819 3774 1576 1577 3411 +18820 3451 2592 393 392 +18821 3451 393 2592 3265 +18822 3781 2372 2315 2508 +18823 3781 2315 2372 3687 +18824 3400 3399 2046 1816 +18825 3400 2046 3399 3330 +18826 1903 2046 3399 1816 +18827 1903 3399 2046 3330 +18828 3609 2596 2587 2597 +18829 3609 2587 2596 3308 +18830 3682 1928 3273 1930 +18831 3682 3273 1928 3248 +18832 3431 3730 2740 3304 +18833 2740 3730 3431 3364 +18834 3513 2232 2139 2247 +18835 3513 2139 2232 3290 +18836 3546 1386 281 1399 +18837 3546 281 1386 3544 +18838 3658 465 28 3246 +18839 3658 28 465 3020 +18840 3726 254 253 1351 +18841 3726 253 254 3485 +18842 3742 2970 3436 3652 +18843 3742 3436 2970 2997 +18844 3531 1946 3532 2021 +18845 3531 3532 1946 3459 +18846 1794 3271 1949 1801 +18847 1949 3271 1794 3211 +18848 1429 3590 1427 1456 +18849 1427 3590 1429 3589 +18850 3601 173 172 3598 +18851 3601 172 173 971 +18852 3766 204 203 952 +18853 3766 203 204 3342 +18854 3345 2925 2713 3245 +18855 3345 2713 2925 2926 +18856 3610 1953 1951 1995 +18857 3610 1951 1953 3328 +18858 1613 2197 286 2282 +18859 1613 286 2197 1616 +18860 3686 2503 2407 3685 +18861 3686 2407 2503 2332 +18862 3679 2938 2918 2917 +18863 3679 2918 2938 3636 +18864 3473 2534 2418 2344 +18865 3473 2418 2534 3197 +18866 2456 3751 2367 339 +18867 2367 3751 2456 3749 +18868 272 3659 3494 271 +18869 3494 3659 272 3495 +18870 2311 3778 2409 2551 +18871 2409 3778 2311 3332 +18872 3439 1124 1049 3283 +18873 3439 1049 1124 1197 +18874 854 1094 148 826 +18875 148 1094 854 1187 +18876 3760 1510 3396 3436 +18877 3760 3396 1510 2048 +18878 3378 2371 2321 2448 +18879 3378 2321 2371 3316 +18880 3628 3354 1583 1582 +18881 1583 3354 3628 3604 +18882 1583 1581 3628 1582 +18883 3628 1581 1583 3604 +18884 3348 1204 3753 1096 +18885 3348 3753 1204 3347 +18886 3603 2569 393 2555 +18887 3603 393 2569 3451 +18888 1677 831 119 1638 +18889 1677 119 831 885 +18890 3293 2528 2303 2451 +18891 3293 2303 2528 3236 +18892 3702 3745 374 3593 +18893 374 3745 3702 3361 +18894 3053 2216 2261 455 +18895 3053 2261 2216 2116 +18896 3442 2632 2859 3254 +18897 3442 2859 2632 2630 +18898 3475 2963 3647 2964 +18899 3475 3647 2963 3375 +18900 3576 2559 401 3574 +18901 3576 401 2559 2565 +18902 3603 2712 3266 394 +18903 3603 3266 2712 3265 +18904 2947 3682 2897 2945 +18905 2897 3682 2947 3273 +18906 3384 2498 2347 2552 +18907 3384 2347 2498 3257 +18908 1409 3590 1543 1544 +18909 1543 3590 1409 3205 +18910 3689 1493 1540 3241 +18911 3689 1540 1493 1453 +18912 3730 2740 2741 2739 +18913 3730 2741 2740 3304 +18914 1403 2269 3311 2171 +18915 3311 2269 1403 1401 +18916 1402 815 158 1404 +18917 158 815 1402 913 +18918 3756 1861 1863 3520 +18919 3756 1863 1861 1862 +18920 3757 1181 1098 3646 +18921 3757 1098 1181 1050 +18922 3672 847 896 3373 +18923 3672 896 847 803 +18924 2902 3329 3330 2904 +18925 3330 3329 2902 3321 +18926 2902 3512 3330 3321 +18927 3589 1737 3591 1428 +18928 3589 3591 1737 3588 +18929 3638 1589 1613 1590 +18930 3638 1613 1589 3240 +18931 3415 1784 3250 3359 +18932 3415 3250 1784 1785 +18933 3770 1126 1011 3440 +18934 3770 1011 1126 1281 +18935 3733 1727 1721 3245 +18936 3733 1721 1727 1645 +18937 257 3593 258 1338 +18938 258 3593 257 3547 +18939 3626 2503 2398 2472 +18940 3626 2398 2503 3625 +18941 3769 2513 2405 2317 +18942 3769 2405 2513 3568 +18943 992 3716 993 192 +18944 993 3716 992 3718 +18945 3758 1295 3757 1050 +18946 3758 3757 1295 3582 +18947 2211 3590 2246 2157 +18948 2246 3590 2211 3589 +18949 3695 2550 2433 3361 +18950 3695 2433 2550 2354 +18951 3764 1526 1595 1846 +18952 3764 1595 1526 3276 +18953 3634 2671 2932 3633 +18954 3634 2932 2671 2936 +18955 3456 147 829 1150 +18956 3456 829 147 881 +18957 3398 1588 1501 3239 +18958 3398 1501 1588 1592 +18959 1594 2169 295 1586 +18960 1594 295 2169 2268 +18961 3347 209 2185 2237 +18962 3347 2185 209 1148 +18963 2326 3758 2368 2434 +18964 2368 3758 2326 3582 +18965 2106 914 3231 817 +18966 3231 914 2106 2108 +18967 2109 2173 331 2107 +18968 331 2173 2109 2270 +18969 3733 2621 3479 2624 +18970 3733 3479 2621 3527 +18971 799 465 903 832 +18972 799 903 465 3177 +18973 31 903 465 832 +18974 31 465 903 3177 +18975 3330 2902 2707 3512 +18976 2707 2902 3330 2904 +3 2 4 2290 +18977 3806 3835 732 3842 +18978 3786 3818 3793 3834 +18979 3793 3830 3794 3834 +18980 604 732 3835 3842 +18981 3783 3812 643 3859 +18982 732 3806 717 3835 +18983 915 3830 3793 3834 +18984 711 3797 735 3809 +18985 735 3797 826 3809 +18986 802 3784 67 3811 +18987 739 3808 3813 3815 +18988 793 3791 545 3867 +18989 732 717 626 3835 +18990 748 743 3788 3858 +18991 751 789 753 3792 +18992 608 565 3849 3858 +18993 741 740 891 3821 +18994 747 748 744 3788 +18995 3794 554 3802 3837 +18996 3784 3811 802 3848 +18997 648 3794 3802 3804 +18998 833 3793 75 3818 +18999 3794 3830 3798 3843 +19000 739 3813 3788 3815 +19001 727 3802 911 3843 +19002 3793 3823 3786 3834 +19003 833 75 879 3818 +19004 3809 3839 3797 3872 +19005 708 3802 727 3843 +19006 741 891 783 3821 +19007 726 3802 708 3804 +19008 75 3793 833 3826 +19009 640 3798 3802 3837 +19010 591 3822 3800 3853 +19011 622 3814 3789 3852 +19012 3794 3830 809 3834 +19013 586 3839 3809 3872 +19014 789 753 3792 3821 +19015 473 472 468 3785 +19016 472 474 469 3785 +19017 748 745 743 3858 +19018 708 3804 3802 3843 +19019 747 612 748 3788 +19020 880 3818 3786 3834 +19021 708 727 713 3843 +19022 659 3811 3784 3827 +19023 151 3788 825 3815 +19024 75 3818 3793 3833 +19025 726 587 3802 3804 +19026 735 716 826 3797 +19027 717 3806 3802 3835 +19028 763 3802 3798 3843 +19029 708 713 3804 3843 +19030 3805 3845 3789 3846 +19031 915 809 3830 3834 +19032 881 735 826 3809 +19033 880 3793 3818 3834 +19034 648 3794 554 3802 +19035 3794 3823 3793 3834 +19036 880 3793 756 3818 +19037 743 3821 3788 3858 +19038 621 3842 562 3872 +19039 659 67 3784 3811 +19040 640 3802 554 3837 +19041 609 3819 566 3841 +19042 75 3793 3826 3853 +19043 560 3811 3827 3851 +19044 586 3842 621 3872 +19045 748 3788 612 3858 +19046 3794 3802 3798 3837 +19047 69 3831 3790 3844 +19048 741 783 876 3788 +19049 586 3809 3842 3872 +19050 741 783 3788 3821 +19051 575 3790 3811 3851 +19052 876 825 151 3788 +19053 741 743 740 3821 +19054 707 736 3813 3824 +19055 111 577 661 3784 +19056 475 476 472 3785 +19057 75 3833 3793 3853 +19058 3800 3805 639 3837 +19059 591 652 3822 3853 +19060 3799 3829 738 3868 +19061 73 3822 652 3826 +19062 626 717 3802 3835 +19063 608 3849 750 3858 +19064 745 3821 743 3858 +19065 830 69 3790 3811 +19066 543 3791 817 3856 +19067 935 3793 792 3830 +19068 718 3809 586 3839 +19069 566 3819 3791 3841 +19070 619 3805 3789 3814 +19071 152 579 747 3788 +19072 643 3812 3783 3827 +19073 848 3795 3842 3871 +19074 542 545 543 3791 +19075 654 69 3790 3844 +19076 787 888 3799 3867 +19077 3800 3822 822 3826 +19078 743 741 3788 3821 +19079 866 6 3784 3866 +19080 711 3797 3809 3839 +19081 743 744 748 3788 +19082 727 720 911 3802 +19083 3798 3830 763 3843 +19084 140 3799 578 3869 +19085 775 3845 3822 3870 +19086 599 140 578 3869 +19087 3782 3813 641 3824 +19088 775 3822 3800 3870 +19089 735 711 716 3797 +19090 888 705 704 3799 +19091 3792 3849 565 3858 +19092 3822 3845 3805 3870 +19093 722 738 3799 3829 +19094 575 3790 654 3811 +19095 747 579 612 3788 +19096 76 3803 3818 3833 +19097 899 3799 3787 3832 +19098 654 3790 69 3811 +19099 609 566 631 3841 +19100 3798 3806 878 3828 +19101 750 3849 3792 3858 +19102 3782 3824 641 3859 +19103 562 3835 3795 3842 +19104 644 3786 595 3864 +19105 578 3799 699 3841 +19106 659 3784 661 3827 +19107 705 3799 888 3867 +19108 716 3808 3797 3839 +19109 598 661 577 3784 +19110 3798 3802 878 3806 +19111 69 830 3790 3831 +19112 741 876 151 3788 +19113 601 639 3805 3837 +19114 3798 3802 3794 3843 +19115 3789 3845 788 3846 +19116 825 3788 870 3815 +19117 930 3811 3783 3848 +19118 548 3798 3814 3835 +19119 722 3829 3799 3869 +19120 566 3791 631 3841 +19121 661 3784 598 3827 +19122 562 604 3835 3842 +19123 152 747 744 3788 +19124 3787 3799 899 3868 +19125 718 728 586 3809 +19126 848 3795 780 3842 +19127 846 3845 3805 3846 +19128 792 935 915 3793 +19129 880 915 756 3793 +19130 473 614 472 3785 +19131 472 614 474 3785 +19132 616 654 650 3811 +19133 880 915 3793 3834 +19134 640 3802 3798 3835 +19135 727 911 864 3843 +19136 783 825 876 3788 +19137 907 816 928 3815 +19138 645 726 712 3804 +19139 622 619 3789 3814 +19140 739 724 3808 3815 +19141 802 866 67 3784 +19142 548 3798 3805 3814 +19143 575 3811 560 3851 +19144 748 746 745 3858 +19145 560 3811 616 3827 +19146 907 3815 3807 3820 +19147 690 577 111 3810 +19148 722 3799 140 3869 +19149 881 721 735 3809 +19150 707 3813 3808 3824 +19151 722 738 140 3799 +19152 575 654 616 3811 +19153 645 587 726 3804 +19154 6 67 866 3784 +19155 543 542 3791 3856 +19156 3795 3806 3798 3828 +19157 655 3838 3831 3844 +19158 721 711 735 3809 +19159 467 576 3785 3862 +19160 3798 3806 3795 3835 +19161 732 710 3806 3842 +19162 626 3802 564 3835 +19163 822 3800 775 3822 +19164 73 822 3822 3826 +19165 610 3814 3795 3835 +19166 609 544 3819 3841 +19167 726 708 712 3804 +19168 732 710 717 3806 +19169 751 753 749 3792 +19170 586 647 3839 3872 +19171 716 3797 711 3839 +19172 595 3786 644 3836 +19173 545 3791 542 3867 +19174 579 3788 152 3813 +19175 647 3797 3839 3872 +19176 586 621 562 3872 +19177 622 3789 3844 3852 +19178 799 3783 910 3820 +19179 713 727 864 3843 +19180 800 3786 3832 3834 +19181 935 3826 3793 3830 +19182 75 909 879 3818 +19183 799 930 910 3783 +19184 930 3783 3811 3850 +19185 3793 3823 3794 3837 +19186 631 3791 3836 3869 +19187 763 878 3798 3802 +19188 3795 3814 3798 3835 +19189 567 3805 3800 3822 +19190 467 3785 468 3862 +19191 654 651 69 3844 +19192 575 654 3790 3844 +19193 722 140 599 3869 +19194 934 3806 3795 3828 +19195 648 3794 3804 3865 +19196 724 151 825 3815 +19197 715 3824 3808 3839 +19198 3831 3838 3789 3844 +19199 780 3795 3806 3842 +19200 728 3809 709 3842 +19201 3789 3814 3796 3852 +19202 656 591 652 3822 +19203 659 111 661 3784 +19204 632 3785 576 3803 +19205 75 833 923 3826 +19206 3798 570 3805 3837 +19207 750 3792 749 3858 +19208 3789 3838 3831 3845 +19209 720 824 911 3802 +19210 718 586 625 3839 +19211 557 3800 3793 3853 +19212 934 878 3806 3828 +19213 707 715 736 3824 +19214 557 3793 3800 3837 +19215 3793 3794 3830 3837 +19216 616 3811 650 3827 +19217 749 3792 753 3821 +19218 833 879 75 791 +19219 639 3800 567 3805 +19220 915 792 3793 3830 +19221 3798 3814 3795 3828 +19222 825 783 870 3788 +19223 3805 3845 846 3870 +19224 883 3787 899 3868 +19225 472 473 474 614 +19226 846 788 3845 3846 +19227 632 3785 3803 3840 +19228 577 3784 111 3810 +19229 3792 3821 749 3858 +19230 643 3851 3783 3859 +19231 616 560 575 3811 +19232 648 3802 587 3804 +19233 622 572 3814 3852 +19234 3782 3820 816 3861 +19235 694 692 693 3810 +19236 76 3818 3803 3863 +19237 736 618 3813 3824 +19238 3792 3812 565 3849 +19239 711 3809 718 3839 +19240 775 862 3822 3845 +19241 910 3783 930 3850 +19242 75 76 909 3818 +19243 610 548 3814 3835 +19244 76 3818 75 3833 +19245 548 3798 570 3805 +19246 700 3799 705 3867 +19247 3799 3841 578 3869 +19248 722 599 3829 3869 +19249 802 3811 930 3848 +19250 699 578 140 3799 +19251 751 3792 749 3825 +19252 576 3803 3785 3862 +19253 848 3842 829 3871 +19254 910 3820 3783 3850 +19255 578 699 611 3841 +19256 932 907 3807 3820 +19257 659 650 3811 3827 +19258 73 656 652 3822 +19259 139 861 3799 3868 +19260 3795 562 3842 3872 +19261 69 651 3831 3844 +19262 748 612 746 3858 +19263 699 3799 700 3841 +19264 865 3789 788 3846 +19265 846 3805 3828 3846 +19266 798 911 3802 3843 +19267 713 864 3804 3843 +19268 643 594 3812 3827 +19269 75 3826 74 3853 +19270 930 3783 799 3848 +19271 707 3808 715 3824 +19272 863 3800 822 3826 +19273 3793 557 3823 3837 +19274 600 3803 576 3862 +19275 854 3797 716 3808 +19276 889 781 3809 3860 +19277 661 650 659 3827 +19278 658 3803 600 3862 +19279 577 3784 633 3827 +19280 542 3791 3841 3867 +19281 3784 3827 3811 3848 +19282 601 3805 570 3837 +19283 3782 3807 3815 3820 +19284 864 713 3804 3868 +19285 636 591 656 3822 +19286 3793 3830 3800 3837 +19287 749 3825 3792 3849 +19288 763 878 3802 3843 +19289 629 565 3812 3849 +19290 3808 3824 3797 3839 +19291 6 659 67 3784 +19292 63 35 2 685 +19293 64 41 5 678 +19294 869 788 865 3789 +19295 3787 3834 3804 3868 +19296 753 789 913 3821 +19297 612 3788 579 3858 +19298 799 3783 3820 3848 +19299 476 468 472 3785 +19300 469 475 472 3785 +19301 3802 3806 3798 3835 +19302 3782 3824 3859 3861 +19303 3829 3868 3799 3869 +19304 152 3788 739 3813 +19305 861 787 888 3799 +19306 631 3841 3791 3869 +19307 76 804 3818 3863 +19308 76 804 909 3818 +19309 848 780 829 3842 +19310 704 705 701 3799 +19311 933 3786 880 3818 +19312 897 3830 3794 3843 +19313 866 3784 802 3848 +19314 661 598 650 3827 +19315 750 749 3792 3849 +19316 783 741 876 891 +19317 542 3819 3791 3856 +19318 826 889 781 3809 +19319 610 3795 635 3835 +19320 741 744 743 3788 +19321 773 3804 3834 3868 +19322 870 3815 3788 3854 +19323 929 3790 892 3850 +19324 6 691 111 3784 +19325 732 604 714 3842 +19326 637 3788 579 3813 +19327 897 3794 852 3843 +19328 562 604 635 3835 +19329 74 75 923 3826 +19330 3789 3838 622 3844 +19331 549 643 3812 3859 +19332 917 800 933 3786 +19333 3802 3804 3794 3843 +19334 829 3842 3809 3871 +19335 775 846 3845 3870 +19336 700 3841 3799 3867 +19337 157 749 3821 3858 +19338 854 3797 3808 3861 +19339 699 700 698 3841 +19340 631 3836 552 3869 +19341 3811 3827 3783 3848 +19342 830 3790 929 3850 +19343 761 3807 907 3815 +19344 917 3786 933 3818 +19345 601 548 570 3805 +19346 780 3806 872 3842 +19347 924 822 73 3826 +19348 691 111 3784 3810 +19349 897 809 852 3794 +19350 562 635 3795 3835 +19351 467 40 576 3862 +19352 750 749 157 3858 +19353 598 577 633 3827 +19354 76 3862 1 3863 +19355 822 863 775 3800 +19356 643 3827 3783 3851 +19357 839 3791 3816 3856 +19358 601 570 639 3837 +19359 569 587 645 3804 +19360 800 3786 917 3816 +19361 597 579 152 3813 +19362 720 824 3802 3806 +19363 934 780 3795 3806 +19364 475 3855 3785 3856 +19365 3807 3817 3812 3859 +19366 702 700 705 3867 +19367 911 824 798 3802 +19368 3805 3822 567 3838 +19369 3797 3839 3824 3857 +19370 3786 917 3816 3818 +19371 3782 3815 3808 3861 +19372 3857 3859 3824 3861 +19373 3807 3812 3783 3859 +19374 691 3784 6 3866 +19375 718 709 728 3809 +19376 706 3829 3804 3868 +19377 562 621 604 3842 +19378 567 3800 591 3822 +19379 739 3808 707 3813 +19380 830 68 69 3811 +19381 76 3803 3862 3863 +19382 610 635 548 3835 +19383 861 888 704 3799 +19384 3801 3847 808 3860 +19385 839 817 793 3791 +19386 655 3831 70 3844 +19387 870 3788 783 3854 +19388 596 640 3798 3835 +19389 763 3830 3798 3870 +19390 3786 3816 800 3832 +19391 788 3789 869 3845 +19392 797 899 3799 3868 +19393 644 547 3786 3864 +19394 3786 3818 3816 3863 +19395 832 3792 789 3825 +19396 632 3840 3803 3864 +19397 800 3832 823 3834 +19398 3796 3857 624 3872 +19399 551 3784 3810 3849 +19400 839 817 3791 3856 +19401 548 596 3798 3835 +19402 3801 3859 3857 3861 +19403 35 3855 475 3856 +19404 830 3811 3790 3850 +19405 3805 3814 3798 3828 +19406 705 700 701 3799 +19407 932 907 761 3807 +19408 832 3807 3792 3848 +19409 3809 3842 3795 3871 +19410 691 3810 3784 3866 +19411 716 854 826 3797 +19412 797 3799 861 3868 +19413 924 769 822 3826 +19414 686 3810 64 3825 +19415 706 3804 713 3868 +19416 869 3789 865 3847 +19417 933 800 880 3786 +19418 598 3784 577 3827 +19419 740 742 891 3821 +19420 892 3847 3801 3850 +19421 852 3794 809 3843 +19422 551 3784 577 3810 +19423 809 3794 897 3830 +19424 700 702 3841 3867 +19425 476 3785 475 3855 +19426 542 3841 79 3867 +19427 800 880 3786 3834 +19428 3810 3825 686 3849 +19429 699 701 700 3799 +19430 559 641 3813 3824 +19431 553 579 637 3788 +19432 3789 3796 3847 3852 +19433 611 699 698 3841 +19434 587 648 554 3802 +19435 892 808 3801 3847 +19436 656 605 636 3822 +19437 727 708 720 3802 +19438 590 622 3838 3844 +19439 68 654 69 3811 +19440 637 3788 3813 3817 +19441 3808 3815 928 3861 +19442 883 3787 823 3832 +19443 826 3860 3797 3861 +19444 740 743 742 3821 +19445 587 717 726 3802 +19446 3812 3817 549 3859 +19447 473 468 614 3785 +19448 474 614 469 3785 +19449 3787 3868 3829 3869 +19450 762 895 899 3832 +19451 720 3802 717 3806 +19452 825 794 3808 3815 +19453 833 756 3793 3818 +19454 588 641 3824 3859 +19455 904 3860 3796 3871 +19456 775 3800 863 3870 +19457 551 3812 3784 3849 +19458 862 822 775 3822 +19459 883 3834 3787 3868 +19460 658 617 600 3803 +19461 864 911 798 3843 +19462 716 715 3808 3839 +19463 3783 3827 3811 3851 +19464 805 3798 878 3828 +19465 724 825 3808 3815 +19466 5 3825 749 3849 +19467 636 567 591 3822 +19468 139 725 861 3868 +19469 773 3804 864 3843 +19470 830 929 892 3850 +19471 846 3828 3805 3870 +19472 575 620 654 3844 +19473 3784 3848 866 3866 +19474 751 749 5 3825 +19475 152 151 739 3788 +19476 824 878 3802 3806 +19477 79 545 542 3867 +19478 591 567 639 3800 +19479 892 3790 929 3847 +19480 897 763 3830 3843 +19481 3787 3799 3868 3869 +19482 865 788 846 3846 +19483 745 746 157 3858 +19484 111 659 6 3784 +19485 562 3795 610 3872 +19486 586 647 625 3839 +19487 549 643 594 3812 +19488 76 653 3803 3833 +19489 3786 3787 3834 3865 +19490 746 612 585 3858 +19491 648 571 3794 3865 +19492 626 717 587 3802 +19493 833 915 935 3793 +19494 915 809 897 3830 +19495 929 3790 830 3831 +19496 616 650 598 3827 +19497 547 644 3786 3836 +19498 151 744 741 3788 +19499 551 633 577 3784 +19500 570 3798 640 3837 +19501 557 3793 592 3853 +19502 934 878 780 3806 +19503 574 3833 3793 3864 +19504 560 3827 643 3851 +19505 3793 3833 574 3853 +19506 466 468 476 3862 +19507 935 833 3793 3826 +19508 640 570 596 3798 +19509 603 642 558 3865 +19510 620 651 654 3844 +19511 798 3802 878 3843 +19512 545 914 793 3867 +19513 904 882 3860 3871 +19514 3794 3834 809 3843 +19515 648 587 569 3804 +19516 3804 3829 569 3865 +19517 601 639 567 3805 +19518 929 3790 3831 3847 +19519 637 553 3788 3817 +19520 765 76 1 3863 +19521 854 826 3797 3861 +19522 889 3860 826 3861 +19523 563 3805 567 3838 +19524 3796 3814 572 3852 +19525 660 76 3803 3862 +19526 848 3828 3795 3871 +19527 763 851 3830 3870 +19528 554 3794 623 3837 +19529 75 923 833 791 +19530 848 934 780 3795 +19531 704 701 139 3799 +19532 3787 3786 3836 3865 +19533 631 552 3841 3869 +19534 151 152 744 3788 +19535 720 717 710 3806 +19536 3791 3832 3799 3867 +19537 686 3825 5 3849 +19538 933 880 756 3818 +19539 3809 3860 781 3871 +19540 3796 3846 904 3871 +19541 729 3809 829 3842 +19542 861 704 139 3799 +19543 871 786 830 3811 +19544 897 852 763 3843 +19545 780 872 829 3842 +19546 3824 3839 647 3857 +19547 789 3792 832 3854 +19548 762 883 823 3832 +19549 932 816 907 3820 +19550 562 635 610 3795 +19551 832 3792 3825 3848 +19552 548 3805 619 3814 +19553 3789 3831 869 3845 +19554 879 909 75 791 +19555 773 3834 3804 3843 +19556 566 580 3791 3819 +19557 579 3788 553 3858 +19558 631 3791 580 3836 +19559 468 3785 476 3862 +19560 552 578 3841 3869 +19561 3816 3818 917 3863 +19562 3785 3855 476 3862 +19563 600 632 576 3803 +19564 712 645 3804 3829 +19565 839 3791 793 3867 +19566 881 826 781 3809 +19567 925 825 794 3808 +19568 887 3831 70 3845 +19569 571 3794 3823 3837 +19570 706 712 3804 3829 +19571 3787 3832 3786 3834 +19572 3797 3860 3809 3872 +19573 653 617 658 3803 +19574 3807 3815 761 3854 +19575 869 3831 3789 3847 +19576 3800 3826 3793 3853 +19577 3782 3817 3807 3859 +19578 647 3857 3797 3872 +19579 908 69 830 786 +19580 557 592 3793 3823 +19581 787 3799 899 3867 +19582 651 70 3831 3844 +19583 548 596 570 3798 +19584 3786 3793 3818 3864 +19585 805 763 3798 3870 +19586 908 830 69 3831 +19587 3799 3832 3791 3869 +19588 630 565 608 3858 +19589 3789 3814 3805 3846 +19590 466 476 3855 3862 +19591 641 549 602 3859 +19592 632 550 3785 3840 +19593 789 3821 3792 3854 +19594 3793 3826 3800 3830 +19595 934 3795 848 3828 +19596 733 711 718 3839 +19597 580 3791 3819 3840 +19598 632 595 3840 3864 +19599 708 713 712 3804 +19600 756 915 833 3793 +19601 1 3862 867 3863 +19602 904 3846 3796 3847 +19603 3786 3840 595 3864 +19604 568 647 3824 3839 +19605 5 686 64 3825 +19606 565 3792 581 3812 +19607 648 571 554 3794 +19608 3792 3807 832 3854 +19609 861 797 899 3799 +19610 3793 3823 592 3864 +19611 3786 3836 595 3840 +19612 3782 3815 3807 3817 +19613 699 140 701 3799 +19614 3860 3871 3809 3872 +19615 823 3787 883 3834 +19616 75 657 3833 3853 +19617 746 585 157 3858 +19618 559 641 602 3813 +19619 72 3822 862 3845 +19620 590 3838 655 3844 +19621 632 550 576 3785 +19622 651 655 70 3844 +19623 610 3795 3814 3872 +19624 833 879 756 3818 +19625 783 3788 3821 3854 +19626 815 832 789 3825 +19627 561 632 3803 3864 +19628 572 3796 624 3872 +19629 613 577 690 3810 +19630 799 3820 3807 3848 +19631 726 717 708 3802 +19632 626 587 564 3802 +19633 599 578 638 3869 +19634 888 787 845 3867 +19635 551 3810 584 3849 +19636 823 3832 3787 3834 +19637 802 67 902 3811 +19638 557 591 3800 3853 +19639 76 765 804 3863 +19640 555 624 3857 3872 +19641 599 638 3829 3869 +19642 653 617 3803 3833 +19643 68 830 786 3811 +19644 745 157 3821 3858 +19645 157 608 750 3858 +19646 862 775 846 3845 +19647 3786 3834 3823 3865 +19648 3824 3857 588 3859 +19649 567 636 605 3822 +19650 640 554 623 3837 +19651 871 3811 830 3850 +19652 798 824 878 3802 +19653 3800 3830 863 3870 +19654 808 836 892 3801 +19655 3787 3832 3799 3869 +19656 580 631 566 3791 +19657 3796 3814 3789 3846 +19658 3794 3798 3830 3837 +19659 728 714 621 3842 +19660 574 592 3793 3853 +19661 707 716 715 3808 +19662 73 822 72 3822 +19663 706 713 731 3868 +19664 713 706 712 3804 +19665 40 467 466 3862 +19666 581 3792 565 3858 +19667 468 466 467 3862 +19668 839 793 895 3867 +19669 551 633 3784 3827 +19670 655 3838 71 3845 +19671 64 3825 3810 3866 +19672 76 653 660 3803 +19673 567 563 601 3805 +19674 603 3836 642 3865 +19675 574 3793 592 3864 +19676 805 878 934 3828 +19677 883 773 3834 3868 +19678 3816 3791 3836 3840 +19679 895 787 899 3867 +19680 892 3790 3847 3850 +19681 879 909 804 3818 +19682 3807 3820 3783 3848 +19683 649 605 656 3822 +19684 544 80 542 3841 +19685 880 809 915 3834 +19686 729 881 829 3809 +19687 3800 3826 863 3830 +19688 614 582 469 3785 +19689 566 609 606 3819 +19690 140 738 139 3799 +19691 3797 647 3839 3857 +19692 3786 3832 3787 3836 +19693 3789 3846 865 3847 +19694 3804 3794 3834 3865 +19695 3786 3823 3793 3864 +19696 3797 3824 3808 3861 +19697 3797 3857 3824 3861 +19698 892 3801 836 3850 +19699 3814 3828 3805 3846 +19700 619 548 601 3805 +19701 76 75 653 3833 +19702 572 3814 3796 3872 +19703 797 861 725 3868 +19704 703 702 705 3867 +19705 3797 3857 3860 3872 +19706 645 569 3804 3829 +19707 3791 3832 3816 3836 +19708 1 3855 867 3862 +19709 720 708 717 3802 +19710 3801 3847 3790 3850 +19711 862 72 822 3822 +19712 566 628 580 3819 +19713 569 3829 558 3865 +19714 575 560 593 3851 +19715 580 3836 3791 3840 +19716 871 830 755 3850 +19717 3788 3817 553 3858 +19718 3796 3847 3801 3860 +19719 542 80 79 3841 +19720 622 3844 556 3852 +19721 567 3822 605 3838 +19722 615 645 730 3829 +19723 70 655 71 3845 +19724 714 604 621 3842 +19725 3816 3832 3786 3836 +19726 3782 3813 3815 3817 +19727 765 1 867 3863 +19728 709 3809 729 3842 +19729 736 618 597 3813 +19730 729 721 881 3809 +19731 724 825 925 3808 +19732 800 823 880 3834 +19733 659 650 67 3811 +19734 557 591 639 3800 +19735 3812 3825 3784 3849 +19736 3816 3836 3786 3840 +19737 649 605 3822 3838 +19738 571 3823 3794 3865 +19739 3789 3847 3844 3852 +19740 871 930 802 3811 +19741 3808 3824 3782 3861 +19742 152 723 597 3813 +19743 69 68 830 786 +19744 631 580 552 3836 +19745 3801 3860 836 3861 +19746 575 3790 556 3844 +19747 64 3810 65 3866 +19748 3800 3822 3805 3870 +19749 603 3787 3836 3865 +19750 660 3803 658 3862 +19751 3796 3860 3857 3872 +19752 139 701 140 3799 +19753 3816 3819 3791 3840 +19754 3796 3846 3789 3847 +19755 5 678 815 3825 +19756 76 765 909 804 +19757 891 742 843 3821 +19758 732 714 710 3842 +19759 554 571 623 3794 +19760 152 739 723 3813 +19761 629 565 581 3812 +19762 805 851 763 3870 +19763 563 590 622 3838 +19764 580 3819 628 3840 +19765 557 3800 639 3837 +19766 3851 3857 3801 3859 +19767 551 577 613 3810 +19768 802 902 871 3811 +19769 3796 3852 624 3857 +19770 603 3836 3787 3869 +19771 547 595 644 3836 +19772 558 603 3787 3869 +19773 869 3831 887 3845 +19774 75 74 657 3853 +19775 608 157 585 3858 +19776 619 601 563 3805 +19777 584 551 613 3810 +19778 3807 3817 3815 3854 +19779 733 718 625 3839 +19780 556 3844 3790 3852 +19781 3823 3836 3786 3865 +19782 3790 3847 3801 3852 +19783 872 734 719 3806 +19784 878 805 763 3798 +19785 3804 3834 3794 3843 +19786 571 3823 557 3837 +19787 64 696 65 3810 +19788 688 3810 686 3849 +19789 551 3784 3812 3827 +19790 573 3857 3851 3859 +19791 634 655 590 3838 +19792 872 824 734 3806 +19793 872 3806 719 3842 +19794 603 558 3787 3865 +19795 651 590 655 3844 +19796 3795 3846 3814 3871 +19797 648 589 571 3865 +19798 3787 3804 3834 3865 +19799 836 3801 808 3860 +19800 3795 3828 3814 3846 +19801 3786 3803 3818 3863 +19802 712 730 645 3829 +19803 64 678 5 3825 +19804 3803 3786 3840 3863 +19805 547 3823 3786 3864 +19806 3828 3846 3795 3871 +19807 694 693 613 3810 +19808 3807 3812 3792 3848 +19809 549 3817 602 3859 +19810 597 637 579 3813 +19811 839 3816 3791 3832 +19812 836 3820 3801 3861 +19813 903 802 930 3848 +19814 711 721 718 3809 +19815 617 561 3803 3833 +19816 903 866 802 3848 +19817 835 678 64 3825 +19818 617 561 600 3803 +19819 739 724 707 3808 +19820 867 3862 3855 3863 +19821 581 3817 3792 3858 +19822 857 662 666 525 +19823 33 466 476 3855 +19824 891 843 783 3821 +19825 3787 3829 558 3869 +19826 156 749 753 3821 +19827 71 3838 3822 3845 +19828 767 889 826 3861 +19829 561 595 632 3864 +19830 3789 3805 3838 3845 +19831 861 899 787 3799 +19832 581 3812 3792 3817 +19833 611 552 578 3841 +19834 738 3829 706 3868 +19835 623 570 640 3837 +19836 3812 3825 3792 3848 +19837 835 815 678 3825 +19838 835 3825 64 3866 +19839 572 624 3796 3852 +19840 719 729 829 3842 +19841 688 693 692 3810 +19842 692 694 689 3810 +19843 610 3814 572 3872 +19844 640 564 3802 3835 +19845 904 882 808 3860 +19846 799 932 3807 3820 +19847 750 752 749 3849 +19848 3822 3838 3805 3845 +19849 3799 3791 3841 3869 +19850 589 569 558 3865 +19851 471 3819 36 3856 +19852 3801 3847 3796 3852 +19853 3786 3818 3803 3864 +19854 698 700 697 3841 +19855 638 558 3829 3869 +19856 68 902 67 3811 +19857 720 734 824 3806 +19858 157 749 156 3821 +19859 34 476 475 3855 +19860 550 3819 3785 3840 +19861 3795 3871 3814 3872 +19862 3814 3871 3796 3872 +19863 3832 3836 3791 3869 +19864 781 829 3809 3871 +19865 652 656 107 636 +19866 623 3794 571 3837 +19867 715 716 711 3839 +19868 3796 3871 3860 3872 +19869 605 106 656 636 +19870 550 628 3819 3840 +19871 3792 3825 3812 3849 +19872 851 863 3830 3870 +19873 816 3820 836 3861 +19874 593 560 643 3851 +19875 558 3829 3787 3865 +19876 554 640 587 3802 +19877 547 3786 3823 3836 +19878 3811 3850 3783 3851 +19879 829 872 719 3842 +19880 3798 3828 805 3870 +19881 3782 3813 3808 3815 +19882 572 624 555 3872 +19883 3804 3829 3787 3868 +19884 3808 3813 3782 3824 +19885 707 736 723 3813 +19886 640 564 587 3802 +19887 618 568 3824 3839 +19888 3785 3819 3816 3840 +19889 470 582 36 3819 +19890 588 3824 647 3857 +19891 3795 3835 3806 3842 +19892 35 34 475 3855 +19893 588 568 647 3824 +19894 772 3855 3816 3863 +19895 573 588 3857 3859 +19896 3788 3815 3813 3817 +19897 66 3810 691 3866 +19898 581 549 3812 3817 +19899 739 707 723 3813 +19900 719 734 710 3806 +19901 846 788 862 3845 +19902 3792 3812 3807 3817 +19903 745 742 743 3821 +19904 600 561 632 3803 +19905 3810 3784 3825 3849 +19906 717 587 726 626 +19907 751 5 815 3825 +19908 796 867 901 3855 +19909 74 3826 652 3853 +19910 848 759 3828 3871 +19911 836 3801 3820 3850 +19912 70 887 768 3831 +19913 649 3822 71 3838 +19914 635 596 548 3835 +19915 3784 3825 3812 3848 +19916 3795 3842 3809 3872 +19917 3816 3840 3786 3863 +19918 822 769 863 3826 +19919 3791 3819 3816 3856 +19920 3803 3840 3786 3864 +19921 929 3831 869 3847 +19922 797 883 899 3868 +19923 770 903 3848 3866 +19924 69 651 70 3831 +19925 3814 3846 3796 3871 +19926 80 544 609 3841 +19927 652 656 636 591 +19928 612 579 553 3858 +19929 652 74 73 3826 +19930 650 654 68 3811 +19931 67 6 866 764 +19932 866 3848 903 3866 +19933 3782 3807 3820 3859 +19934 574 557 592 3853 +19935 3851 3852 3801 3857 +19936 901 867 1 3855 +19937 551 629 3812 3849 +19938 3844 3847 3790 3852 +19939 645 615 569 3829 +19940 651 590 104 655 +19941 767 3860 889 3861 +19942 839 3816 772 3856 +19943 771 531 478 919 +19944 581 565 630 3858 +19945 851 863 792 3830 +19946 772 3816 3855 3856 +19947 3787 3829 3804 3865 +19948 754 72 862 3845 +19949 781 848 829 3871 +19950 720 710 734 3806 +19951 65 3810 695 3866 +19952 618 715 646 3839 +19953 835 64 65 3866 +19954 3818 3833 3803 3864 +19955 3830 3837 3798 3870 +19956 839 895 762 3832 +19957 622 572 619 3814 +19958 653 658 660 3803 +19959 559 3813 618 3824 +19960 523 484 766 494 +19961 3783 3820 3807 3859 +19962 562 610 627 3872 +19963 3790 3801 3851 3852 +19964 788 869 887 3845 +19965 802 67 866 764 +19966 854 3808 928 3861 +19967 643 549 3851 3859 +19968 66 691 6 3866 +19969 135 686 5 3849 +19970 908 69 768 3831 +19971 471 36 2 3856 +19972 767 836 3860 3861 +19973 822 73 72 924 +19974 820 120 669 670 +19975 3815 3817 3788 3854 +19976 908 768 830 3831 +19977 590 651 620 3844 +19978 563 567 605 3838 +19979 729 709 721 3809 +19980 3800 3837 3830 3870 +19981 919 531 506 488 +19982 832 799 3807 3848 +19983 784 869 865 3847 +19984 892 784 808 3847 +19985 761 832 3807 3854 +19986 736 597 723 3813 +19987 545 79 914 3867 +19988 771 478 834 919 +19989 573 3852 3851 3857 +19990 637 3813 602 3817 +19991 2 3819 542 3856 +19992 3785 3816 3819 3856 +19993 3823 3834 3794 3865 +19994 599 638 558 3829 +19995 928 3808 794 3815 +19996 913 843 156 3821 +19997 561 3803 3833 3864 +19998 489 834 506 541 +19999 910 930 755 3850 +20000 581 602 549 3817 +20001 56 666 662 525 +20002 3783 3812 3807 3848 +20003 820 669 491 670 +20004 3792 3817 3807 3854 +20005 72 71 3822 3845 +20006 3783 3850 3820 3859 +20007 71 887 70 3845 +20008 156 753 913 3821 +20009 3790 3850 3811 3851 +20010 466 3855 33 3862 +20011 836 3820 910 3850 +20012 892 755 830 3850 +20013 784 904 808 3847 +20014 761 832 932 3807 +20015 3803 3785 3862 3863 +20016 3805 3828 3798 3870 +20017 3816 3855 3785 3863 +20018 107 652 636 591 +20019 79 3841 702 3867 +20020 695 3810 66 3866 +20021 547 3836 3823 3865 +20022 618 646 568 3839 +20023 506 919 488 790 +20024 882 781 3860 3871 +20025 765 867 804 3863 +20026 920 533 873 487 +20027 759 3846 3828 3871 +20028 784 929 869 3847 +20029 3785 3803 3840 3863 +20030 882 781 889 3860 +20031 3825 3848 3784 3866 +20032 641 588 549 3859 +20033 660 658 40 3862 +20034 721 709 718 3809 +20035 34 859 926 684 +20036 3793 3833 3818 3864 +20037 3801 3850 3790 3851 +20038 656 649 106 605 +20039 832 799 932 3807 +20040 839 800 3816 3832 +20041 3792 3817 3854 3858 +20042 3799 3841 3791 3867 +20043 576 550 614 3785 +20044 664 511 125 873 +20045 926 34 35 841 +20046 34 841 926 3855 +20047 719 3806 710 3842 +20048 550 582 614 3785 +20049 644 3823 547 3864 +20050 551 584 629 3849 +20051 698 697 611 3841 +20052 658 4 40 576 +20053 881 781 829 3809 +20054 854 767 826 3861 +20055 34 859 683 527 +20056 718 728 90 586 +20057 770 3848 3825 3866 +20058 3857 3860 3801 3861 +20059 3782 3859 3820 3861 +20060 676 900 65 528 +20061 873 664 511 505 +20062 467 40 4 576 +20063 577 111 14 690 +20064 72 837 822 924 +20065 647 555 3857 3872 +20066 34 926 796 3855 +20067 3797 3860 3857 3861 +20068 3785 3855 3816 3856 +20069 609 583 80 3841 +20070 616 575 102 654 +20071 586 562 627 3872 +20072 67 650 68 3811 +20073 3801 3852 3796 3857 +20074 915 897 792 3830 +20075 65 695 66 3866 +20076 3790 3844 3831 3847 +20077 577 14 111 661 +20078 904 865 3846 3847 +20079 491 522 831 670 +20080 3783 3827 3812 3848 +20081 35 841 34 3855 +20082 3831 3844 3789 3847 +20083 853 503 480 541 +20084 66 900 65 3866 +20085 799 910 932 3820 +20086 839 772 817 3856 +20087 914 79 845 3867 +20088 768 887 869 3831 +20089 706 730 712 3829 +20090 649 72 71 3822 +20091 65 696 695 3810 +20092 777 537 480 503 +20093 925 737 724 3808 +20094 900 66 65 528 +20095 728 621 90 586 +20096 832 3825 770 3848 +20097 763 798 878 3843 +20098 5 749 135 3849 +20099 901 765 1 867 +20100 79 702 703 3867 +20101 892 929 784 3847 +20102 3820 3850 3801 3859 +20103 837 72 73 924 +20104 3787 3836 3832 3869 +20105 856 528 676 675 +20106 584 687 135 3849 +20107 926 33 34 796 +20108 913 789 843 3821 +20109 581 549 594 3812 +20110 862 72 754 822 +20111 610 572 627 3872 +20112 5 15 815 678 +20113 650 616 102 654 +20114 543 2 542 3856 +20115 838 797 731 3868 +20116 65 835 900 677 +20117 36 3819 2 3856 +20118 622 556 572 3852 +20119 870 761 907 3815 +20120 649 634 605 3838 +20121 587 87 726 626 +20122 104 620 590 651 +20123 859 34 33 527 +20124 838 773 883 3868 +20125 3788 3854 3817 3858 +20126 662 666 127 857 +20127 635 604 564 3835 +20128 35 841 3855 3856 +20129 667 665 920 533 +20130 683 859 34 684 +20131 660 1 76 3862 +20132 573 3851 549 3859 +20133 49 491 669 670 +20134 757 834 489 541 +20135 609 631 583 3841 +20136 582 606 36 3819 +20137 4 658 600 576 +20138 717 726 87 626 +20139 43 676 528 675 +20140 638 578 552 3869 +20141 157 156 745 3821 +20142 797 725 731 3868 +20143 866 795 6 3866 +20144 859 33 34 926 +20145 681 847 60 682 +20146 528 676 900 856 +20147 766 523 494 806 +20148 584 13 135 687 +20149 3 36 470 582 +20150 542 2 36 3819 +20151 637 559 602 3813 +20152 722 615 730 3829 +20153 759 934 848 3828 +20154 3785 3840 3816 3863 +20155 926 859 133 684 +20156 770 866 903 3866 +20157 796 33 34 3855 +20158 783 3821 884 3854 +20159 816 836 767 3861 +20160 634 649 655 3838 +20161 795 900 66 3866 +20162 904 784 865 3847 +20163 706 738 722 3829 +20164 608 585 630 3858 +20165 3801 3857 3796 3860 +20166 552 3836 603 3869 +20167 634 104 590 655 +20168 845 79 703 3867 +20169 663 54 511 664 +20170 557 571 592 3823 +20171 615 558 569 3829 +20172 900 66 528 856 +20173 618 93 736 597 +20174 152 11 579 597 +20175 543 817 2 3856 +20176 3820 3859 3801 3861 +20177 3783 3851 3850 3859 +20178 494 56 662 525 +20179 851 775 863 3870 +20180 870 761 3815 3854 +20181 742 156 843 3821 +20182 3812 3827 3784 3848 +20183 512 492 779 844 +20184 840 667 920 533 +20185 35 685 841 3856 +20186 583 552 611 3841 +20187 65 900 835 3866 +20188 656 73 72 3822 +20189 615 722 599 3829 +20190 677 900 65 676 +20191 858 518 771 820 +20192 919 506 834 790 +20193 847 490 682 803 +20194 853 506 834 541 +20195 929 830 768 3831 +20196 825 870 794 3815 +20197 573 549 588 3859 +20198 910 816 932 3820 +20199 606 546 36 3819 +20200 820 491 831 670 +20201 70 768 69 3831 +20202 923 769 74 3826 +20203 926 35 685 841 +20204 820 831 120 670 +20205 140 10 599 578 +20206 142 713 864 731 +20207 528 856 499 675 +20208 563 634 590 3838 +20209 835 815 15 678 +20210 683 62 34 527 +20211 676 65 42 528 +20212 737 716 707 3808 +20213 697 700 702 3841 +20214 479 536 779 512 +20215 907 928 794 3815 +20216 914 79 9 845 +20217 491 771 518 820 +20218 487 873 920 782 +20219 642 3836 547 3865 +20220 610 548 619 3814 +20221 853 821 503 541 +20222 925 854 737 3808 +20223 737 854 716 3808 +20224 558 638 603 3869 +20225 766 484 813 494 +20226 653 109 617 3833 +20227 838 142 864 731 +20228 839 800 917 3816 +20229 754 71 72 3845 +20230 560 616 598 3827 +20231 654 620 103 651 +20232 67 802 902 764 +20233 546 544 542 3819 +20234 870 783 884 3854 +20235 131 847 681 682 +20236 584 135 607 3849 +20237 6 795 66 3866 +20238 533 920 840 487 +20239 533 53 665 873 +20240 767 836 808 3860 +20241 854 928 767 3861 +20242 728 709 714 3842 +20243 867 3855 772 3863 +20244 3792 3854 3821 3858 +20245 80 702 79 3841 +20246 827 896 521 540 +20247 618 559 597 3813 +20248 535 671 47 508 +20249 555 627 572 3872 +20250 607 565 629 3849 +20251 805 3828 846 3870 +20252 683 859 502 527 +20253 499 43 528 675 +20254 926 859 33 796 +20255 479 779 898 512 +20256 663 511 125 664 +20257 133 859 683 684 +20258 649 634 105 605 +20259 490 60 847 682 +20260 733 625 646 3839 +20261 705 888 137 703 +20262 2 35 471 3856 +20263 921 499 530 801 +20264 873 511 125 813 +20265 3855 3862 3785 3863 +20266 505 873 533 487 +20267 836 910 755 3850 +20268 49 522 491 670 +20269 57 916 666 525 +20270 722 615 84 730 +20271 789 884 3821 3854 +20272 776 850 483 810 +20273 623 571 557 3837 +20274 872 780 824 3806 +20275 75 657 653 3833 +20276 144 911 720 824 +20277 503 480 777 853 +20278 535 522 671 885 +20279 607 135 752 3849 +20280 489 478 834 849 +20281 3850 3851 3801 3859 +20282 665 667 52 533 +20283 668 122 877 667 +20284 595 3836 580 3840 +20285 481 492 512 844 +20286 553 585 612 3858 +20287 123 667 665 920 +20288 530 921 674 675 +20289 725 738 706 3868 +20290 719 709 729 3842 +20291 859 502 132 683 +20292 649 105 634 655 +20293 911 727 144 720 +20294 589 558 642 3865 +20295 518 858 482 820 +20296 520 499 6 801 +20297 591 108 652 3853 +20298 900 835 112 677 +20299 592 3823 644 3864 +20300 3809 3871 3795 3872 +20301 841 685 8 3856 +20302 157 12 608 585 +20303 3788 3821 3854 3858 +20304 583 631 552 3841 +20305 572 556 624 3852 +20306 490 847 60 681 +20307 103 575 620 654 +20308 559 618 568 3824 +20309 692 695 696 3810 +20310 620 575 556 3844 +20311 919 831 531 488 +20312 653 657 109 3833 +20313 683 34 62 684 +20314 677 65 42 676 +20315 823 883 773 3834 +20316 577 598 14 661 +20317 872 824 145 734 +20318 607 97 608 752 +20319 606 77 546 609 +20320 511 813 484 494 +20321 521 507 827 540 +20322 754 862 887 3845 +20323 84 599 615 722 +20324 482 491 518 820 +20325 486 530 499 801 +20326 520 67 503 890 +20327 752 135 749 3849 +20328 510 877 504 668 +20329 757 534 821 541 +20330 806 523 536 868 +20331 530 499 921 675 +20332 584 135 13 607 +20333 36 3 606 582 +20334 685 2 8 3856 +20335 789 832 884 3854 +20336 766 523 868 498 +20337 697 583 611 3841 +20338 857 666 916 525 +20339 583 697 80 3841 +20340 856 921 499 675 +20341 834 757 853 541 +20342 506 478 834 489 +20343 834 927 478 771 +20344 57 916 679 666 +20345 773 864 798 3843 +20346 156 18 843 913 +20347 553 3817 581 3858 +20348 926 685 134 841 +20349 516 776 850 483 +20350 896 901 1 803 +20351 856 676 114 675 +20352 770 832 815 3825 +20353 540 827 896 778 +20354 593 643 549 3851 +20355 768 69 908 818 +20356 813 766 494 806 +20357 657 574 3833 3853 +20358 665 920 533 873 +20359 783 843 884 3821 +20360 574 561 3833 3864 +20361 534 503 821 541 +20362 70 768 887 819 +20363 896 765 76 521 +20364 754 887 71 3845 +20365 550 580 628 3840 +20366 801 6 520 906 +20367 891 742 155 843 +20368 914 845 793 3867 +20369 935 769 833 3826 +20370 831 531 771 919 +20371 544 546 77 609 +20372 750 608 97 752 +20373 664 665 53 873 +20374 511 873 505 813 +20375 561 644 595 3864 +20376 876 17 151 825 +20377 735 148 881 826 +20378 923 833 769 3826 +20379 884 832 761 3854 +20380 90 718 586 625 +20381 509 931 828 481 +20382 715 92 618 646 +20383 918 868 814 498 +20384 918 526 874 498 +20385 707 724 737 3808 +20386 67 821 503 890 +20387 931 828 680 509 +20388 828 779 492 844 +20389 630 553 581 3858 +20390 921 856 114 675 +20391 742 745 156 3821 +20392 487 840 860 782 +20393 507 758 538 827 +20394 866 6 795 906 +20395 806 857 536 525 +20396 33 3855 1 3862 +20397 657 74 652 3853 +20398 2 817 8 3856 +20399 48 522 671 535 +20400 818 757 534 893 +20401 905 517 874 811 +20402 530 855 500 673 +20403 845 79 9 703 +20404 747 152 11 579 +20405 12 157 746 585 +20406 674 921 115 675 +20407 860 513 782 905 +20408 885 671 535 508 +20409 583 80 7 609 +20410 487 920 840 782 +20411 8 2 543 817 +20412 6 866 764 906 +20413 840 504 877 667 +20414 524 814 774 501 +20415 45 674 530 673 +20416 477 517 905 526 +20417 614 39 474 582 +20418 98 584 613 693 +20419 488 919 831 790 +20420 801 499 6 906 +20421 513 860 477 905 +20422 614 467 37 576 +20423 613 577 100 690 +20424 850 483 810 495 +20425 779 536 479 868 +20426 779 536 857 525 +20427 670 522 119 671 +20428 517 782 513 905 +20429 663 125 511 813 +20430 657 574 109 3833 +20431 857 127 662 806 +20432 545 78 543 914 +20433 540 507 827 778 +20434 566 606 628 3819 +20435 852 798 763 3843 +20436 785 860 513 504 +20437 828 129 680 509 +20438 502 132 803 859 +20439 486 777 537 500 +20440 89 621 714 604 +20441 811 526 874 918 +20442 772 3855 841 3856 +20443 515 496 886 760 +20444 917 3818 804 3863 +20445 521 896 1 502 +20446 804 917 933 3818 +20447 886 776 483 810 +20448 812 514 774 501 +20449 73 514 812 501 +20450 714 621 89 728 +20451 853 757 821 541 +20452 824 780 878 3806 +20453 726 645 86 587 +20454 618 736 92 715 +20455 68 67 902 821 +20456 502 682 132 683 +20457 479 898 779 868 +20458 843 789 884 3821 +20459 815 15 5 751 +20460 885 535 488 508 +20461 777 821 503 853 +20462 841 8 817 3856 +20463 538 75 507 827 +20464 782 484 874 517 +20465 672 47 671 508 +20466 828 680 129 931 +20467 829 719 146 729 +20468 574 591 557 3853 +20469 495 850 72 894 +20470 874 484 766 498 +20471 617 109 574 3833 +20472 478 927 834 849 +20473 810 526 485 495 +20474 483 850 516 495 +20475 888 845 137 703 +20476 894 850 72 754 +20477 153 876 741 891 +20478 723 736 93 597 +20479 852 773 798 3843 +20480 848 882 759 3871 +20481 683 502 61 527 +20482 901 33 502 859 +20483 813 511 912 494 +20484 615 599 558 3829 +20485 759 846 3828 3846 +20486 688 692 696 3810 +20487 695 692 689 3810 +20488 574 592 561 3864 +20489 36 3 546 606 +20490 607 135 13 752 +20491 657 652 108 3853 +20492 656 72 649 3822 +20493 868 479 814 498 +20494 897 763 851 3830 +20495 832 903 799 3848 +20496 515 886 483 810 +20497 3810 3825 3784 3866 +20498 803 1 896 502 +20499 896 847 490 540 +20500 840 504 667 533 +20501 767 928 816 3861 +20502 670 48 522 671 +20503 818 534 69 893 +20504 926 841 796 3855 +20505 530 674 116 673 +20506 477 860 760 905 +20507 513 487 782 517 +20508 586 627 647 3872 +20509 771 478 531 518 +20510 131 847 682 803 +20511 513 760 496 477 +20512 922 774 814 501 +20513 72 837 754 822 +20514 930 799 903 3848 +20515 637 602 553 3817 +20516 546 542 36 3819 +20517 663 511 912 813 +20518 484 813 782 874 +20519 11 152 723 597 +20520 477 760 515 811 +20521 778 828 931 481 +20522 524 814 479 498 +20523 881 829 147 729 +20524 547 3823 571 3865 +20525 732 626 88 604 +20526 839 762 800 3832 +20527 823 800 762 3832 +20528 526 905 477 811 +20529 532 847 490 681 +20530 496 886 483 515 +20531 593 3851 573 3852 +20532 533 53 873 505 +20533 918 766 868 498 +20534 610 619 572 3814 +20535 808 882 889 3860 +20536 875 538 758 827 +20537 70 69 768 818 +20538 481 828 492 844 +20539 513 860 760 477 +20540 856 6 66 499 +20541 887 71 70 819 +20542 837 514 774 812 +20543 916 529 57 679 +20544 1 765 901 896 +20545 649 71 655 3838 +20546 827 75 76 909 +20547 521 76 896 827 +20548 646 715 733 3839 +20549 931 59 680 681 +20550 1 765 896 521 +20551 842 500 855 673 +20552 824 720 145 734 +20553 778 540 507 481 +20554 671 522 119 885 +20555 519 497 776 849 +20556 538 875 75 827 +20557 68 67 821 503 +20558 657 108 574 3853 +20559 529 680 129 509 +20560 667 123 840 920 +20561 530 674 44 675 +20562 807 886 483 496 +20563 487 505 873 782 +20564 729 147 881 721 +20565 540 896 847 778 +20566 523 766 484 498 +20567 599 10 140 722 +20568 910 836 816 3820 +20569 73 514 837 812 +20570 731 797 141 725 +20571 61 682 502 683 +20572 140 10 578 699 +20573 742 156 18 843 +20574 918 524 814 485 +20575 580 603 552 3836 +20576 622 590 556 3844 +20577 860 513 487 782 +20578 916 57 529 525 +20579 597 559 637 3813 +20580 801 856 499 906 +20581 536 779 857 806 +20582 838 797 141 731 +20583 917 772 3816 3863 +20584 520 503 537 890 +20585 581 551 629 3812 +20586 933 756 879 3818 +20587 766 523 806 868 +20588 890 67 821 764 +20589 896 76 765 827 +20590 559 588 641 3824 +20591 814 524 918 498 +20592 536 779 806 868 +20593 903 832 770 3848 +20594 803 682 132 502 +20595 103 102 575 654 +20596 603 547 642 3836 +20597 633 560 598 3827 +20598 534 757 818 497 +20599 810 485 774 495 +20600 496 807 886 760 +20601 858 785 482 820 +20602 859 901 33 796 +20603 900 795 66 856 +20604 490 682 803 502 +20605 517 513 477 905 +20606 536 779 492 525 +20607 54 511 664 505 +20608 877 122 840 667 +20609 856 6 499 906 +20610 488 790 885 508 +20611 608 12 157 750 +20612 476 34 33 3855 +20613 860 785 840 504 +20614 517 905 526 811 +20615 67 902 821 764 +20616 901 33 1 502 +20617 593 549 573 3851 +20618 917 772 839 3816 +20619 860 760 496 513 +20620 529 680 58 679 +20621 129 529 916 679 +20622 770 815 835 3825 +20623 591 574 108 3853 +20624 69 908 893 786 +20625 529 129 680 679 +20626 502 803 901 859 +20627 647 555 588 3857 +20628 928 854 794 3808 +20629 70 818 819 516 +20630 794 870 907 3815 +20631 803 901 1 502 +20632 524 774 485 501 +20633 711 733 715 3839 +20634 18 156 753 913 +20635 149 737 854 716 +20636 537 777 486 890 +20637 500 45 530 673 +20638 664 124 665 873 +20639 88 714 732 604 +20640 829 146 719 872 +20641 719 710 714 3842 +20642 782 487 505 517 +20643 886 515 760 810 +20644 35 2 685 3856 +20645 526 517 874 498 +20646 557 639 570 3837 +20647 918 874 766 498 +20648 873 53 664 505 +20649 774 814 524 485 +20650 523 479 868 498 +20651 600 658 110 617 +20652 7 80 583 697 +20653 853 539 480 842 +20654 672 671 885 508 +20655 520 486 499 801 +20656 534 757 497 489 +20657 484 782 505 517 +20658 840 504 533 487 +20659 817 543 78 914 +20660 113 900 677 676 +20661 916 529 129 828 +20662 615 645 85 730 +20663 489 519 478 849 +20664 804 933 879 3818 +20665 931 532 847 778 +20666 854 148 149 716 +20667 530 44 499 675 +20668 806 536 494 525 +20669 828 529 129 509 +20670 858 760 496 860 +20671 790 488 539 508 +20672 882 848 781 3871 +20673 667 504 52 533 +20674 582 628 606 3819 +20675 831 522 531 488 +20676 507 778 481 844 +20677 918 811 526 485 +20678 498 524 918 485 +20679 507 827 778 844 +20680 547 571 589 3865 +20681 807 519 776 849 +20682 779 492 916 828 +20683 513 482 785 504 +20684 479 536 523 868 +20685 466 33 1 3862 +20686 818 69 534 497 +20687 813 782 505 484 +20688 483 497 776 519 +20689 771 927 478 518 +20690 855 921 530 801 +20691 755 892 836 3850 +20692 916 529 492 525 +20693 488 539 506 790 +20694 702 80 697 3841 +20695 818 819 516 776 +20696 520 890 801 906 +20697 827 507 758 844 +20698 886 483 776 807 +20699 644 592 547 3823 +20700 507 493 758 844 +20701 556 593 573 3852 +20702 742 18 155 843 +20703 893 821 68 786 +20704 534 821 68 893 +20705 119 831 522 670 +20706 775 805 846 3870 +20707 499 921 856 801 +20708 772 841 817 3856 +20709 547 580 595 3836 +20710 526 874 517 811 +20711 913 753 158 751 +20712 712 645 86 726 +20713 532 540 778 481 +20714 149 737 925 854 +20715 850 72 71 495 +20716 539 500 480 842 +20717 765 1 76 521 +20718 909 827 75 791 +20719 815 913 158 751 +20720 785 840 504 877 +20721 544 7 80 609 +20722 492 779 536 512 +20723 624 3852 573 3857 +20724 510 504 51 668 +20725 856 66 6 906 +20726 647 627 555 3872 +20727 758 538 493 507 +20728 143 864 727 911 +20729 896 521 490 502 +20730 530 674 921 855 +20731 795 6 66 906 +20732 679 916 128 666 +20733 121 877 510 668 +20734 811 918 774 485 +20735 630 585 553 3858 +20736 890 520 67 764 +20737 853 834 506 790 +20738 658 653 110 617 +20739 779 898 512 844 +20740 490 60 532 681 +20741 699 83 578 611 +20742 652 107 108 591 +20743 519 807 496 518 +20744 773 809 880 3834 +20745 856 795 66 906 +20746 787 895 845 3867 +20747 767 808 889 3860 +20748 853 480 777 842 +20749 79 9 545 914 +20750 893 68 69 786 +20751 821 534 757 893 +20752 515 526 810 495 +20753 768 70 818 819 +20754 66 528 856 499 +20755 922 812 774 501 +20756 494 912 813 806 +20757 489 757 497 849 +20758 50 510 668 669 +20759 540 847 532 778 +20760 500 777 480 842 +20761 845 136 137 703 +20762 855 530 116 673 +20763 842 672 46 673 +20764 515 526 811 810 +20765 842 46 500 673 +20766 724 151 17 825 +20767 774 810 495 894 +20768 842 117 672 673 +20769 769 935 863 3826 +20770 148 881 721 735 +20771 70 818 516 497 +20772 91 718 625 733 +20773 867 841 772 3855 +20774 563 605 634 3838 +20775 741 740 153 891 +20776 841 867 796 3855 +20777 803 896 490 502 +20778 494 523 536 806 +20779 668 510 121 669 +20780 818 776 497 849 +20781 33 502 859 527 +20782 519 776 483 807 +20783 489 834 757 849 +20784 864 713 143 727 +20785 821 902 68 786 +20786 770 3825 835 3866 +20787 861 139 16 725 +20788 776 516 818 497 +20789 712 85 645 730 +20790 46 672 842 508 +20791 759 865 846 3846 +20792 526 477 515 811 +20793 518 807 496 858 +20794 506 539 853 790 +20795 529 58 680 509 +20796 501 875 74 538 +20797 835 900 795 3866 +20798 811 760 515 810 +20799 898 493 479 512 +20800 850 71 72 754 +20801 492 529 916 828 +20802 532 59 931 681 +20803 632 595 550 3840 +20804 503 821 68 534 +20805 539 853 790 842 +20806 498 918 526 485 +20807 760 477 905 811 +20808 846 805 759 3828 +20809 669 491 510 820 +20810 511 55 912 494 +20811 794 854 925 3808 +20812 897 851 792 3830 +20813 501 922 875 538 +20814 484 874 517 498 +20815 580 547 603 3836 +20816 853 480 506 541 +20817 931 680 59 532 +20818 40 466 1 3862 +20819 894 495 774 514 +20820 782 505 873 813 +20821 583 81 7 697 +20822 827 875 75 791 +20823 773 880 823 3834 +20824 842 672 885 508 +20825 550 595 580 3840 +20826 486 855 530 801 +20827 512 493 481 844 +20828 497 757 818 849 +20829 493 507 481 844 +20830 589 642 547 3865 +20831 768 869 929 3831 +20832 559 568 588 3824 +20833 643 560 594 3827 +20834 113 900 676 856 +20835 105 104 634 655 +20836 522 831 119 885 +20837 486 855 777 500 +20838 145 719 872 734 +20839 774 918 814 485 +20840 720 145 144 824 +20841 602 581 553 3817 +20842 519 478 927 518 +20843 927 478 519 849 +20844 842 500 46 508 +20845 714 88 89 604 +20846 514 485 774 501 +20847 657 108 109 574 +20848 520 537 486 890 +20849 733 625 91 646 +20850 547 592 571 3823 +20851 920 665 124 873 +20852 531 491 831 771 +20853 40 1 660 3862 +20854 115 921 674 855 +20855 511 912 55 663 +20856 81 583 611 697 +20857 76 521 507 827 +20858 797 861 141 725 +20859 731 725 706 3868 +20860 890 520 764 906 +20861 769 74 812 923 +20862 501 493 922 538 +20863 74 75 875 923 +20864 855 116 842 673 +20865 510 877 121 820 +20866 480 537 777 500 +20867 898 493 524 479 +20868 740 742 155 891 +20869 898 524 814 479 +20870 719 714 709 3842 +20871 71 516 850 495 +20872 617 574 561 3833 +20873 520 6 67 764 +20874 486 520 890 801 +20875 578 10 83 699 +20876 55 662 912 494 +20877 584 607 629 3849 +20878 764 520 6 906 +20879 116 674 530 855 +20880 625 568 646 3839 +20881 492 529 828 481 +20882 715 733 91 646 +20883 666 916 128 857 +20884 805 934 759 3828 +20885 723 93 11 597 +20886 84 10 599 722 +20887 669 510 121 820 +20888 76 765 827 909 +20889 490 847 896 803 +20890 861 16 139 704 +20891 831 488 790 885 +20892 538 493 922 758 +20893 912 125 663 813 +20894 837 894 72 754 +20895 672 671 118 885 +20896 649 105 106 605 +20897 760 515 496 477 +20898 514 894 72 837 +20899 581 594 551 3812 +20900 682 490 60 502 +20901 495 485 774 514 +20902 490 847 532 540 +20903 556 573 624 3852 +20904 845 895 793 3867 +20905 874 484 813 766 +20906 917 867 772 3863 +20907 510 491 482 820 +20908 507 75 76 827 +20909 807 483 519 496 +20910 517 874 782 905 +20911 858 496 518 482 +20912 931 680 130 681 +20913 483 515 810 495 +20914 726 86 87 587 +20915 870 884 761 3854 +20916 561 592 644 3864 +20917 635 564 596 3835 +20918 590 620 556 3844 +20919 510 785 877 820 +20920 497 519 489 849 +20921 923 75 875 791 +20922 842 885 790 508 +20923 842 790 539 508 +20924 577 14 100 690 +20925 467 4 37 576 +20926 557 570 623 3837 +20927 509 828 529 481 +20928 819 887 71 754 +20929 898 493 512 844 +20930 760 496 807 858 +20931 653 109 110 617 +20932 697 611 81 698 +20933 534 68 69 893 +20934 925 724 150 825 +20935 656 106 107 636 +20936 807 519 927 518 +20937 479 814 898 868 +20938 620 104 103 651 +20939 552 603 638 3869 +20940 876 151 17 741 +20941 771 531 491 518 +20942 818 69 908 893 +20943 746 748 95 612 +20944 612 748 95 747 +20945 894 72 495 514 +20946 555 573 588 3857 +20947 722 730 706 3829 +20948 662 912 494 806 +20949 922 493 898 758 +20950 49 491 510 669 +20951 506 539 480 853 +20952 747 94 612 579 +20953 510 482 785 820 +20954 568 625 647 3839 +20955 611 699 83 698 +20956 9 136 845 703 +20957 812 875 74 501 +20958 718 90 91 625 +20959 497 776 516 483 +20960 534 757 489 541 +20961 746 96 12 585 +20962 680 931 509 532 +20963 777 855 486 890 +20964 865 759 904 3846 +20965 847 532 931 681 +20966 518 927 807 858 +20967 91 92 715 646 +20968 775 851 805 3870 +20969 518 771 927 858 +20970 70 69 818 497 +20971 875 812 922 501 +20972 771 491 831 820 +20973 596 564 640 3835 +20974 835 795 866 3866 +20975 888 138 861 704 +20976 521 896 490 540 +20977 812 74 73 501 +20978 500 855 777 842 +20979 887 862 788 3845 +20980 912 662 55 663 +20981 530 855 486 500 +20982 842 116 117 673 +20983 831 522 491 531 +20984 842 539 500 508 +20985 829 146 147 729 +20986 611 82 81 698 +20987 538 922 875 758 +20988 88 717 626 732 +20989 555 624 573 3857 +20990 509 59 680 532 +20991 774 894 514 837 +20992 883 797 838 3868 +20993 500 46 45 673 +20994 813 505 511 484 +20995 470 39 3 582 +20996 584 98 13 687 +20997 510 50 49 669 +20998 662 55 56 494 +20999 812 837 73 924 +21000 110 4 658 600 +21001 819 516 776 850 +21002 474 473 38 614 +21003 693 613 99 694 +21004 90 89 621 728 +21005 616 102 101 650 +21006 96 746 612 585 +21007 831 119 120 670 +21008 11 94 747 579 +21009 815 158 15 751 +21010 118 672 885 842 +21011 633 594 560 3827 +21012 72 73 514 837 +21013 736 92 93 618 +21014 835 15 112 678 +21015 598 101 14 661 +21016 912 662 127 806 +21017 704 888 137 705 +21018 861 16 141 725 +21019 75 74 875 538 +21020 682 132 131 803 +21021 770 835 866 3866 +21022 855 486 890 801 +21023 83 82 611 698 +21024 543 78 8 817 +21025 850 819 71 754 +21026 499 44 43 675 +21027 838 141 142 731 +21028 840 122 123 667 +21029 51 50 510 668 +21030 495 810 850 894 +21031 121 120 669 820 +21032 682 60 61 502 +21033 613 99 98 693 +21034 38 39 474 614 +21035 867 917 804 3863 +21036 85 84 615 730 +21037 95 96 746 612 +21038 481 778 828 844 +21039 100 99 613 694 +21040 473 37 38 614 +21041 608 97 12 750 +21042 516 819 71 850 +21043 876 17 153 741 +21044 154 153 740 891 +21045 146 145 719 872 +21046 155 154 740 891 +21047 147 148 881 721 +21048 724 17 150 825 +21049 86 85 645 712 +21050 612 95 94 747 +21051 126 662 912 663 +21052 664 53 54 505 +21053 493 898 758 844 +21054 672 118 117 842 +21055 544 77 7 609 +21056 546 3 77 606 +21057 13 97 607 752 +21058 931 130 847 681 +21059 662 127 126 912 +21060 859 132 133 683 +21061 74 875 812 923 +21062 685 8 134 841 +21063 56 57 666 525 +21064 737 724 150 925 +21065 713 143 142 864 +21066 87 88 717 626 +21067 545 9 78 914 +21068 671 47 48 535 +21069 519 807 927 849 +21070 676 114 113 856 +21071 861 138 16 704 +21072 504 52 51 667 +21073 819 71 70 516 +21074 511 55 54 663 +21075 676 42 43 528 +21076 61 62 683 527 +21077 753 158 18 913 +21078 672 46 47 508 +21079 65 42 41 677 +21080 63 62 34 684 +21081 847 130 131 681 +21082 522 49 48 670 +21083 133 134 926 684 +21084 58 57 529 679 +21085 888 137 138 704 +21086 737 150 149 925 +21087 52 53 665 533 +21088 666 128 127 857 +21089 58 59 680 509 +21090 674 116 115 855 +21091 664 125 124 873 +21092 877 121 122 668 +21093 60 59 532 681 +21094 124 123 665 920 +21095 112 113 900 677 +21096 114 115 921 675 +21097 680 130 129 931 +21098 727 144 143 911 +21099 128 129 916 679 +21100 912 125 126 663 +21101 674 44 45 530 +21102 671 119 118 885 +21103 33 468 476 466 +21104 3822 3853 3826 3800 +21105 3826 3853 3822 652 +21106 3849 608 607 565 +21107 3815 3820 816 3782 +21108 816 3820 3815 907 +21109 3842 586 728 3809 +21110 3842 728 586 621 +21111 626 3835 604 732 +21112 604 3835 626 564 +21113 3815 739 151 3788 +21114 3815 151 739 724 +21115 3819 3841 542 3791 +21116 542 3841 3819 544 +21117 602 3859 3782 641 +21118 3782 3859 602 3817 +21119 3782 3813 602 641 +21120 602 3813 3782 3817 +21121 3868 139 738 3799 +21122 3868 738 139 725 +21123 3861 3815 816 3782 +21124 3861 816 3815 928 +21125 3845 655 3831 70 +21126 3845 3831 655 3838 +21127 715 3824 618 736 +21128 715 618 3824 3839 +21129 3830 935 863 792 +21130 3830 863 935 3826 +21131 3868 864 773 3804 +21132 3868 773 864 838 +21133 3832 883 899 762 +21134 3832 899 883 3787 +21135 789 751 913 815 +21136 913 751 789 753 +21137 789 3825 751 815 +21138 751 3825 789 3792 +21139 809 3843 773 852 +21140 773 3843 809 3834 +21141 3870 3837 3805 3800 +21142 3870 3805 3837 3798 +21143 3867 839 3832 895 +21144 3867 3832 839 3791 +21145 3860 904 3847 808 +21146 3860 3847 904 3796 +21147 3826 924 74 73 +21148 3826 74 924 769 +21149 812 74 924 73 +21150 812 924 74 769 +21151 622 3838 3805 563 +21152 3805 3838 622 3789 +21153 3805 619 622 563 +21154 622 619 3805 3789 +21155 3860 826 3809 889 +21156 3860 3809 826 3797 +21157 690 691 3810 111 +21158 690 3810 691 689 +21159 658 576 3862 600 +21160 3862 576 658 40 +21161 693 3810 584 613 +21162 582 469 474 614 +21163 786 3811 902 68 +21164 902 3811 786 871 +21165 899 3867 3832 895 +21166 3832 3867 899 3799 +21167 3851 575 3852 593 +21168 3851 3852 575 3790 +21169 556 3852 575 593 +21170 556 575 3852 3790 +21171 3865 569 648 589 +21172 3865 648 569 3804 +21173 3850 871 930 755 +21174 3850 930 871 3811 +21175 470 471 3819 36 +21176 470 3819 471 469 +21177 687 686 3849 688 +21178 687 3849 686 135 +21179 901 3855 33 796 +21180 33 3855 901 1 +21181 904 3871 759 882 +21182 759 3871 904 3846 +21183 3819 550 582 628 +21184 3819 582 550 3785 +21185 650 598 101 616 +21186 650 101 598 661 +21187 919 478 506 531 +21188 919 506 478 834 +21189 864 731 3868 838 +21190 3868 731 864 713 +21191 716 826 148 735 +21192 716 148 826 854 +21193 3827 551 594 3812 +21194 3827 594 551 633 +21195 888 703 3867 845 +21196 3867 703 888 705 +21197 493 501 898 524 +21198 493 898 501 922 +21199 814 898 501 524 +21200 814 501 898 922 +21201 609 546 3819 544 +21202 609 3819 546 606 +21203 752 608 3849 750 +21204 752 3849 608 607 +21205 914 543 793 817 +21206 914 793 543 545 +21207 3791 793 543 817 +21208 3791 543 793 545 +21209 668 504 667 877 +21210 668 667 504 51 +21211 777 503 890 537 +21212 890 503 777 821 +21213 481 931 532 509 +21214 481 532 931 778 +21215 525 806 662 494 +21216 525 662 806 857 +21217 684 926 685 134 +21218 678 835 677 112 +21219 504 860 487 840 +21220 504 487 860 513 +21221 510 785 504 877 +21222 510 504 785 482 +21223 525 779 916 857 +21224 525 916 779 492 +21225 522 885 488 831 +21226 488 885 522 535 +21227 485 811 810 774 +21228 485 810 811 526 +21229 496 513 858 860 +21230 496 858 513 482 +21231 785 858 513 860 +21232 785 513 858 482 +21233 34 63 926 35 +21234 34 926 63 684 +21235 685 926 63 35 +21236 685 63 926 684 +21237 678 835 65 677 +21238 65 835 678 64 +21239 65 41 678 677 +21240 678 41 65 64 +21241 3849 688 584 687 +21242 98 584 688 687 +21243 98 688 584 693 +21244 688 64 3810 696 +21245 688 3810 64 686 +21246 3810 689 613 694 +21247 3810 613 689 690 +21248 100 613 689 694 +21249 100 689 613 690 +21250 66 689 3810 695 +21251 66 3810 689 691 +21252 468 37 614 467 +21253 468 614 37 473 +21254 35 469 3856 475 +21255 35 3856 469 471 +21256 3785 3856 469 475 +21257 469 39 582 474 +21258 469 582 39 470 +21259 3785 467 614 576 +21260 3785 614 467 468 +21261 582 469 3819 470 +21262 582 3819 469 3785 +21263 688 584 3810 3849 +21264 688 3810 584 693 +21265 3856 469 3819 3785 +21266 3856 3819 469 471 +$EndElements +//+ +Field[1] = Max; +//+ +Field[1].FieldsList = {2}; +//+ +Field[1].FieldsList = {10}; diff --git a/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.stp b/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.stp new file mode 100644 index 00000000..8fb27132 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector.stp @@ -0,0 +1,1026 @@ +ISO-10303-21; +HEADER; +/* Generated by software containing ST-Developer + * from STEP Tools, Inc. (www.steptools.com) + */ + +FILE_DESCRIPTION( +/* description */ (''), +/* implementation_level */ '2;1'); + +FILE_NAME( +/* name */ 'C:\\Users\\pablo\\OneDrive\\Desktop\\act23mmwithconnector. +stp', +/* time_stamp */ '2023-09-11T19:30:36+09:00', +/* author */ ('pablo'), +/* organization */ (''), +/* preprocessor_version */ 'ST-DEVELOPER v18.1', +/* originating_system */ 'Autodesk Inventor 2022', +/* authorisation */ ''); + +FILE_SCHEMA (('AUTOMOTIVE_DESIGN { 1 0 10303 214 3 1 1 }')); +ENDSEC; + +DATA; +#10=MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',(#18,#19, +#20),#931); +#11=CONSTRUCTIVE_GEOMETRY_REPRESENTATION_RELATIONSHIP('CGRR','None',#938, +#12); +#12=CONSTRUCTIVE_GEOMETRY_REPRESENTATION('',(#13),#930); +#13=GEOMETRIC_CURVE_SET('Sketch1',(#927)); +#14=SHAPE_REPRESENTATION_RELATIONSHIP('SRR','None',#938,#15); +#15=ADVANCED_BREP_SHAPE_REPRESENTATION('',(#540,#16,#17),#930); +#16=MANIFOLD_SOLID_BREP('Solid3',#538); +#17=MANIFOLD_SOLID_BREP('Solid4',#539); +#18=STYLED_ITEM('',(#947),#540); +#19=STYLED_ITEM('',(#947),#16); +#20=STYLED_ITEM('',(#947),#17); +#21=ORIENTED_CLOSED_SHELL('',*,#537,.F.); +#22=PLANE('',#563); +#23=PLANE('',#567); +#24=PLANE('',#571); +#25=PLANE('',#572); +#26=PLANE('',#573); +#27=PLANE('',#574); +#28=PLANE('',#575); +#29=PLANE('',#579); +#30=PLANE('',#580); +#31=PLANE('',#581); +#32=PLANE('',#585); +#33=PLANE('',#589); +#34=PLANE('',#593); +#35=PLANE('',#594); +#36=PLANE('',#595); +#37=PLANE('',#599); +#38=PLANE('',#603); +#39=PLANE('',#607); +#40=PLANE('',#611); +#41=PLANE('',#612); +#42=PLANE('',#613); +#43=FACE_OUTER_BOUND('',#75,.T.); +#44=FACE_OUTER_BOUND('',#76,.T.); +#45=FACE_OUTER_BOUND('',#77,.T.); +#46=FACE_OUTER_BOUND('',#78,.T.); +#47=FACE_OUTER_BOUND('',#79,.T.); +#48=FACE_OUTER_BOUND('',#80,.T.); +#49=FACE_OUTER_BOUND('',#81,.T.); +#50=FACE_OUTER_BOUND('',#82,.T.); +#51=FACE_OUTER_BOUND('',#83,.T.); +#52=FACE_OUTER_BOUND('',#84,.T.); +#53=FACE_OUTER_BOUND('',#85,.T.); +#54=FACE_OUTER_BOUND('',#86,.T.); +#55=FACE_OUTER_BOUND('',#87,.T.); +#56=FACE_OUTER_BOUND('',#88,.T.); +#57=FACE_OUTER_BOUND('',#89,.T.); +#58=FACE_OUTER_BOUND('',#90,.T.); +#59=FACE_OUTER_BOUND('',#91,.T.); +#60=FACE_OUTER_BOUND('',#92,.T.); +#61=FACE_OUTER_BOUND('',#93,.T.); +#62=FACE_OUTER_BOUND('',#94,.T.); +#63=FACE_OUTER_BOUND('',#95,.T.); +#64=FACE_OUTER_BOUND('',#96,.T.); +#65=FACE_OUTER_BOUND('',#97,.T.); +#66=FACE_OUTER_BOUND('',#98,.T.); +#67=FACE_OUTER_BOUND('',#99,.T.); +#68=FACE_OUTER_BOUND('',#100,.T.); +#69=FACE_OUTER_BOUND('',#101,.T.); +#70=FACE_OUTER_BOUND('',#102,.T.); +#71=FACE_OUTER_BOUND('',#103,.T.); +#72=FACE_OUTER_BOUND('',#104,.T.); +#73=FACE_OUTER_BOUND('',#105,.T.); +#74=FACE_OUTER_BOUND('',#106,.T.); +#75=EDGE_LOOP('',(#349,#350,#351,#352)); +#76=EDGE_LOOP('',(#353,#354,#355,#356)); +#77=EDGE_LOOP('',(#357,#358,#359,#360)); +#78=EDGE_LOOP('',(#361,#362,#363,#364)); +#79=EDGE_LOOP('',(#365,#366,#367,#368)); +#80=EDGE_LOOP('',(#369,#370,#371,#372)); +#81=EDGE_LOOP('',(#373,#374,#375,#376,#377,#378)); +#82=EDGE_LOOP('',(#379,#380,#381,#382,#383,#384)); +#83=EDGE_LOOP('',(#385,#386,#387,#388)); +#84=EDGE_LOOP('',(#389,#390,#391,#392)); +#85=EDGE_LOOP('',(#393,#394,#395,#396)); +#86=EDGE_LOOP('',(#397,#398,#399,#400)); +#87=EDGE_LOOP('',(#401,#402,#403,#404)); +#88=EDGE_LOOP('',(#405,#406,#407,#408)); +#89=EDGE_LOOP('',(#409,#410,#411,#412)); +#90=EDGE_LOOP('',(#413,#414,#415,#416)); +#91=EDGE_LOOP('',(#417,#418,#419,#420)); +#92=EDGE_LOOP('',(#421,#422,#423,#424)); +#93=EDGE_LOOP('',(#425,#426,#427,#428)); +#94=EDGE_LOOP('',(#429,#430,#431,#432)); +#95=EDGE_LOOP('',(#433,#434,#435,#436,#437,#438)); +#96=EDGE_LOOP('',(#439,#440,#441,#442,#443,#444)); +#97=EDGE_LOOP('',(#445,#446,#447,#448)); +#98=EDGE_LOOP('',(#449,#450,#451,#452)); +#99=EDGE_LOOP('',(#453,#454,#455,#456)); +#100=EDGE_LOOP('',(#457,#458,#459,#460)); +#101=EDGE_LOOP('',(#461,#462,#463,#464)); +#102=EDGE_LOOP('',(#465,#466,#467,#468)); +#103=EDGE_LOOP('',(#469,#470,#471,#472)); +#104=EDGE_LOOP('',(#473,#474,#475,#476)); +#105=EDGE_LOOP('',(#477,#478,#479,#480,#481,#482,#483,#484)); +#106=EDGE_LOOP('',(#485,#486,#487,#488,#489,#490,#491,#492)); +#107=LINE('',#780,#157); +#108=LINE('',#783,#158); +#109=LINE('',#786,#159); +#110=LINE('',#788,#160); +#111=LINE('',#789,#161); +#112=LINE('',#795,#162); +#113=LINE('',#798,#163); +#114=LINE('',#800,#164); +#115=LINE('',#801,#165); +#116=LINE('',#807,#166); +#117=LINE('',#809,#167); +#118=LINE('',#810,#168); +#119=LINE('',#816,#169); +#120=LINE('',#818,#170); +#121=LINE('',#820,#171); +#122=LINE('',#821,#172); +#123=LINE('',#824,#173); +#124=LINE('',#826,#174); +#125=LINE('',#827,#175); +#126=LINE('',#832,#176); +#127=LINE('',#835,#177); +#128=LINE('',#836,#178); +#129=LINE('',#844,#179); +#130=LINE('',#847,#180); +#131=LINE('',#850,#181); +#132=LINE('',#852,#182); +#133=LINE('',#853,#183); +#134=LINE('',#859,#184); +#135=LINE('',#862,#185); +#136=LINE('',#864,#186); +#137=LINE('',#865,#187); +#138=LINE('',#871,#188); +#139=LINE('',#873,#189); +#140=LINE('',#874,#190); +#141=LINE('',#882,#191); +#142=LINE('',#885,#192); +#143=LINE('',#888,#193); +#144=LINE('',#890,#194); +#145=LINE('',#891,#195); +#146=LINE('',#897,#196); +#147=LINE('',#900,#197); +#148=LINE('',#902,#198); +#149=LINE('',#903,#199); +#150=LINE('',#909,#200); +#151=LINE('',#912,#201); +#152=LINE('',#914,#202); +#153=LINE('',#915,#203); +#154=LINE('',#921,#204); +#155=LINE('',#923,#205); +#156=LINE('',#924,#206); +#157=VECTOR('',#620,10.); +#158=VECTOR('',#623,10.); +#159=VECTOR('',#626,10.); +#160=VECTOR('',#627,10.); +#161=VECTOR('',#628,10.); +#162=VECTOR('',#635,10.); +#163=VECTOR('',#638,10.); +#164=VECTOR('',#639,10.); +#165=VECTOR('',#640,10.); +#166=VECTOR('',#647,10.); +#167=VECTOR('',#650,10.); +#168=VECTOR('',#651,10.); +#169=VECTOR('',#658,10.); +#170=VECTOR('',#659,10.); +#171=VECTOR('',#660,10.); +#172=VECTOR('',#661,10.); +#173=VECTOR('',#664,10.); +#174=VECTOR('',#665,10.); +#175=VECTOR('',#666,10.); +#176=VECTOR('',#671,10.); +#177=VECTOR('',#676,10.); +#178=VECTOR('',#677,10.); +#179=VECTOR('',#686,10.); +#180=VECTOR('',#689,10.); +#181=VECTOR('',#692,10.); +#182=VECTOR('',#693,10.); +#183=VECTOR('',#694,10.); +#184=VECTOR('',#701,10.); +#185=VECTOR('',#704,10.); +#186=VECTOR('',#705,10.); +#187=VECTOR('',#706,10.); +#188=VECTOR('',#713,10.); +#189=VECTOR('',#716,10.); +#190=VECTOR('',#717,10.); +#191=VECTOR('',#726,10.); +#192=VECTOR('',#729,10.); +#193=VECTOR('',#732,10.); +#194=VECTOR('',#733,10.); +#195=VECTOR('',#734,10.); +#196=VECTOR('',#741,10.); +#197=VECTOR('',#744,10.); +#198=VECTOR('',#745,10.); +#199=VECTOR('',#746,10.); +#200=VECTOR('',#753,10.); +#201=VECTOR('',#756,10.); +#202=VECTOR('',#757,10.); +#203=VECTOR('',#758,10.); +#204=VECTOR('',#765,10.); +#205=VECTOR('',#768,10.); +#206=VECTOR('',#769,10.); +#207=CIRCLE('',#561,2.); +#208=CIRCLE('',#562,2.); +#209=CIRCLE('',#565,2.); +#210=CIRCLE('',#566,2.); +#211=CIRCLE('',#569,7.5); +#212=CIRCLE('',#570,7.5); +#213=CIRCLE('',#577,5.5); +#214=CIRCLE('',#578,5.5); +#215=CIRCLE('',#583,7.5); +#216=CIRCLE('',#584,7.5); +#217=CIRCLE('',#587,2.); +#218=CIRCLE('',#588,2.); +#219=CIRCLE('',#591,2.); +#220=CIRCLE('',#592,2.); +#221=CIRCLE('',#597,2.); +#222=CIRCLE('',#598,2.); +#223=CIRCLE('',#601,2.); +#224=CIRCLE('',#602,2.); +#225=CIRCLE('',#605,2.); +#226=CIRCLE('',#606,2.); +#227=CIRCLE('',#609,2.); +#228=CIRCLE('',#610,2.); +#229=VERTEX_POINT('',#776); +#230=VERTEX_POINT('',#777); +#231=VERTEX_POINT('',#779); +#232=VERTEX_POINT('',#781); +#233=VERTEX_POINT('',#785); +#234=VERTEX_POINT('',#787); +#235=VERTEX_POINT('',#791); +#236=VERTEX_POINT('',#793); +#237=VERTEX_POINT('',#797); +#238=VERTEX_POINT('',#799); +#239=VERTEX_POINT('',#803); +#240=VERTEX_POINT('',#805); +#241=VERTEX_POINT('',#814); +#242=VERTEX_POINT('',#815); +#243=VERTEX_POINT('',#817); +#244=VERTEX_POINT('',#819); +#245=VERTEX_POINT('',#823); +#246=VERTEX_POINT('',#825); +#247=VERTEX_POINT('',#829); +#248=VERTEX_POINT('',#831); +#249=VERTEX_POINT('',#840); +#250=VERTEX_POINT('',#841); +#251=VERTEX_POINT('',#843); +#252=VERTEX_POINT('',#845); +#253=VERTEX_POINT('',#849); +#254=VERTEX_POINT('',#851); +#255=VERTEX_POINT('',#855); +#256=VERTEX_POINT('',#857); +#257=VERTEX_POINT('',#861); +#258=VERTEX_POINT('',#863); +#259=VERTEX_POINT('',#867); +#260=VERTEX_POINT('',#869); +#261=VERTEX_POINT('',#878); +#262=VERTEX_POINT('',#879); +#263=VERTEX_POINT('',#881); +#264=VERTEX_POINT('',#883); +#265=VERTEX_POINT('',#887); +#266=VERTEX_POINT('',#889); +#267=VERTEX_POINT('',#893); +#268=VERTEX_POINT('',#895); +#269=VERTEX_POINT('',#899); +#270=VERTEX_POINT('',#901); +#271=VERTEX_POINT('',#905); +#272=VERTEX_POINT('',#907); +#273=VERTEX_POINT('',#911); +#274=VERTEX_POINT('',#913); +#275=VERTEX_POINT('',#917); +#276=VERTEX_POINT('',#919); +#277=EDGE_CURVE('',#229,#230,#207,.T.); +#278=EDGE_CURVE('',#230,#231,#107,.T.); +#279=EDGE_CURVE('',#232,#231,#208,.T.); +#280=EDGE_CURVE('',#229,#232,#108,.T.); +#281=EDGE_CURVE('',#233,#229,#109,.T.); +#282=EDGE_CURVE('',#234,#232,#110,.T.); +#283=EDGE_CURVE('',#233,#234,#111,.T.); +#284=EDGE_CURVE('',#235,#233,#209,.T.); +#285=EDGE_CURVE('',#236,#234,#210,.T.); +#286=EDGE_CURVE('',#235,#236,#112,.T.); +#287=EDGE_CURVE('',#237,#235,#113,.T.); +#288=EDGE_CURVE('',#238,#236,#114,.T.); +#289=EDGE_CURVE('',#237,#238,#115,.T.); +#290=EDGE_CURVE('',#239,#237,#211,.T.); +#291=EDGE_CURVE('',#240,#238,#212,.T.); +#292=EDGE_CURVE('',#239,#240,#116,.T.); +#293=EDGE_CURVE('',#230,#239,#117,.T.); +#294=EDGE_CURVE('',#231,#240,#118,.T.); +#295=EDGE_CURVE('',#241,#242,#119,.T.); +#296=EDGE_CURVE('',#242,#243,#120,.T.); +#297=EDGE_CURVE('',#243,#244,#121,.T.); +#298=EDGE_CURVE('',#241,#244,#122,.T.); +#299=EDGE_CURVE('',#242,#245,#123,.T.); +#300=EDGE_CURVE('',#245,#246,#124,.T.); +#301=EDGE_CURVE('',#246,#243,#125,.T.); +#302=EDGE_CURVE('',#245,#247,#213,.T.); +#303=EDGE_CURVE('',#247,#248,#126,.T.); +#304=EDGE_CURVE('',#248,#246,#214,.T.); +#305=EDGE_CURVE('',#247,#241,#127,.T.); +#306=EDGE_CURVE('',#244,#248,#128,.T.); +#307=EDGE_CURVE('',#249,#250,#215,.T.); +#308=EDGE_CURVE('',#250,#251,#129,.T.); +#309=EDGE_CURVE('',#252,#251,#216,.T.); +#310=EDGE_CURVE('',#249,#252,#130,.T.); +#311=EDGE_CURVE('',#253,#249,#131,.T.); +#312=EDGE_CURVE('',#254,#252,#132,.T.); +#313=EDGE_CURVE('',#253,#254,#133,.T.); +#314=EDGE_CURVE('',#255,#253,#217,.T.); +#315=EDGE_CURVE('',#256,#254,#218,.T.); +#316=EDGE_CURVE('',#255,#256,#134,.T.); +#317=EDGE_CURVE('',#257,#255,#135,.T.); +#318=EDGE_CURVE('',#258,#256,#136,.T.); +#319=EDGE_CURVE('',#257,#258,#137,.T.); +#320=EDGE_CURVE('',#259,#257,#219,.T.); +#321=EDGE_CURVE('',#260,#258,#220,.T.); +#322=EDGE_CURVE('',#259,#260,#138,.T.); +#323=EDGE_CURVE('',#250,#259,#139,.T.); +#324=EDGE_CURVE('',#251,#260,#140,.T.); +#325=EDGE_CURVE('',#261,#262,#221,.T.); +#326=EDGE_CURVE('',#262,#263,#141,.T.); +#327=EDGE_CURVE('',#264,#263,#222,.T.); +#328=EDGE_CURVE('',#261,#264,#142,.T.); +#329=EDGE_CURVE('',#265,#261,#143,.T.); +#330=EDGE_CURVE('',#266,#264,#144,.T.); +#331=EDGE_CURVE('',#265,#266,#145,.T.); +#332=EDGE_CURVE('',#267,#265,#223,.T.); +#333=EDGE_CURVE('',#268,#266,#224,.T.); +#334=EDGE_CURVE('',#267,#268,#146,.T.); +#335=EDGE_CURVE('',#269,#267,#147,.T.); +#336=EDGE_CURVE('',#270,#268,#148,.T.); +#337=EDGE_CURVE('',#269,#270,#149,.T.); +#338=EDGE_CURVE('',#271,#269,#225,.T.); +#339=EDGE_CURVE('',#272,#270,#226,.T.); +#340=EDGE_CURVE('',#271,#272,#150,.T.); +#341=EDGE_CURVE('',#273,#271,#151,.T.); +#342=EDGE_CURVE('',#274,#272,#152,.T.); +#343=EDGE_CURVE('',#273,#274,#153,.T.); +#344=EDGE_CURVE('',#275,#273,#227,.T.); +#345=EDGE_CURVE('',#276,#274,#228,.T.); +#346=EDGE_CURVE('',#275,#276,#154,.T.); +#347=EDGE_CURVE('',#262,#275,#155,.T.); +#348=EDGE_CURVE('',#263,#276,#156,.T.); +#349=ORIENTED_EDGE('',*,*,#277,.T.); +#350=ORIENTED_EDGE('',*,*,#278,.T.); +#351=ORIENTED_EDGE('',*,*,#279,.F.); +#352=ORIENTED_EDGE('',*,*,#280,.F.); +#353=ORIENTED_EDGE('',*,*,#281,.T.); +#354=ORIENTED_EDGE('',*,*,#280,.T.); +#355=ORIENTED_EDGE('',*,*,#282,.F.); +#356=ORIENTED_EDGE('',*,*,#283,.F.); +#357=ORIENTED_EDGE('',*,*,#284,.T.); +#358=ORIENTED_EDGE('',*,*,#283,.T.); +#359=ORIENTED_EDGE('',*,*,#285,.F.); +#360=ORIENTED_EDGE('',*,*,#286,.F.); +#361=ORIENTED_EDGE('',*,*,#287,.T.); +#362=ORIENTED_EDGE('',*,*,#286,.T.); +#363=ORIENTED_EDGE('',*,*,#288,.F.); +#364=ORIENTED_EDGE('',*,*,#289,.F.); +#365=ORIENTED_EDGE('',*,*,#290,.T.); +#366=ORIENTED_EDGE('',*,*,#289,.T.); +#367=ORIENTED_EDGE('',*,*,#291,.F.); +#368=ORIENTED_EDGE('',*,*,#292,.F.); +#369=ORIENTED_EDGE('',*,*,#293,.T.); +#370=ORIENTED_EDGE('',*,*,#292,.T.); +#371=ORIENTED_EDGE('',*,*,#294,.F.); +#372=ORIENTED_EDGE('',*,*,#278,.F.); +#373=ORIENTED_EDGE('',*,*,#294,.T.); +#374=ORIENTED_EDGE('',*,*,#291,.T.); +#375=ORIENTED_EDGE('',*,*,#288,.T.); +#376=ORIENTED_EDGE('',*,*,#285,.T.); +#377=ORIENTED_EDGE('',*,*,#282,.T.); +#378=ORIENTED_EDGE('',*,*,#279,.T.); +#379=ORIENTED_EDGE('',*,*,#293,.F.); +#380=ORIENTED_EDGE('',*,*,#277,.F.); +#381=ORIENTED_EDGE('',*,*,#281,.F.); +#382=ORIENTED_EDGE('',*,*,#284,.F.); +#383=ORIENTED_EDGE('',*,*,#287,.F.); +#384=ORIENTED_EDGE('',*,*,#290,.F.); +#385=ORIENTED_EDGE('',*,*,#295,.T.); +#386=ORIENTED_EDGE('',*,*,#296,.T.); +#387=ORIENTED_EDGE('',*,*,#297,.T.); +#388=ORIENTED_EDGE('',*,*,#298,.F.); +#389=ORIENTED_EDGE('',*,*,#299,.T.); +#390=ORIENTED_EDGE('',*,*,#300,.T.); +#391=ORIENTED_EDGE('',*,*,#301,.T.); +#392=ORIENTED_EDGE('',*,*,#296,.F.); +#393=ORIENTED_EDGE('',*,*,#302,.T.); +#394=ORIENTED_EDGE('',*,*,#303,.T.); +#395=ORIENTED_EDGE('',*,*,#304,.T.); +#396=ORIENTED_EDGE('',*,*,#300,.F.); +#397=ORIENTED_EDGE('',*,*,#305,.T.); +#398=ORIENTED_EDGE('',*,*,#298,.T.); +#399=ORIENTED_EDGE('',*,*,#306,.T.); +#400=ORIENTED_EDGE('',*,*,#303,.F.); +#401=ORIENTED_EDGE('',*,*,#305,.F.); +#402=ORIENTED_EDGE('',*,*,#302,.F.); +#403=ORIENTED_EDGE('',*,*,#299,.F.); +#404=ORIENTED_EDGE('',*,*,#295,.F.); +#405=ORIENTED_EDGE('',*,*,#306,.F.); +#406=ORIENTED_EDGE('',*,*,#297,.F.); +#407=ORIENTED_EDGE('',*,*,#301,.F.); +#408=ORIENTED_EDGE('',*,*,#304,.F.); +#409=ORIENTED_EDGE('',*,*,#307,.T.); +#410=ORIENTED_EDGE('',*,*,#308,.T.); +#411=ORIENTED_EDGE('',*,*,#309,.F.); +#412=ORIENTED_EDGE('',*,*,#310,.F.); +#413=ORIENTED_EDGE('',*,*,#311,.T.); +#414=ORIENTED_EDGE('',*,*,#310,.T.); +#415=ORIENTED_EDGE('',*,*,#312,.F.); +#416=ORIENTED_EDGE('',*,*,#313,.F.); +#417=ORIENTED_EDGE('',*,*,#314,.T.); +#418=ORIENTED_EDGE('',*,*,#313,.T.); +#419=ORIENTED_EDGE('',*,*,#315,.F.); +#420=ORIENTED_EDGE('',*,*,#316,.F.); +#421=ORIENTED_EDGE('',*,*,#317,.T.); +#422=ORIENTED_EDGE('',*,*,#316,.T.); +#423=ORIENTED_EDGE('',*,*,#318,.F.); +#424=ORIENTED_EDGE('',*,*,#319,.F.); +#425=ORIENTED_EDGE('',*,*,#320,.T.); +#426=ORIENTED_EDGE('',*,*,#319,.T.); +#427=ORIENTED_EDGE('',*,*,#321,.F.); +#428=ORIENTED_EDGE('',*,*,#322,.F.); +#429=ORIENTED_EDGE('',*,*,#323,.T.); +#430=ORIENTED_EDGE('',*,*,#322,.T.); +#431=ORIENTED_EDGE('',*,*,#324,.F.); +#432=ORIENTED_EDGE('',*,*,#308,.F.); +#433=ORIENTED_EDGE('',*,*,#324,.T.); +#434=ORIENTED_EDGE('',*,*,#321,.T.); +#435=ORIENTED_EDGE('',*,*,#318,.T.); +#436=ORIENTED_EDGE('',*,*,#315,.T.); +#437=ORIENTED_EDGE('',*,*,#312,.T.); +#438=ORIENTED_EDGE('',*,*,#309,.T.); +#439=ORIENTED_EDGE('',*,*,#323,.F.); +#440=ORIENTED_EDGE('',*,*,#307,.F.); +#441=ORIENTED_EDGE('',*,*,#311,.F.); +#442=ORIENTED_EDGE('',*,*,#314,.F.); +#443=ORIENTED_EDGE('',*,*,#317,.F.); +#444=ORIENTED_EDGE('',*,*,#320,.F.); +#445=ORIENTED_EDGE('',*,*,#325,.T.); +#446=ORIENTED_EDGE('',*,*,#326,.T.); +#447=ORIENTED_EDGE('',*,*,#327,.F.); +#448=ORIENTED_EDGE('',*,*,#328,.F.); +#449=ORIENTED_EDGE('',*,*,#329,.T.); +#450=ORIENTED_EDGE('',*,*,#328,.T.); +#451=ORIENTED_EDGE('',*,*,#330,.F.); +#452=ORIENTED_EDGE('',*,*,#331,.F.); +#453=ORIENTED_EDGE('',*,*,#332,.T.); +#454=ORIENTED_EDGE('',*,*,#331,.T.); +#455=ORIENTED_EDGE('',*,*,#333,.F.); +#456=ORIENTED_EDGE('',*,*,#334,.F.); +#457=ORIENTED_EDGE('',*,*,#335,.T.); +#458=ORIENTED_EDGE('',*,*,#334,.T.); +#459=ORIENTED_EDGE('',*,*,#336,.F.); +#460=ORIENTED_EDGE('',*,*,#337,.F.); +#461=ORIENTED_EDGE('',*,*,#338,.T.); +#462=ORIENTED_EDGE('',*,*,#337,.T.); +#463=ORIENTED_EDGE('',*,*,#339,.F.); +#464=ORIENTED_EDGE('',*,*,#340,.F.); +#465=ORIENTED_EDGE('',*,*,#341,.T.); +#466=ORIENTED_EDGE('',*,*,#340,.T.); +#467=ORIENTED_EDGE('',*,*,#342,.F.); +#468=ORIENTED_EDGE('',*,*,#343,.F.); +#469=ORIENTED_EDGE('',*,*,#344,.T.); +#470=ORIENTED_EDGE('',*,*,#343,.T.); +#471=ORIENTED_EDGE('',*,*,#345,.F.); +#472=ORIENTED_EDGE('',*,*,#346,.F.); +#473=ORIENTED_EDGE('',*,*,#347,.T.); +#474=ORIENTED_EDGE('',*,*,#346,.T.); +#475=ORIENTED_EDGE('',*,*,#348,.F.); +#476=ORIENTED_EDGE('',*,*,#326,.F.); +#477=ORIENTED_EDGE('',*,*,#348,.T.); +#478=ORIENTED_EDGE('',*,*,#345,.T.); +#479=ORIENTED_EDGE('',*,*,#342,.T.); +#480=ORIENTED_EDGE('',*,*,#339,.T.); +#481=ORIENTED_EDGE('',*,*,#336,.T.); +#482=ORIENTED_EDGE('',*,*,#333,.T.); +#483=ORIENTED_EDGE('',*,*,#330,.T.); +#484=ORIENTED_EDGE('',*,*,#327,.T.); +#485=ORIENTED_EDGE('',*,*,#347,.F.); +#486=ORIENTED_EDGE('',*,*,#325,.F.); +#487=ORIENTED_EDGE('',*,*,#329,.F.); +#488=ORIENTED_EDGE('',*,*,#332,.F.); +#489=ORIENTED_EDGE('',*,*,#335,.F.); +#490=ORIENTED_EDGE('',*,*,#338,.F.); +#491=ORIENTED_EDGE('',*,*,#341,.F.); +#492=ORIENTED_EDGE('',*,*,#344,.F.); +#493=CYLINDRICAL_SURFACE('',#560,2.); +#494=CYLINDRICAL_SURFACE('',#564,2.); +#495=CYLINDRICAL_SURFACE('',#568,7.5); +#496=CYLINDRICAL_SURFACE('',#576,5.5); +#497=CYLINDRICAL_SURFACE('',#582,7.5); +#498=CYLINDRICAL_SURFACE('',#586,2.); +#499=CYLINDRICAL_SURFACE('',#590,2.); +#500=CYLINDRICAL_SURFACE('',#596,2.); +#501=CYLINDRICAL_SURFACE('',#600,2.); +#502=CYLINDRICAL_SURFACE('',#604,2.); +#503=CYLINDRICAL_SURFACE('',#608,2.); +#504=ADVANCED_FACE('',(#43),#493,.T.); +#505=ADVANCED_FACE('',(#44),#22,.T.); +#506=ADVANCED_FACE('',(#45),#494,.T.); +#507=ADVANCED_FACE('',(#46),#23,.T.); +#508=ADVANCED_FACE('',(#47),#495,.T.); +#509=ADVANCED_FACE('',(#48),#24,.T.); +#510=ADVANCED_FACE('',(#49),#25,.T.); +#511=ADVANCED_FACE('',(#50),#26,.F.); +#512=ADVANCED_FACE('',(#51),#27,.F.); +#513=ADVANCED_FACE('',(#52),#28,.F.); +#514=ADVANCED_FACE('',(#53),#496,.F.); +#515=ADVANCED_FACE('',(#54),#29,.F.); +#516=ADVANCED_FACE('',(#55),#30,.F.); +#517=ADVANCED_FACE('',(#56),#31,.T.); +#518=ADVANCED_FACE('',(#57),#497,.T.); +#519=ADVANCED_FACE('',(#58),#32,.T.); +#520=ADVANCED_FACE('',(#59),#498,.T.); +#521=ADVANCED_FACE('',(#60),#33,.T.); +#522=ADVANCED_FACE('',(#61),#499,.T.); +#523=ADVANCED_FACE('',(#62),#34,.T.); +#524=ADVANCED_FACE('',(#63),#35,.T.); +#525=ADVANCED_FACE('',(#64),#36,.F.); +#526=ADVANCED_FACE('',(#65),#500,.T.); +#527=ADVANCED_FACE('',(#66),#37,.T.); +#528=ADVANCED_FACE('',(#67),#501,.T.); +#529=ADVANCED_FACE('',(#68),#38,.T.); +#530=ADVANCED_FACE('',(#69),#502,.T.); +#531=ADVANCED_FACE('',(#70),#39,.T.); +#532=ADVANCED_FACE('',(#71),#503,.T.); +#533=ADVANCED_FACE('',(#72),#40,.T.); +#534=ADVANCED_FACE('',(#73),#41,.T.); +#535=ADVANCED_FACE('',(#74),#42,.F.); +#536=CLOSED_SHELL('',(#504,#505,#506,#507,#508,#509,#510,#511)); +#537=CLOSED_SHELL('',(#512,#513,#514,#515,#516,#517)); +#538=CLOSED_SHELL('',(#518,#519,#520,#521,#522,#523,#524,#525)); +#539=CLOSED_SHELL('',(#526,#527,#528,#529,#530,#531,#532,#533,#534,#535)); +#540=BREP_WITH_VOIDS('Solid2',#536,(#21)); +#541=DERIVED_UNIT_ELEMENT(#543,1.); +#542=DERIVED_UNIT_ELEMENT(#933,-3.); +#543=( +MASS_UNIT() +NAMED_UNIT(*) +SI_UNIT($,.GRAM.) +); +#544=DERIVED_UNIT((#541,#542)); +#545=MEASURE_REPRESENTATION_ITEM('density measure', +POSITIVE_RATIO_MEASURE(1.),#544); +#546=PROPERTY_DEFINITION_REPRESENTATION(#551,#548); +#547=PROPERTY_DEFINITION_REPRESENTATION(#552,#549); +#548=REPRESENTATION('material name',(#550),#930); +#549=REPRESENTATION('density',(#545),#930); +#550=DESCRIPTIVE_REPRESENTATION_ITEM('Generic','Generic'); +#551=PROPERTY_DEFINITION('material property','material name',#940); +#552=PROPERTY_DEFINITION('material property','density of part',#940); +#553=DATE_TIME_ROLE('creation_date'); +#554=APPLIED_DATE_AND_TIME_ASSIGNMENT(#555,#553,(#940)); +#555=DATE_AND_TIME(#556,#557); +#556=CALENDAR_DATE(2023,4,5); +#557=LOCAL_TIME(17,5,46.,#558); +#558=COORDINATED_UNIVERSAL_TIME_OFFSET(0,0,.BEHIND.); +#559=AXIS2_PLACEMENT_3D('placement',#774,#614,#615); +#560=AXIS2_PLACEMENT_3D('',#775,#616,#617); +#561=AXIS2_PLACEMENT_3D('',#778,#618,#619); +#562=AXIS2_PLACEMENT_3D('',#782,#621,#622); +#563=AXIS2_PLACEMENT_3D('',#784,#624,#625); +#564=AXIS2_PLACEMENT_3D('',#790,#629,#630); +#565=AXIS2_PLACEMENT_3D('',#792,#631,#632); +#566=AXIS2_PLACEMENT_3D('',#794,#633,#634); +#567=AXIS2_PLACEMENT_3D('',#796,#636,#637); +#568=AXIS2_PLACEMENT_3D('',#802,#641,#642); +#569=AXIS2_PLACEMENT_3D('',#804,#643,#644); +#570=AXIS2_PLACEMENT_3D('',#806,#645,#646); +#571=AXIS2_PLACEMENT_3D('',#808,#648,#649); +#572=AXIS2_PLACEMENT_3D('',#811,#652,#653); +#573=AXIS2_PLACEMENT_3D('',#812,#654,#655); +#574=AXIS2_PLACEMENT_3D('',#813,#656,#657); +#575=AXIS2_PLACEMENT_3D('',#822,#662,#663); +#576=AXIS2_PLACEMENT_3D('',#828,#667,#668); +#577=AXIS2_PLACEMENT_3D('',#830,#669,#670); +#578=AXIS2_PLACEMENT_3D('',#833,#672,#673); +#579=AXIS2_PLACEMENT_3D('',#834,#674,#675); +#580=AXIS2_PLACEMENT_3D('',#837,#678,#679); +#581=AXIS2_PLACEMENT_3D('',#838,#680,#681); +#582=AXIS2_PLACEMENT_3D('',#839,#682,#683); +#583=AXIS2_PLACEMENT_3D('',#842,#684,#685); +#584=AXIS2_PLACEMENT_3D('',#846,#687,#688); +#585=AXIS2_PLACEMENT_3D('',#848,#690,#691); +#586=AXIS2_PLACEMENT_3D('',#854,#695,#696); +#587=AXIS2_PLACEMENT_3D('',#856,#697,#698); +#588=AXIS2_PLACEMENT_3D('',#858,#699,#700); +#589=AXIS2_PLACEMENT_3D('',#860,#702,#703); +#590=AXIS2_PLACEMENT_3D('',#866,#707,#708); +#591=AXIS2_PLACEMENT_3D('',#868,#709,#710); +#592=AXIS2_PLACEMENT_3D('',#870,#711,#712); +#593=AXIS2_PLACEMENT_3D('',#872,#714,#715); +#594=AXIS2_PLACEMENT_3D('',#875,#718,#719); +#595=AXIS2_PLACEMENT_3D('',#876,#720,#721); +#596=AXIS2_PLACEMENT_3D('',#877,#722,#723); +#597=AXIS2_PLACEMENT_3D('',#880,#724,#725); +#598=AXIS2_PLACEMENT_3D('',#884,#727,#728); +#599=AXIS2_PLACEMENT_3D('',#886,#730,#731); +#600=AXIS2_PLACEMENT_3D('',#892,#735,#736); +#601=AXIS2_PLACEMENT_3D('',#894,#737,#738); +#602=AXIS2_PLACEMENT_3D('',#896,#739,#740); +#603=AXIS2_PLACEMENT_3D('',#898,#742,#743); +#604=AXIS2_PLACEMENT_3D('',#904,#747,#748); +#605=AXIS2_PLACEMENT_3D('',#906,#749,#750); +#606=AXIS2_PLACEMENT_3D('',#908,#751,#752); +#607=AXIS2_PLACEMENT_3D('',#910,#754,#755); +#608=AXIS2_PLACEMENT_3D('',#916,#759,#760); +#609=AXIS2_PLACEMENT_3D('',#918,#761,#762); +#610=AXIS2_PLACEMENT_3D('',#920,#763,#764); +#611=AXIS2_PLACEMENT_3D('',#922,#766,#767); +#612=AXIS2_PLACEMENT_3D('',#925,#770,#771); +#613=AXIS2_PLACEMENT_3D('',#926,#772,#773); +#614=DIRECTION('axis',(0.,0.,1.)); +#615=DIRECTION('refdir',(1.,0.,0.)); +#616=DIRECTION('center_axis',(0.,0.,1.)); +#617=DIRECTION('ref_axis',(0.,-1.,0.)); +#618=DIRECTION('center_axis',(0.,0.,1.)); +#619=DIRECTION('ref_axis',(0.,-1.,0.)); +#620=DIRECTION('',(0.,0.,1.)); +#621=DIRECTION('center_axis',(0.,0.,1.)); +#622=DIRECTION('ref_axis',(0.,-1.,0.)); +#623=DIRECTION('',(0.,0.,1.)); +#624=DIRECTION('center_axis',(0.,-1.,0.)); +#625=DIRECTION('ref_axis',(1.,0.,0.)); +#626=DIRECTION('',(1.,0.,0.)); +#627=DIRECTION('',(1.,0.,0.)); +#628=DIRECTION('',(0.,0.,1.)); +#629=DIRECTION('center_axis',(0.,0.,1.)); +#630=DIRECTION('ref_axis',(-1.,0.,0.)); +#631=DIRECTION('center_axis',(0.,0.,1.)); +#632=DIRECTION('ref_axis',(-1.,0.,0.)); +#633=DIRECTION('center_axis',(0.,0.,1.)); +#634=DIRECTION('ref_axis',(-1.,0.,0.)); +#635=DIRECTION('',(0.,0.,1.)); +#636=DIRECTION('center_axis',(-1.,0.,0.)); +#637=DIRECTION('ref_axis',(0.,-1.,0.)); +#638=DIRECTION('',(0.,-1.,0.)); +#639=DIRECTION('',(0.,-1.,0.)); +#640=DIRECTION('',(0.,0.,1.)); +#641=DIRECTION('center_axis',(0.,0.,1.)); +#642=DIRECTION('ref_axis',(1.,2.44929359829471E-16,0.)); +#643=DIRECTION('center_axis',(0.,0.,1.)); +#644=DIRECTION('ref_axis',(1.,2.44929359829471E-16,0.)); +#645=DIRECTION('center_axis',(0.,0.,1.)); +#646=DIRECTION('ref_axis',(1.,2.44929359829471E-16,0.)); +#647=DIRECTION('',(0.,0.,1.)); +#648=DIRECTION('center_axis',(1.,0.,0.)); +#649=DIRECTION('ref_axis',(0.,1.,0.)); +#650=DIRECTION('',(0.,1.,0.)); +#651=DIRECTION('',(0.,1.,0.)); +#652=DIRECTION('center_axis',(0.,0.,1.)); +#653=DIRECTION('ref_axis',(1.,0.,0.)); +#654=DIRECTION('center_axis',(0.,0.,1.)); +#655=DIRECTION('ref_axis',(1.,0.,0.)); +#656=DIRECTION('center_axis',(1.29526019539601E-16,-1.,0.)); +#657=DIRECTION('ref_axis',(-1.,-1.29526019539601E-16,0.)); +#658=DIRECTION('',(1.,1.29526019539601E-16,0.)); +#659=DIRECTION('',(0.,0.,-1.)); +#660=DIRECTION('',(-1.,-1.29526019539601E-16,0.)); +#661=DIRECTION('',(0.,0.,-1.)); +#662=DIRECTION('center_axis',(1.,1.29526019539601E-16,0.)); +#663=DIRECTION('ref_axis',(1.29526019539601E-16,-1.,0.)); +#664=DIRECTION('',(-1.29526019539601E-16,1.,0.)); +#665=DIRECTION('',(0.,0.,-1.)); +#666=DIRECTION('',(1.29526019539601E-16,-1.,0.)); +#667=DIRECTION('center_axis',(0.,0.,-1.)); +#668=DIRECTION('ref_axis',(1.,1.29526019539601E-16,0.)); +#669=DIRECTION('center_axis',(0.,0.,1.)); +#670=DIRECTION('ref_axis',(1.,1.29526019539601E-16,0.)); +#671=DIRECTION('',(0.,0.,-1.)); +#672=DIRECTION('center_axis',(0.,0.,-1.)); +#673=DIRECTION('ref_axis',(1.,1.29526019539601E-16,0.)); +#674=DIRECTION('center_axis',(-1.,-1.29526019539601E-16,0.)); +#675=DIRECTION('ref_axis',(-1.29526019539601E-16,1.,0.)); +#676=DIRECTION('',(1.29526019539601E-16,-1.,0.)); +#677=DIRECTION('',(-1.29526019539601E-16,1.,0.)); +#678=DIRECTION('center_axis',(0.,0.,1.)); +#679=DIRECTION('ref_axis',(1.,0.,0.)); +#680=DIRECTION('center_axis',(0.,0.,1.)); +#681=DIRECTION('ref_axis',(1.,0.,0.)); +#682=DIRECTION('center_axis',(0.,0.,-1.)); +#683=DIRECTION('ref_axis',(-1.,0.,0.)); +#684=DIRECTION('center_axis',(0.,0.,-1.)); +#685=DIRECTION('ref_axis',(-1.,0.,0.)); +#686=DIRECTION('',(0.,0.,-1.)); +#687=DIRECTION('center_axis',(0.,0.,-1.)); +#688=DIRECTION('ref_axis',(-1.,0.,0.)); +#689=DIRECTION('',(0.,0.,-1.)); +#690=DIRECTION('center_axis',(-1.,0.,0.)); +#691=DIRECTION('ref_axis',(0.,1.,0.)); +#692=DIRECTION('',(0.,1.,0.)); +#693=DIRECTION('',(0.,1.,0.)); +#694=DIRECTION('',(0.,0.,-1.)); +#695=DIRECTION('center_axis',(0.,0.,-1.)); +#696=DIRECTION('ref_axis',(0.,-1.,0.)); +#697=DIRECTION('center_axis',(0.,0.,-1.)); +#698=DIRECTION('ref_axis',(0.,-1.,0.)); +#699=DIRECTION('center_axis',(0.,0.,-1.)); +#700=DIRECTION('ref_axis',(0.,-1.,0.)); +#701=DIRECTION('',(0.,0.,-1.)); +#702=DIRECTION('center_axis',(0.,-1.,0.)); +#703=DIRECTION('ref_axis',(-1.,0.,0.)); +#704=DIRECTION('',(-1.,0.,0.)); +#705=DIRECTION('',(-1.,0.,0.)); +#706=DIRECTION('',(0.,0.,-1.)); +#707=DIRECTION('center_axis',(0.,0.,-1.)); +#708=DIRECTION('ref_axis',(1.,0.,0.)); +#709=DIRECTION('center_axis',(0.,0.,-1.)); +#710=DIRECTION('ref_axis',(1.,0.,0.)); +#711=DIRECTION('center_axis',(0.,0.,-1.)); +#712=DIRECTION('ref_axis',(1.,0.,0.)); +#713=DIRECTION('',(0.,0.,-1.)); +#714=DIRECTION('center_axis',(1.,0.,0.)); +#715=DIRECTION('ref_axis',(0.,-1.,0.)); +#716=DIRECTION('',(0.,-1.,0.)); +#717=DIRECTION('',(0.,-1.,0.)); +#718=DIRECTION('center_axis',(0.,0.,-1.)); +#719=DIRECTION('ref_axis',(-1.,0.,0.)); +#720=DIRECTION('center_axis',(0.,0.,-1.)); +#721=DIRECTION('ref_axis',(-1.,0.,0.)); +#722=DIRECTION('center_axis',(0.,0.,-1.)); +#723=DIRECTION('ref_axis',(0.,1.,0.)); +#724=DIRECTION('center_axis',(0.,0.,-1.)); +#725=DIRECTION('ref_axis',(0.,1.,0.)); +#726=DIRECTION('',(0.,0.,-1.)); +#727=DIRECTION('center_axis',(0.,0.,-1.)); +#728=DIRECTION('ref_axis',(0.,1.,0.)); +#729=DIRECTION('',(0.,0.,-1.)); +#730=DIRECTION('center_axis',(0.,1.,0.)); +#731=DIRECTION('ref_axis',(1.,0.,0.)); +#732=DIRECTION('',(1.,0.,0.)); +#733=DIRECTION('',(1.,0.,0.)); +#734=DIRECTION('',(0.,0.,-1.)); +#735=DIRECTION('center_axis',(0.,0.,-1.)); +#736=DIRECTION('ref_axis',(-1.,2.77555756156289E-16,0.)); +#737=DIRECTION('center_axis',(0.,0.,-1.)); +#738=DIRECTION('ref_axis',(-1.,2.77555756156289E-16,0.)); +#739=DIRECTION('center_axis',(0.,0.,-1.)); +#740=DIRECTION('ref_axis',(-1.,2.77555756156289E-16,0.)); +#741=DIRECTION('',(0.,0.,-1.)); +#742=DIRECTION('center_axis',(-1.,0.,0.)); +#743=DIRECTION('ref_axis',(0.,1.,0.)); +#744=DIRECTION('',(0.,1.,0.)); +#745=DIRECTION('',(0.,1.,0.)); +#746=DIRECTION('',(0.,0.,-1.)); +#747=DIRECTION('center_axis',(0.,0.,-1.)); +#748=DIRECTION('ref_axis',(0.,-1.,0.)); +#749=DIRECTION('center_axis',(0.,0.,-1.)); +#750=DIRECTION('ref_axis',(0.,-1.,0.)); +#751=DIRECTION('center_axis',(0.,0.,-1.)); +#752=DIRECTION('ref_axis',(0.,-1.,0.)); +#753=DIRECTION('',(0.,0.,-1.)); +#754=DIRECTION('center_axis',(0.,-1.,0.)); +#755=DIRECTION('ref_axis',(-1.,0.,0.)); +#756=DIRECTION('',(-1.,0.,0.)); +#757=DIRECTION('',(-1.,0.,0.)); +#758=DIRECTION('',(0.,0.,-1.)); +#759=DIRECTION('center_axis',(0.,0.,-1.)); +#760=DIRECTION('ref_axis',(1.,0.,0.)); +#761=DIRECTION('center_axis',(0.,0.,-1.)); +#762=DIRECTION('ref_axis',(1.,0.,0.)); +#763=DIRECTION('center_axis',(0.,0.,-1.)); +#764=DIRECTION('ref_axis',(1.,0.,0.)); +#765=DIRECTION('',(0.,0.,-1.)); +#766=DIRECTION('center_axis',(1.,0.,0.)); +#767=DIRECTION('ref_axis',(0.,-1.,0.)); +#768=DIRECTION('',(0.,-1.,0.)); +#769=DIRECTION('',(0.,-1.,0.)); +#770=DIRECTION('center_axis',(0.,0.,-1.)); +#771=DIRECTION('ref_axis',(-1.,0.,0.)); +#772=DIRECTION('center_axis',(0.,0.,-1.)); +#773=DIRECTION('ref_axis',(-1.,0.,0.)); +#774=CARTESIAN_POINT('',(0.,0.,0.)); +#775=CARTESIAN_POINT('Origin',(5.5,-2.,0.)); +#776=CARTESIAN_POINT('',(5.5,-4.,0.)); +#777=CARTESIAN_POINT('',(7.5,-2.,0.)); +#778=CARTESIAN_POINT('Origin',(5.5,-2.,0.)); +#779=CARTESIAN_POINT('',(7.5,-2.,23.)); +#780=CARTESIAN_POINT('',(7.5,-2.,0.)); +#781=CARTESIAN_POINT('',(5.5,-4.,23.)); +#782=CARTESIAN_POINT('Origin',(5.5,-2.,23.)); +#783=CARTESIAN_POINT('',(5.5,-4.,0.)); +#784=CARTESIAN_POINT('Origin',(-5.5,-4.,0.)); +#785=CARTESIAN_POINT('',(-5.5,-4.,0.)); +#786=CARTESIAN_POINT('',(-5.5,-4.,0.)); +#787=CARTESIAN_POINT('',(-5.5,-4.,23.)); +#788=CARTESIAN_POINT('',(-5.5,-4.,23.)); +#789=CARTESIAN_POINT('',(-5.5,-4.,0.)); +#790=CARTESIAN_POINT('Origin',(-5.5,-2.,0.)); +#791=CARTESIAN_POINT('',(-7.5,-2.,0.)); +#792=CARTESIAN_POINT('Origin',(-5.5,-2.,0.)); +#793=CARTESIAN_POINT('',(-7.5,-2.,23.)); +#794=CARTESIAN_POINT('Origin',(-5.5,-2.,23.)); +#795=CARTESIAN_POINT('',(-7.5,-2.,0.)); +#796=CARTESIAN_POINT('Origin',(-7.5,0.,0.)); +#797=CARTESIAN_POINT('',(-7.5,0.,0.)); +#798=CARTESIAN_POINT('',(-7.5,0.,0.)); +#799=CARTESIAN_POINT('',(-7.5,0.,23.)); +#800=CARTESIAN_POINT('',(-7.5,0.,23.)); +#801=CARTESIAN_POINT('',(-7.5,0.,0.)); +#802=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#803=CARTESIAN_POINT('',(7.5,1.83697019872103E-15,0.)); +#804=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#805=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,23.)); +#806=CARTESIAN_POINT('Origin',(0.,0.,23.)); +#807=CARTESIAN_POINT('',(7.5,1.83697019872103E-15,0.)); +#808=CARTESIAN_POINT('Origin',(7.5,-2.,0.)); +#809=CARTESIAN_POINT('',(7.5,-2.,0.)); +#810=CARTESIAN_POINT('',(7.5,-2.,23.)); +#811=CARTESIAN_POINT('Origin',(0.,1.75,23.)); +#812=CARTESIAN_POINT('Origin',(0.,1.75,0.)); +#813=CARTESIAN_POINT('Origin',(5.5,-2.,21.5)); +#814=CARTESIAN_POINT('',(-5.5,-2.,21.5)); +#815=CARTESIAN_POINT('',(5.5,-2.,21.5)); +#816=CARTESIAN_POINT('',(-5.5,-2.,21.5)); +#817=CARTESIAN_POINT('',(5.5,-2.,1.5)); +#818=CARTESIAN_POINT('',(5.5,-2.,21.5)); +#819=CARTESIAN_POINT('',(-5.5,-2.,1.5)); +#820=CARTESIAN_POINT('',(-5.5,-2.,1.5)); +#821=CARTESIAN_POINT('',(-5.5,-2.,21.5)); +#822=CARTESIAN_POINT('Origin',(5.5,8.32667268468867E-16,21.5)); +#823=CARTESIAN_POINT('',(5.5,7.12393107467807E-16,21.5)); +#824=CARTESIAN_POINT('',(5.5,-2.,21.5)); +#825=CARTESIAN_POINT('',(5.5,7.12393107467807E-16,1.5)); +#826=CARTESIAN_POINT('',(5.5,7.12393107467807E-16,21.5)); +#827=CARTESIAN_POINT('',(5.5,-2.,1.5)); +#828=CARTESIAN_POINT('Origin',(0.,0.,21.5)); +#829=CARTESIAN_POINT('',(-5.5,-7.12393107467807E-16,21.5)); +#830=CARTESIAN_POINT('Origin',(0.,0.,21.5)); +#831=CARTESIAN_POINT('',(-5.5,-7.12393107467807E-16,1.5)); +#832=CARTESIAN_POINT('',(-5.5,-7.12393107467807E-16,21.5)); +#833=CARTESIAN_POINT('Origin',(0.,0.,1.5)); +#834=CARTESIAN_POINT('Origin',(-5.5,-2.,21.5)); +#835=CARTESIAN_POINT('',(-5.5,-7.12393107467807E-16,21.5)); +#836=CARTESIAN_POINT('',(-5.5,-7.12393107467807E-16,1.5)); +#837=CARTESIAN_POINT('Origin',(0.,1.75,21.5)); +#838=CARTESIAN_POINT('Origin',(0.,1.75,1.5)); +#839=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#840=CARTESIAN_POINT('',(-7.5,0.,0.)); +#841=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,0.)); +#842=CARTESIAN_POINT('Origin',(0.,0.,0.)); +#843=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-1.)); +#844=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,0.)); +#845=CARTESIAN_POINT('',(-7.5,0.,-1.)); +#846=CARTESIAN_POINT('Origin',(0.,0.,-1.)); +#847=CARTESIAN_POINT('',(-7.5,0.,0.)); +#848=CARTESIAN_POINT('Origin',(-7.5,-2.,0.)); +#849=CARTESIAN_POINT('',(-7.5,-2.,0.)); +#850=CARTESIAN_POINT('',(-7.5,-2.,0.)); +#851=CARTESIAN_POINT('',(-7.5,-2.,-1.)); +#852=CARTESIAN_POINT('',(-7.5,-2.,-1.)); +#853=CARTESIAN_POINT('',(-7.5,-2.,0.)); +#854=CARTESIAN_POINT('Origin',(-5.5,-2.,0.)); +#855=CARTESIAN_POINT('',(-5.5,-4.,0.)); +#856=CARTESIAN_POINT('Origin',(-5.5,-2.,0.)); +#857=CARTESIAN_POINT('',(-5.5,-4.,-1.)); +#858=CARTESIAN_POINT('Origin',(-5.5,-2.,-1.)); +#859=CARTESIAN_POINT('',(-5.5,-4.,0.)); +#860=CARTESIAN_POINT('Origin',(5.5,-4.,0.)); +#861=CARTESIAN_POINT('',(5.5,-4.,0.)); +#862=CARTESIAN_POINT('',(5.5,-4.,0.)); +#863=CARTESIAN_POINT('',(5.5,-4.,-1.)); +#864=CARTESIAN_POINT('',(5.5,-4.,-1.)); +#865=CARTESIAN_POINT('',(5.5,-4.,0.)); +#866=CARTESIAN_POINT('Origin',(5.5,-2.,0.)); +#867=CARTESIAN_POINT('',(7.5,-2.,0.)); +#868=CARTESIAN_POINT('Origin',(5.5,-2.,0.)); +#869=CARTESIAN_POINT('',(7.5,-2.,-1.)); +#870=CARTESIAN_POINT('Origin',(5.5,-2.,-1.)); +#871=CARTESIAN_POINT('',(7.5,-2.,0.)); +#872=CARTESIAN_POINT('Origin',(7.5,1.94289029309402E-15,0.)); +#873=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,0.)); +#874=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-1.)); +#875=CARTESIAN_POINT('Origin',(0.,1.75,-1.)); +#876=CARTESIAN_POINT('Origin',(0.,1.75,0.)); +#877=CARTESIAN_POINT('Origin',(5.5,-5.55111512312578E-16,-1.)); +#878=CARTESIAN_POINT('',(5.5,2.,-1.)); +#879=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-1.)); +#880=CARTESIAN_POINT('Origin',(5.5,-5.55111512312578E-16,-1.)); +#881=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-3.)); +#882=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-1.)); +#883=CARTESIAN_POINT('',(5.5,2.,-3.)); +#884=CARTESIAN_POINT('Origin',(5.5,-5.55111512312578E-16,-3.)); +#885=CARTESIAN_POINT('',(5.5,2.,-1.)); +#886=CARTESIAN_POINT('Origin',(-5.5,2.,-1.)); +#887=CARTESIAN_POINT('',(-5.5,2.,-1.)); +#888=CARTESIAN_POINT('',(-5.5,2.,-1.)); +#889=CARTESIAN_POINT('',(-5.5,2.,-3.)); +#890=CARTESIAN_POINT('',(-5.5,2.,-3.)); +#891=CARTESIAN_POINT('',(-5.5,2.,-1.)); +#892=CARTESIAN_POINT('Origin',(-5.5,-5.55111512312578E-16,-1.)); +#893=CARTESIAN_POINT('',(-7.5,0.,-1.)); +#894=CARTESIAN_POINT('Origin',(-5.5,-5.55111512312578E-16,-1.)); +#895=CARTESIAN_POINT('',(-7.5,0.,-3.)); +#896=CARTESIAN_POINT('Origin',(-5.5,-5.55111512312578E-16,-3.)); +#897=CARTESIAN_POINT('',(-7.5,0.,-1.)); +#898=CARTESIAN_POINT('Origin',(-7.5,-2.,-1.)); +#899=CARTESIAN_POINT('',(-7.5,-2.,-1.)); +#900=CARTESIAN_POINT('',(-7.5,-2.,-1.)); +#901=CARTESIAN_POINT('',(-7.5,-2.,-3.)); +#902=CARTESIAN_POINT('',(-7.5,-2.,-3.)); +#903=CARTESIAN_POINT('',(-7.5,-2.,-1.)); +#904=CARTESIAN_POINT('Origin',(-5.5,-2.,-1.)); +#905=CARTESIAN_POINT('',(-5.5,-4.,-1.)); +#906=CARTESIAN_POINT('Origin',(-5.5,-2.,-1.)); +#907=CARTESIAN_POINT('',(-5.5,-4.,-3.)); +#908=CARTESIAN_POINT('Origin',(-5.5,-2.,-3.)); +#909=CARTESIAN_POINT('',(-5.5,-4.,-1.)); +#910=CARTESIAN_POINT('Origin',(5.5,-4.,-1.)); +#911=CARTESIAN_POINT('',(5.5,-4.,-1.)); +#912=CARTESIAN_POINT('',(5.5,-4.,-1.)); +#913=CARTESIAN_POINT('',(5.5,-4.,-3.)); +#914=CARTESIAN_POINT('',(5.5,-4.,-3.)); +#915=CARTESIAN_POINT('',(5.5,-4.,-1.)); +#916=CARTESIAN_POINT('Origin',(5.5,-2.,-1.)); +#917=CARTESIAN_POINT('',(7.5,-2.,-1.)); +#918=CARTESIAN_POINT('Origin',(5.5,-2.,-1.)); +#919=CARTESIAN_POINT('',(7.5,-2.,-3.)); +#920=CARTESIAN_POINT('Origin',(5.5,-2.,-3.)); +#921=CARTESIAN_POINT('',(7.5,-2.,-1.)); +#922=CARTESIAN_POINT('Origin',(7.5,1.94289029309402E-15,-1.)); +#923=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-1.)); +#924=CARTESIAN_POINT('',(7.5,1.94289029309402E-15,-3.)); +#925=CARTESIAN_POINT('Origin',(0.,-1.,-3.)); +#926=CARTESIAN_POINT('Origin',(0.,-1.,-1.)); +#927=CARTESIAN_POINT('',(0.,0.,23.)); +#928=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#932, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#929=UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(0.01),#932, +'DISTANCE_ACCURACY_VALUE', +'Maximum model space distance between geometric entities at asserted c +onnectivities'); +#930=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#928)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#932,#934,#935)) +REPRESENTATION_CONTEXT('','3D') +); +#931=( +GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#929)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#932,#934,#935)) +REPRESENTATION_CONTEXT('','3D') +); +#932=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.MILLI.,.METRE.) +); +#933=( +LENGTH_UNIT() +NAMED_UNIT(*) +SI_UNIT(.CENTI.,.METRE.) +); +#934=( +NAMED_UNIT(*) +PLANE_ANGLE_UNIT() +SI_UNIT($,.RADIAN.) +); +#935=( +NAMED_UNIT(*) +SI_UNIT($,.STERADIAN.) +SOLID_ANGLE_UNIT() +); +#936=SHAPE_DEFINITION_REPRESENTATION(#937,#938); +#937=PRODUCT_DEFINITION_SHAPE('',$,#940); +#938=SHAPE_REPRESENTATION('',(#559),#930); +#939=PRODUCT_DEFINITION_CONTEXT('part definition',#944,'design'); +#940=PRODUCT_DEFINITION('ACTBODYSOFA23mm2','ACTBODYSOFA23mm2',#941,#939); +#941=PRODUCT_DEFINITION_FORMATION('',$,#946); +#942=PRODUCT_RELATED_PRODUCT_CATEGORY('ACTBODYSOFA23mm2', +'ACTBODYSOFA23mm2',(#946)); +#943=APPLICATION_PROTOCOL_DEFINITION('international standard', +'automotive_design',2009,#944); +#944=APPLICATION_CONTEXT( +'Core Data for Automotive Mechanical Design Process'); +#945=PRODUCT_CONTEXT('part definition',#944,'mechanical'); +#946=PRODUCT('ACTBODYSOFA23mm2','ACTBODYSOFA23mm2',$,(#945)); +#947=PRESENTATION_STYLE_ASSIGNMENT((#949)); +#948=PRESENTATION_STYLE_ASSIGNMENT((#950)); +#949=SURFACE_STYLE_USAGE(.BOTH.,#953); +#950=SURFACE_STYLE_USAGE(.BOTH.,#954); +#951=SURFACE_STYLE_RENDERING_WITH_PROPERTIES($,#961,(#952)); +#952=SURFACE_STYLE_TRANSPARENT(0.); +#953=SURFACE_SIDE_STYLE('',(#955,#951)); +#954=SURFACE_SIDE_STYLE('',(#956)); +#955=SURFACE_STYLE_FILL_AREA(#957); +#956=SURFACE_STYLE_FILL_AREA(#958); +#957=FILL_AREA_STYLE('',(#959)); +#958=FILL_AREA_STYLE('',(#960)); +#959=FILL_AREA_STYLE_COLOUR('',#961); +#960=FILL_AREA_STYLE_COLOUR('',#962); +#961=COLOUR_RGB('',0.749019607843137,0.749019607843137,0.749019607843137); +#962=COLOUR_RGB('',1.,1.,0.); +ENDSEC; +END-ISO-10303-21; +//+ +SetFactory("OpenCASCADE"); +BooleanUnion{ Volume{3}; Delete; }{ Volume{2}; Delete; } +//+ +BooleanFragments{ Volume{2}; Delete; }{ Volume{1}; Delete; } diff --git a/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector075.msh b/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector075.msh new file mode 100644 index 00000000..6cff2044 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/data/mesh/act23mmwithconnector075.msh @@ -0,0 +1,56586 @@ +$MeshFormat +4.1 0 8 +$EndMeshFormat +$Entities +32 52 25 2 +1 5.5 2 -1 0 +2 7.5 1.94289029309402e-15 -1 0 +3 7.5 1.94289029309402e-15 -3 0 +4 5.5 2 -3 0 +5 -7.5 0 -1 0 +6 -5.5 2 -1 0 +7 7.5 -2 -3 0 +8 7.5 1.90758359496969e-15 0 0 +9 7.5 -2 0 0 +10 5.5 -4 -3 0 +11 -5.5 -4 -3 0 +12 -7.5 -2 -3 0 +13 -7.5 0 -3 0 +14 -5.5 2 -3 0 +15 -7.5 0 0 0 +16 5.5 -4 0 0 +17 -5.5 -4 0 0 +18 -7.5 -2 0 0 +19 7.5 -2 23 0 +20 5.5 -4 23 0 +21 -5.5 -4 23 0 +22 -7.5 -2 23 0 +23 -7.5 0 23 0 +24 7.5 1.94289029309402e-15 23 0 +25 -5.5 -2 21.5 0 +26 5.5 -2 21.5 0 +27 5.5 -2 1.5 0 +28 -5.5 -2 1.5 0 +29 5.5 7.12393107467807e-16 21.5 0 +30 5.5 7.12393107467807e-16 1.5 0 +31 -5.5 -7.12393107467807e-16 1.5 0 +32 -5.5 -7.12393107467807e-16 21.5 0 +1 5.4999999 -9.999999828202988e-08 -1.0000001 7.5000001 2.000000099999999 -0.9999999000000001 0 2 1 -2 +2 7.4999999 -9.99999980571097e-08 -3.0000001 7.5000001 1.000000019428903e-07 -0.9999999000000002 0 2 2 -3 +3 5.4999999 -9.999999828202988e-08 -3.0000001 7.5000001 2.000000099999999 -2.9999999 0 2 4 -3 +4 5.4999999 1.9999999 -3.0000001 5.5000001 2.0000001 -0.9999999000000002 0 2 1 -4 +5 -7.5000001 -9.999999983634211e-08 -1.0000001 7.5000001 7.5000001 -0.9999999000000001 0 2 5 -2 +6 -7.5000001 -9.999999994736442e-08 -1.0000001 -5.4999999 2.000000099999999 -0.9999999000000001 0 2 5 -6 +7 -5.5000001 1.9999999 -1.0000001 5.5000001 2.0000001 -0.9999999000000001 0 2 6 -1 +8 7.4999999 -2.0000001 -3.0000001 7.5000001 1.000000019457659e-07 -2.9999999 0 2 3 -7 +9 7.4999999 -9.99999980571097e-08 -1.0000001 7.5000001 1.000000019428903e-07 9.999999994736442e-08 0 2 8 -2 +10 7.4999999 -2.0000001 -1.000000001110223e-07 7.5000001 1.000000020567882e-07 1.000000001110223e-07 0 2 8 -9 +11 7.4999999 -2.0000001 -3.0000001 7.5000001 -1.9999999 1.000000000583867e-07 0 2 9 -7 +12 5.4999999 -4.0000001 -3.0000001 7.5000001 -1.9999999 -2.9999999 0 2 7 -10 +13 -5.5000001 -4.0000001 -3.0000001 5.5000001 -3.9999999 -2.9999999 0 2 10 -11 +14 -7.5000001 -4.0000001 -3.0000001 -5.4999999 -1.9999999 -2.9999999 0 2 11 -12 +15 -7.5000001 -2.0000001 -3.0000001 -7.4999999 9.999999994736442e-08 -2.9999999 0 2 12 -13 +16 -7.5000001 -9.999999994736442e-08 -3.0000001 -5.4999999 2.000000099999999 -2.9999999 0 2 13 -14 +17 -5.5000001 1.9999999 -3.0000001 5.5000001 2.0000001 -2.9999999 0 2 14 -4 +18 -5.5000001 1.9999999 -3.0000001 -5.4999999 2.0000001 -0.9999999000000002 0 2 6 -14 +19 -7.500000100000001 -1.00000001612699e-07 -1.000000016011864e-07 7.500000100000001 7.500000100000001 1.000000016011864e-07 0 2 15 -8 +20 -7.5000001 -1e-07 -1.0000001 -7.4999999 1e-07 9.999999994736442e-08 0 2 15 -5 +21 -7.5000001 -1e-07 -3.0000001 -7.4999999 1e-07 -0.9999999000000002 0 2 5 -13 +22 5.4999999 -4.0000001 -1.000000004440892e-07 7.5000001 -1.999999899999999 1.000000004440892e-07 0 2 9 -16 +23 5.4999999 -4.0000001 -3.0000001 5.5000001 -3.9999999 1.000000000583867e-07 0 2 16 -10 +24 -5.500000100000001 -4.000000100000001 -1.000000008881784e-07 5.500000100000001 -3.999999899999999 1.000000008881784e-07 0 2 16 -17 +25 -5.5000001 -4.0000001 -3.0000001 -5.4999999 -3.9999999 1.000000000583867e-07 0 2 17 -11 +26 -7.5000001 -4.0000001 -1.000000004440892e-07 -5.4999999 -1.999999899999999 1.000000004440892e-07 0 2 17 -18 +27 -7.5000001 -2.0000001 -3.0000001 -7.4999999 -1.9999999 1.000000000583867e-07 0 2 18 -12 +28 -7.5000001 -2.0000001 -1e-07 -7.4999999 9.999999994736442e-08 1e-07 0 2 18 -15 +29 7.4999999 -2.0000001 -9.99999993922529e-08 7.5000001 -1.9999999 23.0000001 0 2 9 -19 +30 5.4999999 -4.0000001 22.9999999 7.5000001 -1.9999999 23.0000001 0 2 20 -19 +31 5.4999999 -4.0000001 -9.99999993922529e-08 5.5000001 -3.9999999 23.0000001 0 2 16 -20 +32 -5.5000001 -4.0000001 22.9999999 5.5000001 -3.9999999 23.0000001 0 2 21 -20 +33 -5.5000001 -4.0000001 -9.99999993922529e-08 -5.4999999 -3.9999999 23.0000001 0 2 17 -21 +34 -7.5000001 -4.0000001 22.9999999 -5.4999999 -1.9999999 23.0000001 0 2 22 -21 +35 -7.5000001 -2.0000001 -9.99999993922529e-08 -7.4999999 -1.9999999 23.0000001 0 2 18 -22 +36 -7.5000001 -2.0000001 22.9999999 -7.4999999 9.999999994736442e-08 23.0000001 0 2 23 -22 +37 -7.5000001 -1e-07 -9.99999993922529e-08 -7.4999999 1e-07 23.0000001 0 2 15 -23 +38 -7.5000001 -1.000000007245205e-07 22.9999999 7.5000001 7.5000001 23.0000001 0 2 24 -23 +39 7.4999999 -9.99999981630298e-08 -9.99999993922529e-08 7.5000001 1.000000018369702e-07 23.0000001 0 2 8 -24 +40 7.4999999 -2.0000001 22.9999999 7.5000001 1.000000017237213e-07 23.0000001 0 2 19 -24 +41 -5.5000001 -2.0000001 21.4999999 5.5000001 -1.999999899999999 21.5000001 0 2 25 -26 +42 5.4999999 -2.0000001 1.499999900000001 5.5000001 -1.9999999 21.5000001 0 2 26 -27 +43 -5.5000001 -2.0000001 1.4999999 5.5000001 -1.999999899999999 1.5000001 0 2 27 -28 +44 -5.5000001 -2.0000001 1.499999900000001 -5.4999999 -1.9999999 21.5000001 0 2 25 -28 +45 5.4999999 -2.0000001 21.4999999 5.5000001 1.000000008355428e-07 21.5000001 0 2 26 -29 +46 5.4999999 -9.999999928760689e-08 1.499999900000001 5.5000001 1.000000007123931e-07 21.5000001 0 2 29 -30 +47 5.4999999 -2.0000001 1.4999999 5.5000001 1.000000008355428e-07 1.5000001 0 2 30 -27 +48 -5.5000001 -1.000000011686097e-07 1.4999999 5.5000001 5.5000001 1.5000001 0 2 31 -30 +49 -5.5000001 -1.000000007123931e-07 1.499999900000001 -5.4999999 9.999999928760689e-08 21.5000001 0 2 32 -31 +50 -5.5000001 -9.999999983634211e-08 21.4999999 5.5000001 5.5000001 21.5000001 0 2 29 -32 +51 -5.5000001 -2.0000001 21.4999999 -5.4999999 9.99999993922529e-08 21.5000001 0 2 32 -25 +52 -5.5000001 -2.0000001 1.4999999 -5.4999999 9.99999993922529e-08 1.5000001 0 2 28 -31 +1 5.4999999 -9.999999828202988e-08 -3.0000001 7.5000001 2.000000099999999 -0.9999999000000002 0 4 1 2 -3 -4 +2 -7.5000001 -9.999999983634211e-08 -1.0000001 7.5000001 7.5000001 -0.9999999000000001 0 4 5 -1 -7 -6 +3 7.4999999 -2.0000001 -3.0000001 7.5000001 1.000000020567882e-07 1.000000000583867e-07 0 5 -8 -2 -9 10 11 +4 -7.5000001 -4.0000001 -3.0000001 7.5000001 2.0000001 -2.9999999 0 8 8 12 13 14 15 16 17 3 +5 -5.5000001 1.9999999 -3.0000001 5.5000001 2.0000001 -0.9999999000000002 0 4 7 4 -17 -18 +6 -7.5000001 -9.999999983634211e-08 -1.0000001 7.5000001 7.5000001 9.999999994736442e-08 0 4 19 9 -5 -20 +7 -7.5000001 -9.999999994736442e-08 -3.0000001 -5.4999999 2.000000099999999 -0.9999999000000002 0 4 6 18 -16 -21 +8 5.4999999 -4.0000001 -3.0000001 7.5000001 -1.9999999 1.000000000583867e-07 0 4 -12 -11 22 23 +9 -5.500000100000001 -4.000000100000001 -3.000000100000001 5.500000100000001 -3.999999899999999 1.000000009465651e-07 0 4 -13 -23 24 25 +10 -7.5000001 -4.0000001 -3.0000001 -5.4999999 -1.9999999 1.000000000583867e-07 0 4 -14 -25 26 27 +11 -7.5000001 -2.0000001 -3.0000001 -7.4999999 9.999999994736442e-08 1.000000000583867e-07 0 5 21 -15 -27 28 20 +12 -7.500000100000001 -4.000000100000001 -1.000000016011864e-07 7.500000100000001 7.500000100000001 1.000000016011864e-07 0 6 22 24 26 28 19 10 +13 5.4999999 -4.0000001 -9.99999993922529e-08 7.5000001 -1.9999999 23.0000001 0 4 -22 29 -30 -31 +14 -5.500000100000001 -4.000000100000001 -1.000000011686097e-07 5.500000100000001 -3.999999899999999 23.0000001 0 4 -24 31 -32 -33 +15 -7.5000001 -4.0000001 -9.99999993922529e-08 -5.4999999 -1.9999999 23.0000001 0 4 -26 33 -34 -35 +16 -7.5000001 -2.0000001 -9.99999993922529e-08 -7.4999999 9.999999994736442e-08 23.0000001 0 4 -28 35 -36 -37 +17 -7.5000001 -1.000000007245205e-07 -9.99999993922529e-08 7.5000001 7.5000001 23.0000001 0 4 -19 37 -38 -39 +18 7.4999999 -2.0000001 -9.99999993922529e-08 7.5000001 1.000000020567882e-07 23.0000001 0 4 -10 39 -40 -29 +19 -7.5000001 -4.0000001 22.9999999 7.5000001 7.5000001 23.0000001 0 6 40 38 36 34 32 30 +20 -5.5000001 -2.0000001 1.499999900000001 5.5000001 -1.999999899999999 21.5000001 0 4 44 -43 -42 -41 +21 5.4999999 -2.0000001 1.499999900000001 5.5000001 1.000000008355428e-07 21.5000001 0 4 42 -47 -46 -45 +22 -5.5000001 -1.000000011686097e-07 1.499999900000001 5.5000001 5.5000001 21.5000001 0 4 46 -48 -49 -50 +23 -5.5000001 -2.0000001 1.499999900000001 -5.4999999 9.99999993922529e-08 21.5000001 0 4 49 -52 -44 -51 +24 -5.5000001 -2.0000001 21.4999999 5.5000001 5.5000001 21.5000001 0 4 41 45 50 51 +25 -5.5000001 -2.0000001 1.4999999 5.5000001 5.5000001 1.5000001 0 4 -52 -43 -47 -48 +1 -7.500000100000001 -4.000000100000001 -1.000000011686097e-07 7.500000100000001 7.500000100000001 23.0000001 0 14 13 14 15 16 17 18 19 12 -20 -21 -22 -23 -24 25 +2 -7.500000100000001 -4.000000100000001 -3.000000100000002 7.500000100000001 7.500000100000001 1.00000001612699e-07 0 12 1 2 3 4 5 6 7 8 9 10 11 -12 +$EndEntities +$Nodes +111 7459 1 7459 +0 1 0 1 +1 +5.5 2 -1 +0 2 0 1 +2 +7.5 1.94289029309402e-15 -1 +0 3 0 1 +3 +7.5 1.94289029309402e-15 -3 +0 4 0 1 +4 +5.5 2 -3 +0 5 0 1 +5 +-7.5 0 -1 +0 6 0 1 +6 +-5.5 2 -1 +0 7 0 1 +7 +7.5 -2 -3 +0 8 0 1 +8 +7.5 1.90758359496969e-15 0 +0 9 0 1 +9 +7.5 -2 0 +0 10 0 1 +10 +5.5 -4 -3 +0 11 0 1 +11 +-5.5 -4 -3 +0 12 0 1 +12 +-7.5 -2 -3 +0 13 0 1 +13 +-7.5 0 -3 +0 14 0 1 +14 +-5.5 2 -3 +0 15 0 1 +15 +-7.5 0 0 +0 16 0 1 +16 +5.5 -4 0 +0 17 0 1 +17 +-5.5 -4 0 +0 18 0 1 +18 +-7.5 -2 0 +0 19 0 1 +19 +7.5 -2 23 +0 20 0 1 +20 +5.5 -4 23 +0 21 0 1 +21 +-5.5 -4 23 +0 22 0 1 +22 +-7.5 -2 23 +0 23 0 1 +23 +-7.5 0 23 +0 24 0 1 +24 +7.5 1.94289029309402e-15 23 +0 25 0 1 +25 +-5.5 -2 21.5 +0 26 0 1 +26 +5.5 -2 21.5 +0 27 0 1 +27 +5.5 -2 1.5 +0 28 0 1 +28 +-5.5 -2 1.5 +0 29 0 1 +29 +5.5 7.12393107467807e-16 21.5 +0 30 0 1 +30 +5.5 7.12393107467807e-16 1.5 +0 31 0 1 +31 +-5.5 -7.12393107467807e-16 1.5 +0 32 0 1 +32 +-5.5 -7.12393107467807e-16 21.5 +1 1 0 4 +33 +34 +35 +36 +6.118033988749894 1.902113032590307 -1 +6.675570504584944 1.618033988749896 -1 +7.118033988749893 1.175570504584948 -1 +7.402113032590306 0.6180339887498961 -1 +1 2 0 2 +37 +38 +7.5 1.94289029309402e-15 -1.666666666666667 +7.5 1.94289029309402e-15 -2.333333333333336 +1 3 0 4 +39 +40 +41 +42 +6.118033988749894 1.902113032590307 -3 +6.675570504584944 1.618033988749896 -3 +7.118033988749893 1.175570504584948 -3 +7.402113032590306 0.6180339887498961 -3 +1 4 0 2 +43 +44 +5.5 2 -1.666666666666667 +5.5 2 -2.333333333333336 +1 5 0 31 +45 +46 +47 +48 +49 +50 +51 +52 +53 +54 +55 +56 +57 +58 +59 +60 +61 +62 +63 +64 +65 +66 +67 +68 +69 +70 +71 +72 +73 +74 +75 +-7.463885450041477 0.7351285524717031 -1 +-7.355889603024229 1.463177415120959 -1 +-7.177052517991568 2.177135079408464 -1 +-6.929096493834653 2.870125742738169 -1 +-6.614409482612666 3.535475526194976 -1 +-6.236022092269094 4.16677674764701 -1 +-5.797578400220534 4.757949631227333 -1 +-5.303300858899114 5.3033008588991 -1 +-4.75794963122735 5.79757840022052 -1 +-4.166776747647029 6.236022092269081 -1 +-3.535475526194998 6.614409482612655 -1 +-2.870125742738189 6.929096493834644 -1 +-2.177135079408485 7.177052517991561 -1 +-1.463177415120982 7.355889603024224 -1 +-0.7351285524717257 7.463885450041475 -1 +-2.210857636287394e-14 7.5 -1 +0.7351285524716783 7.463885450041479 -1 +1.46317741512094 7.355889603024233 -1 +2.177135079408449 7.177052517991572 -1 +2.870125742738157 6.929096493834657 -1 +3.535475526194968 6.61440948261267 -1 +4.166776747647006 6.236022092269096 -1 +4.757949631227335 5.797578400220533 -1 +5.303300858899101 5.303300858899112 -1 +5.797578400220523 4.757949631227346 -1 +6.236022092269086 4.166776747647021 -1 +6.614409482612662 3.535475526194984 -1 +6.929096493834651 2.870125742738174 -1 +7.177052517991568 2.177135079408465 -1 +7.355889603024228 1.463177415120961 -1 +7.463885450041477 0.7351285524717029 -1 +1 6 0 4 +76 +77 +78 +79 +-7.402113032590307 0.6180339887498941 -1 +-7.118033988749896 1.175570504584945 -1 +-6.675570504584947 1.618033988749894 -1 +-6.118033988749895 1.902113032590307 -1 +1 7 0 14 +80 +81 +82 +83 +84 +85 +86 +87 +88 +89 +90 +91 +92 +93 +-4.766666666666666 2 -1 +-4.033333333333331 2 -1 +-3.299999999999997 2 -1 +-2.566666666666663 2 -1 +-1.833333333333327 2 -1 +-1.09999999999999 2 -1 +-0.3666666666666538 2 -1 +0.3666666666666831 2 -1 +1.100000000000015 2 -1 +1.833333333333345 2 -1 +2.566666666666677 2 -1 +3.300000000000008 2 -1 +4.033333333333339 2 -1 +4.766666666666669 2 -1 +1 8 0 2 +94 +95 +7.5 -0.6666666666666655 -3 +7.5 -1.333333333333335 -3 +1 9 0 1 +96 +7.5 1.94289029309402e-15 -0.5000000000000006 +1 10 0 2 +97 +98 +7.5 -0.6666666666666655 0 +7.5 -1.333333333333335 0 +1 11 0 3 +99 +100 +101 +7.5 -2 -0.75 +7.5 -2 -1.5 +7.5 -2 -2.25 +1 12 0 4 +102 +103 +104 +105 +7.402113032590307 -2.618033988749894 -3 +7.118033988749896 -3.175570504584945 -3 +6.675570504584948 -3.618033988749894 -3 +6.118033988749896 -3.902113032590307 -3 +1 13 0 14 +106 +107 +108 +109 +110 +111 +112 +113 +114 +115 +116 +117 +118 +119 +4.766666666666666 -4 -3 +4.033333333333331 -4 -3 +3.299999999999997 -4 -3 +2.566666666666663 -4 -3 +1.833333333333327 -4 -3 +1.09999999999999 -4 -3 +0.3666666666666538 -4 -3 +-0.3666666666666831 -4 -3 +-1.100000000000015 -4 -3 +-1.833333333333345 -4 -3 +-2.566666666666677 -4 -3 +-3.300000000000008 -4 -3 +-4.033333333333339 -4 -3 +-4.766666666666669 -4 -3 +1 14 0 4 +120 +121 +122 +123 +-6.118033988749894 -3.902113032590307 -3 +-6.675570504584945 -3.618033988749896 -3 +-7.118033988749894 -3.175570504584948 -3 +-7.402113032590307 -2.618033988749896 -3 +1 15 0 2 +124 +125 +-7.5 -1.333333333333333 -3 +-7.5 -0.6666666666666643 -3 +1 16 0 4 +126 +127 +128 +129 +-7.402113032590307 0.6180339887498941 -3 +-7.118033988749896 1.175570504584945 -3 +-6.675570504584947 1.618033988749894 -3 +-6.118033988749895 1.902113032590307 -3 +1 17 0 14 +130 +131 +132 +133 +134 +135 +136 +137 +138 +139 +140 +141 +142 +143 +-4.766666666666666 2 -3 +-4.033333333333331 2 -3 +-3.299999999999997 2 -3 +-2.566666666666663 2 -3 +-1.833333333333327 2 -3 +-1.09999999999999 2 -3 +-0.3666666666666538 2 -3 +0.3666666666666831 2 -3 +1.100000000000015 2 -3 +1.833333333333345 2 -3 +2.566666666666677 2 -3 +3.300000000000008 2 -3 +4.033333333333339 2 -3 +4.766666666666669 2 -3 +1 18 0 2 +144 +145 +-5.5 2 -1.666666666666667 +-5.5 2 -2.333333333333336 +1 19 0 31 +146 +147 +148 +149 +150 +151 +152 +153 +154 +155 +156 +157 +158 +159 +160 +161 +162 +163 +164 +165 +166 +167 +168 +169 +170 +171 +172 +173 +174 +175 +176 +-7.463885450041477 0.7351285524717031 0 +-7.355889603024229 1.463177415120959 0 +-7.177052517991568 2.177135079408464 0 +-6.929096493834653 2.870125742738169 0 +-6.614409482612666 3.535475526194976 0 +-6.236022092269094 4.16677674764701 0 +-5.797578400220534 4.757949631227333 0 +-5.303300858899114 5.3033008588991 0 +-4.75794963122735 5.79757840022052 0 +-4.166776747647029 6.236022092269081 0 +-3.535475526194998 6.614409482612655 0 +-2.870125742738189 6.929096493834644 0 +-2.177135079408485 7.177052517991561 0 +-1.463177415120982 7.355889603024224 0 +-0.7351285524717257 7.463885450041475 0 +-2.210857636287394e-14 7.5 0 +0.7351285524716783 7.463885450041479 0 +1.46317741512094 7.355889603024233 0 +2.177135079408449 7.177052517991572 0 +2.870125742738157 6.929096493834657 0 +3.535475526194968 6.61440948261267 0 +4.166776747647006 6.236022092269096 0 +4.757949631227335 5.797578400220533 0 +5.303300858899101 5.303300858899112 0 +5.797578400220523 4.757949631227346 0 +6.236022092269086 4.166776747647021 0 +6.614409482612662 3.535475526194984 0 +6.929096493834651 2.870125742738174 0 +7.177052517991568 2.177135079408465 0 +7.355889603024228 1.463177415120961 0 +7.463885450041477 0.7351285524717029 0 +1 20 0 1 +177 +-7.5 0 -0.5000000000000006 +1 21 0 2 +178 +179 +-7.5 0 -1.666666666666667 +-7.5 0 -2.333333333333336 +1 22 0 4 +180 +181 +182 +183 +7.402113032590307 -2.618033988749894 0 +7.118033988749896 -3.175570504584945 0 +6.675570504584948 -3.618033988749894 0 +6.118033988749896 -3.902113032590307 0 +1 23 0 3 +184 +185 +186 +5.5 -4 -0.75 +5.5 -4 -1.5 +5.5 -4 -2.25 +1 24 0 14 +187 +188 +189 +190 +191 +192 +193 +194 +195 +196 +197 +198 +199 +200 +4.766666666666666 -4 0 +4.033333333333331 -4 0 +3.299999999999997 -4 0 +2.566666666666663 -4 0 +1.833333333333327 -4 0 +1.09999999999999 -4 0 +0.3666666666666538 -4 0 +-0.3666666666666831 -4 0 +-1.100000000000015 -4 0 +-1.833333333333345 -4 0 +-2.566666666666677 -4 0 +-3.300000000000008 -4 0 +-4.033333333333339 -4 0 +-4.766666666666669 -4 0 +1 25 0 3 +201 +202 +203 +-5.5 -4 -0.75 +-5.5 -4 -1.5 +-5.5 -4 -2.25 +1 26 0 4 +204 +205 +206 +207 +-6.118033988749894 -3.902113032590307 0 +-6.675570504584945 -3.618033988749896 0 +-7.118033988749894 -3.175570504584948 0 +-7.402113032590307 -2.618033988749896 0 +1 27 0 3 +208 +209 +210 +-7.5 -2 -0.75 +-7.5 -2 -1.5 +-7.5 -2 -2.25 +1 28 0 2 +211 +212 +-7.5 -1.333333333333333 0 +-7.5 -0.6666666666666643 0 +1 29 0 30 +213 +214 +215 +216 +217 +218 +219 +220 +221 +222 +223 +224 +225 +226 +227 +228 +229 +230 +231 +232 +233 +234 +235 +236 +237 +238 +239 +240 +241 +242 +7.5 -2 0.7419354838709664 +7.5 -2 1.483870967741933 +7.5 -2 2.225806451612899 +7.5 -2 2.967741935483865 +7.5 -2 3.709677419354832 +7.5 -2 4.451612903225799 +7.5 -2 5.193548387096767 +7.5 -2 5.935483870967734 +7.5 -2 6.677419354838699 +7.5 -2 7.419354838709663 +7.5 -2 8.161290322580628 +7.5 -2 8.903225806451593 +7.5 -2 9.645161290322557 +7.5 -2 10.38709677419352 +7.5 -2 11.12903225806449 +7.5 -2 11.87096774193545 +7.5 -2 12.61290322580642 +7.5 -2 13.35483870967739 +7.5 -2 14.09677419354836 +7.5 -2 14.83870967741933 +7.5 -2 15.5806451612903 +7.5 -2 16.32258064516127 +7.5 -2 17.06451612903224 +7.5 -2 17.80645161290321 +7.5 -2 18.54838709677418 +7.5 -2 19.29032258064515 +7.5 -2 20.03225806451612 +7.5 -2 20.77419354838709 +7.5 -2 21.51612903225806 +7.5 -2 22.25806451612903 +1 30 0 4 +243 +244 +245 +246 +6.118033988749894 -3.902113032590307 23 +6.675570504584945 -3.618033988749896 23 +7.118033988749894 -3.175570504584948 23 +7.402113032590307 -2.618033988749896 23 +1 31 0 30 +247 +248 +249 +250 +251 +252 +253 +254 +255 +256 +257 +258 +259 +260 +261 +262 +263 +264 +265 +266 +267 +268 +269 +270 +271 +272 +273 +274 +275 +276 +5.5 -4 0.7419354838709664 +5.5 -4 1.483870967741933 +5.5 -4 2.225806451612899 +5.5 -4 2.967741935483865 +5.5 -4 3.709677419354832 +5.5 -4 4.451612903225799 +5.5 -4 5.193548387096767 +5.5 -4 5.935483870967734 +5.5 -4 6.677419354838699 +5.5 -4 7.419354838709663 +5.5 -4 8.161290322580628 +5.5 -4 8.903225806451593 +5.5 -4 9.645161290322557 +5.5 -4 10.38709677419352 +5.5 -4 11.12903225806449 +5.5 -4 11.87096774193545 +5.5 -4 12.61290322580642 +5.5 -4 13.35483870967739 +5.5 -4 14.09677419354836 +5.5 -4 14.83870967741933 +5.5 -4 15.5806451612903 +5.5 -4 16.32258064516127 +5.5 -4 17.06451612903224 +5.5 -4 17.80645161290321 +5.5 -4 18.54838709677418 +5.5 -4 19.29032258064515 +5.5 -4 20.03225806451612 +5.5 -4 20.77419354838709 +5.5 -4 21.51612903225806 +5.5 -4 22.25806451612903 +1 32 0 14 +277 +278 +279 +280 +281 +282 +283 +284 +285 +286 +287 +288 +289 +290 +-4.766666666666666 -4 23 +-4.033333333333331 -4 23 +-3.299999999999997 -4 23 +-2.566666666666663 -4 23 +-1.833333333333327 -4 23 +-1.09999999999999 -4 23 +-0.3666666666666538 -4 23 +0.3666666666666831 -4 23 +1.100000000000015 -4 23 +1.833333333333345 -4 23 +2.566666666666677 -4 23 +3.300000000000008 -4 23 +4.033333333333339 -4 23 +4.766666666666669 -4 23 +1 33 0 30 +291 +292 +293 +294 +295 +296 +297 +298 +299 +300 +301 +302 +303 +304 +305 +306 +307 +308 +309 +310 +311 +312 +313 +314 +315 +316 +317 +318 +319 +320 +-5.5 -4 0.7419354838709664 +-5.5 -4 1.483870967741933 +-5.5 -4 2.225806451612899 +-5.5 -4 2.967741935483865 +-5.5 -4 3.709677419354832 +-5.5 -4 4.451612903225799 +-5.5 -4 5.193548387096767 +-5.5 -4 5.935483870967734 +-5.5 -4 6.677419354838699 +-5.5 -4 7.419354838709663 +-5.5 -4 8.161290322580628 +-5.5 -4 8.903225806451593 +-5.5 -4 9.645161290322557 +-5.5 -4 10.38709677419352 +-5.5 -4 11.12903225806449 +-5.5 -4 11.87096774193545 +-5.5 -4 12.61290322580642 +-5.5 -4 13.35483870967739 +-5.5 -4 14.09677419354836 +-5.5 -4 14.83870967741933 +-5.5 -4 15.5806451612903 +-5.5 -4 16.32258064516127 +-5.5 -4 17.06451612903224 +-5.5 -4 17.80645161290321 +-5.5 -4 18.54838709677418 +-5.5 -4 19.29032258064515 +-5.5 -4 20.03225806451612 +-5.5 -4 20.77419354838709 +-5.5 -4 21.51612903225806 +-5.5 -4 22.25806451612903 +1 34 0 4 +321 +322 +323 +324 +-7.402113032590307 -2.618033988749894 23 +-7.118033988749896 -3.175570504584945 23 +-6.675570504584948 -3.618033988749894 23 +-6.118033988749896 -3.902113032590307 23 +1 35 0 30 +325 +326 +327 +328 +329 +330 +331 +332 +333 +334 +335 +336 +337 +338 +339 +340 +341 +342 +343 +344 +345 +346 +347 +348 +349 +350 +351 +352 +353 +354 +-7.5 -2 0.7419354838709664 +-7.5 -2 1.483870967741933 +-7.5 -2 2.225806451612899 +-7.5 -2 2.967741935483865 +-7.5 -2 3.709677419354832 +-7.5 -2 4.451612903225799 +-7.5 -2 5.193548387096767 +-7.5 -2 5.935483870967734 +-7.5 -2 6.677419354838699 +-7.5 -2 7.419354838709663 +-7.5 -2 8.161290322580628 +-7.5 -2 8.903225806451593 +-7.5 -2 9.645161290322557 +-7.5 -2 10.38709677419352 +-7.5 -2 11.12903225806449 +-7.5 -2 11.87096774193545 +-7.5 -2 12.61290322580642 +-7.5 -2 13.35483870967739 +-7.5 -2 14.09677419354836 +-7.5 -2 14.83870967741933 +-7.5 -2 15.5806451612903 +-7.5 -2 16.32258064516127 +-7.5 -2 17.06451612903224 +-7.5 -2 17.80645161290321 +-7.5 -2 18.54838709677418 +-7.5 -2 19.29032258064515 +-7.5 -2 20.03225806451612 +-7.5 -2 20.77419354838709 +-7.5 -2 21.51612903225806 +-7.5 -2 22.25806451612903 +1 36 0 2 +355 +356 +-7.5 -0.6666666666666667 23 +-7.5 -1.333333333333336 23 +1 37 0 30 +357 +358 +359 +360 +361 +362 +363 +364 +365 +366 +367 +368 +369 +370 +371 +372 +373 +374 +375 +376 +377 +378 +379 +380 +381 +382 +383 +384 +385 +386 +-7.5 0 0.7419354838709664 +-7.5 0 1.483870967741933 +-7.5 0 2.225806451612899 +-7.5 0 2.967741935483865 +-7.5 0 3.709677419354832 +-7.5 0 4.451612903225799 +-7.5 0 5.193548387096767 +-7.5 0 5.935483870967734 +-7.5 0 6.677419354838699 +-7.5 0 7.419354838709663 +-7.5 0 8.161290322580628 +-7.5 0 8.903225806451593 +-7.5 0 9.645161290322557 +-7.5 0 10.38709677419352 +-7.5 0 11.12903225806449 +-7.5 0 11.87096774193545 +-7.5 0 12.61290322580642 +-7.5 0 13.35483870967739 +-7.5 0 14.09677419354836 +-7.5 0 14.83870967741933 +-7.5 0 15.5806451612903 +-7.5 0 16.32258064516127 +-7.5 0 17.06451612903224 +-7.5 0 17.80645161290321 +-7.5 0 18.54838709677418 +-7.5 0 19.29032258064515 +-7.5 0 20.03225806451612 +-7.5 0 20.77419354838709 +-7.5 0 21.51612903225806 +-7.5 0 22.25806451612903 +1 38 0 31 +387 +388 +389 +390 +391 +392 +393 +394 +395 +396 +397 +398 +399 +400 +401 +402 +403 +404 +405 +406 +407 +408 +409 +410 +411 +412 +413 +414 +415 +416 +417 +7.463885450041477 0.7351285524717049 23 +7.355889603024229 1.463177415120961 23 +7.177052517991567 2.177135079408465 23 +6.929096493834652 2.87012574273817 23 +6.614409482612665 3.535475526194979 23 +6.236022092269093 4.166776747647012 23 +5.797578400220532 4.757949631227336 23 +5.303300858899112 5.303300858899101 23 +4.757949631227348 5.79757840022052 23 +4.166776747647027 6.236022092269082 23 +3.535475526194993 6.614409482612657 23 +2.870125742738187 6.929096493834645 23 +2.177135079408481 7.177052517991563 23 +1.463177415120977 7.355889603024225 23 +0.7351285524717206 7.463885450041476 23 +1.694093709027744e-14 7.5 23 +-0.7351285524716834 7.463885450041479 23 +-1.463177415120942 7.355889603024233 23 +-2.177135079408448 7.177052517991572 23 +-2.870125742738157 6.929096493834657 23 +-3.535475526194967 6.614409482612671 23 +-4.166776747647005 6.236022092269097 23 +-4.757949631227329 5.797578400220538 23 +-5.303300858899095 5.303300858899117 23 +-5.79757840022052 4.757949631227349 23 +-6.236022092269083 4.166776747647026 23 +-6.614409482612659 3.535475526194988 23 +-6.929096493834649 2.870125742738178 23 +-7.177052517991566 2.177135079408469 23 +-7.355889603024227 1.463177415120966 23 +-7.463885450041476 0.7351285524717044 23 +1 39 0 30 +418 +419 +420 +421 +422 +423 +424 +425 +426 +427 +428 +429 +430 +431 +432 +433 +434 +435 +436 +437 +438 +439 +440 +441 +442 +443 +444 +445 +446 +447 +7.5 1.83697019872103e-15 0.7419354838709664 +7.5 1.83697019872103e-15 1.483870967741933 +7.5 1.83697019872103e-15 2.225806451612899 +7.5 1.83697019872103e-15 2.967741935483865 +7.5 1.83697019872103e-15 3.709677419354832 +7.5 1.83697019872103e-15 4.451612903225799 +7.5 1.83697019872103e-15 5.193548387096767 +7.5 1.83697019872103e-15 5.935483870967734 +7.5 1.83697019872103e-15 6.677419354838699 +7.5 1.83697019872103e-15 7.419354838709663 +7.5 1.83697019872103e-15 8.161290322580628 +7.5 1.83697019872103e-15 8.903225806451593 +7.5 1.83697019872103e-15 9.645161290322557 +7.5 1.83697019872103e-15 10.38709677419352 +7.5 1.83697019872103e-15 11.12903225806449 +7.5 1.83697019872103e-15 11.87096774193545 +7.5 1.83697019872103e-15 12.61290322580642 +7.5 1.83697019872103e-15 13.35483870967739 +7.5 1.83697019872103e-15 14.09677419354836 +7.5 1.83697019872103e-15 14.83870967741933 +7.5 1.83697019872103e-15 15.5806451612903 +7.5 1.83697019872103e-15 16.32258064516127 +7.5 1.83697019872103e-15 17.06451612903224 +7.5 1.83697019872103e-15 17.80645161290321 +7.5 1.83697019872103e-15 18.54838709677418 +7.5 1.83697019872103e-15 19.29032258064515 +7.5 1.83697019872103e-15 20.03225806451612 +7.5 1.83697019872103e-15 20.77419354838709 +7.5 1.83697019872103e-15 21.51612903225806 +7.5 1.83697019872103e-15 22.25806451612903 +1 40 0 2 +448 +449 +7.5 -1.333333333333333 23 +7.5 -0.6666666666666634 23 +1 41 0 14 +450 +451 +452 +453 +454 +455 +456 +457 +458 +459 +460 +461 +462 +463 +-4.766666666666666 -2 21.5 +-4.033333333333331 -2 21.5 +-3.299999999999997 -2 21.5 +-2.566666666666663 -2 21.5 +-1.833333333333327 -2 21.5 +-1.09999999999999 -1.999999999999999 21.5 +-0.3666666666666538 -1.999999999999999 21.5 +0.3666666666666831 -1.999999999999999 21.5 +1.100000000000015 -1.999999999999999 21.5 +1.833333333333345 -1.999999999999999 21.5 +2.566666666666677 -1.999999999999999 21.5 +3.300000000000008 -1.999999999999999 21.5 +4.033333333333339 -1.999999999999999 21.5 +4.766666666666669 -1.999999999999999 21.5 +1 42 0 26 +464 +465 +466 +467 +468 +469 +470 +471 +472 +473 +474 +475 +476 +477 +478 +479 +480 +481 +482 +483 +484 +485 +486 +487 +488 +489 +5.5 -2 20.75925925925926 +5.5 -2 20.01851851851852 +5.5 -2 19.27777777777778 +5.5 -2 18.53703703703704 +5.5 -2 17.7962962962963 +5.5 -2 17.05555555555556 +5.5 -2 16.31481481481482 +5.5 -2 15.57407407407408 +5.5 -2 14.83333333333334 +5.5 -2 14.09259259259261 +5.5 -2 13.35185185185187 +5.5 -2 12.61111111111113 +5.5 -2 11.87037037037039 +5.5 -2 11.12962962962965 +5.5 -2 10.38888888888892 +5.5 -2 9.648148148148179 +5.5 -2 8.907407407407437 +5.5 -2 8.166666666666694 +5.5 -2 7.425925925925949 +5.5 -2 6.685185185185206 +5.5 -2 5.944444444444462 +5.5 -2 5.203703703703717 +5.5 -2 4.462962962962973 +5.5 -2 3.722222222222232 +5.5 -2 2.981481481481485 +5.5 -2 2.240740740740744 +1 43 0 14 +490 +491 +492 +493 +494 +495 +496 +497 +498 +499 +500 +501 +502 +503 +4.766666666666666 -1.999999999999999 1.5 +4.03333333333333 -1.999999999999999 1.5 +3.299999999999997 -1.999999999999999 1.5 +2.566666666666663 -1.999999999999999 1.5 +1.833333333333327 -1.999999999999999 1.5 +1.09999999999999 -1.999999999999999 1.5 +0.3666666666666538 -1.999999999999999 1.5 +-0.3666666666666831 -1.999999999999999 1.5 +-1.100000000000015 -1.999999999999999 1.5 +-1.833333333333345 -2 1.5 +-2.566666666666676 -2 1.5 +-3.300000000000007 -2 1.5 +-4.033333333333339 -2 1.5 +-4.766666666666669 -2 1.5 +1 44 0 26 +504 +505 +506 +507 +508 +509 +510 +511 +512 +513 +514 +515 +516 +517 +518 +519 +520 +521 +522 +523 +524 +525 +526 +527 +528 +529 +-5.5 -2 20.75925925925926 +-5.5 -2 20.01851851851852 +-5.5 -2 19.27777777777778 +-5.5 -2 18.53703703703704 +-5.5 -2 17.7962962962963 +-5.5 -2 17.05555555555556 +-5.5 -2 16.31481481481482 +-5.5 -2 15.57407407407408 +-5.5 -2 14.83333333333334 +-5.5 -2 14.09259259259261 +-5.5 -2 13.35185185185187 +-5.5 -2 12.61111111111113 +-5.5 -2 11.87037037037039 +-5.5 -2 11.12962962962965 +-5.5 -2 10.38888888888892 +-5.5 -2 9.648148148148179 +-5.5 -2 8.907407407407437 +-5.5 -2 8.166666666666694 +-5.5 -2 7.425925925925949 +-5.5 -2 6.685185185185206 +-5.5 -2 5.944444444444462 +-5.5 -2 5.203703703703717 +-5.5 -2 4.462962962962973 +-5.5 -2 3.722222222222232 +-5.5 -2 2.981481481481485 +-5.5 -2 2.240740740740744 +1 45 0 2 +530 +531 +5.5 -1.333333333333333 21.5 +5.5 -0.6666666666666636 21.5 +1 46 0 26 +532 +533 +534 +535 +536 +537 +538 +539 +540 +541 +542 +543 +544 +545 +546 +547 +548 +549 +550 +551 +552 +553 +554 +555 +556 +557 +5.5 7.12393107467807e-16 20.75925925925926 +5.5 7.12393107467807e-16 20.01851851851852 +5.5 7.12393107467807e-16 19.27777777777778 +5.5 7.12393107467807e-16 18.53703703703704 +5.5 7.12393107467807e-16 17.7962962962963 +5.5 7.12393107467807e-16 17.05555555555556 +5.5 7.12393107467807e-16 16.31481481481482 +5.5 7.12393107467807e-16 15.57407407407408 +5.5 7.12393107467807e-16 14.83333333333334 +5.5 7.12393107467807e-16 14.09259259259261 +5.5 7.12393107467807e-16 13.35185185185187 +5.5 7.12393107467807e-16 12.61111111111113 +5.5 7.12393107467807e-16 11.87037037037039 +5.5 7.12393107467807e-16 11.12962962962965 +5.5 7.12393107467807e-16 10.38888888888892 +5.5 7.12393107467807e-16 9.648148148148179 +5.5 7.12393107467807e-16 8.907407407407437 +5.5 7.12393107467807e-16 8.166666666666694 +5.5 7.12393107467807e-16 7.425925925925949 +5.5 7.12393107467807e-16 6.685185185185206 +5.5 7.12393107467807e-16 5.944444444444462 +5.5 7.12393107467807e-16 5.203703703703717 +5.5 7.12393107467807e-16 4.462962962962973 +5.5 7.12393107467807e-16 3.722222222222232 +5.5 7.12393107467807e-16 2.981481481481485 +5.5 7.12393107467807e-16 2.240740740740744 +1 47 0 2 +558 +559 +5.5 -0.6666666666666661 1.5 +5.5 -1.333333333333335 1.5 +1 48 0 23 +560 +561 +562 +563 +564 +565 +566 +567 +568 +569 +570 +571 +572 +573 +574 +575 +576 +577 +578 +579 +580 +581 +582 +-5.452946737555957 0.7178940572102817 1.5 +-5.312592044589876 1.423504748063861 1.5 +-5.081337428812079 2.10475887800799 1.5 +-4.763139720814415 2.749999999999996 1.5 +-4.363443371601798 3.348187859547957 1.5 +-3.889087296526017 3.889087296526005 1.5 +-3.348187859547973 4.363443371601787 1.5 +-2.750000000000011 4.763139720814406 1.5 +-2.104758878008007 5.081337428812073 1.5 +-1.423504748063874 5.312592044589874 1.5 +-0.7178940572102942 5.452946737555956 1.5 +-1.149265596607264e-14 5.5 1.5 +0.7178940572102764 5.452946737555958 1.5 +1.423504748063856 5.312592044589877 1.5 +2.104758878007985 5.081337428812081 1.5 +2.749999999999996 4.763139720814415 1.5 +3.348187859547959 4.363443371601797 1.5 +3.889087296526007 3.889087296526017 1.5 +4.363443371601792 3.348187859547965 1.5 +4.763139720814412 2.750000000000003 1.5 +5.081337428812076 2.104758878007998 1.5 +5.312592044589875 1.423504748063865 1.5 +5.452946737555957 0.717894057210285 1.5 +1 49 0 26 +583 +584 +585 +586 +587 +588 +589 +590 +591 +592 +593 +594 +595 +596 +597 +598 +599 +600 +601 +602 +603 +604 +605 +606 +607 +608 +-5.5 -7.12393107467807e-16 20.75925925925926 +-5.5 -7.12393107467807e-16 20.01851851851852 +-5.5 -7.12393107467807e-16 19.27777777777778 +-5.5 -7.12393107467807e-16 18.53703703703704 +-5.5 -7.12393107467807e-16 17.7962962962963 +-5.5 -7.12393107467807e-16 17.05555555555556 +-5.5 -7.12393107467807e-16 16.31481481481482 +-5.5 -7.12393107467807e-16 15.57407407407408 +-5.5 -7.12393107467807e-16 14.83333333333334 +-5.5 -7.12393107467807e-16 14.09259259259261 +-5.5 -7.12393107467807e-16 13.35185185185187 +-5.5 -7.12393107467807e-16 12.61111111111113 +-5.5 -7.12393107467807e-16 11.87037037037039 +-5.5 -7.12393107467807e-16 11.12962962962965 +-5.5 -7.12393107467807e-16 10.38888888888892 +-5.5 -7.12393107467807e-16 9.648148148148179 +-5.5 -7.12393107467807e-16 8.907407407407437 +-5.5 -7.12393107467807e-16 8.166666666666694 +-5.5 -7.12393107467807e-16 7.425925925925949 +-5.5 -7.12393107467807e-16 6.685185185185206 +-5.5 -7.12393107467807e-16 5.944444444444462 +-5.5 -7.12393107467807e-16 5.203703703703717 +-5.5 -7.12393107467807e-16 4.462962962962973 +-5.5 -7.12393107467807e-16 3.722222222222232 +-5.5 -7.12393107467807e-16 2.981481481481485 +-5.5 -7.12393107467807e-16 2.240740740740744 +1 50 0 23 +609 +610 +611 +612 +613 +614 +615 +616 +617 +618 +619 +620 +621 +622 +623 +624 +625 +626 +627 +628 +629 +630 +631 +5.452946737555957 0.7178940572102832 21.5 +5.312592044589876 1.423504748063863 21.5 +5.081337428812079 2.104758878007992 21.5 +4.763139720814414 2.749999999999997 21.5 +4.363443371601797 3.34818785954796 21.5 +3.889087296526017 3.889087296526006 21.5 +3.348187859547972 4.363443371601787 21.5 +2.750000000000011 4.763139720814406 21.5 +2.104758878008006 5.081337428812073 21.5 +1.423504748063875 5.312592044589873 21.5 +0.7178940572102948 5.452946737555956 21.5 +1.06155815836224e-14 5.5 21.5 +-0.7178940572102747 5.452946737555958 21.5 +-1.423504748063856 5.312592044589878 21.5 +-2.104758878007986 5.081337428812081 21.5 +-2.749999999999995 4.763139720814415 21.5 +-3.348187859547957 4.363443371601799 21.5 +-3.889087296526008 3.889087296526015 21.5 +-4.36344337160179 3.348187859547968 21.5 +-4.763139720814412 2.750000000000001 21.5 +-5.081337428812076 2.104758878007996 21.5 +-5.312592044589874 1.423504748063867 21.5 +-5.452946737555957 0.717894057210283 21.5 +1 51 0 2 +632 +633 +-5.5 -0.6666666666666672 21.5 +-5.5 -1.333333333333336 21.5 +1 52 0 2 +634 +635 +-5.5 -1.333333333333333 1.5 +-5.5 -0.6666666666666646 1.5 +2 1 0 13 +636 +637 +638 +639 +640 +641 +642 +643 +644 +645 +646 +647 +648 +7.372361564270609 0.703037817362708 -2.557409122322194 +6.062974428786783 1.919129957176479 -2.074483971780935 +5.974820864364867 1.942818866174559 -2.569737309298218 +6.203037817362705 1.872361564270609 -1.442590877677806 +7.419129957176478 0.5629744287867847 -1.925516028219067 +7.442818866174559 0.4748208643648708 -1.430262690701784 +7.008444328569765 1.313238633153057 -2.511013000594855 +7.205487705975489 1.044658645092483 -2.076823996122759 +6.813238633153054 1.508444328569768 -1.488986999405145 +6.544658645092479 1.705487705975492 -1.923176003877242 +6.914213562373093 1.414213562373096 -2 +6.497684542345019 1.733385575677209 -2.438628149419134 +7.233385575677207 0.9976845423450225 -1.561371850580867 +2 2 0 126 +649 +650 +651 +652 +653 +654 +655 +656 +657 +658 +659 +660 +661 +662 +663 +664 +665 +666 +667 +668 +669 +670 +671 +672 +673 +674 +675 +676 +677 +678 +679 +680 +681 +682 +683 +684 +685 +686 +687 +688 +689 +690 +691 +692 +693 +694 +695 +696 +697 +698 +699 +700 +701 +702 +703 +704 +705 +706 +707 +708 +709 +710 +711 +712 +713 +714 +715 +716 +717 +718 +719 +720 +721 +722 +723 +724 +725 +726 +727 +728 +729 +730 +731 +732 +733 +734 +735 +736 +737 +738 +739 +740 +741 +742 +743 +744 +745 +746 +747 +748 +749 +750 +751 +752 +753 +754 +755 +756 +757 +758 +759 +760 +761 +762 +763 +764 +765 +766 +767 +768 +769 +770 +771 +772 +773 +774 +0.03505865087212071 4.609150865947603 -1 +-2.501624799696178 4.446335129256431 -1 +2.5016247996962 4.446335129256427 -1 +-4.172911941791438 3.842110967216025 -1 +4.172911941791456 3.84211096721602 -1 +-1.202043938873667 5.691265685569718 -1 +1.236957332086196 5.695588525831354 -1 +1.058669260987386 3.584360259595467 -1 +-1.088556488364478 3.585273192249623 -1 +-0.0100606488249352 6.104415656559221 -1 +-5.292274469060259 3.312403472503033 -1 +5.292274469060271 3.312403472503032 -1 +-3.622278015302317 5.038859425431511 -1 +3.622278015302336 5.038859425431506 -1 +-3.022738241169594 3.243944463694708 -1 +3.022738241169614 3.243944463694705 -1 +-2.524447752956972 5.812857020260289 -1 +2.524447752956998 5.812857020260285 -1 +-0.02930754182265814 3.136439048843455 -1 +1.078951708155158 4.63211364004736 -1 +-1.154323809763335 4.577666133172865 -1 +1.982364718295035 3.005049399401134 -1 +-1.982364718295013 3.005049399401136 -1 +-4.436942483639164 3.13053913730825 -1 +4.436942483639178 3.130539137308248 -1 +-4.355380657549508 4.866055984633681 -1 +4.355380657549514 4.866055984633682 -1 +0.8402823110303291 6.512234512432515 -1 +-0.8870953745181374 6.528554889109961 -1 +-6.241133244564612 2.917106529712296 -1 +6.241133244564613 2.917106529712299 -1 +-3.292370977186514 3.97684786739966 -1 +3.292370977186531 3.976847867399655 -1 +-5.167873869473682 4.139138503879601 -1 +5.167873869473691 4.139138503879593 -1 +-1.952452363848747 6.333201785004642 -1 +1.952452363848775 6.333201785004639 -1 +0.5555807246089688 5.457292173744125 -1 +-0.5679628544904346 5.438203850443683 -1 +-0.2407134026673516 3.940362842233456 -1 +0.7833842963483698 2.790392365586603 -1 +-0.7833842963483433 2.790392365586604 -1 +-2.161838545971838 5.113774690603821 -1 +2.161838545971864 5.113774690603819 -1 +1.878628335545001 3.729722346261763 -1 +-1.893388281144333 3.726768543898265 -1 +3.709568945936922 2.670220156564124 -1 +-3.709568945936909 2.670220156564124 -1 +3.388105033561547 5.817999655419747 -1 +-3.388105033561517 5.817999655419747 -1 +0.6100048481499574 4.17984035251461 -1 +5.133333333333336 2.595538899591845 -1 +-5.133333333333333 2.595538899591844 -1 +-2.905056344763209 5.149263640429685 -1 +2.905056344763232 5.149263640429682 -1 +-0.336306588922278 6.896278045986016 -1 +-4.173850510609437 5.500035986678148 -1 +4.173850510609437 5.500035986678153 -1 +2.580258158590996 2.713053460853803 -1 +-2.580258158590976 2.713053460853804 -1 +1.446959627841168 2.597596440655514 -1 +-1.446959627841143 2.597596440655516 -1 +-5.941842911631469 3.470233642642442 -1 +5.94184291163147 3.470233642642445 -1 +-2.53896154012788 3.768190452622925 -1 +2.538961540127899 3.76819045262292 -1 +-1.751133316517143 4.516067926204958 -1 +1.736901449556263 4.513211944883674 -1 +6.501527236941858 2.301620294731356 -1 +-6.501527236941858 2.301620294731354 -1 +-3.674201758929283 3.40450792595308 -1 +3.674201758929301 3.404507925953077 -1 +-3.907492423088643 4.446370722676175 -1 +3.907492423088655 4.446370722676168 -1 +-4.748779140944819 3.694170961867131 -1 +4.748779140944834 3.694170961867127 -1 +2.936127073411969 6.29802045838076 -1 +-2.936127073411947 6.298020458380752 -1 +1.448426615055329 6.743971965104199 -1 +0.3726074823209543 6.914843465334603 -1 +-0.001525798720449491 2.512919819900927 -1 +-1.474123433208115 6.763879418721035 -1 +0.4682606036155748 3.503796427924334 -1 +4.997996537428772 4.749823595197786 -1 +-4.997996537428774 4.749823595197782 -1 +-1.761195012023612 5.718261272211842 -1 +1.759589980762042 5.717742204126543 -1 +-0.5311043762449092 3.385709036259671 -1 +-0.8080179187709376 5.941505392821154 -1 +-0.8529980960500581 4.12010038616077 -1 +1.302284131992622 4.126409680441682 -1 +0.8196652207923156 5.933954299202518 -1 +-1.306621312287824 5.130152088677075 -1 +1.297011189498104 5.143614756953036 -1 +0.5951953147052756 4.884206753597486 -1 +-4.55840576171281 4.289611789245066 -1 +4.55840576171282 4.289611789245062 -1 +-0.5741817184580422 4.764813783071941 -1 +5.842773247174545 2.425967636989942 -1 +-5.842773247174542 2.425967636989942 -1 +1.430001247803392 3.141424162300096 -1 +-1.438930682398662 3.141015988358229 -1 +3.096847280591052 2.523265088954511 -1 +-3.096847280591034 2.523265088954512 -1 +2.081653286053768 2.49355995964653 -1 +-2.081653286053747 2.493559959646531 -1 +4.75261297836889 5.24370036209436 -1 +-4.752612978368908 5.243700362094351 -1 +-2.492057602472868 6.510045655094378 -1 +2.49205760247287 6.510045655094383 -1 +-5.700054192033488 4.029150427097086 -1 +5.700054192033491 4.02915042709709 -1 +-0.00141185679361195 5.256425445758585 -1 +-1.34807999836787 4.105175236337296 -1 +2.470880121077991 3.241249810427431 -1 +-2.47088012107797 3.241249810427435 -1 +4.41140639470135 2.450576573711224 -1 +-4.411406394701343 2.450576573711224 -1 +-1.339988427016649 6.181547687194207 -1 +-1.024905923239255 7.02527433097513 -1 +-3.239044222578666 4.638092368255486 -1 +3.239044222578684 4.638092368255482 -1 +1.006601268170954 7.012247126988391 -1 +1.342895637262498 6.156115548616961 -1 +-5.690271441152843 2.944250036287912 -1 +5.690271441152848 2.944250036287912 -1 +2 3 0 13 +775 +776 +777 +778 +779 +780 +781 +782 +783 +784 +785 +786 +787 +7.5 -0.9423115287880405 -0.914660501966107 +7.5 -0.9917871638762032 -1.986491628614919 +7.5 -0.610288212065118 -1.377187280356543 +7.5 -0.4788060397319973 -0.7495473245812077 +7.5 -1.370298505186782 -1.289108322753888 +7.5 -0.5242438976266968 -2.4715403412179 +7.5 -1.429917946194454 -0.5684099562974805 +7.5 -1.420611347119692 -2.406284160402689 +7.5 -0.8864395735757998 -0.4410862554871237 +7.5 -0.4429054834289495 -1.934782404621852 +7.5 -0.4063824559948918 -0.3381267160136663 +7.5 -1.569365488527112 -1.897272706136246 +7.5 -1 -2.655288294277351 +2 4 0 206 +788 +789 +790 +791 +792 +793 +794 +795 +796 +797 +798 +799 +800 +801 +802 +803 +804 +805 +806 +807 +808 +809 +810 +811 +812 +813 +814 +815 +816 +817 +818 +819 +820 +821 +822 +823 +824 +825 +826 +827 +828 +829 +830 +831 +832 +833 +834 +835 +836 +837 +838 +839 +840 +841 +842 +843 +844 +845 +846 +847 +848 +849 +850 +851 +852 +853 +854 +855 +856 +857 +858 +859 +860 +861 +862 +863 +864 +865 +866 +867 +868 +869 +870 +871 +872 +873 +874 +875 +876 +877 +878 +879 +880 +881 +882 +883 +884 +885 +886 +887 +888 +889 +890 +891 +892 +893 +894 +895 +896 +897 +898 +899 +900 +901 +902 +903 +904 +905 +906 +907 +908 +909 +910 +911 +912 +913 +914 +915 +916 +917 +918 +919 +920 +921 +922 +923 +924 +925 +926 +927 +928 +929 +930 +931 +932 +933 +934 +935 +936 +937 +938 +939 +940 +941 +942 +943 +944 +945 +946 +947 +948 +949 +950 +951 +952 +953 +954 +955 +956 +957 +958 +959 +960 +961 +962 +963 +964 +965 +966 +967 +968 +969 +970 +971 +972 +973 +974 +975 +976 +977 +978 +979 +980 +981 +982 +983 +984 +985 +986 +987 +988 +989 +990 +991 +992 +993 +-4.490990060568561 -1.01096867539982 -3 +4.496543123147978 -0.9812009451514618 -3 +1.466627355311597 -1.033370129731211 -3 +-1.520325203252027 -1.029308943089426 -3 +2.900829805437549 0.03558939671398265 -3 +2.995631376884867 -2.120144423703643 -3 +-5.71045336708097 -2.210453367080975 -3 +5.710453367080973 0.210453367080975 -3 +-5.710453367080975 0.2104533670809721 -3 +5.710453367080973 -2.210453367080975 -3 +-0.03816451669721242 0.1405661286850293 -3 +-2.919150558492587 0.04096686014569939 -3 +-0.01564657969659539 -2.154327090185409 -3 +-2.944477559454692 -2.091325527852514 -3 +-1.414515294182717 0.2781440741138594 -3 +1.460651387182441 0.4146702190041791 -3 +1.478207500178645 -2.237057901693317 -3 +-1.534810138215936 -2.265347219503915 -3 +4.336125099972572 0.6031175742357098 -3 +4.336125099972572 -2.603117574235712 -3 +-4.344681103970185 0.6111360552572493 -3 +-4.248495799850036 -2.724585396418762 -3 +6.22689447976946 -1 -3 +-6.226894479769462 -0.9999999999999988 -3 +-0.3328845601831271 -1.009882806112765 -3 +-3.324000643178883 -1.001464448472788 -3 +3.311271887249614 -1.031191169809001 -3 +5.209548426807959 1.058694327312217 -3 +5.20954842680796 -3.058694327312217 -3 +-5.217933733634097 1.059680451966977 -3 +-5.230119951747454 -3.061113569487788 -3 +-6.546303948262691 -1.871030132078887 -3 +6.560722106074002 -0.1371527497838864 -3 +6.546303948262691 -1.871030132078886 -3 +-6.560722106074002 -0.1371527497838879 -3 +2.449909433465544 -2.98489752065294 -3 +2.398698852865245 0.969803420518645 -3 +-2.470219014106676 -2.993177993303406 -3 +-0.5658951625846221 0.9910594298923607 -3 +0.5479854209058819 0.9867374046914037 -3 +-2.426469287918347 0.9848740833875136 -3 +0.5222781348401067 -2.997542713976518 -3 +-0.5721750703030775 -3.004699389751544 -3 +3.434231706304985 1.016855676858413 -3 +3.434231706304983 -3.016855676858413 -3 +-3.445023249782139 1.021756026241085 -3 +-3.460566217880884 -3.028944120904563 -3 +2.619915076516067 -0.6363074908591542 -3 +-6.324255585324116 -2.824255585324122 -3 +6.324255585324117 0.8242555853241225 -3 +6.324255585324121 -2.824255585324121 -3 +-6.324255585324122 0.8242555853241187 -3 +2.023829693601405 -1.758496965664918 -3 +-5.312234061876904 -1.423331743295699 -3 +5.312440406243684 -1.42324417320698 -3 +0.5648148036352356 -0.6268789900064209 -3 +-2.599843126460906 -0.575713555483342 -3 +-3.930691048280525 -1.767485921988246 -3 +-2.144427011880061 -1.803248819066047 -3 +-3.877637659835078 -0.3371731525900638 -3 +0.9284991528807671 -1.76725380011341 -3 +-0.8225578491726474 -0.406252200313223 -3 +3.878548381356305 -1.67101993241647 -3 +3.916856162503809 -0.2523541784304895 -3 +-4.864255170387822 -0.1918203467016579 -3 +4.865639738519281 -0.1938494919548052 -3 +-0.9414165873108425 -1.801397545679857 -3 +4.915059410484685 -2.027980113713078 -3 +-4.915339013131898 -2.027868729075874 -3 +5.5644161228351 -0.6160249062521951 -3 +-5.564280196203864 -0.6159975413150746 -3 +2.176260186461768 0.1756648034676207 -3 +0.7608698234010399 0.1477629271325722 -3 +-1.45466262190963 1.466102332034877 -3 +-2.262857067523765 0.2914122763151246 -3 +1.467511456091872 1.484826520700552 -3 +1.46873341954444 -3.486190385077302 -3 +-1.471471665810243 -3.49002158059371 -3 +1.452383112640675 -0.1393294641027698 -3 +4.522737421335572 1.31039178472315 -3 +4.522737421335572 -3.310391784723151 -3 +5.817854572904197 1.305731566200813 -3 +5.817854572904203 -3.30573156620081 -3 +-5.813202109553972 1.312503603056375 -3 +-4.536877363924834 1.311279069870765 -3 +-5.819493690436831 -3.313373118387564 -3 +-4.596571642211921 -3.368620244872922 -3 +6.91923799055388 -0.999982005300756 -3 +-6.919237990553883 -0.9999820053007553 -3 +2.690902006292422 -1.499533704716916 -3 +-2.720079410546724 -1.359606138484459 -3 +0.2120269237360609 -1.475025335557761 -3 +-1.72106329881354 -0.3797171170571314 -3 +-5.965066116473202 -1.628954389631074 -3 +5.965066088390755 -1.628953729671047 -3 +6.866607520695307 0.3741447299298835 -3 +-6.865136280102314 -2.374979717875064 -3 +6.865136280102314 -2.374979717875063 -3 +-6.866607520695307 0.3741447299298801 -3 +-0.00783078193974077 1.406038664807992 -3 +-0.004480323588583086 -3.407800079273164 -3 +3.657961408188575 0.3403352985424113 -3 +3.658482020205485 -2.342480694251468 -3 +-3.666252304768015 0.3422103226507103 -3 +-3.67469457220533 -2.365930950041825 -3 +-5.041514806262033 0.4000249785052181 -3 +5.037755990545332 0.3970801773352159 -3 +-2.824265497534491 -3.381388815800883 -3 +2.812563292537649 -3.376208767487485 -3 +2.804028195770941 1.373693084131769 -3 +-2.825859975833427 1.382047059903743 -3 +-0.6688188357912916 0.4405193859212144 -3 +0.6020286404347311 -2.330464409102507 -3 +2.367333663384356 -2.330918612308003 -3 +-0.6429193233194034 -2.369512567214042 -3 +-2.317102740565239 -2.469133116755831 -3 +-1.511324951614378 -1.624087267227149 -3 +-0.03690573189950178 0.7629865042963855 -3 +1.473869012143767 -1.594772586119261 -3 +3.925285512189295 1.386073007163455 -3 +3.925285512189291 -3.386073007163455 -3 +-3.930080566337072 1.396070525174573 -3 +3.353196432478426 -0.3934899121505909 -3 +-6.026772495148577 -0.399078037887596 -3 +6.026833176680377 -0.3990902543773817 -3 +-3.307621697328288 -0.3669388850312079 -3 +-3.927793398655238 -3.42442995243925 -3 +-0.03084389772515863 -0.4742841611029076 -3 +-3.358338359503707 -1.61665767490037 -3 +-3.966219227456739 -1.125457154685204 -3 +-0.01270408331187983 -2.738528561180889 -3 +-0.9094321390232728 -1.257122638131127 -3 +3.311059493973609 -1.701363491735122 -3 +-4.494180288629392 -1.600133161672181 -3 +4.497093070056287 -1.598909662383146 -3 +5.676283545281715 0.762293507206796 -3 +5.71335895867896 -2.730258936434045 -3 +-5.725931444945074 -2.731215627943902 -3 +-5.684088936817506 0.76259792809772 -3 +0.9327048256924633 -1.17888469854834 -3 +3.916856162503808 -0.8593383515183757 -3 +7.042981598311711 -1.663318627345587 -3 +-7.042981598311712 -1.663318627345587 -3 +7.04398597633998 -0.3372119237438091 -3 +-7.043985976339981 -0.3372119237438098 -3 +2.020096370965821 -1.186054406614801 -3 +-5.295130266429517 -2.446406160744212 -3 +6.244488362707575 0.2902205896975205 -3 +-6.23018080708591 -2.285863259494347 -3 +6.229635352312356 -2.285821725087247 -3 +-6.244488362707576 0.2902205896975167 -3 +-2.164798258314144 1.458613247184133 -3 +5.285541116022726 -2.445280128902914 -3 +-2.103140545114123 -1.148631617355191 -3 +-2.1710829684388 -3.465536184544409 -3 +-2.948554266957885 -2.72165008744317 -3 +2.953025248797147 -2.695250949210325 -3 +2.895335025838177 0.6519902800388071 -3 +-5.062498481344972 -0.8652457140854749 -3 +5.062498481344972 -0.8652457140854743 -3 +-5.168502659675649 -3.562491248450783 -3 +-5.145579193910075 1.575354612836945 -3 +5.141149890030948 1.58135106221687 -3 +5.141149890030945 -3.581351062216872 -3 +2.163570522492351 -3.460308240033881 -3 +2.166720892158882 1.479988441834819 -3 +0.7333333333333489 1.542758957283881 -3 +-2.924268740719713 0.6772111047739791 -3 +0.7397852786450063 -3.529268582356605 -3 +-0.7333333333333489 -3.556842004829461 -3 +-0.3682786637872205 -1.674019504696152 -3 +-0.7333333333333217 1.558728357491919 -3 +-4.37051329585767 0.0594216401346972 -3 +4.36242795108095 0.05974820200821052 -3 +1.845435081929668 -0.5938455625973476 -3 +-1.849000969260185 -2.932552788175384 -3 +-6.563221787439883 -0.6125111067923471 -3 +6.563226210292052 -0.6125119972070527 -3 +-1.809696165009942 0.8926263986480638 -3 +-6.559989317819739 -1.383020502015534 -3 +6.559989316357715 -1.383020467656932 -3 +-4.42873872992289 -0.4678480163132712 -3 +1.837211900043143 -2.902320904458501 -3 +1.793004642539703 0.9065843620852285 -3 +6.341926061946507 1.318278547896791 -3 +6.341926061946513 -3.318278547896788 -3 +4.43538126449987 -0.4866421780629719 -3 +1.127226010575714 0.9138900651496358 -3 +-6.344341972960913 1.317454662911115 -3 +-6.348560013849138 -3.315778055934412 -3 +1.108040812281012 -2.913807482777458 -3 +-4.252680144419436 -2.097200831839378 -3 +-1.133951750040366 -2.936495925011342 -3 +-1.107820235468587 0.9378633296837153 -3 +4.257061596415067 -2.048701595399975 -3 +4.853802294924703 -2.689092785777414 -3 +4.782377632135187 0.8220623927949045 -3 +-4.790497362325025 0.8265988456002944 -3 +5.407384833365425 -1.896858756783769 -3 +-5.408471972967071 -1.896930989772753 -3 +-4.857131334674166 -2.725718820119911 -3 +5.737164416961212 -1.026690486627236 -3 +-5.737164416961212 -1.026690486627236 -3 +1.129433252281475 -0.6056352318285998 -3 +-5.361944891133799 -0.1680133422131147 -3 +5.362158187152676 -0.168387425950854 -3 +2 5 0 40 +994 +995 +996 +997 +998 +999 +1000 +1001 +1002 +1003 +1004 +1005 +1006 +1007 +1008 +1009 +1010 +1011 +1012 +1013 +1014 +1015 +1016 +1017 +1018 +1019 +1020 +1021 +1022 +1023 +1024 +1025 +1026 +1027 +1028 +1029 +1030 +1031 +1032 +1033 +4.527272727272733 2 -2.000000000000001 +-4.445436295312541 2 -2.030082565865532 +2.200000000000011 2 -2 +0.8195709861995271 2 -2.017379296819283 +-2.936094177930909 2 -2.013659835397336 +-1.51186868686868 2 -2.017379296819284 +3.471108280062406 2 -2.008497664541634 +-0.3036796536796418 2 -2 +-3.686353428947338 2 -1.6666833383655 +1.478288095789549 2 -1.638811207063379 +-2.202497025447705 2 -1.669780844892123 +2.880211683648616 2 -1.613808672704736 +2.891538482353631 2 -2.383233329975427 +1.484596871599105 2 -2.39721367891379 +-2.207208555749611 2 -2.405037774507598 +-0.9363035113035014 2 -1.633035438358769 +-0.9475308641975211 2 -2.369606159566712 +-3.671585983016586 2 -2.402892769424009 +0.231060606060618 2 -1.616944444444444 +0.2513229374086352 2 -2.365234461259229 +4.179061175143248 2 -1.63154350791054 +4.149249073091582 2 -2.370719878585462 +4.921969696969697 2 -1.565833333333334 +4.9219696969697 2 -2.434166666666665 +-4.953782770999875 2 -1.525691301402454 +-4.944693321276968 2 -2.470002062299566 +-4.37711449905195 2 -1.444491441126697 +-4.372343119921218 2 -2.580595479517822 +2.200000000000011 2 -1.43277777777778 +2.200000000000011 2 -2.567222222222221 +-2.93333333333333 2 -2.567222222222222 +-2.93333333333333 2 -1.432777777777778 +-1.492245158872772 2 -1.448727440143215 +-1.519988288029826 2 -2.558404646178719 +0.7991172709432774 2 -1.454626989665421 +0.8044314923747926 2 -2.55596548739846 +-5.068782477517876 2 -2.005155185913511 +5.074242424242426 2 -2.000000000000001 +3.54511046285036 2 -1.463447061318223 +3.543224207406817 2 -2.538216277279677 +2 6 0 32 +1034 +1035 +1036 +1037 +1038 +1039 +1040 +1041 +1042 +1043 +1044 +1045 +1046 +1047 +1048 +1049 +1050 +1051 +1052 +1053 +1054 +1055 +1056 +1057 +1058 +1059 +1060 +1061 +1062 +1063 +1064 +1065 +7.418823824735858 1.10047855841521 -0.5 +7.485508052221022 0.4660141630189297 -0.5 +-7.485508052221022 0.4660141630189278 -0.4999999999999999 +-7.418823824735858 1.100478558415211 -0.5 +-7.27523439895908 1.822351349274475 -0.5 +7.27523439895908 1.822351349274477 -0.5 +-7.061580488872658 2.526673900441646 -0.5 +7.061580488872656 2.526673900441649 -0.5 +-6.779919698425828 3.20666320072711 -0.5 +6.779919698425823 3.206663200727118 -0.5 +3.206663200727099 6.779919698425832 -0.5 +2.526673900441632 7.061580488872663 -0.5 +3.855770581449151 6.432964575002048 -0.5 +1.82235134927446 7.275234398959085 -0.5 +1.100478558415189 7.418823824735861 -0.5 +4.467744783693242 6.024056486104843 -0.5 +0.3680075574556101 7.490965921538794 -0.5 +-0.3680075574556576 7.490965921538792 -0.5 +-1.100478558415233 7.418823824735854 -0.5 +-1.822351349274498 7.275234398959076 -0.5 +-2.526673900441668 7.061580488872649 -0.5 +-3.206663200727132 6.779919698425817 -0.5 +-3.855770581449177 6.432964575002032 -0.5 +-4.467744783693261 6.024056486104829 -0.5 +-5.036692161352646 5.557133440162186 -0.5 +-5.5571334401622 5.036692161352631 -0.5 +-6.024056486104842 4.467744783693242 -0.5 +-6.432964575002044 3.855770581449157 -0.5 +5.036692161352633 5.557133440162198 -0.5 +5.557133440162188 5.036692161352645 -0.5 +6.024056486104834 4.467744783693253 -0.5 +6.432964575002038 3.855770581449166 -0.5 +2 7 0 13 +1066 +1067 +1068 +1069 +1070 +1071 +1072 +1073 +1074 +1075 +1076 +1077 +1078 +-6.203037817362707 1.872361564270609 -2.557409122322195 +-7.419129957176479 0.5629744287867827 -2.074483971780935 +-7.442818866174559 0.474820864364868 -2.569737309298218 +-7.372361564270609 0.7030378173627054 -1.442590877677806 +-6.062974428786783 1.919129957176479 -1.925516028219067 +-5.97482086436487 1.942818866174558 -1.430262690701784 +-6.813238633153056 1.508444328569766 -2.511013000594856 +-6.544658645092481 1.70548770597549 -2.076823996122759 +-7.008444328569768 1.313238633153054 -1.488986999405145 +-7.205487705975491 1.04465864509248 -1.923176003877242 +-6.914213562373096 1.414213562373094 -2 +-7.233385575677208 0.9976845423450202 -2.438628149419134 +-6.497684542345022 1.733385575677207 -1.561371850580867 +2 8 0 14 +1079 +1080 +1081 +1082 +1083 +1084 +1085 +1086 +1087 +1088 +1089 +1090 +1091 +1092 +6.704523363974518 -3.596597465123727 -0.8588989475007441 +6.117371225707729 -3.902328249716157 -1.109014035240354 +6.123310561006318 -3.900390471597348 -0.4507342791411839 +6.603556950910945 -3.667981431580142 -1.622876768685649 +7.406994712792853 -2.602802758271812 -1.063744308260413 +7.402275386764796 -2.617534090483147 -1.889978530919655 +7.1681985025757 -3.103228786790933 -1.376347215906079 +7.09547326530495 -3.206012047907135 -2.139425420916377 +7.400310428877432 -2.623554547653749 -2.5487344638098 +7.396875382620818 -2.63392726933547 -0.3998424641620199 +7.105506744031278 -3.192622360544227 -0.6103183755973975 +6.10261765144837 -3.90705321534635 -1.935639605428511 +6.691566261006417 -3.606290710186418 -2.388481719337907 +6.133531915099188 -3.897007462439396 -2.599836115892926 +2 9 0 59 +1093 +1094 +1095 +1096 +1097 +1098 +1099 +1100 +1101 +1102 +1103 +1104 +1105 +1106 +1107 +1108 +1109 +1110 +1111 +1112 +1113 +1114 +1115 +1116 +1117 +1118 +1119 +1120 +1121 +1122 +1123 +1124 +1125 +1126 +1127 +1128 +1129 +1130 +1131 +1132 +1133 +1134 +1135 +1136 +1137 +1138 +1139 +1140 +1141 +1142 +1143 +1144 +1145 +1146 +1147 +1148 +1149 +1150 +1151 +-1.46666666666668 -4 -1.5 +-3.603318582446144 -4 -1.494142806358722 +3.666666666666664 -4 -1.5 +0.8654820377976931 -4 -1.516401477842376 +2.210543938386688 -4 -1.553185441945833 +-0.3560415854670396 -4 -1.925320585165455 +-2.577291747866312 -4 -1.074679414834542 +-4.484243694618902 -4 -0.9274786239721562 +-4.460453520176891 -4 -2.061335659369321 +4.427073645941761 -4 -0.9380574624641728 +4.439567105240593 -4 -2.058888580818334 +-2.253030303030318 -4 -2.076666666666665 +-0.680303030303044 -4 -0.9233333333333335 +2.899927078269322 -4 -0.9089423648247172 +1.500072921730663 -4 -0.9089423648247164 +2.963271847137408 -4 -2.134901235295946 +1.529213810087493 -4 -2.193296384676759 +-3.114883571626077 -4 -2.143638565367365 +0.1849791820864404 -4 -0.843022457455971 +-1.082968529597756 -4 -2.201021936864634 +-1.850364803735597 -4 -0.7989780631353646 +-3.282968529597751 -4 -0.798978063135364 +0.3367172840442585 -4 -2.183427895010307 +3.694045133077706 -4 -0.7058190350797502 +3.865579787404255 -4 -2.252981648585534 +2.220605919122315 -4 -2.376276612383708 +2.20039209623916 -4 -0.6345071173152608 +-3.881172652433465 -4 -2.253742679297123 +0.8735265781745944 -4 -0.6363161113734994 +-3.925876036567708 -4 -0.686128133096317 +-1.737432352754803 -4 -2.312267060815667 +-1.195900980578555 -4 -0.6877329391843323 +-4.925546568380756 -4 -1.499001275298346 +4.938411065762105 -4 -1.499618255410313 +-2.93050687618307 -4 -1.528369928771017 +-0.02792264077697215 -4 -1.474905205910386 +2.935102382615021 -4 -1.524257260516624 +1.526328177000634 -4 -1.542956417322421 +0.9115285152647123 -4 -2.425160345988884 +-0.8312207619611263 -4 -1.475536904800862 +-2.088106026894597 -4 -1.512623261758265 +-2.391175367818425 -4 -0.5453316706347189 +-0.5421579655149245 -4 -2.454668329365279 +-4.256219559451804 -4 -1.5 +4.256219559451797 -4 -1.5 +-4.925444459204051 -4 -2.397903109775353 +-4.932677259238833 -4 -0.598878736132616 +4.924107472944893 -4 -2.397598093368851 +4.922025229728422 -4 -0.6017656656483381 +4.399999999999998 -4 -0.4229182760155424 +4.404179195084247 -4 -2.551947395820234 +-4.406843942021879 -4 -2.559487114649712 +-0.2838288482712965 -4 -0.543072626699828 +-2.649504485062062 -4 -2.456927373300172 +-4.428559398085092 -4 -0.4424970986402178 +-0.08529130547667041 -4 -2.535404329482491 +-2.849887443888131 -4 -0.4620822359668911 +2.93333333333333 -4 -0.3811285417088673 +1.46666666666666 -4 -0.3811285417088657 +2 10 0 14 +1152 +1153 +1154 +1155 +1156 +1157 +1158 +1159 +1160 +1161 +1162 +1163 +1164 +1165 +-7.096597465123727 -3.204523363974519 -0.8588989475007442 +-7.402328249716157 -2.617371225707729 -1.109014035240354 +-7.400390471597348 -2.623310561006318 -0.4507342791411838 +-7.167981431580142 -3.103556950910945 -1.622876768685649 +-6.102802758271812 -3.906994712792853 -1.063744308260413 +-6.117534090483147 -3.902275386764796 -1.889978530919655 +-6.603228786790933 -3.668198502575699 -1.376347215906079 +-6.706012047907135 -3.59547326530495 -2.139425420916377 +-6.123554547653749 -3.900310428877432 -2.5487344638098 +-6.13392726933547 -3.896875382620818 -0.3998424641620197 +-6.692622360544227 -3.605506744031278 -0.6103183755973975 +-7.40705321534635 -2.602617651448369 -1.935639605428511 +-7.106290710186418 -3.191566261006417 -2.388481719337907 +-7.397007462439396 -2.633531915099188 -2.599836115892926 +2 11 0 13 +1166 +1167 +1168 +1169 +1170 +1171 +1172 +1173 +1174 +1175 +1176 +1177 +1178 +-7.5 -0.9423115287880401 -0.9146605019661057 +-7.5 -0.9917871638762055 -1.986491628614915 +-7.5 -0.6102882120651192 -1.377187280356542 +-7.5 -0.4788060397319975 -0.7495473245812074 +-7.5 -1.370298505186783 -1.289108322753887 +-7.5 -0.5242438976266977 -2.4715403412179 +-7.5 -1.429917946194454 -0.5684099562974798 +-7.5 -1.420611347119692 -2.406284160402689 +-7.5 -0.8864395735757975 -0.441086255487123 +-7.5 -0.4429054834289512 -1.93478240462185 +-7.5 -0.4063824559948919 -0.3381267160136662 +-7.5 -1.569365488527112 -1.897272706136244 +-7.5 -0.9999999999999987 -2.655288294277353 +2 12 0 346 +1179 +1180 +1181 +1182 +1183 +1184 +1185 +1186 +1187 +1188 +1189 +1190 +1191 +1192 +1193 +1194 +1195 +1196 +1197 +1198 +1199 +1200 +1201 +1202 +1203 +1204 +1205 +1206 +1207 +1208 +1209 +1210 +1211 +1212 +1213 +1214 +1215 +1216 +1217 +1218 +1219 +1220 +1221 +1222 +1223 +1224 +1225 +1226 +1227 +1228 +1229 +1230 +1231 +1232 +1233 +1234 +1235 +1236 +1237 +1238 +1239 +1240 +1241 +1242 +1243 +1244 +1245 +1246 +1247 +1248 +1249 +1250 +1251 +1252 +1253 +1254 +1255 +1256 +1257 +1258 +1259 +1260 +1261 +1262 +1263 +1264 +1265 +1266 +1267 +1268 +1269 +1270 +1271 +1272 +1273 +1274 +1275 +1276 +1277 +1278 +1279 +1280 +1281 +1282 +1283 +1284 +1285 +1286 +1287 +1288 +1289 +1290 +1291 +1292 +1293 +1294 +1295 +1296 +1297 +1298 +1299 +1300 +1301 +1302 +1303 +1304 +1305 +1306 +1307 +1308 +1309 +1310 +1311 +1312 +1313 +1314 +1315 +1316 +1317 +1318 +1319 +1320 +1321 +1322 +1323 +1324 +1325 +1326 +1327 +1328 +1329 +1330 +1331 +1332 +1333 +1334 +1335 +1336 +1337 +1338 +1339 +1340 +1341 +1342 +1343 +1344 +1345 +1346 +1347 +1348 +1349 +1350 +1351 +1352 +1353 +1354 +1355 +1356 +1357 +1358 +1359 +1360 +1361 +1362 +1363 +1364 +1365 +1366 +1367 +1368 +1369 +1370 +1371 +1372 +1373 +1374 +1375 +1376 +1377 +1378 +1379 +1380 +1381 +1382 +1383 +1384 +1385 +1386 +1387 +1388 +1389 +1390 +1391 +1392 +1393 +1394 +1395 +1396 +1397 +1398 +1399 +1400 +1401 +1402 +1403 +1404 +1405 +1406 +1407 +1408 +1409 +1410 +1411 +1412 +1413 +1414 +1415 +1416 +1417 +1418 +1419 +1420 +1421 +1422 +1423 +1424 +1425 +1426 +1427 +1428 +1429 +1430 +1431 +1432 +1433 +1434 +1435 +1436 +1437 +1438 +1439 +1440 +1441 +1442 +1443 +1444 +1445 +1446 +1447 +1448 +1449 +1450 +1451 +1452 +1453 +1454 +1455 +1456 +1457 +1458 +1459 +1460 +1461 +1462 +1463 +1464 +1465 +1466 +1467 +1468 +1469 +1470 +1471 +1472 +1473 +1474 +1475 +1476 +1477 +1478 +1479 +1480 +1481 +1482 +1483 +1484 +1485 +1486 +1487 +1488 +1489 +1490 +1491 +1492 +1493 +1494 +1495 +1496 +1497 +1498 +1499 +1500 +1501 +1502 +1503 +1504 +1505 +1506 +1507 +1508 +1509 +1510 +1511 +1512 +1513 +1514 +1515 +1516 +1517 +1518 +1519 +1520 +1521 +1522 +1523 +1524 +-0.007448718700270988 1.732549512569409 0 +3.611777723147425 -0.03924471437003096 0 +-3.616685730912322 -0.08499451335206221 0 +2.918800409957688 3.125661273983173 0 +-2.855812315090159 3.128757236398526 0 +-0.6858555706371536 -0.968711217611558 0 +0.4031200202089922 4.718942747706224 0 +5.305061793363475 -1.619411016852633 0 +-5.171061593549962 -1.716457799300581 0 +1.579485054999873 -1.511651844906277 0 +4.889825490598049 1.819136739499511 0 +-4.876676298336352 1.883609795551783 0 +-1.741584802983803 5.003736921765134 0 +-2.850389368359249 -1.946909754228621 0 +1.996245881712571 1.300678616112999 0 +-1.96991192923344 1.261551693185134 0 +5.623656536812066 0.1416789610056808 0 +-5.623656536812076 0.1416789610056632 0 +2.364812959552855 5.020600657992714 0 +3.327429175611435 -2.112237259916826 0 +-1.140346470395687 3.292968386930117 0 +0.6376783493456198 0.0111951858888113 0 +1.181508236586789 3.02202864582377 0 +-4.639881086133862 3.518954974391454 0 +4.543385883283516 3.52494003500788 0 +-3.405008102938154 4.855414973952002 0 +0.03743395911859236 -2.508241833064132 0 +-0.4442039135332707 5.908920227411057 0 +-2.052350091667424 -0.2268584834159662 0 +-4.006119807409396 -2.541911144472358 0 +-1.296316141850686 -2.510958665759706 0 +3.455272929841765 1.417570856410942 0 +-3.465582897563624 1.438743719875645 0 +1.214869501660218 5.950776817399035 0 +-0.8004764909430063 0.4535957957065042 0 +1.887021517955705 -0.1846762275137863 0 +3.871870971594622 4.770566499363289 0 +6.057308052214105 -2.557308052214108 0 +-6.060168164897139 -2.541220878923331 0 +-6.23041346389358 -0.9383078109217138 0 +6.149951287767109 -0.9446815959932717 0 +-3.95325424380996 -1.302679123748735 0 +2.213501100709423 -2.76140870530484 0 +4.431608204627788 -2.793183794642018 0 +6.08410685419002 1.369226730954272 0 +-6.084106854190034 1.369226730954251 0 +4.686326544681392 -0.5626241533598551 0 +-4.555089171255406 0.712965368151004 0 +4.642548177963161 0.6817476859814493 0 +-5.619809997307964 2.847345865449567 0 +5.619809997307947 2.847345865449594 0 +0.3286236863635329 -1.175322091187235 0 +2.922342466398553 -1.051680020600297 0 +-2.696081719630973 5.716968354620948 0 +2.017242559398397 3.925763628237778 0 +-1.934844893103304 2.477391189449248 0 +-0.7344977912775632 4.447444509222265 0 +0.03527201325176973 3.536114418903151 0 +-1.587305155414755 6.164957551467823 0 +3.884417288834063 2.490647525188372 0 +-3.939014715580777 2.513219766072318 0 +-4.869737458371377 -0.6211134069147297 0 +-2.064699053799774 3.905910792978658 0 +-5.0409417047864 -2.925630285321197 0 +0.9056392318411391 1.106113951912834 0 +2.121064262235866 2.440131990827894 0 +-3.023012057426681 -3.013271494119192 0 +4.109835721419232 -1.405850212326475 0 +-2.879497887731215 -0.8718247662562746 0 +1.141536242746483 -2.860718998685792 0 +-1.823677204462485 -1.27878635339848 0 +-1.069178272454329 1.842262370335951 0 +-4.503603246387111 4.576774794345032 0 +2.215607970671577 6.081249485367273 0 +-2.715612814440694 0.5760707157092819 0 +2.725918995779007 0.6306619071703139 0 +3.198523294467337 5.614258355827998 0 +6.54977143303759 -0.08883676267207141 0 +-6.549771433037598 -0.08883676267207896 0 +-6.60863182915852 -1.838521044880582 0 +6.608631829158522 -1.838521044880581 0 +5.30191220479813 -3.060601914200779 0 +0.36844324508486 6.566839508053182 0 +2.956842165474066 4.138267574529962 0 +1.423983197214024 4.77686614178099 0 +3.627709427771418 -2.930077310777982 0 +1.176518572450221 2.019431877505208 0 +-3.627073976542595 3.818796677729248 0 +4.714576168657968 4.552891698500103 0 +-2.948595223720597 1.994469555214233 0 +-0.4396566554562439 -3.075054727662812 0 +-2.012750318321677 -3.161212207969921 0 +-0.151553694513181 -0.3498150498513639 0 +-0.4196095492184411 2.59516368172654 0 +1.289581984567494 -0.6553622786133007 0 +2.524229813039575 -2.059094144009116 0 +3.124778590008551 2.243629905198674 0 +5.429059235286885 -0.8887155284621704 0 +-6.272223017296145 2.247844184076912 0 +6.272223017296127 2.247844184076937 0 +1.535974046447337 0.6130816598959292 0 +-0.6502781612407975 -1.896320644669405 0 +0.2514545011476494 5.487192014160422 0 +1.006964585542881 3.902155659080355 0 +3.834295257301144 3.593078667583699 0 +5.456448197707132 3.728503513963048 0 +-5.392027360159977 3.710499237909989 0 +0.1209511740383066 0.7056700619997518 0 +-1.145878051466452 -0.3294253889144043 0 +-1.655135134335495 0.6454033452757315 0 +-5.329433354500511 0.8328579608632766 0 +5.330658382842402 0.9356335307402381 0 +-2.611299845444957 4.567198747881284 0 +-3.49076952969238 5.670157404454035 0 +6.603407082918565 0.6903733432763446 0 +-6.603407082918572 0.6903733432763315 0 +-4.71480237777008 2.703950396248351 0 +4.589889549813764 2.787518606906238 0 +-5.680987055544762 -3.30771359538091 0 +3.703172566903959 -0.915283767725656 0 +0.7629829101048254 2.549160738792816 0 +-0.9589149189787265 6.626903829056558 0 +-3.538074969787086 -1.911138519492058 0 +-0.9791166916242651 5.189226153802107 0 +1.026017038339874 -2.081361509184032 0 +-4.356716864524185 -1.853867014566636 0 +-4.329644026498713 -0.0277071301732037 0 +0.3684155243947428 -3.136058944935054 0 +-4.314628767321798 -3.265451567078116 0 +5.971937757187024 -1.924539501377454 0 +-5.889045119769836 -1.857415476569162 0 +-5.536294085887765 -1.088848767286869 0 +5.428667405084478 -2.412735135725103 0 +2.932714384953957 -3.338150310150418 0 +2.108251431837203 -0.8699606432443376 0 +3.769436641736402 0.6589089207843701 0 +-3.767539453587855 0.6895909028139187 0 +1.586867724330953 6.569501976216431 0 +4.237854126708022 1.40121404599548 0 +-4.27277459760427 1.349244392739518 0 +-1.912933252877293 -2.03912274707025 0 +-2.863795258827448 3.814457700812522 0 +6.727993579791288 -2.625693980719432 0 +-6.726250496425324 -2.64154161808082 0 +6.125693980719434 -3.22799357979129 0 +-0.4694685919767745 1.316371630010922 0 +-5.401711467005406 -2.344749129333586 0 +4.09022928309114 5.519553117746375 0 +2.576056509336239 -0.340591205785866 0 +-1.246743579599352 -3.175752384961219 0 +-2.290563572976116 6.386082887735622 0 +2.767548759434065 1.494792285170585 0 +4.920837478227691 0.06894939530730237 0 +2.055263592508941 3.10997226007022 0 +-0.2667782462963973 4.993993482326005 0 +-5.590354492016323 1.948570081656098 0 +5.590354492016307 1.948570081656118 0 +1.746705666095247 5.395873725299071 0 +4.60157092971592 -2.066276548907879 0 +-2.689422150920225 1.276056270135515 0 +-2.810567682450757 -0.1658855545760667 0 +-2.186487022660574 3.166311794963766 0 +-1.344398987490149 3.978271612008253 0 +-1.137141497666709 2.527721179479265 0 +-1.270883747125967 -1.705711513598653 0 +-5.170906154860271 4.534795696627256 0 +-6.834870744317876 -1.120841578411872 0 +6.826450397787701 -1.120968945015278 0 +4.283443648293791 0.05081675689798781 0 +-3.59980540412091 -3.288545705461159 0 +-4.143921319339754 5.254158504387217 0 +1.633965883274112 -3.321876963954708 0 +3.064572928335832 4.863873731352112 0 +1.673000879245732 -2.266425991930385 0 +-5.957496083376769 -0.405233183877443 0 +-1.271107086577138 1.218795805241147 0 +5.972976946618165 -0.3951945161340027 0 +-4.676319696401258 -1.275528040038705 0 +-6.286286498705154 -3.137097369787593 0 +-3.504499749747592 -0.734502479495267 0 +4.185411676831465 4.120098717042979 0 +3.496562989226441 -1.486161585899449 0 +-5.007450721841308 0.1173400823214361 0 +-3.981367873991292 3.185239344461154 0 +-6.683170329970066 1.681851305866196 0 +6.683170329970046 1.681851305866229 0 +-0.6318958874051999 3.772994059464424 0 +2.915886898878094 6.215449488290467 0 +2.925116780417162 -2.640193546031836 0 +4.728874893801823 -1.251344086254342 0 +4.228794049613415 -3.423815144503062 0 +-2.02341078590155 5.652585766245757 0 +5.89705507286884 0.67293804751132 0 +-5.959219307590988 0.690325553152598 0 +0.9489925407447662 5.262201098115504 0 +3.964780156649648 -2.352479990024225 0 +-0.1541731406419254 -1.42247743226982 0 +-0.1866288084328664 6.735418615724138 0 +6.266777484506218 2.970962083073127 0 +-6.266777484506225 2.97096208307312 0 +0.9094799781400489 6.720987949358221 0 +-2.481743343079831 -2.561878583830697 0 +-2.285305235389066 1.910338206991229 0 +-5.099636961738361 -3.49917871318487 0 +-0.1282653251998023 4.23688766505454 0 +-4.740599335375101 -2.35925603259152 0 +-4.158356817623536 -0.6744207822871169 0 +4.073186829063276 3.075032401347112 0 +4.570765436488334 5.180427367987998 0 +0.6505453484787035 1.771272498265506 0 +-3.202732209028964 -1.35354894672804 0 +0.4251119209414196 -0.5903762997186459 0 +2.420168464166545 4.383997407149727 0 +1.283584591776556 0.006766972282437056 0 +-2.976603218246531 6.263342924651581 0 +-2.282228721098726 -0.7638719633949478 0 +-2.904748027638783 5.174692222554333 0 +0.9103175153070923 -1.289675374123574 0 +-3.579246215109492 2.116731628373704 0 +-4.226347148881606 3.979027453826983 0 +7.007213638377284 0.235126453774289 0 +-7.007213638377285 0.235126453774281 0 +0.4374019106176141 -1.801887776345644 0 +5.328454028129942 4.3421609245868 0 +2.582094866499531 3.674470463601657 0 +-1.682413642000661 -0.6368408874180727 0 +-1.077979687757423 5.852820932700427 0 +1.403370015453461 1.470057911045047 0 +-1.696129679745908 6.752532327022887 0 +3.842950945665645 1.906815521729149 0 +-3.321952029455237 2.696917251936114 0 +-5.093563837192537 3.155036769197667 0 +5.063231821388875 3.208814117226702 0 +-4.257904474870899 2.006185462528911 0 +-2.490677034738686 -1.354239037147284 0 +-3.364662199208779 -2.515042347796931 0 +2.593919994089108 5.577921430091807 0 +2.223247491858876 0.4226725940564833 0 +5.821762313991876 -1.374401135323901 0 +4.817269798540734 1.254267376804267 0 +-4.85448885717242 1.252450718676609 0 +3.513946166083894 2.978977172049372 0 +6.985881946228003 -0.4418925569714616 0 +-6.985881946228007 -0.4418925569714651 0 +-2.583181457100008 -3.392262091008125 0 +1.498621967423279 3.542288454091594 0 +-1.323181328672189 4.582651971989534 0 +7.006943084203478 -2.180759818917759 0 +-7.006943084203477 -2.180759818917762 0 +0.694511053520667 3.382820044824739 0 +5.308367942087498 -0.327917129427334 0 +-1.670205166295796 3.449203573721221 0 +5.677941152038926 -3.504658617580438 0 +-2.588832786569823 2.562364205825519 0 +-3.186584065481821 0.885173943373493 0 +-1.611248152403997 1.873010074113662 0 +6.038693450880609 3.449812747265555 0 +-6.003228829480491 3.525952353550551 0 +7.099433317792173 -1.670211244500198 0 +-7.099433317792172 -1.670211244500201 0 +-2.153526736078508 0.3623061289338456 0 +5.21866000442367 -3.554997127303732 0 +-0.5121506743063774 2.047475693948776 0 +-5.381274636215549 -0.3607798332512471 0 +0.9530556893119201 0.5105538860507308 0 +1.781557850433438 1.962171744801141 0 +1.51314923738668 2.517149542970174 0 +0.8871211722245806 -3.45015936649224 0 +-5.204758519731128 2.425988061941919 0 +5.078948753525216 2.450383797275097 0 +6.578382846282524 -3.078382846282524 0 +4.396917191261863 2.218482779332581 0 +-1.933996898896239 4.498853475608315 0 +0.4602953504826389 3.994700628230416 0 +3.555020887829736 4.207327442225935 0 +3.153599623371853 0.9024754143279743 0 +2.251826438072591 -3.486879157666333 0 +3.600088364699315 5.97146453545864 0 +-0.6924137610612691 -2.51624316584831 0 +2.584901101914608 2.620998076738665 0 +4.250677726006579 -0.9460037437942268 0 +2.368700507800657 6.6247409974561 0 +-0.1928455368528729 0.2058559789060723 0 +-0.1503692138435432 -3.533887377765661 0 +-0.714422954787904 -3.561500844070579 0 +0.2522634473896693 1.304799009669106 0 +-4.77593624214272 5.093321650895825 0 +-2.318520346749384 5.102339248112628 0 +0.1278982970086175 6.153189512834539 0 +2.880243489922398 -1.64303904992007 0 +-0.5099784858196423 3.17093018806881 0 +-6.22957400886558 -1.433060870584274 0 +-3.891927053610223 4.49064889916801 0 +-0.04756935969746154 -0.9013404181277247 0 +1.475869548146816 4.21127450494139 0 +-5.337268259867637 1.463800115335198 0 +5.312908981428899 1.479942759822201 0 +2.39601607428985 2.010400436474993 0 +6.135876467548342 0.2239352069537135 0 +-6.135876467548351 0.2239352069537042 0 +0.6548881350473641 -2.526186720015918 0 +6.275746717178446 -1.440622444518097 0 +-1.81329431925704 -2.635678621794791 0 +4.902256849386405 3.995532085644085 0 +0.3539475473592345 7.04510588374453 0 +-3.36229813566019 3.315176229048869 0 +4.922107748568189 -2.708504499642646 0 +-1.488123829943349 5.533268165141683 0 +0.1032815774229818 2.924126062150237 0 +-5.692202095617389 4.221624793705454 0 +3.054476858594399 0.1921346328329494 0 +-3.21939794937469 0.3799910987937132 0 +-5.65012808724784 -2.80183865589769 0 +3.22683329219101 3.619630432328966 0 +-1.324393480612031 -1.052700439952111 0 +-0.6455083116555005 -0.1161592279063357 0 +3.624510239134423 -3.538408553086293 0 +-4.467044574975263 -2.772920822554763 0 +2.518657256864227 0.9983123332146558 0 +-3.291599379600512 4.249450974283626 0 +1.69871384188068 5.927926398820241 0 +-4.786552999284566 4.064010431420142 0 +0.9523884381105185 4.438179041638897 0 +0.63685634396436 6.023531149986816 0 +6.505772232188058 -0.5882604468603314 0 +-6.51490330500092 -0.5777870838427459 0 +3.317819064023511 -0.4924208059527082 0 +6.425542580924316 -2.268919585000441 0 +-6.425542580924319 -2.268919585000448 0 +6.867554517145146 1.193557763883058 0 +-6.867554517145161 1.193557763883038 0 +-1.613805010024414 2.982719224908723 0 +5.766580911333678 -2.925781041966935 0 +4.811624813116309 -3.25685041338204 0 +-3.056179525094121 -3.524607455991131 0 +2.185538519392558 -1.528235447359945 0 +-2.272695859466922 0.8557082926863162 0 +1.943551385502463 4.66590841467614 0 +3.578909113942037 5.236540977347455 0 +0.09626681563023684 2.269958031242214 0 +-0.1048508450333266 -1.955024780857505 0 +3.900035794524536 -1.884601119414971 0 +-1.581630024415258 0.04469675169460663 0 +1.657916204238993 -2.796967936874134 0 +5.233601603260403 0.4487752639089149 0 +3.975536212176109 -0.4841267380507484 0 +2 13 0 104 +1525 +1526 +1527 +1528 +1529 +1530 +1531 +1532 +1533 +1534 +1535 +1536 +1537 +1538 +1539 +1540 +1541 +1542 +1543 +1544 +1545 +1546 +1547 +1548 +1549 +1550 +1551 +1552 +1553 +1554 +1555 +1556 +1557 +1558 +1559 +1560 +1561 +1562 +1563 +1564 +1565 +1566 +1567 +1568 +1569 +1570 +1571 +1572 +1573 +1574 +1575 +1576 +1577 +1578 +1579 +1580 +1581 +1582 +1583 +1584 +1585 +1586 +1587 +1588 +1589 +1590 +1591 +1592 +1593 +1594 +1595 +1596 +1597 +1598 +1599 +1600 +1601 +1602 +1603 +1604 +1605 +1606 +1607 +1608 +1609 +1610 +1611 +1612 +1613 +1614 +1615 +1616 +1617 +1618 +1619 +1620 +1621 +1622 +1623 +1624 +1625 +1626 +1627 +1628 +6.83774016463603 -3.48675863942994 2.174366737869888 +6.407529899965572 -3.782242823149662 1.676423481655588 +6.107862812997988 -3.905387834687251 2.043134326967468 +7.427413132236071 -2.533927539731694 22.30987908476981 +7.266479540793241 -2.937843287526707 22.56578331026792 +6.034203170353218 -3.927336756455543 0.6904195180241434 +6.437843287526706 -3.766479540793241 0.4342166897320861 +6.205561312673089 -3.871412096268224 21.99266409756959 +6.754192290478743 -3.557883724320812 22.15881623411816 +6.839217064471962 -3.485428441301398 21.5739982683064 +6.118918393336044 -3.901825444774133 21.37933470943371 +7.371747741804522 -2.704670413065337 1.007772309572872 +7.059509534247001 -3.252170121266557 0.8417945007756145 +6.986654005682437 -3.337856444985173 1.427964760096903 +7.40201584202576 -2.618333030561234 1.621502757422671 +6.987978198509366 -3.33638350811465 20.83072687700493 +6.387434972816612 -3.792333442477147 20.98289711405101 +7.282947802999905 -2.906144101000394 21.32560703401776 +7.292864388864938 -2.886361824053785 2.01908415463453 +6.914213562373095 -3.414213562373095 20.03225806451612 +7.363349561056377 -2.726586824344489 20.37465750171636 +6.2935479337859 -3.835832693026282 20.39892600103283 +6.914213562373093 -3.414213562373097 19.29032258064515 +6.914213562373095 -3.414213562373095 18.54838709677418 +6.273122879904261 -3.844527314129162 18.96060902622568 +7.344703535131767 -2.772702314913293 18.87810984542666 +6.27621511112868 -3.843228173953374 19.70213527514464 +7.344703535131767 -2.772702314913293 19.62004532929762 +6.914213562373095 -3.414213562373095 17.80645161290321 +6.272752625722631 -3.844682460327191 18.21867204213181 +7.344703535131766 -2.772702314913294 18.13617436155568 +6.914213562373095 -3.414213562373095 17.06451612903224 +6.272708332859938 -3.844701014345906 17.47673055744806 +7.344703535131767 -2.772702314913292 17.39423887768471 +6.914213562373095 -3.414213562373095 16.32258064516127 +6.272703034744216 -3.844703233611596 16.73479367364433 +7.344703535131767 -2.772702314913292 16.65230339381375 +6.914213562373095 -3.414213562373095 15.5806451612903 +6.914213562373095 -3.414213562373095 14.83870967741933 +6.272702325212259 -3.844703530817776 15.25092241935909 +7.344703535131767 -2.772702314913293 15.16843242607181 +6.272702401015065 -3.844703499065786 15.99285794224131 +7.344703535131767 -2.772702314913293 15.91036790994277 +6.914213562373095 -3.414213562373095 14.09677419354836 +6.272702316145192 -3.844703534615754 14.50898692971771 +7.344703535131767 -2.772702314913292 14.42649694220083 +6.914213562373095 -3.414213562373095 13.35483870967739 +6.272702315060645 -3.844703535070045 13.76705144502687 +7.344703535131767 -2.772702314913293 13.68456145832987 +6.914213562373094 -3.414213562373096 12.61290322580642 +6.272702314930918 -3.844703535124384 13.02511596104261 +7.344703535131766 -2.772702314913297 12.94262597445889 +6.914213562373095 -3.414213562373095 11.87096774193545 +6.914213562373096 -3.414213562373094 11.12903225806449 +6.272702314913545 -3.844703535131662 11.54124499328329 +7.344703535131663 -2.77270231491354 11.45875500671666 +6.2727023149154 -3.844703535130884 12.2831804771563 +7.344703535131755 -2.772702314913323 12.20069049058788 +6.914213562373095 -3.414213562373095 10.38709677419352 +6.914213562373094 -3.414213562373096 9.645161290322555 +6.272702314913295 -3.844703535131766 10.05737402554105 +7.344703535124487 -2.772702314930673 9.974884038958233 +6.272702314913323 -3.844703535131754 10.79930950941205 +7.344703535130897 -2.772702314915371 10.71681952284375 +6.914213562373094 -3.414213562373096 8.903225806451593 +6.272702314913293 -3.844703535131767 9.315438541670087 +7.344703535070903 -2.772702315058596 9.232948554980457 +6.914213562373096 -3.414213562373094 8.16129032258063 +6.272702314913293 -3.844703535131767 8.573503057799121 +7.34470353462293 -2.77270231612806 8.491013070342786 +6.914213562373095 -3.414213562373095 7.419354838709665 +6.914213562373095 -3.414213562373095 6.677419354838699 +6.272702314913293 -3.844703535131767 7.089632090057191 +7.344703499567359 -2.77270239981764 7.007142061826357 +7.405639132306323 -2.607074540252516 20.95815818532144 +6.272702314913293 -3.844703535131767 7.831567573928158 +7.344703530877771 -2.772702325069029 7.749077581137308 +6.914213562373095 -3.414213562373095 5.935483870967734 +6.272702314913293 -3.844703535131767 6.347696606186226 +7.344703237804867 -2.77270302473346 6.26520635965936 +6.914213562373095 -3.414213562373095 5.193548387096767 +6.914213562373095 -3.414213562373095 4.451612903225799 +6.272702314913293 -3.844703535131767 4.863825638444293 +7.344682753424528 -2.772751926052665 4.781330184487431 +6.272702314913293 -3.844703535131767 5.605761122315261 +7.344701049402834 -2.772708249167874 5.52326971498959 +6.914213562373095 -3.414213562373095 3.709677419354832 +6.914213562373095 -3.414213562373095 2.967741935483865 +6.272702314913293 -3.844703535131767 3.379954670702359 +7.343248730532498 -2.776166294933202 3.29801290171268 +6.272702314913293 -3.844703535131767 4.121890154573325 +7.34452976540766 -2.773117031583938 4.039409152993327 +6.227363649510281 -3.863046462483179 2.626266405994981 +7.335840313081854 -2.793530304943372 2.602341072966712 +6.484249266597109 -3.741049505672671 22.53780310605798 +6.944621093172201 -3.38313770000024 22.54727134617754 +7.241049505672672 -2.984249266597108 0.4621968939420276 +6.88313770000024 -3.444621093172201 0.4527286538224561 +5.985548256113054 -3.940165686477723 22.5109279592811 +7.440165686477723 -2.485548256113054 0.489072040718901 +7.132867178202604 -3.154878685554749 22.15941338414756 +6.655603530630215 -3.632354275270838 0.8412333597405049 +6.356189074701875 -3.807467916274352 1.257564329217582 +7.307753817498931 -2.855585258941528 21.74343182815697 +2 14 0 565 +1629 +1630 +1631 +1632 +1633 +1634 +1635 +1636 +1637 +1638 +1639 +1640 +1641 +1642 +1643 +1644 +1645 +1646 +1647 +1648 +1649 +1650 +1651 +1652 +1653 +1654 +1655 +1656 +1657 +1658 +1659 +1660 +1661 +1662 +1663 +1664 +1665 +1666 +1667 +1668 +1669 +1670 +1671 +1672 +1673 +1674 +1675 +1676 +1677 +1678 +1679 +1680 +1681 +1682 +1683 +1684 +1685 +1686 +1687 +1688 +1689 +1690 +1691 +1692 +1693 +1694 +1695 +1696 +1697 +1698 +1699 +1700 +1701 +1702 +1703 +1704 +1705 +1706 +1707 +1708 +1709 +1710 +1711 +1712 +1713 +1714 +1715 +1716 +1717 +1718 +1719 +1720 +1721 +1722 +1723 +1724 +1725 +1726 +1727 +1728 +1729 +1730 +1731 +1732 +1733 +1734 +1735 +1736 +1737 +1738 +1739 +1740 +1741 +1742 +1743 +1744 +1745 +1746 +1747 +1748 +1749 +1750 +1751 +1752 +1753 +1754 +1755 +1756 +1757 +1758 +1759 +1760 +1761 +1762 +1763 +1764 +1765 +1766 +1767 +1768 +1769 +1770 +1771 +1772 +1773 +1774 +1775 +1776 +1777 +1778 +1779 +1780 +1781 +1782 +1783 +1784 +1785 +1786 +1787 +1788 +1789 +1790 +1791 +1792 +1793 +1794 +1795 +1796 +1797 +1798 +1799 +1800 +1801 +1802 +1803 +1804 +1805 +1806 +1807 +1808 +1809 +1810 +1811 +1812 +1813 +1814 +1815 +1816 +1817 +1818 +1819 +1820 +1821 +1822 +1823 +1824 +1825 +1826 +1827 +1828 +1829 +1830 +1831 +1832 +1833 +1834 +1835 +1836 +1837 +1838 +1839 +1840 +1841 +1842 +1843 +1844 +1845 +1846 +1847 +1848 +1849 +1850 +1851 +1852 +1853 +1854 +1855 +1856 +1857 +1858 +1859 +1860 +1861 +1862 +1863 +1864 +1865 +1866 +1867 +1868 +1869 +1870 +1871 +1872 +1873 +1874 +1875 +1876 +1877 +1878 +1879 +1880 +1881 +1882 +1883 +1884 +1885 +1886 +1887 +1888 +1889 +1890 +1891 +1892 +1893 +1894 +1895 +1896 +1897 +1898 +1899 +1900 +1901 +1902 +1903 +1904 +1905 +1906 +1907 +1908 +1909 +1910 +1911 +1912 +1913 +1914 +1915 +1916 +1917 +1918 +1919 +1920 +1921 +1922 +1923 +1924 +1925 +1926 +1927 +1928 +1929 +1930 +1931 +1932 +1933 +1934 +1935 +1936 +1937 +1938 +1939 +1940 +1941 +1942 +1943 +1944 +1945 +1946 +1947 +1948 +1949 +1950 +1951 +1952 +1953 +1954 +1955 +1956 +1957 +1958 +1959 +1960 +1961 +1962 +1963 +1964 +1965 +1966 +1967 +1968 +1969 +1970 +1971 +1972 +1973 +1974 +1975 +1976 +1977 +1978 +1979 +1980 +1981 +1982 +1983 +1984 +1985 +1986 +1987 +1988 +1989 +1990 +1991 +1992 +1993 +1994 +1995 +1996 +1997 +1998 +1999 +2000 +2001 +2002 +2003 +2004 +2005 +2006 +2007 +2008 +2009 +2010 +2011 +2012 +2013 +2014 +2015 +2016 +2017 +2018 +2019 +2020 +2021 +2022 +2023 +2024 +2025 +2026 +2027 +2028 +2029 +2030 +2031 +2032 +2033 +2034 +2035 +2036 +2037 +2038 +2039 +2040 +2041 +2042 +2043 +2044 +2045 +2046 +2047 +2048 +2049 +2050 +2051 +2052 +2053 +2054 +2055 +2056 +2057 +2058 +2059 +2060 +2061 +2062 +2063 +2064 +2065 +2066 +2067 +2068 +2069 +2070 +2071 +2072 +2073 +2074 +2075 +2076 +2077 +2078 +2079 +2080 +2081 +2082 +2083 +2084 +2085 +2086 +2087 +2088 +2089 +2090 +2091 +2092 +2093 +2094 +2095 +2096 +2097 +2098 +2099 +2100 +2101 +2102 +2103 +2104 +2105 +2106 +2107 +2108 +2109 +2110 +2111 +2112 +2113 +2114 +2115 +2116 +2117 +2118 +2119 +2120 +2121 +2122 +2123 +2124 +2125 +2126 +2127 +2128 +2129 +2130 +2131 +2132 +2133 +2134 +2135 +2136 +2137 +2138 +2139 +2140 +2141 +2142 +2143 +2144 +2145 +2146 +2147 +2148 +2149 +2150 +2151 +2152 +2153 +2154 +2155 +2156 +2157 +2158 +2159 +2160 +2161 +2162 +2163 +2164 +2165 +2166 +2167 +2168 +2169 +2170 +2171 +2172 +2173 +2174 +2175 +2176 +2177 +2178 +2179 +2180 +2181 +2182 +2183 +2184 +2185 +2186 +2187 +2188 +2189 +2190 +2191 +2192 +2193 +0.003340636505848593 -4 17.48846082592681 +-0.04894719356620314 -4 5.476898512361152 +-0.0483813391957888 -4 11.46079502609862 +-1.904955382158252 -4 14.51632594084384 +1.941063286349435 -4 14.50195106747699 +1.882060781010376 -4 8.520843973220469 +-1.941063286349455 -4 8.498048932522966 +2.238848484076032 -4 3.16595329199481 +-2.156827983758657 -4 3.210754237785911 +-2.238848484076044 -4 19.83404670800519 +2.156827983758668 -4 19.78924576221409 +2.797211598336565 -4 11.54514011922755 +-2.662076673705905 -4 11.54514011922755 +2.877888270784741 -4 16.98908623501292 +-2.572907269520554 -4 17.09872626275686 +-2.877888270784755 -4 6.01091376498708 +2.572907269520565 -4 5.9012737372431 +-0.05646749412934149 -4 20.68314346168766 +0.05646749412934504 -4 2.316856538312333 +-8.881784197001252e-16 -4 9.371478147729974 +-0.01024173909709614 -4 13.62847160771811 +-3.467987349670621 -4 13.32281121255197 +3.467987349670622 -4 13.32281121255196 +3.616012730086135 -4 9.689470153351937 +-3.616012730086143 -4 9.689470153351939 +-0.4104734088119821 -4 15.68511457146049 +0.2951307473369909 -4 7.433788006387966 +3.669784233690223 -4 1.97574804057626 +-3.669784233690231 -4 1.975748040576258 +-3.66978423369024 -4 21.02425195942373 +3.669784233690249 -4 21.02425195942374 +3.611708388551691 -4 15.40033880849527 +-3.512566834735869 -4 15.51023249750585 +-3.6117083885517 -4 7.599661191504698 +3.512566834735876 -4 7.489767502494116 +3.69478991489771 -4 18.6561160251021 +-3.694789914897715 -4 4.343883974897888 +-3.735402504668826 -4 18.6458138469808 +3.735402504668835 -4 4.354186153019182 +-1.617972664408155 -4 12.65249975740636 +1.565622740229863 -4 12.7471316033509 +1.527923191850242 -4 10.30932031396365 +-1.55496028661871 -4 10.25628392282249 +-1.36227063054329 -4 6.946081328396358 +1.362270630543293 -4 16.05391867160359 +0.8512287979105011 -4 3.988654667561071 +-0.8512287979105038 -4 19.01134533243892 +1.538089998478565 -4 1.732569616230296 +-1.538089998478571 -4 21.2674303837697 +-1.544957168675062 -4 1.678923271950711 +1.544957168675063 -4 21.32107672804929 +-1.52508179386915 -4 4.739391372488148 +1.525081793869151 -4 18.26060862751186 +-1.299790933720916 -4 16.71055323025076 +1.325002698529869 -4 6.315724947581107 +2.099977121673705 -4 4.489694354561609 +-2.09997712167371 -4 18.51030564543837 +-4.064385035125302 -4 11.99722748056721 +4.064385035125301 -4 11.99722748056721 +4.124973287377351 -4 16.65082604025666 +-4.050997849322331 -4 16.75261248096443 +-4.124973287377357 -4 6.349173959743325 +4.050997849322343 -4 6.247387519035538 +-0.9397330462932496 -4 3.450685895061419 +0.9397330462932638 -4 19.54931410493858 +2.327719197689181 -4 7.180234616899927 +-2.32756390239208 -4 15.81985468393597 +4.25854585654452 -4 19.92088382880742 +-4.258545856544514 -4 19.92088382880741 +-4.258545856544519 -4 3.079116171192581 +4.258545856544519 -4 3.07911617119258 +1.392087426032373 -4 11.45960662097293 +-1.190918590587339 -4 11.51470683216409 +-4.308541964481912 -4 10.66950471486521 +4.308541964481909 -4 10.66950471486521 +-0.6747297034593531 -4 8.277388820783717 +0.6747297034593389 -4 14.7226111792162 +4.302587095296525 -4 14.38637778986516 +-4.302587095296525 -4 14.38637778986517 +-4.325238566655598 -4 8.556890553137757 +4.325238566655594 -4 8.556890553137761 +0.3945612436352555 -4 21.79955850096629 +-0.3945612436352484 -4 1.200441499033704 +1.256853847465983 -4 2.82336952872343 +-1.256853847465986 -4 20.17663047127657 +-2.642055184671609 -4 21.85923114467454 +2.642055184671596 -4 1.140768855325463 +-2.632269584408983 -4 1.144858565282787 +2.632269584408984 -4 21.85514143471721 +-2.528206611991429 -4 7.077017858995776 +2.528206611991443 -4 15.92298214100421 +-0.6394765698175098 -4 14.58028918810515 +0.622669318224629 -4 8.437156736279317 +3.082750683290939 -4 14.38142775928772 +-3.02306149105469 -4 14.43512171568188 +-3.082750683290944 -4 8.618572240712231 +3.023061491054699 -4 8.564878284318077 +-0.4236008884082478 -4 12.56426092613496 +0.4693860375793122 -4 10.40658036454349 +4.449253023835837 -4 1.118808908413495 +-4.449253023835841 -4 1.118808908413491 +-4.44925302383584 -4 21.88119109158649 +4.449253023835837 -4 21.8811910915865 +-2.608023919396365 -4 4.350986670879911 +2.608023919396356 -4 18.64901332912009 +1.152718142657147 -4 17.21418732635999 +-1.152718142657134 -4 5.785812673639992 +0.2847967564885518 -4 18.58637872781626 +-0.2847967564885616 -4 4.413621272183753 +2.637439275361853 -4 10.41535054380003 +-2.642426676636713 -4 10.40904614851685 +-2.656153792166811 -4 12.61511366043472 +2.656153792166815 -4 12.61511366043472 +-4.430948190582666 -4 17.80871102752261 +4.43094819058267 -4 5.191288972477349 +4.371725234132025 -4 17.76455986129352 +-4.371725234132031 -4 5.235440138706466 +-1.064887087047639 -4 17.78713326045305 +1.06488708704762 -4 5.212866739546919 +-0.6960340986046658 -4 21.95672834406622 +0.6960340986046623 -4 1.043271655933778 +0.2869029297016334 -4 16.49864625464581 +-0.3501268619543838 -4 6.600508117736775 +-1.161709253975352 -4 9.300698452625458 +1.161918636457306 -4 13.77453721461338 +-1.340135769376252 -4 15.39656300420117 +1.332682336890922 -4 7.562239299719685 +-4.518434628122317 -4 12.9838709677419 +4.518434628122318 -4 12.9838709677419 +2.653852549422407 -4 2.239508055556572 +-2.653852549422416 -4 20.76049194444343 +-2.653852549422414 -4 2.239508055556566 +2.653852549422435 -4 20.76049194444343 +0.6010479783816711 -4 12.43945563685014 +-0.6007975200781956 -4 10.57651662080414 +-2.35406141763794 -4 13.56267359366075 +2.324569067016235 -4 13.58743848006015 +2.463476592176953 -4 9.416713722719464 +-2.406998291627495 -4 9.403095764930233 +4.465666574228834 -4 15.89526042413661 +-4.46566657422884 -4 7.104739575863361 +-4.52642618880731 -4 15.79868221228345 +4.526426188807321 -4 7.201317787716512 +3.245379637061474 -4 3.458014654773121 +-3.246217431330711 -4 3.37569304681429 +-3.245379637061474 -4 19.54198534522688 +3.246217431330722 -4 19.6243069531857 +4.51446968748478 -4 9.777418477656665 +-4.514469687484781 -4 9.777418477656674 +-1.050365957115366 -4 2.565760789851251 +1.050365957115377 -4 20.43423921014875 +2.980623160512467 -4 4.737608271008146 +-2.98062316051246 -4 18.26239172899184 +-1.223496053322032 -4 13.73219867448456 +0.9648283134061311 -4 9.446817800784176 +4.536328280169482 -4 2.203706200649135 +-4.536328280169486 -4 2.203706200649144 +-4.536328280169483 -4 20.79629379935085 +4.536328280169485 -4 20.79629379935086 +-4.410615960097567 -4 19.03822633917047 +-4.452212043124788 -4 3.966757448820375 +4.452212043124783 -4 19.03324255117963 +4.410615960097573 -4 3.961773660829512 +-3.321435528058009 -4 16.26624489759322 +3.321435528058018 -4 6.733755102406747 +3.690246983005586 -4 17.8773108147762 +-3.690246983005597 -4 5.122689185223787 +-0.02500622450735435 -4 19.66732281794236 +0.02500622450735168 -4 3.332677182057623 +3.397062431351028 -4 0.8988836913851648 +-3.396230322485166 -4 0.8992314558373149 +-3.397062431351033 -4 22.10111630861484 +3.39623032248516 -4 22.10076854416268 +1.71283875031043 -4 5.697660196828815 +-1.885746931974045 -4 17.24100180104984 +-1.685986843158416 -4 6.202979569273952 +1.685986843158413 -4 16.79702043072602 +1.572938097237903 -4 3.866177566537471 +-1.572938097237905 -4 19.13382243346252 +-1.388749388981863 -4 7.844885343959907 +1.390026154155767 -4 15.16244181002561 +0.7467212763781816 -4 15.50086216729126 +-0.6036873429276852 -4 7.38323676707992 +-3.251305913239118 -4 6.736384030255068 +3.251305913239111 -4 16.26361596974491 +-1.466666666666679 -4 0.8012481440655574 +1.466666666666681 -4 22.19875185593444 +-1.690692732206467 -4 3.834638983635003 +1.690692732206473 -4 19.16536101636499 +2.288177184970878 -4 18.05927572826099 +-2.288177184970889 -4 4.940724271739004 +-3.473373013124006 -4 10.86755214112411 +3.473373013124007 -4 10.86755214112411 +-3.616907265375277 -4 17.38361688586891 +3.616907265375291 -4 5.616383114131053 +2.004253698172044 -4 10.88601978766839 +1.976578049842288 -4 12.2135325970802 +-2.102469533182484 -4 10.84611326398405 +-2.053405392482508 -4 12.05264891029514 +1.389752332143325 -4 0.651162379383603 +-1.38975233214333 -4 22.3488376206164 +-0.6743369265812627 -4 21.20913487049192 +0.6743369265812538 -4 1.790865129508073 +2.659519861887665 -4 4.119270046219558 +-2.659519861887674 -4 18.88072995378043 +1.896315280034434 -4 20.54149363384958 +-1.896315280034426 -4 2.458506366150421 +2.578285503801768 -4 15.07047665534799 +-2.578285503801767 -4 7.929523344651987 +-4.720070559507564 -4 11.42979219131299 +4.720070559507564 -4 11.42979219131299 +-0.4377085301746595 -4 16.40069926378982 +0.3821391020684377 -4 6.141894233942294 +1.921073122790529 -4 2.475433202689397 +-1.921073122790536 -4 20.5245667973106 +-2.078100346547392 -4 16.56081605368584 +2.039202743569484 -4 6.451625389283667 +-3.364079219391363 -4 2.647559190069818 +3.364079219391357 -4 2.647559190069818 +-3.364079219391386 -4 20.35244080993018 +3.364079219391412 -4 20.35244080993019 +2.845464626542109 -4 7.826486212010908 +-2.845442441499657 -4 15.17352654525133 +4.810021995773148 -4 15.13975698409589 +-4.865428621289557 -4 7.790142232747137 +4.87410856622934 -4 7.803939120154732 +-4.85899961313679 -4 15.17768113509447 +-3.207676758579011 -4 12.17082151981421 +3.22698174781196 -4 12.17082151981422 +0.6495349141204443 -4 13.15583857603792 +0.7741644779250549 -4 17.90605798989799 +-0.7761255229377957 -4 5.111667994347816 +-0.4602344190762366 -4 18.30528441338461 +0.4602344190762144 -4 4.69471558661538 +-4.852799566099112 -4 13.67824884372508 +4.85279956609911 -4 13.67824884372508 +-0.707557033833635 -4 13.29371417597802 +0.9084698874312949 -4 6.959076403072514 +-4.823900311529745 -4 12.24193548387095 +4.823900311529737 -4 12.24193548387095 +-0.5956690182163253 -4 9.847478362606314 +0.001966315958023657 -4 8.632423604703188 +0.0005052038037014484 -4 14.35460270959825 +-0.6678083872109992 -4 17.13657549077365 +1.765737513882839 -4 9.239079029191611 +-1.267159535760237 -4 18.4781395919473 +1.26715953576023 -4 4.521860408052675 +4.752707471075974 -4 17.13505684565978 +-4.75270747107597 -4 17.13505684565974 +-4.752707471075972 -4 5.864943154340215 +4.752707471075977 -4 5.864943154340217 +-1.000079609669603 -4 4.214284211681837 +0.9822410816120151 -4 18.78356729423608 +1.090708777076655 -4 10.76878118453453 +-0.628580800516696 -4 11.85197809099878 +-0.05781036334025647 -4 22.35380838450465 +0.05781036334025913 -4 0.646191615495344 +-1.546786999881633 -4 3.1040692544968 +1.546786999881643 -4 19.8959307455032 +2.18751837438973 -4 22.36482965712857 +-2.187518374389726 -4 0.6351703428714152 +-1.64232078019793 -4 16.03024677950552 +2.221736709827447 -4 0.5910131667975973 +-2.221736709827458 -4 22.40898683320241 +1.634612523180638 -4 6.93894912907386 +4.952803333891534 -4 3.413293463100594 +-4.959736014396075 -4 3.414124094432405 +-4.95280333389154 -4 19.5867065368994 +4.959736014396071 -4 19.58587590556759 +-0.839324406620559 -4 1.793259185626594 +0.8393244066205652 -4 21.2067408143734 +-4.840123932555854 -4 9.113965380886711 +4.84012393255585 -4 9.113965380886711 +-0.7777218631182947 -4 0.6320016718254038 +0.7777218631183143 -4 22.36799832817459 +-3.865909505642446 -4 12.69514179936962 +3.865909505642433 -4 12.6951417993696 +-1.734765456379245 -4 9.639897758160673 +-4.874652983927389 -4 18.31524804470304 +4.870216699118021 -4 18.30085619624469 +-4.870216699118027 -4 4.699143803755299 +4.874652983927389 -4 4.684751955296933 +-3.502928382625863 -4 5.931287150891522 +3.502928382625857 -4 17.06871284910847 +4.8101518792901 -4 16.43798526049002 +4.773666021995059 -4 6.559414314154724 +-4.810151879290119 -4 6.562014739509955 +-4.773666021995052 -4 16.44058568584524 +-3.983352108613557 -4 11.29832786570383 +3.983352108613557 -4 11.29832786570383 +-2.001186503007445 -4 15.19147002979932 +2.001186503007488 -4 7.808529970200649 +3.669228656127984 -4 14.73936699133796 +3.593923923337544 -4 8.188416056738761 +-3.673003901354505 -4 8.251177732495826 +-3.590144980603948 -4 14.8021307933054 +-3.615145469484691 -4 14.02883872762236 +3.634115849299901 -4 8.920092531392598 +-3.65724404434211 -4 8.939501803417802 +3.620057523020161 -4 14.02068593395743 +-1.670975328451113 -4 5.410824789315776 +1.670975328451116 -4 17.58917521068422 +1.702373358323639 -4 13.39518716067976 +-1.276408864565517 -4 8.657752577335511 +2.825504198503346 -4 0.526133142701645 +-2.825504198503352 -4 22.47386685729836 +-2.816536989590112 -4 0.5358520727983035 +2.81653698959011 -4 22.4641479272017 +3.883718517408694 -4 16.02512775100291 +-3.883718517408685 -4 6.974872248997078 +-2.237808611656354 -4 21.27113416249951 +2.234363627736834 -4 21.27328757421606 +2.237808611656349 -4 1.728865837500501 +-2.234363627736832 -4 1.726712425783955 +0.08616760382559896 -4 21.25503900131506 +-0.0861676038255963 -4 1.744960998684936 +1.915126592273516 -4 15.67416557880739 +-1.915049043368385 -4 7.326279462129467 +-1.249491223634037 -4 12.17425335731347 +1.19936214621728 -4 12.20836678144897 +0.6052302134716534 -4 11.79369450455085 +-1.249491223634053 -4 10.82574664268648 +4.934833371731411 -4 10.758064516129 +-4.934833371731409 -4 10.758064516129 +-4.882754560976498 -4 1.63610957441469 +4.882754560976494 -4 1.636109574414692 +-4.882754560976495 -4 21.36389042558529 +4.882754560976496 -4 21.3638904255853 +3.914016954907721 -4 6.922406860451845 +-3.914016954907701 -4 16.07759313954812 +3.778252988210223 -4 19.33225604318403 +-3.788546078732152 -4 19.32803360891609 +-3.778252988210218 -4 3.667743956815961 +3.788546078732157 -4 3.671966391083909 +3.822728872886444 -4 10.27383038842373 +-3.822728872886446 -4 10.27383038842373 +0.5405806568856315 -4 14.0228431156338 +1.264985037164973 -4 14.41468222546488 +4.117921212469454 -4 13.52460919210249 +-4.117336444191423 -4 13.5255797627769 +3.119250887338843 -4 18.32351783519102 +-3.119250887338866 -4 4.676482164808939 +0.4189236930675424 -4 20.10784944874522 +-0.4189236930675211 -4 2.892150551254751 +-0.5157355180855649 -4 20.18431948055317 +0.5157355180855543 -4 2.815680519446804 +-0.03879860637667321 -4 7.975844364381981 +-0.03633639353648288 -4 15.12995984216476 +4.971660111387061 -4 14.41774792689723 +-5.002877254906485 -4 14.43555832793048 +2.112446676919746 -4 9.973023118434869 +-2.150355624084142 -4 13.01912123136082 +-0.9995988740707675 -4 15.9419322186718 +1.667475672182341 -4 3.217980485246835 +-1.667475672182342 -4 19.78201951475316 +-3.758881131588979 -4 17.93904098977603 +3.758881131588989 -4 5.060959010223931 +-3.078241899071477 -4 1.713612451276313 +3.060868258630407 -4 1.713449266002637 +-3.060868258630426 -4 21.28655073399737 +3.078241899071489 -4 21.2863875487237 +4.875248360602315 -4 22.3739395748724 +4.875248360602304 -4 0.6260604251276024 +-4.875248360602316 -4 22.3739395748724 +-4.875248360602308 -4 0.626060425127599 +-2.963103483183685 -4 13.79113169014535 +3.028383390209804 -4 9.204190274501006 +2.991150776943289 -4 13.77333857767224 +-3.032773237997973 -4 9.214104486272694 +-1.335264572811573 -4 14.8025456206235 +1.315177157911683 -4 8.199853068441724 +0.4694305562661443 -4 11.07041238302428 +-2.168779458561148 -4 10.02091691629131 +-0.9735427354604971 -4 6.393425121617845 +0.9630054134183812 -4 16.62310060711256 +0.5119501619883025 -4 17.1054206406924 +-0.4865535590845971 -4 5.918367775607644 +-0.5591166177360911 -4 8.996673628520345 +-0.7844198703179046 -4 15.22183010223188 +0.7616005509358095 -4 7.86376316103294 +0.26182571103696 -4 6.801720459809857 +3.97638688726609 -4 2.49478432677208 +-3.976386887266094 -4 2.494784326772087 +-3.976386887266105 -4 20.50521567322789 +3.976386887266145 -4 20.50521567322789 +0.03734798343550771 -4 12.99722445306683 +-0.6360299344358662 -4 13.97229736389308 +-2.468795236183676 -4 6.450549087872652 +2.468795236183663 -4 16.54945091212732 +0.9930751995574276 -4 10.04778770004666 +4.949535494121108 -4 2.777932844407815 +-4.948595510932021 -4 2.750301102039402 +4.948595510932019 -4 20.24969889796059 +-4.949535494121108 -4 20.22206715559217 +4.216702139850126 -4 1.696883712698763 +-4.216702139850131 -4 1.696883712698757 +-4.216702139850134 -4 21.30311628730121 +4.216702139850128 -4 21.30311628730122 +0.02384385786134935 -4 12.18456810628336 +-2.374066204463554 -4 17.76141621232624 +2.345248174186283 -4 5.228360787320171 +1.067347483100801 -4 3.36093099436439 +-1.067347483100802 -4 19.6390690056356 +-2.516872127257271 -4 3.723516466469821 +2.516872127257274 -4 19.27648353353016 +2.935176955008458 -4 7.214901709900838 +-2.935167715090749 -4 15.7851036034112 +-3.003148812766443 -4 7.476841878765331 +3.00314881276643 -4 15.52315812123464 +2.727477200642909 -4 20.11930808393078 +-2.778193811180222 -4 20.15479985251178 +2.778193811180184 -4 2.845200147488193 +-2.727477200642881 -4 2.880691916069193 +-5.006158224100202 -4 8.505102859160765 +5.007894213088157 -4 8.507862236642286 +-0.4000413767404112 -4 3.746057423727485 +0.3979177424478433 -4 19.2536868031675 +-0.6587886889280217 -4 11.19145455243899 +-3.205543831499862 -4 12.79649425856597 +3.209404829346449 -4 12.79649425856596 +1.004646269743176 -4 21.7788252454996 +-1.004646269743168 -4 1.221174754500394 +2.488373419813754 -4 14.2187617906958 +-2.431983084985819 -4 14.16489112877398 +2.488373419813759 -4 8.78123820930414 +-2.488373419813763 -4 8.781238209304137 +2.140203011733288 -4 12.95137203781907 +2.727478724349211 -4 6.621326618467282 +-2.712103009085223 -4 16.36414420432477 +-1.240223352212744 -4 20.79135208020767 +1.240223352212717 -4 2.208647919792307 +0.9454448873357011 -4 5.785404437688592 +-2.013155084375457 -4 1.197382549990885 +2.013155084375459 -4 21.80261745000912 +-0.03081673011146346 -4 10.0723402305696 +3.158223871472929 -4 18.96367300415914 +-3.158223871472943 -4 4.036326995840829 +4.043297354765544 -4 22.39636125056614 +-4.043297354765545 -4 22.39636125056613 +4.043297354765553 -4 0.6036387494338646 +-4.043297354765557 -4 0.6036387494338585 +-0.1084306282782466 -4 16.90207084021128 +0.510885009129221 -4 9.044539386163335 +2.843167605668313 -4 9.843992377988004 +-2.84470622736081 -4 9.850306654080622 +1.868434286704119 -4 1.183741589200371 +-1.868434286704126 -4 21.81625841079963 +-4.190617792224897 -4 9.215449273690178 +4.185992153216453 -4 9.211567419285135 +-4.215838174855632 -4 4.673582910280763 +4.215838174855625 -4 18.32641708971923 +4.059662333230062 -4 17.30329623902607 +-4.059662333230065 -4 5.696703760973932 +3.227625360659216 -4 6.096663408701354 +-3.325253137440712 -4 16.88483025998953 +0.7333333333333201 -4 0.4577259996222109 +-0.7333333333333201 -4 22.54227400037779 +-4.117456944581358 -4 15.29211626126707 +-4.174999913871769 -4 7.700365583027985 +4.159431399031803 -4 15.28516726594595 +4.124380172445566 -4 7.693789646782287 +-1.806735981799933 -4 13.92063026159463 +1.988634074992239 -4 15.09000478563331 +-1.988634074992256 -4 7.909995214366681 +-2.799534249707177 -4 13.1845576077866 +2.798244804479447 -4 13.17442803785068 +3.38164243112306 -4 11.48537500536616 +-3.363256727091677 -4 11.48537500536615 +4.951569004739621 -4 10.24744915463339 +-4.95156900473962 -4 10.24744915463339 +2.928927606257014 -4 17.62395033636339 +-2.928927606257028 -4 5.376049663636609 +-2.085774010515121 -4 4.334986912228953 +2.08577401051512 -4 18.66501308777104 +4.242100154173091 -4 4.650591950369381 +-4.242100154173086 -4 18.34940804963059 +3.189024408907761 -4 15.02295366714072 +-3.189779457953072 -4 7.975155277626013 +-2.194858567857966 -4 19.22236045496167 +2.194858567857948 -4 3.777639545038316 +1.176893015594146 -4 8.814714999013439 +-0.1871791258993554 -4 19.03368591169066 +0.186926312293088 -4 3.966283639130164 +-1.137725669726201 -4 12.79758252423263 +-1.672243635559524 -4 17.84359917824441 +1.698022133795654 -4 5.030088497262038 +-0.03605138427328569 -4 10.78792182941649 +-1.335500000811726 -4 17.29926235299934 +-2.851597055390914 -4 10.92748728836137 +2.81805384731649 -4 11.00923486461527 +2.601278209257114 -4 12.0472508996704 +-2.632385312811716 -4 12.08202243736504 +-4.947094892312538 -4 17.67027737247776 +4.947094892312526 -4 5.329722627522211 +-4.973541315043485 -4 5.358288568058477 +4.973541315043484 -4 17.64171143194153 +0.05475928182361223 -4 18.06819804811957 +-0.05475928182365131 -4 4.931801951880447 +4.140053366435771 -4 5.686783974036024 +-4.140053366435758 -4 17.31321602596394 +1.81388046752089 -4 13.98209298983183 +2.32012507830097 -4 17.26799314219581 +-2.32012507830098 -4 5.732006857804178 +0.1538319940278932 -4 15.89795566751897 +1.992077182830066 -4 16.19950754685371 +-1.992061673049039 -4 6.80058146133364 +-1.215728448469293 -4 9.877688282071276 +-0.5056189111368239 -4 17.74637244872494 +0.5056189111368106 -4 5.253627551275063 +5.032078146877693 -4 15.89384393624261 +-5.054373743338357 -4 7.078273320648909 +5.056775616678237 -4 7.086128617580799 +-5.050202817671773 -4 15.90140863552375 +-1.181162883447431 -4 21.74193032003522 +1.181162883447433 -4 1.258069679964767 +-5.0793181292995 -4 12.9838709677419 +5.079318129299507 -4 12.9838709677419 +3.212774264908505 -4 4.000309488833015 +-3.212774264908502 -4 18.99969051116699 +1.217638830102131 -4 13.15664224900591 +-2.441325780541173 -4 14.69626707207007 +2.442225508423416 -4 8.279708272605415 +-1.834886428785138 -4 9.046788615813162 +2.706626799842184 -4 3.562685039443377 +-2.7066267998422 -4 19.43731496055664 +0.1689669375931508 -4 1.238495225766014 +-0.1689669375931508 -4 21.76150477423398 +0.4782765042615909 -4 9.712078103744336 +-3.201246969255388 -4 10.36520645512072 +3.20124696925539 -4 10.36520645512073 +-5.056395977724418 -4 1.121920586241667 +5.056395977724417 -4 1.121920586241669 +5.056395977724419 -4 21.87807941375832 +-5.056395977724415 -4 21.87807941375832 +-0.4807855227165705 -4 2.252025914444915 +0.4807855227165838 -4 20.74797408555508 +1.046641321810277 -4 12.74148696933877 +5.080161615493811 -4 18.93587628124671 +-5.047614455583299 -4 18.95577811963845 +-5.080161615493816 -4 4.064123718753288 +5.0476144555833 -4 4.044221880361533 +-1.57112920640172 -4 13.28263145981682 +1.464297615992888 -4 9.771412476283313 +-3.77742021343633 -4 21.63836283184255 +3.777420213436324 -4 1.361637168157449 +-3.777420213436336 -4 1.361637168157442 +3.77742021343631 -4 21.63836283184255 +3.0836987269738 -4 5.440208054771292 +-3.076025527329862 -4 17.54014563907555 +3.726587535799117 -4 3.070288146778302 +-3.700262746750212 -4 3.066919651825781 +-3.726587535799126 -4 19.92971185322169 +3.700262746750237 -4 19.93308034817421 +2.255281749878439 -4 11.51914105824222 +-1.775359140438471 -4 11.4950725149608 +0.5292488671794597 -4 3.49284540051201 +-0.5292994299007159 -4 19.50714850965214 +-4.318157370104952 -4 12.47954393288742 +4.318157370104947 -4 12.47954393288741 +-1.235913414348623 -4 14.24450782747437 +-1.037554080343813 -4 10.30972569580302 +-1.405359022234721 -4 2.183104486406372 +1.405359022234721 -4 20.81689551359363 +0.7025464488138766 -4 16.11489667363444 +-0.8224068927214647 -4 6.830812833707724 +2 15 0 101 +2194 +2195 +2196 +2197 +2198 +2199 +2200 +2201 +2202 +2203 +2204 +2205 +2206 +2207 +2208 +2209 +2210 +2211 +2212 +2213 +2214 +2215 +2216 +2217 +2218 +2219 +2220 +2221 +2222 +2223 +2224 +2225 +2226 +2227 +2228 +2229 +2230 +2231 +2232 +2233 +2234 +2235 +2236 +2237 +2238 +2239 +2240 +2241 +2242 +2243 +2244 +2245 +2246 +2247 +2248 +2249 +2250 +2251 +2252 +2253 +2254 +2255 +2256 +2257 +2258 +2259 +2260 +2261 +2262 +2263 +2264 +2265 +2266 +2267 +2268 +2269 +2270 +2271 +2272 +2273 +2274 +2275 +2276 +2277 +2278 +2279 +2280 +2281 +2282 +2283 +2284 +2285 +2286 +2287 +2288 +2289 +2290 +2291 +2292 +2293 +2294 +-6.975809378287104 -3.349809867707239 2.184884888293978 +-7.263476628223464 -2.943477705995008 1.521464539222618 +-7.39726573385794 -2.63275803837525 2.035237743307004 +-7.447224216436836 -2.456418504140609 22.27940282082402 +-7.268081574049774 -2.934819526703241 22.58831918632284 +-7.399076719348205 -2.627301852404137 21.52358032521456 +-7.273296770584798 -2.924888405935293 22.07495632633341 +-7.007704950997249 -3.314087432684136 21.5719003828723 +-6.115395941539965 -3.902968164509365 1.539819345521561 +-5.950871238496276 -3.948516134471777 0.9869496894263309 +-6.515625297593695 -3.722935069840915 0.9401893597580425 +-6.746984416577325 -3.563659126796281 1.539675177542286 +-6.124760421987945 -3.899914317835792 22.04974410764576 +-6.392809786096171 -3.789662170872176 21.48857357153757 +-6.624690011848704 -3.653805423031307 21.9949370811842 +-6.955823867546449 -3.371341265579834 22.37928541030598 +-6.519935161827457 -3.720387242939216 22.41476713435782 +-7.401187486233547 -2.620875303252567 0.4302484315490926 +-7.409711859703322 -2.594138546896662 0.9885285451103873 +-7.09919849638001 -3.201067928626817 0.8400560407808019 +-6.839588132038802 -3.485093814040309 20.83045974847028 +-7.299304138002197 -2.873215104638126 21.00859981198638 +-6.364155221923522 -3.803672850719416 2.035447077292034 +-6.914213562373095 -3.414213562373095 20.03225806451612 +-6.177339380878351 -3.881810660802869 20.29617898812653 +-7.334025018603133 -2.797716886581811 20.39035523599539 +-6.914213562373096 -3.414213562373094 19.29032258064515 +-6.914213562373095 -3.414213562373095 18.54838709677418 +-7.344471753255671 -2.77325542445039 18.96080081273988 +-6.272702314913293 -3.844703535131766 18.87810984542666 +-7.342762066635902 -2.777321018478068 19.70361603584151 +-6.272702314913293 -3.844703535131767 19.62004532929763 +-6.914213562373096 -3.414213562373094 17.80645161290321 +-6.914213562373094 -3.414213562373096 17.06451612903224 +-7.344700219784153 -2.772710229729294 17.47673369592183 +-6.272702314913293 -3.844703535131767 17.39423887768471 +-7.344675817267993 -2.772768483561966 18.21869664992075 +-6.272702314913293 -3.844703535131767 18.13617436155569 +-6.914213562373095 -3.414213562373095 16.32258064516127 +-6.914213562373095 -3.414213562373095 15.5806451612903 +-7.34470348769769 -2.772702428154576 15.992857992571 +-6.272702314913293 -3.844703535131767 15.91036790994277 +-7.344703138571573 -2.772703261636825 16.73479407194114 +-6.272702314913292 -3.844703535131767 16.65230339381375 +-6.914213562373095 -3.414213562373095 14.83870967741933 +-6.914213562373096 -3.414213562373094 14.09677419354836 +-7.344703534453105 -2.772702316533489 14.50898693051261 +-6.272702314913293 -3.844703535131767 14.42649694220084 +-7.344703529457995 -2.77270232845852 15.25092242569483 +-6.272702314913293 -3.844703535131767 15.1684324260718 +-6.914213562373095 -3.414213562373095 13.35483870967739 +-6.914213562373094 -3.414213562373096 12.61290322580642 +-7.344703535122057 -2.772702314936474 13.02511596105501 +-6.272702314913297 -3.844703535131766 12.94262597445889 +-7.34470353505059 -2.77270231510709 13.76705144512631 +-6.272702314913293 -3.844703535131767 13.68456145832987 +-6.914213562373095 -3.414213562373095 11.87096774193545 +-7.344703535130606 -2.772702314916065 12.28318047715785 +-6.272702314913317 -3.844703535131757 12.2006904905879 +-6.914213562373096 -3.414213562373094 11.12903225806449 +-6.914213562373095 -3.414213562373095 10.38709677419352 +-7.34470353513175 -2.772702314913332 10.79930950941208 +-6.272702314914998 -3.844703535131053 10.71681952284453 +-7.344703535131629 -2.772702314913624 11.54124499328348 +-6.118931494477302 -3.901821181169274 20.96630658329613 +-6.272702314913497 -3.844703535131682 11.45875500671676 +-6.914213562373095 -3.414213562373095 9.645161290322557 +-6.914213562373095 -3.414213562373095 8.903225806451593 +-7.344703535131767 -2.772702314913293 9.315438541670085 +-6.272702315032518 -3.844703535081826 9.232948555030447 +-7.344703535131766 -2.772702314913297 10.05737402554106 +-6.272702314927554 -3.844703535125793 9.974884038964515 +-6.914213562373095 -3.414213562373095 8.161290322580628 +-7.344703535131767 -2.772702314913293 8.573503057799121 +-6.272702315910049 -3.84470353471425 8.491013070739383 +-6.914213562373093 -3.414213562373097 7.419354838709661 +-6.914213562373096 -3.414213562373094 6.677419354838699 +-7.344703535131767 -2.772702314913293 7.089632090057191 +-6.272702384580128 -3.84470350594999 7.007142086479333 +-7.344703535131767 -2.772702314913293 7.831567573928155 +-6.272702323246411 -3.844703531641223 7.749077584271248 +-6.914213562373095 -3.414213562373095 5.935483870967734 +-7.344703535131767 -2.772702314913293 6.347696606186227 +-6.272702897344318 -3.844703291165194 6.265206552585087 +-6.914213562373095 -3.414213562373095 5.193548387096767 +-7.344703535131767 -2.772702314913293 5.605761122315261 +-6.272707184167453 -3.844701495509776 5.523271215653572 +-6.914213562373095 -3.414213562373095 4.451612903225799 +-6.914213562373095 -3.414213562373095 3.709677419354832 +-7.344703535131767 -2.772702314913293 4.121890154573325 +-6.273042610316517 -3.844560956605942 4.039497875424597 +-7.344703535131767 -2.772702314913293 4.863825638444293 +-6.272743022593183 -3.844686483127567 4.78134177416002 +-6.914213562373095 -3.414213562373095 2.967741935483866 +-7.344703535131767 -2.772702314913293 3.379954670702358 +-6.275545098045783 -3.843510184646984 3.298683140557567 +-7.381810660802868 -2.677339380878354 2.703821011873451 +-6.289104591900564 -3.837746974706106 2.6075936694374 +-6.095640915447262 -3.909243803144362 22.62844584949131 +-6.740637427219093 -3.568699708096866 0.4260260070313455 +-6.179563889849486 -3.881008484726381 0.4303563382867571 +2 16 0 80 +2295 +2296 +2297 +2298 +2299 +2300 +2301 +2302 +2303 +2304 +2305 +2306 +2307 +2308 +2309 +2310 +2311 +2312 +2313 +2314 +2315 +2316 +2317 +2318 +2319 +2320 +2321 +2322 +2323 +2324 +2325 +2326 +2327 +2328 +2329 +2330 +2331 +2332 +2333 +2334 +2335 +2336 +2337 +2338 +2339 +2340 +2341 +2342 +2343 +2344 +2345 +2346 +2347 +2348 +2349 +2350 +2351 +2352 +2353 +2354 +2355 +2356 +2357 +2358 +2359 +2360 +2361 +2362 +2363 +2364 +2365 +2366 +2367 +2368 +2369 +2370 +2371 +2372 +2373 +2374 +-7.5 -1.035676089721354 0.9288091779290176 +-7.5 -1.000000000000003 22.02999844163939 +-7.5 -1 11.49999999999996 +-7.5 -1 7.048387096774182 +-7.5 -1 8.532258064516109 +-7.5 -1 10.01612903225804 +-7.5 -0.9798902939517933 2.584865721261228 +-7.5 -0.9999999999999993 5.564516129032249 +-7.5 -0.9999999999999999 4.080645161290315 +-7.5 -1 14.46774193548385 +-7.5 -0.9811948405704101 17.34651921729981 +-7.5 -1.01017766662396 19.69161687616492 +-7.5 -1 12.9838709677419 +-7.5 -0.9999999999999987 15.95161290322577 +-7.5 -1.011766073320285 20.96603259407187 +-7.5 -0.9991895884202429 18.47671093041408 +-7.5 -1.251947331063092 1.755191783096147 +-7.5 -1.359601410317264 16.681631385218 +-7.5 -1.293574401664929 9.274193548387075 +-7.5 -0.7064255983350638 6.306451612903218 +-7.5 -1.293574401664935 10.758064516129 +-7.5 -0.7064255983350629 7.790322580645144 +-7.5 -0.7064255983350738 13.72580645161287 +-7.5 -1.293574401664924 12.24193548387092 +-7.5 -0.706425598335067 3.338709677419348 +-7.5 -0.7064255983350602 15.20967741935481 +-7.5 -1.293574401664933 4.822580645161282 +-7.5 -0.616425597828798 20.3631173655619 +-7.5 -1.390814011918913 20.35738758829194 +-7.5 -1.406291809127396 7.790322580645143 +-7.5 -0.5937081908726048 10.758064516129 +-7.5 -1.406291809127396 6.306451612903215 +-7.5 -1.406291809127396 15.20967741935481 +-7.5 -1.406405358242446 3.338709677419349 +-7.5 -0.5937081908726028 4.822580645161282 +-7.5 -0.5937081908726031 9.274193548387075 +-7.5 -0.5937081908726021 12.24193548387093 +-7.5 -1.406291809127399 13.72580645161287 +-7.5 -0.6019286052525988 16.67516215562668 +-7.5 -1.37102364650592 19.11805906318403 +-7.5 -0.6352637281286256 19.13106447829383 +-7.5 -0.528964936593403 1.932891999215736 +-7.5 -1.38226240027749 17.93834735857878 +-7.5 -0.6340265579878355 17.92067968703233 +-7.5 -0.6307288383247195 21.67466541774155 +-7.5 -1.371335433669763 21.64570126697189 +-7.5 -1.436546132500867 0.577742714664173 +-7.5 -0.5634538674991405 22.42225728533581 +-7.5 -0.5261214810672994 0.5277592751942424 +-7.5 -1.436546132500861 22.42225728533581 +-7.5 -1.545613869984219 1.138170772925798 +-7.5 -0.5571183064075248 1.228409781174673 +-7.5 -0.431191467221643 7.048387096774182 +-7.5 -0.4311914672216521 11.49999999999996 +-7.5 -1.568808532778347 11.49999999999996 +-7.5 -1.568808532778357 7.048387096774182 +-7.5 -1.568808532778354 8.532258064516109 +-7.5 -1.568808532778352 10.01612903225804 +-7.5 -0.4311914672216457 8.532258064516109 +-7.5 -0.4311914672216481 10.01612903225804 +-7.5 -1.553808556055728 2.588643333572549 +-7.5 -0.4311914672216443 2.596774193548382 +-7.5 -1.568808532778355 5.564516129032249 +-7.5 -0.4311914672216448 5.564516129032248 +-7.5 -1.568808532778356 4.080645161290315 +-7.5 -0.4311914672216436 4.080645161290315 +-7.5 -1.568808532778362 14.46774193548385 +-7.5 -1.568808532778369 19.66129032258062 +-7.5 -0.4311914672216376 14.46774193548385 +-7.5 -0.4311914672216311 19.66129032258062 +-7.5 -0.4311914672216504 15.95161290322577 +-7.5 -0.4311914672216392 12.9838709677419 +-7.5 -1.568808532778361 12.9838709677419 +-7.5 -1.56880853277835 15.95161290322577 +-7.5 -0.4434300007621689 17.36266576037886 +-7.5 -1.544611730233033 17.36749314060641 +-7.5 -1.000000000000001 22.62480012584007 +-7.5 -0.9998792786654158 0.3755782693251747 +-7.5 -0.4574114405302651 21.0457923787918 +-7.5 -1.541919647014045 21.03294131575857 +2 17 0 1209 +2375 +2376 +2377 +2378 +2379 +2380 +2381 +2382 +2383 +2384 +2385 +2386 +2387 +2388 +2389 +2390 +2391 +2392 +2393 +2394 +2395 +2396 +2397 +2398 +2399 +2400 +2401 +2402 +2403 +2404 +2405 +2406 +2407 +2408 +2409 +2410 +2411 +2412 +2413 +2414 +2415 +2416 +2417 +2418 +2419 +2420 +2421 +2422 +2423 +2424 +2425 +2426 +2427 +2428 +2429 +2430 +2431 +2432 +2433 +2434 +2435 +2436 +2437 +2438 +2439 +2440 +2441 +2442 +2443 +2444 +2445 +2446 +2447 +2448 +2449 +2450 +2451 +2452 +2453 +2454 +2455 +2456 +2457 +2458 +2459 +2460 +2461 +2462 +2463 +2464 +2465 +2466 +2467 +2468 +2469 +2470 +2471 +2472 +2473 +2474 +2475 +2476 +2477 +2478 +2479 +2480 +2481 +2482 +2483 +2484 +2485 +2486 +2487 +2488 +2489 +2490 +2491 +2492 +2493 +2494 +2495 +2496 +2497 +2498 +2499 +2500 +2501 +2502 +2503 +2504 +2505 +2506 +2507 +2508 +2509 +2510 +2511 +2512 +2513 +2514 +2515 +2516 +2517 +2518 +2519 +2520 +2521 +2522 +2523 +2524 +2525 +2526 +2527 +2528 +2529 +2530 +2531 +2532 +2533 +2534 +2535 +2536 +2537 +2538 +2539 +2540 +2541 +2542 +2543 +2544 +2545 +2546 +2547 +2548 +2549 +2550 +2551 +2552 +2553 +2554 +2555 +2556 +2557 +2558 +2559 +2560 +2561 +2562 +2563 +2564 +2565 +2566 +2567 +2568 +2569 +2570 +2571 +2572 +2573 +2574 +2575 +2576 +2577 +2578 +2579 +2580 +2581 +2582 +2583 +2584 +2585 +2586 +2587 +2588 +2589 +2590 +2591 +2592 +2593 +2594 +2595 +2596 +2597 +2598 +2599 +2600 +2601 +2602 +2603 +2604 +2605 +2606 +2607 +2608 +2609 +2610 +2611 +2612 +2613 +2614 +2615 +2616 +2617 +2618 +2619 +2620 +2621 +2622 +2623 +2624 +2625 +2626 +2627 +2628 +2629 +2630 +2631 +2632 +2633 +2634 +2635 +2636 +2637 +2638 +2639 +2640 +2641 +2642 +2643 +2644 +2645 +2646 +2647 +2648 +2649 +2650 +2651 +2652 +2653 +2654 +2655 +2656 +2657 +2658 +2659 +2660 +2661 +2662 +2663 +2664 +2665 +2666 +2667 +2668 +2669 +2670 +2671 +2672 +2673 +2674 +2675 +2676 +2677 +2678 +2679 +2680 +2681 +2682 +2683 +2684 +2685 +2686 +2687 +2688 +2689 +2690 +2691 +2692 +2693 +2694 +2695 +2696 +2697 +2698 +2699 +2700 +2701 +2702 +2703 +2704 +2705 +2706 +2707 +2708 +2709 +2710 +2711 +2712 +2713 +2714 +2715 +2716 +2717 +2718 +2719 +2720 +2721 +2722 +2723 +2724 +2725 +2726 +2727 +2728 +2729 +2730 +2731 +2732 +2733 +2734 +2735 +2736 +2737 +2738 +2739 +2740 +2741 +2742 +2743 +2744 +2745 +2746 +2747 +2748 +2749 +2750 +2751 +2752 +2753 +2754 +2755 +2756 +2757 +2758 +2759 +2760 +2761 +2762 +2763 +2764 +2765 +2766 +2767 +2768 +2769 +2770 +2771 +2772 +2773 +2774 +2775 +2776 +2777 +2778 +2779 +2780 +2781 +2782 +2783 +2784 +2785 +2786 +2787 +2788 +2789 +2790 +2791 +2792 +2793 +2794 +2795 +2796 +2797 +2798 +2799 +2800 +2801 +2802 +2803 +2804 +2805 +2806 +2807 +2808 +2809 +2810 +2811 +2812 +2813 +2814 +2815 +2816 +2817 +2818 +2819 +2820 +2821 +2822 +2823 +2824 +2825 +2826 +2827 +2828 +2829 +2830 +2831 +2832 +2833 +2834 +2835 +2836 +2837 +2838 +2839 +2840 +2841 +2842 +2843 +2844 +2845 +2846 +2847 +2848 +2849 +2850 +2851 +2852 +2853 +2854 +2855 +2856 +2857 +2858 +2859 +2860 +2861 +2862 +2863 +2864 +2865 +2866 +2867 +2868 +2869 +2870 +2871 +2872 +2873 +2874 +2875 +2876 +2877 +2878 +2879 +2880 +2881 +2882 +2883 +2884 +2885 +2886 +2887 +2888 +2889 +2890 +2891 +2892 +2893 +2894 +2895 +2896 +2897 +2898 +2899 +2900 +2901 +2902 +2903 +2904 +2905 +2906 +2907 +2908 +2909 +2910 +2911 +2912 +2913 +2914 +2915 +2916 +2917 +2918 +2919 +2920 +2921 +2922 +2923 +2924 +2925 +2926 +2927 +2928 +2929 +2930 +2931 +2932 +2933 +2934 +2935 +2936 +2937 +2938 +2939 +2940 +2941 +2942 +2943 +2944 +2945 +2946 +2947 +2948 +2949 +2950 +2951 +2952 +2953 +2954 +2955 +2956 +2957 +2958 +2959 +2960 +2961 +2962 +2963 +2964 +2965 +2966 +2967 +2968 +2969 +2970 +2971 +2972 +2973 +2974 +2975 +2976 +2977 +2978 +2979 +2980 +2981 +2982 +2983 +2984 +2985 +2986 +2987 +2988 +2989 +2990 +2991 +2992 +2993 +2994 +2995 +2996 +2997 +2998 +2999 +3000 +3001 +3002 +3003 +3004 +3005 +3006 +3007 +3008 +3009 +3010 +3011 +3012 +3013 +3014 +3015 +3016 +3017 +3018 +3019 +3020 +3021 +3022 +3023 +3024 +3025 +3026 +3027 +3028 +3029 +3030 +3031 +3032 +3033 +3034 +3035 +3036 +3037 +3038 +3039 +3040 +3041 +3042 +3043 +3044 +3045 +3046 +3047 +3048 +3049 +3050 +3051 +3052 +3053 +3054 +3055 +3056 +3057 +3058 +3059 +3060 +3061 +3062 +3063 +3064 +3065 +3066 +3067 +3068 +3069 +3070 +3071 +3072 +3073 +3074 +3075 +3076 +3077 +3078 +3079 +3080 +3081 +3082 +3083 +3084 +3085 +3086 +3087 +3088 +3089 +3090 +3091 +3092 +3093 +3094 +3095 +3096 +3097 +3098 +3099 +3100 +3101 +3102 +3103 +3104 +3105 +3106 +3107 +3108 +3109 +3110 +3111 +3112 +3113 +3114 +3115 +3116 +3117 +3118 +3119 +3120 +3121 +3122 +3123 +3124 +3125 +3126 +3127 +3128 +3129 +3130 +3131 +3132 +3133 +3134 +3135 +3136 +3137 +3138 +3139 +3140 +3141 +3142 +3143 +3144 +3145 +3146 +3147 +3148 +3149 +3150 +3151 +3152 +3153 +3154 +3155 +3156 +3157 +3158 +3159 +3160 +3161 +3162 +3163 +3164 +3165 +3166 +3167 +3168 +3169 +3170 +3171 +3172 +3173 +3174 +3175 +3176 +3177 +3178 +3179 +3180 +3181 +3182 +3183 +3184 +3185 +3186 +3187 +3188 +3189 +3190 +3191 +3192 +3193 +3194 +3195 +3196 +3197 +3198 +3199 +3200 +3201 +3202 +3203 +3204 +3205 +3206 +3207 +3208 +3209 +3210 +3211 +3212 +3213 +3214 +3215 +3216 +3217 +3218 +3219 +3220 +3221 +3222 +3223 +3224 +3225 +3226 +3227 +3228 +3229 +3230 +3231 +3232 +3233 +3234 +3235 +3236 +3237 +3238 +3239 +3240 +3241 +3242 +3243 +3244 +3245 +3246 +3247 +3248 +3249 +3250 +3251 +3252 +3253 +3254 +3255 +3256 +3257 +3258 +3259 +3260 +3261 +3262 +3263 +3264 +3265 +3266 +3267 +3268 +3269 +3270 +3271 +3272 +3273 +3274 +3275 +3276 +3277 +3278 +3279 +3280 +3281 +3282 +3283 +3284 +3285 +3286 +3287 +3288 +3289 +3290 +3291 +3292 +3293 +3294 +3295 +3296 +3297 +3298 +3299 +3300 +3301 +3302 +3303 +3304 +3305 +3306 +3307 +3308 +3309 +3310 +3311 +3312 +3313 +3314 +3315 +3316 +3317 +3318 +3319 +3320 +3321 +3322 +3323 +3324 +3325 +3326 +3327 +3328 +3329 +3330 +3331 +3332 +3333 +3334 +3335 +3336 +3337 +3338 +3339 +3340 +3341 +3342 +3343 +3344 +3345 +3346 +3347 +3348 +3349 +3350 +3351 +3352 +3353 +3354 +3355 +3356 +3357 +3358 +3359 +3360 +3361 +3362 +3363 +3364 +3365 +3366 +3367 +3368 +3369 +3370 +3371 +3372 +3373 +3374 +3375 +3376 +3377 +3378 +3379 +3380 +3381 +3382 +3383 +3384 +3385 +3386 +3387 +3388 +3389 +3390 +3391 +3392 +3393 +3394 +3395 +3396 +3397 +3398 +3399 +3400 +3401 +3402 +3403 +3404 +3405 +3406 +3407 +3408 +3409 +3410 +3411 +3412 +3413 +3414 +3415 +3416 +3417 +3418 +3419 +3420 +3421 +3422 +3423 +3424 +3425 +3426 +3427 +3428 +3429 +3430 +3431 +3432 +3433 +3434 +3435 +3436 +3437 +3438 +3439 +3440 +3441 +3442 +3443 +3444 +3445 +3446 +3447 +3448 +3449 +3450 +3451 +3452 +3453 +3454 +3455 +3456 +3457 +3458 +3459 +3460 +3461 +3462 +3463 +3464 +3465 +3466 +3467 +3468 +3469 +3470 +3471 +3472 +3473 +3474 +3475 +3476 +3477 +3478 +3479 +3480 +3481 +3482 +3483 +3484 +3485 +3486 +3487 +3488 +3489 +3490 +3491 +3492 +3493 +3494 +3495 +3496 +3497 +3498 +3499 +3500 +3501 +3502 +3503 +3504 +3505 +3506 +3507 +3508 +3509 +3510 +3511 +3512 +3513 +3514 +3515 +3516 +3517 +3518 +3519 +3520 +3521 +3522 +3523 +3524 +3525 +3526 +3527 +3528 +3529 +3530 +3531 +3532 +3533 +3534 +3535 +3536 +3537 +3538 +3539 +3540 +3541 +3542 +3543 +3544 +3545 +3546 +3547 +3548 +3549 +3550 +3551 +3552 +3553 +3554 +3555 +3556 +3557 +3558 +3559 +3560 +3561 +3562 +3563 +3564 +3565 +3566 +3567 +3568 +3569 +3570 +3571 +3572 +3573 +3574 +3575 +3576 +3577 +3578 +3579 +3580 +3581 +3582 +3583 +7.401076913216227 1.214108942664443 21.59477149482386 +7.471582895414296 0.6522645452211328 22.00397163583777 +7.372335652692747 1.377921269171575 22.20291518406499 +7.470203315816426 0.6678790462091714 21.42360093163208 +-7.401076913575033 1.214108940477197 1.405228504860977 +-7.471582895461806 0.6522645446769135 0.9960283639388922 +-7.372335652796974 1.377921268613927 0.7970848154936697 +-7.470203320803431 0.6678789904296961 1.576399037789711 +-4.079403759283815 6.293525638999262 17.58915743837292 +-3.606802252963565 6.575787215840926 17.16210589566045 +-3.40358614347796 6.683232852738622 17.66986817064408 +-4.066678570659632 6.301755739707604 16.91645614845351 +6.798391807858584 3.167312555912551 3.164306582610129 +7.006842696586411 2.674725299034215 3.087120368529376 +6.96462665961861 2.782799937496354 3.855956028480468 +7.16352410216152 2.221243444053574 3.327950418085569 +-1.770471064500799 7.288033494006831 3.554103926919403 +-1.183166009066482 7.406086564103183 3.583762465003015 +-1.356935927944257 7.376227008942584 4.395269429164126 +-7.091454152775726 2.441572853526985 22.0086461598478 +-6.89293885702564 2.955908305970613 21.66646330330654 +-6.845628897990703 3.063880707696467 22.38100699442541 +-6.643476954424073 3.480547939051586 21.99347891579425 +7.091455684572479 2.441568404477885 0.9913512245500116 +6.89293661727195 2.955913528889424 1.333527567938689 +6.845631142338081 3.063875693146023 0.6189894027285577 +6.643483121871398 3.480536166944665 1.006506276949551 +-7.463983939245271 0.734127887148175 18.09998537439131 +-7.377906615115964 1.347773711951714 17.72850988705793 +-7.364673799129379 1.418301742372629 18.46621566387594 +-7.241836859163897 1.950845689760007 18.27135380514611 +7.464640654054436 0.7274200339815815 4.89976340162851 +7.381805372481996 1.326253913395146 5.271234647200382 +7.379509752983011 1.338968186936729 4.561576820538178 +7.268636552314573 1.84849199899716 4.748807243331169 +7.421324966707068 1.083483151013594 20.08229760795668 +7.481193185600701 0.5307998867008562 19.77557542695067 +7.483731713707017 0.493720201385196 20.38387502754338 +-7.421325057012396 1.083482532466464 2.91770214098571 +-7.481193284915673 0.5307984869351483 3.224423941551358 +-7.483731714732439 0.4937201858420052 2.616124966406503 +-0.6472133266341946 7.472022143290737 3.850489814082602 +-6.583580438720082 3.592557390898898 20.36172823576429 +-6.711333330447679 3.347835857329639 20.87018061142659 +-6.868748598188211 3.011692662754201 20.37452226691087 +6.596411519502166 3.568943130028708 2.63362659230272 +6.891999886567264 2.958096949654762 2.572642379824656 +6.68268210194518 3.404667373524402 2.175664730106361 +7.486770111849532 0.4452788927363894 15.31511448591297 +7.479663720346173 0.5519335381522349 15.909516009143 +3.96704848499606 6.364945115057196 20.87634316769223 +4.698629544192471 5.845757470716831 20.82040315105087 +4.094836192836809 6.283495568060324 21.49460869229841 +4.625295037515281 5.903951711856772 21.66271672359922 +-7.292690749410543 1.751188634460001 5.840169729418735 +-7.269873644204218 1.843620676089551 5.248934298295101 +-7.108516211823162 2.391442507409971 5.903583136266629 +-6.534496109835128 3.681081443074792 22.53337208795887 +6.534499237341716 3.681075891255235 0.4666210238107668 +-7.036178692672394 2.596572626518082 5.121376793341907 +-7.075599186363292 2.48714618668367 4.377769501528922 +-6.842511361216254 3.070836738028657 4.485180015429218 +-7.213869894043723 2.051848228259003 4.721037118074527 +-6.811152052720609 3.139778290695035 18.28187713259567 +-6.867650201783344 3.014196527425708 18.95007065634515 +-7.036826238090256 2.594817237287539 18.36235564400798 +-7.146100471907206 2.276674778137538 20.53872653824791 +-6.997866982266742 2.698121142295312 19.9489677408111 +-6.918851444195181 2.894735686234282 21.00127715632025 +7.146091543974791 2.276702801230761 2.461289969638228 +6.927188656854334 2.874727345740576 1.992977095442321 +-6.622613561795888 3.520083750582816 18.6008806060653 +-2.059552505273984 7.211674110636146 22.35490888642593 +-1.529123031437816 7.342464351614275 22.07249142731902 +-1.037916666956091 7.427834744557445 22.40925484439483 +-6.949905507492123 2.81936401284592 1.449333235627912 +-7.048368447984938 2.563299089347634 0.9745428704898845 +-6.797164673108469 3.169945174075766 1.013333879511384 +7.430577182280135 1.018097607392243 2.110708968990606 +7.387495015423753 1.294185997872489 1.552717773434733 +7.463832388985904 0.7356670912341887 1.465791221007012 +-7.12623566377155 2.338111473901631 1.664462348129522 +7.427927376324113 1.037253533160913 20.88720454811788 +6.876018916849546 2.995056569603853 4.615240483970882 +7.094233391462685 2.433485686716863 4.612874411391157 +-7.430577266342768 1.018096993861605 20.8892909847798 +-7.387495015401732 1.29418599799819 21.44728222656389 +-7.463832388981793 0.7356670912758964 21.53420877898131 +-7.481025917692381 0.5331521535311032 15.85640059776384 +-7.485510365003774 0.4659770116873412 15.22093048877125 +-7.427927408548812 1.037253302394997 2.112795388636725 +6.949905503444849 2.819364022822699 21.55066675981146 +7.052157190425851 2.552857019404917 22.02256855341559 +6.821557700616575 3.117106115800153 21.9606417016367 +7.126235486185588 2.33811201515865 21.33553720066771 +7.075140215024947 2.488451514041762 0.4323913886509858 +-3.506294202196658 6.629924657765131 3.863702163050854 +-3.088070414067449 6.834750991642731 3.280351687560465 +-2.918284629478398 6.908951788900406 3.992367496107299 +-7.026450823973278 2.622782647930486 0.4079848458900042 +-6.851132666862718 3.051553896139891 0.5246776720624174 +1.839393324614625 7.270944381396625 3.630606369646802 +1.400522972214081 7.368075420644161 3.040337163263116 +2.260894525796256 7.151108721256064 3.015410739877231 +-7.075140215655197 2.488451512249844 22.56760861125016 +1.790654264819224 7.283100802809523 2.446417898047414 +7.026450824126901 2.622782647518927 22.59201515396139 +6.833882649408572 3.089991575087621 22.48181182280146 +3.021880971233936 6.864272386472892 3.332687154012997 +2.848674524548912 6.937943027525236 2.625927637730888 +-7.48801495022408 0.423830278791738 1.993782413738847 +2.322313408939204 7.13139961232444 2.107534003852923 +-7.486259845603642 0.4537769541333523 21.03528291855435 +-7.483559509908783 0.496323545334903 20.40104323581954 +-4.091514596031903 6.28565894003627 18.89427987786202 +-4.542983861857291 5.967520224591134 18.85496244156296 +-4.497119207716144 6.002159514007481 18.13215942872943 +7.488014945361123 0.4238303647079241 21.00621756652106 +6.678339656180992 3.413177322771312 4.23506424210927 +7.486259834653905 0.453777134778402 1.964717115664665 +7.483559510033762 0.4963235434504841 2.598956764322738 +-4.573037417981181 5.944520903634205 1.283736355032258 +-4.854898230209379 5.71663915026214 2.111872294166868 +-5.132537901865223 5.468734285546971 1.374793177825503 +7.279808315889284 1.803993038764077 0.5608413393379251 +-7.220784935941272 2.02737882717651 0.5971824956823634 +7.258217039184072 1.888990580203614 21.76427157912073 +7.220784935924633 2.027378827235769 22.40281750433738 +-7.279808315955767 1.803993038495783 22.43915866062178 +-7.26201844935345 1.874323355573986 21.71937022260926 +-7.258217040196272 1.888990576314364 1.235728420158533 +7.26201845015902 1.87432335245282 1.280629776877549 +-7.478890668721602 0.5623116265105439 22.27394681134179 +7.478890668721523 0.5623116265116067 0.7260531886565814 +7.415255880619151 1.124268751208134 2.91197915770069 +-7.415256806988971 1.124262641202547 20.08802122674853 +-5.348972575922656 5.257232388056225 2.114858296790885 +-7.485093703587271 0.4726227338143925 7.615098568030009 +-7.47899320495877 0.5609462007898319 7.052091789726827 +6.026885720272194 4.463927476424669 2.014929083220277 +5.703760142704565 4.870022611291945 2.166291453219624 +5.679154495747222 4.898694133484364 1.377969306545528 +-2.52986531975945 7.060437767155689 2.211522094656341 +-2.054765271272209 7.213039559019044 2.900271090938117 +-2.703731303848226 6.995701325570666 2.835736566532589 +5.376307046772891 5.229275527147155 2.066907083517396 +7.292032817605318 1.753926277517686 1.931967741117328 +7.290203999748091 1.761512316748578 21.13075850322643 +-7.283050682044835 1.790858107937718 21.0829020696928 +-7.290204154363512 1.761511676856265 1.86924147214249 +-2.411721293475946 7.101661805703979 3.500942892687639 +4.518642157130909 5.985973024980928 18.23130667311713 +4.679383438142933 5.861174851412779 18.89522383160804 +4.049226673276684 6.31298371203543 18.93094116488912 +-7.088464822991742 2.450238040111339 21.33387251570498 +7.132230527041301 2.319760269756373 1.671778586849282 +7.474846665535056 0.6137322924039887 10.10115788182096 +7.486094839800026 0.4564910180051852 9.379006007052546 +-3.729859565257037 6.506777053462074 20.39552935203831 +-4.284683292429559 6.155606313237958 20.25568255610982 +-3.935781919493166 6.384326172916817 19.73079366269622 +-4.496128778299558 6.002901465870194 19.53259578429872 +-1.259626544266144 7.393466099805972 1.311351512419869 +-1.249754061688186 7.395141295830248 0.587760098498319 +-0.7143307451252988 7.465904606045321 0.9145661991093925 +-1.776655838450368 7.286528256426392 1.074488301497988 +-3.578082566612765 6.591458499186793 13.47959311412147 +-3.058014680633167 6.848251325194777 13.37802754102836 +-3.135264198474527 6.813231128162604 14.07050641925661 +6.549196070100495 3.654863996837672 17.07193682087814 +6.546626903793464 3.659463920101905 17.8889946656573 +6.201240551747675 4.218366463378945 17.28749781817154 +6.569203513858411 3.618779517117658 6.927157668228594 +6.892241918681587 2.957532981112528 7.43492629809378 +6.606181925419512 3.550825308046083 7.565807178869854 +5.886062449449477 4.64803924694928 7.078903876902828 +6.221734769191565 4.188080283594475 6.853109623290182 +6.26175828642028 4.127999898552198 7.368312237778571 +-6.867452694045486 3.014646495867698 5.779080698091024 +-6.784065573751929 3.197882782566289 5.235683040786003 +-4.534353790897963 5.974080322440374 4.870157438964406 +-4.864288330286373 5.708651245245222 4.323036756411452 +-4.253924014405555 6.17690298447885 4.135927428735802 +-5.222300956778406 5.383082083419437 5.048668887144255 +-3.896775912231935 6.408208602242047 22.46550999064943 +-3.706206773991949 6.520278471692462 21.92434194781064 +-3.32094400812805 6.724680728099915 22.42924045215066 +-4.180036365770015 6.22714187897146 22.00674185690294 +7.478370239868651 0.5691911413988315 6.359099671139 +6.158535694187212 4.280471715059223 19.70517255271147 +6.269848072221111 4.115702267082158 18.98193005650109 +6.515647081943509 3.714342889874469 19.29493488698393 +5.889372266739523 4.643844776019045 19.14524672012823 +-7.465535363544324 0.7181794592364156 6.372676008475459 +-7.272394195295735 1.833652821072978 6.426927109910904 +-7.390980481601693 1.274130103475625 6.113349768450509 +7.469941721189086 0.6707985405758193 16.63242599376103 +7.43227406284745 1.005635249344946 22.55212840245453 +-7.389150968098578 1.284697618370893 6.83451037416526 +-7.464878195559031 0.7249782931008036 16.62660862256462 +-7.432274062852095 1.00563524931061 0.447871597508918 +-7.397645261722264 1.23484597489652 22.02784135014478 +-7.411343323827214 1.149778298787106 22.54968129004522 +7.397645261850622 1.234845974127563 0.9721586495570208 +7.411343323827268 1.149778298786767 0.450318709846846 +-3.464922293323072 6.651639910671111 19.31794255039647 +-3.301135971836171 6.734426575102683 19.92727423280531 +3.637923376945935 6.558621311180444 1.080140605588242 +3.115201918502053 6.822427501041044 1.21730710287793 +3.288365093464816 6.740671703330621 0.6204069639360369 +4.568375380990149 5.948104435731026 22.40395670726737 +5.000610774138231 5.589623590687716 22.55043589601816 +-4.489852566937034 6.007597184163477 0.5480233018045276 +-4.950594776327231 5.633969414240864 0.6342035815604072 +1.618638305259999 7.323251329617538 1.783309279424435 +3.578235626832937 6.591375410251149 1.586718168165415 +-6.921837916114148 2.887587204405185 17.74093666218088 +-6.706003186025001 3.358499853956011 7.634097513631388 +-6.635091426606897 3.496507080011087 8.392974676616292 +-6.883049071652684 2.978864796734005 8.016463576011445 +-6.428805877591389 3.862700478712583 7.81171348470211 +-2.438875576724599 7.092382245850561 13.63752536705269 +-0.221454457220865 7.496729815284596 17.30891648188507 +0.416703323467254 7.488414941775819 17.25986884494804 +0.2322387646034558 7.49640348141797 17.85952405842923 +0.1076570577346965 7.499227290722685 16.66663828102534 +-0.0398572034549795 7.499894092807761 3.384763331344351 +0.7350995824373892 7.463888303284044 3.353532551642843 +0.4831980210004456 7.484418459205849 3.813229573772259 +5.020350373648579 5.571901123118263 0.6550229615980252 +5.250473392814848 5.355607262612088 1.382859542004812 +4.749301008758633 5.804665358847505 1.379933674922 +0.5909184341931012 7.476684786998231 2.823705491789084 +-5.044194449374356 5.550324527169646 22.33524750093194 +-5.282865514932552 5.323657760519211 21.73161093001905 +-4.697777023299854 5.846442596943544 21.74503531587008 +-5.558658065213543 5.035009484999648 10.39173888385826 +-5.971368313010667 4.537924687604691 10.82223296915977 +-5.982903041763935 4.522706180247822 10.25804707149332 +5.214074745823544 5.391050412022238 21.49264630972416 +4.969570087462243 5.617238925468678 22.03838422891095 +-5.654320211886434 4.927338322203229 11.2567810117617 +7.484436024085531 0.4829258756483973 22.55046204054303 +-7.484436024085534 0.4829258756483497 0.4495379594569371 +-2.250636046660678 7.154343952136464 15.96975013951739 +-2.486849788288884 7.075703366485026 16.59865741442573 +-3.031481774499694 6.860037773283481 16.22422089815205 +-1.87803144770009 7.261060382716115 16.52387731383839 +5.004069495240189 5.586527408579197 4.170389860349037 +4.621079577777036 5.907251775221029 4.679263331288322 +4.5523981414103 5.960341530657789 3.857865266670864 +5.170909404144981 5.432466836909821 4.633403655277237 +-7.198302646312528 2.105810773096687 15.94148198644103 +-7.036931377852501 2.594532093344559 16.23034381355394 +-7.226418213074899 2.007206967340287 16.60719702093089 +7.409864677556326 1.159269364860078 16.97078166845905 +7.310490122691738 1.675331061619329 16.86607669628866 +7.396074480727366 1.244219544748202 16.18489114472336 +-6.982976842998909 2.736427307666147 16.70891527440495 +-7.067674617496461 2.509576757382855 17.21820027450271 +1.528633561536717 7.342566270354226 8.063758687410854 +2.057892425574546 7.212147999366271 8.649577067804703 +1.29892013171851 7.386664097643561 8.791865783682105 +2.308603274673984 7.135849698540782 7.937865894496078 +6.578558232423548 3.601745629915079 16.39005053953457 +6.839856344332761 3.076745876553811 16.13678679502764 +6.871581737607245 3.005222857523647 16.75968930979607 +-6.760669379534438 3.24705243884749 16.2730939164267 +5.927265774769878 4.595380336298797 18.54106837676033 +6.073742331025095 4.399960692587362 17.91446858173045 +6.305710096534863 4.06054432046472 18.38845057741116 +-6.206564725491701 4.210528982002396 4.158039200280873 +-5.823830219133366 4.725780525871786 4.279321846607322 +-6.190453075280339 4.234181234046576 4.697811060270207 +7.364752929557436 1.417890787957654 8.984579557440764 +7.430637599774925 1.017656553465436 9.478827249987368 +7.313075739363082 1.664008182173127 9.583965961940258 +-5.979087166695605 4.527749623494646 3.765583256075485 +6.458592782064756 3.812686621722409 14.34190855136102 +6.357789488032745 3.978506356141752 14.94176468257408 +6.131666223375079 4.318873617637033 14.54489482029659 +6.653473427079717 3.461400201528867 14.89663801131108 +3.482459014420568 6.642475382933754 2.655941395247562 +3.690774700472167 6.529026122658308 3.17020297022712 +2.932974270859471 6.90272858560123 22.54560261007887 +3.5898658446363 6.585048459769578 22.42604025470909 +-0.8909650255962794 7.446890715135023 21.66855750476331 +-1.569417430159973 7.333957248982985 21.50961918024466 +-6.517750637432769 3.710650431965362 5.75914357584866 +-6.532450448764815 3.684710454626299 4.984688567213681 +-7.133501598296158 2.315848645120436 12.2429143359828 +-7.135264328773087 2.310411859071526 11.62223222517583 +-6.853391689818167 3.046477038471042 11.92587114206054 +3.126696909872428 6.817167038718813 13.60281408225577 +3.403962836919681 6.68304099978967 13.0999841346265 +3.620672239064339 6.568160513969556 13.65788278912474 +-6.652783674084843 3.462725716228502 3.226915993525613 +-6.732155103314142 3.305765821246471 3.799079498921113 +-6.91697637123729 2.899213320841538 3.203212976443693 +-6.998019727575095 2.697724947519631 3.838378655274812 +7.059191910283588 2.533339608853646 18.36008458254256 +7.194243226492132 2.119637798793011 18.97779757243539 +6.930382879751725 2.867018161791827 18.76520348691943 +6.858735729049523 3.034426502497548 19.26846563247712 +7.48563900914828 0.4639058360460163 18.09236615015199 +7.468710229542501 0.6843738065759118 17.46303853516823 +-5.879176988128276 4.6567454238194 2.339571167142646 +-5.609115382460646 4.978737252179849 2.812666149882622 +-5.603694332331206 4.984837994338343 1.570665293359911 +3.032300359342575 6.859675978552551 21.87545388879716 +2.352964772463131 7.121345152395546 22.18811422474856 +2.414445501072784 7.100736083135987 21.56547666950974 +2.914273821223592 6.910644549890469 21.17654941822584 +-7.48506611379683 0.4730594804994545 4.911136419196968 +-7.467274143659681 0.6998691759404541 5.540791571321306 +3.275010048187994 6.747170457626491 19.94468431942316 +3.3994636132083 6.685330742938061 19.28256263160215 +3.938487983740655 6.382657158420032 19.77087207490673 +-7.429925773283371 1.022840654011906 9.911577424915761 +-7.413646953973167 1.134829873524826 10.53893376459311 +-7.476160282481652 0.5975177241252974 10.59155074257076 +6.079241903705623 4.392359033165394 15.4200606087316 +5.610994097836717 4.976619860310965 14.8047046898526 +-7.48565985920895 0.4635692744648156 9.665280015650566 +5.522804561449312 5.074310768570909 15.57430678646729 +-5.689065708531651 4.887180308113182 14.75940059488576 +-6.065025326563892 4.411968697547451 15.35677075170656 +-6.240328180186436 4.160325011771441 14.75970303053263 +-5.600072953347142 4.98890598399988 15.46801091366153 +7.351184947398572 1.48663373738815 15.48482177361254 +7.43638616358453 0.9747619330116288 15.50990169258551 +-6.501539418150116 3.738981839249856 0.7207340675381411 +-4.084543746408249 6.290190965596932 0.8171052352742111 +-4.063008722910214 6.304122470063183 1.452477929960422 +-2.301016374770511 7.138299772567552 0.9446466070193746 +-2.87969036316218 6.925126960013865 1.021368377817613 +-2.544728368270339 7.055094438185797 0.4687356592782554 +-4.482542633113472 6.013053429192206 22.44862457236066 +-4.169577847737996 6.234149546782832 21.43404747847942 +-5.498575520764269 5.100555581743222 22.38406505021689 +4.12699920535602 6.262417868442729 22.17451122781748 +7.42413197956743 1.064079108884389 7.502241288488906 +7.333507413594835 1.571518060586516 7.403076737844657 +7.41168692334904 1.147561305663813 6.856176191040476 +4.503461726077845 5.99740214440819 0.6445605763730535 +5.498868672593563 5.100239535705076 0.6154633500630394 +6.831097875205247 3.096143055378153 6.727164222331078 +6.840712856041254 3.074841072509587 8.172811483634385 +6.53354028610912 3.682777664995425 8.241881352708397 +-5.740319764984966 4.826875697148512 21.66548204918849 +5.911632993587835 4.615473469658745 0.638145887844591 +-5.911628743804641 4.615478912899803 22.36185028718248 +-5.571919534391834 5.020329939581927 21.03569368121212 +6.044755180644302 4.439699855403954 22.34056795817951 +5.680768855239346 4.896821950341126 22.4773795385801 +6.833981462952569 3.089773027913324 14.30550841183112 +7.043975637029332 2.575346039843427 13.80453828099054 +7.125888797784792 2.339168408132517 14.43626277886132 +6.908189006422975 2.920089836209966 14.94376838032765 +6.806478860319747 3.149896113210782 9.309570115240495 +7.028662247944602 2.616850588841159 9.473645043120023 +6.917002715975319 2.899150466462557 10.08794703234661 +7.27205115201148 1.835012818082889 7.95602727445667 +7.168808918626807 2.204127647895362 7.353300479768783 +6.574310616745334 3.609493027358495 9.679009008385107 +7.19675631076896 2.111089435198596 9.927572005091827 +6.706947275563607 3.356614103946103 20.3438764090244 +6.572065961275638 3.613578420436192 20.91557005445899 +6.328517049739506 4.024906452472701 20.30451959655071 +4.166581531688376 6.23615252698275 1.424058627321713 +6.21602545095966 4.196549486545079 20.83397812700303 +-3.59218775850873 6.583782127897309 21.37937451053864 +6.58724981056127 3.585824860929561 19.79007908511141 +6.769894847935814 3.227773806804332 15.50714193754107 +7.01574955824701 2.651274813359958 15.54059844030098 +6.594738516020154 3.57203358121397 15.88659338355695 +3.655016490355596 6.549110966782336 21.84847429406186 +3.510918776577082 6.627476846000934 21.37146744559297 +-6.942381521914257 2.837840517749982 15.67798630053824 +-6.686007344783836 3.398132690978473 15.51359377864916 +-6.480762645590492 3.774879538676557 16.01701782837335 +7.271221332589707 1.838298216419836 15.01053253284808 +7.392572903138095 1.264858044125268 15.01063908977197 +-3.851405183281701 6.435579081496152 18.14882200221012 +-5.025223413490434 5.567506591330409 6.394054458598301 +-5.191670607800973 5.412629333336569 5.789687891277794 +-4.764564243400973 5.79214360755195 5.914040906661667 +6.254437032299709 4.139084126832651 2.647149543286084 +6.395338449738333 3.917862441855059 2.002937516981778 +-4.57541021194511 5.942694792131631 6.488781395784279 +-6.25074073807396 4.144664066650348 20.36707686448466 +-5.974506095401374 4.533792773827652 21.02806405492544 +-6.383026871547135 3.937888769011537 21.00387217680667 +-4.265976754780291 6.168585115541021 6.018789863554432 +-6.422756735215645 3.872750433508731 21.59875159119176 +-6.676333370192174 3.417100046831876 21.35685118235539 +-6.125700271575171 4.327331300330941 21.6354413288348 +6.417273478807556 3.881829607052991 1.402745536745223 +6.693890955305791 3.382576514799825 1.612800537899529 +6.112123864552308 4.346486151406692 1.369894541892344 +7.120392449521169 2.355846209921594 15.10866513468455 +7.346599451714346 1.509131040059301 14.37609810803449 +1.020330521195534 7.430270898662904 1.294771750912259 +1.003149833093141 7.43260993274672 2.191043787543129 +7.246655236501918 1.932870374153247 13.80520696867121 +-6.735991470608581 3.297941616810165 2.637923973049114 +-6.5417842582358 3.668113782136301 2.069992329668837 +-6.312044474655425 4.050690626297189 2.815998247166407 +-6.357443611514562 3.979059025248643 3.674040081184569 +7.469625522037147 0.6743104333549054 5.54762255534192 +-6.255096322610977 4.138087721986888 2.124578635163133 +6.331700872060556 4.019896026857857 6.275250960464574 +-7.467392029445776 0.6986102479707168 17.40382675265323 +7.178112445727058 2.173637899121724 9.121691340749219 +7.233004088386187 1.983343605477556 8.51884271809741 +7.24540031186494 1.937569178333363 4.04607797309473 +5.938947217033668 4.580273567516252 7.95865950897554 +6.402775871466082 3.905695986603637 5.66036131011873 +6.658812805841065 3.451117502602169 6.243253768222202 +-6.874655229470142 2.998185363835737 14.95890945466446 +5.988915148816271 4.514742001518912 5.686706450064021 +5.285122915233989 5.321416707124953 20.86938226410357 +1.126322625384994 7.414944190184161 3.847693524776057 +-0.4821464974971051 7.48448627194621 22.22991677209361 +-0.3337588793485075 7.492569987024214 21.35168624978733 +3.105964470919091 6.826637877124309 1.980919547738824 +3.446891484809588 6.661001358050242 20.88363499520633 +5.659521900661491 4.921362804745546 19.83779925680517 +5.94756892898554 4.569072535533421 20.42567511501315 +5.540004248458417 5.055526968285571 20.49315457860373 +5.226405071843923 5.37909751027104 20.31864045724908 +-5.027390043923948 5.565550228526769 18.98814534285238 +7.453988993076441 0.8294866431084101 4.281080808353443 +7.484144808916174 0.4874181769005909 3.876842257528817 +-2.947466029710487 6.896553052337283 21.28093845196556 +-3.129554439230725 6.815855706504595 21.89738600212624 +-3.476161971866801 6.645772938142493 20.89596210689621 +-7.484523466293249 0.4815687723531236 13.52975774115114 +-7.479330324374763 0.5564331935534582 12.8936557997367 +-7.11934206839254 2.359018548722378 6.644812814036735 +-7.433676141985992 0.9952180746290027 13.31583511392216 +-7.453849774841522 0.8307367417509561 18.7201549153544 +-7.484079109443403 0.4884259243660616 19.12175598534206 +-7.021156957735156 2.636921495768732 7.366020735611243 +-6.93474277160086 2.856456317140108 6.498563877551642 +-6.716852735249346 3.336748317295354 6.934753975599388 +-7.392120324558459 1.26750033816553 16.10750858324989 +-7.312967577495618 1.664483466573902 15.54686934332383 +-7.121859041617722 2.351408894966569 15.30874083969345 +3.574111614153791 6.593612528013076 3.704346041571739 +-7.067030450526414 2.511390175048958 14.48366998090986 +-7.275774437673263 1.820194036936809 14.89796299100958 +1.60342403133595 7.326597530623227 1.042258969349176 +1.084538738263991 7.421170778603922 0.5395647767589371 +-7.238990483153914 1.961381346094395 14.18585063559781 +0.473829480798925 7.485017409674197 0.936267806393852 +0.4334789771831374 7.487462585972651 0.4169693913671382 +-6.946176469310548 2.828538926229663 9.994070132152517 +-6.969445269074712 2.770709772129177 9.462676978453278 +-6.718409960446217 3.333611795542047 9.490136529574254 +-6.694526099289007 3.381319314400566 10.08240366324189 +-6.811067089728185 3.139962595194666 8.962748776954285 +1.703278438221844 7.304029200509028 21.66271950737997 +2.125133943852048 7.192621616676901 20.95159759838864 +-1.784057408444908 7.284719566556618 20.93738126575131 +-1.117677077103361 7.416252284767401 20.96540012002966 +-3.51284144115556 6.626457953484662 1.73562412758179 +-3.837292360648802 6.4440039834645 2.082421149604162 +1.236235698044932 7.397413149127157 20.93587918655461 +1.653532871496893 7.315451390234183 20.34596587102564 +5.267651631151025 5.338712044382235 19.81413243012936 +5.064083844958303 5.53218354822328 19.30065792590204 +5.508854662975025 5.089451866578396 19.34816925024788 +5.523664680105617 5.073374468906638 18.82545354224548 +-5.958074309251983 4.555365026584751 3.178205756378695 +-5.307102206934328 5.299496784144019 19.95633488738763 +-5.124122167491144 5.476620491929842 20.62499955527406 +-5.496192870633675 5.103122958424141 20.41628216963776 +7.161636073598748 2.227323225158197 20.59848947567529 +6.901710357601012 2.935369506515816 20.95307585565369 +6.98248122553164 2.737691716592314 20.34578560786622 +-5.884702002405109 4.649761536131644 20.37887258858281 +-5.733071949133549 4.835481984875763 19.78432763932214 +-5.899982103859412 4.630357564393775 18.42062562465805 +-5.519863408560107 5.077510014843809 19.20671919655755 +-6.039174303144712 4.447288357666565 19.13581709446505 +-7.161639695777149 2.22731157853341 2.40147566261657 +-6.899751687097461 2.93997051964739 2.046944019166813 +-6.993177152692866 2.710253366579313 2.633520099448496 +-5.039416082214444 5.55466340567261 19.55297486225088 +-5.405445709836078 5.199149611043593 18.38629405931446 +-6.922591378412657 2.885780415680781 12.7034226075683 +0.053941377728132 7.499806019342686 6.142981006989785 +-0.6940538743940758 7.467816897824864 5.934138576797972 +-0.007107357875358122 7.499996632363513 5.53727236481119 +2.827816108588156 6.946470762625388 19.55092638274092 +1.751953832541615 7.292506960479554 22.4193071885859 +1.209341124756475 7.401857472551923 22.31557252627061 +-6.558944069873158 3.637341431358311 12.97643529205156 +-6.836643349991264 3.083878678712933 13.33260046286364 +-2.858039511158347 6.934090434415877 9.595785615941409 +-2.411652655354763 7.10168511481045 10.23548113690493 +-2.93287699597367 6.902769916960035 10.57330711002752 +-2.835400084276831 6.943378598498208 19.56030945576402 +-5.034299689309923 5.559300912724011 3.58510145479327 +-4.559297384144125 5.955065689220946 3.74163727219304 +-6.794353542800568 3.175965984615289 14.15183664440517 +-6.513845980999546 3.717500576437892 14.27543586752215 +-6.614716721898382 3.53490066183449 14.83927524511189 +-5.63791742426582 4.94609817099902 17.58615721287825 +-5.219371668300016 5.385922334024795 16.99040304894918 +-5.08098826887088 5.516661872146644 17.71413007883906 +-5.386528406033329 5.218746183806609 4.324321902909094 +5.124401946239545 5.47635870751509 17.75086552066654 +5.375780839891141 5.22981647493096 16.98055218473339 +5.712752155254054 4.859471454041085 17.49375506293907 +5.858027205597788 4.683323313468352 16.80954974796562 +5.491055737728659 5.108650201878886 16.30784930389327 +4.99347552824003 5.595998762407651 16.45304958129291 +-3.539666613668492 6.612167591953537 18.78320677360874 +-2.162028948623266 7.181617563287185 21.54085645988163 +-2.496051930211473 7.072462425611576 20.85265165806813 +-2.223009710141857 7.162976185121309 20.39877790630233 +-1.616013121617953 7.323831073335771 20.27176756944631 +-0.2858755876607637 7.494549696171186 6.705044564742713 +-7.267020764274175 1.854834011874915 17.27718247554139 +-7.392577700912057 1.264830002797932 16.90202926946334 +5.885570517561075 4.648662139026224 4.862981782331122 +6.245624607045413 4.152369596732548 5.076967597002994 +-6.400087216827262 3.910100205494005 15.36824976571721 +-6.101041229365912 4.362028876288794 9.50951477629421 +-6.326217490652624 4.028519859819586 10.13253010024174 +-6.289055695107963 4.086291529471447 10.76104106325993 +-7.034144567234581 2.602078055563328 13.84012939521038 +5.522574463243207 5.074561192648485 5.663473196853654 +5.234437227088156 5.371281682771222 6.385254176341065 +4.932815468636568 5.649542596740003 5.826701624487063 +5.675633537485339 4.902773087567042 6.360023332536042 +6.365573371761908 3.966040298423068 22.39675407468104 +6.604481001442853 3.553987999639337 22.16881370711436 +-7.228290420978063 2.000454345891647 3.99205549712193 +7.241152574894575 1.95338408591287 18.25874439637741 +7.458208714076174 0.790647062397773 14.82621948051203 +7.469659476617359 0.6739341981087502 14.2521585475367 +7.419049831692401 1.098953863847326 13.63030291286832 +-6.263618007688837 4.125177505727009 1.437422342909097 +2.918037315111536 6.909056247246555 20.53980857064036 +6.27395605226367 4.109437364684377 21.56118417416961 +-5.472682559937415 5.128327758456634 0.7318965676026321 +5.360176902826693 5.245808190393855 22.1897986725542 +2.259125341201715 7.151667825950828 20.38033486249642 +7.059806116107578 2.531627461331946 6.746161572342318 +7.091256709091441 2.442146245777601 7.963826154421026 +3.272587565842127 6.748345769438278 18.21239186034373 +3.379757085802675 6.695314932172094 18.70522817966391 +2.871048412905472 6.928714239363099 18.49211541299584 +-6.356535922791998 3.980508894884531 6.532345178779872 +-6.696441313697364 3.377524793722041 6.295033007813939 +-6.023087997079591 4.469050344249409 5.89052145331601 +-6.219574447254335 4.191287832523667 5.293919782651257 +6.667961506185238 3.433407833630007 21.49551156888349 +-6.658789950912145 3.451161600045908 1.458012839529484 +2.842453008562385 6.940494283126717 18.99823768065439 +5.910861733761668 4.616461151612998 2.703820085072282 +-6.531521236816456 3.686357325737107 13.57865435898409 +-0.655531356436684 7.471296985177894 4.472864078106842 +0.7322285426386446 7.464170507252985 18.99674668772826 +0.6188512369149541 7.47442460304262 19.76308992447039 +0.0368392933375127 7.499909523885365 19.08404199513327 +-7.424353027075104 1.062535707334457 19.35300325234325 +-7.3161108299691 1.650612711573747 19.5447722898481 +0.3154417844705826 7.493363495828159 18.45827285434893 +-7.287249851382386 1.773693773887528 20.07846825358418 +-2.973123671265891 6.885530889870325 17.07260157639876 +7.430788962213279 1.016550736092057 3.633173873909658 +7.321700270276024 1.625639920843486 3.455863184934524 +0.06147748063333202 7.49974803039242 20.00161354852121 +7.287232275299197 1.773765983955518 2.921555130776593 +-7.168676366019537 2.204558722119448 19.74616282921666 +7.276755771589358 1.816266896863164 6.701766656858553 +7.154399785776927 2.250458554445083 6.310534814934117 +7.279811589812256 1.803979827169683 5.907062033109439 +1.140476718456948 7.412780372752026 4.527927956512824 +1.463958954807064 7.355734101953401 5.002262813678272 +0.7335660382547633 7.464039179125415 5.117853968991312 +7.33863416839467 1.547400575956427 20.58904865402791 +-7.338634193848825 1.547400455238656 2.410951243927019 +1.427341675857745 7.362927117686254 5.533382334815612 +7.403730773368277 1.197819116344188 6.123958678537152 +5.748366930907182 4.817289448191041 21.72437746283498 +5.974411303764366 4.533917684900398 21.15153913446952 +-5.882381389451873 4.652696980142835 1.142828810083567 +-5.997918746915587 4.502773668018253 1.667952373024015 +-7.131026544488921 2.323458719623486 8.156138935783027 +-5.570989512722815 5.021361951615558 7.921138083159461 +-5.731624594198027 4.837197485237118 7.355942583937538 +-5.148619185860971 5.453597022056572 7.556042799604898 +-5.4003803578364 5.204410820707258 6.899065688610514 +3.899344122375916 6.406646190893672 0.6281432696675606 +7.002191298338 2.686878676360283 8.784934186224582 +-2.706455355621769 6.994647911655471 22.43456706755402 +7.15554590461057 2.246811698164953 17.80366874229592 +7.383753702584905 1.315363546539018 10.11929026644309 +5.09231924653024 5.506204199938256 18.60423590404939 +7.105422670320803 2.400618394516543 19.79589829522165 +6.880151031857655 2.985552173188075 19.86773329381005 +-7.14248834743558 2.287981688464082 3.239076380344053 +5.568978583332221 5.02359209514338 18.15093841761853 +-7.182961903717374 2.157558409347213 18.99120253485337 +-2.55878569841887 7.050008209184374 21.90188073539755 +-6.740003880673978 3.289733680482315 17.15054327089701 +-6.422603199682252 3.87300505285383 16.57808763517569 +-6.447331632163058 3.83169868660228 17.28161608415218 +-7.294007339153401 1.745696690830431 7.587033056207648 +-7.23333999037428 1.982118206276361 7.029170145712646 +-3.19212618743184 6.78677614213935 0.4436446668290568 +2.568588650251042 7.046442531221094 0.6434962627323001 +-4.800046391604686 5.762773172565691 7.0682349515365 +3.596187135669571 6.581598444545572 5.157506754151173 +3.478633202671286 6.644479741956695 4.591766572108336 +4.050033786921431 6.312465946426551 4.980954483996593 +3.938068694948149 6.382915866112398 4.218905415891638 +7.322551275078079 1.621802338095615 19.55434633200251 +7.449425262915417 0.8695189775028354 19.38022481971117 +7.279163453711666 1.806593317309809 20.1186119750364 +-7.319951388844292 1.633496760007961 3.493541542438686 +-7.449509742810547 0.8687949077720964 3.62313487810288 +-7.279163579735158 1.806592809533246 2.881387846565123 +4.500830692331859 5.999376890891546 19.56274950996592 +4.413819791840391 6.063678326326195 2.019878777722584 +3.830693513622699 6.447928908160277 2.084872786147609 +7.218508857338264 2.035467974822746 15.71970602939301 +-2.764964899789645 6.971726407636148 17.78071348120035 +-2.386879230566606 7.110049756414491 18.47931958165596 +-3.164178617198509 6.799851004137056 18.31748452435684 +2.412174157696485 7.101507997104648 4.656426137367914 +2.651393931505979 7.015704541952524 5.262848270812261 +1.994698962963963 7.229880776828239 5.063224718320605 +-2.881120818771118 6.924531957298171 18.96654455039945 +2.136689451978019 7.189197325557692 5.6005877035929 +-0.1296521335190367 7.498879271216063 2.716645857034585 +-0.682506005815972 7.468881144590877 3.111780138412796 +-7.420065002618557 1.092078457307569 4.970799299982851 +7.486664941620574 0.4470436800911112 10.77918009485064 +7.430995979410294 1.015036331363583 10.69954474325823 +7.432793860566526 1.001786118053431 18.02809398538684 +-2.165536404192004 7.180560708058888 4.105626648838968 +7.301947897624637 1.712178991920866 10.61879441633519 +-7.331449776456507 1.58108955321823 20.55307806474346 +7.331447247623157 1.581101279273038 2.446925064390359 +-7.479719733698943 0.5511739338127403 19.68199345615151 +2.544397226173819 7.055213870283379 3.937220363208984 +1.798845808862868 7.281081908338656 4.36479808416965 +3.23988106928634 6.764109006874445 4.054851014865208 +-0.09786728876784995 7.499361439068611 2.014026398240737 +0.3442498591642821 7.492095303349082 2.281697166752781 +7.479727706181737 0.551065732356221 3.317863689528096 +-0.6837767410691583 7.468764915859438 2.426654329653078 +7.46496943868472 0.7240381754459801 11.35990135462331 +4.144271994286269 6.251000690879382 3.49194341623816 +-6.041132096081822 4.444628555648948 0.6468629710375926 +5.092728863142622 5.505825344715726 3.592648792986852 +4.640430426260886 5.892062920491616 3.175593503932979 +-5.846829720606925 4.697295202372056 9.091435918894714 +-5.409192884520476 5.195250940816338 9.137512287831994 +-5.665573713376135 4.91439462175163 9.671560372938018 +-5.642473101683472 4.940900454044636 8.510200286716348 +7.404270225826449 1.194479980133598 11.73919670545336 +7.367023791022289 1.406044260509457 11.14859227199522 +1.857649535248781 7.26630154921952 18.58390701562319 +2.089446666505352 7.203069667012091 17.94265701587056 +2.396532547357857 7.10680179472134 18.54720092429621 +1.461623509216172 7.35619852351108 17.94854948135628 +7.47711970498732 0.5853895432020758 7.914546402011114 +7.47147217190513 0.6535316246726309 8.736929195556415 +-7.350153645396482 1.491724300621531 4.545304564109576 +-2.026015969614134 7.221167446533039 9.656859258749952 +-5.802262648739089 4.752236121558696 5.018161510425172 +4.991131488268987 5.598089537226945 6.940634319859647 +4.843067310891422 5.726665611171559 6.434017484294031 +5.420291607970952 5.183670406628847 6.957060760657424 +1.260325086199824 7.393347055095913 19.64891486949853 +2.538193434373398 7.057448128729235 5.979420767227233 +3.166433289743983 6.798801381243689 5.611838325541261 +3.642900167119085 6.555858324613471 5.930144703976648 +3.985422186175242 6.353456539391936 5.607233841625248 +-0.5268661634461013 7.481471248746171 19.67714299578207 +-0.6552341214847609 7.471323058604955 19.02532332658844 +-1.201023473419714 7.403211642003412 19.62843555461385 +4.911326427805714 5.668233650753747 17.11017237821887 +7.349235343996347 1.496241911775934 17.63965422007058 +4.505808563898457 5.995639180729551 16.63219319264764 +2.384392366648261 7.110884125189322 9.276652646702631 +1.782533155535227 7.285092693261879 9.166580022912594 +7.46749793488725 0.697477306049921 18.71741720591516 +7.376803654294356 1.353797564626793 19.00058484606841 +-7.466035931107331 0.7129568538237702 4.291253219758723 +-7.379712518146484 1.337850196962309 4.001723433554122 +-7.006559593520032 2.675466812063346 19.42199919923477 +4.590776030663681 5.930832609025803 17.4711062801816 +1.903066816676508 7.254539040577613 9.753705394022692 +-7.40585638483784 1.184605929056832 11.17119149586426 +-7.481682604867914 0.5238562780160811 11.31069296067558 +-1.721007617107017 7.299872107226238 18.49593360637144 +-2.083496656524577 7.204792965953351 17.8551399570703 +6.965927705171453 2.779541546069203 6.155028543791907 +-7.34977527254657 1.493587440715469 18.99839806145696 +-1.393146993401388 7.369473621282369 2.886800542671242 +-1.247121337745525 7.395585735351854 2.070951959772284 +-0.7410536377048436 7.463299505315622 1.694717604854467 +6.755670952224754 3.257439175988812 5.68054646412728 +7.371626645555995 1.381709303192558 4.009644910578916 +7.174260477820608 2.186318045569128 13.29779012197266 +6.974391512916857 2.758235491134379 13.12518249591569 +6.851177282090848 3.051453727219578 13.65230466077526 +-3.285629363783612 6.742005612860531 2.430338097064088 +-2.966110436869811 6.888554919305789 1.668177874909543 +6.087372689267702 4.381083626451076 4.342756270858276 +5.973037964148679 4.535726786176458 3.788027049631184 +6.400077281513985 3.91011646765778 3.774526651327597 +7.387164609073715 1.29607061476171 12.81582610252942 +7.464203601351126 0.7318911104644458 12.27854400594625 +7.47081135164815 0.6610429245405663 13.02424410519406 +4.457247189909534 6.031827872879294 5.455040363346519 +5.02880927080162 5.564267904935893 5.220930625337063 +7.242096697904358 1.949880872823467 16.37780745426251 +7.47370329902318 0.6275021897731098 7.118657150343111 +7.360000809720926 1.442355046757666 18.44531712400602 +-5.042705292250338 5.551677524452446 21.22654459005973 +-4.604299661423139 5.920339908131861 20.90963759951814 +-7.434286674445667 0.9906470825473516 9.291919464057809 +-5.601010066627558 4.987853870507509 5.575131367248916 +-7.32242495814492 1.622372562741481 9.376182856652507 +-3.547615872966289 6.607905993420127 6.974340702138244 +-4.214676284004261 6.203749174575971 7.025080031145638 +-3.972999076069816 6.361232454607235 6.4454057396124 +-3.945049070738776 6.378603909121739 7.5402805473049 +-3.805750369356137 6.462682424980019 5.782568092662878 +-4.329909968895705 6.123877828733817 5.516912209914062 +-1.431739506909892 7.362073212373905 5.822303174813901 +-2.183027917894078 7.175262302501215 5.756451538846151 +-1.656575033488207 7.314763096534539 5.157852552082713 +-2.326783010198213 7.129942554007917 5.157418551515019 +-7.172279861210942 2.19280678411664 17.7738432086116 +7.203605109686221 2.087599919453574 5.258317407221286 +-6.293889265912195 4.078842716805253 22.2435128283284 +6.293896821698143 4.078831057768639 0.7564751378058322 +-3.646043151550961 6.554110873110734 3.088779962064835 +-3.837985483493359 6.443591190360717 4.554394842871835 +-1.690071657270059 7.307096399616776 1.630744063292198 +-2.299699868071849 7.138724011809836 1.579319143223448 +6.718266643401622 3.333900614619024 3.666677506166723 +6.513202560038219 3.718627759256309 3.170466305509606 +5.63591027692315 4.948385125520448 21.06225343708504 +-6.479317639859477 3.777359252415079 19.17859915109999 +-6.752398518554709 3.264217248686149 19.65248814219011 +-6.434815426225654 3.852680940644883 19.74850728982098 +2.109444648055067 7.197238586902052 1.516895257510822 +-7.132350156040641 2.319392431570613 11.04651064187954 +-6.916389101377114 2.900614038156727 11.32417399653031 +-7.282723696078385 1.79218736927208 11.28704050626586 +4.092648113467545 6.284920955694713 17.72186441399472 +3.431605729160194 6.668889121854924 17.71090748970901 +3.75154446833933 6.494298584302431 17.30375632518874 +3.843234135639847 6.440462046984877 18.28098903558748 +4.224301879320132 6.197198853705793 17.0833671048603 +-6.034772494168545 4.453259586373419 16.5083878658239 +-6.198356085605417 4.222603679726324 15.96588529026232 +-6.077669691355198 4.394534232746675 17.08099849679902 +6.910710550934885 2.91411730738439 17.85325557347813 +6.799297505936647 3.165367818400209 18.31780316204629 +7.039762354554301 2.586840928893789 17.34111498683858 +-7.117689221804944 2.364000876015433 9.026725085352345 +-7.187832748982898 2.141275407940082 9.823319909741832 +-4.693949320816894 5.849516199960696 15.99369565561523 +-5.247791755676445 5.358234941569315 16.05554475709628 +-5.152156765311324 5.450255100970665 15.25625278570443 +-6.207132078939738 4.209692548702012 17.78767839010492 +-6.943613148914084 2.834825645119544 8.54113120949313 +-6.157284648480715 4.282271098095462 7.259881050680127 +-5.999151304979235 4.501131371107261 7.964422941493356 +-6.592113413518776 3.576875835600928 17.90098973386529 +6.600649959671332 3.561098160664889 18.70613590482161 +2.199511248934896 7.170226653726426 0.9956893830558696 +1.849760552967354 7.268313827614072 0.5121348972317831 +-6.476061565368702 3.782938884194969 7.205994475663484 +0.02271730748685866 7.499965594850456 4.158113556134708 +-5.981588329857002 4.524444833581079 6.628428300715064 +-7.427537139648686 1.040044248644942 7.465997334618873 +0.4330674841685396 7.487486397594051 1.598854826716291 +-7.439102409977235 0.9538109528994154 8.094474657855551 +-7.303380939796534 1.706055933495938 8.186164755349417 +3.641987243118785 6.556365526796079 20.39619711374105 +4.292573913137534 6.150106438123743 20.29419454571765 +-6.618134095507522 3.528498419141043 11.23222468607074 +-6.912159318878255 2.910679224930924 10.67640318730508 +-4.063806760125237 6.303608063352323 20.81014362645575 +6.167374026019355 4.267727454182356 3.205387235018293 +6.399082458814012 3.911744327700728 4.480224390746067 +-4.81954432408077 5.746476529859044 20.11393433502025 +7.22239792212526 2.021625151822349 17.29926192474452 +7.121881288183854 2.351341514331063 16.79722577880774 +-4.825890537025363 5.741148014521927 9.157531795750391 +-5.087285573590585 5.510855241497196 8.655671636801074 +-5.22942356643182 5.376163052107656 9.77692704224364 +-5.254173136569522 5.35197763924245 8.17573920803823 +-4.8215999334101 5.744751872982829 8.167146465540666 +6.731851511237582 3.306384011370773 8.758215820927898 +6.477651054563212 3.780216503762201 8.930943743359084 +-4.472626468862866 6.020432913838281 7.586240585641702 +-4.275282426092726 6.162139253306654 8.188909922071813 +-4.494636345519525 6.004018997432877 8.68950025310081 +-1.156503750010132 7.410296827807406 6.570557494898602 +-1.853169167722803 7.267445495894797 6.495038433554033 +-7.265079145737653 1.862424496769696 8.750873172734311 +5.985742354017348 4.51894771725928 10.34225580786985 +6.156406360073063 4.283533673224941 11.07331809973243 +5.745192937173765 4.821074373482397 10.74174686176063 +5.793006777533286 4.763514718719091 11.40228088493083 +4.831563981636827 5.736374246102644 20.05240984939624 +6.959153664508595 2.796458523518022 5.331468787091172 +6.660961597349572 3.446968319934814 5.043743586306388 +4.939418327611214 5.643770599949862 2.044665348935319 +5.13910117617895 5.46256707977084 2.792595059595839 +5.55414604788852 5.039986277632543 2.736883727386477 +-1.625174859798798 7.321803512460435 17.21423667445289 +-2.298930822517328 7.138971709796853 17.23240241145131 +-1.319670977447758 7.382985067794874 17.83809797998578 +-1.88737735134854 7.258636699382093 0.4869561857367345 +4.147674997441504 6.248743242892815 2.697722713545443 +7.303555664551305 1.705307788875825 11.54704968882798 +-7.472730155641933 0.63898671422784 14.64301434662764 +-7.416524876241037 1.115866820054196 12.52261194279235 +-7.486311803207739 0.4529189609107754 12.30681147541442 +-7.455705604393793 0.813912735255433 11.8628643710948 +5.905758664784302 4.622987626343505 16.09047800655408 +-5.803712148396268 4.750465798062079 15.99467666962421 +3.808454226132032 6.461089413361888 6.575096179406189 +3.956916720162983 6.371248705685144 7.345026143451959 +3.441749231716108 6.663659822198428 7.108543961497118 +3.591374001820913 6.584226057711327 7.793287665420436 +4.329817537221563 6.123943181837059 6.149834968888518 +-3.485790373772962 6.640727781660061 1.095964632567247 +-3.698565078925789 6.524616184646471 0.4679840454483463 +-6.546662920184868 3.659399487549362 4.38178231163753 +-2.767819680429846 6.970593534027445 5.742137211707901 +-3.297026377884499 6.736439494535213 5.727430042416327 +-2.941151923112782 6.89924817390779 5.117686771882505 +-3.508498135278304 6.628758619436121 5.096957810167013 +-2.577996609483701 7.043005997547534 6.360085296967886 +-4.022308100041604 6.330168840429117 5.138181406781707 +2.692035681402158 7.000210274703012 16.92979881580365 +2.924166225470194 6.906464499714699 17.42392916054745 +2.33062987508059 7.128686020956585 17.34191816404629 +-2.256199772074371 7.152591319828888 19.13853639873663 +2.251910699868361 7.153942842923641 19.22411262478521 +3.29566636638732 6.737104956987341 17.01566704269291 +1.667838751993511 7.312203080970107 17.2239304758366 +-7.353986902351978 1.472710643689232 13.81592175940946 +-7.378488732114614 1.344583217974129 14.50562225527991 +-7.454560669225204 0.8243332025586964 14.04382911817992 +-7.218845869848563 2.034272427028976 13.52755503516982 +-7.339820785672386 1.541762249574033 13.10243859345523 +-7.174100225514093 2.186843833994243 12.87302114402243 +-2.702687390043227 6.996104692734474 20.16937663948767 +-2.24816663539752 7.155120319008297 19.86295202840067 +5.540731069539976 5.054730380053361 5.041544992643514 +0.8505008440616643 7.451620515985123 18.20367381955683 +1.299231730852464 7.386609297204375 18.76682589124567 +1.668377053762744 7.312080278995707 19.20331531210869 +-4.018947751431972 6.332302817400626 2.678244291564309 +-4.314795971407278 6.134536308893079 2.074795565791175 +-4.476486140364407 6.017563612885649 2.600719228753456 +-4.090583212032682 6.286265106200692 3.436252973433604 +-4.52134639292003 5.983930714440889 3.163039407672695 +-7.281595937392027 1.796763925660776 10.59690542128766 +7.202123319369658 2.09270630825058 12.73724290912135 +7.306541185111192 1.692470357280726 13.23194288565742 +-4.826879056001771 5.740316940616734 2.831657008693624 +-7.397977414461659 1.232854482538467 8.760804291167899 +-3.244716994709645 6.761790563470774 7.592898605416156 +-2.904058153847824 6.914943690231322 6.977505727856631 +2.842418973205045 6.940508222080281 12.5506051551372 +2.968443205246396 6.887549995261486 11.91276969310841 +3.459345484631374 6.654541969058466 12.44462258366969 +-2.244625940945095 7.156231856587399 7.143323331767498 +5.55520823827049 5.038815478805678 4.172537201299312 +-5.202258813615297 5.402453445996732 2.827680348375241 +6.759837646698556 3.248783617029137 10.78249686169202 +6.929059155034454 2.870215884917581 11.34273825627322 +6.577840210087023 3.603056781479068 11.37034913872672 +6.907226000329129 2.922367016713892 11.96079072363778 +6.99382131305082 2.708590674338983 10.75680694372587 +7.186219667293576 2.146682764966217 11.09168813213407 +-4.410051172517662 6.066419755982569 9.446191789070832 +-3.942634587273144 6.380096591058597 8.872044539993336 +-3.936711434538911 6.38375305609252 9.741774706365332 +-3.350360474961764 6.710073374249642 9.122584632414176 +-4.801860289293502 5.761261820305179 9.87650373261007 +-0.07637634638317312 7.499611100164671 4.798569115929586 +-1.163230311108687 7.409243904968846 18.94075497550956 +-0.9483483863938319 7.439800759296194 18.41766319378208 +-0.2641849434997554 7.495345643506244 18.37775859002006 +-1.682508309197569 7.308841617485027 19.15961985772314 +0.05604080368457524 7.499790625632317 22.03430140479052 +0.596804286383295 7.476217268362024 22.20205246381469 +1.737802071437589 7.295892266234969 6.122275868131749 +2.273178683423759 7.147213350196552 6.622406580844493 +7.385797468868513 1.303838850800006 8.147910159041864 +6.233603571027444 4.170394048441214 11.9080530277498 +6.409993907945601 3.893838478943404 10.65052944196603 +2.583789788848462 7.040882780379348 1.402951167084204 +3.60241282871673 6.578192898623232 11.85403288992879 +-3.144365180115555 6.809035733059187 4.534266280553262 +-2.535255573186965 7.058504032627907 4.58222165562971 +0.6216465653508393 7.474192635180573 10.28393856887856 +0.5318554353087183 7.481118218283452 11.18353609465634 +-0.02844161547818137 7.499946071440046 10.66163488007283 +-7.325770218022675 1.607199649306832 11.87487821991358 +1.127862406147077 7.414710135453721 10.92514106142703 +-0.5903749403941465 7.476727722055593 11.21203640358066 +-0.6794203509533063 7.469162468892378 10.41399214128859 +-1.191697230627967 7.404718611163671 10.87687830530703 +7.12129579054913 2.353114162871669 5.742646636612911 +7.311945927908408 1.668965771771149 12.14451271321618 +-7.29693858059391 1.733403401127429 12.50991790622134 +-7.477822394443862 0.5763438532281374 8.77439125095999 +2.71763183301954 6.99031309886466 20.06701300397727 +-3.075634114789365 6.840356335158559 20.5690064695194 +5.290842354458848 5.31573016435789 11.70495518205234 +4.816672432615026 5.748883950549571 11.34426431904786 +5.336938268099545 5.269448730417123 10.92475621645573 +4.922128184660416 5.658856256680457 10.4629541862399 +-0.5825140947809146 7.4773442698181 17.82217467084917 +7.486586703524932 0.4483520163930211 13.64644147121805 +-2.030792284448323 7.21982566946219 15.21651982595228 +-1.466154329758985 7.355296831626103 15.9291317454972 +-2.371484460395976 7.115199326378735 14.37593981154763 +-1.556107991078932 7.336792754337572 14.62189159574807 +-0.1385724154532025 7.498719736440045 0.5892851922065786 +-1.822012129253399 7.275319360746543 13.86437028101871 +1.004933178041359 7.432369023916378 16.69009429364828 +-6.325701207389639 4.029330494614366 18.5385596774196 +7.044604056905421 2.57362656215537 16.23381824389981 +6.787974533779432 3.18957704543438 17.38433862759279 +-4.982053926214687 5.606169697421656 10.45562567081998 +-5.182388596400623 5.421517171041404 10.99010969757212 +2.805260206067855 6.955610338155246 8.559401701678954 +3.142705464461009 6.809801932776527 9.201736400166771 +0.4889196700818591 7.484046870257231 16.06177847135192 +4.065534732075854 6.30249373996396 12.14079813493886 +4.102125117550692 6.278739484957129 12.72722322226312 +-7.419233122523281 1.097715752667078 15.30743004664125 +-5.524357513315626 5.072620039493712 3.568263189095562 +1.921799689007443 7.24959902031353 7.278010075689139 +2.673712043434644 7.007229403180157 7.200350896773182 +1.380092153916959 7.37192957418184 6.709122402329522 +2.98543168433129 6.880203315178327 7.833781970324329 +2.891370597066051 6.920258381767397 16.44850279288868 +3.106228165999114 6.826517895732332 15.98166368119324 +3.393981421876234 6.688115587215802 16.42168297671037 +3.640948103736199 6.556942649276397 15.89402423381899 +-7.345231323281194 1.515775975363377 10.03067662974625 +0.5828293352388217 7.477319704679283 20.50803027300543 +1.036458477541417 7.428038356412313 20.23808967150071 +1.057638349261068 7.425052263935408 7.418727535567347 +0.1868795929441807 7.497671373015826 7.394755371079749 +0.6039605220479199 7.475642560195586 6.769673959682487 +0.727488953048905 7.464633937655068 8.071192596354145 +-0.4804755531190052 7.484593725971703 20.50210729945182 +0.0809052732346648 7.499563609755092 20.72764677974513 +-1.040105957516185 7.4275284985747 20.22370387158464 +0.9691504552119951 7.437119563054125 17.48382093085722 +1.340912298275594 7.37915674100593 14.50485129749923 +1.405230519566761 7.367179052179886 13.77313994382397 +1.952846377012274 7.241297606630323 14.38010296935303 +4.377906945752601 6.08965768942156 7.629796024147184 +4.744141569711785 5.808882918989897 7.463236472525313 +4.67684284063426 5.86320228578275 8.128859298018179 +5.156786739138333 5.445874633798232 7.659301115065554 +4.072991629581438 6.297677284948756 8.196332579097666 +4.637527031614521 5.894348397494383 8.872533643191858 +-0.1061802487076224 7.499248345986709 8.089904773354824 +-0.6670497455112923 7.470277413658299 7.336935589855245 +1.99404228108931 7.2300619209816 13.62087525358527 +-2.919784941333164 6.908317877483931 12.22378862308165 +-2.264289260063578 7.15003455563403 12.40118212616269 +-2.733091876380186 6.984282983618622 12.88074457329199 +-4.57510488299009 5.942929859054391 11.16283095614495 +-3.997612206964533 6.345793618037712 10.66259187710179 +-4.092511029507372 6.285010220624986 11.59932704348729 +-3.490204820134513 6.638408718473864 11.04873030193456 +4.639624938514585 5.89269721179644 2.623768887780708 +-6.428886741118123 3.862565891978492 8.969630437104207 +6.44481668413679 3.8359272552894 12.69777803894613 +6.774530435480255 3.218033153768261 12.59514740934348 +6.684835541744286 3.40043729244231 13.26912604874007 +0.2558032054231009 7.495636378593566 13.36679944024238 +-0.5951707773471343 7.476347486961265 13.43768419910713 +-0.06998729639147595 7.499673444780367 12.73526684579505 +-0.1531669062465289 7.498435830146902 14.0373945665311 +-0.4557899279800221 7.486137558284109 12.07245927976799 +0.3707623140410386 7.49083008127183 12.03406550311848 +-0.03275344231438933 7.499928480460102 11.46260650071719 +2.230741718111014 7.160572001389213 12.79040279010136 +1.49216191806648 7.35006481673952 13.12749767116425 +1.600523436112197 7.327231723540317 12.39693147823645 +0.8038078959838604 7.456801785373807 12.74078253410339 +2.676380599428941 7.006210593965927 13.29900350295545 +3.535411603701256 6.614443649500275 9.790337067548386 +3.959935732459271 6.369372731658295 9.091432478801707 +4.073189847681821 6.29754908394859 9.743323719011597 +-2.138893747836655 7.188541822613629 13.07106671631237 +4.454571178598683 6.033804406408774 10.05727296314545 +4.420413045674948 6.058873534381348 10.73075024647559 +4.390322371519872 6.080712908379422 9.51501210865681 +4.851493292623793 5.719529074288052 9.677532281297552 +1.7164898591135 7.300935732052468 15.18544302824033 +4.258355770899215 6.17384856701631 14.89555737188502 +4.718805912642564 5.829482889485959 14.83422618042218 +4.618993461362751 5.908883092758574 15.68936796803721 +1.357924560973929 7.376045070815644 15.98000084049269 +0.9520838063694108 7.439323653777212 15.26345533492018 +2.661664893005383 7.011814315663432 10.38914856436809 +3.281406035459232 6.744062160927323 10.59084444885542 +2.584212425719004 7.040727671111808 11.16309560676798 +-2.513966610519805 7.066114341078239 8.830625268354765 +-1.955608408088116 7.24055217191445 8.029844427728001 +-1.721677137518431 7.29971422962203 8.919025995665699 +-2.632698979535486 7.022741351007654 7.838436084455536 +2.935431929144996 6.901683808271434 9.838813476332986 +5.114414496349937 5.485687227643006 15.15756523305007 +6.987425579787014 2.725047479758492 12.57059906830552 +7.135550247516552 2.309528667318608 12.20011293362016 +-0.03640301976696286 7.499911654156458 15.25966170342857 +-0.5211028902054954 7.48187488386564 16.07515107808198 +0.2113223959843721 7.497022265203394 8.809461190920707 +-0.4851968541985257 7.484289145448341 8.76984631384798 +4.639907862943229 5.892474439774651 13.0756338882315 +5.215096477960037 5.390062033554792 12.57730044995882 +5.093487556613837 5.505123478235524 13.50944188782811 +5.579432454206031 5.011978999252937 13.00674655483921 +4.091797847334355 6.285474554602057 13.46489472834503 +-3.961036621178791 6.368688160499029 15.27253660477284 +-4.218306564742389 6.201281297107177 15.7456761598893 +-4.576470605820003 5.941878221073326 15.20067748746877 +0.4939717030537626 7.483715117278461 14.60714647208671 +0.6925731551968586 7.467954366806258 13.90912713554959 +-1.186315437185373 7.40558273760382 16.61502018539361 +-1.047061163609605 7.426551213023479 15.31099853195141 +-0.9747279542730739 7.436390617440603 17.35193813522587 +-7.112955350036098 2.378206506675324 10.38086890629921 +-1.700106949534953 7.304768056560247 12.32427317324634 +-1.509032196645943 7.346619755335506 13.24553589369827 +-1.012147324984527 7.431390030978503 12.70756791167545 +-0.7563989808005859 7.461759885030061 8.035886145336052 +-1.058247142722851 7.424965520789907 13.99059175961262 +-0.6980479437975015 7.467444614334952 14.64625291040032 +4.080608077479895 6.29274484768021 15.59228706938558 +3.660365054375136 6.546123102165839 15.04313549986099 +3.920909412147489 6.393470839984588 14.26256735641842 +4.521777581198813 5.983604892217383 14.05735751400028 +-5.174435927587342 5.429107922236702 13.53053186799944 +-5.221448703408015 5.383908750868532 12.5653959186148 +-4.653919940808747 5.881413876317729 13.03007756491096 +-5.756323449182563 4.807779149294499 13.00475748536162 +-1.215442140248972 7.400858085634868 8.426938235520174 +6.591774344999621 3.577500661719689 11.96291913588895 +-2.318234221278936 7.132726694279771 10.98114483975204 +-1.853061846387702 7.267472861556636 10.52412645490791 +-1.74949832399314 7.293096435283521 11.34900385736208 +-2.963490295970646 6.889682522851674 11.44956534291106 +-4.590958292594175 5.930691524237353 17.21623870476877 +0.8002324233427255 7.457186337260926 9.504252690625254 +1.338369032641028 7.379618440845537 10.19067822353398 +1.999537430043156 7.228544117998895 15.81936781844439 +2.337609034683808 7.126400494005697 15.01036517924012 +2.613367211259786 7.029958166241976 15.74991402580759 +4.147997024703737 6.248529481649978 11.51155336938142 +-3.591751531065415 6.584020119887943 14.67349980691677 +-3.352989253150448 6.70876017370256 15.46102660038082 +-3.719064989883176 6.512952909473955 15.93600190518789 +-3.647326727071498 6.553396657153442 8.226912969435974 +-3.052634974088213 6.850651043147173 8.451808944895754 +6.081037750492128 4.389872421504941 12.74170031995914 +-3.951693379755452 6.374489738982795 13.99771677105843 +-4.053677489987026 6.310126687093729 13.13733490767079 +-3.465124199342748 6.651534731408179 12.78040553931643 +2.366906212709078 7.116723612747594 9.884569821520587 +2.069783605226845 7.208744400208276 10.51579842788316 +-4.548872568408905 5.96303264760281 13.68805257118919 +1.825131112997387 7.274537539965611 11.27149760335395 +2.301132408702257 7.138262368225208 11.97765720270564 +0.8553469198862498 7.451065806087146 6.000247869139668 +0.5942302087348516 7.476422303416717 4.38857428739635 +6.223379609957308 4.185635702060993 16.59548120319397 +3.406136975082378 6.681933171394089 8.434100271786598 +-3.429372660708634 6.670037717583326 10.11373000400747 +-4.455068983863519 6.033436860448385 10.28164547092152 +-6.147379126016611 4.296478776977169 19.75223229140723 +-5.202591328467333 5.402133233173401 14.38032613610313 +-5.694252517633833 4.881135960554751 13.87078774223537 +-2.692618228980688 6.999986219483643 15.53745768756851 +5.524592546348286 5.072364063908758 13.88839245479244 +5.084011949130383 5.513875452084449 14.3514362094392 +5.946086760391833 4.57100122925962 13.47764911041258 +5.910360521233651 4.617102826344968 14.09523068645108 +6.30074856836212 4.068238866915595 13.58237780616347 +-5.669263810042142 4.910137253901 16.70746726431607 +-2.868884185096954 6.92961063354216 14.87739532605421 +-6.647352272842901 3.473140907122875 12.40246792742292 +1.125654961590763 7.415045576896079 11.72045392366731 +-1.19408794715764 7.404333459161118 11.76705062527067 +-2.338815467749447 7.126004645509006 11.79679544097584 +-1.524289981496887 7.34346921095937 7.230333118239573 +-4.875599294352009 5.698993904270664 16.56652701579391 +-3.532624160740756 6.615932779204356 12.02846368375189 +-4.064364744253457 6.303248307473658 12.49218640357833 +-4.73330466350782 5.817716645077786 12.14445721234283 +5.828399686504051 4.720143757806481 12.17121841381502 +4.743085615318444 5.809745161860308 12.12351027553061 +1.710119978497908 7.302430393995023 16.54739758908575 +2.257295843322212 7.152245484861399 16.55804046522241 +-5.808209649519497 4.744965823610176 12.06156801118239 +-5.219207360857223 5.386081555674197 11.70267121679299 +-1.339346770168924 7.379441051274688 10.14836692267904 +-1.35294166675977 7.37696067810757 9.511214174243808 +3.393277491114345 6.688472760525884 14.28992445757885 +-1.986533642381298 7.232128600051805 4.663389809793289 +5.531908511364555 5.06438428852831 3.415169189257363 +-1.874006710167439 7.262100168012516 2.243391147724217 +2.666712986276683 7.009895994151647 14.13059458322272 +-5.002368205952716 5.58805085267425 18.36522340493114 +5.50519948959957 5.093405401076243 8.030681689636845 +5.122731452753166 5.477921363343346 8.464151293455762 +5.628951604012446 4.956299409810279 8.639894696905404 +5.840105430473341 4.705652830474833 3.208869092101661 +-6.060830989559424 4.417728796111881 8.736300828051647 +-6.285962104262681 4.091048817085111 8.377351623997511 +3.904553157912535 6.403472857523115 10.94775412953775 +3.9116524161653 6.399138643216615 10.32635308023206 +4.437344305146994 6.046484558615819 6.898947749011606 +3.190461153422645 6.78755903315036 15.50361234292705 +3.040840167996511 6.85589462234499 4.926895611832167 +2.92087646130363 6.907856447393966 4.4257111693927 +2.987652418167103 6.879239276854692 14.99991803590116 +6.07800040916767 4.394076811590535 8.806680364580341 +5.813044374280942 4.739041580598412 9.485608994198619 +5.103641279815283 5.495711572395828 15.80595128271545 +0.8921529822898194 7.446748488850109 13.27468413068857 +-5.566816311863439 5.025988076982586 6.264847480494834 +-6.162848711787216 4.274259673396394 13.36033262530167 +-0.8536449419657869 7.451260988118469 5.171372094886991 +7.140798699220863 2.293249645635127 11.69332351883915 +-0.1373633848972426 7.498741981191883 9.666910454763418 +-0.7774282954866808 7.459598195973874 9.857683347514225 +5.431984706468902 5.171415874660242 10.05656897646817 +6.614475860314995 3.535351339444244 13.83826930787182 +6.004571592381782 4.493898084287373 6.383752577631151 +-6.291742904114981 4.082152768885405 14.01367579113996 +3.07231289338486 6.841848689143977 6.410848122188874 +-4.496477450960347 6.002640296819821 16.62428297027694 +3.874504068648896 6.421699013658546 16.65123192373704 +2.729399030793699 6.985726943611698 17.95901089048207 +6.290540906805167 4.08400478694759 10.0167483240428 +6.26097611117024 4.129186134743211 9.400527887724348 +6.24622571768128 4.151465317665196 8.387715735873281 +6.313572764637676 4.04830815843179 7.884749006311862 +-7.396715395986025 1.240403704760391 5.515127332804632 +5.620090961604549 4.966344488986931 7.466418778514256 +-4.937765633177728 5.645216608050479 14.75508899439038 +-4.59869163675165 5.924697058084104 14.35514079695785 +-4.130502823491349 6.260107541019563 16.30075405300923 +-3.55235667021878 6.605358588869505 16.55917789151702 +-0.5566934285581094 7.479310959346471 16.83047073706565 +-6.005056257403036 4.493250420956373 14.17485798139302 +-3.287485084750197 6.741100935125137 6.311708755435135 +-6.580995950742985 3.597289576376141 10.5983152686334 +6.289019066337625 4.086347902864101 16.01407249318006 +1.632163989803858 7.32024867817942 10.79184394172941 +6.463144214313489 3.804966079347631 15.46624640780205 +-4.148567728506677 6.248150590534207 14.66669108764011 +2.251049288590595 7.154213940073066 19.86835916118286 +-1.811997210721538 7.277820148116974 19.64232980691497 +1.772780759972535 7.287472015525768 19.71719804369048 +-7.05961091661644 2.532171737064845 13.26444303704199 +4.129310796625844 6.260893893436402 16.14518642606297 +5.279260579866657 5.327232652124926 9.207903196825878 +1.337959067170051 7.379692780500923 9.507179360741167 +-6.154354623227247 4.286480977627383 11.4220249521774 +3.406715446153217 6.68163826235311 11.31740867800468 +0.4958671362945847 7.483589765823819 21.3646687393531 +-0.06932111808936391 7.499679631996746 1.293308100183166 +-6.226563885824895 4.180897293134715 12.5440768781818 +6.612223254217174 3.539562633488727 10.20976929159034 +0.7506447926458223 7.462340946062014 8.807965770046509 +-4.827690464621105 5.739634550893156 5.360201691895756 +7.137038290723122 2.304926123925012 10.45717637681688 +1.066995948623921 7.423713332667159 21.61318192392523 +1.743642737695822 7.294498612192657 11.79303693621019 +-6.435902695657334 3.850864382451122 9.588603055502791 +-0.7525224138955897 7.462151835535428 9.363505982906322 +-1.114946229201836 7.416663326994735 8.984836684984197 +-6.192922341192694 4.230568859616445 12.01557446246017 +-6.455009065793908 3.818750837711 11.89891384752194 +1.001567233681629 7.432823358348786 12.23775282414386 +-1.296883320782343 7.38702197453592 7.795578032862426 +-0.04095241278933071 7.499888192492388 14.64023051518921 +-4.897218984694311 5.6804265874976 13.93744054422202 +2 18 0 81 +3584 +3585 +3586 +3587 +3588 +3589 +3590 +3591 +3592 +3593 +3594 +3595 +3596 +3597 +3598 +3599 +3600 +3601 +3602 +3603 +3604 +3605 +3606 +3607 +3608 +3609 +3610 +3611 +3612 +3613 +3614 +3615 +3616 +3617 +3618 +3619 +3620 +3621 +3622 +3623 +3624 +3625 +3626 +3627 +3628 +3629 +3630 +3631 +3632 +3633 +3634 +3635 +3636 +3637 +3638 +3639 +3640 +3641 +3642 +3643 +3644 +3645 +3646 +3647 +3648 +3649 +3650 +3651 +3652 +3653 +3654 +3655 +3656 +3657 +3658 +3659 +3660 +3661 +3662 +3663 +3664 +7.5 -0.9643239102786443 0.9288091779290182 +7.5 -0.9999999999999978 22.02999844163939 +7.5 -0.9811948405704127 11.58896465366788 +7.5 -0.9811948405704152 6.395416266571138 +7.5 -0.9999999999999991 7.790322580645144 +7.5 -0.9796064338740877 9.232098968471881 +7.5 -1.020109706048206 2.584865721261228 +7.5 -0.9827832472667417 4.038550581375127 +7.5 -0.9999999999999991 14.46774193548385 +7.5 -1.018805159429589 17.34651921729981 +7.5 -0.9866455199833934 19.69161687616492 +7.5 -0.9999999999999991 12.9838709677419 +7.5 -0.9999999999999991 15.95161290322577 +7.5 -0.988233926679718 20.96603259407186 +7.5 -0.9991895884202409 10.45877294055361 +7.5 -1.000810411579758 5.26522455345687 +7.5 -0.9991895884202422 18.47671093041408 +7.5 -0.7480526689369058 1.755191783096147 +7.5 -0.6403985896827336 16.681631385218 +7.5 -1.359601410317271 12.25385248574968 +7.5 -0.7064255983350709 13.72580645161287 +7.5 -1.317961462470468 8.530692698154057 +7.5 -1.359601410317274 7.06030409865293 +7.5 -0.7064255983350565 15.20967741935481 +7.5 -1.318827415623949 3.336701472050962 +7.5 -1.38312057168654 20.36311736556189 +7.5 -0.6086673246700431 20.35738758829193 +7.5 -0.6019286052526001 7.066773328244253 +7.5 -1.406291809127395 15.20967741935481 +7.5 -0.5937727051569177 8.530634487052954 +7.5 -0.5935946417575535 3.338709677419349 +7.5 -0.6019286052525972 12.260321715341 +7.5 -1.406291809127399 13.72580645161287 +7.5 -1.398071394747401 16.67516215562668 +7.5 -0.6278031724758655 4.621915082965097 +7.5 -1.365928441047606 9.815463470061847 +7.5 -1.367101622065825 19.11805906318403 +7.5 -0.6306880329485147 19.13106447829383 +7.5 -0.6293193217605957 9.802131165331748 +7.5 -1.363367560683454 4.608582778234995 +7.5 -1.471035063406596 1.932891999215736 +7.5 -1.38226240027749 10.99713651238892 +7.5 -0.6340265579878341 11.01480418393536 +7.5 -1.382262400277486 5.803588125292188 +7.5 -0.6342966951810882 5.821255796838622 +7.5 -1.365703304818913 17.92067968703233 +7.5 -0.6375350952212671 17.91773507510792 +7.5 -1.369271161675282 21.67466541774155 +7.5 -0.6286645663302342 21.64570126697188 +7.5 -1.43654613250087 22.42225728533582 +7.5 -0.5634538674991258 22.42225728533582 +7.5 -0.5634538674991321 0.5777427146641736 +7.5 -1.4738785189327 0.5277592751942426 +7.5 -0.4543861300157794 1.138170772925798 +7.5 -1.442881693592474 1.228409781174674 +7.5 -0.4311914672216428 7.790322580645144 +7.5 -1.550385438237578 9.24926237405305 +7.5 -1.568808532778355 7.790322580645144 +7.5 -0.4405396921583196 9.222650343526146 +7.5 -1.568808532778355 2.596774193548382 +7.5 -0.4461914439442705 2.588643333572549 +7.5 -1.550536651113291 4.054308360044411 +7.5 -0.4408362123000313 4.032093132868041 +7.5 -1.568808532778362 14.46774193548385 +7.5 -1.568808532778368 19.66129032258062 +7.5 -0.4311914672216366 14.46774193548385 +7.5 -0.4311914672216288 19.66129032258062 +7.5 -1.568808532778361 12.9838709677419 +7.5 -0.4311914672216375 12.9838709677419 +7.5 -0.4311914672216495 15.95161290322577 +7.5 -1.568808532778349 15.95161290322577 +7.5 -1.544611730233035 11.56799073036128 +7.5 -0.4434300007621681 11.57281811058883 +7.5 -0.4593477688667171 17.36337068391223 +7.5 -1.556515971799181 17.36266576037885 +7.5 -1.544611730233035 6.374442343264538 +7.5 -0.4434840282008199 6.37926972349209 +7.5 -0.999999999999998 22.61777626275197 +7.5 -1.000120721334583 0.375578269325175 +7.5 -1.542523726543357 21.0457923787918 +7.5 -0.4580274281480925 21.03294131575856 +2 19 0 346 +3665 +3666 +3667 +3668 +3669 +3670 +3671 +3672 +3673 +3674 +3675 +3676 +3677 +3678 +3679 +3680 +3681 +3682 +3683 +3684 +3685 +3686 +3687 +3688 +3689 +3690 +3691 +3692 +3693 +3694 +3695 +3696 +3697 +3698 +3699 +3700 +3701 +3702 +3703 +3704 +3705 +3706 +3707 +3708 +3709 +3710 +3711 +3712 +3713 +3714 +3715 +3716 +3717 +3718 +3719 +3720 +3721 +3722 +3723 +3724 +3725 +3726 +3727 +3728 +3729 +3730 +3731 +3732 +3733 +3734 +3735 +3736 +3737 +3738 +3739 +3740 +3741 +3742 +3743 +3744 +3745 +3746 +3747 +3748 +3749 +3750 +3751 +3752 +3753 +3754 +3755 +3756 +3757 +3758 +3759 +3760 +3761 +3762 +3763 +3764 +3765 +3766 +3767 +3768 +3769 +3770 +3771 +3772 +3773 +3774 +3775 +3776 +3777 +3778 +3779 +3780 +3781 +3782 +3783 +3784 +3785 +3786 +3787 +3788 +3789 +3790 +3791 +3792 +3793 +3794 +3795 +3796 +3797 +3798 +3799 +3800 +3801 +3802 +3803 +3804 +3805 +3806 +3807 +3808 +3809 +3810 +3811 +3812 +3813 +3814 +3815 +3816 +3817 +3818 +3819 +3820 +3821 +3822 +3823 +3824 +3825 +3826 +3827 +3828 +3829 +3830 +3831 +3832 +3833 +3834 +3835 +3836 +3837 +3838 +3839 +3840 +3841 +3842 +3843 +3844 +3845 +3846 +3847 +3848 +3849 +3850 +3851 +3852 +3853 +3854 +3855 +3856 +3857 +3858 +3859 +3860 +3861 +3862 +3863 +3864 +3865 +3866 +3867 +3868 +3869 +3870 +3871 +3872 +3873 +3874 +3875 +3876 +3877 +3878 +3879 +3880 +3881 +3882 +3883 +3884 +3885 +3886 +3887 +3888 +3889 +3890 +3891 +3892 +3893 +3894 +3895 +3896 +3897 +3898 +3899 +3900 +3901 +3902 +3903 +3904 +3905 +3906 +3907 +3908 +3909 +3910 +3911 +3912 +3913 +3914 +3915 +3916 +3917 +3918 +3919 +3920 +3921 +3922 +3923 +3924 +3925 +3926 +3927 +3928 +3929 +3930 +3931 +3932 +3933 +3934 +3935 +3936 +3937 +3938 +3939 +3940 +3941 +3942 +3943 +3944 +3945 +3946 +3947 +3948 +3949 +3950 +3951 +3952 +3953 +3954 +3955 +3956 +3957 +3958 +3959 +3960 +3961 +3962 +3963 +3964 +3965 +3966 +3967 +3968 +3969 +3970 +3971 +3972 +3973 +3974 +3975 +3976 +3977 +3978 +3979 +3980 +3981 +3982 +3983 +3984 +3985 +3986 +3987 +3988 +3989 +3990 +3991 +3992 +3993 +3994 +3995 +3996 +3997 +3998 +3999 +4000 +4001 +4002 +4003 +4004 +4005 +4006 +4007 +4008 +4009 +4010 +0.007448718700271053 1.732549512569409 23 +-3.611777723147425 -0.03924471437003163 23 +3.616685730912323 -0.08499451335206176 23 +-2.918800409957688 3.125661273983171 23 +2.855812315090158 3.128757236398526 23 +0.6858555706371541 -0.9687112176115598 23 +-0.4031200202089925 4.718942747706224 23 +-5.305061793363473 -1.619411016852633 23 +5.171061593549961 -1.716457799300581 23 +-1.579485054999873 -1.511651844906277 23 +-4.889825490598049 1.819136739499509 23 +4.876676298336354 1.883609795551783 23 +1.741584802983804 5.003736921765134 23 +2.85038936835925 -1.946909754228622 23 +-1.99624588171257 1.300678616112997 23 +1.96991192923344 1.261551693185133 23 +-5.623656536812067 0.1416789610056803 23 +5.623656536812075 0.1416789610056635 23 +-2.364812959552856 5.020600657992713 23 +-3.327429175611435 -2.112237259916826 23 +1.140346470395686 3.292968386930118 23 +-0.6376783493456195 0.01119518588881063 23 +-1.181508236586788 3.02202864582377 23 +4.639881086133862 3.518954974391454 23 +-4.543385883283516 3.524940035007881 23 +3.405008102938154 4.855414973952002 23 +-0.03743395911859213 -2.508241833064131 23 +0.4442039135332702 5.908920227411056 23 +2.052350091667426 -0.2268584834159677 23 +4.006119807409396 -2.541911144472357 23 +1.296316141850685 -2.510958665759706 23 +-3.455272929841763 1.417570856410942 23 +3.465582897563624 1.438743719875645 23 +-1.214869501660218 5.950776817399033 23 +0.8004764909430072 0.4535957957065033 23 +-1.887021517955704 -0.184676227513787 23 +-3.871870971594621 4.770566499363291 23 +-6.057308052214105 -2.557308052214108 23 +6.060168164897137 -2.541220878923331 23 +-6.149951287767109 -0.9446815959932735 23 +6.230413463893578 -0.9383078109217133 23 +3.953254243809962 -1.302679123748735 23 +-2.213501100709423 -2.761408705304841 23 +-4.431608204627786 -2.793183794642018 23 +-6.08410685419002 1.369226730954272 23 +6.084106854190037 1.36922673095425 23 +-4.686326544681393 -0.5626241533598559 23 +-4.64254817796316 0.6817476859814484 23 +4.555089171255407 0.7129653681510031 23 +5.619809997307965 2.847345865449569 23 +-5.619809997307947 2.847345865449593 23 +-0.3286236863635326 -1.175322091187236 23 +-2.922342466398551 -1.051680020600298 23 +2.696081719630973 5.716968354620949 23 +-2.017242559398398 3.925763628237776 23 +1.934844893103303 2.477391189449248 23 +0.7344977912775629 4.447444509222265 23 +-0.03527201325176992 3.536114418903152 23 +1.587305155414754 6.164957551467822 23 +-3.884417288834061 2.49064752518837 23 +3.939014715580777 2.513219766072317 23 +4.869737458371378 -0.6211134069147293 23 +2.064699053799773 3.905910792978658 23 +5.0409417047864 -2.925630285321198 23 +-0.9056392318411385 1.106113951912833 23 +-2.121064262235865 2.440131990827894 23 +3.023012057426681 -3.013271494119192 23 +-4.109835721419232 -1.405850212326474 23 +2.879497887731217 -0.871824766256275 23 +-1.141536242746483 -2.860718998685792 23 +1.823677204462485 -1.278786353398482 23 +1.069178272454329 1.84226237033595 23 +4.503603246387112 4.576774794345031 23 +-2.215607970671577 6.081249485367274 23 +2.715612814440694 0.5760707157092819 23 +-2.725918995779007 0.6306619071703137 23 +-3.198523294467337 5.614258355827999 23 +-6.54977143303759 -0.08883676267207319 23 +6.549771433037595 -0.08883676267207674 23 +6.608631829158519 -1.838521044880582 23 +-6.608631829158521 -1.838521044880581 23 +-5.30191220479813 -3.060601914200779 23 +-0.3684432450848611 6.566839508053182 23 +-2.956842165474067 4.13826757452996 23 +-1.423983197214024 4.776866141780989 23 +-3.627709427771418 -2.930077310777982 23 +-1.17651857245022 2.019431877505207 23 +3.627073976542596 3.818796677729247 23 +-4.714576168657967 4.552891698500106 23 +2.948595223720595 1.994469555214233 23 +0.4396566554562444 -3.07505472766281 23 +2.012750318321678 -3.161212207969923 23 +0.1515536945131816 -0.3498150498513644 23 +0.4196095492184408 2.59516368172654 23 +-1.289581984567493 -0.6553622786133015 23 +-2.524229813039576 -2.059094144009117 23 +-3.12477859000855 2.243629905198672 23 +-5.429059235286885 -0.8887155284621699 23 +6.272223017296147 2.247844184076912 23 +-6.272223017296126 2.247844184076937 23 +-1.535974046447336 0.6130816598959283 23 +0.6502781612407973 -1.896320644669405 23 +-0.2514545011476497 5.487192014160423 23 +-1.006964585542881 3.902155659080355 23 +-3.834295257301144 3.593078667583699 23 +-5.456448197707132 3.728503513963046 23 +5.392027360159975 3.71049923790999 23 +-0.1209511740383058 0.7056700619997509 23 +1.145878051466453 -0.3294253889144056 23 +1.655135134335495 0.6454033452757302 23 +-5.330658382842404 0.9356335307402401 23 +5.329433354500512 0.8328579608632748 23 +2.611299845444957 4.567198747881285 23 +3.49076952969238 5.670157404454036 23 +-6.603407082918562 0.6903733432763468 23 +6.603407082918573 0.6903733432763308 23 +-4.589889549813762 2.787518606906238 23 +4.714802377770082 2.703950396248352 23 +5.680987055544762 -3.30771359538091 23 +-3.703172566903958 -0.915283767725656 23 +-0.7629829101048251 2.549160738792815 23 +0.9589149189787247 6.626903829056558 23 +3.538074969787087 -1.911138519492058 23 +0.9791166916242651 5.189226153802108 23 +-1.026017038339874 -2.081361509184032 23 +4.356716864524185 -1.853867014566636 23 +4.329644026498713 -0.02770713017320392 23 +-0.3684155243947426 -3.136058944935054 23 +4.314628767321797 -3.265451567078117 23 +-5.971937757187022 -1.924539501377455 23 +5.889045119769833 -1.857415476569161 23 +5.536294085887766 -1.088848767286868 23 +-5.428667405084476 -2.412735135725104 23 +-2.932714384953957 -3.338150310150419 23 +-2.108251431837203 -0.8699606432443385 23 +-3.769436641736402 0.6589089207843692 23 +3.767539453587856 0.6895909028139191 23 +-1.586867724330953 6.569501976216431 23 +-4.237854126708021 1.401214045995478 23 +4.27277459760427 1.349244392739518 23 +1.912933252877294 -2.039122747070252 23 +2.863795258827448 3.814457700812522 23 +-6.727993579791288 -2.625693980719432 23 +6.726250496425323 -2.64154161808082 23 +-6.125693980719434 -3.22799357979129 23 +0.4694685919767749 1.316371630010921 23 +5.4017114670054 -2.34474912933359 23 +-4.090229283091137 5.519553117746376 23 +-2.576056509336239 -0.3405912057858664 23 +1.246743579599352 -3.175752384961219 23 +2.290563572976113 6.386082887735623 23 +-2.767548759434064 1.494792285170584 23 +-4.92083747822769 0.06894939530730149 23 +-2.055263592508941 3.10997226007022 23 +0.266778246296397 4.993993482326005 23 +5.590354492016323 1.9485700816561 23 +-5.590354492016307 1.948570081656113 23 +-1.746705666095248 5.395873725299071 23 +-4.601570929715917 -2.066276548907878 23 +2.689422150920224 1.276056270135514 23 +2.810567682450758 -0.1658855545760667 23 +2.186487022660574 3.166311794963766 23 +1.344398987490149 3.978271612008254 23 +1.137141497666708 2.527721179479265 23 +1.270883747125968 -1.705711513598657 23 +5.170906154860269 4.534795696627258 23 +-6.826450397787701 -1.120968945015281 23 +6.834870744317877 -1.120841578411872 23 +-4.28344364829379 0.0508167568979867 23 +3.599805404120911 -3.288545705461158 23 +4.143921319339753 5.254158504387219 23 +-1.633965883274112 -3.321876963954708 23 +-3.064572928335832 4.863873731352111 23 +-1.673000879245732 -2.266425991930385 23 +5.957496083376767 -0.4052331838774426 23 +1.271107086577139 1.218795805241146 23 +-5.972976946618164 -0.3951945161340058 23 +4.676319696401261 -1.275528040038706 23 +6.286286498705152 -3.137097369787593 23 +3.504499749747595 -0.734502479495267 23 +-4.185411676831464 4.12009871704298 23 +-3.49656298922644 -1.486161585899449 23 +5.007450721841309 0.1173400823214363 23 +3.981367873991292 3.185239344461154 23 +6.683170329970071 1.681851305866195 23 +-6.683170329970051 1.681851305866224 23 +0.6318958874051993 3.772994059464425 23 +-2.915886898878094 6.215449488290467 23 +-2.925116780417162 -2.640193546031837 23 +-4.728874893801822 -1.251344086254341 23 +-4.228794049613415 -3.423815144503062 23 +2.023410785901549 5.652585766245758 23 +-5.897055072868836 0.6729380475113245 23 +5.959219307590988 0.6903255531525958 23 +-0.9489925407447666 5.262201098115504 23 +-3.964780156649647 -2.352479990024225 23 +0.1541731406419253 -1.422477432269819 23 +0.1866288084328636 6.735418615724138 23 +-6.266777484506216 2.970962083073131 23 +6.266777484506227 2.970962083073122 23 +-0.9094799781400507 6.720987949358221 23 +2.481743343079833 -2.561878583830699 23 +2.285305235389066 1.910338206991228 23 +5.09963696173836 -3.499178713184871 23 +0.1282653251998021 4.236887665054541 23 +4.7405993353751 -2.359256032591521 23 +4.158356817623538 -0.6744207822871169 23 +-4.073186829063276 3.075032401347111 23 +-4.570765436488331 5.180427367988003 23 +-0.650545348478703 1.771272498265506 23 +3.202732209028966 -1.35354894672804 23 +-0.4251119209414191 -0.5903762997186472 23 +-2.420168464166546 4.383997407149725 23 +-1.283584591776556 0.00676697228243639 23 +2.976603218246529 6.263342924651581 23 +2.282228721098728 -0.7638719633949487 23 +2.904748027638782 5.174692222554333 23 +-0.9103175153070922 -1.289675374123575 23 +3.579246215109491 2.116731628373704 23 +4.226347148881607 3.979027453826982 23 +-7.007213638377284 0.2351264537742894 23 +7.007213638377285 0.2351264537742819 23 +-0.4374019106176141 -1.801887776345644 23 +-5.328454028129941 4.3421609245868 23 +-2.582094866499532 3.674470463601656 23 +1.682413642000662 -0.6368408874180749 23 +1.077979687757423 5.852820932700427 23 +-1.403370015453461 1.470057911045046 23 +1.696129679745904 6.752532327022888 23 +-3.842950945665644 1.906815521729148 23 +3.321952029455237 2.696917251936114 23 +5.093563837192538 3.155036769197669 23 +-5.063231821388874 3.208814117226702 23 +4.257904474870902 2.006185462528911 23 +2.490677034738687 -1.354239037147285 23 +3.364662199208779 -2.515042347796931 23 +-2.593919994089108 5.577921430091806 23 +-2.223247491858876 0.4226725940564826 23 +-5.821762313991873 -1.374401135323901 23 +-4.817269798540733 1.254267376804264 23 +4.854488857172421 1.252450718676608 23 +-3.513946166083894 2.97897717204937 23 +-6.985881946228006 -0.4418925569714593 23 +6.985881946228006 -0.4418925569714593 23 +2.583181457100009 -3.392262091008126 23 +-1.498621967423279 3.542288454091594 23 +1.323181328672189 4.582651971989536 23 +7.006943084203479 -2.180759818917764 23 +-7.006943084203479 -2.180759818917762 23 +-0.6945110535206668 3.382820044824739 23 +-5.308367942087498 -0.3279171294273349 23 +1.670205166295795 3.449203573721221 23 +-5.677941152038926 -3.504658617580438 23 +2.588832786569822 2.562364205825519 23 +3.186584065481822 0.8851739433734933 23 +1.611248152403997 1.873010074113661 23 +-6.038693450880608 3.449812747265557 23 +6.003228829480489 3.525952353550552 23 +7.099433317792169 -1.670211244500212 23 +-7.099433317792172 -1.670211244500214 23 +2.15352673607851 0.3623061289338436 23 +-5.21866000442367 -3.554997127303732 23 +0.5121506743063773 2.047475693948776 23 +5.381274636215549 -0.3607798332512457 23 +-0.95305568931192 0.5105538860507304 23 +-1.781557850433437 1.96217174480114 23 +-1.513149237386679 2.517149542970174 23 +-0.8871211722245806 -3.45015936649224 23 +-5.078948753525214 2.450383797275095 23 +5.20475851973113 2.425988061941921 23 +-6.578382846282524 -3.078382846282524 23 +-4.396917191261861 2.218482779332582 23 +1.933996898896239 4.498853475608316 23 +-0.4602953504826389 3.994700628230417 23 +-3.555020887829735 4.207327442225939 23 +-3.153599623371852 0.9024754143279736 23 +-2.251826438072591 -3.486879157666333 23 +-3.600088364699316 5.971464535458641 23 +0.6924137610612698 -2.516243165848309 23 +-2.584901101914606 2.620998076738664 23 +-4.250677726006579 -0.9460037437942264 23 +-2.368700507800658 6.624740997456101 23 +0.192845536852874 0.2058559789060719 23 +0.1503692138435435 -3.533887377765661 23 +0.714422954787904 -3.561500844070579 23 +-0.2522634473896686 1.304799009669105 23 +4.775936242142719 5.093321650895826 23 +2.318520346749383 5.102339248112629 23 +-0.1278982970086184 6.15318951283454 23 +-2.880243489922398 -1.64303904992007 23 +0.5099784858196419 3.170930188068811 23 +6.229574008865578 -1.433060870584273 23 +3.891927053610224 4.49064889916801 23 +0.04756935969746184 -0.9013404181277251 23 +-1.475869548146817 4.21127450494139 23 +5.337268259867639 1.463800115335197 23 +-5.312908981428894 1.479942759822201 23 +-2.396016074289848 2.010400436474992 23 +-6.135876467548345 0.2239352069537277 23 +6.135876467548345 0.2239352069537002 23 +-0.654888135047364 -2.526186720015918 23 +-6.275746717178445 -1.440622444518098 23 +1.813294319257039 -2.635678621794794 23 +-4.902256849386401 3.99553208564409 23 +-0.3539475473592389 7.045105883744529 23 +3.362298135660189 3.315176229048869 23 +-4.922107748568187 -2.708504499642646 23 +1.488123829943349 5.533268165141685 23 +-0.1032815774229819 2.924126062150238 23 +5.692202095617384 4.221624793705455 23 +-3.054476858594401 0.1921346328329498 23 +3.21939794937469 0.3799910987937132 23 +5.650128087247839 -2.801838655897688 23 +-3.226833292191009 3.619630432328965 23 +1.324393480612032 -1.052700439952114 23 +0.6455083116555014 -0.1161592279063364 23 +-3.624510239134423 -3.538408553086293 23 +4.46704457497526 -2.772920822554767 23 +-2.518657256864226 0.9983123332146548 23 +3.291599379600513 4.249450974283624 23 +-1.698713841880679 5.927926398820241 23 +4.786552999284566 4.064010431420143 23 +-0.9523884381105191 4.438179041638898 23 +-0.6368563439643609 6.023531149986817 23 +-6.505772232188061 -0.5882604468603345 23 +6.514903305000925 -0.5777870838427472 23 +-3.31781906402351 -0.4924208059527091 23 +-6.425542580924317 -2.268919585000446 23 +6.425542580924317 -2.268919585000449 23 +-6.86755451714515 1.193557763883057 23 +6.867554517145163 1.193557763883037 23 +1.613805010024413 2.982719224908724 23 +-5.766580911333678 -2.925781041966935 23 +-4.811624813116309 -3.25685041338204 23 +3.056179525094121 -3.524607455991131 23 +-2.185538519392558 -1.528235447359946 23 +2.272695859466922 0.8557082926863151 23 +-1.943551385502464 4.665908414676136 23 +-3.578909113942032 5.236540977347454 23 +-0.09626681563023683 2.269958031242214 23 +0.1048508450333262 -1.955024780857503 23 +-3.900035794524534 -1.88460111941497 23 +1.581630024415259 0.04469675169460507 23 +-1.657916204238993 -2.796967936874134 23 +-5.233601603260402 0.4487752639089166 23 +-3.975536212176109 -0.4841267380507484 23 +2 20 0 481 +4011 +4012 +4013 +4014 +4015 +4016 +4017 +4018 +4019 +4020 +4021 +4022 +4023 +4024 +4025 +4026 +4027 +4028 +4029 +4030 +4031 +4032 +4033 +4034 +4035 +4036 +4037 +4038 +4039 +4040 +4041 +4042 +4043 +4044 +4045 +4046 +4047 +4048 +4049 +4050 +4051 +4052 +4053 +4054 +4055 +4056 +4057 +4058 +4059 +4060 +4061 +4062 +4063 +4064 +4065 +4066 +4067 +4068 +4069 +4070 +4071 +4072 +4073 +4074 +4075 +4076 +4077 +4078 +4079 +4080 +4081 +4082 +4083 +4084 +4085 +4086 +4087 +4088 +4089 +4090 +4091 +4092 +4093 +4094 +4095 +4096 +4097 +4098 +4099 +4100 +4101 +4102 +4103 +4104 +4105 +4106 +4107 +4108 +4109 +4110 +4111 +4112 +4113 +4114 +4115 +4116 +4117 +4118 +4119 +4120 +4121 +4122 +4123 +4124 +4125 +4126 +4127 +4128 +4129 +4130 +4131 +4132 +4133 +4134 +4135 +4136 +4137 +4138 +4139 +4140 +4141 +4142 +4143 +4144 +4145 +4146 +4147 +4148 +4149 +4150 +4151 +4152 +4153 +4154 +4155 +4156 +4157 +4158 +4159 +4160 +4161 +4162 +4163 +4164 +4165 +4166 +4167 +4168 +4169 +4170 +4171 +4172 +4173 +4174 +4175 +4176 +4177 +4178 +4179 +4180 +4181 +4182 +4183 +4184 +4185 +4186 +4187 +4188 +4189 +4190 +4191 +4192 +4193 +4194 +4195 +4196 +4197 +4198 +4199 +4200 +4201 +4202 +4203 +4204 +4205 +4206 +4207 +4208 +4209 +4210 +4211 +4212 +4213 +4214 +4215 +4216 +4217 +4218 +4219 +4220 +4221 +4222 +4223 +4224 +4225 +4226 +4227 +4228 +4229 +4230 +4231 +4232 +4233 +4234 +4235 +4236 +4237 +4238 +4239 +4240 +4241 +4242 +4243 +4244 +4245 +4246 +4247 +4248 +4249 +4250 +4251 +4252 +4253 +4254 +4255 +4256 +4257 +4258 +4259 +4260 +4261 +4262 +4263 +4264 +4265 +4266 +4267 +4268 +4269 +4270 +4271 +4272 +4273 +4274 +4275 +4276 +4277 +4278 +4279 +4280 +4281 +4282 +4283 +4284 +4285 +4286 +4287 +4288 +4289 +4290 +4291 +4292 +4293 +4294 +4295 +4296 +4297 +4298 +4299 +4300 +4301 +4302 +4303 +4304 +4305 +4306 +4307 +4308 +4309 +4310 +4311 +4312 +4313 +4314 +4315 +4316 +4317 +4318 +4319 +4320 +4321 +4322 +4323 +4324 +4325 +4326 +4327 +4328 +4329 +4330 +4331 +4332 +4333 +4334 +4335 +4336 +4337 +4338 +4339 +4340 +4341 +4342 +4343 +4344 +4345 +4346 +4347 +4348 +4349 +4350 +4351 +4352 +4353 +4354 +4355 +4356 +4357 +4358 +4359 +4360 +4361 +4362 +4363 +4364 +4365 +4366 +4367 +4368 +4369 +4370 +4371 +4372 +4373 +4374 +4375 +4376 +4377 +4378 +4379 +4380 +4381 +4382 +4383 +4384 +4385 +4386 +4387 +4388 +4389 +4390 +4391 +4392 +4393 +4394 +4395 +4396 +4397 +4398 +4399 +4400 +4401 +4402 +4403 +4404 +4405 +4406 +4407 +4408 +4409 +4410 +4411 +4412 +4413 +4414 +4415 +4416 +4417 +4418 +4419 +4420 +4421 +4422 +4423 +4424 +4425 +4426 +4427 +4428 +4429 +4430 +4431 +4432 +4433 +4434 +4435 +4436 +4437 +4438 +4439 +4440 +4441 +4442 +4443 +4444 +4445 +4446 +4447 +4448 +4449 +4450 +4451 +4452 +4453 +4454 +4455 +4456 +4457 +4458 +4459 +4460 +4461 +4462 +4463 +4464 +4465 +4466 +4467 +4468 +4469 +4470 +4471 +4472 +4473 +4474 +4475 +4476 +4477 +4478 +4479 +4480 +4481 +4482 +4483 +4484 +4485 +4486 +4487 +4488 +4489 +4490 +4491 +-0.1923557659816186 -2.000000000000001 16.01948822623212 +-0.1922008945621414 -2.000000000000001 6.981796757270097 +0.9187723576505649 -2 11.49999999999999 +-2.200590573397125 -2.000000000000001 13.35888674040356 +-1.969905312471975 -2.000000000000001 9.767374782367067 +-2.227445942311961 -2.000000000000001 18.28501979901599 +2.400285560304462 -2 18.26060521562173 +2.400285560304449 -2 4.739394784378273 +-2.227445942311975 -2.000000000000001 4.714980200983995 +2.501131995208394 -2 14.15434233233837 +2.410626301548065 -2 8.820059516079361 +-2.881924529004127 -2.000000000000001 15.78529528396619 +-2.881924529004126 -2.000000000000001 7.214704716033811 +1.332267629550188e-14 -2.000000000000001 19.10324173421307 +0.09988129524176248 -2.000000000000001 3.935877656394258 +3.186809855138458 -2 11.96443883615428 +0.2235435819704144 -2.000000000000001 13.7787707881874 +0.1958945111201107 -2.000000000000001 9.32234333641536 +3.250953235991233 -2 16.25442072396735 +3.250953235991237 -2 6.745579276032649 +-3.309061726855774 -2.000000000000001 11.52259414417081 +-1.076667953498837 -2.000000000000001 11.5 +-3.606632389600748 -2.000000000000001 19.64991083050744 +3.604234541993264 -2 19.65777776301172 +3.604234541993258 -2 3.342222236988281 +-3.606632389600753 -2.000000000000001 3.350089169492573 +3.812269436320951 -2 10.22711011193536 +-3.640767378200138 -2.000000000000001 13.90541657307101 +-3.673973222075185 -2.000000000000001 8.914644508824093 +-3.661005325496857 -2.000000000000001 17.1520215329559 +-3.661005325496864 -2.000000000000001 5.847978467044101 +-1.312193312353027 -2.000000000000001 15.01646349248404 +-1.344244958595471 -2.000000000000001 8.143942315904619 +1.581047746336031 -2 6.295673497743097 +1.581047746336043 -2 16.70432650225692 +-0.732315075604971 -2.000000000000001 17.55332457081025 +-0.7323150756049825 -2.000000000000001 5.446675429189753 +1.515950633330269 -2 19.85435229724455 +-1.538155716203093 -2.000000000000001 19.7673577407756 +1.542603186595302 -2 3.208693839662935 +-1.509541602573298 -2.000000000000001 3.168617827386228 +3.704737758373763 -2 17.8655091142507 +3.704737758373751 -2 5.134490885749297 +3.883573307826901 -2 13.42480816109425 +2.146862272729233 -2 10.31135344223035 +3.858647661728365 -2 8.123114698146503 +1.869124175664866 -2 12.71248705837846 +1.103097200941557 -2 8.074805686022099 +1.117433534516451 -2 14.94412735280359 +3.990230808514264 -2 14.9341778314916 +-1.657594491164001 -2.000000000000001 16.25850692543284 +-1.657594491164001 -2.000000000000001 6.741493074567167 +0.682692182276039 -2 5.16728427534445 +0.6826921822760417 -2 17.83271572465555 +-4.082802035510662 -2.000000000000001 10.27625918353421 +-4.123463070416971 -2.000000000000001 12.71379135397813 +-4.17816115402141 -2.000000000000001 15.30288831918368 +-4.178161154021407 -2.000000000000001 7.697111680816322 +-0.07894779792412976 -2.000000000000001 12.39983383299988 +-0.7187583614955706 -2.000000000000001 10.19397230044908 +-4.350716942221462 -2.000000000000001 18.62735579575372 +-4.35071694222146 -2.000000000000001 4.372644204246299 +2.289729388115731 -2 7.555226741655719 +2.304384942897385 -2 15.42956253866071 +4.25791422344879 -2 11.31014626771014 +-2.181912389958718 -2.000000000000001 12.045547323343 +-2.412213829742512 -2.000000000000001 5.919202120325219 +-2.412213829742508 -2.000000000000001 17.08079787967478 +0.3978159043312139 -2 20.26880837596444 +-0.3978159043312246 -2.000000000000001 2.731191624035556 +-2.535212543875918 -2.000000000000001 14.54961378946619 +-2.53521254387592 -2.000000000000001 8.450386210533805 +-1.131273629421443 -2.000000000000001 4.310209754263848 +-1.131273629421403 -2.000000000000001 18.68979024573615 +-2.641972966911059 -2.000000000000001 20.35934052474705 +2.641972966911054 -2 2.640659475252953 +-2.632157906995403 -2.000000000000001 2.64476937181043 +2.632157906995405 -2 20.35523062818958 +0.8931083662621013 -2 10.29971045224426 +4.388116073431066 -2 16.6990139157195 +4.394230457079866 -2 6.240644835713397 +-0.1513047236585408 -2.000000000000001 8.180462086399634 +-1.010105796640739 -2.000000000000001 13.84945671811785 +-0.167507290217686 -2.000000000000001 14.83852098211984 +4.387315508949081 -2 9.268528412247321 +2.084934553850981 -2 11.57525032235409 +1.345362228431878 -2 13.77530786617557 +1.411805200151094 -2 9.310021718136234 +-2.278740995564254 -2.000000000000001 10.86596201123571 +2.705091697880175 -2 17.28360237723736 +2.608644152772827 -2 5.805595099022444 +4.424319112386568 -2 18.73718935014601 +4.424319112386566 -2 4.262810649853982 +-4.4323381310048 -2.000000000000001 20.43038829322244 +4.33988401282968 -2 20.46392086060903 +4.339884012829671 -2 2.536079139390978 +-4.432338131004805 -2.000000000000001 2.569611706777561 +4.379090698159919 -2 12.44537438064505 +1.211364165592087 -2 18.83909175643164 +1.226596144963301 -2 4.235215612788537 +-4.461640197060017 -2.000000000000001 11.50000000000003 +-0.0789477979241342 -2.000000000000001 11.03185428670007 +-1.164404952161897 -2.000000000000001 12.61895958178432 +-4.410517731509913 -2.000000000000001 16.39715749091815 +-4.410517731509909 -2.000000000000001 6.602842509081864 +0.6960788289981297 -2 2.543359885072562 +-0.6960788289981306 -2.000000000000001 20.45664011492744 +-0.7955879351212767 -2.000000000000001 9.064340239660687 +2.891963863064321 -2 13.00151680177449 +-3.031117833735591 -2.000000000000001 12.75253926138729 +-3.119141902884827 -2.000000000000001 9.823417609911139 +2.599148781920052 -2 19.24094032482649 +-2.653295717652689 -2.000000000000001 3.739426609447854 +-2.653295717652673 -2.000000000000001 19.26057339055214 +2.599148781920043 -2 3.759059675173514 +4.461343785537215 -2 7.314034267138428 +3.016143658652723 -2 10.97344741051308 +0.8402816289317405 -2 12.81226668994204 +3.408982070369785 -2 9.168796352899761 +0.5230853488408789 -2 16.81415847996665 +0.5231269711546753 -2 6.187350587975814 +-3.270244377838074 -2.000000000000001 18.15654487462113 +-3.270244377838084 -2.000000000000001 4.843455125378867 +1.049111897296623 -2 7.235384048258044 +-4.557141015037045 -2.000000000000001 9.486854823404379 +-4.730095018078609 -2.000000000000001 13.54537379503411 +1.051707131391088 -2 15.76816602848722 +3.428244027191093 -2 18.55759478098433 +3.428244027191083 -2 4.442405219015658 +4.537472976207248 -2 15.74403684747699 +4.524136609758647 -2 14.28959392904961 +-1.745159277636699 -2.000000000000001 17.47221547759469 +-1.745159277636705 -2.000000000000001 5.527784522405318 +-4.570844204606903 -2.000000000000001 19.34446134971601 +-4.570844204606907 -2.000000000000001 3.655538650284011 +3.251657428556613 -2 14.07801297268738 +1.535287949306383 -2 17.61186126036772 +1.535287949306366 -2 5.388138739632289 +-0.829463408441022 -2.000000000000001 15.57753900279373 +-0.8675629853085036 -2.000000000000001 7.341287650120584 +-3.517084265664195 -2.000000000000001 2.524173907223808 +-3.517960610299513 -2.000000000000001 20.47619304782597 +3.507433647890346 -2 2.518070047845619 +3.509349923099667 -2 20.51590486131341 +-4.62229980583437 -2.000000000000001 14.60540512530838 +-4.622299805834363 -2.000000000000001 8.39459487469162 +4.57087033992865 -2 10.41469860985093 +-4.858033390976463 -2.000000000000001 17.44217961423457 +-4.858033390976461 -2.000000000000001 5.557820385765451 +-1.985233551204142 -2.000000000000001 15.51639078344942 +-1.985233551204138 -2.000000000000001 7.48360921655058 +-0.5844748472786963 -2.000000000000001 16.58739381913674 +-0.584443872994802 -2.000000000000001 6.412863177563709 +-2.936397123755793 -2.000000000000001 13.68789205636999 +-3.621825182305656 -2.000000000000001 16.4172441159702 +-3.621825182305658 -2.000000000000001 6.582755884029806 +-3.303047647011482 -2.000000000000001 15.02028810725361 +-3.33236588771436 -2.000000000000001 8.052028782023317 +3.184081222985085 -2 7.650383294925772 +3.194307097918526 -2 15.3555985917716 +-0.1280276501772288 -2.000000000000001 4.784230026113477 +-0.1179341133433791 -2.000000000000001 18.20443484075403 +-1.538667868424811 -2.000000000000001 10.87256583483008 +1.46666666666668 -2 20.69867185800531 +-1.466666666666681 -2.000000000000001 2.301328141994691 +-1.862518848837702 -2.000000000000001 8.874113821910134 +2.20824623311636 -2 16.2729956095334 +2.293423517464527 -2 6.620913961945547 +2.741561439680176 -2 9.972415836881375 +-1.389782981471797 -2.000000000000001 20.84885201679695 +1.389782981471788 -2 2.151147983203057 +-1.807678356220602 -2.000000000000001 14.0565414477288 +4.721338152194439 -2 19.54014493046909 +4.721338152194445 -2 3.459855069530906 +4.677842566706255 -2 17.51324015955447 +4.677842566706244 -2 5.486759840445512 +-0.6901989444339645 -2.000000000000001 19.653246271329 +0.7155710670926494 -2 3.245578639832392 +0.7569986712855394 -2 19.49554485758418 +-0.7268465427306223 -2.000000000000001 3.516724542007708 +0.1166760174543837 -2.000000000000001 10.19589863571242 +4.674270586073877 -2 8.530626445151837 +-3.328929844137742 -2.000000000000001 10.62999199958326 +2.976034373999896 -2 17.9096498218788 +2.941104286520737 -2 5.104925183424154 +3.40669830620675 -2 17.0707109069252 +3.40203762272843 -2 5.933450457307295 +4.843623221539279 -2 13.01155921408475 +-1.905843527816085 -2.000000000000001 19.01287305093919 +-1.928480889658866 -2.000000000000001 4.004177120307872 +-0.4977682837690729 -2.000000000000001 13.14242413390456 +2.126131522104315 -2 9.527945660046237 +-4.775232764591253 -2.000000000000001 10.83004372115235 +-4.774439788717261 -2.000000000000001 12.16649121485059 +3.607794234134301 -2 12.6608935722898 +1.498073652025573 -2 10.90379227528522 +3.154207848082664 -2 8.590060857486442 +1.884517368035357 -2 8.272728446379194 +1.897768927793158 -2 14.73058481100357 +-2.292424368674521 -2.000000000000001 16.31840525193094 +-2.292424368674519 -2.000000000000001 6.681594748069067 +0.5493453634264682 -2 14.5211394100788 +0.3707613674839676 -2 15.39970547933711 +1.262402999243723 -2 12.25590072730668 +-3.443817086985796 -2.000000000000001 13.14062602995652 +0.3663307955182855 -2 7.62569850633823 +0.5033241908460901 -2 8.551722963026233 +0.06092550356329518 -2.000000000000001 17.3809832378863 +0.06055170415976807 -2.000000000000001 5.618651361343534 +-2.624999433519349 -2.000000000000001 9.288795702920243 +2.464451978466195 -2 12.25517162901115 +2.172103614654042 -2 13.4142305706458 +-3.317943884890799 -2.000000000000001 4.04666644820897 +-3.317943884890799 -2.000000000000001 18.95333355179104 +4.820700766423143 -2 14.98310268898359 +0.5679799969007409 -2 4.434523268187693 +0.5481355337428324 -2 18.57909297249706 +1.825131987861343 -2 3.86065891592332 +1.828116755876465 -2 19.15679450125875 +1.663472502877925 -2 15.96907534672935 +-4.677895244153349 -2.000000000000001 15.76535880531055 +-4.677895244153348 -2.000000000000001 7.234641194689466 +-3.970370384533314 -2.000000000000001 11.94540240740735 +1.64502567557077 -2 6.986616899560678 +-0.3737185315536271 -2.000000000000001 11.68567777773393 +3.763983537144843 -2 15.73262551938402 +-0.05735596008082045 -2.000000000000001 20.84938163533071 +0.05735596008082222 -2.000000000000001 2.150618364669295 +-1.193745169415743 -2.000000000000001 9.495838202889917 +2.187405817472623 -2 20.86487844365334 +-2.187405817472616 -2.000000000000001 2.135121556346654 +-1.864518632817282 -2.000000000000001 11.46120011781846 +-4.872173412201247 -2.000000000000001 4.833333333333346 +-4.872173412201263 -2.000000000000001 18.16666666666667 +4.880145388614145 -2 18.2309575789695 +4.88014538861414 -2 4.769042421030505 +2.221780135147157 -2 2.090950061128712 +-2.221780135147165 -2.000000000000001 20.9090499388713 +-0.7347120419189919 -2.000000000000001 14.44755275345399 +4.765156938803088 -2 11.72407223987942 +2.726125691040409 -2 14.80127766048168 +-3.972640216863082 -2.000000000000001 11.05294690230187 +-4.883035163027792 -2.000000000000001 10.12603895302561 +-4.787969992936569 -2.000000000000001 12.94375340040899 +0.7562463792964902 -2 20.85747521669222 +-0.7562463792964973 -2.000000000000001 2.142524783307788 +-3.791379116874236 -2.000000000000001 9.569996569555784 +3.826778451052393 -2 7.390636576844656 +3.935155952823651 -2 11.92669123656116 +3.667340831533178 -2 10.8821435146057 +0.5711753342340513 -2 12.21767345320875 +-1.158394843204452 -2.000000000000001 6.020464346019507 +-1.158398714989937 -2.000000000000001 16.97956777856806 +-2.845916599252826 -2.000000000000001 12.17231888755332 +-2.713299954014319 -2.000000000000001 5.263423597263735 +-2.713299954014296 -2.000000000000001 17.73657640273627 +1.522901706970581 -2 9.996569394002456 +-3.589269769190736 -2.000000000000001 15.70242349322187 +-3.590796124912465 -2.000000000000001 7.301341442704665 +-0.7790319188812393 -2.000000000000001 10.86554669358809 +4.8584782546355 -2 9.800863457226084 +-1.811879399647207 -2.000000000000001 12.66796509419909 +2.886635712350103 -2 13.638653610869 +-0.4209419727553518 -2.000000000000001 9.602670607784091 +-2.849676075804878 -2.000000000000001 20.94891670228887 +-2.863160351247627 -2.000000000000001 2.06578222346516 +2.890144484742608 -2 20.93105416583529 +2.847570683323043 -2 2.049935916845456 +-1.606594674728729 -2.000000000000001 18.20058353771321 +-1.607436487732354 -2.000000000000001 4.800050505068349 +-2.21891632260968 -2.000000000000001 19.77754015430872 +2.218916322609688 -2 3.222459845691287 +-2.234143481633152 -2.000000000000001 3.228033172504503 +2.227718118990944 -2 19.77909531043977 +0.6069288912385282 -2 10.91096033836056 +-0.03232062293219329 -2.000000000000001 3.223871154779022 +0.06340173222327294 -2.000000000000001 19.7661715854931 +0.806362403309933 -2 9.647462673392539 +-2.604060192294591 -2.000000000000001 10.25185518902828 +4.911257713898155 -2 7.835959705265552 +-3.910336061546605 -2.000000000000001 14.61899833060184 +-3.980474913592209 -2.000000000000001 8.331456595643179 +4.757468043797763 -2 6.732879199666058 +-1.476156995030036 -2.000000000000001 12.06546528652118 +-0.7512426627758062 -2.000000000000001 8.470189707824815 +-4.026240893079169 -2.000000000000001 5.172501161711168 +-4.026240893079168 -2.000000000000001 17.82749883828884 +2.57052420988029 -2 8.179957038571541 +-1.409941907887927 -2.000000000000001 13.26299318865098 +-4.899342003781239 -2.000000000000001 15.18886944386912 +-4.899342003781239 -2.000000000000001 7.811130556130895 +1.010883018923553 -2 17.24944770833981 +1.010831835287635 -2 5.750897094561054 +-4.958746911805926 -2.000000000000001 18.79065972539025 +-4.958746911805925 -2.000000000000001 4.209340274609772 +4.85153705155142 -2 11.03121798951719 +-3.130175644224984 -2.000000000000001 17.01818484765599 +-3.130175644224995 -2.000000000000001 5.981815152344007 +-4.855721613249374 -2.000000000000001 3.056781590268141 +-4.855721613249381 -2.000000000000001 19.94321840973187 +-0.220768280161856 -2.000000000000001 8.825308249288286 +-3.962707036619866 -2.000000000000001 3.881304752688951 +-3.962707036619866 -2.000000000000001 19.11869524731107 +1.023367356242949 -2 20.22249302828785 +-1.02146392229294 -2.000000000000001 2.779341599170642 +-1.914567060649984 -2.000000000000001 16.8363323739264 +-1.914567060649986 -2.000000000000001 6.163667626073611 +-2.567050373101683 -2.000000000000001 11.51678450041416 +3.896271734770465 -2 8.849249237790447 +-4.896773085307457 -2.000000000000001 16.82925061054114 +-4.896773085307467 -2.000000000000001 6.170749389458893 +4.913056271385537 -2 16.27884664910964 +-2.53654599082893 -2.000000000000001 15.17916121236178 +-2.536152885191635 -2.000000000000001 7.810027062498389 +-3.013369235200768 -2.000000000000001 3.213623204989471 +-3.01336923520077 -2.000000000000001 19.78637679501055 +2.96707222236141 -2 19.79301625641096 +2.966921720415583 -2 3.212220438377813 +-1.912672185455982 -2.000000000000001 14.77117983441739 +-2.018496738962666 -2.000000000000001 8.141140215749088 +-0.02974828233297799 -2.000000000000001 16.64074559208851 +-0.0297482823329851 -2.000000000000001 6.359254407911505 +4.846429077344947 -2 2.124261916937506 +-4.875085443045167 -2.000000000000001 20.87396421824435 +4.846429077344955 -2 20.8757380830625 +-4.875085443045181 -2.000000000000001 2.126035781755643 +0.2454028060764024 -2.000000000000001 13.05352807308109 +2.353509679701741 -2 10.96223376955705 +2.731730038096274 -2 11.53547660014723 +1.599181348075285 -2 7.645869878048808 +-0.502113964061496 -2.000000000000001 4.277293339071171 +-0.66140961725133 -2.000000000000001 18.85227569951076 +2.810241336546191 -2 4.341766909291412 +2.814399680293722 -2 18.65996821038751 +-0.316562488338139 -2.000000000000001 7.604543530096665 +2.785225965006796 -2 7.166031618526802 +2.786678516081304 -2 15.83248447910922 +0.8201276600716145 -2 13.43539224063508 +0.2608770759535428 -2.000000000000001 11.62433328150053 +4.300669726157238 -2 9.830273494013785 +-3.063238939778795 -2.000000000000001 8.783950798903994 +-0.8758284353911998 -2.000000000000001 18.20640747008578 +-0.8859405168174188 -2.000000000000001 4.799552838980738 +1.387907151639096 -2 13.10999228912253 +1.799812140350197 -2 4.646217606335199 +1.798062538727911 -2 18.36689107743655 +-0.7299192296252786 -2.000000000000001 15.05244686476968 +5.001641081356292 -2 18.90740740740741 +5.001641081356294 -2 4.092592592592592 +-2.75361869803549 -2.000000000000001 18.63189560443534 +-2.75460081320638 -2.000000000000001 4.368844112143115 +-0.2904200973765221 -2.000000000000001 15.42301675625867 +1.617524276734486 -2 15.33261088474861 +-0.4075937782682679 -2.000000000000001 13.906420960513 +2.217048455304039 -2 17.67144700327954 +2.217134921691084 -2 5.304480703039843 +-3.11524756479934 -2.000000000000001 14.29720478048327 +4.973053675165414 -2 13.78530060925478 +-1.226017388219202 -2.000000000000001 19.26615790134818 +1.351147165558807 -2 14.37681865271976 +1.296493101382216 -2 8.681938372476035 +-4.179229254270034 -2.000000000000001 3.149649214457426 +-4.179282482199762 -2.000000000000001 19.85037307387165 +3.935244201309933 -2 6.613370747639124 +-2.00598309506823 -2.000000000000001 2.695574014008503 +1.983594879980672 -2 20.30957324995623 +3.846953567092943 -2 16.37489360221256 +4.043524121169406 -2 2.103771606497475 +-4.043524121169431 -2.000000000000001 20.89622839350252 +4.043524121169436 -2 20.89622839350253 +-4.043524121169428 -2.000000000000001 2.103771606497467 +-0.6666353353016836 -2.000000000000001 12.24454888728619 +4.065477431805292 -2 17.24733590818778 +4.063445800676742 -2 5.756111323870311 +4.905769193999144 -2 16.95539432461989 +4.965908213516775 -2 6.217982701090925 +3.932717681145891 -2 19.1382033944099 +3.932717681145886 -2 3.861796605590097 +1.846539998144975 -2 12.12863830612559 +1.866048884972222 -2 2.678684629551118 +-1.865307639906856 -2.000000000000001 20.31732396718865 +3.966206845006104 -2 18.43102698825383 +3.966206845006098 -2 4.568973011746163 +4.984012869931692 -2 9.231114774036172 +3.905930139433181 -2 14.1944526375738 +4.168607364624523 -2 3.113453978187454 +4.168607364624523 -2 19.88654602181256 +2.81454069146009 -2 9.324076575609148 +2.026006149871333 -2 5.888700352460987 +2.179185214205955 -2 17.03322508821502 +-1.945543755738865 -2.000000000000001 10.39642798192854 +-3.479194206128795 -2.000000000000001 12.40181670141487 +-2.885002526051748 -2.000000000000001 6.520525811035624 +-2.88500252605175 -2.000000000000001 16.47947418896437 +5.055071905449362 -2 14.41569272559141 +1.494665928931473 -2 11.64901102370399 +-1.298891282183766 -2.000000000000001 3.742547835056953 +-4.254137246365767 -2.000000000000001 16.99078189003745 +-4.254137246365755 -2.000000000000001 6.009218109962568 +-2.441255330963768 -2.000000000000001 12.72996588748941 +0.733333333333321 -2 1.957770421516731 +-0.733333333333321 -2.000000000000001 21.04222957848329 +3.413650233092599 -2 14.67270393880121 +3.511036517045831 -2 11.47230775592591 +1.853502786329255 -2 14.09025684657662 +1.844358826004632 -2 8.93696728525738 +1.21942244746579 -2 3.688821074282565 +-5.035260838659223 -2.000000000000001 11.49981960308223 +4.869602118947984 -2 20.22240186163583 +4.869602118947981 -2 2.777598138364176 +-1.399792954624569 -2.000000000000001 15.72539566112612 +-1.445660692785024 -2.000000000000001 7.261178000726142 +2.756142200580297 -2 16.62457319749792 +4.979220657563118 -2 12.35446435330865 +2.830531055885949 -2 6.343418654732101 +3.227007102656429 -2 19.1915133467666 +3.226640704213105 -2 3.80907949459969 +1.045447550928232 -2 6.514339485528698 +-4.924915599884329 -2.000000000000001 14.0351666060517 +-4.924915599884317 -2.000000000000001 8.96483339394827 +-4.095533816236212 -2.000000000000001 15.91701444492089 +-4.095839087380558 -2.000000000000001 7.083738542264424 +0.4964351308981749 -2 6.770293461080934 +1.049266920295029 -2 16.48412549104112 +0.4885459270939423 -2 16.22185660674432 +-2.405630037884779 -2.000000000000001 13.99815850188494 +-4.321372657325103 -2.000000000000001 13.99737691761587 +-4.258363945549558 -2.000000000000001 8.943730127677888 +2.674506907245188 -2 10.50539335403129 +-3.31248586655896 -2.000000000000001 17.5825646658611 +-3.312485866558983 -2.000000000000001 5.41743533413889 +1.155108473929052 -2 18.24593055827771 +1.162473682759329 -2 4.774275900457635 +1.328107556521091 -2 19.33644585312978 +-0.686183563735292 -2.000000000000001 7.948085058069264 +4.190730740273377 -2 12.9696143544133 +-1.222777725800809 -2.000000000000001 8.762629109574132 +-1.201160131495001 -2.000000000000001 20.22973367346726 +1.197059060478095 -2 2.760095891166337 +0.8302232462084636 -2 9.08730136107568 +4.346459639658001 -2 7.838874338509395 +-1.223659235670306 -2.000000000000001 17.6824197669544 +-1.225849240199183 -2.000000000000001 5.318905528332731 +-3.259952569103728 -2.000000000000001 9.281223957558577 +-2.817568626390807 -2.000000000000001 10.95743756888644 +-4.174580867323863 -2.000000000000001 13.37438967834411 +-0.9943148667904573 -2.000000000000001 16.19363167836141 +-0.9843096300031533 -2.000000000000001 6.793180501044537 +3.304324909186447 -2 13.36077702374298 +-1.355472338517868 -2.000000000000001 14.42823884924042 +-4.969410659276734 -2.000000000000001 16.2452998359308 +-4.969410659276727 -2.000000000000001 6.754700164069227 +-0.1654190142811789 -2.000000000000001 20.26950389983039 +0.1476069700664686 -2.000000000000001 2.689983311625195 +-3.558495035798417 -2.000000000000001 10.13545325877313 +-0.01892635098294981 -2.000000000000001 14.3139004089012 +4.309900984350293 -2 17.991763535771 +4.309659123501651 -2 5.008646848997813 +2.967611506781148 -2 12.46257175918596 +2.388804334749366 -2 12.79411667159967 +3.210078911743763 -2 10.38836595604638 +-0.339202486290163 -2.000000000000001 10.55595646031962 +3.859026612266314 -2 9.518940519533018 +3.30774319364018 -2 9.766617558817508 +0.8628284325731848 -2 13.99486885831654 +-2.176835266628641 -2.000000000000001 5.241274566685945 +-2.176835266628633 -2.000000000000001 17.75872543331405 +-0.4478236185158906 -2.000000000000001 5.917191629202433 +-0.4477989134623801 -2.000000000000001 17.08280281106855 +-3.73281834280081 -2.000000000000001 18.52085760304599 +-3.732818342800812 -2.000000000000001 4.479142396954011 +0.7671794246856125 -2 3.934590400782412 +-1.357608731071366 -2.000000000000001 10.26528763267546 +4.372125928108504 -2 13.63219604919008 +5.026013908646626 -2 7.198796856636237 +-5.091123657922543 -2.000000000000001 2.596115776819421 +-5.091123657922537 -2.000000000000001 20.4038842231806 +2.288002663424523 -2 18.7370398659062 +2.289641727065904 -2 4.246576584449393 +-2.788415952693963 -2.000000000000001 13.14737194018134 +4.186644868478791 -2 10.79103061390422 +2 21 0 71 +4492 +4493 +4494 +4495 +4496 +4497 +4498 +4499 +4500 +4501 +4502 +4503 +4504 +4505 +4506 +4507 +4508 +4509 +4510 +4511 +4512 +4513 +4514 +4515 +4516 +4517 +4518 +4519 +4520 +4521 +4522 +4523 +4524 +4525 +4526 +4527 +4528 +4529 +4530 +4531 +4532 +4533 +4534 +4535 +4536 +4537 +4538 +4539 +4540 +4541 +4542 +4543 +4544 +4545 +4546 +4547 +4548 +4549 +4550 +4551 +4552 +4553 +4554 +4555 +4556 +4557 +4558 +4559 +4560 +4561 +4562 +5.5 -1.036008230452674 20.57175882575281 +5.5 -0.9639917695473266 2.428241174247184 +5.5 -0.9813939756750217 13.81081030431435 +5.5 -0.9999999999999999 15.20370370370371 +5.5 -0.9800955117200852 11.45739848754329 +5.5 -0.9813939756750198 10.10710660061066 +5.5 -0.9616180986400952 19.00772388456125 +5.5 -1.038381901359902 3.99227611543877 +5.5 -1.017307560370043 16.64258367272845 +5.5 -0.9800955117200842 7.75369478383959 +5.5 -0.9826924396299541 6.35741632727157 +5.5 -0.9993375183903391 12.68154621750445 +5.5 -0.9993375183903388 17.86673140268962 +5.5 -0.9993375183903389 8.977842513800761 +5.5 -1.00066248160966 5.133268597310387 +5.5 -1.21604938271605 19.71851851851852 +5.5 -0.7839506172839527 3.281481481481478 +5.5 -1.358975065946739 7.055555555555578 +5.5 -1.383213156852628 10.76980038110911 +5.5 -0.6814291546815319 15.94286022683956 +5.5 -1.359822948878115 14.47483942882068 +5.5 -0.6020484978431991 14.48128665314343 +5.5 -1.405494881756579 15.9412239101834 +5.5 -0.6025464577995705 10.77130625565908 +5.5 -0.5977984008640707 7.055555555555578 +5.5 -0.6276395104989857 5.775153938158681 +5.5 -1.366158481392686 12.03966087665617 +5.5 -1.372360489501013 17.22484606184134 +5.5 -1.366158481392686 8.335957172952476 +5.5 -0.6295007343131613 12.02668117719758 +5.5 -1.363263589560457 5.788133637617275 +5.5 -0.6367364104395415 17.21186636238275 +5.5 -0.6295007343131614 8.322977473493884 +5.5 -0.5241625760917136 19.58045229765176 +5.5 -1.475837423908284 3.419547702348261 +5.5 -0.6341357123155588 13.23746457246031 +5.5 -1.362192923401253 13.24046792712962 +5.5 -1.382373113854592 9.515740740740764 +5.5 -0.6341357123155588 9.53376086875662 +5.5 -1.382373113854596 18.40462962962963 +5.5 -0.6308397328097379 18.42460449015577 +5.5 -1.369160267190265 4.575395509844249 +5.5 -0.617626886145406 4.595370370370375 +5.5 -1.436213991769547 20.92222222222222 +5.5 -0.5637860082304452 2.077777777777769 +5.5 -1.473753118823112 2.027314713009396 +5.5 -0.5262468811768887 20.9726852869906 +5.5 -0.4548063899419977 2.637503645377656 +5.5 -1.449588821593779 2.729801215551426 +5.5 -0.5504111784062208 20.27019878444858 +5.5 -1.545193610058 20.36249635462234 +5.5 -0.4314128943758586 15.20370370370371 +5.5 -1.568587105624141 15.20370370370371 +5.5 -1.56858710562414 11.50000000000003 +5.5 -0.4424285407665631 11.45107718408 +5.5 -1.559032586325527 16.63580480302472 +5.5 -0.449617859030125 16.65883362461327 +5.5 -1.568587105624139 7.796296296296328 +5.5 -0.4414789293794629 7.744964081096338 +5.5 -0.4416260701986018 6.363551090123098 +5.5 -1.568587105624141 6.314814814814827 +5.5 -1.558290334026596 10.04631980183191 +5.5 -0.4436152291580295 10.08984215241269 +5.5 -0.4323292657361082 18.95067318394319 +5.5 -1.512008119042148 18.98913736950485 +5.5 -0.4435156371667556 13.79480119487251 +5.5 -1.540681969590878 13.79411242094182 +5.5 -0.4879918809578518 4.010862630495165 +5.5 -1.5676707342639 4.049326816056833 +5.5 -1.000111581384905 1.875356076042117 +5.5 -0.9998884186150943 21.12464392395787 +2 22 0 804 +4563 +4564 +4565 +4566 +4567 +4568 +4569 +4570 +4571 +4572 +4573 +4574 +4575 +4576 +4577 +4578 +4579 +4580 +4581 +4582 +4583 +4584 +4585 +4586 +4587 +4588 +4589 +4590 +4591 +4592 +4593 +4594 +4595 +4596 +4597 +4598 +4599 +4600 +4601 +4602 +4603 +4604 +4605 +4606 +4607 +4608 +4609 +4610 +4611 +4612 +4613 +4614 +4615 +4616 +4617 +4618 +4619 +4620 +4621 +4622 +4623 +4624 +4625 +4626 +4627 +4628 +4629 +4630 +4631 +4632 +4633 +4634 +4635 +4636 +4637 +4638 +4639 +4640 +4641 +4642 +4643 +4644 +4645 +4646 +4647 +4648 +4649 +4650 +4651 +4652 +4653 +4654 +4655 +4656 +4657 +4658 +4659 +4660 +4661 +4662 +4663 +4664 +4665 +4666 +4667 +4668 +4669 +4670 +4671 +4672 +4673 +4674 +4675 +4676 +4677 +4678 +4679 +4680 +4681 +4682 +4683 +4684 +4685 +4686 +4687 +4688 +4689 +4690 +4691 +4692 +4693 +4694 +4695 +4696 +4697 +4698 +4699 +4700 +4701 +4702 +4703 +4704 +4705 +4706 +4707 +4708 +4709 +4710 +4711 +4712 +4713 +4714 +4715 +4716 +4717 +4718 +4719 +4720 +4721 +4722 +4723 +4724 +4725 +4726 +4727 +4728 +4729 +4730 +4731 +4732 +4733 +4734 +4735 +4736 +4737 +4738 +4739 +4740 +4741 +4742 +4743 +4744 +4745 +4746 +4747 +4748 +4749 +4750 +4751 +4752 +4753 +4754 +4755 +4756 +4757 +4758 +4759 +4760 +4761 +4762 +4763 +4764 +4765 +4766 +4767 +4768 +4769 +4770 +4771 +4772 +4773 +4774 +4775 +4776 +4777 +4778 +4779 +4780 +4781 +4782 +4783 +4784 +4785 +4786 +4787 +4788 +4789 +4790 +4791 +4792 +4793 +4794 +4795 +4796 +4797 +4798 +4799 +4800 +4801 +4802 +4803 +4804 +4805 +4806 +4807 +4808 +4809 +4810 +4811 +4812 +4813 +4814 +4815 +4816 +4817 +4818 +4819 +4820 +4821 +4822 +4823 +4824 +4825 +4826 +4827 +4828 +4829 +4830 +4831 +4832 +4833 +4834 +4835 +4836 +4837 +4838 +4839 +4840 +4841 +4842 +4843 +4844 +4845 +4846 +4847 +4848 +4849 +4850 +4851 +4852 +4853 +4854 +4855 +4856 +4857 +4858 +4859 +4860 +4861 +4862 +4863 +4864 +4865 +4866 +4867 +4868 +4869 +4870 +4871 +4872 +4873 +4874 +4875 +4876 +4877 +4878 +4879 +4880 +4881 +4882 +4883 +4884 +4885 +4886 +4887 +4888 +4889 +4890 +4891 +4892 +4893 +4894 +4895 +4896 +4897 +4898 +4899 +4900 +4901 +4902 +4903 +4904 +4905 +4906 +4907 +4908 +4909 +4910 +4911 +4912 +4913 +4914 +4915 +4916 +4917 +4918 +4919 +4920 +4921 +4922 +4923 +4924 +4925 +4926 +4927 +4928 +4929 +4930 +4931 +4932 +4933 +4934 +4935 +4936 +4937 +4938 +4939 +4940 +4941 +4942 +4943 +4944 +4945 +4946 +4947 +4948 +4949 +4950 +4951 +4952 +4953 +4954 +4955 +4956 +4957 +4958 +4959 +4960 +4961 +4962 +4963 +4964 +4965 +4966 +4967 +4968 +4969 +4970 +4971 +4972 +4973 +4974 +4975 +4976 +4977 +4978 +4979 +4980 +4981 +4982 +4983 +4984 +4985 +4986 +4987 +4988 +4989 +4990 +4991 +4992 +4993 +4994 +4995 +4996 +4997 +4998 +4999 +5000 +5001 +5002 +5003 +5004 +5005 +5006 +5007 +5008 +5009 +5010 +5011 +5012 +5013 +5014 +5015 +5016 +5017 +5018 +5019 +5020 +5021 +5022 +5023 +5024 +5025 +5026 +5027 +5028 +5029 +5030 +5031 +5032 +5033 +5034 +5035 +5036 +5037 +5038 +5039 +5040 +5041 +5042 +5043 +5044 +5045 +5046 +5047 +5048 +5049 +5050 +5051 +5052 +5053 +5054 +5055 +5056 +5057 +5058 +5059 +5060 +5061 +5062 +5063 +5064 +5065 +5066 +5067 +5068 +5069 +5070 +5071 +5072 +5073 +5074 +5075 +5076 +5077 +5078 +5079 +5080 +5081 +5082 +5083 +5084 +5085 +5086 +5087 +5088 +5089 +5090 +5091 +5092 +5093 +5094 +5095 +5096 +5097 +5098 +5099 +5100 +5101 +5102 +5103 +5104 +5105 +5106 +5107 +5108 +5109 +5110 +5111 +5112 +5113 +5114 +5115 +5116 +5117 +5118 +5119 +5120 +5121 +5122 +5123 +5124 +5125 +5126 +5127 +5128 +5129 +5130 +5131 +5132 +5133 +5134 +5135 +5136 +5137 +5138 +5139 +5140 +5141 +5142 +5143 +5144 +5145 +5146 +5147 +5148 +5149 +5150 +5151 +5152 +5153 +5154 +5155 +5156 +5157 +5158 +5159 +5160 +5161 +5162 +5163 +5164 +5165 +5166 +5167 +5168 +5169 +5170 +5171 +5172 +5173 +5174 +5175 +5176 +5177 +5178 +5179 +5180 +5181 +5182 +5183 +5184 +5185 +5186 +5187 +5188 +5189 +5190 +5191 +5192 +5193 +5194 +5195 +5196 +5197 +5198 +5199 +5200 +5201 +5202 +5203 +5204 +5205 +5206 +5207 +5208 +5209 +5210 +5211 +5212 +5213 +5214 +5215 +5216 +5217 +5218 +5219 +5220 +5221 +5222 +5223 +5224 +5225 +5226 +5227 +5228 +5229 +5230 +5231 +5232 +5233 +5234 +5235 +5236 +5237 +5238 +5239 +5240 +5241 +5242 +5243 +5244 +5245 +5246 +5247 +5248 +5249 +5250 +5251 +5252 +5253 +5254 +5255 +5256 +5257 +5258 +5259 +5260 +5261 +5262 +5263 +5264 +5265 +5266 +5267 +5268 +5269 +5270 +5271 +5272 +5273 +5274 +5275 +5276 +5277 +5278 +5279 +5280 +5281 +5282 +5283 +5284 +5285 +5286 +5287 +5288 +5289 +5290 +5291 +5292 +5293 +5294 +5295 +5296 +5297 +5298 +5299 +5300 +5301 +5302 +5303 +5304 +5305 +5306 +5307 +5308 +5309 +5310 +5311 +5312 +5313 +5314 +5315 +5316 +5317 +5318 +5319 +5320 +5321 +5322 +5323 +5324 +5325 +5326 +5327 +5328 +5329 +5330 +5331 +5332 +5333 +5334 +5335 +5336 +5337 +5338 +5339 +5340 +5341 +5342 +5343 +5344 +5345 +5346 +5347 +5348 +5349 +5350 +5351 +5352 +5353 +5354 +5355 +5356 +5357 +5358 +5359 +5360 +5361 +5362 +5363 +5364 +5365 +5366 +3.761277278813112 4.012828582419667 20.73608815952614 +4.317184622163877 3.407626290858748 20.48531310934714 +4.195519708473463 3.556348460965368 21.02418537542336 +4.01371930348316 3.76032676144596 19.99049932000333 +-3.761277278813111 4.012828582419667 2.263911840473863 +-4.317184622163884 3.407626290858738 2.514686890652865 +-4.195519708473469 3.556348460965362 1.975814624576646 +-4.013719303483172 3.760326761445947 3.009500679996673 +-4.273893376630376 3.46176767059764 20.89110741845771 +-4.266948147390552 3.47032469770198 20.39059068297315 +-3.759234510790579 4.014742319611698 20.72051830700737 +-4.075007066101208 3.693821518593613 19.96428775062503 +4.273893376630353 3.461767670597667 2.108892581542285 +4.266948147390469 3.470324697702081 2.609409317026909 +3.759234510790537 4.014742319611737 2.279481692992618 +4.075007066100881 3.693821518593972 3.03571224937507 +3.484069864970143 4.255732272595039 20.11704770118952 +-2.175261853712903 5.05155776645002 11.82587441684553 +-1.532352455435371 5.28222452687513 11.99061364305677 +-1.976907729953858 5.132429817079693 12.59517342423381 +-3.484069864970146 4.255732272595036 2.882952298810487 +-2.666739966954939 4.810249260552427 12.32574489521443 +-3.169977450792207 4.494579286370299 12.1260312728268 +-2.929684860552606 4.654776752740013 11.4838930248201 +-3.541847585756689 4.207768491643701 20.00435442814357 +-4.014562925820235 3.75942608846479 19.34992132160168 +3.541847585756679 4.20776849164371 2.995645571856436 +4.014562925815568 3.759426088469773 3.650078678398788 +-5.477730089209867 0.494442180406221 15.9564665142498 +-5.475790760101965 0.5154760436547315 15.42359023012678 +-5.382857725723366 1.129089325350421 15.864074230095 +5.477730089210382 0.4944421804005176 7.043533485748755 +5.475790760149791 0.5154760431466934 7.576409769270755 +5.382857725731149 1.129089325313322 7.135925769609786 +-1.470478571204561 5.299782332476325 12.53063367049206 +2.066693639198487 5.096938041775328 19.78010157950505 +1.626461203487187 5.254010273453128 19.9345354636002 +1.672459604922738 5.239549491120556 19.28540588455588 +2.666746250934345 4.810245776790165 10.67424661217908 +3.169984262620186 4.494574482055043 10.87396178128498 +2.929692093905863 4.654772200108773 11.51609884593065 +-2.06653929147099 5.097000623583107 3.21988224625791 +-1.62631901806727 5.254054287069436 3.065521378011844 +-1.67245960492276 5.23954949112055 3.714594115444129 +2.175271716291589 5.051553519492973 11.17411239036038 +1.532363007739328 5.282221465682036 11.00937267820098 +1.976914762061606 5.132427108449072 10.40481585174413 +-2.651305519544296 4.818773603525481 10.58389082710883 +-2.178119595059208 5.050326230019118 11.09834742691163 +1.470489374829722 5.29977933488866 10.46935318859894 +2.651310577819849 4.818770820441721 12.41610212177771 +2.178128571905131 5.050322358449064 11.90164195289829 +-2.012247814234457 5.118677439935892 15.65342189866697 +-1.347623946740488 5.332345609407889 16.09703220228544 +-1.914808888268559 5.155919599975132 16.25792093320716 +2.926520235932058 4.656767044708181 20.2844519313225 +2.398583833423502 4.949423763837506 20.31859211688091 +2.730291283244871 4.774464316406299 19.59292560029763 +4.495777305586393 3.168278147286687 19.90317015198286 +4.700337311587625 2.856016309004068 20.39985915843822 +-2.926520235932061 4.65676704470818 2.715548068677503 +-2.399632838679047 4.948915258875741 2.681135050844155 +-2.730291283244882 4.774464316406294 3.407074399702385 +-1.325105757323941 5.337986018331909 15.47736062966347 +-4.495777305586402 3.168278147286673 3.096829848017144 +-4.700337311587633 2.856016309004054 2.600140841561782 +2.012247725730922 5.118677474728284 7.346577827102909 +1.347624033255111 5.332345587543368 6.902967527564748 +1.914808860411503 5.155919610320703 6.742078902809343 +-4.677484481355989 2.893292056926484 20.43172446693072 +-4.516370965098922 3.138852227425087 19.89549054119866 +1.325105548193285 5.337986070246659 7.522639021819332 +4.677484481355985 2.893292056926493 2.56827553306929 +4.516370965098917 3.138852227425094 3.104509458801353 +-5.380819715027353 1.138762132481125 5.357206090255275 +-5.470772856566077 0.5662546704971556 5.891175647330421 +-5.465562835814836 0.6145102828754695 5.175488374783974 +5.380819715027218 1.138762132481761 17.64279390974449 +5.470772856565919 0.5662546704986871 17.10882435266234 +5.465562835814829 0.6145102828755359 17.82451162521573 +-5.453726546372142 0.7119457545317558 17.81964074678342 +-5.468557896454871 0.5872601920112381 17.10941990400865 +-5.363174220691938 1.219164582205956 17.63434563470168 +5.45372654637214 0.7119457545317639 5.180359253216604 +5.468557896446722 0.5872601920871232 5.890580096000107 +5.363174220687164 1.219164582226959 5.365654365303353 +0.7861043116747412 5.44353194269735 11.58061818877561 +1.013977230130627 5.405723834675299 10.88261054804744 +-4.242174857626317 3.500564594079524 9.166296162947463 +-3.771196392454867 4.003508182773627 9.20940917067772 +-4.161230077520448 3.596409910165854 9.680675881044202 +1.614715063284835 5.257632096714361 11.55159822029663 +4.242174577981466 3.500564932968358 13.83370299378574 +3.771196007089638 4.003508545777214 13.79058973086956 +4.161229743881973 3.596410296202585 13.31932269990462 +3.614500692797209 4.145525870353302 12.58978789734755 +3.847670405060284 3.930067741658307 12.09880001405927 +4.076040724309517 3.692680870826823 12.66142011571349 +4.402468301379711 3.296706364744493 12.11900466108254 +-3.614499268471457 4.145527112228225 10.41020853008531 +-3.847667537661743 3.93007054893726 10.90119579464743 +-4.076039545628856 3.692682171873138 10.33857727200835 +-4.402465797675227 3.296709708224219 10.88099260308144 +-2.108607461544727 5.079741585269659 17.54601747547295 +-2.088239607911925 5.088148517874439 18.17297187257287 +-2.577954911575851 4.858410076751648 18.05496586702932 +-1.453082105362799 5.304578437074374 18.07451779797109 +2.108606548071668 5.079741964453439 5.45398300341531 +2.088239601121574 5.088148520661283 4.82702812202335 +2.577948897402802 4.858413267969253 4.94503322946538 +1.453082104713521 5.304578437252231 4.9254821923573 +-0.7860922698195969 5.443533681656602 11.41936434041259 +-1.013964913318322 5.40572614498361 12.11737460203865 +-2.512223171203179 4.892722630404246 5.300194883813568 +-3.053747024833882 4.574344664355564 5.504442209778208 +-2.919981264345708 4.660870027781298 4.844036304084803 +-1.614704282739634 5.257635407605046 11.44838823873579 +2.514508045181924 4.891548761968481 17.73142432789513 +3.053747024571651 4.574344664530623 17.49555779003734 +2.916543034454688 4.663022274037926 18.15978426414112 +4.971093787030926 2.353343697920586 14.77614696928421 +5.185692395331088 1.832646823860322 14.12776164025952 +5.24202251463693 1.664692150530998 14.71529190949587 +5.385908219233333 1.114447241458665 14.07299997156314 +-4.971093839718785 2.353343586625196 8.223852929231779 +-5.185692523898742 1.832646460062797 8.872238181181624 +-5.242022521012647 1.664692130454221 8.284708068139775 +-5.385908229687095 1.114447190937654 8.926999992155578 +5.315965286277514 1.410855440891244 8.334015814298887 +5.195364878627121 1.805043982269631 8.865917669289814 +5.045725734367321 2.188755768363241 8.118216766140744 +5.373903658315382 1.170965187844862 8.895321023936665 +-5.315965284995651 1.410855445721177 14.66598418396256 +-5.195364858952001 1.805044038899509 14.13408229017915 +-5.045725733178118 2.188755771104702 14.8817832305252 +-5.373903655837197 1.170965199217981 14.10467896113361 +-4.046740797724591 3.724766961305277 6.175531055780272 +-4.007835618518883 3.766597092194939 5.502613439164861 +-3.595097908531253 4.16236363477222 5.971636115779225 +-3.50243531093186 4.240630482927939 5.175185968627275 +4.046740797713896 3.724766961316896 16.8244689442203 +4.007835617870396 3.766597092884959 17.49738656005231 +3.595097907247073 4.162363635881387 17.02836387929646 +3.502435310600509 4.240630483201611 17.82481403103838 +-5.010674143055129 2.267850222593798 11.39351149283185 +-5.019325105451389 2.248638584963221 12.11485479368467 +-5.214234864351768 1.749787066867992 11.60608578076643 +-5.227392687083999 1.71007768683786 12.30164606452802 +-5.428900153511891 0.8815004952911637 3.01675994996863 +-5.310575775203681 1.431008363294854 3.306658691360283 +-5.400300717335753 1.042474058354909 3.59443502943834 +-5.232284789133102 1.6950504079249 2.74394016949714 +-5.368314027026498 1.196329598075104 2.449700901030006 +5.428900153511891 0.8815004952911695 19.98324005003137 +5.310575775203678 1.431008363294866 19.69334130863972 +5.400300717335751 1.042474058354919 19.40556497056167 +5.232284789133099 1.69505040792491 20.25605983050286 +5.368314027026497 1.19632959807511 20.55029909897 +-5.411339877535848 0.9835653154673121 19.44917206052074 +-5.311381874488377 1.428013509514646 19.6907009721914 +-5.431297774595965 0.8666051486512825 20.09236800214336 +-5.361429202071238 1.226815760893934 20.63433728931205 +-5.231037537993018 1.698895604829193 20.28802942633693 +5.411339877535846 0.983565315467325 3.550827939479269 +5.311381874488375 1.428013509514654 3.30929902780861 +5.431297774595964 0.8666051486512906 2.907631997856647 +5.361429202071239 1.226815760893932 2.365662710687957 +5.231037537993015 1.698895604829201 2.711970573663081 +-5.472709109275105 0.5472248214922967 20.77278484580872 +-5.472014953203678 0.5541230476305286 2.216673949260795 +5.472709109275105 0.5472248214923 2.227215154191288 +5.472014953203677 0.5541230476305368 20.78332605073921 +-5.482497148315788 0.4384347371151621 3.436053554344358 +5.482497148315788 0.4384347371151704 19.56394644565565 +-5.482513994836586 0.4382240253808296 19.56393250908492 +5.482513994836586 0.4382240253808379 3.436067490915086 +-4.775635725365867 2.728241818206229 11.8072139099439 +5.010674775874732 2.26784882441769 11.60648711761775 +5.019325838318885 2.248636949083694 10.88514403911231 +5.21423521075417 1.749786034614351 11.39391347582475 +-5.317632782137576 1.404557437179338 10.05498448414246 +-5.096257898675524 2.068370235278813 10.22909878871527 +-5.209469802219797 1.763923008455874 10.82424438164172 +-5.140849411952942 1.954908520525471 19.66777355282684 +-5.29904520833992 1.47313267561674 19.07084146226447 +-5.034626955285789 2.21416607803248 19.03737759700989 +-5.481221430171733 0.4541053109424547 10.68221897462279 +-5.463276626797649 0.634514380519858 10.10061943276592 +5.317632792444877 1.404557398156054 12.94501520218681 +5.096258038005192 2.068369891984381 12.77090058338577 +5.209470197057076 1.763921842365504 12.1757549778443 +-3.992792746991361 3.78253963357599 11.8776812836939 +-3.528977442214035 4.218568265696844 11.50029638451709 +-3.693695814395859 4.075121008106938 12.35948254352473 +-5.220605730990088 1.730686511634456 2.048877350606368 +-5.385776370435307 1.115084251373272 1.940288678105823 +5.220605730990086 1.730686511634464 20.95112264939364 +5.385776370435305 1.11508425137328 21.05971132189418 +-5.455005557873402 0.7020786021310552 7.756705087151627 +4.993247231362075 2.305966627359334 20.82842918248378 +3.992795141524012 3.782537105941229 11.12231476535362 +3.528981603021195 4.218564785035067 11.49969637234739 +3.693698847994938 4.075118258446112 10.64051329331807 +5.455005557146023 0.7020786077826439 15.24329490592823 +1.657381828100227 5.244338421181755 20.97683553753585 +2.192438619940514 5.044126574323184 20.93042451810752 +-1.66662621048625 5.241407928650492 2.053845367602968 +-2.237997772390889 5.024078619087625 2.061313901379876 +-2.257961664811557 5.015137996131455 20.96255216152463 +-1.637106700341403 5.250702967384203 20.97052414394294 +2.25767162282702 5.015268571420838 2.037742338254901 +1.637654521902824 5.250532131783523 2.029888231474924 +4.986892509122331 2.319677370338293 20.19228630703844 +-4.994281531805845 2.30372567400354 20.19432795419796 +-4.98335072057874 2.327276433023665 20.83431293862204 +5.140849411952935 1.954908520525491 3.33222644717317 +5.299045208339917 1.473132675616751 3.929158537735546 +5.03462695528579 2.214166078032481 3.962622402990132 +-4.993247231362078 2.305966627359325 2.171570817516219 +-4.986892509122335 2.319677370338286 2.807713692961556 +1.220328845617222 5.362909425727283 20.36037653804514 +1.859530465959767 5.176113063503101 20.38175174450586 +4.994281531805842 2.303725674003547 2.805672045802044 +4.983350720578737 2.327276433023673 2.165687061377962 +-1.229000630365913 5.360928786186232 2.636197795021147 +-1.860498419404162 5.175765221819342 2.617230226841961 +-5.053527844046605 2.170681075019006 3.956472041404673 +-5.305698519135421 1.448986964759929 3.940348124236674 +-5.139309328694331 1.958953706445207 3.350451536109656 +-1.920576374638516 5.153773994771247 20.45224075908283 +1.920051232040922 5.153969660983477 2.549441461511144 +5.0535278440466 2.17068107501902 19.04352795859533 +5.305698519135408 1.448986964759979 19.05965187576332 +5.139309328694326 1.958953706445224 19.64954846389035 +3.155361773917996 4.504852059246461 3.339142202523938 +2.499308170155378 4.899332471938863 3.395437067744627 +2.888888691159873 4.680205351273445 2.774581799606676 +2.356925541824801 4.969396541864401 2.672185101771131 +-3.155361773918014 4.504852059246448 19.66085779747608 +-2.500946758226416 4.89849622971344 19.60427859143536 +-2.888888691159884 4.680205351273439 20.22541820039332 +-2.359058533826236 4.968384328328638 20.32812247432406 +-0.751425092880375 5.448427326283221 19.94441086747722 +-0.7286434345159736 5.451520773631589 19.27259212950035 +-0.1745048658698942 5.497230944010606 19.45006694063901 +5.227392953533448 1.710076872350733 10.69835318216947 +0.7313709392590744 5.451155524217531 3.069480548279252 +0.7292583766425669 5.451438545934151 3.729666793865334 +0.07890490949555239 5.499433972260918 3.559720906022054 +4.77563670953724 2.728240095468199 11.19278423315653 +-1.694658720968588 5.232411663797595 5.901271668811129 +-2.196985468865216 5.04214784091017 6.475373092536266 +-2.188382956872763 5.045887437712897 5.748225947979154 +5.48122144954089 0.4541050771494042 12.31778087710347 +5.46327663945922 0.6345142715015719 12.89938047652152 +5.268571883430765 1.578654588288016 10.02404736598337 +5.335796358245354 1.333895506902852 9.436720810720116 +5.450939545359613 0.7329789034035918 9.977371544333709 +5.123799849464316 1.999168602852061 9.492534710717168 +-5.268571693643828 1.5786552216792 12.97595220373191 +-5.335796318687084 1.333895665142279 13.5632790084084 +-5.450939510568176 0.7329791621368046 13.02262831003278 +-5.12379970194205 1.999168980946472 13.50746493567334 +-4.392320878340514 3.310214086988032 4.265228436520456 +-4.240901894491027 3.502106669035429 3.659999067447611 +-4.08323863542111 3.684720104187611 4.287330547591772 +2.510886324540992 4.893408818526511 9.918660025348121 +3.141761344944701 4.514347754815889 10.23680404049846 +4.392320878330065 3.310214087001898 18.73477156346637 +4.240901894485453 3.502106669042178 19.34000093254072 +4.083238635398172 3.684720104213029 18.71266945237214 +1.453442492594296 5.304479703111444 9.86639629908929 +0.9178735184091102 5.422869001202526 10.31192147771104 +-2.510882431895435 4.893410815903245 13.08133394326501 +-3.141756579617173 4.514351071242932 12.76319070270829 +-1.453436194972178 5.304481428673759 13.13359475120308 +-0.9178624304782304 5.422870877931412 12.68806593556608 +-4.937765342530779 2.42249322436656 17.46092741625911 +-5.088389169430112 2.08765314658023 16.83824443892554 +-4.688615348281875 2.875219316131489 16.88897063155009 +-0.585657652613466 5.468729753236603 13.80477343624097 +-0.3591131540836222 5.488263636393947 14.41032820408435 +-1.03709485912978 5.40133633957066 14.22070381773394 +4.937765342530772 2.422493224366574 5.539072583740918 +5.088389169111818 2.08765314735603 6.161755561244814 +4.688615347656697 2.875219317150967 6.111029369054787 +-2.809464556133646 4.728309307546279 4.210142102825358 +-3.405684259476996 4.318716791449821 4.508618783858825 +-5.211566047630919 1.757719923986937 20.92340118337728 +2.813531674717698 4.725890341021491 18.79912052629948 +3.405684259474934 4.318716791451446 18.49138121614132 +-4.786464133656978 2.709199346156602 5.78397039293117 +-4.997686318703415 2.296329998028312 5.447928489574473 +-4.742591685872107 2.785287076962942 5.076250127598776 +-5.118272152380046 2.013278464140252 6.138066935313313 +4.786464133573848 2.70919934630347 17.21602960691761 +4.997686318676581 2.296329998086714 17.55207151038277 +4.742591685856623 2.785287076989307 17.92374987239872 +5.118272152370384 2.013278464164816 16.86193306469039 +3.197110537359145 4.475319453615252 20.8111479668233 +-5.38336751009986 1.126656225829882 21.07218686743499 +5.211566047630918 1.75771992398694 2.076598816622724 +5.383367510099859 1.126656225829886 1.927813132565017 +-3.197110537359147 4.475319453615251 2.188852033176701 +-3.201086581678501 4.472476349473282 20.76419076954355 +3.201086581678487 4.472476349473291 2.23580923045645 +0.06011532916270899 5.499671458114536 13.95884954928087 +0.5856609727474247 5.468729397675528 9.195221636896843 +0.3591116326501976 5.488263735945577 8.589671151108407 +1.037094252674728 5.401336456014294 8.779293494075338 +-4.273773139356108 3.461916110092536 4.971177262103524 +-3.83982116152894 3.937737097302782 4.720954873427537 +-4.447490766557506 3.235711031811359 5.513296224022758 +-0.06011452809586817 5.499671466870709 9.041146941923065 +-2.646762656774909 4.821270313797166 5.984566833027301 +4.27377313934601 3.461916110105002 18.02882273786845 +3.837593134380751 3.939908493220842 18.29437538770882 +4.447490766557499 3.23571103181137 17.48670377597727 +-1.575534253310781 5.269505841788624 6.521298529403206 +1.694225053909136 5.232552098804806 17.11330055406454 +2.231946079851533 5.026770006339595 16.55220664250123 +2.199764890529101 5.040935868109759 17.27776894379152 +2.660061906156462 4.813945435442247 17.01517644959751 +1.610704467302804 5.258862150599765 16.47941131396281 +-2.391072854904075 4.953056692845427 4.645476687463972 +-5.096856460806345 2.066894825078581 9.534091841104551 +-4.800391764820603 2.684443872432898 9.481510855151512 +-4.891962950688174 2.513702148046633 10.03379178540015 +-2.298887338367595 4.99651048287634 3.974843198008681 +5.09685637337353 2.066895040683398 13.46590768935055 +4.80039150679439 2.684444333841976 13.5184884447788 +4.891963248424284 2.513701568616715 12.96620735289273 +4.625018151333335 2.976442020237785 20.95726200968921 +-4.625018151333339 2.976442020237776 2.042737990310787 +1.010557544806951 5.406364161674068 18.88531951637341 +0.2685750643118522 5.493438580236415 18.83912084368752 +0.6796190499436738 5.45784920522303 18.25734746628549 +-4.633098369214002 2.963848764897857 20.9814388229926 +4.633098369213989 2.963848764897878 2.018561177007399 +0.4961601125162191 5.477574750083096 19.3278260237904 +-0.8210578697434463 5.438369606282047 13.22909859246372 +-0.3194120580440881 5.490717251614405 12.80088307640872 +-0.2596713372932558 5.493866652603459 13.39143592298194 +0.8210662103073845 5.438368347058837 9.770893181757119 +0.3194250833122771 5.490716493878639 10.19910321122251 +0.2596786609819472 5.493866306439448 9.608555597391057 +-5.231951367568638 1.696079269196065 6.994196678783307 +-5.098004349952544 2.06406192927076 7.54862755757337 +-5.338008536986814 1.325015041067797 7.690950308004201 +-5.04183988427705 2.197692103392369 6.853947944688267 +5.23195136681049 1.696079271534749 16.00580331788455 +5.098004348705434 2.064061932350986 15.45137243522652 +5.338008535460469 1.325015047216891 15.30904968389035 +5.0418398838663 2.197692104334695 16.14605205503421 +4.549562327218363 3.090547302785615 13.67868645721495 +-5.031644854520294 2.220934501055682 15.62617884428618 +-4.915334368164055 2.467688807192929 16.22889256805091 +-5.183019965519857 1.840191304463355 16.06981868706756 +4.5705869430963 3.059368398149791 12.96012686971 +5.03164485429528 2.220934501565464 7.373821155416168 +4.915334368193626 2.46768880713403 6.771107431942962 +5.183019965479798 1.840191304576182 6.930181312697009 +-4.795733947972296 2.692756190275319 6.385319788968577 +-4.783748787098689 2.713991072559345 7.100044726632545 +-4.3983653243618 3.302178443611387 6.727830031229576 +4.79573394775506 2.692756190662211 16.61468021079603 +4.783748785836071 2.713991074784868 15.89995527042291 +4.398365322767977 3.302178445734293 16.27216996434933 +4.436952469835771 3.250146578297394 16.98530402431957 +-4.436952470101494 3.25014657793464 6.014695975270911 +-4.339724395933278 3.378874393543143 19.47637821709665 +-4.698447450874927 2.859124263016019 19.25236383221937 +4.700629253236157 2.855535785736275 19.1592918321355 +5.210910551001198 1.759662248689902 17.57738409306446 +5.056890707941086 2.162835261396276 18.19846243653412 +5.031846199045763 2.220478288375889 4.832022893192221 +5.174142663188317 1.865006086042217 5.476482783107834 +4.735893554108302 2.796660909755675 4.954607103532439 +-5.210910551009926 1.759662248664052 5.422615906915887 +-5.056890707946234 2.162835261384239 4.801537563447035 +1.710654196771959 5.227204053704665 9.106489896918768 +1.954426227515769 5.141032787407456 9.682074035265968 +-5.031846199053325 2.220478288358751 18.16797710681387 +-5.174142663229304 1.865006085928504 17.52351721692148 +-4.735893554147441 2.796660909689396 18.04539289649522 +4.339724395933272 3.378874393543151 3.523621782903373 +4.698447450875043 2.85912426301583 3.747636167780918 +-4.70062925323617 2.855535785736254 3.840708167864513 +-3.530423486090813 4.217358178867238 19.22529394861429 +3.530179987161032 4.217562004078629 3.774685096968607 +-4.837199620709983 2.617536977657278 15.29609969951526 +-4.549562557228615 3.090546964189903 9.321312641536226 +4.837199620709977 2.617536977657289 7.703900300484776 +-0.2046242557175721 5.496192219525445 4.157073566587549 +0.3883083882325613 5.486275293459874 4.173778512426068 +-0.07125864645562176 5.499538362926957 4.701969757988433 +0.6445787640685148 5.462098334606574 4.794253692481327 +-4.813151104728688 2.661498909082813 7.654082848287452 +-0.4414875749696833 5.482252157749349 18.80195011354745 +0.05010323804276654 5.499771783041332 18.3071587773718 +-0.6599812624622861 5.460258669074085 18.20667139764824 +4.813151096649549 2.661498923693422 15.34591712786255 +1.188601873583592 5.370030315195025 9.337409104559695 +-1.710653178645179 5.227204386896608 13.89350600713789 +-1.9544233937067 5.141033864713593 13.31791977384671 +-5.301564784369081 1.464039219808547 16.45650287980687 +-5.426100124428276 0.8985752276128283 15.07406223853605 +-1.188597836379683 5.370031208787667 13.66258514651467 +5.30156478429565 1.464039220074455 6.543497120114719 +5.426100124678966 0.8985752260990223 7.925937759641416 +-4.570586393961214 3.059369218537805 10.03987183643348 +-5.391076468856118 1.089171477291728 7.089188054095684 +-5.31931975811065 1.398154966723522 6.540134042306363 +3.955245708645478 3.821783796114261 9.993216833642693 +4.258966669038487 3.480115359010274 9.389598101507303 +4.368554159643581 3.341516804425915 9.994689125969929 +5.391076467936988 1.089171481841154 15.91081194338765 +5.319319758110647 1.398154966723534 16.45986595769366 +2.298887338367579 4.996510482876347 19.02515680199133 +2.663123586883296 4.81225235840618 20.8515299598476 +5.348370385706227 1.28254988881549 11.81227538301385 +-1.845374830184476 5.1811766748608 5.119718592588899 +3.544944596296389 4.205159665124386 9.808341104588452 +2.44511692045554 4.926601591899026 18.36318203432473 +1.837405724514574 5.184008121475223 17.91664722890685 +-2.663123586883308 4.812252358406174 2.148470040152397 +-5.334410047792129 1.33942877452083 16.99090502186604 +-5.441214520162712 0.8019878712115736 6.569278309192056 +5.334410047726437 1.339428774782458 6.009094978207489 +5.44121452016345 0.8019878712065678 16.43072169077789 +-5.337449053647151 1.327266966258535 5.961153968498753 +5.337449053647148 1.327266966258548 17.03884603150127 +-5.43703214088581 0.8298683624374804 16.42055026296465 +-5.459002220958722 0.6702945259866965 18.93301751783885 +5.437032140862797 0.8298683625882517 6.579449736978205 +-1.192146203293393 5.369244586529203 18.8324858566556 +-1.85855777813809 5.176462400647996 19.33368808294322 +-1.7921334428386 5.199832470672441 18.68156600907093 +-1.295268439269758 5.345304450658698 19.64301949796906 +1.160084220155056 5.376263070400038 4.166371625530637 +1.867433637045109 5.173267015265351 3.705027559552281 +1.792133442838583 5.199832470672447 4.31843399092908 +1.288213191225761 5.347009142871549 3.357568374909469 +1.801093938770176 5.196735573773726 18.63619514643198 +1.100525363306066 5.388770168110721 19.62023108651966 +-1.849146677823631 5.179831711927891 4.386394205408841 +-1.165447534413337 5.375102979900002 4.139748903113059 +-1.096504652039414 5.389589738380457 3.372285337730283 +-5.478202233943307 0.489183282644203 18.34109250066941 +5.459002220958721 0.6702945259867071 4.066982482161166 +5.478202233943307 0.4891832826442137 4.658907499330606 +-5.460222360708862 0.6602815850945287 4.065231019918414 +-5.478672404849342 0.4838891198842227 4.657617304735403 +5.46022236070886 0.6602815850945393 18.93476898008159 +5.478672404849341 0.4838891198842335 18.3423826952646 +-5.477347823348086 0.4986590238469432 7.124969835706715 +5.477347823142162 0.4986590261088473 15.87503016219416 +-5.348370250443319 1.282550452876167 11.18772410497208 +-3.955245033207059 3.821784495139789 13.0067810992373 +-4.258966549463349 3.480115505346375 13.61040114170976 +-4.368552901781578 3.341518448899505 13.00530950049696 +-2.707706826431882 4.787308611536777 20.79263660836428 +2.707296049781381 4.787540923985729 2.207721729993523 +5.3760085949413 1.16126292764269 10.57430281841764 +-3.544943309815396 4.205160749625995 13.1916558715719 +4.065481115269776 3.704303348996247 11.64302085600955 +3.270525152278468 4.421952648809563 12.08515396208009 +-4.411283811240181 3.284901084765004 18.91775468474105 +-4.065478532771891 3.704306183291402 11.35697536560351 +-3.270520472447209 4.42195611006076 10.91483945573122 +4.411283811240176 3.284901084765012 4.082245315258959 +3.287740096828187 4.409168295235302 5.821932839834675 +3.116736766037026 4.531661056525858 5.137820268540118 +3.568883935242205 4.184861701032678 5.15169270648175 +-5.397077129924198 1.059036568608081 4.617269756544118 +-5.227395834084631 1.710068067006292 4.424748118299139 +5.397077129924189 1.059036568608128 18.38273024345586 +5.227395834084624 1.710068067006317 18.5752518817008 +-5.376885863223022 1.15719419885878 18.40446731576727 +-5.194811327105779 1.806636453682226 18.56624467896874 +5.37688586322302 1.157194198858793 4.595532684232751 +5.194811327105776 1.806636453682236 4.433755321031285 +-4.853169490029221 2.587807160715324 4.421902753661399 +4.853169490025221 2.587807160722827 18.57809724633592 +2.735793113450708 4.771313869407009 5.662860505156253 +-3.287740093430427 4.409168297768876 17.17806715476095 +-3.11673985477435 4.531658932186001 17.86217552427774 +-3.568887932569373 4.184858292076412 17.84830108219976 +-4.744587472524049 2.781885999743313 15.80006045326363 +-4.739391196694875 2.790729489701773 18.5993931219278 +4.744587471353688 2.781886001739399 7.199939546216502 +4.739391196686404 2.790729489716159 4.400606878082552 +-1.890387951770005 5.164923367466628 19.95212868899368 +-2.402021353429759 4.947756402417915 18.77674197483531 +-3.04142299744655 4.58254799763224 19.07309385408561 +1.887246578738406 5.166072042765197 3.048260788350003 +2.402021353825841 4.947756402225626 4.223258024406622 +3.04107416509485 4.582779497465775 3.926697653074573 +-2.73579311824287 4.771313866659262 17.33713947752031 +4.881094441616244 2.534742008967187 12.25455484286339 +-0.4718815953703434 5.479719678957195 12.17701767900035 +9.64165449218056e-06 5.499999999991549 11.49998960636863 +0.2945238078721912 5.49210849552305 12.3436081388982 +-5.401706578124941 1.035164742367967 8.293851412668884 +5.401706574718429 1.035164760143861 14.70614856926462 +0.4718946416021625 5.479718555475926 10.82296674564377 +-0.2945078137729298 5.492109353210903 10.65637701912656 +-2.442457928950143 4.927920379359692 13.7558707809145 +-3.019207235214041 4.597215208235436 13.43581879316506 +2.442458904439585 4.927919895871257 9.244125730707983 +3.019208729730804 4.597214226715708 9.564177752792213 +-1.154924835660694 5.377373766437862 1.984754680248667 +-0.5272360885008175 5.474670958786688 2.26018407973207 +-0.4279984950714094 5.483321738528263 3.00267062135309 +-4.881092959724299 2.534744862610413 10.74544372961813 +-5.257246915253555 1.615968710110744 15.36729725439038 +5.257246915666979 1.615968708765748 7.632702744383451 +1.075767488469191 5.393767172464222 20.98681840530856 +0.443003895921329 5.482129836860718 20.68968843360761 +-3.581664847833093 4.17392823582255 18.632563788543 +-4.014430398760081 3.759567604593776 18.72914107747249 +-3.922661226888961 3.855220992247006 18.13196311091248 +0.7109876791200571 5.453851530811916 20.01831688673403 +3.581664847833083 4.173928235822559 4.367436211457019 +4.014389319034238 3.759611468652555 4.270823643577728 +3.92266122688895 3.855220992247017 4.868036889087534 +-0.9103092156916173 5.424143907735756 10.6572989586918 +-0.8435910699740785 5.43491988042694 10.12566897198158 +0.9103252043395166 5.424141224410019 12.34268781617939 +0.8436024422159923 5.434918115251343 12.87432089487581 +-3.069346436891189 4.563892247889226 18.41830878857166 +4.887613760812203 2.522148236150918 14.15586007781105 +3.069330614810631 4.56390288864544 4.581644115973422 +4.657266373120569 2.925725539041621 14.81180641807936 +-5.270720478530249 1.5714660789218 4.932906855283971 +4.470142697837525 3.204344591483547 14.30120488782947 +5.270720478530152 1.571466078922128 18.06709314471576 +-4.860757800678228 2.573525520204872 3.28510250818227 +-5.252863386847634 1.630161415049318 18.02119842313573 +4.86075780067822 2.573525520204887 19.71489749181773 +5.252863386847631 1.630161415049334 4.978801576864292 +-4.862655898856476 2.569937277311709 19.7284188091918 +4.862655898856472 2.569937277311716 3.271581190808238 +3.23219281432577 4.450048270639416 19.68477042767006 +3.211881589044636 4.464730300696347 19.14187529089168 +3.714620376491541 4.056056638972618 19.23239163760566 +-3.233172570911298 4.449336481623617 3.314052838118759 +-3.218066613281897 4.460274349463313 3.851210916964938 +-4.887613961513926 2.522147847215571 8.844139548610606 +-4.657266470578231 2.925725383905294 8.188193414766419 +-4.470143052798878 3.204344096303318 8.698794641950879 +-3.797702240792797 3.97837374944554 6.774694188131834 +3.797702238018037 3.978373752094289 16.22530580519761 +-3.713033560219439 4.057509307528962 3.766240052674128 +-4.552600305781377 3.086070390609927 17.50903290764184 +-4.387542903536551 3.316544477257322 18.15128119070974 +4.552600305442014 3.08607039111056 5.490967092546736 +4.387542903510241 3.316544477292131 4.848718809288972 +2.400018993208323 4.948728001440299 6.225130770538806 +2.55133407503864 4.872442348304054 6.896070966351141 +1.852173433794142 5.178750193931661 5.994508052648928 +1.245449046528342 5.357131384659297 6.272387957952738 +-4.487268363592511 3.180318008171791 15.42559946447477 +0.1563154490014154 5.497778231286115 14.7486780366831 +0.8160347683199298 5.439125596719848 14.30363816255019 +0.7613807892416119 5.447045005668103 15.17610792728718 +4.487268338056182 3.180318044202263 7.574400529395531 +1.26753552898055 5.351948587455974 14.74177218953571 +-4.462618889660586 3.214814558515703 7.560590555941271 +-0.3337168402985644 5.489866398237861 15.08649405111333 +-0.8803546236734138 5.429086086679493 14.88216714301635 +4.462618865175851 3.214814592503991 15.43940942387444 +-0.1563164991579149 5.497778201427465 8.251321527547523 +-0.8160359584916154 5.439125418157654 8.696360594287867 +-0.7613816641979094 5.44704488336779 7.823906280405918 +-1.267536183161795 5.351948432522088 8.258231492318245 +-2.400019004425708 4.948727996000128 16.77486918719005 +-2.551334115420344 4.872442327159173 16.10392892728257 +0.3337161318161887 5.489866441304892 7.913505606064513 +-1.852173433325923 5.178750194099119 17.00549189240353 +0.8803538221095775 5.429086216657188 8.117832251694237 +-1.245449067140265 5.357131379867349 16.72761190139187 +-2.126514819065657 5.072271160367332 14.39218431016264 +2.126514313995397 5.072271372114536 8.607814456004228 +1.930404332828591 5.150100883652339 12.70846807930957 +-4.902846442338161 2.492407824344169 14.1323059063664 +4.902846455847626 2.492407797769533 8.867694018679057 +-5.312615642174913 1.423416677757582 9.463231510414337 +5.312615593223335 1.423416860459461 13.53676829224787 +-4.60009179295529 3.014822630999273 4.542149883376176 +4.600091792946952 3.014822631011997 18.45785011661776 +-1.930398879886459 5.150102927566896 10.2915243293462 +-4.706115764323725 2.846484570972363 14.83325528621944 +-4.468437306821826 3.206722319597209 14.22259031094761 +4.706115765294521 2.84648456936734 8.166744685826231 +4.468437272026495 3.206722368083089 8.777409534618734 +-3.75286190224086 4.020699882198261 17.13974851003485 +-4.114042780293788 3.650294782878851 17.5799920940136 +-4.305865859602696 3.421917474035271 16.89623789009677 +3.752861898985891 4.020699885236403 5.86025148844811 +4.114042779556804 3.650294783709465 5.420007906181958 +4.305865858824858 3.42191747501404 6.103762110785983 +-4.297349949204566 3.432605921755586 8.147355905290485 +-3.979211264870267 3.796824687752856 7.582713976096613 +0.1693897436120644 5.49739093704996 2.769191037235796 +-0.6021933711295057 5.46693361435528 3.784763985375442 +-4.258823100591838 3.480291050740632 12.39972910145598 +4.297349820210012 3.432606083246515 14.85264389728539 +3.979211185629052 3.796824770800548 15.41728584243933 +4.258823571053184 3.480290475038225 10.60026818535716 +-4.089685752019594 3.677563112949652 15.37616413967135 +-4.332768471493559 3.387789452199083 14.84356421830604 +-3.582666480438033 4.173068522076501 15.27243150975339 +-3.761152986404268 4.012945079721656 15.91932036553529 +-3.219863149472922 4.458977606881013 15.87041530251663 +4.089685705571798 3.677563164602575 7.623835838397769 +4.332768464096381 3.387789461659607 8.156435747559879 +3.582666419597833 4.173068574309084 7.727568435011907 +3.761152972648945 4.012945092613903 7.080679612713013 +0.00859348493915372 5.499993286542866 6.949201801918528 +-0.49667240046519 5.477528322758007 7.270944104288713 +-0.4331430396371151 5.482917754919722 6.511039488849669 +-1.080749306665185 5.392771174094328 6.975253381797472 +0.2058566076280722 5.496146200484105 6.486612644377148 +3.21986308800105 4.458977651270338 7.129584644855523 +0.07605022133179161 5.499474189759907 5.872027222628528 +-0.008606923824768567 5.499993265528811 16.05079518850903 +0.4966721940137065 5.477528341477898 15.72905566469597 +0.4330960912435158 5.482921463576656 16.48894854519679 +1.080701140578544 5.392780826693427 16.02482937138342 +-4.612747920796539 2.995422611116368 13.55922661213226 +-0.2058643427099294 5.496145910763342 16.51339829399369 +-0.07652082782679226 5.499467661774974 17.12813372129423 +-4.006237679348617 3.768296651879654 14.26326210832936 +-0.4503169949203 5.481533964510843 5.353788374303956 +0.1633266977833135 5.497574409663883 5.225006086685358 +-0.719982446070173 5.452671389085427 4.645824552854151 +0.4478143651860431 5.48173898451331 17.64824117182599 +-0.1632469796515455 5.497576777420634 17.77529343477993 +1.483742103252614 5.296084343270555 12.08475678825232 +4.612748175542081 2.995422218825453 9.440772866312606 +3.610881024890024 4.148679093891111 14.48056012238396 +3.912586625658921 3.865445109779072 14.85278998250487 +3.527644235238074 4.219683181186899 15.06104198425362 +4.075181305061565 3.693629289855266 14.37595018833746 +-3.610881585042449 4.148678606351826 8.519439241958256 +-3.912586827714917 3.865444905258866 8.14720961023448 +-3.527644383443847 4.219683057287251 7.938957578785955 +-4.075181773769333 3.693628772729907 8.6240492470044 +-3.9252569189357 3.852578113464725 13.64621038695281 +3.925256771494772 3.852578263687117 9.353788767267462 +4.006237615841942 3.76829671939632 8.73673771924272 +0.2340919843679714 5.495016009335611 13.153950822796 +0.7999481195281591 5.441514771280453 13.53880779599189 +1.386546545258634 5.322357436120891 13.15323255976159 +-0.2340833126269 5.495016378751716 9.846039515930865 +-0.799943582484997 5.44151543826176 9.461187489143972 +-1.386540058153988 5.322359126095714 9.846762940595683 +-1.483731098539208 5.296087426320267 10.9152302100982 +-0.1932804998209266 5.496602827964649 20.9242680198105 +0.1791536249842918 5.497081405496465 2.07319147826119 +-2.706538977167704 4.787968960328795 14.4697620706192 +-2.965259326563874 4.6321957132904 13.9684408809637 +2.706538263468055 4.787969363768248 8.530237134075927 +2.96525965757986 4.632195501393412 9.03155726583601 +1.485973882151698 5.29545858463297 15.2552901047851 +1.786125422977793 5.201899265978955 15.92056720995871 +2.065934928272491 5.097245616226839 15.27866034451625 +1.048251920920306 5.399182151982547 16.7808874013297 +0.5459418673305135 5.472837242006715 17.08692134112777 +-1.105971215971166 5.387655117900854 6.207049115150282 +-0.547172600658835 5.472714330667028 5.913521965915479 +-1.485973414051052 5.295458715988017 7.744722500437499 +-1.786125515302598 5.201899234278287 7.079432577158233 +-2.065929584655296 5.097247782013937 7.721341101271557 +5.457561409164187 0.6819262901529852 8.601237658188898 +-5.457561408567907 0.6819262949251033 14.39876233814545 +-5.471047710444051 0.5635928938914262 8.531481429127112 +5.437437414913428 0.8272087758840456 13.4365332259694 +5.478393306359543 0.4870387878136174 13.88183849061731 +5.471047708814177 0.5635929097133374 14.46851854787566 +-5.437437425105866 0.8272087088867498 9.563466675619097 +-5.478393309285252 0.4870387549041523 9.118161468499679 +3.156122689830591 4.504318990339884 13.97003839472711 +2.965924984821659 4.631769530580147 14.70748665520834 +-3.156123621223387 4.504318337723898 9.029960173350085 +-2.965925506708846 4.631769196392873 8.292512504224987 +-1.118262340363096 5.385117393161049 5.422454260386857 +1.110851453982848 5.386651004769493 17.57767688051653 +-1.30423711652273 5.34312320126389 9.259324409775171 +1.304237435362373 5.343123123436271 13.7406729193378 +-1.990424689967828 5.127202897639851 9.409259810498352 +1.990421424192005 5.127204165441188 13.59073739435787 +-4.416614647299824 3.277730168463633 11.71959396175861 +-3.49514084160964 4.24664461631913 16.51821534157802 +-2.480109406462052 4.909079071677136 8.852780795636503 +-4.226352540942053 3.519651147439567 16.12250040175081 +-4.685748956887469 2.879888316068522 11.27349814085874 +3.495140828239167 4.24664462732351 6.481784644921877 +4.226352526841336 3.519651164371527 6.877499593935692 +2.480107670002005 4.909079948951455 14.14721759432155 +-3.296241039491157 4.402816713147875 9.592693972464616 +-2.680639741058173 4.802517108627472 9.72568794371586 +-3.195581176312167 4.47641161485395 10.22055736041476 +3.195583301528583 4.476410097722469 12.77943855920452 +3.682450531845129 4.085285556789578 13.07942308431976 +3.296241173064899 4.402816613145696 13.40730369155956 +-3.68244926002021 4.085286703204146 9.920574519076151 +2.68064040523125 4.802516737903329 13.27430878120827 +4.416615883377039 3.277728502896732 11.2804030717266 +-5.376008548437103 1.161263142931522 12.4256967776994 +-3.479613335564772 4.259376836458569 13.90443341363639 +4.685750137102374 2.879886395788052 11.7264994396198 +3.479613527882232 4.259376679348631 9.095565712197642 +4.661777998536826 2.918531461601535 10.58519702700777 +-4.661776756188122 2.918533446007455 12.4148014270987 +-5.462128318490723 0.6443246327292718 13.66037891778869 +-4.902239404101271 2.493601577012015 13.46234898717918 +2.433465236027011 4.932367275968812 15.82633964032092 +3.041162244928413 4.582721047589737 15.51375541232369 +2.84219432985214 4.708708038449224 16.28419128732825 +5.462128320792956 0.644324613212566 9.339621073909147 +-2.433465344662352 4.932367222371763 7.173660143464488 +-3.041162370653767 4.582720964156509 7.486244212244873 +-2.842194343125339 4.70870803043747 6.71580866322366 +4.902239687652367 2.493601019571101 9.53765054467388 +-5.024512846674126 2.237022720851683 12.76944561730299 +-3.17672415366882 4.489813320339402 14.40738685392724 +-3.551699021442334 4.19945640066492 14.61405799166421 +3.176723730320634 4.489813619875301 8.592612662072957 +3.551698878909094 4.199456521212702 8.385941663922697 +-4.706970393214506 2.845071126949566 13.05270566327089 +5.024513184626128 2.237021961787191 10.23055353804391 +4.706970970969951 2.845070171093536 9.947293586600159 +-1.892846417907292 5.164022892882596 8.450049693212094 +-1.471254131155683 5.299567084352961 8.821526666189731 +1.892845355599715 5.164023282265929 14.54995135793013 +1.471252386977955 5.299567568567427 14.17847167016615 +-0.8167601724779215 5.439016714503995 17.4408441895794 +0.8167601711569361 5.439016714702364 5.559155761930306 +1.311406507125179 5.341368080657777 2.6597272368533 +-1.320470713201806 5.339134489369632 20.3436227618141 +-1.481645893992888 5.296671166384979 14.65643272508214 +1.481645478671969 5.296671282563315 8.343565682391477 +-0.1954876313485898 5.496524773526425 20.26465924331706 +-0.7115321916568008 5.453780518157664 20.65527740099823 +0.6965290054741168 5.455716941386644 2.353627742646889 +-1.108478556158927 5.387139806106374 20.99688392771067 +-3.931560443197724 3.846145145659861 16.53550027770735 +1.106103939997509 5.387627870772255 2.005763226260708 +4.571068068055903 3.058649492373993 6.736684940952259 +-4.571068072295729 3.058649486037687 16.26331506145214 +-1.352662260654173 5.331069762121103 4.794899282421031 +1.327168241360013 5.337473602663096 18.20886250420431 +3.931560434785412 3.846145154258994 6.464499713145464 +3.918174256782305 3.859781145801978 8.156900166617666 +-3.918174351849584 3.859781049296461 14.84309975740893 +2.676898484364142 4.804603470049215 7.469143400343679 +-2.676898488309966 4.804603467850789 15.53085642139562 +5.455376201340396 0.6991927501403503 11.82622422435464 +5.405682618508358 1.014196937461666 12.34144139640151 +-5.455376170416751 0.6991929914187236 11.1737754900686 +-5.405682477281952 1.01419769019992 10.6585583481099 +0.2415270219694205 5.494694231498108 19.95150230057103 +3.110432353243674 4.535990583752905 16.88062954904695 +3.348866646514343 4.362922436150312 16.49093303714022 +-3.100692808191171 4.542653861921636 6.118373325531085 +-3.34886665676099 4.362922428285251 6.509066926579614 +1.312247359966703 5.341161565264659 12.60005450133026 +-1.312230648701175 5.341165670956977 10.39993571125023 +-5.380931999153816 1.138231444163497 11.79550163701581 +5.380932082495059 1.138231050171884 11.2044979100801 +-5.465047856186089 0.619073444427902 12.26132632709278 +-5.478332155205763 0.4877261498408518 11.67836235758554 +5.465047882919356 0.6190732084323023 10.73867351665439 +5.478332183630177 0.4877258305665397 11.32163744641406 +-3.024892606326991 4.593476321936177 16.63952129072726 +3.024892600391554 4.593476325844776 6.360478687108458 +2.603101078211457 4.844983465050665 15.3119493462416 +2.403714109811393 4.946934250451851 14.78398259372507 +-2.603101223168346 4.844983387168574 7.688050311379675 +-2.403714797120416 4.946933916488511 8.216016471285707 +-4.171319124909612 3.584703161792245 7.189230094433317 +4.171319124909602 3.584703161792254 15.81076990556672 +1.467991489063784 5.300471770327269 5.58314892563916 +3.068205403653442 4.564659417852751 7.928109245182952 +-1.467991471615771 5.300471775159582 17.41685102802783 +-3.068205555073298 4.564659316073583 15.07189052384701 +0.04336334387488142 5.499829053744124 7.516516723453904 +-0.04336404037939467 5.499829048252497 15.48348132664468 +0.6932508498555318 5.45613446124402 7.526957744348987 +-0.693251249791085 5.456134410428604 15.47304193372372 +0.6433684309355581 5.462241029291505 6.201253084747005 +0.6919062437981196 5.456305137159502 6.928908083285474 +-0.6433684283855644 5.462241029591856 16.79874683158138 +-0.6919132283470655 5.456304251454307 16.07109098573525 +-2.428417037494979 4.934854677901276 15.04890374850188 +2.428416843401992 4.934854773413449 7.951095815167829 +-3.322688038599348 4.382892218404284 6.996437403624599 +3.322688007950999 4.382892241638918 16.0035625063526 +-3.554653624087862 4.196955755396884 7.370199583960627 +3.554653549599459 4.196955818485581 15.62980019694837 +1.828536252119373 5.187143257582658 7.951360844458426 +-1.828536585607129 5.187143140023824 15.04863866781608 +2 23 0 70 +5367 +5368 +5369 +5370 +5371 +5372 +5373 +5374 +5375 +5376 +5377 +5378 +5379 +5380 +5381 +5382 +5383 +5384 +5385 +5386 +5387 +5388 +5389 +5390 +5391 +5392 +5393 +5394 +5395 +5396 +5397 +5398 +5399 +5400 +5401 +5402 +5403 +5404 +5405 +5406 +5407 +5408 +5409 +5410 +5411 +5412 +5413 +5414 +5415 +5416 +5417 +5418 +5419 +5420 +5421 +5422 +5423 +5424 +5425 +5426 +5427 +5428 +5429 +5430 +5431 +5432 +5433 +5434 +5435 +5436 +-5.5 -0.9639917695473266 20.57175882575281 +-5.5 -1.036008230452671 2.428241174247187 +-5.5 -1.000000000000002 13.72222222222224 +-5.5 -1.000000000000004 12.24074074074076 +-5.5 -0.9813939756750223 15.1151156216116 +-5.5 -1 10.75925925925929 +-5.5 -1.01483442463684 18.91046040487246 +-5.5 -1 9.277777777777811 +-5.5 -1.019904488279914 17.46852743838267 +-5.5 -0.96161809864009 3.99227611543877 +-5.5 -1 7.796296296296328 +-5.5 -1.019904488279917 6.35741632727157 +-5.5 -1.000662481609661 16.2443797084215 +-5.5 -1.000662481609661 5.133268597310387 +-5.5 -1.21604938271603 3.281481481481467 +-5.5 -0.7468948084592992 19.7462788438376 +-5.5 -0.7057613168724335 12.9814814814815 +-5.5 -0.6815257263447589 7.057139773160475 +-5.5 -1.29423868312757 10.01851851851855 +-5.5 -0.672603794623309 18.16904351537147 +-5.5 -1.359822948878115 14.45108649710527 +-5.5 -1.294238683127577 11.50000000000002 +-5.5 -0.7057613168724317 8.537037037037068 +-5.5 -0.5941251709225621 11.50000000000003 +-5.5 -0.6020484978432006 14.44463927278252 +-5.5 -0.5941251709225626 10.01851851851855 +-5.5 -1.406359559826907 18.17352828932761 +-5.5 -1.405874829077447 12.9814814814815 +-5.5 -1.405874829077443 8.537037037037065 +-5.5 -1.405743666141735 7.057855937170615 +-5.5 -0.6338415186073136 5.775153938158681 +-5.5 -0.633841518607313 16.88626504926978 +-5.5 -1.370499265686839 5.788133637617275 +-5.5 -1.370499265686838 16.89924474872838 +-5.5 -1.469848553199933 19.56886843602282 +-5.5 -0.5241625760917081 3.419547702348254 +-5.5 -1.382373113854594 15.70648148148149 +-5.5 -0.6343565395187802 15.68846135346564 +-5.5 -1.382373113854591 4.595370370370372 +-5.5 -0.6310605600129557 4.575395509844249 +-5.5 -0.5637860082304531 20.92222222222222 +-5.5 -0.5262468811768917 2.027314713009396 +-5.5 -1.436213991769542 2.077777777777779 +-5.5 -1.473753118823111 20.9726852869906 +-5.5 -0.4548063899420003 20.36249635462234 +-5.5 -1.545193610057981 2.637503645377667 +-5.5 -1.442414708338278 20.27289486173027 +-5.5 -0.5504111784062171 2.729801215551426 +-5.5 -1.56858710562414 10.75925925925929 +-5.5 -0.4314128943758597 10.75925925925929 +-5.5 -1.568587105624141 13.72222222222224 +-5.5 -0.4314128943758597 13.72222222222224 +-5.5 -0.4314128943758573 12.24074074074075 +-5.5 -1.568587105624144 12.24074074074075 +-5.5 -1.578208507532736 18.89353438900754 +-5.5 -0.4458479503858619 18.91279893915769 +-5.5 -1.568587105624142 9.277777777777811 +-5.5 -1.559352662758732 17.47863046565811 +-5.5 -0.448686907603536 17.4510339080939 +-5.5 -0.4314128943758575 9.277777777777811 +-5.5 -1.568587105624139 7.796296296296328 +-5.5 -0.4314128943758599 7.796296296296328 +-5.5 -0.449597308799603 6.339841916258322 +-5.5 -1.559229484021698 6.366607106337828 +-5.5 -1.544718007681546 15.13601820152116 +-5.5 -0.443559802607401 15.13112473105344 +-5.5 -1.512008119042142 4.010862630495161 +-5.5 -0.432351799124187 4.049326816056826 +-5.5 -1.000111581384906 21.12464392395787 +-5.5 -0.9998884186150943 1.875356076042124 +2 24 0 158 +5437 +5438 +5439 +5440 +5441 +5442 +5443 +5444 +5445 +5446 +5447 +5448 +5449 +5450 +5451 +5452 +5453 +5454 +5455 +5456 +5457 +5458 +5459 +5460 +5461 +5462 +5463 +5464 +5465 +5466 +5467 +5468 +5469 +5470 +5471 +5472 +5473 +5474 +5475 +5476 +5477 +5478 +5479 +5480 +5481 +5482 +5483 +5484 +5485 +5486 +5487 +5488 +5489 +5490 +5491 +5492 +5493 +5494 +5495 +5496 +5497 +5498 +5499 +5500 +5501 +5502 +5503 +5504 +5505 +5506 +5507 +5508 +5509 +5510 +5511 +5512 +5513 +5514 +5515 +5516 +5517 +5518 +5519 +5520 +5521 +5522 +5523 +5524 +5525 +5526 +5527 +5528 +5529 +5530 +5531 +5532 +5533 +5534 +5535 +5536 +5537 +5538 +5539 +5540 +5541 +5542 +5543 +5544 +5545 +5546 +5547 +5548 +5549 +5550 +5551 +5552 +5553 +5554 +5555 +5556 +5557 +5558 +5559 +5560 +5561 +5562 +5563 +5564 +5565 +5566 +5567 +5568 +5569 +5570 +5571 +5572 +5573 +5574 +5575 +5576 +5577 +5578 +5579 +5580 +5581 +5582 +5583 +5584 +5585 +5586 +5587 +5588 +5589 +5590 +5591 +5592 +5593 +5594 +0.1260391528737067 1.753842355281062 21.5 +-2.527774931418073 0.8207258306601577 21.5 +2.590767764017114 0.684125639141784 21.5 +-1.732308150216403 2.861230772884857 21.5 +1.982966008536436 2.744085975521038 21.5 +-0.8285329072289472 -0.08808761978927215 21.5 +0.1833518176235552 3.659628629799722 21.5 +1.055503955253407 -0.1609244217347601 21.5 +-3.857575757575757 -0.333333333333333 21.5 +3.890655591551989 -0.3632222452258231 21.5 +-3.196882908702238 2.299591235928677 21.5 +3.43188058941867 2.098935092392581 21.5 +-2.108696134303379 -0.557955059326984 21.5 +-1.235001712744983 1.497339957522153 21.5 +-3.949406134933171 1.071555114440563 21.5 +1.594465327849443 1.495202045961456 21.5 +2.363647558892365 -0.6387792440792084 21.5 +-1.04929422189926 4.02032095710725 21.5 +4.050197128440948 0.9430955202537462 21.5 +1.507099725431412 4.033992812104938 21.5 +-0.5528401267869202 2.609367086135473 21.5 +0.1225607260948443 -0.912070764540962 21.5 +-2.766848841591169 3.368590152221255 21.5 +0.8510322488489701 2.621550173657812 21.5 +0.1942323782836227 0.6263831184234425 21.5 +3.026146291912303 3.166561513834628 21.5 +-4.579193379553093 -1.003981329657631 21.5 +-2.223006089578527 1.928462270478183 21.5 +4.604365595146285 -1.033319166542594 21.5 +-1.121150127289897 -1.014769494784579 21.5 +-3.083800337828424 -1.001070834782048 21.5 +2.350443825944525 1.748997238102378 21.5 +-1.710353789836619 0.5719761383783282 21.5 +-2.052913125563722 4.075592478122904 21.5 +-4.502468416343149 0.1264187696197276 21.5 +-0.2130813723629632 4.550780430159239 21.5 +1.466295800628535 -0.9213594177368414 21.5 +-4.137480995927993 2.066002535206672 21.5 +3.287102825626262 -1.079571617990327 21.5 +-2.935608437578853 0.1419661074992855 21.5 +1.773622316052392 0.5915188054568179 21.5 +4.614917405639535 0.2375888322435489 21.5 +0.8886979579795027 4.451538304260969 21.5 +2.348399063240036 3.857919857495912 21.5 +4.224020587727844 1.765385477365563 21.5 +-0.6584095472991829 0.8831994156846155 21.5 +2.914851104423055 0.008353277991467234 21.5 +-3.169849783183885 1.444402451249562 21.5 +-3.543130188472514 3.068192174477395 21.5 +3.312821434960771 1.302594455940582 21.5 +3.755276440894042 2.812054493983783 21.5 +0.9665207141722737 0.9083191933196991 21.5 +-3.779024302286559 -1.180093823367682 21.5 +-1.213044975119613 2.270860846348436 21.5 +0.7529931767103033 -1.368193215795737 21.5 +-3.569211468755329 0.3255580869623218 21.5 +0.9625720859680936 3.395279268049732 21.5 +-2.484955668783469 2.63724724399357 21.5 +-2.327113619953439 -1.250641378926229 21.5 +-0.5554940368602607 3.383450208262089 21.5 +1.451511055744129 2.208044628352591 21.5 +3.641467827644553 0.3096708241890787 21.5 +-1.518398043409719 -0.1725828513025773 21.5 +-4.713566414527522 0.8961639220417593 21.5 +-4.929944869796088 -0.3680983917760492 21.5 +-0.8345713117548066 4.720314224208944 21.5 +-0.47541494208698 -1.247850893904215 21.5 +2.69556781253694 2.456192666658564 21.5 +0.2898700411639212 -0.1849598883855339 21.5 +2.081845784920657 -1.434888589148725 21.5 +-2.250178002300109 0.0828042861347007 21.5 +-0.54034023595542 1.793715299898266 21.5 +3.927210001471683 -1.132965680502547 21.5 +0.1755690499405978 2.894868114152778 21.5 +0.840387438185074 1.79889055520881 21.5 +2.286812656965698 0.07708605712550298 21.5 +4.878481320168193 0.8628491701103091 21.5 +-1.890469845955914 1.288390452236506 21.5 +4.947706553082251 -0.3783641108892031 21.5 +-1.196901919101215 3.326517369993182 21.5 +2.203619068146915 1.169040071533888 21.5 +1.515239718457313 4.721560687104549 21.5 +1.708630124354942 -0.1725134738291971 21.5 +-1.610154193345267 4.505048549695259 21.5 +-2.674124791523752 4.043293271737269 21.5 +1.816681288723518 3.369051354237115 21.5 +-4.184050895868312 2.63914088343386 21.5 +-2.066526247352111 3.439762571356517 21.5 +0.3911196002947163 1.258863310490971 21.5 +-0.4847219167272906 -0.5629562872628178 21.5 +3.058425956564317 3.758291962759999 21.5 +-3.253801355243259 3.7439162957197 21.5 +-4.501623291653553 1.631843226883793 21.5 +0.3281113780138997 4.883960310045504 21.5 +2.174548133239016 4.458615755729555 21.5 +1.412952537564229 2.867602279963657 21.5 +0.737444739970202 -0.7095015416387667 21.5 +-3.187715259429222 0.8113193637556689 21.5 +-0.06839504768747631 2.278374857724 21.5 +0.08002779214363936 -1.505622974848183 21.5 +-0.1186460022692497 1.24710945146029 21.5 +4.247032031081308 2.459888843609787 21.5 +-2.534043557216291 1.485267604948883 21.5 +-1.526870615995637 -1.442212183548988 21.5 +4.709325701947788 1.419918758760295 21.5 +3.580932327991128 3.380543805446877 21.5 +2.848658969233105 -1.331761331555525 21.5 +-4.966684389108661 -1.472440484808014 21.5 +-0.3643411100549401 0.1747243501620372 21.5 +4.977955751877102 -1.486511837898944 21.5 +2.463443227810053 3.173790610222723 21.5 +2.768562448569636 1.237454197105067 21.5 +0.7353148795737022 3.931304783938119 21.5 +-4.38928938646187 -1.533362662242348 21.5 +0.7105892299500003 0.3016837341352565 21.5 +-3.298539607798732 -0.4677161617363108 21.5 +-3.765335465166634 1.74961172730684 21.5 +-1.794541926254763 2.292220637677882 21.5 +-2.699192023454406 -0.5214960523195717 21.5 +-1.595157941452315 3.873448385255023 21.5 +-2.989038799057392 -1.506400121278334 21.5 +4.461906269699015 -1.530559336988817 21.5 +3.220971787716393 0.7151337490092371 21.5 +3.754729935137058 1.527502636488118 21.5 +-2.997954401887347 2.843405201655224 21.5 +-0.4296130299302895 4.068883720886372 21.5 +-4.329641345110929 -0.5518176217029933 21.5 +3.375524380594932 -0.5047337792794964 21.5 +0.437657005118661 2.242998013604654 21.5 +0.2487969384829012 4.257682696514987 21.5 +-0.3315768698282752 5.058885441603438 21.5 +-1.311883991053167 0.9348418190845942 21.5 +1.998404385766517 2.197305116262588 21.5 +-1.065220159053761 0.4204722131736953 21.5 +-2.245798681277974 4.542231010041587 21.5 +-2.741913517555512 1.968172181188321 21.5 +-4.114224820018542 0.5605269330082348 21.5 +0.9928288680220685 4.991287777129894 21.5 +4.381515401217226 -0.5255584653047514 21.5 +-1.702853149480391 -0.8807177867038516 21.5 +-5.060255208949076 0.3038409149794585 21.5 +-5.095164527691569 -0.9689040412483396 21.5 +3.240465916918935 2.680291592859402 21.5 +5.11557477435463 0.3352924850014849 21.5 +-1.075715375031403 2.808347392209176 21.5 +1.446893619118571 -1.54488824453626 21.5 +5.106005580021128 -0.9796390230661474 21.5 +2.925135800301926 1.791714750891345 21.5 +-0.9180204704078317 -1.540966514447556 21.5 +1.238447273633589 0.3072704137877231 21.5 +4.114020879342213 0.131016715800264 21.5 +-4.558059245523006 2.249143856215126 21.5 +-3.750553457688603 2.358098177288913 21.5 +2.796009031163264 4.247791751626893 21.5 +-1.084945230929658 -0.4890236429440962 21.5 +-1.712111167259775 1.803183458108053 21.5 +3.479261025932879 -1.50885972600968 21.5 +2.921404401746673 -0.6863035393136254 21.5 +2 25 0 158 +5595 +5596 +5597 +5598 +5599 +5600 +5601 +5602 +5603 +5604 +5605 +5606 +5607 +5608 +5609 +5610 +5611 +5612 +5613 +5614 +5615 +5616 +5617 +5618 +5619 +5620 +5621 +5622 +5623 +5624 +5625 +5626 +5627 +5628 +5629 +5630 +5631 +5632 +5633 +5634 +5635 +5636 +5637 +5638 +5639 +5640 +5641 +5642 +5643 +5644 +5645 +5646 +5647 +5648 +5649 +5650 +5651 +5652 +5653 +5654 +5655 +5656 +5657 +5658 +5659 +5660 +5661 +5662 +5663 +5664 +5665 +5666 +5667 +5668 +5669 +5670 +5671 +5672 +5673 +5674 +5675 +5676 +5677 +5678 +5679 +5680 +5681 +5682 +5683 +5684 +5685 +5686 +5687 +5688 +5689 +5690 +5691 +5692 +5693 +5694 +5695 +5696 +5697 +5698 +5699 +5700 +5701 +5702 +5703 +5704 +5705 +5706 +5707 +5708 +5709 +5710 +5711 +5712 +5713 +5714 +5715 +5716 +5717 +5718 +5719 +5720 +5721 +5722 +5723 +5724 +5725 +5726 +5727 +5728 +5729 +5730 +5731 +5732 +5733 +5734 +5735 +5736 +5737 +5738 +5739 +5740 +5741 +5742 +5743 +5744 +5745 +5746 +5747 +5748 +5749 +5750 +5751 +5752 +-0.1260391528737063 1.753842355281062 1.5 +2.527774931418074 0.820725830660159 1.5 +-2.590767764017115 0.6841256391417836 1.5 +1.732308150216403 2.861230772884858 1.5 +-1.982966008536436 2.744085975521038 1.5 +0.8285329072289486 -0.08808761978927171 1.5 +-0.1833518176235556 3.659628629799722 1.5 +-1.055503955253406 -0.1609244217347596 1.5 +3.85757575757576 -0.333333333333333 1.5 +-3.89065559155199 -0.3632222452258254 1.5 +3.196882908702237 2.299591235928677 1.5 +-3.431880589418671 2.098935092392581 1.5 +2.108696134303381 -0.5579550593269835 1.5 +1.235001712744984 1.497339957522154 1.5 +3.949406134933171 1.071555114440563 1.5 +-1.594465327849443 1.495202045961456 1.5 +-2.363647558892365 -0.6387792440792088 1.5 +1.049294221899259 4.02032095710725 1.5 +-4.05019712844095 0.9430955202537435 1.5 +-1.507099725431412 4.033992812104938 1.5 +0.5528401267869203 2.609367086135472 1.5 +-0.1225607260948426 -0.912070764540962 1.5 +2.766848841591168 3.368590152221255 1.5 +-0.8510322488489701 2.621550173657811 1.5 +-0.1942323782836216 0.6263831184234416 1.5 +-3.026146291912303 3.166561513834629 1.5 +4.579193379553093 -1.003981329657631 1.5 +2.223006089578526 1.928462270478184 1.5 +-4.604365595146286 -1.033319166542595 1.5 +1.121150127289899 -1.014769494784579 1.5 +3.083800337828426 -1.001070834782047 1.5 +-2.350443825944526 1.748997238102378 1.5 +1.71035378983662 0.5719761383783288 1.5 +2.052913125563722 4.075592478122905 1.5 +4.50246841634315 0.1264187696197281 1.5 +0.213081372362962 4.550780430159239 1.5 +-1.466295800628534 -0.9213594177368418 1.5 +4.137480995927993 2.066002535206673 1.5 +-3.287102825626262 -1.079571617990329 1.5 +2.935608437578855 0.1419661074992862 1.5 +-1.773622316052392 0.5915188054568179 1.5 +-4.614917405639538 0.2375888322435455 1.5 +-0.8886979579795027 4.451538304260969 1.5 +-2.348399063240036 3.857919857495913 1.5 +-4.224020587727844 1.765385477365562 1.5 +0.6584095472991838 0.8831994156846155 1.5 +-2.914851104423056 0.008353277991465458 1.5 +3.169849783183885 1.444402451249562 1.5 +3.543130188472514 3.068192174477395 1.5 +-3.312821434960771 1.302594455940582 1.5 +-3.755276440894042 2.812054493983782 1.5 +-0.9665207141722727 0.9083191933196991 1.5 +3.77902430228656 -1.180093823367681 1.5 +1.213044975119613 2.270860846348437 1.5 +-0.7529931767103022 -1.368193215795737 1.5 +3.56921146875533 0.3255580869623222 1.5 +-0.9625720859680941 3.395279268049732 1.5 +2.484955668783468 2.63724724399357 1.5 +2.32711361995344 -1.250641378926229 1.5 +0.5554940368602603 3.383450208262089 1.5 +-1.45151105574413 2.20804462835259 1.5 +-3.641467827644556 0.3096708241890758 1.5 +1.51839804340972 -0.1725828513025767 1.5 +4.713566414527522 0.8961639220417605 1.5 +4.929944869796089 -0.3680983917760488 1.5 +0.8345713117548065 4.720314224208945 1.5 +0.4754149420869811 -1.247850893904215 1.5 +-2.695567812536941 2.456192666658564 1.5 +-0.2898700411639196 -0.1849598883855339 1.5 +-2.081845784920656 -1.434888589148726 1.5 +2.250178002300111 0.08280428613470137 1.5 +0.5403402359554205 1.793715299898266 1.5 +-3.927210001471684 -1.132965680502548 1.5 +-0.1755690499405977 2.894868114152778 1.5 +-0.8403874381850738 1.79889055520881 1.5 +-2.286812656965698 0.07708605712550276 1.5 +-4.878481320168193 0.8628491701103068 1.5 +1.890469845955915 1.288390452236507 1.5 +-4.947706553082252 -0.3783641108892053 1.5 +1.196901919101214 3.326517369993181 1.5 +-2.203619068146915 1.169040071533888 1.5 +-1.515239718457313 4.721560687104549 1.5 +-1.708630124354941 -0.1725134738291971 1.5 +1.610154193345266 4.505048549695259 1.5 +2.674124791523753 4.043293271737269 1.5 +-1.816681288723518 3.369051354237115 1.5 +4.184050895868312 2.63914088343386 1.5 +2.06652624735211 3.439762571356517 1.5 +-0.3911196002947157 1.25886331049097 1.5 +0.4847219167272919 -0.5629562872628178 1.5 +-3.058425956564317 3.75829196276 1.5 +3.253801355243259 3.743916295719699 1.5 +4.501623291653553 1.631843226883793 1.5 +-0.3281113780138999 4.883960310045504 1.5 +-2.174548133239016 4.458615755729555 1.5 +-1.412952537564229 2.867602279963657 1.5 +-0.7374447399702007 -0.7095015416387671 1.5 +3.187715259429224 0.8113193637556702 1.5 +0.06839504768747659 2.278374857724 1.5 +-0.08002779214363859 -1.505622974848183 1.5 +0.1186460022692503 1.24710945146029 1.5 +-4.247032031081309 2.459888843609786 1.5 +2.534043557216292 1.485267604948885 1.5 +1.526870615995638 -1.442212183548987 1.5 +-4.709325701947788 1.419918758760293 1.5 +-3.580932327991129 3.380543805446877 1.5 +-2.848658969233105 -1.331761331555525 1.5 +4.966684389108661 -1.472440484808013 1.5 +0.3643411100549412 0.1747243501620366 1.5 +-4.977955751877102 -1.486511837898945 1.5 +-2.463443227810053 3.173790610222723 1.5 +-2.768562448569637 1.237454197105066 1.5 +-0.7353148795737019 3.931304783938119 1.5 +4.389289386461869 -1.533362662242346 1.5 +-0.7105892299499978 0.3016837341352561 1.5 +3.298539607798734 -0.4677161617363108 1.5 +3.765335465166634 1.74961172730684 1.5 +1.794541926254763 2.292220637677883 1.5 +2.699192023454407 -0.5214960523195717 1.5 +1.595157941452314 3.873448385255022 1.5 +2.989038799057392 -1.506400121278334 1.5 +-4.461906269699016 -1.530559336988818 1.5 +-3.220971787716396 0.7151337490092344 1.5 +-3.754729935137059 1.527502636488117 1.5 +2.997954401887347 2.843405201655224 1.5 +0.4296130299302883 4.068883720886372 1.5 +4.32964134511093 -0.5518176217029924 1.5 +-3.375524380594933 -0.5047337792794977 1.5 +-0.4376570051186606 2.242998013604654 1.5 +-0.2487969384829016 4.257682696514987 1.5 +0.3315768698282758 5.058885441603438 1.5 +1.311883991053168 0.9348418190845947 1.5 +-1.998404385766517 2.197305116262588 1.5 +1.065220159053762 0.4204722131736962 1.5 +2.245798681277975 4.542231010041587 1.5 +2.741913517555511 1.968172181188323 1.5 +4.114224820018543 0.5605269330082359 1.5 +-0.9928288680220686 4.991287777129894 1.5 +-4.381515401217227 -0.5255584653047563 1.5 +1.702853149480393 -0.8807177867038511 1.5 +5.060255208949076 0.3038409149794599 1.5 +5.095164527691569 -0.9689040412483383 1.5 +-3.240465916918935 2.680291592859402 1.5 +-5.115574774354631 0.3352924850014831 1.5 +1.075715375031403 2.808347392209175 1.5 +-1.446893619118571 -1.544888244536261 1.5 +-5.106005580021128 -0.9796390230661487 1.5 +-2.925135800301927 1.791714750891344 1.5 +0.9180204704078325 -1.540966514447556 1.5 +-1.238447273633588 0.3072704137877236 1.5 +-4.114020879342218 0.13101671580026 1.5 +4.558059245523006 2.249143856215127 1.5 +3.750553457688603 2.358098177288913 1.5 +-2.796009031163265 4.247791751626893 1.5 +1.08494523092966 -0.4890236429440966 1.5 +1.712111167259775 1.803183458108055 1.5 +-3.479261025932879 -1.508859726009681 1.5 +-2.921404401746674 -0.6863035393136263 1.5 +3 1 0 1462 +5753 +5754 +5755 +5756 +5757 +5758 +5759 +5760 +5761 +5762 +5763 +5764 +5765 +5766 +5767 +5768 +5769 +5770 +5771 +5772 +5773 +5774 +5775 +5776 +5777 +5778 +5779 +5780 +5781 +5782 +5783 +5784 +5785 +5786 +5787 +5788 +5789 +5790 +5791 +5792 +5793 +5794 +5795 +5796 +5797 +5798 +5799 +5800 +5801 +5802 +5803 +5804 +5805 +5806 +5807 +5808 +5809 +5810 +5811 +5812 +5813 +5814 +5815 +5816 +5817 +5818 +5819 +5820 +5821 +5822 +5823 +5824 +5825 +5826 +5827 +5828 +5829 +5830 +5831 +5832 +5833 +5834 +5835 +5836 +5837 +5838 +5839 +5840 +5841 +5842 +5843 +5844 +5845 +5846 +5847 +5848 +5849 +5850 +5851 +5852 +5853 +5854 +5855 +5856 +5857 +5858 +5859 +5860 +5861 +5862 +5863 +5864 +5865 +5866 +5867 +5868 +5869 +5870 +5871 +5872 +5873 +5874 +5875 +5876 +5877 +5878 +5879 +5880 +5881 +5882 +5883 +5884 +5885 +5886 +5887 +5888 +5889 +5890 +5891 +5892 +5893 +5894 +5895 +5896 +5897 +5898 +5899 +5900 +5901 +5902 +5903 +5904 +5905 +5906 +5907 +5908 +5909 +5910 +5911 +5912 +5913 +5914 +5915 +5916 +5917 +5918 +5919 +5920 +5921 +5922 +5923 +5924 +5925 +5926 +5927 +5928 +5929 +5930 +5931 +5932 +5933 +5934 +5935 +5936 +5937 +5938 +5939 +5940 +5941 +5942 +5943 +5944 +5945 +5946 +5947 +5948 +5949 +5950 +5951 +5952 +5953 +5954 +5955 +5956 +5957 +5958 +5959 +5960 +5961 +5962 +5963 +5964 +5965 +5966 +5967 +5968 +5969 +5970 +5971 +5972 +5973 +5974 +5975 +5976 +5977 +5978 +5979 +5980 +5981 +5982 +5983 +5984 +5985 +5986 +5987 +5988 +5989 +5990 +5991 +5992 +5993 +5994 +5995 +5996 +5997 +5998 +5999 +6000 +6001 +6002 +6003 +6004 +6005 +6006 +6007 +6008 +6009 +6010 +6011 +6012 +6013 +6014 +6015 +6016 +6017 +6018 +6019 +6020 +6021 +6022 +6023 +6024 +6025 +6026 +6027 +6028 +6029 +6030 +6031 +6032 +6033 +6034 +6035 +6036 +6037 +6038 +6039 +6040 +6041 +6042 +6043 +6044 +6045 +6046 +6047 +6048 +6049 +6050 +6051 +6052 +6053 +6054 +6055 +6056 +6057 +6058 +6059 +6060 +6061 +6062 +6063 +6064 +6065 +6066 +6067 +6068 +6069 +6070 +6071 +6072 +6073 +6074 +6075 +6076 +6077 +6078 +6079 +6080 +6081 +6082 +6083 +6084 +6085 +6086 +6087 +6088 +6089 +6090 +6091 +6092 +6093 +6094 +6095 +6096 +6097 +6098 +6099 +6100 +6101 +6102 +6103 +6104 +6105 +6106 +6107 +6108 +6109 +6110 +6111 +6112 +6113 +6114 +6115 +6116 +6117 +6118 +6119 +6120 +6121 +6122 +6123 +6124 +6125 +6126 +6127 +6128 +6129 +6130 +6131 +6132 +6133 +6134 +6135 +6136 +6137 +6138 +6139 +6140 +6141 +6142 +6143 +6144 +6145 +6146 +6147 +6148 +6149 +6150 +6151 +6152 +6153 +6154 +6155 +6156 +6157 +6158 +6159 +6160 +6161 +6162 +6163 +6164 +6165 +6166 +6167 +6168 +6169 +6170 +6171 +6172 +6173 +6174 +6175 +6176 +6177 +6178 +6179 +6180 +6181 +6182 +6183 +6184 +6185 +6186 +6187 +6188 +6189 +6190 +6191 +6192 +6193 +6194 +6195 +6196 +6197 +6198 +6199 +6200 +6201 +6202 +6203 +6204 +6205 +6206 +6207 +6208 +6209 +6210 +6211 +6212 +6213 +6214 +6215 +6216 +6217 +6218 +6219 +6220 +6221 +6222 +6223 +6224 +6225 +6226 +6227 +6228 +6229 +6230 +6231 +6232 +6233 +6234 +6235 +6236 +6237 +6238 +6239 +6240 +6241 +6242 +6243 +6244 +6245 +6246 +6247 +6248 +6249 +6250 +6251 +6252 +6253 +6254 +6255 +6256 +6257 +6258 +6259 +6260 +6261 +6262 +6263 +6264 +6265 +6266 +6267 +6268 +6269 +6270 +6271 +6272 +6273 +6274 +6275 +6276 +6277 +6278 +6279 +6280 +6281 +6282 +6283 +6284 +6285 +6286 +6287 +6288 +6289 +6290 +6291 +6292 +6293 +6294 +6295 +6296 +6297 +6298 +6299 +6300 +6301 +6302 +6303 +6304 +6305 +6306 +6307 +6308 +6309 +6310 +6311 +6312 +6313 +6314 +6315 +6316 +6317 +6318 +6319 +6320 +6321 +6322 +6323 +6324 +6325 +6326 +6327 +6328 +6329 +6330 +6331 +6332 +6333 +6334 +6335 +6336 +6337 +6338 +6339 +6340 +6341 +6342 +6343 +6344 +6345 +6346 +6347 +6348 +6349 +6350 +6351 +6352 +6353 +6354 +6355 +6356 +6357 +6358 +6359 +6360 +6361 +6362 +6363 +6364 +6365 +6366 +6367 +6368 +6369 +6370 +6371 +6372 +6373 +6374 +6375 +6376 +6377 +6378 +6379 +6380 +6381 +6382 +6383 +6384 +6385 +6386 +6387 +6388 +6389 +6390 +6391 +6392 +6393 +6394 +6395 +6396 +6397 +6398 +6399 +6400 +6401 +6402 +6403 +6404 +6405 +6406 +6407 +6408 +6409 +6410 +6411 +6412 +6413 +6414 +6415 +6416 +6417 +6418 +6419 +6420 +6421 +6422 +6423 +6424 +6425 +6426 +6427 +6428 +6429 +6430 +6431 +6432 +6433 +6434 +6435 +6436 +6437 +6438 +6439 +6440 +6441 +6442 +6443 +6444 +6445 +6446 +6447 +6448 +6449 +6450 +6451 +6452 +6453 +6454 +6455 +6456 +6457 +6458 +6459 +6460 +6461 +6462 +6463 +6464 +6465 +6466 +6467 +6468 +6469 +6470 +6471 +6472 +6473 +6474 +6475 +6476 +6477 +6478 +6479 +6480 +6481 +6482 +6483 +6484 +6485 +6486 +6487 +6488 +6489 +6490 +6491 +6492 +6493 +6494 +6495 +6496 +6497 +6498 +6499 +6500 +6501 +6502 +6503 +6504 +6505 +6506 +6507 +6508 +6509 +6510 +6511 +6512 +6513 +6514 +6515 +6516 +6517 +6518 +6519 +6520 +6521 +6522 +6523 +6524 +6525 +6526 +6527 +6528 +6529 +6530 +6531 +6532 +6533 +6534 +6535 +6536 +6537 +6538 +6539 +6540 +6541 +6542 +6543 +6544 +6545 +6546 +6547 +6548 +6549 +6550 +6551 +6552 +6553 +6554 +6555 +6556 +6557 +6558 +6559 +6560 +6561 +6562 +6563 +6564 +6565 +6566 +6567 +6568 +6569 +6570 +6571 +6572 +6573 +6574 +6575 +6576 +6577 +6578 +6579 +6580 +6581 +6582 +6583 +6584 +6585 +6586 +6587 +6588 +6589 +6590 +6591 +6592 +6593 +6594 +6595 +6596 +6597 +6598 +6599 +6600 +6601 +6602 +6603 +6604 +6605 +6606 +6607 +6608 +6609 +6610 +6611 +6612 +6613 +6614 +6615 +6616 +6617 +6618 +6619 +6620 +6621 +6622 +6623 +6624 +6625 +6626 +6627 +6628 +6629 +6630 +6631 +6632 +6633 +6634 +6635 +6636 +6637 +6638 +6639 +6640 +6641 +6642 +6643 +6644 +6645 +6646 +6647 +6648 +6649 +6650 +6651 +6652 +6653 +6654 +6655 +6656 +6657 +6658 +6659 +6660 +6661 +6662 +6663 +6664 +6665 +6666 +6667 +6668 +6669 +6670 +6671 +6672 +6673 +6674 +6675 +6676 +6677 +6678 +6679 +6680 +6681 +6682 +6683 +6684 +6685 +6686 +6687 +6688 +6689 +6690 +6691 +6692 +6693 +6694 +6695 +6696 +6697 +6698 +6699 +6700 +6701 +6702 +6703 +6704 +6705 +6706 +6707 +6708 +6709 +6710 +6711 +6712 +6713 +6714 +6715 +6716 +6717 +6718 +6719 +6720 +6721 +6722 +6723 +6724 +6725 +6726 +6727 +6728 +6729 +6730 +6731 +6732 +6733 +6734 +6735 +6736 +6737 +6738 +6739 +6740 +6741 +6742 +6743 +6744 +6745 +6746 +6747 +6748 +6749 +6750 +6751 +6752 +6753 +6754 +6755 +6756 +6757 +6758 +6759 +6760 +6761 +6762 +6763 +6764 +6765 +6766 +6767 +6768 +6769 +6770 +6771 +6772 +6773 +6774 +6775 +6776 +6777 +6778 +6779 +6780 +6781 +6782 +6783 +6784 +6785 +6786 +6787 +6788 +6789 +6790 +6791 +6792 +6793 +6794 +6795 +6796 +6797 +6798 +6799 +6800 +6801 +6802 +6803 +6804 +6805 +6806 +6807 +6808 +6809 +6810 +6811 +6812 +6813 +6814 +6815 +6816 +6817 +6818 +6819 +6820 +6821 +6822 +6823 +6824 +6825 +6826 +6827 +6828 +6829 +6830 +6831 +6832 +6833 +6834 +6835 +6836 +6837 +6838 +6839 +6840 +6841 +6842 +6843 +6844 +6845 +6846 +6847 +6848 +6849 +6850 +6851 +6852 +6853 +6854 +6855 +6856 +6857 +6858 +6859 +6860 +6861 +6862 +6863 +6864 +6865 +6866 +6867 +6868 +6869 +6870 +6871 +6872 +6873 +6874 +6875 +6876 +6877 +6878 +6879 +6880 +6881 +6882 +6883 +6884 +6885 +6886 +6887 +6888 +6889 +6890 +6891 +6892 +6893 +6894 +6895 +6896 +6897 +6898 +6899 +6900 +6901 +6902 +6903 +6904 +6905 +6906 +6907 +6908 +6909 +6910 +6911 +6912 +6913 +6914 +6915 +6916 +6917 +6918 +6919 +6920 +6921 +6922 +6923 +6924 +6925 +6926 +6927 +6928 +6929 +6930 +6931 +6932 +6933 +6934 +6935 +6936 +6937 +6938 +6939 +6940 +6941 +6942 +6943 +6944 +6945 +6946 +6947 +6948 +6949 +6950 +6951 +6952 +6953 +6954 +6955 +6956 +6957 +6958 +6959 +6960 +6961 +6962 +6963 +6964 +6965 +6966 +6967 +6968 +6969 +6970 +6971 +6972 +6973 +6974 +6975 +6976 +6977 +6978 +6979 +6980 +6981 +6982 +6983 +6984 +6985 +6986 +6987 +6988 +6989 +6990 +6991 +6992 +6993 +6994 +6995 +6996 +6997 +6998 +6999 +7000 +7001 +7002 +7003 +7004 +7005 +7006 +7007 +7008 +7009 +7010 +7011 +7012 +7013 +7014 +7015 +7016 +7017 +7018 +7019 +7020 +7021 +7022 +7023 +7024 +7025 +7026 +7027 +7028 +7029 +7030 +7031 +7032 +7033 +7034 +7035 +7036 +7037 +7038 +7039 +7040 +7041 +7042 +7043 +7044 +7045 +7046 +7047 +7048 +7049 +7050 +7051 +7052 +7053 +7054 +7055 +7056 +7057 +7058 +7059 +7060 +7061 +7062 +7063 +7064 +7065 +7066 +7067 +7068 +7069 +7070 +7071 +7072 +7073 +7074 +7075 +7076 +7077 +7078 +7079 +7080 +7081 +7082 +7083 +7084 +7085 +7086 +7087 +7088 +7089 +7090 +7091 +7092 +7093 +7094 +7095 +7096 +7097 +7098 +7099 +7100 +7101 +7102 +7103 +7104 +7105 +7106 +7107 +7108 +7109 +7110 +7111 +7112 +7113 +7114 +7115 +7116 +7117 +7118 +7119 +7120 +7121 +7122 +7123 +7124 +7125 +7126 +7127 +7128 +7129 +7130 +7131 +7132 +7133 +7134 +7135 +7136 +7137 +7138 +7139 +7140 +7141 +7142 +7143 +7144 +7145 +7146 +7147 +7148 +7149 +7150 +7151 +7152 +7153 +7154 +7155 +7156 +7157 +7158 +7159 +7160 +7161 +7162 +7163 +7164 +7165 +7166 +7167 +7168 +7169 +7170 +7171 +7172 +7173 +7174 +7175 +7176 +7177 +7178 +7179 +7180 +7181 +7182 +7183 +7184 +7185 +7186 +7187 +7188 +7189 +7190 +7191 +7192 +7193 +7194 +7195 +7196 +7197 +7198 +7199 +7200 +7201 +7202 +7203 +7204 +7205 +7206 +7207 +7208 +7209 +7210 +7211 +7212 +7213 +7214 +6.450112521647904 -0.8191671376809075 21.9621639928489 +-6.43815810435718 -0.876581629393808 21.97116528474401 +-3.886391438936729 5.193658694402391 5.800279472338873 +-3.040672020982357 -3.001148692073245 13.03042239710985 +5.712773867901124 3.022708317381587 15.49957417410569 +2.104282496431766 6.154619961048901 20.13351157100954 +1.013932909352117 6.394794770970917 9.405700051526866 +2.984084751210705 -3.002047912970955 10.63813863221043 +-1.414662628664753 -2.949827497039711 21.94378450105091 +1.475222734377208 -3.09055538538219 0.9950790465650046 +2.520807568841546 -3.008674369625401 4.453506529760412 +2.342037391400865 -3.008387862555565 18.49832604313007 +1.363743484575836 6.336614437099517 10.55798279873313 +-2.060604686444727 6.070345658187982 1.0258385942629 +-6.49931051236818 -0.9999999999999987 1.5396704450279 +6.499310512368181 -1.000000000000001 1.539670445027894 +1.304677979773728 -3.006117489361405 12.87799830438549 +-4.579801094907528 4.605759949720254 8.483547777579581 +2.80193597368607 5.843180130992197 16.20722631275213 +6.367985901501084 1.223845637673664 11.55894535650344 +3.700752187681754 5.3182575902063 16.26637883341694 +-6.272954087707467 1.656397051260865 2.145851731918767 +6.272954041141483 1.65639703869493 20.85414826767337 +-5.532159531104931 3.459112472991692 15.72567203408221 +2.317013048236773 6.068369881761518 4.556328362518462 +5.206380265625256 3.890227066963643 3.280538771840243 +-1.879243581306037 6.191503448897147 20.58128470135711 +6.035854711852272 2.36765976023942 20.04232936335633 +6.490140587652452 -0.7994328376639189 20.93531755401746 +6.414512846720476 1.187576424089115 3.677556984415083 +6.501800657102953 0.1699888750914769 3.416450408614166 +-1.019469481144668 6.427900216298458 13.594812167058 +6.483005051723532 0.5512726931610199 15.59090712338393 +-4.333639437120953 4.812933988257364 14.93231070850146 +-4.404852153207893 4.75478616274127 13.88667199572199 +-2.743350267936422 -2.998926632029939 14.04310414288416 +6.324343969362852 1.464260851634961 2.679013519746396 +2.467513074342905 6.025267509125646 17.16079175061354 +2.575182070262596 5.959561231332318 18.20610751068149 +-3.706599250831166 5.375001436060602 14.33148884137831 +-6.495609930777702 -1.223227546425204 21.00594795300706 +-6.160996920999338 2.095593670589548 4.725132796954608 +-1.239795204652375 6.357688399684847 1.615799373781437 +6.498766110348254 -1.330892951750396 3.762268301483751 +-5.395497862062041 -2.980252067266718 21.93113318697786 +-6.322006917893623 -2.516006032963495 21.99676540497395 +-6.22853715219849 1.850004342962478 11.32777210625049 +2.957197370750897 5.782643470802153 20.60554573231476 +6.163192347848653 2.005465662496533 17.13136833309697 +-0.6034796031682413 -2.986296171648247 15.3483982150329 +6.31655965634115 -2.509050589114032 1.035453999218007 +5.38036810737408 -2.997392527190083 1.05120396257419 +6.393879728958695 1.076249240075908 1.725479933864378 +-6.438715005300828 0.8864632299041544 19.72574927010209 +-0.4706158637436922 -3.017311465979231 16.82253974721819 +2.697760897894483 -3.023960340911696 13.53731565749798 +6.480568895760014 0.2498287899633837 21.98765310723604 +-5.824249360189002 2.855927478963613 21.69112630729394 +6.362340621583648 1.346386784208164 14.93778639825327 +-2.506896705767158 -2.976039380797862 12.14569088593153 +-6.504878119243088 -0.6691163617254368 3.762261187760474 +-1.965720463316328 6.18026865450208 4.691643769147355 +-0.2258719028412107 6.473445728538819 14.74155026925625 +-0.2235380134988492 -3.033650087893869 10.42874037312364 +-1.124367246799803 -2.907322184650865 10.10848002468905 +-0.8992776740317191 -3.011894180511875 8.757871055868328 +5.663583041924769 3.230858572997436 7.881794248619538 +-6.353111138322113 1.291924881163978 21.75853675686933 +3.750768264066934 5.305097979267726 9.800659188457621 +-6.502714311509643 -0.08987112194122075 20.4032258064516 +6.22902355478768 1.771706271555613 4.616477419598062 +1.528975469679885 6.276446535580962 19.26734207854728 +-6.499889464849277 0.1242864241751545 10.75925925925929 +2.504556656463749 6.011015383323051 19.21474204946342 +6.1865164375606 1.918113589881099 21.89892304426423 +6.241880645150663 1.853593379260174 5.9978008484874 +4.3860530481765 4.769883211441774 6.694365662232758 +-6.330927574452719 1.259299791543544 1.123908339441367 +1.099860951573533 6.395469011709603 20.20180980643772 +5.819251352984985 2.839394363378553 13.76383307022426 +6.500835576767835 -0.07404499816203891 6.30865193956113 +3.375997636146458 5.532069405063154 17.22643989212904 +1.917832731476254 6.137173993600627 1.027499300706654 +5.388446462595636 -2.992221944962521 4.092592592592602 +2.181269621129746 -3.000611350309898 9.13899393779411 +3.18690898368016 -2.989490682510569 9.438671895550009 +4.356200033841942 4.837215346842728 8.067777095540528 +-0.8059637323254532 -2.996474946922759 6.580325280675921 +-4.971112245992062 4.211703543512858 9.358547145319635 +-4.217292372584663 4.931097754594215 9.564547632923867 +-0.0268287430929325 6.498489080586792 2.36858200285812 +-2.518359796730485 -3.007547817187073 11.08720434394942 +5.386065566212026 -2.989802829133673 7.055555555555578 +5.340188263068241 3.734544449733396 18.61936169887205 +4.71348971672151 4.446818115105765 19.08358516880564 +4.386947779237213 -2.996354862547276 12.74415638738659 +-2.674858175671357 5.927290222515225 5.431302528005505 +5.566883291745138 3.313529075904876 1.026918126448744 +0.7046628731242374 -2.952302136372633 21.93805856651719 +-0.7046628731242306 -2.952302136372634 1.06194143348281 +-1.381078515896153 -2.961778992094908 17.32096231284904 +-6.500620352746294 0.2969028131006295 2.316351235960527 +6.500620352793457 0.2969028159366505 20.68364875772335 +-5.755974460726234 3.018268224448704 18.2450137769515 +-6.153448632567102 2.065222276242586 18.2804386172246 +2.984460902118256 -3.026164497278383 12.54816364781043 +-2.996168564349589 5.771860092736159 20.56153052719403 +-6.386889902454863 1.128518114923085 10.27091749423633 +-6.139264984502875 2.134577777372962 10.02555026930106 +2.157016653375825 6.149682620380547 21.1874796734753 +-6.485518841112031 0.6101663565640354 7.359042668678391 +-1.14440041147269 6.41536241584246 19.27797684725704 +4.231122748256299 -3.002724845060621 9.531991458154494 +-6.28904411990016 1.583030683598709 3.626995024851151 +-6.039980139817982 2.358086758449076 2.944112411204609 +6.331056167157266 1.443983982205505 18.02516981229979 +6.452614303929609 0.8595924938254396 7.165986421948617 +-6.38566415662754 1.24129968848574 12.74550989010502 +-1.529968396518115 -3.027200877114659 14.48001824293091 +-1.638023869442987 -3.00183459923847 15.52350593409257 +2.247540012798957 6.083823038538266 10.04595143565342 +3.353978736835994 5.555767622151014 5.297913136696918 +6.258482944691567 1.792558747216686 0.9609202122585708 +1.076036258219117 -2.988723601019802 3.963947975039102 +3.000757524816504 -3.021110590568521 19.32082398820894 +2.314426324180337 -3.002521739897254 20.14040908749063 +6.457806377066712 0.420947406407117 18.02614637546028 +-6.502073047051756 0.06809661380114221 4.822580645161283 +-6.49230063728371 0.4046959524345246 3.802079794700326 +0.06711046878887404 6.465304348492246 1.028401823180598 +-5.220234174187404 3.812736576049185 8.417083333154615 +5.782655513930924 2.906619317387997 21.79510046434542 +3.958363916309451 -2.994557599163545 11.01538854296162 +2.579475773120683 5.953217561478564 2.381858332853134 +6.458548616045688 0.7970027205942107 19.75344134189449 +5.772703920072287 3.037145142912494 3.387734110971862 +5.994129999473239 2.440522022957039 2.56976481854638 +1.954873095560684 -3.023975715046102 5.347157983926953 +-3.301268796477386 -3.008523526866394 8.977334866529032 +-6.172354635699817 1.998331515170998 13.44203753288686 +-6.37712010426788 1.178368528872339 5.837481782162063 +6.500305926824129 0.2715631317781488 13.94836296347104 +0.7931204071409591 -3.013510346484815 8.782504870308435 +-6.262521292132192 1.750552152156816 20.81050850532602 +-6.469233359864223 0.3879811104151212 12.02984626871231 +-5.314433285652083 3.755210294121951 4.422006166316403 +-5.433218847399478 -2.996943288241415 1.11290322580645 +-4.359390732055423 -2.928025669596579 1.060632735740106 +-6.50120803589653 0.0546269748153164 15.20967741935481 +-3.905924203551969 5.228791762274957 6.838975255170991 +6.46697950912649 0.1792909327896358 11.50000000000002 +-2.237242957634515 6.079893576231529 2.94828630341658 +-1.465007347448779 -2.983964750254458 11.29785002941841 +2.431098693541184 -3.004178046995734 3.413414800959969 +6.424067168635189 0.8574836398042153 12.54080334791881 +-5.636040450193843 3.27004773573868 7.517951839390132 +-3.613402416930643 5.386856701919593 15.45030121255462 +-5.989831739900672 2.521830335740753 17.33289283305183 +6.487140469357988 0.5986369770800262 10.4742669123742 +0.1112063885292026 6.47893060942122 9.927135286570818 +5.263508470380133 3.900505353058855 15.72026005396935 +-5.731445527833483 3.087954323138074 9.762010301561746 +1.633829530425184 -2.976051339737495 2.850225482634182 +2.88204004737781 5.773742379933197 21.92017317725758 +1.600348645561529 6.249709407696654 2.272427784239382 +1.700031361702986 6.283212473792802 5.358395724568088 +6.4642279785004 0.2282046546761954 1.041326672003498 +-6.44690321308385 0.3680139616689569 6.308207489146697 +-0.01067514030494554 6.501680969772797 18.65492887841165 +6.207133138993986 -2.664130190390237 21.9485330721351 +-4.051938018183781 5.106101798124783 16.34831046651438 +6.499680963896491 -0.6977060546842981 19.88181800456812 +5.991064528671895 2.577255053826783 12.78324228083923 +6.212717962698474 1.917877105896007 13.53873520308072 +0.4972223920837192 6.463130355826117 3.567200890457795 +1.423846390164047 -3.007487131636682 19.59473994778505 +-1.905860740127544 6.177534856256398 21.95814028298121 +-6.435864811160442 0.1906713290991505 21.97630033045475 +-3.452458403919632 5.491443861215796 2.334091130666444 +2.311122250697879 -2.958331259453011 21.96549491264113 +-2.311122250697877 -2.958331259453011 1.034505087358867 +-6.38983083309193 1.073775113464816 13.87858371280584 +2.796309281709245 -3.01546762554312 8.292618433590949 +-3.268078085757824 5.59452150148855 16.91649127920581 +-6.378691574804016 1.34292813408608 8.529300045215159 +-6.449692202724032 0.7193978036882546 9.336229183473288 +-6.486535817492457 0.3081123881124634 8.36768348110493 +-4.801041629758127 -2.957845515622847 12.67027372954958 +5.915050667287947 2.673721527192666 7.025625938084571 +-2.849105075450155 5.831359634360347 21.61225285422587 +-3.124711554629746 5.71630529515967 7.371463521146056 +-5.824679421220767 2.84708872021253 6.568427372308358 +-0.7011651437458792 6.425589135054033 21.97811414658816 +5.429178136663867 -2.999230000899276 14.46296296296297 +-0.3829917445841278 -3.004897317757247 14.27205639659941 +6.489195543476852 -1.593739398728271 6.721960301701327 +4.189374737690537 -2.9568429124105 21.97367686492355 +5.223740015805357 -2.984272701914738 21.98319112536415 +3.610062940698853 -3.002018175297426 14.38239238712249 +-0.6180730616382567 -3.000447973008444 18.03680252169559 +0.6423045544704661 -3.010946721076736 16.46661688824576 +0.2599914171450219 -2.996367633393163 20.98322947633563 +-0.2599914171450145 -2.996367633393164 2.016770523664371 +5.861533068419194 2.835548005737355 18.62081118885047 +-0.9475446672446092 6.450720656168642 9.306157455049812 +3.505588309850903 -2.986268745873822 4.069034073959115 +3.412502907821975 -2.989213463527303 3.013130674469463 +0.6843585059201865 -3.001145783572381 13.72712233883435 +4.27747745310638 4.940704363508646 15.47644486004063 +-4.998878166433 4.134787160676241 5.365672011547865 +5.381481113948227 3.667272019493672 21.19121188669964 +4.75881449187685 4.413378634616849 20.78615408293724 +-4.744264640417161 4.386668978184183 15.80872119288338 +0.3626440923205229 -3.011420605026593 19.64064934877238 +-1.775843385354137 -3.015457161166955 8.188732431226301 +5.164480556911066 -2.999640579118133 18.60604580966836 +6.491010728577098 0.2777493952264815 2.383112192567934 +-0.2163282859848971 6.512155662911145 4.442478528332045 +5.809538217327314 2.858528627885062 5.978011621720158 +5.077503186224332 4.061785689966195 7.579374578763324 +-0.3550581397033656 -2.969827757992906 21.92746617769217 +0.3550581397033692 -2.969827757992907 1.072533822307843 +-3.131568629864001 5.667776503929217 6.318563042258384 +-2.235089306871118 6.070121357546867 6.692309135864151 +-2.138885518595083 -2.983661215033532 9.196131391047263 +-5.81753565385487 2.881623526422901 4.110962061248578 +6.501641968885288 -0.08041511521978034 16.69354838709675 +3.473752722218302 5.506880689068333 8.699300491731206 +4.812470858818953 4.356483657466783 2.415781876958971 +0.6995349034253238 -3.001128476423862 9.935353757692713 +-5.361111832626301 3.637577099233817 19.50955474744481 +-6.346687153875672 1.458205410690051 6.753812333191648 +-4.587835537603049 4.613617445772132 6.326833917287318 +-0.9176585400362507 6.406795385809502 20.28239130457417 +6.505733005982616 -0.5195010122238647 15.56235366172976 +6.499829847743362 -0.3758165936988496 7.370852222752294 +-2.892916942495344 -3.012674440219606 19.14126220514435 +5.445513051915857 3.548516352672751 4.241842309090212 +5.043897604156592 -2.990246053603183 8.84409913823459 +-5.463032207049104 -2.997502833411129 20.38888888888889 +2.892826404708761 5.841663672477392 15.16253860865128 +4.497626841105856 -2.976629270155895 4.65723669423425 +-6.471588513739134 -2.034365413820601 1.046009778183409 +-3.305356214303037 -3.012396817958655 10.02655103359874 +1.613529431692436 6.326046320746872 18.24226407941068 +3.445157348743324 5.482239548045618 1.057363659566302 +0.1500309922597899 -3.011383121145097 2.9880632068957 +0.769941831592314 -3.019957028298284 2.153934884777169 +-6.488069955185106 0.2443521270667012 13.07473779309291 +-2.017599198942835 6.180932610844746 12.75849702543197 +-2.44237437338245 6.010906743960811 13.74021081428214 +-0.111212082140818 6.48219379881975 13.07284043909329 +2.566585723141612 5.962780375484573 5.889853706036862 +-2.428940574794486 -2.985258587033344 17.46643132057997 +-5.386773177316108 3.558264855903754 12.00604242711389 +-2.433990700193534 6.011259386056228 19.73301051874562 +4.500846910287341 4.658272133820122 21.93025142492588 +5.833150734042594 2.887727160057393 16.61097202798098 +-0.3657763399417837 6.459951638248776 16.86282059801178 +-0.4205803563853542 6.453907821759259 15.79387600148176 +-6.149387267679612 2.050675788784511 19.34391291926219 +6.482976329293841 -1.617301436183583 14.17885834842607 +-5.223056932748815 3.864763045459527 2.041179744083055 +-4.841036272728653 4.277541333448311 1.086179839629445 +-6.500241365625319 0.3969657298294944 16.27891747389624 +-3.327635654100169 -3.01635605139226 15.86564574801297 +-4.354905494208374 -3.004286768036118 16.09025073315827 +6.502092131144246 -0.09229187225048271 18.95050469964278 +5.449446625029464 3.538947458805947 11.37188677564335 +6.493698005445817 -0.3415121897378724 4.34217071069713 +0.3675069326655115 6.485467523015659 6.136817818127791 +-5.00562011002724 4.124763266715474 14.48948359859463 +1.684680977238243 -3.027170956999474 11.8784964618525 +1.709496322708985 -2.987582819896277 13.8247867789147 +-1.556337189932462 -3.010850323767334 5.819287185116506 +-6.060426111873502 2.26137748538126 5.744712177714566 +-2.775938962596702 -3.015204351867393 4.006238013635701 +0.7690588548559324 6.439181069067308 7.873633199258663 +5.087618055574453 4.007813923511256 6.532397229281114 +-3.800489583255769 -3.013867255513135 19.63329275569859 +4.105609003852252 -3.015938780871628 18.71825785840945 +4.040032001725912 -2.991209309525359 17.65277012356038 +6.072163087308954 2.295537388609911 10.41679002890281 +6.310357307859426 1.434237821343131 9.844483581093098 +5.543982788987115 3.424071388934409 14.62695491334764 +1.392616504976737 6.302852500288516 21.94178294461272 +3.71008626080314 5.313065978771152 20.04424474749352 +-6.48885815420771 -1.59760616989269 14.12486363677093 +4.581030670890822 4.635886920551647 9.681915675732899 +5.946766707873652 2.591284649737332 8.684257509655932 +6.305673040043899 1.625763050649089 8.822929914548444 +6.464127286477349 0.7429236760661725 8.233080955100936 +-6.498505654021873 -0.1006996402863634 17.3935738646128 +6.071375527615739 2.28024056684335 11.75697744357643 +-5.105624791117034 4.048735357014594 7.048533914458001 +-6.498646363134292 0.1881047313535077 1.11290322580645 +4.547296323971651 4.623476119970601 14.49898510040338 +-3.757491098259941 5.309532494509783 3.580184807593319 +6.500301114466257 -0.2424320892821074 9.848280965837494 +-6.514931902835851 -0.4531377903053442 7.462264952852875 +2.615008376543879 5.951271105884777 8.236322828598915 +6.471664575943713 0.7680150189499424 4.619353658660838 +1.673118074489209 -2.997542487783238 14.99224960565904 +-5.553543852426658 3.324843747985487 14.06414778819695 +-3.59617628940663 -3.027798323399616 3.385904566324266 +-5.938846305155375 2.742003558226709 8.346030661074392 +-6.193726184930637 1.95427919968402 7.68055281468652 +6.127621040786362 2.308935214884168 15.04137591370123 +-5.343501386705279 -2.982055693649766 18.90740740740741 +5.573728640850264 3.329826106733638 20.00850156588109 +-2.514938519004928 5.980136847449882 15.26407650098751 +-0.6570133596463594 -2.982013715719152 7.60885870924154 +-3.759761476129077 5.31934730307797 13.28970086353346 +1.55270270350357 -2.979623578643817 8.045395701888504 +-6.535138138107862 -1.305139849583819 19.96467485785346 +-6.48438710456846 -1.647500030602725 17.12942676381969 +-2.502710858512024 5.994374731730718 18.56803472019594 +-2.871601240022273 5.821071006033864 4.292605724922689 +2.600557040962697 -3.018576743239543 17.48696703723621 +2.017708056055402 -3.004078649969486 16.58979508742885 +2.643648488752925 -3.021286438138878 6.983785162986325 +1.588219652752341 6.278923716992498 16.67074827665643 +-3.357747810039035 5.540384215324119 17.95222742883644 +3.350952274009982 -3.015106223485149 5.125360416173541 +6.503904605322154 -0.7473010825458442 2.865250757179215 +6.499779925762517 -1.887604708088112 7.731449475312305 +3.788210272808274 -3.027549614625479 8.594714597805721 +-6.473571203969275 0.3606228665924536 18.79482443803992 +-5.106531961005763 -2.999994966997187 11.11248045043093 +-1.605701788931688 6.319626701490073 10.12419609324355 +-5.85377704479913 2.837877194744548 19.95548763011616 +-2.35046346697908 6.032868162520325 16.644398698456 +-2.025206030745538 6.170820798147163 17.64112995275521 +-1.158273444406993 6.400554550504534 18.21397821059482 +-5.505547245301593 3.426980326614693 17.33722121260902 +-6.000459506072253 2.476605987483867 1.120636631152571 +-5.496505221936951 3.425759738028892 1.098929190972999 +-1.110896668167776 -2.985202346840391 13.52768824556397 +1.367925526286797 6.336986610773604 12.90832548575193 +6.493677053536113 -1.264334695032571 11.61692926591689 +5.146437421139353 -2.975619915174335 13.45905397194597 +6.155102757324552 -2.754476026196263 13.72222222222224 +4.874465100181549 4.349153252476041 16.68033028772508 +5.045086063461726 4.073336767579847 17.67477578449159 +1.314021303996607 -2.977599807140824 21.07346815306421 +-1.3140213039966 -2.977599807140823 1.926531846935792 +6.06094715073274 2.126193715997229 3.693251332050101 +-5.198726492210571 -2.965546045420998 4.212335323264983 +5.269122824566292 3.814556015102636 9.657236435963295 +5.652801977641442 3.233328620490532 10.4124187097047 +4.22477191846447 4.930703701885999 17.45536384056244 +-5.976346983805485 2.534548384062757 15.98401419937237 +5.20317704122727 3.898050005676582 13.76344333231003 +-3.939851349456998 5.119076566404091 10.54395044075869 +-1.502896383724041 -2.977805953224228 12.44852564443865 +5.463179542922541 3.539941796298122 2.304332728355314 +6.283566393325242 1.757615137278547 7.654717606604951 +-6.498995717566638 -1.520876767758532 7.419641965408338 +4.308725262914876 -2.937757050142771 1.056409118800339 +6.493683601155801 -1.586888753746389 15.59454373518506 +-0.5935366579668038 -2.994402293502086 19.1964409323171 +-0.8892486912051314 -3.009669596616751 20.21103077176053 +-6.503238599016501 -0.4296364244063977 19.44049840879058 +-6.46716707698483 -1.818676568965393 18.16666666666667 +-4.832097470055913 4.37873537207407 11.63396194688669 +1.69802659055154 -3.055622737866734 10.01648305907719 +-6.262741239855314 -2.649154012846593 17.42592592592593 +-1.930632110957249 -3.017795679483387 20.05546161732507 +6.473570678217266 -0.7150115599456327 13.71690326120949 +3.31294817025803 5.582920741554236 3.485797041654345 +6.482020203912487 -0.5631063450209455 17.63583918996564 +-5.345882254407206 3.705270609949913 21.26051091942394 +4.330897372412547 4.831580271583908 1.085442402678551 +-4.322628671431874 -2.935324094059091 21.94118581660032 +1.287278366296675 -3.01207449498159 18.54769842276209 +-3.701326499099642 5.273103487410696 21.93804480276436 +1.655752950865797 6.292028654061201 11.5501546636194 +0.7457883131509402 6.426168773837097 12.06320019365666 +4.306993590700682 4.835346716208262 4.76234443404836 +-4.444942036500628 -2.994872222214869 5.621167368919448 +-3.832915649155907 -3.016537376243592 4.757550935238352 +5.239912380024573 -2.999927696162843 12.1127423029734 +-6.500000418550965 -0.3736474483312121 9.646934980961376 +-6.497497543396808 -1.446587909199208 9.653768524008681 +0.1026928199801189 6.469841089737336 20.52266229151875 +3.949760499636805 -3.007381846424123 19.74679151365675 +-0.4113964697249641 -3.019536400389677 11.45714311323613 +-4.181991162515956 -3.013534046748768 11.62944437319485 +-6.473995813002272 -1.67090618678224 2.322554987720038 +-3.734117596196564 -3.012659050715872 13.78403208175362 +-5.877433041559781 2.772401985660232 11.5511053831911 +-4.222959599354492 -3.013529488758429 6.823516575525074 +-5.093368920109207 -2.993924577284153 7.452769082311312 +0.9849922191233815 -2.993866794063395 4.99290594328292 +-5.46303220704911 -2.997502833411126 2.611111111111114 +6.329422438374813 1.302234809087709 16.27970030385343 +-3.648009805622326 -3.00504633921106 16.86157641268512 +0.6572260987487106 6.486401378115866 17.85016370833298 +-4.506585376507205 -3.043542283811173 17.43116935111303 +-3.885398989137931 -3.012668409117178 18.27974825411085 +-5.29429883211064 -2.999148311607532 16.68674417799657 +-6.375099729832565 1.247777244258578 17.26085435245753 +3.969260546161045 5.147148162541914 19.06965079694742 +4.31371903392271 -2.984410533806999 6.877034564608756 +-6.498576960299408 -1.93217913199571 6.314814814814834 +-1.72630421804796 6.247447314901795 5.697186612490997 +6.482487382847188 0.6177136584165998 9.249879674395695 +6.504589300190052 -0.2407641006080064 8.627492042220537 +-0.5553504475469798 6.468178570958716 3.438696457429523 +-1.528602936385141 6.27006842599666 3.750978008843046 +-1.397460890019824 6.381938514384385 16.84607985430178 +3.451471462000092 5.489933692578968 2.087641678545805 +6.493605768643793 -1.605024341180427 19.33877957727899 +4.101722981162058 5.022314992382529 5.745816613939406 +-2.341129895731718 -3.02465827479278 2.070112229653049 +-1.875904662538065 -2.998380885539231 3.019620453681991 +6.522904097628889 -1.747264744180924 20.48506283874573 +-5.616451876237301 3.294964360136933 3.165095296886841 +-6.52514914285643 -0.9498778978512054 14.93862321319931 +-4.71773936896142 4.468707658790646 16.8588582434264 +-4.056085760310849 5.060616311915458 17.37339988821808 +-4.366368569893536 4.772156004111059 18.31833062770848 +-2.88022377506441 -2.985212958295347 8.003378143509341 +-3.89656641398737 -3.004733729157923 8.141809291287139 +-4.711096150210788 4.442173020348469 3.864577819032392 +2.666003476538513 -3.002967591590869 11.59335445808955 +3.541161278555311 5.437089085123892 6.798157420498571 +-1.662725302633063 6.308168333026557 8.525150344918886 +-0.6374774276991659 6.440824023136345 8.293066033513298 +-2.467962088708822 5.929042847565623 8.08507077642653 +0.2622502328174594 6.47814532642278 8.742012344872421 +-6.500141035293646 -1.430496289812707 11.12929014645812 +-6.524262951165467 -0.6499751458477753 11.84084360797586 +-1.893797165682649 -2.992822950108159 4.585192774744201 +-1.184646504198797 -3.042956118468096 3.810577173326639 +-4.78088121368246 4.358663036481055 20.64902636318931 +5.984634092913956 2.561065810374761 1.563031080142295 +6.471731999722761 -1.649126051339105 2.350395110392803 +-2.964780940309625 5.783057382510931 1.459364679771285 +5.036746749691163 -2.994863999771363 3.095173005257791 +-5.204193479688336 -3.008671803665695 6.382940216254416 +5.213691533453365 -2.974234961675319 9.86923240442456 +2.610806008881976 5.937091652843468 6.956657550523319 +-2.526450752774276 -3.046203873945023 15.0339094442279 +-6.343238729685765 1.453466805859118 16.21103072796885 +4.988769770817104 -3.001189152323238 19.91836813801022 +5.873791305065626 2.838766135934368 17.6149243128121 +-6.499638266430628 -0.8462369729616088 13.35449087135984 +-6.518071071546846 -1.563900980118728 12.56367227747362 +6.291527833456525 -2.546179766464923 6.994347202819564 +-0.5372847273850647 -2.994622803550695 4.653618577985725 +-0.2945123075117094 -3.00314714563698 5.669552834778864 +0.6959858181079597 -3.009683339781914 5.99431851795583 +2.793364301257439 -3.020349366675881 21.05478868924941 +-0.1628281534397673 -3.016695565339433 9.432189641212236 +5.207430701382219 3.898889021740732 5.230672855983511 +-6.313116891591418 -2.570245240112381 18.88881676321203 +-3.949037199205936 5.169308082787516 7.877139059691132 +4.432326799151346 -2.990899110336025 5.824191176164475 +0.07061814657646276 6.512483780384044 7.121622416906185 +-3.265574012618712 5.613647797425472 19.20319006143447 +-3.743729786498402 5.274015807952221 20.02914221305575 +-2.094895687996963 6.106536786866899 1.991870625201493 +-5.797600628368242 2.927052220658914 13.12204623507679 +0.7641663571924113 6.476165893095744 4.509740058967287 +-0.8653827906859299 6.402296750381271 6.268101466560384 +-0.9463493196213879 6.412315492568601 7.302697378441371 +-0.8280062659390659 6.4212014348163 5.251032918094764 +-4.778256054578752 4.370778083328107 21.91795720777009 +-2.696328777705862 -3.001277392960476 5.676833769128502 +-0.8618816003928863 -3.00702058566944 2.842061689937512 +-1.059197580594137 6.425716595443287 12.38804389784358 +-4.490281772062808 -3.019254416958939 9.004134868222145 +-1.795891052911316 -3.003808216655108 6.805935044140837 +4.65392204653236 4.505484275268842 13.09273941079274 +3.998331086131441 5.149286493203322 12.53250590371847 +-6.52338417039269 0.5981223663828794 21.09438097038991 +-2.177903499712987 -2.924614043882116 10.17280879452636 +-6.092866215279509 2.295386028558087 12.34285162763387 +6.018296575981227 -1.61631813491238 0.8338540625910015 +6.414701220003536 -1.618943284921925 21.43102019516548 +-6.514442628287716 -0.9216315812621556 6.539081823054465 +-4.439230600061907 4.662642017432399 19.71209585531156 +1.5713059604061 6.286157535925912 3.856805902874938 +2.393504919178346 5.973159836580448 3.369848085268393 +-5.278925983689473 -2.995769837884154 10.05229776627995 +-5.125933746510565 4.065835320825039 13.4375129327106 +-4.088047072922355 5.032353180942495 21.01178474731601 +-6.479285676208324 -1.74512532408199 8.65454699500795 +0.411342188842981 -2.994707870917591 14.99551407846301 +4.820203119366058 4.376453099836501 11.36735247361739 +0.2497868508263866 -3.000659310024309 12.64819081370181 +-1.195028576709084 6.320902491750946 14.56943438430487 +6.208680291642042 1.667947784205049 19.37603271331027 +-5.766577651634469 2.981094122619456 1.997551648390408 +2.394168234996761 -3.022826813486706 1.403360283097423 +3.323336030643543 -2.983150514044707 1.942077236885311 +-2.394168234996765 -3.022826813486706 21.59663971690259 +6.534252213587371 -1.284404266389176 12.67038862513343 +-5.310897681693152 3.727754778153678 10.51133610229882 +6.522752093880841 -1.411720125656958 17.03402627818623 +4.990930759208561 -3.024846838970435 11.10637395257536 +6.430281349972208 -0.9924612415621354 10.55356289690729 +5.045996032737476 -2.992922526889369 17.30867648740239 +5.953353519756443 2.70062154932645 4.969210133632235 +-6.115057530216206 2.144925194734729 14.99091114892485 +-6.41645452181163 1.103478409622281 4.710352465612674 +6.495217927116095 -2.17318265698779 12.12725760606017 +6.498198358359046 -1.728165987518727 4.763731985639816 +6.329654373829262 -2.539164164474805 4.126430211489924 +4.10280641855582 5.040249481704948 10.90517402223989 +-6.018296575981226 -1.61631813491238 22.18118766011988 +-3.666408265763993 5.414937850202598 4.814527275981727 +-6.514225439861129 -0.669782133375689 8.667600304554142 +3.474852463247049 5.501508072274907 18.230995848761 +-6.499800998701614 -0.2392355143168469 14.18986287121351 +0.3452818596006839 6.42024391642373 19.56951337445544 +3.153283737811866 -3.017368162283952 15.29431030323381 +4.124208525491944 -3.003211062483214 15.73397030797423 +1.559944187844029 6.312225571026758 8.529791746597434 +-1.373789836792924 6.420483657874478 2.59711350497356 +0.7789472767473168 6.543441189875025 1.750156115054728 +-4.965997223491945 4.154332123092525 17.78756939961828 +0.6264544129449389 6.43558456907624 16.85940741836995 +0.9396273382429819 6.420824377829041 15.85732262163295 +-3.336656099422833 -2.977436160115543 0.9775827670419382 +4.500526621980486 4.7882553496284 19.94817672609429 +2.004700883114467 6.183265012236975 15.61107241166154 +1.292572804076906 6.393978102752601 14.86874610610907 +4.004017023187889 5.121348905123284 2.875930968311236 +-1.476980927974557 -2.986528445957584 18.63499784287429 +-6.486248585207664 -1.652486825231798 4.3486481046786 +-6.46964974873086 -1.443318761406991 5.381522366132041 +3.667567343787143 -3.045329194988058 13.40617733425725 +-6.281948846822942 -2.613862144160331 1.901379398744916 +1.638741562317307 6.304449604954452 13.90216761004879 +-0.2478025671671367 6.500626233655353 11.71954262228471 +-5.177193797755789 -3.000528442441809 15.41652095448372 +-5.324927082111444 -2.999416002098537 14.37400124651582 +-6.14447103662978 -2.770833235245751 13.72580645161288 +-6.502499292360715 -1.986798185506558 3.338421744294485 +-6.232477565913408 -2.67885870921113 4.09877892574296 +-6.469418020485382 -0.6287666695640937 16.48933331026324 +-6.45791348084582 -1.596316312562227 16.08060829662684 +2.911005036835506 5.83669216835877 13.91017635249146 +3.731044344117048 5.318668213268635 14.38184206844252 +-5.619546250588726 3.299066659901728 5.308443842111661 +3.388496642730866 5.634288036636221 7.738552792418794 +-3.301738748784647 -2.981975605071312 21.00778554854654 +6.564887380651111 -0.02681888973279577 12.99286426113131 +6.387164616408904 -2.503983086283375 14.69378504259369 +-3.31091511383197 5.576108439514422 8.612192317797692 +6.229763859106678 -2.685230043147593 10.01612903225804 +6.500173701244147 -1.703182400252232 9.762965072314474 +6.476026089458056 -1.511234218477743 8.721415746861329 +6.521840711341567 -2.012744662685568 10.76101236866769 +-6.539660235155536 -0.6871774594581846 2.488377508126536 +-2.026203209148381 -2.971775803010396 16.5209795318433 +-4.641356074693205 -3.008046527401038 3.267952603797489 +3.59650760270541 -3.003748365448816 16.67210759329583 +6.50308687810493 -1.020484875923848 5.829450418914611 +3.594740750661074 5.33946441481557 13.40849661400496 +3.552313774290081 -2.974052950786968 7.59170449497798 +4.544819673952674 -3.015982917188714 7.886713865346371 +0.517915380549832 6.543527383443009 21.85640876316478 +-6.442361546934048 -2.25460074774956 20.38888888888889 +-6.070644084476802 -2.80843638863518 11.50000000000002 +6.460143735777661 0.9056708891669454 6.177841430440145 +-6.533739086342433 -0.5782606561590584 18.32821030435132 +-3.413719721874799 -2.958742655094863 2.04946515642215 +6.125331191493462 -2.791629016013449 18.20048102238008 +5.933862147406554 -2.88855912660623 1.923211918814838 +-6.511768947248228 -0.4869736225237588 5.646091296377143 +-2.842878188514835 -3.031678169698418 6.717230941904692 +6.052982093277955 -2.878543111785245 12.71555513806247 +-2.080862579384582 -2.987601716678921 13.2985840515283 +-6.252473998424269 -2.660033918863382 7.055555555555578 +5.235214695953618 3.857327244743622 8.572603487099766 +-6.299577423571651 -2.615603100273393 9.232342079317213 +2.806903292070916 5.814788014408168 12.82682984984885 +3.26492140296288 5.578308608030114 11.90459224187798 +-6.499075298481734 -1.295039515692096 18.98952779629491 +2.447002384244808 -3.039814548527051 2.416198769743635 +1.918707997349344 6.279112429184018 7.595058675496567 +3.792559206025983 -2.999999862933456 20.77312952152235 +6.49788803796583 0.8106061889691277 17.11953013791608 +0.5246644600369459 6.440730341701182 11.08943210234822 +-2.94340710577174 5.789263988816035 12.8875553549071 +0.4152803222397733 -3.033031186751981 17.99075939608404 +3.252700890833827 5.662720135554117 10.63471746627712 +5.448810719357134 3.464735631334987 12.45881261403407 +-3.584304601508996 -2.946472056982334 6.084319880359088 +-1.716772246320052 6.271965140349353 15.85878842708502 +1.690232179050118 6.270646635552852 6.565926537082481 +0.5979619776167141 6.424916953803631 13.84413411145146 +4.23825617237275 -3.012281683182409 2.404999317745592 +-4.704027607893446 -2.983845559376823 13.60797759506212 +-5.323670781389362 -3.044098720543049 8.434592298243649 +-4.973508038334575 4.037577133545813 2.99138339358704 +1.248065549313944 -2.954515734501804 6.873841373914307 +-3.658286014220247 5.386509774702938 12.26995087717167 +-6.11002556335582 -2.804470728409541 5.984586272804265 +-4.774318250130195 -3.046418604523909 19.69830322660118 +-4.228063206488012 -3.006800125905723 20.56638406076299 +0.6708653170304456 -2.976504322147557 11.70955318798275 +-4.47963566224686 4.708481290889173 12.84808413099119 +5.195147608075783 -2.980860617634953 20.94056667561455 +-5.400136726468617 -2.99950229609896 17.89939234640469 +4.823370509827259 4.309420770666964 4.095953191802099 +6.498145168427381 -1.768415627748438 18.16666666666667 +-4.684795955298891 4.486619965365161 10.32932672126882 +5.78708441809516 2.868522860722104 20.82991850766216 +6.569621124306699 -2.153551641249988 13.08995184897574 +5.146036533010824 4.069169112071002 1.521802655394462 +2.717387929729853 5.870435909804304 9.210011825238871 +3.778157308267924 -2.965373449423976 11.97760501985029 +-3.313976594521225 -2.993121478880113 22.02111374210077 +6.536331311002488 -2.173616636644286 3.209437137438 +-6.431580487222768 1.315200658134383 18.80308618553987 +6.175187596451688 2.216700651955821 16.00344759968815 +-1.533964954301693 -2.97289697884997 20.96133631229725 +-6.436064672194338 1.146750615357914 14.92558090709884 +0.3509057892721289 -3.047696558808873 7.844855105983688 +0.1668019112469916 -2.952714505361372 6.854642074170482 +3.437678413660098 -2.987945726471955 6.294045556244952 +-4.452644256219537 4.77102787556186 4.791073512411466 +-5.398617533792235 -3.005962701403923 5.303563838962939 +-4.358944367343097 4.842034919222129 2.908287710234729 +-4.305729716839079 4.834686966136741 1.834214180169568 +-0.7131162028683401 6.46266229296505 10.7650492462603 +-6.02279133509361 -2.718453684056692 21.11176255952274 +-5.715037766334341 -3.000142435511865 12.45304913721296 +3.270566787796116 -2.902276655701293 18.23724093505226 +2.540622009094899 -3.055506620519976 14.5157339273514 +-6.437825039791563 -2.382187941974836 5.033392067983014 +3.785144719683968 5.323381387010309 21.11830048807157 +3.681977431564915 5.203895829291072 22.10518060823537 +-6.37090331001109 0.9187606234123105 11.25429043302381 +6.438124812448258 -2.353341685996922 17.35840207044152 +-1.16752426589043 6.302575775581135 21.17723225117221 +-4.929814287460334 4.106959417160492 18.7655154364709 +-5.33321179298064 3.613785840898705 6.195712509819249 +1.320155444729417 -2.987162850275582 10.94400056791122 +0.1156983373351747 -3.040925129008613 3.948870057406977 +-6.186931346386279 -2.728990636735522 15.20967741935481 +4.082715201111856 5.103452263720099 3.849795796491875 +5.817890089382733 2.74076567643282 9.615148595402076 +-4.394293805427311 4.589354136726076 7.303737540634369 +-6.627149207712543 -0.3659836137965126 21.25247415550651 +-5.639100025161106 2.958936809496112 14.93125573219258 +-3.917134203682603 -3.002142459381213 14.97896563704691 +-2.600066399957965 5.976931667967635 11.94054759381446 +-6.426973139101115 -2.339102439103958 10.66228323338333 +4.502343643773004 -3.107523830686578 14.81645315525215 +5.168161270915379 -2.99520961644233 15.62069506159792 +5.70813895347688 -2.999264203237995 16.50819369608041 +6.475294661447162 -2.339431375531768 16.30160059307673 +2.001869859595293 -2.86841343438668 6.290375293239955 +2.567407975815391 5.9639068015147 11.29913459577384 +4.993709062795208 3.826297810431139 22.07453231939922 +-3.788505221440457 5.273025985590818 1.007877757361112 +6.43646296561174 0.9384296771557414 18.81807649523661 +6.164506502379031 -2.746175533136578 20.38888888888889 +-5.971154196939858 -0.9999999999999989 0.8373586982368345 +6.473272827851001 1.088833416644893 21.57163930933321 +6.004955577891511 -2.784279343964513 11.50000000000002 +6.002710712352013 -2.944557546818876 2.904999617725486 +1.262972684911749 -2.987923765574794 17.27560884540768 +6.557756966253772 -0.4074795742474294 14.61621738569975 +6.106706816540556 -2.806775290810075 7.971573842600698 +6.045246294933126 -2.888419895209621 9.030066729643291 +-5.330011412925885 3.855145820331464 16.5365448992121 +-1.482551989990327 6.290884651920363 11.44588367088225 +-2.369827228756918 6.083115342181289 10.91881067652353 +-2.582241898430053 5.917326124225594 9.865291993104785 +5.85889012660036 -2.962227612220233 19.36699184591218 +-4.292324618051117 -2.921336598799907 9.971920072433628 +6.370372772633454 -0.974157328497453 18.65290659835118 +3.193549507926806 5.770973124727019 4.398044319133167 +-2.902812544881516 -2.915679347853057 20.11578543929426 +5.647762048363602 3.527315946424405 7.037945253954569 +0.9902050508118803 6.30299022817558 21.11241719096623 +-6.377706226854533 -1.825904655376307 15.18998886432397 +2.173147748846095 -2.853714714912356 12.84875256723881 +-6.096930578815693 2.104296301062118 9.058089659670022 +-0.3329285431342429 6.410124313294302 17.7891932569368 +-6.379022900130145 -2.558751286147321 8.05698075978918 +3.249593894568599 -2.802390948885844 22.09162493627831 +-3.475034999900794 -3.042132306267375 10.9748976171736 +6.124599928790023 -2.853102841768759 15.55865141219203 +-6.406983158741113 -2.544966507668176 16.42959993260468 +-3.448395402782671 5.544242586749978 9.585680620821993 +6.595481764312204 0.3141051855484061 5.445727054749827 +2.676339697118263 5.81694119814252 1.464739488355286 +-4.101315591730126 5.003492171886096 11.49488436698268 +-3.348887748607662 5.655045108194224 11.35160486923376 +-4.851117273124653 -3.069596843058981 1.873860213398135 +-3.434402619933879 -3.092357698092699 12.18654822035202 +-6.479174847654568 1.070626982503413 2.857072292245092 +-6.436335838517361 -2.486877256905319 12.84668866995535 +6.189771918746362 -0.628613720193801 0.8127851035851821 +-3.05005500006306 5.889383019436033 3.374802976378918 +5.021963623858474 4.283100340323708 10.44469687333416 +6.566241919726147 -0.4852358491163991 12.16561402376104 +-5.845850715050354 3.095404853217222 20.82083891749626 +5.156565463067584 -0.6288987107172896 0.7519132649140612 +-5.156565463067583 -0.6288987107172904 22.24808673508594 +1.386604551758873 -2.90271196247302 15.8903885351296 +2.301165852554995 -3.000754035391069 15.6927168667635 +6.499090183549214 -2.037378718584649 5.736893125891132 +6.049297084438585 -2.890828554268084 6.066113428820499 +6.194250237813426 -2.733627895341624 5.093584020740479 +5.266734801348457 -3.03747423583372 5.284921654389133 +-3.04582634577006 5.861609774415642 16.03283099532357 +3.283784713048266 -3.003876051277059 0.9396967627822698 +-0.6401001597335593 -2.898505401451386 21.07271594069191 +-4.084152385425528 5.199432901522701 19.08817563139139 +-6.356208864788315 0.6253713460326029 17.9287891289623 +0.2118777047915343 6.408377886492589 5.241261486521183 +6.537141060522154 1.198667043482468 14.03450230098074 +4.27943975314184 4.992173316880449 1.998588503251515 +1.655429134530957 -2.963140640974326 1.937204752841775 +-2.36575733478201 -2.909796690709885 18.38707739417631 +-5.198704605695848 -1.272668150714039 0.7336271490204246 +2.13713353625063 6.291716385425401 12.36250865346063 +-6.364036348084739 -0.7616633935161315 10.48823004357624 +-6.004170192969719 -2.693906396902621 19.73026875435297 +6.364895084382994 1.782169353734429 12.48335008804921 +0.8415060928549489 6.58324539588483 2.705827275411427 +-1.212640637611154 5.89048327459662 0.8696233077943706 +-3.222276742486151 5.664805717034127 10.45461623720719 +5.156850281120104 4.141391095039664 19.83935152152939 +5.025811364158355 -3.11609187757595 1.909524820092624 +-6.088460027062307 2.572667630298475 14.16700960131849 +-1.443955657683788 3.239906508849209 0.7648591769306663 +1.443955657683787 3.23990650884921 22.23514082306933 +-2.863463573281968 5.684109943671232 14.47753170449934 +-2.805993534240377 -2.898041049583389 2.883464392502987 +0.998394493498229 6.310593448630138 0.8539501463968898 +-5.81571881927374 1.997109331282275 22.0840802290626 +-3.488380320905714 -2.977468068156885 7.340984292896019 +4.395101098298677 -2.849099030163311 13.95275659680586 +5.303883347374014 3.571667202081448 16.94112167611862 +4.111402368452287 4.901266644349718 8.945146630407159 +5.825916960008353 1.158846934672561 22.16693465423955 +-2.548858094745716 5.375689462762094 0.8020304720655436 +5.994586646999863 0.953701988919573 0.8368794578039475 +4.710084418829587 4.684623573634595 3.26641767702932 +4.370994237677017 -2.827158601079209 3.737614402412228 +6.194436472103207 1.471457502578874 10.72405620203234 +5.997754719629342 -1.51841623398864 22.17633675996521 +4.702061067456925 4.731907107917426 18.21238193795245 +-4.941544679954434 -3.10846723761769 21.13999160309448 +-6.575403409334473 -2.081626465130348 11.79129778073592 +2.206035686558925 6.256590723300881 14.6591938778397 +-1.866853376832803 6.371617925928659 7.507413251263729 +-5.150297817602824 3.34715691716223 22.09007714745574 +-6.1929777163634 -2.85621425208841 3.180252900346515 +6.119531803792429 1.584698495747357 6.817065589504256 +4.627158279032533 4.288079499311436 5.805630604936705 +-1.877205958028288 6.016583492206149 9.335469042037216 +3.374209230042288 5.778693515379235 19.33977362568106 +6.285239299368041 0.506519577068682 14.7512659631017 +-0.2343684143622669 -3.157049278763749 13.39434690791109 +0.8543880182200357 6.320874601209465 18.69662196995619 +-6.624201600001344 -0.8310303229325582 4.722261261640789 +-6.708173056764183 -0.5813399104022626 0.8253791614388091 +6.369846036458235 -1.031848767849037 7.969799407755755 +2.02284496308946 5.708404238126755 22.11773111638573 +4.815987126036465 4.118417326746779 12.26177380436749 +6.04869996041485 1.814269182580974 1.958240084755025 +4.727865804069478 -2.900060299406047 16.43711341690515 +-1.178394325258101 -3.180646568147341 16.28248714604825 +6.255578895332562 1.249021586066656 5.340364599819755 +-4.188949243400468 -3.119048553015969 2.490596601996191 +0.03089479284160017 -1.188862985271091 0.7537788932994617 +-0.03089479284160035 -1.188862985271091 22.24622110670054 +0.1319583639659567 1.438542377007056 22.25083124472208 +-0.1319583639659562 1.438542377007056 0.7491687552779256 +3.711843827455286 -2.854664741593962 10.20249186076711 +-0.1358372186633865 4.590149556470402 0.7494809379243268 +0.1358372186633855 4.590149556470402 22.25051906207567 +-3.28270707985806 -2.877165299909713 17.65238691066066 +6.339465011723408 2.095792244402343 18.61740658996348 +-0.1056461030254565 -3.176564379679698 16.0429100526402 +-1.319789951547661 3.937830597733083 22.2563866039054 +-2.002566284803239 4.369587396055784 22.25077369609025 +1.31978995154766 3.937830597733085 0.7436133960946002 +2.00256628480324 4.369587396055785 0.7492263039097454 +-5.590461927310139 3.647566371184457 9.10323233480467 +4.528105130762393 3.967298764066974 0.8398750593425436 +2.18728899262124 -2.761388380584178 19.30120570123329 +6.494632155934976 -2.440641601117187 18.96232222978681 +6.303200461125378 -1.03038138588048 16.26136247422223 +0.9221623775155928 -2.866421347063965 20.29837323271959 +-2.83359524023025 0.9336108224141295 22.24903437874042 +2.833595240230251 0.9336108224141295 0.7509656212595804 +-6.585458740218506 -2.069865563102272 19.5488751496824 +-5.426823103209266 3.808678829748355 20.3803642150527 +-5.880551734987407 3.072487430515713 10.62471802223168 +4.958808715213554 3.990695481870283 14.9292195662646 +3.663152445339311 5.550353776397384 15.43227056092639 +6.028223306723941 2.913261315236041 11.14389710001911 +-0.6052936849469537 -3.129144799857166 12.34571194906376 +-2.020880231749868 5.992222687108023 14.52387564290506 +-2.971014548901162 -2.833912474409837 4.851275548491701 +-4.189854352390702 -2.831138053621039 3.988123564352544 +-1.761012245864524 6.476162960340695 19.8187984895637 +-2.819944809574567 0.9304571544591891 0.7368041393457663 +2.819944809574567 0.9304571544591893 22.26319586065423 +-3.570026859380059 -1.210580030792211 0.7306212473333298 +3.57002685938006 -1.210580030792209 22.26937875266667 +2.164103414606198 6.231856630014455 13.22228150850368 +-6.633586998888088 -2.073998086889049 21.27407212133262 +4.139573345087795 5.231609881665705 7.355052376525556 +5.783944263330872 -3.096035584911443 10.68343594160902 +5.196976275817705 0.1602497453731656 0.734907561552664 +-5.196976275817705 0.1602497453731649 22.26509243844734 +-5.767937873858986 0.4303753370328493 0.7759079095502224 +-6.297940294571895 -2.888801265925433 1.073652860389498 +0.9679618084729851 6.614158967992704 7.002033955744672 +5.193558408864839 -2.84054437464208 6.219490582587596 +6.702238414438753 -2.132482653978121 22.26855264015182 +-5.521704534771916 3.000307152974475 16.57145177283574 +-0.06192699137767263 -2.826103956418007 8.584019691120966 +-3.883115694037456 -2.82196824154298 12.88540046261896 +-5.460317439126324 -2.788324550819443 9.240924076531975 +5.160537965298962 -0.6438068264979541 22.2397742936086 +-6.177086120611652 -2.954380970087829 10.05614113066803 +-6.172982637976106 0.8937554031418797 1.855625060861921 +3.984730138053941 -0.7915397031562861 0.777281052567261 +-3.98473013805394 -0.7915397031562862 22.22271894743274 +-5.763193454768866 -2.334889949469598 0.7435439962866582 +-6.199244515352671 -2.329889700593037 14.45493820652436 +5.527283726447728 2.445481146101323 0.7983011336311474 +2.734586935155321 -2.881461957421005 5.755869997204822 +-6.643082964077693 -0.0699564970755775 3.090563404640717 +1.852061246666457 6.454689739799604 9.310486171235651 +-4.089931466419461 5.249784149923604 8.775686152879302 +6.6416810887705 -0.9468122877119568 9.360334786972556 +-1.485752880349124 2.061752370219513 22.24310697497389 +1.485752880349125 2.061752370219514 0.7568930250261108 +2.025802144211496 0.9873798624281778 22.25455820630024 +-2.025802144211496 0.9873798624281789 0.7454417936997572 +4.534791795396869 -2.986139609472338 10.38616340598337 +-6.669499406720989 -0.9259246899227743 17.55546096882433 +2.517732677808626 -2.824436330334575 9.94419267342175 +2.141175758890777 -2.82576244161767 10.72331404808519 +0.5394467128471261 -3.225371766426404 10.73231494439042 +-1.162262958411799 4.678680346367697 0.7804383820603213 +1.162262958411799 4.678680346367697 22.21956161793968 +1.136499306399979 5.504945317752713 22.25169002800006 +-1.238116421016148 -2.80150202458213 5.072010977745603 +-5.60491175169001 2.887591933039548 19.10741516678326 +-1.375863474688461 -2.809279425285201 19.45421009233514 +-3.569710030323662 5.684829651970341 21.18407170709581 +4.403330000297629 5.068118873467053 11.7432729559336 +-0.1931549279355134 2.38261822772029 0.7442726014724842 +0.1931549279355132 2.382618227720289 22.25572739852752 +-4.925236576525001 4.005799898405868 12.59274252315995 +-1.872907957128605 6.040580533782626 19.11485102158504 +1.684559851488984 -3.236228588461814 4.535073796476368 +3.179193790398735 -2.784034366333834 20.16224643612649 +-2.822657425028089 -3.228225691110377 16.73665377266985 +-6.441419283281843 0.4944089610808678 5.412005087545142 +-1.06592747354488 6.179647977546801 15.36748333886957 +4.26660251099574 2.343972043529507 0.7704033139630269 +-4.26660251099574 2.343972043529507 22.22959668603697 +-5.016777709122972 4.42612652783378 7.812734421046012 +2.821652779529045 -2.812886744247133 16.35120461608043 +-6.063968929858416 1.570729994087627 20.02065619557439 +-4.478666488964691 -2.825496866448968 18.90063186794199 +-5.84386816888915 -3.073948838331733 15.99564882483917 +4.155716155402402 4.77536776402922 13.74443450418196 +4.109825127407905 4.68282661247222 16.62421645555201 +-6.26164054783082 -0.4528876842841559 12.63187355220443 +2.627064033760208 -2.473345143465829 0.7870098791886456 +-3.276175764763693 5.844534793138468 13.75160693394195 +5.010173108563809 1.5538999334784 22.2522163659965 +-5.010173108563809 1.553899933478395 0.7477836340035061 +-0.8696500073730458 -2.376222871439294 22.20800234986249 +0.8696500073730429 -2.376222871439294 0.7919976501375063 +0.1640737713047776 -3.169951683160904 18.81046472646921 +-2.654612303084468 -2.478834473372336 22.20406417824396 +1.286740259459964 4.745177973570531 0.7974729829579795 +-1.286740259459962 4.74517797357053 22.20252701704202 +6.313660129909832 2.400305352924715 21.24850209108203 +2.916421568298186 3.787631195711259 0.7470521394310755 +-2.916421568298186 3.787631195711258 22.25294786056892 +6.433462026045749 -1.839061772113444 1.531316173097202 +-0.3204269567243521 6.277360548968201 21.23350486318957 +-3.116486073821718 -0.5155384203215252 0.7113714079993262 +3.116486073821717 -0.5155384203215249 22.28862859200067 +-2.243747127971263 5.844112940113565 3.746568161451278 +-2.855618953008979 6.055889796556833 17.49948026030134 +-1.170858644084031 -0.1516188269739046 22.22219002542985 +1.170858644084033 -0.1516188269739049 0.7778099745701551 +6.243202083463077 -0.1973191310503978 10.77566166992256 +5.869304798324827 2.105637782240842 17.95838223762728 +-0.2388708145909614 6.458518387915293 13.90226175830631 +6.572977292956777 -2.389521242469764 21.06578472972314 +2.644136904820935 1.738064637754003 22.2755332119146 +-2.644136904820936 1.738064637754003 0.7244667880853973 +-6.3522632159848 2.175644179889001 16.65143887028434 +-6.418718494920459 1.809182437773106 14.28338676206366 +-2.397843317465536 -3.18225593900733 20.75470838155498 +5.327792458875339 3.261792908239399 13.25083069633382 +6.213959761331447 2.579074094368225 7.874162105411322 +-5.099693021872665 -2.747744841954165 11.92400216824049 +5.749339189383349 3.347992531829657 9.02178219920966 +1.86559933197747 -2.760188865825719 17.83526861558304 +6.573304487083877 -2.366873037815564 8.566776893917044 +-0.4554182600515337 6.668776169494394 1.660530454831493 +-2.580041041532284 5.257875091590924 22.19852120092271 +5.916861799585006 -3.055309925678391 17.35541098532774 +-2.679970786215575 6.133614422333945 8.938729275608395 +0.479922109521262 -2.718845701924944 17.22580127816334 +-6.13142195215255 1.44759271606426 9.555099434380242 +0.1807173138956534 -3.20636692890079 5.017274679083958 +6.7327411310851 -0.7911650583538048 6.679104715846184 +-2.249608293042912 -3.29561514447663 7.580599933365926 +-5.876356199291239 -0.3448172497008714 22.11035951105795 +0.1779377870788234 3.83014155762852 0.7545109223508942 +-0.1779377870788248 3.83014155762852 22.2454890776491 +1.901146144221755 -3.273614862008595 7.322836656389804 +6.357974677338071 2.149066058296008 9.449542719486248 +-6.719779803047797 -0.6073409072123637 15.68429102407267 +-6.661118149636204 1.118201048267425 20.47812101478644 +1.041339284677529 -2.785266411680579 14.46646036531189 +6.273584142473323 -1.171213332901244 14.8790687469516 +0.9617888680428154 6.653459689390891 5.554464390169222 +-1.506437605892132 -2.572629535021197 0.878937025077175 +-1.599059224252483 -3.299529967625863 1.234693628841089 +1.506437605892137 -2.572629535021195 22.12106297492283 +1.599059224252484 -3.299529967625863 21.76530637115891 +-6.331589945886572 2.279673512102646 6.920362750496841 +-1.766627356862924 5.204316371749949 0.7843825270602892 +-5.493901071534683 -3.135141764771509 13.28146586873821 +-2.075668062349894 -3.175058801860439 19.18470870445858 +-6.158981879206764 0.8512287835669162 15.7012135894159 +-5.763517860421326 2.330916143982146 21.07679096131951 +5.266357185288184 -1.406016481650179 0.7542788435250581 +6.692210727134719 1.063216221675668 20.48648287128649 +6.70246799702588 0.7897061236579707 13.32530472770084 +5.618403538793785 3.688498294497384 5.947037683754719 +6.651926351512846 -2.298960252334179 19.83096487449776 +-4.024120539762883 4.452932435259841 0.8557525559406386 +6.000214576294752 1.836538550374036 14.3524847753891 +3.99050399405734 3.35100838151703 0.7686975139440184 +-0.8141325723014905 -0.9038517488625423 22.26718296254636 +0.8141325723014905 -0.9038517488625419 0.7328170374536433 +2.88562160528926 2.768586778612685 22.24896694237356 +-2.885621605289259 2.768586778612685 0.7510330576264365 +-4.33189419070029 -2.751197718400148 10.8190162759859 +3.127088602735679 5.377054612361674 6.078577919869478 +-4.016964169863082 4.717915708516699 15.65535293183489 +6.073499872846113 2.834709415854054 4.147158423812485 +1.824054210192641 6.473399376900406 17.44778685264997 +-6.172215633715069 1.312766319106706 11.9516009226289 +-5.241059468222106 2.674839910719449 0.8069371074938509 +-5.679475274056169 3.588461194010059 11.23571959944012 +-4.322346615392416 -2.764093445730985 14.30327952800982 +6.742957181151044 -0.5583081296717295 11.30360132344528 +-5.894545388915906 0.7669527333223582 22.18714297902563 +-1.023301300814906 6.226446256383244 4.440620038475209 +-5.45556807176941 -3.168149816267752 3.49489875980991 +5.624204383469196 2.740620876618258 19.41711962995887 +5.888091117076589 -0.273497939228326 22.19613731092936 +5.429124649184697 0.398854600891744 22.25054276615743 +-5.245122722928468 -0.4817700827655777 0.7719910630454724 +-5.201605636085485 2.532970227338715 22.19134527596455 +-1.67887398768496 5.98245110773353 13.49730134663305 +-4.204946030517151 3.726612228559951 22.25968277334785 +2.329401436190414 -3.2955348786644 12.22930735689235 +-1.545631338438447 6.603016426142399 0.7585383173437067 +-0.7377768269207712 6.559488199437826 0.897528674383935 +4.996211830902241 1.518377292365719 0.7524409802772658 +-4.996211830902237 1.518377292365717 22.24755901972273 +-1.833967346997512 -0.6290456787004167 22.26758066553337 +1.833967346997513 -0.6290456787004162 0.7324193344666354 +-2.504018876323828 -3.180117279435941 15.86260456066956 +1.399917844543107 -2.817135514471774 9.293729848725315 +2.16912988538576 4.773280049785519 22.26051816352886 +5.103347011669015 2.783524827934569 22.25708397272175 +5.368801108155004 3.113869251941879 5.348201094424248 +4.902594348881718 4.579103654821769 8.890640012758928 +6.255742333183096 -0.462379573834956 5.18714625302793 +-0.1007480033302127 -3.269948389012693 20.2834161652253 +-4.945642136893277 -2.41489367029219 0.7951851779059231 +4.902504508087049 4.682096414989553 15.93472791795522 +-4.946617064088277 0.5407294598959873 0.7125972531845587 +-5.554676975058861 3.828932428201441 18.28437698816654 +-1.543324561212742 6.532207737524979 6.734302990494045 +2.215790395352093 5.407613607634285 0.7322657982931052 +0.6670741089298222 6.694927945066847 13.08683714339698 +-0.6519246419554553 6.688347057043218 10.00503923122623 +-3.318213736456364 5.89835843702069 22.25577360594569 +-5.446486495948172 3.929097599060833 3.641058474847367 +-5.236427527793451 -1.414715606328734 22.24017245034564 +0.2378062984825539 6.244602926623352 16.19067191250165 +0.2782125483663959 6.345046436574701 15.37679286503788 +-6.227619515115243 0.3681901053471509 10.03402589053029 +5.988347247267827 1.4662126245987 20.11987409503076 +6.018992180751921 -3.039935286010439 21.19375619262985 +-0.5543598144061804 5.112853994827957 22.29183156694195 +0.5543598144061808 5.112853994827956 0.7081684330580477 +-0.9691493102526472 3.894415240175515 0.7258521350207883 +0.9691493102526467 3.894415240175516 22.27414786497921 +-4.916535783665804 4.58033082951762 2.344072229895866 +-6.762949331665292 -1.627237333468196 13.34811986272278 +2.645029574482294 5.626956440283974 19.89376964321928 +6.679839222538348 0.8345382778307429 3.014099421331991 +4.378109951824984 -1.237524303144547 22.2491606606096 +-4.378109951824982 -1.237524303144548 0.7508393393903969 +5.709989154990947 3.591299020829925 16.25374612496549 +6.76120902554606 0.04770523080089759 19.7046218276995 +-1.936338137585493 -0.917479069928372 0.7759064722301265 +-2.359682236433126 -0.2258085052274439 0.7508669806180868 +-1.116830406340314 -0.7202625004366401 0.7468172895503087 +1.936338137585495 -0.9174790699283742 22.22409352776987 +2.359682236433126 -0.2258085052274447 22.24913301938191 +1.116830406340316 -0.7202625004366414 22.25318271044969 +-0.3966078255772543 5.816160558315696 0.8387611894384165 +-6.71301356841609 -2.238219085421238 9.869913820164822 +-6.70981622141185 -1.195625799194173 3.137776937334303 +-0.8880796882506288 -3.278312598387711 10.81612669883828 +5.369254255923819 -3.213385833540695 7.8732171437537 +2.494697925940377 1.788396125773826 0.7614703190076467 +2.905557532565516 2.504872673207103 0.7522785994716016 +2.116631028054085 2.77784854479864 0.7635281819996249 +-2.494697925940378 1.788396125773824 22.23852968099235 +-2.905557532565515 2.504872673207103 22.2477214005284 +-2.116631028054085 2.777848544798638 22.23647181800037 +-4.604425891091792 4.902593919002433 5.573095033150248 +3.7790066935572 -2.359244874465299 0.8030604587595148 +3.814583649442246 -1.567628138766756 0.7253843245442468 +-0.4446041736303111 6.657389261026181 19.64990217758692 +1.454392162258955e-14 -2.265468348961108 22.20180745904474 +-1.471045507628332e-14 -2.265468348961114 0.798192540955258 +-2.656725987141077 5.664454585858459 2.385107883827774 +-6.748854343694645 -0.2504547903546461 1.758784507229754 +6.547352050182585 -2.507978521581451 2.39680262543402 +5.949483284867485 3.068680802999545 11.94477746960655 +-3.214867827350006 -3.243970486665977 14.65490423401758 +6.794425073375858 -0.4663933943077382 2.123809258677782 +6.139598777807171 0.4815950215053262 16.28921473539554 +1.414855172521807 6.109223627137348 3.06513388365316 +-4.637146058286069 -3.213775328636375 4.841503100821689 +-1.249163526399113 0.6485910435674747 22.24921594252283 +1.249163526399118 0.6485910435674733 0.7507840574771703 +-2.592556433019515 0.1162871051731671 22.28022198317123 +2.592556433019516 0.1162871051731671 0.7197780168287709 +-6.045281295676735 -3.161917104591381 22.25768831039434 +4.452386473129513 -3.208833215599112 21.2291735184739 +-4.008873653536645 4.540164274305629 22.20539064761512 +2.183432208904878 6.421678371716684 1.737548470336067 +6.7317386539204 -1.23198305203224 0.7979401105800696 +4.795536386420689 3.194767960935954 0.7750291419563158 +1.019413598506921 2.193295217299508 22.22959160824772 +-1.019413598506921 2.193295217299509 0.7704083917522804 +4.378950285836861 4.401369905538339 7.400958470069273 +-6.25686138908004 0.5004477759966196 14.45147884533946 +-6.114508822015432 1.167356708690988 7.795703303057827 +-6.36826720256448 2.284247492444528 20.22207038521234 +-3.390101535904042 -3.274942741402298 5.376749172186501 +-0.3369840576627257 3.017756053950814 22.21063486637615 +0.3369840576627267 3.017756053950814 0.7893651336238537 +-3.800811425373288 -2.359150561157138 22.19795822603158 +-3.814965725777025 -1.56724123586766 22.27520139452569 +-6.191720918072763 -3.009227324782573 18.18223498275686 +2.825938066435394 6.130018005806894 5.160260169010096 +2.678382258047258 6.232974030642023 0.7720941889328542 +-2.821962975599424 -2.334284032079154 0.7586850428374083 +-0.07097573175378209 5.935479849292261 22.20198580746576 +-3.006560263325579 4.526317033438818 0.7380020138181871 +3.00656026332558 4.526317033438817 22.26199798618181 +-5.807357862686461 2.211227698798135 1.83656883560329 +-1.197439036985863 5.769803872798998 22.17430222206548 +-5.300904101175031 4.106214504378931 15.26317036592146 +6.200117627377613 0.1911181003622172 12.22353384307065 +3.45229272051822 -3.274919592755645 21.46006332985161 +-5.797111823196889 -2.824963371228489 10.74827667608929 +-2.12773449119179 5.846962809814891 21.26174137839798 +-1.38589959029999 -3.225280279476267 9.368358866796321 +0.5431092602412371 6.200697183724133 14.62277009229935 +2.057309201642756 -2.785556107912058 20.86210702204588 +5.712253556205546 3.614312060749306 17.88085275884736 +-3.534036873941447 1.983171204661465 22.24773634208679 +3.534036873941447 1.983171204661464 0.7522636579132128 +2.980327066595128 5.396403498208501 14.53925334065983 +4.630605756432061 4.134968485620781 8.195580595388344 +-4.537477024668206 5.014382135400432 1.093178153809796 +-1.280944334142905 6.043222948662013 7.900741201080268 +-5.892917719789788 -3.107767565827934 7.660105660812506 +4.71898032440971 -2.745406323534921 17.99393591865898 +6.755033363747761 0.8766924894138217 0.7456413235810693 +0.7725109072119826 6.133139732128146 10.07888217650005 +-3.835480900721406 1.950043865562619 0.7805402614429984 +-3.681990047594401 1.123831096953017 0.7664165645610187 +3.835480900721405 1.95004386556262 22.219459738557 +3.681990047594401 1.123831096953019 22.23358343543898 +-6.218558574723238 -1.607094038082271 10.39386961986088 +5.926649590556845 3.368548253720308 1.709354899273029 +-6.777027007712035 -1.012715005787252 7.983978857304638 +-6.760343601985141 0.5735601205695614 17.02659427687793 +-0.9295207648347013 -2.661527340893648 14.75156234237059 +4.528811424014328 -3.258275140037211 11.76077756923209 +-5.748672029156011 1.754235494177533 0.9338092648536446 +5.656918679575544 3.765429258922742 19.34826894528015 +5.238425229982338 -1.408039125247416 22.21871997409737 +5.068201430643565 -2.217383515117133 22.25317301132696 +0.8621199833737352 -3.039721572920139 3.167340151115253 +-0.4295059445359051 3.29137639049481 0.816684696070601 +0.4295059445359043 3.291376390494813 22.1833153039294 +1.252053457867014 -1.674131046060872 0.785933282121599 +-1.252053457867013 -1.674131046060872 22.2140667178784 +-2.812938604508586 6.167269980460326 0.7758186144013716 +2.146513254820283 6.436464873647497 10.778633185317 +6.56299252403022 -2.385067405382983 9.360691340474927 +-6.280878421516634 2.376503617686239 3.70385021695276 +1.242066443280868 0.6709447117027328 22.26300200385854 +-1.242066443280868 0.6709447117027331 0.7369979961414567 +3.366603972365141 3.634324945128419 22.24717764410719 +3.800284998346952 4.328923346317366 22.20118322695215 +2.5244105396183 3.535780581895816 22.26455810599406 +-3.366603972365142 3.634324945128419 0.7528223558928159 +-2.524410539618301 3.535780581895817 0.7354418940059452 +-2.091375062185014 -3.343835300219712 14.11439398527681 +2.522065565106256 -1.651144658657615 0.7484440602416361 +-4.885595419725852 -2.389724102723464 22.22897505568987 +4.875085007272487 -2.394212546339785 0.7720558327205095 +4.529464743066094 -2.826079446414933 20.53975242572834 +1.576208834675462 6.019742310412576 20.68761619325515 +6.567990985529234 1.364524872602584 22.29596591483079 +6.330826295196401 2.61098477018519 22.20735133698906 +-5.500376620533151 2.846040710440148 12.37351451523077 +-6.81367724606501 -1.595283356013319 22.01791142966022 +0.6258273026815669 2.238387213579668 0.7591871163551822 +-0.6258273026815674 2.238387213579669 22.24081288364482 +-3.26734893197829 0.267605753382371 0.7922682185602139 +3.267348931978289 0.267605753382371 22.20773178143979 +6.774066384512124 -0.9596372804773372 4.797345814484645 +-2.52000433684076 -1.663617660283904 22.25495509170661 +-3.464316303685097 5.799680384042645 5.48825091928734 +1.23804104619051 5.549825490860346 0.705035491046738 +-6.407663515071201 2.06727762670576 21.53913875141599 +1.061697384682484 6.12082217517628 6.121403351528479 +1.718141421618493 4.131288235113479 22.32433771343072 +-1.853335200601599 4.226638299749939 0.7754612922123076 +-6.789872345777021 -1.343909359251339 0.9126859289637 +4.49875515455956 -0.2002570854072867 0.7131304459589159 +-4.49875515455956 -0.2002570854072867 22.28686955404108 +6.728870357128065 -0.1352578521730506 21.32456371107543 +-3.883532357322202 -3.303633506156751 9.417890894430766 +4.478740865383357 0.9304720898650566 22.21292431577753 +2.98797200953724 5.537577821991724 9.887877426503513 +1.953803712362123 -2.759831811928067 3.979562565547413 +-5.639770393618138 3.708728376626973 12.89245735917394 +-5.702874138055174 -3.219565168846654 1.787360248673312 +-4.676932910557529 -3.214814462927302 18.21099373767639 +-3.839170181201787 3.017722725460588 22.23928711594911 +-6.618241513773426 1.44528187734648 18.01693927827151 +-6.528914527470369 1.692861966413922 15.48464904808818 +6.105744743744846 0.4544607285449393 6.64927604614398 +-2.858379544786865 -2.726649105901438 1.546469515875468 +3.987110984606871 -3.347564196863182 3.347489680400312 +-1.016611335884045 6.658100418695233 17.48071478609218 +6.343611426738026 2.439842644642169 19.32338927246293 +0.001808773057302093 6.215549254802646 7.869670221251827 +-3.340396949020969 -0.1851381195647216 22.25444334110435 +3.34039694902097 -0.1851381195647222 0.745556658895649 +2.229519524152513 -2.176248380471583 22.24143287305711 +6.059815253926089 -3.167692711641094 0.7551836769535395 +-6.755060043844865 0.3868239665373266 13.79619482631444 +6.778683584084376 0.4259611188344093 1.699822681955974 +6.746572193434649 -1.443551273295263 13.43432350083852 +-0.3147454660448287 6.761404335194314 5.785615121301691 +-2.004898242119925 -3.235227947058729 3.801885321657755 +0.7004154988563515 1.408903523897757 0.7482828265502629 +-0.7004154988563519 1.408903523897756 22.25171717344974 +-6.478743860725695 1.953824892869197 1.452187911064899 +1.033122608192069 -3.280554662226976 7.548398518997051 +-6.041208393129335 -3.059221561288453 4.798491543150429 +-5.834293947989602 2.275654547005698 10.76255124347817 +5.921185076222197 1.942679918381104 5.302355874331409 +6.065494744634139 -0.9999999999999983 21.4603295549721 +-2.054646022690149 0.7173312502025796 22.21754115549962 +2.054646022690152 0.7173312502025787 0.7824588445003811 +3.228278872584426 6.063033957795676 16.75295910108091 +-2.28679378034764 -2.691879092832199 6.274525385910008 +6.806542228562058 -1.629109005053527 16.3119889726694 +-3.147396211852962 -2.741783108182045 18.4319925412019 +-6.144285184982532 2.892989785408549 4.848892931293485 +-4.120973443369715 -3.321931063846206 12.28965902071831 +-0.1358600579391402 6.799143043812341 22.31729009465042 +-6.201278720937408 -1.374054922682119 11.86178208859902 +-1.872131469456123 -2.669573108335666 11.85873975112965 +-1.787870535298039 -3.223993044650398 17.94708510927927 +2.895307975252075 5.505179337669139 18.75980500355936 +1.645475962438293 -2.668195016151365 20.22954307056137 +-4.330738652808235 0.9806022111368684 22.26061831033456 +4.330738652808237 0.9806022111368761 0.7393816896654415 +-4.118098564164177 0.4095886492035326 0.7087753325195293 +-4.05692722922343 -0.4104416587783464 0.7821011944571779 +-4.4529078627484 5.08077829359561 21.72667729903591 +-1.420526187357618 -3.260114072341399 7.489926955328822 +1.752739850155536 2.505283667229307 22.22463653684514 +-1.752739850155537 2.505283667229306 0.7753634631548558 +4.38405552179035 -3.311176386689918 17.01759406827312 +-6.203388723096198 -0.05874069916753236 11.45311708394527 +6.809546170753707 0.2037882696120184 6.961844141804779 +-2.068235770242472 -2.761113368219566 5.2995949895513 +5.227288252868305 3.988697326828848 12.99047706033702 +-3.984970007420344 5.50577105913295 2.879488249976285 +6.216895495406976 -0.5705982799959333 3.608958803298095 +1.454263051347921 6.646575977735571 1.383500801851033 +5.887321378024694 3.477546749723092 4.885812010362029 +2.134232522404401 5.787932714604976 16.53641745919905 +-2.028295037143931 3.573561207914816 22.28493500052227 +2.02829503714393 3.573561207914817 0.7150649994777246 +-6.220711885025237 2.736705377174808 7.55812155617593 +2.676359071524956 4.771082754637782 0.6788437135639627 +-2.791984364066578 -3.296449475884634 9.502879165086883 +4.120312567473993 4.605281509923335 21.22845110700454 +4.372097603885893 5.081570620106358 20.66162599841819 +-0.3331511871802673 -0.2147498965406997 22.24985553205847 +0.3331511871802691 -0.2147498965406982 0.7501444679415273 +3.326406832437662 -3.319510435183859 17.56873321136051 +-6.796489469437447 0.2065909457214656 19.75743979072574 +-6.07529565415918 0.852654554220913 3.416310636589348 +3.684033755070432 2.891601555819365 22.30253396629098 +-3.684033755070431 2.891601555819365 0.6974660337090176 +1.515832699363564 6.076108406976893 9.86795016126241 +-1.748641675175481 6.433241079437829 15.10084467585912 +-6.177128276894067 -0.1510099238586501 4.187614077319424 +4.890656874785917 -3.326660677557842 19.23692214169985 +-2.630363775573802 -0.8456267201561436 22.25597050032706 +-6.712161349339498 -2.357290918206259 15.70255280423074 +-2.157854817824264 -2.625703931401108 14.3454919347895 +-1.81239067961231 -3.209205149278057 10.62634719280497 +6.759311479242294 -2.350267530283741 15.54320914310648 +2.632258972756001 -0.8342916777894716 0.7403050039049986 +-3.032971151962782 -2.731077158906996 11.61432191066763 +4.563348981742781 -1.6989750725991 0.7769273803351276 +-3.728426680619126 -2.258929296943849 0.750940082996005 +-6.547665207691297 1.993684711823018 22.31267748603845 +6.193474450356358 0.102631782856573 17.37587727839535 +3.298131273722086 5.894009048852641 21.28528320774781 +4.907304923019793 4.610086343410681 13.81529022723631 +0.7981490605138716 -2.224867543450207 22.26100413544718 +0.7347994608946929 -1.425170264039002 22.30096726977657 +-0.7981490605138692 -2.22486754345021 0.7389958645528182 +-0.7347994608946941 -1.425170264039004 0.6990327302234322 +-4.754461158271715 -3.303531680294271 10.50990522393403 +-6.746071177507209 -0.2035840602108222 6.755033284618571 +0.5466661763983195 6.81159409958312 0.6397462185267491 +0.3728578971930854 0.1684789201163756 22.21733183959849 +-0.3236887195028945 0.6068654119780964 22.19948544314985 +-0.372857897193085 0.1684789201163732 0.7826681604015142 +0.3236887195028925 0.6068654119780973 0.800514556850155 +-2.614475466294861 6.235069368666665 22.28028557764987 +3.772644884797282 4.298119940054869 0.7917543523344184 +0.6217565704732679 -2.700009256650002 15.71950369494932 +-4.360885783984257 5.132169444835726 4.079632652295254 +6.77053002334961 -2.053002131846025 0.6828024775193149 +-4.784541665854437 -2.682294589671074 2.609856267693639 +-6.52466979777566 2.002215640918593 10.65546902961481 +2.083919173295065 6.47684278883788 18.80558706263463 +6.099521475201772 2.880034326820181 14.49917300802623 +-5.089538093955477 3.516024921655209 9.680854993047658 +4.416423065419154 5.256826009712732 22.31019012150987 +2.064996081283054 -3.240760754013595 0.7231891079583121 +-2.064996081283049 -3.2407607540136 22.27681089204169 +-3.996508190892353 -3.239581293807297 21.28692506730817 +4.623195626656753 4.145489300517291 4.811014178572362 +-4.613144266310571 -2.685700741456276 15.00657088141633 +6.021327841973322 1.559479400224837 15.60851937287756 +3.916103398708176 4.842832842738877 18.1819731754672 +3.905445286463533 -0.3632358350146416 22.30352719291414 +1.295727390807778 -3.328223533004144 5.619837444541947 +2.062786287247563 -3.378221129904242 13.33171117043098 +-6.608638612004541 -2.419179173686016 2.62649545167287 +-5.924472479776605 1.652516597953234 5.266273070432299 +-1.887965488909062 6.542513650533661 12.07166669443559 +-5.850563755523278 1.945075311236214 6.417279003160618 +-6.056218086066112 -1.000000000000002 21.4603295549721 +6.218341211737275 0.2947696240282794 7.646747405970998 +-6.459441991600179 1.873577683343861 0.6985488989276705 +-5.896260496081645 3.367610867630034 22.25389609683371 +-6.524541298576811 1.984378605325542 17.36526986506772 +2.089380476666918 5.817765172384491 8.776089278707264 +-6.69654312621223 -0.3534173470381777 22.36461137914586 +-6.597921119841704 1.873605794449979 6.098456718216933 +-0.3038130793369829 -2.674933449795839 19.83619482169808 +1.600685009442289 -3.315050554330653 8.739020654095665 +6.810996104362827 0.01109486174681697 16.00832374998528 +5.429096735753555 2.915537292805251 2.726877094248907 +-4.536426934105455 5.039979879776293 20.38541533112753 +6.529168472537365 -2.812459145217465 10.74685941267321 +3.276302496805385 5.883285070031659 2.753158055046619 +-6.280115571150856 -3.057670895985671 20.41090042025321 +4.191183832841592 3.604891802767796 22.26521456034331 +-2.357071265574937 5.707899184687554 7.358216972110747 +-4.659192132040336 -2.74540723613374 8.086516040673391 +-4.359537406168187 -3.233713056095103 7.558381841938096 +-1.812284671233945 5.306824381055442 22.17527815670089 +1.332584352408367 -3.337918044295794 16.51784207944053 +-4.50299416920615 3.060834021558654 0.7266060046965026 +4.250681599127148 -2.194690379796552 22.26408647705519 +6.790330264949012 -1.454287566249034 3.037460502603276 +-6.79388591208328 -0.5223159841419375 11.10795583640445 +5.813903232637191 3.630899811691406 2.951224313945717 +-2.569505943158851 6.318595009137399 20.86639164259016 +-6.210615867046825 -1.372691761638099 3.691062185228279 +6.071490286011255 1.240742138003489 13.14361378438603 +-6.094366664783171 3.02938507282543 5.862157064665285 +3.80765001740089 -3.317328284552084 15.04654452694809 +-2.479645849759478 -1.58413229085495 0.7925153263141351 +-1.667132372374256 -1.69316653082439 0.7211070696720659 +0.3057256282683524 -2.686535178664694 14.30544599180482 +5.117285055103889 4.374800068221727 21.50257986930001 +0.8714207559896285 -3.283852804383175 1.351215524741306 +5.709104255273293 3.541774177085893 22.26389930167399 +6.176995299291754 -0.252882815757036 18.27118862322716 +2.724658134794536 6.322598442427175 19.85356878775247 +1.592067874712296 6.549060159528273 4.611857055927863 +-4.133622460810614 -2.731114694672807 1.797925892417286 +6.672728022821711 -1.822827969381505 14.89004831000788 +-6.10423493784938 -3.07156823869274 8.605342975379974 +5.861921595469516 -3.240440420694612 22.27737898183576 +6.915837477601097 -1.130431206831582 22.32388735219568 +-3.276080171995579 5.986561078834024 15.07273077074074 +1.619333979684166 -1.654224443440067 22.27745946687355 +6.78484064324026 -1.211378490377865 7.334197882197882 +4.048810065105528 -2.696217986628044 5.220942411502152 +-5.616118216165334 2.730935526595824 9.066904455109238 +6.14832106444099 -0.3610101977159634 1.743622482241339 +6.806769897922032 -0.3367331554673698 1.388788624764569 +-0.493155540570092 -3.257054586683612 3.494371467763542 +3.296230583288958 -2.707853543740274 11.27293257149883 +2.378457092075147 6.382488740591199 21.90931843143562 +-4.548877637906164 -1.717673836426301 22.21126990547861 +3.738429091538297 -2.619264490922233 9.209650038899051 +6.295692406661718 2.562478461272088 0.8489274298766284 +-2.477705461606164 6.3709968623586 15.92687728630876 +6.143108744613074 0.446730475177204 21.33656609422583 +2.528385346206975 -2.636354767734939 5.090835495095366 +-3.009609891537001 -2.621645584182757 12.45619288257581 +3.651200819331594 5.190806843893788 4.649237682971861 +4.691937638822473 4.854772066467641 12.41601870056406 +-1.898797728489112 6.491141789765075 18.46854538057005 +6.053656797179921 -3.13769211004409 3.677211565701208 +-1.210881056386508 -3.324544685770905 4.518323491136459 +-5.890851492020873 1.748309356753574 17.6655606252892 +-6.774034647746632 0.7838227730177129 0.7414710597361118 +-6.14097821625734 2.629519870665471 22.3382403183105 +-5.568029755600558 2.584553852230897 7.222086370974564 +-5.478221734628173 4.036665621477024 21.94990740461931 +-0.9272411338101475 1.401058174918377 0.8128861195708356 +0.9272411338101474 1.401058174918376 22.18711388042916 +-3.575181590046617 1.197127027351794 22.18396813204292 +3.575181590046617 1.197127027351794 0.8160318679570829 +2.878731415022688 -3.332776911060482 3.897309849190096 +6.719514237948012 1.367249865121323 4.295516313571547 +-6.400772815917298 2.39491119843853 2.275512843326511 +1.462609513298223 -3.35523949140509 20.44960376697578 +5.788850684156199 -2.248902144226785 22.38471967570266 +4.163962358259683 5.413887901498629 6.381845152124639 +5.052323067647142 3.689937494233014 20.47612176142529 +1.634369209627226 -3.302865847810939 3.539573902003098 +-1.15894670852424 6.036390096186591 12.99302557621957 +-5.200297039116522 4.392997864417975 19.43425531326718 +-4.752012692556079 4.828946582108657 18.98340753826627 +6.766257236463905 -2.340875038417744 14.0153963625756 +-3.182232279353126 5.987999519892769 19.85815829920963 +-3.953591754958714 5.528407894708128 1.731316927256413 +0.1832384002380195 -3.327840295856065 16.94350584605635 +-0.3342941477909047 -3.349193713711941 17.45990537557261 +0.7459325892830453 -2.655889656898915 19.02710291363983 +-3.705154462117484 -2.695854914822029 18.94815792594722 +-1.871445057985774 1.743998128981046 0.7161084047781823 +1.871445057985771 1.743998128981046 22.28389159522182 +3.097556277907016 5.271592914282615 15.83039205595787 +6.12787880889075 -0.6359427125577557 19.24256766507349 +-4.583462546156025 2.22396713251904 0.8166481628100584 +-0.268885800608847 6.851962885714737 9.201103300716934 +6.414847143064693 2.117188269769183 11.08513697753672 +-3.256834671595646 5.258734867829527 3.021665676461642 +-0.5993411023121917 -2.635099127935229 16.19269882384929 +-2.704462325242656 6.276543801080325 6.117343521778903 +-5.756025574150777 -3.255419320898485 6.894341883482802 +2.691978584045351 6.325808059052331 15.70144392451786 +5.759016102708218 2.150695933383809 20.68520711110949 +-1.049575033681824 -2.679349152173819 11.88587692071564 +0.3784829641311678 6.120304856713964 9.328178745487529 +-5.185789995866118 4.384346521035319 10.92939793001959 +4.007604074808894 4.690654792505271 10.21157620822725 +6.142730776266463 0.3037631408189197 4.091432684343028 +-6.832607966021657 -0.9156784064302026 14.04310080118785 +-6.681078143664147 1.08897316770719 4.017501367036089 +-4.592153045074559 -2.698991916396163 16.75196433418368 +-6.253857367489621 0.03621212497112514 9.046590895831899 +1.135860850594961 6.128963345429302 17.35647199189579 +4.011436855858158 -3.251087387661985 1.701755049502067 +4.668693928930042 -2.65019076782545 19.03161612833724 +-0.8966130398216476 6.726923319631592 16.35263248762246 +-2.918750524718421 5.413895189504448 4.931649731845568 +-6.535551473941669 1.813551873920793 2.825876630048685 +6.83228217943898 0.7155424378239684 16.21613025822814 +5.038056607387482 4.55065063743406 0.9191792654004227 +-0.4831539378549 6.129744228041755 19.14273352907622 +6.159345673052209 -1.019190674938919 4.361474186842903 +-6.14353664058565 -0.4332109809066687 1.257472083313182 +0.1086495426163356 6.806137987745651 12.37139411875089 +-0.3366217184168949 6.191517914860984 12.40796468914272 +-0.6765897289301758 6.746754937714352 2.720704817196753 +-6.702895398069723 -2.136815362997937 22.40145348531551 +3.673357919194938 -2.752177186098619 12.6951033591933 +-1.439302296615292 -3.358412717571802 2.546048618029752 +5.402261971297303 -2.733242984759747 2.465980029095983 +-5.98822539596861 3.44335387569774 8.195359988347365 +-1.376751939526726 6.671754713946086 21.78803236971783 +-1.871807889684815 6.550802164209245 21.23875396085423 +-2.931522564129333 -3.340198437596015 10.57297833516379 +1.941370388369909 -3.337469287491837 17.27202787949561 +-3.496234777953247 -3.285967900612274 4.111572926135126 +6.405270173889662 2.51411967982783 5.722030366073682 +-5.779457401155833 -3.246893741463786 17.2552708465792 +5.991440220892653 1.570884427753073 3.280294822458113 +3.03617567416958 6.048041199151534 17.6339181924896 +0.02110544993099082 -2.653885077223212 11.99044810819925 +-3.728893859311019 -2.620454487741398 10.4528797792103 +-1.279990247069513 -2.669794448940697 17.9945899566271 +6.471601965089745 2.105571262652513 3.049073718195835 +3.449238166943246 -2.679042209002445 15.92197471382112 +-1.722513875618689 -2.58515632447998 3.607649607798215 +2.255854551637109 5.696917837252605 20.65209857349312 +4.370380991142872 2.513643509699481 22.32215990963284 +-6.760871971749468 0.8531469981764905 22.25036714957238 +2.14644274458965 -3.337352814055524 8.260906279599068 +-2.743878181327602 4.525458441700891 22.32571777397831 +3.646947778047056 4.994208076976346 11.54355914632139 +6.055192098923647 3.143279600571566 2.417791548202976 +4.953097568832504 4.728523614467263 15.16359813543785 +4.370127067244108 4.32697431202791 15.13487025303877 +-0.7277228032163554 6.764051017189413 18.73549839614222 +1.329304660689039 2.835599969364309 0.7528169314593695 +-1.329304660689039 2.835599969364309 22.24718306854063 +-4.696682801033194 -3.335574629801823 14.62833340466537 +-6.7434291004947 -2.26786967166037 13.80296714342436 +1.064546425116321 -2.668074906488712 17.92197875652036 +-4.658020695676192 4.100012019223172 4.528879275274051 +5.907632266770507 0.009283482898075096 0.6452901677723508 +-6.835380109337813 0.6299797596801738 15.52030735836401 +4.725546407212748 0.02401568688604155 22.26010907366086 +-1.868261476535162 -2.537463174578321 22.34681910292455 +1.86826147653516 -2.537463174578321 0.6531808970754502 +-3.923182820702478 -2.646472554206196 15.61913996361747 +-5.363178404909704 3.061100219242105 4.661142758274837 +5.592826540231938 -3.281335718588728 20.33411760307023 +-5.514971819814221 -3.304642349529674 19.66839654569748 +-2.940830866737521 5.387846395787695 8.022242368725776 +3 2 0 245 +7215 +7216 +7217 +7218 +7219 +7220 +7221 +7222 +7223 +7224 +7225 +7226 +7227 +7228 +7229 +7230 +7231 +7232 +7233 +7234 +7235 +7236 +7237 +7238 +7239 +7240 +7241 +7242 +7243 +7244 +7245 +7246 +7247 +7248 +7249 +7250 +7251 +7252 +7253 +7254 +7255 +7256 +7257 +7258 +7259 +7260 +7261 +7262 +7263 +7264 +7265 +7266 +7267 +7268 +7269 +7270 +7271 +7272 +7273 +7274 +7275 +7276 +7277 +7278 +7279 +7280 +7281 +7282 +7283 +7284 +7285 +7286 +7287 +7288 +7289 +7290 +7291 +7292 +7293 +7294 +7295 +7296 +7297 +7298 +7299 +7300 +7301 +7302 +7303 +7304 +7305 +7306 +7307 +7308 +7309 +7310 +7311 +7312 +7313 +7314 +7315 +7316 +7317 +7318 +7319 +7320 +7321 +7322 +7323 +7324 +7325 +7326 +7327 +7328 +7329 +7330 +7331 +7332 +7333 +7334 +7335 +7336 +7337 +7338 +7339 +7340 +7341 +7342 +7343 +7344 +7345 +7346 +7347 +7348 +7349 +7350 +7351 +7352 +7353 +7354 +7355 +7356 +7357 +7358 +7359 +7360 +7361 +7362 +7363 +7364 +7365 +7366 +7367 +7368 +7369 +7370 +7371 +7372 +7373 +7374 +7375 +7376 +7377 +7378 +7379 +7380 +7381 +7382 +7383 +7384 +7385 +7386 +7387 +7388 +7389 +7390 +7391 +7392 +7393 +7394 +7395 +7396 +7397 +7398 +7399 +7400 +7401 +7402 +7403 +7404 +7405 +7406 +7407 +7408 +7409 +7410 +7411 +7412 +7413 +7414 +7415 +7416 +7417 +7418 +7419 +7420 +7421 +7422 +7423 +7424 +7425 +7426 +7427 +7428 +7429 +7430 +7431 +7432 +7433 +7434 +7435 +7436 +7437 +7438 +7439 +7440 +7441 +7442 +7443 +7444 +7445 +7446 +7447 +7448 +7449 +7450 +7451 +7452 +7453 +7454 +7455 +7456 +7457 +7458 +7459 +-5.421953879588722 -2.186139171828373 -1.509709376747846 +5.982008257705705 0.03766993299152924 -1.507537665905594 +5.741249294355017 -1.877445939777433 -1.509401227558004 +-5.886960036800951 -0.7218980011567596 -1.501680874425559 +4.585597613956262 -0.887373997161794 -1.483520903327961 +-4.255855165250007 -1.193118746805837 -1.497482712276241 +3.159072540780759 -1.449369735189667 -1.495224574034669 +-4.703973221712292 0.48854114829679 -1.50820612377955 +1.257088241106894 -1.316820956074052 -1.500544032074163 +4.336912286950755 -2.348735433462847 -1.435692465244198 +2.542017517189152 0.5089232017546385 -1.516110230763817 +4.68510492109473 0.474388220584105 -1.670055000753453 +0.2240559384582768 -2.445227906331018 -1.517213677318163 +-3.242648571964831 -0.002359252526177635 -1.493299289025745 +1.570522712676566 -2.643045732648299 -1.358645918975014 +-1.952695433514209 -0.8402432229054052 -1.500552062755026 +-0.2186812954371161 -1.003045075378037 -1.495577668063545 +1.045023704404846 0.1975402931418401 -1.498319242886841 +-3.260144469464604 -2.36010086070291 -1.522825826228377 +-1.737860766324343 -2.347615872584033 -1.493221220077321 +-1.840242693713671 0.6009330717809089 -1.582157921394612 +-0.3941619619975072 0.4471825581804719 -1.428190419330591 +-6.079474101850105 0.5001905375297671 -1.752512052029209 +3.593765887716759 -0.1581386072402292 -1.779422879504268 +2.875535853844602 -2.711951220705342 -1.305019400703759 +-4.402391400790229 -2.81092395612945 -1.226547924737803 +6.367337735177919 -0.983828696842284 -1.132913221777036 +-6.366490473298938 -1.678022970929204 -1.892258700860472 +5.563145526130793 -0.8582258458500096 -1.945750230443704 +-3.075622074933569 -1.201101054015223 -1.200705344579225 +5.320960189324074 -2.903106949790912 -1.153354042624968 +2.258098283275256 -0.6537234347689854 -1.207608418278653 +3.678579854494565 0.856995557376764 -1.167947018588991 +6.533380379521378 -0.5939236682487006 -2.018692416541581 +-2.824952222975291 0.9228275099173318 -1.047408310700207 +-0.7391194073876324 -1.946219307827538 -1.882686579827372 +-4.492170052026596 -2.09091904318171 -1.981025560871238 +6.522716824987193 -1.58059450882252 -2.033853949569609 +2.176741743359571 -1.848300948339431 -1.884543805412886 +-6.561014442454452 -0.3748369633435181 -2.077877673117325 +-6.374622226447565 -2.343205286157839 -1.060918726166272 +-4.930945190984337 -0.4753527287341311 -1.95387072926543 +5.611696870371762 0.9506160197214644 -1.941880133217597 +5.941555526566728 0.9046845527743852 -0.9851607434407373 +-5.172844976015708 -1.303970727308936 -0.9767939753827557 +5.094351904497227 -0.2234401434787802 -1.050917249814126 +6.355260095052179 -2.558466011122138 -1.003812919545298 +5.991436552023677 -2.802174831363343 -1.974538655238915 +-5.012015760808274 -2.956456444726903 -2.019023032682261 +-0.7789081501475124 -2.894182410614353 -1.279563391903861 +5.410286644456341 -1.106742726129245 -1.018976376675652 +-2.485689259390288 -2.968554492762995 -1.933370673167676 +-6.60890452343945 -0.679758088556098 -0.9185675847481162 +-6.494744716717971 0.2849818172238218 -0.9008639503598461 +-5.781141325053708 0.972228887137265 -0.9334999666205136 +-1.03630280453013 -0.38331026190655 -1.094700224539862 +4.930957479655463 -1.638859562026431 -2.066243215766814 +-2.495256180372497 -1.719097801638974 -1.968361310705683 +-6.169625865795107 -2.672067708277251 -2.003873963628088 +4.807908516407752 -3.039981248376169 -2.03424126366819 +1.679076246404837 0.9311354952317139 -1.022315048308372 +-4.627756879505968 -0.3883097992957974 -0.9735440203928895 +-3.739424370475323 0.936397041893535 -1.597346436765013 +-5.631728416674155 -3.019735433816634 -0.9837300405937675 +-4.912467951079987 1.111390848465977 -2.141678518156125 +-2.354571939558281 -0.05159509340635007 -0.9706666840810115 +2.231120352134524 -3.052978497098612 -2.011190306836725 +-3.65838671545264 -1.639431240268336 -2.093796137556929 +-1.190899837080784 -1.447531088407632 -1.042194101486054 +0.4538190105452132 -1.476312249701697 -0.9383404674541613 +0.4161991016072929 0.9745900884111836 -1.922288690483435 +-2.744656476510793 -3.016248887237357 -0.9645771222609147 +1.029948286673851 -2.137837143502953 -2.057523375817063 +4.129688781722632 -0.1908724113943337 -0.9476601824499165 +3.487038973698129 -2.275930918161906 -1.996098417783948 +6.535784171460977 0.4168418399643008 -2.13666272565243 +0.2532079109374031 -0.2331709681364156 -0.9678506003256973 +-5.180437514094075 -1.409282381497272 -2.038699227533363 +4.978433898350824 1.050088201989433 -0.9397573909595878 +1.62067043685479 -0.4931418972425697 -2.00018836997701 +0.6301331765646838 -0.6320159298263539 -1.888884216261045 +-1.01077100969455 1.042771794082056 -1.986806571688668 +-1.115713110822006 0.04667645586956165 -1.99586964954758 +1.44086934219314 0.990622198876096 -2.02227627253018 +-2.694196168137502 0.8615049750629418 -2.040615018098539 +-2.397948290857877 -0.1090709729582068 -2.045475112480108 +-4.055867259271043 -0.01970853752189887 -2.062020436579961 +-1.089221864004143 -0.9756169066637557 -2.032748366283094 +3.220583290624675 -0.6063951400213229 -0.9789971933406766 +-5.557376789380099 0.02346186663938235 -0.9658721973490835 +2.833595240230251 0.9336108224141295 -0.8114829340066485 +-3.959334866353379 -1.961244310471437 -0.9185258981898115 +3.988272270465968 -1.452288555611188 -1.987280070101977 +4.009396056943758 -1.52633172041475 -1.006533748168479 +-1.123396624010379 0.9887891688135599 -0.9829202169239046 +-6.14955517349322 -1.459540489499071 -1.03349494044125 +-2.511421798555336 -1.97788381016601 -1.027980708759312 +-0.1981468490022275 -3.069810170648788 -2.115558016306196 +4.800757575757579 1.189664917502204 -2.147868457300276 +6.574666130416579 0.2586852831837591 -0.8462042748977717 +0.7864775215481812 -3.094166137198983 -2.054104952215994 +-1.365119050552607 -3.06823264318579 -2.051680856303472 +4.873769923015439 -0.2959269104507831 -2.102501348868699 +0.6835214307388265 0.9566931440964004 -0.9611752024416949 +3.852887024782842 0.7209616033243615 -2.120540179305421 +1.908664570355187 -1.808518524874126 -0.9205770567021446 +-0.4555124111355225 -2.049916940893246 -0.9791062983997035 +-0.2151452984189823 -0.2393229242903662 -2.055077010755316 +3.607627336683375 -2.351895140125545 -0.8586521689075748 +-4.892936986300448 1.115085028553345 -0.8893355544271828 +0.7644545148969031 -3.025003803257142 -0.909867861560493 +-3.9664180769601 0.2799178620319548 -0.9637037987561832 +2.652002297755708 -0.3185456563584714 -2.057636188652151 +-3.111439057295971 -0.7730539075776356 -2.0761339006306 +5.026897718640209 -1.981777430077178 -0.8650557165350659 +-5.304783362440446 0.3101137058379263 -2.152253631860308 +-3.897187859655059 -2.883155049088495 -2.081729172764932 +4.187428598635405 -3.092301446372594 -0.8793095568602903 +3.889292039499681 -3.115740772777414 -1.785868863490967 +6.70677129714154 -1.785015621864736 -1.205194671233602 +2.983899746611685 1.097294941990305 -2.11225873933809 +6.018296575981228 -1.61631813491238 -0.753903919779398 +-5.42195387958872 -2.186139171828374 -2.282977771572001 +-3.74311646847186 -0.6046106096955781 -1.025439265866655 +-1.628926860030155 -3.070517276715997 -0.873486324518139 +1.646320831707852 -1.311800157149936 -2.236362240334329 +-4.226602862836966 -0.8142612368747505 -2.23682991138316 +1.340651037544398 -0.5338958893088598 -0.9510632811831541 +-1.993560190887245 0.9633253987263608 -0.8117268017563888 +0.2022315609619869 -1.654594393054074 -2.058565655666916 +2.640268909656636 -1.331645855028506 -0.7905699138715505 +5.452209783025402 -2.245015662699283 -2.227236343747831 +-1.607416928115748 -1.706345894770642 -2.109814606832651 +-5.73680726180659 -0.3823433111810364 -2.232992652056364 +-4.831826880708455 -2.114511894242384 -0.8492961046524248 +-5.663327586426893 1.207466307995777 -1.818106458191436 +5.885546026198376 -0.3976534509909492 -0.8171706314174531 +5.546861792187785 0.1694508198551564 -2.194043628414072 +-6.769216376219905 -1.022311120953904 -1.636032332762519 +0.9960103647011945 -2.172229901126592 -0.87899769169437 +5.817456345953098 -3.229796469287929 -0.6886204386225782 +-3.603054450633696 -2.797899653293623 -0.8180234309414345 +1.847711145751879 0.1098698794531145 -1.206828424715132 +3.08597850055508 -3.029837350859408 -2.073004605503366 +6.743895542157889 -0.02728819006962272 -1.548601341744529 +-0.3727838048022702 -0.7186578062133706 -0.7362502591780196 +-3.248376945493158 -3.209151402116384 -1.62890577684302 +-1.835114012180053 1.21485016053951 -2.195001167664864 +2.636695091821228 0.02003077068123854 -0.7957352267563568 +-6.169432461186274 -1.017888459378676 -2.233540204713133 +-0.06681858478753706 -2.821993162477734 -0.7972472617734885 +-1.565986243369839 0.2363065252626174 -0.8703675444631358 +4.252336118687554 -0.760340601528317 -2.276351265623633 +-4.029953716624813 1.129977044413036 -0.8033185375587867 +-5.647422117989402 -2.259875742714851 -0.7511108527974822 +5.777740800982749 -1.539808795997626 -2.251120801907954 +6.732074831964989 -0.4699669338448313 -0.7129289235849802 +-1.998361825572694 -1.340506621302151 -0.822924220076906 +1.908855239127502 0.2943824343263277 -2.022902881519186 +3.300277520058047 -0.8895422893741691 -2.143556781983511 +-1.222557650279345 -2.343764798650345 -0.838244137599834 +-2.978434979960211 -0.5305531871148399 -0.738948263534454 +-5.847206485564422 -0.7980978313427949 -0.6920819969444275 +6.640923437252837 -2.347895097638135 -1.789409424369451 +2.717981887914969 -2.327247335565535 -2.261919826560013 +3.433649752629436 0.1927132458909295 -0.761947196596505 +2.180603312205779 -3.106918007038065 -0.8511546620215628 +1.240174852096264 0.3272454044674665 -0.732579895566748 +4.326189984963883 -2.142766133896278 -2.208605259227927 +4.523277029743601 -0.8165567456210712 -0.7140668858984988 +2.135458135993799 1.20993975482585 -1.644569170924099 +6.527843874982796 0.732781745544099 -1.442195686029223 +2.507848398172181 -1.098730182790852 -1.849710573541253 +5.379170998883509 0.4903144542198378 -1.323229407659243 +-3.392847528531264 0.4510287043152763 -2.158398604541768 +-6.335144336482399 1.007824168288712 -2.234686279887856 +-6.763567794778551 0.1929604954528524 -1.609457790475176 +-0.2744677404802893 1.181879930523843 -2.276193442311358 +4.363590838701112 1.194740435281049 -1.457804383393767 +-1.754374846011698 -0.5431121497250828 -0.7881469062859517 +3.353685534559181 -3.150833541248379 -0.7664629492268056 +1.506988034046713 -2.769186687566697 -2.263823209240702 +-1.909811261107103 -2.496241082424113 -2.284759795213582 +3.786742966660579 -0.8718732286389739 -1.476434470349451 +-6.811857207161078 -1.754254635878249 -1.27578368030468 +-3.097463613049216 0.2444455716479689 -0.7629728027655005 +3.13225767967954 0.3087232978606758 -2.265676313046901 +-1.697466032073124 -0.474514859568084 -2.163275429393146 +-2.337694019093079 -0.9627910779373713 -2.197876135161566 +6.276051388386747 1.089940565257229 -2.192634102279525 +0.2525595773995978 -3.240683015528129 -1.481104429307496 +-0.2034360347137285 1.119087071042622 -0.8464786544403925 +1.171935088082283 0.1095834106984712 -2.288037991793226 +-4.718479681200617 0.35928413743714 -0.7263356038138483 +-4.456084227045735 1.229958773603044 -1.522816593814925 +1.470992917221329 -2.961301182600884 -0.6974465117830383 +6.879077341405717 -1.097124875295724 -1.631123827021409 +-4.307104937955059 -1.084521985332752 -0.6958582564917456 +3.084641416575072 -1.634853297422169 -2.252843834309953 +4.331034001020427 0.5809308368468603 -0.7529465095471761 +0.4418667567962434 0.1918439090494186 -2.004570050010912 +2.623585946750765 -1.969541886430719 -1.249428357468928 +-6.835030539118232 0.2315842588914571 -2.309310648805345 +4.353599741121313 -2.370636675840474 -0.6653446688772033 +-0.1642584763498149 -2.308380272895444 -2.255268474998109 +5.107775616986511 -2.293558802014937 -1.552475026618406 +1.212304381562659 -3.309534040952415 -1.458470690172708 +-2.681329257558949 -0.5643443680956206 -1.459568434771987 +6.16285559472759 -2.147243528787433 -2.295983275761154 +-5.727623336552092 -1.547983886967556 -1.60215416514176 +-5.818820169768141 -1.614255054501406 -2.318660436265208 +-2.902576383224905 -2.355142534363448 -2.242280301399533 +6.224164402572697 -0.1262336972218713 -2.406953177129503 +-0.4687954370937713 -1.353484206362448 -2.301918020063131 +-3.215949161539083 -2.117896208023828 -0.693686576055933 +4.184704389468411 0.03081818402704897 -2.245316478709969 +-4.860896676792861 -1.729510666958948 -1.473024351067486 +-5.694069231144895 -3.248990472797023 -1.740115158317069 +0.8679027777604744 -1.289493384540902 -2.231873172115604 +5.690989749550309 0.288535732335845 -0.7038768060780968 +1.165963028774014 1.337590163282816 -1.406025991069492 +-6.86564570652905 -0.1661291324763015 -0.5895020386761112 +-4.123885564023237 1.194564572284211 -2.250088214755675 +-3.338484927846707 1.311846802490864 -2.175650274232898 +3.320118629582538 -1.662913391558747 -0.7175588005562428 +5.464443789352748 -3.300873763405937 -1.775601566222736 +-6.764506627886907 -2.240040705145703 -2.244843215674823 +1.212508520885977 -1.428147488072883 -0.7182459708301139 +6.033044504397255 -1.272675959763702 -1.660751665871574 +-2.277413083703715 1.241926388285416 -1.502129842880252 +-0.4999729720040666 0.4576504413474897 -2.184770589584447 +-0.4390090844115594 0.06714462179951783 -0.7386710170499603 +6.702238414438753 -2.132482653978119 -0.6048540061892675 +-0.4611126513773651 1.381815991002981 -1.54013847329682 +-3.595348256623069 -1.345036260346714 -0.6673723726669074 +-6.432859150035165 0.9183189614797633 -1.264905798982144 +4.709211731949696 0.4888743744952417 -2.378479115883064 +-6.850009930319612 -0.9526664901857204 -2.316422766922861 +-0.5883153466412387 -1.419513741064365 -0.6052487462500447 +5.498002114644939 1.349281520985198 -1.347213913986661 +3.692798046955809 1.329602260333439 -1.734792578629129 +6.876383606233515 -1.148077017779457 -0.6913015819848224 +-1.970445896957984 -2.409632615567568 -0.7101363220682321 +-4.89375630340431 -3.210708235625797 -0.7348892500826916 +-4.588721451657211 0.4573500173256287 -2.234056713431043 +$EndNodes +$Elements +111 41323 1 41323 +0 1 15 1 +1 1 +0 2 15 1 +2 2 +0 3 15 1 +3 3 +0 4 15 1 +4 4 +0 5 15 1 +5 5 +0 6 15 1 +6 6 +0 7 15 1 +7 7 +0 8 15 1 +8 8 +0 9 15 1 +9 9 +0 10 15 1 +10 10 +0 11 15 1 +11 11 +0 12 15 1 +12 12 +0 13 15 1 +13 13 +0 14 15 1 +14 14 +0 15 15 1 +15 15 +0 16 15 1 +16 16 +0 17 15 1 +17 17 +0 18 15 1 +18 18 +0 19 15 1 +19 19 +0 20 15 1 +20 20 +0 21 15 1 +21 21 +0 22 15 1 +22 22 +0 23 15 1 +23 23 +0 24 15 1 +24 24 +0 25 15 1 +25 25 +0 26 15 1 +26 26 +0 27 15 1 +27 27 +0 28 15 1 +28 28 +0 29 15 1 +29 29 +0 30 15 1 +30 30 +0 31 15 1 +31 31 +0 32 15 1 +32 32 +1 1 1 5 +33 1 33 +34 33 34 +35 34 35 +36 35 36 +37 36 2 +1 2 1 3 +38 2 37 +39 37 38 +40 38 3 +1 3 1 5 +41 4 39 +42 39 40 +43 40 41 +44 41 42 +45 42 3 +1 4 1 3 +46 1 43 +47 43 44 +48 44 4 +1 5 1 32 +49 5 45 +50 45 46 +51 46 47 +52 47 48 +53 48 49 +54 49 50 +55 50 51 +56 51 52 +57 52 53 +58 53 54 +59 54 55 +60 55 56 +61 56 57 +62 57 58 +63 58 59 +64 59 60 +65 60 61 +66 61 62 +67 62 63 +68 63 64 +69 64 65 +70 65 66 +71 66 67 +72 67 68 +73 68 69 +74 69 70 +75 70 71 +76 71 72 +77 72 73 +78 73 74 +79 74 75 +80 75 2 +1 6 1 5 +81 5 76 +82 76 77 +83 77 78 +84 78 79 +85 79 6 +1 7 1 15 +86 6 80 +87 80 81 +88 81 82 +89 82 83 +90 83 84 +91 84 85 +92 85 86 +93 86 87 +94 87 88 +95 88 89 +96 89 90 +97 90 91 +98 91 92 +99 92 93 +100 93 1 +1 8 1 3 +101 3 94 +102 94 95 +103 95 7 +1 9 1 2 +104 8 96 +105 96 2 +1 10 1 3 +106 8 97 +107 97 98 +108 98 9 +1 11 1 4 +109 9 99 +110 99 100 +111 100 101 +112 101 7 +1 12 1 5 +113 7 102 +114 102 103 +115 103 104 +116 104 105 +117 105 10 +1 13 1 15 +118 10 106 +119 106 107 +120 107 108 +121 108 109 +122 109 110 +123 110 111 +124 111 112 +125 112 113 +126 113 114 +127 114 115 +128 115 116 +129 116 117 +130 117 118 +131 118 119 +132 119 11 +1 14 1 5 +133 11 120 +134 120 121 +135 121 122 +136 122 123 +137 123 12 +1 15 1 3 +138 12 124 +139 124 125 +140 125 13 +1 16 1 5 +141 13 126 +142 126 127 +143 127 128 +144 128 129 +145 129 14 +1 17 1 15 +146 14 130 +147 130 131 +148 131 132 +149 132 133 +150 133 134 +151 134 135 +152 135 136 +153 136 137 +154 137 138 +155 138 139 +156 139 140 +157 140 141 +158 141 142 +159 142 143 +160 143 4 +1 18 1 3 +161 6 144 +162 144 145 +163 145 14 +1 19 1 32 +164 15 146 +165 146 147 +166 147 148 +167 148 149 +168 149 150 +169 150 151 +170 151 152 +171 152 153 +172 153 154 +173 154 155 +174 155 156 +175 156 157 +176 157 158 +177 158 159 +178 159 160 +179 160 161 +180 161 162 +181 162 163 +182 163 164 +183 164 165 +184 165 166 +185 166 167 +186 167 168 +187 168 169 +188 169 170 +189 170 171 +190 171 172 +191 172 173 +192 173 174 +193 174 175 +194 175 176 +195 176 8 +1 20 1 2 +196 15 177 +197 177 5 +1 21 1 3 +198 5 178 +199 178 179 +200 179 13 +1 22 1 5 +201 9 180 +202 180 181 +203 181 182 +204 182 183 +205 183 16 +1 23 1 4 +206 16 184 +207 184 185 +208 185 186 +209 186 10 +1 24 1 15 +210 16 187 +211 187 188 +212 188 189 +213 189 190 +214 190 191 +215 191 192 +216 192 193 +217 193 194 +218 194 195 +219 195 196 +220 196 197 +221 197 198 +222 198 199 +223 199 200 +224 200 17 +1 25 1 4 +225 17 201 +226 201 202 +227 202 203 +228 203 11 +1 26 1 5 +229 17 204 +230 204 205 +231 205 206 +232 206 207 +233 207 18 +1 27 1 4 +234 18 208 +235 208 209 +236 209 210 +237 210 12 +1 28 1 3 +238 18 211 +239 211 212 +240 212 15 +1 29 1 31 +241 9 213 +242 213 214 +243 214 215 +244 215 216 +245 216 217 +246 217 218 +247 218 219 +248 219 220 +249 220 221 +250 221 222 +251 222 223 +252 223 224 +253 224 225 +254 225 226 +255 226 227 +256 227 228 +257 228 229 +258 229 230 +259 230 231 +260 231 232 +261 232 233 +262 233 234 +263 234 235 +264 235 236 +265 236 237 +266 237 238 +267 238 239 +268 239 240 +269 240 241 +270 241 242 +271 242 19 +1 30 1 5 +272 20 243 +273 243 244 +274 244 245 +275 245 246 +276 246 19 +1 31 1 31 +277 16 247 +278 247 248 +279 248 249 +280 249 250 +281 250 251 +282 251 252 +283 252 253 +284 253 254 +285 254 255 +286 255 256 +287 256 257 +288 257 258 +289 258 259 +290 259 260 +291 260 261 +292 261 262 +293 262 263 +294 263 264 +295 264 265 +296 265 266 +297 266 267 +298 267 268 +299 268 269 +300 269 270 +301 270 271 +302 271 272 +303 272 273 +304 273 274 +305 274 275 +306 275 276 +307 276 20 +1 32 1 15 +308 21 277 +309 277 278 +310 278 279 +311 279 280 +312 280 281 +313 281 282 +314 282 283 +315 283 284 +316 284 285 +317 285 286 +318 286 287 +319 287 288 +320 288 289 +321 289 290 +322 290 20 +1 33 1 31 +323 17 291 +324 291 292 +325 292 293 +326 293 294 +327 294 295 +328 295 296 +329 296 297 +330 297 298 +331 298 299 +332 299 300 +333 300 301 +334 301 302 +335 302 303 +336 303 304 +337 304 305 +338 305 306 +339 306 307 +340 307 308 +341 308 309 +342 309 310 +343 310 311 +344 311 312 +345 312 313 +346 313 314 +347 314 315 +348 315 316 +349 316 317 +350 317 318 +351 318 319 +352 319 320 +353 320 21 +1 34 1 5 +354 22 321 +355 321 322 +356 322 323 +357 323 324 +358 324 21 +1 35 1 31 +359 18 325 +360 325 326 +361 326 327 +362 327 328 +363 328 329 +364 329 330 +365 330 331 +366 331 332 +367 332 333 +368 333 334 +369 334 335 +370 335 336 +371 336 337 +372 337 338 +373 338 339 +374 339 340 +375 340 341 +376 341 342 +377 342 343 +378 343 344 +379 344 345 +380 345 346 +381 346 347 +382 347 348 +383 348 349 +384 349 350 +385 350 351 +386 351 352 +387 352 353 +388 353 354 +389 354 22 +1 36 1 3 +390 23 355 +391 355 356 +392 356 22 +1 37 1 31 +393 15 357 +394 357 358 +395 358 359 +396 359 360 +397 360 361 +398 361 362 +399 362 363 +400 363 364 +401 364 365 +402 365 366 +403 366 367 +404 367 368 +405 368 369 +406 369 370 +407 370 371 +408 371 372 +409 372 373 +410 373 374 +411 374 375 +412 375 376 +413 376 377 +414 377 378 +415 378 379 +416 379 380 +417 380 381 +418 381 382 +419 382 383 +420 383 384 +421 384 385 +422 385 386 +423 386 23 +1 38 1 32 +424 24 387 +425 387 388 +426 388 389 +427 389 390 +428 390 391 +429 391 392 +430 392 393 +431 393 394 +432 394 395 +433 395 396 +434 396 397 +435 397 398 +436 398 399 +437 399 400 +438 400 401 +439 401 402 +440 402 403 +441 403 404 +442 404 405 +443 405 406 +444 406 407 +445 407 408 +446 408 409 +447 409 410 +448 410 411 +449 411 412 +450 412 413 +451 413 414 +452 414 415 +453 415 416 +454 416 417 +455 417 23 +1 39 1 31 +456 8 418 +457 418 419 +458 419 420 +459 420 421 +460 421 422 +461 422 423 +462 423 424 +463 424 425 +464 425 426 +465 426 427 +466 427 428 +467 428 429 +468 429 430 +469 430 431 +470 431 432 +471 432 433 +472 433 434 +473 434 435 +474 435 436 +475 436 437 +476 437 438 +477 438 439 +478 439 440 +479 440 441 +480 441 442 +481 442 443 +482 443 444 +483 444 445 +484 445 446 +485 446 447 +486 447 24 +1 40 1 3 +487 19 448 +488 448 449 +489 449 24 +1 41 1 15 +490 25 450 +491 450 451 +492 451 452 +493 452 453 +494 453 454 +495 454 455 +496 455 456 +497 456 457 +498 457 458 +499 458 459 +500 459 460 +501 460 461 +502 461 462 +503 462 463 +504 463 26 +1 42 1 27 +505 26 464 +506 464 465 +507 465 466 +508 466 467 +509 467 468 +510 468 469 +511 469 470 +512 470 471 +513 471 472 +514 472 473 +515 473 474 +516 474 475 +517 475 476 +518 476 477 +519 477 478 +520 478 479 +521 479 480 +522 480 481 +523 481 482 +524 482 483 +525 483 484 +526 484 485 +527 485 486 +528 486 487 +529 487 488 +530 488 489 +531 489 27 +1 43 1 15 +532 27 490 +533 490 491 +534 491 492 +535 492 493 +536 493 494 +537 494 495 +538 495 496 +539 496 497 +540 497 498 +541 498 499 +542 499 500 +543 500 501 +544 501 502 +545 502 503 +546 503 28 +1 44 1 27 +547 25 504 +548 504 505 +549 505 506 +550 506 507 +551 507 508 +552 508 509 +553 509 510 +554 510 511 +555 511 512 +556 512 513 +557 513 514 +558 514 515 +559 515 516 +560 516 517 +561 517 518 +562 518 519 +563 519 520 +564 520 521 +565 521 522 +566 522 523 +567 523 524 +568 524 525 +569 525 526 +570 526 527 +571 527 528 +572 528 529 +573 529 28 +1 45 1 3 +574 26 530 +575 530 531 +576 531 29 +1 46 1 27 +577 29 532 +578 532 533 +579 533 534 +580 534 535 +581 535 536 +582 536 537 +583 537 538 +584 538 539 +585 539 540 +586 540 541 +587 541 542 +588 542 543 +589 543 544 +590 544 545 +591 545 546 +592 546 547 +593 547 548 +594 548 549 +595 549 550 +596 550 551 +597 551 552 +598 552 553 +599 553 554 +600 554 555 +601 555 556 +602 556 557 +603 557 30 +1 47 1 3 +604 30 558 +605 558 559 +606 559 27 +1 48 1 24 +607 31 560 +608 560 561 +609 561 562 +610 562 563 +611 563 564 +612 564 565 +613 565 566 +614 566 567 +615 567 568 +616 568 569 +617 569 570 +618 570 571 +619 571 572 +620 572 573 +621 573 574 +622 574 575 +623 575 576 +624 576 577 +625 577 578 +626 578 579 +627 579 580 +628 580 581 +629 581 582 +630 582 30 +1 49 1 27 +631 32 583 +632 583 584 +633 584 585 +634 585 586 +635 586 587 +636 587 588 +637 588 589 +638 589 590 +639 590 591 +640 591 592 +641 592 593 +642 593 594 +643 594 595 +644 595 596 +645 596 597 +646 597 598 +647 598 599 +648 599 600 +649 600 601 +650 601 602 +651 602 603 +652 603 604 +653 604 605 +654 605 606 +655 606 607 +656 607 608 +657 608 31 +1 50 1 24 +658 29 609 +659 609 610 +660 610 611 +661 611 612 +662 612 613 +663 613 614 +664 614 615 +665 615 616 +666 616 617 +667 617 618 +668 618 619 +669 619 620 +670 620 621 +671 621 622 +672 622 623 +673 623 624 +674 624 625 +675 625 626 +676 626 627 +677 627 628 +678 628 629 +679 629 630 +680 630 631 +681 631 32 +1 51 1 3 +682 32 632 +683 632 633 +684 633 25 +1 52 1 3 +685 28 634 +686 634 635 +687 635 31 +2 1 2 40 +688 33 639 1 +689 639 43 1 +690 641 36 2 +691 37 641 2 +692 636 38 3 +693 42 636 3 +694 638 39 4 +695 44 638 4 +696 34 639 33 +697 644 34 35 +698 34 644 639 +699 36 648 35 +700 35 648 644 +701 36 641 648 +702 38 640 37 +703 640 641 37 +704 38 636 640 +705 39 647 40 +706 39 638 647 +707 642 41 40 +708 40 647 642 +709 41 636 42 +710 41 642 636 +711 43 637 44 +712 43 639 637 +713 637 638 44 +714 636 643 640 +715 642 643 636 +716 637 647 638 +717 639 645 637 +718 645 647 637 +719 644 645 639 +720 640 648 641 +721 643 648 640 +722 642 646 643 +723 647 646 642 +724 646 648 643 +725 644 646 645 +726 648 646 644 +727 646 647 645 +2 2 2 307 +728 1 747 33 +729 93 700 1 +730 700 747 1 +731 75 2 36 +732 76 5 45 +733 79 748 6 +734 6 701 80 +735 6 748 701 +736 33 717 34 +737 33 747 717 +738 34 74 35 +739 34 73 74 +740 34 717 73 +741 35 75 36 +742 35 74 75 +743 77 45 46 +744 76 45 77 +745 78 46 47 +746 77 46 78 +747 48 718 47 +748 47 718 78 +749 49 678 48 +750 678 718 48 +751 50 711 49 +752 49 711 678 +753 51 759 50 +754 50 759 711 +755 52 733 51 +756 51 733 682 +757 682 759 51 +758 53 756 52 +759 52 756 733 +760 54 705 53 +761 705 756 53 +762 55 698 54 +763 698 705 54 +764 56 726 55 +765 55 726 698 +766 57 757 56 +767 56 757 726 +768 58 730 57 +769 57 730 684 +770 684 757 57 +771 59 768 58 +772 58 768 730 +773 60 704 59 +774 704 768 59 +775 61 728 60 +776 60 728 704 +777 62 771 61 +778 61 771 728 +779 63 727 62 +780 727 771 62 +781 64 758 63 +782 685 727 63 +783 63 758 685 +784 65 725 64 +785 725 758 64 +786 66 697 65 +787 697 725 65 +788 67 706 66 +789 66 706 697 +790 68 755 67 +791 67 755 706 +792 69 732 68 +793 732 755 68 +794 70 760 69 +795 683 732 69 +796 69 760 683 +797 71 712 70 +798 712 760 70 +799 72 679 71 +800 679 712 71 +801 73 717 72 +802 72 717 679 +803 78 718 79 +804 718 748 79 +805 80 766 81 +806 701 766 80 +807 81 696 82 +808 81 766 696 +809 82 752 83 +810 696 752 82 +811 83 754 84 +812 83 752 708 +813 708 754 83 +814 84 710 85 +815 84 754 710 +816 85 690 86 +817 85 710 690 +818 86 729 87 +819 690 729 86 +820 87 689 88 +821 87 729 689 +822 88 709 89 +823 689 709 88 +824 89 753 90 +825 709 753 89 +826 90 751 91 +827 707 751 90 +828 90 753 707 +829 91 695 92 +830 91 751 695 +831 92 765 93 +832 695 765 92 +833 93 765 700 +834 649 699 688 +835 688 746 649 +836 649 743 699 +837 649 761 743 +838 746 761 649 +839 650 713 680 +840 680 769 650 +841 650 702 691 +842 691 715 650 +843 694 713 650 +844 650 715 694 +845 650 769 702 +846 681 714 651 +847 651 770 681 +848 692 703 651 +849 651 716 692 +850 651 714 693 +851 693 716 651 +852 703 770 651 +853 652 719 672 +854 672 723 652 +855 680 719 652 +856 652 721 680 +857 652 744 721 +858 723 744 652 +859 673 720 653 +860 653 724 673 +861 653 720 681 +862 681 722 653 +863 722 745 653 +864 653 745 724 +865 654 737 687 +866 687 741 654 +867 654 741 734 +868 734 767 654 +869 654 767 737 +870 686 740 655 +871 655 742 686 +872 735 742 655 +873 655 772 735 +874 740 772 655 +875 689 731 656 +876 656 749 689 +877 656 739 693 +878 693 749 656 +879 656 731 699 +880 699 739 656 +881 657 736 690 +882 690 750 657 +883 657 750 694 +884 694 762 657 +885 657 738 736 +886 657 762 738 +887 658 728 676 +888 676 740 658 +889 677 704 658 +890 658 737 677 +891 658 740 686 +892 686 761 658 +893 687 737 658 +894 658 761 687 +895 704 728 658 +896 672 701 659 +897 659 723 672 +898 682 723 659 +899 659 759 682 +900 701 773 659 +901 711 759 659 +902 659 773 711 +903 660 700 673 +904 673 724 660 +905 660 724 683 +906 683 760 660 +907 660 774 700 +908 660 760 712 +909 712 774 660 +910 674 705 661 +911 661 721 674 +912 698 702 661 +913 661 705 698 +914 702 769 661 +915 661 769 721 +916 662 706 675 +917 675 722 662 +918 662 703 697 +919 697 706 662 +920 662 770 703 +921 722 770 662 +922 680 713 663 +923 663 719 680 +924 696 719 663 +925 663 752 696 +926 708 752 663 +927 663 764 708 +928 713 764 663 +929 664 714 681 +930 681 720 664 +931 664 720 695 +932 695 751 664 +933 664 751 707 +934 707 763 664 +935 664 763 714 +936 684 734 665 +937 665 757 684 +938 691 702 665 +939 665 734 691 +940 665 702 698 +941 698 726 665 +942 726 757 665 +943 666 735 685 +944 685 758 666 +945 666 703 692 +946 692 735 666 +947 697 703 666 +948 666 725 697 +949 666 758 725 +950 688 731 667 +951 667 736 688 +952 689 729 667 +953 667 731 689 +954 667 729 690 +955 690 736 667 +956 668 739 699 +957 699 743 668 +958 716 739 668 +959 668 742 716 +960 668 743 742 +961 715 741 669 +962 669 762 715 +963 669 746 738 +964 738 762 669 +965 741 746 669 +966 670 749 693 +967 693 763 670 +968 707 753 670 +969 670 763 707 +970 709 749 670 +971 670 753 709 +972 694 750 671 +973 671 764 694 +974 671 754 708 +975 708 764 671 +976 671 750 710 +977 710 754 671 +978 672 719 696 +979 696 766 672 +980 672 766 701 +981 695 720 673 +982 673 765 695 +983 700 765 673 +984 674 756 705 +985 721 744 674 +986 674 744 733 +987 733 756 674 +988 706 755 675 +989 675 745 722 +990 732 745 675 +991 675 755 732 +992 676 771 727 +993 727 772 676 +994 728 771 676 +995 676 772 740 +996 677 768 704 +997 677 767 730 +998 730 768 677 +999 737 767 677 +1000 711 773 678 +1001 678 748 718 +1002 678 773 748 +1003 679 774 712 +1004 717 747 679 +1005 747 774 679 +1006 721 769 680 +1007 681 770 722 +1008 682 744 723 +1009 733 744 682 +1010 724 745 683 +1011 683 745 732 +1012 730 767 684 +1013 684 767 734 +1014 685 772 727 +1015 735 772 685 +1016 742 743 686 +1017 743 761 686 +1018 687 746 741 +1019 687 761 746 +1020 699 731 688 +1021 736 738 688 +1022 738 746 688 +1023 689 749 709 +1024 710 750 690 +1025 691 741 715 +1026 734 741 691 +1027 716 742 692 +1028 692 742 735 +1029 714 763 693 +1030 693 739 716 +1031 694 764 713 +1032 715 762 694 +1033 700 774 747 +1034 748 773 701 +2 3 2 39 +1035 2 777 37 +1036 96 778 2 +1037 2 778 777 +1038 38 780 3 +1039 3 780 94 +1040 95 782 7 +1041 7 782 101 +1042 8 785 96 +1043 97 785 8 +1044 9 781 98 +1045 99 781 9 +1046 37 784 38 +1047 777 784 37 +1048 38 784 780 +1049 94 787 95 +1050 780 787 94 +1051 95 787 782 +1052 96 785 778 +1053 98 783 97 +1054 783 785 97 +1055 781 783 98 +1056 100 779 99 +1057 779 781 99 +1058 101 786 100 +1059 100 786 779 +1060 782 786 101 +1061 777 778 775 +1062 775 779 777 +1063 778 783 775 +1064 775 781 779 +1065 775 783 781 +1066 777 779 776 +1067 776 784 777 +1068 779 786 776 +1069 780 784 776 +1070 776 787 780 +1071 776 786 782 +1072 782 787 776 +1073 778 785 783 +2 4 2 466 +1074 3 883 42 +1075 94 931 3 +1076 3 931 883 +1077 39 869 4 +1078 4 950 143 +1079 869 950 4 +1080 7 929 95 +1081 102 885 7 +1082 885 929 7 +1083 10 870 105 +1084 106 951 10 +1085 10 951 870 +1086 11 948 119 +1087 120 873 11 +1088 873 948 11 +1089 12 884 123 +1090 124 930 12 +1091 12 930 884 +1092 13 932 125 +1093 126 886 13 +1094 886 932 13 +1095 14 871 129 +1096 130 949 14 +1097 14 949 871 +1098 40 972 39 +1099 39 972 869 +1100 41 972 40 +1101 42 883 41 +1102 41 883 837 +1103 837 972 41 +1104 95 875 94 +1105 875 931 94 +1106 95 929 875 +1107 103 885 102 +1108 104 973 103 +1109 838 885 103 +1110 103 973 838 +1111 105 973 104 +1112 870 973 105 +1113 107 868 106 +1114 868 951 106 +1115 108 908 107 +1116 107 908 868 +1117 109 896 108 +1118 108 896 832 +1119 832 908 108 +1120 110 952 109 +1121 109 952 896 +1122 111 864 110 +1123 864 952 110 +1124 112 956 111 +1125 111 956 864 +1126 113 888 112 +1127 888 956 112 +1128 114 957 113 +1129 113 957 888 +1130 115 865 114 +1131 865 957 114 +1132 116 942 115 +1133 115 942 865 +1134 117 895 116 +1135 895 942 116 +1136 118 914 117 +1137 834 895 117 +1138 117 914 834 +1139 119 874 118 +1140 874 914 118 +1141 119 948 874 +1142 121 977 120 +1143 120 977 873 +1144 122 977 121 +1145 123 884 122 +1146 122 884 836 +1147 836 977 122 +1148 125 876 124 +1149 876 930 124 +1150 125 932 876 +1151 127 886 126 +1152 128 976 127 +1153 839 886 127 +1154 127 976 839 +1155 129 976 128 +1156 871 976 129 +1157 131 872 130 +1158 872 949 130 +1159 132 909 131 +1160 131 909 872 +1161 133 898 132 +1162 132 898 833 +1163 833 909 132 +1164 134 939 133 +1165 133 939 898 +1166 135 861 134 +1167 861 939 134 +1168 136 959 135 +1169 135 959 861 +1170 137 887 136 +1171 887 959 136 +1172 138 954 137 +1173 137 954 887 +1174 139 863 138 +1175 863 954 138 +1176 140 953 139 +1177 139 953 863 +1178 141 897 140 +1179 897 953 140 +1180 142 907 141 +1181 831 897 141 +1182 141 907 831 +1183 143 867 142 +1184 867 907 142 +1185 143 950 867 +1186 917 921 788 +1187 788 969 917 +1188 921 946 788 +1189 946 969 788 +1190 922 928 789 +1191 789 947 922 +1192 928 974 789 +1193 789 974 947 +1194 906 927 790 +1195 790 933 906 +1196 927 991 790 +1197 790 962 933 +1198 790 991 962 +1199 791 880 849 +1200 849 919 791 +1201 791 941 880 +1202 791 919 904 +1203 904 941 791 +1204 835 859 792 +1205 792 910 835 +1206 859 945 792 +1207 889 910 792 +1208 792 945 889 +1209 793 901 877 +1210 877 920 793 +1211 793 920 890 +1212 890 944 793 +1213 793 944 901 +1214 794 936 881 +1215 881 987 794 +1216 794 934 925 +1217 925 936 794 +1218 794 987 934 +1219 894 923 795 +1220 795 993 894 +1221 795 935 912 +1222 912 993 795 +1223 923 935 795 +1224 796 926 893 +1225 893 992 796 +1226 911 938 796 +1227 796 992 911 +1228 796 938 926 +1229 882 937 797 +1230 797 986 882 +1231 797 937 924 +1232 924 940 797 +1233 940 986 797 +1234 849 899 798 +1235 798 915 849 +1236 798 905 860 +1237 860 915 798 +1238 899 905 798 +1239 799 862 844 +1240 844 913 799 +1241 799 955 862 +1242 799 913 891 +1243 891 955 799 +1244 879 900 800 +1245 800 958 879 +1246 900 918 800 +1247 800 918 902 +1248 902 958 800 +1249 801 878 846 +1250 846 903 801 +1251 801 916 878 +1252 892 916 801 +1253 801 943 892 +1254 903 943 801 +1255 849 880 802 +1256 802 899 849 +1257 802 880 862 +1258 862 966 802 +1259 802 981 899 +1260 966 981 802 +1261 859 866 803 +1262 803 971 859 +1263 803 866 860 +1264 860 975 803 +1265 803 975 971 +1266 840 901 804 +1267 804 906 840 +1268 804 900 848 +1269 848 906 804 +1270 804 978 900 +1271 901 970 804 +1272 970 978 804 +1273 805 903 846 +1274 846 904 805 +1275 854 902 805 +1276 805 904 854 +1277 902 980 805 +1278 805 963 903 +1279 805 980 963 +1280 806 889 831 +1281 831 907 806 +1282 806 907 867 +1283 867 984 806 +1284 806 961 889 +1285 894 961 806 +1286 806 984 894 +1287 832 890 807 +1288 807 908 832 +1289 807 982 855 +1290 855 983 807 +1291 868 908 807 +1292 807 983 868 +1293 890 982 807 +1294 833 891 808 +1295 808 909 833 +1296 872 909 808 +1297 808 985 872 +1298 891 960 808 +1299 808 960 893 +1300 893 985 808 +1301 809 892 834 +1302 834 914 809 +1303 856 979 809 +1304 809 988 856 +1305 809 914 874 +1306 874 988 809 +1307 809 979 892 +1308 810 965 875 +1309 875 968 810 +1310 810 968 882 +1311 882 989 810 +1312 912 965 810 +1313 810 989 912 +1314 876 964 811 +1315 811 967 876 +1316 881 967 811 +1317 811 990 881 +1318 811 964 911 +1319 911 990 811 +1320 843 879 812 +1321 812 915 843 +1322 849 915 812 +1323 812 919 849 +1324 879 958 812 +1325 812 958 919 +1326 844 878 813 +1327 813 913 844 +1328 847 913 813 +1329 813 917 847 +1330 878 916 813 +1331 916 917 813 +1332 814 877 835 +1333 835 910 814 +1334 850 920 814 +1335 814 928 850 +1336 814 920 877 +1337 910 928 814 +1338 867 950 815 +1339 815 984 867 +1340 869 923 815 +1341 815 950 869 +1342 815 923 894 +1343 894 984 815 +1344 816 951 868 +1345 868 983 816 +1346 816 924 870 +1347 870 951 816 +1348 816 940 924 +1349 816 983 940 +1350 817 926 871 +1351 871 949 817 +1352 817 949 872 +1353 872 985 817 +1354 893 926 817 +1355 817 985 893 +1356 873 925 818 +1357 818 948 873 +1358 874 948 818 +1359 818 988 874 +1360 925 934 818 +1361 934 988 818 +1362 881 936 819 +1363 819 967 881 +1364 884 930 819 +1365 819 936 884 +1366 930 967 819 +1367 883 931 820 +1368 820 935 883 +1369 912 935 820 +1370 820 965 912 +1371 931 965 820 +1372 821 937 882 +1373 882 968 821 +1374 821 929 885 +1375 885 937 821 +1376 821 968 929 +1377 822 932 886 +1378 886 938 822 +1379 822 938 911 +1380 911 964 822 +1381 822 964 932 +1382 823 944 896 +1383 896 952 823 +1384 901 944 823 +1385 823 970 901 +1386 952 970 823 +1387 824 945 859 +1388 859 971 824 +1389 897 945 824 +1390 824 953 897 +1391 824 971 953 +1392 825 942 895 +1393 895 943 825 +1394 825 943 903 +1395 903 963 825 +1396 825 963 942 +1397 887 905 826 +1398 826 959 887 +1399 826 905 899 +1400 899 981 826 +1401 826 981 959 +1402 860 905 827 +1403 827 975 860 +1404 827 905 887 +1405 887 954 827 +1406 954 975 827 +1407 862 955 828 +1408 828 966 862 +1409 898 939 828 +1410 828 955 898 +1411 939 966 828 +1412 888 918 829 +1413 829 956 888 +1414 829 918 900 +1415 900 978 829 +1416 829 978 956 +1417 830 918 888 +1418 888 957 830 +1419 902 918 830 +1420 830 980 902 +1421 957 980 830 +1422 889 945 831 +1423 831 945 897 +1424 832 944 890 +1425 896 944 832 +1426 833 955 891 +1427 898 955 833 +1428 892 943 834 +1429 834 943 895 +1430 835 962 859 +1431 877 933 835 +1432 933 962 835 +1433 836 925 873 +1434 873 977 836 +1435 884 936 836 +1436 836 936 925 +1437 837 923 869 +1438 869 972 837 +1439 883 935 837 +1440 837 935 923 +1441 870 924 838 +1442 838 973 870 +1443 838 937 885 +1444 924 937 838 +1445 871 926 839 +1446 839 976 871 +1447 839 938 886 +1448 926 938 839 +1449 877 901 840 +1450 840 933 877 +1451 906 933 840 +1452 841 921 856 +1453 856 987 841 +1454 841 987 881 +1455 881 990 841 +1456 841 946 921 +1457 841 990 946 +1458 855 922 842 +1459 842 986 855 +1460 882 986 842 +1461 842 989 882 +1462 922 947 842 +1463 947 989 842 +1464 843 915 860 +1465 860 991 843 +1466 843 927 879 +1467 843 991 927 +1468 862 880 844 +1469 844 941 878 +1470 880 941 844 +1471 845 916 892 +1472 892 979 845 +1473 845 917 916 +1474 845 921 917 +1475 845 979 921 +1476 878 941 846 +1477 846 941 904 +1478 891 913 847 +1479 847 960 891 +1480 917 969 847 +1481 847 969 960 +1482 848 900 879 +1483 879 927 848 +1484 848 927 906 +1485 890 920 850 +1486 850 982 890 +1487 850 928 922 +1488 922 982 850 +1489 851 910 889 +1490 889 961 851 +1491 851 928 910 +1492 851 974 928 +1493 961 974 851 +1494 893 960 852 +1495 852 992 893 +1496 852 969 946 +1497 946 992 852 +1498 960 969 852 +1499 853 961 894 +1500 894 993 853 +1501 947 974 853 +1502 853 993 947 +1503 853 974 961 +1504 854 958 902 +1505 904 919 854 +1506 919 958 854 +1507 855 982 922 +1508 940 983 855 +1509 855 986 940 +1510 921 979 856 +1511 934 987 856 +1512 856 988 934 +1513 912 989 857 +1514 857 993 912 +1515 857 989 947 +1516 947 993 857 +1517 858 990 911 +1518 911 992 858 +1519 946 990 858 +1520 858 992 946 +1521 859 962 866 +1522 866 991 860 +1523 861 966 939 +1524 959 981 861 +1525 861 981 966 +1526 953 971 863 +1527 863 975 954 +1528 971 975 863 +1529 864 970 952 +1530 956 978 864 +1531 864 978 970 +1532 942 963 865 +1533 865 980 957 +1534 963 980 865 +1535 962 991 866 +1536 929 968 875 +1537 875 965 931 +1538 876 967 930 +1539 932 964 876 +2 5 2 114 +1540 43 1016 1 +1541 1 1016 93 +1542 4 1017 44 +1543 143 1017 4 +1544 80 1018 6 +1545 6 1018 144 +1546 14 1019 130 +1547 145 1019 14 +1548 44 1031 43 +1549 43 1031 1016 +1550 1017 1031 44 +1551 81 1020 80 +1552 80 1020 1018 +1553 82 1002 81 +1554 1002 1020 81 +1555 83 1025 82 +1556 82 1025 1002 +1557 84 1004 83 +1558 1004 1025 83 +1559 85 1026 84 +1560 84 1026 1004 +1561 86 1009 85 +1562 1009 1026 85 +1563 87 1012 86 +1564 1001 1009 86 +1565 86 1012 1001 +1566 88 1028 87 +1567 87 1028 1012 +1568 89 1003 88 +1569 1003 1028 88 +1570 90 1022 89 +1571 89 1022 1003 +1572 91 1005 90 +1573 1005 1022 90 +1574 92 1032 91 +1575 91 1032 1005 +1576 93 1014 92 +1577 1014 1032 92 +1578 93 1016 1014 +1579 130 1021 131 +1580 1019 1021 130 +1581 131 1011 132 +1582 131 1021 1011 +1583 132 1024 133 +1584 1011 1024 132 +1585 133 1008 134 +1586 133 1024 1008 +1587 134 1027 135 +1588 1008 1027 134 +1589 135 1010 136 +1590 135 1027 1010 +1591 136 1013 137 +1592 136 1010 1001 +1593 1001 1013 136 +1594 137 1029 138 +1595 1013 1029 137 +1596 138 1007 139 +1597 138 1029 1007 +1598 139 1023 140 +1599 1007 1023 139 +1600 140 1006 141 +1601 140 1023 1006 +1602 141 1033 142 +1603 1006 1033 141 +1604 142 1015 143 +1605 142 1033 1015 +1606 1015 1017 143 +1607 144 1030 145 +1608 1018 1030 144 +1609 145 1030 1019 +1610 994 1015 1014 +1611 1014 1016 994 +1612 994 1017 1015 +1613 1016 1031 994 +1614 994 1031 1017 +1615 1002 1011 995 +1616 995 1020 1002 +1617 1011 1021 995 +1618 1018 1020 995 +1619 995 1030 1018 +1620 995 1021 1019 +1621 1019 1030 995 +1622 996 1007 1003 +1623 1003 1022 996 +1624 1005 1006 996 +1625 996 1022 1005 +1626 1006 1023 996 +1627 996 1023 1007 +1628 1003 1007 997 +1629 997 1028 1003 +1630 1007 1029 997 +1631 997 1013 1012 +1632 1012 1028 997 +1633 997 1029 1013 +1634 998 1011 1002 +1635 1002 1025 998 +1636 1004 1008 998 +1637 998 1025 1004 +1638 1008 1024 998 +1639 998 1024 1011 +1640 999 1008 1004 +1641 1004 1026 999 +1642 999 1027 1008 +1643 1009 1010 999 +1644 999 1026 1009 +1645 1010 1027 999 +1646 1000 1006 1005 +1647 1005 1032 1000 +1648 1000 1033 1006 +1649 1014 1015 1000 +1650 1000 1032 1014 +1651 1015 1033 1000 +1652 1001 1010 1009 +1653 1012 1013 1001 +2 6 2 130 +1654 75 1035 2 +1655 1035 96 2 +1656 1036 45 5 +1657 177 1036 5 +1658 96 1035 8 +1659 1035 176 8 +1660 146 1036 15 +1661 1036 177 15 +1662 1037 46 45 +1663 1036 1037 45 +1664 1038 47 46 +1665 46 1037 1038 +1666 1040 48 47 +1667 47 1038 1040 +1668 48 1042 49 +1669 48 1040 1042 +1670 1061 50 49 +1671 1061 49 1042 +1672 50 1060 51 +1673 50 1061 1060 +1674 1059 52 51 +1675 1059 51 1060 +1676 52 1058 53 +1677 52 1059 1058 +1678 53 1057 54 +1679 53 1058 1057 +1680 1056 55 54 +1681 1056 54 1057 +1682 55 1055 56 +1683 55 1056 1055 +1684 1054 57 56 +1685 1054 56 1055 +1686 57 1053 58 +1687 57 1054 1053 +1688 1052 59 58 +1689 1052 58 1053 +1690 59 1051 60 +1691 59 1052 1051 +1692 1050 61 60 +1693 1050 60 1051 +1694 61 1048 62 +1695 61 1050 1048 +1696 62 1047 63 +1697 62 1048 1047 +1698 1045 64 63 +1699 1045 63 1047 +1700 64 1044 65 +1701 64 1045 1044 +1702 65 1046 66 +1703 65 1044 1046 +1704 1049 67 66 +1705 1049 66 1046 +1706 67 1062 68 +1707 67 1049 1062 +1708 1063 69 68 +1709 1063 68 1062 +1710 69 1064 70 +1711 69 1063 1064 +1712 70 1065 71 +1713 70 1064 1065 +1714 71 1043 72 +1715 71 1065 1043 +1716 1041 73 72 +1717 1041 72 1043 +1718 1039 74 73 +1719 73 1041 1039 +1720 74 1034 75 +1721 74 1039 1034 +1722 1034 1035 75 +1723 1037 146 147 +1724 1037 1036 146 +1725 1038 147 148 +1726 1038 1037 147 +1727 1040 148 149 +1728 1040 1038 148 +1729 150 1042 149 +1730 1042 1040 149 +1731 1061 150 151 +1732 1061 1042 150 +1733 152 1060 151 +1734 1060 1061 151 +1735 1059 152 153 +1736 1059 1060 152 +1737 154 1058 153 +1738 1058 1059 153 +1739 155 1057 154 +1740 1057 1058 154 +1741 1056 155 156 +1742 1056 1057 155 +1743 157 1055 156 +1744 1055 1056 156 +1745 1054 157 158 +1746 1054 1055 157 +1747 159 1053 158 +1748 1053 1054 158 +1749 1052 159 160 +1750 1052 1053 159 +1751 161 1051 160 +1752 1051 1052 160 +1753 1050 161 162 +1754 1050 1051 161 +1755 163 1048 162 +1756 1048 1050 162 +1757 164 1047 163 +1758 1047 1048 163 +1759 1045 164 165 +1760 1045 1047 164 +1761 166 1044 165 +1762 1044 1045 165 +1763 167 1046 166 +1764 1046 1044 166 +1765 1049 167 168 +1766 1049 1046 167 +1767 169 1062 168 +1768 1062 1049 168 +1769 1063 169 170 +1770 1063 1062 169 +1771 171 1064 170 +1772 1064 1063 170 +1773 172 1065 171 +1774 1065 1064 171 +1775 173 1043 172 +1776 1043 1065 172 +1777 1041 173 174 +1778 1041 1043 173 +1779 1039 174 175 +1780 1039 1041 174 +1781 176 1034 175 +1782 1034 1039 175 +1783 1035 1034 176 +2 7 2 40 +1784 76 1069 5 +1785 1069 178 5 +1786 1071 79 6 +1787 144 1071 6 +1788 1068 126 13 +1789 179 1068 13 +1790 129 1066 14 +1791 1066 145 14 +1792 77 1069 76 +1793 1074 77 78 +1794 77 1074 1069 +1795 79 1078 78 +1796 78 1078 1074 +1797 79 1071 1078 +1798 126 1077 127 +1799 126 1068 1077 +1800 1072 128 127 +1801 127 1077 1072 +1802 128 1066 129 +1803 128 1072 1066 +1804 145 1070 144 +1805 1070 1071 144 +1806 145 1066 1070 +1807 178 1067 179 +1808 178 1069 1067 +1809 1067 1068 179 +1810 1066 1073 1070 +1811 1072 1073 1066 +1812 1067 1077 1068 +1813 1069 1075 1067 +1814 1075 1077 1067 +1815 1074 1075 1069 +1816 1070 1078 1071 +1817 1073 1078 1070 +1818 1072 1076 1073 +1819 1077 1076 1072 +1820 1076 1078 1073 +1821 1074 1076 1075 +1822 1078 1076 1074 +1823 1076 1077 1075 +2 8 2 44 +1824 101 1087 7 +1825 1087 102 7 +1826 1088 99 9 +1827 180 1088 9 +1828 105 1092 10 +1829 1092 186 10 +1830 1081 183 16 +1831 184 1081 16 +1832 1083 100 99 +1833 99 1088 1083 +1834 100 1084 101 +1835 1084 100 1083 +1836 1087 101 1084 +1837 102 1087 103 +1838 1091 104 103 +1839 103 1087 1086 +1840 103 1086 1091 +1841 1092 105 104 +1842 1092 104 1091 +1843 1088 180 181 +1844 1089 181 182 +1845 1088 181 1089 +1846 183 1081 182 +1847 182 1081 1079 +1848 182 1079 1089 +1849 185 1080 184 +1850 1081 184 1080 +1851 1090 185 186 +1852 1080 185 1090 +1853 186 1092 1090 +1854 1079 1081 1080 +1855 1079 1080 1082 +1856 1085 1079 1082 +1857 1085 1089 1079 +1858 1090 1082 1080 +1859 1082 1086 1085 +1860 1082 1091 1086 +1861 1090 1091 1082 +1862 1083 1085 1084 +1863 1083 1089 1085 +1864 1088 1089 1083 +1865 1086 1084 1085 +1866 1086 1087 1084 +1867 1092 1091 1090 +2 9 2 154 +1868 10 1140 106 +1869 186 1140 10 +1870 119 1138 11 +1871 11 1138 203 +1872 16 1141 184 +1873 187 1141 16 +1874 17 1139 200 +1875 201 1139 17 +1876 106 1143 107 +1877 1140 1143 106 +1878 107 1117 108 +1879 107 1143 1117 +1880 108 1108 109 +1881 108 1117 1108 +1882 109 1118 110 +1883 1108 1118 109 +1884 110 1109 111 +1885 110 1118 1109 +1886 111 1131 112 +1887 1109 1131 111 +1888 112 1148 113 +1889 112 1131 1115 +1890 1115 1148 112 +1891 113 1135 114 +1892 113 1148 1135 +1893 114 1123 115 +1894 1112 1123 114 +1895 114 1135 1112 +1896 115 1146 116 +1897 1123 1146 115 +1898 116 1146 117 +1899 117 1120 118 +1900 1110 1120 117 +1901 117 1146 1110 +1902 118 1144 119 +1903 1120 1144 118 +1904 119 1144 1138 +1905 184 1126 185 +1906 184 1141 1126 +1907 185 1126 186 +1908 1126 1140 186 +1909 188 1142 187 +1910 187 1142 1141 +1911 189 1116 188 +1912 1116 1142 188 +1913 190 1150 189 +1914 189 1150 1116 +1915 191 1119 190 +1916 1119 1150 190 +1917 192 1151 191 +1918 191 1151 1119 +1919 193 1121 192 +1920 1121 1151 192 +1921 194 1145 193 +1922 1111 1121 193 +1923 193 1145 1111 +1924 195 1145 194 +1925 196 1124 195 +1926 1124 1145 195 +1927 197 1134 196 +1928 1113 1124 196 +1929 196 1134 1113 +1930 198 1149 197 +1931 197 1149 1134 +1932 199 1122 198 +1933 198 1122 1114 +1934 1114 1149 198 +1935 200 1147 199 +1936 199 1147 1122 +1937 1139 1147 200 +1938 202 1125 201 +1939 1125 1139 201 +1940 203 1125 202 +1941 203 1138 1125 +1942 1093 1123 1112 +1943 1112 1132 1093 +1944 1093 1124 1113 +1945 1113 1133 1093 +1946 1093 1133 1123 +1947 1093 1132 1124 +1948 1094 1120 1110 +1949 1110 1127 1094 +1950 1114 1122 1094 +1951 1094 1127 1114 +1952 1094 1136 1120 +1953 1122 1136 1094 +1954 1095 1116 1106 +1955 1106 1129 1095 +1956 1108 1117 1095 +1957 1095 1129 1108 +1958 1095 1137 1116 +1959 1117 1137 1095 +1960 1107 1121 1096 +1961 1096 1130 1107 +1962 1109 1130 1096 +1963 1096 1131 1109 +1964 1096 1121 1111 +1965 1111 1128 1096 +1966 1096 1128 1115 +1967 1115 1131 1096 +1968 1106 1119 1097 +1969 1097 1129 1106 +1970 1097 1119 1107 +1971 1107 1130 1097 +1972 1097 1118 1108 +1973 1108 1129 1097 +1974 1109 1118 1097 +1975 1097 1130 1109 +1976 1098 1132 1112 +1977 1112 1135 1098 +1978 1115 1128 1098 +1979 1098 1148 1115 +1980 1128 1132 1098 +1981 1135 1148 1098 +1982 1099 1133 1113 +1983 1113 1134 1099 +1984 1114 1127 1099 +1985 1099 1149 1114 +1986 1127 1133 1099 +1987 1134 1149 1099 +1988 1100 1136 1122 +1989 1122 1147 1100 +1990 1125 1136 1100 +1991 1100 1139 1125 +1992 1100 1147 1139 +1993 1120 1136 1101 +1994 1101 1144 1120 +1995 1101 1136 1125 +1996 1125 1138 1101 +1997 1138 1144 1101 +1998 1116 1137 1102 +1999 1102 1142 1116 +2000 1102 1137 1126 +2001 1126 1141 1102 +2002 1141 1142 1102 +2003 1103 1137 1117 +2004 1117 1143 1103 +2005 1126 1137 1103 +2006 1103 1140 1126 +2007 1103 1143 1140 +2008 1104 1127 1110 +2009 1110 1146 1104 +2010 1123 1133 1104 +2011 1104 1146 1123 +2012 1104 1133 1127 +2013 1105 1128 1111 +2014 1111 1145 1105 +2015 1124 1132 1105 +2016 1105 1145 1124 +2017 1105 1132 1128 +2018 1116 1150 1106 +2019 1106 1150 1119 +2020 1119 1151 1107 +2021 1107 1151 1121 +2 10 2 44 +2022 1160 120 11 +2023 203 1160 11 +2024 123 1165 12 +2025 1165 210 12 +2026 1161 201 17 +2027 204 1161 17 +2028 1154 207 18 +2029 208 1154 18 +2030 120 1160 121 +2031 1164 122 121 +2032 121 1160 1159 +2033 121 1159 1164 +2034 1165 123 122 +2035 1165 122 1164 +2036 1156 202 201 +2037 201 1161 1156 +2038 202 1157 203 +2039 1157 202 1156 +2040 1160 203 1157 +2041 1161 204 205 +2042 1162 205 206 +2043 1161 205 1162 +2044 207 1154 206 +2045 206 1154 1152 +2046 206 1152 1162 +2047 209 1153 208 +2048 1154 208 1153 +2049 1163 209 210 +2050 1153 209 1163 +2051 210 1165 1163 +2052 1152 1154 1153 +2053 1152 1153 1155 +2054 1158 1152 1155 +2055 1158 1162 1152 +2056 1163 1155 1153 +2057 1155 1159 1158 +2058 1155 1164 1159 +2059 1163 1164 1155 +2060 1156 1158 1157 +2061 1156 1162 1158 +2062 1161 1162 1156 +2063 1159 1157 1158 +2064 1159 1160 1157 +2065 1165 1164 1163 +2 11 2 39 +2066 5 1169 177 +2067 178 1168 5 +2068 1168 1169 5 +2069 12 1173 124 +2070 210 1173 12 +2071 125 1171 13 +2072 13 1171 179 +2073 177 1176 15 +2074 15 1176 212 +2075 18 1172 208 +2076 211 1172 18 +2077 124 1178 125 +2078 1173 1178 124 +2079 125 1178 1171 +2080 1169 1176 177 +2081 179 1175 178 +2082 178 1175 1168 +2083 1171 1175 179 +2084 208 1170 209 +2085 208 1172 1170 +2086 209 1177 210 +2087 1170 1177 209 +2088 210 1177 1173 +2089 212 1174 211 +2090 211 1174 1172 +2091 212 1176 1174 +2092 1166 1169 1168 +2093 1168 1170 1166 +2094 1166 1174 1169 +2095 1170 1172 1166 +2096 1172 1174 1166 +2097 1167 1170 1168 +2098 1168 1175 1167 +2099 1167 1177 1170 +2100 1167 1175 1171 +2101 1171 1178 1167 +2102 1173 1177 1167 +2103 1167 1178 1173 +2104 1174 1176 1169 +2 12 2 753 +2105 97 8 1421 +2106 8 176 1399 +2107 8 1399 1421 +2108 9 98 1437 +2109 180 9 1426 +2110 1426 9 1437 +2111 146 15 1400 +2112 15 212 1422 +2113 1400 15 1422 +2114 16 183 1431 +2115 187 16 1440 +2116 16 1431 1440 +2117 17 200 1382 +2118 204 17 1297 +2119 1297 17 1382 +2120 18 207 1427 +2121 211 18 1438 +2122 18 1427 1438 +2123 98 97 1346 +2124 1346 97 1421 +2125 98 1346 1437 +2126 147 146 1509 +2127 1294 146 1400 +2128 146 1294 1509 +2129 148 147 1363 +2130 1363 147 1509 +2131 149 148 1277 +2132 1277 148 1363 +2133 150 149 1378 +2134 149 1277 1378 +2135 151 150 1436 +2136 150 1378 1436 +2137 152 151 1488 +2138 151 1436 1488 +2139 153 152 1344 +2140 1344 152 1488 +2141 154 153 1465 +2142 153 1344 1465 +2143 155 154 1349 +2144 1349 154 1465 +2145 156 155 1292 +2146 1292 155 1349 +2147 157 156 1393 +2148 156 1292 1393 +2149 158 157 1329 +2150 1329 157 1393 +2151 159 158 1407 +2152 158 1329 1407 +2153 160 159 1300 +2154 1300 159 1407 +2155 161 160 1376 +2156 160 1300 1376 +2157 162 161 1483 +2158 161 1376 1483 +2159 163 162 1379 +2160 1379 162 1483 +2161 164 163 1316 +2162 1316 163 1379 +2163 165 164 1460 +2164 164 1316 1460 +2165 166 165 1366 +2166 1366 165 1460 +2167 167 166 1456 +2168 166 1366 1456 +2169 168 167 1326 +2170 1326 167 1456 +2171 169 168 1387 +2172 168 1326 1387 +2173 170 169 1402 +2174 1267 169 1387 +2175 169 1267 1402 +2176 171 170 1402 +2177 172 171 1435 +2178 1284 171 1402 +2179 171 1284 1435 +2180 173 172 1377 +2181 1377 172 1435 +2182 174 173 1278 +2183 1278 173 1377 +2184 175 174 1364 +2185 174 1278 1364 +2186 176 175 1508 +2187 175 1364 1508 +2188 176 1293 1399 +2189 1293 176 1508 +2190 181 180 1321 +2191 1321 180 1426 +2192 182 181 1449 +2193 181 1321 1449 +2194 183 182 1323 +2195 1323 182 1449 +2196 183 1323 1431 +2197 188 187 1369 +2198 1369 187 1512 +2199 187 1440 1512 +2200 189 188 1495 +2201 188 1369 1495 +2202 190 189 1312 +2203 1312 189 1495 +2204 191 190 1455 +2205 190 1312 1455 +2206 192 191 1350 +2207 1350 191 1455 +2208 193 192 1446 +2209 192 1350 1446 +2210 194 193 1462 +2211 1306 193 1446 +2212 193 1306 1462 +2213 195 194 1463 +2214 194 1462 1463 +2215 196 195 1328 +2216 1328 195 1463 +2217 197 196 1423 +2218 1270 196 1328 +2219 196 1270 1423 +2220 198 197 1513 +2221 197 1423 1513 +2222 199 198 1348 +2223 1348 198 1513 +2224 200 199 1307 +2225 1307 199 1348 +2226 200 1307 1382 +2227 205 204 1357 +2228 204 1297 1357 +2229 206 205 1357 +2230 207 206 1322 +2231 1322 206 1357 +2232 207 1322 1427 +2233 212 211 1345 +2234 1345 211 1438 +2235 212 1345 1422 +2236 1324 1179 1441 +2237 1179 1324 1464 +2238 1388 1179 1464 +2239 1179 1388 1518 +2240 1441 1179 1518 +2241 1314 1180 1347 +2242 1180 1314 1489 +2243 1347 1180 1524 +2244 1180 1489 1505 +2245 1180 1505 1524 +2246 1305 1181 1315 +2247 1181 1305 1385 +2248 1315 1181 1490 +2249 1339 1181 1358 +2250 1181 1339 1490 +2251 1358 1181 1385 +2252 1182 1275 1420 +2253 1275 1182 1458 +2254 1332 1182 1403 +2255 1182 1332 1458 +2256 1403 1182 1492 +2257 1182 1420 1492 +2258 1320 1183 1340 +2259 1183 1320 1484 +2260 1340 1183 1432 +2261 1183 1409 1432 +2262 1409 1183 1484 +2263 1271 1184 1472 +2264 1184 1271 1494 +2265 1280 1184 1343 +2266 1184 1280 1375 +2267 1184 1287 1493 +2268 1287 1184 1494 +2269 1343 1184 1493 +2270 1184 1375 1472 +2271 1185 1281 1333 +2272 1281 1185 1373 +2273 1185 1333 1383 +2274 1373 1185 1501 +2275 1185 1383 1452 +2276 1185 1452 1501 +2277 1186 1276 1368 +2278 1276 1186 1417 +2279 1308 1186 1311 +2280 1186 1308 1417 +2281 1311 1186 1337 +2282 1337 1186 1368 +2283 1187 1304 1356 +2284 1304 1187 1384 +2285 1309 1187 1310 +2286 1187 1309 1325 +2287 1310 1187 1356 +2288 1187 1325 1384 +2289 1273 1188 1313 +2290 1188 1273 1396 +2291 1188 1303 1352 +2292 1303 1188 1396 +2293 1313 1188 1514 +2294 1188 1352 1514 +2295 1189 1317 1418 +2296 1317 1189 1450 +2297 1189 1335 1448 +2298 1335 1189 1475 +2299 1189 1418 1475 +2300 1189 1448 1450 +2301 1295 1190 1412 +2302 1190 1295 1447 +2303 1190 1318 1412 +2304 1318 1190 1419 +2305 1334 1190 1447 +2306 1190 1334 1474 +2307 1419 1190 1474 +2308 1302 1191 1425 +2309 1191 1302 1486 +2310 1191 1370 1466 +2311 1370 1191 1486 +2312 1425 1191 1451 +2313 1451 1191 1466 +2314 1301 1192 1389 +2315 1192 1301 1414 +2316 1319 1192 1380 +2317 1192 1319 1413 +2318 1380 1192 1414 +2319 1389 1192 1413 +2320 1279 1193 1406 +2321 1193 1279 1416 +2322 1193 1330 1476 +2323 1330 1193 1497 +2324 1406 1193 1444 +2325 1193 1416 1497 +2326 1444 1193 1476 +2327 1194 1288 1354 +2328 1288 1194 1515 +2329 1338 1194 1381 +2330 1194 1338 1515 +2331 1194 1354 1434 +2332 1381 1194 1434 +2333 1195 1331 1429 +2334 1331 1195 1523 +2335 1355 1195 1429 +2336 1195 1355 1477 +2337 1371 1195 1477 +2338 1195 1371 1523 +2339 1289 1196 1361 +2340 1196 1289 1372 +2341 1196 1353 1442 +2342 1353 1196 1478 +2343 1361 1196 1442 +2344 1196 1372 1478 +2345 1336 1197 1415 +2346 1197 1336 1516 +2347 1351 1197 1391 +2348 1197 1351 1415 +2349 1391 1197 1516 +2350 1264 1198 1367 +2351 1198 1264 1374 +2352 1198 1274 1367 +2353 1274 1198 1468 +2354 1198 1360 1468 +2355 1360 1198 1520 +2356 1198 1374 1520 +2357 1341 1199 1365 +2358 1199 1341 1430 +2359 1199 1342 1469 +2360 1342 1199 1510 +2361 1365 1199 1469 +2362 1199 1430 1510 +2363 1200 1271 1390 +2364 1271 1200 1461 +2365 1273 1200 1390 +2366 1200 1273 1392 +2367 1286 1200 1443 +2368 1200 1286 1461 +2369 1200 1392 1443 +2370 1299 1201 1428 +2371 1201 1299 1445 +2372 1201 1332 1424 +2373 1332 1201 1445 +2374 1201 1424 1428 +2375 1202 1285 1410 +2376 1285 1202 1500 +2377 1202 1295 1362 +2378 1295 1202 1410 +2379 1202 1362 1398 +2380 1202 1398 1500 +2381 1283 1203 1359 +2382 1203 1283 1386 +2383 1296 1203 1386 +2384 1203 1296 1411 +2385 1359 1203 1482 +2386 1203 1411 1482 +2387 1204 1291 1395 +2388 1291 1204 1498 +2389 1204 1292 1349 +2390 1292 1204 1395 +2391 1204 1349 1471 +2392 1204 1471 1498 +2393 1205 1269 1306 +2394 1269 1205 1457 +2395 1205 1306 1479 +2396 1401 1205 1479 +2397 1205 1401 1519 +2398 1457 1205 1519 +2399 1281 1206 1333 +2400 1206 1281 1467 +2401 1300 1206 1376 +2402 1206 1300 1405 +2403 1206 1302 1333 +2404 1302 1206 1405 +2405 1376 1206 1467 +2406 1207 1339 1394 +2407 1339 1207 1439 +2408 1207 1394 1404 +2409 1207 1404 1521 +2410 1439 1207 1521 +2411 1208 1301 1304 +2412 1301 1208 1414 +2413 1208 1304 1384 +2414 1208 1307 1348 +2415 1307 1208 1496 +2416 1208 1348 1414 +2417 1208 1384 1496 +2418 1209 1280 1343 +2419 1280 1209 1457 +2420 1319 1209 1343 +2421 1209 1319 1481 +2422 1209 1328 1457 +2423 1328 1209 1481 +2424 1210 1275 1330 +2425 1275 1210 1408 +2426 1210 1314 1317 +2427 1314 1210 1454 +2428 1210 1317 1408 +2429 1210 1330 1454 +2430 1268 1211 1338 +2431 1211 1268 1397 +2432 1315 1211 1318 +2433 1211 1315 1433 +2434 1318 1211 1412 +2435 1338 1211 1433 +2436 1211 1397 1412 +2437 1212 1316 1379 +2438 1316 1212 1499 +2439 1336 1212 1373 +2440 1212 1336 1499 +2441 1373 1212 1502 +2442 1212 1379 1502 +2443 1213 1286 1324 +2444 1286 1213 1461 +2445 1213 1287 1494 +2446 1287 1213 1521 +2447 1288 1213 1354 +2448 1213 1288 1521 +2449 1213 1324 1354 +2450 1461 1213 1494 +2451 1214 1273 1313 +2452 1273 1214 1392 +2453 1214 1279 1392 +2454 1279 1214 1416 +2455 1214 1313 1327 +2456 1214 1327 1416 +2457 1267 1215 1359 +2458 1215 1267 1387 +2459 1326 1215 1387 +2460 1215 1326 1517 +2461 1215 1351 1453 +2462 1351 1215 1517 +2463 1359 1215 1453 +2464 1216 1308 1311 +2465 1308 1216 1506 +2466 1216 1311 1511 +2467 1321 1216 1449 +2468 1216 1321 1506 +2469 1216 1323 1449 +2470 1323 1216 1511 +2471 1309 1217 1325 +2472 1217 1309 1507 +2473 1217 1322 1357 +2474 1322 1217 1507 +2475 1325 1217 1491 +2476 1217 1357 1491 +2477 1218 1310 1353 +2478 1310 1218 1470 +2479 1218 1345 1470 +2480 1345 1218 1504 +2481 1218 1353 1504 +2482 1276 1219 1355 +2483 1219 1276 1417 +2484 1346 1219 1480 +2485 1219 1346 1503 +2486 1355 1219 1503 +2487 1219 1417 1480 +2488 1301 1220 1304 +2489 1220 1301 1389 +2490 1304 1220 1356 +2491 1356 1220 1385 +2492 1220 1358 1385 +2493 1358 1220 1389 +2494 1221 1274 1352 +2495 1274 1221 1367 +2496 1221 1312 1367 +2497 1312 1221 1455 +2498 1221 1350 1455 +2499 1350 1221 1522 +2500 1221 1352 1522 +2501 1222 1264 1369 +2502 1264 1222 1374 +2503 1222 1337 1374 +2504 1337 1222 1485 +2505 1222 1369 1512 +2506 1485 1222 1512 +2507 1223 1278 1335 +2508 1278 1223 1364 +2509 1223 1290 1371 +2510 1290 1223 1475 +2511 1293 1223 1371 +2512 1223 1293 1508 +2513 1223 1335 1475 +2514 1364 1223 1508 +2515 1277 1224 1334 +2516 1224 1277 1363 +2517 1289 1224 1372 +2518 1224 1289 1474 +2519 1224 1294 1372 +2520 1294 1224 1509 +2521 1334 1224 1474 +2522 1224 1363 1509 +2523 1276 1225 1368 +2524 1225 1276 1429 +2525 1225 1331 1347 +2526 1331 1225 1429 +2527 1225 1347 1524 +2528 1368 1225 1459 +2529 1459 1225 1524 +2530 1226 1289 1361 +2531 1289 1226 1419 +2532 1226 1305 1315 +2533 1305 1226 1361 +2534 1226 1315 1318 +2535 1226 1318 1419 +2536 1227 1290 1418 +2537 1290 1227 1523 +2538 1314 1227 1317 +2539 1227 1314 1347 +2540 1317 1227 1418 +2541 1331 1227 1347 +2542 1227 1331 1523 +2543 1228 1277 1334 +2544 1277 1228 1378 +2545 1285 1228 1410 +2546 1228 1285 1436 +2547 1228 1334 1447 +2548 1378 1228 1436 +2549 1410 1228 1447 +2550 1278 1229 1335 +2551 1229 1278 1377 +2552 1229 1284 1411 +2553 1284 1229 1435 +2554 1335 1229 1448 +2555 1229 1377 1435 +2556 1229 1411 1448 +2557 1230 1375 1401 +2558 1375 1230 1472 +2559 1390 1230 1396 +2560 1230 1390 1472 +2561 1396 1230 1401 +2562 1298 1231 1360 +2563 1231 1298 1505 +2564 1313 1231 1327 +2565 1231 1313 1514 +2566 1327 1231 1505 +2567 1360 1231 1468 +2568 1468 1231 1514 +2569 1292 1232 1393 +2570 1232 1292 1395 +2571 1329 1232 1370 +2572 1232 1329 1393 +2573 1370 1232 1466 +2574 1232 1395 1466 +2575 1233 1332 1403 +2576 1332 1233 1424 +2577 1391 1233 1403 +2578 1233 1391 1516 +2579 1424 1233 1473 +2580 1473 1233 1516 +2581 1234 1340 1432 +2582 1340 1234 1510 +2583 1342 1234 1434 +2584 1234 1342 1510 +2585 1381 1234 1432 +2586 1234 1381 1434 +2587 1302 1235 1333 +2588 1235 1302 1425 +2589 1333 1235 1383 +2590 1235 1341 1365 +2591 1341 1235 1425 +2592 1235 1365 1383 +2593 1365 1236 1383 +2594 1236 1365 1469 +2595 1383 1236 1452 +2596 1236 1428 1452 +2597 1428 1236 1487 +2598 1236 1469 1487 +2599 1300 1237 1405 +2600 1237 1300 1407 +2601 1237 1329 1370 +2602 1329 1237 1407 +2603 1237 1370 1486 +2604 1405 1237 1486 +2605 1238 1275 1408 +2606 1275 1238 1420 +2607 1238 1296 1386 +2608 1296 1238 1450 +2609 1238 1386 1420 +2610 1238 1408 1450 +2611 1295 1239 1362 +2612 1239 1295 1412 +2613 1362 1239 1409 +2614 1239 1397 1409 +2615 1397 1239 1412 +2616 1240 1305 1361 +2617 1305 1240 1385 +2618 1240 1310 1356 +2619 1310 1240 1442 +2620 1240 1356 1385 +2621 1240 1361 1442 +2622 1241 1291 1320 +2623 1291 1241 1451 +2624 1241 1320 1340 +2625 1241 1340 1430 +2626 1341 1241 1430 +2627 1241 1341 1451 +2628 1242 1297 1382 +2629 1297 1242 1491 +2630 1307 1242 1382 +2631 1242 1307 1496 +2632 1325 1242 1384 +2633 1242 1325 1491 +2634 1384 1242 1496 +2635 1243 1279 1406 +2636 1279 1243 1443 +2637 1243 1286 1443 +2638 1286 1243 1464 +2639 1388 1243 1406 +2640 1243 1388 1464 +2641 1244 1332 1445 +2642 1332 1244 1458 +2643 1444 1244 1445 +2644 1244 1444 1476 +2645 1458 1244 1476 +2646 1348 1245 1414 +2647 1245 1348 1513 +2648 1245 1380 1414 +2649 1380 1245 1423 +2650 1423 1245 1513 +2651 1246 1298 1360 +2652 1298 1246 1459 +2653 1246 1337 1368 +2654 1337 1246 1520 +2655 1246 1360 1520 +2656 1246 1368 1459 +2657 1247 1339 1358 +2658 1339 1247 1394 +2659 1247 1358 1389 +2660 1247 1389 1413 +2661 1394 1247 1413 +2662 1303 1248 1352 +2663 1248 1303 1479 +2664 1248 1306 1446 +2665 1306 1248 1479 +2666 1350 1248 1446 +2667 1248 1350 1522 +2668 1352 1248 1522 +2669 1249 1319 1343 +2670 1319 1249 1413 +2671 1249 1343 1493 +2672 1394 1249 1404 +2673 1249 1394 1413 +2674 1404 1249 1493 +2675 1324 1250 1354 +2676 1250 1324 1441 +2677 1250 1342 1434 +2678 1342 1250 1441 +2679 1354 1250 1434 +2680 1344 1251 1465 +2681 1251 1344 1500 +2682 1251 1349 1465 +2683 1349 1251 1471 +2684 1251 1398 1471 +2685 1398 1251 1500 +2686 1316 1252 1460 +2687 1252 1316 1499 +2688 1252 1336 1415 +2689 1336 1252 1499 +2690 1366 1252 1415 +2691 1252 1366 1460 +2692 1253 1338 1433 +2693 1338 1253 1515 +2694 1253 1339 1439 +2695 1339 1253 1490 +2696 1253 1433 1490 +2697 1253 1439 1515 +2698 1254 1416 1489 +2699 1416 1254 1497 +2700 1454 1254 1489 +2701 1254 1454 1497 +2702 1351 1255 1415 +2703 1255 1351 1517 +2704 1255 1366 1415 +2705 1366 1255 1456 +2706 1456 1255 1517 +2707 1293 1256 1399 +2708 1256 1293 1477 +2709 1355 1256 1477 +2710 1256 1355 1503 +2711 1399 1256 1421 +2712 1421 1256 1503 +2713 1257 1294 1400 +2714 1294 1257 1478 +2715 1257 1353 1478 +2716 1353 1257 1504 +2717 1257 1400 1422 +2718 1257 1422 1504 +2719 1258 1309 1470 +2720 1309 1258 1507 +2721 1258 1345 1438 +2722 1345 1258 1470 +2723 1427 1258 1438 +2724 1258 1427 1507 +2725 1308 1259 1480 +2726 1259 1308 1506 +2727 1346 1259 1437 +2728 1259 1346 1480 +2729 1259 1426 1437 +2730 1426 1259 1506 +2731 1260 1311 1485 +2732 1311 1260 1511 +2733 1431 1260 1440 +2734 1260 1431 1511 +2735 1440 1260 1512 +2736 1260 1485 1512 +2737 1261 1376 1467 +2738 1376 1261 1483 +2739 1261 1379 1483 +2740 1379 1261 1502 +2741 1261 1467 1502 +2742 1262 1351 1391 +2743 1351 1262 1453 +2744 1262 1391 1403 +2745 1262 1403 1492 +2746 1453 1262 1492 +2747 1263 1336 1373 +2748 1336 1263 1516 +2749 1263 1373 1501 +2750 1473 1263 1501 +2751 1263 1473 1516 +2752 1312 1264 1367 +2753 1264 1312 1495 +2754 1369 1264 1495 +2755 1265 1299 1388 +2756 1299 1265 1445 +2757 1265 1388 1406 +2758 1265 1406 1444 +2759 1265 1444 1445 +2760 1320 1266 1484 +2761 1266 1320 1498 +2762 1362 1266 1398 +2763 1266 1362 1484 +2764 1398 1266 1471 +2765 1471 1266 1498 +2766 1267 1359 1482 +2767 1402 1267 1482 +2768 1268 1338 1381 +2769 1268 1381 1432 +2770 1397 1268 1409 +2771 1409 1268 1432 +2772 1306 1269 1462 +2773 1328 1269 1457 +2774 1269 1328 1463 +2775 1462 1269 1463 +2776 1270 1328 1481 +2777 1270 1380 1423 +2778 1380 1270 1481 +2779 1390 1271 1472 +2780 1271 1461 1494 +2781 1272 1342 1441 +2782 1342 1272 1469 +2783 1272 1441 1518 +2784 1469 1272 1487 +2785 1487 1272 1518 +2786 1273 1390 1396 +2787 1352 1274 1514 +2788 1274 1468 1514 +2789 1330 1275 1476 +2790 1275 1458 1476 +2791 1276 1355 1429 +2792 1392 1279 1443 +2793 1375 1280 1519 +2794 1280 1457 1519 +2795 1281 1373 1502 +2796 1467 1281 1502 +2797 1424 1282 1428 +2798 1282 1424 1473 +2799 1428 1282 1452 +2800 1452 1282 1501 +2801 1282 1473 1501 +2802 1283 1359 1453 +2803 1386 1283 1420 +2804 1420 1283 1492 +2805 1283 1453 1492 +2806 1284 1402 1482 +2807 1411 1284 1482 +2808 1285 1344 1488 +2809 1344 1285 1500 +2810 1436 1285 1488 +2811 1324 1286 1464 +2812 1287 1404 1493 +2813 1404 1287 1521 +2814 1439 1288 1515 +2815 1288 1439 1521 +2816 1289 1419 1474 +2817 1371 1290 1523 +2818 1418 1290 1475 +2819 1320 1291 1498 +2820 1395 1291 1466 +2821 1291 1451 1466 +2822 1293 1371 1477 +2823 1372 1294 1478 +2824 1295 1410 1447 +2825 1411 1296 1448 +2826 1448 1296 1450 +2827 1357 1297 1491 +2828 1298 1459 1524 +2829 1505 1298 1524 +2830 1388 1299 1518 +2831 1299 1428 1487 +2832 1299 1487 1518 +2833 1302 1405 1486 +2834 1303 1396 1401 +2835 1303 1401 1479 +2836 1417 1308 1480 +2837 1309 1310 1470 +2838 1353 1310 1442 +2839 1311 1337 1485 +2840 1314 1454 1489 +2841 1433 1315 1490 +2842 1408 1317 1450 +2843 1319 1380 1481 +2844 1321 1426 1506 +2845 1427 1322 1507 +2846 1431 1323 1511 +2847 1326 1456 1517 +2848 1416 1327 1489 +2849 1489 1327 1505 +2850 1454 1330 1497 +2851 1374 1337 1520 +2852 1430 1340 1510 +2853 1341 1425 1451 +2854 1422 1345 1504 +2855 1346 1421 1503 +2856 1362 1409 1484 +2857 1401 1375 1519 +2 13 2 278 +2858 1624 180 9 +2859 213 1624 9 +2860 183 1530 16 +2861 1530 247 16 +2862 1528 242 19 +2863 246 1528 19 +2864 1623 243 20 +2865 276 1623 20 +2866 180 1621 181 +2867 180 1624 1621 +2868 181 1622 182 +2869 1621 1622 181 +2870 1531 183 182 +2871 1622 1531 182 +2872 1530 183 1531 +2873 214 1536 213 +2874 1624 213 1536 +2875 1539 214 215 +2876 1536 214 1539 +2877 1618 215 216 +2878 215 1543 1539 +2879 215 1618 1543 +2880 1614 216 217 +2881 216 1614 1618 +2882 1616 217 218 +2883 217 1616 1614 +2884 1608 218 219 +2885 218 1608 1616 +2886 1610 219 220 +2887 219 1610 1608 +2888 1604 220 221 +2889 220 1604 1610 +2890 1598 221 222 +2891 221 1598 1604 +2892 1601 222 223 +2893 222 1601 1598 +2894 1594 223 224 +2895 223 1594 1601 +2896 1591 224 225 +2897 224 1591 1594 +2898 1586 225 226 +2899 225 1586 1591 +2900 1588 226 227 +2901 226 1588 1586 +2902 1580 227 228 +2903 227 1580 1588 +2904 1582 228 229 +2905 228 1582 1580 +2906 1576 229 230 +2907 229 1576 1582 +2908 1573 230 231 +2909 230 1573 1576 +2910 1570 231 232 +2911 231 1570 1573 +2912 1565 232 233 +2913 232 1565 1570 +2914 1567 233 234 +2915 233 1567 1565 +2916 1561 234 235 +2917 234 1561 1567 +2918 1558 235 236 +2919 235 1558 1561 +2920 1555 236 237 +2921 236 1555 1558 +2922 1550 237 238 +2923 237 1550 1555 +2924 1552 238 239 +2925 238 1552 1550 +2926 1545 239 240 +2927 239 1545 1552 +2928 1599 240 241 +2929 240 1599 1545 +2930 1528 241 242 +2931 1628 241 1528 +2932 241 1542 1599 +2933 241 1628 1542 +2934 243 1619 244 +2935 243 1623 1619 +2936 244 1620 245 +2937 1619 1620 244 +2938 1529 246 245 +2939 1620 1529 245 +2940 1528 246 1529 +2941 1530 248 247 +2942 1527 249 248 +2943 248 1526 1527 +2944 248 1627 1526 +2945 1627 248 1530 +2946 1617 250 249 +2947 249 1527 1617 +2948 1613 251 250 +2949 250 1617 1613 +2950 1615 252 251 +2951 251 1613 1615 +2952 1607 253 252 +2953 252 1615 1607 +2954 1609 254 253 +2955 253 1607 1609 +2956 1603 255 254 +2957 254 1609 1603 +2958 1597 256 255 +2959 255 1603 1597 +2960 1600 257 256 +2961 256 1597 1600 +2962 1593 258 257 +2963 257 1600 1593 +2964 1590 259 258 +2965 258 1593 1590 +2966 1585 260 259 +2967 259 1590 1585 +2968 1587 261 260 +2969 260 1585 1587 +2970 1579 262 261 +2971 261 1587 1579 +2972 1581 263 262 +2973 262 1579 1581 +2974 1575 264 263 +2975 263 1581 1575 +2976 1572 265 264 +2977 264 1575 1572 +2978 1569 266 265 +2979 265 1572 1569 +2980 1564 267 266 +2981 266 1569 1564 +2982 1566 268 267 +2983 267 1564 1566 +2984 1560 269 268 +2985 268 1566 1560 +2986 1557 270 269 +2987 269 1560 1557 +2988 1554 271 270 +2989 270 1557 1554 +2990 1549 272 271 +2991 271 1554 1549 +2992 1551 273 272 +2993 272 1549 1551 +2994 1546 274 273 +2995 273 1551 1546 +2996 1535 275 274 +2997 274 1541 1535 +2998 274 1546 1541 +2999 275 1532 276 +3000 1532 275 1535 +3001 1623 276 1532 +3002 1525 1527 1526 +3003 1525 1526 1538 +3004 1527 1525 1617 +3005 1538 1543 1525 +3006 1618 1525 1543 +3007 1612 1617 1525 +3008 1525 1618 1612 +3009 1627 1538 1526 +3010 1528 1529 1625 +3011 1625 1628 1528 +3012 1620 1625 1529 +3013 1530 1531 1626 +3014 1626 1627 1530 +3015 1622 1626 1531 +3016 1532 1534 1533 +3017 1619 1532 1533 +3018 1534 1532 1535 +3019 1532 1619 1623 +3020 1533 1534 1625 +3021 1533 1620 1619 +3022 1625 1620 1533 +3023 1534 1535 1541 +3024 1534 1541 1540 +3025 1540 1542 1534 +3026 1628 1534 1542 +3027 1534 1628 1625 +3028 1536 1538 1537 +3029 1621 1536 1537 +3030 1538 1536 1539 +3031 1536 1621 1624 +3032 1537 1538 1626 +3033 1537 1622 1621 +3034 1626 1622 1537 +3035 1538 1539 1543 +3036 1538 1627 1626 +3037 1546 1540 1541 +3038 1540 1599 1542 +3039 1544 1545 1540 +3040 1540 1546 1544 +3041 1599 1540 1545 +3042 1545 1544 1552 +3043 1551 1544 1546 +3044 1544 1551 1547 +3045 1547 1552 1544 +3046 1547 1549 1548 +3047 1548 1550 1547 +3048 1549 1547 1551 +3049 1552 1547 1550 +3050 1554 1548 1549 +3051 1550 1548 1555 +3052 1548 1554 1553 +3053 1553 1555 1548 +3054 1557 1553 1554 +3055 1555 1553 1558 +3056 1553 1557 1556 +3057 1556 1558 1553 +3058 1560 1556 1557 +3059 1558 1556 1561 +3060 1556 1560 1559 +3061 1559 1561 1556 +3062 1566 1559 1560 +3063 1561 1559 1567 +3064 1559 1566 1562 +3065 1562 1567 1559 +3066 1562 1564 1563 +3067 1563 1565 1562 +3068 1564 1562 1566 +3069 1567 1562 1565 +3070 1569 1563 1564 +3071 1565 1563 1570 +3072 1563 1569 1568 +3073 1568 1570 1563 +3074 1572 1568 1569 +3075 1570 1568 1573 +3076 1568 1572 1571 +3077 1571 1573 1568 +3078 1575 1571 1572 +3079 1573 1571 1576 +3080 1571 1575 1574 +3081 1574 1576 1571 +3082 1581 1574 1575 +3083 1576 1574 1582 +3084 1574 1581 1577 +3085 1577 1582 1574 +3086 1577 1579 1578 +3087 1578 1580 1577 +3088 1579 1577 1581 +3089 1582 1577 1580 +3090 1587 1578 1579 +3091 1580 1578 1588 +3092 1578 1587 1583 +3093 1583 1588 1578 +3094 1583 1585 1584 +3095 1584 1586 1583 +3096 1585 1583 1587 +3097 1588 1583 1586 +3098 1590 1584 1585 +3099 1586 1584 1591 +3100 1584 1590 1589 +3101 1589 1591 1584 +3102 1593 1589 1590 +3103 1591 1589 1594 +3104 1589 1593 1592 +3105 1592 1594 1589 +3106 1600 1592 1593 +3107 1594 1592 1601 +3108 1592 1600 1595 +3109 1595 1601 1592 +3110 1595 1597 1596 +3111 1596 1598 1595 +3112 1597 1595 1600 +3113 1601 1595 1598 +3114 1603 1596 1597 +3115 1598 1596 1604 +3116 1596 1603 1602 +3117 1602 1604 1596 +3118 1609 1602 1603 +3119 1604 1602 1610 +3120 1602 1609 1605 +3121 1605 1610 1602 +3122 1605 1607 1606 +3123 1606 1608 1605 +3124 1607 1605 1609 +3125 1610 1605 1608 +3126 1615 1606 1607 +3127 1608 1606 1616 +3128 1606 1615 1611 +3129 1611 1616 1606 +3130 1611 1613 1612 +3131 1612 1614 1611 +3132 1613 1611 1615 +3133 1616 1611 1614 +3134 1617 1612 1613 +3135 1614 1612 1618 +2 14 2 1220 +3136 16 1991 187 +3137 247 1991 16 +3138 200 1993 17 +3139 17 1993 291 +3140 20 1990 276 +3141 290 1990 20 +3142 21 1992 277 +3143 320 1992 21 +3144 187 2068 188 +3145 1991 2068 187 +3146 188 2068 189 +3147 189 1933 190 +3148 1798 1933 189 +3149 189 2068 1798 +3150 190 1891 191 +3151 190 1933 1891 +3152 191 1828 192 +3153 191 1891 1828 +3154 192 2084 193 +3155 1828 2084 192 +3156 193 1885 194 +3157 193 2084 1885 +3158 194 1902 195 +3159 1885 1902 194 +3160 195 1814 196 +3161 195 1902 1814 +3162 196 1889 197 +3163 1814 1889 196 +3164 197 1935 198 +3165 1889 1935 197 +3166 198 2069 199 +3167 198 1935 1799 +3168 1799 2069 198 +3169 199 2069 200 +3170 200 2069 1993 +3171 248 2160 247 +3172 247 2160 1991 +3173 249 1954 248 +3174 1954 2160 248 +3175 250 2019 249 +3176 1784 1954 249 +3177 249 2019 1784 +3178 251 1894 250 +3179 1894 2019 250 +3180 252 2169 251 +3181 251 2169 1894 +3182 253 1910 252 +3183 1910 2169 252 +3184 254 2122 253 +3185 253 2122 1910 +3186 255 1914 254 +3187 254 1914 1879 +3188 1879 2122 254 +3189 256 2140 255 +3190 255 2140 1914 +3191 257 1854 256 +3192 1854 2140 256 +3193 258 2043 257 +3194 257 2043 1854 +3195 259 1901 258 +3196 1901 2043 258 +3197 260 2097 259 +3198 1776 1901 259 +3199 259 2097 1776 +3200 261 1951 260 +3201 1951 2097 260 +3202 262 1839 261 +3203 1839 1951 261 +3204 263 1868 262 +3205 262 1868 1839 +3206 264 2145 263 +3207 263 2145 1868 +3208 265 1864 264 +3209 1864 2145 264 +3210 266 1977 265 +3211 265 1977 1864 +3212 267 1852 266 +3213 1852 1977 266 +3214 268 2138 267 +3215 267 2138 1852 +3216 269 1913 268 +3217 1913 2138 268 +3218 270 2124 269 +3219 1876 1913 269 +3220 269 2124 1876 +3221 271 1908 270 +3222 1908 2124 270 +3223 272 2166 271 +3224 271 2166 1908 +3225 273 1897 272 +3226 1897 2166 272 +3227 274 2021 273 +3228 273 2021 1897 +3229 275 1956 274 +3230 274 1956 1787 +3231 1787 2021 274 +3232 276 2161 275 +3233 275 2161 1956 +3234 1990 2161 276 +3235 277 2067 278 +3236 1992 2067 277 +3237 278 2067 279 +3238 279 1934 280 +3239 1800 1934 279 +3240 279 2067 1800 +3241 280 1892 281 +3242 280 1934 1892 +3243 281 1829 282 +3244 281 1892 1829 +3245 282 2085 283 +3246 1829 2085 282 +3247 283 1884 284 +3248 283 2085 1884 +3249 284 1903 285 +3250 1884 1903 284 +3251 285 1815 286 +3252 285 1903 1815 +3253 286 1888 287 +3254 1815 1888 286 +3255 287 1936 288 +3256 1888 1936 287 +3257 288 2066 289 +3258 288 1936 1801 +3259 1801 2066 288 +3260 289 2066 290 +3261 290 2066 1990 +3262 291 2159 292 +3263 1993 2159 291 +3264 292 1953 293 +3265 292 2159 1953 +3266 293 2020 294 +3267 293 1953 1785 +3268 1785 2020 293 +3269 294 1895 295 +3270 294 2020 1895 +3271 295 2168 296 +3272 1895 2168 295 +3273 296 1909 297 +3274 296 2168 1909 +3275 297 2123 298 +3276 1909 2123 297 +3277 298 1915 299 +3278 1878 1915 298 +3279 298 2123 1878 +3280 299 2139 300 +3281 1915 2139 299 +3282 300 1853 301 +3283 300 2139 1853 +3284 301 2042 302 +3285 1853 2042 301 +3286 302 1900 303 +3287 302 2042 1900 +3288 303 2098 304 +3289 303 1900 1777 +3290 1777 2098 303 +3291 304 1952 305 +3292 304 2098 1952 +3293 305 1838 306 +3294 305 1952 1838 +3295 306 1867 307 +3296 1838 1867 306 +3297 307 2144 308 +3298 1867 2144 307 +3299 308 1863 309 +3300 308 2144 1863 +3301 309 1978 310 +3302 1863 1978 309 +3303 310 1855 311 +3304 310 1978 1855 +3305 311 2141 312 +3306 1855 2141 311 +3307 312 1916 313 +3308 312 2141 1916 +3309 313 2121 314 +3310 313 1916 1877 +3311 1877 2121 313 +3312 314 1907 315 +3313 314 2121 1907 +3314 315 2167 316 +3315 1907 2167 315 +3316 316 1896 317 +3317 316 2167 1896 +3318 317 2022 318 +3319 1896 2022 317 +3320 318 1955 319 +3321 1786 1955 318 +3322 318 2022 1786 +3323 319 2162 320 +3324 1955 2162 319 +3325 320 2162 1992 +3326 1629 2004 1859 +3327 1859 2125 1629 +3328 1872 2070 1629 +3329 1629 2136 1872 +3330 1629 2070 2004 +3331 2125 2136 1629 +3332 1841 2005 1630 +3333 1630 2137 1841 +3334 1630 2005 1860 +3335 1860 2126 1630 +3336 2126 2137 1630 +3337 1631 2027 1883 +3338 1883 2046 1631 +3339 1631 2000 1949 +3340 1949 2027 1631 +3341 1631 2115 2000 +3342 2046 2115 1631 +3343 1632 1998 1919 +3344 1919 2149 1632 +3345 1632 2188 1998 +3346 2052 2090 1632 +3347 1632 2149 2052 +3348 2090 2188 1632 +3349 1809 1966 1633 +3350 1633 2091 1809 +3351 1633 2051 1836 +3352 1836 2091 1633 +3353 1966 2129 1633 +3354 1633 2129 2051 +3355 1634 2053 1873 +3356 1873 2109 1634 +3357 1634 1999 1920 +3358 1920 2150 1634 +3359 1634 2109 1999 +3360 1634 2150 2053 +3361 1808 1932 1635 +3362 1635 2092 1808 +3363 1635 2054 1837 +3364 1837 2092 1635 +3365 1932 2151 1635 +3366 1635 2151 2054 +3367 1636 1982 1842 +3368 1842 2040 1636 +3369 1636 2108 1982 +3370 2040 2152 1636 +3371 1636 2152 2108 +3372 1637 1886 1816 +3373 1816 2032 1637 +3374 1835 1886 1637 +3375 1637 2041 1835 +3376 2032 2041 1637 +3377 1638 1983 1843 +3378 1843 2039 1638 +3379 1638 2107 1983 +3380 2039 2153 1638 +3381 1638 2153 2107 +3382 1639 1887 1817 +3383 1817 2033 1639 +3384 1834 1887 1639 +3385 1639 2038 1834 +3386 2033 2038 1639 +3387 1640 2095 1857 +3388 1857 2119 1640 +3389 1640 2118 2095 +3390 1640 2182 2118 +3391 2119 2182 1640 +3392 1641 2117 1826 +3393 1826 2183 1641 +3394 1827 2120 1641 +3395 1641 2183 1827 +3396 1856 2096 1641 +3397 1641 2120 1856 +3398 2096 2117 1641 +3399 1813 1912 1642 +3400 1642 2017 1813 +3401 1912 2099 1642 +3402 1642 2130 2017 +3403 2099 2130 1642 +3404 1643 1844 1803 +3405 1803 2028 1643 +3406 1643 2057 1844 +3407 2028 2177 1643 +3408 1643 2083 2057 +3409 1643 2177 2083 +3410 1812 1911 1644 +3411 1644 2016 1812 +3412 1911 2100 1644 +3413 1644 2131 2016 +3414 2100 2131 1644 +3415 1645 1845 1802 +3416 1802 2029 1645 +3417 1645 2056 1845 +3418 2029 2176 1645 +3419 1645 2082 2056 +3420 1645 2176 2082 +3421 1646 1943 1830 +3422 1830 1973 1646 +3423 1646 2164 1943 +3424 1646 1973 1971 +3425 1971 2164 1646 +3426 1647 1944 1831 +3427 1831 1974 1647 +3428 1647 2163 1944 +3429 1647 1974 1972 +3430 1972 2163 1647 +3431 1869 2006 1648 +3432 1648 2063 1869 +3433 1648 2006 1870 +3434 1870 2071 1648 +3435 1648 2156 2063 +3436 2071 2156 1648 +3437 1858 1965 1649 +3438 1649 2014 1858 +3439 1865 2014 1649 +3440 1649 2015 1865 +3441 1649 1965 1871 +3442 1871 2015 1649 +3443 1650 1968 1904 +3444 1904 2047 1650 +3445 1925 1968 1650 +3446 1650 1994 1925 +3447 1650 2093 1994 +3448 2047 2093 1650 +3449 1905 1967 1651 +3450 1651 2048 1905 +3451 1651 1967 1928 +3452 1928 1996 1651 +3453 1996 2094 1651 +3454 1651 2094 2048 +3455 1776 1963 1652 +3456 1652 2077 1776 +3457 1652 1995 1926 +3458 1926 2077 1652 +3459 1963 2158 1652 +3460 1652 2072 1995 +3461 1652 2158 2072 +3462 1653 1964 1777 +3463 1777 2076 1653 +3464 1927 1997 1653 +3465 1653 2076 1927 +3466 1653 2157 1964 +3467 1997 2073 1653 +3468 2073 2157 1653 +3469 1840 1981 1654 +3470 1654 2132 1840 +3471 1654 2007 1976 +3472 1976 2132 1654 +3473 1981 2007 1654 +3474 1655 1975 1811 +3475 1811 2009 1655 +3476 1866 2008 1655 +3477 1655 2009 1866 +3478 1655 2008 1975 +3479 1847 1987 1656 +3480 1656 2010 1847 +3481 1987 2173 1656 +3482 1656 2023 2010 +3483 1656 2173 2023 +3484 1657 1986 1846 +3485 1846 2011 1657 +3486 1657 2174 1986 +3487 2011 2024 1657 +3488 2024 2174 1657 +3489 1848 1988 1658 +3490 1658 2012 1848 +3491 1988 2172 1658 +3492 1658 2025 2012 +3493 1658 2172 2025 +3494 1659 1989 1849 +3495 1849 2013 1659 +3496 1659 2175 1989 +3497 2013 2026 1659 +3498 2026 2175 1659 +3499 1660 1937 1813 +3500 1813 2037 1660 +3501 1921 2088 1660 +3502 1660 2105 1921 +3503 1660 2088 1937 +3504 2037 2105 1660 +3505 1792 1958 1661 +3506 1661 2035 1792 +3507 1661 1924 1851 +3508 1851 2035 1661 +3509 1661 2086 1924 +3510 1958 2086 1661 +3511 1662 1938 1812 +3512 1812 2036 1662 +3513 1923 2087 1662 +3514 1662 2106 1923 +3515 1662 2087 1938 +3516 2036 2106 1662 +3517 1793 1957 1663 +3518 1663 2034 1793 +3519 1663 1922 1850 +3520 1850 2034 1663 +3521 1663 2089 1922 +3522 1957 2089 1663 +3523 1790 1959 1664 +3524 1664 2079 1790 +3525 1664 1969 1794 +3526 1794 2079 1664 +3527 1959 2064 1664 +3528 1664 2064 1969 +3529 1789 1961 1665 +3530 1665 2078 1789 +3531 1665 1970 1795 +3532 1795 2078 1665 +3533 1961 2065 1665 +3534 1665 2065 1970 +3535 1666 1984 1781 +3536 1781 2147 1666 +3537 1666 1960 1788 +3538 1788 2104 1666 +3539 1666 2147 1960 +3540 1666 2104 1984 +3541 1667 1985 1780 +3542 1780 2146 1667 +3543 1667 1962 1791 +3544 1791 2103 1667 +3545 1667 2146 1962 +3546 1667 2103 1985 +3547 1827 1947 1668 +3548 1668 1980 1827 +3549 1947 2112 1668 +3550 1668 2170 1980 +3551 2112 2170 1668 +3552 1669 1948 1825 +3553 1825 2055 1669 +3554 1669 2055 1931 +3555 1931 2148 1669 +3556 1669 2165 1948 +3557 2148 2165 1669 +3558 1824 1882 1670 +3559 1670 1979 1824 +3560 1882 2018 1670 +3561 1670 2171 1979 +3562 2018 2171 1670 +3563 1671 1950 1826 +3564 1826 2001 1671 +3565 1671 2001 1906 +3566 1906 2135 1671 +3567 1671 2189 1950 +3568 2135 2189 1671 +3569 1804 2002 1672 +3570 1672 2134 1804 +3571 1672 1811 1808 +3572 1808 1946 1672 +3573 1672 2193 1811 +3574 1946 2134 1672 +3575 2002 2193 1672 +3576 1805 2003 1673 +3577 1673 2133 1805 +3578 1673 1810 1809 +3579 1809 1945 1673 +3580 1673 2192 1810 +3581 1945 2133 1673 +3582 2003 2192 1673 +3583 1806 1875 1674 +3584 1674 2030 1806 +3585 1674 1875 1862 +3586 1862 2111 1674 +3587 1674 2184 2030 +3588 2111 2184 1674 +3589 1807 1874 1675 +3590 1675 2031 1807 +3591 1675 1874 1861 +3592 1861 2110 1675 +3593 1675 2185 2031 +3594 2110 2185 1675 +3595 1676 2059 1831 +3596 1831 2143 1676 +3597 1676 1941 1842 +3598 1842 2059 1676 +3599 1676 2074 1941 +3600 1676 2143 2074 +3601 1677 2058 1830 +3602 1830 2142 1677 +3603 1677 1939 1843 +3604 1843 2058 1677 +3605 1677 2075 1939 +3606 1677 2142 2075 +3607 1814 2050 1678 +3608 1678 2061 1814 +3609 1835 1942 1678 +3610 1678 2190 1835 +3611 1678 2050 1898 +3612 1898 2190 1678 +3613 1942 2061 1678 +3614 1815 2049 1679 +3615 1679 2062 1815 +3616 1834 1940 1679 +3617 1679 2191 1834 +3618 1679 2049 1899 +3619 1899 2191 1679 +3620 1940 2062 1679 +3621 1816 1880 1680 +3622 1680 2101 1816 +3623 1680 1929 1819 +3624 1819 2101 1680 +3625 1680 1880 1860 +3626 1860 1929 1680 +3627 1817 1881 1681 +3628 1681 2102 1817 +3629 1681 1930 1818 +3630 1818 2102 1681 +3631 1681 1881 1859 +3632 1859 1930 1681 +3633 1803 1844 1682 +3634 1682 2116 1803 +3635 1840 1872 1682 +3636 1682 1981 1840 +3637 1844 1890 1682 +3638 1872 2116 1682 +3639 1890 1981 1682 +3640 1802 1845 1683 +3641 1683 2060 1802 +3642 1683 1866 1841 +3643 1841 2060 1683 +3644 1845 1893 1683 +3645 1683 1893 1866 +3646 1684 1832 1780 +3647 1780 2029 1684 +3648 1684 1875 1806 +3649 1806 2108 1684 +3650 1684 2108 1832 +3651 1684 2114 1875 +3652 2029 2114 1684 +3653 1685 1833 1781 +3654 1781 2028 1685 +3655 1685 1874 1807 +3656 1807 2107 1685 +3657 1685 2107 1833 +3658 1685 2113 1874 +3659 2028 2113 1685 +3660 1686 1867 1838 +3661 1838 1917 1686 +3662 1856 1904 1686 +3663 1686 2096 1856 +3664 1686 2186 1867 +3665 1904 2186 1686 +3666 1917 2096 1686 +3667 1839 1868 1687 +3668 1687 1918 1839 +3669 1687 1905 1857 +3670 1857 2095 1687 +3671 1868 2187 1687 +3672 1687 2187 1905 +3673 1687 2095 1918 +3674 1768 1913 1688 +3675 1688 1937 1768 +3676 1688 1912 1813 +3677 1813 1937 1688 +3678 1688 1913 1876 +3679 1876 2080 1688 +3680 1688 2080 1912 +3681 1689 1958 1792 +3682 1792 2083 1689 +3683 1689 2083 1822 +3684 1822 2128 1689 +3685 1877 1916 1689 +3686 1689 2128 1877 +3687 1916 1958 1689 +3688 1769 1915 1690 +3689 1690 1938 1769 +3690 1690 1911 1812 +3691 1812 1938 1690 +3692 1690 1915 1878 +3693 1878 2081 1690 +3694 1690 2081 1911 +3695 1691 1957 1793 +3696 1793 2082 1691 +3697 1691 2082 1823 +3698 1823 2127 1691 +3699 1879 1914 1691 +3700 1691 2127 1879 +3701 1914 1957 1691 +3702 1692 1886 1778 +3703 1778 1972 1692 +3704 1692 1880 1816 +3705 1816 1886 1692 +3706 1692 2044 1880 +3707 1972 2044 1692 +3708 1693 1887 1779 +3709 1779 1971 1693 +3710 1693 1881 1817 +3711 1817 1887 1693 +3712 1693 2045 1881 +3713 1971 2045 1693 +3714 1694 1893 1845 +3715 1845 2056 1694 +3716 1850 1920 1694 +3717 1694 2034 1850 +3718 1694 1920 1893 +3719 1694 2056 2034 +3720 1695 1890 1844 +3721 1844 2057 1695 +3722 1851 1919 1695 +3723 1695 2035 1851 +3724 1695 1919 1890 +3725 1695 2057 2035 +3726 1787 2013 1696 +3727 1696 2021 1787 +3728 1790 1897 1696 +3729 1696 1959 1790 +3730 1897 2021 1696 +3731 1696 2181 1959 +3732 2013 2181 1696 +3733 1697 2012 1786 +3734 1786 2022 1697 +3735 1697 1896 1788 +3736 1788 1960 1697 +3737 1697 2022 1896 +3738 1960 2180 1697 +3739 1697 2180 2012 +3740 1785 2011 1698 +3741 1698 2020 1785 +3742 1789 1895 1698 +3743 1698 1961 1789 +3744 1895 2020 1698 +3745 1698 2179 1961 +3746 2011 2179 1698 +3747 1699 2010 1784 +3748 1784 2019 1699 +3749 1699 1894 1791 +3750 1791 1962 1699 +3751 1699 2019 1894 +3752 1962 2178 1699 +3753 1699 2178 2010 +3754 1700 1882 1824 +3755 1824 2182 1700 +3756 1825 1948 1700 +3757 1700 2182 1825 +3758 1700 2000 1882 +3759 1948 1949 1700 +3760 1949 2000 1700 +3761 1883 1947 1701 +3762 1701 2046 1883 +3763 1947 2183 1701 +3764 1950 2046 1701 +3765 1701 2183 1950 +3766 1777 1964 1702 +3767 1702 2098 1777 +3768 1820 1917 1702 +3769 1702 1964 1820 +3770 1702 1917 1838 +3771 1838 1952 1702 +3772 1952 2098 1702 +3773 1703 1963 1776 +3774 1776 2097 1703 +3775 1703 1918 1821 +3776 1821 1963 1703 +3777 1839 1918 1703 +3778 1703 1951 1839 +3779 1703 2097 1951 +3780 1808 1811 1704 +3781 1704 1932 1808 +3782 1811 1975 1704 +3783 1704 1975 1870 +3784 1870 2006 1704 +3785 1704 2006 1932 +3786 1809 1810 1705 +3787 1705 1966 1809 +3788 1810 1976 1705 +3789 1871 1965 1705 +3790 1705 1976 1871 +3791 1965 1966 1705 +3792 1706 1977 1852 +3793 1852 2088 1706 +3794 1706 1967 1864 +3795 1864 1977 1706 +3796 1921 1928 1706 +3797 1706 2088 1921 +3798 1928 1967 1706 +3799 1855 1978 1707 +3800 1707 2086 1855 +3801 1863 1968 1707 +3802 1707 1978 1863 +3803 1707 1925 1924 +3804 1924 2086 1707 +3805 1707 1968 1925 +3806 1708 2042 1853 +3807 1853 2087 1708 +3808 1900 2042 1708 +3809 1708 2076 1900 +3810 1923 1927 1708 +3811 1708 2087 1923 +3812 1927 2076 1708 +3813 1854 2043 1709 +3814 1709 2089 1854 +3815 1709 2043 1901 +3816 1901 2077 1709 +3817 1709 1926 1922 +3818 1922 2089 1709 +3819 1709 2077 1926 +3820 1710 1903 1884 +3821 1884 2155 1710 +3822 1710 1943 1899 +3823 1899 2049 1710 +3824 1710 2049 1903 +3825 1710 2155 1943 +3826 1711 1902 1885 +3827 1885 2154 1711 +3828 1711 1944 1898 +3829 1898 2050 1711 +3830 1711 2050 1902 +3831 1711 2154 1944 +3832 1842 1982 1712 +3833 1712 2059 1842 +3834 1712 2030 1974 +3835 1974 2059 1712 +3836 1982 2030 1712 +3837 1843 1983 1713 +3838 1713 2058 1843 +3839 1713 2031 1973 +3840 1973 2058 1713 +3841 1983 2031 1713 +3842 1714 1934 1800 +3843 1800 1988 1714 +3844 1892 1934 1714 +3845 1714 2075 1892 +3846 1714 1988 1939 +3847 1939 2075 1714 +3848 1715 1933 1798 +3849 1798 1987 1715 +3850 1891 1933 1715 +3851 1715 2074 1891 +3852 1715 1987 1941 +3853 1941 2074 1715 +3854 1799 1935 1716 +3855 1716 1986 1799 +3856 1716 1935 1889 +3857 1889 2061 1716 +3858 1942 1986 1716 +3859 1716 2061 1942 +3860 1801 1936 1717 +3861 1717 1989 1801 +3862 1717 1936 1888 +3863 1888 2062 1717 +3864 1940 1989 1717 +3865 1717 2062 1940 +3866 1812 2016 1718 +3867 1718 2036 1812 +3868 1718 1946 1837 +3869 1837 2036 1718 +3870 1718 2134 1946 +3871 2016 2134 1718 +3872 1813 2017 1719 +3873 1719 2037 1813 +3874 1719 1945 1836 +3875 1836 2037 1719 +3876 1719 2133 1945 +3877 2017 2133 1719 +3878 1871 1976 1720 +3879 1720 2015 1871 +3880 1976 2007 1720 +3881 1720 2007 1998 +3882 1998 2188 1720 +3883 1720 2188 2015 +3884 1870 1975 1721 +3885 1721 2071 1870 +3886 1975 2008 1721 +3887 1721 2008 1999 +3888 1999 2109 1721 +3889 1721 2109 2071 +3890 1836 2051 1722 +3891 1722 2105 1836 +3892 1722 1928 1921 +3893 1921 2105 1722 +3894 1722 1996 1928 +3895 1722 2051 1996 +3896 1851 1924 1723 +3897 1723 2149 1851 +3898 1924 1925 1723 +3899 1925 1994 1723 +3900 1994 2052 1723 +3901 2052 2149 1723 +3902 1837 2054 1724 +3903 1724 2106 1837 +3904 1724 1927 1923 +3905 1923 2106 1724 +3906 1724 1997 1927 +3907 1724 2054 1997 +3908 1850 1922 1725 +3909 1725 2150 1850 +3910 1922 1926 1725 +3911 1926 1995 1725 +3912 1995 2053 1725 +3913 2053 2150 1725 +3914 1726 2014 1865 +3915 1865 2112 1726 +3916 1726 1947 1883 +3917 1883 2027 1726 +3918 1726 2112 1947 +3919 1726 2027 2014 +3920 1882 2000 1727 +3921 1727 2018 1882 +3922 2000 2115 1727 +3923 1727 2156 2018 +3924 1727 2115 2063 +3925 2063 2156 1727 +3926 1954 2023 1728 +3927 1728 2160 1954 +3928 1728 2068 1991 +3929 1991 2160 1728 +3930 2023 2173 1728 +3931 1728 2173 2068 +3932 1729 2024 1953 +3933 1953 2159 1729 +3934 1993 2069 1729 +3935 1729 2159 1993 +3936 1729 2174 2024 +3937 2069 2174 1729 +3938 1955 2025 1730 +3939 1730 2162 1955 +3940 1730 2067 1992 +3941 1992 2162 1730 +3942 2025 2172 1730 +3943 1730 2172 2067 +3944 1731 2026 1956 +3945 1956 2161 1731 +3946 1990 2066 1731 +3947 1731 2161 1990 +3948 1731 2175 2026 +3949 2066 2175 1731 +3950 1819 1970 1732 +3951 1732 2101 1819 +3952 1970 2065 1732 +3953 1732 2065 2032 +3954 2032 2101 1732 +3955 1818 1969 1733 +3956 1733 2102 1818 +3957 1969 2064 1733 +3958 1733 2064 2033 +3959 2033 2102 1733 +3960 1805 1930 1734 +3961 1734 2003 1805 +3962 1734 1930 1859 +3963 1859 2004 1734 +3964 1734 2004 2003 +3965 1804 1929 1735 +3966 1735 2002 1804 +3967 1735 1929 1860 +3968 1860 2005 1735 +3969 1735 2005 2002 +3970 1859 1881 1736 +3971 1736 2125 1859 +3972 1736 2110 1861 +3973 1861 2125 1736 +3974 1881 2045 1736 +3975 2045 2110 1736 +3976 1860 1880 1737 +3977 1737 2126 1860 +3978 1737 2111 1862 +3979 1862 2126 1737 +3980 1880 2044 1737 +3981 2044 2111 1737 +3982 1824 1979 1738 +3983 1738 2118 1824 +3984 1979 2072 1738 +3985 2072 2158 1738 +3986 1738 2158 2118 +3987 1739 2001 1826 +3988 1826 2117 1739 +3989 1739 2073 2001 +3990 1739 2157 2073 +3991 2117 2157 1739 +3992 1827 1980 1740 +3993 1740 2120 1827 +3994 1740 2047 1856 +3995 1856 2120 1740 +3996 1980 2093 1740 +3997 1740 2093 2047 +3998 1741 2055 1825 +3999 1825 2119 1741 +4000 1857 2048 1741 +4001 1741 2119 1857 +4002 2048 2094 1741 +4003 1741 2094 2055 +4004 1742 2121 1877 +4005 1877 2128 1742 +4006 1742 2104 1907 +4007 1907 2121 1742 +4008 1984 2104 1742 +4009 1742 2128 1984 +4010 1743 2122 1879 +4011 1879 2127 1743 +4012 1743 2103 1910 +4013 1910 2122 1743 +4014 1985 2103 1743 +4015 1743 2127 1985 +4016 1744 2079 1794 +4017 1794 2080 1744 +4018 1744 2080 1876 +4019 1876 2124 1744 +4020 1908 2079 1744 +4021 1744 2124 1908 +4022 1745 2078 1795 +4023 1795 2081 1745 +4024 1745 2081 1878 +4025 1878 2123 1745 +4026 1909 2078 1745 +4027 1745 2123 1909 +4028 1861 1874 1746 +4029 1746 2136 1861 +4030 1746 2116 1872 +4031 1872 2136 1746 +4032 1874 2113 1746 +4033 2113 2116 1746 +4034 1802 2060 1747 +4035 1747 2114 1802 +4036 1862 1875 1747 +4037 1747 2137 1862 +4038 1875 2114 1747 +4039 2060 2137 1747 +4040 1748 2085 1829 +4041 1829 2142 1748 +4042 1748 2142 1830 +4043 1830 2155 1748 +4044 1884 2085 1748 +4045 1748 2155 1884 +4046 1749 2084 1828 +4047 1828 2143 1749 +4048 1749 2143 1831 +4049 1831 2154 1749 +4050 1885 2084 1749 +4051 1749 2154 1885 +4052 1750 2070 1840 +4053 1840 2132 1750 +4054 2003 2004 1750 +4055 1750 2192 2003 +4056 2004 2070 1750 +4057 2132 2192 1750 +4058 1751 2009 1811 +4059 1811 2193 1751 +4060 1751 2005 1841 +4061 1841 2009 1751 +4062 2002 2005 1751 +4063 1751 2193 2002 +4064 1752 2006 1869 +4065 1869 2135 1752 +4066 1752 2135 1906 +4067 1906 2151 1752 +4068 1932 2006 1752 +4069 1752 2151 1932 +4070 1753 1965 1858 +4071 1858 2148 1753 +4072 1931 2129 1753 +4073 1753 2148 1931 +4074 1753 1966 1965 +4075 1753 2129 1966 +4076 1890 1919 1754 +4077 1754 1981 1890 +4078 1919 1998 1754 +4079 1754 2007 1981 +4080 1998 2007 1754 +4081 1866 1893 1755 +4082 1755 2008 1866 +4083 1893 1920 1755 +4084 1920 1999 1755 +4085 1999 2008 1755 +4086 1756 1968 1863 +4087 1863 2144 1756 +4088 1756 2144 1867 +4089 1867 2186 1756 +4090 1904 1968 1756 +4091 1756 2186 1904 +4092 1864 1967 1757 +4093 1757 2145 1864 +4094 1868 2145 1757 +4095 1757 2187 1868 +4096 1757 1967 1905 +4097 1905 2187 1757 +4098 1842 1941 1758 +4099 1758 2040 1842 +4100 1758 1987 1847 +4101 1847 2040 1758 +4102 1941 1987 1758 +4103 1843 1939 1759 +4104 1759 2039 1843 +4105 1759 1988 1848 +4106 1848 2039 1759 +4107 1939 1988 1759 +4108 1760 1942 1835 +4109 1835 2041 1760 +4110 1846 1986 1760 +4111 1760 2041 1846 +4112 1760 1986 1942 +4113 1761 1940 1834 +4114 1834 2038 1761 +4115 1849 1989 1761 +4116 1761 2038 1849 +4117 1761 1989 1940 +4118 1858 2014 1762 +4119 1762 2165 1858 +4120 1762 1949 1948 +4121 1948 2165 1762 +4122 1762 2027 1949 +4123 2014 2027 1762 +4124 1869 2063 1763 +4125 1763 2189 1869 +4126 1763 2046 1950 +4127 1950 2189 1763 +4128 1763 2115 2046 +4129 2063 2115 1763 +4130 1764 2093 1980 +4131 1980 2170 1764 +4132 1764 2052 1994 +4133 1994 2093 1764 +4134 1764 2090 2052 +4135 1764 2170 2090 +4136 1931 2055 1765 +4137 1765 2129 1931 +4138 1996 2051 1765 +4139 1765 2094 1996 +4140 2051 2129 1765 +4141 2055 2094 1765 +4142 1766 1979 1873 +4143 1873 2053 1766 +4144 1766 2072 1979 +4145 1766 2053 1995 +4146 1995 2072 1766 +4147 1906 2001 1767 +4148 1767 2151 1906 +4149 1997 2054 1767 +4150 1767 2073 1997 +4151 2001 2073 1767 +4152 2054 2151 1767 +4153 1768 2088 1852 +4154 1852 2138 1768 +4155 1768 2138 1913 +4156 1937 2088 1768 +4157 1769 2087 1853 +4158 1853 2139 1769 +4159 1769 2139 1915 +4160 1938 2087 1769 +4161 1855 2086 1770 +4162 1770 2141 1855 +4163 1770 1958 1916 +4164 1916 2141 1770 +4165 1770 2086 1958 +4166 1854 2089 1771 +4167 1771 2140 1854 +4168 1771 1957 1914 +4169 1914 2140 1771 +4170 1771 2089 1957 +4171 1772 2040 1847 +4172 1847 2178 1772 +4173 1962 2146 1772 +4174 1772 2178 1962 +4175 1772 2152 2040 +4176 2146 2152 1772 +4177 1846 2041 1773 +4178 1773 2179 1846 +4179 1773 2065 1961 +4180 1961 2179 1773 +4181 1773 2041 2032 +4182 2032 2065 1773 +4183 1774 2039 1848 +4184 1848 2180 1774 +4185 1960 2147 1774 +4186 1774 2180 1960 +4187 1774 2153 2039 +4188 2147 2153 1774 +4189 1849 2038 1775 +4190 1775 2181 1849 +4191 1775 2064 1959 +4192 1959 2181 1775 +4193 1775 2038 2033 +4194 2033 2064 1775 +4195 1776 2077 1901 +4196 1900 2076 1777 +4197 1778 1886 1835 +4198 1835 2190 1778 +4199 1898 2163 1778 +4200 1778 2190 1898 +4201 1778 2163 1972 +4202 1779 1887 1834 +4203 1834 2191 1779 +4204 1899 2164 1779 +4205 1779 2191 1899 +4206 1779 2164 1971 +4207 1832 2146 1780 +4208 1985 2176 1780 +4209 1780 2176 2029 +4210 1833 2147 1781 +4211 1984 2177 1781 +4212 1781 2177 2028 +4213 1865 2015 1782 +4214 1782 2170 1865 +4215 2015 2188 1782 +4216 2090 2170 1782 +4217 1782 2188 2090 +4218 1783 2109 1873 +4219 1873 2171 1783 +4220 2018 2156 1783 +4221 1783 2171 2018 +4222 2071 2109 1783 +4223 1783 2156 2071 +4224 1784 2023 1954 +4225 2010 2023 1784 +4226 1953 2024 1785 +4227 1785 2024 2011 +4228 1786 2025 1955 +4229 2012 2025 1786 +4230 1956 2026 1787 +4231 1787 2026 2013 +4232 1896 2167 1788 +4233 1907 2104 1788 +4234 1788 2167 1907 +4235 1789 2168 1895 +4236 1789 2078 1909 +4237 1909 2168 1789 +4238 1790 2166 1897 +4239 1790 2079 1908 +4240 1908 2166 1790 +4241 1894 2169 1791 +4242 1910 2103 1791 +4243 1791 2169 1910 +4244 2035 2057 1792 +4245 2057 2083 1792 +4246 2034 2056 1793 +4247 2056 2082 1793 +4248 1912 2080 1794 +4249 1794 2099 1912 +4250 1969 2099 1794 +4251 1911 2081 1795 +4252 1795 2100 1911 +4253 1970 2100 1795 +4254 1971 1973 1796 +4255 1796 2045 1971 +4256 1973 2185 1796 +4257 1796 2110 2045 +4258 1796 2185 2110 +4259 1972 1974 1797 +4260 1797 2044 1972 +4261 1974 2184 1797 +4262 1797 2111 2044 +4263 1797 2184 2111 +4264 1798 2173 1987 +4265 2068 2173 1798 +4266 1986 2174 1799 +4267 1799 2174 2069 +4268 1800 2172 1988 +4269 2067 2172 1800 +4270 1989 2175 1801 +4271 1801 2175 2066 +4272 1802 2114 2029 +4273 1803 2113 2028 +4274 1803 2116 2113 +4275 1804 2131 1929 +4276 2016 2131 1804 +4277 1804 2134 2016 +4278 1805 2130 1930 +4279 2017 2130 1805 +4280 1805 2133 2017 +4281 1806 2030 1982 +4282 1982 2108 1806 +4283 1807 2031 1983 +4284 1983 2107 1807 +4285 1808 2092 1946 +4286 1809 2091 1945 +4287 1810 2132 1976 +4288 1810 2192 2132 +4289 1814 2061 1889 +4290 1902 2050 1814 +4291 1815 2062 1888 +4292 1903 2049 1815 +4293 1816 2101 2032 +4294 1817 2102 2033 +4295 1930 2130 1818 +4296 1818 2099 1969 +4297 1818 2130 2099 +4298 1929 2131 1819 +4299 1819 2100 1970 +4300 1819 2131 2100 +4301 1820 2096 1917 +4302 1964 2157 1820 +4303 1820 2117 2096 +4304 1820 2157 2117 +4305 1918 2095 1821 +4306 1821 2158 1963 +4307 2095 2118 1821 +4308 2118 2158 1821 +4309 1984 2128 1822 +4310 1822 2177 1984 +4311 2083 2177 1822 +4312 1985 2127 1823 +4313 1823 2176 1985 +4314 2082 2176 1823 +4315 2118 2182 1824 +4316 1825 2182 2119 +4317 1950 2183 1826 +4318 1827 2183 1947 +4319 1891 2074 1828 +4320 2074 2143 1828 +4321 1892 2075 1829 +4322 2075 2142 1829 +4323 1943 2155 1830 +4324 1830 2058 1973 +4325 1944 2154 1831 +4326 1831 2059 1974 +4327 2108 2152 1832 +4328 1832 2152 2146 +4329 2107 2153 1833 +4330 1833 2153 2147 +4331 1945 2091 1836 +4332 1836 2105 2037 +4333 1946 2092 1837 +4334 1837 2106 2036 +4335 1840 2070 1872 +4336 1866 2009 1841 +4337 1841 2137 2060 +4338 1846 2179 2011 +4339 2010 2178 1847 +4340 2012 2180 1848 +4341 1849 2181 2013 +4342 1850 2150 1920 +4343 1851 2149 1919 +4344 1856 2047 1904 +4345 1905 2048 1857 +4346 1858 2165 2148 +4347 1861 2136 2125 +4348 1862 2137 2126 +4349 1865 2170 2112 +4350 1869 2189 2135 +4351 1979 2171 1873 +4352 1944 2163 1898 +4353 1943 2164 1899 +4354 2031 2185 1973 +4355 2030 2184 1974 +2 15 2 272 +4356 2294 204 17 +4357 291 2294 17 +4358 207 2211 18 +4359 2211 325 18 +4360 2292 320 21 +4361 324 2292 21 +4362 2197 321 22 +4363 354 2197 22 +4364 204 2294 205 +4365 2293 206 205 +4366 2294 2293 205 +4367 2211 207 206 +4368 2211 206 2213 +4369 206 2293 2213 +4370 292 2203 291 +4371 2203 2294 291 +4372 2202 292 293 +4373 292 2202 2203 +4374 2291 293 294 +4375 293 2216 2202 +4376 293 2291 2216 +4377 2289 294 295 +4378 294 2289 2291 +4379 2284 295 296 +4380 295 2284 2289 +4381 2286 296 297 +4382 296 2286 2284 +4383 2280 297 298 +4384 297 2280 2286 +4385 2277 298 299 +4386 298 2277 2280 +4387 2272 299 300 +4388 299 2272 2277 +4389 2274 300 301 +4390 300 2274 2272 +4391 2268 301 302 +4392 301 2268 2274 +4393 2263 302 303 +4394 302 2263 2268 +4395 2265 303 304 +4396 303 2265 2263 +4397 2256 304 305 +4398 304 2256 2265 +4399 2259 305 306 +4400 305 2259 2256 +4401 2252 306 307 +4402 306 2252 2259 +4403 2247 307 308 +4404 307 2247 2252 +4405 2249 308 309 +4406 308 2249 2247 +4407 2241 309 310 +4408 309 2241 2249 +4409 2243 310 311 +4410 310 2243 2241 +4411 2235 311 312 +4412 311 2235 2243 +4413 2237 312 313 +4414 312 2237 2235 +4415 2229 313 314 +4416 313 2229 2237 +4417 2231 314 315 +4418 314 2231 2229 +4419 2223 315 316 +4420 315 2223 2231 +4421 2225 316 317 +4422 316 2225 2223 +4423 2218 317 318 +4424 317 2218 2225 +4425 2258 318 319 +4426 318 2258 2218 +4427 2206 319 320 +4428 2207 319 2206 +4429 319 2207 2258 +4430 2292 2206 320 +4431 321 2198 322 +4432 321 2197 2198 +4433 2209 323 322 +4434 2198 2209 322 +4435 323 2292 324 +4436 2209 2210 323 +4437 323 2210 2292 +4438 2212 326 325 +4439 325 2211 2212 +4440 2196 327 326 +4441 326 2195 2196 +4442 2195 326 2212 +4443 2290 328 327 +4444 327 2196 2290 +4445 2288 329 328 +4446 328 2290 2288 +4447 2283 330 329 +4448 329 2288 2283 +4449 2285 331 330 +4450 330 2283 2285 +4451 2279 332 331 +4452 331 2285 2279 +4453 2276 333 332 +4454 332 2279 2276 +4455 2271 334 333 +4456 333 2276 2271 +4457 2273 335 334 +4458 334 2271 2273 +4459 2267 336 335 +4460 335 2273 2267 +4461 2262 337 336 +4462 336 2267 2262 +4463 2264 338 337 +4464 337 2262 2264 +4465 2255 339 338 +4466 338 2264 2255 +4467 2257 340 339 +4468 339 2255 2257 +4469 2251 341 340 +4470 340 2257 2251 +4471 2246 342 341 +4472 341 2251 2246 +4473 2248 343 342 +4474 342 2246 2248 +4475 2240 344 343 +4476 343 2248 2240 +4477 2242 345 344 +4478 344 2240 2242 +4479 2234 346 345 +4480 345 2242 2234 +4481 2236 347 346 +4482 346 2234 2236 +4483 2228 348 347 +4484 347 2236 2228 +4485 2230 349 348 +4486 348 2228 2230 +4487 2222 350 349 +4488 349 2230 2222 +4489 2224 351 350 +4490 350 2222 2224 +4491 2219 352 351 +4492 351 2224 2219 +4493 2199 353 352 +4494 352 2215 2199 +4495 352 2219 2215 +4496 353 2197 354 +4497 353 2199 2197 +4498 2194 2196 2195 +4499 2194 2195 2205 +4500 2196 2194 2290 +4501 2205 2216 2194 +4502 2291 2194 2216 +4503 2287 2290 2194 +4504 2194 2291 2287 +4505 2205 2195 2213 +4506 2195 2212 2213 +4507 2198 2197 2200 +4508 2199 2200 2197 +4509 2200 2209 2198 +4510 2199 2201 2200 +4511 2201 2199 2215 +4512 2201 2209 2200 +4513 2208 2201 2207 +4514 2214 2207 2201 +4515 2201 2208 2209 +4516 2201 2215 2214 +4517 2202 2204 2203 +4518 2202 2205 2204 +4519 2205 2202 2216 +4520 2294 2203 2204 +4521 2205 2213 2204 +4522 2293 2204 2213 +4523 2204 2293 2294 +4524 2206 2208 2207 +4525 2210 2208 2206 +4526 2210 2206 2292 +4527 2214 2258 2207 +4528 2209 2208 2210 +4529 2212 2211 2213 +4530 2219 2214 2215 +4531 2217 2218 2214 +4532 2214 2219 2217 +4533 2258 2214 2218 +4534 2218 2217 2225 +4535 2224 2217 2219 +4536 2217 2224 2220 +4537 2220 2225 2217 +4538 2220 2222 2221 +4539 2221 2223 2220 +4540 2222 2220 2224 +4541 2225 2220 2223 +4542 2230 2221 2222 +4543 2223 2221 2231 +4544 2221 2230 2226 +4545 2226 2231 2221 +4546 2226 2228 2227 +4547 2227 2229 2226 +4548 2228 2226 2230 +4549 2231 2226 2229 +4550 2236 2227 2228 +4551 2229 2227 2237 +4552 2227 2236 2232 +4553 2232 2237 2227 +4554 2232 2234 2233 +4555 2233 2235 2232 +4556 2234 2232 2236 +4557 2237 2232 2235 +4558 2242 2233 2234 +4559 2235 2233 2243 +4560 2233 2242 2238 +4561 2238 2243 2233 +4562 2238 2240 2239 +4563 2239 2241 2238 +4564 2240 2238 2242 +4565 2243 2238 2241 +4566 2248 2239 2240 +4567 2241 2239 2249 +4568 2239 2248 2244 +4569 2244 2249 2239 +4570 2244 2246 2245 +4571 2245 2247 2244 +4572 2246 2244 2248 +4573 2249 2244 2247 +4574 2251 2245 2246 +4575 2247 2245 2252 +4576 2245 2251 2250 +4577 2250 2252 2245 +4578 2257 2250 2251 +4579 2252 2250 2259 +4580 2250 2257 2253 +4581 2253 2259 2250 +4582 2253 2255 2254 +4583 2254 2256 2253 +4584 2255 2253 2257 +4585 2259 2253 2256 +4586 2264 2254 2255 +4587 2256 2254 2265 +4588 2254 2264 2260 +4589 2260 2265 2254 +4590 2260 2262 2261 +4591 2261 2263 2260 +4592 2262 2260 2264 +4593 2265 2260 2263 +4594 2267 2261 2262 +4595 2263 2261 2268 +4596 2261 2267 2266 +4597 2266 2268 2261 +4598 2273 2266 2267 +4599 2268 2266 2274 +4600 2266 2273 2269 +4601 2269 2274 2266 +4602 2269 2271 2270 +4603 2270 2272 2269 +4604 2271 2269 2273 +4605 2274 2269 2272 +4606 2276 2270 2271 +4607 2272 2270 2277 +4608 2270 2276 2275 +4609 2275 2277 2270 +4610 2279 2275 2276 +4611 2277 2275 2280 +4612 2275 2279 2278 +4613 2278 2280 2275 +4614 2285 2278 2279 +4615 2280 2278 2286 +4616 2278 2285 2281 +4617 2281 2286 2278 +4618 2281 2283 2282 +4619 2282 2284 2281 +4620 2283 2281 2285 +4621 2286 2281 2284 +4622 2288 2282 2283 +4623 2284 2282 2289 +4624 2282 2288 2287 +4625 2287 2289 2282 +4626 2290 2287 2288 +4627 2289 2287 2291 +2 16 2 226 +4628 212 2343 15 +4629 15 2343 357 +4630 18 2341 211 +4631 325 2341 18 +4632 22 2344 354 +4633 356 2344 22 +4634 23 2342 355 +4635 386 2342 23 +4636 211 2372 212 +4637 2341 2372 211 +4638 212 2372 2343 +4639 326 2345 325 +4640 325 2345 2341 +4641 327 2311 326 +4642 2311 2345 326 +4643 328 2355 327 +4644 327 2355 2311 +4645 329 2328 328 +4646 2328 2355 328 +4647 330 2359 329 +4648 329 2359 2328 +4649 331 2321 330 +4650 2321 2359 330 +4651 332 2357 331 +4652 331 2357 2321 +4653 333 2326 332 +4654 2326 2357 332 +4655 334 2350 333 +4656 333 2350 2326 +4657 335 2324 334 +4658 2324 2350 334 +4659 336 2351 335 +4660 335 2351 2324 +4661 337 2313 336 +4662 2313 2351 336 +4663 338 2352 337 +4664 337 2352 2313 +4665 339 2315 338 +4666 2315 2352 338 +4667 340 2349 339 +4668 339 2349 2315 +4669 341 2318 340 +4670 2318 2349 340 +4671 342 2367 341 +4672 341 2367 2318 +4673 343 2332 342 +4674 2332 2367 342 +4675 344 2361 343 +4676 343 2361 2332 +4677 345 2327 344 +4678 2327 2361 344 +4679 346 2368 345 +4680 345 2368 2327 +4681 347 2312 346 +4682 2312 2368 346 +4683 348 2370 347 +4684 347 2370 2312 +4685 349 2337 348 +4686 2337 2370 348 +4687 350 2334 349 +4688 349 2334 2310 +4689 2310 2337 349 +4690 351 2362 350 +4691 350 2362 2334 +4692 352 2323 351 +4693 2323 2362 351 +4694 353 2374 352 +4695 352 2374 2323 +4696 354 2340 353 +4697 2340 2374 353 +4698 354 2344 2340 +4699 355 2371 356 +4700 2342 2371 355 +4701 356 2371 2344 +4702 357 2346 358 +4703 2343 2346 357 +4704 358 2336 359 +4705 358 2346 2336 +4706 359 2356 360 +4707 2336 2356 359 +4708 360 2319 361 +4709 360 2356 2319 +4710 361 2360 362 +4711 2319 2360 361 +4712 362 2329 363 +4713 362 2360 2329 +4714 363 2358 364 +4715 2329 2358 363 +4716 364 2314 365 +4717 364 2358 2314 +4718 365 2347 366 +4719 2314 2347 365 +4720 366 2316 367 +4721 366 2347 2316 +4722 367 2353 368 +4723 2316 2353 367 +4724 368 2330 369 +4725 368 2353 2330 +4726 369 2354 370 +4727 2330 2354 369 +4728 370 2325 371 +4729 370 2354 2325 +4730 371 2348 372 +4731 2325 2348 371 +4732 372 2331 373 +4733 372 2348 2331 +4734 373 2366 374 +4735 2331 2366 373 +4736 374 2317 375 +4737 374 2366 2317 +4738 375 2363 376 +4739 2317 2363 375 +4740 376 2320 377 +4741 376 2363 2320 +4742 377 2365 378 +4743 2320 2365 377 +4744 378 2333 379 +4745 378 2365 2333 +4746 379 2369 380 +4747 2333 2369 379 +4748 380 2338 381 +4749 380 2369 2338 +4750 381 2335 382 +4751 2310 2335 381 +4752 381 2338 2310 +4753 382 2364 383 +4754 2335 2364 382 +4755 383 2322 384 +4756 383 2364 2322 +4757 384 2373 385 +4758 2322 2373 384 +4759 385 2339 386 +4760 385 2373 2339 +4761 2339 2342 386 +4762 2295 2345 2311 +4763 2311 2346 2295 +4764 2341 2345 2295 +4765 2295 2372 2341 +4766 2295 2346 2343 +4767 2343 2372 2295 +4768 2339 2340 2296 +4769 2296 2342 2339 +4770 2340 2344 2296 +4771 2296 2371 2342 +4772 2344 2371 2296 +4773 2297 2325 2315 +4774 2315 2349 2297 +4775 2318 2331 2297 +4776 2297 2349 2318 +4777 2297 2348 2325 +4778 2331 2348 2297 +4779 2314 2326 2298 +4780 2298 2347 2314 +4781 2298 2324 2316 +4782 2316 2347 2298 +4783 2298 2350 2324 +4784 2326 2350 2298 +4785 2313 2330 2299 +4786 2299 2351 2313 +4787 2316 2324 2299 +4788 2299 2353 2316 +4789 2324 2351 2299 +4790 2330 2353 2299 +4791 2300 2330 2313 +4792 2313 2352 2300 +4793 2315 2325 2300 +4794 2300 2352 2315 +4795 2325 2354 2300 +4796 2300 2354 2330 +4797 2301 2336 2311 +4798 2311 2355 2301 +4799 2301 2328 2319 +4800 2319 2356 2301 +4801 2301 2355 2328 +4802 2301 2356 2336 +4803 2302 2326 2314 +4804 2314 2358 2302 +4805 2302 2329 2321 +4806 2321 2357 2302 +4807 2302 2357 2326 +4808 2302 2358 2329 +4809 2319 2328 2303 +4810 2303 2360 2319 +4811 2321 2329 2303 +4812 2303 2359 2321 +4813 2328 2359 2303 +4814 2329 2360 2303 +4815 2317 2332 2304 +4816 2304 2363 2317 +4817 2304 2327 2320 +4818 2320 2363 2304 +4819 2304 2361 2327 +4820 2332 2361 2304 +4821 2305 2333 2312 +4822 2312 2370 2305 +4823 2305 2369 2333 +4824 2337 2338 2305 +4825 2305 2370 2337 +4826 2338 2369 2305 +4827 2306 2323 2322 +4828 2322 2364 2306 +4829 2306 2362 2323 +4830 2306 2335 2334 +4831 2334 2362 2306 +4832 2306 2364 2335 +4833 2307 2332 2317 +4834 2317 2366 2307 +4835 2307 2331 2318 +4836 2318 2367 2307 +4837 2307 2366 2331 +4838 2307 2367 2332 +4839 2312 2333 2308 +4840 2308 2368 2312 +4841 2320 2327 2308 +4842 2308 2365 2320 +4843 2327 2368 2308 +4844 2333 2365 2308 +4845 2322 2323 2309 +4846 2309 2373 2322 +4847 2323 2374 2309 +4848 2309 2340 2339 +4849 2339 2373 2309 +4850 2309 2374 2340 +4851 2334 2335 2310 +4852 2310 2338 2337 +4853 2336 2346 2311 +2 17 2 2542 +4854 8 176 2508 +4855 8 2508 418 +4856 2618 146 15 +4857 357 2618 15 +4858 23 2507 386 +4859 23 417 2507 +4860 2617 387 24 +4861 447 2617 24 +4862 146 2575 147 +4863 146 2618 2575 +4864 147 2500 148 +4865 2381 2500 147 +4866 147 2575 2381 +4867 148 2474 149 +4868 148 2500 2474 +4869 149 2475 150 +4870 149 2474 2475 +4871 2706 151 150 +4872 150 2475 2706 +4873 3035 152 151 +4874 151 2706 3035 +4875 152 2923 153 +4876 3035 2923 152 +4877 153 2588 154 +4878 153 2923 2588 +4879 154 2587 155 +4880 154 2588 2587 +4881 155 3218 156 +4882 155 2587 2707 +4883 2707 3218 155 +4884 2990 157 156 +4885 3218 2990 156 +4886 158 157 2711 +4887 157 2990 2711 +4888 3203 159 158 +4889 2711 3203 158 +4890 2538 160 159 +4891 3203 2538 159 +4892 3314 161 160 +4893 2539 160 2538 +4894 160 2539 3314 +4895 2831 162 161 +4896 3314 2831 161 +4897 162 2828 163 +4898 2831 2828 162 +4899 163 3159 164 +4900 3159 163 2828 +4901 165 164 2991 +4902 164 3159 2991 +4903 166 165 2584 +4904 2584 165 2991 +4905 166 2973 167 +4906 2973 166 2584 +4907 2719 168 167 +4908 2973 2719 167 +4909 2604 169 168 +4910 2604 168 2719 +4911 2720 170 169 +4912 2720 169 2604 +4913 170 2725 171 +4914 2725 170 2720 +4915 2433 172 171 +4916 2433 171 3121 +4917 2725 3121 171 +4918 172 2400 173 +4919 2433 2400 172 +4920 2470 174 173 +4921 2470 173 2400 +4922 2499 175 174 +4923 2499 174 2470 +4924 2579 176 175 +4925 2499 2579 175 +4926 2508 176 2579 +4927 358 2380 357 +4928 2380 2618 357 +4929 359 2485 358 +4930 2380 358 2382 +4931 2485 2382 358 +4932 2415 359 360 +4933 2485 359 2415 +4934 2414 360 361 +4935 2414 2415 360 +4936 3071 361 362 +4937 2414 361 3001 +4938 3001 361 3071 +4939 363 2688 362 +4940 2688 3071 362 +4941 2689 363 364 +4942 2688 363 2689 +4943 2568 364 365 +4944 2568 2689 364 +4945 2513 365 366 +4946 2513 2568 365 +4947 2512 366 367 +4948 2512 2513 366 +4949 3301 367 368 +4950 367 3165 2512 +4951 3165 367 3301 +4952 369 2698 368 +4953 2698 3301 368 +4954 370 2698 369 +4955 371 2695 370 +4956 2695 2698 370 +4957 3077 371 372 +4958 3077 2695 371 +4959 3208 372 373 +4960 372 3209 3077 +4961 3208 3209 372 +4962 2813 373 374 +4963 2813 3208 373 +4964 2812 374 375 +4965 2812 2813 374 +4966 3206 375 376 +4967 2812 375 3235 +4968 3235 375 3206 +4969 377 2464 376 +4970 3206 376 2464 +4971 378 2463 377 +4972 2463 2464 377 +4973 379 2574 378 +4974 2574 2463 378 +4975 2787 379 380 +4976 2787 2574 379 +4977 2402 380 381 +4978 380 2402 2787 +4979 2817 381 382 +4980 381 2816 2402 +4981 381 2817 2816 +4982 3025 382 383 +4983 382 3025 2817 +4984 384 2488 383 +4985 2488 3025 383 +4986 2487 384 385 +4987 384 2487 2488 +4988 2507 385 386 +4989 2462 2487 385 +4990 385 2507 2462 +4991 387 2572 388 +4992 387 2617 2572 +4993 388 2502 389 +4994 2377 2502 388 +4995 388 2572 2377 +4996 389 2481 390 +4997 389 2502 2481 +4998 390 2482 391 +4999 390 2481 2482 +5000 392 391 2913 +5001 391 2482 2914 +5002 391 2914 2913 +5003 2728 393 392 +5004 392 2913 2728 +5005 393 2729 394 +5006 2728 2729 393 +5007 394 2586 395 +5008 394 2924 2586 +5009 2924 394 2729 +5010 395 2585 396 +5011 395 2586 2585 +5012 2660 397 396 +5013 396 2585 2715 +5014 2715 2660 396 +5015 397 2659 398 +5016 397 2660 2659 +5017 2659 399 398 +5018 2871 400 399 +5019 2659 2685 399 +5020 2685 2871 399 +5021 2872 401 400 +5022 2871 2872 400 +5023 3280 402 401 +5024 3280 401 2872 +5025 402 2798 403 +5026 2798 402 3279 +5027 3279 402 3280 +5028 403 2449 404 +5029 403 2798 2449 +5030 404 2447 405 +5031 2447 404 2448 +5032 2448 404 2449 +5033 406 405 2975 +5034 405 2447 2975 +5035 406 2561 407 +5036 2561 406 2975 +5037 407 2559 408 +5038 2561 2559 407 +5039 2712 409 408 +5040 2559 2712 408 +5041 2608 410 409 +5042 2608 409 2712 +5043 2714 411 410 +5044 2714 410 2608 +5045 411 2726 412 +5046 2726 411 2714 +5047 2432 413 412 +5048 2432 412 3120 +5049 2726 3120 412 +5050 413 2396 414 +5051 2432 2396 413 +5052 2479 415 414 +5053 2479 414 2396 +5054 2503 416 415 +5055 2503 415 2479 +5056 2577 417 416 +5057 2503 2577 416 +5058 2507 417 2577 +5059 2508 419 418 +5060 2494 420 419 +5061 2455 2494 419 +5062 419 2508 2455 +5063 420 2495 421 +5064 420 2494 2495 +5065 3031 422 421 +5066 2495 3031 421 +5067 2808 423 422 +5068 422 3031 2808 +5069 2406 424 423 +5070 423 2807 2406 +5071 423 2808 2807 +5072 2784 425 424 +5073 424 2406 2784 +5074 425 2563 426 +5075 2784 2563 425 +5076 426 3101 427 +5077 2563 3101 426 +5078 427 3048 428 +5079 3101 3048 427 +5080 428 3049 429 +5081 3048 3049 428 +5082 2532 430 429 +5083 3049 2532 429 +5084 430 2531 431 +5085 430 2532 2531 +5086 3018 432 431 +5087 2531 3018 431 +5088 432 3033 433 +5089 3018 3033 432 +5090 433 3096 434 +5091 433 3033 3096 +5092 434 3097 435 +5093 3097 434 3096 +5094 435 3309 436 +5095 3097 3309 435 +5096 2918 437 436 +5097 3309 2918 436 +5098 2423 438 437 +5099 437 2917 2423 +5100 2917 437 2918 +5101 2424 439 438 +5102 2423 2424 438 +5103 2571 440 439 +5104 2424 2571 439 +5105 2680 441 440 +5106 2571 2680 440 +5107 441 2679 442 +5108 2679 441 2680 +5109 3069 443 442 +5110 2679 3069 442 +5111 2411 444 443 +5112 2411 443 2998 +5113 2998 443 3069 +5114 2412 445 444 +5115 2411 2412 444 +5116 445 2492 446 +5117 2492 445 2412 +5118 446 2376 447 +5119 2376 446 2378 +5120 2492 2378 446 +5121 2376 2617 447 +5122 2375 2377 2376 +5123 2375 2376 2378 +5124 2501 2377 2375 +5125 2378 2457 2375 +5126 2375 2457 2522 +5127 2375 2522 2501 +5128 2572 2376 2377 +5129 2376 2572 2617 +5130 2502 2377 2501 +5131 2378 2492 2457 +5132 2379 2381 2380 +5133 2379 2380 2382 +5134 2505 2381 2379 +5135 2382 2465 2379 +5136 2379 2465 2524 +5137 2379 2524 2505 +5138 2575 2380 2381 +5139 2380 2575 2618 +5140 2500 2381 2505 +5141 2382 2485 2465 +5142 2383 2385 2384 +5143 2383 2384 2386 +5144 2758 2385 2383 +5145 3447 2383 2386 +5146 2758 2383 2491 +5147 2383 3447 2491 +5148 2384 2385 2948 +5149 2386 2384 3548 +5150 2384 2948 3548 +5151 2758 3009 2385 +5152 2948 2385 3007 +5153 3009 3007 2385 +5154 3536 3447 2386 +5155 2386 3547 3536 +5156 2386 3548 3547 +5157 2387 2389 2388 +5158 2388 2421 2387 +5159 2389 2387 3126 +5160 2420 2387 2421 +5161 2387 2420 3127 +5162 2387 3127 3126 +5163 2388 2389 2390 +5164 2444 2388 2390 +5165 2421 2388 2444 +5166 2790 2390 2389 +5167 2458 2459 2389 +5168 2458 2389 2493 +5169 2459 2790 2389 +5170 2389 3126 2493 +5171 2444 2390 2952 +5172 2790 2950 2390 +5173 2952 2390 2950 +5174 2391 2393 2392 +5175 2391 2392 3082 +5176 2393 2391 3021 +5177 2525 2391 2518 +5178 2518 2391 3082 +5179 2525 3021 2391 +5180 2392 2393 2416 +5181 2392 2416 3016 +5182 3082 2392 3016 +5183 2416 2393 2940 +5184 3527 2940 2393 +5185 3503 2393 3021 +5186 2393 3503 3116 +5187 3116 3527 2393 +5188 2394 2396 2395 +5189 2394 2395 2529 +5190 2396 2394 2479 +5191 2503 2479 2394 +5192 2503 2394 2504 +5193 2504 2394 2529 +5194 2395 2396 2397 +5195 2395 2397 2770 +5196 2443 2529 2395 +5197 2443 2395 2770 +5198 2432 2397 2396 +5199 2397 2432 3120 +5200 2769 2770 2397 +5201 3120 2769 2397 +5202 2398 2400 2399 +5203 2398 2399 2530 +5204 2400 2398 2470 +5205 2499 2470 2398 +5206 2499 2398 2506 +5207 2506 2398 2530 +5208 2399 2400 2401 +5209 2399 2401 2773 +5210 2445 2530 2399 +5211 2445 2399 2773 +5212 2433 2401 2400 +5213 2401 2433 3121 +5214 2772 2773 2401 +5215 3121 2772 2401 +5216 2402 2404 2403 +5217 2403 2787 2402 +5218 2402 2816 2404 +5219 2403 2404 2405 +5220 2405 3118 2403 +5221 2787 2403 2901 +5222 2900 2901 2403 +5223 3118 2900 2403 +5224 2983 2405 2404 +5225 2404 2816 3081 +5226 2404 3081 2983 +5227 2405 2983 2440 +5228 2405 2440 3118 +5229 2406 2408 2407 +5230 2407 2784 2406 +5231 2406 2807 2408 +5232 2407 2408 2409 +5233 2409 3119 2407 +5234 2784 2407 2963 +5235 2956 2963 2407 +5236 3119 2956 2407 +5237 2790 2409 2408 +5238 2408 3086 2790 +5239 2408 2807 3086 +5240 2409 2790 2459 +5241 2409 2459 3119 +5242 2410 2412 2411 +5243 2410 2411 2998 +5244 2457 2412 2410 +5245 2457 2410 2960 +5246 2960 2410 2999 +5247 2410 2998 2997 +5248 2410 2997 2999 +5249 2457 2492 2412 +5250 2413 2415 2414 +5251 2413 2414 3001 +5252 2465 2415 2413 +5253 2465 2413 2961 +5254 2961 2413 3002 +5255 2413 3001 3000 +5256 2413 3000 3002 +5257 2465 2485 2415 +5258 2416 2601 3016 +5259 3161 2601 2416 +5260 2940 3161 2416 +5261 2417 2419 2418 +5262 2417 2418 2767 +5263 2417 3130 2419 +5264 2417 2767 2765 +5265 2417 2765 3131 +5266 3130 2417 3131 +5267 2418 2419 2443 +5268 2418 2443 2770 +5269 2767 2418 2770 +5270 2419 2442 2441 +5271 2419 2441 2443 +5272 2442 2419 3130 +5273 2420 2421 2422 +5274 2420 2422 2763 +5275 2420 2763 2762 +5276 2420 2762 3127 +5277 2422 2421 2445 +5278 2421 2444 2445 +5279 2422 2445 2773 +5280 2763 2422 2773 +5281 2705 2424 2423 +5282 2705 2423 2917 +5283 2424 2632 2571 +5284 2424 2705 2632 +5285 2425 2427 2426 +5286 2425 2426 3168 +5287 2752 2427 2425 +5288 2752 2425 2801 +5289 2425 3167 2801 +5290 3168 3167 2425 +5291 2426 2427 2428 +5292 2426 2428 2614 +5293 2426 2614 2796 +5294 2805 2426 2796 +5295 2426 2805 3194 +5296 3168 2426 3194 +5297 2715 2428 2427 +5298 2751 2715 2427 +5299 2751 2427 2752 +5300 2585 2615 2428 +5301 2715 2585 2428 +5302 2428 2615 2614 +5303 2429 2431 2430 +5304 2429 2430 3543 +5305 2569 2431 2429 +5306 2429 2570 2569 +5307 2429 3543 2570 +5308 2430 2431 2434 +5309 2434 2437 2430 +5310 2437 3050 2430 +5311 3017 2430 3050 +5312 3543 2430 3017 +5313 2553 2434 2431 +5314 2819 2553 2431 +5315 2569 2814 2431 +5316 2814 2819 2431 +5317 2434 2436 2435 +5318 2434 2435 2437 +5319 2554 2436 2434 +5320 2553 2554 2434 +5321 2674 2435 2436 +5322 2915 2437 2435 +5323 2915 2435 2674 +5324 2436 2554 2664 +5325 2436 2664 3219 +5326 2672 2674 2436 +5327 3219 2672 2436 +5328 2915 3050 2437 +5329 2438 2440 2439 +5330 2438 2439 2446 +5331 2438 2591 2440 +5332 3156 2438 2446 +5333 2591 2438 3156 +5334 2440 2983 2439 +5335 2439 3129 2446 +5336 2983 3073 2439 +5337 2439 3073 3130 +5338 2439 3130 3129 +5339 2440 2591 3118 +5340 2441 2442 2953 +5341 2441 2529 2443 +5342 2441 2523 2529 +5343 2441 3023 2523 +5344 2441 2953 2947 +5345 3023 2441 2947 +5346 2442 3073 2953 +5347 3073 2442 3130 +5348 2444 2530 2445 +5349 2444 2521 2530 +5350 2444 3024 2521 +5351 3024 2444 2952 +5352 2446 3129 3317 +5353 3317 3156 2446 +5354 2448 2895 2447 +5355 2447 2895 2984 +5356 2975 2447 2984 +5357 2661 2448 2449 +5358 2661 2662 2448 +5359 2895 2448 2662 +5360 2449 2798 2661 +5361 2450 2452 2451 +5362 2450 2451 2456 +5363 2936 2452 2450 +5364 2450 2456 2862 +5365 2862 2936 2450 +5366 2475 2451 2452 +5367 2451 2505 2456 +5368 2451 2475 2474 +5369 2474 2500 2451 +5370 2451 2500 2505 +5371 2706 2475 2452 +5372 2936 2706 2452 +5373 2453 2455 2454 +5374 2453 2454 2521 +5375 2494 2455 2453 +5376 2494 2453 2495 +5377 2495 2453 2509 +5378 2509 2453 3024 +5379 3024 2453 2521 +5380 2455 2578 2454 +5381 2521 2454 2506 +5382 2578 2506 2454 +5383 2455 2508 2578 +5384 2456 2505 2524 +5385 2524 2861 2456 +5386 2456 2861 2862 +5387 2457 2960 2522 +5388 2458 3195 2459 +5389 3196 2458 2493 +5390 3195 2458 3196 +5391 2459 3195 3119 +5392 2460 2462 2461 +5393 2460 2461 2523 +5394 2487 2462 2460 +5395 2487 2460 2488 +5396 2488 2460 2510 +5397 2510 2460 3023 +5398 3023 2460 2523 +5399 2462 2576 2461 +5400 2523 2461 2504 +5401 2576 2504 2461 +5402 2462 2507 2576 +5403 2463 3327 2464 +5404 2821 2463 2574 +5405 3327 2463 2821 +5406 2464 3327 3206 +5407 2465 2961 2524 +5408 2466 2468 2467 +5409 2466 2467 2469 +5410 2935 2468 2466 +5411 2466 2469 2854 +5412 2854 2935 2466 +5413 2482 2467 2468 +5414 2467 2501 2469 +5415 2467 2482 2481 +5416 2481 2502 2467 +5417 2467 2502 2501 +5418 2914 2482 2468 +5419 2935 2914 2468 +5420 2469 2501 2522 +5421 2522 2853 2469 +5422 2469 2853 2854 +5423 2471 2473 2472 +5424 2471 2472 3122 +5425 3288 2473 2471 +5426 2471 2557 3123 +5427 3248 2557 2471 +5428 3122 3248 2471 +5429 3123 3288 2471 +5430 2525 2472 2473 +5431 2519 2472 2525 +5432 3090 2472 2519 +5433 3122 2472 3090 +5434 2525 2473 3021 +5435 2473 3289 3021 +5436 2473 3288 3289 +5437 2476 2478 2477 +5438 2797 2476 2477 +5439 2478 2476 3026 +5440 3027 2476 2797 +5441 3026 2476 3027 +5442 2477 2478 2480 +5443 2477 2480 2778 +5444 2607 2602 2477 +5445 2602 2797 2477 +5446 2607 2477 2778 +5447 2480 2478 2486 +5448 2483 2484 2478 +5449 2478 3026 2483 +5450 2478 2484 2486 +5451 2480 2486 2589 +5452 2589 2778 2480 +5453 2483 2657 2484 +5454 2483 2658 2657 +5455 2483 2824 2658 +5456 2483 3028 2824 +5457 2483 3026 3028 +5458 2800 2486 2484 +5459 2657 2800 2484 +5460 3132 2589 2486 +5461 2800 3286 2486 +5462 3286 3132 2486 +5463 2510 3025 2488 +5464 2489 2491 2490 +5465 2489 2490 2536 +5466 2489 2758 2491 +5467 2535 2489 2536 +5468 2580 2489 2535 +5469 2580 2894 2489 +5470 2758 2489 2894 +5471 3507 2490 2491 +5472 2536 2490 2806 +5473 2806 2490 3507 +5474 2491 3447 2886 +5475 2886 3507 2491 +5476 2493 3126 3094 +5477 2493 3094 3173 +5478 3173 3196 2493 +5479 2509 3031 2495 +5480 2496 2498 2497 +5481 3246 2496 2497 +5482 2588 2498 2496 +5483 2587 2588 2496 +5484 2707 2587 2496 +5485 2707 2496 2708 +5486 2708 2496 3246 +5487 2497 2498 2511 +5488 3262 2497 2511 +5489 2497 3247 3246 +5490 3253 3247 2497 +5491 2497 3262 3253 +5492 2511 2498 2683 +5493 2588 2923 2498 +5494 2498 2923 2683 +5495 2578 2499 2506 +5496 2578 2579 2499 +5497 2576 2503 2504 +5498 2576 2577 2503 +5499 2504 2529 2523 +5500 2506 2530 2521 +5501 2507 2577 2576 +5502 2508 2579 2578 +5503 2949 2509 2950 +5504 2949 3031 2509 +5505 2950 2509 2952 +5506 2509 3024 2952 +5507 2944 2510 2945 +5508 2944 3025 2510 +5509 2945 2510 2947 +5510 2510 3023 2947 +5511 2681 2682 2511 +5512 2683 2681 2511 +5513 3262 2511 2682 +5514 3163 2513 2512 +5515 3163 2512 3165 +5516 2513 2573 2568 +5517 2513 3163 2573 +5518 2514 2516 2515 +5519 2938 2514 2515 +5520 2514 2774 2516 +5521 2762 2763 2514 +5522 2514 2938 2762 +5523 2514 2763 2774 +5524 2515 2516 2520 +5525 3199 2515 2520 +5526 3199 2938 2515 +5527 2605 2520 2516 +5528 2720 2605 2516 +5529 2725 2720 2516 +5530 2725 2516 2774 +5531 2517 2519 2518 +5532 2518 3505 2517 +5533 3090 2519 2517 +5534 2517 3091 3090 +5535 3125 3091 2517 +5536 3505 3125 2517 +5537 2525 2518 2519 +5538 3082 3505 2518 +5539 2605 3197 2520 +5540 3197 3198 2520 +5541 2520 3198 3199 +5542 2960 2853 2522 +5543 2961 2861 2524 +5544 2526 2528 2527 +5545 2527 2978 2526 +5546 2528 2526 3139 +5547 2978 2888 2526 +5548 3074 2526 2888 +5549 3074 3136 2526 +5550 3136 3139 2526 +5551 3003 2527 2528 +5552 2978 2527 2846 +5553 2527 3003 2846 +5554 2691 2692 2528 +5555 2528 2929 2691 +5556 2692 3003 2528 +5557 2528 3139 2929 +5558 2650 2531 2532 +5559 2977 2531 2650 +5560 2531 2977 3019 +5561 2531 3019 3018 +5562 3049 2650 2532 +5563 2533 2535 2534 +5564 2533 2534 3171 +5565 2535 2533 2581 +5566 3303 2581 2533 +5567 2533 3171 2811 +5568 3303 2533 2811 +5569 2534 2535 2536 +5570 2536 3174 2534 +5571 3104 3171 2534 +5572 3104 2534 3174 +5573 2535 2581 2580 +5574 2536 2806 2864 +5575 2536 2864 3174 +5576 2537 2539 2538 +5577 2537 2538 2540 +5578 3084 2539 2537 +5579 2537 2540 3124 +5580 3083 3084 2537 +5581 2537 3124 3083 +5582 2540 2538 3203 +5583 3084 3567 2539 +5584 3567 3314 2539 +5585 3125 2540 2709 +5586 2709 2540 3203 +5587 2540 3125 3124 +5588 2541 2543 2542 +5589 2542 3462 2541 +5590 2543 2541 3460 +5591 3460 2541 3461 +5592 3461 2541 3462 +5593 2542 2543 2596 +5594 2542 2596 3362 +5595 3462 2542 3362 +5596 2596 2543 3312 +5597 3484 3312 2543 +5598 3454 2543 3460 +5599 3454 3484 2543 +5600 2544 2546 2545 +5601 2545 3319 2544 +5602 3470 2546 2544 +5603 2544 2641 2639 +5604 3470 2544 2639 +5605 3319 2641 2544 +5606 2644 2545 2546 +5607 2644 2645 2545 +5608 2545 2645 3157 +5609 3145 3144 2545 +5610 3319 2545 3144 +5611 3145 2545 3157 +5612 2644 2546 2890 +5613 2891 2890 2546 +5614 3470 2891 2546 +5615 2547 2549 2548 +5616 2547 2548 2721 +5617 2549 2547 2552 +5618 2547 2551 2552 +5619 2786 2551 2547 +5620 2721 2793 2547 +5621 2793 2786 2547 +5622 2722 2548 2549 +5623 2548 2926 2721 +5624 2927 2548 2722 +5625 2548 2738 2926 +5626 2738 2548 2927 +5627 2549 2552 3542 +5628 2722 2549 2723 +5629 2549 3542 2723 +5630 2550 2552 2551 +5631 2550 2551 3533 +5632 2552 2550 2791 +5633 3544 2791 2550 +5634 3055 2550 2912 +5635 2550 3533 2912 +5636 3055 3544 2550 +5637 3533 2551 2786 +5638 2791 3542 2552 +5639 2553 2663 2554 +5640 2553 2932 2663 +5641 2819 2932 2553 +5642 2554 2663 2664 +5643 2555 2557 2556 +5644 2555 2556 2558 +5645 3123 2557 2555 +5646 3571 2555 2558 +5647 3113 3225 2555 +5648 2555 3571 3113 +5649 3225 3123 2555 +5650 2880 2556 2557 +5651 2556 2887 2558 +5652 2879 2556 2880 +5653 2887 2556 2879 +5654 3248 2880 2557 +5655 2558 3106 2760 +5656 2760 3571 2558 +5657 2887 3052 2558 +5658 3106 2558 3052 +5659 2559 2561 2560 +5660 2559 2560 2562 +5661 2712 2559 2562 +5662 2560 2561 2810 +5663 2562 2560 2713 +5664 2713 2560 2746 +5665 2560 2810 2746 +5666 2975 2810 2561 +5667 2712 2562 2610 +5668 2610 2562 2713 +5669 2563 2963 2718 +5670 2718 3101 2563 +5671 2963 2563 2784 +5672 2564 2566 2565 +5673 2564 2565 2567 +5674 2747 2566 2564 +5675 2802 2564 2567 +5676 2564 2743 2747 +5677 2564 2803 2743 +5678 2803 2564 2802 +5679 2566 3157 2565 +5680 2565 2643 2567 +5681 2565 2645 2643 +5682 2565 3157 2645 +5683 2747 2678 2566 +5684 3157 2566 2678 +5685 2567 2643 2848 +5686 2802 2567 2847 +5687 2848 2847 2567 +5688 2570 2568 2573 +5689 2689 2568 2570 +5690 2569 2570 2573 +5691 2573 2989 2569 +5692 2569 2989 2814 +5693 3543 2689 2570 +5694 2630 2571 2632 +5695 2680 2571 2630 +5696 2573 2988 2989 +5697 2573 3163 2988 +5698 2901 2574 2787 +5699 2574 2901 2821 +5700 2878 2580 2581 +5701 2878 3013 2580 +5702 2894 2580 3013 +5703 2878 2581 3239 +5704 2581 3303 3239 +5705 2582 2584 2583 +5706 2582 2583 2590 +5707 2584 2582 2973 +5708 2744 2582 2590 +5709 2973 2582 2744 +5710 2991 2583 2584 +5711 2590 2583 2800 +5712 2583 3286 2800 +5713 2583 2991 3286 +5714 2615 2585 2586 +5715 2586 2924 2615 +5716 2777 2778 2589 +5717 2827 2777 2589 +5718 3132 2827 2589 +5719 3005 2744 2590 +5720 2590 2800 3005 +5721 2985 2634 2591 +5722 3118 2591 2634 +5723 3156 2985 2591 +5724 2592 2594 2593 +5725 2592 2593 2595 +5726 2818 2594 2592 +5727 2595 3160 2592 +5728 2592 2820 2818 +5729 2592 3160 2820 +5730 2593 2594 3153 +5731 2595 2593 3513 +5732 2593 3153 2836 +5733 2836 3368 2593 +5734 3513 2593 3368 +5735 2818 2968 2594 +5736 2968 3153 2594 +5737 3154 2595 3155 +5738 3154 3160 2595 +5739 3513 3155 2595 +5740 2596 3312 3315 +5741 2596 3315 3387 +5742 3362 2596 3387 +5743 2597 2599 2598 +5744 2597 2598 2600 +5745 2599 2597 3308 +5746 2600 3549 2597 +5747 3308 2597 3425 +5748 3549 3425 2597 +5749 3347 2598 2599 +5750 3316 2600 2598 +5751 2598 3347 3316 +5752 3242 2599 2946 +5753 2946 2599 3277 +5754 3347 2599 3242 +5755 2599 3308 3277 +5756 2600 3316 3324 +5757 3324 3410 2600 +5758 3549 2600 3410 +5759 2601 2603 2602 +5760 2601 2602 2607 +5761 3161 2603 2601 +5762 3015 2601 2607 +5763 3015 3016 2601 +5764 2797 2602 2603 +5765 2603 3469 2797 +5766 3161 3469 2603 +5767 2604 2606 2605 +5768 2720 2604 2605 +5769 2604 2719 2606 +5770 2606 3197 2605 +5771 2606 2719 2744 +5772 2606 2744 3004 +5773 2606 3004 3197 +5774 3030 2607 2778 +5775 3015 2607 3030 +5776 2608 2610 2609 +5777 2714 2608 2609 +5778 2608 2712 2610 +5779 2610 3103 2609 +5780 2714 2609 2724 +5781 2609 2727 2724 +5782 2609 3103 2727 +5783 2713 3104 2610 +5784 2610 3104 3103 +5785 2611 2613 2612 +5786 2611 2612 2616 +5787 2613 2611 3040 +5788 3321 2611 2616 +5789 3040 2611 3179 +5790 3179 2611 3320 +5791 3320 2611 3321 +5792 2907 2612 2613 +5793 2616 2612 3564 +5794 2612 2907 3564 +5795 2905 2906 2613 +5796 3040 2905 2613 +5797 2906 2907 2613 +5798 2615 2924 2614 +5799 2796 2614 3128 +5800 2924 2964 2614 +5801 2614 2964 3128 +5802 3499 3321 2616 +5803 3499 2616 3498 +5804 2616 3564 3498 +5805 2619 2621 2620 +5806 2619 2620 2622 +5807 2619 3477 2621 +5808 3311 2619 2622 +5809 3310 2619 3311 +5810 2619 3310 3477 +5811 2948 2620 2621 +5812 2622 2620 3201 +5813 2620 2948 3201 +5814 3548 2948 2621 +5815 3455 3456 2621 +5816 3477 3455 2621 +5817 3456 3548 2621 +5818 3200 2622 3201 +5819 2622 3200 3423 +5820 3311 2622 3423 +5821 2623 2625 2624 +5822 2623 2624 2626 +5823 3036 2625 2623 +5824 3261 2623 2626 +5825 3036 2623 3261 +5826 2625 2996 2624 +5827 3099 2626 2624 +5828 2996 2995 2624 +5829 2995 3098 2624 +5830 3099 2624 3098 +5831 2625 3034 2996 +5832 2625 3037 3034 +5833 3036 3037 2625 +5834 3099 3241 2626 +5835 3241 3261 2626 +5836 2627 2629 2628 +5837 2628 2753 2627 +5838 2627 2821 2629 +5839 2627 2753 2823 +5840 2822 2821 2627 +5841 2627 2823 2822 +5842 2628 2629 2633 +5843 2633 2642 2628 +5844 2753 2628 2642 +5845 2633 2629 2634 +5846 2629 2900 2634 +5847 2821 2901 2629 +5848 2629 2901 2900 +5849 2630 2632 2631 +5850 2630 2631 3065 +5851 3065 2680 2630 +5852 3100 2631 2632 +5853 3065 2631 3175 +5854 2631 3100 3176 +5855 2631 3176 3175 +5856 2632 2705 2704 +5857 2632 2704 3006 +5858 2632 3006 3100 +5859 2985 2633 2634 +5860 2985 2642 2633 +5861 3118 2634 2900 +5862 2635 2637 2636 +5863 2635 2636 2638 +5864 2635 3343 2637 +5865 2638 3329 2635 +5866 3340 2635 3329 +5867 3340 3343 2635 +5868 2637 3068 2636 +5869 3322 2638 2636 +5870 3067 2636 3068 +5871 2636 3067 3322 +5872 3068 2637 3563 +5873 3570 2637 3343 +5874 3448 3563 2637 +5875 2637 3570 3448 +5876 3322 3332 2638 +5877 3329 2638 3330 +5878 2638 3332 3330 +5879 2639 2641 2640 +5880 2639 2640 2750 +5881 3553 2639 2750 +5882 3553 3470 2639 +5883 3318 2640 2641 +5884 2640 2749 2748 +5885 2640 2748 2750 +5886 3318 2749 2640 +5887 3176 2641 3146 +5888 3319 3146 2641 +5889 3318 2641 3176 +5890 2753 2642 2754 +5891 2754 2642 2755 +5892 2986 2755 2642 +5893 2985 2986 2642 +5894 2643 2645 2644 +5895 2644 2982 2643 +5896 2643 2982 2848 +5897 2982 2644 2890 +5898 2646 2648 2647 +5899 2646 2647 2652 +5900 2646 3219 2648 +5901 2646 2652 2783 +5902 2783 3219 2646 +5903 2648 3052 2647 +5904 2647 3328 2652 +5905 2647 3052 2887 +5906 2887 3328 2647 +5907 2934 2648 2664 +5908 2664 2648 3219 +5909 2648 2934 3052 +5910 2649 2651 2650 +5911 2649 2650 3049 +5912 2788 2651 2649 +5913 2649 2789 2788 +5914 2789 2649 3283 +5915 3283 2649 3049 +5916 2977 2650 2651 +5917 2740 2651 2788 +5918 2740 2977 2651 +5919 2783 2652 2849 +5920 2652 3328 2849 +5921 2653 2655 2654 +5922 2653 2654 2656 +5923 2653 3482 2655 +5924 2656 2730 2653 +5925 2653 2730 3532 +5926 3532 3482 2653 +5927 2696 2654 2655 +5928 2656 2654 3555 +5929 2654 2696 3555 +5930 2655 2697 2696 +5931 3481 2697 2655 +5932 3482 3481 2655 +5933 2730 2656 2733 +5934 2733 2656 2748 +5935 2656 3555 2748 +5936 3204 2657 2658 +5937 2657 3005 2800 +5938 3204 3005 2657 +5939 2824 3034 2658 +5940 3204 2658 3034 +5941 2659 2660 2684 +5942 2684 2685 2659 +5943 2751 2684 2660 +5944 2751 2660 2715 +5945 2661 2840 2662 +5946 2661 2798 2799 +5947 2840 2661 2799 +5948 2662 2840 2839 +5949 2895 2662 2839 +5950 2663 2934 2664 +5951 2931 2663 2932 +5952 2663 2931 2933 +5953 2663 2933 2934 +5954 2665 2667 2666 +5955 2666 3293 2665 +5956 2667 2665 2866 +5957 3238 2866 2665 +5958 2665 3300 3238 +5959 3300 2665 3293 +5960 2667 3134 2666 +5961 2666 3134 3133 +5962 2666 3133 3135 +5963 3293 2666 3135 +5964 2866 3485 2667 +5965 3134 2667 3169 +5966 2667 3579 3169 +5967 2667 3485 3579 +5968 2668 2670 2669 +5969 2668 2669 3383 +5970 3502 2670 2668 +5971 3506 2668 3383 +5972 2668 3506 3502 +5973 2669 2670 3417 +5974 2669 3259 3257 +5975 3257 3383 2669 +5976 3259 2669 3326 +5977 3417 3326 2669 +5978 2670 3435 3417 +5979 3435 2670 3502 +5980 2671 2673 2672 +5981 2672 2783 2671 +5982 2673 2671 2780 +5983 2780 2671 2782 +5984 2782 2671 2783 +5985 2672 2673 2674 +5986 3219 2783 2672 +5987 2981 2674 2673 +5988 2780 2863 2673 +5989 2981 2673 2863 +5990 2674 2981 2915 +5991 2675 2677 2676 +5992 2676 2916 2675 +5993 2677 2675 3145 +5994 2976 2675 2916 +5995 3144 2675 2976 +5996 3144 3145 2675 +5997 2676 2677 2678 +5998 2678 2979 2676 +5999 2676 3102 2916 +6000 2997 2676 2979 +6001 3070 2676 2997 +6002 3070 3102 2676 +6003 3157 2678 2677 +6004 3145 3157 2677 +6005 2678 2747 2980 +6006 2979 2678 2980 +6007 2679 2680 3020 +6008 3020 3069 2679 +6009 3020 2680 3065 +6010 2849 2682 2681 +6011 2967 2681 2683 +6012 2782 2681 2785 +6013 2849 2681 2782 +6014 2785 2681 2967 +6015 2682 2849 3328 +6016 2682 3328 3262 +6017 2923 2966 2683 +6018 2683 2966 2967 +6019 2686 2685 2684 +6020 2686 2684 2687 +6021 2684 2752 2687 +6022 2684 2751 2752 +6023 2686 2837 2685 +6024 2685 2837 2871 +6025 2687 2838 2686 +6026 2837 2686 2838 +6027 2687 2752 2801 +6028 2801 2921 2687 +6029 2687 2921 2838 +6030 2688 2689 3017 +6031 3017 3071 2688 +6032 2689 3543 3017 +6033 2690 2692 2691 +6034 2691 2870 2690 +6035 2690 3167 2692 +6036 2690 2870 3302 +6037 2690 2921 3167 +6038 2690 3302 2921 +6039 2937 2870 2691 +6040 2929 2937 2691 +6041 2692 3168 3003 +6042 2692 3167 3168 +6043 2693 2695 2694 +6044 2694 3337 2693 +6045 2695 2693 2698 +6046 3105 2698 2693 +6047 3105 2693 3107 +6048 3107 2693 3337 +6049 3076 2694 2695 +6050 3076 3250 2694 +6051 2694 3250 3337 +6052 3076 2695 3077 +6053 2696 2697 2699 +6054 2696 2699 3210 +6055 3210 3553 2696 +6056 3553 3555 2696 +6057 2699 2697 3406 +6058 2697 3479 3406 +6059 3479 2697 3478 +6060 2697 3481 3478 +6061 3301 2698 3105 +6062 2699 2892 3210 +6063 3523 2892 2699 +6064 3406 3523 2699 +6065 2700 2702 2701 +6066 2700 2701 2703 +6067 2700 3550 2702 +6068 2700 2703 3151 +6069 3475 2700 3151 +6070 2700 3475 3476 +6071 3550 2700 3476 +6072 2904 2701 2702 +6073 2703 2701 3211 +6074 2904 3142 2701 +6075 3142 3211 2701 +6076 2882 2883 2702 +6077 2702 3534 2882 +6078 2883 2904 2702 +6079 3534 2702 3550 +6080 3150 3151 2703 +6081 3150 2703 3211 +6082 2705 2757 2704 +6083 2704 2757 2756 +6084 2704 2756 3006 +6085 2917 2757 2705 +6086 2936 2920 2706 +6087 2706 2920 3035 +6088 3217 2707 2708 +6089 3218 2707 3217 +6090 2708 2842 2841 +6091 3217 2708 2841 +6092 2842 2708 3246 +6093 2709 2711 2710 +6094 3125 2709 2710 +6095 2709 3203 2711 +6096 2990 2710 2711 +6097 2990 3217 2710 +6098 3125 2710 3091 +6099 2710 3217 3091 +6100 3171 2713 2746 +6101 3104 2713 3171 +6102 2726 2714 2724 +6103 2716 2718 2717 +6104 3283 2716 2717 +6105 2716 3101 2718 +6106 3048 3101 2716 +6107 3048 2716 3283 +6108 2717 2718 2954 +6109 2737 2717 2738 +6110 3283 2717 2737 +6111 2954 2738 2717 +6112 2718 2963 2954 +6113 2719 2973 2744 +6114 2793 2721 3080 +6115 2721 2926 3080 +6116 2722 2723 3182 +6117 2722 2974 2927 +6118 2722 3182 2974 +6119 3182 2723 3183 +6120 3541 3183 2723 +6121 2723 3542 3541 +6122 2726 2724 2771 +6123 2724 2727 2766 +6124 2766 2771 2724 +6125 3121 2725 2774 +6126 3120 2726 2771 +6127 2856 2766 2727 +6128 2851 2852 2727 +6129 3103 2851 2727 +6130 2856 2727 2852 +6131 2729 2728 2964 +6132 2913 2922 2728 +6133 2964 2728 2922 +6134 2924 2729 2964 +6135 2730 2732 2731 +6136 2731 3089 2730 +6137 2733 2732 2730 +6138 3532 2730 3089 +6139 2731 2732 2779 +6140 2731 2779 3087 +6141 3087 3088 2731 +6142 2731 3088 3089 +6143 2732 2733 2775 +6144 2756 2732 2775 +6145 2732 2756 2776 +6146 2779 2732 2776 +6147 2748 2749 2733 +6148 2733 2749 2775 +6149 2734 2736 2735 +6150 2974 2734 2735 +6151 2739 2736 2734 +6152 2734 3183 2739 +6153 3182 2734 2974 +6154 2734 3182 3183 +6155 2735 2736 2740 +6156 2735 2740 2788 +6157 2974 2735 2788 +6158 3569 2736 2739 +6159 2736 3572 2740 +6160 3267 2736 3263 +6161 2736 3569 3263 +6162 2736 3267 3572 +6163 2737 2738 2927 +6164 2789 2737 2927 +6165 3283 2737 2789 +6166 2954 2926 2738 +6167 3540 2739 3183 +6168 2739 3540 3539 +6169 2739 3539 3569 +6170 3022 2977 2740 +6171 3572 3022 2740 +6172 2741 2743 2742 +6173 2742 2854 2741 +6174 2741 2747 2743 +6175 2980 2747 2741 +6176 2854 2855 2741 +6177 2741 2855 2980 +6178 2745 2742 2743 +6179 2745 2922 2742 +6180 2742 2935 2854 +6181 2742 2922 2935 +6182 2743 2803 2745 +6183 3004 2744 3005 +6184 2745 2803 2965 +6185 2745 2965 2922 +6186 2746 2810 2809 +6187 2746 2809 2811 +6188 2746 2811 3171 +6189 3555 2750 2748 +6190 2749 3006 2775 +6191 3006 2749 3318 +6192 3553 2750 3555 +6193 2753 2754 2794 +6194 2753 2794 2823 +6195 2755 2904 2754 +6196 2883 2794 2754 +6197 2904 2883 2754 +6198 2755 3142 2904 +6199 2755 2986 3142 +6200 2757 2776 2756 +6201 2775 3006 2756 +6202 2776 2757 2917 +6203 3009 2758 2894 +6204 2759 2761 2760 +6205 2759 2760 3525 +6206 2764 2761 2759 +6207 2992 2764 2759 +6208 2759 2972 2992 +6209 2972 2759 3525 +6210 2760 2761 3571 +6211 3525 2760 3106 +6212 2768 2761 2764 +6213 2768 3113 2761 +6214 2761 3113 3571 +6215 2938 3172 2762 +6216 2762 3172 3127 +6217 2763 2773 2772 +6218 2763 2772 2774 +6219 2768 2764 3110 +6220 2992 3109 2764 +6221 2764 3109 3110 +6222 2765 2767 2766 +6223 2856 2765 2766 +6224 2856 3474 2765 +6225 2765 3474 3131 +6226 2766 2767 2771 +6227 2767 2770 2769 +6228 2767 2769 2771 +6229 3110 3112 2768 +6230 2768 3112 3113 +6231 3120 2771 2769 +6232 3121 2774 2772 +6233 2776 2919 2779 +6234 2776 2917 2918 +6235 2776 2918 2919 +6236 3164 2778 2777 +6237 2827 2828 2777 +6238 2777 2828 2830 +6239 2830 3164 2777 +6240 3164 3030 2778 +6241 2919 3252 2779 +6242 3087 2779 3252 +6243 2780 2782 2781 +6244 2781 2862 2780 +6245 2862 2863 2780 +6246 2785 2781 2782 +6247 2785 2920 2781 +6248 2781 2936 2862 +6249 2781 2920 2936 +6250 2849 2782 2783 +6251 2785 2967 2920 +6252 2792 2786 2793 +6253 2795 2786 2792 +6254 2795 3533 2786 +6255 2788 2789 2974 +6256 2927 2974 2789 +6257 2790 3086 2950 +6258 2791 3508 3510 +6259 3508 2791 3544 +6260 3510 3521 2791 +6261 3541 2791 3521 +6262 3542 2791 3541 +6263 2793 3085 2792 +6264 2795 2792 2903 +6265 2903 2792 3196 +6266 2792 3085 3196 +6267 2793 3080 3085 +6268 2823 2794 2825 +6269 2825 2794 2881 +6270 2883 2881 2794 +6271 2795 2903 2902 +6272 3241 2795 2902 +6273 2795 2909 2912 +6274 2909 2795 3241 +6275 3533 2795 2912 +6276 2805 2796 2804 +6277 2796 3128 2804 +6278 2957 3027 2797 +6279 3469 2957 2797 +6280 2799 2798 3279 +6281 2799 3344 2840 +6282 3279 3566 2799 +6283 2799 3345 3344 +6284 3566 3345 2799 +6285 3167 2921 2801 +6286 2802 2804 2803 +6287 2804 2802 2805 +6288 2802 2845 2805 +6289 2847 2845 2802 +6290 3128 2803 2804 +6291 2965 2803 3128 +6292 3194 2805 2845 +6293 2859 2864 2806 +6294 2806 2865 2859 +6295 2806 3507 2865 +6296 2808 2949 2807 +6297 3086 2807 2949 +6298 2949 2808 3031 +6299 2810 2984 2809 +6300 3303 2811 2809 +6301 2896 2809 2895 +6302 2984 2895 2809 +6303 2809 2896 3303 +6304 2975 2984 2810 +6305 2812 2815 2813 +6306 2812 3235 2815 +6307 2813 2815 3207 +6308 3208 2813 3207 +6309 2818 2819 2814 +6310 2814 2989 2818 +6311 3237 3207 2815 +6312 3233 2815 3235 +6313 3233 3237 2815 +6314 2817 2944 2816 +6315 3081 2816 2944 +6316 2944 2817 3025 +6317 2818 2820 2819 +6318 2988 2968 2818 +6319 2988 2818 2989 +6320 2932 2819 2820 +6321 2931 2932 2820 +6322 3160 2931 2820 +6323 3327 2821 2822 +6324 2826 2822 2823 +6325 3327 2822 2826 +6326 2825 2826 2823 +6327 3028 2996 2824 +6328 3034 2824 2996 +6329 2829 2826 2825 +6330 2825 2908 2829 +6331 2825 2881 2908 +6332 3234 2826 2829 +6333 3234 3327 2826 +6334 2827 3159 2828 +6335 2827 3132 3158 +6336 3158 3159 2827 +6337 2830 2828 2831 +6338 2829 2908 3236 +6339 3233 3234 2829 +6340 3236 3233 2829 +6341 2831 3314 2830 +6342 2830 3567 3164 +6343 2830 3314 3567 +6344 2832 2834 2833 +6345 2832 2833 3148 +6346 2832 2835 2834 +6347 2835 2832 3170 +6348 3148 3426 2832 +6349 3426 3170 2832 +6350 2836 2833 2834 +6351 2833 2836 3147 +6352 3148 2833 3147 +6353 2834 2835 3575 +6354 2836 2834 3368 +6355 3368 2834 3575 +6356 2906 2835 3552 +6357 3575 2835 2906 +6358 3170 3552 2835 +6359 2836 3153 3147 +6360 2843 2837 2838 +6361 2843 3573 2837 +6362 2837 2872 2871 +6363 3573 2872 2837 +6364 2838 2844 2843 +6365 2844 2838 2925 +6366 2925 2838 2921 +6367 2898 2839 2840 +6368 2895 2839 2896 +6369 2839 2897 2896 +6370 2839 2898 2897 +6371 2840 3346 2898 +6372 3346 2840 3344 +6373 3090 2841 2842 +6374 3091 2841 3090 +6375 3217 2841 3091 +6376 3090 2842 3245 +6377 2842 3246 3245 +6378 3339 2843 2844 +6379 2843 3339 3338 +6380 3338 3566 2843 +6381 3573 2843 3566 +6382 2925 3557 2844 +6383 3056 3339 2844 +6384 2844 3559 3056 +6385 3559 2844 3557 +6386 2845 2847 2846 +6387 2845 2846 3194 +6388 2848 2846 2847 +6389 2846 2848 2978 +6390 2846 3003 3194 +6391 2978 2848 2982 +6392 2850 2852 2851 +6393 2851 3174 2850 +6394 2850 2857 2852 +6395 2850 2859 2857 +6396 2859 2850 2864 +6397 2864 2850 3174 +6398 2851 3103 3104 +6399 2851 3104 3174 +6400 2852 2857 2856 +6401 2853 2855 2854 +6402 2853 2979 2855 +6403 2853 2960 2999 +6404 2853 2999 2979 +6405 2979 2980 2855 +6406 3474 2856 2857 +6407 2860 2857 2859 +6408 3474 2857 2860 +6409 2858 2860 2859 +6410 2865 2858 2859 +6411 3317 2860 2858 +6412 2884 2858 2865 +6413 3152 2858 2884 +6414 2858 3152 3317 +6415 2860 3317 3129 +6416 2860 3129 3474 +6417 2861 2863 2862 +6418 2861 2981 2863 +6419 2861 2961 3002 +6420 2861 3002 2981 +6421 2884 2865 2886 +6422 3507 2886 2865 +6423 2866 2874 2873 +6424 2866 2873 3485 +6425 3560 2874 2866 +6426 3238 3560 2866 +6427 2867 2869 2868 +6428 2899 2867 2868 +6429 2867 3468 2869 +6430 2867 2899 3342 +6431 3468 2867 3342 +6432 3527 2868 2869 +6433 3187 2899 2868 +6434 3187 2868 3114 +6435 3527 3114 2868 +6436 3274 2869 2959 +6437 2869 3468 2959 +6438 3274 3527 2869 +6439 3230 2870 2937 +6440 3230 3557 2870 +6441 3302 2870 3557 +6442 3280 2872 3573 +6443 2874 2939 2873 +6444 2939 3526 2873 +6445 3568 3485 2873 +6446 2873 3526 3568 +6447 2874 2908 2881 +6448 2874 2881 2939 +6449 3560 2908 2874 +6450 2875 2877 2876 +6451 2875 2876 3051 +6452 3472 2877 2875 +6453 2875 3051 3401 +6454 3272 2875 3401 +6455 2875 3272 3472 +6456 3443 2876 2877 +6457 3051 2876 3444 +6458 2876 3443 3444 +6459 3446 2877 3366 +6460 3366 2877 3472 +6461 3443 2877 3446 +6462 2878 3229 3013 +6463 3240 3229 2878 +6464 2878 3239 3240 +6465 2879 2880 3249 +6466 2879 3328 2887 +6467 3253 2879 3249 +6468 3262 2879 3253 +6469 3262 3328 2879 +6470 2880 3248 3249 +6471 2881 2883 2882 +6472 2881 2882 2939 +6473 2939 2882 3534 +6474 2884 2886 2885 +6475 2884 2885 3483 +6476 3152 2884 3143 +6477 2884 3483 3143 +6478 3447 2885 2886 +6479 3483 2885 3150 +6480 3490 3150 2885 +6481 2885 3447 3490 +6482 2888 2890 2889 +6483 2889 3064 2888 +6484 2982 2890 2888 +6485 2888 2978 2982 +6486 3064 3074 2888 +6487 2889 2890 2891 +6488 2889 2891 2892 +6489 2892 2893 2889 +6490 2893 3064 2889 +6491 3210 2892 2891 +6492 3470 3210 2891 +6493 2893 2892 3523 +6494 3064 2893 3066 +6495 3395 3066 2893 +6496 2893 3523 3395 +6497 3013 3009 2894 +6498 2896 2897 3239 +6499 3303 2896 3239 +6500 3240 2897 2898 +6501 3239 2897 3240 +6502 3346 3063 2898 +6503 3558 2898 3063 +6504 2898 3558 3240 +6505 3187 3358 2899 +6506 2899 3341 3342 +6507 3358 3341 2899 +6508 2902 2903 3092 +6509 3261 2902 3092 +6510 2902 3261 3241 +6511 3173 3092 2903 +6512 3173 2903 3196 +6513 2905 3575 2906 +6514 3038 2905 3040 +6515 2905 3038 3512 +6516 3512 3368 2905 +6517 3575 2905 3368 +6518 2907 2906 3552 +6519 2907 3552 3169 +6520 2907 3169 3564 +6521 3236 2908 3560 +6522 2909 2911 2910 +6523 2912 2909 2910 +6524 3099 2911 2909 +6525 2909 3241 3099 +6526 2910 2911 3054 +6527 2910 3055 2912 +6528 2910 3054 3053 +6529 2910 3053 3055 +6530 3054 2911 3216 +6531 2911 3099 3098 +6532 2911 3098 3216 +6533 2914 2922 2913 +6534 2935 2922 2914 +6535 3000 2915 2981 +6536 3072 2915 3000 +6537 3072 3050 2915 +6538 2976 2916 3065 +6539 2916 3102 3065 +6540 3309 2919 2918 +6541 3097 3095 2919 +6542 3252 2919 3095 +6543 3097 2919 3309 +6544 2966 2920 2967 +6545 2966 3035 2920 +6546 3302 2925 2921 +6547 2964 2922 2965 +6548 2923 3035 2966 +6549 2925 3302 3557 +6550 2954 2955 2926 +6551 2955 3080 2926 +6552 2928 2930 2929 +6553 2929 3139 2928 +6554 3538 2930 2928 +6555 2928 3139 3137 +6556 3538 2928 3137 +6557 2929 2930 2937 +6558 2937 2930 3046 +6559 2930 3538 3046 +6560 2933 2931 3162 +6561 2931 3160 3154 +6562 3154 3162 2931 +6563 2933 3052 2934 +6564 2933 3106 3052 +6565 3106 2933 3525 +6566 3525 2933 3162 +6567 3046 3230 2937 +6568 3172 2938 3511 +6569 3199 3511 2938 +6570 2939 3534 3526 +6571 2940 3274 3161 +6572 2940 3527 3274 +6573 2941 2943 2942 +6574 2941 2942 3056 +6575 2941 2946 2943 +6576 2941 3242 2946 +6577 2941 3056 3243 +6578 2941 3243 3242 +6579 2951 2942 2943 +6580 2942 2951 3338 +6581 2942 3339 3056 +6582 3338 3339 2942 +6583 3277 2943 2946 +6584 3061 2951 2943 +6585 2943 3062 3061 +6586 3277 3062 2943 +6587 3081 2944 2945 +6588 2947 2953 2945 +6589 2983 2945 2953 +6590 2983 3081 2945 +6591 3007 3201 2948 +6592 3086 2949 2950 +6593 2951 3061 3344 +6594 2951 3345 3338 +6595 3345 2951 3344 +6596 2953 3073 2983 +6597 2954 2956 2955 +6598 2954 2963 2956 +6599 2956 3298 2955 +6600 3298 3080 2955 +6601 2956 3119 3298 +6602 2957 2959 2958 +6603 2958 3027 2957 +6604 3469 2959 2957 +6605 2958 2959 2962 +6606 2958 2962 3012 +6607 3027 2958 3012 +6608 2959 3468 2962 +6609 3274 2959 3469 +6610 3014 3012 2962 +6611 3281 3014 2962 +6612 3468 3281 2962 +6613 3128 2964 2965 +6614 2988 3166 2968 +6615 2968 3147 3153 +6616 3189 3147 2968 +6617 3166 3189 2968 +6618 2969 2971 2970 +6619 2970 3155 2969 +6620 3180 2971 2969 +6621 2969 3155 3041 +6622 3041 3180 2969 +6623 2970 2971 2972 +6624 3162 2970 2972 +6625 3155 2970 3154 +6626 3162 3154 2970 +6627 2992 2972 2971 +6628 2992 2971 3184 +6629 3180 3181 2971 +6630 2971 3181 3184 +6631 3525 3162 2972 +6632 2976 3065 3175 +6633 3144 2976 3146 +6634 3146 2976 3175 +6635 3022 3019 2977 +6636 2979 2999 2997 +6637 2981 3002 3000 +6638 2985 2987 2986 +6639 3156 2987 2985 +6640 3143 2986 2987 +6641 3141 3142 2986 +6642 2986 3143 3141 +6643 3143 2987 3152 +6644 3152 2987 3156 +6645 3163 3165 2988 +6646 2988 3165 3166 +6647 3217 2990 3218 +6648 2991 3159 3158 +6649 3158 3286 2991 +6650 2992 3184 3109 +6651 2993 2995 2994 +6652 2994 3518 2993 +6653 3060 2995 2993 +6654 3058 3059 2993 +6655 2993 3518 3058 +6656 2993 3059 3060 +6657 2994 2995 2996 +6658 2994 2996 3028 +6659 3519 2994 3028 +6660 3518 2994 3519 +6661 2995 3060 3098 +6662 2998 3070 2997 +6663 3069 3070 2998 +6664 3001 3072 3000 +6665 3071 3072 3001 +6666 3194 3003 3168 +6667 3004 3005 3204 +6668 3004 3367 3197 +6669 3367 3004 3204 +6670 3006 3318 3100 +6671 3007 3009 3008 +6672 3008 3079 3007 +6673 3007 3079 3201 +6674 3009 3013 3008 +6675 3229 3008 3013 +6676 3078 3079 3008 +6677 3008 3229 3078 +6678 3010 3012 3011 +6679 3011 3518 3010 +6680 3027 3012 3010 +6681 3027 3010 3026 +6682 3519 3026 3010 +6683 3518 3519 3010 +6684 3011 3012 3014 +6685 3057 3011 3014 +6686 3057 3058 3011 +6687 3518 3011 3058 +6688 3281 3057 3014 +6689 3015 3032 3016 +6690 3015 3030 3029 +6691 3015 3029 3032 +6692 3016 3032 3082 +6693 3071 3017 3050 +6694 3019 3033 3018 +6695 3019 3022 3043 +6696 3019 3043 3033 +6697 3020 3065 3102 +6698 3069 3020 3102 +6699 3021 3289 3503 +6700 3268 3043 3022 +6701 3022 3572 3268 +6702 3026 3519 3028 +6703 3164 3029 3030 +6704 3032 3029 3084 +6705 3029 3567 3084 +6706 3029 3164 3567 +6707 3082 3032 3083 +6708 3083 3032 3084 +6709 3033 3043 3042 +6710 3033 3042 3096 +6711 3037 3204 3034 +6712 3036 3198 3037 +6713 3036 3504 3198 +6714 3036 3261 3504 +6715 3198 3367 3037 +6716 3204 3037 3367 +6717 3038 3040 3039 +6718 3038 3039 3041 +6719 3038 3041 3512 +6720 3179 3039 3040 +6721 3041 3039 3178 +6722 3177 3178 3039 +6723 3177 3039 3179 +6724 3512 3041 3155 +6725 3180 3041 3178 +6726 3042 3043 3205 +6727 3299 3096 3042 +6728 3042 3205 3299 +6729 3043 3268 3205 +6730 3044 3046 3045 +6731 3044 3045 3047 +6732 3044 3230 3046 +6733 3044 3047 3243 +6734 3044 3244 3230 +6735 3044 3243 3244 +6736 3538 3045 3046 +6737 3045 3232 3047 +6738 3228 3232 3045 +6739 3045 3538 3228 +6740 3232 3347 3047 +6741 3047 3242 3243 +6742 3242 3047 3347 +6743 3283 3049 3048 +6744 3071 3050 3072 +6745 3401 3051 3403 +6746 3403 3051 3501 +6747 3051 3444 3500 +6748 3051 3500 3501 +6749 3516 3053 3054 +6750 3055 3053 3354 +6751 3352 3354 3053 +6752 3516 3352 3053 +6753 3516 3054 3216 +6754 3544 3055 3354 +6755 3056 3244 3243 +6756 3244 3056 3559 +6757 3057 3535 3058 +6758 3281 3282 3057 +6759 3535 3057 3282 +6760 3535 3059 3058 +6761 3059 3216 3060 +6762 3212 3216 3059 +6763 3059 3535 3212 +6764 3098 3060 3216 +6765 3061 3062 3063 +6766 3346 3061 3063 +6767 3346 3344 3061 +6768 3063 3062 3275 +6769 3275 3062 3276 +6770 3276 3062 3277 +6771 3278 3063 3275 +6772 3063 3278 3558 +6773 3074 3064 3066 +6774 3140 3074 3066 +6775 3537 3140 3066 +6776 3395 3561 3066 +6777 3561 3537 3066 +6778 3067 3068 3075 +6779 3075 3463 3067 +6780 3322 3067 3323 +6781 3323 3067 3405 +6782 3463 3405 3067 +6783 3075 3068 3563 +6784 3069 3102 3070 +6785 3140 3136 3074 +6786 3075 3449 3464 +6787 3075 3563 3449 +6788 3463 3075 3464 +6789 3076 3077 3209 +6790 3076 3135 3250 +6791 3293 3135 3076 +6792 3076 3209 3293 +6793 3202 3079 3078 +6794 3078 3276 3202 +6795 3278 3078 3229 +6796 3078 3275 3276 +6797 3275 3078 3278 +6798 3200 3201 3079 +6799 3200 3079 3202 +6800 3080 3195 3085 +6801 3195 3080 3298 +6802 3082 3083 3505 +6803 3124 3505 3083 +6804 3196 3085 3195 +6805 3088 3087 3251 +6806 3087 3252 3251 +6807 3088 3371 3089 +6808 3088 3251 3407 +6809 3370 3371 3088 +6810 3370 3088 3407 +6811 3532 3089 3371 +6812 3090 3245 3122 +6813 3092 3094 3093 +6814 3092 3093 3261 +6815 3173 3094 3092 +6816 3093 3094 3172 +6817 3172 3511 3093 +6818 3504 3261 3093 +6819 3504 3093 3511 +6820 3126 3127 3094 +6821 3094 3127 3172 +6822 3095 3097 3096 +6823 3095 3096 3299 +6824 3095 3251 3252 +6825 3299 3251 3095 +6826 3176 3100 3318 +6827 3254 3105 3107 +6828 3301 3105 3254 +6829 3107 3148 3147 +6830 3189 3107 3147 +6831 3107 3337 3148 +6832 3254 3107 3189 +6833 3108 3110 3109 +6834 3108 3109 3111 +6835 3108 3551 3110 +6836 3255 3108 3111 +6837 3255 3256 3108 +6838 3551 3108 3256 +6839 3111 3109 3184 +6840 3551 3112 3110 +6841 3185 3111 3184 +6842 3111 3185 3457 +6843 3255 3111 3457 +6844 3225 3113 3112 +6845 3221 3223 3112 +6846 3551 3221 3112 +6847 3223 3225 3112 +6848 3114 3116 3115 +6849 3115 3188 3114 +6850 3527 3116 3114 +6851 3187 3114 3188 +6852 3115 3116 3117 +6853 3115 3117 3220 +6854 3115 3224 3188 +6855 3220 3224 3115 +6856 3503 3117 3116 +6857 3117 3222 3220 +6858 3222 3117 3289 +6859 3503 3289 3117 +6860 3119 3195 3298 +6861 3122 3245 3248 +6862 3123 3225 3223 +6863 3288 3123 3223 +6864 3124 3125 3505 +6865 3130 3131 3129 +6866 3129 3131 3474 +6867 3132 3286 3158 +6868 3170 3133 3134 +6869 3135 3133 3250 +6870 3170 3426 3133 +6871 3426 3250 3133 +6872 3170 3134 3169 +6873 3136 3138 3137 +6874 3136 3137 3139 +6875 3138 3136 3140 +6876 3231 3137 3138 +6877 3231 3227 3137 +6878 3227 3538 3137 +6879 3140 3537 3138 +6880 3231 3138 3537 +6881 3142 3141 3211 +6882 3141 3143 3483 +6883 3141 3483 3211 +6884 3146 3319 3144 +6885 3175 3176 3146 +6886 3337 3250 3148 +6887 3426 3148 3250 +6888 3149 3151 3150 +6889 3150 3490 3149 +6890 3149 3420 3151 +6891 3419 3420 3149 +6892 3419 3149 3547 +6893 3536 3149 3490 +6894 3547 3149 3536 +6895 3211 3483 3150 +6896 3545 3151 3420 +6897 3151 3545 3475 +6898 3317 3152 3156 +6899 3155 3513 3512 +6900 3469 3161 3274 +6901 3165 3254 3166 +6902 3165 3301 3254 +6903 3166 3254 3189 +6904 3552 3170 3169 +6905 3579 3564 3169 +6906 3177 3186 3178 +6907 3273 3177 3179 +6908 3186 3177 3269 +6909 3269 3177 3273 +6910 3178 3181 3180 +6911 3186 3181 3178 +6912 3273 3179 3320 +6913 3185 3184 3181 +6914 3185 3181 3186 +6915 3521 3540 3183 +6916 3183 3541 3521 +6917 3270 3185 3186 +6918 3457 3185 3270 +6919 3270 3186 3269 +6920 3187 3188 3489 +6921 3489 3358 3187 +6922 3224 3260 3188 +6923 3188 3260 3489 +6924 3190 3192 3191 +6925 3191 3285 3190 +6926 3531 3192 3190 +6927 3285 3539 3190 +6928 3531 3190 3522 +6929 3539 3522 3190 +6930 3191 3192 3193 +6931 3191 3193 3284 +6932 3284 3265 3191 +6933 3191 3265 3285 +6934 3193 3192 3306 +6935 3192 3531 3306 +6936 3284 3193 3494 +6937 3193 3306 3304 +6938 3193 3304 3494 +6939 3198 3197 3367 +6940 3504 3199 3198 +6941 3511 3199 3504 +6942 3425 3200 3202 +6943 3425 3423 3200 +6944 3202 3276 3308 +6945 3202 3308 3425 +6946 3528 3205 3268 +6947 3205 3528 3299 +6948 3235 3206 3234 +6949 3206 3327 3234 +6950 3207 3209 3208 +6951 3293 3209 3207 +6952 3207 3237 3300 +6953 3207 3300 3293 +6954 3470 3553 3210 +6955 3212 3214 3213 +6956 3213 3516 3212 +6957 3535 3214 3212 +6958 3516 3216 3212 +6959 3213 3214 3215 +6960 3355 3213 3215 +6961 3355 3351 3213 +6962 3516 3213 3351 +6963 3214 3332 3215 +6964 3330 3332 3214 +6965 3214 3535 3330 +6966 3215 3332 3471 +6967 3355 3215 3471 +6968 3220 3222 3221 +6969 3221 3551 3220 +6970 3551 3224 3220 +6971 3221 3222 3223 +6972 3222 3288 3223 +6973 3222 3289 3288 +6974 3256 3260 3224 +6975 3224 3551 3256 +6976 3226 3228 3227 +6977 3226 3227 3231 +6978 3226 3497 3228 +6979 3226 3231 3333 +6980 3497 3226 3333 +6981 3538 3227 3228 +6982 3497 3232 3228 +6983 3558 3229 3240 +6984 3278 3229 3558 +6985 3230 3244 3559 +6986 3230 3559 3557 +6987 3231 3335 3333 +6988 3335 3231 3537 +6989 3316 3347 3232 +6990 3496 3316 3232 +6991 3497 3496 3232 +6992 3235 3234 3233 +6993 3236 3237 3233 +6994 3236 3238 3237 +6995 3560 3238 3236 +6996 3237 3238 3300 +6997 3245 3246 3247 +6998 3249 3245 3247 +6999 3248 3245 3249 +7000 3247 3253 3249 +7001 3408 3251 3299 +7002 3407 3251 3408 +7003 3255 3404 3256 +7004 3255 3458 3404 +7005 3457 3458 3255 +7006 3404 3260 3256 +7007 3257 3259 3258 +7008 3258 3467 3257 +7009 3379 3383 3257 +7010 3257 3467 3379 +7011 3258 3259 3287 +7012 3258 3287 3565 +7013 3258 3400 3467 +7014 3400 3258 3565 +7015 3259 3325 3287 +7016 3259 3326 3325 +7017 3402 3260 3404 +7018 3489 3260 3402 +7019 3263 3265 3264 +7020 3263 3264 3267 +7021 3285 3265 3263 +7022 3569 3285 3263 +7023 3264 3265 3266 +7024 3264 3266 3528 +7025 3267 3264 3268 +7026 3268 3264 3528 +7027 3442 3266 3265 +7028 3284 3442 3265 +7029 3266 3370 3407 +7030 3442 3370 3266 +7031 3408 3266 3407 +7032 3266 3408 3528 +7033 3267 3268 3572 +7034 3269 3271 3270 +7035 3473 3271 3269 +7036 3273 3473 3269 +7037 3270 3271 3272 +7038 3270 3272 3457 +7039 3272 3271 3472 +7040 3472 3271 3364 +7041 3364 3271 3473 +7042 3458 3272 3401 +7043 3272 3458 3457 +7044 3473 3273 3320 +7045 3308 3276 3277 +7046 3280 3566 3279 +7047 3280 3573 3566 +7048 3281 3331 3282 +7049 3468 3331 3281 +7050 3329 3330 3282 +7051 3329 3282 3331 +7052 3535 3282 3330 +7053 3442 3284 3369 +7054 3459 3369 3284 +7055 3494 3459 3284 +7056 3569 3539 3285 +7057 3325 3453 3287 +7058 3565 3287 3453 +7059 3290 3292 3291 +7060 3290 3291 3294 +7061 3290 3529 3292 +7062 3449 3290 3294 +7063 3448 3290 3449 +7064 3529 3290 3448 +7065 3378 3291 3292 +7066 3294 3291 3486 +7067 3377 3291 3378 +7068 3377 3486 3291 +7069 3295 3292 3296 +7070 3295 3378 3292 +7071 3529 3296 3292 +7072 3554 3449 3294 +7073 3466 3294 3486 +7074 3466 3554 3294 +7075 3295 3296 3297 +7076 3295 3297 3487 +7077 3295 3376 3378 +7078 3487 3376 3295 +7079 3500 3297 3296 +7080 3500 3296 3530 +7081 3529 3530 3296 +7082 3444 3445 3297 +7083 3297 3500 3444 +7084 3297 3445 3487 +7085 3408 3299 3528 +7086 3304 3306 3305 +7087 3305 3495 3304 +7088 3494 3304 3414 +7089 3414 3304 3495 +7090 3305 3306 3307 +7091 3389 3305 3307 +7092 3453 3305 3389 +7093 3495 3305 3453 +7094 3307 3306 3531 +7095 3388 3389 3307 +7096 3388 3307 3391 +7097 3531 3391 3307 +7098 3311 3424 3310 +7099 3310 3313 3312 +7100 3312 3484 3310 +7101 3424 3313 3310 +7102 3477 3310 3484 +7103 3423 3410 3311 +7104 3311 3410 3424 +7105 3312 3313 3315 +7106 3315 3313 3431 +7107 3432 3313 3424 +7108 3431 3313 3432 +7109 3315 3428 3387 +7110 3428 3315 3431 +7111 3324 3316 3396 +7112 3316 3496 3396 +7113 3320 3321 3363 +7114 3473 3320 3363 +7115 3321 3499 3363 +7116 3322 3323 3471 +7117 3471 3332 3322 +7118 3384 3385 3323 +7119 3384 3323 3405 +7120 3323 3385 3471 +7121 3324 3396 3397 +7122 3324 3397 3409 +7123 3409 3410 3324 +7124 3325 3326 3495 +7125 3453 3325 3495 +7126 3413 3326 3417 +7127 3495 3326 3413 +7128 3340 3329 3331 +7129 3340 3331 3342 +7130 3342 3331 3468 +7131 3333 3335 3334 +7132 3334 3452 3333 +7133 3497 3333 3452 +7134 3334 3335 3336 +7135 3334 3336 3517 +7136 3452 3334 3517 +7137 3336 3335 3537 +7138 3336 3433 3434 +7139 3433 3336 3561 +7140 3517 3336 3434 +7141 3537 3561 3336 +7142 3345 3566 3338 +7143 3340 3342 3341 +7144 3340 3341 3343 +7145 3343 3341 3357 +7146 3357 3341 3358 +7147 3357 3411 3343 +7148 3411 3570 3343 +7149 3348 3350 3349 +7150 3349 3422 3348 +7151 3348 3392 3350 +7152 3348 3397 3392 +7153 3348 3421 3397 +7154 3348 3422 3421 +7155 3349 3350 3359 +7156 3349 3359 3380 +7157 3349 3380 3524 +7158 3349 3524 3422 +7159 3359 3350 3506 +7160 3392 3451 3350 +7161 3506 3350 3451 +7162 3351 3353 3352 +7163 3352 3516 3351 +7164 3351 3355 3353 +7165 3352 3353 3354 +7166 3354 3353 3509 +7167 3353 3355 3356 +7168 3353 3356 3509 +7169 3354 3509 3508 +7170 3354 3508 3544 +7171 3355 3385 3356 +7172 3355 3471 3385 +7173 3390 3356 3385 +7174 3390 3391 3356 +7175 3356 3391 3562 +7176 3509 3356 3562 +7177 3358 3430 3357 +7178 3357 3412 3411 +7179 3412 3357 3430 +7180 3430 3358 3581 +7181 3489 3581 3358 +7182 3380 3359 3379 +7183 3359 3383 3379 +7184 3383 3359 3506 +7185 3360 3362 3361 +7186 3361 3488 3360 +7187 3362 3360 3462 +7188 3446 3360 3488 +7189 3491 3360 3446 +7190 3462 3360 3491 +7191 3361 3362 3387 +7192 3361 3387 3427 +7193 3488 3361 3427 +7194 3363 3365 3364 +7195 3364 3473 3363 +7196 3493 3365 3363 +7197 3499 3493 3363 +7198 3364 3365 3366 +7199 3364 3366 3472 +7200 3366 3365 3491 +7201 3491 3365 3492 +7202 3492 3365 3493 +7203 3446 3366 3491 +7204 3513 3368 3512 +7205 3369 3371 3370 +7206 3369 3370 3442 +7207 3482 3371 3369 +7208 3482 3369 3459 +7209 3482 3532 3371 +7210 3372 3374 3373 +7211 3372 3373 3375 +7212 3372 3382 3374 +7213 3372 3375 3422 +7214 3524 3382 3372 +7215 3422 3524 3372 +7216 3429 3373 3374 +7217 3375 3373 3431 +7218 3428 3373 3429 +7219 3428 3431 3373 +7220 3376 3374 3377 +7221 3376 3429 3374 +7222 3382 3377 3374 +7223 3375 3421 3422 +7224 3582 3421 3375 +7225 3432 3375 3431 +7226 3432 3582 3375 +7227 3376 3377 3378 +7228 3429 3376 3487 +7229 3382 3580 3377 +7230 3580 3486 3377 +7231 3379 3381 3380 +7232 3467 3381 3379 +7233 3380 3381 3382 +7234 3382 3524 3380 +7235 3580 3382 3381 +7236 3574 3381 3467 +7237 3381 3574 3486 +7238 3486 3580 3381 +7239 3384 3386 3385 +7240 3515 3386 3384 +7241 3405 3399 3384 +7242 3399 3515 3384 +7243 3386 3390 3385 +7244 3390 3386 3388 +7245 3515 3388 3386 +7246 3427 3387 3428 +7247 3389 3388 3515 +7248 3388 3391 3390 +7249 3514 3453 3389 +7250 3514 3389 3515 +7251 3391 3531 3562 +7252 3397 3396 3392 +7253 3396 3450 3392 +7254 3450 3451 3392 +7255 3393 3395 3394 +7256 3394 3436 3393 +7257 3393 3433 3395 +7258 3393 3434 3433 +7259 3435 3434 3393 +7260 3435 3393 3436 +7261 3394 3395 3406 +7262 3394 3406 3479 +7263 3436 3394 3479 +7264 3523 3406 3395 +7265 3395 3433 3561 +7266 3450 3396 3496 +7267 3397 3421 3409 +7268 3398 3400 3399 +7269 3405 3398 3399 +7270 3400 3398 3464 +7271 3398 3405 3463 +7272 3398 3463 3464 +7273 3565 3399 3400 +7274 3514 3515 3399 +7275 3514 3399 3565 +7276 3400 3464 3466 +7277 3400 3466 3467 +7278 3401 3403 3402 +7279 3401 3402 3404 +7280 3404 3458 3401 +7281 3441 3402 3403 +7282 3441 3581 3402 +7283 3581 3489 3402 +7284 3577 3441 3403 +7285 3501 3577 3403 +7286 3424 3410 3409 +7287 3421 3582 3409 +7288 3432 3424 3409 +7289 3582 3432 3409 +7290 3423 3549 3410 +7291 3529 3411 3412 +7292 3411 3529 3448 +7293 3570 3411 3448 +7294 3412 3430 3441 +7295 3441 3577 3412 +7296 3412 3576 3529 +7297 3576 3412 3577 +7298 3413 3415 3414 +7299 3414 3495 3413 +7300 3436 3415 3413 +7301 3417 3436 3413 +7302 3414 3415 3416 +7303 3414 3416 3494 +7304 3416 3415 3478 +7305 3479 3415 3436 +7306 3478 3415 3479 +7307 3416 3480 3459 +7308 3416 3459 3494 +7309 3480 3416 3478 +7310 3436 3417 3435 +7311 3418 3420 3419 +7312 3419 3456 3418 +7313 3418 3556 3420 +7314 3454 3418 3455 +7315 3556 3418 3454 +7316 3455 3418 3456 +7317 3456 3419 3547 +7318 3546 3545 3420 +7319 3556 3546 3420 +7320 3549 3423 3425 +7321 3427 3428 3429 +7322 3427 3429 3487 +7323 3487 3445 3427 +7324 3427 3445 3488 +7325 3441 3430 3581 +7326 3435 3502 3434 +7327 3502 3520 3434 +7328 3520 3517 3434 +7329 3437 3439 3438 +7330 3437 3438 3440 +7331 3465 3439 3437 +7332 3437 3440 3476 +7333 3437 3583 3465 +7334 3437 3476 3475 +7335 3583 3437 3475 +7336 3493 3438 3439 +7337 3440 3438 3498 +7338 3499 3438 3493 +7339 3498 3438 3499 +7340 3465 3461 3439 +7341 3461 3492 3439 +7342 3492 3493 3439 +7343 3526 3476 3440 +7344 3568 3440 3498 +7345 3440 3568 3526 +7346 3443 3445 3444 +7347 3488 3445 3443 +7348 3446 3488 3443 +7349 3447 3536 3490 +7350 3563 3448 3449 +7351 3449 3554 3464 +7352 3450 3452 3451 +7353 3452 3450 3497 +7354 3450 3496 3497 +7355 3520 3451 3452 +7356 3506 3451 3520 +7357 3517 3520 3452 +7358 3453 3514 3565 +7359 3455 3484 3454 +7360 3556 3454 3460 +7361 3455 3477 3484 +7362 3547 3548 3456 +7363 3480 3482 3459 +7364 3465 3460 3461 +7365 3465 3546 3460 +7366 3546 3556 3460 +7367 3492 3461 3462 +7368 3492 3462 3491 +7369 3554 3466 3464 +7370 3583 3546 3465 +7371 3466 3574 3467 +7372 3574 3466 3486 +7373 3545 3546 3475 +7374 3546 3583 3475 +7375 3526 3550 3476 +7376 3478 3481 3480 +7377 3480 3481 3482 +7378 3485 3568 3579 +7379 3564 3578 3498 +7380 3578 3568 3498 +7381 3500 3530 3501 +7382 3501 3530 3576 +7383 3501 3576 3577 +7384 3520 3502 3506 +7385 3508 3509 3510 +7386 3510 3509 3562 +7387 3521 3510 3522 +7388 3562 3522 3510 +7389 3521 3522 3540 +7390 3522 3562 3531 +7391 3540 3522 3539 +7392 3526 3534 3550 +7393 3530 3529 3576 +7394 3578 3564 3579 +7395 3568 3578 3579 +2 18 2 228 +7396 8 3635 97 +7397 418 3635 8 +7398 98 3636 9 +7399 9 3636 213 +7400 242 3633 19 +7401 19 3633 448 +7402 24 3634 447 +7403 449 3634 24 +7404 97 3662 98 +7405 3635 3662 97 +7406 98 3662 3636 +7407 213 3638 214 +7408 3636 3638 213 +7409 214 3624 215 +7410 214 3638 3624 +7411 215 3643 216 +7412 3624 3643 215 +7413 216 3608 217 +7414 216 3643 3608 +7415 217 3645 218 +7416 3608 3645 217 +7417 218 3623 219 +7418 218 3645 3623 +7419 219 3627 220 +7420 219 3623 3599 +7421 3599 3627 219 +7422 220 3659 221 +7423 3627 3659 220 +7424 221 3606 222 +7425 221 3659 3606 +7426 222 3641 223 +7427 3606 3641 222 +7428 223 3605 224 +7429 223 3641 3605 +7430 224 3640 225 +7431 3605 3640 224 +7432 225 3619 226 +7433 225 3640 3619 +7434 226 3625 227 +7435 226 3619 3598 +7436 3598 3625 226 +7437 227 3655 228 +7438 3625 3655 227 +7439 228 3603 229 +7440 228 3655 3603 +7441 229 3651 230 +7442 3603 3651 229 +7443 230 3616 231 +7444 230 3651 3616 +7445 231 3647 232 +7446 3616 3647 231 +7447 232 3612 233 +7448 232 3647 3612 +7449 233 3654 234 +7450 3612 3654 233 +7451 234 3617 235 +7452 234 3654 3617 +7453 235 3658 236 +7454 3617 3658 235 +7455 236 3629 237 +7456 236 3658 3629 +7457 237 3620 238 +7458 3600 3620 237 +7459 237 3629 3600 +7460 238 3648 239 +7461 3620 3648 238 +7462 239 3609 240 +7463 239 3648 3609 +7464 240 3663 241 +7465 3609 3663 240 +7466 241 3631 242 +7467 241 3663 3631 +7468 3631 3633 242 +7469 419 3637 418 +7470 418 3637 3635 +7471 420 3601 419 +7472 3601 3637 419 +7473 421 3644 420 +7474 420 3644 3601 +7475 422 3614 421 +7476 3614 3644 421 +7477 423 3646 422 +7478 422 3646 3614 +7479 424 3618 423 +7480 3618 3646 423 +7481 425 3628 424 +7482 3599 3618 424 +7483 424 3628 3599 +7484 426 3660 425 +7485 425 3660 3628 +7486 427 3611 426 +7487 3611 3660 426 +7488 428 3639 427 +7489 427 3639 3611 +7490 429 3613 428 +7491 3613 3639 428 +7492 430 3642 429 +7493 429 3642 3613 +7494 431 3622 430 +7495 3622 3642 430 +7496 432 3626 431 +7497 3598 3622 431 +7498 431 3626 3598 +7499 433 3656 432 +7500 432 3656 3626 +7501 434 3615 433 +7502 3615 3656 433 +7503 435 3652 434 +7504 434 3652 3615 +7505 436 3604 435 +7506 3604 3652 435 +7507 437 3649 436 +7508 436 3649 3604 +7509 438 3607 437 +7510 3607 3649 437 +7511 439 3653 438 +7512 438 3653 3607 +7513 440 3602 439 +7514 3602 3653 439 +7515 441 3657 440 +7516 440 3657 3602 +7517 442 3630 441 +7518 3630 3657 441 +7519 443 3621 442 +7520 442 3621 3600 +7521 3600 3630 442 +7522 444 3650 443 +7523 443 3650 3621 +7524 445 3610 444 +7525 3610 3650 444 +7526 446 3664 445 +7527 445 3664 3610 +7528 447 3632 446 +7529 3632 3664 446 +7530 447 3634 3632 +7531 448 3661 449 +7532 3633 3661 448 +7533 449 3661 3634 +7534 3584 3637 3601 +7535 3601 3638 3584 +7536 3635 3637 3584 +7537 3584 3662 3635 +7538 3584 3638 3636 +7539 3636 3662 3584 +7540 3631 3632 3585 +7541 3585 3633 3631 +7542 3632 3634 3585 +7543 3585 3661 3633 +7544 3634 3661 3585 +7545 3586 3615 3603 +7546 3603 3655 3586 +7547 3586 3656 3615 +7548 3625 3626 3586 +7549 3586 3655 3625 +7550 3626 3656 3586 +7551 3587 3611 3606 +7552 3606 3659 3587 +7553 3587 3660 3611 +7554 3627 3628 3587 +7555 3587 3659 3627 +7556 3628 3660 3587 +7557 3588 3613 3605 +7558 3605 3641 3588 +7559 3606 3611 3588 +7560 3588 3641 3606 +7561 3611 3639 3588 +7562 3588 3639 3613 +7563 3605 3613 3589 +7564 3589 3640 3605 +7565 3613 3642 3589 +7566 3589 3622 3619 +7567 3619 3640 3589 +7568 3589 3642 3622 +7569 3590 3624 3601 +7570 3601 3644 3590 +7571 3590 3614 3608 +7572 3608 3643 3590 +7573 3590 3644 3614 +7574 3590 3643 3624 +7575 3608 3614 3591 +7576 3591 3645 3608 +7577 3614 3646 3591 +7578 3618 3623 3591 +7579 3591 3646 3618 +7580 3623 3645 3591 +7581 3592 3616 3604 +7582 3604 3649 3592 +7583 3607 3612 3592 +7584 3592 3649 3607 +7585 3612 3647 3592 +7586 3592 3647 3616 +7587 3593 3617 3602 +7588 3602 3657 3593 +7589 3593 3658 3617 +7590 3593 3630 3629 +7591 3629 3658 3593 +7592 3593 3657 3630 +7593 3594 3610 3609 +7594 3609 3648 3594 +7595 3594 3650 3610 +7596 3620 3621 3594 +7597 3594 3648 3620 +7598 3621 3650 3594 +7599 3603 3615 3595 +7600 3595 3651 3603 +7601 3604 3616 3595 +7602 3595 3652 3604 +7603 3615 3652 3595 +7604 3616 3651 3595 +7605 3602 3617 3596 +7606 3596 3653 3602 +7607 3596 3612 3607 +7608 3607 3653 3596 +7609 3596 3654 3612 +7610 3617 3654 3596 +7611 3609 3610 3597 +7612 3597 3663 3609 +7613 3610 3664 3597 +7614 3597 3632 3631 +7615 3631 3663 3597 +7616 3597 3664 3632 +7617 3619 3622 3598 +7618 3598 3626 3625 +7619 3599 3623 3618 +7620 3599 3628 3627 +7621 3600 3621 3620 +7622 3629 3630 3600 +7623 3624 3638 3601 +2 19 2 753 +7624 19 3912 246 +7625 448 3923 19 +7626 19 3923 3912 +7627 243 3783 20 +7628 20 3868 290 +7629 3783 3868 20 +7630 277 3926 21 +7631 21 3917 324 +7632 21 3926 3917 +7633 321 3913 22 +7634 22 3924 356 +7635 3913 3924 22 +7636 355 3907 23 +7637 23 3885 417 +7638 23 3907 3885 +7639 387 3886 24 +7640 24 3908 449 +7641 3886 3908 24 +7642 244 3843 243 +7643 243 3843 3783 +7644 245 3843 244 +7645 246 3808 245 +7646 3808 3843 245 +7647 246 3912 3808 +7648 278 3855 277 +7649 3855 3998 277 +7650 277 3998 3926 +7651 279 3981 278 +7652 278 3981 3855 +7653 280 3798 279 +7654 3798 3981 279 +7655 281 3941 280 +7656 280 3941 3798 +7657 282 3836 281 +7658 3836 3941 281 +7659 283 3932 282 +7660 282 3932 3836 +7661 284 3948 283 +7662 3792 3932 283 +7663 283 3948 3792 +7664 285 3949 284 +7665 284 3949 3948 +7666 286 3814 285 +7667 3814 3949 285 +7668 287 3909 286 +7669 3756 3814 286 +7670 286 3909 3756 +7671 288 3999 287 +7672 287 3999 3909 +7673 289 3834 288 +7674 3834 3999 288 +7675 290 3793 289 +7676 3793 3834 289 +7677 290 3868 3793 +7678 322 3807 321 +7679 3807 3913 321 +7680 323 3935 322 +7681 322 3935 3807 +7682 324 3809 323 +7683 3809 3935 323 +7684 324 3917 3809 +7685 356 3831 355 +7686 3831 3907 355 +7687 356 3924 3831 +7688 388 3995 387 +7689 3780 3886 387 +7690 387 3995 3780 +7691 389 3849 388 +7692 3849 3995 388 +7693 390 3763 389 +7694 3763 3849 389 +7695 391 3864 390 +7696 390 3864 3763 +7697 392 3922 391 +7698 391 3922 3864 +7699 393 3974 392 +7700 392 3974 3922 +7701 394 3830 393 +7702 3830 3974 393 +7703 395 3951 394 +7704 394 3951 3830 +7705 396 3835 395 +7706 3835 3951 395 +7707 397 3778 396 +7708 3778 3835 396 +7709 398 3879 397 +7710 397 3879 3778 +7711 399 3815 398 +7712 3815 3879 398 +7713 400 3893 399 +7714 399 3893 3815 +7715 401 3786 400 +7716 3786 3893 400 +7717 402 3862 401 +7718 401 3862 3786 +7719 403 3969 402 +7720 402 3969 3862 +7721 404 3865 403 +7722 3865 3969 403 +7723 405 3802 404 +7724 3802 3865 404 +7725 406 3946 405 +7726 405 3946 3802 +7727 407 3852 406 +7728 3852 3946 406 +7729 408 3942 407 +7730 407 3942 3852 +7731 409 3812 408 +7732 3812 3942 408 +7733 410 3873 409 +7734 409 3873 3812 +7735 411 3888 410 +7736 3753 3873 410 +7737 410 3888 3753 +7738 412 3888 411 +7739 413 3921 412 +7740 3770 3888 412 +7741 412 3921 3770 +7742 414 3863 413 +7743 3863 3921 413 +7744 415 3764 414 +7745 3764 3863 414 +7746 416 3850 415 +7747 415 3850 3764 +7748 417 3994 416 +7749 416 3994 3850 +7750 417 3885 3779 +7751 3779 3994 417 +7752 449 3832 448 +7753 3832 3923 448 +7754 449 3908 3832 +7755 3810 3927 3665 +7756 3665 3950 3810 +7757 3874 3950 3665 +7758 3665 4004 3874 +7759 3927 4004 3665 +7760 3800 3833 3666 +7761 3666 3975 3800 +7762 3833 4010 3666 +7763 3666 3991 3975 +7764 3666 4010 3991 +7765 3791 3801 3667 +7766 3667 3871 3791 +7767 3801 3976 3667 +7768 3825 3844 3667 +7769 3667 3976 3825 +7770 3844 3871 3667 +7771 3668 3906 3761 +7772 3761 3944 3668 +7773 3818 3889 3668 +7774 3668 3944 3818 +7775 3889 3978 3668 +7776 3668 3978 3906 +7777 3806 3826 3669 +7778 3669 3970 3806 +7779 3826 3918 3669 +7780 3669 3918 3895 +7781 3895 3970 3669 +7782 3757 3958 3670 +7783 3670 3980 3757 +7784 3766 3829 3670 +7785 3670 3861 3766 +7786 3670 3979 3773 +7787 3773 3980 3670 +7788 3829 3979 3670 +7789 3670 3958 3861 +7790 3671 3819 3767 +7791 3767 3859 3671 +7792 3671 3869 3819 +7793 3859 3987 3671 +7794 3671 3938 3869 +7795 3671 3987 3938 +7796 3672 3854 3762 +7797 3762 3903 3672 +7798 3794 3797 3672 +7799 3672 3903 3794 +7800 3797 3823 3672 +7801 3823 3854 3672 +7802 3673 3842 3790 +7803 3790 3870 3673 +7804 3795 3796 3673 +7805 3673 3811 3795 +7806 3796 3842 3673 +7807 3673 3870 3811 +7808 3759 3799 3674 +7809 3674 3882 3759 +7810 3674 3838 3789 +7811 3789 3882 3674 +7812 3799 4000 3674 +7813 3674 4000 3838 +7814 3675 3904 3803 +7815 3803 3936 3675 +7816 3675 3933 3821 +7817 3821 3961 3675 +7818 3675 3961 3904 +7819 3675 3936 3933 +7820 3782 3898 3676 +7821 3676 3934 3782 +7822 3676 3898 3804 +7823 3804 3905 3676 +7824 3820 3934 3676 +7825 3676 3960 3820 +7826 3905 3960 3676 +7827 3788 3911 3677 +7828 3677 3972 3788 +7829 3677 3952 3856 +7830 3856 3972 3677 +7831 3911 3937 3677 +7832 3937 3952 3677 +7833 3787 3875 3678 +7834 3678 3900 3787 +7835 3805 3866 3678 +7836 3678 3899 3805 +7837 3866 3900 3678 +7838 3875 3899 3678 +7839 3765 3892 3679 +7840 3679 3902 3765 +7841 3679 3962 3816 +7842 3816 3983 3679 +7843 3892 3930 3679 +7844 3679 3983 3902 +7845 3930 3962 3679 +7846 3680 3840 3774 +7847 3774 4001 3680 +7848 3824 3867 3680 +7849 3680 4001 3824 +7850 3680 3920 3840 +7851 3867 3920 3680 +7852 3681 3915 3817 +7853 3817 4009 3681 +7854 3841 3915 3681 +7855 3681 3963 3841 +7856 3857 3963 3681 +7857 3681 4009 3857 +7858 3776 3847 3682 +7859 3682 3858 3776 +7860 3682 3928 3839 +7861 3839 3964 3682 +7862 3847 3928 3682 +7863 3682 3964 3858 +7864 3822 3901 3683 +7865 3683 4002 3822 +7866 3837 3877 3683 +7867 3683 3901 3837 +7868 3877 4002 3683 +7869 3750 3853 3684 +7870 3684 3860 3750 +7871 3684 3853 3760 +7872 3760 3954 3684 +7873 3684 3954 3846 +7874 3846 4006 3684 +7875 3684 4006 3860 +7876 3827 3851 3685 +7877 3685 3916 3827 +7878 3685 3955 3828 +7879 3828 3996 3685 +7880 3851 3955 3685 +7881 3685 3996 3916 +7882 3686 3876 3757 +7883 3757 3947 3686 +7884 3759 3876 3686 +7885 3686 3878 3759 +7886 3772 3929 3686 +7887 3686 3947 3772 +7888 3686 3929 3878 +7889 3785 3914 3687 +7890 3687 3931 3785 +7891 3687 3910 3818 +7892 3818 3931 3687 +7893 3687 3914 3910 +7894 3688 3896 3771 +7895 3771 3986 3688 +7896 3688 3848 3782 +7897 3782 3896 3688 +7898 3688 3884 3848 +7899 3688 3986 3884 +7900 3769 3845 3689 +7901 3689 3872 3769 +7902 3781 3872 3689 +7903 3689 3897 3781 +7904 3845 3968 3689 +7905 3689 3968 3897 +7906 3690 3881 3777 +7907 3777 3984 3690 +7908 3690 3835 3778 +7909 3778 3881 3690 +7910 3690 3957 3835 +7911 3690 3984 3957 +7912 3691 3792 3755 +7913 3755 3943 3691 +7914 3691 3965 3792 +7915 3887 3965 3691 +7916 3691 4005 3887 +7917 3943 4005 3691 +7918 3767 3819 3692 +7919 3692 3953 3767 +7920 3786 3862 3692 +7921 3692 3891 3786 +7922 3692 3819 3788 +7923 3788 3891 3692 +7924 3862 3953 3692 +7925 3693 3880 3825 +7926 3825 3925 3693 +7927 3693 3890 3880 +7928 3693 4007 3890 +7929 3925 4007 3693 +7930 3694 3790 3787 +7931 3787 3900 3694 +7932 3694 3870 3790 +7933 3694 3834 3793 +7934 3793 3982 3694 +7935 3694 3900 3834 +7936 3694 3982 3870 +7937 3695 3829 3766 +7938 3766 3943 3695 +7939 3805 3829 3695 +7940 3695 3967 3805 +7941 3695 3943 3814 +7942 3814 3967 3695 +7943 3696 3816 3761 +7944 3761 3894 3696 +7945 3696 3803 3800 +7946 3800 3940 3696 +7947 3696 3894 3803 +7948 3696 3940 3816 +7949 3754 3824 3697 +7950 3697 3883 3754 +7951 3801 3804 3697 +7952 3697 3919 3801 +7953 3804 3898 3697 +7954 3824 3919 3697 +7955 3697 3898 3883 +7956 3698 3865 3802 +7957 3802 3985 3698 +7958 3822 3859 3698 +7959 3698 3985 3822 +7960 3859 3988 3698 +7961 3698 3988 3865 +7962 3699 3810 3772 +7963 3772 3947 3699 +7964 3699 3980 3773 +7965 3773 4007 3699 +7966 3774 3840 3699 +7967 3699 4007 3774 +7968 3699 3840 3810 +7969 3947 3980 3699 +7970 3700 3799 3759 +7971 3759 3878 3700 +7972 3700 3878 3765 +7973 3765 3902 3700 +7974 3700 3813 3799 +7975 3700 3902 3813 +7976 3753 3845 3701 +7977 3701 3873 3753 +7978 3812 3873 3701 +7979 3701 4003 3812 +7980 3701 3939 3837 +7981 3837 4003 3701 +7982 3845 3939 3701 +7983 3702 3797 3794 +7984 3794 3992 3702 +7985 3702 3997 3797 +7986 3807 3935 3702 +7987 3702 3992 3807 +7988 3702 3935 3809 +7989 3809 3997 3702 +7990 3795 3811 3703 +7991 3703 3993 3795 +7992 3703 3843 3808 +7993 3808 3993 3703 +7994 3811 3977 3703 +7995 3703 3977 3843 +7996 3762 3841 3704 +7997 3704 3903 3762 +7998 3831 3966 3704 +7999 3704 3989 3831 +8000 3841 3989 3704 +8001 3704 3966 3903 +8002 3705 3839 3796 +8003 3796 3956 3705 +8004 3705 3956 3832 +8005 3832 3990 3705 +8006 3705 3990 3839 +8007 3787 3790 3706 +8008 3706 3875 3787 +8009 3790 3842 3706 +8010 3842 3871 3706 +8011 3706 3871 3844 +8012 3844 3875 3706 +8013 3707 3838 3760 +8014 3760 3853 3707 +8015 3707 3853 3798 +8016 3798 3941 3707 +8017 3707 3941 3836 +8018 3836 4008 3707 +8019 3707 4008 3838 +8020 3708 3855 3750 +8021 3750 3860 3708 +8022 3708 3860 3823 +8023 3823 3971 3708 +8024 3708 3998 3855 +8025 3971 3998 3708 +8026 3709 3821 3764 +8027 3764 3850 3709 +8028 3709 3857 3775 +8029 3775 3961 3709 +8030 3779 3857 3709 +8031 3709 3994 3779 +8032 3709 3961 3821 +8033 3850 3994 3709 +8034 3763 3820 3710 +8035 3710 3849 3763 +8036 3776 3858 3710 +8037 3710 3960 3776 +8038 3710 3858 3780 +8039 3780 3995 3710 +8040 3820 3960 3710 +8041 3710 3995 3849 +8042 3762 3854 3711 +8043 3711 3915 3762 +8044 3711 3833 3817 +8045 3817 3915 3711 +8046 3711 4010 3833 +8047 3854 3945 3711 +8048 3945 4010 3711 +8049 3712 3904 3775 +8050 3775 4009 3712 +8051 3800 3803 3712 +8052 3712 3833 3800 +8053 3803 3904 3712 +8054 3817 3833 3712 +8055 3712 4009 3817 +8056 3713 3847 3776 +8057 3776 3905 3713 +8058 3713 3801 3791 +8059 3791 3847 3713 +8060 3713 3804 3801 +8061 3713 3905 3804 +8062 3714 3820 3763 +8063 3763 3864 3714 +8064 3771 3896 3714 +8065 3714 3922 3771 +8066 3714 3934 3820 +8067 3864 3922 3714 +8068 3896 3934 3714 +8069 3764 3821 3715 +8070 3715 3863 3764 +8071 3715 3897 3770 +8072 3770 3921 3715 +8073 3821 3933 3715 +8074 3715 3921 3863 +8075 3715 3933 3897 +8076 3716 3887 3861 +8077 3861 3958 3716 +8078 3876 3882 3716 +8079 3716 3958 3876 +8080 3882 3887 3716 +8081 3784 3846 3717 +8082 3717 3991 3784 +8083 3799 3813 3717 +8084 3717 4000 3799 +8085 3813 3991 3717 +8086 3846 3954 3717 +8087 3954 4000 3717 +8088 3778 3879 3718 +8089 3718 3881 3778 +8090 3815 3856 3718 +8091 3718 3879 3815 +8092 3856 3952 3718 +8093 3718 3952 3881 +8094 3719 3889 3818 +8095 3818 3910 3719 +8096 3877 3889 3719 +8097 3719 4002 3877 +8098 3910 3959 3719 +8099 3959 4002 3719 +8100 3720 3918 3826 +8101 3826 3996 3720 +8102 3828 3920 3720 +8103 3720 3996 3828 +8104 3867 3918 3720 +8105 3720 3920 3867 +8106 3788 3819 3721 +8107 3721 3911 3788 +8108 3819 3869 3721 +8109 3721 3851 3827 +8110 3827 3911 3721 +8111 3721 3869 3851 +8112 3851 3869 3722 +8113 3722 3955 3851 +8114 3869 3938 3722 +8115 3722 3938 3914 +8116 3914 3973 3722 +8117 3722 3973 3955 +8118 3786 3891 3723 +8119 3723 3893 3786 +8120 3723 3856 3815 +8121 3815 3893 3723 +8122 3723 3972 3856 +8123 3891 3972 3723 +8124 3724 3894 3761 +8125 3761 3906 3724 +8126 3724 3872 3781 +8127 3781 3936 3724 +8128 3724 3906 3872 +8129 3724 3936 3894 +8130 3782 3848 3725 +8131 3725 3898 3782 +8132 3848 3895 3725 +8133 3725 3895 3883 +8134 3883 3898 3725 +8135 3726 3847 3791 +8136 3791 3871 3726 +8137 3726 3842 3796 +8138 3796 3928 3726 +8139 3726 3871 3842 +8140 3726 3928 3847 +8141 3727 3806 3777 +8142 3777 3937 3727 +8143 3727 3826 3806 +8144 3727 3916 3826 +8145 3827 3916 3727 +8146 3727 3937 3827 +8147 3728 3868 3783 +8148 3783 3977 3728 +8149 3793 3868 3728 +8150 3728 3982 3793 +8151 3811 3870 3728 +8152 3728 3977 3811 +8153 3870 3982 3728 +8154 3729 3892 3765 +8155 3765 3929 3729 +8156 3729 3929 3772 +8157 3772 3950 3729 +8158 3874 3892 3729 +8159 3729 3950 3874 +8160 3730 3931 3818 +8161 3818 3944 3730 +8162 3930 3931 3730 +8163 3730 3962 3930 +8164 3944 3962 3730 +8165 3834 3900 3731 +8166 3731 3999 3834 +8167 3731 3900 3866 +8168 3866 3909 3731 +8169 3909 3999 3731 +8170 3732 3846 3784 +8171 3784 3945 3732 +8172 3732 3854 3823 +8173 3823 4006 3732 +8174 3732 4006 3846 +8175 3732 3945 3854 +8176 3733 3844 3825 +8177 3825 3880 3733 +8178 3733 3875 3844 +8179 3733 3899 3875 +8180 3880 3899 3733 +8181 3789 3838 3734 +8182 3734 3965 3789 +8183 3734 3932 3792 +8184 3792 3965 3734 +8185 3836 3932 3734 +8186 3734 4008 3836 +8187 3838 4008 3734 +8188 3735 3829 3805 +8189 3805 3899 3735 +8190 3735 3979 3829 +8191 3880 3890 3735 +8192 3735 3899 3880 +8193 3890 3979 3735 +8194 3810 3840 3736 +8195 3736 3927 3810 +8196 3736 3920 3828 +8197 3828 3927 3736 +8198 3840 3920 3736 +8199 3830 3951 3737 +8200 3737 3986 3830 +8201 3737 3951 3835 +8202 3835 3957 3737 +8203 3737 3957 3884 +8204 3884 3986 3737 +8205 3802 3946 3738 +8206 3738 3985 3802 +8207 3738 3901 3822 +8208 3822 3985 3738 +8209 3852 3901 3738 +8210 3738 3946 3852 +8211 3739 3919 3824 +8212 3824 4001 3739 +8213 3739 3925 3825 +8214 3825 3976 3739 +8215 3739 3976 3919 +8216 3739 4001 3925 +8217 3740 3975 3902 +8218 3902 3983 3740 +8219 3940 3975 3740 +8220 3740 3983 3940 +8221 3837 3901 3741 +8222 3741 4003 3837 +8223 3741 3901 3852 +8224 3852 3942 3741 +8225 3942 4003 3741 +8226 3779 3885 3742 +8227 3742 3963 3779 +8228 3841 3963 3742 +8229 3742 3989 3841 +8230 3885 3907 3742 +8231 3907 3989 3742 +8232 3743 3886 3780 +8233 3780 3964 3743 +8234 3743 3964 3839 +8235 3839 3990 3743 +8236 3743 3908 3886 +8237 3743 3990 3908 +8238 3744 3956 3795 +8239 3795 3993 3744 +8240 3744 3923 3832 +8241 3832 3956 3744 +8242 3912 3923 3744 +8243 3744 3993 3912 +8244 3794 3966 3745 +8245 3745 3992 3794 +8246 3831 3924 3745 +8247 3745 3966 3831 +8248 3745 3924 3913 +8249 3913 3992 3745 +8250 3746 3971 3797 +8251 3797 3997 3746 +8252 3917 3926 3746 +8253 3746 3997 3917 +8254 3926 3998 3746 +8255 3746 3998 3971 +8256 3747 3953 3862 +8257 3862 3969 3747 +8258 3747 3969 3865 +8259 3865 3988 3747 +8260 3747 3988 3953 +8261 3748 3877 3837 +8262 3837 3939 3748 +8263 3748 3889 3877 +8264 3748 3978 3889 +8265 3939 3978 3748 +8266 3749 3859 3822 +8267 3822 4002 3749 +8268 3749 3987 3859 +8269 3959 3987 3749 +8270 3749 4002 3959 +8271 3798 3853 3750 +8272 3750 3981 3798 +8273 3855 3981 3750 +8274 3751 3874 3785 +8275 3785 3931 3751 +8276 3751 3892 3874 +8277 3751 3930 3892 +8278 3751 3931 3930 +8279 3806 3970 3752 +8280 3752 3984 3806 +8281 3848 3884 3752 +8282 3752 3970 3848 +8283 3884 3957 3752 +8284 3957 3984 3752 +8285 3753 3968 3845 +8286 3888 3968 3753 +8287 3754 3867 3824 +8288 3754 3918 3867 +8289 3883 3895 3754 +8290 3895 3918 3754 +8291 3792 3948 3755 +8292 3814 3943 3755 +8293 3755 3949 3814 +8294 3948 3949 3755 +8295 3756 3967 3814 +8296 3756 3909 3866 +8297 3866 3967 3756 +8298 3876 3958 3757 +8299 3757 3980 3947 +8300 3758 3927 3828 +8301 3828 3955 3758 +8302 3758 4004 3927 +8303 3955 3973 3758 +8304 3973 4004 3758 +8305 3759 3882 3876 +8306 3838 4000 3760 +8307 3760 4000 3954 +8308 3816 3962 3761 +8309 3761 3962 3944 +8310 3762 3915 3841 +8311 3878 3929 3765 +8312 3861 4005 3766 +8313 3766 4005 3943 +8314 3767 3988 3859 +8315 3953 3988 3767 +8316 3910 3914 3768 +8317 3768 3959 3910 +8318 3914 3938 3768 +8319 3938 3987 3768 +8320 3768 3987 3959 +8321 3769 3939 3845 +8322 3872 3906 3769 +8323 3906 3978 3769 +8324 3769 3978 3939 +8325 3770 3968 3888 +8326 3897 3968 3770 +8327 3771 3974 3830 +8328 3830 3986 3771 +8329 3922 3974 3771 +8330 3810 3950 3772 +8331 3773 3979 3890 +8332 3890 4007 3773 +8333 3925 4001 3774 +8334 3774 4007 3925 +8335 3857 4009 3775 +8336 3904 3961 3775 +8337 3776 3960 3905 +8338 3806 3984 3777 +8339 3881 3952 3777 +8340 3777 3952 3937 +8341 3779 3963 3857 +8342 3858 3964 3780 +8343 3897 3933 3781 +8344 3933 3936 3781 +8345 3782 3934 3896 +8346 3843 3977 3783 +8347 3784 4010 3945 +8348 3991 4010 3784 +8349 3874 4004 3785 +8350 3785 3973 3914 +8351 3785 4004 3973 +8352 3788 3972 3891 +8353 3789 3887 3882 +8354 3789 3965 3887 +8355 3903 3966 3794 +8356 3795 3956 3796 +8357 3839 3928 3796 +8358 3797 3971 3823 +8359 3800 3975 3940 +8360 3919 3976 3801 +8361 3894 3936 3803 +8362 3805 3967 3866 +8363 3807 3992 3913 +8364 3912 3993 3808 +8365 3917 3997 3809 +8366 3812 4003 3942 +8367 3902 3975 3813 +8368 3975 3991 3813 +8369 3940 3983 3816 +8370 3860 4006 3823 +8371 3916 3996 3826 +8372 3827 3937 3911 +8373 3831 3989 3907 +8374 3908 3990 3832 +8375 3848 3970 3895 +8376 3887 4005 3861 +2 20 2 1044 +8377 25 450 4334 +8378 504 25 4334 +8379 463 26 4335 +8380 26 464 4335 +8381 489 27 4333 +8382 27 490 4333 +8383 503 28 4336 +8384 28 529 4336 +8385 450 451 4379 +8386 4334 450 4379 +8387 451 452 4379 +8388 452 453 4275 +8389 4152 452 4275 +8390 452 4152 4379 +8391 453 454 4248 +8392 453 4248 4275 +8393 454 455 4180 +8394 454 4180 4248 +8395 455 456 4412 +8396 4180 455 4412 +8397 456 457 4237 +8398 456 4237 4412 +8399 457 458 4255 +8400 4237 457 4255 +8401 458 459 4174 +8402 458 4174 4255 +8403 459 460 4240 +8404 4174 459 4240 +8405 460 461 4277 +8406 4240 460 4277 +8407 461 462 4380 +8408 461 4154 4277 +8409 4154 461 4380 +8410 462 463 4380 +8411 463 4335 4380 +8412 464 465 4419 +8413 4335 464 4419 +8414 465 466 4183 +8415 465 4183 4419 +8416 466 467 4358 +8417 4183 466 4358 +8418 467 468 4245 +8419 467 4245 4358 +8420 468 469 4185 +8421 468 4185 4245 +8422 469 470 4385 +8423 4185 469 4385 +8424 470 471 4322 +8425 470 4322 4385 +8426 471 472 4225 +8427 4140 471 4225 +8428 471 4140 4322 +8429 472 473 4405 +8430 4225 472 4405 +8431 473 474 4368 +8432 473 4368 4405 +8433 474 475 4198 +8434 474 4198 4368 +8435 475 476 4424 +8436 4198 475 4424 +8437 476 477 4250 +8438 476 4250 4424 +8439 477 478 4306 +8440 4250 477 4306 +8441 478 479 4271 +8442 4157 478 4271 +8443 478 4157 4306 +8444 479 480 4394 +8445 4271 479 4394 +8446 480 481 4192 +8447 480 4192 4394 +8448 481 482 4290 +8449 4192 481 4290 +8450 482 483 4485 +8451 4290 482 4485 +8452 483 484 4386 +8453 4293 483 4386 +8454 483 4293 4485 +8455 484 485 4186 +8456 484 4186 4386 +8457 485 486 4246 +8458 4186 485 4246 +8459 486 487 4359 +8460 4246 486 4359 +8461 487 488 4184 +8462 487 4184 4359 +8463 488 489 4420 +8464 4184 488 4420 +8465 489 4333 4420 +8466 490 491 4378 +8467 4333 490 4378 +8468 491 492 4378 +8469 492 493 4278 +8470 4153 492 4278 +8471 492 4153 4378 +8472 493 494 4247 +8473 493 4247 4278 +8474 494 495 4181 +8475 494 4181 4247 +8476 495 496 4411 +8477 4181 495 4411 +8478 496 497 4238 +8479 496 4238 4411 +8480 497 498 4256 +8481 4238 497 4256 +8482 498 499 4175 +8483 498 4175 4256 +8484 499 500 4241 +8485 4175 499 4241 +8486 500 501 4276 +8487 4241 500 4276 +8488 501 502 4381 +8489 501 4151 4276 +8490 4151 501 4381 +8491 502 503 4381 +8492 503 4336 4381 +8493 505 504 4487 +8494 504 4334 4487 +8495 506 505 4310 +8496 4310 505 4487 +8497 507 506 4304 +8498 506 4144 4304 +8499 4144 506 4310 +8500 508 507 4244 +8501 4244 507 4304 +8502 509 508 4158 +8503 4158 508 4244 +8504 510 509 4320 +8505 509 4158 4320 +8506 511 510 4461 +8507 510 4320 4461 +8508 512 511 4300 +8509 511 4231 4300 +8510 4231 511 4461 +8511 513 512 4429 +8512 4155 512 4300 +8513 512 4155 4429 +8514 514 513 4429 +8515 515 514 4254 +8516 514 4136 4254 +8517 4136 514 4429 +8518 516 515 4204 +8519 4204 515 4254 +8520 517 516 4418 +8521 516 4204 4418 +8522 518 517 4203 +8523 4203 517 4418 +8524 519 518 4253 +8525 518 4203 4253 +8526 520 519 4430 +8527 4135 519 4253 +8528 519 4135 4430 +8529 521 520 4430 +8530 522 521 4301 +8531 521 4156 4301 +8532 4156 521 4430 +8533 523 522 4462 +8534 4232 522 4301 +8535 522 4232 4462 +8536 524 523 4321 +8537 4321 523 4462 +8538 525 524 4159 +8539 4159 524 4321 +8540 526 525 4243 +8541 525 4159 4243 +8542 527 526 4305 +8543 526 4243 4305 +8544 528 527 4309 +8545 4145 527 4305 +8546 527 4145 4309 +8547 529 528 4486 +8548 528 4309 4486 +8549 4336 529 4486 +8550 4149 4011 4362 +8551 4011 4149 4457 +8552 4011 4162 4331 +8553 4162 4011 4457 +8554 4011 4213 4362 +8555 4213 4011 4435 +8556 4011 4331 4435 +8557 4012 4150 4345 +8558 4150 4012 4458 +8559 4163 4012 4332 +8560 4012 4163 4458 +8561 4216 4012 4345 +8562 4012 4216 4433 +8563 4332 4012 4433 +8564 4013 4206 4285 +8565 4206 4013 4406 +8566 4214 4013 4261 +8567 4013 4214 4406 +8568 4261 4013 4349 +8569 4013 4285 4349 +8570 4014 4164 4436 +8571 4164 4014 4490 +8572 4014 4182 4299 +8573 4182 4014 4436 +8574 4272 4014 4299 +8575 4014 4272 4410 +8576 4014 4410 4490 +8577 4015 4176 4220 +8578 4176 4015 4239 +8579 4015 4220 4289 +8580 4239 4015 4483 +8581 4015 4289 4401 +8582 4015 4401 4483 +8583 4016 4199 4279 +8584 4199 4016 4360 +8585 4016 4266 4360 +8586 4266 4016 4477 +8587 4016 4279 4477 +8588 4194 4017 4344 +8589 4017 4194 4365 +8590 4344 4017 4488 +8591 4356 4017 4365 +8592 4017 4356 4488 +8593 4018 4195 4343 +8594 4195 4018 4366 +8595 4018 4343 4489 +8596 4018 4355 4366 +8597 4355 4018 4489 +8598 4200 4019 4280 +8599 4019 4200 4361 +8600 4265 4019 4361 +8601 4019 4265 4476 +8602 4280 4019 4476 +8603 4146 4020 4251 +8604 4020 4146 4273 +8605 4020 4209 4251 +8606 4209 4020 4415 +8607 4222 4020 4273 +8608 4020 4222 4415 +8609 4021 4202 4398 +8610 4202 4021 4416 +8611 4021 4207 4298 +8612 4207 4021 4398 +8613 4208 4021 4298 +8614 4021 4208 4416 +8615 4160 4022 4210 +8616 4022 4160 4323 +8617 4165 4022 4268 +8618 4022 4165 4404 +8619 4022 4167 4268 +8620 4167 4022 4323 +8621 4210 4022 4404 +8622 4023 4161 4211 +8623 4161 4023 4324 +8624 4023 4166 4269 +8625 4166 4023 4403 +8626 4168 4023 4269 +8627 4023 4168 4324 +8628 4023 4211 4403 +8629 4172 4024 4227 +8630 4024 4172 4342 +8631 4024 4187 4287 +8632 4187 4024 4342 +8633 4024 4189 4227 +8634 4189 4024 4287 +8635 4025 4171 4226 +8636 4171 4025 4341 +8637 4025 4188 4286 +8638 4188 4025 4482 +8639 4190 4025 4286 +8640 4025 4190 4341 +8641 4025 4226 4482 +8642 4026 4205 4259 +8643 4205 4026 4469 +8644 4221 4026 4339 +8645 4026 4221 4469 +8646 4026 4259 4414 +8647 4339 4026 4414 +8648 4201 4027 4337 +8649 4027 4201 4364 +8650 4212 4027 4466 +8651 4027 4212 4475 +8652 4337 4027 4348 +8653 4348 4027 4475 +8654 4027 4364 4466 +8655 4191 4028 4274 +8656 4028 4191 4288 +8657 4028 4217 4311 +8658 4217 4028 4450 +8659 4274 4028 4311 +8660 4028 4288 4450 +8661 4170 4029 4236 +8662 4029 4170 4347 +8663 4029 4196 4377 +8664 4196 4029 4423 +8665 4236 4029 4377 +8666 4029 4347 4423 +8667 4030 4169 4258 +8668 4169 4030 4346 +8669 4197 4030 4374 +8670 4030 4197 4425 +8671 4030 4258 4374 +8672 4346 4030 4425 +8673 4031 4193 4252 +8674 4193 4031 4455 +8675 4233 4031 4252 +8676 4031 4233 4402 +8677 4031 4264 4318 +8678 4264 4031 4402 +8679 4031 4318 4455 +8680 4032 4173 4242 +8681 4173 4032 4270 +8682 4032 4235 4270 +8683 4235 4032 4382 +8684 4032 4242 4294 +8685 4032 4294 4382 +8686 4033 4152 4326 +8687 4152 4033 4373 +8688 4033 4224 4313 +8689 4224 4033 4326 +8690 4033 4313 4373 +8691 4154 4034 4327 +8692 4034 4154 4397 +8693 4327 4034 4426 +8694 4387 4034 4397 +8695 4034 4387 4426 +8696 4035 4153 4328 +8697 4153 4035 4396 +8698 4035 4328 4427 +8699 4035 4388 4396 +8700 4388 4035 4427 +8701 4151 4036 4325 +8702 4036 4151 4372 +8703 4223 4036 4312 +8704 4036 4223 4325 +8705 4312 4036 4372 +8706 4037 4157 4350 +8707 4157 4037 4491 +8708 4260 4037 4471 +8709 4037 4260 4491 +8710 4037 4350 4473 +8711 4471 4037 4474 +8712 4037 4473 4474 +8713 4038 4164 4215 +8714 4164 4038 4367 +8715 4038 4215 4456 +8716 4038 4291 4367 +8717 4291 4038 4437 +8718 4437 4038 4456 +8719 4039 4168 4292 +8720 4168 4039 4351 +8721 4257 4039 4438 +8722 4039 4257 4454 +8723 4039 4292 4438 +8724 4351 4039 4454 +8725 4165 4040 4307 +8726 4040 4165 4408 +8727 4297 4040 4408 +8728 4040 4297 4440 +8729 4307 4040 4440 +8730 4041 4166 4308 +8731 4166 4041 4409 +8732 4041 4296 4409 +8733 4296 4041 4441 +8734 4041 4308 4441 +8735 4042 4149 4357 +8736 4149 4042 4421 +8737 4160 4042 4329 +8738 4042 4160 4421 +8739 4249 4042 4357 +8740 4042 4249 4460 +8741 4329 4042 4460 +8742 4043 4150 4422 +8743 4150 4043 4445 +8744 4043 4161 4330 +8745 4161 4043 4422 +8746 4176 4043 4330 +8747 4043 4176 4447 +8748 4043 4295 4445 +8749 4295 4043 4447 +8750 4044 4148 4303 +8751 4148 4044 4399 +8752 4178 4044 4234 +8753 4044 4178 4399 +8754 4234 4044 4428 +8755 4044 4303 4428 +8756 4147 4045 4302 +8757 4045 4147 4400 +8758 4045 4177 4230 +8759 4177 4045 4400 +8760 4045 4230 4434 +8761 4302 4045 4434 +8762 4046 4172 4218 +8763 4172 4046 4352 +8764 4046 4218 4479 +8765 4046 4263 4452 +8766 4263 4046 4479 +8767 4352 4046 4452 +8768 4171 4047 4219 +8769 4047 4171 4353 +8770 4219 4047 4478 +8771 4262 4047 4453 +8772 4047 4262 4478 +8773 4047 4353 4453 +8774 4174 4048 4314 +8775 4048 4174 4376 +8776 4048 4189 4314 +8777 4189 4048 4444 +8778 4229 4048 4284 +8779 4048 4229 4444 +8780 4284 4048 4376 +8781 4049 4187 4369 +8782 4187 4049 4448 +8783 4049 4199 4281 +8784 4199 4049 4369 +8785 4049 4281 4391 +8786 4049 4391 4448 +8787 4050 4188 4417 +8788 4188 4050 4449 +8789 4050 4228 4282 +8790 4228 4050 4417 +8791 4050 4282 4390 +8792 4050 4390 4449 +8793 4175 4051 4315 +8794 4051 4175 4375 +8795 4051 4190 4315 +8796 4190 4051 4407 +8797 4200 4051 4283 +8798 4051 4200 4407 +8799 4283 4051 4375 +8800 4138 4052 4194 +8801 4052 4138 4392 +8802 4194 4052 4196 +8803 4196 4052 4383 +8804 4383 4052 4467 +8805 4052 4392 4467 +8806 4053 4139 4195 +8807 4139 4053 4393 +8808 4053 4195 4197 +8809 4053 4197 4384 +8810 4053 4384 4468 +8811 4393 4053 4468 +8812 4054 4146 4395 +8813 4146 4054 4459 +8814 4205 4054 4446 +8815 4054 4205 4459 +8816 4054 4395 4484 +8817 4446 4054 4484 +8818 4055 4179 4202 +8819 4179 4055 4439 +8820 4055 4202 4267 +8821 4206 4055 4267 +8822 4055 4206 4338 +8823 4055 4338 4439 +8824 4056 4169 4207 +8825 4169 4056 4258 +8826 4192 4056 4319 +8827 4056 4192 4451 +8828 4056 4207 4319 +8829 4258 4056 4451 +8830 4057 4214 4354 +8831 4214 4057 4389 +8832 4057 4221 4389 +8833 4221 4057 4470 +8834 4222 4057 4354 +8835 4057 4222 4470 +8836 4058 4134 4216 +8837 4134 4058 4340 +8838 4058 4208 4340 +8839 4208 4058 4371 +8840 4058 4216 4217 +8841 4058 4217 4371 +8842 4137 4059 4213 +8843 4059 4137 4363 +8844 4209 4059 4363 +8845 4059 4209 4370 +8846 4059 4212 4213 +8847 4212 4059 4370 +8848 4060 4140 4225 +8849 4140 4060 4236 +8850 4141 4060 4225 +8851 4060 4141 4395 +8852 4060 4170 4236 +8853 4170 4060 4413 +8854 4060 4395 4413 +8855 4061 4160 4210 +8856 4160 4061 4421 +8857 4061 4210 4316 +8858 4263 4061 4316 +8859 4061 4263 4457 +8860 4421 4061 4457 +8861 4161 4062 4211 +8862 4062 4161 4422 +8863 4211 4062 4317 +8864 4062 4262 4317 +8865 4262 4062 4458 +8866 4062 4422 4458 +8867 4148 4063 4303 +8868 4063 4148 4443 +8869 4063 4171 4219 +8870 4171 4063 4226 +8871 4063 4219 4303 +8872 4226 4063 4443 +8873 4064 4147 4302 +8874 4147 4064 4442 +8875 4172 4064 4218 +8876 4064 4172 4227 +8877 4218 4064 4302 +8878 4064 4227 4442 +8879 4065 4135 4253 +8880 4135 4065 4257 +8881 4193 4065 4252 +8882 4065 4193 4465 +8883 4065 4203 4252 +8884 4203 4065 4253 +8885 4257 4065 4465 +8886 4204 4066 4233 +8887 4066 4204 4254 +8888 4066 4215 4402 +8889 4215 4066 4456 +8890 4233 4066 4402 +8891 4066 4254 4456 +8892 4155 4067 4291 +8893 4067 4155 4300 +8894 4167 4067 4268 +8895 4067 4167 4291 +8896 4231 4067 4300 +8897 4067 4231 4431 +8898 4268 4067 4431 +8899 4068 4156 4292 +8900 4156 4068 4301 +8901 4068 4168 4269 +8902 4168 4068 4292 +8903 4068 4232 4301 +8904 4232 4068 4432 +8905 4068 4269 4432 +8906 4069 4201 4337 +8907 4201 4069 4382 +8908 4235 4069 4349 +8909 4069 4235 4382 +8910 4261 4069 4337 +8911 4069 4261 4349 +8912 4070 4191 4274 +8913 4191 4070 4472 +8914 4239 4070 4274 +8915 4070 4239 4483 +8916 4070 4270 4472 +8917 4270 4070 4483 +8918 4144 4071 4304 +8919 4071 4144 4313 +8920 4244 4071 4297 +8921 4071 4244 4304 +8922 4297 4071 4480 +8923 4071 4313 4480 +8924 4072 4145 4305 +8925 4145 4072 4312 +8926 4072 4243 4296 +8927 4243 4072 4305 +8928 4072 4296 4481 +8929 4312 4072 4481 +8930 4169 4073 4298 +8931 4073 4169 4346 +8932 4073 4178 4234 +8933 4178 4073 4346 +8934 4073 4208 4298 +8935 4208 4073 4340 +8936 4073 4234 4340 +8937 4074 4170 4251 +8938 4170 4074 4347 +8939 4177 4074 4230 +8940 4074 4177 4347 +8941 4209 4074 4251 +8942 4074 4209 4363 +8943 4230 4074 4363 +8944 4250 4075 4259 +8945 4075 4250 4306 +8946 4259 4075 4414 +8947 4075 4260 4414 +8948 4260 4075 4491 +8949 4075 4306 4491 +8950 4242 4076 4294 +8951 4076 4242 4318 +8952 4264 4076 4318 +8953 4076 4264 4410 +8954 4076 4272 4294 +8955 4272 4076 4410 +8956 4143 4077 4317 +8957 4077 4143 4476 +8958 4077 4211 4317 +8959 4211 4077 4403 +8960 4077 4265 4308 +8961 4265 4077 4476 +8962 4077 4308 4403 +8963 4078 4142 4316 +8964 4142 4078 4477 +8965 4210 4078 4316 +8966 4078 4210 4404 +8967 4266 4078 4307 +8968 4078 4266 4477 +8969 4307 4078 4404 +8970 4079 4189 4287 +8971 4189 4079 4314 +8972 4079 4237 4255 +8973 4237 4079 4463 +8974 4079 4255 4314 +8975 4079 4287 4463 +8976 4080 4190 4286 +8977 4190 4080 4315 +8978 4080 4238 4256 +8979 4238 4080 4464 +8980 4080 4256 4315 +8981 4080 4286 4464 +8982 4081 4167 4323 +8983 4167 4081 4367 +8984 4182 4081 4329 +8985 4081 4182 4436 +8986 4081 4323 4329 +8987 4367 4081 4436 +8988 4168 4082 4324 +8989 4082 4168 4351 +8990 4176 4082 4220 +8991 4082 4176 4330 +8992 4220 4082 4351 +8993 4324 4082 4330 +8994 4190 4083 4341 +8995 4083 4190 4407 +8996 4083 4200 4280 +8997 4200 4083 4407 +8998 4083 4280 4353 +8999 4341 4083 4353 +9000 4199 4084 4279 +9001 4084 4199 4369 +9002 4279 4084 4352 +9003 4084 4342 4352 +9004 4342 4084 4369 +9005 4085 4152 4275 +9006 4152 4085 4326 +9007 4248 4085 4275 +9008 4085 4248 4391 +9009 4085 4281 4326 +9010 4281 4085 4391 +9011 4086 4153 4278 +9012 4153 4086 4328 +9013 4247 4086 4278 +9014 4086 4247 4390 +9015 4086 4282 4328 +9016 4282 4086 4390 +9017 4151 4087 4276 +9018 4087 4151 4325 +9019 4087 4241 4276 +9020 4241 4087 4375 +9021 4283 4087 4325 +9022 4087 4283 4375 +9023 4154 4088 4277 +9024 4088 4154 4327 +9025 4088 4240 4277 +9026 4240 4088 4376 +9027 4284 4088 4327 +9028 4088 4284 4376 +9029 4089 4191 4285 +9030 4191 4089 4288 +9031 4089 4206 4267 +9032 4206 4089 4285 +9033 4089 4267 4288 +9034 4140 4090 4322 +9035 4090 4140 4377 +9036 4185 4090 4383 +9037 4090 4185 4385 +9038 4322 4090 4385 +9039 4090 4377 4383 +9040 4091 4186 4384 +9041 4186 4091 4386 +9042 4293 4091 4374 +9043 4091 4293 4386 +9044 4374 4091 4384 +9045 4216 4092 4217 +9046 4092 4216 4345 +9047 4217 4092 4311 +9048 4092 4295 4311 +9049 4295 4092 4445 +9050 4092 4345 4445 +9051 4182 4093 4299 +9052 4093 4182 4460 +9053 4093 4201 4299 +9054 4201 4093 4364 +9055 4093 4249 4364 +9056 4249 4093 4460 +9057 4212 4094 4213 +9058 4094 4212 4466 +9059 4213 4094 4362 +9060 4094 4249 4357 +9061 4249 4094 4466 +9062 4094 4357 4362 +9063 4095 4192 4319 +9064 4192 4095 4394 +9065 4271 4095 4350 +9066 4095 4271 4394 +9067 4095 4319 4473 +9068 4350 4095 4473 +9069 4206 4096 4338 +9070 4096 4206 4406 +9071 4096 4221 4339 +9072 4221 4096 4389 +9073 4338 4096 4339 +9074 4389 4096 4406 +9075 4097 4222 4354 +9076 4222 4097 4415 +9077 4348 4097 4354 +9078 4097 4348 4475 +9079 4097 4370 4415 +9080 4370 4097 4475 +9081 4202 4098 4267 +9082 4098 4202 4416 +9083 4267 4098 4288 +9084 4288 4098 4450 +9085 4371 4098 4416 +9086 4098 4371 4450 +9087 4173 4099 4242 +9088 4099 4173 4401 +9089 4242 4099 4318 +9090 4289 4099 4401 +9091 4099 4289 4455 +9092 4318 4099 4455 +9093 4100 4194 4196 +9094 4194 4100 4365 +9095 4100 4196 4423 +9096 4365 4100 4400 +9097 4400 4100 4423 +9098 4178 4101 4399 +9099 4101 4178 4425 +9100 4195 4101 4197 +9101 4101 4195 4366 +9102 4197 4101 4425 +9103 4101 4366 4399 +9104 4102 4183 4358 +9105 4183 4102 4387 +9106 4245 4102 4358 +9107 4102 4245 4467 +9108 4387 4102 4392 +9109 4392 4102 4467 +9110 4184 4103 4359 +9111 4103 4184 4388 +9112 4103 4246 4359 +9113 4246 4103 4468 +9114 4103 4388 4393 +9115 4103 4393 4468 +9116 4104 4152 4373 +9117 4152 4104 4379 +9118 4310 4104 4373 +9119 4104 4310 4487 +9120 4104 4334 4379 +9121 4334 4104 4487 +9122 4105 4154 4380 +9123 4154 4105 4397 +9124 4335 4105 4380 +9125 4105 4335 4419 +9126 4397 4105 4419 +9127 4153 4106 4378 +9128 4106 4153 4396 +9129 4106 4333 4378 +9130 4333 4106 4420 +9131 4106 4396 4420 +9132 4151 4107 4372 +9133 4107 4151 4381 +9134 4107 4309 4372 +9135 4309 4107 4486 +9136 4336 4107 4381 +9137 4107 4336 4486 +9138 4108 4198 4424 +9139 4198 4108 4446 +9140 4205 4108 4259 +9141 4108 4205 4446 +9142 4108 4250 4259 +9143 4250 4108 4424 +9144 4189 4109 4227 +9145 4109 4189 4444 +9146 4227 4109 4442 +9147 4109 4229 4356 +9148 4229 4109 4444 +9149 4109 4356 4442 +9150 4110 4226 4443 +9151 4226 4110 4482 +9152 4228 4110 4355 +9153 4110 4228 4417 +9154 4355 4110 4443 +9155 4110 4417 4482 +9156 4203 4111 4252 +9157 4111 4203 4418 +9158 4111 4204 4233 +9159 4204 4111 4418 +9160 4111 4233 4252 +9161 4191 4112 4285 +9162 4112 4191 4472 +9163 4235 4112 4270 +9164 4112 4235 4349 +9165 4270 4112 4472 +9166 4285 4112 4349 +9167 4201 4113 4299 +9168 4113 4201 4382 +9169 4272 4113 4294 +9170 4113 4272 4299 +9171 4294 4113 4382 +9172 4165 4114 4408 +9173 4114 4165 4431 +9174 4231 4114 4431 +9175 4114 4231 4461 +9176 4114 4320 4408 +9177 4320 4114 4461 +9178 4115 4166 4409 +9179 4166 4115 4432 +9180 4115 4232 4432 +9181 4232 4115 4462 +9182 4321 4115 4409 +9183 4115 4321 4462 +9184 4116 4181 4411 +9185 4181 4116 4449 +9186 4116 4188 4449 +9187 4188 4116 4464 +9188 4238 4116 4411 +9189 4116 4238 4464 +9190 4117 4180 4412 +9191 4180 4117 4448 +9192 4117 4187 4448 +9193 4187 4117 4463 +9194 4237 4117 4412 +9195 4117 4237 4463 +9196 4118 4239 4274 +9197 4239 4118 4447 +9198 4118 4274 4311 +9199 4295 4118 4311 +9200 4118 4295 4447 +9201 4205 4119 4459 +9202 4119 4205 4469 +9203 4119 4222 4273 +9204 4222 4119 4470 +9205 4119 4273 4459 +9206 4119 4469 4470 +9207 4215 4120 4402 +9208 4120 4215 4490 +9209 4120 4264 4402 +9210 4264 4120 4410 +9211 4410 4120 4490 +9212 4121 4193 4289 +9213 4193 4121 4465 +9214 4220 4121 4289 +9215 4121 4220 4454 +9216 4257 4121 4454 +9217 4121 4257 4465 +9218 4122 4229 4284 +9219 4229 4122 4488 +9220 4122 4284 4327 +9221 4122 4327 4426 +9222 4344 4122 4426 +9223 4122 4344 4488 +9224 4123 4200 4283 +9225 4200 4123 4361 +9226 4223 4123 4325 +9227 4123 4223 4361 +9228 4123 4283 4325 +9229 4199 4124 4281 +9230 4124 4199 4360 +9231 4124 4224 4326 +9232 4224 4124 4360 +9233 4281 4124 4326 +9234 4228 4125 4282 +9235 4125 4228 4489 +9236 4282 4125 4328 +9237 4328 4125 4427 +9238 4125 4343 4427 +9239 4343 4125 4489 +9240 4258 4126 4374 +9241 4126 4258 4451 +9242 4290 4126 4451 +9243 4126 4290 4485 +9244 4126 4293 4374 +9245 4293 4126 4485 +9246 4260 4127 4414 +9247 4127 4260 4471 +9248 4127 4338 4339 +9249 4338 4127 4439 +9250 4127 4339 4414 +9251 4439 4127 4471 +9252 4128 4214 4261 +9253 4214 4128 4354 +9254 4128 4261 4337 +9255 4128 4337 4348 +9256 4128 4348 4354 +9257 4207 4129 4319 +9258 4129 4207 4398 +9259 4319 4129 4473 +9260 4129 4398 4474 +9261 4473 4129 4474 +9262 4130 4218 4302 +9263 4218 4130 4331 +9264 4130 4302 4434 +9265 4331 4130 4435 +9266 4130 4434 4435 +9267 4219 4131 4303 +9268 4131 4219 4332 +9269 4303 4131 4428 +9270 4131 4332 4433 +9271 4428 4131 4433 +9272 4132 4224 4360 +9273 4224 4132 4480 +9274 4266 4132 4360 +9275 4132 4266 4440 +9276 4297 4132 4440 +9277 4132 4297 4480 +9278 4223 4133 4361 +9279 4133 4223 4481 +9280 4133 4265 4361 +9281 4265 4133 4441 +9282 4133 4296 4441 +9283 4296 4133 4481 +9284 4216 4134 4433 +9285 4234 4134 4340 +9286 4134 4234 4428 +9287 4134 4428 4433 +9288 4135 4257 4438 +9289 4430 4135 4438 +9290 4254 4136 4456 +9291 4136 4429 4437 +9292 4136 4437 4456 +9293 4137 4213 4435 +9294 4137 4230 4363 +9295 4230 4137 4434 +9296 4434 4137 4435 +9297 4138 4194 4344 +9298 4138 4344 4426 +9299 4138 4387 4392 +9300 4387 4138 4426 +9301 4195 4139 4343 +9302 4343 4139 4427 +9303 4388 4139 4393 +9304 4139 4388 4427 +9305 4140 4236 4377 +9306 4141 4225 4405 +9307 4368 4141 4405 +9308 4141 4368 4484 +9309 4395 4141 4484 +9310 4142 4263 4316 +9311 4263 4142 4452 +9312 4142 4279 4452 +9313 4279 4142 4477 +9314 4262 4143 4317 +9315 4143 4262 4453 +9316 4280 4143 4453 +9317 4143 4280 4476 +9318 4144 4310 4373 +9319 4313 4144 4373 +9320 4309 4145 4372 +9321 4145 4312 4372 +9322 4146 4251 4413 +9323 4273 4146 4459 +9324 4395 4146 4413 +9325 4147 4356 4365 +9326 4356 4147 4442 +9327 4147 4365 4400 +9328 4355 4148 4366 +9329 4148 4355 4443 +9330 4366 4148 4399 +9331 4357 4149 4362 +9332 4149 4421 4457 +9333 4345 4150 4445 +9334 4422 4150 4458 +9335 4155 4291 4437 +9336 4429 4155 4437 +9337 4292 4156 4438 +9338 4156 4430 4438 +9339 4157 4271 4350 +9340 4306 4157 4491 +9341 4158 4244 4297 +9342 4158 4297 4408 +9343 4320 4158 4408 +9344 4243 4159 4296 +9345 4296 4159 4409 +9346 4159 4321 4409 +9347 4323 4160 4329 +9348 4161 4324 4330 +9349 4263 4162 4457 +9350 4162 4263 4479 +9351 4331 4162 4479 +9352 4163 4262 4458 +9353 4262 4163 4478 +9354 4163 4332 4478 +9355 4215 4164 4490 +9356 4164 4367 4436 +9357 4165 4268 4431 +9358 4165 4307 4404 +9359 4269 4166 4432 +9360 4308 4166 4403 +9361 4291 4167 4367 +9362 4207 4169 4298 +9363 4251 4170 4413 +9364 4171 4341 4353 +9365 4342 4172 4352 +9366 4173 4270 4483 +9367 4401 4173 4483 +9368 4174 4240 4376 +9369 4255 4174 4314 +9370 4175 4241 4375 +9371 4256 4175 4315 +9372 4176 4239 4447 +9373 4347 4177 4423 +9374 4177 4400 4423 +9375 4178 4346 4425 +9376 4202 4179 4398 +9377 4398 4179 4474 +9378 4179 4439 4471 +9379 4179 4471 4474 +9380 4248 4180 4391 +9381 4391 4180 4448 +9382 4247 4181 4390 +9383 4390 4181 4449 +9384 4182 4329 4460 +9385 4183 4387 4397 +9386 4183 4397 4419 +9387 4388 4184 4396 +9388 4396 4184 4420 +9389 4245 4185 4467 +9390 4185 4383 4467 +9391 4186 4246 4468 +9392 4384 4186 4468 +9393 4287 4187 4463 +9394 4187 4342 4369 +9395 4286 4188 4464 +9396 4417 4188 4482 +9397 4192 4290 4451 +9398 4289 4193 4455 +9399 4377 4196 4383 +9400 4197 4374 4384 +9401 4368 4198 4484 +9402 4198 4446 4484 +9403 4208 4371 4416 +9404 4370 4209 4415 +9405 4212 4370 4475 +9406 4214 4389 4406 +9407 4371 4217 4450 +9408 4218 4331 4479 +9409 4332 4219 4478 +9410 4220 4351 4454 +9411 4469 4221 4470 +9412 4223 4312 4481 +9413 4313 4224 4480 +9414 4228 4355 4489 +9415 4356 4229 4488 +9416 4364 4249 4466 +9417 4308 4265 4441 +9418 4266 4307 4440 +9419 4279 4352 4452 +9420 4353 4280 4453 +2 21 2 200 +9421 464 26 4535 +9422 26 530 4535 +9423 27 489 4537 +9424 559 27 4537 +9425 531 29 4538 +9426 29 532 4538 +9427 557 30 4536 +9428 30 558 4536 +9429 465 464 4542 +9430 464 4535 4542 +9431 466 465 4507 +9432 4507 465 4542 +9433 467 466 4556 +9434 466 4507 4556 +9435 468 467 4531 +9436 4531 467 4556 +9437 469 468 4519 +9438 468 4504 4519 +9439 4504 468 4531 +9440 470 469 4547 +9441 469 4519 4547 +9442 471 470 4514 +9443 4514 470 4547 +9444 472 471 4544 +9445 471 4514 4544 +9446 473 472 4512 +9447 4512 472 4544 +9448 474 473 4558 +9449 473 4512 4558 +9450 475 474 4528 +9451 4528 474 4558 +9452 476 475 4518 +9453 475 4503 4518 +9454 4503 475 4528 +9455 477 476 4545 +9456 476 4518 4545 +9457 478 477 4510 +9458 4510 477 4545 +9459 479 478 4553 +9460 478 4510 4553 +9461 480 479 4529 +9462 4529 479 4553 +9463 481 480 4520 +9464 480 4505 4520 +9465 4505 480 4529 +9466 482 481 4549 +9467 481 4520 4549 +9468 483 482 4509 +9469 4509 482 4549 +9470 484 483 4552 +9471 483 4509 4552 +9472 485 484 4522 +9473 4522 484 4552 +9474 486 485 4533 +9475 4506 485 4522 +9476 485 4506 4533 +9477 487 486 4560 +9478 486 4533 4560 +9479 488 487 4526 +9480 4526 487 4560 +9481 489 488 4540 +9482 488 4526 4540 +9483 4537 489 4540 +9484 530 531 4562 +9485 4535 530 4562 +9486 531 4538 4562 +9487 532 533 4541 +9488 4538 532 4541 +9489 533 534 4525 +9490 533 4525 4541 +9491 534 535 4555 +9492 4525 534 4555 +9493 535 536 4532 +9494 535 4532 4555 +9495 536 537 4523 +9496 4504 536 4523 +9497 536 4504 4532 +9498 537 538 4548 +9499 4523 537 4548 +9500 538 539 4511 +9501 538 4511 4548 +9502 539 540 4543 +9503 4511 539 4543 +9504 540 541 4513 +9505 540 4513 4543 +9506 541 542 4557 +9507 4513 541 4557 +9508 542 543 4527 +9509 542 4527 4557 +9510 543 544 4521 +9511 4503 543 4521 +9512 543 4503 4527 +9513 544 545 4546 +9514 4521 544 4546 +9515 545 546 4515 +9516 545 4515 4546 +9517 546 547 4554 +9518 4515 546 4554 +9519 547 548 4530 +9520 547 4530 4554 +9521 548 549 4524 +9522 4505 548 4524 +9523 548 4505 4530 +9524 549 550 4550 +9525 4524 549 4550 +9526 550 551 4516 +9527 550 4516 4550 +9528 551 552 4551 +9529 4516 551 4551 +9530 552 553 4517 +9531 552 4517 4551 +9532 553 554 4534 +9533 553 4506 4517 +9534 4506 553 4534 +9535 554 555 4559 +9536 4534 554 4559 +9537 555 556 4508 +9538 555 4508 4559 +9539 556 557 4539 +9540 4508 556 4539 +9541 557 4536 4539 +9542 558 559 4561 +9543 4536 558 4561 +9544 559 4537 4561 +9545 4507 4492 4541 +9546 4492 4507 4542 +9547 4535 4492 4542 +9548 4492 4535 4562 +9549 4492 4538 4541 +9550 4538 4492 4562 +9551 4493 4508 4539 +9552 4508 4493 4540 +9553 4536 4493 4539 +9554 4493 4536 4561 +9555 4493 4537 4540 +9556 4537 4493 4561 +9557 4494 4512 4513 +9558 4512 4494 4558 +9559 4494 4513 4557 +9560 4494 4527 4528 +9561 4527 4494 4557 +9562 4494 4528 4558 +9563 4511 4495 4514 +9564 4495 4511 4543 +9565 4512 4495 4513 +9566 4495 4512 4544 +9567 4513 4495 4543 +9568 4514 4495 4544 +9569 4510 4496 4515 +9570 4496 4510 4545 +9571 4515 4496 4546 +9572 4496 4518 4521 +9573 4518 4496 4545 +9574 4496 4521 4546 +9575 4497 4510 4515 +9576 4510 4497 4553 +9577 4497 4515 4554 +9578 4529 4497 4530 +9579 4497 4529 4553 +9580 4530 4497 4554 +9581 4498 4507 4525 +9582 4507 4498 4556 +9583 4498 4525 4555 +9584 4531 4498 4532 +9585 4498 4531 4556 +9586 4532 4498 4555 +9587 4499 4508 4526 +9588 4508 4499 4559 +9589 4499 4526 4560 +9590 4499 4533 4534 +9591 4533 4499 4560 +9592 4499 4534 4559 +9593 4500 4511 4514 +9594 4511 4500 4548 +9595 4500 4514 4547 +9596 4500 4519 4523 +9597 4519 4500 4547 +9598 4500 4523 4548 +9599 4509 4501 4516 +9600 4501 4509 4549 +9601 4516 4501 4550 +9602 4501 4520 4524 +9603 4520 4501 4549 +9604 4501 4524 4550 +9605 4502 4509 4516 +9606 4509 4502 4552 +9607 4502 4516 4551 +9608 4502 4517 4522 +9609 4517 4502 4551 +9610 4502 4522 4552 +9611 4518 4503 4521 +9612 4527 4503 4528 +9613 4519 4504 4523 +9614 4504 4531 4532 +9615 4520 4505 4524 +9616 4505 4529 4530 +9617 4517 4506 4522 +9618 4533 4506 4534 +9619 4525 4507 4541 +9620 4526 4508 4540 +2 22 2 1708 +9621 4734 532 29 +9622 609 4734 29 +9623 30 557 4733 +9624 30 4733 582 +9625 560 4732 31 +9626 4732 608 31 +9627 32 583 4731 +9628 32 4731 631 +9629 533 532 4734 +9630 534 533 4736 +9631 4734 4716 533 +9632 4736 533 4716 +9633 5016 535 534 +9634 4736 5016 534 +9635 536 535 5017 +9636 5016 5017 535 +9637 537 536 4641 +9638 4641 536 4642 +9639 4642 536 5017 +9640 538 537 4641 +9641 5019 539 538 +9642 4992 538 4641 +9643 5019 538 4992 +9644 4766 540 539 +9645 4766 539 5019 +9646 5243 541 540 +9647 5243 540 4766 +9648 542 541 5242 +9649 5243 5242 541 +9650 543 542 4817 +9651 4817 542 5241 +9652 5241 542 5242 +9653 544 543 4816 +9654 4816 543 4817 +9655 5338 545 544 +9656 544 4816 5322 +9657 5338 544 5322 +9658 5337 546 545 +9659 5337 545 5338 +9660 4820 547 546 +9661 546 5337 4820 +9662 5284 548 547 +9663 547 4820 5284 +9664 549 548 5238 +9665 548 5284 5238 +9666 4595 550 549 +9667 549 4972 4595 +9668 4972 549 5238 +9669 551 550 4594 +9670 4594 550 4595 +9671 4647 552 551 +9672 4997 551 4594 +9673 4647 551 4997 +9674 4647 553 552 +9675 5013 554 553 +9676 4646 553 4647 +9677 5013 553 4646 +9678 555 554 5012 +9679 554 5013 5012 +9680 4738 556 555 +9681 555 5012 4738 +9682 4733 557 556 +9683 556 4728 4733 +9684 4728 556 4738 +9685 560 561 4758 +9686 560 4758 4732 +9687 4757 561 562 +9688 4758 561 4757 +9689 562 563 4781 +9690 562 4781 4757 +9691 563 564 4896 +9692 563 4896 4781 +9693 4569 564 565 +9694 4896 564 4569 +9695 4567 565 566 +9696 565 4567 4569 +9697 566 567 4866 +9698 4567 566 4866 +9699 567 568 4770 +9700 4988 567 4770 +9701 567 4988 4866 +9702 568 569 4769 +9703 568 4769 4770 +9704 569 570 5074 +9705 569 5074 4769 +9706 5075 570 571 +9707 570 5075 5074 +9708 571 572 5223 +9709 5075 571 5223 +9710 5312 572 573 +9711 5309 5223 572 +9712 5312 5309 572 +9713 4774 573 574 +9714 4774 5312 573 +9715 4773 574 575 +9716 4773 4774 574 +9717 4868 575 576 +9718 4773 575 5025 +9719 4868 5025 575 +9720 576 577 4577 +9721 4868 576 4577 +9722 577 578 4575 +9723 4575 4577 577 +9724 4901 578 579 +9725 4901 4575 578 +9726 579 580 4786 +9727 4901 579 4786 +9728 580 581 4864 +9729 4864 4786 580 +9730 4865 581 582 +9731 4864 581 4865 +9732 4733 4865 582 +9733 4731 583 584 +9734 4737 584 585 +9735 584 4723 4731 +9736 4723 584 4737 +9737 585 586 4996 +9738 585 4996 4737 +9739 5011 586 587 +9740 586 5011 4996 +9741 4644 587 588 +9742 4643 587 4644 +9743 5011 587 4643 +9744 4644 588 589 +9745 589 590 4591 +9746 4995 589 4591 +9747 4644 589 4995 +9748 4592 590 591 +9749 4591 590 4592 +9750 591 592 5239 +9751 591 4969 4592 +9752 4969 591 5239 +9753 5279 592 593 +9754 592 5279 5239 +9755 4824 593 594 +9756 593 4824 5279 +9757 5335 594 595 +9758 594 5335 4824 +9759 5336 595 596 +9760 5335 595 5336 +9761 596 597 4749 +9762 596 4749 5324 +9763 5336 596 5324 +9764 597 598 4750 +9765 4749 597 4750 +9766 598 599 5245 +9767 4750 598 5244 +9768 5244 598 5245 +9769 5240 599 600 +9770 5240 5245 599 +9771 4761 600 601 +9772 5240 600 4761 +9773 5018 601 602 +9774 4761 601 5018 +9775 602 603 4638 +9776 4990 602 4638 +9777 5018 602 4990 +9778 603 604 4638 +9779 604 605 5015 +9780 4638 604 4639 +9781 4639 604 5015 +9782 5014 605 606 +9783 5014 5015 605 +9784 606 607 4735 +9785 4735 5014 606 +9786 607 608 4732 +9787 4732 4711 607 +9788 4735 607 4711 +9789 609 610 4760 +9790 609 4760 4734 +9791 4759 610 611 +9792 4760 610 4759 +9793 611 612 4762 +9794 611 4762 4759 +9795 612 613 4895 +9796 612 4895 4762 +9797 4565 613 614 +9798 4895 613 4565 +9799 4563 614 615 +9800 614 4563 4565 +9801 615 616 4862 +9802 4563 615 4862 +9803 616 617 4768 +9804 4982 616 4768 +9805 616 4982 4862 +9806 617 618 4767 +9807 617 4767 4768 +9808 618 619 5080 +9809 618 5080 4767 +9810 5081 619 620 +9811 619 5081 5080 +9812 620 621 5222 +9813 5081 620 5222 +9814 5310 621 622 +9815 5308 5222 621 +9816 5310 5308 621 +9817 4772 622 623 +9818 4772 5310 622 +9819 4771 623 624 +9820 4771 4772 623 +9821 4867 624 625 +9822 4771 624 5024 +9823 4867 5024 624 +9824 625 626 4573 +9825 4867 625 4573 +9826 626 627 4571 +9827 4571 4573 626 +9828 4900 627 628 +9829 4900 4571 627 +9830 628 629 4777 +9831 4900 628 4777 +9832 629 630 4851 +9833 4851 4777 629 +9834 4863 630 631 +9835 4851 630 4863 +9836 4731 4863 631 +9837 4563 4564 4565 +9838 4563 4566 4564 +9839 4579 4566 4563 +9840 4862 4579 4563 +9841 4565 4564 4895 +9842 4566 4621 4564 +9843 4564 4621 4622 +9844 4895 4564 4622 +9845 4579 5108 4566 +9846 4566 4832 4621 +9847 4832 4566 5108 +9848 4567 4568 4569 +9849 4567 4570 4568 +9850 4583 4570 4567 +9851 4866 4583 4567 +9852 4569 4568 4896 +9853 4570 4627 4568 +9854 4568 4627 4628 +9855 4896 4568 4628 +9856 4583 5116 4570 +9857 4570 4827 4627 +9858 4827 4570 5116 +9859 4571 4572 4573 +9860 4632 4572 4571 +9861 4632 4571 4900 +9862 4572 4574 4573 +9863 4572 4633 4574 +9864 4632 4633 4572 +9865 4573 4574 4587 +9866 4573 4587 4867 +9867 4574 4588 4587 +9868 4588 4574 4933 +9869 4633 4933 4574 +9870 4575 4576 4577 +9871 4635 4576 4575 +9872 4635 4575 4901 +9873 4576 4578 4577 +9874 4576 4636 4578 +9875 4635 4636 4576 +9876 4577 4578 4589 +9877 4577 4589 4868 +9878 4578 4590 4589 +9879 4590 4578 4948 +9880 4636 4948 4578 +9881 4579 4862 4618 +9882 4618 5106 4579 +9883 4579 5106 5108 +9884 4580 4581 4582 +9885 4580 4679 4581 +9886 4582 4584 4580 +9887 4580 4584 4586 +9888 4586 4611 4580 +9889 4580 4611 4679 +9890 4581 4597 4582 +9891 4675 4597 4581 +9892 4581 4674 4675 +9893 4581 4679 4674 +9894 4582 4836 4584 +9895 4597 4838 4582 +9896 4582 4967 4836 +9897 4967 4582 4838 +9898 4583 4866 4623 +9899 4623 5109 4583 +9900 4583 5109 5116 +9901 4584 4585 4586 +9902 4584 4837 4585 +9903 4836 4837 4584 +9904 4586 4585 4755 +9905 4755 4585 4756 +9906 4585 4837 4756 +9907 4586 4610 4611 +9908 4586 5032 4610 +9909 4586 4755 5032 +9910 4588 4951 4587 +9911 4587 4801 4803 +9912 4587 4951 4801 +9913 4803 4867 4587 +9914 4933 5030 4588 +9915 5083 4951 4588 +9916 5030 5083 4588 +9917 4590 4952 4589 +9918 4589 4797 4799 +9919 4589 4952 4797 +9920 4799 4868 4589 +9921 4948 5033 4590 +9922 5087 4952 4590 +9923 5033 5087 4590 +9924 4591 4592 4593 +9925 4591 4593 4995 +9926 4969 4593 4592 +9927 4968 4593 4920 +9928 4920 4593 5078 +9929 4593 4968 4995 +9930 5078 4593 4969 +9931 4594 4595 4596 +9932 4594 4596 4997 +9933 4972 4596 4595 +9934 4971 4596 4924 +9935 4924 4596 5079 +9936 4596 4971 4997 +9937 5079 4596 4972 +9938 4597 4675 4839 +9939 4597 4839 4838 +9940 4598 4599 4600 +9941 4599 4598 4784 +9942 4598 4600 4981 +9943 4598 4620 4619 +9944 4784 4598 4619 +9945 4620 4598 4981 +9946 4600 4599 5007 +9947 4783 4599 4784 +9948 5007 4599 4783 +9949 5006 4600 4897 +9950 4600 5007 4897 +9951 4600 5006 4981 +9952 4601 4602 4603 +9953 4601 4830 4602 +9954 4607 4601 4603 +9955 4609 4601 4607 +9956 4609 4829 4601 +9957 4829 4830 4601 +9958 4603 4602 4764 +9959 4764 4602 4765 +9960 4602 4830 4765 +9961 4603 4614 4607 +9962 4603 4613 4614 +9963 4603 5029 4613 +9964 4603 4764 5029 +9965 4604 4605 4606 +9966 4605 4604 4788 +9967 4604 4606 4891 +9968 4604 4625 4624 +9969 4788 4604 4624 +9970 4625 4604 4891 +9971 4606 4605 5010 +9972 4787 4605 4788 +9973 5010 4605 4787 +9974 4606 5008 4891 +9975 5008 4606 5009 +9976 4606 5010 5009 +9977 4607 4608 4609 +9978 4607 4654 4608 +9979 4607 4614 4654 +9980 4608 4612 4609 +9981 4650 4612 4608 +9982 4608 4649 4650 +9983 4608 4654 4649 +9984 4612 4834 4609 +9985 4609 4944 4829 +9986 4944 4609 4834 +9987 4611 4610 5154 +9988 5266 4610 5032 +9989 4610 5265 5154 +9990 5265 4610 5266 +9991 4679 4611 5221 +9992 4611 5154 5221 +9993 4612 4650 4835 +9994 4612 4835 4834 +9995 4614 4613 5147 +9996 5267 4613 5029 +9997 4613 5271 5147 +9998 5271 4613 5267 +9999 4654 4614 5202 +10000 4614 5147 5202 +10001 4615 4616 4617 +10002 4615 4626 4616 +10003 4615 4617 5140 +10004 4626 4615 5366 +10005 4615 5140 5321 +10006 5321 5359 4615 +10007 5359 5366 4615 +10008 5144 4617 4616 +10009 4626 5358 4616 +10010 4616 5358 5144 +10011 4617 5139 5140 +10012 4617 5142 5139 +10013 5144 5142 4617 +10014 4618 4619 4620 +10015 4982 4619 4618 +10016 4618 4620 5106 +10017 4618 4862 4982 +10018 4619 4768 4784 +10019 4619 4982 4768 +10020 4620 4981 4852 +10021 5107 4620 4852 +10022 4620 5107 5106 +10023 4621 5102 4622 +10024 4832 4935 4621 +10025 4935 5102 4621 +10026 4775 4762 4622 +10027 4895 4622 4762 +10028 4622 5102 4775 +10029 4623 4624 4625 +10030 4988 4624 4623 +10031 4623 4625 5109 +10032 4623 4866 4988 +10033 4624 4770 4788 +10034 4624 4988 4770 +10035 4625 4891 4849 +10036 5110 4625 4849 +10037 4625 5110 5109 +10038 5133 4626 5305 +10039 4626 5133 5354 +10040 5366 5305 4626 +10041 5354 5358 4626 +10042 4627 5100 4628 +10043 4827 4950 4627 +10044 4950 5100 4627 +10045 4782 4781 4628 +10046 4896 4628 4781 +10047 4628 5100 4782 +10048 4629 4630 4631 +10049 4629 4634 4630 +10050 4629 4631 5122 +10051 4634 4629 5365 +10052 4629 5122 5320 +10053 5320 5360 4629 +10054 5360 5365 4629 +10055 5124 4631 4630 +10056 4634 5356 4630 +10057 4630 5356 5124 +10058 4631 5121 5122 +10059 4631 5123 5121 +10060 5124 5123 4631 +10061 4632 5104 4633 +10062 4632 4777 4776 +10063 4776 5104 4632 +10064 4777 4632 4900 +10065 4633 4934 4933 +10066 4633 5104 4934 +10067 5143 4634 5306 +10068 4634 5143 5353 +10069 5365 5306 4634 +10070 5353 5356 4634 +10071 4635 5105 4636 +10072 4635 4786 4785 +10073 4785 5105 4635 +10074 4786 4635 4901 +10075 4636 4949 4948 +10076 4636 5105 4949 +10077 4637 4638 4639 +10078 4637 4993 4638 +10079 4639 5037 4637 +10080 4637 4941 4993 +10081 5097 4941 4637 +10082 5097 4637 5037 +10083 4638 4993 4990 +10084 4639 5015 5037 +10085 4640 4641 4642 +10086 4640 4994 4641 +10087 4642 5039 4640 +10088 4640 4936 4994 +10089 5099 4936 4640 +10090 5099 4640 5039 +10091 4641 4994 4992 +10092 4642 5017 5039 +10093 4643 4644 4645 +10094 4645 5041 4643 +10095 5041 5011 4643 +10096 4644 4989 4645 +10097 4995 4989 4644 +10098 4989 4946 4645 +10099 4645 4946 5101 +10100 5041 4645 5101 +10101 4646 4647 4648 +10102 4648 5043 4646 +10103 5043 5013 4646 +10104 4647 4991 4648 +10105 4997 4991 4647 +10106 4991 4939 4648 +10107 4648 4939 5103 +10108 5043 4648 5103 +10109 4650 4649 5068 +10110 4654 5202 4649 +10111 4649 5065 5064 +10112 4649 5064 5068 +10113 5065 4649 5091 +10114 4649 5202 5091 +10115 5068 4835 4650 +10116 4651 4652 4653 +10117 5211 4652 4651 +10118 4651 4653 4954 +10119 4954 5113 4651 +10120 5113 5211 4651 +10121 4653 4652 5270 +10122 4652 5211 5208 +10123 4652 5208 5248 +10124 5248 5264 4652 +10125 5270 4652 5264 +10126 4653 4664 4973 +10127 5270 4664 4653 +10128 4973 4954 4653 +10129 4655 4656 4657 +10130 5207 4656 4655 +10131 4655 4657 4917 +10132 4917 5098 4655 +10133 5098 5207 4655 +10134 4657 4656 5268 +10135 4656 5207 5204 +10136 4656 5204 5246 +10137 5246 5269 4656 +10138 5268 4656 5269 +10139 4657 4660 4921 +10140 5268 4660 4657 +10141 4921 4917 4657 +10142 4658 4659 4660 +10143 4659 4658 5029 +10144 5268 4658 4660 +10145 4658 5267 5029 +10146 4658 5268 5267 +10147 4659 4661 4660 +10148 4659 5028 4661 +10149 4659 4764 5028 +10150 4659 5029 4764 +10151 4661 4921 4660 +10152 5062 4921 4661 +10153 5028 5272 4661 +10154 4661 5275 5062 +10155 5272 5275 4661 +10156 4662 4663 4664 +10157 4663 4662 5032 +10158 5270 4662 4664 +10159 4662 5266 5032 +10160 4662 5270 5266 +10161 4663 4665 4664 +10162 4663 5031 4665 +10163 4663 4755 5031 +10164 4663 5032 4755 +10165 4665 4973 4664 +10166 5077 4973 4665 +10167 5031 5256 4665 +10168 4665 5260 5077 +10169 5256 5260 4665 +10170 4666 4667 4668 +10171 4666 4669 4667 +10172 4666 4668 5061 +10173 4669 4666 5349 +10174 5061 5139 4666 +10175 4666 5139 5142 +10176 5142 5349 4666 +10177 5056 4668 4667 +10178 4669 5000 4667 +10179 4667 5000 5056 +10180 5061 4668 5049 +10181 5049 4668 5093 +10182 5056 5093 4668 +10183 4669 4963 4998 +10184 5301 4963 4669 +10185 4669 4998 5000 +10186 5349 5301 4669 +10187 4670 4671 4672 +10188 4670 4673 4671 +10189 4670 4672 5047 +10190 4673 4670 5347 +10191 5047 5121 4670 +10192 4670 5121 5123 +10193 5123 5347 4670 +10194 5059 4672 4671 +10195 4673 5004 4671 +10196 4671 5004 5059 +10197 5047 4672 5035 +10198 5035 4672 5095 +10199 5059 5095 4672 +10200 4673 4959 5002 +10201 5302 4959 4673 +10202 4673 5002 5004 +10203 5347 5302 4673 +10204 4675 4674 5063 +10205 4679 5221 4674 +10206 4674 5064 5063 +10207 4674 5069 5064 +10208 5069 4674 5089 +10209 4674 5221 5089 +10210 5063 4839 4675 +10211 4676 4677 4678 +10212 4676 4877 4677 +10213 4887 4676 4678 +10214 4877 4676 4815 +10215 4815 4676 4984 +10216 4887 4984 4676 +10217 4678 4677 4702 +10218 4701 4702 4677 +10219 5329 4701 4677 +10220 4677 4877 5329 +10221 4678 4702 4850 +10222 4849 4678 4850 +10223 4849 4887 4678 +10224 4680 4681 4682 +10225 4680 4885 4681 +10226 4986 4680 4682 +10227 4885 4680 4884 +10228 4884 4680 4987 +10229 4986 4987 4680 +10230 4682 4681 4706 +10231 4705 4706 4681 +10232 5327 4705 4681 +10233 4681 4885 5327 +10234 4682 4706 4853 +10235 4852 4682 4853 +10236 4852 4986 4682 +10237 4683 4684 4685 +10238 4684 4683 5094 +10239 4685 4914 4683 +10240 4964 4683 4914 +10241 4683 4964 5096 +10242 4683 5096 5094 +10243 4684 4686 4685 +10244 4686 4684 5151 +10245 4892 4684 5094 +10246 4892 5151 4684 +10247 5067 4685 4686 +10248 4685 4915 4914 +10249 4915 4685 5067 +10250 5243 5067 4686 +10251 4686 5151 5241 +10252 5241 5242 4686 +10253 5242 5243 4686 +10254 4687 4688 4689 +10255 4688 4687 5111 +10256 4689 4910 4687 +10257 4960 4687 4910 +10258 4687 4960 5112 +10259 4687 5112 5111 +10260 4688 4690 4689 +10261 4690 4688 5150 +10262 4888 4688 5111 +10263 4888 5150 4688 +10264 5066 4689 4690 +10265 4689 4911 4910 +10266 4911 4689 5066 +10267 5240 5066 4690 +10268 4690 5150 5244 +10269 5245 5240 4690 +10270 5244 5245 4690 +10271 4691 4692 4693 +10272 4691 4694 4692 +10273 4693 5079 4691 +10274 4694 4691 5238 +10275 5079 4972 4691 +10276 5238 4691 4972 +10277 5149 4693 4692 +10278 4819 4692 4694 +10279 4692 4819 4821 +10280 5149 4692 4821 +10281 4922 4693 4955 +10282 5079 4693 4922 +10283 5157 4955 4693 +10284 5149 5157 4693 +10285 5284 4819 4694 +10286 4694 5238 5284 +10287 4695 4696 4697 +10288 4695 4698 4696 +10289 4697 5078 4695 +10290 4698 4695 5239 +10291 5078 4969 4695 +10292 5239 4695 4969 +10293 5148 4697 4696 +10294 4823 4696 4698 +10295 4696 4823 4825 +10296 5148 4696 4825 +10297 4918 4697 4953 +10298 5078 4697 4918 +10299 5155 4953 4697 +10300 5148 5155 4697 +10301 5279 4823 4698 +10302 4698 5239 5279 +10303 4699 4700 4701 +10304 4932 4700 4699 +10305 4701 5114 4699 +10306 4927 4932 4699 +10307 5114 4927 4699 +10308 4700 4702 4701 +10309 4700 4874 4702 +10310 4700 4873 4874 +10311 4700 4875 4873 +10312 4700 4932 4875 +10313 5330 5114 4701 +10314 5329 5330 4701 +10315 4702 4874 4850 +10316 4703 4704 4705 +10317 4931 4704 4703 +10318 4705 5115 4703 +10319 4930 4931 4703 +10320 5115 4930 4703 +10321 4704 4706 4705 +10322 4704 4879 4706 +10323 4704 4878 4879 +10324 4704 4880 4878 +10325 4704 4931 4880 +10326 5328 5115 4705 +10327 5327 5328 4705 +10328 4706 4879 4853 +10329 4707 4708 4709 +10330 4707 4739 4708 +10331 4709 4745 4707 +10332 5260 4739 4707 +10333 4745 5077 4707 +10334 5077 5260 4707 +10335 4708 4710 4709 +10336 4708 5289 4710 +10337 5278 4708 4739 +10338 4708 5278 5289 +10339 5333 4709 4710 +10340 4709 5020 4745 +10341 5020 4709 5333 +10342 4710 4822 5273 +10343 4822 4710 5289 +10344 5273 5333 4710 +10345 4711 4712 4713 +10346 4711 4714 4712 +10347 4711 4713 4735 +10348 4714 4711 4715 +10349 4732 4715 4711 +10350 4713 4712 4790 +10351 4714 4791 4712 +10352 4790 4712 4791 +10353 5014 4735 4713 +10354 5014 4713 4790 +10355 4757 4714 4715 +10356 4781 4714 4757 +10357 4781 4782 4714 +10358 4714 4782 4791 +10359 4758 4715 4732 +10360 4757 4715 4758 +10361 4716 4717 4718 +10362 4716 4719 4717 +10363 4716 4718 4736 +10364 4719 4716 4720 +10365 4734 4720 4716 +10366 4718 4717 4795 +10367 4719 4796 4717 +10368 4795 4717 4796 +10369 5016 4736 4718 +10370 5016 4718 4795 +10371 4759 4719 4720 +10372 4762 4719 4759 +10373 4762 4775 4719 +10374 4719 4775 4796 +10375 4760 4720 4734 +10376 4759 4720 4760 +10377 4721 4722 4723 +10378 4747 4722 4721 +10379 4737 4721 4723 +10380 4721 4737 4996 +10381 4747 4721 4996 +10382 4722 4725 4723 +10383 4722 4746 4725 +10384 4746 4722 4747 +10385 4724 4723 4725 +10386 4723 4724 4731 +10387 4724 4725 4851 +10388 4731 4724 4863 +10389 4863 4724 4851 +10390 4746 4776 4725 +10391 4725 4776 4777 +10392 4851 4725 4777 +10393 4726 4727 4728 +10394 4779 4727 4726 +10395 4738 4726 4728 +10396 4726 4738 5012 +10397 4779 4726 5012 +10398 4727 4730 4728 +10399 4727 4778 4730 +10400 4778 4727 4779 +10401 4729 4728 4730 +10402 4728 4729 4733 +10403 4729 4730 4864 +10404 4733 4729 4865 +10405 4865 4729 4864 +10406 4778 4785 4730 +10407 4730 4785 4786 +10408 4864 4730 4786 +10409 5260 5256 4739 +10410 5278 4739 5256 +10411 4740 4741 4742 +10412 4740 4812 4741 +10413 4742 4753 4740 +10414 4753 5062 4740 +10415 5275 4812 4740 +10416 5062 5275 4740 +10417 4741 4808 4742 +10418 4741 5295 4808 +10419 5277 4741 4812 +10420 4741 5277 5295 +10421 4742 4983 4753 +10422 5334 4742 4808 +10423 4983 4742 5334 +10424 4743 4744 4745 +10425 4744 4743 4888 +10426 4743 4745 5325 +10427 4743 4750 5244 +10428 5325 4750 4743 +10429 5150 4888 4743 +10430 5244 5150 4743 +10431 5077 4745 4744 +10432 4744 4888 4890 +10433 5077 4744 4890 +10434 5325 4745 5020 +10435 4746 4747 4748 +10436 5104 4746 4748 +10437 4746 5104 4776 +10438 4748 4747 5042 +10439 4747 4996 5041 +10440 5042 4747 5041 +10441 4748 5052 4934 +10442 4748 4934 5104 +10443 5042 4945 4748 +10444 4945 5052 4748 +10445 5325 4749 4750 +10446 5325 5324 4749 +10447 4751 4752 4753 +10448 4752 4751 4892 +10449 4751 4753 5323 +10450 4751 4817 5241 +10451 5323 4817 4751 +10452 5151 4892 4751 +10453 5241 5151 4751 +10454 5062 4753 4752 +10455 4752 4892 4894 +10456 5062 4752 4894 +10457 5323 4753 4983 +10458 4754 4755 4756 +10459 4754 5031 4755 +10460 5169 4754 4756 +10461 4754 5256 5031 +10462 4754 5169 5256 +10463 4756 4837 5027 +10464 5021 4756 5027 +10465 5169 4756 5021 +10466 4761 4974 4911 +10467 4911 5066 4761 +10468 4974 4761 5018 +10469 5240 4761 5066 +10470 4763 4764 4765 +10471 4763 5028 4764 +10472 5172 4763 4765 +10473 4763 5272 5028 +10474 4763 5172 5272 +10475 4765 4830 4985 +10476 4976 4765 4985 +10477 5172 4765 4976 +10478 4766 4979 4915 +10479 4915 5067 4766 +10480 4979 4766 5019 +10481 5243 4766 5067 +10482 4784 4768 4767 +10483 4783 4784 4767 +10484 4783 4767 5080 +10485 4788 4770 4769 +10486 4787 4788 4769 +10487 4787 4769 5074 +10488 4772 4771 4792 +10489 4792 4771 4804 +10490 4771 5024 4804 +10491 4772 4792 5304 +10492 5310 4772 5304 +10493 4774 4773 4793 +10494 4793 4773 4800 +10495 4773 5025 4800 +10496 4774 4793 5303 +10497 5312 4774 5303 +10498 4775 5102 4796 +10499 4778 4779 4780 +10500 5105 4778 4780 +10501 4778 5105 4785 +10502 4780 4779 5044 +10503 4779 5012 5043 +10504 5044 4779 5043 +10505 5044 4938 4780 +10506 4938 5054 4780 +10507 4780 5054 4949 +10508 4780 4949 5105 +10509 4782 5100 4791 +10510 4783 5085 5007 +10511 5080 5081 4783 +10512 5085 4783 5081 +10513 4787 5076 5010 +10514 5074 5075 4787 +10515 5076 4787 5075 +10516 4789 4790 4791 +10517 5038 4790 4789 +10518 4789 4791 5100 +10519 4789 4942 5038 +10520 4789 5045 4942 +10521 4950 5045 4789 +10522 5100 4950 4789 +10523 5037 5014 4790 +10524 5037 4790 5038 +10525 4804 5055 4792 +10526 4792 5055 5304 +10527 4800 5058 4793 +10528 4793 5058 5303 +10529 4794 4795 4796 +10530 5040 4795 4794 +10531 4794 4796 5102 +10532 4935 5046 4794 +10533 5102 4935 4794 +10534 4794 4937 5040 +10535 4794 5046 4937 +10536 5039 5016 4795 +10537 5039 4795 5040 +10538 4797 4798 4799 +10539 4798 4797 5060 +10540 4797 4952 5060 +10541 4798 4800 4799 +10542 4800 4798 5058 +10543 4798 5003 5058 +10544 4798 5059 5003 +10545 4798 5060 5059 +10546 4799 4800 5025 +10547 5025 4868 4799 +10548 4801 4802 4803 +10549 4802 4801 5057 +10550 4801 4951 5057 +10551 4802 4804 4803 +10552 4804 4802 5055 +10553 4802 4999 5055 +10554 4802 5056 4999 +10555 4802 5057 5056 +10556 4803 4804 5024 +10557 5024 4867 4803 +10558 4805 4806 4807 +10559 4805 5001 4806 +10560 5307 4805 4807 +10561 5001 4805 5304 +10562 5308 5304 4805 +10563 4805 5307 5308 +10564 4807 4806 4961 +10565 4961 4806 4998 +10566 4806 5001 4998 +10567 4898 4902 4807 +10568 4961 4898 4807 +10569 5326 4807 4902 +10570 5326 5307 4807 +10571 4808 4818 5026 +10572 4818 4808 5295 +10573 5026 5334 4808 +10574 4809 4810 4811 +10575 4809 5005 4810 +10576 5167 4809 4811 +10577 5005 4809 5303 +10578 4809 5167 5309 +10579 5309 5303 4809 +10580 4811 4810 4957 +10581 4957 4810 5002 +10582 4810 5005 5002 +10583 4957 4956 4811 +10584 4956 5168 4811 +10585 5076 5167 4811 +10586 5076 4811 5168 +10587 5275 5272 4812 +10588 5277 4812 5272 +10589 4813 4814 4815 +10590 4814 4813 4881 +10591 4984 4813 4815 +10592 4813 5233 4881 +10593 4984 5250 4813 +10594 5250 5233 4813 +10595 4814 4877 4815 +10596 5287 4877 4814 +10597 4881 5236 4814 +10598 4814 5236 5285 +10599 4814 5285 5287 +10600 5323 4816 4817 +10601 5323 5322 4816 +10602 4818 4819 4820 +10603 4818 4821 4819 +10604 5026 4818 4820 +10605 4821 4818 5295 +10606 5284 4820 4819 +10607 4820 5337 5026 +10608 5149 4821 5288 +10609 4821 5295 5288 +10610 4822 4823 4824 +10611 4822 4825 4823 +10612 5273 4822 4824 +10613 4825 4822 5289 +10614 5279 4824 4823 +10615 4824 5335 5273 +10616 5148 4825 5280 +10617 4825 5289 5280 +10618 4826 4827 4828 +10619 4827 4826 4950 +10620 4826 4828 4873 +10621 4826 4873 5152 +10622 4950 4826 5152 +10623 4827 5116 4828 +10624 4828 4874 4873 +10625 5116 4874 4828 +10626 4829 5073 4830 +10627 4944 5072 4829 +10628 5072 5073 4829 +10629 4985 4830 5073 +10630 4831 4832 4833 +10631 4832 4831 4935 +10632 4831 4833 4878 +10633 4831 4878 5153 +10634 4935 4831 5153 +10635 4832 5108 4833 +10636 4833 4879 4878 +10637 5108 4879 4833 +10638 4834 4835 4906 +10639 4834 4906 4965 +10640 4834 4943 4944 +10641 4834 4965 4943 +10642 4906 4835 4907 +10643 4835 5068 4907 +10644 4836 5071 4837 +10645 4967 5070 4836 +10646 5070 5071 4836 +10647 5027 4837 5071 +10648 4838 4839 4903 +10649 4838 4903 4970 +10650 4838 4966 4967 +10651 4838 4970 4966 +10652 4903 4839 4904 +10653 4839 5063 4904 +10654 4840 4841 4842 +10655 4840 4946 4841 +10656 4840 4842 5117 +10657 4840 4945 4946 +10658 4840 4947 4945 +10659 4840 5117 4947 +10660 4842 4841 4919 +10661 4841 4920 4919 +10662 4841 4968 4920 +10663 4989 4841 4946 +10664 4968 4841 4989 +10665 5314 4842 4919 +10666 4842 5161 5117 +10667 4842 5314 5161 +10668 4843 4844 4845 +10669 4843 4869 4844 +10670 4843 4845 4970 +10671 4843 4905 4869 +10672 4905 4843 4903 +10673 4903 4843 4970 +10674 5133 4845 4844 +10675 4869 5126 4844 +10676 5126 5132 4844 +10677 5132 5133 4844 +10678 4970 4845 4966 +10679 5305 4966 4845 +10680 5305 4845 5133 +10681 4846 4847 4848 +10682 4846 4939 4847 +10683 4846 4848 5119 +10684 4846 4938 4939 +10685 4846 4940 4938 +10686 4846 5119 4940 +10687 4848 4847 4923 +10688 4847 4924 4923 +10689 4847 4971 4924 +10690 4991 4847 4939 +10691 4971 4847 4991 +10692 5313 4848 4923 +10693 4848 5164 5119 +10694 4848 5313 5164 +10695 4850 5110 4849 +10696 4849 4891 4887 +10697 5116 4850 4874 +10698 5116 5110 4850 +10699 4853 5107 4852 +10700 4852 4981 4986 +10701 5108 4853 4879 +10702 5108 5107 4853 +10703 4854 4855 4856 +10704 4854 4857 4855 +10705 4854 4856 4875 +10706 4854 4925 4857 +10707 4854 4875 4932 +10708 4925 4854 4932 +10709 4942 4856 4855 +10710 4857 4941 4855 +10711 4941 4942 4855 +10712 4875 4856 4873 +10713 4856 5152 4873 +10714 4856 4942 5045 +10715 5152 4856 5045 +10716 4909 4857 4912 +10717 4857 4909 4975 +10718 4912 4857 4925 +10719 4941 4857 4993 +10720 4993 4857 4975 +10721 4858 4859 4860 +10722 4858 4861 4859 +10723 4858 4860 4880 +10724 4858 4928 4861 +10725 4858 4880 4931 +10726 4928 4858 4931 +10727 4937 4860 4859 +10728 4861 4936 4859 +10729 4936 4937 4859 +10730 4880 4860 4878 +10731 4860 5153 4878 +10732 4860 4937 5046 +10733 5153 4860 5046 +10734 4913 4861 4916 +10735 4861 4913 4980 +10736 4916 4861 4928 +10737 4936 4861 4994 +10738 4994 4861 4980 +10739 5215 4869 4905 +10740 5127 5126 4869 +10741 5127 4869 5216 +10742 4869 5215 5216 +10743 4870 4871 4872 +10744 4870 4876 4871 +10745 4870 4872 4965 +10746 4870 4908 4876 +10747 4908 4870 4906 +10748 4906 4870 4965 +10749 5143 4872 4871 +10750 4876 5135 4871 +10751 5135 5141 4871 +10752 5141 5143 4871 +10753 4965 4872 4943 +10754 5306 4943 4872 +10755 5306 4872 5143 +10756 5218 4876 4908 +10757 5136 5135 4876 +10758 5136 4876 5219 +10759 4876 5218 5219 +10760 5329 4877 5287 +10761 5233 5185 4881 +10762 4881 5185 5236 +10763 4882 4883 4884 +10764 4883 4882 4886 +10765 4987 4882 4884 +10766 4882 5231 4886 +10767 4987 5251 4882 +10768 5251 5231 4882 +10769 4883 4885 4884 +10770 5283 4885 4883 +10771 4886 5229 4883 +10772 4883 5229 5281 +10773 4883 5281 5283 +10774 5327 4885 5283 +10775 4886 5192 5229 +10776 5231 5192 4886 +10777 4891 5008 4887 +10778 4887 5008 4984 +10779 4888 4889 4890 +10780 4889 4888 5111 +10781 4889 4973 4890 +10782 4973 4889 4954 +10783 4954 4889 5111 +10784 5077 4890 4973 +10785 4892 4893 4894 +10786 4893 4892 5094 +10787 4893 4921 4894 +10788 4921 4893 4917 +10789 4917 4893 5094 +10790 5062 4894 4921 +10791 4897 4898 4899 +10792 4897 4902 4898 +10793 5316 4897 4899 +10794 4897 5007 4902 +10795 4897 5316 5006 +10796 4899 4898 4962 +10797 4898 4961 4962 +10798 5200 4899 4962 +10799 5200 5251 4899 +10800 4899 5251 5316 +10801 4902 5007 5085 +10802 5085 5326 4902 +10803 4903 4904 4905 +10804 4905 4904 5215 +10805 5065 4904 5063 +10806 4904 5065 5215 +10807 4906 4907 4908 +10808 4908 4907 5218 +10809 5069 4907 5068 +10810 4907 5069 5218 +10811 4909 4910 4911 +10812 4909 4912 4910 +10813 4909 4911 4974 +10814 4909 4974 4975 +10815 4912 4926 4910 +10816 4960 4910 4926 +10817 4912 4925 4926 +10818 4913 4914 4915 +10819 4913 4916 4914 +10820 4913 4915 4979 +10821 4913 4979 4980 +10822 4916 4929 4914 +10823 4964 4914 4929 +10824 4916 4928 4929 +10825 5098 4917 5094 +10826 4918 4919 4920 +10827 4918 5051 4919 +10828 5078 4918 4920 +10829 5051 4918 4953 +10830 4919 5051 5314 +10831 4922 4923 4924 +10832 4922 5053 4923 +10833 5079 4922 4924 +10834 5053 4922 4955 +10835 4923 5053 5313 +10836 4925 4927 4926 +10837 4927 4925 4932 +10838 4926 4927 5131 +10839 4926 5131 4960 +10840 4927 5114 5345 +10841 5345 5131 4927 +10842 4928 4930 4929 +10843 4930 4928 4931 +10844 4929 4930 5134 +10845 4929 5134 4964 +10846 4930 5115 5346 +10847 5346 5134 4930 +10848 4934 5030 4933 +10849 5052 5030 4934 +10850 5153 5046 4935 +10851 5099 4937 4936 +10852 4937 5099 5040 +10853 4939 4938 5103 +10854 5054 4938 4940 +10855 5044 5103 4938 +10856 5054 4940 5120 +10857 4940 5119 5120 +10858 5097 4942 4941 +10859 4942 5097 5038 +10860 4944 4943 5072 +10861 5146 5072 4943 +10862 5306 5146 4943 +10863 4946 4945 5101 +10864 5052 4945 4947 +10865 5042 5101 4945 +10866 5052 4947 5118 +10867 4947 5117 5118 +10868 4949 5033 4948 +10869 5054 5033 4949 +10870 5152 5045 4950 +10871 5057 4951 5082 +10872 5082 4951 5083 +10873 5060 4952 5086 +10874 5086 4952 5087 +10875 4953 5125 5051 +10876 5125 4953 5155 +10877 5113 4954 5111 +10878 4955 5129 5053 +10879 5129 4955 5157 +10880 4956 4957 4958 +10881 5199 4956 4958 +10882 5199 5168 4956 +10883 4957 4959 4958 +10884 4959 4957 5002 +10885 4959 5198 4958 +10886 5197 4958 5198 +10887 5197 5199 4958 +10888 4959 5302 5198 +10889 5112 4960 5131 +10890 4961 4963 4962 +10891 4963 4961 4998 +10892 4963 5201 4962 +10893 5200 4962 5201 +10894 4963 5301 5201 +10895 5096 4964 5134 +10896 4967 4966 5070 +10897 5145 5070 4966 +10898 5305 5145 4966 +10899 4995 4968 4989 +10900 4997 4971 4991 +10901 4990 4975 4974 +10902 4990 4974 5018 +10903 4993 4975 4990 +10904 4976 4977 4978 +10905 4977 4976 5213 +10906 4978 5172 4976 +10907 4985 5213 4976 +10908 5203 4978 4977 +10909 4977 5158 5203 +10910 4977 5214 5158 +10911 4977 5213 5214 +10912 5277 5172 4978 +10913 5203 5296 4978 +10914 4978 5296 5277 +10915 4992 4980 4979 +10916 4992 4979 5019 +10917 4994 4980 4992 +10918 4981 5006 4986 +10919 5322 5323 4983 +10920 4983 5334 5322 +10921 5315 4984 5008 +10922 5315 5250 4984 +10923 4985 5073 5276 +10924 5213 4985 5276 +10925 4986 5006 4987 +10926 5316 4987 5006 +10927 5316 5251 4987 +10928 5041 4996 5011 +10929 4998 4999 5000 +10930 4998 5001 4999 +10931 5056 5000 4999 +10932 5001 5055 4999 +10933 5304 5055 5001 +10934 5002 5003 5004 +10935 5002 5005 5003 +10936 5059 5004 5003 +10937 5005 5058 5003 +10938 5303 5058 5005 +10939 5009 5315 5008 +10940 5009 5010 5168 +10941 5168 5199 5009 +10942 5315 5009 5199 +10943 5168 5010 5076 +10944 5043 5012 5013 +10945 5015 5014 5037 +10946 5017 5016 5039 +10947 5324 5325 5020 +10948 5020 5333 5324 +10949 5021 5022 5023 +10950 5022 5021 5212 +10951 5023 5169 5021 +10952 5027 5212 5021 +10953 5193 5023 5022 +10954 5022 5156 5193 +10955 5022 5196 5156 +10956 5022 5212 5196 +10957 5278 5169 5023 +10958 5193 5294 5023 +10959 5023 5294 5278 +10960 5337 5334 5026 +10961 5027 5071 5274 +10962 5212 5027 5274 +10963 5030 5052 5118 +10964 5083 5030 5118 +10965 5033 5054 5120 +10966 5087 5033 5120 +10967 5034 5035 5036 +10968 5034 5047 5035 +10969 5034 5036 5162 +10970 5034 5340 5047 +10971 5162 5261 5034 +10972 5261 5340 5034 +10973 5095 5036 5035 +10974 5086 5088 5036 +10975 5086 5036 5095 +10976 5036 5088 5163 +10977 5162 5036 5163 +10978 5097 5037 5038 +10979 5099 5039 5040 +10980 5042 5041 5101 +10981 5044 5043 5103 +10982 5340 5121 5047 +10983 5048 5049 5050 +10984 5048 5061 5049 +10985 5048 5050 5159 +10986 5048 5339 5061 +10987 5159 5257 5048 +10988 5257 5339 5048 +10989 5093 5050 5049 +10990 5082 5084 5050 +10991 5082 5050 5093 +10992 5050 5084 5160 +10993 5159 5050 5160 +10994 5125 5314 5051 +10995 5129 5313 5053 +10996 5056 5057 5093 +10997 5082 5093 5057 +10998 5059 5060 5095 +10999 5086 5095 5060 +11000 5339 5139 5061 +11001 5063 5064 5065 +11002 5068 5064 5069 +11003 5065 5091 5092 +11004 5065 5092 5215 +11005 5069 5089 5090 +11006 5069 5090 5218 +11007 5070 5225 5071 +11008 5070 5145 5224 +11009 5070 5224 5225 +11010 5274 5071 5225 +11011 5072 5227 5073 +11012 5072 5146 5226 +11013 5072 5226 5227 +11014 5276 5073 5227 +11015 5075 5167 5076 +11016 5167 5075 5223 +11017 5326 5085 5081 +11018 5307 5081 5222 +11019 5081 5307 5326 +11020 5083 5084 5082 +11021 5118 5084 5083 +11022 5084 5118 5160 +11023 5087 5088 5086 +11024 5120 5088 5087 +11025 5088 5120 5163 +11026 5090 5089 5332 +11027 5221 5332 5089 +11028 5218 5090 5219 +11029 5090 5220 5219 +11030 5332 5220 5090 +11031 5092 5091 5331 +11032 5202 5331 5091 +11033 5215 5092 5216 +11034 5092 5217 5216 +11035 5331 5217 5092 +11036 5096 5098 5094 +11037 5170 5098 5096 +11038 5170 5096 5134 +11039 5207 5098 5170 +11040 5107 5108 5106 +11041 5110 5116 5109 +11042 5112 5113 5111 +11043 5165 5113 5112 +11044 5165 5112 5131 +11045 5211 5113 5165 +11046 5345 5114 5166 +11047 5166 5114 5363 +11048 5330 5361 5114 +11049 5361 5363 5114 +11050 5346 5115 5171 +11051 5171 5115 5364 +11052 5328 5362 5115 +11053 5362 5364 5115 +11054 5118 5117 5160 +11055 5117 5161 5160 +11056 5120 5119 5163 +11057 5119 5164 5163 +11058 5121 5340 5122 +11059 5122 5187 5320 +11060 5122 5340 5187 +11061 5124 5347 5123 +11062 5124 5302 5347 +11063 5355 5302 5124 +11064 5124 5356 5355 +11065 5125 5155 5174 +11066 5173 5125 5174 +11067 5125 5173 5259 +11068 5125 5259 5314 +11069 5126 5127 5128 +11070 5352 5126 5128 +11071 5132 5126 5352 +11072 5127 5130 5128 +11073 5127 5300 5130 +11074 5253 5127 5216 +11075 5300 5127 5253 +11076 5228 5128 5130 +11077 5190 5128 5192 +11078 5352 5128 5190 +11079 5192 5128 5228 +11080 5129 5157 5179 +11081 5178 5129 5179 +11082 5129 5178 5262 +11083 5129 5262 5313 +11084 5130 5299 5228 +11085 5130 5300 5299 +11086 5165 5131 5166 +11087 5166 5131 5345 +11088 5132 5354 5133 +11089 5352 5354 5132 +11090 5170 5134 5171 +11091 5171 5134 5346 +11092 5135 5136 5137 +11093 5351 5135 5137 +11094 5141 5135 5351 +11095 5136 5138 5137 +11096 5136 5298 5138 +11097 5252 5136 5219 +11098 5298 5136 5252 +11099 5235 5137 5138 +11100 5183 5137 5185 +11101 5351 5137 5183 +11102 5185 5137 5235 +11103 5138 5297 5235 +11104 5138 5298 5297 +11105 5139 5339 5140 +11106 5140 5177 5321 +11107 5140 5339 5177 +11108 5141 5353 5143 +11109 5351 5353 5141 +11110 5144 5349 5142 +11111 5144 5301 5349 +11112 5357 5301 5144 +11113 5144 5358 5357 +11114 5145 5359 5224 +11115 5145 5305 5366 +11116 5145 5366 5359 +11117 5146 5360 5226 +11118 5146 5306 5365 +11119 5146 5365 5360 +11120 5202 5147 5331 +11121 5255 5217 5147 +11122 5217 5331 5147 +11123 5271 5255 5147 +11124 5148 5156 5155 +11125 5148 5193 5156 +11126 5148 5280 5193 +11127 5149 5158 5157 +11128 5149 5203 5158 +11129 5149 5288 5203 +11130 5254 5220 5154 +11131 5220 5332 5154 +11132 5221 5154 5332 +11133 5265 5254 5154 +11134 5155 5156 5174 +11135 5174 5156 5196 +11136 5157 5158 5179 +11137 5179 5158 5214 +11138 5159 5160 5161 +11139 5159 5161 5311 +11140 5311 5257 5159 +11141 5311 5161 5259 +11142 5314 5259 5161 +11143 5162 5163 5164 +11144 5162 5164 5317 +11145 5317 5261 5162 +11146 5313 5262 5164 +11147 5317 5164 5262 +11148 5209 5165 5166 +11149 5211 5165 5209 +11150 5166 5210 5209 +11151 5363 5210 5166 +11152 5167 5223 5309 +11153 5278 5256 5169 +11154 5205 5170 5171 +11155 5207 5170 5205 +11156 5171 5206 5205 +11157 5364 5206 5171 +11158 5277 5272 5172 +11159 5173 5174 5319 +11160 5175 5176 5173 +11161 5175 5173 5319 +11162 5259 5173 5176 +11163 5319 5174 5196 +11164 5175 5177 5176 +11165 5175 5350 5177 +11166 5319 5291 5175 +11167 5350 5175 5291 +11168 5177 5257 5176 +11169 5311 5176 5257 +11170 5259 5176 5311 +11171 5339 5257 5177 +11172 5321 5177 5350 +11173 5178 5179 5318 +11174 5180 5181 5178 +11175 5180 5178 5318 +11176 5262 5178 5181 +11177 5318 5179 5214 +11178 5180 5187 5181 +11179 5180 5348 5187 +11180 5318 5293 5180 +11181 5348 5180 5293 +11182 5187 5261 5181 +11183 5317 5181 5261 +11184 5262 5181 5317 +11185 5182 5183 5184 +11186 5183 5182 5351 +11187 5184 5186 5182 +11188 5356 5182 5186 +11189 5182 5356 5351 +11190 5183 5185 5184 +11191 5185 5233 5184 +11192 5184 5188 5186 +11193 5234 5188 5184 +11194 5233 5234 5184 +11195 5235 5236 5185 +11196 5188 5355 5186 +11197 5186 5355 5356 +11198 5340 5261 5187 +11199 5320 5187 5348 +11200 5197 5198 5188 +11201 5234 5197 5188 +11202 5198 5302 5188 +11203 5188 5302 5355 +11204 5189 5190 5191 +11205 5190 5189 5352 +11206 5191 5194 5189 +11207 5358 5189 5194 +11208 5189 5358 5352 +11209 5190 5192 5191 +11210 5192 5231 5191 +11211 5191 5195 5194 +11212 5232 5195 5191 +11213 5231 5232 5191 +11214 5228 5229 5192 +11215 5294 5193 5280 +11216 5195 5357 5194 +11217 5194 5357 5358 +11218 5200 5201 5195 +11219 5232 5200 5195 +11220 5201 5301 5195 +11221 5195 5301 5357 +11222 5274 5196 5212 +11223 5291 5196 5274 +11224 5196 5291 5319 +11225 5197 5250 5199 +11226 5250 5197 5234 +11227 5199 5250 5315 +11228 5251 5200 5232 +11229 5296 5203 5288 +11230 5204 5205 5206 +11231 5204 5207 5205 +11232 5204 5206 5247 +11233 5247 5246 5204 +11234 5282 5247 5206 +11235 5282 5206 5364 +11236 5208 5209 5210 +11237 5208 5211 5209 +11238 5208 5210 5249 +11239 5249 5248 5208 +11240 5286 5249 5210 +11241 5286 5210 5363 +11242 5276 5214 5213 +11243 5293 5214 5276 +11244 5214 5293 5318 +11245 5217 5253 5216 +11246 5253 5217 5255 +11247 5220 5252 5219 +11248 5252 5220 5254 +11249 5307 5222 5308 +11250 5225 5224 5290 +11251 5350 5290 5224 +11252 5224 5359 5350 +11253 5225 5290 5274 +11254 5227 5226 5292 +11255 5348 5292 5226 +11256 5226 5360 5348 +11257 5227 5292 5276 +11258 5230 5229 5228 +11259 5228 5299 5230 +11260 5230 5281 5229 +11261 5341 5281 5230 +11262 5230 5299 5342 +11263 5230 5342 5341 +11264 5232 5231 5251 +11265 5234 5233 5250 +11266 5237 5236 5235 +11267 5235 5297 5237 +11268 5237 5285 5236 +11269 5343 5285 5237 +11270 5237 5297 5344 +11271 5237 5344 5343 +11272 5247 5263 5246 +11273 5246 5263 5271 +11274 5269 5246 5271 +11275 5263 5247 5342 +11276 5341 5247 5282 +11277 5341 5342 5247 +11278 5249 5258 5248 +11279 5248 5258 5265 +11280 5264 5248 5265 +11281 5258 5249 5344 +11282 5343 5249 5286 +11283 5343 5344 5249 +11284 5254 5298 5252 +11285 5255 5300 5253 +11286 5265 5258 5254 +11287 5254 5258 5297 +11288 5254 5297 5298 +11289 5271 5263 5255 +11290 5255 5263 5299 +11291 5255 5299 5300 +11292 5344 5297 5258 +11293 5342 5299 5263 +11294 5265 5266 5264 +11295 5266 5270 5264 +11296 5267 5268 5269 +11297 5271 5267 5269 +11298 5335 5333 5273 +11299 5290 5291 5274 +11300 5292 5293 5276 +11301 5295 5277 5296 +11302 5289 5278 5294 +11303 5294 5280 5289 +11304 5281 5282 5283 +11305 5282 5281 5341 +11306 5362 5283 5282 +11307 5282 5364 5362 +11308 5328 5327 5283 +11309 5283 5362 5328 +11310 5285 5286 5287 +11311 5286 5285 5343 +11312 5361 5287 5286 +11313 5286 5363 5361 +11314 5330 5329 5287 +11315 5287 5361 5330 +11316 5296 5288 5295 +11317 5291 5290 5350 +11318 5293 5292 5348 +11319 5303 5309 5312 +11320 5304 5308 5310 +11321 5348 5360 5320 +11322 5350 5359 5321 +11323 5338 5322 5334 +11324 5336 5324 5333 +11325 5333 5335 5336 +11326 5334 5337 5338 +11327 5351 5356 5353 +11328 5352 5358 5354 +2 23 2 198 +11329 25 504 5410 +11330 633 25 5410 +11331 529 28 5409 +11332 28 634 5409 +11333 31 608 5408 +11334 635 31 5408 +11335 583 32 5407 +11336 32 632 5407 +11337 504 505 5413 +11338 5410 504 5413 +11339 505 506 5401 +11340 505 5401 5413 +11341 506 507 5421 +11342 5401 506 5421 +11343 507 508 5393 +11344 507 5393 5421 +11345 508 509 5424 +11346 5393 508 5424 +11347 509 510 5400 +11348 509 5400 5424 +11349 510 511 5403 +11350 510 5379 5400 +11351 5379 510 5403 +11352 511 512 5431 +11353 5403 511 5431 +11354 512 513 5387 +11355 512 5387 5431 +11356 513 514 5417 +11357 5387 513 5417 +11358 514 515 5394 +11359 514 5394 5417 +11360 515 516 5420 +11361 5394 515 5420 +11362 516 517 5388 +11363 516 5388 5420 +11364 517 518 5415 +11365 5388 517 5415 +11366 518 519 5385 +11367 518 5385 5415 +11368 519 520 5423 +11369 5385 519 5423 +11370 520 521 5395 +11371 520 5395 5423 +11372 521 522 5427 +11373 5395 521 5427 +11374 522 523 5396 +11375 522 5396 5427 +11376 523 524 5430 +11377 5396 523 5430 +11378 524 525 5399 +11379 524 5399 5430 +11380 525 526 5405 +11381 525 5380 5399 +11382 5380 525 5405 +11383 526 527 5433 +11384 5405 526 5433 +11385 527 528 5381 +11386 527 5381 5433 +11387 528 529 5412 +11388 5381 528 5412 +11389 529 5409 5412 +11390 584 583 5411 +11391 583 5407 5411 +11392 585 584 5382 +11393 5382 584 5411 +11394 586 585 5422 +11395 585 5382 5422 +11396 587 586 5386 +11397 5386 586 5422 +11398 588 587 5425 +11399 587 5386 5425 +11400 589 588 5398 +11401 5398 588 5425 +11402 590 589 5404 +11403 5379 589 5398 +11404 589 5379 5404 +11405 591 590 5432 +11406 590 5404 5432 +11407 592 591 5391 +11408 5391 591 5432 +11409 593 592 5418 +11410 592 5391 5418 +11411 594 593 5383 +11412 5383 593 5418 +11413 595 594 5419 +11414 594 5383 5419 +11415 596 595 5390 +11416 5390 595 5419 +11417 597 596 5416 +11418 596 5390 5416 +11419 598 597 5392 +11420 5392 597 5416 +11421 599 598 5426 +11422 598 5392 5426 +11423 600 599 5389 +11424 5389 599 5426 +11425 601 600 5428 +11426 600 5389 5428 +11427 602 601 5384 +11428 5384 601 5428 +11429 603 602 5429 +11430 602 5384 5429 +11431 604 603 5397 +11432 5397 603 5429 +11433 605 604 5406 +11434 5380 604 5397 +11435 604 5380 5406 +11436 606 605 5434 +11437 605 5406 5434 +11438 607 606 5402 +11439 5402 606 5434 +11440 608 607 5414 +11441 607 5402 5414 +11442 5408 608 5414 +11443 632 633 5435 +11444 5407 632 5435 +11445 633 5410 5435 +11446 634 635 5436 +11447 5409 634 5436 +11448 635 5408 5436 +11449 5367 5382 5411 +11450 5382 5367 5413 +11451 5407 5367 5411 +11452 5367 5407 5435 +11453 5367 5410 5413 +11454 5410 5367 5435 +11455 5368 5381 5412 +11456 5381 5368 5414 +11457 5368 5408 5414 +11458 5408 5368 5436 +11459 5409 5368 5412 +11460 5368 5409 5436 +11461 5383 5369 5394 +11462 5369 5383 5418 +11463 5387 5369 5391 +11464 5369 5387 5417 +11465 5391 5369 5418 +11466 5394 5369 5417 +11467 5370 5383 5394 +11468 5383 5370 5419 +11469 5370 5388 5390 +11470 5388 5370 5420 +11471 5370 5390 5419 +11472 5370 5394 5420 +11473 5371 5387 5391 +11474 5387 5371 5431 +11475 5371 5391 5432 +11476 5403 5371 5404 +11477 5371 5403 5431 +11478 5404 5371 5432 +11479 5372 5385 5392 +11480 5385 5372 5415 +11481 5388 5372 5390 +11482 5372 5388 5415 +11483 5390 5372 5416 +11484 5372 5392 5416 +11485 5373 5382 5401 +11486 5382 5373 5422 +11487 5386 5373 5393 +11488 5373 5386 5422 +11489 5393 5373 5421 +11490 5373 5401 5421 +11491 5385 5374 5392 +11492 5374 5385 5423 +11493 5389 5374 5395 +11494 5374 5389 5426 +11495 5392 5374 5426 +11496 5395 5374 5423 +11497 5375 5386 5393 +11498 5386 5375 5425 +11499 5375 5393 5424 +11500 5398 5375 5400 +11501 5375 5398 5425 +11502 5400 5375 5424 +11503 5376 5381 5402 +11504 5381 5376 5433 +11505 5376 5402 5434 +11506 5405 5376 5406 +11507 5376 5405 5433 +11508 5406 5376 5434 +11509 5384 5377 5396 +11510 5377 5384 5428 +11511 5377 5389 5395 +11512 5389 5377 5428 +11513 5377 5395 5427 +11514 5396 5377 5427 +11515 5378 5384 5396 +11516 5384 5378 5429 +11517 5378 5396 5430 +11518 5397 5378 5399 +11519 5378 5397 5429 +11520 5399 5378 5430 +11521 5379 5398 5400 +11522 5379 5403 5404 +11523 5380 5397 5399 +11524 5380 5405 5406 +11525 5402 5381 5414 +11526 5401 5382 5413 +2 24 2 359 +11527 450 25 5544 +11528 25 633 5544 +11529 26 463 5546 +11530 530 26 5546 +11531 29 531 5515 +11532 609 29 5580 +11533 29 5515 5580 +11534 32 631 5577 +11535 632 32 5501 +11536 5501 32 5577 +11537 451 450 5550 +11538 450 5544 5550 +11539 452 451 5489 +11540 5489 451 5550 +11541 453 452 5557 +11542 452 5489 5557 +11543 454 453 5495 +11544 5495 453 5557 +11545 455 454 5540 +11546 454 5495 5540 +11547 456 455 5585 +11548 455 5540 5585 +11549 457 456 5536 +11550 456 5503 5536 +11551 5503 456 5585 +11552 458 457 5491 +11553 5491 457 5536 +11554 459 458 5582 +11555 458 5491 5582 +11556 460 459 5506 +11557 5506 459 5582 +11558 461 460 5543 +11559 460 5506 5543 +11560 462 461 5593 +11561 461 5543 5593 +11562 463 462 5558 +11563 462 5509 5558 +11564 5509 462 5593 +11565 5546 463 5558 +11566 531 530 5583 +11567 530 5546 5583 +11568 5515 531 5583 +11569 610 609 5513 +11570 5513 609 5580 +11571 611 610 5541 +11572 610 5513 5541 +11573 612 611 5538 +11574 611 5481 5538 +11575 5481 611 5541 +11576 613 612 5538 +11577 614 613 5542 +11578 5487 613 5538 +11579 613 5487 5542 +11580 615 614 5527 +11581 5527 614 5542 +11582 616 615 5590 +11583 615 5527 5590 +11584 617 616 5531 +11585 5531 616 5590 +11586 618 617 5518 +11587 5518 617 5531 +11588 619 618 5574 +11589 618 5518 5574 +11590 620 619 5530 +11591 5530 619 5574 +11592 621 620 5567 +11593 620 5530 5567 +11594 622 621 5502 +11595 5502 621 5567 +11596 623 622 5520 +11597 622 5502 5520 +11598 624 623 5571 +11599 623 5520 5571 +11600 625 624 5521 +11601 5521 624 5571 +11602 626 625 5528 +11603 625 5521 5528 +11604 627 626 5485 +11605 5485 626 5528 +11606 628 627 5523 +11607 627 5485 5523 +11608 629 628 5588 +11609 628 5523 5588 +11610 630 629 5529 +11611 5529 629 5588 +11612 631 630 5500 +11613 5500 630 5529 +11614 631 5500 5577 +11615 633 632 5578 +11616 632 5501 5578 +11617 5544 633 5578 +11618 5437 5508 5535 +11619 5508 5437 5537 +11620 5437 5511 5525 +11621 5511 5437 5565 +11622 5437 5525 5537 +11623 5437 5535 5565 +11624 5438 5469 5507 +11625 5469 5438 5514 +11626 5476 5438 5507 +11627 5438 5476 5534 +11628 5484 5438 5534 +11629 5438 5484 5539 +11630 5514 5438 5539 +11631 5477 5439 5512 +11632 5439 5477 5517 +11633 5439 5483 5512 +11634 5483 5439 5559 +11635 5439 5517 5548 +11636 5439 5548 5559 +11637 5440 5490 5554 +11638 5490 5440 5581 +11639 5440 5494 5524 +11640 5494 5440 5554 +11641 5516 5440 5524 +11642 5440 5516 5581 +11643 5441 5497 5532 +11644 5497 5441 5569 +11645 5504 5441 5547 +11646 5441 5504 5569 +11647 5522 5441 5532 +11648 5441 5522 5547 +11649 5442 5499 5570 +11650 5499 5442 5591 +11651 5526 5442 5545 +11652 5442 5526 5591 +11653 5545 5442 5570 +11654 5443 5493 5510 +11655 5493 5443 5549 +11656 5496 5443 5510 +11657 5443 5496 5562 +11658 5549 5443 5566 +11659 5443 5562 5566 +11660 5473 5444 5519 +11661 5444 5473 5533 +11662 5505 5444 5533 +11663 5444 5505 5551 +11664 5519 5444 5586 +11665 5444 5551 5586 +11666 5471 5445 5563 +11667 5445 5471 5573 +11668 5489 5445 5552 +11669 5445 5489 5563 +11670 5445 5492 5552 +11671 5492 5445 5573 +11672 5498 5446 5564 +11673 5446 5498 5587 +11674 5446 5509 5564 +11675 5509 5446 5575 +11676 5575 5446 5587 +11677 5447 5484 5553 +11678 5484 5447 5572 +11679 5447 5485 5561 +11680 5485 5447 5589 +11681 5494 5447 5561 +11682 5447 5494 5572 +11683 5447 5553 5589 +11684 5481 5448 5538 +11685 5448 5481 5560 +11686 5486 5448 5560 +11687 5448 5486 5584 +11688 5448 5487 5538 +11689 5487 5448 5579 +11690 5448 5504 5579 +11691 5504 5448 5584 +11692 5449 5495 5555 +11693 5495 5449 5576 +11694 5499 5449 5507 +11695 5449 5499 5576 +11696 5507 5449 5555 +11697 5482 5450 5508 +11698 5450 5482 5568 +11699 5450 5490 5508 +11700 5490 5450 5592 +11701 5514 5450 5568 +11702 5450 5514 5592 +11703 5451 5484 5534 +11704 5484 5451 5553 +11705 5492 5451 5534 +11706 5451 5492 5573 +11707 5451 5500 5529 +11708 5500 5451 5573 +11709 5451 5529 5553 +11710 5452 5468 5517 +11711 5468 5452 5569 +11712 5452 5477 5488 +11713 5477 5452 5517 +11714 5452 5488 5511 +11715 5497 5452 5511 +11716 5452 5497 5569 +11717 5473 5453 5506 +11718 5453 5473 5519 +11719 5483 5453 5512 +11720 5453 5483 5594 +11721 5506 5453 5543 +11722 5512 5453 5519 +11723 5543 5453 5594 +11724 5454 5496 5516 +11725 5496 5454 5562 +11726 5502 5454 5520 +11727 5454 5502 5562 +11728 5454 5516 5556 +11729 5520 5454 5556 +11730 5478 5455 5513 +11731 5455 5478 5587 +11732 5455 5481 5541 +11733 5481 5455 5560 +11734 5486 5455 5559 +11735 5455 5486 5560 +11736 5455 5498 5559 +11737 5498 5455 5587 +11738 5513 5455 5541 +11739 5456 5479 5518 +11740 5479 5456 5549 +11741 5456 5480 5522 +11742 5480 5456 5531 +11743 5493 5456 5522 +11744 5456 5493 5549 +11745 5456 5518 5531 +11746 5490 5457 5508 +11747 5457 5490 5581 +11748 5457 5496 5510 +11749 5496 5457 5581 +11750 5508 5457 5535 +11751 5457 5510 5535 +11752 5491 5458 5533 +11753 5458 5491 5536 +11754 5458 5503 5526 +11755 5503 5458 5536 +11756 5505 5458 5526 +11757 5458 5505 5533 +11758 5459 5485 5528 +11759 5485 5459 5561 +11760 5494 5459 5524 +11761 5459 5494 5561 +11762 5459 5521 5524 +11763 5521 5459 5528 +11764 5493 5460 5510 +11765 5460 5493 5532 +11766 5460 5497 5511 +11767 5497 5460 5532 +11768 5510 5460 5565 +11769 5460 5511 5565 +11770 5461 5482 5537 +11771 5482 5461 5545 +11772 5488 5461 5525 +11773 5461 5488 5551 +11774 5461 5505 5545 +11775 5505 5461 5551 +11776 5525 5461 5537 +11777 5462 5504 5547 +11778 5504 5462 5579 +11779 5462 5527 5542 +11780 5527 5462 5547 +11781 5462 5542 5579 +11782 5463 5489 5550 +11783 5489 5463 5563 +11784 5463 5501 5563 +11785 5501 5463 5578 +11786 5544 5463 5550 +11787 5463 5544 5578 +11788 5464 5494 5554 +11789 5494 5464 5572 +11790 5464 5514 5539 +11791 5514 5464 5592 +11792 5464 5539 5572 +11793 5464 5554 5592 +11794 5509 5465 5558 +11795 5465 5509 5575 +11796 5515 5465 5575 +11797 5465 5515 5583 +11798 5465 5546 5558 +11799 5546 5465 5583 +11800 5503 5466 5526 +11801 5466 5503 5585 +11802 5526 5466 5591 +11803 5466 5540 5576 +11804 5540 5466 5585 +11805 5466 5576 5591 +11806 5467 5489 5552 +11807 5489 5467 5557 +11808 5495 5467 5555 +11809 5467 5495 5557 +11810 5467 5552 5555 +11811 5504 5468 5569 +11812 5468 5504 5584 +11813 5517 5468 5548 +11814 5548 5468 5584 +11815 5469 5499 5507 +11816 5499 5469 5570 +11817 5469 5514 5568 +11818 5469 5568 5570 +11819 5470 5520 5556 +11820 5520 5470 5571 +11821 5521 5470 5524 +11822 5470 5521 5571 +11823 5524 5470 5556 +11824 5471 5500 5573 +11825 5500 5471 5577 +11826 5501 5471 5563 +11827 5471 5501 5577 +11828 5502 5472 5562 +11829 5472 5502 5567 +11830 5472 5530 5566 +11831 5530 5472 5567 +11832 5562 5472 5566 +11833 5473 5491 5533 +11834 5491 5473 5582 +11835 5473 5506 5582 +11836 5523 5474 5588 +11837 5474 5523 5589 +11838 5529 5474 5553 +11839 5474 5529 5588 +11840 5553 5474 5589 +11841 5509 5475 5564 +11842 5475 5509 5593 +11843 5543 5475 5593 +11844 5475 5543 5594 +11845 5564 5475 5594 +11846 5476 5492 5534 +11847 5492 5476 5552 +11848 5476 5507 5555 +11849 5552 5476 5555 +11850 5488 5477 5586 +11851 5477 5512 5519 +11852 5477 5519 5586 +11853 5478 5513 5580 +11854 5478 5515 5575 +11855 5515 5478 5580 +11856 5478 5575 5587 +11857 5518 5479 5574 +11858 5530 5479 5566 +11859 5479 5530 5574 +11860 5479 5549 5566 +11861 5522 5480 5547 +11862 5480 5527 5547 +11863 5527 5480 5590 +11864 5480 5531 5590 +11865 5482 5508 5537 +11866 5482 5545 5570 +11867 5568 5482 5570 +11868 5498 5483 5559 +11869 5483 5498 5564 +11870 5483 5564 5594 +11871 5539 5484 5572 +11872 5523 5485 5589 +11873 5548 5486 5559 +11874 5486 5548 5584 +11875 5542 5487 5579 +11876 5511 5488 5525 +11877 5551 5488 5586 +11878 5554 5490 5592 +11879 5493 5522 5532 +11880 5540 5495 5576 +11881 5516 5496 5581 +11882 5576 5499 5591 +11883 5505 5526 5545 +11884 5535 5510 5565 +11885 5516 5524 5556 +2 25 2 359 +11886 27 5702 490 +11887 559 5702 27 +11888 503 5704 28 +11889 28 5704 634 +11890 30 5659 558 +11891 582 5735 30 +11892 30 5735 5659 +11893 31 5738 560 +11894 635 5673 31 +11895 5673 5738 31 +11896 490 5708 491 +11897 5702 5708 490 +11898 491 5647 492 +11899 491 5708 5647 +11900 492 5715 493 +11901 5647 5715 492 +11902 493 5653 494 +11903 493 5715 5653 +11904 494 5698 495 +11905 5653 5698 494 +11906 495 5743 496 +11907 5698 5743 495 +11908 496 5694 497 +11909 5661 5694 496 +11910 496 5743 5661 +11911 497 5649 498 +11912 497 5694 5649 +11913 498 5740 499 +11914 5649 5740 498 +11915 499 5664 500 +11916 499 5740 5664 +11917 500 5701 501 +11918 5664 5701 500 +11919 501 5751 502 +11920 5701 5751 501 +11921 502 5716 503 +11922 5667 5716 502 +11923 502 5751 5667 +11924 503 5716 5704 +11925 558 5736 559 +11926 5659 5736 558 +11927 559 5736 5702 +11928 560 5671 561 +11929 560 5738 5671 +11930 561 5699 562 +11931 5671 5699 561 +11932 562 5696 563 +11933 5639 5696 562 +11934 562 5699 5639 +11935 563 5696 564 +11936 564 5700 565 +11937 564 5696 5645 +11938 5645 5700 564 +11939 565 5685 566 +11940 565 5700 5685 +11941 566 5748 567 +11942 5685 5748 566 +11943 567 5689 568 +11944 567 5748 5689 +11945 568 5676 569 +11946 568 5689 5676 +11947 569 5732 570 +11948 5676 5732 569 +11949 570 5688 571 +11950 570 5732 5688 +11951 571 5725 572 +11952 5688 5725 571 +11953 572 5660 573 +11954 572 5725 5660 +11955 573 5678 574 +11956 5660 5678 573 +11957 574 5729 575 +11958 5678 5729 574 +11959 575 5679 576 +11960 575 5729 5679 +11961 576 5686 577 +11962 5679 5686 576 +11963 577 5643 578 +11964 577 5686 5643 +11965 578 5681 579 +11966 5643 5681 578 +11967 579 5746 580 +11968 5681 5746 579 +11969 580 5687 581 +11970 580 5746 5687 +11971 581 5658 582 +11972 581 5687 5658 +11973 5658 5735 582 +11974 634 5741 635 +11975 5704 5741 634 +11976 635 5741 5673 +11977 5666 5693 5595 +11978 5595 5695 5666 +11979 5669 5683 5595 +11980 5595 5723 5669 +11981 5683 5695 5595 +11982 5693 5723 5595 +11983 5627 5665 5596 +11984 5596 5672 5627 +11985 5596 5665 5634 +11986 5634 5692 5596 +11987 5596 5692 5642 +11988 5642 5697 5596 +11989 5596 5697 5672 +11990 5597 5670 5635 +11991 5635 5675 5597 +11992 5641 5670 5597 +11993 5597 5717 5641 +11994 5675 5706 5597 +11995 5706 5717 5597 +11996 5648 5712 5598 +11997 5598 5739 5648 +11998 5652 5682 5598 +11999 5598 5712 5652 +12000 5598 5682 5674 +12001 5674 5739 5598 +12002 5655 5690 5599 +12003 5599 5727 5655 +12004 5599 5705 5662 +12005 5662 5727 5599 +12006 5599 5690 5680 +12007 5680 5705 5599 +12008 5657 5728 5600 +12009 5600 5749 5657 +12010 5600 5703 5684 +12011 5684 5749 5600 +12012 5600 5728 5703 +12013 5651 5668 5601 +12014 5601 5707 5651 +12015 5601 5668 5654 +12016 5654 5720 5601 +12017 5601 5724 5707 +12018 5720 5724 5601 +12019 5602 5677 5631 +12020 5631 5691 5602 +12021 5602 5691 5663 +12022 5663 5709 5602 +12023 5602 5744 5677 +12024 5709 5744 5602 +12025 5603 5721 5629 +12026 5629 5731 5603 +12027 5603 5710 5647 +12028 5647 5721 5603 +12029 5650 5710 5603 +12030 5603 5731 5650 +12031 5604 5722 5656 +12032 5656 5745 5604 +12033 5667 5722 5604 +12034 5604 5733 5667 +12035 5604 5745 5733 +12036 5642 5711 5605 +12037 5605 5730 5642 +12038 5643 5719 5605 +12039 5605 5747 5643 +12040 5605 5719 5652 +12041 5652 5730 5605 +12042 5711 5747 5605 +12043 5606 5696 5639 +12044 5639 5718 5606 +12045 5606 5718 5644 +12046 5644 5742 5606 +12047 5645 5696 5606 +12048 5606 5737 5645 +12049 5662 5737 5606 +12050 5606 5742 5662 +12051 5653 5713 5607 +12052 5607 5734 5653 +12053 5607 5665 5657 +12054 5657 5734 5607 +12055 5607 5713 5665 +12056 5608 5666 5640 +12057 5640 5726 5608 +12058 5648 5666 5608 +12059 5608 5750 5648 +12060 5608 5726 5672 +12061 5672 5750 5608 +12062 5642 5692 5609 +12063 5609 5711 5642 +12064 5609 5692 5650 +12065 5650 5731 5609 +12066 5658 5687 5609 +12067 5609 5731 5658 +12068 5687 5711 5609 +12069 5626 5675 5610 +12070 5610 5727 5626 +12071 5635 5646 5610 +12072 5610 5675 5635 +12073 5646 5669 5610 +12074 5610 5669 5655 +12075 5655 5727 5610 +12076 5611 5664 5631 +12077 5631 5677 5611 +12078 5611 5670 5641 +12079 5641 5752 5611 +12080 5611 5701 5664 +12081 5611 5677 5670 +12082 5611 5752 5701 +12083 5654 5674 5612 +12084 5612 5720 5654 +12085 5612 5678 5660 +12086 5660 5720 5612 +12087 5674 5714 5612 +12088 5612 5714 5678 +12089 5613 5671 5636 +12090 5636 5745 5613 +12091 5639 5699 5613 +12092 5613 5718 5639 +12093 5613 5717 5644 +12094 5644 5718 5613 +12095 5656 5717 5613 +12096 5613 5745 5656 +12097 5613 5699 5671 +12098 5637 5676 5614 +12099 5614 5707 5637 +12100 5638 5680 5614 +12101 5614 5689 5638 +12102 5614 5680 5651 +12103 5651 5707 5614 +12104 5676 5689 5614 +12105 5615 5666 5648 +12106 5648 5739 5615 +12107 5654 5668 5615 +12108 5615 5739 5654 +12109 5615 5693 5666 +12110 5668 5693 5615 +12111 5616 5691 5649 +12112 5649 5694 5616 +12113 5661 5684 5616 +12114 5616 5694 5661 +12115 5616 5684 5663 +12116 5663 5691 5616 +12117 5643 5686 5617 +12118 5617 5719 5643 +12119 5617 5682 5652 +12120 5652 5719 5617 +12121 5679 5682 5617 +12122 5617 5686 5679 +12123 5618 5668 5651 +12124 5651 5690 5618 +12125 5655 5669 5618 +12126 5618 5690 5655 +12127 5618 5723 5668 +12128 5669 5723 5618 +12129 5640 5695 5619 +12130 5619 5703 5640 +12131 5619 5683 5646 +12132 5646 5709 5619 +12133 5663 5703 5619 +12134 5619 5709 5663 +12135 5619 5695 5683 +12136 5662 5705 5620 +12137 5620 5737 5662 +12138 5685 5700 5620 +12139 5620 5705 5685 +12140 5700 5737 5620 +12141 5647 5708 5621 +12142 5621 5721 5647 +12143 5659 5721 5621 +12144 5621 5736 5659 +12145 5621 5708 5702 +12146 5702 5736 5621 +12147 5652 5712 5622 +12148 5622 5730 5652 +12149 5672 5697 5622 +12150 5622 5750 5672 +12151 5697 5730 5622 +12152 5712 5750 5622 +12153 5623 5716 5667 +12154 5667 5733 5623 +12155 5623 5733 5673 +12156 5673 5741 5623 +12157 5704 5716 5623 +12158 5623 5741 5704 +12159 5624 5684 5661 +12160 5661 5743 5624 +12161 5624 5749 5684 +12162 5698 5734 5624 +12163 5624 5743 5698 +12164 5734 5749 5624 +12165 5647 5710 5625 +12166 5625 5715 5647 +12167 5625 5713 5653 +12168 5653 5715 5625 +12169 5710 5713 5625 +12170 5626 5727 5662 +12171 5662 5742 5626 +12172 5626 5706 5675 +12173 5626 5742 5706 +12174 5657 5665 5627 +12175 5627 5728 5657 +12176 5672 5726 5627 +12177 5726 5728 5627 +12178 5678 5714 5628 +12179 5628 5729 5678 +12180 5628 5682 5679 +12181 5679 5729 5628 +12182 5628 5714 5682 +12183 5658 5731 5629 +12184 5629 5735 5658 +12185 5629 5721 5659 +12186 5659 5735 5629 +12187 5630 5720 5660 +12188 5660 5725 5630 +12189 5688 5724 5630 +12190 5630 5725 5688 +12191 5630 5724 5720 +12192 5649 5691 5631 +12193 5631 5740 5649 +12194 5664 5740 5631 +12195 5632 5746 5681 +12196 5681 5747 5632 +12197 5632 5711 5687 +12198 5687 5746 5632 +12199 5632 5747 5711 +12200 5633 5722 5667 +12201 5667 5751 5633 +12202 5633 5751 5701 +12203 5701 5752 5633 +12204 5633 5752 5722 +12205 5650 5692 5634 +12206 5634 5710 5650 +12207 5665 5713 5634 +12208 5634 5713 5710 +12209 5635 5744 5646 +12210 5670 5677 5635 +12211 5677 5744 5635 +12212 5671 5738 5636 +12213 5673 5733 5636 +12214 5636 5738 5673 +12215 5733 5745 5636 +12216 5637 5732 5676 +12217 5637 5724 5688 +12218 5688 5732 5637 +12219 5707 5724 5637 +12220 5638 5705 5680 +12221 5685 5705 5638 +12222 5638 5748 5685 +12223 5689 5748 5638 +12224 5666 5695 5640 +12225 5703 5728 5640 +12226 5640 5728 5726 +12227 5641 5717 5656 +12228 5656 5722 5641 +12229 5722 5752 5641 +12230 5642 5730 5697 +12231 5643 5747 5681 +12232 5644 5717 5706 +12233 5706 5742 5644 +12234 5645 5737 5700 +12235 5646 5683 5669 +12236 5646 5744 5709 +12237 5648 5750 5712 +12238 5680 5690 5651 +12239 5653 5734 5698 +12240 5654 5739 5674 +12241 5657 5749 5734 +12242 5684 5703 5663 +12243 5668 5723 5693 +12244 5682 5714 5674 +3 1 4 24462 +12245 2250 6452 6319 6506 +12246 5758 5824 4599 5831 +12247 5924 6165 3648 6169 +12248 5764 5877 1733 6385 +12249 5962 5985 3525 6394 +12250 1604 6202 5948 6462 +12251 5839 5980 3353 6300 +12252 5319 5173 5786 6024 +12253 4569 6016 6015 6381 +12254 3065 5801 3175 6338 +12255 3175 5801 2631 6338 +12256 4487 5992 6355 6356 +12257 3932 2085 5761 5973 +12258 2064 1733 5877 6385 +12259 5292 5839 5348 5980 +12260 3300 6231 5870 6711 +12261 1607 6464 5836 6465 +12262 5860 5799 6936 7019 +12263 5650 6954 6923 7114 +12264 5492 6953 6922 7113 +12265 3315 6245 6557 6724 +12266 3990 3743 3908 5753 +12267 5360 6195 6053 6300 +12268 4128 5960 4348 6244 +12269 5402 5813 6309 6777 +12270 4560 5796 6261 6262 +12271 590 6017 5901 6679 +12272 5267 6314 6228 6332 +12273 1615 6262 5836 6464 +12274 5143 4871 4872 6030 +12275 2688 5880 6259 6617 +12276 4871 4872 6030 6183 +12277 6055 6242 1810 6460 +12278 2169 5994 5836 6501 +12279 3073 6083 6013 6606 +12280 5883 5908 3155 6621 +12281 1467 1502 5882 6775 +12282 5533 6529 6774 7009 +12283 6528 6771 5691 7011 +12284 5867 6170 4782 6247 +12285 3499 6358 6117 6447 +12286 4574 6551 6188 7124 +12287 4693 6042 6109 6660 +12288 4574 6188 6235 7124 +12289 5038 5866 5794 6872 +12290 2056 6410 6073 6588 +12291 5052 6606 6393 6744 +12292 2250 6384 6319 6452 +12293 5360 5320 6195 6300 +12294 2322 5822 5793 6067 +12295 333 6157 6110 6329 +12296 2785 6015 2782 6247 +12297 5869 6044 2716 6109 +12298 6075 6174 5093 6469 +12299 5672 6802 6594 6940 +12300 5514 6801 6593 6939 +12301 5814 6158 5315 6220 +12302 4198 6093 5848 6134 +12303 6042 6043 4691 6109 +12304 4756 6117 6358 6447 +12305 6291 2241 6397 6586 +12306 1502 6491 5882 6758 +12307 2048 5858 2094 6286 +12308 1314 6923 6903 6954 +12309 3800 6922 6904 6953 +12310 5349 6085 6086 6919 +12311 4609 6342 5873 6411 +12312 1502 6758 5882 6775 +12313 4833 5847 5846 6504 +12314 4574 5983 6551 7124 +12315 4099 5905 5844 6992 +12316 2926 5941 5828 6511 +12317 5991 6316 4290 6779 +12318 3180 6210 5770 6621 +12319 3060 6707 5874 7120 +12320 2894 6075 6069 6213 +12321 6027 6204 1735 6605 +12322 2169 5836 1894 6501 +12323 3015 5843 2607 5927 +12324 524 6157 6285 6387 +12325 4099 5844 6230 6992 +12326 2183 5844 5812 6949 +12327 5089 6382 6082 6425 +12328 2926 5828 5941 7179 +12329 4449 6000 5915 6864 +12330 2054 5977 5967 6175 +12331 2704 5811 5785 7029 +12332 483 6462 6202 6463 +12333 5923 5936 5339 6466 +12334 3536 5936 2386 6173 +12335 2598 6011 6276 6438 +12336 5402 6309 5813 6589 +12337 5790 5834 5771 6941 +12338 6030 6183 4872 6272 +12339 2931 6047 5908 6394 +12340 5968 6323 6256 6847 +12341 5042 5856 5857 6606 +12342 5277 6021 6102 6455 +12343 5561 6784 6641 6913 +12344 6256 6323 5968 6667 +12345 5758 5826 5824 7077 +12346 6363 6447 3321 7148 +12347 6106 3321 6363 6447 +12348 4118 4239 5818 6207 +12349 2054 5891 5977 6175 +12350 4416 6066 5837 7047 +12351 483 5948 6202 6462 +12352 6075 5093 6213 6469 +12353 28 634 5767 6141 +12354 4628 6170 6015 6247 +12355 5946 6093 1977 6494 +12356 3609 5924 3648 6169 +12357 4663 6363 6117 6447 +12358 334 6329 6110 6439 +12359 5863 5939 2512 6052 +12360 4161 6326 6226 6673 +12361 2598 6276 6150 6438 +12362 4668 6069 4667 6647 +12363 2382 6582 6048 7107 +12364 5177 5909 5923 6466 +12365 2446 6606 5856 6744 +12366 1569 6303 5946 6442 +12367 2382 5854 6048 6582 +12368 3315 6557 6003 6724 +12369 4724 4863 5896 6680 +12370 2931 5908 5944 6394 +12371 5886 4793 6237 6799 +12372 4095 5991 5865 7095 +12373 5155 6024 6402 6831 +12374 524 6354 6157 6387 +12375 3908 3634 5753 5809 +12376 2382 5830 6582 7107 +12377 3602 6123 5979 6253 +12378 4490 5788 5756 6328 +12379 5827 6631 3820 6736 +12380 5348 5980 5839 6300 +12381 5832 6037 2653 6105 +12382 5312 6274 5917 6968 +12383 5562 6676 5472 6757 +12384 5720 6675 5630 6758 +12385 5367 5822 5411 6067 +12386 5325 5860 5799 6936 +12387 3055 5829 5972 6813 +12388 4792 5859 5779 6008 +12389 3230 5758 5824 7077 +12390 5924 6430 6165 7136 +12391 28 5767 634 5995 +12392 1398 6878 6699 7060 +12393 5806 5822 4731 6680 +12394 4926 5908 6047 6394 +12395 5897 373 6185 6628 +12396 1823 6211 6076 6377 +12397 6179 6195 3212 6707 +12398 4128 5769 4348 5960 +12399 5058 6237 4793 6799 +12400 1740 5812 5756 6328 +12401 6015 6170 2782 6247 +12402 3237 5892 3236 5934 +12403 4341 6203 6187 7091 +12404 6923 6954 1314 7114 +12405 6922 6953 3800 7113 +12406 2613 6252 5841 6363 +12407 2156 5982 2071 6207 +12408 5761 5973 2142 6468 +12409 2613 5841 6252 7022 +12410 2688 6259 3017 6617 +12411 5177 5923 5339 6466 +12412 4341 6396 6203 7091 +12413 6291 6292 2241 6586 +12414 3546 5786 3545 5787 +12415 6056 6402 6024 6831 +12416 4782 6170 4628 6247 +12417 2967 6016 6015 6089 +12418 5836 6262 1615 7104 +12419 2091 6386 6055 6461 +12420 1311 5803 6232 6883 +12421 5781 5855 3610 5924 +12422 5073 5821 5227 6908 +12423 4173 5905 4099 6992 +12424 5887 6020 4736 6414 +12425 5049 6075 6173 6174 +12426 5436 5767 6141 6309 +12427 3222 5814 5849 6070 +12428 6260 6308 1580 6418 +12429 4560 6261 486 6262 +12430 4885 5771 5790 5834 +12431 3559 5824 5758 5831 +12432 429 3642 6051 6160 +12433 5848 6093 2145 6134 +12434 5769 5960 4128 6244 +12435 5946 6407 266 6442 +12436 4878 4833 5846 6504 +12437 3899 3733 6564 6645 +12438 5052 5030 6393 6606 +12439 2160 5804 6111 6485 +12440 429 6051 6159 6160 +12441 5983 6393 5030 6606 +12442 5821 5980 5227 6908 +12443 5839 5980 5292 6496 +12444 5828 5941 4847 6511 +12445 5211 5841 5770 5883 +12446 5472 6676 6534 6757 +12447 5630 6675 6533 6758 +12448 2056 6073 6377 6588 +12449 4112 6357 6139 6601 +12450 5904 6162 4605 6273 +12451 5283 5773 5771 5834 +12452 270 6256 5968 6667 +12453 2086 1770 6019 6290 +12454 2382 5830 2379 6582 +12455 3258 6333 6332 6477 +12456 2931 5908 3160 5944 +12457 4569 6381 6015 6761 +12458 3154 5908 6047 6621 +12459 6002 6224 4597 7036 +12460 3055 5972 5829 6031 +12461 5833 6445 6313 6739 +12462 5985 6047 3525 6394 +12463 1732 6186 6029 6558 +12464 5763 2029 6076 7099 +12465 4454 5996 5891 6975 +12466 4855 5794 6028 6945 +12467 5143 6030 6272 6336 +12468 218 6261 5796 6262 +12469 4926 5944 5908 6394 +12470 6110 6241 5427 6856 +12471 5829 6031 5972 6813 +12472 6172 6173 2886 6275 +12473 5998 6125 2606 6473 +12474 2142 6373 5761 6468 +12475 3233 3237 3236 5934 +12476 617 5862 5916 7189 +12477 2966 6016 2967 6089 +12478 5946 472 6407 6442 +12479 6125 6473 6366 7162 +12480 1996 5808 5951 6286 +12481 1378 2706 2452 6088 +12482 5943 5975 3108 5976 +12483 632 633 6751 7038 +12484 6529 6633 456 6790 +12485 496 6528 6634 6791 +12486 5968 6256 2124 6847 +12487 5823 6099 5044 6709 +12488 6194 6305 1590 6423 +12489 2423 437 5785 6515 +12490 4955 5053 5819 5941 +12491 1398 6699 6016 7060 +12492 3130 6083 3073 6606 +12493 516 6384 6452 6506 +12494 5816 5817 4070 6207 +12495 1748 5761 2085 5973 +12496 6124 6188 2727 6221 +12497 5543 460 461 6924 +12498 5793 5822 5367 6067 +12499 2738 6109 5941 6511 +12500 4863 6229 5896 6680 +12501 3421 5815 3582 6652 +12502 3315 5784 6245 6724 +12503 4272 4410 5812 6328 +12504 4082 5977 5891 6175 +12505 2794 6104 6258 6402 +12506 5923 5936 3536 6173 +12507 4445 4295 6064 6577 +12508 227 6260 6092 6308 +12509 5812 6328 4410 7100 +12510 5971 4848 6433 6697 +12511 565 6699 6878 7060 +12512 1960 6624 6032 7132 +12513 3013 6069 6008 6213 +12514 3108 5976 5975 7142 +12515 3116 5814 3503 6717 +12516 5941 5971 4923 6433 +12517 2071 5982 5895 6207 +12518 3535 6195 6005 6707 +12519 5775 5780 2999 6755 +12520 4756 6358 6353 6447 +12521 5313 6031 6433 6697 +12522 5206 5961 6298 6554 +12523 1378 2706 6088 6089 +12524 6090 6107 4113 6556 +12525 3797 5798 6264 6882 +12526 270 5968 6323 6667 +12527 5824 6269 3056 6517 +12528 456 6633 6529 6868 +12529 496 6634 6528 6867 +12530 3899 6772 5543 6924 +12531 5957 6183 6181 7138 +12532 5886 5917 4793 6799 +12533 2755 6104 5776 6576 +12534 5772 5903 5338 5911 +12535 5143 6030 4872 6272 +12536 4116 6000 4449 6864 +12537 3444 6082 6382 6425 +12538 486 5836 6464 6465 +12539 5330 5902 5755 5985 +12540 5843 2607 5927 6481 +12541 5731 6903 6923 6954 +12542 6904 6922 5573 6953 +12543 2789 6043 6042 6660 +12544 3099 6166 6131 6512 +12545 2461 5820 6229 6680 +12546 5020 5799 5325 6390 +12547 4605 6162 5010 6273 +12548 2141 6153 6019 6290 +12549 3294 5765 3554 6129 +12550 6117 6447 6363 7148 +12551 4173 5905 5817 6778 +12552 3258 6411 6333 6477 +12553 6150 6276 5200 6438 +12554 554 6054 5013 6739 +12555 2745 5963 2743 6364 +12556 5782 5823 5043 6054 +12557 1421 418 5919 7090 +12558 5780 6246 2999 6755 +12559 1754 5802 1998 5872 +12560 5954 6097 2164 6547 +12561 5039 6414 5868 6536 +12562 5823 5044 6257 6709 +12563 3899 6645 5543 6772 +12564 4485 6156 5845 6316 +12565 2704 5785 6148 7029 +12566 5874 6166 3060 7120 +12567 4964 5134 5757 6037 +12568 4667 6069 6085 6647 +12569 3627 6313 6261 6462 +12570 1580 6418 6308 7051 +12571 5039 5868 5040 6536 +12572 3109 5943 5902 5975 +12573 2094 5858 5808 6286 +12574 5155 5174 6024 6831 +12575 4813 4815 5976 7142 +12576 6077 6797 5768 7089 +12577 4342 6113 5952 6635 +12578 4832 5846 5847 6861 +12579 6393 6606 5983 6744 +12580 6066 6677 4073 7192 +12581 5337 5772 5338 5911 +12582 3385 5821 3386 6908 +12583 4523 5979 6253 6546 +12584 4523 5979 6123 6253 +12585 2491 6174 6075 6469 +12586 3819 6604 6534 6826 +12587 2371 5754 2296 7044 +12588 6261 6313 3627 6894 +12589 5817 4239 6207 6836 +12590 5937 6059 2968 6437 +12591 4198 5848 4424 6134 +12592 5782 2808 6054 7150 +12593 1735 6027 5840 6204 +12594 4790 5866 5038 6872 +12595 1556 6409 6408 6667 +12596 1202 6016 6089 7060 +12597 5209 5770 5210 6400 +12598 3154 3155 5908 6621 +12599 5349 6163 6085 6919 +12600 5173 5786 6024 6831 +12601 2968 6059 6058 6437 +12602 2164 6547 6097 7118 +12603 3610 5924 5855 6768 +12604 332 6285 6157 6387 +12605 2727 6221 6188 6957 +12606 2331 6201 6185 6628 +12607 3899 6564 5543 6645 +12608 5184 5186 6023 6212 +12609 1378 2452 2475 6088 +12610 3199 2938 3511 5778 +12611 5315 5814 6220 6717 +12612 6091 6129 5202 6130 +12613 3692 6317 6038 6604 +12614 5939 6052 600 6266 +12615 5955 6098 2163 7171 +12616 5688 570 6533 6602 +12617 6290 6291 310 6397 +12618 6261 6313 4522 6462 +12619 4550 6160 5988 7039 +12620 5919 6453 1421 7090 +12621 3390 5821 5980 6496 +12622 3043 5911 5772 6502 +12623 4813 5849 4815 7142 +12624 5884 6736 5827 6887 +12625 2322 5793 5822 6401 +12626 6375 6376 4134 6934 +12627 3065 3175 5801 5868 +12628 1701 1883 6139 7146 +12629 2439 5857 5856 6606 +12630 4791 5978 5867 6872 +12631 4550 5988 6160 6520 +12632 513 6349 6291 6690 +12633 4978 6102 6101 6455 +12634 6632 1318 6851 6955 +12635 366 2512 5939 6052 +12636 4737 5806 6080 6981 +12637 3028 5777 6237 6431 +12638 2598 2597 6011 6438 +12639 6052 6266 5939 6856 +12640 3571 3113 5755 6265 +12641 5050 6174 6173 6275 +12642 1900 6238 6225 6579 +12643 4878 5846 6096 6504 +12644 6117 4665 6713 7148 +12645 3038 3041 5841 5883 +12646 4917 6037 5832 6105 +12647 263 6134 6093 6327 +12648 5519 6774 4007 6873 +12649 1521 5677 6771 6874 +12650 4561 5768 4493 6190 +12651 3908 5753 3743 5809 +12652 2086 6290 6019 7028 +12653 3019 5911 3043 6502 +12654 6040 6171 5391 7151 +12655 5963 6062 2743 6364 +12656 4628 6015 6170 6351 +12657 1501 6540 6637 6675 +12658 3987 6538 6638 6676 +12659 2382 6048 5854 6793 +12660 588 6045 6017 6295 +12661 5157 6042 5819 6662 +12662 3160 2931 3154 5908 +12663 5432 6171 5901 6268 +12664 2158 5838 5760 6532 +12665 3353 5980 5839 6496 +12666 2147 5989 6944 7132 +12667 3658 6362 6253 6391 +12668 4712 6451 5866 7160 +12669 5348 5292 5293 5839 +12670 6095 6096 2889 6103 +12671 1467 1281 1502 6775 +12672 2955 2926 5828 6511 +12673 5803 27 6232 6883 +12674 2168 6100 6311 6718 +12675 6352 4134 6376 6934 +12676 3333 5771 6970 7144 +12677 6594 6802 1406 6940 +12678 6593 6801 3892 6939 +12679 5867 5978 5100 6170 +12680 5926 6700 2731 7021 +12681 5167 5927 5843 6161 +12682 1556 6391 6409 6667 +12683 5773 6627 5961 6742 +12684 2794 2754 6104 6402 +12685 5311 5176 5965 6708 +12686 5806 4721 6371 6623 +12687 5794 6259 2437 7152 +12688 2379 5830 2382 7107 +12689 1311 5804 5803 6883 +12690 3875 3678 3899 6564 +12691 6156 6315 4374 6377 +12692 6013 6371 4721 6623 +12693 3116 6220 5814 6717 +12694 5955 2163 6223 7171 +12695 2789 6109 6043 6660 +12696 5803 6324 1538 6794 +12697 5769 6025 1948 6357 +12698 5819 5941 5053 6433 +12699 2029 6588 6076 7099 +12700 3300 2665 6231 6711 +12701 3545 5786 3475 5787 +12702 5979 3602 6253 6546 +12703 430 429 6051 6159 +12704 5980 6367 5227 6908 +12705 6161 6162 2392 6273 +12706 6632 6743 1318 6955 +12707 6594 6780 5672 6940 +12708 6593 6783 5514 6939 +12709 2279 6157 6354 6387 +12710 5818 6207 4239 6836 +12711 2192 5953 6460 7015 +12712 4881 6158 5976 6745 +12713 6246 6695 2999 6755 +12714 5911 6036 2650 6159 +12715 2489 6075 6213 6469 +12716 5870 5892 3237 5934 +12717 3571 6265 5755 6786 +12718 366 5863 2512 6052 +12719 5770 6400 5209 6621 +12720 4849 6050 5110 6265 +12721 1462 5852 1885 5974 +12722 1884 3948 5851 5973 +12723 5184 6212 6023 6218 +12724 2323 6067 5793 6318 +12725 25 6264 5798 6882 +12726 6082 6425 3444 6426 +12727 3542 5972 5819 6330 +12728 5822 6067 2322 6115 +12729 2613 2905 5841 7022 +12730 5782 5783 2808 7150 +12731 3571 6378 6265 6786 +12732 6131 6361 2626 7027 +12733 5927 5970 3161 6161 +12734 6173 6174 2886 6275 +12735 4847 5941 5828 5971 +12736 329 6293 6284 6294 +12737 4920 6197 6104 6915 +12738 5772 6046 4983 6480 +12739 2018 6118 5982 6395 +12740 6045 380 6321 6470 +12741 5923 5965 5311 6172 +12742 4693 6042 4691 6109 +12743 429 3642 430 6051 +12744 5991 6079 5865 7095 +12745 3381 6129 6091 6130 +12746 539 5785 5987 6515 +12747 3191 6102 6021 6455 +12748 3066 3140 5834 6103 +12749 1967 6093 5848 6494 +12750 6270 6461 2037 6622 +12751 554 6054 6739 7150 +12752 3381 6091 6129 6477 +12753 3621 6165 5924 6430 +12754 5759 4872 6183 6272 +12755 2461 2523 5820 6680 +12756 6202 6462 1604 6463 +12757 4849 6070 6050 6265 +12758 2392 6162 6161 6717 +12759 474 4558 6014 6928 +12760 258 5991 6423 6779 +12761 5850 6366 6108 6855 +12762 4923 5971 4848 6433 +12763 5173 5965 5786 6831 +12764 5801 5868 4640 6338 +12765 6025 6178 2182 6600 +12766 5039 5040 4795 6536 +12767 5799 5860 5325 6390 +12768 2382 5854 2485 6793 +12769 4416 4208 5837 6066 +12770 5779 5859 4792 6835 +12771 2120 5812 1641 6450 +12772 5849 4813 6158 7142 +12773 5277 5172 6021 6455 +12774 4493 5768 4561 7089 +12775 601 5939 5863 6052 +12776 2018 6395 5982 6601 +12777 5291 5787 5786 5792 +12778 1710 5851 5954 5973 +12779 1711 5852 5955 5974 +12780 611 6631 5827 6736 +12781 3354 3544 3508 5972 +12782 6007 6117 5256 6713 +12783 572 5882 6491 6758 +12784 2148 5769 1753 6026 +12785 5823 6054 5782 7116 +12786 1420 6701 6640 6781 +12787 5330 5329 5755 5902 +12788 3065 5868 5801 6338 +12789 5776 6402 2904 6831 +12790 4516 6672 5988 7086 +12791 5765 6129 3294 6339 +12792 5075 6665 5795 7168 +12793 5755 5902 5329 5975 +12794 5165 5770 5209 6621 +12795 5429 5920 6325 7007 +12796 5976 6158 4813 7142 +12797 5643 5719 6640 6781 +12798 4389 4057 5769 6025 +12799 4712 5866 5867 7160 +12800 5429 6325 6234 7007 +12801 2162 6126 1730 6505 +12802 4668 6075 6069 6647 +12803 5543 3899 3678 6564 +12804 5159 6173 6172 6275 +12805 4699 5985 5962 6394 +12806 3040 2613 5841 6363 +12807 5839 6300 3353 6567 +12808 3820 5827 6736 6887 +12809 5110 6050 4850 6265 +12810 1667 5994 5958 6076 +12811 2531 6051 5911 6159 +12812 5293 5839 5292 6496 +12813 2506 5805 2521 6523 +12814 5007 4599 5824 5831 +12815 5075 5795 6273 7168 +12816 2906 5914 3575 6542 +12817 6004 7166 6130 7167 +12818 4340 6352 6066 6934 +12819 5828 5971 5941 7179 +12820 5898 5978 2646 6750 +12821 4164 5756 4490 5788 +12822 28 5767 5995 6141 +12823 5820 5896 4863 6229 +12824 2524 2379 5830 6582 +12825 4082 5967 5977 6175 +12826 5202 6129 6091 6477 +12827 3230 5758 3557 5824 +12828 3087 5926 5925 6480 +12829 4411 496 495 6000 +12830 5193 6216 6056 6910 +12831 4881 5233 6158 6745 +12832 4832 5847 6484 6861 +12833 5755 5902 2764 5985 +12834 4345 6375 6064 6376 +12835 5862 7000 5916 7189 +12836 5797 6126 2162 6505 +12837 5193 6056 6239 6910 +12838 1705 6242 6055 6681 +12839 2605 6366 6473 7162 +12840 2371 2296 5754 6889 +12841 6701 6781 1420 6841 +12842 2439 6013 5857 6606 +12843 2127 1823 6211 7087 +12844 1822 6149 6151 6535 +12845 4740 4812 5275 6021 +12846 5272 6243 6021 6455 +12847 1670 6118 2018 6395 +12848 601 6052 5863 7007 +12849 6333 6411 4614 6477 +12850 6024 6056 5155 6402 +12851 1862 5876 6396 6671 +12852 2702 6402 6056 6831 +12853 4855 6028 6299 6945 +12854 4246 5836 486 6465 +12855 6416 6476 634 6585 +12856 4812 6021 4740 6555 +12857 451 6126 6505 7026 +12858 3238 5870 3300 6231 +12859 5283 5771 4885 5834 +12860 3230 5824 5826 7077 +12861 4670 5777 5918 6823 +12862 1675 6113 5952 6283 +12863 5887 6695 6246 6755 +12864 5212 6239 5787 6358 +12865 5845 6202 1597 6463 +12866 5395 5427 6241 6856 +12867 4291 6403 6142 6796 +12868 1810 6460 6242 7015 +12869 2643 5846 5847 6504 +12870 5951 6270 4413 6386 +12871 3358 6181 6219 6921 +12872 3077 6390 5897 6962 +12873 5832 5926 2731 7021 +12874 4485 5845 4290 6316 +12875 6101 6330 4977 6738 +12876 2637 6183 6030 6272 +12877 6069 6075 5056 6213 +12878 6332 6333 4614 6477 +12879 5260 6252 6552 6713 +12880 3528 5772 3205 6480 +12881 3109 5902 3110 5975 +12882 5911 6051 4820 6159 +12883 3887 6633 6529 6790 +12884 1401 6634 6528 6791 +12885 5754 6674 6264 7038 +12886 1502 1281 6758 6775 +12887 4629 6053 5360 6195 +12888 3557 5758 3230 7077 +12889 2094 1651 2048 6286 +12890 2641 3176 5801 6372 +12891 4987 5791 5790 6710 +12892 3755 5851 3948 5973 +12893 1269 5852 1462 5974 +12894 5398 6295 6068 6598 +12895 4625 6050 6070 6454 +12896 6336 6346 4630 6573 +12897 632 6751 6674 7038 +12898 2159 5900 5899 6449 +12899 3075 5873 5765 6985 +12900 3038 5883 5841 6542 +12901 3797 5797 5798 6882 +12902 5759 6183 4872 7147 +12903 4272 5812 6107 6328 +12904 5258 6444 6427 6668 +12905 4786 4901 6108 6855 +12906 5312 573 6274 6968 +12907 3757 6774 6529 7009 +12908 1271 6771 6528 7011 +12909 577 5981 6366 6473 +12910 5816 5817 2189 6778 +12911 5311 5965 5923 6708 +12912 495 6000 5974 7074 +12913 5836 6192 1894 6501 +12914 3639 6160 5988 6520 +12915 6137 6317 3566 6643 +12916 3570 6030 2637 6183 +12917 2159 1729 5900 6449 +12918 5677 1521 6770 6874 +12919 4007 6773 5519 6873 +12920 5069 6339 5912 6382 +12921 2738 5941 2926 6511 +12922 1754 2007 1998 5802 +12923 5770 5841 3041 5883 +12924 3066 5834 5773 6103 +12925 4850 6265 6050 7016 +12926 1862 6146 5876 6671 +12927 4776 6693 6083 6816 +12928 4108 6134 5848 6859 +12929 2707 6413 3218 6869 +12930 5677 6770 1521 6771 +12931 4007 5519 6773 6774 +12932 3065 3175 2631 6338 +12933 5823 6257 6937 7179 +12934 2437 2915 5794 7152 +12935 5772 5911 5337 6502 +12936 5346 6095 5913 6742 +12937 1850 5935 6073 7192 +12938 4446 6286 5848 6494 +12939 1994 2093 5756 5788 +12940 4634 5353 6030 6573 +12941 5059 6237 5777 6431 +12942 5543 6772 5506 6924 +12943 5038 4790 5037 6259 +12944 4933 5983 4574 7124 +12945 6076 6211 1823 7087 +12946 3337 5861 5860 6670 +12947 4815 4814 5976 7142 +12948 5613 6632 6851 6955 +12949 4040 6151 6149 6535 +12950 2931 3154 5908 6047 +12951 3284 6021 6343 6522 +12952 4663 6106 6363 6447 +12953 6001 6200 5418 6268 +12954 5428 600 6052 6266 +12955 4953 4918 6104 6402 +12956 5100 5867 4791 5978 +12957 6528 6634 1401 6867 +12958 3887 6529 6633 6868 +12959 2650 2531 5911 6159 +12960 4736 6020 5887 6768 +12961 5533 5505 6529 7009 +12962 5663 6528 5691 7011 +12963 3621 6430 5924 7136 +12964 4855 6028 5794 7035 +12965 1501 6675 6637 6758 +12966 3987 6676 6638 6757 +12967 2938 5778 6108 7064 +12968 5227 5980 5821 6496 +12969 2438 5856 2439 5857 +12970 6204 6205 4332 6376 +12971 4527 6121 6251 6302 +12972 6319 6452 6384 6506 +12973 3610 5781 445 5855 +12974 6290 7028 2086 7201 +12975 2174 6322 6278 7079 +12976 5312 5917 573 6968 +12977 4844 4843 6245 6652 +12978 5800 5862 5758 7189 +12979 4795 6414 5039 6536 +12980 3039 5841 5770 5842 +12981 5161 6087 6275 6424 +12982 2906 5914 6542 7022 +12983 6022 6739 6054 7150 +12984 5823 3119 6257 7179 +12985 5161 6275 6172 6424 +12986 4795 6246 6414 6536 +12987 2242 6435 6397 6586 +12988 3595 6251 6121 6302 +12989 2148 1753 5769 5960 +12990 474 6014 6365 6928 +12991 4953 6104 5776 6402 +12992 5059 6122 6237 6431 +12993 1664 2064 5877 6385 +12994 4618 6039 5800 6388 +12995 496 5974 495 6000 +12996 5756 6328 5812 7100 +12997 3181 5770 3180 6210 +12998 1960 1666 6624 7132 +12999 4389 4057 6025 6436 +13000 5010 6162 6161 6273 +13001 617 5916 616 7000 +13002 5424 6068 6116 6598 +13003 3629 6123 6362 6430 +13004 1850 6073 6677 7192 +13005 4866 6380 5931 6381 +13006 1625 1529 3808 1620 +13007 3345 6137 3566 6643 +13008 1710 5954 1943 5973 +13009 1711 5955 1944 5974 +13010 5818 6064 4295 6577 +13011 5802 4362 6537 7015 +13012 4389 6025 4221 6436 +13013 3781 6620 6509 6913 +13014 4860 5846 5153 5956 +13015 3762 3903 3704 6264 +13016 5952 6669 6341 7130 +13017 5802 6242 4362 7015 +13018 2153 6432 1638 6691 +13019 5118 6087 4947 6744 +13020 5402 6309 5414 6777 +13021 4600 4599 5758 5824 +13022 5871 5947 2188 6090 +13023 2950 5782 6099 7186 +13024 534 6020 4736 6768 +13025 5756 6450 2047 6578 +13026 2688 3017 2689 6617 +13027 2601 3015 2607 5927 +13028 1850 2034 6073 6315 +13029 4574 5983 4633 6551 +13030 577 6366 6125 6473 +13031 4509 6672 4516 7086 +13032 4804 5859 4792 6008 +13033 3358 6219 6212 6921 +13034 5016 4736 6020 6414 +13035 2643 6096 5846 6504 +13036 6136 6241 2313 6266 +13037 5981 2520 6366 6473 +13038 4650 6129 5765 6339 +13039 3610 5855 444 6768 +13040 6171 6296 5403 6679 +13041 4427 4125 5906 7115 +13042 3028 6237 6122 6431 +13043 4917 6105 5832 6659 +13044 4246 5994 5836 6465 +13045 4881 5976 5236 6745 +13046 5961 5206 6298 7197 +13047 2764 5755 2768 5902 +13048 4281 6432 5989 6691 +13049 516 6319 6384 6506 +13050 5038 5037 5794 6259 +13051 3515 5821 3388 6342 +13052 6142 6403 4291 6714 +13053 3875 3899 3733 6564 +13054 2837 5862 6038 6434 +13055 5113 6542 5883 7088 +13056 2071 6207 5895 6577 +13057 4670 5777 4671 5918 +13058 5428 6266 6052 6856 +13059 1998 5802 1720 6858 +13060 6151 6152 1984 6535 +13061 4876 6181 5957 6183 +13062 5822 6229 4731 6680 +13063 4883 5790 5771 6970 +13064 3307 6455 6263 7149 +13065 1804 6027 2131 6942 +13066 3535 3212 6195 6707 +13067 1642 6071 6312 6622 +13068 6110 6241 335 6439 +13069 2453 5789 5805 6764 +13070 5093 6075 5049 6174 +13071 4612 5873 5765 6870 +13072 5035 5874 6166 7101 +13073 5353 6212 6030 6573 +13074 2428 6976 6388 6977 +13075 4920 6104 5078 6915 +13076 4443 6146 4110 6614 +13077 2327 6296 6171 6679 +13078 6123 6253 3629 6362 +13079 6098 6167 5933 6685 +13080 5332 5221 5089 6082 +13081 4860 6495 4880 6839 +13082 6330 6738 3508 6843 +13083 5688 5732 570 6602 +13084 5050 6173 5160 6275 +13085 2524 5830 5774 6582 +13086 4479 4046 5807 7130 +13087 5304 5055 5779 6560 +13088 2452 6088 2706 6089 +13089 4417 6909 5876 7122 +13090 3704 6264 5754 6674 +13091 4655 5207 6105 7001 +13092 3307 6041 6455 7149 +13093 6068 6116 348 6119 +13094 2985 6576 5910 6656 +13095 2980 5780 6719 6920 +13096 6023 6218 6212 6929 +13097 4922 6109 5941 6660 +13098 1549 6323 5968 6428 +13099 2327 6171 6296 6435 +13100 2793 5971 5941 6433 +13101 372 5897 373 6185 +13102 6029 6930 6490 7188 +13103 4281 6120 6432 6691 +13104 627 6188 6124 6221 +13105 2557 6050 6070 6265 +13106 4416 4371 6066 7047 +13107 2748 5757 2656 7021 +13108 2718 6320 5869 6511 +13109 4121 6230 5996 6975 +13110 490 6485 6348 7156 +13111 2174 6278 5900 7079 +13112 5888 5990 4949 6709 +13113 4945 5042 5856 5857 +13114 1642 6072 6071 6622 +13115 1701 6139 5905 7146 +13116 4454 4121 5996 6975 +13117 5771 5834 5773 6941 +13118 4261 5769 6244 6357 +13119 5781 5924 3609 6169 +13120 423 6054 6022 6445 +13121 3087 3088 5925 5926 +13122 3574 6129 3381 6130 +13123 3354 3508 5839 5972 +13124 1959 6033 5877 6138 +13125 3648 3609 3594 5924 +13126 2853 2999 5775 5780 +13127 5195 5200 6276 6438 +13128 3917 3746 3926 5797 +13129 4404 6616 6018 6733 +13130 3100 5801 3176 6372 +13131 3259 6332 3258 6333 +13132 4890 6252 5914 6552 +13133 6017 6045 588 6857 +13134 334 333 6110 6329 +13135 3593 6123 3602 6253 +13136 5771 5790 3333 6970 +13137 5157 5819 6330 6662 +13138 2506 5875 5805 6523 +13139 4509 5948 6672 7086 +13140 6234 6285 2302 6325 +13141 2153 5989 6432 6691 +13142 2331 2307 6201 6628 +13143 5050 5084 6174 6275 +13144 3124 5795 3125 6727 +13145 6136 6478 2300 6854 +13146 4176 4447 5818 5967 +13147 5421 507 6209 6334 +13148 4387 5877 4426 6033 +13149 3487 6382 6289 6425 +13150 3657 5979 3602 6123 +13151 4444 4229 5928 6127 +13152 2112 6107 6090 6556 +13153 2364 2322 6067 6115 +13154 6004 6747 6130 7166 +13155 1607 1615 5836 6464 +13156 4118 4274 4239 6207 +13157 3547 5923 5909 6466 +13158 5015 6259 5881 6987 +13159 5783 6022 2808 7150 +13160 3167 6514 5800 7077 +13161 2744 6164 5998 6473 +13162 4541 5855 5781 5924 +13163 6017 6154 4995 6197 +13164 1664 5877 6033 6385 +13165 5502 5562 5472 6757 +13166 5720 5630 5660 6758 +13167 2759 2761 2764 5755 +13168 3167 6039 5800 6514 +13169 6353 6358 3493 6447 +13170 5091 6091 5202 6130 +13171 2591 5856 2438 5857 +13172 3116 6158 5814 6220 +13173 3337 5860 2693 6670 +13174 25 5798 5797 6882 +13175 6153 6290 2141 6625 +13176 2473 5814 6070 6646 +13177 2926 5941 3080 7179 +13178 6263 3453 6342 7194 +13179 5880 5406 6325 6518 +13180 5015 5880 6259 6987 +13181 5374 6241 6136 6266 +13182 2702 6056 6024 6831 +13183 6110 6157 2350 6234 +13184 5348 6300 5839 6567 +13185 2042 6350 6225 7056 +13186 2724 6124 2727 6221 +13187 3628 6313 5833 6445 +13188 1751 6204 5840 6376 +13189 4455 5844 6441 7176 +13190 2326 6234 6157 6285 +13191 2183 5905 5844 6949 +13192 4786 6855 6108 7049 +13193 6188 6221 626 6240 +13194 4192 6079 5991 7095 +13195 5786 5787 3546 5792 +13196 5134 5757 6037 6553 +13197 5823 6937 3119 7179 +13198 3645 5796 218 6261 +13199 479 6194 5991 6423 +13200 5221 5089 6082 6425 +13201 5866 5014 6259 7152 +13202 4714 6451 4712 7160 +13203 265 6093 5946 6094 +13204 6056 6216 5280 6486 +13205 6499 6569 582 6729 +13206 5803 5804 27 6883 +13207 6313 6445 3628 6739 +13208 5091 5331 5202 6091 +13209 5955 5974 496 6000 +13210 2840 6392 5986 6643 +13211 4404 6310 6616 6733 +13212 2605 6473 6125 7162 +13213 4815 5975 4814 7142 +13214 5358 6345 6163 7158 +13215 5946 6303 472 6442 +13216 3613 6307 6160 6520 +13217 5211 5113 4651 5841 +13218 6855 7049 6189 7195 +13219 5021 6239 5212 6358 +13220 3952 6521 5916 6735 +13221 3077 5825 6390 6962 +13222 5873 6342 4609 6908 +13223 4526 6077 5796 7062 +13224 2192 6537 5953 7015 +13225 3544 5972 3354 6813 +13226 4175 4375 6167 6168 +13227 6058 6059 4689 6437 +13228 5393 6116 6321 6598 +13229 2283 6294 6284 6387 +13230 1819 6186 1732 6558 +13231 1822 6151 1984 6535 +13232 6172 6275 3143 6424 +13233 1824 6395 6025 6600 +13234 3982 5950 5949 6863 +13235 6016 6699 564 7060 +13236 6043 6109 6042 6660 +13237 6066 6352 4340 6677 +13238 1850 6073 5935 6315 +13239 477 6308 6260 6418 +13240 326 5995 5767 6141 +13241 4600 5824 5758 5826 +13242 6533 6602 570 6775 +13243 2717 5869 2716 6109 +13244 4274 5817 4239 6207 +13245 2071 1870 6207 6577 +13246 5211 5113 5841 5883 +13247 5424 6116 5393 6598 +13248 6116 6209 507 6334 +13249 5688 6533 570 6775 +13250 4949 5990 5054 6709 +13251 3283 2716 6044 6109 +13252 3100 6148 5801 6372 +13253 560 6632 6571 6860 +13254 5020 4745 5325 5799 +13255 1607 5836 252 6465 +13256 2139 6145 6144 6193 +13257 2899 6218 6212 6219 +13258 3581 6181 6180 6845 +13259 5543 3678 3899 6924 +13260 4920 5078 6197 6915 +13261 1226 6632 1419 6743 +13262 487 5796 4560 6262 +13263 3180 2971 6210 6621 +13264 3238 5892 5870 6231 +13265 4161 4211 6226 6326 +13266 3620 6362 6165 6430 +13267 4404 6149 6018 6616 +13268 3560 5892 3238 6231 +13269 1749 2084 5974 7074 +13270 6333 6342 3453 7194 +13271 4786 6189 6855 7049 +13272 6027 6222 2131 6942 +13273 4810 5927 6217 6236 +13274 3657 3602 3593 6123 +13275 3733 6645 3899 6772 +13276 442 6430 6020 7076 +13277 4405 5946 6406 6494 +13278 2300 6478 2315 6854 +13279 1998 1720 5871 6858 +13280 6289 6339 5064 6382 +13281 3566 6317 6137 6434 +13282 4665 5256 6117 6713 +13283 2824 6122 3028 6237 +13284 2704 6148 5785 7161 +13285 5845 6316 2140 6779 +13286 4942 5794 4855 6945 +13287 2330 6135 6136 6266 +13288 4416 6734 4371 7047 +13289 4850 6050 5110 7016 +13290 5879 6123 441 7076 +13291 4290 6316 5845 6779 +13292 5450 6593 5514 6801 +13293 5608 6594 5672 6802 +13294 5768 6077 4493 6190 +13295 6228 6332 3326 6333 +13296 1597 6202 5845 6422 +13297 3547 5936 5923 6466 +13298 3055 6567 5829 6813 +13299 1421 3635 418 7090 +13300 2034 1793 6073 6315 +13301 5250 5315 6158 6220 +13302 5948 6313 3659 6462 +13303 3494 6243 6021 6522 +13304 5056 6008 6069 6213 +13305 5766 5795 3125 6215 +13306 554 5013 6054 7150 +13307 1711 1944 2154 5974 +13308 1710 1943 2155 5973 +13309 5206 6298 5247 6554 +13310 4947 6087 5856 6744 +13311 2570 5920 5893 5984 +13312 5153 5846 4860 6096 +13313 5362 5364 5961 6627 +13314 6053 6195 3332 6300 +13315 2056 1645 6410 6588 +13316 2729 6412 6009 7073 +13317 4694 6043 4819 6159 +13318 6131 3241 6512 7027 +13319 4741 6555 6046 7139 +13320 4286 6223 5999 7091 +13321 5078 6104 6258 6915 +13322 4880 6495 6096 6839 +13323 5335 5870 5897 6001 +13324 4855 6945 6299 7211 +13325 3055 5972 3544 6813 +13326 5757 6060 2748 6372 +13327 2941 3056 6269 6517 +13328 428 5988 6160 7039 +13329 4634 6030 6336 6573 +13330 1793 6073 6315 6377 +13331 5113 5883 5112 7088 +13332 5230 5993 5342 6507 +13333 4609 5873 4612 6870 +13334 5777 6236 5004 7078 +13335 5946 1977 6406 6494 +13336 3129 6606 2446 6744 +13337 5937 4689 6059 6437 +13338 5995 6141 326 6287 +13339 1967 1757 5848 6093 +13340 6490 6930 6168 7188 +13341 6105 6553 3481 7001 +13342 3319 5801 3146 6199 +13343 2465 2485 2382 5854 +13344 2193 6064 5840 6958 +13345 6200 6201 2307 6628 +13346 221 5948 1604 6202 +13347 3434 6298 5993 6842 +13348 6041 6101 4977 6738 +13349 4876 6183 5957 7138 +13350 1326 5998 1517 6125 +13351 2015 2188 5947 6090 +13352 6893 6907 3801 7031 +13353 5976 6508 5236 6745 +13354 6015 6381 6016 6761 +13355 6212 6218 5184 6219 +13356 2086 7028 6403 7201 +13357 2007 1720 1998 5802 +13358 1705 6242 6681 7072 +13359 5961 6298 6049 7197 +13360 5118 6275 6087 6744 +13361 1586 6306 6305 6308 +13362 4663 6117 6363 7148 +13363 6255 6306 4497 6592 +13364 6291 6292 513 6690 +13365 5277 6102 4978 6455 +13366 4303 6410 6205 7032 +13367 6583 6788 5625 6994 +13368 4283 6029 6490 7188 +13369 5075 5843 6665 7168 +13370 3583 5787 3465 5792 +13371 3881 3952 5916 6735 +13372 1604 5948 221 6462 +13373 2641 5801 6010 6372 +13374 4965 6272 5759 6590 +13375 1883 6556 6139 7146 +13376 4907 5912 6339 6849 +13377 4691 6043 6044 6109 +13378 5773 6103 5834 6627 +13379 1666 6944 6152 7132 +13380 5159 5160 6173 6275 +13381 2794 6104 2753 6258 +13382 4609 6411 5873 6870 +13383 2250 2251 6452 6506 +13384 2477 6236 5927 6799 +13385 5260 6552 6143 6713 +13386 3146 6199 5801 6651 +13387 4148 5890 6410 7032 +13388 5643 6781 6701 6841 +13389 5054 5990 6257 6709 +13390 3781 6509 6725 6913 +13391 5412 6777 6293 7066 +13392 3230 5826 5824 7020 +13393 5134 5913 5757 6553 +13394 5177 5339 5140 6466 +13395 560 561 6632 6860 +13396 4167 6196 6018 6796 +13397 263 2145 6093 6134 +13398 371 3077 5897 6962 +13399 2750 5757 2640 6010 +13400 5799 6231 2665 6711 +13401 5327 5773 5283 5834 +13402 1704 5818 6064 6958 +13403 2045 6635 5966 7131 +13404 1382 1242 5899 5900 +13405 6139 6357 1631 6601 +13406 2378 6417 5855 7098 +13407 4756 6358 6117 6612 +13408 4493 6077 5768 7089 +13409 4815 5849 5975 7142 +13410 3207 5870 5897 6711 +13411 4334 5992 4487 6356 +13412 4112 6139 5816 6601 +13413 6584 6821 5467 6989 +13414 3283 6043 2737 6109 +13415 4860 5846 5956 6839 +13416 4584 6353 6404 6448 +13417 3109 3110 5943 5975 +13418 5850 6366 2725 7162 +13419 4164 5788 4490 6328 +13420 1743 2127 6211 7087 +13421 5574 5530 6603 6604 +13422 6077 6190 5768 6797 +13423 4192 5991 4095 7095 +13424 4765 6263 6243 6455 +13425 5786 5909 3420 6708 +13426 6184 5390 6478 7063 +13427 2531 430 6051 6159 +13428 520 5423 6241 6331 +13429 565 6016 4569 6381 +13430 2782 6170 6015 6351 +13431 5786 5792 3420 5909 +13432 4983 5323 5772 6480 +13433 6049 6298 5206 7197 +13434 4629 6053 6195 6336 +13435 3039 5842 5770 6591 +13436 5756 4410 6328 7100 +13437 1427 2211 1322 5995 +13438 5407 5822 5793 6401 +13439 5184 5182 5186 6212 +13440 2160 1728 1954 6111 +13441 4965 6272 6590 7043 +13442 6136 6241 5423 6331 +13443 4754 6117 4756 6447 +13444 2428 6009 6388 6976 +13445 6191 6413 2707 6869 +13446 1569 6094 5946 6303 +13447 4632 5983 4633 6083 +13448 2808 423 6054 7150 +13449 6129 6130 3486 6339 +13450 1994 5788 5756 6142 +13451 6228 6314 5268 6626 +13452 2158 2072 5760 5838 +13453 4754 4756 6117 6612 +13454 5227 5821 5073 6496 +13455 4234 6410 6073 6677 +13456 6209 6479 2223 7213 +13457 4683 5757 6060 7021 +13458 523 6110 6157 6329 +13459 5999 6000 4116 6864 +13460 3881 6735 5916 6828 +13461 4860 5153 5046 5956 +13462 1731 5950 2161 6806 +13463 5643 6640 6701 6781 +13464 3378 6289 3295 6382 +13465 2169 1791 5994 6501 +13466 3547 2386 3536 5936 +13467 2160 6111 1954 6485 +13468 2617 2572 2376 5809 +13469 2648 2934 5898 5962 +13470 6221 6240 6188 6957 +13471 2743 5963 2745 7121 +13472 4208 5837 6066 7192 +13473 5898 5962 2934 6299 +13474 5043 5782 4779 5823 +13475 3692 6317 6604 6826 +13476 5052 5856 6606 6744 +13477 1642 6312 6071 6980 +13478 5391 6040 5387 6171 +13479 6141 6293 5412 6777 +13480 5881 6259 5880 6987 +13481 3155 5908 5883 7173 +13482 3646 3591 6022 6967 +13483 5799 6390 3135 7019 +13484 6051 6255 4497 6592 +13485 3103 6188 6240 6957 +13486 5774 6451 4715 7160 +13487 262 6254 6134 6418 +13488 467 6362 6165 6545 +13489 3490 6172 5923 6173 +13490 2524 5774 5830 6933 +13491 6253 6409 4547 6943 +13492 509 6153 6119 6443 +13493 461 5543 3678 6564 +13494 5213 6041 4977 6738 +13495 2915 5866 5794 7152 +13496 5319 5174 5173 6024 +13497 4613 6332 6228 6333 +13498 5391 5369 6040 7151 +13499 2930 5791 2929 5826 +13500 2531 2532 430 6159 +13501 4885 5771 4883 5790 +13502 5769 6436 1669 6726 +13503 4738 4728 4726 5782 +13504 4774 5886 6446 6808 +13505 6081 6319 306 6661 +13506 4110 6146 5876 6614 +13507 6534 6603 5530 6604 +13508 490 6111 6485 7156 +13509 5837 5838 2053 5935 +13510 3103 2727 6188 6957 +13511 2605 6366 2520 6473 +13512 3630 6123 6430 7076 +13513 5858 6286 2048 7170 +13514 481 5991 4290 6779 +13515 3013 6008 2580 6213 +13516 4698 5934 6374 6657 +13517 5897 6001 373 6628 +13518 2855 6364 5780 6639 +13519 4176 5967 5818 5977 +13520 5587 6907 7031 7207 +13521 4450 5982 5895 6734 +13522 5221 6425 6082 6426 +13523 5275 4740 6021 6795 +13524 3340 6336 6030 6573 +13525 2744 5998 2606 6473 +13526 3505 3124 5795 6215 +13527 5153 4878 5846 6096 +13528 5773 5961 2893 6742 +13529 5024 5942 5859 6608 +13530 6152 6624 1666 7132 +13531 4956 5970 4811 6161 +13532 3579 6143 6007 6888 +13533 4298 4208 6066 7192 +13534 6171 6268 5391 7151 +13535 1421 5919 1256 6453 +13536 4028 5895 4450 5982 +13537 1848 6356 6301 6432 +13538 3199 5778 3511 6500 +13539 2453 5805 5969 6764 +13540 1466 6689 6498 6901 +13541 5350 5792 5786 5909 +13542 2925 2844 5758 6885 +13543 5218 5957 5912 7147 +13544 2176 6076 2029 6588 +13545 2027 1631 6139 6357 +13546 2906 6252 5914 7022 +13547 610 5827 5775 7145 +13548 2654 2656 3555 5757 +13549 3108 5943 3110 5975 +13550 5859 6008 4804 7127 +13551 4837 6065 6353 6358 +13552 3294 6129 3486 6339 +13553 4086 6249 5959 6335 +13554 6022 6054 423 7150 +13555 6252 6713 4665 7148 +13556 2748 6060 5757 7021 +13557 5533 5505 5458 6529 +13558 5663 5616 5691 6528 +13559 363 6325 5880 6617 +13560 2378 5855 2492 6905 +13561 4461 6019 6153 6290 +13562 5983 6606 3129 6744 +13563 2808 6022 423 7150 +13564 2364 6067 2306 6115 +13565 4890 5914 4744 6936 +13566 1964 6706 6429 7006 +13567 6050 6380 6177 7016 +13568 5860 5861 3337 7019 +13569 2127 6211 1823 6377 +13570 5359 6489 5909 7084 +13571 4625 6050 4849 6070 +13572 5118 5117 4947 6087 +13573 4629 5360 5320 6195 +13574 3949 3948 3755 5851 +13575 1462 1269 1463 5852 +13576 3497 6970 6280 7144 +13577 1764 5756 2093 5788 +13578 4765 6263 6455 7149 +13579 369 5938 6135 7154 +13580 4459 6286 5808 7170 +13581 1809 1810 6055 6242 +13582 4994 5801 4640 6338 +13583 6179 6195 5320 6300 +13584 586 6321 6080 6470 +13585 5272 6021 5172 6455 +13586 5773 2893 6627 6742 +13587 6212 6218 2899 6929 +13588 6264 6751 633 7038 +13589 1314 1347 6903 6923 +13590 3833 6904 3800 6922 +13591 4422 5840 6064 6958 +13592 3613 6160 6307 6592 +13593 2808 5783 422 6022 +13594 547 4820 6051 6159 +13595 2743 6062 5963 7121 +13596 1774 6032 2180 6432 +13597 4257 5891 4454 5996 +13598 3692 6038 3891 6604 +13599 2192 6460 1810 7015 +13600 363 364 6325 6617 +13601 217 6262 5796 6370 +13602 3652 3595 6121 6302 +13603 2751 6389 5916 7000 +13604 3903 6264 3762 6751 +13605 4680 5790 4884 5791 +13606 6192 6419 487 7104 +13607 3038 3512 5883 6542 +13608 3344 5986 6137 6643 +13609 4214 6025 5769 6357 +13610 4832 4935 5846 6861 +13611 5260 4739 6007 6143 +13612 2637 5759 6183 6272 +13613 5330 5287 5329 5902 +13614 5784 6245 4843 6652 +13615 3020 5879 5868 6338 +13616 3684 6820 6821 6895 +13617 3125 5795 5766 6727 +13618 6061 6209 2223 7213 +13619 5776 6104 2754 6402 +13620 508 507 6116 6822 +13621 4945 5856 5042 6606 +13622 5399 6285 6234 6325 +13623 3610 445 444 5855 +13624 6108 7049 6855 7195 +13625 2064 1959 1664 5877 +13626 4860 6096 5846 6839 +13627 2331 6185 373 6628 +13628 3572 6035 6036 6502 +13629 6242 6460 6055 7015 +13630 1378 6088 1228 6089 +13631 4633 5983 4632 6551 +13632 6720 6905 5753 6938 +13633 5808 5858 2094 7033 +13634 6264 6674 6751 7038 +13635 1475 6499 5875 6729 +13636 3449 5765 5759 6985 +13637 1304 6766 6741 6997 +13638 4128 4261 5769 6244 +13639 6191 6215 3091 6792 +13640 1996 5951 1928 6286 +13641 4933 4574 6235 7124 +13642 374 6268 6200 6926 +13643 2980 5780 2741 6062 +13644 3833 3800 3666 6922 +13645 1314 1180 1347 6923 +13646 4461 6290 6153 6625 +13647 1809 6055 1810 6460 +13648 4432 6144 6493 7057 +13649 2361 6040 6171 6435 +13650 4337 4128 4348 6244 +13651 6228 6314 3326 6332 +13652 5782 5783 4738 6764 +13653 3385 3386 3384 6908 +13654 2703 5786 5965 6831 +13655 2075 6250 5761 6373 +13656 3786 2872 6038 6317 +13657 5860 6936 5861 7019 +13658 516 6384 515 6452 +13659 5327 5834 6103 6627 +13660 2378 5855 6905 7098 +13661 5902 5943 3111 6210 +13662 1804 6226 6027 6942 +13663 4387 5877 6033 6138 +13664 3087 5925 3088 6480 +13665 2906 6542 2905 7022 +13666 5968 6323 467 6428 +13667 3283 6044 6043 6109 +13668 5801 6148 2631 6338 +13669 5848 6368 4108 6859 +13670 1666 2147 6944 7132 +13671 4262 5840 6027 6204 +13672 4749 5860 5825 6390 +13673 2705 5785 2704 5811 +13674 2171 5982 6118 6734 +13675 2168 6100 1789 6311 +13676 2430 5794 6028 7035 +13677 4351 5891 4082 5977 +13678 1539 6642 5803 6794 +13679 4959 6217 6471 6683 +13680 2906 3575 2905 6542 +13681 5808 6286 5858 7170 +13682 520 6331 6241 6439 +13683 6139 2027 6357 7183 +13684 2646 5898 3219 5978 +13685 5359 5909 5321 7084 +13686 5731 6923 5650 6954 +13687 5492 5573 6922 6953 +13688 1431 1260 1440 5804 +13689 2079 1744 6034 6847 +13690 1733 2064 1969 6385 +13691 6090 4201 6516 6556 +13692 6068 6295 2312 6598 +13693 5819 5972 5179 6330 +13694 1931 2148 1753 6026 +13695 4444 6127 5928 7131 +13696 1569 5946 1564 6442 +13697 1322 1507 1427 5995 +13698 3050 2437 6259 7152 +13699 5359 5321 6063 7084 +13700 4765 6243 4763 6455 +13701 5349 6086 5301 6919 +13702 1977 6093 1864 6494 +13703 5983 6083 4632 6551 +13704 2369 6295 6045 6598 +13705 1577 6327 6260 6418 +13706 2379 2524 2465 6582 +13707 1944 5974 5955 7074 +13708 2894 2489 6075 6213 +13709 3292 6339 6289 6382 +13710 4877 5755 5975 6896 +13711 590 589 6017 6679 +13712 434 6302 5907 6832 +13713 3580 6130 6091 6747 +13714 1975 6375 6064 6577 +13715 5929 5942 2984 7175 +13716 2912 6031 5829 6512 +13717 3684 6636 6820 6895 +13718 5432 5391 6171 6268 +13719 4724 4731 4863 6680 +13720 2534 6240 6214 6608 +13721 3559 5758 2844 5831 +13722 3389 5821 6263 6342 +13723 5759 5765 3449 6849 +13724 4424 5848 4108 6134 +13725 6199 6495 4858 6839 +13726 1638 6432 6120 6691 +13727 5906 5915 4282 6335 +13728 4786 579 4901 6855 +13729 4290 5845 482 6779 +13730 5294 6216 5193 6910 +13731 6132 4296 6344 6817 +13732 2097 6254 1951 6568 +13733 4537 5768 4561 6190 +13734 477 4545 476 6260 +13735 2759 5755 2764 5985 +13736 2852 6235 6188 7124 +13737 1438 325 1427 1258 +13738 5149 6042 5157 6662 +13739 1322 5995 2211 6572 +13740 5340 5261 6166 7120 +13741 5758 5831 4599 6885 +13742 5870 5934 2815 6001 +13743 6021 4740 6555 6795 +13744 4416 5837 6734 7047 +13745 3621 3594 5924 6165 +13746 2753 2794 2754 6104 +13747 3292 5912 6339 6382 +13748 6595 6773 3925 6873 +13749 6596 6770 1439 6874 +13750 2636 6590 6272 7043 +13751 2352 6136 2300 6854 +13752 2670 6297 2669 6314 +13753 1960 6032 2147 7132 +13754 5067 6472 5811 6515 +13755 3635 1421 6453 7090 +13756 6117 3321 6447 7148 +13757 3917 3926 320 5797 +13758 6061 6479 6209 7213 +13759 5071 6340 6065 6630 +13760 5313 4923 4848 6433 +13761 593 6001 5418 6268 +13762 5955 6000 1944 7074 +13763 5801 6148 4980 6372 +13764 6467 6787 6249 7156 +13765 2071 5895 1870 6577 +13766 5129 5819 5053 6433 +13767 2238 6397 2241 6586 +13768 217 218 5796 6262 +13769 631 6716 6570 6730 +13770 5931 6966 6380 7140 +13771 482 4290 4485 5845 +13772 534 5016 4736 6020 +13773 5868 5879 4642 6338 +13774 4964 5096 5134 6037 +13775 5143 4634 6030 6336 +13776 4759 610 5775 7145 +13777 6005 6195 3282 6346 +13778 2022 6356 5992 6505 +13779 2230 6119 6116 6822 +13780 3354 5972 5839 6813 +13781 4802 6213 6214 7127 +13782 2517 6215 5904 6792 +13783 5909 6063 5321 7084 +13784 4167 6018 6403 6796 +13785 2124 5968 270 6256 +13786 4553 6306 6255 6308 +13787 5771 5993 5281 6280 +13788 5941 5971 3080 7179 +13789 2670 3435 6297 6314 +13790 3419 5909 3547 5923 +13791 3134 6143 5799 7019 +13792 4955 5819 4693 6660 +13793 5159 6172 5160 6275 +13794 1898 2163 5955 6098 +13795 1899 2164 5954 6097 +13796 2176 6377 6076 6588 +13797 4447 4176 5818 6836 +13798 3497 6074 6280 6970 +13799 1285 1202 1500 6016 +13800 5776 5125 6402 6831 +13801 4712 5866 6451 6982 +13802 2974 2789 6042 6660 +13803 4798 4800 6237 7052 +13804 3089 2731 5832 5926 +13805 5225 6065 5792 6630 +13806 1669 6025 5769 6726 +13807 3121 5850 2774 6366 +13808 1995 2053 5838 5935 +13809 2617 3780 2572 5809 +13810 2054 5977 5891 6975 +13811 1915 6144 6132 6193 +13812 5267 6228 4613 6332 +13813 1650 1994 5756 6142 +13814 5860 5938 2693 6670 +13815 3053 5829 3055 6567 +13816 2364 2322 2306 6067 +13817 2473 5814 3289 6070 +13818 5436 6141 5368 6309 +13819 4832 6484 4621 6861 +13820 5418 6001 593 6200 +13821 5313 6433 4848 6697 +13822 6076 6377 6211 7087 +13823 3099 6131 3241 6512 +13824 2833 2834 5914 7088 +13825 5783 5969 421 6077 +13826 2725 5850 3121 6366 +13827 2147 6032 5989 7132 +13828 4551 6313 5833 6672 +13829 1590 6194 1585 6305 +13830 6057 6311 1961 6559 +13831 5300 6281 5130 6507 +13832 5092 6091 6130 6747 +13833 1667 1985 2103 5994 +13834 2079 6034 6033 6847 +13835 3515 3386 5821 6908 +13836 3319 2641 3146 5801 +13837 520 6331 6439 7081 +13838 6241 6266 5395 6856 +13839 3351 3353 6300 6567 +13840 1709 5865 2077 5991 +13841 3762 6264 3704 6674 +13842 4163 4478 4332 6204 +13843 6014 6121 4494 6682 +13844 481 5991 6422 6423 +13845 6021 6243 3191 6455 +13846 3434 5993 6298 6554 +13847 3124 3125 2540 6727 +13848 4721 4722 6013 6623 +13849 5094 5832 4917 6037 +13850 3949 1903 3948 5851 +13851 1462 1463 1902 5852 +13852 5259 5965 5776 6424 +13853 3059 3535 6005 6707 +13854 601 600 5939 6052 +13855 2910 5829 6166 6512 +13856 3066 6103 5773 6627 +13857 2382 2379 2465 6582 +13858 4367 4291 6142 6796 +13859 516 6452 515 6506 +13860 5054 6257 5990 6737 +13861 4653 5270 5842 6363 +13862 2800 2590 6164 6446 +13863 4671 5777 4670 6823 +13864 2807 5782 2808 6054 +13865 1959 1664 5877 6033 +13866 2056 6377 2082 6588 +13867 4737 6080 585 6981 +13868 4924 4847 5941 6511 +13869 1775 2181 6138 6615 +13870 3502 6297 5993 6507 +13871 1869 5817 5816 6207 +13872 3457 3111 5943 6210 +13873 4800 5886 6237 7052 +13874 6056 6402 2882 6486 +13875 3348 6347 6281 6837 +13876 5221 6082 5332 6426 +13877 2650 5911 2977 6036 +13878 4379 6505 6356 7026 +13879 4427 5906 4328 5959 +13880 5770 5841 4652 5842 +13881 6184 6185 5390 7063 +13882 5824 5831 3056 6269 +13883 4176 5977 5818 6836 +13884 2439 3073 6013 6606 +13885 5998 6164 2590 6446 +13886 5399 6157 6234 6285 +13887 5414 6309 5402 6589 +13888 1597 6422 5845 6779 +13889 5007 5824 4902 6269 +13890 3009 6069 2894 6075 +13891 1668 5812 1980 6107 +13892 3570 2637 5759 6183 +13893 5805 5969 4733 6927 +13894 4731 5806 4723 5822 +13895 6078 6307 3641 6520 +13896 1808 5967 5818 6958 +13897 5049 6173 5050 6174 +13898 6087 3143 6275 6424 +13899 4742 4741 6046 7139 +13900 3450 6074 6277 6280 +13901 467 6428 6323 6545 +13902 6529 5505 6978 7009 +13903 5663 6979 6528 7011 +13904 1593 6423 6422 6779 +13905 3497 3333 3226 5790 +13906 1284 6543 5850 7162 +13907 4507 6165 5924 6169 +13908 3207 5897 3209 6711 +13909 574 4774 6446 6808 +13910 5079 6109 4922 6660 +13911 5065 6130 6004 6747 +13912 2465 5854 2382 6582 +13913 4812 6102 6021 6555 +13914 2352 2300 2315 6854 +13915 5657 6732 6649 6940 +13916 5499 6731 6648 6939 +13917 4443 4110 4355 6614 +13918 2302 6234 2326 6285 +13919 2312 6295 6068 6296 +13920 2097 6254 6568 6597 +13921 5007 5831 5824 6269 +13922 2933 5962 3525 6394 +13923 6117 6358 3438 6612 +13924 2091 1836 6386 6461 +13925 1943 5973 5954 6468 +13926 5331 5202 6091 6477 +13927 3094 5888 5778 7064 +13928 1308 1311 5803 6232 +13929 4788 6215 5904 6273 +13930 4982 6388 5800 7000 +13931 5069 4907 5912 6339 +13932 1580 6260 227 6308 +13933 2641 5801 3319 6199 +13934 6132 6133 4296 6817 +13935 1625 1620 3808 5922 +13936 3348 6288 6281 6347 +13937 4274 4070 5817 6207 +13938 509 6153 6360 7180 +13939 5014 4790 5866 6259 +13940 2022 6355 5992 6356 +13941 2888 6103 6096 6504 +13942 5340 6179 5261 7120 +13943 4653 5842 5841 6363 +13944 3762 6674 6459 6751 +13945 6227 6228 5268 6626 +13946 3630 441 6123 7076 +13947 2097 6568 6194 6597 +13948 4274 5816 4070 6207 +13949 6051 6160 3642 6592 +13950 1198 6787 6788 6881 +13951 1669 6726 6436 7033 +13952 4704 6096 6095 6103 +13953 6341 6669 6420 7129 +13954 441 5879 2680 6999 +13955 589 6295 6017 6679 +13956 5960 1965 6681 7072 +13957 2938 5778 5981 6108 +13958 1980 6107 5812 6328 +13959 2491 6173 6075 6174 +13960 2641 3318 3176 6372 +13961 2072 5760 5838 6599 +13962 5892 5934 4698 6657 +13963 1763 5816 2189 6778 +13964 1625 3808 1529 6575 +13965 4854 6028 5944 7068 +13966 3497 3333 6970 7144 +13967 4875 5962 4873 6299 +13968 2745 2742 5963 6364 +13969 6134 476 6327 6418 +13970 3082 2392 6162 6273 +13971 4530 6160 6051 6592 +13972 5967 6064 5818 6958 +13973 2513 2568 5863 5920 +13974 2250 2245 6384 6452 +13975 4523 4548 5979 6546 +13976 2523 5896 5820 6680 +13977 5436 5408 5767 6309 +13978 1716 6167 5933 6917 +13979 1810 6537 2192 7015 +13980 1193 6780 6594 6940 +13981 3679 6783 6593 6939 +13982 2601 5927 3161 6161 +13983 1934 1714 6369 7025 +13984 4340 4134 6352 6934 +13985 5957 7138 5912 7147 +13986 5994 6211 1743 6465 +13987 6026 6055 4415 6681 +13988 5188 6218 6023 6929 +13989 2364 5822 2322 6115 +13990 4845 4844 4843 6245 +13991 4539 5969 6077 7089 +13992 4720 4760 4734 5775 +13993 3250 6390 5860 7019 +13994 4488 4356 5764 6544 +13995 6134 6254 476 6418 +13996 3786 6038 3692 6317 +13997 4574 4933 4633 5983 +13998 2273 6329 334 6439 +13999 1659 6337 6206 6833 +14000 2642 6104 2755 6576 +14001 2155 5973 1943 6468 +14002 2459 6099 5823 6709 +14003 1867 6140 6661 6946 +14004 1957 6315 6156 6377 +14005 3182 2723 6042 6662 +14006 633 5410 25 7038 +14007 3648 5924 3594 6165 +14008 5403 6296 6171 6435 +14009 554 6739 6022 7150 +14010 5230 5281 5993 6280 +14011 4890 6552 5914 6936 +14012 4982 4768 616 7000 +14013 582 5805 4733 6927 +14014 5186 5356 6023 6212 +14015 1860 1735 6204 6605 +14016 2930 5791 5826 7020 +14017 3547 3536 5923 5936 +14018 4474 6532 4471 6599 +14019 5313 4848 6031 6697 +14020 3091 6191 5766 6215 +14021 5195 6276 6011 6438 +14022 1353 1478 6048 6571 +14023 1398 6016 1202 7060 +14024 4422 6226 5840 6958 +14025 2749 2748 6060 6372 +14026 4786 6189 579 6855 +14027 5393 6321 6116 6334 +14028 2291 6287 6147 6911 +14029 6260 6327 476 6418 +14030 4503 6302 6251 6456 +14031 4680 5790 5791 7182 +14032 1899 2164 6097 7118 +14033 4741 6035 6555 7139 +14034 5050 5160 5084 6275 +14035 332 6157 2279 6387 +14036 1719 2037 6461 6622 +14037 6422 6423 5991 6779 +14038 474 4558 473 6014 +14039 6228 6333 3325 6609 +14040 2477 5927 6481 6799 +14041 6061 6355 2167 6624 +14042 4501 4509 4516 6520 +14043 2974 6042 2789 6043 +14044 583 6229 5822 6401 +14045 2815 6001 5934 6926 +14046 3541 3542 5819 6330 +14047 381 6080 6321 6470 +14048 5400 6068 5375 6598 +14049 4492 4542 5924 6169 +14050 3757 6529 6978 7009 +14051 1271 6528 6979 7011 +14052 5967 5977 2151 6836 +14053 532 5781 4541 5855 +14054 6134 6327 1581 6418 +14055 4119 5808 5858 7170 +14056 1564 5946 266 6442 +14057 2330 6136 2313 6266 +14058 4331 5953 5807 6537 +14059 3055 3544 3354 6813 +14060 1764 2093 5756 6328 +14061 4811 5970 5927 6161 +14062 3293 3135 5799 6390 +14063 567 5931 6191 7128 +14064 2241 6292 2239 6586 +14065 542 5894 6302 6696 +14066 6238 6429 6225 6579 +14067 4994 6148 5801 6338 +14068 2721 3080 5941 5971 +14069 3443 3444 6425 6426 +14070 1898 2163 6098 7171 +14071 362 2360 5881 6987 +14072 2745 2743 2742 6364 +14073 5779 5986 5304 6560 +14074 4948 5033 4949 5778 +14075 2641 6010 5801 6199 +14076 5945 6392 2661 6643 +14077 529 6287 6147 7034 +14078 1517 5998 1351 7014 +14079 4720 5775 6695 6755 +14080 2174 1657 6322 7079 +14081 1717 5932 1936 6440 +14082 4123 4283 6029 6490 +14083 4516 4551 5833 6672 +14084 3528 6046 5772 6480 +14085 2980 6719 2747 6920 +14086 3609 5781 3610 5924 +14087 4538 5781 532 6905 +14088 2992 5985 5902 6400 +14089 5884 5963 2935 6364 +14090 3107 5938 5937 6670 +14091 502 6741 6766 6997 +14092 3557 5758 3559 5824 +14093 2318 6185 2331 6201 +14094 4510 6255 6092 6308 +14095 5396 6157 6110 6234 +14096 5106 6155 5107 6514 +14097 3368 6542 6058 7173 +14098 5071 6065 5225 6630 +14099 4819 6043 6036 6159 +14100 4778 5889 5888 6099 +14101 634 5995 5767 6416 +14102 2386 5936 2383 6173 +14103 5425 6321 6045 6598 +14104 5865 5991 1709 6079 +14105 1881 5928 6127 7131 +14106 5763 5890 2029 7099 +14107 2889 6096 2890 6103 +14108 5274 5792 5225 6065 +14109 5836 6192 487 7104 +14110 1421 418 1256 5919 +14111 3195 6257 3119 7179 +14112 5325 5799 4745 6936 +14113 2243 6291 2241 6397 +14114 4507 5924 4542 6169 +14115 2761 5755 2759 5985 +14116 3791 7031 6907 7207 +14117 5106 6155 6039 6279 +14118 5340 6166 6707 7120 +14119 5853 6310 4263 6525 +14120 5214 4977 6330 6738 +14121 539 5987 540 6515 +14122 2643 5847 2848 6504 +14123 4734 5775 4760 7098 +14124 5608 6594 6802 6931 +14125 6593 6801 5450 6932 +14126 3033 5903 5772 5911 +14127 495 5762 6474 7074 +14128 2840 5986 3344 6643 +14129 2243 310 6291 6397 +14130 1667 1985 5994 6076 +14131 2473 3021 5814 6646 +14132 5118 5117 6087 6275 +14133 5543 6645 5594 6772 +14134 5940 6349 1756 6578 +14135 542 6302 4817 6696 +14136 4368 5946 4405 6494 +14137 1675 5952 1874 6283 +14138 4743 5860 5325 6936 +14139 495 6474 6000 7074 +14140 4171 6396 4226 6671 +14141 3125 5795 3124 6215 +14142 1823 6076 2176 6377 +14143 5012 5782 5043 6054 +14144 5763 5958 4139 6076 +14145 5061 5049 6075 6173 +14146 4410 4490 5756 6328 +14147 4798 6237 6122 7052 +14148 2927 6109 2789 6660 +14149 428 6160 6044 7039 +14150 2002 1804 5840 6027 +14151 372 371 5897 6962 +14152 5125 5155 6402 6831 +14153 5291 5196 5786 5787 +14154 6004 6224 7166 7167 +14155 2754 5776 2755 6104 +14156 4743 5861 5860 6936 +14157 4987 5997 5791 6710 +14158 6100 527 6311 6718 +14159 5396 5430 6157 6234 +14160 540 5987 6421 6515 +14161 1823 2127 1985 7087 +14162 4712 5867 4714 7160 +14163 5291 5786 5350 5792 +14164 6584 6922 3991 6989 +14165 2521 5805 5789 6523 +14166 1720 5947 5871 6858 +14167 5799 6143 2666 6231 +14168 4616 6084 6163 6345 +14169 4875 6299 4873 7211 +14170 3223 6070 5849 7159 +14171 5643 5747 6781 6841 +14172 6055 6681 6242 7015 +14173 5093 5056 6075 6213 +14174 5998 6746 1255 6974 +14175 5543 461 3678 6924 +14176 2016 1804 2131 6942 +14177 4510 6092 4545 6308 +14178 5781 5855 532 6905 +14179 3394 6049 5961 6298 +14180 1967 5848 6286 6494 +14181 4733 5805 5789 5969 +14182 5796 6022 3591 6967 +14183 486 5836 6262 6464 +14184 3108 3109 3110 5943 +14185 5789 5969 5805 6764 +14186 2876 6082 6426 6427 +14187 1804 2002 5840 6226 +14188 4877 5755 5329 5975 +14189 6006 1781 6475 6535 +14190 531 6720 6503 6938 +14191 632 6459 6674 6751 +14192 4713 5014 5866 6982 +14193 5258 6304 6444 6668 +14194 4709 6143 5799 6231 +14195 4683 6037 5757 7021 +14196 6124 6221 2724 7110 +14197 6319 6384 306 6661 +14198 3322 6272 6053 7043 +14199 2247 6452 6292 6690 +14200 4441 6344 4296 6817 +14201 2168 6311 1895 6718 +14202 529 6449 6147 6911 +14203 4504 6253 6123 6362 +14204 2984 5942 5929 7013 +14205 1378 1436 2706 6089 +14206 5818 5977 5967 6836 +14207 371 3077 372 5897 +14208 5885 6254 4075 6859 +14209 5384 6110 6052 6234 +14210 5430 5399 6157 6234 +14211 2750 5757 6010 6767 +14212 445 5855 5781 6905 +14213 4417 4050 6909 7122 +14214 5321 6063 5909 6466 +14215 3434 3435 6298 6842 +14216 2370 6116 6068 6598 +14217 1446 2084 1828 5762 +14218 3932 2085 1829 5761 +14219 1198 6629 6787 6881 +14220 5238 6043 4694 6159 +14221 3532 2653 3482 5832 +14222 5947 5960 1649 6516 +14223 6025 6178 4221 6726 +14224 4744 5914 5861 6936 +14225 3388 5821 3389 6342 +14226 2183 6107 5905 6949 +14227 4989 6197 6154 6656 +14228 3146 5801 2976 6651 +14229 5838 6079 5935 7095 +14230 4390 4282 5915 6335 +14231 2930 2929 2937 5826 +14232 5348 5839 5180 6567 +14233 3107 5937 6437 6670 +14234 5519 5586 5444 6873 +14235 5677 5744 5602 6874 +14236 3448 6183 5759 7147 +14237 5971 6433 2793 6697 +14238 1669 6436 5769 7033 +14239 3787 6440 461 7061 +14240 1827 5812 1668 6107 +14241 5890 6588 2029 7099 +14242 5998 6974 1351 7014 +14243 374 6200 6001 6926 +14244 3655 227 228 6092 +14245 5327 5773 5834 6627 +14246 5366 6063 6345 6986 +14247 2650 2531 2977 5911 +14248 5775 6417 4760 7098 +14249 6583 6923 1505 6994 +14250 4074 6055 6386 6461 +14251 4201 6090 4113 6556 +14252 6301 6369 451 7026 +14253 4030 6315 6073 6377 +14254 3444 6382 3297 6425 +14255 582 5919 5805 6927 +14256 4875 4856 6299 7211 +14257 4679 6404 6425 6426 +14258 2090 2188 1782 6880 +14259 4960 6058 5908 7109 +14260 3369 6343 5925 6659 +14261 5792 5909 5350 6489 +14262 364 5920 6325 6617 +14263 3718 5916 3952 6521 +14264 6503 6720 5753 6938 +14265 3506 6297 6288 6565 +14266 2185 6113 6114 6740 +14267 430 2532 429 6159 +14268 1431 1440 247 5804 +14269 467 4556 6165 6362 +14270 3222 5814 3117 5849 +14271 2518 6162 5904 6273 +14272 1993 5899 2159 5900 +14273 4487 6355 4310 6356 +14274 1284 5850 2725 7162 +14275 593 6001 6268 6926 +14276 5773 5961 5362 7135 +14277 5561 6641 5485 6913 +14278 3602 6546 5979 7048 +14279 2871 3893 6038 7093 +14280 3990 3743 5753 6720 +14281 4694 4819 5284 6159 +14282 4836 6340 5071 6630 +14283 2187 6368 5848 6859 +14284 5882 6758 571 6775 +14285 4990 5893 5920 5984 +14286 4123 6029 4283 7188 +14287 5104 4633 5983 6083 +14288 5839 5972 3508 6843 +14289 2947 5806 2945 6623 +14290 5677 5602 6771 6874 +14291 5519 5444 6774 6873 +14292 2853 2855 5780 6639 +14293 5991 6079 4192 6316 +14294 2808 5782 2949 5783 +14295 4444 4109 4229 6127 +14296 6090 6328 5871 6991 +14297 5767 5995 326 6902 +14298 5340 6707 6179 7120 +14299 6088 6247 2450 7117 +14300 4509 6520 6078 7086 +14301 4813 4815 4814 5976 +14302 5061 6075 5936 6173 +14303 3090 6454 5931 6792 +14304 617 616 4768 7000 +14305 3055 3354 6567 6813 +14306 3106 5985 5962 6786 +14307 2164 5954 6547 6740 +14308 5272 5172 6243 6455 +14309 3612 6112 5987 6682 +14310 1693 5966 5928 7131 +14311 5855 5887 4716 6695 +14312 2459 5823 3119 6257 +14313 2999 5780 2979 6246 +14314 5428 5377 6266 6856 +14315 2524 5774 2465 6582 +14316 4860 5956 6199 6839 +14317 3014 5918 3011 6005 +14318 2322 5793 2323 6067 +14319 440 6123 441 6999 +14320 5183 6212 5184 6219 +14321 4631 6336 6195 6346 +14322 2491 6075 2489 6469 +14323 4409 4115 6132 6144 +14324 6008 6069 3013 6613 +14325 582 6569 5658 6729 +14326 631 6570 5500 6730 +14327 4393 5958 5994 7087 +14328 5818 5967 4043 6064 +14329 4173 5817 5905 6992 +14330 4902 6269 5824 6517 +14331 5921 6150 2946 6517 +14332 3117 5849 5814 6158 +14333 3439 6065 5787 6358 +14334 2965 2803 5963 5964 +14335 5819 6042 2723 6662 +14336 5802 6537 4362 7141 +14337 567 6191 6413 7128 +14338 1773 6057 6029 6490 +14339 6323 6428 1548 6545 +14340 3307 3388 5821 6263 +14341 4964 5757 4683 6037 +14342 4389 5769 4214 6025 +14343 4790 5038 4789 6872 +14344 1305 6955 6722 6956 +14345 6288 6297 3506 6507 +14346 4262 6027 5840 6226 +14347 6058 6542 2836 7088 +14348 4938 6257 5044 6709 +14349 3408 3407 6046 6480 +14350 5957 6082 5090 6748 +14351 2471 6070 6050 6454 +14352 5269 5268 6228 6314 +14353 2185 1796 6113 6740 +14354 3256 5943 3108 5976 +14355 5872 6196 4329 6991 +14356 4771 4792 5859 6835 +14357 6333 6342 4603 6411 +14358 4251 6386 6270 6461 +14359 5993 5342 6507 6842 +14360 5436 5767 5409 6141 +14361 1285 1202 6016 6089 +14362 5294 5193 6239 6910 +14363 5797 319 6383 6505 +14364 3389 5821 3388 6263 +14365 4636 5778 4949 5888 +14366 6023 6212 2899 6929 +14367 3142 6424 5776 6831 +14368 1395 6498 6413 6827 +14369 5897 6390 3209 6711 +14370 1822 6149 2128 6151 +14371 2506 2530 5875 6523 +14372 3541 5819 2723 6662 +14373 5880 6518 2360 6987 +14374 4616 6163 5358 6345 +14375 4273 5808 4459 6286 +14376 4656 5207 4655 7001 +14377 4112 4285 6357 6601 +14378 6048 6582 5830 7107 +14379 5188 5234 6218 6929 +14380 1937 6312 6271 7187 +14381 3256 5976 3108 7142 +14382 6397 6435 2242 6990 +14383 5765 6849 5759 6985 +14384 4646 5013 6054 6445 +14385 3153 2968 6058 6437 +14386 5885 4075 6368 6859 +14387 4658 6227 6522 7102 +14388 5793 6318 504 6566 +14389 2902 6361 6208 7027 +14390 1878 6193 6132 6379 +14391 4172 4342 5952 6635 +14392 3525 5962 3106 5985 +14393 3503 5814 3021 6162 +14394 3457 3185 6210 6304 +14395 5933 6098 499 6167 +14396 2783 2646 5978 6750 +14397 2156 1783 2071 5982 +14398 4990 5018 4974 5863 +14399 2780 6170 5867 6247 +14400 4927 6047 5985 6394 +14401 5113 5841 5883 6542 +14402 3746 3998 3926 5797 +14403 2242 344 6435 6586 +14404 4058 6066 5895 6375 +14405 4747 4721 6013 6371 +14406 5408 6793 608 7165 +14407 4337 4348 5960 6244 +14408 1804 2016 6226 6942 +14409 3734 3932 5761 5973 +14410 2162 5797 1992 6126 +14411 4867 5859 6214 6608 +14412 5840 6027 1804 6226 +14413 6243 6609 6263 7194 +14414 2097 1951 6254 6597 +14415 5018 5863 4990 5920 +14416 4282 5915 5906 6909 +14417 574 6446 5835 6808 +14418 1314 6903 1347 6954 +14419 3833 3800 6904 6953 +14420 4598 4600 4599 5758 +14421 3646 422 3614 6967 +14422 3990 5753 3908 7083 +14423 4286 5999 6396 7091 +14424 6029 2032 6490 6930 +14425 1917 6140 6441 6706 +14426 258 6423 1593 6779 +14427 1743 1985 2127 7087 +14428 5061 5048 5049 6173 +14429 5842 6106 5266 6444 +14430 2453 5789 3024 5805 +14431 4028 5895 5982 6207 +14432 4617 6466 6084 7097 +14433 4196 6312 6071 6622 +14434 2891 6096 6095 6495 +14435 4800 5025 5886 7052 +14436 4877 6896 5849 7159 +14437 219 6462 6261 6464 +14438 4723 5806 4731 6680 +14439 4084 5952 6113 6283 +14440 2359 6293 6777 7066 +14441 5785 5811 2917 6515 +14442 4731 6229 4863 6680 +14443 5280 6216 4825 6486 +14444 5092 6130 5065 6747 +14445 5374 6136 6135 6266 +14446 3332 6195 6053 6336 +14447 4634 6336 4630 6573 +14448 5272 6021 6243 6522 +14449 3148 5861 3337 6670 +14450 6034 6385 4052 6980 +14451 6177 6351 3328 6380 +14452 1791 5958 5994 6501 +14453 5395 5377 5427 6856 +14454 3781 6509 6620 6723 +14455 1292 3218 6413 6869 +14456 2360 362 5880 6987 +14457 222 6078 5948 6202 +14458 5958 6076 5763 7115 +14459 5398 6068 5400 6598 +14460 2954 5828 6320 6511 +14461 6045 6295 379 6857 +14462 5424 5393 5375 6598 +14463 2534 3171 6240 6608 +14464 1722 2105 5951 6270 +14465 1720 2188 5871 5947 +14466 4990 5920 5863 5984 +14467 5094 6700 5832 7021 +14468 5398 5400 6068 6295 +14469 3429 6004 5784 6224 +14470 5974 6634 495 7074 +14471 3300 3293 2665 6711 +14472 4702 5755 6265 6378 +14473 1606 6262 1615 6464 +14474 5391 6268 5369 7151 +14475 370 6135 369 6754 +14476 1722 2105 6270 6386 +14477 4950 5978 5898 6750 +14478 4426 5877 4387 6138 +14479 1908 5968 2124 6847 +14480 2392 6161 2416 6717 +14481 6341 6420 2004 7129 +14482 5076 5010 6161 6273 +14483 2315 6478 6184 6854 +14484 5955 6223 6098 7171 +14485 3762 6264 6674 6751 +14486 1311 1511 1216 6925 +14487 6407 6408 1566 6442 +14488 1382 5899 1993 5900 +14489 1823 1985 6076 7087 +14490 329 6284 2283 6294 +14491 2572 2376 5809 6886 +14492 1926 5838 5865 6079 +14493 3217 6191 2707 6869 +14494 2643 2982 6096 6504 +14495 4331 6537 5807 7141 +14496 3236 3233 5934 6657 +14497 2995 2624 5874 7101 +14498 5856 5857 2591 5910 +14499 3322 6367 6590 7043 +14500 5227 6367 5072 6908 +14501 1819 6558 6222 6964 +14502 6064 6375 1655 6376 +14503 5901 6171 2363 6268 +14504 3441 5957 3577 6180 +14505 5231 6276 6074 6277 +14506 4640 5868 4642 6338 +14507 2552 5819 3542 5972 +14508 3514 6263 3453 6342 +14509 336 6331 6241 6776 +14510 2928 2929 5791 6267 +14511 593 6268 592 6926 +14512 2327 2368 6296 6679 +14513 2702 2904 6402 6831 +14514 4978 6101 6041 6455 +14515 2159 1953 1729 6449 +14516 4728 5782 4738 6764 +14517 3515 3388 3389 6342 +14518 3435 6298 6297 6314 +14519 2920 6015 2785 6247 +14520 5796 6370 4526 7062 +14521 505 6355 5992 6479 +14522 1311 5804 1511 6925 +14523 1642 2017 6072 6622 +14524 5778 4636 6108 7049 +14525 4779 5823 5782 6099 +14526 513 514 6349 6690 +14527 370 6135 5825 6478 +14528 4670 5918 6005 6823 +14529 4257 6429 6225 6906 +14530 1753 6026 5960 6681 +14531 4057 5769 6025 6436 +14532 2203 5899 2294 6572 +14533 4950 6170 5978 6750 +14534 3021 3289 2473 5814 +14535 4621 6484 6062 6861 +14536 2738 5941 6109 6660 +14537 5179 5819 5129 5972 +14538 2731 6700 2732 7021 +14539 5287 5329 5902 5975 +14540 4188 5876 4482 6396 +14541 5233 6218 6158 6745 +14542 4668 5056 6069 6075 +14543 5815 6245 3432 6652 +14544 2939 6216 6056 6486 +14545 4636 4576 5778 6108 +14546 508 6116 6119 6822 +14547 2785 2782 2781 6247 +14548 2452 2706 1378 2475 +14549 2317 6200 374 6268 +14550 2800 6164 5886 6446 +14551 5754 5793 2339 6401 +14552 4955 4922 5053 5941 +14553 1537 1621 1622 1449 +14554 2151 1932 5967 6836 +14555 6328 6880 5871 6991 +14556 4138 4387 4426 6033 +14557 1318 1419 1226 6632 +14558 3952 3718 3881 5916 +14559 2669 6314 6297 6332 +14560 2768 5975 5755 6896 +14561 5054 4940 6257 6737 +14562 4728 5969 5789 6764 +14563 4601 6342 4609 6411 +14564 3070 6414 6246 6536 +14565 4776 4725 6693 6816 +14566 5112 5883 5908 7173 +14567 5327 5283 4885 5834 +14568 227 228 6092 6260 +14569 4496 6255 6650 6715 +14570 531 4538 29 6938 +14571 4948 5033 5778 6361 +14572 2086 6019 6018 7210 +14573 6129 4614 6411 6477 +14574 1297 2203 291 5899 +14575 5106 6039 6155 6514 +14576 3908 447 3634 5809 +14577 3434 5993 3502 6842 +14578 6548 6922 3800 7113 +14579 6549 6923 1314 7114 +14580 5364 5282 5362 5961 +14581 5350 5909 5359 6489 +14582 3312 6003 3315 6557 +14583 28 6141 5995 6287 +14584 3488 6426 6425 7036 +14585 4063 6146 6205 6671 +14586 2530 2506 2521 6523 +14587 3428 6002 6224 7123 +14588 4680 5834 5790 7182 +14589 5832 6700 5926 7021 +14590 4538 6905 532 7098 +14591 5843 5927 5167 6481 +14592 1877 6151 6153 7180 +14593 2189 5816 1869 5817 +14594 2640 5757 2748 6372 +14595 335 6241 6110 6856 +14596 4546 5903 6456 6715 +14597 5908 5944 4926 7109 +14598 4855 5794 4942 7035 +14599 4190 4341 6187 7091 +14600 4663 5031 6117 7148 +14601 5313 6031 5972 6433 +14602 5821 6041 3391 7149 +14603 5339 5936 5923 6173 +14604 3111 5902 3109 5943 +14605 5677 6769 6770 6771 +14606 6772 6773 5519 6774 +14607 4884 5790 4987 5791 +14608 1287 6874 6771 7011 +14609 3773 6873 6774 7009 +14610 3252 5926 3087 6480 +14611 2077 5865 1901 5991 +14612 4618 4982 4862 5800 +14613 1819 6186 6558 6964 +14614 3290 5765 6339 6849 +14615 5970 6220 2940 6717 +14616 3349 6091 6288 6747 +14617 441 2680 440 6999 +14618 2439 3130 3073 6606 +14619 5861 5914 2832 6552 +14620 2428 6388 6009 7023 +14621 2033 5764 2102 6544 +14622 5780 5775 6639 7145 +14623 4666 4668 4667 6647 +14624 4742 5772 6502 7139 +14625 4983 5772 4742 6046 +14626 2832 5861 2833 5914 +14627 4126 6156 4485 6316 +14628 3131 6083 5983 6551 +14629 1928 6286 5951 6494 +14630 4516 5833 5988 6672 +14631 3671 6534 6676 6757 +14632 1185 6533 6675 6758 +14633 6509 6620 628 6913 +14634 487 6419 6370 7104 +14635 6246 6536 4794 6920 +14636 6084 6085 5142 6163 +14637 2383 5936 6075 6173 +14638 3830 6009 2729 6412 +14639 3293 5799 2666 6711 +14640 6114 6120 1713 6373 +14641 5862 6434 2838 6885 +14642 5362 5961 5773 6627 +14643 4207 6079 5935 6315 +14644 4714 4715 6451 7160 +14645 3961 6716 6492 6730 +14646 5112 5908 6058 7173 +14647 3572 6036 3022 6502 +14648 6043 6044 2649 6159 +14649 3144 6199 3146 6651 +14650 4034 5877 4426 6138 +14651 3592 6121 6014 6421 +14652 4089 5982 6118 6395 +14653 4393 5994 5958 6501 +14654 421 6077 5969 6797 +14655 6840 6953 5553 7113 +14656 6841 6954 5711 7114 +14657 5499 5507 6731 6939 +14658 5657 5665 6732 6940 +14659 3555 5913 5757 6767 +14660 1185 6675 1501 6758 +14661 3671 6676 3987 6757 +14662 4877 5975 5849 6896 +14663 4214 4389 4057 5769 +14664 5115 6742 5346 7197 +14665 3181 3180 2971 6210 +14666 5873 6411 6342 6870 +14667 4241 4175 4375 6167 +14668 2661 6392 2840 6643 +14669 3499 3493 6358 6447 +14670 4044 6352 6205 6410 +14671 4196 6071 4100 6622 +14672 5901 6171 5432 6679 +14673 5310 5304 5779 6392 +14674 5377 5395 6266 6856 +14675 4270 5817 5816 6778 +14676 2112 6090 1865 6556 +14677 4667 6085 4666 6647 +14678 4023 6326 4161 6673 +14679 4812 4741 6102 6555 +14680 5358 6618 6345 7158 +14681 3892 6801 6593 6932 +14682 1406 6802 6594 6931 +14683 3166 6059 5937 6815 +14684 3982 6863 5949 7061 +14685 3981 6126 3750 6369 +14686 218 3645 217 5796 +14687 6036 6043 2649 6159 +14688 3024 5789 2521 5805 +14689 4742 6046 5772 7139 +14690 3439 6353 6065 6358 +14691 2844 5831 5758 6885 +14692 1305 6743 6722 6955 +14693 5228 6277 6280 6281 +14694 2666 5799 2665 6711 +14695 1308 1311 1216 5803 +14696 4557 6121 541 6421 +14697 4955 4693 4922 6660 +14698 4173 5817 4270 6778 +14699 236 6362 3658 6391 +14700 5357 6163 6011 7158 +14701 5226 6053 5980 6300 +14702 4526 4540 6077 7062 +14703 5760 6178 2118 7092 +14704 4763 6243 4765 6263 +14705 3508 2791 6330 6843 +14706 2648 5898 2934 6299 +14707 6571 6632 560 6743 +14708 3781 6509 3689 6725 +14709 1783 5895 2071 5982 +14710 6179 6707 3212 7120 +14711 5001 5304 5986 6560 +14712 6157 6329 2276 6354 +14713 5808 5951 4146 6386 +14714 2882 6402 2883 6486 +14715 5904 6215 2517 6273 +14716 4558 6121 6014 6928 +14717 370 2354 6135 6478 +14718 4823 5892 5870 5934 +14719 3381 6129 3574 6477 +14720 5658 6729 6569 6954 +14721 5500 6730 6570 6953 +14722 3336 5771 5773 6941 +14723 3162 3525 6047 6394 +14724 2667 6231 6143 6888 +14725 4441 4041 4296 6344 +14726 573 4774 574 6808 +14727 2712 6128 3812 6957 +14728 4751 5925 4752 5926 +14729 2106 6176 6175 6493 +14730 5893 5920 2689 6617 +14731 2872 3573 6038 6317 +14732 4030 4374 6315 6377 +14733 4551 4502 6313 6672 +14734 2938 5778 3199 5981 +14735 4949 5888 5778 5990 +14736 1824 6025 2182 6600 +14737 1741 2094 5858 7033 +14738 1940 6687 5932 6838 +14739 461 6564 3787 7061 +14740 2976 5801 3175 5868 +14741 2118 6178 5760 6600 +14742 2160 5804 1991 6111 +14743 6191 6498 6413 6869 +14744 1610 6463 6462 6464 +14745 2156 2071 1648 6207 +14746 4811 5927 5167 6161 +14747 5813 5881 2360 6987 +14748 3399 6342 5873 6908 +14749 5345 6047 5131 6621 +14750 3236 5934 5892 6657 +14751 3252 5926 6480 7067 +14752 4942 6945 4855 7211 +14753 5966 6740 6547 7046 +14754 4421 5872 4149 7141 +14755 2349 2318 6506 6948 +14756 2968 3189 5937 6437 +14757 3784 6584 3991 6989 +14758 3371 5925 5832 6659 +14759 1766 5838 5837 6599 +14760 5956 3144 6536 6651 +14761 6100 1789 6311 6559 +14762 5850 6543 6366 7162 +14763 3038 3512 3041 5883 +14764 5409 5767 634 6141 +14765 5963 5964 2803 7121 +14766 4967 6003 6002 6340 +14767 3392 6280 6277 6281 +14768 1735 5840 2005 6204 +14769 4572 4574 4633 6551 +14770 6788 6881 5715 6994 +14771 5954 6468 4237 6740 +14772 3107 5937 3189 6437 +14773 5756 5812 1740 6450 +14774 4631 6195 6005 6346 +14775 5357 5358 6163 7158 +14776 1940 5932 6206 6838 +14777 346 6296 6068 6443 +14778 6120 6373 4391 6658 +14779 2543 6489 6003 6557 +14780 4873 6299 5962 7211 +14781 2142 5761 1748 5973 +14782 2894 2489 2758 6075 +14783 5082 6469 6174 7125 +14784 5892 6216 5289 6231 +14785 3378 6289 3292 6339 +14786 5821 3307 6263 7149 +14787 2414 6451 5881 6589 +14788 3178 3039 5770 6591 +14789 5067 5243 6472 6515 +14790 5699 5613 6632 6851 +14791 4965 4872 5759 6272 +14792 2416 6161 5970 6717 +14793 5803 6642 6324 6794 +14794 1976 5947 5802 6242 +14795 3205 5772 3528 7139 +14796 4509 5948 4502 6672 +14797 2642 6576 2985 6656 +14798 5142 6085 5349 6163 +14799 336 6241 6136 6776 +14800 5098 6037 4917 6105 +14801 6071 6312 4196 6980 +14802 3542 2791 5972 6330 +14803 6025 6357 4406 6395 +14804 5975 5976 4814 7142 +14805 3602 3653 6546 7048 +14806 5153 4860 4878 6096 +14807 5264 5842 5266 6444 +14808 1764 5756 5788 6328 +14809 1705 6055 1966 6681 +14810 4774 5886 4773 6446 +14811 1744 6256 6034 6847 +14812 4492 5924 5781 6169 +14813 457 5954 5851 5973 +14814 497 5955 5852 5974 +14815 5429 5920 603 6325 +14816 371 5825 3077 6962 +14817 2998 6414 6020 6768 +14818 5978 6170 5867 6872 +14819 481 6422 5991 6779 +14820 2430 7035 6028 7045 +14821 1704 6064 5818 6577 +14822 3508 5972 2791 6843 +14823 3413 6228 6227 6626 +14824 4855 6299 6028 7068 +14825 5238 6044 6043 6159 +14826 4345 4092 6064 6375 +14827 499 6098 5933 6685 +14828 3954 3846 3717 6895 +14829 2947 5806 6623 6680 +14830 3156 5856 5910 6087 +14831 3367 6282 3004 6473 +14832 3497 3333 5790 6970 +14833 5165 5883 5770 6621 +14834 5429 6234 5384 7007 +14835 3881 5916 6389 6828 +14836 5753 5781 3631 6233 +14837 4444 4109 6127 7131 +14838 4238 5999 5955 6000 +14839 2433 5850 1377 7096 +14840 2019 6348 6192 6485 +14841 1809 6055 1705 6242 +14842 1556 1559 6408 6409 +14843 5334 5338 5337 5772 +14844 6531 1324 7011 7111 +14845 6530 3810 7009 7112 +14846 3344 6137 3345 6643 +14847 4158 6153 6151 6360 +14848 3546 5787 3583 5792 +14849 6167 6322 1760 6490 +14850 4704 6103 6095 6627 +14851 5874 6707 6166 7120 +14852 3420 3151 5786 6708 +14853 1298 6583 1505 6994 +14854 4560 6261 5796 7164 +14855 2077 5865 1709 6079 +14856 5032 6106 6448 6483 +14857 3610 3664 445 5781 +14858 5769 5960 1753 6026 +14859 4860 4880 6096 6839 +14860 3107 3337 2693 6670 +14861 2465 5774 6451 6582 +14862 6022 6445 6054 6739 +14863 4989 6656 6154 7106 +14864 4190 6396 4341 7091 +14865 329 2283 6293 6294 +14866 3479 6049 6298 6626 +14867 2764 2768 3110 5902 +14868 6271 6524 6312 6961 +14869 507 6209 6116 6822 +14870 606 5881 4735 6589 +14871 5334 5772 5337 6502 +14872 5065 6004 6130 7167 +14873 2930 5826 2937 7020 +14874 3428 6724 6002 7123 +14875 1817 6127 5928 6544 +14876 2192 6460 5953 7059 +14877 428 5988 3639 6160 +14878 5014 5881 5015 6259 +14879 6167 6168 4375 6490 +14880 509 6153 4158 6360 +14881 1969 6071 6385 6980 +14882 5956 6199 3144 6651 +14883 4078 4404 6310 6616 +14884 1202 6089 1410 7060 +14885 4171 6203 6396 6671 +14886 6068 6295 5400 6296 +14887 5817 6230 1906 6992 +14888 4978 6041 4976 6455 +14889 4867 6214 6240 6608 +14890 4884 5790 4680 5834 +14891 6821 6895 5557 6989 +14892 1867 6384 5940 6661 +14893 362 5881 5880 6987 +14894 5529 6840 6620 6953 +14895 5687 6841 6619 6954 +14896 2656 5757 2654 6037 +14897 1841 6205 6204 6376 +14898 4491 6254 5885 6597 +14899 2133 6460 6072 6461 +14900 3553 5913 3555 6767 +14901 1861 5952 1675 6113 +14902 3490 5923 3536 6173 +14903 5346 5115 6095 6742 +14904 5269 5268 6314 6626 +14905 6090 6516 1865 6556 +14906 6208 6512 3241 7027 +14907 5901 6268 376 6814 +14908 3129 2446 3317 6744 +14909 5871 5872 4329 6991 +14910 4711 6451 5854 6982 +14911 5339 5923 5048 6173 +14912 1537 1449 1622 6925 +14913 2433 1435 1377 5850 +14914 1637 6168 6490 6930 +14915 1906 6230 5817 6836 +14916 3281 5918 3014 6346 +14917 4918 6258 6104 6402 +14918 5184 5183 5182 6212 +14919 3090 5904 6454 6792 +14920 4434 6420 5953 7059 +14921 2079 6033 1908 6847 +14922 5925 6343 3370 6795 +14923 5203 6330 6101 6662 +14924 5339 5048 5936 6173 +14925 3639 3613 6160 6520 +14926 4655 6105 4657 7001 +14927 4344 4426 5877 6385 +14928 491 6249 6787 7156 +14929 2568 5920 2570 5984 +14930 5925 6046 3407 6480 +14931 4947 5856 5052 6744 +14932 4396 6348 6192 6501 +14933 4602 6342 6263 7149 +14934 4665 5260 5256 6713 +14935 565 564 6699 7060 +14936 2608 3873 6221 6957 +14937 2645 5956 5846 6839 +14938 451 6369 6820 7026 +14939 6080 6371 5011 6470 +14940 6288 6297 5255 6565 +14941 3846 6821 3717 6895 +14942 5304 5001 5055 6560 +14943 3338 6137 5831 6434 +14944 515 6384 5940 6690 +14945 4261 4214 5769 6357 +14946 3053 3055 3354 6567 +14947 2016 2131 6222 6942 +14948 6025 4221 6436 6726 +14949 5806 6080 2944 6371 +14950 4699 5962 4932 6394 +14951 5865 5991 4394 6194 +14952 4146 5951 5808 6286 +14953 3292 6289 3378 6382 +14954 4701 5330 5755 5985 +14955 1318 6743 1226 6955 +14956 5407 5367 5793 5822 +14957 504 5793 5413 6318 +14958 3565 3514 6333 6342 +14959 4198 475 6093 6134 +14960 3385 3384 6367 6908 +14961 592 5279 593 6926 +14962 2360 5880 362 6518 +14963 4849 5110 4850 6265 +14964 4552 6313 5948 6462 +14965 5873 6367 4944 7043 +14966 6261 6262 1608 6464 +14967 5393 6321 5386 6598 +14968 4259 6368 4075 6859 +14969 309 6292 6291 6690 +14970 4581 4597 6224 7036 +14971 5964 6976 4565 7073 +14972 5055 6008 5779 6560 +14973 3574 3486 6129 6130 +14974 6072 6071 6663 7177 +14975 2359 6284 6293 7066 +14976 6241 6331 2267 6439 +14977 3094 5778 5888 5990 +14978 3103 6240 6188 7050 +14979 2856 6188 6551 7124 +14980 1780 5763 2029 6076 +14981 576 5998 6164 6473 +14982 3577 5957 3441 6181 +14983 2719 5998 1326 6125 +14984 4208 4021 4416 5837 +14985 611 5827 5884 6736 +14986 2423 5785 2917 6515 +14987 372 373 2331 6185 +14988 5025 6164 5886 7052 +14989 1810 2132 2192 6537 +14990 2247 6384 6452 6690 +14991 3488 6404 6426 7036 +14992 6388 6389 6009 7023 +14993 5997 6710 4987 7155 +14994 3605 6307 3613 6520 +14995 3428 5784 6724 7123 +14996 2086 6018 6403 7210 +14997 2638 6053 6272 6336 +14998 5891 5996 4257 6906 +14999 3566 6137 3338 6434 +15000 4629 5365 6053 6336 +15001 1478 1257 1353 6048 +15002 4951 6235 6214 6469 +15003 4877 5849 4676 7159 +15004 5825 5860 4749 6754 +15005 3579 6007 3485 6888 +15006 6220 6471 3274 6929 +15007 5173 6024 5174 6831 +15008 4776 6457 6083 6693 +15009 4496 6650 4546 6715 +15010 6374 6692 5078 6915 +15011 2019 6485 6192 7172 +15012 4277 6337 6206 6615 +15013 5188 5184 6023 6218 +15014 5813 5376 6518 7066 +15015 1992 5797 3998 6126 +15016 2243 6290 310 6397 +15017 6033 6034 1794 6385 +15018 477 6260 476 6418 +15019 2839 5779 2898 5986 +15020 2572 5809 3780 6886 +15021 5242 5894 5241 6472 +15022 4774 5917 5886 6808 +15023 1858 5769 2165 6244 +15024 5811 6472 5067 6700 +15025 3107 3254 5937 5938 +15026 5014 5037 4790 6259 +15027 1822 2128 1984 6151 +15028 523 6193 6145 7143 +15029 5157 6330 5158 6662 +15030 4927 5985 4699 6394 +15031 5001 5986 5864 6560 +15032 4334 5992 6356 6505 +15033 1773 6029 2032 6490 +15034 3274 6220 5970 6471 +15035 6514 6763 5800 7077 +15036 3624 5768 6190 6797 +15037 5775 2999 6695 6755 +15038 3349 6288 6347 6747 +15039 4188 5876 6396 6864 +15040 2020 6527 6449 7018 +15041 5004 6236 5002 7078 +15042 1660 6271 6270 7187 +15043 1318 6850 6632 6851 +15044 5125 5174 5155 6831 +15045 3734 5973 5761 6633 +15046 5270 4662 6106 6363 +15047 5118 5052 6393 6744 +15048 2704 5785 2705 7161 +15049 5793 6067 5413 6318 +15050 5260 6007 5256 6713 +15051 4824 5934 5870 6001 +15052 3577 5957 6181 7138 +15053 3060 5874 3098 6166 +15054 2807 5782 6054 7116 +15055 4015 5817 6230 6836 +15056 3579 3485 6143 6888 +15057 1368 6458 1459 6583 +15058 3945 3854 6459 6584 +15059 381 6321 380 6470 +15060 1983 6120 6114 6607 +15061 3605 3641 6307 6520 +15062 3159 6491 5835 6968 +15063 5778 5888 4636 7049 +15064 4652 5770 5211 5841 +15065 4825 6216 5892 6486 +15066 3473 6106 5842 6444 +15067 3646 3614 3591 6967 +15068 2169 1894 1791 6501 +15069 4832 4621 4935 6861 +15070 3322 2636 6272 7043 +15071 4496 6092 6255 6715 +15072 4802 4804 6008 7127 +15073 4916 5757 6010 6372 +15074 5689 6827 6498 6901 +15075 5879 6338 2680 6999 +15076 344 6040 6586 7202 +15077 2739 6102 6101 6399 +15078 3322 6590 2636 7043 +15079 5635 6770 6596 6874 +15080 5477 6773 6595 6873 +15081 1231 6881 6788 6994 +15082 6017 6197 2574 6857 +15083 4394 5991 479 6194 +15084 4119 4459 5808 7170 +15085 428 427 5988 7039 +15086 6143 6936 5799 7019 +15087 3705 5753 6503 6720 +15088 4876 5957 5218 7147 +15089 532 6905 5855 7098 +15090 440 2680 6338 6999 +15091 3717 6895 6821 6989 +15092 2171 1783 5982 6734 +15093 6232 6453 1417 6694 +15094 6224 6289 4674 6425 +15095 5042 5857 5041 6371 +15096 3797 3997 3702 6805 +15097 259 5991 6194 6423 +15098 6002 6003 3362 6340 +15099 1966 6055 6026 6681 +15100 5023 5294 6239 6910 +15101 6144 1812 6344 6493 +15102 2501 5827 2522 6417 +15103 5887 4716 6695 6755 +15104 4134 4058 6375 6934 +15105 5983 4933 6393 7124 +15106 1290 6569 6499 6729 +15107 1231 1360 6788 6881 +15108 3355 3353 5980 6300 +15109 2672 6170 5978 6872 +15110 3629 6123 3593 6253 +15111 3794 3797 5798 6264 +15112 4618 5800 4862 6388 +15113 4926 6047 4927 6394 +15114 5786 5787 5196 6024 +15115 6040 6435 344 6586 +15116 2567 2643 5846 5847 +15117 5817 6207 1869 6836 +15118 1247 6769 6644 7070 +15119 2522 5827 5775 6417 +15120 3177 5842 3039 6591 +15121 6731 6868 3674 6895 +15122 3565 6342 6333 6411 +15123 6571 6632 1289 6860 +15124 5951 6270 2105 7069 +15125 4862 5800 4982 6388 +15126 2737 6043 2789 6109 +15127 5407 5411 5367 5822 +15128 3678 461 6440 6924 +15129 6147 2020 6449 7018 +15130 4808 6035 4741 7139 +15131 4510 4553 6255 6308 +15132 2624 3098 2995 5874 +15133 5260 6143 6007 6713 +15134 5300 6288 6281 6507 +15135 1297 2294 2203 5899 +15136 1899 5954 5851 6097 +15137 1898 5955 5852 6098 +15138 5782 5789 2950 6764 +15139 1701 5905 1947 7146 +15140 6155 2526 6504 7030 +15141 1862 5876 1674 6396 +15142 4598 4600 5758 5826 +15143 5338 5911 5903 6650 +15144 6208 6361 5990 7027 +15145 4409 4115 4321 6132 +15146 5807 5853 4263 6525 +15147 4615 6063 6466 7097 +15148 4086 5959 5906 6335 +15149 1960 1788 6032 6624 +15150 4383 6256 6034 6961 +15151 2640 2750 2748 5757 +15152 3908 5753 3634 7083 +15153 1813 6270 6622 7187 +15154 1495 6111 1264 6467 +15155 5866 6982 5014 7152 +15156 1743 6211 5994 7087 +15157 5296 6101 6102 6399 +15158 5891 6176 1927 6906 +15159 4549 6078 4509 6520 +15160 592 6814 5279 6926 +15161 5829 6166 5261 7120 +15162 6201 6506 2318 6948 +15163 1857 6178 5858 6368 +15164 2297 6185 2318 6948 +15165 4011 6537 4362 7015 +15166 6111 6485 5804 6883 +15167 3787 461 3678 6564 +15168 2843 6434 5831 6885 +15169 529 6147 528 7034 +15170 4289 5844 4455 7176 +15171 4802 6213 4801 6214 +15172 2437 3050 2915 7152 +15173 4924 5941 6109 6511 +15174 3144 3145 5956 6536 +15175 5391 5369 5387 6040 +15176 3333 5790 5771 6941 +15177 2950 5782 2790 6099 +15178 4860 4858 6495 6839 +15179 542 5241 5894 6696 +15180 3322 2638 6053 6272 +15181 5360 6053 5226 6300 +15182 367 6052 5939 6856 +15183 3066 3064 6103 6627 +15184 2747 2980 2741 6062 +15185 5274 5787 5291 5792 +15186 3085 6257 5971 6969 +15187 468 6256 6323 6847 +15188 6732 6867 1188 6881 +15189 4290 5991 4192 6316 +15190 4193 5996 7176 7184 +15191 556 5783 5969 6764 +15192 4905 4903 5784 7123 +15193 4574 4572 6188 6551 +15194 3546 3420 3545 5786 +15195 2294 5899 1297 6572 +15196 2816 6371 6470 6914 +15197 475 6093 6134 6327 +15198 2580 6213 6008 7127 +15199 4753 4983 6046 6480 +15200 6035 4818 6399 6678 +15201 6323 6362 1555 6391 +15202 2438 2439 2440 5857 +15203 5839 3508 6738 6843 +15204 2649 6036 2651 6043 +15205 576 6125 5998 6473 +15206 4860 6199 4858 6839 +15207 3167 2692 6039 6514 +15208 5390 6962 6478 7063 +15209 4007 6772 3890 6774 +15210 1521 6769 1404 6771 +15211 5346 6742 5913 7197 +15212 2015 1782 2188 6090 +15213 4621 6062 4935 6861 +15214 2309 5793 2322 6401 +15215 2920 6089 6015 6247 +15216 3648 6169 6165 6698 +15217 1810 6242 6537 7015 +15218 5311 5257 5923 6172 +15219 5214 5213 4977 6738 +15220 4281 5989 4124 6691 +15221 1933 1715 6467 7024 +15222 6536 6719 4794 6920 +15223 4778 5888 5889 7049 +15224 3059 5874 3060 6707 +15225 4448 6120 6114 6373 +15226 3234 5934 6374 6814 +15227 2671 5867 6170 6872 +15228 5492 6922 6548 7113 +15229 5650 6923 6549 7114 +15230 3421 3582 3375 6652 +15231 4840 5856 4947 6087 +15232 5369 6268 6200 7151 +15233 5561 5459 6641 6784 +15234 5719 5617 6640 6781 +15235 2910 2912 5829 6512 +15236 4463 6740 6468 7046 +15237 2741 5780 2855 6364 +15238 5976 6158 3224 6745 +15239 2668 6332 6297 6565 +15240 5899 5900 1242 6741 +15241 5123 4631 6005 6346 +15242 3131 3129 5983 6083 +15243 5061 5936 5048 6173 +15244 3042 5772 3033 5903 +15245 1466 6498 1291 6901 +15246 511 6625 6443 6990 +15247 5279 6001 593 6926 +15248 255 5845 6463 6574 +15249 4780 5888 4949 6709 +15250 2230 6116 6209 6822 +15251 1543 5803 1538 6794 +15252 529 28 6449 6911 +15253 5353 5356 6212 6573 +15254 1955 2162 1730 6505 +15255 2905 3040 2613 5841 +15256 5762 495 6634 7074 +15257 2715 6389 2751 7000 +15258 4396 6348 6501 6918 +15259 3449 3563 3075 5759 +15260 6082 6382 5090 6748 +15261 3293 6390 5799 6711 +15262 441 6123 5879 6999 +15263 1717 5932 6440 6833 +15264 5507 6803 6731 6939 +15265 5665 6804 6732 6940 +15266 5925 5926 4751 6480 +15267 6040 6200 5417 6762 +15268 2258 6383 319 6505 +15269 5802 5947 4094 6242 +15270 367 5939 6266 6856 +15271 2623 6361 6131 6398 +15272 5041 6470 6914 7106 +15273 1397 1268 6705 6850 +15274 3883 3754 6704 6852 +15275 1720 5802 5947 6858 +15276 4234 4340 6352 6677 +15277 3371 3089 5832 5925 +15278 1948 5769 1669 6025 +15279 2815 5870 3237 5934 +15280 2333 6295 2369 6598 +15281 6853 6893 5498 6907 +15282 5310 5986 5304 6392 +15283 4173 4270 5905 6778 +15284 5290 5291 5350 5792 +15285 5164 6208 6512 6697 +15286 1910 5836 5994 6465 +15287 3394 6298 5961 6554 +15288 2838 5862 2837 6434 +15289 4845 4843 5784 6245 +15290 4443 4226 4110 6146 +15291 5775 5827 2522 6639 +15292 2769 6124 5810 6457 +15293 4612 5765 5873 6985 +15294 5776 6104 5051 6576 +15295 4876 7138 5957 7147 +15296 618 6038 5862 6434 +15297 1777 6225 6238 6429 +15298 4110 6614 5876 6909 +15299 6002 6340 3360 6404 +15300 3541 6330 5819 6662 +15301 4421 6525 5872 7141 +15302 6051 6255 431 6650 +15303 1231 1468 1360 6881 +15304 5852 5955 498 6098 +15305 458 5851 5954 6097 +15306 2393 3116 3503 6717 +15307 2518 2525 5904 6162 +15308 5349 5301 6163 6919 +15309 4182 6328 6090 6991 +15310 3208 373 5897 6001 +15311 3487 6289 6224 6425 +15312 4396 5959 6348 6918 +15313 5230 6280 5993 6507 +15314 5428 6052 5377 6856 +15315 4817 6302 5907 6696 +15316 445 5781 3664 6905 +15317 4831 4878 4833 5846 +15318 5024 4771 5859 5942 +15319 6475 6535 1781 6944 +15320 3457 3185 3111 6210 +15321 5056 4802 6008 6213 +15322 4965 6590 5759 6985 +15323 5074 6215 4769 6273 +15324 2816 6371 6080 6470 +15325 2598 6150 2599 6438 +15326 3223 5849 6896 7159 +15327 5853 6006 4316 6310 +15328 1901 5991 5865 6194 +15329 4989 4968 6197 6656 +15330 618 6434 5862 6885 +15331 4188 6396 5999 6864 +15332 4672 5874 6431 6823 +15333 5057 6213 5093 6469 +15334 3190 6102 3191 6455 +15335 1689 1877 6151 7153 +15336 6113 6283 1675 6607 +15337 3441 6180 3581 6181 +15338 4099 4242 5844 5905 +15339 6238 6706 6081 7006 +15340 4900 6457 6124 6551 +15341 3612 5987 3607 6682 +15342 3421 6347 3348 6837 +15343 2769 5810 2770 6457 +15344 1636 5915 5906 6335 +15345 3581 6219 6181 6845 +15346 4512 6014 4494 6682 +15347 6119 6443 6153 7180 +15348 6168 6187 1886 7171 +15349 422 5783 3614 6967 +15350 1639 5928 5878 6544 +15351 2689 5893 2570 5920 +15352 370 5825 6135 6754 +15353 5993 6297 3502 6842 +15354 5076 6273 6161 7168 +15355 271 5968 1549 6323 +15356 4015 6230 5977 6836 +15357 5981 6282 4589 6500 +15358 4802 6214 4803 7127 +15359 2748 2656 2733 7021 +15360 5781 6905 4538 6938 +15361 4139 5763 4343 5958 +15362 4618 4862 6039 6388 +15363 6244 6516 4201 6556 +15364 4455 6441 4193 7176 +15365 4671 5059 5777 6431 +15366 5285 5975 5943 7055 +15367 573 574 5835 6808 +15368 1704 1975 6064 6577 +15369 5948 4509 6078 7086 +15370 4668 5061 6075 6647 +15371 6684 6825 499 7071 +15372 4963 5921 6086 7163 +15373 5267 5269 5268 6228 +15374 5113 5112 5111 7088 +15375 2465 5774 2961 6451 +15376 6023 6212 5356 6573 +15377 1748 1829 2085 5761 +15378 3475 5787 5786 6024 +15379 626 6188 627 6221 +15380 4832 5846 4831 5847 +15381 1868 5848 2145 6134 +15382 4780 4949 5054 6709 +15383 2915 5794 5866 6872 +15384 4118 6207 5818 6577 +15385 6253 4547 6546 6943 +15386 5070 5071 5225 6630 +15387 6121 6251 3595 6928 +15388 5129 5972 5819 6433 +15389 631 5820 4863 6229 +15390 5994 6076 1985 7087 +15391 3482 5832 2653 6105 +15392 4513 4494 6121 6682 +15393 5813 2360 6518 6987 +15394 4831 4832 4935 5846 +15395 4655 4657 4656 7001 +15396 483 484 6462 6463 +15397 6165 6362 4556 6430 +15398 6587 6619 1448 6729 +15399 4392 6034 6033 6385 +15400 5225 5792 6489 6630 +15401 572 6491 6274 6968 +15402 5398 6045 6295 6598 +15403 5989 6475 4124 6691 +15404 2853 5780 5775 6639 +15405 1657 6527 6322 7079 +15406 633 25 6264 7038 +15407 4251 4413 6270 6386 +15408 6232 6694 1311 6883 +15409 4344 5877 5764 6385 +15410 5037 5097 5038 5794 +15411 462 6337 5949 6833 +15412 2387 6099 5888 7186 +15413 3294 3554 3466 6129 +15414 5353 6030 6212 6921 +15415 5319 5786 5196 6024 +15416 2633 2642 2985 6656 +15417 4356 6127 5764 6544 +15418 2477 2797 5927 6236 +15419 3794 3797 3702 5798 +15420 6200 6268 2317 7151 +15421 1743 5994 1985 7087 +15422 5444 6774 6873 7009 +15423 5602 6771 6874 7011 +15424 2037 1813 6270 6622 +15425 3242 6150 5997 6517 +15426 5093 6174 5082 6469 +15427 2642 6104 6576 6656 +15428 5889 6189 2445 6523 +15429 3514 3453 6333 6342 +15430 4934 5983 5030 6606 +15431 2257 6319 6405 6506 +15432 4017 6071 5764 6663 +15433 1705 6681 1965 7072 +15434 4518 6251 6092 6456 +15435 2055 6726 1669 7033 +15436 570 6602 6482 6775 +15437 5829 5261 6179 7120 +15438 3602 6253 6546 6943 +15439 5824 5826 5006 7020 +15440 1202 1398 1500 6016 +15441 2079 1908 1744 6847 +15442 2942 5831 6137 6269 +15443 3059 3212 3535 6707 +15444 1353 6571 6048 7165 +15445 5159 5923 5257 6172 +15446 4720 5775 4734 6695 +15447 5870 6231 4710 6711 +15448 5207 5098 6105 6553 +15449 4726 5782 4728 7181 +15450 6078 6202 1601 6422 +15451 509 6360 6119 7180 +15452 531 6580 6503 6720 +15453 3873 6807 6221 6957 +15454 5148 6056 5280 6486 +15455 2718 2954 6320 6511 +15456 3630 6430 442 7076 +15457 1603 5845 1597 6463 +15458 4149 5872 5802 7141 +15459 5902 5943 5287 5975 +15460 3998 6126 5797 6882 +15461 5277 4978 5172 6455 +15462 1885 5852 1711 5974 +15463 1884 5851 1710 5973 +15464 5870 5892 4822 6231 +15465 1637 6490 2032 6930 +15466 5800 7000 5862 7189 +15467 5274 5787 5792 6065 +15468 3283 2717 2716 6109 +15469 1991 5804 1512 6111 +15470 4355 6614 5763 7099 +15471 2303 6777 5813 7066 +15472 3978 3769 6641 6913 +15473 1632 6196 5871 6880 +15474 6250 6369 1714 7025 +15475 2124 6256 1744 6847 +15476 363 2689 364 6617 +15477 3199 5981 5778 6500 +15478 1908 6033 5968 6847 +15479 2780 2782 6170 6247 +15480 541 6121 5894 6421 +15481 3328 6351 2682 6380 +15482 6086 7163 5921 7198 +15483 2955 5828 2954 6511 +15484 2708 2707 6191 6413 +15485 3091 5766 3125 6215 +15486 5770 5842 4652 6591 +15487 3295 6289 3487 6382 +15488 2154 5974 1944 7074 +15489 2045 5966 1693 7131 +15490 2002 5840 1735 6027 +15491 5257 5923 5159 6173 +15492 5365 6053 6336 7043 +15493 3237 5870 3238 5892 +15494 2501 2469 2522 5827 +15495 2725 3121 2774 6366 +15496 1960 1666 1788 6624 +15497 4014 4164 4490 6328 +15498 5931 6381 6380 6966 +15499 2693 5938 5860 6754 +15500 457 456 5954 5973 +15501 496 5955 497 5974 +15502 4094 4362 5802 6242 +15503 5827 6639 5775 7145 +15504 369 368 5938 7154 +15505 3004 6282 6164 6473 +15506 4759 611 610 7145 +15507 3144 3146 2976 6651 +15508 5165 5131 5883 6621 +15509 573 5917 5835 6968 +15510 3538 5791 5790 7182 +15511 4978 5296 6101 6102 +15512 4020 6026 5808 6386 +15513 6260 6327 1576 6365 +15514 6228 6609 4659 7194 +15515 4441 4296 6133 6817 +15516 1861 5952 6113 6635 +15517 6176 6225 4292 7056 +15518 4096 6025 6395 6600 +15519 5054 6257 4938 6709 +15520 3797 3702 5798 6805 +15521 28 634 6476 6585 +15522 4704 6504 6103 7030 +15523 2542 3362 6003 6340 +15524 3252 6472 5926 6696 +15525 5241 6472 5894 6696 +15526 572 5312 573 6274 +15527 332 331 6285 6387 +15528 496 4238 5955 6000 +15529 5423 6136 5374 6241 +15530 5139 6084 5936 6647 +15531 4877 4677 5755 6896 +15532 5895 6066 1999 6934 +15533 3449 5759 3075 6985 +15534 2513 2568 2573 5863 +15535 1915 6132 1878 6193 +15536 5940 6349 4254 6690 +15537 5967 6175 4324 6673 +15538 4516 4509 4502 6672 +15539 1932 5818 1808 5967 +15540 2694 2695 5860 6390 +15541 5770 6210 5210 6400 +15542 3556 3420 5792 5909 +15543 4474 5838 6532 6599 +15544 4225 6406 5946 6407 +15545 4860 4858 4880 6495 +15546 4873 5962 5898 7211 +15547 3028 6122 2824 6431 +15548 5957 6180 3441 6181 +15549 1240 6722 6766 6956 +15550 5323 5907 5772 6480 +15551 440 6338 5979 6999 +15552 2307 2318 2331 6201 +15553 632 6674 6401 7038 +15554 5377 6110 5427 6856 +15555 1710 5851 1899 5954 +15556 1711 5852 1898 5955 +15557 3290 6339 5912 6849 +15558 4221 4389 4096 6025 +15559 5282 5362 5961 7135 +15560 1666 1960 2147 7132 +15561 560 6571 5830 6860 +15562 4040 4297 6151 6535 +15563 2833 6437 2836 7088 +15564 5386 6321 5425 6598 +15565 2036 6326 6493 6673 +15566 4611 6448 6426 6483 +15567 4617 4615 6466 7097 +15568 4359 5836 4246 5994 +15569 5815 3421 6753 6837 +15570 1803 6006 5853 6310 +15571 1713 6114 1983 6120 +15572 4234 6352 6410 6677 +15573 5904 6162 2525 6646 +15574 4780 5044 6099 6709 +15575 2950 5789 5782 7186 +15576 3890 6772 4007 6773 +15577 1521 1404 6769 6770 +15578 6021 6343 5275 6795 +15579 3723 6521 6038 7093 +15580 6655 6705 1268 6850 +15581 6654 6704 3754 6852 +15582 4823 4698 5892 5934 +15583 4733 4729 5789 5805 +15584 2739 6399 6101 6662 +15585 4698 6374 4695 6657 +15586 3371 3369 5925 6659 +15587 4489 4018 4355 5763 +15588 4355 6614 4110 6909 +15589 2443 6693 5896 6816 +15590 5041 5011 6371 6470 +15591 6096 6103 4704 6504 +15592 3485 6216 6231 6888 +15593 4379 451 6505 7026 +15594 3004 6164 2744 6473 +15595 5766 6191 3091 6869 +15596 626 6240 6221 6957 +15597 4611 6404 6426 6448 +15598 2697 6553 6049 7001 +15599 4658 6228 6227 7102 +15600 270 5968 271 6323 +15601 5875 6189 580 6523 +15602 3089 3088 2731 5926 +15603 4987 5790 4882 6710 +15604 4003 6666 6128 6749 +15605 2761 5755 5985 6786 +15606 3122 5931 3090 6454 +15607 5791 5006 5826 7020 +15608 5165 5209 5166 6621 +15609 4742 4808 4741 7139 +15610 5157 5819 5179 6330 +15611 6017 4644 6154 6857 +15612 1846 6322 6057 6490 +15613 1905 5848 2187 6368 +15614 5790 5791 3538 6710 +15615 4097 4348 5769 5960 +15616 3119 6526 5828 6937 +15617 2220 6479 6209 6550 +15618 3345 3566 2799 6643 +15619 6244 6357 2027 7183 +15620 6290 6397 2243 6625 +15621 5873 6342 3399 6870 +15622 2063 5816 5982 6207 +15623 2566 5956 6719 6861 +15624 4820 6036 5911 6159 +15625 2469 2522 5827 6639 +15626 4896 4628 6015 6247 +15627 5055 6008 6560 6613 +15628 515 5940 4254 6690 +15629 5159 5923 6172 6173 +15630 3252 6696 5926 7067 +15631 3358 3357 6181 6921 +15632 6154 6197 6017 6857 +15633 4225 5946 472 6407 +15634 6243 6263 3306 6455 +15635 4210 6310 4404 6733 +15636 425 3628 5833 6445 +15637 2609 6221 2727 6957 +15638 2717 5869 6109 6511 +15639 1635 5967 2092 6673 +15640 3087 3088 3251 6480 +15641 2910 6166 2911 6512 +15642 5990 6737 6257 6969 +15643 5910 6656 4841 7106 +15644 3573 6038 6317 6434 +15645 4963 6086 5921 6438 +15646 4164 5756 5788 6142 +15647 1507 5995 1322 6572 +15648 2430 5794 2434 6028 +15649 1512 1440 1260 5804 +15650 5211 5209 5165 5770 +15651 4673 6217 5918 7078 +15652 1555 6362 6323 6545 +15653 3769 6725 6641 6913 +15654 5759 3290 5912 6849 +15655 3357 6030 6183 6921 +15656 584 4723 5806 5822 +15657 4471 6532 5760 6599 +15658 5241 6472 6696 7067 +15659 2484 6237 5886 7052 +15660 4603 6342 6333 7194 +15661 5923 5965 3150 6708 +15662 5966 6113 1796 6740 +15663 2078 6559 6133 7178 +15664 2373 2309 2322 6401 +15665 4454 5891 4220 6975 +15666 3312 3315 6245 6557 +15667 5795 6215 5074 6273 +15668 4871 4872 6183 7147 +15669 5119 6208 5164 6697 +15670 2631 5801 3100 6148 +15671 3035 1285 6016 6089 +15672 6061 6624 2167 6912 +15673 616 6388 4982 7000 +15674 5927 6236 4810 6799 +15675 4052 6385 4194 6980 +15676 2741 2743 6062 6364 +15677 4367 6142 5788 6796 +15678 6246 4794 6719 6920 +15679 6186 6930 6029 7188 +15680 3095 3252 6480 7067 +15681 1846 6057 6322 6527 +15682 6133 6558 4441 6817 +15683 1741 5858 6436 7033 +15684 3546 3545 3475 5787 +15685 3801 6893 6853 6907 +15686 6080 6115 585 6981 +15687 2882 6056 2702 6402 +15688 1660 1937 6271 7187 +15689 3312 6557 6245 6986 +15690 3831 5754 2371 7044 +15691 5177 5140 5909 6466 +15692 2709 5766 2711 6727 +15693 1677 2075 5761 6373 +15694 6305 6306 1586 6871 +15695 1906 5977 6230 6836 +15696 6641 6725 5528 6913 +15697 5166 5209 6400 6621 +15698 539 4543 540 5987 +15699 5155 6024 5156 6056 +15700 3621 3620 6165 6430 +15701 1968 1756 6349 6578 +15702 2977 5911 3019 6502 +15703 3212 6707 3059 7120 +15704 1983 6114 2031 6607 +15705 2416 5970 2940 6717 +15706 2949 5783 5782 6764 +15707 5320 6179 5122 6195 +15708 1291 6498 6827 6901 +15709 4124 5989 4281 6432 +15710 2283 6284 330 6387 +15711 3781 3689 3872 6725 +15712 5041 6470 6371 6914 +15713 6072 6460 2133 7059 +15714 4813 5976 4881 6158 +15715 2904 5776 2754 6402 +15716 5869 6963 3048 7039 +15717 2953 2947 2945 6623 +15718 5285 4814 5975 7055 +15719 5932 6206 460 6440 +15720 4674 6224 4675 6289 +15721 3435 6297 6298 6842 +15722 4175 6223 6168 7171 +15723 4651 5841 5113 7022 +15724 2228 6116 2230 6119 +15725 4272 6107 5812 6949 +15726 5962 6299 4875 6394 +15727 3242 2946 6150 6517 +15728 4581 6002 4597 7036 +15729 3241 2626 6361 7027 +15730 3413 6314 6228 6626 +15731 5315 5814 4984 6158 +15732 5070 4836 5071 6630 +15733 5240 5938 5937 5939 +15734 6066 6375 4058 6934 +15735 2027 6139 6556 7183 +15736 6017 6295 6045 6857 +15737 4374 6156 4258 6315 +15738 4673 4671 5777 5918 +15739 3232 6276 6074 7155 +15740 4840 5910 5856 6087 +15741 5812 1641 6450 6995 +15742 28 5409 634 6141 +15743 1867 6140 1838 6661 +15744 1967 1864 6093 6494 +15745 4673 4959 5918 6217 +15746 2526 2527 6155 6504 +15747 6034 6256 1744 6961 +15748 4680 5791 6267 7182 +15749 5197 6220 5234 6929 +15750 3011 6005 5918 6823 +15751 511 6397 6625 6990 +15752 5215 5065 6004 6747 +15753 4714 5774 4715 7160 +15754 468 6323 6256 6667 +15755 2721 5941 2793 5971 +15756 4652 5211 4651 5841 +15757 5432 5901 591 6268 +15758 2748 2733 6060 7021 +15759 4721 4996 5806 6371 +15760 2936 6088 2452 6089 +15761 5117 5161 6087 6275 +15762 4571 6124 627 6188 +15763 1772 5906 2152 7115 +15764 6083 6457 4632 6551 +15765 2414 2415 6451 6589 +15766 5785 6798 5987 7048 +15767 3134 2666 5799 6143 +15768 6214 4587 6240 7050 +15769 1631 2115 6139 6601 +15770 3728 5950 3982 6863 +15771 6258 6374 5078 6915 +15772 2956 6320 5828 6526 +15773 5337 5911 5338 6650 +15774 3336 5773 5771 6554 +15775 3164 5843 3029 6665 +15776 1867 6661 5940 6946 +15777 4702 5755 6378 6786 +15778 3986 6009 6412 7054 +15779 4656 6049 5207 7001 +15780 2104 6624 6152 6912 +15781 4698 5934 5239 6374 +15782 4416 4371 4208 6066 +15783 4790 4713 5014 5866 +15784 5808 6436 5858 7033 +15785 4977 6041 4978 6101 +15786 5410 5793 504 6566 +15787 3021 6162 5814 6646 +15788 6055 4059 6681 7015 +15789 3224 6158 5976 7142 +15790 5283 5771 5773 7135 +15791 526 6100 6379 6935 +15792 5185 5236 6508 6745 +15793 2425 5800 6039 6388 +15794 5992 6479 6355 7213 +15795 2671 2673 5867 6872 +15796 5286 5943 5902 6210 +15797 2582 5998 2590 6446 +15798 6641 6725 3939 6807 +15799 3981 3855 3750 6126 +15800 1717 6206 5932 6833 +15801 3368 2836 6058 6542 +15802 3592 6421 6014 6682 +15803 4026 5858 6178 6368 +15804 6192 6501 6348 6918 +15805 4760 5775 610 6417 +15806 3075 5759 6590 6985 +15807 3201 6084 2620 6163 +15808 569 5795 5766 6215 +15809 2703 2700 5786 6831 +15810 4446 4054 6286 6494 +15811 5041 4643 6470 7106 +15812 4207 5838 4398 5935 +15813 5197 5188 6471 6929 +15814 5981 6282 3198 6473 +15815 3781 6725 3872 6913 +15816 6271 6406 4140 6407 +15817 1353 6048 6519 7165 +15818 1968 6349 6142 6578 +15819 2544 6010 6199 6495 +15820 5987 6546 3653 7048 +15821 2440 5857 2439 6013 +15822 5106 5107 4620 6514 +15823 488 4526 6370 7062 +15824 5116 6177 6050 6380 +15825 3020 5868 3065 6338 +15826 2417 6083 3131 6551 +15827 5074 5075 5795 6273 +15828 1751 1841 6204 6376 +15829 4854 4855 6028 7068 +15830 1902 1885 1462 5852 +15831 3948 1903 1884 5851 +15832 5836 5994 4359 6501 +15833 5417 6200 5394 6762 +15834 5040 4794 4795 6536 +15835 5949 5950 1731 6806 +15836 4747 4721 4722 6013 +15837 4043 6064 5967 6958 +15838 5188 5234 5184 6218 +15839 4814 5976 5975 7055 +15840 4827 5898 6177 6750 +15841 3566 6317 2799 6643 +15842 3157 5846 2645 5956 +15843 3510 3508 6330 6738 +15844 2917 5811 6472 6515 +15845 1521 6770 6769 6771 +15846 4007 6773 6772 6774 +15847 440 5979 6123 6999 +15848 3448 7138 6183 7147 +15849 3837 6807 6128 7193 +15850 4935 5956 5846 6719 +15851 1689 6151 6149 7153 +15852 2312 6295 2333 6598 +15853 487 6370 6262 7104 +15854 5125 5776 5259 5965 +15855 5197 6471 6220 6929 +15856 2544 6495 6199 6839 +15857 5784 6224 6004 7123 +15858 3603 6251 6092 6260 +15859 6090 6107 2170 6328 +15860 5813 6518 5376 6987 +15861 4854 5944 6394 7068 +15862 507 6360 6061 6822 +15863 5912 5957 5218 6748 +15864 4112 4270 4472 5816 +15865 612 5884 5963 6412 +15866 539 5987 5785 6798 +15867 462 5949 6440 6833 +15868 3107 2693 5938 6670 +15869 3148 3337 5861 7019 +15870 2596 6003 6002 6724 +15871 3237 3238 3236 5892 +15872 531 6503 530 6938 +15873 3085 5971 2792 6969 +15874 2041 6168 6167 6490 +15875 5398 5400 5375 6598 +15876 2299 2313 6241 6266 +15877 4597 6224 6002 7123 +15878 2478 6237 6236 6799 +15879 372 371 6962 7063 +15880 2834 6542 5914 7088 +15881 5372 6184 5390 6478 +15882 5206 5247 5282 6554 +15883 6825 7070 499 7071 +15884 1620 5922 1533 7082 +15885 2465 6451 5854 6582 +15886 2784 6445 6320 6526 +15887 1994 1764 2093 5788 +15888 3278 5864 6560 6613 +15889 4146 5951 4413 6386 +15890 479 6305 6194 6423 +15891 3981 2067 6126 6369 +15892 6225 6350 1900 6579 +15893 5927 5970 4957 6217 +15894 5807 5953 4331 6669 +15895 3034 6282 6122 7052 +15896 5852 5974 1269 6791 +15897 5851 5973 3755 6790 +15898 5206 6049 5204 6298 +15899 5304 5986 5779 6392 +15900 5185 4881 5236 6745 +15901 3074 5834 3140 6103 +15902 5059 6122 4798 6237 +15903 2056 1845 6073 6410 +15904 3214 3215 3332 6300 +15905 2174 2024 1657 7079 +15906 2783 2646 3219 5978 +15907 4218 6669 5952 7130 +15908 3206 6814 6268 6926 +15909 3467 6129 6411 6477 +15910 6184 6185 2297 6948 +15911 440 3657 441 6123 +15912 5268 6227 4658 6228 +15913 3571 2555 3113 6265 +15914 6103 2526 6267 7030 +15915 6184 6405 338 6854 +15916 3090 5904 2519 6454 +15917 4286 6396 4190 7091 +15918 6072 6663 6420 7177 +15919 1866 6352 6205 6376 +15920 542 4817 5241 6696 +15921 1827 5812 2183 5844 +15922 4194 6385 6071 6980 +15923 5327 5834 4681 6103 +15924 5402 5414 5381 6777 +15925 4218 6341 5952 6669 +15926 335 334 6110 6439 +15927 4965 4872 6272 7043 +15928 1709 6079 5991 6316 +15929 5032 6106 6447 6448 +15930 474 6094 6093 6327 +15931 4926 4925 5944 6394 +15932 2995 5874 6431 7101 +15933 6133 6559 4481 7178 +15934 1871 5947 6242 7072 +15935 5407 6401 5793 7038 +15936 5970 6217 3274 6471 +15937 4496 6255 4515 6650 +15938 3614 5796 3591 6967 +15939 5140 5339 5936 6466 +15940 4026 4469 4221 5858 +15941 5291 5196 5319 5786 +15942 2349 2297 2318 6948 +15943 514 6201 6452 6762 +15944 1255 5998 1456 6824 +15945 4543 540 5987 6421 +15946 6188 4587 6235 7050 +15947 3448 5912 7138 7147 +15948 2888 2890 6096 6103 +15949 1872 5807 5853 7130 +15950 1228 6089 6088 6712 +15951 1650 1994 2093 5756 +15952 364 2689 5920 6617 +15953 4546 5903 544 6456 +15954 4958 5970 6220 6471 +15955 522 6110 6329 6439 +15956 4734 6695 5775 7098 +15957 3622 6255 6051 6592 +15958 1503 1421 6453 6809 +15959 6284 6285 331 6387 +15960 5947 6090 4364 6516 +15961 4789 5978 4791 6872 +15962 5276 5227 5073 6496 +15963 2776 6472 5811 6700 +15964 2045 1881 6635 7131 +15965 4550 6160 4524 6520 +15966 5962 6299 5898 7211 +15967 3006 6060 5811 7029 +15968 5007 5085 5831 6269 +15969 5107 6514 6155 6951 +15970 1716 5933 1935 6278 +15971 5776 5965 5125 6831 +15972 4680 6267 5834 7182 +15973 4801 6214 6213 6469 +15974 1650 6142 5756 6578 +15975 3528 5772 6046 7139 +15976 3629 6253 3658 6362 +15977 6137 6269 5307 6789 +15978 508 6116 6068 6119 +15979 2936 6088 6089 6247 +15980 2665 3238 3300 6231 +15981 533 5855 5924 6768 +15982 5868 5879 3020 6414 +15983 490 491 6111 7156 +15984 4875 4873 4856 7211 +15985 1459 1368 1225 6458 +15986 3945 3854 3711 6459 +15987 1512 6111 5804 6883 +15988 1297 5899 1491 6572 +15989 2326 2350 6157 6234 +15990 1585 6305 6194 6568 +15991 4216 4134 6375 6376 +15992 1728 2160 1991 6111 +15993 5272 6243 5028 6522 +15994 2850 6235 2852 7124 +15995 4226 5876 4110 6146 +15996 1745 6133 6132 6817 +15997 4696 5892 4698 6657 +15998 6326 6344 1812 6493 +15999 6264 6751 3797 6882 +16000 4980 4861 5801 6372 +16001 4781 5867 4782 6247 +16002 2303 2359 6777 7066 +16003 1292 6413 6498 6869 +16004 4238 4464 5999 6000 +16005 3293 3209 6390 6711 +16006 4463 4237 6468 6740 +16007 5024 5859 4867 6608 +16008 5980 6053 5226 6367 +16009 2910 6166 5829 7120 +16010 1689 6149 6019 7153 +16011 5800 6514 6039 6763 +16012 5969 6797 6077 7089 +16013 3640 6306 6307 6871 +16014 2488 6229 5822 6680 +16015 2928 6267 5791 7182 +16016 6177 6378 5116 7016 +16017 6074 6276 3316 6277 +16018 5104 4632 4633 6083 +16019 4039 6176 5891 6225 +16020 4128 4261 4214 5769 +16021 1539 5803 1543 6794 +16022 6151 6152 4297 6912 +16023 5252 5957 6180 6513 +16024 4837 6353 4756 6358 +16025 5796 6262 487 6370 +16026 451 6126 450 6505 +16027 572 571 5882 6758 +16028 6168 6223 6187 7171 +16029 5269 6228 5267 6314 +16030 1925 5788 1994 6142 +16031 3107 3105 3254 5938 +16032 3341 6212 6030 6921 +16033 2671 6170 2672 6872 +16034 5794 2430 6259 7035 +16035 3560 2874 5892 6216 +16036 4096 6025 4406 6395 +16037 3692 3786 3891 6038 +16038 5243 5894 5242 6472 +16039 4193 7176 6441 7184 +16040 5273 5870 4710 6711 +16041 1877 6153 6151 7153 +16042 1193 6594 1406 6940 +16043 3679 6593 3892 6939 +16044 4209 4415 6055 6681 +16045 6151 2121 6360 7180 +16046 514 6762 6452 7202 +16047 3358 6181 3430 6219 +16048 261 6254 262 6418 +16049 4905 5784 6004 7123 +16050 1983 1713 2031 6114 +16051 3485 6888 6007 6910 +16052 4167 6403 6018 7210 +16053 5139 5936 5061 6647 +16054 1353 6722 6571 7165 +16055 5929 6835 5942 7175 +16056 4634 5356 5353 6573 +16057 4827 5898 4826 7204 +16058 3129 5983 6083 6606 +16059 5858 4221 6178 6726 +16060 5000 6613 4669 7103 +16061 5410 5793 25 7038 +16062 3258 6332 3257 6477 +16063 4324 5967 4330 6175 +16064 3340 2635 6030 6336 +16065 4631 4630 6336 6346 +16066 3012 3010 3011 5918 +16067 2034 1663 1793 6315 +16068 1794 6033 2079 6034 +16069 3571 2555 6265 6378 +16070 5889 6099 4778 7181 +16071 5197 5234 5188 6929 +16072 5247 6554 6298 6842 +16073 3368 6058 2836 7173 +16074 586 587 6321 6470 +16075 2459 3119 3195 6257 +16076 2078 6133 6559 6800 +16077 2971 6400 6210 6621 +16078 3461 6340 6065 6353 +16079 1309 6416 5995 6585 +16080 2363 5901 376 6171 +16081 5211 5770 5165 5883 +16082 4673 5777 5004 7078 +16083 3243 3244 3056 5824 +16084 3142 3211 6424 6831 +16085 1724 5891 2054 6175 +16086 2845 2846 2847 6279 +16087 2641 3319 6010 6199 +16088 5858 6436 4221 6726 +16089 5408 5767 6309 6793 +16090 1285 1488 3035 6016 +16091 3678 461 3787 6440 +16092 5069 5064 6339 6382 +16093 4565 5963 5964 7073 +16094 5156 6056 6024 6239 +16095 1677 6250 2075 6373 +16096 2430 5893 7035 7045 +16097 2623 2626 6131 6361 +16098 5404 6171 5403 6679 +16099 6092 6255 3625 6308 +16100 2926 2721 3080 5941 +16101 6131 6361 5086 6398 +16102 3434 3502 3435 6842 +16103 5335 4824 5870 6001 +16104 5901 6017 590 6692 +16105 4523 6253 4500 6546 +16106 4917 5832 4893 6659 +16107 2893 5961 3523 6742 +16108 325 1427 1258 5995 +16109 5519 6773 5477 6873 +16110 5677 6770 5635 6874 +16111 2082 6377 2176 6588 +16112 4474 4471 4179 6599 +16113 5070 6003 6340 6630 +16114 2985 6087 5910 6576 +16115 4400 6420 6072 6663 +16116 5574 619 5530 6604 +16117 2086 1855 1770 6290 +16118 4659 6609 6228 7102 +16119 5082 4951 6469 7125 +16120 2712 3812 3873 6957 +16121 5038 5794 4942 5978 +16122 5881 4735 6589 6982 +16123 5033 5990 5778 6361 +16124 5260 6252 5077 6552 +16125 5187 6300 5348 6567 +16126 6298 6554 5993 6842 +16127 5808 6386 6026 7033 +16128 6150 3347 6710 7155 +16129 2722 3182 2723 6042 +16130 5115 5961 6742 7197 +16131 1827 1641 5812 5844 +16132 4819 6036 5284 6159 +16133 2800 5886 6164 7052 +16134 515 6452 6201 6506 +16135 4278 6248 6249 6335 +16136 5964 6279 2804 6484 +16137 5053 5941 4923 6433 +16138 2741 6062 5780 6364 +16139 6032 4152 6356 6432 +16140 5972 6330 2791 6843 +16141 4219 6205 6204 6671 +16142 5778 5990 3093 6361 +16143 5789 5805 4729 6523 +16144 511 6443 6296 6990 +16145 3164 3030 3029 5843 +16146 5748 6879 6827 6901 +16147 2596 3315 6003 6724 +16148 1648 2071 1870 6207 +16149 5780 6062 4775 6364 +16150 3917 3746 5797 6805 +16151 4344 4138 4426 6385 +16152 4576 5981 5778 6108 +16153 3431 6245 5784 6652 +16154 517 6184 6405 6506 +16155 3485 2667 6143 6888 +16156 552 6445 5833 6739 +16157 2891 6495 6095 6767 +16158 4774 573 5917 6808 +16159 1966 6026 1753 6681 +16160 1652 5838 2158 6532 +16161 4160 5872 6310 6733 +16162 4947 5052 5118 6744 +16163 5871 6328 6090 6880 +16164 5243 5894 6472 6515 +16165 1721 6375 5895 6934 +16166 2263 6579 6331 6581 +16167 2944 5806 2817 6080 +16168 2089 6315 6079 6316 +16169 2797 6217 5927 6236 +16170 1995 1725 2053 5935 +16171 5889 6189 7049 7195 +16172 5965 6172 3483 6424 +16173 5996 6429 1964 7184 +16174 4258 6315 6156 6316 +16175 1420 6640 1182 6781 +16176 3515 3384 3386 6908 +16177 4220 6230 4121 6975 +16178 1994 5788 1925 6796 +16179 4844 6245 5815 6652 +16180 4462 6144 6145 6193 +16181 1378 1228 1436 6089 +16182 4877 4677 6896 7159 +16183 4250 6134 4108 6859 +16184 2722 2723 5819 6042 +16185 2598 2599 2597 6438 +16186 3797 5797 3997 6805 +16187 483 6202 5845 6463 +16188 509 508 6119 6360 +16189 4073 6066 4340 6677 +16190 5822 6115 2364 6981 +16191 6100 6559 4072 6800 +16192 3192 3191 6243 6455 +16193 1905 2048 6286 7170 +16194 5758 4598 5826 6763 +16195 5928 6127 4229 6544 +16196 4977 4976 4978 6041 +16197 5287 5361 5286 5902 +16198 5390 6185 6962 7063 +16199 29 6720 531 6938 +16200 2725 1284 3121 5850 +16201 522 6145 6329 7143 +16202 2471 2557 6050 6070 +16203 2530 6189 5875 6523 +16204 5413 504 5410 5793 +16205 2121 6151 1877 7180 +16206 5097 5794 5037 7035 +16207 458 5851 457 5954 +16208 497 498 5852 5955 +16209 3448 5759 5912 7147 +16210 5069 6382 5912 6748 +16211 3326 6332 3259 6333 +16212 5116 6378 6177 7204 +16213 2809 2984 5942 7175 +16214 4801 4951 6214 6469 +16215 4082 5891 4351 6175 +16216 437 5894 6421 6515 +16217 4593 6197 5078 6915 +16218 2284 6294 6100 6718 +16219 4405 6406 4141 6494 +16220 4591 590 6017 6692 +16221 2929 6267 6514 6951 +16222 5395 6241 5374 6266 +16223 2954 5828 2956 6320 +16224 1708 2042 6225 7056 +16225 5835 5917 573 6808 +16226 2443 5896 6693 6898 +16227 3193 6021 3494 6243 +16228 3808 1620 3843 5922 +16229 1693 5928 1881 7131 +16230 6205 6410 6352 7032 +16231 2201 5798 6383 6566 +16232 1612 6370 6419 7104 +16233 4704 6095 4703 6627 +16234 2047 5756 1740 6450 +16235 3631 5753 3632 5781 +16236 3220 5849 3117 6158 +16237 2844 2843 5831 6885 +16238 6147 6510 528 7034 +16239 558 6453 559 6694 +16240 2743 6484 6062 7121 +16241 5815 3424 6245 6618 +16242 4990 5863 4974 5984 +16243 1777 6225 1900 6238 +16244 4148 6410 4303 7032 +16245 5625 6788 5715 6994 +16246 3119 5823 6526 6937 +16247 2815 2813 5870 6001 +16248 2228 348 6116 6119 +16249 572 6274 573 6968 +16250 2835 2832 5914 6552 +16251 4709 4708 6143 6231 +16252 4081 5788 6196 6796 +16253 2929 5826 5791 6951 +16254 2361 6171 2327 6435 +16255 3052 6378 5962 7204 +16256 3024 5789 2453 6764 +16257 4003 3741 6666 6749 +16258 5819 5972 2552 6433 +16259 2965 5964 5963 7073 +16260 4894 5832 5925 6659 +16261 3797 5798 5797 6805 +16262 2795 6031 6512 6697 +16263 4364 5947 6516 7072 +16264 1738 5760 6599 6600 +16265 4410 5756 4490 7100 +16266 3447 3536 2386 6173 +16267 2095 6178 6368 7092 +16268 4409 6144 6132 6344 +16269 5341 6554 5282 6842 +16270 5270 6106 5842 6363 +16271 5215 5092 5065 6747 +16272 4998 6613 6086 7103 +16273 2068 6111 1495 6467 +16274 6004 6224 3429 7166 +16275 6570 6730 3775 6953 +16276 6569 6729 1290 6954 +16277 264 263 6093 6327 +16278 3499 3438 6117 6358 +16279 521 6241 6110 6439 +16280 4756 6353 4585 6447 +16281 366 2512 367 5939 +16282 4198 4424 475 6134 +16283 5458 6529 5505 6978 +16284 5663 5616 6528 6979 +16285 2223 6209 2220 6479 +16286 3241 6131 2626 7027 +16287 2488 6680 5822 6981 +16288 563 6015 6089 6247 +16289 4039 4257 6225 6906 +16290 2988 5984 6059 6815 +16291 3399 5873 3405 6908 +16292 2809 5942 7065 7175 +16293 5359 6063 6489 7084 +16294 4951 6235 6469 7125 +16295 3627 3659 6313 6462 +16296 5392 6135 6136 6478 +16297 3803 6620 6840 6953 +16298 1317 6619 6841 6954 +16299 1721 5895 1999 6934 +16300 5767 6793 5408 7165 +16301 4827 6177 5898 7204 +16302 2238 2241 2239 6586 +16303 4233 6450 6578 6946 +16304 2433 2401 5850 7096 +16305 6185 6201 2318 6948 +16306 4316 5853 4142 6006 +16307 1319 6825 6684 7071 +16308 4449 4188 4116 6864 +16309 3155 2595 5908 7173 +16310 2833 2836 2834 7088 +16311 2650 2651 2649 6036 +16312 5070 5225 6489 6630 +16313 2953 2945 6013 6623 +16314 5779 6008 3239 6560 +16315 5843 3164 6274 6665 +16316 1474 1289 6632 6860 +16317 3096 5907 5903 6832 +16318 325 2211 1427 5995 +16319 4604 6454 5904 6792 +16320 5398 5425 6045 6598 +16321 1872 5853 2116 7130 +16322 1862 1875 5876 6146 +16323 4506 6313 6261 6894 +16324 2170 6090 2112 6107 +16325 3095 6696 3252 7067 +16326 3090 2517 5904 6792 +16327 2063 5982 2156 6207 +16328 6122 6282 3034 6398 +16329 5956 6536 5040 6651 +16330 5467 6922 6584 6989 +16331 4092 6064 6375 6577 +16332 2031 2185 6113 6114 +16333 4803 6214 5859 7127 +16334 4232 6144 4432 7057 +16335 5956 4794 6536 6719 +16336 3917 5797 320 6805 +16337 4792 5779 5055 6008 +16338 2349 6184 2297 6948 +16339 6065 6340 4837 6353 +16340 4039 6225 5891 6906 +16341 5436 5409 5368 6141 +16342 2409 6526 5823 7116 +16343 6188 6235 2852 7050 +16344 6195 6336 3330 6346 +16345 2440 2983 5857 6013 +16346 570 5732 6482 6602 +16347 4949 5778 5033 5990 +16348 4094 5947 5802 6858 +16349 5249 6304 6210 6591 +16350 5892 6216 2874 6486 +16351 4675 6224 4674 6425 +16352 5213 6496 6041 6738 +16353 557 5969 4539 7089 +16354 5349 6085 4669 6086 +16355 6262 6370 1611 7104 +16356 3206 376 6268 6814 +16357 2300 6136 6135 6478 +16358 3163 5863 2573 5984 +16359 1779 6547 2164 7118 +16360 5366 6063 4615 6345 +16361 2081 1745 6132 6817 +16362 5933 6278 1716 6917 +16363 6016 6381 2683 6761 +16364 5823 6257 5044 6937 +16365 5130 6281 5228 6507 +16366 5625 6923 6583 6994 +16367 6554 6842 5341 7135 +16368 5241 5242 542 5894 +16369 1704 1808 5818 6958 +16370 3051 6082 6427 6513 +16371 5821 6342 3515 6908 +16372 1652 1926 5838 5865 +16373 5397 5399 6234 6325 +16374 3198 6282 5981 6500 +16375 3521 6330 6101 6738 +16376 3397 6281 6753 6837 +16377 3201 6085 6084 6163 +16378 435 6121 5894 6302 +16379 5878 6206 2038 6615 +16380 4854 6299 4855 7068 +16381 514 6040 6762 7202 +16382 4746 6083 6013 6623 +16383 1670 2018 1882 6395 +16384 2013 6138 2181 6337 +16385 2976 5801 5868 6651 +16386 4283 6490 6168 7188 +16387 4602 4830 6342 7149 +16388 4368 6093 5946 6494 +16389 3299 3205 5772 6480 +16390 2211 5995 2212 6572 +16391 2018 1882 6395 6601 +16392 4865 4729 5805 6523 +16393 1691 6211 2127 6377 +16394 2550 5972 3055 6031 +16395 2162 1992 1730 6126 +16396 2845 2847 2802 6279 +16397 2183 5812 1827 6949 +16398 3439 3465 5787 6065 +16399 3079 6086 6085 6919 +16400 5837 7047 6066 7192 +16401 509 6119 6068 6443 +16402 4751 6480 5926 7067 +16403 2793 5941 2547 6433 +16404 3287 6333 3258 6411 +16405 5314 5259 5776 6424 +16406 2640 6010 5757 6372 +16407 2519 3090 2517 5904 +16408 5763 2108 6614 6909 +16409 4583 5931 6380 7140 +16410 3465 5792 5787 6065 +16411 4658 4659 6228 7102 +16412 3214 3332 6195 6300 +16413 4074 6055 4209 6386 +16414 6250 6301 4275 6658 +16415 2357 2326 6157 6285 +16416 4303 4044 6205 6410 +16417 6632 6850 5639 6851 +16418 1380 5933 6684 6825 +16419 2929 5791 6267 6951 +16420 548 6159 6051 6160 +16421 565 564 6016 6699 +16422 3273 3179 5842 6363 +16423 4989 4841 6656 7106 +16424 1661 2086 6018 6403 +16425 5905 6107 1947 7146 +16426 571 5843 5223 6274 +16427 6105 6227 4657 7001 +16428 5100 4791 4789 5978 +16429 4665 6117 5031 7148 +16430 3255 6182 5943 7055 +16431 4250 4424 4108 6134 +16432 5790 6074 3497 6970 +16433 2719 2606 5998 6125 +16434 4078 6310 6006 6616 +16435 5050 5159 5160 6173 +16436 4920 6104 6197 6656 +16437 4050 5915 4282 6909 +16438 5069 5068 4907 6339 +16439 5000 4669 6069 7103 +16440 508 6360 507 6822 +16441 3488 3443 6425 6426 +16442 3645 5796 6261 6894 +16443 2450 6088 2936 6247 +16444 4448 4391 6120 6373 +16445 4060 6271 6270 7069 +16446 4023 4324 6175 6673 +16447 2237 6625 6443 7180 +16448 2731 3089 5832 7021 +16449 1894 6501 6192 6918 +16450 6029 6186 1732 6930 +16451 5895 6375 1721 6577 +16452 1957 1793 6315 6377 +16453 2242 6397 2240 6586 +16454 2444 5889 2445 6523 +16455 1495 1369 1264 6111 +16456 1213 6874 7011 7111 +16457 3699 6873 7009 7112 +16458 457 5973 5851 6790 +16459 497 5974 5852 6791 +16460 2705 2704 2757 5811 +16461 3349 6288 3348 6347 +16462 4876 6183 7138 7147 +16463 6013 6083 3073 6816 +16464 4671 4672 5059 6431 +16465 5689 6498 6689 6901 +16466 4584 6353 6340 6404 +16467 2082 1823 2176 6377 +16468 6570 6716 3775 6730 +16469 4680 4884 4987 5791 +16470 4550 549 6160 7039 +16471 584 5806 4737 6981 +16472 3227 3538 5790 7182 +16473 5259 6172 5965 6424 +16474 3284 3494 6021 6522 +16475 2939 2874 6216 6486 +16476 2096 5844 6441 6995 +16477 3099 3241 2909 6512 +16478 2189 1763 1869 5816 +16479 1904 2047 6450 6578 +16480 3142 2755 5776 6424 +16481 4861 6010 5801 6372 +16482 523 6110 5396 6157 +16483 6835 7065 5942 7175 +16484 619 6604 6317 6826 +16485 3538 5997 5791 7020 +16486 601 5863 602 7007 +16487 5841 5842 3179 6363 +16488 6034 4196 6312 6980 +16489 5825 6962 371 7063 +16490 4890 5077 6252 6552 +16491 4712 5866 4791 5867 +16492 4588 4933 6235 7124 +16493 3163 3165 5863 6815 +16494 2359 2303 6284 7066 +16495 2327 6296 2368 6435 +16496 5902 6210 2992 6400 +16497 3150 5965 5923 6172 +16498 3613 6307 3605 6592 +16499 6024 6056 3550 6239 +16500 5467 6821 5557 6989 +16501 5187 6179 6300 6567 +16502 4752 5925 4892 5926 +16503 2323 5793 352 6318 +16504 5357 6011 5358 7158 +16505 1858 5960 5769 6244 +16506 522 523 6145 7143 +16507 4935 6062 6719 6861 +16508 4987 6710 4882 7155 +16509 4608 4612 5765 6870 +16510 2480 6481 5917 6799 +16511 5274 5225 5071 6065 +16512 2847 6279 5847 6484 +16513 4011 4362 6537 7141 +16514 4810 6217 5002 6236 +16515 1284 5850 6543 6810 +16516 4135 6429 6238 6579 +16517 2891 6095 3210 6767 +16518 4718 6246 5887 6414 +16519 5030 5118 5052 6393 +16520 3390 5980 3356 6496 +16521 6033 6034 4392 6847 +16522 4652 5841 4653 5842 +16523 5893 6259 2430 7035 +16524 4286 4190 6223 7091 +16525 5179 5157 5129 5819 +16526 6270 6271 4060 7187 +16527 5017 5016 535 6414 +16528 4135 6225 6429 6579 +16529 5004 5777 5003 6236 +16530 4800 4799 5025 7052 +16531 483 6463 5845 6574 +16532 3125 5766 2709 6727 +16533 4342 4084 5952 6113 +16534 1969 2099 6071 6980 +16535 3322 2636 2638 6272 +16536 4007 3925 6773 6873 +16537 1521 1439 6770 6874 +16538 5777 5003 6236 6237 +16539 1309 6476 6416 6585 +16540 5226 6053 5146 6367 +16541 5529 5553 6840 6953 +16542 5687 5711 6841 6954 +16543 3099 3098 6131 6166 +16544 2366 6001 6200 6628 +16545 5325 5860 4749 6390 +16546 1559 6408 6409 6442 +16547 3357 3430 3358 6181 +16548 1838 6140 6081 6661 +16549 1781 6006 2177 6535 +16550 5129 5313 5972 6433 +16551 4332 6205 4131 6376 +16552 5838 5935 4207 7095 +16553 4041 6132 4296 6344 +16554 2453 5969 5805 6927 +16555 4740 6046 4741 6555 +16556 487 4560 486 6262 +16557 6528 6703 5661 6867 +16558 6529 6702 5503 6868 +16559 1791 5958 1667 5994 +16560 2729 6009 2924 7073 +16561 2977 6036 5911 6502 +16562 4743 5325 4745 6936 +16563 4506 4522 6261 6313 +16564 507 6061 6209 6822 +16565 3134 5799 3133 7019 +16566 3229 6008 3013 6613 +16567 4935 6719 5846 6861 +16568 5040 5956 4794 6536 +16569 2101 1732 6186 6930 +16570 4859 6010 4858 6199 +16571 4428 6205 4044 6352 +16572 5936 6084 2948 6647 +16573 5866 6259 5794 7152 +16574 1934 6369 3798 7025 +16575 5763 2108 6909 7115 +16576 3580 3381 6091 6130 +16577 4182 6090 5871 6991 +16578 2997 5887 6246 6414 +16579 1796 6113 5966 6635 +16580 2950 5789 2952 6764 +16581 4175 6098 6223 7171 +16582 482 5948 6078 6202 +16583 1428 6540 6819 7199 +16584 6538 6818 3914 7200 +16585 5791 5997 3538 6710 +16586 2095 5760 2118 7092 +16587 4356 4229 6127 6544 +16588 327 326 6141 6287 +16589 4677 5329 4877 5755 +16590 4974 6059 5984 6815 +16591 587 6045 6321 6470 +16592 2384 2383 5936 6647 +16593 6443 6625 6153 7180 +16594 504 6383 5992 6505 +16595 6006 6310 1643 6616 +16596 6254 6418 261 6568 +16597 5262 5972 5313 6031 +16598 4142 4477 6006 6950 +16599 4151 6322 6057 6527 +16600 4672 4670 5874 6823 +16601 1775 6138 5877 6615 +16602 6138 6337 2013 6884 +16603 1301 6825 6563 6997 +16604 1980 5812 1740 6328 +16605 4876 5136 5957 6181 +16606 4958 6220 5197 6471 +16607 4629 6195 4631 6336 +16608 6227 6626 4656 7001 +16609 4059 6055 6460 7015 +16610 2428 2614 6976 6977 +16611 6340 6353 3491 6404 +16612 4537 4561 4493 6190 +16613 5099 5040 5868 6651 +16614 3391 5821 3390 6496 +16615 5332 6082 5154 6426 +16616 470 6112 6546 6943 +16617 5192 6277 6074 6280 +16618 6092 6251 4518 6260 +16619 5954 4079 6547 6740 +16620 6463 6464 1609 6465 +16621 3546 3475 3583 5787 +16622 6351 6380 4570 6761 +16623 2732 2731 5926 6700 +16624 5807 6525 4263 7141 +16625 4220 5977 6230 6975 +16626 5404 5403 6296 6679 +16627 6007 6888 6612 6910 +16628 6649 6732 1214 6940 +16629 6648 6731 3700 6939 +16630 5350 5909 5786 6708 +16631 5810 6124 2769 7041 +16632 5987 6421 3607 6682 +16633 3505 2517 6215 6273 +16634 4752 5925 4751 6480 +16635 470 4547 6409 6943 +16636 2036 6493 6175 6673 +16637 5816 5982 4191 6601 +16638 5777 5918 3010 7078 +16639 4905 4904 4903 7123 +16640 1976 1720 5802 5947 +16641 5896 6229 5820 6680 +16642 5206 5282 5961 6554 +16643 1979 6599 6118 6600 +16644 5782 6764 4728 7181 +16645 6459 6584 3854 7094 +16646 5028 6243 4764 6609 +16647 456 5954 5973 6468 +16648 1701 5905 6139 6778 +16649 2758 3009 2894 6075 +16650 3353 3356 5980 6496 +16651 2593 2836 6058 7173 +16652 4793 5917 5303 6799 +16653 6100 6311 4145 6559 +16654 5257 5048 5923 6173 +16655 5934 6001 5279 6926 +16656 4307 6006 6535 6616 +16657 3227 5790 3538 6710 +16658 1432 6705 6655 6960 +16659 3918 6704 6654 6959 +16660 3793 1990 5949 5950 +16661 496 4411 4238 6000 +16662 3151 5965 5786 6708 +16663 3190 6101 6102 6455 +16664 1817 5928 1639 6544 +16665 5816 6139 2115 6601 +16666 3858 5809 3964 6721 +16667 2371 5754 3831 6889 +16668 2141 6019 1770 6290 +16669 5811 6060 2732 6700 +16670 5763 6614 4355 6909 +16671 4450 4288 5982 6734 +16672 6147 528 6718 7018 +16673 6111 6787 6467 7156 +16674 435 436 5894 6121 +16675 3028 5777 3026 6237 +16676 3278 3078 3275 5864 +16677 3307 3306 6263 6455 +16678 4605 6162 5904 6646 +16679 2692 6514 3167 7077 +16680 4434 5953 6460 7059 +16681 1544 6428 6415 6698 +16682 2131 6222 6027 6964 +16683 5818 5967 1932 6836 +16684 5815 6012 3424 6618 +16685 6097 6838 1679 7118 +16686 4516 4502 4551 6672 +16687 5824 5006 5997 7020 +16688 5871 6196 5872 6991 +16689 434 6456 6302 6832 +16690 6531 7011 5619 7111 +16691 6530 7009 5461 7112 +16692 517 6405 6319 6506 +16693 554 5013 553 6739 +16694 5000 6069 6613 7103 +16695 1944 5955 1647 6000 +16696 5760 5885 1821 6532 +16697 3144 5956 3145 6199 +16698 574 4774 4773 6446 +16699 4146 5808 4273 6286 +16700 4683 6700 5094 7021 +16701 3435 3502 6297 6842 +16702 1661 6403 6018 6796 +16703 4833 4831 5846 5847 +16704 4666 6085 6084 6647 +16705 2792 5971 6697 6969 +16706 6069 6075 3009 6647 +16707 5041 6371 5857 6914 +16708 2807 2949 2808 5782 +16709 1807 1675 6283 6607 +16710 4446 4484 4054 6494 +16711 2322 5822 2373 6401 +16712 1538 6324 5803 6925 +16713 6151 6153 4158 7153 +16714 5186 5188 5184 6023 +16715 4964 4914 4683 5757 +16716 6475 6950 4477 7185 +16717 2311 326 5767 6141 +16718 5070 6340 4836 6630 +16719 469 4547 6253 6409 +16720 499 6684 5933 6825 +16721 3178 3177 3039 6591 +16722 4196 6034 4052 6980 +16723 4616 6084 5144 6163 +16724 334 2271 333 6329 +16725 4248 4391 6373 6658 +16726 505 506 6355 6479 +16727 6160 6307 4505 6520 +16728 6023 6573 5356 6899 +16729 5962 5985 4700 6786 +16730 608 5414 5854 6309 +16731 5884 6412 612 6736 +16732 4799 6122 6282 7052 +16733 2315 6184 338 6854 +16734 5952 6283 4084 7185 +16735 1456 5998 2973 6824 +16736 6008 7065 3239 7127 +16737 3184 5902 3111 6210 +16738 3485 6231 2667 6888 +16739 5865 6532 1963 6597 +16740 470 6546 4547 6943 +16741 5835 5917 6808 6968 +16742 6149 6535 2177 6616 +16743 522 6329 523 7143 +16744 1910 5836 2169 5994 +16745 6067 6115 5382 6334 +16746 5906 1772 5959 7115 +16747 6100 6294 2284 6935 +16748 4161 6673 6226 6958 +16749 4479 4218 4046 7130 +16750 5287 5902 5286 5943 +16751 4344 5764 5877 6544 +16752 2002 2005 1735 5840 +16753 4495 6112 5987 6546 +16754 4608 4609 4612 6870 +16755 1438 325 1258 6902 +16756 5078 6104 4918 6258 +16757 2884 6172 2886 6275 +16758 1746 2116 5853 7130 +16759 4850 6378 6265 7016 +16760 5965 6424 3211 6831 +16761 2072 5838 1766 6599 +16762 367 366 5939 6052 +16763 5082 6174 5083 7125 +16764 5775 5827 610 6417 +16765 558 6458 6453 6694 +16766 465 6359 6198 7212 +16767 2443 6457 6693 6816 +16768 4367 4291 4038 6142 +16769 3541 2791 3542 6330 +16770 4435 5953 4331 6537 +16771 4971 5828 4847 6511 +16772 4693 6109 5079 6660 +16773 4899 6150 5997 7155 +16774 4100 6071 4400 6622 +16775 4425 6377 6073 6588 +16776 5384 6234 6052 7007 +16777 1399 1256 418 5919 +16778 592 6268 6814 6926 +16779 5390 6185 6184 6948 +16780 2866 3560 3238 6231 +16781 5996 6429 4257 6906 +16782 3457 5943 6182 7214 +16783 580 6189 5875 6587 +16784 5266 6444 6106 6483 +16785 5869 6320 2718 6963 +16786 4159 6132 6193 6379 +16787 1722 6270 5951 6386 +16788 580 6619 6587 6729 +16789 3621 3620 3594 6165 +16790 4216 6375 4345 6376 +16791 3389 6263 3514 6342 +16792 5296 5203 6101 6399 +16793 4298 4208 4073 6066 +16794 376 5901 2363 6268 +16795 1702 6441 1964 6706 +16796 5389 5377 5395 6266 +16797 6346 6573 3331 6899 +16798 4076 4272 5812 6949 +16799 616 6389 6388 7000 +16800 6015 6016 2683 6761 +16801 1879 6465 6211 6574 +16802 4073 4234 6073 6677 +16803 4871 4870 4872 7147 +16804 6301 6356 4152 6432 +16805 2700 6024 5786 6831 +16806 4625 6070 4891 6454 +16807 4354 6026 5769 6436 +16808 2603 5927 2797 6217 +16809 4272 4410 4076 5812 +16810 3290 5759 3449 6849 +16811 4907 6339 5068 6849 +16812 2129 6026 2051 7033 +16813 4061 4263 6310 6525 +16814 6106 6444 3473 6483 +16815 5945 6830 3802 7174 +16816 2311 6141 5767 6309 +16817 4351 4220 5891 5977 +16818 6084 6345 4617 7097 +16819 3501 6082 5957 6748 +16820 2941 6269 5921 6517 +16821 1568 6094 1569 6303 +16822 2305 2312 2333 6598 +16823 3184 3109 3111 5902 +16824 3581 6508 6219 6845 +16825 4843 4905 4903 5784 +16826 3048 6963 427 7039 +16827 4097 5960 5769 6026 +16828 2033 5878 5877 6544 +16829 2955 2954 2926 6511 +16830 4667 6069 4669 6085 +16831 5358 6011 5194 6012 +16832 4693 5079 4922 6660 +16833 1415 1255 6746 6974 +16834 5090 6382 5069 6748 +16835 5203 6101 6399 6662 +16836 5321 5909 5140 6466 +16837 5129 5053 5313 6433 +16838 6538 6676 3914 6818 +16839 6540 6675 1428 6819 +16840 4292 6225 4438 7056 +16841 2635 6272 6030 6336 +16842 3097 5907 434 6302 +16843 2393 6162 2392 6717 +16844 4506 6739 6313 6894 +16845 6097 6687 1679 6838 +16846 538 5987 5979 6546 +16847 3807 5798 2198 7169 +16848 2428 2614 6009 6976 +16849 4191 5982 5816 6207 +16850 1870 1721 6375 6577 +16851 5810 2443 6457 6693 +16852 2349 6506 6184 6948 +16853 5967 6673 4161 6958 +16854 4821 6042 6399 6678 +16855 5825 5860 2695 6390 +16856 5830 6571 1224 6860 +16857 2095 6368 5885 7092 +16858 2665 5799 2666 6231 +16859 1400 6048 357 6519 +16860 4914 5757 4916 6372 +16861 3671 3938 3987 6676 +16862 1185 1452 1501 6675 +16863 5843 5309 6274 6481 +16864 1861 1874 1675 5952 +16865 2824 2483 6122 6237 +16866 4672 4671 4670 6823 +16867 6121 6421 4513 6682 +16868 268 6408 6407 6524 +16869 5865 6079 5838 7095 +16870 2661 6392 5945 7174 +16871 3166 5937 3165 6815 +16872 3219 5978 5898 7211 +16873 3030 5843 3164 6274 +16874 4929 6010 5757 6767 +16875 2599 6150 5921 6438 +16876 2889 3064 2893 6627 +16877 3405 6367 5873 6590 +16878 3559 3557 2844 5758 +16879 5134 6037 5096 6553 +16880 1633 6026 6055 6386 +16881 611 5827 610 7145 +16882 4657 6227 4656 7001 +16883 3219 6945 5978 7211 +16884 6528 1401 6703 6867 +16885 3887 6702 6529 6868 +16886 2118 5760 1738 6600 +16887 3563 3075 5759 6590 +16888 3663 6233 6169 6653 +16889 4632 6083 4776 6457 +16890 572 573 6491 6968 +16891 1810 6242 2132 6537 +16892 5186 6023 5356 6899 +16893 2521 2506 2454 5805 +16894 4337 6244 5960 6516 +16895 4527 6251 4503 6302 +16896 3165 5939 5863 6815 +16897 6482 6602 1302 6775 +16898 1372 6571 5830 7107 +16899 2683 6015 2967 6016 +16900 1967 1864 1757 6093 +16901 5094 4917 5098 6037 +16902 4445 6064 4092 6577 +16903 4724 5896 6623 6680 +16904 5758 5800 2921 5862 +16905 5990 6208 5120 6737 +16906 4793 5886 4774 5917 +16907 5993 5341 6842 7135 +16908 2043 6316 5991 6779 +16909 5259 5311 5965 6172 +16910 4021 4207 4398 5935 +16911 2366 373 6001 6628 +16912 4738 5782 4726 7150 +16913 5043 5012 4779 5782 +16914 4278 6249 4086 6335 +16915 6018 6196 1851 6796 +16916 2074 6248 5762 6474 +16917 5791 5997 5006 7020 +16918 1942 5933 1716 6167 +16919 2406 6054 423 6445 +16920 3446 6426 6404 6448 +16921 568 5766 6191 6215 +16922 482 5948 4509 6078 +16923 5890 6410 1645 6588 +16924 3420 5786 3546 5792 +16925 2834 2836 6542 7088 +16926 5955 5999 1647 6000 +16927 5982 6395 4089 6601 +16928 4118 4311 6207 6577 +16929 1761 6206 5878 6838 +16930 6641 6807 3939 7193 +16931 2790 5823 2459 6099 +16932 4877 4676 4677 7159 +16933 4943 6985 4944 7043 +16934 6013 6623 6083 6816 +16935 2461 6229 2460 6680 +16936 4709 6231 5799 6711 +16937 5873 6367 3405 6908 +16938 523 522 6110 6329 +16939 25 6566 6264 7038 +16940 3556 5909 5792 7084 +16941 5854 6451 2415 6589 +16942 3122 5931 6454 6966 +16943 1643 6006 1803 6310 +16944 235 6409 6391 6943 +16945 2224 6479 6318 7053 +16946 3074 6103 2526 6267 +16947 2370 2337 6116 6598 +16948 5841 6542 5113 7022 +16949 5760 6600 6178 7092 +16950 5428 5377 5389 6266 +16951 3157 5956 2645 6839 +16952 4028 4450 4288 5982 +16953 3307 5821 3391 7149 +16954 1475 5875 1335 6729 +16955 5381 6777 5412 7066 +16956 1326 1517 1215 6125 +16957 5316 4899 5997 7155 +16958 4920 6197 4968 6656 +16959 5215 6004 4905 6652 +16960 5277 5172 5272 6021 +16961 4649 6129 4650 6339 +16962 2530 2445 6189 6523 +16963 5775 6695 6417 7098 +16964 32 6229 583 6401 +16965 5016 6020 535 6414 +16966 482 5845 6422 6779 +16967 2878 2580 3013 6008 +16968 4799 6282 6164 7052 +16969 3234 3235 5934 6814 +16970 1789 6559 6100 6800 +16971 5106 4620 6039 6514 +16972 4663 6117 5031 6447 +16973 3322 6053 6367 7043 +16974 5958 5959 4035 6501 +16975 2174 5900 2024 7079 +16976 5041 6914 5857 7106 +16977 4482 5876 4226 6396 +16978 3293 2666 2665 6711 +16979 5393 5386 5375 6598 +16980 4654 6129 5202 6477 +16981 3449 3075 5765 6985 +16982 3535 3282 6005 6195 +16983 1353 6048 1257 6519 +16984 4529 4497 6306 6592 +16985 4810 5927 4957 6217 +16986 4656 6626 6049 7001 +16987 4710 5870 4822 6231 +16988 1859 1681 6420 7203 +16989 5040 6536 5868 6651 +16990 514 513 6040 7202 +16991 4959 6471 5302 6683 +16992 4669 4667 5000 6069 +16993 2443 6693 5810 6898 +16994 462 5949 6337 6806 +16995 1855 6290 2086 7201 +16996 1859 6127 1681 7203 +16997 3548 6084 5936 6466 +16998 3256 5976 6508 7055 +16999 4794 6246 4795 6536 +17000 5956 6719 6536 6920 +17001 427 6963 5988 7039 +17002 2925 5758 2921 5862 +17003 3119 5823 2409 6526 +17004 559 4561 4537 5768 +17005 635 5436 5408 5767 +17006 2314 6234 2302 6325 +17007 6071 6072 4400 6622 +17008 1492 6640 1420 6701 +17009 2273 2271 334 6329 +17010 5024 624 5942 6608 +17011 4887 5814 6070 7159 +17012 2670 3417 3435 6314 +17013 4821 6399 4818 6678 +17014 6050 6177 5116 7016 +17015 6282 6398 4589 6500 +17016 473 5946 6093 6094 +17017 4663 6363 4665 7148 +17018 2716 5869 3048 6044 +17019 3998 1992 3926 5797 +17020 6248 6467 1715 7024 +17021 4488 4229 4356 6544 +17022 5813 6589 6309 6777 +17023 1702 6706 1964 7006 +17024 30 5919 582 6927 +17025 3034 3204 6282 7052 +17026 3188 3224 6158 6745 +17027 5334 4742 5772 6502 +17028 4078 6006 4307 6616 +17029 3659 6313 5948 6672 +17030 372 6962 6185 7063 +17031 3018 5903 3033 5911 +17032 3621 6020 6430 7136 +17033 2095 2118 6178 7092 +17034 4012 6064 5840 6376 +17035 3572 6035 2740 6036 +17036 1630 6204 6205 6671 +17037 2883 2882 2702 6402 +17038 616 5916 6389 7000 +17039 2938 5981 2514 6108 +17040 3375 6347 3421 6652 +17041 5166 5345 5131 6621 +17042 5279 5934 4824 6001 +17043 2393 2940 6220 6717 +17044 4668 5093 5056 6075 +17045 530 6503 531 6862 +17046 5029 6228 4659 7194 +17047 5394 6201 6200 6628 +17048 4425 6073 6410 6588 +17049 4791 5866 4790 6872 +17050 1397 6850 6705 6984 +17051 3883 6852 6704 6983 +17052 471 6993 6303 7080 +17053 5480 5590 6735 6828 +17054 4687 6058 4960 7109 +17055 4432 6493 4068 7057 +17056 2207 5797 6383 6805 +17057 5365 5360 4629 6053 +17058 1671 5817 1906 6992 +17059 1586 6308 6305 7051 +17060 4289 6230 5844 7176 +17061 2799 6643 6317 6947 +17062 2518 5904 2517 6273 +17063 305 306 6081 6319 +17064 5192 6280 6074 6970 +17065 5139 4666 6084 6647 +17066 4121 4454 4220 6975 +17067 3909 3999 1936 6440 +17068 6081 6238 4203 6706 +17069 474 4528 4558 6928 +17070 5053 5129 4955 5819 +17071 5369 6200 6040 7151 +17072 606 5881 6589 6987 +17073 4823 5870 4824 5934 +17074 6026 6386 2051 7033 +17075 5986 6137 5307 6789 +17076 5358 6012 6618 7158 +17077 4669 6085 6069 7103 +17078 6547 6740 4079 7046 +17079 5416 6478 5390 6962 +17080 376 5901 2320 6171 +17081 2028 6006 1781 6475 +17082 5055 6560 5001 6613 +17083 593 6200 6001 6628 +17084 4519 6253 4504 6362 +17085 2031 6113 1675 6607 +17086 440 5979 3657 6123 +17087 4013 4406 6357 6395 +17088 31 6048 5854 6582 +17089 470 6409 6112 6943 +17090 2998 5887 6414 6768 +17091 4096 6178 6025 6600 +17092 6046 6555 4740 6795 +17093 2736 6102 3569 6399 +17094 6311 6527 2020 7018 +17095 5869 3048 6044 7039 +17096 6019 6149 6018 7210 +17097 265 5946 1572 6094 +17098 5052 4934 5030 6606 +17099 6425 6426 6404 7036 +17100 2223 6209 6061 6822 +17101 4919 5051 6104 6576 +17102 2860 6393 5983 6744 +17103 614 4565 6976 7073 +17104 3103 6188 2851 7050 +17105 5854 6048 31 6793 +17106 5203 5158 6330 6662 +17107 4972 6044 5869 6109 +17108 1657 2024 6527 7079 +17109 3362 3360 6002 6340 +17110 5059 5003 5777 6237 +17111 6034 6312 4383 6961 +17112 4778 5889 4785 7049 +17113 4218 5952 4046 7130 +17114 5958 6076 5994 7087 +17115 1789 1961 6311 6559 +17116 6152 1781 6535 6944 +17117 6222 6344 4441 6817 +17118 1922 5935 6079 6315 +17119 2521 5789 2444 6523 +17120 1707 6403 6142 6714 +17121 5115 5364 5961 7197 +17122 5157 5158 5149 6662 +17123 3187 6218 2899 6219 +17124 3083 5795 6665 7168 +17125 5945 6643 2799 6947 +17126 4082 4330 5967 6175 +17127 5108 6155 5847 7030 +17128 262 6134 1581 6418 +17129 5962 2933 6299 6394 +17130 5771 6554 5773 7135 +17131 559 6453 6232 6694 +17132 4345 6064 4012 6376 +17133 5993 6842 6554 7135 +17134 2599 2946 5921 6150 +17135 3468 6573 6023 6899 +17136 5802 5872 4149 6858 +17137 2171 5982 2018 6118 +17138 455 5761 6468 6633 +17139 514 513 6292 6690 +17140 5779 3239 6008 7065 +17141 3293 3207 3209 6711 +17142 2225 2223 6479 7213 +17143 3543 2430 5893 6259 +17144 1968 6142 1650 6578 +17145 3057 3014 3011 6005 +17146 5422 6115 6080 6321 +17147 6035 6036 4818 6678 +17148 3049 6159 6044 6160 +17149 5187 5181 5829 6813 +17150 464 6415 6359 7212 +17151 4910 6059 6058 7109 +17152 4741 6035 6102 6555 +17153 2901 2574 6197 6857 +17154 584 5822 5806 6981 +17155 3028 3519 5777 6431 +17156 3093 3504 5778 6361 +17157 2974 2927 2789 6660 +17158 518 6581 6405 6776 +17159 2056 2082 1645 6588 +17160 4502 5948 6313 6672 +17161 4172 5952 6341 6635 +17162 4355 5890 6614 7099 +17163 428 3048 427 7039 +17164 4188 4286 5999 6396 +17165 2695 2693 5860 6754 +17166 2952 5789 2950 7186 +17167 3093 5778 3094 5990 +17168 4226 6146 4063 6671 +17169 2650 6036 2649 6159 +17170 4817 6696 5907 7067 +17171 5377 6052 5384 6110 +17172 3165 5937 5939 6815 +17173 2125 6341 5952 6635 +17174 5195 5200 5232 6276 +17175 2056 1645 1845 6410 +17176 4737 5806 4996 6080 +17177 4142 4477 6950 7185 +17178 5384 5396 6110 6234 +17179 4305 4072 6100 6559 +17180 3095 6480 5907 7067 +17181 3388 3391 3307 5821 +17182 3723 3815 6521 7093 +17183 2019 6192 250 7172 +17184 4670 6005 5874 6823 +17185 6391 6409 6253 6943 +17186 3343 6030 3570 6183 +17187 2366 6200 2307 6628 +17188 3148 6437 5861 6670 +17189 4780 4938 5044 6709 +17190 4405 4368 473 5946 +17191 1292 3218 2707 6413 +17192 1428 6540 1282 6675 +17193 3914 6538 3768 6676 +17194 5796 3614 6077 6967 +17195 4305 6100 4145 6559 +17196 423 2808 422 6022 +17197 1318 6632 1226 6743 +17198 5015 5881 5014 6987 +17199 305 6319 6081 6834 +17200 4181 5915 4449 6000 +17201 3059 6005 5874 6707 +17202 2100 6222 1819 6558 +17203 2800 2590 3005 6164 +17204 378 6017 6295 6679 +17205 1741 6436 5858 6726 +17206 5229 5771 5281 6280 +17207 4615 6345 6063 7097 +17208 1581 6327 1577 6418 +17209 4582 4967 6002 6340 +17210 4159 6193 524 6379 +17211 3421 3348 6281 6837 +17212 5164 6512 6031 6697 +17213 6491 6758 1502 6897 +17214 4655 5207 5098 6105 +17215 3287 3259 3258 6333 +17216 5934 5239 6374 6814 +17217 1247 6644 6563 7070 +17218 482 5845 6202 6422 +17219 4628 4568 6015 6351 +17220 4854 6394 6299 7068 +17221 5249 6210 5208 6591 +17222 5951 6286 4395 6494 +17223 221 222 5948 6202 +17224 3858 6497 5809 6721 +17225 5966 6547 4079 7046 +17226 6080 6115 381 6321 +17227 4894 5925 6343 6659 +17228 2525 6162 3021 6646 +17229 5023 6612 5294 6910 +17230 2708 2707 3217 6191 +17231 2717 6109 2738 6511 +17232 3396 3450 6074 6277 +17233 3307 3391 6041 7149 +17234 6458 6583 1368 6996 +17235 372 5897 6185 6962 +17236 534 6020 6768 7136 +17237 561 5830 5774 6933 +17238 470 6408 6407 6442 +17239 4528 6251 6121 6928 +17240 2016 6222 6326 6942 +17241 1788 2167 6355 6624 +17242 3116 2393 6220 6717 +17243 473 5946 6094 6303 +17244 3758 6811 6611 6866 +17245 1272 6812 6610 6865 +17246 6014 6121 3616 6928 +17247 569 5074 5795 6215 +17248 4592 5901 6692 6814 +17249 5459 6641 6784 6785 +17250 5617 6640 6781 6782 +17251 4050 4417 4188 6864 +17252 1430 6879 6487 6901 +17253 2439 5856 2446 6606 +17254 2966 2967 2920 6089 +17255 6072 2017 6461 6622 +17256 4151 6057 6322 6490 +17257 4558 4494 6014 6121 +17258 2782 6015 2681 6351 +17259 1743 2103 1985 5994 +17260 4684 5832 5094 6700 +17261 4026 6368 6178 7092 +17262 5018 602 601 5863 +17263 6200 6268 6001 6926 +17264 2750 2640 2639 6010 +17265 5131 4926 5908 6047 +17266 2780 6247 5867 7117 +17267 4513 4557 541 6421 +17268 3104 2534 3171 6240 +17269 524 6193 6354 6379 +17270 5928 5966 1693 6547 +17271 4593 4920 5078 6197 +17272 5350 5786 5175 6708 +17273 2383 6075 5936 6647 +17274 4905 6004 5784 6652 +17275 6089 6247 6088 6712 +17276 5909 6489 5792 7084 +17277 4538 6905 29 6938 +17278 6620 6730 5529 6953 +17279 6619 6729 5687 6954 +17280 6241 6331 6136 6776 +17281 1833 1781 5989 6475 +17282 2897 5779 3239 6560 +17283 2855 2854 6364 6639 +17284 569 5766 568 6215 +17285 6017 6679 377 7206 +17286 1733 5764 2033 5877 +17287 3144 2675 3145 6536 +17288 2901 6197 6154 6857 +17289 3214 6195 6179 6300 +17290 4988 6191 5931 6792 +17291 5450 5514 5568 6801 +17292 5726 5608 5672 6802 +17293 4582 6340 6002 6404 +17294 3176 3100 2631 5801 +17295 5903 6650 432 6715 +17296 3259 3257 3258 6332 +17297 5958 6501 1791 6918 +17298 5683 6531 5619 7111 +17299 5525 6530 5461 7112 +17300 1738 6599 1979 6600 +17301 4929 5757 5913 6767 +17302 6126 6820 6369 7026 +17303 1851 6018 2035 6733 +17304 3635 6453 1421 6809 +17305 2557 6070 3123 6265 +17306 1316 5835 3159 6491 +17307 1189 1448 6619 6729 +17308 4901 4786 6108 7049 +17309 1990 2161 1731 5950 +17310 1870 5895 1721 6577 +17311 2753 6258 6104 6915 +17312 4433 6205 6352 6376 +17313 2697 3481 6553 7001 +17314 4900 4632 6457 6551 +17315 442 5879 441 7076 +17316 4799 6164 5025 7052 +17317 5335 5897 594 6001 +17318 6056 6216 2939 6910 +17319 2651 6043 6036 6678 +17320 4930 5913 5346 6095 +17321 2006 6207 5818 6836 +17322 2667 2666 6143 6231 +17323 1771 1854 2140 6316 +17324 2089 6156 6315 6316 +17325 3743 5809 5753 6720 +17326 428 6044 3048 7039 +17327 434 433 6456 6832 +17328 5808 2051 6386 7033 +17329 1431 5804 247 6925 +17330 2690 2692 3167 7077 +17331 3051 5957 6082 6513 +17332 2139 6144 1915 6193 +17333 1938 6144 1812 6344 +17334 4663 4665 5031 7148 +17335 4945 5857 5856 5910 +17336 5895 5982 1783 6734 +17337 5213 5214 6496 6738 +17338 4319 6079 4192 7095 +17339 4415 6026 4020 6386 +17340 2033 5877 5764 6544 +17341 3022 2977 3019 6502 +17342 3158 3159 2991 5835 +17343 1972 5955 2163 6223 +17344 4488 5764 4344 6544 +17345 2031 6114 6113 6607 +17346 3210 6095 5913 6767 +17347 491 6787 6111 7156 +17348 1691 6156 6211 6377 +17349 577 5981 4575 6366 +17350 4817 5241 6696 7067 +17351 4405 5946 4225 6406 +17352 577 6125 6366 6543 +17353 2203 1297 291 2294 +17354 542 5894 6121 6302 +17355 3299 3528 3205 6480 +17356 4243 6132 6379 6800 +17357 3791 3801 6907 7031 +17358 2227 6443 6119 7180 +17359 1475 1223 5875 6499 +17360 2327 2308 2368 6679 +17361 5814 6162 5008 6646 +17362 5194 6012 6011 6752 +17363 5794 6872 2435 6945 +17364 1691 2127 1823 6377 +17365 3403 6180 5957 6513 +17366 5894 6121 436 6421 +17367 1756 5940 6578 6946 +17368 1821 5885 5760 7092 +17369 6115 6321 5422 6334 +17370 4845 6557 6245 6724 +17371 5421 6209 506 6334 +17372 6081 6706 6140 7006 +17373 1677 5761 2142 6373 +17374 2148 5769 1858 5960 +17375 468 6253 6362 6391 +17376 5079 4693 4691 6109 +17377 2321 331 6284 6285 +17378 2490 2491 2489 6469 +17379 4215 5756 4164 6142 +17380 5281 5993 5771 7135 +17381 3057 6005 3282 6346 +17382 4958 6217 5970 6471 +17383 2742 2935 5963 6364 +17384 1874 6283 5952 6950 +17385 2865 6275 6174 6393 +17386 4993 5893 4990 5984 +17387 4884 4885 5790 5834 +17388 2956 5828 3119 6526 +17389 4263 5853 4316 6310 +17390 4024 6113 4342 6635 +17391 4590 6398 6361 6500 +17392 3404 6508 6182 7055 +17393 3909 1936 5932 6440 +17394 6451 6589 5854 6982 +17395 4070 5816 4270 5817 +17396 5084 6174 6275 6393 +17397 4916 5757 4929 6010 +17398 473 6303 6094 7126 +17399 5859 6835 5779 7065 +17400 2487 384 2488 6229 +17401 2478 5886 2484 6237 +17402 514 6452 6292 7202 +17403 455 5761 6373 6468 +17404 4059 6055 4363 6460 +17405 4620 6514 5107 6951 +17406 3627 6261 219 6462 +17407 2120 1641 1856 6450 +17408 2933 2934 5962 6299 +17409 4080 5999 4286 6223 +17410 2750 6010 2639 6767 +17411 6361 6398 3036 6500 +17412 3041 5770 3039 5841 +17413 4843 4905 5784 6652 +17414 2712 3873 2608 6957 +17415 1906 5977 2001 6230 +17416 2122 1743 6211 6465 +17417 4857 5944 4854 6028 +17418 5090 5957 5219 6082 +17419 5090 6082 5089 6382 +17420 5480 5590 6828 6877 +17421 5040 5039 5099 5868 +17422 3981 2067 3855 6126 +17423 4615 6063 5321 6466 +17424 4017 4344 5764 6385 +17425 5234 6220 6218 6929 +17426 1217 1507 1322 6572 +17427 5035 5874 5034 6166 +17428 4615 4617 6345 7097 +17429 5806 4996 6080 6371 +17430 383 5822 2364 6981 +17431 607 5854 6589 6982 +17432 3035 6016 2966 6089 +17433 3592 3607 6421 6682 +17434 471 6112 6993 7080 +17435 1730 6505 6126 7026 +17436 473 6014 6303 7126 +17437 3599 3627 6313 6894 +17438 459 5932 6687 6838 +17439 1917 6441 1702 6706 +17440 509 6119 6153 7180 +17441 458 5954 4255 6097 +17442 4256 498 5955 6098 +17443 3269 3473 3273 5842 +17444 6035 6102 2736 6399 +17445 4246 4359 486 5836 +17446 5850 579 6189 6855 +17447 3161 2601 2603 5927 +17448 4566 5847 6279 6484 +17449 3939 6641 3769 6725 +17450 4496 4515 4546 6650 +17451 2242 2240 344 6586 +17452 2309 2323 2322 5793 +17453 5224 5792 5350 6489 +17454 3154 3155 2595 5908 +17455 2732 5811 2756 6060 +17456 5294 6612 5278 6910 +17457 3206 5901 376 6814 +17458 2655 6105 6037 6553 +17459 1548 6323 1549 6428 +17460 1644 6326 6222 6344 +17461 2871 2685 3893 7093 +17462 5156 6024 5022 6239 +17463 6355 6479 506 7213 +17464 563 6088 6247 6712 +17465 2745 5963 2803 7121 +17466 5119 6208 6697 6737 +17467 4658 6522 4659 7102 +17468 5366 6345 4626 6986 +17469 4260 5760 4471 6532 +17470 2727 6124 2766 6188 +17471 4099 4173 4242 5905 +17472 4995 6017 4644 6154 +17473 5009 5008 5814 6162 +17474 5788 6142 1925 6796 +17475 2842 6191 5931 7128 +17476 5082 5083 4951 7125 +17477 2461 5820 2462 6229 +17478 1608 219 6261 6464 +17479 4581 6425 6404 7036 +17480 6289 6382 4674 6425 +17481 1729 1993 2159 5900 +17482 495 5974 496 6634 +17483 5034 5340 5261 6166 +17484 3533 2551 6031 6697 +17485 4658 6227 4660 6522 +17486 6158 6218 5250 6220 +17487 4952 5086 6361 6398 +17488 369 6135 368 7154 +17489 1362 6878 1398 7060 +17490 4175 4315 6168 6223 +17491 5260 5077 6143 6552 +17492 3834 5949 1801 6440 +17493 3206 5901 6814 7206 +17494 3083 6273 5795 7168 +17495 2533 5859 6214 7127 +17496 3532 2653 5832 7021 +17497 5963 7073 6412 7075 +17498 4787 4605 5010 6273 +17499 6060 6700 4683 7021 +17500 5998 6446 2582 6824 +17501 2366 6001 374 6200 +17502 5873 6590 6367 7043 +17503 3234 6374 3206 6814 +17504 5008 4887 5814 6070 +17505 2567 5847 5846 6861 +17506 4862 6039 6388 6977 +17507 4609 4608 6411 6870 +17508 6446 6746 5998 6974 +17509 6243 6263 4764 7194 +17510 5167 5843 5076 6161 +17511 2027 6556 6244 7183 +17512 1681 6127 5764 6663 +17513 6061 6355 506 7213 +17514 3149 3420 5909 6708 +17515 452 6821 6820 6895 +17516 4771 4792 4804 5859 +17517 4747 5042 5041 6371 +17518 4461 6153 6019 7153 +17519 1595 6202 1597 6422 +17520 2029 5890 5763 6614 +17521 1780 5763 6076 7115 +17522 2683 6381 6016 6844 +17523 579 578 4901 6366 +17524 5427 6110 521 6241 +17525 4724 6623 4723 6680 +17526 4504 6362 6123 6430 +17527 4422 4458 5840 6226 +17528 2743 2803 6484 7121 +17529 1774 5989 6032 6432 +17530 2021 6359 6198 6884 +17531 1448 6619 6587 6810 +17532 5179 6330 5972 6843 +17533 1635 2151 1932 5967 +17534 333 2350 6110 6157 +17535 2306 6115 6067 6334 +17536 3336 5773 3561 6941 +17537 534 4736 533 6768 +17538 4422 5840 4150 6064 +17539 1284 1482 6543 7162 +17540 5021 5022 5212 6239 +17541 1633 6026 1966 6055 +17542 4665 6363 6252 7148 +17543 533 5887 5855 6768 +17544 3117 5814 3116 6158 +17545 2824 3028 2483 6237 +17546 3320 6106 3321 6363 +17547 1857 2095 6178 6368 +17548 3003 6039 6155 6279 +17549 6128 6240 6807 6957 +17550 563 4896 6015 6247 +17551 5036 6131 6166 6512 +17552 4624 6454 6792 7140 +17553 6271 6312 1688 6961 +17554 5844 5905 4242 6949 +17555 3201 6084 6085 6647 +17556 4191 5982 4089 6601 +17557 2179 6057 1846 6527 +17558 2682 6380 6351 6761 +17559 620 6317 6434 6643 +17560 4161 4023 4211 6326 +17561 1871 5947 1976 6242 +17562 2708 6413 6191 7128 +17563 5039 5879 5868 6414 +17564 4039 5891 4257 6906 +17565 2764 2761 2768 5755 +17566 5793 6566 25 7038 +17567 5358 5357 5194 6011 +17568 5430 5378 5399 6234 +17569 4093 4460 5871 6858 +17570 4558 4528 6121 6928 +17571 2247 2244 6292 6452 +17572 5463 6584 6459 7094 +17573 5187 5348 5180 6567 +17574 4142 6006 5853 6950 +17575 2546 6096 2891 6495 +17576 2291 6287 2194 7034 +17577 5006 5824 4600 5826 +17578 5039 5017 4642 5879 +17579 5011 6080 4996 6371 +17580 3837 4003 6128 6807 +17581 3428 6224 5784 7123 +17582 2513 5920 5863 7007 +17583 601 602 6052 7007 +17584 5861 6936 6552 7019 +17585 5387 6171 6040 6435 +17586 1938 1812 6144 6493 +17587 1926 5865 2077 6079 +17588 2288 6293 6294 6510 +17589 459 5932 6686 6687 +17590 499 5933 6684 6685 +17591 3431 3432 6245 6652 +17592 5971 6737 6697 6969 +17593 6088 2450 6933 7117 +17594 4914 6060 5757 6372 +17595 5864 6613 3278 7103 +17596 3307 6041 3531 6455 +17597 5132 6012 5815 6618 +17598 4681 6103 5834 7030 +17599 6324 6642 489 6794 +17600 5142 6084 4666 6085 +17601 4112 5816 4285 6601 +17602 2278 6387 6354 6935 +17603 3222 3289 3117 5814 +17604 4802 4801 4803 6214 +17605 3013 3229 2878 6008 +17606 3034 6282 3037 6398 +17607 6243 4764 6609 7194 +17608 6127 6341 1881 6635 +17609 4815 5849 4877 5975 +17610 1967 6286 1928 6494 +17611 4592 6692 6374 6814 +17612 486 6262 6261 6464 +17613 5371 5403 5404 6171 +17614 4738 5783 5782 7150 +17615 2052 5788 2149 6880 +17616 2536 6213 6214 6469 +17617 4720 6695 4734 6755 +17618 4513 6121 4557 6421 +17619 3232 3347 6276 7155 +17620 3095 5907 6696 7067 +17621 5953 7059 6420 7129 +17622 573 5835 6491 6968 +17623 4256 6098 5955 6223 +17624 1830 6373 2142 6468 +17625 2361 344 6040 6435 +17626 5062 5925 6046 6795 +17627 1607 1606 1615 6464 +17628 2428 6389 6388 7023 +17629 1431 1260 5804 6925 +17630 5063 4674 4675 6289 +17631 5993 6280 5771 7144 +17632 4702 6378 4700 6786 +17633 4855 4941 6028 7035 +17634 2549 5941 5819 6433 +17635 5253 5217 6288 6565 +17636 3239 7065 3303 7127 +17637 608 5854 31 6793 +17638 3390 5821 3385 5980 +17639 2442 3073 6083 6816 +17640 4644 6017 588 6857 +17641 4396 6501 5959 6918 +17642 3803 6730 6620 6953 +17643 1317 6729 6619 6954 +17644 4034 4426 4387 6138 +17645 2885 6172 3490 6173 +17646 4241 6098 4175 6167 +17647 2817 6080 5806 6981 +17648 1712 5915 6000 6864 +17649 6426 6427 5154 6483 +17650 2743 2745 2803 7121 +17651 3114 6218 6158 6220 +17652 5424 5375 6068 6598 +17653 485 6261 4522 6462 +17654 3329 6336 3340 6573 +17655 2331 2366 2307 6628 +17656 3986 3884 6009 7054 +17657 5274 5291 5290 5792 +17658 5017 5879 5039 6414 +17659 3580 6091 3382 6747 +17660 5039 4642 5868 5879 +17661 5674 6819 6540 7199 +17662 5516 6818 6538 7200 +17663 5399 5378 5397 6234 +17664 3256 5943 5976 7055 +17665 3700 3878 6648 6801 +17666 1392 6649 1214 6802 +17667 4892 5925 5832 5926 +17668 4566 6279 5964 6484 +17669 3511 3093 3504 5778 +17670 2997 3070 5887 6414 +17671 4979 5019 5785 6798 +17672 6731 6803 3700 6939 +17673 6732 6804 1214 6940 +17674 2776 5811 2732 6700 +17675 4866 6381 5931 7128 +17676 4866 4583 5931 6380 +17677 4764 6243 4763 6263 +17678 1533 1619 1620 7082 +17679 4700 5962 4699 5985 +17680 3206 6814 6374 7206 +17681 4074 6386 4251 6461 +17682 2279 6157 2276 6354 +17683 4289 5996 6230 7176 +17684 4894 5832 4892 5925 +17685 4355 5763 4018 7099 +17686 5597 6561 6596 6770 +17687 5439 6562 6595 6773 +17688 1503 1421 1256 6453 +17689 5586 6873 5551 7009 +17690 5744 6874 5709 7011 +17691 5787 6239 3437 6358 +17692 4248 6373 6250 6658 +17693 4950 4627 6170 6750 +17694 5187 6179 5320 6300 +17695 4703 4931 6095 6096 +17696 5309 5917 5312 6274 +17697 1566 6407 267 6408 +17698 5228 6281 6280 6507 +17699 4541 532 4538 5781 +17700 2985 2986 2987 6087 +17701 1600 6422 1597 6779 +17702 1899 1779 2164 7118 +17703 3485 6216 6888 6910 +17704 235 6391 6253 6943 +17705 3156 5856 2591 5910 +17706 2967 6015 2920 6089 +17707 5023 6239 6612 6910 +17708 4221 6025 4096 6178 +17709 6342 6411 3399 6870 +17710 4721 4996 4737 5806 +17711 1822 2177 6149 6535 +17712 4091 4384 6211 6377 +17713 4523 4500 4548 6546 +17714 5081 6434 6137 6643 +17715 6091 6347 6288 6747 +17716 3391 6041 5821 6496 +17717 5108 6155 5106 6279 +17718 1830 2142 5973 6468 +17719 6503 6580 531 6862 +17720 5899 6449 28 6911 +17721 452 6820 6636 6895 +17722 2948 5936 3548 6084 +17723 4702 4701 5755 6786 +17724 3150 5923 3490 6172 +17725 6122 6398 2996 6431 +17726 6222 6326 4308 6344 +17727 6061 506 6479 7213 +17728 4400 6072 6071 6663 +17729 5252 5957 5136 6180 +17730 5882 6274 3164 6665 +17731 4984 5814 5849 6158 +17732 3252 3087 3251 6480 +17733 567 5931 4988 6191 +17734 1867 306 6384 6661 +17735 3290 5765 3294 6339 +17736 1852 6406 6271 6407 +17737 3450 6277 3392 6280 +17738 2188 1998 1720 5871 +17739 1571 6327 6094 6365 +17740 3596 5987 3612 6112 +17741 6092 6251 3603 6456 +17742 4805 5864 5001 5986 +17743 5031 4665 5256 6117 +17744 5936 6084 5139 6466 +17745 5112 5883 5131 5908 +17746 1908 2124 1744 6847 +17747 2168 1789 1895 6311 +17748 3501 3051 5957 6082 +17749 468 6323 5968 6847 +17750 2688 5880 3071 6259 +17751 4404 4307 6149 6616 +17752 298 6354 6193 6379 +17753 513 6292 6586 7202 +17754 1395 6413 1204 6827 +17755 3322 6367 3067 6590 +17756 4984 5849 5814 7159 +17757 4297 6152 6151 6535 +17758 6103 6504 2526 7030 +17759 1860 6204 6203 6605 +17760 513 6586 6040 7202 +17761 4681 5834 6267 7030 +17762 4530 6051 4497 6592 +17763 5287 5943 5285 5975 +17764 6468 6740 6114 7046 +17765 4394 5865 4095 5991 +17766 255 5845 1603 6463 +17767 5819 2722 6042 6660 +17768 303 6238 1900 6579 +17769 4446 5848 6286 7170 +17770 490 4333 6348 6485 +17771 5059 5003 5004 5777 +17772 2965 2803 2745 5963 +17773 6052 6110 2298 6234 +17774 4090 6524 6256 6961 +17775 5787 6024 3476 6239 +17776 5299 6297 6507 6842 +17777 5192 6074 4886 6970 +17778 2440 2591 2438 5857 +17779 4659 6522 6609 7102 +17780 5841 6363 6252 7022 +17781 5968 6033 1908 6988 +17782 4691 6042 4692 6043 +17783 5114 5902 5330 5985 +17784 3505 6215 5795 6273 +17785 2963 6320 2956 6526 +17786 4213 4362 6242 7015 +17787 3497 5790 3226 6710 +17788 529 6147 6449 7018 +17789 5962 4700 6378 6786 +17790 2243 310 2241 6291 +17791 1353 6416 6722 7165 +17792 5094 4893 4917 5832 +17793 3119 6937 5828 7179 +17794 5782 2790 6099 7116 +17795 5853 5952 1746 7130 +17796 4233 6140 6450 6946 +17797 4094 6242 5947 7072 +17798 4363 6460 6055 6461 +17799 4413 5951 4060 6270 +17800 5228 6280 5230 6507 +17801 4992 6148 4994 6338 +17802 2437 5794 2430 6259 +17803 4467 4392 6034 6847 +17804 1470 5995 1309 6416 +17805 4196 4194 6071 6980 +17806 1276 1417 6453 6694 +17807 1768 6407 6271 6524 +17808 5654 6675 6540 6819 +17809 5496 6676 6538 6818 +17810 4254 6349 5940 6578 +17811 2653 6037 5832 7021 +17812 3324 6752 6012 6753 +17813 3012 3010 5918 7078 +17814 4807 5307 6269 6789 +17815 4749 5825 596 6962 +17816 2846 6155 5847 6279 +17817 3051 6082 2876 6427 +17818 3107 6437 3148 6670 +17819 4654 4614 6129 6477 +17820 2803 5964 2804 6484 +17821 5073 5227 5072 6908 +17822 4117 6468 6114 7046 +17823 4209 4370 4415 6681 +17824 2997 6246 3070 6414 +17825 4422 6064 4043 6958 +17826 3281 3014 3057 6346 +17827 5218 5069 5912 6748 +17828 4285 6395 6357 6601 +17829 5689 6498 568 6689 +17830 1927 5891 1923 6176 +17831 2207 6383 5798 6805 +17832 2187 1687 6368 6859 +17833 5115 5961 6627 6742 +17834 581 5875 580 6523 +17835 268 6407 2138 6524 +17836 5411 5822 584 6115 +17837 4145 6100 527 6311 +17838 4014 5788 4164 6328 +17839 514 6292 513 7202 +17840 4285 5816 4191 6601 +17841 5959 6249 1847 6335 +17842 30 582 4733 6927 +17843 370 6478 5825 7063 +17844 1664 6033 1794 6385 +17845 2623 3036 6361 6398 +17846 4032 5905 6139 7146 +17847 1796 2110 6113 6635 +17848 4145 4305 527 6100 +17849 5240 4690 5937 5938 +17850 618 6604 6603 6735 +17851 5846 5956 3157 6861 +17852 5266 5842 5270 6106 +17853 6429 6706 6238 7006 +17854 1491 6572 5899 6585 +17855 581 6587 5875 6729 +17856 1566 267 6407 6442 +17857 1908 270 2124 5968 +17858 2946 2941 5921 6517 +17859 459 6687 6097 6838 +17860 418 1256 1399 1421 +17861 4496 6092 4510 6255 +17862 556 5969 4728 6764 +17863 628 6620 6509 6723 +17864 505 6318 6067 6550 +17865 5393 5373 6321 6334 +17866 3026 3028 3519 5777 +17867 2016 6326 6226 6942 +17868 3473 5842 3269 6444 +17869 5864 5986 4805 7163 +17870 4505 6307 6160 6592 +17871 4712 6451 4711 6982 +17872 3837 6128 4003 6666 +17873 3602 3617 6253 6943 +17874 4289 4455 4193 7176 +17875 6011 6012 5358 7158 +17876 6238 6579 303 6581 +17877 1788 6355 6032 6624 +17878 4296 6133 6132 6800 +17879 2364 383 2322 5822 +17880 4289 4193 5996 7176 +17881 3624 6190 3590 6797 +17882 4625 6050 6454 7140 +17883 5261 5187 5829 6179 +17884 2395 2443 5810 6898 +17885 2352 6776 6136 6854 +17886 5382 5367 5411 6067 +17887 6271 1688 6524 6961 +17888 434 5907 3096 6832 +17889 4221 4026 5858 6178 +17890 424 6445 6022 6739 +17891 1780 6076 5958 7115 +17892 5777 6236 3026 6237 +17893 1506 1308 1216 5803 +17894 5829 6031 5317 6512 +17895 2905 6542 5841 7022 +17896 516 6506 6201 6948 +17897 4871 6030 5141 6921 +17898 3591 6022 5796 6894 +17899 6152 6624 4071 6912 +17900 3820 6631 3934 6736 +17901 2912 2795 6031 6512 +17902 3069 5879 6020 6414 +17903 4962 6150 5921 6517 +17904 1661 6018 1851 6796 +17905 460 6440 461 6924 +17906 5439 6595 5512 6773 +17907 5597 6596 5670 6770 +17908 2012 1848 2180 6356 +17909 4168 6175 5891 6176 +17910 1976 6242 5802 6537 +17911 4808 4742 6502 7139 +17912 1943 5954 1646 6468 +17913 6044 6159 548 6160 +17914 5317 5829 5262 6031 +17915 29 6905 6720 6938 +17916 634 5409 5436 5767 +17917 5132 4844 5133 5815 +17918 2862 2450 6247 7117 +17919 2563 5833 6320 6445 +17920 6128 6666 3837 7193 +17921 1208 5900 6278 6997 +17922 4206 6395 6118 6600 +17923 1423 1935 5933 6278 +17924 2339 5754 2340 5793 +17925 3125 2709 2540 6727 +17926 3055 5829 2912 6031 +17927 580 5746 579 6619 +17928 5841 4653 6363 7022 +17929 5928 6547 1693 7118 +17930 3574 3381 3486 6130 +17931 2277 6193 6354 7143 +17932 5277 6021 4812 6102 +17933 4262 4062 6027 6226 +17934 1929 6605 6186 6964 +17935 4588 6393 4933 7124 +17936 2695 5860 5825 6754 +17937 5989 6032 4033 7132 +17938 2832 2833 2834 5914 +17939 5282 6554 5341 7135 +17940 2151 5967 1635 5977 +17941 2097 1951 260 6568 +17942 6534 6757 3819 6826 +17943 3519 5777 6431 6823 +17944 4188 5999 4116 6864 +17945 4319 4192 4095 7095 +17946 4433 6205 4428 6352 +17947 5917 6274 5309 6481 +17948 4601 4609 6342 6908 +17949 3160 5908 2820 5944 +17950 6318 6479 2224 6550 +17951 4812 4740 4741 6555 +17952 4308 6326 6222 6942 +17953 5216 6347 6091 6747 +17954 2985 2986 6087 6576 +17955 471 6303 472 7080 +17956 483 484 5948 6462 +17957 508 5424 6068 6116 +17958 3052 5962 5898 7204 +17959 3007 6085 6069 6647 +17960 220 5948 3659 6462 +17961 524 6285 525 6387 +17962 2267 6241 336 6331 +17963 4408 6149 4040 6151 +17964 4797 6282 6122 6398 +17965 6053 5146 6367 7043 +17966 2915 2435 5794 6872 +17967 4622 4775 6062 6364 +17968 2051 6026 2129 6386 +17969 4866 4567 6380 6381 +17970 259 6194 1590 6423 +17971 3371 3088 3089 5925 +17972 5379 6296 6295 6679 +17973 2330 6135 2300 6136 +17974 533 5855 4541 5924 +17975 3149 5909 5923 6708 +17976 6253 6391 469 6409 +17977 2884 3143 6172 6275 +17978 1654 5802 1981 6537 +17979 4171 6204 6203 6671 +17980 602 5863 5920 7007 +17981 492 6788 6787 6881 +17982 5810 6124 628 6457 +17983 4385 6408 6256 6524 +17984 4779 6099 5782 7181 +17985 5974 6000 5955 7074 +17986 2444 2445 2530 6523 +17987 3525 5985 3106 6786 +17988 5270 4652 4653 5842 +17989 2167 6355 6061 7213 +17990 5307 4805 5986 6789 +17991 5289 4822 5892 6231 +17992 3473 3273 5842 6106 +17993 3283 2789 2737 6043 +17994 6057 6311 4372 6527 +17995 5219 5957 5090 6748 +17996 5789 6523 5889 7186 +17997 5257 5048 5339 5923 +17998 5993 6507 6297 6842 +17999 569 6482 5732 6602 +18000 3550 6056 3534 6239 +18001 2710 5766 3091 6869 +18002 384 5822 2488 6229 +18003 1492 6701 1283 7014 +18004 4984 4815 4813 5849 +18005 5699 6632 5639 6851 +18006 5258 5265 6427 6444 +18007 4861 4916 6010 6372 +18008 5404 5432 6171 6679 +18009 2747 6719 6062 6861 +18010 2593 3368 2836 7173 +18011 1707 6142 6349 6714 +18012 5979 5987 538 7048 +18013 4566 6484 5964 7121 +18014 608 6793 31 7165 +18015 523 5396 5430 6157 +18016 3131 3130 3129 6083 +18017 518 6238 6081 6834 +18018 3978 3769 3939 6641 +18019 4241 499 6098 6167 +18020 1602 6463 1610 6464 +18021 4804 4792 5055 6008 +18022 2613 6252 6363 7148 +18023 4434 4045 6420 7059 +18024 4957 5970 4958 6217 +18025 523 6329 6157 6354 +18026 1801 1936 3999 6440 +18027 4603 6342 4601 6411 +18028 2799 2661 2840 6643 +18029 347 346 6068 6443 +18030 3208 2813 373 6001 +18031 4870 5759 4872 7147 +18032 1632 2149 6196 6880 +18033 2800 6164 3005 7052 +18034 3094 5778 3172 7064 +18035 6127 6635 1881 7131 +18036 4063 6205 4219 6671 +18037 5027 5212 5787 6358 +18038 3190 3285 3191 6102 +18039 3453 6263 6609 7194 +18040 5934 5279 6814 6926 +18041 4733 5789 4728 5969 +18042 4841 6576 6104 6656 +18043 2838 6434 2843 6885 +18044 1869 6207 2006 6836 +18045 561 5774 6829 6933 +18046 1512 1991 1440 5804 +18047 2947 6680 6623 6816 +18048 626 4571 627 6188 +18049 4962 5921 6150 6438 +18050 1635 5967 2054 5977 +18051 529 6147 6287 6911 +18052 4963 4961 5921 7163 +18053 4080 5955 5999 6223 +18054 2567 2848 2643 5847 +18055 2016 2134 6226 6326 +18056 1495 2068 1369 6111 +18057 5757 6037 2656 7021 +18058 471 6442 6303 6993 +18059 5036 6131 6512 7027 +18060 3074 2526 3136 6267 +18061 459 6686 6097 6687 +18062 499 6684 6098 6685 +18063 4244 6061 6360 6912 +18064 4191 5816 4274 6207 +18065 4438 4039 4257 6225 +18066 4414 5885 4075 6368 +18067 506 6334 6209 6550 +18068 5359 5350 5321 5909 +18069 5248 5842 6444 6591 +18070 378 377 6017 6679 +18071 618 6521 6604 6735 +18072 3233 2815 3237 5934 +18073 1610 1604 6462 6463 +18074 2384 5936 2948 6647 +18075 4830 5821 6342 7149 +18076 4528 6365 6251 6928 +18077 3179 5841 3039 5842 +18078 4581 6404 6002 7036 +18079 6641 6784 3668 6913 +18080 6436 6726 1741 7033 +18081 2352 2315 338 6854 +18082 2359 6293 2328 6777 +18083 2590 5998 2744 6164 +18084 2947 6623 2953 6816 +18085 1990 1731 5949 5950 +18086 4276 6322 6167 6490 +18087 3007 6069 6085 7103 +18088 4570 6351 6177 6380 +18089 3572 2740 3022 6036 +18090 6488 6811 3828 6866 +18091 6487 6812 1342 6865 +18092 5050 5093 5049 6174 +18093 4184 5836 4359 6501 +18094 6281 6288 5127 6837 +18095 27 6694 6232 6883 +18096 5843 6274 3030 6481 +18097 3908 3743 447 5809 +18098 3663 3597 3609 6169 +18099 3641 6078 223 6307 +18100 5514 6593 5592 6783 +18101 5750 5672 6594 6780 +18102 1921 5951 2105 7069 +18103 6081 6140 1838 7006 +18104 5989 6475 1781 6944 +18105 5185 6508 6219 6745 +18106 3161 5970 2416 6161 +18107 5047 5874 6005 6707 +18108 4513 4512 4494 6682 +18109 4207 4129 5838 7095 +18110 4078 4307 4404 6616 +18111 4691 6044 4972 6109 +18112 2889 2893 6095 6627 +18113 4317 6027 4062 6226 +18114 6301 6432 4275 6658 +18115 6081 6140 4111 6661 +18116 2310 6116 6321 6334 +18117 4686 5067 5243 6472 +18118 5187 5829 6179 6567 +18119 2551 6433 6031 6697 +18120 3156 5910 2985 6087 +18121 5226 5980 5348 6300 +18122 4683 5757 4914 6060 +18123 5136 6180 5957 6181 +18124 3596 3602 3653 6546 +18125 5208 5770 4652 6591 +18126 1813 6312 1937 7187 +18127 5392 6135 5374 6136 +18128 4497 6051 4554 6255 +18129 5021 6239 6358 6612 +18130 5229 5281 5230 6280 +18131 1728 1954 6111 7156 +18132 5935 6079 4207 7095 +18133 2153 5989 1774 6432 +18134 2473 2525 3021 6646 +18135 541 6421 5894 6515 +18136 2176 1780 2029 6076 +18137 4989 4995 6154 6197 +18138 1292 6413 1395 6498 +18139 4786 5889 6189 7049 +18140 2648 2664 5898 6299 +18141 482 483 5948 6202 +18142 4390 6335 5915 6474 +18143 1700 6357 6395 6601 +18144 2476 6236 2478 6237 +18145 1980 1668 1827 5812 +18146 2713 6240 6608 6957 +18147 2950 6099 2790 7186 +18148 1765 2051 5808 7033 +18149 474 6365 4528 6928 +18150 611 6639 5827 7145 +18151 556 5969 5783 6077 +18152 3047 5997 3242 6150 +18153 3344 3345 2799 6643 +18154 3297 6382 3487 6425 +18155 4880 4878 4860 6096 +18156 3092 6208 5990 6969 +18157 4085 6120 4391 6658 +18158 4861 5801 6010 6199 +18159 1344 1251 1465 6844 +18160 3716 6529 3887 6702 +18161 1230 6528 1401 6703 +18162 1380 5933 1481 6684 +18163 2944 2945 5806 6371 +18164 4518 4521 6251 6456 +18165 6154 6470 2787 6857 +18166 3211 5965 3483 6424 +18167 1858 5960 6244 6516 +18168 2888 6096 2890 6504 +18169 4984 5814 4887 7159 +18170 1521 1207 1404 6770 +18171 3693 3890 4007 6773 +18172 4837 5027 6065 6358 +18173 4270 6139 5905 6778 +18174 3134 2667 2666 6143 +18175 1636 5906 5915 7122 +18176 1809 1966 1705 6055 +18177 6155 6267 2526 7030 +18178 2942 5831 3338 6137 +18179 4974 5984 5863 6815 +18180 1652 5865 5838 6532 +18181 6242 6681 4059 7015 +18182 1850 6073 1694 6677 +18183 1549 5968 271 6428 +18184 2886 6174 2865 6275 +18185 588 6017 589 6295 +18186 2207 5797 319 6383 +18187 2335 6321 6115 6334 +18188 4662 4663 6106 6363 +18189 5175 5319 5173 5786 +18190 1797 2184 5999 6396 +18191 3347 3047 6150 6710 +18192 2816 6470 2402 6914 +18193 2724 2766 2727 6124 +18194 2704 6148 3006 7029 +18195 4477 6475 6006 6950 +18196 4307 6535 6149 6616 +18197 1417 6232 1219 6453 +18198 6135 6266 368 7154 +18199 4571 4900 6124 6551 +18200 3505 3125 3124 6215 +18201 6459 3854 6751 7094 +18202 604 5880 5406 6325 +18203 3457 6182 6304 7214 +18204 627 6509 628 6913 +18205 4568 6351 4570 6761 +18206 3171 3104 6240 6608 +18207 1914 6156 5845 6574 +18208 4417 5876 4188 6864 +18209 2472 2525 2473 6646 +18210 2837 6038 5862 7093 +18211 4414 5885 6368 7092 +18212 2992 2972 5985 6400 +18213 1914 6211 6156 6574 +18214 6038 6317 619 6604 +18215 2425 5800 3167 6039 +18216 5041 4645 4643 7106 +18217 2083 6149 2177 6616 +18218 5432 591 5391 6268 +18219 4692 6043 6042 6678 +18220 514 6040 5417 6762 +18221 4850 5116 6378 7016 +18222 5407 5793 5435 7038 +18223 583 5822 5407 6401 +18224 1919 5872 5871 6196 +18225 2693 3105 3107 5938 +18226 3349 3380 6091 6747 +18227 4742 4741 4740 6046 +18228 5324 4749 596 6962 +18229 2096 5844 2117 6441 +18230 2257 6319 2253 6405 +18231 1674 1862 1875 5876 +18232 5936 6075 5061 6647 +18233 4736 5887 533 6768 +18234 6180 5297 6513 6668 +18235 4654 6129 4614 6411 +18236 1976 2132 6242 6537 +18237 6137 6434 6317 6643 +18238 5392 6136 5385 6478 +18239 2490 3507 6174 6469 +18240 2096 6441 6140 6450 +18241 2603 2797 3469 6217 +18242 4693 5819 5157 6042 +18243 505 5992 504 6318 +18244 6291 6349 1863 6690 +18245 5909 6466 6063 7084 +18246 4861 6010 4859 6199 +18247 3397 6753 3421 6837 +18248 6085 6086 3079 7103 +18249 564 6089 6016 7060 +18250 6037 6105 5098 6553 +18251 4686 5067 6472 6700 +18252 4270 4070 4472 5816 +18253 5023 5294 5193 6239 +18254 5327 6103 4705 6627 +18255 1580 1577 6260 6418 +18256 3041 3039 3038 5841 +18257 5115 5346 5171 7197 +18258 2173 6111 6467 7156 +18259 4749 5825 5324 6390 +18260 6021 4661 6343 6522 +18261 3961 3709 6492 6716 +18262 2889 6095 2890 6096 +18263 2208 2207 2201 6805 +18264 3168 2425 6039 6388 +18265 4281 6607 6120 6691 +18266 4703 6095 4704 6096 +18267 5880 6259 5881 7152 +18268 1690 6132 1915 6144 +18269 4624 6454 4604 6792 +18270 2131 1819 6222 6964 +18271 4060 6270 5951 7069 +18272 6186 6187 4083 7105 +18273 5158 5214 4977 6330 +18274 5621 6583 6458 6996 +18275 2170 6107 1668 6328 +18276 4776 4777 6457 6693 +18277 3112 5975 2768 6896 +18278 4164 5788 4038 6142 +18279 1853 6350 2042 7056 +18280 4234 4178 6073 6410 +18281 3001 5881 2414 6451 +18282 2183 1947 5905 6107 +18283 2389 5888 2387 6099 +18284 3525 2933 3106 5962 +18285 2476 3026 6236 6237 +18286 5075 570 5795 6665 +18287 5240 5937 5066 6815 +18288 1423 1513 1935 6278 +18289 474 6094 6327 6365 +18290 4891 4625 4849 6070 +18291 4900 628 6124 6457 +18292 4967 6002 6003 6724 +18293 451 6820 6126 7026 +18294 3129 6083 3130 6606 +18295 5299 5230 5342 6507 +18296 626 6807 6240 6957 +18297 3216 3212 3059 7120 +18298 2741 2742 2743 6364 +18299 5401 6067 5382 6334 +18300 4253 6238 6429 6706 +18301 4007 6774 3773 6873 +18302 1287 1521 6771 6874 +18303 4605 4606 6162 6646 +18304 458 457 4255 5954 +18305 497 4256 498 5955 +18306 4447 5818 4239 6836 +18307 5827 6497 3820 6631 +18308 1432 6655 1381 6960 +18309 3918 6654 3867 6959 +18310 4329 5871 4042 5872 +18311 3541 3542 2723 5819 +18312 4167 6403 4291 6796 +18313 5294 5278 6888 6910 +18314 5857 5910 4945 7106 +18315 1270 5933 1889 6685 +18316 3756 5932 1888 6687 +18317 5997 6150 3047 6710 +18318 5238 4691 6043 6044 +18319 561 6860 5830 6933 +18320 1285 1410 1202 6089 +18321 5660 5612 5720 6637 +18322 5562 5502 5454 6638 +18323 2642 2754 2755 6104 +18324 2438 2446 2439 5856 +18325 3018 5911 431 6650 +18326 4317 6027 6226 6942 +18327 3059 5874 6005 6823 +18328 538 4511 5987 6546 +18329 5294 6888 6216 6910 +18330 6200 6201 5394 6762 +18331 5220 5090 5219 6082 +18332 4463 6468 4117 7046 +18333 3551 3108 5975 7142 +18334 6198 6359 2021 7212 +18335 4100 4400 4423 6622 +18336 3491 6404 6353 6448 +18337 4991 6320 5828 6511 +18338 4664 6252 6363 7022 +18339 5881 6259 5014 7152 +18340 3070 3102 6414 6536 +18341 1930 6420 1681 6663 +18342 6655 6705 5662 6960 +18343 5504 6654 6704 6959 +18344 5275 6021 4661 6343 +18345 4296 4072 6133 6800 +18346 3020 2680 5879 6338 +18347 3453 6609 6333 7194 +18348 5357 5301 6011 6163 +18349 4953 5776 5125 6402 +18350 4038 6142 4291 6714 +18351 4254 4456 6349 6578 +18352 2514 6108 5981 6366 +18353 1690 6132 6144 6344 +18354 5007 4902 5085 6269 +18355 1312 1933 6467 7024 +18356 6095 6096 4931 6495 +18357 2893 5773 3395 5961 +18358 5606 6705 6655 6850 +18359 5448 6704 6654 6852 +18360 306 1838 6081 6661 +18361 2888 2889 2890 6103 +18362 4823 4698 4696 5892 +18363 1639 5878 2033 6544 +18364 5821 6496 6041 7149 +18365 25 6751 6264 6882 +18366 1625 5922 3808 6575 +18367 4646 6445 6054 6526 +18368 2786 2793 6433 6697 +18369 2841 6191 2842 7128 +18370 3631 5781 3597 6233 +18371 2550 3544 3055 5972 +18372 1718 6226 2134 6326 +18373 4471 5760 4439 6599 +18374 5334 4742 4983 5772 +18375 4211 6226 6326 6942 +18376 2928 3139 2929 6267 +18377 5875 6189 2530 7096 +18378 6073 6410 1845 6677 +18379 5018 602 5863 5920 +18380 5216 6091 5092 6747 +18381 1247 6563 1389 7070 +18382 1739 6230 6975 7176 +18383 4331 4011 6537 7141 +18384 567 6413 566 7128 +18385 1245 6278 5933 6825 +18386 6091 6288 5217 6565 +18387 4234 4073 4340 6677 +18388 2198 3807 2209 5798 +18389 2141 1916 6019 6153 +18390 3592 3616 6014 6121 +18391 2770 5810 2443 6457 +18392 1781 2147 5989 6944 +18393 2103 1791 1667 5994 +18394 4606 5008 6162 6646 +18395 587 6045 5425 6321 +18396 2472 2473 6454 6646 +18397 6187 7091 6203 7105 +18398 2599 5921 3277 6438 +18399 1980 5756 2093 6328 +18400 4853 6267 6155 7030 +18401 4146 4273 4459 6286 +18402 4142 6950 5853 7185 +18403 4668 4666 5061 6647 +18404 6566 6889 6264 7038 +18405 1745 6132 6133 6800 +18406 1854 2140 6316 6779 +18407 4061 5872 4421 6525 +18408 437 2918 5894 6515 +18409 2497 6380 6381 6966 +18410 5810 6457 628 6693 +18411 25 6383 504 6505 +18412 5362 5115 5364 6627 +18413 1321 5803 1621 7017 +18414 4270 5816 6139 6778 +18415 5132 5815 5133 6618 +18416 600 5428 5389 6266 +18417 5914 6552 5861 6936 +18418 5229 5192 4886 6970 +18419 1582 1576 6260 6327 +18420 1861 6113 2110 6635 +18421 2711 5766 2709 6869 +18422 632 6401 5407 7038 +18423 5901 6679 6017 7206 +18424 2783 5978 6170 6750 +18425 5815 6012 5132 6753 +18426 5177 5140 5321 5909 +18427 3471 6053 5980 6367 +18428 3168 6388 6039 6977 +18429 2582 2973 5998 6824 +18430 3150 5965 3151 6708 +18431 519 6136 5423 6331 +18432 2149 6196 5788 6796 +18433 2846 5847 2847 6279 +18434 5282 5961 6554 7135 +18435 1789 6100 2168 6800 +18436 1231 1360 1298 6788 +18437 384 6229 2487 6401 +18438 5860 6390 5799 7019 +18439 3205 3043 5772 7139 +18440 5912 6382 3292 6748 +18441 2134 1804 2016 6226 +18442 3430 6181 3581 6219 +18443 2031 1675 1807 6607 +18444 4929 4928 6010 6767 +18445 4734 5855 4716 6695 +18446 5100 4782 5867 6170 +18447 3717 3846 3784 6821 +18448 460 6206 5932 6838 +18449 3006 6372 6060 7029 +18450 6289 7166 6224 7167 +18451 618 6603 5518 6735 +18452 4031 6140 6441 6995 +18453 432 3018 431 6650 +18454 2284 6510 6294 6718 +18455 1778 6223 2163 7171 +18456 6288 6347 5127 6837 +18457 6180 6182 5297 6668 +18458 2089 1771 6156 6316 +18459 5404 5901 5432 6679 +18460 2478 6236 2476 6799 +18461 5187 5829 6567 6813 +18462 1547 6545 6428 6698 +18463 6011 6163 5301 6919 +18464 4472 4191 4112 5816 +18465 5895 6207 4028 6577 +18466 2123 1878 6132 6379 +18467 492 6787 6629 6881 +18468 4427 4125 4328 5906 +18469 2095 1821 5760 7092 +18470 4507 4542 465 6169 +18471 4640 5868 5801 6651 +18472 5272 4661 6021 6522 +18473 509 508 6068 6119 +18474 4056 6079 4207 6315 +18475 1723 2149 2052 5788 +18476 5981 6108 4575 6366 +18477 3819 6603 6534 6604 +18478 5253 5217 6091 6288 +18479 1709 5991 2043 6316 +18480 1847 6249 5959 6348 +18481 3159 5835 3158 6968 +18482 6258 6486 4696 6657 +18483 5236 6508 5976 7055 +18484 5292 5980 5227 6496 +18485 4575 6108 4901 6366 +18486 2549 5819 5941 6660 +18487 5019 4766 4979 5785 +18488 3992 3794 5798 7169 +18489 5916 6735 616 6828 +18490 2213 1322 2211 6572 +18491 341 6201 6452 6506 +18492 3568 6007 6612 6910 +18493 4111 6140 6081 6706 +18494 5380 6325 5406 6518 +18495 5324 5825 4749 6962 +18496 2249 6292 309 6690 +18497 5787 6065 5027 6358 +18498 1556 6391 1561 6409 +18499 1918 5885 2095 6368 +18500 3899 6772 6924 7085 +18501 6078 6422 1601 6664 +18502 1999 6066 5895 7047 +18503 3484 6489 2543 6557 +18504 2357 2302 2326 6285 +18505 3586 6092 3603 6456 +18506 1931 1669 2148 7033 +18507 382 381 6080 6115 +18508 5875 6587 1335 6729 +18509 4787 4788 5904 6273 +18510 1612 1611 6370 7104 +18511 5773 6554 5961 7135 +18512 4569 564 6015 6016 +18513 4244 6624 6061 6912 +18514 4753 6046 5925 6480 +18515 424 6739 6022 6894 +18516 488 487 6192 6419 +18517 5796 6077 3614 7062 +18518 2003 7059 5953 7129 +18519 3596 5987 6112 6546 +18520 6210 6400 5770 6621 +18521 2689 2570 2568 5920 +18522 1400 1257 6048 6519 +18523 3597 5781 3609 6169 +18524 5375 5386 5425 6598 +18525 6211 6377 4384 7087 +18526 2117 6441 5844 7176 +18527 4487 4310 4104 6356 +18528 6297 6332 5255 6565 +18529 1972 5999 5955 6223 +18530 5034 5340 6166 6707 +18531 1928 5951 1706 6494 +18532 348 6068 2370 6116 +18533 3369 6343 6659 6965 +18534 5964 6484 2803 7121 +18535 2780 2781 2782 6247 +18536 1625 1533 1620 5922 +18537 1922 6079 2089 6315 +18538 3069 6020 2998 6414 +18539 5506 6924 6772 7085 +18540 5646 7011 6874 7111 +18541 5488 7009 6873 7112 +18542 2647 5898 6177 7204 +18543 3292 3378 3295 6382 +18544 4348 4354 4097 5769 +18545 258 1593 257 6779 +18546 4978 5277 5296 6102 +18547 3572 6035 6502 7139 +18548 5092 6091 5091 6130 +18549 4448 6114 6120 6607 +18550 2908 5892 2874 6486 +18551 3504 5778 6361 6500 +18552 1716 1986 6167 6917 +18553 3819 3692 6604 6826 +18554 4891 6454 6070 6646 +18555 5915 6909 4050 7122 +18556 1824 6118 6395 6600 +18557 3555 2656 2748 5757 +18558 5172 4763 6243 6455 +18559 5783 6077 3614 6967 +18560 4489 5763 4355 6909 +18561 5987 6798 538 7048 +18562 614 6009 6412 7073 +18563 5788 6196 2149 6880 +18564 1727 5982 2063 6601 +18565 1906 5817 2135 6836 +18566 3986 6009 3830 6412 +18567 4733 4865 4729 5805 +18568 4445 4092 4295 6577 +18569 25 5793 5410 6566 +18570 3909 3731 3999 6440 +18571 6009 6389 6388 6976 +18572 493 4278 6248 6249 +18573 6146 6205 6671 7032 +18574 5979 538 6798 7048 +18575 4775 6062 5780 6719 +18576 1874 5952 1746 6950 +18577 5939 6266 600 7154 +18578 1762 2027 6244 6357 +18579 5089 5090 5332 6082 +18580 4753 5925 4752 6480 +18581 5823 6257 2459 6709 +18582 5833 6313 4517 6739 +18583 3085 5971 6257 7179 +18584 4711 5854 607 6982 +18585 4673 5004 5002 7078 +18586 4221 4469 4470 5858 +18587 352 6318 5793 6566 +18588 259 258 5991 6423 +18589 4629 4631 4630 6336 +18590 4293 5845 4485 6156 +18591 3362 6002 2596 6003 +18592 2115 6139 5816 6778 +18593 6735 6828 3777 6877 +18594 4214 4406 6025 6357 +18595 2473 6070 6454 6646 +18596 5053 4923 5313 6433 +18597 1850 2034 1694 6073 +18598 4687 6058 4910 6059 +18599 6281 6347 6288 6837 +18600 5836 4184 6192 6501 +18601 4781 5867 6247 6829 +18602 4497 6255 4553 6306 +18603 5755 6265 3113 6896 +18604 6656 7042 6154 7106 +18605 3200 6085 6163 6919 +18606 4822 4710 5273 5870 +18607 5368 5412 5381 6777 +18608 5914 6252 2906 6552 +18609 4945 5042 4748 6606 +18610 1849 6206 6337 6615 +18611 3488 6404 3446 6426 +18612 5218 5090 5069 6748 +18613 3341 6030 3357 6921 +18614 1679 6838 1940 7118 +18615 4299 6107 6090 6328 +18616 4788 4605 4787 5904 +18617 6453 6809 3635 7090 +18618 4781 4782 4628 6247 +18619 4569 6015 4568 6761 +18620 3215 6053 3332 6300 +18621 4091 6156 6211 6574 +18622 3629 3593 3658 6253 +18623 5774 5830 561 6582 +18624 3793 3728 3868 5950 +18625 2655 6037 2654 6553 +18626 2276 6329 2270 6354 +18627 3049 429 6159 6160 +18628 4849 6070 6265 7159 +18629 2947 5896 6680 6816 +18630 2808 2949 3031 5783 +18631 4905 6004 4904 7123 +18632 5186 5182 5356 6212 +18633 1919 5871 1632 6196 +18634 6263 6342 4602 7194 +18635 627 6725 6509 6913 +18636 4328 5906 4086 5959 +18637 249 6419 6324 7172 +18638 1824 6118 1670 6395 +18639 2389 6099 2459 6709 +18640 5855 5887 2412 6768 +18641 1954 6485 6111 7156 +18642 2910 2911 2909 6512 +18643 3402 6180 6508 6845 +18644 4223 6029 6558 7178 +18645 481 6423 6422 6664 +18646 6186 4083 6605 7105 +18647 4845 5784 4970 6724 +18648 2976 5868 6536 6651 +18649 2996 6431 6398 7101 +18650 3975 3800 6548 6922 +18651 1314 6549 1489 6923 +18652 2920 2785 2781 6247 +18653 5054 4938 4780 6709 +18654 3592 6682 6014 7080 +18655 4427 4035 5958 5959 +18656 2949 3031 5783 6764 +18657 5906 6909 2108 7115 +18658 6088 6829 6247 7117 +18659 4967 4836 6003 6340 +18660 2891 3470 6495 6767 +18661 1735 1929 6027 6605 +18662 3705 6503 3796 6720 +18663 3410 6012 6011 7158 +18664 3093 3172 3094 5778 +18665 5192 5229 6280 6970 +18666 4020 5808 4146 6386 +18667 5240 5938 5939 7154 +18668 5418 6200 5369 6268 +18669 5832 6105 3482 6659 +18670 4539 6077 4536 7089 +18671 6050 6380 2879 6966 +18672 473 5946 4368 6093 +18673 1672 5840 2002 6226 +18674 2876 6082 3444 6426 +18675 4687 4689 6058 6059 +18676 5300 5127 5130 6281 +18677 1242 1382 1307 5900 +18678 488 4540 4526 7062 +18679 5356 6573 6346 6899 +18680 4675 4581 4597 6224 +18681 1472 1271 1184 6528 +18682 3670 3958 3757 6529 +18683 6222 4441 6558 6817 +18684 2779 5926 6472 6700 +18685 5114 6047 5345 6400 +18686 1781 1666 2147 6944 +18687 466 6428 6198 7157 +18688 2769 7041 6124 7110 +18689 6158 6218 3114 6745 +18690 5215 6347 6004 6652 +18691 2716 3101 3048 5869 +18692 471 6407 472 6442 +18693 3179 3040 5841 6363 +18694 2703 5786 3151 5965 +18695 3560 2866 2874 6216 +18696 6052 6110 5377 6856 +18697 6072 4045 6460 7059 +18698 2207 5798 2201 6805 +18699 4421 4457 6525 7141 +18700 339 6405 6184 6506 +18701 5780 6639 6364 7145 +18702 2747 2566 6719 6861 +18703 4338 5760 4127 7092 +18704 5898 5978 4950 7211 +18705 556 4539 5969 6077 +18706 2728 6412 7073 7075 +18707 5953 6420 4434 6669 +18708 3596 3653 5987 6546 +18709 3599 6313 6739 6894 +18710 3494 6243 6522 7102 +18711 5802 6537 6242 7015 +18712 3787 3900 6440 7061 +18713 3136 3140 3074 5834 +18714 5064 6289 6130 6339 +18715 4636 4948 4949 5778 +18716 4197 6377 6076 7087 +18717 4589 6398 4952 6500 +18718 2172 6126 6369 7026 +18719 5822 6229 384 6401 +18720 2119 1857 6178 6726 +18721 5174 5156 5155 6024 +18722 1975 1655 6064 6375 +18723 6352 6410 1683 7032 +18724 6150 6276 3347 7155 +18725 5076 5075 6273 7168 +18726 5076 6161 5843 7168 +18727 6428 6988 6198 7157 +18728 3078 5864 3278 7103 +18729 1851 6196 6018 6733 +18730 2342 2371 2296 7044 +18731 5247 5282 6554 6842 +18732 4819 6043 4692 6678 +18733 226 6306 1586 6308 +18734 3242 5997 3243 6517 +18735 4201 4069 6244 6556 +18736 2797 6217 6236 7078 +18737 3828 6811 3758 6866 +18738 1272 1342 6812 6865 +18739 2640 2748 2749 6372 +18740 5584 6654 5486 6852 +18741 5742 6655 5644 6850 +18742 1821 2158 5760 6532 +18743 5164 6208 5119 6512 +18744 6126 6505 5797 6882 +18745 1669 1948 2165 5769 +18746 5768 6232 559 6453 +18747 4275 6250 453 6301 +18748 1708 7056 6176 7057 +18749 4074 4251 6270 6461 +18750 5223 5843 5309 6274 +18751 1906 1767 2001 5977 +18752 2850 2852 6235 7050 +18753 5078 6258 4695 6374 +18754 2526 2978 2527 6504 +18755 5355 6023 5186 6899 +18756 3077 3209 5897 6390 +18757 2484 2483 6237 7052 +18758 1746 5952 5853 6950 +18759 3078 3275 5864 7198 +18760 4651 5113 4954 7022 +18761 3263 6102 6035 6555 +18762 1704 5818 1870 6577 +18763 3235 5934 6814 6926 +18764 5804 6324 1627 6925 +18765 6072 6420 4045 7059 +18766 2782 6170 6351 6750 +18767 1972 1647 2163 5955 +18768 2600 6276 6011 6752 +18769 467 6323 6362 6545 +18770 2810 5942 2984 7013 +18771 4551 4517 5833 6313 +18772 2148 2165 1858 5769 +18773 1929 6027 6605 6964 +18774 5322 5772 5907 6832 +18775 1944 1711 1898 5955 +18776 1710 1899 1943 5954 +18777 3974 3830 2729 6412 +18778 4802 4999 5056 6008 +18779 4250 4075 6254 6859 +18780 4420 6192 4396 6348 +18781 567 6413 6191 6498 +18782 6059 6973 6058 7109 +18783 5238 4691 4694 6043 +18784 1781 6152 1666 6944 +18785 2643 2644 5846 6096 +18786 4670 5918 5347 6005 +18787 4628 6170 4627 6351 +18788 4642 6338 5879 6999 +18789 564 6015 6016 6089 +18790 5000 4998 4669 6613 +18791 4624 4604 6454 7140 +18792 3290 3449 5765 6849 +18793 3503 3021 2393 6162 +18794 4119 5858 5808 6436 +18795 6030 6212 3341 6573 +18796 2366 2331 373 6628 +18797 1930 6420 6663 7177 +18798 6704 6877 5547 6959 +18799 5705 6705 6879 6960 +18800 548 547 6051 6159 +18801 5998 6746 6446 6824 +18802 476 6134 4250 6254 +18803 2795 6512 6208 6697 +18804 2477 5927 2602 6481 +18805 2668 6297 3506 6565 +18806 5780 6364 4775 7145 +18807 3048 5869 3101 6963 +18808 4821 4692 6042 6678 +18809 1910 252 5836 6465 +18810 3285 6021 3191 6102 +18811 3232 6074 6710 7155 +18812 3940 6548 3800 7113 +18813 1314 1454 6549 7114 +18814 2995 6431 2996 7101 +18815 2363 376 2320 6171 +18816 1886 6187 6168 6930 +18817 2037 1719 1813 6622 +18818 6297 5246 6314 6842 +18819 3071 6259 5880 7152 +18820 4684 5926 5832 6700 +18821 5755 4677 6265 6896 +18822 1633 2129 6026 6386 +18823 3453 3325 6333 6609 +18824 473 6014 472 6303 +18825 2239 6586 6292 7202 +18826 3714 3820 6736 6887 +18827 3448 3570 5759 6183 +18828 3336 6554 5771 7144 +18829 31 6793 6048 7165 +18830 4791 5867 5866 6872 +18831 5891 6225 6176 6906 +18832 2164 6547 1971 6740 +18833 6090 6328 2170 6880 +18834 1818 1969 2099 6071 +18835 5105 4636 4949 5888 +18836 3206 6268 375 6926 +18837 4871 6183 6030 6921 +18838 3649 436 6121 6421 +18839 5214 6738 6330 6843 +18840 5250 6218 5234 6220 +18841 4670 5047 5874 6005 +18842 4899 5997 6150 6517 +18843 3049 2649 6044 6159 +18844 1970 1732 6029 6558 +18845 3357 6183 6181 6921 +18846 2949 5782 2807 7116 +18847 552 5833 4517 6739 +18848 6422 6423 1592 6664 +18849 4930 5913 6095 6495 +18850 2944 6080 2816 6371 +18851 3659 3587 6313 6672 +18852 4346 6073 4030 6315 +18853 5115 5961 5364 6627 +18854 3631 3597 3663 6233 +18855 2006 1870 5818 6577 +18856 3004 2744 2606 6473 +18857 5148 5280 4825 6486 +18858 3435 3417 6298 6314 +18859 4190 6223 6187 7188 +18860 4350 6532 5865 6597 +18861 4244 4304 6061 6624 +18862 3291 6130 3377 6339 +18863 3413 6227 6228 7102 +18864 3681 6674 3963 6716 +18865 1717 1936 1801 6440 +18866 576 6974 5998 7014 +18867 3620 3600 6362 6430 +18868 4463 4079 6740 7046 +18869 6265 6378 5755 6786 +18870 3022 3019 3043 6502 +18871 3306 6263 6243 6609 +18872 2412 5887 5855 6695 +18873 4709 4710 6231 6711 +18874 6132 6344 2081 6817 +18875 3367 3198 6282 6473 +18876 2444 6523 5789 7186 +18877 6333 6609 6228 7194 +18878 1674 2184 6396 6864 +18879 3041 5770 5883 6621 +18880 5156 5193 6056 6239 +18881 5893 5984 4993 7037 +18882 6050 2879 6380 7016 +18883 1454 1489 1314 6549 +18884 3975 3800 3940 6548 +18885 344 6586 2240 7202 +18886 2139 6145 6193 7143 +18887 4680 5791 4986 6267 +18888 2705 2917 2423 5785 +18889 2253 6405 6319 6834 +18890 5015 6259 5880 6617 +18891 5398 5375 5425 6598 +18892 2389 5888 6099 6709 +18893 2006 5818 6207 6577 +18894 4715 6451 5774 6582 +18895 1970 1819 1732 6558 +18896 5123 5124 6346 6899 +18897 5681 6619 5747 6701 +18898 2423 2917 437 6515 +18899 3046 3045 3538 7020 +18900 5057 4801 6213 6469 +18901 2567 2847 5847 6484 +18902 2833 5861 3148 6437 +18903 3577 5957 3403 6180 +18904 3042 3033 3096 5903 +18905 5139 5061 4666 6647 +18906 2721 2547 2793 5941 +18907 1492 6640 6701 7014 +18908 5335 5897 5870 6711 +18909 4090 6312 6524 6961 +18910 4584 4586 6353 6448 +18911 4841 6104 4920 6656 +18912 4434 6460 4045 7059 +18913 3071 5880 5881 7152 +18914 30 5919 6927 7089 +18915 4930 6495 4928 6767 +18916 4593 5078 6692 6915 +18917 6218 6220 3114 6929 +18918 529 6287 28 6911 +18919 6165 6169 465 6698 +18920 567 6413 6498 6827 +18921 4165 6018 4404 6149 +18922 5846 6719 5956 6861 +18923 2045 1693 1881 7131 +18924 2006 6207 1870 6577 +18925 3149 5923 3150 6708 +18926 572 5882 6274 6491 +18927 5116 6050 5109 6380 +18928 4846 6257 5971 6937 +18929 5799 6143 4707 6936 +18930 2883 2904 2754 6402 +18931 4148 5890 4399 6410 +18932 4223 4481 6559 7178 +18933 2728 6412 2729 7073 +18934 2840 3344 2799 6643 +18935 4680 4681 5834 6267 +18936 487 4526 5796 6370 +18937 4081 4367 5788 6796 +18938 5786 5965 5173 6708 +18939 3428 3387 6002 6724 +18940 4352 5952 4084 7185 +18941 3312 2596 3315 6003 +18942 4422 4043 5967 6958 +18943 1348 1208 5900 6278 +18944 5824 5997 3243 7020 +18945 1539 1538 1543 5803 +18946 4210 4160 6310 6733 +18947 4677 6265 6896 7159 +18948 4460 4182 4093 5871 +18949 3394 5961 6049 7196 +18950 1973 6114 6468 6740 +18951 5771 6554 5993 7144 +18952 5903 4546 6650 6715 +18953 3219 2648 2664 5898 +18954 2850 2852 2857 7124 +18955 5973 6468 5761 6633 +18956 5038 4942 4789 5978 +18957 2929 2930 2928 5791 +18958 3079 6085 3200 6919 +18959 2794 6402 6258 6486 +18960 2596 6002 3387 6724 +18961 3256 3255 5943 7055 +18962 5964 6976 2614 6977 +18963 6098 6167 1678 7171 +18964 528 5412 6141 6293 +18965 463 5950 5949 6806 +18966 480 479 5991 6423 +18967 5809 6905 6720 7098 +18968 1205 1269 5974 6791 +18969 3691 3755 5973 6790 +18970 464 6359 465 7212 +18971 2648 5898 3052 5962 +18972 463 6359 5950 6806 +18973 4871 5143 5141 6030 +18974 3644 6077 421 6797 +18975 5403 6171 5371 6435 +18976 579 5850 578 6366 +18977 518 6776 6405 6854 +18978 1938 1690 6144 6344 +18979 5942 6608 2811 7065 +18980 6134 6254 262 6859 +18981 4558 4528 4494 6121 +18982 1242 1307 1496 5900 +18983 1849 6206 1659 6337 +18984 590 5901 5404 6679 +18985 421 5969 5783 6764 +18986 3717 3784 3991 6989 +18987 2704 3006 5811 7029 +18988 2770 2395 2443 5810 +18989 336 2313 6136 6241 +18990 4670 5347 5123 6005 +18991 4783 4599 5831 6885 +18992 544 6456 5903 6832 +18993 1984 6151 1742 6152 +18994 1596 6202 1604 6463 +18995 2711 5766 1329 6727 +18996 2727 2851 3103 6188 +18997 4578 5981 4589 6500 +18998 2837 6038 3573 6434 +18999 3505 2518 2517 6273 +19000 3333 3226 5790 6941 +19001 4665 6252 5260 6713 +19002 4659 5028 4764 6609 +19003 4863 5820 630 5896 +19004 1765 2129 2051 7033 +19005 5009 4606 5008 6162 +19006 3369 3370 5925 6343 +19007 2428 6009 2615 7023 +19008 4239 5817 4015 6836 +19009 5903 5907 5772 6832 +19010 5964 2614 6976 7073 +19011 2465 2524 2961 5774 +19012 563 6247 6089 6712 +19013 4271 5865 4394 6194 +19014 3229 3013 6069 6613 +19015 5256 6117 6007 6612 +19016 1696 6198 6138 6884 +19017 477 476 6254 6418 +19018 2574 6017 2821 6197 +19019 4093 5871 6090 6858 +19020 4332 6204 4219 6205 +19021 4507 465 6165 6169 +19022 2591 5910 5857 7042 +19023 4244 6360 6151 6912 +19024 2063 5982 5816 6601 +19025 421 3614 5783 6077 +19026 2672 2783 5978 6170 +19027 4060 6406 5951 6494 +19028 5326 4807 5307 6269 +19029 435 3604 436 6121 +19030 2091 1633 6055 6386 +19031 6029 6186 4361 6558 +19032 2883 2702 2904 6402 +19033 4894 4893 5832 6659 +19034 2323 351 6067 6318 +19035 4377 6312 6271 6524 +19036 2004 6341 1859 6420 +19037 2474 6088 2451 7040 +19038 5802 6525 1981 6537 +19039 1496 1242 5900 6741 +19040 4089 6118 4267 6395 +19041 1645 5890 1802 6410 +19042 5794 6259 5037 7035 +19043 2483 6122 6237 7052 +19044 4112 4285 4349 6357 +19045 2767 6124 2769 6457 +19046 3312 6245 3313 6986 +19047 2135 5817 1869 6836 +19048 1708 6225 6176 7056 +19049 3349 6091 3380 6288 +19050 3312 2543 6003 6557 +19051 4593 6692 6197 6915 +19052 3075 6590 5873 6985 +19053 1224 6571 1289 6860 +19054 558 5768 559 6453 +19055 4192 4290 481 5991 +19056 5390 6184 5388 6948 +19057 4765 6455 4976 7149 +19058 6612 6888 5278 6910 +19059 5109 6380 6050 7140 +19060 6067 6334 5401 6550 +19061 3043 6502 5772 7139 +19062 4244 6151 4297 6912 +19063 2738 2548 5941 6660 +19064 2925 2838 2844 6885 +19065 3620 237 6165 6362 +19066 3737 3986 3884 6009 +19067 3778 5916 2660 6389 +19068 4000 6731 3674 6895 +19069 5803 6642 1539 7017 +19070 1940 1679 6687 6838 +19071 2267 6439 6331 7081 +19072 5114 5985 6047 6400 +19073 250 6419 6192 7104 +19074 1801 6440 5949 6833 +19075 1961 6057 1698 6311 +19076 2004 6420 7059 7129 +19077 4964 5134 4929 5757 +19078 1945 6460 2133 6461 +19079 6197 6656 6104 6915 +19080 2775 2732 2756 6060 +19081 4518 6092 4521 6456 +19082 1394 6769 1247 7070 +19083 3560 2874 2908 5892 +19084 5910 6087 4840 6576 +19085 4030 4374 4258 6315 +19086 3202 6086 3079 6919 +19087 4928 6495 6010 6767 +19088 5308 6137 5986 6643 +19089 3258 3467 6411 6477 +19090 2776 2732 6472 6700 +19091 6020 6414 5887 6768 +19092 1987 6249 6248 6335 +19093 4983 4753 5323 6480 +19094 4845 6245 5784 6724 +19095 3288 2473 3289 6070 +19096 3126 5888 2389 6709 +19097 1598 1601 6078 6202 +19098 4795 6246 4718 6414 +19099 3354 5839 6567 6813 +19100 3454 6489 5792 6630 +19101 4984 5849 4813 6158 +19102 3052 2887 6378 7204 +19103 601 5428 600 6052 +19104 505 6067 5401 6550 +19105 5921 6438 6086 7198 +19106 3668 6784 6641 6785 +19107 1182 6781 6640 6782 +19108 503 502 6741 6766 +19109 4277 461 6206 6337 +19110 526 6284 6294 6387 +19111 3484 6063 6489 6557 +19112 2198 5798 2200 7169 +19113 4924 4971 4847 6511 +19114 4998 6086 5864 7163 +19115 3220 5849 6158 7142 +19116 2233 6443 6625 6990 +19117 1781 2028 2177 6006 +19118 5986 6789 4805 7163 +19119 4693 5819 6042 6660 +19120 4577 6282 5981 6473 +19121 5231 6074 5192 6277 +19122 1608 6261 218 6262 +19123 6186 6605 1929 7105 +19124 364 6325 5920 7007 +19125 2306 6067 2362 6334 +19126 1958 6018 6019 6149 +19127 1696 2021 6198 6884 +19128 1958 6018 2086 6019 +19129 5208 6210 5770 6591 +19130 5963 2922 7073 7075 +19131 2920 2936 6089 6247 +19132 3230 3557 3559 5824 +19133 4022 6018 6196 6733 +19134 3396 6074 3316 6277 +19135 3596 3607 3612 5987 +19136 1220 6563 6766 6997 +19137 5322 5903 5772 6832 +19138 5331 6091 5147 6477 +19139 4166 6344 6326 6493 +19140 4519 468 6253 6362 +19141 5185 5233 4881 6745 +19142 250 6192 6419 7172 +19143 5133 5815 4844 6245 +19144 6381 6966 5931 7128 +19145 2024 5900 6449 7079 +19146 548 6051 4530 6160 +19147 561 6829 6860 6933 +19148 2237 6443 2227 7180 +19149 298 6193 1878 6379 +19150 2409 2407 6526 7116 +19151 5193 5280 6056 6216 +19152 2761 5985 2759 6786 +19153 3256 6508 3404 7055 +19154 5577 5471 5500 6570 +19155 5629 5658 5735 6569 +19156 6331 6579 2263 7081 +19157 2001 1906 6230 6992 +19158 5041 5011 4996 6371 +19159 3345 3338 3566 6137 +19160 5877 5878 2038 6615 +19161 1298 1505 1231 6994 +19162 631 6229 5930 6716 +19163 2387 5888 5889 7186 +19164 2362 6334 6067 6550 +19165 2497 6966 6381 7128 +19166 3217 2707 3218 6869 +19167 2947 5896 3023 6680 +19168 4734 6695 4716 6755 +19169 5142 5139 4666 6084 +19170 2853 2979 2999 5780 +19171 2124 1744 6256 6961 +19172 4495 5987 6112 6682 +19173 2220 2224 6479 6550 +19174 1839 6254 5885 6859 +19175 5357 5358 5144 6163 +19176 1306 1269 1462 5974 +19177 3792 3755 3948 5973 +19178 4581 6224 6425 7036 +19179 3112 3110 2768 5975 +19180 473 6093 474 6094 +19181 3399 3384 6342 6908 +19182 5311 5159 5257 6172 +19183 4522 6313 4552 6462 +19184 4883 4885 5283 5771 +19185 617 5916 6521 6735 +19186 1850 1663 2034 6315 +19187 5271 6314 5267 6332 +19188 4244 6152 4071 6912 +19189 1818 5764 6071 6663 +19190 4649 6130 6129 6339 +19191 5872 6525 5802 7141 +19192 5463 6459 6751 7094 +19193 514 5394 6201 6762 +19194 1913 6256 6524 6961 +19195 4334 6356 4379 6505 +19196 4061 6310 5872 6525 +19197 5754 6264 3966 6889 +19198 6056 3526 6239 6910 +19199 3052 5898 2647 7204 +19200 4248 6250 4275 6658 +19201 3056 5824 3559 5831 +19202 2668 3383 6332 6565 +19203 1548 6428 1547 6545 +19204 4617 6084 4616 6345 +19205 2758 2489 2491 6075 +19206 2669 3326 6314 6332 +19207 3925 6595 6562 6773 +19208 1439 6596 6561 6770 +19209 4365 6071 4017 6663 +19210 1192 6563 6825 7070 +19211 5206 5282 5364 5961 +19212 4022 6018 4167 6196 +19213 3498 6117 3438 6612 +19214 3244 5824 3243 7020 +19215 6117 6713 3564 7148 +19216 4148 6146 5890 7032 +19217 4761 5863 5939 6815 +19218 2959 3274 6217 6471 +19219 5233 5250 6158 6218 +19220 1668 2170 2112 6107 +19221 3434 6298 3393 6554 +19222 4808 6502 6035 7139 +19223 5822 6680 5806 6981 +19224 4222 5808 4020 6026 +19225 6124 6188 4571 6551 +19226 4072 6559 6133 6800 +19227 2799 5945 2661 6643 +19228 5962 6378 4700 7204 +19229 4569 4567 6381 6761 +19230 2819 6028 5944 6688 +19231 6165 6362 237 6545 +19232 4180 6373 6114 6468 +19233 4672 6431 5874 7101 +19234 6614 6909 2108 7122 +19235 5070 6003 4836 6340 +19236 6263 6342 5821 7149 +19237 5812 5844 1641 6995 +19238 4404 6018 4022 6733 +19239 5247 5341 5282 6842 +19240 4471 5760 4260 7092 +19241 5224 5290 5350 5792 +19242 5403 5371 5431 6435 +19243 3570 3343 2637 6030 +19244 4461 4231 6019 6290 +19245 504 6318 5992 6383 +19246 3625 6255 6092 6715 +19247 1774 2180 1848 6432 +19248 5480 6828 6735 6877 +19249 3793 3868 1990 5950 +19250 3463 3405 5873 6590 +19251 1859 6341 6127 7203 +19252 499 5933 6167 6917 +19253 1470 5995 6416 6902 +19254 2922 2935 5884 5963 +19255 3294 3466 3486 6129 +19256 6284 6285 5405 6518 +19257 3397 3421 6281 6837 +19258 473 472 5946 6303 +19259 327 2196 326 6287 +19260 370 369 2698 6754 +19261 6297 6314 6298 6842 +19262 5959 6501 5958 6918 +19263 2462 5820 2461 7191 +19264 2417 6457 6083 6551 +19265 5907 6302 4817 6832 +19266 1319 7070 6825 7071 +19267 1709 2077 1901 5991 +19268 6007 5278 6612 6888 +19269 516 6201 5420 6948 +19270 4329 5872 4160 6196 +19271 2836 6437 6058 7088 +19272 1813 6622 6312 7187 +19273 2929 6514 5826 6951 +19274 3188 3224 3115 6158 +19275 4627 6351 6170 6750 +19276 517 6184 6506 6948 +19277 5875 6499 581 6729 +19278 2027 1949 1631 6357 +19279 1762 1858 2165 6244 +19280 1850 5935 1922 6315 +19281 1569 1572 5946 6094 +19282 3493 6353 3439 6358 +19283 5953 6537 4435 7015 +19284 1514 6732 1188 6881 +19285 4989 4841 4968 6656 +19286 3019 3018 3033 5911 +19287 1217 1507 6572 6585 +19288 2083 1822 2177 6149 +19289 4975 4993 4990 5984 +19290 5289 5892 4825 6216 +19291 6036 6043 4819 6678 +19292 6648 3700 6801 6939 +19293 6649 1214 6802 6940 +19294 5999 6396 2184 6864 +19295 5203 6399 5288 6662 +19296 2312 6068 346 6296 +19297 3590 6190 6077 6797 +19298 1754 1981 2007 5802 +19299 5792 6065 3465 6630 +19300 4941 4855 4942 7035 +19301 1940 6206 1761 6838 +19302 2965 3128 2803 5964 +19303 5261 5829 5162 6166 +19304 4131 4332 4219 6205 +19305 6114 6740 6113 7046 +19306 514 4254 6349 6690 +19307 1344 6016 1251 6844 +19308 1796 2110 2185 6113 +19309 5800 6039 4618 6763 +19310 5248 6444 6304 6591 +19311 4805 5001 5304 5986 +19312 4420 6192 6348 7172 +19313 1720 2015 2188 5947 +19314 519 5423 520 6331 +19315 2944 3081 2945 6371 +19316 1361 6722 1305 6743 +19317 1803 5853 1682 6310 +19318 3037 6398 6282 6500 +19319 1789 6559 2078 7178 +19320 4789 4791 4790 6872 +19321 1348 5900 2069 6278 +19322 2097 260 6194 6568 +19323 3630 442 441 7076 +19324 5575 6765 6580 7031 +19325 1598 6078 222 6202 +19326 4980 5801 4994 6148 +19327 1652 2077 1926 5865 +19328 3170 5861 2832 6552 +19329 2050 5852 1902 6685 +19330 2049 5851 1903 6687 +19331 5240 5245 4690 5938 +19332 6222 6558 2100 6817 +19333 4345 4092 4445 6064 +19334 6415 6428 465 6698 +19335 2361 6171 6040 7151 +19336 5326 5307 6137 6269 +19337 4841 5910 6576 6656 +19338 2072 1738 5760 6599 +19339 4244 4297 6152 6912 +19340 357 6048 1400 7107 +19341 1739 6992 6230 7176 +19342 4527 6121 4528 6251 +19343 2201 5798 2207 6383 +19344 2254 6581 6405 6834 +19345 4253 4203 6238 6706 +19346 612 5963 5884 6364 +19347 3803 6953 6840 7113 +19348 1317 6954 6841 7114 +19349 2902 3241 6361 7027 +19350 5776 6424 5965 6831 +19351 2909 3241 6208 6512 +19352 4451 6315 4258 6316 +19353 5172 4765 4763 6455 +19354 6086 6438 3308 7198 +19355 6151 6360 6153 7180 +19356 2167 1896 6355 7213 +19357 1956 2161 5950 6806 +19358 533 534 6768 7136 +19359 1607 1609 6464 6465 +19360 1729 2024 5900 6449 +19361 4588 6235 4951 7125 +19362 3658 6253 235 6391 +19363 1711 1885 1902 5852 +19364 1710 1884 1903 5851 +19365 5262 6031 5829 6813 +19366 1706 6406 1977 6494 +19367 337 336 6136 6776 +19368 423 6022 424 6445 +19369 303 6579 2263 6581 +19370 4491 4306 6254 6597 +19371 4161 5967 4324 6673 +19372 1963 6532 5885 6597 +19373 3301 5939 5938 7154 +19374 3003 6155 2846 6279 +19375 4815 4877 4814 5975 +19376 4278 4247 6248 6335 +19377 6270 6386 1836 6461 +19378 4956 5168 5970 6161 +19379 2171 1783 2018 5982 +19380 4950 4827 4627 6750 +19381 2635 2637 6030 6272 +19382 2106 6175 2036 6493 +19383 3485 6216 2866 6231 +19384 6113 6740 5966 7046 +19385 3284 6343 3494 6522 +19386 3992 3794 3702 5798 +19387 4052 6034 4392 6385 +19388 4998 5864 6086 6613 +19389 4998 6086 4669 7103 +19390 3103 2609 2727 6957 +19391 2183 1827 6107 6949 +19392 5862 6038 618 6521 +19393 4435 4331 4011 6537 +19394 610 6497 5827 6631 +19395 1643 1803 1844 6310 +19396 2563 425 5833 6445 +19397 4760 610 609 6417 +19398 4093 6090 5947 6858 +19399 4083 6187 6186 7188 +19400 5262 5829 5317 6813 +19401 1262 6974 6640 7014 +19402 2383 6075 2491 6173 +19403 275 6359 5950 6756 +19404 4395 5951 4146 6286 +19405 1830 2142 1748 5973 +19406 2177 6535 6006 6616 +19407 5228 5128 6277 6281 +19408 3229 6613 6069 7103 +19409 2220 6209 2224 6550 +19410 5240 5245 5938 7154 +19411 1766 5837 1979 6599 +19412 5868 6414 3102 6536 +19413 5824 3243 5997 6517 +19414 3974 2729 2728 6412 +19415 4787 5074 4769 6273 +19416 3234 3206 3235 6814 +19417 5864 6789 5986 7163 +19418 5575 7031 6580 7207 +19419 3509 5839 3508 6738 +19420 5059 5060 6122 6431 +19421 1456 2973 2584 6824 +19422 4701 4700 5985 6786 +19423 312 6153 2141 6625 +19424 3786 3280 2872 6317 +19425 4160 6196 5872 6733 +19426 4897 5824 5006 5997 +19427 1996 1722 1928 5951 +19428 1859 6420 6341 7203 +19429 5055 4792 5304 5779 +19430 481 4290 482 6779 +19431 4734 5855 6695 7098 +19432 4809 5167 5927 6481 +19433 5953 6669 5807 7129 +19434 5307 4807 4805 6789 +19435 2015 6090 5947 6516 +19436 5219 5218 5957 6748 +19437 5701 6644 5752 7070 +19438 2649 6043 3283 6044 +19439 4023 4161 4324 6673 +19440 4200 6186 6029 7188 +19441 5360 5226 5348 6300 +19442 1760 6322 1846 6490 +19443 4462 6145 523 6193 +19444 5165 5166 5131 6621 +19445 2886 6172 2885 6173 +19446 1664 2079 1794 6033 +19447 3886 3780 2617 5809 +19448 5990 6361 5033 7027 +19449 1701 6139 2046 6778 +19450 4859 5801 6199 6651 +19451 4998 4669 6613 7103 +19452 4419 6198 465 6359 +19453 4470 4221 5858 6436 +19454 5315 5009 5008 5814 +19455 1575 264 1572 6094 +19456 1661 2035 1851 6018 +19457 5453 5543 5594 6772 +19458 5270 5266 5264 5842 +19459 5911 6036 4820 6502 +19460 4635 6108 4636 7049 +19461 2807 2808 423 6054 +19462 4803 4867 5024 5859 +19463 1818 1681 5764 6663 +19464 3384 3399 3405 6908 +19465 1837 1635 2092 6673 +19466 4199 4124 6475 6691 +19467 1276 1417 1219 6453 +19468 4911 6059 4974 6815 +19469 2686 2837 5862 7093 +19470 1962 5958 1791 6918 +19471 1547 6428 1544 6698 +19472 5408 608 31 7165 +19473 5328 5773 5327 6627 +19474 4540 6190 6077 7062 +19475 2001 6230 5977 6975 +19476 4447 4239 4176 6836 +19477 4725 5896 6693 6816 +19478 5897 595 6628 6962 +19479 5995 6572 1507 6585 +19480 466 467 6165 6545 +19481 5978 6872 5794 6945 +19482 6503 6580 3796 6720 +19483 3652 6121 435 6302 +19484 335 6110 2324 6856 +19485 3497 6074 3450 6280 +19486 4502 5948 4552 6313 +19487 5007 4783 4599 5831 +19488 499 500 5933 6917 +19489 6014 6421 6121 6682 +19490 3968 6509 6221 6725 +19491 505 5992 6318 6479 +19492 6497 6631 609 6721 +19493 3405 3067 6367 6590 +19494 4860 5956 4937 6199 +19495 6010 4858 6199 6495 +19496 5310 5308 5304 5986 +19497 507 4244 6061 6360 +19498 3042 3299 5772 5907 +19499 4116 5999 4464 6000 +19500 3727 6735 6877 6900 +19501 2557 6050 6265 7016 +19502 6354 6387 6379 6935 +19503 516 515 6201 6506 +19504 5864 5986 3063 6560 +19505 4126 4258 6156 6316 +19506 5083 6174 6393 7125 +19507 2655 3481 6105 6553 +19508 28 529 6141 6287 +19509 2570 5984 5893 7045 +19510 5903 6456 433 6832 +19511 2703 2700 3151 5786 +19512 3293 3076 3135 6390 +19513 5354 6012 5132 6618 +19514 4225 4140 6406 6407 +19515 3500 6382 6082 6748 +19516 6013 6083 4746 6606 +19517 1423 1245 1513 6278 +19518 3402 3581 6180 6845 +19519 3402 6508 3581 6845 +19520 5206 5204 6049 7197 +19521 5298 5252 5136 6180 +19522 4658 4659 5029 6228 +19523 2314 2326 2302 6234 +19524 4350 5865 4271 6597 +19525 1745 1795 6133 6817 +19526 4331 4479 5807 6669 +19527 4945 5856 4840 5910 +19528 3602 6546 3596 6943 +19529 5859 5942 4771 6835 +19530 4636 5888 5105 7049 +19531 1906 1671 2135 5817 +19532 4461 510 6290 6625 +19533 6041 6101 3522 6455 +19534 6023 6471 5188 6929 +19535 2462 6229 5820 7191 +19536 6369 6636 3798 7025 +19537 5859 7065 6008 7127 +19538 6014 472 6303 7080 +19539 2257 6405 339 6506 +19540 2817 5806 2944 6981 +19541 3926 1992 320 5797 +19542 3670 6529 3757 6774 +19543 1184 6528 1271 6771 +19544 5823 6099 2790 7116 +19545 4766 5785 5811 7029 +19546 4087 6167 4375 6490 +19547 1768 2138 6407 6524 +19548 3854 6584 3945 7094 +19549 306 6319 2252 6384 +19550 2839 2898 2840 5986 +19551 5486 6852 6654 6853 +19552 5644 6850 6655 6851 +19553 5115 6627 6095 6742 +19554 5916 6521 3718 7093 +19555 4411 495 4181 6000 +19556 5162 5261 5317 5829 +19557 6147 6510 2289 6718 +19558 6219 6508 5185 6845 +19559 3045 3538 5997 6710 +19560 5460 6811 6488 6866 +19561 6487 5618 6812 6865 +19562 2270 6354 6329 7143 +19563 2351 2299 2313 6241 +19564 1774 5989 2147 6032 +19565 1752 1869 2006 6836 +19566 2953 6623 6013 6816 +19567 2288 6293 2283 6294 +19568 344 343 6040 7202 +19569 2019 249 6485 7172 +19570 2927 2737 2789 6109 +19571 4323 6196 4160 6733 +19572 3447 3490 3536 6173 +19573 5856 6087 3156 6744 +19574 2278 2279 6354 6387 +19575 6142 6349 4456 6578 +19576 2670 2669 3417 6314 +19577 6007 6143 4739 6888 +19578 1977 266 5946 6406 +19579 1289 6632 6571 6743 +19580 4461 6153 510 6625 +19581 5791 5826 5006 6951 +19582 2001 5977 1767 6975 +19583 6187 6203 4083 7105 +19584 490 6485 6111 6883 +19585 6061 6360 315 6822 +19586 2354 2300 6135 6478 +19587 1827 5812 6107 6949 +19588 4677 4702 5755 6265 +19589 1788 2167 6624 6912 +19590 1794 6385 6034 6980 +19591 2311 5767 326 6902 +19592 2180 6032 1697 6356 +19593 2393 2392 2416 6717 +19594 2004 7059 2003 7129 +19595 4163 4012 5840 6376 +19596 6079 6315 4056 6316 +19597 1372 1224 5830 6571 +19598 2766 6188 6124 6551 +19599 2776 2917 2757 5811 +19600 4637 6259 4639 6617 +19601 2144 6349 5940 6690 +19602 5008 4887 4984 5814 +19603 4511 4495 5987 6546 +19604 466 6428 6545 6698 +19605 3592 3612 3607 6682 +19606 1306 2084 1446 5974 +19607 3792 2085 3932 5973 +19608 5913 6553 5346 7197 +19609 6182 6304 5258 6668 +19610 1713 6120 1843 6373 +19611 2033 2102 1817 6544 +19612 1277 6088 2474 7040 +19613 5215 4905 4869 6652 +19614 1305 6722 1240 6956 +19615 2989 6059 5984 6688 +19616 5034 6166 5874 6707 +19617 3557 2925 2844 5758 +19618 580 5875 581 6587 +19619 3096 5903 433 6832 +19620 2627 6104 6656 6915 +19621 6257 6737 5971 6969 +19622 6190 489 6642 6794 +19623 5009 6162 5814 6717 +19624 5915 6000 4181 6474 +19625 1186 1311 1308 6232 +19626 1751 2005 5840 6204 +19627 4673 5002 6217 7078 +19628 5240 5939 5937 6815 +19629 520 6350 6579 7081 +19630 548 6044 5238 6159 +19631 1669 5769 2148 7033 +19632 2741 2980 2855 5780 +19633 3404 6180 6182 6508 +19634 4485 4290 4126 6316 +19635 421 2495 5969 6764 +19636 2938 2515 2514 5981 +19637 443 2998 6020 6768 +19638 5254 5258 6427 6668 +19639 4716 5855 533 5887 +19640 4965 4943 4872 7043 +19641 2629 6154 6197 6656 +19642 5971 6257 4846 6737 +19643 568 6191 4770 6215 +19644 2518 2391 6162 6273 +19645 5926 6696 6472 7067 +19646 227 1580 228 6260 +19647 4832 5847 4566 6484 +19648 5287 5285 4814 5975 +19649 4409 4115 6144 6344 +19650 6014 6682 472 7080 +19651 5406 5376 6518 6987 +19652 4383 4090 6256 6961 +19653 4060 5951 4395 6494 +19654 4608 6129 6411 6870 +19655 4223 6559 6057 7178 +19656 489 6794 6419 7172 +19657 5323 5322 4983 5772 +19658 482 6202 6078 6422 +19659 1459 1368 6583 6996 +19660 3040 2611 2613 6363 +19661 5932 6440 460 6924 +19662 2713 6608 6128 6957 +19663 572 6758 6491 6897 +19664 2924 6009 3951 7023 +19665 5259 5161 5311 6172 +19666 1852 6271 1768 6407 +19667 5219 5090 5218 6748 +19668 4707 5799 4709 6143 +19669 3344 6137 5986 6789 +19670 2010 5959 2178 6918 +19671 4884 4680 4885 5834 +19672 427 3639 428 5988 +19673 3126 2387 2389 5888 +19674 4964 4683 5096 6037 +19675 5228 6277 5192 6280 +19676 617 5916 5862 6521 +19677 2915 2435 2437 5794 +19678 3156 2985 2987 6087 +19679 3966 5754 3704 6264 +19680 5032 6448 4610 6483 +19681 514 6292 6452 6690 +19682 6250 6636 6369 7025 +19683 2971 2992 6210 6400 +19684 569 4769 5074 6215 +19685 3879 5916 3718 7093 +19686 4897 4902 5824 6517 +19687 302 1900 6350 6579 +19688 2038 5878 1761 6206 +19689 2648 3052 2934 5962 +19690 2040 5906 5959 6335 +19691 4882 6074 5790 6970 +19692 6103 6267 5834 7030 +19693 2125 5952 1861 6635 +19694 5076 4787 5010 6273 +19695 5015 4639 6259 6617 +19696 4418 6081 4111 6661 +19697 1870 6375 1975 6577 +19698 2183 1947 1701 5905 +19699 4423 4196 4100 6622 +19700 2844 2838 2843 6885 +19701 4854 5944 4925 6394 +19702 3786 3280 6317 6947 +19703 5828 6320 4991 6526 +19704 4338 6178 6600 7092 +19705 2078 6559 1789 6800 +19706 518 4203 6081 6238 +19707 2171 6118 1873 6734 +19708 2465 2415 5854 6451 +19709 3384 3405 6367 6908 +19710 5970 6161 5168 6717 +19711 4367 4038 5788 6142 +19712 5748 5638 6879 6901 +19713 4250 4259 4075 6859 +19714 1742 6152 6151 6912 +19715 5929 3802 6830 7174 +19716 2717 2738 2954 6511 +19717 4787 5904 4605 6273 +19718 4373 6355 6032 6356 +19719 4042 4149 4421 5872 +19720 4613 6228 5029 6333 +19721 4951 4587 6214 6235 +19722 2816 6080 2402 6470 +19723 513 4429 6291 6349 +19724 1742 1984 2128 6151 +19725 6306 6307 4529 6592 +19726 5123 5347 5124 6899 +19727 4847 5971 5828 6937 +19728 4640 5801 4936 6651 +19729 4456 6349 6142 6714 +19730 2881 2882 2883 6486 +19731 4159 6132 4321 6193 +19732 526 6100 4243 6379 +19733 2910 2911 6166 7120 +19734 5251 4987 4882 7155 +19735 4086 5906 4282 6335 +19736 4882 5790 6074 6710 +19737 4060 6406 6271 7069 +19738 1984 6152 1781 6535 +19739 2183 5844 5905 6992 +19740 4471 4439 4179 6599 +19741 3082 6162 2391 6273 +19742 560 5830 561 6860 +19743 4631 5121 6005 6195 +19744 1757 2145 5848 6093 +19745 4338 6600 5760 7092 +19746 3468 6683 3281 6899 +19747 4042 4149 5872 6858 +19748 508 6119 6360 6822 +19749 4350 4473 5865 6532 +19750 3468 6023 6683 6899 +19751 1689 6019 1916 7153 +19752 4876 5219 5218 5957 +19753 3001 5881 6451 7152 +19754 4818 6036 4819 6678 +19755 5195 5194 6011 6752 +19756 495 4181 6000 6474 +19757 4159 4321 524 6193 +19758 4607 4601 4609 6411 +19759 3916 6877 6488 6900 +19760 3583 3437 3465 5787 +19761 4233 6450 6140 6995 +19762 3168 2425 3167 6039 +19763 5983 6393 2860 7124 +19764 2946 3277 2599 5921 +19765 4766 5811 5785 6515 +19766 5298 5252 6180 6513 +19767 461 6206 6337 6833 +19768 5258 6304 6182 7214 +19769 6107 6556 1947 7146 +19770 1833 6475 5989 6691 +19771 2258 6383 5992 7053 +19772 2968 5937 3166 6059 +19773 4799 6122 4797 6282 +19774 270 6323 1554 6667 +19775 5954 1646 6468 6740 +19776 1818 6663 6071 7177 +19777 3316 6074 3232 6276 +19778 251 6192 5836 7104 +19779 1746 1872 2116 7130 +19780 4627 4827 6351 6750 +19781 2996 6122 3034 6398 +19782 3281 6346 3331 6899 +19783 5127 6288 5253 6347 +19784 5975 5976 5943 7055 +19785 6198 273 6428 7212 +19786 270 271 1554 6323 +19787 3372 6004 6347 6652 +19788 3100 3176 3318 6372 +19789 2095 5885 1821 7092 +19790 4698 5239 4695 6374 +19791 1297 1491 1357 6572 +19792 2230 2228 348 6116 +19793 4807 4805 6789 7163 +19794 6827 6879 1291 6901 +19795 3191 6021 3193 6243 +19796 5629 6569 6903 6954 +19797 6570 6904 5471 6953 +19798 5845 6156 4293 6574 +19799 4458 4150 4422 5840 +19800 4565 613 5963 7073 +19801 2116 1872 1682 5853 +19802 2689 3543 2570 5893 +19803 5103 5823 5044 6937 +19804 6198 6359 4419 6884 +19805 1567 6442 6409 6993 +19806 3865 3802 5945 6830 +19807 4161 4330 4324 5967 +19808 2321 6285 6284 6518 +19809 1213 7011 1324 7111 +19810 3699 7009 3810 7112 +19811 2847 2802 6279 6484 +19812 455 6468 456 6633 +19813 1512 1369 1991 6111 +19814 4813 4881 5233 6158 +19815 2545 3145 5956 6199 +19816 4507 4492 4542 5924 +19817 5748 6827 5689 6901 +19818 29 6905 4538 7098 +19819 3376 6224 6289 7166 +19820 1451 1466 1291 6901 +19821 2521 3024 2444 5789 +19822 2462 5930 6229 7191 +19823 2373 5822 384 6401 +19824 2225 2223 2220 6479 +19825 5221 5332 5154 6426 +19826 424 3628 6445 6739 +19827 3804 6852 6631 6907 +19828 2252 6319 2250 6384 +19829 436 437 5894 6421 +19830 4223 6057 6029 7178 +19831 5392 6478 597 6754 +19832 2890 6095 2891 6096 +19833 526 6387 6294 6935 +19834 4679 6404 4581 6425 +19835 2755 2986 2642 6576 +19836 3893 2872 2871 6038 +19837 5374 6135 5426 6266 +19838 4257 4454 4121 5996 +19839 1707 6714 6349 7201 +19840 311 6290 2243 6625 +19841 5423 5374 5395 6241 +19842 5266 5270 4662 6106 +19843 1678 6167 6098 6685 +19844 5160 6172 5161 6275 +19845 629 5588 6620 6730 +19846 5746 6619 580 6729 +19847 3119 5828 3298 7179 +19848 1366 1255 1456 6824 +19849 5291 5175 5350 5786 +19850 4803 4867 5859 6214 +19851 4596 4972 5869 6109 +19852 2187 5848 1868 6859 +19853 5770 6210 3181 6591 +19854 2878 2580 6008 7127 +19855 2802 2804 6279 6484 +19856 4854 4875 6299 6394 +19857 3338 2942 3339 5831 +19858 3855 1992 3998 6126 +19859 2960 5775 2999 6695 +19860 5181 5317 5829 6813 +19861 2729 3830 2924 6009 +19862 3605 3641 223 6307 +19863 3291 3377 3378 6339 +19864 2966 2683 2967 6016 +19865 631 5820 6229 6716 +19866 4239 4015 5977 6836 +19867 3338 5831 2843 6434 +19868 3272 6427 6444 6668 +19869 5417 6040 5369 6200 +19870 6009 6976 2614 7073 +19871 3404 6182 3255 7055 +19872 4535 6169 5781 6233 +19873 3206 2464 5901 7206 +19874 350 2222 6209 6550 +19875 3546 3583 3465 5792 +19876 4938 5044 6257 6937 +19877 4257 5996 4465 7184 +19878 2477 2797 2602 5927 +19879 4841 4920 4968 6656 +19880 5913 6495 4930 6767 +19881 4433 6352 4134 6376 +19882 6087 2986 6424 6576 +19883 513 5417 514 6040 +19884 1877 1916 6153 7153 +19885 5506 460 5543 6924 +19886 2731 2730 3089 7021 +19887 3625 6255 3598 6308 +19888 5262 5129 5313 5972 +19889 1885 1711 2154 5974 +19890 2155 1884 1710 5973 +19891 1601 6202 1595 6422 +19892 2096 6441 6450 6995 +19893 6337 6806 5949 6833 +19894 4549 482 4509 6078 +19895 4019 4361 6186 6558 +19896 2298 6110 6052 6856 +19897 2883 6402 2794 6486 +19898 6145 6846 6329 7143 +19899 4493 4561 4536 7089 +19900 4232 6145 6144 7057 +19901 4085 6432 6120 6658 +19902 5884 6364 2935 6639 +19903 4489 4125 5763 6909 +19904 3369 3370 6343 6795 +19905 2444 5889 6523 7186 +19906 3645 6261 3623 6894 +19907 4260 5760 6532 7092 +19908 2376 6417 5809 6886 +19909 3278 6560 3229 6613 +19910 2761 3571 3113 5755 +19911 6101 6330 3521 6662 +19912 3424 6618 6012 7158 +19913 4514 470 6112 6546 +19914 2250 2251 2245 6452 +19915 4929 5913 4930 6767 +19916 6233 6575 3631 7083 +19917 4580 6404 4611 6448 +19918 2472 3090 2519 6454 +19919 1688 6271 1937 6312 +19920 5980 6053 3471 6300 +19921 5084 6275 5118 6393 +19922 5944 6028 2819 7068 +19923 479 6305 6423 6871 +19924 3311 6618 6345 6986 +19925 4702 4700 4701 6786 +19926 3663 6169 240 6653 +19927 2262 6331 336 6776 +19928 4437 6349 4456 6714 +19929 6234 6325 2314 7007 +19930 486 6464 485 6465 +19931 3071 5880 362 5881 +19932 1710 2049 1899 5851 +19933 1898 1711 2050 5852 +19934 4524 6160 4505 6520 +19935 5300 5127 6281 6288 +19936 3078 5864 7103 7198 +19937 2311 2301 6141 6309 +19938 2669 6297 2668 6332 +19939 5762 6248 2074 7024 +19940 5761 6250 2075 7025 +19941 5026 5911 4820 6502 +19942 5250 5315 4984 6158 +19943 4626 5366 4615 6345 +19944 4196 4052 4194 6980 +19945 4166 6144 6344 6493 +19946 490 5804 6485 6883 +19947 2767 2769 2770 6457 +19948 2490 6174 2491 6469 +19949 2968 3147 3189 6437 +19950 4437 4456 6142 6714 +19951 5533 6774 6529 7003 +19952 5691 6771 6528 7005 +19953 6463 6465 254 6574 +19954 2709 3125 2710 5766 +19955 6192 6348 1699 6918 +19956 6418 6568 477 7051 +19957 4043 5818 4447 5967 +19958 3580 3486 3381 6130 +19959 5858 6178 1857 6726 +19960 4441 6133 4133 6558 +19961 4316 6006 4078 6310 +19962 5895 6375 6066 6934 +19963 2108 5763 1832 7115 +19964 500 499 5933 6825 +19965 3116 3117 3503 5814 +19966 1704 1870 1975 6577 +19967 2192 1673 6460 7059 +19968 3603 6092 228 6260 +19969 464 465 6415 7212 +19970 3229 6069 3013 7103 +19971 5322 5772 5323 5907 +19972 3843 5922 1620 7082 +19973 4308 4403 6326 6942 +19974 4902 5007 4897 5824 +19975 3148 3337 3107 6670 +19976 2158 1652 2072 5838 +19977 5861 5914 4888 7088 +19978 3315 3428 5784 6724 +19979 1918 5885 6368 6859 +19980 4457 4263 6525 7141 +19981 5154 6426 6082 6427 +19982 4919 5051 4918 6104 +19983 2102 2033 1733 5764 +19984 3384 3515 6342 6908 +19985 370 2695 5825 6754 +19986 2371 2344 2296 6889 +19987 1756 6578 1904 6946 +19988 2280 6354 6379 6935 +19989 4168 4351 5891 6175 +19990 4565 5964 5963 7121 +19991 5248 5842 5264 6444 +19992 5168 4956 5970 6717 +19993 3254 3165 5937 5939 +19994 2597 6011 6438 6919 +19995 2948 2384 3548 5936 +19996 6203 6605 4083 7105 +19997 4664 6363 4653 7022 +19998 5151 5926 4686 7067 +19999 4359 4184 487 5836 +20000 1643 6310 1844 6616 +20001 4753 5062 5925 6046 +20002 5832 6037 5094 7021 +20003 3461 3492 6340 6353 +20004 5394 6200 5383 6628 +20005 5180 5348 5293 5839 +20006 3502 5993 3520 6507 +20007 5215 6004 6347 6747 +20008 5392 6135 6478 6754 +20009 306 1867 1838 6661 +20010 3229 6560 6008 6613 +20011 1285 1344 1488 6016 +20012 357 1422 1400 6519 +20013 3479 6049 3394 6298 +20014 5963 6412 5884 7075 +20015 3249 6050 2879 6966 +20016 1898 1778 2163 7171 +20017 1940 5932 1717 6206 +20018 5379 5404 6296 6679 +20019 4860 5046 4937 5956 +20020 4636 4635 4576 6108 +20021 4652 5842 5248 6591 +20022 5054 4940 4938 6257 +20023 5861 6552 3170 7019 +20024 1775 1849 2181 6615 +20025 1423 5933 1245 6278 +20026 5115 5171 5364 7197 +20027 2242 6435 344 6990 +20028 586 5422 6080 6321 +20029 4495 4514 6112 6546 +20030 375 3206 376 6268 +20031 2563 2718 6320 6963 +20032 2779 2732 5926 6700 +20033 2712 6128 2562 6749 +20034 5785 4979 6148 7029 +20035 499 6825 500 7070 +20036 2323 2374 352 5793 +20037 6058 6059 2968 6973 +20038 1611 6262 1614 6370 +20039 1554 271 1549 6323 +20040 3351 3353 3355 6300 +20041 1719 6461 2017 6622 +20042 4086 4153 5959 6249 +20043 4976 6455 6041 7149 +20044 2320 6171 5901 6679 +20045 1474 1224 1289 6860 +20046 4169 4207 5935 6315 +20047 466 6428 467 6545 +20048 4586 6447 6353 6448 +20049 5531 5480 5590 6735 +20050 1788 6624 2104 6912 +20051 4878 4879 4833 6504 +20052 5876 6864 5915 7122 +20053 4296 6132 4243 6800 +20054 5060 6122 6431 7101 +20055 2988 6059 3166 6815 +20056 4082 5967 4176 5977 +20057 4714 5867 5774 7160 +20058 2515 5981 2520 6366 +20059 4172 4024 4342 6635 +20060 5441 6704 5547 6959 +20061 5705 5599 6705 6960 +20062 4554 6255 6051 6650 +20063 2779 6472 2732 6700 +20064 6057 6559 1961 7178 +20065 5161 6172 5259 6424 +20066 25 5797 6383 6505 +20067 1682 6310 5853 6525 +20068 1825 6025 1669 6726 +20069 4306 478 6254 6597 +20070 372 3208 373 5897 +20071 3533 6031 2795 6697 +20072 4942 5978 5794 7211 +20073 5032 6106 4663 6447 +20074 5156 5022 5193 6239 +20075 4615 5321 5140 6466 +20076 1699 6192 2019 6348 +20077 3397 6281 6277 6753 +20078 6028 6688 2819 7045 +20079 2096 6450 1641 6995 +20080 5731 6954 5650 7114 +20081 5492 5573 6953 7113 +20082 3468 3331 6573 6899 +20083 2693 2698 5938 6754 +20084 4103 5994 4393 6501 +20085 3640 6307 224 6871 +20086 4247 6248 6335 6474 +20087 3639 3588 3613 6520 +20088 2352 338 6776 6854 +20089 3091 2710 3125 5766 +20090 3315 3313 3312 6245 +20091 6177 6380 2879 7016 +20092 3201 2620 2622 6163 +20093 6453 6458 1276 6694 +20094 6878 6984 564 7060 +20095 4422 5967 4161 6958 +20096 5825 597 6478 6754 +20097 4733 5969 557 7089 +20098 569 5766 5795 6482 +20099 1186 1311 6232 6694 +20100 2093 1980 1740 5756 +20101 630 5896 5820 6898 +20102 1491 1217 6572 6585 +20103 2717 3283 2737 6109 +20104 6548 6783 3983 6939 +20105 1497 6549 6780 6940 +20106 4673 4959 5302 5918 +20107 2340 5793 5754 6889 +20108 625 6240 6128 6608 +20109 4537 559 5768 6642 +20110 347 2228 2236 6119 +20111 1382 1993 1307 5900 +20112 4338 4439 4127 5760 +20113 2027 6139 1883 6556 +20114 5120 6208 5990 7027 +20115 1689 1916 1877 7153 +20116 2929 6267 2528 6514 +20117 4849 4625 5110 6050 +20118 470 6407 6408 6524 +20119 3049 6044 428 6160 +20120 5398 6045 588 6295 +20121 1878 1915 1690 6132 +20122 5002 6236 6217 7078 +20123 4270 4173 4483 5817 +20124 4979 5785 6148 6798 +20125 5821 4985 6496 7149 +20126 2608 3873 3753 6221 +20127 3428 6002 3427 6224 +20128 4574 6188 4587 6235 +20129 2827 3159 3158 6968 +20130 4861 4859 5801 6199 +20131 2879 6050 2880 7016 +20132 4794 4796 6246 6719 +20133 2041 1835 6167 6168 +20134 2732 6700 6060 7021 +20135 5144 6084 5142 6163 +20136 3373 5784 3429 6004 +20137 3363 6447 6106 6448 +20138 2568 2570 2573 5984 +20139 1488 1344 3035 6016 +20140 5162 5829 5317 6512 +20141 2298 6110 2350 6234 +20142 606 4735 607 6589 +20143 2360 5813 361 5881 +20144 4462 6144 4232 6145 +20145 1790 6033 6138 6988 +20146 4289 5996 4121 6230 +20147 1996 5808 2051 6386 +20148 3220 3117 3115 6158 +20149 4937 5956 5040 6651 +20150 4383 4185 6034 6256 +20151 4806 5864 4805 7163 +20152 4303 6205 6146 7032 +20153 2389 6099 2387 7186 +20154 1344 1285 1500 6016 +20155 5135 6181 4876 6183 +20156 4436 4164 4014 5788 +20157 2959 3274 3469 6217 +20158 5068 5765 4650 6849 +20159 3454 5792 6489 7084 +20160 5355 5186 5356 6899 +20161 2591 3156 2438 5856 +20162 2096 1641 5844 6995 +20163 4811 5167 5076 6161 +20164 2741 2855 2854 6364 +20165 5140 5936 5139 6466 +20166 2922 5963 5884 7075 +20167 2436 2435 6872 6945 +20168 5058 4793 5303 6799 +20169 4239 5977 4176 6836 +20170 5330 5114 5361 5902 +20171 1848 6432 6301 6658 +20172 2315 6184 6478 7063 +20173 3463 5873 3075 6590 +20174 5892 4696 6486 6657 +20175 2797 2957 6217 7078 +20176 3612 6682 3592 7080 +20177 4584 6340 4582 6404 +20178 6203 6396 1737 7091 +20179 5353 6212 5351 6921 +20180 4679 4611 6404 6426 +20181 5044 5823 4779 6099 +20182 2918 6472 5894 6515 +20183 5937 6059 4689 6815 +20184 5008 6070 5814 6646 +20185 1803 5853 6006 6950 +20186 5338 5772 5322 5903 +20187 4644 588 6045 6857 +20188 1696 6138 2013 6884 +20189 5173 5125 5965 6831 +20190 5108 5847 6155 6279 +20191 2313 2330 2300 6136 +20192 3085 3196 6257 6969 +20193 3739 6773 6562 6893 +20194 1253 6770 6561 6892 +20195 2480 5917 2478 6799 +20196 3214 3212 6179 6195 +20197 4697 6258 6402 6486 +20198 4352 4342 4084 5952 +20199 4362 4357 4094 5802 +20200 5370 6201 5394 6628 +20201 374 375 6268 6926 +20202 3865 5945 3802 7174 +20203 5926 6472 4686 7067 +20204 2407 6054 6526 7116 +20205 4962 4899 6150 6517 +20206 4251 4146 4413 6386 +20207 4596 6109 5869 6511 +20208 3329 6346 6336 6573 +20209 5988 6916 550 7039 +20210 470 6409 6408 6442 +20211 2522 6417 5775 6695 +20212 1199 6487 1342 6865 +20213 3685 6488 3828 6866 +20214 4929 5757 5134 5913 +20215 603 6325 5920 6617 +20216 3640 6307 6306 6592 +20217 1959 5877 1775 6138 +20218 4186 5994 6465 7087 +20219 611 6364 5884 6639 +20220 494 6867 6881 7209 +20221 3831 5754 3966 6889 +20222 3022 6036 2977 6502 +20223 2477 2476 6236 6799 +20224 2946 3242 2941 6517 +20225 1661 2086 1958 6018 +20226 5893 6617 6259 7035 +20227 6167 6322 4276 6917 +20228 5200 6276 6150 7155 +20229 4948 5778 4590 6361 +20230 533 6768 5924 7136 +20231 3308 6438 6086 6919 +20232 2106 1662 6176 6493 +20233 4637 6259 6617 7035 +20234 3550 6024 2702 6056 +20235 5850 2401 6855 7096 +20236 4590 4952 6398 6500 +20237 3439 5787 3437 6358 +20238 4279 6475 4477 7185 +20239 1905 2187 1687 6368 +20240 2544 6010 3319 6199 +20241 3401 6182 6180 6668 +20242 4608 5765 6129 6870 +20243 3812 6128 2712 6749 +20244 362 2360 361 5881 +20245 1701 1883 2046 6139 +20246 541 540 6421 6515 +20247 5895 6734 1783 7047 +20248 1585 1590 259 6194 +20249 2074 1941 6248 6474 +20250 5238 4694 5284 6159 +20251 325 5995 1258 6902 +20252 5200 5195 5201 6438 +20253 4510 4545 477 6308 +20254 4758 5774 561 6582 +20255 509 4158 508 6360 +20256 5140 5139 6084 6466 +20257 2510 5806 2947 6680 +20258 2523 5820 5896 6898 +20259 2069 5900 2174 6278 +20260 1979 5837 6118 6599 +20261 4993 5984 4975 7037 +20262 5009 5814 5315 6717 +20263 3330 6195 3332 6336 +20264 582 5805 5919 6499 +20265 5898 5962 4873 7204 +20266 3624 6190 5768 6642 +20267 2393 2416 2940 6717 +20268 6492 6716 630 6730 +20269 4695 6374 6258 6657 +20270 4724 4723 4731 6680 +20271 4056 4192 6079 6316 +20272 2565 2645 3157 5846 +20273 6471 6683 6023 6899 +20274 3705 3990 5753 6720 +20275 1397 6705 1409 6984 +20276 3895 3883 6704 6983 +20277 3130 2442 3073 6083 +20278 5121 6005 6195 6707 +20279 1717 6440 1801 6833 +20280 4697 4696 6258 6486 +20281 3176 3146 2641 5801 +20282 4230 6072 6460 6461 +20283 3573 6317 3566 6434 +20284 4950 5100 5978 6170 +20285 1905 5848 6368 7170 +20286 4061 4263 4316 6310 +20287 4243 6100 4072 6800 +20288 3285 6021 6102 6555 +20289 2386 2383 3447 6173 +20290 4672 4670 5047 5874 +20291 1642 6312 1813 6622 +20292 3051 3403 5957 6513 +20293 526 6294 6100 6935 +20294 2215 6318 6383 7053 +20295 3548 5936 3547 6466 +20296 5027 5021 5212 6358 +20297 2893 6095 6627 6742 +20298 5183 6212 6219 6921 +20299 4184 487 5836 6192 +20300 4341 4171 6203 6396 +20301 474 6093 475 6327 +20302 3534 6056 3526 6239 +20303 3273 3320 3179 6363 +20304 1922 5935 1725 6079 +20305 2753 2823 6258 6915 +20306 5210 5209 5208 5770 +20307 5122 6195 6179 6707 +20308 5839 6496 5293 6843 +20309 3688 7054 6736 7190 +20310 6206 6440 5932 6833 +20311 2402 6080 381 6470 +20312 4581 6224 4675 6425 +20313 4707 4709 4708 6143 +20314 5020 5799 6390 6711 +20315 3153 3147 2968 6437 +20316 2972 6047 5985 6400 +20317 565 6878 564 7060 +20318 2536 6213 2535 6214 +20319 3497 6074 5790 6710 +20320 4634 4630 5356 6573 +20321 2335 381 6115 6321 +20322 5815 6245 5133 6618 +20323 5079 4924 6109 6511 +20324 3884 6876 6009 7054 +20325 4379 451 450 6505 +20326 2466 2468 2935 5884 +20327 2387 5889 5888 7195 +20328 2554 6028 6945 7068 +20329 3248 2471 6050 6454 +20330 2756 2704 3006 5811 +20331 6454 6966 5931 7140 +20332 3291 3486 6130 6339 +20333 2567 6484 5847 6861 +20334 6041 6496 4985 7149 +20335 1708 1853 2042 7056 +20336 4262 4047 4478 6204 +20337 1986 1716 6278 6917 +20338 3621 5924 3650 6768 +20339 2834 2836 3368 6542 +20340 3647 3592 6014 7080 +20341 1790 6033 1959 6138 +20342 4958 5970 5199 6220 +20343 2327 2368 345 6435 +20344 2253 2254 6405 6834 +20345 6587 6619 579 6810 +20346 3204 6164 6282 7052 +20347 1968 1650 1904 6578 +20348 5274 5027 5787 6065 +20349 1357 2294 1297 6572 +20350 478 6568 6305 7051 +20351 2582 2584 2973 6824 +20352 5194 5189 6012 6752 +20353 3523 2893 3395 5961 +20354 3396 3496 3316 6074 +20355 6298 6314 5246 6842 +20356 3543 3017 2430 6259 +20357 4770 6215 6191 6792 +20358 1768 6271 1688 6524 +20359 4567 4570 6380 6761 +20360 466 5968 467 6428 +20361 2992 2972 2759 5985 +20362 467 5968 4245 6847 +20363 3311 6345 6618 7158 +20364 2973 1456 1326 5998 +20365 4708 6143 6231 6888 +20366 4590 4952 6361 6398 +20367 3357 6030 3343 6183 +20368 4058 5895 4217 6375 +20369 593 5418 592 6268 +20370 3565 6333 3287 6411 +20371 3655 3625 227 6092 +20372 2108 6909 5906 7122 +20373 4210 4078 4404 6310 +20374 4129 4398 4207 5838 +20375 6221 6509 3968 7110 +20376 4537 5768 6190 6642 +20377 1893 6410 6352 6677 +20378 5299 6507 5342 6842 +20379 2440 2439 2983 6013 +20380 3222 3117 3220 5849 +20381 3501 3500 6082 6748 +20382 6015 6351 4568 6761 +20383 6405 6776 338 6854 +20384 275 6756 5950 7082 +20385 3830 3951 2924 6009 +20386 2780 2671 5867 6170 +20387 2562 6608 2560 6749 +20388 6272 6336 6053 7043 +20389 4553 478 6306 6308 +20390 1672 2193 5840 6958 +20391 3403 3501 3051 5957 +20392 3837 4003 3741 6666 +20393 2495 2453 5969 6764 +20394 6238 6581 304 6834 +20395 4620 6039 6514 6763 +20396 529 528 6141 7034 +20397 4822 5870 4823 5892 +20398 5268 4658 5267 6228 +20399 4673 4670 4671 5918 +20400 457 456 5973 6790 +20401 496 5974 497 6791 +20402 4083 6187 4341 6203 +20403 3094 5990 5888 6709 +20404 4927 5345 5114 6047 +20405 5950 6359 26 6756 +20406 1774 2147 1960 6032 +20407 5485 5561 5459 6641 +20408 5643 5719 5617 6640 +20409 1380 6684 1319 6825 +20410 6210 6304 3185 6591 +20411 1304 6741 1384 6997 +20412 3505 3124 3083 5795 +20413 364 2314 6325 7007 +20414 3261 3241 2626 6361 +20415 480 6307 6306 6871 +20416 539 4766 5785 6515 +20417 4388 4393 5958 6501 +20418 5778 5981 4578 6500 +20419 2600 2598 6011 6276 +20420 1507 1258 1427 5995 +20421 4617 5140 6084 6466 +20422 5078 6374 4969 6692 +20423 3238 3237 3300 5870 +20424 3201 2948 6084 6647 +20425 5670 6596 5635 6770 +20426 5512 6595 5477 6773 +20427 4701 5985 5755 6786 +20428 3925 6562 3739 6773 +20429 1439 6561 1253 6770 +20430 2687 5862 5800 7000 +20431 3591 5796 3645 6894 +20432 4163 4332 4012 6376 +20433 2215 6383 6318 6566 +20434 5243 5242 4686 6472 +20435 2542 6340 6003 6630 +20436 5215 5216 5092 6747 +20437 3510 3508 2791 6330 +20438 3328 6351 6177 6750 +20439 5812 6450 5756 7100 +20440 1192 1389 6563 7070 +20441 4827 6177 6351 6750 +20442 3157 2565 5846 6861 +20443 4683 4684 5094 6700 +20444 2630 6338 6148 7161 +20445 456 6468 5973 6633 +20446 1707 6403 1924 6796 +20447 545 5337 5338 6650 +20448 602 5429 5384 7007 +20449 3677 6604 6521 6735 +20450 3476 5787 3475 6024 +20451 5366 6557 6063 6986 +20452 587 5425 5386 6321 +20453 2750 3555 5757 6767 +20454 6250 6301 1988 6369 +20455 1941 6335 6248 6474 +20456 4115 6144 4462 6193 +20457 3424 3432 5815 6245 +20458 4709 5799 4707 6936 +20459 6076 6377 4197 6588 +20460 1775 5877 2038 6615 +20461 2931 6394 5944 7068 +20462 3714 3820 3934 6736 +20463 4243 4305 4072 6100 +20464 2544 6010 6495 6767 +20465 6062 6364 5963 7121 +20466 382 6115 6080 6981 +20467 4894 5925 5062 6343 +20468 492 6249 6248 6467 +20469 3164 6274 5882 7008 +20470 5793 6889 6566 7038 +20471 2192 1673 1810 6460 +20472 454 6868 6895 7208 +20473 6364 6639 611 7145 +20474 3420 3149 3151 6708 +20475 2081 6132 1690 6344 +20476 4927 5114 5985 6047 +20477 5385 5392 5374 6136 +20478 539 538 5987 6798 +20479 2589 5917 6274 6968 +20480 3930 3730 6593 6783 +20481 1244 6594 1444 6780 +20482 2468 5884 2466 6887 +20483 5175 5786 5173 6708 +20484 3649 6121 3592 6421 +20485 5771 6280 5229 6970 +20486 4273 4146 4020 5808 +20487 2870 3230 5826 7077 +20488 4344 5877 4122 6544 +20489 4085 4391 4248 6658 +20490 1555 6362 236 6391 +20491 2836 3153 6058 6437 +20492 4714 5774 5867 6829 +20493 4510 478 4553 6308 +20494 4047 6203 6204 6605 +20495 4970 4845 4843 5784 +20496 2475 2451 2474 6088 +20497 2443 5896 2441 6816 +20498 3315 5784 3431 6245 +20499 3712 6570 3775 6953 +20500 1227 6569 1290 6954 +20501 1791 6501 1894 6918 +20502 5327 4681 4705 6103 +20503 5215 6347 5216 6747 +20504 2965 3128 5964 7073 +20505 5296 5288 5203 6399 +20506 4588 4951 5083 7125 +20507 307 5940 1867 6384 +20508 600 6266 5389 7154 +20509 4801 4951 4587 6214 +20510 2149 5788 1723 6796 +20511 5310 5779 4772 6392 +20512 1956 5950 6359 6806 +20513 2584 1366 1456 6824 +20514 1460 2991 3159 5835 +20515 5344 5258 6182 7214 +20516 4243 6379 6100 6800 +20517 3262 3328 2682 6380 +20518 2081 1795 1745 6817 +20519 2940 5970 3527 6220 +20520 2880 2879 3249 6050 +20521 3372 6347 6004 6747 +20522 4144 6355 6061 6624 +20523 488 6370 487 6419 +20524 1240 6766 1385 6956 +20525 5588 629 6620 6723 +20526 1963 1821 5885 6532 +20527 5847 6155 6504 7030 +20528 3615 6251 3595 6456 +20529 4923 5941 4847 5971 +20530 1431 1511 1260 6925 +20531 3678 3787 3900 6440 +20532 2302 6325 6285 6518 +20533 5779 6008 5859 7065 +20534 5859 2811 6608 7065 +20535 4118 4239 4447 5818 +20536 2004 6420 1734 7059 +20537 2928 3139 6267 7182 +20538 452 6301 6250 6369 +20539 4226 4063 4171 6671 +20540 4965 4872 4870 5759 +20541 2898 5986 5779 6560 +20542 5829 5162 6166 6512 +20543 1739 6230 2001 6975 +20544 2339 2296 2340 5754 +20545 5723 5595 6531 6610 +20546 5437 6530 5565 6611 +20547 2609 2724 2727 6221 +20548 2443 2529 5896 6898 +20549 3737 3830 3986 6009 +20550 2714 2608 3753 6221 +20551 367 6266 2353 6856 +20552 1987 6248 6249 6467 +20553 5187 5181 5261 5829 +20554 1353 6519 6416 7165 +20555 5459 6641 6785 6971 +20556 5617 6640 6782 6972 +20557 4657 6105 6659 6965 +20558 4134 4058 4216 6375 +20559 515 514 6201 6452 +20560 5858 6368 4026 7170 +20561 3609 3597 3610 5781 +20562 522 6329 6145 6846 +20563 2910 2909 2912 6512 +20564 5262 5972 6031 6813 +20565 5416 5372 5390 6478 +20566 3773 3980 6873 7009 +20567 1287 1494 6874 7011 +20568 2738 2926 2954 6511 +20569 4100 4196 4194 6071 +20570 525 6285 6284 6387 +20571 2879 6177 3328 6380 +20572 339 338 6184 6405 +20573 4780 6099 5888 6709 +20574 4706 4704 6103 7030 +20575 4909 5984 4974 6059 +20576 3596 6546 6112 6943 +20577 1736 1881 6341 6635 +20578 5290 5225 5274 5792 +20579 3448 5759 3290 5912 +20580 440 2571 5979 6338 +20581 2886 6173 2491 6174 +20582 4603 4602 6342 7194 +20583 3303 7065 5859 7127 +20584 1834 1761 5878 6838 +20585 4246 4186 5994 6465 +20586 2140 5845 1914 6156 +20587 562 6247 6088 6829 +20588 3224 3115 6158 7142 +20589 510 6068 6296 6443 +20590 5366 5359 6063 6557 +20591 4520 6307 6078 6520 +20592 3418 5909 3556 7084 +20593 4201 4364 6090 6516 +20594 5906 6909 5915 7122 +20595 2939 2881 2874 6486 +20596 2453 3024 2521 5805 +20597 2384 2383 2386 5936 +20598 1270 6684 5933 6685 +20599 3756 6686 5932 6687 +20600 5761 6250 454 6373 +20601 4582 6002 4581 6404 +20602 2305 6068 2312 6598 +20603 4697 6258 4918 6402 +20604 370 2325 6478 7063 +20605 5835 6491 1499 6897 +20606 5224 5225 5792 6489 +20607 2516 2520 2605 6366 +20608 2041 1773 2032 6490 +20609 4616 5144 5358 6163 +20610 593 5383 6200 6628 +20611 2171 1873 1783 6734 +20612 4617 4615 5140 6466 +20613 4351 4082 4220 5977 +20614 2259 6319 305 6834 +20615 5837 6118 4202 6734 +20616 1704 1808 1932 5818 +20617 2074 5762 1676 6474 +20618 3704 3966 3831 5754 +20619 330 2283 329 6284 +20620 2322 384 2373 5822 +20621 2309 2339 5793 6401 +20622 220 221 5948 6462 +20623 2877 6427 6426 6483 +20624 1636 1842 5915 6335 +20625 2174 1986 6278 6322 +20626 5940 6384 515 6661 +20627 528 6293 6141 7034 +20628 4220 5891 5977 6975 +20629 5286 5943 6210 7214 +20630 2622 6163 6345 7158 +20631 478 6305 6308 7051 +20632 4963 5921 4962 6438 +20633 5947 6090 5871 6858 +20634 3057 3535 3282 6005 +20635 6412 6736 5884 7075 +20636 4523 6123 5979 6999 +20637 4673 5918 5777 7078 +20638 3526 6056 2939 6910 +20639 2299 6266 6241 6856 +20640 5018 4974 5863 6815 +20641 5185 6218 5233 6745 +20642 5348 5187 5320 6300 +20643 5662 6655 5742 6705 +20644 5504 6654 5584 6704 +20645 2562 6128 6608 6749 +20646 1667 5958 1780 6076 +20647 625 6807 6641 7193 +20648 4644 6045 6470 6857 +20649 4809 5927 4810 6799 +20650 3408 6046 3528 6480 +20651 4501 4549 4509 6520 +20652 2004 1734 2003 7059 +20653 4573 6240 4587 7050 +20654 5046 5956 4935 6719 +20655 3192 3191 3193 6243 +20656 4236 4060 6271 7187 +20657 2240 6397 2238 6586 +20658 6308 6418 477 7051 +20659 247 1440 1991 5804 +20660 3386 3385 3390 5821 +20661 268 267 6407 6408 +20662 4232 4432 4068 7057 +20663 2173 6111 2068 6467 +20664 4230 6460 4363 6461 +20665 2267 335 6241 6439 +20666 3457 5943 3255 6182 +20667 4285 4089 6395 6601 +20668 2499 5875 1364 6848 +20669 6534 6676 5566 6760 +20670 5724 6533 6675 6759 +20671 4929 4930 4928 6767 +20672 514 5417 5394 6762 +20673 5939 368 6266 7154 +20674 3421 3409 3582 5815 +20675 4367 4167 4291 6796 +20676 4546 544 4521 6456 +20677 4046 4263 5807 5853 +20678 2533 6214 2534 7127 +20679 5308 5222 6137 6643 +20680 4308 6326 4403 6344 +20681 626 6221 6807 6957 +20682 1430 1241 6879 6901 +20683 515 4254 514 6690 +20684 4669 6086 6085 7103 +20685 5754 6401 6674 7038 +20686 5881 6982 6451 7152 +20687 6008 6213 4802 7127 +20688 5118 6393 6275 6744 +20689 5952 5853 6950 7185 +20690 3266 3407 5925 6046 +20691 545 5338 5903 6650 +20692 3553 2696 3555 5913 +20693 3000 6451 5866 7152 +20694 2216 6287 2291 6911 +20695 2566 3157 5956 6861 +20696 4751 4752 4892 5926 +20697 5952 6950 6283 7185 +20698 5480 6877 6735 6900 +20699 5120 5990 5033 7027 +20700 524 6193 523 6354 +20701 1556 6408 1560 6667 +20702 4078 4316 4142 6006 +20703 378 379 2333 6295 +20704 4882 6710 6074 7155 +20705 4845 4966 6557 6724 +20706 3398 5873 3399 6870 +20707 5349 4669 5301 6086 +20708 4630 6346 5356 6573 +20709 5674 5654 6540 6819 +20710 5516 5496 6538 6818 +20711 2740 6036 6035 6678 +20712 4862 6388 6976 6977 +20713 2063 1869 5816 6207 +20714 3479 6298 3436 6626 +20715 5796 6894 6022 7164 +20716 4117 4180 6114 6468 +20717 2411 2412 5887 6768 +20718 3604 3649 436 6121 +20719 1945 6055 6460 6461 +20720 2630 2631 6148 6338 +20721 3364 6448 6106 6483 +20722 434 3096 433 6832 +20723 1861 1675 2110 6113 +20724 4952 5086 5087 6361 +20725 5930 6229 32 6401 +20726 2865 6393 6174 7125 +20727 630 6693 5896 6898 +20728 2115 2046 6139 6778 +20729 5026 4820 6036 6502 +20730 5149 5288 6399 6662 +20731 4125 4343 4489 5763 +20732 614 6976 6009 7073 +20733 2461 2460 2523 6680 +20734 3163 2988 3165 6815 +20735 524 6157 5399 6285 +20736 4646 553 5013 6445 +20737 3494 6522 6965 7102 +20738 482 6422 481 6779 +20739 239 6169 3648 6698 +20740 6226 6326 1718 6673 +20741 2024 6449 6527 7079 +20742 3482 3371 3532 5832 +20743 4096 6395 4206 6600 +20744 5065 6130 6289 7167 +20745 4285 4112 4191 5816 +20746 2899 6212 3358 6219 +20747 5314 5259 5125 5776 +20748 1972 1647 5955 5999 +20749 1945 2091 6055 6461 +20750 4918 5078 4920 6104 +20751 5062 5275 6343 6795 +20752 3298 3119 2956 5828 +20753 3389 3453 3514 6263 +20754 508 5424 509 6068 +20755 3815 3718 6521 7093 +20756 2056 6073 1793 6377 +20757 543 6302 4503 6456 +20758 1612 6419 6370 6794 +20759 2627 6104 2628 6656 +20760 1651 1905 2048 6286 +20761 4137 4059 4363 6460 +20762 2596 3387 3315 6724 +20763 6458 1368 6694 6996 +20764 521 520 6439 7081 +20765 2201 6383 2215 6566 +20766 2776 2756 2732 5811 +20767 3114 6158 3116 6220 +20768 611 610 5827 6631 +20769 1919 1998 5871 5872 +20770 5359 6489 6063 6557 +20771 370 2354 369 6135 +20772 1727 2156 2063 5982 +20773 1705 1966 1965 6681 +20774 5213 4976 4977 6041 +20775 4897 5824 5997 6517 +20776 1182 6782 6640 6972 +20777 3668 6785 6641 6971 +20778 4726 4779 5012 5782 +20779 1551 6415 6428 7212 +20780 6002 6404 3360 7036 +20781 5272 5028 4661 6522 +20782 1980 1740 5756 6328 +20783 5001 6560 5864 6613 +20784 6150 6710 5997 7155 +20785 370 2325 2354 6478 +20786 3044 3244 3243 7020 +20787 1382 1297 291 5899 +20788 3421 3422 3348 6347 +20789 1538 1627 6324 6925 +20790 3426 5861 2832 7019 +20791 580 579 6587 6619 +20792 1883 2027 1631 6139 +20793 5808 6026 4222 6436 +20794 2385 3009 6075 6647 +20795 2152 1772 2040 5906 +20796 3122 3245 5931 6966 +20797 4577 4589 5981 6282 +20798 5213 4985 6041 6496 +20799 332 2279 331 6387 +20800 3527 6220 3274 6929 +20801 5940 6384 307 6690 +20802 5436 5368 5408 6309 +20803 4257 6429 5996 7184 +20804 5080 4783 6434 6885 +20805 5492 6548 5534 7113 +20806 5692 5650 6549 7114 +20807 5233 5234 5250 6218 +20808 5833 6320 4647 6916 +20809 5110 6050 5116 7016 +20810 3045 5997 3538 7020 +20811 2773 2401 6189 6855 +20812 1654 1976 5802 6537 +20813 3165 2512 5863 5939 +20814 4074 4209 4251 6386 +20815 2958 6683 6217 7078 +20816 5277 4812 4741 6102 +20817 4202 6118 5837 6599 +20818 4172 5952 4218 6341 +20819 3309 435 5894 6696 +20820 4778 5888 4780 6099 +20821 4613 5267 5029 6228 +20822 6482 6728 5795 6775 +20823 1248 1306 1446 5974 +20824 3734 3792 3932 5973 +20825 1674 6396 5876 6864 +20826 3642 6160 3613 6592 +20827 2629 6154 2901 6197 +20828 2001 1671 1906 6992 +20829 2583 2582 2590 6446 +20830 5782 6099 5823 7116 +20831 2518 2391 2525 6162 +20832 5397 6234 5429 6325 +20833 4123 6029 4325 6490 +20834 6632 6850 1318 7137 +20835 584 6115 5822 6981 +20836 5248 6304 5249 6591 +20837 5869 6044 4972 7039 +20838 5887 6246 4718 6755 +20839 4846 5971 4939 6937 +20840 1585 6194 260 6568 +20841 4879 6504 4704 7030 +20842 4531 4556 6362 6430 +20843 3102 5868 3020 6414 +20844 2944 2817 2816 6080 +20845 2700 3475 5786 6024 +20846 4390 4247 6335 6474 +20847 4232 7056 6145 7057 +20848 6318 6383 504 6566 +20849 6561 6770 5597 6892 +20850 5439 6562 6773 6893 +20851 2956 2954 2955 5828 +20852 2891 3210 3470 6767 +20853 4506 6894 6261 7164 +20854 4151 6057 4372 6527 +20855 6089 6712 1410 7060 +20856 1460 3159 1316 5835 +20857 3340 3329 2635 6336 +20858 4042 5872 5871 6858 +20859 1831 1944 6000 7074 +20860 2637 3068 5759 6590 +20861 5850 6189 579 6587 +20862 263 2145 264 6093 +20863 1372 1289 1224 6571 +20864 2504 2461 2523 5820 +20865 1563 6303 6442 6993 +20866 1847 2010 6249 6348 +20867 6298 6314 3436 6626 +20868 1834 1940 6838 7118 +20869 5907 6302 3097 6696 +20870 6214 6235 4587 7050 +20871 5353 5143 4634 6030 +20872 502 6997 6278 7079 +20873 5024 624 4771 5942 +20874 2483 2658 2824 6122 +20875 4862 4579 6039 6977 +20876 1655 1811 6064 6376 +20877 2407 2963 2956 6526 +20878 296 6379 6100 6935 +20879 3471 5980 3385 6367 +20880 4257 4135 6225 6429 +20881 602 5384 6052 7007 +20882 2430 6028 2431 7045 +20883 4070 4191 4472 5816 +20884 5756 6142 4215 6578 +20885 2131 6027 1929 6964 +20886 4096 4406 4206 6395 +20887 5877 5878 4327 6544 +20888 6189 6855 2401 7096 +20889 3753 6221 3873 6807 +20890 4577 5981 577 6473 +20891 4573 4587 6188 7050 +20892 1921 1722 2105 5951 +20893 4821 4819 4692 6678 +20894 6029 6057 1773 7178 +20895 2687 5862 7000 7093 +20896 4844 5815 4869 6652 +20897 366 5863 6052 7007 +20898 6190 6370 488 6794 +20899 6634 6867 495 7209 +20900 455 6633 6868 7208 +20901 3172 3511 2938 5778 +20902 6154 2403 6470 6914 +20903 3479 6049 6626 7001 +20904 503 5716 502 6766 +20905 5012 5782 6054 7150 +20906 616 6389 5916 6828 +20907 442 6020 5879 7076 +20908 584 4731 4723 5822 +20909 6078 6520 3641 7086 +20910 6531 7011 1286 7012 +20911 6530 7009 3772 7010 +20912 5586 5551 5444 7009 +20913 5602 5744 5709 7011 +20914 4037 6532 4350 6597 +20915 5937 5938 4690 6670 +20916 3324 6277 6276 6752 +20917 5062 6343 5925 6795 +20918 4354 4222 6026 6436 +20919 5978 6945 5794 7211 +20920 3681 6570 6674 6716 +20921 2067 2172 6126 6369 +20922 4428 4433 4131 6205 +20923 1804 1672 2002 6226 +20924 5820 6492 3709 6716 +20925 4765 5172 4976 6455 +20926 608 31 5854 6582 +20927 2947 2510 2945 5806 +20928 5847 6504 4879 7030 +20929 2601 3161 2416 6161 +20930 3277 6438 5921 7198 +20931 3359 6288 6091 6565 +20932 6278 6997 5900 7079 +20933 1357 1322 2293 6572 +20934 4191 4028 5982 6207 +20935 3371 5832 3482 6659 +20936 3632 5781 5753 6905 +20937 2376 2378 5809 6417 +20938 1486 6482 1370 6689 +20939 3483 6172 3143 6424 +20940 6309 6589 2319 6777 +20941 1847 6249 1758 6335 +20942 611 5884 5827 6639 +20943 368 2698 369 5938 +20944 3278 6613 3229 7103 +20945 6011 5301 6438 6919 +20946 3065 2976 3175 5868 +20947 3193 3284 3494 6021 +20948 2000 1631 6357 6601 +20949 2356 6309 5854 6589 +20950 6244 6556 4069 7183 +20951 3677 3972 6521 6604 +20952 6048 6571 5830 6582 +20953 5404 590 5432 5901 +20954 4959 6217 4958 6471 +20955 4086 4282 4390 6335 +20956 5933 6167 1942 6685 +20957 4068 6493 6176 7057 +20958 6533 6758 1333 6775 +20959 431 432 6650 6715 +20960 2144 1756 5940 6349 +20961 3200 6085 3201 6163 +20962 3450 3496 3396 6074 +20963 3563 5759 3068 6590 +20964 2244 6292 6452 7202 +20965 1748 2142 1829 5761 +20966 3066 2893 3064 6627 +20967 4244 4304 507 6061 +20968 2330 368 6135 6266 +20969 5952 6341 2125 7130 +20970 5195 6011 6276 6752 +20971 2618 357 1400 7107 +20972 467 4556 466 6165 +20973 4160 5872 4061 6310 +20974 359 5854 2356 6309 +20975 481 480 5991 6423 +20976 4766 4979 5785 7029 +20977 3336 5993 6554 7144 +20978 2483 2658 6122 7052 +20979 253 1607 252 6465 +20980 6128 6807 625 7193 +20981 5772 5907 3299 6480 +20982 1918 1839 5885 6859 +20983 5780 6246 4796 6719 +20984 2624 2996 6398 7101 +20985 1758 1987 6248 6335 +20986 4723 6623 5806 6680 +20987 3092 3093 5990 6361 +20988 6278 6322 1986 6917 +20989 3159 2828 1316 6491 +20990 5366 5145 5359 6557 +20991 4590 6361 5778 6500 +20992 512 6291 6290 6397 +20993 6205 6352 1683 7032 +20994 567 4866 4988 5931 +20995 3363 3321 6106 6447 +20996 2972 6047 6400 6621 +20997 4588 6393 6235 7125 +20998 1644 6344 6222 6817 +20999 4410 4014 4490 6328 +21000 2739 6101 3540 6662 +21001 4861 4858 4859 6010 +21002 2335 6115 2306 6334 +21003 4299 6090 4182 6328 +21004 1559 1566 6408 6442 +21005 6154 6656 2629 7042 +21006 5216 5253 5217 6091 +21007 4097 5769 4354 6026 +21008 2954 2956 2963 6320 +21009 4104 4334 4487 6356 +21010 5103 5043 5823 6526 +21011 1362 6984 6878 7060 +21012 5789 7181 5782 7186 +21013 5147 6477 6091 6565 +21014 2719 1326 1387 6125 +21015 1571 1576 6327 6365 +21016 5117 5160 5161 6275 +21017 5030 5983 4933 6393 +21018 3561 5773 3336 6554 +21019 2921 5800 5758 7077 +21020 2912 2909 2795 6512 +21021 4543 6421 5987 6682 +21022 3677 6603 6604 6735 +21023 6280 6281 3451 6507 +21024 2843 2838 2837 6434 +21025 1650 1925 1994 6142 +21026 5388 5390 5372 6184 +21027 1284 6543 1482 6810 +21028 1708 1853 7056 7057 +21029 4090 4383 6312 6961 +21030 3420 3546 3556 5792 +21031 4850 4702 6265 6378 +21032 4960 5112 5131 5908 +21033 2785 2681 2782 6015 +21034 4262 4062 4317 6027 +21035 3540 6101 3521 6662 +21036 2153 2039 1638 6432 +21037 578 6366 5850 6810 +21038 318 2258 319 6505 +21039 1477 6499 5919 6848 +21040 5921 6269 4898 6517 +21041 3494 6522 6343 6965 +21042 4686 6472 5926 6700 +21043 2867 6023 2899 6929 +21044 1640 2119 1857 6178 +21045 5043 6054 5823 6526 +21046 4165 6149 6019 7210 +21047 4867 6214 4587 6240 +21048 3631 3632 3597 5781 +21049 1698 6057 2179 6527 +21050 4505 6160 4530 6592 +21051 5145 6489 5359 6557 +21052 227 6092 3625 6308 +21053 1579 262 1581 6418 +21054 5948 6078 222 7086 +21055 1659 6206 1989 6833 +21056 5561 5459 6784 6785 +21057 5719 5617 6781 6782 +21058 3886 447 3743 5809 +21059 1330 6841 6780 7114 +21060 3816 6840 6783 7113 +21061 5901 377 6679 7206 +21062 2311 5767 2336 6309 +21063 2147 1833 1781 5989 +21064 5913 6095 3210 6742 +21065 3815 3893 2685 7093 +21066 1913 1876 6256 6961 +21067 1301 1192 6563 6825 +21068 3006 2749 2775 6060 +21069 1633 2129 1966 6026 +21070 5930 3963 6674 6716 +21071 455 5761 6633 7208 +21072 5762 6634 495 7209 +21073 5177 5923 5909 6708 +21074 2728 7073 2922 7075 +21075 620 6434 5081 6643 +21076 4588 4933 4574 6235 +21077 1862 1674 2111 6396 +21078 4813 4814 4881 5976 +21079 4873 5898 5152 7211 +21080 4882 4987 4884 5790 +21081 1607 1615 252 5836 +21082 4563 5964 6279 6977 +21083 4327 5878 5877 6615 +21084 4588 6235 6393 7124 +21085 3371 3369 3370 5925 +21086 4285 4191 4089 6601 +21087 4565 614 613 7073 +21088 6398 6431 6122 7101 +21089 2399 2773 2401 6189 +21090 3325 6228 3326 6333 +21091 2647 6177 5898 6750 +21092 5057 5093 5082 6469 +21093 5911 6051 431 6650 +21094 2545 6199 5956 6839 +21095 4455 6441 5844 6995 +21096 4986 6267 5791 6951 +21097 3978 6641 3668 6913 +21098 4589 6282 4797 6398 +21099 2497 6381 6380 6761 +21100 5226 5292 5348 5980 +21101 1849 2038 6206 6615 +21102 4866 566 6381 7128 +21103 4164 4367 4038 5788 +21104 3577 6181 3412 7138 +21105 3515 3386 3388 5821 +21106 2902 6208 3092 6969 +21107 3483 5965 3150 6172 +21108 2878 6008 3229 6560 +21109 3519 6431 2994 6823 +21110 5187 6567 5180 6813 +21111 3055 2910 2912 5829 +21112 2200 2198 2209 5798 +21113 4263 4479 4046 5807 +21114 4148 4044 4303 6410 +21115 2711 1329 5766 6869 +21116 5391 5418 5369 6268 +21117 610 6417 5827 6497 +21118 2650 2532 2531 6159 +21119 3077 5825 2695 6390 +21120 2247 6384 2245 6452 +21121 5753 6233 3631 7083 +21122 524 525 6354 6387 +21123 1824 2118 1738 6600 +21124 1637 2041 2032 6490 +21125 1270 1889 1814 6685 +21126 3756 1888 1815 6687 +21127 4571 4632 4900 6551 +21128 5257 5159 5048 6173 +21129 5767 6416 5995 6902 +21130 5386 5393 5373 6321 +21131 520 6579 6331 7081 +21132 5119 5164 4848 6697 +21133 2317 374 375 6268 +21134 25 5410 504 6566 +21135 5917 6481 5309 6799 +21136 2065 1732 6029 7178 +21137 4420 4396 4106 6348 +21138 5837 5838 4398 6599 +21139 3270 6304 6444 6591 +21140 2499 2578 2506 5875 +21141 1879 254 6465 6574 +21142 2678 6719 5956 6920 +21143 1707 1924 1925 6796 +21144 2434 6028 5794 6945 +21145 2594 6058 2968 6973 +21146 255 6463 254 6574 +21147 4859 4936 5801 6651 +21148 2398 5875 2530 7096 +21149 1718 2134 6226 6673 +21150 617 616 5916 6735 +21151 2388 2389 2387 7186 +21152 4703 4704 4931 6096 +21153 492 6467 6248 6629 +21154 1700 6025 1824 6395 +21155 3730 6593 6783 6785 +21156 6594 6780 1244 6782 +21157 484 4552 483 5948 +21158 4942 5794 6945 7211 +21159 2528 6267 6155 6514 +21160 2403 2787 6154 6470 +21161 1220 6766 1304 6997 +21162 6099 7181 5889 7186 +21163 3342 2899 6023 6212 +21164 1819 2101 1732 6186 +21165 5800 6388 2425 7000 +21166 6120 6607 1983 6691 +21167 223 6307 6078 6664 +21168 2535 6214 6213 7127 +21169 5356 6346 4630 6899 +21170 4778 5105 5888 7049 +21171 2402 381 380 6470 +21172 4605 4606 5010 6162 +21173 4674 6289 5064 6382 +21174 1707 6142 1968 6349 +21175 5968 6988 6428 7157 +21176 2918 2917 6472 6515 +21177 2102 5764 1681 6127 +21178 2233 6625 6397 6990 +21179 2746 2811 5942 6608 +21180 4171 4047 6203 6204 +21181 1757 1868 2187 5848 +21182 1980 1668 6107 6328 +21183 4611 4610 6448 6483 +21184 3198 2520 5981 6473 +21185 2336 6309 5767 6793 +21186 5504 5569 6654 6959 +21187 5727 6655 5662 6960 +21188 3307 3389 3388 6263 +21189 4728 6764 5789 7181 +21190 2022 1786 6356 6505 +21191 4270 4032 5905 6139 +21192 4093 5871 4182 6090 +21193 5308 5307 5986 6137 +21194 4308 4441 6222 6344 +21195 4725 6623 5896 6816 +21196 1642 2130 6071 7177 +21197 4926 4927 4925 6394 +21198 5881 5014 6982 7152 +21199 3612 6112 6682 7080 +21200 5308 5986 5310 6392 +21201 4647 6320 5833 6445 +21202 4608 5765 4650 6129 +21203 3415 3413 6227 6626 +21204 4225 4405 472 5946 +21205 5024 4867 624 6608 +21206 2095 1821 2118 5760 +21207 2901 2574 2821 6197 +21208 5624 6732 5734 6867 +21209 5466 6731 5576 6868 +21210 3674 6731 6702 6868 +21211 1188 6732 6703 6867 +21212 6167 1986 6322 6917 +21213 3421 3409 5815 6753 +21214 2239 2240 6586 7202 +21215 2470 1364 2499 5875 +21216 5413 6067 505 6318 +21217 573 6491 5835 6897 +21218 4113 6090 4299 6107 +21219 3232 6710 3347 7155 +21220 3006 6148 6372 7029 +21221 5837 1873 6118 6734 +21222 567 6498 5689 6827 +21223 6007 6117 3498 6612 +21224 4183 6198 6138 7157 +21225 3604 435 3652 6121 +21226 5331 5217 5147 6091 +21227 5006 5791 4987 5997 +21228 3853 6636 6369 6820 +21229 481 6078 6307 6664 +21230 4692 4691 4693 6042 +21231 3652 3615 3595 6456 +21232 4855 4857 4854 6028 +21233 6467 6629 1312 7024 +21234 5324 6390 5825 6962 +21235 5200 5232 6276 7155 +21236 1955 6505 1730 7026 +21237 509 6068 510 6443 +21238 2983 5857 6013 6371 +21239 1900 6225 2042 6350 +21240 1863 6349 6291 7201 +21241 4944 6367 5873 6908 +21242 3366 6426 6448 6483 +21243 5426 6266 6135 7154 +21244 1830 1677 2142 6373 +21245 4617 5144 4616 6084 +21246 5419 6628 595 6962 +21247 4632 4776 4777 6457 +21248 3465 3437 3439 5787 +21249 2862 2450 2936 6247 +21250 215 6190 6642 6794 +21251 2359 6284 329 6293 +21252 2206 5797 2207 6805 +21253 5287 5330 5361 5902 +21254 2974 6042 6043 6678 +21255 4400 4045 6072 6420 +21256 5260 4707 4739 6143 +21257 1894 5836 251 6192 +21258 4433 4131 6205 6376 +21259 2917 5811 2776 6472 +21260 4895 5963 6364 7121 +21261 6148 6338 4992 6798 +21262 1956 1731 2161 6806 +21263 3603 3655 228 6092 +21264 4415 4020 4209 6386 +21265 6564 6765 3706 7061 +21266 5316 5251 4899 7155 +21267 1500 6016 1398 6699 +21268 4790 4791 4712 5866 +21269 5701 5751 6563 7070 +21270 6086 7103 5864 7198 +21271 4165 6018 6149 7210 +21272 5809 6720 3964 6721 +21273 2897 3239 5779 7065 +21274 3044 3243 5997 7020 +21275 4647 5833 552 6445 +21276 4909 5984 6059 6688 +21277 3499 3493 3438 6358 +21278 4024 5966 6113 6635 +21279 4535 5781 4562 6938 +21280 4689 4688 6058 6437 +21281 2530 2521 2444 6523 +21282 5993 6554 5771 7135 +21283 3467 6129 3400 6411 +21284 3815 3879 3718 7093 +21285 6482 6602 569 6689 +21286 1651 1996 1928 6286 +21287 4657 6227 6105 6965 +21288 333 2350 334 6110 +21289 4774 4793 4773 5886 +21290 1830 2155 1943 6468 +21291 5922 5950 26 6756 +21292 3727 6735 3777 6877 +21293 5119 6697 4848 6737 +21294 3572 6502 3022 7139 +21295 1344 1465 2923 6844 +21296 1223 1335 1475 5875 +21297 461 6337 462 6833 +21298 5854 6309 359 6793 +21299 3282 3330 6336 6346 +21300 4654 5202 4614 6477 +21301 2578 5875 2499 6848 +21302 1630 6205 2137 6671 +21303 547 5284 4820 6159 +21304 4262 6027 4453 6605 +21305 2477 6481 2480 6799 +21306 5214 5293 6496 6843 +21307 3176 2631 3175 5801 +21308 3609 3610 3594 5924 +21309 2841 2708 6191 7128 +21310 2678 2566 5956 6719 +21311 2647 6177 2887 7204 +21312 350 349 6334 6550 +21313 3207 3208 3209 5897 +21314 6177 6378 2887 7204 +21315 5042 5101 5041 5857 +21316 5621 6458 6694 6996 +21317 4741 6035 5295 6102 +21318 2644 5846 6096 6839 +21319 2436 6872 5978 6945 +21320 3324 6277 6752 6753 +21321 1758 6249 1987 6335 +21322 1976 1871 1720 5947 +21323 5404 5432 5371 6171 +21324 5166 5209 5210 6400 +21325 4061 4457 4263 6525 +21326 2830 3164 5882 7008 +21327 3985 5929 3802 6830 +21328 4763 5272 5172 6243 +21329 521 6145 6350 6846 +21330 5904 6454 4604 6646 +21331 4680 4682 4681 6267 +21332 3026 6236 5777 7078 +21333 4250 6254 6134 6859 +21334 2096 1917 6140 6441 +21335 331 330 6284 6387 +21336 528 6510 6147 6718 +21337 3282 6195 3330 6346 +21338 4637 6617 5893 7035 +21339 538 5979 4548 6546 +21340 6284 6293 527 6294 +21341 4650 5765 5068 6339 +21342 3497 6280 3452 7144 +21343 4059 6460 4137 7015 +21344 6233 6503 5922 6575 +21345 5185 6219 6218 6745 +21346 5101 5041 5857 7106 +21347 1597 5845 256 6779 +21348 3188 6158 3114 6745 +21349 4215 4164 4038 6142 +21350 581 5875 5805 6499 +21351 3909 5932 3731 6440 +21352 4035 5959 4396 6501 +21353 5148 6402 6056 6486 +21354 5476 6803 6548 6922 +21355 5634 6804 6549 6923 +21356 466 6545 6165 6698 +21357 4274 4070 4239 5817 +21358 4523 6123 4519 6253 +21359 3837 3939 6807 7193 +21360 2875 6513 6427 6668 +21361 4820 5284 6036 6159 +21362 2280 2278 6354 6935 +21363 5890 1802 6410 7032 +21364 6563 6644 5701 7070 +21365 4569 4568 4567 6761 +21366 2449 5945 3865 7174 +21367 2820 5944 5908 6973 +21368 4625 6454 4891 6646 +21369 5930 6229 5820 6716 +21370 4299 4272 6107 6328 +21371 4885 4883 4884 5790 +21372 3427 6224 6002 7036 +21373 529 6141 6287 7034 +21374 466 5968 6428 7157 +21375 4526 4540 4508 6077 +21376 2821 6197 6017 7206 +21377 2040 5906 1772 5959 +21378 524 523 6157 6354 +21379 2280 6354 298 6379 +21380 2010 6348 5959 6918 +21381 5329 4701 5330 5755 +21382 4895 6364 4622 7121 +21383 5103 6526 5823 6937 +21384 5646 5619 7011 7111 +21385 5488 5461 7009 7112 +21386 5144 5142 5349 6163 +21387 5624 6703 6732 6867 +21388 5466 6702 6731 6868 +21389 517 6319 6081 6661 +21390 3917 3997 3746 6805 +21391 4683 5094 6037 7021 +21392 4894 4893 4892 5832 +21393 2434 2554 6028 6945 +21394 5377 5384 5396 6110 +21395 4830 6342 5821 6908 +21396 3228 5790 3227 6710 +21397 6161 6162 5168 6717 +21398 4586 4585 6353 6447 +21399 1836 6270 2105 6386 +21400 5075 5843 571 6665 +21401 5224 5350 5359 6489 +21402 519 6581 518 6776 +21403 564 563 6015 6089 +21404 3254 3189 3107 5937 +21405 3527 5970 3274 6220 +21406 586 6080 5011 6470 +21407 504 5992 4334 6505 +21408 3034 3204 3037 6282 +21409 5809 6721 6497 7098 +21410 5916 7000 5862 7093 +21411 5373 5382 6115 6334 +21412 506 5421 507 6209 +21413 4853 6155 5108 7030 +21414 618 617 6521 6735 +21415 2815 2813 3207 5870 +21416 4496 4545 4510 6092 +21417 1610 1602 1604 6463 +21418 4267 6118 5982 6734 +21419 3980 6774 3757 7009 +21420 1271 1494 6771 7011 +21421 4582 4836 4967 6340 +21422 515 5420 516 6201 +21423 1827 2183 1641 5844 +21424 4754 4755 6117 6447 +21425 2490 3507 2491 6174 +21426 5848 6134 1868 6859 +21427 4850 5110 5116 7016 +21428 2542 3362 2596 6003 +21429 1581 6134 263 6327 +21430 2250 6319 2257 6506 +21431 5301 6086 6438 6919 +21432 5315 6220 5199 6717 +21433 221 3659 220 5948 +21434 2514 5981 2515 6366 +21435 4286 4025 4190 6396 +21436 2790 6099 2390 7186 +21437 2947 2441 3023 5896 +21438 3660 5833 3628 6672 +21439 1370 6482 5766 6689 +21440 3738 6666 7013 7058 +21441 560 6571 6048 6582 +21442 2516 6366 2605 7162 +21443 5629 5658 6569 6954 +21444 5500 6570 5471 6953 +21445 5083 6393 4588 7125 +21446 5173 5174 5125 6831 +21447 2651 2788 6043 6678 +21448 5180 6567 5839 6813 +21449 1885 2084 1306 5974 +21450 1884 2085 3792 5973 +21451 4469 5858 4026 7170 +21452 3672 3797 6264 6751 +21453 4046 5853 5952 7185 +21454 2979 6246 5780 6920 +21455 2213 2211 2212 6572 +21456 4622 6364 6062 7121 +21457 3533 2786 2551 6697 +21458 2513 365 5920 7007 +21459 3361 6002 3360 7036 +21460 4371 5895 4058 6066 +21461 4672 5874 5035 7101 +21462 4631 5121 5123 6005 +21463 5849 6070 5814 7159 +21464 1561 6391 235 6409 +21465 3076 3293 3209 6390 +21466 3365 6353 6447 6448 +21467 452 451 6301 6369 +21468 4535 6233 5781 6938 +21469 6187 6223 4190 7091 +21470 358 6048 2382 6793 +21471 215 6642 1539 6794 +21472 3047 3243 3242 5997 +21473 467 4531 4556 6362 +21474 1809 1705 1810 6242 +21475 6496 6738 5214 6843 +21476 5085 5081 5831 6137 +21477 4060 5951 6406 7069 +21478 5258 6304 5248 6444 +21479 3276 6086 3308 7198 +21480 4144 6061 4304 6624 +21481 464 6415 6653 6756 +21482 464 4419 465 6359 +21483 6270 6271 1660 7069 +21484 3993 3808 3703 5922 +21485 2361 2327 344 6435 +21486 2407 3119 2409 6526 +21487 5275 5062 4740 6795 +21488 2950 2790 2390 7186 +21489 3410 6012 3324 6752 +21490 3586 3603 3615 6456 +21491 6138 6337 4154 6615 +21492 2356 5854 359 6589 +21493 452 6369 6250 6636 +21494 3297 3295 3487 6382 +21495 4061 4421 4457 6525 +21496 4697 6402 5148 6486 +21497 3163 2573 2988 5984 +21498 341 6452 2251 6506 +21499 1756 1968 1904 6578 +21500 5448 5584 6654 6704 +21501 5606 5742 6655 6705 +21502 1251 6016 1500 6699 +21503 2643 2848 2982 6504 +21504 4552 5948 484 6462 +21505 4953 5125 5155 6402 +21506 4732 5854 4711 6451 +21507 4550 549 4524 6160 +21508 4189 5966 5928 6547 +21509 3509 6496 5839 6738 +21510 2721 2793 3080 5971 +21511 1644 2016 6222 6326 +21512 6164 6282 4868 6473 +21513 4364 6516 4027 7072 +21514 3244 3230 3559 5824 +21515 3787 3678 3875 6564 +21516 1301 1192 1389 6563 +21517 2114 5890 2029 6614 +21518 607 6589 4735 6982 +21519 1351 5998 1255 6974 +21520 2876 3444 3443 6426 +21521 349 2230 6116 6209 +21522 1684 2029 5763 6614 +21523 3592 3604 3616 6121 +21524 4330 4176 4082 5967 +21525 5215 4869 6347 6652 +21526 4714 4782 4781 5867 +21527 2477 2476 2797 6236 +21528 2779 2732 2731 5926 +21529 3266 3408 3407 6046 +21530 3700 3765 3878 6801 +21531 1279 1392 1214 6802 +21532 1853 6145 6350 7056 +21533 6149 6151 4408 7153 +21534 4536 6077 4493 7089 +21535 1739 6975 2073 7176 +21536 1830 5973 2155 6468 +21537 4687 4910 4689 6059 +21538 1758 6248 1941 6335 +21539 4252 4031 6140 6441 +21540 4313 6032 6624 7132 +21541 1467 5882 1502 7008 +21542 4277 4154 6337 6615 +21543 1553 6323 1555 6391 +21544 3816 6783 6548 7113 +21545 1330 6780 6549 7114 +21546 6462 6463 484 6464 +21547 5031 6117 4755 6447 +21548 4705 6103 4704 6627 +21549 3580 3381 3382 6091 +21550 4823 4824 5279 5934 +21551 4516 5833 551 5988 +21552 5070 4967 4836 6003 +21553 610 4760 4759 5775 +21554 482 483 4509 5948 +21555 4837 6340 4584 6353 +21556 4323 4022 6196 6733 +21557 2217 6479 2224 7053 +21558 3605 3588 3641 6520 +21559 4025 4188 4482 6396 +21560 4248 454 6250 6373 +21561 3419 3149 5909 5923 +21562 5904 6215 4788 6792 +21563 4844 4869 5815 6837 +21564 5076 5843 5075 7168 +21565 3688 6412 6736 7054 +21566 6453 6458 558 7205 +21567 5114 5902 5985 6400 +21568 2114 6614 6146 7032 +21569 4084 6283 6113 6607 +21570 4356 5764 6127 6663 +21571 1372 5830 1224 7107 +21572 4293 6156 4091 6574 +21573 4119 4470 4469 5858 +21574 4073 4169 4298 5935 +21575 3003 6155 6039 6514 +21576 2391 3082 2392 6162 +21577 4359 5994 4103 6501 +21578 479 4394 480 5991 +21579 561 4758 4757 5774 +21580 5899 28 6287 6911 +21581 2277 6193 298 6354 +21582 3743 3908 447 3886 +21583 4361 6029 4200 6186 +21584 1895 6311 2020 6718 +21585 3630 3600 442 6430 +21586 5029 6333 6228 7194 +21587 4579 6279 6039 6977 +21588 3676 6736 6631 7190 +21589 4684 4892 5832 5926 +21590 5781 6233 5753 6938 +21591 5021 5023 6239 6612 +21592 2746 5942 2811 7065 +21593 2695 2698 2693 6754 +21594 5302 6471 6023 6899 +21595 522 521 6110 6439 +21596 5382 5411 584 6115 +21597 4821 4818 4819 6678 +21598 5370 6201 6628 6948 +21599 1811 6064 2193 6958 +21600 2128 6149 1689 6151 +21601 5788 4081 6196 6991 +21602 2135 2189 1869 5817 +21603 4675 6224 4597 7123 +21604 2606 2744 2719 5998 +21605 4091 4374 4384 6377 +21606 564 6878 5700 6984 +21607 511 6296 6435 6990 +21608 3069 3020 5879 6414 +21609 225 1586 6306 6871 +21610 4267 6118 4206 6395 +21611 3236 5892 2908 6657 +21612 2623 3261 2626 6361 +21613 1988 6369 6301 7026 +21614 2522 2457 6417 6695 +21615 382 2335 381 6115 +21616 1322 2213 2293 6572 +21617 3376 3429 6224 7166 +21618 471 472 6303 6442 +21619 4270 5816 4112 6139 +21620 5811 6060 4685 7029 +21621 5513 609 6631 6721 +21622 2988 3166 3165 6815 +21623 4752 4753 5062 5925 +21624 4186 6465 6211 7087 +21625 2900 6154 2629 7042 +21626 3999 3834 1801 6440 +21627 1257 6048 1478 7107 +21628 607 608 5414 5854 +21629 532 4541 533 5855 +21630 5149 5203 5288 6662 +21631 631 5577 5500 6570 +21632 5735 5658 582 6569 +21633 1380 1481 1319 6684 +21634 4242 4318 5844 6949 +21635 5336 6390 5897 6711 +21636 5492 5476 6548 6922 +21637 5650 5634 6549 6923 +21638 2207 319 2258 6383 +21639 5968 272 6428 6988 +21640 3334 3335 3333 5771 +21641 6019 6290 4231 7028 +21642 3578 3498 3568 6007 +21643 6211 6465 5994 7087 +21644 2972 3525 5985 6047 +21645 1847 5959 2010 6348 +21646 602 5920 5429 7007 +21647 4080 4286 4190 6223 +21648 4616 6345 5358 6618 +21649 5068 6339 5765 6849 +21650 468 467 5968 6323 +21651 5848 1905 6286 7170 +21652 2433 1377 2400 7096 +21653 2795 2909 6208 6512 +21654 1673 2133 6460 7059 +21655 3290 3292 5912 6339 +21656 5686 6701 6640 7014 +21657 1916 6019 6153 7153 +21658 4795 4718 5016 6414 +21659 575 6446 5998 6974 +21660 4770 6191 4988 6792 +21661 5834 6267 3136 7182 +21662 3588 3605 3613 6520 +21663 2624 6398 6131 7101 +21664 2357 6157 332 6285 +21665 3485 6007 3579 6910 +21666 2497 3247 6966 7128 +21667 1848 2012 6301 6356 +21668 28 5899 6287 6572 +21669 4777 628 6457 6693 +21670 5106 6039 4579 6279 +21671 521 520 6241 6439 +21672 3802 2449 3865 7174 +21673 460 5932 459 6838 +21674 3672 3797 3794 6264 +21675 5116 4874 6378 7204 +21676 5278 5294 5023 6612 +21677 570 6482 5795 6775 +21678 3020 2679 3069 5879 +21679 4323 4022 4167 6196 +21680 4516 4551 551 5833 +21681 2399 6189 2401 7096 +21682 6048 6571 1478 7107 +21683 6088 6933 6829 7117 +21684 1367 6629 6467 6787 +21685 6476 6585 1187 6741 +21686 1867 1838 6140 6946 +21687 2548 2926 2738 5941 +21688 5373 5422 6321 6334 +21689 220 1604 221 6462 +21690 2137 6671 6205 7032 +21691 350 6209 349 6550 +21692 3052 2647 2887 7204 +21693 6138 6198 4397 6884 +21694 1967 1928 1706 6494 +21695 2782 6351 2849 6750 +21696 1306 1462 1885 5974 +21697 1884 3792 3948 5973 +21698 2033 2038 5877 5878 +21699 5210 5770 5208 6210 +21700 3070 6246 2676 6536 +21701 5335 594 4824 6001 +21702 251 1894 2169 5836 +21703 1963 5865 1652 6532 +21704 5876 6146 1875 6614 +21705 4309 6311 527 6718 +21706 5297 5258 6513 6668 +21707 1677 1939 2075 6250 +21708 3778 2660 2715 6389 +21709 3803 6620 3894 6840 +21710 1317 6619 1408 6841 +21711 5025 6164 575 6446 +21712 5979 6546 5987 7048 +21713 627 6221 6124 6509 +21714 1979 6118 1824 6600 +21715 5539 6783 6548 6939 +21716 5697 6780 6549 6940 +21717 4144 6032 6355 6624 +21718 2582 6446 2583 6824 +21719 3567 5882 3164 6665 +21720 5047 5034 5035 5874 +21721 335 2351 6241 6856 +21722 519 6136 6331 6776 +21723 5070 6489 6003 6630 +21724 5303 5917 5309 6799 +21725 4839 4675 4597 7123 +21726 4407 4190 6187 7188 +21727 6019 6149 4165 7153 +21728 6181 6183 3412 7138 +21729 4644 6470 6154 6857 +21730 1296 6619 1448 6810 +21731 4019 6558 6186 6964 +21732 4024 6113 5966 7046 +21733 4937 6199 5956 6651 +21734 4448 6114 4180 6373 +21735 4573 6188 626 6240 +21736 5804 6324 27 6485 +21737 2683 2967 6015 6761 +21738 4890 5077 4973 6252 +21739 1316 1499 5835 6491 +21740 1942 1716 1986 6167 +21741 216 6370 6190 6794 +21742 4435 6537 4011 7015 +21743 4113 6556 6107 7146 +21744 3325 3326 3259 6333 +21745 4278 4247 493 6248 +21746 309 6291 1863 6690 +21747 3662 3635 1421 6809 +21748 3107 3189 3147 6437 +21749 1422 1257 1400 6519 +21750 560 5830 6571 6582 +21751 570 5074 5075 5795 +21752 4080 4256 5955 6223 +21753 4810 4957 5002 6217 +21754 6169 1545 6653 6698 +21755 1721 1870 2071 5895 +21756 6249 6467 492 6787 +21757 1817 1639 2033 6544 +21758 3308 6438 3277 7198 +21759 1901 5865 1776 6194 +21760 6169 6233 464 6653 +21761 4141 6406 4060 6494 +21762 2876 6426 2877 6427 +21763 5000 6069 5056 6613 +21764 6063 6557 3484 6986 +21765 2055 1741 6726 7033 +21766 5899 6449 5900 6741 +21767 4122 4488 4344 6544 +21768 6528 6791 5694 7005 +21769 5536 6529 6790 7003 +21770 4237 5954 456 6468 +21771 2410 2997 5887 6695 +21772 2306 2362 2334 6334 +21773 4990 5893 4638 5920 +21774 4135 6238 4253 6579 +21775 4898 6269 5921 7163 +21776 6323 6391 1553 6667 +21777 2931 3160 2820 5944 +21778 5043 4646 6054 6526 +21779 2936 2452 2706 6089 +21780 5295 6102 6035 6399 +21781 254 6463 1609 6465 +21782 6077 6190 3590 7062 +21783 2734 6399 6042 6678 +21784 2554 2553 6028 7068 +21785 609 4760 6417 7098 +21786 3566 3338 2843 6434 +21787 479 480 6306 6871 +21788 2985 2642 2986 6576 +21789 634 5436 635 5767 +21790 558 4561 559 5768 +21791 4755 5031 4754 6117 +21792 1887 5928 1693 7118 +21793 517 6506 516 6948 +21794 3436 6314 3413 6626 +21795 5149 6399 6042 6662 +21796 2563 6320 2784 6445 +21797 6095 6495 5913 6767 +21798 3424 6245 6618 6986 +21799 4695 6258 4696 6657 +21800 6006 6475 2028 6950 +21801 4238 4116 4464 6000 +21802 5164 6031 4848 6697 +21803 6497 6721 609 7098 +21804 1616 6262 217 6370 +21805 6114 6373 2058 6468 +21806 4946 4945 5910 7106 +21807 5184 6218 5185 6219 +21808 4582 4597 4581 6002 +21809 1890 6310 5872 6733 +21810 509 510 6153 6443 +21811 3228 3227 3538 6710 +21812 4927 5114 4699 5985 +21813 3737 6009 3884 6876 +21814 5295 5296 6102 6399 +21815 2061 5933 1942 6685 +21816 1940 2062 5932 6687 +21817 4570 6177 5116 6380 +21818 4255 6097 5954 6547 +21819 4910 6058 4687 7109 +21820 4897 5006 5316 5997 +21821 1807 1983 6607 6691 +21822 4491 5885 6532 6597 +21823 6233 6575 5922 6653 +21824 4772 5310 5304 5779 +21825 4737 584 4723 5806 +21826 6294 6387 2281 6935 +21827 5992 6383 6318 7053 +21828 5861 4888 6437 7088 +21829 272 271 5968 6428 +21830 4243 6132 4159 6379 +21831 4778 4785 5105 7049 +21832 437 3607 5987 6421 +21833 372 6185 2348 7063 +21834 1703 5885 6254 6597 +21835 2311 326 2345 6902 +21836 4364 5947 4093 6090 +21837 594 6001 5897 6628 +21838 5998 6125 576 7014 +21839 5779 4772 6392 6835 +21840 1721 2008 6375 6934 +21841 4089 5982 4267 6118 +21842 5419 6185 6628 6962 +21843 3315 3387 3428 6724 +21844 2263 6579 302 7081 +21845 568 6191 5766 6498 +21846 5833 6313 3628 6672 +21847 1229 1377 5850 7096 +21848 4013 6357 4285 6395 +21849 470 6408 4385 6524 +21850 3463 3067 3405 6590 +21851 562 563 6088 6247 +21852 3020 3065 2680 6338 +21853 378 6295 2365 6679 +21854 2739 3569 6102 6399 +21855 3521 6101 3522 6738 +21856 2063 2156 1648 6207 +21857 2144 5940 307 6690 +21858 3790 6765 6862 6863 +21859 2223 6061 315 6822 +21860 3126 3094 5888 6709 +21861 4119 4470 5858 6436 +21862 2031 1807 1983 6607 +21863 2810 2809 2984 5942 +21864 1866 6352 6376 6934 +21865 6403 6714 1707 7201 +21866 4961 4962 4963 5921 +21867 2778 6274 5917 6481 +21868 3107 3147 3148 6437 +21869 2627 6656 6197 6915 +21870 2712 2562 2559 6749 +21871 4991 4997 6320 6511 +21872 1914 1879 6211 6574 +21873 3826 6877 6704 6959 +21874 1340 6879 6705 6960 +21875 229 6251 3603 6260 +21876 5202 6129 4649 6130 +21877 4347 4074 6270 6461 +21878 2089 6079 1709 6316 +21879 1697 6355 2022 6356 +21880 6305 6306 478 6308 +21881 2389 2790 2459 6099 +21882 4895 5963 612 6364 +21883 2237 6153 6625 7180 +21884 4867 6240 625 6608 +21885 1791 1962 1667 5958 +21886 5549 5566 6676 6760 +21887 5724 6675 5707 6759 +21888 5831 6434 4783 6885 +21889 4248 453 4275 6250 +21890 4451 4056 6315 6316 +21891 2643 2982 2644 6096 +21892 4482 4188 4417 5876 +21893 5051 5125 4953 5776 +21894 2749 6060 3006 6372 +21895 471 6112 6409 6993 +21896 617 5862 618 6521 +21897 5254 6513 5258 6668 +21898 5149 4693 5157 6042 +21899 3737 3951 3830 6009 +21900 5322 5907 4816 6832 +21901 5062 6046 4740 6795 +21902 1262 1351 6974 7014 +21903 2284 6100 295 6718 +21904 301 6350 6145 6846 +21905 4620 4618 6039 6763 +21906 1848 6301 1759 6658 +21907 546 6051 5911 6650 +21908 4195 4139 6076 7099 +21909 378 2365 377 6679 +21910 5805 5875 581 6523 +21911 4732 6451 4715 6582 +21912 2393 2940 3527 6220 +21913 4274 4118 4311 6207 +21914 462 6440 5949 7061 +21915 6026 6436 5808 7033 +21916 5300 5130 5299 6507 +21917 3009 3007 6069 6647 +21918 4095 4394 4271 5865 +21919 6203 6204 1860 6671 +21920 1516 6637 6541 6746 +21921 4932 5962 4875 6394 +21922 1216 1321 1506 5803 +21923 1286 6531 1324 7011 +21924 3772 6530 3810 7009 +21925 1812 6326 1644 6344 +21926 3000 3001 6451 7152 +21927 2681 6351 6015 6761 +21928 614 6412 613 7073 +21929 2504 2576 5820 6998 +21930 1628 5922 6575 6653 +21931 2632 6148 2704 7161 +21932 3738 7013 5929 7058 +21933 2988 5984 2989 6059 +21934 2016 1718 2134 6326 +21935 3003 3194 6039 6279 +21936 3269 6444 5842 6591 +21937 4271 5865 6194 6597 +21938 606 607 5402 6589 +21939 6251 6260 229 6365 +21940 2786 6433 2551 6697 +21941 214 1539 6642 7017 +21942 2441 5896 2947 6816 +21943 4051 6168 4315 6223 +21944 6380 6381 4567 6761 +21945 1762 1949 2027 6357 +21946 5907 6480 5323 7067 +21947 251 250 6192 7104 +21948 3063 5986 5864 6789 +21949 4797 6122 5060 6398 +21950 5820 6998 2576 7191 +21951 3284 6343 6021 6795 +21952 4206 6118 4267 6600 +21953 4094 5802 4357 6858 +21954 3271 3473 6444 6483 +21955 4448 4180 4391 6373 +21956 5416 5825 6478 6962 +21957 1919 1632 2149 6196 +21958 2938 6108 2762 7064 +21959 522 6439 6329 6846 +21960 609 6497 610 6631 +21961 2998 5887 3070 6414 +21962 1357 1491 1217 6572 +21963 1964 6429 5996 6906 +21964 5111 4954 5113 7088 +21965 3563 2637 3068 5759 +21966 5970 5199 6220 6717 +21967 3599 6313 3628 6739 +21968 5077 6552 4890 6936 +21969 5108 5847 4879 7030 +21970 5072 5226 5146 6367 +21971 4625 6454 4604 7140 +21972 2096 1641 2117 5844 +21973 2655 2653 6037 6105 +21974 1334 6712 6088 6860 +21975 4806 5001 4805 5864 +21976 4497 4530 4554 6051 +21977 2058 6114 1713 6373 +21978 1664 1969 2064 6385 +21979 1631 2115 2046 6139 +21980 6271 6312 4377 7187 +21981 1517 1326 1456 5998 +21982 2195 5995 326 6287 +21983 2498 6381 2683 6844 +21984 1383 6675 6533 6759 +21985 3869 6676 6534 6760 +21986 5235 5185 5236 6508 +21987 4600 5007 4599 5824 +21988 452 453 6250 6301 +21989 6248 6629 6467 7024 +21990 2681 6015 2967 6761 +21991 1970 2100 1819 6558 +21992 2453 2494 2495 5969 +21993 2528 2526 6155 6267 +21994 525 6379 6354 6387 +21995 3592 3649 3604 6121 +21996 4685 6060 5811 6700 +21997 4148 4399 4044 6410 +21998 3252 2779 5926 6472 +21999 3394 3393 6298 6554 +22000 2370 2312 2305 6068 +22001 221 1598 222 6202 +22002 3149 3150 3151 6708 +22003 2562 2713 2560 6608 +22004 2600 2598 2597 6011 +22005 3738 5929 3985 7058 +22006 4852 4620 5107 6951 +22007 2339 5754 6401 7044 +22008 4222 4020 4415 6026 +22009 2319 6309 2356 6589 +22010 2627 2753 6104 6915 +22011 2095 2118 1640 6178 +22012 4900 4777 628 6457 +22013 3533 2912 2795 6031 +22014 352 5793 2374 6566 +22015 6257 6709 5990 6969 +22016 5780 6246 6719 6920 +22017 3689 3781 3897 6509 +22018 3731 5932 3866 6440 +22019 1551 6415 1544 6428 +22020 6065 6340 3461 6630 +22021 563 562 6088 6712 +22022 4130 4331 5953 6669 +22023 2370 6068 2305 6598 +22024 4898 6269 4902 6517 +22025 2843 3338 3339 5831 +22026 2941 2943 5921 6269 +22027 3613 3605 3589 6592 +22028 4970 4843 4903 5784 +22029 5957 6748 5912 7138 +22030 1362 1266 1398 6878 +22031 1587 6568 6418 7051 +22032 1723 1994 1925 6796 +22033 3360 6340 3491 6404 +22034 1592 6422 1593 6423 +22035 5927 4809 6481 6799 +22036 5897 6628 6185 6962 +22037 566 6413 6381 7128 +22038 4375 4087 4241 6167 +22039 471 6409 6442 6993 +22040 3575 5914 2834 6542 +22041 4162 5807 4263 7141 +22042 2872 3280 3573 6317 +22043 5881 6589 6451 6982 +22044 526 525 6284 6387 +22045 1810 1976 2132 6242 +22046 3272 6444 6304 6668 +22047 3290 3448 3449 5759 +22048 582 6499 5919 7205 +22049 3449 3075 3464 5765 +22050 3022 6502 3043 7139 +22051 250 6419 249 7172 +22052 1486 1237 1370 6482 +22053 5104 6083 5983 6606 +22054 2983 6013 2945 6371 +22055 5346 5913 5134 6553 +22056 1819 1929 6186 6964 +22057 2089 6156 1957 6315 +22058 4188 4025 4286 6396 +22059 4372 6527 6311 7018 +22060 5405 5406 5376 6518 +22061 4864 580 6189 6523 +22062 618 5518 617 6735 +22063 2302 2358 6325 6518 +22064 5005 4810 6236 6799 +22065 1344 2923 6016 6844 +22066 5305 6618 6245 6986 +22067 1734 2004 1859 6420 +22068 4474 6532 5838 7095 +22069 6348 6485 4333 7172 +22070 3142 2986 2755 6424 +22071 5204 6298 6049 6626 +22072 3235 6814 3206 6926 +22073 624 6128 5942 6608 +22074 527 6100 6294 6718 +22075 1582 1574 1576 6327 +22076 4408 4040 4297 6151 +22077 3334 3336 3335 5771 +22078 5242 5241 4686 6472 +22079 6366 6543 5850 6810 +22080 4786 4864 6189 6523 +22081 2008 1721 1999 6934 +22082 1612 1611 1614 6370 +22083 466 465 6428 6698 +22084 5850 6855 6189 7096 +22085 464 6359 6415 6756 +22086 4283 4375 6168 6490 +22087 461 462 6440 6833 +22088 4726 5782 5012 7150 +22089 4958 5199 5197 6220 +22090 5086 6131 5087 6361 +22091 1904 6578 6450 6946 +22092 4147 6420 4400 6663 +22093 469 470 4547 6409 +22094 1845 1645 1802 6410 +22095 3836 3932 1829 5761 +22096 1350 1446 1828 5762 +22097 2558 5962 6378 6786 +22098 630 6492 5820 6716 +22099 5929 6666 6835 7058 +22100 1706 1977 1864 6494 +22101 4126 4451 4258 6316 +22102 4989 4968 4995 6197 +22103 3206 2464 376 5901 +22104 3934 6631 3676 6736 +22105 4392 6033 4138 6385 +22106 493 6248 492 6249 +22107 3867 6959 6654 7134 +22108 1381 6960 6655 7133 +22109 4877 4815 4676 5849 +22110 529 6449 4336 7018 +22111 3051 6427 2875 6513 +22112 2801 2687 5800 7000 +22113 632 32 6401 6674 +22114 472 6014 4512 6682 +22115 513 514 4429 6349 +22116 3608 5796 3614 7062 +22117 6197 6692 6017 7206 +22118 2363 6268 6171 7151 +22119 3881 5916 3778 6389 +22120 5361 5902 5114 6400 +22121 3096 434 3097 5907 +22122 3350 6281 6288 6507 +22123 2007 1976 1720 5802 +22124 1215 1517 1351 7014 +22125 3556 3418 3420 5909 +22126 5260 4739 5256 6007 +22127 3256 3404 3255 7055 +22128 4150 5840 4012 6064 +22129 552 5833 4647 6916 +22130 6025 6436 5769 6726 +22131 3709 6492 5820 6998 +22132 1907 6061 2167 6912 +22133 1436 1285 3035 6089 +22134 4708 4739 6143 6888 +22135 3574 6129 3467 6477 +22136 3548 2621 6084 6466 +22137 4269 6176 4068 6493 +22138 4866 5931 4583 7140 +22139 2931 5944 2932 7068 +22140 4796 4717 6246 6755 +22141 2631 2630 3065 6338 +22142 3143 3152 6087 6275 +22143 304 6081 1952 7006 +22144 1569 266 1564 5946 +22145 1910 2169 1791 5994 +22146 3342 6212 6023 6573 +22147 4847 4939 5971 6937 +22148 4422 4161 6226 6958 +22149 2307 6201 6200 6762 +22150 5235 5185 6508 6845 +22151 3925 3774 6595 6873 +22152 1288 6596 1439 6874 +22153 4395 6286 4054 6494 +22154 2431 2430 2434 6028 +22155 4296 4243 4072 6800 +22156 3369 6659 3482 6965 +22157 3662 1421 1346 6809 +22158 1697 6032 6355 6356 +22159 4786 6189 5889 6523 +22160 5919 6499 1477 7205 +22161 3146 3175 2976 5801 +22162 4253 6238 4135 6429 +22163 4625 4604 6454 6646 +22164 619 6317 6038 6434 +22165 5156 5196 5022 6024 +22166 1784 6348 2019 6485 +22167 1538 6324 1525 6794 +22168 3563 3449 3448 5759 +22169 3066 5773 2893 6627 +22170 3076 2695 2694 6390 +22171 2109 5895 1783 7047 +22172 3565 3514 3453 6333 +22173 5305 6557 5366 6986 +22174 4613 4614 6332 6333 +22175 2410 2999 2997 6695 +22176 4334 504 4487 5992 +22177 5195 5191 5194 6752 +22178 3787 6564 3706 7061 +22179 1818 1930 6663 7177 +22180 4168 5891 4039 6176 +22181 4148 4303 6146 7032 +22182 1598 221 1604 6202 +22183 3865 3698 3802 6830 +22184 5136 6180 6181 6845 +22185 3301 5938 368 7154 +22186 3675 6723 6620 6730 +22187 3794 6264 5798 7169 +22188 2035 6018 1792 6733 +22189 571 6758 6533 6775 +22190 2471 3123 2557 6070 +22191 2296 2340 5754 6889 +22192 1290 1523 1371 6569 +22193 501 6825 6563 7070 +22194 5844 6949 4318 6995 +22195 2571 5979 6338 7161 +22196 6007 6143 3579 6713 +22197 6218 6219 3187 6745 +22198 4199 6607 4281 6691 +22199 5253 6288 5255 6565 +22200 6277 6281 5128 6753 +22201 2317 2366 374 6200 +22202 3549 6011 2597 6919 +22203 4166 6144 4115 6344 +22204 2929 3139 2528 6267 +22205 6623 6680 5896 6816 +22206 5984 6688 4909 7037 +22207 4753 4752 4751 6480 +22208 1684 5763 2108 6614 +22209 4519 6123 4504 6253 +22210 4965 4870 4906 5759 +22211 302 6579 6350 7081 +22212 5693 5595 6610 6890 +22213 5437 6611 5535 6891 +22214 1698 6311 6057 6527 +22215 4674 6382 5089 6425 +22216 2992 5902 3184 6210 +22217 27 6485 6324 7172 +22218 454 455 5761 6373 +22219 5154 6427 6082 6513 +22220 1365 6675 1383 6759 +22221 3869 3851 6676 6760 +22222 1617 6324 249 6419 +22223 2284 296 6100 6935 +22224 5032 6447 4586 6448 +22225 1700 6357 6025 6395 +22226 4219 6204 4171 6671 +22227 5060 6398 6122 7101 +22228 2713 6240 3104 6608 +22229 4348 4128 4354 5769 +22230 1237 5766 1370 6482 +22231 4930 5346 5115 6095 +22232 3491 6340 3492 6353 +22233 5248 5249 5208 6591 +22234 3428 3429 5784 6224 +22235 4074 4363 6055 6461 +22236 4190 4025 4341 6396 +22237 3359 3380 6091 6288 +22238 3551 3256 3108 7142 +22239 4167 6018 4268 7210 +22240 241 6575 6233 6653 +22241 2453 2494 5969 6927 +22242 5900 6741 502 6997 +22243 4275 6432 4085 6658 +22244 3602 3657 440 5979 +22245 2298 6052 6234 7007 +22246 5865 6532 4473 7095 +22247 4899 5316 5997 6517 +22248 4439 5760 4338 6600 +22249 5697 5672 6780 6940 +22250 5539 5514 6783 6939 +22251 6058 6437 4688 7088 +22252 5951 6406 1706 6494 +22253 3786 2872 3893 6038 +22254 2942 3056 5831 6269 +22255 4109 4356 4229 6127 +22256 4378 6348 6249 7156 +22257 5461 7009 6530 7010 +22258 5619 7011 6531 7012 +22259 1936 1717 1888 5932 +22260 1935 1716 1889 5933 +22261 4027 4337 5960 6516 +22262 556 6077 5783 6967 +22263 4704 4880 4931 6096 +22264 5929 6666 5942 6835 +22265 1584 1590 6305 6423 +22266 3219 2646 2648 5898 +22267 4786 5889 4864 6523 +22268 2803 3128 2804 5964 +22269 3434 3435 3393 6298 +22270 5379 5400 6295 6296 +22271 4714 4757 5774 6829 +22272 5888 6099 5889 7186 +22273 1821 1963 2158 6532 +22274 1396 6703 1401 6867 +22275 3887 3882 6702 6868 +22276 3549 6011 6919 7158 +22277 2039 6120 6432 6658 +22278 291 2159 1993 5899 +22279 4320 4158 509 6153 +22280 4729 4728 4733 5789 +22281 1788 2167 1896 6355 +22282 3629 6362 3600 6430 +22283 5922 6653 1534 6756 +22284 2401 2433 2400 7096 +22285 3162 6047 2931 6394 +22286 6185 6628 6201 6948 +22287 519 6331 6581 6776 +22288 1956 5950 275 6359 +22289 5309 5843 5167 6481 +22290 5949 6440 3694 7061 +22291 5972 6031 2550 6433 +22292 6146 6671 2137 7032 +22293 249 2019 250 7172 +22294 2458 2459 6257 6709 +22295 4279 4016 4477 6475 +22296 475 6260 6251 6365 +22297 1579 261 6418 6568 +22298 4274 4191 4070 5816 +22299 4914 6060 6372 7029 +22300 6302 6456 543 6832 +22301 4099 4242 4318 5844 +22302 1396 1230 1401 6703 +22303 3882 3716 3887 6702 +22304 527 6293 6284 7066 +22305 3440 6358 6239 6612 +22306 3746 3997 3797 5797 +22307 1790 1908 6033 6988 +22308 2384 2385 2383 6647 +22309 2036 1718 6326 6673 +22310 1589 1592 6423 6664 +22311 358 2382 2485 6793 +22312 1807 6607 6283 6691 +22313 3121 1435 2433 5850 +22314 331 2357 332 6285 +22315 2340 2374 5793 6566 +22316 534 535 5016 6020 +22317 4837 4585 4756 6353 +22318 450 6505 6126 6882 +22319 5701 6563 5633 6644 +22320 5543 6564 5475 6645 +22321 1571 6094 1573 6365 +22322 4320 4158 6153 7153 +22323 614 6412 6009 7054 +22324 529 28 4336 6449 +22325 1813 1660 2037 6270 +22326 5036 6512 5163 7027 +22327 2002 1735 1804 6027 +22328 2673 2780 2671 5867 +22329 4935 6062 5102 6719 +22330 2021 1787 6359 6884 +22331 5093 5057 5056 6213 +22332 2281 6294 2285 6387 +22333 493 492 6248 6629 +22334 437 2918 436 5894 +22335 1696 6138 6198 6988 +22336 4689 5937 4688 6437 +22337 1978 1863 6291 7201 +22338 1738 1979 1824 6600 +22339 2443 2419 6457 6816 +22340 521 6350 520 7081 +22341 2853 2855 2979 5780 +22342 4141 4060 4395 6494 +22343 5181 5262 5317 6813 +22344 5418 593 5383 6200 +22345 4738 4726 5012 7150 +22346 3982 3870 6863 7061 +22347 2353 5939 368 6266 +22348 3866 6440 5932 6924 +22349 5995 6287 2195 6572 +22350 5568 6801 5514 6939 +22351 5726 6802 5672 6940 +22352 5203 5149 5158 6662 +22353 3215 3471 6053 6300 +22354 6296 6443 346 6990 +22355 2589 5917 2778 6274 +22356 1182 1420 1492 6640 +22357 3504 3511 5778 6500 +22358 305 2259 306 6319 +22359 5065 6130 5064 6289 +22360 5760 6532 5838 6599 +22361 5877 6138 4034 6615 +22362 6236 6237 5003 6799 +22363 4379 6356 6301 7026 +22364 2283 2285 6294 6387 +22365 475 6134 476 6327 +22366 3466 3574 3486 6129 +22367 315 6360 6061 6912 +22368 631 32 5930 6229 +22369 1655 6376 6375 6934 +22370 2706 1436 3035 6089 +22371 5225 5290 5224 5792 +22372 2529 2441 2443 5896 +22373 3819 6757 3767 6826 +22374 4634 5306 5365 6336 +22375 4438 4257 4135 6225 +22376 6029 1970 6558 7178 +22377 6023 6471 2869 6683 +22378 2445 6189 5889 7195 +22379 3522 6101 6041 6738 +22380 259 5991 1901 6194 +22381 3098 2624 3099 6131 +22382 3441 3577 3403 6180 +22383 4216 4345 4012 6376 +22384 4686 5926 5151 6700 +22385 5302 6683 6471 6899 +22386 6211 6465 4186 6574 +22387 4995 6017 6197 6692 +22388 4385 6256 4090 6524 +22389 547 4530 548 6051 +22390 2739 3539 6101 6102 +22391 4284 4327 5878 6544 +22392 551 5988 5833 6916 +22393 3724 6784 6840 6913 +22394 4405 4225 4141 6406 +22395 2385 3009 2758 6075 +22396 4754 4756 4755 6447 +22397 1632 1919 1998 5871 +22398 6499 6569 1371 7205 +22399 4456 4215 6142 6578 +22400 2065 6029 1773 7178 +22401 472 6682 4544 7080 +22402 1260 1511 1311 5804 +22403 517 6319 516 6506 +22404 4696 4825 5892 6486 +22405 4214 4013 4406 6357 +22406 3709 6998 5820 7191 +22407 5683 5619 5646 7111 +22408 5525 5461 5488 7112 +22409 2956 3119 2407 6526 +22410 367 2316 6052 6856 +22411 1715 6248 1987 6467 +22412 3122 3245 3090 5931 +22413 1586 1588 6308 7051 +22414 4094 4213 4362 6242 +22415 5075 5223 571 5843 +22416 4111 6140 4204 6661 +22417 2192 1750 5953 6537 +22418 424 3599 6739 6894 +22419 424 6022 3618 6894 +22420 569 568 4769 6215 +22421 6042 6399 2734 6662 +22422 3105 3301 3254 5938 +22423 4782 4791 5100 5867 +22424 429 3049 428 6160 +22425 3885 5930 386 7191 +22426 3347 3316 3232 6276 +22427 1638 2039 6120 6432 +22428 5513 6721 6631 6907 +22429 2581 3239 3303 7127 +22430 1700 1948 6025 6357 +22431 1988 1714 6250 6369 +22432 348 2370 2337 6116 +22433 4372 6311 6057 6559 +22434 635 5767 5408 7165 +22435 5937 4690 6437 6670 +22436 2072 1995 1766 5838 +22437 2666 3133 3134 5799 +22438 4567 4568 4570 6761 +22439 3087 2731 3088 5926 +22440 527 6294 6510 6718 +22441 5373 6115 5422 6334 +22442 4414 4075 4259 6368 +22443 3674 6868 3838 7208 +22444 1352 1188 6867 7209 +22445 4084 6113 4369 6607 +22446 485 4246 486 6465 +22447 1783 6734 1873 7047 +22448 4223 4325 4123 6029 +22449 3750 6369 6126 6820 +22450 4260 6532 5885 7092 +22451 4592 6374 4969 6814 +22452 2255 2257 2253 6405 +22453 5208 4652 5248 6591 +22454 5346 6553 5134 7197 +22455 3837 3701 4003 6807 +22456 1302 6602 6482 6689 +22457 4266 6006 6475 6535 +22458 1353 1196 6571 6722 +22459 2544 6495 3470 6767 +22460 1234 1432 1381 6960 +22461 3918 3867 3720 6959 +22462 510 6296 511 6443 +22463 4027 6516 5960 7072 +22464 4763 4764 5028 6243 +22465 4237 457 456 5954 +22466 496 4238 497 5955 +22467 5944 6688 6028 7037 +22468 4566 5847 5108 6279 +22469 6190 6370 216 7062 +22470 4088 6206 5878 6615 +22471 5193 5294 5280 6216 +22472 4432 6144 4166 6493 +22473 5240 4761 5939 6815 +22474 1779 1693 6547 7118 +22475 1370 6498 5766 6869 +22476 4116 4181 4449 6000 +22477 4821 6042 5149 6399 +22478 2647 2652 6177 6750 +22479 1400 6048 1257 7107 +22480 5836 487 6262 7104 +22481 2661 5945 2799 6947 +22482 1636 5915 1982 7122 +22483 2709 2711 3203 6727 +22484 2663 6299 2933 6394 +22485 5643 5681 5747 6701 +22486 4529 4530 4497 6592 +22487 625 6128 6240 6807 +22488 580 6587 581 6729 +22489 1328 5852 6684 6685 +22490 5851 6686 3814 6687 +22491 4980 4913 4861 6372 +22492 6174 6469 3507 7125 +22493 4266 6535 6475 6944 +22494 1735 1860 1929 6605 +22495 5512 5477 5519 6773 +22496 5670 5635 5677 6770 +22497 450 5797 6505 6882 +22498 5147 6332 4614 6477 +22499 6299 6945 6028 7068 +22500 2544 2546 6495 6839 +22501 2488 2510 6680 6981 +22502 2245 2252 2250 6384 +22503 3409 3424 5815 6012 +22504 3340 6030 3341 6573 +22505 5022 5021 5023 6239 +22506 3322 6053 3471 6367 +22507 475 476 6260 6327 +22508 4959 4957 4958 6217 +22509 3780 3964 3858 5809 +22510 4572 4571 6188 6551 +22511 5949 5950 463 6863 +22512 5092 5091 5065 6130 +22513 2333 2369 2305 6598 +22514 2622 2620 2619 7097 +22515 3059 6005 3058 6823 +22516 2072 1738 2158 5760 +22517 4482 4110 4226 5876 +22518 4170 6270 4060 7187 +22519 1967 5848 1905 6286 +22520 3166 2968 3189 5937 +22521 522 521 5427 6110 +22522 5026 5337 5911 6502 +22523 5117 4840 4947 6087 +22524 1645 2029 5890 6588 +22525 2933 3525 3162 6394 +22526 613 6736 7054 7190 +22527 248 1627 5804 6324 +22528 248 6324 5804 6485 +22529 1560 1556 1559 6408 +22530 1959 1775 2181 6138 +22531 3234 6374 5934 6657 +22532 1640 1857 2095 6178 +22533 5833 2563 6320 6963 +22534 5815 4869 6652 6837 +22535 1548 1549 1547 6428 +22536 4664 6252 4665 6363 +22537 2288 6294 2282 6510 +22538 5308 5222 5307 6137 +22539 1559 6409 1567 6442 +22540 4518 6251 475 6260 +22541 5406 6518 5880 6987 +22542 5066 5937 4689 6815 +22543 2417 3131 2765 6551 +22544 1606 1615 6262 7104 +22545 5291 5274 5196 5787 +22546 5213 5276 4985 6496 +22547 5281 5771 5229 6970 +22548 4730 5889 4778 7181 +22549 2607 2602 2601 5927 +22550 510 511 6290 6625 +22551 5034 5874 5047 6707 +22552 2787 2402 380 6470 +22553 2564 6062 2743 6484 +22554 575 6746 6446 6974 +22555 4511 4514 4495 6546 +22556 1633 2051 2129 6386 +22557 4019 4361 4200 6186 +22558 4879 5847 4833 6504 +22559 1839 1703 5885 6254 +22560 3505 5795 3083 6273 +22561 6370 6419 488 6794 +22562 519 4253 6238 6579 +22563 526 6379 525 6935 +22564 1642 2017 2130 7177 +22565 1785 6449 2020 6527 +22566 1598 1601 222 6078 +22567 2853 2999 2960 5775 +22568 2439 2446 3129 6606 +22569 4490 4164 4215 5756 +22570 4884 5790 4883 6970 +22571 3495 6228 3325 6609 +22572 2338 6045 6321 6598 +22573 4123 4200 6029 7188 +22574 2553 2434 2554 6028 +22575 5612 6540 5654 6675 +22576 5454 6538 5496 6676 +22577 2761 3571 5755 6786 +22578 2203 2294 2204 6572 +22579 5385 6478 6136 6854 +22580 2933 2663 2934 6299 +22581 1803 2116 1682 5853 +22582 630 6492 6693 6898 +22583 624 6666 6128 7193 +22584 4491 5885 4260 6532 +22585 2526 6103 2888 6504 +22586 461 460 6206 6440 +22587 1517 1255 1351 5998 +22588 2161 275 1956 5950 +22589 2166 272 5968 6988 +22590 1398 1266 6699 6878 +22591 2511 2683 6381 6761 +22592 5782 7181 6099 7186 +22593 3225 3113 6265 6896 +22594 3007 3008 6069 7103 +22595 2269 6329 2273 6439 +22596 4491 6532 4037 6597 +22597 2328 2303 2359 6777 +22598 2906 2835 5914 6552 +22599 4448 6120 4049 6607 +22600 453 452 6250 6636 +22601 1511 5804 1260 6925 +22602 3604 3652 3595 6121 +22603 3449 3294 3290 5765 +22604 3401 6180 6513 6668 +22605 4607 4603 4601 6411 +22606 4529 4497 4553 6306 +22607 1306 1205 1269 5974 +22608 3691 3755 3792 5973 +22609 2669 2670 2668 6297 +22610 1817 1881 5928 6127 +22611 6083 6693 6457 6816 +22612 377 2463 6017 7206 +22613 2006 1870 1704 5818 +22614 533 5924 4525 7136 +22615 1877 6153 313 7180 +22616 5235 6508 6182 6845 +22617 1764 6328 5788 6880 +22618 1893 1845 6410 6677 +22619 514 4254 4136 6349 +22620 6297 6314 5271 6332 +22621 3312 3484 2543 6557 +22622 2230 2226 6119 6822 +22623 370 2698 2695 6754 +22624 4492 5781 4535 6169 +22625 620 6317 619 6434 +22626 4731 5822 583 6229 +22627 446 5809 2378 6905 +22628 4575 5981 4576 6108 +22629 1980 1827 1740 5812 +22630 3971 3708 3998 6882 +22631 571 572 5882 6274 +22632 2667 3579 3485 6143 +22633 2131 1929 1819 6964 +22634 5959 6249 4153 6348 +22635 444 5855 2412 6768 +22636 1189 6619 1317 6729 +22637 3803 3675 6620 6730 +22638 2239 2240 2238 6586 +22639 2637 5759 6272 6590 +22640 5959 6918 5958 7115 +22641 5091 5202 4649 6130 +22642 1597 1603 255 5845 +22643 518 4253 4203 6238 +22644 1825 1948 1669 6025 +22645 4230 4177 6072 6461 +22646 5147 6091 5217 6565 +22647 4195 4343 4139 7099 +22648 513 6292 6291 6586 +22649 4682 4680 4986 6267 +22650 5831 6137 5081 6434 +22651 3367 3197 3198 6473 +22652 3733 3899 3880 6772 +22653 6720 6905 29 7098 +22654 1788 1697 6032 6355 +22655 5812 4318 6949 6995 +22656 497 5694 6791 7005 +22657 5536 6790 457 7003 +22658 4108 6368 5848 7170 +22659 4439 4471 4127 5760 +22660 5817 6778 5905 6992 +22661 2951 2942 6137 6269 +22662 3270 6444 3269 6591 +22663 3336 3517 5993 7144 +22664 2782 2681 2849 6351 +22665 578 4575 4901 6366 +22666 5882 6491 1502 7008 +22667 484 6465 6463 6574 +22668 435 6302 5894 6696 +22669 2123 6379 6132 6800 +22670 4688 5937 4690 6437 +22671 2748 2750 3555 5757 +22672 2385 6075 2383 6647 +22673 2334 6334 2362 6550 +22674 6541 6637 574 6746 +22675 2233 6443 2232 6625 +22676 4592 4969 6374 6692 +22677 4269 4168 6176 6493 +22678 3372 6347 3375 6652 +22679 4938 5103 5044 6937 +22680 3138 3140 3136 5834 +22681 5672 5608 5750 6594 +22682 5592 5514 5450 6593 +22683 1630 6204 1841 6205 +22684 3182 6042 2734 6662 +22685 3704 6674 5754 7044 +22686 2939 3526 3534 6056 +22687 4840 4945 4947 5856 +22688 4721 4747 4996 6371 +22689 2148 1858 1753 5960 +22690 4664 4665 4663 6363 +22691 2513 5863 366 7007 +22692 4878 4831 5153 5846 +22693 4620 6763 6514 6951 +22694 3266 6046 5925 6795 +22695 1637 6168 2041 6490 +22696 4224 5989 4033 7132 +22697 5623 6476 5741 6722 +22698 3704 3989 6674 7044 +22699 351 6067 6318 6550 +22700 294 6147 2289 6718 +22701 2001 6230 1739 6992 +22702 5922 26 6653 6756 +22703 2883 2754 2794 6402 +22704 3396 3392 3450 6277 +22705 3376 6224 3487 6289 +22706 4110 5876 4417 6909 +22707 2774 6366 5850 6855 +22708 310 6291 6290 7201 +22709 2413 2414 2415 6451 +22710 1573 6365 6094 7126 +22711 3885 386 5930 7044 +22712 4784 5758 4599 6885 +22713 2450 2452 2936 6088 +22714 3335 5771 3336 6941 +22715 1533 5922 1532 7082 +22716 2637 6272 3068 6590 +22717 4750 4749 5860 6754 +22718 1536 5803 1539 7017 +22719 6415 6653 1545 6698 +22720 3190 6101 3539 6102 +22721 1858 6244 2014 6516 +22722 4420 6348 4333 7172 +22723 3078 7103 6086 7198 +22724 5878 6206 4088 6838 +22725 2995 2996 2624 7101 +22726 4544 6682 6112 7080 +22727 1723 5788 1994 6796 +22728 2518 2519 2517 5904 +22729 3278 5864 3558 6560 +22730 2604 2719 1387 6125 +22731 2669 2668 3383 6332 +22732 3993 3808 5922 6575 +22733 5168 6161 5010 6162 +22734 4573 6188 6240 7050 +22735 445 2412 444 5855 +22736 4199 4281 4124 6691 +22737 469 6256 4385 6408 +22738 5380 6285 6325 6518 +22739 3214 6179 3213 6300 +22740 1712 5915 2059 6000 +22741 5688 571 6533 6775 +22742 2625 2624 2996 6398 +22743 2339 2296 5754 7044 +22744 3807 3702 3935 6805 +22745 1914 1691 6156 6211 +22746 2625 2996 3034 6398 +22747 2123 298 1878 6379 +22748 5789 5889 4730 7181 +22749 5254 6427 6513 6668 +22750 6182 6508 5235 7055 +22751 3502 3506 6297 6507 +22752 2041 6167 1760 6490 +22753 3374 6004 3429 7166 +22754 5673 6722 5738 6743 +22755 4217 6375 5895 6577 +22756 1729 2024 2174 5900 +22757 2064 1733 2033 5877 +22758 5275 5272 4661 6021 +22759 3819 3788 6603 6604 +22760 4659 6609 4764 7194 +22761 2999 2979 2997 6246 +22762 5051 5314 5125 5776 +22763 28 6287 5995 6572 +22764 431 5911 2531 6051 +22765 5272 4812 5277 6021 +22766 490 4333 4378 6348 +22767 1512 1222 6111 6883 +22768 491 6249 492 6787 +22769 2796 5964 2614 6977 +22770 5812 6949 5844 6995 +22771 2319 2356 6309 6777 +22772 6631 6852 5481 6907 +22773 3834 2066 1801 5949 +22774 5921 6269 2943 6789 +22775 3100 3006 6148 6372 +22776 1849 2038 1761 6206 +22777 5289 6231 6216 6888 +22778 1447 6712 6632 7137 +22779 3113 2768 2761 5755 +22780 3565 3287 3258 6411 +22781 3186 3185 6304 6591 +22782 2212 2211 325 5995 +22783 2671 2672 2673 6872 +22784 3694 5949 3834 6440 +22785 4448 4117 4180 6114 +22786 6141 6309 2301 6777 +22787 4549 4520 6078 6520 +22788 3997 5797 3746 6805 +22789 1834 1940 1761 6838 +22790 2613 6363 2611 7148 +22791 516 6384 6319 6661 +22792 3202 3079 6086 7103 +22793 451 6369 452 6820 +22794 1739 2001 2073 6975 +22795 2462 5930 385 6229 +22796 4921 6343 6522 6965 +22797 6145 7056 1853 7057 +22798 3708 6126 3998 6882 +22799 5249 6210 6304 7214 +22800 4463 4237 4117 6468 +22801 4506 6739 6894 7164 +22802 1839 262 6254 6859 +22803 3494 3304 6243 7102 +22804 5276 5292 5227 6496 +22805 5918 6683 5302 6899 +22806 2514 6108 6366 6855 +22807 5931 6792 6454 7140 +22808 4945 5052 5856 6606 +22809 1693 5966 1971 6547 +22810 2718 2954 2963 6320 +22811 5084 5083 6174 6393 +22812 6299 6394 2663 7068 +22813 1757 2145 1868 5848 +22814 1937 1688 1768 6271 +22815 517 6405 6184 6854 +22816 5297 6182 6180 6845 +22817 5253 5255 5217 6565 +22818 2627 2753 2628 6104 +22819 5396 5378 5430 6234 +22820 1988 2172 6369 7026 +22821 262 1579 261 6418 +22822 2012 2180 1697 6356 +22823 3765 6801 3700 6939 +22824 1279 6802 1214 6940 +22825 5602 6874 5744 7011 +22826 5586 5444 6873 7009 +22827 3615 3603 6251 6456 +22828 293 6147 2020 6449 +22829 1945 6055 1809 6460 +22830 6563 6825 501 6997 +22831 5119 6208 5163 6512 +22832 3301 368 5939 7154 +22833 1799 1935 1513 6278 +22834 2361 2304 6171 7151 +22835 4292 4168 4039 6176 +22836 4404 4022 4210 6733 +22837 2622 2619 6345 7097 +22838 1751 1841 2005 6204 +22839 1498 6827 6699 6878 +22840 28 529 5409 6141 +22841 3025 2817 2944 6981 +22842 2713 6128 2610 6957 +22843 1620 1619 3843 7082 +22844 1649 5960 1858 6516 +22845 5499 5469 5507 6939 +22846 5665 5657 5627 6940 +22847 341 6452 6201 6762 +22848 1737 6396 6203 6671 +22849 489 6190 488 6794 +22850 3030 2607 3015 5843 +22851 5087 6361 6131 7027 +22852 2754 2904 2755 5776 +22853 2728 3974 6412 7075 +22854 4851 5896 630 6693 +22855 5020 5333 5799 6711 +22856 3550 2702 3534 6056 +22857 6154 6914 6470 7106 +22858 580 579 6189 6587 +22859 4916 4861 4913 6372 +22860 1780 5958 2146 7115 +22861 5561 6784 5494 6785 +22862 5719 6781 5652 6782 +22863 2193 2002 1672 5840 +22864 4701 4700 4699 5985 +22865 1846 6057 1773 6490 +22866 1284 2725 1402 7162 +22867 2922 5884 2935 7075 +22868 3404 6180 3401 6182 +22869 3375 3422 3421 6347 +22870 6620 6723 629 6730 +22871 552 4551 4517 5833 +22872 6192 6485 6348 7172 +22873 6092 6456 3586 6715 +22874 4399 6410 5890 6588 +22875 4244 4071 6624 6912 +22876 1789 1961 1698 6311 +22877 1859 1881 6127 6341 +22878 3807 5798 3702 6805 +22879 1264 6467 6111 6787 +22880 4726 4779 5782 7181 +22881 3796 6580 6503 6862 +22882 1927 1923 1708 6176 +22883 1769 1915 2139 6144 +22884 4667 4668 5056 6069 +22885 2047 1740 1856 6450 +22886 2546 2890 2891 6096 +22887 6133 6558 1970 7178 +22888 4234 4178 4073 6073 +22889 1868 2145 263 6134 +22890 1251 6016 6699 6844 +22891 2964 2728 2729 7073 +22892 3850 6998 3709 7191 +22893 1814 2050 1902 6685 +22894 1815 2049 1903 6687 +22895 5481 6852 6631 7190 +22896 1844 1803 1682 6310 +22897 2557 3248 2471 6050 +22898 335 2273 334 6439 +22899 5528 6725 626 6913 +22900 1777 6429 6238 7006 +22901 6044 6160 549 7039 +22902 1435 1229 1377 5850 +22903 4607 4609 4608 6411 +22904 1766 1979 2072 6599 +22905 5100 4628 4782 6170 +22906 4536 4539 4493 6077 +22907 5417 5369 5394 6200 +22908 3147 2833 3148 6437 +22909 2059 6000 5915 6474 +22910 4650 5765 4835 6849 +22911 1578 6418 1580 7051 +22912 2835 2832 2834 5914 +22913 1307 1348 1208 5900 +22914 4082 4324 4330 6175 +22915 2386 3547 3548 5936 +22916 4563 5964 4566 6279 +22917 5299 5130 5228 6507 +22918 454 6868 5540 6895 +22919 3665 6891 6530 6932 +22920 1179 6890 6531 6931 +22921 3943 5851 6790 7002 +22922 1457 5852 6791 7004 +22923 4340 4073 4208 6066 +22924 2985 3156 2591 5910 +22925 291 1993 1382 5899 +22926 4244 4297 4071 6152 +22927 475 6251 4528 6365 +22928 4807 6789 6269 7163 +22929 571 570 6665 6775 +22930 5698 494 6867 6881 +22931 4496 4510 4515 6255 +22932 2769 2397 2770 5810 +22933 1463 1328 1902 5852 +22934 3949 3814 1903 5851 +22935 3945 6584 3732 7094 +22936 2679 2680 441 5879 +22937 2856 6188 2766 6551 +22938 5220 5154 6082 6513 +22939 5825 6478 6135 6754 +22940 5249 5210 5208 6210 +22941 6247 6829 5867 7117 +22942 4851 4863 630 5896 +22943 4705 4704 4703 6627 +22944 1849 2013 2181 6337 +22945 5245 6754 5938 7154 +22946 4521 4503 6251 6456 +22947 25 504 4334 6505 +22948 3422 3349 3348 6347 +22949 2283 330 2285 6387 +22950 1321 5803 1216 6925 +22951 3886 2617 447 5809 +22952 1970 6558 6133 6817 +22953 3347 6150 2598 6276 +22954 2942 2941 3056 6269 +22955 470 6407 471 6442 +22956 2165 2148 1669 5769 +22957 1179 6610 6531 6890 +22958 3665 6611 6530 6891 +22959 437 2917 2918 6515 +22960 4172 6341 4227 6635 +22961 4439 6599 5760 6600 +22962 609 6417 610 6497 +22963 4056 4451 4192 6316 +22964 3930 6593 3679 6783 +22965 1444 6594 1193 6780 +22966 5303 4793 4774 5917 +22967 6318 6479 5992 7053 +22968 630 5820 6492 6898 +22969 5859 6608 5942 7065 +22970 4657 6105 4917 6659 +22971 4444 4229 4048 5928 +22972 1663 1957 1793 6315 +22973 6217 6683 5918 7078 +22974 3071 2688 362 5880 +22975 464 6653 26 6756 +22976 2338 6045 380 6321 +22977 4310 505 506 6355 +22978 479 6306 6305 6871 +22979 525 5405 6284 6285 +22980 1284 1435 3121 5850 +22981 3409 3324 6012 6753 +22982 4818 6036 6035 6502 +22983 4379 6301 451 7026 +22984 613 6736 6412 7054 +22985 5045 5978 4942 7211 +22986 3705 6503 5753 7083 +22987 5353 5356 5351 6212 +22988 1890 5872 6310 6525 +22989 5379 5404 5403 6296 +22990 5283 5327 5328 5773 +22991 506 6061 4144 6355 +22992 3140 5834 3138 6941 +22993 4614 6333 4603 6411 +22994 2523 2504 5820 6898 +22995 3678 6440 3866 6924 +22996 1866 6205 2009 6376 +22997 331 330 2321 6284 +22998 3172 5778 2938 7064 +22999 264 1575 263 6327 +23000 4589 4797 4952 6398 +23001 2466 5884 2935 6639 +23002 1792 6018 6149 6616 +23003 2638 6272 2635 6336 +23004 3010 3026 5777 7078 +23005 5692 5650 5634 6549 +23006 5492 5476 5534 6548 +23007 628 6124 5810 6509 +23008 5379 6295 5404 6679 +23009 3282 6336 3329 6346 +23010 3545 3151 3475 5786 +23011 5127 5253 5216 6347 +23012 28 6572 5995 6585 +23013 1949 1762 1948 6357 +23014 4263 4162 4479 5807 +23015 1986 1760 6167 6322 +23016 5378 5429 5397 6234 +23017 4714 5867 4781 6829 +23018 6503 6575 6233 7083 +23019 29 4538 532 7098 +23020 4041 4409 6132 6344 +23021 1862 6396 1737 6671 +23022 4488 4356 4017 5764 +23023 4334 4379 450 6505 +23024 4924 4847 4923 5941 +23025 3230 2937 2870 5826 +23026 4323 4329 4160 6196 +23027 3841 3704 3989 6674 +23028 28 5899 6572 6585 +23029 4775 5102 6062 6719 +23030 5121 6195 5122 6707 +23031 4117 4412 4180 6468 +23032 310 2243 311 6290 +23033 3377 3291 3486 6130 +23034 1686 6450 6140 6946 +23035 2995 5874 2993 6431 +23036 5565 6530 5511 6611 +23037 5669 5723 6531 6610 +23038 480 4529 6306 6307 +23039 26 6233 5922 6653 +23040 1678 1942 6167 6685 +23041 3437 6239 3440 6358 +23042 298 6193 2277 7143 +23043 1227 6903 6569 6954 +23044 3712 6904 6570 6953 +23045 4471 4127 5760 7092 +23046 6169 6653 6415 6698 +23047 3069 443 2998 6020 +23048 2262 2267 336 6331 +23049 3484 6489 6063 7084 +23050 1919 1754 1998 5872 +23051 1555 237 6362 6545 +23052 2104 6152 1742 6912 +23053 304 305 6081 6834 +23054 1906 2151 1767 5977 +23055 3453 6263 3305 6609 +23056 3562 6041 3391 6496 +23057 6366 6543 6125 7162 +23058 618 5080 6434 6885 +23059 3037 3036 6398 6500 +23060 5833 6916 5988 6963 +23061 6169 464 6415 6653 +23062 2991 5835 1460 6824 +23063 4399 6588 5890 7099 +23064 2902 6208 3241 7027 +23065 3519 2994 3518 6823 +23066 3322 3067 2636 6590 +23067 6187 1880 7091 7105 +23068 4946 4945 4840 5910 +23069 4646 4647 6445 6526 +23070 2270 2277 6354 7143 +23071 528 6510 6293 7034 +23072 4571 4572 4632 6551 +23073 2694 2695 2693 5860 +23074 3286 5835 3158 6824 +23075 2282 6294 2284 6510 +23076 3446 3366 6426 6448 +23077 2920 2781 2936 6247 +23078 1608 6262 1606 6464 +23079 1747 6146 2114 6614 +23080 5407 583 5411 5822 +23081 511 6397 6290 6625 +23082 5230 5281 5341 5993 +23083 4425 4030 6073 6377 +23084 2546 6096 6495 6839 +23085 1209 6684 5852 7004 +23086 3695 6686 5851 7002 +23087 2562 6128 2713 6608 +23088 2321 6284 2303 6518 +23089 4948 4578 4590 5778 +23090 3826 6488 6877 6959 +23091 1340 6487 6879 6960 +23092 1307 2069 1348 5900 +23093 6352 6677 6066 6934 +23094 1866 1683 6205 6352 +23095 595 594 5897 6628 +23096 624 625 6128 6608 +23097 3157 2545 3145 5956 +23098 563 4896 564 6015 +23099 5922 6233 26 6503 +23100 2143 5762 1828 7074 +23101 4233 6140 4031 6995 +23102 3790 6765 6863 7061 +23103 249 6324 6485 7172 +23104 1512 1485 1222 6883 +23105 1797 6396 5999 7091 +23106 3267 3263 6035 6555 +23107 4086 4278 4153 6249 +23108 5188 6023 5302 6471 +23109 2993 5874 3059 6823 +23110 5413 5793 5367 6067 +23111 517 518 6081 6834 +23112 2821 6915 6197 7206 +23113 4569 565 564 6016 +23114 4527 542 6121 6302 +23115 236 3658 235 6391 +23116 3257 6332 3383 6565 +23117 4289 4099 5844 6230 +23118 4216 4433 4134 6376 +23119 4189 5928 5966 7131 +23120 4158 6151 4244 6360 +23121 4730 5889 5789 6523 +23122 4955 5157 4693 5819 +23123 3646 6022 3591 6894 +23124 579 578 5850 6810 +23125 3598 3619 226 6306 +23126 5395 5374 5389 6266 +23127 32 583 5407 6401 +23128 2865 2858 6275 6393 +23129 2805 2804 5964 6279 +23130 1873 6734 5837 7047 +23131 1397 1268 1409 6705 +23132 3883 3754 3895 6704 +23133 5211 5165 5113 5883 +23134 2315 2300 2325 6478 +23135 4700 4932 4699 5962 +23136 1749 2084 1885 5974 +23137 1748 2085 1884 5973 +23138 5036 5163 5088 7027 +23139 4776 4632 5104 6083 +23140 3468 3281 3331 6899 +23141 27 489 6324 6642 +23142 2427 2715 2751 7000 +23143 4958 5197 5198 6471 +23144 6124 6509 6221 7110 +23145 4498 6165 6430 7136 +23146 1376 1467 5882 6775 +23147 1726 6516 6244 6556 +23148 4578 5778 4576 5981 +23149 4827 6177 4570 6351 +23150 6035 6399 2736 6678 +23151 2422 6855 2445 7195 +23152 1326 2719 2973 5998 +23153 502 6766 6563 6997 +23154 3276 3308 6086 6919 +23155 1747 2114 6146 7032 +23156 3773 6774 3980 7009 +23157 1287 6771 1494 7011 +23158 5299 5263 6297 6842 +23159 4180 4412 455 6468 +23160 6208 6737 5990 6969 +23161 3236 2829 3233 6657 +23162 2940 3274 3527 5970 +23163 3401 6180 3403 6513 +23164 1621 1537 1536 5803 +23165 5762 6248 494 6474 +23166 2359 329 2328 6293 +23167 1449 1321 1216 6925 +23168 1872 5807 1840 6525 +23169 4388 5958 4035 6501 +23170 28 6585 6476 6741 +23171 4368 4484 4198 6093 +23172 1567 1562 6442 6993 +23173 4916 4914 4929 5757 +23174 625 6240 626 6807 +23175 2122 6211 1879 6465 +23176 2715 3778 6389 7023 +23177 4925 4854 4857 5944 +23178 3499 6117 3321 6447 +23179 2530 6189 2399 7096 +23180 2096 6140 1686 6450 +23181 3988 6826 6757 6830 +23182 1776 5865 1963 6597 +23183 4909 6688 6059 7109 +23184 2901 2629 2900 6154 +23185 5305 5366 4626 6986 +23186 628 6620 5523 6913 +23187 1334 1228 6088 6712 +23188 3951 6009 3737 7023 +23189 2064 1775 1959 5877 +23190 533 4525 534 7136 +23191 367 5939 2353 6266 +23192 1532 5922 6756 7082 +23193 4326 5989 4124 6432 +23194 27 5804 5803 6324 +23195 521 6350 6439 6846 +23196 1301 6563 1220 6997 +23197 4051 6223 4190 7188 +23198 4707 4708 4739 6143 +23199 4474 4473 6532 7095 +23200 2162 320 1992 5797 +23201 575 6164 5998 6446 +23202 5322 5323 4816 5907 +23203 5325 4749 5324 6390 +23204 268 1566 267 6408 +23205 5806 6680 2510 6981 +23206 1241 1291 6879 6901 +23207 1700 6395 1882 6601 +23208 2406 423 424 6445 +23209 5059 5060 6431 7101 +23210 1429 6458 1355 7205 +23211 6439 6846 6350 7081 +23212 5314 5776 5051 6576 +23213 1676 6474 5762 7074 +23214 4197 4384 6377 7087 +23215 2256 304 6581 6834 +23216 1970 2100 6558 6817 +23217 25 5798 6264 6566 +23218 319 5797 2162 6505 +23219 4652 4651 4653 5841 +23220 1386 1238 6619 6701 +23221 5195 6276 5191 6752 +23222 4862 6976 4563 6977 +23223 5373 5401 5382 6334 +23224 1491 1297 1242 5899 +23225 6087 6275 3152 6744 +23226 519 6776 518 6854 +23227 5593 5543 461 6564 +23228 4732 5854 6451 6582 +23229 4015 5817 4483 6230 +23230 4389 4221 4057 6436 +23231 538 4548 4511 6546 +23232 2672 2671 2783 6170 +23233 491 4378 6249 7156 +23234 4659 4658 4660 6522 +23235 2302 6285 2321 6518 +23236 4962 5921 4898 6517 +23237 2427 6389 2715 7000 +23238 1984 1781 2177 6535 +23239 2722 2723 2549 5819 +23240 5910 7042 6656 7106 +23241 5899 503 6449 6741 +23242 1341 1430 6487 6901 +23243 2109 1999 5895 7047 +23244 3187 2899 3358 6219 +23245 2011 6322 1657 6527 +23246 3025 2944 5806 6981 +23247 2884 3143 3483 6172 +23248 1694 6073 1845 6677 +23249 3231 5790 3226 6941 +23250 4833 4832 4831 5847 +23251 3562 6496 3509 6738 +23252 2684 7000 5916 7093 +23253 2840 6392 2661 7174 +23254 2607 5843 3030 6481 +23255 510 6443 511 6625 +23256 3488 3446 3443 6426 +23257 5643 6640 5686 6701 +23258 4663 5031 4755 6447 +23259 3342 2899 2867 6023 +23260 2696 6553 5913 7196 +23261 526 6284 527 6294 +23262 3356 3391 3390 6496 +23263 1847 2010 1656 6249 +23264 5840 6226 1672 6958 +23265 2886 2884 2885 6172 +23266 2093 2047 1650 5756 +23267 1607 253 1609 6465 +23268 3261 2902 3241 6361 +23269 599 600 5389 7154 +23270 1204 6413 6699 6827 +23271 2951 6269 6137 6789 +23272 1977 1852 266 6406 +23273 377 2463 378 6017 +23274 5861 6437 4888 6670 +23275 4039 4454 4257 5891 +23276 5093 5050 5082 6174 +23277 4387 6138 6033 7157 +23278 1645 2176 2029 6588 +23279 2837 3573 2843 6434 +23280 1355 6458 6453 7205 +23281 2339 2340 2309 5793 +23282 1374 6787 1222 6883 +23283 1929 6605 1860 7105 +23284 1789 2078 1665 7178 +23285 6388 6389 2427 7000 +23286 1772 6918 5959 7115 +23287 5075 571 570 6665 +23288 1792 6018 1958 6149 +23289 2541 6340 2542 6630 +23290 4937 4794 5040 5956 +23291 1387 1326 1215 6125 +23292 4465 5996 4193 7184 +23293 1930 1859 1681 6420 +23294 3409 6012 5815 6753 +23295 4180 455 6373 6468 +23296 4911 4909 4974 6059 +23297 5798 6383 5797 6805 +23298 478 6194 6305 6568 +23299 5297 6180 5138 6845 +23300 5116 6177 4828 7204 +23301 1322 1357 1217 6572 +23302 2870 3557 3230 7077 +23303 2841 2842 2708 7128 +23304 6531 6610 5595 6890 +23305 5437 6530 6611 6891 +23306 5104 4746 6083 6606 +23307 5728 6649 5600 7012 +23308 5570 6648 5442 7010 +23309 6320 6445 4647 6526 +23310 5135 6181 6183 6921 +23311 3363 6106 3364 6448 +23312 489 488 6419 6794 +23313 4844 5815 5126 6837 +23314 3370 3266 3407 5925 +23315 4837 4756 5027 6358 +23316 2961 6451 5774 7160 +23317 2315 6478 2325 7063 +23318 6049 6553 2697 7196 +23319 2747 6719 2678 6920 +23320 340 2318 6201 6506 +23321 5593 461 462 6564 +23322 2916 2976 5868 6536 +23323 6028 7037 6688 7045 +23324 3728 3982 3870 6863 +23325 4752 4894 4892 5925 +23326 2668 3506 3383 6565 +23327 2252 306 2259 6319 +23328 5358 5194 5189 6012 +23329 1387 2604 6125 7162 +23330 2407 2408 6054 7116 +23331 5246 6297 5263 6842 +23332 2959 6217 2958 6683 +23333 1827 1641 2120 5812 +23334 385 6229 5930 6401 +23335 5077 4890 4744 6936 +23336 1281 1333 6758 6775 +23337 5942 2560 6608 6749 +23338 1722 1996 2051 6386 +23339 6197 6915 6692 7206 +23340 3170 3426 2832 7019 +23341 2422 2773 2445 6855 +23342 2074 1676 1941 6474 +23343 506 5401 6334 6550 +23344 4220 4289 4121 6230 +23345 3154 6047 2970 6621 +23346 1491 6585 5899 6741 +23347 2868 6218 3114 6929 +23348 3531 6041 3522 6455 +23349 3153 2968 2594 6058 +23350 6230 6992 5844 7176 +23351 5259 5311 5176 5965 +23352 2476 2478 3026 6237 +23353 5960 6516 5947 7072 +23354 4373 6032 4152 6356 +23355 1975 1870 1721 6375 +23356 1261 1467 1502 7008 +23357 437 3607 438 5987 +23358 4931 6096 4880 6495 +23359 239 3609 3648 6169 +23360 5929 7013 6666 7058 +23361 338 2315 339 6184 +23362 1724 1923 1927 5891 +23363 2033 1639 2038 5878 +23364 2006 1648 1870 6207 +23365 2576 6998 2503 7191 +23366 3972 3723 6521 6604 +23367 4199 6475 6283 6691 +23368 340 2349 2318 6506 +23369 3257 6477 6332 6565 +23370 1988 6301 6250 6658 +23371 4156 4292 4438 7056 +23372 4868 6164 4799 6282 +23373 1642 1813 2017 6622 +23374 2177 6006 1643 6616 +23375 524 5430 5399 6157 +23376 5013 5043 4646 6054 +23377 3238 3560 3236 5892 +23378 522 5396 523 6110 +23379 5271 6297 5246 6314 +23380 2659 5916 3879 7093 +23381 241 6233 3663 6653 +23382 5803 6324 5804 6925 +23383 2340 6566 5793 6889 +23384 1789 1961 6559 7178 +23385 1957 6156 1691 6377 +23386 3436 6298 3417 6314 +23387 3955 3828 3758 6866 +23388 1272 1469 1342 6865 +23389 4152 6032 4033 6432 +23390 2552 3542 2791 5972 +23391 4610 5154 6427 6483 +23392 4227 6635 6341 7131 +23393 1850 1922 1663 6315 +23394 4390 5915 4181 6474 +23395 2882 3534 2702 6056 +23396 482 5845 483 6202 +23397 4866 4567 4583 6380 +23398 1374 1520 6787 6996 +23399 4262 4453 4047 6605 +23400 4484 6093 4368 6494 +23401 421 5783 3031 6764 +23402 6041 6496 3562 6738 +23403 521 6350 6145 7056 +23404 4978 4976 5172 6455 +23405 2428 2614 2615 6009 +23406 1307 1208 1496 5900 +23407 337 336 2313 6136 +23408 5407 632 32 6401 +23409 4114 6019 4165 7153 +23410 1654 2007 1981 5802 +23411 2868 3114 6220 6929 +23412 589 4591 590 6017 +23413 2299 6241 2351 6856 +23414 4277 6206 460 6838 +23415 4321 4115 4462 6193 +23416 1826 6992 1739 7176 +23417 3400 6411 6129 6870 +23418 3387 2596 3362 6002 +23419 3906 3978 3668 6913 +23420 2993 6431 5874 6823 +23421 4841 4919 6104 6576 +23422 616 4862 4982 6388 +23423 1499 6746 5835 6897 +23424 5637 6602 6533 6759 +23425 5479 6603 6534 6760 +23426 5778 7049 6108 7064 +23427 422 3646 423 6022 +23428 2039 1638 6120 6658 +23429 5694 6528 496 6791 +23430 5536 6529 456 6790 +23431 3272 6427 3472 6444 +23432 4289 4099 4455 5844 +23433 4157 6194 478 6597 +23434 4551 4502 4517 6313 +23435 5289 4822 4825 5892 +23436 571 6665 5882 6775 +23437 4381 6322 6527 7079 +23438 4842 6087 5161 6424 +23439 3601 5768 3624 6797 +23440 4130 5953 4434 6669 +23441 5864 6086 6613 7103 +23442 6140 6450 6441 6995 +23443 4154 6138 4397 6337 +23444 2410 2411 2412 5887 +23445 1262 1453 1351 7014 +23446 5019 539 5785 6798 +23447 2624 2623 6131 6398 +23448 2461 5820 2576 7191 +23449 580 4786 4864 6189 +23450 2035 1792 2057 6733 +23451 3561 5773 3537 6941 +23452 1730 6126 2172 7026 +23453 3487 6425 6224 7036 +23454 6610 6812 5618 6865 +23455 5460 6611 6811 6866 +23456 4380 6806 6337 6884 +23457 5131 4927 4926 6047 +23458 5314 6424 5776 6576 +23459 2395 6898 5810 7108 +23460 3056 3244 3559 5824 +23461 5479 6534 5566 6760 +23462 5637 6533 5724 6759 +23463 5293 5214 5318 6843 +23464 4774 573 5312 5917 +23465 5224 5070 5225 6489 +23466 1290 1371 6499 6569 +23467 6530 6611 3927 6811 +23468 6531 6610 1441 6812 +23469 4144 4313 6032 6624 +23470 4198 475 474 6093 +23471 4166 4403 6326 6344 +23472 6187 6223 6168 7188 +23473 4935 4621 5102 6062 +23474 5407 5367 5435 5793 +23475 1912 6961 6312 6980 +23476 3306 3305 6263 6609 +23477 3474 3131 5983 6551 +23478 361 5881 5813 6589 +23479 4927 4699 4932 6394 +23480 623 6835 6666 7058 +23481 3579 6007 3568 6910 +23482 4444 4048 4189 5928 +23483 2869 6471 6023 6929 +23484 3860 6820 3708 6882 +23485 2329 362 5880 6518 +23486 4673 5002 4959 6217 +23487 2175 1801 5949 6833 +23488 2418 2770 2443 6457 +23489 3328 6177 2652 6750 +23490 6094 6303 1568 7126 +23491 4051 6168 6223 7188 +23492 5992 6355 2022 7213 +23493 4240 4277 460 6838 +23494 5335 5336 5897 6711 +23495 3595 3604 6121 6928 +23496 4121 4465 4257 5996 +23497 4709 5020 5333 5799 +23498 3129 3130 2439 6606 +23499 4695 4696 4698 6657 +23500 2289 6510 2284 6718 +23501 4904 7123 6004 7167 +23502 1860 6605 6203 7105 +23503 3371 3482 3369 6659 +23504 4017 4344 4488 5764 +23505 4548 5979 537 6999 +23506 3667 6893 3801 7031 +23507 1196 6571 6722 6743 +23508 3456 6466 5909 7084 +23509 6265 6378 2555 7016 +23510 5370 5394 5383 6628 +23511 2696 2655 2654 6553 +23512 2958 6217 2957 7078 +23513 5362 5773 5328 6627 +23514 2404 6371 2816 6914 +23515 1678 6167 1835 7171 +23516 1278 1364 2470 5875 +23517 1703 6254 1951 6597 +23518 511 6435 6397 6990 +23519 3775 3712 4009 6570 +23520 1523 1290 1227 6569 +23521 3221 3112 6896 7142 +23522 6034 6256 4185 6847 +23523 3390 3385 3356 5980 +23524 3688 6412 3896 6736 +23525 3650 5924 3610 6768 +23526 3288 3223 3123 6070 +23527 5552 6584 5467 6922 +23528 5625 5710 6583 6923 +23529 6381 6844 2498 7128 +23530 2513 365 2568 5920 +23531 3359 6091 3380 6565 +23532 4560 487 4526 5796 +23533 2354 2325 2300 6478 +23534 5416 5825 597 6478 +23535 5137 6219 6181 6921 +23536 4076 5812 4318 6949 +23537 1790 1908 2079 6033 +23538 539 538 4511 5987 +23539 4024 5966 6635 7131 +23540 2387 2421 5889 7195 +23541 5266 5265 6444 6483 +23542 3205 3268 3043 7139 +23543 4323 4329 6196 6991 +23544 458 5851 6097 6686 +23545 498 5852 6098 6684 +23546 5606 6705 6850 6984 +23547 6704 6852 5448 6983 +23548 463 6806 4380 6884 +23549 1245 5933 1380 6825 +23550 489 6419 488 7172 +23551 3454 3556 5792 7084 +23552 6631 6736 611 7190 +23553 2774 5850 2772 6855 +23554 4025 4226 4171 6396 +23555 6417 6695 5855 7098 +23556 5027 5212 5274 5787 +23557 3462 3491 3360 6340 +23558 5448 6654 5584 6852 +23559 5742 5606 6655 6850 +23560 2541 3461 6340 6630 +23561 5480 6735 5531 6900 +23562 2878 3229 3240 6560 +23563 4850 5116 4874 6378 +23564 1370 5766 1329 6869 +23565 1913 1876 269 6256 +23566 4241 499 4175 6098 +23567 5293 5318 5839 6843 +23568 4201 6244 4337 6516 +23569 5677 5635 5744 6874 +23570 5586 5519 5477 6873 +23571 454 6250 5761 7208 +23572 494 6248 5762 7209 +23573 3253 6380 2497 6966 +23574 1938 1812 1690 6344 +23575 3052 2558 5962 6378 +23576 5305 4626 6618 6986 +23577 4221 4339 4026 6178 +23578 3324 3316 6276 6277 +23579 3437 5787 3476 6239 +23580 5057 4951 4801 6469 +23581 3992 5798 3807 7169 +23582 461 462 6564 7061 +23583 2641 3319 2544 6010 +23584 1680 6186 1929 7105 +23585 1470 1258 5995 6902 +23586 2487 6229 385 6401 +23587 481 6078 4520 6307 +23588 3180 3181 3178 5770 +23589 342 6452 6762 7202 +23590 2993 3060 3059 5874 +23591 3392 6277 3397 6281 +23592 3359 3506 6288 6565 +23593 1523 1195 1371 6569 +23594 2175 5949 1731 6806 +23595 1912 2080 6961 6980 +23596 1575 6094 1571 6327 +23597 4612 4835 5765 6985 +23598 4344 4426 4122 5877 +23599 2297 6185 6184 7063 +23600 4160 4061 4210 6310 +23601 2711 1329 3203 6727 +23602 5020 6390 5333 6711 +23603 5807 6537 5953 7129 +23604 4897 5997 5316 6517 +23605 3482 6659 6105 6965 +23606 5076 5075 4787 6273 +23607 2048 1741 2094 5858 +23608 2735 2736 6399 6678 +23609 560 6048 31 6582 +23610 467 468 5968 6847 +23611 6307 6664 224 6871 +23612 1583 6305 6568 7051 +23613 6019 7028 4231 7210 +23614 6275 6393 2858 6744 +23615 4560 4533 486 6261 +23616 2558 3106 5962 6786 +23617 1703 1918 1839 5885 +23618 2551 2550 6031 6433 +23619 6124 6457 2767 6551 +23620 3379 3380 6091 6565 +23621 466 4358 5968 7157 +23622 4682 4681 6267 7030 +23623 5136 5138 6180 6845 +23624 4686 6472 5241 7067 +23625 5183 5184 5185 6219 +23626 4558 4494 4512 6014 +23627 3593 3602 3617 6253 +23628 2527 2528 2526 6155 +23629 4512 472 473 6014 +23630 582 6569 6499 7205 +23631 2935 6364 2854 6639 +23632 4761 5018 601 5863 +23633 4756 4585 4755 6447 +23634 4169 4056 4207 6315 +23635 5882 6665 3567 6728 +23636 5621 6458 5736 6694 +23637 3763 2502 5827 6887 +23638 548 549 6044 6160 +23639 4514 4547 470 6546 +23640 1459 6583 1246 6996 +23641 608 5408 5414 6309 +23642 1674 2184 2111 6396 +23643 6169 6415 465 6698 +23644 2590 2582 2744 5998 +23645 4238 4411 4116 6000 +23646 1912 6312 1642 6980 +23647 4036 6057 4151 6490 +23648 4052 4467 4392 6034 +23649 2278 2279 2275 6354 +23650 5837 5935 2053 7192 +23651 2412 5855 2492 6695 +23652 2061 1716 1942 5933 +23653 2062 1717 1940 5932 +23654 4150 4445 4043 6064 +23655 1242 1297 1382 5899 +23656 5060 4798 5059 6122 +23657 3361 3362 3360 6002 +23658 3309 5894 2918 6696 +23659 5793 5754 6889 7038 +23660 5495 6895 6731 6989 +23661 3362 3462 3360 6340 +23662 3036 3261 2623 6361 +23663 3211 3150 3483 5965 +23664 434 3652 6302 6456 +23665 4663 5032 4662 6106 +23666 2800 6446 5886 6808 +23667 4560 4533 6261 7164 +23668 5353 5141 6030 6921 +23669 2563 2784 425 6445 +23670 1556 1561 1559 6409 +23671 2020 6147 294 6718 +23672 6225 6350 4430 7056 +23673 1836 2037 6270 6461 +23674 5554 6783 6593 6785 +23675 5712 6780 6594 6782 +23676 5337 4820 5026 5911 +23677 1938 6493 6144 7057 +23678 2983 2945 3081 6371 +23679 601 602 5384 6052 +23680 1728 6111 2173 7156 +23681 2733 2749 2748 6060 +23682 3014 3012 3011 5918 +23683 4492 4541 5781 5924 +23684 462 6765 6564 7061 +23685 428 3639 3613 6160 +23686 4139 4393 4053 7087 +23687 5085 5326 5081 6137 +23688 4054 4395 4146 6286 +23689 2610 2562 2712 6128 +23690 3968 3689 6509 6725 +23691 4756 5021 6358 6612 +23692 4964 4929 4914 5757 +23693 3480 6965 6105 7001 +23694 4994 4936 4640 5801 +23695 461 6440 6206 6833 +23696 1914 5845 255 6574 +23697 2920 2967 2785 6015 +23698 2591 5857 3118 7042 +23699 3498 3568 6007 6612 +23700 527 6294 6293 6510 +23701 5302 6023 5355 6899 +23702 4043 4161 4422 5967 +23703 3392 3451 6280 6281 +23704 360 359 5854 6589 +23705 6034 6961 2080 6980 +23706 5308 5986 6392 6643 +23707 468 469 6253 6391 +23708 5485 6641 5528 6913 +23709 4215 4038 4456 6142 +23710 6583 6903 1524 6923 +23711 6584 6904 4010 6922 +23712 3843 3703 3808 5922 +23713 565 6016 6381 6699 +23714 3501 3576 3530 6748 +23715 3943 5851 3755 6790 +23716 1457 5852 1269 6791 +23717 5363 5210 6210 6400 +23718 4875 4932 4700 5962 +23719 2957 2958 2959 6217 +23720 3479 6626 3415 7001 +23721 4471 4260 4127 7092 +23722 3134 3169 6143 6552 +23723 2465 2415 2485 5854 +23724 5266 6106 4610 6483 +23725 3401 6513 2875 6668 +23726 5077 6143 6552 6936 +23727 5884 6639 2466 6887 +23728 3063 5986 2898 6560 +23729 1211 6655 6850 6851 +23730 3697 6654 6852 6853 +23731 4796 6246 5780 6755 +23732 5813 6589 5881 6987 +23733 4848 6697 5971 6737 +23734 2114 5890 6614 7032 +23735 5036 5035 5034 6166 +23736 1740 1827 2120 5812 +23737 4399 5890 4366 7099 +23738 5709 6874 5646 7011 +23739 5551 6873 5488 7009 +23740 4204 5940 515 6661 +23741 4232 4068 7056 7057 +23742 4780 4778 5105 5888 +23743 462 463 5949 6806 +23744 2906 6252 2907 6552 +23745 1771 2140 1914 6156 +23746 6140 4252 6441 6706 +23747 3051 2876 2875 6427 +23748 1555 6323 1548 6545 +23749 3477 6063 6986 7097 +23750 3702 3807 3992 5798 +23751 475 4528 474 6365 +23752 3836 3734 3932 5761 +23753 1350 1248 1446 5762 +23754 3786 3862 3280 6947 +23755 2333 2312 2308 6295 +23756 432 3033 3018 5903 +23757 1749 2143 1828 7074 +23758 1852 2088 6271 6406 +23759 5305 6245 6557 6986 +23760 4355 4366 5890 7099 +23761 5915 6335 1842 6474 +23762 5974 6634 1479 6791 +23763 3965 5973 6633 6790 +23764 1966 2129 1753 6026 +23765 4583 6380 5109 7140 +23766 3460 5792 3465 6630 +23767 2678 2747 2566 6719 +23768 4139 4053 6076 7087 +23769 495 5762 494 6474 +23770 217 6370 5796 7062 +23771 516 6319 517 6661 +23772 580 579 4786 6189 +23773 582 581 6499 6729 +23774 3220 6158 3115 7142 +23775 4175 4315 4051 6168 +23776 5077 4707 5260 6143 +23777 5963 613 6412 7073 +23778 4906 4965 5759 6985 +23779 333 2326 2350 6157 +23780 6365 6928 6014 7126 +23781 3624 5768 3638 6642 +23782 4957 4956 4958 5970 +23783 4754 5169 4756 6612 +23784 5827 6417 2501 6886 +23785 4630 4634 4629 6336 +23786 3445 3443 3444 6425 +23787 6175 6176 4168 6493 +23788 2182 6178 6025 6726 +23789 5753 6720 5809 6905 +23790 1593 6422 1600 6779 +23791 4720 4734 4716 6755 +23792 1563 1568 1569 6303 +23793 2257 2255 339 6405 +23794 2201 2199 5798 6566 +23795 4446 6286 4054 7170 +23796 4773 5025 575 6446 +23797 5299 5228 5230 6507 +23798 2015 5947 1649 6516 +23799 3180 5770 3041 6621 +23800 5942 6128 624 6666 +23801 5045 4789 4942 5978 +23802 3627 220 3659 6462 +23803 611 612 5884 6364 +23804 4612 5873 4609 6985 +23805 1497 6780 1193 6940 +23806 3679 3983 6783 6939 +23807 4203 4111 4418 6081 +23808 4599 4784 4598 5758 +23809 4303 4044 4428 6205 +23810 1616 1614 6262 6370 +23811 353 6566 6889 7169 +23812 3157 2545 5956 6839 +23813 1873 1979 5837 6118 +23814 4697 5148 4696 6486 +23815 5145 6003 5070 6489 +23816 3425 3549 2597 6919 +23817 3428 3387 3427 6002 +23818 1729 1953 2024 6449 +23819 1683 6410 1802 7032 +23820 505 6479 6318 6550 +23821 307 1867 306 6384 +23822 4365 4194 4017 6071 +23823 2677 5956 3145 6536 +23824 4506 4522 485 6261 +23825 2537 6665 5795 6728 +23826 3448 3411 6183 7138 +23827 2600 3324 6276 6752 +23828 479 478 6305 6306 +23829 2715 2585 3778 7023 +23830 2249 2247 6292 6690 +23831 5975 6896 3112 7142 +23832 3373 5784 6004 6652 +23833 1652 2158 1963 6532 +23834 4447 4043 4295 5818 +23835 2938 2514 2762 6108 +23836 4826 4950 5152 5898 +23837 3398 3405 3399 5873 +23838 1477 1293 6499 6848 +23839 5639 6850 6632 7137 +23840 5594 5543 5475 6645 +23841 5752 5701 5633 6644 +23842 4345 4216 4092 6375 +23843 512 6291 6397 6586 +23844 3790 6862 3673 6863 +23845 2102 1818 1681 5764 +23846 5929 622 6392 6830 +23847 2405 5857 2983 6371 +23848 2908 5892 6486 6657 +23849 268 2138 1913 6524 +23850 4590 5778 4578 6500 +23851 2929 2691 5826 6514 +23852 2766 6124 2724 7110 +23853 1700 2000 6357 6601 +23854 4124 5989 4360 6475 +23855 3276 6086 3202 6919 +23856 3709 5820 6716 7191 +23857 2078 6133 1665 7178 +23858 5236 5235 6508 7055 +23859 2055 2094 1741 7033 +23860 2578 2455 2454 6848 +23861 4047 4353 6203 6605 +23862 2108 1684 1832 5763 +23863 3352 5839 3353 6567 +23864 2454 2453 2521 5805 +23865 1830 6114 2058 6468 +23866 2477 2478 2476 6799 +23867 2232 6443 2237 6625 +23868 3328 2849 6351 6750 +23869 217 1616 218 6262 +23870 1745 6133 2078 6800 +23871 2061 1889 5933 6685 +23872 2062 1888 5932 6687 +23873 2826 6657 6258 6915 +23874 1941 1842 6335 6474 +23875 4382 4201 4113 6556 +23876 2884 2886 2865 6275 +23877 1629 6341 2004 7129 +23878 462 6337 4380 6806 +23879 2051 1996 1765 5808 +23880 6549 6804 1489 6923 +23881 6548 6803 3975 6922 +23882 2602 5927 2607 6481 +23883 2405 5857 6371 6914 +23884 2998 2997 3070 5887 +23885 1696 1787 2021 6884 +23886 3230 2937 5826 7020 +23887 2183 1826 5844 6992 +23888 2040 5959 1847 6335 +23889 1951 6254 261 6568 +23890 3705 5753 3990 7083 +23891 5301 6086 4963 6438 +23892 2921 2925 3302 5758 +23893 3069 5879 442 6020 +23894 3650 3610 444 6768 +23895 2164 1779 1971 6547 +23896 519 6136 6776 6854 +23897 3261 6361 3036 6500 +23898 27 6324 5803 6642 +23899 5335 5870 5273 6711 +23900 4422 4150 4043 6064 +23901 2637 3343 2635 6030 +23902 2689 2568 364 5920 +23903 1897 6198 273 6988 +23904 2986 3143 2987 6087 +23905 4092 6375 4217 6577 +23906 5032 4610 6106 6483 +23907 225 6306 3640 6871 +23908 2669 3326 3417 6314 +23909 5867 6829 5774 7117 +23910 1935 1889 1423 5933 +23911 1936 1888 3909 5932 +23912 3173 5990 6709 6969 +23913 4279 6283 4016 6475 +23914 6131 6398 5086 7101 +23915 1844 6616 6310 6733 +23916 1223 1364 5875 6848 +23917 1877 2128 1689 6151 +23918 4757 561 5774 6829 +23919 4993 7035 5893 7037 +23920 3248 6454 6050 6966 +23921 5455 6853 5498 6907 +23922 3138 5834 3136 7182 +23923 2734 2735 6399 6678 +23924 3675 3933 6620 6723 +23925 3456 3419 3418 5909 +23926 5513 609 610 6631 +23927 5671 560 561 6632 +23928 2868 2899 6218 6929 +23929 1894 6192 1699 6918 +23930 1491 5899 1242 6741 +23931 4992 4980 4994 6148 +23932 5074 4787 5075 6273 +23933 3085 2792 3196 6969 +23934 483 5845 4293 6574 +23935 5805 6499 5875 6848 +23936 382 6080 2817 6981 +23937 2244 6452 2246 7202 +23938 3472 6444 6427 6483 +23939 4594 4596 5869 6916 +23940 5003 6237 5058 6799 +23941 4708 4709 4710 6231 +23942 2750 3553 3555 6767 +23943 3462 3492 3491 6340 +23944 3332 6053 2638 6336 +23945 3567 3314 5882 6728 +23946 2488 2460 2487 6229 +23947 3149 3420 3419 5909 +23948 5671 560 6632 6743 +23949 229 6260 1576 6365 +23950 6038 6521 3723 6604 +23951 5336 5897 6390 6962 +23952 4513 4494 4557 6121 +23953 2672 2783 3219 5978 +23954 4733 557 30 7089 +23955 5036 6166 5162 6512 +23956 3333 5771 3335 6941 +23957 3688 6736 3782 7190 +23958 559 6232 5768 6642 +23959 604 5406 5380 6325 +23960 3916 3727 6877 6900 +23961 4794 4796 4795 6246 +23962 3293 3135 2666 5799 +23963 4427 4328 4035 5959 +23964 5960 6026 4097 6681 +23965 3170 2832 5861 7019 +23966 469 6256 6408 6667 +23967 1311 6694 1186 6883 +23968 3549 3410 6011 7158 +23969 2357 2326 332 6157 +23970 5422 585 6080 6115 +23971 2616 6117 3564 7148 +23972 4458 4163 4012 5840 +23973 5352 5132 6012 6753 +23974 3198 3197 2520 6473 +23975 3228 3226 5790 6710 +23976 2959 6471 6217 6683 +23977 1831 1944 1647 6000 +23978 3350 6281 3348 6288 +23979 1909 2168 6100 6800 +23980 515 514 5394 6201 +23981 2897 3239 3240 6560 +23982 1979 1766 1873 5837 +23983 3747 6826 5945 6947 +23984 3336 3517 3434 5993 +23985 3024 2453 2509 6764 +23986 4841 4946 5910 7106 +23987 2465 2413 2415 6451 +23988 5813 2319 6589 6777 +23989 2898 2839 2897 5779 +23990 6258 6657 6374 6915 +23991 6329 6439 2269 6846 +23992 1492 1283 1453 7014 +23993 2264 6405 6581 6776 +23994 4434 6460 5953 7015 +23995 481 6422 6078 6664 +23996 4603 4602 4601 6342 +23997 4383 6034 4196 6312 +23998 1498 6699 1266 6878 +23999 3444 3297 3445 6425 +24000 2022 5992 318 6505 +24001 4261 6357 6244 7183 +24002 2826 6374 6657 6915 +24003 377 2320 5901 6679 +24004 3739 3925 4001 6562 +24005 1439 1515 1253 6561 +24006 4498 6165 4556 6430 +24007 469 6408 470 6409 +24008 2815 2812 2813 6001 +24009 4413 4060 4170 6270 +24010 5247 5206 5204 6298 +24011 4611 4580 4679 6404 +24012 4168 4351 4039 5891 +24013 4956 4811 5168 6161 +24014 3484 3454 6489 7084 +24015 5400 510 6068 6296 +24016 5504 6704 5441 6959 +24017 5662 6705 5599 6960 +24018 5125 5259 5173 5965 +24019 3234 5934 3233 6657 +24020 359 2415 360 5854 +24021 3797 6751 3672 6882 +24022 6649 6979 5600 7012 +24023 5442 6648 6978 7010 +24024 1334 6632 6712 6860 +24025 1776 6194 5865 6597 +24026 3802 2448 2449 7174 +24027 6009 6876 3737 7023 +24028 2065 1970 1732 7178 +24029 5866 6451 3000 7160 +24030 3591 3614 3608 5796 +24031 4876 5135 5136 6181 +24032 1685 6475 1833 6691 +24033 527 6510 528 6718 +24034 1614 1612 6370 6794 +24035 5929 6830 3985 7058 +24036 344 2240 343 7202 +24037 2247 2245 2244 6452 +24038 2902 3261 3092 6361 +24039 3194 6039 6279 6977 +24040 3254 3301 3165 5939 +24041 486 5836 487 6262 +24042 1432 1340 6705 6960 +24043 3918 3826 6704 6959 +24044 2382 6048 2380 7107 +24045 6221 6509 627 6725 +24046 477 6418 6254 6568 +24047 4120 4490 5756 7100 +24048 1219 6232 1480 6809 +24049 6227 3416 6965 7102 +24050 2682 3262 6380 6761 +24051 4679 6425 5221 6426 +24052 2233 2232 6443 6990 +24053 3214 3535 3212 6195 +24054 5297 6182 5258 6668 +24055 6083 6457 2419 6816 +24056 3226 3231 3227 5790 +24057 1292 1204 1395 6413 +24058 1600 1595 1597 6422 +24059 4015 4220 5977 6230 +24060 4847 5828 4939 6937 +24061 3757 6529 3958 6978 +24062 1472 1271 6528 6979 +24063 25 504 6383 6566 +24064 2256 6581 2254 6834 +24065 3670 6529 6774 7003 +24066 6528 6771 1184 7005 +24067 6003 6489 5145 6557 +24068 2174 1657 1986 6322 +24069 4841 5910 4840 6576 +24070 1506 5803 1321 7017 +24071 3132 3158 6808 6968 +24072 2153 1774 2039 6432 +24073 1760 2041 1835 6167 +24074 3724 3906 6784 6913 +24075 1834 6838 5878 7118 +24076 4507 5924 6165 7136 +24077 2597 6438 3308 6919 +24078 2322 2323 2306 6067 +24079 2106 1662 1923 6176 +24080 1957 2089 1771 6156 +24081 6487 6879 5680 6901 +24082 3955 3685 3828 6866 +24083 1469 1199 1342 6865 +24084 372 2348 371 7063 +24085 1924 6403 1661 6796 +24086 2398 2506 2530 5875 +24087 5195 6011 5301 6438 +24088 1850 6677 1920 7192 +24089 2291 2289 6147 6510 +24090 4358 467 466 5968 +24091 3039 3179 3040 5841 +24092 4584 4586 4585 6353 +24093 3037 6282 3198 6500 +24094 5325 4750 4749 5860 +24095 3938 3914 3768 6676 +24096 1452 1428 1282 6675 +24097 1905 1967 1757 5848 +24098 4527 4503 543 6302 +24099 2931 3162 3154 6047 +24100 6004 7123 6224 7167 +24101 3016 6161 2392 7168 +24102 4432 4269 4068 6493 +24103 2288 329 2283 6293 +24104 1334 6632 1447 6712 +24105 1970 6029 1732 7178 +24106 4342 4352 4172 5952 +24107 4513 6421 4543 6682 +24108 1592 1601 6422 6664 +24109 4431 4165 6019 7210 +24110 3261 3504 6361 6500 +24111 1709 2089 1922 6079 +24112 6287 6572 5899 6911 +24113 1584 6423 6305 6871 +24114 5064 6130 4649 6339 +24115 3394 3406 5961 7196 +24116 5067 5811 4766 6515 +24117 5281 5341 5993 7135 +24118 2922 2742 2935 5963 +24119 2587 1292 2707 6413 +24120 422 421 3614 5783 +24121 1439 1515 6561 6596 +24122 3925 4001 6562 6595 +24123 1772 5958 6918 7115 +24124 5578 632 633 6751 +24125 2261 2267 6331 7081 +24126 3357 3341 3343 6030 +24127 4712 4791 4714 5867 +24128 5144 4617 5142 6084 +24129 28 6476 5704 6741 +24130 3602 3596 3617 6943 +24131 2687 2921 5800 5862 +24132 4633 4632 4572 6551 +24133 2231 6822 6360 7180 +24134 4042 4329 4460 5871 +24135 2410 5887 2412 6695 +24136 4526 4499 5796 6967 +24137 1302 6482 1486 6689 +24138 1703 1963 5885 6597 +24139 6167 6168 1835 7171 +24140 2430 2437 2434 5794 +24141 3183 3541 2723 6662 +24142 4753 4983 4742 6046 +24143 3804 6853 6852 6907 +24144 4264 5812 4410 7100 +24145 556 4539 557 5969 +24146 6312 6961 6034 6980 +24147 4350 4095 4271 5865 +24148 1208 1304 1384 6997 +24149 565 5700 564 6878 +24150 3853 3684 6636 6820 +24151 4866 4623 5931 7140 +24152 2288 6293 6510 7034 +24153 3311 6618 3424 7158 +24154 2250 2257 2251 6506 +24155 3228 3226 3227 5790 +24156 5578 6459 632 6751 +24157 5108 4833 4879 5847 +24158 4563 6279 4579 6977 +24159 5150 5861 4888 6670 +24160 4889 7022 4954 7088 +24161 572 5309 5312 6274 +24162 2185 6114 1973 6740 +24163 4590 4589 4952 6500 +24164 2709 5766 2710 6869 +24165 1417 1480 1219 6232 +24166 575 576 5998 6164 +24167 3456 5909 3418 7084 +24168 466 6165 465 6698 +24169 607 5414 5402 6589 +24170 2688 3071 3017 6259 +24171 477 476 4250 6254 +24172 3041 5883 3155 6621 +24173 5638 5748 5689 6901 +24174 2054 5891 1724 6975 +24175 3542 2552 2549 5819 +24176 3225 6265 3123 6896 +24177 622 5929 6392 6835 +24178 5778 5888 7049 7064 +24179 1997 1724 5891 6975 +24180 2142 1677 2075 5761 +24181 2143 1676 2074 5762 +24182 3961 3775 6716 6730 +24183 4845 4970 4966 6724 +24184 480 6664 6307 6871 +24185 2160 248 5804 6485 +24186 3494 6965 3416 7102 +24187 591 6268 5901 6814 +24188 3730 6783 6784 6785 +24189 6780 6781 1244 6782 +24190 4234 4340 4134 6352 +24191 521 6439 6350 7081 +24192 3776 6631 6721 6907 +24193 4772 5779 4792 6835 +24194 6731 6803 5449 6989 +24195 2786 2793 2547 6433 +24196 2227 2236 6119 6443 +24197 521 522 6145 6846 +24198 4396 5959 4153 6348 +24199 2504 2503 2576 6998 +24200 1229 5850 6587 7096 +24201 1276 6453 1355 6458 +24202 6271 6407 4140 6524 +24203 4485 4293 483 5845 +24204 2610 6128 2712 6957 +24205 1563 6442 1562 6993 +24206 4928 4916 4929 6010 +24207 1601 223 6078 6664 +24208 1958 6019 1689 6149 +24209 1834 1679 1940 7118 +24210 3079 3201 3200 6085 +24211 5644 6655 6561 6851 +24212 5486 6654 6562 6853 +24213 1670 2171 2018 6118 +24214 3085 2793 2792 5971 +24215 2649 2651 2788 6043 +24216 1746 5853 2116 6950 +24217 5820 6229 5930 7191 +24218 2515 2520 2516 6366 +24219 1359 6543 1267 7014 +24220 3308 2599 3277 6438 +24221 4565 5963 4895 7121 +24222 5872 6196 1919 6733 +24223 1636 5906 2040 6335 +24224 4529 479 480 6306 +24225 521 6145 4301 7056 +24226 6417 6497 5809 6886 +24227 4660 6227 4657 6965 +24228 2778 5917 2480 6481 +24229 4309 527 528 6718 +24230 4326 4124 4281 6432 +24231 4133 4441 4296 6133 +24232 3713 6907 6721 7207 +24233 1752 2135 1869 6836 +24234 2684 2687 7000 7093 +24235 1212 1499 6491 6897 +24236 478 477 6254 6568 +24237 1729 2174 2069 5900 +24238 5864 7163 6086 7198 +24239 1580 1577 1582 6260 +24240 5260 4665 5077 6252 +24241 5689 567 568 6498 +24242 2948 3548 2621 6084 +24243 3344 5986 3346 6789 +24244 5000 5056 4999 6613 +24245 5653 6881 6732 6994 +24246 5549 5566 5443 6676 +24247 5724 5601 5707 6675 +24248 501 6563 5751 7070 +24249 1911 6344 1644 6817 +24250 2462 2461 2576 7191 +24251 425 424 3628 6445 +24252 3005 2590 2744 6164 +24253 4656 6227 5268 6626 +24254 3213 6300 6179 6567 +24255 5727 6655 6960 7133 +24256 5569 6654 6959 7134 +24257 2066 1990 1731 5949 +24258 3010 3518 3011 6823 +24259 2536 2489 6213 6469 +24260 2769 2397 5810 7041 +24261 4323 4160 4022 6733 +24262 3440 3438 6358 6612 +24263 3446 6404 3491 6448 +24264 5271 5255 6297 6332 +24265 3454 5792 3460 6630 +24266 2553 2819 6028 7068 +24267 3143 6087 2986 6424 +24268 1971 6547 5966 6740 +24269 5059 4798 5003 6237 +24270 551 550 5988 6916 +24271 1195 1371 6569 7205 +24272 2610 2713 2562 6128 +24273 3121 2772 2774 5850 +24274 4136 4254 4456 6349 +24275 3841 6674 3989 7044 +24276 4089 4267 4206 6395 +24277 3079 3200 3202 6919 +24278 4383 4090 4185 6256 +24279 3568 6612 3440 6910 +24280 5511 6611 6530 6811 +24281 5669 6610 6531 6812 +24282 2581 6008 3239 7127 +24283 4658 5268 4660 6227 +24284 3656 3586 6456 6715 +24285 5315 5250 5199 6220 +24286 612 5963 613 6412 +24287 4016 6283 4199 6475 +24288 5439 6773 5483 6893 +24289 5641 5597 6770 6892 +24290 1545 240 6169 6653 +24291 1830 6468 1646 6740 +24292 2330 2313 2299 6266 +24293 3714 6736 5884 6887 +24294 3179 3039 3177 5842 +24295 1777 6225 6429 6906 +24296 1267 6543 6125 7014 +24297 4102 6033 4392 6847 +24298 3616 6121 3604 6928 +24299 4653 4664 5270 6363 +24300 3957 6876 6389 7023 +24301 5215 6004 5065 7167 +24302 3357 3412 6181 6183 +24303 3618 6022 3646 6894 +24304 1856 1641 2096 6450 +24305 3060 2995 3098 5874 +24306 2805 2845 2802 6279 +24307 343 2361 344 6040 +24308 1205 5974 1479 6791 +24309 3965 3691 5973 6790 +24310 1658 1848 2012 6301 +24311 5356 5182 5351 6212 +24312 1960 1788 1697 6032 +24313 3641 6520 3588 7086 +24314 4851 4724 4863 5896 +24315 5317 6031 5164 6512 +24316 3346 2898 3063 5986 +24317 3527 3116 2393 6220 +24318 4696 5148 4825 6486 +24319 1232 1292 6498 6869 +24320 3934 6736 3676 7190 +24321 5835 6808 3158 6968 +24322 6732 6804 5607 6994 +24323 1413 1394 1247 7070 +24324 4628 4568 4896 6015 +24325 3896 6736 6412 7075 +24326 2916 5868 3102 6536 +24327 4744 5861 4743 6936 +24328 4914 4685 6060 7029 +24329 3999 3731 3834 6440 +24330 1196 6722 1361 6743 +24331 4846 4847 4939 5971 +24332 4628 4627 4568 6351 +24333 1822 1984 2177 6535 +24334 2427 6388 2428 6389 +24335 4546 545 5903 6650 +24336 5860 5861 4743 6670 +24337 527 6100 526 6294 +24338 5624 5734 5698 6867 +24339 5466 5576 5540 6868 +24340 4279 6283 6475 7185 +24341 3035 1344 2923 6016 +24342 4281 6120 4085 6432 +24343 4202 4055 6118 6599 +24344 4725 5896 4851 6693 +24345 2015 1865 6090 6516 +24346 5150 4888 6437 6670 +24347 2533 5859 2811 6608 +24348 5448 5504 5584 6704 +24349 5606 5662 5742 6705 +24350 2447 3802 5929 7174 +24351 5464 6783 5554 6785 +24352 5622 6780 5712 6782 +24353 512 6290 6291 7028 +24354 5187 5180 5181 6813 +24355 2100 2131 1819 6222 +24356 3038 5841 2905 6542 +24357 2658 3034 6122 7052 +24358 385 6401 5930 7044 +24359 4677 4678 4702 6265 +24360 1676 5762 2143 7074 +24361 3812 4003 6128 6749 +24362 5108 5106 4579 6279 +24363 3003 2846 3194 6279 +24364 3000 3001 2413 6451 +24365 5078 4695 4969 6374 +24366 5421 5373 5393 6334 +24367 3170 3134 3133 7019 +24368 3199 3198 5981 6500 +24369 5148 5155 6056 6402 +24370 4277 6206 4088 6615 +24371 5165 5131 5112 5883 +24372 269 6408 6256 6667 +24373 587 5386 586 6321 +24374 1367 1198 6629 6787 +24375 4215 4120 4490 5756 +24376 4266 4307 6006 6535 +24377 2958 5918 6683 7078 +24378 2183 1827 1947 6107 +24379 3336 5993 3434 6554 +24380 5354 5352 5132 6012 +24381 1887 1639 1817 5928 +24382 3791 6907 3713 7207 +24383 2600 3410 3324 6752 +24384 3035 1436 1488 1285 +24385 3086 2950 5782 7116 +24386 1999 1721 2109 5895 +24387 2949 3086 5782 7116 +24388 5622 6594 5712 6780 +24389 5464 6593 5554 6783 +24390 541 540 4513 6421 +24391 6155 6514 6267 6951 +24392 2164 1943 1899 5954 +24393 1898 2163 1944 5955 +24394 2276 2279 332 6157 +24395 1862 2111 1737 6396 +24396 5922 6503 26 7119 +24397 4051 4375 4175 6168 +24398 2779 2776 2732 6472 +24399 1824 1700 2182 6025 +24400 4306 4157 478 6597 +24401 2812 6001 2815 6926 +24402 5137 6181 6219 6845 +24403 3632 3664 5781 6905 +24404 1503 1346 1421 6809 +24405 4475 5960 4097 6681 +24406 631 630 6716 6730 +24407 4186 4468 5994 7087 +24408 2294 2293 2204 6572 +24409 1468 6629 1198 6881 +24410 619 6038 618 6434 +24411 3035 2923 2966 6016 +24412 3168 3167 2692 6039 +24413 2190 1678 1835 7171 +24414 5828 6937 5971 7179 +24415 3228 3497 3226 6710 +24416 2371 3831 2344 6889 +24417 576 6164 4868 6473 +24418 1578 1587 6418 7051 +24419 2962 5918 3281 6683 +24420 3250 5860 3337 7019 +24421 4760 4720 4759 5775 +24422 3194 3168 6039 6977 +24423 3063 3346 5986 6789 +24424 1525 6324 6419 6794 +24425 3448 3411 3570 6183 +24426 4304 4144 506 6061 +24427 6476 6722 5623 6766 +24428 6380 6966 6050 7140 +24429 2045 1796 5966 6635 +24430 5152 5898 4950 7211 +24431 5263 5255 5299 6297 +24432 2310 349 6116 6334 +24433 517 6081 4418 6661 +24434 494 495 6867 7209 +24435 455 6868 454 7208 +24436 2549 2722 5819 6660 +24437 2121 1877 313 7180 +24438 4170 4060 4236 7187 +24439 3178 5770 3181 6591 +24440 4640 5099 5868 6651 +24441 5157 4955 5129 5819 +24442 6138 6988 6033 7157 +24443 2477 2480 2478 6799 +24444 525 5405 526 6284 +24445 3650 3621 3594 5924 +24446 27 490 5804 6485 +24447 4006 6820 3860 7094 +24448 347 2236 346 6443 +24449 247 1991 2160 5804 +24450 4758 4715 4757 5774 +24451 1232 6498 1370 6869 +24452 4183 4397 6138 6198 +24453 523 4462 522 6145 +24454 1644 2016 2131 6222 +24455 5140 5339 5139 5936 +24456 1865 6516 1726 6556 +24457 5921 6789 2943 7198 +24458 4178 4425 6073 6410 +24459 2898 5779 2897 6560 +24460 4656 4657 5268 6227 +24461 5900 6449 503 6741 +24462 2948 2620 3201 6084 +24463 3415 6227 3413 7102 +24464 3058 6005 3011 6823 +24465 4455 4031 6441 6995 +24466 4554 4515 6255 6650 +24467 2883 2794 2881 6486 +24468 4701 5114 5330 5985 +24469 2409 2408 2407 7116 +24470 4015 4483 4401 6230 +24471 372 3077 3209 5897 +24472 4249 4093 5947 6858 +24473 618 617 4767 5862 +24474 2101 6930 6186 7105 +24475 4944 5873 4829 6908 +24476 4637 5037 4639 6259 +24477 5527 6828 5590 6877 +24478 5748 5685 6827 6879 +24479 4689 4690 4688 5937 +24480 4795 5016 5039 6414 +24481 3668 6641 3889 6971 +24482 1403 1182 6640 6972 +24483 3076 3077 2695 6390 +24484 6062 6484 4621 7121 +24485 4849 4850 4678 6265 +24486 3687 6538 3914 7200 +24487 1428 1201 6540 7199 +24488 5287 5286 5285 5943 +24489 2224 6209 2222 6550 +24490 4876 5136 5219 5957 +24491 2573 3163 2513 5863 +24492 4246 4186 4468 5994 +24493 2606 6125 2605 6473 +24494 4302 4434 6420 6669 +24495 6341 7131 6127 7203 +24496 1860 1735 2005 6204 +24497 2972 2970 6047 6621 +24498 2805 2802 2804 6279 +24499 1294 1478 1372 6571 +24500 3286 3158 5835 6808 +24501 4535 464 6169 6233 +24502 631 4863 4731 6229 +24503 526 525 6387 6935 +24504 5529 6620 5588 6730 +24505 5746 5687 6619 6729 +24506 3395 5961 5773 6554 +24507 5041 4643 5011 6470 +24508 2792 5971 2793 6697 +24509 518 6581 6238 6834 +24510 4048 6547 5928 6952 +24511 4935 5153 4831 5846 +24512 2730 2731 2732 7021 +24513 4751 5323 6480 7067 +24514 2537 5795 6727 6728 +24515 5004 4673 4671 5777 +24516 3511 3172 3093 5778 +24517 4873 5152 4856 7211 +24518 2498 2511 2683 6381 +24519 4736 4716 533 5887 +24520 2648 2934 2664 6299 +24521 2041 1637 1835 6168 +24522 1328 6684 1270 6685 +24523 3814 6686 3756 6687 +24524 2359 2303 2321 6284 +24525 2375 2522 2457 6417 +24526 5690 6487 5618 6812 +24527 5532 6488 5460 6811 +24528 454 6636 6250 7208 +24529 6058 6973 5908 7109 +24530 4427 4139 4343 5958 +24531 5128 6753 6281 6837 +24532 364 2358 363 6325 +24533 3001 2414 2413 6451 +24534 2141 6290 311 6625 +24535 2069 1993 1729 5900 +24536 3349 3524 3380 6747 +24537 2369 6045 2338 6598 +24538 6198 6988 6138 7157 +24539 5082 4951 5057 6469 +24540 1376 5882 6728 6775 +24541 5922 6575 6503 7119 +24542 1692 6223 6187 7091 +24543 4217 4450 4028 5895 +24544 3154 2970 3155 6621 +24545 3627 3659 3587 6313 +24546 4103 4359 4246 5994 +24547 2576 2461 2504 5820 +24548 3084 5795 2537 6665 +24549 360 5854 2415 6589 +24550 2072 1979 1738 6599 +24551 3007 6085 3079 7103 +24552 2015 1871 1649 5947 +24553 1630 1860 6204 6671 +24554 2378 446 2376 5809 +24555 4732 607 4711 5854 +24556 533 4716 4734 5855 +24557 1605 1602 1610 6464 +24558 3450 3497 3496 6074 +24559 4416 5837 4202 6734 +24560 4706 6103 4681 7030 +24561 3114 3188 3115 6158 +24562 1516 1336 6637 6746 +24563 2919 6472 3252 6696 +24564 4922 4923 5053 5941 +24565 1694 2056 1845 6073 +24566 442 2679 441 5879 +24567 5595 5669 5723 6531 +24568 5437 5511 5565 6530 +24569 1918 6368 1687 6859 +24570 4233 6450 4402 6578 +24571 1793 2056 2034 6073 +24572 1553 6391 1556 6667 +24573 2892 6095 2893 6742 +24574 465 6198 466 6428 +24575 1316 2828 1379 6491 +24576 5797 5798 25 6383 +24577 1686 2096 1917 6140 +24578 4991 4971 4997 6511 +24579 4432 4166 4269 6493 +24580 1730 1992 2067 6126 +24581 3185 3181 6210 6591 +24582 473 4368 474 6093 +24583 3270 6304 3272 6444 +24584 4050 4390 4282 5915 +24585 5701 5752 5611 7070 +24586 455 454 5761 7208 +24587 494 5762 495 7209 +24588 2224 6318 2219 7053 +24589 2560 2746 5942 6608 +24590 2126 6203 1860 6671 +24591 4888 4890 4889 5914 +24592 1189 1450 1317 6619 +24593 3803 3675 3936 6620 +24594 4142 4477 4078 6006 +24595 4004 6611 3665 6891 +24596 1518 6610 1179 6890 +24597 1519 6791 6528 7005 +24598 4005 6790 6529 7003 +24599 5434 5813 5376 6987 +24600 4981 5826 6763 6951 +24601 4824 4823 4822 5870 +24602 2068 1728 1991 6111 +24603 4672 5035 5095 7101 +24604 496 5694 5661 6528 +24605 5503 456 5536 6529 +24606 6264 6566 5798 6889 +24607 2195 326 2196 6287 +24608 3811 3977 6863 7119 +24609 3113 2768 5755 6896 +24610 2036 6326 1812 6493 +24611 3270 3186 6304 6591 +24612 2567 2847 2848 5847 +24613 1405 6728 6482 6775 +24614 4276 6167 4087 6490 +24615 4540 4493 6077 6190 +24616 2253 2256 2254 6834 +24617 1945 1673 2133 6460 +24618 4654 4608 6129 6411 +24619 5257 5339 5177 5923 +24620 1456 1255 1517 5998 +24621 5019 539 4766 5785 +24622 5463 6459 5578 6751 +24623 4520 4505 6307 6520 +24624 3507 2886 2491 6174 +24625 2691 2937 2929 5826 +24626 1222 6787 6111 6883 +24627 1922 1850 1725 5935 +24628 4385 4185 4090 6256 +24629 4842 4840 6087 6576 +24630 529 528 5412 6141 +24631 1537 1538 5803 6925 +24632 2175 5949 6806 6833 +24633 3223 3225 3123 6896 +24634 2428 2715 6389 7023 +24635 3067 3322 3323 6367 +24636 301 6350 6846 7081 +24637 5942 6666 5929 7013 +24638 5950 6863 3977 7119 +24639 4539 6077 556 6967 +24640 3283 2649 2789 6043 +24641 481 480 6423 6664 +24642 4842 6087 6424 6576 +24643 5081 5080 4783 6434 +24644 265 1569 1572 5946 +24645 4548 4523 5979 6999 +24646 4898 4807 6269 7163 +24647 2216 2194 2291 6287 +24648 1780 1667 2146 5958 +24649 2243 6397 2233 6625 +24650 3591 3645 3623 6894 +24651 3778 3879 2660 5916 +24652 2675 2677 3145 6536 +24653 3701 3873 3812 6807 +24654 236 3629 3658 6362 +24655 5005 6236 5003 6799 +24656 4430 6350 6225 6579 +24657 1399 418 2508 5919 +24658 510 6153 6443 6625 +24659 1712 6000 1974 6864 +24660 2192 2132 1750 6537 +24661 2151 5977 1906 6836 +24662 4857 5944 6028 7037 +24663 5930 6674 3963 7044 +24664 4341 4025 4171 6396 +24665 1809 1810 1673 6460 +24666 6182 6508 6180 6845 +24667 5316 5006 4987 5997 +24668 6341 6635 6127 7131 +24669 2892 3210 6095 6742 +24670 4673 5347 4670 5918 +24671 2302 2329 2358 6518 +24672 3073 2983 2439 6013 +24673 28 5899 503 6449 +24674 3925 4007 3774 6873 +24675 1288 1439 1521 6874 +24676 3365 6353 3493 6447 +24677 4855 6299 4856 7211 +24678 1365 6675 6759 6865 +24679 3851 6676 6760 6866 +24680 4222 4119 5808 6436 +24681 296 297 6379 6935 +24682 3299 3408 3528 6480 +24683 1799 1716 1935 6278 +24684 4203 4111 6081 6706 +24685 4120 5756 4215 7100 +24686 4396 6192 4184 6501 +24687 5171 5346 5134 7197 +24688 4849 6265 4678 7159 +24689 2032 1773 2065 6029 +24690 2601 6161 3016 7168 +24691 4201 4382 4069 6556 +24692 3020 2680 2679 5879 +24693 215 6190 3624 6642 +24694 2326 2298 2350 6234 +24695 4108 4424 4198 5848 +24696 3307 3531 3306 6455 +24697 3513 5883 6542 7173 +24698 436 3309 435 5894 +24699 3122 6454 3248 6966 +24700 5018 5863 4761 6815 +24701 5147 6332 6477 6565 +24702 4461 510 511 6290 +24703 3898 6631 6852 7190 +24704 4689 5066 4690 5937 +24705 4587 4574 4573 6188 +24706 3062 5864 3275 7198 +24707 2974 6043 2788 6678 +24708 504 5413 505 6318 +24709 616 615 6388 6389 +24710 3354 5839 3352 6567 +24711 4788 6215 4769 6792 +24712 4469 4119 5858 7170 +24713 4623 4988 5931 6792 +24714 464 26 6359 6756 +24715 3029 5843 3032 6665 +24716 3549 6919 3423 7158 +24717 4770 567 4988 6191 +24718 1563 1565 6303 6993 +24719 3647 3612 3592 7080 +24720 3201 6085 3007 6647 +24721 4458 4012 4150 5840 +24722 4595 5869 4972 7039 +24723 2378 2375 2457 6417 +24724 3050 2437 2430 6259 +24725 4566 5964 4564 7121 +24726 2820 5908 3160 6973 +24727 3634 5753 3632 7083 +24728 5122 5320 5187 6179 +24729 5183 6219 5137 6921 +24730 4915 5811 4685 7029 +24731 5432 5391 5371 6171 +24732 5769 6436 6026 7033 +24733 3606 5948 222 7086 +24734 4398 4202 5837 6599 +24735 1777 1900 303 6238 +24736 6264 6889 5754 7038 +24737 1410 6089 1228 6712 +24738 358 357 6048 6519 +24739 4409 4166 4115 6344 +24740 1353 1257 1504 6519 +24741 1886 1816 6187 6930 +24742 5828 6526 4991 6937 +24743 4758 4715 5774 6582 +24744 4247 494 6248 6474 +24745 2928 2930 3538 5791 +24746 6488 6811 5532 6959 +24747 6487 6812 5690 6960 +24748 3064 2889 2888 6103 +24749 2794 6258 2825 6486 +24750 3497 3450 3452 6280 +24751 1910 252 2169 5836 +24752 3573 3566 2843 6434 +24753 2549 2547 5941 6433 +24754 5055 4999 6008 6613 +24755 3865 5945 2449 6947 +24756 3855 2067 1992 6126 +24757 6278 6322 501 7079 +24758 3589 3642 3613 6592 +24759 1621 5803 1536 7017 +24760 4014 6328 4182 6991 +24761 6009 6876 6389 6976 +24762 6478 6962 5825 7063 +24763 2837 2838 2686 5862 +24764 2971 2992 3184 6210 +24765 4592 591 5901 6814 +24766 4503 4518 4521 6251 +24767 3744 6575 6503 7083 +24768 2014 6244 1726 6516 +24769 276 5950 3868 7082 +24770 3512 3513 5883 6542 +24771 2263 6331 2260 6581 +24772 2129 1931 1753 6026 +24773 2068 1991 1369 6111 +24774 6381 6413 566 6699 +24775 5387 6040 513 6586 +24776 5761 7025 4008 7208 +24777 5762 7024 1522 7209 +24778 5126 5815 5132 6753 +24779 4228 4417 4050 6909 +24780 3397 6277 3324 6753 +24781 2223 316 6061 7213 +24782 2651 2650 2977 6036 +24783 2301 2311 2336 6309 +24784 4317 6027 6942 6964 +24785 350 2222 349 6209 +24786 635 634 5767 6416 +24787 4809 5309 6481 6799 +24788 1187 6476 1309 6585 +24789 3575 2834 3368 6542 +24790 3373 6004 3372 6652 +24791 5530 6534 5479 6603 +24792 5637 5688 6533 6602 +24793 3930 3962 3730 6783 +24794 1476 1244 1444 6780 +24795 5228 5128 5192 6277 +24796 624 4867 625 6608 +24797 3776 3905 6631 6907 +24798 5434 5402 5813 6987 +24799 2173 2068 1798 6467 +24800 2256 2259 305 6834 +24801 1911 1812 1644 6344 +24802 3287 3565 3453 6333 +24803 2587 1349 6413 6844 +24804 3313 3315 3431 6245 +24805 1698 1961 2179 6057 +24806 6488 6877 5522 6900 +24807 3634 3632 3585 7083 +24808 5763 6614 5890 7099 +24809 4023 4166 6326 6493 +24810 6151 6360 2121 6912 +24811 2265 304 6238 6581 +24812 431 2531 430 6051 +24813 3471 3385 3323 6367 +24814 4897 4600 5006 5824 +24815 4944 5072 6367 6908 +24816 4063 4219 4171 6671 +24817 3258 3467 3400 6411 +24818 1258 1507 1309 5995 +24819 2552 2549 5819 6433 +24820 3626 431 3598 6255 +24821 3049 2649 3283 6044 +24822 2445 6855 6189 7195 +24823 4431 4165 4114 6019 +24824 2518 3082 2391 6273 +24825 4083 6186 4200 7188 +24826 2512 3163 3165 5863 +24827 5533 6774 5444 7009 +24828 5691 6771 5602 7011 +24829 2447 5929 3946 7013 +24830 4612 4609 4834 6985 +24831 2800 5886 2484 6808 +24832 3747 3988 5945 6826 +24833 541 5894 5243 6515 +24834 2951 6137 3344 6789 +24835 1797 2111 2184 6396 +24836 489 6324 6794 7172 +24837 470 4322 6407 6524 +24838 4687 6058 4688 7088 +24839 4068 6176 7056 7057 +24840 4853 5108 4879 7030 +24841 1772 5958 1962 6918 +24842 5565 6611 5511 6811 +24843 5723 6610 5669 6812 +24844 5303 5312 5309 5917 +24845 2303 2319 5813 6777 +24846 463 5949 6863 7061 +24847 234 6409 235 6943 +24848 1282 1428 1424 6540 +24849 3768 3914 3910 6538 +24850 4272 4014 4410 6328 +24851 6427 6444 5265 6483 +24852 2949 5782 2950 6764 +24853 4944 6367 5072 7043 +24854 2501 2467 2469 5827 +24855 5042 4747 4748 6013 +24856 6283 6475 1685 6691 +24857 4577 4868 6282 6473 +24858 4981 5006 5826 6951 +24859 3182 3183 2723 6662 +24860 2015 1865 1782 6090 +24861 3267 6555 6035 7139 +24862 5200 4962 4899 6150 +24863 4640 4642 4641 6338 +24864 2645 2643 2644 5846 +24865 3906 3668 6784 6913 +24866 5561 5494 5459 6785 +24867 5719 5652 5617 6782 +24868 2778 3030 6274 6481 +24869 1854 6316 2043 6779 +24870 3068 6272 2636 6590 +24871 494 6629 6248 7209 +24872 1698 2020 6311 6527 +24873 1535 6756 275 7082 +24874 577 4577 4575 5981 +24875 4902 4898 4807 6269 +24876 5037 5014 5015 6259 +24877 5274 5071 5027 6065 +24878 1824 1979 1670 6118 +24879 5458 5533 6529 7003 +24880 5691 6528 5616 7005 +24881 241 1628 6575 6653 +24882 2115 5816 1763 6778 +24883 6640 6974 576 7014 +24884 5069 5064 5068 6339 +24885 295 2284 296 6100 +24886 4650 4612 4835 5765 +24887 376 377 2320 5901 +24888 2766 6124 2767 6551 +24889 5271 5267 4613 6332 +24890 1773 1846 2179 6057 +24891 1251 1500 1398 6699 +24892 4267 5982 4288 6734 +24893 450 5797 25 6505 +24894 4718 6246 4717 6755 +24895 1744 1794 2079 6034 +24896 5245 598 6754 7154 +24897 4938 6257 4940 6737 +24898 6531 6812 1441 7111 +24899 6530 6811 3927 7112 +24900 3889 6641 6539 6971 +24901 1403 6640 6541 6972 +24902 5004 4671 5059 5777 +24903 4074 4230 4363 6461 +24904 346 2312 347 6068 +24905 618 5862 4767 6885 +24906 2157 5996 1964 7176 +24907 485 486 6261 6464 +24908 3458 6182 3401 6668 +24909 3232 3316 3496 6074 +24910 1534 1532 1533 5922 +24911 4952 5087 4590 6361 +24912 581 5805 582 6499 +24913 1973 6114 1830 6468 +24914 5938 6670 5860 6754 +24915 549 5238 548 6044 +24916 508 5393 5424 6116 +24917 2428 6388 2426 6977 +24918 3763 5827 3820 6887 +24919 5758 4784 6763 7189 +24920 3954 6636 3684 6895 +24921 4997 6320 6511 6916 +24922 3203 1329 1407 6727 +24923 2329 2360 362 6518 +24924 6243 3304 6609 7102 +24925 4034 6138 4397 6615 +24926 5256 6007 5169 6612 +24927 4121 4193 4465 5996 +24928 6128 6666 5942 6749 +24929 2683 2681 2967 6761 +24930 569 570 5732 6482 +24931 5851 6097 6686 6687 +24932 5852 6098 6684 6685 +24933 5429 603 5397 6325 +24934 5736 6458 558 6694 +24935 2138 1852 1768 6407 +24936 1830 1943 1646 6468 +24937 5793 6401 5754 7038 +24938 3665 3874 6891 6932 +24939 1388 6890 1179 6931 +24940 3841 3963 6674 7044 +24941 5320 5360 5348 6300 +24942 2316 2298 6052 6856 +24943 1790 6138 1696 6988 +24944 4392 4387 4138 6033 +24945 2047 2093 1740 5756 +24946 5266 5032 4610 6106 +24947 3533 2551 2550 6031 +24948 3108 3111 3109 5943 +24949 2714 6221 3888 7110 +24950 5549 6676 5443 6760 +24951 5601 5707 6675 6759 +24952 4088 6206 4277 6838 +24953 4456 4038 4437 6142 +24954 5178 5972 5262 6813 +24955 5894 6472 2918 6696 +24956 1911 2081 6344 6817 +24957 5305 5133 6245 6618 +24958 1580 6308 1588 7051 +24959 2980 2747 2678 6920 +24960 3476 6024 3550 6239 +24961 5636 6955 5745 6956 +24962 517 6081 6319 6834 +24963 4075 4414 4260 5885 +24964 2294 1357 2293 6572 +24965 3484 6557 3312 6986 +24966 5756 6578 4215 7100 +24967 3623 6261 219 6894 +24968 3501 5957 3576 6748 +24969 303 1900 302 6579 +24970 4920 4841 4919 6104 +24971 440 2680 2571 6338 +24972 3062 6789 5864 7198 +24973 4481 4133 6133 6558 +24974 369 2330 368 6135 +24975 439 3602 5979 7048 +24976 2166 5968 1908 6988 +24977 4829 5873 4609 6908 +24978 5443 6760 6676 6866 +24979 5601 6759 6675 6865 +24980 2908 3236 3560 5892 +24981 2231 315 6360 6822 +24982 5673 5623 5741 6722 +24983 517 5388 6184 6948 +24984 6525 6537 5802 7141 +24985 4652 5264 5248 5842 +24986 485 6261 6462 6464 +24987 2972 6400 2971 6621 +24988 5810 6509 6124 7041 +24989 2564 2743 2803 6484 +24990 4255 5954 4079 6547 +24991 5058 4798 4800 6237 +24992 5200 6150 4899 7155 +24993 2597 2599 3308 6438 +24994 5039 4642 4640 5868 +24995 3728 3811 3977 6863 +24996 439 5979 2571 7161 +24997 3558 3278 3063 5864 +24998 1309 5995 1507 6585 +24999 3404 3402 6180 6508 +25000 4789 4950 5100 5978 +25001 305 1952 304 6081 +25002 3698 3985 3802 6830 +25003 2104 1984 1742 6152 +25004 2323 352 351 6318 +25005 2298 2347 6052 7007 +25006 1849 1989 1659 6206 +25007 2543 6003 6489 6630 +25008 569 568 5766 6689 +25009 2116 5853 1803 6950 +25010 1818 1930 1681 6663 +25011 5205 6553 5207 7197 +25012 5174 5319 5196 6024 +25013 237 238 6165 6545 +25014 2974 2734 6042 6678 +25015 6208 2903 6697 6969 +25016 5888 7064 2387 7195 +25017 4204 4111 4233 6140 +25018 4874 4700 6378 7204 +25019 2237 2232 2227 6443 +25020 5244 6670 5938 6754 +25021 5728 6802 6649 7012 +25022 5570 6801 6648 7010 +25023 586 5011 587 6470 +25024 2424 5785 2423 7048 +25025 5979 6798 537 6999 +25026 3558 5864 3063 6560 +25027 4589 4578 4577 5981 +25028 2025 1955 1730 7026 +25029 2892 3210 2891 6095 +25030 3708 6820 6126 6882 +25031 3144 3319 3146 6199 +25032 3262 2879 3328 6380 +25033 5489 5467 6584 6821 +25034 1537 1626 1538 6925 +25035 5928 6544 4048 6952 +25036 2237 6153 312 6625 +25037 5625 6583 5647 6788 +25038 5869 6511 6320 6916 +25039 5208 5211 4652 5770 +25040 5062 4894 4752 5925 +25041 3083 6665 3032 7168 +25042 463 26 5950 6359 +25043 4620 4981 6763 6951 +25044 2440 3118 2591 5857 +25045 3311 3424 6618 6986 +25046 1974 1647 5999 6000 +25047 4156 4438 6225 7056 +25048 1787 6806 6359 6884 +25049 2460 6229 2488 6680 +25050 4056 4192 4319 6079 +25051 6450 6995 4402 7100 +25052 1994 2052 1764 5788 +25053 4596 4972 4595 5869 +25054 3957 3737 6876 7023 +25055 4777 4900 4632 6457 +25056 2736 2740 6035 6678 +25057 2991 3158 5835 6824 +25058 2220 2224 2217 6479 +25059 3152 3156 6087 6744 +25060 4660 6522 6227 6965 +25061 3083 3124 2537 5795 +25062 576 577 6125 6473 +25063 4664 4973 6252 7022 +25064 1305 1361 1240 6722 +25065 4096 4338 6178 6600 +25066 5304 4792 4772 5779 +25067 1391 6541 1403 6640 +25068 3877 6539 3889 6641 +25069 4748 6013 4746 6606 +25070 4641 4992 4994 6338 +25071 1277 6860 6088 7040 +25072 2229 6119 6822 7180 +25073 3415 6626 6227 7001 +25074 622 5310 4772 6392 +25075 2682 6351 2681 6761 +25076 4780 5105 4949 5888 +25077 3073 2953 6013 6816 +25078 4449 4181 4390 5915 +25079 3630 3593 3629 6123 +25080 2639 6010 2544 6767 +25081 1754 5872 1890 6525 +25082 2625 3034 3037 6398 +25083 3474 6551 5983 7124 +25084 3747 3953 3988 6826 +25085 2777 6491 6274 7008 +25086 2669 3259 3326 6332 +25087 3468 3342 6023 6573 +25088 5809 6497 6417 7098 +25089 3635 3637 418 7090 +25090 214 1539 215 6642 +25091 482 6078 481 6422 +25092 359 6309 2356 6793 +25093 4861 4859 4936 5801 +25094 3480 3416 6965 7001 +25095 2642 2628 6104 6656 +25096 2495 421 3031 6764 +25097 4273 4119 4459 5808 +25098 4953 4697 4918 6402 +25099 3298 5828 2955 7179 +25100 3625 3598 226 6308 +25101 1727 2018 5982 6601 +25102 5463 6459 6584 6904 +25103 6458 6583 5621 6903 +25104 479 478 6194 6305 +25105 3790 3706 6765 7061 +25106 571 5223 572 6274 +25107 1399 5919 2508 6848 +25108 2467 2469 5827 6639 +25109 3302 2921 5758 7077 +25110 519 6579 6238 6581 +25111 1834 2191 1679 7118 +25112 2898 3346 2840 5986 +25113 2153 1833 5989 6691 +25114 4397 6198 4419 6884 +25115 4343 4018 4489 5763 +25116 3266 5925 3370 6795 +25117 3694 6440 3900 7061 +25118 1519 6528 1375 7005 +25119 4005 6529 3861 7003 +25120 2797 2957 3469 6217 +25121 3259 3287 3325 6333 +25122 4144 6032 4373 6355 +25123 4176 4239 4015 5977 +25124 559 5736 558 6694 +25125 5439 5512 5483 6773 +25126 5670 5641 5597 6770 +25127 3230 5824 3244 7020 +25128 424 3599 3628 6739 +25129 2514 6366 2774 6855 +25130 4674 5064 5069 6382 +25131 3781 3897 6509 6723 +25132 3638 6642 6809 7017 +25133 1304 1301 1220 6997 +25134 4323 4167 4081 6196 +25135 2682 3328 2849 6351 +25136 5084 5118 5083 6393 +25137 2829 3236 2908 6657 +25138 2647 2652 3328 6177 +25139 1973 6468 1830 6740 +25140 2873 6216 3485 6910 +25141 4697 5078 4918 6258 +25142 3477 6063 3484 6986 +25143 5120 5054 5033 5990 +25144 2835 3170 2832 6552 +25145 1655 1866 6376 6934 +25146 4729 4730 5789 6523 +25147 5360 5146 5226 6053 +25148 4839 6224 4675 7123 +25149 4460 4042 5871 6858 +25150 6345 6618 4626 6986 +25151 2532 3049 429 6159 +25152 2590 2800 2583 6446 +25153 5104 5983 4934 6606 +25154 4260 5885 4414 7092 +25155 2694 3337 3250 5860 +25156 466 6198 4183 7157 +25157 3062 3063 3275 5864 +25158 5798 6566 2199 7169 +25159 5297 5298 6180 6513 +25160 524 6354 525 6379 +25161 4025 4482 4226 6396 +25162 6539 6666 3683 7058 +25163 577 4575 578 6366 +25164 2658 3204 3034 7052 +25165 1659 6806 6337 6833 +25166 5286 6210 5249 7214 +25167 519 6331 6579 6581 +25168 1258 1309 1470 5995 +25169 3202 6086 3078 7103 +25170 3525 3106 2760 6786 +25171 2546 2891 3470 6495 +25172 1273 6703 1188 6732 +25173 3759 6702 3674 6731 +25174 1532 5922 1534 6756 +25175 2614 5964 2796 7073 +25176 1844 6310 1890 6733 +25177 4573 4867 4587 6240 +25178 5258 5265 5254 6427 +25179 4037 4350 4157 6597 +25180 2841 2708 3217 6191 +25181 4132 6152 6535 6944 +25182 573 572 6491 6897 +25183 4388 4103 4393 6501 +25184 4342 4369 4084 6113 +25185 2243 2241 2238 6397 +25186 366 2513 2512 5863 +25187 2260 6581 6331 6776 +25188 5097 4942 5794 7035 +25189 2773 6189 2445 6855 +25190 3708 3750 6126 6820 +25191 1757 1864 2145 6093 +25192 5355 5302 5188 6023 +25193 6251 6365 3651 6928 +25194 1597 256 1600 6779 +25195 5347 5918 5302 6899 +25196 4187 6114 4448 6607 +25197 4017 4194 4344 6385 +25198 1690 2081 1878 6132 +25199 2821 2822 6915 7206 +25200 6261 6894 5796 7164 +25201 439 7048 5979 7161 +25202 1580 1578 1577 6418 +25203 5583 530 531 6862 +25204 2570 2569 5984 7045 +25205 3581 3441 3402 6180 +25206 467 4245 468 6847 +25207 4685 4683 6060 6700 +25208 6128 6608 6240 6957 +25209 2848 2847 2846 5847 +25210 1746 1874 1861 5952 +25211 4757 4715 4714 5774 +25212 3489 6219 3581 6508 +25213 3631 6233 241 6575 +25214 4435 4130 4331 5953 +25215 1861 5952 2125 7130 +25216 2200 5798 2199 7169 +25217 4542 4492 4535 6169 +25218 1265 6890 6594 7199 +25219 3751 6891 6593 7200 +25220 2309 2374 2323 5793 +25221 4592 5901 590 6692 +25222 1263 1516 1336 6637 +25223 4368 4405 4141 6494 +25224 2734 2735 2736 6399 +25225 5398 5425 588 6045 +25226 272 1549 271 6428 +25227 518 6405 6581 6834 +25228 2206 319 2207 5797 +25229 1685 6475 6283 6950 +25230 4732 4711 4715 6451 +25231 6780 6841 5642 7114 +25232 6783 6840 5484 7113 +25233 3592 3616 3647 6014 +25234 4527 542 4557 6121 +25235 1907 315 2167 6061 +25236 2212 5995 2195 6572 +25237 517 6319 6405 6834 +25238 358 6519 6048 6793 +25239 608 5854 4732 6582 +25240 4841 4989 4946 7106 +25241 3454 2543 6489 6630 +25242 3807 2198 2209 3935 +25243 5240 4761 600 5939 +25244 4580 4611 4586 6448 +25245 1579 1581 1577 6418 +25246 4706 4879 4704 7030 +25247 560 561 5830 6582 +25248 3730 6783 3962 6784 +25249 1244 6780 1476 6781 +25250 4874 5116 4828 7204 +25251 2679 442 3069 5879 +25252 342 6452 341 6762 +25253 2057 6616 1844 6733 +25254 1879 2122 1743 6211 +25255 3620 3600 237 6362 +25256 4220 4454 4351 5891 +25257 3352 3354 3353 5839 +25258 5103 4648 5043 6526 +25259 3419 3547 3149 5923 +25260 4248 4275 4085 6658 +25261 3381 3574 3467 6477 +25262 5150 6437 4690 6670 +25263 5725 6533 571 6758 +25264 1187 6585 1325 6741 +25265 3708 3750 3855 6126 +25266 4594 550 6916 7039 +25267 3083 5795 3084 6665 +25268 4448 4391 4049 6120 +25269 2398 2530 2399 7096 +25270 3298 2956 2955 5828 +25271 3762 3704 3841 6674 +25272 5606 5737 6705 6984 +25273 5579 6704 5448 6983 +25274 2589 2480 2778 5917 +25275 4873 5962 4700 7204 +25276 1630 2126 1860 6671 +25277 3028 3026 2483 6237 +25278 583 4731 584 5822 +25279 1574 1571 1576 6327 +25280 3414 6227 3415 7102 +25281 4891 6070 5008 6646 +25282 3284 3442 6343 6795 +25283 484 4186 6465 6574 +25284 3963 5930 3779 6716 +25285 2736 3267 3263 6035 +25286 3485 3579 3568 6910 +25287 5240 4690 5066 5937 +25288 552 553 6445 6739 +25289 5749 6703 6649 6732 +25290 5591 6702 6648 6731 +25291 2630 6148 2632 7161 +25292 5530 5479 5574 6603 +25293 5637 5732 5688 6602 +25294 4129 4474 5838 7095 +25295 3359 3349 3380 6288 +25296 4802 4804 5055 6008 +25297 1562 1559 1567 6442 +25298 3062 3063 5864 6789 +25299 2429 3543 2430 5893 +25300 5009 5168 6162 6717 +25301 1826 5844 6992 7176 +25302 6072 6461 4177 6622 +25303 558 4561 5768 7089 +25304 4678 6265 4677 7159 +25305 5930 6401 32 6674 +25306 4280 6186 4083 6605 +25307 2739 2736 3569 6399 +25308 1278 5875 2470 7096 +25309 4318 4076 4264 5812 +25310 275 2161 276 5950 +25311 3525 2760 5985 6786 +25312 3424 3313 6245 6986 +25313 6303 7080 1570 7126 +25314 2824 6122 2996 6431 +25315 3674 3838 4000 7208 +25316 1352 1514 1188 7209 +25317 3750 3853 6369 6820 +25318 5133 4844 4845 6245 +25319 4539 4508 6077 6967 +25320 3718 3778 3881 5916 +25321 574 6637 573 6746 +25322 2565 2567 2643 5846 +25323 2060 2137 6205 7032 +25324 3606 3659 5948 6672 +25325 4930 6095 4931 6495 +25326 3746 5797 3797 6882 +25327 1683 1845 1802 6410 +25328 26 464 6233 6653 +25329 3459 3494 6343 6965 +25330 2549 5941 2548 6660 +25331 271 2166 272 5968 +25332 4190 4083 4407 6187 +25333 4993 6028 7035 7037 +25334 1386 1420 1238 6701 +25335 475 474 6327 6365 +25336 6446 6808 2583 6824 +25337 2058 1713 1843 6373 +25338 4914 4915 4685 7029 +25339 3578 3568 3579 6007 +25340 4921 6522 4660 6965 +25341 4753 4751 5323 6480 +25342 1765 1996 2094 5808 +25343 3802 3946 2447 5929 +25344 5020 5324 5333 6390 +25345 3264 6555 6046 6795 +25346 1989 6206 1717 6833 +25347 3176 3175 3146 5801 +25348 2797 6236 3027 7078 +25349 4149 4357 5802 6858 +25350 2265 303 2263 6581 +25351 4991 5828 4971 6511 +25352 4350 4037 4473 6532 +25353 3022 2740 2977 6036 +25354 4251 4020 4146 6386 +25355 5197 5188 5198 6471 +25356 4948 4636 4578 5778 +25357 4063 6146 4303 6205 +25358 2599 3242 2946 6150 +25359 1909 1789 2168 6800 +25360 3980 3699 6873 7009 +25361 1494 1213 6874 7011 +25362 2878 3239 2581 6008 +25363 4993 4638 4990 5893 +25364 5032 4586 4610 6448 +25365 3435 3417 3436 6298 +25366 2885 3150 3490 6172 +25367 3262 2497 6380 6761 +25368 5145 4966 6003 6557 +25369 5081 6137 5222 6643 +25370 4531 6362 4504 6430 +25371 4317 4143 6027 6964 +25372 5932 6686 3967 6924 +25373 4444 5928 4189 7131 +25374 1975 1655 1811 6064 +25375 2186 5940 1756 6946 +25376 2303 5813 2360 6518 +25377 3151 2700 3475 5786 +25378 249 1617 1527 6324 +25379 4609 4829 4944 5873 +25380 1746 5952 2136 7130 +25381 229 3651 6251 6365 +25382 5238 4972 4691 6044 +25383 1475 1290 6499 6729 +25384 3842 3790 6765 6862 +25385 4939 5828 4991 6937 +25386 2018 2156 1727 5982 +25387 2729 2924 2964 7073 +25388 6533 6602 1235 6759 +25389 3721 6534 6603 6760 +25390 4126 4293 4485 6156 +25391 1513 1348 1799 6278 +25392 3988 5945 6826 6830 +25393 3109 2764 3110 5902 +25394 5380 5405 6285 6518 +25395 3463 5873 3398 6870 +25396 1994 1723 2052 5788 +25397 3207 3237 2815 5870 +25398 575 5998 576 6974 +25399 302 1900 2042 6350 +25400 1277 1228 1378 6088 +25401 4353 4083 6203 6605 +25402 2067 2172 1730 6126 +25403 3508 3544 2791 5972 +25404 4853 4682 4852 6267 +25405 468 6362 6323 6391 +25406 1817 1881 1693 5928 +25407 1636 1842 1982 5915 +25408 1917 1820 1702 6441 +25409 3597 3632 3664 5781 +25410 4836 4584 4837 6340 +25411 5065 6289 5064 7167 +25412 4222 4470 4119 6436 +25413 1852 2088 1768 6271 +25414 5371 5391 5387 6171 +25415 515 4204 4254 5940 +25416 4372 4151 4036 6057 +25417 3090 3245 2842 5931 +25418 3221 3551 3112 7142 +25419 470 471 6112 6409 +25420 5318 5180 5839 6813 +25421 4028 4217 5895 6577 +25422 1264 6111 1222 6787 +25423 3270 3186 3185 6304 +25424 3618 3646 3591 6894 +25425 5152 5898 4873 7204 +25426 1616 1608 218 6262 +25427 1844 6310 1682 6525 +25428 2335 2310 6321 6334 +25429 3551 5975 3112 7142 +25430 4105 4154 4397 6337 +25431 1209 5852 1457 7004 +25432 3695 5851 3943 7002 +25433 1719 2017 1813 6622 +25434 4202 6118 4267 6734 +25435 597 596 4749 5825 +25436 4934 4933 5030 5983 +25437 2453 5805 2454 6927 +25438 5205 5170 5207 6553 +25439 4504 6430 6123 7076 +25440 1624 1321 1621 7017 +25441 360 2356 359 6589 +25442 573 6746 6637 6897 +25443 6127 7131 4442 7203 +25444 5953 6420 6669 7129 +25445 2951 2942 3338 6137 +25446 3083 2537 3084 5795 +25447 6274 6491 2777 6968 +25448 3801 3713 3791 6907 +25449 255 1603 254 6463 +25450 6227 6965 3416 7001 +25451 226 225 1586 6306 +25452 3276 3202 3308 6919 +25453 2480 2486 2478 5917 +25454 5929 6830 6392 7174 +25455 2056 1793 2082 6377 +25456 4361 4123 4200 6029 +25457 4737 4996 585 6080 +25458 1492 1453 6640 7014 +25459 4583 5116 5109 6380 +25460 4507 6165 4498 7136 +25461 4347 4074 4170 6270 +25462 5005 5003 5058 6799 +25463 4377 6271 4140 6524 +25464 4629 5320 5122 6195 +25465 5843 3032 6665 7168 +25466 5242 5243 541 5894 +25467 4800 5025 4773 5886 +25468 3281 2962 3014 5918 +25469 5406 5434 5376 6987 +25470 5389 6266 5426 7154 +25471 2452 2451 2475 6088 +25472 2327 6171 2320 6679 +25473 3522 6101 3190 6455 +25474 3577 3441 3412 6181 +25475 3380 3382 6091 6747 +25476 3549 3425 3423 6919 +25477 2078 1745 1795 6133 +25478 4594 4596 4595 5869 +25479 3714 6887 5884 7075 +25480 6074 6276 5231 7155 +25481 3077 3076 3209 6390 +25482 3048 3101 427 6963 +25483 6130 7166 6289 7167 +25484 5044 5043 4779 5823 +25485 4523 4519 4500 6253 +25486 5151 4751 4892 5926 +25487 2728 2964 2922 7073 +25488 2836 3147 3153 6437 +25489 3901 6666 3738 7058 +25490 3430 3441 3581 6181 +25491 4346 4030 4169 6315 +25492 4618 4619 4982 5800 +25493 1918 2095 1687 6368 +25494 3347 3232 3047 6710 +25495 1675 2031 2185 6113 +25496 4227 7131 6341 7203 +25497 4407 4051 4190 7188 +25498 4083 4190 4341 6187 +25499 3532 3371 3089 5832 +25500 3567 2830 3164 5882 +25501 5223 5309 572 6274 +25502 5768 3638 6642 6809 +25503 1666 1781 1984 6152 +25504 475 6327 6260 6365 +25505 4778 4730 4785 5889 +25506 6227 6965 6522 7102 +25507 1696 2013 1787 6884 +25508 4461 511 4231 6290 +25509 5140 5139 4617 6084 +25510 620 619 5081 6434 +25511 2787 2901 6154 6857 +25512 4903 4970 5784 7123 +25513 2800 2583 6446 6808 +25514 2856 2727 2766 6188 +25515 4090 6312 4377 6524 +25516 4053 4197 6076 7087 +25517 3624 3643 3590 6190 +25518 3705 3796 3839 6720 +25519 4176 4043 4447 5967 +25520 301 1853 6145 6350 +25521 544 5338 5322 5903 +25522 539 540 4766 6515 +25523 2751 5916 2684 7000 +25524 5571 6539 623 6666 +25525 4097 4475 4348 5960 +25526 1833 1685 1781 6475 +25527 1899 2191 1779 7118 +25528 5286 5363 5210 6210 +25529 4326 4033 4224 5989 +25530 3660 425 3628 5833 +25531 3291 3294 3486 6339 +25532 5753 6503 6233 7083 +25533 5081 4783 5831 6434 +25534 2335 2306 2334 6334 +25535 5637 5724 5707 6759 +25536 5479 5566 5549 6760 +25537 4459 4054 4146 6286 +25538 1227 1347 6903 6954 +25539 3833 6904 3712 6953 +25540 3321 6117 2616 7148 +25541 1879 1743 2127 6211 +25542 2626 3241 3099 6131 +25543 1707 6349 1863 7201 +25544 1443 6649 6802 7012 +25545 3929 6648 6801 7010 +25546 5434 5402 5376 5813 +25547 4615 5359 5321 6063 +25548 5261 5340 5187 6179 +25549 1934 1714 1800 6369 +25550 4865 5805 581 6523 +25551 1592 1593 1589 6423 +25552 3577 3501 3403 5957 +25553 1429 1276 1355 6458 +25554 2106 2036 1662 6493 +25555 1859 1736 1881 6341 +25556 4622 4762 4775 6364 +25557 2067 1800 2172 6369 +25558 4809 5167 4811 5927 +25559 4638 5920 5893 6617 +25560 5101 5857 4945 7106 +25561 3981 1800 2067 6369 +25562 5608 6802 5726 6931 +25563 5450 6801 5568 6932 +25564 5205 5207 6049 7197 +25565 5220 5332 5090 6082 +25566 630 4863 631 5820 +25567 4998 5001 4806 5864 +25568 6393 7124 6235 7125 +25569 3093 3261 3504 6361 +25570 4688 4687 4689 6058 +25571 5055 5001 4999 6613 +25572 4181 4116 4411 6000 +25573 2794 2753 2823 6258 +25574 1706 6406 5951 7069 +25575 336 2267 335 6241 +25576 3728 3977 5950 6863 +25577 2522 5775 2960 6695 +25578 2376 2375 2378 6417 +25579 3714 3864 6887 7075 +25580 440 2571 439 5979 +25581 6416 6519 1218 6902 +25582 3115 3117 3116 6158 +25583 518 4203 517 6081 +25584 5365 5146 6053 7043 +25585 2429 5893 2430 7045 +25586 2897 5779 2839 7175 +25587 1371 1477 6499 7205 +25588 4622 4775 5102 6062 +25589 4076 4410 4264 5812 +25590 1632 5871 2188 6880 +25591 1696 2181 2013 6138 +25592 2431 6028 2819 7045 +25593 4866 4583 4623 7140 +25594 4712 4713 5866 6982 +25595 3688 3848 7054 7190 +25596 1596 1604 1602 6463 +25597 2931 2663 6394 7068 +25598 2456 6933 2450 7117 +25599 2013 6337 1659 6806 +25600 2449 3969 3865 6947 +25601 3447 2885 3490 6173 +25602 1190 1447 6632 7137 +25603 5230 5341 5342 5993 +25604 2564 6062 6484 6861 +25605 492 5715 6788 6881 +25606 4210 4022 4160 6733 +25607 4519 4504 468 6362 +25608 4566 4621 6484 7121 +25609 248 5804 1627 6925 +25610 2552 5972 2550 6433 +25611 3334 5771 3333 7144 +25612 6291 6714 4155 7028 +25613 4400 4147 4045 6420 +25614 2662 6392 7174 7175 +25615 1222 1264 1369 6111 +25616 3355 3353 3356 5980 +25617 2421 2445 2444 5889 +25618 2894 3009 3013 6069 +25619 1764 5788 2052 6880 +25620 3399 3384 3515 6342 +25621 4078 4266 4307 6006 +25622 2136 1861 2125 7130 +25623 5235 6182 5297 6845 +25624 1724 2054 1837 6175 +25625 2572 2377 2376 6886 +25626 4906 5759 4870 7147 +25627 4928 4858 6010 6495 +25628 2550 3055 2912 6031 +25629 3625 6092 3586 6715 +25630 3836 4008 5761 7025 +25631 1522 5762 1350 7024 +25632 1958 2086 1770 6019 +25633 1211 6655 1268 6850 +25634 3697 6654 3754 6852 +25635 1654 2132 1976 6537 +25636 3504 3199 3511 6500 +25637 3639 5988 3611 7086 +25638 1257 1478 1294 7107 +25639 2914 6887 3864 7075 +25640 2444 3024 2952 5789 +25641 3025 2510 2488 6981 +25642 383 2488 384 5822 +25643 3119 2459 2409 5823 +25644 1260 5804 1311 6883 +25645 30 558 6458 7205 +25646 2994 2995 2993 6431 +25647 5344 5258 5297 6182 +25648 4818 5026 6036 6502 +25649 2112 1865 1726 6556 +25650 1589 6664 6423 6871 +25651 30 582 5919 7205 +25652 2462 385 2487 6229 +25653 2264 6405 2254 6581 +25654 4276 4151 6322 6490 +25655 2011 2179 1846 6527 +25656 2969 3180 3041 6621 +25657 1645 2082 2176 6588 +25658 2840 3346 3344 5986 +25659 1790 1959 1696 6138 +25660 4846 4938 6257 6937 +25661 4578 4636 4576 5778 +25662 4450 5895 4371 6734 +25663 5839 6813 5972 6843 +25664 5261 5162 5034 6166 +25665 214 1536 1539 7017 +25666 6283 6950 6475 7185 +25667 4818 6035 4808 6502 +25668 1493 7005 6771 7071 +25669 5950 6756 5922 7082 +25670 469 4519 468 6253 +25671 3648 3594 3620 6165 +25672 5835 6446 574 6746 +25673 2311 2301 2355 6141 +25674 4331 4479 4162 5807 +25675 1945 1836 2091 6461 +25676 5245 5244 5938 6754 +25677 5069 4907 5218 5912 +25678 4862 4563 4579 6977 +25679 452 5557 6821 6895 +25680 3898 6631 3804 6852 +25681 4637 5037 6259 7035 +25682 3869 6534 3721 6760 +25683 1383 6533 1235 6759 +25684 4233 4402 6450 6995 +25685 1353 1196 1478 6571 +25686 1219 6453 6232 6809 +25687 1806 6614 2108 7122 +25688 5675 6561 5706 6655 +25689 5517 6562 5548 6654 +25690 3622 6051 3642 6592 +25691 2589 6808 5917 6968 +25692 4394 4095 4192 5991 +25693 4047 4353 4171 6203 +25694 3323 3385 3384 6367 +25695 1590 1585 1584 6305 +25696 2925 2921 2838 5862 +25697 3285 3265 6021 6555 +25698 1277 1334 6088 6860 +25699 5376 5813 5402 7066 +25700 3551 3108 3110 5975 +25701 1356 6476 1187 6766 +25702 5942 6666 623 6835 +25703 2751 2684 2752 7000 +25704 3497 3452 3333 7144 +25705 2906 2835 3575 5914 +25706 4619 5800 4618 6763 +25707 2826 2825 6258 6657 +25708 4844 5126 4869 6837 +25709 2338 2369 380 6045 +25710 3626 6255 3625 6715 +25711 3294 3449 3554 5765 +25712 3320 3363 3321 6106 +25713 4753 4740 5062 6046 +25714 5214 6330 5158 6843 +25715 2311 327 326 6141 +25716 1294 1478 6571 7107 +25717 4015 4239 4483 5817 +25718 2718 2716 2717 5869 +25719 300 301 6145 6846 +25720 2091 1836 1633 6386 +25721 1847 2178 2010 5959 +25722 1839 1951 1703 6254 +25723 4307 4165 4404 6149 +25724 2524 5774 6933 7117 +25725 526 4243 525 6379 +25726 3643 6190 216 7062 +25727 1274 6629 1468 6881 +25728 3913 3807 2198 7169 +25729 4282 4086 4328 5906 +25730 1229 6587 5850 6810 +25731 1222 1369 1512 6111 +25732 4537 6190 489 6642 +25733 1685 2028 6475 6950 +25734 3762 3915 6459 6674 +25735 3136 6267 3139 7182 +25736 3350 3451 6281 6507 +25737 374 2366 373 6001 +25738 5018 4990 602 5920 +25739 4562 4535 4492 5781 +25740 4266 6006 4477 6475 +25741 4048 5928 4229 6544 +25742 2470 2499 2398 5875 +25743 2401 3121 2433 5850 +25744 4821 4692 5149 6042 +25745 1843 6373 6120 6658 +25746 544 5903 5322 6832 +25747 3379 6091 6477 6565 +25748 3998 3708 3855 6126 +25749 1722 1836 2105 6386 +25750 2887 6378 6177 7016 +25751 2772 3121 2401 5850 +25752 2240 2242 2238 6397 +25753 2395 5810 2397 7108 +25754 3427 6002 3361 7036 +25755 5704 5716 503 6766 +25756 4230 6072 4045 6460 +25757 3131 2417 3130 6083 +25758 3198 2520 3199 5981 +25759 2524 6933 2456 7117 +25760 312 6153 2237 7180 +25761 4889 4888 5914 7088 +25762 3399 6342 3565 6411 +25763 4354 5769 4057 6436 +25764 3336 5771 3334 7144 +25765 3677 6521 3952 6735 +25766 2283 2285 2281 6294 +25767 5988 6963 6916 7039 +25768 454 453 6250 6636 +25769 4548 537 4523 6999 +25770 1728 2068 2173 6111 +25771 3776 6631 6497 6721 +25772 3009 3007 3008 6069 +25773 6126 6820 451 6882 +25774 1328 1270 1814 6685 +25775 1815 3814 3756 6687 +25776 2534 6214 2535 7127 +25777 6111 6787 491 6883 +25778 2622 6345 3311 7158 +25779 4991 6320 4647 6526 +25780 1224 5830 7040 7107 +25781 3584 3637 3635 7090 +25782 5370 6628 6185 6948 +25783 1545 6169 239 6698 +25784 4633 4934 5104 5983 +25785 3043 3033 3042 5772 +25786 4509 4552 4502 5948 +25787 3289 3503 3117 5814 +25788 3323 3405 3067 6367 +25789 215 216 6190 6794 +25790 5020 5325 5324 6390 +25791 4860 4937 4859 6199 +25792 2089 1957 1663 6315 +25793 2230 6209 2221 6822 +25794 3550 3534 3526 6239 +25795 5331 5147 5202 6477 +25796 541 542 5242 5894 +25797 2403 2402 2787 6470 +25798 4161 4043 4330 5967 +25799 5274 5212 5196 5787 +25800 1508 2499 1364 6848 +25801 6549 6780 5642 7114 +25802 6548 6783 5484 7113 +25803 1344 1500 1251 6016 +25804 3816 3696 6840 7113 +25805 1330 1210 6841 7114 +25806 2662 2840 6392 7175 +25807 2501 2522 2375 6417 +25808 3993 5922 3703 7119 +25809 3358 3430 3581 6219 +25810 4017 5764 4356 6663 +25811 3355 5980 3471 6300 +25812 4764 4763 4765 6263 +25813 5839 6738 6496 6843 +25814 5150 4743 5861 6670 +25815 336 2351 2313 6241 +25816 3283 2716 3048 6044 +25817 5115 4703 4930 6095 +25818 3002 3000 6451 7160 +25819 3879 2659 2660 5916 +25820 4478 4219 4332 6204 +25821 5240 5066 4761 6815 +25822 1843 1677 6373 6658 +25823 472 4405 473 5946 +25824 1569 1568 1572 6094 +25825 2920 3035 2966 6089 +25826 5636 5745 5733 6956 +25827 4070 4270 4483 5817 +25828 5875 6499 1223 6848 +25829 1799 2069 2174 6278 +25830 5108 4566 4832 5847 +25831 4560 4526 4499 5796 +25832 3253 2497 3247 6966 +25833 1491 1325 6585 6741 +25834 3372 3422 3375 6347 +25835 3956 3744 6503 7083 +25836 2324 335 334 6110 +25837 622 6392 4772 6835 +25838 1547 1552 6545 6698 +25839 2419 6083 2417 6457 +25840 3586 3655 3603 6092 +25841 1737 2044 1880 7091 +25842 1240 6722 6476 6766 +25843 1964 6441 1820 7176 +25844 5401 505 5413 6067 +25845 4775 5780 4796 6719 +25846 4199 6283 6607 6691 +25847 5237 6182 5235 7055 +25848 571 5725 5688 6533 +25849 5365 5146 5360 6053 +25850 5406 5880 605 6987 +25851 4481 4223 4133 6558 +25852 4002 6539 3683 7058 +25853 4277 4154 461 6337 +25854 565 4569 4567 6381 +25855 3677 3972 3856 6521 +25856 2974 2789 2788 6043 +25857 2136 5952 1861 7130 +25858 6341 7129 1629 7130 +25859 6347 6652 4869 6837 +25860 2684 5916 2659 7093 +25861 3142 2755 2904 5776 +25862 2354 2300 2330 6135 +25863 4014 4299 4182 6328 +25864 3222 3221 3223 5849 +25865 5889 7181 5789 7186 +25866 1922 1725 1926 6079 +25867 5164 5119 5163 6512 +25868 1779 1693 1971 6547 +25869 4363 4209 4074 6055 +25870 3081 2944 2816 6371 +25871 543 4817 6302 6832 +25872 1543 1538 1525 6794 +25873 5295 5288 5296 6399 +25874 5434 606 5402 6987 +25875 2777 6491 2828 6968 +25876 423 3618 424 6022 +25877 4909 7037 6688 7109 +25878 5109 5116 5110 6050 +25879 2851 2727 2852 6188 +25880 2045 2110 1796 6635 +25881 1997 5891 6906 6975 +25882 3462 3461 3492 6340 +25883 1851 1695 6196 6733 +25884 2662 2839 2840 7175 +25885 2076 1708 6225 6906 +25886 347 2370 348 6068 +25887 4521 6456 544 6832 +25888 629 5810 628 6693 +25889 4299 4113 4201 6090 +25890 479 6423 480 6871 +25891 557 4539 4536 7089 +25892 2736 2740 3572 6035 +25893 4505 4529 6307 6592 +25894 5400 510 509 6068 +25895 2567 5846 2565 6861 +25896 4364 4201 4027 6516 +25897 5338 5334 5322 5772 +25898 5450 6891 6593 6932 +25899 5608 6890 6594 6931 +25900 4365 4400 6071 6663 +25901 5607 6732 5665 6804 +25902 5449 6731 5507 6803 +25903 3090 2472 3122 6454 +25904 4329 4460 5871 6991 +25905 3025 5806 2510 6981 +25906 3954 3760 6636 6895 +25907 25 6383 5798 6566 +25908 2501 6417 2375 6886 +25909 26 5950 5922 7119 +25910 506 6209 6061 6479 +25911 6593 6891 3751 6932 +25912 6594 6890 1265 6931 +25913 2223 2221 6209 6822 +25914 5451 5553 6953 7113 +25915 5609 5711 6954 7114 +25916 5131 4926 4960 5908 +25917 6479 7053 2225 7213 +25918 4547 4500 6253 6546 +25919 4563 6976 5964 6977 +25920 5333 6390 5336 6711 +25921 2228 2230 2226 6119 +25922 4596 5079 4972 6109 +25923 5144 5349 5301 6163 +25924 2645 5846 2644 6839 +25925 4714 4781 4757 6829 +25926 1370 1329 1232 6869 +25927 469 4385 470 6408 +25928 506 5401 5421 6334 +25929 481 4549 4520 6078 +25930 5288 4821 5149 6399 +25931 4729 4728 5789 7181 +25932 5092 5331 5091 6091 +25933 3231 3227 5790 7182 +25934 1840 6525 5807 6537 +25935 3944 3730 6784 6785 +25936 1458 1244 6781 6782 +25937 5068 4650 4835 6849 +25938 5061 5049 4668 6075 +25939 1798 2068 1495 6467 +25940 1863 6349 2144 6690 +25941 3881 6389 3690 6828 +25942 4921 4657 6659 6965 +25943 4022 4268 4167 6018 +25944 2765 2767 6457 6551 +25945 2091 1809 1945 6055 +25946 3173 6709 2493 6969 +25947 3092 3261 3093 6361 +25948 2278 2281 6387 6935 +25949 5317 5261 5181 5829 +25950 2906 3552 2835 6552 +25951 4191 4274 4028 6207 +25952 613 612 6736 7190 +25953 487 488 4526 6370 +25954 4023 4166 4403 6326 +25955 2601 3016 3015 7168 +25956 2201 2200 2209 5798 +25957 4601 4829 4609 6908 +25958 4920 4593 4968 6197 +25959 31 6048 560 6571 +25960 302 2263 303 6579 +25961 2949 3086 2950 5782 +25962 2544 2546 3470 6495 +25963 5839 5318 6813 6843 +25964 4854 4932 4875 6394 +25965 5587 5455 5498 6907 +25966 2066 3793 1990 5949 +25967 3787 3706 3790 7061 +25968 5336 6390 5324 6962 +25969 4598 5758 4784 6763 +25970 5047 6005 5121 6707 +25971 6595 7112 3840 7134 +25972 6596 7111 1354 7133 +25973 2339 6401 385 7044 +25974 578 6543 6366 6810 +25975 3142 3211 3141 6424 +25976 5300 5253 5127 6288 +25977 519 6238 518 6581 +25978 587 4644 6045 6470 +25979 2704 2632 3006 6148 +25980 2914 2935 5884 7075 +25981 5481 6631 611 7190 +25982 3745 3966 6264 6889 +25983 4995 4591 6017 6692 +25984 2852 2851 6188 7050 +25985 4640 4936 5099 6651 +25986 5037 5015 4639 6259 +25987 468 6391 6323 6667 +25988 1616 1614 1611 6262 +25989 5869 6916 6320 6963 +25990 1292 1395 1232 6498 +25991 3011 3058 3057 6005 +25992 4110 4417 4228 6909 +25993 627 628 5523 6913 +25994 4642 4641 6338 6999 +25995 3885 3779 5930 7191 +25996 5079 6109 4596 6511 +25997 1942 1835 1678 6167 +25998 1370 5766 6498 6689 +25999 454 6895 6636 7208 +26000 5465 6580 5575 6765 +26001 2821 6017 2463 7206 +26002 6379 6387 525 6935 +26003 3567 3164 3029 6665 +26004 4917 4657 4655 6105 +26005 4709 5799 5333 6711 +26006 5008 4891 4887 6070 +26007 2398 2470 5875 7096 +26008 3383 3257 2669 6332 +26009 1758 1987 1941 6248 +26010 1684 2114 2029 6614 +26011 4389 4214 4406 6025 +26012 1438 2341 325 6902 +26013 1579 6418 1587 6568 +26014 2692 3003 6039 6514 +26015 544 4546 545 5903 +26016 2129 1931 6026 7033 +26017 4824 5273 5335 5870 +26018 3042 3205 3043 5772 +26019 1571 1573 1576 6365 +26020 248 247 5804 6925 +26021 2151 1635 2054 5977 +26022 2864 6469 6235 7125 +26023 4453 6027 4143 6605 +26024 1696 6198 1897 6988 +26025 4962 4898 4899 6517 +26026 1969 1664 1794 6385 +26027 5041 4996 4747 6371 +26028 2478 2484 2483 6237 +26029 5077 4707 6143 6936 +26030 3915 6570 6459 6674 +26031 5012 5043 5013 6054 +26032 465 6169 464 6415 +26033 3820 5827 3710 6497 +26034 433 6456 5903 6715 +26035 4296 4041 4409 6132 +26036 2661 2798 5945 6947 +26037 3488 3443 3445 6425 +26038 1534 5922 1542 6653 +26039 4372 6057 4036 6559 +26040 5246 6314 6298 6626 +26041 4993 6028 4941 7035 +26042 5395 5427 521 6241 +26043 5624 6703 5749 6732 +26044 5591 5466 6702 6731 +26045 3552 2906 2907 6552 +26046 4871 5135 6183 6921 +26047 238 6165 6545 6698 +26048 5347 4673 5302 5918 +26049 2301 6309 2356 6777 +26050 1284 1402 1482 7162 +26051 4620 4618 5106 6039 +26052 2395 2394 6898 7108 +26053 3278 3558 3229 6560 +26054 2944 2945 2510 5806 +26055 595 5419 594 6628 +26056 2836 2833 3147 6437 +26057 4213 4011 4362 7015 +26058 3946 5929 3738 7013 +26059 426 5833 3660 6672 +26060 4195 6076 4197 6588 +26061 4254 5940 4066 6578 +26062 3953 6826 3747 6947 +26063 1430 1340 6487 6879 +26064 3916 3826 6488 6877 +26065 242 3631 6575 7083 +26066 364 2314 2358 6325 +26067 2761 2759 2760 6786 +26068 2418 2443 2419 6457 +26069 5254 5297 5258 6513 +26070 3330 3214 3332 6195 +26071 2412 2492 2457 6695 +26072 2071 1783 2109 5895 +26073 320 5797 2206 6805 +26074 259 1590 258 6423 +26075 4694 4692 4819 6043 +26076 4641 4994 4640 6338 +26077 3070 2676 3102 6536 +26078 4755 5032 4663 6447 +26079 3578 6007 3579 6713 +26080 2123 6132 1745 6800 +26081 6124 7041 6509 7110 +26082 4118 4447 4295 5818 +26083 3022 3043 3268 7139 +26084 4422 4062 4458 6226 +26085 2275 2279 2276 6354 +26086 6584 5550 6821 7094 +26087 1791 2103 1910 5994 +26088 5384 5378 5396 6234 +26089 1967 1706 1864 6494 +26090 4910 4687 4960 7109 +26091 4309 4145 527 6311 +26092 3202 3078 3079 7103 +26093 4716 5887 4718 6755 +26094 3381 3379 6091 6477 +26095 2488 5822 383 6981 +26096 3095 3252 3251 6480 +26097 2946 2941 2943 5921 +26098 3836 4008 3734 5761 +26099 1522 1248 1350 5762 +26100 2661 5945 2449 7174 +26101 1307 1993 2069 5900 +26102 2402 6470 2403 6914 +26103 3094 3127 3126 5888 +26104 1855 2141 1770 6290 +26105 3837 3939 3701 6807 +26106 3893 3723 3786 6038 +26107 4420 4106 4333 6348 +26108 2827 2777 2828 6968 +26109 2092 6673 5967 6958 +26110 5703 5600 6979 7012 +26111 5442 6978 5545 7010 +26112 2269 2271 2273 6329 +26113 2877 6426 3366 6483 +26114 2678 2566 3157 5956 +26115 5628 6541 5679 6972 +26116 5521 5470 6539 6971 +26117 4643 6154 4644 6470 +26118 521 6439 522 6846 +26119 462 4380 463 6806 +26120 5001 5864 4998 6613 +26121 2324 6110 2298 6856 +26122 5098 5096 6037 6553 +26123 1583 6305 1585 6568 +26124 3314 1376 5882 6728 +26125 2682 2849 2681 6351 +26126 3256 5976 3260 6508 +26127 1460 1316 1252 5835 +26128 1525 6324 1617 6419 +26129 5067 4685 5811 6700 +26130 2266 6439 2267 7081 +26131 5708 6788 6583 6996 +26132 4696 4695 4697 6258 +26133 4068 4269 4168 6176 +26134 223 224 6307 6664 +26135 582 581 4865 5805 +26136 2026 2175 1731 6806 +26137 623 4771 5942 6835 +26138 3155 3041 3512 5883 +26139 263 1581 262 6134 +26140 1371 1477 1293 6499 +26141 2655 2697 3481 6553 +26142 3395 5773 3561 6554 +26143 433 3096 3033 5903 +26144 1631 2000 2115 6601 +26145 4149 5802 4362 7141 +26146 6852 6853 5481 6907 +26147 4037 4491 4260 6532 +26148 2019 1699 1894 6192 +26149 6665 6728 5882 6775 +26150 613 7054 6983 7190 +26151 1359 1283 6701 7014 +26152 3348 3397 3421 6281 +26153 501 6322 6278 6917 +26154 6984 7060 1239 7137 +26155 3026 3519 3010 5777 +26156 1237 5766 6482 6727 +26157 1235 6533 1333 6602 +26158 3819 3721 6534 6603 +26159 1844 1890 6310 6525 +26160 5130 6281 5127 6837 +26161 431 3626 432 6715 +26162 3859 6830 6638 7058 +26163 2315 2297 6184 7063 +26164 4433 4332 4131 6376 +26165 4382 6556 4113 7146 +26166 2473 6070 2471 6454 +26167 2541 3461 3462 6340 +26168 4281 4391 4085 6120 +26169 4720 4759 5775 7145 +26170 6539 6641 3877 7193 +26171 2951 2943 6269 6789 +26172 4024 4172 4227 6635 +26173 2458 6709 6257 6969 +26174 494 6881 6629 7209 +26175 5123 5124 4631 6346 +26176 5334 4808 4742 6502 +26177 4122 5877 4327 6544 +26178 4729 5789 4730 7181 +26179 3597 3664 3610 5781 +26180 4317 6226 4062 6942 +26181 4331 4218 4479 6669 +26182 365 364 5920 7007 +26183 4718 4716 4736 5887 +26184 6453 7089 5919 7205 +26185 4187 6114 6607 7046 +26186 4023 6175 4168 6493 +26187 2082 1691 1823 6377 +26188 3114 6218 3187 6745 +26189 3841 3742 3963 7044 +26190 5232 5191 5195 6276 +26191 339 6184 2349 6506 +26192 1997 2054 1724 6975 +26193 1775 2038 1849 6615 +26194 6016 6381 6699 6844 +26195 3831 2371 3907 7044 +26196 5138 5298 5136 6180 +26197 597 5825 4749 6754 +26198 384 2322 383 5822 +26199 4678 4850 4702 6265 +26200 4832 4566 4621 6484 +26201 5301 5195 5357 6011 +26202 3915 3681 6570 6674 +26203 351 6318 2224 6550 +26204 624 6128 625 7193 +26205 4883 5771 5281 6970 +26206 4682 6267 4853 7030 +26207 4339 4221 4096 6178 +26208 3026 3027 6236 7078 +26209 470 471 6409 6442 +26210 5067 4685 4915 5811 +26211 2404 2816 2402 6914 +26212 2828 6491 2777 7008 +26213 493 6248 494 6629 +26214 2672 5978 2436 6872 +26215 6787 491 6883 6996 +26216 5044 5103 5043 5823 +26217 2381 1509 7040 7107 +26218 1829 3836 5761 7025 +26219 1828 1350 5762 7024 +26220 3615 3656 3586 6456 +26221 5971 6937 6257 7179 +26222 5334 4983 5322 5772 +26223 2275 2276 2270 6354 +26224 2518 2525 2519 5904 +26225 259 260 1585 6194 +26226 4809 5309 5167 6481 +26227 1803 6006 2028 6950 +26228 4474 4398 4129 5838 +26229 1481 5933 1270 6684 +26230 3967 5932 3756 6686 +26231 3085 6257 3195 7179 +26232 2603 2601 2602 5927 +26233 3194 2846 2845 6279 +26234 4273 4020 4222 5808 +26235 471 4225 472 6407 +26236 309 1978 1863 6291 +26237 5289 4710 4822 6231 +26238 2421 2445 5889 7195 +26239 2890 6096 2982 6504 +26240 2994 6431 2993 6823 +26241 6619 6701 5681 6810 +26242 4847 4991 4939 5828 +26243 1874 1807 1675 6283 +26244 502 6563 5751 6997 +26245 3252 2779 3087 5926 +26246 4252 4031 4233 6140 +26247 384 2487 385 6401 +26248 6757 6826 621 6830 +26249 3350 6288 3506 6507 +26250 5709 5646 5619 7011 +26251 5461 5551 5488 7009 +26252 6280 6507 3451 7144 +26253 1329 5766 1237 6727 +26254 5558 6765 463 6862 +26255 2869 3274 6471 6929 +26256 4507 4556 4498 6165 +26257 1316 1212 1499 6491 +26258 1974 6000 5999 6864 +26259 3184 3111 3185 6210 +26260 3028 2994 3519 6431 +26261 1889 1716 2061 5933 +26262 1717 2062 1888 5932 +26263 3847 3713 6721 7207 +26264 1985 1667 1780 6076 +26265 1995 1652 1926 5838 +26266 4816 5907 4817 6832 +26267 2667 2665 2666 6231 +26268 2112 1947 6107 6556 +26269 349 2222 2230 6209 +26270 467 6323 468 6362 +26271 2727 2856 2852 6188 +26272 4149 4357 4362 5802 +26273 3299 3205 3042 5772 +26274 2076 1927 1708 6906 +26275 1189 1448 1450 6619 +26276 3936 3675 3933 6620 +26277 3748 6641 3939 7193 +26278 5036 5088 6131 7027 +26279 594 5335 595 5897 +26280 3981 3798 1800 6369 +26281 1772 2146 5958 7115 +26282 1747 2114 1875 6614 +26283 3394 5961 3395 6554 +26284 2515 2938 3199 5981 +26285 2533 2811 3171 6608 +26286 5699 5639 5613 6851 +26287 1871 1976 1705 6242 +26288 1277 1334 1228 6088 +26289 2186 1756 1904 6946 +26290 6451 6982 5866 7152 +26291 5636 5673 5738 6743 +26292 1336 6637 6746 6897 +26293 4497 4510 4553 6255 +26294 2931 2820 2932 5944 +26295 6329 6846 2272 7143 +26296 5885 6532 5760 7092 +26297 1367 6467 1264 6787 +26298 5177 5257 5923 6708 +26299 4282 4228 4050 6909 +26300 4265 6222 4441 6558 +26301 506 507 6061 6209 +26302 4730 4864 5889 6523 +26303 2526 3074 2888 6103 +26304 3584 3635 6809 7090 +26305 1228 1410 1285 6089 +26306 3596 6112 3654 6943 +26307 2355 6141 2301 6777 +26308 2365 6295 2308 6679 +26309 4945 4748 5052 6606 +26310 3362 2542 3462 6340 +26311 1843 6120 1638 6658 +26312 4943 4944 5072 7043 +26313 2555 3225 3113 6265 +26314 2632 2704 2705 7161 +26315 3415 3436 3413 6626 +26316 5374 5426 5389 6266 +26317 3540 2739 3539 6101 +26318 307 2144 1867 5940 +26319 5999 6223 1972 7091 +26320 2205 6572 6287 6911 +26321 5339 5048 5061 5936 +26322 1248 5762 1522 7209 +26323 4008 3734 5761 7208 +26324 2790 5782 2950 7116 +26325 2573 2989 2988 5984 +26326 5235 5297 5138 6845 +26327 5486 5548 6562 6654 +26328 5644 5706 6561 6655 +26329 361 5813 2319 6589 +26330 3964 5809 3743 6720 +26331 3455 6466 6063 7097 +26332 3233 3235 2815 5934 +26333 2413 2465 2961 6451 +26334 596 5825 5416 6962 +26335 2657 2800 3005 7052 +26336 2361 2304 2327 6171 +26337 1685 2028 1781 6475 +26338 4275 6301 4152 6432 +26339 5754 6401 5930 6674 +26340 5022 5023 5193 6239 +26341 379 380 6045 6857 +26342 4820 5284 4819 6036 +26343 5996 6975 6230 7176 +26344 1695 1890 5872 6733 +26345 5835 3286 6808 6824 +26346 335 2324 2351 6856 +26347 5629 6903 5731 6954 +26348 5573 5471 6904 6953 +26349 5006 4986 5791 6951 +26350 1914 254 1879 6574 +26351 4756 5169 5021 6612 +26352 421 2495 420 5969 +26353 2095 1918 1821 5885 +26354 3802 3738 3946 5929 +26355 4462 4115 4232 6144 +26356 1846 6322 2011 6527 +26357 534 4555 535 6020 +26358 1830 2058 6373 6468 +26359 3126 2493 3094 6709 +26360 2642 2633 2628 6656 +26361 434 3615 3652 6456 +26362 4132 6152 4297 6535 +26363 4624 4625 4604 7140 +26364 1700 1949 1948 6357 +26365 1339 6770 1253 6892 +26366 3825 6773 3739 6893 +26367 1291 6827 1320 6879 +26368 3806 3777 6828 6877 +26369 6413 6699 6381 6844 +26370 2139 6193 299 7143 +26371 6540 6972 5674 7199 +26372 5516 6538 6971 7200 +26373 3705 3839 3990 6720 +26374 6820 451 6882 7094 +26375 2224 2220 2222 6209 +26376 4806 4998 5864 7163 +26377 4312 4223 4481 6559 +26378 3040 2905 3038 5841 +26379 4984 4676 5849 7159 +26380 4036 4151 4325 6490 +26381 2567 2802 2847 6484 +26382 2705 2423 2424 5785 +26383 1763 2063 1869 5816 +26384 598 6135 5392 6754 +26385 1930 1734 1859 6420 +26386 3369 6343 3442 6795 +26387 3745 3831 3966 6889 +26388 2146 1962 1772 5958 +26389 3095 3299 5907 6480 +26390 2765 6457 2417 6551 +26391 476 4518 475 6260 +26392 341 340 6201 6506 +26393 4154 4397 6138 6615 +26394 1638 6120 1983 6691 +26395 342 2246 6452 7202 +26396 3049 3048 428 6044 +26397 517 6184 5415 6854 +26398 5328 5362 5283 5773 +26399 3179 2611 3040 6363 +26400 3261 3036 3504 6500 +26401 270 1908 271 5968 +26402 1577 1581 1574 6327 +26403 3160 3154 2595 5908 +26404 3786 3723 3891 6038 +26405 4046 4218 4172 5952 +26406 2806 3507 6469 7125 +26407 3331 6346 3329 6573 +26408 5527 6875 6828 6877 +26409 5685 6878 6827 6879 +26410 5204 5246 6298 6626 +26411 6850 6984 1239 7137 +26412 4607 4614 4603 6411 +26413 1553 1555 1558 6391 +26414 3966 3704 3903 6264 +26415 2942 3056 3339 5831 +26416 3042 3096 3299 5907 +26417 3066 3395 2893 5773 +26418 3101 5869 2718 6963 +26419 3279 2799 6317 6947 +26420 6487 6759 1341 6901 +26421 4921 6343 4661 6522 +26422 2632 2630 2631 6148 +26423 6539 6666 5571 7193 +26424 4091 6211 4386 6574 +26425 1526 1538 1627 6324 +26426 4604 4605 5904 6646 +26427 351 2362 6067 6550 +26428 2993 3059 3058 6823 +26429 4040 6149 4307 6535 +26430 3364 6106 3473 6483 +26431 4201 4364 4093 6090 +26432 463 6765 5558 7061 +26433 3891 6038 3723 6604 +26434 4904 6004 5215 7167 +26435 5908 6973 5944 7109 +26436 3379 3359 3380 6565 +26437 2820 6688 5944 6973 +26438 506 505 5401 6550 +26439 5435 5793 5410 7038 +26440 1244 1476 1458 6781 +26441 3730 3962 3944 6784 +26442 1551 6428 273 7212 +26443 1294 6571 1372 7107 +26444 5263 5246 5271 6297 +26445 3853 3798 6369 6636 +26446 3198 3037 3367 6282 +26447 617 4767 5862 7189 +26448 3901 3738 6666 7013 +26449 4497 4554 4515 6255 +26450 6595 6873 3840 7112 +26451 6596 6874 1354 7111 +26452 2397 2395 2770 5810 +26453 3282 3330 3329 6336 +26454 1267 6125 1215 7014 +26455 5862 6521 5916 7093 +26456 3479 3478 6049 7001 +26457 5558 463 5546 6862 +26458 507 508 4244 6360 +26459 2141 1916 1770 6019 +26460 455 4412 456 6468 +26461 5318 5180 5293 5839 +26462 5719 5643 5605 6781 +26463 5374 5392 5426 6135 +26464 1302 1405 6482 6775 +26465 2814 6688 5984 7045 +26466 2553 2819 2431 6028 +26467 4329 4042 4160 5872 +26468 2541 3462 2542 6340 +26469 5387 5369 5417 6040 +26470 2249 2247 2244 6292 +26471 5669 6812 6531 7111 +26472 5511 6811 6530 7112 +26473 1728 2023 1954 7156 +26474 1755 6066 6677 6934 +26475 4456 4254 4066 6578 +26476 297 6379 2123 6800 +26477 5286 5210 5249 6210 +26478 463 6863 6765 7061 +26479 2928 5791 3538 7182 +26480 2687 2921 2801 5800 +26481 1768 1913 2138 6524 +26482 2900 6914 6154 7042 +26483 4676 4815 4984 5849 +26484 5207 6553 6049 7197 +26485 489 27 6324 7172 +26486 4386 4293 4091 6574 +26487 3105 2698 3301 5938 +26488 6243 6609 6522 7102 +26489 5092 5216 5217 6091 +26490 6063 6466 3455 7084 +26491 2544 6199 2545 6839 +26492 1702 1820 1964 6441 +26493 1480 6232 1259 6809 +26494 3190 3191 3192 6455 +26495 2531 3019 2977 5911 +26496 2497 6381 2498 7128 +26497 3753 3845 3968 6725 +26498 3339 2844 2843 5831 +26499 2635 2638 2636 6272 +26500 5945 621 6826 6830 +26501 2693 3337 2694 5860 +26502 2611 6363 3321 7148 +26503 4364 4249 4093 5947 +26504 3928 6721 6580 7207 +26505 3354 3508 3509 5839 +26506 2489 2535 2536 6213 +26507 4950 4627 5100 6170 +26508 2460 2461 2462 6229 +26509 258 1901 259 5991 +26510 2691 2870 2937 5826 +26511 4877 5329 5287 5975 +26512 2621 6084 6466 7097 +26513 519 4135 4253 6579 +26514 4318 5812 4264 6995 +26515 2889 2891 2890 6095 +26516 3008 3013 6069 7103 +26517 3977 7082 5950 7119 +26518 4049 6120 4281 6607 +26519 3181 2971 3184 6210 +26520 3952 3677 3856 6521 +26521 2528 6155 3003 6514 +26522 5059 5095 5060 7101 +26523 3577 3576 5957 7138 +26524 5750 6594 5622 6780 +26525 5464 5592 6593 6783 +26526 4967 4838 6002 6724 +26527 463 6862 6765 6863 +26528 1285 1436 1228 6089 +26529 4397 6138 4387 7157 +26530 1934 1800 3798 6369 +26531 3432 3431 3375 6652 +26532 2266 6846 6439 7081 +26533 461 6440 462 7061 +26534 1776 2097 6194 6597 +26535 5703 5728 5600 7012 +26536 5545 5570 5442 7010 +26537 4635 4901 4575 6108 +26538 2746 2809 5942 7065 +26539 4845 5305 6245 6557 +26540 4959 4958 5198 6471 +26541 4544 4495 6112 6682 +26542 4437 6142 4038 6714 +26543 368 3301 2698 5938 +26544 1256 6453 5919 7205 +26545 4009 6570 3681 6716 +26546 3409 3424 3432 5815 +26547 4987 4986 4680 5791 +26548 4248 4391 4180 6373 +26549 2657 5886 2800 7052 +26550 5227 5292 5226 5980 +26551 3710 6497 5827 6886 +26552 505 4487 504 5992 +26553 2383 2491 3447 6173 +26554 4491 4037 4157 6597 +26555 527 6293 528 6510 +26556 5046 4794 5956 6719 +26557 4839 4675 6224 7167 +26558 4356 6663 6127 7203 +26559 6388 6389 615 6976 +26560 2382 358 2380 6048 +26561 3718 3879 3778 5916 +26562 5319 5175 5291 5786 +26563 4741 5295 5277 6102 +26564 4271 6194 4157 6597 +26565 4083 4407 6187 7188 +26566 1724 1837 2106 6175 +26567 4262 4163 4458 5840 +26568 2752 2684 2687 7000 +26569 4896 4781 4628 6247 +26570 1493 6771 6769 7071 +26571 4199 4124 4360 6475 +26572 4842 5117 5161 6087 +26573 2041 1760 1846 6490 +26574 514 4136 4429 6349 +26575 5279 4824 593 6001 +26576 4355 4366 4148 5890 +26577 1460 5835 1252 6824 +26578 1901 2043 1709 5991 +26579 2265 6238 303 6581 +26580 1314 1489 1180 6923 +26581 3666 3800 3975 6922 +26582 5829 6567 3053 7120 +26583 5583 6580 5465 6862 +26584 1756 2186 1867 5940 +26585 3488 6425 3445 7036 +26586 2645 2565 2643 5846 +26587 3856 3718 3952 6521 +26588 4024 6635 4227 7131 +26589 5199 5970 4956 6717 +26590 3854 3945 3732 7094 +26591 4889 5914 4890 7022 +26592 446 447 5809 6905 +26593 4051 4315 4190 6223 +26594 1687 1857 1905 6368 +26595 1186 6883 6694 6996 +26596 4989 4995 4644 6154 +26597 3771 6412 3974 7075 +26598 5255 6332 5147 6565 +26599 241 3663 240 6653 +26600 3596 3612 3654 6112 +26601 3423 6919 6163 7158 +26602 1630 1841 2137 6205 +26603 2697 6553 2696 7196 +26604 1353 1442 1196 6722 +26605 2903 6208 2902 6969 +26606 5433 5405 5376 7066 +26607 4502 4552 4522 6313 +26608 3479 3394 3436 6298 +26609 3021 3503 3289 5814 +26610 3168 2426 6388 6977 +26611 5357 5144 5301 6163 +26612 1654 1976 2007 5802 +26613 367 2353 2316 6856 +26614 3157 2645 2545 6839 +26615 4158 4297 4244 6151 +26616 621 5945 6392 6830 +26617 588 4644 589 6017 +26618 4743 4750 5860 6670 +26619 3453 3389 3305 6263 +26620 452 4275 453 6301 +26621 3491 6353 3365 6448 +26622 614 6009 6876 7054 +26623 3421 3397 3409 6753 +26624 3303 5859 2533 7127 +26625 2280 2277 298 6354 +26626 3448 5912 3529 7138 +26627 2714 2724 6221 7110 +26628 6274 6491 5882 7008 +26629 3521 6330 3541 6662 +26630 4150 4012 4345 6064 +26631 604 5880 6325 6617 +26632 4966 5070 5145 6003 +26633 5850 6587 579 6810 +26634 480 6423 6664 6871 +26635 5555 5449 6803 6989 +26636 4358 4245 467 5968 +26637 3553 3210 5913 6767 +26638 1208 6278 1414 6997 +26639 1895 2020 294 6718 +26640 3556 3460 3454 5792 +26641 3389 3514 3515 6342 +26642 1218 1470 6416 6902 +26643 1356 1187 1304 6766 +26644 422 3031 421 5783 +26645 3803 6840 3894 7113 +26646 1317 6841 1408 7114 +26647 5942 6835 5859 7065 +26648 2406 2807 423 6054 +26649 5223 5167 5309 5843 +26650 3039 3041 3178 5770 +26651 4709 4745 5020 5799 +26652 2142 2075 1829 5761 +26653 2143 2074 1828 5762 +26654 2549 2723 3542 5819 +26655 4021 4398 4202 5837 +26656 2978 2848 5847 6504 +26657 3410 2600 3549 6011 +26658 3204 3367 3037 6282 +26659 2746 2811 2809 7065 +26660 4094 5947 4466 7072 +26661 1850 1694 1920 6677 +26662 2704 2756 2757 5811 +26663 5276 5213 5214 6496 +26664 3458 3457 3255 6182 +26665 2780 2673 2863 5867 +26666 5730 6780 6781 6841 +26667 5572 6783 6784 6840 +26668 3204 3005 3004 6164 +26669 3015 3029 3030 5843 +26670 2805 6279 5964 6977 +26671 1765 5808 2094 7033 +26672 4554 6051 546 6650 +26673 4421 4149 4457 7141 +26674 4486 6147 529 7018 +26675 1237 1329 1370 5766 +26676 1304 1187 1384 6741 +26677 1251 6699 1349 6844 +26678 2380 2379 2382 7107 +26679 3433 3561 3336 6554 +26680 378 2333 2365 6295 +26681 373 2813 374 6001 +26682 3223 5849 3221 6896 +26683 5086 5087 6131 7027 +26684 2699 5913 6742 7196 +26685 5871 6880 6196 6991 +26686 3052 2887 2558 6378 +26687 4284 6544 5878 6952 +26688 3242 3243 2941 6517 +26689 1934 3798 3941 7025 +26690 1933 1312 1455 7024 +26691 4991 4847 4971 5828 +26692 294 2291 2289 6147 +26693 3192 6243 3306 6455 +26694 350 6334 2334 6550 +26695 3127 2387 5888 7064 +26696 5204 5207 4656 6049 +26697 2925 3557 3302 5758 +26698 3285 6102 3263 6555 +26699 3213 6179 3516 6567 +26700 3540 3522 3521 6101 +26701 2560 5942 2810 6749 +26702 5135 4876 4871 6183 +26703 3473 3320 3273 6106 +26704 6514 6763 5826 6951 +26705 2803 2804 2802 6484 +26706 4889 5914 7022 7088 +26707 4028 4288 4191 5982 +26708 1359 6701 6543 7014 +26709 2674 2436 2435 6872 +26710 1309 1310 6416 6476 +26711 1498 1471 6699 6827 +26712 2314 2302 2358 6325 +26713 3056 3559 2844 5831 +26714 5107 5106 5108 6155 +26715 569 5766 6482 6689 +26716 3271 3473 3269 6444 +26717 3817 6570 3712 6904 +26718 1331 6569 1227 6903 +26719 1211 6561 6655 6851 +26720 3697 6562 6654 6853 +26721 1613 6419 250 7104 +26722 1205 1306 1479 5974 +26723 3965 3691 3792 5973 +26724 5228 5192 5229 6280 +26725 613 612 6412 6736 +26726 3291 3378 3292 6339 +26727 4543 5987 4495 6682 +26728 426 5833 6672 6963 +26729 2040 1847 1758 6335 +26730 1519 7004 6791 7005 +26731 4005 7002 6790 7003 +26732 1213 1286 1324 7011 +26733 3699 3772 3810 7009 +26734 5067 4915 4766 5811 +26735 5448 5584 5486 6852 +26736 5742 5644 5606 6850 +26737 4276 4241 6167 6917 +26738 5384 5429 5378 6234 +26739 4259 6368 4108 7170 +26740 1359 1267 1215 7014 +26741 1907 315 6061 6912 +26742 1201 1424 6540 7199 +26743 3910 6538 3687 7200 +26744 2307 2367 6201 6762 +26745 3333 3231 3226 6941 +26746 2719 2604 2606 6125 +26747 3820 6497 3960 6631 +26748 2059 5915 1842 6474 +26749 4597 6002 4838 7123 +26750 4283 4087 4375 6490 +26751 2732 6060 2733 7021 +26752 4945 5101 5042 5857 +26753 3763 2481 2502 6887 +26754 2543 3484 3454 6489 +26755 4296 4159 4243 6132 +26756 2009 6205 1841 6376 +26757 4123 4325 4283 6490 +26758 2854 2935 2742 6364 +26759 3554 3449 3464 5765 +26760 2825 6486 6258 6657 +26761 2509 2950 2952 6764 +26762 4074 4251 4170 6270 +26763 5807 7129 6669 7130 +26764 502 5900 6997 7079 +26765 516 517 4418 6661 +26766 3286 2583 6808 6824 +26767 1367 1312 6467 6629 +26768 1269 1328 1463 5852 +26769 3755 3814 3949 5851 +26770 4267 6118 4055 6600 +26771 1840 1981 6525 6537 +26772 261 1839 262 6254 +26773 1777 6238 2098 7006 +26774 2759 5985 2760 6786 +26775 3034 2996 2824 6122 +26776 5805 5919 6499 6848 +26777 429 3613 3642 6160 +26778 3985 3738 3802 5929 +26779 2859 7124 6393 7125 +26780 2381 2505 2379 5830 +26781 629 630 6492 6693 +26782 4702 4874 4700 6378 +26783 4594 6916 5869 7039 +26784 3197 3367 3004 6473 +26785 1695 5872 1919 6733 +26786 2215 6383 2214 7053 +26787 3304 3306 6243 6609 +26788 1520 6788 6787 6996 +26789 5713 5607 6804 6994 +26790 272 1897 273 6988 +26791 2662 6392 2840 7174 +26792 4794 4937 5046 5956 +26793 361 2414 5881 6589 +26794 5400 5424 5375 6068 +26795 2002 1751 2005 5840 +26796 3885 386 2507 7191 +26797 367 2316 366 6052 +26798 2385 2758 2383 6075 +26799 493 492 4278 6249 +26800 4795 4796 4717 6246 +26801 4372 4036 4312 6559 +26802 3354 3352 3053 6567 +26803 5151 5926 4684 6700 +26804 2987 3152 3156 6087 +26805 3672 6882 6751 7094 +26806 2587 2588 1349 6844 +26807 2974 6042 2722 6660 +26808 3073 2442 2953 6816 +26809 3753 3968 6221 6725 +26810 2989 5984 2814 6688 +26811 229 1582 1576 6260 +26812 4420 4184 4396 6192 +26813 2031 1973 2185 6114 +26814 5549 6760 5443 6866 +26815 5601 5707 6759 6865 +26816 3993 6575 5922 7119 +26817 5517 6595 6562 6654 +26818 5675 6596 6561 6655 +26819 4245 5968 4358 7157 +26820 1886 6168 1637 6930 +26821 3051 3401 3403 6513 +26822 1349 6699 6413 6844 +26823 1595 1596 1597 6202 +26824 32 4731 583 6229 +26825 2889 2893 2892 6095 +26826 2144 1863 1756 6349 +26827 4965 4834 4943 6985 +26828 3015 3032 3029 5843 +26829 4544 4495 4514 6112 +26830 1598 1595 1601 6202 +26831 1706 5951 1921 7069 +26832 5300 5255 5253 6288 +26833 2646 2647 5898 6750 +26834 2021 6359 274 7212 +26835 5045 4950 5978 7211 +26836 3127 5888 3094 7064 +26837 3472 6427 2877 6483 +26838 2797 3027 2957 7078 +26839 2972 2992 2971 6400 +26840 1224 7040 1509 7107 +26841 5280 5289 4825 6216 +26842 4859 6199 4937 6651 +26843 4023 4269 4166 6493 +26844 5198 5188 5302 6471 +26845 2317 6268 375 7151 +26846 5905 6949 6107 7146 +26847 2674 2672 2436 6872 +26848 5211 5208 5209 5770 +26849 1632 2188 2090 6880 +26850 621 6643 5945 6826 +26851 3983 3740 6548 6939 +26852 1254 6549 1497 6940 +26853 2170 1865 2112 6090 +26854 1262 6640 1453 7014 +26855 2028 1643 2177 6006 +26856 1798 1933 1715 6467 +26857 4416 4021 4202 5837 +26858 3323 3322 3471 6367 +26859 3770 7041 3120 7110 +26860 3850 3709 3994 7191 +26861 5361 5114 5363 6400 +26862 345 344 6435 6990 +26863 2136 1746 1861 5952 +26864 5463 5550 6584 7094 +26865 2872 3573 2837 6038 +26866 295 6100 2168 6718 +26867 5038 5097 4942 5794 +26868 5919 6848 5805 6927 +26869 6000 6474 2059 7074 +26870 2372 1345 6519 6902 +26871 5122 6179 5340 6707 +26872 1945 1809 1673 6460 +26873 5197 5250 5234 6220 +26874 3869 3721 3851 6760 +26875 1365 1383 1235 6759 +26876 1981 1754 1890 6525 +26877 2231 6360 314 7180 +26878 4279 4199 4016 6283 +26879 2949 2807 3086 7116 +26880 6038 6521 5862 7093 +26881 3440 6612 6239 6910 +26882 5094 5098 5096 6037 +26883 2088 6271 6406 7069 +26884 2401 2772 5850 6855 +26885 1782 1865 2170 6090 +26886 3551 3110 3112 5975 +26887 4027 4337 4348 5960 +26888 446 3632 447 6905 +26889 3180 3178 3041 5770 +26890 3262 2497 3253 6380 +26891 5178 5129 5262 5972 +26892 3719 3889 6539 6971 +26893 1403 6541 1233 6972 +26894 6303 6993 1565 7080 +26895 2372 1422 2343 6519 +26896 1252 5835 1499 6746 +26897 3842 3673 3790 6862 +26898 604 6325 603 6617 +26899 1499 1252 1316 5835 +26900 3744 3923 6575 7083 +26901 5433 6284 5405 7066 +26902 1873 2171 1979 6118 +26903 3705 3956 6503 7083 +26904 1838 1952 6081 7006 +26905 4981 5006 4600 5826 +26906 6033 6847 4102 7157 +26907 6147 6449 293 6911 +26908 5931 4623 6792 7140 +26909 1802 1645 2029 5890 +26910 5993 6507 6280 7144 +26911 4287 5966 4079 7046 +26912 3127 2420 2387 7064 +26913 2332 6762 6200 7151 +26914 3543 2429 2570 5893 +26915 3928 6720 6580 6721 +26916 2815 5934 3235 6926 +26917 4232 4301 6145 7056 +26918 3047 3044 3243 5997 +26919 5081 5222 620 6643 +26920 2288 2283 2282 6294 +26921 1686 6140 1838 6946 +26922 4284 4048 6544 6952 +26923 502 6278 501 7079 +26924 5643 5747 5605 6781 +26925 577 6366 578 6543 +26926 4625 4891 4604 6646 +26927 3615 3603 3595 6251 +26928 2030 6864 5876 7122 +26929 3761 3724 6784 6840 +26930 3485 2866 2667 6231 +26931 3791 3667 3801 7031 +26932 304 2256 305 6834 +26933 5367 5410 5435 5793 +26934 587 4644 588 6045 +26935 1907 6360 315 6912 +26936 4107 6527 4372 7018 +26937 5353 5141 5143 6030 +26938 3200 3201 2622 6163 +26939 6280 6970 5771 7144 +26940 5610 6874 6596 7111 +26941 5452 6873 6595 7112 +26942 4784 5758 6885 7189 +26943 4959 5198 5302 6471 +26944 3889 3877 3719 6539 +26945 1233 1403 1391 6541 +26946 4024 4287 5966 7131 +26947 5398 588 589 6295 +26948 4386 6211 4186 6574 +26949 2959 2869 6471 6683 +26950 2458 2459 3195 6257 +26951 3213 3351 6300 6567 +26952 1707 1968 1863 6349 +26953 5833 6320 6916 6963 +26954 4247 4390 4181 6474 +26955 3436 3415 3479 6626 +26956 5827 2467 6639 6887 +26957 5170 5098 5207 6553 +26958 4682 6267 4986 6951 +26959 2915 5866 2981 6872 +26960 2972 3162 3525 6047 +26961 4018 5763 4343 7099 +26962 6430 7076 4555 7136 +26963 4335 4419 6359 6884 +26964 4101 4425 6410 6588 +26965 5686 577 6701 7014 +26966 3643 3590 6190 7062 +26967 2435 2434 5794 6945 +26968 2420 2387 7064 7195 +26969 4095 4350 4473 5865 +26970 1828 5762 2074 7024 +26971 2075 1829 5761 7025 +26972 4520 4524 4505 6520 +26973 2321 2357 331 6285 +26974 6291 6349 4429 6714 +26975 1969 6385 1794 6980 +26976 5270 4664 4662 6363 +26977 3919 6562 6853 6893 +26978 1433 6561 6851 6892 +26979 570 569 5074 5795 +26980 4931 4930 4703 6095 +26981 2858 6393 2865 7125 +26982 4481 6133 4072 6559 +26983 1551 1544 1547 6428 +26984 3160 5908 2592 6973 +26985 5251 5200 4899 7155 +26986 1251 1349 1465 6844 +26987 1401 6528 1519 6791 +26988 3887 6529 4005 6790 +26989 1345 1422 2372 6519 +26990 4451 4056 4258 6315 +26991 4952 4797 5060 6398 +26992 1905 1757 2187 5848 +26993 5035 4672 5047 5874 +26994 3327 6915 2822 7206 +26995 2958 5918 2962 6683 +26996 4830 4601 6342 6908 +26997 4801 4802 5057 6213 +26998 2965 5963 2922 7073 +26999 4856 4854 4875 6299 +27000 229 3603 228 6260 +27001 3233 3234 3235 5934 +27002 305 306 1838 6081 +27003 1939 1988 6250 6658 +27004 5221 4674 5089 6425 +27005 3683 6666 6539 7193 +27006 2919 3309 2918 6696 +27007 458 6097 459 6686 +27008 498 6098 499 6684 +27009 4165 6149 4408 7153 +27010 4598 4981 5826 6763 +27011 5830 6571 6048 7107 +27012 2660 2684 2751 5916 +27013 2312 346 2368 6296 +27014 3380 3382 3381 6091 +27015 2854 2855 2853 6639 +27016 4222 4119 4273 5808 +27017 1682 1872 1840 6525 +27018 1775 2033 2038 5877 +27019 2945 2983 2953 6013 +27020 4331 5807 4162 7141 +27021 5015 605 5880 6987 +27022 5413 5410 5367 5793 +27023 1662 6176 6493 7057 +27024 4771 4804 5024 5859 +27025 1396 1188 6703 6867 +27026 3882 3674 6702 6868 +27027 1265 1299 6890 7199 +27028 3785 6891 3751 7200 +27029 1412 1318 6850 7137 +27030 3134 3170 3169 6552 +27031 6419 6794 6324 7172 +27032 2792 6697 2903 6969 +27033 3502 3434 3520 5993 +27034 4144 4313 4373 6032 +27035 4356 6127 4442 7203 +27036 4582 4967 4838 6002 +27037 4347 4177 6461 6622 +27038 2769 6124 2771 7110 +27039 3754 6654 3918 6704 +27040 1268 6655 1432 6705 +27041 618 6038 619 6604 +27042 629 6492 5810 6693 +27043 2907 6552 6252 6713 +27044 6003 6557 4966 6724 +27045 2974 2734 3182 6042 +27046 2863 2780 5867 7117 +27047 1711 1902 2050 5852 +27048 1710 1903 2049 5851 +27049 1768 1688 1913 6524 +27050 5708 6583 5621 6996 +27051 3206 6374 3327 7206 +27052 4770 568 567 6191 +27053 6791 7004 497 7005 +27054 6790 7002 457 7003 +27055 6338 6798 5979 6999 +27056 1747 1875 6146 6614 +27057 1898 2190 1778 7171 +27058 1846 1657 2011 6322 +27059 5583 531 6580 6862 +27060 2910 3054 2911 7120 +27061 250 1617 249 6419 +27062 5560 6852 5486 6853 +27063 5644 5718 6850 6851 +27064 5838 6532 5865 7095 +27065 2000 1631 1949 6357 +27066 2002 2193 1751 5840 +27067 4125 4282 5906 6909 +27068 5835 6746 573 6897 +27069 2485 5854 359 6793 +27070 501 6278 502 6997 +27071 4251 4413 4170 6270 +27072 597 5416 596 5825 +27073 2701 3142 2904 5776 +27074 479 4553 478 6306 +27075 5747 5605 6781 6841 +27076 4026 6368 4259 7170 +27077 2490 2806 3507 6469 +27078 5132 5126 4844 5815 +27079 1867 5940 2186 6946 +27080 5049 5048 5050 6173 +27081 6392 6835 5929 7175 +27082 2908 2874 2881 6486 +27083 2292 3917 320 6805 +27084 1807 6283 1685 6691 +27085 5086 6131 5088 7027 +27086 5204 6049 4656 6626 +27087 5183 5351 6212 6921 +27088 5382 5413 5367 6067 +27089 2814 5984 2569 7045 +27090 4069 4337 4201 6244 +27091 2850 2864 6235 7124 +27092 603 5429 602 5920 +27093 5258 5248 5265 6444 +27094 2828 1379 6491 7008 +27095 6541 6640 1391 6974 +27096 3052 2558 3106 5962 +27097 2368 6296 346 6990 +27098 5333 5324 5336 6390 +27099 5014 4735 606 5881 +27100 4079 5966 4189 6547 +27101 1287 1494 1213 6874 +27102 3699 3773 3980 6873 +27103 4480 6152 4132 6944 +27104 1374 1337 1520 6996 +27105 569 5795 570 6482 +27106 3574 3466 3467 6129 +27107 2594 6058 6973 7173 +27108 2102 1681 1817 6127 +27109 4590 4578 4589 6500 +27110 5205 5170 6553 7197 +27111 2319 2301 2356 6777 +27112 2444 5789 2952 7186 +27113 254 1609 253 6465 +27114 1980 2170 1668 6328 +27115 4032 4173 4270 5905 +27116 5428 5384 5377 6052 +27117 5753 6905 5781 6938 +27118 2029 1780 1684 5763 +27119 319 2162 1955 6505 +27120 433 3656 6456 6715 +27121 3968 6509 3770 7110 +27122 1513 1245 1348 6278 +27123 2711 2709 2710 6869 +27124 3668 3818 6785 6971 +27125 1332 6782 1182 6972 +27126 4810 4809 4811 5927 +27127 4721 5806 4723 6623 +27128 2560 2746 2810 5942 +27129 5018 4761 4974 6815 +27130 2157 1964 1820 7176 +27131 3773 4007 3890 6774 +27132 1287 1521 1404 6771 +27133 574 573 5835 6746 +27134 297 2280 6379 6935 +27135 1424 6972 6540 7199 +27136 3910 6971 6538 7200 +27137 3211 3483 3141 6424 +27138 5679 6640 6541 6974 +27139 4437 4136 4456 6349 +27140 5884 6736 3714 7075 +27141 1830 1748 2155 5973 +27142 2832 3148 2833 5861 +27143 3779 6716 5930 7191 +27144 1914 2140 255 5845 +27145 2135 1671 2189 5817 +27146 3373 3431 5784 6652 +27147 1495 1312 1798 6467 +27148 4598 4981 4600 5826 +27149 4830 5821 5073 6908 +27150 3642 3622 430 6051 +27151 2467 5827 2502 6887 +27152 4610 6427 5265 6483 +27153 556 4733 4728 5969 +27154 2363 6171 2304 7151 +27155 3468 6023 2869 6683 +27156 3767 6757 3988 6826 +27157 4485 483 482 5845 +27158 2054 1767 2151 5977 +27159 2766 2771 6124 7110 +27160 3307 3391 3531 6041 +27161 2868 6220 3527 6929 +27162 1701 1950 5905 6778 +27163 454 453 6636 6895 +27164 4116 4188 4464 5999 +27165 2703 5965 3211 6831 +27166 5394 5370 5420 6201 +27167 2572 3780 3995 6886 +27168 2381 7040 5830 7107 +27169 5351 5182 5183 6212 +27170 1708 6176 2087 7057 +27171 2801 5800 2425 7000 +27172 1428 1201 1424 6540 +27173 3910 3914 3687 6538 +27174 5155 5156 5148 6056 +27175 1633 1809 2091 6055 +27176 2848 2846 2978 5847 +27177 2178 5959 1772 6918 +27178 2653 2656 2654 6037 +27179 4009 3681 3857 6716 +27180 3217 3091 6191 6869 +27181 214 6642 3638 7017 +27182 3868 276 1990 5950 +27183 2557 6265 2555 7016 +27184 4776 4725 4777 6693 +27185 4680 4681 4885 5834 +27186 363 2329 362 5880 +27187 4776 5104 4746 6083 +27188 4443 4063 4226 6146 +27189 4308 4041 4441 6344 +27190 4183 6138 4397 7157 +27191 2661 2799 2798 6947 +27192 4306 4250 4075 6254 +27193 1706 1928 1921 5951 +27194 5103 4648 6526 6937 +27195 3982 5949 3694 7061 +27196 2141 312 1916 6153 +27197 1579 1578 1587 6418 +27198 511 512 6290 6397 +27199 4912 4925 5944 7109 +27200 3016 2392 3082 7168 +27201 3937 3911 3677 6603 +27202 1425 1191 1451 6602 +27203 484 6463 483 6574 +27204 4597 4582 4838 6002 +27205 5341 5342 5993 6842 +27206 4213 6242 4059 7015 +27207 4216 4058 4217 6375 +27208 4247 494 493 6248 +27209 453 4248 454 6250 +27210 1278 6587 5875 7096 +27211 567 566 6413 6827 +27212 2413 3002 3000 6451 +27213 4120 4410 4490 7100 +27214 2332 6200 2317 7151 +27215 4308 6222 4077 6942 +27216 4602 4830 4601 6342 +27217 4633 4933 4934 5983 +27218 2229 6119 2226 6822 +27219 5265 5264 5266 6444 +27220 2545 2544 3319 6199 +27221 4562 5781 4538 6938 +27222 276 2161 1990 5950 +27223 3187 2868 2899 6218 +27224 503 6449 5900 7079 +27225 4958 4956 5199 5970 +27226 1260 1311 1485 6883 +27227 3209 3208 372 5897 +27228 314 6360 2121 7180 +27229 3924 3831 3745 6889 +27230 2212 326 2195 5995 +27231 2523 5896 2529 6898 +27232 2014 1649 1858 6516 +27233 3396 3397 3392 6277 +27234 1695 1919 6196 6733 +27235 1899 1679 6097 6687 +27236 1678 6098 1898 6685 +27237 1914 1879 1691 6211 +27238 522 4301 521 6145 +27239 1746 2116 2113 6950 +27240 4809 5303 5309 6799 +27241 3681 3841 3963 6674 +27242 546 5911 5337 6650 +27243 3080 5971 2793 7179 +27244 4543 4513 540 6421 +27245 1422 357 2343 6519 +27246 5301 4669 4963 6086 +27247 3545 3420 3151 5786 +27248 2225 6479 2217 7053 +27249 1551 1546 6415 7212 +27250 3821 6492 6723 6730 +27251 4921 4660 4657 6965 +27252 2154 1944 1831 7074 +27253 5090 5089 5069 6382 +27254 3793 3694 3982 5949 +27255 217 5796 3608 7062 +27256 4432 4232 4115 6144 +27257 2627 2823 2753 6915 +27258 362 2688 363 5880 +27259 1211 1268 1397 6850 +27260 3697 3754 3883 6852 +27261 248 249 6324 6485 +27262 1707 1925 1968 6142 +27263 3822 3738 3985 7058 +27264 2282 2284 2289 6510 +27265 5314 5161 5259 6424 +27266 250 1894 251 6192 +27267 5008 4984 5315 5814 +27268 4455 4031 4193 6441 +27269 1672 1804 2134 6226 +27270 4798 4797 4799 6122 +27271 5283 5281 5771 7135 +27272 2924 3951 2586 7023 +27273 1696 2021 1897 6198 +27274 4745 4744 4743 6936 +27275 4581 4679 4580 6404 +27276 298 299 6193 7143 +27277 5686 5643 5617 6640 +27278 5459 5528 5485 6641 +27279 4335 463 4380 6884 +27280 4584 4582 4580 6404 +27281 3953 3862 6826 6947 +27282 3359 3383 3506 6565 +27283 4527 4528 4503 6251 +27284 4828 4827 4826 7204 +27285 4102 4392 4467 6847 +27286 3052 2648 2647 5898 +27287 608 4732 31 6582 +27288 2111 6396 1797 7091 +27289 3899 3735 6772 7085 +27290 4846 4939 4938 6937 +27291 1229 5850 1411 6810 +27292 1843 1939 1677 6658 +27293 5150 4743 4888 5861 +27294 2309 2373 2339 6401 +27295 564 563 6089 7060 +27296 5002 5005 4810 6236 +27297 2032 6029 1732 6930 +27298 1274 6881 1514 7209 +27299 5508 5437 5535 6891 +27300 5666 5595 5693 6890 +27301 568 4770 4769 6215 +27302 4106 4396 4153 6348 +27303 2332 2307 6200 6762 +27304 2637 2636 3068 6272 +27305 2715 2427 2428 6389 +27306 2203 2202 292 6911 +27307 3619 3640 6306 6592 +27308 4505 548 4530 6160 +27309 5168 5010 5009 6162 +27310 3401 3051 2875 6513 +27311 5729 6541 574 6974 +27312 2632 3100 3006 6148 +27313 485 6462 484 6464 +27314 568 6498 5766 6689 +27315 563 6712 6089 7060 +27316 4216 4217 4092 6375 +27317 2620 2948 2621 6084 +27318 2122 1879 254 6465 +27319 3812 3942 4003 6749 +27320 2505 5830 2381 7040 +27321 3390 3391 3388 5821 +27322 2796 5964 3128 7073 +27323 4845 4966 5305 6557 +27324 5161 5160 5159 6172 +27325 276 275 5950 7082 +27326 4160 4421 4061 5872 +27327 4725 4724 4851 5896 +27328 2409 5823 2790 7116 +27329 3400 3399 6411 6870 +27330 2554 6945 6299 7068 +27331 2405 2440 2983 5857 +27332 1868 6134 262 6859 +27333 4882 6074 5231 7155 +27334 4466 4094 4249 5947 +27335 2321 2302 2357 6285 +27336 4860 4859 4858 6199 +27337 1798 1312 1933 6467 +27338 2858 2860 6393 7124 +27339 4580 4582 4581 6404 +27340 2457 2522 2960 6695 +27341 3069 3102 3020 6414 +27342 1774 1960 2180 6032 +27343 4020 4251 4209 6386 +27344 2612 6713 6252 7148 +27345 4035 4388 4427 5958 +27346 3221 6896 5849 7142 +27347 421 3644 3614 6077 +27348 2818 6059 2989 6688 +27349 3326 6228 3413 6314 +27350 3440 3498 3438 6612 +27351 4223 6029 4361 6558 +27352 2243 2233 2235 6625 +27353 4317 6942 4077 6964 +27354 3501 3577 3576 5957 +27355 4187 4369 6113 6607 +27356 3762 3841 3915 6674 +27357 2502 2467 2501 5827 +27358 3505 2517 3125 6215 +27359 3856 3815 3718 6521 +27360 1387 2720 2604 7162 +27361 5192 6277 5190 6752 +27362 550 4516 551 5988 +27363 5866 2981 6872 7160 +27364 5097 4941 4942 7035 +27365 4474 4473 4037 6532 +27366 2655 3482 2653 6105 +27367 1345 1218 6519 6902 +27368 488 6419 6192 7172 +27369 1913 6524 1688 6961 +27370 2702 6024 2700 6831 +27371 1544 6415 1545 6698 +27372 2298 6234 2314 7007 +27373 1875 1806 5876 6614 +27374 349 2334 350 6334 +27375 5714 5674 6540 6972 +27376 5516 6538 5556 6971 +27377 5508 6530 5437 6891 +27378 5666 6531 5595 6890 +27379 6638 6757 621 6830 +27380 4143 4453 4262 6027 +27381 4790 4712 4713 5866 +27382 1254 6804 6549 6940 +27383 3740 6803 6548 6939 +27384 5267 4658 5029 6228 +27385 2882 2939 3534 6056 +27386 4943 4834 4944 6985 +27387 3190 3539 3285 6102 +27388 226 1586 1588 6308 +27389 1471 1266 1498 6699 +27390 3695 6686 7002 7085 +27391 4608 4612 4650 5765 +27392 5109 5110 4625 6050 +27393 1910 253 252 6465 +27394 1867 1686 1838 6946 +27395 1563 1562 1565 6993 +27396 3502 2670 3435 6297 +27397 2070 5807 1872 7130 +27398 3567 2539 3314 6728 +27399 2896 5779 2897 7175 +27400 3710 5827 3763 6886 +27401 5244 4690 5938 6670 +27402 631 5500 630 6730 +27403 582 5658 581 6729 +27404 3260 5976 3224 6745 +27405 3177 3269 5842 6591 +27406 4611 4610 4586 6448 +27407 5176 5173 5965 6708 +27408 3342 3341 6212 6573 +27409 4080 4315 4256 6223 +27410 2747 2741 2743 6062 +27411 618 6521 6038 6604 +27412 2340 2374 2309 5793 +27413 5452 7112 6595 7134 +27414 5610 7111 6596 7133 +27415 5152 4826 5898 7204 +27416 5148 5193 5280 6056 +27417 4171 4219 4047 6204 +27418 1385 1305 1240 6956 +27419 1491 1242 1325 6741 +27420 1331 6458 1429 6569 +27421 3817 6459 3915 6570 +27422 2308 2365 2333 6295 +27423 234 1561 235 6409 +27424 4451 4290 4192 6316 +27425 3557 3302 5758 7077 +27426 3940 3740 3975 6548 +27427 1254 1489 1454 6549 +27428 1558 1555 236 6391 +27429 1690 1812 1911 6344 +27430 4746 6013 4722 6623 +27431 3927 6530 3665 6611 +27432 1441 6531 1179 6610 +27433 524 4321 523 6193 +27434 3587 3628 6313 6672 +27435 598 5392 597 6754 +27436 4649 4608 4650 6129 +27437 2496 2498 6844 7128 +27438 3092 3093 3094 5990 +27439 1484 6705 1183 6878 +27440 3970 6704 3669 6875 +27441 4406 4013 4206 6395 +27442 3356 3509 3562 6496 +27443 2530 2445 2399 6189 +27444 4828 6177 4827 7204 +27445 1911 2081 1690 6344 +27446 5591 5576 5466 6731 +27447 5734 5624 5749 6732 +27448 3606 221 222 5948 +27449 2318 2297 2331 6185 +27450 3907 2371 2342 7044 +27451 2814 2989 2569 5984 +27452 2201 2214 2215 6383 +27453 6184 6478 5372 6854 +27454 1604 1596 1598 6202 +27455 5085 4783 5007 5831 +27456 575 574 6446 6746 +27457 2495 2509 2453 6764 +27458 5201 5195 5301 6438 +27459 4865 4733 582 5805 +27460 3377 3486 3580 6130 +27461 1376 1206 1467 6775 +27462 4000 3760 6895 7208 +27463 2589 2486 5917 6808 +27464 1997 5891 1927 6906 +27465 2699 5913 3210 6742 +27466 1987 6249 1656 7156 +27467 2926 2548 2721 5941 +27468 4582 4584 4836 6340 +27469 365 364 2568 5920 +27470 2492 5855 445 6905 +27471 1308 1417 1186 6232 +27472 2055 1825 1669 6726 +27473 3900 3866 3678 6440 +27474 1878 2081 1745 6132 +27475 4894 6343 4921 6659 +27476 5015 5014 605 6987 +27477 6017 6692 5901 7206 +27478 3583 3475 3437 5787 +27479 2153 2107 1833 6691 +27480 4811 4957 4810 5927 +27481 5220 5154 5332 6082 +27482 4080 4256 4238 5955 +27483 5033 6361 5087 7027 +27484 239 1545 240 6169 +27485 3888 6221 3968 7110 +27486 586 5422 585 6080 +27487 2192 1750 2003 5953 +27488 4033 4152 4373 6032 +27489 3005 6164 3204 7052 +27490 3231 5790 6941 7182 +27491 4575 4576 4635 6108 +27492 481 6307 480 6664 +27493 512 4300 6290 7028 +27494 4522 4552 484 6462 +27495 5516 6971 5440 7200 +27496 5598 5674 6972 7199 +27497 3012 5918 2958 7078 +27498 1964 6429 1777 7006 +27499 2189 6778 5817 6992 +27500 4430 520 6350 6579 +27501 4079 4255 4237 5954 +27502 4176 4330 4043 5967 +27503 4376 5878 4088 6838 +27504 4094 4249 5947 6858 +27505 238 3648 6165 6698 +27506 2714 3888 2726 7110 +27507 2063 1648 1869 6207 +27508 1763 2115 2063 5816 +27509 4629 4634 5365 6336 +27510 3500 3296 6382 6748 +27511 4240 4088 4277 6838 +27512 2855 2980 2979 5780 +27513 5142 4666 5349 6085 +27514 3174 6214 2534 7050 +27515 4895 612 4762 6364 +27516 5143 4872 5306 6272 +27517 4284 5878 4376 6952 +27518 5072 6367 5146 7043 +27519 2278 2275 2280 6354 +27520 353 2199 6566 7169 +27521 4683 5094 5096 6037 +27522 3625 3655 3586 6092 +27523 2451 2452 2450 6088 +27524 3168 3003 3194 6039 +27525 5768 6453 558 7089 +27526 1429 6569 6458 7205 +27527 1767 5977 2054 6975 +27528 3520 6507 5993 7144 +27529 274 6359 275 6756 +27530 3387 3361 3427 6002 +27531 3097 6302 435 6696 +27532 4434 4137 6460 7015 +27533 2811 2533 3303 5859 +27534 3019 2531 3018 5911 +27535 5151 4751 5926 7067 +27536 1250 7111 6812 7133 +27537 3736 7112 6811 7134 +27538 2381 1509 1363 7040 +27539 3066 3561 3395 5773 +27540 6022 6967 5796 7164 +27541 4122 4327 4284 6544 +27542 3775 6570 4009 6716 +27543 4681 4706 4705 6103 +27544 2527 2846 3003 6155 +27545 3201 3007 2948 6647 +27546 2026 6806 1659 6833 +27547 1589 6423 1584 6871 +27548 4737 4723 4721 5806 +27549 1646 5954 2164 6740 +27550 1662 6493 1938 7057 +27551 1492 1420 1283 6701 +27552 215 3624 214 6642 +27553 3971 3746 3797 6882 +27554 5697 6549 5596 6940 +27555 5438 5539 6548 6939 +27556 4640 5099 5039 5868 +27557 3356 3562 3391 6496 +27558 1792 6149 2083 6616 +27559 1588 1580 227 6308 +27560 2830 5882 3314 7008 +27561 4911 4689 6059 6815 +27562 4929 5134 4930 5913 +27563 2860 2858 6393 6744 +27564 1640 2118 2182 6178 +27565 2201 2215 2199 6566 +27566 3411 3343 3570 6183 +27567 350 2334 2362 6550 +27568 378 6017 2574 6857 +27569 2981 2863 5867 7160 +27570 4594 5869 4595 7039 +27571 5529 5451 5553 6953 +27572 5687 5609 5711 6954 +27573 2030 5876 1674 7122 +27574 3284 3193 3191 6021 +27575 2684 2660 2659 5916 +27576 3085 3196 3195 6257 +27577 4762 4775 6364 7145 +27578 4267 4202 4055 6118 +27579 2726 3770 3120 7110 +27580 1204 6413 1349 6699 +27581 1777 2076 6225 6906 +27582 5128 6281 5130 6837 +27583 5295 5296 5277 6102 +27584 4491 4075 4260 5885 +27585 4231 6290 4300 7028 +27586 3310 6986 6345 7097 +27587 4523 4504 4519 6123 +27588 4014 4182 4436 6991 +27589 506 6479 505 6550 +27590 2691 2870 5826 7077 +27591 2167 6061 316 7213 +27592 5648 6594 5608 6890 +27593 5490 6593 5450 6891 +27594 2428 2426 2614 6977 +27595 5029 4659 4764 7194 +27596 4339 4026 6178 7092 +27597 432 3656 433 6715 +27598 5746 580 5687 6729 +27599 629 5529 5588 6730 +27600 2497 3246 3247 7128 +27601 6392 6830 5945 7174 +27602 5285 5286 5343 5943 +27603 2160 1954 248 6485 +27604 4316 4263 4142 5853 +27605 3156 2446 2438 5856 +27606 1695 1844 1890 6733 +27607 3025 2944 2510 5806 +27608 5521 6539 6641 6971 +27609 6541 6640 5679 6972 +27610 5464 5514 5592 6783 +27611 5750 5622 5672 6780 +27612 337 2262 336 6776 +27613 3276 3308 3277 7198 +27614 4927 5131 5345 6047 +27615 4382 4069 6556 7183 +27616 251 5836 1615 7104 +27617 2587 1349 1292 6413 +27618 5245 5244 4690 5938 +27619 5878 6952 5928 7118 +27620 3606 3587 3659 6672 +27621 3835 3778 2585 7023 +27622 3928 3839 6580 6720 +27623 2886 3507 2865 6174 +27624 1780 1832 5763 7115 +27625 4691 4972 5079 6109 +27626 5541 6631 5481 6907 +27627 2266 2269 6439 6846 +27628 2771 2769 2767 6124 +27629 3512 3513 3155 5883 +27630 2140 256 5845 6779 +27631 439 3653 3602 7048 +27632 6389 6876 615 6976 +27633 2603 2602 2797 5927 +27634 4276 4241 4087 6167 +27635 3857 3681 3963 6716 +27636 2318 2307 2367 6201 +27637 4426 4034 4327 5877 +27638 613 6412 614 7054 +27639 2272 6329 2269 6846 +27640 4354 4128 4214 5769 +27641 4902 5326 5085 6269 +27642 5701 501 5751 7070 +27643 4149 4042 4357 6858 +27644 270 269 6256 6667 +27645 5179 5972 5178 6843 +27646 1625 1534 1533 5922 +27647 1554 1549 1548 6323 +27648 4858 4861 4928 6010 +27649 2780 2862 6247 7117 +27650 1566 1564 267 6442 +27651 5031 5256 4754 6117 +27652 4402 6578 6450 7100 +27653 2683 6016 2923 6844 +27654 1658 1988 6301 7026 +27655 535 6020 4555 7076 +27656 1986 1716 1799 6278 +27657 266 1852 267 6407 +27658 1209 6684 7004 7071 +27659 2878 6008 2581 7127 +27660 3104 3103 6240 6957 +27661 5184 5233 5185 6218 +27662 5710 6923 5625 6994 +27663 4299 4093 4182 6090 +27664 3413 3436 3417 6314 +27665 1878 1745 2123 6132 +27666 3988 6757 3859 6830 +27667 267 2138 268 6407 +27668 5026 4820 4818 6036 +27669 4245 6847 5968 7157 +27670 2482 3864 2914 6887 +27671 4944 4829 5072 6908 +27672 3728 5950 3977 7082 +27673 4521 543 4503 6456 +27674 2523 3023 5896 6680 +27675 4770 4788 4769 6792 +27676 1387 6125 1267 7162 +27677 231 6014 6928 7126 +27678 3062 2943 6789 7198 +27679 3776 6721 3713 6907 +27680 1641 2183 1826 5844 +27681 3352 3353 3351 6567 +27682 1862 1747 1875 6146 +27683 2739 2734 6399 6662 +27684 2553 2431 2434 6028 +27685 1806 5876 6614 7122 +27686 1272 6610 1487 6865 +27687 3758 6611 3973 6866 +27688 3650 3594 3610 5924 +27689 3418 3419 3420 5909 +27690 4766 5811 4915 7029 +27691 1709 2043 1854 6316 +27692 5467 5552 6922 6989 +27693 5159 5311 5161 6172 +27694 5136 5252 5219 5957 +27695 1203 1359 1283 6701 +27696 2262 2260 6331 6776 +27697 5036 5162 5163 6512 +27698 6146 6614 5890 7032 +27699 2258 5992 2218 7053 +27700 2624 2625 2623 6398 +27701 1459 1246 1368 6996 +27702 3601 3624 3590 6797 +27703 3456 3548 3547 6466 +27704 1801 2066 2175 5949 +27705 5002 5004 5003 6236 +27706 3017 3050 2430 6259 +27707 2103 1743 1910 5994 +27708 6222 6942 6027 6964 +27709 340 2318 341 6201 +27710 4482 4417 4110 5876 +27711 4037 4260 4471 6532 +27712 3300 3237 3207 5870 +27713 4948 4590 5033 6361 +27714 4980 4861 4994 5801 +27715 1593 1600 257 6779 +27716 1425 6602 1451 6901 +27717 4698 5279 5239 5934 +27718 4272 4113 4299 6107 +27719 3714 3763 3820 6887 +27720 2533 2534 2535 7127 +27721 4703 6095 5115 6627 +27722 1788 1907 2167 6912 +27723 5016 5017 5039 6414 +27724 376 2363 375 6268 +27725 1764 1980 2093 6328 +27726 3669 6875 6704 6877 +27727 1183 6878 6705 6879 +27728 1869 1648 2006 6207 +27729 6118 6599 4055 6600 +27730 5370 5420 6201 6948 +27731 1616 217 1614 6370 +27732 2673 2981 2863 5867 +27733 4609 5873 4834 6985 +27734 574 6541 5678 6637 +27735 4631 5122 5121 6195 +27736 3978 3906 3769 6913 +27737 225 3640 224 6871 +27738 3215 3355 3471 6300 +27739 3865 3747 5945 6947 +27740 6571 6722 31 7165 +27741 5572 5484 6783 6840 +27742 5642 6780 5730 6841 +27743 5158 5157 5179 6330 +27744 626 4573 4571 6188 +27745 2128 1822 1689 6149 +27746 3979 7003 6774 7085 +27747 2383 2758 2491 6075 +27748 3197 2605 2520 6473 +27749 3621 3600 3620 6430 +27750 3756 3909 1888 5932 +27751 1270 1423 1889 5933 +27752 3336 3561 3537 6941 +27753 6584 6821 3732 7094 +27754 3157 2566 2565 6861 +27755 6742 7196 5913 7197 +27756 5612 5654 5720 6675 +27757 5454 5496 5562 6676 +27758 3143 2884 3152 6275 +27759 2657 2483 2484 7052 +27760 1412 6632 1318 7137 +27761 2384 2386 3548 5936 +27762 5767 635 6416 7165 +27763 2700 3476 3475 6024 +27764 4470 4057 4221 6436 +27765 2046 2115 1763 6778 +27766 32 631 5930 6716 +27767 5128 5190 6277 6753 +27768 3377 6130 3580 7166 +27769 2765 2767 2417 6457 +27770 2502 5827 2501 6886 +27771 4521 4518 4496 6092 +27772 5250 4984 4813 6158 +27773 3865 3747 3988 5945 +27774 631 4731 32 6229 +27775 3793 2066 3834 5949 +27776 1887 1693 1779 7118 +27777 3821 6723 3675 6730 +27778 3255 3457 3111 5943 +27779 3278 3275 3063 5864 +27780 2740 2651 6036 6678 +27781 4565 613 4895 5963 +27782 3781 3872 6620 6913 +27783 493 6629 494 6881 +27784 2395 2529 2443 6898 +27785 4702 4701 4677 5755 +27786 3370 3088 3371 5925 +27787 2558 6378 3571 6786 +27788 2808 3031 422 5783 +27789 560 4758 561 6582 +27790 1536 1537 1538 5803 +27791 4824 4822 5273 5870 +27792 2563 5833 426 6963 +27793 2780 2782 2671 6170 +27794 3057 3282 3281 6346 +27795 2923 1465 2588 6844 +27796 260 1951 261 6568 +27797 3722 6676 3851 6866 +27798 1236 6675 1365 6865 +27799 1799 1348 2069 6278 +27800 4848 4923 4847 5971 +27801 3255 3108 3256 5943 +27802 3911 6603 3937 6900 +27803 2922 2745 2742 5963 +27804 3032 5843 3015 7168 +27805 2962 2958 3012 5918 +27806 1400 1257 1294 7107 +27807 4688 4690 5150 6437 +27808 2529 2523 2441 5896 +27809 5893 5984 7037 7045 +27810 3703 5922 3843 7082 +27811 2496 2587 6413 6844 +27812 566 6699 6413 6827 +27813 4594 4997 4596 6916 +27814 461 460 4277 6206 +27815 2458 2493 6709 6969 +27816 2074 6248 1715 7024 +27817 1714 2075 6250 7025 +27818 3943 3755 3691 6790 +27819 1457 1269 1205 6791 +27820 542 543 4817 6302 +27821 2028 1803 1643 6006 +27822 4592 590 4591 6692 +27823 5239 5934 5279 6814 +27824 3788 3819 3692 6604 +27825 4389 4406 4096 6025 +27826 6541 6746 574 6974 +27827 5509 6564 462 6765 +27828 5667 6563 502 6766 +27829 2276 2271 2270 6329 +27830 1970 6133 1795 6817 +27831 4416 4202 4098 6734 +27832 3453 3495 3325 6609 +27833 3185 3186 3181 6591 +27834 1967 1905 1651 6286 +27835 2545 3144 3145 6199 +27836 4255 4174 6097 6547 +27837 5679 6541 5729 6974 +27838 634 635 5741 6476 +27839 432 433 5903 6715 +27840 4492 4507 4541 5924 +27841 4618 4862 4579 6039 +27842 3314 2539 1376 6728 +27843 3734 6633 5761 7208 +27844 1248 6634 5762 7209 +27845 3815 2659 3879 7093 +27846 2011 1657 2024 6527 +27847 3350 3348 3349 6288 +27848 611 4762 612 6364 +27849 4593 5078 4969 6692 +27850 3404 3401 3458 6182 +27851 320 2162 319 5797 +27852 4938 4846 6257 6737 +27853 4735 5881 5014 6982 +27854 5024 4804 4803 5859 +27855 4745 5799 4709 6936 +27856 4214 4057 4354 5769 +27857 3291 3290 3294 6339 +27858 3866 5932 3967 6924 +27859 613 6983 5487 7190 +27860 2092 1635 1808 5967 +27861 3335 3336 3537 6941 +27862 1432 1234 1340 6960 +27863 3918 3720 3826 6959 +27864 4099 4318 4455 5844 +27865 1836 1719 2037 6461 +27866 546 4820 5337 5911 +27867 5272 5275 4812 6021 +27868 1834 5878 1639 7118 +27869 1840 1654 1981 6537 +27870 2829 3234 3233 6657 +27871 2265 2256 304 6581 +27872 5085 5081 4783 5831 +27873 3386 3390 3388 5821 +27874 4046 4452 5853 7185 +27875 1566 1560 1559 6408 +27876 4027 4201 4337 6516 +27877 4335 4419 464 6359 +27878 2701 5776 2904 6831 +27879 4297 4040 4440 6535 +27880 2026 2013 1659 6806 +27881 4013 4349 4285 6357 +27882 1700 1882 2000 6601 +27883 5823 6526 6054 7116 +27884 4196 4383 4052 6034 +27885 4157 4271 478 6194 +27886 4895 4762 4622 6364 +27887 3860 3708 3823 6882 +27888 4494 4528 4527 6121 +27889 4131 4219 4303 6205 +27890 3892 6593 3751 6932 +27891 1406 6594 1265 6931 +27892 1846 1773 2041 6490 +27893 2901 2403 2787 6154 +27894 3365 6447 3363 6448 +27895 2744 3004 3005 6164 +27896 3798 1800 1934 3981 +27897 1312 1798 1933 1495 +27898 3798 6636 3707 7025 +27899 3271 3364 3473 6483 +27900 454 4180 455 6373 +27901 3602 440 439 5979 +27902 5795 6482 5766 6727 +27903 1677 1830 2058 6373 +27904 3569 3263 3285 6102 +27905 2217 2224 2219 7053 +27906 1629 1859 2004 6341 +27907 2701 3142 5776 6831 +27908 4521 543 6456 6832 +27909 4563 4566 4579 6279 +27910 327 6141 2355 7034 +27911 4006 6821 6820 7094 +27912 1309 1310 1470 6416 +27913 1265 6594 1445 7199 +27914 3751 6593 3931 7200 +27915 1328 5852 1209 6684 +27916 3814 5851 3695 6686 +27917 1267 6125 6543 7162 +27918 1914 255 254 6574 +27919 2757 2756 2776 5811 +27920 1198 1468 1274 6629 +27921 2797 2476 3027 6236 +27922 426 2563 425 5833 +27923 3743 3780 3886 5809 +27924 1849 1761 1989 6206 +27925 2253 2254 2255 6405 +27926 2024 6449 1785 6527 +27927 2316 2298 2347 6052 +27928 4809 4810 5005 6799 +27929 3649 3592 3607 6421 +27930 6602 6689 1191 6901 +27931 1413 1247 1389 7070 +27932 2166 1908 1790 6988 +27933 2823 2826 2825 6258 +27934 5837 2053 7047 7192 +27935 4550 5988 550 7039 +27936 5826 6514 2691 7077 +27937 2740 2651 2977 6036 +27938 2215 6318 352 6566 +27939 1999 6066 1755 6934 +27940 5504 5441 5569 6959 +27941 5727 5662 5599 6960 +27942 2504 5820 6898 6998 +27943 223 224 3605 6307 +27944 4189 5966 4287 7131 +27945 582 30 6569 7205 +27946 5116 4570 4827 6177 +27947 3010 3027 3026 7078 +27948 3527 2868 3114 6220 +27949 2463 2821 2574 6017 +27950 4774 5312 5303 5917 +27951 2419 2442 6083 6816 +27952 2858 3152 6275 6744 +27953 3537 3140 3138 6941 +27954 548 5284 547 6159 +27955 3046 3044 3045 7020 +27956 6113 6607 6114 7046 +27957 3789 3887 6633 6868 +27958 1401 6634 1303 6867 +27959 3570 2637 3448 5759 +27960 361 3071 362 5881 +27961 3474 2765 3131 6551 +27962 4109 4442 6127 7131 +27963 4886 5192 5231 6074 +27964 4187 6607 6113 7046 +27965 4006 3860 3823 7094 +27966 2156 2018 1783 5982 +27967 2451 6088 2450 6933 +27968 3584 6809 5768 7090 +27969 1221 1312 6629 7024 +27970 2610 2712 2608 6957 +27971 2910 5829 3054 7120 +27972 4299 4014 4272 6328 +27973 1750 5953 6537 7129 +27974 623 6666 6539 7058 +27975 3620 237 238 6165 +27976 4327 5877 4034 6615 +27977 4384 4374 4197 6377 +27978 1736 6341 2125 6635 +27979 4814 5236 5976 7055 +27980 512 5431 5387 6435 +27981 2783 6170 2782 6750 +27982 5353 5351 5141 6921 +27983 2974 2735 2734 6678 +27984 459 5932 460 6924 +27985 3039 3040 3038 5841 +27986 4534 6022 554 6739 +27987 5739 6890 6819 7199 +27988 5581 6891 6818 7200 +27989 4376 5878 6838 6952 +27990 4648 4991 6526 6937 +27991 4107 4151 4372 6527 +27992 1503 6453 1219 6809 +27993 4139 4388 4393 5958 +27994 4877 5287 4814 5975 +27995 5390 6185 5419 6962 +27996 2570 2569 2573 5984 +27997 2696 5913 2699 7196 +27998 457 4237 4255 5954 +27999 4256 497 4238 5955 +28000 1912 1813 1642 6312 +28001 3295 3376 3487 6289 +28002 2673 2981 5867 6872 +28003 1536 1538 1539 5803 +28004 3059 3535 3058 6005 +28005 4030 4258 4169 6315 +28006 1223 1508 1364 6848 +28007 1899 2049 1679 6687 +28008 1678 1898 2050 6685 +28009 1458 6781 1182 6782 +28010 3944 6784 3668 6785 +28011 3645 3608 217 5796 +28012 6417 6497 609 7098 +28013 2919 2918 6472 6696 +28014 6020 4555 7076 7136 +28015 2221 2220 2223 6209 +28016 2514 2763 6108 6855 +28017 3582 3409 3432 5815 +28018 3412 6183 3411 7138 +28019 2556 2555 6378 7016 +28020 5014 5881 606 6987 +28021 1506 1259 1308 7017 +28022 4378 4153 6249 6348 +28023 2653 2656 6037 7021 +28024 1202 1362 1398 7060 +28025 2664 2554 6299 7068 +28026 2336 5767 2346 6793 +28027 1907 2121 6360 6912 +28028 5676 5689 6689 6901 +28029 586 5386 5422 6321 +28030 3677 3937 6603 6735 +28031 3424 3313 3432 6245 +28032 4641 4992 6338 6798 +28033 5164 5317 5262 6031 +28034 1570 7080 232 7126 +28035 4615 4617 4616 6345 +28036 2257 2250 2253 6319 +28037 2046 1883 1631 6139 +28038 1841 1866 1683 6205 +28039 3900 3731 3866 6440 +28040 1203 6543 1359 6701 +28041 5201 4963 4962 6438 +28042 5163 6512 6208 7027 +28043 3296 3292 6382 6748 +28044 5272 4763 5028 6243 +28045 3215 3471 3332 6053 +28046 3761 3724 3906 6784 +28047 1524 6583 1459 6903 +28048 4010 6584 3945 6904 +28049 3478 2697 6049 7001 +28050 4843 4869 4905 6652 +28051 3327 6374 6915 7206 +28052 2244 2248 6292 7202 +28053 2101 1816 6930 7105 +28054 4317 4077 4143 6964 +28055 2976 3065 2916 5868 +28056 2350 2298 2324 6110 +28057 2225 2220 2217 6479 +28058 506 4144 4310 6355 +28059 2364 2306 2335 6115 +28060 2234 6443 2232 6990 +28061 1857 1687 2095 6368 +28062 5358 6012 5354 6618 +28063 2754 2642 2753 6104 +28064 5427 5377 5396 6110 +28065 5177 5909 5350 6708 +28066 2281 2284 6294 6935 +28067 3439 3493 3492 6353 +28068 1922 2089 1663 6315 +28069 3098 6166 2911 7120 +28070 231 7080 6014 7126 +28071 5044 4779 4780 6099 +28072 4390 4247 4086 6335 +28073 218 1608 219 6261 +28074 329 2359 330 6284 +28075 3177 3273 3179 5842 +28076 3407 3408 3251 6480 +28077 2466 6639 2467 6887 +28078 4026 4414 6368 7092 +28079 3527 3114 3116 6220 +28080 3928 3847 6721 7207 +28081 4412 4117 4237 6468 +28082 314 2231 315 6360 +28083 2030 1674 5876 6864 +28084 1423 1380 1245 5933 +28085 3731 3909 3866 5932 +28086 5930 6401 5754 7044 +28087 3314 2830 3567 5882 +28088 3821 6723 6492 7108 +28089 3830 3974 3771 6412 +28090 526 5433 527 6284 +28091 5205 5207 5204 6049 +28092 1824 1670 1882 6395 +28093 3332 3322 2638 6053 +28094 6649 1200 6979 7012 +28095 6648 3686 6978 7010 +28096 3740 3975 6548 6803 +28097 1489 6549 1254 6804 +28098 360 2415 2414 6589 +28099 3166 3254 3165 5937 +28100 2963 2784 2563 6320 +28101 2416 3161 2940 5970 +28102 2377 2501 2375 6886 +28103 2524 2861 5774 7117 +28104 5810 6492 629 6723 +28105 3133 5799 3135 7019 +28106 4586 4755 4585 6447 +28107 1926 2077 1709 6079 +28108 31 6722 6571 6743 +28109 2939 6216 2873 6910 +28110 619 618 5080 6434 +28111 3272 2875 6427 6668 +28112 4314 6547 4048 6952 +28113 1625 1628 5922 6575 +28114 2336 2356 6309 6793 +28115 328 6293 2288 7034 +28116 5480 5522 6877 6900 +28117 623 4771 624 5942 +28118 3220 3221 3222 5849 +28119 3915 3841 3681 6674 +28120 3343 3341 3340 6030 +28121 5486 5584 5548 6654 +28122 5644 5742 5706 6655 +28123 2080 6034 1744 6961 +28124 3148 3250 3337 7019 +28125 338 6405 2264 6776 +28126 6415 6756 6359 7212 +28127 547 546 4554 6051 +28128 2406 2407 2408 6054 +28129 4670 5121 5047 6005 +28130 3336 3434 3433 6554 +28131 1572 1571 1575 6094 +28132 1946 6226 2134 6673 +28133 1352 6867 6634 7209 +28134 3838 6868 6633 7208 +28135 5120 6208 5119 6737 +28136 2153 1638 2107 6691 +28137 4898 5921 4961 7163 +28138 1818 6071 2130 7177 +28139 2149 1851 6196 6796 +28140 4842 6424 5314 6576 +28141 4287 4024 5966 7046 +28142 4762 6364 611 7145 +28143 2790 2389 2390 6099 +28144 1712 5915 6864 7122 +28145 5030 4933 4588 6393 +28146 4210 4316 4078 6310 +28147 3303 2533 2581 7127 +28148 2542 6003 2543 6630 +28149 32 6674 6570 6716 +28150 2606 2605 3197 6473 +28151 4276 500 4241 6917 +28152 594 593 6001 6628 +28153 1700 2000 1949 6357 +28154 631 630 5820 6716 +28155 2261 6331 2263 7081 +28156 5026 5334 5337 6502 +28157 2539 3567 6665 6728 +28158 4311 4028 6207 6577 +28159 28 503 5899 6741 +28160 2916 2675 2976 6536 +28161 2392 2393 2391 6162 +28162 1374 1264 1222 6787 +28163 4962 4961 4898 5921 +28164 5169 6007 5278 6612 +28165 1632 1998 2188 5871 +28166 2303 2328 2319 6777 +28167 5369 5383 5394 6200 +28168 3728 3977 3783 7082 +28169 4469 4026 4205 7170 +28170 4457 4162 4263 7141 +28171 3232 6074 3497 6710 +28172 2124 6256 1876 6961 +28173 1987 2173 1798 6467 +28174 5570 5499 6648 6801 +28175 5657 6649 5728 6802 +28176 3392 3350 3451 6281 +28177 4451 4126 4290 6316 +28178 1726 6244 2027 6556 +28179 2003 5953 1750 7129 +28180 4297 4132 4480 6152 +28181 4720 5775 6755 7145 +28182 3682 3964 6720 6721 +28183 5589 6620 6840 6913 +28184 3032 3083 3084 6665 +28185 2963 2563 2718 6320 +28186 2411 5887 2998 6768 +28187 2332 2307 2317 6200 +28188 358 2346 357 6519 +28189 2962 3012 3014 5918 +28190 3272 6304 3457 6668 +28191 4883 5283 5281 5771 +28192 4625 5109 6050 7140 +28193 3611 6672 5988 6963 +28194 3964 3780 3743 5809 +28195 379 2787 380 6857 +28196 3684 3954 3760 6636 +28197 3571 2558 2555 6378 +28198 3509 3508 3510 6738 +28199 349 2337 2310 6116 +28200 4124 4326 4224 5989 +28201 1556 1558 1561 6391 +28202 4770 4769 6215 6792 +28203 5373 5422 5386 6321 +28204 3793 3834 3694 5949 +28205 1416 1214 6804 6940 +28206 3902 3700 6803 6939 +28207 1256 5919 1477 7205 +28208 2346 6519 5767 6902 +28209 2444 2421 5889 7186 +28210 2961 5774 2861 7160 +28211 5751 502 5667 6563 +28212 462 5509 5593 6564 +28213 4072 4481 4296 6133 +28214 4667 4669 4666 6085 +28215 1734 7059 6420 7177 +28216 4280 4200 4083 6186 +28217 5098 5170 5096 6553 +28218 1826 2001 1739 6992 +28219 3549 2600 2597 6011 +28220 1546 6756 6415 7212 +28221 1636 2152 2040 5906 +28222 4130 4434 4302 6669 +28223 1510 6487 1340 6960 +28224 3996 6488 3826 6959 +28225 3095 5907 3097 6696 +28226 474 4368 4198 6093 +28227 1518 1487 6819 6890 +28228 3973 6818 4004 6891 +28229 2984 5929 2447 7013 +28230 3184 2992 3109 5902 +28231 4305 4243 526 6100 +28232 2917 2776 2918 6472 +28233 457 6790 5851 7002 +28234 497 6791 5852 7004 +28235 3008 3229 3013 7103 +28236 2200 2201 2199 5798 +28237 2113 2116 1803 6950 +28238 1206 6728 1405 6775 +28239 2244 2246 2248 7202 +28240 3218 1292 1393 6869 +28241 3078 6086 3276 7198 +28242 3099 2911 3098 6166 +28243 4267 4089 4288 5982 +28244 2597 3308 3425 6919 +28245 3563 3448 2637 5759 +28246 3480 3482 6105 6965 +28247 3260 6508 5976 6745 +28248 3485 2873 2866 6216 +28249 2630 2680 3065 6338 +28250 4019 4265 6558 6964 +28251 550 4550 4516 5988 +28252 1841 2009 1866 6205 +28253 5390 5370 6185 6948 +28254 621 6392 5945 6643 +28255 1348 1414 1208 6278 +28256 4684 5151 4892 5926 +28257 230 6928 6365 7126 +28258 5867 6872 2981 7160 +28259 1199 6759 6487 6865 +28260 3685 6760 6488 6866 +28261 607 4732 608 5854 +28262 532 533 4734 5855 +28263 3141 2986 3142 6424 +28264 2330 2353 368 6266 +28265 5607 5657 5665 6732 +28266 5499 5507 5449 6731 +28267 4252 6140 4111 6706 +28268 1649 1965 1858 5960 +28269 2517 3091 3125 6215 +28270 26 6863 5950 7119 +28271 4566 5108 4579 6279 +28272 4839 5063 4675 7167 +28273 4506 6261 4533 7164 +28274 2747 6062 2564 6861 +28275 4641 6798 6338 6999 +28276 2234 346 6443 6990 +28277 5000 4667 5056 6069 +28278 2449 2798 3969 6947 +28279 1692 6223 1778 7171 +28280 1589 1591 6664 6871 +28281 3101 2718 2563 6963 +28282 3830 3771 3986 6412 +28283 6603 6735 3937 6900 +28284 5581 6818 5516 7200 +28285 5739 6819 5674 7199 +28286 376 2464 377 5901 +28287 568 5676 5689 6689 +28288 5147 4614 5202 6477 +28289 4364 4466 5947 7072 +28290 3950 6932 6530 7010 +28291 1464 6931 6531 7012 +28292 512 6291 4155 7028 +28293 30 6453 558 7205 +28294 1271 1494 1184 6771 +28295 3670 3757 3980 6774 +28296 2826 6258 2823 6915 +28297 4835 6849 5765 6985 +28298 351 2362 2323 6067 +28299 5415 517 5388 6184 +28300 2503 3994 2577 7191 +28301 2813 2812 374 6001 +28302 545 5338 544 5903 +28303 3535 3330 3282 6195 +28304 5505 5533 5444 7009 +28305 5691 5602 5663 7011 +28306 4143 6605 6027 6964 +28307 5364 5206 5961 7197 +28308 2467 2466 2469 6639 +28309 3369 3284 3442 6343 +28310 3781 6620 3933 6723 +28311 3767 3692 3819 6826 +28312 5294 5289 6216 6888 +28313 4096 4338 4339 6178 +28314 4909 6059 4910 7109 +28315 2214 6383 2258 7053 +28316 3464 3463 3398 6870 +28317 517 516 5388 6948 +28318 4882 4886 6074 6970 +28319 4195 6076 6588 7099 +28320 1725 1850 2150 5935 +28321 4306 478 477 6254 +28322 2886 3447 2491 6173 +28323 2793 5971 3085 7179 +28324 160 2538 1300 6728 +28325 6583 6788 1246 6996 +28326 3572 3267 6035 7139 +28327 2766 2724 2771 7110 +28328 4912 5944 7037 7109 +28329 2124 1876 1744 6961 +28330 2544 2639 2641 6010 +28331 3384 3405 3323 6367 +28332 4773 4793 4800 5886 +28333 5395 520 5423 6241 +28334 4511 4543 539 5987 +28335 3431 3432 3313 6245 +28336 3475 3476 3437 5787 +28337 2800 2484 2486 6808 +28338 5100 4627 4628 6170 +28339 1540 1545 6415 6653 +28340 2760 2759 3525 5985 +28341 2304 2363 2320 6171 +28342 5440 6971 6785 7200 +28343 5598 6972 6782 7199 +28344 4222 4354 4057 6436 +28345 5284 548 5238 6159 +28346 3103 3104 6240 7050 +28347 5384 5428 601 6052 +28348 3723 3815 3856 6521 +28349 4305 526 527 6100 +28350 2003 2192 5953 7059 +28351 1850 2150 5935 7192 +28352 3376 3374 3429 7166 +28353 4511 4495 4543 5987 +28354 3813 6803 6731 6989 +28355 4881 4814 5236 5976 +28356 5445 6904 6584 6922 +28357 5603 6903 6583 6923 +28358 2070 7129 5807 7130 +28359 3155 5883 3513 7173 +28360 4823 5279 4698 5934 +28361 3499 3438 3498 6117 +28362 4318 4455 5844 6995 +28363 2499 2506 2398 5875 +28364 4570 5116 4583 6380 +28365 621 5308 5310 6392 +28366 2247 2252 2245 6384 +28367 2871 2872 2837 6038 +28368 5111 4889 4954 7088 +28369 2415 359 2485 5854 +28370 2412 445 2492 5855 +28371 2381 5830 2379 7107 +28372 3972 3723 3856 6521 +28373 1929 2131 1804 6027 +28374 3950 3665 6530 6932 +28375 1179 6531 1464 6931 +28376 3587 3660 3628 6672 +28377 1680 1819 1929 6186 +28378 2419 2442 3130 6083 +28379 4985 4976 5213 6041 +28380 2941 2942 2943 6269 +28381 3529 5912 3292 6748 +28382 2200 2199 2197 7169 +28383 469 468 6256 6667 +28384 4300 4231 511 6290 +28385 5329 4677 4701 5755 +28386 2524 2456 2861 7117 +28387 28 5704 503 6741 +28388 5389 5426 599 7154 +28389 1652 1995 2072 5838 +28390 5382 5422 5373 6115 +28391 1731 2175 2066 5949 +28392 591 592 6268 6814 +28393 4400 4100 4365 6071 +28394 1337 1374 1222 6883 +28395 5164 5313 4848 6031 +28396 5228 5130 5128 6281 +28397 5517 6595 6654 7134 +28398 5675 6596 6655 7133 +28399 4914 4916 4913 6372 +28400 3501 3500 3051 6082 +28401 1986 1799 2174 6278 +28402 4334 450 25 6505 +28403 3688 3782 3848 7190 +28404 1592 1594 1601 6664 +28405 2935 2468 2914 5884 +28406 2739 3569 3539 6102 +28407 1342 6812 6487 6960 +28408 3828 6811 6488 6959 +28409 3979 6774 6772 7085 +28410 3167 5800 2921 7077 +28411 3564 2616 3498 6117 +28412 3859 6757 6638 6830 +28413 3214 3212 3213 6179 +28414 1349 2588 1465 6844 +28415 1784 1699 2019 6348 +28416 3357 3343 3411 6183 +28417 4987 5006 4986 5791 +28418 3959 6538 6539 6638 +28419 6540 6541 1473 6637 +28420 2657 2484 5886 7052 +28421 1592 1601 1595 6422 +28422 4058 4371 4217 5895 +28423 4491 4157 4306 6597 +28424 4015 4289 4220 6230 +28425 4212 6242 4094 7072 +28426 6163 6919 6011 7158 +28427 6219 6508 3489 6745 +28428 5370 5419 6185 6628 +28429 1188 1514 1313 6732 +28430 4000 3799 3674 6731 +28431 1204 6699 1471 6827 +28432 3688 3896 3782 6736 +28433 3167 2425 2801 5800 +28434 31 5738 6722 6743 +28435 307 6384 2247 6690 +28436 4446 4108 4198 5848 +28437 4336 28 503 6449 +28438 358 2346 6519 6793 +28439 2655 3481 3482 6105 +28440 4135 4430 6225 6579 +28441 1751 1811 2009 6376 +28442 3488 3360 6404 7036 +28443 5759 6849 4906 6985 +28444 4432 4115 4166 6144 +28445 4560 5796 4499 7164 +28446 3314 5882 1376 7008 +28447 5305 4626 5133 6618 +28448 5270 5264 4652 5842 +28449 2981 5866 3000 7160 +28450 5938 6754 6135 7154 +28451 4097 4354 4222 6026 +28452 3554 5765 3464 6870 +28453 2693 2698 3105 5938 +28454 3835 6389 3778 7023 +28455 2098 1777 303 6238 +28456 2775 2733 2732 6060 +28457 4473 4095 5865 7095 +28458 1327 6804 6732 6994 +28459 5086 6398 4952 7101 +28460 5588 5529 5474 6620 +28461 5746 5687 5632 6619 +28462 4805 5304 5308 5986 +28463 4980 6148 4979 7029 +28464 4725 4724 5896 6623 +28465 2154 1749 1885 5974 +28466 2155 1748 1884 5973 +28467 216 3643 215 6190 +28468 4253 6429 4065 6706 +28469 629 6723 6492 6730 +28470 1542 5922 1628 6653 +28471 4844 4869 4843 6652 +28472 5118 5160 5117 6275 +28473 516 515 6384 6661 +28474 2612 2907 6252 6713 +28475 5056 5057 4802 6213 +28476 5447 5485 5589 6913 +28477 2646 2647 2648 5898 +28478 2676 6246 2979 6920 +28479 1725 2150 2053 5935 +28480 4764 6263 4602 7194 +28481 6348 6485 1784 7156 +28482 3647 6014 231 7080 +28483 2914 2922 2935 7075 +28484 4234 6352 4044 6410 +28485 6232 6453 5768 6809 +28486 1449 1531 1622 6925 +28487 3727 3937 6735 6900 +28488 2719 2744 2973 5998 +28489 5012 6054 5013 7150 +28490 3318 2640 2749 6372 +28491 425 3660 426 5833 +28492 3374 3373 3429 6004 +28493 2310 2334 349 6334 +28494 2228 2227 2236 6119 +28495 3680 6654 6595 7134 +28496 1194 6655 6596 7133 +28497 2376 447 2617 5809 +28498 1537 1622 1626 6925 +28499 4970 6724 5784 7123 +28500 5060 4952 6398 7101 +28501 6409 6943 234 6993 +28502 1963 1776 1652 5865 +28503 4109 4442 4356 6127 +28504 2897 5779 2896 7065 +28505 4166 4308 4403 6344 +28506 3401 3404 3402 6180 +28507 1697 2022 1786 6356 +28508 2215 2219 6318 7053 +28509 2108 5906 1636 7122 +28510 248 1526 1627 6324 +28511 3061 3344 3346 6789 +28512 1692 1778 1886 7171 +28513 5960 6681 4475 7072 +28514 3369 3459 6343 6965 +28515 4271 4394 479 6194 +28516 1550 1555 1548 6545 +28517 2739 2734 2736 6399 +28518 4073 4178 4346 6073 +28519 4206 4267 4055 6600 +28520 5186 5355 5188 6023 +28521 3474 3131 3129 5983 +28522 301 302 6350 7081 +28523 6527 7018 4107 7079 +28524 2961 3002 6451 7160 +28525 3066 3537 3561 5773 +28526 3645 218 3623 6261 +28527 1759 6301 1988 6658 +28528 386 385 5930 7044 +28529 3668 3889 3818 6971 +28530 1403 1332 1182 6972 +28531 4605 4788 4604 5904 +28532 2522 2853 2960 5775 +28533 1685 6283 1874 6950 +28534 1547 1544 1552 6698 +28535 2241 2249 2239 6292 +28536 3339 3056 2844 5831 +28537 2017 2133 1805 6072 +28538 1940 1717 1989 6206 +28539 5788 6880 6328 6991 +28540 4183 4419 4397 6198 +28541 5122 5187 5340 6179 +28542 3060 2993 2995 5874 +28543 3680 3824 6595 6654 +28544 1338 6596 1194 6655 +28545 3679 3930 3892 6593 +28546 1406 1193 1444 6594 +28547 4088 4284 4327 5878 +28548 4966 4967 5070 6003 +28549 2281 2285 2278 6387 +28550 6050 6966 6454 7140 +28551 3498 3440 3568 6612 +28552 2403 6154 2900 6914 +28553 309 2241 310 6291 +28554 2722 2974 3182 6042 +28555 274 6359 6756 7212 +28556 4526 4508 4499 6967 +28557 4492 4538 4562 5781 +28558 1840 6537 5807 7129 +28559 2150 2053 5935 7192 +28560 3187 6219 3489 6745 +28561 1334 1447 1228 6712 +28562 2826 6374 3234 6657 +28563 3114 3115 3116 6158 +28564 5518 6735 6603 6900 +28565 3200 6163 3423 6919 +28566 6269 6789 5921 7163 +28567 2859 6393 2858 7125 +28568 4261 4013 4214 6357 +28569 2173 1987 1656 7156 +28570 4379 4152 6301 6356 +28571 342 2246 341 6452 +28572 2397 5810 7041 7108 +28573 459 6097 4174 6838 +28574 1376 6728 1206 6775 +28575 5336 595 5335 5897 +28576 3958 6529 3876 6978 +28577 1472 6528 1390 6979 +28578 3590 3614 6077 7062 +28579 486 4359 487 5836 +28580 1788 1896 1697 6355 +28581 2805 2804 2796 5964 +28582 1535 1532 6756 7082 +28583 3749 6638 4002 7058 +28584 1204 1349 1471 6699 +28585 4884 4882 5790 6970 +28586 5036 6131 5086 7101 +28587 2621 2620 6084 7097 +28588 1372 1224 1294 7107 +28589 3087 2779 2731 5926 +28590 2640 2641 2639 6010 +28591 2298 2314 2347 7007 +28592 1275 6780 1330 6841 +28593 3816 3761 6783 6840 +28594 3007 3079 3008 7103 +28595 506 6209 6479 6550 +28596 1540 6653 6415 6756 +28597 5084 5160 5118 6275 +28598 1540 1534 6653 6756 +28599 4861 4916 4928 6010 +28600 3708 3860 3750 6820 +28601 2880 6050 2557 7016 +28602 5245 598 5244 6754 +28603 2163 1647 1944 5955 +28604 1943 2164 1646 5954 +28605 1777 6429 1964 6906 +28606 1479 6634 1401 6791 +28607 3965 6633 3887 6790 +28608 2505 6933 5830 7040 +28609 3657 3630 441 6123 +28610 4298 4169 4207 5935 +28611 2274 6846 2266 7081 +28612 1841 1630 2005 6204 +28613 4771 4772 4792 6835 +28614 30 558 6453 7089 +28615 3692 3953 3862 6826 +28616 3304 3193 3494 6243 +28617 5922 7082 3703 7119 +28618 270 1554 1557 6667 +28619 1760 1942 1986 6167 +28620 4134 4433 4428 6352 +28621 524 523 5430 6157 +28622 3663 3609 240 6169 +28623 529 4486 528 6147 +28624 5306 6272 4872 7043 +28625 2821 2629 2901 6197 +28626 1755 6066 1920 6677 +28627 5045 4950 4789 5978 +28628 1960 1697 2180 6032 +28629 562 6712 6632 6860 +28630 3309 3097 435 6696 +28631 3041 3155 2969 6621 +28632 1417 1186 6232 6694 +28633 2646 2652 2647 6750 +28634 4071 6624 6152 7132 +28635 2605 6125 2604 7162 +28636 4322 470 4385 6524 +28637 3400 6129 3466 6870 +28638 5573 5471 5445 6904 +28639 5603 5731 5629 6903 +28640 1988 1800 1714 6369 +28641 4336 7018 6449 7079 +28642 296 2168 295 6100 +28643 4744 4888 4743 5861 +28644 4735 4711 607 6982 +28645 5002 4957 4959 6217 +28646 5942 6608 6128 6749 +28647 2887 6177 2879 7016 +28648 2109 1783 1873 7047 +28649 476 4424 4250 6134 +28650 319 2206 320 5797 +28651 30 6458 6569 7205 +28652 4080 4190 4315 6223 +28653 3138 6941 5834 7182 +28654 4949 5033 5054 5990 +28655 1909 297 2123 6800 +28656 1653 6906 5996 6975 +28657 4029 6312 4196 6622 +28658 534 4555 6020 7136 +28659 4882 4886 5231 6074 +28660 3624 3638 214 6642 +28661 1570 1568 6303 7126 +28662 1701 1950 2183 5905 +28663 3000 2981 2915 5866 +28664 2564 2747 2743 6062 +28665 2022 6355 1896 7213 +28666 2264 6581 2260 6776 +28667 3272 3472 3271 6444 +28668 2997 2676 3070 6246 +28669 2182 2119 6178 6726 +28670 6699 6827 566 6878 +28671 446 2378 2492 6905 +28672 4350 4271 4157 6597 +28673 2524 2861 2961 5774 +28674 2539 6665 2537 6728 +28675 2302 2321 2329 6518 +28676 3516 3053 6567 7120 +28677 1665 6133 1970 7178 +28678 4182 5871 4460 6991 +28679 1715 1987 1798 6467 +28680 4004 6818 6611 6891 +28681 1518 6819 6610 6890 +28682 1284 1411 5850 6810 +28683 4428 4131 4303 6205 +28684 315 2223 316 6061 +28685 2528 3139 2526 6267 +28686 1388 1265 6890 6931 +28687 3874 3751 6891 6932 +28688 293 2020 1785 6449 +28689 3469 2957 2959 6217 +28690 4434 5953 4435 7015 +28691 2626 2624 2623 6131 +28692 3470 2639 2544 6767 +28693 4393 5994 4468 7087 +28694 2092 5967 1808 6958 +28695 3961 3775 3709 6716 +28696 5696 6984 6850 7137 +28697 1744 2080 1794 6034 +28698 3576 6748 5957 7138 +28699 1892 1934 3941 7025 +28700 1933 1455 1891 7024 +28701 4558 4512 473 6014 +28702 2914 3864 3922 7075 +28703 3502 3520 3506 6507 +28704 3238 2665 2866 6231 +28705 1776 1901 2077 5865 +28706 4926 5944 4925 7109 +28707 2223 315 2231 6822 +28708 4684 4892 5094 5832 +28709 1415 1351 1255 6974 +28710 357 2380 358 6048 +28711 3541 3521 2791 6330 +28712 3806 3727 3777 6877 +28713 1241 1291 1320 6879 +28714 4425 4197 6377 6588 +28715 4381 6322 4151 6527 +28716 503 502 5900 6741 +28717 5558 6765 462 7061 +28718 5205 6049 5204 7197 +28719 2126 1737 6203 6671 +28720 4111 4252 4233 6140 +28721 1830 1973 2058 6114 +28722 621 6392 622 6830 +28723 3049 2650 2649 6159 +28724 4083 4341 4353 6203 +28725 1553 1558 1556 6391 +28726 3606 6672 5948 7086 +28727 2437 2435 2434 5794 +28728 3373 3372 3375 6652 +28729 5614 6759 6487 6901 +28730 3562 3522 6041 6738 +28731 6467 6629 492 6787 +28732 3270 3269 3186 6591 +28733 5481 6852 5560 6853 +28734 5639 6850 5718 6851 +28735 2570 5893 2429 7045 +28736 2631 3100 2632 6148 +28737 343 6762 6040 7202 +28738 5956 6536 2677 6920 +28739 1843 1713 1983 6120 +28740 2706 2920 2936 6089 +28741 2765 2766 2767 6551 +28742 3745 6889 6264 7169 +28743 2513 3163 2512 5863 +28744 2701 3211 3142 6831 +28745 527 6284 5433 7066 +28746 3169 3579 6143 6713 +28747 5618 6487 5651 6865 +28748 5493 5460 6488 6866 +28749 2034 2056 1694 6073 +28750 4653 5841 4651 7022 +28751 1794 6034 2080 6980 +28752 4168 4082 4351 6175 +28753 4395 4060 4413 5951 +28754 1525 6419 1612 6794 +28755 3316 3347 2598 6276 +28756 1584 6305 1586 6871 +28757 3993 3795 6575 7119 +28758 2127 1691 1879 6211 +28759 4682 4852 6267 6951 +28760 2133 1805 6072 7059 +28761 1655 2009 1811 6376 +28762 1986 1846 1760 6322 +28763 1353 6416 1310 6722 +28764 2762 7064 6108 7195 +28765 3165 367 2512 5939 +28766 1973 1830 1646 6740 +28767 1941 1676 1842 6474 +28768 4158 4244 508 6360 +28769 4425 4030 4346 6073 +28770 3422 6347 3372 6747 +28771 4443 4148 4063 6146 +28772 4547 4500 4519 6253 +28773 4480 4071 6152 7132 +28774 4641 537 6798 6999 +28775 1840 5807 2070 7129 +28776 3379 6477 3257 6565 +28777 2662 2840 2661 7174 +28778 3596 3653 3607 5987 +28779 2201 2207 2214 6383 +28780 2476 3026 3027 6236 +28781 2613 2907 2906 6252 +28782 1502 6758 1373 6897 +28783 3973 6611 6818 6866 +28784 6610 6819 1487 6865 +28785 4609 4944 4834 5873 +28786 4055 6599 4439 6600 +28787 160 2539 2538 6728 +28788 1624 1621 1536 7017 +28789 6046 6555 3264 7139 +28790 4023 4168 4269 6493 +28791 4662 4664 4663 6363 +28792 4360 6475 5989 6944 +28793 4695 5239 4969 6374 +28794 2931 2663 2933 6394 +28795 3284 6021 3265 6795 +28796 5638 5680 6879 6901 +28797 2967 2681 2785 6015 +28798 3426 3148 2832 5861 +28799 5631 6769 6771 7071 +28800 5454 5516 5496 6538 +28801 5612 5674 5654 6540 +28802 4141 4225 4060 6406 +28803 1875 1806 1674 5876 +28804 1792 1958 1689 6149 +28805 4292 4068 4168 6176 +28806 1355 1276 1219 6453 +28807 1800 1988 2172 6369 +28808 1335 5875 1278 6587 +28809 5702 5621 5736 6694 +28810 454 5540 5495 6895 +28811 5693 6610 6819 6890 +28812 5535 6611 6818 6891 +28813 443 6020 3621 6768 +28814 4291 6403 4167 7210 +28815 4837 5027 5071 6065 +28816 587 4643 4644 6470 +28817 3054 5829 3053 7120 +28818 4644 4995 589 6017 +28819 5597 5635 5670 6596 +28820 5439 5477 5512 6595 +28821 1774 1848 2039 6432 +28822 3252 2919 2779 6472 +28823 5286 5343 5943 7214 +28824 4857 4912 5944 7037 +28825 4978 5296 5203 6101 +28826 4291 4067 6403 7210 +28827 3901 3683 6666 7058 +28828 5485 5528 626 6913 +28829 6542 7022 5914 7088 +28830 1606 6262 1611 7104 +28831 3445 3297 3487 6425 +28832 6669 7129 6341 7130 +28833 27 5804 490 6883 +28834 3724 6840 6620 6913 +28835 5117 4842 4840 6087 +28836 6705 6878 1484 6984 +28837 6704 6875 3970 6983 +28838 1336 6746 1499 6897 +28839 2547 2721 2548 5941 +28840 3744 3993 3795 6575 +28841 1692 1886 1816 6187 +28842 3426 3148 5861 7019 +28843 3709 3821 3961 6492 +28844 528 6147 4486 7018 +28845 1986 1657 1846 6322 +28846 3497 3232 3496 6074 +28847 3369 3482 3459 6965 +28848 3916 6488 3827 6900 +28849 3409 3397 3324 6753 +28850 2611 3320 3321 6363 +28851 2914 5884 2468 6887 +28852 5807 6537 6525 7141 +28853 5250 4813 5233 6158 +28854 5979 6798 6338 7161 +28855 4064 6341 4218 6669 +28856 32 5930 6674 6716 +28857 4347 6270 4170 7187 +28858 2017 6072 1805 7177 +28859 5659 6458 5721 6903 +28860 5501 6459 5563 6904 +28861 4195 4053 4197 6076 +28862 30 7089 6453 7205 +28863 4021 4298 4207 5935 +28864 2534 2536 2535 6214 +28865 4285 4089 4206 6395 +28866 511 6296 5403 6435 +28867 483 4552 4509 5948 +28868 3035 2920 2706 6089 +28869 4869 5216 5215 6347 +28870 3900 3694 3834 6440 +28871 4184 488 487 6192 +28872 2644 6096 2546 6839 +28873 459 6686 5932 6924 +28874 461 4380 462 6337 +28875 1635 1932 1808 5967 +28876 6189 6587 5850 7096 +28877 1573 6094 1568 7126 +28878 4685 4683 4914 6060 +28879 2609 2714 2724 6221 +28880 3547 3536 3149 5923 +28881 3763 3710 3820 5827 +28882 5537 6530 6932 7010 +28883 6531 6931 5695 7012 +28884 1997 6906 1653 6975 +28885 4227 4442 7131 7203 +28886 3004 2606 3197 6473 +28887 4052 4392 4138 6385 +28888 2380 6048 357 7107 +28889 2798 2449 5945 6947 +28890 3796 6580 3839 6720 +28891 5214 5293 5276 6496 +28892 522 4462 4232 6145 +28893 4088 5878 4327 6615 +28894 1689 2083 1792 6149 +28895 5630 6533 5725 6758 +28896 5567 5472 6534 6757 +28897 4289 4193 4121 5996 +28898 4825 4823 4696 5892 +28899 4187 4117 6114 7046 +28900 1614 1618 1612 6794 +28901 5294 5289 5280 6216 +28902 1658 2172 1988 7026 +28903 5698 5653 494 6881 +28904 498 5740 7005 7071 +28905 1519 1401 1375 6528 +28906 3861 4005 3887 6529 +28907 4729 4864 4730 6523 +28908 3563 3068 3075 6590 +28909 1218 1345 1470 6902 +28910 312 313 6153 7180 +28911 3409 3324 3410 6012 +28912 426 6672 3611 6963 +28913 238 6545 1552 6698 +28914 5065 4649 5064 6130 +28915 1497 6549 1330 6780 +28916 3816 3983 6548 6783 +28917 4212 4059 6242 6681 +28918 4921 4657 4917 6659 +28919 5494 6783 5464 6785 +28920 5652 6780 5622 6782 +28921 4461 6019 4114 7153 +28922 4899 4897 5316 6517 +28923 381 2817 382 6080 +28924 5452 6811 7112 7134 +28925 5610 6812 7111 7133 +28926 1695 1919 1851 6196 +28927 1747 6146 2137 7032 +28928 4308 4441 4265 6222 +28929 627 6124 628 6509 +28930 3888 2714 3753 6221 +28931 2503 2577 2576 7191 +28932 3400 3467 3466 6129 +28933 5191 5192 5190 6752 +28934 4710 4709 5333 6711 +28935 1972 2163 1778 6223 +28936 229 3651 3603 6251 +28937 3003 2528 2527 6155 +28938 2261 2266 2267 7081 +28939 3269 3273 3177 5842 +28940 2534 3174 2536 6214 +28941 3376 6289 3378 7166 +28942 4539 556 4508 6967 +28943 341 2251 340 6506 +28944 2239 6292 2248 7202 +28945 4914 6372 4913 7029 +28946 3284 3459 3494 6343 +28947 1751 2009 1841 6376 +28948 2854 2742 2741 6364 +28949 4322 4140 6407 6524 +28950 2147 2153 1833 5989 +28951 5308 6392 621 6643 +28952 4848 5971 4846 6737 +28953 4002 6638 6539 7058 +28954 2105 1836 2037 6270 +28955 2267 2273 335 6439 +28956 3021 2391 2393 6162 +28957 1451 6602 1191 6901 +28958 1732 2032 2065 6029 +28959 1873 1766 2053 5837 +28960 2800 2657 2484 5886 +28961 3897 3968 3689 6509 +28962 1895 1789 1698 6311 +28963 1443 1200 6649 7012 +28964 3929 3686 6648 7010 +28965 2252 2259 2250 6319 +28966 2447 2448 3802 7174 +28967 5714 6541 5628 6972 +28968 5470 5556 6539 6971 +28969 27 4333 490 6485 +28970 3285 3265 3191 6021 +28971 4972 6044 549 7039 +28972 1684 1780 1832 5763 +28973 2139 6145 1853 7057 +28974 4077 6942 6222 6964 +28975 5009 5010 4606 6162 +28976 1211 6561 1338 6655 +28977 3824 3697 6562 6654 +28978 377 5901 2464 7206 +28979 2352 2313 2300 6136 +28980 2549 2547 2548 5941 +28981 1215 1267 1387 6125 +28982 1300 6482 1405 6728 +28983 4777 4725 4851 6693 +28984 2327 345 344 6435 +28985 4904 5215 5065 7167 +28986 4854 4856 4855 6299 +28987 5362 5283 5773 7135 +28988 1224 1363 1509 7040 +28989 1818 2102 1733 5764 +28990 4481 4133 4296 6133 +28991 1841 2060 2137 6205 +28992 2810 6749 5942 7013 +28993 2458 6257 3196 6969 +28994 5421 5401 5373 6334 +28995 4911 4689 4910 6059 +28996 4181 495 494 6474 +28997 5486 5560 5448 6852 +28998 5718 5606 5644 6850 +28999 2288 6510 2287 7034 +29000 5721 6458 5621 6903 +29001 5463 5563 6459 6904 +29002 247 2160 248 5804 +29003 3894 3803 3936 6620 +29004 1408 1317 1450 6619 +29005 5254 6427 5154 6513 +29006 3853 3707 3798 6636 +29007 2738 6109 2927 6660 +29008 1675 2185 2110 6113 +29009 259 1901 1776 6194 +29010 6187 6930 6186 7188 +29011 1873 5837 2053 7047 +29012 4541 4538 4492 5781 +29013 1640 2182 2119 6178 +29014 4108 5848 4446 7170 +29015 2593 6058 2594 7173 +29016 2106 1837 2036 6175 +29017 300 6145 2139 7143 +29018 3214 3213 3215 6300 +29019 4947 4945 5052 5856 +29020 1964 5996 1653 6906 +29021 3130 2417 2419 6083 +29022 5798 6889 6566 7169 +29023 6580 6765 5465 6862 +29024 1419 6632 1289 6743 +29025 4853 5107 5108 6155 +29026 2308 2327 2320 6679 +29027 438 3607 3653 5987 +29028 498 7005 7004 7071 +29029 4907 4908 5912 6849 +29030 553 4646 4647 6445 +29031 6208 6697 6737 6969 +29032 1508 2579 2499 6848 +29033 1703 1963 1821 5885 +29034 524 5399 525 6285 +29035 4242 5905 4032 6949 +29036 622 6638 621 6830 +29037 4174 6097 6547 6952 +29038 5190 5192 5128 6277 +29039 4268 6018 4165 7210 +29040 2445 2773 2399 6189 +29041 4262 4317 4143 6027 +29042 5176 5173 5259 5965 +29043 2888 2890 2982 6504 +29044 2858 6393 2859 7124 +29045 2218 7053 5992 7213 +29046 5120 5163 5119 6208 +29047 2391 3021 2525 6162 +29048 4883 5281 5229 6970 +29049 274 2021 1787 6359 +29050 3750 3684 3853 6820 +29051 3528 6046 3264 7139 +29052 5413 5382 5401 6067 +29053 1629 2125 6341 7130 +29054 3516 6179 3212 7120 +29055 3477 6986 3310 7097 +29056 2027 2014 1762 6244 +29057 1376 2539 160 6728 +29058 3715 6509 6723 7041 +29059 3924 2344 3831 6889 +29060 1793 1957 1691 6377 +29061 460 459 4240 6838 +29062 6349 6714 6291 7201 +29063 2336 359 2356 6793 +29064 3303 2811 5859 7065 +29065 3771 3896 6412 7075 +29066 6459 6570 3817 6904 +29067 1331 6458 6569 6903 +29068 3455 6063 3477 7097 +29069 4128 4337 4261 6244 +29070 2537 6727 2538 6728 +29071 3395 3561 3433 6554 +29072 5575 6580 5515 7207 +29073 5423 5385 5374 6136 +29074 2332 2361 6040 7151 +29075 5913 7196 6553 7197 +29076 4669 4998 4963 6086 +29077 1367 1221 1312 6629 +29078 4906 6849 5759 7147 +29079 5416 597 5392 6478 +29080 4376 4284 4088 5878 +29081 3118 5857 6914 7042 +29082 1431 1531 183 1323 +29083 273 1551 272 6428 +29084 634 6416 635 6476 +29085 370 5825 371 7063 +29086 3645 3591 3608 5796 +29087 3931 6593 3730 6785 +29088 1445 6594 1244 6782 +29089 2716 2718 3101 5869 +29090 4266 4440 4307 6535 +29091 6819 6890 1299 7199 +29092 6818 6891 3785 7200 +29093 1874 1685 1807 6283 +29094 30 5919 7089 7205 +29095 4205 4026 4259 7170 +29096 3816 6548 3696 7113 +29097 1330 6549 1210 7114 +29098 3166 3189 3254 5937 +29099 2550 2912 3533 6031 +29100 2903 2902 3092 6969 +29101 3558 3063 2898 6560 +29102 3368 3513 6542 7173 +29103 5569 5468 5504 6654 +29104 5727 5626 5662 6655 +29105 5696 7060 6984 7137 +29106 2483 3026 2478 6237 +29107 513 6291 512 6586 +29108 5767 6519 2346 6793 +29109 6088 6933 2451 7040 +29110 4037 4471 4474 6532 +29111 3658 3593 3617 6253 +29112 2060 6205 1683 7032 +29113 3676 6631 3898 7190 +29114 513 5387 5417 6040 +29115 6803 6922 5555 6989 +29116 541 5243 540 6515 +29117 2455 2453 2454 6927 +29118 4604 4606 4605 6646 +29119 4912 4925 4857 5944 +29120 5323 4817 4816 5907 +29121 3414 3415 3413 7102 +29122 5043 4648 4646 6526 +29123 4063 4303 4219 6205 +29124 1561 1558 235 6391 +29125 269 1560 6408 6667 +29126 3055 3053 2910 5829 +29127 4297 4480 4071 6152 +29128 4112 4235 6139 7183 +29129 4125 4282 4328 5906 +29130 4982 5800 4619 7189 +29131 3822 6830 3859 7058 +29132 568 567 6191 6498 +29133 5314 4842 5161 6424 +29134 5321 5350 5177 5909 +29135 1259 6232 1308 7017 +29136 4655 5098 4917 6105 +29137 3776 3713 3905 6907 +29138 2973 2744 2582 5998 +29139 2270 6329 2272 7143 +29140 4342 4187 4369 6113 +29141 5151 4686 5241 7067 +29142 2227 6119 2229 7180 +29143 1300 6727 6482 6728 +29144 6224 7123 4839 7167 +29145 4114 4165 4408 7153 +29146 4623 4624 4988 6792 +29147 4211 6326 4403 6942 +29148 4235 4032 6139 7146 +29149 2900 2403 2901 6154 +29150 3217 3091 2841 6191 +29151 2387 3126 3127 5888 +29152 5521 6641 6539 7193 +29153 3817 3711 3915 6459 +29154 1429 1331 1225 6458 +29155 1661 1792 2035 6018 +29156 3921 3120 3770 7041 +29157 1633 1966 1809 6055 +29158 2480 2589 2486 5917 +29159 5388 5372 5415 6184 +29160 4514 470 471 6112 +29161 4799 4868 5025 6164 +29162 1736 2125 1861 6635 +29163 1712 2059 1974 6000 +29164 3483 3150 2885 6172 +29165 4563 4564 4566 5964 +29166 3640 3605 224 6307 +29167 310 6290 1855 7201 +29168 5359 4615 5366 6063 +29169 2360 2319 361 5813 +29170 5494 6784 6783 6785 +29171 5652 6781 6780 6782 +29172 4733 556 557 5969 +29173 1259 6809 6232 7017 +29174 2364 6115 382 6981 +29175 2933 2934 3052 5962 +29176 4016 4266 4477 6475 +29177 4254 4204 4066 5940 +29178 2800 3286 2583 6808 +29179 1959 1790 1664 6033 +29180 4302 4434 4045 6420 +29181 1786 6356 6505 7026 +29182 2869 6023 2867 6929 +29183 2924 2615 6009 7023 +29184 4142 4279 4477 7185 +29185 5079 4596 4924 6511 +29186 368 2353 367 5939 +29187 5780 6755 5775 7145 +29188 4188 4286 4464 5999 +29189 2668 3502 3506 6297 +29190 3410 3424 6012 7158 +29191 5189 5352 6012 6752 +29192 5026 4818 4808 6502 +29193 5256 5278 5169 6007 +29194 4292 4068 6176 7056 +29195 4450 4217 4371 5895 +29196 4535 464 4542 6169 +29197 4404 4165 4022 6018 +29198 4187 4117 4448 6114 +29199 2863 7117 5867 7160 +29200 2315 2297 2349 6184 +29201 331 2285 330 6387 +29202 2418 2767 2770 6457 +29203 2997 2998 2410 5887 +29204 4287 4189 4079 5966 +29205 25 5797 450 6882 +29206 297 2280 298 6379 +29207 4946 5101 4945 7106 +29208 5015 5880 604 6617 +29209 4639 5015 604 6617 +29210 5354 5132 5133 6618 +29211 2551 2552 2550 6433 +29212 5878 6544 5928 6952 +29213 2625 3037 3036 6398 +29214 4183 466 465 6198 +29215 3531 3522 3190 6455 +29216 3891 3723 3972 6604 +29217 4559 6022 6967 7150 +29218 3036 3037 3198 6500 +29219 3082 6273 3083 7168 +29220 3312 2543 2596 6003 +29221 3438 3493 3439 6358 +29222 6503 6575 3795 7119 +29223 3324 3396 3316 6277 +29224 1237 6482 1300 6727 +29225 3584 5768 3601 7090 +29226 4857 6028 4993 7037 +29227 5721 5621 6583 6903 +29228 5463 6584 5563 6904 +29229 2762 6108 2763 7195 +29230 3857 3963 3779 6716 +29231 5930 6716 5820 7191 +29232 3871 6765 6564 7031 +29233 2130 1818 2099 6071 +29234 4705 4706 4704 6103 +29235 2943 2942 2951 6269 +29236 5025 4868 575 6164 +29237 4065 4257 4465 7184 +29238 3787 3694 3900 7061 +29239 236 1555 237 6362 +29240 330 2359 2321 6284 +29241 3359 3506 3350 6288 +29242 2071 2109 1721 5895 +29243 2703 3151 3150 5965 +29244 593 4824 594 6001 +29245 5905 4032 6949 7146 +29246 4274 4311 4028 6207 +29247 1892 1714 1934 7025 +29248 1715 1933 1891 7024 +29249 3530 3500 3501 6748 +29250 1386 1203 6701 6810 +29251 5370 5419 5390 6185 +29252 2972 2971 2970 6621 +29253 4798 5060 4797 6122 +29254 1929 1860 1680 7105 +29255 2910 3053 3054 5829 +29256 2394 6998 6898 7108 +29257 5830 6860 1224 7040 +29258 5566 6534 5472 6676 +29259 5724 6533 5630 6675 +29260 5126 5815 6753 6837 +29261 4967 6003 4966 6724 +29262 2495 2494 420 5969 +29263 304 303 2265 6238 +29264 3020 3102 3065 5868 +29265 4781 6247 562 6829 +29266 1385 6766 6563 6956 +29267 4722 4746 4747 6013 +29268 3744 3795 6503 6575 +29269 604 5380 5397 6325 +29270 4399 4101 6410 6588 +29271 2339 2342 2296 7044 +29272 2255 2254 2264 6405 +29273 2152 5906 2108 7115 +29274 1480 1308 1259 6232 +29275 5921 7163 6789 7198 +29276 4973 5077 4665 6252 +29277 4236 6271 4377 7187 +29278 3327 6374 2826 6915 +29279 2984 2809 2895 7175 +29280 3437 3476 3440 6239 +29281 6804 6923 5713 6994 +29282 598 6135 6754 7154 +29283 1928 1722 1921 5951 +29284 2594 6973 2592 7173 +29285 5363 5166 5210 6400 +29286 5269 6314 5246 6626 +29287 1196 1442 1361 6722 +29288 5415 6184 5372 6854 +29289 1529 3808 246 3912 +29290 3407 3088 3370 5925 +29291 4004 3665 3874 6891 +29292 1388 1518 1179 6890 +29293 1674 5876 1806 7122 +29294 1777 2076 1900 6225 +29295 4834 5873 4944 6985 +29296 521 4430 520 6350 +29297 1265 1445 1299 7199 +29298 3751 3931 3785 7200 +29299 6692 6915 6374 7206 +29300 618 4767 5080 6885 +29301 418 419 5919 7090 +29302 2523 2460 3023 6680 +29303 6637 6758 572 6897 +29304 4993 4857 4941 6028 +29305 2152 1636 2108 5906 +29306 2914 5884 6887 7075 +29307 1391 6640 1262 6974 +29308 3428 3427 3429 6224 +29309 1999 1920 1755 6066 +29310 2908 6486 2825 6657 +29311 5086 5088 5087 7027 +29312 4412 4237 456 6468 +29313 4568 4569 4896 6015 +29314 3848 6983 7054 7190 +29315 4265 6222 6558 6964 +29316 517 518 6405 6854 +29317 3168 2692 3003 6039 +29318 4156 6225 4430 7056 +29319 5509 6564 6765 7031 +29320 1498 1204 1471 6827 +29321 2790 2409 2459 5823 +29322 4799 4797 4589 6282 +29323 5418 5383 5369 6200 +29324 2661 2798 2449 5945 +29325 553 4647 552 6445 +29326 4286 4080 4464 5999 +29327 5558 5509 462 6765 +29328 5716 5667 502 6766 +29329 1858 1762 2014 6244 +29330 301 2042 1853 6350 +29331 2664 6299 2554 6945 +29332 2317 2307 2366 6200 +29333 2736 3572 3267 6035 +29334 4786 4730 4864 5889 +29335 2073 6975 5996 7176 +29336 4942 4855 4856 7211 +29337 3429 3373 3428 5784 +29338 3480 6105 3481 7001 +29339 5163 6208 5120 7027 +29340 2876 2877 2875 6427 +29341 4664 4653 4973 7022 +29342 4960 5908 4926 7109 +29343 2984 2895 5929 7175 +29344 5739 5615 6819 6890 +29345 5581 5457 6818 6891 +29346 1300 1376 160 6728 +29347 3903 3672 3794 6264 +29348 3657 3593 3630 6123 +29349 4289 4401 4099 6230 +29350 3306 3305 3307 6263 +29351 2613 2612 6252 7148 +29352 565 6381 566 6699 +29353 3939 6725 3845 6807 +29354 5064 6289 5063 7167 +29355 3167 2921 2690 7077 +29356 4033 6032 4313 7132 +29357 1656 1987 1847 6249 +29358 6369 6636 452 6820 +29359 4743 5244 4750 6670 +29360 2539 3084 2537 6665 +29361 4199 4049 4281 6607 +29362 2961 3002 2413 6451 +29363 3509 3353 3354 5839 +29364 1896 2167 316 7213 +29365 5010 5168 5076 6161 +29366 3472 3271 6444 6483 +29367 4100 4194 4365 6071 +29368 354 353 6889 7169 +29369 4616 4626 4615 6345 +29370 1583 6568 1587 7051 +29371 1708 2042 1900 6225 +29372 4866 4623 4988 5931 +29373 1712 1982 5915 7122 +29374 2979 5780 2980 6920 +29375 2441 2523 3023 5896 +29376 2205 6287 2216 6911 +29377 4364 4466 4249 5947 +29378 2795 6208 2903 6697 +29379 5062 5275 4661 6343 +29380 5810 6693 6492 6898 +29381 1390 6703 6649 6979 +29382 3876 6702 6648 6978 +29383 1275 6781 6780 6841 +29384 3761 6784 6783 6840 +29385 6629 6881 1274 7209 +29386 4921 6659 6343 6965 +29387 3599 3623 219 6894 +29388 1482 6543 1203 6810 +29389 6563 6766 5667 6956 +29390 3286 3132 3158 6808 +29391 2390 6099 2389 7186 +29392 3851 6760 3685 6866 +29393 1365 6759 1199 6865 +29394 5835 6746 1252 6824 +29395 2658 3034 2824 6122 +29396 3369 3442 3370 6795 +29397 3796 3928 3839 6580 +29398 4230 4074 4177 6461 +29399 3188 3114 3187 6745 +29400 3901 6666 6749 7013 +29401 3103 2851 3104 7050 +29402 576 6640 5679 6974 +29403 3078 3276 3275 7198 +29404 4230 4045 4434 6460 +29405 2323 2362 2306 6067 +29406 3264 6046 3266 6795 +29407 4685 4684 4683 6700 +29408 3044 5997 3045 7020 +29409 233 6943 6112 6993 +29410 4885 4681 5327 5834 +29411 4630 6346 5124 6899 +29412 4098 4202 4267 6734 +29413 4817 5907 5323 7067 +29414 4921 4661 4660 6522 +29415 2331 2348 372 6185 +29416 1872 2070 1840 5807 +29417 5438 5514 5539 6939 +29418 5672 5697 5596 6940 +29419 4008 3838 3734 7208 +29420 1248 1522 1352 7209 +29421 2355 327 2311 6141 +29422 604 605 5406 5880 +29423 4525 533 4541 5924 +29424 3324 3316 2600 6276 +29425 1820 6441 2117 7176 +29426 5177 5176 5257 6708 +29427 5170 5134 5096 6553 +29428 1190 1447 1334 6632 +29429 3934 3820 3676 6631 +29430 1414 6278 1245 6825 +29431 3588 3639 3611 7086 +29432 2370 347 2312 6068 +29433 3277 5921 2943 7198 +29434 2971 3180 2969 6621 +29435 2923 2683 2966 6016 +29436 4864 581 580 6523 +29437 2794 2823 2825 6258 +29438 6389 6876 6009 7023 +29439 2791 2550 2552 5972 +29440 5390 5419 595 6962 +29441 5179 5129 5178 5972 +29442 5217 5331 5092 6091 +29443 619 6317 620 6826 +29444 5335 5333 5336 6711 +29445 5875 6587 6189 7096 +29446 5509 6765 5575 7031 +29447 1302 1405 1486 6482 +29448 5608 5666 6890 6931 +29449 5450 5508 6891 6932 +29450 628 5810 629 6723 +29451 5968 6847 6033 7157 +29452 4694 4691 4692 6043 +29453 576 4577 577 6473 +29454 3050 6259 3071 7152 +29455 1959 2181 1696 6138 +29456 1810 1705 1976 6242 +29457 3013 3009 3008 6069 +29458 1699 6348 2010 6918 +29459 1826 2117 5844 7176 +29460 1608 1605 1610 6464 +29461 2189 5817 1671 6992 +29462 4233 4031 4402 6995 +29463 3835 3957 6389 7023 +29464 3357 3411 3412 6183 +29465 3611 5988 427 6963 +29466 4591 589 4995 6017 +29467 1708 1923 2087 6176 +29468 4140 4236 4060 6271 +29469 6441 6706 4252 7184 +29470 2330 369 2354 6135 +29471 5391 592 5418 6268 +29472 3120 7041 2769 7110 +29473 3260 3224 3188 6745 +29474 4070 4483 4239 5817 +29475 2796 2805 5964 6977 +29476 4363 4059 4209 6055 +29477 1524 1459 1225 6903 +29478 3711 4010 3945 6904 +29479 1605 1608 1606 6464 +29480 5667 6766 5733 6956 +29481 2974 2722 2927 6660 +29482 4270 4235 4032 6139 +29483 1575 1581 263 6327 +29484 2203 2204 2202 6572 +29485 5587 5478 6907 7207 +29486 2497 2511 6381 6761 +29487 3858 6497 3710 6886 +29488 5912 6849 4908 7147 +29489 2814 2819 6688 7045 +29490 1893 6677 6352 6934 +29491 4155 6291 4429 6714 +29492 5093 4668 5049 6075 +29493 4093 4249 4460 6858 +29494 1698 2179 2011 6527 +29495 4046 4452 4263 5853 +29496 6802 6931 1243 7012 +29497 6801 6932 3729 7010 +29498 1787 1956 6359 6806 +29499 1853 300 301 6145 +29500 4459 4054 6286 7170 +29501 2696 2697 2655 6553 +29502 5256 4739 5278 6007 +29503 5782 5789 6764 7181 +29504 3332 2638 3330 6336 +29505 3135 3133 2666 5799 +29506 3777 6735 3881 6828 +29507 6004 3374 6747 7166 +29508 2036 6175 1837 6673 +29509 4187 6113 4024 7046 +29510 3991 6922 3813 6989 +29511 1625 1529 1528 6575 +29512 6562 6595 3824 6654 +29513 1338 6561 6596 6655 +29514 6530 6891 5508 6932 +29515 6531 6890 5666 6931 +29516 2310 2338 6321 6598 +29517 4013 4285 4206 6395 +29518 3819 3788 3721 6603 +29519 1235 1333 1302 6602 +29520 3217 2710 3091 6869 +29521 4431 6019 4231 7210 +29522 3516 6567 6179 7120 +29523 4153 4328 4086 5959 +29524 349 2230 348 6116 +29525 4775 4719 5780 7145 +29526 1895 1698 2020 6311 +29527 2560 2713 2746 6608 +29528 622 5929 6835 7058 +29529 3259 2669 3257 6332 +29530 4613 4614 5147 6332 +29531 1504 1345 1218 6519 +29532 4207 6079 4319 7095 +29533 5702 5621 6694 6996 +29534 3206 3327 2464 7206 +29535 4371 4058 4208 6066 +29536 5590 616 6735 6828 +29537 3682 3858 3964 6721 +29538 3380 3381 3379 6091 +29539 4564 5964 4565 7121 +29540 592 5391 591 6268 +29541 1644 6222 2100 6817 +29542 4469 4205 4119 7170 +29543 3690 6828 6389 6876 +29544 1821 1918 1703 5885 +29545 1835 6168 1886 7171 +29546 5385 6136 519 6854 +29547 436 3649 437 6421 +29548 2928 3137 3139 7182 +29549 1797 5999 1972 7091 +29550 5691 5616 5649 7005 +29551 5458 5491 5533 7003 +29552 4421 4160 4042 5872 +29553 1797 2184 1974 5999 +29554 2418 2419 2417 6457 +29555 4382 6556 7146 7183 +29556 3821 3933 3675 6723 +29557 2909 3241 2795 6208 +29558 2736 2735 2740 6678 +29559 466 4507 465 6165 +29560 3813 6922 6803 6989 +29561 2260 2263 2261 6331 +29562 1968 1756 1863 6349 +29563 2604 2605 2606 6125 +29564 3682 6720 3928 6721 +29565 4649 4654 4608 6129 +29566 2036 1718 1812 6326 +29567 4912 4926 4925 7109 +29568 312 2141 311 6625 +29569 4158 4408 4297 6151 +29570 2402 2816 381 6080 +29571 1229 1435 1284 5850 +29572 3077 371 2695 5825 +29573 3937 3777 3727 6735 +29574 4507 4525 5924 7136 +29575 1847 1987 1758 6249 +29576 5475 5543 5593 6564 +29577 5751 5633 5701 6563 +29578 5462 6875 6704 6983 +29579 5620 6878 6705 6984 +29580 3550 2700 2702 6024 +29581 1756 1867 2144 5940 +29582 435 3097 434 6302 +29583 4326 4152 4033 6432 +29584 4904 4839 7123 7167 +29585 4193 6441 4252 7184 +29586 3530 6748 3576 7138 +29587 4969 6374 5239 6814 +29588 2746 2809 2810 5942 +29589 3919 6853 3801 6893 +29590 1433 6851 1315 6892 +29591 5199 5250 5197 6220 +29592 1546 1544 1551 6415 +29593 4154 4034 4397 6615 +29594 3347 3047 3242 6150 +29595 5610 5655 6812 7133 +29596 5497 6811 5452 7134 +29597 248 249 1527 6324 +29598 4975 4990 4974 5984 +29599 1579 1587 261 6568 +29600 2326 2314 2298 6234 +29601 4525 4541 4507 5924 +29602 501 5751 6563 6997 +29603 3478 3481 2697 7001 +29604 5397 603 604 6325 +29605 628 6509 5810 6723 +29606 1919 1890 1754 5872 +29607 4765 4602 4764 6263 +29608 3474 3129 2860 5983 +29609 2875 3472 3272 6427 +29610 5517 6654 5468 7134 +29611 5675 6655 5626 7133 +29612 4649 4650 5068 6339 +29613 5083 5082 5084 6174 +29614 3722 3869 3851 6676 +29615 1365 1236 1383 6675 +29616 617 4768 4767 7189 +29617 1720 1871 2015 5947 +29618 1860 6203 1737 7105 +29619 2988 2968 3166 6059 +29620 3710 3763 3849 6886 +29621 564 4896 4569 6015 +29622 1395 1291 6498 6827 +29623 4323 6196 4081 6991 +29624 1707 2086 6403 7201 +29625 5357 5195 5194 6011 +29626 5748 567 5689 6827 +29627 1715 2074 1941 6248 +29628 1714 2075 1939 6250 +29629 5621 5721 5659 6458 +29630 5563 5501 5463 6459 +29631 5076 5167 5075 5843 +29632 5628 5729 5679 6541 +29633 5571 5521 5470 6539 +29634 2932 5944 2819 7068 +29635 3973 6611 4004 6818 +29636 1518 1487 6610 6819 +29637 6827 6878 1320 6879 +29638 6828 6875 3806 6877 +29639 1962 2146 1667 5958 +29640 2059 1712 1842 5915 +29641 2936 2781 2862 6247 +29642 5011 586 4996 6080 +29643 6291 7028 6290 7201 +29644 4796 5780 4719 6755 +29645 5104 4748 4746 6606 +29646 4748 4747 4746 6013 +29647 4493 4508 4540 6077 +29648 2411 444 2412 6768 +29649 1642 6071 2099 6980 +29650 4893 5094 4892 5832 +29651 374 6001 2812 6926 +29652 4233 4402 4066 6578 +29653 4327 4122 4426 5877 +29654 2702 2701 2904 6831 +29655 2183 5905 1950 6992 +29656 5555 5449 5507 6803 +29657 5713 5607 5665 6804 +29658 1426 1321 1624 7017 +29659 3924 6889 3745 7169 +29660 3823 6882 3672 7094 +29661 6033 6988 5968 7157 +29662 6420 6669 6341 7203 +29663 3206 3234 3327 6374 +29664 3521 3510 6330 6738 +29665 5218 5912 4908 7147 +29666 298 2277 299 7143 +29667 5889 7049 5888 7195 +29668 3804 6631 3905 6907 +29669 1786 2022 318 6505 +29670 3150 3149 3490 5923 +29671 1337 6883 1186 6996 +29672 5190 6752 6277 6753 +29673 5255 5147 5217 6565 +29674 4644 4643 4645 6154 +29675 457 5851 458 7002 +29676 498 497 5852 7004 +29677 433 3033 432 5903 +29678 2230 2222 2221 6209 +29679 3523 6742 5961 7196 +29680 4355 4018 4366 7099 +29681 1258 1345 1438 6902 +29682 4940 5120 5119 6737 +29683 563 4781 4896 6247 +29684 2316 2347 366 6052 +29685 6538 6539 5556 6971 +29686 6540 6541 5714 6972 +29687 2791 3544 2550 5972 +29688 3345 3344 2951 6137 +29689 469 6391 468 6667 +29690 507 5393 508 6116 +29691 3000 5866 2915 7152 +29692 4348 4475 4027 5960 +29693 1691 2082 1793 6377 +29694 3202 3276 3078 6086 +29695 595 5897 5336 6962 +29696 2850 6235 2864 7050 +29697 5220 5254 5154 6513 +29698 2048 1857 1741 5858 +29699 1919 1695 1890 5872 +29700 635 5741 6476 6722 +29701 2175 6806 2026 6833 +29702 6723 7041 5810 7108 +29703 3205 3528 3268 7139 +29704 2611 3179 3320 6363 +29705 5202 4654 4649 6129 +29706 3720 6959 3867 7134 +29707 1381 1234 6960 7133 +29708 1847 1772 2178 5959 +29709 3483 3143 3141 6424 +29710 1367 1264 1198 6787 +29711 6636 6895 3760 7208 +29712 3456 3455 6466 7084 +29713 3617 235 6253 6943 +29714 427 3611 3639 5988 +29715 1406 1243 6802 6931 +29716 3892 3729 6801 6932 +29717 3502 2668 2670 6297 +29718 308 2249 309 6690 +29719 1555 1550 237 6545 +29720 1243 6931 1464 7012 +29721 3729 6932 3950 7010 +29722 4910 4909 4911 6059 +29723 4544 472 4512 6682 +29724 6066 7047 1999 7192 +29725 4045 4230 4177 6072 +29726 3865 3969 3747 6947 +29727 1352 1303 6634 6867 +29728 3789 6633 3838 6868 +29729 4708 6231 5289 6888 +29730 5266 4610 5265 6483 +29731 2619 3310 6345 7097 +29732 3840 3680 6595 7134 +29733 1354 1194 6596 7133 +29734 5021 5027 4756 6358 +29735 1904 2047 1856 6450 +29736 6345 6986 6063 7097 +29737 255 256 1597 5845 +29738 4165 4268 4022 6018 +29739 1844 1682 1890 6525 +29740 1473 6540 1233 6541 +29741 3719 3959 6538 6539 +29742 4242 4173 4032 5905 +29743 1466 1395 1291 6498 +29744 5988 6672 5833 6963 +29745 2600 3316 2598 6276 +29746 5531 6735 5518 6900 +29747 1872 1746 2136 7130 +29748 5231 6276 5232 7155 +29749 1341 1241 1430 6901 +29750 4894 5062 4921 6343 +29751 375 6268 2363 7151 +29752 4795 4717 4718 6246 +29753 4660 5268 4657 6227 +29754 1816 6187 6930 7105 +29755 3153 2593 2836 6058 +29756 5352 5354 5358 6012 +29757 317 5992 2022 7213 +29758 3901 3738 3822 7058 +29759 2508 5919 419 6927 +29760 2599 2598 3347 6150 +29761 2233 6397 2242 6990 +29762 3290 3291 3292 6339 +29763 3695 3814 3943 5851 +29764 1209 1328 1457 5852 +29765 3168 2426 2425 6388 +29766 1842 1758 1941 6335 +29767 1653 5996 2073 6975 +29768 496 6634 5974 6791 +29769 456 6633 5973 6790 +29770 1924 1661 1851 6796 +29771 5800 6763 5758 7077 +29772 5996 6906 5891 6975 +29773 3986 6412 3688 7054 +29774 1559 1562 1566 6442 +29775 2340 353 2374 6566 +29776 3961 6492 3821 6730 +29777 3663 241 3631 6233 +29778 5459 6785 5524 6971 +29779 5617 6782 5682 6972 +29780 4532 4555 6430 7076 +29781 2786 2547 2551 6433 +29782 2096 2117 1820 6441 +29783 1363 2500 2381 7040 +29784 4930 5134 5346 5913 +29785 4697 4695 5078 6258 +29786 4346 4178 4425 6073 +29787 4600 4897 5007 5824 +29788 1970 1665 1795 6133 +29789 1518 1299 1487 6890 +29790 3973 4004 3785 6891 +29791 1586 6305 1583 7051 +29792 4527 543 542 6302 +29793 2466 2935 2854 6639 +29794 5684 6528 5616 6979 +29795 5526 6529 5458 6978 +29796 1505 6923 1327 6994 +29797 3950 3874 3665 6932 +29798 1179 1464 1388 6931 +29799 1593 258 1590 6423 +29800 2330 2299 2353 6266 +29801 4248 4180 454 6373 +29802 4172 4218 4064 6341 +29803 1628 1542 1534 5922 +29804 5537 5461 6530 7010 +29805 5695 5619 6531 7012 +29806 4871 5141 5135 6921 +29807 6580 6721 29 7207 +29808 4905 5215 4904 6004 +29809 2896 2897 2839 7175 +29810 4046 4172 4352 5952 +29811 4739 5278 6007 6888 +29812 5849 6896 5975 7142 +29813 3279 2799 3566 6317 +29814 4418 517 4203 6081 +29815 4082 4176 4220 5977 +29816 438 2424 2423 7048 +29817 2311 2346 2336 5767 +29818 3624 3601 3638 5768 +29819 341 6201 2367 6762 +29820 2233 2234 2232 6990 +29821 4264 6995 5812 7100 +29822 2865 2858 2884 6275 +29823 562 6632 6712 7137 +29824 5073 4830 4985 5821 +29825 6264 6889 5798 7169 +29826 4869 5127 6347 6837 +29827 2578 2499 2579 6848 +29828 3104 3174 2534 7050 +29829 31 6571 5738 6743 +29830 484 4386 4186 6574 +29831 2676 2997 2979 6246 +29832 2567 2564 6484 6861 +29833 4431 4114 4231 6019 +29834 1327 6923 6804 6994 +29835 1428 6819 1201 7199 +29836 3687 3914 6818 7200 +29837 4276 4087 4151 6490 +29838 2497 2511 2498 6381 +29839 3366 3446 3491 6448 +29840 4440 4132 4297 6535 +29841 2270 2277 2275 6354 +29842 4053 4195 4139 6076 +29843 4211 4062 4161 6226 +29844 1968 1925 1650 6142 +29845 5398 5379 5400 6295 +29846 3990 3839 3743 6720 +29847 4145 6311 4372 6559 +29848 3715 7041 6723 7108 +29849 5145 5070 5224 6489 +29850 4079 4189 4314 6547 +29851 522 4232 4301 6145 +29852 4783 4784 4599 6885 +29853 6196 6880 5788 6991 +29854 500 6825 5933 6917 +29855 2126 1862 1737 6671 +29856 231 6014 3616 6928 +29857 3137 3136 3139 7182 +29858 2869 3527 3274 6929 +29859 4654 4607 4608 6411 +29860 252 1615 251 5836 +29861 1887 1817 1693 5928 +29862 3977 3703 7082 7119 +29863 3167 2801 2921 5800 +29864 5101 4645 5041 7106 +29865 2194 6287 2196 7034 +29866 5235 5237 5297 6182 +29867 5537 5461 5525 6530 +29868 5695 5619 5683 6531 +29869 2886 2885 3447 6173 +29870 3521 3541 3183 6662 +29871 3867 6654 3680 7134 +29872 1381 6655 1194 7133 +29873 4626 6345 4616 6618 +29874 4148 4366 4399 5890 +29875 4782 4714 4791 5867 +29876 5642 6549 5697 6780 +29877 5539 5484 6548 6783 +29878 3516 3213 3212 6179 +29879 1315 6851 1318 6955 +29880 2137 6146 1862 6671 +29881 1299 6819 1487 6890 +29882 3973 3785 6818 6891 +29883 1957 1771 1914 6156 +29884 1553 1548 1555 6323 +29885 4168 4023 4324 6175 +29886 1626 1627 1538 6925 +29887 2991 3286 3158 6824 +29888 1521 1439 1207 6770 +29889 4007 3925 3693 6773 +29890 4743 4750 5325 5860 +29891 5473 5491 5582 7003 +29892 5649 5740 5631 7005 +29893 3756 3967 3866 5932 +29894 1270 1481 1380 5933 +29895 2515 3199 2520 5981 +29896 2463 2574 378 6017 +29897 4901 6108 4635 7049 +29898 1636 2040 1842 6335 +29899 4091 4186 4386 6211 +29900 3611 5988 6672 7086 +29901 5032 4755 4586 6447 +29902 584 5411 583 5822 +29903 5201 5301 4963 6438 +29904 3297 3500 3296 6382 +29905 4355 4110 4228 6909 +29906 2630 2571 6338 7161 +29907 3095 3299 3096 5907 +29908 1683 2060 1841 6205 +29909 1676 2059 6474 7074 +29910 4849 4887 6070 7159 +29911 3690 6389 3957 6876 +29912 1842 1712 1982 5915 +29913 2157 2073 5996 7176 +29914 3327 2826 2822 6915 +29915 626 6221 627 6725 +29916 5599 5662 5705 6705 +29917 5441 5504 5547 6704 +29918 4669 5349 4666 6085 +29919 5238 549 4972 6044 +29920 2455 2508 419 6927 +29921 1396 1188 1273 6703 +29922 3674 3759 3882 6702 +29923 1967 1651 1928 6286 +29924 4922 4924 4923 5941 +29925 4246 485 4186 6465 +29926 3073 2953 2983 6013 +29927 2821 3327 2822 7206 +29928 458 5582 7003 7085 +29929 4265 4077 6222 6964 +29930 443 3621 3650 6768 +29931 4585 4837 4584 6353 +29932 3919 3976 6562 6893 +29933 1433 1490 6561 6892 +29934 2896 7065 5779 7175 +29935 3468 3331 3342 6573 +29936 450 6126 451 6882 +29937 3248 2880 3249 6050 +29938 2349 339 2315 6184 +29939 3274 2959 2869 6471 +29940 635 6722 6416 7165 +29941 4284 4048 4229 6544 +29942 3777 3952 3881 6735 +29943 2027 1726 2014 6244 +29944 2924 6009 2614 7073 +29945 5247 5204 5246 6298 +29946 3329 2638 2635 6336 +29947 4907 4908 5218 5912 +29948 2313 2352 337 6136 +29949 300 6846 6145 7143 +29950 635 6476 6416 6722 +29951 3100 3318 3006 6372 +29952 2147 1774 2153 5989 +29953 465 4542 464 6169 +29954 4701 4699 5114 5985 +29955 477 4250 4306 6254 +29956 4621 4622 5102 6062 +29957 4555 4498 6430 7136 +29958 29 609 6721 7098 +29959 592 5239 5279 6814 +29960 420 5969 2494 6927 +29961 5229 5230 5228 6280 +29962 3086 2790 2950 7116 +29963 1397 1239 6850 6984 +29964 3725 6852 3883 6983 +29965 5152 4873 4826 7204 +29966 5614 6487 5680 6901 +29967 4745 4709 4707 6936 +29968 5779 6835 6392 7175 +29969 2262 2261 2267 6331 +29970 360 2319 2356 6589 +29971 2931 2932 2663 7068 +29972 4213 4094 4212 6242 +29973 222 1601 223 6078 +29974 2866 2873 2874 6216 +29975 220 1610 1604 6462 +29976 3109 2992 2764 5902 +29977 4900 628 627 6124 +29978 1988 1848 1658 6301 +29979 2895 2447 5929 7174 +29980 4415 4097 4222 6026 +29981 5162 5036 5034 6166 +29982 4708 4710 5289 6231 +29983 3636 6809 1437 7017 +29984 1220 6563 1385 6766 +29985 3871 3706 6564 6765 +29986 4266 6475 4360 6944 +29987 233 6993 6112 7080 +29988 3783 276 3868 7082 +29989 2496 6413 2708 7128 +29990 458 7003 7002 7085 +29991 1789 1665 1961 7178 +29992 269 2124 270 6256 +29993 5336 5324 596 6962 +29994 5851 6686 458 7002 +29995 498 5852 6684 7004 +29996 3104 2610 3103 6957 +29997 1263 6637 1336 6897 +29998 5112 5113 5165 5883 +29999 1579 1577 1578 6418 +30000 4215 6578 4402 7100 +30001 5297 5298 5138 6180 +30002 3828 6488 3996 6959 +30003 1342 6487 1510 6960 +30004 1616 1606 1608 6262 +30005 4919 5314 5051 6576 +30006 1775 2064 2033 5877 +30007 4692 4693 5149 6042 +30008 4796 4775 4719 5780 +30009 3143 3152 2987 6087 +30010 3520 3451 6507 7144 +30011 3277 2946 2943 5921 +30012 4537 27 559 6642 +30013 5193 5148 5156 6056 +30014 2737 2738 2717 6109 +30015 2089 1854 1771 6316 +30016 2667 3169 3579 6143 +30017 2097 1703 1951 6597 +30018 3899 6924 3805 7085 +30019 242 3631 241 6575 +30020 5196 5156 5174 6024 +30021 1805 7059 1734 7177 +30022 5762 6248 7024 7209 +30023 5761 6250 7025 7208 +30024 447 2376 446 5809 +30025 5535 6818 5457 6891 +30026 5693 6819 5615 6890 +30027 5063 5064 4674 6289 +30028 2496 2497 2498 7128 +30029 2559 408 2712 3942 +30030 4687 4688 5111 7088 +30031 5203 4977 4978 6101 +30032 4778 6099 4779 7181 +30033 590 4592 591 5901 +30034 1617 1525 1527 6324 +30035 1827 1668 1947 6107 +30036 4577 4868 4589 6282 +30037 3265 6021 6555 6795 +30038 4622 6062 4621 7121 +30039 2111 1797 2044 7091 +30040 3861 3887 3716 6529 +30041 1230 1375 1401 6528 +30042 4058 4340 4208 6066 +30043 5412 5368 5409 6141 +30044 4664 4973 4665 6252 +30045 527 528 6293 7066 +30046 5136 6181 5137 6845 +30047 6012 6752 5352 6753 +30048 2121 1742 6151 6912 +30049 5835 6808 6446 6824 +30050 1237 1405 1300 6482 +30051 309 1863 308 6690 +30052 3210 2696 3553 5913 +30053 248 1527 1526 6324 +30054 5069 5089 4674 6382 +30055 5684 6703 6528 6979 +30056 5526 6702 6529 6978 +30057 3106 2933 3052 5962 +30058 2416 3016 2601 6161 +30059 2835 2834 3575 5914 +30060 5544 5463 5578 6751 +30061 4537 489 27 6642 +30062 5681 6701 578 6810 +30063 2404 2983 3081 6371 +30064 1840 1750 6537 7129 +30065 265 264 1864 6093 +30066 3488 3360 3446 6404 +30067 4252 4193 4031 6441 +30068 4874 4873 4700 7204 +30069 629 628 4777 6693 +30070 3045 5997 3047 6710 +30071 3018 2531 431 5911 +30072 2766 2771 2767 6124 +30073 5102 4775 4796 6719 +30074 2101 2032 1732 6930 +30075 3072 2915 3050 7152 +30076 1802 2029 2114 5890 +30077 1823 1985 2176 6076 +30078 5248 5264 5265 6444 +30079 3150 3211 2703 5965 +30080 6704 6875 5462 6877 +30081 6705 6878 5620 6879 +30082 5218 4908 4876 7147 +30083 1284 1482 1411 6810 +30084 4841 4840 4842 6576 +30085 1749 5974 2154 7074 +30086 3256 3260 3404 6508 +30087 2396 2395 2397 7108 +30088 3638 5768 3584 6809 +30089 1535 275 1532 7082 +30090 5046 4935 4794 6719 +30091 4647 4991 4997 6320 +30092 4765 4602 6263 7149 +30093 4508 4493 4539 6077 +30094 1634 7047 2053 7192 +30095 463 462 5949 7061 +30096 4085 4275 4152 6432 +30097 4265 4077 4308 6222 +30098 1347 1331 1227 6903 +30099 3833 3817 3712 6904 +30100 4264 4402 6995 7100 +30101 3213 3516 3351 6567 +30102 5308 5307 4805 5986 +30103 5857 7042 5910 7106 +30104 3755 3943 3814 5851 +30105 1269 1457 1328 5852 +30106 4531 468 4504 6362 +30107 1493 6769 1249 7071 +30108 242 3633 3631 7083 +30109 3311 6345 3310 6986 +30110 490 6111 491 6883 +30111 1753 1858 1965 5960 +30112 1835 1637 1886 6168 +30113 366 6052 2347 7007 +30114 5343 5285 5943 7055 +30115 3479 3478 2697 6049 +30116 4467 6034 4185 6847 +30117 3521 3510 2791 6330 +30118 1703 1776 1963 6597 +30119 3221 5849 3220 7142 +30120 585 4996 586 6080 +30121 1939 1988 1714 6250 +30122 1941 1987 1715 6248 +30123 1625 1628 1534 5922 +30124 2949 2950 2509 6764 +30125 5158 6330 5179 6843 +30126 1974 5999 2184 6864 +30127 2889 2892 2891 6095 +30128 2592 3160 2595 5908 +30129 1503 1219 1346 6809 +30130 4065 6429 4257 7184 +30131 3267 3264 6555 7139 +30132 1838 1702 1952 7006 +30133 4589 4868 4799 6282 +30134 5866 6872 5867 7160 +30135 2487 2460 2462 6229 +30136 4740 4753 4742 6046 +30137 3721 6603 3911 6760 +30138 1235 6602 1425 6759 +30139 4390 4050 4449 5915 +30140 4533 4506 485 6261 +30141 2968 6059 2818 6973 +30142 1727 1882 2018 6601 +30143 2424 2705 5785 7161 +30144 1418 6729 1317 6954 +30145 3803 3904 6730 6953 +30146 2303 2319 2360 5813 +30147 1851 2035 1695 6733 +30148 4517 6313 4506 6739 +30149 1505 6583 1524 6923 +30150 3991 6584 4010 6922 +30151 1773 2179 1961 6057 +30152 616 615 4862 6388 +30153 3463 3405 3398 5873 +30154 548 4505 4524 6160 +30155 1605 1606 1607 6464 +30156 4019 4476 4265 6964 +30157 6125 6543 577 7014 +30158 591 5432 590 5901 +30159 4717 4796 4719 6755 +30160 1947 1668 2112 6107 +30161 4336 4486 529 7018 +30162 4540 4537 4493 6190 +30163 4120 4215 4402 7100 +30164 554 6022 4559 7150 +30165 2781 2780 2862 6247 +30166 1652 1776 2077 5865 +30167 2794 2825 2881 6486 +30168 2687 2838 2921 5862 +30169 5613 5639 5718 6851 +30170 5455 5481 5560 6853 +30171 1888 286 3756 1815 +30172 196 1814 1270 1889 +30173 5544 5463 6751 7094 +30174 3219 2436 5978 6945 +30175 5676 6689 6602 6901 +30176 4999 4802 5055 6008 +30177 4240 4376 4088 6838 +30178 5827 6639 5884 6887 +30179 2240 2239 2248 7202 +30180 1377 2470 2400 7096 +30181 4729 4730 4728 7181 +30182 339 2255 338 6405 +30183 4785 4730 4786 5889 +30184 5637 5688 5724 6533 +30185 5566 5479 5530 6534 +30186 328 2328 6293 6777 +30187 4433 4216 4012 6376 +30188 2514 2774 2763 6855 +30189 3321 3499 2616 6117 +30190 4023 4403 4211 6326 +30191 351 2219 2224 6318 +30192 1295 1239 7060 7137 +30193 2005 1630 1860 6204 +30194 5722 5604 6892 6956 +30195 3210 2699 2696 5913 +30196 5564 5446 6893 7031 +30197 1387 1267 2720 7162 +30198 438 5987 3653 7048 +30199 4995 6197 4593 6692 +30200 1545 1599 240 6653 +30201 4213 4212 4059 6242 +30202 5139 5339 5061 5936 +30203 2762 2514 2763 6108 +30204 1708 2087 1853 7057 +30205 5862 6885 5758 7189 +30206 579 6619 5681 6810 +30207 3687 6818 3785 7200 +30208 1201 6819 1299 7199 +30209 3795 6862 6503 7119 +30210 4270 4112 4235 6139 +30211 5684 5600 5749 6649 +30212 5591 5526 5442 6648 +30213 2467 2502 2481 6887 +30214 1609 1605 1607 6464 +30215 5690 6812 5655 6960 +30216 5497 5532 6811 6959 +30217 4409 4321 4159 6132 +30218 419 2508 418 5919 +30219 1434 1250 6812 7133 +30220 3736 6811 3920 7134 +30221 2672 3219 2436 5978 +30222 233 3654 6112 6943 +30223 2907 2613 2612 6252 +30224 1859 1881 1681 6127 +30225 2978 2526 2888 6504 +30226 3266 3528 3408 6046 +30227 293 6449 1953 6911 +30228 4662 5032 5266 6106 +30229 2235 311 2243 6625 +30230 4373 4152 4104 6356 +30231 3139 3136 2526 6267 +30232 2332 6040 343 6762 +30233 5137 6181 5135 6921 +30234 1580 1582 228 6260 +30235 2139 1915 299 6193 +30236 1907 314 315 6360 +30237 3919 3801 3976 6893 +30238 1433 1315 1490 6892 +30239 4347 4177 4074 6461 +30240 3821 3715 6723 7108 +30241 365 2314 364 7007 +30242 1938 6144 1769 7057 +30243 1661 1924 2086 6403 +30244 4373 4313 4033 6032 +30245 3871 7031 3791 7207 +30246 2036 1812 1662 6493 +30247 2990 1393 2711 6869 +30248 4565 4564 4563 5964 +30249 4029 6312 6622 7187 +30250 2676 2916 3102 6536 +30251 4499 5796 6967 7164 +30252 615 6389 616 6828 +30253 5276 5293 5292 6496 +30254 2304 2320 2327 6171 +30255 2295 6519 2346 6902 +30256 562 4781 563 6247 +30257 2038 1834 1761 5878 +30258 1945 1719 1836 6461 +30259 436 2918 3309 5894 +30260 4245 4102 6847 7157 +30261 1187 1309 1325 6585 +30262 512 5387 513 6586 +30263 3838 6633 3734 7208 +30264 1248 1352 6634 7209 +30265 3960 6497 3776 6631 +30266 3373 3375 3431 6652 +30267 5003 5005 5002 6236 +30268 1806 1684 2108 6614 +30269 4841 4946 4840 5910 +30270 2907 3552 6552 6713 +30271 3141 3143 2986 6424 +30272 1838 1952 305 6081 +30273 4571 4900 627 6124 +30274 2686 5862 2687 7093 +30275 5050 5084 5082 6174 +30276 4515 4510 4497 6255 +30277 3903 3672 6264 6751 +30278 27 5803 6232 6642 +30279 354 2197 353 7169 +30280 3169 6143 6552 6713 +30281 2683 2923 2498 6844 +30282 2778 3030 3164 6274 +30283 6851 6892 5656 6955 +30284 1686 1917 1838 6140 +30285 5950 7082 5922 7119 +30286 2880 3248 2557 6050 +30287 2207 2258 2214 6383 +30288 2869 3468 2867 6023 +30289 5724 5630 5720 6675 +30290 5562 5566 5472 6676 +30291 3902 3765 3700 6939 +30292 1279 1214 1416 6940 +30293 4461 4231 4114 6019 +30294 4103 4468 4393 5994 +30295 1319 1192 6825 7070 +30296 5118 5030 5083 6393 +30297 3200 3423 3425 6919 +30298 380 2369 379 6045 +30299 1945 2133 1719 6461 +30300 3094 3173 3092 5990 +30301 5919 7089 6453 7090 +30302 5372 6478 5385 6854 +30303 4040 4307 4440 6535 +30304 623 6539 5520 7058 +30305 4976 6041 4985 7149 +30306 1978 6291 310 7201 +30307 6450 6578 5756 7100 +30308 230 231 6928 7126 +30309 3606 3659 221 5948 +30310 2231 2229 6822 7180 +30311 1773 6057 1961 7178 +30312 4153 4396 4035 5959 +30313 5177 5350 5175 6708 +30314 1802 5890 2114 7032 +30315 1250 1441 6812 7111 +30316 3736 3927 6811 7112 +30317 1280 7004 1519 7005 +30318 3766 7002 4005 7003 +30319 5570 5469 5499 6801 +30320 5627 5657 5728 6802 +30321 3973 6818 3722 6866 +30322 1236 1487 6819 6865 +30323 2364 2335 382 6115 +30324 5352 5358 5189 6012 +30325 1848 1988 1759 6301 +30326 1912 1688 6312 6961 +30327 5521 6641 5459 6971 +30328 5679 6640 5617 6972 +30329 2244 2248 2239 6292 +30330 2113 1874 1746 6950 +30331 1352 1274 1514 7209 +30332 4000 3838 3760 7208 +30333 4727 4778 4779 7181 +30334 5943 5343 7055 7214 +30335 337 6136 2352 6776 +30336 2083 1689 1822 6149 +30337 2447 2984 2895 5929 +30338 4096 4206 4338 6600 +30339 2264 338 2255 6405 +30340 4291 6714 6403 7028 +30341 4165 4040 4408 6149 +30342 2642 2628 2753 6104 +30343 1840 2070 1750 7129 +30344 2634 6656 5910 7042 +30345 5295 4741 4808 6035 +30346 1737 1860 2126 6203 +30347 6769 7070 1249 7071 +30348 2589 6274 2777 6968 +30349 437 3649 3607 6421 +30350 3145 2677 3157 5956 +30351 5606 6850 5645 6984 +30352 5448 6852 5487 6983 +30353 2458 2389 2459 6709 +30354 4090 4383 4377 6312 +30355 5629 5735 5659 6569 +30356 5501 5471 5577 6570 +30357 3984 6875 6828 6876 +30358 3153 2594 2593 6058 +30359 4807 4806 4805 7163 +30360 3842 6765 6580 6862 +30361 2197 3913 2198 7169 +30362 4126 4258 4374 6156 +30363 2168 296 1909 6100 +30364 5905 6778 1950 6992 +30365 237 3600 3629 6362 +30366 2842 5931 3246 7128 +30367 2233 2232 2235 6625 +30368 4624 6792 4623 7140 +30369 4320 6153 4461 7153 +30370 242 3912 3923 6575 +30371 1472 1230 1390 6528 +30372 3716 3876 3958 6529 +30373 1938 1662 1812 6493 +30374 4920 4919 4918 6104 +30375 4125 4228 4282 6909 +30376 2644 2982 2890 6096 +30377 3713 3776 3847 6721 +30378 2820 3160 2592 6973 +30379 5688 570 571 6775 +30380 4577 576 4868 6473 +30381 6785 6971 3818 7200 +30382 6782 6972 1332 7199 +30383 2650 3049 2532 6159 +30384 1704 1975 1811 6064 +30385 1907 2121 314 6360 +30386 2647 3328 2887 6177 +30387 5867 7117 5774 7160 +30388 4029 4196 4423 6622 +30389 2227 2226 2229 6119 +30390 2039 1843 1638 6658 +30391 5590 616 5531 6735 +30392 5730 6781 5605 6841 +30393 5572 6784 5447 6840 +30394 2471 3288 3123 6070 +30395 2782 2783 2671 6170 +30396 2819 5944 2820 6688 +30397 4847 4846 4848 5971 +30398 5520 5556 6538 6539 +30399 5714 6540 5678 6541 +30400 2714 2726 2724 7110 +30401 3029 3032 3084 6665 +30402 5564 6645 6564 7031 +30403 1540 6415 1541 6756 +30404 3295 3378 3376 6289 +30405 2516 2514 2515 6366 +30406 3981 3750 3798 6369 +30407 4637 4638 5893 6617 +30408 2185 1973 1796 6740 +30409 2101 6186 1680 7105 +30410 2664 6299 2663 7068 +30411 3924 2344 6889 7169 +30412 3487 3376 3429 6224 +30413 5730 6780 5652 6781 +30414 5572 6783 5494 6784 +30415 1353 1310 1442 6722 +30416 5050 5048 5159 6173 +30417 1386 1296 1203 6810 +30418 2009 1655 1866 6376 +30419 293 2291 6147 6911 +30420 4975 4974 4909 5984 +30421 3818 6971 3910 7200 +30422 1332 6972 1424 7199 +30423 3636 213 6809 7017 +30424 5231 5191 5232 6276 +30425 5473 6774 5491 7003 +30426 5649 5631 6771 7005 +30427 1887 1834 1639 7118 +30428 3423 6163 2622 7158 +30429 4227 6341 4064 7203 +30430 3685 3827 3916 6488 +30431 1341 1430 1199 6487 +30432 3201 3079 3007 6085 +30433 3413 6228 3495 7102 +30434 4581 4675 4674 6425 +30435 5768 6642 6232 6809 +30436 5722 6644 6563 6956 +30437 6226 6673 1946 6958 +30438 4682 4706 4681 7030 +30439 4427 4388 4139 5958 +30440 5148 4697 5155 6402 +30441 1712 6864 2030 7122 +30442 1351 1453 1215 7014 +30443 3187 3358 3489 6219 +30444 327 2355 328 7034 +30445 5969 6927 6797 7089 +30446 2615 2614 2924 6009 +30447 3050 3017 3071 6259 +30448 5736 5621 5659 6458 +30449 5463 5501 5578 6459 +30450 3314 160 1376 2539 +30451 2988 2989 2818 6059 +30452 3709 6716 3779 7191 +30453 3724 6620 3872 6913 +30454 6002 6724 4838 7123 +30455 2197 2198 2200 7169 +30456 4187 4448 4049 6607 +30457 4379 452 451 6301 +30458 4547 4519 469 6253 +30459 6509 7041 3770 7110 +30460 2634 5910 2591 7042 +30461 1338 1194 1381 6655 +30462 3680 3867 3824 6654 +30463 353 2197 2199 7169 +30464 2686 2685 2837 7093 +30465 3404 3458 3255 6182 +30466 5737 5662 5606 6705 +30467 5504 5448 5579 6704 +30468 4911 5066 4689 6815 +30469 1327 1214 6732 6804 +30470 3813 3700 6731 6803 +30471 1770 1916 1958 6019 +30472 484 4186 485 6465 +30473 1567 6409 234 6993 +30474 5569 5468 6654 7134 +30475 5727 5626 6655 7133 +30476 5509 5564 6564 7031 +30477 475 4518 4503 6251 +30478 233 6112 3612 7080 +30479 5406 5405 5380 6518 +30480 5636 6743 5671 6955 +30481 5571 5521 6539 7193 +30482 3658 3617 235 6253 +30483 5588 6620 628 6723 +30484 2796 2804 3128 5964 +30485 6338 6798 6148 7161 +30486 517 6405 518 6834 +30487 3400 3399 3565 6411 +30488 365 2513 366 7007 +30489 4851 630 629 6693 +30490 3443 2877 2876 6426 +30491 4592 4969 591 6814 +30492 4679 5221 4611 6426 +30493 2236 2234 346 6443 +30494 475 4424 476 6134 +30495 5185 5137 6219 6845 +30496 1259 1437 6809 7017 +30497 5758 6763 5800 7189 +30498 5992 7053 6479 7213 +30499 512 4300 511 6290 +30500 3099 2624 2626 6131 +30501 1742 2128 1877 6151 +30502 5453 5506 5543 6772 +30503 4280 6186 6605 6964 +30504 4414 4259 4026 6368 +30505 1638 1983 2107 6691 +30506 2627 2629 6197 6656 +30507 4648 4991 4647 6526 +30508 1568 1573 1571 6094 +30509 575 4868 576 6164 +30510 3808 1529 1528 3912 +30511 4887 4891 4849 6070 +30512 3063 3061 3346 6789 +30513 4785 5889 4786 7049 +30514 5036 5088 5086 6131 +30515 4091 4293 4374 6156 +30516 2078 1789 1909 6800 +30517 1601 1594 223 6664 +30518 3722 6818 6676 6866 +30519 1236 6819 6675 6865 +30520 235 1558 236 6391 +30521 326 2212 325 5995 +30522 230 6365 1573 7126 +30523 4192 481 480 5991 +30524 3584 3601 3637 7090 +30525 5768 6809 6453 7090 +30526 4951 4588 4587 6235 +30527 6714 7028 6291 7201 +30528 2061 1814 1889 6685 +30529 2062 1815 1888 6687 +30530 2117 1641 1826 5844 +30531 3183 3182 2734 6662 +30532 4513 4543 4495 6682 +30533 1915 1878 298 6193 +30534 1411 1482 1203 6810 +30535 613 5542 6983 7054 +30536 2599 3347 3242 6150 +30537 4484 4395 4054 6494 +30538 2316 2324 2298 6856 +30539 490 6694 6883 6996 +30540 3304 3305 3306 6609 +30541 3809 3935 3702 6805 +30542 5297 5254 5298 6513 +30543 2372 6519 2295 6902 +30544 3626 3598 3625 6255 +30545 6179 6567 5829 7120 +30546 4577 4578 4576 5981 +30547 6360 6822 6119 7180 +30548 3287 3453 3325 6333 +30549 3001 361 2414 5881 +30550 4979 6148 4992 6798 +30551 4278 4086 4247 6335 +30552 26 463 5950 6863 +30553 3457 3270 3185 6304 +30554 4814 5285 5236 7055 +30555 3270 3271 3269 6444 +30556 4878 4880 4704 6096 +30557 5456 6760 6488 6900 +30558 3699 4007 3773 6873 +30559 1521 1287 1213 6874 +30560 1422 15 357 1400 +30561 428 3613 429 6160 +30562 2749 2733 2775 6060 +30563 4626 5358 5354 6618 +30564 2218 2225 7053 7213 +30565 3394 3395 3393 6554 +30566 381 2338 380 6321 +30567 5414 5408 5368 6309 +30568 4975 5984 4909 7037 +30569 5749 6649 5657 6732 +30570 5591 6648 5499 6731 +30571 3507 2865 6174 7125 +30572 1738 2118 2158 5760 +30573 4146 4395 4413 5951 +30574 1653 2157 2073 5996 +30575 5908 2592 6973 7173 +30576 248 1530 247 6925 +30577 6580 6720 29 6721 +30578 1939 1759 1988 6658 +30579 4535 530 6233 6938 +30580 5382 584 585 6115 +30581 626 6221 6725 6807 +30582 3931 3930 3730 6593 +30583 1444 1244 1445 6594 +30584 259 1776 2097 6194 +30585 2458 3196 2493 6969 +30586 2030 1674 1806 7122 +30587 251 1613 250 7104 +30588 3118 5857 2405 6914 +30589 1587 1583 1585 6568 +30590 1229 1284 1411 5850 +30591 4806 4961 4998 7163 +30592 6186 6930 6187 7105 +30593 2177 1643 2083 6616 +30594 4565 5964 4563 6976 +30595 4016 4199 4360 6475 +30596 5458 5536 5491 6529 +30597 5649 5616 5694 6528 +30598 5722 6563 5667 6956 +30599 2868 3187 3114 6218 +30600 4377 4140 4090 6524 +30601 3284 3265 3442 6795 +30602 4408 6151 4158 7153 +30603 612 4895 613 5963 +30604 5123 5121 4670 6005 +30605 2715 396 3778 2585 +30606 2580 2535 6213 7127 +30607 5546 5583 5465 6862 +30608 5810 6723 6509 7041 +30609 4452 4142 5853 7185 +30610 5381 5376 5402 7066 +30611 2202 6572 2205 6911 +30612 2440 2405 3118 5857 +30613 3319 3144 2545 6199 +30614 4530 4529 4505 6592 +30615 4572 4573 4574 6188 +30616 4995 4968 4593 6197 +30617 4263 4452 4142 5853 +30618 2195 6287 2205 6572 +30619 2269 2272 2270 6329 +30620 1415 1255 1366 6824 +30621 6022 6739 4534 7164 +30622 4985 5821 4830 7149 +30623 5473 6772 6774 7085 +30624 5810 6898 6492 7108 +30625 1862 2137 1747 6146 +30626 5344 6182 5237 7214 +30627 623 5571 5520 6539 +30628 574 5729 5678 6541 +30629 2099 1642 2130 6071 +30630 2879 2887 3328 6177 +30631 2096 1686 1856 6450 +30632 4808 4818 5295 6035 +30633 6139 7146 6556 7183 +30634 1449 1216 1323 6925 +30635 4700 4873 4875 5962 +30636 2649 2788 2789 6043 +30637 2331 2297 2348 6185 +30638 2708 2496 2707 6413 +30639 3366 6448 3364 6483 +30640 4056 4319 4207 6079 +30641 1920 6066 1999 7192 +30642 4019 6186 4280 6964 +30643 5223 5075 5167 5843 +30644 6152 6944 4480 7132 +30645 3102 2916 3065 5868 +30646 3372 6004 3374 6747 +30647 4631 5124 4630 6346 +30648 3049 3283 3048 6044 +30649 3769 3845 3939 6725 +30650 2118 1821 2158 5760 +30651 3565 3399 3514 6342 +30652 27 6232 559 6642 +30653 5490 5450 5508 6891 +30654 5648 5608 5666 6890 +30655 4089 4191 4288 5982 +30656 5501 6570 6459 6904 +30657 5659 6569 6458 6903 +30658 3764 6492 3709 6998 +30659 231 232 7080 7126 +30660 426 3660 3611 6672 +30661 5465 5515 5575 6580 +30662 1910 2122 253 6465 +30663 5515 6580 29 7207 +30664 3253 2879 3262 6380 +30665 5604 5656 6892 6956 +30666 5498 6893 5446 7031 +30667 3416 3415 6227 7001 +30668 1300 2538 6727 6728 +30669 1317 1418 1189 6729 +30670 3803 3904 3675 6730 +30671 6916 6963 5869 7039 +30672 3363 3499 3321 6447 +30673 3477 3484 3310 6986 +30674 2975 2447 3946 7013 +30675 4436 4081 5788 6991 +30676 3098 2911 3216 7120 +30677 5684 6649 5749 6703 +30678 5526 6648 5591 6702 +30679 4024 4189 4287 7131 +30680 1859 1629 2125 6341 +30681 3741 3901 6666 6749 +30682 1844 1695 2057 6733 +30683 4984 4887 4676 7159 +30684 3092 5990 3173 6969 +30685 1591 224 6664 6871 +30686 4435 4434 4130 5953 +30687 6688 7037 5944 7109 +30688 266 1569 265 5946 +30689 1227 1314 1347 6954 +30690 3833 3712 3800 6953 +30691 4462 523 4321 6193 +30692 5295 4821 5288 6399 +30693 3271 3270 3272 6444 +30694 1877 1916 313 6153 +30695 459 458 4174 6097 +30696 498 4175 499 6098 +30697 3427 3487 6224 7036 +30698 4159 524 525 6379 +30699 2149 1723 1851 6796 +30700 1563 1564 1562 6442 +30701 5178 6813 5318 6843 +30702 232 1565 6993 7080 +30703 1919 2149 1851 6196 +30704 5554 6785 6593 7200 +30705 5712 6782 6594 7199 +30706 1971 5966 1796 6740 +30707 4236 4140 4377 6271 +30708 3465 3460 3546 5792 +30709 5722 6892 6644 6956 +30710 5834 6941 5790 7182 +30711 1839 1868 262 6859 +30712 2580 2535 2489 6213 +30713 333 2276 332 6157 +30714 512 513 4429 6291 +30715 3430 3412 3441 6181 +30716 3616 231 3647 6014 +30717 5564 6893 6645 7031 +30718 6539 6638 5520 7058 +30719 2644 2890 2546 6096 +30720 5766 6498 6191 6869 +30721 5045 5152 4950 7211 +30722 5660 5630 5725 6758 +30723 5567 5502 5472 6757 +30724 3342 3340 3341 6573 +30725 2795 3241 2902 6208 +30726 1449 1323 1531 6925 +30727 5587 7031 5575 7207 +30728 3901 3822 3683 7058 +30729 6528 6703 1390 6979 +30730 3876 6529 6702 6978 +30731 2543 2542 2596 6003 +30732 2435 2436 2434 6945 +30733 3058 3535 3057 6005 +30734 1296 1386 1238 6619 +30735 3781 3872 3724 6620 +30736 4535 26 464 6233 +30737 3365 3493 3363 6447 +30738 4403 4308 4077 6942 +30739 1697 1896 2022 6355 +30740 1907 1788 2104 6912 +30741 3474 5983 2860 7124 +30742 1813 1688 1937 6312 +30743 5554 5464 5592 6593 +30744 5712 5622 5750 6594 +30745 6278 6825 1414 6997 +30746 498 7004 6684 7071 +30747 620 6643 621 6826 +30748 4049 4391 4281 6120 +30749 222 6078 3641 7086 +30750 2965 2922 2964 7073 +30751 573 6637 572 6897 +30752 3673 6863 6862 7119 +30753 3345 2951 3338 6137 +30754 5714 5682 5674 6972 +30755 5524 5516 5556 6971 +30756 4386 483 4293 6574 +30757 3231 6941 3138 7182 +30758 4381 4151 4107 6527 +30759 3262 2511 2497 6761 +30760 2801 2752 2687 7000 +30761 3716 3876 6529 6702 +30762 1230 1390 6528 6703 +30763 3280 3566 3573 6317 +30764 5682 5598 5674 6972 +30765 5516 5524 5440 6971 +30766 3920 6811 6959 7134 +30767 6812 6960 1434 7133 +30768 1985 1780 2176 6076 +30769 3282 3329 3331 6346 +30770 2930 2937 3046 7020 +30771 5206 5205 5204 7197 +30772 3867 3918 3754 6654 +30773 1268 1381 1432 6655 +30774 5489 5557 5467 6821 +30775 2618 2380 357 7107 +30776 1603 1609 254 6463 +30777 4212 6681 6242 7072 +30778 2332 6040 6762 7151 +30779 3711 6459 3817 6904 +30780 1331 1225 6458 6903 +30781 3045 3228 3538 6710 +30782 316 2167 315 6061 +30783 5356 4630 5124 6899 +30784 3328 2652 2849 6750 +30785 1897 2021 273 6198 +30786 5493 5460 5532 6488 +30787 5690 5651 5618 6487 +30788 1644 1812 2016 6326 +30789 2591 2634 2985 5910 +30790 3185 3181 3184 6210 +30791 3584 3638 3601 5768 +30792 3457 3272 3270 6304 +30793 5715 5625 5647 6788 +30794 3988 3767 3859 6757 +30795 1281 1373 1502 6758 +30796 1904 6450 1856 6946 +30797 1475 1290 1223 6499 +30798 3264 3265 6555 6795 +30799 1563 1570 1568 6303 +30800 1355 1503 1256 6453 +30801 6232 6809 6642 7017 +30802 3438 3437 3440 6358 +30803 3379 3257 3383 6565 +30804 2411 2998 443 6768 +30805 1329 2711 1393 6869 +30806 4041 4166 4409 6344 +30807 3138 3136 3137 7182 +30808 4266 4016 4360 6475 +30809 3430 3357 3412 6181 +30810 6200 6762 6040 7151 +30811 3330 3535 3214 6195 +30812 537 5979 538 6798 +30813 1226 1315 1318 6955 +30814 4504 4532 6430 7076 +30815 1302 1191 6602 6689 +30816 2299 2353 6266 6856 +30817 1431 247 1530 6925 +30818 3000 2915 3072 7152 +30819 1535 1532 1534 6756 +30820 493 492 6629 6881 +30821 5725 5630 5688 6533 +30822 5567 5472 5530 6534 +30823 4554 4530 547 6051 +30824 4367 4164 4436 5788 +30825 1490 1339 1253 6892 +30826 3976 3825 3739 6893 +30827 5394 5420 515 6201 +30828 1600 1593 1592 6422 +30829 4295 4092 4311 6577 +30830 562 6088 6712 6860 +30831 5497 6959 6811 7134 +30832 5655 6960 6812 7133 +30833 1450 1448 1296 6619 +30834 3936 3933 3781 6620 +30835 4688 5150 4888 6437 +30836 2927 2738 2737 6109 +30837 1707 2086 1924 6403 +30838 2859 2858 2865 7125 +30839 3695 7002 3829 7085 +30840 3342 3341 2899 6212 +30841 1276 6458 1368 6694 +30842 5622 5697 5672 6780 +30843 5464 5539 5514 6783 +30844 458 7002 6686 7085 +30845 470 4322 471 6407 +30846 5142 4617 5139 6084 +30847 2278 2285 2279 6387 +30848 507 4304 506 6061 +30849 2922 2965 2745 5963 +30850 4855 4941 4857 6028 +30851 1390 1273 6649 6703 +30852 3759 6648 3876 6702 +30853 3097 3095 3096 5907 +30854 4897 4898 4902 6517 +30855 341 2246 2251 6452 +30856 551 4594 550 6916 +30857 2416 2392 3016 6161 +30858 4603 6333 5029 7194 +30859 4106 4378 4333 6348 +30860 545 546 5337 6650 +30861 3062 3061 3063 6789 +30862 312 2237 313 7180 +30863 2134 1946 1672 6226 +30864 434 433 3615 6456 +30865 4027 5960 4475 7072 +30866 2564 2802 2567 6484 +30867 3512 3038 2905 6542 +30868 3715 6509 3897 6723 +30869 3228 3232 3497 6710 +30870 3451 3450 3392 6280 +30871 4334 4104 4379 6356 +30872 4342 4024 4187 6113 +30873 4046 5952 4352 7185 +30874 3739 3919 3976 6562 +30875 1490 1253 1433 6561 +30876 5183 5185 5137 6219 +30877 4294 6107 4272 6949 +30878 5176 5175 5173 6708 +30879 4172 4064 4227 6341 +30880 2899 3341 3358 6212 +30881 4154 4380 461 6337 +30882 2915 2674 2435 6872 +30883 2010 1699 1784 6348 +30884 2182 6025 1825 6726 +30885 2587 2707 2496 6413 +30886 4200 4280 4019 6186 +30887 1662 2087 6176 7057 +30888 5583 5515 5465 6580 +30889 3919 6562 3697 6853 +30890 1433 6561 1211 6851 +30891 634 5704 28 6476 +30892 2994 2996 2995 6431 +30893 2894 2580 2489 6213 +30894 3822 3985 6830 7058 +30895 509 5424 5400 6068 +30896 1795 1665 2078 6133 +30897 3788 3677 6603 6604 +30898 5452 5477 6595 6873 +30899 5635 6596 5610 6874 +30900 1598 1596 1595 6202 +30901 4803 4587 4867 6214 +30902 3108 3255 3111 5943 +30903 3740 3902 6803 6939 +30904 1416 6804 1254 6940 +30905 4989 6154 4645 7106 +30906 4928 4930 4931 6495 +30907 6488 6760 3827 6900 +30908 1206 1300 1405 6728 +30909 2110 1736 1861 6635 +30910 419 6927 5919 7090 +30911 3363 3473 3364 6106 +30912 2456 2450 2862 7117 +30913 3590 3608 3614 7062 +30914 450 6882 451 7094 +30915 3445 6425 3487 7036 +30916 3762 6459 3854 6751 +30917 2284 2286 296 6935 +30918 1209 7004 1343 7071 +30919 2885 2884 3483 6172 +30920 3523 5961 3406 7196 +30921 4566 4564 4621 7121 +30922 3745 3966 3794 6264 +30923 5120 5033 5087 7027 +30924 1530 1531 1431 1323 +30925 2281 2284 2282 6294 +30926 3192 3193 3306 6243 +30927 4820 4819 4818 6036 +30928 2895 7174 5929 7175 +30929 2972 3525 2759 5985 +30930 478 4271 479 6194 +30931 2732 2733 2730 7021 +30932 3745 6264 3794 7169 +30933 3651 3595 3603 6251 +30934 1416 1254 1497 6940 +30935 3983 3902 3740 6939 +30936 2124 269 1876 6256 +30937 5076 5168 4811 6161 +30938 378 2574 379 6857 +30939 3152 2884 2858 6275 +30940 3458 3272 3457 6668 +30941 5568 6801 5482 6932 +30942 5726 6802 5640 6931 +30943 2864 2806 6469 7125 +30944 2664 2663 2554 7068 +30945 4721 4723 4722 6623 +30946 3387 3362 3361 6002 +30947 3881 3778 3690 6389 +30948 1302 1486 1191 6689 +30949 1340 1510 1430 6487 +30950 3916 3826 3996 6488 +30951 1481 1270 1328 6684 +30952 3967 3756 3814 6686 +30953 5491 6529 5536 7003 +30954 5649 6528 5694 7005 +30955 353 6566 2340 6889 +30956 1873 2053 1634 7047 +30957 588 5425 587 6045 +30958 1697 1786 2012 6356 +30959 3080 2793 3085 7179 +30960 4185 6256 468 6847 +30961 1817 1681 1881 6127 +30962 6446 6746 5835 6824 +30963 5352 5126 5132 6753 +30964 6233 6503 5753 6938 +30965 1927 1997 1724 5891 +30966 3564 3578 3579 6713 +30967 2897 2896 3239 7065 +30968 301 2268 302 7081 +30969 3369 3459 3284 6343 +30970 3479 6049 2697 7196 +30971 3512 3368 3513 6542 +30972 1612 6419 1613 7104 +30973 220 3627 219 6462 +30974 612 611 6736 7190 +30975 2429 2430 2431 7045 +30976 3288 2471 2473 6070 +30977 5473 6772 5519 6774 +30978 5631 6769 5677 6771 +30979 5006 4981 4986 6951 +30980 2940 3161 3274 5970 +30981 3248 6050 3249 6966 +30982 2887 2556 6378 7016 +30983 5502 621 6638 6757 +30984 3651 3595 6251 6928 +30985 4540 488 489 6190 +30986 5509 5446 5564 7031 +30987 1324 6531 1441 7111 +30988 3927 3810 6530 7112 +30989 3857 3779 3709 6716 +30990 5616 6528 5649 7005 +30991 5458 6529 5491 7003 +30992 298 2123 297 6379 +30993 4119 4205 4459 7170 +30994 3726 3871 3791 7207 +30995 625 4573 626 6240 +30996 3824 6562 4001 6595 +30997 1338 6561 1515 6596 +30998 4705 5328 5327 6627 +30999 5137 5136 5135 6181 +31000 1245 1414 1348 6278 +31001 1839 261 1951 6254 +31002 2329 2303 2360 6518 +31003 2348 6185 2297 7063 +31004 5645 6850 5696 6984 +31005 3426 3250 3148 7019 +31006 2293 1322 206 2213 +31007 2138 267 1852 6407 +31008 2279 2285 331 6387 +31009 6543 6701 1203 6810 +31010 1398 1266 1471 6699 +31011 3392 3348 3350 6281 +31012 6139 4235 7146 7183 +31013 5517 5548 5468 6654 +31014 5675 5706 5626 6655 +31015 5481 6853 5455 6907 +31016 2079 1664 1790 6033 +31017 1859 2125 1736 6341 +31018 466 4556 4507 6165 +31019 5326 4902 4807 6269 +31020 5462 5542 6875 6983 +31021 5620 5700 6878 6984 +31022 6112 6943 6409 6993 +31023 458 4255 4174 6097 +31024 4256 4175 498 6098 +31025 1377 1278 2470 7096 +31026 622 6835 623 7058 +31027 6875 6983 5542 7054 +31028 3326 3413 3417 6314 +31029 217 216 6370 7062 +31030 5396 522 5427 6110 +31031 2428 2585 2715 7023 +31032 491 4378 492 6249 +31033 4148 4303 4063 6146 +31034 4078 4477 4266 6006 +31035 5604 5722 5667 6956 +31036 1240 6476 1356 6766 +31037 4450 4371 4098 6734 +31038 4244 4071 4304 6624 +31039 5580 5513 5478 7207 +31040 1973 1713 2058 6114 +31041 1296 1448 1411 6810 +31042 3824 3697 3919 6562 +31043 1433 1338 1211 6561 +31044 386 2339 385 7044 +31045 482 4549 481 6078 +31046 5611 6769 5664 7070 +31047 1583 1584 1585 6305 +31048 3473 3363 3320 6106 +31049 1541 6415 1546 6756 +31050 3526 3476 3550 6239 +31051 624 623 5942 6666 +31052 5591 5499 5576 6731 +31053 5749 5657 5734 6732 +31054 1819 1680 2101 6186 +31055 3009 2385 3007 6647 +31056 3673 6862 3795 7119 +31057 2595 2592 5908 7173 +31058 3771 3896 3688 6412 +31059 443 3069 442 6020 +31060 2667 3134 3169 6143 +31061 4039 4351 4454 5891 +31062 4383 4196 4377 6312 +31063 5385 5423 519 6136 +31064 1796 1971 2045 5966 +31065 4323 4081 4329 6991 +31066 5035 5036 5095 7101 +31067 3788 3972 3677 6604 +31068 3818 3944 3668 6785 +31069 1458 1182 1332 6782 +31070 5516 5581 5496 6818 +31071 5674 5739 5654 6819 +31072 2571 2680 2630 6338 +31073 2218 2258 318 5992 +31074 4850 4874 4702 6378 +31075 420 6797 5969 6927 +31076 5656 6955 6892 6956 +31077 2265 2263 2260 6581 +31078 4178 4101 4425 6410 +31079 1787 1956 274 6359 +31080 6105 6965 6227 7001 +31081 1589 1594 1592 6664 +31082 2665 2667 2866 6231 +31083 4103 4246 4468 5994 +31084 2233 2238 2242 6397 +31085 5538 613 5487 7190 +31086 3877 3683 4002 6539 +31087 503 4336 6449 7079 +31088 273 6198 2021 7212 +31089 577 576 6125 7014 +31090 4174 6838 6097 6952 +31091 6503 6862 26 7119 +31092 274 1956 275 6359 +31093 2131 2100 1644 6222 +31094 5572 5464 5494 6783 +31095 5652 5730 5622 6780 +31096 2166 271 1908 5968 +31097 1784 2019 249 6485 +31098 4865 4864 4729 6523 +31099 3132 6808 2589 6968 +31100 5234 5233 5184 6218 +31101 3256 3224 5976 7142 +31102 2774 2772 2763 6855 +31103 5307 5081 5326 6137 +31104 2873 2939 2874 6216 +31105 3897 6509 3715 7041 +31106 1712 2030 1982 7122 +31107 2612 3564 6713 7148 +31108 4503 4528 475 6251 +31109 1691 1957 1914 6156 +31110 4529 4553 479 6306 +31111 28 5899 6585 6741 +31112 572 6637 5660 6758 +31113 2635 2636 2637 6272 +31114 4159 4296 4409 6132 +31115 1856 6450 1686 6946 +31116 5065 5064 5063 7167 +31117 2030 2184 1674 6864 +31118 3901 6749 3852 7013 +31119 1575 1571 1574 6327 +31120 4224 6944 5989 7132 +31121 1894 250 2019 6192 +31122 3365 3491 3492 6353 +31123 5942 6749 6666 7013 +31124 6392 5929 7174 7175 +31125 6413 6844 6381 7128 +31126 3480 3459 3482 6965 +31127 2107 1685 1833 6691 +31128 3809 2210 3935 6805 +31129 1972 6223 1692 7091 +31130 2850 2859 2864 7124 +31131 5169 5278 5023 6612 +31132 5178 5972 6813 6843 +31133 5247 6298 5246 6842 +31134 4392 4102 4387 6033 +31135 2089 1709 1854 6316 +31136 529 5412 5409 6141 +31137 2678 5956 2677 6920 +31138 519 6331 520 6579 +31139 345 2242 344 6990 +31140 4994 4861 4936 5801 +31141 3812 2712 408 3942 +31142 4502 4522 4517 6313 +31143 490 6883 491 6996 +31144 5752 6644 5641 6770 +31145 5594 6645 5483 6773 +31146 3484 6063 3455 7084 +31147 335 2351 336 6241 +31148 5538 5481 611 7190 +31149 3314 1376 1483 7008 +31150 622 6830 5929 7058 +31151 3494 3459 3416 6965 +31152 2038 1639 1834 5878 +31153 3683 6539 3877 7193 +31154 2318 2367 341 6201 +31155 5442 6648 5526 6978 +31156 5684 5600 6649 6979 +31157 2676 6536 6246 6920 +31158 5783 6967 6022 7150 +31159 2335 2334 2310 6334 +31160 4637 5893 4993 7035 +31161 3824 4001 3680 6595 +31162 1194 1338 1515 6596 +31163 3775 4009 3857 6716 +31164 3531 3562 3522 6041 +31165 5362 5328 5115 6627 +31166 5271 5269 5267 6314 +31167 1540 1545 1544 6415 +31168 4654 4614 4607 6411 +31169 2096 1820 1917 6441 +31170 4266 4132 6535 6944 +31171 1445 6594 6782 7199 +31172 3931 6593 6785 7200 +31173 3825 6645 3733 6773 +31174 1339 6644 1247 6770 +31175 5754 6674 5930 7044 +31176 3979 6772 3735 7085 +31177 3452 6280 3451 7144 +31178 3927 6611 3758 6811 +31179 1441 6610 1272 6812 +31180 1865 2014 1726 6516 +31181 5708 5647 6583 6788 +31182 1511 1431 1323 6925 +31183 5550 5489 6584 6821 +31184 3714 6736 3896 7075 +31185 5653 6732 5607 6994 +31186 629 6492 630 6730 +31187 3628 3627 3587 6313 +31188 2975 2984 2447 7013 +31189 1721 2008 1975 6375 +31190 5437 5525 5511 6530 +31191 5669 5595 5683 6531 +31192 5426 6135 598 7154 +31193 258 2043 1901 5991 +31194 3905 3804 3676 6631 +31195 1318 1190 1419 6632 +31196 4171 4353 4341 6203 +31197 3781 3933 3897 6723 +31198 2270 2272 2277 7143 +31199 1277 1334 6860 7040 +31200 4437 4429 6349 6714 +31201 1958 1916 1689 6019 +31202 4869 5127 5216 6347 +31203 32 6570 631 6716 +31204 3959 3987 6538 6638 +31205 1501 6540 1473 6637 +31206 5564 5475 5509 6564 +31207 5633 5667 5722 6563 +31208 4612 4834 4835 6985 +31209 2483 2657 2658 7052 +31210 2842 3245 3246 5931 +31211 4583 4567 4570 6380 +31212 5555 6803 5476 6922 +31213 5713 6804 5634 6923 +31214 3830 2729 2924 3951 +31215 1430 1241 1340 6879 +31216 3916 3727 3826 6877 +31217 1291 1241 1451 6901 +31218 4201 4093 4299 6090 +31219 31 4732 560 6582 +31220 1926 1709 1922 6079 +31221 4225 471 4140 6407 +31222 4559 6967 6022 7164 +31223 5944 6973 6688 7109 +31224 4098 4267 4288 6734 +31225 2970 3162 2972 6047 +31226 555 556 5783 6967 +31227 251 2169 252 5836 +31228 274 6756 1541 7212 +31229 5513 6907 5478 7207 +31230 4293 4126 4374 6156 +31231 6862 6863 26 7119 +31232 5400 5379 510 6296 +31233 1493 1343 7005 7071 +31234 3400 3565 3258 6411 +31235 4105 4380 6337 6884 +31236 1920 6677 6066 7192 +31237 2332 2361 343 6040 +31238 2831 3314 1483 7008 +31239 2269 2273 2266 6439 +31240 5483 6773 6645 6893 +31241 5641 6770 6644 6892 +31242 3409 3410 3424 6012 +31243 1826 1739 2117 7176 +31244 26 4335 464 6359 +31245 453 452 6636 6895 +31246 2336 2356 2301 6309 +31247 552 551 5833 6916 +31248 3758 3973 3955 6866 +31249 1272 1487 1469 6865 +31250 5495 6731 5449 6989 +31251 1470 1345 1258 6902 +31252 3872 6725 3769 6913 +31253 1923 1662 2087 6176 +31254 5248 5258 5249 6304 +31255 3825 6645 6773 6893 +31256 6644 6770 1339 6892 +31257 4150 4345 4445 6064 +31258 1278 1223 1364 5875 +31259 2621 6466 3455 7097 +31260 1672 1811 2193 6958 +31261 5318 5178 5180 6813 +31262 2725 1284 171 3121 +31263 2726 3770 412 3120 +31264 2924 2729 394 3951 +31265 2635 3343 3340 6030 +31266 4381 6527 4107 7079 +31267 2262 2264 2260 6776 +31268 2584 1366 166 1456 +31269 6797 7089 6927 7090 +31270 3113 3112 2768 6896 +31271 1538 1526 1525 6324 +31272 4178 4399 4101 6410 +31273 2558 2556 2555 6378 +31274 4098 4371 4416 6734 +31275 5632 5747 6619 6841 +31276 5589 6620 5474 6840 +31277 5456 6488 5522 6900 +31278 5443 6676 6818 6866 +31279 5601 6675 6819 6865 +31280 5633 6563 5722 6644 +31281 5475 6564 5564 6645 +31282 4291 4167 4067 7210 +31283 2867 3468 3342 6023 +31284 1461 7011 6979 7012 +31285 3947 7009 6978 7010 +31286 3349 3359 3350 6288 +31287 5629 5731 5658 6954 +31288 5573 5500 5471 6953 +31289 430 3622 431 6051 +31290 5426 5392 598 6135 +31291 4223 4361 4133 6558 +31292 4307 4040 4165 6149 +31293 2417 2767 2418 6457 +31294 2849 2783 2782 6750 +31295 2235 2232 2237 6625 +31296 4993 4637 4638 5893 +31297 1471 1349 1251 6699 +31298 3061 2951 3344 6789 +31299 612 611 5884 6736 +31300 233 234 6943 6993 +31301 5108 4832 4833 5847 +31302 4876 4871 6183 7147 +31303 2896 2809 7065 7175 +31304 1893 1755 6677 6934 +31305 2858 2859 2860 7124 +31306 5501 5471 6570 6904 +31307 5629 6569 5659 6903 +31308 2198 3913 321 3807 +31309 5265 4610 5154 6427 +31310 4388 4035 4396 6501 +31311 4909 4912 7037 7109 +31312 3808 1528 1529 6575 +31313 3669 6704 3826 6877 +31314 1340 1183 6705 6879 +31315 1895 295 2168 6718 +31316 1437 1426 213 7017 +31317 1326 2973 167 1456 +31318 3422 3372 3524 6747 +31319 3899 3805 3735 7085 +31320 5249 6304 5258 7214 +31321 1589 1584 1591 6871 +31322 2593 2594 2592 7173 +31323 5758 6763 5826 7077 +31324 423 3646 3618 6022 +31325 465 4419 4183 6198 +31326 2448 2449 404 3802 +31327 3191 3265 3284 6021 +31328 5060 5086 4952 7101 +31329 517 5415 518 6854 +31330 1466 1370 6498 6689 +31331 4943 5306 4872 7043 +31332 3572 3022 3268 7139 +31333 5422 5382 585 6115 +31334 3307 3305 3389 6263 +31335 3196 2458 3195 6257 +31336 3082 3505 3083 6273 +31337 1843 1983 1638 6120 +31338 5614 6602 5637 6759 +31339 5456 6603 5479 6760 +31340 1302 1206 1405 6775 +31341 5684 5661 6528 6703 +31342 5526 5503 6529 6702 +31343 3355 3356 3385 5980 +31344 215 1539 1543 6794 +31345 5574 6603 618 6604 +31346 4112 4349 4235 7183 +31347 2614 2796 3128 7073 +31348 6751 6882 450 7094 +31349 2031 1713 1973 6114 +31350 4830 4829 4601 6908 +31351 2496 2588 2587 6844 +31352 575 574 6746 6974 +31353 3455 3484 3477 6063 +31354 262 1868 263 6134 +31355 4261 6244 4069 7183 +31356 3529 3448 3290 5912 +31357 1692 6187 1880 7091 +31358 2411 2410 2998 5887 +31359 3157 2677 2678 5956 +31360 1206 1281 1467 6775 +31361 2335 2310 381 6321 +31362 2219 352 2215 6318 +31363 3492 3493 3365 6353 +31364 4199 4279 4084 6283 +31365 6389 6828 615 6876 +31366 3682 3928 3847 6721 +31367 620 6317 6643 6826 +31368 3890 6772 3979 6774 +31369 1493 1404 6769 6771 +31370 3365 3363 3364 6448 +31371 2622 2619 3311 6345 +31372 530 26 6233 6503 +31373 1443 6802 1243 7012 +31374 3929 6801 3729 7010 +31375 1205 1479 1401 6791 +31376 3691 3965 3887 6790 +31377 6168 6930 6187 7188 +31378 3240 3229 3558 6560 +31379 530 6503 6233 6938 +31380 6648 6702 5526 6978 +31381 5684 6649 6703 6979 +31382 4830 5073 4829 6908 +31383 1849 1659 2013 6337 +31384 5263 5271 5255 6297 +31385 4375 4051 4283 6168 +31386 2317 375 2363 7151 +31387 614 6876 6009 6976 +31388 329 2288 328 6293 +31389 1497 1330 1193 6780 +31390 3816 3679 3983 6783 +31391 2569 2989 2573 5984 +31392 564 6984 5645 7060 +31393 574 4773 575 6446 +31394 233 3654 3612 6112 +31395 3805 6686 3695 7085 +31396 4064 6341 6669 7203 +31397 424 3618 3599 6894 +31398 5379 589 5404 6295 +31399 4280 6605 4143 6964 +31400 3934 3782 6736 7190 +31401 2496 6844 6413 7128 +31402 1584 1589 1590 6423 +31403 1984 2104 1666 6152 +31404 1319 1249 7070 7071 +31405 3726 6580 3842 6765 +31406 2324 334 2350 6110 +31407 3941 3798 3707 7025 +31408 1221 1455 1312 7024 +31409 5933 6825 6278 6917 +31410 551 4551 552 5833 +31411 4686 5151 4684 6700 +31412 3615 433 3656 6456 +31413 4545 4496 4518 6092 +31414 565 6699 566 6878 +31415 2959 3468 2869 6683 +31416 4428 4044 4234 6352 +31417 3853 3798 3750 6369 +31418 5271 5147 5255 6332 +31419 3748 3939 3837 7193 +31420 2888 3074 3064 6103 +31421 5579 5448 5487 6983 +31422 5606 5645 5737 6984 +31423 3885 3907 386 7044 +31424 238 1550 1552 6545 +31425 5064 4649 5068 6339 +31426 4927 4932 4925 6394 +31427 4535 530 26 6233 +31428 5015 605 604 5880 +31429 3805 6924 6686 7085 +31430 1181 6892 6955 6956 +31431 2218 5992 317 7213 +31432 1190 6632 1412 7137 +31433 2674 2673 2672 6872 +31434 5168 5199 4956 6717 +31435 4232 4068 4301 7056 +31436 4398 4179 4202 6599 +31437 5334 5026 4808 6502 +31438 3858 3710 3780 6886 +31439 621 5310 622 6392 +31440 4422 4161 4062 6226 +31441 594 5383 593 6628 +31442 6649 6703 1273 6732 +31443 6648 6702 3759 6731 +31444 3581 3489 3358 6219 +31445 5269 4656 5268 6626 +31446 27 490 6694 6883 +31447 4247 4181 494 6474 +31448 7004 7005 1343 7071 +31449 2557 2555 2556 7016 +31450 2828 163 3159 1316 +31451 3192 3306 3531 6455 +31452 3162 2931 2933 6394 +31453 1384 1187 1325 6741 +31454 2345 2295 2311 6902 +31455 2443 2441 2419 6816 +31456 536 6123 4523 6999 +31457 3327 3234 2826 6374 +31458 354 3924 3913 7169 +31459 500 6825 501 7070 +31460 4281 4085 4326 6432 +31461 2619 3477 3310 7097 +31462 4598 4620 4981 6763 +31463 3047 3045 3044 5997 +31464 3550 3476 2700 6024 +31465 4223 4123 4361 6029 +31466 2227 2232 2236 6443 +31467 5645 564 5700 6984 +31468 5487 613 5542 6983 +31469 2310 2337 2338 6598 +31470 5795 6482 6727 6728 +31471 2223 2225 316 7213 +31472 4906 6849 4835 6985 +31473 3997 3917 3809 6805 +31474 4081 4367 4436 5788 +31475 2209 3935 2210 6805 +31476 1236 1428 6675 6819 +31477 3722 3914 6676 6818 +31478 478 4510 477 6308 +31479 3976 3739 6562 6893 +31480 1490 1253 6561 6892 +31481 536 4504 6123 7076 +31482 624 5571 6666 7193 +31483 3748 3877 6641 7193 +31484 3454 3460 2543 6630 +31485 1877 2121 1742 6151 +31486 1634 1999 7047 7192 +31487 5359 5145 5224 6489 +31488 4904 4839 4903 7123 +31489 457 7002 458 7003 +31490 498 497 7004 7005 +31491 4858 4931 4880 6495 +31492 385 2373 384 6401 +31493 1606 1616 1611 6262 +31494 3638 6809 213 7017 +31495 4527 4557 4494 6121 +31496 1702 1964 1777 7006 +31497 3394 3406 3395 5961 +31498 1525 1617 1612 6419 +31499 1600 1592 1595 6422 +31500 2424 5785 7048 7161 +31501 1407 1329 1237 6727 +31502 2473 2471 2472 6454 +31503 4738 555 5783 7150 +31504 4778 4780 4779 6099 +31505 1559 1561 1567 6409 +31506 3186 3178 3181 6591 +31507 510 4320 509 6153 +31508 5618 5668 6610 6865 +31509 5510 6611 5460 6866 +31510 3741 3852 3901 6749 +31511 297 2286 2280 6935 +31512 1660 2105 6270 7069 +31513 480 4505 4529 6307 +31514 4716 4718 4717 6755 +31515 5122 4631 4629 6195 +31516 463 4335 26 6359 +31517 2372 2341 1345 6902 +31518 4567 4866 566 6381 +31519 293 1953 292 6911 +31520 6088 6860 6829 6933 +31521 3905 3960 3776 6631 +31522 1474 1289 1419 6632 +31523 2685 2659 3815 7093 +31524 512 6397 6435 6586 +31525 6636 7025 6250 7208 +31526 4434 4137 4230 6460 +31527 2970 2971 2969 6621 +31528 6927 7089 5919 7090 +31529 3864 3714 3922 7075 +31530 4069 4261 4337 6244 +31531 1596 1602 1603 6463 +31532 1495 1264 1312 6467 +31533 484 485 4522 6462 +31534 5826 6763 6514 7077 +31535 345 2368 346 6990 +31536 3978 3939 3748 6641 +31537 1453 1262 1492 6640 +31538 240 3609 239 6169 +31539 5237 6182 7055 7214 +31540 1964 2157 1653 5996 +31541 5628 5679 5682 6972 +31542 5521 5524 5470 6971 +31543 1703 2097 1776 6597 +31544 1791 1894 1699 6918 +31545 4618 4579 5106 6039 +31546 1301 1414 6825 6997 +31547 5673 31 5738 6722 +31548 3127 3094 3172 7064 +31549 1613 1617 250 6419 +31550 3296 3292 3295 6382 +31551 4255 4314 4174 6547 +31552 1342 1199 1510 6487 +31553 3828 3685 3996 6488 +31554 3218 1393 2990 6869 +31555 2282 2283 2281 6294 +31556 3123 3225 2555 6265 +31557 4265 4476 4077 6964 +31558 6049 7196 5961 7197 +31559 4107 7018 4336 7079 +31560 4450 4098 4288 6734 +31561 3957 3737 3884 6876 +31562 2575 2618 146 7107 +31563 5262 5313 5164 6031 +31564 4381 501 6322 7079 +31565 2396 2432 3863 7041 +31566 2003 1750 2004 7129 +31567 5390 596 5416 6962 +31568 1974 1972 1797 5999 +31569 5299 5342 5263 6842 +31570 5610 5646 6874 7111 +31571 5488 6873 5452 7112 +31572 5136 5137 5138 6845 +31573 2795 2903 2792 6697 +31574 5014 606 605 6987 +31575 2405 6371 2404 6914 +31576 1583 1586 1584 6305 +31577 4854 4925 4932 6394 +31578 2243 2238 2233 6397 +31579 6602 6759 5614 6901 +31580 2878 2581 2580 7127 +31581 4083 4200 4407 7188 +31582 5273 4710 5333 6711 +31583 1633 1836 2051 6386 +31584 1850 1920 2150 7192 +31585 5154 4611 5221 6426 +31586 6875 6876 3752 7054 +31587 1698 1785 2020 6527 +31588 4644 4645 4989 6154 +31589 1472 1184 1375 6528 +31590 3958 3670 3861 6529 +31591 5509 5575 5446 7031 +31592 1912 1688 1813 6312 +31593 3260 3256 3224 5976 +31594 4506 4517 4522 6313 +31595 3991 3784 4010 6584 +31596 1298 1524 1505 6583 +31597 3992 3745 3794 7169 +31598 1589 1591 1594 6664 +31599 3924 354 2344 7169 +31600 5618 6610 5723 6812 +31601 5565 5460 6611 6811 +31602 1540 1534 1542 6653 +31603 3431 3315 3428 5784 +31604 526 5405 5433 6284 +31605 4767 6885 5862 7189 +31606 4908 6849 4906 7147 +31607 2908 2825 2829 6657 +31608 2932 2820 2819 5944 +31609 4688 6437 4888 7088 +31610 2012 6356 1786 7026 +31611 574 5678 573 6637 +31612 3877 3889 3748 6641 +31613 1262 1391 1403 6640 +31614 3825 3925 3739 6773 +31615 1439 1253 1339 6770 +31616 1373 6637 1263 6897 +31617 1302 1333 1206 6775 +31618 2396 2394 2395 7108 +31619 485 486 4533 6261 +31620 4766 4915 4979 7029 +31621 2037 1660 2105 6270 +31622 3897 3770 6509 7041 +31623 3169 6552 3552 6713 +31624 2006 1704 1932 5818 +31625 1501 6637 1373 6758 +31626 3987 6638 3859 6757 +31627 1310 6416 6476 6722 +31628 2803 2802 2564 6484 +31629 3553 3470 3210 6767 +31630 3888 3770 2726 7110 +31631 3624 215 3643 6190 +31632 5678 6541 6540 6637 +31633 5520 6539 6538 6638 +31634 2250 2259 2253 6319 +31635 214 3638 213 7017 +31636 3849 2502 2377 6886 +31637 5604 5667 5733 6956 +31638 2951 3061 2943 6789 +31639 1672 6226 1946 6958 +31640 3802 2449 404 3865 +31641 3172 2938 2762 7064 +31642 2451 6933 2505 7040 +31643 2817 381 2816 6080 +31644 306 2252 307 6384 +31645 525 5380 5405 6285 +31646 4429 4155 512 6291 +31647 2934 2663 2664 6299 +31648 2404 2405 2983 6371 +31649 1461 1286 1213 7011 +31650 3699 3947 3772 7009 +31651 4184 4420 488 6192 +31652 2749 3006 3318 6372 +31653 1885 193 1306 2084 +31654 1884 283 3792 2085 +31655 2266 2274 2269 6846 +31656 4661 4921 5062 6343 +31657 3235 3206 375 6926 +31658 3842 6580 3796 6862 +31659 4183 4397 4387 7157 +31660 6593 6891 5490 7200 +31661 6594 6890 5648 7199 +31662 4816 4817 543 6832 +31663 4383 4185 4467 6034 +31664 2432 3120 3921 7041 +31665 3352 3516 3053 6567 +31666 1388 1406 1265 6931 +31667 3874 3892 3751 6932 +31668 2623 2625 3036 6398 +31669 3863 2396 7041 7108 +31670 3634 3661 3908 7083 +31671 5462 6704 5579 6983 +31672 5620 6705 5737 6984 +31673 230 3651 6365 6928 +31674 1547 1549 1551 6428 +31675 3155 3513 2595 7173 +31676 3705 3956 3796 6503 +31677 3795 3796 6503 6862 +31678 2145 1864 264 6093 +31679 2998 3070 3069 6414 +31680 1197 1336 1516 6746 +31681 3849 2377 388 6886 +31682 25 450 6751 6882 +31683 6232 6642 5803 7017 +31684 5491 5536 457 7003 +31685 5649 5694 497 7005 +31686 4047 4219 4478 6204 +31687 5116 4827 4828 6177 +31688 3373 3374 3372 6004 +31689 5652 5622 5712 6782 +31690 5494 5464 5554 6785 +31691 3439 3437 3438 6358 +31692 2818 2968 2988 6059 +31693 5189 5190 5352 6752 +31694 3790 6863 3870 7061 +31695 4360 5989 4224 6944 +31696 2221 2222 2220 6209 +31697 3539 3522 3540 6101 +31698 4803 4801 4587 6214 +31699 6449 7018 6527 7079 +31700 2140 1854 256 6779 +31701 5073 5072 4829 6908 +31702 2274 2266 2268 7081 +31703 1464 6531 1286 7012 +31704 3950 6530 3772 7010 +31705 1792 1661 1958 6018 +31706 3377 3376 3378 7166 +31707 3471 3355 3385 5980 +31708 5676 569 6602 6689 +31709 2275 2277 2280 6354 +31710 468 4531 467 6362 +31711 5908 6973 6058 7173 +31712 5576 5449 5495 6731 +31713 5734 5607 5653 6732 +31714 3669 3970 3895 6704 +31715 1183 1484 1409 6705 +31716 2687 2686 2838 5862 +31717 5469 6801 5568 6939 +31718 5627 6802 5726 6940 +31719 6629 7024 6248 7209 +31720 3626 3625 3586 6715 +31721 4613 5029 4603 6333 +31722 537 4548 538 5979 +31723 5036 5086 5095 7101 +31724 3120 3770 412 3921 +31725 3121 1284 171 1435 +31726 3638 3636 213 6809 +31727 6978 7009 5545 7010 +31728 6979 7011 5703 7012 +31729 3934 3676 3782 7190 +31730 1769 2139 1853 7057 +31731 5574 5518 618 6603 +31732 5732 5676 569 6602 +31733 4590 5087 5033 6361 +31734 274 275 1535 6756 +31735 1571 1572 1568 6094 +31736 2541 2542 2543 6630 +31737 5133 4845 5305 6245 +31738 5645 6984 5696 7060 +31739 3940 3696 6548 7113 +31740 1210 6549 1454 7114 +31741 3789 3734 3838 6633 +31742 1303 1248 1352 6634 +31743 3827 3721 3911 6760 +31744 1235 1425 1341 6759 +31745 1229 6587 1278 7096 +31746 4437 4038 4291 6714 +31747 1531 1626 1622 6925 +31748 3770 3968 3897 6509 +31749 511 512 6397 6435 +31750 419 6797 6927 7090 +31751 1882 1700 1824 6395 +31752 3028 2824 2996 6431 +31753 2270 2271 2269 6329 +31754 3677 3911 3788 6603 +31755 1191 1425 1302 6602 +31756 1760 1835 1942 6167 +31757 1401 1303 1396 6867 +31758 3789 3882 3887 6868 +31759 4009 3712 3817 6570 +31760 1331 1523 1227 6569 +31761 3839 3964 3743 6720 +31762 1847 2040 1772 5959 +31763 2420 7064 2762 7195 +31764 1511 1323 1216 6925 +31765 2390 2389 2388 7186 +31766 2420 2762 2763 7195 +31767 31 6048 6571 7165 +31768 3685 3827 6488 6760 +31769 1341 6487 1199 6759 +31770 3183 3540 3521 6662 +31771 4727 4728 4730 7181 +31772 226 3619 225 6306 +31773 5879 6999 6123 7076 +31774 3895 6704 3970 6983 +31775 1409 6705 1484 6984 +31776 3741 4003 3942 6749 +31777 5506 6772 5582 7085 +31778 4168 4324 4082 6175 +31779 3521 3522 3510 6738 +31780 361 2319 360 6589 +31781 1937 1768 2088 6271 +31782 1676 2059 1842 6474 +31783 3536 3490 3149 5923 +31784 3423 3200 2622 6163 +31785 6014 7080 6303 7126 +31786 2341 1438 1345 6902 +31787 603 5920 4638 6617 +31788 5243 5067 4766 6515 +31789 5640 6931 6802 7012 +31790 5482 6932 6801 7010 +31791 3584 3635 3662 6809 +31792 2051 1836 1722 6386 +31793 3290 3292 3529 5912 +31794 4674 4679 4581 6425 +31795 3928 6580 3726 7207 +31796 3619 3640 225 6306 +31797 489 4537 4540 6190 +31798 3298 2955 3080 7179 +31799 3400 3398 3399 6870 +31800 1974 1831 1647 6000 +31801 2040 1758 1842 6335 +31802 3776 6497 3858 6721 +31803 3880 3825 3733 6773 +31804 1394 1339 1247 6770 +31805 296 2286 297 6935 +31806 1417 1308 1480 6232 +31807 5214 5158 5179 6843 +31808 3790 3673 3870 6863 +31809 4901 4635 4786 7049 +31810 3532 2730 2653 7021 +31811 3803 3800 6953 7113 +31812 1314 6954 1317 7114 +31813 2426 2796 2614 6977 +31814 615 4862 6388 6976 +31815 3001 3071 361 5881 +31816 1315 6892 6851 6955 +31817 5392 5385 5372 6478 +31818 4550 4524 4501 6520 +31819 2561 3852 3942 6749 +31820 3749 4002 3822 7058 +31821 5058 5003 4798 6237 +31822 4052 4383 4467 6034 +31823 4825 4822 4823 5892 +31824 3539 3569 3285 6102 +31825 1345 1504 1422 6519 +31826 4574 4587 4588 6235 +31827 5554 5440 6785 7200 +31828 5712 5598 6782 7199 +31829 1983 1807 2107 6691 +31830 1623 276 3783 7082 +31831 5240 599 5245 7154 +31832 2226 2227 2228 6119 +31833 2821 2627 2629 6197 +31834 4291 6403 4067 7028 +31835 2289 2284 295 6718 +31836 5599 6487 5690 6960 +31837 5441 6488 5532 6959 +31838 1270 1380 1423 5933 +31839 3866 3909 3756 5932 +31840 4559 554 4534 6022 +31841 4280 4453 4143 6605 +31842 3995 3849 388 6886 +31843 5686 6640 576 7014 +31844 4626 4616 5358 6618 +31845 4205 4259 4108 7170 +31846 5529 6730 5500 6953 +31847 5687 6729 5658 6954 +31848 5714 5678 5628 6541 +31849 5520 5470 5556 6539 +31850 1359 1453 1283 7014 +31851 3095 3251 3299 6480 +31852 2729 3830 394 3951 +31853 4365 4147 4400 6663 +31854 2010 6348 1784 7156 +31855 4646 4648 4647 6526 +31856 5627 5726 5672 6940 +31857 5469 5568 5514 6939 +31858 4620 4852 4981 6951 +31859 2264 2254 2260 6581 +31860 4997 4647 6320 6916 +31861 2245 2246 2244 6452 +31862 314 2121 313 7180 +31863 1550 1547 1552 6545 +31864 3556 3546 3460 5792 +31865 1429 1195 6569 7205 +31866 157 2711 2990 1393 +31867 4992 4979 4980 6148 +31868 481 4520 480 6307 +31869 4230 4137 4363 6460 +31870 3997 3809 3702 6805 +31871 1498 1320 6827 6878 +31872 3806 6828 3984 6875 +31873 2877 3446 3366 6426 +31874 2868 2867 2899 6929 +31875 232 3647 231 7080 +31876 2692 2528 3003 6514 +31877 1798 189 1933 1495 +31878 279 1934 1800 3981 +31879 3744 3795 3956 6503 +31880 5659 30 6458 6569 +31881 5501 32 6459 6570 +31882 3399 3515 3514 6342 +31883 2055 1669 1931 7033 +31884 1219 1480 1346 6809 +31885 1309 1187 1310 6476 +31886 2421 2422 2445 7195 +31887 3752 6875 3984 6876 +31888 4136 4437 4429 6349 +31889 3001 3071 5881 7152 +31890 1443 6649 1392 6802 +31891 3878 3929 6648 6801 +31892 5126 6753 5128 6837 +31893 2098 6238 304 7006 +31894 1977 266 265 5946 +31895 5774 7117 2861 7160 +31896 3122 3248 3245 6966 +31897 3414 3416 3415 6227 +31898 4532 4555 4498 6430 +31899 1805 6072 7059 7177 +31900 5722 5604 5656 6892 +31901 5498 5564 5446 6893 +31902 3165 3301 367 5939 +31903 1469 1365 1199 6865 +31904 3851 3685 3955 6866 +31905 1528 3808 3912 6575 +31906 4913 4980 4979 7029 +31907 3744 3832 3923 7083 +31908 488 6192 4420 7172 +31909 1319 6684 1209 7071 +31910 5497 5532 5460 6811 +31911 5655 5690 5618 6812 +31912 2205 2194 2216 6287 +31913 555 556 4738 5783 +31914 5308 621 5222 6643 +31915 191 1828 1891 7024 +31916 1829 1892 281 7025 +31917 3070 3102 3069 6414 +31918 4305 4145 4072 6559 +31919 4113 6107 4294 7146 +31920 5634 5596 6549 6804 +31921 5476 5438 6548 6803 +31922 1346 1259 1437 6809 +31923 2288 2282 2287 6510 +31924 2011 2024 1785 6527 +31925 5739 5648 6890 7199 +31926 5581 5490 6891 7200 +31927 1355 6453 1256 7205 +31928 3826 3669 3918 6704 +31929 1432 1340 1183 6705 +31930 2818 6059 6688 6973 +31931 214 213 1536 7017 +31932 4758 4732 4715 6582 +31933 350 2224 2222 6550 +31934 4627 4827 4570 6351 +31935 1318 1412 1190 6632 +31936 3804 3898 3676 6631 +31937 3888 3968 3770 7110 +31938 370 371 2325 7063 +31939 5555 6922 5552 6989 +31940 2231 314 2229 7180 +31941 3590 3614 3644 6077 +31942 3989 3831 3907 7044 +31943 1206 1333 1281 6775 +31944 2239 2249 2244 6292 +31945 4575 4577 4576 5981 +31946 3402 3441 3403 6180 +31947 1233 6541 6540 6972 +31948 3719 6539 6538 6971 +31949 2321 2303 2329 6518 +31950 4476 4143 4077 6964 +31951 3084 2539 3567 6665 +31952 4438 4430 4156 6225 +31953 2763 6108 6855 7195 +31954 3264 3528 3266 6046 +31955 1950 6778 2189 6992 +31956 260 259 2097 6194 +31957 5610 6812 5669 7111 +31958 5452 6811 5511 7112 +31959 1893 6352 1866 6934 +31960 3888 3753 3968 6221 +31961 2915 2981 2674 6872 +31962 3248 3122 2471 6454 +31963 1863 2144 308 6690 +31964 5783 555 6967 7150 +31965 5091 4649 5065 6130 +31966 1405 1237 1486 6482 +31967 1335 1223 1278 5875 +31968 1816 1886 1637 6930 +31969 1804 1735 1929 6027 +31970 4322 4140 471 6407 +31971 3397 3396 3324 6277 +31972 340 2257 339 6506 +31973 5525 5511 6530 7112 +31974 5669 6531 5683 7111 +31975 1803 2028 2113 6950 +31976 32 6459 6570 6674 +31977 5083 5030 4588 6393 +31978 3078 3278 3229 7103 +31979 4637 5097 5037 7035 +31980 5307 5222 5081 6137 +31981 2594 2968 2818 6973 +31982 3277 2943 3062 7198 +31983 5221 4679 4674 6425 +31984 5636 5671 5613 6955 +31985 1734 6420 1930 7177 +31986 3686 3876 6648 6978 +31987 1390 6649 1200 6979 +31988 3562 3531 3391 6041 +31989 3174 2850 2864 7050 +31990 3170 3552 3169 6552 +31991 3488 3361 3360 7036 +31992 5204 4656 5246 6626 +31993 4105 4397 4419 6884 +31994 4720 6755 4719 7145 +31995 2187 1868 1687 6859 +31996 626 6725 627 6913 +31997 4102 4387 6033 7157 +31998 2477 2778 2480 6481 +31999 3491 3446 3360 6404 +32000 3709 3775 3857 6716 +32001 3529 5912 6748 7138 +32002 3472 2875 2877 6427 +32003 3815 3893 399 2685 +32004 1200 1461 6979 7012 +32005 3686 3947 6978 7010 +32006 4973 4889 4890 7022 +32007 1972 1974 1647 5999 +32008 4243 4159 525 6379 +32009 2765 2856 2766 6551 +32010 5704 5741 5623 6476 +32011 2587 1292 155 2707 +32012 7002 7003 3829 7085 +32013 1496 1384 1242 6741 +32014 4224 4360 4124 5989 +32015 2130 2017 1805 7177 +32016 1550 1548 1547 6545 +32017 1912 2080 1688 6961 +32018 4418 4111 4204 6661 +32019 5011 4643 587 6470 +32020 3834 3731 3900 6440 +32021 6688 6973 6059 7109 +32022 228 1582 229 6260 +32023 536 5879 5017 7076 +32024 3326 3325 3495 6228 +32025 1434 6812 1342 6960 +32026 3920 6811 3828 6959 +32027 3190 3522 3539 6101 +32028 1232 1393 1292 6869 +32029 3737 3957 3835 7023 +32030 4619 4618 4620 6763 +32031 253 2122 254 6465 +32032 4106 4153 4378 6348 +32033 2088 1660 6271 7069 +32034 1557 1553 1556 6667 +32035 1761 1940 1989 6206 +32036 1653 1997 1927 6906 +32037 293 1785 1953 6449 +32038 4638 603 602 5920 +32039 1692 1972 1778 6223 +32040 4062 6226 4211 6942 +32041 1408 6841 1210 7114 +32042 3696 3894 6840 7113 +32043 256 255 2140 5845 +32044 1747 2137 2060 7032 +32045 3436 3394 3393 6298 +32046 3170 2835 3552 6552 +32047 1978 1707 1863 7201 +32048 3960 3820 3710 6497 +32049 3705 3990 3832 7083 +32050 4619 6763 4784 7189 +32051 1541 6756 1546 7212 +32052 1825 1700 1948 6025 +32053 4385 469 4185 6256 +32054 3744 3923 3912 6575 +32055 4101 4195 4197 6588 +32056 5710 5647 5625 6583 +32057 5552 5489 5467 6584 +32058 1234 1510 1340 6960 +32059 3720 3996 3826 6959 +32060 5271 5246 5269 6314 +32061 4428 4234 4134 6352 +32062 1699 2010 2178 6918 +32063 32 632 6459 6674 +32064 6787 6788 491 6996 +32065 4302 4045 4147 6420 +32066 268 1560 1566 6408 +32067 2536 2490 2489 6469 +32068 3044 3230 3244 7020 +32069 1268 1432 1409 6705 +32070 3754 3918 3895 6704 +32071 5704 6476 5623 6766 +32072 5713 6923 5710 6994 +32073 2829 2826 3234 6657 +32074 2227 2229 2237 7180 +32075 1938 1690 1769 6144 +32076 4312 4145 4372 6559 +32077 611 5481 5541 6631 +32078 3456 3418 3455 7084 +32079 5190 5352 6752 6753 +32080 3132 2827 3158 6968 +32081 2092 1946 6673 6958 +32082 3848 6983 6875 7054 +32083 622 5502 621 6638 +32084 3450 3451 3452 6280 +32085 2171 1670 1979 6118 +32086 31 6722 635 7165 +32087 2262 2260 2261 6331 +32088 1718 1946 2134 6673 +32089 2045 1881 1736 6635 +32090 3443 3446 2877 6426 +32091 5559 6853 6562 6893 +32092 5717 6851 6561 6892 +32093 1553 1554 1548 6323 +32094 503 5900 502 7079 +32095 4220 4176 4015 5977 +32096 6420 7059 6072 7177 +32097 4137 4434 4435 7015 +32098 3381 3467 3379 6477 +32099 4613 4603 4614 6333 +32100 536 4642 5017 5879 +32101 562 6829 6088 6860 +32102 1436 1488 151 3035 +32103 2088 1660 1937 6271 +32104 4261 4349 6357 7183 +32105 4084 6283 4279 7185 +32106 566 565 4567 6381 +32107 1476 1444 1193 6780 +32108 3962 3930 3679 6783 +32109 4006 3684 6820 6821 +32110 294 2020 293 6147 +32111 3311 3310 3424 6986 +32112 3480 3482 3481 6105 +32113 5456 6603 6760 6900 +32114 3943 6790 4005 7002 +32115 1457 6791 1519 7004 +32116 3689 3769 3872 6725 +32117 4045 4177 4400 6072 +32118 536 6123 6999 7076 +32119 3195 3119 3298 7179 +32120 3801 6853 3804 6907 +32121 4028 4311 4217 6577 +32122 2088 6406 1706 7069 +32123 1223 6499 1293 6848 +32124 5723 5693 5595 6610 +32125 5437 5565 5535 6611 +32126 293 2291 294 6147 +32127 1472 1390 1271 6979 +32128 3757 3958 3876 6978 +32129 3310 3484 3312 6986 +32130 238 239 3648 6698 +32131 6638 6830 622 7058 +32132 4619 5800 6763 7189 +32133 2739 3183 2734 6662 +32134 1865 2015 1649 6516 +32135 4387 4397 4034 6138 +32136 2481 3864 2482 6887 +32137 3590 6077 3644 6797 +32138 2695 371 370 5825 +32139 3472 3364 3271 6483 +32140 2514 2516 2774 6366 +32141 6852 6983 3725 7190 +32142 2387 2420 2421 7195 +32143 4559 6022 4534 7164 +32144 4511 4548 4500 6546 +32145 3785 3687 3914 6818 +32146 1428 1299 1201 6819 +32147 2025 1730 2172 7026 +32148 2538 1407 1300 6727 +32149 1183 1320 6878 6879 +32150 3806 6875 3669 6877 +32151 520 5395 521 6241 +32152 2290 328 2288 7034 +32153 361 360 2414 6589 +32154 2778 2607 3030 6481 +32155 1380 1319 1192 6825 +32156 6020 7076 6430 7136 +32157 2589 2778 2777 6274 +32158 5344 5249 5258 7214 +32159 3771 3688 3986 6412 +32160 3285 3263 3265 6555 +32161 310 1978 309 6291 +32162 2826 2829 2825 6657 +32163 191 1350 1828 7024 +32164 1829 281 3836 7025 +32165 2900 3118 6914 7042 +32166 5537 5437 5508 6530 +32167 5666 5695 5595 6531 +32168 4192 480 4394 5991 +32169 2816 2404 3081 6371 +32170 4433 4012 4332 6376 +32171 5128 5130 5127 6837 +32172 1787 2013 2026 6806 +32173 1606 1611 1615 7104 +32174 3499 3363 3493 6447 +32175 3382 3377 3580 7166 +32176 2786 2792 2793 6697 +32177 5691 5649 6771 7005 +32178 5533 5491 6774 7003 +32179 501 6825 6278 6997 +32180 5537 6530 5508 6932 +32181 5666 5695 6531 6931 +32182 573 5660 572 6637 +32183 5480 5456 5522 6900 +32184 238 3648 3620 6165 +32185 300 1853 2139 6145 +32186 5626 5742 5662 6655 +32187 5584 5504 5468 6654 +32188 3382 6747 3374 7166 +32189 3472 2877 3366 6483 +32190 2076 1708 1900 6225 +32191 4719 6755 5780 7145 +32192 2536 2864 2806 6469 +32193 3444 2876 3051 6082 +32194 4283 6168 4051 7188 +32195 3968 3845 3689 6725 +32196 4207 4319 4129 7095 +32197 5431 511 5403 6435 +32198 1181 6644 6892 6956 +32199 1971 1693 2045 5966 +32200 4053 4384 4197 7087 +32201 1501 1282 1473 6540 +32202 3987 3768 3959 6538 +32203 6645 6893 3667 7031 +32204 5365 5306 5146 7043 +32205 276 1532 275 7082 +32206 268 269 1560 6408 +32207 4067 4231 7028 7210 +32208 3333 3335 3231 6941 +32209 1932 2151 1752 6836 +32210 3194 6279 2805 6977 +32211 1764 2170 1980 6328 +32212 5701 5611 5664 7070 +32213 1211 6850 1318 6851 +32214 3697 6852 3804 6853 +32215 4245 4102 4467 6847 +32216 4546 4515 545 6650 +32217 5610 5655 5669 6812 +32218 5452 5497 5511 6811 +32219 1198 6787 1520 6788 +32220 318 2022 317 5992 +32221 1353 1218 1310 6416 +32222 2903 2795 2902 6208 +32223 1337 1311 1186 6883 +32224 3402 3489 3581 6508 +32225 4906 4834 4965 6985 +32226 4939 4991 4648 6937 +32227 1292 1349 1204 6413 +32228 5639 6632 5699 7137 +32229 562 561 6829 6860 +32230 2561 3852 407 3942 +32231 1346 3636 3662 6809 +32232 5876 6909 6614 7122 +32233 5537 6932 5482 7010 +32234 5640 5695 6931 7012 +32235 2230 2221 2226 6822 +32236 3690 3835 3957 6389 +32237 1224 1509 1294 7107 +32238 3137 2928 3538 7182 +32239 215 1618 216 6794 +32240 1484 6878 1362 6984 +32241 3970 6875 3848 6983 +32242 4938 4940 4846 6737 +32243 29 6721 5580 7207 +32244 1229 1278 1377 7096 +32245 3984 6828 3690 6876 +32246 3171 2713 3104 6608 +32247 1825 2182 1700 6025 +32248 1544 1545 1552 6698 +32249 2370 2305 2337 6598 +32250 558 5659 30 6458 +32251 5501 32 632 6459 +32252 6148 6798 5785 7161 +32253 2252 2247 307 6384 +32254 1619 1623 3843 7082 +32255 3416 3480 3478 7001 +32256 2584 165 1366 6824 +32257 3816 3696 3761 6840 +32258 1275 1330 1210 6841 +32259 5745 6955 5656 6956 +32260 5390 5388 5370 6948 +32261 512 4155 4300 7028 +32262 2025 1658 2012 7026 +32263 2618 1400 1294 7107 +32264 284 1903 3948 3949 +32265 1902 194 1463 1462 +32266 619 5080 5081 6434 +32267 5559 5498 6853 6893 +32268 5717 5656 6851 6892 +32269 3940 3696 3816 6548 +32270 1330 1454 1210 6549 +32271 3991 4010 3666 6922 +32272 1505 1524 1180 6923 +32273 3373 3431 3428 5784 +32274 3304 3306 3193 6243 +32275 3296 3529 3292 6748 +32276 3661 3832 3908 7083 +32277 5237 7055 5343 7214 +32278 2807 6054 2408 7116 +32279 6828 6875 615 6876 +32280 2444 2388 2421 7186 +32281 3595 3616 3604 6928 +32282 5663 5684 5616 6979 +32283 5526 5458 5505 6978 +32284 6420 6663 4147 7203 +32285 466 4183 4358 7157 +32286 2952 2950 2390 7186 +32287 6228 6609 3495 7102 +32288 5005 5058 5303 6799 +32289 329 328 2328 6293 +32290 4276 6322 501 6917 +32291 4187 4049 4369 6607 +32292 5344 5297 5237 6182 +32293 3434 3517 3520 5993 +32294 1563 1565 1570 6303 +32295 2738 2927 2548 6660 +32296 4489 4355 4228 6909 +32297 4105 4380 4154 6337 +32298 497 5694 496 6791 +32299 5536 456 457 6790 +32300 4489 4228 4125 6909 +32301 4002 3683 3822 7058 +32302 2619 3310 3311 6345 +32303 2740 2788 2651 6678 +32304 2112 1726 1947 6556 +32305 5642 5697 5730 6780 +32306 5539 5572 5484 6783 +32307 5124 5355 5356 6899 +32308 2326 333 332 6157 +32309 3847 3928 3726 7207 +32310 3832 3990 3908 7083 +32311 6022 6894 6739 7164 +32312 1212 6491 1502 6897 +32313 3439 3461 3465 6065 +32314 4294 4113 4272 6107 +32315 4004 3927 3665 6611 +32316 1441 1179 1518 6610 +32317 3821 3709 3764 6492 +32318 219 1610 220 6462 +32319 5678 6540 5612 6637 +32320 5520 6538 5454 6638 +32321 3379 3383 3359 6565 +32322 313 1916 312 6153 +32323 5524 5521 5459 6971 +32324 5682 5679 5617 6972 +32325 2343 2295 2372 6519 +32326 3281 3282 3331 6346 +32327 4257 4065 4135 6429 +32328 3393 3435 3436 6298 +32329 2010 2023 1656 7156 +32330 3619 3589 3640 6592 +32331 3848 6875 3752 7054 +32332 5518 6603 5456 6900 +32333 4197 4374 4030 6377 +32334 1551 1549 272 6428 +32335 300 2272 6846 7143 +32336 4979 4992 5019 6798 +32337 1677 2058 1843 6373 +32338 4720 4719 4759 7145 +32339 3829 7003 3979 7085 +32340 5531 5518 5456 6900 +32341 5341 5247 5342 6842 +32342 519 4253 518 6238 +32343 2962 3281 3468 6683 +32344 3672 6751 3854 7094 +32345 5480 5527 5590 6877 +32346 5748 5638 5685 6879 +32347 4349 4013 4261 6357 +32348 2057 1643 1844 6616 +32349 5121 5122 5340 6707 +32350 559 6232 27 6694 +32351 1855 311 2141 6290 +32352 5759 6849 5912 7147 +32353 4055 4179 4439 6599 +32354 4138 4344 4194 6385 +32355 339 2349 340 6506 +32356 4734 532 5855 7098 +32357 3082 2518 3505 6273 +32358 2073 2001 1767 6975 +32359 2818 6688 2820 6973 +32360 311 1855 310 6290 +32361 5162 5317 5164 6512 +32362 5738 6571 560 6743 +32363 248 1627 1530 6925 +32364 1509 147 2381 1363 +32365 1305 1226 6743 6955 +32366 1867 2186 1686 6946 +32367 3949 285 1903 3814 +32368 348 2337 349 6116 +32369 3162 2970 3154 6047 +32370 3084 3567 3029 6665 +32371 307 2247 308 6690 +32372 620 621 6757 6826 +32373 4565 4895 4564 7121 +32374 4470 4222 4057 6436 +32375 5827 6497 6417 6886 +32376 2401 2773 2772 6855 +32377 4240 459 4174 6838 +32378 3673 3811 6863 7119 +32379 6492 6723 5810 7108 +32380 4309 4372 6311 7018 +32381 2292 3809 3917 6805 +32382 576 5679 575 6974 +32383 3842 3726 3796 6580 +32384 2798 2799 3279 6947 +32385 3933 3821 3715 6723 +32386 3406 3523 3395 5961 +32387 1591 1584 1586 6871 +32388 3823 3797 3672 6882 +32389 1197 1415 6746 6974 +32390 4264 4402 4031 6995 +32391 3216 3516 3212 7120 +32392 3516 3054 3053 7120 +32393 1790 1696 1897 6988 +32394 1373 1501 1263 6637 +32395 3859 3987 3749 6638 +32396 1261 1502 1379 7008 +32397 1389 1247 1358 6563 +32398 3844 3875 3733 6564 +32399 226 227 3625 6308 +32400 3448 3529 3411 7138 +32401 4595 4972 549 7039 +32402 5515 29 5580 7207 +32403 1252 6746 1415 6824 +32404 4253 4065 4203 6706 +32405 4834 4906 4835 6985 +32406 2575 1509 2381 7107 +32407 4990 4638 602 5920 +32408 2638 3329 3330 6336 +32409 1915 1769 1690 6144 +32410 3120 2769 2771 7110 +32411 4310 4144 4373 6355 +32412 3759 3700 3878 6648 +32413 1214 1392 1273 6649 +32414 5679 5729 575 6974 +32415 552 4517 553 6739 +32416 1224 6860 1334 7040 +32417 3520 5993 3517 7144 +32418 7049 7064 5888 7195 +32419 5021 5169 5023 6612 +32420 4475 4097 4370 6681 +32421 2315 2325 2297 7063 +32422 4149 4362 4011 7141 +32423 1780 2146 1832 7115 +32424 4174 6547 4314 6952 +32425 1726 2027 1883 6556 +32426 3956 3832 3744 7083 +32427 2539 2537 2538 6728 +32428 191 1891 1455 7024 +32429 1892 3941 281 7025 +32430 6838 6952 5878 7118 +32431 2544 2545 2546 6839 +32432 2400 173 2470 1377 +32433 2213 2212 2195 6572 +32434 2561 3942 2559 6749 +32435 1576 1573 230 6365 +32436 1816 1880 6187 7105 +32437 150 1378 1436 2706 +32438 4364 4027 4466 7072 +32439 2251 2257 340 6506 +32440 3199 3504 3198 6500 +32441 3401 3402 3403 6180 +32442 1460 1366 165 6824 +32443 5519 6772 5453 6773 +32444 5611 5677 6769 6770 +32445 3267 3264 3263 6555 +32446 2511 2681 2683 6761 +32447 2761 2760 3571 6786 +32448 2441 2947 2953 6816 +32449 2251 2246 2245 6452 +32450 299 1915 298 6193 +32451 5542 5462 5579 6983 +32452 5620 5737 5700 6984 +32453 3762 3711 3854 6459 +32454 1225 1368 1276 6458 +32455 15 357 2343 1422 +32456 1346 1437 3636 6809 +32457 528 4486 4309 7018 +32458 3806 3970 3669 6875 +32459 1484 1183 1320 6878 +32460 3062 2943 3061 6789 +32461 1346 1480 1259 6809 +32462 2561 6749 2810 7013 +32463 3224 3220 3115 7142 +32464 1306 1462 193 1885 +32465 1884 3792 283 3948 +32466 3557 2870 3302 7077 +32467 4559 6967 555 7150 +32468 3696 3803 3894 7113 +32469 1317 1408 1210 7114 +32470 25 633 6264 6751 +32471 1312 1933 189 1495 +32472 1934 279 3798 3981 +32473 1315 1181 6892 6955 +32474 3177 3186 3269 6591 +32475 3227 3137 3538 7182 +32476 1367 1312 1264 6467 +32477 3348 3392 3397 6281 +32478 5019 538 539 6798 +32479 1445 6782 1332 7199 +32480 3931 6785 3818 7200 +32481 589 5379 5398 6295 +32482 3752 3848 3970 6875 +32483 1362 1484 1266 6878 +32484 2469 2854 2853 6639 +32485 367 3301 368 5939 +32486 3440 6239 3526 6910 +32487 5523 6620 5589 6913 +32488 3901 3837 3741 6666 +32489 2065 1773 1961 7178 +32490 3799 3813 6731 6989 +32491 1223 1290 1371 6499 +32492 5491 458 5582 7003 +32493 5649 498 5740 7005 +32494 3951 394 2924 2586 +32495 4425 4197 4030 6377 +32496 2929 2528 2691 6514 +32497 1358 6563 1247 6644 +32498 3733 3844 6564 6645 +32499 3988 3859 3698 6830 +32500 5675 5597 6561 6596 +32501 5439 6562 5517 6595 +32502 3801 3667 3976 6893 +32503 1315 1181 1490 6892 +32504 3516 3352 3351 6567 +32505 5693 6610 5668 6819 +32506 5535 6611 5510 6818 +32507 18 325 1427 1438 +32508 1295 6712 1447 7137 +32509 2249 308 2247 6690 +32510 2584 2582 2583 6824 +32511 5682 6782 5598 6972 +32512 5524 6785 5440 6971 +32513 3835 3778 396 2585 +32514 2266 2273 2267 6439 +32515 3444 3051 3500 6082 +32516 3701 3753 3873 6807 +32517 389 2502 3763 2481 +32518 2557 3123 2555 6265 +32519 234 1567 1561 6409 +32520 536 4504 4523 6123 +32521 4294 6949 4032 7146 +32522 4108 4446 4205 7170 +32523 4153 4278 492 6249 +32524 6914 7042 5857 7106 +32525 4377 6312 4029 7187 +32526 4520 4505 480 6307 +32527 2481 3763 3864 6887 +32528 352 2219 351 6318 +32529 358 2485 359 6793 +32530 1376 1300 1206 6728 +32531 1274 1367 1198 6629 +32532 237 1550 238 6545 +32533 3433 3393 3395 6554 +32534 4969 5239 591 6814 +32535 4712 4711 4713 6982 +32536 3456 3455 2621 6466 +32537 4642 5879 536 6999 +32538 1231 1514 6881 6994 +32539 1273 1188 1313 6732 +32540 3759 3674 3799 6731 +32541 2589 3132 2486 6808 +32542 544 5322 4816 6832 +32543 1541 1540 1546 6415 +32544 6278 6825 501 6917 +32545 5526 5503 5458 6529 +32546 5661 5616 5684 6528 +32547 5613 6851 5656 6955 +32548 6453 7089 5768 7090 +32549 3416 6227 3414 7102 +32550 4184 4359 4103 6501 +32551 1327 6732 1313 6994 +32552 3819 6534 3671 6757 +32553 1185 1333 6533 6758 +32554 1685 1874 2113 6950 +32555 2960 2999 2410 6695 +32556 1531 1323 1530 6925 +32557 1474 6632 1334 6860 +32558 613 5538 612 7190 +32559 2268 2263 302 7081 +32560 2175 2026 1659 6833 +32561 1399 176 1293 6848 +32562 3962 6783 3761 6784 +32563 1476 6780 1275 6781 +32564 6548 6803 5438 6939 +32565 5596 6549 6804 6940 +32566 5496 5443 6676 6818 +32567 5654 5601 6675 6819 +32568 6519 6793 5767 7165 +32569 4572 4571 4573 6188 +32570 4746 4722 4725 6623 +32571 1701 2046 1950 6778 +32572 3884 3752 6876 7054 +32573 1540 1544 1546 6415 +32574 2711 157 1329 1393 +32575 150 1378 2706 2475 +32576 6492 6898 5820 6998 +32577 4000 6895 3717 6989 +32578 5473 5582 6772 7085 +32579 1815 286 3756 3814 +32580 196 1814 1328 1270 +32581 2397 7041 2396 7108 +32582 3844 3871 6564 7031 +32583 3183 2739 3540 6662 +32584 1243 1464 1286 7012 +32585 3729 3950 3772 7010 +32586 29 6580 531 6720 +32587 3355 3215 3213 6300 +32588 3213 3351 3355 6300 +32589 5491 457 458 7003 +32590 498 5649 497 7005 +32591 469 468 4185 6256 +32592 4109 4227 4442 7131 +32593 2887 2556 2558 6378 +32594 5768 6797 3601 7090 +32595 579 5681 578 6810 +32596 6048 6793 6519 7165 +32597 2479 6998 2394 7108 +32598 4102 4245 4358 7157 +32599 3194 2845 2805 6279 +32600 1203 1283 1386 6701 +32601 527 5381 528 7066 +32602 3577 3412 3576 7138 +32603 2288 2287 2290 7034 +32604 1217 1309 1507 6585 +32605 3336 3334 3517 7144 +32606 609 4734 4760 7098 +32607 231 3616 230 6928 +32608 4294 6107 6949 7146 +32609 1316 2828 163 1379 +32610 2896 2895 2809 7175 +32611 4544 4514 471 6112 +32612 2274 2272 2269 6846 +32613 2981 3000 3002 7160 +32614 2538 3203 1407 6727 +32615 5456 5493 6488 6760 +32616 5651 6487 5614 6759 +32617 5067 4686 4685 6700 +32618 3832 3956 3705 7083 +32619 3471 3322 3332 6053 +32620 223 3641 222 6078 +32621 4943 5072 5146 7043 +32622 4322 4090 4140 6524 +32623 1363 147 2381 2500 +32624 2377 3849 388 2502 +32625 3967 6686 3805 6924 +32626 3860 3684 3750 6820 +32627 5527 615 5590 6828 +32628 566 5748 5685 6827 +32629 4153 4035 4328 5959 +32630 1289 6571 1196 6743 +32631 31 635 5408 7165 +32632 4939 5103 4938 6937 +32633 5507 5438 6803 6939 +32634 5596 6804 5665 6940 +32635 4213 4059 4137 7015 +32636 3760 3853 3684 6636 +32637 1233 1473 1424 6540 +32638 3959 3910 3719 6538 +32639 1397 1409 1239 6984 +32640 3895 3725 3883 6983 +32641 5685 566 6827 6878 +32642 5527 615 6828 6875 +32643 4094 4357 4249 6858 +32644 1211 1338 1268 6655 +32645 3824 3754 3697 6654 +32646 1385 6563 1358 6956 +32647 191 1455 1350 7024 +32648 281 3941 3836 7025 +32649 3852 6749 2561 7013 +32650 5685 5620 6878 6879 +32651 5527 5462 6875 6877 +32652 525 5399 5380 6285 +32653 3698 3822 3985 6830 +32654 1371 1293 1223 6499 +32655 1504 1257 1422 6519 +32656 3999 3834 288 1801 +32657 1513 1348 198 1799 +32658 2101 1680 1816 7105 +32659 1694 1845 1893 6677 +32660 4726 4727 4779 7181 +32661 2087 1662 1938 7057 +32662 5676 6602 5614 6901 +32663 452 4152 4275 6301 +32664 3927 3736 3810 7112 +32665 1324 1441 1250 7111 +32666 1852 1977 1706 6406 +32667 4104 4152 4379 6356 +32668 2408 2807 2406 6054 +32669 1883 1947 1726 6556 +32670 3789 3887 3965 6633 +32671 1479 1303 1401 6634 +32672 434 3652 435 6302 +32673 625 4867 4573 6240 +32674 2107 1807 1685 6691 +32675 1812 1718 2016 6326 +32676 2919 3252 3095 6696 +32677 1399 8 418 1421 +32678 4186 4091 4384 6211 +32679 1904 1856 1686 6946 +32680 4531 4498 4556 6430 +32681 1557 1556 1560 6667 +32682 4376 6838 4174 6952 +32683 1295 7060 6712 7137 +32684 3082 3083 3032 7168 +32685 4882 5231 5251 7155 +32686 4320 510 4461 6153 +32687 5605 5642 5730 6841 +32688 5572 5447 5484 6840 +32689 2500 148 2474 7040 +32690 4463 4287 4079 7046 +32691 1728 2173 2023 7156 +32692 1310 6476 1240 6722 +32693 5731 5609 6954 7114 +32694 5451 6953 5573 7113 +32695 1339 1490 1181 6892 +32696 3976 3667 3825 6893 +32697 490 5702 6694 6996 +32698 5647 5621 5708 6583 +32699 5550 5489 5463 6584 +32700 1574 1581 1575 6327 +32701 6487 6759 5651 6865 +32702 5493 6488 6760 6866 +32703 2281 2286 2284 6935 +32704 5145 5305 4966 6557 +32705 6820 6821 451 7094 +32706 577 6543 6701 7014 +32707 3001 3000 3072 7152 +32708 4637 4639 4638 6617 +32709 2903 3092 3173 6969 +32710 4294 4242 4032 6949 +32711 4067 7028 6403 7210 +32712 2451 2450 2456 6933 +32713 302 2042 301 6350 +32714 1482 1267 6543 7162 +32715 5335 5273 5333 6711 +32716 2812 2815 3235 6926 +32717 4302 6669 6420 7203 +32718 2617 387 2572 3780 +32719 3453 3305 3495 6609 +32720 1437 9 213 1426 +32721 3331 3329 3340 6573 +32722 4899 4898 4897 6517 +32723 5704 5623 5716 6766 +32724 5701 500 501 7070 +32725 1540 1599 1545 6653 +32726 4019 4265 4361 6558 +32727 426 3611 427 6963 +32728 1590 1589 1593 6423 +32729 1373 6758 6637 6897 +32730 3667 6645 3825 6893 +32731 1339 1181 6644 6892 +32732 1723 1925 1924 6796 +32733 1997 1653 2073 6975 +32734 3621 443 442 6020 +32735 6898 6998 6492 7108 +32736 2719 2973 167 1326 +32737 4186 6211 4384 7087 +32738 5706 5675 5597 6561 +32739 5517 5439 5548 6562 +32740 241 1542 1628 6653 +32741 1989 1717 1801 6833 +32742 217 216 1614 6370 +32743 1273 1200 1390 6649 +32744 3876 3759 3686 6648 +32745 4129 4473 4474 7095 +32746 2898 2897 3240 6560 +32747 3194 2426 3168 6977 +32748 342 341 2367 6762 +32749 4258 4056 4169 6315 +32750 4253 4135 4065 6429 +32751 2339 386 2342 7044 +32752 1520 1246 6788 6996 +32753 1368 1186 6694 6996 +32754 3474 2856 2765 6551 +32755 4005 3861 3766 7003 +32756 1519 1375 1280 7005 +32757 4065 6706 6429 7184 +32758 1506 1321 1426 7017 +32759 624 5571 623 6666 +32760 5728 5640 6802 7012 +32761 5482 6801 5570 7010 +32762 3380 3524 3382 6747 +32763 1264 1374 1198 6787 +32764 2427 2426 2428 6388 +32765 531 4562 4538 6938 +32766 2231 2229 2226 6822 +32767 1860 1737 1880 7105 +32768 1603 1602 1609 6463 +32769 4459 4205 4054 7170 +32770 4041 4308 4166 6344 +32771 1765 2094 2055 7033 +32772 3297 3296 3295 6382 +32773 391 3864 3922 2914 +32774 5452 5488 5477 6873 +32775 5646 5635 5610 6874 +32776 5961 7196 6742 7197 +32777 4174 4376 4240 6838 +32778 3995 388 2377 6886 +32779 2561 407 2559 3942 +32780 26 6503 530 6862 +32781 1362 1239 6984 7060 +32782 1470 1310 1218 6416 +32783 1562 1564 1566 6442 +32784 1277 2474 148 7040 +32785 510 5403 511 6296 +32786 420 419 6797 6927 +32787 2197 3913 321 2198 +32788 1273 1392 1200 6649 +32789 3878 3686 3759 6648 +32790 1843 2039 1759 6658 +32791 5812 6995 6450 7100 +32792 2703 3211 2701 6831 +32793 3732 6821 4006 7094 +32794 2460 2488 2510 6680 +32795 2639 3553 2750 6767 +32796 4353 4280 4083 6605 +32797 3945 3784 3732 6584 +32798 1298 1246 1459 6583 +32799 1997 1767 2054 6975 +32800 2735 2974 2788 6678 +32801 1529 245 3808 1620 +32802 3260 3489 6508 6745 +32803 4382 7146 4235 7183 +32804 1425 1451 1341 6901 +32805 2536 2806 2490 6469 +32806 3822 3698 3859 6830 +32807 2908 2881 2825 6486 +32808 2871 399 3893 2685 +32809 4864 4865 581 6523 +32810 1358 1385 1220 6563 +32811 3844 3871 3706 6564 +32812 2505 2381 2500 7040 +32813 2860 3317 2858 6744 +32814 5181 5178 5262 6813 +32815 4431 4268 4165 7210 +32816 3795 3673 3796 6862 +32817 4312 4481 4072 6559 +32818 3779 3885 417 7191 +32819 4535 4562 530 6938 +32820 5767 6519 6416 6902 +32821 4547 4514 4500 6546 +32822 3480 3416 3459 6965 +32823 3424 3310 3313 6986 +32824 1530 1323 1431 6925 +32825 3763 3714 3864 6887 +32826 176 2579 1508 6848 +32827 1594 1591 224 6664 +32828 4061 4316 4210 6310 +32829 3670 3861 6529 7003 +32830 1375 6528 1184 7005 +32831 4029 4377 4196 6312 +32832 219 3623 218 6261 +32833 2907 3169 3552 6713 +32834 5984 6688 7037 7045 +32835 2477 2602 2607 6481 +32836 4908 4906 4870 7147 +32837 5614 5676 5637 6602 +32838 5479 5456 5518 6603 +32839 5505 5545 6978 7009 +32840 5703 6979 5663 7011 +32841 1319 1249 1413 7070 +32842 5531 617 5518 6735 +32843 2080 1744 1876 6961 +32844 1530 1531 183 1431 +32845 575 5729 574 6974 +32846 2541 3460 3461 6630 +32847 3908 24 447 3886 +32848 3218 155 1292 2707 +32849 5435 5410 633 7038 +32850 5554 6593 5490 7200 +32851 5712 6594 5648 7199 +32852 597 4749 4750 6754 +32853 3870 3811 3728 6863 +32854 1678 2061 1942 6685 +32855 1940 1679 2062 6687 +32856 4242 4076 4318 6949 +32857 3709 3779 3994 7191 +32858 3786 3862 401 3280 +32859 2206 2207 2208 6805 +32860 3636 1437 213 7017 +32861 4255 4079 4314 6547 +32862 1632 2052 2149 6880 +32863 3434 3393 3433 6554 +32864 303 304 2098 6238 +32865 3975 6803 3813 6922 +32866 1489 6804 1327 6923 +32867 4132 4440 4266 6535 +32868 458 6686 459 7085 +32869 1295 1410 6712 7060 +32870 492 4378 4153 6249 +32871 5513 5580 609 6721 +32872 3683 3837 6666 7193 +32873 3312 3313 3310 6986 +32874 3258 3257 3467 6477 +32875 5137 5351 5183 6921 +32876 3864 391 2482 2914 +32877 5403 510 5379 6296 +32878 4379 4152 452 6301 +32879 1354 6596 1288 6874 +32880 3774 3840 6595 6873 +32881 1528 1529 246 3912 +32882 4727 4726 4728 7181 +32883 612 5538 611 7190 +32884 6686 6924 459 7085 +32885 2237 312 2235 6625 +32886 5731 5650 5609 7114 +32887 5492 5451 5573 7113 +32888 3977 3703 3843 7082 +32889 229 230 3651 6365 +32890 4151 501 4276 6322 +32891 3067 3068 2636 6590 +32892 5166 5114 5345 6400 +32893 632 5407 5435 7038 +32894 1240 1356 1385 6766 +32895 3871 3726 3842 6765 +32896 3478 3480 3481 7001 +32897 3966 3903 3794 6264 +32898 4476 4019 4280 6964 +32899 1412 6850 1239 7137 +32900 5520 6638 622 7058 +32901 3611 6672 3606 7086 +32902 2871 3893 400 2872 +32903 5692 5609 5650 7114 +32904 5492 5534 5451 7113 +32905 2706 1436 151 3035 +32906 2502 3849 389 3763 +32907 232 6993 233 7080 +32908 4884 4883 4882 6970 +32909 2449 3969 403 3865 +32910 1786 318 1955 6505 +32911 3893 3786 400 2872 +32912 3921 3863 2432 7041 +32913 1831 1974 2059 6000 +32914 1336 1252 1499 6746 +32915 4017 4356 4365 6663 +32916 3529 6748 3530 7138 +32917 521 4301 4156 7056 +32918 3629 236 237 6362 +32919 5643 5686 577 6701 +32920 409 2608 2712 3873 +32921 446 2492 445 6905 +32922 1714 1892 2075 7025 +32923 1891 2074 1715 7024 +32924 2814 2431 2819 7045 +32925 516 4204 515 6661 +32926 1474 1334 1224 6860 +32927 5715 6881 5653 6994 +32928 226 1588 227 6308 +32929 1197 1351 1415 6974 +32930 3264 3266 3265 6795 +32931 3986 3688 3884 7054 +32932 381 2310 2338 6321 +32933 1305 1226 1361 6743 +32934 3413 3495 3414 7102 +32935 1625 1528 1628 6575 +32936 4928 4931 4858 6495 +32937 2655 2653 2654 6037 +32938 3568 2873 3485 6910 +32939 4999 5001 4998 6613 +32940 343 342 6762 7202 +32941 5664 7070 6769 7071 +32942 4554 546 4515 6650 +32943 1612 1617 1613 6419 +32944 4076 4294 4272 6949 +32945 2195 2194 2205 6287 +32946 3429 3427 3487 6224 +32947 2552 2547 2549 6433 +32948 2196 2194 2195 6287 +32949 231 1570 232 7126 +32950 2204 2205 2202 6572 +32951 3334 3333 3452 7144 +32952 3665 3927 3810 6530 +32953 1179 1441 1324 6531 +32954 243 3843 1619 1623 +32955 4425 4101 4197 6588 +32956 3914 3973 3785 6818 +32957 1428 1487 1299 6819 +32958 3589 3619 3622 6592 +32959 1373 1263 1336 6897 +32960 2584 2991 165 6824 +32961 417 2577 3994 7191 +32962 1457 1205 1519 6791 +32963 4005 3943 3691 6790 +32964 225 224 1591 6871 +32965 2209 2210 2208 6805 +32966 4768 4982 4619 7189 +32967 5638 5614 5680 6901 +32968 4151 4087 4325 6490 +32969 5544 5550 5463 7094 +32970 2292 2210 3809 6805 +32971 3707 7025 6636 7208 +32972 2232 2234 2236 6443 +32973 2969 3155 2970 6621 +32974 3713 3801 3804 6907 +32975 5168 5009 5199 6717 +32976 2504 6898 2394 6998 +32977 2479 2394 2396 7108 +32978 2537 2540 2538 6727 +32979 5126 5352 5128 6753 +32980 3491 3365 3366 6448 +32981 1903 1884 284 3948 +32982 1902 194 1462 1885 +32983 499 498 6684 7071 +32984 3974 2913 3922 7075 +32985 1399 2508 176 6848 +32986 5495 5557 6895 6989 +32987 5459 5494 5524 6785 +32988 5652 5682 5617 6782 +32989 4727 4730 4778 7181 +32990 317 2218 318 5992 +32991 3622 3642 3589 6592 +32992 4202 4179 4055 6599 +32993 5717 6561 5597 6892 +32994 5439 5559 6562 6893 +32995 2627 2628 2629 6656 +32996 614 6876 6875 7054 +32997 1911 1644 2100 6817 +32998 2905 3368 3512 6542 +32999 5366 5305 5145 6557 +33000 5269 5246 4656 6626 +33001 5733 5745 5604 6956 +33002 29 5515 531 6580 +33003 5943 7055 6182 7214 +33004 1376 1261 1483 7008 +33005 625 6641 5521 7193 +33006 4234 4044 4178 6410 +33007 2661 2449 2448 7174 +33008 459 6924 5506 7085 +33009 2811 2746 3171 6608 +33010 2213 1322 206 2211 +33011 3955 3973 3722 6866 +33012 1236 1469 1487 6865 +33013 5446 5575 5587 7031 +33014 3875 3706 3787 6564 +33015 1389 1220 1301 6563 +33016 5608 5726 5640 6931 +33017 5450 5568 5482 6932 +33018 1361 1442 1240 6722 +33019 548 4524 549 6160 +33020 3416 3414 3494 7102 +33021 5480 5531 5456 6900 +33022 540 5243 4766 6515 +33023 4087 4283 4325 6490 +33024 3023 2510 2947 6680 +33025 270 1557 269 6667 +33026 3959 3749 3987 6638 +33027 1501 1473 1263 6637 +33028 1201 1332 1424 7199 +33029 3687 3818 3910 7200 +33030 2299 2316 2353 6856 +33031 5114 5166 5363 6400 +33032 4907 5068 4835 6849 +33033 2584 166 2973 1456 +33034 1460 165 2991 6824 +33035 4619 4598 4784 6763 +33036 1502 6491 1379 7008 +33037 1508 1223 1293 6848 +33038 3529 3530 3576 7138 +33039 3152 3317 3156 6744 +33040 3410 3311 3424 7158 +33041 3218 2990 3217 6869 +33042 2924 2586 2615 7023 +33043 2924 2614 2964 7073 +33044 319 1955 318 6505 +33045 2280 2286 2278 6935 +33046 4018 4343 4195 7099 +33047 4446 4054 4205 7170 +33048 1981 1682 1840 6525 +33049 5610 6596 5675 7133 +33050 5452 6595 5517 7134 +33051 3028 2996 2994 6431 +33052 225 1591 1586 6871 +33053 4135 519 4430 6579 +33054 1357 1322 206 2293 +33055 195 1902 1463 1328 +33056 2008 1655 6375 6934 +33057 626 627 5485 6913 +33058 1866 1893 1683 6352 +33059 2919 2918 2776 6472 +33060 5599 5680 5690 6487 +33061 5532 5441 5522 6488 +33062 27 490 5702 6694 +33063 1482 1359 1203 6543 +33064 5505 5444 5551 7009 +33065 5602 5709 5663 7011 +33066 632 5578 5501 6459 +33067 5736 5659 558 6458 +33068 5575 5509 5465 6765 +33069 5623 5733 5667 6766 +33070 5601 6819 5668 6865 +33071 5510 5443 6818 6866 +33072 1408 6619 1238 6841 +33073 3894 6620 3724 6840 +33074 3031 2509 2495 6764 +33075 5579 5487 5542 6983 +33076 5737 5645 5700 6984 +33077 4015 4401 4289 6230 +33078 3979 3890 3735 6772 +33079 1493 1404 1249 6769 +33080 3759 3700 6648 6731 +33081 1214 6649 1273 6732 +33082 1692 1880 2044 7091 +33083 5604 5745 5656 6956 +33084 2540 2709 3203 6727 +33085 1816 1880 1692 6187 +33086 5392 5372 5416 6478 +33087 5454 5520 5556 6538 +33088 5612 5678 5714 6540 +33089 3326 3495 3413 6228 +33090 3788 3692 3891 6604 +33091 3529 3296 3530 6748 +33092 4613 5147 5271 6332 +33093 5646 5709 5744 6874 +33094 5488 5551 5586 6873 +33095 3366 3364 3472 6483 +33096 598 4750 5244 6754 +33097 623 5520 622 7058 +33098 173 2470 1377 1278 +33099 2488 383 3025 6981 +33100 5009 5315 5199 6717 +33101 1379 1212 1316 6491 +33102 5498 5446 5587 7031 +33103 4606 4891 5008 6646 +33104 2451 2500 2474 7040 +33105 2720 2605 2604 7162 +33106 5438 5534 5476 6548 +33107 5692 5634 5596 6549 +33108 1200 1392 1443 6649 +33109 3878 3929 3686 6648 +33110 2293 2213 2204 6572 +33111 3821 6492 3764 7108 +33112 4456 4066 4215 6578 +33113 2549 2548 2722 6660 +33114 328 2355 2328 6777 +33115 5547 6704 5462 6877 +33116 5705 6705 5620 6879 +33117 5589 5474 5553 6840 +33118 5632 5711 5747 6841 +33119 4101 4195 6588 7099 +33120 1354 1434 1194 7133 +33121 3840 3920 3680 7134 +33122 5928 6952 6547 7118 +33123 3841 3989 3742 7044 +33124 1612 1613 1611 7104 +33125 2560 2810 2561 6749 +33126 5265 5154 5254 6427 +33127 2975 3852 2561 7013 +33128 4122 4229 4488 6544 +33129 1185 1501 1373 6758 +33130 3671 3987 3859 6757 +33131 4194 4052 4138 6385 +33132 5545 7009 5461 7010 +33133 5703 7011 5619 7012 +33134 3466 3554 3464 6870 +33135 1906 2135 1752 6836 +33136 233 234 3654 6943 +33137 3897 3715 3770 7041 +33138 4123 4283 4200 7188 +33139 4047 4453 4353 6605 +33140 285 1815 1903 3814 +33141 2905 3575 3368 6542 +33142 2178 1772 1962 6918 +33143 2616 3499 3498 6117 +33144 4048 4284 4376 6952 +33145 2769 3120 2397 7041 +33146 2613 2611 2612 7148 +33147 2553 2932 2819 7068 +33148 1489 1327 1505 6923 +33149 3991 3975 3813 6922 +33150 5569 6959 5497 7134 +33151 5727 6960 5655 7133 +33152 2702 2700 2701 6831 +33153 3964 3839 3682 6720 +33154 351 2224 350 6550 +33155 4000 3954 3717 6895 +33156 3311 3423 2622 7158 +33157 5460 5510 5565 6611 +33158 5618 5668 5723 6610 +33159 3672 3854 3823 7094 +33160 2978 2982 2848 6504 +33161 6097 6952 6838 7118 +33162 5538 6852 5481 7190 +33163 4953 5155 4697 6402 +33164 3531 3190 3192 6455 +33165 3991 3813 3717 6989 +33166 6547 6952 6097 7118 +33167 3914 3938 3722 6676 +33168 1452 1236 1428 6675 +33169 1698 2011 1785 6527 +33170 4213 4435 4011 7015 +33171 2994 2993 3518 6823 +33172 3843 1623 3783 7082 +33173 3548 3456 2621 6466 +33174 3722 3973 3914 6818 +33175 1236 1487 1428 6819 +33176 240 1599 241 6653 +33177 4506 4534 6739 7164 +33178 4594 4595 550 7039 +33179 1386 1283 1420 6701 +33180 3186 3177 3178 6591 +33181 2776 2779 2919 6472 +33182 5702 5708 5621 6996 +33183 269 1557 1560 6667 +33184 4438 4135 4430 6225 +33185 2129 1765 1931 7033 +33186 2024 1953 1785 6449 +33187 230 229 1576 6365 +33188 1314 1317 1210 7114 +33189 3803 3696 3800 7113 +33190 4266 4360 4132 6944 +33191 3382 3372 3374 6747 +33192 5717 5644 6561 6851 +33193 5559 5486 6562 6853 +33194 2500 2451 2505 7040 +33195 1434 6960 1234 7133 +33196 3720 3920 6959 7134 +33197 2697 2696 2699 7196 +33198 3715 3897 3933 6723 +33199 4765 4830 4602 7149 +33200 5344 5237 5343 7214 +33201 4999 4998 5000 6613 +33202 3927 3758 3828 6811 +33203 1342 1441 1272 6812 +33204 2872 3786 401 3280 +33205 5699 6632 562 7137 +33206 3265 3266 3442 6795 +33207 614 6875 5542 7054 +33208 1585 260 1587 6568 +33209 553 4534 554 6739 +33210 4869 5126 5127 6837 +33211 1418 1290 1475 6729 +33212 3904 3775 3961 6730 +33213 621 5567 620 6757 +33214 5236 5237 5235 7055 +33215 2778 3164 2777 6274 +33216 2499 2470 174 1364 +33217 563 6712 7060 7137 +33218 3840 3680 3774 6595 +33219 1288 1354 1194 6596 +33220 4347 4423 4177 6622 +33221 4154 4277 4088 6615 +33222 5767 6416 6519 7165 +33223 5979 7048 6798 7161 +33224 1232 1466 1370 6498 +33225 5467 5555 5552 6989 +33226 1221 7024 6629 7209 +33227 2529 2395 2394 6898 +33228 377 2365 2320 6679 +33229 217 3608 216 7062 +33230 6789 7163 5864 7198 +33231 1231 1514 1468 6881 +33232 4141 4484 4368 6494 +33233 2507 417 3885 7191 +33234 4199 4369 4049 6607 +33235 2215 2214 2219 7053 +33236 5544 6751 450 7094 +33237 1535 1541 274 6756 +33238 4130 4218 4331 6669 +33239 3440 3476 3526 6239 +33240 2403 2900 3118 6914 +33241 549 4550 550 7039 +33242 3587 3606 3611 6672 +33243 241 1628 1528 6575 +33244 5099 4937 5040 6651 +33245 4784 6885 4767 7189 +33246 2653 2730 2656 7021 +33247 2448 404 2447 3802 +33248 4006 3846 3684 6821 +33249 1198 1520 1360 6788 +33250 2425 2426 2427 6388 +33251 223 1594 224 6664 +33252 1400 146 2618 1294 +33253 3886 387 2617 3780 +33254 3365 3364 3366 6448 +33255 425 2784 424 6445 +33256 3223 3221 3112 6896 +33257 2035 2057 1695 6733 +33258 2292 320 2206 6805 +33259 5588 628 629 6723 +33260 5455 5587 5478 6907 +33261 317 2022 1896 7213 +33262 536 6999 5879 7076 +33263 4549 4501 4520 6520 +33264 5708 491 6788 6996 +33265 1434 1342 1234 6960 +33266 3920 3828 3720 6959 +33267 4898 4961 4807 7163 +33268 4313 6624 4071 7132 +33269 450 5544 25 6751 +33270 4661 5028 4659 6522 +33271 1777 1964 1653 6906 +33272 2728 2922 2913 7075 +33273 4280 4143 4476 6964 +33274 5668 6819 6610 6865 +33275 5510 6818 6611 6866 +33276 2720 2604 169 1387 +33277 4907 4906 4908 6849 +33278 354 6889 2344 7169 +33279 5541 5481 5455 6907 +33280 4495 4512 4513 6682 +33281 5696 5645 5606 6850 +33282 5538 5487 5448 6852 +33283 4326 4085 4152 6432 +33284 4329 4182 4460 6991 +33285 2479 2396 414 7108 +33286 572 5725 571 6758 +33287 4559 4499 6967 7164 +33288 1516 6541 1391 6974 +33289 1971 1646 2164 6740 +33290 5713 5710 5625 6994 +33291 2949 2509 3031 6764 +33292 3526 2939 2873 6910 +33293 1840 1750 2132 6537 +33294 3993 3912 3808 6575 +33295 3442 3266 3370 6795 +33296 1335 1189 1475 6729 +33297 3675 3961 3821 6730 +33298 3368 2593 3513 7173 +33299 5693 5668 5615 6819 +33300 5535 5510 5457 6818 +33301 1852 1706 2088 6406 +33302 5185 5235 5137 6845 +33303 3955 3722 3851 6866 +33304 1469 1236 1365 6865 +33305 2254 2256 2265 6581 +33306 1476 1330 1275 6780 +33307 3962 3816 3761 6783 +33308 5483 6645 5564 6893 +33309 5722 5641 6644 6892 +33310 351 350 2362 6550 +33311 1893 1866 1755 6934 +33312 1505 1327 1231 6994 +33313 4212 4475 6681 7072 +33314 5244 5150 4690 6670 +33315 2566 2747 2564 6861 +33316 2523 2529 2504 6898 +33317 2892 2893 3523 6742 +33318 1246 6583 1298 6788 +33319 3599 3627 3628 6313 +33320 2861 7117 2863 7160 +33321 1446 1306 193 2084 +33322 3932 3792 283 2085 +33323 311 2235 312 6625 +33324 3844 6564 6645 7031 +33325 2479 3764 6998 7108 +33326 294 2289 295 6718 +33327 4817 5323 4751 7067 +33328 1784 249 1954 6485 +33329 3984 3690 3957 6876 +33330 1429 1355 1195 7205 +33331 3732 6584 3784 6821 +33332 5752 5633 5722 6644 +33333 5475 5564 5594 6645 +33334 1483 162 2831 7008 +33335 5495 453 454 6895 +33336 395 2586 3951 7023 +33337 3765 3892 3729 6801 +33338 1279 1406 1243 6802 +33339 1426 1624 213 7017 +33340 6563 6644 1358 6956 +33341 5513 6631 5541 6907 +33342 4934 5052 4748 6606 +33343 6492 6998 3764 7108 +33344 494 5653 493 6881 +33345 1685 2113 2028 6950 +33346 3721 3788 3911 6603 +33347 1235 1302 1425 6602 +33348 1445 1244 1332 6782 +33349 3931 3730 3818 6785 +33350 1190 1295 1447 7137 +33351 1310 1240 1442 6722 +33352 493 5715 492 6881 +33353 3250 3133 3135 7019 +33354 1526 1527 1525 6324 +33355 4521 544 543 6832 +33356 1304 1208 1301 6997 +33357 3776 3710 3858 6497 +33358 4903 4838 4970 7123 +33359 4141 4395 4484 6494 +33360 2425 6388 2427 7000 +33361 1634 1920 1999 7192 +33362 1277 148 1363 7040 +33363 5119 4848 4846 6737 +33364 2455 2494 2453 6927 +33365 4995 4593 4591 6692 +33366 4531 4504 4532 6430 +33367 1251 1398 1471 6699 +33368 1911 1795 2081 6817 +33369 2274 300 2272 6846 +33370 1426 180 1624 1321 +33371 2377 2502 2501 6886 +33372 2959 2958 2962 6683 +33373 2088 1706 1921 7069 +33374 257 1600 256 6779 +33375 2575 146 1294 7107 +33376 5476 5507 5438 6803 +33377 5634 5665 5596 6804 +33378 3767 3988 3953 6826 +33379 3494 3414 3304 7102 +33380 4997 4971 4596 6511 +33381 276 20 1623 3783 +33382 2898 3240 3558 6560 +33383 3279 3566 3280 6317 +33384 3787 3790 3694 7061 +33385 4265 4441 4133 6558 +33386 2673 2674 2981 6872 +33387 4748 5104 4934 6606 +33388 3279 6317 3280 6947 +33389 2572 3995 2377 6886 +33390 3903 3762 3672 6751 +33391 1361 1289 1196 6743 +33392 1975 2008 1655 6375 +33393 4954 4653 4651 7022 +33394 3795 3796 3956 6503 +33395 2332 2367 2307 6762 +33396 3940 3983 3740 6548 +33397 1497 1254 1454 6549 +33398 1325 1242 1384 6741 +33399 3817 3915 3681 6570 +33400 1195 1331 1429 6569 +33401 2432 3120 412 3921 +33402 2433 3121 171 1435 +33403 5554 5490 5440 7200 +33404 5712 5648 5598 7199 +33405 2618 1294 146 7107 +33406 2087 1938 1769 7057 +33407 1473 1282 1424 6540 +33408 3910 3959 3768 6538 +33409 6829 6933 5774 7117 +33410 564 5645 5696 7060 +33411 414 3764 2479 7108 +33412 2012 1786 2025 7026 +33413 2385 2384 2948 6647 +33414 2151 1906 1752 6836 +33415 4524 4520 4501 6520 +33416 3719 6538 3910 6971 +33417 1424 1233 6540 6972 +33418 610 5541 5513 6631 +33419 5671 561 5699 6632 +33420 453 5557 452 6895 +33421 3231 3137 3227 7182 +33422 3683 3837 3901 6666 +33423 4838 6724 4970 7123 +33424 2396 3863 414 7108 +33425 300 2274 301 6846 +33426 233 1567 234 6993 +33427 1487 1272 1518 6610 +33428 3758 4004 3973 6611 +33429 1319 1481 1209 6684 +33430 3805 3967 3695 6686 +33431 451 6821 5550 7094 +33432 1368 1337 1186 6996 +33433 169 2720 1387 1267 +33434 414 3863 3764 7108 +33435 180 1621 1624 1321 +33436 2287 2194 2290 7034 +33437 4759 4762 611 7145 +33438 501 4151 4381 6322 +33439 2558 2760 3106 6786 +33440 2424 7048 439 7161 +33441 2468 2466 2467 6887 +33442 2763 6855 2422 7195 +33443 1185 1281 1333 6758 +33444 3767 3819 3671 6757 +33445 1197 1516 1391 6974 +33446 2287 2282 2289 6510 +33447 4055 4439 4338 6600 +33448 2482 2914 2468 6887 +33449 1525 1612 1618 6794 +33450 1982 2108 1636 7122 +33451 2291 2287 2289 6510 +33452 1344 152 3035 2923 +33453 1854 2043 257 6779 +33454 6860 6933 6088 7040 +33455 4570 4568 4627 6351 +33456 5385 519 518 6854 +33457 2612 3564 2907 6713 +33458 2569 2570 2429 7045 +33459 578 6701 6543 6810 +33460 2023 2010 1784 7156 +33461 1401 1519 1205 6791 +33462 3887 4005 3691 6790 +33463 2612 2616 3564 7148 +33464 1231 1313 1514 6994 +33465 2784 2406 424 6445 +33466 3872 3769 3906 6913 +33467 5710 5713 5634 6923 +33468 5555 5476 5552 6922 +33469 3035 1488 152 1344 +33470 3762 3915 3711 6459 +33471 1429 1225 1276 6458 +33472 1533 1532 1619 7082 +33473 2657 3005 3204 7052 +33474 3885 23 386 3907 +33475 2913 3974 2728 7075 +33476 5664 499 7070 7071 +33477 5499 5442 5570 6648 +33478 5657 5600 5728 6649 +33479 4155 6714 4291 7028 +33480 2660 396 3778 2715 +33481 5294 5278 5289 6888 +33482 4067 4167 4268 7210 +33483 1335 1278 1229 6587 +33484 1464 1324 1286 6531 +33485 3772 3950 3810 6530 +33486 3231 3138 3137 7182 +33487 614 615 6876 6976 +33488 5128 5352 5190 6753 +33489 2559 2562 2560 6749 +33490 5205 5171 5170 7197 +33491 241 1528 242 6575 +33492 308 2144 307 6690 +33493 1466 1191 1370 6689 +33494 614 615 6875 6876 +33495 1542 241 1599 6653 +33496 406 2975 3852 2561 +33497 1382 17 291 1297 +33498 1301 1414 1192 6825 +33499 5611 5752 5641 6770 +33500 5453 5594 5483 6773 +33501 2396 2397 2432 7041 +33502 342 2248 2246 7202 +33503 1588 1586 1583 7051 +33504 4635 4636 5105 7049 +33505 365 2347 2314 7007 +33506 635 5673 5741 6722 +33507 2324 2299 2351 6856 +33508 3406 3479 2697 7196 +33509 4841 4842 4919 6576 +33510 4596 4971 4924 6511 +33511 558 4536 4561 7089 +33512 2735 2788 2740 6678 +33513 2629 6656 2634 7042 +33514 3719 4002 3959 6539 +33515 1516 1473 1233 6541 +33516 2677 6536 2676 6920 +33517 3230 3046 2937 7020 +33518 1192 1413 1389 7070 +33519 4000 3717 3799 6989 +33520 1381 1434 1234 7133 +33521 3720 3867 3920 7134 +33522 2505 2451 2456 6933 +33523 3944 3962 3761 6784 +33524 1476 1275 1458 6781 +33525 5582 5506 5473 6772 +33526 1445 1332 1201 7199 +33527 3931 3818 3687 7200 +33528 2026 1731 1956 6806 +33529 1219 1503 1355 6453 +33530 148 2500 1363 7040 +33531 3907 2342 386 7044 +33532 1794 2080 1912 6980 +33533 4876 4870 4871 7147 +33534 4381 4107 4336 7079 +33535 2290 2194 2196 7034 +33536 5707 5614 5637 6759 +33537 5456 5479 5549 6760 +33538 3829 3805 3695 7085 +33539 3661 448 3832 7083 +33540 382 2817 3025 6981 +33541 20 276 3868 3783 +33542 3917 21 320 3926 +33543 1431 16 247 1440 +33544 1414 1245 1380 6825 +33545 581 5658 5687 6729 +33546 630 5500 5529 6730 +33547 5444 5473 5519 6774 +33548 5631 5677 5602 6771 +33549 2831 2830 3314 7008 +33550 5370 5383 5419 6628 +33551 3198 3504 3036 6500 +33552 1831 6000 2059 7074 +33553 3661 3633 448 7083 +33554 3173 2493 3196 6969 +33555 4147 4302 6420 7203 +33556 1212 1502 1373 6897 +33557 2699 6742 3523 7196 +33558 562 6632 561 6860 +33559 2981 2861 2863 7160 +33560 3753 3701 3845 6807 +33561 6154 7042 6914 7106 +33562 3888 3770 412 2726 +33563 171 1402 1284 2725 +33564 2778 2477 2607 6481 +33565 3463 3075 3067 6590 +33566 5340 5034 5047 6707 +33567 3828 3996 3720 6959 +33568 1234 1342 1510 6960 +33569 1649 2014 1865 6516 +33570 3732 4006 3823 7094 +33571 3050 3071 3072 7152 +33572 3495 6609 3304 7102 +33573 32 5577 631 6570 +33574 30 5735 582 6569 +33575 288 3999 1801 1936 +33576 198 1513 1799 1935 +33577 3350 3506 3451 6507 +33578 1520 1337 1246 6996 +33579 4606 4604 4891 6646 +33580 5506 459 460 6924 +33581 4338 4206 4055 6600 +33582 2003 1673 2192 7059 +33583 5739 5648 5615 6890 +33584 5581 5490 5457 6891 +33585 1267 1402 2720 7162 +33586 614 4565 4563 6976 +33587 5713 5665 5634 6804 +33588 5507 5476 5555 6803 +33589 357 2346 2343 6519 +33590 3678 3805 3899 6924 +33591 2399 2401 2400 7096 +33592 2083 1643 2057 6616 +33593 4006 3684 3860 6820 +33594 2332 343 342 6762 +33595 3870 3982 3694 7061 +33596 3960 3710 3776 6497 +33597 3251 3408 3299 6480 +33598 1828 2074 1891 7024 +33599 2075 1892 1829 7025 +33600 1494 1287 1184 6771 +33601 3980 3773 3670 6774 +33602 3606 222 3641 7086 +33603 1465 1349 154 2588 +33604 4911 4974 4761 6815 +33605 3170 3133 3426 7019 +33606 5715 5653 5625 6994 +33607 3850 3764 3709 6998 +33608 2098 304 1952 7006 +33609 5477 5517 5452 6595 +33610 5610 5635 5675 6596 +33611 5714 5674 5612 6540 +33612 5556 5516 5454 6538 +33613 3239 2896 3303 7065 +33614 3760 3707 6636 7208 +33615 2587 154 1349 2588 +33616 5124 5347 5302 6899 +33617 2851 3174 3104 7050 +33618 2332 2304 2361 7151 +33619 5499 5449 5576 6731 +33620 5734 5657 5607 6732 +33621 4372 4145 4309 6311 +33622 2152 2108 1832 7115 +33623 5415 5372 5385 6854 +33624 1465 153 1344 2923 +33625 1416 1497 1193 6940 +33626 3983 3679 3902 6939 +33627 243 3843 1623 3783 +33628 1349 1292 155 2587 +33629 2819 2820 2818 6688 +33630 5533 5491 5473 6774 +33631 5649 5631 5691 6771 +33632 1191 1486 1370 6689 +33633 2763 2422 2420 7195 +33634 261 1587 260 6568 +33635 1211 1397 1412 6850 +33636 3697 3883 3898 6852 +33637 1371 1195 1477 7205 +33638 4381 502 501 7079 +33639 6403 7028 6714 7201 +33640 2975 3946 3852 7013 +33641 3662 1346 98 3636 +33642 4725 4723 4724 6623 +33643 3863 7041 3715 7108 +33644 4682 4986 4852 6951 +33645 4839 4904 5063 7167 +33646 1362 1295 1239 7060 +33647 5060 5095 5086 7101 +33648 4678 4677 4676 7159 +33649 233 3612 232 7080 +33650 1502 1212 1379 6491 +33651 4347 4029 6622 7187 +33652 445 3664 446 6905 +33653 3816 3983 3940 6548 +33654 1330 1497 1454 6549 +33655 4402 4215 4066 6578 +33656 3848 3725 6983 7190 +33657 3953 3692 3767 6826 +33658 2686 2687 2684 7093 +33659 1387 2719 168 1326 +33660 2913 2922 2914 7075 +33661 366 2347 365 7007 +33662 418 3637 419 7090 +33663 5457 5496 5581 6818 +33664 5615 5654 5739 6819 +33665 1620 244 3843 1619 +33666 5470 5524 5556 6971 +33667 5682 5714 5628 6972 +33668 2123 1745 1909 6800 +33669 325 2341 2345 6902 +33670 1297 17 291 2294 +33671 3673 3795 3811 7119 +33672 2830 2828 2777 7008 +33673 1520 1198 1374 6787 +33674 3572 3268 3267 7139 +33675 5137 5135 5351 6921 +33676 3379 3467 3257 6477 +33677 2710 2990 2711 6869 +33678 1226 1419 1289 6743 +33679 1950 2189 1671 6992 +33680 1902 195 1814 1328 +33681 2913 2914 3922 7075 +33682 4498 4531 4532 6430 +33683 3202 3425 3308 6919 +33684 1329 1393 1232 6869 +33685 2457 2410 2412 6695 +33686 2125 1629 2136 7130 +33687 5706 5742 5626 6655 +33688 5468 5548 5584 6654 +33689 3714 3896 3771 7075 +33690 2223 2231 2221 6822 +33691 1286 1443 1243 7012 +33692 3929 3729 3772 7010 +33693 4514 4511 4500 6546 +33694 3002 2961 2861 7160 +33695 628 5588 5523 6620 +33696 5746 5681 579 6619 +33697 5452 5517 5468 7134 +33698 5626 5610 5675 7133 +33699 3812 409 2712 3873 +33700 2621 3455 3477 7097 +33701 168 2604 2719 1387 +33702 3770 3715 3921 7041 +33703 4339 4414 4026 7092 +33704 5728 5703 5640 7012 +33705 5482 5570 5545 7010 +33706 1417 1276 1186 6694 +33707 3232 3045 3047 6710 +33708 2575 1294 1509 7107 +33709 5194 5191 5189 6752 +33710 4641 537 538 6798 +33711 3520 3451 3506 6507 +33712 5710 5603 6583 6923 +33713 5445 6584 5552 6922 +33714 1295 1412 1239 7137 +33715 3596 3654 3617 6943 +33716 1359 1482 1267 6543 +33717 5830 6933 6860 7040 +33718 1286 7011 1461 7012 +33719 3947 3772 7009 7010 +33720 3256 3551 3224 7142 +33721 383 2364 382 6981 +33722 3899 3735 3880 6772 +33723 3668 3761 3906 6784 +33724 1182 1275 1420 6781 +33725 578 5681 5643 6701 +33726 5077 4745 4707 6936 +33727 3957 3752 3984 6876 +33728 484 483 4386 6574 +33729 2373 385 2339 6401 +33730 5286 5249 5343 7214 +33731 2157 1739 2073 7176 +33732 1200 1286 1461 7012 +33733 3686 3772 3947 7010 +33734 1723 1924 1851 6796 +33735 4625 4624 4623 7140 +33736 402 3280 3862 6947 +33737 1341 1199 1365 6759 +33738 3685 3851 3827 6760 +33739 1840 2132 1654 6537 +33740 2556 2880 2557 7016 +33741 5675 5635 5597 6596 +33742 5477 5439 5517 6595 +33743 2404 2402 2403 6914 +33744 2372 2341 211 1345 +33745 1303 1479 1248 6634 +33746 3789 3965 3734 6633 +33747 3799 3813 3700 6731 +33748 1327 1214 1313 6732 +33749 2380 2381 2379 7107 +33750 3751 3892 3930 6593 +33751 1265 1406 1444 6594 +33752 4626 5354 5133 6618 +33753 3416 3478 3415 7001 +33754 5495 5467 5557 6989 +33755 2798 3969 403 2449 +33756 1407 1300 159 2538 +33757 2328 2301 2319 6777 +33758 5190 5189 5191 6752 +33759 2913 3922 392 3974 +33760 5493 5522 5456 6488 +33761 5680 5614 5651 6487 +33762 25 5544 633 6751 +33763 2233 2242 2234 6990 +33764 598 5245 599 7154 +33765 4623 4583 5109 7140 +33766 4284 4229 4122 6544 +33767 2849 2652 2783 6750 +33768 4713 4735 5014 6982 +33769 4725 4722 4723 6623 +33770 2385 2948 3007 6647 +33771 3707 4008 7025 7208 +33772 1522 7024 1221 7209 +33773 2579 176 2508 6848 +33774 2634 2591 3118 7042 +33775 2543 3460 2541 6630 +33776 2552 2551 2547 6433 +33777 1343 1319 1209 7071 +33778 1221 6629 1274 7209 +33779 5702 559 27 6694 +33780 3713 3804 3905 6907 +33781 1271 6979 1461 7011 +33782 3757 6978 3947 7009 +33783 5164 5163 5162 6512 +33784 2611 3321 2616 7148 +33785 4245 4185 468 6847 +33786 1481 1328 1209 6684 +33787 3967 3814 3695 6686 +33788 3821 3764 3715 7108 +33789 2618 357 15 1400 +33790 5678 5612 5660 6637 +33791 5502 5520 5454 6638 +33792 5559 5498 5455 6853 +33793 5656 5613 5717 6851 +33794 3113 3225 3112 6896 +33795 1918 1687 1839 6859 +33796 3159 164 1460 1316 +33797 5496 5510 5443 6818 +33798 5654 5668 5601 6819 +33799 499 500 5664 7070 +33800 2338 2337 2305 6598 +33801 3489 3402 3260 6508 +33802 5566 5530 5472 6534 +33803 5688 5630 5724 6533 +33804 1184 6771 1493 7005 +33805 3979 3670 6774 7003 +33806 2887 2879 2556 7016 +33807 5697 5642 5596 6549 +33808 5438 5539 5484 6548 +33809 5244 4743 5150 6670 +33810 591 5239 592 6814 +33811 5676 568 569 6689 +33812 5451 5529 5500 6953 +33813 5609 5687 5658 6954 +33814 2699 3210 2892 6742 +33815 4353 4453 4280 6605 +33816 1388 1265 1299 6890 +33817 3785 3874 3751 6891 +33818 2183 1950 1826 6992 +33819 3171 2746 2713 6608 +33820 2210 323 3809 3935 +33821 2583 3286 2991 6824 +33822 1235 1341 1365 6759 +33823 3851 3721 3827 6760 +33824 1416 1489 1254 6804 +33825 3740 3902 3975 6803 +33826 4287 4187 4024 7046 +33827 5214 5179 5318 6843 +33828 4311 4092 4217 6577 +33829 1295 1410 1447 6712 +33830 5641 5717 5597 6892 +33831 5439 5483 5559 6893 +33832 420 2494 419 6927 +33833 4361 4265 4133 6558 +33834 2305 2369 2338 6598 +33835 3528 3264 3268 7139 +33836 162 2828 2831 7008 +33837 1515 1338 1253 6561 +33838 3739 4001 3824 6562 +33839 1250 1342 1434 6812 +33840 3736 3828 3920 6811 +33841 2092 1808 1946 6958 +33842 3928 3682 3839 6720 +33843 5724 5720 5601 6675 +33844 5443 5566 5562 6676 +33845 5501 5577 32 6570 +33846 5659 5735 30 6569 +33847 274 1541 1546 7212 +33848 581 5687 580 6729 +33849 630 5529 629 6730 +33850 3647 232 3612 7080 +33851 2278 2286 2281 6935 +33852 2708 2842 3246 7128 +33853 4318 4031 4455 6995 +33854 3912 19 242 3923 +33855 2792 2903 3196 6969 +33856 2578 2508 2455 6848 +33857 4292 4156 4068 7056 +33858 1319 1413 1192 7070 +33859 2692 2691 2528 6514 +33860 5232 5200 5251 7155 +33861 3924 22 354 3913 +33862 5478 5587 5575 7207 +33863 3940 3800 3696 7113 +33864 1314 1210 1454 7114 +33865 3953 3747 3862 6947 +33866 1293 176 1508 6848 +33867 535 536 5017 7076 +33868 4227 4064 4442 7203 +33869 1275 1182 1458 6781 +33870 3944 3761 3668 6784 +33871 1970 1795 2100 6817 +33872 406 2975 3946 3852 +33873 1181 6955 1305 6956 +33874 4212 4094 4466 7072 +33875 277 3998 3855 1992 +33876 1512 187 1991 1369 +33877 5484 6840 5553 7113 +33878 5642 6841 5711 7114 +33879 595 5336 596 6962 +33880 1570 1573 1568 7126 +33881 3938 3869 3722 6676 +33882 1452 1383 1236 6675 +33883 4339 4127 4414 7092 +33884 3716 3958 3861 6529 +33885 1472 1375 1230 6528 +33886 2900 2629 2634 7042 +33887 328 2290 327 7034 +33888 1366 1252 1415 6824 +33889 3012 3027 3010 7078 +33890 4757 562 561 6829 +33891 1278 174 2470 1364 +33892 3884 3752 3957 6876 +33893 3223 3112 3225 6896 +33894 2783 2652 2646 6750 +33895 4682 4853 4706 7030 +33896 2703 2701 2700 6831 +33897 248 1954 249 6485 +33898 3454 3418 3556 7084 +33899 1277 1224 1334 7040 +33900 3617 234 235 6943 +33901 3267 3268 3264 7139 +33902 5750 5608 5648 6594 +33903 5490 5592 5450 6593 +33904 3689 3845 3769 6725 +33905 2202 2205 2216 6911 +33906 1289 1372 1196 6571 +33907 1792 2083 2057 6616 +33908 2888 2982 2978 6504 +33909 4839 4597 4838 7123 +33910 3778 3835 3690 6389 +33911 5722 5656 5641 6892 +33912 5483 5564 5498 6893 +33913 3789 3838 3674 6868 +33914 1352 1188 1303 6867 +33915 2630 2632 2571 7161 +33916 3766 3943 4005 7002 +33917 1280 1457 1519 7004 +33918 2424 439 2571 7161 +33919 5644 5706 5717 6561 +33920 5559 5486 5548 6562 +33921 3847 3791 3713 7207 +33922 2895 2448 2447 7174 +33923 531 5515 5583 6580 +33924 1388 1299 1518 6890 +33925 3874 3785 4004 6891 +33926 1311 1337 1485 6883 +33927 1196 1372 1478 6571 +33928 563 7060 5696 7137 +33929 4914 4913 4915 7029 +33930 1483 1379 162 7008 +33931 3611 3606 3588 7086 +33932 5628 5678 5729 6541 +33933 5470 5520 5571 6539 +33934 3601 6797 419 7090 +33935 3817 3681 4009 6570 +33936 1195 1523 1331 6569 +33937 2371 3831 356 2344 +33938 555 4508 556 6967 +33939 1567 1565 1562 6993 +33940 1939 1843 1759 6658 +33941 1875 1684 1806 6614 +33942 417 3994 3779 7191 +33943 239 238 1552 6698 +33944 578 577 6543 6701 +33945 417 2507 2577 7191 +33946 1217 1325 1309 6585 +33947 5651 6759 5707 6865 +33948 5493 6760 5549 6866 +33949 5505 5545 5526 6978 +33950 5684 5663 5703 6979 +33951 2852 2850 2851 7050 +33952 2923 1465 153 2588 +33953 3697 3898 3804 6852 +33954 1211 1412 1318 6850 +33955 3027 2958 2957 7078 +33956 2472 2471 3122 6454 +33957 5571 624 5521 7193 +33958 2218 2225 2217 7053 +33959 1818 2130 1930 7177 +33960 3591 3623 3618 6894 +33961 352 2374 353 6566 +33962 1402 2725 2720 7162 +33963 3636 1346 98 1437 +33964 3868 1990 290 3793 +33965 1307 1382 200 1993 +33966 2911 3054 3216 7120 +33967 2372 2295 2341 6902 +33968 4889 5111 4888 7088 +33969 3971 3823 3708 6882 +33970 2486 3286 2800 6808 +33971 2558 3571 2760 6786 +33972 3797 3823 3971 6882 +33973 463 5558 462 7061 +33974 1240 1310 1356 6476 +33975 1237 1300 1407 6727 +33976 5702 5736 559 6694 +33977 5445 5563 6584 6904 +33978 5721 6583 5603 6903 +33979 2493 3126 2389 6709 +33980 2213 2195 2205 6572 +33981 3924 3745 3913 7169 +33982 4046 4352 4452 7185 +33983 4212 4475 4370 6681 +33984 4849 4678 4887 7159 +33985 4767 4784 4783 6885 +33986 4224 4480 6944 7132 +33987 1540 1541 1534 6756 +33988 374 2812 375 6926 +33989 3816 3962 3679 6783 +33990 1476 1193 1330 6780 +33991 5252 5254 5220 6513 +33992 5519 5473 5453 6772 +33993 5631 5611 5677 6769 +33994 3811 3870 3673 6863 +33995 1578 1583 1587 7051 +33996 597 4750 598 6754 +33997 5745 5636 5613 6955 +33998 4388 4396 4184 6501 +33999 2341 1438 211 1345 +34000 4317 4062 4211 6942 +34001 3651 3616 3595 6928 +34002 4788 4770 4624 6792 +34003 501 502 5751 6997 +34004 5547 5480 5522 6877 +34005 5705 5638 5680 6879 +34006 4203 4252 4111 6706 +34007 5611 5670 5677 6770 +34008 5512 5519 5453 6773 +34009 2919 3095 3097 6696 +34010 4659 4660 4661 6522 +34011 293 2216 2291 6911 +34012 5005 5303 4809 6799 +34013 2344 3831 356 3924 +34014 1334 1474 1190 6632 +34015 3676 3820 3960 6631 +34016 192 1350 1446 1828 +34017 282 3836 3932 1829 +34018 1825 2055 1741 6726 +34019 1578 1580 1588 7051 +34020 5527 5547 5462 6877 +34021 5685 5705 5620 6879 +34022 5077 4744 4745 6936 +34023 2953 2442 2441 6816 +34024 3693 3925 3825 6773 +34025 1207 1439 1339 6770 +34026 1969 1794 2099 6980 +34027 4859 4937 4936 6651 +34028 5582 458 459 7085 +34029 5546 26 530 6862 +34030 245 3843 3808 1620 +34031 4120 4264 4410 7100 +34032 3662 3636 3584 6809 +34033 1466 1232 1395 6498 +34034 3715 3863 3921 7041 +34035 5505 5461 5545 7009 +34036 5619 5703 5663 7011 +34037 4388 4184 4103 6501 +34038 1801 3834 288 2066 +34039 2069 198 1348 1799 +34040 1485 1337 1222 6883 +34041 2462 2576 2507 7191 +34042 5713 5653 5607 6994 +34043 3724 3936 3781 6620 +34044 1450 1296 1238 6619 +34045 2199 2215 352 6566 +34046 5605 5711 5642 6841 +34047 5484 5447 5553 6840 +34048 2196 327 2290 7034 +34049 499 5740 498 7071 +34050 1543 1618 215 6794 +34051 5523 5589 5485 6913 +34052 3067 3075 3068 6590 +34053 3479 3415 3478 7001 +34054 3562 3510 3522 6738 +34055 5478 5575 5515 7207 +34056 1325 1217 1491 6585 +34057 4105 4335 4380 6884 +34058 3660 3587 3611 6672 +34059 5741 5704 634 6476 +34060 4064 6669 4302 7203 +34061 4452 4279 4142 7185 +34062 299 300 2139 7143 +34063 1317 1314 1227 6954 +34064 3803 3800 3712 6953 +34065 1978 310 1855 7201 +34066 4480 4313 4071 7132 +34067 3946 2447 405 3802 +34068 5179 5178 5318 6843 +34069 2365 2308 2320 6679 +34070 3762 3854 3672 6751 +34071 5581 5440 5490 7200 +34072 5598 5648 5739 7199 +34073 232 1565 233 6993 +34074 3848 3782 3725 7190 +34075 3518 3058 3011 6823 +34076 5178 5181 5180 6813 +34077 3916 3827 3727 6900 +34078 343 2240 2248 7202 +34079 633 5544 5578 6751 +34080 3742 3907 3885 7044 +34081 2863 2862 2780 7117 +34082 4544 4512 4495 6682 +34083 3771 3922 3714 7075 +34084 2991 164 1460 3159 +34085 1291 1498 1320 6827 +34086 3806 3777 3984 6828 +34087 1335 1229 1448 6587 +34088 3774 4001 3925 6595 +34089 1288 1515 1439 6596 +34090 1343 1493 1249 7071 +34091 5111 4688 4888 7088 +34092 1403 1182 1492 6640 +34093 3978 3889 3668 6641 +34094 5610 5727 5655 7133 +34095 5569 5497 5452 7134 +34096 492 5715 5647 6788 +34097 3824 3919 3739 6562 +34098 1253 1338 1433 6561 +34099 5495 5449 5555 6989 +34100 159 1407 2538 3203 +34101 1795 1911 2100 6817 +34102 1186 1276 1368 6694 +34103 1411 1203 1296 6810 +34104 5088 5120 5087 7027 +34105 4067 4231 4300 7028 +34106 1826 1671 2001 6992 +34107 2786 3533 2795 6697 +34108 4532 535 4555 7076 +34109 1672 1808 1811 6958 +34110 1745 2078 1909 6800 +34111 3716 3882 3876 6702 +34112 1230 1396 1390 6703 +34113 3101 2563 426 6963 +34114 2481 3864 390 2482 +34115 4331 4162 4011 7141 +34116 1410 1228 1447 6712 +34117 2204 2213 2205 6572 +34118 1181 1358 6644 6956 +34119 2610 2608 2609 6957 +34120 3844 6645 3667 7031 +34121 1249 1404 1394 6769 +34122 3880 3735 3890 6772 +34123 576 5686 5679 6640 +34124 5521 625 5528 6641 +34125 1355 1256 1477 7205 +34126 2585 2586 395 7023 +34127 5251 5231 5232 7155 +34128 5557 5489 452 6821 +34129 390 3763 3864 2481 +34130 149 1277 1378 2474 +34131 346 2234 345 6990 +34132 5364 5171 5206 7197 +34133 3939 3845 3701 6807 +34134 5642 5692 6549 7114 +34135 5484 5534 6548 7113 +34136 3974 3922 3771 7075 +34137 5689 5676 5614 6901 +34138 5570 5482 5568 6801 +34139 5726 5728 5640 6802 +34140 452 451 6820 6821 +34141 3470 3553 2639 6767 +34142 492 491 6787 6788 +34143 554 4559 555 7150 +34144 5585 5466 5540 6868 +34145 5624 5698 5743 6867 +34146 1747 1802 2114 7032 +34147 3751 3930 3931 6593 +34148 1265 1444 1445 6594 +34149 3427 3445 3487 7036 +34150 2588 2498 2923 6844 +34151 4886 4883 5229 6970 +34152 5247 5246 5263 6842 +34153 5527 614 615 6875 +34154 5685 565 566 6878 +34155 5599 5690 5655 6960 +34156 5497 5441 5532 6959 +34157 2036 1837 1718 6673 +34158 1360 1246 1298 6788 +34159 3776 3858 3682 6721 +34160 2662 7174 2895 7175 +34161 5537 5508 5482 6932 +34162 5666 5640 5695 6931 +34163 3761 3894 3724 6840 +34164 1275 1408 1238 6841 +34165 3520 3452 3451 7144 +34166 1493 1287 1404 6771 +34167 3890 3979 3773 6774 +34168 2460 2510 3023 6680 +34169 2511 2682 2681 6761 +34170 3732 3784 3846 6821 +34171 3372 3382 3524 6747 +34172 2434 2436 2554 6945 +34173 4794 4935 5102 6719 +34174 3941 1934 280 3798 +34175 1312 190 1933 1455 +34176 2260 2254 2265 6581 +34177 1624 213 9 1426 +34178 285 286 1815 3814 +34179 3852 3741 3942 6749 +34180 4399 4178 4044 6410 +34181 2133 1673 1805 7059 +34182 1388 1243 1406 6931 +34183 3892 3874 3729 6932 +34184 3918 3669 3895 6704 +34185 1432 1183 1409 6705 +34186 3046 3230 3044 7020 +34187 2389 2458 2493 6709 +34188 1341 1451 1241 6901 +34189 5502 5567 621 6757 +34190 6798 7048 5785 7161 +34191 3303 2809 2811 7065 +34192 2685 399 3815 2659 +34193 2182 1825 2119 6726 +34194 1427 325 18 2211 +34195 337 2352 338 6776 +34196 5163 5120 5088 7027 +34197 2857 2859 2850 7124 +34198 5458 5503 5536 6529 +34199 5661 5694 5616 6528 +34200 2919 3097 3309 6696 +34201 3726 3928 3796 6580 +34202 2529 2394 2504 6898 +34203 5343 5237 5285 7055 +34204 3500 3530 3296 6748 +34205 3944 3818 3730 6785 +34206 1458 1332 1244 6782 +34207 1280 1343 7004 7005 +34208 3766 3829 7002 7003 +34209 2261 2263 2268 7081 +34210 3732 3823 3854 7094 +34211 295 1895 294 6718 +34212 5523 5485 627 6913 +34213 3016 3082 3032 7168 +34214 3229 3008 3078 7103 +34215 1421 8 418 3635 +34216 2199 352 353 6566 +34217 3169 3564 3579 6713 +34218 1220 1385 1356 6766 +34219 3871 3842 3706 6765 +34220 3327 2821 2463 7206 +34221 2682 2511 3262 6761 +34222 1199 1430 1510 6487 +34223 3685 3916 3996 6488 +34224 5445 5471 5563 6904 +34225 5629 5721 5603 6903 +34226 5632 5747 5681 6619 +34227 5523 5474 5589 6620 +34228 251 1615 1613 7104 +34229 3673 3842 3796 6862 +34230 1252 1336 1415 6746 +34231 1805 2003 1734 7059 +34232 511 5431 512 6435 +34233 536 4532 4504 7076 +34234 3632 446 3664 6905 +34235 5725 572 5660 6758 +34236 280 1892 1934 3941 +34237 1891 1933 190 1455 +34238 382 3025 383 6981 +34239 5298 5254 5252 6513 +34240 6108 7064 7049 7195 +34241 536 4523 537 6999 +34242 2008 1999 1755 6934 +34243 2070 1629 7129 7130 +34244 500 501 6825 6917 +34245 2355 2301 2328 6777 +34246 2428 2615 2585 7023 +34247 2085 282 3932 1829 +34248 2084 192 1446 1828 +34249 5526 5466 5503 6702 +34250 5684 5624 5661 6703 +34251 3803 3712 3904 6953 +34252 1418 1317 1227 6954 +34253 1687 1868 1839 6859 +34254 5574 618 619 6604 +34255 3454 3484 3455 7084 +34256 4838 4966 4970 6724 +34257 1437 1259 1426 7017 +34258 1395 1204 1291 6827 +34259 3777 3881 3690 6828 +34260 5502 622 5520 6638 +34261 5660 573 5678 6637 +34262 1946 1837 2092 6673 +34263 1522 1350 1221 7024 +34264 3836 3707 4008 7025 +34265 1777 2098 1702 7006 +34266 3726 3791 3847 7207 +34267 538 4992 4641 6798 +34268 3425 3202 3200 6919 +34269 4739 4708 5278 6888 +34270 2066 290 1990 3793 +34271 2069 1307 200 1993 +34272 2114 1684 1875 6614 +34273 4940 5119 4846 6737 +34274 5779 7065 6835 7175 +34275 4507 4498 4525 7136 +34276 5738 560 5671 6743 +34277 2676 2677 2675 6536 +34278 5652 5598 5682 6782 +34279 5524 5494 5440 6785 +34280 3754 3824 3867 6654 +34281 1338 1381 1268 6655 +34282 3474 2860 2857 7124 +34283 5045 4942 4856 7211 +34284 4886 4882 4883 6970 +34285 162 1379 2828 7008 +34286 4010 3784 3945 6584 +34287 1524 1298 1459 6583 +34288 5639 5699 562 7137 +34289 503 4381 4336 7079 +34290 1345 212 2372 1422 +34291 3568 3440 3526 6910 +34292 1907 2104 1742 6912 +34293 4067 4431 4231 7210 +34294 4347 4029 4423 6622 +34295 2691 2690 2870 7077 +34296 2504 2394 2503 6998 +34297 1552 1545 239 6698 +34298 3633 3585 3631 7083 +34299 2993 3058 3518 6823 +34300 3878 3765 3929 6801 +34301 1443 1392 1279 6802 +34302 4318 4264 4031 6995 +34303 323 2292 2210 3809 +34304 5507 5469 5438 6939 +34305 5596 5665 5627 6940 +34306 5479 5518 5574 6603 +34307 5676 5732 5637 6602 +34308 2121 1907 1742 6912 +34309 2822 2826 2823 6915 +34310 2090 1764 2052 6880 +34311 3169 2907 3564 6713 +34312 3204 2658 2657 7052 +34313 5177 5175 5176 6708 +34314 552 4647 551 6916 +34315 5456 5549 5493 6760 +34316 5651 5614 5707 6759 +34317 1279 1416 1193 6940 +34318 3679 3765 3902 6939 +34319 5474 5523 5588 6620 +34320 5746 5632 5681 6619 +34321 4842 5314 4919 6576 +34322 402 3969 2798 6947 +34323 5611 5641 5670 6770 +34324 5512 5453 5483 6773 +34325 3510 3562 3509 6738 +34326 6553 7196 6049 7197 +34327 5550 451 5489 6821 +34328 3634 24 447 3908 +34329 2629 2633 2634 6656 +34330 4684 4685 4686 6700 +34331 4260 4414 4127 7092 +34332 1453 1359 1215 7014 +34333 2676 2675 2916 6536 +34334 3711 3833 4010 6904 +34335 1347 1524 1225 6903 +34336 5708 491 5647 6788 +34337 97 1421 1346 3662 +34338 212 2343 2372 1422 +34339 1327 1416 1214 6804 +34340 3813 3902 3700 6803 +34341 1391 1262 1351 6974 +34342 3260 3188 3489 6745 +34343 2441 2442 2419 6816 +34344 2574 2787 379 6857 +34345 5388 516 5420 6948 +34346 4622 4564 4895 7121 +34347 5668 5693 5723 6610 +34348 5565 5510 5535 6611 +34349 1368 1246 1337 6996 +34350 5126 5128 5127 6837 +34351 5696 563 564 7060 +34352 3674 3882 3789 6868 +34353 1303 1188 1396 6867 +34354 5531 616 617 6735 +34355 3002 2861 2981 7160 +34356 1460 1252 1366 6824 +34357 2045 1736 2110 6635 +34358 2733 2656 2730 7021 +34359 3507 2806 2865 7125 +34360 1551 273 1546 7212 +34361 4187 4463 4117 7046 +34362 2524 2505 2456 6933 +34363 2214 2217 2219 7053 +34364 3867 3680 3920 7134 +34365 1381 1194 1434 7133 +34366 2595 2593 2592 7173 +34367 2533 2535 2581 7127 +34368 4936 4937 5099 6651 +34369 2422 2421 2420 7195 +34370 534 4525 4555 7136 +34371 614 5542 613 7054 +34372 358 359 2336 6793 +34373 175 2499 1508 2579 +34374 2577 2503 416 3994 +34375 3780 387 2572 3995 +34376 146 2575 1294 1509 +34377 5635 5646 5744 6874 +34378 5477 5488 5586 6873 +34379 3696 3894 3761 6840 +34380 1210 1408 1275 6841 +34381 5515 5580 5478 7207 +34382 2812 3235 375 6926 +34383 5594 5564 5483 6645 +34384 5722 5641 5752 6644 +34385 562 6712 563 7137 +34386 1200 1443 1286 7012 +34387 3686 3929 3772 7010 +34388 5738 31 560 6571 +34389 2861 2456 2862 7117 +34390 4794 5102 4796 6719 +34391 1482 1402 1267 7162 +34392 1624 1536 213 7017 +34393 5527 5542 614 6875 +34394 5685 5700 565 6878 +34395 594 5419 5383 6628 +34396 5629 5659 5721 6903 +34397 5471 5501 5563 6904 +34398 4071 4144 4304 6624 +34399 2266 2261 2268 7081 +34400 5720 5654 5601 6675 +34401 5496 5443 5562 6676 +34402 1528 3912 242 6575 +34403 388 2572 3995 2377 +34404 2381 2575 147 1509 +34405 3825 3880 3693 6773 +34406 1207 1339 1394 6770 +34407 2540 3203 2538 6727 +34408 2475 149 1378 2474 +34409 1912 1642 2099 6980 +34410 2496 3246 2497 7128 +34411 5478 5513 5455 6907 +34412 5103 4939 4648 6937 +34413 5768 7089 6797 7090 +34414 5710 5634 5650 6923 +34415 5476 5492 5552 6922 +34416 2868 3527 2869 6929 +34417 2218 317 2225 7213 +34418 1498 1266 1320 6878 +34419 3806 3984 3752 6875 +34420 2567 2565 2564 6861 +34421 4772 4771 623 6835 +34422 4144 4071 4313 6624 +34423 3908 3661 449 3832 +34424 5638 5689 5614 6901 +34425 4941 4637 4993 7035 +34426 4873 4828 4826 7204 +34427 5618 5651 5668 6865 +34428 5510 5460 5493 6866 +34429 5546 530 5583 6862 +34430 5537 5482 5461 7010 +34431 5695 5640 5619 7012 +34432 5504 5462 5547 6704 +34433 5705 5662 5620 6705 +34434 2621 2619 2620 7097 +34435 5615 5648 5666 6890 +34436 5490 5508 5457 6891 +34437 1707 1855 2086 7201 +34438 2763 2773 2422 6855 +34439 230 1573 231 7126 +34440 2410 2457 2960 6695 +34441 5466 5526 5591 6702 +34442 5684 5749 5624 6703 +34443 2299 2324 2316 6856 +34444 2633 2629 2628 6656 +34445 2818 2989 2814 6688 +34446 354 3913 2197 7169 +34447 2699 3523 3406 7196 +34448 1805 1734 1930 7177 +34449 520 4430 519 6579 +34450 3427 3488 3445 7036 +34451 4312 4072 4145 6559 +34452 3245 3248 3249 6966 +34453 3314 1376 161 1483 +34454 5527 5480 5547 6877 +34455 5685 5638 5705 6879 +34456 3884 3848 3752 7054 +34457 3699 3774 4007 6873 +34458 1213 1288 1521 6874 +34459 4620 4598 4619 6763 +34460 1535 1534 1541 6756 +34461 3764 3850 415 6998 +34462 3680 4001 3774 6595 +34463 1288 1194 1515 6596 +34464 1340 1320 1183 6879 +34465 3669 3826 3806 6877 +34466 1220 1389 1358 6563 +34467 3875 3844 3706 6564 +34468 5693 5615 5666 6890 +34469 5508 5535 5457 6891 +34470 622 4772 623 6835 +34471 545 4515 546 6650 +34472 2810 2984 2975 7013 +34473 5608 5640 5666 6931 +34474 5450 5482 5508 6932 +34475 2588 2496 2498 6844 +34476 3724 3872 3906 6913 +34477 3601 420 419 6797 +34478 3464 3400 3466 6870 +34479 5625 5653 5713 6994 +34480 599 5426 598 7154 +34481 4224 4033 4313 7132 +34482 4211 4403 4077 6942 +34483 5362 5282 5283 7135 +34484 3869 3819 3721 6534 +34485 1383 1333 1235 6533 +34486 2262 337 2264 6776 +34487 2101 1816 2032 6930 +34488 3590 3644 3601 6797 +34489 3780 3710 3995 6886 +34490 4365 4356 4147 6663 +34491 2444 2952 2390 7186 +34492 1291 1204 1498 6827 +34493 3984 3777 3690 6828 +34494 432 3626 3656 6715 +34495 577 5686 576 7014 +34496 3842 3790 3706 6765 +34497 1220 1356 1304 6766 +34498 3807 322 2198 3935 +34499 5537 5525 5437 6530 +34500 5683 5595 5695 6531 +34501 1816 1680 1880 7105 +34502 4333 489 4420 7172 +34503 1324 1250 1354 7111 +34504 3810 3736 3840 7112 +34505 5561 5447 5494 6784 +34506 5652 5719 5605 6781 +34507 2325 2348 2297 7063 +34508 2645 2644 2545 6839 +34509 3764 415 2479 6998 +34510 3377 3382 3374 7166 +34511 1408 1450 1238 6619 +34512 3936 3724 3894 6620 +34513 2801 2425 2752 7000 +34514 4418 4204 516 6661 +34515 2556 2879 2880 7016 +34516 2044 1797 1972 7091 +34517 3032 3015 3016 7168 +34518 1315 1305 1181 6955 +34519 2959 2962 3468 6683 +34520 5672 5596 5627 6940 +34521 5469 5514 5438 6939 +34522 5328 4705 5115 6627 +34523 1277 1363 1224 7040 +34524 606 5434 605 6987 +34525 625 5521 624 7193 +34526 2448 2895 2662 7174 +34527 3853 3760 3707 6636 +34528 4989 4645 4946 7106 +34529 4320 4408 4158 7153 +34530 3911 3937 3827 6900 +34531 1699 1962 1791 6918 +34532 1777 1653 2076 6906 +34533 3901 3852 3738 7013 +34534 4327 4034 4154 6615 +34535 5569 5452 5468 7134 +34536 5727 5610 5626 7133 +34537 2560 2561 2559 6749 +34538 1794 1912 2099 6980 +34539 1622 1621 181 1449 +34540 3404 3260 3402 6508 +34541 5467 5495 5555 6989 +34542 4775 4762 4719 7145 +34543 1202 1295 1362 7060 +34544 3219 2664 2436 6945 +34545 4967 4966 4838 6724 +34546 3898 6852 3725 7190 +34547 3263 3264 3265 6555 +34548 3188 3187 3489 6745 +34549 4703 5115 4705 6627 +34550 2854 2469 2466 6639 +34551 3907 3831 355 2371 +34552 3843 3783 3977 7082 +34553 596 5390 595 6962 +34554 2052 1632 2090 6880 +34555 3277 3062 3276 7198 +34556 3744 3912 3993 6575 +34557 1816 1637 2032 6930 +34558 402 3279 3280 6947 +34559 3027 3012 2958 7078 +34560 4592 4593 4969 6692 +34561 1259 1506 1426 7017 +34562 1890 1682 1981 6525 +34563 3231 3537 3138 6941 +34564 3686 3947 3757 6978 +34565 1200 1461 1271 6979 +34566 1540 1542 1599 6653 +34567 3927 4004 3758 6611 +34568 1441 1518 1272 6610 +34569 3228 3045 3232 6710 +34570 5306 4943 5146 7043 +34571 455 5540 454 6868 +34572 494 495 5698 6867 +34573 577 578 5643 6701 +34574 5642 5692 5596 6549 +34575 5438 5484 5534 6548 +34576 1423 197 1889 1935 +34577 1936 287 3909 1888 +34578 3888 2714 410 3753 +34579 3979 3829 3670 7003 +34580 1184 1493 1343 7005 +34581 1814 195 196 1328 +34582 2277 2272 299 7143 +34583 2644 2546 2545 6839 +34584 3869 3671 3819 6534 +34585 1185 1333 1383 6533 +34586 3132 2589 2827 6968 +34587 2819 2818 2814 6688 +34588 1190 1412 1295 7137 +34589 2296 2344 2340 6889 +34590 2066 3834 289 3793 +34591 199 1307 2069 1348 +34592 401 400 3786 2872 +34593 5673 635 31 6722 +34594 1445 1201 1299 7199 +34595 3687 3785 3931 7200 +34596 1197 1415 1336 6746 +34597 3676 3898 3782 7190 +34598 4591 4593 4592 6692 +34599 5613 5656 5745 6955 +34600 5572 5494 5447 6784 +34601 5730 5652 5605 6781 +34602 1755 1920 1893 6677 +34603 5691 5631 5602 6771 +34604 5473 5444 5533 6774 +34605 2403 3118 2405 6914 +34606 4155 4291 4067 7028 +34607 338 2264 337 6776 +34608 4203 4065 4252 6706 +34609 2975 2561 2810 7013 +34610 2424 2632 2705 7161 +34611 2109 1634 1999 7047 +34612 320 21 3917 2292 +34613 2432 413 2396 3863 +34614 1266 1484 1320 6878 +34615 3752 3970 3806 6875 +34616 172 2400 2433 1377 +34617 1665 1970 2065 7178 +34618 5684 5703 5600 6979 +34619 5442 5526 5545 6978 +34620 5652 5712 5598 6782 +34621 5494 5554 5440 6785 +34622 3844 3825 3667 6645 +34623 1339 1181 1358 6644 +34624 4393 4468 4053 7087 +34625 3671 3859 3767 6757 +34626 1185 1373 1281 6758 +34627 2030 1712 1974 6864 +34628 3847 3776 3682 6721 +34629 3194 2805 2426 6977 +34630 4224 4480 4132 6944 +34631 2660 3778 397 3879 +34632 4564 4622 4621 7121 +34633 5489 5552 5445 6584 +34634 5603 5647 5710 6583 +34635 3101 426 427 6963 +34636 5618 5723 5669 6812 +34637 5565 5511 5460 6811 +34638 3683 3877 3837 7193 +34639 2614 3128 2964 7073 +34640 4065 4252 6706 7184 +34641 5696 6850 5639 7137 +34642 1525 1618 1543 6794 +34643 5541 610 611 6631 +34644 561 562 5699 6632 +34645 3913 3992 3807 7169 +34646 1211 1318 1315 6851 +34647 3697 3804 3801 6853 +34648 1815 1679 2049 6687 +34649 1678 2050 1814 6685 +34650 3829 3979 3735 7085 +34651 97 1421 3662 3635 +34652 5559 5455 5486 6853 +34653 5717 5613 5644 6851 +34654 5593 5509 5475 6564 +34655 5633 5751 5667 6563 +34656 1531 1622 182 1449 +34657 3636 9 213 1437 +34658 5497 5460 5511 6811 +34659 5655 5618 5669 6812 +34660 1212 1336 1499 6897 +34661 2221 2231 2226 6822 +34662 399 398 3815 2659 +34663 4761 5066 4911 6815 +34664 166 165 1366 2584 +34665 1295 1202 1410 7060 +34666 3862 402 401 3280 +34667 2503 415 3850 6998 +34668 3608 3590 3643 7062 +34669 175 2499 1364 1508 +34670 3994 2503 416 3850 +34671 2895 2896 2839 7175 +34672 1634 2053 2150 7192 +34673 1324 1464 1179 6531 +34674 3665 3810 3950 6530 +34675 3978 3748 3889 6641 +34676 1262 1403 1492 6640 +34677 2463 377 2464 7206 +34678 492 5647 491 6788 +34679 3799 3717 3813 6989 +34680 5509 5558 5465 6765 +34681 5667 5716 5623 6766 +34682 3736 3927 3828 6811 +34683 1441 1342 1250 6812 +34684 1806 2108 1982 7122 +34685 439 2424 438 7048 +34686 1367 1274 1221 6629 +34687 2062 1679 1815 6687 +34688 1678 1814 2061 6685 +34689 4444 4189 4109 7131 +34690 2752 2427 2751 7000 +34691 5532 5522 5493 6488 +34692 5651 5690 5680 6487 +34693 5473 5506 5453 6772 +34694 5631 5664 5611 6769 +34695 3302 2690 2921 7077 +34696 2831 3314 161 1483 +34697 2516 2605 2720 7162 +34698 322 2209 2198 3935 +34699 3719 3818 3889 6971 +34700 1233 1332 1403 6972 +34701 4301 4068 4156 7056 +34702 4508 4559 4499 6967 +34703 1292 156 3218 1393 +34704 3342 3331 3340 6573 +34705 2592 2818 2820 6973 +34706 1305 1315 1226 6955 +34707 452 5489 451 6821 +34708 5381 527 5433 7066 +34709 3606 3641 3588 7086 +34710 2583 2991 2584 6824 +34711 620 5222 621 6643 +34712 1831 1749 2154 7074 +34713 3835 3951 3737 7023 +34714 2796 2426 2805 6977 +34715 4322 4385 4090 6524 +34716 2611 2616 2612 7148 +34717 4102 4183 4387 7157 +34718 1327 1313 1231 6994 +34719 1412 1397 1239 6850 +34720 3725 3898 3883 6852 +34721 3852 407 406 2561 +34722 5706 5597 5717 6561 +34723 5559 5548 5439 6562 +34724 444 2411 443 6768 +34725 3805 3678 3866 6924 +34726 1516 1233 1391 6541 +34727 4002 3719 3877 6539 +34728 2914 3922 391 2913 +34729 3694 3790 3870 7061 +34730 3882 3759 3876 6702 +34731 1390 1396 1273 6703 +34732 3969 402 3862 6947 +34733 4517 4506 553 6739 +34734 5644 5613 5718 6851 +34735 5560 5486 5455 6853 +34736 4894 4921 4893 6659 +34737 3833 3711 3817 6904 +34738 1331 1347 1225 6903 +34739 1950 1763 2189 6778 +34740 5047 5121 5340 6707 +34741 1974 2184 2030 6864 +34742 629 4777 4851 6693 +34743 2336 2346 358 6793 +34744 2008 1755 1866 6934 +34745 169 2720 1267 1402 +34746 2720 2725 2516 7162 +34747 1209 1280 1343 7004 +34748 3695 3766 3829 7002 +34749 5080 4767 4783 6885 +34750 3634 3661 449 3908 +34751 5591 5442 5499 6648 +34752 5749 5600 5657 6649 +34753 1352 1221 1274 7209 +34754 3760 3838 3707 7208 +34755 3078 3008 3079 7103 +34756 3844 3733 3825 6645 +34757 1358 1247 1339 6644 +34758 4130 4302 4218 6669 +34759 3907 23 386 2342 +34760 5747 5711 5605 6841 +34761 5589 5553 5447 6840 +34762 18 325 1438 2341 +34763 4088 4327 4154 6615 +34764 1665 2065 1961 7178 +34765 488 4420 489 7172 +34766 4758 560 4732 6582 +34767 4708 5289 5278 6888 +34768 1375 1184 1280 7005 +34769 3670 3766 3861 7003 +34770 2566 2564 2565 6861 +34771 2000 1727 2115 6601 +34772 2787 2574 2901 6857 +34773 3843 245 244 1620 +34774 2965 2964 3128 7073 +34775 3937 3677 3952 6735 +34776 5610 5669 5646 7111 +34777 5488 5452 5511 7112 +34778 4381 503 502 7079 +34779 550 4595 549 7039 +34780 2008 1866 1655 6934 +34781 2109 1873 1634 7047 +34782 4785 4786 4635 7049 +34783 2070 1872 1629 7130 +34784 5646 5669 5683 7111 +34785 5525 5488 5511 7112 +34786 5285 5237 5236 7055 +34787 4997 551 4647 6916 +34788 323 2210 2209 3935 +34789 2363 2304 2317 7151 +34790 3103 2610 2609 6957 +34791 4508 555 4559 6967 +34792 2436 2664 2554 6945 +34793 3414 3495 3304 7102 +34794 4352 4084 4279 7185 +34795 3919 3697 3801 6853 +34796 1315 1433 1211 6851 +34797 4155 4437 4291 6714 +34798 1340 1241 1320 6879 +34799 3826 3727 3806 6877 +34800 1361 1226 1289 6743 +34801 2214 2258 2218 7053 +34802 5434 5406 605 6987 +34803 4212 4370 4059 6681 +34804 4309 4107 4372 7018 +34805 2792 2786 2795 6697 +34806 2067 277 3855 1992 +34807 2068 1991 187 1369 +34808 518 5415 5385 6854 +34809 2823 2627 2822 6915 +34810 3661 3634 3585 7083 +34811 3975 3902 3813 6803 +34812 1489 1416 1327 6804 +34813 3905 3676 3960 6631 +34814 1419 1190 1474 6632 +34815 3777 3937 3952 6735 +34816 161 160 1376 3314 +34817 2585 395 3835 7023 +34818 2317 2304 2332 7151 +34819 1189 1418 1475 6729 +34820 3961 3675 3904 6730 +34821 2554 2663 2553 7068 +34822 4904 5065 5063 7167 +34823 3886 24 447 2617 +34824 3975 3991 3666 6922 +34825 1505 1180 1489 6923 +34826 3714 3934 3896 6736 +34827 5579 5462 5504 6704 +34828 5737 5620 5662 6705 +34829 2676 2979 2678 6920 +34830 2342 3907 355 2371 +34831 5701 5664 500 7070 +34832 2066 289 290 3793 +34833 1307 200 199 2069 +34834 287 286 3909 1888 +34835 1423 197 196 1889 +34836 2398 2399 2400 7096 +34837 3993 3703 3795 7119 +34838 4770 4988 4624 6792 +34839 3452 3520 3517 7144 +34840 5570 5568 5469 6801 +34841 5726 5627 5728 6802 +34842 4335 4105 4419 6884 +34843 4249 4357 4042 6858 +34844 2828 2830 2831 7008 +34845 2927 2722 2548 6660 +34846 3909 286 3756 1888 +34847 1270 1423 196 1889 +34848 5105 4785 4635 7049 +34849 1427 207 1322 2211 +34850 2137 2126 1630 6671 +34851 5601 5651 5707 6865 +34852 5493 5549 5443 6866 +34853 5538 5448 5481 6852 +34854 5696 5606 5639 6850 +34855 553 4506 4534 6739 +34856 3217 2990 2710 6869 +34857 1611 1613 1615 7104 +34858 1973 1971 1796 6740 +34859 4382 4113 4294 7146 +34860 396 395 3835 2585 +34861 5709 5619 5663 7011 +34862 5505 5551 5461 7009 +34863 4457 4149 4011 7141 +34864 1449 1621 181 1321 +34865 5463 5489 5563 6584 +34866 5621 5647 5721 6583 +34867 4376 4174 4048 6952 +34868 2069 198 199 1348 +34869 3834 289 288 2066 +34870 3455 3418 3454 7084 +34871 2589 2777 2827 6968 +34872 5420 5370 5388 6948 +34873 5124 5302 5355 6899 +34874 1512 1991 187 1440 +34875 3998 277 3926 1992 +34876 2432 2397 3120 7041 +34877 3840 3774 3699 6873 +34878 1354 1288 1213 6874 +34879 2807 2408 3086 7116 +34880 5462 5542 5527 6875 +34881 5685 5620 5700 6878 +34882 300 299 2272 7143 +34883 4734 29 532 7098 +34884 230 3616 3651 6928 +34885 323 324 2292 3809 +34886 1336 1212 1373 6897 +34887 5496 5457 5510 6818 +34888 5654 5615 5668 6819 +34889 4347 4170 4029 7187 +34890 2467 2482 2468 6887 +34891 2398 2400 2470 7096 +34892 5545 5461 5482 7010 +34893 5640 5703 5619 7012 +34894 2850 3174 2851 7050 +34895 1825 1741 2119 6726 +34896 4857 4909 4912 7037 +34897 2699 2892 3523 6742 +34898 4910 4960 4926 7109 +34899 5205 5206 5171 7197 +34900 5481 5448 5560 6852 +34901 5639 5606 5718 6850 +34902 1356 1310 1187 6476 +34903 1946 1718 1837 6673 +34904 3526 2873 3568 6910 +34905 2234 2242 345 6990 +34906 615 4563 4862 6976 +34907 459 5506 5582 7085 +34908 1414 1380 1192 6825 +34909 2295 2343 2346 6519 +34910 4625 4623 5109 7140 +34911 3586 3656 3626 6715 +34912 3549 3423 3410 7158 +34913 2448 2662 2661 7174 +34914 4909 4910 4912 7109 +34915 343 2248 342 7202 +34916 1982 2030 1806 7122 +34917 4533 4560 4499 7164 +34918 404 405 2447 3802 +34919 3272 3401 2875 6668 +34920 1660 1921 2105 7069 +34921 530 4562 531 6938 +34922 2237 2229 313 7180 +34923 316 2225 317 7213 +34924 1409 1484 1362 6984 +34925 3895 3970 3848 6983 +34926 292 2202 293 6911 +34927 4835 4906 4907 6849 +34928 2503 2479 415 6998 +34929 2726 3120 2771 7110 +34930 4719 4762 4759 7145 +34931 395 3951 3835 7023 +34932 2420 3127 2762 7064 +34933 2175 1989 1801 6833 +34934 3410 3423 3311 7158 +34935 2087 1769 1853 7057 +34936 3537 3231 3335 6941 +34937 2380 2575 2381 7107 +34938 4738 5012 555 7150 +34939 5552 5492 5445 6922 +34940 5710 5650 5603 6923 +34941 3688 3848 3884 7054 +34942 5557 453 5495 6895 +34943 2771 2724 2726 7110 +34944 5601 5668 5651 6865 +34945 5510 5493 5443 6866 +34946 443 3650 444 6768 +34947 3888 411 2714 2726 +34948 1991 247 16 1440 +34949 3926 21 320 1992 +34950 3729 3874 3950 6932 +34951 1464 1243 1388 6931 +34952 2444 2390 2388 7186 +34953 1300 160 159 2538 +34954 3766 3695 3943 7002 +34955 1457 1280 1209 7004 +34956 5381 5433 5376 7066 +34957 1831 1676 2143 7074 +34958 2206 2208 2210 6805 +34959 3866 3967 3805 6924 +34960 4437 4155 4429 6714 +34961 4460 4249 4042 6858 +34962 4641 4642 536 6999 +34963 2580 2581 2535 7127 +34964 5516 5440 5581 7200 +34965 5674 5598 5739 7199 +34966 1950 2046 1763 6778 +34967 3001 3072 3071 7152 +34968 5435 633 632 7038 +34969 180 181 1621 1321 +34970 5708 490 491 6996 +34971 3516 3216 3054 7120 +34972 5455 5513 5541 6907 +34973 1350 192 191 1828 +34974 3836 282 281 1829 +34975 2678 2677 2676 6920 +34976 1287 1493 1184 6771 +34977 3670 3773 3979 6774 +34978 5712 5750 5648 6594 +34979 5592 5490 5554 6593 +34980 2678 2979 2980 6920 +34981 1997 2073 1767 6975 +34982 1197 1391 1351 6974 +34983 3941 3707 3836 7025 +34984 1221 1350 1455 7024 +34985 2380 2618 2575 7107 +34986 4954 4973 4653 7022 +34987 3896 3934 3782 6736 +34988 1532 1623 1619 7082 +34989 5715 493 5653 6881 +34990 4024 4227 4189 7131 +34991 313 2229 314 7180 +34992 4435 4213 4137 7015 +34993 5664 5740 499 7071 +34994 1931 1765 2055 7033 +34995 2455 419 2494 6927 +34996 2481 2482 2467 6887 +34997 4734 609 29 7098 +34998 2684 2659 2685 7093 +34999 2292 2206 2210 6805 +35000 1920 1694 1893 6677 +35001 1623 1532 276 7082 +35002 2714 410 411 3888 +35003 554 5012 5013 7150 +35004 1680 1860 1880 7105 +35005 3608 3643 216 7062 +35006 182 1531 1449 1323 +35007 4765 4985 4830 7149 +35008 2903 3173 3196 6969 +35009 3247 3245 3249 6966 +35010 413 2432 3921 3863 +35011 1435 172 2433 1377 +35012 4186 4384 4468 7087 +35013 1402 171 170 2725 +35014 604 603 4638 6617 +35015 3888 412 411 2726 +35016 273 2021 274 7212 +35017 2719 167 168 1326 +35018 5599 5655 5727 6960 +35019 5441 5497 5569 6959 +35020 4921 4917 4893 6659 +35021 3458 3401 3272 6668 +35022 3946 3738 3852 7013 +35023 562 5696 5639 7137 +35024 4857 4975 4909 7037 +35025 4473 4319 4095 7095 +35026 3719 3910 3818 6971 +35027 1424 1332 1233 6972 +35028 3250 3426 3133 7019 +35029 1653 1927 2076 6906 +35030 4027 4475 4212 7072 +35031 5730 5697 5622 6780 +35032 5572 5539 5464 6783 +35033 392 2913 3974 2728 +35034 3759 3799 3700 6731 +35035 1214 1273 1313 6732 +35036 4765 4976 4985 7149 +35037 3863 3715 3764 7108 +35038 3636 3638 3584 6809 +35039 2662 2895 2839 7175 +35040 3855 278 277 2067 +35041 4903 4839 4838 7123 +35042 2496 2708 3246 7128 +35043 4442 4064 4147 7203 +35044 2044 1972 1692 7091 +35045 3811 3703 3977 7119 +35046 4236 4029 4170 7187 +35047 3913 321 22 2197 +35048 2772 2773 2763 6855 +35049 4174 4314 4048 6952 +35050 2806 2864 2859 7125 +35051 5484 5451 5534 7113 +35052 5642 5609 5692 7114 +35053 3644 420 3601 6797 +35054 397 396 3778 2660 +35055 2025 2172 1658 7026 +35056 1978 1855 1707 7201 +35057 155 154 1349 2587 +35058 3748 3837 3877 7193 +35059 2348 2325 371 7063 +35060 170 2720 1402 2725 +35061 1495 1798 189 2068 +35062 1800 2067 279 3981 +35063 5241 4817 4751 7067 +35064 1808 1672 1946 6958 +35065 3788 3891 3972 6604 +35066 3766 3670 3829 7003 +35067 1280 1184 1343 7005 +35068 2166 1897 272 6988 +35069 4913 4979 4915 7029 +35070 3127 3172 2762 7064 +35071 1344 153 152 2923 +35072 1399 418 8 2508 +35073 4382 4294 4032 7146 +35074 5617 5679 5686 6640 +35075 5459 5521 5528 6641 +35076 5484 5553 5451 7113 +35077 5609 5642 5711 7114 +35078 4064 4218 4302 6669 +35079 1530 16 247 1431 +35080 3551 3221 3220 7142 +35081 3398 3400 3464 6870 +35082 4461 4114 4320 7153 +35083 3377 3374 3376 7166 +35084 244 243 3843 1619 +35085 204 17 1297 2294 +35086 4638 4639 604 6617 +35087 2186 1904 1686 6946 +35088 5141 5351 5135 6921 +35089 2214 2218 2217 7053 +35090 5636 5738 5671 6743 +35091 2711 157 158 1329 +35092 2503 2394 2479 6998 +35093 4555 4525 4498 7136 +35094 4857 4993 4975 7037 +35095 4764 4602 4603 7194 +35096 2372 211 212 1345 +35097 1346 98 97 3662 +35098 2720 169 170 1402 +35099 3298 3080 3195 7179 +35100 1805 1673 2003 7059 +35101 2859 2865 2806 7125 +35102 4076 4242 4294 6949 +35103 615 614 4563 6976 +35104 609 5580 29 6721 +35105 2173 1656 2023 7156 +35106 2137 1862 2126 6671 +35107 4908 4870 4876 7147 +35108 3710 3849 3995 6886 +35109 1913 1688 1876 6961 +35110 1831 2059 1676 7074 +35111 1382 291 17 1993 +35112 5743 5698 495 6867 +35113 5540 455 5585 6868 +35114 2004 1750 2070 7129 +35115 2431 2814 2569 7045 +35116 2292 324 3917 3809 +35117 5343 5249 5344 7214 +35118 3763 390 389 2481 +35119 1277 149 148 2474 +35120 30 557 4536 7089 +35121 3327 2463 2464 7206 +35122 2619 2621 3477 7097 +35123 1243 1443 1279 6802 +35124 3765 3729 3929 6801 +35125 1565 1567 233 6993 +35126 353 2340 354 6889 +35127 2340 2344 354 6889 +35128 256 1854 257 6779 +35129 2828 162 163 1379 +35130 2136 1629 1872 7130 +35131 1990 20 276 3868 +35132 402 2798 3279 6947 +35133 4559 4534 4499 7164 +35134 2686 2684 2685 7093 +35135 1583 1578 1588 7051 +35136 1570 231 1573 7126 +35137 1528 246 19 3912 +35138 450 451 5550 7094 +35139 4189 4227 4109 7131 +35140 408 409 2712 3812 +35141 4926 4912 4910 7109 +35142 1671 1826 1950 6992 +35143 3529 3576 3412 7138 +35144 4245 4467 4185 6847 +35145 1181 1305 1385 6956 +35146 1195 1355 1477 7205 +35147 4101 4366 4195 7099 +35148 3871 3667 3791 7031 +35149 5283 5282 5281 7135 +35150 1646 1971 1973 6740 +35151 1390 1200 1271 6979 +35152 3686 3757 3876 6978 +35153 2080 1876 1688 6961 +35154 1530 183 16 1431 +35155 1727 2000 1882 6601 +35156 1297 1357 204 2294 +35157 2166 1790 1897 6988 +35158 3304 3495 3305 6609 +35159 2790 3086 2408 7116 +35160 2060 1683 1802 7032 +35161 2068 187 188 1369 +35162 4235 4382 4032 7146 +35163 403 404 2449 3865 +35164 5342 5247 5263 6842 +35165 1802 1747 2060 7032 +35166 293 2202 2216 6911 +35167 3551 3220 3224 7142 +35168 3661 448 449 3832 +35169 151 150 1436 2706 +35170 4183 4102 4358 7157 +35171 1301 1208 1414 6997 +35172 321 322 2198 3807 +35173 1409 1362 1239 6984 +35174 3895 3848 3725 6983 +35175 5151 5241 4751 7067 +35176 4463 4187 4287 7046 +35177 1181 1385 1358 6956 +35178 3844 3667 3871 7031 +35179 3513 2593 2595 7173 +35180 438 3653 439 7048 +35181 1271 1461 1494 7011 +35182 3757 3947 3980 7009 +35183 2857 2860 2859 7124 +35184 3795 3703 3811 7119 +35185 2070 1629 2004 7129 +35186 544 4816 543 6832 +35187 3195 3080 3085 7179 +35188 3815 398 3879 2659 +35189 1772 2152 2146 7115 +35190 4352 4279 4452 7185 +35191 4053 4468 4384 7087 +35192 4011 4162 4457 7141 +35193 3831 356 355 2371 +35194 274 1546 273 7212 +35195 4981 4852 4986 6951 +35196 1659 1989 2175 6833 +35197 2858 3317 3152 6744 +35198 4360 4224 4132 6944 +35199 4889 4973 4954 7022 +35200 3727 3827 3937 6900 +35201 2594 2818 2592 6973 +35202 555 5012 554 7150 +35203 5500 5573 5451 6953 +35204 5731 5609 5658 6954 +35205 3249 3253 3247 6966 +35206 4300 4155 4067 7028 +35207 2130 1805 1930 7177 +35208 3637 3601 419 7090 +35209 2409 2790 2408 7116 +35210 2157 1820 2117 7176 +35211 2586 2585 2615 7023 +35212 2067 3855 278 3981 +35213 4757 4781 562 6829 +35214 1357 205 2294 2293 +35215 1322 207 206 2211 +35216 1834 1887 1779 7118 +35217 1835 1886 1778 7171 +35218 2863 2861 2862 7117 +35219 2663 2932 2553 7068 +35220 3830 393 3974 2729 +35221 562 563 5696 7137 +35222 1832 2146 2152 7115 +35223 5590 615 616 6828 +35224 5748 566 567 6827 +35225 342 2367 2332 6762 +35226 4200 4051 4407 7188 +35227 536 537 4641 6999 +35228 3913 22 354 2197 +35229 2479 414 415 3764 +35230 2470 173 174 1278 +35231 1246 1360 1520 6788 +35232 3846 4006 3732 6821 +35233 5019 4992 538 6798 +35234 4713 4711 4735 6982 +35235 1357 206 205 2293 +35236 1834 1779 2191 7118 +35237 2569 2429 2431 7045 +35238 4317 4211 4077 6942 +35239 1778 2190 1835 7171 +35240 5045 4856 5152 7211 +35241 30 4536 558 7089 +35242 4506 4533 4534 7164 +35243 3132 3286 2486 6808 +35244 2752 2425 2427 7000 +35245 4200 4283 4051 7188 +35246 500 4276 501 6917 +35247 5656 5717 5641 6892 +35248 5498 5559 5483 6893 +35249 278 279 2067 3981 +35250 3747 3969 3862 6947 +35251 4065 4465 4193 7184 +35252 2896 2809 3303 7065 +35253 2405 2404 2403 6914 +35254 2098 1952 1702 7006 +35255 535 4532 536 7076 +35256 3412 3411 3529 7138 +35257 3923 19 242 3633 +35258 2150 1920 1634 7192 +35259 1626 1531 1530 6925 +35260 2344 22 354 3924 +35261 1787 2026 1956 6806 +35262 4081 4182 4329 6991 +35263 2579 2508 2578 6848 +35264 5281 5282 5341 7135 +35265 1274 1468 1514 6881 +35266 163 164 3159 1316 +35267 4382 4235 4069 7183 +35268 3992 3913 3745 7169 +35269 5097 4637 4941 7035 +35270 1465 154 153 2588 +35271 3427 3361 3488 7036 +35272 4594 551 4997 6916 +35273 1528 19 242 3912 +35274 3969 403 402 2798 +35275 156 155 1292 3218 +35276 1261 1379 1483 7008 +35277 2507 23 386 3885 +35278 5489 5445 5563 6584 +35279 5721 5647 5603 6583 +35280 3218 156 2990 1393 +35281 3808 246 245 1529 +35282 317 1896 316 7213 +35283 3954 4000 3760 6895 +35284 188 1495 2068 1369 +35285 4768 4784 4767 7189 +35286 4874 4828 4873 7204 +35287 2178 1962 1699 6918 +35288 4887 4678 4676 7159 +35289 148 147 1363 2500 +35290 3849 389 388 2502 +35291 3735 3805 3829 7085 +35292 2608 409 410 3873 +35293 1531 182 183 1323 +35294 2577 2507 2576 7191 +35295 4261 4069 4349 7183 +35296 3302 2870 2690 7077 +35297 2869 2867 2868 6929 +35298 4768 4619 4784 7189 +35299 4319 4473 4129 7095 +35300 2507 417 23 3885 +35301 1399 8 176 2508 +35302 1623 20 243 3783 +35303 407 408 2559 3942 +35304 4065 4193 4252 7184 +35305 4147 4064 4302 7203 +35306 1319 1343 1249 7071 +35307 1495 189 188 2068 +35308 2973 166 167 1456 +35309 490 5708 5702 6996 +35310 3617 3654 234 6943 +35311 3782 3898 3725 7190 +35312 4436 4182 4081 6991 +35313 2975 2447 405 3946 +35314 4235 4349 4069 7183 +35315 4806 4807 4961 7163 +35316 394 393 3830 2729 +35317 1438 211 18 2341 +35318 4224 4313 4480 7132 +35319 4534 4533 4499 7164 +35320 4264 4120 4402 7100 +35321 5550 5544 450 7094 +35322 3062 3275 3276 7198 +35323 2157 2117 1739 7176 +35324 3618 3623 3599 6894 +35325 3980 3947 3699 7009 +35326 1494 1461 1213 7011 +35327 4027 4212 4466 7072 +35328 5101 4946 4645 7106 +35329 2604 168 169 1387 +35330 3634 449 24 3908 +35331 174 175 2499 1364 +35332 415 416 2503 3850 +35333 4879 4706 4853 7030 +35334 5235 5138 5137 6845 +35335 1427 18 207 2211 +35336 4195 4366 4018 7099 +35337 2396 413 414 3863 +35338 2400 172 173 1377 +35339 4114 4408 4320 7153 +35340 2424 2571 2632 7161 +35341 3633 3661 3585 7083 +35342 1462 194 193 1885 +35343 283 284 1884 3948 +35344 2728 3974 393 2729 +35345 2343 212 15 1422 +35346 2900 2634 3118 7042 +35347 4603 5029 4764 7194 +35348 2344 356 22 3924 +35349 1357 205 204 2294 +35350 1624 9 180 1426 +35351 392 391 3922 2913 +35352 3923 448 19 3633 +35353 4067 4268 4431 7210 +35354 322 323 2209 3935 +35355 1891 190 191 1455 +35356 280 281 1892 3941 +35357 2295 2345 2341 6902 +35358 3707 3838 4008 7208 +35359 1352 1522 1221 7209 +35360 3974 393 392 2728 +35361 1831 2143 1749 7074 +35362 3517 3334 3452 7144 +35363 4486 4336 4107 7018 +35364 2699 3406 2697 7196 +35365 3742 3989 3907 7044 +35366 4236 4377 4029 7187 +35367 197 1423 1513 1935 +35368 3909 3999 287 1936 +35369 279 280 1934 3798 +35370 1933 189 190 1312 +35371 1991 16 187 1440 +35372 3926 277 21 1992 +35373 1903 284 285 3949 +35374 98 9 3636 1437 +35375 97 8 1421 3635 +35376 3907 355 23 2342 +35377 1530 1627 1626 6925 +35378 1378 150 149 2475 +35379 395 394 3951 2586 +35380 2088 1921 1660 7069 +35381 1460 165 164 2991 +35382 4309 4486 4107 7018 +35383 15 146 2618 1400 +35384 397 2660 3879 2659 +35385 405 406 2975 3946 +35386 1513 198 197 1935 +35387 3999 288 287 1936 +35388 3864 391 390 2482 +35389 416 417 2577 3994 +35390 1508 176 175 2579 +35391 1902 194 195 1463 +35392 161 162 2831 1483 +35393 412 413 2432 3921 +35394 2433 171 172 1435 +35395 3886 387 24 2617 +35396 1382 17 200 1993 +35397 1990 290 20 3868 +35398 1407 159 158 3203 +35399 387 388 2572 3995 +35400 2575 146 147 1509 +35401 3917 21 324 2292 +35402 3893 400 399 2871 +35403 193 192 1446 2084 +35404 3932 283 282 2085 +35405 3879 398 397 2659 +35406 1488 152 151 3035 +35407 156 157 2990 1393 +35408 1622 181 182 1449 +35409 6161 5927 7168 2601 +35410 6161 7168 5927 5843 +35411 3015 7168 5927 2601 +35412 3015 5927 7168 5843 +35413 6334 6209 349 6116 +35414 6334 349 6209 6550 +35415 6708 5311 5257 5923 +35416 6708 5257 5311 5176 +35417 6908 5980 3385 5821 +35418 6908 3385 5980 6367 +35419 7192 4298 4073 6066 +35420 7192 4073 4298 5935 +35421 6237 4793 4800 5058 +35422 6237 4800 4793 5886 +35423 5911 3043 3033 3019 +35424 5911 3033 3043 5772 +35425 6858 1998 5872 5871 +35426 6858 5872 1998 5802 +35427 5975 2768 5902 3110 +35428 5975 5902 2768 5755 +35429 4295 6064 4043 4445 +35430 4043 6064 4295 5818 +35431 7146 1883 1947 1701 +35432 7146 1947 1883 6556 +35433 6260 4545 4518 6092 +35434 6260 4518 4545 476 +35435 7115 4427 5959 5906 +35436 7115 5959 4427 5958 +35437 7000 617 7189 4768 +35438 7000 7189 617 5916 +35439 7192 6073 4073 5935 +35440 7192 4073 6073 6677 +35441 5866 5038 6259 4790 +35442 5866 6259 5038 5794 +35443 4398 5935 5837 4021 +35444 5837 5935 4398 5838 +35445 6967 422 6022 3646 +35446 6967 6022 422 5783 +35447 2694 6390 3250 3076 +35448 3250 6390 2694 5860 +35449 6239 5212 6024 5022 +35450 6239 6024 5212 5787 +35451 5196 6024 5212 5022 +35452 5196 5212 6024 5787 +35453 6274 6665 571 5843 +35454 571 6665 6274 5882 +35455 5763 7115 4343 5958 +35456 5763 4343 7115 4125 +35457 4427 4343 7115 5958 +35458 4427 7115 4343 4125 +35459 6001 3208 5870 5897 +35460 6001 5870 3208 2813 +35461 3207 5870 3208 5897 +35462 3207 3208 5870 2813 +35463 6104 4953 5051 4918 +35464 6104 5051 4953 5776 +35465 6650 3018 5903 432 +35466 6650 5903 3018 5911 +35467 6156 2140 6316 1771 +35468 6156 6316 2140 5845 +35469 7022 2613 2906 6252 +35470 7022 2906 2613 2905 +35471 6409 6667 469 6408 +35472 469 6667 6409 6391 +35473 6855 4901 5850 579 +35474 6855 5850 4901 6108 +35475 6366 5850 4901 579 +35476 6366 4901 5850 6108 +35477 6671 5876 4226 6146 +35478 6671 4226 5876 6396 +35479 6992 4401 4099 4173 +35480 6992 4099 4401 6230 +35481 7203 1681 6663 6127 +35482 7203 6663 1681 6420 +35483 4516 7086 6520 4509 +35484 6520 7086 4516 5988 +35485 2053 5838 1766 1995 +35486 1766 5838 2053 5837 +35487 6193 4115 6132 4321 +35488 6193 6132 4115 6144 +35489 2454 6848 5875 2578 +35490 5875 6848 2454 5805 +35491 5875 2506 2454 2578 +35492 2454 2506 5875 5805 +35493 7074 2084 1828 1749 +35494 7074 1828 2084 5762 +35495 6923 1347 1524 1180 +35496 6923 1524 1347 6903 +35497 6922 3833 4010 3666 +35498 6922 4010 3833 6904 +35499 6895 3846 3684 3954 +35500 6895 3684 3846 6821 +35501 7184 1964 6706 6429 +35502 7184 6706 1964 6441 +35503 6627 2889 6103 6095 +35504 6627 6103 2889 3064 +35505 6431 4671 6823 5777 +35506 6431 6823 4671 4672 +35507 5811 2705 2917 2757 +35508 5811 2917 2705 5785 +35509 2148 7033 6026 1931 +35510 6026 7033 2148 5769 +35511 5950 3982 3793 3728 +35512 5950 3793 3982 5949 +35513 6758 5720 6637 5660 +35514 6758 6637 5720 6675 +35515 6757 5562 6638 5502 +35516 6757 6638 5562 6676 +35517 6494 4446 6093 5848 +35518 6494 6093 4446 4484 +35519 4198 6093 4446 5848 +35520 4198 4446 6093 4484 +35521 2756 6060 3006 2775 +35522 3006 6060 2756 5811 +35523 6244 6357 1948 1762 +35524 1948 6357 6244 5769 +35525 1948 2165 6244 1762 +35526 6244 2165 1948 5769 +35527 5941 4955 6660 5819 +35528 5941 6660 4955 4922 +35529 5956 5153 4935 5846 +35530 5956 4935 5153 5046 +35531 6259 3543 6617 5893 +35532 6259 6617 3543 3017 +35533 2689 6617 3543 5893 +35534 2689 3543 6617 3017 +35535 5834 3066 6941 3140 +35536 5834 6941 3066 5773 +35537 3537 6941 3066 3140 +35538 3537 3066 6941 5773 +35539 6881 1360 1198 1468 +35540 6881 1198 1360 6788 +35541 6517 3056 3243 2941 +35542 6517 3243 3056 5824 +35543 5970 4811 4957 4956 +35544 5970 4957 4811 5927 +35545 6302 3595 6456 3652 +35546 6302 6456 3595 6251 +35547 5935 1995 6079 5838 +35548 5935 6079 1995 1725 +35549 1926 6079 1995 5838 +35550 1926 1995 6079 1725 +35551 4516 6520 4550 4501 +35552 4550 6520 4516 5988 +35553 6070 3222 3223 5849 +35554 6070 3223 3222 3288 +35555 6267 3074 5834 3136 +35556 6267 5834 3074 6103 +35557 2764 5985 2992 2759 +35558 2992 5985 2764 5902 +35559 7130 4046 5853 5952 +35560 7130 5853 4046 5807 +35561 6109 4922 4924 5079 +35562 6109 4924 4922 5941 +35563 6815 3163 5984 5863 +35564 6815 5984 3163 2988 +35565 6386 1996 5951 1722 +35566 6386 5951 1996 5808 +35567 6840 5474 5529 6620 +35568 6840 5529 5474 5553 +35569 6841 5632 5687 6619 +35570 6841 5687 5632 5711 +35571 6934 4340 4058 6066 +35572 6934 4058 4340 4134 +35573 6336 5143 5306 6272 +35574 6336 5306 5143 4634 +35575 6176 2106 5891 1923 +35576 6176 5891 2106 6175 +35577 1724 5891 2106 1923 +35578 1724 2106 5891 6175 +35579 4820 6051 546 547 +35580 546 6051 4820 5911 +35581 5837 7192 4021 5935 +35582 5837 4021 7192 4208 +35583 4298 4021 7192 5935 +35584 4298 7192 4021 4208 +35585 7122 4417 5915 5876 +35586 7122 5915 4417 4050 +35587 6864 5915 4417 5876 +35588 6864 4417 5915 4050 +35589 6985 7043 5873 4944 +35590 5873 7043 6985 6590 +35591 6617 2688 363 2689 +35592 6617 363 2688 5880 +35593 6793 608 6309 5408 +35594 6793 6309 608 5854 +35595 6515 5987 437 5785 +35596 6515 437 5987 6421 +35597 6679 589 5404 590 +35598 6679 5404 589 6295 +35599 6286 2094 1996 5808 +35600 6286 1996 2094 1651 +35601 6621 5908 5131 5883 +35602 6621 5131 5908 6047 +35603 5925 3089 5926 3088 +35604 5925 5926 3089 5832 +35605 6282 3004 3204 3367 +35606 6282 3204 3004 6164 +35607 6231 3560 6216 2866 +35608 6231 6216 3560 5892 +35609 6442 1569 1563 1564 +35610 6442 1563 1569 6303 +35611 7179 2926 2955 3080 +35612 7179 2955 2926 5828 +35613 6062 2980 6719 2747 +35614 6062 6719 2980 5780 +35615 6585 634 5995 28 +35616 6585 5995 634 6416 +35617 6799 5886 2478 6237 +35618 6799 2478 5886 5917 +35619 6334 507 5393 5421 +35620 6334 5393 507 6116 +35621 6606 5042 6013 5857 +35622 6606 6013 5042 4748 +35623 6204 4163 4262 5840 +35624 6204 4262 4163 4478 +35625 6792 2841 3091 6191 +35626 6792 3091 2841 3090 +35627 4738 6764 556 4728 +35628 556 6764 4738 5783 +35629 6604 5530 6826 619 +35630 6604 6826 5530 6534 +35631 620 6826 5530 619 +35632 5830 2524 2505 2379 +35633 5830 2505 2524 6933 +35634 6327 264 6094 6093 +35635 6327 6094 264 1575 +35636 6727 3124 2537 2540 +35637 6727 2537 3124 5795 +35638 5939 601 4761 600 +35639 5939 4761 601 5863 +35640 6442 267 266 1564 +35641 6442 266 267 6407 +35642 7052 4798 4799 6122 +35643 7052 4799 4798 4800 +35644 6857 378 6295 379 +35645 6857 6295 378 6017 +35646 7098 2378 5809 6905 +35647 7098 5809 2378 6417 +35648 6777 5368 6141 6309 +35649 6777 6141 5368 5412 +35650 6504 2527 5847 2978 +35651 6504 5847 2527 6155 +35652 2846 5847 2527 2978 +35653 2846 2527 5847 6155 +35654 6093 1977 265 5946 +35655 6093 265 1977 1864 +35656 6389 2751 2660 2715 +35657 6389 2660 2751 5916 +35658 6443 347 6119 6068 +35659 6443 6119 347 2236 +35660 6414 5879 7076 5017 +35661 7076 5879 6414 6020 +35662 7076 535 6414 5017 +35663 6414 535 7076 6020 +35664 5809 3634 6905 447 +35665 5809 6905 3634 5753 +35666 3632 6905 3634 447 +35667 3632 3634 6905 5753 +35668 6867 5661 496 5743 +35669 6867 496 5661 6528 +35670 6868 5503 456 5585 +35671 6868 456 5503 6529 +35672 6544 2102 6127 5764 +35673 6544 6127 2102 1817 +35674 5907 3042 5903 5772 +35675 5907 5903 3042 3096 +35676 7187 1660 1813 6270 +35677 7187 1813 1660 1937 +35678 1782 6880 2170 2090 +35679 2170 6880 1782 6090 +35680 7124 2852 2856 6188 +35681 7124 2856 2852 2857 +35682 7127 4804 4803 4802 +35683 7127 4803 4804 5859 +35684 5914 4744 4888 4890 +35685 5914 4888 4744 5861 +35686 5913 3555 2654 2696 +35687 5913 2654 3555 5757 +35688 6037 2654 5913 5757 +35689 6553 6037 5913 5757 +35690 585 6981 584 4737 +35691 584 6981 585 6115 +35692 6385 1733 6071 1969 +35693 6385 6071 1733 5764 +35694 1818 6071 1733 1969 +35695 1818 1733 6071 5764 +35696 6578 2047 1650 1904 +35697 6578 1650 2047 5756 +35698 7087 4139 5958 6076 +35699 7087 5958 4139 4393 +35700 6614 4443 5890 4355 +35701 6614 5890 4443 6146 +35702 4148 5890 4443 4355 +35703 4148 4443 5890 6146 +35704 7168 2392 6273 6161 +35705 7168 6273 2392 3082 +35706 6989 3784 6821 3717 +35707 6989 6821 3784 6584 +35708 6295 2369 379 2333 +35709 6295 379 2369 6045 +35710 6994 1298 6788 1231 +35711 6994 6788 1298 6583 +35712 6225 4292 4039 6176 +35713 6225 4039 4292 4438 +35714 6058 4960 5112 4687 +35715 6058 5112 4960 5908 +35716 3289 6070 3222 3288 +35717 3222 6070 3289 5814 +35718 6679 2368 6295 2308 +35719 6679 6295 2368 6296 +35720 2312 6295 2368 2308 +35721 2312 2368 6295 6296 +35722 7093 3723 3893 6038 +35723 7093 3893 3723 3815 +35724 6129 3554 6870 5765 +35725 6129 6870 3554 3466 +35726 6385 4426 6033 4138 +35727 6385 6033 4426 5877 +35728 6683 4959 5918 5302 +35729 6683 5918 4959 6217 +35730 4415 6055 6386 4209 +35731 6386 6055 4415 6026 +35732 6072 1642 7177 2017 +35733 6072 7177 1642 6071 +35734 6115 5411 6067 5382 +35735 6115 6067 5411 5822 +35736 6125 1517 7014 5998 +35737 6125 7014 1517 1215 +35738 6609 5028 6522 4659 +35739 6609 6522 5028 6243 +35740 6695 2997 6246 2999 +35741 6695 6246 2997 5887 +35742 6213 3013 2894 2580 +35743 6213 2894 3013 6069 +35744 6346 6005 6899 5918 +35745 6346 6899 6005 5123 +35746 5347 6899 6005 5918 +35747 5347 6005 6899 5123 +35748 6957 3812 6807 6128 +35749 6957 6807 3812 3873 +35750 7099 4139 5763 4343 +35751 7099 5763 4139 6076 +35752 7210 2086 7028 6403 +35753 7210 7028 2086 6019 +35754 3059 7120 3060 3216 +35755 3060 7120 3059 6707 +35756 4827 5898 4950 4826 +35757 4827 4950 5898 6750 +35758 6568 6597 478 6194 +35759 478 6597 6568 6254 +35760 2985 6656 2634 2633 +35761 2634 6656 2985 5910 +35762 6368 7170 1857 1905 +35763 6368 1857 7170 5858 +35764 2048 1857 7170 1905 +35765 2048 7170 1857 5858 +35766 6711 3300 3207 5870 +35767 6711 3207 3300 3293 +35768 6512 2911 3099 6166 +35769 6512 3099 2911 2909 +35770 6925 1311 5803 1216 +35771 6925 5803 1311 5804 +35772 5970 3161 6217 5927 +35773 2603 3161 6217 3469 +35774 2603 6217 3161 5927 +35775 7072 1705 1871 1965 +35776 7072 1871 1705 6242 +35777 7143 523 6354 6329 +35778 7143 6354 523 6193 +35779 7034 6147 2291 6287 +35780 7034 2291 6147 6510 +35781 6090 2188 6880 1782 +35782 6090 6880 2188 5871 +35783 6715 4496 6456 4546 +35784 6715 6456 4496 6092 +35785 4521 6456 4496 4546 +35786 4521 4496 6456 6092 +35787 6376 4163 6204 5840 +35788 6376 6204 4163 4332 +35789 7101 2624 3098 6131 +35790 3098 2624 7101 5874 +35791 3098 6166 7101 6131 +35792 7101 6166 3098 5874 +35793 6701 1238 6841 1420 +35794 6701 6841 1238 6619 +35795 5978 5038 6872 4789 +35796 5978 6872 5038 5794 +35797 6371 5042 6013 4747 +35798 6371 6013 5042 5857 +35799 6137 5085 6269 5831 +35800 6137 6269 5085 5326 +35801 6287 327 7034 6141 +35802 6287 7034 327 2196 +35803 6621 5345 6400 5166 +35804 6621 6400 5345 6047 +35805 7077 2692 2691 2690 +35806 7077 2691 2692 6514 +35807 6923 5731 5603 6903 +35808 6923 5603 5731 5650 +35809 5573 6922 5445 5492 +35810 5445 6922 5573 6904 +35811 6737 5054 5120 5990 +35812 6737 5120 5054 4940 +35813 6740 4237 4079 4463 +35814 6740 4079 4237 5954 +35815 6652 3582 3432 5815 +35816 6652 3432 3582 3375 +35817 1597 6463 1596 1603 +35818 1596 6463 1597 6202 +35819 6899 3281 5918 6683 +35820 6899 5918 3281 6346 +35821 7072 1965 5947 5960 +35822 7072 5947 1965 1871 +35823 1649 5947 1965 5960 +35824 1649 1965 5947 1871 +35825 7156 4378 490 491 +35826 7156 490 4378 6348 +35827 6446 5025 5886 4773 +35828 6446 5886 5025 6164 +35829 1753 6681 1965 1966 +35830 1965 6681 1753 5960 +35831 6424 2755 6576 2986 +35832 6424 6576 2755 5776 +35833 3503 6717 6162 2393 +35834 6162 6717 3503 5814 +35835 6885 2925 5862 5758 +35836 6885 5862 2925 2838 +35837 6363 3273 6106 5842 +35838 6363 6106 3273 3320 +35839 6602 1333 6775 6533 +35840 6602 6775 1333 1302 +35841 6191 2842 6792 2841 +35842 6191 6792 2842 5931 +35843 3090 6792 2842 2841 +35844 3090 2842 6792 5931 +35845 6796 1707 6142 1925 +35846 6796 6142 1707 6403 +35847 1384 1208 6741 1496 +35848 1384 6741 1208 6997 +35849 5900 6741 1208 1496 +35850 5900 1208 6741 6997 +35851 1282 6675 1501 1452 +35852 1501 6675 1282 6540 +35853 3768 6676 3987 3938 +35854 3987 6676 3768 6538 +35855 6505 2258 5992 318 +35856 6505 5992 2258 6383 +35857 6233 3597 6169 5781 +35858 6233 6169 3597 3663 +35859 6299 7211 2664 5898 +35860 6299 2664 7211 6945 +35861 3219 2664 7211 5898 +35862 3219 7211 2664 6945 +35863 2519 6454 6646 2472 +35864 6646 6454 2519 5904 +35865 6646 2525 2519 2472 +35866 2519 2525 6646 5904 +35867 1255 6746 6824 1415 +35868 6824 6746 1255 5998 +35869 5984 2568 5863 2573 +35870 5984 5863 2568 5920 +35871 3250 6390 3135 3076 +35872 3250 3135 6390 7019 +35873 6816 4776 6623 6083 +35874 6816 6623 4776 4725 +35875 4746 6623 4776 6083 +35876 4746 4776 6623 4725 +35877 5661 6867 5624 5743 +35878 5624 6867 5661 6703 +35879 5503 6868 5466 5585 +35880 5466 6868 5503 6702 +35881 7171 4175 6167 6168 +35882 7171 6167 4175 6098 +35883 5999 4238 4080 4464 +35884 5999 4080 4238 5955 +35885 6511 2718 2717 5869 +35886 6511 2717 2718 2954 +35887 7214 3457 6210 6304 +35888 7214 6210 3457 5943 +35889 6744 3129 2860 3317 +35890 6744 2860 3129 5983 +35891 6382 3444 3500 6082 +35892 6382 3500 3444 3297 +35893 6329 333 2276 2271 +35894 6329 2276 333 6157 +35895 6119 347 348 6068 +35896 6119 348 347 2228 +35897 6094 264 265 6093 +35898 6094 265 264 1572 +35899 6414 4736 4718 5016 +35900 6414 4718 4736 5887 +35901 6330 5203 4977 5158 +35902 6330 4977 5203 6101 +35903 6792 2517 3091 3090 +35904 6792 3091 2517 6215 +35905 6367 5227 5226 5980 +35906 6367 5226 5227 5072 +35907 6947 6643 6826 5945 +35908 6947 6826 6643 6317 +35909 5939 3254 5938 5937 +35910 5939 5938 3254 3301 +35911 6340 5071 4837 4836 +35912 6340 4837 5071 6065 +35913 2654 6553 5913 2696 +35914 5913 6553 2654 6037 +35915 6706 1917 7006 1702 +35916 6706 7006 1917 6140 +35917 1838 7006 1917 1702 +35918 1838 1917 7006 6140 +35919 6121 541 542 4557 +35920 6121 542 541 5894 +35921 7101 5036 6166 5035 +35922 7101 6166 5036 6131 +35923 7047 4371 5895 6734 +35924 7047 5895 4371 6066 +35925 6385 4017 6071 5764 +35926 6385 6071 4017 4194 +35927 6399 4818 5295 4821 +35928 6399 5295 4818 6035 +35929 6377 4091 6156 6211 +35930 6377 6156 4091 4374 +35931 6432 2180 6356 6032 +35932 6432 6356 2180 1848 +35933 6102 2736 3263 6035 +35934 6102 3263 2736 3569 +35935 6345 6163 7097 6084 +35936 6345 7097 6163 2622 +35937 2620 7097 6163 6084 +35938 2620 6163 7097 2622 +35939 6240 2534 7050 3104 +35940 6240 7050 2534 6214 +35941 6718 7018 2020 6147 +35942 2020 7018 6718 6311 +35943 7183 4112 6357 6139 +35944 7183 6357 4112 4349 +35945 6292 309 2241 2249 +35946 6292 2241 309 6291 +35947 3144 6536 2976 2675 +35948 3144 2976 6536 6651 +35949 6464 219 1610 1608 +35950 6464 1610 219 6462 +35951 6864 4449 4050 5915 +35952 6864 4050 4449 4188 +35953 7178 4481 6558 4223 +35954 7178 6558 4481 6133 +35955 6365 7126 474 6094 +35956 6365 474 7126 6014 +35957 473 474 7126 6094 +35958 473 7126 474 6014 +35959 6082 6513 5252 5220 +35960 5252 6513 6082 5957 +35961 5252 5219 6082 5220 +35962 6082 5219 5252 5957 +35963 2201 6805 2209 2208 +35964 2209 6805 2201 5798 +35965 7212 465 6428 6198 +35966 7212 6428 465 6415 +35967 6005 3014 6346 3057 +35968 6005 6346 3014 5918 +35969 6336 5306 7043 6272 +35970 6336 7043 5306 5365 +35971 6435 5371 5387 6171 +35972 6435 5387 5371 5431 +35973 7106 4643 6154 4645 +35974 7106 6154 4643 6470 +35975 6777 5414 5368 6309 +35976 6777 5368 5414 5381 +35977 7034 2291 2287 2194 +35978 7034 2287 2291 6510 +35979 6681 4415 4097 4370 +35980 6681 4097 4415 6026 +35981 7051 478 477 6308 +35982 7051 477 478 6568 +35983 6632 5671 5613 5699 +35984 7124 2856 3474 6551 +35985 7124 3474 2856 2857 +35986 5412 7066 528 5381 +35987 528 7066 5412 6293 +35988 7088 5861 2833 6437 +35989 7088 2833 5861 5914 +35990 6796 4081 4167 6196 +35991 6796 4167 4081 4367 +35992 6615 2181 6337 1849 +35993 6615 6337 2181 6138 +35994 6493 6673 4023 6175 +35995 4023 6673 6493 6326 +35996 6297 6507 5255 5299 +35997 6297 5255 6507 6288 +35998 5300 5255 6507 5299 +35999 5300 6507 5255 6288 +36000 1666 6624 2104 1788 +36001 2104 6624 1666 6152 +36002 6947 3786 6826 6317 +36003 6947 6826 3786 3862 +36004 3692 6826 3786 6317 +36005 3692 3786 6826 3862 +36006 6400 5361 6210 5363 +36007 6400 6210 5361 5902 +36008 5286 6210 5361 5363 +36009 5286 5361 6210 5902 +36010 6465 1743 1910 2122 +36011 6465 1910 1743 5994 +36012 6766 1187 6741 6476 +36013 6766 6741 1187 1304 +36014 7128 4866 567 5931 +36015 7128 567 4866 566 +36016 6450 2120 1740 1856 +36017 6450 1740 2120 5812 +36018 6685 1898 5852 6098 +36019 6685 5852 1898 2050 +36020 6687 1899 5851 6097 +36021 6687 5851 1899 2049 +36022 6306 3598 6592 6255 +36023 6306 6592 3598 3619 +36024 3622 6592 3598 6255 +36025 3622 3598 6592 3619 +36026 6254 4491 4075 4306 +36027 6254 4075 4491 5885 +36028 6752 3410 6011 2600 +36029 6752 6011 3410 6012 +36030 6754 369 5938 6135 +36031 6754 5938 369 2698 +36032 6612 4754 5256 6117 +36033 6612 5256 4754 5169 +36034 7176 7184 1964 6441 +36035 1964 7184 7176 5996 +36036 6230 4483 6992 5817 +36037 6230 6992 4483 4401 +36038 4173 6992 4483 5817 +36039 4173 4483 6992 4401 +36040 6553 7001 5207 6049 +36041 5207 7001 6553 6105 +36042 6355 4487 505 5992 +36043 6355 505 4487 4310 +36044 2182 6600 2118 1824 +36045 2118 6600 2182 6178 +36046 6715 431 6255 6650 +36047 6715 6255 431 3626 +36048 5073 6496 4985 5276 +36049 4985 6496 5073 5821 +36050 1308 7017 5803 1506 +36051 5803 7017 1308 6232 +36052 6308 4545 6260 6092 +36053 6308 6260 4545 477 +36054 6906 1708 6176 1927 +36055 6906 6176 1708 6225 +36056 6371 6623 2945 5806 +36057 2945 6623 6371 6013 +36058 7062 488 6190 6370 +36059 7062 6190 488 4540 +36060 3538 7020 2930 3046 +36061 2930 7020 3538 5791 +36062 5402 7066 6777 5381 +36063 6777 7066 5402 5813 +36064 7026 2012 6301 1658 +36065 7026 6301 2012 6356 +36066 6526 2963 2784 2407 +36067 6526 2784 2963 6320 +36068 6652 6837 3421 5815 +36069 3421 6837 6652 6347 +36070 6859 4259 4108 4250 +36071 6859 4108 4259 6368 +36072 6438 5200 4962 5201 +36073 6438 4962 5200 6150 +36074 6430 442 3621 3600 +36075 6430 3621 442 6020 +36076 6605 4262 6204 4047 +36077 6605 6204 4262 6027 +36078 6366 2725 2516 2774 +36079 6366 2516 2725 7162 +36080 6577 4118 4295 5818 +36081 6577 4295 4118 4311 +36082 6480 3088 3407 5925 +36083 6480 3407 3088 3251 +36084 7057 2139 6144 1769 +36085 7057 6144 2139 6145 +36086 6372 2641 2640 6010 +36087 6372 2640 2641 3318 +36088 5547 6959 6488 5441 +36089 6488 6959 5547 6877 +36090 6488 5522 5547 5441 +36091 5547 5522 6488 6877 +36092 6960 5705 6487 6879 +36093 6960 6487 5705 5599 +36094 5680 6487 5705 6879 +36095 5680 5705 6487 5599 +36096 2170 6880 1764 2090 +36097 1764 6880 2170 6328 +36098 6445 5013 6739 553 +36099 6445 6739 5013 6054 +36100 6725 5528 6807 6641 +36101 6725 6807 5528 626 +36102 625 6807 5528 6641 +36103 625 5528 6807 626 +36104 3456 5909 3547 3419 +36105 3456 3547 5909 6466 +36106 6490 4036 6029 4325 +36107 6490 6029 4036 6057 +36108 4223 6029 4036 4325 +36109 4223 4036 6029 6057 +36110 6347 5253 6091 6288 +36111 6347 6091 5253 5216 +36112 6921 3341 3358 3357 +36113 6921 3358 3341 6212 +36114 6410 1893 1683 1845 +36115 6410 1683 1893 6352 +36116 6461 2017 2133 1719 +36117 6461 2133 2017 6072 +36118 7089 4733 6927 30 +36119 7089 6927 4733 5969 +36120 6327 1582 1577 6260 +36121 6327 1577 1582 1574 +36122 6690 515 6452 514 +36123 6690 6452 515 6384 +36124 6448 4580 4584 4586 +36125 6448 4584 4580 6404 +36126 7022 5113 7088 6542 +36127 7022 7088 5113 4954 +36128 4140 6406 4060 4225 +36129 4060 6406 4140 6271 +36130 6779 258 2043 257 +36131 6779 2043 258 5991 +36132 1639 7118 5928 1887 +36133 5928 7118 1639 5878 +36134 4769 6273 4788 4787 +36135 4788 6273 4769 6215 +36136 6718 4309 7018 528 +36137 6718 7018 4309 6311 +36138 5107 6951 6267 4852 +36139 6267 6951 5107 6155 +36140 6267 4853 5107 4852 +36141 5107 4853 6267 6155 +36142 6884 4397 6337 4105 +36143 6884 6337 4397 6138 +36144 6054 6526 2406 2407 +36145 6054 2406 6526 6445 +36146 2784 2406 6526 2407 +36147 2784 6526 2406 6445 +36148 7080 471 4544 472 +36149 7080 4544 471 6112 +36150 6857 380 6470 2787 +36151 6857 6470 380 6045 +36152 6882 3746 3998 3971 +36153 6882 3998 3746 5797 +36154 7093 2871 2837 6038 +36155 7093 2837 2871 2685 +36156 2879 6966 3253 3249 +36157 3253 6966 2879 6380 +36158 7163 4963 4998 6086 +36159 7163 4998 4963 4961 +36160 6814 7206 6692 6374 +36161 6692 7206 6814 5901 +36162 6823 3010 5918 3011 +36163 6823 5918 3010 5777 +36164 6208 3092 6361 2902 +36165 6208 6361 3092 5990 +36166 6987 5402 6589 606 +36167 6987 6589 5402 5813 +36168 7092 4338 4339 4127 +36169 7092 4339 4338 6178 +36170 6681 4209 4059 6055 +36171 6681 4059 4209 4370 +36172 7008 3164 2777 2830 +36173 7008 2777 3164 6274 +36174 6830 3865 3988 5945 +36175 6830 3988 3865 3698 +36176 6353 3461 3439 6065 +36177 6353 3439 3461 3492 +36178 6064 2193 6376 1811 +36179 6064 6376 2193 5840 +36180 1751 6376 2193 1811 +36181 1751 2193 6376 5840 +36182 6430 3630 3629 6123 +36183 6430 3629 3630 3600 +36184 6639 2522 2853 2469 +36185 6639 2853 2522 5775 +36186 6325 5399 5380 5397 +36187 6325 5380 5399 6285 +36188 6496 3353 3509 5839 +36189 6496 3509 3353 3356 +36190 6552 3134 6936 6143 +36191 7019 6936 3134 6143 +36192 5795 6775 6665 570 +36193 6665 6775 5795 6728 +36194 6223 4175 4256 6098 +36195 6223 4256 4175 4315 +36196 6547 4048 4189 4314 +36197 6547 4189 4048 5928 +36198 6967 4526 6077 5796 +36199 6967 6077 4526 4508 +36200 6504 4878 4704 6096 +36201 6504 4704 4878 4879 +36202 6770 1404 1394 1207 +36203 6770 1394 1404 6769 +36204 6773 3890 3880 3693 +36205 6773 3880 3890 6772 +36206 7043 6985 4965 4943 +36207 7043 4965 6985 6590 +36208 7156 2010 6249 1656 +36209 7156 6249 2010 6348 +36210 6308 3598 6306 6255 +36211 6308 6306 3598 226 +36212 5747 6701 6841 5643 +36213 6841 6701 5747 6619 +36214 6270 6622 4347 6461 +36215 6270 4347 6622 7187 +36216 1903 6687 3814 1815 +36217 3814 6687 1903 5851 +36218 1902 6685 1328 1814 +36219 1328 6685 1902 5852 +36220 6613 5056 6008 6069 +36221 6613 6008 5056 4999 +36222 4604 6792 4788 4624 +36223 4788 6792 4604 5904 +36224 6226 4458 4262 4062 +36225 6226 4262 4458 5840 +36226 6747 3580 7166 3382 +36227 6747 7166 3580 6130 +36228 6886 3858 5809 3780 +36229 6886 5809 3858 6497 +36230 6175 6673 2054 1837 +36231 6175 2054 6673 5967 +36232 1635 2054 6673 1837 +36233 1635 6673 2054 5967 +36234 2063 6601 2115 1727 +36235 2115 6601 2063 5816 +36236 6676 5454 6638 5562 +36237 6676 6638 5454 6538 +36238 6675 5612 6637 5720 +36239 6675 6637 5612 6540 +36240 7066 5405 6518 6284 +36241 7066 6518 5405 5376 +36242 5935 6315 4073 4169 +36243 5935 4073 6315 6073 +36244 4346 4073 6315 4169 +36245 4346 6315 4073 6073 +36246 6658 1848 2039 1759 +36247 6658 2039 1848 6432 +36248 6729 1448 1335 1189 +36249 6729 1335 1448 6587 +36250 6356 4310 4373 6355 +36251 6356 4373 4310 4104 +36252 6867 496 495 5743 +36253 6867 495 496 6634 +36254 6868 456 455 5585 +36255 6868 455 456 6633 +36256 6255 3622 431 3598 +36257 6255 431 3622 6051 +36258 6081 6238 304 6834 +36259 304 6238 6081 7006 +36260 7086 3639 6520 3588 +36261 7086 6520 3639 5988 +36262 6726 1857 1741 2119 +36263 6726 1741 1857 5858 +36264 7207 3871 6580 3726 +36265 7207 6580 3871 7031 +36266 6765 6580 3871 3726 +36267 6765 3871 6580 7031 +36268 6525 1754 5802 1981 +36269 6525 5802 1754 5872 +36270 2454 6927 6848 2455 +36271 6848 6927 2454 5805 +36272 6886 3763 2502 5827 +36273 6886 2502 3763 3849 +36274 6589 5414 5854 607 +36275 6589 5854 5414 6309 +36276 7019 6552 3134 6936 +36277 7019 3134 6552 3170 +36278 6518 7066 2303 5813 +36279 2303 7066 6518 6284 +36280 6221 2608 2609 2714 +36281 6221 2609 2608 6957 +36282 6925 1321 1537 1449 +36283 6925 1537 1321 5803 +36284 1621 1537 1321 1449 +36285 1621 1321 1537 5803 +36286 7044 3704 3831 5754 +36287 7044 3831 3704 3989 +36288 6486 2882 2939 2881 +36289 6486 2939 2882 6056 +36290 6464 1602 1609 1605 +36291 6464 1609 1602 6463 +36292 6958 1704 1811 6064 +36293 6958 1811 1704 1808 +36294 2828 6968 3159 2827 +36295 3159 6968 2828 6491 +36296 6058 5112 5883 7088 +36297 5883 5112 6058 7173 +36298 5883 6542 6058 7088 +36299 6058 6542 5883 7173 +36300 1420 6841 1275 1238 +36301 1275 6841 1420 6781 +36302 6862 5558 5465 5546 +36303 6862 5465 5558 6765 +36304 6805 3807 2209 3935 +36305 6805 2209 3807 5798 +36306 421 6797 420 3644 +36307 420 6797 421 5969 +36308 5880 6518 363 2329 +36309 5880 363 6518 6325 +36310 2358 363 6518 2329 +36311 2358 6518 363 6325 +36312 6957 3104 2713 6240 +36313 6957 2713 3104 2610 +36314 6406 266 6407 1852 +36315 6406 6407 266 5946 +36316 5765 6870 3075 3464 +36317 5765 3075 6870 5873 +36318 3463 3075 6870 3464 +36319 3463 6870 3075 5873 +36320 2423 7048 5987 438 +36321 5987 7048 2423 5785 +36322 5987 437 2423 438 +36323 2423 437 5987 5785 +36324 6560 2878 3239 3240 +36325 6560 3239 2878 6008 +36326 6991 4014 5788 4436 +36327 6991 5788 4014 6328 +36328 6608 2533 2534 3171 +36329 6525 1872 5853 1682 +36330 6525 5853 1872 5807 +36331 6883 1260 1512 1485 +36332 6883 1512 1260 5804 +36333 6483 4611 5154 6426 +36334 6483 5154 4611 4610 +36335 6867 5734 6881 6732 +36336 6867 6881 5734 5698 +36337 5653 6881 5734 6732 +36338 5653 5734 6881 5698 +36339 6868 5576 6895 6731 +36340 6868 6895 5576 5540 +36341 5495 6895 5576 6731 +36342 5495 5576 6895 5540 +36343 7172 27 4333 489 +36344 7172 4333 27 6485 +36345 6524 268 6256 1913 +36346 6524 6256 268 6408 +36347 269 6256 268 1913 +36348 269 268 6256 6408 +36349 6599 4474 4398 4179 +36350 6599 4398 4474 5838 +36351 7083 3632 3631 5753 +36352 7083 3631 3632 3585 +36353 6658 1677 6250 1939 +36354 6658 6250 1677 6373 +36355 6417 6695 2378 5855 +36356 6417 2378 6695 2457 +36357 2492 2378 6695 5855 +36358 2492 6695 2378 2457 +36359 6810 1386 6619 6701 +36360 6810 6619 1386 1296 +36361 6634 7074 1248 5762 +36362 1248 7074 6634 5974 +36363 7074 1446 1248 5762 +36364 1248 1446 7074 5974 +36365 7074 2084 1446 5762 +36366 1446 2084 7074 5974 +36367 7099 4399 4101 4366 +36368 7099 4101 4399 6588 +36369 6676 3671 3869 6534 +36370 6676 3869 3671 3938 +36371 6675 1185 1383 6533 +36372 6675 1383 1185 1452 +36373 4033 6432 5989 4326 +36374 5989 6432 4033 6032 +36375 6592 3605 3640 6307 +36376 6592 3640 3605 3589 +36377 7155 5316 4987 5997 +36378 7155 4987 5316 5251 +36379 6823 3519 3010 3518 +36380 6823 3010 3519 5777 +36381 7191 3850 2503 3994 +36382 7191 2503 3850 6998 +36383 6955 5671 6632 6743 +36384 6955 6632 5671 5613 +36385 1378 2474 6088 2475 +36386 6088 2474 1378 1277 +36387 1399 6848 1256 5919 +36388 1399 1256 6848 1293 +36389 1477 1256 6848 5919 +36390 1477 6848 1256 1293 +36391 3775 6953 3904 3712 +36392 3904 6953 3775 6730 +36393 1290 6954 1418 1227 +36394 1418 6954 1290 6729 +36395 6100 6800 296 1909 +36396 6100 296 6800 6379 +36397 297 296 6800 1909 +36398 297 6800 296 6379 +36399 6598 2310 6116 6321 +36400 6598 6116 2310 2337 +36401 6834 2259 2253 2256 +36402 6834 2253 2259 6319 +36403 6669 4479 7130 4218 +36404 6669 7130 4479 5807 +36405 7120 3098 3060 3216 +36406 7120 3060 3098 6166 +36407 4400 6622 4177 4423 +36408 4177 6622 4400 6072 +36409 6884 463 6359 4335 +36410 6884 6359 463 6806 +36411 7196 3394 3479 6049 +36412 7196 3479 3394 3406 +36413 6744 2446 3156 5856 +36414 6744 3156 2446 3317 +36415 4204 4233 6946 6140 +36416 4204 6661 6946 5940 +36417 6946 6661 4204 6140 +36418 6917 4241 499 500 +36419 6917 499 4241 6167 +36420 6913 5561 5447 5485 +36421 6913 5447 5561 6784 +36422 4890 7022 6252 4973 +36423 6252 7022 4890 5914 +36424 5973 3965 3734 3792 +36425 5973 3734 3965 6633 +36426 5974 1479 1248 1306 +36427 5974 1248 1479 6634 +36428 3123 6896 7159 3223 +36429 7159 6896 3123 6265 +36430 7159 6070 3123 3223 +36431 3123 6070 7159 6265 +36432 6559 4036 4223 6057 +36433 6559 4223 4036 4312 +36434 7171 1678 1898 2190 +36435 7171 1898 1678 6098 +36436 2608 3753 410 2714 +36437 410 3753 2608 3873 +36438 6709 3173 3094 5990 +36439 6709 3094 3173 2493 +36440 7101 5059 4672 6431 +36441 7101 4672 5059 5095 +36442 1188 6881 7209 1514 +36443 7209 6881 1188 6867 +36444 7189 4982 7000 4768 +36445 7189 7000 4982 5800 +36446 3203 1329 158 1407 +36447 158 1329 3203 2711 +36448 7171 1692 6187 1886 +36449 7171 6187 1692 6223 +36450 273 6988 6428 272 +36451 6428 6988 273 6198 +36452 6913 5447 6840 5589 +36453 6913 6840 5447 6784 +36454 7008 1467 1376 1261 +36455 7008 1376 1467 5882 +36456 3674 6895 7208 4000 +36457 7208 6895 3674 6868 +36458 7128 3247 5931 3246 +36459 7128 5931 3247 6966 +36460 3245 5931 3247 3246 +36461 3245 3247 5931 6966 +36462 6743 5673 6955 5636 +36463 6743 6955 5673 6722 +36464 6955 5673 6956 5636 +36465 6955 6956 5673 6722 +36466 6956 5673 5733 5636 +36467 1218 6519 1353 1504 +36468 1353 6519 1218 6416 +36469 6586 5387 6435 512 +36470 6586 6435 5387 6040 +36471 7118 1679 1899 2191 +36472 7118 1899 1679 6097 +36473 6725 3753 6807 6221 +36474 6725 6807 3753 3845 +36475 219 6894 3627 3599 +36476 3627 6894 219 6261 +36477 7021 3089 3532 2730 +36478 7021 3532 3089 5832 +36479 1406 6940 1279 1193 +36480 1279 6940 1406 6802 +36481 3892 6939 3765 3679 +36482 3765 6939 3892 6801 +36483 6733 1792 6616 6018 +36484 6733 6616 1792 2057 +36485 2006 6836 1932 1752 +36486 1932 6836 2006 5818 +36487 484 6464 6465 485 +36488 6465 6464 484 6463 +36489 6741 5704 6766 6476 +36490 6741 6766 5704 503 +36491 6117 6713 3498 3564 +36492 6117 3498 6713 6007 +36493 3578 3498 6713 3564 +36494 3578 6713 3498 6007 +36495 3465 6630 3461 3460 +36496 3461 6630 3465 6065 +36497 6764 3024 2952 2509 +36498 6764 2952 3024 5789 +36499 6720 7098 6721 5809 +36500 6721 7098 6720 29 +36501 7031 5498 6907 5587 +36502 7031 6907 5498 6893 +36503 6808 2484 5917 5886 +36504 6808 5917 2484 2486 +36505 2478 5917 2484 5886 +36506 2478 2484 5917 2486 +36507 6747 3422 3349 3524 +36508 6747 3349 3422 6347 +36509 6670 4750 6754 5244 +36510 6670 6754 4750 5860 +36511 7156 1987 6467 2173 +36512 7156 6467 1987 6249 +36513 7186 2421 2387 2388 +36514 7186 2387 2421 5889 +36515 6667 1554 1553 6323 +36516 6667 1553 1554 1557 +36517 3457 6668 6182 3458 +36518 6182 6668 3457 6304 +36519 6996 1374 6883 6787 +36520 6996 6883 1374 1337 +36521 5779 7175 5986 2839 +36522 5779 5986 7175 6392 +36523 2840 5986 7175 2839 +36524 2840 7175 5986 6392 +36525 6911 2203 6572 5899 +36526 6911 6572 2203 2202 +36527 2864 7050 6214 3174 +36528 6214 7050 2864 6235 +36529 6214 2536 2864 3174 +36530 7070 1394 1249 1413 +36531 7070 1249 1394 6769 +36532 2375 6886 2376 2377 +36533 2376 6886 2375 6417 +36534 6607 4084 4199 4369 +36535 6607 4199 4084 6283 +36536 6916 4596 6511 4997 +36537 6916 6511 4596 5869 +36538 6806 2013 6884 1787 +36539 6806 6884 2013 6337 +36540 6990 2368 6435 345 +36541 6990 6435 2368 6296 +36542 7082 3728 3868 3783 +36543 7082 3868 3728 5950 +36544 1247 6770 6769 1394 +36545 6769 6770 1247 6644 +36546 3733 6773 6772 3880 +36547 6772 6773 3733 6645 +36548 5899 6911 2159 6449 +36549 1953 2159 6911 6449 +36550 1953 6911 2159 292 +36551 7035 7045 7037 6028 +36552 7037 7045 7035 5893 +36553 6807 4003 3812 3701 +36554 6807 3812 4003 6128 +36555 6276 6752 5231 5191 +36556 6276 5231 6752 6277 +36557 5192 5231 6752 5191 +36558 5192 6752 5231 6277 +36559 7029 4980 6372 4913 +36560 7029 6372 4980 6148 +36561 6909 7115 4125 5763 +36562 4125 7115 6909 5906 +36563 6989 4000 6731 3799 +36564 6989 6731 4000 6895 +36565 5134 7197 5170 5171 +36566 5170 7197 5134 6553 +36567 7094 3860 6882 6820 +36568 7094 6882 3860 3823 +36569 7166 6130 6339 3377 +36570 6339 6130 7166 6289 +36571 6339 3378 7166 3377 +36572 7166 3378 6339 6289 +36573 6927 2508 6848 2455 +36574 6927 6848 2508 5919 +36575 326 6902 325 2345 +36576 325 6902 326 5995 +36577 7034 2355 6293 6141 +36578 7034 6293 2355 328 +36579 6777 6293 2355 6141 +36580 6777 2355 6293 328 +36581 7156 1954 1784 2023 +36582 7156 1784 1954 6485 +36583 7026 1955 1786 2025 +36584 7026 1786 1955 6505 +36585 6794 1614 216 6370 +36586 6794 216 1614 1618 +36587 6810 1229 1448 1411 +36588 6810 1448 1229 6587 +36589 7207 5513 6721 5580 +36590 7207 6721 5513 6907 +36591 3066 3074 6103 3064 +36592 3066 6103 3074 3140 +36593 7080 1570 1565 6303 +36594 7080 1565 1570 232 +36595 6915 2821 2627 2822 +36596 6915 2627 2821 6197 +36597 7154 600 5240 599 +36598 7154 5240 600 5939 +36599 7003 5473 7085 5582 +36600 7003 7085 5473 6774 +36601 7005 5631 7071 5740 +36602 7005 7071 5631 6771 +36603 7058 3749 3859 3822 +36604 7058 3859 3749 6638 +36605 3885 7044 3779 3742 +36606 3885 3779 7044 5930 +36607 3963 3779 7044 3742 +36608 3963 7044 3779 5930 +36609 4430 7056 521 4156 +36610 521 7056 4430 6350 +36611 6768 7136 3621 5924 +36612 3621 7136 6768 6020 +36613 2462 7191 385 5930 +36614 2462 385 7191 2507 +36615 386 385 7191 5930 +36616 386 7191 385 2507 +36617 7134 3736 3840 3920 +36618 7134 3840 3736 7112 +36619 7133 1250 1354 1434 +36620 7133 1354 1250 7111 +36621 6974 1516 6746 1197 +36622 6974 6746 1516 6541 +36623 7112 3699 3840 3810 +36624 7112 3840 3699 6873 +36625 7111 1213 1354 1324 +36626 7111 1354 1213 6874 +36627 6994 1514 6732 1313 +36628 6994 6732 1514 6881 +36629 7088 4687 5112 5111 +36630 7088 5112 4687 6058 +36631 6802 5657 6940 5627 +36632 6802 6940 5657 6649 +36633 6801 5499 6939 5469 +36634 6801 6939 5499 6648 +36635 7167 4675 6289 5063 +36636 7167 6289 4675 6224 +36637 1191 6901 1466 1451 +36638 1466 6901 1191 6689 +36639 7105 1737 7091 6203 +36640 7105 7091 1737 1880 +36641 3945 6904 6459 3711 +36642 6459 6904 3945 6584 +36643 6903 1459 6458 6583 +36644 6903 6458 1459 1225 +36645 2346 6902 2311 2295 +36646 2311 6902 2346 5767 +36647 7124 2864 7125 2859 +36648 7124 7125 2864 6235 +36649 6759 1425 6901 6602 +36650 6759 6901 1425 1341 +36651 3911 6760 6900 3827 +36652 6900 6760 3911 6603 +36653 3942 2712 6749 3812 +36654 3942 6749 2712 2559 +36655 7203 4356 4147 4442 +36656 7203 4147 4356 6663 +36657 6770 5752 6769 5611 +36658 6770 6769 5752 6644 +36659 7070 6769 5752 5611 +36660 7070 5752 6769 6644 +36661 6773 5594 6772 5453 +36662 6773 6772 5594 6645 +36663 7091 2111 1737 2044 +36664 7091 1737 2111 6396 +36665 7083 242 3923 6575 +36666 7083 3923 242 3633 +36667 7081 2274 301 2268 +36668 7081 301 2274 6846 +36669 6637 1516 1473 1263 +36670 6637 1473 1516 6541 +36671 6638 4002 3959 3749 +36672 6638 3959 4002 6539 +36673 7071 5631 5664 5740 +36674 7071 5664 5631 6769 +36675 463 6862 26 5546 +36676 463 26 6862 6863 +36677 5487 7190 6852 5538 +36678 6852 7190 5487 6983 +36679 7083 448 3923 3633 +36680 7083 3923 448 3832 +36681 4714 4711 6451 4715 +36682 6451 4711 4714 4712 +36683 4719 4716 6755 4720 +36684 6755 4716 4719 4717 +36685 6826 5530 6757 620 +36686 6826 6757 5530 6534 +36687 5567 6757 5530 620 +36688 5567 5530 6757 6534 +36689 6214 2533 6608 5859 +36690 6214 6608 2533 2534 +36691 3161 6217 3274 5970 +36692 3161 3274 6217 3469 +36693 6946 4204 4066 4233 +36694 4066 4204 6946 5940 +36695 4066 6578 6946 4233 +36696 6946 6578 4066 5940 +36697 5673 5623 6766 5733 +36698 6766 5623 5673 6722 +36699 6766 6956 5673 5733 +36700 5673 6956 6766 6722 +36701 2864 6214 6469 2536 +36702 6469 6214 2864 6235 +36703 2203 6911 291 5899 +36704 2203 291 6911 292 +36705 2159 291 6911 5899 +36706 2159 6911 291 292 +3 2 4 4617 +36707 7247 7393 92 7414 +36708 1260 1440 1512 7245 +36709 7235 7366 7230 7402 +36710 7284 7354 1401 7365 +36711 7243 7260 7216 7317 +36712 7219 7308 7271 7329 +36713 1269 1463 7264 7365 +36714 7284 7295 7291 7342 +36715 858 990 7292 7348 +36716 7270 7230 7366 7402 +36717 1440 7245 1260 7355 +36718 1438 1345 1258 7399 +36719 7217 7329 7261 7336 +36720 7270 7366 7297 7402 +36721 7235 7300 7299 7362 +36722 7237 7222 7330 7350 +36723 7235 7297 7366 7402 +36724 7267 7310 1345 7399 +36725 1519 7321 7284 7365 +36726 7243 7248 810 7427 +36727 810 7248 7243 7370 +36728 1427 1258 7255 7399 +36729 875 7248 968 7252 +36730 7241 7243 7216 7248 +36731 7271 7308 7224 7329 +36732 7243 7248 7241 7443 +36733 810 7252 7248 7370 +36734 7235 7296 1026 7309 +36735 1026 7296 7235 7362 +36736 1367 7323 7239 7416 +36737 1313 7246 7320 7442 +36738 7323 7416 1367 7439 +36739 7245 7261 7217 7329 +36740 7235 7309 1026 7444 +36741 7235 1026 7362 7444 +36742 7236 7318 7291 7415 +36743 7251 7292 7220 7341 +36744 782 7248 875 7252 +36745 7237 7269 7222 7350 +36746 810 968 7248 7252 +36747 1274 7381 7320 7416 +36748 874 1101 1144 7331 +36749 953 7335 1023 7385 +36750 7230 7235 7280 7366 +36751 7237 7218 7268 7391 +36752 1105 7264 1463 7365 +36753 1313 7342 7246 7442 +36754 1023 7298 953 7385 +36755 7284 7291 1390 7342 +36756 7222 7269 7237 7304 +36757 7249 7280 7228 7299 +36758 7228 7299 7280 7300 +36759 7284 7227 7354 7365 +36760 77 1036 76 7268 +36761 1401 1519 7284 7365 +36762 1311 7261 7245 7329 +36763 954 1029 7285 7298 +36764 7291 7318 7232 7415 +36765 1133 7316 7266 7339 +36766 7288 7317 7219 7430 +36767 1311 7261 7329 7336 +36768 7284 7321 7227 7365 +36769 7305 7335 1005 7455 +36770 7234 7347 7272 7372 +36771 7223 7295 7284 7342 +36772 1080 7355 7262 7440 +36773 7218 7259 7256 7276 +36774 1172 1345 1438 7399 +36775 7225 7327 7238 7363 +36776 7219 7271 7265 7329 +36777 7216 7317 7260 7352 +36778 1313 7320 7246 7345 +36779 7267 7268 7218 7391 +36780 89 90 1193 7275 +36781 7328 7338 7301 7341 +36782 90 1193 7275 7305 +36783 7220 7338 7328 7341 +36784 7238 7327 7303 7363 +36785 1433 7368 7249 7400 +36786 7216 7260 7243 7351 +36787 7235 7230 7300 7402 +36788 857 7352 7243 7427 +36789 7235 7280 7299 7300 +36790 7235 7280 7249 7299 +36791 7230 7280 7235 7300 +36792 857 7317 7243 7352 +36793 1390 7284 7342 7442 +36794 1317 7247 92 7414 +36795 873 818 925 7263 +36796 7243 7317 7216 7352 +36797 7270 7231 7322 7446 +36798 942 963 7266 7316 +36799 879 7344 7295 7428 +36800 7291 7322 7231 7446 +36801 802 7235 7297 7362 +36802 953 7298 971 7385 +36803 7237 7222 7304 7330 +36804 7216 7243 7241 7351 +36805 7304 7330 7256 7348 +36806 879 7295 7344 7433 +36807 90 7305 7275 7385 +36808 7237 7268 7218 7304 +36809 7266 7316 7234 7339 +36810 7284 7287 7227 7344 +36811 824 7373 7335 7385 +36812 930 7242 967 7452 +36813 1205 1401 7354 7365 +36814 7223 7246 7320 7387 +36815 1475 7258 7293 7454 +36816 7215 7263 7240 7278 +36817 7227 7287 7284 7354 +36818 1345 7310 1258 7399 +36819 7239 1129 7358 7395 +36820 1143 1103 7274 7333 +36821 1427 7255 208 7399 +36822 7229 7281 7253 7416 +36823 7229 7239 7281 7416 +36824 902 7250 7316 7419 +36825 7219 7260 7243 7317 +36826 7230 7272 7347 7372 +36827 7261 7262 1082 7355 +36828 7225 7247 7238 7401 +36829 7233 7251 7240 7306 +36830 1172 7267 1345 7399 +36831 824 7335 7373 7401 +36832 7220 7259 7256 7292 +36833 7238 7247 7225 7380 +36834 1029 997 7285 7298 +36835 1293 7258 35 7314 +36836 1005 7335 7305 7385 +36837 7223 7287 7284 7344 +36838 7267 7377 7268 7436 +36839 7219 7307 7271 7308 +36840 7243 7271 7219 7317 +36841 796 7237 938 7348 +36842 810 968 875 7248 +36843 1143 7274 868 7333 +36844 7219 7329 7265 7384 +36845 101 7378 7252 7423 +36846 7260 7265 7243 7351 +36847 7259 7276 7218 7304 +36848 7223 7253 7229 7287 +36849 7272 7311 7234 7372 +36850 7231 7270 7360 7446 +36851 7237 796 7330 7348 +36852 7216 7352 7260 7388 +36853 7226 7247 7238 7288 +36854 7243 7260 7219 7265 +36855 7218 7276 7256 7304 +36856 7223 7320 7253 7387 +36857 824 7335 953 7385 +36858 7231 7360 7291 7446 +36859 7284 7287 7223 7354 +36860 7266 7286 1133 7339 +36861 7240 7251 7233 7331 +36862 7285 7318 7236 7415 +36863 1485 7245 1512 7332 +36864 873 7263 925 7432 +36865 820 38 7290 7427 +36866 816 7262 7346 7440 +36867 1298 7308 7303 7384 +36868 1158 7273 7255 7432 +36869 1158 7255 7278 7432 +36870 7218 7304 7256 7348 +36871 816 7262 924 7346 +36872 885 7252 821 7423 +36873 7237 7330 7304 7348 +36874 967 819 7242 7441 +36875 7236 7270 7322 7446 +36876 7229 7253 7223 7320 +36877 7228 7301 7328 7338 +36878 988 7263 7251 7337 +36879 816 7346 7274 7440 +36880 7236 7309 7297 7366 +36881 7283 7347 7234 7372 +36882 7215 7278 7240 7349 +36883 938 7237 796 7390 +36884 929 821 101 7252 +36885 7256 7259 7220 7276 +36886 7238 7225 7363 7380 +36887 1166 7267 1172 7399 +36888 7271 7307 7224 7308 +36889 91 7305 1005 7455 +36890 1427 208 1258 7399 +36891 90 7275 89 7385 +36892 7237 7348 7254 7417 +36893 7260 7352 7317 7388 +36894 7259 7304 7218 7377 +36895 874 7263 1101 7331 +36896 7220 7282 7251 7341 +36897 1129 7281 7239 7358 +36898 1216 7261 1311 7336 +36899 1322 1427 1507 7255 +36900 7303 7384 7308 7398 +36901 7248 7370 7252 7443 +36902 1401 1205 1519 7365 +36903 878 7282 7272 7328 +36904 7219 7308 7329 7384 +36905 7299 7300 862 7362 +36906 7236 7322 7291 7446 +36907 7262 7355 7245 7440 +36908 7223 7320 7246 7442 +36909 1485 7245 7332 7418 +36910 7226 7317 7288 7430 +36911 824 953 971 7385 +36912 1372 1478 7268 7304 +36913 1311 7245 7261 7355 +36914 7244 7282 7233 7306 +36915 7234 7286 7266 7339 +36916 1496 1208 7240 7349 +36917 7234 7272 7266 7311 +36918 7241 7265 7243 7443 +36919 821 885 101 7252 +36920 965 810 875 7248 +36921 7238 7288 7219 7430 +36922 7220 7282 7244 7306 +36923 1154 1427 1322 7255 +36924 979 7251 892 7282 +36925 921 7292 7251 7341 +36926 7266 7311 7272 7426 +36927 7254 7267 7218 7391 +36928 7276 7304 7259 7377 +36929 1136 7331 7240 7361 +36930 1367 7416 1274 7439 +36931 7237 938 7348 7417 +36932 7244 7328 7220 7338 +36933 7296 7297 7235 7362 +36934 7266 7233 7311 7426 +36935 7238 7247 7226 7319 +36936 7245 7274 1126 7332 +36937 7223 7246 7342 7442 +36938 7297 7309 7235 7366 +36939 7231 7291 7284 7295 +36940 7231 7284 7321 7344 +36941 7230 7270 7366 7394 +36942 1080 1082 7262 7355 +36943 818 934 925 7337 +36944 963 7266 7316 7397 +36945 7248 7243 7370 7443 +36946 7223 7284 7295 7344 +36947 926 7330 7279 7350 +36948 7247 7225 7335 7401 +36949 7233 7282 7251 7306 +36950 805 7250 7347 7397 +36951 967 7242 930 7441 +36952 7254 7348 938 7417 +36953 7218 7256 7259 7292 +36954 7295 7223 7344 7433 +36955 7218 7268 7267 7304 +36956 7237 7254 7218 7391 +36957 7243 7265 7241 7351 +36958 1512 1440 1141 7245 +36959 38 931 7248 7427 +36960 38 820 931 7427 +36961 7227 7315 7229 7325 +36962 7244 7282 7220 7328 +36963 7231 7322 7295 7428 +36964 980 830 902 7316 +36965 1493 7283 7270 7453 +36966 7250 7316 7234 7397 +36967 7227 7287 7229 7315 +36968 926 938 796 7390 +36969 857 993 7317 7352 +36970 7218 7237 7304 7348 +36971 873 925 7273 7432 +36972 1080 7262 1082 7440 +36973 7230 7347 7283 7372 +36974 830 957 7312 7316 +36975 7247 7335 7305 7455 +36976 7230 7244 7272 7372 +36977 35 7314 7258 7386 +36978 1512 1485 1260 7245 +36979 7265 7271 7217 7329 +36980 7245 7262 7261 7355 +36981 1493 7270 7360 7453 +36982 962 7327 7294 7387 +36983 92 1210 91 7247 +36984 1390 7284 1230 7360 +36985 990 7292 7348 7364 +36986 1286 7318 7291 7446 +36987 82 7277 7249 7368 +36988 7266 7286 7234 7311 +36989 1007 953 1023 7298 +36990 1427 1258 1507 7255 +36991 7219 7243 7265 7271 +36992 7220 7259 7292 7431 +36993 1298 7303 7288 7384 +36994 7217 7265 7243 7271 +36995 83 1338 82 7249 +36996 7242 7215 7337 7424 +36997 1475 1 7258 7454 +36998 1472 1390 1230 7360 +36999 7272 7311 7233 7426 +37000 7238 7363 7303 7380 +37001 1479 1205 7354 7365 +37002 7227 7321 7284 7344 +37003 967 930 819 7441 +37004 1216 1311 1308 7336 +37005 1141 1512 7245 7332 +37006 1223 1 33 7258 +37007 7225 7373 7335 7401 +37008 1141 7245 1440 7355 +37009 7215 7251 7240 7263 +37010 7249 7277 1025 7438 +37011 7275 7318 88 7435 +37012 938 7254 822 7348 +37013 947 7271 7243 7317 +37014 1129 1097 7239 7281 +37015 1276 1429 7260 7384 +37016 1172 1166 1174 7267 +37017 7236 7296 7297 7309 +37018 7235 7297 7296 7309 +37019 7244 7311 7272 7372 +37020 1029 954 863 7298 +37021 7320 7381 7229 7416 +37022 1105 1124 1463 7264 +37023 78 1509 77 7450 +37024 962 7294 7340 7387 +37025 870 924 816 7262 +37026 91 7247 7305 7455 +37027 957 1135 7312 7316 +37028 7236 7297 7270 7366 +37029 1357 1162 7255 7278 +37030 1219 1417 7265 7336 +37031 926 7279 817 7350 +37032 834 7361 7266 7426 +37033 7312 7315 829 7419 +37034 885 101 7252 7423 +37035 1286 7406 7318 7446 +37036 923 7352 7290 7404 +37037 7230 7366 7280 7394 +37038 7249 7299 7438 7444 +37039 7224 7271 7329 7420 +37040 1158 7255 1162 7278 +37041 875 780 965 7248 +37042 930 7441 7242 7452 +37043 7224 7274 7245 7332 +37044 7256 7304 7222 7330 +37045 1097 1129 7239 7381 +37046 7240 7251 7215 7431 +37047 7309 7343 1026 7444 +37048 1166 7353 7267 7399 +37049 1317 1210 92 7247 +37050 7242 7255 7215 7424 +37051 7386 7404 7257 7454 +37052 7219 7317 7271 7367 +37053 7215 7255 7242 7273 +37054 7239 7358 7333 7395 +37055 7337 7242 7424 7425 +37056 926 7330 7350 7390 +37057 7284 7231 7295 7344 +37058 918 7312 829 7419 +37059 7229 7223 7287 7354 +37060 1274 1221 7320 7381 +37061 7215 7273 7242 7337 +37062 950 7257 44 7313 +37063 144 1018 6 7350 +37064 7289 7308 7221 7323 +37065 7255 1163 7399 7441 +37066 1442 7304 7276 7377 +37067 7241 7248 7216 7359 +37068 7222 7269 7324 7350 +37069 7231 7295 7344 7428 +37070 7229 7325 7315 7421 +37071 1353 7268 7377 7436 +37072 1311 7261 1216 7355 +37073 7250 7264 7234 7316 +37074 7244 7272 7233 7282 +37075 990 7292 7364 7425 +37076 1023 996 7298 7385 +37077 989 810 7243 7370 +37078 817 949 145 7279 +37079 7220 7328 7282 7341 +37080 7303 7288 7384 7398 +37081 1152 1322 1357 7255 +37082 804 7287 7253 7340 +37083 895 7266 834 7361 +37084 996 1023 7335 7385 +37085 1098 7312 1112 7316 +37086 7227 7229 7287 7354 +37087 870 7262 816 7440 +37088 7231 7321 7250 7344 +37089 7239 7281 1097 7381 +37090 895 1110 7266 7361 +37091 38 7248 784 7359 +37092 1098 7312 7264 7405 +37093 979 892 7251 7331 +37094 1276 7260 7265 7384 +37095 1357 7255 1217 7278 +37096 1493 7270 7283 7394 +37097 7217 7261 7245 7262 +37098 1005 7305 90 7385 +37099 7270 7231 7302 7322 +37100 7223 7229 7320 7354 +37101 963 825 942 7266 +37102 892 7282 7251 7331 +37103 799 7328 7300 7389 +37104 7250 7234 7347 7397 +37105 7229 7227 7325 7354 +37106 7246 7223 7294 7387 +37107 946 858 990 7292 +37108 967 7242 819 7425 +37109 1018 7324 6 7350 +37110 1438 1258 208 7399 +37111 82 1025 7249 7277 +37112 7278 7432 7263 7458 +37113 913 7301 7328 7389 +37114 1258 7310 7255 7399 +37115 7324 7350 1018 7409 +37116 1219 7241 7336 7351 +37117 7251 7282 7220 7306 +37118 1219 7336 7265 7351 +37119 7225 7305 7275 7363 +37120 1240 7276 7259 7377 +37121 911 822 7254 7348 +37122 1438 1427 208 1258 +37123 952 864 7281 7396 +37124 1317 92 93 7293 +37125 7249 7438 1025 7444 +37126 208 1427 1154 7255 +37127 1496 1307 7240 7356 +37128 7218 7254 7237 7348 +37129 7251 7282 921 7341 +37130 840 7253 933 7340 +37131 7224 7308 7289 7323 +37132 7233 7286 7266 7311 +37133 7220 7306 7244 7449 +37134 1352 7320 7381 7410 +37135 804 7253 840 7340 +37136 93 7293 92 7393 +37137 1105 7264 7365 7405 +37138 1309 7310 7259 7369 +37139 946 858 7292 7348 +37140 1479 1205 1401 7354 +37141 7239 7229 7381 7416 +37142 7335 7373 7225 7385 +37143 7225 7275 7357 7363 +37144 7270 7302 7297 7322 +37145 7254 7353 7267 7391 +37146 908 1143 868 7333 +37147 807 7289 7333 7383 +37148 921 788 7292 7341 +37149 863 953 1007 7298 +37150 7223 7340 7294 7387 +37151 892 7282 7331 7426 +37152 1141 7245 1102 7332 +37153 954 7285 975 7298 +37154 7225 7305 7335 7385 +37155 1513 7286 1114 7356 +37156 44 869 638 7257 +37157 1274 1367 1221 7381 +37158 1354 84 7309 7343 +37159 935 7290 923 7352 +37160 1338 83 1381 7343 +37161 1298 7288 1524 7384 +37162 7303 7327 7246 7363 +37163 7225 7305 7247 7335 +37164 7247 7335 7319 7401 +37165 7244 7311 1413 7429 +37166 7285 7318 1012 7406 +37167 962 7340 933 7387 +37168 7301 7326 7276 7338 +37169 1478 1353 7268 7304 +37170 1367 7381 7239 7395 +37171 7296 7297 981 7445 +37172 923 7290 935 7404 +37173 931 965 780 7248 +37174 1389 7244 1413 7429 +37175 878 916 7272 7282 +37176 875 787 780 7248 +37177 1442 7276 1240 7377 +37178 933 7340 7253 7387 +37179 7281 7381 7229 7421 +37180 873 7273 1160 7432 +37181 1211 7249 1433 7368 +37182 1338 7249 83 7343 +37183 7247 7319 7238 7401 +37184 936 7273 7337 7425 +37185 1322 1217 1357 7255 +37186 1390 1396 7284 7442 +37187 7256 7276 7222 7304 +37188 1497 1416 7275 7305 +37189 84 1381 83 7343 +37190 7275 7305 1416 7363 +37191 983 7274 7346 7383 +37192 91 7247 1210 7305 +37193 7240 7278 7263 7458 +37194 1389 7244 7429 7449 +37195 951 870 816 7440 +37196 1496 7349 7240 7458 +37197 7251 7282 7233 7331 +37198 84 1194 1381 7343 +37199 7247 7288 7226 7414 +37200 7234 7286 7339 7457 +37201 44 638 637 7257 +37202 1168 7254 1175 7391 +37203 1390 7342 1396 7442 +37204 1269 1463 1328 7264 +37205 7229 7381 7320 7410 +37206 7216 7248 7243 7427 +37207 804 7253 7287 7396 +37208 1122 7240 1100 7458 +37209 7224 7307 7289 7308 +37210 1245 7286 1513 7356 +37211 1102 7245 1126 7332 +37212 943 834 7266 7426 +37213 7267 7353 1168 7391 +37214 7303 7308 1298 7439 +37215 1253 7280 7249 7343 +37216 1390 1396 1230 7284 +37217 1338 1381 1194 7343 +37218 1012 7285 7406 7448 +37219 7241 7359 7351 7371 +37220 7258 7386 7257 7454 +37221 7291 7318 1200 7382 +37222 1390 7291 7284 7360 +37223 1100 1147 1122 7458 +37224 7289 7307 7221 7308 +37225 7240 7349 7278 7458 +37226 1217 7278 7255 7369 +37227 818 925 7263 7337 +37228 807 7289 890 7333 +37229 1155 7255 1158 7273 +37230 7243 7265 7217 7443 +37231 7241 7216 7351 7359 +37232 1028 7318 7285 7435 +37233 77 1294 1036 7268 +37234 878 916 7282 7328 +37235 1307 1122 7240 7356 +37236 1155 7255 7273 7441 +37237 7246 7345 7320 7387 +37238 879 7295 843 7428 +37239 1475 7293 1 7454 +37240 84 1026 7309 7343 +37241 7272 7282 916 7426 +37242 1429 1276 7260 7351 +37243 963 942 865 7316 +37244 7246 7303 1327 7345 +37245 1307 7240 1122 7458 +37246 7279 1018 7350 7409 +37247 1485 7329 7245 7418 +37248 1173 1177 7242 7452 +37249 7376 7394 7372 7422 +37250 1368 7329 7308 7384 +37251 1372 7268 7269 7304 +37252 1327 7303 7246 7363 +37253 1092 7262 870 7440 +37254 957 1112 1135 7316 +37255 1026 7343 84 7444 +37256 815 7257 950 7313 +37257 7287 7315 7227 7419 +37258 7272 7282 7244 7328 +37259 1294 7268 77 7450 +37260 1506 1216 1308 7447 +37261 1198 7323 1367 7439 +37262 1112 7312 1135 7316 +37263 7219 7288 7238 7398 +37264 1218 1470 7267 7310 +37265 82 7249 1211 7368 +37266 936 7337 794 7425 +37267 7253 7340 7223 7387 +37268 1175 7254 1168 7353 +37269 879 843 7295 7433 +37270 983 816 940 7346 +37271 816 7274 951 7440 +37272 7234 7311 7286 7457 +37273 825 895 942 7266 +37274 7289 7323 7221 7416 +37275 7249 7280 1253 7400 +37276 975 7298 7285 7407 +37277 1133 1093 7316 7339 +37278 7240 7215 7349 7431 +37279 885 7378 101 7423 +37280 7231 7283 7270 7302 +37281 7271 7317 947 7367 +37282 805 7250 854 7347 +37283 639 7404 7386 7454 +37284 838 7262 7378 7423 +37285 979 892 845 7282 +37286 911 938 822 7348 +37287 1133 7286 1099 7339 +37288 7233 7331 7282 7426 +37289 7217 7329 7271 7420 +37290 1307 1496 7240 7458 +37291 1496 7240 1208 7356 +37292 7250 7283 7231 7302 +37293 88 7275 1406 7318 +37294 145 949 817 871 +37295 6 7324 7269 7350 +37296 7289 7323 7239 7333 +37297 890 7289 807 7383 +37298 1524 7288 1298 7303 +37299 895 943 834 7266 +37300 7327 7374 7303 7387 +37301 897 1023 953 7335 +37302 7231 7283 7250 7321 +37303 1433 1315 7368 7400 +37304 637 7257 638 7404 +37305 7275 1416 7357 7363 +37306 1153 7255 1163 7399 +37307 638 7257 869 7404 +37308 7265 7336 7241 7351 +37309 1463 1124 1328 7264 +37310 7331 7361 834 7426 +37311 1177 7353 7242 7452 +37312 863 1007 1029 7298 +37313 901 7379 7253 7396 +37314 1463 1269 1145 7365 +37315 34 1508 1223 7258 +37316 832 890 7289 7333 +37317 871 926 817 7350 +37318 977 1160 873 7273 +37319 7228 7277 7249 7389 +37320 1368 7265 7329 7384 +37321 824 7373 859 7401 +37322 7232 7318 7285 7415 +37323 7228 7249 7299 7389 +37324 1031 44 7257 7313 +37325 1208 7306 7240 7349 +37326 827 7407 7285 7415 +37327 7277 7299 7249 7389 +37328 1353 1257 7268 7436 +37329 1413 7372 7244 7376 +37330 1330 1193 90 7305 +37331 1214 7246 7342 7357 +37332 1497 7275 1193 7305 +37333 1093 7264 7316 7339 +37334 7226 7288 7238 7430 +37335 965 810 7248 7427 +37336 7220 7292 7251 7431 +37337 1294 77 1509 7450 +37338 1276 7265 7260 7351 +37339 7222 7276 7301 7326 +37340 799 913 7328 7389 +37341 7239 7323 1367 7395 +37342 44 43 1031 7257 +37343 1155 1163 7255 7441 +37344 7219 7367 7238 7430 +37345 1475 1 1223 7258 +37346 7254 1168 7353 7391 +37347 946 7292 788 7341 +37348 7267 7304 7268 7377 +37349 7260 7288 1331 7414 +37350 802 981 966 7362 +37351 874 1144 914 7331 +37352 1353 7268 7304 7377 +37353 78 7269 1224 7450 +37354 7263 7215 7337 7432 +37355 7236 7318 7285 7406 +37356 7250 7321 7227 7344 +37357 7239 7323 7289 7416 +37358 910 851 7401 7430 +37359 83 82 1338 1268 +37360 7222 7276 7256 7301 +37361 1007 1023 996 7298 +37362 7242 7337 7273 7425 +37363 1158 1152 1162 7255 +37364 817 7279 926 7330 +37365 7230 7272 7244 7422 +37366 639 7386 7258 7454 +37367 7227 7264 7250 7419 +37368 1173 7242 1177 7441 +37369 7359 7371 7241 7411 +37370 1106 7239 1129 7381 +37371 967 7364 7242 7425 +37372 7244 7306 7233 7429 +37373 1258 1345 1470 7310 +37374 7246 7357 1214 7363 +37375 7229 7281 7239 7381 +37376 780 875 965 931 +37377 1311 1216 1511 7355 +37378 7236 7309 7366 7446 +37379 7283 7372 7234 7457 +37380 7266 7272 7234 7397 +37381 7313 7393 994 7455 +37382 1258 1309 1507 7255 +37383 1125 7263 7432 7458 +37384 1309 7255 7310 7369 +37385 1413 7311 7244 7372 +37386 7237 7350 7330 7390 +37387 1132 1098 1112 7316 +37388 1276 1219 1417 7265 +37389 7283 7234 7375 7457 +37390 900 829 7315 7419 +37391 1463 1145 1105 7365 +37392 939 1008 7299 7362 +37393 780 38 931 7248 +37394 203 948 818 7263 +37395 967 7242 7364 7452 +37396 7230 7270 7283 7302 +37397 956 829 888 7315 +37398 873 203 818 7263 +37399 7236 7366 7270 7446 +37400 84 1434 1194 7343 +37401 828 939 898 7299 +37402 1173 7242 7441 7452 +37403 1354 1434 84 7343 +37404 7320 7387 7345 7416 +37405 1394 7372 7376 7394 +37406 1172 1438 208 7399 +37407 1372 1196 1478 7304 +37408 968 7252 810 7370 +37409 7218 7267 7254 7353 +37410 1134 7286 1270 7339 +37411 7220 7292 7256 7341 +37412 7253 7281 7229 7396 +37413 852 7256 7301 7459 +37414 782 875 968 7252 +37415 7253 7379 7281 7396 +37416 1097 7381 7281 7421 +37417 888 829 7312 7315 +37418 7323 7239 7333 7395 +37419 7278 7349 7215 7369 +37420 1309 7255 1258 7310 +37421 7300 7328 7228 7389 +37422 7224 7274 7332 7333 +37423 939 7299 828 7362 +37424 939 1008 898 7299 +37425 1413 7244 1247 7376 +37426 7223 7342 7284 7442 +37427 7233 7272 7244 7311 +37428 802 7300 862 7402 +37429 883 820 38 7290 +37430 7217 7262 7245 7420 +37431 7244 7376 7372 7422 +37432 938 822 7254 7417 +37433 81 7277 82 7368 +37434 900 7315 7287 7419 +37435 809 7251 988 7263 +37436 923 7257 7352 7404 +37437 91 90 1005 7305 +37438 784 7359 7248 7411 +37439 963 825 7266 7397 +37440 7291 7295 7232 7342 +37441 1294 7269 7268 7450 +37442 84 85 1354 7309 +37443 7230 7302 7283 7347 +37444 1242 1325 7349 7369 +37445 7240 7306 7251 7431 +37446 7234 7283 7250 7347 +37447 1474 6 80 7324 +37448 7253 7229 7287 7396 +37449 1322 1507 1217 7255 +37450 7234 7250 7283 7375 +37451 7219 7238 7367 7398 +37452 7234 7264 7250 7375 +37453 1125 7240 7263 7458 +37454 1137 7332 7274 7333 +37455 1147 1307 1122 7458 +37456 7220 7251 7306 7431 +37457 82 1338 1211 7249 +37458 7273 7337 7215 7432 +37459 7279 7330 7222 7350 +37460 952 864 1109 7281 +37461 835 7327 962 7387 +37462 33 7258 1 7454 +37463 7238 7303 7327 7374 +37464 830 980 957 7316 +37465 1037 77 1294 1036 +37466 7270 7297 7236 7322 +37467 971 953 863 7298 +37468 1028 1012 7285 7318 +37469 7253 7287 7223 7340 +37470 7216 7243 7352 7427 +37471 7246 7327 7303 7387 +37472 7242 7255 7399 7441 +37473 7232 7318 7291 7382 +37474 7320 7253 7387 7416 +37475 936 7273 7425 7441 +37476 847 7328 7301 7341 +37477 7240 7331 7233 7356 +37478 948 873 203 818 +37479 7218 7292 7259 7424 +37480 7226 7238 7319 7430 +37481 1474 7269 6 7324 +37482 838 7262 1086 7378 +37483 1128 1098 7264 7405 +37484 1345 7267 1470 7310 +37485 75 36 2 1035 +37486 834 7331 1110 7361 +37487 789 7271 947 7367 +37488 799 7300 7299 7389 +37489 819 7425 7242 7441 +37490 1114 1094 7356 7361 +37491 991 790 7340 7433 +37492 7251 7263 7215 7337 +37493 1507 7255 1309 7369 +37494 819 936 7425 7441 +37495 929 885 101 821 +37496 1479 7354 7325 7365 +37497 1357 1162 1152 7255 +37498 878 7328 7272 7403 +37499 901 840 804 7253 +37500 1524 7288 7303 7380 +37501 895 834 1110 7361 +37502 7235 7343 7309 7444 +37503 7218 7348 7292 7364 +37504 1353 1257 1478 7268 +37505 7227 7312 7264 7419 +37506 7225 7246 7327 7363 +37507 1120 1144 1101 7331 +37508 1475 7258 1290 7293 +37509 926 7350 871 7390 +37510 7228 7328 7301 7389 +37511 923 894 7352 7451 +37512 952 970 864 7396 +37513 1015 7319 7313 7455 +37514 1143 1117 1103 7333 +37515 1413 1389 1247 7244 +37516 1005 1032 91 7455 +37517 7250 7264 7227 7321 +37518 1496 1384 1208 7349 +37519 1100 1122 1136 7240 +37520 7256 7292 7218 7348 +37521 852 7301 960 7459 +37522 35 7258 34 7386 +37523 7230 7403 7272 7422 +37524 7331 7356 7240 7361 +37525 7224 7323 7289 7333 +37526 1324 7309 85 7406 +37527 1223 33 34 7258 +37528 805 902 854 7250 +37529 1208 7240 7306 7356 +37530 901 7253 804 7396 +37531 1425 762 669 738 +37532 38 780 784 7248 +37533 1345 1218 1470 7267 +37534 824 945 7335 7401 +37535 1172 1174 1345 7267 +37536 7219 7317 7367 7430 +37537 816 924 940 7346 +37538 1101 1144 1138 874 +37539 7243 7271 842 7370 +37540 1024 898 1008 7299 +37541 1075 7391 7390 7450 +37542 7257 7216 7290 7386 +37543 852 7256 969 7301 +37544 807 7333 7274 7383 +37545 776 780 787 7248 +37546 873 203 7263 7432 +37547 7257 7258 7216 7386 +37548 938 7237 7390 7417 +37549 7217 7271 7243 7370 +37550 717 33 34 1364 +37551 1330 1497 1193 7305 +37552 954 827 975 7285 +37553 1079 7261 1082 7355 +37554 1483 1050 1048 771 +37555 7284 7291 7231 7360 +37556 1318 1419 1190 7324 +37557 838 7378 885 7423 +37558 7223 7246 7294 7342 +37559 1200 7291 1286 7318 +37560 828 7299 862 7362 +37561 1314 7247 1317 7414 +37562 1454 7305 7247 7380 +37563 1457 1269 7264 7365 +37564 1133 7266 1099 7286 +37565 947 7243 857 7317 +37566 7233 7356 7331 7361 +37567 1416 7275 7357 7382 +37568 1166 1170 7353 7399 +37569 1173 7441 930 7452 +37570 1348 1513 1114 7356 +37571 7221 7303 7374 7387 +37572 804 840 906 7340 +37573 827 975 7285 7407 +37574 6 1224 79 7269 +37575 1313 1214 7246 7342 +37576 1224 7269 1294 7450 +37577 43 1031 7257 7454 +37578 7249 7299 7277 7438 +37579 7246 7327 7294 7357 +37580 7243 7217 7370 7443 +37581 983 7274 816 7346 +37582 991 790 7294 7340 +37583 7226 7260 7317 7388 +37584 1152 1154 1322 7255 +37585 777 7371 7359 7411 +37586 1219 7265 1276 7351 +37587 7230 7372 7394 7422 +37588 1352 7320 1221 7381 +37589 7245 7329 7217 7420 +37590 856 988 7251 7337 +37591 5 76 45 1036 +37592 7225 7247 7305 7380 +37593 1318 7324 80 7368 +37594 1097 1130 7381 7421 +37595 1328 7264 1124 7339 +37596 7294 7357 7327 7373 +37597 1114 7356 7286 7361 +37598 89 1406 88 7275 +37599 1253 1439 7280 7343 +37600 81 1318 80 7368 +37601 1149 1114 1513 7286 +37602 1337 7308 1368 7329 +37603 7225 7238 7327 7401 +37604 7287 7344 7223 7433 +37605 7280 7394 7376 7422 +37606 90 89 1022 7385 +37607 933 7253 877 7387 +37608 1313 7320 1188 7442 +37609 7245 7224 7332 7418 +37610 7240 7349 7306 7431 +37611 7238 7288 7247 7380 +37612 1454 1210 7247 7305 +37613 1219 7241 7351 7371 +37614 1384 7349 1496 7458 +37615 910 7401 7238 7430 +37616 831 1033 7335 7455 +37617 954 975 863 7298 +37618 1310 7259 1309 7310 +37619 7242 7273 7255 7441 +37620 946 7292 7256 7348 +37621 7242 7399 1177 7441 +37622 7218 7304 7267 7377 +37623 993 7352 857 7427 +37624 1104 7266 1133 7316 +37625 1125 7240 1136 7263 +37626 864 1109 7281 7396 +37627 952 7281 970 7396 +37628 7228 7326 7301 7338 +37629 1198 1367 1274 7439 +37630 1294 1372 7268 7269 +37631 1007 997 1029 7298 +37632 1475 1418 1189 7293 +37633 868 7274 807 7333 +37634 913 7301 847 7328 +37635 1331 7288 1347 7414 +37636 7230 7270 7302 7402 +37637 923 815 894 7451 +37638 786 7252 100 7334 +37639 1143 908 1117 7333 +37640 7233 7306 7240 7356 +37641 1034 1293 35 7314 +37642 7290 7352 935 7427 +37643 1031 7313 7257 7454 +37644 7248 7359 7241 7411 +37645 675 722 745 1359 +37646 1090 7262 1092 7440 +37647 1309 7259 1187 7369 +37648 1242 7369 7349 7458 +37649 840 877 933 7253 +37650 1418 1317 7293 7414 +37651 7294 7295 7223 7342 +37652 7232 7295 7294 7342 +37653 1482 1359 745 724 +37654 90 91 1330 7305 +37655 1030 7279 1018 7350 +37656 981 7297 802 7445 +37657 7216 7258 7257 7388 +37658 1113 1133 1099 7339 +37659 1184 1493 7360 7453 +37660 1141 1126 1102 7245 +37661 7351 7359 7314 7371 +37662 1457 7365 7264 7375 +37663 1354 1194 1434 7343 +37664 7283 7321 7231 7453 +37665 1442 1361 7276 7304 +37666 861 7296 1027 7362 +37667 968 929 782 7252 +37668 1200 7342 7291 7382 +37669 824 859 945 7401 +37670 7226 7388 7257 7454 +37671 1025 7277 1002 7438 +37672 801 7272 916 7426 +37673 966 828 862 7362 +37674 82 1002 1025 7277 +37675 1097 7281 1130 7421 +37676 1099 7266 1127 7286 +37677 7215 7263 7278 7432 +37678 1086 1087 885 7378 +37679 7264 7339 1328 7375 +37680 817 893 985 7279 +37681 7371 7411 775 7456 +37682 849 7322 7302 7428 +37683 1337 7308 7329 7418 +37684 7283 7302 7250 7347 +37685 1126 7274 7245 7440 +37686 7282 7328 813 7341 +37687 946 7256 7292 7341 +37688 1160 7273 1159 7432 +37689 1105 1128 7264 7405 +37690 1015 7313 994 7455 +37691 100 7252 786 7378 +37692 7259 7215 7369 7424 +37693 7232 7298 7275 7357 +37694 1433 1211 1338 7249 +37695 7314 7351 7216 7359 +37696 7257 7290 7216 7352 +37697 835 962 933 7387 +37698 7242 7425 7273 7441 +37699 1354 85 84 1434 +37700 804 906 7287 7340 +37701 1260 1485 1311 7245 +37702 7285 7236 7406 7448 +37703 1327 1313 7246 7345 +37704 7259 7310 1310 7377 +37705 832 7333 7289 7358 +37706 1508 1293 1223 7258 +37707 1093 1132 7264 7339 +37708 1153 1155 1163 7255 +37709 809 7251 7263 7331 +37710 7258 7314 1371 7434 +37711 960 852 969 7301 +37712 7246 7225 7327 7357 +37713 7298 7357 7232 7373 +37714 1078 7350 1071 7450 +37715 6 1474 1224 7269 +37716 983 7346 855 7383 +37717 1008 7299 7362 7444 +37718 888 7312 1115 7315 +37719 1464 87 7318 7406 +37720 1159 1160 977 7273 +37721 1129 7239 1106 7395 +37722 854 7347 7250 7428 +37723 1457 7264 1328 7375 +37724 1153 1163 209 7399 +37725 81 1002 82 7277 +37726 1327 7246 1214 7363 +37727 973 870 1092 7262 +37728 7231 7291 7295 7322 +37729 7323 7333 7332 7395 +37730 968 882 821 7252 +37731 7249 7277 7228 7400 +37732 7268 7391 7267 7436 +37733 7275 7357 7298 7373 +37734 1399 7314 96 7371 +37735 87 1012 7318 7406 +37736 1126 7274 1137 7332 +37737 679 717 1041 1377 +37738 678 718 1378 1040 +37739 7291 7322 7236 7415 +37740 1311 7245 1485 7329 +37741 7226 7293 7388 7454 +37742 825 943 895 7266 +37743 7297 7302 7270 7402 +37744 7272 7397 7266 7426 +37745 859 7373 7327 7401 +37746 898 7299 1024 7438 +37747 838 1086 885 7378 +37748 7231 7321 7284 7453 +37749 7234 7316 7264 7339 +37750 7253 7320 7229 7416 +37751 7285 7298 997 7435 +37752 1444 1445 89 1265 +37753 1352 7381 1221 7410 +37754 900 918 829 7419 +37755 1034 1035 1293 7314 +37756 1158 1155 1152 7255 +37757 777 775 7371 7411 +37758 877 7374 7387 7413 +37759 7294 7295 991 7433 +37760 1125 1136 1101 7263 +37761 1348 1245 1513 7356 +37762 931 38 883 820 +37763 969 7301 7256 7341 +37764 998 7438 7299 7444 +37765 673 1386 1203 1283 +37766 891 7301 7389 7459 +37767 865 942 1123 7316 +37768 1400 1036 7268 7436 +37769 101 786 7252 7378 +37770 89 90 1476 1193 +37771 827 954 887 7285 +37772 1006 1023 897 7335 +37773 1109 1130 7281 7421 +37774 1169 7267 1168 7436 +37775 1177 7242 7353 7399 +37776 7222 7301 7277 7326 +37777 7277 7301 7228 7326 +37778 907 7313 1015 7319 +37779 7239 7381 1106 7395 +37780 1311 1511 1260 7355 +37781 1253 7249 1515 7343 +37782 7259 7369 7310 7424 +37783 1009 1026 7296 7309 +37784 889 7401 851 7430 +37785 7235 7299 7249 7444 +37786 7285 7298 7232 7407 +37787 897 953 824 7335 +37788 7249 7280 7235 7343 +37789 1289 7304 7269 7408 +37790 1493 1287 7270 7394 +37791 7228 7280 7249 7400 +37792 1013 954 1029 7285 +37793 1100 7240 1125 7458 +37794 7226 7313 7293 7454 +37795 1311 1260 7245 7355 +37796 6 1071 144 7350 +37797 718 78 79 1363 +37798 1219 7336 7241 7456 +37799 1024 1008 998 7299 +37800 978 7287 7315 7396 +37801 7253 877 7387 7413 +37802 1218 7310 7267 7377 +37803 911 7254 964 7364 +37804 7230 7244 7372 7422 +37805 951 186 870 7440 +37806 1514 7320 1313 7345 +37807 1163 209 7399 7441 +37808 1361 7276 7304 7408 +37809 80 1190 1474 7324 +37810 910 7374 7238 7401 +37811 1422 7267 1174 7436 +37812 1115 956 888 7315 +37813 7228 7338 7328 7422 +37814 7328 7338 7244 7422 +37815 7257 7313 815 7451 +37816 6 7269 1071 7350 +37817 852 7330 7256 7459 +37818 887 954 1013 7285 +37819 1105 7365 1111 7405 +37820 1200 1392 7342 7382 +37821 7246 7303 7221 7387 +37822 866 7294 962 7373 +37823 1458 707 90 753 +37824 901 7281 7379 7396 +37825 7259 7276 1240 7412 +37826 7319 7335 7247 7455 +37827 7320 7354 7229 7410 +37828 7290 7352 7257 7404 +37829 7277 7326 7228 7400 +37830 7242 7310 7255 7424 +37831 774 679 1435 1377 +37832 7255 7278 7215 7369 +37833 935 923 795 7352 +37834 7221 7303 7246 7345 +37835 7232 7285 7407 7415 +37836 998 7299 1008 7444 +37837 7276 7326 1305 7338 +37838 1406 7275 1243 7318 +37839 644 34 7258 7386 +37840 87 1388 1464 7318 +37841 1413 1394 7372 7376 +37842 7245 7274 7224 7420 +37843 991 7295 7294 7407 +37844 1424 1473 739 1282 +37845 1477 1371 7314 7434 +37846 1109 7281 7396 7421 +37847 1071 7350 7269 7450 +37848 917 7282 813 7341 +37849 7346 7383 7274 7420 +37850 1179 87 1464 7406 +37851 7233 7282 7272 7426 +37852 7295 7322 7291 7415 +37853 1378 678 711 773 +37854 801 878 916 7272 +37855 951 7274 1140 7440 +37856 843 7322 7295 7415 +37857 1200 1390 7291 7342 +37858 1318 1190 80 7324 +37859 1396 7342 1273 7442 +37860 998 1025 7438 7444 +37861 7226 7257 7313 7454 +37862 7284 7321 1519 7453 +37863 1006 996 1023 7335 +37864 7240 7263 7251 7331 +37865 959 861 981 7296 +37866 7230 7402 7347 7403 +37867 7219 7265 7260 7384 +37868 1216 1449 1323 7355 +37869 7250 7321 7283 7375 +37870 989 7243 842 7370 +37871 1132 1128 1098 7264 +37872 1493 7283 7372 7394 +37873 952 1109 1118 7281 +37874 1413 1247 1394 7376 +37875 7226 7317 7352 7388 +37876 7264 7365 7321 7375 +37877 7325 7354 7227 7365 +37878 812 879 843 7428 +37879 1314 1210 1317 7247 +37880 7286 7356 1245 7429 +37881 7307 7374 814 7413 +37882 952 896 823 7281 +37883 1353 1504 1257 7436 +37884 1276 1225 1429 7384 +37885 832 807 890 7333 +37886 849 7297 7302 7322 +37887 864 7315 1109 7396 +37888 822 964 911 7254 +37889 7230 7302 7347 7402 +37890 1038 1363 718 1040 +37891 1041 717 1039 1364 +37892 1388 88 1243 7318 +37893 1075 7390 7391 7417 +37894 1328 1457 1269 7264 +37895 1127 7286 7266 7361 +37896 1439 1253 1515 7343 +37897 7264 7321 7250 7375 +37898 1443 1200 7318 7382 +37899 1080 1079 1082 7355 +37900 7224 7307 7271 7383 +37901 7245 7224 7418 7420 +37902 1480 7336 1219 7456 +37903 993 857 912 7427 +37904 7261 7262 7217 7378 +37905 1485 1512 1222 7332 +37906 999 7296 1026 7362 +37907 90 707 1458 751 +37908 1243 7318 7275 7382 +37909 1375 7284 1519 7453 +37910 7232 7298 7285 7435 +37911 1219 7241 7371 7456 +37912 1120 914 1144 7331 +37913 1124 7264 1132 7339 +37914 1135 1112 1098 7312 +37915 1459 1298 1524 7384 +37916 7218 7364 7292 7424 +37917 1168 1175 178 7391 +37918 752 708 1183 1432 +37919 1368 1337 1246 7308 +37920 773 711 1378 1436 +37921 7224 7332 7323 7333 +37922 7291 7342 7232 7382 +37923 7242 7310 7218 7353 +37924 782 875 929 968 +37925 724 1482 1359 1203 +37926 7251 7292 856 7337 +37927 1366 666 725 1255 +37928 1435 660 712 774 +37929 7306 7429 7244 7449 +37930 7244 7233 7311 7429 +37931 908 1117 7333 7358 +37932 7349 7412 7306 7431 +37933 7245 7418 7329 7420 +37934 7227 7315 7312 7419 +37935 1263 668 716 1473 +37936 987 7337 7292 7425 +37937 7246 7221 7345 7387 +37938 946 992 858 7348 +37939 1082 1086 7262 7378 +37940 1130 1107 7381 7421 +37941 1390 1273 1396 7342 +37942 1454 7247 1314 7380 +37943 1110 7331 1120 7361 +37944 7349 7369 7278 7458 +37945 7277 7368 81 7409 +37946 7242 7218 7310 7424 +37947 771 1048 1483 1379 +37948 968 882 7252 7370 +37949 1122 1114 1094 7356 +37950 671 1510 750 1430 +37951 7234 7372 7311 7457 +37952 1274 7416 7345 7439 +37953 998 1024 7299 7438 +37954 784 777 7359 7411 +37955 865 1112 957 7316 +37956 7326 7368 1315 7400 +37957 1485 7332 1222 7418 +37958 799 7299 955 7389 +37959 7226 7260 7388 7414 +37960 1497 1416 1193 7275 +37961 7245 7355 185 7440 +37962 7220 7244 7338 7449 +37963 765 1296 1386 1238 +37964 7230 7283 7270 7394 +37965 1231 1327 7303 7345 +37966 1474 80 6 1190 +37967 910 7327 7374 7401 +37968 7327 7357 7225 7373 +37969 1071 7269 79 7450 +37970 1093 7264 1132 7316 +37971 1400 1036 1294 7268 +37972 1078 1071 79 7450 +37973 877 7253 840 7379 +37974 7309 7406 1213 7446 +37975 1313 1273 7342 7442 +37976 1491 1325 1242 7369 +37977 1380 7311 7286 7429 +37978 1432 83 754 1381 +37979 874 1138 1101 7263 +37980 893 985 7279 7459 +37981 1435 712 679 774 +37982 1270 7339 7286 7457 +37983 7289 7413 7379 7416 +37984 852 992 7256 7330 +37985 1457 7321 7365 7375 +37986 1287 7270 7366 7446 +37987 7221 7323 7308 7439 +37988 1352 7354 7320 7410 +37989 1406 89 1193 7275 +37990 7232 7285 7318 7435 +37991 7250 7302 7231 7428 +37992 7220 7306 7412 7431 +37993 7287 7340 906 7433 +37994 1185 1383 649 1452 +37995 1312 7381 1367 7395 +37996 967 819 881 7425 +37997 7293 7313 7226 7393 +37998 100 7334 7252 7378 +37999 88 1406 1243 7318 +38000 1317 1408 92 1210 +38001 7225 7327 7373 7401 +38002 739 716 668 1473 +38003 91 1210 1330 7305 +38004 821 7252 882 7423 +38005 1394 7376 7280 7394 +38006 1030 1018 144 7350 +38007 669 1425 738 1235 +38008 791 7347 7402 7403 +38009 1368 7265 1186 7329 +38010 952 1118 896 7281 +38011 786 7252 7334 7411 +38012 965 912 810 7427 +38013 7323 7221 7416 7439 +38014 1359 653 745 724 +38015 7226 7288 7260 7414 +38016 854 919 7347 7428 +38017 1290 7293 7258 7434 +38018 1041 1043 679 1377 +38019 1040 1378 678 1042 +38020 749 709 670 1445 +38021 7302 7322 7231 7428 +38022 922 7271 789 7367 +38023 885 1087 101 7378 +38024 1461 1286 7291 7446 +38025 1413 7311 1192 7429 +38026 1389 1413 1192 7429 +38027 639 644 7258 7386 +38028 1363 718 78 1038 +38029 1039 717 34 1364 +38030 887 7285 1013 7392 +38031 1276 7265 1368 7384 +38032 1181 7338 7326 7400 +38033 923 935 837 7404 +38034 1263 716 692 1516 +38035 7302 7347 919 7428 +38036 1445 1299 709 1265 +38037 1196 1361 7304 7408 +38038 7236 7406 7309 7446 +38039 947 989 857 7243 +38040 83 7343 7249 7444 +38041 658 1261 1467 1502 +38042 1338 82 1211 1268 +38043 7215 7251 7337 7431 +38044 958 7250 854 7419 +38045 1327 1313 1214 7246 +38046 89 1445 1244 753 +38047 1520 7308 1246 7418 +38048 1454 1210 1314 7247 +38049 861 1010 1027 7296 +38050 1370 1191 734 1486 +38051 935 7290 837 7404 +38052 1214 7357 7342 7382 +38053 1186 7265 1417 7336 +38054 7289 7221 7413 7416 +38055 7257 7386 7290 7404 +38056 7315 7325 7227 7405 +38057 79 1224 78 7269 +38058 968 821 929 7252 +38059 878 813 916 7328 +38060 654 734 1486 1237 +38061 1033 831 907 7455 +38062 1524 1298 1505 7303 +38063 7275 7305 7225 7385 +38064 7299 7300 7228 7389 +38065 979 7251 809 7331 +38066 76 7268 1036 7436 +38067 1403 1492 714 1262 +38068 812 843 915 7428 +38069 654 734 1237 767 +38070 1475 1189 93 7293 +38071 7218 7242 7353 7364 +38072 908 868 807 7333 +38073 1177 7399 209 7441 +38074 723 1500 1398 744 +38075 947 842 7243 7271 +38076 813 7282 916 7328 +38077 1293 1371 7258 7314 +38078 831 7335 7319 7455 +38079 7294 991 7340 7433 +38080 1449 7261 1079 7355 +38081 1213 7366 7309 7446 +38082 709 670 1445 753 +38083 864 978 7315 7396 +38084 43 44 637 7257 +38085 1507 1217 7255 7369 +38086 673 720 1386 1283 +38087 7256 7330 992 7348 +38088 1169 1176 1174 7436 +38089 1300 768 1052 1051 +38090 799 862 7299 7300 +38091 7289 7333 7239 7358 +38092 973 1092 1091 7262 +38093 850 7289 7307 7413 +38094 896 7281 1108 7358 +38095 7317 7352 853 7451 +38096 37 38 784 7359 +38097 33 717 1278 1364 +38098 1523 1227 7293 7414 +38099 89 1445 1444 1244 +38100 7313 7393 7293 7454 +38101 7295 7407 843 7415 +38102 1169 1174 7267 7436 +38103 1380 7286 7311 7457 +38104 1385 7276 1305 7338 +38105 958 854 7250 7428 +38106 1381 1194 84 1434 +38107 7234 7316 7266 7397 +38108 1254 1416 1497 7305 +38109 7329 7418 7224 7420 +38110 1305 7326 1181 7338 +38111 958 7250 7419 7428 +38112 896 823 7281 7358 +38113 846 7397 7272 7426 +38114 1429 7260 1331 7434 +38115 813 7328 847 7341 +38116 907 7319 1015 7455 +38117 1357 1217 1491 7278 +38118 889 910 851 7401 +38119 90 1476 1193 1330 +38120 983 940 855 7346 +38121 7275 7357 7373 7385 +38122 7237 7269 7268 7304 +38123 1515 7249 1338 7343 +38124 1092 870 186 7440 +38125 871 7350 1066 7390 +38126 791 7347 7302 7402 +38127 1161 1162 1357 7278 +38128 145 1066 871 7350 +38129 7281 7358 823 7379 +38130 1216 7261 1449 7355 +38131 1368 7308 1246 7384 +38132 865 957 980 7316 +38133 1380 7286 1245 7429 +38134 7227 7344 7287 7419 +38135 7303 7398 7308 7439 +38136 7225 7357 7246 7363 +38137 809 7263 874 7331 +38138 1491 7278 1217 7369 +38139 1289 7269 7324 7408 +38140 7259 7215 7349 7369 +38141 7222 7277 7301 7459 +38142 7225 7373 7357 7385 +38143 710 671 1234 1510 +38144 1357 1297 1161 7278 +38145 845 917 921 7282 +38146 892 916 7282 7426 +38147 1399 96 1421 7371 +38148 1009 7309 7296 7448 +38149 88 709 1299 1265 +38150 1388 87 88 7318 +38151 1476 1444 89 1193 +38152 1310 1240 7259 7377 +38153 1110 834 1120 7331 +38154 1416 7357 1214 7382 +38155 38 640 7290 7359 +38156 1099 1133 1127 7266 +38157 1028 87 1012 7318 +38158 1477 7314 7351 7434 +38159 7320 7345 1274 7416 +38160 1475 93 1 7293 +38161 706 1049 1046 1456 +38162 7259 7349 1187 7369 +38163 848 7287 906 7433 +38164 7252 7334 7217 7378 +38165 7239 7289 7379 7416 +38166 762 669 715 1425 +38167 7247 7226 7319 7393 +38168 917 921 7282 7341 +38169 848 7344 7287 7433 +38170 1419 1474 1190 7324 +38171 850 7307 7289 7383 +38172 900 7287 7344 7419 +38173 7253 7379 877 7413 +38174 715 1341 762 1425 +38175 1050 1483 728 771 +38176 1422 1174 1176 7436 +38177 7275 7225 7357 7385 +38178 7232 7295 7291 7415 +38179 7275 7373 7298 7385 +38180 7277 7228 7301 7389 +38181 864 978 956 7315 +38182 1000 7335 1033 7455 +38183 901 970 7281 7396 +38184 7272 7347 846 7403 +38185 1242 1325 1384 7349 +38186 1523 1331 1227 7414 +38187 1075 7390 1076 7450 +38188 1408 91 92 1210 +38189 1294 1224 1372 7269 +38190 1341 762 1425 738 +38191 1298 1231 7303 7439 +38192 1174 1422 1345 7267 +38193 762 1341 715 1241 +38194 1335 1 33 1223 +38195 1249 1493 7283 7372 +38196 1181 7376 7338 7400 +38197 1364 33 34 1223 +38198 907 867 7313 7319 +38199 1196 7304 1289 7408 +38200 754 708 83 1432 +38201 7238 7303 7374 7398 +38202 897 1033 1006 7335 +38203 1013 1029 997 7285 +38204 932 964 822 7254 +38205 1027 7296 999 7362 +38206 1352 1221 1522 7410 +38207 7389 7437 808 7459 +38208 96 1399 1035 7314 +38209 1075 1076 1074 7450 +38210 7260 7288 7219 7384 +38211 669 1425 1235 1302 +38212 1129 1108 7281 7358 +38213 145 7279 1030 7350 +38214 968 810 882 7370 +38215 7218 7242 7364 7424 +38216 7220 7276 7259 7412 +38217 7274 7333 7224 7383 +38218 7267 7353 7310 7399 +38219 7259 7412 7349 7431 +38220 1304 7306 7349 7412 +38221 913 847 7301 7389 +38222 7230 7347 7272 7403 +38223 996 1003 7298 7385 +38224 944 7289 793 7379 +38225 825 7266 903 7426 +38226 1499 655 772 735 +38227 1173 1177 210 7441 +38228 1405 654 1486 1237 +38229 959 1010 861 7296 +38230 7221 7398 7303 7439 +38231 7303 7221 7374 7398 +38232 835 877 7374 7387 +38233 7346 7420 7274 7440 +38234 1310 7310 1470 7377 +38235 7231 7284 7360 7453 +38236 7264 7312 7227 7405 +38237 7259 1356 7349 7412 +38238 1416 1279 7275 7382 +38239 1186 7329 7265 7336 +38240 7226 7257 7352 7451 +38241 1429 7351 7260 7434 +38242 823 901 970 7281 +38243 1002 7277 81 7409 +38244 1226 7368 7326 7408 +38245 1416 7305 1254 7363 +38246 1253 1338 1515 7249 +38247 1191 741 734 1486 +38248 7232 7275 7298 7435 +38249 1136 1125 1100 7240 +38250 1405 654 1237 767 +38251 1224 6 79 1334 +38252 1078 7390 7350 7450 +38253 1477 7314 1256 7351 +38254 707 670 753 1332 +38255 92 7393 7247 7455 +38256 1170 1166 1172 7399 +38257 929 101 782 7252 +38258 1274 7345 1468 7439 +38259 7230 7280 7300 7422 +38260 1244 1476 89 753 +38261 861 981 7296 7362 +38262 826 959 981 7296 +38263 1470 1309 1258 7310 +38264 1386 695 765 1238 +38265 1033 907 1015 7455 +38266 692 1336 1263 1516 +38267 84 710 1234 1434 +38268 89 7275 88 7435 +38269 7390 7391 7237 7450 +38270 851 928 7367 7374 +38271 850 7307 814 7413 +38272 38 37 640 7359 +38273 1166 1169 1174 7267 +38274 850 920 7289 7413 +38275 1478 1196 1353 7304 +38276 7222 7304 7276 7408 +38277 1359 745 675 1267 +38278 817 893 7279 7330 +38279 7217 7261 7334 7336 +38280 1480 1259 7336 7456 +38281 1408 92 91 1238 +38282 1445 89 709 753 +38283 7238 7374 7327 7401 +38284 7262 7420 7346 7440 +38285 7225 7305 7363 7380 +38286 1109 7396 7315 7421 +38287 7228 7300 7280 7422 +38288 7241 7411 7371 7456 +38289 7229 7315 7287 7396 +38290 894 853 7352 7451 +38291 895 1110 1146 7266 +38292 1432 754 1234 1381 +38293 96 785 1421 7371 +38294 752 83 708 1432 +38295 1113 1134 1270 7339 +38296 668 1263 1501 1473 +38297 7227 7250 7344 7419 +38298 903 7266 825 7397 +38299 1156 1158 1162 7278 +38300 1216 1321 1449 7261 +38301 7292 7337 7251 7431 +38302 827 7285 887 7392 +38303 7217 7334 7252 7443 +38304 1028 7285 997 7435 +38305 1214 7342 1392 7382 +38306 724 1359 653 1203 +38307 1187 1309 1310 7259 +38308 1514 1188 1313 7320 +38309 943 7266 825 7426 +38310 1148 1115 888 7312 +38311 1416 1214 7357 7363 +38312 819 936 881 7425 +38313 673 765 1296 1386 +38314 722 675 1215 1359 +38315 1095 7332 7333 7395 +38316 7233 7361 7331 7426 +38317 1470 1310 1309 7310 +38318 836 873 925 7273 +38319 1016 7313 1031 7454 +38320 7271 7346 986 7370 +38321 1108 896 1118 7281 +38322 899 981 802 7445 +38323 776 784 780 7248 +38324 34 639 644 7258 +38325 793 7289 920 7413 +38326 849 7302 7297 7402 +38327 1496 1208 1307 7356 +38328 7319 7393 7313 7455 +38329 990 841 7292 7425 +38330 1154 1153 208 7255 +38331 838 1091 1086 7262 +38332 900 978 7287 7315 +38333 1304 7306 1208 7349 +38334 944 7358 7289 7379 +38335 76 77 7268 7450 +38336 809 979 856 7251 +38337 1462 1306 1111 7365 +38338 942 895 1146 7266 +38339 739 668 1501 1473 +38340 671 710 1234 754 +38341 1442 1361 1240 7276 +38342 1475 1223 1290 7258 +38343 82 81 1211 1397 +38344 7252 7370 882 7423 +38345 901 7281 823 7379 +38346 641 7359 7314 7386 +38347 793 944 890 7289 +38348 101 100 786 7378 +38349 1326 697 1517 1456 +38350 7261 7217 7334 7378 +38351 959 7296 826 7392 +38352 903 7397 846 7426 +38353 1224 1474 6 1334 +38354 1049 706 1326 1456 +38355 913 847 813 7328 +38356 835 7374 7327 7387 +38357 1306 7325 1111 7365 +38358 1175 7391 7254 7417 +38359 7229 7396 7281 7421 +38360 669 715 1425 741 +38361 1132 1105 1128 7264 +38362 1183 1409 752 1432 +38363 89 7385 7275 7435 +38364 891 7301 847 7389 +38365 7232 7318 7275 7435 +38366 7226 7388 7293 7414 +38367 7285 7392 7236 7448 +38368 911 7348 7254 7364 +38369 1363 79 718 1277 +38370 1423 1270 1134 7286 +38371 1466 1232 702 1395 +38372 1175 1171 179 7254 +38373 1253 1433 7249 7400 +38374 645 639 637 7404 +38375 1432 752 83 1268 +38376 922 7307 7271 7367 +38377 1290 1523 7293 7434 +38378 7290 7386 643 7404 +38379 7250 7231 7344 7428 +38380 1385 1305 1181 7338 +38381 827 860 7407 7415 +38382 7254 7353 1175 7452 +38383 1512 1141 1142 7332 +38384 743 668 1373 1501 +38385 1093 1124 1132 7339 +38386 81 82 1211 7368 +38387 1505 7303 7363 7380 +38388 1510 1342 710 750 +38389 905 7415 7285 7445 +38390 1454 1489 1254 7305 +38391 7276 7338 1385 7412 +38392 1253 1433 1338 7249 +38393 1219 7371 1503 7456 +38394 7250 7347 7302 7428 +38395 1080 185 7355 7440 +38396 716 692 742 1263 +38397 7222 7368 7326 7409 +38398 7294 7342 7246 7357 +38399 1269 1462 1145 7365 +38400 7277 7222 7326 7409 +38401 1384 1304 1208 7349 +38402 1381 83 1338 1268 +38403 79 1071 6 7269 +38404 955 799 862 7299 +38405 7292 7424 7364 7425 +38406 7232 7342 7294 7357 +38407 7265 7329 7217 7336 +38408 1082 1085 1086 7378 +38409 1185 649 699 1452 +38410 908 7333 832 7358 +38411 641 640 7359 7386 +38412 7277 7326 7368 7409 +38413 83 84 7343 7444 +38414 731 1282 1452 1428 +38415 1307 1348 1122 7356 +38416 7294 7373 866 7407 +38417 908 807 832 7333 +38418 708 671 1340 754 +38419 844 7300 799 7328 +38420 1268 752 82 1397 +38421 7294 7327 7246 7387 +38422 815 923 869 7257 +38423 1263 1373 668 1501 +38424 7271 7307 7219 7367 +38425 1251 1500 1344 744 +38426 718 1277 1378 1040 +38427 717 1041 1377 1278 +38428 1242 1384 1496 7458 +38429 184 7245 1141 7355 +38430 856 7292 987 7337 +38431 1190 80 6 1447 +38432 35 1034 1508 1293 +38433 1254 7305 1489 7363 +38434 1366 725 666 758 +38435 1246 7308 1337 7418 +38436 754 1340 708 1432 +38437 1090 1091 1092 7262 +38438 744 1251 1398 721 +38439 1435 1229 660 774 +38440 1157 1160 1159 7432 +38441 2 96 7314 7371 +38442 1378 711 678 1042 +38443 1501 739 1473 1282 +38444 874 818 948 7263 +38445 739 656 1424 1282 +38446 1429 1331 1195 7434 +38447 7217 7346 7262 7420 +38448 7221 7308 7398 7439 +38449 1136 1120 1101 7331 +38450 998 1008 1004 7444 +38451 831 7319 907 7455 +38452 1016 7393 7313 7454 +38453 678 1277 748 1378 +38454 679 1377 747 1278 +38455 84 1026 85 7309 +38456 1279 1243 7275 7382 +38457 646 643 7386 7404 +38458 1476 89 1444 1244 +38459 86 1324 85 7406 +38460 1282 1452 699 731 +38461 946 921 788 7292 +38462 873 1160 203 7432 +38463 1259 7447 7336 7456 +38464 7247 7226 7393 7414 +38465 796 938 911 7348 +38466 710 84 85 1434 +38467 772 655 1499 1212 +38468 1161 1156 1162 7278 +38469 793 890 920 7289 +38470 809 988 874 7263 +38471 964 7254 932 7452 +38472 678 718 1277 1378 +38473 1377 679 717 1278 +38474 826 7296 981 7445 +38475 919 7302 904 7347 +38476 900 7287 848 7344 +38477 81 80 1318 1412 +38478 994 7393 1014 7455 +38479 7223 7295 7294 7433 +38480 750 1510 1342 1199 +38481 83 84 754 1381 +38482 859 866 962 7373 +38483 1003 1007 996 7298 +38484 777 2 7359 7371 +38485 1169 1168 5 7436 +38486 1242 7349 1384 7458 +38487 891 7389 808 7459 +38488 1005 90 1022 7385 +38489 947 857 993 7317 +38490 851 910 928 7374 +38491 1471 721 1498 1266 +38492 1211 1318 81 7368 +38493 7297 7322 849 7445 +38494 648 643 7290 7386 +38495 7277 7222 7409 7459 +38496 1256 7351 7314 7371 +38497 1273 1200 1392 7342 +38498 1445 670 749 1332 +38499 666 697 725 1255 +38500 977 873 836 7273 +38501 7224 7289 7307 7383 +38502 979 809 892 7331 +38503 7290 7359 640 7386 +38504 672 1202 723 1410 +38505 996 7335 1005 7385 +38506 1293 1477 1371 7314 +38507 662 703 1517 1255 +38508 7379 7413 7253 7416 +38509 1520 7323 7308 7418 +38510 803 7373 7298 7407 +38511 36 641 7314 7386 +38512 697 1046 1044 1456 +38513 1378 773 1436 1228 +38514 7248 7216 7359 7427 +38515 1299 1487 729 1518 +38516 891 808 7389 7437 +38517 1439 7280 7343 7366 +38518 7326 7368 7222 7408 +38519 643 640 648 7290 +38520 1388 1243 1464 7318 +38521 202 7278 201 7458 +38522 1393 1232 698 726 +38523 7320 7354 1352 7442 +38524 7262 7217 7378 7423 +38525 853 7317 993 7352 +38526 864 956 1131 7315 +38527 731 1452 688 1236 +38528 1458 1275 90 751 +38529 7215 7337 7292 7431 +38530 7252 7378 7217 7423 +38531 913 891 847 7389 +38532 850 920 890 7289 +38533 642 7290 643 7404 +38534 1232 702 665 1466 +38535 7255 7310 7242 7399 +38536 1105 1111 1128 7405 +38537 1406 89 1444 1193 +38538 1231 7345 7303 7439 +38539 964 7364 7254 7452 +38540 710 671 1510 750 +38541 1120 834 914 7331 +38542 850 7289 890 7383 +38543 924 7346 7262 7423 +38544 88 1388 1243 1406 +38545 7277 7409 7437 7459 +38546 7264 7227 7365 7405 +38547 1443 1200 1286 7318 +38548 7271 855 7346 7383 +38549 1387 1063 732 1062 +38550 7324 7222 7368 7408 +38551 901 840 7253 7379 +38552 7286 7311 7233 7429 +38553 7308 7224 7329 7418 +38554 744 674 1251 721 +38555 790 962 7294 7340 +38556 90 89 1476 753 +38557 1102 1126 1137 7332 +38558 43 7257 637 7454 +38559 1433 1490 1315 7400 +38560 1166 1168 7267 7353 +38561 985 7437 7279 7459 +38562 1150 1455 1312 7381 +38563 768 1300 704 1051 +38564 1482 724 1411 1203 +38565 946 7256 992 7348 +38566 869 7257 923 7404 +38567 7262 7245 7420 7440 +38568 1234 710 84 754 +38569 7223 7354 7320 7442 +38570 756 674 1465 733 +38571 1274 1221 1352 7320 +38572 7226 7352 7257 7388 +38573 7224 7333 7289 7383 +38574 7268 7269 7237 7450 +38575 1268 1409 752 1397 +38576 1499 1336 735 1252 +38577 1471 674 661 721 +38578 77 1294 1509 1037 +38579 1097 1106 1129 7381 +38580 1350 7381 1151 7410 +38581 1142 1369 1512 7332 +38582 684 1407 1053 1054 +38583 854 919 904 7347 +38584 949 1019 145 7279 +38585 1435 679 1043 1377 +38586 1196 1289 1361 7408 +38587 7285 7415 7236 7445 +38588 1132 1124 1105 7264 +38589 1492 681 714 1262 +38590 1321 1089 7261 7447 +38591 803 971 7298 7373 +38592 732 755 1387 1062 +38593 80 7368 7324 7409 +38594 1158 1159 7273 7432 +38595 1232 698 702 1395 +38596 675 732 755 1387 +38597 1287 7366 1213 7446 +38598 7285 7236 7392 7445 +38599 835 933 877 7387 +38600 846 7347 7272 7397 +38601 1449 1321 1089 7261 +38602 1030 1018 7279 7409 +38603 1017 950 44 7313 +38604 1388 1179 87 1464 +38605 7216 7314 7258 7434 +38606 1224 79 78 1363 +38607 1145 1463 1462 1269 +38608 1483 728 771 1379 +38609 1417 1186 1276 7265 +38610 944 823 7358 7379 +38611 905 7285 7392 7445 +38612 1277 718 1363 1040 +38613 717 1041 1278 1364 +38614 765 673 695 1386 +38615 1300 767 1237 730 +38616 1414 1245 7356 7429 +38617 1508 1364 34 1223 +38618 641 2 7314 7359 +38619 1285 723 1202 1410 +38620 1297 7278 1491 7458 +38621 7218 7310 7267 7353 +38622 1233 1516 716 1473 +38623 900 829 978 7315 +38624 80 81 7368 7409 +38625 1394 7280 1207 7394 +38626 1312 1106 7381 7395 +38627 795 935 7352 7427 +38628 1223 1335 1 1475 +38629 184 1141 1440 7355 +38630 754 84 1234 1381 +38631 642 837 7290 7404 +38632 774 1435 1229 1377 +38633 1031 1017 44 7313 +38634 7275 7318 7232 7382 +38635 80 1295 1190 766 +38636 1434 1354 85 1250 +38637 752 708 663 1183 +38638 1175 7254 179 7417 +38639 1152 1153 1154 7255 +38640 1293 1035 1399 7314 +38641 184 185 7245 7355 +38642 977 836 1159 7273 +38643 715 1341 1425 1451 +38644 186 951 1140 7440 +38645 1452 1383 688 1236 +38646 1122 1348 1114 7356 +38647 1446 1121 1306 7325 +38648 7222 7301 7256 7459 +38649 1199 750 1510 1430 +38650 1069 7268 76 7391 +38651 1366 1044 725 758 +38652 856 934 988 7337 +38653 772 685 1316 1499 +38654 7216 7258 7314 7386 +38655 792 859 7327 7401 +38656 7266 7286 7233 7361 +38657 742 692 1336 1263 +38658 1010 999 1027 7296 +38659 1371 1223 1293 7258 +38660 705 1292 1056 1057 +38661 7296 7309 7236 7448 +38662 7238 7303 7288 7380 +38663 1233 716 1516 1391 +38664 1411 724 673 1203 +38665 7217 7336 7334 7443 +38666 864 1131 1109 7315 +38667 1388 88 1265 1406 +38668 1150 1119 1455 7381 +38669 1449 1089 1079 7261 +38670 7261 7334 1083 7378 +38671 1304 7349 1356 7412 +38672 665 1370 1232 1466 +38673 920 850 814 7413 +38674 1090 1082 7262 7440 +38675 711 1378 1436 1042 +38676 738 1425 1341 1235 +38677 718 678 1277 748 +38678 747 717 679 1278 +38679 947 842 989 7243 +38680 92 93 1450 1317 +38681 7218 7259 7310 7424 +38682 942 1146 1104 7266 +38683 7220 7412 7259 7431 +38684 1379 772 1316 1212 +38685 997 7298 1003 7435 +38686 1326 697 706 1517 +38687 7227 7321 7264 7365 +38688 7264 7234 7339 7375 +38689 1435 1065 712 760 +38690 76 7268 1069 7450 +38691 941 846 7347 7403 +38692 1270 7286 1380 7457 +38693 1451 715 1341 1241 +38694 6 1018 80 7324 +38695 1126 7245 185 7440 +38696 894 853 993 7352 +38697 1043 712 679 1435 +38698 208 7255 1153 7399 +38699 782 7252 786 7411 +38700 697 706 1046 1456 +38701 1336 735 1252 1415 +38702 1 700 1448 747 +38703 7288 7380 1347 7414 +38704 1524 7288 1347 7384 +38705 892 801 916 7426 +38706 1203 653 673 1283 +38707 1111 7365 7325 7405 +38708 1290 7258 1371 7434 +38709 1335 1 1448 747 +38710 7271 7383 7346 7420 +38711 844 7402 7300 7403 +38712 92 695 91 1238 +38713 1186 1368 1276 7265 +38714 892 7331 834 7426 +38715 723 659 672 1410 +38716 7259 7349 7215 7431 +38717 735 1336 692 1415 +38718 96 1035 2 7314 +38719 1265 1299 88 1388 +38720 36 7314 35 7386 +38721 1458 763 707 1332 +38722 1016 7293 7393 7454 +38723 1252 735 666 1415 +38724 893 7279 7330 7459 +38725 82 1025 83 7249 +38726 7308 7323 1520 7439 +38727 1294 1372 1478 7268 +38728 902 854 7250 7419 +38729 1520 1246 1337 7418 +38730 1342 1441 690 1272 +38731 1045 685 1460 1047 +38732 7249 7343 7235 7444 +38733 888 829 918 7312 +38734 1505 7303 1327 7363 +38735 1187 7259 1356 7349 +38736 735 692 666 1415 +38737 1356 7259 1240 7412 +38738 7324 7368 7222 7409 +38739 1401 7354 7284 7442 +38740 1004 7362 1026 7444 +38741 1189 93 1 1475 +38742 742 1373 668 1263 +38743 657 750 1199 1430 +38744 1509 1224 78 1363 +38745 1079 1085 1082 7261 +38746 1482 724 1284 1411 +38747 1298 1360 1231 7439 +38748 921 856 7251 7292 +38749 1324 1213 7309 7406 +38750 1345 1422 1504 7267 +38751 1275 90 91 1330 +38752 672 1239 1295 766 +38753 946 852 992 7256 +38754 1504 7267 1422 7436 +38755 1359 1453 653 1283 +38756 1310 1442 1240 7377 +38757 1108 108 896 7358 +38758 900 7344 800 7419 +38759 7294 7295 7232 7407 +38760 641 2 36 7314 +38761 814 7307 928 7374 +38762 7221 7253 7413 7416 +38763 1215 675 706 1326 +38764 830 957 888 7312 +38765 1012 7392 7285 7448 +38766 743 1373 1281 1185 +38767 1156 1158 7278 7432 +38768 897 831 1033 7335 +38769 89 1003 7385 7435 +38770 210 1177 209 7441 +38771 1499 772 685 735 +38772 772 1316 727 1379 +38773 1430 1199 657 1341 +38774 1202 723 1285 1500 +38775 7314 7359 2 7371 +38776 1492 714 664 1403 +38777 655 1499 1336 735 +38778 911 990 858 7348 +38779 1446 1121 7325 7410 +38780 1519 1375 1401 7284 +38781 7236 7297 7296 7445 +38782 1375 1230 1401 7284 +38783 946 788 969 7341 +38784 823 970 952 7281 +38785 1434 710 1234 1342 +38786 1114 7286 1127 7361 +38787 1491 1297 1357 7278 +38788 1355 1477 1256 7351 +38789 1218 1470 7310 7377 +38790 903 7266 7397 7426 +38791 1461 1286 1200 7291 +38792 743 1281 761 1185 +38793 1083 7334 7261 7447 +38794 701 6 80 1447 +38795 846 878 7272 7403 +38796 145 1070 1066 7350 +38797 874 948 1138 7263 +38798 739 1501 699 1282 +38799 1182 1458 707 751 +38800 1145 1111 1105 7365 +38801 1171 932 7254 7452 +38802 946 969 7256 7341 +38803 739 693 716 1473 +38804 1123 1104 1133 7316 +38805 691 1370 1191 734 +38806 1425 669 741 1302 +38807 639 34 33 7258 +38808 636 643 642 7290 +38809 1015 907 867 7313 +38810 702 691 665 1466 +38811 767 1237 1405 1300 +38812 1054 757 1393 1055 +38813 757 1393 1055 726 +38814 804 7287 978 7396 +38815 1137 7274 1103 7333 +38816 1449 1079 1323 7355 +38817 1078 1076 7390 7450 +38818 1448 765 1450 1296 +38819 1517 697 662 1255 +38820 7325 7405 7315 7421 +38821 746 669 1235 1302 +38822 789 922 947 7271 +38823 743 761 649 1185 +38824 827 7285 905 7415 +38825 1344 1251 744 733 +38826 1226 1315 7326 7368 +38827 832 896 108 7358 +38828 856 988 809 7251 +38829 1253 7280 1339 7400 +38830 797 7346 924 7423 +38831 1364 1278 33 1223 +38832 7223 7294 7340 7433 +38833 684 1407 1054 1329 +38834 1095 7333 1117 7358 +38835 1159 1155 1158 7273 +38836 845 892 916 7282 +38837 938 926 839 7390 +38838 1107 7410 7381 7421 +38839 1370 665 691 1466 +38840 5 76 7268 7391 +38841 932 1171 7254 7417 +38842 7216 7352 7290 7427 +38843 769 1498 650 1291 +38844 984 7313 867 7451 +38845 178 7391 1175 7417 +38846 1028 1012 997 7285 +38847 1108 1117 108 7358 +38848 1285 659 723 1410 +38849 1097 1130 1107 7381 +38850 836 1164 7273 7441 +38851 752 696 82 1397 +38852 185 1126 184 7245 +38853 7224 7274 7383 7420 +38854 1391 1403 714 1262 +38855 674 1251 1465 733 +38856 1010 7296 959 7392 +38857 706 697 1326 1456 +38858 7230 7372 7283 7394 +38859 973 1091 838 7262 +38860 997 1007 1003 7298 +38861 1200 1273 1390 7342 +38862 7258 7293 7388 7434 +38863 1220 7306 7412 7449 +38864 781 7447 1437 7456 +38865 1077 7390 1075 7417 +38866 790 962 991 7294 +38867 754 1234 1340 1432 +38868 1190 1295 80 1447 +38869 1428 731 689 1487 +38870 1287 7366 7270 7394 +38871 1261 1376 658 1467 +38872 868 1143 1140 7274 +38873 915 7322 843 7415 +38874 1242 1297 1491 7458 +38875 7272 7347 7234 7397 +38876 842 7271 986 7370 +38877 1215 1387 675 1326 +38878 1009 85 1026 7309 +38879 1499 1316 772 1212 +38880 1070 1066 7350 7390 +38881 7334 7336 7241 7443 +38882 791 941 7347 7403 +38883 801 846 7272 7426 +38884 1418 7293 1227 7414 +38885 7241 7336 7265 7443 +38886 1008 7362 1004 7444 +38887 1090 1080 1082 7440 +38888 734 741 654 1486 +38889 5 7391 7268 7436 +38890 1434 85 710 1342 +38891 671 1340 1510 1430 +38892 1340 1183 708 1432 +38893 7290 7359 7216 7427 +38894 782 101 786 7252 +38895 1232 665 698 726 +38896 987 7292 841 7425 +38897 843 7295 991 7407 +38898 1473 739 693 1424 +38899 1471 1398 721 1266 +38900 1371 1290 1223 7258 +38901 1103 1140 1143 7274 +38902 1498 721 680 1266 +38903 791 904 7302 7347 +38904 7235 7343 7280 7366 +38905 1164 1155 7273 7441 +38906 96 778 785 7371 +38907 648 7290 640 7386 +38908 662 675 706 1215 +38909 203 1138 948 7263 +38910 715 694 762 1241 +38911 838 924 870 7262 +38912 1413 1319 7311 7372 +38913 1446 1151 1121 7410 +38914 1194 1515 1338 7343 +38915 672 696 1239 766 +38916 1153 1152 1155 7255 +38917 1288 7309 1213 7366 +38918 7381 7410 7229 7421 +38919 778 777 775 7371 +38920 1020 1002 81 7409 +38921 776 784 7248 7411 +38922 1398 652 723 744 +38923 1318 1226 1419 7324 +38924 817 926 893 7330 +38925 928 922 789 7367 +38926 83 7249 1025 7444 +38927 1090 1092 186 7440 +38928 1340 708 1183 764 +38929 932 7254 822 7417 +38930 910 792 7327 7401 +38931 7265 7336 7217 7443 +38932 763 670 707 1332 +38933 758 1366 1044 1460 +38934 1500 682 1344 744 +38935 636 642 883 7290 +38936 1202 723 1500 1398 +38937 980 963 7316 7397 +38938 944 832 7289 7358 +38939 1229 1335 1448 747 +38940 1436 1061 711 1042 +38941 1149 1099 1114 7286 +38942 1058 1349 1465 756 +38943 731 1428 1236 1487 +38944 1303 1352 7354 7442 +38945 7247 7380 7288 7414 +38946 6 748 1334 1447 +38947 7230 7394 7280 7422 +38948 1430 657 694 1341 +38949 1500 723 682 744 +38950 1261 728 1483 1379 +38951 1394 1339 7280 7376 +38952 1171 7254 1175 7452 +38953 701 659 773 1410 +38954 7226 7313 7257 7451 +38955 1075 1069 7391 7450 +38956 826 7392 7296 7445 +38957 1502 1467 658 1281 +38958 666 1366 758 1252 +38959 1327 1231 1313 7345 +38960 1383 688 1365 1235 +38961 7277 7409 1002 7437 +38962 811 911 964 7364 +38963 824 971 859 7373 +38964 777 778 2 7371 +38965 750 694 671 1430 +38966 7336 7447 7334 7456 +38967 1291 702 769 1395 +38968 1285 723 682 1500 +38969 883 642 837 7290 +38970 1189 1450 93 1317 +38971 1127 7266 1110 7361 +38972 1487 729 689 1299 +38973 7280 7366 1207 7394 +38974 714 693 763 1403 +38975 1299 729 87 1518 +38976 661 702 1395 1204 +38977 1264 7323 1374 7418 +38978 700 765 1448 1296 +38979 874 988 818 7263 +38980 996 1006 1005 7335 +38981 179 7254 1171 7417 +38982 1345 1504 1218 7267 +38983 1466 702 1291 1395 +38984 902 958 854 7419 +38985 7257 7352 7216 7388 +38986 1249 1493 7372 7394 +38987 1524 1347 1225 7384 +38988 1159 836 1164 7273 +38989 986 7346 797 7370 +38990 697 662 706 1517 +38991 748 6 701 1447 +38992 1226 7326 1305 7408 +38993 1208 7356 7306 7429 +38994 807 7274 983 7383 +38995 1319 7311 7372 7457 +38996 917 788 921 7341 +38997 81 82 696 1397 +38998 1234 1340 671 754 +38999 7345 7387 7221 7416 +39000 800 7344 958 7419 +39001 1229 1448 700 747 +39002 7308 7384 7219 7398 +39003 696 752 1409 1397 +39004 946 990 841 7292 +39005 1243 1406 1279 7275 +39006 917 813 847 7341 +39007 802 862 880 7402 +39008 1212 655 1499 1336 +39009 1195 1331 1523 7434 +39010 7221 7253 7387 7413 +39011 1191 1425 715 741 +39012 668 1373 742 743 +39013 731 656 1282 1428 +39014 1282 699 656 731 +39015 1249 1493 1343 7283 +39016 1343 7375 7283 7453 +39017 650 680 1498 769 +39018 1115 7315 7312 7405 +39019 936 794 881 7425 +39020 7262 7346 7217 7423 +39021 1437 7447 1259 7456 +39022 744 1251 674 733 +39023 1432 1409 752 1268 +39024 1415 666 1366 1255 +39025 76 5 7268 7436 +39026 1284 660 712 1435 +39027 7296 7392 1010 7448 +39028 7294 7232 7357 7373 +39029 1106 1150 1312 7381 +39030 7307 7367 928 7374 +39031 1465 1349 674 756 +39032 1381 1432 83 1268 +39033 1394 1339 1207 7280 +39034 7284 7354 7223 7442 +39035 1181 1315 1490 7400 +39036 1044 758 1460 1045 +39037 201 7278 1297 7458 +39038 1030 145 1019 7279 +39039 1412 1211 81 1397 +39040 1513 1423 1149 7286 +39041 793 7379 7289 7413 +39042 1249 7283 1343 7372 +39043 852 893 7330 7459 +39044 80 1020 81 7409 +39045 100 1083 7334 7378 +39046 844 799 913 7328 +39047 1107 1151 7381 7410 +39048 1409 752 663 1183 +39049 1097 1109 1130 7281 +39050 1261 658 676 1502 +39051 1400 7268 1257 7436 +39052 1516 1263 716 1473 +39053 1284 724 660 1411 +39054 1324 86 85 1250 +39055 1166 1168 1169 7267 +39056 1264 7332 7323 7418 +39057 1141 184 1126 7245 +39058 1295 701 80 1447 +39059 1448 93 1 1189 +39060 91 1275 1408 1238 +39061 838 924 7262 7423 +39062 1486 1302 654 1405 +39063 1288 7343 7309 7366 +39064 1248 7325 1479 7354 +39065 7338 7376 7244 7422 +39066 955 7389 7299 7438 +39067 639 7258 33 7454 +39068 1030 7279 995 7409 +39069 7228 7376 7338 7422 +39070 762 694 1341 1241 +39071 1231 1327 1505 7303 +39072 1185 743 1373 1501 +39073 7229 7315 7396 7421 +39074 1486 734 1370 1237 +39075 7222 7256 7330 7459 +39076 870 973 838 7262 +39077 866 7373 803 7407 +39078 1228 701 773 1410 +39079 886 7390 1077 7417 +39080 1314 7380 7247 7414 +39081 7288 7219 7384 7398 +39082 1099 1149 1134 7286 +39083 1296 700 673 1411 +39084 1359 675 1215 1267 +39085 685 1460 1047 1316 +39086 722 1453 653 1359 +39087 1387 706 675 1326 +39088 1460 758 1366 1252 +39089 1251 1471 1398 721 +39090 951 816 868 7274 +39091 1458 707 763 1182 +39092 7221 7303 7345 7439 +39093 681 1492 720 1283 +39094 7218 7310 7259 7377 +39095 1321 1088 1089 7447 +39096 720 1420 1386 1283 +39097 1239 81 696 1397 +39098 1476 1275 90 1458 +39099 946 969 852 7256 +39100 720 673 653 1283 +39101 1075 7391 1067 7417 +39102 736 688 1365 1236 +39103 1102 1142 1141 7332 +39104 712 1043 1065 1435 +39105 757 1329 1054 1393 +39106 766 1190 80 1412 +39107 7252 7411 7248 7443 +39108 1370 684 665 1329 +39109 1456 697 1517 1255 +39110 7326 7338 7228 7400 +39111 34 35 1039 1508 +39112 7288 7303 7238 7398 +39113 7239 7358 7281 7379 +39114 663 696 1409 1484 +39115 1220 7306 1304 7412 +39116 1505 7363 1489 7380 +39117 738 1365 688 1235 +39118 696 663 719 1484 +39119 739 699 656 1282 +39120 7218 7353 7254 7364 +39121 1107 7325 7410 7421 +39122 756 1465 1058 733 +39123 641 648 640 7386 +39124 918 830 7312 7419 +39125 1256 1503 1355 7371 +39126 741 691 1191 734 +39127 1207 7280 1439 7366 +39128 765 1450 93 1448 +39129 984 815 7313 7451 +39130 1493 1404 1287 7394 +39131 855 986 7271 7346 +39132 747 1335 33 1278 +39133 1248 7325 7354 7410 +39134 801 846 878 7272 +39135 1226 7324 7368 7408 +39136 862 7300 880 7402 +39137 1303 7354 1401 7442 +39138 1262 651 1351 770 +39139 820 7290 935 7427 +39140 1078 1076 1073 7390 +39141 1517 703 1351 1255 +39142 1256 1355 7351 7371 +39143 1480 1417 1219 7336 +39144 7260 7351 7216 7434 +39145 1173 210 930 7441 +39146 703 662 697 1255 +39147 1190 1318 80 1412 +39148 975 803 7298 7407 +39149 1453 681 653 1283 +39150 7283 7375 7321 7453 +39151 1395 1292 661 1204 +39152 1474 1289 7269 7324 +39153 1373 1281 686 743 +39154 1379 676 772 1212 +39155 1492 681 1453 1283 +39156 7271 7307 922 7383 +39157 999 1026 1004 7362 +39158 1123 1133 1093 7316 +39159 999 1009 1026 7296 +39160 1420 720 1492 1283 +39161 1127 1114 1099 7286 +39162 7236 7392 7445 7448 +39163 1159 1164 836 977 +39164 1325 1187 7349 7369 +39165 80 701 1295 766 +39166 1298 1231 1505 7303 +39167 1313 1188 1273 7442 +39168 832 890 944 7289 +39169 1106 1312 1150 7395 +39170 1342 710 1234 1510 +39171 178 1175 179 7417 +39172 687 654 1405 737 +39173 1471 1251 674 721 +39174 747 33 717 1278 +39175 814 7374 877 7413 +39176 769 1291 1395 1204 +39177 684 1237 767 730 +39178 7313 7319 7226 7393 +39179 82 83 752 1268 +39180 1451 691 650 1466 +39181 849 7302 919 7428 +39182 1403 693 763 1332 +39183 1362 696 719 1484 +39184 827 860 975 7407 +39185 1069 7268 7391 7450 +39186 7286 7233 7356 7429 +39187 748 79 6 1334 +39188 1232 1292 698 1395 +39189 7241 7248 7411 7443 +39190 742 668 716 1263 +39191 7219 7307 7308 7398 +39192 1323 1511 1216 7355 +39193 898 955 7299 7438 +39194 7237 7391 7390 7417 +39195 1113 1270 196 7339 +39196 1383 649 688 746 +39197 1021 1019 872 7279 +39198 7309 7406 7236 7448 +39199 201 1161 1297 7278 +39200 690 710 1342 750 +39201 1235 1383 688 746 +39202 1500 1251 1398 744 +39203 7216 7351 7314 7434 +39204 1249 1404 1493 7394 +39205 814 850 928 7307 +39206 750 657 694 1430 +39207 709 689 88 1299 +39208 1121 1111 1306 7325 +39209 1233 716 693 1473 +39210 1277 748 1378 1228 +39211 747 1377 1229 1278 +39212 7226 7352 7317 7451 +39213 1260 1431 1440 7355 +39214 731 667 689 1487 +39215 1341 1365 738 1235 +39216 7228 7328 7300 7422 +39217 728 1483 1376 1261 +39218 1466 1451 691 1191 +39219 684 1370 734 1237 +39220 804 906 848 7287 +39221 7221 7307 7289 7413 +39222 663 1409 1183 1484 +39223 1086 103 885 1087 +39224 1387 755 706 1062 +39225 724 673 660 1411 +39226 785 783 1421 7371 +39227 7292 7337 7215 7424 +39228 1341 657 694 762 +39229 749 1201 1445 1332 +39230 1236 667 731 1487 +39231 750 1342 690 1199 +39232 1335 33 1 747 +39233 721 1398 652 1266 +39234 1129 1108 1097 7281 +39235 654 1405 737 767 +39236 7312 7315 7227 7405 +39237 844 7300 7328 7403 +39238 1212 740 655 1373 +39239 910 7327 835 7374 +39240 1407 1300 1237 730 +39241 1450 1408 92 1317 +39242 1464 7318 1286 7406 +39243 984 894 815 7451 +39244 1061 759 1488 1436 +39245 7236 7445 7296 7448 +39246 1052 730 1407 1053 +39247 7252 7217 7370 7423 +39248 1351 703 651 1197 +39249 958 7419 7344 7428 +39250 736 1365 657 1199 +39251 1193 1416 1279 7275 +39252 891 7389 833 7437 +39253 85 7309 1009 7448 +39254 860 843 7407 7415 +39255 1237 684 1370 1329 +39256 7237 7254 7391 7417 +39257 850 7307 922 7367 +39258 651 716 1233 1391 +39259 859 962 835 7327 +39260 1183 1340 764 1320 +39261 1203 1359 653 1283 +39262 1509 78 77 1038 +39263 743 699 668 1501 +39264 1033 1000 1006 7335 +39265 985 872 7279 7437 +39266 1418 1227 1317 7414 +39267 661 674 1471 1349 +39268 7334 7447 99 7456 +39269 1453 770 1215 722 +39270 654 741 1302 1486 +39271 7299 7389 7277 7438 +39272 665 684 1370 734 +39273 696 1362 1409 1484 +39274 1198 1274 1468 7439 +39275 1355 1477 7351 7434 +39276 1479 7325 1306 7365 +39277 1353 7304 1442 7377 +39278 925 936 836 7273 +39279 880 7300 844 7402 +39280 1403 714 1233 1391 +39281 882 986 797 7370 +39282 772 727 676 1379 +39283 86 1324 1441 1250 +39284 1291 1451 650 1466 +39285 990 7348 911 7364 +39286 1386 1296 673 1203 +39287 853 7430 7317 7451 +39288 724 683 1482 1284 +39289 1414 1380 1245 7429 +39290 993 795 7352 7427 +39291 1016 994 7313 7393 +39292 1339 1253 1439 7280 +39293 1264 1367 7323 7395 +39294 1314 1347 1180 7380 +39295 709 749 1201 1445 +39296 1181 7326 1315 7400 +39297 7259 7215 7424 7431 +39298 178 5 1168 7391 +39299 791 7302 849 7402 +39300 1305 7326 7276 7408 +39301 1197 692 1336 1415 +39302 1232 1370 665 1329 +39303 1048 771 727 1379 +39304 706 675 755 1387 +39305 861 966 981 7362 +39306 7287 7223 7340 7433 +39307 702 665 698 1232 +39308 1351 1262 770 1453 +39309 687 654 1302 1405 +39310 697 666 703 1255 +39311 79 7269 78 7450 +39312 1201 1299 709 1445 +39313 203 1125 7263 7432 +39314 1341 1365 657 738 +39315 1314 1347 7380 7414 +39316 1420 695 720 1386 +39317 1282 656 1424 1428 +39318 1452 688 699 731 +39319 1291 769 1498 1204 +39320 1462 1111 1145 7365 +39321 689 1428 1487 1299 +39322 650 702 1291 1466 +39323 698 705 1292 1056 +39324 695 673 720 1386 +39325 1399 1256 7314 7371 +39326 1415 703 666 1255 +39327 702 650 691 1466 +39328 1336 1212 655 1373 +39329 1179 86 87 7406 +39330 1272 729 667 1487 +39331 1013 7285 1012 7392 +39332 1504 1218 7267 7377 +39333 1363 1224 79 1277 +39334 7266 7361 7233 7426 +39335 1284 1065 1435 760 +39336 765 92 1450 1238 +39337 7217 7346 7271 7370 +39338 7321 7375 1280 7453 +39339 1296 1448 700 1411 +39340 7298 7373 7232 7407 +39341 774 1229 700 747 +39342 773 748 701 1228 +39343 1454 1489 7305 7380 +39344 896 944 823 7358 +39345 1110 1127 1104 7266 +39346 1484 680 719 1266 +39347 1104 1127 1133 7266 +39348 7260 7216 7388 7434 +39349 1441 86 690 1272 +39350 1489 7363 7305 7380 +39351 991 927 790 7433 +39352 872 1021 7279 7437 +39353 1344 682 1060 1059 +39354 680 721 1498 769 +39355 728 1376 658 1261 +39356 1275 91 695 1238 +39357 1082 1086 1091 7262 +39358 662 703 1351 1517 +39359 7221 7308 7307 7398 +39360 1451 650 715 1241 +39361 1078 79 78 7450 +39362 1287 1213 1494 7446 +39363 743 649 699 1185 +39364 982 850 890 7383 +39365 1089 1083 7261 7447 +39366 7239 7289 7358 7379 +39367 7253 7221 7387 7416 +39368 1034 1039 35 1508 +39369 1507 1309 1217 7369 +39370 1313 1273 1214 7342 +39371 1246 1520 1360 7439 +39372 1138 1125 1101 7263 +39373 759 1488 1060 1061 +39374 1240 1356 1310 7259 +39375 720 653 681 1283 +39376 663 1183 764 1320 +39377 7274 7420 7245 7440 +39378 1355 1219 1276 7351 +39379 1296 765 1450 1238 +39380 672 701 1295 1410 +39381 1220 1301 7306 7449 +39382 1015 994 1014 7455 +39383 1248 7354 1352 7410 +39384 7296 7445 7392 7448 +39385 7319 7401 889 7430 +39386 691 1370 1466 1191 +39387 90 1275 1476 1330 +39388 726 1055 55 1056 +39389 1078 1074 1076 7450 +39390 7277 7437 1002 7438 +39391 681 714 664 1492 +39392 7226 7319 7313 7451 +39393 1095 1108 1129 7358 +39394 1197 651 1351 1391 +39395 748 1228 1334 1447 +39396 797 7370 7346 7423 +39397 1362 672 1239 1295 +39398 87 88 1299 1388 +39399 1482 745 683 724 +39400 1199 1365 657 1341 +39401 1181 1358 7338 7376 +39402 1284 1065 760 1064 +39403 145 1030 144 7350 +39404 1031 1016 994 7313 +39405 1237 734 684 767 +39406 7350 7390 7237 7450 +39407 701 672 659 1410 +39408 1373 655 1336 742 +39409 1275 695 91 751 +39410 730 1407 1300 1052 +39411 904 919 791 7302 +39412 1151 1350 1119 7381 +39413 1075 1074 1069 7450 +39414 1501 699 668 739 +39415 685 1499 735 1252 +39416 835 877 814 7374 +39417 1383 1365 688 1236 +39418 1 1448 1189 1335 +39419 7298 7385 1003 7435 +39420 93 700 765 1448 +39421 1281 761 686 743 +39422 1208 7306 1301 7429 +39423 1291 1498 650 1320 +39424 688 738 1235 746 +39425 7220 7412 7306 7449 +39426 1435 712 1284 760 +39427 2 778 96 7371 +39428 1264 7323 7332 7395 +39429 805 854 904 7347 +39430 785 778 783 7371 +39431 828 955 862 7299 +39432 744 682 1344 733 +39433 856 841 987 7292 +39434 7252 7370 7217 7443 +39435 1018 80 7324 7409 +39436 671 708 1340 764 +39437 798 849 7322 7445 +39438 1411 673 1296 1203 +39439 1197 703 692 1415 +39440 1098 1115 7312 7405 +39441 736 1365 1469 1236 +39442 769 661 721 1204 +39443 1134 1149 1423 7286 +39444 974 7317 853 7430 +39445 7238 7374 7367 7398 +39446 7224 7383 7271 7420 +39447 1113 1093 1133 7339 +39448 720 1492 664 1420 +39449 733 1465 1058 1059 +39450 1226 7324 1318 7368 +39451 1061 711 759 1436 +39452 928 7307 850 7367 +39453 1403 1233 693 1332 +39454 708 663 1183 764 +39455 1318 1211 81 1412 +39456 1275 91 90 751 +39457 1246 7308 1520 7439 +39458 648 646 643 7386 +39459 1442 1196 1361 7304 +39460 844 7328 878 7403 +39461 951 868 1140 7274 +39462 7222 7276 7326 7408 +39463 748 1277 79 1334 +39464 1416 1214 1279 7382 +39465 7310 7353 7242 7399 +39466 789 947 974 7367 +39467 7233 7286 7356 7361 +39468 1518 87 1299 1388 +39469 1228 748 701 1447 +39470 1442 1353 1196 7304 +39471 1264 7332 1495 7395 +39472 741 669 746 1302 +39473 1071 1078 1070 7350 +39474 1501 1452 699 1282 +39475 1275 1458 1182 751 +39476 798 7322 7415 7445 +39477 1156 7278 202 7432 +39478 1391 651 1351 1262 +39479 7232 7373 7294 7407 +39480 932 179 1171 7417 +39481 1334 1474 6 1190 +39482 797 924 937 7423 +39483 768 730 1300 1052 +39484 1495 7332 1116 7395 +39485 745 722 653 1359 +39486 1312 1221 1367 7381 +39487 1093 1132 1112 7316 +39488 89 1003 1022 7385 +39489 899 826 981 7445 +39490 638 972 647 7404 +39491 786 7334 779 7411 +39492 762 1341 657 738 +39493 1284 1229 660 1435 +39494 901 804 970 7396 +39495 78 1509 1363 1038 +39496 1364 34 1039 1508 +39497 1333 649 1383 746 +39498 1451 715 691 1191 +39499 980 963 865 7316 +39500 7338 7376 7228 7400 +39501 901 877 840 7379 +39502 894 795 923 7352 +39503 1021 995 1019 7279 +39504 1394 1404 1249 7394 +39505 946 841 921 7292 +39506 1387 732 1063 1267 +39507 1190 6 1334 1447 +39508 1037 1509 77 1038 +39509 1381 84 1234 1434 +39510 696 672 1239 1362 +39511 1084 101 1087 7378 +39512 1340 671 694 1430 +39513 7258 7388 7216 7434 +39514 765 700 673 1296 +39515 761 1333 649 1185 +39516 1277 79 718 748 +39517 744 1398 652 721 +39518 882 7370 797 7423 +39519 1082 1091 1090 7262 +39520 43 1016 1031 7454 +39521 686 655 740 1373 +39522 660 683 724 1284 +39523 646 7386 644 7404 +39524 843 991 7295 7433 +39525 1487 1272 729 1518 +39526 7334 7336 7261 7447 +39527 7236 7322 7297 7445 +39528 1362 719 652 1266 +39529 1083 1085 7261 7378 +39530 1350 1151 1446 7410 +39531 1451 1425 715 1191 +39532 798 7322 915 7415 +39533 193 1306 1446 1121 +39534 7334 7411 7252 7443 +39535 693 714 1233 1403 +39536 978 829 956 7315 +39537 1330 91 1275 1210 +39538 770 662 1215 722 +39539 879 7344 848 7433 +39540 1469 1365 736 1199 +39541 7259 7424 7292 7431 +39542 1328 1124 1113 7339 +39543 750 690 657 1199 +39544 1222 1264 1374 7418 +39545 846 941 878 7403 +39546 651 1197 1516 1391 +39547 1380 7311 1192 7457 +39548 721 652 680 1266 +39549 799 891 913 7389 +39550 993 912 795 7427 +39551 1181 1358 1385 7338 +39552 1089 1088 1083 7447 +39553 1391 714 651 1262 +39554 1332 1458 763 1182 +39555 1192 7311 1319 7457 +39556 838 103 885 1086 +39557 1047 1048 727 1316 +39558 784 777 37 7359 +39559 1329 1054 684 757 +39560 699 743 1185 1501 +39561 1498 680 650 1320 +39562 1234 671 1340 1510 +39563 640 636 38 7290 +39564 695 92 765 1238 +39565 695 1275 1420 751 +39566 1370 691 665 734 +39567 900 879 800 7344 +39568 1188 7320 1352 7442 +39569 934 794 925 7337 +39570 7241 7411 7334 7443 +39571 729 87 689 1299 +39572 792 945 859 7401 +39573 667 690 729 1272 +39574 7322 7236 7415 7445 +39575 1005 7335 1000 7455 +39576 816 983 868 7274 +39577 992 7330 796 7348 +39578 764 1340 713 1320 +39579 636 883 38 7290 +39580 729 689 667 1487 +39581 740 772 676 1212 +39582 714 651 1233 1391 +39583 1452 731 1428 1236 +39584 76 1036 5 7436 +39585 770 1215 1351 1453 +39586 201 1297 1382 7458 +39587 1197 692 651 1516 +39588 1361 1305 7276 7408 +39589 886 839 1077 7390 +39590 1488 682 1060 1344 +39591 995 7279 1021 7437 +39592 880 7402 844 7403 +39593 7308 7323 7224 7418 +39594 770 1262 681 1453 +39595 801 903 846 7426 +39596 1125 202 201 7458 +39597 1030 995 1018 7409 +39598 1107 7325 1121 7410 +39599 1095 1116 7332 7395 +39600 1465 1251 1344 733 +39601 1518 1179 87 1388 +39602 1351 662 1215 770 +39603 1401 1303 1479 7354 +39604 1469 1272 667 1487 +39605 866 991 7294 7407 +39606 1300 1376 704 1051 +39607 939 861 1027 7362 +39608 1385 1240 7276 7412 +39609 716 651 1516 1391 +39610 811 990 911 7364 +39611 1247 1358 7376 7449 +39612 2 1035 36 7314 +39613 853 947 993 7317 +39614 1336 692 1197 1516 +39615 1226 1315 1305 7326 +39616 1453 653 681 722 +39617 1110 895 117 834 +39618 900 848 879 7344 +39619 660 673 700 1411 +39620 961 7430 853 7451 +39621 1081 1323 1079 7355 +39622 7254 7348 7218 7364 +39623 1394 1249 7372 7394 +39624 7220 7338 7276 7412 +39625 1049 1387 706 1062 +39626 1395 702 769 1204 +39627 1167 7353 1177 7452 +39628 990 7364 811 7425 +39629 845 916 917 7282 +39630 645 646 644 7404 +39631 700 660 1229 774 +39632 1237 684 1407 730 +39633 1460 758 685 1045 +39634 736 657 690 1199 +39635 1495 1369 1116 7332 +39636 1355 1195 1477 7434 +39637 7220 7338 7412 7449 +39638 1485 1337 7329 7418 +39639 900 978 804 7287 +39640 1502 740 1212 1373 +39641 1276 1368 1225 7384 +39642 1421 7371 783 7456 +39643 947 7317 974 7367 +39644 1351 1215 662 1517 +39645 1096 1111 7325 7405 +39646 709 689 1299 1201 +39647 7292 7337 7424 7425 +39648 1514 1274 7320 7345 +39649 1158 1157 1159 7432 +39650 48 718 678 1040 +39651 72 679 717 1041 +39652 1429 1355 1276 7351 +39653 1239 696 81 766 +39654 661 1471 721 1204 +39655 1241 650 713 1320 +39656 1352 1248 1303 7354 +39657 86 1179 1324 7406 +39658 1333 1383 649 1185 +39659 1354 7309 1288 7343 +39660 1502 658 686 1281 +39661 995 1002 7409 7437 +39662 652 1398 1362 1266 +39663 1235 738 669 746 +39664 1072 1077 839 7390 +39665 7241 7336 7334 7456 +39666 1070 1073 1066 7390 +39667 838 937 924 7423 +39668 1467 1206 658 1281 +39669 1159 1164 1155 7273 +39670 1253 1490 1433 7400 +39671 1038 718 47 1040 +39672 1041 717 73 1039 +39673 794 7337 987 7425 +39674 724 653 673 1203 +39675 781 99 7447 7456 +39676 811 7364 964 7452 +39677 7232 7357 7275 7382 +39678 803 866 859 7373 +39679 1341 694 1430 1241 +39680 1304 1187 1356 7349 +39681 1220 1301 1304 7306 +39682 1040 678 48 1042 +39683 679 72 1043 1041 +39684 1418 1475 1290 7293 +39685 828 898 955 7299 +39686 1222 7332 1264 7418 +39687 652 672 1202 723 +39688 838 885 937 7423 +39689 1333 761 1206 1281 +39690 7293 7393 7226 7414 +39691 989 882 810 7370 +39692 852 893 992 7330 +39693 1095 1117 1108 7358 +39694 1385 1220 7412 7449 +39695 1278 1335 33 1223 +39696 1295 1190 766 1412 +39697 663 696 752 1409 +39698 1192 7311 1380 7429 +39699 790 933 962 7340 +39700 7290 7216 7359 7386 +39701 1441 86 1272 1518 +39702 1213 1354 1324 7309 +39703 1340 713 694 764 +39704 1437 99 1426 7447 +39705 93 1016 7293 7393 +39706 1520 1374 7323 7418 +39707 1084 1087 1086 7378 +39708 798 7415 905 7445 +39709 693 1233 1473 1424 +39710 740 1502 686 1373 +39711 1343 7283 1493 7453 +39712 1197 1351 703 1415 +39713 1399 1421 1256 7371 +39714 1201 749 1424 1332 +39715 1436 711 759 1285 +39716 763 664 714 1403 +39717 833 7437 7389 7438 +39718 707 664 1182 751 +39719 974 947 853 7317 +39720 865 1123 1112 7316 +39721 1267 1359 745 1482 +39722 763 693 670 1332 +39723 1290 1523 1227 7293 +39724 914 809 874 7331 +39725 1167 1175 7353 7452 +39726 1264 1369 1495 7332 +39727 1405 1206 737 1300 +39728 1113 196 1328 7339 +39729 806 984 867 7451 +39730 836 7273 936 7441 +39731 1329 684 665 757 +39732 7232 7407 7295 7415 +39733 1393 698 1292 1056 +39734 7238 7401 7319 7430 +39735 1206 761 658 1281 +39736 943 825 903 7426 +39737 1268 82 1211 1397 +39738 1361 1305 1240 7276 +39739 7235 7309 7343 7366 +39740 1109 7315 1131 7421 +39741 684 1407 730 1053 +39742 1009 7296 1010 7448 +39743 1315 1211 1433 7368 +39744 1266 1484 680 1320 +39745 735 1336 655 742 +39746 1366 1044 166 1456 +39747 1044 1046 166 1456 +39748 674 1251 1471 1349 +39749 786 100 779 7334 +39750 1192 1413 1319 7311 +39751 5 1036 177 7436 +39752 1484 1183 663 1320 +39753 1137 1126 1103 7274 +39754 1095 1129 1106 7395 +39755 872 1019 949 7279 +39756 705 674 1349 756 +39757 1275 1182 1420 751 +39758 667 690 1272 1469 +39759 7267 7310 7218 7377 +39760 1420 1182 664 751 +39761 699 1185 1452 1501 +39762 1295 1202 672 1410 +39763 1000 1033 1015 7455 +39764 184 1440 1431 7355 +39765 719 663 680 1484 +39766 691 650 715 1451 +39767 703 692 651 1197 +39768 1513 1245 1423 7286 +39769 803 859 971 7373 +39770 930 967 876 7452 +39771 638 869 972 7404 +39772 1107 1121 7325 7421 +39773 728 658 676 1261 +39774 723 682 659 1285 +39775 1191 715 691 741 +39776 1279 1214 1392 7382 +39777 681 651 1262 770 +39778 1459 1368 1246 7384 +39779 93 7293 1016 7454 +39780 764 713 663 1320 +39781 7269 7350 7237 7450 +39782 700 93 1 1448 +39783 1057 1058 53 756 +39784 1012 1013 997 7285 +39785 1521 1213 1287 7366 +39786 1164 1163 1155 7441 +39787 1115 1131 956 7315 +39788 1400 177 1036 7436 +39789 7233 7306 7356 7429 +39790 36 648 641 7386 +39791 7228 7376 7280 7400 +39792 651 716 693 1233 +39793 881 990 811 7425 +39794 1302 741 1191 1486 +39795 1096 7405 7325 7421 +39796 1448 1450 93 1189 +39797 723 1202 652 1398 +39798 7217 7271 7346 7420 +39799 1522 1248 1352 7410 +39800 76 1069 77 7450 +39801 1209 1457 1328 7375 +39802 1420 664 695 751 +39803 1273 1392 1214 7342 +39804 947 922 842 7271 +39805 842 855 986 7271 +39806 1106 1119 1150 7381 +39807 657 1365 736 738 +39808 1344 1465 733 1059 +39809 1406 1193 1279 7275 +39810 995 1002 1020 7409 +39811 1383 1235 1333 746 +39812 813 917 916 7282 +39813 1420 1275 695 1238 +39814 7228 7280 7376 7422 +39815 672 652 1202 1362 +39816 741 1191 1425 1302 +39817 1289 1419 1226 7324 +39818 690 1469 736 1199 +39819 169 1063 1387 1062 +39820 87 88 689 1299 +39821 1410 1228 701 1447 +39822 1316 1048 727 1379 +39823 1398 1202 652 1362 +39824 781 99 1437 7447 +39825 1351 651 703 770 +39826 1308 1186 1417 7336 +39827 160 1300 1052 1051 +39828 1336 1373 742 1263 +39829 1409 1239 696 1397 +39830 1049 66 706 1046 +39831 1056 54 705 1057 +39832 1335 1189 1 1475 +39833 718 47 78 1038 +39834 34 73 717 1039 +39835 961 974 853 7430 +39836 7338 7376 1358 7449 +39837 85 1434 1250 1342 +39838 1131 7315 1096 7421 +39839 1343 1280 7375 7453 +39840 739 656 693 1424 +39841 1499 685 1316 1252 +39842 1232 698 1292 1393 +39843 1119 1350 1455 7381 +39844 893 926 796 7330 +39845 782 786 776 7411 +39846 1330 1210 1454 7305 +39847 1272 86 729 1518 +39848 43 637 639 7454 +39849 1415 1351 703 1255 +39850 686 1502 1281 1373 +39851 943 892 834 7426 +39852 904 941 846 7347 +39853 769 650 702 1291 +39854 656 689 749 1201 +39855 1396 1401 7284 7442 +39856 93 92 1450 765 +39857 1107 1151 1119 7381 +39858 1017 994 1015 7313 +39859 1247 1389 1358 7449 +39860 7314 7359 7216 7386 +39861 1098 1115 1148 7312 +39862 985 808 7437 7459 +39863 1407 684 1237 1329 +39864 1403 664 1492 1182 +39865 1436 759 1488 1285 +39866 7319 7335 831 7401 +39867 7235 7362 7299 7444 +39868 1379 1261 676 1502 +39869 681 651 714 1262 +39870 1505 1327 1489 7363 +39871 836 884 1164 7441 +39872 7353 7364 7242 7452 +39873 1147 1382 1307 7458 +39874 1148 112 888 1115 +39875 1376 1206 658 1467 +39876 1408 1275 91 1210 +39877 1333 761 1281 1185 +39878 938 7390 839 7417 +39879 1351 703 662 770 +39880 661 698 705 1292 +39881 1177 7353 1170 7399 +39882 736 667 688 1236 +39883 1349 674 1251 1465 +39884 1484 719 1362 1266 +39885 1215 662 675 722 +39886 203 202 1125 7432 +39887 80 81 766 1412 +39888 689 709 749 1201 +39889 687 1333 761 1206 +39890 1125 1138 203 7263 +39891 677 658 704 1376 +39892 935 820 883 7290 +39893 1443 7318 1243 7382 +39894 1050 161 1051 1483 +39895 7221 7374 7307 7413 +39896 7258 7257 7388 7454 +39897 1229 700 1448 1411 +39898 1420 695 1386 1238 +39899 1450 92 1408 1238 +39900 985 872 817 7279 +39901 650 694 715 1241 +39902 1257 1400 1294 7268 +39903 702 661 769 1204 +39904 648 36 35 7386 +39905 1227 1418 1290 7293 +39906 185 1080 1090 7440 +39907 980 805 963 7397 +39908 1422 1176 177 7436 +39909 827 905 860 7415 +39910 1474 1419 1289 7324 +39911 1248 1479 1303 7354 +39912 1288 1354 1213 7309 +39913 1179 87 86 1518 +39914 658 677 1206 1376 +39915 798 899 849 7445 +39916 1277 748 1228 1334 +39917 1229 1335 747 1278 +39918 1140 7274 1126 7440 +39919 1410 701 1295 1447 +39920 740 655 772 1212 +39921 1326 1387 706 1049 +39922 1324 1179 86 1441 +39923 688 667 731 1236 +39924 1484 663 680 1320 +39925 722 1215 1453 1359 +39926 1241 1291 650 1320 +39927 692 1336 735 742 +39928 1502 686 658 740 +39929 835 910 792 7327 +39930 640 37 641 7359 +39931 1373 686 655 742 +39932 1332 763 1403 1182 +39933 1303 1188 1352 7442 +39934 1441 1179 86 1518 +39935 967 7364 811 7452 +39936 1387 675 732 1267 +39937 193 1462 1306 1111 +39938 681 770 1453 722 +39939 974 7367 7317 7430 +39940 647 637 638 7404 +39941 1257 1294 1478 7268 +39942 1488 1060 682 759 +39943 791 941 904 7347 +39944 1095 7332 1137 7333 +39945 736 1365 688 738 +39946 907 806 867 7319 +39947 975 803 971 7298 +39948 880 941 7402 7403 +39949 793 877 7379 7413 +39950 800 879 958 7344 +39951 7323 7332 7224 7418 +39952 714 651 693 1233 +39953 1148 1135 1098 7312 +39954 1146 1110 1104 7266 +39955 1118 1097 1108 7281 +39956 1083 99 7334 7447 +39957 868 983 807 7274 +39958 716 651 692 1516 +39959 7279 7437 7409 7459 +39960 1077 1075 1067 7417 +39961 37 777 2 7359 +39962 1208 1414 7356 7429 +39963 1219 1503 1346 7456 +39964 689 656 1428 1201 +39965 1230 1396 1401 7284 +39966 1300 677 767 730 +39967 1308 7336 1259 7447 +39968 196 1270 1328 7339 +39969 1206 677 658 737 +39970 1339 1439 1207 7280 +39971 745 732 675 1267 +39972 184 1080 185 7355 +39973 727 685 1047 1316 +39974 878 844 813 7328 +39975 766 81 1239 1412 +39976 1483 1050 162 1048 +39977 1241 713 1340 1320 +39978 880 862 844 7300 +39979 971 863 975 7298 +39980 677 1206 1376 1300 +39981 1116 1369 1142 7332 +39982 1457 1280 7321 7375 +39983 956 888 112 1115 +39984 705 1292 1057 1349 +39985 201 1156 1161 7278 +39986 847 7301 969 7341 +39987 1027 1008 939 7362 +39988 1384 1325 1187 7349 +39989 1063 683 69 1064 +39990 682 51 1060 1059 +39991 735 666 685 1252 +39992 1271 1461 7291 7446 +39993 749 1424 656 1201 +39994 1004 1026 84 7444 +39995 7389 7437 7277 7438 +39996 1287 1521 7366 7394 +39997 7367 7374 7307 7398 +39998 1048 1047 163 1316 +39999 81 1239 1412 1397 +40000 741 687 654 1302 +40001 1243 1286 1464 7318 +40002 1316 727 685 772 +40003 650 1451 1291 1241 +40004 1204 661 1471 1349 +40005 666 692 703 1415 +40006 7229 7354 7325 7410 +40007 1107 1121 1151 7410 +40008 1264 1367 1198 7323 +40009 690 710 85 1342 +40010 683 1063 1402 1064 +40011 886 839 7390 7417 +40012 1271 7291 1390 7360 +40013 713 650 680 1320 +40014 1096 7325 1121 7421 +40015 643 636 640 7290 +40016 157 1054 1393 1055 +40017 1053 57 684 1054 +40018 1045 63 685 1047 +40019 1506 1308 1259 7447 +40020 797 940 924 7346 +40021 742 1373 686 743 +40022 1209 7375 7339 7457 +40023 55 698 726 1056 +40024 1337 1368 1186 7329 +40025 1300 704 677 768 +40026 1289 7324 1226 7408 +40027 1423 1380 1270 7286 +40028 1295 701 672 766 +40029 682 1344 733 1059 +40030 7279 7409 7222 7459 +40031 1346 1480 1219 7456 +40032 666 1366 1252 1415 +40033 921 856 979 7251 +40034 798 915 860 7415 +40035 1118 1109 1097 7281 +40036 1340 694 713 1241 +40037 791 7402 941 7403 +40038 7307 7374 7221 7398 +40039 685 758 1460 1252 +40040 1312 1455 1221 7381 +40041 711 659 759 1285 +40042 644 35 34 7386 +40043 675 1387 1215 1267 +40044 866 991 962 7294 +40045 1208 1348 1307 7356 +40046 1240 1305 1385 7276 +40047 918 830 888 7312 +40048 1271 1390 1472 7360 +40049 689 656 731 1428 +40050 937 885 821 7423 +40051 652 672 719 1362 +40052 745 683 732 1267 +40053 775 783 778 7456 +40054 1277 1224 79 1334 +40055 745 683 1267 1482 +40056 736 1469 667 1236 +40057 660 700 1229 1411 +40058 1051 704 60 1050 +40059 719 680 652 1266 +40060 761 658 687 1206 +40061 7227 7325 7365 7405 +40062 1344 1285 682 1500 +40063 1502 658 676 740 +40064 805 7347 846 7397 +40065 7275 7385 7298 7435 +40066 7346 7370 7217 7423 +40067 1340 694 671 764 +40068 849 919 812 7428 +40069 7247 7393 7319 7455 +40070 1446 7325 1248 7410 +40071 918 902 830 7419 +40072 963 903 825 7397 +40073 1289 1372 1224 7269 +40074 1166 1170 1168 7353 +40075 676 1379 1502 1212 +40076 850 922 7307 7383 +40077 729 690 86 1272 +40078 7334 7411 7241 7456 +40079 915 843 860 7415 +40080 1304 1301 1208 7306 +40081 1019 995 1030 7279 +40082 7244 7376 7338 7449 +40083 1001 1010 7392 7448 +40084 1096 7315 1115 7405 +40085 7230 7300 7403 7422 +40086 685 1460 1316 1252 +40087 694 1340 1430 1241 +40088 905 7285 827 7392 +40089 1206 687 1405 737 +40090 1065 1284 171 1064 +40091 694 650 713 1241 +40092 210 12 930 7441 +40093 705 661 1292 1349 +40094 928 850 922 7367 +40095 1262 1492 681 1453 +40096 638 44 4 869 +40097 1126 1140 1103 7274 +40098 193 1306 1121 1111 +40099 1187 1310 1356 7259 +40100 1289 1224 1474 7269 +40101 1137 1116 1102 7332 +40102 1121 1096 1111 7325 +40103 1207 7366 1521 7394 +40104 49 711 1061 1042 +40105 1043 71 712 1065 +40106 7219 7367 7307 7398 +40107 1000 1005 1006 7335 +40108 775 7411 779 7456 +40109 921 841 856 7292 +40110 1022 996 1005 7385 +40111 1038 148 1363 1040 +40112 1039 174 1041 1364 +40113 1093 1113 1124 7339 +40114 1403 763 664 1182 +40115 1284 660 1229 1411 +40116 7232 7342 7357 7382 +40117 1261 676 728 1379 +40118 1004 1025 998 7444 +40119 672 696 719 1362 +40120 1362 1239 696 1409 +40121 1461 1200 1271 7291 +40122 1479 1306 1205 7365 +40123 1469 690 1342 1199 +40124 1089 1085 1079 7261 +40125 1249 1343 1319 7372 +40126 1202 672 1362 1295 +40127 1284 712 660 760 +40128 646 642 643 7404 +40129 1164 884 1165 7441 +40130 7279 7222 7330 7459 +40131 1182 664 1492 1420 +40132 1481 1209 7339 7457 +40133 7364 7424 7242 7425 +40134 880 791 849 7402 +40135 758 685 666 1252 +40136 7258 7388 7293 7454 +40137 7230 7300 7402 7403 +40138 1046 1049 167 1456 +40139 641 37 2 7359 +40140 1311 1485 1337 7329 +40141 686 658 761 1281 +40142 1439 7343 1288 7366 +40143 939 133 898 1008 +40144 859 835 792 7327 +40145 1053 1407 158 1054 +40146 100 1084 1083 7378 +40147 664 681 1492 720 +40148 664 695 720 1420 +40149 851 7367 974 7430 +40150 1005 1000 1032 7455 +40151 7280 7376 1339 7400 +40152 1 7293 93 7454 +40153 1181 1305 1315 7326 +40154 1396 1303 1401 7442 +40155 1254 1497 1454 7305 +40156 1075 1077 1076 7390 +40157 1405 1302 687 1206 +40158 1222 1512 1369 7332 +40159 847 891 960 7301 +40160 201 202 1156 7278 +40161 1209 1328 7339 7375 +40162 676 1502 740 1212 +40163 1236 1469 667 1487 +40164 1423 1245 1380 7286 +40165 1001 7392 1012 7448 +40166 1017 1015 867 7313 +40167 1424 656 693 749 +40168 136 1010 959 7392 +40169 775 778 7371 7456 +40170 690 1342 1272 1469 +40171 101 1084 100 7378 +40172 852 960 893 7459 +40173 1014 7393 92 7455 +40174 766 1239 1295 1412 +40175 955 833 7389 7438 +40176 1068 179 13 7417 +40177 7292 7424 7215 7431 +40178 1207 1439 1521 7366 +40179 1048 1050 61 771 +40180 1428 656 1424 1201 +40181 1243 1443 1286 7318 +40182 707 664 763 1182 +40183 1067 1075 1069 7391 +40184 939 828 966 7362 +40185 1057 53 705 756 +40186 1086 838 103 1091 +40187 44 4 869 950 +40188 1323 1449 182 1079 +40189 7237 7391 7268 7450 +40190 998 1025 1002 7438 +40191 7328 7403 7300 7422 +40192 1380 1192 1319 7457 +40193 1083 99 100 7334 +40194 697 706 66 1046 +40195 705 698 54 1056 +40196 867 984 815 7313 +40197 157 1054 1329 1393 +40198 1480 1259 1308 7336 +40199 872 949 817 7279 +40200 737 1206 677 1300 +40201 144 1070 145 7350 +40202 674 661 705 1349 +40203 901 793 877 7379 +40204 1083 1085 1089 7261 +40205 1385 1358 1220 7449 +40206 173 1043 1041 1377 +40207 149 1378 1040 1042 +40208 711 49 678 1042 +40209 679 71 712 1043 +40210 779 7411 7334 7456 +40211 1285 682 1488 1344 +40212 1037 1294 146 1036 +40213 1034 1035 176 1293 +40214 1324 1286 1213 7406 +40215 1271 7291 7360 7446 +40216 1339 7376 1181 7400 +40217 1242 1382 1297 7458 +40218 1524 1225 1459 7384 +40219 791 919 849 7302 +40220 1077 839 127 1072 +40221 1480 1346 1259 7456 +40222 1424 693 1233 1332 +40223 1098 1128 1115 7405 +40224 783 7371 778 7456 +40225 995 7409 7279 7437 +40226 1279 1443 1243 7382 +40227 1414 1208 1301 7429 +40228 811 964 876 7452 +40229 1352 1514 1274 7320 +40230 1346 1421 783 7456 +40231 727 771 676 1379 +40232 1179 1464 1324 7406 +40233 658 704 1376 728 +40234 7344 7419 7250 7428 +40235 932 876 964 7452 +40236 1024 898 133 1008 +40237 855 940 986 7346 +40238 1056 1292 155 1057 +40239 1052 768 59 1051 +40240 771 728 676 1379 +40241 918 900 800 7419 +40242 1280 1519 1457 7321 +40243 794 987 881 7425 +40244 969 847 960 7301 +40245 1011 1002 7437 7438 +40246 209 1163 210 7441 +40247 1097 1119 1106 7381 +40248 162 1483 1048 1379 +40249 1426 1088 1321 7447 +40250 1009 999 1010 7296 +40251 1123 1093 1112 7316 +40252 1227 1331 1347 7414 +40253 798 860 905 7415 +40254 838 973 103 1091 +40255 1520 7323 1198 7439 +40256 1304 1384 1187 7349 +40257 1014 92 1032 7455 +40258 1119 1097 1107 7381 +40259 1157 203 1160 7432 +40260 689 1428 1299 1201 +40261 1346 1437 1259 7456 +40262 1204 1292 661 1349 +40263 7226 7430 7319 7451 +40264 1416 1254 1489 7363 +40265 862 799 844 7300 +40266 1114 1127 1094 7361 +40267 683 1063 732 1402 +40268 1049 1326 167 1456 +40269 1462 1269 1306 7365 +40270 930 876 1173 7452 +40271 682 1488 759 1285 +40272 648 644 646 7386 +40273 1147 1139 1382 7458 +40274 796 992 893 7330 +40275 1325 1309 1187 7369 +40276 1422 15 177 1176 +40277 134 939 861 1027 +40278 1366 165 1044 1460 +40279 1054 1407 158 1329 +40280 932 13 179 7417 +40281 805 904 846 7347 +40282 1096 7315 7405 7421 +40283 101 7 885 929 +40284 1081 1323 182 1079 +40285 855 7271 922 7383 +40286 1346 1503 1421 7371 +40287 787 875 95 929 +40288 1178 930 124 876 +40289 1460 165 1044 1045 +40290 1167 1175 1168 7353 +40291 1248 1306 1479 7325 +40292 1052 1407 159 1053 +40293 958 7344 879 7428 +40294 1094 1110 1120 7361 +40295 869 923 837 7404 +40296 1288 1213 1521 7366 +40297 879 927 843 7433 +40298 1198 1374 1264 7323 +40299 1497 1330 1454 7305 +40300 667 690 1469 736 +40301 889 7319 831 7401 +40302 891 833 808 7437 +40303 1124 196 1328 1113 +40304 12 884 930 7441 +40305 850 982 922 7383 +40306 993 795 894 7352 +40307 880 844 941 7403 +40308 1504 1353 1218 7377 +40309 741 746 687 1302 +40310 910 835 814 7374 +40311 994 1017 1031 7313 +40312 171 1284 1065 1435 +40313 1264 1222 1369 7332 +40314 1354 1288 1194 7343 +40315 1270 1481 7339 7457 +40316 804 848 900 7287 +40317 848 906 927 7433 +40318 660 683 1284 760 +40319 1154 206 1152 1322 +40320 891 799 955 7389 +40321 1302 1333 687 1206 +40322 1505 1489 1180 7380 +40323 1033 1006 141 897 +40324 83 1004 84 7444 +40325 1116 1142 1102 7332 +40326 1109 1131 1096 7421 +40327 1301 7429 7306 7449 +40328 1446 1306 1248 7325 +40329 876 967 811 7452 +40330 138 1029 954 863 +40331 1387 1063 169 1267 +40332 161 1376 1051 1483 +40333 1235 1333 746 1302 +40334 759 659 682 1285 +40335 7234 7339 7375 7457 +40336 1266 680 1498 1320 +40337 1293 1035 176 1399 +40338 1294 1400 146 1036 +40339 1112 957 114 865 +40340 1389 7429 1301 7449 +40341 7254 7364 7353 7452 +40342 663 713 680 1320 +40343 1016 1014 994 7393 +40344 911 992 796 7348 +40345 1057 154 1058 1349 +40346 160 1376 1300 1051 +40347 797 986 940 7346 +40348 649 1333 761 746 +40349 855 807 983 7383 +40350 163 1048 1316 1379 +40351 1148 888 113 957 +40352 1150 1495 1116 7395 +40353 1290 1371 1523 7434 +40354 985 808 872 7437 +40355 950 1017 867 7313 +40356 209 208 1153 7399 +40357 1413 1249 1319 7372 +40358 7374 7221 7387 7413 +40359 1312 1495 1150 7395 +40360 746 1333 687 1302 +40361 1001 1013 1012 7392 +40362 1256 1477 1293 7314 +40363 1198 1520 1374 7323 +40364 1178 876 1171 7452 +40365 1376 704 677 1300 +40366 864 970 978 7396 +40367 1260 1511 1431 7355 +40368 1227 1314 1317 7414 +40369 932 1171 876 7452 +40370 1468 7345 1231 7439 +40371 898 833 955 7438 +40372 1006 1023 140 897 +40373 939 966 861 7362 +40374 898 1024 132 7438 +40375 871 1066 976 7390 +40376 1503 7371 1346 7456 +40377 1426 99 1088 7447 +40378 911 858 992 7348 +40379 196 1113 1134 1270 +40380 913 813 844 7328 +40381 5 1069 76 7391 +40382 1049 168 1387 1062 +40383 177 1400 15 7436 +40384 1454 1314 1489 7380 +40385 926 871 839 7390 +40386 1173 876 1178 7452 +40387 939 134 1008 1027 +40388 1200 1390 1271 7291 +40389 1083 1084 1085 7378 +40390 887 1013 136 7392 +40391 890 807 982 7383 +40392 1267 732 1063 1402 +40393 821 882 937 7423 +40394 1054 57 684 757 +40395 758 63 685 1045 +40396 755 732 68 1062 +40397 1058 52 756 733 +40398 150 1061 1436 1042 +40399 1346 7371 1421 7456 +40400 7317 7430 7226 7451 +40401 1311 1337 1186 7329 +40402 1011 1002 995 7437 +40403 996 1022 1003 7385 +40404 897 1023 140 953 +40405 950 867 815 7313 +40406 917 969 788 7341 +40407 1293 1399 1256 7314 +40408 7345 7416 7221 7439 +40409 1491 1217 1325 7369 +40410 801 892 943 7426 +40411 937 882 797 7423 +40412 208 18 1427 1438 +40413 842 922 855 7271 +40414 949 145 14 871 +40415 99 9 1437 1426 +40416 7229 7410 7325 7421 +40417 730 1300 677 768 +40418 1319 7375 1209 7457 +40419 1277 1363 148 1040 +40420 1278 1041 174 1364 +40421 1029 138 1007 863 +40422 1050 704 60 728 +40423 177 15 1422 7436 +40424 930 884 819 7441 +40425 1071 1070 144 7350 +40426 1018 1020 80 7409 +40427 1135 1148 113 957 +40428 897 141 1033 831 +40429 959 887 136 7392 +40430 1513 198 1348 1114 +40431 1436 1378 150 1042 +40432 883 642 41 837 +40433 1156 1157 1158 7432 +40434 94 875 787 780 +40435 1178 125 1171 876 +40436 1394 1247 1339 7376 +40437 704 59 768 1051 +40438 1063 69 683 732 +40439 733 51 682 1059 +40440 1109 1096 1130 7421 +40441 792 910 889 7401 +40442 729 86 87 1518 +40443 1095 1116 1137 7332 +40444 1377 1041 173 1278 +40445 1378 1277 149 1040 +40446 1045 1460 164 1047 +40447 843 927 991 7433 +40448 1402 1284 760 1064 +40449 1218 1310 1470 7377 +40450 1514 1468 1274 7345 +40451 1173 1167 1177 7452 +40452 186 10 951 870 +40453 1339 1181 1490 7400 +40454 1122 1147 199 1307 +40455 154 1058 1349 1465 +40456 873 203 11 948 +40457 906 933 790 7340 +40458 806 7319 889 7430 +40459 658 687 1206 737 +40460 897 824 945 7335 +40461 1100 1125 1139 7458 +40462 159 1300 1407 1052 +40463 945 831 7335 7401 +40464 837 642 972 7404 +40465 1085 1084 1086 7378 +40466 902 800 958 7419 +40467 683 1402 760 1064 +40468 1468 1231 1360 7439 +40469 1009 1010 1001 7448 +40470 906 840 933 7340 +40471 860 843 991 7407 +40472 93 92 1014 7393 +40473 1139 1125 201 7458 +40474 1055 1393 156 1056 +40475 636 642 41 883 +40476 880 941 791 7402 +40477 1455 1119 191 1350 +40478 1270 1380 1481 7457 +40479 776 777 784 7411 +40480 807 855 982 7383 +40481 1184 1287 1494 7360 +40482 1416 1327 1214 7363 +40483 1217 1309 1325 7369 +40484 1280 1519 7321 7453 +40485 1226 1318 1315 7368 +40486 1047 1460 164 1316 +40487 35 644 648 7386 +40488 179 1067 178 7417 +40489 732 1063 68 1062 +40490 733 1058 52 1059 +40491 1008 999 1004 7362 +40492 839 127 886 1077 +40493 1167 1170 1177 7353 +40494 1156 202 1157 7432 +40495 961 889 851 7430 +40496 886 1077 1068 7417 +40497 1067 7391 178 7417 +40498 1115 1096 1131 7315 +40499 728 61 1050 771 +40500 151 1060 1488 1061 +40501 851 974 961 7430 +40502 1068 13 886 7417 +40503 884 836 936 7441 +40504 7319 7430 806 7451 +40505 987 794 934 7337 +40506 909 1011 7437 7438 +40507 1352 1188 1514 7320 +40508 647 972 642 7404 +40509 1004 83 1025 7444 +40510 1287 1404 1521 7394 +40511 1348 1414 1245 7356 +40512 1072 1076 1077 7390 +40513 1221 1455 1350 7381 +40514 905 827 887 7392 +40515 94 875 780 931 +40516 125 932 1171 876 +40517 1061 1488 151 1436 +40518 99 779 100 7334 +40519 901 823 944 7379 +40520 1439 1515 1288 7343 +40521 1116 1095 1106 7395 +40522 1267 683 732 1402 +40523 1069 1074 77 7450 +40524 909 132 1011 7438 +40525 777 779 775 7411 +40526 1394 1207 1404 7394 +40527 135 861 959 1010 +40528 1151 191 1119 1350 +40529 1394 1249 1413 7372 +40530 761 1333 687 746 +40531 798 849 915 7322 +40532 1118 896 109 952 +40533 1307 1242 1496 7458 +40534 887 959 826 7392 +40535 1361 1289 1226 7408 +40536 910 814 928 7374 +40537 929 95 787 782 +40538 124 1173 930 1178 +40539 842 986 882 7370 +40540 51 682 1060 759 +40541 760 69 683 1064 +40542 1457 1205 1269 7365 +40543 7 101 885 1087 +40544 929 787 875 782 +40545 1173 930 1178 876 +40546 976 1072 839 7390 +40547 1457 1209 1280 7375 +40548 1319 1343 1209 7375 +40549 1326 168 1387 1049 +40550 153 1058 1465 1059 +40551 1523 1371 1195 7434 +40552 982 855 922 7383 +40553 886 938 839 7417 +40554 1147 1100 1139 7458 +40555 109 1108 896 1118 +40556 757 1054 56 1055 +40557 758 1044 64 1045 +40558 944 896 832 7358 +40559 883 3 38 931 +40560 1431 1323 1081 7355 +40561 1013 887 137 954 +40562 879 848 927 7433 +40563 1001 1010 136 7392 +40564 837 935 883 7290 +40565 1509 1294 146 1037 +40566 1508 1034 176 1293 +40567 975 860 803 7407 +40568 1003 89 88 7435 +40569 730 57 684 1053 +40570 1194 1288 1515 7343 +40571 1073 1072 1066 7390 +40572 1480 1308 1417 7336 +40573 907 831 806 7319 +40574 932 886 13 7417 +40575 1170 1172 208 7399 +40576 898 132 833 7438 +40577 965 820 912 7427 +40578 1350 1446 1248 7410 +40579 1482 683 1267 1402 +40580 831 889 806 7319 +40581 1495 188 1116 1369 +40582 1181 1339 1358 7376 +40583 882 989 842 7370 +40584 1117 1137 1103 7333 +40585 836 122 1164 884 +40586 1028 997 1003 7435 +40587 1514 1313 1231 7345 +40588 905 7392 826 7445 +40589 1343 1280 1209 7375 +40590 1404 1207 1521 7394 +40591 1490 1253 1339 7400 +40592 909 1011 1021 7437 +40593 683 1402 1284 760 +40594 199 1122 1307 1348 +40595 1020 1018 995 7409 +40596 995 1021 1011 7437 +40597 135 861 1010 1027 +40598 1027 999 1008 7362 +40599 1163 1164 1165 7441 +40600 93 1014 1016 7393 +40601 10 186 1092 870 +40602 178 1069 5 7391 +40603 1147 1382 200 1307 +40604 1437 1426 1259 7447 +40605 8 96 785 1421 +40606 106 868 1143 1140 +40607 177 1176 1169 7436 +40608 894 961 853 7451 +40609 990 881 841 7425 +40610 1220 1304 1356 7412 +40611 1128 1096 1115 7405 +40612 1167 1168 1170 7353 +40613 1393 1292 156 1056 +40614 1192 1380 1414 7429 +40615 809 834 892 7331 +40616 1184 7360 1472 7453 +40617 1177 1170 209 7399 +40618 1167 1171 1175 7452 +40619 1269 1205 1306 7365 +40620 1065 1043 172 1435 +40621 917 847 969 7341 +40622 1083 1088 99 7447 +40623 56 757 1055 726 +40624 1044 64 725 758 +40625 1369 188 1116 1142 +40626 819 884 936 7441 +40627 1431 1081 184 7355 +40628 1119 190 1150 1455 +40629 1047 63 685 727 +40630 1344 1060 152 1059 +40631 637 647 645 7404 +40632 186 1140 1126 7440 +40633 15 1400 1422 7436 +40634 873 11 203 1160 +40635 1 93 1016 7454 +40636 1489 1327 1416 7363 +40637 1382 1139 201 7458 +40638 1231 1468 1514 7345 +40639 58 730 1052 1053 +40640 1057 1292 155 1349 +40641 1402 1482 683 1284 +40642 1481 1209 1328 7339 +40643 909 808 833 7437 +40644 1048 62 1047 727 +40645 871 145 14 1066 +40646 1348 1208 1414 7356 +40647 1464 1286 1324 7406 +40648 909 833 132 7438 +40649 1346 783 98 781 +40650 1314 1180 1489 7380 +40651 822 886 932 7417 +40652 198 1122 1348 1114 +40653 1011 132 1024 7438 +40654 1001 136 1013 7392 +40655 1345 1172 211 1174 +40656 1488 1060 152 1344 +40657 914 834 809 7331 +40658 1184 1472 1375 7453 +40659 211 1438 1172 1345 +40660 1165 1164 122 884 +40661 781 98 1346 1437 +40662 1347 1314 1227 7414 +40663 881 987 841 7425 +40664 891 955 833 7389 +40665 1367 1264 1312 7395 +40666 1107 1096 1121 7421 +40667 1346 781 1437 7456 +40668 175 1039 1034 1508 +40669 839 976 127 1072 +40670 1439 1288 1521 7366 +40671 976 1066 1072 7390 +40672 126 1068 886 1077 +40673 1315 1318 1211 7368 +40674 34 35 74 1039 +40675 814 877 920 7413 +40676 1346 783 781 7456 +40677 934 856 987 7337 +40678 1396 1273 1188 7442 +40679 837 972 869 7404 +40680 1000 1015 1014 7455 +40681 1096 1128 1111 7405 +40682 897 945 831 7335 +40683 1192 1301 1389 7429 +40684 1247 1358 1339 7376 +40685 1431 1511 1323 7355 +40686 909 7437 833 7438 +40687 1271 7360 1494 7446 +40688 903 805 846 7397 +40689 938 886 822 7417 +40690 1019 872 130 1021 +40691 872 909 1021 7437 +40692 1328 1270 1481 7339 +40693 1017 1015 143 867 +40694 1081 1079 1080 7355 +40695 976 839 871 7390 +40696 871 14 129 1066 +40697 1382 201 17 1297 +40698 96 8 1399 1421 +40699 1360 1520 1198 7439 +40700 1385 1356 1240 7412 +40701 1520 1337 1374 7418 +40702 639 33 1 7454 +40703 1068 1077 1067 7417 +40704 844 878 941 7403 +40705 62 1048 771 727 +40706 46 77 78 1038 +40707 759 1060 50 1061 +40708 760 1065 70 1064 +40709 949 872 130 1019 +40710 836 1164 122 977 +40711 961 806 889 7430 +40712 1161 17 201 1297 +40713 78 1074 1078 7450 +40714 1069 178 1067 7391 +40715 1426 99 9 1088 +40716 945 889 831 7401 +40717 186 1126 185 7440 +40718 1039 35 74 1034 +40719 868 106 951 1140 +40720 1371 1477 1195 7434 +40721 1426 1321 1506 7447 +40722 1435 1043 172 1377 +40723 642 646 647 7404 +40724 1392 1200 1443 7382 +40725 804 978 970 7396 +40726 1225 1368 1459 7384 +40727 1465 1344 153 1059 +40728 206 205 1162 1357 +40729 208 209 1170 7399 +40730 1184 1343 1493 7453 +40731 1431 184 16 1440 +40732 893 808 985 7459 +40733 918 800 902 7419 +40734 1303 1396 1188 7442 +40735 58 730 768 1052 +40736 1149 198 1513 1114 +40737 1154 208 18 1427 +40738 1307 1382 1242 7458 +40739 928 974 851 7367 +40740 866 860 991 7407 +40741 793 920 877 7413 +40742 77 46 1037 1038 +40743 1312 1150 190 1455 +40744 905 826 899 7445 +40745 1174 212 1422 1176 +40746 1104 942 1123 1146 +40747 212 1345 1174 1422 +40748 181 1089 1321 1088 +40749 795 912 935 7427 +40750 903 801 943 7426 +40751 117 1146 895 1110 +40752 1310 1353 1442 7377 +40753 907 1033 141 831 +40754 945 792 889 7401 +40755 200 1139 1382 1147 +40756 1131 956 112 1115 +40757 97 1421 783 1346 +40758 1421 785 97 783 +40759 1037 147 1509 1038 +40760 1002 1011 998 7438 +40761 958 919 854 7428 +40762 1116 1106 1150 7395 +40763 1481 1319 1209 7457 +40764 1402 1063 170 1064 +40765 1322 1154 207 1427 +40766 775 779 781 7456 +40767 645 647 646 7404 +40768 1421 1503 1256 7371 +40769 1164 1159 121 977 +40770 115 1123 865 942 +40771 1039 175 1364 1508 +40772 1312 1264 1495 7395 +40773 636 3 38 883 +40774 1089 1449 181 1321 +40775 1220 1389 1301 7449 +40776 103 102 885 1087 +40777 1361 1226 1305 7408 +40778 1494 1271 1184 7360 +40779 1079 1449 182 1089 +40780 1 43 639 7454 +40781 1095 1137 1117 7333 +40782 647 638 39 972 +40783 1143 908 107 1117 +40784 1016 43 1 7454 +40785 1323 183 1431 1081 +40786 903 963 805 7397 +40787 104 103 973 1091 +40788 1123 1112 114 865 +40789 1094 1127 1110 7361 +40790 40 642 647 972 +40791 137 1029 1013 954 +40792 942 116 115 1146 +40793 886 127 126 1077 +40794 1267 1063 169 1402 +40795 1144 119 1138 874 +40796 932 179 13 1171 +40797 869 39 638 972 +40798 1328 1463 195 1124 +40799 120 11 873 1160 +40800 1220 1358 1389 7449 +40801 977 1159 121 1160 +40802 960 808 893 7459 +40803 85 1009 86 7448 +40804 1468 1360 1198 7439 +40805 636 42 3 883 +40806 1150 189 1116 1495 +40807 1463 1105 1145 1124 +40808 759 50 711 1061 +40809 70 712 1065 760 +40810 776 779 777 7411 +40811 1122 199 198 1348 +40812 998 1011 1024 7438 +40813 1169 5 177 7436 +40814 1472 1184 1271 7360 +40815 956 111 864 1131 +40816 195 196 1328 1124 +40817 1485 1222 1337 7418 +40818 837 642 41 972 +40819 1462 193 1145 1111 +40820 1284 1402 171 1064 +40821 203 1157 202 7432 +40822 950 1017 143 867 +40823 101 7 929 782 +40824 1173 210 12 930 +40825 114 1135 957 1112 +40826 1142 1512 187 1141 +40827 108 109 1108 896 +40828 776 786 779 7411 +40829 1163 1165 210 7441 +40830 208 18 1438 1172 +40831 1092 105 10 870 +40832 912 820 935 7427 +40833 806 7430 961 7451 +40834 99 9 781 1437 +40835 1321 180 181 1088 +40836 115 1123 942 1146 +40837 77 1074 78 7450 +40838 1353 1310 1218 7377 +40839 1015 142 143 867 +40840 1144 1120 118 914 +40841 1107 1130 1096 7421 +40842 1220 1356 1385 7412 +40843 1423 196 1134 1270 +40844 1321 1426 180 1088 +40845 1141 1512 187 1440 +40846 1146 942 116 895 +40847 868 107 106 1143 +40848 122 123 1165 884 +40849 1032 1000 1014 7455 +40850 808 909 872 7437 +40851 1090 186 185 7440 +40852 1073 1076 1072 7390 +40853 1345 211 212 1174 +40854 901 944 793 7379 +40855 783 98 97 1346 +40856 1054 158 157 1329 +40857 948 1138 119 874 +40858 1363 1509 147 1038 +40859 1161 1162 205 1357 +40860 204 1161 1357 1297 +40861 108 107 908 1117 +40862 1167 1178 1171 7452 +40863 1280 1375 1519 7453 +40864 1277 148 149 1040 +40865 1041 174 173 1278 +40866 197 196 1134 1423 +40867 1145 195 194 1463 +40868 1120 117 118 914 +40869 1021 909 131 1011 +40870 142 1015 907 867 +40871 177 15 1400 1036 +40872 1048 163 162 1379 +40873 47 46 78 1038 +40874 34 74 73 1039 +40875 1145 195 1463 1124 +40876 207 206 1154 1322 +40877 1446 1151 192 1121 +40878 66 65 697 1046 +40879 698 55 54 1056 +40880 49 48 678 1042 +40881 679 72 71 1043 +40882 1369 1512 187 1142 +40883 155 154 1057 1349 +40884 182 183 1323 1081 +40885 1431 16 184 1081 +40886 1280 1343 1184 7453 +40887 160 161 1376 1051 +40888 1144 118 119 874 +40889 4 39 638 869 +40890 1248 1522 1350 7410 +40891 864 111 110 1109 +40892 798 905 899 7445 +40893 189 1150 1312 1495 +40894 4 44 1017 950 +40895 1044 166 165 1366 +40896 1504 1422 1257 7436 +40897 718 48 47 1040 +40898 717 73 72 1041 +40899 50 49 711 1061 +40900 712 71 70 1065 +40901 1164 121 122 977 +40902 812 958 879 7428 +40903 1259 1426 1506 7447 +40904 1350 1151 192 1446 +40905 159 160 1300 1052 +40906 1280 1184 1375 7453 +40907 1109 864 111 1131 +40908 1047 164 163 1316 +40909 107 868 908 1143 +40910 939 134 133 1008 +40911 885 102 7 1087 +40912 1001 1012 86 7448 +40913 928 789 974 7367 +40914 1279 1392 1443 7382 +40915 874 1144 118 914 +40916 170 169 1063 1402 +40917 1015 1033 142 907 +40918 86 1009 1001 7448 +40919 1147 200 199 1307 +40920 1068 1067 179 7417 +40921 1080 184 1081 7355 +40922 1326 167 168 1049 +40923 826 905 887 7392 +40924 1337 1222 1374 7418 +40925 887 137 136 1013 +40926 1028 1003 88 7435 +40927 1161 204 17 1297 +40928 41 42 636 883 +40929 1400 1257 1422 7436 +40930 1165 123 12 884 +40931 1154 18 207 1427 +40932 872 131 130 1021 +40933 1007 138 139 863 +40934 780 38 3 931 +40935 875 95 94 787 +40936 1178 124 125 876 +40937 205 204 1161 1357 +40938 1292 155 156 1056 +40939 866 803 860 7407 +40940 1006 140 141 897 +40941 40 41 642 972 +40942 775 781 783 7456 +40943 1167 1173 1178 7452 +40944 1380 1319 1481 7457 +40945 949 14 145 1019 +40946 888 113 112 1148 +40947 1402 170 171 1064 +40948 1438 18 211 1172 +40949 12 124 1173 930 +40950 929 7 95 782 +40951 9 180 1426 1088 +40952 62 63 1047 727 +40953 781 9 98 1437 +40954 873 977 120 1160 +40955 976 128 127 1072 +40956 181 182 1449 1089 +40957 1055 55 56 726 +40958 65 64 725 1044 +40959 806 894 984 7451 +40960 894 806 961 7451 +40961 1068 13 126 886 +40962 52 51 733 1059 +40963 68 69 1063 732 +40964 1139 201 17 1382 +40965 175 174 1039 1364 +40966 1141 16 184 1440 +40967 60 59 704 1051 +40968 730 58 57 1053 +40969 1138 11 203 948 +40970 1119 191 190 1455 +40971 1431 183 16 1081 +40972 1446 192 193 1121 +40973 647 39 40 972 +40974 13 125 932 1171 +40975 1035 96 8 1399 +40976 861 135 134 1027 +40977 1138 119 11 948 +40978 951 10 186 1140 +40979 1463 194 1145 1462 +40980 1146 116 117 895 +40981 1301 1192 1414 7429 +40982 1423 1134 197 1149 +40983 75 74 35 1034 +40984 1271 1494 1461 7446 +40985 1494 1213 1461 7446 +40986 1151 192 191 1350 +40987 958 812 919 7428 +40988 755 68 67 1062 +40989 52 53 1058 756 +40990 872 909 131 1021 +40991 1400 15 146 1036 +40992 870 1092 105 973 +40993 871 129 976 1066 +40994 1046 167 166 1456 +40995 1072 976 128 1066 +40996 1048 61 62 771 +40997 1123 114 115 865 +40998 1023 139 140 953 +40999 951 106 10 1140 +41000 77 46 45 1037 +41001 1050 60 61 728 +41002 758 64 63 1045 +41003 56 57 1054 757 +41004 147 148 1363 1038 +41005 1033 141 142 907 +41006 152 153 1344 1059 +41007 1058 154 153 1465 +41008 136 135 959 1010 +41009 780 3 94 931 +41010 909 132 131 1011 +41011 194 193 1145 1462 +41012 130 14 949 1019 +41013 67 66 706 1049 +41014 705 54 53 1057 +41015 162 161 1050 1483 +41016 149 150 1378 1042 +41017 1118 109 110 952 +41018 212 15 1422 1176 +41019 176 175 1034 1508 +41020 1092 104 973 1091 +41021 1116 189 188 1495 +41022 1513 1423 197 1149 +41023 59 58 768 1052 +41024 1387 168 169 1062 +41025 137 138 1029 954 +41026 1043 173 172 1377 +41027 898 133 132 1024 +41028 1017 143 4 950 +41029 121 120 977 1160 +41030 104 105 1092 973 +41031 1141 187 16 1440 +41032 1065 172 171 1435 +41033 151 150 1061 1436 +41034 1135 113 114 957 +41035 1060 50 51 759 +41036 70 69 760 1064 +41037 1509 146 147 1037 +41038 1513 197 198 1149 +41039 1407 158 159 1053 +41040 8 176 1035 1399 +41041 187 188 1369 1142 +41042 1393 156 157 1055 +41043 129 128 976 1066 +41044 112 111 956 1131 +41045 164 165 1460 1045 +41046 785 97 8 1421 +41047 17 200 1139 1382 +41048 1150 190 189 1312 +41049 1060 152 151 1488 +41050 7362 802 862 966 +41051 7402 7235 802 7300 +41052 7402 802 7235 7297 +41053 7248 787 782 875 +41054 7248 782 787 776 +41055 7416 1367 7381 7239 +41056 7416 7381 1367 1274 +41057 7446 7318 7236 7406 +41058 7446 7236 7318 7291 +41059 7281 7416 7379 7253 +41060 7379 7416 7281 7239 +41061 92 7414 7293 1317 +41062 7293 7414 92 7393 +41063 7317 7288 7260 7226 +41064 7317 7260 7288 7219 +41065 7432 7255 7215 7273 +41066 7432 7215 7255 7278 +41067 7362 7300 802 7235 +41068 7362 802 7300 862 +41069 7263 1136 7331 7240 +41070 7263 7331 1136 1101 +41071 7341 7338 7256 7220 +41072 7341 7256 7338 7301 +41073 7276 7256 7338 7220 +41074 7276 7338 7256 7301 +41075 810 7427 989 7243 +41076 810 989 7427 912 +41077 857 989 7427 7243 +41078 857 7427 989 912 +41079 7257 950 869 815 +41080 7257 869 950 44 +41081 7390 7330 796 926 +41082 7390 796 7330 7237 +41083 7350 7409 7222 7279 +41084 7222 7409 7350 7324 +41085 971 7385 7373 824 +41086 7373 7385 971 7298 +41087 817 7350 145 871 +41088 145 7350 817 7279 +41089 7258 1508 35 34 +41090 7258 35 1508 1293 +41091 77 1036 45 76 +41092 45 1036 77 1037 +41093 7419 830 7316 902 +41094 7419 7316 830 7312 +41095 7411 782 7248 776 +41096 7411 7248 782 7252 +41097 1509 7450 1224 1294 +41098 1224 7450 1509 78 +41099 644 7404 639 645 +41100 639 7404 644 7386 +41101 7337 818 988 7263 +41102 7337 988 818 934 +41103 7400 7277 7368 7249 +41104 7400 7368 7277 7326 +41105 7361 1136 7356 7240 +41106 7361 7356 1136 1094 +41107 1122 7356 1136 7240 +41108 1122 1136 7356 1094 +41109 7419 7264 7316 7312 +41110 7419 7316 7264 7250 +41111 7336 1216 7447 1308 +41112 7336 7447 1216 7261 +41113 7451 923 7257 7352 +41114 7451 7257 923 815 +41115 7377 7436 1504 1353 +41116 1504 7436 7377 7267 +41117 1099 7339 1134 1113 +41118 1134 7339 1099 7286 +41119 7282 979 921 845 +41120 7282 921 979 7251 +41121 7358 1095 7395 1129 +41122 7358 7395 1095 7333 +41123 7367 7430 7374 7238 +41124 7367 7374 7430 851 +41125 910 7374 7430 7238 +41126 910 7430 7374 851 +41127 7453 7270 7231 7283 +41128 7453 7231 7270 7360 +41129 7427 931 965 820 +41130 7427 965 931 7248 +41131 7380 1524 1347 1180 +41132 7380 1347 1524 7288 +41133 7457 7283 1319 7375 +41134 7457 1319 7283 7372 +41135 1343 1319 7283 7375 +41136 1343 7283 1319 7372 +41137 7378 1082 7261 7262 +41138 7378 7261 1082 1085 +41139 7304 1372 1289 7269 +41140 7304 1289 1372 1196 +41141 7337 936 925 7273 +41142 7337 925 936 794 +41143 7361 1136 1120 1094 +41144 7361 1120 1136 7331 +41145 7297 981 7362 7296 +41146 7297 7362 981 802 +41147 7369 7424 7255 7310 +41148 7255 7424 7369 7215 +41149 7380 1505 1524 1180 +41150 7380 1524 1505 7303 +41151 1098 7264 7316 1132 +41152 1098 7316 7264 7312 +41153 1493 7360 1287 1184 +41154 1287 7360 1493 7270 +41155 7408 7269 7222 7304 +41156 7408 7222 7269 7324 +41157 7293 1189 1317 1418 +41158 7293 1317 1189 93 +41159 1246 7384 1298 1459 +41160 1298 7384 1246 7308 +41161 7422 7272 7328 7403 +41162 7422 7328 7272 7244 +41163 7293 7414 7434 1523 +41164 1331 7414 7434 7260 +41165 1331 7434 7414 1523 +41166 753 1458 1332 1244 +41167 753 1332 1458 707 +41168 7449 1247 7244 7376 +41169 7449 7244 1247 1389 +41170 7337 7432 925 7263 +41171 925 7432 7337 7273 +41172 7455 91 92 1032 +41173 7455 92 91 7247 +41174 7365 1519 1457 1205 +41175 7365 1457 1519 7321 +41176 89 1265 1406 1444 +41177 1406 1265 89 88 +41178 7336 1311 1186 7329 +41179 7336 1186 1311 1308 +41180 7454 7404 637 639 +41181 7454 637 7404 7257 +41182 7459 7389 7277 7301 +41183 7459 7277 7389 7437 +41184 7316 1104 942 1123 +41185 7316 942 1104 7266 +41186 725 1255 1456 1366 +41187 1456 1255 725 697 +41188 1456 1044 725 1366 +41189 725 1044 1456 697 +41190 7458 202 7432 1125 +41191 7458 7432 202 7278 +41192 7250 7397 902 7316 +41193 7250 902 7397 805 +41194 980 902 7397 7316 +41195 980 7397 902 805 +41196 7284 7453 1230 7360 +41197 7284 1230 7453 1375 +41198 1472 1230 7453 7360 +41199 1472 7453 1230 1375 +41200 1332 753 1445 670 +41201 1332 1445 753 1244 +41202 1265 709 89 88 +41203 1265 89 709 1445 +41204 753 1476 1458 1244 +41205 753 1458 1476 90 +41206 962 7373 7327 859 +41207 7327 7373 962 7294 +41208 7447 1216 1321 1506 +41209 7447 1321 1216 7261 +41210 1452 649 688 1383 +41211 1452 688 649 699 +41212 85 1354 1324 1250 +41213 1324 1354 85 7309 +41214 7436 1168 7391 7267 +41215 7436 7391 1168 5 +41216 1377 774 747 1229 +41217 1377 747 774 679 +41218 1378 773 748 678 +41219 1378 748 773 1228 +41220 915 7428 849 812 +41221 849 7428 915 7322 +41222 802 7445 849 899 +41223 849 7445 802 7297 +41224 7371 1355 1219 1503 +41225 7371 1219 1355 7351 +41226 7358 908 108 832 +41227 7358 108 908 1117 +41228 7406 1012 86 87 +41229 7406 86 1012 7448 +41230 1332 749 693 670 +41231 1332 693 749 1424 +41232 1044 697 65 1046 +41233 1044 65 697 725 +41234 1056 726 1393 698 +41235 1056 1393 726 1055 +41236 1357 1152 206 1322 +41237 1357 206 1152 1162 +41238 1491 7458 7369 1242 +41239 7369 7458 1491 7278 +41240 1483 728 704 1050 +41241 704 728 1483 1376 +41242 704 1051 1483 1050 +41243 1483 1051 704 1376 +41244 7402 802 849 880 +41245 7402 849 802 7297 +41246 1109 952 110 864 +41247 1109 110 952 1118 +41248 85 7406 7448 86 +41249 7448 7406 85 7309 +41250 7390 1070 1078 7350 +41251 7390 1078 1070 1073 +41252 7446 1286 1213 1461 +41253 7446 1213 1286 7406 +41254 7260 7384 1331 7288 +41255 1347 1331 7384 7288 +41256 1347 7384 1331 1225 +41257 7359 7427 38 7248 +41258 38 7427 7359 7290 +41259 773 1410 1285 1228 +41260 1285 1410 773 659 +41261 1285 1436 773 1228 +41262 1028 7318 88 87 +41263 88 7318 1028 7435 +41264 1232 726 757 665 +41265 757 726 1232 1393 +41266 757 1329 1232 665 +41267 1232 1329 757 1393 +41268 7322 843 7428 915 +41269 7322 7428 843 7295 +41270 706 1517 1215 1326 +41271 1215 1517 706 662 +41272 1120 834 117 914 +41273 117 834 1120 1110 +41274 721 1204 1498 769 +41275 1498 1204 721 1471 +41276 7459 891 960 808 +41277 7459 960 891 7301 +41278 7433 790 906 927 +41279 7433 906 790 7340 +41280 1395 698 661 1292 +41281 1395 661 698 702 +41282 7439 1246 1298 1360 +41283 7439 1298 1246 7308 +41284 7446 1287 7360 1494 +41285 7446 7360 1287 7270 +41286 1007 953 139 1023 +41287 139 953 1007 863 +41288 1250 86 1342 1441 +41289 1250 1342 86 85 +41290 690 1342 86 1441 +41291 690 86 1342 85 +41292 811 7425 967 881 +41293 967 7425 811 7364 +41294 867 7451 7319 806 +41295 7319 7451 867 7313 +41296 7410 1221 1350 7381 +41297 7410 1350 1221 1522 +41298 7456 99 779 781 +41299 7456 779 99 7334 +41300 7434 1355 1429 7351 +41301 7434 1429 1355 1195 +41302 1300 737 767 677 +41303 1300 767 737 1405 +41304 756 1057 1349 705 +41305 756 1349 1057 1058 +41306 706 1062 67 1049 +41307 67 1062 706 755 +41308 7449 1385 7338 7412 +41309 7449 7338 1385 1358 +41310 7441 12 1165 210 +41311 7441 1165 12 884 +41312 1148 957 7312 888 +41313 7312 957 1148 1135 +41314 7314 35 1035 36 +41315 7314 1035 35 1034 +41316 75 1035 35 36 +41317 75 35 1035 1034 +41318 7388 7414 7434 7293 +41319 7434 7414 7388 7260 +41320 7384 1331 1429 7260 +41321 7384 1429 1331 1225 +41322 773 1285 711 1436 +41323 711 1285 773 659 +$EndElements diff --git a/examples/python3/tutorial/formation/chiba/fingerController.py b/examples/python3/tutorial/formation/chiba/fingerController.py new file mode 100644 index 00000000..f6a755a1 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/fingerController.py @@ -0,0 +1,28 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +import Sofa.Core +import Sofa.constants.Key as Key + + +class FingerController(Sofa.Core.Controller): + + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, args, kwargs) + self.node = args[0] + self.fingerNode = self.node.getChild('finger') + self.pressureConstraint = self.fingerNode.cavity.getObject('SurfacePressureConstraint') + + def onKeypressedEvent(self, e): + pressureValue = self.pressureConstraint.value.value[0] + + if e["key"] == Key.plus: + pressureValue += 0.01 + if pressureValue > 3: + pressureValue = 3 + + if e["key"] == Key.minus: + pressureValue -= 0.01 + if pressureValue < 0: + pressureValue = 0 + + self.pressureConstraint.value = [pressureValue] diff --git a/examples/python3/tutorial/formation/chiba/loopstest_function_param3.py b/examples/python3/tutorial/formation/chiba/loopstest_function_param3.py new file mode 100644 index 00000000..446737ec --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/loopstest_function_param3.py @@ -0,0 +1,125 @@ +import math + + +def looptest(int, loopnum): + vertex_loop = [] + loops = [] + spring_set = [] + spring = [] + Ks = 10e12 + Kd = 0 + indices1 = [] + indices2 = [] + lengths = [] + + for loop_id in range(0, loopnum): + for v_id in range(0, 45): + if v_id == 0: + vertex_loop.append( + [int * loop_id + 1, 7.5 * math.cos(v_id / 25 * math.pi), 7.5 * math.sin(v_id / 25 * math.pi)]) + if 0 < v_id < 25: + vertex_loop.append( + [int * loop_id + 1, 7.5 * math.cos(v_id / 25 * math.pi), 7.5 * math.sin(v_id / 25 * math.pi)]) + L = (math.dist(vertex_loop[v_id], vertex_loop[v_id - 1])) + spring.append([v_id - 1, v_id, Ks, Kd, L]) + indices1.append(v_id - 1) + indices2.append(v_id) + lengths.append(L) + elif 25 <= v_id < 28: + vertex_loop.append([int * (loop_id) + 1, 7.5 * math.cos(math.pi), 7.5 * math.sin(math.pi) - v_id + 25]) + L = (math.dist(vertex_loop[v_id], vertex_loop[v_id - 1])) + spring.append([v_id - 1, v_id, Ks, Kd, L]) + indices1.append(v_id - 1) + indices2.append(v_id) + lengths.append(L) + elif v_id >= 28 and v_id < 42: + vertex_loop.append([int * (loop_id) + 1, 7.5 * math.cos(math.pi) + 1 + v_id - 28, -4]) + L = (math.dist(vertex_loop[v_id], vertex_loop[v_id - 1])) + spring.append([v_id - 1, v_id, Ks, Kd, L]) + indices1.append(v_id - 1) + indices2.append(v_id) + lengths.append(L) + elif v_id >= 42: + vertex_loop.append([int * (loop_id) + 1, -7.5 + 15, -2]) + L = (math.dist(vertex_loop[v_id], vertex_loop[v_id - 1])) + spring.append([v_id - 1, v_id, Ks, Kd, L]) + indices1.append(v_id - 1) + indices2.append(v_id) + lengths.append(L) + if v_id == 43: + L = (math.dist(vertex_loop[v_id], vertex_loop[0])) + spring.append([v_id, 0, Ks, Kd, L]) + indices1.append(v_id - 1) + indices2.append(0) + lengths.append(L) + spring_set.append(spring) + loops.append(vertex_loop) + vertex_loop = [] + spring = [] + return loops, spring_set, indices1, indices2, lengths + + # fiber.addObject('MeshTopology', src='@loader', name='container') + # fiber.addObject('MechanicalObject', name='lines', template='Vec3', showObject=True, showObjectScale=1) + + +# def generate_loop_data(loop_num, loop_spacing): +# loops = [] +# spring_set = [] +# indices1 = [] +# indices2 = [] +# lengths = [] +# Ks = 10e12 +# Kd = 0 +# +# def generate_vertex(loop_id, v_id): +# if v_id == 0: +# return [loop_id * loop_spacing + 1, 7.5 * math.cos(v_id / 25 * math.pi), 7.5 * math.sin(v_id / 25 * math.pi)] +# elif 0 < v_id < 25: +# L = math.dist(loops[loop_id][v_id], loops[loop_id][v_id - 1]) +# spring_set[loop_id].append([v_id - 1, v_id, Ks, Kd, L]) +# indices1.append(v_id - 1) +# indices2.append(v_id) +# lengths.append(L) +# return [loop_id * loop_spacing + 1, 7.5 * math.cos(v_id / 25 * math.pi), 7.5 * math.sin(v_id / 25 * math.pi)] +# elif 25 <= v_id < 28: +# L = math.dist(loops[loop_id][v_id], loops[loop_id][v_id - 1]) +# spring_set[loop_id].append([v_id - 1, v_id, Ks, Kd, L]) +# indices1.append(v_id - 1) +# indices2.append(v_id) +# lengths.append(L) +# return [loop_id * loop_spacing + 1, 7.5 * math.cos(math.pi), 7.5 * math.sin(math.pi) - v_id + 25] +# elif 28 <= v_id < 42: +# L = math.dist(loops[loop_id][v_id], loops[loop_id][v_id - 1]) +# spring_set[loop_id].append([v_id - 1, v_id, Ks, Kd, L]) +# indices1.append(v_id - 1) +# indices2.append(v_id) +# lengths.append(L) +# return [loop_id * loop_spacing + 1, 7.5 * math.cos(math.pi) + 1 + v_id - 28, -4] +# else: +# L = math.dist(loops[loop_id][v_id], loops[loop_id][v_id - 1]) +# spring_set[loop_id].append([v_id - 1, v_id, Ks, Kd, L]) +# indices1.append(v_id - 1) +# indices2.append(v_id) +# lengths.append(L) +# return [loop_id * loop_spacing + 1, -7.5 + 15, -2] +# +# for loop_id in range(loop_num): +# vertex_loop = [generate_vertex(loop_id, v_id) for v_id in range(45)] +# L = math.dist(vertex_loop[43], vertex_loop[0]) +# spring_set[loop_id].append([43, 0, Ks, Kd, L]) +# indices1.append(43) +# indices2.append(0) +# lengths.append(L) +# loops.append(vertex_loop) +# +# return loops, spring_set, indices1, indices2, lengths +# +# loop_num = 5 +# loop_spacing = 10 +# loops_data, spring_data, indices1, indices2, lengths = generate_loop_data(loop_num, loop_spacing) +# +# print(loops_data) +# print(spring_data) +# print(indices1) +# print(indices2) +# print(lengths) diff --git a/examples/python3/tutorial/formation/chiba/problemmappingtransversalfiber.png b/examples/python3/tutorial/formation/chiba/problemmappingtransversalfiber.png new file mode 100644 index 0000000000000000000000000000000000000000..ee21cc35b691f7ef4f88131722df8ff6f2e21585 GIT binary patch literal 461877 zcma&NRajhI6eS2Dfdmcikl^kP1;O3j-Q7vy!QCNP;qLD48YrA#L8~A@fWmF~yT5OG zdU_t_;mW@EJe_T8ud{cQijp)MG7&Ny92}agjD#8-9KzfCJB^R;-o6M_NJ+ju;N8`v z#o%gZNuY1SduvfeQ8>7U1e7P!4{!1(7a3i5I5_m7|1S73=W+`;xYrU{2~iCnqrW{! z26$sP!U2%n45RnNn#H#ig=XhH-f`Tm1SvLL%d2q>w_CpFJweE3@Tn{};S_~*xkrIF zq?bmuhcqAeuloAVuU!qTtgUBr_&MDV*Vg>KD}?62V2<)HHg<N%nR0S+6e?C4sajG} zQpd-~BVtqVs+5k7r)C`oAq52m;o;$l23B;j2C91O!VQ|=*OOXy?HUy_6=*^;2ywwb z-U$c@9IQkPXsWBLGvYCb>aMTqnW;Z9zZ6wV*vS=FN=z~oSBgzm7FX96mntxcra4wu z6<L;-ITu@(JAdKi;so=~v2!hFOu$err8oeTnY~f9paM`q63cI}%J%Bd6sRo}IvE=m zi)u-O82+G#NW;Oo9KF}l!X?omXIH5<KPhK-Od+NzDQgHRDxS`Afii$U#qSWz&#3_^ zczCMHC4hSC4vYXmW>RoPhb^@~Hnt;ze`YXd0>izP2^}XJ*Bmd`95>fo67uT`4RkOG zOq1fFp}uVPf$E;2P-bh@zyVp4CrqOi=W2}bB7z(9v#MOBgk5z;a4i{%wP3wyC`Wa8 z!zzsbX{^-QuD><Oo<iANBS*^4ueG>fdR0PFQYVP|iiSInF4}WnQGi;6IY08Kc*Od^ z7jrJ9K^Sr4n-pTW!TTzh<j&b}Dc)XKOL7boYrEq0wWNM3sabu!+2myO4IL|k1srm{ z*1?4;b-|n*mqcb-wT?b63Nx=xRWt{VxX0pUi1m?K6mGD{67shTXyYG700WvtTrao? zycZZt*3hue*||@6Fq?$&y1G9cSrOzxg;l{I?+|t5tI5qA&yfiIx9H?xLt)-&YF13W zu)xi!$;(Nt&RMAu$Dm2gXkV!o#h{-QRS_?1nHhlVpIM`@GOsc<qw;&Ce^qpIH7k}8 zN}xS&ZCYF<yDk(iGZYF9#j>qPBBRfi%dW(<B~0e9pN(!rpETn*3{PLry56JgC?sO2 z<RCS~#^wZ_9i&uC(Em&#AR;1$aKf{hX@214NViFJ`eZh||7}+CJz$rM0|Ct{#O>wl zk(dK~sT`OFqS|07m&&S4e_Cun&BK#f5HFDci=_e%|0bu7o{{MN6iyYU>$t2wTZpOv zyZ(;75oZ1E233Ke#O(l0)d19OQ6S!+MRB~nhg+rtC@3Jq)<-yO!2)1S`eC*UM(Jh_ z8ADZ}7inZ^Sk;=6gwd*Gk97T5Z~Muy%LsVTr;B}h`$hKp1z=X+LKSl1F_ld+!VXr- zg54$X(a$t6fJ=+3t1F9ZY9<ycdszgn5EKz8(V8YLRKpmwOOKbvD`+}8lB=-!*ORL_ z`P)+p$_lD$Yk?u6n>VPZE*;KCdlr9{HFGe8rG1dACvsEt)Ga+L#TZzM|CY+}bSIUH z*disxliLa;XZ0E|T3X^(AiI&S6){%SYiE%EqmNIDL|gdmPbPu*z~N|)U5YC(x(+-H zF9n9vbV^An_{Uo2$S~2!N`&6}*%Vrvm0AxQNc7fIITBTlREy0{?9-?u>xB7zRiu!0 zL!?)wO;S+%gE6u{twxbywy?60G|6G&WYNDaJ0&Ca(0Qpi_a&-?ki*biW@300iH3u8 z>%BMo@&YI4qBg6Qi5h*fT_79Pyo8!c0Nr-Xd+IO0Xm)kQc~XZ*VR2|^3J1$~9Fg}@ zu^Dx+a@d_*g50O&%0ko;x&(h5lTU9dAbeB7Gc%6V%iFJnz(}%&Oe%R?{g~V$u5J8Z z6_+wwvMFS*e{5#QkklCHgBdC^?ez3*I`u2=*BFs9tL}~E;59EwE0t25M*NAh!ADMZ z+wG73yJRp0zlY6h7#foMBbP|Co51o*bbzR>q1c&WM~wL=HW&$!Keh<)G{>sV@yEjM z<YK$@uaurg5L=nv^OLnV^n2&Pj{QK<;E#yYuiQv#oHS_uY73UVq81X9%f(ibdZWe6 zDLlB$r78>pc*o(bdNk<kh|5w^X$sA8)6J+16AEaanOQ#}L|JT@Nv!CZ1miyiE@+ad zL=zN>9}OI6`PJDMP1RlF4m6J@UNM^JT#JVjQ}=lZ53(a!w)P_e#S-3s#U762C%mF^ zH22>MeP=+Imwc`p95_#Dp2^~@w&$v&l%R2NyDW!CD^~bLvfA&KHCJSFpQuqW_BvD2 zt?v$-{JCw%V1rq5>wn+(&!jC+Z(5j)tb;+E3)n8Tff~RkY*?h@FgDSzQ<6LLJzZl( z;ghNf^2VfO++VMkQCd{$s<bcG5~ZygM`edc0X2c%$paUvH)HX|Ca@NVN+a*lu+Y3Z zA!6JMI|+-?oow>1F&sZ{%;zqugzD?Tc$VL))tn>kD%I46f7N(L;vZr?j75g2%;GS- zI(paluYAmUXt9ZDYpZ-|EdAzr(J^QIlMfw-r-y!eHkvHoTQ3ZrC-pMZ3wjgP)3^)= z6Jaa;RQ|2B>||jf2`nwPm6Rg0z>}l7p5T&@AF9c!jLFT)?Er=KPV3NcX2?!ap|Zoj z#)PpA*HGJfO6%>+A1H>+s0_+I8S8vQ=fB#Cqs7H-P2<D4+e`J^gXL_hNK5y!l=wW2 zYxK&N5Fcj~on%Ls#lPp@vk0`&L4_J+<1lh^@g##RlT%G5F0mxxyXhxW%faNz((L=} zBgEu5V{(C(57X~FEfLqlrPdXYMCf781DmqblO+Gc!r!!!YEr{6se(GMI+gGy#lC6d z1rM1rutd6KOhh7KxLVKe%jsK~%f?}bB>9y{2+v=7R8@)-9T!X6Ar|ZDh6(lBHk4RT zRTZ63Ikx%p{H7kMe@>ch`?i#It?yB=Q23h^PXxmE`u%a6a|Ix^)QN9Dw;Yh3U_e*v zj*HsR?}Fl^R!B@*BkC`8=k&1<0S!7DpzKf+Y#DGj^Sb%c`U{&jpM})3kWr7w)WXeY z-AiFL!E{V`x;IrG#{<Teo;%=OHqZJ_ypZkGkH+?WqMXUXAHkDYVG^OsZ+n>f7&$YY zjgK=mo2&}lIdLAO)6IVsn@P|-a;`lLQJYJS@)VkLVm%$uV3ifbnqQ~vENqLMEGQT1 ztg5YT3#|()is_B%lBWlx5}mR1llA3iCHRKN)Kc?l-DFA`TS1ZgR|*NSmS8l&`_81K zV1?O;;h~iW8e||9CXTqPy)y8w;(c(+&2){$D9tc4T?0F`7o?Gclj=<JIUDQb$yr(Y zg2s4GtvIoN{w;C>C`k<|6~!r8F5W^uqsBNK&i@Kf|8GZmbp#HJy;MPx%5ly`bOFgs zBkncPez+1@Dlui6^m@SZ2wqK1OEjedSt2}(YPp+W5l45TKrYB{>?QrWH5kd!9$UkD zyl86|;`TQiit$ox-J4Q7&T+Tg<gEbzrKZ!T`EAPE7iXC#T;2fjMFk;HP;8XX9ZI+D zLHcv1#T<<lxl#344%}i{v6e>}X09)O@NuR62E+l$9x^ZPxfCJ5kYwK$#I(Z77uhpq zM4;N_p1pIPX+!KXSTJj<{mWcJ#4uJI!mBNy)D3u4m`_C^Kg=0l??UKJ8{O{uVVxv{ z62Z-VwrX?5YsiWYB@wPZt#BnpugxPVsZ+IIi}KZI3YeikkzMXL=tz%C&Suu+rO4#5 zrAx|Uusum?5GJ%u61e(YN{i))l^V%R)kb;Sx$8uma9H1rO`}2K?{AnHjP5Ko3NB0v zZcZ<8{<4sCmjo*Ch?x3jtXx{-Tv=vKQNqQ;!M2z}mY9r1OcW#C8iy9wPVCZW_UFeL zoqT8<vGkm->d$7`gz$?zk+XJJ3T8D;eAFn<j7Iqj4u3~ON`F#ukZwohu4Xehq$}lT z8vp;y;1STIa_xpWw~&@fI&pRhX=aiCXOa)hCS(6kt8m(<$`H&hNzsItJ50P^g=#XF z>63Dk1}GpS*_2p?iQC_xBW=K7wYJV9LDkt_8}I53R)*K^KeG3KCrZQG7!^Ny6My$V zrmtR)s9*Y6T>h=oC|e1gTR=M_z&k%}wz>Cf&6)<Sqx2px^GtdV-7r)`18lG(W^G7U z%hRKC7~2s5SrYagGcwS5#|tzQ&s>7!k^)+bPa=MOTQJ%B^IiGkb8qujCi<3O%zjLL zk-C<Ln6mxvV^W(XTD#}(T-k0Fd;9u4X)8Rp$o9kpTa$Y--g%pwPq*X-G3a0CpZ(8I z34#GbE_O6t%mY6hKbX&&4)SxMZE_VX1uyiCkb*E>O&&=7k+sV7j&Zp1XDK)@IjQss zbs>pK0-0F4DQetmEnh23nE*0Il9|<-;|960n#D(j3bJcK8rL$qQWljJhMVKVTH00x zWzG&37G`!f{msMUD%!@%Q!>U@3^lY+0)mrc0$Y1R8`-|jg#~tQHg*oS<rL@%@rA89 zg1`77nh=6rd4)Ui^9AFe$ld1(Hp3LYl;mVTPzq7P??h}@vn?(eU3Jk7AI4JYP9XRk zhKhzdgKA;?<iX=j%g*S2_lAf8FBl7y!Da;qi1wPQ;bxKXdI5eV(w4*8Kv<g!!TtYO z(IMRw^GXM*#0<pA#-Z#9iF{>9si`?M$Q;FN<WttduK<rgkqWjis-KlH<1+ec+m4Hl zw0usbYEEr>NhuS=H3Rps&J!N(tXNS30GwPGi+6+KDA8Vdqi0R+oy4-gFHDejy}$0d zyd0)E&v>Sj>4ioGmn&k3K^u@pypDr3iA|MdK`^dRqo>1Q6X1?yl9GTRv9IH=ShzFF z*N@?A8~;jr$UFw)27TO%5z=gHN)D6t;C*GQUgt3BYs3G<Ik=-i;|q=*)dd_1I!6rb zX9n)e#c4A-ioQy|pQEM~(AE4NQSz|sf5kQm-BnhKxK;k{=E~i<whhs_S3R*ySYM~< z;|n(3$_Ri7v2{%Z*Ow?`IQliXiCB>jO{eHIWAyScf(#@kxrJi;ALZxDzNlSLDzd7% z(Ogp4l~#g{#CvLcdovWa^^}!qK<vqc$3(JIQsGj-QJM`tk_m<JVI7(U&K<?=)!}gi zE1P`gg(P-vj&#C*^yZXMS=tKI#niN7O+XaG1TW1uBEQ3g@I6CUF-zQ1<q?czMtb>Q zF;hkSMFk+(TpLU%H3`<#`-W6lRlXvq?7XRu`u{G6_TD7QH&5;h8yx>1NFHOJ^24f; zP@mitv9HWa5zS1a8|7t=e(rdb#zv&xQcd1+B?6I`_=yu+$&}}5Uh`?rroBKG^Sh;0 zu`~>ov^|TS3<l@p9+Cjji~#mdKrl-;Ai9`QCSKyeu8&D5Y8%7!T&nqMji=UF!;FAT z(qv4m+Bnk6D8Yc<FH!U6pWOMwdQVaXx$`z*uO^DV#vmLeYVv_MkN>N<_}}a>-H=8e z#Q{*B>-YDyXaf_@E)E~#(T9WN?z<vPr*xQphL79JbidOt`L5(K3Q~)OWJZCTI&YlM zbB8v9f2!2E<P1DUb>1z1#zs(4W^E}@WtuI@7M0lNdq1Crrruz}WG7e6IGemXO<&6( z*-~|Ble+L+#fjOAy;8J8-~;BMGtheUY6)r&=T6QdFm|%>veBqHSqPyBtafj3Kd)a7 zVZDX~m|Zw$W;NPA&~R2?OJ}OtW4C<HOz$f-Wh3lNaiw-Nw|7T7nw)&mVz@@t4B__N z;DXuPK$qBfT)_(*8PF_Zi2lix!!@cs!-*!fI10Bq_91WOB!ih|!mEqBtNevg3>8t; zAX<ga2P$0XS$1-zhi@XS$XOy7!1o>T`#W*yOYY**bzE!-(rBN{!_FC%l_mQBKt*pD zRjytO*OE@^``;os`TqmHa>8VEEABF$z>0*pQG^pm3isWUc&W<X%Mym;zz@2P`En8C zLeZ$K9=2ZI`7;+GO62I;V{U;@BtMeS{y1LLmmXj<mN1@q{F~HsSdR&dnd<^GD+{n$ z;Q^V(f=W6l)A4LN{zAF`4ef)V3qY&m$(w1NxbIW-UbxkZ-dd__mQ_7vrQr2!5z1qH zjnW}KBGqEzK5vnCi~!V1w_CCIEE_=;leUb=y!mv#(R$D*77vHS(JQB8!WcWspyUnu zt?0qSQ+QqG@`6^6a>wEE$%(HX1vG|jMfEUo1%LF#Qj|D)yD<D?Fq*cUOL6w~%#a)9 zjuP)F#0s}_u8y)9HQul%6m8pdfNgpkjiXOS?h_ttG2JPfF}G^-ky6)*dtuYQ0H~sP z1UuHWQMosCpP^mYWLIEyjZ#(`WC~>-?MQ3y#*tnr9N}dhW&QS=C{HP*jP|c9Us|2` zMv*$(xZKVVd`+NX??^Xun}2#^_glvC%Y*=<?X`-wy;Jq6O|7$i{-2_nWeM>jT4-z8 zq>+VTlyAtQ7uNZoUY5YrNCYsNYC|*?=2zh{GzOwu;~9Eo`k9%)9B>Ngdosv6nFbx& z^3E8MeLM2v^1rJ4&7bK9^fXfo2o4$&-ZA~hb^LFxt_-HU2jKGql0m;UlbkOzH4OEB zx_lj48rb~2N=oLh>d7YbSQK@O`FAw!*tQEI%Np${>KaF%LoZ`LBMt9y@JHiGkFicW zBI7qte}s~E&5eO%YaSD?vIu(Ps=@<OvuDDRXS-HZt8JyR#zJplndh|3^-eD5Y73k; zhUqPd&_<~5iHjp;Y-(+leQ1Sk&RPpHH|bgOgeiwmN1)&|eJj?cXTeWuBZ693dBi9R zc_;3-i_=)-EX^O@*V8ve`Iaq$euQVw;l=mu!bqeJ?xVbe3Fx=!kN!H)un%WHk3&9v zB_NCbs_0@tFU32VgZCao?qJBPM%0d%%ah{N_Pp?%-J2KYS9q<VRyF62AtwO9U=}EH z<^8K0iqKae?F*qdZYm(&@+jg7!_W#`kFRYlMY)Ffu$?-7>#_suaTxu36oy@Q_}bGL zK)ZXv)Eph%2W04@lsD*hbNi|{7=n7%5n8^#%N~&cJtL)dRaGZ1PWj+jnVyN*bLTaC zWjB?Fnyk@j&o1Qgc5YR+BtcbfwaP*X9z6~5JOi$dl5tfaH_li}2NAS9Ih{kdQq|JG zagNd-4V+qziGg0x(_z~&zvMC8#ePi<qza@z$hg4z|ImG5Q9AkmK@j{sBoZ9n?P3<v zm%GY_&7(q>q$?*k=17j}3cU4n4>}aCKiQ5XpDx*Li;6p&kE+HNx{H8k&YO{?ejdJP z@Z0HM@nSR3Mt~(*JN4tpY^pXmONRM{b^iR|@wmHnn$zkK?Tjk+SCoBaA|zQ_7TV~4 zc&W&9wIzv9h#=hLE*)$2_zkMPvHwK5^wGW3O#aAhh0+PTa$c7*jR4%METG&>e=#du z%p^%35~41a=modEG*m7{pn=gtEULU0-svV0<Zs1|+}H7be#(S$Q`fgb8mfiUwtBv2 zB7mh3u}Qxk4I*4%M3GzTBM@9Rv%s!)6UFZoTtwES7nMF}5$LHew9xN#l8o?2t!rKO zn~QcjtsiV<u=&<zKtCE?>uLXiyN1oNhI7x?6w1c*gm<2h&m4AI9;F%V!$F*>p43c0 ztZa4`u(}}YEyq?8QT!08uvdB(-gLcY67rl8V0{Rij-B<YML<G6*Q4*ryB~{Bw~Z6p z(_$Wu71dcHWy}G+mVYm5kySv5KpOSXFt(3rz20|CIpe4MRVm4sHJ`56Y&zqV=tf>> zBoU`Mp%%gvDYjUViS}WIDr3^ZQRX2FjB)W|W3RT1=`RQT-U>3kpw;Sy+sGZRp8oUy zgQ+l2u$m&J(3iiMwY)F<;kO6p9I&qE%aw+W3aPCMe3>gM7sjHAk1{&+&dMHkIEgap zG|GrK1=N4iiC@#=-;6VnuB(Bx07^cnnVEO4W}~AfZPv<pH$&%l0$grpY+gC>PQ^kd zS?%Tz(whSv4y;*HEtHkZkW9=BZNTPg0mtSs1Bxmk%i*j;X_6*~#nQIxu=P~49NX=M zG@TWe*)XrwxdxWn3R1%q{qI63XnqUj*a9BXj`FiVkLB7<=|+Q$AYfv1IrGAl27(?N zZTIUb+M~fA;Ay%Z#LX(vHfH*15KHw<zr^*lv*mZERFyEY%z1hBNgGIH`@&rV{6huR zS#>aq7oQ<o7iq&B$~LdqFD=MA;x>kq7(w+S?@3i|rI;ypRbY<(!E^VQC&;CX-^@RK z`-TTNEi#j1_xmxuxk3eSprV%d1ecJ`tJjxP?}A+M&O_!+M6lor^ZQwkg>0;K9sE1~ z5<)wWXCY^Shey|SL==v3jMJ)mH})n<E71LgVX)5h;IqQ@u$uFe8j?k08bh5X&$^Yx zKf$Z@^9ZNvQqIv3tCz#?wn<|XgkK-0>2y*^(#o@t`70AS&(W5;XBPeAxDDc94wer~ z76L3l0i#ZV7vOp?qMi}rx)TQ}F90B&IjshaDw&@AR+kmk3UEdQ^7z@%Nisk%Z!>rA zHMi<se8y!R@(TFQw!tzTKK}yV=#vOB#`({dT8(ConoP|b|BGdL#RXDvJ?aBBCh>MH z-quL3MXC`Rf7FT^z`~Izc6b&~ib05`??Y9I<*h|Wp(h3~=zhRF^#6dhfm|%DAR(a` zBbk9vjcczKpgoS|;pr(^M~7#qm0G-6t$u;lva2X8F8f*{PECEGd&j`*JS50B$bI+H zefnjOfTL5o^OwvsyzS;@H?n=-KonWz@jo}?CC0}%BlHscQ>c@>98pa&wp@cIq?A85 z#vsxueI;ABjLhgGBe1*<SoX~NrHYxsu0a!eVY2WP)#&XW*H{L%isu|BF;QJ?XRv^Y zhH%I{&;A9d@EWbp?mLk8+>O$7w8RNF^K=RFP_<-UBU-0rdNprFX^H5?Eo!=ya33D~ zj{j3>GGZ&Gy=E+M#nmV}@=86ExCKClVLRH&=?Jbi<(OW!0)CJe7nCQ9P~&MfFj0u( z)x&CO3%k;pEof~Dq8K=YL>g<HrB0+O03EK;k5I~zZJH5oE@Wh;x1$4)=Ra(PoC&JI zo<Kfs@HBE={+nCn6{W`uxv}o!0%1q^CZ&FQ^1egsJ*zXOxt8!aXOg$FR~Oz9b9+pq z<b!GVItGka5n8PJw?48<7>S#hjT=oiw0hp*F^>pnAw{E=(mhZ$#!eo?^Ch3FqXMfo zC040H3#$@SDV#Fd+e+2RNIjirY*f#c#DlCI_;bNF$@A6^r$A%MW44y(%?h#xlpLeB zLUmD((KxS@ITP!YHO)nBQr+;TDVOj31~#ol$G?^ofVQ?=OX`F+rMFdBitH)O&EPDH zZ$r(gi1v2PD@*Rn^L5pA=OuM&UC1qaGb%N`wY3=vzr-Fka~oj2a=4agmekNN1@NgZ zG}G1d{^)+cI9m`WFOe+yL3<?`6pwY$jc*-Y!LM99o#4~Tde&SLK|uMAqSV1&51E`A z{X=L!vgija%+lmRWA^BhK>pB?RjmV<2I^N)$dJh&OUf<^L2boI%T!U`Sv3yr1_&#X zJq0keTwb=O_oG;5G6TC#dv{`Bh(y8*m#1yNu8$jT=j03>?!U5;CvJ(hyHK)cT7S7B z+88y6`mFtzT9bykOVL%i#bzCkim%6mJq35G{XtMw+rR%lNu(z$1)INgEERExuSOHs zIvlEfBdB@OqgP<oQ;}f_G0Ta$%}GKqyN;x8vH=O~e{kud<N2QIr=A7^aNO8jp8POW zVb`7Sl^4zMnp5kMhW%_NOCDk7*rw$K^|?&Pkcx9!bxO0=`}VApHVM^_BX#A}uYXWv z=;NzLHLNxZ*V!aG{Jiq(#ubV9r^@i9As-0>ZY~Z25KjW5cg0`i_wkH!<023zz=g^^ zYsD(nNl`g=i6TWfUvVXMEIYB~-HXS33d>Udj5Uv`Oq+h0H>Dq?5xMvaJPz656hfp( z%z=J^nNNS{*{XUcLJ9xEl~O6h^u|fAM|(=Jhtwi)D&ocm+_CP_MK)6HF&a+<kxF8w z??%`}H-0C$ejrAR08!Zg)eb|kcl)hzPymv1u<YDQWKm{+VC!U9x3@-3>^Wncf;fco zly;C-jlP2U&%Fp1n|~!r6^0+?N^utj*jz9E@H(+0w`V8nBO7>fT<yW#4&Til{qk(D zL7h{XLooy>%IbUVg-#vlvq8BY!i(&29IX0CNf6!EdvD-dM+^LqVmq$u=MYlfT{x;Y zpIsI>X7C~$3lo#&n2R=W$Z@O4&8hZu+j5Tn8mjKmsW<FY)QuXv_R#)}23meG^4I$v zJ<H-cfWzvemdr^C(-1UKrX__GGUgsk8i7J$P)ud^uAxWUV?zqpi4B*gj7$C}(nFbt zt9DODn$|z4xho6F^fc?*KA?f-_De-(VEN?L6)_;K`p$x?<fIV05~5;LxysUF3ndH5 z{bC93wBn-&#kJRzXu_lt9Ia(DrQ*u!QieeC;Kkd!KA59`>zAI&pnKqjUWF>*Gd~6Z z(c4pMEi#e<ABn(>K#oE4GY*IR?$uB5H$KK*zg@se2BVR|XvR04Y8^BF{Bry$3(Lu( zWV0KbcT-j*;ob1mH3VuAbSbYmxb#tGP|L8n=z%{XEx-C8s%!n&i1McM)r{F{Fs!c+ zG5u?}uyQIL-sRp@BDvO#5Xn!O-P&9(&;d=A=FlHx4LX=~06Du^Q&Yx*C45l`<-45R zn&+}s25LF2(3S^Uh$^9jCRUDNH5nl>F^YRsbc~uD1^@sEtHE(pwc6w>(s{+E6YtwK zC?xGLs;m^km(`O^KDa#i+-J3`NLJOJwNh(PaZ=YuHkLm-e^k16NaZs(A;-|B?;*M= z%Gy1;1-c^ZslD>(4PvOF9-5i??Wd6<NxZPB(#ifqO&eH1czPllk%uO6{B7eNzP8z3 zM_xm1T~GF){Hvrh0V6;Fz)ygrUD&#fA}+^MG%c69_pM?j+*EBTGKnQApm{QZ=lw$Z zXtTdrNZXWGaOE#32i3+e%Q#X;?-D=&SD*H^rtZ<deGV_jsXURQx%8WRRSmXH(4SCx z5P>$n$ZcST$ERmIKN5#H(=_%CRP1V$(oCyonyF1A>=63ygwY9LGm{fxw@n)gX?;=d zP4oS*1k>ef`*ts+oEs6`;^onWN6ouD<&qMB?7g1k1TsRWl;ct9@;jkvB^jQi{Bmk; zy+UF4fkL~`JLOKYtKkW2+>coI^y>+w#y#5_dG!*vxk5-z!*$aVtgQ<@aQ+0be0fn1 zY0LL7@W6#{`;bp;ca9EGeQS3Ipn&WT^u#)>8QjT*c)vGHC|vjyyP7Z~KVM{usL9W9 z`Z?V(xO3DJET^IQeY)9AjM8tL&Hpz}Ik<dQNn2V^=t(J^a~##5nVlOBjh-psQ=#_G zCGue)?_UTAn_3VI9ct?Du51Liq-~o|v4zHsqm!pEZvxHHh}_S4hi699wq3u&7vjq~ zi)<g?0E3n>oy(X@gHa}mH(@Asw1&Q-9D#)oqoX1}A<s%&a(U|~>W&o76!FfI8WBf| zXNDUy8fhic`5MLA@tn%ZHtpSvl?+J&<V28TS7}_s+nE06oCq?cVUK?E#K#WE@j(P# zp_qyiuO^m(r70u&Kaf4M)C2xosQ-v#FLSV%_yJj26VZ~O8udI3n<ZUGE43QsgtA%# zv0iSYMItU#3wNpRMWZCTK$=Mpz80?PrDP}8j7WX;BE>GoCwRB~6&0`Kvp%B#{xx0r zkI2;0jXpSQZH3yAkyIjzjPl5jsc~d!)juqx`EgnqMC7(2aduqRI_q@GFh2v*7>)d% zsCOC+Rqgc*FlijC!wZM-GgR&9E(638ie+WDI4=9BA((mlin3{3iuhK$k11>BM20|q z^m8ebq7{8@f%X7S8uGEAYy$K<p>S_xqT+l-oCm2vAF7Rq!M4lI3D3*24}H1hmw&ti znJy;uPakQX1pk7fL#FEeDZCUUEIW;Jlf~#K^Ja}YQ91Y&C!+*llc`%CHPPdLerldd zjfx2wMYn6p=)@q&W46FoDVq+OHj`j|w-6B!pu)+0$MWuI|M6pYcg(<M5pUdxa_>Fo zhHAu_&w?VcfMsQq@B>y3#KFJwcM{gRssxI_qbYTkiiUQybD96&2^t~&xFh?-PWU#S zy;Z4=u27VehEV|X`hmE^^~RNw&N%{p=O6ov{l7#T8%Ug;rZNeOslt`zBa)J4zlEo_ zQ8?C2t6QeDY;$8SbK09!IM-xG^=W5^&b$6StHuh2kz<%$(@dicO9Ya{hFq+2B|QJz zh#Spj+d++`6;{u?)3cn^&!w-c4(!E#m^m!~sfKKvC9SbHib$s^tHkXcW4kl;O+mo> zB~53+{0iet-r*13mHN~RI?yys%XXD4jFE?hhFEo(4pc!swG1zdx=@Tww<3rhj&8&( zHES3xX?<BaL#mm)vYv+2)FkxAV=b$;j%cb3eW|p>T!Gh^{E{WqDu*a4oh#6>r}^9Z zk@A?hjWhAOdp~txA~@}|YQFjPM5_l&i@g5__RoPyjh85hKJyGSkKH5f`_TxngLRrQ z7lat8WSdlj);2khW{pl=Q?n6FX%65}p+(>ZYk$?`hQ`pnmG|BXGJVA<gps&OtnUQr zK>fqb48Sgz50>911Qp#93Wq7n+kd)+Nau<9@DI4RCen8|n?z6?#+aCysWDw(r0R;- zlAiRNJT_@rE=X&HHZfYHZ<}rKhH8yi{%7J44ODb|`6o9&a9z7m;U8hq4iLbsK<J<e zM--xCUK>>YgfD9G^z@x5-I#=d6bBcNk)m3bFcou0E~;Bdxk(59>r+gBhXgZUetjBU zAuN$dPPikQ$n_`xOa@WJMVYRShAaDl)EX%Afn>vbL|wSBk;KF$zx}70_&zR7hD&0N zDCzo-{{$XRa!d?8H(!R0=xkMK>F9$D^B~cLF&5o3?g8!s#dmYp?nVYEp#n?4xAxWH zQdB>j$(Q(Lg@6WBsZJEch$2xEv6QRq!~A1Goq!-k8Uy1Wcp@5kH$le^t7)-21yL=C z!YIdi%8f4S2k$wfjfAi_^@ftq2-KqCE!XFosGW4qhMMj&$FJDby4EK#424V;Z+#AH zrB-U|LXjNhx8he%b57DRN9^eh7v@9`w<(TCJr$}lwo{dO%iKw!(|((ahs{Gq*YyhK zD~+G(3lMm4?B(m?ifOCQb*o5}g`;`L>NieCzAseA;N5rFyExNUsw9`F{k>6a_j~`? z_Y1&@1>d}xa+716klN%@TK}!{&VpxaMr?~qC@W#6N_B*CRE2vZ^bEpSRxu}7=)m0) zku=6;tI%p#)6{eu!ql34(W$@k*%ys=mXZQ%;;7zKh^WJ&)%K(2Oc@c_S`DP5sxTMS z=BORaAep4g0NtoOyaO+PHPn0#uN-yMY`KyG3Nlnx^9vCnbaNQ~*b4Iq>6=2LY<Uk> z{`wrDNjINfTUC+AwJadq_|RnKv6i%(16})K7`r$!{l&^HV_nctc`dyA+NTfeLf_Sz zm&_>@wBS~HLVDUiY~x`VTM;)O$KJfz72voK(JUb!v5z297<jPYeMsR|3ybR}zH+gk zLXQ)>d#6wn61PR(_Ps~X_*L=n(_g)iS~NFW--Bt_S+b+Fg_?mB)$Gf@wNz0qD}^Fn zd3&pxrkPA=D*q6(eS!S4Mc3mgs`m=FvC^V$N|u27CeeNob5BA(k#U*~soL=|c+Ul_ zE)7nAPI8?2#74po_T=6Qc}?=ba5`|{Z%{AA7~m|`q3-qb?UQC6S4@lyMu@Lp8c}Lq zY(9Rv6zhdc)=#q5=6WxG=;F#=68=Nu6Ho(D@jYMBT*NI29>-LELV4H@`=FLsX?G&) z(2=KU@LLw?{|~1{|M?WsV&OuZS|I+>#jBR>*Mb;SSp$Fcnc`Z9Q8aU^8u!SO;@4wi z%>tcDBg>$c<y=Hlz5l*u5*;TB{jZ|6Zf%<pEoKD6N9E7T5@|Rr?<|Aj<KxS18*J_) z8PL;+99XurcbcUCqYqG3C-H-uP(GPm%e<R<*(04C85w8YUJEc_G2WNKe4uf^WINNj z5opV<GiaQ{KQhE_#NRzePduG=YMbK;-ZRPl^h~0`@Z(yLuScRr+J-QKkbDR5dRBi$ z;76u$AIdVquTq%{BW|ciT<-9Kl`~NLsyomMq%4xV|M))J>mZG<rj(CmSS#ilo@yuc zX$d;*{OnUIVkeyuN3W`V-y5#9nBMf|#8JGgAWZRc;|p{?Cyl#d4Ss54ZoPG9RyW5W zD9IDk?t}XzS3brAY)%6@jIntI${CmrTA_7t8N_R`arP8&6rFhRXfw~i@Z}xKJtQXy z_b-|orYexVw!dlq1v*o32>N~1Q2Y{dE$Vy>UUnol(Y)F%$Ym?m*Mk|vY-NFo?K_=i zt$kZ2NjZp?o+*hu6uUl$<p)K6-p=kM@||At?wH#Z-!9_WG<hhLg;p|<D?r761Iric zO!~zVmkkx6(%+q9>3WC&b@o~~7S~^kFJnBnO@GORf(b=BZ4|YUctrz!7ZbOF{;j8O ztrT0Q*qf`UljJ4Hrfn;<_$;Ws+EVt!Doyf>qwdIJY(NgvJ`kLIH;*z`5Y#)B)eo>s z-IQdk{*+rI?b-sVKmvG_Qt?I$v=BTln`}#=I$T@%G_7p6#h%y%E+(J@Wt=Jajzp0f zm4-6X1?LCir6y`@&g16>JJ7bZi%3Tq{-i-}K8iONb)iAh5lGiEel$dw=C}2ydGVH% z=W(GBsY_4_Y({$Bs&(MpbNbn2)Lc3%O{%AJM`n{^X-YbCs1o0!@#z;bNcb7nmO6j& zS0DL@vdz)|8DJ2~-(RF-V3JB0{r9h$+(W3_kCLbY=KE@_&zAm}K5hqkO$zK&ZZ%Uo zbrMTB$f=4c$tK*P&mS^Bm!y(K%SNaw)yN&1*;?95w6bZ3Hlh4(Of-vnqqU?US8dOg z2369iRv2RD1zaI9m=VVBLB%c2%{a%=-zM%`iv3^T<%E50-aT%xXn3V?Va9=HKWLg( zWB8ZXk2Q=&`Sm`gfAa_D<nJn<9nD2F%32(4l~lC=7t%0=Fc-`_wR)1$WF{3DwW_^U z)f<!cZgzGv$gyNDlp2M)4~HrEu~-M7*8GF61h&J3OkO!B_weWQt7S<vexiov{x&EP z5sq9Q!{y3{%}M0(F1&?L{do(}lL3iK>BYD_{BvL@asDIvemXdV9o5Ab{Rp+aCuqgJ zT_|h?d(l63;=}62`?2JPJz*efKz$`keAiAQW9y@t>qp>m*#=qgqA4FFPJC<iAcDrD z08f%1Y>6_1(8f9lnr&|K@v<g1<0+!q%+kT%vnx_2UiE*RG*QbMSj9juG9`wI83X-q znw$<Hrjt24VU(NvFzjPh3DV93rCUdctvn}JGxJ~e`ki5B8(Tx(eBV~sa1@r(Q~cL~ z4$9m=$`jmll|72U2nKHoyn%Q#Qiv&%wAPo&V6$B4dh)mG>mfOj(78|e>)M9j$3_4I z^Vo<umeTZBo9t7#Z=ky%tGdeVaUXFSim1JABl?I6RijS3QyKGC%yA-pB1G9>qlA;! z4)Gw%nm>_)`K(Ey=e4_iwq6#^FgjU4G6xpR^U9q6>~WrMbmilEuYSEXqw$NZ>e;mY z&u?3Jh<S#&biyXRe>02JNrAd%b9wTSIOY(EaJW`9T6wBk8c4H*t9IwgUq&Qy@Knbd z)H%UXlpqIoepx*Zf7W#E#hP6;?Lfk7731#Ih?`xlJZmgX6W13OX~rbJF+0(Ut;zQF z7IvU36fkrvdfsYIs8CbyS>zd=h*>w6BXvskp*+Z#giS|tFw+er&wc<Jp9}IR4!O(@ zK>y`4YC=ulfOyJmg6##v1;e7v;=#mEvY#Ry-~HD4XM4Bfo#<_)lILwXbY;0B%LP?G z{xai0aJ;A9#ZM3%f%^kLzB3dUIJJT=&d&NzGE7Ii_VdTg1Eeb2=G{rRnh`d9Nk2?J z{9hpkV`jhpAxY4eM2ru{8!F5c^6T(^|7wgnJFb`3^ntJtv%||wRNm&gL`C7`2Sb`W znTA1;+i7TxaIi!|JJozt%$^+D?1*|VU66Gy2Uqc1=`Y!Uet3BJmPY~t0^s4{jf{+L zZf;15=#<{SVDkwkSl80tqRtaos>`y6L=&n;9w-?bOlJhSH>^9DqO;jD{@!3xQDbaf z+Sc1+&7X_*WzbfMWERn>POPRA3!Q?K>|;<aGmFI2uo?8#QovCKx*&ZnQf=thJ=|h( zYtZ_utV@{AG%!BbU#`PQiJ*?1S<%tkK!0LeU1wiCWt|pBDmdNQY){Fe3s3~hia>H& zIoQ5>(>JE?j&OuJBk(`nObM#&OqbH<f2}ge3lWI*R+fII{h1k7E0RYlw6CyFN@dVL zD`0CnyT(g`%))QpM6UICScWF1VIzev(71^b(OtidV*ie<i5}6@7oRkkXZcfr$8a`J z$2<*&z#pZtceYayXO5?gKKAVwEz4u`BJ%BL9~=t;DLeKoyH5-P?8TmIQ;#50QvHMI z>)N{pbSAp3*ktY{%JR!j^cc|x@1<1Z<2iNlrT2hq?9-E8V#pZwci0!o#S;B({t^sN z8FH&Ju9FJ15{=UL)@ukNr~92aYbwBR3_N}`wJiM;VQkulSOIt;kL+!H&;O*GOUI94 z3Q~2Is)d5NYwLwJPBqP;MQj?Kj779ksb<x{rx#ZxuL}6ElS<In5XJ|bg(ft+MMev^ zFAE!H6^*}w&W^zd?w!64oIFlqi<a$kFNYphxswr&L_clgF<U!oJ&Lmz7T`5?e(y&K z5Y#2u3cHj^7)Lu-XAs$Vp3X67lu2j<=MrlZ8hnKN1^83ZTZ_bFs_?iIK^Y15%1Q32 z3wR3)JvTN|W6#jx4KJ7Cg*M*ZGpUVjIBUHYcfdP<@=CGzERLxp{g^g|!>4t95fMQI zC6CQ83IN>?Nl%qu4f*(blg_DWWL0)FwHu+ml<eLJtxjS{RjIXy<kOIf-s2(5rUpk& znOj=Jo(>}qj?h`*wJ0(cSHOmem~xsX`O<kb;-)B#Z<=KcEUu4p?na#w05uQ13{#l* zl}`v{j-N!DqMfS!kEJ$a&2f>PI0&WtK^^lga{%k*T3q8E4*!uO2!QZt!EXEyM4cfD z2+J^^;tbXK`Wlm8juKMRKqE%|=5TPcBWLm1%0|RcW(+Ym!Y`FYa4V^*|I;&Qy79fN zwqMF<k|9Ydoem}x6z?0hq6MZ-bx|>|+IIdjMQ0{vXY0GTxa10W9xvBSJ+8OdceS_w z%*t}pE#xrZRfQSn=Xejl54{wsj|of16*JvpbkHRGSo7YNkyr<tr-;JftKKKSLQQ(& z6L*)|XgxCXdM!)!A}XDCMNb(j$dS@?p=KQ7wtMKcABm@Y_E4w+q~c!b;TC^1Y>($F zd|ftZp3~>6?g$BfGn`%671#7X<9^&mZ`A2H!}Kctq33)FeAkq~#_}yr!9#}b!Rz&e zk^Qb>Y{{0?d@J|cGNyyg-Ep=1tfjTX^@z^t{_Qg+=4CIvVTHK2*PU4c1`pC9tIf|` zAF^O2_Erxkzvp)b?`q#A(Z#|!?TAve1_TX-Ke7-fKWhPq-H|)voNc+#^q+8=8rcpI zN_&Rpsj9ukyzpUmasBWvuZWrv;=WIh0U0}6{~S-VSj8N%Lvjj<VL%ag5$sYKgo9Nn zoPdr`O3hN%>kBEftc?TxdOBT1^1S`)PiH06cMU8|(1x!)3ng5J2LzdCqyA$Jf~deo zv@?$amXdZbr#Fy*A2ZJO*9+d7r)|xL+{Hx&wbB(i24xM;*$sY#zr)TvZ4o|3P#mDP z_$^#!9`$ea{r1PBO`Tpe!F0AJe(jK1;6kwV)jubmb#SIL-CtW=1MmKdZBgJK!P$J! zNt`j0u~!O#{^UDnCbtnY@98TE;vVZV?Y+NZ6=!8tl#>L1H0L90JHTlA0_SzvbF=Sq zW0SgZK2=@p5MXy*IeC1E^s06Y6Yv;Lar&^ZNjeJ=FVmlc8Xev`LL<NCE@*!*m1bpB z??&5fOg3sFBvxQ&G<5C9)VIseH97>{uXZC>u4kk+V->d*5=*nBYdx~O2W#qgTC&RP z)_;`eF`q|owz->(7(7;uErPjs@JR#bHa{?T3wt<+;7-kVx*I)$FuHC#1=>%@nBCNq z&l=Oh$o$`d0@|H3$c2oAGrvqBEX)1*^xvI*A?h2HwpY2IkWqqKO15S)!K}bC%*6v0 zG#o>%_5MBe=j5r7*J8~M2<A#=-KB_ah=`?W&Y^P`w=w}bI=ZN+=nsOh(9p<lCMNm0 zxun`bzV7sbus~b@mWlo|2DoT<4*y3>r4CSosg1-Wjo|e&AUUKXDQUW2=GWY}UoyQx zOew~=gv1Ru7Kd8y2jYDL&@RWu!I|x6tjqmH8lO2gE1BTtk#wGvKUtd<d{`(YK*p@n z{6k-j$>1w}kGP>o(oEh$_J*0brR%dg=YLNJ^wT!icR{aXl(j;R#$*)%tZhii2q^KP zY$fgU;VgBi13AkbIn{`#m&JQkzl(}yOO){BGl~DuAfJ8NL&qW;GXG0`^(jMYgAP^q zyD!92B_qW@dG3at$l`EuYTD+R!Pk!J*DVqr(Bv9@HQq;j7HN?-pqL-S_Kb2&HG%m0 zyXzC5RBXukKYXX5tq2d%J{p~4`kr#AhkA9ZtcZnXb1%_fNMWfKAEDuwO>9IvTK#)m z!Z~xtNw#7VQXro@O)L56gb$492f7mZgI-YrKT!ARy5i#Bt^?C)WJ4TsS4)4TC0jw; zL+YRf<c9hQf(clI9?pDd@5T3xHw9zDdSXFs^N&QOps=*%-G6KC?4+{TY~u88eWwxE z3YP}1%UHfSCK6>6Fr3W4-2rGlIat<9Vve@+kN{F3ju?i2iC}nA!Itu0h>IYypmh}A zLib1cYL8&f5(ncSa7Wd0SoBe~N-MGS28JiC;Xs{zJRyUa8MK(?&LV`7^X4&rcZ2fK zO%{mr6NMRhtwfLp7PkiHHS`a3hAlta{V^ZjP~R+?I^2eOvp2S(^yG1+zd$V(Z=|B~ z4b;m?KEf7K2u|`gzX6s(wFFhhX|~4mMOUpJ*JDI?6PRcW1;_x`q6lH|<G?L5`A6T9 z9=vALZMVO=k?JTeUXt;Zu-W3*ZOHr)dMMIxAU^=>ZoeM36N_7jwdY<l8S-Y?9~dd$ zz2?Fqml)IU&gt+0W;1VRla4Bl)HtT-sj;uhp8=o`Kp!7AYBM%oEEE|M6Fxz~7)!ti zaL@Ry=ko!jo+g?_Q}r#3m%N?${~#lr{BQg#&JyuS`&T0G{k!Dgih|ybhTfzCP;WyL zf97&gB_ol?D2ue8^jPv?e>i%_+y`ZWdD$ZegoWo)r$>61&Dye6*n180fIOS`LZL_4 z9_<lZk8X8aR--B1V@FFydDBp4P@h0pi>FadmEn%$AMIZ8Wc)^he~Y;DEkD^vi5AHE z&faB`l`BdQ{lJ7qxO&*x6_r;L?2qk;QzVn;56m^qZjT7W_5uK?iul`JMvt+_iWQHD z!QWkGXV84|R<7s+;)24~+3h>Iyzv8sV$O@^I6r+Q-^mIKCxqm@J5hyNbXDCX-!5SM zISRL7c^-e&Q%AO!$XK5%Nn8FfL_d)-r~qm1d<o##QhqoZWXbQM%{o44OCJD%h``vE zEl9;#<&x~yM_=7|2CefuFQX*8*vwgFZX1*Jk}IXMzLqFn4g59XgVaU$hLef@a)3tD zk3cFmG}Y1MXQg(k$B!8?c)tH!<7D9FdH2D0{>N-{i9LYME>{q*H3A{mwLm>gJBcvZ zPR_o@wy#Qi<Cd2Ff{!yc1>{jBAX{QXPn(B<1eG)pLc*7`RcPy+kB{RvW^(U$aQ3mY zCR#YXfoF9lvy8^BtAlAIBr~T`<k+q}r-7OKggp*A;jx-sR|tmayIBm0mYN}#@Q~vg z>NRe#Uw$R1K&%3Dh28y&m0qu|1-voPOcu%kw3ql*1-@Q?koCMiU&-fel_O4n4NX!^ z*|0f{{rp}<qKpBem-)%wz(2ZH+B=+oAl8gwK9}EU6%vJOM2_w`z5Sco-N*#SlpyF1 zAXo5Gh|hrsK=){kq4V28Ee{r1j5F1@W&fu=i^C$r(y1sm2;Pm1m7Gyi5TbZ^dt1wC zba|cb?Cb!qk6nMtVue7H*xsMZbAtbCTZXeQgs9<`r1ig=0*6g%Uf6+Dn~I!?nd5}X z!NZBD3UA}ER^2P}3k&nwD|L#8*`3WJV#?JwQkpIPJeosKXnQ~6oIq<I%vZQ6Sqok@ zRW|9fGcz{e_?c<XB{$FVrwldjFK*I^byhD2TyJk_H;|8br^z-c0N1Ee-jm$w(QXCV zsxAM9(J+KuO7MOaN#}JB2C=Ce#OY`4f{={5{y2T}B43yxRK5Egk}(nK_ak3awIzaD zK_sr>=t7*tp{*p8ijs<SYt4m8tRD&1hq7Hzaoj1m>s;hnhg#V=Zu_)!cKas<MH=V6 zM>_kcp5V6l!8<{WM;Pt?W)dvbQRZL2Lf&O(>dWl#Y4~t`dTCI=eygtukNpTU4;440 z1+i1m9(?mnU`G*OO5RxnXu;~Q%`&A0oKVqWBkg`>{A+V=R_d+w*yH=d!>D4;T_30u zL1DkpE4cD`byuzF?8~zaxLaBPL*^Wv@DvRJ9ZsuiFr&;|rK=0YzR!3k9`{UVH~fnn zGFaY~v%{&Pc{`kEq()+wV&fhSvGQo#QGVNHqbpwa+C+(70QOCq8vKn?!I-}qd6Vos z<a6|BfUE~)^mReR5;UwrZMu`%rP^&Vs1OyB^Z{TXgzSA|Vt_FHX;=%xpnl-GlFyj% z<nR3Q!)BO&yVpl=mfb^32;&%Jfs+zwp>Sjf`Nk{I-HyyeuPM$f9s$x-%i#?(e*Q4S zU6^%}Bf!Um(H8XE#~tg%!)J_l`kzk3z9P%&apbw;j;ME?!%!rmjhO2xT{Wd6VC#NQ z;dT6n`JKy0gulBF8nP}$-!GkqG~r0^|C_s<)%nW6F1%7HM2DxRRnI~3?`_(Q;H|xh zIMv}3dWI0rolq&&9h0{fEiEmLxI*mDuNNTMWE1%}h+z;6CjM_K7A3XWLeiG{-+w*2 z)K0a8?CfS7R5iF0u`tv)5B@=!vAJ*30*Bb8h(J9jJiR7Fo?nDpU&`d$VC2~B+_-02 z5jVBc+r<BXh>t7f*PjnVZsPi4&ynXCvhHUPIW~kK@Ba1%c6f5)arXvpTyK8otwtS= zY+VIKW72->{B#I2^H*<91Znl|D`qgN@@0~pc_Lufnb{+4-1ZA13EjT%>Dl8_B$0)r zK9+B?R?a8-3VNB%*rEbMM_EmKPI#_$#Ruexwjz94?5s_vnG>Njl)2kmqdSK0QMt;V z{4fpk`mYeWh4bwhNCKiOc=?`o?cdj+p0`s4h+P$nx3~=fFrhyfo%oIu1aL@Y*tb=7 zO|F{~cqv&Cop=9zB@AmzA`gSv#G-uf>LQBQGYv&VoTx8ixmg~4G2trV1bNJgK@n|5 zY`~ZZ#5-d^g5UqH^U;+_vZP{#Kb@$qEsX|c3A+=FGacjUN~^Y{ShS=lEVrU6UKd{V zdQ63p@u_wKdK_(|^K?rePVcrG@<k_e^ppcI#tr|Bl(=t+V`CJ>E5;(_mVfOzgLuH5 z>ft0d%<`gCxt4SEmV`Qaw6IJ5mVr@Eg@SD65ALf}m%OC&C(`1?P319|ARQgY_LM*q zN!N_!9T=X%X)d|K3XRV|tkEPSp4-vi8<}%so2M{F)MF(t`B>eLv9opi(@8PD`sTly z``VPfh0p8keO8lV2@zY(n;FY_<To^CI!XxZ*x!yGI;=?a!sGP&AGww8!i*Nns4$?C zx&Iege-#x67pQ@u!5u<y55e7?f#B{M+#xu@U4y&32X}XOcZb2<-3B`U>1li0`^wWS z)}Gm)@8x9n;WkAxnd%e{ug=Sim_Y4ri&Yx38ef;5W|%zht;Q42z(nhRISR=H|C0s( z4;c>~X(hpd*9#C^3ljc2x|;P0lp3}%3fVGDrbrH~3=9lbR#qe=Bt@b|o1u8hl9Hjt z#Z<$NFhOCfKl1Opd%zta90NH_-Lm|KZ_k3VF`5)Zf-*5CufeddZQ|bm;OZGG`@-CO z!fUpy{<?C1XU61ZbW<~^qgttd^O8oa(de%2KKyKfiszbm;ZGjyN=J~?CzPz!d-jiG zbe*@YKd8}#r|a*qotoWWknp$o&a+(muquzkQL-rB7QOp_4oPX<=kjjeCJ(AtW14DF z@N;CjFP?6p<6=cir(3yj2><!A3pK0YsbNM=JXjzzeI4z+yL8n%)Srr(47^5p|1(3) zGVQ+S{YQUgPXKZ&f0j*_7gc1_hRHb28>1y4hfgof8(Cb1iNiB6xjL8UTC0a^R_Y1; z6Bo{L##HLOw{Z??FE0C~wyEVZnk?HwwzfTe$H*qKSY%oQV)iHGAEQ`T9QUx2{70Dy z<PB!;G!sQ;nHOi7a7+0VSGeuWoJ3bEn+c0A#s`?nF~>7J)!sS7<?_Z$9Jo<3GwC1k zMf@rmuSF8LWuLKjg3uhW`9sau_(4U0J5&<k`B+Ge5U%V-A&+J$CUvpBHV$3nTu@rQ z|K!T%w}%sJjPT|H0+T<dJ!A_`vTj7tElHAk0TMDdUII;S9YCXu_HhIP!haMcr4X`C z%8P2>*g44L7??uzLqr||ZC|M_PX4T?GZ#Ij-}m}$spY@1CS7w1O4-#{$nMA|>Llr{ z&efZOYKq{RT!v)3tq)~&k+-I<`}qYYo(A`Mnbo@aD+GTmZ!f|c5dBf#o8=_G9NNp` z=0p@+@4~amxDqwjf)hll@@#gN>{F0O>sE@e`FB?lrzgHb|2z|=HRs~yaQ9|QTfgQy z36HC|&CI*(^_+lSjLv;aUaF}!usaKGuV~p1Au5I4w5lHn)y~ujUmlacgWF2R#>PUT zsoxwl>T7CBv>MBzqN1Kjb9V7Ax^2kg{EmKCG00p$KAPErL4?hr_~qp#VL^>BnA!dB zLFTNWu7n07iMax30BdYD!Hs{_gknl-T=xAq$H{MUGH|L+9=xc*xi6>*+Rn`FyQ{VE zgis^KY9YrALT&Bb{%&C#`N9`Qy66R!(DgQ~FT72+;1;1y!%X7PA`R;7Y}?%A!59`V zU?4h|-C;N><0GnGr14oZEGgIJRB0#L&neq$iSb$n;r{)Fe%wM{`;vZ~w><NNKVsR= zMYJ&s`Jr~zbgormQUj*#a7uLcUIad}KLcf3uzRS`vh@2rdLM|nX5R$x1w?X08_r&O z<C0A!3aHgRa{1n1+n&OoAE?ELrE`9g4y!$c3;^T?=S?<b`+M+437QPmi|<vkTe-l5 zo#29|gHN~P7eT2{s(eTS=XW-A7*{3S7@XM>S*z-)!I$J0hv4bGhxx-3(cKpI`Rb|| zq^*{Hf1AdyqFg%1${~!cfmgXMwCVo}wyb{tDtCcR7mzrDJGMuGlHXqTh9|o38mdWA z7wn!P@KrD$6X~ZpX;aaomXosh<}c61yv=HsGqCgUym&q0Uq&;}kR4N@H8Vt*wbtu{ zTXN`7*Hu;F<X~oh8DLPv?OB$gTP}ZeK_e|b`&#BoPi^^=?cPem!k|f{bZE$!1$XHj z{J&nD?-a%7YE)x2Ni-J!m2{$3eOe+NW`c<~hXj{wB>ffJodv5MM>NdENo>`AxFgGA z_CCu0)!p>MVy>&p0I(2+%AgO2@{qBXsFSvf<`u(c%rfxi1NRw%|0;3c5dAVUo84B+ z=u`(w<WMB%9bngNY45yjmI(}qrLB%Uj>7|Vu;Z}Q$MWJlaTfeuFU;XG8dH~D2~;Y+ z8E-W&v@9d<^eFF$-2bnN$8G$#WZ+q+{5Dt9;uk3)(cXXS4QBjNEc6TvogE#gi{&`@ z_+t~nPqJ1M6BE+%RKDw~h(C6>w-w9PEB*Yw@bU41H)R<A6(X$s7|i>O{IBQNlTLm9 z>wn4JaQ7@(8pJ%=p}2>5$H_SIKaoS(R}a|)Sy_`IRLr?F&JXO!o8h11Q}`Vdr4A$l zWOft0(H=Ls53`iNu6=@NJE!Hlpg&V;+;isNfAy|Nib~{*OxgflIvQMl_}u&OPElAj z*r`|ZDrne-C{5a^mFrZfzVwZ$q<X;w?y|7sB~<5~y%)A>+<3F&ljlv^tiWxts|g76 z9=WeAAw`x0&u&g^G=29)#vA%he{$rSG2(ZKuA5YtXnbQY^@L0a{zsW^g;@3dlM?Y; z_|_m91Ky^mc;yCCUG|pIMqsSaQ~o6x0R0z&TOu;iydjzIB;msA&g@T}iZF)8*~}jW z?>939(_Xce(!z&Qs_LNDZAwJD+_pJN9A2jitlfZ!UDIm24E`)r`!6Zmvcvqxb6r1A zKGq^RnN<Wfnn4*aDN0mOL#?gyf9<D3Jc$Fg^5@B7m#uH{UCH5OTnaw85P*7O37QMj zLDSmMT_K-*&qt*DfYX7_D_=MaCQR$Kr~_S+3)|~1C?ZRtoh~PBagE@MzdLAY$;O3A z#hquf)%_s9Ub}O+L-v!H?W!6A<P?94d4$fjPAedtvp&B%;P2DO8|y=$r^fbIN6~(J zk?>0Sr^;hPD*c8(fwDAVPRhc3#`ccTbE62atr$+T%g7H|w;g=lnNEZuSKmwYqc;`p z^UU_PkOg7l|2kXr;{kD1;@PtP6f)?X6#?qKV80i_O)(0c+gaFRcGhquKlPpqwSw)a zbqCGTYLbnwLy1P>Pu9mle3d$z45mU?nBG~YCUvb+PsJ!6L&ORLtK_lqN$-<|U}~rD z52ki5bZksJ|Gz>7Sb~fEWbha`?_FD4o1TvOg<fz;(#^5=1%uK|a#t_If=bMa#t2$e zQ${ADaUXHHL@Dq@X)>K7jR1l5ewlK+9$5^E`M++tV&v0j;C+cnK_YQxxzUNz>H;-F za?f+fF*+a0mdRW>X#~*I<ojoQ;6%^BPcx%Ja|;D$t@)+esF{0KdZ5U|W(Ypo4$tWl zlf>6}#5GJgnX9Ij!1Rl%Y2FAw4SSj4X7st?U%oejDV~HEut5w0e-9@a8?A{?<{93X zRW$z~vOYPtRS_(9aK!*3uIvo$`F%qD<3UoaYpu`7MWO}fwAL;ZDA9gCdl-eyBEyFP z7p^DsY|K<hn<PiDhq;zYhH5?N_EUjZGVeoG1LjLDR^P{+mpmNn^8L6wIx<|jh>r9~ zO=d2zy;UUcqdrR&CIa2~75d)zMk2)YzGYJw&Ll<(WB~~ghkoHK6s$)byJT|Bb;N#s zhRE2Kpwc~d`Veba0%CK(!L4ByF7(oIZNwjB*86ab{voT{-D6lNJlJyDIf_no!rbR^ zltx|a2rwq5^&Y8Ai88aB`Hqscs<ZeM`*7%J=fFc$?wa>_eaxt!xQCVLs8sNU@vl8y zfDHO+C)2qH=%OJ4rX2O4lHX5%I`=7bn2+E<+-*CaijzwuXU7hXQ2a{LsUu8)=J*Bo zB1ibQdi*RJ$)vC78N6oH*fH?KRHb>I@5<PW7n!m%7L;hpN5~ks&BN}w$Voog>-2`x zPvGBBm2e<d*Cy{Vt(HWx#Tx{{k;7g%-bho%D)wX%-C3SjUY|tYRN;kO9aS<VdiS($ zWBgN`B{-3D3<sm*+6uI>SU>Aapmix$J^B0_Vai&JY~Je5(|GE;sJ>s^l(b{kKV6Y3 zw8wUqQrlo0U0eN=(#p9t2dKG;MW6aPt>2YR>Jm15X?o;=Y`{fdK<%t4!wCVIKG5@? z%b*f-J`J84wHq_DR#??2aiQ$}KN|SHbNnH5GV426rgI<K3mxh%d$HCC!=fBZ?r?m5 zUI9kX(yt1eTC+hDzcs(po$l{rVqy-EkBWW}Aw<6qKvR(M00NDrqkF2$C43>4L=C6I z=cKnCJyZ!_g=^G5Rmvp>Hzd18(f)<RKF2tDPL52htTfaq+k0yX)=<0~=P4<cXvOMN zunZrCteoI%yOXHn<zn4vsa!4NT^C+9(=c4-+t7N!>R1DJbv|Lu*SPrFKoDI>{S(x( zEq}LYa1(=CakdxtgfpC(Bq)D+pHkpArNG)||G~2iHg{%^w&4$c*}-*(3yf!>$KF%u zUp|supF+DBCO?yHUt~kr%$9C0!8gmDg@f)0w9?Caf@7BzYt}A#1eNF7=?O-P4565a z?hQg&^Cr~pKtAS(Hb=YCohT5pZ5Op(qWwmAw#Rw74N1@g`X|r!=~~rv$xrPV1kF6y zMA>t}hY7%2Me0_v%$5IaQz>#UK(G;9p%={enWBs7)6tOqS0G_MZ;u@+Bu_Y(uM{Sq zaQ<f+{yt<N#Iie3o7A#PG{X%!sy~)I_U;EO5I-R()Tx3yy~`1RkJhpIN<sK#exrld z4`o{s{>ZE0)z1fqEhTddSbOKZ>-g@*<9W(6aeim-n=nB~>JCR>^0{!e$W8eJJ-2lj zRJWrBefURCFV__^q27DHedi6y;>xKhaMGcyEq`8ZCK8AJh+|S#1N89k{3vL~?uwGW zM|L>Wl6JWG;^!6JG3M07EiayET<@j)MYgNGg3ZxKnJyLkl|QO3xR5z%Vk=rDGh!|j z1z0UAW)sdAdNd#1ZYw>cv0B?LY}gTpZnK7HttdXVTJuR@DG>qRE_DS^NeeDKFnYXL zfgm{hBi24nQcI%C3K6o9@*~@V{*?g+a|cdHoawy@tmg*_kS(shpk3%B1fY&dkjuzR z_y3DTZbAy)^tHet%*Aqzr>7?z!9I-{GStwV?3d@~|D3`Q^#%;Mfjqw-@lOH7VL0Y+ zu(06Ycf>8SF<OKs_+hpdUpCM;<7$(!|HUJ1s{gm-aT1q_EcLYDmS9_aa+Yy|mwF6N zbkE1({T?+r)aq3^{r7krf8h<6c%xofGxLGIA-?%>LT)MGe<RV-;dfh6u1%cVoBJjY z>d$=3EZyA6G>@4F4&++>cu(0Rb|bPOE^sNjU#~S&xL(I<c>)~#VWzl7@v5JpM_C*W z&Vac{V@E$sKSR439@<Owg-YnJd1tr2;3P#y+2p*Chge+AJ!o4TaV)p2e8FTjU1LCQ zk4UZt8;sP)K6z6`Zs`dYpnf`rC=pKSb$Ozpw7r%#9KiYVyFqJlHz-?9gXNMikr3PR zWV$-P@z@!2Yg6o%;lAu``<!*cHY=_@=VbPzpTWM1Se`vdP;70!bph#_lf0How@VXe zHc#?#m=CSPb#S`D&Mqnh9?B>VFUlNYhIs`v4sjnD0NM)iR++iOJM9uaqe^wdqnk3I znkO6AC!yTi5z%=Kg@LQDq92%%r_ohWf|_}KRxjQzaBBYwKOtV3f$M>X6y4zsf=+w7 zxn{BL7@9u1J0u*Oh-Ol697~&FbA6=r8t*t-1}ik%ae-}V$JdG<<$w^teoGoX=Y4I* zir?dDi4Ijrxm->k8-WlHyhli^Y?uczApCnlQuJb9>FrKem_=52o@}LXGp?Le-7^iR zg=U>`J$0QR&n<MDzE}hwd~3wx2E<15X=B&d778mJQgLh}RS2JnzIbG7q~ZHki&dzo zcHvR`#q3S)X7r=ve0<$SWq}3TzIM5o+5>^Z?15V-&1Re<JEKp4tb2sM<Imo8OEjO_ z6XK<f;W9YfT3A+)>FGj9;j*y$7ci$&4q#Icm5!Wlq(ut{``CT6EFWOBU}a`!$F$|h z&=Lnv{n*vjg^i6JZg=h-5Z@5in;8tFrKJV-P3(tg)yk-?UlF+R0--YfPzIjK5B^Wa z81x|e-$n{}Lc=$j_=b`#vFNMu35VoFY@r_}JLmlFRwWjD)4_a^E-PSH=&F7}(If@- zt=2&>M*{R_?;e@gQ{npkOrP_-uP#f|33+}h*O%V1Q08i?h;v>7C{|g>U(LUQP0CJm zSDj}D>`$5+;LXd${}Wip%#PogVl*PW@Oij&>Nta}CE4g(Fr(Jibym(-d0olreOee~ zGri4DTPODEB(rYp%F5#9UgZjm$ZGEVM8$=ceTEMlRZ3Fl#~X<hx~izZ!Uzm*m(yZ! zMbh1zvGYbNmV4-2QY;?av^AO#qx^ctQTb$bdd|GGW>8tzs8IQS>g3`!{X->bvi_|n zixF-<>1()4ft%pP%9r^{1$ko+jD>&3c@393GNOOITGY6%w6rG>!lw)aoYCwq^TW?I zC<1|e(^CZa!O6t}ip?Csd;O*f`4_%zN4ivfvc`egAIXU(9Ws665-r!nGSP?cT7r-5 zOJRYR{f&|y(bCBo#*YHPy@Gpotd}XgW|DSPEHm<a>eeqbe--o%NSNQ(La;)vy}Oqa z+Og8hsy`iK8qAiCi2{K6Dzqau5NcVzmw3@;1}}`rb)meo%CCe3zxA!Yp;SY*eBlTW z*YS5@s@?x;sjAmzfku5z*jjn!ji#%Y`y%uESJfn)S4QX}(+<lsDUZ#W2g!nyKxOnl zcP`o(8HX3f+R--I)22KL=(T|#`z+~f)pcnVmE8l%#;#b4lf$k%JsvA_;@Z4=NmYa! zf7JyA7VVn<$noM&B3=oS)?T&jCp%(9`T(%6J9<7LG!XZ@fj;+0e>6qq=Utf*>IoI3 z8Ny_fXal1Dv+1DCE50V-=2)o_V<Iuo1r-=yo9NQl{^*&bErW@m_~09pi8((%hlGMk zLkM#w6N&^=N2)%rGO%r8q^zW*w37{zI#O>Sfg4~q0}q!T931TJsWe)uDTPBKiqt5H z`t`<z!;r)Lud7n?e@oP#K8|u)fL$NZ@Q|vMhphIzqW<!NsDxQzwNiW8*wT!TeGAf< zm&`9bwbXkrU&nhq#Yw4gy`G2R@qTQ8E)S3CMPiUc#8p(-&-oC052QOt?ru1aGyxjK zE~_6}g<gq=A6%&zsKs5Lv{_vTeleUQ4xmtVg*;wBo-?xQQFcC_Av;w#wvHVL9<+Nc zL*K>_YT14M`pn<Z7BQ>zy&V9q2k11bzOm?D9fh!eMjzgbJ_S4Uel+vS`W*28n04l! z@Exg6ft)Tbxx+>I=IF^UT&>D|**bfL4olHzIp=&vqSxk~;mZ5%!K#x>+52ar^eflM z`?p_NznmengVFG3I-?UelByb&)|A$rG(g0w-Gt&jxe*#FifZ0{9d>#X@1zAbPb%i~ z=#Th^>GS0@AWqQH@SfS`84uIw!x2&^*-rrHYVc(S2r1J-ZoxxycBz4HL{50kThwe@ zho90JS;6=Frqi7#+^`onR__iEewX+#c`T^Nn}DVC0B-<_hFWsWHzoaPm*U5k(eYw) z0;8eX^0|+C^AgiRqRcu#G-TL1*+zP(oP@t8FopXQb^NJ6<}uSc$Z=9J5H)_UN&NSm zXPzab{K(ZcWCm(q@1M&Jg4`K06PM^Rl0Eh7X%Pckp*=L10zV+z_WWy5^dx1S_WT3H zX;+9ocDhOanPX%NRKNK8soQ|Z+i=`lrnq@MQ}^IFm0J$|X5)KmP=%Y<`gadekSj+b z>aTL!Ij&5HA9&+eh8mEZa$dDYYiBzeif;~v5A@ufKc6HOXAH|4iha7d*pjg`Lx1k= zNJx_TsYWJ^-LlLp{Lhl;|6pscDm8aS`i6?<{#g*yEE#M9ZV~H52(A%CSTBUw%JOo` z{59r33tH578mV3P^ztz$+V9_c*4H!Kl^yVWVdY2FSUETvYigLexVTtYXhzfi_gw!! zZXqqp2dM}7Qq+nw?ie(H_5&+pVntHI%)r8cb{@VgzpF^9IWt*9X-|Nj<j8|xSfgvV z8CXY#0HuM|r2Y2Tj3EgK3KIFN!esI|CHhbyZ1WSX#uv(x$JY{5e4x)~?;u)%nHgbx zs^7T>;%uHvH~iM>u=j|}!tfh|<SEQEfX2xi^@^T34slAf+1wuJ;bUMVU))Xt3+b#p zOM|}OT}yTaN^Ug7S28!f&^V5V2YR@MH29J{!gELr<0*JaG-~i2=6^E?&$s;PEQ!&* zR0i@U#&q$ZtgUUDpz6?2iDEFRlaP9&9ko?nbo6G-U51IBbkLowUpx-Vy6sYu%jV+R z^gjGLV#+WX?a1#$=VZQLYoZg?|1Og1g<bIDdehX44GAbeO2p4}`9vo+sXh=DDsfee zn;C8srpS?PXxKT|XB1_6P`OrjGFmF>6>MeazzgI3nz`nM*k6#AOONVKw&_*zM2Oj8 z3qP#7IalsE7RKS0;5Py1mK45>78@77vaE@U+=YsyHP=1HAaU@(;IT#W4fT(<By0qb zV#k<28#vri&x6|7yqpJUJ|&$ZF<%dGl6P(o&P5iAL0s<)_Fab3jxiSf)+Oind(zXy zt!kbO+BDBWd`r>bOUmt60>+*NTaHzm^NawGU)S{Xw~XL3nhJmJ6}q%Y%+ct>VS(Y} z8=dfUv(2)#CD98KE<D899E@o!DB|#Xvfwg`-X2i1mh2g^dOkqbdb8H$K5&lEMSIUa z#Os=L82Nd1rufJwV^-Xh84&o^#b$WS|BM+&633zjE%^HX=M=(A3_p|POVBT@tgLKp zb*Wcsf&G=2Sa|9_@Om_%i-UvVw|>X${9XY&p6sF2OKu(>7&tgjaDd}VY2_XxwAbwS z?_c$1lexLy8Fl%G8KzkOU*{RDj(boa$H{(Rp>Gw6yj;D=70SKNg~nyG*d2<S1zT33 z;$sBZpy_v__OGpXwT2TfU-#3*9tcf(C><IrpOF_xAlniTS2`Z2Cu$#vWcvuk!S*1R zic^-HY_K%X+@>}3<!u_AHHoZvV#<4?s`6l+J)#Rt<X{iXy@%Kkv&uXlX!ksbbvY8B zJ1V{bV28}#Y+DxSi3FyRh!{I9aYL45t?*^h+@NyM=K9&ENOtbg8;K2PWu7C$XD?mq zJjpFLg?c<!u=*fNkX4iB3;dp7mSi4LJ5%PVp@^?`o`l*+7x&Yga7sTDhe1?=Cj?>9 z6EZsLuc&T|op<9+ohre@29l6YAoYgqo0bc<=PnVPo;}S5x%JK}=f2Ljg9TjwkK#P8 z%e1wMLiy?0{nCb(-84#oq8c4R?^R*Q@R@+{I#o&2X|VFNvvH~?%mi7nLvdZr8T!b{ z+i2V~O*~Yw$Cg;LYJ-CK+nM5(S0EvFbVm@>%N*K<Z86y?k8O8+lVf!)4bG$Sw-lm) zZgV%4YGYLFh(&rFG5(%<&$&7j<?CHyv+N+pnG>1G>mdvhZwET~OH4URLmT2=29hdS z5fW_Wk;u~K*;k4+Kv0tcZW=Mg(<FeT$Eojz=4$qxh_|CJlA2O4V&u2lvdO||fUA#> zg*;>Zice3hNec`)eHJ9Ezz*N_!G}p^cZkGv><e@EwGc!;%kssg;^JNFdYnD_IC0*C z4SPh0^`CI}1V^Ok+`S@mn*_u%6D*#N9&qc-sdMx+ZqPYri=X1$V$XRZGTln~pgN}z zq+O$)BWs>BZTtVhAewmS&p<FX_#Md;Ra|T?B|Ts;rmP(eR;8oO;|KVIOVJX@S%&S$ zldSm}7%HWcXnDA~pI={>5(MWNwqQ${t)!SS%G4{<-2yTw96gFu)XG$81VG>=V+u_S zv6Qm^%b6hu%yGnbQT!mnm$VBs@h~Z(0-Bf&c?8dC{C>y`*fbl^7c0h|6@SzobtQYb z;;3*@5<7xd+uEf0##yaI#qoLiD=15>{|LrX%)Lwu#*%u0k=EWl0;2gJNiIyM7>GTU z1F(P4b~WSU_QbdEM9#U-fZz3HvRxtyhuw2x0TJU*F6Wa$J5EVX9FUcP%fRt@`|a9Y zWB(PM9prR`dmjlmeIu}1qO59yfO~|gHubuK@=S>!NY%HU5@hE3ug+qxHQn8w-cJtQ zniOz{nFupZA@Np(4Pz!nN6k@><b|}IqRkC|?7QnTE@tk<nRDgE=4ugi|N8H53iBoG zshJdJIR2Df4fQ`C-b{$*j&tna7R^77a4~4=LF9Zt&5B1o6t1}0-B5u~%3(=g3IcQp z_7}c53Hr>8CqqK;{PobD)~X1%^cC@88nro}<4R2l<~hktZy$YNcCV&N`KM}3wQ8%6 z6GcPC@=kj`l!c7v)2Mb8+O_!u&bjST?u{<%b<>5wyZQCl<a1|w)MPfBh`SDE2){gs za$C3VK06>l(}dFSMIg1jDgq5A6A3ZvW&z0@zc({K(#Pi)mq?q$AqaZG((>sIeo}OO zITaK3!mor>*4@fh`yII-W0qXRBjaG&)nLw>%YE|V{VU2={u10hY$`F#!BL|xME~nD zyR-ZQUZnbFz4l`Z*LKMBNW0qyE(}7C^ZVgVu0W-?2d)Ow&N2orG3-1^j`qj3eDUIi zLoo|2@&{akSN74e0*soTTI1_Onqyv>vzjhnhr)V{_r{ZY(N{UvB*y}<LQ&nLm6SP- zn?smP{Qm+U2BxChzE%&RR2rAn75SZ=ojE!B_V&ywKTucJ*6_jm1jKv0yM5$gJQ#Q6 zH^O9WY;4&LqI)-@7KVnTOaA+qG9FH0Pahv2Q&UqDX`-ONq?+GlTwGm`1}N-~SOB!{ zY*oU?aX<gcRv|a3xfi|16J?<=ZlMpt(zN3ION_*1>A(p=7UPG*-4I8t#1x|@jQvrR z*njTmK|c1X3{GBC*qEy9IjV94j7E?no&KRc$N+WNlBE=gMv)&-9^~BF%%;e}8=-Ua z3*}v>+aYOGGbUnH%UUJ!p6vU~mcO$sDjZ~o-L*s3YosNv3j%5!TfFd5at=;%e<CR| zjiekLwRa9xUol@ZzSnO*pn50dZCZ~nk(F%P3|G*H9V>PM3HbdLC?Q#APgtB_F9BJ8 z>Vea;;Q`Y{_Qg>te1*LLxGj=dTGR)P?sCBH<pA}9bO=^LOb6sI7a#B3S?$Phx>Q1> zTP-Cf)T*oPcsMO|xpAY7Eg7a|7uuj@&(sSA+Z)2mRoNIstAqW&CO!swi!kus2{_*# zEPlb_GejKs-&0`OWJ`7QGT@-h8*UnFzXA8suy_s+TZL%beCc07(KjNOOlNMcrP}An z-Ng)A9od-v@@U&2^;d^3Aw63POlbveUpIYl8(zg<LdhQp$36u;8J1KzW)bU$J&TJS z-MjoX9a+oM6tm_SWok<})?9U(6pat1d)8`ykg;=0_L<S@w|=H=IuXt*OVj1L?&jS3 zgcmFGH#YhHuB|RdSA&BZDea5G*0r5x*H~}3zqR%nZ&hjiX;bONDxlkc8b~c<n<x&A zUnOxyZzb=vEpCt@(9mB|AAn@+P#4+$IvP<tVI*h)WjUOw*WqSV9A05f(=42*-GV|# z+Q-k(7juPT1;i6kfBx_zB4%{`RW8R!z&1WMK(>AX7XYe@AE&H=Y_zA?MeJRRLCNyg znM>XMdm;#$O(Y^6-+U@w+KTnfie1DO&o*Cn=-W2Gp!~vb5IlJs|2|H!l{ED{dpW8` zGEw4WmER8mS5_cLImbupew<=?|4AV2fsA@~!ZMlCBOv7Vr-;&P<U@y<3VoWzYeZfO znp>QF&o8zIydj&@O0yO5WjI15JoOVAd+H$EP?NaED2I;h|I*OG)dBTAM=+!1YJs6s zq)S$(Z>}()3j^g?Qp^_IHiV=OX|lsPIXSgp)U%^TGz*1ik6|!_Ytd5v{{FHtsq@Tg zMu>wf;11F5;uk_Ze0*B!M9qNRFKi68^aHDv6%{(Vx@l$(<W$?8EtNypH#fDlwKTs= z!IM;<6y*}(J5-ReF+s9Tk=IPfP5dGa&7u1uTXY_N_HcxX1NF0*O}mfa>}@Qm5%fpE z4=?$ca1n4dumbV~y*an$=S#2i=K#LxP`7#vxra%axj|X3#9Tx@N@4ZW8Nu-hfh4eK zakg5(?9}wi=ZIh9Q0YQW)zc~m3RmUmq}rb*crh6@B6uC+q%;?btL6+gAlsbaI}rYF z(MxL*(D%5XjNk3sivqj{BZC&ZTQq5{J%X+eh;xV}-Y2Dsb4Tbd<k~Z8&2E+wPY@{T zh8gS>v*CbPnWA&`0!{kMeuC!OCkC5^KY|IKh>-7u_O#0wF}_k?(V%y~0N!~XsXJ=? zjRRu8vrC?y-!XOU`!R~e4UrZ$-nIH`q~Lh*5F3F&+`{$f=SW2fj^dkfw1S?GT+id> z-c{e$RAkV->U;@LFUihF-bmwDIlVlOqo}N-t>2HxdVVsT>0MtIS4yk8eTMupGTL=E z_B|+Vxvee8(rokaWjuf)SsM0kC_uuM&R`qt%s)E`be%Bms{|(!A4Dob&SrDxR_ub| zyj4X?>&OKpD`rLW$#O;A7hKit^UF^rIoZwa4{a+p`>l)xRSjnju9EA+?QPhZw(pnX z^_e!CTN8W{q;cPKR=0q<X@oF{TE*tBaw=~v{?;G!CLPfd6O3lUXTgfkonJd{W1Eh; zB+LHVRQ^n2JdGU9U!#My-vs8#bC&F&MH$TqLSou4Es(|0D}YPP3{r)r&A;`Y6<llg zYa5;=P>$k18>XiJQN_NmqKaAEV$)7CO{K+z5rrQvy|uKWCpQYmppuAt2mbo7ONJ|K zov{P7QOOBF04ZIMw9IXmX|*i$*c%S{j{Nxg8S{l$g^2@TnM^&{?_KHBq70*_DYc6X zXo?mz)zvoTe~ElFelT5KAr|*~K5Fpe*xPA5o1@k*@A}zGAn(NC{)q2|kZ0N*%-fbF zEG;W5vk!(0uhw9Bu7J14&+DfOlK~fugvSxoWtGD7cfk@$?|(Tk@U*iThk(R?i{9Eb zkd4YtWvqdf<d42(YVIfK3ROAxf{cfE#G`Q=Vea`xtOM4;JW<;}k<qsSfi!Vnh8M~; zs(nDOga-Hn71Z3^sTj<?xA*rIN(Hcvl;BIS>)9YQj_j1?T3;+C$f$#9I&pe6&4U(s zykTx@Ypb`{-#xFil!k<ryGM>jD`B3_E4Gi-x?K8?J+do3Y>sJ2UwzkiKn1BvW;~M- zHP5-A-IBufCzzw-F#@=8_P{iX6-s4m#rYcI>L0F%H>DIT<<KiEtFa1(O4O;#LW660 z1aU##$R6|y@reg!C0{Y&rk`HtZrjwm<cC$pkbyAk>(;1~M~00~qE*u87SB<q{#yBL zEHQxin}5?yi6=={3{o3;56kltEC;9UuP?0J?5Fr^Vg>yGC&?tec=l&(+NajXbv;=^ z*Xq?8<H~HzCHfIpVgG3f_FbtpN8QF7*Vm$44=sOrJx)h58B8@XB?C^6&0*@3O8$6C zy(_~Mv=kk;4zplPxjVaNZ~rE=pN;A+Z6V2ag%q(>es(TR<HIqGVt-Nn<j&{O4X>!g z3Y1_iyC&=&AS?BH?})St3p|!5FAg_$bf#Lb<%VncYW{6beChh_?l9pR2ht+u>4bAs z-&gpB$gr7Y(v+sN{MZ(eqwnBwXDKLQ&#MJU5O5QIlu0}zE^MMR@9ytwPK`%NX|bN> zKatNdHtaHo5dJg6N<?O?)Vy`c`_SCX{k-vZUH}`S&pi>%N<tvOhz#(RvRXP?+DQ1` z&7*3L=s0{>J)12heyx7X{ZntfWNn`g0iMrKT}vXGefS@2XjzQagZ)2&K71o@9H$qA zLt}kQS$9_c6ujwYp`ZP4xu|sN0>Mesd4non*LJ|!g6q+^<X#IU+*WyDW}mvQf^Ejo zhEOr)iMxAq0KY3{lT={WXJ<O5XAAn&>#oI@rRDxY)SBXQI-T3*Hh|{V_Si$z@d`Ly z$1uS%x%p4GVew11>gX+MC>}1t@G!G4S~2@cJG<NxsmT{Dm!Le$=Ol0LdIk-J^7ME_ zG+(uUOumny!=eBFnT`(r0mmUFBqSc!cWqp}miqbvh%iG2M|S;iQ3=2Lh@8KC)4KUe zJ6wZivcr%3muXjM;HwyQPcde88M)&tA(mK-rny*HpJ3vu%>RVfdd2DL@pD8-RiMYf zi0`ijMNp`%3UMeth)P@S3*cLTW}9Dr!8?_GNK<`12Az200WeGLD_I!hXlXpRiF9G; z{lmk7j!{V{2Q4bR{c{5CyK5D3(#s)!Mj{BQp2X1b5p{xf6+eki1N)|r9@1-Mu=Z@{ z%M-Cs3~qpEou`o=g*<}2BRpw%o!d0BR4h5fBP(I`N<?DLUUveq_aDbfljn#YJeaVG zuQjWGWm~O@_Xqbj6h9t(cmQ*zwuMwTWEdE_>tkam>#qE(+OH7HLVo}Nd%*zD0mjuR z_u*~8hd^t^xfjtLFyEK(RABPKBjw`uQO?}2b#{gDUT);fi>#X=A;SUAVu$qKD4#E1 zFoTsre%<Eem4F&hhLLZ?1?iXFkGm*U_dsCtXo&LlnO!xGe%w~C3KoxAxPV8e*fKXG z$l?v2T~2)R$ej^Jtg4kK8-~Z$eYKG_g0~nf=MvQcS<fia1rzj0FVYgOQlf@rRSt(N zWW&lh?+|#bNxYHB{Ih@lw2iL5|CS5s`IGO#d2+?Ipzn@qKxR7d&FhPIw~fJ%bhF%k z6>gW+HA5G#dh?Pb8t>DfvMLe{E@R;=iSj8!EoffZ&d%o_MZkefZQN!=V~v2{Gh^l} zL)H^6#_iOK$KmLIpDB>6vi;5vqa}M&Md?uj#kwD+6z=Z-INFeQa;&4yu_-Sqs=hf~ zZjfDDw%LpT*r)xB_W>E@PuA64RSvImo5sJgTo2LoQM<1$U3|$qSvK(C$HcllkDcM6 z9t|c?GouC<6D%z48z8cN3m>g3xtX`E#7#Bkvu!y!ZKAhCxt(yHw{D`9?$s5dt#f!s zT`Dl|!CG6|Iu_^>X$xK@hxfQzeB$@-38`UcM-T235vEEsm5-Q8T~S%Y1rJrvvZ0$` zEB&>-D2c#;;8um3q#la7gq^?m$FXIH?4hGzx;tR&kUZv@$}CqNdEl{9n8ek7>Iv*Q zw#C_gN2Ijd0U?*w+pT%|0*m$0Pbd>?`||dfS%@m^woA&Y`Zh|Ca|%tFc1};r?EB82 zo@29;k_gWoSJvT+Ck-EE2)6<H9a3byBa-Obv%PqKU3W#gAoor9VXc-bMpgX2PF+eq zQ!~mVE1=$GBVm1nlPWw@Js%w_rS-1<ceiO*XO1O`{&%<8sQGKvHh>>#>-Vkuulk1s ziufJr8JRDMns{F1HA1vGKd(}OM)SS$JBUyC0NA3|0V^d-WwdYqbGG|MaR6TRJK)u1 zjEPONlXaeqGo__}#E|$7Y!OaG;nF8C^cXDnBV=Y~ZftC1W@W7wx3sieH{!FA3gv;L zdMmB=sq^;a!`$55_V}pv1%|Hu1}_y<By~T#I*bGBnT%aVSiDe%w{^UvOYVzHs67U# z>njB$#2UW`(inq3yT}Y#@I7}E_`#3hxgw@bqj_@=a!_&<6NIenM8p04=z_;`{f{HD zVo-sQ<J`#Wcf3oh1s1b48usWA@Iu}vG1oEvl5X!VRO%lXs4Fv6$S#O<y{Y^m!Hnz< z6+WoR`Jc{34bj1~g)&XXj4^^CQb&2%Z4wM7-Ey6dl~$XCC*RsfNDnmH*E=Em`;BIN zy)CCxpQ@_sWd*v}rY9f0Vat4yXosD`g%d;@<VRnKpCP_2@7Q263*e~vgp%zAnzVWL zIp4SIuTX=GCDr9S8~R*g3^-3<eqE_A3sjue9P#zAaV>W;11Y)2VZQ<LCzttuu-rlp zi4{zp_07m0N3BR#9-+8Vdm|6j_eW37$F~WJreMaNAfQaDID3-Ig$bt=&-E({>cGB4 zS$#r3u+5O8WRc_#-h^c6ZO<^oekhd@FYV)I+U6}uEF}3h3vwfQljKU(dpD+E8d@4< z>RYH#cUH#XDP#R+L4L%0>A&i&IMceDI_vHZOvbZ__5baj3PMe|WjRABxqba@K6~6c zP(tfC<aNSwYL`&6|ASUd_tcV)%!|ouqM3`Wb4>wsi7TBd%0;EL?~2L6K;CWBPRIe; zyg1Jn_MVD~Oz_E{)~Ru)^obVZNU_OwYOw?L+3n5l2$Zb3s6{b+1Z!ta_^#h0mjiQO z{Md**hGK6h%l<@K$9#CfsGdBJo`tr5kwA1T&?d!vV*tD)=O4jzz%Q)VxWMtEc)xmA zAIUeYW*Jeg8KvzE|Keooc(+AH4MZcTzo9RyubI3)Min6`!zET+^2)Egy+5@@w!^6^ zR!eY?t7CP2X3_%~X-s$h4XL?);s3Jge@8+1<g$bD{38mKl#+tePV}g8-WY^rM5R)y zOyQz(zPhqr^LcZ9y)Dv(Z(=uuz)dEDkut^~pot%t^-aduchG$mz?xE5Tf2jse7(HP zmZ@~CB45))VcvY}r|S*QyBbu6|5b+uoALyo+V`Php|Rth{_z!(x%;FcgSSxT`>nq! z(84&##r$4kbEUmB6+VKc1O){zK^0Uf)ME$PliPmaKbM&>e0Uzm3Dc?9@zed#@g9Uk z3nYSjL;CN!h9sQU3+z7+TnVfpFai#ohj=4uYtrM?Mi|=TKZ>67aYq?QdQqo-9k!om z#@IDEFVv*88i$}%%k-1k35Wl<$BE9(KUU(gc|Z_oZB-{$eLjtYPRq_D{>=g~>SOx! z@V$9jmW`A}xkq_GmMe*$A1ObfEVo^Z6q`|duYsE6^RZaEm^zNA@kZFBcl(!jCYMdG z(RiN4&wxBH&<FSkQ&3hvn}1PtjTaIvGbZlXl4N=~x&Nx_S+}&$48q&NpI1l)L%U6e zcWhLg=?lSz(2R5ZkMfJZH>fz>cCO}kWDERW`XEcf&9(we@9Eth&$^bM!8m+6aFc?o zR9I|vEL0dW^|ka!-Q9ihvTo7R3p4Ah-4ZS#5L}141AVTkHxLnZH7^vX13ijX`ZY^1 z+T)!7Tj_>eJu{_#*Ew3rajM*tSqAyt5E)#Yn5Bt7TLzLpx=`qH8M{9{Fg_-^P%|Ix zRq025N3<;^VP7!wf?v2xJCcAl%YTzQmgiT!s=T*yr~1C{-Fsa4#CO^M??H_fAPb9A zI+h1ciKL=FLAGFGE{xI=#s|#|dAjDr!-H3Ob;ey=<;AY!rus@sMy@YHituogdcL_Z zMJIN(C^KOQlJ_~x^_H#6uUdzHZ+Bk|0V2u!gS0g}1NO8}PHtz#z5@@`n=*75Qpk1t z#{e}AK<y|_GzSH|9rU-#=}B85B?f|_#`A|+ChFRPI~1}_7})vhM)SY*vz$bNTfN!Z zHM3hwU5n#6sVnaE3ylEHd9UvBoBYzd9Palv8+B|{em~u7SXLnVT*7Z7?zC+3@k)vO zyt2mSRnpSn3-9T&n<$1VS!D0T4*YD`vr#vNz>gQ>c7d!V#>%qWv@$2#j`?|{dBuW{ zBnS<q5T2^{O{L0Hq6;9Ssey)tQU@x<ueshEAUXax|3IJwEv^2>(P}~sk}|U4Bks8) zriRry_A|XFmCJ|M$mL)6Z|(T<{RrIIo0#qRE;^Zmo10m>7@nlj=Dvg0VQ{F!ce#gF zSS}x#alKHP!<1|c*_bQ!4tkX4=Z!052t*&4nJp6nW#lbRe>E@@bVq5fz_9QCB!%=1 zKftc*Mv1+Ls=Q-Zss9t05yEWfyeTvuxDC>v+QZSh-%NrsJnP*E-!Pa-zNtzD;SnCP zkXb5!^Bs%AJt&kAwyCWy$*`)ReM1`k@!6~63o+G)JTx#MT0!oJ{048v+?Q12YT(=3 z)xWryl;9vlIO-F!iRelAi0So@qH1*IEtHNK)t=n^=Kh|Yjm@}j(9@P^Nkylj*2|XZ zQJOxe*R)oOCrY#TRpFVbP{O(@{GUYMhpB}q?2)p`I}Tv?m9|UBO7nf3<4{~VB`z8{ zGKzkLI<@RmoZ~5O`VjkQo9BD8{E<eZ=N2J8YKT(_R?m01OEjg2;Wrl`)yu|It=qfu z(XaGz8RW>`?RDlD*+wSnKlHJBiu>sh)e^abDIt&#^FjoVZ-NYn-qD;2Ga!Lia)TR~ z2?x|1wTq!r>ex@|&bt`3Y6{#OpPwL?xY75U2nu5C_(*k{+$x#ULCeXR$z-2)8xUGW zyWflem*>6AOOcF@1d!~)I~vc5p=Kr(<k+7eQkfFjxW=+|stUJuS<vls`ujd+g7|9^ zfRfOJLt)jrGW?~D7qrVitb>mq=<-A{r7DO)lw-Vas=2JaS~3`1ld*ygSLQ|E5^?`~ z1(j(#3#phN8Z&nl>Gw<73mvn_?Tg~fBS+c2=H-^zUUP`S)=7u{F_Fjx5vc3s`iz2I zTA~u!izMb09A0=@1KhyAg4gJ;N*=p<I0@u{xxI9nrqWMqnr_V@_Lg2wgTETwXgc+K zyj~H2Ny|~LIVSB<)BUlYbB<b=9Ys*{ldmdgUZPN(MOV8!8HQGkN2kt_VL`nEE7BmQ zsnEU>xBH#@m}?Y*Nwb|~@`d-yt;lAJN5lsHfVQi{L_rB-5qwU8{@3E%bh72m{tvzt zqL@-wmNT-`tQNrWZ>5}&nN0U8x`bjaf(1es^{S@!^oQHD?)~T0tLhzxM9ZtUkE;9h zlGZqQmUI_m?1rRj%aQ?k>mYsY?qe?Q()k)(veoKw&OpoewGZB42;&Im15A7_0bswN zsj4yZF*3>~Qu+{qWPMJPkQ@b;dkhxnL8iwx+&d1pZ`UZbx_za*W*S{k+$_02dkmaR z@W%JVlAn+d?nL2ZbonJOFMmF;((2$*BoUx>Lplrx4PBF9NJZ&}_D1pOlc_`)ZY6oB z-6sdWS*j^8pH<#-iY1iqKzT9nUg((a?)u<w<90GbASEQl1G?w`$fI9X0&9{~hq?<o z$|b;9RG9Gz4K@Vt$9Kf9EI;UbKuNvxP)~m-e+IxxSxHbVMT!0l;t{IUYIGCFp{Q#@ zM)mrJP0PYfFPV|AgU$%WZTE5#H&aOtcvY?etRh{f9x;~>EE&7@NBd<VsSvu5oU7xW zo2Ek5w(m%y))4GUqDDk;nu&SM4qXP5t=`hd5@FAiZ8@eo)|zlqzF|JHo^wCnMmXO5 zdKB<VzWAPvK>Z>+M^*CQaE7X$>0lS~e@ItY8vH`6h{+K)ChK2&@f#El9>DI05j7j@ z&RrX<I4c`#nVR{U_DLz(=cbMP_vegr>`ndkMV|Y4iUq0QO*&N{iq2Gr1sK&2mZ1|Y zC&j`j;dc5Lf-1Nw)=)_oYT5>&Y&p_06K0Aw>}zQc)-^!$3@KHL3t^MH_OYU0nLAAM z?J|y>OM6YtTGmkKpHVB3Yr5wSk%Hyp3_qx+>&?2O$|rssSDeX%D=os<(3~pcOBhX9 z;@?|TU2nP1vjvyGaOKWtDU7E0Cv^NM9PKUM-&R<vbI>I93mbjlD{TrpAD5kR?Z4N* z-86K;ZN&in@FHs5(0#PSNSZL|J&{h?i&-37kQ;pcVGJ!6_V?2;;Jcy9+5)V(64t|g zM&~?}G7%$mkhVV{{D1ugtVTHFEj^>8oA1Bt1aVB?Y~BPUYX~6A_MMNzSNJxTjWsa_ zvhfMT`@nJCV3*ym@lq3S66ZZ(uzSO<JDr%@Zl<+IZeAracB1-S%*40KJOBytv)?(f zHnVf5)mo}!mUz8Lsrl-=-_3Tv6shZ3wNnP-PgJG^Q_98!U_bHu<-T$y$)%hs$XVY& z5)tRg;lI}zGWj;qFk^^R_u9Q?3~{C94N13VOIIvhr?^>m`t&<m`$mHl9Nq;Ui;ckQ zUdn6UUHQ5H?Rv_EKF;E3e5h8$5iWWR%$uQAXOsBD-`Qp6qvD3FVwOWjt*%6YqPIzr zOzpG;c9i7ALb+<9lclH0yOi^x+P4<Mz=W{5HzXhG_^q4;W{SI`arobVY7?$7Jb9O! zDV!RfI4`ngVZ9qoqQUQJ7tv0><^z+7&#O~sYPbv(DC+9#cdMp6U4+i{Qps5!Zf<YC zb^YB$f5Us!*rn&AHj|MJ=1%*ryh|HRM8rnxBA4k0;OG1CDCw14eeA}$Q`e&C5-%IW zU8@P$eeRz5%qfrvFTIZVUZ)W%jl3isTKV-q7ejiEjI<T`EBK3Bdw=XGd0)c6&C-*P zWeT5&%+`X6jE-#`jOK1|?ZgQG6{8>?A~;t%5*+HVv%6B@ZG#UbE`_J&rG|qp-U)DP z2;HK@{0f0?X76W=n;H2;*bkKoMaXo&?^gSj0uf6Q^PUHDEVRamsYmVW-*5oZkze2U zj!y-Hq!smZBJPP3_v?B(L-~G#s~!x7;re0&oPO)1V*5NnK6um`q-_<ii^2O)5PU`! zMm?Ni!XIRe?~kJNK>*D0Bk0U{sB?=ImfGfBXu{Djo-}w#L~y1&Y)~z!z+|%<K2yma zKiDEA-hWQSgr@bYnpqNb3(R=#(9yQb3zv4S@`jb$o?l^Z-M5>Kfec!^x$1J~N(Obk zYo9NcO}VQu6Z#>F%T^h#M#mejSt;i1>xtNPcZLxtXhTz8fG5oNY?1OBNwgR2)|al| zxd+1wwiL_Mw14QwoTs1~Uk0C|?&nU6{A_Hi93d<oerfrxJ`$B36nOX;#=JdKUQbv6 z*XIftP!8WZle*Rp)1!D#N*uZWZH{RhFHwS@pVVUFS$_(=FDqQLD{Pi~lpEwfv_wHu zcz^V17f9)jkjN;ucp%gzF|bB<$?ki|(PK=uNu}ajQFfj@#IWe3ng;FGpT?nORdpe7 zzjUpum+&w#*JTLlsbsMJ({@fv&P3U~Ut2PKTA7OZX1k~P?XW9FQ@G!0VJu)hgumJ= z%*Cxc#2g~?7Rh?cJj82+M8gm7B{th8d>Yv&M(b+k8iiLk#4{qpq^nJYJzWqkYIUAd z-D97Bn+y^tV@GK3=AY~NEP$vb673FPs!7sIRaL!W7?Q{nk5HkTBDGjCUCv=zt?s_~ zpk0S)6>9w@;-@d*2RT&l)%0aC3rGf&cQpGz-JzYO;|XhqaTQEiFl7b3-}6s#S3K#< zatba!YEG$wFh(jdg~~;ejmiwSu1EK543{E<#nU)5GTIifb#T^HWA=$9-3*J}ovxFt zUC2eL()xK{>I%Xx2l0=dNKrYLbx70QH}7R0!RXfZy$YwdYOMJJ{(H|Lq;X)ed?3Q6 zn$qZUffLbz8!O;a_3VD^rrL<CmKFu&5{uWQ?+kB9M_6(E+JjVqL6uQ+K8_~PFt<Ii z1S+o7Uv_;a)LZ68*ZHy`{|>48hsSMB!2H|uGrUHBv}7#qj=kG7e=rDbxW3%bZWPL2 zr7pu1ICz-?l^LwS0=Mht;&cvNnGHkY->QGwlM#5-$c!9BBso4j9Qp`9!OS`6I4>3T z>r7TWQRw}bGEWL$^YyPb_3sj<zatMgcQPlWrxXL~@U&y<$jR!&Z}9MZ^$oWcYOHp( z8@>`SGi2%w<l!*mbc){s;HdlfgWSG^>Oa#R$HB9SrdDIQjp57_Our&$bF>2QYIghw zL=q+Nmlai&p>e_3nR19(#7Uh|9@=fXKdG0c!~Ayz7S$fWilQV~N22sc$I<LKYpWxC zD09mAR~EwUGhB4+e<{!sw|WCev^3<7zxv=S&`AFHp&bl<@C-O(QJL9GFNOE^tx^gL z1aiC-iaKy5^k-`36-xGp<Rj{s25<ijKdl$A#zP-v$)D+7Opr0$L4+q73yzl&2>*%K z<Nk@@QMlqugXu2Tj}@4-YqlddCvQ)-dl3Ufap*0|wo+&e2d{wPdO@g(^g{+PK3U-a zTgNB03i8W7oT{dsPY@2WJNv~a-B-EsT<mrp@wb?^Kb5s8<|5^tJ~WS0NdJQL3YG{K zykT-0tPjN>-RDwxEe_n*TxJhZyx3;B&?nb}?A8OT5N=cSnFOyA!tllHr)W#O$n&>e zuLt4geY+ENKW9TI{j{6zU4BdxHh4w1qFX3FZD;D?0bVz(Qs_ZtKpMDSyNFld^rxZ5 zX&%fpQ;fSn+1g=So6Nga4*BrOMNa>ncb*D5f0}ti`pOk_@@0x%@}}&^O)RBC;lWp; zJs^l)J?hkZt#;};`OTJBucOLwFIalR<|1|7gUiU`!GCHZ=yp3*-{gid2UX9e?cgyS z*=@u9jG{Z?SUnUUW^TM_)ncyt@{I8kD{2be0wad^YUd`8nHlN-;Od*AE9=5#W81bm zws&l+lMXw!ZQJPBwr#uPq+{E*?*7j><K8ju+j?40>szyCRee>YcFNC`_nE_kSAh~a zR`FCm0n==<9i^P4aK-}X2cS(?sF+=6!r2%RRBMHO3`~6NmF8lgBmS>42Ho^ZvylNn zhZsZ?^d-xAkBwH9Ggl0+f?fI#AJ|~nEZv?5{ML?V=4YBUzvs4hhS>{@JI$rfo~EKj zGQ@jEvX!q5_Zd1PtK7<kuaz|J#VLO?0lXg3-+f%AV}&SNujY4nf+K-d>T$o}a%0V? z^oFwV<6on%dD-~&4-fS$$}-cpzgdv1UvXHFO`Vg~ekUs6;W7h&^#Oc6t*e47wk}Km zCbfq#R{=>Ub9Gi_t6v{0lq8#~S`F1kJu|7NOeB_y#^tr8CS=_$x@WBenzuPVR9>=3 z-{RlLsuvxr0d?Cu%t52sIH86haNp!E7lMWuw_T~;=fr}EKZl}l1dJ`J{FQ<Rbs(Tu zR2>kmSAqYM;DM^Yz&Rt0KTIX2l--?=68()dO&6_1N`pl!iQBYCPlkO>2W$xskpqS% zh9<VRokmfnU{caOmcIQ-C5m`P_XSf<JYgYF_kU;6i11=?Gely$Jysqvmg4tgAR5Br zk01wDkMQt4W9B%&;*pV%<e5ySY<9T3A7$FTJzsB^D(2SccD7h9MN-~S1{%U0z_Fzf zMW9jI9Jn5wWA+@uARt(8b$Pr$UGk016-lGVqFS{ZI>S<mOZ>}ayW^0F!Q*)87?MWn zvD_7{zo`sIO)#tuDFvweFJX0O4T`WpHS*fo+4=eT)xiJOy&Xo(42&|ecQE`e)#v!d zZAFHp$pUqJIQgRnd$jIa|Mjjy7G>B643$ZR775pI0=ouySN?HPq7)IO3V~rJC<!@F z4w+0({Ywh?P*1Dr3*0S~h!Y4ZqWnIV7ynrxZ~V4d2LJeh%y|oEw@x?ZIp2Nt&RpQJ zH-~8MCF;q(az%(&T(FgAbslHLyO0fvU%o|4CAWE{PonS1#!Eveco1YcbL$t^=Zp{= zbeLrXs#&J<>lXldT0F1WAP0GtlITrzpu$D)TlCL^fgckUBfLV3dq{@n4TDf};quvK zc$zDjji;RQ=L1;W1zBO?GH;jI`7zF)$dJ@I+5<HhLZUf{phD&Am<M*nUbX1$NAs<U zAwsi;_fO}GWs`E~xcu^O-&{}V(V+s13^8s3&A~;koP^p@J;p3=ZLMpEX$d8yHNnBN z(z10=*=ycR-!qSalB-}!xy&t$mxDt$kTe_?yAx1nXx@5kZNDGvxc{c&ppm0b$FlYb zKiGCNL8*j<nP%TeJtYhWq~jl*8!|r@Fr9sWtsFHw`&CP_@|OBrR^Pcp#EqIeBNGz) zpKj)5{_=(Dof5~arj&=G{wFVV=r)g^xX~w8ItJkCot8W${MXg&4SM%`@r@hmB24(Z zdNWr>R<-}yz=M&>{y9dtT%7b8-ur&{z0KU5`^eR|zUZgtC<_ym?m%?w$(z`G-8(tN zzqZBYlaac$Wv(2dFz&XZ{-jqW&I}d<$gYOSH2hbyylVgrE|U%`^gdVDYF2CoddpXQ zbnYH%+lTeo-MyaGjGIqvzasPDSXecmL4LdH&vWZ3(y|B9s{yk%oRIEVhtVvwGbmg2 z)1D3sGLfX&cdF?3-24g2^0SD4+Or4GUbM+aC@vHghIZE{M~CO9*eB=IuXH^s$$U9} z`E6W&P*+>PY~Q^-8G^`3t)4z~5sbn3Y~%4d!<iR~oYOzy1{U-In}6c}f`(A-oyB&i zgrkDSq5{9x@%c&E5F~_rgWG=Wz<XMHCEx$x_5U;%2SKKc3IM|n@E@cg#M0g?MPPv{ zEtSw-Ke=!OH~kaBt*BCt2se3H`ozQKx&{h4(!=?(VlXrUP9J}{Zl|kUB6qP;#Q9&g z0-BKiqM^;rZlJX~OXY@^G@nAN)pp8)n-U&%ALuE^MQ^^^>~wO-if%+E;EsPr5RVq2 zLt^gUM+?D=P6W>h<8mq_0(d@LZEEY8_J$(jH=uHN<DC6BpYmxjEZJxsEJ^#(Rrm|2 zoIe(*V$HN~Nu3B|cO`bwctX3;O3iBfId??`CJkcg%W<fWBzBFn>f88vxI_0bHS`Hk zilZ9+BK-o1K3yXG;IUNdAEZuHIjb?+e^sIZt9pB6hO}XC0#?+1O6mSg`n#WsQB#50 zIdMJSlYZifvQ01?>=_}*C3{8`QE@s;=fAHC5!1ur$MhyqxIm~h=9rvUoK&N)W}SZ@ zQAX^Z<;8G~1sx}Mdb!lQ;eQ^y@4`mnP^fb%X@i&}e80SyLB8)JF`|y^R(%hC>eN_6 zTx_SgV%@dy0huAd_^|5Zb2FUUn<Yo=2Q6HCzi~gyTpj=RC9{e3w=25&c(&^b)^Clk zhO}($&VXgUGslZS=G$U<KiOc_siqfM*Zu&9d7t-RZisfFje7OJxNz~H<+23$WXYLI z%2LFRC*O<gf!PP^xIpjgILK~NpHyE7G3EDJd8gj)RiB5st4>2n@O)h2bHA~g%uiAZ zy3*<OxGC1gOjCcXEprca^?oz$2S2UTV`z4|oRpFI2^uZmkbe?$4d$1pZoRqLd>y}K zW=P#KKQI7ya2rR%!3v7SXN?lM2EL86x40YWCv7u@mR94gT$(mNIdr(~h<vl-B1)C1 z^*pD?@5%YMNKXpIx-3l!w&)NbAC|?G$Luz1220-O=CCPj)kF)FUaRn3a<zOmritQa z-$8xb!l$drV?(^T_cJ*fb=S_ie|=zJaCeX6N4Evlr0lX0TyfdC+=huoB%d80uCmh6 zie0AWQ5A|hDt$A&@q;X70gl~1T2A((wLRDb3>^jD0N*Pd)phHQ1O3Q%@1tFhzua!$ zfdw;&_p$po4AyP%)#EdN%qS3|`f5a1&N3Q?0WPn42yJj@-R*7|JrRA^wZa^+?3?~? z?~x<+U2|duPk6LQh-X}vT>9qMU*PYL#C=~ewdX7M_REKWXJZ!rZ}ebrY@(oNZ_?3+ z@OS=P!^ENe@Y;oy`|xw)dYK`jL=#6(q?<ILDvLb4kB9)o*>Wu5+<hLyq}L$=Rhi*x zI@h0&!9t{6Sv2LzWg*-jD)xH2DRdCPP%6ZK6$J>x`T@YcVwgIJD~(~a$;iZH6)DCD zzhI&ted4q-hahg6HJF8thZFq1X&yK6MtW!{D1Ad^Kr>RL35AA+1`&Q1B{OrKMy;Nl zjJr2$+Qtp(eR7T?OhrFMxz%z_e}BI<Q$6p1Rz$;#VKHzELr#XfmV`wFM${eyb=<MT z<$Q#`I^%<@0FK$fu--c|iG>^cT6{#YPXyy3JcdyzF{G{xi$SZdB60|ro@_Wz4rj>K zzXm7jgQTD&`n8UTWY0<^abe4?_h%qM$3fr#f?&o=R#vu!NV0)?PxMHUKDRp=m@XS; zb3m-W8!f`sf=LXQJ5X={`Bk~gt+E>g@g*|zT?sTM>RA6IePW8f!B#pjtp3U-Dj#p% z6CKVpeF?@WFRD^ZY245#iRsUOLoQj0y_#jPJXQJ7dl&w&c7CNQe|Axu@pr=W?u|<G zfr}v;IAjRS*;}?|Cv5sY_-XAI(O%1P0JTQhmreaB_u)vWMTq^+M|0;EH6}OD3SrCv zU$fQ$cBSQo1ZqPlDYYy?cMPF?0q`pZ!1o~al?CIh>FqO7zkIK7@Z~H^2E7FO?CtCe zk=bYBqN{!ljE<2<l7BzCT){%NSu(BF@#nE(HrKFieLuP5KQ1lepLvDu*dD)lD688v zik9>L9mFA!UnxN$<t_5;n~_D-ooU}%H=L=H`}f(0q}pp~>hI+}Opguc7xV7)L0JLs zJ6TL=Eultm$+f_X@5fF~=5?y>;s@dyKh%^TMdpq3hy(W`kDU6sUsnW_#XO?Gv55Oo zV21pe4<fjBZdW@2DwlAwM&g|5&(A4!EqH1KsSjT<<H{eYcoav?kql{H>xGDgzcrL~ zt%{n(CH;1TU2q(50R#H4g&!eVy_<#Nx9pdg^1#^pboOJHW3kf_g6cRM2k4}kf&Jqs z#I1pnvOZjxzrwYnIB2oysOC$jceP(`GtkD{uEJIDjIW1Gma%yOB&|V!A~!)sLSuK! z2D5`9{CPTLOV-1QR}vf*eXO!qiX#J`Bw?&1)2T_Kmdnd$x4Cc4Ew?-Bq0Al+{JVT+ z3gl+NyvxR}pSWdg7eYw^%O9Z|ET5DiSVKHLLfO<fenf<P;<2_^-3It;R0U5y(J(<C zl`%<7hNo=t_bs5iCoQ1HpYL4Rwie3wXaD+jJ0DMGVk@{hrN$LoEEYmPIp5)2sWt*u z8N#POc(`NoBngfLX1*#+r!ofE8V3z>h7#!e$HyZe8~6<UhRt|#vN1=Q)6nX#_f#+9 zJ!YI`@Nn;j?Lzp_z5<>Hd?J{0(Ud4qb_F5nREdaxqEX7CT4E4;lXBOlF-^cK*Ba&@ z0<DP3p@wyRcPpjb58p#)bH_78$q?GYpmWvfn@(=ekB=t*1_-41MMoD}{tKgH#s+46 zdI445oX9i)a~O(upr-Qu(NwzZEyN7@D9~Lf{Sz3C1Z4O;3|r=kWwECzq4M?d>9cT= zsdp|Mkrv`Cl#ZvfH5CdaVlp^w*78N6u_kY`vLoQbL`6l10rdY;E{8jQoFqt%SU_|d z!srd}_`|U6?sL*vIHMkQXJ+D0qW;iCqBadc#ADY78-@I|Sf}ZeFwz+42^uWW^Bw~w z%>oAs)swa%gMXp80m}nhTR9<_85s?l+)-_5Mo@!Wk?n;#eB;^?KYlN!_M;t`$e@IE zVIzeP66_4_E#&3{?ZtdUy)<PH`lSE49`P|+OsavjA||k^ohCtTy7vUt&4dGqwj5Wb z7@!-QZRxqcZ%qFbgR{hKczJV?{WY`v3fOE#(%as&#g9^8DdReL>sl~RgxF3s_a)x` zEq;w8*>i1w<Ul%ROSVc+)!Gc$XQsicWbALcx(-S@WYVgt|8vn=xzx>k&8%)W6dW^y zuj9Lyo@4aMGP+y%5WrT#DjdXU!yB6Kq-sj|Bg>xTxs(rhu5WJl^QrDBW-{)qGa58+ zq!4cf0IY6pMo+SP4e#wplF|jg{4PErbug#a1!I{49q?gX-J&8QA_@%M+}yS}X$Ya< zuv&0dHfd;}3P>WQV8f-{xQ?^VzjLzp6YwAJNxi>%-#vPIeowOU@i|R#G&<?tZ>{ol z5?SBIsH;ymDB@<Qw`LN!5a256-WdlO7QgEy9>phFqQ@y97vc3sxO|Xfw^7<XCL={n z<dFKtR@<qluV-Z$+%7uat@1!!r$R0)j%{d_lvZY}2Jk$NO)r2vCd~FhXjYCU1bXOu z?APK8syw0|uRpt!EjDD|M|h5?uJc=FkLuY01mhWXs7sxkU#K2`VbCvjHcdpfq#s;z zMy;5AO`oDSxA-)T(P{h5tcz0RBE~pzUgRx#QH~&+ceBZJi-|y*<)39960vjm2VY@B z4yyI@D>ExplqnuQpwZ>rRQnDzkB^j!X!vAfSZ2yz4(Glx-IbO^5!zfY5D=D%UJ3$E z6Zi8deHLZ+HrUQrcK9<JDcF6<7Q6j!k!&u$Y!4S(*+f_WsyY>fieWlZAfj1#)5tp& z7w0K4JY6-VXc9?l;|dif6_Kkn%*r&bS|vI1n$$u5!aHRr%Za6&ozUG{k1kBr1O^;a zOyN`{$#3qBoxsLqKN;L?w9@I8OVe}6mEaOBdTeIa(B<YLP`d;jRNyyO+a|32hSvUW zZjYRmEqxA7Z#<&U;PPX+qU)V%89a2<0I5yfR>lD7aBH>Qv=@Z|CdF`*g_uF@RPE%s zcST0R(Pw*6BO)Ri_m{^K@)f|e@m(aqkK4nK-VdND*A$qGgZ!wMY=^n=uqC?By$vJ6 zM4LTx<G=t3ptK<NIPqfwh)9EEfcRj5KDdK`KKLqF_3`w@yma6W73MG_#}k2!%&L8? z2`U8821wjk;G+;yi27idLM;R)i{RnRv^nhe)iB?X6Itjx#?N+pJ>#;OlJJ4>kV{1S z?*?#@;6?@|2Lhb0HgIpbqsa8X7fKbwged&)Kn{X#g<up&5y#N2)0jBHlpuSaU`CLs z!ayKsp^UaBUm^XEf}jxh{)B@Y#1}=NQ{TZ-)UW!&Qux~ooCh(pOQMs4?1HSN2p&nE z8+=G0EDB)?@$MSVB1wS=4lfANWetP~ojW|*7lyj4VGU>+7&>qt7=VQFAN6`>eOEq6 z1)u@%_<27CJR$IgQjFkbif1ie*f<=hYi6-T4<R_BB1Y}x+@iEa%{skTcwa7GJuGH2 zCAUscJPvqmyv5MXe0ppp8%w=;oufYIeedb;m>;C$DoR7udAc3`Xe7ms=6DytCh3^P z-Px6S7uMUCOHLK?W>3rK;8UnIS}q-K^zbzupjP`y{;O#^5&qbLup~>UFg>a`uA6a0 zj3wR2X7|+;>ZR1vzM7LUYiTl%6`VpSY6orNj>mePoz`e_sS=$v@N@{N*(yXwGQQ37 zX>!rwZdNQ7z}2(@n}65ZxawH&P+)!^Pm@Sd;|jonQc6x3Md&IQ)>oODNw^m*s=c4U ztg2No&NV7TYQHdQ4KgZ!JaA%@<EIv@L*7Pmj;u0uwc@DfVWu!oqB~DbpA_iq{QmT( z!GlQuT5Oyd?$5S`Z?;i?Q_gj^%wRapn)02u%a94ZK6Qp*@KZ?Yot=frz!0ts8XMto zs^09>^SYXOl*{_0^pfF@i7UX(Z(>XMOE~5o<t&CdDt*ZRrtyHWNL1rWy{UATEuVqQ z&YY3bO`bo#scyQ<A*TobNe}g!Xnzu8e-fnsSllJ-JY!<;N!=Fx>uu+SP^*dCez>db z=Y7F<4q=av=T3`<0l*93cb|~~hg8T8X7=~f_${`3v6GS|bTQgzE4afiU%RKtTB}87 z*vkreHu2u0Y_5*tEIFBthCIk8jgk)<u{aryHp1~Ucr&NDm1hHnR2H0xZ9h&m_ATZq ziE}2;HKFMHk299Hb<c=T8uF4t@x<yPS)#<7^190|9^L-L+3>ku5xQCV&+<<RCtLRF zS%asx*L#O!?y#xmdp=(GY8IoBn{}Rt-4DhBkR6*HuU%u5P>p^YeDBo2J%5D$Sd{HD zWpZ~?kl3iw-BzdgI0HyVJS6DTU0sJV62$ljh_Pt^+LI1?i28=~k>DfUN4{hTMAMrt zBBYSM^qM5m+i&4G-#2@CmRLi5C_>OMkfc74+VXN(LkN;+mYi19?ZE<la3$=EFgnCL zcH=RW6^dx5i<SC1N-;;<A@m!7WB-=ET4X)$CcIX&<r3UTRoXr-w|!oqOTHLLOcXO7 zBxiYHVc`yAp=2DC_`Wxi;rqiW_;m0~I-6MmR(usR?KE>;m^wegjVeJ`AvqKS2okhB ziP=CftWxxhR=$#rjg12OH+UZGFN`c0JS>AN%|1sZ6W{9)DRz<<6mK{kWQF{aGHew? z9H<w?S0$^miG57G0?>r))Bztj#R$<0)HncB>Zm>w?IZe!glExgMX-PTwp85gT9<qz zw78ymaxT$0=+aBcOPt^X358m@vESn1iAd><i$`d&!u9#pqrRc-15L*UqxEU<OzF(R zheFN~xKS%2a<`!(Fz6Rf*Ujo*JA287jh|}9?1Mv)utqEIT#%6GeM-s+h23Rlx<ls3 zmy4ku;V2iU^C!w>TUIMYcnP#Dg1{_9Sh${rT4s?;cm-N=(nQ8c0`r@Btw|3!mM>8o zP1`c7U1RE^=VT||Iq?#!cO6HnPxlaaX7qA<uI^5&`(703y{@*MceUxAqc@Djs7for zy!3?5agxB|UH$Bgc`?(YTnW|Q%{F=Z*O%B*EB^_e0-*QEh0SwC<9d99X^|^H%dDO$ zkK@mT^M3hM@cn|EkBiYN)4HUX3eSBQ$5gI0n&06TWs-9eD^`CLq1PN^h?cB{IoPE` zF(W|H?dp(*eS_~1{t;SGw%9_duu_mQEt*Z*B^5mU4;9WYBE;AvP4}ZJ?l0F$4b$#@ zq{01iFW%<yLfcbzw&)S!*R_hna#YLZYVFXepN^M$`$<aAM`Kc!nZlR%=1LH-F}1MG z#O9}^@ELsXkSfm*Ewo*3{IFhwYOUhuf8hljgQ=LhzR3KMw(|xxPG7_uI>p|R=B$t% z9}5Hk1XRt4=DN$mCyjQ&y+uxHuJ36V2@dR>fuGK{CGbmC?nCZMwru_7RcD*cdKYZn z0Jhb4462cNtb!j2?7Vo3v$`wS3>S|k)-!ROd?wnP@{R}v9?)A=H`5E@Gjn2w*z-D1 zwtv0OFvOQs%Ovoc<BA$2wtTRH5p!}Wn%cRq_;n!wX!Nu&HZEQW8GIg313d8dGu)Pc zPj2@|2UTw~<zDRF#oh7UVYkx#AQX0~(8p(Y+t~uRLL~!}#Bj*LK43xIB1IwE%=VGz z^z-e>Z#3*p>U6ki+Bh&u>vYB>4X>h5)FD71UP%2NQIBqW0|$~)322lVA986iF~=q) zW46KCXVJj5K5Ih3Na`pq$&o*=izR7b3GooXhkDIsaz4c#zMrlnfl$DnJO^zmc*uLk zj;U>AC5Zjzak0$-m%|c63WV%cQyh9P>=m2<1xAa_XawOPBshUw@{U@y3)UWs0Ulp9 z*a6F=|0@B9Q3#kcx&0=jIDCOxDp_~)VS-7c0a`;U80Ct?tPesV#2uU`+~Ir*)-nW` z{tpL?C}D-|kqNW-b0PJa#kunnAb!BCK`THrAiUyO&3Q`srvVv(Jc%26DR9N$=#?P0 z-AH>|XwtII0z_dkk|bFP2dNTs$_r4b!5psCJq$1qu-CzF^amKjdL~YiB7b#CVc1jD zKDv-kH_u>+fnpT1=%H0Ig78#{4>jKRK?dhT6|Y(WmalhDe_!t>M@MTM?@sBW1!LYN zwmrSZHml1d9i+J;#+n(dx#35OhjqTyB!uhvOLXHodTSNHvG~;@U96}0>?}yecO=x` zC$=l%4w1H|$_?^f`G*@?+_r`=^PqjFR`>A|!N`l`zeHF1m2|8{DIV<nfhmAe*n3g+ zI0Oy?oNnhjzuMOsH|kmSf>*KZg$Bu?xhst(->A_NL^~w@vBtmplZKq(QASNk3lgIy zc284;#(TdiYEQN7&Qky85HFEi(i=_2cLpo>GO0ODerhHWK)JRTeTO>t)<N#ONJC)( zqlaAYrXogip@&u2eiX_Z6_kzA&JfW7)X@>6lTY})?P!a)q%XKW^wlmMSCRMB-&D!7 z+3>(?VHglJe2ab<G@<0!h6}(Tj_GJzKb-EeQzf!5SQwKLx+d4~oNx-tHGo-k;7!Aj zRI{Ju2ru*oV&i2T#23TcoIM)&W#TaOw<{OAIekjg#lDRs&fdo>?OR77)rL@E2iLrZ zSoOs0J8?Lc+i<!}o8Gx~<qx`AEJzTqbKk4yu2F$otstrMZ7Y5nmcE&twer>-dZ!$* zQs=)W^b%UwgSf=VpkCDC90WSzrc|^jmbtd6H5WdanZLFTwG3>c2BD?AH=GvdNMD4g ztOHKl;D64p2(IwU)V<IUcx*Ey19aB+<mvPdqF+SF1<lrnXUEv=JcmqOV@j5o%5R~b zWAm+f>lDyjUgaLSJma#?58L8wwUd<Idz5D8uD~|=MO_xX6!G{xzN$R#j~UYhd`#C{ zE_aY$3&6PRQOPCx?rExWo-L8YXsZf=6j@}az*XK(HV}qq?-=ZO?<m^C^u0SgfeQxl z{TjMymXrdS6zA7rL1r#Qf!5HgDc~j`V|n5h)8zjP_a#w;()Z(P)Ex`tR;iFefL0L0 z5OpWxX0Ra8iV|B3?8b9EBn9VxV0vGz)OY|qZR!i(jcWB*=?QA6ee?t&pDRT7j^Og~ zLz&a@Gzo9lGl}MxEku&P(6EWnp>PE^M?aClMl4Cr%mPU|*<l<g28;KL{R-R5Xp_Z) zkmQRorXAP{LNNJXM5wS?EH`oQY;<NI3h0r@oFV#gq70PbFdN0X(4(}x{V<Jvfv*Yf zCy&Nu3za3}bEU^YxJrRS#Dj<ff8z9cb4H=sppCF0fsTYafZnUU>UYdTYjrJ)X#wja zeOZLT=o>?{K@F-CA+Es}R67}eh7&@H^w-`Uf)Nr0rGfMkD^Q}?u^HZ<OZ%WV#5hI$ z!k#DJ0d7NbD>Vl`lws^koM=ycfF#J!OY|{_iW>A+s`~M5Wi||q*eDur;Eg-%#)|Hb zEwD8_J$&xza$R}^4Hct<E9w<+;LWrkel~3esCTM#?p~Wczj&6}&bK_}XLt#?Nfkh; zSY{2EIH|WQjcOeq!KGGzb$IpI?c{C6(am%rda{$Lm|iK!+DQbRvybOVus(JFT)K!h zEg#CkJ<TCv-ZEM8kAvouxLQK+a8GybDGK>r{#(S<E5cZxKfSwvR5b2-<-~K>V(TxH zroOmr#Alrq(cHEe-_}Blk-<ny`A7{rNdRiCOnQ3-n&$Av1{~=ep#W92ue_dZ(ZX%w z>`D0S=SjT%)88^HycoEAU<!(>=A{5dI^LKui4geS_yMFv^;=%U{_71%Lu~OUEIUhR zN3oI@E=Q`0HY{Q+6+E)zO>qaf!fMdE4@G_)EE%-1awmo*exkDFF*!5Er86EnsjkPv zeuk<*VSyvms8T0G?!)HFv3iHe+=ICmb+Ld2J4@gNfq8pMszquQ)qqd_>T5Zuny=SD zAa&8!yF?tN@1(%&7!2A~cXe*cd?ElZsTqVRIyJ+G;=ED$JcXw^*ZKEb$_bBrwYz!N z+OE?`do%tCe08dwr?9MEBJ*~QBvcIAZxyBGqpd7Li_pw5Qw~C1;TfdF+mjO)T>&N> zqAi2s){LCajC{AonA{qH63gUgbqj-a-<abArVFDVgbk~uHZj}vOz*DY#VHZ&gG`cX zZ7!H|6n<!H*K<x3mnfDgQUfep2C2sd)J@OqfYv<hqo%2>V7%wp-+8n@|GAwor=XJF z*5ldITP+zfZI9{_c%N>xJMGr)^zT@<X`{&J2Dn)xz0l2)7wu9-143bcvG-jEfDQ#c zhfkk&@`?Pqeb~|10zWL^#s~oE!W!W3dkhG<6LA>x!BF^dHNq3`Z=uu98c7!sH-Rj* zKY+S(_iCUV(DjO66dVuFz>>FgZAs(*J1-G@S%dM`ZKqW0QxTvObQXipb@i_r{}*bS zyxr|WW4GtyUP%bM4*pgQiUi1hlTH~7f$P~K?7uN;7a=PB${lSK_@^MEI2C=n$bQAS zWmFLIbZ!T-6POE47MCG-ur^YM9Tcy45a11BFw_BU&`%W#KDc6*|NA1rQ0@Jv+qj)0 zOrDSZH6-jTgpid#tOI9gMF5clqQm-7CYTq9Rz9c$%uiGaga?a%Rk&bEn5(a1s86%; zl|!0H12h<n61yfKVt4HRdjiptWVpn49(*7$Ml<DT{O}WdrFqEyqIG)yUIbZtX6?a( z4`uN}OBfnr3UMnJs9vg^IEgEk+}c{w?SGVho?Lf!%8unn)GP;2i(cs{xLf69cSSOq zyXR_VSO`#@*jA>oZ4NB24$bfrdmX@Orq9D%y0LXY<2FU|{31UMv<wyR9xKLg3|Tc> zr&L`ac)B}J_oZ;&G&7U6L$FZphL5wG?ea;;R(Sitz&&S^wmHP1i0zvn%i`fOU!3gd z7@Rg1DgdiGZM?L|zv?>h*e)x8=l1C?w%;gUyJKP`XzOTz?6y`sJ|aFRwAlz;l5%pW zIsfdOAK$fREY)o(a`HT4C;QZK{17{4AcHE?a>2Eir;DDDElR#Kw&YQ{DWYoEMEn5z zhn^i?qMh%|8H_jOL(jhML=$N0R{~c;Y$fOO&wDbg$Km4g&*goYMx?b2w>&b5!Kjx> zl0O#kvZ{UFd`Bt&Tr%CiNRfdjSx<Z=?@}1UbYh8-jhtU-K=Dv_l`DnE!z%wHCTN-O z#oHYsCZf>ex5bmD9k}9YJj9PPN4EI4YDauD$!w>_zRNm`L#0+ZJVMctYYXw;xrn;x zArnj?Ym6dOlG*A*Ts$buypd2vbrCfEbM3B<I--f}6qYjcq(2&xkwvL%y_g^EW*UAz zytTF@c%XWqbeHN7M<S9LY5!hA<qIzV2M%6t#L1B?!!8Y_%oa30knCy`zmc7CxI&u7 znGgocLtI4tesW9NVJNGCq=LWe-hEbz-7z=j-U3mf!D=D1BDvuzKs^Y(C>X9)5-)*< z7)@p{M0AMs4#XoJ_8IK|_+q`YYd$%_|28|}cuksLPm^9kP<I9yo64Kj##g-IZIa5G zDWtOyf0%FmeIi^}ub$p2geRW9=G?6XCS<&v$!(>h?ihshg8?<^o!D5WWvk5&jx5X% z=J`5CCSD0{T-(eIGe<3d5V;`YJ9qz8(bM@4b!NXG@iXAzLpkWIVs{Wq`2JQQy?Z|# zuy)LVvrXD~;4c*ZQ%aox3sZ*<h|@(Gn}+<=dn@xnd|_pfq9q+8dcg&k&Vc$HC`}b` z7V{**p^*;mC4gbTd6M3m$i!B2VeV#NC^SNG_5fxm@^@<oOg5NEDdrWCf*-0S(S&?h z)=(1g6Dq)Zj$wJ&yn+HSR?x^n56p?F-Yk?uM?};k{)kL;Ta!HM;6fN?Qf9UjSTEJT zL;<-L=H`7x2E}!jJ;$IR6Gk)d@dbYSDB{S(0tBq226qSJguKo>p>T@*slnt#cb#t6 zIeuWUu<rf~<R=K<flp%m4dB3;mJL9Xf&!l85M?lU5Sl2+i2<}itcEDaCOgY{)ZU13 zlJMj`Kyi@<l2(`=DFJG}PnZW>RF7Z};{}%haRX6>tZ(0A&@oS}22E0${_LC76C%7D z3V@9uoh1Y&Q%DSt36Y;LOJ=GOv*-f=pSD`h)--!NyHz+{W@wUmT|6C@&Xn}bK>9H6 zW$;R}34gR&v(97%3eL@h0=fi3oG$yZ>e5|Wnk~J0Z!M4wD&$O7l**L^t9dliMqX|P zf71Kuv{-jPH%c^YN+2(F(VJIkTw^STT$5^JI<Ix?IV=b6qk9w^y}HRRm)XyW<Z%vN z4%t6Hqj{}8TZ~t<nXEh=(nb_LmYqK<Py5;FL$Q2{V8Ls%3BRxAAC?u|R%>Tj^pT@W zck9`yXx*CaruEim`PPl7X|LCMxXnATn-xo@H7}$!jmn$AmEn75@+1eMbv=oihQqA) z&1>Od<)7f><&lS!8X2|_t9@MhKpY)Ai_GNF%ruWsf3_3-TxD*%{(wPbDD@PrwR;r{ zoU-bl7Uh0b=iZ~b@L{Ox((yV=SPyU>P7OYycG)XSqUe-$^-NVuw|`j8;|{!ATlRs{ zeM~2$KTj1d+_RWrJ7YU->7izTGa;s)lb65DNLc60{K0cdx7njm*+d=^IRpJSPd#Rf z(4$Y_7F2IO#h9UJb-;*vcf2u!XEi2VYm!1Vv7wX~>WRy*>5-vXYmeXK>V75e&uc;v z=%0^}0+F%B#p;&W!vd5uROuKa6C2}2-mtfl`DlGKJc8=qM+Xb14;`nenUA_%)3fdS z<!(rnf(_Fj#)_LE-BH@U)+;Axzu$jz#!N0vP#C;y1Ljv%DDqF$qt+=NTCMREIp$aG zo}+W-{^D-IOL|PDUHG2TX`0NH&CJ&rcrX~5mmxQwBrg2A;W3l{Nq5QZma?&Farg2F zZ#wgv+pm8pVjrKqLc196{N_gRro&#{UUQ*De(;mJ3lYemD0tv_;lO|a-7n%`?xex( z?}6g`rU(H1FX-{MV_}LcWDsO1H_-RM`+&^78dzT_BB)zt1BxSh=va7ADSy7eI1!m5 zN&YK4mNp@lKjA~%@IqRXDGa-vZRbJkA)jQc#GYzWLY3P~N<u)M4pd60H&OP3&|lqg z?)64cByLty87EZnCSt4G>mHVZnPLUOlNK${wkx1b!5cYLc?U1Au+Op2PCq`2=yn~O z2+C}LwCry%EV}2@MZ}1RD@e;?y^*Bt-#kerp?-eu^_^i*7$HQWpo_NsT{##=kcxp6 z{emnahY}8ly&>TssNEyjB19qgn;l>$Jq|MnD6rKE<4><sp#ur@gwxLiw9u)^K>L%w z$0JJEy1KeAU^ST2w0L2aVK~EU<Z7T8h@5c`<_0g=FBmw26#E#tqJiXnKL{MJL8t>k zvLF{lS@oEP`sPT;YovfT3I~|8lJfEhl^t^u0^9^hB4{syfqqh`@pvMGHd2V4(6&SZ zzY}HB0H8-*G8!iWKd9|P>Vu96<}uj7_uY!>sw}Ow*R#pSLwn({q-P;x>uFu=oL29< z^Rl}+Dfiol+kCS=uJ&s7{eH1NV?4_>?(f;lclDj?G0u300&3XeLiM>R4n0+J{WAN0 znT^DB(+m%TA^@L25gp88rOU0x^r6Wr%Wbqs17H+~@V;2KewF^-<whtg&>i-5McmeI z^`c%aHCQwEzGm`J{%zdAh4?C>6}3g+kQdU!{(>HJUwEhe`=9o8{qYaPf9)nseNNAb zt;ko2yRvH!u~on4c;Ed`HNaDKBbZww=PL~O)t63UEjq3U%z|2*R&qy%l}8aYQ=QK~ zS?8$IWssXU-f~97>u2KSkxDbg*rL0j82$8&I+H50WpnF_EVlKMVnC$k)e5d8!H-+q zer@$B8}$`J>Mc@-WE|B0_H7<Byza<C6N#bTysX*(p>~IH)>$=Uv<h8f`Y=@lg}V4i z=S93fR+*2!znV$Jca-1?_IW8EM76cK@wyZ!ph&M`A>^u%`(S;kQ?Bm0_6O#y_n)ep zr_yur_~#MzNsCjLV+<CQD)o)RkM{)KcY3s|-txqR<zOGE;Ln_z`BN***liqKNvFW_ znMe&%;XjY*i2_Mx>^2RqIJ0w2oBlzn<Yg9BYUH6El*-%A8BZa>8PAn}d<Co7EMQ|b zcqucQJYAO(T0G_^W}245YItYcu8^tCd#V>toFONV13w2#U_EU1rE$zDowr_T;^k~h z;=YEqf|gh*?Zl+6hI#>}ik_;qGvnx}?4#MvV0T(n<60w$HPq$Nx9Ag)YN#S93I*yM zGfO`?uGW{lj}92%j~R5C?Hn|wZ0#{lZcb`oZj$ph&<E1*RlC^k^{PP(F?w}^utiv3 zu-qwLSa8VY@R1;LAg)jivczRxJZ7od@VIdg0<lGKJYI>2V5i}3Z+LFR+bBcn2B$c? z$PDcVLm}EIM~D(pgD!BuP>?A}L0dgm_UUzqi-Z9nhhP7fz5i3>gW(V1Ox-@T4Qft_ zosIlW{s6Pj<w@E!+814eu;pK~QLWA8tg|%<x+N5uB0}<gq5KsEiY_97a{#2^ghKVR zcF;GJcoemo%u)CHwMcZt#Ua5JQyFz%?yG?2y#S(qDGZZCri8Heej#mh7}~*0;v+=u zz)dnfDFiq$d$_+5sguYaIFJlFZ765`^sj_y{vZv5r91SA^4YwY0${~?Vi(FZ1fUJ} z%KM{n(8&<h2NO3>yAhy6eHXjfD1$CgR>JEA*~*$t$XSpI`ARxSWidx!KEhTcMB}q{ zARFisZtRd`?UOq>kp5-?9|}No5KtS$-Id&NL-Ch$XE_=Fgl8=<&w{KM1%o-LaI~ra z7L9|0RlB5qkg{gDco|VQZbj<|zW%A$sy0zilj|l#{xI^}sD+3>Wx0JAbV{PLlap=3 z<?6o4%r^5Q=$dDwr#IpKf;amYYOmzyAkorH)VeP(Yh2Y?aVCe{{BN4-A}0q=ns?TW z5$WRy-yei3jqg--n5$M2(EOJPH_bmS?K6kMe0nqN5cNzC>a7}Em1jzy9t*N77JQm7 z&N-YeGnC^>YTqDLl8iI1L<iEq$;nop)!(7!jG5;B#2A{09!?!L_4}!NWf${%ey$3% zh<s;PUJhdA-2VRHHA<#i<<FB~h`FC1d(waS*L~Za+H2mjWe`Ce^C_b$DxKyy&lo*{ zv|9O`;E<7z8ck9CR8p+H&A9ea^BAz4tk|`ZBDvmR9xvN8ooP<k8XRD^2i-BOu)5z_ zz2>rBVkbHCrn9=JO&5|OT_(-gJY77UPVvjnym|WgM!bU79oDZq?K!r3GDn;}q->WO z&9#F;AZyNM_<mP;kv53ecy88M>wLy{+pW;$W*ljYZ`0h;Jw+35m11^|n-^WURbYW) z(7iBBP4;*onUCFk+{wg=Yj<e<33rhtwcAXGd;b?xvd>kuA6n)%8sqk5Lc%hOMgcys zkg?sOX*=~mR9W~SL;gOl&GoF?YuoARDA1LM0%42g2!2Xry@eaNzQ|v|$AJZ=1;-@s zjQ;yKNwvc>m*;{%1zxTgbk6L@slcIH+?B6HlBiVMjZm9sqb@<ri<IZp!G&zg^L$DV zunP!^2B@&;beZ@6S(bP%i`YdsIGaWlZlH4Ts3wQ8utazv`*@Tt-#DHJDn|9CmNAGD z3iUZWUi)3`QKK>0i&fJ1w3cTpJAY;^c6(kNrQ0OA8QtT+urjvUU%cW_cATVcm~UjI z{B4oR1J8GyE-~rUg9+R@U(jC|Ulg-Mwk5IL@wuIbNDw1K*M)I>kt2kCc4Bu5Slar0 zNTKfP!*Xsk+E!KN$b~^6m|aOi>HKkq?)&~1BFM%aILbl^9DFi<s8xQWdO~!ALd?qQ z6P=u7<?W#O6Gb-CH{%E)AV@GitdCXX;elMh8Sx+Fbq0N!TUiZ?8Pt#v=V51+^y!lz zwlmKMo$O$&AgBzOqQp7!+@(f|#v}YeGE(Q49P9ydnfxlkaTs#p4h41yuwnLCFeIjb z(^#05hu3T%`rKdG1j<<KcZ9gX#>67J%-P|c!Rz;l!l-vTND+^vxgk(Md;)?{noWgp z3T9<M)?&6X^Toy>cKnr04g$Yi&i{#bI;;)hqa<)giEb5*!2nl<yb;Y&p6o@<jkz&$ z5>;u$L|Fd_8@>pffJ;Kjx1Ap(zx~h5GY|vzx}-jytNVZT*3!ceh8#KYeaURAM@GvY zYN{!2Yzyvm@f1IKK3n#!w+?jSs{Y<$Fln(b8y&{A<%;&+zV;(7oU=Zkwyd4`6R}d6 zqW=r9TYzL^PAnk0?sS?lTNr0CHjQi(*NuZkZjq3_Ng8A7uG%|Xqb=Ff&3|!z37Rln zh!$tn9S<n7*Wm5=`>nH3G<tTB$Jo6=VyER1myu26@+Q|D&R~iAg*o^-Ty4wF9qC*k zh2vFP{;x1ce!AA`d$H<iGU4ZCb&xc5T1Uu{Yh-E5=_24yN-uf-bBdSPJwR1LFqY7p z+;J#og$kdbqt=DzAv*N)vu6UP^U%)xlCQzJMCS7vHfTDT$hvgy@`em>?b^8!!qQUl zY4<CKw6M|GSTXc?Y$!*9-lhH*x^4MeU&&z@0Q;0lRMB9&k}-XeC5g8<-hNDb<xubx z9CxEccW}&|qS~=!>vyruJ{uLv<8x69{zqyY9Ny~pVS&&SVTW%7MOx2w(^WP_K&;i< zEQjN#m>bxS3l3eNSykV;>$B~py3!DNGtZP)@~Ni?{0BSRAAk@BQadd4XYi*TUr8gS z*uX9_pl6nrEE(M{xDa{GtZ}9ZF{;plGXlUzB>h}`!qn9FRL$HkbJA+DWi~&dZ<PsA zt%|=DpLa%ECSb#Jxezd_CU3vd9xA~A)8JNA{+azA<HgUL0;uAD%_>p2#Xif{I+}z@ zk|071Ll^Y*3WaX|?Rnjdt;<bJ950j2xwVogiKTgP7jUHLxvutHwFTaRr7$pd33QP| z`IHRDs#z(8=N<h}d!FMgaZ!}IHc?2$TpwZ50!>{ij^cJH(o(KwJ-@f#uXAhDX=82U z<JME~-wD|P#gOO+KiRsWrtduI1bIRK#qI`kBfjyYU-_QL4uu3lU*{$lCEQ&hA4LeE z!6^|!61p-#Zlg|Ez<8iPkaia-UXf5(TI#4KF$ydmL4be=!R-D#LiIn~3tH`~AqpB# zm8#9U12;kWh4kOhmp4mx`Q4DALZM9ijm^*+D*Y6Q{&dH^OQH~87N&>{#YG_E$3X~6 zDuP9)TCDv|Ob_}@2E&F$E-=5>6qL!rlyHrzs_PvFJy16S3J!H6T|S;f?FKw=6G$Mk z*c@K-bW}?fhBZOD!mdl@(gQ)BIyyRN!WYOF!B+cycjRB*+xk~_<ab!PQ9|3v5}8P$ zMOEZT93J!VHP9G>0KEVa|5i*mku)yIE+~irAChP-Av1!3eEm34jG^n5zOY$CZZQzA z8=`O##y^3^85tQj<o0C$F)ni9Ga94_X2BqMSP3*3pzM5O=(aoY36;TsoB!-dWm>+T z6wq3-*31{b;xy2meX8&&(vnm0Xy!PDE!70pyL=nOyMwzA7cOW^b*=Fnx|~jwr)nkn zd;lAqdmvz<T{Ts{FQ$&Y3zO^oS<6SOSqfK4d>v;^?Et$8tIuZ84x5<`AE8XZ>a*ti zNTYb?{fGIeQwH1D=~uk~c9>WV3exsJZv`%z@enkf6T9ZH<8$iG>LiaQ<@r9(8qYW> z@<dvcpHycAvLfI2#Z64eu+*10TK73md~=rFY08AQc<fGuTIT~3T#G!h6(-{{lTsmN z!f1%jk-v9-oWFDYoEkR@CZ4(}wS6Xk`yG|$z*~MiK%K<tS61R<zEi_=7^-8pc<XTP z%7m<2NRE9n4ZGIBYX6s$={{_+X){}3Dys$gwZmyAb(43O4+`R%;K0Ys5=}GFp?f(f z%wyV5LKj>}U8lr{l*8z`fhvG)!+a23i<|2y(sX3$3itjvq{dI?9$=n<eJT*|^6QkN zJ@-8il+h$+3vP597P|Y-ln*rHJ9F`Qc5^eM7LxnhVyZe$R~P?oQk=SoqgT2{E`Rso zTuI!xKp>}IVswN|w#*`BR0l;Pml@o<fcjHp)f=hA%4MzbOLIlOqGpuFW?~sfJ&;P5 zCTm<S()!8tgzf{Ie;OvZwDD!_N)iKal6y{!FDEi-1u#_!X~+SD71g{8;dhm(g#hgd zZ;T!i+S_xVd_`<~xAP<!*h1Jua|gJfB9r9%qAQg@v{9Rrl&)v3GbuXo<;Y92eJ(}g z1QzPuwG`P0H9S9{7}Ab5+qQqGnytO*kVSK0n5HY-85q}B)U+yX9&SLR;dQ{-C=kb% zD&TX*>eQRxby>LJb5&_}sz09nv|6fya|0EGU0!Up`^~NWLif@HRLTc1Z}8c0#C@&A zaSmX=!X&|N7*1|BNJ#(?j+Mbi0T4yOtpN`G>m=~reBP{NsQ!gPaeI^CJLo9L96RAV zm8d~Fz$l7%kT?irSX+o0<n*y&%0l`Vc6%m)++eLd3=B~0$p8O`@WE6fDGqiF;oXrO zb*LLmY*>53A_%2VAsU7R2@e_s>J!l4SEg@jG#U#z7eKim3!M-j#~2l;j|t;+F9hNx zwub@r4m2Fu;{|syQ#WD%#c?Cb@(tMYXCtLVK){-O28m9&28B!tnnnpP==XBho6Vam zloVwptC!SV0rxgRo6m#$7~bA!QsM=9%%h#H_(`|Ivxm9!1$hawqaMu#19n4bk7W-b z<u7^?p{j&npv0xaG_;SxN{aGBSu%Lne<v;;o)Ot=sIS!dWENB&I$(p+06BTbIUdBz zo*V)tXsC+?9wj017X}`BB5C7FY$&)0ocT|*9TBH=9e0+#d&6&J&tO+W{2CH3AI>)v zD{dEqvY8wS*dssb7>HT&wHh+En)sM09m*LMN;}DrD&6FT>cs`OpVM_!e{8BUOmyfx zG$v2T0iV-|AMTB<*PEzUOpw_wKReE2v>g9!3^~2uq@GK9t@0Q5ZqH4$Hhm$c1E{03 zwI#ghtL@Ju8Wo?leDlu5;%JU}in|MjN}X+wQj-|KtJlOWnq2j6veqb>ZPlbjs#z^4 z!pDXN$p_6pu(h6JTe^#pMz@ewu3h#J<g<_0R!2(xxR=I@=2a{-aWn1beF*rDyNh%S znlQ_jnxdir(tH_fqsRYz(Sfo;R7!&A!d9o3YwPvg<yHW^^9$G}w=g_A_``Zz0`_Ij zp<u~3M<;xfYt=V+40mtFsV_&P;6GWPCH5D!*HL2`(`J6tmPf7*nT*`>QR<4tMMwAN z&iAX?194?&=wiO+sjtO9-gt+A^E9U($-gX{JE~shPt_aJOy#@LUJJFdc-^w<NYRYg zX=SgpODE<>1+my%i-2aM(8+OkUVPEfQs}qmnQ)t=eO~6tCnDJUs?MG`+&@{B*(odu zW!*0v$d|@v_@WsWi?ienf#tuGdV3#!?G`@=bdxm*NaLeFN*8btOPgDt;Ywvz2_)kh zb#8<mz0aaCt(}O71Vv3?)+nT<aT)8WH@ftb4_Y`vz`7vAFiguKoAn}YT!>E{>)7!e zkKC3%>_Elj-YcKzvrt6>gsl4o{A7dn#~uJn*PY9x{?lUfrZ+7of2n?Gf{Tp52~6c& zZAz`%PFbB1Qk<fZqaNXB7%$vus999qdjJ!fd?1@)@-vLK50_(X1#uc&zrqg}!lH=* zreIE*`=hZzjeB2k3JA7v{z<`#R@*&*R-X%lQV_SgldU|-8=S1Eo17UR@@MfI5ja0c zYzU2@t{a6qAOU7af*1;ZfeNJR2{61_jR%f}sM1it?1k;qHkbm?c8QRm9qr{e_=Kq@ zei{oS=nxpTsdK{<%Ip>11*JlgfS6!}i9_DqrTidu?>-QbMKFKt#Dnu^Z{J7+?N<0- z<&f?K)fz+sQdy^DPo_`AJy$&qJ?~_J9}4%C=~y^ah+{3n&Q^?ZIvpj#r`PvWUjdFy z!eM1F*j+<{p9btVO-v^lGbYfJR|i2;k|(KyWUKTA4!&d1Be^Bu^VSzcLSE;7YiLgb zK|<i~)KA1hz)zH5FVQwU?w8$`E^M=b8F23qf(p(t%gyXqgX{(XkvX0k(1yJXouHj| z3=O7_!~qc#BgGN|8NL-IlJM{3C)$~YF*w-6eI<SR&Uc86+!l}X2h&Q1FqdneO$7b< z4hc|EHpQ1hE0h$G%oh*Vd?hdnc)$@&JWEcr)}X4RBsha*B^NfOACrUh_={DfOeShl z9uWCgDc+_w(Q;wo_-IIDy74!+wfj!PwVeH=Kng8-bug-SNWJOAf`S^pud>xkP`OWy z;KB@BnZu@sx?Ct5Wmo><@t?aaLmirh^k_?gS*x1{tNY3G9F<ZriMR@scd)B8rHp;) z0rPcvyA^m+`7M=CwwVk)pXX<7Jo9ta)wA-t4fS(63kj7@_cK%~!V44@j`%amV-C6e zC$om&a;}w`=7!=&>3=^+-$CZg2S+!XFQ3vDZu+;9-n@0!ss1%6FV3y?Kvw`d`B)u| z-aE}&i{CGbkel}%C#5K48loN3`<r_XV#rxb031FK=MsoldxERUBfZp*BUDM9TU}1k z(P1wD^UqhK!8+te(JnmiS0%xfLW?{j*=IAT`H*E+i8kqTTjwlqCi(N#)ah$5j!iI0 z0G!8#c%x^w?uz~QyfoMQ_Vc{w#rGL`dXpE?24K=esbY!{?;?YnJ@&2W=uu`SL*!!J zsjxumq|xRV{o_nQyBK-R!4kfAt7L6vN?e(fnytx%wa^7+68wk7z*cm=>SpN7!%5xS zf`l7d#yad2BYaHl@|@%K>QZ&o(LOJ)+wxnTq^aoM7!EA&73lS8hA?@dMKZBVn&a~x zpyMUHNxhq0q1XU*Q80}6XkyK5Jd|n<BkYB!k_buXRtCq>{07@HT@G=f{5Oo|R-v@h z=b}Uo@#VN-1*L4LZ%O)<ae@dRx|F$(UfFk*n#IigVePcwW%J2u%pqfG$C*4)yYo?% zhrJy93RPfdm3R~u>0b?u|3Ed7%C3~SUtbmGE^u!>F!hF+Y%cqig6sT(48=bV3}wgQ zVpmTe`$qXAew&$Y1k#;>fDCb{KxyMem=%mWICIaEBpLt*=`MpLcIPetannc>Vx{6J zR8l|!qXAS1$12T}691n<D3vtHfNTHb5X}$Tw_>R`kO))>iM&9k%pA6^7>STqE{)mX z<z|<Ji(k(`1Lnpyxa%XEpib`wpBd->5cXD4b#_scF7CnIU4y$jY}_HZyA#|A?he7- z-Q696yL)hl4Fv1`{oUtW^f+UjTkaUJ-c@VXQ#EmMy)B=ww?XQCum&G|>qmc*SKTqB zz%|*+TD;(l;y<7wfKsXh5TmyCe7=lmLI#C|v~|%J*P>Tds*ol2(-Xri!~yK&2ag2W zR$rjwT@$DbQv|;qYwM!lwWIPqlk5*kEg3PZGOh&dj<mS%7f&}lGk)x-Afg8=m>$e^ zEsyv?6dA?!&>Tbrcmg^b8G<C(I~U^p{9e13xGW~@9_CUY2M0a`AeiL<O$596Wa4wK zNDM+_N-2I${s2a^nB1W-KpiUtTWpqvp~V#=2r0#EGX+n40aoVV5sp=s4Kk4ckD`AN zT|5Ljqn9m65-(+jtvuPQTroyr$TKT#9+uy);R4g8z<GF`kJa*G)bJA3$q=`x(3j-H zJ=onEWp}kGKC$39Ylg412Ua_Nj;})PqTllgu}Onz&fg^i-zUK9)En_;XFjRVjCVP* zb9ixb)%B89zf&fM6Pb6bm>s3@jo38{82T~Zhx4M001s=RiTmogDz5Vp6()$h=>ECE zO<80>ysS_J!;Kz_XXz%s?$}~eCZk(&5{oQj>#{d$U$|VRnr0KGy*w#co#rRXcxX{_ zi-^@To&j9;aVy-vC~v_0!7tRSho4%y)R*Lk?_DNO!B!Mp>Ho%1e8w5GdUj&=SFEQl zTu~6Gr+$&Mk*4$3zDwR!W$Rk?lp)id(L9O4?e%RWMxoBoC$S8t$4{xY*OfT}xIq(V z-{vv=@{=O?L4DWH<`C2Ogq_I#{odCveN)S7dHaZQr<pX{ugXk<176<&{)q|higDGl zNpd$jk~%N`y3o&9ed^)uvfP7`?${!2V%i~BBv}wpvI*USFlM3j2XiSW1V4_^yZxIU zzP6jGliP=gtrnZ0QkbRnKGAvv4?eogrXb+7)!Yf8C0Uk}eND%$Al3OoJB~m|wZ;!+ zWx~pg@@(|@SHd&}P|*p9J_EMl9~H)oge{dvvM=Y?Hz#4(O6$LOpcHWC;~HBqnW4^{ z6Xv}b!_6^~&evB+ea*2a^y;NN*2*O=+|Gf-ze49~XkMklXInO{%i^)04SjIYl;QC! z3*u#n)02^>twODAP_F-dAG^JUo)FW}XV}yU&M+k9HV>D%U3U*T>Wyj*B9Fm_^s_cC zJP|1kQ8;i@EEE<p0nCI9BMED!tl*_VQE?m<vMi`+OPY+juTKo5tRWIK(MeKC5V%9Z z5a?T1#SB10dmWSU{}<k4mIc9kjQ<DT!+MN(ris}?9cPBT4Ep+qBo6_@Yc`$$f?}N( zf8|6_vG2hYf;2n^jiLk_E+g%Kxw{0gLR4HnS6XsWQ73FONjW)0&0$?|MnnqHf~Sks za4K;K8YUK>qk{=2Y+&hc!Gq)p-|A^cErEmp6hR;0CA`+4`7g&<LSA$YTt<j}5W^UQ z&xrs|7>CCWQ&OZyY0&OO)^7CQx->FwcFDlH-<lGIetWWW)N`ma&^pVt`UEyZFDjg$ z<-}MLS1)S3b40^K(PZG`BqsTkdML<=|FwLKBdgGY;=n6Bh!a-WA!M*7yr3iAE|6_c z(K|?R2Z-+mL-=+3f8d`-IQtOfY3@W^zc(y`>x>IHik{~cxlKkuY|4FWMM5v>CcV*Y zZp#_nJT}#6GOnO%8on`uWNFE`JgCn&X&L|@MtKxOkJkWSwxs}|rUqMQ!=&`KsaWap zy-{@WVLvRn$WCW2>k!C&Ihem(z4^=QS=WW9*%GZ1y|R)STjR~W&gL<mD=39Lg)EGZ zj=#ghFLmp$y|~;paZrV5+56%78)=h2poJ=(VaazOmG_f_EyA^^A^_>l=qe#pMUbB_ zr%#b!R_dwsVFljQtlS&hEvC4$%{0Ud2L@K<LEa`yGBs}d_dA^w4PWaap5v9f1OK_) zOx0oy8(!S;P+f&DPZ@E@l>_wG2^M5AByFRGUa5;tlFj`?tHEQK6)aKZX-}W;{of5V zi_ONE?TX{W`U;ZrfD=dp9io{YrN@-<pwq+@;^PV8sYVjj2=*3YUx!6)@6R+>pC8iQ z#VKWM85okig#?CHL&5EFkib6zdqr5HoGv9#O+UK?5VXr5NbN{+geWgqKDs}BGBIe0 zaFh^xDxB@dGG(=tBocE&Tp>*Uz80So#S*QbE&U^I8$;^hc(>Q-DG%9zkF<wm!|o$* zao763vIuqcL-fk+CWFJ<y?GfU6I%*naC|%!sgC;6x#(ZmEEK~@<bLzTx8)o+i}shU z))`fNsKFye9I*+u$VV5z+y)zULQjhe_&gzy`tCQH%-NJs@&r73<z-#Zx~};czj55Q zuU2EPLQgt0++T3Up$e7nPcQO}Tu{xrAKJeI%4|_J9;Oz&6A#W5GkdtLXarSew#(95 zo3zT^wmbY_;_%ok{**fxNuiMN#k?``Fz_(dllvdS)|D3(LFNU1{;9#*gF(Cr@{xNX zBu4oeCKogoh!PYabuu<h{7esk)PnhfgoTI-eiH!!EWZ3@JhvrIhI^`jK($+~Te)$# z*V`yK@$W!D*kwdW-Vt}(IP@o!C3J?9vH&x3L--HMm;dJ1|0C3CW!`AP;7@t~!+*Mq zu>1SWfpBU4XJ|Ks^(2p`PWW@tAki^^IY8Fj(qasAdI$CgzQ=biU)0woeADLZ^Fu|( zY%C%I?Dyh-fIV-&y3y>~P&dd;kM_hxYF7k_c~nT7U#gy&pbWwx=8-r_;4HCoT3An5 z7)*7F#vAO>jUbC84_Y}?gE9fu{t~zrCIs(9;3qA#W)uq{><_dk5$}`*kfS*KfIR$M zj%Y~<SENLW-obOYk0H>G04GA~&`pZh3+XLJ6|x_u%!hv4=!B3B<I~KtKmjAx@0br6 z)lWApLh5MnLR2hDX?Ozn1(A>D6k!$ttIPzP`$qTmKllAxB5`D_hO9CKw-^b-$ZvF9 zRg40aB?nOxgUmmvW=4`my#GLVJxIeh+C}rkn$eH{k@Pkr9d9*NqgJCrCADj;DH*n= zNmRi@1c2SAz_yx2#RMc)cpvO^HiQ$5Y;r~I8Zyt68oU>Hvq}?;<=PROuTnq8Sd1SN zi>5cfUwQ}dElzx8JH#yNOr#%UYOI`yaklXvGIcU%-T2n_^~EL)t?T$_@%7rWzU^nz za2Rzw8%uAT%M$D^#HAOv$+`I3ZcHfLnXbG{`${Wd0CLI|u~WTpzsq;9K0vl87RN;< zwffWwlAdS&F3k|>QL=DbapkT^^_Js2bjNGUDlyb&BJpbx8=Yo@e`fHPA(rM1{;4`S z7Oo{Hw7Ph*af#bl_@S{aZxb4Ke(OAUERho^P?HroST8uG-{>15_1q-yN;-it=?6#} zQ_Y}|QCVQr(Yo20<n#D>y;vMaZOdig|7?&6Oc~6ZPc_o{<Wu-<B(xmQNUxf%yev>* z(QTK}_2*U<$d$Fk)#UK(oxJqdZ}=DK#*I7$y+QWE=W84iK5BOFBm>Y5bK1&OxamOD zTaGp8Q6TGY`@i^?J>g@wU-KF^D@QKzqrmC&9DNk@#o?VJ&YD}}8);kuxy?EW9fP<` z5)tu2nYELu*6o`EzjJ|?!OOZOipWkHbhzYKhQ?0Cw%{{aN_fVaHmW9+9k*%u3-XC& z#cBQf&@{cM1|Bi7A|lA4H9l`F4DMqzE#&ROUWQ+?S^igu_vfNlt1vZ$1f5o5w~ud> z)g9GXVtk4fO1@UFL7Vn{+3Jax-;?dvslDUpR8jFYs@0`yyuUqVa#jsFJ9~ilL++); zzj3!4wj)1UuF>`PU?77Kx44wkb0^M-pv7R&HC_u@3tx*R1gi-D8Ks2m+!w{-i~NG2 zhaGjOh>naW4jCv8CxP?>?a1|fDbhz6Gb-j*ixzrBRB&r)z)+NxGK^nRYPi2|z>kbL z7*3DF<>P<5`Qq_W!MkGd`FLO|sO9ZQz7W<R)Gmr23k<v-Z;dkVaD<NV-t%)^$H4+u zZ{D|F>C+RL?zNB{EYcb7Rxb(+j2<#soXO!x840+e`(6%*AQmYsq!-+(XDpc)hWC6r zA6&=xOCFU+J(flUnhZP8Ls^|L+)1$gNfdht8v5>xAs5Wj3m;cl0AesA#JgSTmoyk% z5VJ^)a~bqau$nSV9N0{#ZD{A-cVE<{Fhh{&M;RX=PUL}V3R(qI3z-754f$a}z9kJJ zqY7|UU4X%2iD-8`A>IjLD|1Ur67FUalqUaM%&W~&>=AIIe-%(Tdk<4o!EFq*x~V=_ zmj2clhaNG;0K^b9<TV8m1pNynHfA@OT^$!muruBQPz#w;K$>4td7IQ;L1b~WSw>Qk zs^)8FO(m2hgxBZ3Otss~qEcb4va`CEFari^TN&h9(<j;K6yBEAP^|ofcKG+ydtMgZ zD40+EojNfU4Re#9>a~6n7@RIH`$wrw4r^7k@Lk(&4pwTSFdX}*4bJKFJI-HeG<TMY z2gGjj6Rs(Zdi$3u&Mz^9bgmsEsNFoq7mE%Q+q)?33ig<~806@kql*S3TPoSU>|5p3 zLvoV9$`?Lhq1UFC5R|w$YD9GCKI?CcXOCwZ_qz4wUY+}yx)5HGPjxb%*m^Rxl)AL} zaUNI$3DCoc@E+)tgo7P?sRet+glaL*q#~J8{v|k5Jn(7RO?B5ZzJ)NU6tYk6nBCxt zsMOH{v3TF+CSmu99K7A*XKFI&YSJidiPN_!sHGQ$YiF<aVtp3hV*U7znPR;Xnt-bR zdWSk7D~Xq`{EhD}Vzm9|;}_TYW67WASI)~Of)|9<JTZF|N;la$vn7u^39DDGtCy`S zHy<MAKG$x0I&#{4e|#lU`xT^$Hs81&jYua^4RCOU{e4j@YY`gz4$yiwh89;E02Vnt z))>83PAqjny567=yyVB6D;6~5NRq!LIK^*mwes?ct6D!uFElAN@+f2(s6JTP{2nxr zDQVd-J$L0kgj84CZA*zX)bC;bNcY|55xC66V(gZJ)C2r57M@N9@|GwHJ69+ip<z{I zBrSEjSFbO{hlfy?sN1C1sbbAUZ8Hp_^R9w#?$t$v1O%rK=`$Q)5fSv0l}S5E08nPZ zxS>fP+y?`;A^62`!{FJ&wSpXvJ~6Bl5KDugjJTYX;R1=tV6x$bP>~S|_uLaeT{F>d zHYvYi_H?_gUVMisVq)G=eJF>lASy!uBObykRx-Zo{v!B};84oV2leG520NI2&@Kg3 zF#kJco2ln85or7W#B#76;d0>n1E<aJKZ7oU{888;ZNc3F>F%wGQHd@^DU32Az)``t z2c2qvZv?3nv~G>EM8y*e;va>v<~u&Z`3UKUT<YDgHJBO$teiU(P4WUMzyvd?dl}Fv z;nhjM%3+RfIN%_SXl{v6ku&B9{{-8H$_5RKQ1{F2Q-_HEV2;5?xb2kB<bV%>%sl-5 zEDMM)R1t-mqb9X?!k~q-G(K_SNC*Th;h2MPJI?~tU-YC%E&FUQjHG4SbKyAO$hNXX zgoepsj>&OwQGkGWKu97?2+|{5csJa*C=yPz`1tGp`0+I&(k3Fd4KU&-u;M0$B^pxo z0&kR8w7Za3z1P)wjZI>$&UB;t{ZaLIq0+vPWdp<^k&JT|W&oRUi%6H&bZQK&GcHu3 zL}EM!GO1Sm(ALICT6pql3AT_x+7M9nDI^vuUD{NAO2~(aBJXUm9q7rNlEcXkR3G2a zVA^i<j#5a5+r0iffqC6Iy>Y7nji6&Ga@~;qpJHf#)25ta=pKoeDp^T=v;}BA-ZhqB ziGPGOd#~0m67-aDd<n*SNe^ZtviFqtg!)v;ls)Omu;*4DDfb`&OOS^Y&YB2z8Vv~i z{27TVusy22Z!;-ytE<+gfB5#@hhHXo5i{=eS|3mO7qtYhaJnxM-q&xA6pz9$apYQn zD3iTNXA-NX7<tt-IU>*w9|yjdJHa<zVtuM9`Z(AWL0~!0f?HI8)Jzb^(9ylLhjx3@ z_d95!9?YG8X|_$5*^`vEnbi8Iq`DX)E&4)n@RWz!W`zVcLZpLsfTL2@yev+E_E$ZF z9(b-=_@iWrUT4hbP~<r8md3wA_r-dKlTf-*Mo2QN=Rx_lT%$5vx8A1+^=(XP`WC#* zJH$f%^P4IRI|iN-RhC-;uHn^&$sMrvym-c@Ii4f(Y)<v!){u?^E4n;~^THAGH;V`G zB-rk5nQIrJ%A44ar;a8V03B_wA=8OHM*AkEHKV-d;bfg+<z&~)ed(_2BQO18TYijm z14VUi_e&o}zco6U5C8Z-m*s`E4=-=USJYWYsX~iD>#i%9=|U7ZuTAH9+u}@{w;Oc6 z3b^Gdjk+Hdm7VYIiCMgQP@XW|<N`Flblrq{;N<gF&S}q1y(`IM{npK>!eYNJ_gHV~ z;e!A5Lk}SAx$nJp^c}c>031m`@OL9gT=N86i2V;zLSIB5As?u(U=~$!yg^XHwu2VU z<)sLQaFClE(GW5)iWF&t6pu{~G+Y<oFGUT!HSu9Q3e^Oi>o7g5$p0@7K49t+4afp7 zIjgLPG#(CeZH+*lIrJ4M9LTqZemaAB7b*^VRqvTWXk$(#wQHhIQ4P_HG=-s%#66B9 ziy()Pf^A9(R1;AK(`a6HknL+i!uRWkArm1`oJcx7VancvX%Vl)rTFTjm1AM5W&hGl zm?)tAbz{5(h*4FZc0L>xB~jE)h=D8)+2k6uLJiqh0|{#YydbzTLOE;zlt+ILjI6Z4 zLcV<>PI$i6o(32w4KKkagc$mLt>~ALm=yx02pBT7wlX#Z57hiHT}oWj+&4Z7^e1~- ze|@N&Clo<?O68V-If`bC-6Q@-?7N~5Fb6#Kb#lsro;h|SkHvPPbG%aeOV*5E1kRO| zVdlE2xHsT38?}_|^i-_$RO~8A_)Qhm>s&z!Jb3A8c=U1!c1<E#>wJ{(=|#-BoT5y2 z2Pg;ic##+?sOHM_j=I{d4ioC*%gn)n>W02XW$|XRs%m7j%Gwqs**=xtTW3Q4t!;Fl zR3*GgM@aLN+!Gu2B#hN(4xDr8JB!_w@uS?n8x0SsL`qf}{L@|vCDM89ebR!X2J9}> zIdC>9WcDdC;=KzqKV6?_Th6`ZcS-$ZX!>fVDIW1hF71Dt8PZ)lFW<J$cUTvxLY}`a zqARoLZ2g;$p{UTP^{dTMY)O(C%L{3s356dU?Jna)-w<i0Vpe)PYPq{m3=^=NYWC3d zZfL81W8#GEl%iuEA4*Ph=q&F$mqj1nR`7P>>0C5lEyc^wp!Bj&Drwsz_hGzD`%ZKh zItp|aTIK!gURA71wD9~C(Q76{Fgw3{Qgj$hyP8KnI4<_Jzg7A+9%{CeLMUcPKEW6n zcG=OnB<LJR^7K>g0`IqwKsNTv0yWM;_J>ofbMfcj@zh1V6@~5|&y|*<SxSN{NRMo| zb{F2a6})qv_iJ^fb5vQk!*Wwx&K=;tcSx6Y=|%4jI7T4QOH#iZ{Y9?7ENp(Fta$k_ z;x41TrFI>Xf>Osg!`s;P>YLy?_TO$so2_424~kL>f(iOQ<4tKjf=G%<EC+YDWlKX; z9Yc((4Q1EdY`a^u4kWsJ%!_rIpf2V{41L84gOc;q<z@B0_zx%ide`6Ydjr88O}|zL zrwKYa0-M$-z<r@l#K)m;z-xzkz`w&~hwUETy&1QYzF<)Pt&NQL+Irvb+G9^7UhjC2 z!2N_}LOes;`*|J_@&%43Cg3taapy%HgBTI66pSp8`^Lb-iiu$Tf8jH?wf9}1tnASv zT<VEm2|z?DrYm7^I`A2um<c@rx)mH!IRPb<?H#qGpV%n5zPZ(Y(*~4~AvFfWEl?>p zDc&bS6f@FiQ3w2`H;yMaGOZ^$8nK53pa4;!gZH`U=<kWFz6T->XahuWAsMe-Fm;@7 zS#}TYJ_}Xoa&sZE)b${l@@R&LTY^Ul`B>ZncdsMhkLjGp7sc@?!_xPu3Mb2%Wx-MR zu3(_SUPx0SJSFiJF;PVdctTm4CAED&;S+DE;Xu*YVBBV;Ny)(7i90|bH_oHVDH3+* zWjiW#E$N_uG9@XZBg4*p;2OFljQa5hg2qgphDwm$c-+R_&J42zYd-@-jg$4u8rZ%S zs{sOR9uLIY&030F1FYj*4}@M0DTmP_z@FS)YlZ`>`28;9B`aXv0*mXeNgt1p*0G7r z-c<N!vK?$H8ipOt^PUKK1v<%41)!~ASU`&MhmoYOA9s=TuB!hm)$WfNKtU_rUEYk$ z2sdK=v|hp`eO6PI&PLq7$iE7Q3c6Cdcq%)?pbtS9!7%J1@;1$5B5fwRNrhpVpCG4F zcBjmnL-Mr#0-^Kbat^W(`8LiS<N<&tt#cdEz@KBoS7~FfK{1*!d4+dAN~?J%^4~Wv zOM~Z!ny7;KO8-9u@&%j}pg~Czbj~M#+Yn6r=YTp*?B`^mj&+PYoT<{RTS@Ht<y7Ov zgPDajhu3a0)dS%~ZZ&-mo2rke`HQr-NQYv|d-g&0gg0=gyX&&do~esnD(~@%D07od zfn2~DN2;0-!6r%3RCsa0otd~bs^tdLr`u;MT%);4>G7{K8mY|GW-gUS)HkxC*tV1A z`Vwx;8>QTerFCG+zt^dr1NJxRBgXr}-Zr7OZwle%t!Kqp;>i$Jf%g6Ah<&d=Z)!5V zu4=_|3)J4jxFfxp511sACdASCvKSu<R1%k1qjio|Z`5`EN|#kzI|-jyi>fp7=wI2o zKGoMdOQhj(l-FLJ>)<fymJ#;mbqGiNfiQpjFtb(A%Wf+n#6R`6le<g+a+h%f^Ry`Z zWm<-F8U0{*Re$crAm0pfI`C@kRC7;0c!Nl)7~*-Z7NntG!)G`mr~=}wTdA^<T=C2C zYLp=@r_C{9At=^&OeM(hKt<%6Afef5)E*)c$8aL>EoSftQEw0z!+{Hp>_w>*_I*tp z?pX_t<%^byR}2>!;WH{d4!wg0HUW&=Ekcy-vcosT%iEK^SlZpff&6z*Dp&&8u?mxH z(2rUI$8ho>%cGVs`Cizg5lsB<9JD}r(6bzR>97QocsyEfjRJ|2RE?|yAi`uo=kMIn zpA^Ut2BsxrAdfacfbCPeqts&Z2sa%*2nH1ebu{)eiMXe8FQP(bQw61>Cs_+WcsksT zNgU6z${v6VPW%@Nf)0EQy{@}E(09*#0_Bq;0ZA+$iy0zNh!(B{M>+5Y>y8kPBKM|) zQw)=&EC8W4wVVhtUL91FB@iPtP{!&hDj(^%#~OH$zzwJLhXO?C(NU|9CCrXMKu>BA zk_RpXEJckmU<P~aL4$X@ju@+e*I<quGZzB(&IdT7In$o24l0I!IzNAy@?)Y$>4?A) zVyDv?z&-w4Szf29U1Bh;qV~T)c)mK<s3O&CiP9;d#|rU24&^cr*)iu25Y*;B_N>_2 z{w3jC&}zs2rk@2ezt7XjOcN>XM~tnVg=EZxvjKiZJTBCfy@-J$EV+-d#CIiIz8cBD zfArp^Wb3p3qM{a`_pOX%r&JvDG!ev#RB1`^!{0v%>*@2!vszeyjI21KDX5d6gHIt= z{P0;f=#fpovYty|P!g=TPVjrU9+CHm$@F2?yV0CHzTj~G^8s8WT<NUOJBfcl$-84( ze@EM1m*;xgLRs<it4PGDp^h)zSF|7U0Djr|#`^{IYC|p0khR1JOvBN$pC_K_v&j|L zXq)AVrp=oXNKshuU0(j}DmqBEUuLFWR|RTJ`pY}d(!Jts=U$w!k!@Av=q_opt-ZJ{ z>f%!sP*<?U@@R*<Rx%bii#CfMjy(L`PwxulRm?{uI%Kvf%{j|)ZgyPSb#qK$81XOV zta3oI?_poh>ozTa&V4Xv-nB|gRuQMZNE_ZU<ygNq?YjMAgKm>OkV}b-NG3XFGJ3sd z9ZeY9*6!6y6JF=amgZi%@I5c4f&_qD-}6~XFy)8GY9pbZSFQxNd}&k13&iuepjKf_ z(t!KsNQle%VZAY&rgiBWyt7?GP-p!@47;7I1WV++VfN*=O_`2(v5+&c8#iAn>r4%i zky?oMB<7l@(u6{Hn9V+_ck5tbUUcQx;Ba8@2!4Auc^2mP%N=ogI79AnJ@3h5C&L&~ zm=jjW!I_kbkM~(%Z3xdrdh+r-tEfL0HbH8?&Ob&Pj7eRE90IkLM|}+^{=_(6<VRv| z`rvUolyVHp7ueAWb8UGb;mi?c+gSICB!o*r=)N)Ox76bV9A!*edI;X^FHuj{NALt3 zyawqjOnVI^5h_XjIgETPlILisa`68Um7sS)O>n9BeC|G^gJW6<QogUfO0YiSP}td$ z-z;G5zP0F832?;lN5T^L(5Mql54u00@6+!oUbIF0zmJZK@8&K}AdbTtbV9spK)jIU z^GKw<>)fG(zuwJ~Dv_1$`#|SoRZeieqID}HW5%W+DDeEYAm1FyRiYF1_pic^W-QnJ z9Dg@PCKO|sN#OBUFHI1M|GJCBWo`iM;fcn3BEGL7hr-?$b|BR2da+6d37oVYJEJ1* zr!LpS(m{|7qTwsIWLDb5%C0R{HvT-Xw32gc>8n(y*Voms+7dbCRNY)uV7#jq(cBZ1 z9rmxM&ZA8_O@|OoY}~Djl#AwhGM4L*q^EFjK{qX?<g~~d_k3C82<rK6#GZ$TE`#pk z3=CE~D8}S^MM?(59}$>p9muN+g@Gh=vZ*HPa-;kG=ii3#O=uG016z;0MtzxkNij6u zqhv*`>k`I=4U+p`k3^IYB&E29alKwN&&wU%v*C1ZI5l(rEQdta;buH&&}gA(BU7h; zU)v9{_hF}1bK(|G1YOHa>n)#N!tL2-4GLfDtP_OYP|BE87VvVH`id@Y)0o`zCg?L2 z0}AEx&Wxb8Z)t*aZ<JbHHVbVSc?Z(0$Ak*Y3?4s;f<k+$uaC6{#)@S3o?v<({`C=G z%5hRHi9k$_>;O6VBGQ_>uD2#Htkab|bl!Mvi+h(6_*!N<7df5HzrFEGRiJ%x1hfo= z)4C`Y3u(>_ZV_FnmUpI9P6GJlO?t;xolf3rgXpFkttH^5pUDeuf)-4#wS@{>H@MxJ z6+^n_ad5mpBmXp3ysa)V!E<~v2u2se3_Zumnmm@1aounj_eUz!t=qO=Bsb^ES0+k- z6v_PdE|$DmywW9tOHRBFTK!flq}B6PeNEJsL9F@^?s^WszExnGZk6F3Le?3b<Z9P* zDzj>JNpZeDZ9I<@FJ<fT{NY-p`O7Usz?Ej`9M9q-7|80ajz^Ky9!WbFju@B+jTyf7 zv+h>`evke>s%Ky@iAg*ZbfD*DhK#R|1#CoP#%*3BYQy^t{=HKW0C`xXS_~XHluZ(% z`JajqDYh;YDIz^|Q1^-+2AriiCiM8YAHNpl-k=wqB*ZK-?S`R&luDqUGCVrZ5qk8p z5TQU!>w(Gfe|MsBVq&~zRO>;>5p0pP0Ns?9ga}`luhj&Z4U<+6U{9N+UCa?WKM8_X zj`$7INjCR1>lNJBX}S(8{D(P=e^mJK$$e1X!T$SW#Iklscei6~DbExn;k$B!w25N8 zzYh6Wogypah?<^#AO>13B-m>=9I^p<f^dHq1O(X4@fN=bCbJ~Cq%-uO$mebR-UG+0 zLc|4yFfD=;v<fz^ApKP6*GXXjLTP6bdb1d(m-+ERG~AABIb7e*<8%?wFV+9FAE=4T z-Y$#aO?kjCSXohNApY%H*QPRcKdZ8$qEf3yy+b~9^h!#{edlD2b)v~`gKGKluq4?d zg$mJm1}2M)f?=)cNhY7p?hf^k<6Q;6h*JQMA5pA`d|>o%Y_9?{t9SAD#i3D|q{gKm z+9ve(WL%~pSGwLzP$mO~M<^Tjtd#DpNO+CBj9eq;<bXB}1<p-LW3}D9PPqyr0VYyP z6!KGI?b!CJ8`|{)MGr?=NaT~FOUtQ9K>VZ6R^}zeG7_SfB&KwVBxR~{TnL-X={+=` zk>adUV*0n7GvcN$54|eI_>CHrO8ZmR2f><$5^=>xYZS)v=iztkWgRETchKrIH@9u} zuA77h_{P(>?^hfpImIK(S8f+Mg1+&{22?`^4(S8|u2tBlDl1>98#r=Tvlx)&ipVW; zMZm~~zY`qK7&T}9sd{JkB1-&3eHeb^Ggegk*J&=DwrigQJFuEz*<JE(uGMagHy62{ zEtf<-?kk+XHfYcyX2?nS8m1R#7JUA^71uUU#%wSl)&G7A`s=eGrd7!S^luAFcgX(p z&8=(<oP(aW$J)kWTfq7Yu&(zr9+~g$<e%D?#CaNkNH~E7_#!5ZpCFP+cNy%_naIJB zR0=z9WZTy;dPDQWUp>RGT**^&ariOKnRkP%`4TIY$fEBrG?7cOHm9FF{c-gNgGSr@ zDl|9Xx6A5MNa-Kn`L~0s6~h?~xfXf~R@Fp2EhY9F0y7E@(AJH6ZQ{;afyWx*DU^G% zFA(Wkw72qH#63<D3_5WDvm-Ar+{lMn;tzyZtSJ)Z5Z?B+cV${Nbtk2ga?hY&2=KYl zh)1bdSq1q?Us&BE3Hk--5F=_bWZ(;HspB5cx}G9<W=H5w<0IJOB$7<MV`QWFLf;H2 zZ^K4%tDr=Xiz7opZ)fk6004skX-~g^!d<^@v~#BIpHOkC70&x_c08egKpIF-*<2*$ z;ah2TJv%bcPQm*_$Gs^9FgR&6Pyr%3uY|t8gVtQyO;FxKQ6Ba`!vT`lJ97WfcX&@+ zpYk9<SE(v;u=j9=AGq6dRhUH4ixlJPdW{F*=>FM)^u+nX&A&vL(t^`fJ;$3OFDe3T zBuBvd^8W6XsB2mh<cS~XmLMF+-qN4jiPNZ7RcaQvl+ZKsePcf}zn6IaX;AjN-F?7; zvCyH?;s?B{A6G2pGRFNdJY}n^cNRK?>ZgnSh&;;Xi$Fq@dhh=28y#>^rZo~CX^nb+ zQPO3h==&(k#_%iZREtXfG^x}i`U9KS=)t73#ChuErYim<Y1dLaM@HH-du5`-Jd3e( zQ@fykZ}yMVuhEGtCZL<Z>chysZu1ws*QQD<r_6UsGf^`DjQ(sNDLx4y&&cZ;Y@yjp zC1D{_p_7Y&oNZR0A;+5Om$}ZFV$;stiZsXGO}+sE<oBC}V&_=_CDkZS=*`4=KUHF% zZnYbN5B{yw8aI`u-LoR@vjTSe-!5-cSonqylMyg+L^@kdJz_?Rhok%?=kJp>9!IIj zhBH}e@h20@JK;7Put1^DiV5gh8OvWNv0h%HW5@m1Da)|vnnaV?_2fnaOCleU1r|f^ zo9fNY?MnF6b(sYGH7-RhwaqKBX#x2o4t7|;eb|)OOvUp)F7H%3dG%{xR-DWdTjEBs zs;zQ1Sf$X}{Xmy1e~6|hWpngowT!xc+9rk2Y=4eUERUY)BY2Sq$1ySdp(5NNveJDK zt0Aub=2O(4t@3lp*+wmc7D1rhT5lUav1<6!tkkPo_z&xCBpW=b!KJYP{>A3_;;+md zlEPRlp_xjwrH13K4DO1Ht0jZgUQIsF*7quL4K@3(!Ioru@aLLblX(WKwmFDxOlnF8 z@_V0PL$9#B(VvbK?mz$XdWi&)C`DSRpb8K#U~)w?-ftEaTK!G>v@YW*;X%9=56v1h zPyy|^_3W>}rmgKaCL7?CAR<FGd99YZd)x;vA27!zh`RLM8)xnYD61ok&*sX(jZln} zgHPV-s@0-*f&*P5zlNXJi%j%jL|EG!uc-??1tIqy;n)h`Z`z~e3Ih)?N#p;)NE%!s zR+oVv!M;AKi};h1cv1q(5%UE9q3kKZ(#Cva)x$#$9qg`&+Td+xgXZHqP1O50+rPXA zj_g1F79=2RXFw{9CW;oNdXEE($@5P4a?WbtAxS|Rma30QYU;lb)`?T@pO}y*TL|q* zfeDE^c+%YdqkI@r@)vp6L20-?d?KzfBoFH^oI&Fj{AC99%5oja9x-zb3C-GKogy7K zswb&*$cmF0?!o)4BH@J}jv4hPUfVAWm1nS(W!H77&2`2L4d)Z#vgW$*&1wlcDJD03 z5KXU&f%SK<ltOaD)KR_j6wWI1!d$uN;E4p0lrp}!V`peSbE6jVE9_yz{v#F!T(j*+ zZ=8h1tP|$rV8eiMi~w-y%~yOnv%1XQGM`)XuC*8{eS7x{KElpiuk&6?5FTmLoHefQ zUNK_+Pd-Q@T0n42(Ce>k3Y=l8BBl(<isS`6a;cjbHu61}zdR&Fg)Q!KqkrEX9w#^G z2Y`ogfiLf*UPALlIWCVg8HCqRwI3|d0i{X>u0x@UhDC}`T%o=BO0`QJ+bvxB4wX-> zc_)fl+2a<KH}nI*h|#g3=tWDy=v*gO@3%O0wW(%kch)TAkTT*@ZaIqdT0fz~=C7ry z0gNk1Y~pWRYb2(&3H5fF7Yo6WMT+6ydWcyr|KS+F(-p+m%&oSHDQ!-NIXAi9tUJPQ z^&CI_8mf)<#ekKfYEx9IpqQ>sW;n|h8~P>VHV|7A=SrJf>TPK=rhK7p;&`Drqy4C2 zaj2*e_G4X;3epGtACdN+0=w9n+yp~yhw9IioctbJS(ezCGVt8QX{8>$YbiD2DObHk z@9-ne_<~v$N_l^t#T;*#`85>RS8N5lCnG0<w(anWt>16k4iZ{@H+m~qg*NBwsvZ2= z+zIwDA2o?KJ10{PKns9|>w4Z>mEk%?{8;Yh_i&TK$1)@8+aYb@3b6Q)Z(=&1zwQsm zet*T7bp3(|#5soOfLOzsHFQpguuhoJl~=ht2)a-fP#P&1N3>S1USp*Gr_U?N6e-kg z&l+}LDO!@mfwl_!c7A~JCjhEQx;xNhiBS8Vxqy)jQv&K7qWdpl6d<sSE)e1l`ZQ5M z-IeqvphOx>oiSe*yd@EAylz=3=m0Z8`a?coScHM;OKa~Kq~!48p_~kViK|Gzw&{Jc zOT-@8+=_hSA`^b55Mx1(!_^qUKu6IMW2z@zs0q~kF#mkDeLukKD3rn)xgm$N(O6>8 zP^qb&fm7BPjol-xQdh0hl+k}oGTL5VqA%Bg;;mGX?C~Ax3-ONa+T6DGJZf2p@u|w4 zAGD<W({O=D)RsLSXeA%`X1AOFNwQl`y@lm6i_jq*vbB8>%&tr*WjpLeI^%Yf0@ylQ z3Ku3d?ORS4rZD|}vI!K-Xm1F2K0t)vielDH3LsBcpqq&9|53%<i!b7vgPxVXz|5#9 z6l9k=!&;r>Q1SY7DmL~8`Ps_qhAepV8_idpeqFLToRXhvOed$X?(#$CA2G>az8-(+ zl*F-im4i{tu~H#RdWlT+_-y_;%NvD_mzc^Qey8}N3J2xd5Z{0$z3e2sJNXZ7xZm*E zL2j{@OMJ;m#!-S|>$A1a?8OlMRckH~c)<@`7^i4(WeEbBB?N_V374UaP4w1$`RJc* zvNm?Ht2)Rl`Es$ojXq)?J{f1WF#4Vp?_3|ydMSYCoq6$W%Ox31{OL%Q3b^qSaGY1D zA*Ru}SQ9|)yQPlNW;{Jdgltn^Wm~W@Yf(Iz_(S#_zn#xm8~Gs6_t*~1KOP!0-!@1M zI4I~|>mAtI#F!aA&qZA9#ay@%J3`>j{Fmrmnrxx-_lTL7py!@?jc1lSpyf?Mae4<f zt*4ADy*tFMtn6j+H!ePr?3D1tXqSXW_wfR?;s#qBpR~#}L+vzEN9;2hs+IA650n2A zPwEEc+&frgB0J}qN1H~UrJQ|v&*#)i8&Q^jkDAbH0%_BcqYkW0WunE>^8<1#u>4oQ zzt}4~yM&qlxTz#24-}@uzHnd`ZXgTyw-@;ly31E0=m4E?a!eT7v{~7sM1gGKTu9^W z>AZYg@f{`bCsJ$(tRZ)qK%ECK3WEz1FokfzBPa8AhY`s1K*97#Ki1}7)R!*)Q@VCF z{&u<mrZAzo5D!MExe72sP?#3O#XE$}GpvwYSn!|98+k!L%V^7iv443WIk@mh0gpsJ zAilv<fK+%U9SwXWd!<fUB-Rjo;=WDeE`J=k=5y#tOdDZO*=_{1L-Y`wc=im9@=LbO zaOCIF?6}tJZ6hW$9Wo+{naUq)x)25k$<Tv+{MB$A6@gnfl#vxEWgh6YVm$^oPR02C zSRO$LQ&mu<U`4(`MWJ^n{dp=wm8N=KB{hfD9B?pJCtTkqKET31D+FzJ%uDrz<s2{7 zPOf=hVK7R!Vo*I=%DUiqqABiCqveHR8AC~3Nl2aQSoyfwukws5m92)}tbt@7F-c!G zi71uLqufG=UQQnGFcD<l(aDUY+fLD?WD^)Ky>o>_nG};MfzE+RVBW!07LVXT_*#~q zTr~|~T^F_?@<Ag@gFS{XED!h8&-~A37xs1UjMjl^+|l13GUi<+t@`n*P+5%kWIFD% z_N`BDvPDMh!V{|Ai#)(b!+C5Cibo&64zHw9#%P0&Up+BhqJ*3>#iHQFoDb_)KFv40 zSH21S#z&FAQC((9#|Sq*IP`7Ttb-efLC0u5@8Q0Kgb12}e8OUKQ=Vhu*)|}0Y$}}h z>hjv#613n7&oGBZS|9`6+jbx4f|Dd}d)oI>ysXX3G0*A#XZ?|v-Jk93ap=0)m{%t= zP~L#IwvBtsYqRKUfXI@Zx~GGW<+eC(EGN-ncC6RGw}0OL`8Yo)8QGSJzw1CDn{!^V zP+THSg5Hr?)9Y&P<Q?(jS-a#B*zEPvy*_j@h|gf0n^V74`<RSlzLn?Z^1v}sGyp^? zCGlzWe(sX=5q|7DWj*=1Locj@4KVGUEDcYnfUW7s+X0$5?V{RXDB6<)_*L09_^;5j z--^|W{K`F0-M+-O#n^o$U(Y=Kf7_FE-8-$QcBva5VH-y&e*FH4<?;-#3S3c6oIhVy z<ivlpPM^b7)K*4IdGL51^zhG3^6-3gpAYnhcytQY_}ivD%y5cG4kE~mt0`g1!9qlO z3wfaZV_xe5O<wchF?9va-cvOtAs&N5AjJI}S`HGTnKa)(<A@R1@28q#3ZC%?K1_Y( zfo#gbHwDY__9cPu`#KFO_hg1agMSt=(S666K`FEs@605y)xevtA^N<*VB3=Xq!BO< z71z7n5-e%(8fAn!ACMQ-XM2SPRufew<u3xEoRn9L9eA*ewD$GTfDeg_9&ct0+`4+R zuT^dneO_EuC<6S<-`q!}jPYAz_-#X@Toz)76wXh$IC++vaj7`HAR|cA`_ry-qXc%c z3nd2W79aPmb$XS5y4S!O&$&YTGy|r=lA$EKF3r0@;kSNt{RdW)M?^C0!G?{LbIf{l zD^<RbT}@kprE=7VM4TW6hE+HzJBC@<B>^=#s|oXcngfoR_vL0AI#f)rV2!CuZvz!E zg$wm-L2lGizRPH>jttimIuM8;&~VXH_OM+3oxlmUB6USkmNZEjiD!4(!`6e}ck4Lq zv&|5Q&Q}98HcVAoIS0qV_irKi?f#F$K0snBZ(cwv^COc>u#}<9YK3KXXr_6abwDtB zYw^?#o2ZL~Rr{^~?_E5EUWLDHaCCtyPmcRh60uCWs>4^^&1N<a#bXY?^ZnV`qSCC8 ztH<Itclb<zj-9i8=S6U@s1}FVOzW4;Dt~|NZkg$JAE6aVZ=3mJt<)XA4UO)K?2d-8 zzoF6>K`J#KqYv&D>x*4Yv;H}JmrdzqUAkwzbF=+h9SvXDS_?A&BJD=4``|vl46F^+ zRaIJJo!&|>0$%v}7_lw7U$y&tgUy6=B_&A}T0pJJ%l7>Z6GARd%8q{3g|F@p)__}| zG6U|JcwsL&+!p2ELVbsB(%XkKKT&%08-~Pvl0N98>*Qih&)wU*H^QhlRQs~nrs2*p zGPg~ZOC)Iy{~0I}dGcN;u<;(NoXm3ThU;OLR;v?#wz2%IE#2MrzH>irs!nkkal~p$ zueqoiM<SrsjRQ7gpEtB6(Kq2ZrDEbn9c{On1@>T?uIy{k@}hwTPEn!>uu+24<cE$b z@Z)tF6J$6#dQQ@??@<w$DA`+16I27Bz7?}u@6>E!=lp<oVbFxOfE+^S!@!#|T^B-x zYA+yy7z<wP3dS$aV4>w{>Fl%JQo8Jz*}9(OEM%_vxx+xl^;Dv@6F6;6tS%h1)L4wK z!ZDg2BQWt|{+BI2!8!Nlq<G|84DcfLlx}NBclXLBD_v{q_q*W1VUH%7CBbN(6`pss z{ZR#s^H>!XVP&p~8t0}IovkI^`VQNIUx^Fjh*HNHVh5?zWio{w6^~CZb*)Ge8Q4P6 zn13-fJ9;_;2)yKmW<W>5QrfL=kaoGOm#QpjeU|ANQ@qAGjP=%S*sUz7Z&^E&@LuhH zWCZa<n<5wFi|GqHnYA$A2u~RWt1$jnC-SQuMr+3RfA&DW*}OiTAD2}f3s?25t^wmL z39Yik2L<s2QxiN0V+lJ0Oul-AZq9%>=&ly{iLT#Ds!KvfFokmmb)|N$PrOV!FN!#o z3}<`}=57{49r7+m+YQbh$2+|T9f0VHc5D>R=h4gfnbC{Z-Enq&HJXF0#_LgN4vsbw zSIm-9mwxJ(8AXK$FqavJZIk|+!`Lre!Zf>Pqx2nJvX;c((~awLoodcjb#r=m9NwOM z+h%dXymxT-pF|dK3_NzFv(SsC-v=)R)tJ4HxC}j&y%JO~wlNgK*R^t7G=G@sUkBU1 zJ}YAA3$3ghZ68*|*Sku87)x=M)!AUVHCq(6)IQgsIo`A&^64`_S#@mXnDod)!N0NO zMR{@(NM*op%OPs4GsyJy^!7;55)1yD59&AgJbsKQS~DeQ`@~KSBx#|CKN5>Z3@v)| zSfD7UNq<oSZRhBNs#^v9pLzbbs6+bhOr-`!JZ_h;VT`vw<1_bhVGqsTS5{iF%#dBl zoi%?xwwC+)!}S*;Cm^4Vt@5{GkN9aZqCS7R+oyl^oU?2wBaPdj%SJKvQ(XL+`A_F3 z=XA~!A%}pR<|PJ`P|I<}lexc(ZBIP@E%!k^0Xe(N<VRAeAq>Y0%&9W`RoUiMVrdX> zR*?W_md>fi)CuJTJ2mu^G^kOmVQ!X*)+TF8uGwK2|4%vYSI5uSMu*6XmqxG|6draK zresS426O4>y`iRD{Y9NlK8#$t`1v9Mx--N31$MXf&C#T^kxk8?9M(r7XqSr)D7Iez zT8ahFS^u>pw`nMGRi^gT==@9LOROU3>tBE4u6XXYZ8JN{R#<$?%UpSTse#+b$!bb8 z;rH$RLGw>}*(|Ga;*EhuSL@G4QJT31yPMLsRn_0bH{D^9@=PlOc0a9PiHl75uFpw! zQF9dv^^l(Vz@EBn>)P*&ro#V{`?$BtWh-Ozxm$haYVfsvpwFc0X<v&oC3?p{2&ha5 zY%x^ub%GtO3LX1UIgH{-&8b1c>G<AGo&8x$W><@MpxgalE+70#3kFI#4M}yTjV|*( zVDXgVid@mkS8(V1rP&nR8y6YQhHuXr>4Dz#@M0=kyvB@xjxg{?(Qk}p)40_Lfeof} z-zF#BWhC}xfu>G6E>sQ9u}bwYz((<AKIL0Wk)4k<>aN{T9IH=At2vabySZqj-)mj* z|3pa4-Wln^g>5v@$3wAk5Tu_$?I;)^+QqoP<-dlcco1F=X7%KlFI`f}`MdsNVW!GC z%rqCN!cxCA>$vmctTp`5;d-jOH>){Q-*)wNeT8P}jeS|R41vvtL^2s^N4QV)WF|Dv zCH>DQz)!sVXLIvga{jAs&PuI|4gbyM?L*Lp)(4FN(ws1Ax2e|cEid=E{5HQZy`P9? zF$^>}>F($eg=d}}k=gEbm456|Q6*hC!El}fp>wfywZ@0%qK!2_{n4eeMKbL{H0^5@ zUEh2W8+tI?K{VJA22BicMnI7?fRyRN!guP2Olys5r}M?Qc&7o)HXZvfGdv08*(AnG zjF?A=yy<&BgSX#aMN^m0c6Snn;|255yD+X&yvI%z)yXAi?dUm7;;`zbtxFy8O^zUw z`t)Hn@^MG{39n;{H89LeAXm=tuNvTimcM07UtXgkk<BOa(Vfhr2q9?Mo<TgU<bF-= zTYYNMc~e~rOU`=uNx$_AVG_Xk2gF?tTsd8pPU!cku=z295hBLq2K~s^sFa9#BB1g; z$yS5{TBN*Ov9!y|cmNEo;WE>VKv39u^o_X@a~!?6lx)Yp@2rQG3D%XQ9P->;Wuf8? zcMTI<>7qQAh`NW+A0>8*a4x7!RO@jYbjS9l?;4X4bZ|^rl0YQ@7}(dNjD)EAMN*^^ zK&CEbxZY+o?sI@k%rup4(usSpZYNWp@_)Ae{NEoPQ0^cS6t`p9)A=umF!lwqt}0w0 zyAXw{N_pigo!kJR*s1i+<xj!J#o)jd6hD4p1fl?@A}w2*rsd}4NEq0^L1dh<C2mZv zf1&Yq;~jb)T=K@duUU()aC;8Kw$e%*rDOVpc63WKq%y79wyoAHJ(i6BRJbMQJueGx z&rkGu8R%e4_OAq@+X}i7wZ8A4O17n!ohYW7XACDQz)c6Z8h4)DT@Og(Q(kFJ46ps^ zK=wHgna@l{0+xz$F&C1;8WE7w7#SCz5KN7PJqQFxt@CG6YCpqm`DL9Z1hfuBA~6u) z*WBF$tA8A7O4G^uN}JIVUAezXjvXP&I+snE<<W}Mq@1Z+^J!={wu$xs-M|qkAdj2> zrDFLcKoN2k?c>|MME5Q~Es+)0FcyNh;n(f33fN>EZ@rZcx_l+2VeQaOq0*fa6X&{U zQjjU6F*5B2uZEihy*w`m<kq@a@r+Ga?I1fU5_-yfOU>~{9UqTTw$~U~y_oFCJrW&F zkSN5zws6<cWl;FLa;7g5oUI#`$=P2QtReCsSHWS;cZsnPe}x?oyM~wGw50Y4_+=%O zX@z~y4@)S5{S3#}q{b-M$&|-ipWKXt8KXP>eq=vNRh432jMkubT0+S|`=-U4`rltT zP!k$vz$89${6$wC!hflf64Wctgc)}Yf;y=|*^I$J+b7TmgSao0Sd?mSS0w&Z)se;d zHOM}|XO{Na%z@}@^Tv9T-zJgPHZ7ZbBb}O9&Y{Rlt7xhw61LB^F<_OS($a`_+M@^@ z+ksCC#plYe`jxVND!P88t_1t}bjE8T)3;0)w<57Q?R%Y?p8G0BZc#cP<Ef2s>06}p z>Y#3W*pqA-GO1EVQiZ|7@}Yn}aFLaS?OSPSQ62ZS#eC<@S{i#8d=cN%hi8RHp#F*S z=BP~961)7=-%L=_!x$yzC_dq3vE=<I5SFF+WOMkK86qQXhO;u!YT@&O&iJko+T&pZ z=u@%1W3D$QXP4uStwKLf!?$}kzX-%TnJghzo8+qyD^nlW%r`Ch=~3Y|kAuHzeAe!t zm3hI0|GHA(_4qp3!3DuVmOKg1AIkgj=Cxas)UKA%FN`$8?ae+4Nn9ikQ&Rk|q*zy! zLVdg)>5y9)y&EbEz>kY&{D{0ImVLR86?EUNN~$|*L`Dyo=shsWhtLU@ZBT=*{JKym zwzXRc4{c*-OQ~WGoUF$w`gsodv?h^`fDYh_ENSwhIGr_MO+|dQ<BFbUY2c6&LoP>O zjG7MLM@@;CFw4ssC?#iCNyJOHsETVvXpCK6h=qaCK_pTS>BQQ%TH}xR5BK<=cFg~u zYvRlF5m3IJ|2)A!;SoTn_BmgAKG2zCXy++qZvx<tSc$!5C49FIWq3k1Vm7(<{M>FY zayUfp*14wBeNyE!E!wPS#hF$NvG)LE9Hw<G<skDaf2^<ajV1G`2u9ldK#FDezi>_6 znn}LU&Mfw8*gRzzavZkim1KMuBgnIy$#W6j4BjGH2oy!RaOcym`p|6C%7cx=r+CEk zV$TgjYR&E*x7a{@t3{J$pdtQFAy}SdIfH%SOYriLNXZ2vDtc3OeXpsN0_StS-6l=T zHurQ7H@jpiOs^s42zRDuIoUK3W$>EAL|sNOt|J#W)ez;`%3h@;&(g{%(JdMWDW(-+ zm|OX1;7sQKeRzxeu-c@$x4PoFaIxkedB$XMP@x;ElsTHfo-bpt)TL{{BXur}V1-vv zx)a5EbMCUsBAqvl?{v|IDCJ6$5p_+#C7g+1rv$#lG+?~`FSgz(I<o(X9t|ee#F}(C zu{D|4HYc`idor<Y+qP}nw$X8Je}DIXAMRcEp?meq>2ubq^Qo#`ReRS3_8eurd#RSt zVa8?Qsw2%nO|U(sh}HmIHTgCXx|c`<c4@BHTat8N)<&W+t5i242Nq3iEX&V1u>v$$ z^nGdZ3E5gPH?*fQnWes&uuh3ywD*Y4;P{6GGLMV>fr#VWfbRimVU1uC0UoV;9;C`L zZ6cvfixTW<2aURBWm-j1)c34bG;5YtzF}V<4`w}|L=W6~IUkS*Oxxg<!p#-N1mZw! zrcn_BbnH!vEOcDoaW@pN`7<Cty;D%XoaRoq;O+^?QyA=lTn1u`Dk!zsz4eU*ESfLe zAINCqXA`SjUtA;>H1pn9$C^Sz&$T5x6|1bYHsu<2mUuK(NSR$(Wpkq!7o5K7y70V} z&0h`EB=PDNdR`u#K4`ltQ9#X%fX#VIvL$a@;|oPPN>F4hJlL$X#C>RUnw@@~k@K`k z^91WuuwUP`j58siJmaT$^8Nlf=~T#cS=DIev2n$d`6<qzogW;L;>wT&2v$m<nY?PW z%^fYZOjy2JrJ9sWhJMXDL-op$TtmKfmLy5ldw?bLyM>GS2kKN_kdmRv=0->!rY0EZ z+qa1r$V-|KAFL`zcQ1@jI$p#x+<WzB42p<F0H9`qT&AWn?~s$Dc;uO!n>~h}%HY!R zgc&SPxk`>hBjxDNo^7i#+hl?!QT$2l1i^|7{?JcXNTx07dFYT2|E<NP(sc}+Tg4*) zvDWtm#wsH;{ai+J=AIN4p9H187b!;Q6Qyztld4h>b_@8);3dYUCW#pTOiw@^?Si+u zqe~s}9Efxz6^%Y{Kg5p<rOIv9FXbMJQJ%qb|2}xSX(CE<-vqjba-5<whw+UBU@2{+ zPdgkliC?=)uJkl72<K@;&X8$2^&qUS`CHcrtq1idwC^FPkIr_1YCz>g`E#NAPgj`* zE~Xna=FcX<_JW84qlXiGwijqwfv&*WxNF#krMO|owOAA=W-NbzKUPdX{7bJZ<Kz$3 zo-mQ-_h7&W+W$#EztlkFW!#l75Kea642M5>?R+S4vp9eu1N(yZP!{bhmG}OWiOh9L zYj%av?Tox|KLE1{S#7&IAKsRWy*?ZPEYP58?GLCo^(d5iluSKJW?$f`2p)Xw#LxPn z@qRPWx#4_Wuu0<3m}k~+S=R6@8|-#QAVoKnP1t!cD9x7!3~eHKce_=%;^a$vPR07B zP-%W_VwUaR^31}Mvl=P)1aO%gi(VR-SrTu1$kIU4GR_vIa5zyU>3o)qfBW-?zP(-b ztLe~Y_)wc2@#I&f?aXQSU4`=9#NgrpPWqs~x)Fdn!V9N1k;y6pt2EH-7AZYTqGb7k z&sH{*8Cc@8IY((0HPk-anPncq%XN4dY~!P*A-cLC$wr;sug1yJ<d1|QAX28LT8DIN zd>@fuoCB+8ZZ#y5u_+*FWpx`rlG;Po1dsN?9Fc5=UO<GK=K;D~xGif8AG6^^U@Qe` ztafcOAC<%kHKD)|`i)0!*9`a_stJOh8y>k**b=|!cZR2%@Jbg!`#rKGc+F}gnI;3n zwXqn*j3Nj+!wa#6;L!v8d0{e5%8+aWFL7nebP}`%+j3?IE9THjqdiOo;`+4EBcXR! zxU@0B&F(Rkaz*XRAzeXr<Dtk;KG0luk2ox0f<D7oIPT%gl)o_aLnbgpS;8KR;=aBR zf)bDC6_@UR*yMlsHec5qlw*9Lb?Eq-fB*^MDX0}C%wNt|FV-z6vY3RByv^kr<Z?-R zS$L(CB}Lw5EM50l^XC|tV|-&j84^@os)?w=?I!owL$_NYgn!+V77U1JcDH!}dY3z+ zm|VEgKWOvN|0REoc~L@ZkPh}4vvhi$jHBaqkt^{<e2hr^(>bQ;v()TsCA;jj+ULjJ zUhL%RjI&8LFFDNK*!p@yb%~hcZr;Ee6y;q2E%YF3JkN_uFh*VsOCr`bGkmybgc5($ zMDbO}v1WMPSYlQwSBy76SQ^t<p76~{KRu>dJC*kDh4tPYHj6!$ktX<=Qb(og1aT8u z>c`yY8%i%f)d1n{dF^%O*h)nr&M4r<elCZ0RVPg5-Vaz4#6dfOh3F6T3$H1bwfYx& zi*vCmH_Cyk&-aLJ`fos;l0B77eD&;3v0!=$Aizv2O}>4Ca7TiDEJX6lAo@(6Q?X9W zGshS-Mm6x8TGaK~Xx&7hNrD!6PT1p{xs^VbER{G4M8p?U75TrHg@xwqO{S><lXS9I z63sbuhsQ6H`Mcjmm@E<Hhbc>v>=qd2x#({EGay$$r&MK<IA*bEQ95=y+imnDE)c!a z&jywL9almC;^E_B`c$E7w1_bH^_@lK?lkXR;iV|%6O}Hh?-Z5h(=+48%h-F7rq4mK z7~i76fZRT6s7B2y9qP6v>y01DBZ_s5T&C^XyT;3PXyDWJ7mKGd#{Xan{r{0Q=6g6% zqf~3Xym+Mdw4F=KCwt&xJI0K37c$(e8`6BqOiwrCqiGL&;?aLSoQlr(_<O)Encoz< zFt#_j)!wl5{D>wrY`?@Hdf{@;^(L{{_OF>iqV0)Y`K&v4c1Y^OwNv{hma|ZC+35AH z(`qFsdQ+*?RdFrKm3P_}Y8}zbD97h&^J3;0!4Rv#)8iVmG9=Hq)aWht3}wrQI<qIn z=4VXwFM`vzBOjP+QkAQ$68A^>piQ*!f^bKAU&J^KdBM&Qr9>9ja&e?Ff0%>X-)M+i zP|uUsYu{eN2!DI(J%|srLLm!?O^A&3P1m)ObcI^>4~k6g=>+lg%wapMGE+SnP&^^H zJF@#H6syUa<Rlo%Q&0b$<r-3x$No+vbZcttAqZHB2yLNX=hretvgpg2Of;nFYNnQ8 z_XmVV-wa?|9r^X9)Pbdouz)oxCRt(LHHD#b6UoKUI<Pez%WXe9cD{STJ{r_ZW)#-G zFn%7;Ps@)$YNPY*#tmbcAs7`6STuJUWJzqgAw-5`YV;-<c2)*W9sVW9Ot4TZQLblx z>(Rw@ZVba5qfS;-rM|Z<5QFFJ6}=(^?KD(;;3)tr1~<3~UL}q7^&$m)aZo;7pi*FQ zC^G_xe4mS{kEL=R5eR$=({bL5Hh^we4l&s3-@~tbm58#Lw-aIR&imsTPxnZNK==jr ze{Mv}5A-v}PxXu4;~RguFC-6j<(9{Whgd!Z>nA51Y4p<C5$`2tq+R}@T&Zb2Dd*#b zmF;|7GV3#fb3}qOJZUBoTG6_-OTq6YopzlgIwv{JXKK@7Aw2fIsNU!DPU`72ropbS zhjAF4IdT*{O!0lbd3KaEmzVp2YSv#IjrRwu@vpRugf9b*DB7zy4)%rvXh_Gq-r4G2 z<R9{FpIK{9Y^?w(SG1AI<R)1+{rSPowxf8uKBn<9ms(H9E9nl$f~?&`s^n{!SSsV@ z@D>Hqt3Qz(_>T*jP_UC<1LSk0qJb*~u^gc!cf_F0R~bmixXyYskq;~6zTe2J)J+`4 zBL)(nT1U62r#^7}fe9p}G3j&6{mjft#4w{c$2;8rx}#tVYt%`e%E;Ik2Mq2&L|T>u zi0j^=B=lMds)V3`h_M-DSp5p9JM{tqTzf+$RXuI#pRmEIR&c2MJS3NIq7lzSW&ie` z|E6XDB#_3KL1VjmRkTxdRL80Bi8d;1?!KKI=})^&-d=K6V|J)*$><uTux$F}i)E^+ zN^~d`6=kZ0ii;MBiL1@JyLO*^x@nXDUUld5Z9De4x=^lY9|#OG#37$o10KW+FdQKI zVxrM8(*X9P7vGH?>xe0EXm$SX4Y+zO{~3Qh=6qLdhM>4BP7Z&Ud#<|UOTQx=t3QF* z3x@}VlmDl30eUaO!u|s-trqhN>o$?y1m(BXZIkC@`YZm%(Pp!T)SK7R!%M?cYjL|G zr$1aRFzGK*h0?PWf?~xQK0rd-|1MoMuQS&8Sc{F(oI{GB01M4SXCl6pzwl3=Un%LV zA05($?z{Q{08i;+TZxG$m<%sr^5SkM!mcv!<{;$e((J2B?P>Gf+#YQc^EU6RMqKyf zG_Fox@j%UVPcQOmusOo}z5?L6LZWP>0vEkwLFy&&FHFqg7z@g9_SU-F`EAft_4_Du zAUtEr*O!$Qb<i!`Z_QV%?`o`4O{F7EloIT4buxR9w2=Ottgr=QUKc-C=|8VBKc=!j z@*-vCtP-VSaB4=$?DDm|Z;A2HQkZ!Mu+(m?rOZYBn(AE{j{-bvhpkBr4GZ&OpIAKM z+~Pp7=fMAvsGZ}Glu0o6;&%=PqJ)u^m0?AQt=0%o#_PIiBm={0lz&7YVPX~Del4IZ zQHI4D)3>M@*l0dYkT5J=%Hb0Aq>7$fl;$9_*u79*`k(z<Eh4GU$}AE;73qpqJL??G z!Icl1Ie@;i7pOfBOy4e-KZB$DR=!Z+<D%W)1F&u|X3ju0J_yQ^h340rnQ5ozLYtQa zqvtGH?;UWRt7y6#xk$I(?L<>~$}brfg=bJfT=@ST98i{hf|ynCVA(vS+t1hcHjDpV z>GzfNr(ew`l`Gc*F~frkOtb6zdF=zGT-M1f&?U<HpUR^-Ht7Fp3`js{+UdTLBitT3 zk~K0L1$x&ly<c{;Z2I%6L<Y#kYLA;u*E(4uuQJHBH;`Xk;B}uTNqDziHF#$>ojVVq z!dP%0j`e-l_|DG`99<!ibzHFyreLkB+Pn}o-PfJ{$26VX)Sj<-X_j0R%-f>ymkVie z>xDII1AWwFHFjL-vYBn$mhsaaeCdvmJ>qI*K#c*f)|j(3U3q1Ct(TZR{Mv7;FKJf1 z8GGcBkbMZhhvfjl<GBFgZA}6fE?tv)(A3H3!a9bC-gu<JsYs!5p))cLnLV=39H+5a zBTVMd=sYcy9cj-Re<;HY;9MtjGK)+s*6zzQe_8Jh^rN|iq;Cr0nCJL3>l7|GVNy-| z3~u|DS%Gh=$>Z$1DV$yu`j#fP+7R`7f%!_jKPAw4|4B`*t}3NTNX0;feZ4}ls?ejY z(BcTWkXGuDyBuEqjoRpvI@7R(WOHb%^BeiVk`&XSi0VLssglwiruYR0@^2nR<w~n8 z`$)ub6F60ZK49~kLyf`$ab!vTrmilI^SRG9((tiO3&9U@OY9$&8m$V6)Qi;ROM03= z8^_8p1)>)$m8o=F1LP&;6<(0G^PzlLcwQ;epLt6h55koq?)duiAR_XK=0~QXBqgKa z&;EdIt9)wLiy3H!YJAKHzmRsFKOuNL&}m?Nj=MZp%X74W0!hk$F$J<}@qeur!hEqr znq_4bOR9y-h4n$9eU%W#hn!FCvei$M)GRd^?*fVI(}!5M_4!#I()zOkiN7K+VlVO^ zh!$ws>(?#klFbq1wXJOPX7V-4`y*1hz%n0bSz`@b=T1=y&4I1TMDIfTwHI>K<urF( z)u!(1WRovHlNTup?_2`gk|XK2-B?!6C~2ON2g$p>e1Txw*%OoK6ZXuLIPUxjy2>_+ zvxdeNG*MvQNj!zQrKZ++o)VgaWc;fy{XzjM;TzLXee=&yWxsf`pUfD(84Oc1HN$eR z5T1^to-esXpED8GMvDAva=$)(z+?Gq3dJuJ5-=QA3KXd7zTZhF77iWWO^g+!vC43B zob0dSGE~z!`!HTELRRt*M}f<>5o%HJ`L@3+=$&>+EqYE_%{f2y0M3V=R%V+Ab6r4O zOi2pQJoJQJvV0_=X<A$xzUBRSRT9gwhT;m%gms6*u|gC8gU^#w+&GVRHW!|LvZY9N z34w2(&w>8r_x7h;({gfcMVVHuUu#_obD^LT?%$5eJ<r<a(CDWXgswpo{cqwT1`#rd z=Tv~IP}3I^Ejnwl>zzOZ9i27zUT2_s_RnZ;3a(Z;4xrl-74{@svgmXxu4m|$4X{eL zNWy(_?95_Og+>MSExAl1aSY_57OB-})SB|<uAjB|ZtzcInel77<FkALnB1zMcL`GS z@E*m3467jIRfqb9@I+ze)Bh_K5PI9K8c0lN_@aLq+p(d0N<MVV_gqA=Rt8$gbwCpV zb-3$G{#L~;6|nQ`)OQJh3H2Y<*dO74D)lpGC_Jy2)TJt4Qk}gbKnB6^&v{$1#AVK| zYYb-__w_S8q?_Vc9iwi(<0hG@F}1p_u2t_Y#q~dB2~^gxwBS4%*GcogHJ0e3OxzEu z+$a{|CID}#(0J{v<;Ja=EEfj-5$TI8S4*<1m3tjZpn<W#hcKZhl<2(J*oOJoG`V(e z?yOhx@uk<e-pYXw>^<9zeDg|zq(!GiCC}!Pr}<T>t@Yu#Pg>4+;m=Rjoa(~f`H=XB z?a)}ss>Heo?_W9vVmm@s^aq+LmxD-#d?&H3XrAPQy3Uc}pu&UE-kVPh&ge?TToS~c z?*@POn0Un4VT#(whUU*h{`>($q<)m9Fy2Ml_doL~`IDr`mj5zWMTrrnb+*mCtG|rm zuUICUyI|3su&K^z%PSh|^xGftWR`2y+<b{YL{%R$uv9uYbJr?;CNI56P87&rhGO04 zHIuYKMaduC(I?2UV(>x#loW~R=Gd}-+nBC1X>w_-(-llGC2+*$9mz}U9*6fW{oLH| z5S33G1HsD;8^qf#o}ObTAOp;rm_{>Vvkk8GI`f@f{|YJQ97^&uhZfgoO7Ab&Is!>| z)k7BRF=N2@J7n0oe!;EKe+t;`D;IxiU-pt_fvR#&I*xQcpMm1}Gz$64n`~}^LTbFo zU9z5{Syk#ywHAqGRx67AI*p2lcXlWiB>IY2V*!9fv`<XS=(}B*B4Xsb?VITOZ83MK zI|`RSpMlX3D6jwCxp&m+$+wl!rCu<3AXZARpUsg5GDe=I2z&t3tag8LIUXbV52ezh zA4hV{0{Jb^-@bwXhs&G#P?B%H@c_(zCDQN!z^(T!5w9#35j=!~rr&=wS*Q`%146Cv z;uI2War|U;M1*6^SVAvS>yEm?z`RmoN%{s#Kjtu15ioBArf&NYF-^=8X8D~OMt&?G zC<P^*!##gfnBE|ME#4fQF|dxx@09MERAow5Yn57^MKcA5b4ti*YyWJoW=b?nhm^Y* zbLK+Bi%)FDG~QCCvI~jX7$$9f)a&0AGUW=ABn}Jej_g+h<+?UsX)T{A@E%fCI}2X` zb4{~xS-SU6JcX)k5872TSe4aJk?7N`q3KH#t5@*Wz5;y(r2XA<%zSOmsZLJU5eUUs zRII;JqImOD8>MOSf4DG7cbmq!Pybz-@b>0Os$dzBlsr}(Sx*;z+L+Jje}(8M=rO?( zRif0Po9(iyVtbq9_KYF>@(O+j34$v`<q{osi-Ul}-nw7J07^`1EfxB$*u_Qh^F?IH zYvC#a=HqHS^DBcbyu93&F2ko&{mA$@)fzQj{|wvAUgB5lKn7$g?oz2aHhMu+3yN!T zV0xz-ohL|;cUGhm#E#$IZkl{w`5_rAuZlHl0EcL9O{3%?#_Wr?aB%V$59Re&+d+mb z@+zy-Ol$m8!;|#_Rh}9y2A*UqVd&OOVN?4t0=njsW*#q)e;q})+zY7!>x?CEgj$9D zK1!31;(Ce!vb_UQ=Qz%^5j2jb1?1OFRWf_%Pp~pfb|t6h-IUFUcg*w6(;BL5Lv=k9 z-eAc5Y{BTH6C&m@P?X)w+no3M5fyiZ2JEs4{n#)lva(OFKRF~)T6WR2&2ke{`n8r= zy3~@F#@V8Psp8~tlXqv4NaIgbTCPS{sD<|+u3nn*2_GdpyFP1+nN@t_*Ly_xrPtvn zXfg`^qQ#LsAw>lplkDkylGMF42)X<%3_NHiY@YN59L9l|Ax$<{;ubpdz4ah(Fq{Mh z6HophOb!~@f3wb&349C|8X@Gba5>NoeLU24G!3t)4ju#aBD3ubb$S_7+aWWW>gu>m zAVS=Du$PX04$f;%9Jimn256gEn%(G~0X&kCfXH{h@4UbsmAyU$6lL(%9L(wQQw636 z1?6vk2Jn?(@Fl(U^(!^pV0sxz*h&V<Wy%ut57|3~*npZIh>x&w2I?5p$wD(4AIvcQ zt+0p=U8)Er9qHWOM*%QFz0?k4jLfDOO6|%b`QpJabXgD2?Z|n~uA<(ch`<L|)8kOc zjK#K0`fZ@aB{E7oTSs%n5@z78?L+p=4v__xSXyi=Byu;CH;MMHsN?p02Cx8M*m+KZ zRFrvP!Tp1|`MBBKJ6rA;f7qt%p=f#K7tMzGmRQ;)<Uc2aV<l!hRMzsqz*rc%PvN0z zv#ABs=2z|wQme<+?@gw8`$^{0CQ}{{lp$5av#H<OaHX!_&4j<ap>QNVtxvXX8`!zG zfI-qE=FX}b^*2&wrR-y^SR_KsCblQ2d@0i=aVr?8EvTAufqw6^_$R1uvLh}6O^Kb0 z8U}yTCI(T$tkLe+>#s-dwu55z{T=RYUw^wp&;3ZpD81Y-cwEnr+mdxVkc$=?xia4v zY>x$2k^j!j{m=|hqxE#~7+!8J4;T%mOk%F5{GD9q5E5r@GTf-?{G<RDB%-Ly5n1La z(th|DE4FbF$~p|<Ukg?%o~WP&{hbTYhhaa-Vmq(7R$v)NXhcGM)otL;WV%rIN(bs& zZ$Ts5!=<^*nET(xM^fx*Ms-{GgiEUpdOA<TUw)TDPI&xxKz6chmX1aut;>8TWsvzW z0-unVM0bkMKfmO~l!fm4LHnq4_IpQVY37*9QLRgtsekcZ!=^ZLnbWqNk^j0z@ex{2 z@GMceJdm_>_cPaFkvcD5UX4b(Nt()O#o&eJ!7(T`ry08+4oqH1pCASd@^A2N)^4*O zDE|v1!Pq4M4@;!e#DZ}524CoO+b4P|AvL;dt4FxiRet@=6CgPfk}eIatOZ*eL&6`6 z&>XbUEW}L2P&C7jHAn<Ih(Vu_tVl+A2I`rvEKB7oE|#efe`^d>y<@)fpUr<4!Gen! zp+J;}&M^zf%hPDI7=cxg53%ec2K~WK>x{)oMG4~rcuq=3ieRAWU&-%r-P_~gRIG0F z$Yw$IX}T!xOhM2N;94|(n)w|OBmp#}IvyZhgM^M0G@;pR|M$ULyIudLJtf|bt`1Ag zel$1wXQdI^Eb<>=9UY*@bfVGeMyn=s)Om-eCc_34{&gq}!uz$k2d(YNv$bVvQS43e zuRTo~&T8>YtM#fF>QbuEL#KRUe{AtrgI!#3<WjP=P+(GLQEaxua(nzJWLcg&|JUzF zgxocAW#Z(tp+kCyX-?N<kJ1aiHS%|zNa66O-0`iM9(g=Fwt<Nt3-e6wrg-E>IH?U8 zK(X242vNMiE={>k2E&Ae)?4TVr8UE8q*MCFrn~)k^!=L8&23IH?*sEm^7I1oX%@HL zuZfXg(>?Lf74CKVYo5u&Mz|6L0oN*14OqT6KYb3fK8n2CTYAL3>V}FE9-h^2f9YBw z!{LW0s57JA#cWBxS9ayrrKkl>NY*mgrqD=4qEhAr8hGM}0|QRZDih|Hl_qryt~?Sw zu1uak&UJ0Kkr1Vd{AiiE2w5EW`vbXnTddsPZ02dgOdcpBDY*hE!?2py+pJ=YB@thY zV_dO<L=_`-h6rpsuH8SBd@n7ptw-{%5#qOizaG0fOhP^$V#ORgLbK+&B*%@&8&vlj zE+3UYif`954JxjN*L1_0w1GaF>0+vnI-Ls=Zv}~omABjKu@L>dk~B};4U?f7VoHS* z9mw{q3(0GmzRYg?!&P&CS9#Z`=L?W@Xo@;Dc&;Suz#=m}g<Q8n)z72h0xWQI6Y5%q zLad(y4Z-LXv6N|4%gS^L@jM??S#yH(%OPt}x7K%Y!`7z3Z3uqcD2McZx>mY?VTgnj zG992`18&s3T6Qsy8<Ub1Fo+m75NyleW3ca8C;?%k(cR#!GpaN22Cb?%M($KWFb?1& zI{Y;5xIzE8(_yE~iJEXe(MPuXPSj$cQ|}DIAgUrDN(fvppn6UeB)}M^EoqX~Aovrs zN<s+FZ*+U>b2RmE0{MNkeKjt>5VN3GYt^J*FoX!rNKiukD1&ZDz(4paV8%z@Xs9Vc zQ=d0ydehjw?^p+fcT%v*-xm*(`B5pU-KygFQ1_QnRrU)a5g3M?zu8d@u3`AvtKjA~ zwB@{>h?Go4Vhho?*{1lCKC?cWcU%u3J*_rU*_xkmrF|x`|BX2ms>8uB;h>avE$(I< zv>J!&X1{E5S>R|pCYN!S+YBs~B11yV!?ZQ~e0BAI8)?YvuadMq0=_W5(wLKpL+jo* z`-lz$;#9{G-Wmm`T|@a+NIfhD+Y!!qY5}*mJAcow{_#F(M8`kHyunGj6syqjsIuOs ztj(H-JVip#3fIm$YRot~uTzybLk|e{^IV(Fa}a*mf4UG#{3!szwnlP$Pnx4Yb~Xdz zXu8e=?B7=84n^+Bd@yy#vP!9Ln>mh%dy#ML@!y^-)Jtn6qjDXxVkMJ8JzlHAMm?1s ztjj5MsB;jvxwmJIO`UcX*Z!$dHHY>wQ}V?2%~MeZ)6xgKW;qzWAC+@iZ|gAmdODxa zv$PYMnkWj=kIsccfHI=}3VC?RTx>Llq*yhq-{PfF{q0N39m6OsZS8{}kd3zUkR&r@ zV0W<j(*j1IMT=J&_l}hgznXZ_PDEvO9(GuMzsmb@tunZI=49<F?3QNSVL-)um#CJ{ z_b0))Mif9xupSaLZtqv0iy3;0e=#AYJPzIcm{fn%-?ReK8R{Zec6IwA-HX)I!wE|L z%r$6Lq%Qns9C62}y|gIe@l9E^@(-rBR^#($n5#3Q$xnL(c)39oVtF0u(A)M5Oh4*= z7Me0zhMbTc$ZoB?KgKydM2a{!5wLc~&y8UJY1MEeVE6rm)N)YBm519wQbF|Yd77C5 zQ-gD8>DeRp75V;2<xPvq)0em}M=!5JsT~3DNJMH8j*6-wXu`xP?87hqX(~5358ujx zsu0ukUa3xYgGbB-tu`VoG&)Yns>cEb5!L}er>e{!34uwq<=B>;cVIo}f3znT<lYV8 zh7yadWJZL&7C8;Ll_FxuX`$5b7Q}qU6#n&m3#g5eN0am?h7(+@49+mAXuo?eI%vsi zZp`{3Dfc7(T%h&GBU4<*NsE&t?JzrlNqdehOXEpz*&pmXx{qLEce1u|Kg6QTdOloJ zuj>-w0?bsMI~|e`q`z|x{KI;5uJMpgi(Q~rFY~_4rxKsWU$qf)U@iPT<|<aAGe6t$ z%W0F#(v|Znp~>jw5efZA@>A>U06iD|-+(+SqKKgfZf!r`o68<>+b{W73{mtWd{_K- zk8HWSi;)cVU8AQo=&HM|*AVK+Hm|ivEME5ovfGfJExE}gJ%rYE$yzyUzlWM+AmcwW z=HfYKZ(}M?rPyah^UrWPsV4%}(p_C6&M2*NqqM|$+!Etd^S^6N2;Cawr~3B?Ifd2p z2xf!L3HYpa<6Do_==9%P(O-^gKZ30|of++mdyg6Oc;o~tugP$(fc0x{Piv2UtZtJ= zB(`;D9weLrTi-V++Qb%Y2ZJi<>vT|4CvDr-F5z#qP>nY4$awN|<Q=5*g4GYwi8eRP zE3CJTX8}(8CSx%Io<F=#?YJ|;NTZuYQfOXLd4x_a7~wL3&G7kEsH~3O&lhaFYXS=- zan626Mb$;T(icsO`cHGq49GFo!*U2JvZvGTM6i>I-&AI)aVP}+I*-LAMC7TEH2ptH z^P{md0aWjpJ=QUg>v@`l(-7l_!9TPvYz4qa2cZvo8o(pAOBi5~{}Yn1Lk1B!S`9i* zTae{NYZ(BN;=&v`Xv^>)xo(%FE;LEl`WLOLS|&_6w7d|i5eOY25R|7EsM)Cgc@?f9 zlv~F9LvhmpsvII~EjI;l;~AyFwUT6`rxJdwkboWov%(tAzwS!Oe*sih(d9r;DaJsw zfFE@bY#E+S#2b}=6BP@A3gTIWmXS`2dpW+lG6%6?FF9X)M=jel_`kcRiBHIbHa{Bz zGsuR9s%0uVp0=kK8t*ewgq+bGEsVs|$>JC%%hX^OM{+zQSXYCSY<=yE?p4=^Xlysh zGmQcD<i2T4Q?@q-)js3gVssC<Y!kf}z2liuSy}B;G@GT~@Qsr>{;s^I-D7L-vFsUA zgt;!>l2E}S2z?XU=0m1w=o!YBfM1S_FXg|?pOlNmmf;qT&DnWI3#McF+$+c(DW(}7 z7-IoOGx->EIIW8(#(OIT+?f~}_<~2aBWLW5*Ly47i@9AauFWV744KXC%2oQOKOh?? z2+GXcX~eDma!c7mjPl3S+Pc=rInIcF?t9rs#^Syar!SObEHp^=MbQfs!}zq7ow}Oj z02>G8GBvI0ak1lg@8X@t5iD9ybig-jWJ>kV&c$EpTTNGlQT9crLujks=y3IX9VUl` zsX8fM*LkduUZ!6?`2Z^)oWC+D10v2Zex1798X{|xwn-Viav$Avb_@;&ve|e(v_Gva z?Jbr^UNJ0rx0swAW{9g59wcO*5@L22EekWeB~RtfrRO@`YV_6nk<^n^)xYoHYYa+! z`A7&(2cmnMCE<fIU!OaO$QN-9Vk<%WyUvtUlzz|D4b85%`G+poX;=6cO%As5VS0fQ z23X%jMFlM7F?h)_ufkZO9-WlP8soJxJ#i5q=APw6@RJ*`f2`s(O*HZ;a3~|=&jj*_ zkw0O&g94?MlMomHJGexVmV=A?)6rq@SBEptF`+z!Y;LGQFm;qwq?X>OT0XJzMA*rr z1fH=y!va@}_9N?MIFvakw&mG69KU&}bsCA2`Gz2JT>bfXd+TpjNkizem|uDu16B+k z;J{ij9zysSsY4~X8J=*oh-+{z1GU0FCxInI*gA-y^c=GLR=q0#Koz#bQ(eOE@;MUS zjQIo~PYKc$%mk>#aN)H+7zoU&#=v=p>951z*uZ%xPYj_3GYE)OT5SJxM0Ts--r;@x ztBI0a?cH_6-hS&Mtykp|;$+7NCp01UrnG6qp3QnGan@8>^*OGa)-=bpLz1~8BorWV zPUDPNn43K^68jqMfb)BI=z>jd=!~oSCQlV^j=gl@yzIIPyKW!Z-L%pHE7^y&YAF2C zrXZewbI#o3&s<FHIHJi_r+c#Kr0*}gi4Sz-2aa^Wm``7%&FNcl=g(_K2iZa?b0@lB z_Dw16XT_p)8P3#(spO~aoMtsMr^<DN*RA%CtR;ED#+G>Fdb+ZsD=R{ug3D#c#=9%{ zR#T`^o1e@oadp3xXlh}s(+5R1*7;Kgs@<&^q)Za$WZJ!dH-A=rjleArM|H9&-$$%6 z{tDl{MoJR>(Is)7QTlWyb_uEg=MXnFRk|+y@bM^j%xaI|UWFiL?tXAKz7E6?O_0bA zF?kW0_R4NLjk#u0y7oNs!4Mw*;%rlXW5QV+=n+>c{)2Fi0^{=h=i)BQbHuuE^X<Nv z&)9u#uyI=Mj|UE4bW5sGZY(Mb4C110+y34M|J#5;9mybh^vA!U+qvIa%4PlF?T!s* zA_XtrbDpB<fVfb|OJDwI9`pRu@I-RC=Isa^zH`o%jn%8^GPugw{2;|bsGm1^b%Ip0 zv$cRCTIQd*bsA7?D$Z;wi1;GsmnT~r{21(-+>i<7_tOz}P+BIV3W$k5@FTkrt>($X zLPiX&^@@IP)7t@YmQZjTr}qAXGf0t;H(=3Jxsu#m+h59rAm})Ep*yQkrS*G@;@~a} z0ha11Vk8>O(~rLj=jo0a9_c_3`#7Rt#Znj^Y?)u+XL#7V$_^Vf<GiZ)O}W;N#urFG zvxl(CUaY@7f`_57M1Eo(Y;Y-9=+-TvoQxrdlHWxqIc|ouDM_-lOuh<OVF-SY;vP{0 zJVB)|J;vm@H(c^lvO(B7hGThx<5Wf1FstD+@0KX%p7qF{JYHp6k}>ZP@Z4X7Lsh0w zDHARbT;R-zATS#-8+IN>PtJzZc4Rk8G`v{R8$DrQ-E$b(rEprKzKvy)DRDC0eJ;V= zDu@^FRCGKR9e5(-T|OK-{y-^JY*xw-ZqwnEV_^2}i<G^1;<h~XaR}DD-qPeDIdMn( zJ){u0MKO6b>%ph-pt|NX*4jR`P~X)lyNTfF4B)-Vv4&e^IkoIxF{BehiSqR<>{wkx zF4Z}l1Hk`&`^F4XtWBO|FORj@Bs#JyuYMvBq<4NbSUx@9mDTrbhq@*_as2!-8v>WC z`e>g&+|b&V?wxE`N7`;ax~@8W#x)CVipTyr8&AQf&=@szo4-uS5y)#CGuV2fpMR<P zxGka}td2oHg)-?$*fq@b;uo|nwg3F$t3FxbMm(7f;)EXpPA#L{)6~1yYnS&Y#XQcW z{=x8O@t`N*2#<C(^pDt|>J0Bkf7HJVCO;BT6|)41g8#%!e}DM(fK<fBP@-SI&kku2 z6(!5#k@%0+RhNCz_U%tKsgyTLwXbE@;cDF^kUaHwM3(PMIRR*;pSF6*=VfLzwIns> zOr_q>kQi5~SU{;-Rh~|(hQcXoaGwb(<rYRrpB1K`&0u|d_MX_wAape?3?bJ6NScbf zx{r>Z2ifP3+YRjsO#`(~{;d|brv$gDe@BVo?a@jLZ-*l6fo(Y`%~kq(h)a9`u|<R5 z2^Hdo|3KZeHweamV0jE!KC}Z2a~(0F0f)hPv0oH`D*J>3&bw50P>n&K28_5nd<P;& z?B{auwN!^*$J4=2;POSNP7`pyp}s5MyL9}1fxVsZynCYIvG^|k3H}3!&oL*<HFx3b z(6zdLIUE@AxZ&BvlGb#h-)bJbHWVADOg>Vgi9^sWUJt{k?!@jehM6rxvGs^!W8%nm zngdB!8_D6C`~%6{=@EU{Mm}04OJiKywWH7&e6$>r6xxcf4d}c!hf=Tsyjh9@X#sG# z4}Si2bR&?9Ldqp*zgolN;pzG~?7f^;;x^N$d_%D4*vQ#!$r~qF#$S-%*L(R42DZ<H z%mOpFX8h&X($Y+%-QTG8C8TBDFD3GM#TG*C=+f=wbF9Z6z6`H<cJfwQzrJ#p3)elb zJAqsOed)-bY6~cQYd2sBDai?d&kKPS7xREQB{*&O{G^CCK6K~=_VodQ-P89s?t}I& zE)EWHsS;acs}WTiSF3QjQ|Vj(PPyq%xJJptVR(jZa9Z6Y{=7~f{Q1K^?9<y<Y)%Yj zyDJ{fkQ7gfmeDhg-gNS}a$c^+2U_Z=&7I?OXc5)=TGrz3c_7L!kIc;w`c0HKh`UeJ z%Oy_%f*;3k_qc(E!ME+~z(%EwS*rgtm1%?L_C8PlVz&GfIKLxGzVhkUza0N$@v_|> zn*l&z8qKl2>3e<V0v}w^VDox&{GI{KChfJ>wEcK0zQ}{q9DZ$PQ|`0yXWt@OM#BNx zrg`n2#ri5QwnZ+grW@Tq9vk<HV0bLbLj~nI>wN@O*7q0)oiyvP?agkNqDG$;_!0wh zKULg>gVf6j0s2sDf^Swv+p8!|E5cK)fU%1%o~2H`vGxOE6I&}COcWgJt%7Cs@p8uE z?9GE+U=z=~{YbsreQV5=;k1^WUoOQKoz&l~-#t`^qyU+W51YjYU^wBhoIASJUMiPK z+|uy;EVwBGHe$1{BTPnvzEL%WW`~|3<HXkI<Q80oH#0{%(5cR?g`~|v5&p;BKcqQ1 zYp&-7vu-A@b=*_eVn%9$zB^)4I2+KWr^5TwmtHq-XF?kC71>+TjG$2hTdn(lm$P<6 z(Buq`?+>UKBzoggU*%eMlmUdOjK*=FHrtXW{Y$)|P1<vE%@Up5^mC2<%;)O+y46?5 zZJozlA;D0S4Saae{)9hpKMmdzTt9EWqe3kg9Rrj;4VdZ32GB1Id)e_^vfe*0kgZa0 z$<Htm)mC-;H4*FC0MRzi_qDQxI@QPIkk$O;{J1D^a4lem^0(*?EqabWA17BgmS11` z*L850cZcRoiq#@HOtTS9!=62i?TT<TDqHJhr{B&#4sH@&qjElEz6(D`$L$<dwwG0( zXc2Okq270Yi~e*=@ItdwBn2!AbU&7%Mt{mix+znz?J3ZK%!dsKm0*m+i@3;XI<KB; zhy(!1ss<B*klo}?ND{c`c<t8PEbW2*;VROqKsQ$Ri2f&-L-aj;EeO}6AX~|Jq~<pv zOYh+(1lmT3TvNb<M9`<@wxxQqtWV;~`sLf&NLZDlbHuuJv)WQ;&Td=1wq3W4ZFF0I z3PwuWH*^;-XLsZ&8#sbxEA^ZFl5M#Y4G2pTy{x*;%q3#BHQQ%o)iocNYWU9ZT|+4K z-<(8*d!Y4xqeP@^)8!F-ID&^NZWr)xB>FzQ6;l58<Jr(Y-_&$DK1a5jK>ZtmS?rlK z&=WwV{9fzwdxs2ucPt`AP+uoKQC`2%zWhOqhSk(k%Cbx27I;+xJTKygllj-|{ypxS z9EF<3m~b{e;pqn)J$ZmLwAVXyQafZIeX{3?h!^u6)r(F&N~vcs3n?dW+SbIHc_)i7 z7}=4aDEleb7`Qk^_4iQDlw;R2yY+wg;jZeo8&5T^U*1{zH`GDC^wo;(8P%hZ+Vl}E z3dg!f%Xazf0^jfXBm>%;uPg>g%en{h`8o^#s{H?23!NaE3<sJJgY6}fuq(prM#ABI zGZaM;xu}N{MC=i`CFP~C-9C16j@=JlB%Vh8iorMGWq?S-j)7Y<tcD4nWJ<+DaU^MF z0dhQmmMAP$JE(v~{JFQ7UZmybpsX~~@@k!0CaKi%%(6VuP4w~2bM#7&wZ(=JI`+be z`!?SMTHOd?6E&N;Y()^SKJym^k2@s|*1L_jbk@x<M0l_E)9NDiTIX9f%?`m0pPC@3 zjQJcWa9{mzFT0YftG%AoVtzFx)1HwJ+l8WcFZHRFq4&zkz=`tP0Jsfd)uV^U&hRQW z5z{O!zMm$9Y?EFs*i>1928}7eHV_HYO1?eO3hGtp!!^p~1prg!e$xQ~f!^b8G-`a* zzM9Yj+}@D}q?iPX5&f}#>gIkt9KCvN5561^*<ZfF?Oy|}Z`06qUU}Xq*hUNA3Uq=& zY2@`;x@oC=sXZ=E;$}?0$m1DyU-(g(zpRs<`NrtHhWco;zeR4$Co|oxC{LT?r%^6C z=L`>l{-uDn(c_$O6RAr%;72`z+NE6a%GEQXrcwqDz1W>+?}A=YBfQ67J9B$}Xdnoi zt0!9XcaZ_H)P?@Hc!xf^(XAO;k;>tct#;qMVMT=*@<^`*#o(VPqhs@rq15dig~s}C zx++}3dkU8bWkqU&`reB*ZpvR87<8<Au^|=%`M%1efY2OYD8R1LT!cD-o2&dmI6dK} z$}etpXJXTY(l@K)7Jr>nCB7pw-7lt&(JsqyU7Z=ACYsLb9fhtx%%!7VI3FXz#9LwS z4&rB4b>T-*n(i;@wDnDc$pcMPFwhMeXexfBBBw)00y;-FmX`OF*PA_|VN!epTA5~Y zame5OFfF|xZT#-nCvu05#f}n7?w@7AppE-Kfo$#ieF(dBJv-Q0{n=h!7fC;oz_Y1| zYrgjo$~JjAH8ftYVPz+w*n8c5Ys!?(_GZ$zCHeF0r|+BG9Qgi@VjRfgmGNVr>G$1B zhg`F)aHc(Y?JZWT*PU#1aAvoUHB6KAsC(f9r1cNtA5K53tc|5zB0Vq?VF~Yga(`sq z?s~F5BThbD#DUw}@c|mb-Tt-StP#d-_cX?4jTXOrXwdOIk9hATr)BD3yNL0wVE7mY z9%ov+q~#ykW^focj~=%3xgE#T$T063F<snL*0_w-bz<B;dtId8D^wi;0*1Pm%3||I z1oW=>!~*bJuJU38f#qo~0)`9+ad>YB1!vqnVL#p%uSfy8Wwm0M?=c78-Z1#S5&Fc6 zIS2oNn<sZ;J<Vgh?6wR2@wty3;9Y^cvX#Hhd5_Oc(wDD7kz=tFTa&Y*h+d#bQ(Xqv z3GxRD3n5~S3Ls~o66yAktZ0w|n8<M}Cr?FTd*7Ds!e4jx|JXCsb>)*x-+K>Cb@9V3 zf1$!v6yl$zHT!TqNr$I%eBNZymmp)Lkpqqf=$vjG5_gooWiCI}tSwDJ!0U%>jnkWp zOiH?4@}R4EA726KPk5*AP9(RT(Y1mr-I^I9Xfb~OL^Zj%dw)hOlI6C#!slwssW7HO zobn&s?!A$b;fANJZh$oVeDYQ+mUHDb{tyqaefgdUwYH!2<Mf&K;<xn4m&50ZDN2_A z7T3xy6e(a}^BwV5yGI}Q$d<+x8w;(Iv~o|w^$o$8BmXs$cy!}lvH=$qFI`?f#x9(a zy9O~PiC*Mc>vjDc0Ql~g@xTMvI*zN#7dzZ2A-pjc?ogV(Nk?(8p4$<G--rq-#D^UI z)!r$!w&d!0I^aSMWBU{FE~IMr<?QpA7%|GJ3pkIux5?5$f>sfK-yo@{22}xhlB~c@ zQ?#%%8vT}38^Hdbk!QXHzaMl+{%7P@7Qlx^f2~Y$rDvl{R^m;#E-0)v*9bh&bn-dG zd>0<s<r}~xfmuT7J~?5~M$4f6{#)h-)$(6jpyi_0ckpPRLK5lDBpnrW570>_tI_0R z`~Mtdb4Jp==@M*pY7Fie1dp}j$7Hr&`%hL61RK+5vbauePo;x2+xAzd2Bb1e*C<<U zbWRihqRadA<$t)^QIE9$LzX#=jM|+>3ETwC*xnUx<;$UP9&-GutGJZ&Deo8~ria51 zpeg#IOvTP(IUg7&IM-f|`eHR%E8dJ{WI;{}R(n`=)!!`GjG974XNLDQ?T?LStorKT zoXoUn2;ZjJf#R3?wM;*iP5+zXm|V~cub`msofx~jwYT$oO55&>KX@}_R^OUDP8_ll ziT>p31Wl&5KCzoKf<yXQIGJ$K8-|c1)k&-WoxG)ZP&&``8<4@BJjqov!?Gj=y0)g| zBT@5%_ctQK`sz?2H+(?+jttg{T7WGccLth17tItqvTU(mH1>}y{MGKr&F7@)rtwXn zCb-7gcJjkxo6>W7c1`Bx$BoapD;7cai+2z{m9a)4rsneo64-g`NWhnz*v#jAU=C~< zS&RR9mBzjTl1eaG9v+ir5A-;<;H>Q@M6|q$={)2gI_2I$;Q~?t65rFgZ2p3?iInho zO2Efd>gztLbIp>D3fy_QC^wo2D0#vMB~RLqd?8|s2nfJ(?}4*8Bs4cu7HO^`$D~^6 z7u?1T&#_NnyN{b?3}QLZ(;45xXD!m!TGx#=GQyT1rB|BimoJiankN09y;<YqbT)s+ zUx;nIu-Oh2F5MJXH-S&X8&w=Vahp?)SHjYvrB<KloESI5oI}=dRTt?>v|n@1L${`4 zzdHCjSqyIxuL0o%&X9Vx{JVdJOi>VZe65Ec`?JG;dGz+g0vW0$D`zQ_3ius}JNAXL zlj()B+W4F%r@oL!=+Ch?@L3PvBVlJGVb&>UE?wyE0aoxkkuv{eba!V--BxMX^Nc50 zUY3oJU8oZh1#jiVtG{hF=dd5Z13;nRc06Yce-1Zk(!sR}_Q&?q>=9IUG(9kNdEQ1< ztl4~%51H`c#*>Mg9%`A@ZcV|%<_y@rYsY{ZHHEBMa$_LgejK&DBP^%3J!z**XY8}Q zBZjL7%?3xcjWp%tWwUXac&y}x11IL&XYtJUj<n`$|2;t@@msUwrivx^tM&e;6q~^( zID1+CaP`9{Ui3FKVbVp2Mjf8WZl}{~{=YwbJ7xA5GG6+3bzk$<7N=g)xAHmN7emDI zKq;_Az9@HDIUaoU%t$wUv{{jzCP8#f3M0{b4VO_RuLOI{9%(QcE)&&V5t}<x(N7k> z1Fv=n!^Lb99&}r&)w3rjdn=C*g>BO<NJ5xNw``_97NLDl$?zCylcm+pteQs}Mp7pj z8y8%T`&DbMKWvxvn^znC^_!wrzMW&VPAa<ROm}ZlDPmTz2hG!gORb6MT6^r!$w*Vw zwjVd=p(+4VQ;&)D-KI5Ki`9nYau4m$8amx=t4jA~B)&;fLVAQvrWNncm1Rfr&Z=3; zDaB<5seoreyTkr5DZn(rJTZo}C>Q;uZ$Br%1*@+}u_gj6PzQzDy62VcI)lP(>)%I2 zr|+Av8rAY$<;F84RVe#u%!r^OvO818MTq8LVGh^q?tac)xnyY9aV|3qv~y>dneI)I z-XCmaNhK{0q+8t0;jdTkm3?qhWcM_=ur7AyyFh|(Pyt8pDfV<(Yg@q-(R$l4$I~dP zvba0GPd_slpaS`JXFtep5Q7^HFCW@`Fjy}dRgsjw_66iARq|ZhVM+eVi-7rtie1?E zUg@4ho4)@9#A^3`^6ka$d~4Fsn;gz@^enRo?RNOjwh!EkJ^2<>%6wWfz7Jtp{Y#y` zX`T-#P$28Ffj+*)AnV3|2D$xxRog|yG`Xzyj22(!%tI^u*|ZK@%?3>+>aWkqjJ`*k zhH+M!kme-U#X)(tHS@e&xe0Lfy4>g=Z6B3s&eHWQ5iVp$nlvfO*1?9&kJq!Jb*K1R zu+|lI>hi4!wtVQgSQpv`Fy3gI?zL82uPVU5J)QYzesDTkF(b<TD`m)YeM@49*g<KA zo7LLyww*2Z24{Q{xsdH2$;`LGXXDE4r){hDIk54R`lv#-6zk|dgEzTiyEQNxr=c0j zq<#m7J7u(Jh@9r}le067v27#JiuQv{wc|jr65?+kMjvOFlbi4a9`aVib$t}rZV3GZ z4pUF5x3}!V+~qUeKvZFQY`*S3oD>&AHe|h#;PuQly}MUGoM+syb!H`F_1*BgPIL9< ziKk$~40roQ@<d#rZ+N!=9duW&;3!P~9sLmqfVt54a@HzeC$!p0qPmV!@9j6N<t9wo zUjG<VT0v8Gd6#o5&|F<nTVNEB=TtGUwT%@f`U}hC*L2n0Pm1w!mi!q3rm|hXz3@ZJ zP~dOK2M_+o5yOqR8+F)6nkvFV$9UG6Qnc^+9HGEpud=vt0B6e+m+7~Y{wvk^85-5a zDFN=V+BG`qZqAp5zH*DcSJ2rN{x2O81$kk$50qV0EHo~sp{`fSj95LG*&8Ax;W&ec z1Xfasn-Uln)}cR*!g3MSg=1{03~Va&tml}XmecLko&@<vrdVY|!s3GijfmrhM;dgu zK~=c?qLa*H$7200m)S>+tzJU?OC5`?kmU3TRwEE`uT7<n6MU7PiEVq<TT#_DbM(DE z1giK!a;vBMCy47E`toQ_lZVmbyK>z}t@XnIB@=VS_GmSYZr)?~dINm}PTGjFQ0$4C zdF}RWFS9HqJos}iU(T|-N%^bv*1O?5&6`U$4$uC+%<Sf>H;01a&HUXiO!69uyQ1Fr zlSiQ~z=biP%MXL6zTTtifUMZvCW<KIW`Z#r&YlE<EdZDrK{z2wsAmO^kMO3q4#J!3 za_<yisuNntwB__0Fx&3~lH(F0KTgkq%u4$@>k|6jrA4#z?=Q98eSO$11=Jd@VF@lo zuU(nu=W;{ED4(DY-#$_SLmh<0kQE$@Zvspzp<9!W%7NT|%CICzi)RR(eFR=@A}(nA zOBrd}C~y%=nkOnkm>6NI7msQnd{QFH{VE2B&<gUj)n7E+Xiiuv{iK3YM&U4IgN0-x zGkE=!%+j_+YDeZTiagM=vB1Uq=v~?2j_~p=p5+yv65o~Ltr*%5(m!;pQR;Rc?mrsn zzQNJ!LQ}sMC02LFI(Ye~cXbrXMvqq}SyZD)a-XKs@mwoUTUG^Hb-Jt{rnU6V4c`{? z_RD6bsHbxy`$8Wb%s)Zp{DB)QJPaqD=Syu*V{-h^^mW#Tgz4(*5j>fw%t+HgXIK*M zdzrQyL?fr!TrIy_6leYr;BsT69(M9LiE;)XZ}u?9CDY6h-`c!hm1DU%NwQl0bs9>S z;p{JEyHh9AI!?8+usd0>H8rihTSUSAf+)MJ2b|M;cLZ+T!>8x!>w)hejkD@l>7cWk zt}myycgbv?vbeu3mwI-|uIz590EM=dQ_@E65uh@I7?vvSeLYZg2<gK&Cdbt^lRD_e zWzP}3AhT^yqoIW@+j@7~_7x)U@%we51l&RPx&FWH13DN|xoSu%@+Gec(eh@wpaTO! zj34=bgEl}=V)+XbP^&jE#cA*sJA%qy6C+G*|1Va+<p1L9ouV^)gYLnOZQHhOys_1B zx??9D+qP}KvF)T|+qSJvGWmVqe`d{Ev({Xmn{#oV^HlAsy?2#mf0Pt=g|0R2I2*?P zDO=u<XhOWxZClK$E8w8}6ze{Yr=b82oMz}9{%$%a2lC843_xt4yf#MncJr9z37CU# z@A7dazy$P%9eBy-vWH7}Qjs5(ueeVNVR=0$_lXa`B<FYD9tQyM|Czsmq*Woc8~bZh zI57rg`&)drD_&&Sb+J9ozY@H5O!{0v`}_awH1RzX$VdV^AK2;S<HjAJJj##Py>loo z!du^Ib?9qdcL*ecVCZ;Syb^fX@~@f@s6m8yemB+O?JKxuCP7JoR8QL;mAMaS(-Vxs z*>PV*B6RP))%bk+P$hw-PxT-;MM1X#o!0F2$1%7X^0VbU!R#LeouLgW47NX@x;W}T zIoKm$Np=9~_5BeG@F=zpxIl=jYv;GIdAe__UPcf)lmKZB{7hn6BQg?m`+Yt8rH+iQ znheh6^|3&VMEqa-=38a?eItN^hh*s5=7VG?--+pq+K7bfyRv`u<$MlPiYLbd4-${9 zFSOQ*C?aNIH-Rk8N~Gh6r{zMaVK;nPOE4s!;`$|nK+&sRy#mx(D!w{hM!&bCJLs~; zeez#zm#*q8ljdo8Y)Rs&nRAXVY=-Y>`SVhd|HlAPDkR6fSmylM@>TL-d`tsLj?i=J zD^73pFR>O1_-`ihwD!PPIHm2Q88WDah_(S0I;wObgvEx2t7i9o$IwX+A;cWH6=T8{ zTGYl)%e^6>{R$!27#mU7LSWNG6UDFVltv_c!I8RW%+f1GFAwexp&vKZK@yo;Tij}| z*1|E1y$2{d|4N5MD@d{9)Lm{Q)ZC!Oy#qx8b+r|J9*=mmMu#DqX&{kmarWCC!`=_N zs~gtVGYLO$*<mN@cMW;0K|U${nuJp*aj_Dc1k3j{Ai;e>x7hsXcDBZAoKTV&0xRVu zT#ve>Wdq9CsS$!d#<yZu&;MK~{wc*L!#gJAkV8&VNIuciQ{)%{lluPfP5-Bvjp6z6 z{Y3g-6I8ih)ON6N?feTi7TFIQvMZ^al>A@V?sDuhHLC@)>MsVJgG}0_Oy=ZvmAq*+ z{KP8$^4@u@<4h@gc@tmU_#b9NW7E{=>(uB1Y5{hWU>~lVV{2_I`&Z#bP5ae4S+W_f zY@MEn4<loi4JHkr%S<1R^}GkSCEb(hUYw4LWN}$<hI3PS_lkW-6!x3~mst=tvPM2m ztD*uO6q6;__-*%Y<|es(yE+g1h(wX=PL!*sG~7;zHM5MIc-LDd|0*U4ay$qF32m<a zcx+j+J;ungtbp-@xIx_D8!o8k@}%y?(8EvI2enmnx%vcF^DuL_IDR!;>(B1QK`N9p zo9E3Rx#TaWFZ8A)??9%ObUELLBKtiJ*q&!mH}b|ETq2k`8o}lI&C>eCOY>Bywz~f5 zV*wZRVT}HS+$AEurfEfj@BYg#rK9KJ*;iUie!~znD8ACUX0&UXyZ*#+doq`1xQ;@y zJPe69{X%QLVpWA(@;MxsrvwzYd-4E^5DEjoF<S9VMF=f5dezE#&39#`{N3V+Ma6Xd zzB~F~rEWpYK`}CF&cwSYtWYpth1<KBR)Icp&lB@mDq<luRFG?XooMwN`*;5m<=Rrf zv03t%VkQO`jdy~$Pnh{tOa7Ur7Crxt*=CzV=(NeKUq9JAqw@F0?|d^;Q;?&*X#G{w zJ^Z}I6Kn(P_xqpiG}w#~62W^Hb`ziYI0n3)i1l%U!s|?Z*!n}tu*LHRlcH#e{B}Ea zmAN%zqrd^XN#VN4<RD&$qk#+X)e@1+mH7)ic7pjPR?yFeNo2fwf{#crbpT2~m@a7x z>f~ZiaD&A0(Bqj})BfI{F;pl@E_fCunJVY6k8}{7iP!lr`{)oHfh?rv50^h$_~QMa z#Vw5ji2y-|?Mo<1TSFKAQDL?-8Pbz)#*ncRZep7dsZ_R)m2k>?${R=NlLu3uqPK;3 zXA9)GZ(H8PF72V!;Eg~9Z5M!!F6p<_*o&K!sp#B7K;Yq><y(jMBHp`BR68_iHN!3| z0%u^g$o$@e18$;B;nA?Hig5Qs<$tIFeGWB|eDfiF-w&bw!nXr_5pX*QTDc#=e4y*j z=otl^=YM=>I*Bb{1o{Xpd!7m$lv~MyIA_%am?9z~NV&y=Q7m*RC@A9dqcIWNgHZLI ztnVyPA5&{9gW51(mkRWaOdTR$hZwptoKYn$sC$e1>8P0*5^iAUba!HkiVh6W5sk=D zM}o*DbyWiVQ1Zz`cA4e4Or;8fWoQ!O5Fw3;S+1llHjYW*Pg%UYAs<$Fq@|>&R{unq z$WFVyIQ&)%+KlLZ_P)GoesUnn%9&l9^*z?ST9A+NxSAmY<2~rdG|+11w6{rYL0jjo zx(l8it)>2v_FFOYSfl|JI~l&?Uu15p7hbLTW7fq#eGFzwB1nN4{GPvugXD@Gg!&w7 zL$~R*^e|5XV{<;b?RN~7-UuBruZTqUFP<oF8aG0>uhTyyJ0H?qxST%Lkc_Tw=%IPD zy|}nwH9`YcFB=<LL>d3kv6Co5y<mDNX?g!WQPt<}U0f(iu0xrqo*cOURccmr0Xu5o z#8dQKvW)1@Y&|%6Vf}&*g|%-a^6PbPa1Sp&xdv@lQt-<MH|TAk&tGx=A#aadH?HkB z&<U>dhhPAp^aVG^ZsPzO6+Rbr*Bx`?6$a_vs5D(MHXV~ob=Mgk8{Qd{{qegDd;d}u zQ3C%)@7L`xL}=}SNO0cz;$={uGX0jYk61{*tAZS6ad|^jG&P64wH+4Kv9mc}t@S0I z0o0A*IZCNB+?i4Y;^%bvnv0PY3aCfHS4s_yJZSRRsYkNr4b=&8y*&cqQX&nQ;3eOC zwNC{4>(TUo&^~lm_n&YGi#J-&Yc0@OYJmGP!%7Yku#0w~PU5INhTYxWJ=EowFX&t6 zqwWeyF3-#$S3RFhxAl_w1_Ib0*JPndNwHFuPB3uMUr6R8(1E<)9dVKjJ8Zb2U3+lE za1Vpsl&y48{x|j09V&k-XvqZQ`sO6|amgYqY19@ss%GP(Py_2!EBZ;QKe5;|m|%J( zDmtL>Lm;ulge0gW*xBg&Xg&q+@F(L*>5YnA3p9`6x>x5e#r_0ad^U(O*X|QWT|!PH zOs6VJb)$H;+d&;4iLP{Ai+_S&`)YHtL)rNdB`JS2$k-Xltqvg>cvSx65a26C6ZYJR znf6Ow3daQakY`o!2nHKjo31*hCS587>je6xTM(o}u7zG8<+NhtAo)n>=E^XC-Ti5h zf5@`A*7t!rCuf!obO8v&`1&<W+26RglKjI@*_&aRY*vr3X=zOj{G}fi*)2%<B-zqx z#=w?+cuz!gyyhI^*+9-%{Q4ByzVvU%+du@K|2goZZ>X@Iw&duBQBsqaqA%F%YEkzE z6(mr{%C}7y#jE||s<tLJ^i?14yt>AzCuAC%uykNwx0W`Ltyf_3cylT^akx7g$8}ef zWaVJsS<#U9;bTbO;3?)2z45h4BRc34D}eY|y@0C)x<C<jGe1@_P|Cddvp<3W0k*>2 zNd;Vp1@<q7mNA>o$Mwouqy|l^M5Z}%%L(>oc_MHa=mT@2kgX<w$ss!qROqMHnqnu_ z?%hMxLRVj83x*d{EoTe>te7ep`7cRhL!A0I<D9TZ@J73rB{GxR##_`*3O6iRY|N=y zGDS(S1?Vd`EU<9K^OkvtvrE_%IEb(|r7**#G11V_NJvPqho!8FpAo;UD9w_E0U9gM z$R~pBBSqn;Cy0+8S_&){_0s^&Wnt!`PNmhNc_RD;oWZs`lQOQ~?~df6GDRjR<ifzk z+U1>lhaHCnN!1r`b`x)_Va95es9}y39Y+mV2PY`(mX3&&jtnOgl9rN@WkF5Yn{zzj zI92=Z=r2v2yfnzeMHfp0W~D<)8DRbv&6lCFNXf!0$lS1)OWPw1xrNY^Td@37-NWDo zVqo3{AJun`J7O$z^Q3B<ZC+=5wrkeq(hAiMOb<E`sUTRlmIHQFTN=d@rgWg*^<9J5 zn2g52q1rypB&qt+9z<mozh{SPOixT-g3g2+aOOixu1Z=n$Ii_m+_f4c#$gsYYW7HP zK6bvWU?Jza&v!wKHVA*6fCYjrv$D3~jMiGs>7i{l>gBe1j_(*kq?z<~E^Z%HBW++p z)5*}f3LC8tT1`eUQ730qd^IYM2~_Bt7u?NDwLNr-4oQ?Ju+^Jjo*kyHeYkN8o~+-6 zN*9K7p08aWzENW*s|r%$VTxmINBL{A*b8ChkPGK3l<IHn3d9DV)7UdX2!aQkf^Vy$ z+F8AL!H@7s(vR)Z`@wuu=K3Z9Prb+Myc?~Fh@~>GOKm&2ki3QZxCjpV0>_V&srIXN zqTlTuZ4Oin9_WdW<FKxlbK*PmTHooNLO|?{nbHmSqRv7$GfBR=b`zH1xH$ry*_(Nx zcp1KuImo#{WhHZF|5(J8+A?ST%|2&eXb&<bu8l*`C-i#E8r<*MF!RtQO;YwTYFs$B zU=!K#2<?*Zz{Rm9LQmI786ev)8zm8>)945IPN!nvv9)7=AIwD-)ZH2iEad$3rQ(An zsppYRfAeUIiHXHYR(+>VA<P6!T=cZ+&>83q(Li*D|NhSjh^_*yX05jo_D7~~%tR)B z6Dos^;yUxq@qxRXGrZxeygP+nEvuVDjl<gMHilDBI_B5K`f)SRp?8&^V3a4C>vr;- zdaLI~O6?b*bP~<5rX<V|nW$61w-y2`OMsRBI{#AmQ7mz3f%5DN8M~WRmHGXRiDn_v z-=*O?xnd{<xpy<3v}V*LohX08frYf=BYErJU;MvW1b+&vz$=9NbMi!21On{o6ewwN z*i6jQ>t*4e{k^6t^tXE+=X{);@>Pp4wPK^!SPsTt(isy=co=td7lg9-1z{i$j_^Dn zT(mo!we@{+bCcobjKt8{XPt9=$eb>Vr=RsP7tK3aChTQ(|K*!oQ8PDGZY2qS?+T*~ z9QD_crL3-r3IP+d(Ny@uzXPE&Ziv=f4r+fF%9GjY`qFo&yQM&VmSIuxGOv|TLpRD5 z_d^V_;YS9%B3vN5;g)ln%%y2C=Wj8+1+0vz>#H*#G(?ZSf81Kw-;3J<@K7*n3j1hK zG7$M+A2f<{nKq>TBHQd~z_vnv@PEk1F3+lcZY|`N{CMN<tzz+0<=1NVwOu*89U$ih zwf7rt84C(yLbibkH|zUC<#+n=K_-GY@NZ}5Yks=}M(!UVeCxOg%iH?2`$oDCGhR^U z5v%E+CMlfkmkYwF5X?CpEPMZ$NFy!iZzFFBJdp_|PTn+=%6dz;yVOV>O=&ILhiOq- z5nN}izY;Ywxo0Wo<P*@*3g6C7u1R*l2}YBFrV(bXp@seoMf*@as#Xmp2;nRnc%2o4 zT;Urvk~1#Fi!OkKP&u;^S>gstf+!zXALhxj>P&ftjvoIEL%yK8VAdhBM4S$PZlocO z?nRfwgIX$&kyJASV{_Qiw)YHD8csGG7pp|#`JCJ<tF{tcQldRzG1yHl+qRCeknbDX z4OhYtk;LnvN{Vxp$(yKSm|$?k03!-AP$B<?xz@EOgtV(Hrf~qmFX$|Yy=cp5Wx4j5 z8I04re~~3lng3e=I1vYdmtuEQ;>hoxOW!=O)PmVKRYudtl85MAu}BN^&yniM@as7+ zqwi-*`SGZ_htPE7skv1F?z)me6f%3<7+|J<VuDw-^w_TL_ZL^uAQ2^&O9?c<HuX?& z{QP4s>M~k@-?|Sfo9cD$Gx(>=b@c*ox>=hqX9li%Ht4r`V$z}j(h+6g--SPQ<vY0$ z@#%(**CAadc>{?N(r|>++ZP^uF%N_`dx54bx>6zKnSz2ZkY=qEV5qj#Shx*0fMd1z zA?8^d2j;l`kGsUQ=O>}c7T>3pmb1h4tx=-&!=Lg}?zh--LV*&XUk<p>dZ_eU4;~jq zp+sQ2g+ecoq9ar@SqE-Lwd;w9ARM~h-h9uaUDg%U+-YO;kiCY`H-ZFH&ORlZdskh? zE5rLlkld=^F}pVd1Q8F!<LFNWNUPP?Scc=FcF0(8vlekUA7259;4EK-gM!keutezE zk#obPB0-!GOF#1+l6J)OZlGZx&&}AWz1q)JP4bbFsO&?V1D%J+&?m!s3(7v#VkO{+ z)C*@UX~w*$8_8G+^M%v`rq%Uf=E|Calur<=Od&A8r~?26CTTJ&WGb5$C_yb)m!<iH z^Nz-<Wr60p6Np2F9_`}Qfoa%}z)#U_pjhU}cP)^}R7(du*#~qLaDLH?Bs5_@!rCky z$A}s|;L<Z?2&pwbhqVtLwNAw*)>itwV@YO{Pe5D>i01#qj9q{xET?l^kb*)T7qi4S zp-^|m5HFz|1InvsmQ`3%1F3({D5;uhkFt^tLQ-VVVv_Nm)WZ)>4IQ0F-mdfl((<gu zdw6LO*W`wjVfaVHc6zH~uzvv{e8vON9Tye5p4yJ8See*@r`I(kCu62~_taUfgXPy5 z{+rC>nS5Xe7a@d^!Y72s=^Ofy7|>WUboB~8PAdF+K)M5aE4amkBf}nk6ZVe|n6DeI zc~o6YM8LGf&QHX;Q~N$j<BsxDRd{%vr-OE)H1giriMj06Lo5}eds3vtz<60(egZ6? z8jD#A77%P4R$Y0R2^ysPu-8Q+-$Jt)#{0X1*qRpWTGulaj5X5jD$S+Cc%$p<0Uf&+ zY>>%yn+VrHam}0Oz_xKhdL1v{;R}Gr@0|XIZ6^W<9n-g*@m3G6XBFr)3j5en^ejlX zc=*5B+vIq?iQLT8pqbXSvOi+4?cLrw%({9uzn6x5M8xtrfo*RyNJl~*le&#U^vH3y z4-75Caz?vi*^5-E4;1&n1VDc&7jSuH2Tju2E>anwcauhS)+L8|&!<s%v*CCTYb{2u zhJF4sWqo^Uw5(yplct2PTNHi7ic`KS^Eptgv8{MA!6=rijAxgX<>3Ek7HV;L19<Pb z75`>*4#*uT1wbm$J;Frs)E_^1!##p0>qeT|Yd?!H&$c~-fU%k<FkKG|bRIz&RV4I( zW^bYAdwcGz{2E63U2qXpU{K3C%yo@%A4&xojdUllBKDNMb^G^*PTWZFz+=t77_u|S zr1D}4S|BzHG#B43&dP=M<IP(z8R+Q$z3Gaew}AnVa_0Z3>|2vMBTqs|mS!)4o|A^R z2Nj5IR=W2oWdI`*B53=_Ow_*(>!dXWBeOfy4(RM^YU=1o>KN(^GjJvt&L$W?)g?-* zNZHgX^_oFWd4UV$JqJ{7MF5}s>E-zEjCwO_O%6|QRJ$Dz1CG=un!3C1;20+inKQsg zf*5jVuYFb8tdbsXTwH8?J7oIW!uQ#_&UEW@jNXBHQ{`;Y8&HINJFsSjCOnSUSPHnz zB4mB$lamfr_RP}#Fick8*{~Af&~||L9v}N_LQ1F?Asc{1VK_}@w4OMF7W*6Pr>Aqz zaRW!0<G+N48hs2d0^hMItbm+=!@gSiV}j!sev3@sm~!!Lr*v3(=^4p>u_7@|9LBd; z9Igbq2FujlS^<7<bJdD<G1UY_(HKmALR@$E*6n^uEV!(lw=l!;PyONHZvCE<&tWxt z8qk)B?OJ6G{#HHtn`VXk9;H1ay|)q0bE6+wGCu;5@>V(Qd)kL9?A?%&lyho(a?^)i z6g5MFR$P&KgvcGgqG}-De@7j+9zz7`!0=NCLhxSOcKema8g9uw*WGX0a`z8e{R9;* zYqD&8J|^bA76Oo}K|J_VU?cxQ$@E4HWrJanzIjuJ<?Ue(^QwLmZ!KKY(f+B7S&sSo zsPP11{3;g4vnUw%VQ@o&Zj?Z4C^~E(8~xyc=Uu&OTt>vfUl}|Qgx6gEL{<B^NZ2SO zt=<$u)l*i+OBA1I8Gvs?uapL^QOaJ`9w8}iMcTsM_&R{Etju4azo^cRnMu{RgNs}A zjS$tJlZ8(R3G-8|pqbK6+=3+I3Bgm&7}$d$gHajQvEgdOoojqDFMBi}sm&wwwb>b^ zN@5E1%PT6Dp<+ial_u$|?<Af=F;N)w+2{Pe<tDe#E&T+XtGv*K3pX+cW_S{}VHw43 z)fMKL_OfQ!>|w~UC&9v~sPM%!bR;BoY;nl3QtkN8CK7Y$ML}vo3q{pH5pHQ|95Bhj z(u~t0ZqCmL%lz;4!1>&L1fXK{kR*5(5%Iat4MeXaVjjPYAEm%bM0EnP+<~+^Fs0an zkOK7!<OZ4vrDP=de*1WF4((&}@Yf{|(*V81OMrN%UPAVg?)6hvG?PL{Z(h_~UmJ!P zBCp^xL<Ldp<NEZerkEA`0d~kSDBI-GA4>k3AgCXqootUAJ{h`ib(0V8c^xEVwm#XM z>d)(wZn1n8o`Ce6OEVXX>c_v?yqTTX&Qt7Us^!9&wJ6u<wxbU;ppt12E`!mo3YB}K zI|1elOeafEYxHfI9cg^04ZHC7ZdiZbmu^;MKfHGs{yq55VB5dIG<)eIY@3h7`Y&*g zM1$B>uzxkU8!)D<ZB{aSz@+B(a;{DTlDvD|d*g18U1E7Ect$Lj4LceEO73tIe?#na z_lnDLJb%>zG^oACf=e-G=4TGW=(M^*ezFPSr+s}iFlgn3bGeLX#y>Q;>ihq|w5-DQ zfeqX_r?s)cFe<vbH8mP7nce-31zzI|-9dQwR0W$^<>lUd_v(;HIPpM7gqFo~T6F2p z#i*w`9T`7r30ZYNi5aZTqDMZMxocBW5|CCsCoT<PCs<qplwmFE?>mkO;SCe4TFm{~ zxqcf%@$95WUMXM>7BZLiOYaf#<IL&SjJV&<>IQ{pAITckh6iN*Jp(ytki;))dw-V5 z(>iSBzRZYoyuaw{#E5}_(hTK2?dOEx<cq<ca?|G7u@Zh?SmUU9+!k(QNXn@OxRH2~ z&e>wFUF=$gB)xVp>^Cp~Zfmv<d0S`yFEp@5N1?d$$`Fctnr9EgEdm4`$*#0U(0fqW zuM>9x7AoH0tMjSce4(H52I+v`c=Woz9riZ|ePj5Mq;o!m+6UBfP(h&80?V4Fczjv= zNMjN0@M+6MN_JmWNoCofk#-aIpRc#LG%O%Q3b^?T6?0tf8=5HZ-)f&A!yuwZ>}t;R zoe9MD_^Gt9-+RV`2#R@h<Rs+rwp1{LFbBc5UaT7-RQrGsyAeMeFtY<$hJ{E*_UWz- z#!J)OAgHc+gQh)Cq@5vl76Dg5Fa>mfQ%HKjT&+TqQvaXMK7WvPB{=UUI$zpXP6@FU zVCHi0n{D-aFRGXj)A@h0SiB;RZq;Nc!Ybjs6sRu~Bzh3NmMznX$tD1N!iE*n3;Z7= z9(;^uOnU=pJm*rrgG_D*$B&%t(0vBMq6x5E&UnF1*h|Py>KFJvmYoblL<;-F@tR!> z1gKP8G4>!ce@znbBN0*D7eT+*NxMnQt5%uOO*K|?ru%~m!O9GKyE*zyK%YG$$`sVV zQF6ZK)WD`wn)M~y?@Tc*Qt*=ggZbwYN_#4az$qv#p4a(FBa!@!JUa~cem)yT;V6P$ z6TeZHPuJ>YSD%C(^W>-I=oU3t&Qly#>-=M0z7^lho;|ID0)o#H#@b!aEA;E@3CVpj zA{8pamW`9$8J2tge4}okdC`4oWlT9=mXfxpc3?(*L`c018mRP3Zhd_vw|9j+SXi?d zX=LL^&x59$npo37VMgmc9Gj(ZxNy%+xlCoS0r~@7zL1BOZ0K!ehPN<>K>3y9qGpc+ z=6OnpWri|nVL^n36Lk@e|4<0BHd?dE<E(*uux2qztWQlyKN)SO&?nTbRIMi9n;_jP zRaeZHE&C$l2Noj7ez%oI^RkMxI~a~?)~<!vUNcpD4m=s|7->>;r0(TbiC%wm|5eM% z6MDx21LaN76>!-@IgK@P1Nc@EN>kFt<4B<kt~4iJ5IaiW#5FR<#dC+$L<5Rm+7F0T zu$F^pdP;Jh?G2+oPMAxR<Ju8uAK467@EdS#co6;!80F6+{dvBlQiR>cKGwq{OfrO= zw)MB-=Qh3jNJwyX#d+%7Tv2-Uw_AVE<L{Y&+d<2QQ(#RVj*rkHT4BiLmi7yGi*c_r zmdR<U3?oWIsvt9*E7^g$TQ0<O^zInqd6a77p*&sjs`1luQ~$v=?!#6R(#J&P0>6&n zgRBc4)9X2U+<__LL@H<H`<vo;QPAPJ0(UnSih>aT;^h=fHym`5eI*5{l+|!bL#QFs zo&-u#?|!55xWzVd|Ct@z*sa1q#N^9~**-+<cc=dIUF?>o<7(TF%)c$dTjg^@i{43k zJ6RSn!)D&=jc4;)iMyb^<xOSl0Z8iF>!%(5^|4RAJD0IWK-txjV<D<^FZDIYM<og; z`bW!@$6r3ZSn1I^TR-GrI~I#>;M<lAXDU~moEmZ1;!v#UY6>QH%Pj4|-NbzuXvj#k z8oEAF5n{nHq&V=EvYl?fbw9xT5xWO0H?>4MpWW&2pcP$s;l7w)Dv!qcUKrZsl$NE= zwuqbauMgsF^V(~u{rgw3q;XO-yp8>qTK9Yt=l=<B)jSu$V%50uSsNpqJ<)=z*Ufa- zIA2fKeky=zZe*QZZ_^IxH{WEjV@uyTo4{Nlm!QBG+&T@ltr@$pUH!R*CWx9hDs?0i zHDazTKt@FtVUFXG<FCi}16MRii1ZJpa>T`{O{`>3rV*&puq;<GAEjy3U}#-p-G3Uq zZUI#1k{rb1?v5tr#>DyxlllprOgb*!f(sC)r3PG1Cuq7$+>#`RB!oJ(=d7GqtrsXM zwu@#~!cRTnDcebFVxCTtx`{(>(pII39``{EL3!mp%3+!Io@!nj3H^Ci?>R|Ywl^;S zDt5R%E?xGb$YSoS_UonR7Tj6!3T_jDxQX({*^oU*bG#V|a9!RNuTiv0qwC=9ary^; z<WMVw=W;L*u2vi22XWs0Q=gKpi7V|T(@vhdZN+tW7b}yro)7&4KOGW@(BJ*JrW)*@ zSnSbX&=n9T7oUo!Tef`yZrb*_1A$8Y{VvC*?c~zh2dDlShH5yhW%umSvkdkLD_^W- zjt~7RpC4lU5gs1FEG;$6F<gAd?W4)M$qYj4tk<HU))gA7DQ6I+x4a1u60aWeuu*@9 zw1^2=s)~|tnpM=rM1diIgvAuvs?=}6-_uUDAFX9CR9`gihlKBf!4AqemS`g}5s=po zc&&+cTXI%wc!iSArEk)nLF5|=@I7VD_Eg*SkyrebGOzq9%Wx7uOZgw_Qow&m=szM^ z<$t6|So<ijU2my7@fi{A5te8)&Ik~PIosR)L-O&Is=u-sg}2qGmmy6NrM%YJuS?Ws z-ADK4$A(O0D2z{uLrN(SA&bn)R1z<pSkV9ZMArZ`Vh@y$@_NNRb4E~QtY?yTa>Z#A zsuxlZaq2%5oq81j@J_1|;WuO%q)?+p7Be;)d3+37W-X=82$<!BW05~ZcTNhh=s@qe zewc%3srO!z-oS!&xlFep))Cx&2=cw+g6*M@kb@A`b?GiB7I6*nXQDt@RP^Uv!efQo zraqwUxDXdv4(uE45`pflK5su`&+cfzBNihkK<$>YVU1ZoO$LPuhkR9o@k27Zj%RXQ zmb|vt;zSj1(r~-HhU&9gGy2;E`ys5q5L}mBKJnhxUMS<rZT=gyHmd!k?=gYeaPg+g zPV3jfgDzb*7C6BoboKk%Vzx<r3^khGF86q4{q)C8o*^Sjf$EPFyPDVV)aee2HZZD} zSeTXGmJ11Xv31a!FP_@BEh{vmn>sgnCbFBfZaGEAEKa-8VEGCb?auZ}XHfOu@r>9d zFr&d?$`TwPd-fy8Zl-6>#C1tIWg2ZvP*ypn29^_(#M?@naByI_ln`ievM(q;_LISa zSN>wu_hK-N!fo^??Y))dnB9MN8>A#*|ALbX1NIiau@nIJ`|Z@!pYzy2>rU&N9=7*U z&bSbN4+^c<?2Z!MO5Ggho`fwhAS|*Mez(PvYYVLYR|C?7@}CFmTNcI3uVPiOrJGea z)@aQoGXJ72waP2D-6RXPl@+|{J)kLfv*>ipW~Eti+)9lpcopwe`i^8Z#L70u==eC) z8zx69+HJ%Wl5Hq{giYd7>n#BuB86NFEsEM)xKg=?Lg1o}iep8Vm?(wrV#*HL7?PjB z-U6RWFG4dcu-LBDqLU&$-Pl7$E*114Yd{afqz9V^V_$<D5NM>>b8gB&SVLgS!~4c5 zYX~{Wn#p*MN<rQpdu8FQ;9a&4(N*HknR{M|hrn0AE6QDT(x1KSk5u>>6V2bS!$FjD z_aewsTRu=_p#tf{10LlBf*Ew6>jO1Usk`PmIIxVS@#N@U0F$a{wgDH?6<o^(NBGwJ z@A9f*t0WirV_&8<6~uF?n@#J=(^&Baax(7qZC3~B?`CfLy}5X0<j?TQMRC23R(HEX z57Sf{jl09~SNRC{kBGeI^Oeuc4JSP#Yf^e>DgpK7_uwkCtDH1!?@t)|`w*8`=bfTN zm!Wez2)2$G*GONgWFMXChZLvsXyZ|cav9kt8H>o-=jk|a0+>6zURAktjrGp?NU&+P z?4co@5t_1*af`B%3b-3733a_21w7odQjfiOrI*ey&f@15(HdN!L)9#F#0KTBLEa8E zuvFlKS<M-lzp^q#<q7Vsl=wHPZX^C}=_p*Q5V?WY6aA3Ak&;$cS1u%&Z&%y~3kkGc zd2ZWVyFN+%!)0Wa8`Kqu#<)I^bS`pVFkeb8!5RVxk?d4r>ZDM&T<x3z{@k)?V_gdk zA{VDTPUxKrA-^snH%R>GT9<ZVk5+-EAcr^hioQeMLrLFYFt?J91O4s5m>x$y#V4_* z=Muu*A=T0ip0==)AQWl~u?ywrTJGn0wy>`EF%^hcndxq;_Q3H?u(OkbKpLai6H?0G zhCwz*M*0GukvcTkt{?F3M~Puwu=*oZxUt?{)x-yyC$GEFdm|lLGoDzGFrQjYyqQ1L zQM5qlqu$y^Q-vI#CimaF+h0IR&u{$;F9kMtQY`B0BxX*vT9M%l3<g3L3GX)wT)<9l zc9khFbevbsKN`p&XLaOMU9gKza>iJ)aBb`8jpk9VPfdwJa=d$}W0s$&M!={+N0L)5 z>>Jd(-x_%>d!Fgw<>)d|)j3^5x^}6bE$T6$N__PiRyvOLQ*+XP(qi1!>tD_L6u}Xn z)C^q+a&D}*>2!Ae@{h)z&f3L^yoE1*DM8g0tDoXFPsAGEp`a6zAPz63=@TgK<v30E zNx>nVYK%{@`@36Pk>I!@L9sAuM^Uk>-1R>SBgx7NSzi%A&n-|86&pjnKcf17rFV;x z3*Wv0VAtpSjg)+Gc!C$5$!cGADdCyVdvVmjdN<3^{D;UnPE_`;_aw-H&b6;O6d9&~ z%Bn~Cm!?p9tL9{Vjv_)A7sZ3<IVhQQ{S$jJ(HNH$p>>PWV$Hw_JK58-)dAg;&eO5A zeFg|x^Y97!fEcfcB#%Ufe)YF5X14Xhnu<Sc7knLHBB}xPqYKyXZauHgU3LY@??;-D zrmOJ=2F(?Wh2gPm{PVEU*$K=!;reVah()D$2}8qTKRc`o<_8;wkygQOr)QI<A?u5A zpbkp<?*naEhg<vJmB?CUt(;XpY{BOzmCa`t<r`Z3v~EC@uisDdv>doL2i|WDa*IKB z-V37n)YIlg%6FJ4|IzttcjtTS;a~b($Kk>XF(*ET<#NeBxTc<IHt6kZh(BOPCrIY1 z-*YAdz*Ctfp%B%W9cm5(E^rFj&PiEKDJYpU-pEq2)9Y@}p007M0#$~u-MDu~4r8Qa zi)oq0G4xfY+BWzH+VwsWqC4@j3amhh-wHEKbu}2cYt-Boa3@wOLYAduD^)`2nG}>B zv42&-7cj(~KJDc(=#|V@-aLej{E<V#`HA2Tf#J@YRZ>t?U0IM{6p|la-yX&N4$mom zx%Ho@OtP|2)>q>H=g7}*!Uk0|tvA&?l!U=2*nPK`o>b2l`j==r-3{{3&z`9`_CtWU z)<kE#R%h?8i0*nq!-xvgCx_>KQA7ikxl6ah7>A;noIg`D%?uJ4J9>L@T$WJMgT$qw zU8xCY)qjjQI0iit;?yPjk3i#c)*0j2;sz7c8@Ux7OT#J>TXD{%Gg_lp=WuJLUf#`C zgV6b+d6a0$+(Z9}4+j`qqEm|SM$e#0qe7EQ2l_;7`J$2jkaX!1s6GsoU*9Ob_GCVJ zxzy_(4HM@A;fFICk|<qOrhzN`^Ul!nv*vM(zeTO1afUr`{9;L4EvKoPb(ogtIq35E zl+U*73)VBWQ?Ko@O+n(+XN0Sq-m1y+@Zalzo##e+#_s&1S^omjX=K5Cig+nYNXi6G zCJ4`}Jgv`&XafD<xEPS$cvK|H_?GRl^Svw400G{YgM7}y@}>eIR~Pf8(;~xSoAiFD zpQ)P8D|_uQO`7=E9Xo|^uAzJ}=IQ6|FBr7JzJBz$c*GR`6gGV<`kO-QQd}IDK{ROa zKi^#GTrog%xssn^XgRrR#wyv4pR_LlhjOSfVffAOAHGU@VRdCuJ~?sG5x%oKi?qrz z`~Q8~*2t+!zEA(}>%HJhM>xv|*76nTCVsE4X;c|9L^iuo#@Oih=DLHTr`r*pB(r=X z9M*$?r|FH0qdiMsXzc`!?**pmS~P{xP|Fg6&_cKFEr*u{Gag7+tdT8vnm$Uu%F0WX zQr9!PbTP)ScwK^{0Kc5Fn{5g%W&!Rr==Nqzb2+A(u(Aj1^H>rc-N?PZmrxBo$KaF| zH5>OT`S(JOa;-_Mgi$?{YB0t({*$oTN~Tu0SEvT+!xu$g^wqQS^yuPyz~A9Ub}WFf zi<9lt^ZD18Lh&aVD_DB64(7H`6DfZbk8|rY2442qf$eST+L2Dnc;^Q1d4y#jM$<pK z?75l;neJJx-L2jgKp`m+QdCE%fyKdk<5cr$ii?kU!KWXQ$CwZU`8X30Q`a`<PnG&o zbV(am5^RlhsxBH`PrsUB>x8Wxb8_lXtC{hbJP!pXP~w;ama%!HYlUT?M12Y(Tm}xl z>d#cmC=Z!|e{pD1I7N7n%+VBCzKVj0axyxTPOVcmtxQYfibJG-QZqMkrlsuttqN|v zri>;~r9&cqwswV0PROAoyE7`IAOlwvMTeo5Nus18f%CYGmibF)e>OK*;dA^p>?-WP zl>J|T{;m!_$G$`Lo9wI?$J4h6(f2P|pFTmb{`bR2Q&N&T`T=_e>!jzY74HB<EzWh* zJ3$l@quvdN@8)am<L0$h^uq<`luz`xy(+XCCz-EDwBZ!Xd4ujPoo^b6$<}krd8xSt zb84d;#z8=)tD}VfB-3)8Y*#WhDU*Sfi3UqA?kJn2OR$K8g3RPs9)<rTL+)j|u=ZXq zGSzkKA_f(KL_2DcY&kEX1qq3I(@YVJ*=?8{;jef8mEM{~EuFxid<PA(LWaLXS$Jsf z?pg=;qa;MjzBgJAk7DB!rE;SLA$B!c_g=aynXB9S(XUs`>{GV({asV1oZpJdGybE1 zR{0&U`!ICTkXK+oQOLi+kx?l&Z02!o<9hUPiE$BT$}k-dL93sMYr||72Af1E0A`vT z%;g&C2llx68+^Gir^h;zcRE{jS~qd#K}wBqEI5%R;f#u9Aol7=6b{W)W9mNjctshI zj;_3-oV|||v@dKxK}eKCRV5kg_i~tB*jiWJb6HA%7{VUv*|h#5;JcqAqc!{e`TsK% z0Hez^|EtA6mUmHJ_x0tv#7a5d)|<NSnEF3Zu9z4H*fhCKE?jTDHm2GXbU5D#-=S6e z^CS?R#z9Rd5y-G+T#uvYJPHpXWjQ`DW8IGIp<+CeuAs*_-qO65NF=L1AP-SGFkihc zalTZlPbgJQr*7m%Mb}qm61M&4`&ey4YUn1p;(!a3T_XJTE{GjLs1|AQNGGt%^iVq} zoY0tv%q3NPebCmO(s;3kB5T*U?DI<bLrCM85?JaH3Kf_*<rwEyN$F*u?CPKH3If|e zy`w`H2u%~2DOM@}!;<>s;|17hu4%p+eZy*9^L`pm^-5x#VXs+fh01C5)mMxe_W=4A zjGS-dj}~J-h@zoG1UN}6G}&A%s3>V+kS+l@mZ($!^#eHSjNp3)7N}U`AW&jhSfMNi zFxQ#Ls>|vbmBh?PqXQ|2&FC%>g+HBV(fxVDty)4f(3pb09H(wuP+hc@R4A@bRZu|Q zig7A>89?+z7GYTC3bFk^$?pFf{{HKa{2z3K3m&U<ve;v6*$k|QobS|WN#w#bfQI&l z4dzrbgpd?7;LDQP=;-aXQk~?%6MUY5&mx3ixXZU<WR|Tt=?Wdl%{wiKM9S^2H$vh> zbZa#q6bO}?asTObZdzUHyy{pNn4d~#dfCy%Pg?&wxW%~bcf&^N_tuuhh)Q%i1-9f8 z`0XT+jk9pglV3WFQ;V2TdUI}xkeTcUD--ka95V11BK1c_;LCCUd?JR(U=_h*!6*6g zw1R+rTm=vg-5~BY_^~gPQxr4Al9W;;!8<80VwA~bzQpUdO%x)UsOho2MD6}mhIteI zM56_BX;{*P<9`mICs7byP(G+m#8$#~P%@X8B7XHyB(?{+4ML6ulfRn>l{hE-Q&UoM zTA)M-&~iiGg=tH?%<d2DZv|CcnWOX<Ad;4qEl~j^$eEfM420?i|D;}4rr|hC`prqX zm4zd@BBduLU0j|K0IUanMes%IEX*j2!}=m|PfVA((4(Y$yw<|3&$w~77%bHOe_xmX zwHL32dHe@Umwkx{9g-H(QwX%PnlG&0U4pNM{X*@-+CFPl{dNbxC(U`C0xfxMLOkEw zZ0Wr7y+NGDKun9Pmdvz{p#U2@=NQ~ery6Hat?ojAXOo=1irkiK4DUL*wxwI*tjJsM zG_!}MRz(->@jZUiz}LNzdJq;nouc)z)D;#JuJkcBRKp4T)9ZY#9pdZy;x2$OBs}Nn zfu?EE>+qA#3<qf-0%r?sIJ8)t@R~CSk<uD5=8Eu|8$3traZLbrj@*%ig)GS=agh2M zn=vjoq>VALOEFOfY<e)6NL;YqtRDfXaVwx$i<gAX7}o4(d{qv405Q%DY0nXwoBkm- z2+G`}1Wl+PF`m>CaH=oRX(BRvopFSK1l#!gw(L=PQeOTkFtrfpG(_hI0o!E=Fu!Pr z9K_|z8tzAy55^u8j;&1!0i0Mo$O$}247HCHQ+}v0O~JGeJ|viGOOJCLj?g*81t*PU zigTX<Epf-r&hXWrxU6Wg)zn91Kgf$lHpp<#%D-s&*FMghta>!;|LrHllD33n*NLoo zqNk{faZFPG{}+hzT{!b4Rqe&@sX7WeQ$f+n-0x-bL8>i8Yx9A2x*&_3W|f3}GwD76 zT_a&wr|}=ALyy^nwYzxsrduyA2>sSOvOi9|$F?4;9!9XbFI7LO(=k%?G}O25TpOp? zj>oTabXGax(he2Yg$6oXt&cLU2IXpIA+Fbt)_}*lmWh7=WXJ7J<;8A8779Z@Us2KS z5@7qGih6=LCq(&0U*dKx$LwM9;zDwV!hn!D0dPa0V^F?`>Vv|+U|@t}g|Tsjep!Un zgojDm2U$@glGmET93pe?WRnZ+kVZ0}GGkCtprpBxD{qhp)|v-@))Fv$*SQP?+4Rd4 zIQc%GdpW@PO3VA88*qNDL#oI08zR<d^7VL)M+`XLAZH(WHqvAJaspgtMh4^n0R8WH ztxCKkL21KyDf_I0j3mzR@ffgQ3J5seEKRXa)Ed>LYL;6(o2DgSfxB;^X(dHEQaE4b z7CYHN*b9x}?X&=80wf2u#pDHhs6gcJF)I%6k2Tw0vfquIIi!aOJ+${_(arzo?7l}M z$+O8As;R-ywg0bkK@Cs22KTn?>8)mf>~4yq#KtPR;rOra2dm0$|6)u$lP88QL58I- z4DWRJa1<Bc4WgtX{3REe+pQ~hI{bX0(IS^&$cp(xN2mLJY6X)UCJ!@1Nv(m$P$P5e z8z|xFkTqV%=O^5<db~S9gImPm3?<a<$sr?B8V1ZnLDh$bU9F4v;zz`6$wuR*bZ_PA zI(=m2*e1!L^f0@QLOD$&--?u~6zPva&U<6ox{!xL==gxARcHlb=I=j|Ka_&j5f@I3 zJ|m9<6Al~_0sur1B>~@YV3kgvprHEWbYhrZO`aPE-Vw)D5-DN;3xC2ZJm?5P0^`!p z3W`QTepl$qOng5{*J#q4CMWbu72Qn~pR&BxYv32!JHrrq1{3EF;%!`9)(+H@ThKw+ zQ5~#bn2_}_(qps}C`uOT)NkUt8EbV>atnW&W&_y#2tq1p&1B0(9xX~Y@aNf>X3_GW zspRXYB6g<w-9o=(!@cHXj5FdL(drqSNlU|l3BZJ`5Z-<`fP`4K_c3nQ5OS>A>K2)C zA!Kj-*U}al?E~;HpP0BU8q2T1#%JmWV19;aQg2xqs)kdv8+pO^sc{zQe|$v(PCyWP z1Z)3rAEJZn!<aHtFFyXoSjaz7x4D%%fxX>L1^V{a7c|J9lR3dWUiXsS{q-sNnb|kY zXuFKqzQp#BpzC*AG~vl<=!~a^wYjDT&(`Db4+ft_5Ro-l+1@dMly<r_(Q3tOXViX# zWx6pNUU#_phi)CCcaS@+b+gIpUSPiDlI02JI`KmlUl=}5kC8bt*Y+{MVYZgN-f3_H zfo}=_r{i9}J2W#J6Ma|+p~>k7Et$sOAl6~d#_?KphQ`w@mtw26!;;ry^+<Yl*eN;; zo!UgZ+C$9d2V<hl8=w)#Mk%@Yj$amWFIjVJP%tfKh`B3zxD=>o5iID)#qZ`n(BYwL zfCj1+Hs?WF7Uc*;Yf(et3$=v9j5vlBWl^#aGjX3nz>JJeMCt#yZ4!m0_7V=MEehNm zlLyG1MX4@;vH@yZX@zEUWR-S{Zis=zu}RJ={3^!~4${JB36du$J1EkTJLoiM8>LVz zhEA-Ck(Vs}-b)lBy$4Ygv<yj+Q(U7h78#!3B|{aXMf1n+968uKZ1-~s?B0I)<HIE0 zvf3V1RaIq8)jf7~RSo47O_dZ)b<KE9WfgH_l|t192)7`l$DSXtl-fhYv2l+`KS_e1 zw>2~_CoLDZ3^jsj+@KYSclu@A>UZ3d`_5`ry<0C7nK;QJ>gwMJ2>(O+RY4e=zJ!Fc z;NrmYuOFn3ZP?f?kc8n+;zsln(BH<Fa)(**!a^E$smcG??I4IqJ~t8+adDS&N%3z3 zOf{CXBsP}oSwzA~sJJ?@;I7a=PX#&Dz^H(N2wIJ9t$SK7Wy<T%zvSjNvhC-qeni2w z-!o)1bV#ZMbN;$qRLG1X^NX$z@{>`LXs81c$$!pX1E+}nKOzVX0pKUf4(<?$eCEPi ziNc8}<OWtSa0s_$Ili5+HDsX!DF3OBRnov>G73UO-#cq+vsfy%U{@ds-4Gl2chk_Q z>01bp4Q44IOriYFWS;Zc1o_=S&pwD)e%lO(47`Y+7@sX|yvX<Po5zn6B|uk*_U(wp z%fv==>0>sn`cxQTN@)a;3(K;$9@VZ9c@*{aR{jGcF#<a#B-p;xi0zv`mJ|v7Wj;lh znWQsk^H~lOsYp*Zk)@jD!&u1-ZRptB;C~w%D!%e8<3nxWm>~zY7yleBWv>|LJ_Akw z-o<(`gT1~jb_7OpJF~wQgiYI2EDS(>hMAlR28$z!gEZepO;;y7K!sJo)_M_^>CKyr zJ2;`IZdXDR!R)I~Nn=#h0qv0(Ax2Bq65c(RxtALndtBMBv@kjw%<wyA<}HBnh<u7S ze4u!JJD{K)G~#5ei*k`dM~!p>7<GqvUR*e@eTie*p_6r~f)A~z*@s@Pl2VbioF+;i zlEX|;(%@Jyqt}Ql&P4yN1k>^`9*o<?slA>e6ALx&0z7fJ!(%aQ92^J|AYZc6?A-5# z;hXwDtuh(zY4D!fjwod^g#qq4vl5RRF%`Ng`P3CDJPmezjaQ<*hPTpDQD4F$Njpca z7Bro^M$3UY9n$@&)xZkH5@d0ZFyweY>E`b0fJ93u8W#1h8#+S59_E<9r=NEyaY~OA zWup!tkm~Cuisdl?QF~Mug8Va8S;OjC`YQVq#7u=v@%@4(T&w~Gpbx<;u?)MJ(gG2B zb08@eVl=fAjH~#c@V^C&Ff9wF2)ia28y%$Nfy(BIiWJN=3Cz6B^PnA-9a=E~NX{se zoR=sls}*N;2dfeg64dzUrXc$T_CzfRtcF1?(Cwja<e-8}tuqT;vmUXZegITZ{)A*z z;r(wddDu7R1N*dy_>~K%O;$*a3L_x|3lqMypd~LWBWuJdZMupsCCXm44Jj&ef!LAX zU3V2f3{yjli>~oeu&GHMCFOIbOEGK9kT2d5P|2Jjs*|n|&N=kl-t%mU<zxHuOkrSX zh;BH^&~&H0+~}C>b=51bbqOJM+<LW{o6oy9YH4>82Y2Sq53wGrTG%Fk|Dp$Hl+6Uc z@hmdUQS%|A`q7ftJ?>zM?=%i|=xDA8xqM~)9CTX8Ob6T>Jg$7~*ox8gTxcr)U=&J= zgA8mil%|G1t2w-arYaO>gI%g|@UhmcXJgIZ29)yD^fYz5bXZge8jn_Cp1QUhZ`s7# zZL)vq-cS6oY%4Vx0Y5{7rUn-Tw<8u|&5LtTNr3mqVLlv=SB5sWM^XCj=n<mN84Wyf z!nEr{dw%qjMTlJJ7Rao9h~0!u%u<Ruf`22E8#!shY{M9uUvp`3)mp*%^l1_52@*L{ zxd`sk=_soHL@XE&alt(B{CagV1mxr{4)%@Vv#U||qrfHep8=K75_wP}5!tWen2W}4 zr6cFgvqpqJnIaw(P^`e)RxpYlMw4h*(MPInCXYn3veScJ`&m&6tp|l@;Qq=Kn`L7D z<e22N%XQ8N%vJf{DoTnAoa20HKbE?#H_mWMHWxbSrMY9p_ylZu*XZ?t%2p*VaOx5@ z++Srqmhu2?7Sxi1k@oE<Dv8eK|H4T`=gG&P(?tLnJ4S@D1p^DGG(GP>i6k3=;ycG! zkm~Qa(<No(+%b%G(rVEu>ZQa5XTueb<mv>N&_eAOl7(6%N_7_DjNhv=MHF<9J&K+R zB%&Q=wLh3hC*x--p+61LJ!mXSfSDNb{jF&L%QgjIdyP~L6s*wR=eKTm2gN6}faRRr zNnxcm;XS}v``}#U7Fs~WwS1l(14V6<u3eQ1=J&3G_f427xa$gNH5Q>!xdxNgEadWu zH}Q)S1Z;s@@DQ0KSAh4M5I{jgK3uHC=a)7peE+bHo;pr!JeNOQtSTxg+#JkUvR6fA zL7y^(h<sOgV`Wq?D=4Z}ZWv)XY->LD!@1$&m#C;{mU2SsZ?s>52>}@i{o7nfzL*SL zN%r<tInNj}+^rhVI<n;!XzCo{M<hsas*L^PMs*?k{mtF}76xum1`Z~i8|JCn)oMQk zNR48IqH3cEexY$tg0>$7s6gxz9_9bO-e4`>8_OSMw$fWzdNn%MHOzWUo%|%OdoKPv zrAY^xXM_1L1!fxGoy?}i*WY}ZpO~qgopr#LciJRS;aKt<h0V|XQigZ(+8e<!MOf4O z2}ZB`{yOq&8fw~b<lV3PYL|~OxnjEII{CHXkAuD^UJId_ehkb%-m{Kz)*h|~F`~vP zj^8@o&D+7H46&_BB0iz955n9bo>{xOapLwg%L(9QFz^9wfS#K$`+=I=zI{aP0ly?M zjZ{i+QGPw?J4QtQfTb9=<kFFjbvIrqp*h2_a#>A6tP1WaNdUgcej4LXe5r&BE7lD% z<B6D3swuAi*2Z@z9_a!VEHFL^>C|$55lRou9OL=L6ymTz!TIIeoH)o!;827VQXIQ{ z@BwH;WjNz(3{lA)Ht(n;KZOLdY@~6n95z*;`ChU$6`I2-`2Zg!WJW}=q(Fjg42&l` z*Fj&1B4fqW3nJdfFUwq{Y$_htSlUxeb!IcqnM=UThvZGzvb5W!$755P>qOH#ZUsZ> z_JmepRo;e7`u(|GGH!oI{FULPA8=ZURYSwA1<uZ`64JtkECBrfBJ3U5D+}1A&DgeW z?$}AkPCB-2+qP|+osMm@V<#Qk&Q4F>@64Pz-^_K*{D-yHuBUd@U7pQ4KMjDOUe)`k zSE$v04E9lhG~5cr0&2?w!Gh#QlJm^J2tq*~kv*Fw*A~@*xY)utgz|9Ap^cE=?YaA> z8p%@cO(h?-IrzFNvFe6M>OuS;dU|<VShW!47i8MAgYA|on(A(807**-kIDhOLB2hW z8`R?>1(8K(XXjIvPT2xz>(u5$H&pHZzA4m%d8((-PBE3L9;xzm&F{*k*l$Z+h=B1j z6PHj-h_5sQ;s8rAJZ!daZLKiK@H3!t9xO{y<>g}JI7I3dwarq-ux$kmJ!6=JiHVjp zT!#$SNkS%8Nhwk7XuO8TB~_I>nr;%uF#!;TW^RB3F?gf8PQtCQa-pX3lPYLvAH|aV zz{D7Vii|Q!dchez1qC9xGLt)>VgxJpmIN*#g+#%-rL>F!Wn-ScxxT(uDx@iy?5QZd zSOX=d<{h)vU)-8Dc6>+6*fR7lDhIt(`O2WP+J1Au9sj1M;&>Pj%j`+vKldib))5o^ z-(eXaWB1yn1FzhM>N_|tocUP+y*5aWbY6IGTSRaDTP`^S(CEg7X~@%>*j_J8n%qM$ z7tAU{Mos_(t$pWFOscOyP}nrMoH>0z{a%Y-bD>nN<Vz0rnppe?KMF@|aMpz^<!<(f z4t59xG#>w=+G+#MX4Q9p&ka07=6Zo2=#Rw(q^%pr=KZ1QLX85@fVcXG9q2bw@h7ae z`Z%as$Kao6m#sU))#;q*+GTku_3SlU7g@!0yU4>aluk{IV-G^$GXBj=7Sr8JQ6S-E zixNkiB=d%$X8<Vi4-%%w(Ky^8mi33a65chVhOf1q<R_EIies@D`;<0+hq}dwv5Eeo zZjy=>qfas9l7=<v2}<$ng3-W;4lBG#<Nm1#(@9?*H~wqt7FgX&CKtw#OdCYKc%b`e zkaI;WvPNbj+mxR|KJMF;CIL4xidS}QEpCAUAD1RGohma^CYy-ISlWS=TX4(>U%OGd z(X80F%==L;v5y#*EL$Ch?NerukK*JpqHzLxjO9&x_wsjd8*y!e-8Vsd<#p#5Tkjx( z;u@Ebk8Xqpp#$WjYr>W*=|Df=S0h5}<!>SLd;1+cJ*_va^J=`{%~Qo<4{}UDsJn8^ zqOV#d1K1mPVOF;l2%{TBZ;tHm!cIv#Wh?65dib2$G7``DATp0;3pICEE`}Y?{i;)t zSD9X@2NlepbxLkcd5(CEJbk@2<$1{*im7NSZH*#A2730$j6l=O?~2rO@o*rY<~_|h zrah$9k~U6^z8`z=N~LVO8G2PnCEH+ZAxAUqh9BitvBOf0H(Za%zF!#S9MwHED*s?` z2^YKl1)VJ*6dSDpu8B0-zqW^FjC8S36s+qB1y5LIi5@}}^>aXz<`FIinQg66f5E3s z;m`bh;n&Y1R8)!KpWn?wK2^_@BHHgpYg+cV^9r?P^fJL5^lNnar+O-u#fSIsf}nY3 z7`|^mU{4Y+@)SEbkXYKVZxB&1KG{<xDu#YyDv5~t8CjtfI~r!u82qign(y2pc&`CV z%L-Sn>T8f*YV>T48jdl>y<kxXzM-&j5vc)eyQ-yexD@9OYsTWNfirHmo9Q!~BX*m> z^%#|b(AQz`w5A4VWD1e6Zp1Nj|IrJ+PA5u)q!6So{uu?ERwtMHL3GFe5AE{0KNoSJ z=5rh*>u&5`U-CLm?np5zG|OdoHt)Q1hd5JSqt!R$sQlMA1it0k(WVAjE(-K`G6yya zKuN?2Av{Lw!HkCy_mjh*cf+PiC>98M(X{VKX6v0OaKHCKPiy#v{tRXdnwh4`%T;aY zw3M(264K<t_cd*;lhlZ`$IwqngOB&G(&qCCHfau8a#w?vg_>W<OAbu|u!SB<y{1M` zV^|3nIIbQkhVvCFZ>k&Xh`IR|T3JdBIVuO4-yps!K!&4QB<=0$nF&WWB`t@shz70a z&We&BrPJgaNU{18@3B<s1cgP114Bx`d9c?kOiwPif^uS2JUrzPKhouC&AuY#a+vCz zdSlh3edCW|XwdiXU<3Ce(}((8Xax8mF>;*OhR~bSOKDe+GEs}14~hEikNQ)s1k;MU zuZC4GZ(@W<9dxXUFt<mGkEpC)&<2njTOYk<FWV(;pRV_N;~KpYn3{3Gw<QAJg!}aT zlkz7VhVol#4zJ}4dokpMwYs*Zf*tTz(A}GiIU>7e;}KjZ7PkTUN5#Qb=uL!f4e|Cl z7Py`B_7EKmK~^#kv0sW~4GJW+4WoLMoPQ`USF2VAMBO1jn)#&WmsRXe<s7%1DSj!| zYUJcotN}x+XS%2=R0~4o4|0je_UEUI-8LR0NsP3XdlX*d8hZ!nBWL%-OGmBfTCgRG zoEBh47=o;n!kCH(o2i<0sf{pVX}Y@_YiatUNT%U2fsyWwwU%_t;<uH8gHYgk60kS0 zu6R8SH2|_;n3gC76COA{Y~dyP^8}Kh&d5;__;yTh%3uJz=JoeGs8RdI3qO?(_p(6W zEhIKnA_VVO^1IuHnFG@e@rde>Qoj0-bNQ!|U2!a^6D(+Mk5<?!qQ@7(csUdiY^VVl zJ}E~cDvQ<|m8l(;Ts#F`cj~K>C@vuhdjEuzni~Z>zmy_6K^0u}`5}jLp9C^&r*yLE z1<gL@u+XI?ohM_ZkXted{G}hIE#Tb0AVxNNf;E}ZJl`eD_Q~&WQQ#u-k2>IT1ZQK( z#n54e<33BXrn^JyTU(qq>X-#J(&c3%CkoY=hW#xwQQZ-5fKFf@BS97+kKGK{aQXE* zCi+~5JD=eua|G8Vbgn<xBDVk5DKy~?r96KIw|Pc^?JoX@plF}1rP8p8eIHTQfP=Cs zCkbNg_JA_8OZ)k{cn-gXggO#*CQM@s3X<jt!_M7ACyK)DK19D!U<rt}nd30m3u^yf zXtF}bmc39kR=7qj_xn0CsIBML@1LwcZw3wFYhd>kH!AcFQ#B*+V%MJ{P{gDX;Nb-# z@tR#K-!1X-971h}!4L<?pJ8q&y1*!iNb{tV`O)7*MC1Oj<=(SJi<`^eE4EDtMHFex zW~GOnWMgD=FtXUH8_ze*SGv_})l9q0xG<nDvCAm5&9$B;+i$R_)Y#-JWFUmhR$=8W zI<!tSsnK?prkgBt0p0s3HWjQ^JIi-*F`jA_|H_tqLc@)4=~!qzNp}GF2fS66%AAy1 zhsbZ9qo^Mj8NcjLh+ni1x9rm19VJ=~47wr+6>|j+3)U9DjK(xxB06{!<rD1HaO<^k zSA^Iko*&BuyBzc!->uGcyAO-!z9IWA%upNas(1`<uKTWo?^C-L!|4uiU^7-M<|cn) z3j()3+X%<}+Fd}?YXXS2R(eb93^Ni?YaA--wXeWn9nJ6HZz>wCdwGT`7c6eus-5VK zLk4zQ-LM1+*Wl(YAa2}K$7gVA3_L@L6nZ1S1z#c>AA^KYqMkYnHgobmld~<FPyH>v z5&M8sD3SW|=q|*o3MDBNkoVJ@{(5zod<yn*4>cRBNE-!?(eUwH1N7w=ErxGpSEaBm z^R08_9*(}SHE0`HO!1P2*s@Dd`a-$o*St?MZ}=OUW^LQNfQ%kT=&DYl5o%MMl4Sx6 z=1k+B=(ZX$N)_p2wP60wg-dpr$oVF5evuro3pdn`v}&<4^c>%X`V2>U3~$PBxuvZ1 zuGVUb#R=U;fN6%51qi(jI$pN`{U<q(x)k#o6ix?=yazkjsp2Rmmt0aPrtefZ{)}0b zyqouJ$78JHuFy1@f>imh|Kh_;W_JrDDyo2;RaHt#O0EkxK217ZmXAYaN&cZHMqVt| z8%(2Z99v6QvgFnjr{j@=9HIZCqFh5k0cLxBLU02jR-2FT>d>;0-fOWKB(G{hC7Yk$ zEZ_FCO71~+A274};PJY-Hqf8fTLV^P2kJUqj}x%%kf9;orfZo4T_YN}{wj4~^|NiW zXo?Gp<Hq#&Uq06fu<x@<uw!2GWpRIQo(uo|c);I)+nuG%4Ih1T)i4<%=K<av1KVLX zczaYR-R{e`1BKnoF?Wt{CS>#Mb}dAx<>l=XgZmP$1~^a(aY${DzrL~HJb}FH`I-rr zqai@Jw7-_1+n%k&+W3gB;-nUALpMP#Y7)s8jBSsyg^E;TgtC_el0RNc&O2W&N+q09 zP`Y4{enyjy<2uLv-40Yf8O9GuDVT=wZ6ANx-wKpu3no%T^5<o_9LS`pVNt?T5n-N2 zZq@@H9g+RR2BJ4S#qhP=Z?+KTV{-*8ZvL$~fnDDLsn}Z7w%XPL595>l23#8*7w6=; z>ukw{?EtSi3JkgUBX-MZ6quPmoPHkCOTHK}jxt=jyJ{<@Jo_o+dF<!-?Ge7I_p<(S zb$4A^iToVF7IM%%xF1I{UC~79y!riT^f_vHn)slSZcsYPh?l9o^>rF^@oeZfd~)ai zFJe>lx-KD~+{(>y!oxgu<WlN137KtZ@AeYnipMHOa4>eR(M2VCeX!Q(s-T{I#`e9x ztIJ}zTGHtb)A3VvJch4(Z`ILpM2$rv?`pfO?axhE8>QM4U#o&Kagu=@=(Wj%N>5O2 z4FuA!IoYcMz75&KrY>`=(6I$dYZXgfcB8HH8N};FG!)<Z7(o3z)i$c|V6g--4Nj36 z>SvLXWlYG|(gWPzbnU`%N)aF}gJyQs`MkP@Qh=ju*oWoML^+OcCubp4PL!~0#fd)n zv?q*&>=BbPTjLR|P-Czd<9bP-9j-H!4`V~jMdDjWj*z2%Rxv%o@w{jxNNuZ?gjQ*| zW$Z<m2ZJ&{pA4X}-d`%NS^7&e$6-v7+ZsO#xl6XsU4IRdJLifGlQ1Wc1an~;k#89r zAI?ArpY8Mw8(DZQ;)*Xpe@51Z>Y%OB(~wgF;S+`dw9bs@blU2!WOy4GS7dM|`wwK! zH>iv(63W-wQj_Bs4doD646e{M7li@>=RYD=&1ZJDGCX{?gnSpH6Km!SZ?;}vR)4Hg z`0s`}oa~;=@Ep1Vapl%N?RG6Pi9oMhUPFF+*0pUfc^u5fg*vf>>V@mU;(K09)jsUH zGs3k4A;KwwF>Z&8Y)x5fwa(gXY^F~=Pm`w%h*dj|-M4;u^vBNIwkR(GNNwbC9dtM^ z*<=h_MyBZCA72fJ!=^fJDWL=fPG+x+IO^vxReZiC6djo$^CgC+k#5pCyh_@>e9pOE z{jnKNUT-WN{>{K2OHx-I^J_5tPTsR#EGSjtH|C4B^gx9o%z_(I@4(VqoO_WI*rk5E z|IRdl|0Q~Pb*l3lO)KYV%Rbt+O|$x*Z!LDa&O%yO&;IEOW$58M?6jNMO5fU%9*C^& z8)F{BoO=ShhlFWR$N;mKu9$dGkvs9hNY%dE0gZXJGMn9KyRsBkLf`K76Rw-A-2?vE z_RC!m%(ibRy~=)*s?P%^q5`zB(QG_&XTc=7@I!Iuc|KSps9UPyk;6E~E@y{#Xsd^p zjA;Y!(PETXAFsvM<ur}U@c<Hs5T32zdHwju{h@3UAJFJ5U9p_m$Ph0QJYip>c`n2) z$nXInxX!D0O2ou`%x6Zfvzhdwn0y+M68%bT($JRQRu|9Zge(>&tcY}LQ)7R6aP1ms zpYS{Kr`LViLq_6r_)B^ou*q??OXFtmR-ZcjY!op0O<>}%7w=v^yP^v|H4$Ol+ty#r z(XAActeq;M?k^NN!zTI<5_E~a$N_`))c-1Mgz^#<wPQF`1YU$#%n^!mI`tNAWtTp6 zT#ZITOwm!6aSt_Ur1N4fgGe^NTv-ny;henVUq}nVMF1k+Bz-r|6DVqtWxN<<QuZKU z$(Nt@pa|9keW?dzJRWScwG13xwDtKo8G*DGq=cM|oLuk-sx(6KVHt#2W^N&MR2c>u zz;7c>)SM=XCOP>}X#IE&!tfzRVnV7K`_hDZ+-IhIT1jb9=oyST;ldY1=PYwDYK&ww zU3K*2GFU`OVEyETS{mlndiB_h_?^^GD6%NQ<#tRjPN?X@{Mh^T@hydyUAL&YD?;_& zWyp<|#wH>>r)00!ZjG%fT%#OcBYPYKy(_mjp3A3TFOSc-89$`DmVieXCIRT7)y5h8 zQL4M+Q0ywV&97_!^{cVZloREa+0x9+VSQGlo?`T04oQ7)^rso|i0+i(xJiaQRB!jG zx$CI&q{O4#5)SuF#Kh1lgVCEzi+x1eojk;x6@#F^W79VI>zoHN;W;61Ss}OdfxiE$ zFU{x({^|M-mmQ8<)Ekjz9u0;_;jHcYJH;U5XZOOlhDB~RN(#7IouH)QW>AN|TOR5g zdzwCxJN*d~qrM}s0Oy;5dDK44%fY{GA9;>@V9rH69B6b(7ai5pHU7L*$EC^b>SZTA zgS{mzdL>HDg*w$n5ug?P$YQI-w`B3ltvA5)g+@aIX#)8J>TfKr3AX?2g#zo7!LRu- zeT4Y~gNOmDPVmA3VR?PQ7CImJNoA{zfdeFPmw#>ae1?wz045-&FmQI}Dh>euP=yL% zk>4@yPDWDkd=3>)+h44w*xIrlR?B+1J!n0ywD&eB4@7TlPyC~pB}2U!qMY>hJ-%Ms zK;4USz>PeJFVg&`sfSZZiK6c4b^e7~8GY{HU!v!OuJz*{moE;Q+E8l}K<PD2FryrK z0oXCA>|j~_AO!k`0xf&j!Ex4~lp{zp#tPuo+Fq;=4jkYCz|qZ`xhX<D!@31<i6U5X zQkAJqVq(pAE^j|EVyx~>d=#<sdyp?SqUFB2A~bJt9s4AksBk*^Z04W^Z}=YT%3zTq zj-c&#SRIS+>f*e^e|iFaD&N>v^}~J1NNOS06csfU+rcCUdd78eVg0-$RYM#~PLef~ zpHwM?<LTFX1`-6}15<K;$`dI@iZO^%DSV`!F6m@qV~cB(!=r=gB!#nF!4_~8<arML zvRoNKHd4es4R5R|C^me=_!3VQQmD?Yt?81JgU`d|;s#6C4#iY}cad-nhJLqF!9PkT z=ZCPsul-Ijl2|B;?{8gB8+`ZA_71_PdjjbVAECU<MB3ym`yNVWbuzytNw7>Eq95b& z=3Jhq!=vw*aEw8-uB%03+Ra2lx0XqxQ7^#dwI%7G{wdpk{h8;cT%kXu1a<5fO1mfU z7i^(AELs{STgl$m+M!Mg+v>Y$0fBwN3(LV^^hQSiJXm5@1(({Ukqy!1Y`6ebl`LmK zw<gGm%m6LqWv<H(_i=zUL=Ifz-cXeXB=xpzLdK9k$N^b9HvCW*H<J~R>K>_krFLzF z!Cd|1M&4pm4)N~iT#po>@*d)CW`p=P(v^^u$W69|=Y7NPSof;gmu4IyGVn<6=33|S z6d!5hy4ysMG9RP>B#~)FoI);+aq9wpfJ?aIpe*@kqnpg~-TN0N33lMzSU_k(F%hN3 zHXXDBK=0Q3pl6N=#I#cywW#z1d`=I?dFW^!S&^QbWBui`^2au9{;ZK<5@f{WzA92P z;g$Jo{3EdPwnz&#Rwk(A>vJfZiTXX4pT5G!;B!dj_=An=mJ;1|4g$h;`p$|FUx;zr z<4ofrh1gsIsEY|(ZbEc<?r*Ox2l+P%;uiIX24w#ccB3Zn%V~7SK{;sg>%IdS{o{+q zP7Q)!m|XCCv#AIgOkrav@&@pXzxwI>CNRT)@w?+8u6tw4<LYRC_u?}p%|egRAZSxE z)5>(ll7_|kpNi)r@;mb=Io<#M0DrH8{a?6YU5|#PrR8j+nF*z2n_{wEU4^EE*ygtU z{Z$ifq7A45`RUzr>%P@hzZ!@6JR@&_++6j13@~z&Gn0l&ZY^@VsYfOmft-<vRG~9| zT-Xbf66qdEYdq-@yUH13-QYN-B?baVEPbsUR4ADv1(5h6y+F$2KAteG_?JdnTB_;5 z1|qI>_#9O7A09th@=x>OE`}ygjyWL*;O0H!wt=pSZ-C^e8?T8|KlpoTh%>G0TsTsf zV4iElzL23g#hN9gUe;N==iiVd7een@?>{#8CBI6DXL0TODhq(GMF~2Ly?v9!5@U`Q z5*oIh_|7ZrvyL*i_rLOWe2W~gDpQ9VO}QOk$0k~eD!PrZf80zbV~Oi7vz{g)>WBv6 z_BhCsUP^`Zlv~NR`8Ls!3|SKs#Pn_adz6d#pmfZK=JF42@muNO8gVIcQ3t&|30_ca zPla^o3wg8kfdQ`*x5}duTn4q@Y^J|YtC+xB)V)7%rsGFLs9BJf`quDSyYO3pJKJ-` zNal!AT^famWgt_w9nk$neBFMtzYQb@n5;f>X!kGuV^83fKNKi1y+`l+59UPgw?-JX zAXp@+=P;x`Wa^N|m}(^CF!>dvVn!c~=lC;`nkooJ@>khYNbJjV?|C2n$7X)+$yk8r zd$1ZF0d1HbreiG#hDG1b8?3j5Xbf6rB5Y2tDBuU@-@*>y{eHH7%AnuINT1Eikm`ho zY)k^5wm*Nvo{QdHo|kM5kIB<<dD@&zaGeVQ^~-PE6c_|#9KlCL(5Vc7;?+76ONMCd zBIu~S>0%7<2AYMq_h~LX-m6e^@FD|J6bS-XD0rm6s102=8w<NF{pC*TFHcRs@T$SI zJA!`OSKZ9>&6oS_Y?*ESgqnnC9O;upowh+O@qZ#)Xx?FbnFdLDwrfpjICX9R#iZ3n zU#lzluin;zkc{Ry*<KP_1cGymvXXTL&8C+6==wajn5+lrP^{@$1y_vlHqLQg&=;Sm zfQJcCaa7_uJpAVAY3Ka3;~bw4KgX(ZTMEwhr`bpPsk&!lRH~|t*Bhtvz1<P!1|40i znvzv@WuX#Bu*ABQo)&6CC4Gu8cf1UGv}E-p-YGsGl;mxtbPClYT(n6%YyxS(FFy^k zGlO8sOl&I&>2Rwqlb3B3W|uC-o{p}rp_CxuRh_;~)@dg%97~M*QhGY?6Vc5)duoHB zW=G98#BSoDD1T%Gq+xCTkb~>OGbBzVfPbo}gWE-oqTw%OgmKU#wBBNa>HD#w3b{dj zfxtBSU|uG#RzZySlm2mTO$UrNw+rmW7s_{E%e)5_ERc%?rZNC6Q6_Ho%v@JiSV)ll zK)l*+uJHg5R`(TsFE^IZEQzft;w=eu{`N%gQ@f#&>K9sI9>@lzVG3yefTP=AS(s3C zcoFTn7Cbb&Ia&_NhuRM9aS7#M4pK<amx=Ru-yS2D){BfCZthcU3DQ@MR7vpCBaqO* zk;Aq`&`}Ftk98>GJKBw>meXKrp-UE_%}xlfig{e)zW(1dnW$M!G(0>+7eY)TC}))S z0V#4&o5qGO*?ca9VCCIF0_eoK2=+j*z<Yw*UsZrB$BD``4(H?sWL>E+a?Hjqw0JCV zwwrZ#Vw`jtDc1<DSpGehx5$vUlV-?OLZm!5zoz~v|Hgv5rAoi4<P0XbO;#>*1DA%B zNe9K2u8Y@DF8WT-733ys)r5&QsEQ=)ohWbwsc^5&UL6G)AI?U(6epb_{%3#0g9hkk zpZy^QHe75(0XRcj1i4)z{}Z&_Z~PX%sO{LO(D@~7k>l9ug{}=BaiHjwZi#*1GHM@J zeVHtR9c~#`Z0;W+g_-if_iy04HFJ?hd&nE+`b0P*{eOR-mn(d~_4j`z-cE@r8BCSB zmDL<(m9A)Lw<TpZX6H>o$XViz1TXNLO=u;f$_Nk!35N-{sv8e%JW<w9Tasv<|M-Ze zctCwW*$7*4a=LM`yXW}60QPdATnLUiKRHJ>D*lWVvT-Rdi!mVvX0{VXV)UBT>M*=% zVL3x3ZA~R@brK^PY8MPTVF-Di9D$j*^uWzoVoc)>sjSwY*qFiqaH4&)6jKUQTu8)n z@yD3rMvL18SbN`~m<B^5p^Io$oXRI}U0bc+$&>Y2^Zsog-xtt3xb6Id7T5iHt1wgc z2P<ElpAapYclkgghUPW$Z!Rwc{byrivP!HZX+}Gtv7X1!1pCG_dRzEVCzo8wIhWBz zb;u#6ywIzhZszv>*NO!~)=3@^JP_-$Erk&PIjH*<O}4<+-Sx3djn$nvGwCZ!w{!Jt zCXz=$FbDB0DE}0s#zpRl2AnzsHUrcjNH<#azk-8tsKU%2P+M2Wcl$UFXZa^XCPXqB z_$<CEP_bqGKZ`#x_&9Xtt;DEp$SLCDyFE;wReG3SoF7O)NCFL#<1o+>h|?wc7#^H? zai2c@lMe8EyU<@ZfCzmB5EG`2b`};n(=U5?2sI^e>7oCmiiRvYP~PcgKjdw#Ko5^Z zF_5u%LT7x=vEdUZkba4S@cX5^OESL#CvJAS4j8ogk%bTyf(%pP#wPb21^+HQfEO5v zLui4!OudK7*90Sfq&2|E5(m6&ddKv8Vz0Fgx)m_nA_c*2hP2kkZ?^%i`%@b`W(po} z0xV=H7-E7J?fbP{J9NCmxK&wyt}|jk`$2usJN5;9DIEhvC?n?LZwJv^^*=jbb64Ri zYS(v-y0|X$3GvGjkI@el=j2^ELdXwx&f<Nc&JrizeaH7ghUmF%&)>#NY=75-lP_l_ z{iFyWSt|A)`R@l?rQo>FXiCPgdFMZ++rpnuw8Ta8BL8D_qFx^rVxOihN#l}{_UX@B zX+*58fmYTx@MmW&bEobvS}cXt`(1)6ZPN~HIk~X<I#tA4$AXkBjIuzr2ytsomCf?l zOXqvNH`Gnb6aQnJz@z;3V{9Ixyg_#UH68h~zIta%x2>#~7lPd(#>OOFbH@H&Yg({~ ztat|}ob%P;5%1)rTOv819R`LrjZ3yoWip4hbOEZ?Wez39f=xky^i2{DdHpa=n>jCq zKwakMR<q<Te9fStmE*+xFRHfLQNkYlw&gZga{@WUFn8!}SAzlLA;nEZ;N{I==FS{4 z0j+J%{ZJ{+X`=98sp{Gd>~!S;@Q-i@L~67bq2Nf*D?)rPfVHgY1{vUqjBd_{toweP zOn!PTz4dFl=3|)Nr+08%?z>!hr3512GLA209x+tM)mZlrdi$7Y4w^!M7|%-JPF4(t zyL>Q@wS631mZ*C=L@~o<SC?@e_h$#<9srw&x_@Lrn5hTN0qHKJt@Olvxjq8i#9rnu z4i{kd3T5moK-+uG%umK#C=ewa+rYtlKO2sUt<L~EIZIk%I6(;_z1P7&Wo>?ZayJkt zT@a1nuS@Vynb<Fa^n>%$7mANhcQ64|7!$i`FHrG0qXF`;h5*JJ_kj(YRfZ&A(SK=0 z`sHlj0dwC}T6_?flj+VJ`?DSwGMIQc6Vu@G%$#%0=AnCaj=Z0SP|o>>UlUNA8sHXw z<|E2k8`JRx#tEIe3zg|a?*6#a#!O%o)%tOW@wMl=MhJ22u%8a@dg*&`O`h4!V>!_C z2>dcU1)Y|uVe0U$nq)0=w(oP@Au{NFLImIzH0iFC8BBd}UG)#ZU-G|w#BC!Im3nL+ zJC9&CTTo~#%5dnu9xOn%yJFhbt7;O(Z2!JIn}b{P9CXjgn&P;bJi^{;czf`UUo|CW zF575Cg}aFOPYo?p|2uS){qKK%y8qX0_&=q!Mgx0l>c%9kTUuHh8|x(#^|pj`eO~M^ zfHl>8OGH;acz`YfPXdcn=pK6>=DKl6TiMujU(&1g=UP1#Zz0vC^<V<sr9V9FS?fJq zooVUj_@rxUnlPs`fWybk_}JL=d1rojrXOa=M-&0-CKdtUhCq&MjxiK#<Ppv)Cj@)P z^asuEuq>^#8Vku#t)S~-m$jXWmUM=O!{}Y%v~;<sZ)Ar#kbsRgp3A%&mLfRbZtcql zb~S%s4Y7W++t7>K)o-tBAjjb^f?WjvCFiJBl|s<D_sxu8;|MYql#?WtNCAT33c<y= zLY~z*z6BomM^B8;p=x!8h=J`wkKu`7o6D6zLG5(T>OuXS$7$=y!slAknN=eN3@7xU zcfi^SBs9}QeQss<@^wx~@hYUag(qxB{vI}bo6E#rHfH~#ZsbEmMJwfp;O&#l010-y z?rb{`)$w)Vjg!$WB_8K&i-GIuK%kh;bDTN#L^^{~U09;((*ei*kbkhGqqFAL5#;YD zQVeBylA=J@dtY7L91f^r9aA6o$op*6tIiXhwF8R#oMz=fnLyvQr740bXjalKt{Zur zEzkU{OSwY0<bek@M}OSUy`&o;i1sPB?c<4`88!8`f3nB^WkQq+qYF9dy{^&W*<a%P zMz7H+l@eVK1^>1y?eiI$wf5VbT}nVsR=bzl@H0pzE|Ly-JC0wC(%|J2F;nlceCsDS zbFZ-_6v9+^*aF}>aE^1aSyUe|&Fc9}=~f)O@fBja_;;T3kCxzWOwW}UIP{9YHEndZ zSHc}H0(YRR3ckVey}m=5p8McXV?C`*U)}cSt0pnUt9EhP&qT*QLq^oscRC$9v*NRx zcivNU6@EH9SAcitW1F+-9HO51om0*yjE{`SYK%AOGa-25l>hUgMmp9orN(dlhQwYl zerNFE;KEkExy9d8UH{kcL(@DxtJaA}@t9Lhwa5;^9~t4I8iJFki7b0(Ry)knC2rO$ zZs$ny`uB3YScp2`q;IQZg835`6PB5ZuQLoED?8FLf?#Ol2LjNjO|1gGVcapRDVwgM zDp^FwtE2u8D{#0BiY=KO#|fekl>yDDQ*<QLBiy?l%G>_^oxL6Jw2y<`*Ut8JaJsas z*>tK}SO89c@W-!Oi68c&wdkFsKbI|{B}-{emmJg|xm+u&$(xnly2>FNNd79#sQOcT z&k`$`2+6Y2Sx*N#={@E34NxKfDMV8I8;@HT#|Z3=F!CX$5L}^OV+B4XG5bDI=Yt2R zD#V8$)X%$gyWF7Ov=W{?XW^GVK&7?`rZ>CV>W^#C27OHcm>`WR+v6;5f0=3$DQ{Ip zQp5UM?J2|v^E<cM?FW>5+)mabO=0&~v0lWQgW5_#nLn%C!8Qz2_ZgQ9nqh4TnkLz; z9nB0K6W8+c+B~^yE}m?}b085-+%h27V-GI+!o&r(*yJJZ3UkRPlqs@STz@zkhiiOc zJC27+dNo=vgoJ(EJj(Vmd6wXQGy#Rai4s1;OpsL^Bn#$S#U&^c_wo#$O!9L1KZ#Z; zn3X7nDxZ-1Sbp6G0Vn)nQ^9XN52@d4ybGv)$0U}?kPhc$yrQ<d7jEh#Oph}KccXnJ zu=>*>cfU1Kg0#LRD{=aC<;s>@Esk!%e1PKKq1b8T7-{{*1Djny`3H(5=e*rJ@KNk< zG^*Cl&M6Y0aH&O&^9t^b-LG$e({cSKSn{}#vrCK|sF1Py<OGwM3wkAM_yY@&GM%nD zG7}xF^$T#+Z19nE;?NuTr16`2tiRth6C3G5=xfPW#qyH~sSn)zlhJ%Stz`$mL}Wgk zt{r~6Ei^!1GAU{z6yOOLkuUr*9{ubjwAz(U=$S2amc1)?;Q;T^Zo31#dxzGvI$--q zZ_xVY`I=5ixsTx&d<r&W{kJ49^|$<X^)UaRm*pv@Gjez}aTw70W?5~S8!lRYd1)fy zh(~57m4`6Zlut&MpOfu|p=4f0sUB8RUo<S_k~P<83qg*(+FBph2@E&*xuA@g?3r9Z zLd~x)JW}HlSY0dUKTuv&x)fWormXZUuA3~Yb|#z?ZaJ8LpA*3j<8ZzJ$(dEpwA5QF zvQN<Nd9r_gByif=d6`Sh`Q6ZPue{-9;Ab2CkgE}nEsJA?$1;e4j{7AtYJwxaTV@$A zoIHWJ7sq`oj~Rz}8CA7uH9A&mF&=C)$b_w<n)tVjqS;$LEUd;O8q$FcsiyPdWA-A9 zZpv;hO$|hvDEk(W<>eRRN&QsP?%y>l>H8JlT2`%uTXY@M<k(`gMK^Cr`9-%oi-Lhd zRh%ScPWM44nowN(yG6a^n>+>gr8psX^3DghHv9Fh0a(Xl#@LGoBWH&K^e)4#$3&Hz zqV<D41uwJvqpk8V02^Lr6?BHUd92sN2sfyDSnBt*F$OdR1<oz_EYCoPJmn^D03Rov z?|Wd^oT#A&2B3zC?e|sLD4(=~_t11pK@!9eVKIYzva&7dKGU#3NPor~y<~y*g0#br zMe=f{w3ImhK8e9ew|ur%&zlal);A~ne<nysxP}GLoMyKS#GG^8I-0QHXbnH<$P6K< zhkvNV`Y6Laj@wAI^R`nqLxlIBHz4V`6M*$wNE`n-3{D<EX-LOh<QJ$lGd9dQjbypI z#gj7liJRpUXA8m8*mR-=C-=&-{9qA9-Y?I+x(xO=C})6v?&t*bhcl6@wy(V`2|)m| zBy{I_i<>6@r@0ibFKuw7Y9#9%Jg>nm0C(Dd@JRKQ07_zLw;;*STk`6l<C|?>U?fGy z&KRzr<@m`Kt9{k<DN@~eoKs~5AdTZXv^u@lJXIgQDS)0v2#H!Pfif3);m;(5{4Eb8 zl&4Rab>#9yjNl)*)mo487-1`(92*_rbub*=HV@a+MhEF}E)-Q*Pt6320eCuc{#%ku z5PuNx;1yo2{L2I@evv2p!aqgmdZRKY>7Wl93-IyY$>}<-ec`=GjPVC(UEq~0r6(nm zw=Ek8xGjginEtP6AWr_`xBuIy`QOKbnotrfQA!77gcW+LB+x0vk-&s)IF{3!{^XTX zT+Zd6k<ssJt1E~q^@^i&P@1Ab&Pqvq=GFH?39i9lDVKsr5o!;aHp(|FtIp$nQ^Wr0 zE~x6zC^yD)o*gNtUeGbGN@_zDNwyDz<n4%g?BJdDa{TeJsr<JyA4pii=4D}dY-#$Z zc|%*CAU*wXo$;D0#dKqQvN<KghM7KQv(>q&?&wIzkvq~}o=4`KK*X7W)M!X#$1(Ur z(_2dEJGgkbOfz}t7j12g*FHiYSvFXICr05*i&;deZ40Al{FkEfBN%=CW-TrkXEAyx zR&#Oic{o0IBnTjoy=p!?@iUM~&`Fekv5p}*&+Sh`?u_7>#H+b7*yDwtiHl3dj2(GK zTXdr~a><FWr5kg*0jjG!^#!xTGer4nzJhE#ar==!IY_+UVFPeBhft4)ve;N2(5(Gv zIH)Pv6Sc6p*#jE@*(TWENt1~MO&@GnBV>CU_NFw?h`-^B)I|iM??Cchk3JZEL1Mav zWy)LHA5TPjXC;4}*%^A+1jr4Q+g!*}GpW@#PYDh|l7pawxCD-6B_6=brfVU|bc*db zBlBLqX2;{?rb3F|&-yZ5Uziwrb|Rd<NOy7={~DP4Kw+%|G}?qae7L^M{zCHW*+*>m zcnRkNd3N;pYr^`_87$YUzdYwD&I~^eMnq^c6%vhY=D88(zG3?8hJ<k_Y)v|h72Lr_ z;2a?=tAFu$>%~hiz(k}Q(_cj((gZ{FRxsB#19s)yo(xJ1+#ggWc7gmrk9}LnXGRJL zCbgQcC4e#;#KqR^e%zLM7_Qp~kPt&1-H+}f^PoTsvA%^gz4_VpJ$a!lkz#A74&G95 zAHx!r`vT(=TIU@5obhXkQwhIxcLX9<Ns(8`h~nCZ5W1SykhM)k9$0a*28C`Rr#+y( z&Q<FR_MGm>5#W!W5a~DG%J2J!y6-%|h(Md!13de?`bWR(U87d#6i5U%9ee#|67{ev zu@K$sI%hXwPon>MJwzHDp&#g*QV@02!AhR6zMHC$Va5OZ?wLfx_aEPg!-5|l%uQ+< z)DBE4;@61|4J6xo3LCSBa@e$Q>a5NXFsf;)7)LNX(o^x~rCX1&Nz|6i@NWje6eLks zd~d22%R~v4ZG$ajRt895aLF<%;$h~_O*52~^DHv_gWpX<?62hdcTF9(a3@Z7_hk-e z4px5)(?<!#gycmXzmm4_aM3m4o+Jb|9FO63SjE3+qPP<~fB)EFqL8VnNpF}sIY4fy zDM_FV=D?iE%ZsO#{McC?RZ>qqp!sglnU#*L6OoCCy6(&TNgKw(VnqkS7wD5YNwYLn za(_?)WwL7>Xh+7`*Lx1k(*>rj9vts}o!SXDl0@%rvB~l9mh~ytUz=TH#BI79-X!3k zw}0~4zK;s593<D(=Jm?O#=DLVQAuwI2+px3Xze3I3-q57=K6pp5cRhXWEaeZZ8b4@ zJ;AuU3e~J%O&9rd+CXU~6c}>YTpsz=)$SA75*#?r;8Tr?jES6PLvK45`Y=8A1D!4J zS$<GA-;aDmuUVixm)|Rh++__a$GGl<xwa>Qo&ynTBcO!N3E9-XMrms%TUY>$4S#9+ zr7Okwz0;v51OXoFVFR$7%7<}47}3$gWvjH#!>gA=zYi&KZ3N^A>4be7<mkT5-*Zua zbsSB^OuyV<enUHGj8BuGM_tFefN;Uspx#w|VBdH79u{G&txZ|4gNT-r8Lsk>0i|gj zJx-&LU1ry=*ooKt4_mmL%5Q!vcBSR{&Ga0B{5I#;V_!ddHt|#eMF!2keH+k1u}CMj z*7E*<)~ctS1xGk}wcEH1SZ{hY9D5kuwo{ya<N?A#l@8pB(a?pP9ON?@JgR@tBg};U z@&e3`n>~#L9!UePp&Lg0UaF$X2&0SKK)o`iXqi2&-yb|L=)(!GbQ$+bRo*UfER{fd zT#WunX0|gX;~M{Fz)4I8Fu;Bnc77Q&cT9Zj|4EEQWD~*a7^HCc^6&anCvjJ!Xi+`a znBz`Yy*&)gOqlcyg>CWsU4Nk0hA;g`4jtA>%XxKKL{o_Udy0|r5zYh9N5;3_XhsRp zcKBb*nKatJRt^4#Q5r3&24t!QR!4Chj?~LUf9tYu3Dqej%bl6!o|1Y)(eOt`OHE!{ zSW8&_J4sMq{^xtd1cw|rJ1-|1n?#}~VJjPd#mgtAwtTuO?>0#OF6+Nlgj*CE%4aDo zDz7II?Al+5jPo6$6Oho222$o=@J2183eYI<MsNJ~lg+~|N8h{(4SMEGO3RIn-8nl; z_EIpHU<&VKGBwy$+kH*zmG;mIb9aWjGELi{uWU{vhv#Tf{z=i-sA3oac4W%ujIlX6 z)p9`7tfFRBUrIwQ&D2k9EwTbi=Nbi3O6HC7Qr1X^ok|UL-%<-U<QnA?9#%(;+c4MU z9EiI>a*bVqk+kv8M6lu}549ReXVbrBYb?)<&}E~nzd9uU+x4LY9>uB-iyi?Et_@Z) zhuwMZ?Efe<K;i?jZQ(Y4{Sj^G+K+Q;g+BJW(mD)ipQG&2PnZ1AJFja!`P^)hb?{eE zTPs>U8BO1R_SiBq<8@_#awDPvuLP~kNSE@3KRd+rrU9*gSAFk34)8W`B8~A#H0Z#8 z{fOR|!}IhF$?+>O!q!BDx!N7IP7=LNrucd<9b^MB2Wf*Rp#U4TZ#~a&j@natqYZap zfRaEn9K1!K=#SiAMCH=^4|cQDguI?O%kOO=5cy>Eb>_^^=RLg3V2Y#`$60yra;aty za)5Erw+rG2|Jw|n*ue3%#yGqfO4{T&yWM!;lQMX{hpuDQ1=!3!{qDxwsnFf-1H<3j zDX{||S|khS+_;zw1*b;m;JRMibdWX>e)xe8<>z`~&YQjv8}8HDH+NU1ajb~wIE4;$ z2^>Koq8^vMn6N3obl-?HqkhIfl>>uI-9xi;D3c~bSERXDdXJm8Lcg7~>EeT->i{j( zXBT5KxkzdO#}FjwolaeEpR|UujjI$wqI{Q7ucUc0;?DB^s26~bECt)`Cu_iI77{So zaF-fq?Lc@>uwGWEZxtAji<`r0T((O}4d~VOQs%4shx1`a?SgF|b0&2E^eT9h?&12c z75ua9t_u*djDu<Q`2cxSsSWerR@MLOs#hzxM}=c#|1SthKx$)Rl?DtJ`%l^$x&^c9 zoEpbYS=k;=0pJn{Y~Z3o(4uNm$)u8)yD~Yt6$bZYbX{s%7mITIs5#@hFwK7uE_t!g z(vh7qZh5y-JsZ{=sfni-YpToa+yrJ;R$8>Q3{39r3EeE%7sO7b@U95pL}j<3|4>RC z4U!NE+-1j>QgO>^yX>e)m-UsZ>bi~bdBRqj?k{_F`Mk2Oomm?Y5cHl9cX3bA%?Aku z^tePrkR_n(!{5o*1gST!*tO+~k%t~L676G<DTWGl2EoYee{q!H>~jQBlv2<VC6P$z z_lP9LyXobkI`la$Mnqj*zR>tKX)C+m3OoWc7lAg<!(5o>dY9!dU#({Dk11V_r>?1C z`4MJgdRnpu;SC7SnmN5czq~Wjv8lD8u3-*w{ephm8@>~{&QbSq<M1ioAI4J#^<ejI z{GHLkP~zpw<|2*fVn9z1%^+TQbGF-T6BW%nQFL5^3%6RIZz3oyR7RrPP*-JtfH{BR zwDckSx8$+2+_2>n<j8^^f0S`^5MoZd6&b8Fq_@)ixT1VV&j*$P<@IE5-Mq~(IUEtd z%`k`4--MQL@uNo6+-{MX)lr!sb{I95t{Jyi@cOr&ByT(B!G+WVqG`LtLkI(7=iJMM zVN+k((;=vaC_G7Zq8uk{mjB1rG`{KbIrARt{L{WC-~HmJl;-MsvfLz-QNUpVh*8Lk zuR6iM@@0yg*~J3l9<5BI1>IZ7S2)Kr``QKt^{ubsev`5o>YZK8@jTQVchG*MK5ru2 z1IV`qVGrT??3pi}OIc_yGsY>f*={zulb+3nf0ixh{(T`t=Ch6;ptadAMn@tJDK7v{ zaH!G@E2x24cu<X<G`o2>9?NU5iH<*q9I^Z;oQ?*m*YJQo9n+?fq3-1?Hu?O^g3Fo* ztj>Rd`Rk5@n8)^rX5l*ZA5bQLjm#m&<2?m?f$*+NRSByP`FC8<=0pT&M=sF$XCWgy z#0L_3(#&B`5y2ZT-79S&KvzU+`Pr_<I!f&nSDsjej^(m-oqq+P|1Hrf1ZM(<($o4a zd%p2v-$R?{DuN<KVgI)mc3;p#7Fr~+v#}tj^{XZJ5T5)16ivCuG)-H2l1u3)1$yFy z&3x(|0VD^c8DdkkyAN*IwX!qwY$m6XL6wAmYq)fyd~Yem)z9i2>jcTlYAqG^#@sOl zaS?Tq?`7vSY7{aiMp9bY+sHsDbAx%85Cvttq{QlXIV9MM24f_ce#1npl)p4Iq)}B> zoMk#{W*lbm%IKIQt<g<A6Eyg2$|8ZnCb%q}Tm6pVP8^(`4yB60y*qq*Ko6+V8%3RN zc2@E1CBrIN?*51%|6xWb-kpfZa7h4iq)j{Ji0u8)`*8DC>wua4=81OfZpuXCv(&~X zw3lo?7K@2(r^1)9FYajF1D6k^ghNNg<2GlsV(iBA;{xi*Z>WKch9Kt~co(M7%R8pc zL%rTJe2)rdgI(Nun-fJFmxE-&%e%m+iFqnwZrwx(QxgAz$NQ|~>$&{?m<vF_#z)Z< zVZ4}dAKA}i4bCIy4@^}g&lf*QumCq++fUH%?e_}uSBnxlhCe^LV5V97C$J?Rod^X^ zRdU&e&j->_iJQy&dYs=Q%BA-@U9KyF*=#)xwcujV(Q>f$O<twMJ5Bd(iR>qS;(>4c zHH_p#<0s5QyP|@m+U(Wdy=i|8nMQ&M9Cn4F4Z|oU7Ha2T2&x6ilJTE)x5&*q*yGwm zgc0QH(hWjrrKUyFS7`rR+<KWZ%6>cZv~KbCIvi5KgQ5W{%nwr=IEMVd9PgFy-3%c( zG-;(Ff!m{tp4c%b^r6NhmMT1m-Oj^4>@2f2>tlA%`<0u7=(1=OZ?jVmg0qhzI6~U- zG>M%)xA$z4$@Z}sY(|PjY-EKnEgL@M-?%t<Gflg?_@S?mW!Y+8_b{49nqWV){Q)q& z1je*I#NRk0vR6eeMCffBFlzm6StnM9>JK|<G|nq9?PH7BGAbbk{Jv%}xnkah<Rau= zd;dCdakQ40e1q)>?<v_r9=h*UM6wPTsJ&S~a=$?9GikdxL3Soah>F|ETuib`@IdM? zyXB<*2MlTak6E@Mdy09zRPpBUKa&~%`@zo&ipskfxlLC?NBXkYT2>6k`8G>c;WIhe zl9XgqU%4ix)sfYSmoMRMzQm59%EMaiEQ5ENq^uGz<AeLQ8V*IceoU|~8t*rg)wo$w zUyV+rcJorrq^)M81<OV+ZlE~zWgH7h(IgsNis7UkY>R7kzr(dP1kWt$FE7#QGOiKZ z9t<WatR)^_Qo2z}dp$3ra^jdxN6Yyww|*u&RFP~-D75y}+CuYmD9GflXu86|UGYrH zmzkX+Uu-ztmgxH6MsXq>m|Fj>ZMd<weH{3Kvh|3_(teIR|BIiuc{PS`dniG(wNBGk zWNdhR(`V!;%Um+T091#Y6t!84$#HI$f97`?<pjXGJ#T9|<AJbf-Kk-D06+)Z`i^~d z*}dsLv3zxNK;?CE?FJD>WX`7uq4yYO^$S1)PbHS5mU+YX<3;cV*&F2dKF{y-x22o; zY8VO-*r-jGF4OrVMX362^n${VChQn0UV%3dm*0gZR!9B5nM4LGSJLwfnwcr^=q?@j zD#Fz94(Php1t450dqy;JM7K_#fr=i*{hYA%0t{Tsh|*F)@L2xoA6v}U{yg<J*2gN9 zu=9M>GQF>GKu{qSFBz;@EzUn^(1iE#sH{!yay?=mV%6ep91k~ct=`-BoXn_TvI80L zQE#Tpmk%jKs8Dp+(@giLC$MAVIZN>^9kS}6FyYvu-3rnL+nd(d&S;;39~JexOWvx< zh)zc+>aZI6gPoN5=8M}&amL1^&4CQLJx8Z0Hi{iSFHj#sVP32!#0U!BWsp<4UTmy} zI%I%Fg@*W0vtNyX^tsDMEkYQ{ouM9`MkDikH)wzh=ukr84QwazUOZdov`~Q0SV|h- zuC6C+!gtrq9?7VU<S*x1fiye+p^*>y%R0HI)sWtwoA<AE2jWvqFTJ4UlKi#{L+=sL zY$VVASRZa42rQ`nZnrOu>j7`(wRhOoxtIrTgaQsD_kgajWBVcy=DCqBO>+mK4`87E zWe=&a)y3}(mb%;4q|XuHKN4Tl|4K25Ul9ENgqW7-Nr^}=Du2h|yCo%gnV4=E=r;9q z8?*h<8&*;xS4q0frJ^&PkM36LgN4?D^Y~S{LF>4MfY^wsA#!lZ{70J370h|N!Q$$! z(wbfVhtz34pt7dgNS>0EbetXx^~>N0et;YyG%hiHE$K&7LXewga;)z{FBK<L*FY{^ z@jli0J)O+uh4Z@Vnv(znv^W<1Iv7P*RdH!;xk$PBcMn{3IonulMVitL6M}ZVoZ-T? z`kh5j$UTNa%xHY3|1>X%6l#^ukPO_toC<05{V~F=xuy!TB-4chzkY}|YIQShC+^y9 zXoF(e&0}&jUjs>yUhDAL<sj!1^9%FJr9<T)8vAkUxBqaIG%RGEv(csoPU~cuw8s#9 zFMty3y?ihg#xQ-C_YiKHVspm8Xj$X))%_Ro<8){_<UA$vDCI!lRKCyWcy<K7pV9Rp zmrF(8PCmqeijf}oDMY{E1<sUVX7&iN>TI4;|2Cn{+c<W2?;x~;W(Sp{GP4G<17Heb z+nD<(y=!xFj1RfEsR#h~JlEXByWcwXcRPD&i-^+Sxojm;%(%1*23A_-KZ}~>+_@+x zdB&3ovLW%_MJu6|i<`Afnor$+T`786WWLM?&>*G9Xb7F0ceogdyET}G+v$+@Awu0s z?%*ce%S+E++--a%yBYZr75F9eY=wmo(b0w7IJ4P;@{C|Yg1+<-AIOGtgEu}FJmwUE zlC<6QVYjZHt_wOA$KVf6@iw?UZqw^*=;Ru;h<e#zDR71XIO%I)JW&AF7GpW6SlRF@ z7ERY13xwyK-Lt8{D1!|-A2#zWiwx-(otgIKj*N2k3_rz_E!S@NkO+aS<we1Bs8WN7 zVVkrDhGd7WsjUwxmp<gxwKOh=s~B-``yL*puWLYnfl!7W`7UKxi1)t_d?DcmQ=CkY z5TrLExA1)0ZqPeJBWPJ4f6bk3t%o05t``XhuGihaV*@+{z3##iR)hC0n-hZgO0rq- zJOftsU#I^+kNkfLw~@!X&7b6pg_y3X*`iU2UU=e>lB&gTq9#SO&C)X~Cki9J%eOKR zuxw<k%|+Dg*zA($=jX-3I!|OHesrYGNvhoA{F8Q=m>*Hn-1s?eY3Wuah4ZmPNR_`J zet<az0Z9eUEXW*wkSC>aY)sO3o}U?A)XPn)TpIpsP^r`XKLEo(JijFc1qGT}Vw;ul zV-2x*MEbLotKQX5=>&IFlsR}~N=viTQQ3e%gv5gZof4D<dmJ}-r0O{9JR2xN(Xa3v zMMZh~Q$89fmSM?MO?x6ElDMTqd#p1wu!DU9fWs2zG*jj%iV4;WK+2(mXf*-_Al$)o z6xn^O43MZCjnBL_G<4C?`e2~{+3>=LW4HYFxh8LjKc-}K?exd%XWj(tbiOk7jMW_v zeTOf%ulY{hVKpi>e_~wLxZ%5}PdPCvp{Q#n?E3<}*StUS30j<ddoTvJeIpZonbp_F z#=_KC=zb_r=RK@OLfZCXWGqaHf~{Ym-{DVF&A)C9;r2-*-BG44Fm#^dsVLA4hwCq) zPZNufhp=w<*F|a22e<>c<?E8*-CHo37I1oD(Ttv+14li-69p#4VDJ-8eaPNo_4!jd zd@ci@Jc!AH?TgMldKtDm#C<@*4dr4p21t()1IHOS$u50#Tmp_u^0dgSML<jAr~dfZ zvq1p&cR9ab>E&?BJ0}&wN+3H6ZVz>SGQ<U`2-zqf>$W^NrhX)8WgM6Q_bgnS;vQlP zFYJnwiy@T@sXRz$w?}OpzOqw`^gb83UV)R7zQ(73M-e!3!GQ;FD<C-q9u7Nrk(vBd zRnxGGMT?&Ld!k@MG5I~(!Ej)vTMkWwwx!VeC-lsRiAkWm;mzt{p1XQ}nLPDlzj^O_ zPIa2H)k|%p?(_*pTbTLRI9jKg-%7s-MOKhw4Y9W1{RlJ<xt?^&m=IslEtjlRJ~;u_ z_`|&*n4o%l74ulHOW=?;4_Ej?w<PGCUN$DCTxOy5j*rkKv$A~}f9D72GtvJ36WFN} zIPdJ|87E%aU&^?5C2hu4PyHy^vgeuG{dgIMgSWEq#-{gv4Pk8{+@dHR{nc~#kD?KA zi}h7Kn|z^5D3Sg7vm}InIaN!ddRny?t)Os=X6aT0VMHt|fkjrLIU|gP?U&G{`dmkp zXr2f~qth)lC|W7eSkwZFwOwZk^HM!iXpJUOUBB>11mW$4O+G$F=rk2tq}w`)#zhbj z*%P7Y9|RQIs3*V8_TP&}q0uQGH3-pDJfddnBvLw6v9Pq!JsBApkzJ}$$bz!MmR?z@ zxrTZxIl0b~QpiSq#U<LxE6`cbm@Eb%9?`a+98@K9w250R9(^=2>?y<}tc?FZ_TB=n zj$LaT9~`!#b*Q_$ySux)x2Hy-=oYNB)TmH*rveoB;!;Wr)CH=zyR84pWV6fZIrm<m z=Y7BL``<pl#gLgjNmeq+$}_RSc<TE+k+jKEO&`a<dX6kj`FnbV-U&TYXNSx%w`$NJ z6auPY^@=b`k0=vj`;*WQX;biu3VV^u)gaqc66W=TAyMEp_A((!R3A2r=*1sE@2q+P zH5FCz1gjPJSy;&a<3B9am?sR`p`a1Fs*WzEYtAr-#Ydv9Cf*u)IdMb$Es5_<@uL@; z1CzD}U$XYGKj3-ME<k!TXj%MM{lk|pxxSdXLbUqD=Y@%x4xTV-!9CLe;4X1I{Iu$j zcjhIRGTjN%NuTmZzseo4)&GDCOizFzZ-80hzB3H0yrBDHw`m6=7scndDgga#m>UP3 zw+HuG=X2vW?C2bDvRnMEami1vgE$)IeuSCd!SDqH-2=xF2`BsKENUL=5eJUn!L$&h zMPTCdZQY3w-*WJ*s_=%&up&tL3PY!?Y_xv-xYq~tawTL3NU}4eIoUhA!iek)2`0#m z=-$~{h0?+Aj)X(yQKK7o)_J*@J}deNuL~hP6>bdhCX=hP$qej*3YH?hhJ+0t9ot;Z zIsw7g;MxOtRYvwX`V8>3s_GNKhjMW8cpg#-R{)Gc%Z(>QSdR;eNd@;x@F<0VVu&b! ztT)A1^w$KcZoI%OU9YzJa5NcJ>{ANkOJM7BV8+{b%Yh~(&^;Fhrogz@up=B?&%(|r z&-c3%_twW?91PYTr7rhM%-Zii-|X~-2KPWjc6`b^4o`1^hZ}6z=ex;2tzCM#5`a<_ z=$1g2@31BuhBP|6nYq4|xjsPu{NR_MQ&idIQ{fS`+6xaYj;!dETG2JRY=;k=b%rbV zs{SyK++Z2CV3Yf~Q{RnkW2c>qn0hgI-mWu@LJM{o03ALi!^E^?{d@5Fe73~?xdhi5 zSYg>3Od95zM5OjWFVq)xP>WY@eg2An#Hv%!l%jD)MuO?3kVR7$p!b@IMF$PPe!u`x ztNLj|LDPi}s+BC<`htc)!$i<1>IC#flS4z0hgnz1eW3%h8jpXQON1W%N-2@|h@h@` ztf_kKL5mayMU}2!f@|WZei~UcwT8?ai(eeZ!nDW}g-t%D6d{YI*1*i6Kz;BOkH0eH zM@s{BqeJ$g3=CXPOOLD3MOpcgja?gcwI)1n10I($B5c%A1ez$wmB{TV+5#c|gnWP% z9eoY1ucbw2wx5FxR4KDkFHo&$sbC+%zk7nH504dAG1P=k)MkZjRQ+Qh64Q)=I#nmW zhS1ZR|M4GI3-(0rh4g6=7KVnOupcBrG$PCmxr5aKsTs{KK2M7r=|wX5M!f6b?MiCu zvfZ#zXy|yPjv7wP3UpA?MpzoV83CpTIXee`R^g60e`D^6z?bJ>lY)3LPqcs|+MsB+ zR>{F`T;$E8AiiGEd(#!8b5VxJ9+{rGFFAYVkkhF%N6y}oxLvmhK4}{{Xw2T}+ih>U z#xL!>X@KrbyP%hr;cvS4+jP_`XHYWq`2-phL-hv+nfO8DZTChV3tp6zr=MHFtpI~8 zSdauO7sQ?Em3U7l-n+r8fFWs_4v=&nwl0WWv@v4Ax_})^{SVHJzBb@P=}qu^4#zUd zZi?apq(`Y6og$HZxK@?9LAghHS!gjtmX|bNJ7R8}b<<3;JWZj(SQ$)}t1Oucq(sP; z$Y$B>S7}9pBI^O~j|M_%SqYro<$PK6H1iXgH2pOVPLI3;Ps#l2q5`NuZj=F#0IM`k zN_x0Q-U3N5><G&HRtBYckdLINgsk+>t^hmpo8L=dTU6;Tf7mlE2%;e>6TC~{NjfCI z0pBBcMLpM;tBM_%Qy+%BI5)(v|7QOgUtmBP49$UUiNH*DXqy3Db7B1xXutEZhKbjP zNH~56hOCU7{0`b=Lc1&&lMEK&ut%CaYwW$4!*EpRCfN{kKct=k--mD~7?$nxS?`n9 zBNvn_K@C8wq^es+#iqE*J2t6_o4>`bc(;Dm!=Z1g8fH|De+kS)3ufuj=}FM<P3eNT z(pxu+o}MlVzF2I(H5|Ue?s=YPE@iK`3p*7H+fF{-x#bj>(Nkhn6qV`3qkn1b<z@ka zZh2!*>Q!BUUMOhgMaXwOtt;dz$sMvd{t5hK34e0b9_R(rNDVt4(Ot94p!T3SCJ$47 ztT!+;8YT^##!`F8pCCG9A=Vc)vlj!bce$cvl4^yZVb&F>!(TZMh9--q1_(X+6(A8o zb#-)fYKD%<s4FnpHHk?5iUswBN7M?#q~#Surcu-$^tFjT2KnIHuc$<ULD6a>i>B6K zGgU^~P%DI7t6v0~EjqZSBNQ|e@S3VBx!BruRa0%q;}8l^E$FTmEhGonz@zADYLU-t zu%}vDI?cH}f3dhDI|d|c-pPiC%Js`POrSjNs2+9yD<BJEi4X-*MlMK5R8%pqurd%) zP{0(k--4~y@CSanQo~JCfHg`^k0=?^73!eSh-jX$Zt}Ge(u<|d_Pnt|GZUE-={iDU zsVOA%h;k!rIpmT48N_@OR-~Y&prnd#{-i^TJTo#UN)c0`!U**`+;AUo_G$Pz$UFq` zP7rkwK3s!Yf-AFCZ||M>(e50GuU0x=FX-NH%f9eeqR5C@lP1JpdYE`IVbdhLJ1*Z% zP6U~sbay=H9$@6}ZscQg+<V*kM@DCS*53@9`Z9Z70vvt-y#_xJ1wuEo>vJ63c7%Nz z{Vl(3c7CUVk~z;x_V0RgyL*_YnpaGNSmzdD7rR8?9h!W4M567i5YweThfSZ`%nQ2T zFaF%XSgRvnj--N730RbZbwtU!6XAa4;8_7a<q%N<&%VQpbXaJ<cTL#ww%PVbkCZD- z6w8g3E5wRbHcXW*L*{6U<@Bikhoe4Flv@P{4KLp~^X-6LQc4=+eFn$L*U0Dlkr?HY zZ?SFadU<QlN0S?z-7?hg$_>~YUA`+R-_1Ae$-NIxT;5b<LMoD^LO5>jW+@HX77iVD z2X3Dd2(b|V6+-htzxSGRXCs!3S@QAWmxM#GM*WuWn9s+C#a_4tn`2;PE{rUI9ZA59 zbLjsaMyG(S4~$qBzUUduc?uFYXul(>V>$?-s&zgLc?+X2ezo?34wLTPxdoeg+!D3D zTzLqxPC>vOc<2q=_B=N9Ea?2TRI9YIb$ZF5FQqfyl*~9C>3Zsm>zcqPX0IJ2akCSu zdVheqVZe;Cp79JOJ+GYqq*NRY4_yl3J9wSRjXDFT#)UXc47_kUYs-Pib1|^fA<$&) z30+1<4H-3|`PJqB?@+U<qMN=rA!xm-J+Q)3Lr3iuUa8;mRm4xt7@qz|YfyXC&ouol zu*tvxX<ng*=)g9Sjihcsk2RBw?wY5y1Wgw{Y19POz%Z$Lbp?7vP`5nf`ehoXLhg|& zQ;&8TlY?avj|e=)qE(N~`3W=xJnHG`(O7CiHn@gAV{YQHPCzf%jA3dq6EU?^X#~yI z+5<h}5mT<Bq9O~rTIsq1ePLBZdPFG>1&yUnpdNWV9wv~s@v;c&f|^NCRaM0VQmau{ zpeC5Bc%<G@D@<Vho);c5Epoq@;mAt)LS7RgzdgfvA8^oDQPR;+)5Aywq(6oV(Shy! zkO@0_MEgj{Z)CcSRx=JKKq8^NM;NS%nku&Cib~|ev^1{T167inW_*tSG1E{DBGq>h zorPLFGV-Ux5ooDs@Dx<AZ9syd!V(K5y6YlB_SFsrMe^HUo-kg=i)7h9iV~x$tin;( z;0egAbc_r6k34@^VS9-*QEgct8@(dX<O;MnLQRgQkfWu^)e-Vggj|lgs+yuAs|?2T z=NuyY9x1U$%t<A(ktH6{wBUnNP*G+zS5{I`Mtv9!-9hKPCpx^D)5vYHwnyWB=eOJ` zm!2sNcnDhtM9=2mvl^M=CWVcQW7US(j(S%<_H$a(#cOZ7y|{I=sQ)tO83|=GUzW@? z4+wIF`CY92F6W<g&oqq6n)f1e=);I@X9KNH1e>1-*?ZD|-+52VQ!XbDxH%m4v<`W* zEhcGe+%r-5b7PykSGKvCF>3=`UcT4){+XU$c6}b7p8M>?a@W;^%rEaxy0$GLW>U(H zzLD!!1nvne-d+Z~D!?+Tbp44Zc7B;bc@UEc-`@j-z_HOTn--ng?(5$2+aU!&8f3;) znj<$-sIp@!ZJ8=5(j)fUv=+Jr(*7TgctJrHzyZtar_O)hZ~Ylwg2VKic9YJKFVuc# zH$Z9?Xw^1u(ZG8t?_uIt*Rv1cVIc$oxO#kzcg}owDgDi@oItP4jC`=N2srCnye<Ov zJcgX7;5g@f4+F<WT`k+sF**J&ec#6~w(m;UnuOgw0SVVYG&;d<bn?}!Fe@2G<-yJb zV1^x<^9oiZz~Gg^VlNn&41GQV63TX4Lb_#;ucWPx2WG%NW{l~Y7-&B0j)Mp6^@9ho zVBYysg&ll62T!lT!Bw&LcS`zxspyzju`RCD=z8+{LovJTqaWVL*uUNVoJF{mZEWie zx7LQkT0daM9-ABoi{i@dgW#BN*?Nz+n65pCU-+Dd)5BtYm!)|g&fhDFT;}*}!_k;+ z3y(Ho^i>%(cF$H7MFmpu*n;*m<o1dhcC<6H8dXQoCIIaf9<lObI9Q|WVXqKqduuxI zC?9tJb)ZUe&{*V-I)Ru_wh@#YE86<7k<<a`7d>LmQ#J5$P|#TF1T+=c;?TUJD%HDP zMqmi?2T_lvkS2j9ik7Q-WDWwU9%_OK!6O30k!w{a)NBDU1U$u~yv3;rLXS{a1jbrd zpf7v?7!!SpzXDVdGY->?VInK6AN59$G$E)Jrd%E}b<`emFBk|0B@diBY7corFr%^D zV=bzOGCu)BK&@yAqp{Q#G>7GG0Y`(wZouPVZP%P(G%yObJA<f7{>cOn_?WAO%vNT# z!9UDr(yPH`7(a=40K>H8v)^Q8`<eCh8VYN4?9>ui3^1=SnKZlbNF9F*xni<A@SjW+ ziJHnPYFx}LEz;4Wrzg;5k8E!f+wUb4wkM1@<dFY_5b6*%h<u1}8s!?DJ?OyH|A_G~ zLQ&%i{jZ|H2)R7Mv9xsL`6G`VFQA4fh=vUtlB^U88#HL3r9--%$m0|6xeWx2fg01f zY5&V^N)rz`?S=78y$!Fyya!c_?&q{$;ViK(9;18Jq1U_PLp~eMc%wY<WcPGvl~ua! zS;nySXB;0w)3x3MzQU-F<)@rsafb^DPVnRcxZQ$d{xIVH+gW#B>{xgu+9~DMqYuY? z5}bSz)~`QkI#l}p*q3YKutSF)o1OODbK#N6IrjrcJZ_8p0=9=FZF%iBGwk@%h=u(R zI&8Zb;hYrY`rT=ZU+lbuhXegX4(FYBFIXR+E-HW{VOge!L&q*S`tB_hC&Ga-E?4^o z9v$>(*^)DB9{aS)c4R7y7_wkZ!c>TvO6!{3NV(EXFJC<1!y!+|`vR4DC17(i)7m~8 zqTp&DH?nm9E#XFc`rNc^9=@Y}NOCfSrh@T_yaOKK3gA)(&oUrA84~X1McvAB_0GL^ zKkbllu&pG~)CY!JylUV2NbeTM8h1Q(<|$ZzEZOlrYeNBS{|aL)-R*B>UwRD7=Ea>D zm|`*M<FYuI{tfIRfZOxDVF)zZ>ECfj=&~o!Gy}S&0@?C$WyJ6l7?=T;uYl>lZ`>O| z(OPzWPcV#nTeU2{>a{x@YIULbC|n!udv=(+i(|o-SeW&!c<b%ttw-XP9gVT`Eew1Q z>#hCl{jxTmh&Ma<`P_9ldKa3{cHbTXyP_-YLf{X#FH=Ha4!IY({$%o+l~G31BTuY+ z;dLZ8*bBBCem`mRg9a*tTPn3}tkn$5kB)XjGKkLhasCxpVX0-HMUK9#%F1xvA+NL8 zK%n)bQPdS!+Nm<A7<FSaL4*BuV1Tk{*ob7Vx&!SMauIo6{Ys``JB^{y^dhkNsCQF{ zN7O_PSp;=~{0UO6h~=qnVe14;0{WuBQ>x6rG3m7gYE|!Yg(_iMXrk~GGyHF9453H( z8&$ooz;Lk{lZC_<3kunJ9YM$G=mS9fidHqNP(2<)O)pd{R0e~UMNoI3UqsEksuO6g z*3^oUHd*Mk22DlHw4ht4pn$CCk(HGm+wr4{$^Vf9_$YrCb}<*Zhy39M{A16N9`#}v zFOg+4j=HuEHtwXCOGif!W214^9+=@ZCs&~|HPikR@Q0u25o*P%L@#l<8d{n}A51!* zPkMJ)jj)*g5Hb?RI<&~7A_62s2s-(i{-mj;L-w$iLl$36)XXIsKg}-mMdim0gy14Q zLd68+o3&Krz#mA|LIF>}*U{4@eNnV88gC<M;WI5%C%ty;k$i4gVlXpj&(0%Rx30jb zfl-F1VMI_#&#-UfuYTBfG;h4-WryA`zZ{45-A?uS2rV<p*F_f&-t^#r8?;{UIV&M! zXI$2T&WBxx#o7y<Bc^8r&HUuN?48xFq{HSZ_QM~)JOsBd!wC-%`xP%<?|P!Ui)%A4 zC*3<n?XHg+eyZb)V}|G6w_A0h&#{LyZ62Ln5D>NX#aWv`@zJ~cPu{e3yn4X#)&*Oa zuw9`^YeMc1I+}Pa-pT8!U2wGH@rOZ|qbIkX57FS!`JP7?uft;=eoBVB0E1s&)XA49 zv7hT_D$P~Enklnj_scd@sxqOXS0Ebv-rfsxQpf-rY;{SWvL+&ac?J1|NC4a!7$R=# zv#qPo;sJL*q(Ddxco)Iu3u$`;U~zn=Bfuko$YO}ih9}t&SqS%ivhQv1KR3;zPpiXv z-5r?j8*SgfAKzg`4lF1tU7ZCciO^vBt=X234L!fFeh-poU^Vu&c=X#{A+RO_S~j^l ztmz}C8_?14$;daLp9Sir&_4yPT!vNCp07@TfyoujB%@L9phXsRNrSn5Ijf?}dt^iZ zkHrt4L#8vp{*sU`SFY;VrW&V?(=k1GE^pkqXH#Aj4gOX+;(h7h(-GTZOGmvgTp15% z4Zj@i?hj93#ehc-@4~^L%CS+Yz2e@V1DJC&c8kOJ32Vap?DL##<6~_V9peU8reD@9 z_Y!J!Zzyac;Bc|z;M<Vg!2T6z45)*YG<H6<tX$U-=n*SyP4C!@{hN6I6{r`g47#b~ z-<X2Bg0_wn^0e0js9Viek2P2IR1!VP!^9)8&vjP}y`Xo5EKoLBnX4|S=?g=n`7ev3 zE<j&$B7(d`7Gk|nGoKL{W=-x@C!jKzQB<Xxc~uj#-lO^@8$o+SC}cs_9n>$KFoa>s zvyzRWZlDRK^ynu_QCCp!l!(yANft+4fcnT9wrYCxD=HzV(Lt^LZM9*WbIe1wHD%2r z+v4IyBmk^OWC?m&n#}})rq%sM$Zs%cWF^$9k!})MOD}8D=}Ip4M@&Yw$bKSA(7Thb zl1cQrYC=t}rjW0TEQyB|RadUhpYg*s{RAwplpe|RN*2{$!Cu7!>iVZ!SwZg@0H4Rv z(j-G#c+?bfb!3WAm55-r$k&?vM30ag5qgAqhxSTG59tvNljz09Cyz~*4=fF$3{t6@ z8?p3=ohpP51$OC>f)dgrA(@Iqc2c10>}cyni4g*iga@%ovpNXLHcos2Uzg7qs3R3^ zonx<_cc^Xh{nj^~7hm{z+!=-pk7+$UqQ~Q+*3Z)z!?QClrtCXduwi`UXD1lZ;>@}T zn3@DTLSg710rn3;Vc>xc&(Z|T_D=5Ou+QLzjq>dq9pVlS3Ns$<vtx?8<F*fGBO*79 zj~cu(ti^W!#yj0-Yz#}@0^WL&PHjUbH#_g(MLuh9?F+j?i#azu7e6oDG2h#I;)A<> zsYl}9SUrDn@Y#!tVb4vC&PZpR%DPe*WbET?@xcD@gTu!kIh(urn0wu^eB^By@OgQH zTkl)QlM>S427DX$`f#^Y%Vrt7Tjg1{$g*geZqX*ovPHI8i)@oNna1rhjq%v?i*#E2 znP9e`C=p<xUzYjJ3b*cIFtsG6V_>ck7<PP=`4p1A!{Y+*ssR5&(C=n@&>a>f7Fz+_ z0(bxww*ekjL0CRKx|y|_S)XQ@?_&q&FM`eOtivB*O*+gfhjCRE^NYajH3%nMmbm6i zUQ|rVsaW<6yj{U$%IjIn5>DQRp$1-knz;;F`F!CMFvteA@(SJJ%BhL4cmCVGW8w@S z!@O+h^$nV3fkr7=@i!?bed+U3{habn=@t8eO5b||oCZ&h)m`5HeT>m6{UbZ2uV=of z?3h{JBCDcnT2+HvQ6t`$H!i9g`VLMQXI^X{e6vriVMk}zd$8Ukt$jjDllSkA0nEJe z%+$KH_Yl{P#%?2z`AF=e98I4dF#ot_`F$R*9X145vat$~0w(-1>)>xeO(-@Pv?=<j zL8=EZgqlR8PC#X7!;B6DS_V@6{vp(CXfSZOyRMKouJtCAa$sIzfK(ZZ`l*CKtuU|T zD%JZrQjeJPzw!`iiK0y*hF0%~DECOU!qDoW71abCG;gU^f2-1u!L|AUiO4@yUXdQj z0{vzDBOS0bUGlkL^#*+gc&vBtQB6>-kRH*%{|?yR>!M(b%T5cX%z&&m*U-}8=#UL~ z@Khk==nHvWl$BkqZLo6l*oGZz67A*qL5bvo(aMEhW1ZDLRFEF^Kzd|r)tIA#CK%gt z9r9T=Z9>n4L?2WPh427M1!S87P^o5bEJ4xM)KODWX9Jf36_eF+`Bkb3l^U02n$<Y6 z1ecJFn$i6P68qm-A^CNDd<Yele>ttS8r50zLnV6UCt>LDC>c;=SGnowYHJBJkPDF| zc-lIA)KOcDta>8^N|#HlCCNHGW149&{g^%}b~?q@DkTRRWZ%?sxjgscD_bwv76i-& z&wh`~`vm7PyKW42PVVjcar))YYbFQH(Y-#x;K9|KVC4x?UpRFe9Nj@_on&RwH)er7 zQmbRbpRF{wwL1_N$CDe@SthI(C7K12@u2=6fmwEZ+~%-%JK)1+IDZ#bJ%Pc=F#K)h z?ywBq6=LqGyUSm~sXMTAapZwe*z_7EXA~_=&9jP1-)!i%bAgwS2iU(T6(?n#yqywo zGV`sd$h_~xCF`y_xxdeN1J2UBx2-RqKjdh2*?RNc-Ag^TE(q8%!)yKeCl+fW&DKR* ztcx{Y6=}2~+IVBM(WV&V%^?T&c=?XnbM=G=Sa`#EfITkX1AAV{ZF0p~(@NaM=F0~N z%?7_h@T~x^DtMj>^8_b0_6yn(S#A%2#ONjfQi_WJ*YB5Y?tCU^Cpa{{yKJ!Q4JWV| z7rlFKlw$&HNQD{YFuts6Q6989<-5b<yTuEbk_XdrKpGFr7REXb`R+J4yHm>td;DPR zThckCSz6hkuwdY)Jj3t`@w`aenUNz6y{Ek@YnuZaWn{U2^E?<Akhbt?Nz2^Iju~JS z3Vvt7N$-#g@2D9gUEbv6nnUl98@0)*Fvuzy|E{WEWO|qM%0|Uis%2%}zk;m`7!C`+ zH}aX`zy~XQ3OXgF8N7Jg;_W-Fu-KuuKRvzyD-A-eL^)fGqK=B<4v50`*oV&Cc7n@q z)=(fs7LFyKP>kBOwpiMg<@2fK742UM0eu-DLeFcW-Yx4-K&|TC%>NarRZSvNZ=hE4 zMvyw{-6o>Pe?%ojO|5<%vOwz#RE9d_RPrAIhW3wS*T2&0H$D27py~Q`dPITc<A0ML zAtRwIg!Y=C1I;3@K|^&-GJi!+C~V5*wo+B`vOn0GT_uh-4jB-ciA<a<H?R3r(M^TA z*(SdF0-lf#5&=t(JSAq$_^Mjkd~EV{we?5`3EL}!)Q4q16f8&i7xajfRYH&0Z;~L` zXlPurD>d=+53FW?mg>Bc$3>#6EAa6lYC(@`3;FCZJmQ-f8AR9QX>0K@6L^|B+6@|G zwbvDL8*|m0sjIc*@(nZuE%`!ybv4F7Y0Mk4Igm=Jg>t2xV(u{|KgTJzp6v{Vu}RSX z12DU8kMXHo=3FuP#`hNfFM4^rp1#a)u+o85{D)H--Es7S!G<BTm&Z+96}~Dwe@b%U zz!X^W1lG=vSiUr3{9EYx8McMOu<gFn4#zHjR@Ne?vT-i?66)Ap5eG&`nD+DDa=UQ& zJ7|~#?XoI2KKtI&?$Y>=c|%`UZi;|@f5Z>_Bi`r<O!yAt(!u0C%&>htW|NQAQ<$7v zxiGitN(emOUzueHe<++YS`dEzVNqlzJjtne_dV-%dh+Aa7k>oVZHyGJjWyp8XF1z* z(~_WFbG^6B@!7H<VA}$p&5L|C&GTBn)>UM8&%f6w^FAX^%-HI)%j4~dYcXe=ZVljU z2GazHg0!!dPYQ}73riwU3i7|dg$KO@_ILI&4$4P*gxu&pz~+R4-C?k4-?OFtZyp*J zbZy0l@e}WzJP)_`fcb=H%a(*6dIpO#VQvMqxfImh(SMcyw{4$cOaY9^f!*)no(J6O z@y(EV)UDIyZNV@z0Y-g*5pN6Uz9<d?aJp8!e~kaJ=@AbCVOJ>mb>MsGk^<vifYF1@ zLq26oVk*`=frWcs9bWdzvC(NUvu`tVDEK05e++{@S85lQx5%%W7hfi+0)w1Nwc?UC zg%#5h;i5C_?GyZ9ROHUlw<bK!ZusU~*Own`0rY)ejlPhvq*JtE<0!ioDck4y-q`oz zoLQt#XbGd$U0buM4m+~O7s@v*{m;OX`GX!IXcdzm|0*moqCKYUO@BiD=+R$WKGf>} za(YBj?=}%V{-#H@$3I1nP(4|Qf5vZm^e;iv_5UC}`Y}?2!oDmD$PkSdPo2lrZPZxE z*KE$y?4iVQ6WO*@P;R8EN;-{H$;ZV=Pb_@{#1phac$CWz$Y=*E1o$J`Q7m8m7{=Fn zp8;P*Ak;vP!`ejJnU8AxN%&+7AeqG^#E6~vj6w#pv;|sPLbBDhJoFzsG?LAfXw-Ci zI3;s`0@b#LXmDkDMWaBe2k`MB{wL@Wp{+=YboEG&kx*AhyOB_!%i(J33N%}(D)v!g zB1}zV%q#;X`yW|a`&n7<ciK1Py)C!QN~PRV4XhO_?HZ?FZF|*qVLWt7C39bTeFSEs z=YiueY@F+O=XZndK4m)XTsF&dO|M7YwGIl09PIr^V5^=tmD`?L5eL2ALsRtf1qSbr z>1XIaEdgde2a!8WTpun9gihC<800|n0&L)`wq4I%Ge6S(67-+*U{w^f%ZApuu=sg~ z{*l|AGD;d0K<hM^p8$&&zFa@=wOK4I{|MXzcN?AeTABvab6`+e`P>{h83l>A;6jt= zQ;d5+<9Da}Cpo&o*68djm2e75C+7yWOS{-2!>(z%S?erGn=EmQbfZ>TCM~kf3^L4G zWtg|g#G~oxm)53N4qtG%bY;KGUD5r(-KXRBoOxz=BVqfk59@DKIfT7F_7L8t6{VzS ze*TvA^%J}(2pn)aW^24jc&ZJ+bpY$&_s8!;qu$rm#-83E1skp6Y_4P+djd_D-q?6D zbIzg&t7#v?AHtr`uss#}4!d#k3~c`hqw>pp6<1Er2lH6)bODn#for+vr6x~IY-8+< zl8)|reatw4e4*_#tZI7Ax|z$lQBQWv4qdx2a`%j+&GX+LafP#YA=)C@XNLE!g$ZZp zy@|7e4>pi)3hNn@)s0VhTm`!Tn3YtipIv2;RlX#tyxqmnmbq0evn!T7%ZW~c8v_#E znuNIy_cfY#dy!{GpU7|HquyQvm~l0u-53|UIce(++$9^{?U?K9vGGOlmiXWUuUjbf z*3)RHtwU;@rmhZ_G%c-K&DFq?`6qhBRwnt8phgvwUuA8F%q-NzZ+cWqpvT|zsP_0x zkLrW}ZhAz>5DH5~XqODKB{Ia;L`%Cdhu=(t+e%6Ok=U-cGN&b9prJz6MxtSpjZ$Oq zgnqD}AVYVxRR1UD4>^k52;xP&QI*~9s5irSNR0G(Dmr?aTrQc?j;5H<Aa<2KB}SAC zQK4j|rkm_RiFRCDsG?T=B@m(t3Z9ZaDs~<ZVMs`is0)SMRedC&9;@Xap+^XOg8xJG zh)gXaJ18~aXb80Vx(&4(YiTxW#MA7iq7Ww9_tJ3BEQT4*DD+~O0gQrLGp6rn8>YfS zxyn)zESU;(Vc~I(hg0Ja|3<~1b*eI3XXQ<KS=x5a>0Yx>jJqE?#y5%?vSz~Chf9at zcRmZdf?;_iC=NSs<O|GZm%;C$-)9*47M8?96LT+tb@2K~IOYZuH$K@I3XN_?_e_QE zUn*z4tX%DuKV@yq`I~Um4H|BC8}=3kzJ=}aC2bBp?DieB%RsHXy#Hr#x(z$0zni)| zdVd78FmrEw-fwIP46mq~oe!Jdz+$_EwNru)wu^Reo8sN(J<_9@3nR>Z!8)Yy48VZg zaP@+VO!)x?kSbJ4l`6$d`95VbFWZuA3rRMI6e)nDN9uu?+z(YrS>L_iM>}}f^;vAx zc6$8TsQAlCZ%!u!8@h!XdIs!t_cr!(HFb9p-woV%@AXRm@NH42Tt4|!!71N_5tB^% zcRsXWWt43kSiY>9d&tf3cAP_ex&2Gn?w4-l_}+eK=>Cb(j?dv>B24Xg-}N{cC&Kd7 zq8-V_;za1M;OeOH_a`=Rf_G3{0+;Wl%^2#mZ19!E{Z6dzer9|7hZ}@9K3G8Pe%Q17 z_0HXI&Mf}sI5xp#+GE>^Ze=^ZT;uJx)H-`^#{0z`?)2r`_&CC*(f7{oO*P)|?2;?& z45=9K1$w2y<bba$o)-2^E}Z_c(kBV3yx?w&@H++}XQv0OTXt)~vACsP87n-$1^_f4 zdvnva)RVi5=61f}d;;9;3*YX`{cQ9tMjYQsp{pKOmwfz3N1J>^SyPXghgtwjrko!A zxjxB6hM&(_+wm9trbo2|di+g~YLDOas6O~_rbkFY_}W}Fh@{bF$EqkHXuub=QrGCH zpx9SQ)x+*UYgP58T&}K=tD>TWR7g<?bt85MSrJkXj6+U4*nhN7NhY#B8<sPnn{pH( z!*oM>WMkD>z!RVr?2eLrA?+x__{k{>I#B4eBzon~l!Z_z{E_UMDC;pIA~U<y-AJrj zBz77#)d!Dq!Be?#HE3SRqGqK&z$f@WLyrVJEv`_PjD6_oG-!kwqRvN>)J%i_NNPET zVd72p4adAyRc*=R8gMk2mI~d|_cN9I*sqeAB56=8wdUs^)-FD)TzpQU<f2O6MV-t` z9ll)Z^X~G1SJ!%lU1z4unszK|=}4Ec!|siL4xQ7;jH0Q}+0W3fb!$8`#>N#khd?9i zP(5+z?qE1}8wPE9I_4epO$8;<!v#;OCZ_<`&TGV$xMR++D*!Y$y9?HPnE1n?NBN`7 zU1lUehtD7^gjN}_G!m&*($<-;qc6d#1rfvd_|3_H=^2#=pTj0e;!fN5(`P=4xe1%6 zJPu8SkObH^%||pg=-@~{&zrd$-$gV}J<c!PuUI8fDwn8KN>s?&{(Vfjxgto(&XAQz z2Ti+uKl$*<$5hX<;Dd=>8_qWvv*WOL+M^qJ?pF#PMnRWR$0u~Yv$kdMF5Rd-I{q8= zuRsJ`nic0X&NtNXS->{GxShe?yS-1^`&gXz+;P^~==>cM@$m~+J?}@oxf=cU#?zGj zM?E}@!tEztTDk7xW^ve#jUVUF3cD5rJ^>jPJ$4v&**kI3O}#<K`*k?&a|h0NfniAD z?1ZWbFDn;5FWVbbRgeeM+FkKI43}?0cc<vim!sNDKi0P4s?B}&SamQuz!%?|9@TZs z)$Jj$Are-F!|K3FQ*W@86b)~G$@>~y@PI|JFfj=h1ZQlE$ypiq-T5nkKOE~AWI8a! z^DJDt4SlDd-64%Ua3y>1<*IduO1q7Ev})r!>4Dr~15P_T6h1o&Io6PApVN)$t;cDq zt)s`$<k7xKU7;R%RUy?4&;OlZ!BkfMQPEhdKt)!qeg?hzH$M>krbo2|di+g~YLDOa zs6P0wr$;;<Suai|AytzS&8A#lZzZK*OVMKs^8pOgPEEO)hDs};Mnfe<J_gA03=%#v z5Y}D2M-!zZ$Wcg-5i8YZu$mrG!4TRoiuY~pnyaZb=I|SkufggGbhX*<*kk-MGDHcA zoEzZ}blnyUvdE4M3u<c-dL)aN7-bnl`Vlw#WA(Sv<d;$YdIjkb8$OA*_H!?O0zN*( z|IFMYfk2CcLZ%-HHT8J>hFoq7zD`?J?jt*Ed{U7X<|7o9^i`C!1!T`|d~zMX*)UZ| zk5EiWHxlVtA>SrrD$NzDM2cWdI$ElXH7d+o<s9hv>2%kRo;_ULx-K|q=9||!J&RlP zty5Y$bK*wdPcZuh7)*@mGVF<^KkV{`p_^l!ZiDM37`;BRM+$Vxf^K$!W)UzpDOdII zqXFB(Y`kFpbC?qcJy%3sx&j9z3A1-SP!qXzO9QQ9&?$mG-(hhKOj?t;VfM4_b3*5> zcx0XgX76FS)swEHPaKZ|r%1T(1HETlJXQ!NGT=oVymo*RbBK4$U;6k?t8{x_u}G;> zgxpBELd29AD*`4^ipeCqW`hj_k`5^+=NX-w+tY650Q-(Z#haeMx@d56f$I<9a2)K9 zhf5*Qt4G|#b}#3&dcL5&f7CTF+w{(On)l8A&h{!shTL7d#vHg5{@&r`i<9xs@5Ck@ za=dAG<m&EAH#XhAz2@4DE$8m+cl11I?{~u1&vvKx^j>ElJHx~==4(c5acaHdNV_dA z&e<niORrrhynmzYqGy3gbk3-htX^pu6W)Dt1sJ#2t6T3wle?Xsu*`MD`_c~Sxiem7 zi5`ENGHliR6N&DVyhSsE*2F@uWU`euv&g#NCz$dYjJ=>;?<*$TqHf<RJ>U<WjXlm} z!k&=y+u5*iyXVe<-j)NR9-M~>o1%Ax!ywV)#CR}V?%i+nqt2rP)^GW2Db6*t`fMxx za&&3j>m!ilQ1$doW>fWcT%INeD^vqrQV9iG4Yc&Cs~hDj|MG|>vj#o-Q4MQWu0KJ3 z_2(Z5e$%5`0zLkwN43XqdQ>0$H`5~oB>{v7kOeDx<fy6HN?k3&+$_=5Xbi&)VVM35 zGgOhm*0%@4bYVYkiX;ic#?Vp7(sRm4e!McuPHPASG6pgbhQ73wmD;JRdsx}_QQ_*V z3(+KU^n_}<TrysU2Dh39p`oTDN;SaVpefK52y}&HhO(L}iIm!61U-^}GS{C~pw}t0 zt9cKL>b#OMGgj&he0+%ip{d#UtdP{Qr&!my&G?+|3d-&h+m>po?bKEMEky$vMxU#} z<zvn?U|MT*`C_9C=87O<D$SI@f~hoBs4!6h3w2~gMMlb%HVS28<tj_%N;9=03qkRI zLD8`WS!X(@T<-Yoj%wzOMiAaLGl|){wRv7;hcuWN1DZ=C+m8*ne*tXACm$c0>^LBK z#o{-ElA-PQGL!J~v4;0nKFw%s@7#Zf_s&4*^$CW4fF3iVCv|YSX!Po|OV+55mBK<$ zDFL-|&?<punS><Gj)xK3ZU+Q_?Y?Jj-f%Jz_I!X9X|VAvTzCw<=Uh6N50Vl%n*m`j zpxgy^&N)9W=@PHZl7s0gGe&NtQe~+`KHa~MsWNA(EEK?+jIvdlb^7e2KYjP8(I=ea zz%002)9}XnXb}6uVPCNEDmna;%oE!16}F{-=moSKd+nkROtA@CV-jRDz+(gd#EeO| z_s7AC@30`dWc#NaaYDu-2iI-)<No-Ty(~X_eooes+`=AyVbh!+@3Xk&Ve0>EYjpU| z@Dqm~TAjRd>d2Kd_Sa7Dzjx8W)8~9l@b$RB`*Bwvg_}k_*&7p?0x-u^+TY5_!7q1p zm!qp@J{<n4T(<(6<(CXk$u$c7w0+ynz@0D7n!lg?656H%9+`QTt<#}(28@3N%;b|Z zETiII!@DTBc>41}zf9+B7{525@A5}ISNqz#!u(Z<#<!tIc)`5a@HPPsEbtvT@Ydoj zAGd6JX=j$YXHAmriZ>tZ;n_hD+rHm=&|gEdm5z=MS4)edqsi6c3$@5z5}E>eb3!Y^ z-ygNKblAZ)d1aTqqEM<-Ej6l|yz2e9^aH=?Q7wTUf77Gd<2OC35B|&P5zC5nwb-Lj zlh7mNC2iDIqRq^vGfaTQ#K+FkTVn1n7Ws?CD1IW5yOpQ`)&Vpb>@XP>BupsOjn`4= z6%;PJ-i_^W!bGW2YQp8HHs`1Xh@?Xpg;pBmD<6DaK1Y{Jzwp5_0Jd|8>@vVkxcMP0 zIUwuoWLp8LsgiA%FsU`=Pmo_C4tCJ(ht&A>{|S1;YK0U@DCBDkIW2i=o?>xd1*IlD zUQ;gDPa;No)C5zZtHT#)Gi`W7-#h5!i_|M5>^I2Fm?~2x5GhueBS}&Pu~LOp8Elve zGo($5NS+9{uq6FS6&8wB5~jjdt?*>y)ccLU1!`5i(JD>tlvOeH1vHuMeBn48Uy$rL z{F&p(7uPPs*!R%;bCFqadcT?0eK(#NvGcx56xe#e{AaK%6mFk~bxlGHTb>x(&2(uT z^!NmQzXCF<QLkXiE13GKa>dh<p*yb!_`r05^~lEd_OY-$9fsvs%+H3S(a>d%)8Qfz z0~{!Xn;#+k0Zdwas7LY{rqV>A%0j8qLJh=<m8MLUv8<Df2uTa_!nSFr_kS(F8v~ER zVDL&eaWZWA0!yF6=CI0>zHkB~%7#&8Fu4L&r^E55a3c(+Ndw0%y)~=x*&V%t9(jUU z98Ac8;YG0KEBujAH0WH&q{km87nF`DE1X<fGB>*z+0~RIK1U?}ew+QyHMX|yC_Ur- zVo&1ptxsd6(eZcP<8NOJ6`!~#Ipuuf(7oe_@0p#xZF>Ip{!>>B&t0AB?zJyGd1WuL ztK;WINqL>pbNZy_O?;ct^VnS{&#%t=!cSYr&P&J~`8nVED{PF-9gvdSHoLrYDvWv! z%yh?fJHyI@!2jTP&kxYs#+`tvFem^3|MW>jK~x!IyD=OVJ%#n*Fnv>^;dST|TRtrj zzDC3S<u7Lre7J7?8yky^gO(XPmnT{+dA~vLO2lzk<@kK@HGf90skRo`Cju*g0Lu>2 zBpvxnNzLl;H^R~*)tdC^C;6EkA^u$NYT`FNswL3lZ+cXF{H90s!T(kCh?WdI{_oKv zj83SnBcKdPMvt0vH2lTV;SAGGS*bafqpzW^uYoPGmJXwY>_?Am4tc;^WaA^T_7Yk8 zNW?x;QJ_@fClPszMI9KXW3_Z*r47S0W(gDdmQ(f6oH|FtfX4}xh=($afr`2gp=NwC zB*e}rBIAA9gdQOQqTNUWZ7rU*CSQmBh6eksd!$P2D1eTdDwh%+6-I&XR4FsYtY9AC zfAWb|0z4|?jf&((Me@Z>dK-FR9b{^@wybi>d$8&Xe0+%i8G59R>D6XgEaq4<zG^!S zg?rZKoz;~a@dO4O9_Hs@w)Y705QS;3!3<LB@#&COp%i%!yQ8$2{YaUGLX{bE3x>GK zDLXj{ub3%SijZ(9fC-T*3*~ZaPVpi2q7zK%DaEqOs=4<&=RKeCHl4Hn@C3{I(>C8& zvfAyS2TV;WoANHtEcE@gho6k*x_)+s(VB<)YMdV5_W2C`uN(L|V%4OJ!qdh=vtC`V z**%2g_hG`w;4R(!BpuwWI$hb(>&)^c9_`xLP3E0SxDLm|U`-0kT5{n)Jak-i+`bU( zO5kQHoC&Vnc_g95?gK4S&#~VRv1KZ)iNaOv-q}R$y$tM8sxl*8Vqo4N@6@u2tka1g z=^t%ADB9*FOeuzrS!6=hDHpi+7}lr3v~pOSRb}x3?gc^cZLnMSdUVrMn+E$xCO$tn z;;qkpSo#IV<$=*_Fp4klANg@?84N5domg75CL`_G^XxUlj#+j&<FO@C)ak;7E&)-e zVCA#2PFb1V@^U7A$~F(nGV=R2`EBNmce%EY%P&04zwG)g1z@<vwau~L=e_zg)!FZ) zgU@MOm$ldKFS_k&eA3JMl>d(NuIIhuE?PT#-;T2mi8l*>*0kRoCy(dGF$pu?yl<CL z+UqMY(@t;v<F)O$kWUX`l#xF(-=cR)Ww$Rd_6@9$gsB_iMVDcmH}F=vmHR;O?CgVc z-y5%dXK$XjY2AyJ>tFQidNJZOxSy|Db~=D*-H~b37|R$k6K!o>Ek0SCp`$Al2>+ew zU<;%SKUS{Mszi@JGbEI1u+@#d=V#Q99{m-l-v8zFh&t-sCZfmR^r-gur|8kY(&{%o z`j?>T`hT+bNH&ti(j)RNNVXF+;Bei=(!L5x=s?nhK%>dyYH~D?<R~J+(PtQ>LG4*V z_CqOAXZF-vD)zII`ieyXRuV4@vjB-0Ig^{c9Wo?j-Lzu~IaWh8wYI8CA?BuIkV2`d zw&3tuYp5G2D;a30HsPu_7H}GpZ-w!6_<ZC62-4H9twZ*!<O_6l8{i8ow*Ok%x;oko z)l_+8wVD#?LqgW0!kS@BIr*w4vL<%c5&LykJSWT9loi$RsL0-k45{Y!wMdU>AJwk_ zA0Og>jvgU%)YQ_$%xSN#a@WS96HmFRszL+4pt%M&SWM`qK9|eRwdX1{<}&ToW+j|z zo@&JfD+VMi6Cz}YrANpoe$XSrjgVDTTHsLuj2SRuz?i*FghD!&FoepZ+`^0cpB{97 z?Kw2z(X=?91%W|>?>#aI@aq3OLT&TP8M_Y*Yp~5?(8J+8N%$q0(Bb*0*2yE9rz~m~ zdbGtM6CJ~`t?#t%<kg~=%ediz+qwnXw{kh#<dkjOqZ^k8G--Xna^A;3rX)<?8YhZ} zZSTS86<i4chimCKQsF{69E&VobuxPP#V8AaMww1>dW1BNO$#M?dsV?qvC>qb+>EI( z5#~G2g{<Rm;6Sf9+y3$5cQC37n&(!HdIOgp!j!4E4O3uMdai9s#rcrJ$1Wh6;%?Z> zXWO91W_vzM_okZ<PcWSI+BODEUcu#Puzp-I;K|pK#V{uiwtTHR^5WC*Dcjceu$`u` z=l<ptNngKf13v7U@@h^JG%5g{;<9e3B};<yR>xJf%&zSG8Afi7^Kb%4gQct7d+Z5Z zk_4ka=FWNd&D#Ifk=v2S0$-f*d*yoj!@5mQmZ6EuZ@EZMJ=}lnf#HQmTQ9k9Klf<I z1&=LPJm%i<p7lO+`qON!akj>rA|1#29-IAmfuaApgwp<BvIeB)FN!VgZ|E~;qp$s? z;%&}l(o2=b9q+}=OS?GX+0lisUCzOZO>d^|esk0fZeE64&PB^k-D5hmV;bq<i-C?- z1AJ4`6=-XdVKuTWlosi~1zR9xjz8@IjdhRKKm|nwl^?xI@;)RK*=;h{pYXf)sFpyF z|A<P6ziRa>kOf*_$jjC5-lKZrH$AEis8;`$9tp@UM`VftnSMl;^s^s|H{fXWWf(sj ztL7XvEk1hJMk1o6qm9f$MHQI{=>n1uoT1QDI^2eWSLm;l58)BH(LF1PpRLqiYUwW( zdrK_6B%%Ndvm|q~sqFNofeMPf8D_9DnddY}iR_BhMN!Fsr>>{T&Vj(1!giUE&MkJm zG3oKbqK+nuuc@Mfc}04U$S0X)-9Y3+`_)B_+GQ0&p_K7XLYj~ju@_~cL^c8-_hVkM z^oaCbQIX|SU4V}d@jo=Uh7UqhONS%m>I-=fC6YdhO075?q)J+vTzpu;BAdaCa#OB= zNA{8uqW-GQG?~uILq6`;%@e7VArnG|WJ1Ugm>>;e$O3rzH(bd@mJg9`7<wCW4z@pu zeBo6QZ!Wi0F18mGJ80z{Xi#vdVYY)owxfRTS$^)>#;NCqzd76W$R0t@nN#OGUh^-u z2rQeE0E1t{kT<X<4n~aI<a_gt!JzZZB$u%-V8|!H<K`H+;Fdai%)T)jt}il+U$^4* zy(=(lN#ep~Nq<aBdU+j^uEV1vg>PfwmS47AeDRoDq5I2WGo<V09%cCu>W_l-NG3{{ zoH9&^L>0+g)xJhqCpP96Iwio$@xlJyu>Bk9E1H!9t0UmHGt8Ly;7C&O@ekiUeLp<A zm$7~5`9B8Vk2wQfS{<G5@NxW+x62*A&s+6m`?RNtS0U~u+<XKxeZQ_r1|&=^ds{6Y zyLr;&6?-Dnw}gX<P3qoJ5tsUYv>g3@cPI==f$rHA!@ifU3M*R?2d#5p)JrfM`_-dk z_T`>0#%rB9_7LVrK*ujttuykczOUR6Q)T8|YU@)uV4ugjxQhOtaz}s5opC+V#wSx0 zT*6G+jYMifa{jK!lEYq^lA~UZ4iB#EfB4Y!!PD)&k2iZ=wF)vn;k)>byHUuqJDy)Q zuW~wmImYoy%-M5^D@I#;Z1W3U>L0%_;j;wp*um_rZwBoD$jmwC;8wZwK)||_*O+Dv zRP@Le`Ft)Kf(Ck;4e(`&&&Ss$9s0KLuY`Q|n2fDylP?S^k`G|ZiY!(`Rkj8yGK#8f z^_0~$at(#vQ|<Z_e$%5`0zLkwN43XqdQ>0$rbp~tA2fF8=A!5b1<g4cgB2KWOH+My zCA5KB+6@Fk9lV*xW%s8>+lN+9#y=F5lvVM-nm%%c_Sq1@6TDN2%*RHO)RbXbSC6>0 zXZJlC&M<L?M$b&m0xd;8QX6liO;Rx(t@9I0A4#MgG}N%kH{ftv@c0HCByB`m@C41& zIn6bAE!DZrHMq^WoQ6t@l#}5LEZu<#&7uljJx9)oT_y?<CCRVK%Iw$BSOwLURmdGO ze}6-d@U$MlC-^@^k4T>xpVvgF(NbN>O=8_$MWYFqC1ky0be&z)HrhDZv2EK)V`s<S zvDG+fY}>YNqcI!XXp*Ll(b)R-^Nw%4=Ztgy-apo_d(AcHH7`Wz>O<9o!%rQ^N`kdK zb-TpLpGW!w=PU>q*+Z~k`$g6n-U~IGgiZj#e&@J)GwTSlre$(i;(=DA81e%C@OwmQ zI0`WMw(6BwHGz^a*6Ig_QXD_WLaVrF-jzXWai%q3l~l+MNe-clqgUl)?r&gAf3KBp zYVns7hQuY7BTA3kn~<O=O9(dFaNjCJ2vO`pTj_<q$j4h|R(IZh_FpVEAEP5N9RvT+ z$$Z#yKd$G0^B#HA_Hn>`LY<)Y01ow$@O@e5OCfp0%H4O!CwJDV#_y<P88ebEA5u=# z%K^rlr(0FS1;)#2k9$+w3BBQEd~DrV?UrJsC55lwOz!E9;7oqLS2+G^nKwNsG}z*O z-syz0v^Dic;qSY~XOqUQ5RCX9f7vmk*qWW#=wdl;uay`Y#08N_LVNd0%$>H=<nvbg zd35PLNZMWhaQy>%Va)iol{ciFrY<_<I;xBo!ZPAu#?Nr!(dA?lZ+(aESHHyq|KY=I zQo|;a_w+O%KMy)YM6>}5>@A?ZU8VhlU;7kd%B=8A>-f3K`K9g=#oy@!{|#NH+)~*W z;r5?}uKuU{heGOmm&B14F{}HW%<XvAs^xvDCL!ssH@maPhXi>DCC$OLpMw#o-IpRK z79G2<wTgk=Wgg=W1+H7H^basBJYF?Cz^s?yX1xL>FY_prE{0RCJ#I9vkqiowInlUX zeS>*%39A8Y9`w`WMq3Ix%oo{2>^<}obRkfsKk?vZ!(=w3bG1Up`v5Pd4f;oGXz=fd zGr0fneenQeXd6-JI_T{U=b_j=#c{1>Y{Q}2I_-a)#-qKN7hOtf=rtO6Jf2XQ^X1}J zZf=g@=jocXEJ{Oi=}o;82gwqOTsjEp>D^T{;M>sR%)fo*UY)lZTw6SX*LC7v5G{cu zUhYg7;qf=MEtNAgMI^Otsu&s4vO8f-yQAz?oD9KV35tbW{84|-BFB6Tr(7u>icw@Q zErp<?u1U4!OBtCaU8h~9QYlM|LcM{!awpSH{rDMn2R~usl3$n+T^!N&qb=D+z5dGv z#>wjvg`fWiM)yZ7z;NGoLSt<O-R9T{&rf(sYyb)4!81UuW}YBR@&24*Un2Cqamgc6 z0~3Y8Ga3sT#!<S1Z%+a=IxdJcs8%(U8atA-L*VigkR)9usbX4`V!QEmtj~J0h^I3? z?lu?ew!ucU5g>W2HNrtiQ=jlz$aecOL}!%+6|GXGuex)leu%IOF4HWm-m1U$HI~(e z*Erh+^YWo7cZb8Bv^)3nfJaD=nhm}2AuHRg-9o!xae^)A7fS@|1c4d}Hin7`lH)sA zHMLkWsQ9OL_0WHWFIisU2CHTJcvum5v-MzFVi<V+B7{8p1)FChu`T#WJv~lFmU?p% z?z5lAPBRV&!8stRKyTFa**EwLK%qKBYl3XfnOe_<G^jsMb&FLis{o>WSj=+sr>rd7 zp^Mn%oyPl{Z_(wM10iWaFWkdFHmBQ^1wzcygaInRVfcZ<tG3{^+so-l?$MV~Gt6%; z|47?HQHBL`Vo`0`*ql|?Jec965`19n9Rx{sx4$m39R%sDYzQ<`q}y4UyWZ8@Qo|#J zZt?DgniXxI^bmWvz^=c<3I1-E+o#XpXUactI5QeV>abe*Co|<h%PTe5CG+(RDS+vr z@88q)W(d=FnFWWV)UTwGg74SCX<OI=bKRB+j(VfH>!fb$!pA)`C3>q`0`!&l8dMF8 z@A#H@B^=OaSbe>8bnTWJO&q5mi1oo`NjNfsro$3PBqn}p7H~gg>q=G%>b{?MW0nC| zSk<sZ^hK_6NLDb8ufeUD5crzB{N@!}H07Ng)e>`$!)tHt8ds8LQwR*xk!LZYn@5Lt z^VFXS=ik%^QI}%DTY$t<*<7)>!WaOd!Dx&!OcXw8*fyjam(PC*O92-0r7jVwe{R3l z!TkD?1lAdG(fYltPueEYt3V1dli-VT{J!a?t9~#`g`;OE+WQxiDwBjif_9x8*+Ye) zEFV>n*4B`=4m1zi^VF6lG&a@QGqEtnN{X=7M7>>L7xsqPzKcX9fw`yM7^!|g>I7Pq zpP5x%{|`APDP5%{NpxLWhkAO^882BJJMK`wj|C`^aQB9A*Qsw*g?y;3&XN$D-rOGO zo2@vow6JJFz-_w8z1nZS`R|olX@~p(Ku-)zL8Qi)Oe6tC)%aMz3sLkZcLF`Rq{B<0 zH5Ib5U}e%KnX>@s98_g;%>?lZ1{8)0<HawFLJVZ8m9EBe%4|*`_M_&(wVYm~r#T<h zX*<Eq*2ci9r*eo+iA6Q!@M(N5pRr73sgnMI9zRxEyLh5!bbj-}@eJd?D7f8zoxAV1 z!ndhew5AQd5$aiF^wQp`tkbl2@Xz>wno<S(=HK;1Aa1Q{EL#h{>DX(og1v9TU(cTq z*Pr8RcSLgFJ0!@szUbSF_{gi1tXJ6UoKf_>+8GR0IPh5vs~0T<3LU*gOP6X|iIp{0 zx0;c&=_xV0(f{)AoIfPuviEMj4(z@y5I<rqR97oA04-2d)JDB-;pjmrKp86uG6lez z@kknWqK@?ptaJK()7C}%;#^Xm#|+0K;3o<lGn>wg7-6AG<{XqZ)2C?tZaRu+<tEVR z7y??viMSXOGUTPTnb&N#U4GaQ`%?wcOORzClKVJMvukC0j<+@6t~B_UQr$yZvo8Ch z*Y3pZ2BxC}3<Ej&=v#*8r+W{-lr?#vWQhELix84afBMGilh|%48#uNiH}%?7e3p>F z@?G|8GOyjhKg=TusD@EPUgx{^=Et^Xq{gO)CM>w<I+eGdrmVJ%S^}@_45!S?D>>i4 zz7XUV#Lp~qH}>E={qVG#Juo>K0)%15#kZ@6ONz#R$^KGn(tm;uVRNresr|oXvHw}g zWGqo~xQ7q1=>4@lDJ~oi9F~y&V^3`Zb{{*$vEu!W$kpb`wX&?iCTSsM_jE0VE{nqL zJ2F{BM^7e1QE|unz;grTOhdi6RI0#KdLBX*eM%HZb9x$NiXflB1<fx`Y|rKFTb+zj zkf6%5e@k%tY!!pdwVdO^HLq4OEGp5)mti)b?l^hGwP$^d_@gU&gp1c4Pm7Vzh*3|Z zsjWfgkBQ0bELsOrWAc-B%+^Y#h!XA+HyEK%m&v4)D6X#l&Ufw!snb%<_|)W3uQV_g z@l;R<>=Mrx)~d_F!0d3m6b#2#9HmPW0B=&&wIu9woI8azHQ(`IiN~*6VSJYhSoil@ zu;D$UkzKRenfXbC#?QAmPHovLt|S#9HPmHDlWU<6lob;LDm5chr<hV}M&!(k6ZpF4 zN~t?5lFyk-;c?83$^h!_B{rorGU_sq7#sObL(&i^9BJ;+poph3xVGE)Q-6^ywo4Lq zCuQUz?%xu-v8C-X74F*n9Y&VkmzQim|J=vcUCZYu9cXdp2U)Y(Wj&l9*AG39^(Xwe zdHCh=BN6crhBl)0&>LlCzB4sC%!UHJ0%EnfT=Ex+8Nmp0R#LWJ+^-6e^g_r*4rm7` z8E}25HU%V`9FNkMj}^pAmj62Yea)_TDlT1i#4>uEdohla5SCa(wsG}-akgk6R=0lX z!WoMGdd&B6{@_4sNrxAA{-@`as5UkboqoO*jo=_X?iIfG(s!BbK`hM2eDF${&9%j6 z5>ESL>>kb|nH(QQxvSSwc0L&UJ7c-@#n(iUYnaw4h!EH2Z{;17=eha(%m@U(0*cpW zedWd|#}axoh`fXX6vxZM*x{r@_w^%uGHw#|-~EquXZv0|Z-;Ja{pkolikvoY1zmRk z7$nqm1%w=)u<cQ2!UcZ9JUPR2*zbYOnx3?n?>;zoFNU+AwS`{Y=KLMZ-qnv@&9@Xj z+J^=_np{pbc7MdMG~9zWJN9|4DvOu36=wp+B#KKKMi;b>Iy8>j)zy8CDQ}w7pX8`N z77G%fWKmf{fJ~0sVb*OnKiRrgsH$irC~k5{nndgTZJ^Ko<0=0yYizd{_*6kXzl6n8 zTMq1cAreECl0qe{Nf$)6hrm^Y+UV4k7d=7GS}LhjphMFoZC`>9>s6w8|E-EokJdS4 zNXt*Aszyy3S@tdqF9qX9f~$8ehJ;C##<e1fG3xHz=p$Z?W>`%B+uF9+SU!PB3NB1p zhUmaWT#;o@Wz#%@3gp%-Tu@(OYt&ou#XuXleSDQ1=}WcvrK+tTemA+yfA!&?W;?3g z1wj*Ro;yvE&YHTaSlw0Lk51T*vT#^H*9jvBI!XgVLIhD+msu3cOG*^c(^D&Vo5lp* z{_dBSlKRA@l5k%KLT(sVJ=Gss)}>LhiD4r^n@3Tb6<LE2Bw%%QSTqx`u{-z71tCZB zot-ZZA!pyXoFlFarMXM+-p%Bwma9!4_uvobCb$Q4Mmas$xQ>zih9S>!C3BJ#%SW#j znMhIv(oJqN4kcMYhNMHrpjT;^?9&^<pt%u4<<QDb#)fG$Ww_Fi<1bjhpqp4t_0)rL zE|*uRvVDbYIQSl~x3hh$La^IT7N<i+Y)M!hFz-01zK(}1)bTuLh|^~guvuI&Q2Vur zf8%5m_%#=Gi<~eEM?S&oGAWlthpt4}oIh2zL~zV{!7!Mm#t!&IN_uZM(_D#-Xr_$( zzQ4h@3mz(d?i8%mqT=^%^&Z{5_EdF@_J;6m%=h4V`$sJB8ahNb9A}|!Vy7uinp}Nr zgb$uDh$pr;wcmOvjKg%@Nn8K+?N9j_+aa=oCtUBj>89iLIuYU$Mv*duf;Td*LG@%o z$iZYyB4824@^#Ee<Qc6r!Fcv9Gp+)VIA58TVVkar?1${K)@#u8=VH>z%1tN=-`w^H zL2eu8QV_H6b|1IqoiF)XY>B&W8o4B6BNRmhpO3Z5S4K{1x4~jKB_{Kox4kFGnw2qU zUu>8H?+un}=l47_lPE8=yZDWX_Vv~4{P>)FkH}7RDE>uBgquIlHuhoHKxz6M&@J|Y zSY`fZqNQw22xa%m*wu}TAnBcB-Cv!9O5XC@Z73|kB=HKiH+`}gFGDB>2(g<BbUIuw zf8WtwtPZ<i`m4QT7$7BOSeMAWK%(zUSY&o~$B$jxxy&$M9i&0xRvBJfJTbdo))o-6 zdv~mLrB&w-^MASj9|fgAZIyk5N}>5FFr%3b4GEB<i^^>S*=t4y#zF^Im4&>hOC?MF z=K{;aUdnV=l<@&xx+)z3%G5eJGI{3L1Uiuv%ML@>uBxgYP3?m?9n=N1`&IB<on2jB zHVmgCuHv|9{l6PBKJQk?KWax0xc<6atzgF4amMrG^HQYiSi;e7RTga->A>$OLf<M% zNx>{dkHoPQmONzW?i3)g19WX{N)~*1E%9*m1W*YHS)0<pPZe!4wA@5Gw7;n}sU0d7 z);JZd<_kOE9lxwER?P#uZIlR`Y6Xm`*)#Xy6janyl`)FCSCrMw_{RlhI@Q5uZ&qiT z@{~3Is&sF0P4?q&uEGxmE<ykwzSCo#P8iZwobPL*B;3L7rC5&~xr5Am?5OuUD_xMe zH1w*g+*OZ$Xm5DyY{2B`^|0|M{p#QyUtC_3JGZrtI(PX}5*mzfGQkDte)j81I;xyY z)BOn}DC4O6<n2^ES6VSUY-DiqbWhg-e*)7?#JMP?5oH&$t&h%xJ)X_&u6)YSLucZX zHhzq~B_#>FtU+&5%~2u1(DW8X90kRZmh;{RN6ykroOXOiGgN$@IT@0R(XFY2!`wVl zO$|)DWqn|YJAS5!JahHFNV$86$t`bq*ra{uxRkm1t!!RK=(u0f4n?vf12Gj{J!)>! zuiYtLtq~-KP7txTbkUL&v1eWKCZSH57bbL6d+B90=i30|-|6>Pek^p*7j@kS*OE11 zyNk|!l&xb4HHddLFY7`;ge2TQbmB57%j-Ph>tft;Eta?CaPik;-rvE0_XlRCO_!?1 z(nabrQ@+ID^lk9H58t)T#di&FGRxj-g>HI<SYz2mLssz)aQ+Y&T#_WyE$*;g_q^R! zJsIBBQuIR})(ou`(3!s=v`QCU)5uJOwy*o6=v(-zwiY$E6CV(^T%FA674ae75|rN{ zE%@~HTV92$Pw+;5hh{$83o#y+hBdBc>jYiFb2D@&I_IvtF~AC2e9AWy8v(5BU0EeH z1MN~(3X3do`{pY<9DSpY5fl~%gi8#|^H|deY>0P|UvGCw+4G~?54jNZ_->AUj&3HN zDfp0^4J?s4k~{^A_YKI<5Zt&CUctn9?)w$eXTS@jj+Qv0(19C896{mLU!z2A<-RDZ z9ENUfUEi4RJCa}{ncuW$_nDh$DAN8A%4eKjh^X*4HLzT)cM#NeYI8RN{w7Unjjd7Y zK89_YD^UTw=qZeFlI?|Wv<hb=RZ`-S$+;^6HXVMii4IqMe+Q_rFGus>TS5DW4HOww zV<>XF{bx9_Ka(+2Z?q69o=;b;(CY<BLXV$j3liD3LX-h}Mg4Yz^cGWeb#0Ucs4{v> z;T#u;9i#W=ywqaOXY>G}-O8$$%<@EgRlFrb%J$Z<GtroEj=_(Vw?sa`OGHtKBt($! z7+2M?4$Lq}t&vIih!b8$G6^zAfcs7fV-1!yX#926Tykn_x2>pME`=y)m|0m^Tve$T zOE`tRlalf;9t5o&*%-H6Fs2nAP*)qjxdmiqwvy^CHa*#*ynQhojSk;eNV=k8I*eOa zZRe?7k=}}{wPKr!c(b$Xv9A>ZcjZazMy3bM>4knCxboX}_PSMct@~BnM^$Go;~7SJ zPJHXS^Cab#L`p6!4O!LRwkV`q2<B!4=MfrK%W@2%WYu(uD7=~?8Zc?pxDz79JZ*=^ zBU}r}W-=#3YJ<4R4O3vG2CuaC*ui=yHsU9YHC{tfqFG_>Dky6yLX~8KO;%c(a~xWa z17zC>iAmOUgQ@o#V+Te3@b54qU!VDe{bVRJ1G~;yOa#%p9K;s0=J0+cW-?d)eeU1m zo3E6}d#Yi5iZ^(C<nWPdv|y0^M8l`7k?abYp1|`;0JBMd9Wl6Oa;BA=KkH?&3vf=T zxl{GXNhd^lES5<gBj&vrC??P)aj1SVD`TKImWM%MlR|l`y*20;Bzhh3DbqTBQ_sJh z6E=LN=<srPKSR>Sg~%=;bs8h$Q-M|F%$2#+pnldDK_>0Q#fPq?+GGfl5!iBfPQLxe zSU=3i`7i%vUF08QO44lUw|16r1X6|vY4Ka0S75^RuOp~wJJK0+lXT(6eFQcaW%_BM zmJfO)nGh0dHUX3$OSA4ozT{7W+HUK8w)viR&Px54zkkEpT2e9VV>psevKzeGZ1p69 z<oz&q2fF7P?UUw)xn<Yj1e;gCHuvQ$k*a3Bt1os{XvX=YGIu;H^`|erBDQ{_EMbaz z1dK%DHVP6PDkJ~0erOBeXq{#@dZDn@+h1ECQKl7A_>uf2N1<R^|M|!6Xd>TS;Sw$y zj>N5?_8n2|&Oj+H+i$45H)zTfQ9rT$!oKgL+3e`Vh<`WDqq>1gZgVH-j|W!*nH{S> zx2dHQdBI(ee(QFrEyl&Scx%Ztvh>xLZ+f&w_}BlIdyZ2S;M{(Ok3fRGis@Vnv|su{ zTMMRvwe6%LJ8F&X7&SwE#m833L0sv-&9WRPlSyh-Zj|%|e=;00<2-9;!s*CP2-3DQ zt^v(YY$=_a&==}yY7;h(^D2tQRuZ!yn<Ip$5+j4eT@()-RhCAIa<bKHW$eOU;6w@S z2tHVg%QctPR+N=(@GCW259;9>(M#`SaOh$JtVL|$kkFo?VGVDKmPs^7p<!<rl~wWq zrvqQk9-$9vBg+xNJ{Jfa-jeUj*m!qFId9$~uy!}9@<^Bx^+wIs*$b2x6=KV;vg5m| z`@O(>x>~NsDk!nr>YZmwxbUmX6Lc7A>1Fs+c$lX@>wz^3@g;lI+q+?^^O%*kRyKvy zSe3V@HE4$y1>Om44M<-JLL+5HU<KX3L5L%ty%9CxkzLeJ{Z-e{pm3?U$|8pl8;W<V zw<5F>Q8xogfdPC@<g`P5C3WPsL*IIcgr(qyh2)AL^U5rhy0Y--oVL1x^;LN)aKm$r zq2nFN)MHOY*Sn6Kn`nS+3ZzK1GuaZ|jkQizJ;vZ`22%4-ADgy>(i!@N6mxj(R}uo+ zzq;;1#Pj3cO6%$28tt-=y;1WpbA_IxK`U#;tYr>6&Mrwtuj=SfD=>+{Y}PPv;Z~YF z@Tjk`&8s+8&Dz$LFG+T$Ec`2sPhoY058<0LamR?2t0cOi-yPu8wy4-XCrrwvHnnVH zZ}D;IRu<0o>cEy)Vo2KpQ%FEHrIXkcQjJtb#9|a`7ILd|TH18vvehFo7~nAl0l-0C zWtxVqE;|mG^55rzS3Y^d?N0l0qMU4?MfU32a&{;>{qL;TsAxz@+h2zDQD(}u0%dou zP42r*y1O23z743Xb#j(4O>J-*X9n44@#|DlnJpI%##e#CU%}I8V*`u|VP5XNyM|ky zm$TwC*Jp75@?Pi@)IsE5tn##Y{tok&-Q)a?7umprq7+WzzEzC)>3Wi3Mf7F*PJS9= z%&Wm<1elre#Xj7?ig$l;@#{LVYGcE$^OVk3g|EWWM8o+zvSoibj%9)t>1(@*OX{8- z>FagA;hCXNt@lCS!*)=Ua7}ie?$Ys4o^7c>HPGgu8PCdQe{JR6Wop1NWOtzUXx>A4 zk#unWh;dpr)bE|5;}MDI7WS(}*^D#5vTvGz%lR^%FTRh}c)N_ZhNS{omz2XpthSBT z^%?N85!%Y0LQF$5bmzH#hCDMib{ZFNBf>Ov3#qN}W-RdUqFB}>Mu?I2wRAT!3__l` z!iUD)k7)TQPj6T2-?Zgl2NQ%I)DL7bQEks!*)F%wx%g>O>~j2O3dMXLatVIO<|;fK zR`&xMoec)ejjvj5@Dm<M3rxp0XNkda=Z0cn9TE=?BNjG)Z8(sjwRpi_pWG)p9v11Z zh1<y3xoG0Z>YCa)bNgv|^=hbmcg(ng<fbwcugWK2`ASVM!hx%zfAPl$G*T9~3N%;O z3q;$H7O6(;=|c>Gsa0h{&t9SGG6L5U8?=o$x?5A3h^XHl`gSD(GEPFXl@0QyYcUYo zCah>8qz?1r6h;p~AeAS&6f6pND%}V3ap{v_{&9-3=@aTb<%4?$af-eH1uL^61!pri zs=_<32D<dm?hnR5C$KXRi-94j3OQV9*vGh!>5M~o<5iBsBU{CqR7BmRBqmo@mJejE zX;}FX2Ct?SZ<L~>8}oaC#}Q0b-<H%a3Tnjo4H}srF{83wHa1|*AE0D?@&Xe+Dt1Z& z5SJkwH8nNVO3d^otIc;X00yA3BbVzF^cbe!+{?BDN8iU4;30r|qV7}6%X=r+%ifjF zuxyi1_}m<S$_wYUl1?Vr{IKvuY-IyOeN#}3V*JW9!D~ikL`KK%kS9xp&Ws+D%9C<R zzhiJJ;TATQ>+creX}Gu-hBaAZ)o<(e!z<Z%ok%^Wr>C!>;=%<LJK7CFqIuwzjosjZ zXLKnP7B+IIpztdnyn($CRrh$!GIZQfK91ccvDXeUQE(8x2_{P6k1Nv(Jp^JfHaHW6 z{Vf?c_p@ud!pisQ=-*rcw+w<640^WC8rM>uE|$JsqPqg?S!Ut9AwIrBSrSDg_9XL0 z)+R>zFLCtRiO^#J=1+zwwX$5)qL65*`&t@4q2%{at{CF)m?_}AjT{|z8u|V4F9lfu znJhKJ@;3(ct3>)o-b&9|J00G;4ay5&A9o{1xt~@~wIz!R_-)mVzcYwz?(a`M=gx$5 zWApg!<`zSP<2&a|kv0$0nPom!FE^nqGv1$4Dc*;24e^ctKwW^TU4lVb#%(vCpSf#4 z5itX^{7nCZt4w`4P6J@}9nKPQI{t08rxfu!_(BK5=9yv4y{q<pIVhz*^rx80q<qCt zzVPDiy!fCeMtv~|x^RIyy6ayvc{|v<bb0lk*~CVe`TVgf__Yt{J^Q3JZx`U{(Gm&z zJ}+2fHQgO;FVVw;?8)_FP(@&F13FZCOWkOnDlQ9gf2A4<W?V4SH=OQ&u-=-!lDZYA z?FnW%0oe)<E`Cch69IuS=PS!yN3IE552`nG$X7q(q1E}gvA${Wex03<Q~1x!AaCas zDIC6USB17a4ri8;-4@5sPK#z*+DjaDceSEPr4q^IuS=H8Q<MsbEa~k0uPRD%i6rEV z#f*9js*387iLA}!>_dkktOJyK5sBw1tPhoRRV`^z@9O5}?}c{Q!-&mg4R(3d6_cgY zyx)9su3(_37xjM?sE+VLv}4A^-ly0Y&Ln;a&3jJHu<}IQTWNx2_d3!Na$+Tk0ye0v zT3n*ldcEAGm;0I8b`Yw(n<%TOmC5z>EH-M67XHD4dZ!Cm#YUa1u4Y#EOVKnD9C6uR zQWEu;R?hPRmRK{4o9!Q=M%meM-`_$cLwTODDtSpP7M2MzmApp^kD&_3y2Sq>5`!6A zjjb#z*j(gyPs#__D}dqDpV!|CiK*1{Kc|^>I3;(mzyS98=%WP|(pUXbL>a=<D(u6= zU=H+C8kK#UE2L$<_4U`7pI~&GP6)$lwety_39Ot5xy`K{0Qo#ia4}ijGBx3WI-dKT zfx)I4uMmX?<LPE{X?baRWf+bEjc0jrVGnVkh!Krz?<&V7^rc!53K=3VeIb|Ds(N<e z=<3R9;DGSTli5?>_gZW*<k$F=WkBHwk0{lB6B>-Jo|mj-->RBXRjJwi9b#(z$}O92 zBkPitSQ5F3y2Qh}hB4c16S@u6vO`%hPqGP#yyOc3k+0X7nsi^okb_nI&m%5%_4|&E z-5k}$Bg8~fYg=xtE4M~B)s+>q><;a=U9Yo;P$m1k>_-egrVtT@-OCj7->SyO4^;T+ z1<!(X6czTqHka$Het$$bwCW#bl*}~iiJlKyvX_d`zxzvI2=NDW6&c#ZNJ=K1Bhg#P zJtPT5Fi<0{CnC2oDx{8Q2T-OlxH#usP^(oZVmwG3qXVc#&v_t@E0Y;O+9?wf=KdJe z(w^J7@iR>|dkP!W&f`9k3SoKTX_W29lVP-k2f4P1E*fn__}Cwk6chp^O+LEG1J?kZ z9?L5IJ+kr6ox77^5bI(V#FliV_?k%2L)AP-x9QGna-Wt^)^>Oary+MxMjd1Sw5Qh4 zG`Cs!j8&tr0cLke&ELh>f36oM#{y^E_@=fh8Y`5PE;S8WS}lGC%^XRDRTAy~*BuB( z>Utz!1s>0P`EZ4B`<RGdNoWE>%Mh@kJa&oOf8U%4%$pvvTduuSP3+ZRay};`))ZN3 z*qAytpba+Fgb4RuBtAAnP~E?zbD7quH%P&~mi8`%;BL31WZKuPQc<yE;vnm~6!xEV zD(wYrLk5r8_i$L;y9u3yRnhNeNliUzC4jH*64krOXOBnkQlIP0`|9UbMw(*_!Fqu` z=00<*vqSdb&hM>z9wXNFNx>4${ei$d3NQ2Y++xbN#T11sDD|j>MY$&N5$2S;SKmbI zx}dZu1EiqT$k``yX;IuMJj22~+41D{G7RW_WbsJuutYp&18}sMlynpam0EwJ>B681 zN1lu-NGxo+!>qF}mTxa%MG?vSH+!_U5t4TD-TJgSSr?zo8kejHj)}~<(@p^7sy<i0 zmEggl7S5mu1X9YTJHT~Kuudqk_5I%M-|l)%0P5z|0u6XLVse9|L4KbUr<yAh?&apj zhpHCiu7V>@`o?65Mg1dSO6n9sfif6u#0<8o!kMPXrXUDr8W9PZr|fCi`R(+Tfq@}Y z7aD_~iP|$do*&}9m=y^CCAo4PITtu(p{2C~v&<T7^Pk=0DKw8*bai#LbKQQ>8p$1X zAit*|i8H}6phf0CL#w`hu=x%hQX=dJW~eVjdpF&2;crAQeMJ&rN<^I_rkfjUl=+vE zd3}&Xj68t98BT|&4d%vUpBxY^XG6EIk!2TBT3H%Qa8mOfmR+H-%^nlPJ<VQQ@kC|e zy-e_QoJ3+GXMz546d|KQ!2`Cil9kG$E2$O_-%JIif|kGPPy34t%pd=);o1^S#8;I$ z<Z23b3NznfFiJ_LU2LElnO+)U!UT-3s)*Yev%$gmvJ{jI4t~K8f?P^26MNGA6-WGC z!b8vf7xVb!<lIoQ5-I>~>nXanXM`u8=aqDGgWJpto7fwTEjAxgqMb)Y^`g8o^p0-w zS5IBCxETw%xi`b9?kRz;@8Z^)253T^>SCCVSMz5E9C49o#@y2C!h)G6WVv;XMKYWp za(uj%cM%(IY^iLE7A&g{R+E{g1}{i;S2|+U0nrw>VB$S{_59%5;jfS?(%W)BCX$c# zT)z9rCO&~ri<jt1tl1{0;96UxT+7K>&aetDd7}Fp;_O2{z|zGJY@SK;)ddo%^%{+) z1cfiAK2eD;bXsIW#eU*4R*~J=B;;Nccacad=#~<eVU)b4wBapFndZMDnU-naL7sY5 zWpZiUCYI(bSmY9^p-trTbTaVgZ?rxBqD@a+x7TV7%?X$y6&&gvgxW?Ys+lXrOrWLh zu%`8u%Q~N_xen0nB^#edcEBU?-KM>J=~8hfCnkmg%?OPBm9l<D=4KOF7S!d+o<vSH z?|Z@SNx}ZFo<C`T9#Dj58`I^(#7+pNL4{za0MkO9#WkU@@6kYn`vIx+NVr3+PYWkc z+{O<x@x>K#$GHS0gtL#KhN+D1yktid?}L?#x(v-(zw##nb?370FBcO@^-E?#gr(bB zGo33Bx4jORmmV*tJFh=WEE1q_q+hrdJD2!p+zcx(HwOx@mET@ygidc~>$Wqd_@&^m z<?S>7v?xp{mfx|6T$+p}u;hsd&QJGLY50m&oztoJ88uCY(+~Fy<+5u*Hk*_~9+GVM z2F+&R(raqlq-#HX8V|Rsk+;dx4Rp<|Eu+D6%k*2f`3(>Rtpvwl2MHx-Ic0B-4_=RN zG6rR5XEzr|CquIHjf|%-pW##2W>hnjR?}A-3si&?0cwQ3q*PTvw7q{PC!?#iFB4hl z7_P9gXw1W^zW-RS6&dDI*P?uj$)u_MzAS1Y!E$Ewsi#sC1LX2pj!PHQJPE+JLlV&i zbBS9J?Kxm&YF+N>2;+*CM2(K~+6gomH=X`N^KKM|X=NnJbyYp`L_tH#E6dgO1Ddel zwXXsSGCm?I*zmPg5$H!ZSggAuL46m-FmYc5e1Q&tECSxc+C+t6-<MFKh;ar}XS+dx zI|lQ;=7GB@{WjRs5TF8fGn@w0aH;OZpGxk;y<#J1*kJG>DgBU8Vs%!H|BV`*xTkqG zQkbt=zd@#T=9ezDhsQ&orCL%t<7^~2hr~%9DL&&249HyhZd2r4cqj-z;@itn@@=ed zWm%KjanvyFUfG>U<>~pyrDa99s-UhA)HI``>VE#EOi_f<CF%{Y#8d{t86hVAP5drl zugFZyY|pit`7F|m__>6nI*df7r<bf{`hcFIn12QIhN|h{ST#LG)Pu&Bj%y&tx*@be z$iDKdgU(h2E$cdYGC%hm`Z{nHNptpj%OkhB3pT@7!f;5jbcBh{XS3Rs)h~#FF8b2q zy3^_^mN(_8P#T-SsKQNBq+eMw$+;m=R(f>2b+bvKMo5AHyHsU;lPpjC&jAbi-;m)) zbqzV5VcEF3%GPzWeNMfzAF`KMD=x*f_K~NZwBq~7j}AklgZYc>%B=c9B+9p$m%Gbq z{f{$r>raAd_`(6^au6;{ZPwEM1&==s6rp&8SR8X+4bYQ8WT1*uiQBn<en#7PpLZ{n zj~T5lbqK6gze)m`Di$?@(6G|`=4Wa*-fK5NcA=agb^KD5)?IkM#3slc{mz7GQ3hQ4 zAVs%VMesf(k?)4#0KkD4v5&AVcV0@ZlSxIv@d)3WNSrx2lQt0!>6w$~49>PnDlz<b z!c&!@TW$cF?W@#w70V1T6d04u{5#GnT%@))o=T!dFFeh<-cZopFIC^`kZs>mYsTD1 zw4^Ljrs@<;@1hneudt_D*8>$79Z!c{V6HMCTXp)Cb*)M4A?mP`_Rg6oEhaCsIYr?o z`-<~eI3KN^Wv=bVvt5iv#puZ^;lbv~KIsY*f4QpN6n*o`tO)(MP?egecGFN$RU?R1 zz&O!wnrut8?zqwP#6%22+BG%BL#AV($>Qa@+&bd942~Ocp=-(C{&rfK;TD_WBBOmi z&L}jVnn`J^QQZit5**PW(O?o7m=d8I_xPPktib}@nQ&N^9Y;HiN_8bp%WA?(xuSB% z=%rV;7-j9S%4m0#E>2A)(YY=g5U&@XL}%V(G6yGkd}#aS<<c|!iHTD|tU=p~8}xUO z#I3;;0INi{MD>8m^2!;RkmRHREB1vF;TNqF$llpqPvt?6TnElRoC>AuL@@H)IMzC@ zA_D~FpU}Eq*O8)(ay9P_A+RzfPuRvGiW`J&TI;^cB@1GOtVj?NDPdE^J9VhKsv5HO zX-x55Q17N>c-jAjq8#$9M8nDtHwanj?r+5W^A-_4RrQyw17|qME52a}i5qiDLlsx6 z^MadzY$IpyyBKR}6$)|ABnC|_l{A0Vnu4A}&B|n^V17vM!M{drFM7tcb|Wk0U|ylR z7y`3KVH*gyeVh7RG)VQJdZKI97Mb5#G-kSaWS=aG91~t;nJZFv27h$xUm%OX5o{LR z>OKEAB8m2#VtVR@row;yAzz-eR8lC>oLk+lRsw4(YU*larDt3dzc%GytHSIHDNr%0 zFk?wAYL3^U=YU*sV7weO)}iFH$B_xdn~6||OE15aHqDPfj?!N4nWJ-Wh{)#54aPhb zUb_(mP^A3f%Uvb%2ZEG5q}qhd$DFXcjz|n%F_~~^@p44Cxd2Jgy>*iQ7)=#2FZ1E& zJE2(Z?89UM0Gupt3+0n~PCBCIOO2H8GphsYKe(tSZ#mY%J1F>d0!YlGCkwFE*>c4i z=}@Lt;R|z$Uh<lNz}Wc&ZOBjQ3x}uskIbzXz3Xu;Hamm$Dj=H(4y<o@ywSL;S<$V5 z<)${KQNWht9P%P72S`cbfIjRdB{!JzS8>RB#9Vb2T9H^NNz!3fBfhv5d=B|P8x#%e zTBP)7bBjK1b(1ivs0(QEQL|Z%?8H161|7K(XR=ZwJ60@04nl%5;65NKzLBn7ej>Mu zLlY8HiptPamt6A;NAXBv9iWs7fPrh6+UTbweLkO$zf+6!iUrY`-DDa@ZGvZROWhN3 z9ux%~Z}20cN!v79#U#DB=^a#>F%??%t4;<M?wTjraKjLaD$d73$Q%U5Cu#iI2N+6| z&4F}_q|)xvXq?y>7?cxqg4BG0Hf$j2Nl+%AXLK+U#!^hxK*9JQv1BI<th|(X{!B*A z?CN9<LUvFlKz;~|@n^NUiwmNAZOROOacr1-(a%KQ!x*7hJU1OJY5;#FVS=kLk&x78 z9FRrAUG3*)^ttSZa7bBp#ZTHa;+Up(8hjLK_ywG#=${V*$>Q;CfwSNdBYi~%jM4Zu zjq!%=$;s`F`cO_Qf;C0DIr}#a<lkVq>4V?4@7IC`SG((;5v&ST*k7b+J9O=++`dfg z1h4~tC?$Tw)g_1K&W8u*1Hs;lzb}3XfVruaPGehtIY3oJypO?Gf~sZQe^$Re`LyqR z0eMqhqCdO6@e3vYEm#DQmR2(m#2LXTqN~a3{OE^eB6UrF41mOe6c3CnOt~N!Gu??Y z(4omusMIF)zSBZ0siIc_QL_qL+1%re4o_+pv~_+iz<)5)U5qAvnlTSmPGqJeMgTR( zdl-vRr*`I3YpOqx(@N#uRggcMbV7q?LVCgqwbr4~Su$$xQ>65fU+8)5NE&rSVfHbN zPp}24PZ7o^2c-oKId8}f9S~7aZF%e~*&4dYA)2w4<|>RagXiG4S=wKPs5H?{uU$%n z=HlGLqNn|Snor>eR6!SzVf=DVsJJ4a=rZzNzDyr$Gp`wFZDVg_hc2&+6Y_&RS5DW3 z8A{EV|IkYl)0rqdZ{_=z>ofO@^HC+yX(g%*U8?(SZyMdxmq;+z_)qJYy_PpZ`}RLq z`atj_H-%Dho3MMY;4?EIAoWy;*q~SD+4kb9*L#JezE`M1PrZ~3FOtY6qhszT?rAfa zn!`ZZN&eSL26tS6G7Mm5j$zJLA6pwJAsz_Uj)}>5j3?^f|630wZwj6f1h`Fwd8#tw zwxpztS2>p<050@imfl0D3lq22S?8O!HA3Sv=|B_0G8G!+ATmKz7<&0QRl$7_=v+(Z zqZA{5(GRds&`cEnUZo2!W<uMjo}huep}fMdpuNs085<>Mjv|m}8Wzm2ZW!r6AkY=% zT^qhnTP(Q2GN_FnkcQ6M-d~q%;4IVLC~j09=kl|qfZv$C>mS)YZcJ12tE{B38X_tE z#yeuzjk6$y#mP9yHP)_8cB6%I2=iy;sZI!_qA%n8ACn|YkAkt$IN$mtB!!mSTDJ}E z@9;PABkoMMjW;L8Nw|1UT;SpAN7eVzFl)H<Xmm<R@3aX88Vb9%YRuDx+7HIJmb=Js zotF1{xOqoK7H!9Q*Z-VR3pGDAq{%ByKHZGZm=LcE26k=kb4cC=-ue|2WO7&TB4<>w zr4bOZc<Mh^HTM-!+SH7f`D~h<&X5-0Qf9FfZ(bsc%jNh@=U+^QFIm%z4}LxvlKAAQ z0KKU&`523JRZUJ73Ybu;Ly*6m%H=@ZP#P8k(@7QzwCiMH7hhGOiT)|S7^e*Quf+dg zclQqKaccP$xkxG4j5}fPNwpDHs)%1eCS4Uf$!&(mt4C;;H6N$?7rj7<vVGxng3SyM z_C)pZbQFoys8Acj$^_HSi^l2b{zy+e1i66ZyJydl>k~vmbWx4|xB3TuCz`24wU@pe zqeqxDj+R&-zE^NU``XnyHtHI*8RjG9H(`>VyM^n!qq35Jc6fU&zWaZxIK`O-jrE}K z_z5}xIjM9X*7zu;KfLRP9u5}5^ZQSIV`6%(5O&nZFVb-87dy1?jYR}wG8$9LR^Rwe z4@p1`jkG0Z<^{5gJ4>o;?q4G3Da!yZ*e^Odg6TQrdd2UeOw0p^L|Z<53t}c&p}EcD zp>NgtVqNxhLB_ASbcBiWGp`du=VP+k%|rDqW?_lg%~cqSB@Fx0sU&;Ib}DzNKjJDi zmsv-pgq<lU*#lUa7R2DZ2U}IdZ?)=<v9q~KfunddKAa12iX3IYJ05RZfms=U)36I^ z3W8*zk)#k^3S|(vmxEY3X>$`@TDH5=mU22&Wl}wmi8=Mlo+?Y<Ijv-MSnZhPbz^(C zqeWa9N>n$^)OL<dCAX%k{or4oBdh;-p~rxgCw*dKA@_4#x}3qd`}i{8&5$ynGan`6 z0>m+|ayiGgKymBDslMqWIVs5V33jb!AgZ%!lj_YHGrImX^Oht>yvqpEeg98Y4ko=4 zzBw*Y#$K=n!-2wUsR!4-q9%pel?!k5b<TSIY`-p@gAG$dODDP3SYB6dq-Sv2Kw;n- z;Rw<8Sk5O=onO=J+BHxdi~)m<RM*_#&N?>f-K=3e=vyl40;cbQMFub9%~#)6e<~LI zg(5O_R&%2tOH`zt!}3gwFA$UK)!ZYG_CglezVcd{rW#j8#_lH^(<M;tiW_~rvAD7r z9P+->uuKx*9$^nzTj=VYP>+>L%~zU|N6@c3EGF&tu^ba+TL1FsJ4~<#&C4Z%!1-@l z;XRid(Q(lC0SOlm)E2l)hhBd-MhDkn6x@e(fr~ETmiz338BN%AK^=~ZX^4hNm}|Bx zsJjn<L~_x6C#}K5vopVTHk^0^l2yJI-(PIDGi3!&t#u(G^#+cL?_#t29S744!z>_2 zSM}a-8W?05=ap&x;nc0Bx^8^+rUZIkEeHXa#6;vDgR!xsY2>WzV>o$N;egH8;29Be z%vv&$!c@ox%olNfGxOfBr4ygH6sQoyo^pJW+)c(OTHF;?<+zd(49DpaqWls2?+O7Z zDZgT)(N8J=(ou<Sp52DDjR%X9SFC76^-^?4d_)KDp^Xkp)9wxhjzk*DWHzf~$h(d2 zYwat0LOpXi!c5Rv6yw2$`7Vdk^MI<^q#z?is<5Jv<Q`CcS_)i67?L4FnBe5GNSgKw zRd~}$TcJFoS5kHYQF_)BO-MF3e#n*?Vnj8_VA$CcTFp2Jv8KC&)Eov@$Y2U)36hfh z8MFr`s@|eSQxu+7{~&JOgdTe^4Tt7vlc`d&%8v*q@`r`#3*USkO+J$Tr%oVg77f6! zT=^fWHP}&Y@RJAJ5{Eih^#zW?6KeU!-KHm3E#1+gMA-3ye8#ha>H}l(O=!^l2No%* z-Q*Hd=YPL6-pQ=y8G0;7k*ttOKi$0imGJ`SIB;Jd**&M^1PlFy(sg=4luw8R^I{@V zauB#ktpc#+6I{cxCD)Z|`vDVl)wF$%ltSW@WeTAq!3o1Zhk6*dRFXU`_~}ex-3O;z zn}@oJD#d8T=#zAS$FjHM7e^_m&j~TJ*%)g4_J3O<DV<9G#xZUy@ABolzTLI>JUH^W z^L%>0+;`kYp(_5{#n|n(_PH+JPQ!FhaL@rteWDZgaG!>PO6l0#?jmC2H*|!Wo1q_j zx(g7R;j42S7q<A}%c*dco-(QZ^}Xp)c*e|+4cyLNnETgwjSq<m9#Oi|aNJmx%*yLc zS1)pI=!<Nlfi0Kd`BS+Pn^Yx4Lg7TLd^x>J)W1;~UDBK_p6jh#CV5=YcJWl*QZ$U3 zlu3xfJ|HZ0n;<YYe!@S^tEjJ1!e7@V5*cQjiQeQy_1^xDcF3)Io1@>3H9pCi8sED_ zQW8fTIe|&2nnr>tuIArZ@@@!lmGVQE-m)KGix@tq^7O|swtElK$_F~`_vJz$$9s(s zMUprqu#aLoH70Ek#TpI2ua?Y*nho33t??iu^6us*EZ@WSVgizPQ-Q)EZljb8iwK|v z5Dh3P9;K^F^fxrkx*~NBkn1CCDY3g)S1K1icc_HIr&(6u$|Ns%!?e0tpu&JHlubXR z#H478g+HNAbD^;(?rX;}QkHMYs_yCtGlwievk;TMGryC0sFn_0sdjiM+L`{_05-L> zL0CR5C<FF?ps|O78O!<LPw;F?7<G20?BAPb*cK^Cqqxg}>(kEMU)Md?NSrNIN**I! z)5pO)2?8nXQef*NSR{WhmIq$hn#0_iq>1sX`ISoeLv!J3L(P0p#vUo7EE>)ijHBm` zOIdY`OAU~_B(Q0_|4k?Lld-#zML7mUHJV4t%&3Y$_mXa*?rSkHm^aw-0MgHm<2Tk@ zO<WYR?Bb}@VKy)<OZrDp8d{?1Qxs#-0X=b=9*U;XK7Es<I9e;V$8{qiPOU!6Exk@- zkd}AwnOm!7?im8#aycGeE$cnA1X#&uX!wEq*VeYbJs3NptB_giSA+w+9e?Dd>`oHa zbCL>YUYz$#Z&++|^A2<7KRoz%80_jv(QHW4#FKQ-+)57-uT_>kR7B+V2z`S7HJTr% zL)CrZ$4Q%eMgkztauGTCp2n;A#hfADF6o(fRhj3h(*G#b{T}X163TTYZ9eIQy>Tsr zpYsNw6xXNQBHIs%^=;A!R6#DqJr^W-P9;lcY3$crBHq9jEPLmw_1F;Nc6i-;YDr9D zTE)GV5%C9Cv&kV8=O!*Nk##VcQ6_v`=v+={IW9L@CTX=$Wme;&V^Se450^S2e&i_x z>Aw(#O0ZdJj<hBwmd=xg%{(Or;vywdu3dm=CwkV2#q5r8u_28^zV+7Q`=GTlDyL8y z{NP|$98)9~DU(j=TFO_1#<#+46-q`9*}-yZeND(FjXg)J;G~g4<3Zc%qD2jZ&X_Lm z#xl<@9JKKSeUMf*C-9!)_7J4Iurf*IjzHH`MNM@W-=MB?9Q<&HLEIPJ3(}u#35v`D z8tMVXm}kaq6jEJXqbq>^o#x5w{{&k9@AAhXlx#uzLCLcCu*3+E8@Xz;#B+?Q!?8tM zh_<P$S{m(sD4Y?r_=1&6G=7{E4A?v(2(i5vGdMv<yt$Ff0+cz>9e-qzG<m71ufLgW z2b2S!fM8wA>*Um5oB0M7l~IY?AZa-diq!>kk3TfVI%fBI`{4w^4-hBl$T%<skisaA zRahrUJUX&ky^)%#5H1)k>?+NqC+Iqh4Kh0)E8`_g1~zWCb9z=E>>YDUi|D=e|1L4D zx#-+&#sWWtOkeII-GmU9fWT~h`Yk*}3E}j|58cu8e%?pflUQ1*oZ+C|oAbbSt@v!o zo$eG@9<~XduMeWyL#-vaNM@L&MXdZDM*emIiN~=Gd-Pg_z{eE0Uky6lxoz$({OG0_ zcNQN<L#i86CF+Q{zCjmrCSiB?p)|N<>VFKNe*aE^{5yBqVIi`eh}l%n=5$v>Ic!8s z@^LdXz?<O{AiTwMQE8ao)+kvVZ7*p3A?tx6uSkb5KxtTUC$r;6kz#`)h7Yxee_Y=C zHK0!>5=E%aeJY>~cS4fF0z5MU`HgZ$q?9*Uh%~8BV^lC7_z~n-!2fFl)f>Z5x{b_C zl}5A9o~MC3j6|ZUC<YcG>)F6BGV6+_Px|Lt4m<Cfk;$_39yP)`BHQ<A3FJl8DjcGf z8DY-5d*oY3bOizAa=rr9Zzpg#dQ8(C;1j>;Of-BC>kXtvhGA8OGb}1lklv$QSi>N& zs)Um(lSvrwyVx|hPtR9^VitaWi>%E}NwUBfGVPY(ZgU$qRcoFih&ZEeCs2GTVA`6f z6ru0-OqKfl=4TUP<fwD-{}jMxrvPNI$CeQIN1XVWIGi!|Gb8kGN8AoH(J$qR)BYD6 z$DH9W(9VK3Nkf!~3*-|KE%GWGuQVQ)N!V<;Y@*ufDlxo^`~xRjTwG2O5Nszr{)C3e zqwF6^Bw|n{eBeCM2gDQ3fpYGmgtCMYsDGq2xs3=+r0TS?uBsgG^9>G$Q*8Fhhj&5B zL0i<PpGtoq%e$Cn>q}3!Lb&32Q~$<wmkBGUuw@NL!XiuWn3&8*)$S@*aTYHGRpR@5 z2-6rxaFYmn%)n&&S75IPV`l!AdpH(*4l1%-Nc|-MS2CkEzEbxIhes%)_dyj$?UQmZ z>p!c3(bVe;(udb<k$?6@(jwif7Z=JR!P1=P9Y4*pU=BPDYx%ohCi1g9h){qH{il70 z?J;}Sj@J<Ve<Mojv&O>h1Bkm$yl%F8u%USB&bq98=DhTLl(Q<gR~>ewQx*g=xY4tw zZ-hOWzxO80g&uWm1_(3Il^f+!n}eT_#KQt4@+P~$MHqa}N=wwx_{Q9j`=9RXjT+%< za6RKUc<#)2^4#Njp}~o)pPxS<i0xG9sBF>;7L1~PyZw1re&=1roieDtEX{7bZq9C8 zOL`w?`GCiVNh`XG+?fM(2K6c-VD=Vxl8Y^Xob5^_Wi>I~0epl6>K63|CToXhd#Vlf zEQr^c#1HGg{eFmvOVY;NF17P9a9LFsje$~CQSF{<VuYA2?Q-P#&>(uBaOoNg4pcQX zq~Q{1=U11l%j@^(+t1~_6EqsP*U+tQJJ0`_W}D-S;P+czh`J%rItYIRquCHR{Sa1L zzzdH;PwHJYx5yb)&`4SV61Xw{SMmOTO`ot(by7$z#1O-n5{Iax?)hWKrJfFN`SwY! z_dfO>^h$b?YutQ20Tl%vYZ*}Z6I{};<r1n33a4=>dBvv`Qj0e<B#r}u32<w|%*i6g zEcC)i@8E|sq^1sGm2<{-IZ8=?$w()#T^_uHLaV*yW#dgS#aVun*05&Ob77^#;U!K{ z=-CX=!Qt%|Y`MIe0~3<i3%qH|nNh|)aIqbhL}-N`{LH?_dcu_$C9=lf>m0Xl)QxZu zpm^b2A8jIis%#!eEKHBwc##(RkRvJAtdnY5+F>?bi;io^CR)=m#fKSAu)T1v3x+Dy zHQW<BJNEN31*jESp9(stk1R?RUEH~E_hgum-pjpEedu3B_(Sm|ICk8>ybQ!`zVdMG zxTx=YNqDmk-0h_hcckzdNJnjaXZ6<`iQqHJeGSW+?dmh0N-DC%VH|Q)_VTy<KLGVW z3cuj{LmgACTV#n^Wr|v7nzha{MroC0);P~Xy^Jym8GAsAz>*%kLii0K3e_vlScbvg zM#u!)b5nyJktyC}|8DA$a1NG~$U|nsk?|Xr1`*07<3`o=h=xzO4)w_1Nkfp)BXSWr zkc{pS5>riRC=HVRL<Mi4LQdHv$mtXbN&$>W=ToJ%LWR9j`9Xexqkh_jcAsyy`E<Ya z=Q}OFU+D4v!h)!W<}Tq2rXHQM?%tr#lpbLpPKLntO}F{n7TVgHWK9@(A5vl$6R@BK zpDj~_lTg=R1#e=x5oJgUjEW{#*pw%1ucjVgMZV44QpgqXxw=9f6h7ON#1?N-?1}s+ z<YZTOA(yAm;dRvDxJpEW879=+NIujqds{<AW%aOb_)U*$4_TnU4Akm3J*p3W)1%tp zf0-V!)~(w3U;~WxjipC;1z+7TJ@TO(Y<;=xr$y=nWJ1Uc*l#(}Q!-5(FKV##2qVE@ zF>r4y5w`lQHLNp!fgb${7|36rV4aH>dSLx<xj!%L{|V%M`Y%!wG*NgYy+<@;_CWgE z*sT!ILC!JH@Odec7NraOlP3GH^cg0?<Y4l~TRS>zpMKbVPUxrI?%%CWy}P^r`whEv z6UVIeQPAld^!N&U0-(z>kGXz%{mz9Q@XDLC^Zt(TvYF3Hho(Z8B4}9#1G8XveC1C2 zXv<BHtTzPr?|u2;J=hiuyM5sH6&Rv(aahYs<EOZdun1%RxIFePOnnJsj)d<F$(Z&f zYe-J!sMOrGiRD|(lXgyjY&JFYc`)2~4Ne&qPTvZ=-WBHr6_3!I!f&@^i^R*rB*@>; z{hZysW5@3uKXB)g?SqHr?&tSkGxa;ZD%N7{Q}dNkh8v>HHbk0kj540`(nvR-d~$>p zOO|bjm8&F*6=dT8cKMrx-98cd1paEI2<A+gB~xLgSS2CdE#+opp*!)#-dSm(K(=$- zr%<t1h3)uZDG0I|GluLHWX;awL0*E4$5fH-N`S<Re393jOqN0(LncAvMG2W*PG&>n z{YY-`W>kjKoqg>7law=&S=Gv5!<3T_Ay#2i1t3!WH5HaBRnVkapsI=$=1e)d*$pbe zLK!TT%4}4N&Z!jLQZBmH?6d2_$4>|CbZ#>7T7wx^m%F{PkIj@=M23p;uC?(q@8Pj0 z2F3)wycAlzW!(ua%~qOPdP)k4Dhgy?5fxIB*l#1!x=#x-o)hCh%`Ck{?_~Rp@Kk|t z7bR^CPG@BmKZ!U*WYV8u47h4!1Wmv$(j*<I^mDed*Q7r)B+Vu~UUwyBSFu$)4Q>Yw zHD603EXFK7!dQqt)$!IDzi1F@;{V6=h^9*x=r04c`lm7qL2cl#<2OC3Cw|i-j1Mg! z>y&XL1YRK<NGlLK<tr9-VjE))ht8F$EztJSIXyM$5$!#a(IW*#PBlHkh|or}k=G6X z6g@)xBTtaxKhmRG0+S}AN7cXw;V-hLPlP-yw2&;F)uG#Xilvy7_!IJ{ggtiIORrjX z*}Lya&WM;Vs~#kqU;1?MUg3VHH2pDGw#7l0@6a_Fj02(Fa`%yuxl^Ok)Z46GwbI$z zwP;gh>5MOxBQi?HWE9W+m~Zwp@9?>VS^O1q6xR)EyT9?!^UTES3Zrh%9~r*AXRx<5 z+`k0YUa;s1^!X0`Kb7}6;=Aoh(V%aIor@|5q(iGauR0orow^5;y86V1!qH4HEC;jV zk`o!_eWsXlx~^W6RNnWj&qI$_Nsm7~diL>Q?59M(;&rX|+#Y^mtIpEX2hW>av0ryv zw8~4o*u!v%@6LrD8>dA4(d~<I^E|T_*=8*=Oj>4|x6Za~m1fpHTWpYK+&WX#CC$3y zH>=j^mMt?)TjlN3&oF9}d!Tv7A%m>L2AN0oGmhwI9M%7Jq-n-s-F!RkBCCeQQmtHb ztwO18o}@*lv}J~*QI1v9+(WIupJ<zLreV%;wY-B$RR@(y9kkMqH_Se*R&+$I%z;~M zr<d>0DD6m#oYQ(aM;jF!ZJc(XQNdxQ@`FtIeqo7~pirV*Zl_pvP@!r+Q(~)8>cGo! zXq<IaJL5Q#8|9Kqf}$(B-_LgXa<SKkbG_c4>-Fhet1l-S<(^V4JgHc5hRHvvn}4xI z%9(zjt`2^6z5mPW-IK4h_<li{dq%zR8WZiP1Mzy0I56+?pxtig&cn$I(5dg^gU8_h zEjX~}-LVxfth)s4>hE{b7p6LdxW!a(_&qeZO>}e{$v%vO97K`KU?X(oPxOdzAbNw` z%#x8@+4bs%nY}}w&+o@DVHPG47RHnw5$Yq*qx6V=-IguRKj;y;0WS)KE%}1JqzhTv zjC^2+?{6g=T$AgAF~|&*OpDs$AE|&8zk82r3DoL0J*p3W)1%tpf0-Vk4U**`{v*RT zGJ{CQ`q808`XMMi(!wTRqi*yFK?kkS8vYnL`qL~QvXM_aG>%f*dsH9%7ttg3+3?wo zG&{?h5E;-;Vg}-CH~xfA3V-sDiiR^x?#dgxy6%~qnANnPynP0Yc?X+9N|v8Y*?kL` zxxOP`!Q@xacB%j7yU^!V@rc;ep*<y*Gh7e3R@%maT~N-*U8hFxK00xieV-ZYdh3tb z%1pOzZ`@~w#o}i<JwL+CmvHkcY;ONxQ`h^$dtWdNg?Z0maRLlH7P`_Z$j&Ec!JE?A zA7H}KH*I(LPWb>U;$UXiSF>72AO8X-Ic3*A=eJm}of*D%!Rx9aUkeSK{f|cG+=wr= z_*!h63J=3zeD{MDFTi2#CCdfp&s=`FFY(*dPZ6EJ9Br9y)-Frh<Gtzlu&r~v*U$Cd zve0MSLf<X(z1J`F-8kP5Wz&|&ruS1lEWE6DMp&$k-n%ZwXmzC7vIyH{v8NZtT$vN? zJSW;?R+!hK(15wIZlhnF?fuGT$a}k?pO1F^bZXFhr{zzNt_(dgEB@xRD3`VVzRUf5 z$0Y@{Npa)k-qFc)9sTUdh`3mtRCi8+bMsHv2EVyKKQ>@Sq<7yJ_xioNHR;Lq;fdGu zGHwd<E_MBMqHD@A-Ruj>xmPsuZ)@j1F!*w>?>nz)Pl9HBe%&zlrFQw3?io4rUlvX= zdvxPop6mV6k#iglzs&96`k;BqJAT#scIDrg)93d^=5!t+n$X$SXr9N4RnFra+*R&h zXM%4usmg2!xtfsPKfAc^_MpSpVbddMG$nX$$B39qFm_*H7e}8_4?irwkvnsO-;TK< zp23xjc1NyuGqhKP>yYjrQjFLG`^Q#%Je6G`T!^^H*FD)Qs>*6;H0Ya*5<)>yjZx57 zQXYcz$ixuoQ9oo$Tw+w|))nlqGLPNbqk0u5JI+ogXd{|&I7qFK9yL|dXwKyYNG-7# z6Y5Xt5j((*{|Jaeb-+JT0V#gdqgn#B`c04OgWvS1Hu&GCN30oQO%I!w)G|^RnohJ+ zei9KK%F$4(vsUB<k$rI_UF$N2M6Oil6`@BMxSvE!<{s4x|DE&*3F{Af#9qf!%*h~; zn0|uok)3T<hKb*Pds*MT>!ORhq=TRc8m5*lcwRZ<%9n+1z|8kz7JKgqgfTP14qk^z zfq5$e(r30aJiozz`k@$R&?ct;YUMtQnC_D=MkL<~dK2mV&bHx>{Vl{U&e_}J3fpB> z_WTT8Cf=CU`}WNn&}Q5P&h)dUAz<$c){Ytbb_9!0zTOmHwe1^p-yOUq8jze#cn>q% ze_G!><-&V7kPr9Y6fgtk&iGi~GadS6mN&i|D2XXOmjvc1AbJN)hn;%&7BXLg)#ke) zcj3s@+%=E0hkZ^G<Q`|hLb1xKX|8zM3$u06CL3Z!8)7XsL>sS*+PyBua8vl+eSu=j z%c6_>Pu#IRfAYw&L+2c%7c50L#QUz<oDO;5<m-OHFLa~CvGbsXz5A{mHv5lQfDp)y zgzv$S`UpzKoHH9ZZ_J}W-}!sY7H)O;W5MN(EAO6q0nCbx12dDmeR|KVv1Qg<wJQ74 zv^ZhH=NC$wjT$VJ=q|Hb@+Nsi%;WhXK{FovPW~J>DJ62#ix6hVvI#}+dO%8Rc-I>~ zGwYVEeEQkKHxJq5uoUR{4Mx6&&bHC(x5kPW#cUY-AjTD3LSf9cr){!IG|DTQWR*>R z2`Akk`UGT3AxjDi4bJ)`z}$Dxv9PLfS(Od|ABy{=!GJ$vt?s~-2w3a~3p&RvXz4w| z%)ikU&lYhX`+27i8t%4ooR5=7D$}f^s$LU;fQP(;yriH3kg*T8AhBeKEl@1b7O-^! zPgNBOl~N`vB4r=pr#GQ}X{D?>kYQpi%p%Rn;2P2+_KirF-S|{Sj~eg=@=Y!fGJ2$~ z)mTHLFZ+2%<VGzxJby8<HtbA989l<k-}LCOK)?SD^yt?gB8Kpr9@P{7<@AU(hd<~M z9%RM{Uk=$TXs3Ln7HF`v7>38G^V}m!hP2ocPB&nrSE~1?R>bhJrS})J^oU%kGyaR{ z5eq_C#n#nL$Pdv}Ap2B>Scow{AJ|ywk{i^Z40i6iJ9vnbu?P8-Y@0k-_@r#itq;AP zRt|~=!Gy<mF2UB`p+UBA)d@!RmG17n)o_i&+{C>8MKCI-e0+Mr#LS|_9|~-vOAZ}) zwWGrs$JY0cHSzdk){_w*pnWO`7hIEi!mK1%lms0{TwFfb>&Y=N86J9IU9_#^$Envp zsviv;`UyH`Lc>xRn+S8;ec#eF<@z%?lmSei`8#4#hh<f^&#oGs0$t99JA_xbJptDc zXy4Dd(}?3AKL9)di&@SW0%4nX`Uc<k%Tf{><s&^ZWhyPz%S4Uy#m%!t`k5B`>833+ z_qEA2X_aNx|Fi9)NJq~%A2K{)UyC!_n;t*4+|TQF{MX##FNJwW9go~|IOA#V7;Szu ze%Gm&8y`g&dY(CWwipVaDg&z0N+C~VVQD^N6Fg2!yAoS?@{>=`;Ol*(JukxqBX4Ht zUS^$RpKs8r2sowrZE_1%#+T|ZI%5+6t+zZ}^$g~|t(f^Xe@5`@9WKwTu0CJ5>e?cU z$C{Q827a#U1kkg%Wa+a)y~)SU+<=pJVMhQgiG_JdF#OK5wPzD&?eZM4$?ZZkT#tp( z7h_tal_)_Kr=oJuXE^u>W_5I3-zIpD{@n+6!1*)GPlSGH(7XZ!Rpr`HIUoc2ZHckC z5B;9O$apw$8WwbOTemT6*|9`s-I<Y|d7bw~ng@YlSTfV5J=3I-rk)nkBU0hyMTl4e z))df-vLn4pw%1aT(IGO~h;SEW@|9+ChV)3CJB(3_GPZ~@wHVAWE!DY5gD5@XYm>n> z9rj~_wCjj=BqKLMv!KBjG!yU#E07hJO;yxd^MwHtN#`F6HAw8g>CxW;{r;v$wE>3k zn;z8@zv&SxGGN?jiP+vFG?e5z+9_WvOKf+sRp#-K*|2kn>VTi=5glApLVAS3E6C_k zfJjQZ)9dvx|EuT`<`8C-kHoqiMnTW%<6~E@;bRK55cyeHwnBSHE@~_=J#qTxmvx;l ztX>i}=tHG`M!~|^qG8Ujo4m<r7hl<ET;Q~h;d?uU?dj$@qVM@3eZ|}RZ}7MkyX0x% zz&z-i2c7cETUS;M&W3$)&~4KBfg`U6I)Q_JxWoA5O@U-^jlb~P<|t^D3cWwVxreZ& zwd<AsDX01*&TMw{sPwC`ZRQ_g&?Oys0Ng4Vo&voFBu(p-@E`%0;k%e2TQ)u|o%9jL zrNGh`&|$};+Ycey6-IY{)Vu4ACuxxQ71j(rym^VU(Q{b+p?Gu9%h?g`4KofgWLZ0% z_$*>qa!JrZK3`8}H;Wr)*-eYT@aR=;)@?Y@AW*{hc`bqBWXQ^a{8WGxfTYswW8UE4 zY07jzrnKmKH=7TqU){90;cR>QrtR^|wwJEk-o7Kc?_z$>*W%8TEgoPB!R>?AXj|@E z<8kmt!H%%XF`r7?re}4@%b%27AoeTmH|5k3A7DCd?QiC@IUdG-teW$te3r3`Xrtee z#nHQ_hMjRG)7V!=!Nv%%dk8}Y+?w4rXj1#2o&()mj=yQ_n!n=mvz3?PMp(EVdj^hi za6SgcU5RU(RmHD>RvBfJUV&9GT)hv2`+8ZJ7wxcqHUCIFv+}~|56~eSS`|R=Y?$)` zMsIp9xd}7lU`k}6)y+~DC$OCtZe{qU-CoZTewh<IGB!jP^mRDPv}mEKt=WX9K?h+` zu;g%9K?l}HEMO?~BH9i$1r<tA&@7PRhD-_R5td2Pl|-&8DKgDfHTpA5jF~vvR5XZD zM0%tnKqe%kM?$jE7cl}XH<HmKGWQ7Uhpt{@E@uE*0I{eIkJns->noCAF_xEYJYYPm zMXIxX_(v)r#cz64OQ2T&EIpEi`)l}3kLrov^oX{v7%LUl2;vpAe5CfFp(KM}))KUv zYU-#}-RM!x!8Nk7m)$`dFDk0560@o(8(gC^W@Praj`(k*NBAH-t;kwJbkJEKm~Z%` z@Dy`0%+lP;TGB|?z-TWsynORoUZQQ;5tDaAK2{jymduaK8}=Zf+55Eiugf;Nz~BLX zt9yp5U6{By8dg0knKsgJX2<Q0F3@go<k}Z7`8#wkhoM<j<}uJ{-i6tTurM0>j=Sf3 z2{tW!clj!e-xRSf3fgBuk5sVqgn*N9r0w(d%vGb&k+=7h-W>e-iZM+102~0N^76Jh zup}OIXZzkxf&tq?c0|D+v0xSe5`QoXhDqx~lTX0TM)!tyI31S?zPa$Y1m^ELb@WNz z?9{T!S;Z^DpUjJKX_9dSIS}1-nyl@rLRMsgf>)HQ$d}rhX4}t<zxd!;`u5J(9}G@0 z<2yTy^+`>GPk8`uAkiuL&4o7~Pb8Kc`}Ae+lY*n)4)t+#=yxyfB;0aNL;AGeE^*ev zOCF!#UV7EN)YACZ<*|Qwq^|b-xYhIVt_L@4-K3`;F1>PRuB*$=*eAA+pWnOldd@iG zOTMp9dnL`7X5ko+HtJLH;BS@t!b+~5$$Dy0e7SGPv3{|qhP=DjEBVr(PtP1+nZbjt zI)Q&Q@$<5+ba%*xXz+9@+HvgpBs2e6>q77O!_8<Ic_pf4W(nrl#_;m}k6}kNEDZ$p zMfVmQ&Rn!DZjsT`z6YK&%TG-F29sXH?l2g)`T4vh38&73{p~WRu*x?8g@y3mqVmT2 z<feOX_YMCz!}aaOuP{mCAU${bu7iWOg(z5R<!>qSv6T8**&-vs!h<g=RM3rAS}=?r zTg)`rek0nUEGvarch%V5C!`Gwqpz;yBQ+btvh#k7a&rwH(j!eF(j#rMs$W|+HJjx| za(aZ8L|a41M|u<_kq*J=)YV%Fgq|X42R2d~50(1iAE|&8zv)pefm;2hNA<yPdQ=<y zAE!qwC_PgCL60ONY;M(gWP7(dfzl)NMTDhRbYZ`o9^o4*yEnHr{gA5cHL))EucSv} zq(}H@kQ*tpqYs#GIt<eb+b0tveYQ(LgWRrt)GcL~C?@o9*|b6DmPEmzw=g}iq_by2 z%a>`r<BK-kg=wQ7k7q7DI0KVj!N|8I7hJ!N=)T9^75eUeK44Syt|u@k7sh75@c?K& z^Fpt0&^8lR$3VYnE=E%lS9EnZ-1pu*7{<Pap>IKRmwTTDUaLnu8LNI}*Tm<yHkID* z`_Xi8^y+Bnm0UIDJ<N`Sm9enP7aFubbKxF{gP_Cis3F^8M{JE6yfb*-BLCA}A}@Ce z&wc^n>EKrZZsoxAon-VfYeat8z_Q{A@!=z$-)fL|lp%XYSJNZXheU+#{is|eZjyd* z&eOY(p5^WCa`wT{r%`LNARcnRK}H5dU;h5|^mq6O@D4Ih6udNh3m*W*y5B?7fqt%+ zV9}Dt4wBNT^F6Pp!iiisUjQDTs&3l3T%K$9WSeur*`zl&pWnLXe>gbSJT`vboqL<F zK012H_wXT~_19cB-*9m};3_)iweUmw<m4Pf*OXh1$*=c)$@?P%&OtzrsF;><5$)n{ z_X;)By_~WOUhab+`(%iN<9)74huk){PaI|HyTLJi!rCC0AXx91xG272L43ubK(Gsh zu}|`PJkOi)5(ZxTYUl?e&Etn#Ck#4}$jm%u77dP`Fn4Lh>LpJuoP|67aPo11X+&Z& zK!UV#|HSCFyIe>3e_nR)!|e|++ss~FSGR+z+F%8;iD=hqR^%tP^%GnBi){Tx*8XC# zpG52<k$PBJ-?y`Ei0uJe*sxH^k0@vmuqaY@XH_Q5%y1%k&k=Q2R%yy5^oS0nu}k`8 zOFHBuYjS#ocQxa4d@L-6GK_(Sx;~fdBPAcq!H}`2|9D@L{i_@PkqSuhn;z8?sMUWj zJ^GcDBd4JS0(HgU&|SZhfg#B05k);pi98`xD;g}>2ESgQX~Cc{*!pGBPri_}VJ=a{ z>I(ElpC3K`rzW4$Ba(qc1N<ZZ@RZOabP?OfFhN#UXbn|)oVwB@3ThCslxkJ)dqf7; zRLECpk-If!7*`wHCae{%2R)I~BLsESBj2dUpJw^g<59|sBGMxavwlyI0!t%(l=uYY znxF$)4nHd?9qyzH5Aivn-VGRLFvG-{?8W@VY$Oj)S#zKFyZOhTj+}P;>?xSP^7TG% z81@c2XH<2I&ztR6+;4{SD2)^DZL?1I%Q1Wm^Pg26^i0tkw`~%#s3)*u(fdV9UQGTB zb3TFZWtcJe^6+HP%Yo5vKx@tI`K$bQE)4Lz3cC!S_gdkux!tvYbbi0M(wTm+`zCa0 zbZ+Ok*h6NiCUz;kR=JH_;BP!AUexC$^01E0FAveYwtLFQMGM~y+48jA;i$I9ACI+; z=-I{g_N34U;{uCcK>T;`E(W&>aEQt>dQ~wzA39YQ4Jd!5pLRpN#9mH`SP_%05i6xg zl~9x`#4XaDW`+3;oNj)0%C%Rk<4=#gkMt=1Y+BUi<bbPhic%pX4@y$u(!5*o7SACA zAPbN%9i8NTw%?0W{gNePUmml}2zU#|7sIWNh1j2nX*Ot^cPxb7%}KbKAAKYD?9I=s z9)FsUlGW#1#)Nmd&6gaP2A5CyR5Ud?z4d~<=e%F8y!~+9rH3aD1bXZXh}q$mu-!Fg zi(A+(uK;5Ya4E3U-RhvV=gP42FHe7QyBqI%=h=&snT8`SI^8KYj(}c|K8(GYyn4Rh zy=`CD^uBn=E?E)*V`8(Len@YVQ#v{Y4BTGy`2u5Kz%YyFtM|Ovvg=7&IUt2{41%lI zN^W|BaU3j3%vqH9_A!9*-q(^{*=?tJthojoF6A|wW;fg76w{!oCXe4z$kkLJ6i1US zNLZ*S-9e!Q2pw1-u~6N&mipLQ`A9`x5)pDH!k<LeeqvGrJFv@6QARV&r(HYW?AqO1 zk!i|P!wSw;c2eKTu$m^1PQ)goX+I$QwK-4SS8COlVOsKe`dkfsQ)*j-9+CGYbg{*s z?bZH!(0WI!iM+DN;`t}=PthX`1nYH8%kV2!f(D4kdh;aoPD7vukZMBRb%i`3s7$@} zp`a=uXd_62trMshR7su|R7oCeT_I17l9Cd-X@EcBmwJy-GkK4QJi(MF)d|!ivIh+C zR}w6Ty!S}{bn6QG3=lt&wt9dj3PGFvdgvq1Qd$Y|6cdO6$|Cp+WGmOG-NC%1LQb)H zB^N0@^06TM5~=Z2>qn0$sJW!{NLf_{3mv0G28J+X<VN=;Qasi*2Qg`sh+z1nRQ*D^ z!a&s2)aWCSh5ieWYgIo`zw`+zlTY=_fa>8B31I0F<{LgNtg-krHYY6^=84Ik2$MZ} z<VHf97&V>gXZ*&UPU^nY)!{r09TdQHa2oLjx~0IBz|v-G?qaj*d<+6w6+0<>SULN< z*aMFE6soQkx5+5)^9jz}f;DsA7{-HTB)m8U^ZK42`WEy`pkE5CiiWeUuzy$V!EMn? zrrx%`RI%J2n!n9!mJI{m0yFFSQD>O7IOK?DseO34RS;Z$0Mb5*$2+|?8yY`UaN1}@ zqPG(`-Gx6wLE*AL@21CCTUQU~f{P3MorXWKp7<c^J%r?eTNU{<+qQ(VAvw?mO1r{K zo$PBW75mv;6MxVnhNVYj7so0yrp&Cv_Y2!So(^cS+p3NIPG%ECz{`_`PfmY<Pmq@d zDFyJd3^Fp|)}lKvB?*uX1%-e|cny1%?rmmV#wnccsAs+R=!-v2M~P29x&IsveT73Q zaLFI8+=AO4a3&bmduLcyz^IgpKCziwpTdd+XrBXJGfQ?w=eC+-EQ)(`H0+J@v4n#& zoeIM9HV$1GaX2U~C_O3u%jpBx0{6McZVQb4Bl?zk=+;Z_Yj1k(KNMzb5$x#vRTP~! z>rMKE`%f=fyuUoa<w)}*_YC9qczzll|FK_2=Fs$vMG2{M<5T;7EgFzqwJrqa?|5dh z^oh?o(gh|BNIm0Mb|4C-yesRIk~!i1hlc>m?GpQpb?!L9ZSOfa9|ki_Ltmm1*KecV zpn*_}S6#(fC@^G-5gy5MHnP_vmLDY9$dIsBwqnQHP->38d5b09QmL=C)Kg>{V`h}K zb?3L8MqQP$q17NgMw;3>0&QJ^Y_6f49?1w3TTSswBLT0anyS0hs;81tV~$#LF2_e| zBb!$zr$-1<ni2n@V*XTfsWtdV@aqkY9H<pmYOLC{jw9rb+5^4l=;-`Y#tK2hlppH{ z>i5_4N*+SZVCw{$!=yc6%K*A*fOQ4c1dno+5P#dg{GdlQZ>>GBou=v{WI@&))VqAZ zh-y*~edHb~X`?F9W1T>~VD2O2^r#+1wx$=<iuP&MPao=w_JpBU|7LIvvjD9Rn|D7J zudzU7$Q87e*zTe=#P>yPjQKn@I)|Y4p#4TNvq<QXHoi)tXsB^$6qs(*Pa7GS-ToHU zX0cA7<w_P^b@J;9%q}eSKlQZLqg+wo)0DpqAnKtKJ~%nSC0owO!4g&<OR_u-bC5hJ z1%}5cHf1>zzJdo?nGxDVmR|pV?EM8mRL$G}j}OZd+pvT|+uhyWb=%$D9Y{AKDt2LG zE21<~iXA9mAc`U=C?F`H)N=i=nX~N8U7wGF&+mUf&)2u(;q2LS=FFL$x#l%-X0V_$ z7_u{_-|pAVCIxTwfjO6eOb;9v3$yQnw3FB77#JK!U!FSFs`woF<SzPP+xN>pJZGd` zozGzQ5vJXR9&;Yeobc%WF?g{LI`-JxDFfvB&><OC+=iijPw!hC@44)T{|&H7g3d3X zMgf>)!>BkQ1AJ!R2hwBRrpR>Lo9{=wRt$Lq%WlK2Aec5JxNG%I(}rI63V=z^pzSB9 zQw&``WV_#ZG;+|YRl_c9>3`>R`v-6x64D`{3{K_4;^d<41<<^-plklqy6;a(zIw1( zs@cTT)G<P$j-w^}mdS^H8?<FhZQo~;^Uk-qwOViIQ2FvNnUGonNu}_#3=#mcv%qiE z8CQ#SkPEqm@D1_k0}RqVG*EJ`OSR**>h308TwF51F$>mb!O}uloddjq2OJ_{(Os~Q zh0CEO&mMsLv3E0$zZwwqu2)K#X?|(*Tv+xHgcJ7+dQ;f%R{HiMh4Uu(g}sB&_b|M# zQ^E}hiwFNCIN<j&*ay72-&#BB-k3+lozg$eihDQbRQM|I3+s=cpGTLdyL`bq?9Q5~ zh_wNcNA9~_xw-LS!s^&KhkFSpLgV&bdSrPkb$r67ZYePN9;}<3vVBCtl=1tKdp0D( zpckd}J}K(v=J!v1a~WW~=XLLJ*cAmU_UG5@>pR}^ai`_miFqA$0|S{%!mTHZqIDIP z_o)%$cGT#IY|NPG(5Q(Se<OBdKE>3<wJmW6aUTzMAmsg$)u}7jH_+lq<RaRGrbF3C zg-2ZWSElW9Ji>2lNyPOv_?O(=a9d3*tR<CH9GcAn!a)B!gqef0qFhEnaku*^LZ8t? z?nYG<XPMC^VAf{litccC`F^1%h(}5vnJ{>jD0fiYg%}L9Hma@iHa{ZHUf~WGQMl!H zen_foxh?uxxxjE&aa#<PfdQ>ERxUi;RjM5n#yq>pA5_(`M_6E}f{O{Faz6uiA(n_r zPb(|cqgHG^LUH@wFYXe25ZtMHs8m9)Sa5zgJY3$Z`1@53kCgRC_F{i+EPCBM_0cl& z32Qe00jcna)gATm2c%Qz>WYOL0y?uCm*m)8uqKMNM%?)!;q@GdaM8sXno6WAl)k?H ze;cRu-=#`dDm>x>#_fN<@Iknr60cR^5%r&yPf?C;SbfLxi56e1i=+-A*KO@uu~`_f z#KK=tU0s8yS2G#DW!#pGR-=R0UW9%(q310iE!=9fI}~^U+<c+gtI|FX!KHiNNs{eN zKHEv&Zg+zgw$a_6Lyu%wd>am&2baFj))`%l-wh`(z|;pY=qWwkW>$F5{%2;7@poQz z%l>%k@Wiq@c_1t*Gs}WWw}A{g+vNp}OfG0Ta*223+X>I1+dKMt8u`uRQjnrmwfTMe zpPYZTu<u(i%P%$n=<y-<{M9GZIxh;0gx~<!+9z&Duj@I9@Z=+ee*nA3WiwyHZ&{!F z=G-+)-6Q$x&SQ&?{k}Q}qawEO8SYrMPV#PBZArp3#dLCTyzsz`x`!bd-hYB;#bu95 zOCAHn1LS^$km3G2%{`EczI=s}&(NvGw&tx4MBjmP7s2%~EV%s5E*n-Az`RnJSX{i| zE0E!*=fyzZWSI1%c=P6jD~^fBHYGdne77+IX2d~X4B-o~i2|J=$0o(W*sG-zX5M?8 z00%yS_b2GnbKA=s5dIWIL)P{<7P~GIE**yP6P}NI3hiFO#Q5A6o`>7JZQgeK&bg~G zQJ3z{>au9pl4JWlF1zl!wBq3TIcF}9z2HCnw7=8-%bU0RTkQ<By7j()YVM@RaD6`< z?{+uw;0GuKr?9uv;&M8reQuYQI`K)|ZGZ*tm(Pdfo(TKwe&Ai(Rz6FYB@US5MGVZf z<e1pybRHwj<(RJUAKlO`iq9sr=Mx?#AhZvB4JC!MQEq&S-S|B-9O~-oSf9Z3)`pOj zbsL|rSzkw+FV+(y9&z-;;SsA-VaB9yW>9NTjz`rb(mFgfKUcR#+5&Ttu)2=aR453y zr!V$%c!W3qeLXnT?|c7ADwL5(Dlrks-;49G>Oz0eI-xLkb7dKNUJ3hvKHyKN@{`-C ziqJ#!w$kCjXHog^6XS~WuoB@xsV>BTaVS~2fT^y+9S%S_|No>ajXlB(RqZq?asK|O z@Is^qE+iOSF2p}7)q`+&#092uLE^5$U!sb5q<R)rTyX_tC4_-dg^C*y#ogjh!lOz& z!vE-)5#(xY%CFhF{nhEJwC*N^m}saON`GwPY_x_bR(He?`fR8s#Um}ACO7deePTW> z@`LS^lTZGT@X^F#F+L{7l`6U_@jK!r=n2<)#QhNH^FPJge-QTzqVN|~{R)*6J`VbT z`V$`M5)xtS+K4McSkZ;C7vkWIMHHKT*g=O22A!9o=9noLS6Y7<F!K7+GtlZmQRn-G zXK%o_co<-Ge(Pyy_5wO3!1Cc4UZS*ZB-crjYBwZq+N_8<yFT=p_h8A;m+>C((j69> zpSimqqK`qKH_RPycX_`@6Nlfi2?xiUu)#86`xWT?rcC%vp{;;g*+52|opOgxbkrv$ zV?duNj}JXNdLBs6i)5_#%0##nnfzOi#pnFNeB9X{!P#B2p!&D6v8iQKj8<CLvD*>{ z%ihB7J1}qJ_1%3V_Vx~4JvP|aA5L5<b-bC<=IwFal1=I*_H0EnBq0url&*XQS*uoW zkDa}&7$Ds{pzXPn7h&H8IC{D8OD5!grmaV@pm<nXRFDn9eQ)oreg@t`Q8x5#aJWP3 zGe?tQ=X>x72Wy|~b1z}|&M>zuSe*~E0p{l+^POIB4_c%{$29tyz2~m?PF}A^j}7fu z^Gc7p_v^Hd*>M(5orOy$VQ{Al=e=O#h?w}h;PV+yeuOC<_bqO|2Z2R8d|A(wZ*AVt z2E3LlAGTf=>lO}^>=QcMUmcrPJm*Df^p(4d+e{eJYu!Bi(2<+34%rdj)&9idM;YDT z=d{nrotl_w9g}wO;!C^Tk&{mOFFzQ0by?!u$<NZ~geT5FdvC4Z33q>&>rd9)ec%;& zwGd$Yy8VaO9*gyhKj#`Vv+l_pfAHQASyNbFPh_a4%Lc1bFrw)S?SPhgc{>gMp{w|5 zsnLan*ksu}I#7@ursCl-rLCa#84E&U?Cb{+a?9S<LO>gsb!Ez)HLMiLbfxs&ezul~ zSgym!i2@UTtSOSV($olYcB!Q;s4kZ3O2mjq5e~FvRE0;3kjnM@-k+t)AShKHtV-_t zlQ@IGd8^u~oH$d%ZP91kQ5ml97hZ)#!X8=;Ayw)1k4yC|Twu^oWXej!8+Qp8DwVe? z&wof2ABUR1N?B3vLfm1+0yU)QTP4DSm#C5xCp^OW{3lhl^$5#p^hFhDeCEHs&3_hN zg4b3o@+<cnaKdXV*77UyGobK76z-@x*D4pJia!IAR^<YtqIfQPQU7^p_U{43J!bOQ zi{fYu*bz0NNqC4X)d=x(cB+l2B>v%bMNk|bu|)=ycqGykvbV0-{du&XDBO{n#UI5Z z6bB-B7fcw++x>XDLSc;k;T^H6rK>8AJ>s%7{+hT|jXgqdF^ympU31>ll$A^vMl47S z2*EO@8GCar#9lf7xEhaNSO!j8lSfayJ!)W#(-9aF4HLqkPhIb44lqJ5WbD-R;kRMJ zZ94qOtIgN7)lwJLh`(eBi$}*8*Y;R#`EkXVR~rUB-`MZ|_~t$#=fU?REFN@y>44Z- z10U}91!RRGff>fVb{GxWH~JZ!{aIQ7X1PGd9UJoyn!kk!Pcvrsn0%<4^$6p=rY+9T zc?t_(6<@shXu!ZpyKa`rXP(iR>C-OaQ-iNC_Ia^K^FwF4_-=U#6Eng32?T|}>9)5+ zn%<vV>q4{-1f7DO8}`>t*-2ZB$~N-Bk*#2lJY>%tw;(@<M>b909(FwVa(KJ*&HJBm z3xLDX;2T`>@N91Ux%B)`@b)vjD}mw^xY{)?qHPi+LeExP+qUw#kN|esV3h-#Z<IQn z%{cuUCVGdC-sA6;0ZVgW#U~&`{pQ?&mML`hCYNyNGx~g&1?P=hZyRD9HMH7;2F-8Q z>lEI;>8bnPu+}Jeca!^jI^Fyf1AcEIC>1_O!iM@gaI4X1bgPW7I)%{a9ZZge5!2!# zcEi!7=}Q(wEsD)s`XsH-pxHxv&mU-eVf4i}WSD)oU3dF$yVb-cba-M}-!$l(R5~ZF zWQYI9bC)s>2BrC2{xGT47E3dCuzqu=wP#2N52U>fhk|FE^IvuN?C$MXLf1z{E|0!w zAAHI>e4+VPxB$V6uCyj5jRiG~v;_J*I_nrFC*)~#T(22AOi^OiF3CqbKs0!ihG<6R z^VGRzXsMy#Q8S^=Qe%BW?$|i=M{0MrLB3&`opz&hgN-;mLd%2>*@#VpMDYke8i~Xm zc)TE6yIPcuXm62)L>$TNKsg>^eq>ql$MYhVvdX;lGgK98@FyXEaQPa&<*YP!iysnR zh1XUrGBAXd4kTWP9-{Ck;EInQm8!Twse<t*u=q|@yoxjFl?#$eTx?ebB2lW#F?i^q z((4MMc!VdR&|Y&p-!Ck9u*k=hfe(zr8b6jF`0+=DF@@KnS6J#}KvBvY{GjkB#HT=^ zSLh)Mea3((Z}Z*a9tU^O2Q4iv^cnrEM5wq+*aPvnxZ;Au-Q|b$r-;Q+VO(){`K!?M zp`&Y3;?K{=kLsFg8d_@V8fgBw#&f<FT0~^;P*)c$lB;WLEB*aG>4+s#G2IbMB|@pL zP%4v11yYGXLtPUcrZ~KdrnUx}=BrMQXco~-)1Z8}Fs=}f*sbVqL2o2x_xnL{QH_9$ z9-_Bg^5A}y9};&V_Y2|=QR#Gr;(~-e;LnGCqR;s2AidJIA{)9cl|E6!VyqVXX=)N; zMo4q~%8?GD=i?7fc%K0l9!=~q|JH=AH~c)oV>fhcac`CE&fZ$@Cz!^ytQ|3OPV(+U zaMcqgn8)^S6SK`7IyMMs-o&?B`$K~~lUnYN@4oNJVy74Fy6zh1eBJhD*{a(x<pK14 z3jGsd>VuL=VVQGoDx{MRHyn7#GKx<BD9-~jci*shnDH3ggR@q)9e1+Ns!68S=fhxX zI*fUjd;I3@wj;;Sc#}6g8T4nK9ewGu;p4aCUzaXvzWreL%lmJF%~Lpj6XMQ;f7|<^ z&7LeUxz)X8j8VVyQ=Vj3&-Er{Yv=;_B^%Vstko5^q|AxBiY-ZH8=I#dy!!zLwm)Fh z?cg?lco+p)L6GU4mvi8A`oT|c&SaOS06c}5&hh(20U^tZ+qT}jKN&WBf)!<ykdB3v zdU(Iy@)0&=maf<mykb+-);Hjo24sNW(r6g-lny^yKIPGr-hMk1Vf4x5-Xo%RU54TD z@LL?z>Uj9U9<bHBcdl021&h18+Fp6`2x4Et=j&kG$m{ylh~Ij+bWi!Jp#a??=>Gyn z^ou^)?s3YnSEuUljQ2_CHez;H$AfcT=J!hdRzEsve83xzJD}Zjn_<Tt^JYd&T7G@z z0~i|zmJubpuYk7?H0|l9)_ec<OMs9U)a9aAZ@-CS&(4qiH1tL0w8vkkI3_GL4Y)eC z&|%@*9$j`^w7+(J?fLj+$Dgd)f6c}-+}SPE);`kFxiRCL25g8SW^nw7&VmqQHmC?q z0S}D<Qj&(c77wd`8bqM2rlq0DBLYnA^c*!ziZNEUJ!uo>#+uriVu?&F(ZwxG#Uim3 z&5=k)Btu8jGyBM#3=ypZW_&w4V{IW`B9e&l@~aLu7y#M=isndNn>uQjzSk^ZPT_XY z?r|l~Pm#)7RK@)t6^4p43uqH?i>jQF$IH<lv{x7yuGGMt$^{IsMGJ#g6a&NgT!|pz zRh-Zt3>D`s=l>6hJqo=Lp9SLzeM3LFfc=nI)GDvyLWRDe3FYqcqrxDm%Fv1>PDN2X zLJCvD(hmw_91|;sk3%rkP9=ob;tzlxGE}8f-s4AvS0Mx9Q=wP*@Jg?%AdEPCKnzu- z0i1gl6kd+MrPAL@N%cfrT%n)Jd;CS*Xn>0QT(wUw6YA?B%iv+TuAaPxKoIKWgrzT5 z7R!Iaa`(@|FA;z$oX^HHF<}am>*(q0=+fqQnZ!t-b=AeG4I!pN5$%R64~!~o|0Ikn zd_c}md{`8>UkPEPadE}{1eiQ3_d8+&zzoUdM)dYagY>7fF<qe@l;h8Wfx$Ytp4><x z4s~$sL`WSiL2ZE$_uH!x3$eglTeCeOVb0EY0>Y?)Og9r?m~ZU(6FEx<Cyo+^^s5)! zr`Drs`gc~feY@iT=(W8vVOH|IF-bQ4Ge_0Ee)<wvdV@h5KetQJVP*WR2hi$6k@}Tu z>Jzt(aJ}1O+l?lBt`B<#ZQg;b04#E0`lEtLL2m}WESvBc+VwcvzWY%mr-83w%mbKp z4{F#(_q6i2p1W;X>v;(W3of3bFPyJ^QFi=hVy!8&dS>Tz%7xXBKyUKVUg7C$?v*X> zef*sd_(nnZB{zPXeRuxo8#{Yn-_q+&_coE9zOWmw%?5+)V~l~UNST!qj}$KSwKdw3 zgm^?}(AF$-YLUF}_InuAWyi+j#d`uFEd&&2%HR~hNhsM>_<46;>haI%yT0uf9!i-~ zHs18)wR^BP1st-$HWLmfL-g^YyH~*LJ$Mwr#pkff{kp+muYJ!zr~4V#P&$2OkJY#5 zjg4}4PeTN09gx^;dVo~~w0lou#y$$dPrzVuVr%t;#Dx%LleNzI+6s?|9c%AioOS>H zl&9kwd5w;PI@!?bEzF65n4NIWI7ZR+p}%b1%GT2-SbL6tliTQ1u}NWBjYr9&{GM%p z02}Xt`%N&ZxuSM`JI&$e7RP||71(<TYP9qv-7oce0<#~`i3z;BhMhVIE!ISx1{nLK zY~~#>=@UN3{NB0ouyR>(!>)%cm!Bwz&IlU5c>s~NVsGOknqVrrYVUZ}$vMo~5yASZ zgFTz^$RXI-!Qaibz6Re^TWBVs+0#TMFw>Tr31u}zq8cKhnNZ7ITiZe+tIyZ&N=U4& z-5sm7h&8O`5{(b%m{@}5+N8O(ja#-uo2BuRXh#=%l^PNdU&Lmh<yLK@c}Zp<)4_y{ zc0f74`=7*_I8}zlkC+EB@6h}F3~`=w;%-qnVW_ZtMGu*+qS5f9_CY1ISLhq};D37j z?-yD*^aOV>uDDX8a;2f_Sx}t)<hI;hzF*uA$At<n$G}wON900<LVq~Vxx0M7Fbt}; zA`B8&xc_YwQ9R<#tDLaxQ3bb(LJ(1UT4kvU*Q$tnE-c2Bo>o@e?}yte;t?k<R0txR z=l>vX>NaYCSc^Ap4`-qu^|3UT=wjJyEEEPiJ7G0Zmk|#YX8>6`VLz(sv$9`~6C0$U z9OYe67*{m4N#zDQ`Z`jXnM4%i<Vfc}(H61M-?TxVbLBx|Lp#|PKe8kAG>j|cdZnjT z7RFU2ve2J|KA<=w_#NURjfq9kAAyoOtbtQt)u92C$fTxXak#TfXF^(O@EU89OU|~9 zv^BBNG80KU5?+YCld%{X-9S$wNd;&db))B%^u>c;EHb@6q(_29*D#y2pgT9D>wW0< z7|8g;gBLxr9{Oye(dmFQV9;$Z8GL;5Z6Je>jeiKWKPhT`DINM0T5W&W!Rx_r-^^a2 zIbC0aK>^gsEt-Eni}ae^GNZ8ldsrI=lV(Ks>#}{-^w8x~@AqABr+*@JOD<a%Q)p0k zdDKx@-79Qq|C?dw;dI2eu@`T4`uwfsHyHC8Y#%_MQI{t4^IbB^zm2*5j7fJ!%(#by zwC^^YiG*IO0>&r6*n42yDMCK*c&#*Fwtk2sQP{CbAnm!<BR-oV67fh);UdfT?E38Z zgLD|&&C}-emu;7dK88W*nUd1;P;{~k&I58%-mZdg9>sh0z3<J*dUy>29zygTxONkw z@4@qMDBBCW`<@7T3Z5C@@d<XM!*s8w0e4}|y5w_bVB-8Iy=F(4kK4B3@uxQLb4{+l zsyjE>J`{$$fIew3{~0Vkka@%wX0?jm>Gg5lsb^!t;->mP+rBgX_>y<aOng@jdP=$- zAw7?owh8ZNbZx2N)>*@tJGvgb%@>Y!K0f4KcEh}H#tJYjRv6q(8h7QTb3BZB0|PQ) z^gCFR1f=!8mTdxhnjCH206jU<=NXt~!mxNc%cV=l@Hw}jZ&F#q4QF2g>^lYB+TORF z_TF{bhXorl>hwJ}WqlargU_%Fok<fjqKiaQO<T=GtWirSw9pot2&FXyViSpuiAZEB z(5x%aXsoUt=;CtK#U;qrCfwQSs*@vPQ-q6igo8szHp&fMM>SqgLPijhxNhwu%MGed zF-*gJRWhd8pHE+cWoer^o;q7=7V!u#iEwa|ai{TUr(S@AE#khBn8PD|I$%+SN6bKd zr!WszuB884aiz7=>naFCr78ruol2L9c;Qb85~^aTsxGCcl@$ht+d(c-`uH<c>FVyE z^iQGsg-8D=?zyUtN1QNy{C|l@6g$fCNM(T7NBWW(;tR5fu~0kIm5y#fJW>vX;fi%; zf7p+z`uqnxQXVWnq&lvttzlqbAQMVCJi^K%;#Ye$HN+!*TATU*8y=y*RTKsZ^}~3? zMG-4nXi1_vf;DoH7@wEJBVC!?R459xvF%Ps7d3Lp(WZew6Mr28vCLd7?LgE+ot$cl z#Trrx#_wZ*IyWLahNjp|f4i<p?C}Gz>O2g&3vH61VbZt8&%bti3iTah=Fhk@rtYrQ zzg-wG^ZbY>(B&17t{#&fLBk9%|5QqxPEUUTV>Z9;x#r%in?UTZbbSHCpM&MC60O<W zn!Yb-`xcy{VC{qlrv}_U-|M#9fH?27FghN(zkoS+fwXWxbsECFVR?_+OZr|5y#%X| zyqcDz82GMqY${9$`e@wHdBLdQh2t-JxxNYt0iOtPj|ICY;QF|%y7RH78K1`h9DD)7 z;XBP!&k%4TrM7C|z*>wDj~vt#4t#|*hew*lZq;+PyF=E!6zJ8{b<ve<*BC`|0KmDj zl5+sQP<9&N7{F=B+ETipzSkk=)KN=<`YsBbJTqqQ#GCWSU!T?T$mW{6r<0{)h8#Zq z5_YD8_iMNr10x!q+&k};-RN6OM%=2?e%JilpZdQ|Z=97`H$1NW<l`qU!P;9e^@*b0 z)n_C9(rcRS>eboz;z!t52)hd5Xf7<+^0ITsQ$rg0pYwsmk+AqC7&h|jrRTR%=)axp z4A67%>gm#U=jA4O#qyFuDJXP{N@~Ww8SVGd@(J|&3=K-4Suu>xfL)=`QUAz^$?rGM zOR~O2XZWn~6$U1PXSWBAZLaru0;Zper#~uu4KSq9&Ebu1%~<wmk;n7JYoEJ$=FMGy zzhkFOTc-w@k!C{LCq^W4k*>Z(CXv!tN@e<Ty=oFE79qO25^;5j$XrvSsg`DI%0L9` zEx6Nx?I4#&Iy#0rIfS}81>4zQv$1|^y&-Yk>bP}lTd`>*5xlSfLB|baLMLPnkE8X_ zD<9;9#|_Xcd#8rwUFsMlJPqwk8^j}OOW8aiY=wVx{~3?|TJm8Y{Fmbqr%IQJc;PQR z`hNW^Ji_29ef*<-;n6>ed#?Zec=Wq4C1HA!>*z_vGCf_ni9kEd*|`ZbZOWez|CE>P zOxy?R@EhehRP5j%51}ONom=!AZ-E8BsZh{{4nJ}>6DT{^xKW%O9x>5ya_;{U9{uS( zL3HJRe|KWB7=IvqZuA@rGjp*d)YTDd?QFD%Yb}fhu|!|0W1_9qmPdl!9Sz0mYBlvq z?K*=40_xm~sdXUKdhVmOEh86>PFn8=%@WG$yew2(d2!qgXq=SS>S>N;G)x?OY}1gf zfoGEYy(+Bt0Z5-s({DrnWayL%WYLa=x4?N>_VTe$)?5RfrT*Q<T|IIdJOY69-a6nV zOu7#(On1&zKV(S``E*F>)FjBbdt{B?4;(MTrU0ll_|(=AaJUTCq0o2o)s3AlUtN{4 ze|P5EiyuaYq;(ET>fxW%Y~}GK6Zao?ez0Okl2a_$yacO6a8D?+a6j2DJ$n$q^g@^h zxdxy2AseaF1|%yr*vJ+Yp#!v8&l(+jBrJ5Pm9^IcKE}R<wgWab@_jh*abEmY+F}GJ z+4d;pZz;*%1{2%v8n^R7?<4nSc*ib1{ET#7+htw2w1s;E3y;B?&W^1E*Z&qXcf$1< zldmoR?a`hNpX|kVgU4o`p8VqAyrdHsVfG{F{kow4n|IQA>yA4HY#X}s*zV*dCth}l zdcG_Rq_uaq?{v;57ks`zd=hl)=PDS!bK1p{y1jjz!lC_hsFw}Ml&h}+1cR^K`cjL- zUbDi-oQ#)8+&3yI(N+{1D4^P-w<Cj6*F1$DS<tcwx@N(gm*DOLovQDEFxWdca?biI zb7ONXGK+>Mz>cO5y_((|6c3V8FwQC(cMnE34VzRiu&ZNapItHDZrLF=Ur*X+4(RML zW{L+<H>9iYs}qq#D3$3-<OU)gJ<M)W9SQC0mg%xCZ>d~YVxS{75({YOnn-LcmSDo8 zeQhF%u|QN)D8eIX78(io;Wq0K)}O6k`*_{DXnXrGM~6rUTXbPg_QB2$SnWY%=Vq1U z1~%bN9X4G^JwmS8IUpX<(Q>R-fSiPOrY%u35sERz>#>zdI8#7#)<2hSzwoFk`fI4F zBBiI56$Xae`GrT7)Gs{x9&w@i4m?6p)L=Wm3oQa|*+!cw)3K0<BOINZv1%Xl`j3uE z$wtimcOlbI`od}}5{^vATrBF!<A>Ngm<nkea`i<dHs-kC{EkQ5=YK68p)gdH#-sB1 zq~boQ@CdgUSGBaYqU|jE6B1?P&_Z3PuO*f18R$!;7GeQb-$UJ<YREK+fs9zx8tWHm zdhAro?Uw^i7te2hcE<Q;%PvB*L}>P+%w&fD@&IV|{7cgpnKS&-K9|6JedAxHee~{A zO~#(=nruwAZQGb^d$QZvwr!h}ZP(7WPQUXxFV35D{)hW}Uu#`jgL08xh+4mo#!3k6 z{>q-V+ECjbpP$A-eS?zlPCatn-DUs58>4~B!9n(K3i$xNiUeGtyqg^o__OT)Fju6& zk($T0P+%f$152+qwKnbWd0{uXbL=+P+<F)|f_i=V?JZFq{cK%xtzrhY7Qj;U*&?KH zvZ2UvV`NU-j6C!wkmlXwo;;X+&JqG!`p)zuZM?3CYPJEPHNrc>la)>ZH5rn>*@+Is zLd0<=^fiRVVPS7Z?*|AlN87)U(gDt8E}v6{t?!tMjcuTHNcW?U!`+*Jvl1yh^$|Ag z`kH~+5nVan?2f~!U=DkkV8km!FBF|lMEVB($;%x-ZWQADoj%oPdn9mN%qt=QzDdfo zocr&lsVUcsE(!gSylKO^{eM-8R8|=^*Nqyure8)0ZsU788i^2450AD^3^$WOG&y;0 zc5keg4hcB|$Ehf*wZaqC!UH-#F==oPdn;Ee+jx^b7PVYUXUkaey;BJN)>$~3hmMWz z?225v|DH4*)TL~3j`Vk`GrpkH%KVu7vX5rlqG%D`XjUR69SvHY$_v!TAnGKjz-;N! zJ74KgxQommdYgM;-+5IFa|pG)TyDSYW-GkQ4*0dgeKnhYavU<%KqN#bqlzLF6)aR3 zizB2dTi04Fu`W_*T3My4u5MdMR!S6SA^ii~CmGCi^dPnP!I?~{O+{>3mxVEL{Qkhv z=LZ#Yo?2;!kM<x*1>z=*AgcfUd>CgT;oz^0eE8-DM7KtuvolOf3&6n{!NCE+%_+jZ zvCGtEJ{}Qb*%(od)m%SAn49Y{Of6x&1Zt-kqBQmCt5V-x1^t6nMKx}2ejE;B;NtyT zKs?1H@By|e_~^&g43bnoMQ}Cxd3uI1w3}nN6b@^pXN7CE2BPAMytu`by<hpoqU04C zt$C6roX&cUkrsnrAO(qVwdHDxD37jy05S9W6+kTYuZbHFP_gv&Z=8y+%JA@aoo0~0 zih?kS!^ikC?o#8Cg*qk(>vXgTC9YaSLArGF`*Z4>l^~5jIk8)<Tfdnp1G5!x*%)2x zVYoDgv*w0gGp>1v3g&am9b2%kfM>k+H~RNcLt}kKpXoC8o7yU3I{}g}yc)T7mpWEX zyQ&5(t+8R&3v>&GgTTqQPS<uvWBwS&hS@}b-`u*M02|Q2cQ=Qzy!~Q>*-L)?E2Xpj z;9n<VG;^K{luTssu$b498o)7b5YH;1JzutP<R9kSarZ;&!-DT5^E4$^oZ1o%{2wxb zrmc(;w{*4JU%b0?2zU<WKDgTrky|>gP*pZhbRMa-?JUM<orykNg}SGCf*p&MN!ItF zMWP_V3u4TH>8-Qf`Doe|-}A-ZK)}dlxGZAOd&5tk;vI$OWxlPr=os-RFUSkIo=WDk z+ahzUd5i7Oz!SDBLqUR-Zip)mjgI%B+&s*dF7Os-j^zJ<!oOM%-?Sf?mqGezYG>~3 z;if)LR&!Hv_ihxMv}aGNY}=!ECL_Ic5D+A`{kOClH(-`&=b*wCDmLtQW<f5Ck!N@F zSSZAOv?_I84OFCu>mZq-fD8q{R<nZHWH2)(0M1*Mxwq47d1_n=3eNNP*;BR23@!-u z)?(~Lek5QgpZ}iFzQOhG*M73EEyd1?Lu(6mXNO*>(|=b6i4)PA$2$QQ8?)^<G{(7K z1@BcUx7C-gw;LDhveW&NXP0R)+>M6o^Q{^jJ;z<^T3_MH%NMH+SCt*ge+$rWrCPg; z+4C2Zt~+Y=m~9o1>*bte4H5BmiPYkpO`xElQm+`JvByoJ+LiFzWVC7f_dVMkg~R3O z5Cwx!@uQvHy2$1{T$aK^k|<TD(@zVcSdn&-2n0h#_34E6*li^mb^Ml>PSXQ*TLWbi z3uF@?+8=oaN$6O(Lr_kyFU?baCY#%w62hEd5~zy$A*!kt-hWpr_S$oQBT)SJ>a$Hk zud=Ot;PmnO4~ptWB8HM!Fd>&_x!??t8rj(Kvq?g{ow2HXMXkJF{LnU-By$`<xeAjd z@k>NVXxin_{Pt(h^JbW5Y85ZW1s*}!Jq1sGbNybNA0dHZtU^*R35F=G=fanLDKWt= za85$`?(nrqUX9K!mndHH;rII4*@@cn{O{!j(C~ifI@iMD3>*4bjMq7;B%Khv;pxd4 z8%2RFdT+e8z@N8R&JOV{rBr$T4)R*}=dMgwzGYLyVt|h0a|@;>#I_0jZL||dX6qfw zITB>auV2b;%O42QOu4T?J_XG~&60E#Z(zlwy?Xo_#@>@5nb8Dy_2z*8+N%tN<<=2L z@#24QZG&=)!Wj(K*;2>vRvB6^w7*=QJy$LhTmE?2enBp0=`gWhj%(c_{GkZ^;4S@5 zp9k2YMjE3Mk_-1suW(XsRDWo8R5|!8o!j26)8@3)U{ImRHprR#xfE52h@QO|46KA% zaVbrC73%$|(mW@Bc5HP!+PntT9!redt=m26_!#yaK6sTl7I%oT@M9Iba2Bc>Dvl7F zqi1cptL+>rgvI=AhG?;qhax4-Q27Oc=M}|)?}>}l8BjI7yGNqIPqfzKL(I41%)Gr5 z$XFTploweGA`k9a{9Sv87ggcv9{qkEU@7j&y3tO7*cqQ&wRPl=vRr6pz~(U&c02<j zQK1RK0p6w8#54gy{29=N^?cza0x^t{<h<@J2AaS-$osg{_4#pNg&FuhC)s`fPVXPK z<PFq=uoDVwbNn56t6dm-Hda}N&1mq}AcVP~RuQ}(ooTEuQTG`+%FP;l0FQzS(c&YP z+uM84(!~5%cVm3k4=`K((OH}&a(y^J_6Byb8Xeq|W=h95B|pC30$yhSw47Vnmx<3a zYt}gQnwr9$Yolvh!tHB;j!r!XJ388^%5j4-v{lt*7Q{2vWXL#WsLXjGX%gn-$Y~Kx zbyCLF)r(rfZ`IMd>O%Q87cz-f<jHO|^Iwe)iB^P%*8FCP&(?VHkVNcNY{XhkCX;fR z9Ve$VQPI3}35slUDNOT0R5?@WkMKZWOuc7#V7LDFn_+tO!vk{c2uR;^6F8`{G)g=t z>F84?{pwB)Z>n<)cag1pEQ`3f?J4I!6i@V{gmUQ6ahS$8Y>uN?z}TU?cGc*YF51&# zLf%sk3QQ<}kU(ccdmC+^<A_qu7Wj>{f9l6gP*%7xGAg9LOY=J;BH>YRZ~yEh6^^Aw zd;O7kP)AzGi{G?esZQp5->D|EmN%n!9n>G6HgwW`fD-xM6#rfyv6G00=ySrD>N@TJ z+uk6tvJTz!qtHBN{hVqbxN#%*mcl_n&uy45viMAReYpwT=1sLHdhVUVY@V={U(Mp+ z0h8$#7;p~WHLsz{284747*6+|q5QKVXkGl(FL}4{(k7n}lY)K@xdM4NcC*?;_T&lC z)YBhiGPD4XUAUS|5^7+WwUdVU(V`Qe`IPrYlZpl1K+cyv&tV{O#(YfQ*H<x9nXz~- zM-r*m3Hx^apu@Hy>0ft;B=6d3x#c_@!KNI#c)2t?mAAOh%nIjPMq?cp?Ji+7E=Iyd zSE!XnM=(N1^`P?R*={y9pQY~fNH~V$aNSocJbN6lP4CRJd_TCT_hMQ#E|rdnw$zih z#7sKxKIXA3q7e_596nRFy;Z7RO9OlK+H=A5xpGkvdjPNP=hbK<0pqiJK}kE?vr;iM z_JNr<`L`fBZiW?7tEe~st@euP{x?5%H^S1{b|=Th*>KYGl}@N3cuSiL($mR)?XIn7 zMilX;P%KUFxu)Jg({H_$J`%1EBXV<RJ$44M*-u@~FH#We`P^$XgIU+#u@h5iIWn$G z&#wNH$-SE=TB}Sg3x}=Ri`@szoxhm>%rom3NNrU=R?q`c<TJs6zp&WOW)-59)zeKj zSo|FR?VTEyxZNS~VEghKJ084Ei~eloHU(N`miWBqOYUAa5YSb)T_03ZB9{#xmlcc+ zMCm9icO<Knv^O`W#S}KHn3Rvz&?TnA4u0!p4=hd9Tpglo+`$~JP~2@n+}y#Ot72_y z!K>QFr$V7Ri=xq&_avmIFQ+M1OUr%d17vIbF*(ZQW{-lxk=@IAd1Bh}u|@CrC*HcA zw2T@@sdbNqH1wCFPpqPjyk&e#a2md5b{3$y6m!mrYxR%*f^twzUU|g-(BD{Cw#VPN zr1TvL_8JU6^|}dbGMI09Hhpbp;>=oCD<)Z*Eea%YInk2Hf@Rp~lN|S$R6*kXpQm-r z|8eK$E~4I^D~%G?1nJp6D#pdc%c+!B*NmY?JnLtBj!a>Rr|GG-8;7z_9VOb^`l=r- zE>&l~w-;e75%t@)mYM)ra_|}T7s1Kc;38Q7SGxDX0+Psp$S723okXvGb+bZ*JKCjz zs=mnMxg*iy<mifn7=V630$}}cYSMsaXSk&|$smr?iD>agTff=RyHrEZ>g!ePyH*E9 z75Z-;XmOaedz@1i=aK(CR-Ji+7q1bVxUz*=Z|Cc$D%I@ZYZ_@zxN7GtEI$NRYesGT z?mSb>uq85%W?$D3x8=Rw**dJbq1YWp!s4a7Y#{}uY4JQ5jhm#1cQ&u<O!bBr%yf^W zWnW6dXe06q^@ybMT#i97V6DyeXkR&*RSQhJ;-)ka>Z0V}Wo7$y|CBrKEz$wiAHA2m z2sXTQQQT<h_+@h*`R6Duv2p#xWkVT)f)Yd0nUC{KV<o(i*!}h1KF`ByemdVcTxCP= zj$YXqt_|`nSqw|6z9|dj^Qq8QGE#bM(j~fYPp8xOHI#*u`S{NV&hQUXBVnzdz_JfC zs=?lBAz8_meh;MA>-N)`BXrEXgS4rcp~wd_h7XcWSV(l7z!9EJG7{aq;aJw(KsV#c z!QjW?4t<9m1yVc9)#BJHAds9~e&MFEw9a}zx+ZJ>t{fA6R9f0{u;^*~;k;IVtU+YP zhGp*G?Y~$N^DHTf6>G*>xASI9h=x2j*RqK~l#&Zcw#TsqoVRo2tZh4ApJiWr4zPms z;;NdoCS`6`A6|q@>;^uRkl}&Oj9T9ram<U<d&O(_$Ky#P$-4k1t-+Eek9*H3aq|vW zD_(qC&FZL3M&1QaMWZdE(M<?0G-*nfnSRxLlDL^i@w#deYSh!yu#@#T+R(I!Ascs` z%9`kHHCg<5)$hYEOPbO2p;0d^{j-nhT@Shw(c!pk#dP`)-XBoH_o%$p-{qR27OCXM z$>p;*tc$-5joX%EV+|<SNvQ*%7u-`rqhZ?4n^yx$Ovw{fQO`&SX3uLP!}X)w2Qf&$ zxr3g_&w%eo)bRihq%QD7Cvc#GX!#;^tyXjz{dR}u%p&=|@>TtqEG8g8E;yV`T0*lZ zNJ4OO9I_--|5L!?aaxIIma|GUg_i7hKuf%-swY$uEV3?fBT-ls?M_<MB5)mtB^^{1 zj`M0qj%HxsY~nm+?(?T|mht2?Pg7+Nx&2F#N6B<b3f@P+2a~`7IXG_6wN+lH(~xCX z*`n?l1-2<JdPWu1ihcedbaic`w&`L}nH^&yR^Qb5oi-WYb9k-)(emJ(Z6e7m8R%uO zO=s$r1?({K;11UBGJ(8|x1+Z#vb8L_Bz{kA(bcL|)!GRkF@>}RiEM8yO7qNycY7|4 zuCB4zcr`3+lBc~D>LZo<-7QgHv%P?9lI!%J?)V1e`Gx@uu2C^;`YpzW0viXVVbvu7 zSs0{El$@S3ru!_+x=Y*DLYlJu%>8@Z)+wz=li;(FX!Txt9GQ@;i^E6DXXDiO|HS^e z*FW(@`Tam85G?8LZosv1vS5L=E$)<~4R;491H^#*ul5JsW{c@n-L@V+5w1@~PD}J* zTqbc{!Od7yOQrtkgqaH<8f&&6Pw2R;(l#DNk4^Jk(_rsxug@Xf>dmYGUcKXNuZdWv zxSSO7u9L?XE1UmNDKD-e$up;`n4jhlel!Vz^xz8aKs?|W1&{I@pApV(c-V<2Sjy=* zQ1-~Z0Jx7|Bv@K5JhNLguFl|5UO!B3#t0-CZ?RYOX>@rRxLkvY%`gt+f-6^dtlg=+ z&)<dyT@W11?b_FwVgB$<o+Q3h|Cv=UC^->!-Qc{?t~L5>yL9S$BNdKhN&N}WS`yrh zgMHwM`f4T|8W4X%Wx51Ff3p=>QRFZ=_Y=Izu9`hN9L}+JhJS*QqK}oQ$ndq{ruMYw zVR?qR*#4`Eg<$D8HuS928&P>e1WC8gyv8rb1vWE5;~ekg9LkqbvMS<s)6Lz>YA9DV z3eFIlux4rL+-&8{)b2|>DVy5H2s>8WETkC}Be;-qx_}lbD?*H#hh;^J0Zs?+ACjgp zAVOM7C1mxhifF;IxN0^hwxnV?ikx(K7K09gmE$lx^(``H;>~%DL}vNa89Jen&nuX& ze>Ul?QamcI)@@Ztmkry>;<N#Kb_VYE8R@VV7!LTq+b=NSC-uL;FGrp|R~14(75Cl$ z!+gJ%D0~B&AKH`77xxH3Qp@-|GVp%IK*ofm%W|<UL{pg5x^MZ~%~7a>e1|bC4q1zh zFGn6Xd<7s4oX2GzSqVesM*aGV5m(BCsbVg|^MSC*>y;oD`-0HbIkkkZm^Fkp5{BT# zf6ta>_}e=8Z|@7!eQ>W(s{dDBHztr0-l47_iY*FHO>YJqk`Q5ETAesqGWeCr0l$uM zbgP-2$nB!?gi#|eR_)_(jjO$}WKKXlpMp${VmZe9QiFe4j>ZmOab<>{VhvVQ|Gd1m zK<6wQx4yvhclLwQYQcWYjMWL#GZM(%S%$@?e7BGMq2`TjmBNZl-}>fMDYAtkqZrRB z*|B)wuJ_Qc0h8BTecDQY9iqhZ687R0v^{eAT`Uch#iO6}g*m(I`zt(+L+Hu)#b(`u zfUmw~_lEIG=705lLWdWm={K}kG~&9hquW5@`clQ9j2cnG8yd~NyK+QvHr(1w$nX8H zt7_PTU{u($HV#@1Mi^vntn`gkl`P}dj6p6;F`!8|t?u*Bt#J9vf3L2Mp9QiP`R#z_ zCa+K5duY)PI|C$B*8Oc+u9S82sifdCMox&MF0jy)+G94nNPp}MW(kTG+fR!-Lf@`O zge{#=;I3&-0Ff(0qotemJF0mW68?5yZ;HWz`!W+=Gi0L1RO{=Xla_w$qE&db@ChP! zbc7jxjwK`Y5ghvB=q^?*FV&2lwr@RGuO{MkYfN{?^UQ@70l#&Cx4v+sqF#^602^-7 zGy8&xYi6HZ#uuz$POy8kWxLMnQoSBCh6k6M;w|wrIuK{<&BNpE*;HIYl5&iH>-4Oi z(fonn^jIK=eFp`cLU(7LEp=<d%vnP)a!`JgfSj0sl^;vZXR2H5!!63SdvWLABzcD& zz#O%{bW9Za_ekMT5zD{7jkf)Ry%Hy_nW7zQnw&%B@<uYgsSno$8p{Hd?6IfV>1B5) zv~=6my1Zerzo2oc$W3fT*`|Jfe8PSihZqnt`WQpv-GHc<HGyD8SyqUv5&pwMHh&Ts z5m;2X+V8ua&$H^$U#=dO;{kU&HA@9o3;M#U=v2H_m5huVQ$46aMt3Q~uTp*Yd*EL7 z*%uUngSCl3==*6{5sH5h+m=c~7_Oy-p2M~ZzA`^e^Q@IDfts-9O$=e`8v#$h^mRdO z)p@jgAp0Ua3*+2k*@*g+lZ#bpkqr^XN%#-qyk@@PAOtW8fV}WT*yR^B!LB}rC|cCY z8vOZBAPUMJvN1_qcyexax>gvjuH$ZTAf3;Prr3yyL6Lqn4ckxYXEEZr^m|EXwrK|p zjMa)1ty!XfJw2~-yCDU{NIol#5ep8neOV#Usw0c&NS1IVw|ul#E<A#UBQ#EG3@)>j zj!6SZirt~4ehDnwvQHVIm&bIh^+;G|o*AZBte>qD_aAwlgmSDh+;gu(9=l7E#`-00 z<1(kWoNczTei^)<88wM6I(TgNu(aI(K&OFrlko_YK4;Ud@3X}<jDKEDo&){Dg#V|V zAj`}c?~zSS3G}2B9xMEXL>eMrBKb;r%F2y2{<EpGuf(GW+VhVWFNx6;O@N`v@`TeG z<kfv3dZ?1;z0Pd&F>whr;}KaS{g14b7A;(F%x83ut>A>^oo)t>r>OO1x>=i@1l31E zNv{&Hl&uFu8NF-D={LGTo`7>oj@6f`wNJMYUg$s}#?jCzNk;pV`3XMz16u1${2NOT zx#9PXbt^t=tt^Q(+bj?C(V0n_%l-u~f!9kG^X4&rG}j+OUpJr0A98kSXwKI{*)9t$ zkWUfnx-^`-@HCj)IcF#x#~AnesEdBWDuDIBvVEGH?Q32&URbS{RpOg}h11;_uIB+| ze%yTwT_Q~E8a!#wXs1V%ucW>W@F5`8pEK`=Wih}%ERPm^rwh+B|GM209{*e5z-D>d zRlg(h8s^-xJM*bp?HkRbfBK^Zg_<8a7FkTsN}Ql@zVlj>W`1Nu$8P>3F)&xNyFew# zY;O6yC`=a0Xw%Xt&CodR{;=FMM~(J1y32`Lx!3|tdj7Eb-S$ww%wk5np>9`Q7vxB+ zlY%#gzBj8%F>(sdw}mV$N*Avah2++1uLg6P^F5-K=l6t^Q!9CDX&M@|W_?rIlHVY5 zg^XE#)kji|GIkx-Y*Fw#J}lU|47;sbr8<-+Kx|$|dp_!?zIsdg`3Ks4I;UEGMZs7B z85hPeXr=3h-;8jAf0o}JN&LTYB$6_u3j!2r6UVw08R>$$<Rwwe<yWmWG4rxRC0<=F z2C@)2@&dG?ei8)g%P*@NnBctEtvYd96bEHwpn2!b2@d?ZbUxjldIDU!d1N5F2iv@Y z-4KZ)8yXOSmGuE376?-6VG^b)8#;S2N>I$sQ2TA1&P1d1M^gOs7w<b*;Pt4O6uN1n zW*8@r+-evX8Sd^O(kP*Xgj6;4dajsZWHa3?6vcg^2_hH`!OE^fC-PP>^wg-lyFLK~ zRe)JQ0nc=U=xy4cni`m%%-MJEdc*PHZlF-HD6gg4^>}Qfo5@tWUe`u(;~I}$|H-^> zk<XtuR^9KuH0<;vv?Y}T_VH<odHfR6PR5V#7((SjZwz#db6Hb<G!_DZ!S(q`v;Ze| z{L*rlOE)RN56&i3chw2m*9$H%;g)Ulox|lLZB}izFm(TZdFDcGD>s*63Lv=Ua2!ST zbRIfnd*bUS-x3O$SKCLF)#z5md3Jx@Q1<bzClBx0!f<ewVbIF_%T#w#x`H@&!pi&$ zsd%t|M-KB<Y6F8IY^{mnqTaatDMI`V&p69=pzwI+R?(r$i;$})lntA44;HJDhr{cB zAb28s5)b#BmDv6+=&x)EAMMRo>&jQcVQ{7-Gk9`ME8hU0QK_u`MciA9_`qdHQE2rc zgRb|@Xmz46W@M)hKNm~X7I~+e0?kLE=OyIrQl4D@92V$K=r<ALh>zcAjNX%6lNXv5 zBmik3SFZ$5?pOv%y4-DV{CO}l5YC+U8KkrROdxK{AVqi5$i3md0o9+PWMF7fi3e=8 zrQMi&AHoXTL*|xP4ckS|%2UkYWZRe&Ag@@8ElKKjJv<(|8%9PkybAChSSnTZoWiT; zwM`nsN@&2b5zHrv4ziXi6cFcL^Bn9R&N>PTT3uiKX=zYv-oll^r7uGfROmKRTejBz zS^odidHmw^!GMJ@bV~ThLnK@x8Q=+N)kpz~v60+D@nJYDQ(JkELJ8t+(12Y*G6F>h z^7;Vky*LeNTJ&7>g`~3r;jieT_;&CM0kanJATwHIDYC`^7>ELfn&I8JAUfLK>#&CS zFU)Hg<H~@7xPmD5jUnOI5;+z!99Cx$x-hZWi{dqJLta_M#(`ovk@*0mnfQ~_6LYMv zusU*!X}kE{>Lfc7N++_RX757i0|J4{JjOz2XQ82oA8d?Rdn*#FYJ)MQT1lDT-k0>E zW^YIvOCzM7CczCwhPruLVX?a7KoY9;($gMg;TkCoD`l!K<eG($np|zc@B-Rp+4L4s z;oUK1>!p|W0Y<Zu*^!S$=En&qz`{SSwcDbrRCd6hVSZd}pLJ}h4T0IYwe`V6gZY5M z_TcH!jhDq3&&APAQF95#SiEY7iu(rfTq5z%SQB;Lv+KbinSs^rImzQ<zJO#-1?HC8 z)zCe~X|%$d_y;+8ZPy1!o>!YOi(g#;S6z>bJ*#V3h;6r>oNq05AYN8J<AHn5#Ze*@ zwy(nNn1g_Nt+B^^bA_9pi!VF=?xw@wbD?k>V<Urwd(OsuRAF^oRQltOZ3o+*>8ck% z50aPm5{c;Vd-Pb*Y(##+ChuUw-xpEZ_=p)F2Dx`#$ZA9rM=v=WUt2FKYf9VqRK7VB zS(BHY8-D+WEB2T52zJmo_7P>q{<_HX<H&1pTW+?o`ks*Fq(n*n9nvGjaBb_>#PCY) z>=Z)jLNpq944C-L_iZqa^14{X(@BK0_vZh1Nl4&<fOIu31A*0j!gSKZMva?{1fRjn z*EnCNUB79@?G@6J2@-R6O#i;GbA3|U4d))Ts*~oO#A}uMVZM)eX>UC^46)n70$~(l z)4$)N-}HW$9~_QbnL#X&SYk#_k4<wE=BpMXwZ|;97mkg)Xna+fx3FN5;T+cFVk~4C z(Kyt8Z=>l<i!jQUxQK=8fc<56|Gy`w?>$5A|D|`D#R30>HP0}j2>pmV2|IXYiW8w- zW{w@dCq>a@ZIc01xXE2=TnK9qf5duslc)1!rx(KkIn=A+j>3Hfqsi-$x%?G`r~kTc z5#i>2DV4?e#|(;SlWYtXpzo$h2e)%sPipZ(gu|4L3WSTBPbS&uX6C)?Z?zR$vnUN= zMH3bYE9@yJ527LrYKf(v_GR#7lv?1zx>$xglbmmYZo7yr>&ckP#1N@|FK2pASEw~7 zK&{+O;4Mm>yGtMxonZsMW7f^DzZmPFNMopHl3K8S^W^6agy0d865-yUZ=6TsrLS22 zCFxm7W}`}4yZs52ssfD-;j;E65l}fD5pfdLQ&zI{sY&~Dm;yBdbH%i)B7QTviWrIu z!e!11zt#<ACwf}?@tQn-1`JIoH#Gp+W$&|busLqTT2G+)Pmb><6KYCzw@NcwlIWU3 z1VRKwQTnfE*cdUWn<ePF${H+QZ%p0z(xSP!pTKlUnpNRgCIgDo7~iSzVE%Sh=)KU& zVXt1BXJLr5K?eBz#G8OrhtvRD0Y9e?(bOhnC3H7Y{^2erl%v=e2n}_)2|E$8rD5aB zVhWjg`fMZ)JkC%r<kak5={lNSnaaSVYiF9>f88(>?W#vBekqEU&K)TTpr6g*G8Kpf z&U~UrdBSP!gI7d9I{Co_>JkrEAvN<Rvpu|5817>0lJH0B3}|_6f@}zJ?g;*soMXKZ zgm^1e`lKx{9v*o29F#eTx;UXV^~|K9ZGamZzrA_6T;}X;avMF*Ov4RNcVGMjm;Nr9 z4FY2R_kF7O!)9udV#L5=z91H&82<vwu7}ragn49^-HlcbukBFKc;xSmYs>1}v*$lr z1^c*B(2R9VY^(aOlefG3EY<WVP97uSI7)&O$%*6dIq2*ptXxuL(*5A@R5h(aZKSHf zve#M&5^p#D=E^<j1lw++T<LsiA%10<A(Z+Z11Q4v?ROkh32V-p*y-6vc5x4a3<=p~ z_?9YFXaDb2f`O;J@Y{0s6b7$Kb{!@+M4l2>1TLeLDm8?n%j+Y|q6&3tY3M3v-ak`% zQ@2r^UnSls_Wb0oB6tsP$#TQR5-Su}j0PJ;u34FXdWx$eY-~e~5yIW-Onl1Pv~WM8 zHgOmx>xd7Lme?))^vyJXD>JMFABsA8{hT<4Sn9;>Qh}beZ))%^tf=^TF)}8k7|y>) z*H*_=v`a_y=+LmF!s;IPGS<&bh*~v>CC%r2s}U^)-a0>F1UC3CxQ(s-w;k!k&S}Vq z6rTmCmCPVoCV(r%AoIl48+1@0qD>Xm>S!{*uv|TfyH*<hM`<mQX_!8)d(j!oHFY}_ zOt$b<OlhHH#{dXVv=T5ClBiWN@A}J3>4=<qm7I1ZU-5vP=Dza5BE{hd=>lB-A%C*| zy=v}VR;viD(|rgj-IV?u<sO4D+L6GN);k#mQ>lH3<1Bv|4iGtn`DY{40$}i9qd^FZ zao5i+6Op-2(_gK7e@NAKH#r5cu>a>|wbiVk;c&ce`Iqd!iT~0)_3N;jmdT*RO8Qq? zYG1ezaB+4R*$tiVe1x@Z0jrAc^UahS=*gU<z#A#NuCuWPS)iNU#Kp|I*N`wM2@YdB zcghUpr!44cofi0n=ueMNaBtz&bJ@!{Vqnhty7&C>1ZCY?x5MTv7p&E0D%NHy%O9|t zEirqL)j^y$wK6afZ(xhU!SlD74Qzmzxuc7|EDm~3s8sbo;p~CW2?ewO<kRC#vc>%6 zS%;gMQ`Sab{daB0SFpcF4E5wen5%AK|CwPaU8p=PLF0OCUtOTKxO=bMwAJK5^+rg# zg|hOJ5_dfh{!N2S*B0dx65~ezt_WC%>yRcCAS*XfJ5b>~QRN!2p&N%RCY?_F_+u1} zfpd`8w5T9NptZ_!u;x!~;@ceQuJ8L(ndL)38+gr-%&6$<I*F~KSaug|JvKBPlxhJ7 zA{8I!k)tq9$c4;B6*3zB`X+VZ8Q#AI`kL=q2>YX-Bxwf4F#SLa*gD0EqyX9ja}L4B zZ{rF#VC9kd1#04A<ueD1a|OAB|M^TDj=lI)ZQL0l&PjeXqPr)|Nqj^)Q7=JP)eR3< zab8?1V^(bVX%#-0-tMW9u=oZ+P&dUo<($td9?JKAHC(_if-wxN?~k4xXT>*EX(6{1 zWRv@2WFu3hp@9|Nw1$eZYhp${!<J}_XIMVJ)#iq3A%Np+zc&koJBU`86OAXpNV?}9 zHbBx|6GEY2kPj*d!4fG^ty~Ei92Mr&%NQWBVy#v0NBju;Yc#^u85_Dn2NLHF(L~Te zJ9EEhfitxHdoHBiupq^LD`oRDUV`c&6UaT3eA-9`>krF2*x^Jc41x`rkBD}yFHR7k zW{iDYgTs6f@{%%UVN@%OYL4D*x!07^eW{%<JRn}R<|MkQ+8v8D`abeG0c1~eGo05P z+8y{=57B=fDTaNy)<Vom4prWw-*XST`_A+Ji+<zcq<2#%LRj_e()@y0&;K^cW2HmM zwd87MY!+w{ejjhL>UiH8FIrxzYGpOj6M#7DHLdZ#-(&>!!q@yXXS^*uDh%A$6FSoY zrGm}(3(TAf%x5F}tZ$_$Ki#OZuehRY)Chi9q-+ZJ=5A&e&CdKnZIlvh`6;t?<l+<C z!9sv%)N6kK?e!nYBn+@UuBxEN0D2*8DxIv+J~-w&aM=jJc|${_>uFK;aA~;q@xi>3 z3r*G-Xj~WR-=1y$HwU<C=cjMJ#Jf;tXfBz3aX?Co?lSfw1YT`F%oN+QH?w%ucK_M= z7ZOTZ$eS~orumFY;1DDd`chE9`V)IOX*fNy)O;v>A}~zc`IZh5WpB@Ze#!GEQ45=` z2#-=T#BYc2*C*#mzEZ21bKnUMVl|)kBVkRvgP`KRA?vS=RYYJatcZC47L+22(NmF0 z2%+DuqUdh$w><Io@P$mUyPVW9DG!D$hkgSCp`0}G8J^eQ-!vCD5H5}VEd2Qe3FP># z9qw1=vDYuWjW0ar^58)_7{?ZF3~nehcuwGxky3|zjP;RQU_|&udP$pi`=Cpm^hHjL zyoZ_m@kfYm&6{i)`RtS=Q}Ij&LTFV&UrHQk1T(8tFi_zurIW|l{?ooqyt?t)QO>zL z@O$aTr_I+GN{{)s6Eh=Wde;}U!ac)*9BxrZHv1bnjH@)x9#b6Ee@1|IU>{@6J7=<b zFrd-<s=QbLV^vCuef|%+z~5StegzuC`vHwm*JPr|M4~2+Uo*dIX4K~*Xj%KR9MNsg z>qv^!DuGc-$Pl!o1RGlOcNVC~>}csoPkEUl8IhotcP3I&TsBN(?zBsVpuHr{iliN+ zS4juxEYDRa=hi^M{DGwLOe|bQYHGXjy-Vqj-5AD^t@8by@a$gBYF>n_gg<p1mu5AV zt6m6>NLW5x>Q5h4m#_}-5QLm~KD7^{!ZicHe`~a<?d(P$DRwk>j>WoBIzFK0D)qgW zJ4TCZ$R{$`eQkU|>wi<f1;nhEE?Pd!fBnb?ds>}_(2bnR`ms*INQDY@&{ql+@LXqW zLd1Q56YKo(APLPvPVh_G^&T+2W#3pDJp0J$@?mQezzl5|3OMh9V>QcR=5g>l^)WYg zXf&IyMWV`mLQL-tl!F~IIqa64Hq_&hD9)<G@;P<qSg`A!pM^f!^8Y<;Ame?K8EQ(m z^h4hV(PllwrN+<a?`rhpFcIr%RyN@`S6!2w(*U14lHmR_a=!%Zc`S7@=&Wwh9Qo*C z8`7ox3#k{*29Mh1Np^wCe`lA|<~`_;|0k$fS(XzTSv_iY9IC>lRtlM%A(`g4^d7y> z?|>y?4ob!B@F*i<l*U~PotC;Di>5q6ZLC7D0TP*7ok(QasSU!V{K|SL%Ts3|2A&3T zq7+@7=vBT+icw1#nd*$6z^KMx>uhGNm)*fy84Ivhk}u8Fx7G{!!Gdy)2YyLiU2H<t z1^GS_`s&)jmlJo9=pEp?(j_(8r8+Y3^Ijw~M-}-P!ZwNTQ;{DG*!olbBSm3Xu_y<d z(BBIV3CJjs$??^rkNzDbRc-SOq2{6Vru^=2czrL}qd#a?wLmVz>T0c--Vf&D%!M8J zLA*B$3BF>JTBmAz(^Kyg7UBEx^zAmD@f$2)6fZ#v(g=e@2@hKn;S~-Kio~$YRdo+q zdarR;IRPn!TYXgwPM5@=Y9S&<NA&db!}ZX9>2-PUP`mx)htcHaHczlpcIl48I=h7e z(UR7?j>^P5788g23oK~lUK}6IiBSGx9gU^PCQqxr?cY3w)MoAWl)CG(G&yIT;v#)* zmR7FQWuD%=USCSrtY*Dqv%u^~K%r2Q(x(?5&9#v$8Wpy-moGyHWQKtY4hlvGgrVDd zEbOYY6$ard4&r!8vF(kWJHqjHDsjJ3V~b+&m`^B#=SQ{o3&Lkgo_H!XCzIel)JKPj zpUZd+lCb&wcSvB8d%Hx1R7?3$dL4FmafL4~;hfW#)-P4Hpj!npkNy`4L8zPVda;+8 zD&1hKm+d~$bA{@c(8!E&Vg}9IUQ5I4GI@jhL4JY9;V6z6nKsE?!+g;ocF~eFk>jn0 z_qKS7<ecW{dcQ!^hdkr@xr@yi5mWS1mFFzLC)0jg-E1t-u(227!FYjf-3sgE?X*lV zS*35RJSZ2of;7@)IImmV4R|9qe6L%kn~U`93{pe%esx8_?o~59^D0TD<zqWQy!V9m zQ8KUuZ`Jk3-nV^e^Z$aajex>0$vvVVbmJnBe{H>l`7Z}mVT4#=?L9t}L1Tfxde+zO z46QUHr3H}t)g^9|V;UVvzuL1qpQgHsdVYzx=IggxJ!o-PU5$m@<)u*XcgB#cq>nh4 zXb!s)RFK;G6VH4%B3^>j(-Vf2i;3%Z6MeFzdEfoRLtLbND7gh235_tN={nuf{9};c z^xS1x^n-v<H8<CiVOMXeHI0mP9t*s;r*t-#7Sy{~^c1X-#Hc7{%BeLcGD|nH3u`s+ z*!JvDX2vAEtT`vaZZa;iDE~XVgZ$t{F7Jz5Gl2to$rTgQm#iuPC7J<49V@>4N7<fg zW=r`6K+=Us3Y|J}?u;<yR7+-MgN~X)wby>a<C)?kM*RMsFr_@JI06t=&h_m^bXsp@ z<k3M;liS$eX^!~5@Nn<AUcMh^8R@Q))9gRbDK~?p#3S@pP)$3PR;u{^G0$INRI2h> zusWpF!wbZ+uu$@f#ugd*iv(ZfB5pfF*))YmkOvxp!;e#yQK6()QGJ2@PK~O#-{%Bv zHxLIcwoOc+Pu1NHN5vYjvpW%Nr*;dG4%f?w(^t^XSeJ+iWnEao{2+J4*QYqcI31J_ z*4B^>T~N<K>nOU>Zn13ZDEHx_h`KIode{pZAw=XCDLu|&pKM*Bzj+UXK7QrnG)!&C zpyXNXjYb3r71rkOSN6$eS?N(XmF!naUr3a(=5_7~z+Jcxxu)+3Ar~&F;b$(4gDM`Z z4}MyOQP<5vvFlMW!M*+obRH6)ws1njJt!2gi*vcA;ql*3-Ohshiv{uh^K(jsuu;vQ z5he=fit$gx8q6B&&WDb>&;h}_-McpS!4mpY>aa%gSb1;#iEG*<_Nnj~R%@WGN!RZj z+-^2MY{NOUYkqER+wJiAt~9Z|Ig&VQ5y$P>+GN=ms6x0(zw*{f=DW;JS{Y)m4f!Zu z)!zbAOI&_j?&j`2WuZfUz>kNB_bhC?cFXC-86r2n!!!^G=YSn2yCJ;Do^R%_T}A^8 zow@GcVU(2(hNgnz=oPE@y={{9EYabj#dQgC{tMhkj~o!N8PBUG%yUIvpbFl)>g7aB zM(TDe{J6;Ks-AT7S-M?FaJ|Z15;uQGhT`*=_5EeB&$~y301Q-a*##kD-4`}0d-}8Y z{=;Qp*P#b(+$fB`N997=;ceu|x^{POF#Aqz#8zZ)+j61l>V0@z%s5#NhLu(r&&@3; zsOd3g6&$>J8sVoYQ1^{P*)$u5>(gS4KOje5LukV!NAnu_*f_qMlg2lbS;De4+oe=_ z*IC+FWkVIKR!$q<e(+)|OA9D7g^II?&Icw2S(3nVauN~j@+}oHKH;G59iJQhC8HsN zBChk7!DQyJB06fn1DzAHXn$<2K0WPahpmtBJYU)ImPd^BTYaHXPsOSUxf8vr4fRq! z`RX0xTvGZ}2B?5l=p2+*m#0>90KN*#_Y{YWDvhkwgjBC|lzE4yPtyg<u1irA2X*t; zKGAsg?oqXY2n+6rt2!+k91xy>cVID)zMzmtD4L|@iSPkXB@SM_!;TLBaGyB&W=>hB zH?fPX9&U0qTbqZ10HhvPRh>iEds7wzew%`~Ss%lO2{y}7D;4WGObBmkV@t<iVIA`y zZclN*wHQZ9pI4OdxgJXsxWZlQDu#|1Q7rYh4rVkG7GgmWLq=`c!><XCh1?cN&i`1h zt@j(;&bT+TenS88IDv{NxoAM4;P>Mj-(M-r;!DWhw!Xa;ngocuz$01sZc&YIo5i|` zq<h6axs=qp=NMl0;SfGy9oeS%tx_{=kWpTvBwvzmvn4165gh=al`KoZVj5c_!4u%A z@}#rNQaEm@iYvui`)U@XHET4}P%{AGyT~7KyCE;RL8J$`rU0BQMafm?!EZK#zPGFQ ztHph=4*4x&fW(!-_8rv;T`t!NZ>DBt-TPh-$NfnOM{emObS7lCZ~nU5Y8BZ{$z34c ztG(}xc~Y4kboe}a=Y87At$7t~$L+p|xK)9_I(Ig}oG`cidL6UTVd70cxW?q`a(5T_ zz`lMpjuWrA^fO`&4Gri~lInTx5L%Uo$nRrwjs0gxAbOi#s#s40<-Z5$OotvMh%JEz zz!3hnZ-%G1!yc*iN!(9<o~P5orw)bz(2v?tFu~svaJfD>v^NlQE>8OZ1^y2A&rLgS zf&gXk%2ri()ZP;#$3})sjg+SPufsuwl~bG+Z(a8lUi+=YP9M$ALr|_q!aKSAR^$+d zdYqs`n}`Lc3o_8z6bgz7g4aI`2{4m#W@v;eEs7RFNq`L+opG?Mo{bYA7jmEw%C6GP z>M%cfV?9f^u(*5i9u@=f7w^Eii@Z&l^F|1v<`i4QX53INjD^z+2?Yufl@V|U3?UK3 zSz4(l%!My~m(=u<;B#r|s0V5O-Dfssdy7m2D%&<4IKF&Q5;(Y(1$`c0m(KN@l}Sl_ zk|yPBOaY}_cI8jLzk2nefj}cFY0b+0<hyJ6a;0M&y@zGjbg3^=KTF<n5qE|2I8*eS zQpa6I-J#%eYX9BG-<k%cGwb8Q$MQlyca6$Wls=YPhkOPL#H>SfDrxgC2GaH0KJxq+ zD^ss5!fyDFKQ*a&%0WG4vE2#iC+Ft0Xc2=FLRhHQ66E*@s&y_|4e^bWIgvEq3H@Zt zbHyTK8M4Kdg0Fk-J;NwYwSlEU-b)f)%joJ=3lWL`GKx0@e#M>P7?I}A&oeWkN30<` zZhFePxonwIl&s;Lk}Jh!%UD*@SmcX7Ue=PxKD=ggGWYHOfvz~?)&Ki~8H?e!$S`V= zk-hx3QNU`|ADXI3kAK8&vexEL1UTL3&^sF{Xg)bHc@MC)YbZxAN=NIu%!yxla#eZ4 zG`!GzW0&F4KHKDs)*)1KOhmg<fRI-@5(^JPGN{krw7Ku{(dN1in?tFe@MK*P7}3Yn zvI=0X`Im+^_Y&*gID#1d!y*KiBF2okgK~r}X&*W3L@~OHeZ(CS|8fR(B{(sf<9;{u zHq+6dpX6Q1%lRI!*07+4L!L1fhS%BhKfN>(LdCLF7v#O*`wLD?y}B$6A0i|||BUT9 z$*w`&((8CMYxE<VIoih=$~DrdyP2`=?<6lB?Fz+5qx$2wdOJ(+dqW>x<Ap<!b<yel zwnLQ7JKXUD{QmQ?{;(w_LAl4Z`?_`Qrox8r;0zN}+ob>e%wXoxXp;PMieTputhfqL z)rCl7e0$zZk=f+gC3hFA{}IGJaBK6%-v|iqX2{c`2cZi#$YA{h6fR$;x#h{xOGx*f z8_zyd{KWfFBL{BM-ypryarCj!=Px|~zupEpv=tQK9@Yj?u^F$vP98kiTiT}H4zyR= zKXDpj3Z<e97YTTg7Aw(bMLPk7n`mJEj+HEY<@zQ9$(Uf(_{}LWk5~`?36HDc!TaYD z5}j12duQ=KeT*kPJcm7vyKH>^6+fp>MVy({T?-l<NLMu$%Gb$^OITnjL+-<`bpH1H zM&97D26$vyaTyr}#<qg(e<1^B{@N%1C>rnQAM$nFd&RDxM_AOqDV^I@;bkf}LU@n8 zrbbAb6EBtuD%m5G@|&=E1C;HNnXk{TOZ^Bzb;~<-^cMS`(xfC^IFEO8?oq$1<vvRN z;>+!;_8<y;jgE1kiFGWMUq1u)=-=B!KlRrwy7kcse>@?2oQ8=LJ<4Sg3G?*lpyKD0 zSW~_D^1NDcBfbLNMV2qz8re}L?^mp2jp{Vi<;B&j@qU*xElKgrq3^4HvGMd<DQ>f} zbnxW2BEhszU&EZtXU0y*IeSB45VRB1HZUsA2oh<erojzm!G<@rT#iLx!`DgB7om#a zSX!~pD{!B-1*fv&^pI@KakX9DhSF{MV<cLjp)bCG_mBzkx8NpQT{gy5zgDeEKG_7L z()(Gv(Ns-pi(at{wA-fpVXk%gHxovTftsvPr2h;R#j~<mo?Sq7`WP0wmm|74|5Cbs zY1|D>aAB5X@pkJacFL)JW~AcFRjn20w{vT%v{~f0S$f;kq1&G2neQWB7Coa8C#}XY zr5~k_ilv;i53I!AewX8K?E8iucBXKjw@_3LgjZai{Fv-;g`z(19i;rw!-H=KLW$?4 z%EK!T(LTsi@**YTku69SLdO*!%B^ySuo<Bi0<5mk1|xD2=(@*rrHdb*xKivy?H<hk zK3e+I#x1__l!NZ!GTtTKg(8pR!((_m>-PS3OgA7b34;BI7ol@keUg5x44tuau#Wtr z&c%vgy}q|ME}K(~C!6g+x@Bs$Q5MaB3Gapvx(2O;#NQ|rx@tcgJnFXpvDtrOJOYC` z)+Y~iMf8B8Q|cpzNcRmn0T|5pnqU8|@!EYqHDmU@Yk?1;AKSiv((yosBP%hCe5jC= zzM8I=w_&}%A8f;fwfIG<#l(h&ql{)dJ4|9$Fwm(cth}y5T|tkwlz6I=Fh_Mx25!?1 zBC7DO{VjkX#n^E&W4d-~VZqa)lha{OK%4qyyBa?XPM0sKZJEf~&7<msWD|e_P03Yu zhB_BD^`C{PcJ2)d0ij#^%u9V$nW`d%QF7|Z#dXN2q_s6i`?nk_?(h<WY8LbrTqW+l zIE|k^30dIi|J{(P?)l0*_@ZM`mK{7m^8GhgQ_T<Sz-ZB7Qh0q9|1N~-{<PA1sp*&g zDbjkcm1H(-rKoXG5URtd!kzS!?|M3bjb5c3tFp0m!f$-yRL9!MVaVfCc&}Q?=4SSO zap4RZ1+)`{AzR@6AW6rXytxW}36pd?%`X)!j(%lCyKtHNoxx;U`Z-3{*l(H3fEnIo z!sX7yI&aOvrX}gaCW+sW!Gt}GE{&!lwe6>~ai~+;YM81M>#MS%ilzQNoJnBYfUZ-F zhTuB_&i=NZcEav!W{Lk0s*@2X{3v9PJ;R9{!iQ<IGIen)z@IBD6VMhXpPjF%CRrTV zvzcff7_5Dxou*L!!|x0m!geK~qLQzzLW<DJY9W12J+ZD$?*|74LQP!aW9srSS4s#y zIm(gZE&{jMZ@L4oi~%bfXtS_0@V5SK*V*ARs6G$7#e9{rI7K(3;=RD&S%QsTZQHi} zy0q-SL@_!z<WiqtVmjt>o8aZ`&UH}zl^Tl4)y=Vb_~MWK<Q5ZgSDH3GOzjVGh{A;x zcJ`7#PgTbWzJfwFJ_bHRWf3xYAMHN)9O4KZcbF+~q?RbR@4u2&PBcyhxTB*?d&){l zELj?iFci?7$18EO217Wa<OBzKO1!|r!ZMU}m(fsEH_jRaiHMicELD)~qSussgf~jh zhNwpzm=vjkba>55RzrD<(=x2QzfZG2%}fns@xJCf!oWWz^mlc}4?q#hKlnK}1s}#B zH%!ZB<12M#R16znGA()DS`DSTF+O3_Ze^Te!{|<zAaG~!`pIlW#Q`yg`wyUN-@sY$ zJnOz_%+tW<_YE#&HSodC@aN>3yRupN{H)F@P{o5~Tj8UXBWUYyX<bFFuLuy=cmI`V zrZMj)bE3PPczuc*SmZ9&*;4=|%--zHN)(_+Dv%x}Na<Et;!=~_Z`?0nEkqY^tgO-_ z8WCK`9G#WItAlQT9x?rMb{-~?@s3hYzkVs3NFK=aV6^)TRi(knr`n+wqaF#rpaJao z5gbADB@f81R_ZoFYDJGI&ku^|<rKSe!^s4NxvanmA&g$@;l<7-$^+j?2vq-7wE{J< z?k1+ekyVEBR+AbKGOx7|(9LWT^^95GTX*}VXF8pT`sgSwF_IL}*DX}`cmx3zC|GDu z9MAC7A61F1BZ@ZPsKWwQP7nl-0w?^?vLbsUK^(WkYyVat<cBQ6Xlmb&o0~}JtKgm| z@M|YP(cw)P#Tc=SM<oeKQZ$c3ha2(u4p_bym`kChr3IqMnLg&J$proV52IXa5I~_? zs(_`=#iM5<1g^7L2Ui+xFi4_x+Nds(Ag;X}4%Kn;G(`5@G)%o!RNVYWTPWbdTDFml zsc{-ST!wlnE}XQL0@<)hNdjNj91q{8NtU`-p=_@_Vm4TaM+l$_jOza&M0x$Ieg7jb z`tFWD2yR~rbpjg47>CE%n>9+*q`(pjwmL&5HsNOs%R<u-3aMZj79n1ara9>hD8Svs z!e`x3S-HQaxQHw%Lexl?F3VD6#6D|eEWClf-R_0UX-oQPVrHVJb*qWtsD%mo$Dis{ z<OZLmKvUP2lHhK3-)E)RSe3V_GbD>4);p>7ZpdizOJ1+cY_IE!dQ#90PAw040h?D) z9~*xu=d9f*Dku@Esk%rrQyQ%XrXCO|d@RUkuY3oD>w2%j-$qZny1VK+IS;!i!6fTW zeWF%tH^8&g>|vu?&+xtmz4sSQN8)Gc<5@fmml&qEI4sFo_?KK~gf<#f*lwwLbY~RC z%3+Sp0)$a*iO}9|$I@B@rT*KCnWuxqskVW|hZd7N4D5>wTCt=!zu;u8-SsC^tSs;` zE3)otR$4<JEnrq%t4Pvta-yXw=_r)dX>BU{utnHmK|?|dG)G0-GRMbl2_kY(fEHiM z7Kw{YoaICYP56){qdimR<nb@;3O1o|57=ePZk=P}xw#suJm<&aqS|g;dVRURnLTl# z6)uFh$)aJ)=I2B8$o((6&MC02XkFV))7WmXVmpo9aK*N5+i7guwr#7iZ8f(2uf5N? zI5+?0ydPtZIlu9~&r_E2v_$**DO&T?Krz&)=DtV|PwsRJSh(A31<t%dz;h?^jj#?a zv09#0rob?FXI9}d`B`x};c1WusMzaIR!*#GR@<C9KUvK`Gmm#qX53a<f8nmX3XKK% zs|W}4EX1~%Y*@S?KBCA(qsSnlAR_KQKE_2y=gG*VXlGj9xs&6Z4zFpDYkX&>qcfz- zj$`Xd|J{-PTTW3@udv9vvS>9uHZq9@;||M5yY+aeeDR_2_~7Lf$BVVmzg1p!Kk{3Q zEWoFbCs*eBNA&~c+?Jnaps=(M8p8~QMP9T^)JlYv8@Y*Ho)mqtx^6xRW^RH(IWU4Q zF3&LSydzL05ps_rtl^Y8pcfko{psc{C>adld-`FxNgir2s0L!M-&?C(JtJU`WuTR3 zD^Wv3;{}WUI*>L~9s!OrWqOIpPu-ab+N?S9Cs#3I7<J`YzTq_CKxLHWR{wrnJJ3m} z6QS@BYHy{6VZUEiK?y%MeSuQ3GOh??kM&t8S4OO^D%sGT{OE3)5-e!VoR{0K)W2mu zJH%C_R828kAbD0Htc&`2wDVQw9@zn*A;q$d5<S(JmNi2f3Y;wqPMjmhTpJTK)!6G6 z92vqWpPMb3lQnPL4_rO*>@RpNvZGmyTZ|P;w={p_>{vj7wID<uB?a}%F!|J~OJ~>E zqbMpB^tJh2_C*~9jfAUs2LF~56VGe5zTC!t`W-C=9GTeN`diz~6g*vc6x1MPeJoT> zCp=Z}@Lq@{=yYgoyb;Psu=>7NJFhLT>B4rDpd)Ew@EYAFDZ|XLwiUYIvy9Q&cpMjd zv$$ymy9j|JYXAB7Aw$2Jpy;ix_mnbo2VoTn`OCqwYvNbK_aL+7LwZf(4M7Qt)(!3R zFQ2{yhJd;H;9`n6Kk0RuOa30kZEr&>4|cVG-j@+7H9-Tmo26O*Xr{TA7(cWcT1IfY zx6Lyz%C#fm1F!q?!dSDy!=m#{46CUu2%~pe;A2|DzM1u;0+5iBs|t+3qYIsw<*i7H z=&eN9xC&u*!%A{(4{pXZ3quXS`=dO<05v~hg172AZ(w*^3R{Y4k~vTz$QXZ+aDiZ~ z5t`NRVOcL71@I&PFimy!2|0loP1Kp9R}tA}7~JCB?YLfB8fW`cT-Y7bzn*aZohSKj z(Tr`6eEq9>SzISP`r|XDU*+FGKE%{y`}zPMX;pXQ7V(+Q%#D}1bU9N#X*+!7y}tT! z1HFtjKMc%jnQ%Nuj^71yzeKjf<LXop>+!M9e67A*>QyY!pX_brO%A#%0R`2b+D8!G z@Zk}}y%p)S(aL(Yq_`KPh71(rgr^+vxT-r4=9Liy-?cY{0Gs)ln?mP+emns2`9(D+ zH<9F`skR=TUK7#5!&;JgMRJ!~Q#097KsDZphzv82N{un?)!E6h1Ee2*U!s&Ld%_v9 zp0=aIrBrBL^B+xH6!3t=rKl2<{Hh>Rv~I}BoyIfJdc;e)DSHFk)t(*5A*Mx9HmRi+ zlvOeTbDiPyjY)d0XsuvWlJKn{ylmsJ^$qt?(aM`?DF+=>^x3m5<$>jUO%lFer8$3q zKWD-PWs^MlDKYSswej%nxBlzPcm{tT?0=}Sf5-ws0CwfAeTnhKo0?`j*^td%+S-?i zcnrDFMWvP(O%bjd#kEopkPPa?)_1?!f*$yH<V(Q^ND$WOWAp+a<8aqTwK(zZyBa6# zS0>#h3A$nV_r8AMmo@v+fbO`iXO>e8cjXfhJN|`mwJ)HXOBxA!3xU%b*3w5ahGN)x zsYQmT2l8yy^7RcjbA9}UjvpCbhlLm%w0cjrJE~^yTqAurb*VVa<yIu`$>AU}UU%nk z!)Jq+TwCDZJ;=O&yg-5vr(%qD=RHj`@Dj|k)0Lx}&Smp<Z6w&^Wd&O+7WjzV!#ok$ zG-xR1QJCm~cmTdin`1QQ%7gN_rL5eQ(y)ym&=Cd_qd#M&%EF7WMYJyqr#nBL6*;7w zr8K-B$LG|JAM31szXGS%nPg=lw5$1El|SfI(>GTZIQ4gJ*^$V5kNwZPuU$l^Ebo{* zLZ>Yv;BzcEL+<NcGrZR}39U6pRJk<^-A;~dW|iD#mLHP3w8a>Y6WxSylaDKt+<u7v z4NqJl!4=<ymT#RU#~b51gVBDS^pgc*t;YY7<SU}I^iXyuAiys)QywdRDQ*=yqRn;W zt5Y9Bnc@)KTZ<jbgAxz5$JobblagSC4e#5?;r@{X2#UPp0D3|uZH6XRD47L8Wr@vV z`lPX6je|wpHw;_`Rl#)c?>a7<Xby^nG<ds0uyf$ah*oR*>_tsuhu#K<bd+(Q!4(kD zXmq|d!sVVUjeFAfSIXCARKc1`d#~#M1+-)#W5G8qX8aT@A9pH(*SqF7#&X8jfRvJ3 z&_C@jj0rRv<Z@xcB}U4#986C?*0V5O{!KFuty)qcGu2{s0f`*nZsXipgpo}`Y_Vog zeH7*5KabCp{!}KdH=2Q{w+Ag=PQi={M~sKZWj~*35TrxSiUC){wKBUp6}xiqDy*$2 zEtC*trDWn|%vXbsKfCe3e2*6K9-dd8S+^Is{GV}k;eBEmYF@u&YlYog12JsTZNlck zh|&!;A}D#!zZ*BV4O>o)Z_nWJf&PKCE3bUd&{q(?M=i^b5+f{V4IWmT+^mutAgP&+ zsq$93IA26FZtx@5&`KCfsvp1-hq3khrQs7ZrWSMkPxrtc^&pZNK)nFvbIy$#>-%A$ z<9)<7ZX)%be9;idn&B&8^K;%8Lsjc!)Y%LwU&^Yw0L|!VBl=oO_&YdwJ8G>`c>$eV z^j$w?pO#KW>=CY&;j)JEetys{@n!<7rf%zk>)XZd;C#pBxIh;HL&P6}n;8Zea^62f zvokIr#PO9a{W{<BRh@6J?QCYRp#EJ`LUN$hO7ceC(-xd(I2RHZ&kKrnt$_z#EH?ML z@$U;Ou7{~-wV%r@UTNly8O)VYfjY-W%(XpnHSBs1@1DBCP(nCGDNfP>tjqfO^Ycwd zcd8@FQEqSU9uD!-O{ECdP!Oll?L}?&Sey+qXT#5@U|9Kj|A0TAn*JU(<u|z6WlTId z-)_5(K8v06PN-U^cFs0<7RbY$H@kZ8R(u%ec!Y(Z0zjJ}BT=maHOnfj2^Z7`;OhCE z#x394fZaa6ZYzN&7FXa=$DC#GC%Q!RvzHl=X6qs>fJG``A~=Fsq6r*hyS~v0I$QOU zq2Ab)gW)F@w9Zv4_(AxC<dnJ=<?NvV;O~2ZCXCc(j##RCoOpFSYngO)DGwx=%u4hy z>r=V-jue1b!$t7eD788NzF2L7z4h-3ana4S*?o6&DaW9MclvVnZLgP2bwfyhU)rum z!vss+4pDEhY6AGAcet~j!H!<FuD0NCE#0z-e5AV}*A>@YjK4;?R!?Fq&CTWD?92v5 zg+@;B{@Zh695=yk9N}=7jtfBQBO$n;4=bh9_C63V5{65gQOkVj@mD7kOl}Y56v>U$ zQ0Vo(h*czAHA`!i_8OI^w1$KU%`&8oqmgV-m~bw|Fn@TV(g-w}LXZApO4ZW%Liwoa zEs%ght@$7T)#{;z9?))}c`GH}DW4eiKl=;DPD%n{ef$5@2Ns8I0flRXc~D`S;)0|= z3^2S+E;Ix~Yp^Ulk(eoIe=0e1G;I95f}&5PJrspF@s}0y4d8xgKb<LAn&K|X+e9G< zv}8((el##WM6y`ZdwI>imoEloxu{U5rK+G!%(%SJy0^C_rC5>v8#gTsQD&L>06%%U zBtlu4f^=i64vGkgZ4GxvKN3C?uwk%EK6m0k>g2C_+ifHMhD-i<ipqS1xG)xs)5ds! zlFG4lhW}{Zd-!CD<h$j9H}RUiU{>dT(`+=JMK!|EKLxJ)ghzMZslY`=>u5u}5)6*r z-St$FZ-V`D!G}531xGS5HN6aHv3i^d!nFKy8A;E`nSLXSK5lTEOHU{W*jgC-K0nRK zhF_WA`%i1>vNkhoSr?n_inndNvg^Y-pra%3@p^TZxx3`t;LU;}MAq{-5nhF%?}#l` z>hUzTs5C{B?G&PQ>-$%NyCrV>Wp$goF|%n$$_ekT-*JU1=upfQuoo65bt*;nITRcD zNNkH&VE>+h9L9noEU^+{Vmy_;(?{d5N0UjFo49%#n}57xDNN?^ovNvr<{Z=7$S~%3 zW4jQ2HM9ez1L8q<h^um-`ak6h*3QmOh)~Ygs`{kRf!x~~4&P%<2bT8<g43k>hYGxy z>j?!<g^4b_kg05ReYf)!LVMi%G~MO|^eYk(VAK}mB!a{|?k+1WmFdp-(^89Lrj3#A zw^UE|$rHKZaw^wl#0Y{l)-^AuV}%@l%iV2S7F?Xr<8^p+{nkqc+S`}&MaAR<7I!Bn z)=gCtw)FAqn)djK7Yp=E7PEQ8dTt`@isb`3^>?R-@?iM9AA*B!QYWcbRQP#E@R6-? z3le($h1E4QEGV}DSsNNCKGH;4QT=kHwKM;qS~=PF%di{VcTcX#nlEAC#DXTGqkZ1N zl!pl4#lO(p0=dmxr~zV~k68F0Q1;}2Ain=nze*bM?fHAZz}-lNUzwJc!kZmWq(Xy) z%L{5K=8{6|@=Jx5>x~%;2T7)A=VsosK(Fi>LShX4GJ>6By(x=|1>u4qlV)5%LrhN# zuDwFke0ewrLHQ?K`Cj;$me5DaIbFgGm?)&jqEY;C;E#^hB}_9_G&lq&Qq(%+{rTUr zx*4+Dy#gVN_a1@5nyW5E2gSTuYDfj&X;xVTSy)4Rt?~voL17Ksi?{yj`2zAuM21d? zf7mmOP|3Ohm=%|7(c+fAbk3XA6Z<-PM)k`~(4zbSd<^;?v=gB!w7xKsmsm0D9@fbt z7n1^djDz$4E;U1NWltY8y=dV7E%0@gP8AVVO)IhM&Of$147|y1t(nbit&t3;O0U{+ zwY`M=5(i@$e>SO~biKP794r`pvy9?VwyxLhaOCz3+<2hF?Y>{w>!@V{Z|?dg@HTnd zo-xqBE6T`%-_`ciF}Fl8_K#N%?<vSt6RZ-9O|X~(58=I;l%z@Y@zS9`S7{L8NdQ=) z1<D0*YKfI``)Lc;g(MP5auU6oeVdCXp(?&$YGg+c2uGwAbjh2?sS{X|NZe%}`S;m8 zaL3xK1I{U~FK(MBjG1JZA~%y4Dzq9pRaa>7qyMf=lH;dAl=%Jot>uY8bYpDDl4>q7 zJ*itJANj@9z%^y;q80101nuMLj!gI}jT;%XtWBX6oZqB>KcI;@dP$tSAjf&CleB#` z<qgn))?VC0=!k_FCWYV0W8h8lm64$*C8wWq%+4p<15@-c)c$IPpfQm!!Er2+ghp70 zu&h*&DTm8{xA5%sp1wX*GZQSwBd8<rvs_l}H9jZ@Ytq-oTs`DaohfS{pPAQt93J2? zwTt5L)Aa{?Flt#{sIF#$mi?1eAyp+krs{H>o`r4cDF4wvCEY^lqo+BhncN?u-~pO! zV{&P|Wr@Dss$XPhAEBQ}E%^4+MfZ(k{c<0bp@MlK%3%bD_~e7W{P@ase``v0vn;o% z;1@wJ-bycG4DANjOTh&xVPZcie>YMQ+)y`C<3OcPNWO~l&!6~pyc*bD{|+_+7bVP% zlhefxIi!b0L5eK|*U28dn9l~ryLnOKvK5dL%+bLb=*B9t*6310!#ragM}=W|%UT=y zTWyf`@=9+zJhr(JVKjRfNme>Q<(@S(cnWre+0hh|({=(L`VR?({@`GRifW!Dj*}NS zAbE&^|C_cyzccLg!PDBQ6M7@=C51N9qldIE7RA{VVw?6aLTvIOtjpW!?ONi0_nc<4 z141jgvLQ^4?NMsJdmtg?CsbD_pY2xW;l64k_l|w6?g8-w*Ov20rCHBf?Ix^IrAJQg z!`mEJHdZ=z^oD|G-w;kh{#yIRDS`U~{CPyMhYpza{N3yKiSZD+GP$nVe*)UF7dKLX z#%HetlDej8zB5lk{UYV}-7QyFrJmOI&$gRQZx<-6g|%JdOi&qe?WYh-m;kDOG?%rm zJt-`^Lc8V<A1`QP-RZj?{P`(<+9_V@abEIikdttgZgiV&eA_U!LpQri_SQJ2(XGX! zyJM+kvK@lE=w-bLmY4M|tKzT?*T)_eV_v<-oovYqqKH6LtVbxOe!o&s&kRbP3Kv2o zX2)EN2M;Fi4Go{E#E9@x3NeNfS3YO_MvSuwm3I~NdoVLhdeHNW0yLK5n?rThIwEu> zG0k6*Kz|dvLGk&-{y<Wd(g|6T4o|~MVJjNXKH-f<MD*FbQF-@=lNX-WQmRUq%JGLA zA^~0dU5CPa+1c__^6!t_j&iA4(iNNkAd&7@1S%?I#cD38v`J$5>eL@+H#tiOs|YqH z^O0*v2p+l(D%7FIfM|~3ajkW~&+0=YwX=)El0jOz#&)?16y1;T3Q2%9f?}GQtiM~~ z$kA?B>qIosGayDu|IO#Wt=1<k3E2u-(DDtZME3wuw0zV+Nnq}vm`BGOG3uoBut5}; zXaF?R5YnpyiVF6_aW4r=kQFP7@jMrETv8tiw)fdeHAqhJiam)Mtg9YpY^8(}Q|kPz zx*I349R_sJ7K&t1^m751{=`sic|AQHR)~w13e2S{aikJ+f_GYEc~&#9W5Co`_ji7B zak8<eU=xHRfda(Gzbw2!EwyfLx*&-T^(_ErJS)HcvprBETj8=)2Q@Fhi?1sdj^y>h z%sl@~L6P-?Ul$3!NOMFgOpu-I)cEyWW-w;Ru>;4A*^_Os+f{j0W+SA^-rxj?OI&9y zYP>p&uO_N7&GNMMtTMClx*S`ll1w>o$ZnW!T$P%0Ai{2qg5Q=5wgS`<+u>k$*DP7A z!%#eG(`hDugVXVQ06+G91eH!}y1<6N(~kOC+v@Meu@~;%zUbH%w-z~TIQL{fu$ELH zJ41`Q@;2?!NBZ1ZYiLLuVfnn~bScr%z{gNJGXBX8927ORB^C)`-3>;bD^EFOADcA4 zW9m@WfV8(exuq|-Dw+6nFZ=kFV4;0amQWlsHhrQUuRymxeLUYr&cMLpb5Zg3Vl{al z0G@4wlX@)2yez7%Kd#DgCxJ)P2(ya`{(CjFd#HE^5_guQk`=l|#wsU!qB~!p3R%wy z{-ji~33b<eB8eZ-lX!{<bvAD!F~KYc=QaVuXF(91MxVV1L9dY}mX~{LEi19TEUDcx z*#j1~c{Kb{;`WKn?TGnICH1E9kjADf4dCYcFobMiF_kiI{)J^CwNx5u9%D$Tai|wv zQr#CNYM`xo-z9&kiLZ_R1Az3UA3t!AQmg;aA_B)xucH!zpxS@8l52I^K)vti7N|^a z{M26US0`M8t;sVesHr3*E2~P(f@#sLd<4PGofZ+;o*Lmi==PJD)srA#{5o~j`~v#v z8ksBkp+_}|Ui}NyPQB0izc1^pFIb*e{*AWaSFAl0Ruz8Sm>D57KgRyPGBo)LD)jKf z#woGMYSftH@Ynk#<z5mLK$i7-Xwu7s3NdctvSV3WAto5V1L9DS#EGpj=)aNKR{$le z5_;b+EE#j54(wb_k8&Jdm@urfSgE8A@~XbVTZm4Ymf~LcJ5Pbvs&<)_Ziv|}lUng# z(Wz=R^$`HAN&h(>shSQUcR5^WI^yo4&M5|)<JDx6ZLW)n_!$d_2NF)xN;lUJ3r^nW z3oE9R6KSrTY}W)fEc2efl}~<C1wtNp8|dFafjV_>2$P|{G2znL{ohX}Kr1dt8(b{s zcZt`2;MJK?610Rs%`t8pIv3^jV!fuw{+@)zIjrT0%h2T-*4s5t#m`h{0?h3|UaY(< zr!rITGr(qZHsT+Q>AXABQx)DI`EJ>c60cJz#_xI_Oe-b=C4jiX`7x#t=2!X{XK4SE zC%qGC4i99RAfXs|MpduV_Y?huh5h>PNElpl@p94LqH;Sr><z@VY3NxCekH@Y;g&_< zX=huvfX2x`*)@MAIO|`TDnl9A9C<F|A)<5Qpi`tr183bihf%r*7u$8WGG4D6J#PZg z!d070o_>Cr0k4iaI{3KPE{DpBsVFRr-Ikvlwb^Yet}9Ylw#Sd>RSIOY^KBDFLi-~) zk=7c8uptJ7>_hyf2*AYLGr5cy9_d`aix6MhuPD3WJf*fa#7WDIMkiVy%$~q3SthNJ z5TQWq;owH;w9AZ|79rj%cPJc6WjF~I|H6eg`e@ARLYt24L}NVCK{wYIKK;8`KCeo` zBwjX_ahta~QAYK2LpbSV^$nTakd>=6svhOzuZq-w$M_vWMK`U^t;?zfTJplp_a7cC zY)*b`#=|9LA5Tjp*u{oj>4M^>{T&upX2j@*L$LGBX=)w3-inJ`N`Eale!<Lr&uK=l zsAq=^v;3{lOyH>g$*p`6|4{SF9|_C^VcOJxmgiu|Q{LB7-xO@T`C`VDe@ebr%7MV| zd)ddj>mGqFQ(Bb8lD-@qX`#ohR&mu*`6Kp!lw?H#)*VNLJ0sl73k&X{KmkOysM%<_ zfWJ{gDq(33JXITcN^VLbmZ8~7A6QC!kh|s)#s+D88Ry?5L5U1trC}*U{49q2J?SrS zT1iqj;OqCeGPM<ns2?3_%cy2b1!NI^fm6gq5rM)53%{e;kRyuhuv{x!4e6In88kw; zTgA+jY89jvBaU$pZeUKmL3$Xe(wnwMee%k7$jy@1Hpqc@+!;<7i=KdC?3n}JMh_(C z`EKR$02itqJZRo_;B?E>@|C-SVK3h=i|xva+P)eqs~p8@$*ZeQEslNtICnNPn%_Ow zxNSdwF&-Zdr^Y`l=QfWtU5*-m==eL`<{d8QNm5IN2E0hK*)rKbtlF(_o+NkO4bVO1 zfo!z55KFuPb*A{!RFt>~jHr4VM2(xco5rT_CryQmhlyo%j6|5P<b4ZoGbKkS4Ma2S z;I!d<&eKu0=?+raSHTec`$S7h1Ds@{mHR|A=p701^Ti@zn+boUHsraXoZtjhz5x{b z4DPAEBpLOG(;&DDHXHP<iS}kYl}8yZzTiHLDWHr~SgBvF<dZkQB$svvr@Ke40P3D* zJ{=;D2{Ka|r<$IzP`2?+058oSSEd6Ym<&@0-geEl{pJC91cgirUSS70N;G`J5}iMb z)tI95?nM)6x`|rs!6Pfp;E(}olf`AU&2!&@63o!zWNfE9!!-8Aj;eE1kmrdL!tyW# z*no^p%{qZDs{oU*q~z~uqrp`cBf~PgFF)yEvDlu#qL448x!MbAlQ7$HylzTwMk`c? zquI(l#Z9FRi1qGJXKz!-84fRmGC#X>jg!!f$djwp7mM(TV%Rl`sx+RgHiL2Cvt~v~ z6{KnnHXV2jFmv;zf8+ha4CN}n5j+PRb6d81{DfzYs|9Gv{IG;*Bqn5@nIBrv)<?9# zp{{-ijYeab*4nP1#t966&FLk%3@LRYyjlCYs{(2XR<(m{As7!W|8<9mf5q&e;HaU| z31G1yg~uhcCI9;?DkfH$2Yo>Z$SCV4VTow{(EI?EtjIa$HZkOXgG{)^7VNLuZiNQC zx2C%&rzJZm2&p)-l3^f&b*QmJoR+RAR>IsY@O3s}>`);s&xdtm2|4T(mW6?Poo$hD zSWueQgi`PXM<qcuC8Efw3As!xXPTYxpgtfAJ1;I^A(Yi^kOV}|PL}>F_B~(I_V4cB z%Msfs@#iHvh*y4y3QIeBNDKD0ExY?90ed-qs6gGm+;8n&bhx*u?Zv&NBe~1BrS4gV z`+)A!2YyaE_+il`X;0|6G+^_qmrnc5<zG6Oce0XKo{-0@TzAp3=;;Sein*2_zdu+7 zNOJs#uu8wcSV}Ti>;N}3wmRon9qk$3+&R1`)plM=&2A$DCmolQGSq3W68gAs^HV%c z(|*eCMKrK_URv@M7wnN*0iIou`xUl-&p#Tj=GwqP5e5B^smyk0v>c(5%8l-mx=BUZ z<6k@mn+nuy22~8<&Q3bOps4eV6!+6M{n46bPzBCaHNc6Hmfk$E;wMIl+4j@HuJV;^ zwO6toAiC3Eo1piIvvNEB*eGGv*sAy3l#v#ExTtT;ZD=*N{{AkOk?mih-u%O`z8(IS zu#hnIInB40_<HLh#?$x3Xk6ZV)#}SkfNmFujLzf6H=Tt)Z|OPHcM{POj!&-c-pxXL zR9zD!{(`pZmuw$+stG(45!2BR_1cm3fW~k$S!`mIo{8uxAwlynsOZxj2?;!qE`0eg zHtM*=Ny0{$to<D3J2HV4<x?WDYF*pViKO*U7#F7<m$0PQE0X-g{iP&;e-W;D8QENt zXkFK*X-o8|PGJ~i89n-mA^nRc&#Na9Zr!~U3(I0_xumw>rB&^z^k46as9;(O1Js52 zBtr`<{b*CMK<96WF~=I_ctj^-(jxI}&_YvFCd740v;qO<q%)_vq8Z`Rf$3&!2fu{U zgsY2+ZalY&-3BuqkY8fTP9X(~zCcbJ@e}hT5Ija5C1?-TV(~xd!7|W?k#14A5j;jZ z4_aJkb;Z@ORV2Z~fx*PT3Gz7=rzI`W7;&r-ziy9zWvUrQ2<*L*1?(B(XpE+E4DM6f zEl{9;&OeEh$GV;NyER_^PH0e|m=c2J1ZpInH^3V_k|j?~PMg@Gf4Oz<JUq~dba5#G z_TfN*mzOt82}ry&l+J>RnoQ;la?|G5+`z2_kYEsT2XoCPU5#Zd-IL4kG*4YjPOb0! zMAY$PbUB$keb72vT;WoB>Oa<qgPQ8y(3E>ZOZ8HTbkk~OLUqyl<I+XXdVW%|b@O|i z*Y=G+1QUDal1_}4VSW1#*;dW6&QzAWBvGnk{pw7^WN=Q7H&nZ|x7P}oh3YmRF@B_j zz&*mL_n#srJ-*xC^bP`?7}wVNgQSO@nWE{utG9km21y`6dyCIo7xQkBrokU4b$6b+ zgZsO=AkUoWmDh#8eDzPvrCB0ZV(F_cC-(253|U$`!^W+4-A?leYRReWbi8$=XNq&* zWrcsRk(L@vql<t={UU`K(Kzu80q`4KxHJT%Emx1vd?~9x-ETCtG-x7j{<2n?NUuXe z)7DGgx<qg^v_9Ibt7!Vr!uq0t+nT!YJjv(JY*Roz1!oG`S<+XN^IYB(sFAsghNu8# zf==FU@U`5*p<s7bD2`XZdRP4T`kwUfy1bg4J3Nf3B4KY2MRLv#e5!S?)m7rR&a5vR z{jgG^U;r69EAU&a?wE{}H~qFxu9NLu*3Ji)R7fsrUJhhM&4qvCWua6^K2{iko?~k3 z@fa7ZG)*S^QFzA_Qcm7lJkdy&LwJBb>E#)^`n)XrRz;JLZ-w$EMWbuUsX52js8i~e z#Qgg2=$ht~co5r}mZlz&5-S2YrFRx{&UCHsx4dq`^DHr4*nWTdRXY0`UAKoJX~dQR zbW9Mp&n$gsp(3CttwI|ZGlW(P&hq&1mT|&~80oLU0%WWsHjBdIVo2-ZxddFvKz(|| zDi{^`##tYOB@kz02K9O|$^HGweQL}xnR?kbrrZWu=|4>M|4eH@zq=`N71jSsclx4M zCWR9ggxQM|7UW(&2Pofd&EZn59=r1FA?`ieKIGg`PHZ7oF@kQyE+v9|Ie{1C09uJ5 zzE9j6v8ZU?d~kZT&{{XfL@~?1PPK@1$Ohv1C5C3D1r%&3mW`^4aQ1erDD_D(PD96} zznJRDwDWbB<#d56K-xl*s7!!)xan~00I2&H;=m)QI^c2>rQRbVgX6h)M9b0Ion?!$ z?Y;VN(aqQ_a{pVXhpmah%!z9*imuoM4be@eM}}hkiK~YkuXy-7c3aglv)LC;dlzK= z>p}ck5lv^p@{4JVhYH&z(|H&C2V}N2qy4nl*|ATR>_d)Mg(|Gl8zd|Lyz8FI<{wBQ zqzj~%InRmcw1k?=Q2)=gnZm}(k)!w`S=f+AC)YG|JEm`#?mWxC2-b~D?`|KEASXJS ze?f|p{|<3wd_~dX{7z%>@;I}`QjoA+)qsrtef_F`EJb(th%B{;V2=7;SVE4bLAjYo z-rzUl%3oEh1^Nb68fVKihkJ8Kw`gdMjbYp0IpYtT#1$Rdc#WqU2N2!$?a3b=IWe1% zcepRn*aTf>N=|m;73`J}*=P3FLdy|(BN#p<lKry32T?-#;7HOh9SG1nQhSa{m;4Gm zpm-p)WV{fum<bsX5Ua*DR(N;DgzS8BORw;FKCzuXa?KKz#Y{BQjr=R2gL%M95M^6h zeCtlB?x!e4n$L`z9KYJGJ(||xFZmsh>mT;7vd`a7%_>|eB7b!@^;}RCb%gax0$fUu zIwE?k<GeS?sqW|K*9Ev?C9`6EjuRa2TvIfXWsSu(r>;4cV?{xkcz={0E8YPTQaZ$v zG3_$e`nXusMNyryu0GSF>>9RtCd*+b3{(1^cUPYB*b_OPZk!NcjFq(qio<{lp!m0x z_cQN>LdveM)CtQz4bZ3|>5(%dx5QMB6!{0oN{b>zQz2@ZFexY+gKQDBvhJ*MlooE@ zB`H<IoD0{;#MWO~I!J=~jovgV<gi1@IUslLKlB>?QXduJymC~2>O7?Xbq;(fmy3z= zph}Rj4&@_Syd!&-tPyh^p{xn;@^<wMkzDR?pXOXc7Xkk&djcE#|B5R$uDwFh{1HV1 zY#L&HcwR#X5$$CQ)1se<lfEicav91Ku_KSeGX*NtW&3q&wWN!Y#*H^h2U$E90z!k! zplQ}TxFFk!+r&yql8^O^G<5@INm5cJSn8n7a|1<a36BSvqo6@zx!z}ex4@p7*>qz8 zIG~pO`I)bt;cYD)5|Fnj!1lE>@OAv7<u#yj9cJ#11>`aG{wYilcq9FkhQ!TrimyH0 z^TJIy@I>1MMxT;5+?abw#dzQz_SS3!f)ID<V6y$C20Xwf>%MsrveYdeA4Y959G^!K zzV)y7{2>x|;(d9LC$wo^%zrG_$a1CgL<FzTGe=2HLT9C<O1;;a%`f_ZzsuTe(rT{u z+Ri;QnWh=)ne3^1BX-jQ%lPJT;pbS}wA3Z!kDKtfZui#lBWfxKAwZ-i*Hyk*00hIU z1HSZ{DtACz;|So)P&O#gG!w(N{F{!h(Ku~!>}AcEUH&K4#%9!4<uY!FQxl`%46q`R z+@$yJ`uU?nNZ$grvJ*<2o2c|<|HNn@oSveKL~lqaH6Fepe(c=#pe4=K$k}eTo2J%y zhgs6$J~sQSPlnw@I{K#j+x+W~jV_pMTfI$+(uT#FS(9zDI)YJ)7RWYOd8SY>F4BQ8 z#ae@N=8AQ>5u*Ax;T{<4PF))}{s7uq902+S6raqE<H-3L>&K2iFz4*B8$&Sun*pl> z_yoU}d8}96&A24yRkhhaEy5rmjFmvWd;#3*TCEQY7OUL=0N+}nUID6E3GXb!a8hOr zlZ5R)V=_nhZIk0j(DNAGayCyD5(05EVM9!FD`po3%|zPx(=fqifrQj$bM0w7rAMt} zDHgD>a3E<cSf>=I79*Z)$t7r+TS78-xMemUH_xs^*7#6LMy}$ASp{<}Mn}3wNkLI* znPv`qO+82wR?Qb5$7LBOD5x;UKduCtddl`&`htix(B9AgYkR6u5c#!-q5@|rMk*bO zlhrGyxQ<SsHI{z%HP<$L`L*w+^ywlMSirnyP$}U+{;j9jw3gqDCCORBWwr;D%ewqV zj0po`n`H|JqmaebCW#h$JkKhTSCZ`Lvoy;sR|`=5Sy*12pGCDCt2hZek;-@$p0iL8 zu+AGcrl3&tk~-z3qhs{>i9b8V>LMI~9Ds4=-NMDk+4efRfelt*2#0H$$ol#XpwR0j zd%xkyctRA}0cW&e-T^lgZOUBt5Vy#lyRSL(21}mv2Y&4W^@nphUMcrz&93L`TFT^< zYP1e0vW>23<bxZlWYK&h)*vq#Vza@=N8jbCVgJVdySOc37T>5>WzJ^2G|iQb8=Y1w zq4N<jA9BJAY+ko-K}pRMh~kKdiHomB&c!1&+2(2)GvE`h-92Nlu?WfRe>MTflI?8V zdt6HAYy;Ws#r=D-BVaZSGm2h(oj~^;^%e5~=B|r|5asCjO?P9*n9ZGJ&tLLPDW@(X zS`7)#DHG7;BzT=vV7G##q7`Cp&-ez4)rI&m_df>rZn&wrU|~kO9V|Rdt$$19J(CDn zH7y|%T(7LJ<|LEM!I)@G=3;3x8>3ml`Hl<hT2Yvv9>4A{$YRXP`trB=Y^fQTQmUQs zTV#Ms=LR_UWQlvomZjV&7gEl@l^@5!&hs)4OLei%(>VJbb(lCzOGezexWugd+F5&0 zWGvQQLCL5rSR%lT>0w_xbY6cVWO&!8*imelV5v7*4NXk3kYV#y+>;K^4&C+h=;IXc zWBNE35={${=EGz5ab0=eM=6-#ZRgBzmS~Byow6vx_xC~q@tbt0`V$bARR;G0cTp@g z^D9y)>m0yy5OH-GMw?C_Oqk6-1FC>y@W3p{UvQRfR-%6^n$EguwbGjns!)pgC$dAO zxrp2N=*B63)={-FJrLv0k`qm&-rG1?H^~809xW{X8F*+Fll)p*f^BHJ3SR_Au=Y;N zuHKMa&gGJx?TKL#oKE5du!D|){OdIkV^8eFcJcoI{5RlGw^jRzt^Ce)9-XYp3r=n; z&TWUkYYS8d=|s>jNa|5qc<AsC{BKl0c=30G5x%UXM%Xy#9#KuuRw;jw^9UGo-S9UQ zeo^xn=;uRfQ)13wB_%Ntrkow?Pt<C&godWpzv6i5sxGhL;E1jX(qfxUYSNY$S4dKf zB+RjAR)`Brv$A|>Z$v>~EaVoUc{*&EW?9m+_^fP(w(I3JO$P&>RIeg86XEHY!*RU> zv19s->{IJ5n(}0GSE0<V!MG^;8!czfS|YqfwbMPp+dIJmI_t?pfdH+}>OUtxYN%jd znr{1ey3j{W{@oPnGoX{`{EmP)vV6Fy4Ws($eJftYd1SIF@YUD)jh3%37K_nI-bs<< zjdk1r=*-<zK1!CMp=xys)x8M^6Ox<K{PA;-C5gjEZo4CKMQSgmeb1prU>)3OXB38N z=8WWiJeU&(86TcInJg;P+wl&eHUeVKvc=_X05|8)36Oy8JeU|I1b9A4`^tyqn9TFu zyi$HS(iM_-AV3{?eo*KJ&DH~9<LY~b2bQphPB#zx#;+uW>$BbUHr}zt=(?~EgJzrU z2~9t`6ASBXLSTL5Wc{xBOxNZ#P!ONSM8IY0W&Mc2WzxIxBb9mG*SaC#(ZqC<?ma7A zN9HDE2Fi{SySbCW^6Z4Umqc%OpCPK@)&di~Y4p#mJ)^bk8dpn;rFQ%oHfOf(r}NPD z`X!Ry1qlZ_BHf5?S{VLtUvF9qIY$W${UGZUHSQDM-$ZGn==lSzws_786JF`cj1+q6 zSF^YT@qe@wXv<S>DuN~)bR9Wud!J`@E!D2>KBMQGRQkIR51kF<Cs-Dy_$lbE@u-qZ z27{%cyChsT^tPZYxBOZ|%emQ=1YhUN^v<A0B@%M}U?B9Hmdk!7A5j*xdykRvZ2zJ8 z_)@C<$RZ56dYv$CgYQcq`k4J{r6U5_Vv?kV#T^OWCO3+YwV#?Sb^LhXKL!2T1WE4x z8nWcP(O8LtU%cMwi^@TK#v~Z{vuuVNA3n;Pgr%S@(XIGDLs$Ad7484?)l{4pKL%f9 zz+C5|E$!^PJc+>iW0BNgO+zUfXogo22&{az6&5SaqO$}L;aIJq8AGqYSSiXtei`uW zmBuBZ9kZ*H9Xi<sOPLTRtA&!LWNB%Xf;t|Qf-uI!WzmCjG9lzdHU{to%ot`+Ty4$r z^N9`qU|$VbnO~v6pD2xyXq6g{9s`eo2+Od+d|xJ7a!ZV8D#3zpoXZrv!7{eFpCk3J z>P4qmSBR~uEQik_t3bX`)lBS9c&-xtSsjIr8;x;iRn;xuZHhy~i;4J0^V(CBn@qzn zW`e|67<>;Bmle^z#1g$djClu(Q0*TNGc0iF#*~Bje$E~j&MrReeUHVq-vXtkq%IS3 zHuH8IOKQw{dj=6F@3Y>QswI1^yk*BdZ1!0^t#A&pkKv|Ta<?hW<Y4I}%t+=VIlCV! z7#yO5+OG7@J=NlVh(>i50q}5&vk9&8MQj%2U#>}lfsJ=&1&}MSJ)CUf+rH4@1V+7` zpX<9|UebSB%4!de_kF-_w117i4tsUf0}$DKFE>xygr441Yx@4BFw(`y(C@rs7VEgF znrhzXQ|S42I9VuptY@N<h?I$otM|aKxO8#Y0jJyyj%>VagaU-XGMHTm+zy@IgBapt zFBa8tZKc*SRw%DUnkuGopS#f~IcKeoch^kVoXgj(8s2M9TewI1^{+jDCc<Ud3S6{( zMr{f0$JBDcaxt{&e$Cv)$?A_v6Yf93`@#t2_*fsEHeAoXX{_duks1HX$u&id&3@yh z7n=X1aM2CK>;aUsS)U!mq>-Mc+NcXQ<p*}3fCd|g=5bzm0&8WjwhSyDj(J082@hLW z30{u!1qJn1AYnmMZx|cHtauAk_4&h{mIv>)sD>Fz0Rdim)Ja6wQVe236A{t$vgSWp zog4Sv+XL2QQLR%&5(8~e7lvg<S>szcFfo>~s{kVQbbL_MKmcGJ_1pAG1xJvC&M!~R zsF;Ll{s5FiX8mWWw2XN?et++DQVBwB$s{U(aFxm(=T8;?nLhpJ{;i0>WbNCxuX}M} z0j2-Bi?fGmI(^ms1LUvx3;fXHd8O*<`+{>LMTLHFHoFrAq0H#=ihH^wah(O6^N`P? z4;da)mH|nNKzelFf}Rl)>NR)a2wyCyjoms{rljpzests+Vn@+5M}FfaD|C-rv>UNM z69M-9Dz?8vIw_ZChpMz_*|1=6%`FV%XN9#ZAOWk@JW#GP8U|pBLc~mHu&39o^c}5i z%jl=5-H?FNvFwydtqtUx*(LdqO{5qz)BwdZG?j_Y7Gi&y5H;SMZik+KI14&I*XS`$ zO_Sl>Ul!l(5?_j*`C=qJwWd<>6;}pH%qGf&17_c*v}x518I6@QAR_R)&r%<oMrcw$ zzR~jHcXaS)w=vjU8j4)C%<Ki^8@t3E%PDP|t8Vz~N#I3#eSfGDIut_UfB-u=UESG< za_O-3$brbA%GrLTrngbQuM*PVsKpyO47<y`I$6l(a*kHb(#R5==27SWb!@~4KmEsq zY=*mMfxg;J_3Mrs^4Z1>kryu45<jTWQ9pNE-?*R!YBkhw?YU1nM{P^A-($5`qhV%> z)HQ^}t2G7Y?iF8c`J$E>U#By~5@JUemhansO^+tV{h}*{)hYhrEZyFNdMgS9RCfP6 z&vR9+l?)2)=%3;Y8;%Xgr=O`fFLl}`=2^BgOmH57MO7TJ9=*&*`QE#X^OH~SaIOTM zSI2io<9!SIkQp*j;yMe@W2w~w4?cHQJ-Z%n0GNUe)L|E%E!kryJrK1cxWjcL7=j`1 z?r6?0r}qvsb^6x!6->%e&*?jhj(g8^Jh!2?j?-qE+TF1sPjpMe3i>aq=GrB!9h%>2 z&;Z5U>5cV_<U&MSSG%vNcQ&DqzoA`Ka}h;Bs~WM&G+%d#A-YFd<Ebue(w5gQ>eD1T zDf+jaxz1ouxINn=ifVPkY-<ps430_+F8dg5x4m^9%^xek4l!Ps9xluget%%)3v>fT z3X~;ke4~T)<=i0^2%u^lB_0V{`gGE##~l!<@ok94$_$#)b)}rLB!7pxlADvkG9J(s z-3*<(dm<#Yt-IsY;A%t){Eo(*o!SniTY0878?|UnKSHUc@qHJ+^g-8mlK<Zk?jXqz zqBf;`60~&jAF6=Ob!2C>ut1v4S;YD{sEwU~u^p7pWsr(lCr6GV94K*D;ZO<r0>$$x z9uaQ$%IP-vojiUf#a<15=5HV27(Bew;p^hio+!@)^0G8Ss0Ljni)7Kp1hhgMz4o@M zD3&@iYFN4%+{fm|*`0e+;F@55pUIKo^mxG?K<{0v$#p?_E3!n~f+G^4R_n=SO`FhC z*2xP2E$7dXh#5b3`?93jN8QZ5nwn(}cfek__!q0umY;n~ca(4Jx|^ci*Fy{2MAXKX zo^kJOg0!|wLRVj~W`28B^a{uMSfr>X?$cc=hVH_%W0`=wen6(zz~*k(NMP23p9NZU zh8l!L)T$u>ELzp?eub3|DKbW6iNKl9f<YK@T=r5saf#~c^>1ZSvpDb5hK>XO0R2nB zXC{P8H_~u42dA6VPCEtTAsMZ^HjmfK4IQRt^h0ay3(R{m0vdmBJytERAW=?z{Z_~a z9<F@Jxt!z9N~nS2s;Ii3=2@fANFF5#OywG0owfJRJ)#d@o=<q!Ta4wq9Xp=PNWToQ zSU1G2Y`>%KT1(H<Q^Ojz!roggwFi{*t^Q_;8M^}}0)D#(nzZNd!NvW^UlZo04Vtt_ zHow+wJxR^j)z=MLAL23yTKK8C@WC52wXZK9H#(&ENEog=g@Gv@fdi2UH&Ny5&zJrP zxcsNiYb~$zQr_U;-My{oD_F2qCBd#9a0m|izrU;L1VQW@0I+(9q%X)x1+%P5zhM3z z0}}89>=8?8BtT~mFWR^YZA8R6BFc!~S+v*mIO82+R-zxJ#B*-#vs&jfTP2Sc&zqTg zjj`=|v)97%`K6m;Pul$Vw{3Xl@yEQgF^uzyIQI#T$q~{Iyf%Hq?2fLFGwH^Y()8w; zZxQ<heI(7j&?d6Ui^uhBqZO*A47#sY9~Ot5kIzv!vc!j5+C^RFhi-*60f^GE(F;nH z$6{_EFzhgDUUi-pVIMlZ&B#2wv%@bmi{n$+Qn1-Pn%JLzKO=$EKs0V={#=QK5#5K1 z2T)|`zgHcv>cJoXt1Ro0z!(h$20QS!|LxQYbnceZ9ElFJCC{6`Peema!Vf4M+eOK_ zu3b2~4xRE0e9?{Q8tM1{gZsFK^CVv8i;XX@e@$v|$PhXNjv6lqq+TphyiJ1}0))OQ zdmeEa5LH=^gXmj{;nzRvl=5Rh-@@iF8mLW-rbikIbl%!|!I;6}H3x$DbP0?;`I(uF z`737dEOCng#QKHH^K1;crqrpC?K?*ZPhEO4U!J%mz0Z0^lery>LIh9JlxO&<6}*Rk zBXMWQZ#2gb>h+&~yRHy1jCW|VYiSasGGDy5aH0fhMyISTaTscTEC`;xNk?xGf-R?e zy|OVD)pkfXDt3StGjWE?J^4J+qm-Y|bRQ8isrEGOU%#Z2nUeK72)gh6PyO9(oT?OF zeEe_ol~Lk_Z?6Kjuu$GK*qL8#>zjk40_p%0$S*cZmQ&PB7<zTC@sXnLqY_>_HguN_ zKhclJ#Sd#w-Xm}T+WR5r`s$8Bbz3N6jXdJ-e|-Kz4;xiNd$KirfLH>k%ZnIW3r9Sg zZySE@bf%N1T%KafZ4MD(IwKAs(5x;CvBzX?sI2`p4|t=d%)C{{?*%J&>4qrq;4J<R z<Y1X=ZMC-r1Yqq(M#mtx>3e9Y09rmdf6(RX3@f-O`9N%!t1I8PGq+mr@8pJE;PeB2 z)eP3J6f*5d0ok)*NQmbliz%>Jo58Hpe(-AsEH||S+Nmk<XZw1BJu@f)BtZUr-uMK3 zf75Rq_wK*^t+2N)oUWvw)=dNltO$jWWPRa9)pIN47Q7NTU#3#5X|6`D{0Fe~R?7_L z<_vFz7(bxX&3rM)LKP!y`XlFc*Mog8Jw)`Eezm(^ynUQPNM$^>zNRLi5nwrwxpm>^ zZod3@XxlQ1GyOm_1#WW#(=Ct{!v^J25WL@fc={KHj#PdR@V*DQ-8)>2J&j`yX;xR& zq<aWO0k`W5#j~36^(}yor6kO;$3MlKPGY%?a%Ikq;n4ipx;mt6=#!fb-8+kgg@{W4 z6QRIY1po#pxk&rg784oevpakB-}#m+$jAI&rQd({$4_dQj5Fx7P;v$N)&NP0e!~U= zc{YRSt;WuXs$Xt_<Z3w>U;5E9=rJ7ok<qJQHdq(rjv(v9@-7M%;~<Gjh{|4EwO@C$ zoSZgwSp`|BlikJN`Ev3l%u(|KRMG6{Zu|?^`DHXXkzmxUc4G6?1WQX+1));<`LD0K zC(Likbk^(F`G!!Qio^ieQo?Z9mCa4RO%EOyFo_fcS6A1FaL}V3O}M|`oc-5w<?7{t zd`wLK)feyfTh{oY!P0q}=VcnJ<1}l7$z(hXm&SX8VyD;443k|99Q-ddigh(2GnyYc zHpWXj^*#w_pMhGM)>k?<UxgAa?-trHnmJc(pY6MK<A}Dux)Q{GHmj`ZANI~G-EyY! zj9NHFiC*U6U=&}e%j%DmPK%tn1Qid@x<y>fk7ePs(t^Z(rri(m7wHW}{_M+T+^*>k z`%e4T8B24yjt3u<HOj=C9_O@Y-Mr6W((V$fNOQgQxSC2^&Su!wPan0NBe((av*0!g zRWVA*r9ARYTGXCYtFFGHBgsIZ@-}zd{1jD{>QqHTafoA}>1LV>-BArc5Ddu2=I%9r z^MTkEiS2JuLNFEblO1&#KTIjCUusLb#@lrMZ`Mfj5Kk-H<K*UU8AJcv`?z!^LzOhl z{RvT*n|MMpACl%>ozK(CPOs@E*Ll}ls14cdLrUVaf4pr%M^jJJ*)@}IHr_?2Ve3G& zhH|oUSy!Rs%VY*y!)R5#t>bu!d;pNtO<K*(zj!D?AP2&irzjNH$($F#(%W(d;?yPD z!-@Ay-p8gz^Wdek_l&biIzRXfHG{5;3_g|rgD0xm>$;x@$2mN3sUb)dj+L6eiaLXN z(Aji5nqpnL&9LQDV}G4=L6>RgXIpV>-&x`>q%9>4ZyUFTpx)fG9R>esmb|rvtuUoG zlq3n_w-}{Qst@;Y51VmNA^8+71D`htXO#e(@4&bvZ2D_MT=2`fNjG-CI)nGfxOHi5 ziRqtA1eGU*re~i{Sw$lD=z$qkr>dy+7m7zAozIP&<~uUZT0sCI4<6_FWGE5)$FOe% zejN;{OiW~N)Tc~LG*Ecu6c>j^D$-cOQwX~Nh(eV7i?=Kc{T^C=;XagN60wf%2D0dO zH+W~{nt}J#zBKUjSMK5!HRX=#7!X11IRzgB<!i3s3)-1Th^DBH%5y}5sAX<G3NEaa z+N>TWPq6<41s9@TR=zy?YA5496r2rfv&Z9v$wy!1ThCY16AVa>2*ESui@~d4Nv1qY z5=Z3seUvnL7#0dVV6MHrqn||b<RqOkw`Jl-rPvgoI2m(1jdWyGkpq-aP($+8)bZar z4-J)HLW9c-i~0>_=^8jztL4#ggspJ>VX@HN4Cw2`isW}1Eh9U<oW>q1H!bdT)$xvJ zRlK}U0A1mt&z0?Gu+`2{1*5}MquQy(Ue}A-hJ$O`=@$`|iX>O0^E}gtvZ}L*-I0~z zxayj+MFfkzIup5w{R><9!y{6HrXGi{k4?`iTqPol?4eG%vmhGR`D3`Y00vB9KrUNy z$9kI8wsY{3ZZU{Evc!gST1V0QITNe^!|Zj*4zRPo1~2~#qefOHzNODCUp;WYLHMa~ zH>FvklEyqlPH3)gGGLKFK_++CvHF0IvGAFw9gTXwU9~U~j&kd-L@-I&cp5rQ3geDe z<j$N_cDBCN(`K=hu_dUKP4JR2E$%JWGJiZA(y4iMB0vpM*>=`&pk_ziq-j?oKD{}> zjpybXv8Ov9$HMiQUENh&_}1ucGnO8t)U`D15@1k}+>_dUAbniU?t^vr)hPsSdm!5> zW<qALfp_H5I%Q|o-TEeZnkbmSpt!zu^w!wr=){?{1UKV|e|1Nwn<he@X7m(hQJ650 zhl{^non+R*Sb8w5%0x=nBWKpEX2#oc1(DtmK)txm!56JHoMVfUCf7A@1N9b`fGC$1 z7;}4|G!S5#6|-G_$I)_!P|o)rFX!Wv5<%*uPT&;#V|sP6M(&K8<?-jk_I=&f)<QKd z-_T@XLqgf~U`96cw8mBI*(+g%utf8GcSj7LJnI`J_-65%gY1XF(wc;K8xzS+XV31% zA@DdZIk&2yXgWQ!l}H_1Kn$PheLqy+bvSC|=Ram%R3*=W`o3@L<Qe~ut#691v<;e_ z*v`Z@CKG#N+qRP(+qP}nwr$(CZT<QFb=ErP;@s|w_i9&nb#+xgG+c@)b#QyBwK41B z4;`z*b%ajf$gK+_f@T173LrfWEF@#%Sp$EF+x4#;ks|2A7pCY@BM9jZcKQ(Rix;^M zx9PH>pL5?3K$Tu9d_dju+yLIb?uU|)9|V1hl)$X=>W>74ilekD9#JIX!$m(Jt&jsx zOeUPI5<f=FK4Z@D%n{q3)<zOsghsHST+%k6dmA(%!{5#z4K%X-;D?$^f8HW*lQr;^ zm0lS&`6PL6ZUgtX))4QuxXyZlXO46b5wL*1&V?Y4e#IZM`1W)0Cqb#drR7EjC0deX zLczKD#9o16-3Nb6$HAJsCuez^XbN6t9dUbS2HZcjGd+h<F|)%8jhH*)QR<?>leXzg z9-dy;ORv?+J~J+@4Pz2@hyt0~s_`7-I<AafH#~V9tnaqC9ISsU{TM&6CM!MyChAA_ z*(cW}>Yd}B?WrC!$Z+x>sY~+erjzt+A;2{=7;XeR%|s;ra;uv?sRg%5xFxTw4_igo zF9VMY*K3&%F;z4j405E&odOW_lmtfW8q-bZgs|>X*8Cj{<?Ejph$7dD<^A_d_kZ3y zT=!s}l#*E$r*1ZBXuqB1Ouw+dtDu}rvNAXRvpkiamstHK$g@tRE)=a8%mQX^EY0fC zT)cX3$mrfJ+!p_yR*9wMYBHwK_L)>=G*ieFrsmo2JT)7K{rpIdl`funyn(kt^mm_X zQ?zIw)8TLY->#y>@~df$FOQY8gk6m-2b@~tyS4I9743_<Teony+esEp^TxfQ9akCs zW%=wn_bI8|{&q7>;77?k+h(&xq%gA^Q{Uyx*{$^?>uGcM;+{vTE(1W8fw=VR!iBMQ z$=#ENfbk}_lHF-QTzZmq0by~;E(pLjJnu<ibSa%<(=Z*-bdHD5c$3?{nsPU3+{BT1 zX7iRiSqM=@sdg8U!BB0wVas4un}0=9W}ghJad~&<Ip`?rVTe<yDr9eP*LN%zE`8jt z61v$ML-bVS{)Zb-do7;&etKAa#H5<Ov0*~GS?I>XWeLZXu(L9Bfmx+kbQbOE{`%8q zM%S>+T{@JsAt68501jt9U(Z94gBZd>(V)JSIVjtcsN^v(7f2fJ0dELTAn>4Mib{wV zaD^q8!VK&~inh6gJCaR7;CZ>aAW$eZWwa+qhWoVEavMKpqA;CnwZ;G7LGZr~$46yB zXZZg?Osc2iKmZpw11n4IJo61dIqq*u6H|itv-(nE0~S9)u^V=huaL`ZjQ>SWVx%Bq zPvnz`;CeWjss;*+dV5TzU=*yXEd8AKazAqk381h@q=<o$j-)j<w=tIQ;$T#l1s>cD z?L@jj(h~M$)+{wGEq{Oxv^h!KK%kGBFk+!c^)HAygIwCVIpEB^K1)(S1e??c7|A3$ zk1kC_&J=2p^C4@42@rlBw4Zd%-PSdU=e5_5+Kp|((cQL4WnXP=^?Uu1@V#`^u}+G( zSP>cg53Vyw_4H}OnMO5&H?Jpr!Nf{7v$>3~biI+Kb?l*rovXlF<#7~;@RfDR1q}4M z%%b=;h54Mb^v!NhNH|KA;i5;J(vzjt=D<cQy6Kli+0UW=1`*V!B(#4yZJSQ7E3`Ka zDVB;vhB@AQAw{8+8BxjAE^{42e3{1Y0ce~7N$r7X=56>c8U`OhDD8F6!Xy?j?lmk? zYh5JC9#nF?PY+W`R;GrPGZU#3T`IK5#Bht$pB`Yy?>lL{C~$K}F!#ky?ZSTV148YT z3`u9Nco+(n)S1Ny2&cW+Vd|+XZb!Sdm<z#o;OMfEiRk2@JlJzjvV8_^-x+b&GiORr zK%DrFp;8vEAFF!^ip^rlT>`@*oo_Qd{^Hqf7hWgg`<~I@f27Z3_3Cv-FWuF39-q}U zx<@&ttJ?o@TvDnT+iJu&S_X{V8|cttxw*X*gi9S~l{S574l*B$kjd}EHEYmzvKk8S zHPo^mN4DV85w3pIDY@~(;VTTTVN)-zD!v0PO5{kLQ(7@ZK6TUD;{E1&Zq@4-ofdfw zvtSsRb{5agLKiz}+WP$cTPB~ux@6FZO6}Z*H}Y6R3lG1}y=`rGaE5_(jEUplF4OC< zR|(H!jnYU}+qgEkb&eZ1c~G0x>g*#C7nz6_0ty!jv27@J5N(glEb$T!vuzE{g#=_D zT(?iNKyV=(ZeEdyX-iCA0%jPa@P$(2^ghv$3x<rmA08$SJj|f%*bpz1xiAA~=x*!{ z-3&1{6u72GnOH<Qlm0`96telA?%!JG&>m7AFVr7yh94|`LJOk)S>*@pBJ}C_ArT!G z;(a>n9ncmts8ugj5JMHuiCITmJqQl5DnVLfz1RLpH9lezw?ns^t^J1f6^d8;G=;`k z12!VUPo(FUn8(VA7=Ryv7n+Jp{E0qCobf_L6N{IM7Ee`i$Y5@%r}9ux*VdMV?5Pkq zk?;rx{WKO$zkW3+`j^Ivgf_Pt1sh3SOk^DRch5qE=aE7c-NKUc<wwBxS_EejQh)(r z{EUGaG%{ST(+xgMaK!4I*-|LDGY?bitKQ24wS<VKj{5P#*x9l%lW2*4=UBytetNHM zS90ky7#7?8ZQtgCdGBJ@u(ndTOfUVN_*F~(YQ9YD3;+;V&`~yBANVvMjGqtwyfSCd z$pMks(PYUXNUXo-Cdt8mAndCEC=xQ(ZX|!LjPiiw;q5dg4<d`*c8B(sf<YcFdnoAj zYEGB#oT0h{jO;uUr<1iRv2h<`fMpcTxTJYS9O321uInt~)Zb0d>{GLLWVbV!Eu4{i z;>l(z-ib}q2#h{CXcN2p8h;ty)>p8R-N6yQq7N(5Rw;xKS*n#UoAq18^VJLGs+9E8 zU^#^eFGi(b*3uTuR%N_1ncK=YQ<5Kb7VS8*=g(6d{f>lkWodW~^<`d~5o%+(?=J$I zcE9Y@+25#)6|Aqjv-;;YQ{otIHXR3EY|=<Qa-AX5zZIjFeE0~kR%bgHox@8ue&j(% zzO~Vv@V{crj!wx?TsFSjwWVc!X0Nw7812;~C(n}pIr>GvqrMb#f4Z5>wc#DxAx^7~ zo8jQVmC7Lk!)(IZCb79^COTaHo+O)nzi^BUcVTC)Kfd1oiKnp|iGPBpu*q0+OB`n$ zFYVOyNe*xeFQ6Z$>L3_z@bLdb^%yoZEXP?a0r7`hGr8!xega4F=qe_Dfy6fr-(&7s z60rJek~ZzCKL0N2eH;(L*%9^QF14PtY0WAxokRAd17J}=szYBV%CUR<;N_Cm=|QQJ zuNkQEwVYmmTddTe6AN!VV2|Th<*Mb`VU4GB%4_`EI(x;;QkI{|N1P#cr^Mi4gtq9u zsFAgXi=2KqVQhSpj3$VO1LGF3ILSkL!9-1U^@#jI3Ig!|1<$u&^h};^c{n&Ck{V%7 z=C87FeDFM7O?WvDB3|MagsGGDmSXkMYtwMu5{(dGImA4)DO?`-ET%Fx4zmzH-jF~W zB?cbYk}+lx2SltAP+y@L2w8N<o<=G^ZcWTa<r`ld3bI5@u>!k5MdRXPmC#8%p|sOe zER0duLxxh#B2a}`tP!I(2KKAQSjjTOV{0INIb}^dy+?<X;G(7~G*vlG(UkU=yPBq| zsGz8(q^PE>q@3cy(#pbVcyQ$f*@$t$D%+#gV{RV!4Zabe1$7|6a5Tu+>B%X;w+REI z&iW~zk&domcG>=Sz-By|hPiqA$!Y4i8YSVcIIw0=R{qme(TB`c;z3bz%ib~G;KVv4 z@K5m)68eQ<DIXgeT&V->iV>-Us3PF2sMwt9iLv6-Pu2|8N2jl-Xa8dD)h=$6@3N1{ zbhEv<=6&gzoq9zwf~HygV30ITRmICQ)qGM7k$<?%_fs+Nif3M7_nC$dC;ieUFWQ8; z3L!Hk@AxX)W9iaSt0HplqQz5Qxvxh&)^juG3xLyCAf#b|siOqx(YjB?nI{%U_JpN- zDkTl~`o%s4d!3mPXVe$pv-eAN=Qua%&NZ@sT?T^uBVbQj^<<Qa?{JQ;!m-7r^69vQ z=6Fxxp_iPWk~_W#`BjFFo1ZQdZ^v$MWDedLO3a_NM4pW?*o9)T7x@NzXBJ(Hgj4FT z+1Yi65ZK*18*c)4Gw&n|X=ontYaO{=)24%H&^O$5v+w*C?d|DB9dM8w&QF@Xq1X-V zu`Jrf_T;9QKF{HnQB`&SUMMn@r`%ROzcX(IfduCn<`BBYs%G2rozsEB@jY;|Qn#7? zg$v~)51Y@YTbHe-1hz|ARk#W$M^R(=QRdB-BmkR~cAgKTsRjtN8_7#&+D#gOtoif| z=uxmqWEe8MeE7e`!RGiaOW*S>-zrEsS&v1KN=20`!oHDJ+iBvTXBj6;FN)3J$3YG) zznMOSc*{Zj1EvJ1BFvp1V)xfA%#5vS9qwE+h|^oUA6pxQp<a{B3^N4&(wfcKV(Gt< zh~FRfFvyr#<=a7QjsNBP<8@xUxagjy0k5d)O=&#ap0D>xzTUyT#$(p<?Ud^RB~?fX z$jcQR;&%SS0=M9#iUG?YR|?(SRqY!F5gu?<gvvAq)mP|q%li2VsE>Yn&lksr!BWRs zdrNB@0yjMif-d!q4e0Fj1xy<Y7%{Bir+`U#ZnngPDuMP2Yv>TlVU40HgM$YX5mD7# zSJw`eH|13{NsvrjnA$4bpzL7k*$S;kZIr^jSMQrkC^7YP@X|jNb&ON^74FHdQ;!5# zb<pmMef&YpQ~}=r&N2OjpN6~x3vNUC<0l>h#!KpB5;Oj-b`z14urriu4whPG=moBc z&qe^W5rU2?Q%Hxw#s9_b*!ODU>n>{=mvds6q2hU>Yh<L<=3qukTTP`@rdXkhWTl~@ zaU=L)sILzUkt6<2y+fXWbq6KaohP}AL+CGxrLSc60gD)GK2DmW{?R7>t6{G(p!iO~ zhfI^Y3VCXTK$3KT2&l#u79SxfsHRwR%|aJK2KM8IaVihoL-+Oa7VZosZb#o$T|Z5{ zHGvC^j)l2)W|;>G7c3rNPGS^&IlxJ2Rp{4E#uo8goSSv<I!F9!yZ(Eh_s=gQFyCM0 z9Qs3QWjr9JQ5AgjHdsr}Iqad=dx?kvp0n|!7g05Ly@X2~G&mI@1HV;HtfPdbz~5gr z-8f{Sb_Z!2YrldV*@y1-?E3HC+TQz!$4)4v4vhUOCrdEPha6S^HJ|5(OPFm_sdv!u ze9*!D%T^)2YMnkcnMAQ)+ZcuXC%!9HJ*3>?J-2IDvO5PCZufpA_1JOSb+L)yUv>1% znYl$k-#uITY$PJ1(eN!-ip3|<EH8Hb8Pxdf=q>uFEf>$qbVK+U%{FH{R$Di!=7bNk zwmD|)^{4SIzC-<a9*dT}{*GQsn&`L$PQmI}h9{lz88Pue%M!D#+X&h9IM&38uN<|B zxXC_PNg=tb_1P~d==vNH8QUpXoofp4%;x;D8!>wx-*)Y`!AQFL$1(PWd5JFfm&s6Y z!#(*PB6&<t<PJ)i6w;A3db5O=n)NwI?o`68bIHE@*=HJBc44g)t@U5;PmAyaB)DfM z>v{`|cQf2Fc;?1S9FEhikt2~~r7pJ#ZrkGBK*;*fOX>=>Y(Y6!)Ho4FXuD;vH^lcF zDXwf^TXef&@?-cH!QE+5Q&iFyX)F714oyl#VcPrgf?D<m6Aq!y@%t;fn}Jl5eKOpW zhC91RlhveDl5yhT=Y>bC#HtpjjG@)=Cd^}rO%66PqZ?AdqYuAKT&Ls2<twV{?S&6V zvB_laZMo^07Z&5wYQU1M7IQo71D1mQ+LL%PesWv-*)7#H<IioTz2YicYj@4jX76<J z*AyM9z_zUXx2fl#mhNiJd;MU?)+X|7v#n0rjc${Voz&^Vg12y5DXpZ2vFq6Y`SoR3 z&lBuMAv#8+ht)M^8cPgkMGhqi-@)L={YM;lrN>X?8te&&6bucv(Mb=`-Ms-H7+>E< z&|OJcUQ(%EX)0FblvL{QP;AK>w{Y<4^2y|}+Onwb7T!c|R7~inX!_{C>(5FcO9sw@ z0gXM~BqhKK(h4YJsJWZA62Lt`Aixj@IR*-$Uq%E_+RFc0i9o_~50v<ogn2Elc%Wt( zO#2pi36{f-(~9r*c{R07HBqWydA?B*GdW#4_u>eXetzCj>q!MED1aO*$(@2fpsWA5 zZ${wQiHIOjpwPQgHfj2)34PX@)@)wTG2vE{q^HS1Pr8<tT2-2@XN%>_r3%GPmut-C zOBL#kfYmyqpWE?WHJbg`C!_Z8A9>1w)_4tms_;ML0c60B`{RRJW}vG?W`{{=Cisvq zpiSI!3EI(L2|jft6CV=B0K97Exxv<kmES8EFSjBFdYU%J37wJABwr>lHc=26eT?jY z2G$``YVenZ%V-er3_OH8&rrysi}V>xz9|iKE!~I@JfLz1G5#GYqzM;X!q*qYke|^3 z3eB&E5fE4S0$>sc2NhEgP*GC#BV$b7>klU;oGlz&Wl%QWlX*d?;R22^Krtw-<u6i9 zp<Jc9M*ewCy^n15WE_+{cnO9DF3Y1S={Q4UzBF=q3GXB;-aeBjW;lEU0Fmv~k*M?J zD!qtq(VZbRZr1$nna2AmnfzB<EEC?Cl{=Gb4;HRP+DIF9!8M`DV>yz03uN6rYO94^ zqI$Q^%DHri({4P6;dJ3l$m{vUzl$;Ytz(=vD^=y~ZX8?;EDFC~ymR_bJEPYYSJ|?I zZF6s}9;?{}^AqUgkaOhoA?t7ZQb{YXaYJ>l1a)Pd*@DrEVX=gd3}7<63w#fP541(E zM1>;--(^lfI<I$?^i?O<*6Snm;<*{98!Ew!i|+?FeoKINOALyBd|TOfy=1Oc%M6k6 ziv69ZC^52GFXq|mgCMJ(9;;qe@?*i@%;cuhtwx1U?aB2)$ut{#k?DX(t73xyEro!7 zl)(MXM0Z;4+(ue6VV1z-gF!>jjjy0QaD3ZF9Hb0M1MZlPJCD-o51zPE4IpN561{`F z8pE_SN&0KkAx5h0uV|@b{HgZzMcv6(D(t;;p0S3Jk*b%99L2-IuQ4v?3T{$tZ^@cY zZ{3k~Jm*oaz%`znlz0a(?nn!-RtXEfMe>8!xU;Q-v3?oQAg<HncJuxz*xq*cNz8RD z>8<Ur8OG=X*yd$+t!X2t&}sX(k)?phfBcUc1Iy+1^>&wx^$7CimNJ&p<fdC)<QwfO zcN6uu)C>l|+JO+<SvapA;v@04yXa}sYNRPx{&=@-Ls8RGAn@FRyPIWYZ(dNTihvO5 zUe%(8MfwsVQ*Bsic5K82QN$^*$YbhY-gSDinVH$&&DlLXHzc=_j0L5=XFM&jtppco zs7jhRR6Uw2Q2Z7SO#g0Cu%MXa%)v?^q<O$<I~i<Po7Jg8yFpHHUHQ8q6P)zi9;kV9 z`3UTwZQ=*xUnoO{!V;BsHEzOvBn{)u3&oFufuvltC8bt1lD0{RcpwL8GAJQ~C9}q& z1+=(r`g<|s#P_yy^F&@Sc^k5U%h2%;(UsHMVf^2{Awv8Z(_+fY%^LxWfW<PUd|^05 z;u+!?5;pOqKc!WF|D9R`zwJcO0o)$^p*?``z)UED{^B#ZrlP@VQv1vkXRT%js*_gz zK9NIG+&kj+Jjx;<s`2dLOorwcgN4q|Z;ABBHFWSH)eOP&yxQpo&o)CTM+R9&gb!2% z-!iZO=o81|A}8CgiLWlRCzOG~Ss;Tkqe0y3U5}KY!4ejq?d_4?DC`&wnnb%)?NR{G zZ1S=)5wQd;8GZt_%r=db=<A#GoW`pDS+lSb3+HO)<pK5v4S~s4_lqtbT*N!m6eYd5 zw<Hjjhkb|~e2zx7;|$f)6m$^t6zJV*T1`{kc75h_U~kUbJpWtx49g+*JG-u0RZ+ZX z$~_JuYuesRCW&(43M<jN)7oKGA-rr0aNba3J`JKIjC)~w)89kwDs|=2AoC^rzDj+5 zH|eH)eGFKx@F>smp>EZ}J79TDQQ&^BWF%FYcDc%a8F7CNV=#jn%NV%(2{?90(2dE^ zP0QT4IWD{JUx{nwDQit!+`qUUACKlHi_Muw4M#!@W^Yx;#4eqyd36qjw=btTa|TX% z6i8f`x>N#L=CQo-Ox<{VF9mRqoOVvXXOzs7ES#O*>DQtKLbn28U9e+OAQg)c2$xw$ z)U4)joFGrLf^LxJ9xc!#n9Ueqy{816@g+^oD!B1<GKU4NUE#44>McsGIljL(og=7h zOsspRHGR7t%U7eTv>i@3wy|^{<V(kG8fBnkD#B~r`W_X|_c=GbQ!d(Oo#|n-GspI2 z#nts~C@q`1fHzVRWDmDiUd1iqQ!8&2{YDVWzrx7AWh~|v$4yM&x?+FSv>|?BV(yH8 z9~L?@YPZd;VU~)GrF>1XxV`AZZx#4kA06D_#Y>~im4T7CVR}=_;XFbX4|@+?v3=y+ zD)rgqdBH(#J7<RFdb)Y?!djXCw3zBOa({OZ9t|CI@qy})akf!p{9K}W98W4ymC=z= zbX^>h&-9^QHDB8PrebBj?Jj#Yk*;=c>To~aPm~R(cIWYFbQj4!V>l(=yP-NWzl7AR ztaRBz;kWFx)u7h?4v~_AIesW_Z-9c$<=>wh3kSOUF%YxnXTxHX(Ojf!Su*YPCYuIX z0~J#RwNKD>I+Wh^(v{vwU=bYxj42;N2Ha2e)O!lqbj+#fC#>_UsnfI)!Ie+gW{3bH zxjQ!G7XaiDY#_lKIHrFR)j`0x^(OBWiaiFLVEk7AIv;)l%hU;dD?9*29hBhjG!m%Y zU|0@9PrZLjOit1SE)N(UjLEMsJ_gV`5-*&PzHu}ke|zW0NNQN&XcyU}$81n5UOl2d z+-;yf50np;lbzjNAS+O1(1lV3h^wE*?oXFUr37tui|RV}4GPJp+?~QDPkP@kJKV=b zAsOw0%mZ%<OhB{%zECgnFA*Oix)9uBA^O7$`iEd3|7~@f2_w%btpxh4(0%FS*L%^u zd%(ct^&hsLIPkQ5?D|D+i6hFdRXvd~WT7saTQjp94TDfVAY1}o<1(ROMWQlN08K1Q zf}^jftd^?0J@z8wJIo*4YhM<WG8PTeF*qQpR~CbHLQgh&5}QwO0T-PVo(aUMO5Ufz z2@RDA4dZ|NuoVL-5z9}X7pe`erpvctstN9AN)nGv-5Y5ru7IKdgVI{tSoPIgV&l$5 zlUtxQPx|gI>8iGQ%*%RiNo?^P$l~7NLi5-niAy`bLP`s6?XvrnHby$1@VQX&wUttd z>X0Cu<yyJz<g&?=q>@=vw3caJWo_NkDTCV9{2PlY1Jm35q;Z{p-<W@LZ4lzAJ`;yv z;;a9UQR-~*>r=Hcdq*nuxOz!qyXf&e|K|iLR%>`b#p_&yn$tC!+dnPkw^^ceXP66} zij$j%q#bmkm*`4|OUd^JL%k2S^)HkslX(X5bP@bw`KbQ3)k5Xz)1;>v%KadAF1jMl zLq>e)Np~ozbdHX+=_E{Fs6$_jP>+yFl3Uu@J|rKB{)y8p1gGgvLE}R*u+2O>82H63 zr<&yL(Z>F*jI)H!!QCg(VUS9bt;_c)@Xl$B2m1VH2tdoLKJUscvjOcj&Kt#m`FDZ( zZD?)7CkNCbaATP;hO11ieY!hyR+SEs#<5uX-&n87)U?OqfPaNs*(Gpt3VCGDb(fyW zLqqdl)CEdLdo}0_zb7dDgLsO|n9&`o8r=Hb0E&P^*w?P&CQAGVM#jf_g@jQkt-E0w z(XV^(NFIU8W$yCUW7}dufDKurv3`}Ade@)mjIH?fL00A@9efYU?k|b5H;(4b{tEef z1J9$uNUh`s&%c)`eD%$~Y*oL{XmD$S`<6QKSRVCXW;bS8OXN2^(_x+;uefVCA3X;4 zKF~V<whU#Ibv(XhtS>ko`GVIcl^aKQEq>c+Alwu^OXYx#7+#!uKpE_V`1U$ta;2%t zAVxt%RaOjd2{Oh}N=8aGI6kZd1I=E^=`gS60kVkxfMD>rbkx2ufQe#xWPlQ~FhDA4 z$w+K0G$76(4+?rWZPrrM5PHl3CyyZEbm)B0_}Kh?f(Z%z21PtfHxx~rK=2>-W4Z+| z>$(3@kRANkI4ma(5B&gz9zMi{K%Y{0wIv8st-5&H{a95*tM!2Phf(|iDes>x)>~KN zmmOHMGDB$JS>lhO_*XT8J#;N@XM3CM9}D;mf=^GK(YW1zh_?b=K-@h#3d$gmm_bS1 zE%k-~REB{+euBL8GuJA9+qdcXu=043`w*E2<|$x<UG<BtPy3nsUEJW<$}n>Q=VXTx ztU&igoruzr$Z0vs(NUM$eSxqc?drQywdk;o7cwxSJe87Zls?#ix({wjlj$+n&s@a5 zaiMDxiSO3&Z^3NGW`h;S;p|y{tiGF8FfkZy<FUqJpVdYN^@cqO337U5q4)tPcsDR_ ziBB$|_st^85Q2o-N?KxHEP%V|wMot%T%&&(s*$N+h#OisTej9_`W~DVP(Z{`ij+6O zAi!ncl$IVJ&PHC%8r+%N<~Lh=1jdpJXXlCyZ##!|s_%W?Gf<8$Z5FpWW-Y!>Y3Rw< z4CjL|TV3JUJfvKg_Ond0o_A=N#CB|cj#jxfH!ZX^jb8Rn-9c$^XlX6(UvxCxN&vXE z_21~#<NcWLR-EscDP%{|Z(d(jO2ENjz`oL$_|p4U*K&Zp&72bM#~lx^EbqIzH_x}4 zphG#SH?}mdpPo3LmlD03X6VhL9Pg0Z3lgnlmXlm+rSJ6eV;aS%P3jqpBo5ml$~V^a zZmo)}v}54Ysqau)<w|4`t2hMR3{!Bg(i-~owIdw!AzK&OwsXP-iZ<c1K1_E{(8I@d z*3TboylVq^DxVis?K;8aK7j#QB2N%9N}GtR*Sh+>BI=jk?t0zn`&c+(JW}EK^9P3N zFA*#oB*}Hu;%qcEcPaFSef?XPRRJO<6YbO7lS?$g>c|G7nbyTL95Ks9S9RybCDO-{ zUZD%rfo|P}Il&G)6pqy`W$o`}grv*Y<{vI5fe`6janH#zoZ1|&0*4R^#M{!L#LHRf zXO<o$JhqeX2EH>+7Ndv9WnBdC&8}k+n)3q((Ad=vZ32b!BOeA<iwXa>1ODV5g|L<` z@X;5?I|K$#0%)oe8>QtwQLf`d_=_{KUH`Tp<DR**Zr}IdmY36x;mhFjg#SAmraZ=> zcDzuZAU<O_=H0{$2SqXPrSUgdlsP!^Rs&bGX2Q={G(I-h{SmZ`|0H6riWQg$^r=Jj zO+o?v^mIu<Q8PZ9n0m{9KXOy8c6cRT1Ef;&wE!Wvns7~j?rzQRKb~+;`ambMy(frl zEqEK+q0-<KAeD-v-*mcMFM^`GE&p-%4es)TFW{Uk7Iy@tz&=b`;1*u5pdg==5t&~| zsi}+%dugcLKa+VNh}9Hgi|P+m-w&q{(smC}?I4zQh8UsDiF;?1Eg!%g!9{-oQ<SLp zCE5TFSz2DERab`bm*ADKv9&GznZYmD8ecn*LXb-2e;W7?giT*Q-TOHW*t$}<-qcX1 zkU}8QH3HUsLVh_5*l!(vi`$m&+szG;ezPrrjqHcH>N8rFSa!Ico7Mi^PEc#3aJN+g z8j2E?m;4R1aAggm&gZ2^@H>MZ*{GU;8g(fsNc+N7Atli_3n{3CD8a&i)4M>VTV8WR zxcn4py812ZgH1BQg8H9=f;}qa1Y^j4)QMOIcU|C$K0=_~?2^!TuX1aC>1yb>Vt9D; z)~_!r=5zCvJvf%#ffJ;1Wio<b;~@qEVgWij4bM^EoY1PEG{1PG>egb8wqfUnj%%f- zmb%`wDb{(;ZBI3`kF_wA<R&+lDQ>fTuOqC^hr_?4<>EYQR-eX=cc1dF#i?ZYCaRrT zMxRbiUQ3FeX@$wm3U_+ywGC#2Jd%vxZ0ir7OydhS?ajMR_(hn7!smz5$ano1D0!j$ zQ-Z!k4HP)REj}Ee6JjGM&!otw;beiB#?ne&8Ko}RMo(sSwr{BU4Pr%R3XwcR6pRKW zr?GPxqilv|^mh|xYpx0b8K#8JbzV=f`_1=~JQMUIsRgm&Bt!S1M3Emhi$klD+#etn z3dPQxC>rb5V)-EgS8&M<wK}*8Ut<e)&S>pi>xPdEOGJkui{)NN>*h4=TNn=^&>8TV zW^H>XANevmC`R6Sg<sC?ZIxK^-#fMUsGn&;#<MjDO!TQoWOGA;3>C;63_G^Ck%5s3 z)WXxQbEeNU>G8|zD36mlrO{@iALgIb0aK@r7V`-O0>u;-i=Cm=C_~lm9ERuP-1XKG zn4W(u22Q2U?~1SU2$Rijkj`cgtGw5TmBg)7>yy{2U6glu^Nz{wB&Myuh_)?9L(>># zp4u|h-Ym05Gts%RtDag@kDo%rOpcT!rmj3#&G*36JJZ!Ej+z+Mj1`QfquHn&-xVsu zDe3i+ZJFBR4>J=uKb-j5rJ%MT<Tb4G;PIldTeWIaY{yPt0&gG|tcI$D?USL6q4`uQ z<VwWWD#T0EL)Rj_i?i~dQMdi*sB;Zm%qLn{`-T5~*}FjSv0)+~RhjGR5hO~er7tcn z&GLIL8PcMd)=*8sbI~jw7a|0J)<4S(vdgih$f$-yEIL*}f`n604XI5{1FP+jg=-*h zxp?pQHxfCxZi61!RJs_ywnFY8De(_p5buxtB&x`LLuSG@ee%xwds`t3Y>j>?0rSA( z33Wt9G=ArChiIqZ-I91gpGELu{^BMhBimj$t8NtecO(N;J40;OI-@Eg0^v#HF|)ik zRC0gg&#OsIO^tvM{WFH!2K}_@Akb|6!LZwdnAGbMsw5tBQ9z{+(Kf6XHbEH7Pc>oq zwcI*V00%&w0^0~Q5%j{@(6_5xX#1U2%!kE+wKpMR8d45$Dxl+fJI}}825sP%USx$7 zE7{nKXYP?EyEisR?Xx5S&k@**BMuCW-4HAg!Ke%4uITcrWx`hbTc?&FN^%yF|5d{H zwJ)29!L&42haAv3tG6S3g8V>dhenwXkQQ~wWx`~IHrjwB4YjCoFDCrE$qPTQ>^oD> zN3G1Qs|6iHD^R%ct6@evj|~Uytg4VkbtO82V}5W~((|4%Hn?Q<^LfZRN|nUg+WAVh z-QN9DUKzSo0W=IXR3b(eu_P5eub*ua)b|4n`lBO_Tyz8mxDx4(&kDHF&VQAVd&{pF zTquN*RZstii?GCku(J(Rp9GuH1))-PSq<U)^8Jy3M`kkflijKAl}AF+FZDT>oYDP) z1oxE%8KY|^6C$Fa=gmR$$T>*fJ~Ih^TrbU>wyMWs8uJ`nqhf4czDZr2b~RAYd#bQQ zKudCM+c>=C7+&|hU};Qs&cEig+qADcDk8q$!|RqPmJ!TmFnd1RQ2xCngZtItncXs4 z%Ji?3fFhEtaBhL*tn-;Kx>Kyv|GEkBXu8^gb%M6`wc`E|Vbhk~t^O!WgYZ2*>W^1L z)jRz68}+h`H&Q(Xp{W%APe=wO%JZi4EqCtdJ~LU{6vdYAz;tQE1>nTlJ<gm~8_hyf z7zFRWzQD6=K8u}A0~M*Gkhy&D9wMxn&oXO*CCRl(LD+rw+H85e9mOWBWsU0KGNL@@ zy!FuVy`~~}&;9rE)<bO?y`OyR9OHfHmQVcEoYtRQ2O-67{@uuTUIWX^-;GAbte$<l z;VXA(u-ci@vt5295v$#LT9jaWwYIYO56S@<Ft#7#Jb|6PDr92q;n7$14|@)ot|k>8 z`n&cvJrpthx<8$eOMDgiD6sCZkc_I3mV>E3ke3f9KfS_Jy{S(%0i2`k533ggk_Flm zj8fE(bS48%AHq|%p;?{{W(RaLR35}p+#Qu?_Q>3&ic~n|KHFoB)9wE;@k5DkRDUfC zc7VWYentC>?3#!wloyB}ne-Uk2CE5m`JaUV2E!^4dWiXfe?cUF{LnKlDy$y793~D% zdwY8k5fOCs<heqL_0`o}f*0(R7p2VdYky~hq@<+7@ni_<GVM;c!?8rdN|)Qcn`74( zzK^{NB#3T^8FA8vlAW}D&6E&SOwIDVSz>t8yefG><wAUai^|DMbU<+L7QMl+n`0Dy zo`~ij2>GA4H;qFh5`TK=BEdhl0co;Ws#SntkKz}r+dz^9b)rsptFocZ92r0k)h6+U z1+*wF4WhqaYd|E%?IISW1m1lET)MO_YH$1_3PVgpFc)KY^k_qHYd{=rnL@f2G?GMK zAw)4H2S08cc4AVhkfE?p(3axQoJNegc?<Jn>c)^|b>sU7hssn+w?=6)`!IodkmH$T zdGq{ZUA|Bk5i)_W+6ub%pcWbkQwT26t}Y6r`YW3Y9ganlFzgXIH|_pB3sJWoKL*6y z2*RR%Jco@vKA9Tqgx7DbRZ>F+nMDYr)ghs5g<arR6sE4bwDIo`l<dFyV)p{Lq@q0J z3xAp01n(Tq6WHNtlVARA%za(Rt&;)$_9${N?Jn1u_atOSaQxGn<1lHKS(JUr`u^bO zAH9t>GpzZh%8P$zwitCmwYVG*?Q*q#KeAWMbc}h~E*7t{f!}zjHvB1brsbyYyfk=Q zxDO5ula@Y(f9c)4TJeHKU8R`rtaXagRC7EFrxjHd;l=HstzSHD)`;(A`a)6fwD&H} zzQCPc5v^_M%A;b6%zpXHa$8hHS?<D)qa#3F<LXr7P(B|`#2AmXTY~A1Ay7MKrvAV= z5Y>PAaU+)7O3LYY=zZ!hkxsM`cK>!$NlTq^;_t)sigIoD%RxvEHa5q*kQX^l?KYAQ zCrL@G+P$+8`_-ya!}p*zEh7K7c8EX4am)zPm`V6ES7MiE??X}&YA7<EMYvcP4RSNT zB+xY~z|)}Cu61OnzYLP2--3Xk)(iVYck}W;^%qJefIzljv7P#-r?n)8{VW}d=$Q19 zfF43vy%jY?(M@<U$3+IYaggPO8xTCy6)ov^WX<I<y2C?w%keLyyg+BlMl#Lyc&Qz$ zTKCffZ-{vZw)2o>Rm*jP#ZBdMn|e;hl#sn42ripZmwC({%O4;!sUd%M*`9&WzkAF8 z%T<x~mFkT)W(EfNMU*Wv-?z%XW`yNMMMXwq38nIdVadtK{{H@ffnf5xkE(EvYTqbd z<tIoG4qw%UB4rx>@hh$de<1IV$>5=tGCAM1E>2qS@o$*9_TUSMh7&_;BL(G^3PgSk zTGG)iwcuR*zm4V@zZoAw%H^1NNl(ZVPgbcS{($P~xPY!i3o5DqG`$GC(l>-zU;cG$ zq+B<q(owYfJzZU`aJJw97&RiHD!%BLfYQ?1u3X=Zfem>g9t<=!rI<EIt7(+cx%KMv z+4QH;@W75xi)%ra*#6^Sw&NX>A>$tDhI<ejo1lkR@*(wxm7oQia6-&YJq<X|s3}a? zV(~w)#hejubogl62@_9EUlYcD3p$c02%te$8FaP3_P&-g@JbhVxc3fq;)U5-ct6Jc z!OUtZB4_zWKA`xuRco8;&o?(#FE7Nl6^`HVTQItAg-glyC)Og(yZ^DgU38WUHiup* zND~>6AWQMY?I~IxVRR4Rbw*#eO6@0Yr_>P<dQAHFwr4qWe*q>$0CevjI@z1MRl$Ac z*=*<%NW*sEnlB5_3}E<$HDBa?Sl26Tqy`fa2e;LwmUxTA0LcX|e>V?;djDo~t~_{W zvkS_#mdL%Nx!y#@aW6}l^Gn}Ke1sFbM!-JJ)nzm2bxxSpGi2e%C+%!XdBH_ph2}gn zu2xbsWv!P~vPS1WW#-Z@uTd-LO^N$vIS<%KdYyX9m3cj1l^-SEzCCTuW`DC69j1&- zzVn^wmY`KJ+`a^Fo#$k~q(=qhearL=#r=h#vXx&eA3;zEFCKDg?Lv(0EH<hr2&mj7 zyYf655vf&D->RY^MtmFq_=m-L_IbnO4%t@-1vKTxQF5^(OvJ@7H@hdLjpF}HuC0Yv z!@o8!UoW?8H$I33Ulun?w;$Yr!6S7OodSzX9vhKa7xQcU6loYenFn6*gN6!7$NZ66 z7K(-{2iEz+d5*ZGIPS&ygNlnEuD-th{`MA#6qvP4p;&q{jrrBSRy>hPO+%ynIL5_o z8?-w-M<gZ)w!NiAu}X7wa}!q)O6=yNKO3E%r#~LVDyr}5$D-x@OKQRBQH|PRJx}+R zciWroPlETGKPKlDEta@kp!WdJEb%Xrep$lindNFS$l;$D+ySx;d@MG-8|bh%&5!t! z7#X`EAaKsB*ibs+{xZ+>fM;WGRX{3TO+ApP(Oy)OD0V>(*OZZHDGP%7R{*t661ui* ztilk*R6cM{or((wO&%#oqwHVYdu?xJ<c{!Ngz04mB3Ig<17B6pGRR246Bq<B^_pvL zn=4_PuAFx)p)@B3t)32(!9QUSKv5dz9uP+8tTAYaPMGg^nzz0$p+dWl4A`y@c|bt9 zGCVyY<Y+)hM3@XW{S--%A&!Jp?pNBpKE(SP7P+b{1_T2|9d#F}ybp`iOfF()1zmVU zDq6L%YFFxYLS4m0{qI8jKYt$qiI@AYM%sUAzD>O<-S3rW&p{q;NoMJZ%BOsd(x$NK zua+`KlIxSYFWbJ={9$B-kL6^cD?3G$)+<ifIk=yGxu(N%JBIOV%O_9xMWr%5z|nL| zWolUdWAWub)4ZCyoLFdI_#}QD%cG1ITh({N{I2g>F5Q!`^NiOa4t3iixGyV*cyeJY zxU76?e0sj}1WdJcj6|}dHJYd{rs*j-*9m<>4R!6pOCY#Rvo96heYk>HPpwP%Pbu_+ zmfZ%V@eq6)H~^@?M4zG<w`%Pi+|Ea3+y>;D17-N1>$8h43l!{6*MRRTI*Nu9k}Zo# zpR`|!1V0_i|H?0Tp3z+|G=!4V1Twt&p~5LkSY%f4hZ+ODL<@p8O6vji$><%H=h%_@ znmF68csfYmw{&7MbE9JAshE=_BGv3cxsbDQ>#@e?_OjoWXABJ~<UemRCn*d>Yk2+@ z1gL($8prAE==`km{<qTKG%9xkC(h*gVRP(!6S{#;hN07HS81|$DVF>Q3yb9{5cKlb zT8ckbpj64A^auQF6yO|e|D+tjLh(dkE;}cuqiCvF#Ho$mabS}xiike$9~bZSue6eJ z@xsIxV`vokapEX=gh0^t&<DsN=?^~7H@q%^=pOI{<Dw>L;wC0erhrR#LlTtMSU^58 z6VC0gul5t9lJr`|GhJO-H33c*5*$yEFhR{y=&k;uDAn2>o^{l?%C#+A6a(;aYVP|P zJs8vPJ((Y`<H`co7Z!CmCg3_8+AaawFI;%ve138}$XCPkNP1xuVQ~b?q&)D82ve7Q zuUAZ1y9F(u%;Qd2h>vZt2S`RXW*RoM`%lrHfG$m&>%~5vz9=&sa%zmIGxt1kmlTpW z2btX;+o}_LT{&t~BJOkrZ;}8?GH&O6=nzT<Z#F?UP;ZvjL3lyE4meC$6YH<zD5EgB zlo&?o2{KW_cT^}1mMrvudX_+J<6tzIa6752y?b5t&2|_pZLRssC$U_oa;N(JwI^-d zy3^a4e*hscElSoK6x<H!N36;Umb)FlaYMC^VCVW8J=%JXLxuI9m5#;w<jE>KizD`A zg{!A!H^Qg8Hl&ASzV^&n`GK~5Ro&bMp-G9pov){Gk~=hWm&_2CQxl$tC2#cjq`9TV zoZEgMF{)P-mjbqTAerV!rV}^Uhp>930;~AcHgnInsDF`!#k-Y-M{>p7C=+M(-F*ci z#EA>4khoPKwsz>H#FmwYv1Ku!6MkYt3eH33wTbI=Tle}^s6h|iG1H^jxTkdLKKm&< z{-3F5+H~1@qcL78GMWkDin!`;6zZgvKa1c`KZ&LRQSFVMoUj~QW{R3t0?kaiI;eCy z_@=}Y3`_~bp^I0nY%b)}*q4u#$~=K|Lz#z|o39XFa$ES{Jbep!!|UjnR<vIav|PYl zEg!Z7d)9JLFY4twzCYBZ7Y_I48<C6u(ayo);qDHYbPpEFN8s}5;em;j^*dImu_YFK zZ(SAg`sfJU?O<o8=M?E~I-FMv@#bJB87GkTyHI2sh>21&u56VUjwOETD!%0sJ18jF zPk^36P=7mv=9}!tZk~(04~wj;XDTZv!G?%wY+|ZQmY6#J<DQ|VTfN{zaSzn?h?RQP z5sa2Rv?FhwP*O3GQ7w3@#d^1Z<YZcH>dVGN^jbrwhuQ>({ne0cT4#Nm->kbCVOlis zbAFN_u?`-j8Q8=iFm-MOqcbir_UaAOcMYDubDeMrGZq{y2PU@-wIX)EI`PLleEa%) zabV)O6bmPV#umD-I0WN;*CD_bDVCi6Sw|vVa48PIAanTersd;B(pj;dGy6DR5I=T_ z09Ga$377sKOwWn57bMDvShUMc!S~;6{4$C>oY=WTFmt&SHpc)|a>&=OYy}`LXv6TX z`&)&Wk?bM93hAtF68Aha^^n1L$n%HNLHXh&m*$20+cRbKW|;i8=YnKQ%2uvUjP%&6 zRU@xzBohx|yfm*s<xJAgG8A&Md3;KyC%DNjG4F=8ZdSU_H+rnqtBH>@)}<#e73+~( z%xAMt*Siwd?bgw-Tk?|r&E`z}g48EfC8G_s<(ihA`UW#bM?ej|$I$$iIbO3X|CV*B z9mk?q{QSL`ak{^=$3F79WxKNLSXU9_RMJ_C@rn>ttauW>z53=j+`6DA%@qWUH94R# zB980C%=6)jzU?Ed!|lra!o7p<_%qghYm+FgmepPL;nPZB>Rrl>8SqvwoQs}*{k`LU z5}0F<Pm6KlYhBMVSe`KU=ht^^NX}3yRYK0Y66o$&$}FvLq#L&#iRj#Hj12?`S0Qjk zW}}EfpnP;H=#PjyKL^S>XRw%Qo8yUOQ3c6__lTpM*YdL`*4OaBELnI({x1#zO7w-6 z=u_SJ_PZni?YC?Y=hx35`O6zoS-=AX-^btITJvCk-@wxH6aN&cJA8);(Ns@Q?x%WN zTU$RCFR{h=_W2-;fjy?H+|rJn{M3A0UKB^$-pX>5o^BMs?+f;l7Uw2L4M{{O&X9o@ z$UBi6nTMZOXZDnV2T6mnz}4G{{4yOLD@pG3<%OeH`b-M_D#w*E?oBM|Ccn8JM);{5 zmll4ad#6SD=2IL#(}BM7y{d2b9*7)4`hGS997ECtvg&2kHH3&Tz0VOyo~n{KfhVz= zgsk)|EX+)a0MuoyZa0r=d%h@qULRg~-cZF1-eLk(Mq1hM*N}R)0d&D~v&rNK$gc~; z(HRqPf5sHJe6}Ady$nl_RgmVo=MXRsh4hMekB(r=7Z*lX+e%6=ga-q0P;W*;|1VxS z1lu!9`z_t(v6suX2K_Jv%Qd@I@k{V_k-dPK&mVYoO7h}&2bB6=!LmuM7e`1+aP|PH zS}V|9MMzw=No%L3VRBuE>KsFGGPe7Ce9p0Tx%4{26(*c#0{%@*06-uhsaNmWY}c`D z)#0$E$Tsxd^w@IEGm#%F6T#BMRre%bh}CqQ-L8~#y5V*MYMA20FwOHA6YdS)>AG?F zS>0(`!i@T9&UbPl=kzYC98WFV-Bij@+I7m69WI_REz4uY^ZnCF!@5ygv{}b4ulFRM zwB52KotIgACWo5IlFPBtg{hCOzIo3R{hS;QH(L9j#H{-WPt?$5{!d_jyz$^tkY1!- zBzWsP-}$4#rx|HK+hRp*l6(WF{t0X)r0Q2)AG~(5Y~cbf;RRuJ^EW69aO{XUhBy@r ze;?@g0iXXi0`_7o*IiT%W6X{Ui}EWc7cil(!wj(}ABf|6f+Z%t73q>aY~jud5@zHW zf_-k-&F`;#<?R7<Wn7=mxBs$mT}x*wImqgYyqH(Kv^jAvoWIPv&*95RzHqz6qcbux zUiyfqBH6_DlG*&(6Dj2Q$>MXRy^GcFvtOtmSXfvR1$|U@kyDQ;E|ftE4XF0Q^?$zV z2{9w6rEFvGR!~|9G9M%$5U<7s3x^O87^-kc<)&DY`MK};LGA`>K28Q~WH*zK+}775 zMmW_5E*%6tL!4re+Oh-$8a7X?@am1uRTnEtWd;}s6lobLXzL*8aU9q~tY&g_gq2&r zSiJ{pN+!D|SqUQ6KTA`0i|`C%g5vJ@ha@Nz9bp7bx*yd>Cf}<}m9SXxO|bTtd4_;T zk_6xP<W5K&HAf2(_Ke^lB*J$VxXC?6)RR|4alDWx9zmGd=4)K1fH?!4J}DpC#~%fi z8Sbqw8-;-E?7sISH^@o5L|D5)7LoGJ=Byu=O^|TUpWQKGI@s+hOzgcP;!H)BNVqr$ zeB0KCOAzMw9dJYFEq^Q-(KR9eUz6Y+$*&0ZLx}U5Na|dYF@PV7km(VqL|q^0>245a zJSpb9QL24{nSB`PWUY5+-_hd`mP4T}AOG|7bwCo3IjzD6A3(<}(mMH5<68cOI!wIi zvbjWT8|2c2$Aa^Gb}0N{#$`1|;lMlYOi^c}eLh#-^U1l5_Yv=~sUuUa?mi6;yTsr# zavzP`o+DLPA;v)H)yQu2^DG{GIJ;@pq4_zn!fq6dd%9$HVf=8dy8g7&bHFyuCXQ%H z!C;v)vLd@eUF?Wi+N^<t?gS^2O<;5SSfwrf@`<E!EZ=1DSqH1;V7E+)sbP4sFu(pv zvZz?WEMdK?q{tTDFE~)wg5u<~hE+_D6O&xdIe>>>P<C6kyc29UYP+Q&*MIwyzNC;~ zAW(1xgDL{m*woK7bO;*db{DJqu%vy028Fe9g_ROn3#S6KjLYpeIo}F48ldmFriU=< zS69z}QE1<gZXwbg^GYu;s$3zkgkAUruEc?DU)r}%B9ODv|NhZ}(K)G!iHXI<<SB^R z^kp<&B1!)Bq%q_sCMG1`_}vW=R<OM|xVU^}REj0C9WJ(6VQq%&3&|(8NJGj2Kl+Gx z*gMGo;m+l#8xeSBy>+4WBKqcjNT6ICs7SZ2Poj<<Lo)Nkf%NM&W0GbTgvqNIfL08E zb#$21EK36-CGg1n_Rj@_*01lMV*L;aSt5sV6U=aASL*M()q8UTjX{ciVuqa~fgCP& z!13Yf1;>|u4QkIu0t#Zjqz2T{q1x+<UE1aJH_HY!PsHL6Lb7B{9Hdd>`Bu92g+K_I z0m28ndhYYW3RaHp5Xj09KY*z31dJlEWe=hOgmCeThzl5O6aoFtAfV%vUmKPUuHDc) zIwhLKfC@fx<5ay>A#%<jVlKb&?gr(6K(Zl*M`<LR5|v<2@v}m#E<!AB0^_p+;}S<u zuQo+>st~%b@h%UpKJT$!Xexncl+GZD#4}0xiiDnqc^lf#qsT|J_2mNnJ5)y2%x~{N z3Y1G9mXZe}`C<e{kj{3!0Fe-ZTW>D`SyY}bj6awtaDreGxJFEvG!PgSixvV^r6dL< zidjr^E{a%kBz$Q+-TcNj_A~qvZlBhi3Hx%9tw=o_QzC07KoLt4%-eWwgS_DuUJ2K0 z!g(&gH+OoHdUCFeao+u9R=CpXwPAbp6?)N4a6Xh{gQ)a6Obx>9Q2NdOD<ANF&5_Zm zK%SV^kppfUoqpvh>v{b7h5%E+EjQZCM91Ac8sgcgVWHlcdUTnihCQ0U(b|eFW{R|a zg|*l!^k}8P%K<eRlvZqrQS1pxT88WH+Ot>i<$oP@^<=oY;}`peUBropr{(0V8_uOy zX`%{Q^yY{6z7q{_yE{IKofDLk)EO3;X*s|C-i`Ln4*Hr+x->x5Gb)Lp47(lP7=mWR zrD4HAEU#e67s0|RbHhU$qX8-7aQltE0zDfXnfC?s|K}jvc_KdX@d`iV;n_lI|8uLd z4DRlP3SeLJhj~CiK!6^RoSv_Pdn3mFtgc$y+Xb-t{NGB(QF%A|;BAPpv9Up`)ElY# zk|`C2Ha0RKe*Gs1PJ>Me6^Wef`Q_Irn{H*G^0S2nl7m9f5@`ZM`ZGQQwPf~@{zF1H zxs9R=&vyea8$FuVyW8s<{2!{`sZG+h>AEf3w$<e>+qP}nwrzIVwr$(Cx~wky%lkRj z+ITneFXVZ}h&e}WkS0QwBPhbQUj6+K8wUB@m?3l|Rt%0WOIVqgxABu~D=ROJDok!b z=go}`tb;Jm^=16W;`U`EEKOoS@ggiob8iNseQ_|%jg6H<hsR||T$6Cy&#bN@<D6Dj z>FvnY7L|GD17giW3pRgc&0yh2$57GTgg?FoX5tuuHJrf+Ci|<1sL0SON`xl8w-C&- z_!8FUh2QYYe7ewhdAU3Uf*ipUL6WEg-A*6^85?M8HI+#pu_9CWle`8(Z0#fS`9V$e zf(=3izE&h`OAuRUB=pFQ>k}VOuT1CBnas|Q>zDo58AnoP<>=e6zqX71Tx+$NSMlo6 zf<U4`4O^ro#8X*^X2%NMh~>nzxYc2H@#|hZ8~9GBb2snSAj7Oe15##JmWQh;`P|Gd z%$QnzT6P~^C4PT}z8*{B=G-}Ww+ixFRq{CxXOs8o=jjx<`GsiIkJ)KSW3C(OGSOtv zoG2q;!Vjkjry~!(He8U8#14e$p$I`D>{=mUX<-yUk&<LheI?<sd5!o_s{U3veES5v ziC&n=vwF9+4@aw>5Z3&Y(^!ipa48(SK6@hs*Q~l(SYTf6x%9+Sy|g*sJu)hS$+BvR zympG5<frU<InI^YsY@vSz?u2Be%CATQ?Gbh4fjpg#cw^dJLY7v<>dBRsp7jNQ1Snx z%#(BcW|Ew?bm-R@Ykzj8*Y)8+d#z!al|F_Ljw23%Up6T}&YDrlTg>%RPMGMf)XK!V z#q_kqQ<%0z51*UPmH!hR5Lb~C<4$;!@KH9_YsXB;qVFX%&$cAmvotTvii(XAyeaYt zgq%ndYuc(Ld{>|rl<<5y{~`<#On?uKDC#Y8WE}l-H#V-LE$x#ueZll?ZEbmOupc7j z$3ha*v&irbG<Zx6)i5Av0WvL(2kJ9p(5}WYWLIUIxXHI)t%hs&3cB4mkoR#X&EX-p z@&>+a#{tvTclU;agb--d*av1&E*Hw(n|${2zZWRKUab!SKx;rI9UyOtqz-R^ioenh z-zjVSA_<7+e0W;`h%!AL^Hj_SXJTxuEGS|!mBx7!3<Z=8FeJpr0q5j-5ehv{ItcUM zQP$%DrUXW6iC~#}@?B~N2oF>cco65oIwS<U5H#zx+UxUk=vFf7k-I*p=LlSU3-CM0 z#ByvTnvYLbn|9zE&GyCpBuxA^St`jJ(Eiv)r7Y%q=qw8T%pQI+uoxUNaJ|iKC}!`N z1pQ4u)^EpWiRC~Vh_={apdnd%!Ftw|fc!h4!ytuqQ!!1XD}R^g2*uy6aNFx4w(&0; z;XMmQ3V$*s(PhwKla12Cl9=8%xeEt%T$*hjU8iGHuNrV@AlNLyCWoGpFw{-5U~Krw zyn7XMU&n(fzwpb?6AL1B>XTpyf|jx@?jx1Jpn$#eM>~*<M39AM!A4!zqX_*KU~)by zxH6bc&Y96OnBn=ws2j~D_~_ZBG_CSFr=K>GU?ORHZtI@A`?{}^PssJ?TO~D*QhXO# zPklNN9n<2~r}pgUf7*u_IcML`J?k#hL(dgQ8tpgzI;pdecb-238=<SN^=ljb8&-I~ zVytge%O0z4ZtK)N(QjP=?f+L{_;>>A%mf9lqd<}$z%|*as5ngTo?Sl6rkQBo6Mmfp zJdMBif3roup-uns5z{u$>~QDi$(?m;=SwD!xT@HUN|UDZ{z3f*D*BJImIg&#t%4pK z8)k7jFMsSGpI*LW4D$&%bMH9&(X6nD0(lCwc5sPm0BHaN-H%MX0|YOMdD$z@FP$iP z^pOeb*=!HSL^gD=^OF!7zUgKOZL`eI>g8a3p(#GraC-vIH?Ow9kFLi(#U7>UycM^a zZ4uSHL^FCzWX_%fV)KdSqcFLb3O5v0xl%Uhx8T2fe^@vhw4Own&B|n>Jb5fOmO2q9 z4(K@hij?Y{th)WUUl*gF`I5smX0FaVeV43oFr|eqHCG8I9);yP9xSizl!ihcE9;nO z_lh?t`m#iqeYVj1G;gU>^lml%%#X*bV}qMMSU9yzH=d%l;`7zTzfhpPkk643ta-1C z1P5}!4zA}73B_XVX3i5WE>mEBVI?&T$`p%Jn=v3nspO$@q76<Yl$K&t-Q5iUs4);9 zRCMr|qBi;&M9ngWKn-yWqE9>J4|*=gP+z^UFEr6QCXJ@3bNM7UBt2}F)Xkf$0P1+i zojzFeJ4wN9*$4jr!A`)Y?V#?;<oE6Y>csSK>OfB_C_i!fIlLfE!27LjZ4BD2HUM(k zueH6sEf9Q114OOdXfpBdWGa|4kT{Tfz}DItHgx{?<=I*O%b{bHO2uH_Sl~^6;2i-0 z!M+R?$Zn^Mtn5Ibj;^j?7!npSClc1e8$=S`&(s<6nuxF1kvIe~>d4e(_$IJChr{=v z)IXs4K>trDgqAX|X9;y}pVrcWG&D5K5Z(nvjB@`&7*GLe@$JO~@UJXS>X;vzvqTQX zVS?lP3~Dwxj68~cB<!T^@nJ0U4wbN7BXx=P^wzkd0y{@zxN34LxAM@g2oh9yMDMB% zH6#R?Ocgj)(c&b2C|2G@DtdIOOP0RhGxT&(t`D9zTA?}E#z0k2Xn@bUUs7E}8spEx zkaZdSnxx((k6(J>kY!SP{J&;_t{-K3m9O88_r4H)-)pbtJ%#rWvbtO~cB)?*-<4mU zd+!TRjv#YT?9gw2_tTh#J>)cPs>`Q#+}BT@tO?C`QpY>ZF!85(<{fa^iKjzTw&2E< zBemL0Fypv>TUro^p3JwlHFHOL+4mG}P|w$%78;hp;*cp+Ec?8LlZB_K@7S4i#qAod znxFK0Fl~5rUv;&aX)=Vge?6Jy&@wytg%9J-N@kgAGP6>J^hApJ3C(KQvgr=LAt89g z8OucUq=rpNJlpYmM^MzBLsS^;5ksRpeKupuf|Ut+L`0zoG_6;odk2i0WntYKKEnD) z_<WBO5H)s?w6;dR1tUhr<2Y9E0UD~bQUQ8;f9&kq?fjYt%CNGQLvs<=Sh(Bh4xiD( zOJy%u@jZN`pR0FNPQbB`6BDHAZ_nbBO%|QCS117@t7_)*3u_$jT#(X|<+^&WiAS9u zQNqtdi}_y{p1EE+K%OM0YuI#zrht92|N6A8wpX;`M2Aq%`3XVdKT^)_BCn6VI3CI1 zT2uJB(#80^6rT?%$1klCUiNr`Vy&Bpi|KAfdr715;x^kYLYs~|yW|paaA9V6I@uTv z1<;n^bZUj1W&8t7_@68RUiUO9dWctd%n;0>Zyz2XDs68x0yFCfK}=G4jua_WTe@Yt zh8bbDk5-~AULzAK5*67nfj_S@%s$P{F3ZU?Ru0}H)?GN;VimR^?6=!G4sBRb*a?FH z{16^G6p->kpy_9k%XZl-WRi~`5D6H=|C;^46|SsJRciD8FFL#Mj?%9CKLi3Wui<gQ z`5`J`E|e6|FflR)P+C#@^gq5~qa%kvyNpdu!A?VvL7OAtb8~ZN4}=IfzPbTr6Au9Q zD>fL7ppZ)ipmTC_2djH}dq0#}Is}BLq5`vxx&tdzJoP0K1P+(u@&h?5S8M!cX8tc^ zq6dhlDk`=+9<P=;tQ;U@D@p+s?yLKSnXIz{KEi*4T!u;W%9=gVf*Xo!6vLl^%cF!2 zTp0rX)dHkzFZ@Ay2LYt_Jn>JhM<kO<JuFRRakEON{bI^urq&4gJ5xvRU<_}>GU~ee ziUVbTLOw}#OB2x*EW9~>SlDah4?o7-UVf=~P)(qMX89|V*c&l`R_MH2hAoV7j$%8L z5tdChot~A=r1j~WJ-b!NPRf+EHQDUaGRo`LWpu9XFPy`uql6v|3|3<6)uCkZ7TcX# z3{zMwKi?&SH`_gS@kU$Ro#Ed2Utzmam|vZfW!-$QK#anzJI+vkXXtJR$2EAm^&o=b zl@63uyxCs(C8|{y1>(;x<F=Qr=55(X#d134jpj`L<4*1KA$2`>Hra;8@r|NxUFWjL zgy)wWB)qiZ&!1(typg-uI5f+PbGK^d;CW_r?UJy)QQVVeG5DO>tVzd?y=O?T*L!m; zO~8fnBSnib*Y`QfW0^Qz;t>QCz--iSGK2<<h|PNwSmo1rF<C^Jaf=y+J`J`-bYUPO zk(~sKkzo1quuXuq6NXpm&<_O)DZPV6pKDE|TQ^80?qh(g>_UQP7zdI^W?oP$u!0&~ zb(69g(^E8AZ)VSY9Y@bdrOkDFxi93BrY=RudzdEW>3&E^AF(u>wRA5zJ4}*JKZ4lY zVa@RJ-}SV)y{;S?GblVnU|Pzcb)R8-KSK3zX>vYH64TUAJpI1Hq~AMgK8sGT_k&el z2&gEyD|_=h9SI?`i@wcw!%h^gi`4@~+$im0xx`=C7kgq=%uibWS=WZny|1^f`0ate zP`@)EyC|M(j4{lf58f|5LKzn)ado<Xe(J?xt;!<ZyvJISKs6K;Sj1=J7R2Vu_U~In zaw{`-$aJ%vC2~W676{s;sRYX&{ec-As5f8%cI1ns+rw}NGrrxZ=g&hA&I#-RF(}Ok zVi&YhJ%DHjHE$MVU4Di)hXP(^0)C_gavw_maE65ZInVq5WQ-W-pA;aU2;cMqo41|8 z)RF#Ub$mKB+b2h6K>NZMU4y>uxZh{G)z#ILX>^xIM?>bm0xlfzO2JE{tPaq8VBaCk zKvMthA-%o5rKP1=*jNa@H*o+98kzqdKOl;b(Q5kX!;xriF0LSsAk2SG{n%oV&;@wQ z0r(=cDTtpPbU=hBbzqg!aHb`7_T_a|Wpox;7Z+!jmqFlyipz(=iOJG;kYW;;y%IVm z5<ek;#}JvQ6x_&UvNgc)K@9GHro4>Bb&1mYv`Ol-vukMhrnSWe5#UMk(Nd|7NMurh zL*98)hGJ;5Lzb=Yaw?i)5_<g;`JLh3WBz>xFBPG>i=~Oic)!jKzef3FUHuz+XNFZ? z$Fk$sX+;t8yxjYCcWo@@?vYS@{8?Lj*BhJA=yY`X+dn+r+ArI@=Z`C^@_DIJ1qkVq zXZ7Oc=u18`Q@ze8MR5u*uR0?a%38Q_E**(#O_~}4j|UXtw`qNu$IhR!4=uMiEgc>< zz&W`hm}LtE87@8$GqsMUDn-I4!EWs$w~h3;ogSb?g8sRMqrP&YHzi(?%Z~^vmW^%E zFRT1v`daPbe{b?PSz95OyI1tAbzyVJ1zG9aSoKyW%#62Ca7$mjf7dRA!lY8f_qrDi zE}e`LmRbD`J8xhWMjbvURLB+(i^p<@HeQn0NM?O_vHYu_ut;}}7=D%1y49ycI-x~^ zHjU&YLJi84LRdWm1xR}GGQh4D614)Octa!P?(=4U?NjPF$+wE1n0v9P1&>-IS!7rt zMDmuZB$ByR2orOx=O)u0ip+Ei1aC7g$sfr5IxtP5<mAn=dNQk}b+33XD~WpxPeY;G zl2W~_y-X8`B`k~YxSMU;Ta~B-6&!h9S=H2>IIYjUoegW7_`>GwA@4$Kd>2XD=9x3k zfOS(U>(sWfu5F6!{F@|FTk&>XryLA=+e47_qI}^<N%xAn;`!eC_VpNH>|#V}d&ig4 z5z{H#v0<k+DAo6A7%S)g2UXwjpOK(`?F0r$LnMxh*ev35n&1rQH+1=_nV6WV>l2Dt zj1)Fkbq$dY9G<>55`w6B1wrk-nzc;`GQCK&y>67MmNaImf&P5R;$bl|Er?$zDH|=+ zqr}ASwF2EqSjAWX#;V?O#5sg9cnYm1$}=R!*5Dur1bk$_iDT&7TXctQc20Koa<oDR z_z@zFLzsq!3Rd0Vk(dXG>&l2f2qu(eA5?i6y?-17y+2;WtF{Wr|BvqPxS>AzMdE>2 zk>5J~d=7@n688n>!f|c^&B4y0iG)nzNM|wsj*cRL55PbX3Q-M=pnpjf6Q=HPJog;} z$O^zqb$)(Oyh6IGXfTcguz>d?K2v$uaqL_a>VfcHEAHwzoC(ek4?(y?jgAKdD*Fkp zuJLQ=Y#*Ch9Q#|(&Ma|oEVM5y@nND}kinc~Z9zdJ;{d+nUILjD_v$(KGvvlOd(`c{ z67j>R^B+U65Ut=JrjlO>Y%&;mjR%a06Vt_whfGCD?_sHoQgJc$#!{rsi6Rsun)=iS zSCBoZd-taLk0#lU#_L45k5FMaV~AKKeP@Z$auw-@TsHcI{+{oTN{EQCenrw(TI}KD zAG36MS@Jm9(&v608x^Vg@xL#-;`r$;nR-_5kF8Gi-MH?iNo)XjBaa_K!1j7T<C4~% z$>!D}qyE&$+83*N=KQkZr`31%+lGd*Y4V;b#>9{F{n!1c0*;f<LT(o6mIn3Myy&S8 z{6Zhc%(parCwJcKUe&tR!t<f%Z+4AbO?phc4|Zd?PnfR7;?H0R;AQyL(kTe3b`qYd z$JVsbaFbi5t+I7!##z;Aq{&-!(lUMeMpY_z{>Icf5ge*YFjsZ&V6#;9H8jiC)4lWC zGn2<UDPc;F1eGw)5e7sYNn1J>llEAa<&&jtx-9F)(tets&)qwZ?Dg5w|5;}y{hmT{ z%autT)>AqpyF_SIC$?J?z;($rmx?u&UH%nn=%Ay5tSQbAMDlTP+#cXUGX5i@KQ!C= zH6R{sixH|p!i$nlF3A3ziL1Rh-1-aiYs1N-rd#0pGjdZ#Tdc3SDOgsiY`ME@qQY5V zqn5dIS4wGgx{BLu;KCD8*!Nivw&*Vb<yV<<cq%x0yxE2?(Y4MZ6;Td|(%(~csYy#D z=L%VY&-$h1cY4q6*(bku%W3S3`pY6`CQ>EcBjt38g~wAgmmsy9lKUDtn`)o$C8Y~Y zNB8BRmq69S;Hn$~j_V`?Ev0#MLR-rU0=I|GQnuD?b05f3r;gOz-nO*a;Dsao7=sVf zJXq-R@JzhXH3HvUNme!xP}K8<({m%)R_c2T5v-r>gjbj#iTI%4*B9&-FnlvS5igZe z8Em_dgRr5Q8F&mhHb@9aS(wtuEgFt?N+2<C`DQ4)x^~%MyjSO`Fh)il1Krx%S|}j3 z;XpfZ3gocO{(hj70BIIaMmimmCx*^~!T(H?94bQ5FjPbM?T-HyjS`-_Zt?;B{`)HH zcn|atqNkkK!?gUyLI}*~5Zv5xjSi<10ILNJ8_qz&3mu3=)?d9oIWe`ijy_(F?Q<v~ zvKKJyy6cM}5Jc^Th}IWEuz?>{-45y}G-d)S1v7(c1vPKa$;lB6tFEar)JH-|iwFm< z3qmYBQU{9aNO2hf#xXF0iz8uWRmY$)`)gCpgNA{CVq8*WZ*FXFY_2^$i8A`Y?fdgX z_ZXq+kL<I8ti+Otn>C5e+o&{t?fNu%c77chM_p5AZDm2koRpP`u1qbfz*k**WME%q zSs3qx62e<ROkv}hrlCF@Zp}X!8_>5<bSx3*+YX9<H+{(PLSw|<WxLn@r+l-7+m)fu z!vEFtAyQn}OAk-cOMC9HDjm)jmF-?J)eU#bWtYze6FSEzRPN)QfPAUJyT?t>oyVhA z$ja@UJ+G3_`;zH4<+i>|R|;QW@A7*CdU^4s@MFJ8=;;l%b>X;i&Fpeme!=ti_-BLm zNjr4-ME=(*!oA9&s^ED#=ZSeP?Vis_Z7NH>?&sq5vf*Y=r8L9GEEh|w&K^<0h|$UB zTMJ6oOUH$Km>5Cn{aA(BaYy3)@)ZPpx5y=?@>V0JHhe@~vqPKpBFuG6q>x?$g|-UX z;Od{#Fz7dAkdHx}Gh|~nF7UwFis(^3FO1Is96s;812wPnf5~oirPRFcQ$cN7WxdO# z=1N|MV)3EPx=AnEIl1=kGMoA74I25_hg#%NzeFO3;Sq*MHf=0hIi!avqF!ZCq|qQh z4DeudMiTbtp1}>$iIl$g9V(}ITJzfF1nU)u-cg~H+YQB3?%SB9d9{_!cRO*~+?TnU z9nTJ6jor5M93n{KlX_n!4V}vm0<v`5lrqSerYY&D8OLWE{nO8%Sf;G5OWfEi26Pwo zy)>Bo#pf=u{lqIaYFWn6s8f~p{i(l3J*70{{OIhkyu{#hK74}pFRo{nZM6pL-)@Df zbp9ybAMeX$fyu&YkX5%9&=+3*OpgLmL;&5ebVYM^>ult{0#Xq!@OLcOflvNkM?X*u zq|HWFaVf_<)iFiBcnns>2H!<%jBgBEVT{#t#8*1(;6%A3k&HwA+{GP4Va37C&1@E9 z4F7wCQi+r!%`i05Gy*-~dbVNF9V&=3qztMB(lpv&zr#SF;%{1hyn1!0fQW>!8=zIV zG;E5I;bAZ%<Y-*3b+L6}4e6T)-{cR5|5?cY7u;CxS+@r+{;K6J|1V7n;WZ3?Am@-f z95^-jQhG=3o`0V&8GscCgr58RkS5`kJV5_IxkL&b3FJ61ooQAAXFuH`;^H&($G1s* zyS-c*3$!AMT)Gg*kejjaP^Mfc6o%sn<!{&=9dS(2e|BVCl>Tgi_<dtj)6j@J0CS=h z;oMB8H8Tr5C|4=9KLxmatif$(SXclqu4RBgPcc(VdsE_ssmbUsN(S0<+~pmsUm(G6 zyT>0&UZZfKSp+sUGhGlL8FaBUlrJVNEpL+lROec_XMd<oq)?5qy;H?Cr-wDPA${_A zO@{TG%f1o|o{6|<k<}>pO`~BJNPCp(3R!=turqJJehD2sqAayv!$xN6bpLg}j&!lC zo|*<#mS1Q-iz#)x<ign69x*d^UK7nqOAbD5gub+V<->9L13^Gp@a=HB?qRt5kExE| zv($w1ic6E`uSzn^$It~2;nLZ2z^c0WG*KTq*>YBN?`M2v89U4CUHHb%-&%K2_vGy# zmo6HW2aJxM0;jpgoKt*DT#v=J$-i-WS(iVaM#GLcuC)ec+f%Mb81ASSaLn1vyQhD< zW&hK5_ecx|gsMf$vv`5&iLRiOdrU>!xz5S)h>)w_viP?N=**x3(zAN?CG$dhArzw4 z7y-nQ$t-A45J!(Lb|OBD|CWyZ!$A<0nY+++W!G$VMS;UND1=+FO_Ib>q|_CXOmBD% z5BsTqvG4HfvUv9loqgea$xpF1s#%yYtj=Zsn#e9rN2T}6WEatvjmNr0Rws=_yI|&p z!8DIlIX-7rg+co_W~s<gByO`-V$iyvQp@2zjHUEP-~flSpc6b1${>ZaLS?ZV$9;{Z zx4UU-X$w9%DfG8;D2C!!y4mx6533<Cr~YI@=_&Tfv399>x^L>QE1v7L6#c&dYCBu; z$y4+()2x*2))pme>zqu@V>s2vc3l)MZ4vp>LXiaiW!7`ne!P$(N;oFQW7n}iurGRB zh_lVJPDft&0W3&WGP3q&(GY)HH0mf++gkgRNU$M6#uqf&(VyQ*B!)_<2bBplHnI=Y zz$=CRBM|Q}8kkE*PtqA;RU5J5qs%505rC*)4S>0&tr%h!p)>gYjiZ{#SSWC4SDd3g z_0kv^7>qhZ0<X{*(BCD}=@93@goET~$T8@CK|MkI^a~FC$tFzLqw7ea5l{g-Lu^8P zOylQh(`ZHo*HtX97~du0{QvD#g0%hifB3wH0U5phu|O())I`E=^76g%8zKQB;X|85 zD+FjCD02mpS4KawLO?e5>^2c^6ZC>b9sLBvft?-Z6Gc?5-TCC*rzSPi3hf)(4xyR% zW{6vTeE5xf{{=cAE3Z!hW&fdH=L)mp;ej8xudrgsq#SfeET3v0x)U@Qgd5~?$h=-K z{*~D;Ca*u7F(GIr02}ZFHB?BlG5~^nFfqS0v9dylJr)bg7f)Lqi8X=I=qFV?Xn}K) zrb@y1JMskgC_BAAUdIUi4MIh;t(L24=e56oItXsWkZx2C6ZR<oSbm59={NBSCE&2q z7H>JaikI<cJVqwA_|VX(nq^HH3;PfCF${J&u1hp5V$<46lfjA<j2Brtb{3T^x>Q9i z-^XlbT7Kl9A;XJk=vEYL^N8$&2E#u>fJUrLJU}Aeh%B#Asz*!Zm!b20a2BoG^&iP& z-^<e7$cIMMwr)iJOYd|mJW1OQ2J1(s#)|q%j}^`t2tr(fJ0VR+$u{L>irn|S?{$kQ z@*YlWTt1(*i`BB)HRj4XZp~TyoT9a5;@^@p&wW+?uflsZo<cp?sd-6r!Z_|pT=5-i z=8sh!xD!=lEzk`t?_{i-e>BY3j&QbaJ!Ye<k#KMc94TEkkAThpZSIyJtXbZLe(o|O z%I<ucIMJ$}J5*|az3xm|OxmGvG1TjMwcguWd1r+9iH8z|L*!8mFi#ra`(3g}zcDi; zrbKk121eAA>L}R4BCMiVJeZBt)0{IuCyJKL(A#NWa97tU8*OyQqB&-V<(9d{PrQL* zpPWunjZxhy-^>3JGpBdy&iLE=+0OX8bh~S9^2$6aTicD{nWI+=X0<SbUvNAxU-qhn z^*JDhJTOEcAjol*$noJ`#~;7dImxOEI1$&ea(EqOi#5P^G~~AGxGaak@ApfcB{iOn zH;Csb*~80HjnXNayspKkUB}ZDzEHd!>fA!R*&0M^pW@A<cl4uASqe}5F-To{$6)Q! z2!9e!H2&<bjkG5Br`|*a|2ax<-nxY=e3q*3Saeo9k1RQaI3HG*$)y9Dz306@R%{l& zUp4X{wBDC%$A6!DE&X}~;wKr+X3c)FzPTs%0c~Q|oo?T=3dHw^%!12RGb|QG3ko{u zWS^;HKT41!7g<uxEI<gxv$&`}N^2X?TnkK2g8@v;Cb0LYT=gI2pWcH*Gora6YW-HN z?Lx?@*>eN{=xUTt{F~d@JpBGoOABk>R@nVO0^$%e7CDE(j6vNiEiw*m4Emq|!l`7v z&0U2`1qv-(P=Vr5+926r??8KC6frs$i^wo}F|jUL_zg6I9+Q6X7L{s;PwPr$bRICu zNto_*Ep^9jF<_g6!LGKgg@HW|b^O`MWEI|N5~U`BrvUv%P5V~X-<3P4C1{2W6NMSa zMcUoqkf9&2K&sMS2u!gH_)4D<5cjErQ4ImTu?OKNCIf=3q`-kLkN0|xcpz?nBcJ_T z&<5zWe0_WvzXhCtoPvryXXvl`<sBY?EO;cqqwXnS*yZufS;#z?=td}4KPg!~u%57q ziK9$aQxF|qFa!9L{@S&G2KXE9%&QS2y}U-N0Nun-*@N_veAF{QMH;k+Xy`OX5{ire z!R1Q^s{&pM_?VG}ctyoy<f>=b7lVpq^nt+bC#OXy+^5vm_J)O(78dqp1j5}qTwP7u z7siqzfPt<w&A+y>F|xBGPL%vD#jJ?aB)a_rq$Xe_w-TD~)}P0%kgEpag}%<dGg$NZ zc%r1n7ob8vK%73gAKc$v4YQYXn=;2AC@p}F{$vDG{+K9%u9Tr<WdPE~_Zj<`0;5|Z zL!Z2UevTIf^?(FsEi6phffj<O7_;s!A5-iE$_r{sXRDhL7S}>_6&oe=Vh~g-q^&P3 zp4azLRx%RNLj6`3kmnKSpteRcAX&HFbS`&`!4k1|!DZ>yv@+I)oVw$>{eHJmNjQFQ z)yQZUI=9ePLhpAMHAPS#lHHBCO6b!wTMsMPB~jibP>#Itf#&(u(K#AnDm+Jl*!#I_ zK3jkxJ?9atsp!2w`EU34j**>uguGklXXVJOOTj|3Rs4e$?*yS!T!<1X$bbY+ovTgr zR`>Z|3f#OWfVK3W$?Vw@=M6JLOqVdKyjg1|p}zGD-JVA)av=%rER~V<<yM9(ibX%? zh3;jc|J%csdZOu&Xwcjrgf$5)w5?YXReu5a+hhg0apyOJM1l%6;Rkg7$}(L~!A&y0 z-AT~XKSn8yidg*e7WI>bhqL6DmIrc;<xJdO+HUIypTE^B9(XG=WC(669>tx$B*=IF za^iVVd4za2Z}Q!twRB6b<SOT=W8>eFyY%=~p0r%EqO7iW>(Tr6X(Tp?ybR%8Uug;r zu(Ym`d!vl)27~%9mI%yz-UF6gj!x3sJj$QdxJ$9N^<X5dg2l2n3rSG~4W|3lcEg%z z{-Sa|*<);~NhR`a{tYeXZ_ZQhrfm3)Tb$ov#|tf$@=JI|_Nsm<n$P$X%n!{EFlZac z87cg<xjZCB*1VE+U$o|rs#cpX+36df$ypW);1|s#1wTQQ{<Qu}=BMEY_a=-Mu6-r9 zQ<?N|Hf|+~sZfGjp|*>)6(zqim9W@VoXiA=wIJCE3-cHM!Thk&K0Wb@db#jX)l=Z1 z4sR3z`4bA(&o2m1C1Bwc{JNNedn}e|%q^t{#F1zO*D>%1)HlzqttP<=XdzIDk<T>d zx!?gIP}hx35juP`V?pZ#40X8usW5{^1Bd<oeyr`0p&?LSR4RlQFo6Ih2=kCJ?16dl z{;U1zYpiv28Nw?p5|SoH$9iKVaL9kKoJ3-bz7cV1h#wI0yNA8ddPG1`unJurM`M9Z zr=?;!7>)m#yXb+rgo$SVC;1W))X6p!^;aYx4gx!ttC3&mR}ESK9oAt&$d@`Y56}w` z50@%8(<!BnC4`uZ;3DZ02~{jngo+_3hy|wZePkB!ffDr<H9Z0Pbp&^xwa<SLLyz}_ z<=XSS$1emDfPOH|iRvFn$jep9eZvw35l~5`8PKI#8KIz0GBgiUk$+7r$|2IDap7>J zcA)+_JOrde^SZC|iehJS_YwN=rC&hlE}*UA)#7j?Q1zGkzIp$f;tmxK3=S9(nmcGQ z7(Wm&{k4&U1+#2B6_49<S|Kt)u_MA^gc^ysm=K!3maB7XZLOy|&|BKuTU(o30uX_@ zv36mIvnXU)ni<6y$&l`}jLnse?6l0rk&iTuvawq69@quw+!f}&DA_Kr*pH!=wC}E^ zda&$Rv;dMLNLUYYQAubFQ4>&|uEL+a-aL>((hn-gVp#m|PGt$@Whm81T|YS-48o(M zoQ1>@@YWpQJuNXG;qdFni2C<1E-BK`;OX+h{2qSVK|$&UM#H)Dew=}lnAB<|Uvc>- z`F8Mmsgn2xg@;|4ybl`OX}#MWi_r)I%Alg$Nl4l{pVtiaZRI-9Ij}zX*cU$=fWnBb zOslm`3v2JYNi@^+X(yIm`8tb?MXRzIRu4Cqv25=q0+>5IcEfJhQ6}{Mf%Na5)ft<m zQ}WUfm##$*bIbFDOu>71`4F1NVX#7JnQTJ>pKdMZs%}Ab-+bl5CV#wQi@6GG<a-`* z?CR1x;9v$~Bd`83tEYhO=?(#bGy5SBX9&J?-_!1auwR4x+tcm*^9q{UZ$Fh-<JQSY z=V!pxf|fPq#vhSV!f`rIeT(_7^A6*~Ay&uH2t}9`IQT8A2#{gf7z&uT<dAAp3YQ5s z-ll)XI8ISw1Vv8Xd2St|iCvACkOXxP5!7VL;UYK=SzbHTXFg5+2Ac&3W#c0zQt8y* zWg`pis2v56%)xBE5qdxKMavNlxinpC8egX?Hn-*s)TMmX$(~F5J95O<u?g(z23^Wx zL51f*l%|jt%J~S!(gO<dzH{{UK?!3W$d71cnIbQz<_<){pT@MWkqZ>}aO`t9TmDK6 z>?*m;Glx5P@#0fE1U0JN`gI<S6PE@$Co^TTY<Uizsg^0p_9?0A&!&2(*2l{hrY{BN z&wWLP=E~msWqgv$$MmccL?dBEwO#b8+Wu9y&o9R6z4lCx!!gOt7a*Q$>u=`qQ&Pdy zVocJZ6&c$hzuk<LQA2esNyLLiW|R)<q`naaikwlw9Ez3({7%4$`KZdHh;-ng+%WSn ztu3sI3K}WLwSuO{6^PlH)H8|Ett+YvbDwkPk<5LCwf`u0Ob?8gClTRAW{2dZP>hzs zkX8)$kAqnibl|9$D*$7JWoZJHg1SKrg9}`SA;O_;cUK8BvOsbeRO|<64#{I}7JLns z4uA}WZ_xnpVZjGc51?jC;_WoJf}Bz8*U5no0Ol#Nj61Ox)^B6YFCv2%19KvUW{t{T zi2aIB4h4jIII3`lYt_Vnv-zkhumdXR|9qi2uvE|TtzYKAoEIdA6`yDxdJcb0M=S%R z9ubQi2AtSK?zmsUv3TFn^VzCc)j%u#QD31o4+9<P6$=4URQ!Q(4(-Dx@qMv<`SLv~ zg=H)j%Ju~m#$pF&XJKgp|M<TlI>Z57$vQN0A_*i)2j_)OL|mI#VK^3AKzW*hNFF3u zXh#R0Xg6Xa#jutZg=h5#K+6aoPLTbe0gEKAR1YJ(M;C%<i-$FsGgwcc|A31_o49uB z0`uly3mDx=8IwTukIl)nUj3W_3yT<qg1HU>UKLtBI|V(vVz3WndxSkkbxR{FJDPNL zQ<~qxHSkY{PX^J6EN~4ngXO2}_v-0CsUUdUsI<dR5AK=0h2ojpkeWxFp&DvpBp%d& zYXmN6OntxnK^KKcGO3X6uPt04wQOK{>I-cTkTDJyVS4RA_^mB19_;-AH&7<vqj9k~ zE-&yS;vAQj8xthqN+77{dr5&jQ0(sAZ%6}3#Ke%o_7EWMh1CG&5p1N^HqSRe`6P{< zrp>0m^B7|*`Q7H*V#n4xPuA1Fn#6iec$b{sz1d^6Vf~29v{v%+=A~O+&)wpJ?O&n{ z=lPGF<EgM9sPS6PB)03pLBvCRkUCj)MiSGY;n3&q9Jh==?Q-mMJZav6xh%J=6{FSE zEc$ZU*NG&g#iL^-`+4cSYup33nDu9zQUe$B$FTCwFbLw~#*4-1Y*48y#tW{m*W>QA z8DhmFGj*0w&5hCwg1FZj&+ew{P;+9%fFSk`hEJt$-ZiT2Q$zo?Z0CHl^wCuK^zPip zmJ4i|NVeW_97dZ-c4bC~q!4=x)y(gf{OjEG-Vc2mhFyj)5@Q7(Xm}87ioa@pDLYSE zyW>k81?HBEzb@EL-$LeJu0up~LN;j3{bBS!tPV%jfwlEN?7dn{dFiMeo%~L?(ZlpC z9JAm~hgbbF50la?(j5oxSM=uOKWz2uSR`}mvN(qry-T0AI?{eIZ-^f{1+zL)oHeB$ z4FD2_#zOm&12*1vVv+6NKDB4|A2NP_#jcdN^YDdsJ?@k2eF<#8{R~s9vV3p%EFSL^ zN7C)__)EC`#xa60;Cuz9;u5=b$G0xgm~N%Aa64w_V5N!^kHTdPUkIv>?pYCe&)bfS zV^_CuS$CRj_&Zp)u8(^P*7lcH)l_TfqKf>mvw{dDV^f?|c$Ayf%{s9Z>e@Admd!3; zH7qUx;#O!>Ifz*B-<^zxLZ*W4EcEr&<JlU<2C~8U270R_j3B|G%`R;0kl0)}=;tN| z<;(0qyp60ZcNihT2M20Oq{5NYG81Vxfw+>f==JFN;*5?8l2?!$+GZ9w^Dq=3w%2u& z@n9p@cpat+xbQci<?z1>9oX&lyPMRvz+Au>Z|_7tgq(Qb@Vaa68TCOyR(^ex5W!Cz zOkXX}X;UMVN70s(eS>%`3=BklKUBt(1g95h{lnDViVqk&r2g-M9NswEtSCKAZKM_< z!ZM*MQ|KMQBoUk7E@V_=5TKBHNkb&f@zBo!sP#|?XJg&BthduDm%^3tA)Q@ZMCore zTQ0R&uMzNiJzi}zsn_W_3_%_Ursjic;Xe*wZ>S}+>BWsip%2{^0>Ev;cDLsP0zQ|^ z)p~>P$1|OFYqfS;Eufb{W<VPRB1B6DY3TrTHy|Hzc6}Yoynk{6&JGlgb0J+%|A$hK z38)WPAyWMpBXch~MWZIbglvLTlSw)3J>w7J1gtb}9>2_jAoUNLnD02qr+9El2^W(Q z)K0CPf`ioLAQJ|XmSR{aKQR#wlFJ(i3>xq@hm98G6N$yAIMs`|9UY5}M)kGseS%nd z6{r2k1`t&68^6hVf%X6S=RKD4W>@mgM<g<%2~42{rrj2Jj|4GsHH<*zOk{+DW;}<` z&Q(pD;Z-?pVMX=iveV-793skfZmBH=KaB?PEh-~PDU2Gm6N|-!PQ`rRs|jKI-R|$N zqzbAlGcLsWrlPR8eRR%yPX!ao#K~dxKJO-|#v2zlaj$mrkS0}f>))8%7dM?3z00j_ zx=Y{Vz1MGXR(b_{jVjM5ZEac6^E1V<)t1&`R%|Y1d&TdyNJ`i?{@j$aGH|ErueEHa z*$qU-{^dcZmP5IaseOyc<jbEQQt2Kz1WqqsqPrlFXR|)a(Kl!DNKmdle1y%S@*#}n zkROsuw)}WH$*L{aGJh_29D{hzbGU8o5$XFPhrDt<Yn!p_pFKlmA^Ys{e!E83L5P7b zwu|P2$uVQ=&RaVh5HB!%8BLG-(+A3H1QtYhIC0ASn*&R7v5+X1hyQtIGv+DGMOjGG zRPO|S@6KrW-Q4W-mS(9bd-r(NJ4N483~*-o%5JTE%oK(v;a1D=BB<e(WHM*Z!qqmL z(cP{m*t*TUwJYQDo_g;{)b8bSxpMWdFpb5rWRiF;o?ot%+=l+gNH|x#9-yNkp6$c? zy6HTUW*U`ZOHs$h63M^K;aB$*{&t1ib{H-jk{v0;r-95pjLmRI{4IfCCwH~3W#8%& zNtb7YxV&s5DH{I=*KtFbotQy_opO`fxA!tSbp^!@7Bvitm^gN6f-*R>Oko-SAECcf z_RO%HX|Og08b>cf`43gonD^o)hPCgR)6$M)!AE)FTxTVEtJf<3@uoq%at&+m(DRD@ zc9&f2MXu=%{#A|a44N2BWMty<utc07EHyg7R~p&X#SNFZsT65;ZeOmy``}>lN`#vg zJpfGC5-MFltQX|4U|*QE&Zwz-I#tgK&fd1jTD4ZGSmPFp(~_xPvnfErjfP@VRA+8i zEmHW5GBl}$^D!t?qfit(vth)?x#g^CM5dmJMQRBLu6XJh8g9p^jJ17O-MV5CU$3%l z^dQ|XSfEja#9-L9ulz?EcpJ^3;S(;<p<I@VS(&8QUIo|;ve&x84=-W#>7c@y+#e$% zw7Z-v>RHG4Tl3CGkenVHq2*(&ATCJ8v7rydRq=sDX|I$J(vB*hUi)!2bmW`1H{w;+ zSLG2(Fggux9Y{TWZRB<j^fRg-3R<-vopBIIy<De*sSGxo($Om<&!f)X(h@q4Ubpk{ zd<in8-2Haf!C^m%o6GeAj0=1zpTICbmY9xDH;gTkOsm-fSTD3cp+EHTaxGqeu+Mg@ z6)HGE0S+Cl^4}GatHjM}4X$*l!Zv^i2|5>#OaFz<&+m^-P}}SE?f4su%MJ(yt7F14 zjM{?$16(2_prGTwR6_0Q@rl?S1Z>Ao-$HS-(cMu?Ap<+E1tbe)?oa~^tfGSt2jzJz zRS-X6f`hAvrZ*<Y>a)g*NUq7k@?}d)UnRp74)1NtNBk7im(#10EG+^e?huiE{GTJ* zz>cAkR^swNjEKec=Li~#^HFfAm`CoKRFI~@iP?BE{n=%~9dmwt_<*u2W#W`4qJtke zsHiv!<C7Xkf`llI>iL688WGwg*DKP($ftg`^)rLlaD<vxSX{z%{<{yHY7NoV#Bt!Y zc;2~LntLC`yTh;d6-f=|jdgQn>6@Q<J+SC`@u%8Vaphcc7#A*BdDk1WTvw!4G+mPD z0!W4402h8N+vR_~M5UaA@6Ihn+w&dxUO1NJOh}iWw$ijop5xGYh{eSeA*_wx;HUaX z3Qb`HkCl&cSN=<pMTRED)U=JM<NLTccRjAaU-Ve^%&Dbu<*xg3W)7t<K8JNKOyea) z^D#T3*J=$e#V^QjVnOjap@m13tUGV6lWuspo{@V`S!W@8myJG&50wiP3PxzDz5eab zE`BUriO#d>dDv<5cW4#JQXzoFI%+0s##FgB-7jbJP)}|BB7DevjJ+dW^8$2((wtqI z_KfRhfB!&yG>@oYz~-mI{(X%LN$>f}D(g}l9eV5}9V9eg@Z>a>M_w=9d9wI;&0mAj zWg*(}LEpVoiq5WK<nOGpds}<*B?sUR@ab~Gw>h^w$Kt74rSp4^65$Qh&fxYKeI2@g z`*x2lE5VhktcGn;gUEOWS-@jGZ~3}dijZHk0+81*Cz5x5DLLRKE3zt7V^Pg}1g>}c zC;}sOYZ3bvra&;s`Yd<`YDykO2Vcf@a{Dg#@7lx5tX4uoRi9Kmuizl@JZRVKg$-M! zDQ|Fc{nO^&EWT&*jap6}yVI3c?<CCa(w(wjK2p!GoGgyW*PK$mUUlaiu7Gw<9szF_ zyWR1L>cZ^qq{c61j9ADzU4TjE6_ONG8;l#&VMzsxw9A#30Hv{6bIF-lke7}w9<pBj zodFUe^}s$a(v=`w#Av=+vx%?g{pFIo+&#~4sMGaQfAiWyB&3E|rYcd!3TkZNPC=dp zk5@Q!aayAih}VeG%mj)Dj+9+Tkevkv6BBbb%D~6Q#%3Q{JMboUqi8NquOIsW8B3Uy z3WONQPZW&>V^wLmfTGQ*8~GrHF=9lxaanXfDGN5+Gr%4sR%->q9~;1CD^>(LbprE1 z;%k#$VFgM(_@OeWNCLQrMf?zWxc&{AV$`&I(2A%7s#q9;glKV{2FN+-s)@Hm>JaAi zfze+e{tKkfr<8#jJ~zPo9iljU6Kp@w@cj!5$YA9F*CRTOnv1jZkcK#K8Aw=&^Z8<l zVvvQR>&5axbE)}Uu5OnbII7i7C#wt)lx#Qxey95_JyY85YlYv}`#!wR?>o>G{7k}3 za<bR=cM_SO?=ND=MF;3!@PHQqS{_63eY@py<i(SxEKoW;sY6O6Kp-#>cmEs%!cP=n zZgAZfjbe5WKoGK3Rru{N7KcBTN;6hgJ)HF&KLbsjioB<AWY`}LsB0_y(P8pw=TF*i zjzp!PikJTOAV{ZjYyVyBjKtqRNCOFEJe)Q=e#}JL`at|K7}oI1t|&IJH=bh*G(2$| zi43SE(?2Nq{E@Ez*fI6>E$@!dJRS*OOOWUv6$V_D3Qs&g?C_!1*9z8f!*8)VF0ZQ@ zJUV#W(0oHmC~s1d>0wT?(unp`d_1hKDBiI4qKYts(kgUJWcXDJQg%iqDb?GJ12SQ2 zb9u57#-tw}Z!)vc6Ogte2Cw1*N{c_CF<Xtcufe~2%{NCWR``7Cv>yv5Nadz$n(U=> zwn$^;;MlwQ1#gZ0&!@EPPPL!=aC?GvXzFYX{Y`>KI<N<`IsZnl$;_ZthH>_iT*@yW z`gv`bQdSYjT6H}LLuXag@U;C&iMe3qHa#@Fa7e6H8vlZy(4NKM8TIBh&daa+{1Xyb zCC#SI@28Q}cHT*?CmzC<MV&j@+LyL^h|qHO)2tKf`{jNNa}xdt-^oQ6w+XnUP04bD z$9n5xX@*;$wPtR+G?zB%jU(ua=k_Wq=X}<uVzH1vnCv=g$-J>;6(jH($QvLZpvoAQ zf?GVmH%n-A?<O@Rtv&4p56hLx<)&=(_%GTodNz(T@i${Ggib+z@N(hwV@A$wx^pHj zYBqD@zlyuXQ>9=_|BSY^8a|!1o`*pazbu!LN;gUfcy5-zK4y8Z@&#i~TXr5nKB?Z4 zJ+<@o(PS)7gw8P}n>oHbd2IHc>{o-*>FyPB6&pfXp|)cD)XLuCHCm8ao!8FRjiV>K zj>Pty+6W{1+MqiVuxpcup?|N2NCAcw2U3o8gyh4ht3jG7l`e1p-FFneK%sB2uWkcR zv-ZOy6Vpw+oi<pqH}1;rjz!)xl?Rk)3Knj|6Qso_oD~nP`9r~*d2<zViq^4JNI!=1 znF4m{o25KyLO6{lY7a}RLxN1e;k|k}<M-#YrM@*FxH>ME`=<)El}Q}gEMByI)v3uz zm~03&WV0w?Q#-F0wXEs|U9K_t?D|5%;37k0d_3uF1VmA0er`V(OS$-F4bX)Zw8{2% zxAWtzCi7dpo{u1cuk%Y>owDzSc}CpGKoxpG@V_BZLLlCUh1Iqn21^oj<G1qUx_E8@ zbeXu$?*z7(8;+3yY&D$RSLj?HPGq6N9%0WAFoS%9Ps5pZ!Qh=Cq_`F|WDCBCsSovW zLFL26{UQIu{cnz;na$m{{2QFW+pOwaP^Scp^a{Cq?sGrLgre2TyAF$eE&)I_;&7}W ziXv!hP9JOzwmC>Z6^9>Ggck0#+!Qdlg;3sut2~yEXPl-GcAQ**SdFa-tO&m7G@3}- z-!B1rGVNge0?9y%`^p1%;h=P2CV08~!WN4}zjL_VA#4xj2j;(uHi*1>yq=JN`bgj` zQ2kEk+~J17kM@yVFIP{lV1WCbHUaZmyQA?p6ry=M=a>>RqeC^y;Z^~UxW$Bo3O-N_ z%tVX*9)XhseGHrJra(%3JmPW~NI+$P2w>m~0wH<F?5-3HhF}Dih!9ql(Fdj@BttO; zso58UZtv_I90(-^Do1n?`#l(oB2ZBnk>Cpzel94IeE_NkCX0mcq~Xs1qJpx+lh0z9 zET#nR-3WmTsiq<*?Ch^0A{kjwQP7*AR4jhjcB6S_FDM(|D`w~~JP&(6!!VEB3X=KZ z_nm`E@kiPZ*5NOLD$WmFVl^YAvXYH26{-W~bH&cw#6#caVe~>kZCqMzzU5?klz4e> z*61Q;UVEgW!vGa}N=PNbW~Vnv(UgT{hV<h)rcEkE{RB}uts?lA66!Wee~A{hfJ#^@ zLH|QgQ(7FGcmLS(?{>GBrRFo`2XTsLJgi&SvyRh5@d4@NGWedxyZBc{K5a8LU#{iH zq`c=L!+#$`TRl|je!i~pvW9fI;nX*COPw6L5t^#rL)o0aI(wxnc?+WE9(2_6>>7SN zuZIXjxs)eYHd=j9HQjcWO;n>4+;iq_e6Jy|nk<yv7FRtkTrzyAi|0HuoAWl+;%uoj zS4V!?tw>$ChFS5H!Z1|a$TC%SZTa)MwhLbqChdQZ#aJ(&et*=y@W*ut*qyA=(Iq>~ z{X2p*_9B{#bS<iA*|pOXr4K$`>+D&&c%s!5ixJ~%2gx#8Fd~dY?@$zspnw9?M#Z;D zX0o1-UE<pz{l@AxUeC|rn;Dyn@FuavA!&|4){;$P&(>KP@RzK6tpLq+dFFJnp`WpM zbufNYr^M&mW}aIozM4tqm1Xbn9lQU$={y~S=h?BmN<8U;`PO)DUvjnb$qErWs8uwV zX6Rle`{yLmG=wh$%Bv*`!wb@#d%EH!afFaqb=q67v(&}0cL&f?)ywF7VG@?Ote$;Q zynT>!aXN=)W8-u%w>TNEQzYB$70uyA+>?!_t>Z23ohL$kh)I$CBk%oSQ>3~x-}^K5 zVw`tmiqa2N6k2UDRt*16CuX-UYVDq&`V}fPHiB=j9A34-T9${!`ggGQX!+mp)+DAL z7^U({?3&bL?gv+1?sZ`=`OleBnRWVeFK^e=^-h)lT<=$>%dKLOnXR<6wc6>hR(R=7 zv!${b;>Yv(LKUU9=zK0d{$`u%M#Z!3kHzY7T;5*K@1su~HcNw34>Gd$Bmj=i7;kes zZqe13FH;O2?eTs#PI`Y1?O)*a9sv)3cBQ)xv9gUp4w#-4xHYhdh|gEt7N}%lV^4~{ z9F9G<!G#M&InvW0R`IYnxw?Ww9WIMV0E$7k;X@0f%v*r~4x$Vzy+~bqMfW^dlE6AN zLaJpW(xK2|bI)fTIBrb)-mn--PKN;T*|RG*1qs~|1yY9)SacB1ApEVV57glBUC2Nm zWW)nAt3$z%Msha9JOZm+qnh}n2$~7dl16@U!0hcYG*bh_hg!eK4?z0*>uPz0PShmd zF%rl+O;mjE;DC6WySlsq?t6g%4tAwe48wW0eLz2ZV4iVbxy#Mg0g7d|R<}#7RtI}P zr6Nke9F7obIH1CCC=Af5Oc))b`b<RqgFzDI%xhDCQjVfU!~sSIn*G}$4*X{1Evl}L z;T37{jv67S1Id9jp*WM(`k(sYLOt+Jz@Wvh1E|FofSiv-=Qbf7S1A^WjYFk_LIxZs z&@YQ2`zpG_>XXE`hy0ZYU2_HCq9BuF%mq%s*JwT)6jCDu`(VC=XL2yOU>Y*!y8!m^ zNh+v;`@F`lU|nW0Zv#|`(NYRArjAq*Eir9-brBbAP+@Li-VzmcOX^tynm?^bsv5j{ zI{G}LK@O=!cW8+c+yWx`U%lf(dEH;!4v?NG`YF@w0~1Kzq2jX?ZNm(+O!6f{c9o1w zK*-3b=&0r{kRzoP6Ie*gp*X8S_537w=8nLaxB~x=sdI|Xtc{j+Y}>YN+qP||V>{_| z?4)Dcw$rg~+vfTHG4?onU##nO_l`MhRy`HHvm`cQifyzYg(GL|Bg}=wKP9cXqe8>1 zI+ll(xC>p57>G<7hW8apjVl!*N^Lgc5~c!k9Mu`PY(yrSpJ8=&*6<Rd#gllt)~UEt z7?f1=4)(Xq@6<l&ico*T@s_5uXCaxFKTV)&$5>OUbckMk2OMie-pa%N*C?+joudMq zFNWzY%fR8j(o6e=<yJ=1X^LAVIq8g2+-tCoq~Q|ZyFnSRbQv?{Ezt&K!#ZijXL9KA z1)GgSlIHfImU&FEe&2L+lO;90<M&wa+Cg3kqE9EG1B0$7Z~XIAL6BwHn*O;@>|YAK zW*9-u3laBXwtK03jyUPE*&6Kw21tb5pNH|v@Ndl4WGT5Mv)&{$KK7D@XSVUf=L$D9 z|7VyJ%L#av!X{Tz0DVG&=oOSYL3bAl^&X^|dh_ur*kG+3m~w%4Ss!)&Kr3xdw^G~= z%b&M)LG+m=VDyCT<dyd4?jze?luo|{0>2<-!#Zp9AmW%XmzvcbI>Hr><sMG3o73B4 zfg!3ziT9seZ{oyBs{r=mlTEAeT}(l(TBhro+xpSCX)K<0f_l$nI)Voa4c`>n`{c4i zi_sIsJxy!*)-B|b&6V9vS7q1BdIe*d)(B+&MXp<t3cafXEOx!fF#@qqnESTbvkI<m zIX>0(BmR)#x8<7gf;cb^o#c0cpl<5W@~_4Shh0&wRa~cilM<m8SRvtLB_!)t>k`}h zSd6H&ksLoB&q3Jyr}zF*t7Ur}mh;7Xn>*=?vbQ_M*q5Ynd_V%`B&Hejp`qbyHeB)< z0{wDQf80yWZnMnm#i3g`(EH_TX{pr}Jg#AQN-pLQOCddwhTU-;&a}Pe>)ri&uCTze zSVe(cc6FU+O`Df{9RTM}c50|pnLO+-Q=S=p(`4oFm}TX|BdOuf!~*g*`)rR{O>?qd z`PZs>^9^|6&bGQGe;l?Xe_i8YVxJk-=J+_vatId1Z(yAhz{8i*L20NIPp;yr=Tvu# zs&gjhnN}<1gH+MlBEo=IA%(lvu`)r`Y3}k@Wl*IsS=9kZI`trZzl{J+;6Knntizbl zeS`?x$OFDnBpKSfsWH0H4q-#j#SO)`z(f&Y3}`vc>oeitEK3~cnEj~g6PkwKbVx6n z9lq?IJ!&EW*t6#z=xBWtKPy4F6@XOgt$g*j<SBA3$t=Ma+pE~y{Sk9I5Mmj?#xw>Q ziD1K*4jFtG4}^D$OpKHQy4&p;0s+s}ZVlK6*Ae}P<@bACIH$3aiO`F}!Xf)01F1MU zTLDAWtrzJnZXF(=ws#h!NL@?1iBJl{^n!%J5yV!Q&WVDJ^%I7?QoV8{cM34H!K=yf zLxAK#Z-z0phg6nANJx$GLO8_7bv0Sd6-Xyh@Nr``0OT(r;AV{-Fqcunnkev*oTI_V zzEdHuLnwq*a3DSSZ>ULlq+sCyB>7EJG$@k&NmvZQ@}=-I<DDg-3?xFd@=XaC*>;fS z#^l)T>Dw}tOdO07lnmx9OOr*>@3g4BbLSVtdD6RDitvhv0TF$e+9&GJ+yY6wU5P)j zpV<UKC4mHc{s1&l8ChQ4rB4>tUqD;SHPjM<MAh>yMQ~f>yNh>dWS+cL<aBTyCE2<R zNswnUkPit!U=J1kMeH34lm|FTaw(N7b+y@2F+W2kBrw?vPl(OB-(b4g^fiSF+X}F6 zJW5+Nc`u95?A%I?W~tpM`%l?NksfztYTX^0wW4;P-w1T1bntGyEnJ56DvM~o#a5)0 zLe%tJ^uA}<CUK)*Oy9+H=x{P<TM=$vBDl4Qh0Mgyy7x@^H25ph*Defw9qu(etm=7p zg<Lxp*V|ts+5;jZSwnu&<;^SKpc7UrU4M%!1!5wnZ~}f~IFP;2=tA5~pZiCg3l>XA zFOo9bkF-mMR5V}dw(EbzFWG<dp=!Qw(V})($g)17e6w{dEWW)SvmSDpc5H2s{{cnM z(SD02aNb6$NWeAwcDK$B^(j<PO*+>7{B&&9^UU8oCnZlEc@roO|F?JqJ;j%0(5@^O zv29sGP^bXC`19-g$m`ea(?9f&!_E;$18SEYY~=>vt%gZMO=ffdr_iWy+0lz>9HXYP zo{L18LPWRDf#dG*+`^@Y#0riKojdE;B}p6qGzq|z3|X%AHEcdOt%ksTqiwH!NI>%u ztfWL=n=s2VKtV5?`ZE9i#XoZx&F<h>?Pu#Y+*zrgsQGW+654By&K8ZvpN>5Js=Qh! zIffKOPbq1jxv$_}D2pPJk6LY0S$eZN3mhr8|44y0wWZ>@d&~Ygcg4QJciey7KiuNE z-KGEO?pQ|geaIrE<EhGIQ~n3?4c5WJ1HaMEsn;4K+&r0uR?QI-lCtG6PxHmV&-?j& zt=sLv!o6j=%mu4e3te-r@Y?Ug{d{|Ca}iEmTT=81-H)ICnH*12*ptcPF<aS`ZqDzw z{cP48DThz!9HlL8$NQ4)%Ef%QCZkf_b$8aH?QDy+>1-k37?(i5vG_z~X|FuFs<b0* z;>5&Ol^C8HrdC6#o=!Ctb0o1VfmN8E@%40!17r(|3P~H287JH3RSS$7gAvpcxJOlm zbcw=%3{e8tf@T3ff?>nU&3$K0hQNS2hm1l2vdcPEbrxlr14HyZ<{J-Yb`ON72g12a z)7}fgfV6v7!3Yq~E3YN}@oDmV;jErIVPFE;QZ@}i8w+|70o^14p#*oyvwV7bdcMBC zi?%g;K*;@4AlW>%n`6X?e`F(7pwWX)r!wnH5M<`^MIixjv!@}rhz=a|9#<z&q-eB$ zH>6gdmup|-rjE5p9u^{NHr&_MwY8;M!(2gOQBNh3Te#OkX;FK2ei}e3A;2H(w#n(c zBgQWui=`lk2ZZ+i`I$kp1`mpm0eH4#exKr9NwFH85w*FZO$@7!@H(VV30GoNc@q_- zHyCrEr!STWPK!uPSdj@X9qZc{zSkuYEM*s>FR3l(_OQH8oYmI|YPpz+C25?_3<WdF z*lxARWu0djEgU6*AcI!!ZNnbO#5rX*{NM+T-vpH-0P!iKimAkes^NHsI^@9$7H2kT ziXgug=qw1QgamRPrK#BsPD=^?k^B!<e-Nubc=S3lw!VmNZMqyu%2^gpRvjQyqvkoE zs|vRIyhCSw><H&THczUIO6o+LG4RLl0KP~*?y4tdbK^0`t3_9BAXoo-GMY@hnx3>p z^-!kavZ;Arl|_2O*)whB979~eduPo5Zd07iY~;hC(M3WbpTS`?lgGY-^HD2zOZuyI z2T?bBb<IzvaokmsLTQ+cCPU^ZC*cPC*Ym@r%0HUy3d;FNR<-(pZHR#e@##`kj@jFT z#Z&5~9z}ge<*E9U;1|^h+(Vxj63)3}Y_?g82d54D?1`Fkb^CJHBy)volZqy+*)r>w z)$A8UN56}e2PLN`*bhCcj@z!*qnP^?gfM;LUa?FJMe`H7CYhXC@4m;C6Qg0w9xV0X z6VJbHRFl-^;xiM70}2WHH}C-l#Wacn-u#MgTApRcRjTlX3NySyogRrkQ7K0k1o*Ch z&x@6|TG{SF>^J2YDMW`ht&DfbZ96Q)Row`isr<^_+qnYb8c}73pDMZ-t=x5f9@Iz^ zWQtWL#B^HON_AVimvZamEA6+@+q$W5WyWj2$!Zlu97Zb-146?M$VN2}<0b3?1%753 z<IheuuDrF!byxmZ?uz#Hj-C<O%%iGX1cbAb1|^~kp>~2-!A32aG`v!jf^yM*0~l`u z$P|ZQHYajsJ8e^lW<~MNq|UiTAh%?A`x;ws#yo3D@&a;|E<PW1>N6Ey)jS^Y9a%Fy zmT4}N+|)Ma-a;tN8{V{F9w)QvD|O&sA9AkCRQAM;iGa$>;>ES$diAVh{`ZCmEB(%= zUEI8MENVOYY8?*ykxPS{9{rAY9c^?=c7j4sczNMbAa*>_N!EN~cJRGRv4BOJUyKnX zYxn05L3Yn$Qh0EyYpX4`EBT5$-&;P9_gAySTg7VVwJ;&;%>rD^zceIwrk`-Rv@kuG z5>sZE#G{?&=9*D3i38E=^3gwhSxHH-5C>nKWWjwvj3yy2z<B?Zz*o=K7}py0_oW)e z?t%trvFZg=_WSmuK7(<<ptJ!j{*n8s!tnl4tU&cPkRA`Yiw<Iz&SFCAm?fQKfxZk$ zltn$C+C&VT6TJX(;{UujyPW$gcLB8g`$FQ9r2Rq>we2<Z*Vc#E*RktyhWYRf5jI6N z*MAB2IGlDVl~ChRoS=}<poAAhRE22=%0&2;AKlO+5HqpM(7E7Gl~1O#jRj_v5@4pg z-d(_VH6B>u%okDl<g+-$7s4n@B>~#`(Ib?x=hhdAcx>$w&}@+~<VLgYXo~fAmzT8j zXbIq=5FA0wJw0N?n+Mm2en4|48~b1WD+TCv(A|ksCZsfaJ|yZeNjHpLSoluXY5+eh z0Gudj4j=CG6)jSWqJ%;wY_U&`xDk>cCaQ|cDogfJC{8YU<XDDPHhO<HJ|YxhbHDH8 zhmL>${XrH%K^0KY2JsA;xjVZ&Z-fq2cmlfDPcDW()P4J_iTw%b_f^1Dh;8ExbzagM zKDs>xRO)*Ng$s1U^mTk0ffARSzmrVpb9BfDQ^bIlgAE;k`F;d(Iu7T?1`m#J+D~S8 z$Wt2|4I!s^zVK4hcmk0>w_fvMwaJtCsCDs~3CH64cl(&VJEifQ&r3t!Ov5p1))PDS z`{5n~e&&3)i`@+SX)AG$$HMgs_+k+E5^uw(^~bu!tyv!?#YfyvA!*i0y}I)c6ZF+6 z&Y!hzZ`hbhfAfZqe+2Ld?21H%bSwqIDvq$57CD4YVSjg&!!+6K3B@^jn#(tvtw(qv zI_w^AyuH+FX%F5B5N>!KeRKcmM^x`Lq!3IMFA=0sO4q<q`P)Ac<D^Q#&zGN-UjAO- zY@hyXlijfU@Nw&}!)6fe=cHLASpiLU2V2XXWS>)w?@c*e^~18#ykZlWZFbaQj@i_a zedUq({-*!Zl%?DHx{Pscxmh_B!z&C=sCuP#{+T?WFyC(eNby$!s*@D{T3m*}qqzsW zAqfOw{(2Z~_R=Bg9r9c2yMBk%B)UGaY(ib9m8sijl%M`4$<Idk-%7iVWX&l)*9FQ? z-^IM^LYT8irB%MNRJB;k&I?kq))v&uirP1J46jH8=j;a7I8;8SYnfwh$d^M;)!km^ z(ZW*d4Tf&fl(PR{n|M}zR?gqu1F3?-n;}{DEK#!fCOat$W;YG}gljLTjd4JE;cZ|Z zV6HGNvN<~^uU-=!2g@Uve=dB;T0WzzQ*sn_?gWmppY#Gq$@2T?udAl2hP`3pP;_FC zRanWh0+KT`$GUxKUY}35OK<wF`QH~S^wR)DZ~}JBGv!<ZKR;d%Y6t6ZnMrqVv|nKG z{B?;c`(g>LM0n9q!k|OWV!ri1c1}jpcPf&)Wd>`I&c;y0r3TsW9K*lU8k(;+%D(fZ zRfBa}FLugJhv#dG;htK>CEKy2?BG@h#7NtT?SM7};3f3!@C^(McIB$vA~i56MBcp| zO_q_^*>>ZA3|C1UmfB;!C~lM1iTZ%+fm*NHz;=N=X9j|<A)uWDhD1EC<7A~iM1n{F zmLnbEhWC5R{$>^EFY~g{Z<f5J8yc!z&2dS1sXl!T=}-JX4Vt;ITfrwMcy$cY5Wq1# z2nE>p9E$AU@bIvl9@yXnlu~7}KY!2;G#rsk8bfsnomC|fwtA%o_=>Z;d$^Ml3=#+% zw?JWG%>@@Jx)>NKaG#r<z5Nn(fmdG;t0I~JmnhW0EjNMK*=#<j6`l;?Bh+SCEk6i9 zjb_c?Okg5(B!p|A#T>j(lt8C%Plc&aqcNhjg$32@=H+VLkgr<`dYUKlczFRIFw_tx zDD46<=sNPU2p5U={wjb~lJf7HjpQjb`z~Uh?=GnQ9qKEpqrX!~a9{4#nyHBmou%vU z=Q5KkD6QS^P_*fi5@+PO6m~bfBZ*=9$tk&2PNIBhI)ueQ6Ryf8HL7pGA{EF#f^y<A ztLQWi5}0|*xtI=Pa^7ZXB%-t^=9>|q_zNt2ao<4wRHCVAjbJTP$F5Y0xr}S@kO-<? znOUZ+qSo5v&$}rZs|n*>{a!-?vtn%NFrqT*9lGFikYXq^I|~hkYC1Ma1@u6pWB1v) z6&4f<Yrpk(-71dx=SRff2W_W0-$C@1p--2z`|xYhuj>n0vIJ8Zg*ex<Xok6WST+C` zPB^XX$C{<wC9lGCQ_B3(>Mgcon3E@2yHwM!JYnV1Kw#rteWUm>W9x-v$*0f2VddGt zbg#$yTo{E$5{6!sXFHE4`=!;fC16gW;mcL>3sUW#pSp4Eh`*hoZT5pFMQX~!OFV#} zG_%;mG96!Aox}gmrQ+q}O@MztqM09gmiju*p>sWMd&hM5yY7Btrpddb_96OU!`cjF z=}RmHwoF>XJ?adWcjTtkn^*sn0n%qiHbkBXJkl=8u^!5sO?WI0Wj-ynbOWEj4{3z1 zB2{J@+bm0xTu|jpbMXdcYE1!sDz!P)(V9%xuzUR3tCZ>#<I5}ivu5@)>6ZoQR+e;j zGv_0{`}3n-W^;zUqSBAR2ZY|o@`+#OCG4NV<<{~KS(r{4S$E4Dy<3a^;8IXVvrdP0 z1Jk9c)Q4K}Q42YNzjGcQCgmCR*$zRx3Yu)`El!y9+ake=Vh3P0?$I)wt6P%~Mhgwj zs1W4v1kMGcr`<h;2$}>9UawP%!L_wBPkz&iE4U?$XfCE~)QN(&s10Au)M`oQsB4zE z)Xa*hU(oxX*r&)pvsqFY4<Sd|NqC0Sj32+;%15)jx4T=dyq9yYYT;L39Pp%UK-|`m z3{S?uPXHw(tg@!q8!EEXZJZm|W93DrSqS((FF3QUGkF@-8yoA~04_LstKDLkbDRPH z$IInLWm0XkI5U0AL}6+Pgj{8h-YnJNbI>CsKMx)@L`&#i|67!BGZ-<0703t>l$pk4 zlX_!`pZBkutxDaQoUMtrPHpV0Wail&WPI)}(GS56x2v5-%ad^UN?ABW32`1QEHqY* zU;(=ctuXA5bm9$OgK&ubg9A{5fwAZ|ARr7}_Yg!7;{>B%roID*RW^amqa;zT!mGi= zTWGSscc^sGzDC7&w2cQOMkPcU&7Cv2eI(*qnhwlHdAkxo=`uZ4Ai$nXpD@)#!dvE_ zJc|}E2vQmV&8JP{zo92())1oUT^}6$Q|7G<7`iRxKVk!*Jgx)jyVN2s9*f5OzcQ`g zT+ATS`<1auk_ns!LSw{zw6r?lY2`ftZ?$ik>&dhc{ol4gxm~zig=`)Gdba`~U)yB- ztpc)A2B_HQoa^yyh6y2u@l+`L)D5BHivAF+yGiPiAOdRjCgM$005&e=82l=M4$)@< z9uOpCCdo9CN;=`KUf__BV%b)!qv0%X9Ud7ZyU<M@-zT@d2tzyunJ+5T&G~tSe=)*1 zDUXU;7W%7eMJT|f*%{~(C|r+WY-$=J0t8UR5c;Md8%&K2Ci_R02Noyiwt?3NLNj#J zGqlomc-K3UU8+w{v2by8R26&mm?r?L9`R^>C@LGUXs{O49?pHoQ$Q+#v&{hG8qM5H zPUd^ZUsPiCq8V$%3Y_;4KxV@?&hB)|eF2T_6=F>el$kF$ANm?P3($?3LzZ$nZf>_d zz1o#d43#Jq7r%-52sIQ*2t~wz#i@>k&T8@n32R4^l#y>LBoiz`t#*DS;Ag#)l(H3K z!`OD|e3U)6p!N}gosDoT<5OcBFZFa&tk^AmaX@|CM>!>79DK7MRBCliQQ_F=+H`ik zJ5RZ>D1hG;)`6cFRL?g5(_e%Bcv2TZp^gbnPx;a<7H&Xm=|GV`DVHxHcU5ZVUNqNM z7-D+;-20Csg3j;NxcLNJ;pQKI#$U{wGgs=)?ZQo*IO)?C>wAOsxg-5QFaO5)(eC0k zMi;hOn?A_wc@$wCl@{hcDpLQlwaz@v$$Pv*8X|ZJ;TxW?O_dy<X^W(BG~d{<NJk%& z1$INv-~n7F66r7$fJG(6e|7)qPNCL^u%fDKc28P3JMB%tv20wo;^B9wMp9U&Yn2`* zfa26_s&rf?h_W8n!}o<Hu20sRg+`!g`>YxwBP-e5<?2P*eEw^}@3gq&rM#d0_wVB4 z>>2OYXxPX?g*4cAy(t6FWQ6NN`RE)t{I;p;yT$3GgAfzf!r0klP_HCJ^H98i69HGp z?vHkQ6scZkx$<$=XUD?2^u<2ZMdz!Dy$6<`$bT%>^`-BJL&J{N7q&QD_r9YHkl*PK zzO&COTZmhj!4zt8on(HU;*_>A64xRzf6gG-;Q6EvCBAX?H|#H|b%6_INEG)kksx=# ziNvBwR$Jv=L;wi#<=WOJ0jCAqfo~2;!j)|wZnFHmgBID&sBv)#sFqX|C%fl&Dy_sx zIcvSifd=X5W&X~Wvkf1iGzR@S8fG18hbK(_^NWo}wSOoSBQR|Ctf;Q22PO(I2kSiE zn3M{9xJXK}x|Kyi44Hi?QNn4XA1P?%iLv3k*UBxnrPE*DPnR2|KGCT$^!E0@CyI~e z)F{PY(5|#@a=IZ}>=&lz_oY0`ntKQiX^Sp1I_FpQXjFqkZ;RLJa+wgU1~#dJ2>LPl z1^OuRJ|dQa=tUO7Dd8A5p+Yz!Zco{r{#~KlA&Zb;&=C~%C+X5-5k?NjqgWsT0~WMZ z1_3KGj;R3<>H@<+P*HQR5Uo{OE%9yey5;v?Z)=VSnNvnkov)f;5YM+Cp4kfkyB@(; zwepABJJdUl29^WJf6y{65YQ7}@Vn9$Q8SXUN>pQRtupj?-xrWles@<F!0@<taWNr{ z(&zE(a3T?iiI|D$V`jrNk2{6YutzqH0qWlwGMlhS*FK1o6L=n(X2?${a$F{Ke+&lH zG;s6YKh*Qte9?#FseCvf$%PVmXNb%wA*m)yx1;d;F&)4SFORzo*-S*5O*w~$Y%o~J z)eOv=!+IVJKC6+ihGyEPkFZ6kn+@0al^l<XZ4>0rBoTHIWEvEr4=^EDJd7cDoJpvB z5P5J$A9)o7B_|gzH&;h{M;lkltrMeek1sgKv};{6?U_=;AK37s>(pf;W_dJ;C46Ix zzw%R4Rrq!?ohd;eQo&icK-R(;KdO&X@Y4!`Gmnw<3m9;ZYwK#v)_?nAnubrH>JyYt z(PszpnqEnhKYi;~mcT&aNB;KZKFj5Vvz8@J3bm#~A1tdd+4UGN?KB@GOC8FQh^o*d zYIdtbrWPejN7KqpehWT-gAmnZ+v0|E4jL80g<w#rm3MZkdSJ?IZBbt@Zf$MFq;>#K zo7Cv*DpVakwEvhQ7F@4CtgUlj0)B2TY&!l;D`+fFn^o&2WLrG})g~S?)#yGJ04s8| z_WJS%R~+lsRJB%&O%36_m=qgF>sI@py6!F{>#{v#d*#aB@+O!V@NPC7dGBCl)+gDl zWNZwXDjY!YX5Rd0+<GTYY!#`jpj1xrbUU#=)w;F$bQeDP%_L|1@?WHGz;UiSHl?|Z z)e}%|*E~ZXD9D=bR=Pk>@smY=-o9{QEq;fsc;>3!{VY6~p#aDK-gLTp8fRRsC+;`B zL9lP|>9<dOpT@dNmFOwmt7qd#9WYexnYAAzT)1sqq`#FZb=M`4$i>2Nx7#$e!Nz5* z&OQA04ij$xCNSS89-PG4V4xbD`3oq(P~9}Fw*9$$50_jlIM|Qj?K!F<fRmzRhfURi zT=o=8F;H4*RNLY=d8unnp|zXTboAlPl?1jdABMGg<T2f~Z*br+?MGO52~Eu@YzR?E zzIHQtCeZ0l)oJ3<Xc+FP8)VzpIzL^A+LKf*z5Zq~|JTjD)%rZa`tZnd&n*(;sJcX{ z_CxKJ`;%^I@GA-td-@K$FVendHk^O4^gM|DAV)s)v+cQJ<NAX@!%w&YKFwAz4?)v< z$<~JRS*Yh;nI7Q$zo_f~0njYdiM`?)yk7bqH^3WfKjeBD*#D&id6JoyPQ0;74H+SM z*qJ2Y2TY{eHCl6V^is4WB&#MT6XeTfpS)VAR%>Ez<nUnLUv8YHsRfK?s4~r7x63_x z_ly`8FIT+U1nAoO#dbVpd3s#UH|kp6OlRMpOj#DTx;nXA&lWN7B6sL-b^EZ{E`uzV z8F!D!pL5!5*Qsym6w+!6athpv808tRxpecv;3Fc`5=m2nd|kF<oVq>dJmI|Do^PZ2 zcJrb!>aH#u+!WMR84aj4i#OxwcXhm+Em)RmjuH&RTq43cscNrVH6ieHE0|X=vcv%G z8XFRyHl0cjyb6Vd`3VK6=b<uxlG-7|VbVbq>>(q;RdL?JU!p(45=VxFLJ702@~pBA zi4j3<8d=X3)2S3ep^zYu<W={hYp6}q?;<-Sz~&6Z38f2QsjT`!5rKVx#`(t+{kJ6| zwPC-0<9z)v^NCmxsaY+`?gAm5mzCv}eeIW*iQewQ^wvAxX*Q1YkAX~as}%rXc75c1 zRQBslX9FI;(8|DfL6xAPKxM!w@&Me|NM|CwAf3<x62k;!s98wOO&oLxE#P>lJecx6 z_zp^tpc*hf5e82%L?C!RkmcQR@l%MQ<py(Es!~AjHjEcg{?Kp7u|FtCZ!p2z`)**l zfT&6`gFcQTaU2qgrtqyO3UfQfI1Jd7<PFTN>|~m-LKip-xQK{0a9f{H9~Lo!nGjeW z{7^r-I51-3AYA|cE;R`zgBnncr*q!;d{tu#r{=cE+t$NLi-*&A=>j1PytRX^?(*=~ zzh&jpR_CegM&DtWFj!0piT%>h$<MIwfX^eGF(%K!(p4@e<69|+ReO*w(&KR~4i)Lk z)3t77<Zx?tzC+Jb#!<(+NWT>fWN5ph6IDc<F!YTrsZv#-<p)EVKGFnIO5ixSc30!o zcS>FO4OOjDjnxA414z}3f7N6et`Yg2pAv#_w2iig(UjlhGZ7Fa%WK%0ud}8z@-xAT zbNjMvcNAU%Qss|a&7ejy56~D>8sb-l?7TZ_)of&UwD1N$+Xu%!M-zzCh^UnYKN_yr z<!3(g8nyZ1F@=CCO>N3olkC|KuhJc=*VxO%o@05b_*DDrwu77>Q<}R382@~P7Zn`4 zu7xWa^vr;c&&jXv(VdrEzx<_nT6IIRCEw2}+x21S${h*5LJds;xObs$LDdMg^S3ZQ zk!ASK?`m-r_AikhL}+e_7=H9?*NTNhSW&}LnT^jBL(99XShztlJ1>{xZ=vw~!aqV; zFUIWGjI}((znn@lwz)?UXa%YzzVpVuF4L1aYRhq4q)R!R**b2nV@MsY+NBEJlUm+j z$`=YSX4WL_?Q>>lbq^Ok_YxlfvtY?~3220sQpkkpg&x7&U5)CUcK=8D(R@~pZLNl$ zNB7E}VztE8Dwkl5V~>}8G(Gh1{Nop@A6^<X+3nVU{?9#sb5)YD&9bGI2xtG;FRuG- z0d;E2g5;`g`ik;6uMrbZ9g#|RpK$ibUOD>ezGn=a3_V@C6u3X|tGds<f|9YP@4xeG z?aNkuMRd;R{A=H?aS7m^_?m(%jZ>XU3J!{&q?SwV?>(4+LL=`RO$x*hiWf1%Hddi| zr~{Ror{Eo8bab-roXJ`(fSgf_;Wi|t5^3;I+Ynv>>RDU91Y%y+fyCua>v+O(zge&M zXjRza@wgpJGwdsrkjL@yfD|~NYlhswEtloIA>i-saJxC(>U`*{xuRgRb(<4>{8RhW zH4+mdo7%gJtE8N068tp>AD@wVG@;pK8sWg-2{_~x>NXz3Z#^8&TA@40fbZkMz}F=A z3YErQ3Y7|HugBDCUJ14JcFI7X)~edzKPkk^RYyoe@|l1>j5JFUox*ynwhb8ci}mFU z-tWRpiOLy=8O0iP8b!y$xWg^W{bDy(HU|EULI2yI-J}2<IG-MA>bI5^uq^~)%@_#A zOk{@GawHILtgf*Ra&RS+-tJGQj$dI$Fy!BWaT{}T;*_8>#w5UpTJ+y~h$7fui|Vfg zI=UnLL$ma=KW~TBAeMv(g%~`F^o}TEK3w^`p70ZH#Be}Mc~`g<6uA%STscn&xXdsH zhaF%`g19sZr3O@XN=mr2<E@jVegI`IR%xU1kQxx^MEs8K+GVzh_5^DV#qhebZ|g@j z0^d`TIv6Joiuog|K@{ZUgf3JKP{WjDnMWami0OAFI^D0pQc+B0wT-cNqsNq;DpgAn z4B&&}<;D8Y6U2S{kXI2*u?K8+Y3@PZflq;R0JeBlr$EB0K42(_jLf^*RU}Bk)K_{W z__%l^u<x3hY4eFx2DLIN|G3~`88k?~aaAJ5n%HLr@ka!Cd%M8+-@M!*pgO*3dNtzF zm?3;jHdG{qp|?LUd?*Pqy|0S>g>qaZbqTLde~{nTTig-qK3Jlv>mW9Ty{O+1BsxU~ zg5qCUl(BW=#x?3#>RDQClBHQ#i_H=v@cmIB=*3((j*IFVEL?5utda5fMts90g-8~y zJ~2V1V7evD3+D<gt6PQ@D}edt*8zr;x+5YD4t32d2d0b9yz@C!Si(*`1^miu90A&z zpM4L~(jo0+INX=`a{+~^kD$l9!{>}~{?hyx>*b!Iik28&w6pqOqaOsLy=^<uZap7! zCPOvx_-u<O=aXBD-#E=}!v2zF7M<xJUYO0#et9~61(%~9@`O7R{N@I6S03;Bij1Ee z`~f8Fz6pEncf_|Emc6jZqXJU$5VH279R><FfUb|p%!lUGzt>m~O+S`6IEt~^7L#3) z-TT(Jk~Vx6q7$>-**!|tzijTJ-n#(cZGm4o&elp}`sK&FB8(cDCDDbtZxy6@L61&c zu@GD=yLEkEred|Msvj?eSUN^xbtad)c*>M5%B$e_{-VtSN^5L1B8zYEF{hngVLNZd zGuDroIDduc8U2%artw@;ythp+;x}<74SZwXy9yI(t$&1J%KS+y4hJokFMOW)H=MVZ zDsXE!JQH=uIJ&1rf3N<n^Ryl~<UicBa^72q6-89}@=?2@cI%bmKF;~|k(~b_A-<!u zVT;xtz3xqbqw}_l_S5D~o0}XU@tpe)|F-Pm97D5gHJWWk@=PGQM*-?xsr&0Xk{_)u zt|-UHwTCFn!%&uAW_D_W<@+r{#2D2Zk9%$R9ij6Db@e#@6A#5719t-<(C<0-no;(F zQx=g!5td2ziCr3ZCf_U%I!r4dL+SkAr$RaB6=M#)%i-T--dgmHx+UPH5sk`*gDjcT zs;f)<zqp(Z>l2-_HxBw;JS`JRw4CQT(UrK~Q3l)kz<)ZPFBjT1XJYxgIz2sZub1;} zTU$bSS^#bA9JRs=tUW=lxa`n0+Q*-sghII?d%{)TwoOYFOBcsWrIs%O+Xng*sdOU^ zi`t#E=;~zFy}bdzxEmBPID@kw1o#Mur^gA9k$>#>i<`xl%U*4&R|9g(g90U)E(gqj z37`*vz$0u1YkuqgdP9P&gNA@#mQLqNX9pWtCt{(i@cfO0MOzdmEMx>|qZq0~@*b$O zutG+HOoewx^a`Ti-^EBkh6kj#U@;IWkco}R?O<PV?H3sn=j8fHs|wn_v_*6Z;Xlz) zZp@9|C&0@6HHCx3_I`NwR@j_A@gHkdz8D8c)sU4nZ*c@wNXot-N&+Yk5KXH%p@4}6 zI?z&RH5~x?w_1blKqj452Y7H$K0qrPQs3`B@;b~@t;lzntq>-nLOY4SVEC1qwK-BC z;XqoRFzD<9q(*ry_8TM$`U<x|vyqjQlvZ?f!GUx{hhbJmtBsb5yYyqw;$a9OyTHN~ zfL0Ar3#nKx6aF?OYqJ<yMsy8!Vq!R81Nhc`>O5$^G4VW!(88NAmVVMMC?e!^QJ^uz z1fwW0xPdtE+fXN@fjvxYZXN(PQJc^4+qd22gkHNNSyn-l7jgptTtu5ZP@Z1vj#6k9 z<SHve-S~wY&JzKf^?^x-gfbaJHJBSF*(bql+<(dbEi4Fdxv6M)hJLd-(9u;*%9+K( z*#rGmNW5<-UPi^DOS<DXe)YCvZUGxu(i>TJAf+e(mIYRhl9VY1Ca8~M<xnyc6VKq1 z?jyzjcwdK#L-Sq^1tO+iqUpx}sF;$lbTltdMO!|?aIEOPbt%>Ph?AHf4^!*B4v$rD zeWB}YEpe#<z)tc&7oS<w{U$M#XnU0VTdk8A=B}F=A(L-p39XK|xo#Gq#T~mD{okT5 z`amBv=Bs*MHarA@&{BTrV|YYz<Pk7E47V3QL=x80?&(%<mZ|e5+Ma|Tt`#Ez6-{M# z{1spOx}_gcg&2I)sva(5QJ5-Q98(T{XHHoo*;0-?A9jtZj2!`m3fOGttSMIQRtwtq zezF3NR%hReSD+s5p1FEyW#TUDfu5PS=^B4aNNV!!M;z`vc_OO2qyhhN%w*0X1~npu zh@1V4K5HRr+q@~j`&gmb(<uO~JLcciU-|_$sp%Fwo*FL?<y(eIm2qnH0);Pwi_G1e z^l*IKckEB{rT)~1Swf<wC~i|2RO_`++`{BGwT51);l0GQw9p8}gOx|=EB{<{QI|4f zzv86T!=Kvanr~EN8P)db;q~q;`u)#cl5{qU`gs%Wv*?p6Abxd<6~-m11(cldSG<Ml z7!oh-TAlQNka8*)>RntM>FDP@w6t)RJJF$g%d1QjS3A_(gN*l1-U^C1q*#26Dn$%C zlDx!=cgm9!s@70ayD=0a^2PUjQ9a#l>y@~-xt$=B=hkYHPccd7j9F~Xi^@?aSIfz~ zBq`TnhiMf-Xct3jC-i0*7fr2%j#T!7xBExZ+}gEo3?D2#=O*g8)~^@Wn?mVUHYw|t zFWD6~@V(u)STB@#yg2Z8csJY3C1OLuv%<pTF5j$A0l>jI*_|G>3q{V|BTxJnD-Nr9 zv6kJLSGH>0=y>~@dAHKNdG+Sw&odbhT{o*TiA|hNe^n^f+S^<0FTgzyx2iP((izO* zREnUcf)-eM2nEmAUVJ>tG<St&<^Iu<SGwkCx=}zb&eCt*&U1S_Ek6s$tg;|iJNru_ z2&h{qr_gdRP2)&P?_Q!gb<|}7E@`CMKat_Imk?Fh=>u*3$^Bv>=$9#VF;EdvA>86L zTFPdjPF-Af0_i{y{g1$8QR;YO_!cmB$mxOs{#ty-RYJF)y;ua$EKFbK!D_vgc|!Xh zZ*Bu|R=cmfr-sGvJNW$LI<nugF+pZ!RYp%+j)A{Hsz8Htun4j5B8aSTn0^N`_Avvb z^++J7d4S!%4<QeAHx5uR0PEMM4o4K#zyvW6Cjg0r{z`;CFLH+jm5pW_hjb0V2~3h5 zhK7p<IirJV1qu-hLV*amlvTcR$lrn;+RPPzHw5w#1rom^1Dn9wS>m0dfRl{GhZ3#~ zgu#l=>>&>vl-Ds9m=OUPP7EyT@3|>aM1~^`1*waGB@^>O0Yl&Q!C-)`0YB!+dra;b znNA4cOrKp_oEX*CYXD5LnBytE!M4}u7^xqkArJMnmd!HFAn<&b$Sy(EL68Gb!BT>- zaWG5^mz28+@xOhr^VRxQyBKSJQ1>v+1W714GE&aMvgb20bXl;5G&O<lxMb#^%cvj` zQncEz{h2sehInQ_8`)ojB33olQ7JY=Py~*L$kL=SY{)M<a2rgyLD0{d?NG<6ZX+E* z%E3hTwPIrEqtb~M2_bfxc-pyLnsL#b3luK&zc#kgdqOkuXHNa%CD7M<HGIYm*E?Fw z?9{3$FDz%1=@;+N+5?DYO8<S!W5`djwur_E$eLWs@w_%0{wg?$3dJc+l8dm9-c-Qt z%7M4_EgKO9qNZVf+`N}BqVJ(|!A!Xdm~Nb?e+D=Z;ztN^9+(~A;l~1+e2c4Na=L3V z0&2fTKnc2iiy>k%`P+AP#qCNfZ%(eHFF4O+o=g>Wkej7Tm2a#zyec-0-ikWe_ORXH zcKE-JTM-OZaLLILy;4|iRNl)NHYhoFJlH;6U+OQSyK@-luvB5#<Pj4~!5dZo!4X#7 z#cgnNBr3<-UN-e;&a8PiVJTa$&RaZyWY+97Q<<;rhr02WYfVuTf2ct4ndDZ4J#A`J z{_K_$THkVJKIT|-m)vUMpouPMs6M$+u1u9CntQ|=+;zQ{wLfgnFH^ErEe+QjAf6bI zmTRP|@wxPQjbn})nYZHC1D}*#E*$C^mXGmP_@v==I;NidPVddRPg}1ugH*rhDpec( zLhyUh?97?_qI;r4Lj}a>BX4+Du647v@@!tpzx^uwlV}9<y%kl)t9zEO^kgP3sF#+v zahR|Ao3<8TQPjIK=FZi;S2es_QYG5yu~#@s&Tj4J1M?kb5OpXn<9q1$Kcs*6v-T0S zoVC!w$KKFn0Pmj0N#6ewtXvdQS24<O1D~Jmsk|P|;uX5!K5kLAW!Lb=eb&eFrXHR^ zcU&mfe<A4hem>RhOtp-~V<@|-nPvcNIk(r-5^cuKE=SI-4Gne4S=u`3{RbvA*)P~D zT8Xit;g|_U_ldvycS@_s@P9*zY37?8$>{TVy#NdlvaQ!!-cNQrHS!T0)w-<!4!&1b zh%j-G+xer_dXeZyi;zMHuLmC<2HH}U^i;v{m0fn5M4pB1-Vg>c6N348au7NS4P3Bu zAawAZG0$i<&m+G7s$4oz9-&wteX{6K5IJ%vR3xG-h$@^9xG8v6p-MTBM;~6RkjUiw ztv2|o)2jU|GUOdG#3zVmKj|(Gt4D^0xRZo?uYv?C`Q<~Lc69)8(Uc8DKmwdxK*s;k zt@d8n|7WPWso`hY`~=Du2uj(FG6VtR2ZmJh=mR+o@l0+$hZ1Cyx%Aos3_*RQM8s4C zY6G6@ICSFKJZ_;pLGj4H(Pd1kM%%*ni4oWc6M{4=G;0}*U|yj-!P3J@#iKFMb-oOx z)JTiMfX48lhc9u54y2;+187Iega%0Kkof=@6|gQ;9eXt<PoV-wGLc)fFi@bN8uXeG zxfo5TC|W3hd>@p8Yyt~w-Xu)I!WAh^n7s{g8<{OLp&7feafbivT`zT9C9z46ZE<Z} zWM<j85;*BL0-gNFFRW=dibPx@xSEKG)ARe`bS^(qX;s`*uCV`|+H*)qnu2dWKgFmn zvLD$eJ6pll)S}qvEsMny%&v)@Zh&A(!i3k7)r$y5*Mh7u-s~8K3073aQwQpniU`YT zT<O3mMb-ibBCaoqH({@LfV4%P16P#Ah&{xV+WyHVJ7#*MU#^5LK~H4V&}Nycqj|+V zw|emwDrQ?6SB9UTP9HYOy^8voxo*1Ap!%lip+m*|@QkB%-Y>3aP1{<ePK};A+jn{! z$M0S=x6n|RFfPqEZK)?~_DAjhvPU!G*Poi_N7w6D&yBzse@iKw<CO!K_p${xV-K0D z-wQN62)ev)?pgE7{L$6rb9UNykdk-;c4a<(riBl<<9wS5FKab?iqD-_+O}Knk@73f z#n%QkGIueju5rnX3%LodD@F^%2iX==R2+`e@h^(FvyBvJ7Xoeyjm{H(UCR-Gym7_g zvHA;&i(u}EMAZD(AvW=SlhQ(y5<(mhEEwN@p=7xL!renwudmIT=jQv`i2y<A1m@Wg zyH1CI|I&Ee1*Y$2Ks-sD^7Oj$g3e9Gw)IH|BpZM1dF+mo-%yE(F{A{3@j!~l3Y~YA zSAuKvLv^on!t++~o1t|-?)fGFe-PyHbu%}cMwWt@WFwaBEst)f+6u2Ynk`R@msTJp zyF#fPGs@<NC{OU7Uv^Zb!@bhP*qiUxnC-8-mYVLhquRZ(SU%Px{B9rJn&=u=-LkC< zkxk@?W>I>S^YYL5L)&`w&v9J&`@x~Yii&UPCTwgQFB64&1-n7Te(xa~JAHSBYgCGS z<&^zgz(YE#H2ih1+q<`+C}wk%t=-OyOI+5?qj9RZ3K^l?Zzg6m1U%5#%k&Ml056HW zh0ZAZ8pj%36e<rVjmlp%_zW<(_*r_Q^e%3$*0T-LCx8{t=kaoXsoN~7!QCC9%#Z<a zDw5plVC7vdH}!$+jv;q~sy#^DMAP~?E}M%R{WCR)xs(!L6#ack`g6K_2Y&hMYQ5$9 zZ0bEp-{<MP?~lfcgMPP<`weSV;Y)vC9rTnA+{JvmW-Y;%&okEf5jrX!SH4%{v)egv z>e}g*8jckBLq7s3iftTF9FR;N@}@!^g`pODI#m9yHa+)c;w=%e90rM5v!)bO@0=JB zf-0LstMC9uzY;7P1TB~@Slk#6fFzHEj7{7|qO^%qJyn}D22OU!y!}l_Y`>iNCjP&p z6M*0(0Rs6M3=!KKLX;BZhVgC~B&luqJqjxV7ZI5YtOGWt0%%18tY#dJ+g(CIAp2*6 zl?X(^0P0d5tdS%@NP@v+fLjU<Po`0qsrmp0<^vXqI^vS>+7)K=1enbM+n>><08sf* ziKOQvJ|D^|ED8*97}G6oF^e}*o%2${>A$ZepyNJNFj=rY<f&-KKV&2Rp=JA=A%=8Q z7z3n8r@-0yB;vpOAc$3^!cYb;@{)G}X8{P!I+SkOAx!66A7Ze*I$jbmygnG`MIKvT zN=ZvgP2TQmABEOn@cYj8_6}RNrO9OGeB@~jixzjCT_C=xy|JDm^ur+!NFkRo2#5VA z@F*3NoFBNj=LoRx_ruIU$#7vDgt$kY9yFcu=H~jO$=At@Kh^x>;IpU#z&gc;rXm(D zSW?H#mb}6&Mne#8W_DN4`SDEkaZDf?i?5F3yT~8%4Zf3zvk&}y<G)_Fw2-o_RDT<j zHER?v+AJ=+bLe>3{sYLDQCFFa7Xt4l8GDqH_66v&R0a1T2VOnb^}cJG>kGYa7uS?; z*SyF8M`rZ(wxg?``hmT|l%$M9G(zrUk6+{9RhoPa-vghY=<h#cAI~;Nqntbv4izje zHgBP_4T`#Y2OKB<&C_R7EGMnBF5P<ihr^jHh^ZQWZB6st;3?O1HLd}=^%0e9xux1A zVrv2E>7@RdZu7sQhp06SE!Tb1lNjBduQ_2;2rYEUrj-4%3gdD!UamyqR$%pZrd&KZ zr`Y{V{62q)56DHdMqg~M<}lKg1@9cbz4T6crVztl?%z5<Y`jvEipj9nj6s0(rDXd! zj`!*%CH3xa1PA|%;}wuIXt;mcVr@F6mVXyg-C4L_Ve^@&JgPL&to>>5Ffcj)wXXM( z=K=n+?U#mG!BQx+6;tEJaly~Y*e2<~uDSA$+s$FL5cS=@-7{&qHxFL1%(4`fAJP!} zE?9?L>0<_f9WRO{UEd-80iUrXEOe<qOco>0QObpF^5zCt7wm3cm>}><Rio#p-9^fZ zns|#!-eIZW%U?(5w9Ayfs#QtKQY(MEj%AOl)l<MwU*YVKOr1L^u9v;oF5potzc3f# zsnGOJVE9Qtvi#RQ2cq9uTs>{pB!C$ZeoCy|AD$GETLMCuXs5EB>i?4W{I>A+Y0<*( zH-B`+f-Rr0I;)cheFvYktE6$cxUED@y2?krcy@4@*?J;VgA-^S1HbcIuDGGKW%?+! z)8z>Vh}nR@)92}QzQ{Uc^V$nYUTNpAzAM(Qa@;jw78pA_jT8XV)r#P;9~Y4H<S}`S zHZF9%$L|G-Q;5MaNR@Yj<e<{-(k)d0xT{|7&o}2bDoqh@Vh!L-z1&V&+T<fb`uFza zv*1r>^W{fdvOB!tPZ!UGjBbmL=^<Opqmi22y=ieDp)c)M+evJ?HNc;!414(ggeV#4 z0soqv3+o=JR&p|q9x6jg#wU|Qodk5TI2iLgg$Ww=_(}oBCQ(W|96JONqiX;Lq1%|? z;TCZj3865^H|z{49BmnT531=Xx1ul3$>RF8l}-ZpDcX!p^%lyM${`>%et9+WlLtHf zn?<-{M_nn;keZM*2-M%>KRrEuypIR=>qem_s9_m*?~O9*9wlj^z$MWBUn2Q%0ZCqj zL<~+8G)oyI6i(Qf5`o&g%h5Qn2=FpcG?0{VXCH7}p0(Q>H?fk75n5mh4!aGI84(B& zuo}2Gh~Tc;)A`ac8731<O=P$eF&5fc=Nze-y;{YM4V**%;4M{(%w0Eb8}J>Q{W@A} zp!ZmrMzsz*_fm~Mu4a8Pm#+NT5x6q3WuwKE5yFt7`6a~O@UXWiLvj#NQC1diGNCwd zFywfg$<W5$k`wF%$j08@UXU)>Z(!Cgu0Lp6!cw=AT%X|gK6!0;`hT|`j_+=%(iev5 z1Gatp(%xVX|Cw5<irO~{lCi|i(*!73TJm;wwLhRyt6_yhLmMX=r3ZooTn5DRGXsSn zRVO$^sTLt(XHjae;KQ9iX*Nk=SQx<HyHID0o<pgM8>{z&hHF~La1S|kQXW<ywydiR zjAPOarjUb~`-~gf>C)jIf$PL2s~2O*0Z$_Yz((cCMl*;WrtL1XgOHWGa3(B9Maydg zcl^X_Vz?2KaNK*upwc|L-87{d<Cv?qAve1Reh|6vI+D?;v!4x&aYqV#H)5>v1a9tK zTwaXmKB6tq*y=eH@VsfWmVM#GM-Xz<>JR^N+}8W$ZHEXdu{?Ti2SdnjuBkumBK9A= zJ3TIN4Ysy-?;#>QqKg)-Rdl$1uxJ9O){DT$_7w500Ywn^;J(IFOd)g!W^6h5>6zD~ zm=OJUwNtDhZwd9pC2jKfgOYxqWGxR*T>cazT-1Y*&cFU8{qELMI(z<Y)5@Xg)7Cmv zjqhbxwGxoUP)sCwi|lIS+ZH)Uy71@j*xLX85lCAn{?V<4f2;cIc<^v(hSNSa_d8(( z<t?DF{f6q8VvAe6G_443l9f@Y)yAS`3V_V)U6Z6#m@A2HdIXvBl?&NXS%E!dzn+aW z=Jo!tJ4dNoD^H!7!)5DwDhJ-0k=!oLAuQXnJb%s!CRj)htGzfzFyy(h{h(F50(R>Z zDVEf;TX_)i+~K|O-gYd4uTpj|nK5qZZK27ai=q)Ifk@%>)X-6V0!Q~26^1O+?hcW+ z&G|*&*)Y(M^~Rxh=^pEyZMrLc&eUs_as;kNQi!<F#GXs(Ab;abw)Aypd6HK9z@Xdm z>E%+LQ(2U`N1l7vC|^T)g45eRHd~z?*LCaZviP|`lhlNb@=-9Ads8(9fIfy{j88k5 z`Wwb6q85*HSU5Z{Pun3I6KJj^hD9&e?$oJT-Y{(WxIJH=FEyLKxfK7sywt{DJj)+| z$K?!M+Pf`Fitgs8VHK2!ShCTS_GWW={7NtljLG{YPJSj6DEQ$*PuFHU2w`^`8Drv6 zex+UOyEJ}Osa9rCEfaFiuA@=b#Yt8rc{cw<tNvJ}S?b?hp>MOYM#xNEroLgU-^pRM zTkg@Iy0JmM$gvD0b2;Qsz9`&BdKxloVuajBiUkig;6K0?RlMK{7ELyge-9Pf9c)O1 zB{sOg^687Rijgin1V)(dEEYIr49op+7_=4QCB~M3fgIW{3Pu(&7ak;nx4DnJKL|vE z(}qp|R+|Kn)j|ISOxk?G5?5OR2f+USM~q0B+&}vk7KiH_;a#)*8<TPcu7{9F41<)= zhzj8FWMx$|2Z9Z96cVC@$6=!aMCxWi3HD$<7t;yHAudVE04Dgdv|S*55M3)|5+eG2 zsM7^N+{OFpT)jrG9Ux-&(E=D#!cYUl=Y*b_Y}UaPgcaZkeK16WZS+Nfk|4monwkyU z1Bm39u!H>=k?;i|(LkC(#E%#_(L3r?Oi-<}tM5-2qCg3<fGdI#f)WuCakyt%)h!e< zkYC;*6d30%WDhWHGO?Ki*ch}l60ig?9@x4N&5$ruVqWN8M7!|k061*ER5Tjx-x<>0 zknBPQ+oZuY_Bcs@OU+R{9dr3oJfA`eFRe_>rpBqGOF9kVAXXR{72pD5dIRj6`^MX` zkehAV-2~?z#o4$)QX!;4<0d$-+k?Ad4N;wNDWG^I3M5&_SDD-^(0}LH8{Y{5)gut8 zazVawSbQe5ZF8;LoW{ZQqY~l50igfXV4AaKEGvx%MaE?NNV!NULa^|N*GOz*W3;$( zV1P!2(5gxe3N_bwq}xlLx3HEEhE_{X6v7tf=N%O~DR%0L(dQuvk1BP@Yv8%Ym#4If z67)rM$~mL9Zu}drmP_;gA7SSd9qAu*>o}cEY}>YNJDG_wu{BA@wylY6Yhqgy+nCtK z*Z;M?t8>;m=ejR@{obnDwf9r*L!zaSk=^Nevg!G+Z0cD&BadgcL!}W%xayPYRD3>} zNAG5#lFrGrlHruS2$;n$4K7FQjt^$Uv7`cw@!51Uq4eGv@`Mv$=<9JKxw*x7y*>Qm z982aCE15XL=%GzuPX4*W1-#safTU!V#zB<LWyg*g)knDbhnx8eA*I$AwpB7-z?fOI zaFB#H!Qa=664>;Tkjx^bmO_0`zVG`VT`#ONOPAh6FQl8)Atk;=)p7rZY5DjCo#NLw z@=Q7)#($sZr4y?fZFWAE#^&UQAk)yqcB0eHoZWX`l^@+X=nKUk?>}uV@2|gJI%wMM z#uwnjVywFv5o=y_w4N5tPeCX#6Mvq|99wi(@M1%jD=y1x!fusq-kCS|eGkpePYCOY zf&Zg;Ri+cGQu^LUXs=eYT%=T@^Hl!xb8$1$zRD@hR;_##ALMI)k5!);)%6*e{%-%L zO=**Gh`zSfrb%z!a(7ZNxpi&tI;OnKd=tN8U%gcQ=8{>MXJlxVX?@N7s`=$=Y}z8` zn7qO-X_%l?An0+SGhX9a%X{w4um~WGzs6X&O7$<lfy3{nn%Mms3_l;thd>ybtDRMI zvqWM`ZpeD6Y^h8&NXt&Auw%LLdv49vCcpcm^^aCjdu(^E$`BpPLU+esN9$sq4<}2T zmEzc~1iY#pj0)O{Qq@8P7&?-PN-%F?`*}Vgl>hdCZoQ+QJMq4D>p`TW^Yim#V;M2@ zSs6V4INCKc3#_N6%iuz)8T4$c^qVsiv9!Dfs1a;uZ7r#<gf=_e9#2*B%EGqhw2GIk zI6aqSXB&LfjLMA3cEJ1AdVhfDkw6WjD8e`*SHafQ;jmE6s<5Ub3Y!!(!tzj7p;y62 zBane{?0~K$0aA%K{KHTJ0d>VE^bnAw<fdV<9QM1?21XEhFbp9YfUsgQv2>>&VuSDh zhoNehn(KdssoFTAfcTrQA7uUzmZ;Fms=|3_DhN)eLV${I&k)Epy(n#%yCRtWLV$A6 z$8`Y=?nXRv7;`8L1kU`S@W4wdBtroO-sev$5FV5sjvN!nGRvpo!~*gjteS;Llco82 ziipt3kf{(RE|jT4dP@+<P%cO%ht45af@@;G{n*n7n*&RS;_9a-!4rT;CP9%U!RH_j zhdP3kgbE4c?9)ug2ck%iLQc0y%0m3^3-6WMffw5GN9oKK;qsUEa6V+xs*<VEv**hu z+En4Uu;?Y1rq*2<bmn!@YI0dY#nl{}BW*1d-+Div<S7afL=$8u#Rq=!2=vDx;3EQE zNhokq*A%9uEK#;C@qFQlz-z%s!HLRkp{$Kp!u!Zs>gKf5Goq4S+(Q}(qg6PZmkN)5 zN+RHs{>&&hH5>1~vY3)08bm-cp0}o&#ElT;qlXkgQ<((B?Xc~lQn2-s$7X0CP&iEn zS5|AyXw{u2yDdHHjDe(9yM)adr81viF1u+K`sxm+R$Um_72b19+lV7{9ekTqX)|za zo>sE8uC&N{IXQG6meMJ2s>OzHWl3OqE1l8FN6bG<fA`0kFNXQB4aZg+g?%6OS6WF& zS<?w75gL#Zp*F|puSX)LG-365X*cp!dj+a*ltibgl8_`kLu?1XKo)EG(Gto6D_kW2 zsl}n7Z%LL}@SQQT@MD*!b)A`1yhmm(?o4)!Fz!wQPBL1o&&mvFg+-NFG@XL>{m7@i z_^G~2s8lJsP`T@0wu5!&uQXEmB_S(4zWWQzOssp;A)WDKv>V3EwZrJsoi3j(a=h1+ zHFQkx9JOmiOz&)sq%sKAQf7`{exZI>?3)wSh<2XlmJdONUR##DpC*MwuprJ~bMeND z$Xz@4@NE82lPRR)n)HB@$~ykPp=Coh2QHgwCb>xJ?eNm0%_S|rUM>|&-yo@jbpe){ zS5J4@+~0by50yyV1|fv9|7L$3pR{=SWD(fLd;QB?<PZuC%`Wn{bawbNp1=F<FTUXX zuz8!s^u3$-`_YnoYlv5+Esx>;$;B=$#V<f@1MTz^$svJHU2jlrta49km&oEYHCB)N z^x=cf&@yewKhdh+?APC7521%(u1ztFJ{EgUq5!4kjQB_w3yrWU%FFg$8K{u20d_a{ zw(%2`+;6Wr-+$dh5&YI~=qIO!#dhK47e`5H_ov8yL}Y+u!8i)L1Xr*lmHo4WKN~+# z_({nB>uRntD$P9tjk1b?As<WTFi#DmiDes&C}(++BTdS<R<$o#gCl_$0m(tLTnCwX z<!_Ckr^j-I`sNmqzR*!yfQe09^txCiYMzO=xDkqN2upPxX|K45SlzESc+4Q&fU!VS z|5x&M7BdznFy%VNa5y9uAEQ76+&`dh*bYpW1YA5gI-bCzZ&noT2lYXSE{<R@q(&cd zRM<f{GU-=uAu)x_e>4ILgtyxHFH+z=y#v#Zs@75g+!rm{*j(hdoOo%_lP(+g{{}*P zpG-cPLsfx?qR_w+<)Ng*34oFw!>hP;5XuXxWnp1quzw^#5<gbFq(5mPYyc>Jc(LAE z3vw@+h$Tcn;4?#TqE95EAUZ{2(2~LM1_KL-zV(niyBtlff{=AG&@H`gD(2*ty=Obv zoZSs7q`|#$Rp8Tu{AA?yk`z!V{Uk_yx+=DVuxR~R{c0i_#u9m_D!wQTsB&PWEa-JS z{mAH$;EvxyuY)iX$r&R78z|_zAbs$$#f`|r+3R5D+qcT*#(93;L*{s9cO?t2>^~~@ zPinl*5@Ep{Zj-7jtCS8~@1v-2#uFqkkpN!+99w34l^Mjin#cyL1ldR&A`s(ZMrmSX zW|&~xIXu^mYFEEk1tZ}a@Ffgq2dVq|vl`q$b+vAn41+EnUZFWg%Fd>mD=iB=@*)NR zehJRCXA_O^X5u0nk3U(|9%5RsPh4e(hzuPmhURvgiNce#AP4TAj%wO*|B;O{9nnV~ zo^Q@C(=hYKD_}w{>o1L>P^@NIrEjWsvxX^lMOaeaTtndU1)Ru9m4y=>Zz~BwI;`vw zJ7p=~s{B6wT&?yhMr+qCd+QxF7?K&R{b(3y*Atso%3jt-NE~hK#e!EC4o9#KR5@3h zqOycyGA1%gb0xud`UA~^{u>D8N+}h(!YDueQfJoxuh07fMUTb>!xRD`84qCu0x<(d z#@3=xMaGQBGd1MyhWaR7BLg>pk*pW_Modw?un8{dt~(>)>w)1duF*Buf_HF+>BY2s zzOC;J-HJ;!D-1bn%a@Nmr)DEB&BE#lse;RP;G}keIl?oW<hYM@+zG#PTYca4^gZCn zFz--z%%%5|=>zGWsb#M8W_1lRR<TDS3t0uab(K)hoET~1WNGj3Ada<b7M)P>W2+Up zt>H4J;Pl^>LJCd%ZQET*yPZh6TA`=T-+X_~7V|psPq&NN9JZOmc^5j=(k{T2y(@^2 z=zNU4o5}6)iSPM)m*_O1_4q~Y6}5Pl4NqLs`SfKOdmgN_FtNRnJBiRfD%MIWUuJ}z zd!8Ll(KI(5n=ezthTJyB9`5zKsdMoN<&&%xRke^3GF{!{^cf0O-c4y-w1;Wf@u=nD z!0tJUQRYqk&WhsU<ES(U$FSHSo`4?i|CWkf-j?htv}*Q1aeQBJ>&)1zgV?pyfz{?3 zi>~Qx{(ggIyUpP(rZBx}BmxZm1eeb~vsG*17Pum{#9ML-ma@vNOBKt}UN^fAw;St) zqWZ4FpmfF1hdOR<W(#vPLbT-X#>L-tR&{LjF(PlP<k5Ay91}pgvD?MbX1V-Gi=FQA zOjewxuX)YFM!kNcF;=jUh!PGwRKZy|5#c#91hjw{HKGXYIFbvLOQf_6B|;lI^&r%x zs2Gj`cqr6TfFg}SClAj6au$sJ$!dQ$Deq3QzqY@0TfZea3KTxQr_+xAfzd;)$N~TQ zLlBgGzXIGe$#ckYDc}miK3+6DLC`qb3R<~PW|gE98W2K-13$f*R|Q9kOyhM(et=5! zUIG&<EW6zme!Wj9iKPwFMUpxD;*u=QVubyHF1uf}{p*2?!e$~-QF4YA8s#7gCb#uM znaAA`7+<wcb0BPRJe_8R2yt{zt_-vmgj={4Ry=ft8tA7`M0|*brd=o@l3;(x95SSI z5rjc(VK5#M(mnz>o24r4F3(>y##%BUbvzJu4e6s+qdf74M({K|FcQ!f*#L1@)!qv^ z5vt)Y0iroo8}<nK;~jvXi|7c1;E>R8QDC%Q=PAUe?L>%Z1!j~!4J7x{0DgzT2bYFN zm_XHt=?spLvq*FFa+-ppL;l{kyxKYX9dv<{$X)AFqlYxj>wM%oc6NEXXL+1Hkl)rp zZ)?fk)t#5^GyVHgCia{JvIvcWAq^FPcM%JGQrH`!{G2dqF{|;HMnxZ#1LRRck%R6= z=EM=*xW7h`boM>D?+tKi@1m|3DH&1S8(b{Nxq2Hpw}in)3O1}#WQxM{QmDV1v4jhc zM_7`Q#=~B~`saXG?<UHYDKSVZkv;iQvU*ZTrL?ic>kTYfRxWsQnDb@-<%%;^{d0Wc zv#dO~D#_8hG}Y$@`{zJVx4eHVfZu>i$ff2zrtp%vRmVFE6e6+>V4sD<Qw`Mzl1Ss* ziU0soz2ruyFg6lsEd?jct`I7F^u@557QvaN_2h??Ts)={N??4BWNh0jnRl$-sWT1J zdu%JmueTftgnI+faKOR*nIA+s5469*o6KPF4lHb%<{=SusqmiPtk4JO1@zS(KKb5C z<$n<`tq<Fs$vRm0dA8n7wVn=?z8QGT(=(PkK!jYC;$_DvbSUL3TW*lU_kjAf+}Wj^ zEMaH&oz*5TO)b4O$)uWuE1yjF*z>3<-NrQY8Tr$>)7xN0jWpu@?Kc5gyYGvCBvW$L zK46=2%2waS6;lb~siufsnd-groAtlho%+Ul8h&k5>nx8#bdgm!Y@JG1lCf2I*x$sF zmaivP)N33H1xeQ+njc!XSstj~ddnc@7AbYef0X7%tlZ_Vj#pAD3yyoeDpixalkb&Z z{+ZC^(tlWSZ#-z}*u);Wh|G`5DqBA}F==hh@XM~0O|N+)u=?WF$i*p;L*$l4G(}Ig zg;o>kYa4wJI^#Z@E%3;~dN^CI)TsBK3k-2Sa$Nd%PiI3|ff3JF8PC^MnB+2+SZrKw zRAba!)odwj%GM6oixMQg|G^CXioGXZG|K~2dV6tiY2hWnTB}lf$>glSq|un2>?h#N z`R<WXsRqa5%0kh*IR1Ajl#_^8lP-8LIP{>kxm>G|E)U1$*BJ!S>OZ^H?;m^|#pidd zuE$XD0mAN=8!85K?jbOJar6r4Vj@OS=_FA7(Y*?AUeJ}{2mPPqYzToYmM4x7wyeg^ zN5Qa@#;M>%I{~C<N2u-ls9@;MVX%{Zh;uvA1V03>!MW3Ejq}=8Sx?&M?$n{`Gmc!) zjtEWLzKqez8>oAQ;f823aYVI0gq6f7;{UUPj}!ES1iUFH#zP6$TjGksln5(tW3t)z zO~or>nOp;^GjX~GA4&msjMj`5oPeon5~nxy;6EYsKLYYmAcYx0q6{$x4N<-rq__yI z%7f~a>fGFgzZMB&B0$WvC{QYY7gk&YFrDKRN-PI~q=HO?<B4{X+#B}^-wTx^<}C4c z3A#G{Ny8%nMk)b-flI(<hNPlv7{+|r!;-yzi+C2}LPb~Z!{vm8LMDQPP)0?%A%O!h zhonh{qxi!ODz{3R0#U-HucH+D2%N6FY3SqQ5uHeaMgcEmNHrv?IpNXLZITMtqM9zw zqX9X@Y!X@aXD3i$x+DnFu<4j7G1W|^TA)Rz1{|1JzQj*t<6fxmMIpTq_@wHjXe)s` zsJ`m#?GYg%lN<ed_U2~R6&#%P$yvQNOs#dSW-bO^1BJJ}-J>htf3mr-4?;z7V-9ZR zrls$GUKMH4f*~}^g{0{GEN>asEdNWhSe6Q3oHDMOKT0p_MJ2%leh<c<IXWxf+yJtb zj8eMDk4^p^pCllqL9iK6yJ3;OuU4d#2naq(#j<2ku>^8<Mm_WXDESh_Aums%vk8%^ z?2Q8$J37FH5yvmm#KaW+ViYzNo8Lj~K<?IcKN#wr;I=m8Rr@&lRCDJ(_Us;gn1{$x zZp4sPfBAl6LI7Yo!$Ee0`HhNDPfDDJIFLyitE7OiFW!b(DDf%6Vs3?cRGtqeOK=Y; zV%zHd4Gn<|4PNUQ3ZBt{WhS+ci~G{ZNW5w<_?}8BO`_W|C5{s|se$5LWi`w*oEjq> z;sP57W}0#KJ9y%nTOM(N0_L<k*iwy3n?kYSl}qu?LucCE<xW^%<!G1A>ZX^?3cEwS zV*7L9l<;x#j|4sQZ2JXA+iEe4kJ8&FRnqFZ;7nJB6UEOPk5h1j`@{vxw9`mtV%NA~ zz5G5zX3!vJacy<#9rD|nu%W7>_FUar##C2Y3z*}WTz0XMeYiBJq3d1m+-28CE{s*# z+%S{=O<czwZ_az7264e_{O;9jdl4vBY@qrwLh(zV<rXT0`1MDbrbbR^BW!L_0W-~& zbcOqs?ku^ER|bp%@4VZ~%MvWnLPYnn^HU*_3lnmdr^`y<%3RX+^sNtf(_YI{<;j8Q zUuJ`nu15N=qzkhgdpa)*k9zDoO}JeI{CY!zY3lF4a~FEGzE2KOx+|p-Omnq(F3>F4 z#iV3vvOw2r=pZt%5@ed2`{hlP`M_gt-+$xGWgHYbKJywLDQ%+w=UC0CYnDEKhqRIZ z+r1-#&B;JfQ3@{y-`vc?{(Y2DUtwxOjJ!W6n;~7czOKQQg}stS78U|xBYBc!op)uO zpO1$(A0J|U^d5<dV3SEAbSgNuS5Aa$F!&HP73F*I4pv;AN*i>ar-*s}(WpLDV0Ytp zK)@6@Hx9udl%Fw+Xt+Otu^4JNPq@Dbczf^z3_U8bK7T-JFKJ~4TJqx8KGf09a8pi} z<)e$~+G#Es#iS0;UWzDL8ZmVz^tj@601nCM&(Zy3+0H0S<_1M6bUFz%Tj(!hY6^*$ zx~H)XSCp%C#6A@vGE51y9v*wrbkZz_!JPzD?!G&93hQbxlb&#o1cF*RYhJ(_M4*hN zzi8PuFjyCAkJdgWE`3AKSx=G<YEKi<+b^`ijcO26n9diH+$AAl6q;z)V$~&Z3vYll z|GKekBWTS(H{keAI4NEt+_-b<wC`IWwX;O`P8|KXv?-LZGd3kT6pGUzxfA{S9&KcH zEh3u&MMio9!|dGtHe{pGyQCpI6%WcI#)s0r7+E1O&@t<Q8*MTJhwEhLbTw_P&QPbi zQ0k($C2l`zn^UV@0}Hh9Kcr}<KgV0Yo7Smp4XOUR@eCPp<}!oHMSvcx0qjMf)TDq~ z+a`LBm9fYv7w}(vIyP0BS~M`2x_|9Tmsi*JTj%LE7qwu?s8SO$+UcrSj?Gd2N=+iw zg;<hw5{|<Qga7;xMop6&#^%KxM~TIxM^~WAu*p*RLEy1JbedMnpRJvC_aPQhT`E<G zLt_C-^Yjb59L9rkuD%qxaH0)+_>X<>Ko33^L|8R%oY1g+Ix&b<p<r8c#zBnO03t{8 z$^?WUJ_gb(W=PoB??32};^MKqB}yDK$P#h|HhD&<gGKXDLM3->B~69V@kUx_hUo!7 zjIml6;9w&b#GSTqOS)Bbw72O$+iklb7N|Zlj0p55L-R7U)MM|a=8JNhOY-CAZUx56 z#tN@epDn^C<#xr*EmgsSM0Z2i^*hJEjHe&5FoTJm=LOg58fT209^w;^s>^QQBN6z7 zSwhcke&cyY+cDc`C~?th9GTsg?bjoRuQ7sN?b=~Icx`2>0Xy(y3QI6f<I;)5npts0 z6#5-Wj$g?-DKYt9@*R0|r{uWXyv5L9D}G&#=@c*M!qLUAiZ}nYtpelHzo}QxZhI&% z3V%3^hPpyKh-CFknYJG6GPf_LIa}N+np^evH!F{de;X)znb2$}GY&E7F*qHUag_I% zM;NYp(ced)d+^p_OV=O2?`-eiD)<%&)e2OFHp&4IIg=Dtr7+606zt|wI1v8Sk!s>| zp&~OBH#S1QmQ$r=6JNRXZTBRa?wMHaTAOKWvvr*iYhYi~Fs#U0l`mS^R{ip9u~dRR z2AJ)lJ9_m8CU=Sz%7Z_|!67gVQkS=f-sr?cl`WQRm|w%z{hrm!?^MBU;y{6y8#LV? zmL7#e2meVa(C-SEpnWG1U<(B_hCV7>4{Baxe;56d6>J=4MMDos8vO=pBxL(L0OirQ z?|CWDv7n%peY`{`XAOxsm#_j2B?h)YJe`fGSyrzE%R$Kfd@+<qLpRcCXuy?nVwuME zwX;bGLV2)}u)I_P!V}+SkKE8s!YDa@ut2nkgbc&`DoGKhVs|}?sER|r<fu$%#AsTV zVo7WSfGh>jhdGs=P<;b077*C5<x9<O-}5a%W4KDvfQ)>X)c_SDkQfR%Eh+&Bg+xNS zDBRe~NP$Z9GyEEd)&}tIKSRcU4GV|dAd&|Fj}XbH6Qk2ZmDUS^g(3+|Gztgs_Ku}L zgw$jWY}NmxMsIJY4U#qvAkqd2LaHIxBqFjb7~0>E0WSq$&(fy0jO<{MU76Kc=J|Xn zQ7PIAKTL6DQ_(k-0e}wssc54m!`bxZ9<&@>6<Bnl?~nrh^djd3iB04jP2m~s<hq5% zGu<u6Zw<Zw=HM+|J@KUhN#e9KcBFPO;WS3}yG0rWR&y1cBDrl1Ka1G>)QzD;tMERs zzl}m0kp-Yc$(pr^Zl~9t*PUQ+&|hC(&^@IdMd#Y)VA%G@QXwX&@t7FpMnl)nOz~Lm zuml=^L$dK#9c~bTtk}63Izi=s+vL$Z7+8L3&=j4lcLEThpM*8HnJ6YA6Vsz9MB|Lc z6Hc&-=l%BUCue<tc@MTEKx37KA`a>mV5GpHPsJf-jWgfrmChQB#`mgiQt2lC3v@$* z(-j~xO5`G%{#~tgRGR?~#2!T28wGI7MmEW2>|^lrKV^knUZov)wlr;AFlHwab13*| zWN#(s2YVx5x^968@|f`LQfiyDY9F}zL@KLLbQxkXKg&n##@XK+v>QLv-nuw169=&W zQq{AIuWjXrlQ%i4ueF8KqkGr7)x~8lo|zv8z^>_+WHPU^6|#=dezgTrtt*`-p)snd zGphg9>n>UB{-9L;kR|URI$b_Dx;HshV=wXO>S|uUtXTE_b-X5@`nHvQ=+dK+?UA_r z8{A^Pm7s)D=t(Li>hi>+PJD8C?O6C%ob1hSV2$}o%?)$UpRJYsXWOu$*B!MutyOO` z3lPx`N{%R(U8ri{#p--rUS0&{q!@R5Gh37Ho%JWD{sK2IL2adN4es>PmQuO7b&7g1 z4Yh1q(EIfBYg&>*o{hcSP~XlqU!toJ2>|4;Tfu0S`WZ!ph*P$p<jGGMCjCY(_A=dA z^(gic7aELp$Zt5Bz<w_>T~eAs*K5vVQFR&}ok?E>&JLeJsIOAu#Im9WG)f+<uKP_! z@I4rRoxSfmH)hpcYmfh75|5a5Nd189_CqqzR%!x_?RJJJfYboD0d5{qc;?_(rZX*o zoH^#pUh*piiU1XENEwpt(_2{5a(pOir&wawRGf$$cOI|!l@=`oGGVZ~%qVcz-PB*2 zEHwOMKiC$y|LO&(Lhxq43C1Dpy8;(82t*021OyW&2K~Uh#76bEdY%~v{2qGXAIBRd z_a&Bwf(Jt71hUHj$lpnxV_N%zp39)x;QOMTBOB0c8$CZ|hp(%Eyl0pqPy*UlEb3ed zgturJk@VP8B5jz7;q)?4&Ln}a*0UA|{*U;7rl%tEbLn<eMUmo+P-7BAQKV#`#k2#c z8;)?<j{3=$s48tatnnW`(yBxI$kQFFoBvAM;Syr0DkUDOfe!0jV|l_z`+654CjYvh zu*|;EdQ5C$WMhk?IMk%E(^#^OLCgf}N}W;)Ja=8<YnB4RG|QWys}9zwLJt~QT+}Ph zHLbfN0}-EZ$hi=o@$U=OaEE#|F&KL|MdvccpZgq2&>akIfxo)+-zj2QX0cx7MeuQZ zWeZdfwxi&#`@~ibunh|bjNru?5jen3aGc=WLFosf>Lcpnx6ESL%5Fs!Dn$-?<lQ$! zDLE_D^YKIyX+tA&k4zCI2*`+;5=Wbzu^ss%HHy^o(U7;7OzI-Zo$W+G@Zb(=6qqR$ z)hz^A+`+$Ik$oQemcjMj)Y@zaItVe7?b+g+?813S(|_I0y@d|@W*Fn${qg~}?_DdQ z&;_PE{xZm{GwCJ?9P%k`3k<%^W`BuFxx?`E_^&X1Y)%yuPbHgt6k@j3liU|}I5|DV zyDn!JsyS>35ryP(xM>{-4&N0hx8n!aIu4JvuFyQZW+E4AkbI?ebBL2ImJYfWcJVZU z>3Ua6o;#?gJ-dw`CG#&^zSD1%g2$y8%gDJ|g0hAUA%9YTpe{U~_riO<Pvq!ryx0xK zFB=aSFr40)ob|?Ke`7Rg&EY%u+_oOcx^Aycd+x;3zPxS-(Rfp97#XO2P)f3!iBXiY z&Gq5u{dz%v$;nO1Tr799$@<(k<)v39*24V@>CzLG3_2;N;v!@Oh0)J-%BJPv`g4Vt zTtKWR@riB0`vKoJU`x^Xm%vJEH$^rAfX>Y1s7RxYuG$1bOpx+l74cikwyZJukP*J2 zxJ3$`t_|006c#xj1rz}8lsVI@>}xl^uHXB9RHf0F;W|#!feD`*r=J983L;Z{4ny=` zu#-PA(NDlcGAukYV0TX|o#&_6^Vir0&;|j@?7^bAYS-vn4jDQ52m65^1;tA#*ecb} zF`Qaq5L`kG|6cb1RYBzzs8|;=5<i8UBoo*a7-W<s_*(NDS~+1t85Ip4t@W$C3P<2| zS?4w=7)zBzo&3pf>Zk{u$A6FmivsmmKL`j9E=Ic_>A1W5!Y;-U|NJ2_+7rk{T10|M zMu8nC0XX3oHkeIM8`XanZNrR1vAh>YE90mc7D<32+7BP~%fC7pqeB=4e$y&Ikw6wd z2&ud#ao3Xs<V2>o!Lv$u52E5IMH4wu+Y-9ebrHCX&J_%N_Oe0Z69Nze^G)j&5b_x5 zBMencso5alz@Y@x*1_D%uJsh0>o<SdRS{xhc@2n7WTx|FY4e@j)9^K?#tdZL`DFFZ z_kIvd-ngUPeqrLSAQeF1*dfC^CQMu`mdV&cO>9Yxh-7ZX%I2%q>)LcRs;Mtcy1HA6 z2o?7$l|z`D43$ZL3o<RUwZ)|VwrkN2VEwFQ$q1&I#3d;ql^{(cP>5o}Ro%UTD0NS& zX6px5&MeD8O4a?Vs8@TX0eQB0b@PJOZwO%EC<fzU2_VrCF6&rvfNU0dJ3Ip8fcWAU z$XLsskoFP9UlG}+8G-4>YQt)@cEu8R&%1^Q#sJ`8=><-ug7;5<9!ChGi1TMll~kV4 z1X5J8y{{ClXd+fXN=ESE5DMBl4?ZxQ7papCoeXcCeJz-*cma%eOAt|c6(tP;^{<cO zi>zI^RsRvO_{w!Ucq*$ar7|M7d{knoVmxT*_RhMz_O%~-!!JtB)+K1ae7Vs4aGx2N z@w;F-_;CquQ<=uskPm5RuZ#+r#G#ogb5V-zD_L`6`=XljwD3>owT`NidR21M-iy80 zXKPNe>63<$M~>aSq<U3kcS0B=`&ZpicI|~j5pYxHt~*oU(r7&AaG`c#jg{~T;mU2n zLB)19y~+4zHx!~0{?VhOZLAHp#ozwJtMx0-RTF93=e>L1iyHe(QAW@z)hk^<S?vjA zsyJ-XFSUH2tib=M>hB&=i^;c7P<QSz9F#`M5C_MK%pUB<V@Z-NQPJcwAD~04;2Dtg zuES_ON8UlzRRoYj0fXVEt5DyzwwI>*_X>KH*=6~#@Q#ela|VXjR>$`&WhlVrLqLEN za`zOqVv}#_U{yv~E2HT5nu(9lFyILJqU`%AxO~58C?H5dvy}q-1$2jqHe#W)7=QG5 zlrC#K4B9aGFzok2orp?MXKKo!y+=1mD-f@EjWHQBp3cdPO7pHQ?l@(wyo0?OQ57<B z@}(^%jD^s6i=AN}6pRxX4SlO_YU|Uh*!kdo^{GyQ2Hz6+HIoSZrWc|SX#9Ba!i2dJ zNcvwnmLZb>#h!Pb-Cu2-8Sz(1WS6Lf*D=LZv`8Qn{WtoVWjaFv2UNWxWN=;+lYfxJ zl8}uX7~^iZ!C+-5pBpEEn5c5!kZZOD`%{i*0J~%oP<yYr<B{^#Dn|cx$CLroHhGE6 zOEAg_AmoCnX)-KS4=|WV4Cklmu4r)8wT!n8GBq8`*Ju<X9wbp8l@#pt{!iohn_%=L z{)s36kYZ);H4Th_$Z8d}ny#Bv<%lM>nJ-MMotvYmGeVY09ur@)!5H0<X7_5?s^REX zu%24MSLl4`a@H~3C99jB2jF8U-BO?)rX>bF2b}0z&K_7ewZ%wn=UDQXWN-_H#%5=C zYB4cnZj|Ll5m%>?T^Q&wIOrgC4Z0$x7~J`CI!r>^!!mJR(7M?bSdT+>4)p><@_unQ zB`vZ2HgZGdO>MJ-udS1ZQ^(qi4S8#XZt9Qc&tMBiCHNx;&ny#<(ky&YK=gF5Ol$^A z^G{>T-sXemRZXpvomsu^T~qFHdTG^U29S3<4c4Q_z&U#T7^7njWRq@f<Gpk^KJe{Y z;B*Vw3@dIS#^&qFwZIo1;qb^w?o>&rTR7ThD{aHHub02;%s3|E-n?{4Run5z_fDP& z8=EFBS@+GcP3S+GZZkS}^yRrcHnFJFMcPc?w}ks1+RB56?l5?h3uLD9gIZ_7E2Gc8 zYE1_BHVW^3#+m+eOp;g)536HR8x3KsJn!@3Nr*)ZnEbp;9(U)`YVZ2~Wv&>2y{@<p z^jaXytvx!Q!Y@m@Yf)0toxsp0bdArv7JqJ*HO<J$S5~z11c6vW>PjIUa-ROI_3Yd? z>;63=E--_&oH5{Q4NX;yu@Sm)ealwv<QBf_evvF?WQM8o&@G+*Q-b+D7<%L3^jDEy zwNEiUaizhdUYOXEl#OBRxRd*U9{ei7`p5P9^!irFRAH>X!&_|;UZH~~uE(!QEWD0b zxt3V%Kb&UsxTnpxL4Wom^ZA8VLKPfivnQ4!QM0TyN`jL;*;E_Qo8d4cd}_x}bMg~! zz70^Fmq(b^Xfz@-H0i)3+Pa>zd)Z_Q#kC(!vHm2A#nqHbbf#V8YbGm|bE09X3ZTfw z;csc!7#!*+(1+HVPmroMpOvcw6X3(a`bRok{j4SH_AU<3EyQ6nC?$s6_ULriNAZ&7 z)@uN_4_Oa-yTrj?{Bd(?yYOOd^}N06`~H7+7zFaFc;S0kDbC2_SyM*EWXPT^vbwW6 z*$qH`aQKY|_#k)gXW#T|sX(Zis^WX~<Oj@NMV1*UQPPN$;h<jX^;`djRK{ojM%6ly z+QquWG?zIru<EDW)AR@krV{pg*vX~vA9cvD5}{b9*pjcheZfR4jyvm#wfbOyD~CcE zBN9dXi8+%D|DefZz8$={-`Y>mDEh0naDbH5Hi0T|bskiPi^kR5+d~`YM{orG>a07b z7pR>sDB)=;SjtGsj@u1A!8O1@m^UsQ`E48D_9UPzLTRbPpoj2-(E||FyV=PIO7tA) zES?ogv7>Saqk}>(bWD@P%W0|DHwm#4mCgR;HGrTIE9gq$Fz7MC8})$@AEO6&=>FUU z8zv2Gre03_IVoAu`7I`i(zeM|33j#vI`;^~u`q#(YLH;*D{Ca5ysgQX%rgMvus@A= z6A;hCO9*5vGRdf;r3K!_O)T?+(B`re6fMxb6h`0T(&R7BkSeuJJ&XGr;lGFDbeu&l zRL5*q;<N@!PubTOvi!-RuDt`nZ)LkmTlrloHpkL)!t6OWoa&!%<|UPg%6&-w92Kiy z!XaZ4Uv&t2XzxDq&#2e(6M3ziT_;RiaBFt7*7X<iD%LRD{IZwqh{Ctt&^|{Y2A74R z*$onhVSyTfjfc|Ms~v#Jh4RLw7F(e(;@crHLPR0m!Y=PGx<^5WmxkLRRQ!vA8xYR$ z?ASu^G5SJ4fV@jWdzZz3#P&WpKSG}rbiQA@J~Y$t%%z>d!+CY~GL%zAdkb`!z;=&% zWwK>?bDdw;IH%+tN#cr`{5$_(H8!+0{Md2Z<TJ%e?X3*WWx!_NfB4w?w?eq|(cN-Q zmJj3hCfU&Y%LyB%#%t5!<1ThR$GuZ5n<=5>>=r30_df2KhvIp?uJ<0Vc;@k!-(jH_ zy7Arhr&<N3Yx&vYph4Icg7%%~9)b1Bmvtli0s~c7$J2hby5%0*tz~nm{AfL+MVWU@ zG5PWEQD$4i!G~ZbvpSBY5^<^AH|KW@gR?DD4g3WGgRWIizwTQZ9)tOv0pgl!+uo$B z=<%HdsR&;Hin6auR4Mt0AU;<`dPaHKfysrczAPUI&$qmRp=H~hr3<aKySfw$kB@HU zV1&bmGwZnmDEqrr=U9g6n0P`-qMUkx9AD4*DjA6MDYyShC|Y65@%Tj{V`d8#LcMNB zhW3e-AfjFT`iqTaib)h_7o30<<PS6*oa&MJlC2QFJ`qj?)*6OM2dW5v)`mz|t*2Sp zA#%l;K}>>YO+pNvs45t-46Fc*l)pkg;o=aw{eq;c{48w>xs!<DkSiHvc^OmurCQE^ zKu{LFf;O%IoLENG=AE;NoArV4t8|XJ2)_Z_N-%N3KYvAj5@6Pw;f{h}Z19?9=v-DO zwr2VD=7jc_2rJ<cwkrz>4=f_WfVf#;-jE3;C3{jm9BR5N?wNlf!Dcah9Jw<^a5^>Q zJyhoHW6p(mHkRq|teVl0m6<3NhDjok{Wwe*Rc48#94$CJ{4$kN!;64s7RxFd>0dIl z$kQ|Ld3hJcT81?HnbZ;H1T^e4Z*R*Bd!3Elf!oKMDHrDK=7V-c>>l$tp(RfQfu{AM z3DmK(vVsYx<xtp<)V~LiV}GoFI&1va@ajb^Kc7W9yVAtzGT?Sq4S<z(n<<+`O#D-m zl3CMQBh=%0w>q>IW98%Ka5#~5mb<xrZt0qp?(;BX+ZNKN0|xeWFDoIcG4<tLesre6 zyYAoH_RJUc6F91D0x5&=bwiqaV~$~+fM%b7L93iaQ7jFC#P&OxYb&{n^Ep_i{1f3@ z14=53OILeee%ryneMYs_%jDsFS}nbQw)hZSQbW6_SwlbX;vmGF98-yyiWM7_e*8GU zc{M>Ua48W`E9q&;R~~O-K1x1#eGzY^uAjaLRn!K0t`C>uw{+QcJ?qUq(JDop1Ha-2 zT!)2!Igbg(=-568Ds{~iyS1loJ;KWpQXQ_kmQH9k*r6uP+yU>5nJd!x1;-yhFz%iK z4=Fp-GyHnRI?QTaah-&Xdk+WNxSXNCnSqqurzuUJTQdWK+sqlFn)n2SEUyYH_Z<O^ zTaVc{dB9QYk;8eH9)k*{=mrJkMQ=EoM^A`(LBvWS0-{~I9aKp1f^O2^`<PgPbg}ke zS8zYpb!;wv;bp67uV{Qa7tPG?{uG=%@K#9fD}*GqwR+SR7IszIs7fwC?(I!ca&VXu z(yBYgpW?SbBCP-S&}+05oeuU&t{Wt<LFPDrlS}J$eUb~hX!_nmKm<4LmK7e{BS|qU zT>OgpzYpi72c1Y%0CJ>fo)~yfEZe#Kb+(&O%qt>Uk}*KMJIIL4%4)_g#xe&BIWXIe zPxOiZK@FsUF^W#IaTNGbxMb~Y)y$etngSx<tL3YfgX`J43iEmfbBPY45b5p?gxQfW z{^{h02+9j*Iir)OuihG-)XAT1oS8ju;``yp55^HQygF{}$MWVp665m&+;SLde?T5# z%qf_n=z|v+e9I9eVvE?J#})uGZ6sn993)i;W*vO;PLj<TrsA283pq*eUr-kpd?1<6 zOYO;^uo?um2>&cdW>e2;TM+QbPe#lC#QS&SY*jvT_DxX#dlFN{zFWHf4}J5e$MN-o z>Q;MKKM(PnUC){k<glDP&JJ3~m6X~1(hgT`?Uv6253kWbAE9!k^Uemcjy(x_hbzmy z%@MlXvrV|k9it}8d*ANTGV}}l4Uy7>9$v3-JyNZ=DXn_NtggpB)2w<)$JK2dviB+l z@T>nheTuh-&D{0)s9$epSu5u*_&Uxw&&xf89FEsEJ}2j<%R!Q{@{thb5&IJXy+OuI zQRCFye*L{8{t>3{zB=TTjC=A!kP2!aD?e02<C3{jt4Gb-B5RrC_APQ)l7Bi<os+lS zL?(kxV005i#?Zz5WL?!Mb2RWY!Q>^FO*fv5ctai8CS#OHLn)8QrBMEDoKPo+x0gZv zFM@0T*UbvH$9nV$uc=e6Vyje+G6K(g_flxoix73YkJ6QEwitFvXqpgz@ltg|_ESrD zzgtSxZQyG*RmPLa*$ID2uIjdUa^YA#U3V)VB9L|RX3@1WE@6$nd((geC<47j@zD93 zsE*fcO|OFOKri8KJ90w~>4#*YZucs_l24Sr_QK(6)6VgO)@FJ0k=vD!bjSUg+Ru^c z_nGC&ZUr~laBH9s+d6>)V_Fm{nd$%znwX|(v+4r(#+_0uIML0A>KumlI$ag00X(Ff zhb150AYx}~ZO`CIR_QJLljyoNgS-X{49-LjFKSw(ZC>Kls9-BOnlnZfkuj+PR7;b( zy#ow=EXT10&3sSk5TH%{f11YMI^4q&eUOmuI-tVcE0_C*ASg7-qeuZidkby<f}RRF zMbWD;R2-W_ig(7{?&w&{h92Jej_^s(06CXyGF;r?jxgDQ2F)t3N*`(af-OTt%-Ik8 zRCE0FPcT;7LB^(x=!nx^E<X6FDJQgkOghRR^cU6OaZPe5K~ff#b1M}X_BwXHA&b-D z*J5lLg<=W3D)-z#ilRg2zVTD(9n?`3TL_|j9OIdr34Yl{Vg=V%oH9AM<YMS?8a+91 z1Tn}s8-O@ic@-~rKA4A2nRvhLahn<Mmc5ft%liK1-22lL?+~L)l)i1FkI8x%_W0Gd z#>E=ku`aa>0k6idt?5_xf-GVmg9lH&zLBemt@joB*R$~`4j&8e+`RM>{qJ_XG6Cv| ziu6oX9t_p9F-05PdzFN~n?=h<f;KeY^HXBYT9$Bt9b-FpAD!+kRjh^TPeJ=ns$E$c zkGz^aN{Y-$3r@%W9~@@%m{u*TE~{PUt!VN>FKQ=?$3{4@n!5Bt$~2Fk`E16d2Qvf{ zyF4(UCd}5~c?GwX;PEAs0*1#oJ&D^s$Q39x*LoZ|Y(RVas8EBQwPDCakJCDS_<<nl z9PjZ8++0>UOmj?%hC@?~Hw#Y3(+XiP0+o_Ch-o&;UNTHvQhu<!dIHjjKI(wTU<%O6 z!(+!{`!EB{xi~hlaln0qy($&s-@9ANM<ro{^4o;(9}~6ilI`0QtyV*z(AUQC?J+7b z&GNEoTpVuUjB0fWzZ+8_lfM0TgwBOiBuwuN)lay8omvZq_j!&Chp!Td4)F_=I;+M% z?{<-OF*}6@A091R)B7OpHGm3Ca2m&2r@c7v+1UoaMl-xydk%c!XC3e#o;*3~jXUGs zQieElUtBv^jSly*CWtpP<P&mW?_#nHj&7#k9gb6cI8?`n&gyAJz-zs#3L5_mp|<67 zHLxtP8nH++)WQg;t%`szB59>cPBO&7gmR@7MfrZdtdt_d04b=J!Q$v{FAOr|)=n8Y z>F~W^vFXhyW!-3aG+e{-uC6f-t^q_XJqffEiVH4G@%c6Ed!pNOphplC{C|}b$hZbs zzn!_b`1n&l(8^tyfW7+}){9<TYw~<dfuyyN!VVs3rtdA`3$Fd08aOCr_?-4$H({O4 zgB6odT^-YyB55Y;M#6&QqlcLVJr9v7Qjx3cHJFw>U=M-cULPb!c5yv$qs{eAy&W1~ zNUi_A5PbH`*3~+tx_N1AyrRtX4?6={TuO10l<|o9yohaHxEBKdh$)=0*@O6X_}BoU z&48(S$&o@bf!ait`khZW6a<SRqN$6>`F<4`E~JzR7vswBz|{kd%-YS4e~2@L8c%W7 zEnk`)o4He!N~zY-4#1Z{`?Jm?WQXO|Uv2BJKh+Aih90wBe>9g42M&lobrZPK)V%F- zljo{E6Rx=hk1y!#xSZ;49v){Z3tV6;`Y<PIxYua>3em7KUf&%1aP!e`P4ILTp8pB$ zVNX%+rx2Hf0i<c480}(z&uzhRtQv=;BapV6PFV2u8yY#d35*mf2wk4nW&VTF&OLqA zyZ#{|`KVX^%r*2Po=7OjE}N4Zq2XwDP2;kQ3Q0qCFp-L7_PkCxUG644>^AU9z?^&J z^HQ_<G82U4OXPd9URMYQi6ms>{TcodHg@XJH)O!f@a)?BdPYU-QJ;)QO0K0B3Qo~Y z4hDw)wi6oy8gouiCv-+hez$Rs4h)G9<jsh<kukp=F-gcFYEmgRe{$)j^3Ctg2maws zUE*mhkhpyz%XMh&z_cN1XBrtPV!N`O!=yWJubY>&_D+IV5YQr_D_Mk0T!UF{(qFsc zIP_Ca9Xr5LP9aXx4!b~<7P8_vl1x~`$CeblI`^wPnBWkYx(UG(D&YHIUczxLdF~3{ zK;HHsl$q2AN~xb6ULC8T-zio{5&YXYe#Pi{!Zqe-RC0Y&hy5n3y>fEoJw|weMpsXe zl2vGj)Z8BGJRYd>+(t`~>D^0SV^-FE`ddd+8@(~fS2V}=o|~k!y`4~F=gKB-Jm0ed zG*VYKyPXh#9O)XT&a>n3DyGveW+SK#H~aBM3uXhKQhsJg;{<}^Xvry{GC@p1@y<vV z@JYK^8y{fh2G<XmAqFNZzJiiX!ND3ms6;o-(iu?1+}$QVkl#l9x)IS3DC_2?!yPSd zHphGB{D=k7K>wmZs4>#L{pP|ryf-_h`?nB8gbstkzqA1*zDPu(Y9tgZ{Pu(3Ewdw% zV1uD!EowSzJlBkn3)cMnT$SdfS_Sy}Qi&H)(XOiW8hG>^6y6u8_#$Wp4ZAfA!Jy%t zMgVPyhMkjDTo_-DL6)+ppIQ9ZwpcNSFiiAH1CC$I8Wm!zWv4d1eF9d2Lb&5QN9o=N zA(LPU472=Ps{W3e_b;Q`8A)g6TVC1b7Q?cR2iwwS3wiEux7mJ+HtR`PZ-(vy&udSt zF}_m!xqna4;gXb9x<kKx{4ATg&{*aywe3tp5LR5gtly2n)h&0-e>gHLO}*%uDK-jL z@1|K!U56nqWGXFt<Hd6lD9rxaz43{IR`mY+>M2#tPhmsE?kKF;CF+q|eBhNdcVfPF zJzCi)Rx@Mp)N;0A^D(3HQK@l{$V=6kK+QP)dxp&)t(UyTRM%TBl}qPb^&eVC-c!5R zFX|jSzW|+VlJdXNiTWnDk9?VhSH2_Qy2YsIQ3Bg~Cog}cj@@~uGIc%{gV?U@lYQ&D zMx!X#YE@yTA*flY%{Su7AqBPdODL|dtA`PPDlz<KG?)9vlFvfR8SF=i4W3T<c0>)! z^??@8Z|^+a+GqwBg-P7H5Yxdpm0@^2v3%=fMO94>n<LAJqWrQ|f_)!l&wV<3pPhU5 zV0frCzkOxv86$mg697M`x){cB!m--4rpvQ)`Mkg2J^CkeH!G@3zFvXS&P3_~mV@Fw z+fTwf1TpURqV2EgN4D8WS)dP4uu>bntH%S2|8MDA7w^w4pG+BbJcn{lGqtF16Dv2P zWh3VPq~63bB{2kvbrqBqc+^<-{?a5%2WM47VAU}(%}F8Jlw$|c4m%k;y=+vrXo#8q zr`hVzK#W&H0q2ILby^OtCC}c%hC~c>BKQy!-0_vrcxYaMz%WrNCKx6%_4vMAPMU8Y z0n)-UGS9ja5FhFlhNO`5=V-yGIl|X8S^srf0Jw5rW&t#*scU*?;X2g1koF%2y$z;a z;wz^o*L4EkMn{JK40ll-VRW&lmWb-@NR2~yxzNPf@V?Ve+}g5Z!o>OOHSsMf50Fbu znv5&r3h<#2Xp6{<Zp%<*R6PIlTGDCmBK$LQj^l?dUkQ<_r8^*gmoCFwW!%0vnqc?T zkJP|<t^)@ri9Y~s4h{X<H^!-+N5=7k%KJ)aG+CbR&NGpUHaP}AznrRR%Cd28<?VI~ zc~vhi`PAlxk#6QKCGy4i1tP7YQsGBihE%L4*2<e1{n^xr#cUn!zih0Y%hr>U?arun zJ$|N)yOk|+qgOM$+sFz5MY>y|!uS1TQj5{fi}SVCG6{ymsJD`JpT&~1HDl`X75a+L zU@V8C;o=q>`59Zbe*qd)z>R3+i;62d!?V!^MvSH~D#`h1!iAsD20gUPrI+~xIrLO^ z1*3KxRG|!ATsj`Lj0?7Q{L8$}$$hAAmd|j1wbt@#S}L!sDxO%T9tSEWGdP3T6_Mjh zp)-mb%URXA%=hVw-!OcdO&<G{A#Dh7^dDWH8cN4GdCV`HvCGK5_;14t|JI^sZTV?= zKUS#n69Z#6wHKe-j!)PHJ%9gpC25(B3ek2#o)L?NbHXuQ(U%n=tN)BZ#sCQ^0m=S0 z1obbCGaD-v%oK3R3ANBK^0eI`ZNvMUx=&Q%U#cwcEb}L;fVVTn!@Vo{{oxcKrtZ$2 zMP;qwcy~#OkJ6-#n@NeTrRB7cMT>y}iqFU~3L>u(Ir7}~&jX)CimT1>#}V&G^+PAG zKe=%e*l(Ji@8kbo8%4SQJ;PWV3A&74zeP>YwP5fiD?Prv4ht5F`s8Spxs+XAPe7Ur zY&1U556#!x&8+BEmE&d!{`89eXr2sHEy?{lEbOdm!M&V2VE3+V4)|-uS+Su*=|2r; z*fTFGT1+{%C<m??OjYpRk%p&9C`%6?8QN6~Pbw~bew9y`j&4lh2^N->1!@zGpGYz| zGR9a@5#bN*EyweZ&K~j-hX4PtvF$Gnv*#NSwgaqPFnZQFzaQV3ER_6={Oxg<yNlYm zywoe@txeOo2|-kEP}L8=^dcfd^X3-HxTIzI67lBOSIF@Gm9pZ3-b4|qDecuyra$zI zMPZTKIJRO%DZorZ0VLpDgD}@xCoh2ik<n2;X~$7zY$PKS<s49k2g;}etb(N-X=rAV zK?J0)3{%_u)Q$rW_egPXoLmV=3V06LpTvb@f2qq7OAcamRSy0InkXM>c(=5zO__O6 zg>ex7sdvh5{)8lYuyb{j>0%c@)2F#=6X<!Pdvn%(z|_KG5~`M6TwT0-!*C<oO{SiF zVp;T&@enFn^(!fGD1Vbo^kf>ni#V{tT|2<2Buv{}x6f<?@llON0x)YjO5_$1lb+^I zf;1d%*n0*r*#601gm$>Nucge`)LIN|GM?I>bHC?(HSq_i*1l8uSg~B|#HR9d61qnV zE2y{54|6Vz+8K0szBwaoY+i7LTv6GjWUK9)sa-j>5U1h>BsiLU%I9EN_nV`E>%9j6 z<OK{Gt>>5LnE1);OkUg1bK7Hd^i5Y}Qsk&;t)}7rDPH+jvfMcSv(KWsDgjM7Klwvi zfE;BXmu|;P*glw=CyNNnpdiB-dr|a1wO0*VA2!{kY*dh{mHf95N(YSv;FuJHS^v?7 zXxPeHmfYvI$Azu_%k~T^KxNgb-4;DSqg#MrF8tyiv7Qrde$&8q?BzCowUk`Tbv~2m zyWgkp{XMlhor9n$H$C5X;IdrTI0s=u$LHRyK9h#kuTHUL_Ux9VWi0p{MNK+lht;Rq zx(DV=DZeU=yKei*vn~AXp{kM+w{LP~RFisg`j1`Le6JM1kEnHrvX{2X=?gCI?7Omu z27JX*2M^hUd21ym+8#Bv8@~HiGog2r_klW8;uB1i2wtQ(9In8|=A}P$EA<Vf5bsLR zFsb|3;fjvyWnghgFpc_+;Bj<h1lIt%a!vAx7@gx9mG2x01wjz2Vz$E>*)M)96hD5q zP)Uf@v7kn$3slMX3QT?p{y)mdmllx18m8v!sh`|fyN~BCjpMVxxxKE3O&uNA*36Y> z9Tr-1%m~Ya?+Az%5@;7Wb<U7gY{G7Z;Dm#9bIt1aKa8DYd!1d^w%fE}gT{?*Hg?ja zu~)oe+qRR&ww;v~+qP}nHs4&&w%y;~A2H8!jxqORKQ`ebBLWC?1%z9(u(!+Qs`UFE zEfl!(*=jc3A+a<HU3l`O^uWIZQu-k~*yW}&FKtBIW9QOYu__lv4Ql#Ifan`Cu&yVQ z%=E^3bqtiNW8Jgz70M;(^Yu<rq;wk?6RAX`=fCp5Vf{7SC^sD&U4$On;H1YeFAnJ8 zeF+Jekz_rWb$rIvjT!By_Cb-NoaWJu+`a(_cTca%va6_9t+`M8UPrv1%-xu3dXDZY zpA_z`R{nlCVhxlTV{me^TWVRqtEgRx0qT3(HQb@Ggo&_tPtV%Ut?F8*u`I1SFC~?{ z@a=_>4Sc7*4JzRwH=TUNMp`O!H4EBTkM&xalelBUOOa%yv7}zr$*bS1j-fE!<zupJ zpD;K)H)<%p|3>{00N0TdsZuQ3w>Hsj(z?);9++1uDf5jB%f=6=RbV$!Jf)f1Owj~* zO960htRD>8d$+RK**Da{+a-j0R=7G(zOK+lhQbSR!{=Sjtoq0ppbb0Q!No9<qr2CZ z>E@A<gq~V!I*hy`kUDCpeDEc>N}LOb4du&9(cJJ%8E(OX05(xO7Ud;-c)->a#Imr8 z<!Vj+4d18MmwGNQ;)MfyfL(2TrJ95mO#xjrz&8;?;^-$KgxbiUb|znD#&Y7Zac0*z z^%hN>$77_#X{&l%t?hm^1;SPiynI1a67yldEjng$4>?rHmkZjsLLk{#V*6O7So#G@ z1E9eXkg!D4;$ER0Z#;tAQ1)~UEt%k#4;PnT&1_JxpKxSXQu}ZeBuyWP?u}|?Z~Nzt zc_*|CU&}=0Aatq^XqD^`s{y7PS2NLCkXd+}moNB{MV;ZUoqbiJZmVdpJY|<wUaRV` z_Mu_cZm2Ffp}kPPLYtvDnchRfr`Y3+!O9v=loPwfpa7>ZAIPY$--bd^VSt#RoF~Y; zP!nh9xQvTYh;BIDB+xPA^^X2%YCg$jj>Eb+)lLW%B@<<QNm&Glct$#_sZ(A7m)WaP zKLkUC;YIaQm;pQUvVXSseEBzLKiEr#s+1u)xN8vgA-?1<`aw#$^|5y;=2E>zPQ3Lw z@9*5UY)*N{9wYHQN0F|de4yruc31oT{vi8!=4>L`Mzw^;==^(*fI!u`h0GjAm?`sD zDBu$)H40<K6KvF%ox`>7^lJgL2roI==QPnJ(6hN^0Ey}YM<JpJe@*zr6`Nb6P!C9% z5PwG$EON4j@wc+L%o6TWaO#KPk*I^a9PGzP7TwF9ccEl?f#@C?8r4MG$IcKeTcFY* zWp!&CSBA&@I%-Hv`p@#0(DvoO2z;!7VTbg;$k}6qD1$gZhJ=R+xMRv<#eXo4z_3ea z=7ww2;zdT^PblN3Yr71PC$Ytu&1reKa!XrOa=S9&QF(j#pN-EswHWU%il~?fMEWz6 z%at9@widNZv^jILMK1BidEoG?Rr~rOM!#j_DIs~-@P4$9GMl+4<kQmxWoBz(g7(+K z;U+-K_S7Ah%3uj~&mU(5iVhFQth0M4tj$9Hvaz!!&Ux;N`()_eLS$O<eH61NEC?4i zPf}<RN8Wjs4+@^5?Q)5!SqmS6J!uvfz1R;-QWA)9=s2^NG9n>K@WBb(Px9C`Iag~H zkf>H^6s7Fa8R;Pr$=~WXBax;%t9o{FNmEr0cd9ytK#s>}r3=){?5U~idBhW-OPbi$ zZ(+UiIVy_x2y^X1fVJXtmoU-UN2}><ItE~r2JgdW!mFj*9Cq7Zb{*gzMMXLv&t%a? zjX0n7=1CW>bpxeB?ih*_SNodDhY^U_v`T#2;cfxcY^@*_M=U+<>+6vpK81T5FhmKX zBL)@y`6FA4rwp(z>|{5F$lcD9_7IOt&hhV|TWJR*prn(~moA1i&0Sbi|H7V|xBmls zAeYrMy9H6#A&AGIuuwDmLW;mEa#IhG3&E^m!9<F0=Nhm*`y2Ib?$ju_PwoPh<(V`P zKbw5LDA=kH!ntFwEn|1lNOA&XYjqQaw(L-{<_AWVk*|Uj9ijVYx>u7L!6l(=r!ecR z9QPSF$JRB2tMwy96}Rd_h6P*uP?gSabw~kfCRom9&DweMWs=l$I55!UkQgZm8%djg zn$>B6?G#n_YASu&6%+E~a=HpsIZoOuD~L;#?#&`v0*T3aX8j*nvh^m3i#?=F{*vqH zWlN8C*lP;GwEi=UKFGQ?zCDD7h5gS*P_zLVMVRTkvvKslljVO&NkhcFqskRM@GfV> z;u{B#d?l*$O$GuVHVGZy^oc$!#m7Htz-BaOVW|^<Szo=#NyO9v3IqpsPhn$((M9RR znbRWm<9X{kGh6=N-Q_(R^_XJIHsk(^FD%VOi({M}Le}p+h~(0HQw_;x$KG%qEtS_p zfzeRupr}q&t4wWP7O^f<RA(4Xhl*b{2KoNJhYk1n5R#UXQyM^<axr>6=#cWY6cs^j zDt0#}eWS9cTWaPTns$-6D0#{$uw1*P>aoNV0h6HK^hCw#^;m*rp_E4|E?5K4vf0FU zrW`r&Kmm6wBXx7`$WJ8>tY8Glnj^hiRzD_UZ4(wAsj#)lSiEMM^BS%1#CJ^RvJyXT zKDF<m|9v+?e{xvWm@tq&oKS>W%-JS;*>jI46Exq!nA5*h6%jeME<H!UT)N|#o?rh0 z*O8xFHG76Dy(rwq#eaM5z)qUlpOw4q$<6?jC6XoxH}|NBm>7d&F28LQ;T?}LFJkq- zyhT5X8{~_TXe(59=M#_UXLWO0c)KGPp8o60*oaCP5=CVAs3r%~BMy=WJTq}OYfzrs zx8TgOZu^QZNbhCV%<wGwK3R*EpwlZwmAVHX^AUoK4j1)V$jH5J`_rB%tj+B{B>ONg zhTB~k=#~}FXB9x|iZ^Mn<F>X<>pXO9){aMgIM<#oTeq(Tvx`L=bavh!!;$CBZL3?) zdQICaOjMphRDm}jUP48-crs7@9^pbMK{k_K=Mok_qOakLC}cZgv9LX|`m}=+)V#gK zM2q{9isdRbB^%49txmpu{n7<H?fagxocw_GsQ3fCy^sPZXOk(SV~xYZc-$4)`>2c# z|7MMx>WSi08Z-OAW=pBYdtZsD)dLTb`Ku!p(8Y4|jTTy}W7+<7@H+E(OMF^-(f0JX zK0WJ|HVFuilsV-Wr5-f{^Vlg8<J*BFLS4A@ot<ZNO7#!Dk!%AC#1)Z>xx5D5v<WF& z+tWwoSO*Tu#(xC`Z3Tg05=w$bPAnb}a>!q1+W$rS?K7#PpHP@s=A>ae06*V%p#30z z*d_#f<y>r0il+(r+ZvLODjHGO{KTnxCxZ_bz0BLbiSGFSSWSP$fBRwhUTqf{ot(h) z^A~NRG1Dhj_u%aEeV-@k119RHXrBC%d3-sXs}}Rpc<~VA7<wdi!g|ozy}2$uA&eB? zNj}`b%a{>4)4FxPkOJF7k&ZsgbmZheT#?nF;#N&$(ZP^{C14#Zw_vYe6}y=pk$B?D zs#Jx%i6yH<8C0WaMb%uMrcQp<zNblKgaC0gvcISu%{qLiVeZfcE`>s^!N1(3WzEd3 zdrrZ)Us~5s9uqX&5~CYHtKl3j`w4ER40Ze7NKVY53uQh3zF>D5F1&4fcd;Q)&*5_y zVHS%qybfW4P!%;+dyItgdK%}RZ)>uEsRPA5<fa8+qY0*Cqhy`6Cyq0*=e`WJmZxhN z)YP5*1cAK0H@aqTq$>;kA+Sbk#hiTuP<&Xr-BgH9$2eE+5I?J{e6*nW$a%*n3K%(T zUH}bAQ}aISfwkD7o!nX-@DO-prOWfh)=@oWrbG8wO3&8tGi2}ZY;F6##$w)?BfEB7 zsFgg&UwdY+UKG!x9=E->wF_s@*4dUX8V-}TcNFNF6Z=O0+SHNEQRp9<ejQ^j9OAE- zo<g4qj|$XQn281#xSdhohK@2VcIU-1n5-hl!Uc)3dbDIn#*{>6R5DZ<t?3xH*SD2> zmb}vDbhgC5X3d1P%FsH#iZ4Vk(51<kxwE#d6zt;r{zi4~bz2YrMkyb!kxg5h-$Pb% z!>EbPQ)snnSu|S%=*Bn;CVQT^*`u;A2wws`OHo;tr2EW4G(~rc1f{SNF(Tm(B+=Wt z#N+oyc1YvU6-2S=(AJ+gM=M>E3cvE44V+D1xx%^W3KHape^-!Tr=Wh0@sLp{D`|O2 zT&^X3R60m#Fz1)B5tEvD3YpavbuSCg!jZ1#`jcRl-?;IZYX8z>X0EkwQEw}C*>VOp zvB}VvHIm0!P+BKplYn!&r$$3SbSv6d;n0VvWH;k0A%Q-XLoH{pW3C$($(uVlwLr(N zs{^PDSh;$8bhgRw42v;27j*wA8#Xmm6K3K(LX{Jay$DI)Bud(=ja@lnIiw(jbwJ%U zE8svwQ6^>PzU6WX5Z#312k+n(V=4J)+l)A%z4Kqf#GkPt!+M8_WqV89(HQ8YYWgvD z-$3IV#{IYQCL)@<2ol|h>3SuiFrX+b-h_VqnKjm<`Xlc#0~JtZOCr;+5io{+NqGbE zk;BHx7#;_16;>{yVkmX@5(oRyO+xWh>xEGz``4i(a$a6}@G$BJ$Jw9y+lVEo$L5ky zbos+D{ZM$-W&YXP=cAymRvl+m2gHmh3@~VBXYB16?v}SS%v&I&Ft7g+KE9rMhB0cW zfBCP8_VV8ZEbyfCY;@NoR!&20GlsHc6y<RQw5V6y+(2=(4vp@`*I}@tix(#1G|`YP zRJCVVGFHyzFz|SzsJ|CDZ5}n7X>X#jITz%Zv_WWAdnOM;MZzI)naewg8Ic63HAP4+ zC>(knyCxp56=A3h<^J0!abz*(uER#rEVNU68?H%1*PbrCTz-}bQ>iG(#Ka1qetJ|N zD*_cXtd=)jc|Fi5n%t}%GZb(3^oCZ5V{>$D$lI0HRd_zIkGb<OaPF5skbQdOA|&s) zrI&5fXn159E`z9fi{2>)8=eC9<|gQ@JnO^H8n-h??&y+eS`)=I_a!wk>$RROX7jld zf+lF+JPNke8+jt|T>CNfYKCYDN!j4PQAj?p=6zwlo*|XCbFJd~C_0%x(hh4Ya6-k$ zIH?Ce(p0~uW^(hj-RIr@rZAb80alS!89X6pyo_4$n{>UtU7<#K;&?pkH;i0mRCu4+ z-J~rP^!_pKK+t+<b}2hTkeCQNcKvP92};1(cp~uFtoa!0MptAScrGb7r%up5m^72W zN!wU$C*|;rD08@}pKVIezZS;AONy-*uT_&s)sN*$v8?FaMBc?6kdN_kXbhDm=Ug6v z*?wVoyqY5Kc_vlEc2~H$h21}5CUtVU0RG@&C<->ZmC1Z=>gJ}N_1fD)WqIOo)OxiU zTumdHAl>&&0un~TMe*TO6B@2gvu7M^+$>AqMaf4Vt|%$5;VYg^+C|w9?U)9RZDmY9 z3E?{zI;~c@OebpQFn@MFTp(RV!QMo{-fvu71ZRqW6~Eq0>ps|-vG$=YzGrmu2+0ni zqNdD}oL?%go0m{G*VJw5>zU$15{(oV6fIZdEE@%<h#h!%nhPWe<*m|<WjJ7~e}SwM zsc6t2fpi2K(}ekN$%_$h%4>;p{X+Kr^z>3a4me1Cb=^C-!{g)oHhA*R|KA<)k6`x( zG0NemeFF|F*(ixH{PNXTbSeLndlMBCyX*KG)tU4Wo!e!6Uhxx(eGwO96IrTW)%%iN zXwW+15(Y8)AAwE(q4p;72cI-p0aRAz;1&_qjgr`0YH(brSR;Fa#e;Ifhj1yj3rS-^ zo-#tl`4gqN5=LlclTy5eM0G)#%z}kpfPn`R1w!0()}jK_xQwl6^>aEA7d9xQhqLcw zDyR!R`_i)&ouSN7Kf>He!nRG;Ys84iw31y6e+jd?bc$u4o1SdZJ%IN-Gx#euA$pic zU;SvdrS4`kvv${&MXjY4j3zg1G+H?cUZ1gMN%<@o^4mGXTrECpBGNMgtgKzo;Cm}v zsd}u?h0IA*@Ylr$MKx`3zDmTU6rGImbDpZkTFy|dz2F}mcxEf!4GCjQwaZ!*jI{5~ zHg<*<U%`?s<C!^zNbna45){j6gzoL<?VYzW+;c7MSOT}$Eehn<24+t=A{J$YY49yo zH*fFz(5lmxwR9wFX!!D?^AwE?q?RyuA6ZF0-0L&@D^@b<5UjjXW$Q9LDG2g?jX@u# z*fx<+8pIzxwGLguTlV+pUYub&u=Ue0*<JB??c|%tJ*Z6WlcI^|c^@pG*Pb=k`!mq( zqx}hZcI89)jtz%fOTzl`pW!YSZL?gGCkc5URPdUKCVRDX0y6kOW8Ev+C@X)Ho8=e_ z!9~JfYr0Yu`^ty7e7d*E_M4`0xO3{<yne|=qe7dYGnzGL7yU!;enAvsLzETq*c`VE zmi<32?L2y8({B7&YRCnTM4gB0$dwoF^Q$B~a{PwpMu|+OgfqTAU5!Fiy>B>ORb>fM zeL>>83<XbLaE2&VGx5nkDPDD@&#lSyTfSm%R{wkug>_wy`T1>$$Z7DPdF>-IYg^Lt z7BWJLv-##Ww<CVhe7h{`OL|y(%DUqlSS0LxB~d-I=qi(%hQKN1#>Ol}e>T|3EV4`m zk5Bn@Y5Dp9cz^{;z`d5V+a%)f$r1D*KGm@~^o^br+R}yY5qt=Qynsbo!$95-5Fth# z5cq9hqIgbS2ku^#Has#gR9YQ<y`MyO7LA}PQM}v}p0|<^hWwP&U8o~vgm&7f)Z_i) zZkk^gnJ8%n#t9V+TNkY2V{i4l`f=LvqhagOISkuOG6f5#c&9*pW_3J2{ySU$o7O(x zthoPM*kk&UZgi2@1o$uQ@aLQCf0h3AuG0pvf{3BBAlsbk%8u?3iF$t?d8b56{DNV@ z64dhpF{+mmc_J(rryXWyndwzGZ}t$)M|@mj&o}xqG&bB)ePAm_n4D*LI4f?n8=jv& zO;iA0MJF#>r%IGfwlloJreAngS%S?NTCvtz&p?J5)!00+PWh`vuL@9rqwUk$c(1P~ z+`WbD`~eXKZyxn-_A42+iBbM*8iySU@@c+Z6tP`fR>2}$&ZZywj6Pq+%AXL)Pq}Xy zj<@;2>x5xlo+Q`vk$u!Lz8k-F8J>*eJ&<*!9NbX{=<{p?@>9uQ{oS>K5`Est$F`So z4&^!5-7pkPE5kH4$RC*blj|0>p5Pg?x{EP)<Zd)Xj*TPa>P}F)aN4_#VDSg=UVxdu zjvBfa>ii-Isa2!!9E?k$G<c+CTx?P{5@rmjx)y~~TGVXr&MelPedbcHYcpd_C~0in zvn+Y1y!#^We??)2$cgZ%)M;C+>FbMkQJ4@pMtPMP>Y1OLRXlSxiznG$4s<H}>_L2O zVa)!%30pN0-HD59kpEo0g#lOV%?>_XM?g5h!{>Q3le>(dB4Ky{H8|KDuzGS^fHJII z=QLU*TySman!u}<%z?|J7jmY8AA+c05QN=9+UyCjl8aPRmUo>evh~M4c)*|ZEFV=U zv0wVE)mrVu^L<UW2@_E%@usR2i#j3YCuf{n%Y~_RRY~p5vf%iM8MuDD{N77AgdN!t zUve)Oi2FMEFxoJFz&GEHsls?4q|^<h(oc=YATRj-WiDjL;=@m(Q{<@YI$VItHU96; z5^|GESM3)y5tz-Gc&Och`wKSx7m6+U#(1_r===?rH)Vj`N%E`>rT0rtZ#{{*#oLr9 z&_nA<1p7L^m*4VTBafAr$P<Y*_j+zDewv$0dO9B)NZ~0X2Ok=<39m!$;^q{%;P#|x z&2{8skRr-7qb7E$F0W{@iQ;2vLLkM#W1?k)zSSwx(oN!<h#2(!Z}9U4!VUk=PgaGa zF_ttTAwL)68W8K?{MrcK>32&`St-Wqb*=&^GbYGH5}Z(pLw9%M>WVL#`p?UKRdf_h zC`?Y7o8PSTqmBrTk|g3bd0X$i8q82}QodMHmP#?0{Gva0!2UnT=s%$7lTVGu`-CUn zfBcF4`0OgIgFH=hW#$v?NesMBp-tAmHAD&w=mOwSF{8hbY$D?jZ(j=DIlGYRKu;p! zLLmDh;4M|tVcDyy;=zXLyi};F9yzjg5__1|NB4H7bJ8P<Sy_<}?NUmUBk^N}jy3#t z=^kYhh{e*T?W1clD6h1W2T_ZWzd(FjomIv*XA>-_s@vNB?ecvw2sZ-7sQDB7!%K72 zdBP?gatN}B?)c0^$0L}byK<3Cge4g6m!)|z>CYd9I|<cmtxGu9Po`5jW6F9oTPvOx zz$$hU>5Q{sw?sV;O!|Cdv8AcAS)1ou@J&e*H?uFEvNUs}v77~kyK*Z4l|xMOaTho2 z%*JpPTC~Jza9`?dXy;u1j(ZhBr58Rs51sJTfxVl(6Lv=Cr?U5~-TU+F+9eV)<;H?{ zPu<%)lTX$rCMW$Bn_u^;_vj;d#oF`-`|Zm#+tBwdF{J*HZ-^MDVW>e0>~mb$OjW55 z;EP+@hqRVY@1l~TpRGOrPI&%1PPLmT(zjl4+n7;rV|sd8#(o)zg4O<t5=kIs{>xu? zBd`E68BnZ#I{g)My=+xvrbSb8&ylXND{|9FeI9|o!E12L@vXyw(mThc&0Gjc{sugY z<5JumuW(~}-l#gDfto)ZGiF`G3v$#R;tIKLD<WqfG~XF0*LQlrZmoM;+{yXPvi)6M zZf=ihWn!pf<&5<WrJ22{L7(U;!JD^0aW%iX0^3X(-2nmE%95k|gq~1Rp<JuJyt_ZJ zT`|7v*4BPlQ&5n}KzD0_K&nV#bUsEG6!|3zKCIFA<1*6ck4GFt{RP`fcW4&~E%FDJ z*Y$!Y!kr6S&0v^gGt!I2Ve_}P`$z1B`}2i)oO5@&7WUt%*iQU&_L|K%dn$o4tr56c zQ_@v!WmapOD8a#r9QC>OueYhrK*eRC+q>EW>&i&5OmsXoEOn<l<!A^sbVmHpU$S6{ z?avO^9|T$`H&!+R!b-`2@1J$*A&5x6GOTg=HSaq&>cHv<;xfyOgc7@02d>G6LQ>)2 z?@cC)PS~%Nc=ePkO8|K-Chniud%1D~M^k$O82A?0^k0As`p4rs(VdiyzNm0tr#S4M zo&N)nqN6WAZ;`go{9mKI$iB@tUT<tJc*E*occESjXz2UCa}b40_LN>y;`kX#LlF9H zY^u!S07BTA5<gj{O2iI`<p9QRfAAN}pOUIvh!V-dK~?@rM&R%i{fWt>F&gm~q3*Au zKm7x*v`A~hT^QJ8;$Wj52lOl|ETDe>LfMY&LSzf-tu{;+&#RkWDXud!XAis=5Mx}a zkL*aIq_MJgwcXO|r(?$a4yfvQ&0ZxTiaA`)HNzQWu@+&<NT-WpQ~@@E61ENAS3k?B zzp?Vihwk9-2Qa3?qu3#lR0X8Njy6cg)=Z=@FWp#&M3bn~(Wj(H7}=#@?e6I%i`Nfd zv(Ix^XjVF6Mwp<?xK5t$9e}PH-_{N`ENgb3JDZS{p*>GE^@MtsaXu64XLg~fT6z0P zCX2eqD_e_`YzO4$q@Z)^iI&-G^1w3^$tYWLN1+4joH_JNC$<%q$M3G|g}wunNf%Gp zNL0?WO=R*-qG;7oKvq69mTi$eCT3$=q6sZ_FnnX?$N}JNz(N}EFta=RsCq(g-Q6Jn z27Ss5)~f*ZX&$q`$ouCqLvu3Z4=8SYNR5E0ln5vipQ3@A3TA<y`CNQ8q&16mQ}G6M z#m}ZwSD~E=z+)l9xu&s0v*R3}RSCyPIJZlGjV9K|@;dh9*J9%A&6>OO2$lLPj+*AB z1FP#mif^Xx#RCe)?dpvgmjJKdyRK2!ZDb2BC9mOV(nc~HLL^bK!fl*$Bi2>+S#$SH z32riE>wt(NtowIp_0vy6{=+<i;)?Fv!#>?R|LX15Y=Y`Ty~I6>D~cDJ^}H)RVt01) zHu-J#0<ErDFi!?>P@PxQ3^l4yjxdDG?9GO-bUWq#;jaZvk7mWpp?B6d`7Nti%Psxk zOpkMgVknE7ydHL?XgJCHiGZ>SX-P2Ofp5Xcg?nFW5xHqpt?;`!3JI&Y!eW1dxV=<I znSH*bFrdSQFK;{V0Y3GidGQ}f9b&KghG*tM_e~C}-pRfOaL!Zhuu@iOSmY&KoGRUT zYSA={W};Qgqbr9ghM6p*&Y-K31ANyS8}dBSuGvF?tk=EyqqdWy@;d@#sV_<sCGAbk z&fk26b}t07BNI6R85(;<9U4AoC}EC+i-}Enm&&}<Gnk=xr92Vd2@oJ*pC+Ocx)90@ zA=5|ur3Ye?ThHiE5Kjy{s^2$u|Kp*QCLN)%OaFkJ9wnCmwl`X=Gfo~t-9|4G9sqc* z8)}=HXNiR6r^{HWpP{Unyz(ZwmNMf+y^aoql?PLNjLv(FffSjG;IB&bcY>nQ3ZDk% z(AydVwEn{(HXgyY?l2e>2C`pXqMwNG_8Toxj){hM#$|W^6v@sHoa!emL29%mYb;(A z(oOmM0A$!dxdGlD6MG*qgi35)tTDZh^goddXleXSM<Ak@gh-nT(97YxHcvjEy}4nc zu?SQ;ArdoX^>enDjux3neBe4sg6JIFG#bAx`g{?z;BBd#%QJJ&@DEF2B4^3Z)fnyy zekLNKp|Qb4tcRM1irgXFg$bFWuH>!u@9|xn<oPAMcg19hx-J}h`WXQplXeaYOsEHR z9@Z@JCbnovfq!2yk?mI7_Vx;(V#@L8krf6$d=|w(_Vjg+PAkTyrDao%q(d9f1tsLy z(=_Rb_Z8C#0nf4~k6+i@X3g*K_GvEW7ab~A>sR;=OxN>~EWxD_tI|fEDrWl^749dJ z!C|J=<O;z1u*{~w=T8{0PZ0FfdTuO6y={HWSulln?B*-t;KG%?EUnhWYVxu`U(~;@ zlD3wUdjWbJx!rG|@?c;!ukFyvacwc4dOn)1KWkHaDSlDAA8R_H2&$#UwlqKW<liJj z-zAvCbje!3A6~e_0k}2EXaJu~NNRKjJc#rs0AP1TM4dhLP)P~5CJra74*lTIhETb> zqS;+4=|zD(Y`SBIGwF5X-}4~*-i9k&8b+61j1xu|(jeW%E2=`%7*_(zI`bBKBh)!1 zYcr!dj@GLo&ouE8{B^s579t7&^lJ7o5~^gI4Ap~Q>Kd_dk6L?h@e+xdQw&_928->h z$^iMvOGeIkl7gk+LYia7+&K_9&Hx&YCv6F~9_cd_!$CxMP1(I7%RA1CcbcgfT^8<% zjM;URyXFGiaB+GOO;BW=n5ugnySxhwjm&^okEZvoA9-hQCJ%hRW#u09-P8PTP$`lm z6FFnJw&-|W;h}O3;?Yl3+D7YZpmYUBt2&YzexcaX6nq>BonrEjD|%7Oe@ZE;5>kAG zw*B+En#@RL7;AcLMz&V^NacD?2dqu#MwDwXkN?oLOJNt+JXj;(f6lxZ#MEqArvtoI zHf$_RM>rv+zqKC+&?xg3C55NbEdeDHrOF-;V2U47gyKpi><8k}@a0jl1P)?I+c%JF zI6ntPLoW$$&2~G=qG><Nd`s&jp`23Ml=O!iFrD~Iw_k><Y`;iRkPtPcm@BHOw%8ZO zM9`{6Y#PWXk$6e#$wDIIPTJ)m08hoz=Wp&ZGq;Xnk9RcVkyM^nY&iLkL^ym6ZxS9R ziBCrcOvmLbTF%>ZB)sb@k1vh^W9q}{P>(b>PSF#(cr}WPku1tjQe;y|%Fl2kBvX5Q z%#Cb}7$lSOmw;FEHoeP14i>*feqkLrDgF2aB{-Sw`yv=nrv%Kfc9)#6SLh{iBXN$& zwYTuEtv@k;s7Vg8$i#?;F&H3G@<f+@iswUMoj(m6>zEAg8&jHhb$?@mSd|LsqOIr@ zu~6aq{(AtPc$-sV`m-3KF&7+4+>dIHwSpe9Vh$ChlWtj7cNo&0x6KvV5X>K@AEnv| zH5Kp1k+43e;Yi6-3eSx_11I}gw~V&`nytaeW_V-r)8CWQU+Qtbt8%u9%v8k&#^>|i zGD6D~W@*BF2`$6)yCz-=PJ-OW!4+M?U2+5$JL21j$_V*vBlLI9twu#CKZ|bP<k9Vg zg|GN2ReE}o42#~IBJ~YlTB^7G0;CYp;_4h%1`D+GbJg9?PUr2N9asWo!^>vut#{Db zX{<Wd&%f5K-<eI{8kfDCnmUl=U5>Dr4&5WNqx9SxbEu?fSnY0EC4p`w>-R-UcyTOC znjT{N8<uor%Q;FMqs$mQlsopGc4|yT?iM?PWOM6dCw_-6N-JTPo^83BL=Y%V)K!-Z zB!=Qob%C*#2j3!VhYaGR0ypwGM|m`h9_D;_6}MT@T}1t56%KdZ&wjih*}<l%pZCU7 zCk3-}pPm0q<sP`b>`}bp{T%ej0T~MhOGdVn^2gWFpX~|_iQqS+g1J!7!pBObOfCf- zKPjGGqxnYv;2bzAGL4wZO6)cBr<8ska_~0u{b{~Ex5<tCwcFoJ+t~wj1fGnawv4Xh z_`uc->IDt0vfEeC3+OfO*6*Tt1_3ai&Ovmzp1!$qQ{Sh8+csTltkV;Gp&2*GlToWJ z{&Xo6vN&rN)xpy7v83OReB&kwMNn{!R6H+KZRsGha_#WWzWWp{h;z22@wQmVs<`%W z->EQr&6VIKd{%CVo1VhL_F#80ukw6Wpn*h?LYn?tnoIZ2OZyyCeNCIb{+(@#g}0Ms zEbFW^<9E;wKLM3K?#eGJ`+(7a{vqc6A!NFYGLd20V1arl8pm9<=Vb|7XXDeNXJP%+ z#PtJZYsUgi#bZsg8*~-XAnhBRo7t9~i0wJV`&&s$b@!P|Q)_J54&6Dr5{F&~@rsyH z`8c_{Y#6z(g;~WKtABXE2DxxlTz>MB#!TW}N=WD{Ytz*z{-W*1ZxElO9w)8TQql`` zU5g;XqQm$=1tLGm;FyHzXEw_O{Sa(oacf~Q^cl+J0Y=~|srR#ubNu`%7XaoN>HKS? z*KhO|jZ<+iwWc~B^ds*g9Q}2YP!+%MFTYT?s_!Pd+voqCsUDNIhF0yB_RshQlxcPQ z`+uIEAVO6ajT)j@6Nk;O?0+a(G!R^08AEb0R2b1L5c)4E#LJA*-n#vhhU<AYkdp=Q zyY7p`&?2uQ0tPy7FFsXI%gd)Rf;nG){t+bz{q9GxVqj&3NSLcg-G!m@e+JHbWGISC z2%*YAMasW1eNm{#Trj4e&Jkt_x!voXcve^~=+*DWpEf`7Xi+gp{!qL?Yn`_q(sc-x z$B4c#%wC+Hlp1i#=qkjxhLtWAyO6uJuC9@huGR24Et(zYGs$^uEw7m$GeO61cIMwg z1PbFj>eRIH)CEApGJsiv6x*Xbl+C3Le+%^-+_|Dzfdsg6k}82s0;e<Y&G+jkLAyRZ z3ilh`tdoSfDLi6cRaM+55u=carU}+dilbn3R-P#Y5s@Zf-5+E?oz(bBNLm$}w&ge) zUr0`!5&|?jCmagP!GejZZjkFdr5qdmREf;P8I(;?r@%*l=foysiFJX~%Pq-S2PTME z>KdAcI<wY9rvX!kY3U4<seiBzOPcyF8|i&T9$UiZ63?o6N;c$u!MEDjxg3?8HQzeh z%w8yK!8LDx_F91+3Y6sq+aEfnDBDBPd8r=THlIM3JQEhEF8VT&k+{1M{BlS=UeBeD z0*xshV?An|pm3dj7veO`lJ`Z5KhT$Gw`@pj;K9{+-tL}`I+x0+&P-cdE~A__x*MZF ztMS1`Q=3{lke;NkE@@UXt1a&)qrUdV-KLtrEO})aqSEtj^GYId2BfXbK62e@T~<q8 ztl_Y=S}L2n<>`T)=yJxmi^W?Gt>`A|4{fV2>f)Ox_?11=rk}o|gZbS@l;L>A;3|}k zGf!4FWT+B7w4a;%NiBntgSR{X(Ty3=ll<#~<O?$Rqo8yJ9+_%u4!Lr5(u!{$%W#Qg z8_1vFe=9Sz5LuEvy3;B`Y!?OVA1(r#c{4<IwP$``q!+0B=m5a&64thKoR=nMno&Ni zo)Z(;UWOKzOPz5QtycX?jal-ykO>|#37LSUu&kR={zLa$%bM(8hHrc8#-LG}61!mX zQ*!nR5`=R=Lk&y8{+@8AGZcXls!gOq1$&dEOjhwdFBfN^N5;bFvIO8|ukWIen<uQn z^JV^M>6_`J&vX=`>Ba=JbVzNs9CJ`Wzc>r9RETLz$Npc6m`N*a!~sqDFSgHUVf*S+ z%~atmEToo2gDGo`S=HE|hzlifQ{K3OUF*BWF!wRO!z_5F3Y{4QEZFJk_oR`xej8M) z%6Pp{yr^p0yL^i67OtL5Nu#1O#AZ&Jo`nZmn^CdXF|qC_O%4MJnb?)SRE%UdOrkcC zZEuE<v7{YkFR!iU^6&%BYP0yc!<BW*mDM2d_oCBCUj3{Eq}!3}!K>XsQ;<>$Xci-p znzi}o=caokhs1!||C}a!!~?E{@@3J7wU!a`5L%!wJ7m(05^we^lK=|FAn&0q?9C59 z=!VhM4?o_|Z0yge?N^M?UR^u`3#$On{xX;+DnS%|H7qK3C#~qKU?0UL6X$SH=XVPt zco(BQyuT%-DqWm7XG}CRwDD(dWU&G$BwHA(@Jj|nP*K$pJ918sS6?=6-P(|k{WhPd zP`(irKR^`weeXnj&mzl57vl3{<_>wI7<%L?hKr_N*^5iK<a$*4Zl5_M8(pPHgbwpw zYIsNUom_{^4!L)tdKXo89>~jW<WHAjBpGLEab|g24wTlC3|q@VCX*VoH&bHcs>35D z3a!hCh$tf!Wlus+%%SLm5yajzAd&Ls#E;<SlwzzLe~%V$Q0n?)WY#|dr-@)*32E;o zRocHUV_l@Y4=A}wNx4Y=b*^iAoUOdPObnr}K9;c#G!AB}p97_{gnCFw6Df>j=*E1p z-y99<b*URB7E~q>6B|j7mgYh3(I@vY@o<6v%#Gn%ILOok-POyqD&{IfU>!Qk%FyfY zmDya;hOa$Et-y2MqBVO+KQ7voE#Jm6%VfrHLkOG`Lo-}Xoen%>YOK?_#?I?se*+J% zk(QRwLYYvP57L-)Cy%Bj$M-gD3iM~^u1KuV8zPIfopx4v(S8cG2ZJ`m&Ac*N>8Cpf zq1#R_eiXY^tB)mbK^Gsjg;P&}KE<;gX<RS3)?RTL7=UZKId=iT+1`E`8=HsJ-Fe}% zv+A<ZV8MQy_4uk-Pf`EeFDH{j@#|(8%S<vSmsDEUu?vTIAYXR<gh}To?`ti8fj@)2 zfW>$+JG1Am{j?XA9IwCcQ=JyZzO?#?f&P>jA6K4QR2mKFS%Sdpk(ucf*&;VZT}o-8 zHAs)&GS6gFyYh16bz?gJCa&oR>>#SZM04bGTt>h45^>xCnK7|?3dtK6JB1`z6H^Y` zN@uOwBb65xv@jd><<tI?(Q4u~JfX&(rF1*;X<$t!S2Aa;a#=azJSi*ZJj7qEyqh&Q z?!T125J6b`ZFiYi`Az)WxUoZf%;KHdcJj_{OBPz06RoPG`AA3dr-Xh$U2&TV9ieIF z<=38<B*OWO;zU@3&|>{2Sys%ft!W0T;wzNvs#tu`_^{)4>!&J5Z5kpj-UbVY_nI|F zfX^1g<g;(tlJV(Z%rABncN=D%@6iF~+40CaFSbq@U{U+pti|lp)WH<RQ-{`@xq%rz zKvprc)_T!`bPgM&Y#_X(qjkI4WVcI)7D3O+TFR7x^>0vYm=a$`9Z7}0lUqg^KK39> zEJ0zvG;K+GzjDqL`0}r@ew10oylR@Ns+b(1c;Sv@$prLM)(uhsbOx4k*waJNWF0df zpCQ?i0O3oiuj!YHJ94HbY#mAtcpaFbvN|)Ih-ppGA_0mTFm_M4a2`8jJ!ni)UERJ; zA9bc%?;ptC1VRC-Ojj`ocBp0FWYnuK6niGO4_W!PVbc2dDPe7%iC&jnE%tUQ@24^| zP3OmzPFZr-Fa{A3&@-Ojnx%RMF;sEWM;p~=e<AD#?&S|Z_50mFTfa^c8Uq!f=J|y_ zJdiJuJ2stfB`;w}u~k~jDF1eSei(>ja7+IS&i7+}H5s8snb<87Cw&zLeR`1cQPRB= zds|?(AzxP#fB)gh5%jC|7-Krc{b+|zkpCJNK3<Hl!XQ%tFg-1uD^EP_No0ym&rmC@ z{|mdaysU11YnBjsN6X2BLLUbYMs57M|8;x)rvV&=)P2sRP98G!&n<?sDv^F{9O$}? z4CM+X^HZfz;>1MmT;gkBGKX5~BJ<7&DYPFm{d3UkJeLw;f)a8Ht{6Q-!(EExE|Vc6 zO42Tat?GBDF}NtgoXg4^b4v#wQIn)i3rk$W*a(?|Ign0GnT37w$&IRNQYpYob%}{@ zr*Qp*=|Zax!I`VnjWc%&#2i+9(X28j%RAwCZaPFVQ4+qy>9(|@H6U)rBU!@Qra9>U z>{=B5%ZX{B@TOdS{A4XSUL_)f?^vm>ISmh3Zi8PrR`v2}5x)aWE^p(EJEyzrHEwME z^Tk}SD!OOy!1(u(E&e3ONMGLH8*x`?O@sY0p3X;kWWO~r<UgTsvorx`!L#x-egGtK zu0KTPwd9^7aG_U;Na+$?vWnj0moMM7?u%X0JL75qgn5%i?Z$^@#k#M)RJwlj&^toS zn@l?QmBwvBb{92I5Xjk_<<iY=vh7KFfyI~UBr~lfbWxrvw@`cj;KJjJAIW>P-K&Q5 zt9xY};<w}-6fLfUE2P>5&UT8g2EzZyn#|&1zeaQMl1)4uMQAHjjIikR58V7Pb$H)P zGMbrktksi!4*xc!px>^1)Z+ByYBz*4r`S*&cy`LFjzV!3;%r@Mx2tDoSvk_a4mD6{ zzI@Ng12Vjoy6`{qLqtoi9W(7$ZcuBH3=n0%Z>x5|dvftw1RhE{w|v8!kblCQy@A+E zvnhH;J$A_yVdrtwfvPIls3^XYj$JN`<0=C=24UkD0iZV)wfN~fYDhN*`kJ()2T{3u zj(Xs4@~Hr3-*G5VFDZAdS9FZ%#Za>9uh3Vq-b<`eS2Gzb9F7LN6=sPKji&Od3S`<A zU6T60Yn8HZ_U`V@wp}+x*2y{np9_0(8zMsSvlQ<3Qtg6|#p<q;F?0x21&LTK$Z*lR zDk&q8sd>+p%-Ya#{ZA*=GU#Z(sWbMTFx$v_iE|xYxc4tK5UPBYf66h3XM_Cy1^@FM ztD6qI@;Cu*WSwPXEM=4}udB9G0-{wiZJ=^i6|XV{PooS5JJx+xNR!q9sYU}+36uwG zCxAWtZeI+Z@yW8~4OVL;MQGrV8m~|u5#r}KK8Qp5(RqYlBEX+}i4c?#HhiX77Y2D{ zKV!CluS5whRE)^!f0k%!OBoCe=y~{M`WJq?d0k<$kO#X!z<7yve2<Ej3&-D5lIQ<x zYUKar+aJBZe}8fqt5Zj#YxjS56>t%c8HrMu55VZCzt?DmDg9P{_~1jq5vJi4`d3h1 zt{5vC4*vf}9?}gmw2o{-RnB?j*&|D=?_aj%OiL45iI0^S1HOpQn>j~NlT(()8XT8I zuN?O&X7qQ_2ahkylx{*fe<6;6zV;jNVa_IE`gXb*W3y)y@Zg{uqYv>-H-3pk0hPuf zU<$)z3fZuTbP<euT8iiM*X~g9aJl-1i4~5!4k9YMb(CY}SEAz10xF)`{qK$t9xh4_ z=na&RJ(7b-QCjWi7E~}L{ENj+Ul9z3p8bH;A8K?QUcJ?&2Uj<Tin2PmwlawV1?n?g zp9q6y6d|E{3y$=~yp^D^8-)s~qQJZjL~|SB*5RSGoS~g0{-fpxFYw_&n{(^+ag)CC z;0+HxGkSrMcpXK2s>@XFZN9uHXc33{X<vQwDqcQ@-A&q6)p*Dsn?d2GBa8;+qvY^F zw25E4im$okI23ZNu*_`QOQH&20o=z|RlqILEWdj)hZ07Psm91@z3ph<T$Z;IdBiT^ z<)zAdp0neN07!dAK*CK}hF4<!f#sQ)y78*KLzf_yzq&z*DSzY=%O!Q<Lf+PmX(uZ= zlohMRMpSl`7Vy=1W1QnI+b&LiW}m;>9!EWAtFX9@WuMFO9nJW~if_e*3xV*<cq1jZ z4+&Ifpe-)`)A3HxLMuMW+##^u?eW>4<&~b*TL@u?8Q3=T%RLx^A@)N0*qws+A=5q3 znHSrg$#n;otJ?P&o_BJGPsu9-cp@!QqoQ~-xpGN@HhXBG|1$V5kAR!^QT0aL?dWq2 z0Lkk0mn3pJ)R1M`Yk{!=Z`})%TU(MAJq@_^I|1LmP$3wH<d`o@i^x`;=orMqX-ZJn zm;x7|xc7T6vK7P4C-sg`t7GClC%Aadks4jHPdj?nscqJvXu%0>u!K0+O1agBcq9MH zAJG!ug|_*qV9m*zU2G`K=i}F}VI6f|!}FW(iY%F9r3EkIrd}zRl%2G^e^YRCWHVD= z_O6Yb3D7jWN~S>#XKWpw?mqo2{EN?%4dg|D1KP1)?AJ0i39>k4?%Ku2nbG$ZiOSsP zRIH;k3?>of!K`5YdA37OO4q*ms<z)2ivm<Q;(~z<^328gN@35|^!j4o=aj}en0faI zY=}5Mt)>df4NFevKGH?sJSD}ayKKHj!AoNTw%E8hhzV|zxj=P&V|&~}5Z5UwEz}A1 zW<PGfH+qF!krd{5d>I<=UmpLHX9#{y9%2b+_tC-CsrX4M)jYU204p9X=kgauEO~E3 zP_1A%$VCK#U<!yc=6)Z5W(X-RkUPX^5UuH_82wi)0U_ou@aN+%4x^;rmVe-AiPlru zn4eG=e)MgW#v~J`F~ypGooc(W37<w{bcmnGg8tt{TkE&pgT-gdv<Y}2LNM97Nf?7g zcdr!!YPX?(0t_$MAL$cphbN*3kWc|zp#hYXkG}R}V`^bpyi5{gJZj#5eufix{rv6L zdmm-gpA<29XmRSRI?IObK&<a4NG%SqsuL`$uB|b=nqyq!a%Xevb^YPei#y@BV*XV+ zng0imp6XxnxE{)H_;`q00||s0<Z6^l(5x<oED(&(ZUt>^!{b^74l1b^A#ilWpSTVg z^Q=V&u|r;p{yo<W($-pO{7bjs$gq^fSJ&u_$IF2)J^?l<ks+j;$P+IFmoQPuhvcyZ z%YtRBF#Q8yMT<Y+c|r3E);inhTS&KXt?7Q_vwSe<ZC{hKa(CrMjit*|Me+RbGIam~ zTEmpUt8{+WKQk_};f8m*__kM>tSAA*SFuoy*@GW9Qr!laA<B&6<Mejld%nwIF>{Du zZMluZTok>qm1-g)6OlCKF0eky?^Qx1P*G~Dsohy}d_xp&;6c?VXc2m@{~C3Bk)+bp zP<!l;UJ_-}-5{a8FdRES9J`?A3Cy5z5{el(3Ej|Cc{^VZDnerS_GmCTwpVf65@SfG zn$Oh2l#PsodSq$8u5=hS4`>0D{%Et$LqhLprLNI4^*@sIlxe-^O(9Oe$8`B;q?MoZ zpw-fmMq~KdBKU>!lj?NV6GkleP#1%<aj(hV@TF-QfwWi_mPDF9tU2<`l54?axuhBk zA5v|}D#VijH{7SbZQ%^hEG&DGX9b(C$V@iYO@O@#8w^U&MKhy7&-TYigmd=>HvXD` zE19wj-ifT}Y-x%YYsG7HaZOB2v&JUftK<?_wt77Grh~m(Vq2^}t?A31S~s$_WT~E7 z<L5&w7F+&y6Ly5wWWbXlFv1;c>jk8pWqzUpXt5fwXVqN3fk5|6IloGbAaczh1zqjm z2ZL_6jGIj*g(BD8q-WVJEOTs8sXZExVx5Mc&ajIfZs<@ClJjL)rGFS^%YFGPkPEMk zmF6#$^0<9RH!V1-;3uWvKf7VX)v*Y;x$EH>i40eLdOxARHg_xDxvC8+iaTc2#A4bF z6^bxj!|Y&KG?4t@TOh{1prM<yXTACI-S~2Fc^X(TeK<GC$B}?QkTX@yNv8~(19>`% z8vt7LDj`431}bV7qv%YAbowNBesN~Q4lo<r7mX)gwZ`3?dY_boigF45dWVbmhjQe6 zQjDDs>&(DPO*s}(IG~vZ9irgK;ujBuDGM$ItbI;hAS0p~0`3c~qWR<e@*-Q0mZveS zcX~BBTD>OY2VH!f<EyZrVyEAxY3(#|SQc@<pc)p35uiQ{@w<5V*zfPCnFJI@yG&{L z|A+=VpE1Q4cR62i|NJ8T4vVxt-g$LEbrJ^CQPpfzumKz86%&4WxZv%-L53cBs^ar6 zrWeQ1-R_KAaO|<~H(hj9^oJ6)t`p?u&(GSdS7;_1B_JNm4-ldFIfg_P>Ay2r1ATDy zd<yVV|DID{=Le!tFI_O62YmmRs9&&z-BR^zsQ(FAXhS6YBPp(fo&xEM9f9h`1%<_+ zrSZ#Xo_!|F2$bt$9T&?>4c{Q&hM&Noa0|;ivj}hkQ%6(ZeQ~khzMVR%(L)TY&99H+ z1MNcaRs0C`KV70|m@Xxcws0NhvcPE((4O)9@zOL+e6WOhncVU*sXOLSxlNMo$jSug z>h^fB-_!z5c@q}L)>W`L%aEnyN(l}1!*c0yO{wE;k*+&PJnP$7m~62YtIq7ngp&4p z@y&5bEfe7ZxNe>xX)ty_rHHojqjHkW$@iuukS%M!%F|)G2wP)W@n#oPpGDE!mX`i7 zMw{epKiVOk#6&K66q7g<!=_Ds+%A<!@xg!E2C1qvvhc{CzU=@(4YRlwv8cIlem?JB zu^>1k<nOb#w&o`mlJRe`m@@RMp8u}y+rlYl`bpaZ4#a!bgXcQI2^QPSX`8Xp*lEZ_ zriRFMQVb7IZh}B8fk`G_?jZb>mzwhZj$PUVxQwqn!Ki%4xPo~^P1J57CS7_zC2hD} zwB}D@6EM0iGOKC?zdSmOh}0>Nk*RSs$Hz!L(NV4CCh7-)c#W{6tl%7^I(3m%p^Je4 zHlri8r}bqn^w$YDS?A^1%#G$_a?kItUOzAfd>_zN@ev}@T#+a*Y#o1$0%K<HJL9T< zH>^N73^Iqm!4SbtdhVbHS2!G}YtznR+1HA~!Mj2*_iMnP;ybzZ%#a;uv$!YerkEBd ziD0&!;z0LYbTT~X?$Sj&!I<r#%<RcqonSIPvOT5;2-EFgus3Q|^ob8_Si6h*50E9} zAknMnyy!O8VGyh5TUcf;+OGz}+D_gOX*z=bz_ECLT|0+JX&!ps_CNl;z*WILXZ3sy z<(VM{me<TGXpj-7$n!oyb62x{h-cg>=5U6@OOo~v=lB=BD@8Qq!_O<`3x-+!`()MX zfu!5sK}u37GTe@VBTKvf`a15&QO!-W%YoYp6Ss`F!gJk~I3>OV#KUJ|Hv2bo)a+<{ z^f!`A38A1n79~cabdHK~Zi@njoFkR2(r(I(F-k|;7oEDHmdZ<5P7q}>C7)%A_(8Eq z{flej9u&TKBf~c*-r=4a&ITWYc=kS$)as{N4uM>1p+VaYvONx->bQUEC^gJ(NZeKw zy&Z{A8$al<8j+}#O<t)Ahwl#jVC-9W{eTIr<+^&)aI&gzV_q0aUdkF(HduIcRoTk? zG`Vt<ta&YDaj~0I{CnDFN}-}3;_q2~c^`!JOlplq&=?iyeG)W*^MYgzlb~L^lwpAA z)xT~8vK;Si<ac9>0E$%v{58P{dSU@lo>^kjZvXPp5i9*#5<64JL_1O<I=o?Hnwa{1 z*j%2wdnS-bQ6hC!b7zzZ=UcI`h&&bL`wVq=ZmER2CL!NBrkoOKHhAmG^Z@&S;n>Ge zmMHTrnXwMkZS=P|evlRJ7Hvta2#^~L7bumdl)S^P{Y3pOLxs#MD5%Cskr&mP;3j(} zGrx?Y3*0v(3KsC*J!8N`QSYP30afqk8zkG$Wp=!|?OV+4_DolBTPidpc{j+!pN-V@ z+Ke3Ul4!YXhhVJ<tS_SU-0f6ubvi72Y)RQIH|h6}Wl;y9@HE@LxKC32&<*5c7<_oN zdT+XF2F3lmkDTIT@~{ZuFfQ93!I&#5yN*huX<wP&>PlQ^zrSsF^>x5!I+(_+a~Au= zu_w!awvFVtm!o4l#9=we$=a=9^KHyzk6d5x`5*8GXZ}C3zA-qnu-SHE+qP}nwr$&< z*yhAGCwybuwmGq#+<fQWbE{6BpSx=R*tP5Fr`KBDy;|XJc+jF_2>a<WSY~7Ii9TW# zBF7)*x_hs$aD?$2>?0SLKHhMJE#vS0Rg(`R4L<jiKnoH0dQVuKgV80HBZ1>_?RT<2 z9y)?&w$?Y_#~tSA;iKtvdsu~GBG?lDKsk=0jgV-Miou9M@LGEQQ-%tNw>a(H7vnAY zXwXbz_XPS+6`^^u2bji$&>co}#nY+ut?De;UX{Q{lF>JHYuaYMjkJ-6fwrz#o$tB( zqOar8WB3^cz-;ju4B){(V>nKLmshC`{(F)n6pp_!yhEnYk9zi=vXhX&Sc!oQa;b2L zBSA7ZdV-bx`f6)|#z&w#(TVU634@>V@Nmio5d&y|T-S2zb97do0^Zxy4m)eJr$0>V zfc{D#m&10SIkCM|)u>E4wTR^JSw0WcmRVX0z2^9lbaU9%n8JqS67wHf;rGTA*Dae# zNMC*%-omUvR-(h8MwnbjttjjU!H7KKhFty^uV5`q7nIBC;p|a5<lnZggBt`+&^3ly zx>7_Zh~wdO%i6F;DL0LkzT`vX@d4xCM!d$xu1$kKVYIL0RE!$$FZva~r^He_TTQ4& zm^~|wiiej(^|N*~LP9l$@gZFtQ~o9e3!DbExSnzMHX+IyIcTTCvmd{=&ZzyXMY>4v z<L|s7o}v(WtgBlQPW+E|$q!X3PqHz6K^2csrqZA)v79yb0#yD{bRXX;i&9nAuPW7f zaS^FnBmZ7RRf492GF47h?>qjdS*eEZYD59Urfwi=GdIDq%iXIR{{nv?@6MaOYB#eW z;!}{f)dJXx_rU3D5!rOhT7=YFx6fkWnJBZXc(E3_)WD(X(W84sr)33|V)jGh0y6iy z@)a%grT9VR9QTEY!P$LNI48%Ua}`Fed_>-fdMCqgm`soX^I)FPm@*Ci^yW9&`ly(? zt9QJixFUIby2s=t-(#|n7P+Jn43p0oM{m(CAf{N|>;}M>0%5Cun~G1D;_n<CH3GIj zA|Hk8GZTkWAjL+*&LO#4>2GJudCjAT8q=W0cM{AOAns$~^g70SFx<$n<Ei*ZEsvhh zmI-_dmexGr^gfO*?x7BMz@sfj=Nfp&2pJuYx1Vf0No@FKo-4*b|DdouBWvE6Ke$~r zm-1zA{P!~!aK50XgU5;Kr{&gF4q$h{?b0ft&#rv8(4W&6Ti`_<d6&$)qGdT!HF<{` z^5N}uH?Mjm^g;_Kvp00ET?qJdv$?JIylc!mS1(XIn{mOdSqiXw;d(@K>5_|ZOJCu5 zehXEs0?ZD3GS6xR!vr7PmMakV+A=y%FfjZeUGcns+x#V7UecDfXj&NLe`MIX7YGJp zM-p(4@zU2T-nRuk#a;Tr2sX}SV2XQRg=h~Ukh+`?M{wbFgB^dQaXB7-qw_MWEPlE5 zkB0l*#-5cPu8K)^n|aA9nkx15)T$ehL1}Rq`}IWg0(Gh*=$w`qX*;66Ymgjui$Kl6 zX6g!7bVxaBw)prG%0hU(!i(F@(8&92MDMn1;LHf79ivp_y;=$O_Os)l9a7zMq#u9I zR4A^?vv>r_Hi`)-um}l@&W94u2ZNHI)35t~6NWM`b!p1}TtKSvK_Z@>TRO(oKYN-) zBPu};7qy8L>(t@-s3ElW3AEvu#4q~It?Sze{S=o8UU6_oF&2&_ZR)gHt08D^XjG_4 zZE+4M$oo56Qq=TRD?r7gCU8NI>oKOkVUcmUlvXov^qn;C9#tOMBdD>?N4>hF*na<~ z6lV_=DVmC>bA>d;iWVg;t8{fCtr>Req%etMrR0$G$S-aOn4Fde{e#F3JcVq603Ne@ zDa-A}nM=WsUYWTTs}ad*aUuU-0z0YU;G1Vjk*+cf3Q4W2xV(~2#Q3OJCuWX&*6QH6 z;_HSo&}dhd!x7<eVf5JoVg%?|*`i^gx;7}m6y{qI5-}m1u*~f-2&nr=K}h<vgGIm^ zE;mE~7^%R<1nX1TaGV1caF6OofH@sOQux<feo}-`A#Zz$O@V=}oFsfatbKbO4XsJb z^OWZ`WL>6+ciCpAQ(bTM(4Di$a~hx5_LuBrlum*tiZijHT-i$kyc5pG7MJd~y=o0l zD;~0lb;zXv<g|v-p&#Ze;<0{+NcdixiE6vd@u(MuSMaixkL~LLuB#7x?2d5N$}BsS zH-Df3gHY>nLvqcGZic;PBj?g>??Ss3SgJtafD57C6D_|?I)CLCZYB|3^NNP+4~~K; z)wazwY#=tK@f0`Z>6~2hpP<SzvHXVo$0oqi=KByfhLyvU%}n6ec8%ny2mW-V?uz9v zyf)C|qG^3_$}vT(JlclEmWxZ9*P@=&t^21@IpbP}^32;rcW&++TqDLbsVAY^b^W@f zZEeEtp!DM3s^L~s72^Z?r0#Rgcbx~gy?oB@y;1ht{xrJ6zr<m6W~iWUWgDsmtuZ!q z)_{uC2#HY%>_eB->G65&37}Br!lgMeGR0GATxvEU-hFX`HN?B8XRx{egWnXaM=&uv zG@~MWxw&$Xfa6ZcTghOKGe}GCoQ*!l-iJtKA^PZ>CtG9l&3|Q>{ggnDv_nM%DS0>= z;u12n<x4YBlqpGr@lvy)|9$$=R7f#E;<XWx4~|T#6w6s(Zlx)vcilchokHWBPX|7k zh+o4UXB>ALJ@aYgv-YAHBu0(8An?^T5tTlq)hlifR-t9G{u(=x;9obzd#FXW#mJVb z7~AD5QJQMg5hLXQ5hc4UY_k4iMs{LJq}<$Stpp5e(>JP)R$Hd$Wt=M?{J1JOi=km7 z(yQ_kr^+ONR{&eX0Mx5ytw__jjrE>b4>h26^qwY>WS)=g;s~l<oy)euA0Kla95S1V zt|r{rtz=5PWRR#pU-1ilxpg%pIXJ`?^KsN~5@legfgMj;g37uWo9HOM-^nr(c{Kyz zf^oo^s&l~M^o@q$gdl8;<K$1dR@4V)M@*p!O7*NBmJP1aGl8o|6PHe<1+p=8yX0}o z%jw!76}O28$t$VF$ViFS{|>pnL^pzCDCNe}o75bw)a=*U*eW9=FddBMukrut2@KTT zT7H!?o;eH0-}#*};&{h~D<25q<XCwXJm}2u<8AF%e-Rssjv$fh!&ELT{f#}=v)JKd z!6nM!{pLjf!OmT4{meJfPsE6go(nc(x$27O&C1DGG#u&0KH}~nkENjQL)9uV`HhVX zom@Mxd(QYw+f?P1Z!;83B#|FA0mAGbFjL0(0sf-*yFQq)Z5+Dwsv%23u<?YD9aR!K zf50SS6;^(~2noa`j3XMK0NhkO<1!y+dm`T<+(ggX-dfGcVySWiG_Fc&rne!HVeF90 z?kcD1?q5DB38YDUG*%2KH!4(7Vz(LSzOV0G?RuTiBf;f$!d<?y^;^Ct<khWh&jCz8 zD}#hWU+-TGi;eJQGPldAP_t9^07$`%y)$Sg*NZyk!p2_jKzRt2d8<$A561khacpk; z^`N*_b!VG+C3s<K=})`ub1j$g1<@F)3~YRZa>B!yIt3Hq+KvuFgg@jWyA;xVAEHjT z>MoIZv9SQi+X#9ptsnd^C#$^&_54@*_H;*DYJY_ERG11MP37mYM_THpJoV2_Q%6}2 z^n^u)G@Z(53A%QUxLFJht!Bl-%d^7`Wat3N6YOW?GHpF7`C&#K0gjY4J*rVnzG@}i zQ4}__SV&nn646oWCbbB3YA9F@8DsifH#nSxl50ZCF#2sot<8xQL#kurRReKi7L*vT z3)N%f-dvB;nE=!R%B>_(q051)Yf!UrQEEksuMJ&AwUvu=$;-NS)#B`1yga)vKq2+a zVlW+eU7b{Tk&%`#EcD|;Y#*3Ii2uu#B5a7bn)zNYBCv&Wwy!gSR<rDwL?>evY!1{Y zl&&_|jqdqgVZa}I4N|UvE=t|<rO7H>|MiNgs4x0EDqHr%o0JrvI+(3JaJqLN5-J{d zSZV4^--HxmAmSf@`5GF}f<E8g^;sQSbB*5jMtG%(Al=>5wR9kMlzZ%bqSPVPe@p*h zC=xtcJx4n9*Jv)nH6P)DBQ@`R@Tv9fnaX{-dUUojzrE|x;T&2XLe*27PHffNHi0`& zu`K!d8~ZBj{z~-Ir+XFnMGD-yX6??gJ;;pg74rEeDR;hpwZWwe$=EzVJqu!^u43J| zQSJM)xS>p}WT<GA06#OofNj|w-@|?v&CwV7GTF$|_n7hdUgEhoFm<+irNOARU>Ili zP<W&)pTPBCp22}4g{$c${yCXAe+3QG8T|qxRKg(?iXDes3-6y{hr?Z1wm*-6+(uHx z86Ya=#@gpIYHLCyYLbrB<d0S#Gd+1C?XB2C3x~@MDzW#m=Zz89*fv>kxZeRwe6z1p zo%CB;s8%q!J^{~-{dE}5llNtf75!fns0*~e($ZpH4PIb?NqzEW4ati`W1b4ofV6aJ zJ2h&WicRSPQO0>{GusO!gdPq?K<3<aZ1K)XclNbuC{)H(l%*|yf41Yg&Q1t@xg5_* z8(_}WfpF6G<vu%|!9Q;oj6Xhw1w-7^hlB3tT1QM)*9EBlhwuJxKvSc-9Rk_U+f_3} zOq)pON?nX7V}A;Q=QD_uIA;YPSnik}vvNjY2KO;@ay*|;4oUZNm6#y^{-VBn69G@A zY&lWc^rU=G?Td`PYoJ2elpup7ed=ikz$F2iAcUzQ+qwc_o25q6Os70#+RoL?*GL#w zVvv!MiItZ*#VPi&kbc?hR<#A5L5Rk}Gne0JyOAX?^Bj!j``b%04Bn8KP+BZ?=R7f~ z7UUqK_J`*1k1Hw?7~Ua%{!cB8)5e0RjRb$rAH7y57QT<2wiwSEl?w59f&gXQO<%IS z-*}dS&qy0Qv%M(-e^_rIXFql<WrSnIffA&`aK{U8C_XgJq#5@*wi38e#G3I%KiAdZ zW|`^z*8QU6rFbaHVi(}NI@3V*4g)%&%2^i-><YLu<64-2g&o7m{bv}DsO{zs{r)}y zY!1&tzdQW+oVjYo=FlLRluPD?tFN+-=Dc%F`+UfI!sE+5FP&Xdo8{7fvUDKwUi|vO z0C(NWa`rE2#y2cFKgcsFq(ATmy|7Ca99|00NNX8<ZmY>29_ANtdr$b&b^Zwr<_oYm zKTvv>qagyTGB_xp_!1^`7xSj)mwVU8TdP6+RPA@Dw#kZzV-~B`#*3$AE@+LuDT3_e zUAHX7g4dv6^jiA*BfJM62-}X}$RY4^qQx^pm(H5e!SzYO#Pr~{Mi0Am2!Hy$1~)}^ zCiYI%8*>@kHJ*HrHD(UKFNCHCFQ<=+`PR@LUTw*$KpUBlOYZX}<xG9hdGrIbh{*Gk z2h)VxF*ki;aC&04-6z4O!1~kNlD0!yTfn~yzlPT!KD^S`)KndU$9sh5XTHlb^jeR| z#SU>V&p}Ub4vN9RgtX1M#DuVrMRZ7-C^IvwMkI4c+MQHl{3$t0S}4HLzaaI~Q{wg- zI=wl3m4@sDmTmkOG^d53X83RkVA<VGZ%HNmD@n;FzDSwtqvB(wZGSqb9r?GD@dhzu zaj0@lD*Vs<kIgn_Zf#?s8h>@s0!OGv3d#Sz?4ziXqAOFIb@lToc+U<r#ORw-q+F%3 z@E-CNiSV&3YSH#b@~)A-v($MDvxROW^w^P5xBF+79TEK4Y6a8BP_0wNu>KULaeZgx zb%#k>+R!%?m&B#DP*<FNy;|2u(~npSg?onNo0BA~Aw~B4cAZCqvLi=|m#F7kHVI?x zqhHq3=%!RC_7I>{E4Rs6obmGh*~~@{psoq+7p_%9(c!9?vB|;JylT`>xRee*Ql1rx zainP48wrN!CMD<-Rv5`SoW_{7lJm@I9--Y=M;b&aCN72$MXU`4rwX|;2&_H`2@yJ1 zwQt9Qz`Y>Gr~2g-D-vM<8~^2-OG3m7>w&1NEBdNyg3u+&73SXS<T<!zoa0nlu;yvT zM8L*G2t`+Fed3i7h=BJR5<jOy|KY14Pry-IC8+>AtxJ<W#<(-rb^{w7()0-{1f43H zo&!}v*@bm3IO$T><?My;I-sFRIj*C6Yhrjm$Tnb)i;dytIi8x_RZH*%mZUu}0e@4O zMP#>0LAaIu0-tMQ9{S|KbH2hgu?}%fkdm}UIiU!2x}S!2U*HYz>h(*`C#Tw|%UFC= zLTm+&e{UBHNdANc9=F49uzN_XYB;w!EG$>@{h(0j?*pwC8aFEu4e4+_G4QZK_?bq5 z-V9^7K1JA0*e%DM-?1*-%cpqb(ybmrUpWsKTl{8uQuf@_&(^LTnsW>TK1YyI!<n$T z+s7IHD_=sDS*zB8`bL=LL-t&cBAH2!^D+jhb*?)*7Ai>gU_|4aqrfVyFJSH!h8Z-I z--kXZ19#J{1MF@9>@7~RUbZcxC#7%zPNbS0Oo<yBixEj;Jrfb#WCTh49b%>=!w#fE zon@CsOqoTKKEYmvz|pymh^f9%B_)H>>KLlKGM2vy;cb2c(P3v6%|5)`r{=-m?BSYB zzu^Tm0U~?Ojzx3NK|1L86%*b^w%D14k;~#FMvrTA(Fg<4;YkD0AC<?Y>ccpBMBqQX zR#CAk4^4^kG;?k%N$P(Dff`n5XXfZfeyajpq!-v9)Bs|9E35S6b<Xj!o67=>VU>?( ziz?&+lB<}Gi2magBLMDMtpyHt1Q~OQx{5rNgQa+XCvRnj%s3S*q!HwgQHW=Bt$?Z2 z$<xH`f>sSZMKU{Tl>F<P26Cp(gc&+D*7ja*Q}OKZ<Bm~^6P?5moge6+E`6zt$voI# zQ*mcDE7?@u+q$VYNdO_VqI7;jAUM#^0Qc?~1c5y*i!(AX%0A?lMew<V2%#XmGuk{v z0_F{n{k#g0UHzVCC{9uAVTcFJ>2Fea+M8My^@dRnU{QK*^+@=yk{Y?}i6#V^ndBBU zCH>n&Z2xi?;9wkMXuPka4#>c;mghsjY@TI<qm=~9TXGy>si}BYvu;RzM);}7*;Mr5 z9FsC^<qMeYEQf?7syCx<=<IN_Rl(jgKoK+R?`krpBWwi5UnFMS^Y??dmsvK~1-Y~% zi(9f$em||FMYGiTwAA-{*+hVBN|$a*!{+fo_nz0;;j<W>{f;FrE_3bBY^a<>>p9!n zHdp=SNnL7w@3x{M2SH{hV@wC^)<*8x5^MiG@XZ@R)$Cp87pSXD2w)}IUE>t9%9?=F zcc8rpOs~wqn)&-UBJ1W|%u;P&=<#_qlH<NZAnexZr^$9M%}?a{A}}<%4(=hgWj&yx zFDpB448UGy&+eJB{Wu-|TDAjk;8AqBv|`c&<S>5ir;uBRabGN^={=BGmJT)$LWICQ z*{(vuA6&dmmKT>;Jw<ARm&Z<GM7nEJ7+AuvxGQy+*3=cy@8kFo$R6K9`@(GY5~?4& zyqbW&e4IKle#;|jPQuZe40UM=tOJ-8r*BA;o|r&;!UbQG`5EpFQ4{+p0{Wux1CjT7 z6McKhcJkmkKXO@~fT<|QC&JL(vZ-Gtq`x+DHz6Pr=XEZ*2~i#7Kr!kTl#g2WVa)Cy znN_!od<fAH)C*kHequ=HdAnAQk`PPHL(`zu{r?0P)phFBe(Xo)jH3FF;xmLgCbl## zT+x&+l^7fM_M*miutC}8C$Q)Wr&1s(I|qSx4C~z|AFB})^yho#g8|X;<fUHm_t6~} z!-2nobH$`Gc>~I=JjClVN@i-hv>SALVvumbtd{nVpx+=(TO@;cR!uveqEbN<F^OXg zxb7*=7OhpKcGC`(mh;(1#fB;1!efj>`-N>knVgRqA_^2IK}!8cx+uj;6*wnpF`>l| z*)(TwXhx_%|8$_}z|m>}5@(c_(KA^#1eO4r8{mmyBY|Nr;qkKq##j*cF274YLK>G* z=_{XcPddxgS&z$BxNMftmT1JWNfg3~Cwdldy-B1Zlw00Hj7~V8$V<Ny*q|6Liqq>9 zczb`8HeRGPTa0);^C%1hfCgGle#%^iygsBj3(v-H4A=EH<8ZQ!G-MfWle5^jdW9>_ zDF5E!CISheb@^8k;tHkNAc=L(RL?>ESSZ#4-CIUq_|>|&53-!%&=#<T)p1hgShx*8 zOrz|^#@$%l!tKe4d=5YTV8_?;?vq#DCG0h|kp8_arZ>ukIIjEYkFE+$z8TB}Ww>=$ zT6yqTI%Bk16I0W|V!!f;#pM6p8J#ZxH*M4eC|~Q0woo_ol#A8%CGaN2_TCEgIx)08 zM+so%KkUBoz9wT*@0jNB&pCgYpMCQ3Ut741kQiVnrRMWcZ~rXR?ngQCFc?1%J{R3~ z@c5_q4z!2UX{3eNl#Rdgq#QW4wURbdn<f`eo9wUqV%p5@2e>+i9y)2Bzi1BP6@Vq5 zK~(%6n?CZ%^@QW+Fxg!*fXL2LwUDu!-&pUgWNNGcq@DxhJ{kAs+*Q!ns54<w)2sop zqMAe51`33>w!<!r2VBk*Rq7O^{VD`|XJ}WK4$)ZI<OT;8Fy=tj%EW*MiIwb}SUoFI z!u>x)_(Pum=IHhNf>tvVO!T|iK#hG8Q)<%<XsL#Z3dd(+X^M)-&=>z%h@nEao4dA} z{sh2KiZbt8opID*p>>H84ISG2II>gub{Up|Eyam?^>X=<bSUI4BoQ#4IXDc#mCRxU z$ptYODr;z&Zr{|^ez<K)mXF?5w7Lbo6)Cg8*}2+wwuZP>t%|f8cdV>kK|L*rnv|;c zpAs~@jGDBH@ln+$VJEsoPFlu%?mUN@e4Y;#<Aqs(gXN?cusj60YtGg6>jeZT0Xi}Z z5;b*_3{&wuv$b&@VJukl&P#L;R~80ma!{ymlqmghS^;kenn$B9A9B*K2J#gt(GA<x z2;1trM4bBZlheSz5j12J!7O%_1^4}yCotL)lKZDX6=1ice_GIv3P@b3@M<@r<s*fo zdA&uOgfWH1Z}+idXJIHhY4*i=pnxhM&!Fq_J(_OA4v8WNiJUM;!bFaoYeaXYC<;$@ z2UM9{OxuFQFj+yF8+|Fbjbhs;WBW@HGGcIAgS(toQEbqW4_|NY{bJ(h&`Fjn2Z@lt zsKC`=8!>?kCn7}kHx;SH#WvBV{k$igmrZN_j_OiOLC^c$*}X8&?r9lrrT3+(tRz=` zq3ssH6|>2FVS57OdgEt#5pb6YAI!|sp`jZ9J6+pcIt+Abaw>oBCt_QS;C^jBU_E$3 zlI$CPXeoNE^;kWwgx*iT8ic(*8_tPny1`%BhZd1IROdOHZ13yXX$(DgLFC{Ihg-}N zVO=PYKLAqI-B#90SGJb{pQY<LgGyL}VKup})E=b=&2;#Tr<!3Ri{a3<8sZ@$@2jn* zLoMbW_NtM5+TX^WSw6RRc|CR+UywwRB&rG<52+yZ1P<4o-6t0VAQJf4v;D2SRz^fL z3MV0zi<>X(MRVm%)+O@6ipBI*is?%Ks!gd&N<!OXr1jOQ8<NLwU<#5{qu9Xj;8<R| zgrcF+{BN`4|0w<5!B6y#M-S2Ua2HAI?<7Zzn0$F4ot#3e%co;iOKf=XPc4BqE$XQW z{XF=;SNs1{F4cbUjKq(EBXRhRjK7CL_ctL&6u0QvPHxg}a>x~jIY+%fi3A@DZz#a> zD@a1z)>s3xE@KX<DBv$N`s|!H-+N&*lFV9V_Ys<MXqvrUsWKHQHq0M0EP#0F(pZYJ z%SRA>Rr3!jTSSu*{!CY8!O)Bj(R8p>b=_=Ij}$}Q@&~$w<SXd+(t_nhzG?I4V!>CJ z#C#p>&tAlE^GDRZYK#Z%L=^H26GM&ZmHX|cA4pRO6^diu-tjwk;cSx>gNe8o77q00 z&X>%fv!*9RRZ2(yRxV;nBA^P^U<<=REDd2yoWIvXSTZdS3-lHiC@K5bP^+NcG4tyR z+D{T5+mVIMl6+#m&lc25%loM6;dZI`Hvs+E8cXWKLbWQ*oR($5fN}($>9=I#46OFY zKdDZCfAg1eeF$dS4PnMrxwKFS{139i`y*PWGN-hSuNzJ%Vd#YmOZ19$d~b*Z9%#cS zthx6qnjIc3D7v96<}q<jGT+bQ6_YMBe_#)FfTWfys+s*0EPfU`Tpbqc+qG;Kqe%>> z>ol8Tnj}P$r5!a$KjDO8TzhI}RgAeGyLhXL(Wqjp{0NWVe7zq7XVh`@H&(0Q=2=_) z%9)+du48kP+GFk$On7F+>^@Nf6vgQ3EL3_g7x){vfxaV~!}yXzk%JjPceL9Rv_+wl zv-`FkKF;R-ZBR<w0X=5@?i?+{3y55AstWM^cdNV6B=7gYl1Ey+%Eix;>~n@ET-UK8 zqs<F;4R3s}l^fgjUA~>nnMj;~K}Oz-iSlTNG0(En0uIye@bNPSSgFzS_Y1+bnXe>W zhsW06+I7oMu?RM-E}y@dd{q0>%*fa%L99+Ufukg-VN%zFHdZG4mF-IUCoBJ|T34gK zz~wjgJ0O#B<n2gT74Y;^tGSN&*Djw}YXR-K3;=n#l4GZzg;@9VoL|QOIS+%uvnoEi z14-+|9xUqpg%elKNI^_7<o&7>DeB5MzOQak;;E|o3UD&}uY&Dob%ZdL)JF!W9_3Jx zvGfn$)nF2HW@_qJ(9wx}sm}7CF;*9<oz>KqTyh3zhk8C(@W6c)#fsu4*CS&iY@R~Y zCP(v${0Y`SZ1L>}#`Y=)f4;RgqmOuca3}1%Gp>*?YCin;E43v?Q^;?{`VgHOfF>R) zYfh8MPWq9Y%U`aHh1ZXhGhLc|Ud?J|nU$tKhT(!Z47*SqVccXlj1gUej*edZx9$7@ z@jN~^$<{u@E)b{Hop|Lm>3UL5yvWbA2`CbIz*w0vFK%?&gJl8=^{|#$i$>L8nccUw z%VqP)3aQMW&!=>yMlVhZ2b-*}_RT+*)CR6Vr{IzT5H9ufGaRG$REMzW-O_V>-{oGX zU<La;xtEHlU$I-D_SSbtg=5{dW$^7~dGC{sw@seTL|O%_VAI{Bap_k5F(71ijDOCt zQB`tLd+Y7+>fz&Q;E}X>N$LSIrZ*fcI8FvmF-Rg*8(rQT{d4}g3s_!X%X@&<Lg6I$ zvAZmT(US;9XmIh-T0ofI3L;EGh~jLa8_Wxw+R*TR$xDbr!8YYYb{Kb#Dj^9Y=o#yX zhD$jysjtF~Y#t741G2C>L3bzMtn~+9gP;kUxRP}dLL~WVQ-2(xd>RYxviz2I!{9cX z!^@_6x^h!9TKS;C)j8k858nbS>-ca9;I<KR2!OEsqhJN*39%|mM7maHpWs|QUjQP` z>NOs(m&x}ZGv=+<Cp&FJNyl3ps{a~&i@&@_)OjG5H`oAQ)9`lcY^&Z4lV7J^&jk{m zQCmf=nIjc)^Z|)(x;$gY^#%*)wKjJU1e5=KUN#cCxbOmcx*TO{7v}0rf0mi8y*E$u zTD^^wkRk2f?^}h3<Ba=5qaL1`{dqf9XhC>{%$jvbFDXnE*9r?tgcg8GVP$KSTjrb{ zF;LfThp#FTm!WVn_Mc5F`5duM6{auIsXKG!?M6(DP<Z}_bQ8(tK`KnYGsilKVssq! zaAPMv%BHcN8b%tTL5=LpZ5SDKBuCU0bckB<T(3?wyY*lA=BNEfTKV()zvUk3+j7pI z6d^$T{d`lNq>OfcwUl{dONv~f9qCy-Z=_3vKex49zVI^g<7qc81ocHdNOAxYf_|il zy-TG(IFB`PPN{%EW1l+80tECp1=<4r;Xb_ni%X(UT+i@W_@ZI4{I;-JT~CRg>+EPr zkg&Ll*r>KoTdel4qGqMprVBYQH997f5FEf>uwO$uvN_@B2LxOa6~bZWn*Xle6>>hC z=hvM{VZo~wfy<d8qrXY;y;nA;OZ0=A_uDefa+ghQ6ZtSUTWhjgLPpT4(b+rg?0WCK zq}vJ#;6q`t8rg$VQi^*f#<n0=ee<pBZylrtAe{H~u-qIq;<xT&Z$??)T?rj2RIvZq z8MioE3y}H->D?QUW3CkG@wm1Dgic3={`mgw!NGc}3ZjE+>q6UoP!)Wh`<QMxe^t=A z^=vV~K%qN!0B_d&IsF|gGP%4Wuz7zG-Gb;i?_9Tdc8@;ZqIMgGUTP&9clfG|A&j1x zu$>nk@6j>8^#ZWc3}$Z}7T4>*Re;S<HSZ>x^aZ#_HMoRHG!;M+(A%0Cw^Cv{*$&b> zhlsZF8JT3A=KeJD?<Gfvg4LP>AnkH7XR@!aHU;S|I?cp8Ft#N5b1X*i$#+L4^cX%` zWM1qH08K^aHrZJW+q}&x4}a06`eLsMZiBQoe#5Q{yh6jaiE-pNzbhNwH|K9-P`d2i zF+4YJbpIL&=PJH`*r~NZ;CgYMyjtP8?)_I(Z$}`D=T+ixAUCFv-?38zFLawlY_$F5 zKu7Oi<9?oX;FbY^c)MSwRmA<L>JSj!z;tAhhu<Jzvu%CK!Zm%QNso1*N3pMzj3ULd z+<nb{S--LXVMkEi`f?gS8+oexIQ2ITMr1ffzerI-)zMJ2Ri(&wa4&JJ92K2gb^-Z= zoif_Oxmmn&j@p$~<CGP;UA8K7A4#spwU&%yQl9V_it@p+MnbdSI2HNdr9oE0g!i?z zX0S835#{CpOhts5Ja2{AD3?GUGcwcG0RT1rD=VX^KRHSDTY#fBCN53$NA-!85ciNF z|H&M(KP=&!nyin6HsaFkj*^3K3kVLzOeRN`ZpG0vgj96G_?XoM`kw+3zS9r`Hnlk< z9<sD#HRs6<q|BvDt!wwKl|aw9Z(vUL)koCc5@pIm2bMr(!=}=loKdQD`-m`CWbt3X zuH|orOReOIdf~qGQY9U0t^qY_=_@$&zllnDh0xTJ4e=>Qi7g**48Cq!{F@2b=9ma` za{{_{CsHFgPC9E7J+JCM%_V!u2W|v;HBM*7Sqn3x^#(e;{F;}S-OxKpl_eH#KCq4S z1DPgX9XWZ|cJ6Ln17;Sj6nyC;$#E{=TT{5M6mIKXGa$>`Oa$Fc2aO(b3;J$;k1ZPu z>D|99xw~ICcP}Zj>hiex!;wf1FdpP}y-;<hf6HL5Dr|3D_UfJI2iL@tE%ScXPlwZH zeZa!JSSCMi-|E?m#Yb2L*TL1V&Xs;ldr!H0<v=jIBmLn)daS-THkdl`u@>OjelvO* zl_`_Z<y<<RYly0AjbKjjPjHYO4H{lF6W<FPAiv_4PzuE~-6!Stkx!Uu=5=y?#QW7? zp=pEC50}#~Ugx6VjM#!nl8o(G5WEZ{@t1|SP-NnM6Re40Mncfy-<(*MWG(}PK*k{* zk||ha4{gn@?|DAX$|SD&a`nZ=pnr|qkXq06Z)=$YaQ>h`k2@cMaW~(zt*_(oX(0{u z?2t@6bsLE4vlr5yw+>vb&3pRzg6$N|9>~+IUp4x|9Vd*B)F12@Yl^qs#cH$7$4G8v zCdE5U^KJpDX%yEV@I6UW@RbSLQ_DIYdUa=Q-BYLMauh!uC{H%urx<=ue0a?yUhD0L zLLCg8-JIp``xLC6E_6oI?0LT6+ne&0>xj+DHU%bt$q3Qm28nD-HRqDSe&p*hRp$1t zeC?vfdfH$L>JQc*2M1Q`?gaH$R-C(#hY%grm}5?RAxR(MeqX-{$2@{L?*n3NOT_qT z@Am^J2~}Qp*$ygxh7uT4R2@t*!>9ig!2U;H!~d3jh8D)<siW_1Y|Vxx1eJEvX)d7@ zp<r%DAqB~KnY}}M&gjOm9*EO`N5zE`1xNAw<^kM9>AG9=ZD%-+GCbC)&<`*)Q0>&M z!WC-sk)KUBd)<{asN>_ug#&?KYGlGX73H-2G3jisBs!@{^wEQ=LmUy>1qIZMc`-p6 zvSG>n9RXg@*Yi$m!tLyWWb^xf>ey8n#!U{Y`P%3yer`%KkTJo8I*yqI8s@GEKh5Qf zvs!Z+4e0P02V9@{m}f!|jo7$wZVGqyE)4y5KlKt;%Lm}m-pA-P-@7w+8;7Y89-N*` z?p^;fs+BF0KvvyN^W{kV<hTx>o@y3TkGc^r7od+{X&|uvAI3Ka5A?0wExu6g4vN=k zw0!UZA4v~3*JX`wWMOu}@_6u{?aZO9?)I$L^A9$&pIEFuaPZgp2P~L*zp~=`uhy?u zl5wUF|1rvmHgjja*Lo?Q%mTPM7~;Ymwt9H+Z@$p5IBTz7euowLr6!}hci_+69OeGK zPM2!@{0@|;hKuY&?3!K=oK-Y0oHb$H6l>Cnkg#0YRf~{F$?N`EyQpND@g8kuL4em3 zqIwvDumJEJKB-VStw#NL(c13R<?~CD&wAbs3u+k27W3j?zUF9Y3osTo&F(b{t6$=s z_rB__FUBv+Th_wfU_AWDrs3K~;(|HZd?}f(#E<0w%LN|6$R7n(()ZtTEoXmB;zw;4 z2+DLgb5102=<T$hF;A|~N0-v0&U4-ZGl}c3XVk2R;pO3XtwLT9#KG-E%6>9e;7MS+ zrG(`)I`x0$!#e4^zN9!m#PNlYJo$P|YSH$66sbHQ9$6!vXk1$moF9x?#X3RBfK88S zj!{an4$a&cfN1>XPkQR=I>bO#>NQB3nrWX<y+Dj_l*C4Ectt>N;9g5u4Bq-w1WyCf z?%txIR%-!wuZL%!r`<VvBN-bH=xFNwkn9mHKNw2>>D;OO|3$AagOQ^BP=Y_;dO~7M zLX1XN=xT~wDEO(Qe)XvFo~F=tOsdRlLyiS1r?w3!5RId8u%b~poSK3+5ktneH>U<+ zg_xcpG0OU+_IBp(!&3wL1qsw>DG9Edm20@4KPiJD@eUEg-x{;XF~j)6asa~1cU+v( z7l^Lgh6EpQKJd7`^m@E}%q)`{2M=1dF;$6_O3S7VN?0OKrZiSRPDzu>z6*6@gW2Om zr}_hyD@LHqNMdMWF0X-BGMZvm!`Ohti*9E6)?E$QD_Ot;u@8vBJY^*7m;0oPfGXb9 z875syqTjJj%Smdnf^m*vYdul1d8Zn?&~`p(y0lf?-sg$%-^JD8PUlSRswN1kdoV9{ zNJ>#zdA<ENV-ZLk`WRXRV>Xr<@PUO3u5YUNC^ql-!CZ{<+ZU$Dd-R;O-zvI?UGgvQ zZs9ntxPJ{e9I^RmD87n_$37cul$kyTB=G$+cHi+ayhl64ntg$j?Eo&YF-ktzFnpJh zUy@gEb|>I{A8#S4-=hT00sf}Ei3;kK)N}$iW*_*2&ESw8a3<tVknv{U{rnlH<M7~# z0Ox#fV`jl=>VJO!X7X4fQ5Cz|bc@P*-o0)mVmw6kWs*CT{$8I{L|`A_UkezG5iW3A z*CxVm7$&WqNxZ5#7r$e2=1n9AkRf3HRWvNLG5>o+c9zY_nqpf{0?uKQPIfwVx5-$^ zwW&3@r5E8p=XABn42p}-Bz%W>;+=8Av=Wo)2p%xsLh01fGjw96ro6HwyQccOggycx zq2p<1*>k%38-?JUA;vY+$^BrqJe=NOSWUa}713_S<{9+HY^<^1n5UeX#eE9t1|F<z zVfHXSq-6oc{W56VZd$Fft@(O$C0IcyT1N3Qu3#(Gcc<n?=Da@AC3k8IP9)Cv)bq+@ ziiV(S*pE~MV{zM~YM=$;a)p9*$IInuBIeb~V_iVg<aI25II>Ug&!yf^m8glRxDY8` zllV*HE}iSCIuuH*qId(|`ls1$e7a}l^Wy%Xx~v<Q$PAL}>|mtyvvIkIvJ1mpFjHvC z)6;o*p$n~&B+W(@otERX&9K`<D?Z1NDk}41qW`34{Mil21qhGTTgCVlKp0f_D>x=_ z$R#wWCQhC8mA_VTR%=1(7WC0bn`z_^gBV&<99!JnkZ~jxByGRk^xtFx3>Cy1(3+y3 zmaFKzfbO?|3WOn&WQYefRIyoT=2$7KhhIBaJrBncgCP>+Oy2hc#!cdo^B^vbp5ys+ z=1B27!4Y#=1n5Q0!c^|(NDJXZbTU`f;~YOP_AeSzl;#c1Lido{O_9Mj32m=vo7OI$ zo^C&4r%KBDj3d%g8arZ!_zKOOQ7MDtegFQcYpKZg2W9Zf)Z9?jJH80f^K@*W7?ZHJ zCQ#BYx%R`GE5L2l>K3Fe43n0C{Y|QjkyTQo9U|^-!J5(ja?p5W8(Mnq=RHw6L|RBA zVlm+WEn^@fZV^Glkh8og{QW5F>W^yqsHTu^H0g3&X=hPeHxdpJXbw&wHH|zmV`IC( zq2b$6bkY4=%Vx&TNg-3oXkvA`%t!QuRTeBfCCC8(&`sNA;So5&U^yv~2Zusr#RoOs z`k8;5W_|XF2~U9a1>Q3|sB5FIdBe^V7=-#C9!`f1&ue@;*pzZY2(-V{XqG3xgAyuj zM2M5qjSMlXA8e6*|3f!|28TbcF26IZ*1o`t`1f@9yIkk8(Z8v<h3lqF=f;C<oE(bm zJXT)*wuRtTY6N|c2~MuPqrYD9!Xka|%uNaq8^HBI<?mz;w$6b*yo*@wj#E&YXy5_W z{yYv-EF()kG{v<d)_XS*wR)z-Sgf0t_RvfbBwn?d4inboc$RN3s#_}%G^Mt+nSV=$ z&!?7lY8(A<jBlwl@92IXf+htSCY>wXal#f>g%s%>QVg@=`pls*KMLQ73h&QG(eDn{ zM4gcq%0ShBvHhTd%W>WrIaA%S$Ug$N5nPf0x^$g`U)j|Hba>vchlitCAo!*7fK+yy zw=_8uczj$RC&iqlAaS7L9EP)#%NO9vQsI-bStHrS$edY^$*s5reD7@VZ<Kl)9@kTM zb0=2WHXzf<hBPO`PsWbpn#l@@{Jxt;6?x#ZU6J8xd$*_9txFDeC#ss6GH%<>h1E~x z@6QT2VS=TYPR4_!Px^RwO}`tAAdVcmj3e!*EQfOnnFziqx#6bwfgmyvnh>Vuh3df) zr?kd4mCQ{gOz@nQ4h^Ei^1M8_)>wozdr!XQk@y-<Q97qfStak4w2VVD=n~+n*TSWT z>SAH0Pt#_k^sy-N9Uaq?q1xkbDqn80kcp%0-N>^}$)J{5HrhXO4uSL54WO6IY~2_| z90IiBHreViq!|<02x2HraX}7<dOuW6-d~qfue{!6F{A{sh(Lh0)OAR;A0@eQDB+rJ zA21i+Gj4G6Gku3Hx1~voucY~@M{2Z;6rVw^Y9OD%AV5#9Q!O`9ocf=*YzlI}1&xP| zpIr;MI}SiIkFE$Y21Yubh==iy&bY%*&YM3P32AOZlltisuaP~LoFv|QL{ns;%aI8q zs1qil%Yre$5ywEEBp=OBzv;y`Z!;Jr9QMn90bWls5j%apuMxA?bhIHQe#2*d!3!%` zrcQPKs8~>{L*v%dDyhsB#Qk@qBVw$tPu=qIT!(ou4%+rYTrXH$cdOtxt3%{bEI?T^ z_sv^?g=b~Dn5&P5jCYoRseD}2!MOrrV`Gm*qQNcE)w{%N0eIQazFk>LtI)v~;1>~x zKlQvf7x_%f(T@*X(o}CgXb-jMbJy0Kx*c&<JAU^hZ}%d<(|K=_3%bMl`B=N$f%f3p z>VrV?6aLh1*dykGM;1tK@U4IPf7Usi{;Y%x6|uY9T|XI8xYl;1v1+p(F@uWrSNhdo z{leV=p1{ow<0Os4cXXRQjc$Y(;e!h<UC!+upznqcw4y_J<NsaYVC0Dn>xTd`-%EvL zj4(hRzHxF+ri=MxEx)@U_U?TA)amv{=^6l(mQWY^VXmb(a6b638$JbrcN-gOgkZRe zg4uB$Inb_$HouH*6^w5sfhj?;Dg4VbNdf{tvbX2Bs4Ldn_Ii%k`xWdaCVV;Coq^Na zMc(pab#<2hSwYpuOEA$Z!FPjrREr@jRZ?=Zf7A7mT)F=Dh}%p-uq$(Z-ya<zXrsj( zoqgoITS3PCy+>b;S~_SpDp3OKgmB6RsJpINRCY_J8OI4Wsf5-$#3A%Zmq&N2iOQ}m zWpY208VwzYtxaKVHhbRL%NshvxLlQ)zCljRKM6b!{@pIFKYs&jM%{u(K9;~8Mw@(L zx|u4Lgq#D402M;+_C$>^c)F<_-j1PfkVNne-^vLBo5B~{`L4_GW<Ks@fqSSEFW^RR z=XE6~-NHjNTao51l=dp>=?bZ;RcF%W1F#jL2L{ezRVy=)zFpj|TEx5zBtV}rs<ro9 z;()sfHKJ`XMmb|0$r~}A9?-r-M!GnGvnDxgCjLPSb$?SHc-Xh@2S7-b^ziujYDgPL z%_Ke#wywW}4%O@Pm0)|pGInk}G^YL|Ly!4-O875~f}6IiExq4MnN>(fmPXyf*TC<i zEyFnL?8g$xW-^)>YTa15zwM2m@D#gU7goOaR7{7`v;U^tQ~QstUqFA;TNdVR1e8yc zWIwgWVrsO=xJT(d0Y+00ka!s*a_m)_AR{5{x+bJj27?%~ir{R;{?OzOD4vn$U^ZQn zZ{E%<H-7XAz&uJ{C4!Lzt@#l$5zMH(Q#Y=}A|<>mM^#*f4x*5lXdc1^^Rt&$`vt_0 zCPuh3YWM}_y8z6d8z*fG4KmW>u5GVyL;)>Qw|sGqP4BejFLkqgks75bbgHiSO3<QV z#pNi5XxllB^r^V*x4kXsFq(C!)8jM8OAfznJ=mw3XJU&3nzcL$tPLzz&YLdTRJ=R` zM7v4`EsbI>V32o0A-Ai4f59I4k|sv8Z=+qd+1LkABC+KE{&;f##2}5W8u0jV&&Ub? zAwQ7IS8sYuvSY=8!L@T66?&zRKkhT@2Q)%zxp?{8B%WldHlXnf@+mL>$Ry!8wqomS zfBZnv?WR_MzLYLf_W2YmwFx_Oai`%D@?s0NqZRdo`F8VENMo6;yQ6t7hhh)W2dc2{ zcl&zw_Ps(bClrB*p-^y_zeoNIg=HQLo(s%d0HY@_co|kC5#GMBL^qzk%Y6unL21aq z2Y&p?qi^R6c#}-1G`Qs(Q-Bok;yIwt`!r6<Bi{?U$vaEna_)rPA}-~<{;tk5<fd;A zNrIa9rW8?ScZrm%$!X-E>zw?@f?UUHb}mjugn~y5?i6jlt}dWxuQuAA6d~ZIX{3Wf zu1A;V`=8{I#yfSXZOwyyu$gznk15FEYtkm6ejjrZhOPKYK%t$C?@e))@%$D0xS*?^ z1AGBAn^EbFePA>t!mXr&PDXjs1^N()e_R#iPAokGeDrMluPsmxsWhEb4}H4a>NDrd z#Z@1vqU$b#<eRl4x|hzNWg!i6F0zX=j{uAB5t_K(2%OmmvKYzVW3lq_*6x)9F7+Rv zTLizbkfp%$@V$Ub34Sr}yS^4@k5d^)<W4O->64t{F~1AG?c1Hv;|NUaKUVyim@+S@ zYdUebLm_#=l90So2KF}xV_ht_TWY;3rr(*ACSq`gGNQ$*KYqcFXIxvLjjza**_E!n ze}isSuxmot`jgioOGLG~fHEdEB4;;{Z8;XZJ4|C{%Dn8QL26`{BE?zL_Vu(MRk7QD z2kp`{mxT;7jDT|N*#M^3%b*EM)jqaJlbaOkP%r9ah8)A{8rubP%z1w_5*i5U6ATMr zEG8q>Yx?R^7fT8#t=gv=*yhBSJA*#hJRLCz-ACF+fes~3gp3zMD~15*(kGAArwx(h zVkpdVbBD5FxwQNT(!#>v|6!J;DS{9~GRIKJP&aN^Jr$Y*OBL!vfyL%Fa|TETc_GA? z!@|HXL~-em3ejK+WE9_wg4X35XHy7JGl%NZrfX$JV;@kIrq|UdmZwOoLX&MXV?fP9 zhWbvkFtKGjrr%E8g%Yzg^vaU5qC|x7CMpslL5un}6_A^&L2{iRg^s!nPl3SLyMP&# z3I>oeyEG_Miv;T%>YFJU(V>TW0XX{WbOHg=m8u`_m}X8x^GhB~;%q`}H<q2hDTs+t zvy@WBl)D9KQzT!@Nz4g8Qfj4eRnoNlANRq*7|@U2*19*eA0HE)8Q_x|C&nt4f*x@u z#px=}aqW)q*1mxrBtyp1U4lUjLUMz~IE+^1G@U^!7r7Ltjcf?&I{4Iet2#~@D|$TN z%q;Iwy?Mi+{XFPa6L(JNo4jFz_kYWBZ5;!-dc)Q{_mD0ubC+VZ^N02-LT>%)(ah~` z#4qIN&&1=Z(hpqGS$%<JCl}hqf%Jy3F$gMp?i&u2XweHxQQOt?@mR6v>B1N4QD}O! zTyx7{Vz7TXb*YUu$Xf-G>$nnOckYHJk=XpR@R_T!Ly;vfa>6l7jR#)qXUbvf(sMG) z3a8y2C|~#2yNuWR;UnQfCn8cfgX*HUa3CfI&j`$WDSXOrp^<_&kV?U5vnVJkt7zjr ze8l!82|N2z#Ui<T8^26^q$+(5CEP%&bq$6ATe3>)V1~@K4X?y6AOaPaG>nAwo$$3K z@6dq+%s)g2eY1^0`it1U2?eiw@Nt9*4BCxycX@BJ3<h*|PjUE(?f?We{thsN5u>tg zDL`0ImFz>+*wvipXUDRfqOfCq|5QHk9`dE2uK>v0GCT%6b`)qFk<bj6(r5Sw90s+8 zo)|izx?Z@tT465w1N{ZA|A4eZ5!$-<b{lyC)A<d{WA{zELr&Ilu6BBuyjp#9>_%kp zptB9P@!BRgd9JSHklC*HubDy2k56CCG5zq8oU2N58$PKk5W=55@3HHOmQ3w+P}x?t zTY$V;(~!cLiQIYecT;D<nKtP@3{&1g-mf0+e<;pgx5k4-j2s%WE5;QekT0H})vXSA z!dVV%u5Um;#8m~INQzo{!c3ZL%4rBueYwC8oL1i}l=}dQuF!EP^;fj9>-ecqWaz81 zvrsByMzy7Ip9^oM|5sbSn9ADp;D6%mvXBQ;?*R-o>ObHW78qp_dLg-DpYiQ>z!(~G z0lLKVEuS%3HbZ47f(#whJP{0<1bXOn#6$QNl4@+!L=3gMR#5<@4-IDkYotI0wtdd* zaImLf9|5}kw_>DxK`^<bY4=B4J{q|!jcTNjD^m#A5A`*KX4$i5`k}}YsIs_2{x+6# zsI8uHQh9*yq9E;zxjI=NVR<iaEk`?=3m*tBF_Ca(7dU`646CdZ9iDd0L0C5R=`kcW z_lIhQ3RRPIj(qT@icqDcy*c{%@s;5)&mMuI8c|{+S`sL4i+*&(Nc-h!6Q?Q$AKzJ> z1&GX4`N=o8I#Uaild-PRVE}=({3-c2c1_TNv>1oQ0j$6A+%cmaR*5>r9JMIBv$DqO zKdt(!qB2$qhVfffbMT*7R=+;eVs^7W(xVs$y`&;=t&Cb(1Me}&_Q3bvDbi#i1Pbv> zYqDzaJ#o))gOdE#6CU9kZ}G9n30G<@IQg9Xw?W^$LQ&3bOFqRHzyp!`ex26{W3C6v zOf0>AGJohY`^3d63)JBU6?`Rh^3Hfio?_*+yOPTgpfWU*It(|9=P>6uvM%cQ4&8Wf z$lY7VwR;D({&MZsoy*Qb7O*F>+WB}sb;(#T)R$~jPl<%y9b#0A@g@(yk_WOPQ-8>+ z`Mj=VH3u-L3%*8M^+*0X&1Cet$*E{Hyg<olx)Tcx)CuDcl%IhuA`l7=#u(3DRXm$g z|7jno#Tst%MZ!i2;><c?Nc)}6x*_ppWP;+k^eA(ca^hu&uua=T)=zY3JBjXz1WWML zw}t3fgTe<8bCslQ3l&;}{xN%atvct{ioL^oBdl;6&+*Q?+6d^d0Eui5k_nnQZ!*wW z>(<jayW~D+AgZJ_;Ksr~bu_oP$G*>@>h)f0i(|L%eev*E1F;vrA>r~23e&;s9o39* zU8HaAFXkE3uY7CkSZ=gLZc38XZa(Gp%nO8u*NMLj9UCZmkB7@^+m-LA9RZH(&+xQ- z$HdL;&)=v&<YcY(;5Q|+^a*M1fMFx>J@bZ3;Fp+@akK=OkF6u1JeREM`6}MtEkt&( zaMN|}Io^4luU!B0>$ZNqO__9*gT|1wujgJU5*t@mj)eoJ4ytDc0#oTwrW%>?m%XrL zOkL=gDEg6L0C+3=J_B1_G(;z#ewQiKfS_6yEg^EapV?pQ;kt6gHJQV>5R9WsHF@i4 zl-a;wF?zmlYFdQ9u%kyE#4r;ro~9I<RaiOn4X8T*hpu;wtGo}te`jj4?V8NVZdVf~ z+qP|Ma+7Pa&7E!Awy~RR*V*^)kJou{&h!0re?Ql?uC?B)s2gsHyEu?&8-kBE6thc+ z4#W`J?17(dlV>f%!sv>r&*JiJ`#bN5o)F77Rbj)?FO75&tTYVVAY|tykoauKs_AcG z3D&lcEZpl-kH8o*XFOdx&9R?CsCjfae`aIzVb_e9cD#XqNVj2vEe8pY0kr8gDk0QQ z$WjTlt#?-?Y8r<)A|#2d+a!?%SYhI(@Gu^G%hbHT*CZ*9TrA?GByo&{Fy}0itg19r zX8Z6BVUZq{fr|6doV7H==wB>H^{AqkPS??ubZJT%Fhf0G)Q;DlX`eBn(@!BVXy8!F zK!w#fURFNCK6h_|Le!D;R1BU5A&M)exd)uDg&gp@+9-{QWemVdQ<tw_rMnu_RoG53 zNK785#Q&Dy1f(3D))mXgpy~Uwu2$Dg9}3Jf@^G$i*LX&KvZOjCA@2j<Vq&u0x)e|k z9uJ;5L7Ik*3yyrxrpGG;%<NzNT2XA3b8lWd@J||M!|yhZ6+TV2sp65^iJjIE8;O_} zZT+{;aVOw|PErg9OiP<MJRdwu)!BT0rXfhLb*-(CO)5KRGf8CrkUc8^;M9{KQv}@N zq{bs<ljI#WsJ@DHpSAoI+$C}u4@M)|X-*8~i8kJ_&W?%+Cf0+=sE)$-5v+c<2E8J7 zF#dLpjmFZMit$10)a&0V+3`f;mFZqHTuVYSH~76A$=T^vg%U*T*KGE(h1&wyxPFV5 zqRlYX{2h*_gMid*f_8o`Jd*n+<Xs7mEqMa~&ZjJTbahXcG_&R47ei4aX1lGCujR%D z0=*6UB~vkBL`Zt0=xg4-R<=Wq#|TOEtV3e~Z0WtCNwB;<VKUcJnz=cRclxJ)=y%%R z9NLByj!fC_l?<1Bc%7;aw}><<aY_gPDLkd2P)A&=@|NXv_^<=h6)~n1?sgH|HCled z=`zFFwmKn6JPF^sVA(@zFB1d>yooM19~^%h>8_gT+*V?|mjF&*yKa>{N(SdDa5rEO zo<cWQbiO_MIrjhiHDQIetWc9z?v+@ynI2$V^TCZ+inrK$QMN678>-_cxOWz2h$C<x z^=WhIWTV=nz8yDxKgHkNmc8)2GW;OtC^xReHQcjM6J~Nml2qRvzQe*|qh#`|;)x;A zyrzzqXvZR2q-4Nq?h$-KFb_Bq3Ka(<U=W0>+88gyB!a^-qBX4Y7RXRkvHrw7y)OR! zGcJjRRd|!^u{>UoFHC#jY<%;FavMjDMh1g%7)wYa)D-)AL@tW)1Dt=^eaq{U3f+qc z34u~uoRC#hD5%K+tHL82Cc8hH)HF78afyCZr9y=Ck&zs}O1uggx+#(XW=~uwBQm?Q zn7Pux^3ueglM%VpAb*TM;*^qjuw?!Sz=(oK3Q#zlXq2nQY@;we4X!C-?4Ni1E}Sxz zKgdSuG@$}C#RI`H%&4?^Y7AboKgfQeH}n~;xY*5=OZ0K==MhmZ<NNnf*AQ}jLOuVY z!*W)h0By-X4ZaW&E0SR0TQO5{1M&%)PiFjEJ35rqBnJ>~AFO()mslNtwVr|9V<J<& zfA}XHu7}8dIA5ve#uJymhf9-@a$SE2!dY7y&xVL2vf47yRSK@?fnXhYi<%HOPxOOw z7PKl@;Y0rXO^H)0+_m;MP1duys+T~rjCWZXTg=&(7knpUhzX?vKDbzWl>075x)L%j zYTlHtLt5l~BfrEw)Ap{um5LGkvP*4f$AH)l)o*vSe$H#}%u*(1rC0R$jHHxzOyqzP z^t)-dT^w^|waR7d8?pA!r56S~k7UH~9oJYi*Jz7&29dcBhj}YSIo+++dzn87p||x0 zzi#D~7h;Dr1wgiFTFpyT+sn*M1OS1b%{}w;=0uymU&T7YLOo{yIM8~(o!1RQ2b*?i z&8b?5aorya`d@w887y9qGZ{r%{RpT80;}wEpUo}av5N(AZ<pI-d5({sc?Zsa2@cEp zuGu;{N~iwwHr-wPyJd-UzGWY0`h4BGNQ98W!FmH@TTYwHuQq4jwYYUg0jc%zawEMx z$yLnckBct%?i3s9Sg@xSDqNthz}Vcwf;BYUU#Eb}N980rQ-3nw=bz#DtViMTh}hkL z#YvW<JC#EWgJEaJsp+=yys?~IAYv^K=()Xe^}t;{UW^Wvr2c!N{RCwl-n$JLuHGo= zamsmX)qIbNp2;=R2}0!>K5y6KY@6ZXs$9>K^BH$V4~h(^DryK9p{Z(*gZ>6Qg?ow% z{H|0JauBLE;gj#Oee$$^eP80#xj_tk=6D}+!qxp@WmT~btO!dkYi|9FZ(v#1CrL#q zIqH2|9F6Wk;XnYCIc*(y9G`=n@ixaQ|CzR$fws6N3$on>(%Eg7$MNRLMEZreOlHFe z-0$@dR?Ld8S)2ac`i%SB+o!ZdAw$sRr%GYH9sCsDW97>F8up3#)Eek1_p3yi8`WuY zGOeE+N4u;pQ%7C<JI}v;?O$}X^c+kD3Tl66@XE{qy7VJh5LKg19({Mc<a|QgiV9#C z${MRGyhgIo(R<evW8NDBKv-z`kNWkyGIK}qKWKT4t4N9o#v!aWH7DQ-fr-{`EiQOK zPP!UtVCB&UfY%UR;|m;B1q?)3;<Q}8Po*66M&i6TjMzUvDhW<YB;d4TQ)?V*#~La6 z<}ipSBRR5P?E4yoEsSGuL^SG{vv5@D@3P&z9e;@73-@)r(K}}8c&L(L)SKb5r}Cf7 zMQbshVT!SD9HmLTs!0%on9Mk{hVnB-wbXm~PAaOuGuJQEs7jRqWzbKm><6x3M<sfO zAw$!jBL#*$K-SLWfh$;mIo#*RK*vG7uNYOD<HA)-mJ7+4a}9U5=~Z>WT<=vdmOPMX zDC&<2Hg^|dviY2*O7aP*?_R!(NLKm7Ju&y?#LlmjK%<^RR+-iNyvr4BSE3k=yS3%b z!-um~^&@%S?NY~)8c+3gPdy?u7+IyBU7k0`XYKJt7Nq%`3Lgg0!_3ty#~M++BTrPd zvt5m=1^GI#P|P96Tj3Z<<@H;1_FPd~5>U8=J810sZYE=9pExQaXb{J6_T>=<MQ8vy zb^g`0q|VT_{9^TrFjL_7VvO=b1xj@+J#5T4$rIX|d4CUk>f^VK2jPA(f=%=64V(wB zf1A@WmY!~_Gf({7x={CVs=E3j^)jG0_#puF@+qnV){9LCpXsl@VjjnN0^rGpXW|C{ zQD)5gnsV@FA6c@PiEPBZ-|NFBL#RCWRP&fo>8P?Y4PD@=H*uDL5k=Rz;L}(nvU%np zI&ZkwU73#P7Ia@Dj{bKt;9=Tumok+fv=&6}!28vUiF+Zh{&rBi=A9?FqmaB5!pONP zD>&S@#^tGTdo2gF`gpg2F!SarmqLxlW<K0>fv@zb*nwCTm+6~K(&X0FTz~s6tCnLq zj;*T`AonEBJU1Wm<pv~2wLzvjA|e6k8rZQlyAtl$pPgO3ZJm_-Fr-nRHEn<15wG)w zt3)@kU+i4ne&|0JikN<>?%XOEoRW(PE71vAinZXfNKA2o3lMVewbW2@*cJ~u66d(# zQP_U`3E5pB>qEYVxIv;r@8w^xp2!>AM9}5Db=@M^H}zi2KX>fsG%ubvDL`@OnYw*` zEnb1bCkmC_2Uvcoem^l6M;lau_1|s{EhAFy(kbf^jZxC0Gxb<Vi@CjRNGi82TpKbA zbRe<s2+?QY4arYX*&q}Y?6`k`ZySX5gMB}qxDUGF5C1F5j42o?tRRD_BrF7!xt^Aj z5saj>xGpITzUfq>#3?8k#8L^(O1%P=z_vXo=bvs{{>O7u(`b>35tm{1ebetFM~nUU zy9WK@LK(?8qP_PjoD*3w2rlKqYltO5iZt=mCHXG^bU|*qK!;#L9<8DFiw@!5#eRbN z@X)F4y+zLS2S(2QP5CsB+%;?`+N|t6>c~tAtA^X_)AzVto>*8#3^9pMp$}~JaB<co zwSpi0wqS2o=)9%|t%+3I5W1g3K^5;0Kk@m_#q>D%OJ9%Yi=)--Xyqo(bc}@|7K4l6 zl~jJ_w&C9x&AG}?iA`wJX7-YgI*ISYFNBvn6S<7$T*&Qt73Z_86xnyzr=B=#f+1+l z2I(JrqRZjCaGIMJ$1$+J$38o!|B$wM8@CQ;o)?-RYy9a~T-ImauxRRT|E{`V+3dBr z{lQ=__bJn<2gS(eZh1c)O4@}bqO@mwFbfiQF#Sxq<}ye2-mF^_P>ud|x*agMCStlo z1lNVoySy7~lA45g(cEhWqFqkRwMAbkN|a9<6T#N|Sh$)2>P;KG`L3YDHLe34+P-#g z2Ik(*__%oVJ5nd>1f!kW%fWTwf?S;M1HBomt}l*n*1IQxUzkRhv4pSCaKVJZ?R_-- zDnqK}Bp5FNkI`)?u1*X|=#Ps%Z^vUx+{7<2WeRLWyhPGD*6v0H`~8EpGmo@Ut&m8^ z*#ulSZ$-{EFHleXQ`-J_TM^zlSzTtI@o?)2-yg6C28Efxu08$>D0W_FFC6ZiAm~vr z98t6~_;)myyVMI63)nRdcQ2s(dB1rJRei}vby0a^mNhtxb+nzFuz?EEOEImkuroU8 z=scJr!8e7NJ+Nb(d^$LNyMx0$>xyR~PQV2@wSub_F7Bde&(AcSsJ=7Vi%lF9qR+Kb zoPCz%GEL9hxv>)$Bkz31`ZED4Uq``QWLVT<!9=}Uiw}ToD#QQjcvtjD&g7d;_&T{C zZm6_A(~7*i4q5*qv$fsB5f??+!hB?e<nH_WG%~epFSGHIE;v)Lwtl`bL>p<<aa&y0 z5pF~m+&xS_aino!{llf<t0Yhin$@-Hm#5cCxQQF9EZZ9PscrwHLcKx-oz#S}@7)uw znMhY$^uJd)ZY2QV#e6dCaPiX#V5D@$i}vFKGfCm2OjU9KWZ?*vWJvwVcMZG9*7l?h zHi`PvGw6WRkz7KTAsbvpX#uQKg<<YLs(ys+#!DG9z*s_}V+$b0F5s_uiNZxx1<K;2 zD<{p4xje9X+D3S41h~7lxf4**GYr$y9L`=4%gTBT;LP0M5m67s#2IJ1bYk<AgyP8u z{GyDG`K0*_rw7XEiUDhKw`iHk8l2j!Gof@@eo_{Y=P$4-ZDlrKa>ydjnR$*m1L!*u z{<&JKUtJJzHDOksI@(I^Ydjvs_x6&c4+1JY?^g@SNpv`UwHo-XpT&aQA0wys?V`Fe zDYw9Lp}zc@U1ODFY3pQ+tZ|j@m3NoD<=C1nN#<kG<ko$;+vks}<J@6LP|lZ%KGyQb z>$B{;qM_rCm&?3qe&*^n)1jT|NqXI?8D^_@u2giGuZFGl4+10!5I?p=PTiRw(C&!c z2Q5dE)YR&arUh3Sc1AXaQGM{-azaE(a-CoK_}8~CR!_##Cl&I#x?H&g+e7C~?n{7h zli)#7gXgg~FCup1{GqbK*Vy|WhR+rQB4g8zgTdzDPy5%4luq3$k6&}wBhotdF==(y zN=kA;XB380_ygb9>WA<EyB>iBe;`nJMFh5k4%$`U8oUldu8{jXP+m8{!&XcDxtZeT zc|UQ_Sq5{*zw9g^$v|~53*<hpOswWT;hTPc{v$I#2|i)?mB9Uz13I@k_ESlJzch30 z^;Wj8n|{mJd0t|9lo00(MC%xn`|cdUZ~Y!S&X>P-WtE*5J@FR1d~9xBY#+@p{Uf5N zWxYPI(bjLK%5F}ELo~xAF66ol3pDjm%ZG=4k<O)IwR|6fL-3h!0$3!XpNoqCghj;D zokJh04ME&Nq)sJB5*rEI0I9H#qwT<Pzf}ctQ~l`_t`Umnya*`HoS!d9<-WoC#61bH zrDrXYTi);C&d>aILH$8*Uh>YTf)i&Rd=<ub8CCJqZF)X)J7&V;k?Juf{hP7OZhhBj zLHQ3;pP>4Gegy}UF0WgGA&pyJ?+gGVp3Q|;vuXwI@5HSwF1tg-tI{S|h42FfH1;F} zoHasKrDQ4MZ9IJGXy2&F&}UV3Ph7$i{tMgW<__lMqmK!KwU__)yP1W-|C6g154OA) z3>T*<{aS7~R3ajQN9;&sC<YKF78U~JlgDxAWm!ul#c1ox(W--7lJQ+v>sTZ4A!gz9 ztIGjOvW)eAX)4*1J;t?6h=I$?gN5>01Nm{up=89mw~sA)`gr|z9TT$UhDU;9+k1Zq z%uMn`RFs|iUmEb!lF~IIBt2Pb(GqSTjF>1UO((OVlittBN1ap5Th+b0J7hQ70$Q}$ z%<S}MteWj_6XUBc-?@s|I}%NjJi3Ql|7wcQ@i+Up+O!=$`f+jEg!LXHwCM+VmKZFW zS?C?zF{P8Yhiz~3{M(c4Ucj<e#>t+}a;!Jl<+1RlDcds_DOkviQFfEj^fANu8L7Vg z0{AvZ^>g`T<_5B65B0Aly49lB<3IA6sn4v}o4>m#y}SGkPq5?|hR2Fm7rxhTfx)$t zx^3-54{a!oVIdr+uD!MUNe@|et{`-G0EF0N2d|OaKpRGAbZreEn%rhcXfj)@e7n2n z!hX^i5e~f|uW5Wu^W1sA^R0-T(3P(S+wsHPGs;LIzp;JKTSQ6LFiGitZQ1-W-yYKt z?fc(2&<Z*Kvih$SzWg^K9LoIq(ee(hPSC>P?{0?k%~ku4h18)Yf-~#O??mrmmmc0= zkcGDQj>Tq)wYFe~1D0B0k9{jMVJ->g0&Jus-|ZeqS0e|p{jx8338tih*J+RO%n#NV znyAf_*iI(|sYLMIkHh-kp-c`2Nt;LZ^I?2mZ)9LHQ=Zhu`q<;VRv5qKK4`hIh|hAd z#Qf$R+dfC_^(L242g_&G^4YTJp&*A_F#G@pH3((d^yt@3oOcI&nC1SpJf{)nuUFKQ zEh?8>bX}%^Xbrj@HRxe_=ucM546n^_Qnuq&e{W^ZN8`wYsM^Q8<F*4gKlf$`#Evh8 zpITuaG%3(yv1xAh0_#)&<Zq>3r^yey1?kN>GVq<RXHYW0n#J}r7Wc@_ijMtsimF4> zfIw+rvw$E%EOVprd!EX?=_qp<IV20<U(~AFrJ`n84Mz$$`W9YiNv8~5$~?av{TSw~ z7m811hmKt+C1mX9cDJD4PjFTf2I@!h-fXP&|Bh}7!dfW_1M;N>oGuCDDWxur3E>9V z_TmGrS%fL_=lj6IFnx$xN$#=EI=bI@`2oBv7$M5DYdov-OALlTcb3LtSO=<=Y%Y>f ziJCfieIObcQv4AJ%Y%QQpPW%6mSQUkFp3-CKG_}@yppi(jqY2L#8QKm;H9iZk6ZJZ zi&L0Sjf)8!ijW>F@}_s{oIr9R6>=;#Z;dKS())Jb(%F9R5?es6cNy(5=YC4uUNV~y zt3FP#1@gT<Oy|(_Jw4NHg}ZC-@g@0N)?J<V-gOeBr(%O{rhEBw{tv<NXEF#K;r(K6 zF!(>5LucA1-JRp}G|vyco;WaH<DOsJasJtk$w?A{Yi^=q8w?*rd>IZZygUhQeB?-i zxm-TZ;e~k7NcAN$)BQ~u?_kHqVDGH0PyXF;yWP}W;AuNB-B(_f2%F~^FG@bBmX`UE zlHCyjB|NyioA9n1c|Xx`3_-(h(%}`|ggAuFI7gHb9GoOv8tAWPGMu4KeIztPju31L zk~1NA!lXiuye1@A9dvdrd3_!8(UZa%EDnl}BefV#jE`=ihZQs15$UOz8Yi0chH|^? z@RsVxyS&{n{nAb7we&i(zr8Ggl<{m-Wc4`u@6nJ;R6h{Qe&<mJS22$5TkgxK#pBgq z>*XEAZ!#dS7WGHq@I_BCP7Ns(#r+Yn-<Jx#{y)t%r=$#m39WweM<9J;em66Dfy{Nf zqY4rH6~D35PeMZ5w}d6(dVRoKl^=E!GOj;Vxz9wysL$NBpU1Fw*twID<dmY(ir7tD z;s$7fqpgox_cDVu4lcGOPsN2D3r13BIFpZQJ8RmuZhTxEdtp8f-)FKu$fnzl?$(gt zay)y?a~WDdF58j6esXBwx;gjp-3O7|af6?Su$&^u)k^Mo9S_6K|Af%nnI~Xz{@Bf3 z2|BdP=Pv{*Lc5jNxeXzo@5+*y{PLXL7(}d=J%s<>3OSS+JyF(rtPypJxaYri^toue zkxNTs#yadsLb%V&*qkhx(%CT%UJfP2;1YEVVVfc+Vtonc<bY`%#t1Nj6a`-EKTcx` z*xDWQACeSxp-|K#_yfnT_4fjL(WCHRA-O%AJ+xB=5h4A!Un{|$q9hDuXi=DSWl3tP za#TPoM!3g^YI~}hgt1v<qR8L}6_?-vJf>>i$|Ts);V7p5zVtYZE`ikAtNc`BvNm33 ztDlqpCkC(7#EMA^_zPn?<fLw7O7b(87jvAkkZb&KHfiWO&yD)6QIt0jBy8Uxn#!Qg zwXazreOu*!Z|=Lxw)mI~9O|B5*e!N!i`1bYbZ1xH@A#~4Mf#<6#NI6=3j8j7m-4J{ z>^G<SMiexvZg7D0ohUHVIKbuZ{08=4p>WpUx1-%yFa9xxSDxlg1nwpzGxzp+qvvxv z>#1qoYhD_NHA>S(>FM(%*huocj7dk>Fk^%~<$iKiUQun=Zk49>5Z-gf$4bW^h0bF- zlS<QiuN}tqnHUE43^uJ0iQB@>0FXg|-gb}E;V5wi#<)BGfiIGmZ*VrrEd+X<@&2wD z1ADUuX!h0#WI3jE4u5lf@g~mfxsdo#aOp1lTh0DEGjym7_kHC0KOuGZ^^&j|UzHUJ z@--t99oqJ*KYU!tn)*zp`au`cUb5WVyF@A@V<&I_ZX3e%V|^hzr-91Gm%y2Gz{-K0 zLBBLxdq{RSGR%eWh<0imjB8AmuG?AvJnU1!>?~YNSPUQ-$=>iaqZ0d8M53TfJNu^u zyp3$A^|GPSy6?OeAv|$BbKz35?yJF)tAhvhVVBUbN%$&)p01I)m<a=K3aNclHn-h* z`nSz&?7t)(Ev=_FUYCgjaWui>6!wC@ktnzn(g`TWuS+%qLn`c*g;}A)7{3L0h~AvU zIk&aybyWmdi{$G_l#F;PON=>_KkF5K*SK{wu6U&$7WAjmY;5nZXF}5NzI<SoUv&zb zFw8NAV3!KMKCVC3d0IO>0~UR0dITFqrSUv&oD1C6chJvDoy~MR=hxK)?LJ&EhSP}` z{U2s*I3Hl?(XDG!chT?%$hC_QWeda1rG+aepOdvhid1wo$@q8A)%7jxN)}+5GsyqE z4TB|v|MHzQ|4SZ_2TGBNiAU0xBJzRPm;Z@Ehcg2|O0Hoeg6(8NE#X(gZ50Ai&|+7{ z#8MG3U0fxw0%7qPLP2Bnyg#t#c@b23%4*O^OFBF0(j&*|S_hvR@r#7T)RPv<fJI88 zRcnZ`Ah!<)6Q(;#uvc|b%{ar)AtOHb?XeaOyuYZ3{ZN)r<^55cn0VwfT$l@Q-w9;x zaMkBu)ZCh5kOvcw?Q%RTZ*b;0(r>d`iSg7eV^Z!@P)`?joGu~8{Isb?;194E_78yy zKAOt=heKl3Zfhkrb-vEIbCIQ?_83|no-1#@O7~3iR%ZP6aUV}9!z7ZCMRvO`A%)m^ zl1Stvjb4fBNAwLc!I0Vpey`%>nK=*l5hN@Z3&qNwiT1vT5Gy%QC<%r>Y1V9mTzog2 zZgvj&Uc>b1Rm&WkRmmqFWnLNdkXjpQ)d0afuZ7?Y<^xg}5(fYkq7S;k9v>(T>f9NL zzdrA|HcYozSI-^JtGF*<;fxK=;T^ux4-uxSKL+}dt3ftB=UZo2z^QTRrh9e8N9TT} z^N5(LQ?4;@RI9l~r@?$w=@q`c`t_|Y!pYa?fId{N<{Vi)a7_y~Tu=MhxUAd0FZk{| z|ETbe5apG+?<=rB!qab60(QXX3`co#RJ{B?Jl}g%>1>?7dD$9!^uKf%y(ePl^D^BI zeLMYn1wiks7LuU**8NHNaV6L8*Y7boeC7|4vS;AZ4s<3UK`6&-FPSLfU#hhxBGXd8 zTNMAf9j5Ti*5L8gImPE67oFP(hDCI*4{YJE*qqn?oCtH->d|$<<9e{3BBoDV54BPp zMX>i#nxUILr-}s9-(wGqAc8P23k%4ETK)-cF@jMKmK&B7XzX|ZHE|09ErDl(4vtqJ zQYZS+Yq{X7b`g*+!>xyE-)c4R@6k!xaQE-3L8Uq4{t@S^Q@sAO49~?XaBo^mCq%CF zK|gI60)8_evburhZD|qmYz7x4mv>vF^{`WQ_RBo)vI6sIZLN6fg{^6w1=IAD&gm?k zI~PGnN2ZeB+B}e!RCS@;3EdL13shJluUgyDAq+&5X1<;6T@@7h|DL^+0QpFq5|n1C zb7(qbfP0rSu=RO-uu>Z-S}KS#KQL?lnxBpm{{THnNlTK>N_Iq3zOzw>it#L}!1{X` z_%&o0xOV1To6m@5>AS)6jkv$5o^ox@y9A7h43Q-u2hagZZXW+i*h`uy8J7^N+ve)C zHmc}}4c05g;U_Ffj*t7?Bpo^_XIl7Pjsi=fhKOQaaL}}b=9Zv%6*ry`)rvHLb1d`= zGZ<Q}O4?A7AR0mqA*bcUj?MpyPu73cHN|K8a#rV$IPg2Vq`UETN{YHva7nsu6)kwB zY+nkn+c|nXFkP=%brohSFL-mu!TtV%u_st9cx{`cyp{{E{-U8{Rko7plyM<?>I#o7 z)>B=}d`{*;5~jFF{62Tp)N?G{PQjfHodrW|$?^6yx8Bfg<3Z&z5sFWZ-X_oAy^lB{ z6{w$hOJ*lz0`ZouxATao*5uogr@1#2x$}V9q!YX~KNX|*;qu~ZaRo<rC{&LE?x<nc zY;ZK1IH9vwpPL<n0*hnK0*$ruW0DE`S|1_`x8mMm*)bUyFr5i`%hDQmm};B9f$BF? z;=&yyGPUb&0uWVVf%-uRujLy&Mz1pkyGf+h30}4>+gi<)IVQU2H{)7JJZ-0N!PG~E z`fY6OrrjCpyK`7AuBaCmA-$6*Tbs!1gv5+MZ2q#TV#Xg!Nfn);4f>~7fs9-n)~aH+ zmdAu!LB3Qj-q6nATXohu5zx(Z{qp+EvAln&-8N_LefEVv;Nvm(GpKpe$c+cEs>1j~ zBe^*k_pMbm2Bcja+G)DqK9u7kNzEw9JwIv+y_O!{ESk$TZhmS=#z`vHp15JqWk@{= zUq9Kxb@s8Y-1^<R$!b)nt!UyBr;dJze|EF86V3pX27`fut#anmXDc^$$#3L$?y}bQ zah8noIM($daRWH*xcT9D8m|b76Kovo>kD-Ja>OuEo&}pHQs26vE=Lt}H4COqs*%;F z&}yOUHH5`xiALz7s%d3u{9NYG2M$msg8>3ULXm>MDF6CfsiL#+YUv1>uKdp~|53e% z27bEU1OvrYYJ&4Uf-TFjvvAKw6^1ec!|@S}5t0Z=MT?SW%WmipqSq3VV^b3rS*4@v z>SWLlk75v2^k@@7CPUEFZ4~6Xo+El>!$vQa&E0|8x^SH|;v=;B{?>L2XtvGyT?NM* zSLBQ*yT4!M^MF?{i>Tdx*Wok8Gh>VRX<`+*r*76iimY05D>GLjB-w89?I8wu^o)XV zz=JG-QV<7O&=)P)Iw5LA-<Dn)kJ(7fr&PQd(22aVbkHnwLtpyhI0IAoRAyg!iX9;~ z&6u8LVjFNRV-rh>OQQ%l=d-EuvB<(YsR?jVEsBx$mgoJ2|3RAFQ29RJ&_*Jd{F%DB z&+^o2dRO7nay&4w!z|H)fK*XU!uR2Lh4yq0xa)+BPRv^;ueor0cy#?)Ok{gaNT}bl z!VQ`y_cCf9DX86XCV}n<OQ$AwNpsqj!L{K-Y0v3tqTYG!FxXIkI%hlUgkyu&bGpcm zt3eSaH@Hg{Z;aWrdtvEzV$>x#X<py)g|qU4c5mx!KP&leSHdO+$B=9xq51ZmN3-Ph zF;*})o2A{{<L#{dnclwtpZ3lNDt6az%M&P}$6YJfsB#B`dtZ%Ic)w}Gb=`0Q1aq|e z4#AaG;6>>QXT@OB)@H$ryC6@|3pNSC<$Ke<f!!1QdK{Fhdz3|6r)ITn_ht~@^iO}Z zWc{zl<2zos=_?ndN|prArY9qOSKc$`VR$%N9YJd(1`kLp4yZ;=JqD|G+~2Huvz?s% zc`ZhuNQPgvPX)G>9?Ps>Z@a6ynV-x&BB@`;OYD+OfTW(k&0M5)tJ0XaMHF&z$Y_o| zuTLb%5l_gB%SZHO!Yt?6b8&EWL_-H{(jb#LCwgKJ_D}Vu#y8YRU*)!k_34(8FD$!1 zR*E4$uPW1*F@9VO*g}Jd(6*TvD(-L8AtAD-v~Pv9*PH#XR^^(Jmwg&5`@$%J*`b)O zni4Og0Z@?cauq&RRDA_Hk!3_|-#15L6i2lf1^0_Ce~$c8KgI?aQDdxydz$-##KJg@ zTC-#pqf&pJbkap)@rH<%Ed2R(6v9(c_@BI7V&Hk-O&Gf(S$itlpaGuE7{MaJN0u5` zNVX3Nsc5(d<@7bK&NwMgHWG(;x6Hf7dWe!GSzFlS50YnT6|0ewTB?qSxzMu_)hXir z*pzKz)ki%#S5IMDkeuL9OXb9(OX?H0jtEu}vo>W)Xd(-Q<w6-CFJvTe5oE4mIL09= zu@!qVlaPfV+gTbvvVvX+l@0`dQXdm<lD?e6QPKr@h^83UsaP{CV)Gi=%Hdz}0kn+n zLjsXU-B@5SE^x0$Dtm%}sFRF-Vd8q*wP@*=y(1t90iAHQJ8JhV>uBbd+v|-T8)&cb zSnGAlfhcYg!3&>_nbJrRMjhKEht<7(Rp%C_fMX;jK^eV|QoZ5DeGI49L4WMWD<n9W z>G_$36C2m#5mNWu4+4v1_`>NU;;_7NjM8Uh_SG2%JWk?ZeQjOhS%JFA()oG4pQpYN zV54k%GhB9XU$k`%{nx;pAZa=VsnGifhYLhPn`<Zc{xF<A1JIGSD#{k<10Py2Y!z<C z@TC>mIp(1aU+?%HS`~ZgC0tzR3xdTw8UhZE7%xqU)4ws=*^-KwN08gYEJ=g|D}KH_ zr0`s33iA`>gfH|k*Ux2Mae!V=OJ<;^KEj56&&EAURtJfu3X;|K<6E5J^*XZ1Pwq+{ zD3O2m?o7=GEr<5Zw_00o6FjaD=X{X2i9NgI3$N*dSDtbqKUlI73_(P&D@d;Y&eK|6 z_A5CqQ(FD;0cRV3xpAMrXfes*UJuvDCnjLWN@kiKR#(^BIb|4EnEB{!y^S_`F>x(Q zJy<)hTaR{z;1Fxu>n>i&Mls%Ej;_kyEMsWM;fVFk9JZ$(wt^*PiI}i}2hUvsoq$kA z^0eczxi2L8j$gyXH?+PiU}v0#vKYgDe-2A8q}q}Wsu<t-$ICleqx*FFf}@AXo#}z` zbJ=|Q`*y?ii#ic?4*8_-Ixrm1_tj?kH6ue%SExC9ut5(KoF<vVq6-zjv*;s7XoT-p zvN6GoUBhr1-R$HcZ5#~5KXPe&Su+Dz7d3T=&SqX20Xpf^#((_Pnux6|eWqpqKQ|av z%hOqu|0^5kvYr(-+?S^Q53NR~;u8u?`>?x-GoT^%bOMT-iIT>XeZ%8IR2*%Tg4&B0 zHqM*XQY2ATvQEq8)OVP3m*j}((<&ClRidc@q*!q{6^WHEf!ULuP_--Z+9^==XiDm- zCH5S`3_P6Zj;{+wrUAjhwE>3|8SYW2CI=h~2$MO=A5dgpsp#7{8j6aLU2~-wX<fC7 z{;06n-wsUgRkZ&-rNY4RfOo2ecggR!!2R|%s9@0d5*vs~loaI<pnfIE8;X-NoUUY` z!NBa`oV6152+>53cj_V{Qa%5C^=z@6#YX(bU|&&9KVDQ-=iOds^}_qQplZ5R&HCAt zd{8-5u9a3>t9EnbHSL}(xvBp;ZpvzEwH-zqW69J`Mcq7e>8#=6Gh+)rHicGI;@z$a zAYrb49|^L$G(1w(@P<XU4Y}}T(vVwcGnKu0Np3d4>fw~&M|7kn<%A|<6dv&8CV{g@ z{;865P}3Hh(k7VR@^)0`T*HCrck1je^vMS~Bv$1EDXT}Q<cD-*?lrsm%D$uXC3@Eg z?N?g$+$)lCK><+QyD8GEVTZ-V!u4Uvked*JwArB7*})q=gFM%$Ld1`DCtf%s<}J`J z)~=TF4V7CzD9v()lh;)WUuGgeK$4jv@B4wx7V5`LY-CQ$o0H8rPwE}ERmrg?n4{}A zO26M;G?cy{El5CT8qiOl>WR=)9VC*dr;~bTrJA8pQsoF{_@0CAEaqH6kC<k|LOCyy z8yS@!1)qnD;)XYrPlud$-6-=_y&XmJDLHRC*0*J$qmpax5q+630}e?CgcQ$0-!fZO z<FVo3H#|K@ct=7kT7at-g7}YqWh_*PQ7}HsZ$3;3^4<oXBVAAVNJ4Ja$c!y_wT}IZ z{I<&t6?KMVRJh$l5Re8xvr6NWrtJvgyUitr`nudhWZ$)cf1c05ULTx?$IixV71Pd< zU#Jsk4H`Rhf<%_V&-l0B&A1!YfW0R2+OaNDz^sLEah%N!Ui7*2I0boMjxtZ4B9)@Q z1bmJ6dQC^@4WTixA;QX#ws8LgEuPtvSA;vv(Ml4HiosS_z;grtP5y^yiDszvj?zr* z=n?#hs!xZ3j<r*Lu=2~6v8cVx>9ymZiqru41TtMC6bD^WQBj}V*l|<#q3TiOn6!x- zx~XS;OM;4yUSG3nBv3WMiPaIQ3^($Grn3U8naw{n)*q@0FGB6>-Ou0+0dj~aI60W6 zqR$+U;9+q1mXm{&z>qPYuvke`Lxa`@pZ8xWakUihlEc(r6-02!2uegPylB4#wBi?e z+;0x5x!`<yXL#(SxoWZIS6%pUV2Z^7bwMvR0@3c75t7ua9SuP%dK(&yTB)25Z~16i zlgI%R`i`re4nmGqV*n<@jt>g^XHzfLVd?w2L_Jej<rdMYKdsNr>S^6!`x>>s-7VGR zjZh}C64q6oj+xoK%6ESL2$4A3Ne(yFAgXG~yDJ~uwWo*Zo5xs=7K{x_zq@d0-4eYs z_GhQq(d8HU4$k_^`|}^@O!6bz#qu8<S9aScwf&(wGmkCrcNCc(5C~m<O>&#xS)bq# zw|v^1*ayk+QSoK4*;P=$ZB*;7#?zZ~$O!+?GnS5B?1CPSwK-aqfXXguU4}QL)IoOr zRpSbsx}X^C8jHh8Sz^cWA+ZmZox9!ft5cXKsGgVJ{i-jzUtYc-j>6=awA7HjH%s{q z%LObGfo>qId_(`}=S_N-?$!<(PDX@UJ|D8>3h~NxL3LUIy8-_W8x5!TV7hs<j)msv zuA+l~Gv$7WgOV~=^TL$hmhL3qr`ke9ve;2gf);T=ceuQA04z@u=#9~fOr#{c&gQm9 zwYS|6=EvlxQ^Ua$j%1P)a5HW3dxz48Eff=106|)C??AJNvhc38siAn#<tBnYqi~Yu zhY=c4!I2U41^DxI;&-3k)JUwflXCNVmVQxZ(Nyo5WUNP|1ojL&7y6Cm4M}!o*(1A0 z+IN$B{VSqRoF>V3bfrF*PM$ft-|yQ+d(6912h5emMK)AABgv!2f=dLm&|<Oq+`%CC zX2DpXOdtuRR91Olf}I#ah)1Eq4%S4Aa2pN(>kduX|I&ruXzB9alq(X#XJ_}|>H6is z*t7rpkZ1z-(Ae5oC}J-}twsK;<;jnNsE=#?i#?1PYjG0w$s>;{8yC%RNT&!DvFh6C z+(%a8>@^K5pJU-Z?KUv+I}SV8jdp=k#0Gr<4UPz|b>~DaHcnaZYqA*Ui}NF@02(Z8 zbBc#y8{5aQe~7_Au<y$sEc7HOGwB6U+9c`l#;Aql$0(GttHG30=02@$bqV*lp7hv8 zXv0JCbw3Mb1;cmqzQAs`o>^^7uN&W$gdp%~$66~_-iTu~o84{V(D5p`k=7OUR0~Jo zC21N-@Au%}=$n%<t_I(}nsAgVix%^aQ7(PcBYe*#uY_(e?Z@cW(lo^VwBaNpDW{oE zusX@Kl5$(EV*8RBLp)KxIL?ku;+W^Hcs}C}#ZAx2vw3<yY=3@wxz)FHD=W2;`GJbv z3-VrH<TPdGnDNaEFPZ4~&zuI9AY*K=Zo=B5t#b963n&KJpb*W_+N<)jWz|3(u7rM0 zt3id9)ML-wT{4(zgD4)jp4Pq7$^L?DtI&%J!sJx}hWTeI58W_9^d6f9N!jfyE28OU zEBtMs*1*Lx6Zz5RZ51Zr%<)W<_th&5ZW_ww7k2jx7ibUy^9jN?{;;-lVKEg1Vny4N z2aK7!Sn0y$rds#BTQ<<+w{-5yvo`kpVG+<R=F#xa#iNoXuMR<Ou2tY@8ND%E&fO%u zmE$6HsGaT{9TYU>(E=X#>)q@DMp*7_wYpW2@G67FE3Cw_Ym+SG{ue@}+%4-GJs;DZ zGM|jsvbSNB(TxzI1m!mUSfZCZv5J)D3cpsyx28y3HQ4W|>y^<{x90Xu4#Xs45a*f& ze-WoP#3-NUt_MUCTk|FN9Q8g0+tk-rw=Zg3$5HQUg<lVW)>TMV?vB!n()*Lb$P9kX z9-2n4jnv~r8mos7#A9MkRXhzeH`K&wvvfIT{BkW=3XNKnMHH=Sw&aO}9v=4;2gw9k zTicOw^%um4hwy1)K^`h<WZ_pg7Ge^3tr}ITdsqyX-vD{n+NJ+dkHNxl?SEx%|C<B& zDWs5yz88Pu8`%O)tSub#^8B6Da$+#`BVL$02yQu*GBp+-n4hoWFlef%UuD=0wcAW) zrtxzh$F?w5zBI*N<LAtEK#v$;E;){S845FDqXV@Ywd2Y)zc<zjk4r;ak|r&0CV#FF ziC>5;KU5X#E=rz4s#cVCFp5HX99(VDjBjbHcKIv!B7>Sp9OA1DK7JVMghMpHPKde( zlwyG1?tIq2TE@aiacB40@0^}#ik$hUWKKl#cZOACg~rM)_<!v#fAQ_ikoyE6-@6`B zMbDeMN^~I*%_`M|?^C$j(VDwpD_VZdTRPdgX_%yiX*8WwEM*JAf;aTJqapb^xVbl< zfbEWa*Xq~gu46MzZyu@>ordcDa200r{xSmmy8P$~&|n5s3P1KVRSQ};&$G8~R|@!5 z-15doIohGST`rIF_!jFu8IPX25mY~h`ySlmVVfSs2Hn9|KbCd>*gfXEWlmjSz{bUn zblwC#Jc$AF^DqLX2h}qss2N>(Ax-vr8FyRDS=zJgdkV#wInj;=`V*WTc3|(S9p7&3 zs|_UmT<Z689(wCam{|#44(FB%SYt8JV#Nr4exgrh2N^~;-PyKWfM_)cq2`%>O9SGF z!z8Q8r*LxnJA(N6$^F~m3zsc5k8j<8a+iGH=mC0@AVOznD8jV3qoq@$Ai0bU#=g6Z zpKUyeM?on%9{c{t<x|}&ugFA&i<j7X`p0cIlMCmg;HH#AdFCVD1=qG!4nW1=DpT~7 zDPk*1;UV*!e{uhHMwWg@+3U%ln@zjj65GDB`#1Zq`2eQ*t`7D|1Av2M2pb{WA=BQ~ z@+4q=nbTHey8_2)OC<JB*k+SIf&al_IL4?P-*z8cs#qX(9I6Mrv~TtU5<u~AAo;=_ zWp+T8Ksb`le=q)zwl)?NTh5<#u^QCaze`T5Jnq$7U@WrMM%EAHlU-B#r2Xbdoq`%w zsVNU{b~bWOt5%gC%UTA9Qn#qf+}cXu8wd$z!;`X#@N<b8CEEWsPX66fWchEX5=~Y6 ztoIPjh$*FN*!k-e?6Nl84nd_BuaVcApPI2!-K0=HL%lXtt+LllKNnw|(E1j*Rl-lY z7~%P=Y)LM^A!+37z{$F-AyY<8kD-h*S@hrLW$W9u$<_q*?GZJDj>nd-Vneevl5jbi zQV3gP3o*Y5RTQkTVuU%n+7%2wDTkR0j<#8$5(_lODO_3+6fF}u(zj@RC|cGHC}>`# z-~+aWpT;)d^P>3)Cmni%7X^t|AuHhv+Z`P<2cCL7viS1UEP$hUoEFO-S-cX>b{uS= z)?RwBVvUj)#;Ms#>iHcKt|!t~uUAvZG_$1uEi`yXvax7V*W&6cU=Aw>3_<d2y+FUh zHfv3qL}Yxlvus77w-u;r^lfh1J6+^ZTH=)2T6wu%;zViY@@%QNt`~95CZxJB#_#r* zE0!mlA7b}<EgULIiJ`p|Bb0Xh!-CkJxcz!Yf6O1@oq*Ua)Moo4H;Z$ZvWGV6KDc8* zvl2=`SXztgKnh(lX5Xap<Xa(tI8s<JZ`W5fKhw6HEx2cRB@KE*hVJ|}O}}%T2wHT4 zWEh3AUzwpanwCvXfj6$tEBWg3NPGwLbdF%t4mE$qMND+>G%!J5zn^<7ZIJ`N8K>Sx zQl@`uR6&>LTO0-q52ZscNg|ql?11UK47#*TWj>V4(PJS%2@pUxgA%+2IqWu%4ab~A zDQ#!C=xqqXt(DA>uKNyARq}u9M9<Zn;9GW;KeF{-dm>6T7aokAIp(}0NUL$8L`0ml zA$|#HAmDgkIT!NY_rB=nq!p+g&$6ytHy_y-sjDPP==iSKMbI5!O}Y0XqbWizi}LL9 ztbo>444|NBTWX>hZyzn_cWtw=(0vV#?(Z@bzsb<?-rk+4KSRW&*WQysJ}dh?xY~$) zp>$uX-jK6t6b($P4PO+Lel~MK7dR3}I;SbXQ^-@4cEMIc$WoHMmH@`DOH$Te2=K$T zp6soKpi&glbf#pf4E=~Iq+`OWUm_=H4fb6Q|JL`pO7tpyT}pBD|93A8Gb32+5oCy8 z+&JJEz(I%yReKZ~_czc|(yFRiMgB1|ZK>#@l(%3Sve!WfQL32Lnwi!?(&d^{Dyrk+ zvhSnzh4pMQc-Z&!|1QC?=Rq?hLUMlSxwcNfG5i{}MZPdT|L0bH6i<|ropma8Dt?{W z07CeHHNA@6N;*F=aqUL`f|2QU6r=mHRo;jCBK+-lYF`ax^(T*ZM*9?OM4%igv7+$a zRk-fwyn|cTHw(~T`;I>5K+glwlQ85TPQ@Y`AUEt0$p!H$ywQvU(h5?xS$;-t`B`|n zP*-M3(zPZNm$-h~wQs*HBT_C&A@mbEQy=E>KoV4I+3~T>AnX^=cPLhXlML0=ef5o< zZPqcL6-7>Y0-@UTAlm7IamRF?o9DG`)gZF(OaA@1Ie$We8DaO8w#I^thtkI;m1Pr( zHf~~*%`Ec=9>F$Rf^~>`2K_{#hl;!Z+76$~bfQ>i(<;g~?>#B|GlVT`&&gKUR)NT# zyNQn;Lg<&LI(#!^q-{qW?4rH~L<{1K24*ZZfdDmNG7Q%rjU~R`b5<80q{g~DFK8DJ zq;B1S7%ck-dUwN}!qVMHyQWfKfgM<OKd8oe10h706aT8)fck93t8wL2AEFq!&yIo% zpdnI>bOp@2AJPkTV81o48;KZVyP$)IaEZBrH_ypqR;>A@rxMrX_o*OOeFFsm!@sP5 zi@a$n*QfqFlerwrID|f32J-**ATOzbos<Lz^Z!8O__MKNy8N2ggI(~J)<6N6^y3!; z3O3HYwYeD&47)VQmw(s5Su;WR_GSWcQA(@zs%2LI=hgRxmTS)$YYE1H3$1NhljEb} zh~9$zwZ`RG<Q1U>Y|-y|wmHAB$%*p}f#N#Q3sNpx5tRMpAzI}1iD}~APcDZ|x~HNN z;sfONg4z))N(Bu{WAsuJ<Q@DO4jHq1&A}mRVVVS+Mb8}r|F22tLwz5O_m9l2^43@0 zKpEw}+&cGw;Y)Bl^j{h)X+OEj#9g4jj*QyXH{B;qnur)of;DD-!@PhOaPUP6E)QuR z?knX`hTRV(H48cF@fs&tV=zcrWyIwULT`3Q9M~zkgo$9PZ%+`>ia%~sNL_W-q(I*w zg|!J1p{%CZYb2*Ij91<Olnm)iXHl}uJ6bcaT*PCvF;2jdOiQ3l<90G7Kh1ho!^-np zYnM;%s_<8Zlp#V=MTEcPFQF2^SyEPhvi^KVvi1rUjikY<b^V0D$`t-m^hbxQiae?* z#X(lc1%ol>&lPVS1VLBy_dseLXJks;0en$ZfTqlPQ7M81HDTqKZ1OsWor^g&dd03t zJY6Ahg_eUzB&e8jBiBBrjV4%8KCA4~V`?af;M8Dh`%=cRAImG+z4eHG-#7$S#J{c` zSC7lGshgEe6kOvIkC#7znBa?mc2Ei4(3kf1p({`_{_1mT_-LuW->-#EFR{yM>7Oss z`DC|FXqtz%PRPxeE=)E`{gcZ$;nOL|J*yqQpYLVC5~B_fiOtH$&pqV>{f)0Z8Xb4z zFUdj<ac<weTKJ1Xzq8Le^C;N)$XS#RKlwI{#Pd!A@uH^7+blA%Wz2lVvM>dm0VvIa z^3^xz(GSwq&hrJ{c2W(-XgPH2_O}bb<bBYW-XdcU|7`AJ(R~r;`z2D(4tm0TxcqI) zCU_3`vZp0onQnsu8zxxQA7#Dcggn-!Q<(#uZY@bJtS{S{u6QUSP^Z`&w&MlQ_#@=! zaFkpl(<x-Hv9i!K-tmikVZpMuT&F_&WR+GDvPxyE`$Dq2F7hB!hezY&djWW@R=g{W z4>}3sgmHRp*_9q>5XG_UNyWhgv1FesBfEKArQU6^AHg=nJOe1vvcIsG;_eu9zQxX_ zFbM?rh^U8;1YTKc{!vg`U=1XvtLoTG8%<(;+saj*{)=Cv7M4Swisy<=7qYgYW=UNB z*gN6+>vAhO&brD442w-$5N0eROIkd*mVfbD#K=fV8ga#^M@X8=lox+WD(o>DBqCnD zgVjRC)U7G(Ba74=u7Umbi!kl}GDL`=ZCa-|8%uhI(OSV=2|YlhecO64W)O7<3A8p{ z?l{wEL?2}2<?HdL84#(JXALIu0c)h<ve=$e(0+km7}|aNB>I<YU*Ts*p-2fW8ATWD z*#CaRtSwXFkGDgD`2ar)wIrvEXsRI7q|w40FmVlrBi}YtsCFcCF2F1rtWMw6<9e7x zX)M5g-cG0li?*~bk`@x`hvR*fHXlH1>xjcwjN&AkeIR8hP?hp7`*uyUA#VQzqm11J zL8eiwOnDT@F4cxkq#Grtrbx?we!iFxM_{)#!n<LB$bdEp<x-e9s~oI9P>fFq$3k2# z=T3Xgy?>4dT+Uha9`^7G^L{11zHcg&-h#8iRH6?FU%3v`M{)AFQ0CIrzkVlsMTxZO z=GHc88>!D4gywZe>=gzVJbbnZzq@ALDc8K*);V3Or^xGT3-~s^4<m7wSu+S!q8(Lz zM-@i&1Be8$+J_uC=k96eGEfH`Fp@s|>2RDd&^X}CKoiKf!6UO`>#;NB%L-ts>F@xY zjI~u2g2Bd2@7Wl(mk#1{r%AbRQ&@8eL5-6-Plrrb@<-hDT5isKK?If%5&Hc^ml>B` z-3Qzc(c<3Wj+Pw6r<FCiOxI%4VT~Jx*guwEvF3sXcyMVt26dibh!yQ__kP>AF0ZpY zbIEjnE3bz;bYjEgNt2Lpg*mfZb)LQpW9FdMUMzhCEc16yaM$v{KV$_MloS@8UwL4> zu~6_{BStL%J9+usix0I@kV{JB+x|JnKa6pFr0Tv(C-<jJxPCGJO876#tv=#R!Tm8G zuG(vT(|+r_<rx;P7o-|tpy4Ld{RL(x6`|PX?@=y;he90Pb9cKfNRD+oL09zh<rQFg zb5_H)0A&pFDx>>}$a(!G)usQj(^tYA;c?9GLFBf)dUgj6rc$4=zU5mN^KVm8l$v&i zJFb`=^8Fn&GbCYRoYd*sB<hR$qnA5B{;|g*;_94CV%PS@YD2>n1cLiJ4r5~|`cqk2 z5&`aQk+#{@xduhDbB=TF_nDK-Ckj+bYuwdg4;+x<vD{o2%`5%Yc`4JZWIvBm3}<N% zpr^1TTXuzpRFzDvTBQm^TW0AjhUP7PpeC_9MKnqoF&$;WBHD;~u-GvYp(SK)YNKZZ zMYZIpY`>$2fiZ~~S7${>*iVN=3n%Q@mFCg<cWsCW^bBOFHS{jsgGO-b4)~`Kfc!Tg z1w(`n3K=C@mfWMf1zSib82*=<QHoU_w);bDA@7G<AE5~&j=aoLTF@Yda&%B&rpg&t z_}JT|-SrlcwBiJ#tkOp7>|nQ4gjVc~Zl#VUV)7M7Zm#l#Eav}1*Eu!`7B1Pk%eLKR z+qP}nwr$(CZQDkdZQHJ?^WnygnTh!eJ0f@Hn`^BnqlOGZv5OD0Eiak%^5A3BGRZ`E zebmyZp<zGN9n1tfr6d**!r$xab`cm|=x@VPhBx!1HR2rqeHeCi$H`Ys13MjOq+G)U z*cA3}MkDZ<zEqxR#3vUmm;?p6yRVL&!R|q}FA7u|ZUOwJq@%Q~Yvq(!(6H}b%Eian zO=*L0ov<a%7(1+aab$w<R@6{-;mB92LySU<|KQHo<)%$ZpB#a+Umv)yYx-`kc$<b< z-inm6hoa4NozfpQd=y>aBGvvX>L&{<Yt0rJl`N?>c7u}-OUAYpSx!~@3u_&;GR$61 z7ETlYFlH4;cYN6y@Xar~Nx2meCyhoQ_PEA(NXCEl<Ts@+Qv~OntLj^qNGeA{|72`& zDiY9|N~reG7M6A-7MbAtI8v4LFd^*6HbuP&O|nB9`_F#obQCHkMtvACJnU(`-!M1b z0alH8IOej7kp<p9hliB3bk%$$_gnVXfWP7?P6I;ga-Xir*#YBJTbLtv5xa*xZgwr{ z*eD^-Z$O1mG1dVECnX0<iT(u`;`TiEHN};Dfq-@i@ZQ2J1i>}`@;2Mq!-mHP6ZOZw z`R5jB+9Y(g6YSUDJY{It4iYNU7o+krtL%v?0GnHu*~aHQXSrIPEbkt9?eodKH!SaW z^=C|k65x0gWpe{yX5azMbFi4FPVMniRr&qzhib2qyPG}vlzkiT=-qX@@tj!Gbgk~P znf;}jw$P!<t=i{ejh5U~g{I}=2DNQVeAMQ@eI=FDL^|_M{X$ujR1r?4ub4#t(&-Pa zW4P|s2bQRIKv-$o7b~0}Pw2(97pq<E)B8C&TH@Ym#lO`m?^!{E7<0=vLb|PVk>)kc zx|c|%pb+<7LA!%>X+6Q4!d!gFCEZzGF|KElvrjcY=WZu!^46Bu+Kp6>H}+|}?|D*J z#EPN1c&zj;H=cITt974h*w)uf2WXXUeN|>vEJ+qN@yf}tjL6dm9MuXnb;@KH5JIG0 z-V_o+%2U$@U7MW>Tn^U8Buyyelw--$cZI??D*Pl34U1%_>ourp=D`9TN0=t9254$k zbpuE$mvalHWCj%FQUSjqGCa2-FZyg`<vCO+69{L+m^@3Wn%l6azmN~bWxv7WtS@qd zh;#!{1kljnu~UQbAYtYZge|6bc_(_|=3hvH<Fl;-0ha*1a!nbHXXm9Fk-m!B1p-<q zlPX>JZ}yrXC+)TjeS(fYco>*qcsW#k2&qJwz9Ehr`L_oPXeiN>8*=1F_M*tQeJ!6t zY_;!1J-ejehS>;9o>be%RF=6mbuI6rRcloytw|EU-eI1Xw<f1oDl2pd_X>!w5Gedr zKARXfTACgP`}C>^3r?PsR`rH~4Ky2%-A2KDM1mo812Rlh1fk8C#~BfJVz;iq<q0e^ zk`x0HsE`QH1GJBD_<5=r?F&l}B=Et*W;YdktnDuJxp0^%KM>pzsr9n#y0^adk}iC$ zHo8ulK|nCP*21tO**rUkT3L1VVRcB+3T962Kalv2E8Vf+@;1BUD48$qEWGh0LFyh4 zNKe+yDSy4Hx_|H)UwLY<y)epMA$MefgiKj5w+Hzy>Pz**1Hi)tPQb=XIFVkN@7MUZ zYZ5bMbm??(8-{y#A`rtHHRuC{W%~_`2FiU&im33*h<10pbPo}=QnrL+Ns7>ixga>y z(sR6K(|mOINX19vH1*jV{MD|4h=_^=f(8hiV`%=RlzKt0NC+RNNXWXbNbnTPKs5&d zQ*%+Kel?txF5<`jtBBQLuzHVApIOn6;-WjjfAj{6c4W*nGK!H7v6i<h_uc-AFu&pC zvsx-rY}Vz`hKc<n0}up=4S;_4x#o9>_N80oo)v05jjLV#%G?aob@fMfU0;dB6I>w+ zdDeuo)_uiiGxu_54d1rr^j+wo@@rz}bmwhm-H?v`_E*0f%}Ct!gj69G{76*ShW%yW zURubT?;N??^+UMW_~+53;X!=a27HN{<p4Sc=867n4BiMNuJFMQElW>RrQTI9WLhmu zd)~XF=fu^c{%NlszYoj^1V~n7z2E^QX8<fp@88eT<ME!vjyj$_dAA_PYh2Mddm16n ze>rD{g5H7(eeN@h<ut|uo5i)$pBa**M#ZseJ=|Rs_M8sO#z^R;XaA|&eXw#?l8K8p zOQb&L{XErss?<=_Au{KGHGSM}amer1a+~?rOp1Sk#>u(|VO^ww6<@`?bu>4vL6Y(p z+q{|#_l(MIGskimJ=>b1L@GI;ypKHLZ%-Ok!@+EYR(jnr#!Mw|F}g>AN|h38@)gyh zFp3G3wqb<#&Z&YDe<ul-fN5kY9Fob4Ep35VfQp=&-6|H92(cMr37liTn_G~In%ytd z;N6u>{0<zCqD7C}+NoSF0>|N(FQQ@anBVATw2mfDm*plDS*9$G7$i<d1sy9DgC;J; zujfzUlDWK7fE*a2LC+dVgbu7oCdc~RsHQRReUDLc3v41rH%5<e?SYlwt|87J+CJqa z#8p6vXMO}(y&ytkF7q0{?eok)j?++`QmG8dA_0+0Mao=jI|BCvRhKA<a6IebzI=%3 zPxm-Q%h)2#%ZN^_=HZxW0tt>+9>zV`<BB04?#{JX9W@uFgy__MpnZ_t<M3WEk&CMQ z+SayU+6s9ViACZb-O=s6I$t~}=uL_Tr_<$L`Vd0M_=20=Zu>LBc=G9j4IAEm=1H@C zv3a#5PY(8SsKxb1(c=b>>A+|u49#e>!owPtniG~f_hj9)m{rDC`{eij+u~^S4zH`2 zZ1vl93~|<9bxW~tTnmSldp(qKb&1%fc=8}XByI9hl(k?>9gQg<Sq`CamIta`fU6v& zqfR?YdqwO$3w4cog@@D;+#2<;7CL+f`Z@g&0$4D5F&1RwC>JPgG9xOckrRZdTk!~f z-ws*Yd+AJ*xzQ+{T@(O9YT!05TA!L+3R<COYO%D|MJitqTGwv(Ws$ek=HKfFD-zoq z$Is%U*&ir20NTAh<v`-fd-fZbOebz^?ufY6!BB#ZJ=1}y+6_6XQ!!RaDd_-?*Cx&q zZ;QK=Cmiaz8(tG>X=&ZG*sx39ch&4g>;si8aSN!p&Y@xcx1Q|}k`|k}e6To{puV^J zB9pZ+*Y92n?5AnKu(SE1h)%2bcFW8iutu4xb6-4ETwvOlGE;PLKhdt2>(J<`FGI`T zbPw20ZlEd{axctMx*yeNW$2?sWIyG3{h3q_hgMgr7%{U@VrW13s(CUFJztfw(s(7H z07^Q&EdwmFp=g>Fy;`cAZ)IPV-3zq<0_z5cGr~BmRXNdxV5a6RvEJt?Gk1IVC;v=5 zb#a;wO-{`9uLliFowm0O?agez#@oOHnagcvnp04vrPu?IrsTxLoFaXqWlHBO=nBV? zm5(SyZ3f{v)7^#Xe-`$Gy}{e_UaF|+Xe-GzRcfpPbP0KEP!1upW1hn)>n7^v=C?Zx zq_qYC&uxckRdJEqKZWR(flKZy+yYs@i}Nz4)Q`~|@q)jo5<ag8A9Cq$4+3iPVbSeM zpqF>1B7gC<kuA4sh>-LUP?6*XtMy_A4UrW2bYRgnXu{v-P+L^LfS)o@i(pbI)+FC@ z#9_jAtr#<c#PM6TUqYsuY-VO=BqWF;M8w@F98_a~OnR2_z<;oRD5$8&$5hK-|AAjC zhTQ@;8%*TUrTS|1v_7?lQ6$*KQ!uHI^3hkPO$wtVs+1rdU&2Mm5ut_|yCFY>OARrm zf-9LgJ<2Av%BuUzk;G3BIdDl78%W_yd6VnJg-;(DNILTWUJ&a3oPeCZYY>phjTftj zRy8LoxCeAtXZ;gDCSheWPKuy|3)9}i7#~N=dXfnh#`l*lbxw5x4c-I!K1}RyQkbyG zu|vF)0Syb<9T5Q|hQ-KLEG2wKrucMtFnhTmMK4_56USGHXpR~Y#qENR`tsr1b@)6z zi}vXIHH3COk5%qY_1#uVEzh0PQvC;~m*LBM&XXqQao5`v9@cDIbvv8$YtB%0UG3LA z@fPf7%faxYcW#L*7iW*-;U!cEJ{+Uzus0c_w>Z+z0i(@fR0qJ2but%q%3(0nUmalA zVmtNQH@USJunLpllt8n+QlJW1&Lg~Ks7BU=O=jTbxGwmF!Iqd&izRVz+yO3Egsrk6 zCVd!yu;&K(68Z#49jaevVoGn6tU*Z3u}RQSv%uFC4JIVtrn6Vn1}1T?ORGJ%)1`id z=%O6$YT_v@^Y8sD>T_6DE)4d*Wb`bvA3YxJB?#XIW9o-25K!O9TFVQrZS|iu`N-JN zAoUON5t$FxQp;-g&1vTQmExDniZ350MGwyL%js$xn^Sw+sWC+xRY$NcCZ?}6)gMin zQdRbAwA}?7@Y=gaOGdX9o*(trDNb+30#M(sR%{;Z0C}SaFNdk<EPF)ljGf!3XCS(B zTqX&y4_Y}&7>lb;j>qd(lJX{FvvuZE?(c18Jhkn6XVOZ+YKp71127y7>*{sWjiyTE zd{834i-{~2!op4-e~lYx9G$~wuh-^*XUD>t6Qt2yakM-i0wu{{lX3U%YoApxJ8ZrE zHN)!XDgvaEWnLtele2h-v&<p&NpNfP!Ix7hLm)#4RD?kR!0qLmWvO0Q%ee%kKmmgj z+IBGV-DTEA{i$Q0nbBkDO||$%dH7`dOce2<V*w2o@Tuuw2aIE?dNmrs!X(ODNqI`u zl#@tI!yZS+TB3rh2G^}DB-ANuK5(DeupkA>c0fjrqV47=3|)Z-;$snF6Q-OoEvooC zkf~S#a8#Acu?Q+I%t`+OD2<_p870Ad<XW+x)PS1w-ys-HP)@J}B_s(1!?!_<EP<|5 z3aJDUH0!tM^QckH%Rn6yaeg5tk=;U0qeZd*LGLw24)_#I4oBiO4Ls`e-UYF%LGv3+ zIg>>iJ%j#`AjhJ!q5z%FL2^WV4wuD26gCn-GzOoe3WoYZas=p$c!>-<y@Dt^(XR=h z(fJLV+};ER#^kA>FYNz9=o`YyBFPKg?1Nj<gk1tO^#7zc@{+wOS1f8+G@<^UZw!vG z3DlLb*w*UfJvb^p7y+x7l_|kKK@-Uxivqt@8jdcCaa#E&T|9M)@}3L6cAu~ug#CO! zQWyYFRZiI5g)<eFtrVaur=sGt!t!h$X}c^?IVjKzjk8@8UwH?5^-r*{p-&cKoxr%f zQI6s+0;GN!UUT6>CGH7L*QOsI%|<1@^Y~$51TLm^6JdQX_TRT9BNi)!PUqpjQy0@1 zn_y#7y=i=O3tv0)(Txq%o-~Hb(=huzAX2<1ZCB^WpY%?~LECSi5#uxZ(&%_m?^;kc z(2rK=dz%Z^+CZqG{*Zi65mvae9n-JV4Y|DsFx(=DUBcSkLU<nK*OX;q8k@uJ(wJIa zCik!KsEqB$YoLp)6#_S!pbaA02qPTgcFpj9v}7h40KV{{A!6j%)jAtkT{@~Tl1mz9 zaC$ei=sSWdGsD0XDK=pk0~pLi>KOz`L2y27An%>JAjn;W**p3!<F3iuu;=M{(^cw@ z{BHQoAkgl<UCKOfshUk;Az+TaO|H?weN8{%WkmiK+VO`Y48TM6N$VZ!>L(M~>LP0C zgq9YG^`+<Up5Hdch=}W)+vvVqwH4EAU3=lJcQ_d3-nw_HueN;s{)Kz9?ecxw^^j>L z+tvXo;3^P_S-Ba?omIBkEY`(2in8q)AQ^cmkArs|7UZt#(AgVwJg!@{jEC{SRyj(T z<^Vzh>r-;`Na4W_opozB<c#hHCsOO)$#r^>)Zt0GxVkcb_d0V`HwzKs%HDg64IMd~ z4WIh;kt|hv`(n6RQ&ti5itA5aPj|==)dQ?JGq{;%+pmAK9HMonj=k)AE&fK!|MlEe z=6D%ky^f&2t<X^fh+`ch+Obd8dS9CPEGgCr_6xdL<DfZp^8vj?ciib#9a^Z9CEe~z z(zm2YL^Vcn8732ORts3rUZ@*V1Q*uIp`7x+>`mAO1N`mE4a828tzZwwo4Q=RRF<a9 z2a|2-F!DLLY1|-OH7G%imiqd|N@uI<2_m^ZQgwa?!6>-xw2teCgXPLn{RR;zDsDp) zQNPUGw;ny#a#d*Vc^pNo*s~{n_hFd`BC`uq=2-gbIsPc$#R|5w2v2Xffu?~pa*@MN z=`@uxDf)B%lBnNzEELqYk@&!=(|m9+cwopi88YNdVlVhG;lIL>#sY8#7{{?kl3VOp zVZ@Y#x*QW5R9PhCL}6frV}=nzijf&#EjhfBh1rFOHDmi=8m#U&efl+nba*7xeFVp@ zvin)Nzif=UK5|N%G>vYDF3N=)yBn2fE2R7J#G)dn0F1!|yGZ!C8=%1D;JiArA8wXy zdrOZP9OUV-E0ahLQ=>R*;FD%i_L~0gZQGp?`|(;4!97~x=BlOg^AHo8;p-Cl%j9IK zgebqp;u$#s0Tu(n4EO_~6bl7ue#|&fa{qHG*%r50GTGWG=&Ho7-mR1}8b%r>OQiZu ztm7z;t;YR&!9;z#_A!ws0jwon#=hfw^vX!jlfJv?x@WrA?0~qjl?|D#AMd!Gs(MMU zTAtfBFHWMvRq~a(HuZS%e+GE6u~J#M-nJueI~N@{9Ixh&cSSDbxfZ>?I}}IWr6+it z#J(6FtlC?~9!EL9AM4M;T5OYjre}HHi=f#(Md@<sY%*`j;>T^n_GplVIoL#zwVdxZ z$#+ZgVKuQkr7?zOvhGSmZ#DC*4#~_?<UO~T&tH0Agg{+<B6*QLG^!Czz>Xv8BU~Y} zn&Gf5;XqR4ShgSoslbp<8UBd1{Xb!XWdd9S7b08?Gy_6-d2Wy0D^<loxi=D{_9q@l zK&_VC!-QN5$*^Ji{(iV;Vc0D7k(tw?+54ydHi5Ihw<Y?Q%`?Gt!86fZ+-K4$4GU== zyL_gXZLdbsvd9Hrv^U?+MoL~-S$)~sZ?<|&>3+^nP-OqUGF9o`?=54BX+yGlLq6LE zx(wP}aY0Si4s;2n<-{GFIt<x=-?5|RkK5iAhH!CqBe>iIh4kuLKPR*RJ+;H>Ak?i; zJNhgY{<Fx!F!uGb`8vhOHY@?=!fm_r`GJ8bR2iOz>0o|Ysf1Oj#7f#wD47S{Z_9Gh z6!!pqigM#M_Pu{L9=|BnfysHgeW8EBWMxxnnY=bBtyz?Sq|I$neq&ZMyDh0VvLgmH zg>IwTC_TSm<}P&Mq~&S$^%}UgfuO0L`8@XFeq@hI@6sW)EJ{i_;wv>PP+o8zt~273 zC}8H9^wH`?|2oLfJJSMFW#t;_@N_0P9N7nPs)5Df8XLq$J1QU56q6VEWkyd)<;%@m z6%E_Q5I|83{*F~`bvz%Y^$&yw4Nu+9Q}<Jm2~a8#BBGL1r<fEXl`t}NuVhoHcxWb( z>|y-hJd47JiNZ?Z=D{(IhVmfR^rC5j!zvKN$Q$S)n4-f=qfSE}alh^N&6H1y?5F!P zTyz+z>OPt#Sxo|#faFbGL%#t&yzT9f7zvdCsVP~G&K(6SR>~ma(7-G>m}CSxr%oQ0 zg+bj>fS{X;zPX@qDh-tScKS3+72jhF20Fn3Mwry=%Zd$};b305re2J#_@!(LWzOn0 zu32m~EKUxO){<R&R9Nujr;^#}P4}Q7(dm}lqF{a^KCaGZPETFxMuYrFMIv2>I8|*d zygH2uX-OI)&eT23EV?HRxs9UtZAE5nne%zTt<<y|Yt+^y1b1oQQzbH6iRC`(>cXru z$$0vvIwNPP$7Jemdah(4_#B3yL_6<8#!UzdJ1Z8ZJ9UkOxNs&^wpynr(~;TOeKE6a z^p*|Q<n){O`5Ta`vQ!gqH1rx23m(X-e)#%Y=JHyg14{^iUjUe2;q3bQTBHa?NvY`9 z$oVXyvoq^H%MPg1`}4wq)_P!)^L3f7?wP}FdCgtFY#5upU7AvfnI=NH3Zm<9&%S@) z*}rs>Ufz0=_?I@ZuT}OFDXS5dw!7CQV1Gh<y~jp7Wp-yHefdItCFizc6K&m&7k17f z`2gXF^PlAMif`ukTOzy?1MBFFN3Oq4=F~?5$8jT=Cn<?YN7)AGQ)eEmRE|`6F||Y6 z3$bM&9V<bVaN=qT5!PgKSh85dT&B)@^jQqan)piKEPRI`H0{%VAxnL$(0zZEFw#@P z9`VH7A8rpOw#JfAOE6C1STXN?HViz1RC&tgaRY0CYO|T3SR!_mQGY2wL=q-CYf<0e zST;O{Y*83db32!FS&RB4tGeuEGv>F%qc&QV#0=|`<yG2BJ2my=x`xN4b%l-OC7Xu~ zB-0<VoQFaKcf;|LGPSL+49<@o4$YVBnV{xmyE<@Ow82Owa0ow8PrCIahvVO0GdlKI zzyU}eDqy0F+s$}ru=C$H2qTMK1%@=RzMkUm(Gqs@8`#CJY&Qjbn>~~l5Y;W2Oq48E zYVF?bvpu3(C@NZ~Yh*HDXDZrr49yjMot2h`+l#H;Sqq0X9@6bjs>#-k_cK4C*MQ;v zQYzkRNU<!{v(XQnAHE>K0$dOgxx+usIk_I5|G0FoW5#ookLZb|bvb5kWv0I!w>xh% z3he)}zmD#<!oIJ4JI;N<@a(_#tpY8*pQeQM3(glRF)Nz~B`7hg7$g+shiqV~0KNiB z#SSzx6_-t(hDa*VGu+<VE1GDBetNKjcVG<$d<hdUblE)d8Uz`_^%}}iyoaK<#Q9d% zoPJ=AISutGd{svb<l!yG8^$$#p?r##i=55>1j&0m;`xK1%XtX|WNC3BwY8_x(TA8@ z#uknQf%oQPu@Tzy21NElV&xL`;h~42;wp{4a`D9QlTFRZMG;6fiQtV+bcLlcVCIQ_ zdT|9>V7}l5YJ-1AOqC<p1o46!dN9!)jm}Qe<v>lFtR+;les}%?3@RG}WB6k8-2&fA zv}&tKZdz*Z*=bVjJOoBy#`mGU!;*q;$!`crQaP!ns=a<iG!>1WK-HMPR5+o}@42#| z-E?Whctl&kT-I9$>z>D6XI&6^kalI4CtHUte`b4-Dsy@tzxCl?-sC;TyEn5!G1O-Z z8@C?23sJTPld=aFw?WClg1N$Gd%pH4A{`nQKA46V&Npr(4=oI{I5syuOCl{KBFv|B z^SHbdp97KkPI73xcY50(RFs@A$v)gm%CZmE9LGg?bMS07<A(m_a`X@@or}he$$DP1 zD1N(0);yy{b+Z`tmA?@4Fbp^@Z<BK2bY$UZKyMj+aI2;QY{*hKNc|Ej3aDHYc{G8Z z${PG&>-EG>k-t>}+jBAJ@q@&(tH{n(hoVBEAK+O6$Km$`k+TV!C18HwO&%!cyu#rB zW<eyw!M+mV3qCUU=JtEVI6PJGqx!*J))k(idBbF9!KQu6vv7Gn$;ASldxv^#ru%eA ze}CF&*W{XL9c7=MujO6@eO#C}EnioZDaM+I-32b6=(Td(UH2<p*{SJ5Oj7LfQ;A_e z7<Rwf_ySZ_1wSd<k>k{;EuN2|kzwDmbYK*CaIQY#aKZSA-q~@Z*boQS<CRrKc9ZDW zR%CVWaJjoaue2*y8(M0bD0_Fuy>2bGEPbd|p9~;o5*LSLp0`em>2$GOekX$FYkDwV zaI0}frTeq-nt&RQ@Cak8>t0v1j1oGC*H2#>y);(8uk>QGp|l_DQ8Jlxl#Z!2sOy*I zNtuJ+L+zdXyp&^9G$YJCl1WRuL(r#Jhs5?<R5<Mf)RM^fFD?<86Ji?ig#$~)wv8Q! z`!+Z0>+wlOEfn&O>{M6!ONl~LEs=3!!u}RR?(Ppd_W<S}yzqs?0|X3C6F}Y_XjBqj z?QHQyHh5|bbyjJ60*e8dO8lx&jBz~#APj<trMWao?Wu5h6JY=kqb<akgN~6E{qd1T zh8n)1)G#)%^pArhq+NWO4RAcf<D+5zu-Id9qYo_M1Yq}9VK?9)Fp-4Upm;J`4S!T0 zCe&B)rylNeE?y_n6&_Px=MMvgU%h6<mDa<3+jcGob-M~Y8ZwWYaP#e4w75DP)>QNG zB}LQSzXR{|Eue=KoH_!lb9XC0a?jJLkTs<#7qkt=4n^<zqz0mT3#s>M%JN)q#kYHl z#qn(E6pX&Eq{H&J%}h7z${sVDlQN}`E_*WZ4~UvkhZqV}ps628(x$Ftjej{XRC>E= zocLFzD5e*$EJ(Mir)ns*-!!?^|6^M%Hkgn=`F5s3OVsBltfB_mXtg_*dIna$8Gf1$ zz^UH1)^#aKE~tdWqS&D|uTfjgqOZr#I@4srI%E{YU_{Q#p^K@lNx;*YF>g4!sXO|- z6R4OMX&8@sDTT!l8{7<YQ}{Pv6dZ-}RAHbJln#SrLfUOa6#>ly6D5q05m1}YhBRy* zrfen*YOp05UZ3iQ`oWALN{@~R8j|WGeLL@8N6_$|*`|rl6edSwA&c#Z$0M6nANSyd z0OZeR((jLHM=&{6&UcDz7>j$pOh~!r`MBnD8uj&T<&oGtRGM1FYb8HQ`RoEV|IXSO zIY6T8jgI_wb&Ro6h{i=~#V9(8T}$LALL`O@ndY&n$_f1#$ftL%==f%W@!cu9!p+t7 zcKodz`(!(^xrY0^0Of)_*k!V+w&d9g__~754Fgy#uxb=<r%L?X;If%>Nqga#Y5Tg2 z&3p3Vrdv`=Kz2j3+`iIqA~5nc2?7aaXvEqk+tiHkdO5XdG6c<0L^0;Uz<g)YSXsZ< z(5f|a{W#z8beAL0d5GEiwZa{@3&`?apA=t*Z(#N)W{j~WmLHvo<?gRfR45vsvCil- zPpHy>l2jmyOkcp=1_M|4Xjb;x>C7B=7Uo}!Su8r(PsaU@^ods}T4eAFLI<~Za6~eh z-^M<~mS$St_<n&YRip+xj%_NN+&3i^O-4UwV?b|cfL$c&MKtr9%^h@Z3bQcbyPO(A z#F1h354J~XmI){j4cPn?*aRHd3^2+AZzK?ibpwGA+&>urfEo&|MJNKIZ3Z-_%9!dc zc^q%M$=KY=fYz><>dx5Lt$ry9w(`9fInaJ~W`~1{Rx%wfC?bvfL?)Qpy`pS0)Vh;v zybMIrLWSF+$Zm2{-tIaIW|*w>qSl*CVk?GfNA1}nh1A!jCld*jV8R{?4ql==qLi{e z6Apoex_oe3?wk-Eh_Fa|ZnpJNd|~(N^tNloaY<&;9sjg{_8EYs|Ho)m0zk<yy+++& zBDyFQ^UlQbIoXysFm4-JYht`DVZo6(=f%=~Y9ceW^&%>qeKO_iNP}`+60kW#)m{CT z!ed7aW_0dTQ~mW$RxiGvca5%ou|e)_HhHCOz7(0sBlEGwQQj>5Df%%~i-+n<shf%x zgNv8`_Py0`6EF63yH6pzhbL1u2>P^IU_-g>!dP?jPQ^`9_5yKE{BcY-iLax`2f|32 z;-hVV68;)8h%E-=OnJ~JmQ_<0592rFMQp7q{(#2%?iwPL!ZgqC8HY>%QZBb~M`j4X z#9cs`B+HROH$N0+BKFuCIBuV39goy`XryyPUjR)9+ZK#(V96-=@zKT+UAow-ro8J! zvG$|jHdb5~<Vf!>TCh{-C~}&#7u_V2GdY`N;Oj80I?qy;N$bGMUNlKTp-zkcE^c)f zFG+KsxgUkH5py(<K(eZ_6w0*qDjo2W{9Ijq#jUYmzN=<vuG>0EaNzOk>Kz+fI`fvx znPXrMDRNwQAhEwkO6=-vk%TsMh0>x{iZ=GVY&FHoxmX_U(Oh;W2Ghba?e5GnszAV! z?NRtx$M02h!F;rSRLSh-j&=_bh6q+KI1GO#-w^@%9j1wm#K`_T#3;$?W?8iV<cYG~ z=sOZd$$Ky<eQtI9|7i(b{0kcJgiazhB>Z<y>NTiK2*pqK`$O+6{oHi>009AU`(Pi9 zc9=8Jk62JG`>{aUw}wQx(o{@PWvy<e`worF4Y{%$S8$5JYXGUDIBI{copK7I!5(F* zuNjj@!2Bf4-VX7!hekjs2=ri<w0w*+IZG<=Tn-Ue&V+4tkoc;(DGq)cBdX}0x{P7( zL`LtFc*NXxkfr>693ZfNr>;XOoV&e>cPCLizJ<H!y-{mAaBZ-v03E62NOOMT?G75x z$eVWCqq_U`Xg3v`Nl*<p;>$Cf{<yCfn2Mz(2Ie&2`VlY{S&$q`j8&wHoGTIHEnK%= zl3|+|IE2_*>T_F!QsXk<?&mJeTk3nAGr!PTkpCiQegm4w_Q7iBEzkog3gQ-sZ|am| zH^|ykdqoxfbYMYAGhqH$qzOY%YH|`=ONKoC<5bnKt6@=P(Uoc-R434q>b1O-EvxlO zsjPT^V{CLza<~qrjHmJKR2a9MQ9p8>^EY+Tnd0YUT#GFO&hueUj(;}!bC$HQQD(Rl zM@(!rCB3Do!_G^V8fvkTZ*cWH0)v^S5i@&jV^hAA^ZZF@>v^%jR!Wp^<L}2onumRN ze6rNgA133!eih;q=GV1rP5$}W05(F5SQ(qUu|}JxFKbK;Dnf5`_~}2EQxISj<Gm#( zr-y-SusVU}=^V-gGZ>06AQr~Sn8b)Yf?6j8S*E=lgs1i|7*OAI8FQaT4vpzUrj_B+ z%Za?*Ih%(R^M@1~Crn3$kxo~g((L|bADF}I5sk)YSQ-CNn@DKiQ`}j4b-wvJ-Y1$y zL6aj8t|Y?yO0nyjaEE*Y<TPK3YO^UXIIeyFP^ZqMrewp?_Dtfw@cM8_OxAo<SdIcV zFJ8?`#-JxplrK%E*)W)=99smoDlprsd**(xM}$%GE0%qYPk6;XHNY|y%rYNk;%$lj z(nCxDH<Wa0=m7%^>-O`p)^iQY9>vnD=0~REu<)lM1e}~l6ztEZgD@|MtK-7aOeIDd zLVA%iu0eimQhD!loZ$-}PvQPYTTlZE1CQQ2IYz{nMW$t?4UPLdE97!4hT|>e^eTRw zgrRG4E(TW6Z0;fS=#U1RFZ$Z7j6MnzMLMtO@Wb#u$rcm5`UbPIkUcgWtd1ZY3rx>i zzy{A_fG=eC*Gk+kQzu$Tp4g%pnD&}RD2{05H{lR9v>gSh*;*r3c{J0s>OC3o>=-<g zy+=}iTil6MwRzyq3bWh`mamfbh*Sb{%vQpeig74KBZ+iwC#0KW?^JH*)f-!3lfT#+ zsR7NR#PtN|O&gcJl-Kv7oZ0<V;&!lD-OorHOv!DtMRncitiWf_wAu~wW!IMbhqPh5 zYc&FLRS|N3nck7Akg0ob=&)lHklPg)OL?_YTiy_dvx!lV&^C4_DdYqZ#2*S%vBake z<#W4FSCNex`VrqbM{@3-^+f2#bd6PnZ0MCdR1Fj4y!&>^<IL0q8_|LGg`)9Toh19; zJ_&vg?^PfVyXeb3b=PdWK#pZH_DujKDPDUxO<R{<>PQoz2&B0k6&Q<h-@b>M;x@PP z(xZ`4)Di+!_n$vMkK#i7N>il`<k=|uSHVc03hL|G^0mx>nu|Z!Pv{7=4qxwwtCnMP zrUQQCNHH&Q-R5be^iTRWMH2JK8TfmAu|NpDWI;!Ag`z>AFm@yjOjxA_($0#TVI}-d zL0Yo&gztpe_)pa2Ai4QeT=7SuZJWAYWgk2|f~N@i(iB6XIN}1<*@P@LcKJp;k&qdO z8?eMKbHl(OPZkZ%r?OV`$rcSc^G2*Kcf^*QBw;*dlhO?wn?$b{&5i&oIl;KTI9{a1 z{I}_yPJ)?cmZOJw-HJWV;w_(>s*8pvAaJllxxBbe{47ErGV$&1qt&c9q}$E2N-><D zpM%oX8nSTUb|C%A_f@#>TD;WZKg<HhW7NBtY0G-Pj1;~T0?x^z#uF?1f>{s3tE3Qj zu_yR5d?A9dWjNWsLa_@;i+7>`_dWttDZ%CzyCmVX#Wkbej1ax22y2BLM(#fT|Faz4 zJ0H#d?!@aS;ld#O7Krb#*eSyDz-JerK)|P0R~DC7mOxtB?Om9?Ly)<}bcqv9eNI5* zXh({PSX;MYv9wk^d?ke%TIi|SRH2e%SWY}R^USQsB;#M?12>ZxWpH6ji!g^qJ1Bdk z0}&z7#C*aCTo@@n@J~xltm=LU*#UqDQl>!Rd%|lHd)sQZ>&~+drXL7V>E~+kbPnoW zF^)@e&=F}95`Vfgx4C&K_#e>39v51d+1nU@*<+(&=d;%mt$H8j95~mJWnDvZB_RwD zqz?ts=C$fiTvJdTl{#0G_%5+&>HMi^%Ya8b@5i(c9%qS6*a`2kELT&3XO!?wM}y=K zq8(aI#m^zADFOXN8*q*ycV5ut8Ojc_Pi6nsjj-w+z-G_9TIo%>!R=IvPj)Xa<@?13 z<oW`tI}16mx!_c*@E9rg97c=Th>fG(5R=FmnaLaz$}+F5<TH7&+`Wh<m)pWiyWm&w z_P(Ie9P$a<L1nExkX@+VgDdlsnfq~Els1<jQ5pA&#EQ1o2Dh-wOL#|Jx)*>YYy9Ax zJX|=@hR)a{pLm&R#Mi6|;C5)anLp~_n`8+_{NReMNaqeh+APrCD$uV+wFvYCd?V>* zK7#V;049Y(^h6C-Va=fqYa$|nW*(0h9s-$mh+d$KxE$=mdf+#2D0q3Ii%y!k6g&(G z!wMD9dE=|K!waH-=gNj8ftu$=xj6MbV)M;Dzrw1Blo7O44$&E@qJxpEcP#^y8N!Lj zmPOijeE_bB*e35&`$kiHCk#Tm5tHE7EbxZzRFyliwmEC*yoE;M(IMys`%=&80*sRu zLbjaH=;2&^s9EiK&I3NFOz2e?rrl@JPUpdqN~PizG+#fik+(<crbJ!W)75+f`cbDa zX1s3uc3QNh&)}Ll9|^GMkvd)dh2qKAn^42LPk!e=>8(vsR>W&AJH34*6m&-Y)kMoQ z+`ZLYs_7Y}m10(rU6)Wo1P={1o;<iyCbqb2%dTFL*#GQ~0)A(rlfHJCLr#X@_q4u2 z67E+mItDj^=MWw7-q8UvE@9u`Xtb=%@i9bcRcYKjp~V$owUIc+t6wsUda864p8hv- zi6E81sHK_AZ>8zR-P|byW%%1eQ*J0sU`GOzHp26Q9koSU-IS8dgPzXQ+6V>ZGqK6< z9}+pkWQ=ol%V&Ztu5Kuwc-QqJX*5~fY=}Q(qYUUdqfk|bQkwU54NK8r&J~9-C)br? z%b=r`^aSIj;p$rufI;jh-$L6&99?0h+J)oyD8Og1e<YSVX;A&V&fv=6RCEw$AULDS zOg%qyEGe+xJ-E*Nf(+;cjoUZ+;ywZ)97|C>SEB2q8x+nsOdV~xB|30H&=UEV(2i@V zcG!LnYRd6mWGlOw>qoGYO=V7*h5P{yBKhHV$^F>NqQsT=DHjeb8u)N9scr<L!jDdG zROV{o^uX@{XY<i3aC(q=etH})r%xt$hINd)RX}c;pr{xiuX|_WJ=5=3>EG?;+Pn;c zyjo_{iw3apE@*xpa}g|infCU-$1Fn!u2Mn$QLNIe^KCW?PG7(I-&crlG)r2Z!n{Es zygudGz75A7-}8*A>n(drs4QjDwD3sQQi$Fdofk^yAf9NDcsOr=n)J_@@<jsanCFeI zmyXZr`T#`H-@#c2sLof+=Ja0i&gS*9gv78LDJPyFyH&!q2IpkCa_gKD2??)gi&H01 zlfsEdd{9z+lt*wI(!%K~bd(t?g-Ke<V4jVV6Cg2q`;8GyKVFMS)NPhR{~16EpM=w@ z6hmX|VvFS)_M}fD17Ax@?qp^;{3SNFRTwA_nzF<f#$?xB;Q*s@{}lMK2|DKgfie|r z)roDpUM{qTc&4nNJ~r8G%Po(aXL)W%nbgdNn4WdxV6L+g0(Dq4x?0v%I`BCbzx=wG zAI1ZK2(O0#M@(Q;f)2(dF1HXWvzVuhZbL{Iik6qmj>6TSgDCS`0>Y!USs6SLLI1y> z#YxT<RZQbvsN5UD5E1C4s%<SJ&=z)KbA(yk@(o4ko7?pZBNkX-zpnN&`$8e+WIgMr z`b85Tks%3N(vp$qaZ`R77IKo5Kiq?B*j5FXQbu3Re`DeCYX8)?2a(79<*kJ$5m7^w z3I=y92tzy;4geflq~!@WshhQ0+`E}iUoh(69DG^JjLmfQSa0d8|LhS2*_lE1?ajJ> z6EXRj*WwG^Olt}1aRQ3YPPUfygGZMBV~zNm$$slcuj1~T#b6+5YQ29X4)=!T1toFV zfl2D^)V}1HJcYO0ubd4?@QAP7QS;b-=%ZB18-|CV?GLMz4lPy;yeTY@%NeaHp*E~0 zZVAeg@^dz>I|Zt$3RpU-%g3%69lXW}pDoUe!8bKL`?Phj^D!Cg2)?UCJHpA*@wT*z zgnf{8|9-Kx3JYz(ggTuEQ>M`swkgGBJf#a}QDkGByl=6OkerGI{iwaY)XW{9%`x4& z*Sc>|RK85)<NluXJ~$;k9w(74l!h6wf-$6$GDxl-gqa$UmEtmOe+=&`bEuNoK2Arw z0?e=>9=Nk&%K;#55Ia<WytPqIUbP#=Z&Le~enhxYSi@#Z2MS%-Gr}!N<~Y5JhKSa| z&YqQ{#mL{Y@MUP;ix%pp)a*n7B(#8mr+<5me2gonA!$eu$8xTes}WN|SYr~c@=sja zd5j=nkShwGRg|n_Hs?%9!;&vavqNN19}%k#HaPodbS_^S8c!x5_zF)l6ePK~N!Ado zj=9DlvTxC=!VFW#WO0Yo{GQpcDg>HtCJFp%aPEOfhjsDK=wbow+l1r0@#uASnN7;7 z9@V-fXTgZIc-%!Ha;ZtAGT9imvvDU!3R<VYp#4Q7YM^C+Z9KM?xDl?5WTp;6PU45* z<kvER@?5Y3y|x}sex<AEL!kh(T$%&I(}v=98bA^_Mg%*td(KDs;rI!_9kH-HaD$bG zJ8WhiQ#!MIVW*fKtt-H^_`{4Jvw^n+tPYQOypM{Bfr3#iDmc7TLHXVT%78;(r{r5% zKxbzI^cDmCTPtbk#iBoypp@=v3iCHfK$G5fK?S0l2pLB4%**XmR91nTVGxdmx<g@+ z!O<!cui4BRiq@C{YKl;CeM6%2Bwj-iSfS!sRfv~b3R9Qg93GA8X{6wG5BHAx#@sSy zRB&+1+(ypve|o{;@S2Bp<6<Mhc0lSkW=3fTMp;vI&9D=Ua$m;7J}PS-!D7cnju$Sb zTQBcYB|{9|anAolB#jqn@}*7W0K)5F_lQy*0XrxP=TMBzSc@w>G5+r1K?TK{L668* zJ({_cD!L;YS@{e8$s8X%d9R&M<Qk3e>W+RZ`M8`$ibEU?;BCCUXSn_K^(rMPv>l+I zJ0@q{wV691hth<4TH({7a@_dTYX74q2f>BYw+dqQ)%TECN1R<+mo<8Jg~irH`!vz9 z>PpLxk60rb_^qkN*!zB2bWE7&fP1lw+l%R8bl+JikdLRs7mTvF&fm?<)a%DY%4V(Z z@vd%D4)o~-S<PY>wDOxww48-s&E4oNZcwDDe|pYjYECjpj`F%XG>Crnihd+0JOxDh z2QC}D`Z>9_)_SjlK{VDYwy#k;S~nhGpAGUN!nv(XJDigC(R<BC<^1zK!0EGYKeLT9 zu%T11b$u#C$8qdQ1P6;Uc%P+Je(p!Fo2ABq?bh2Z2nxr-icI^N!f@SK+Q+In^L#SZ zO^eZ?%iy|d@49C1<vFlsGqzYQYGw3t_P6121ODl}?pe-|#XD`^48dlxIt&6H>eOIc za1B<@@Kiou#1H%+KMmeQz9Oo-B8r=0>Py3jEus!a*uXw7b?QPMuUy)Z2;L*e9nRUu z4-4T~h-51)9KeDdxmzjg8&Y%(eTjBJX!I<o%}HxnuMcm$3%^GyPuf?f`)vlg)=}my zL?c%kmBfN7lD#Ce_ftJfT<M3yxs>$}W5$#lXA`-N&_6=qan#6<@9>vHE({PNj91{d zpi$V;hgaKE1SlkoDq|Cq5g3YJ)|MloL65RxAm$En-!zOP;b)CNG%h{dJ-OH4$FR)A zuDB?_=s7BYo%!GOso;NKC(R&z=l=I?63QOop*q21n3NlW@?Wxvac;PLHEx`$NU$d= zZp)FWu>q-(*s^q%3G4;*AOYy6f+prdCT0SrrqgLlHa%%+(Gmit=uA&cEYYMCSe1){ z--O=qrKn%3sGJx$(qFBvzqGt?wSPE!;Y<HuQ12fhk(f}txdp$ujov~=@he<1UOWY@ zR~;)8=T3dp;DXi$=nc#GE}5xm10nS~OIuxFel%+Cl2X+IWdDsjcId^&_6S|7UWRwD z?)wL#^AXU<$^{o<c~`e5Qp}*55B6>_`YtGQ`qdJA=i0o{W`Z6$#kAeY{Mz3oMmw{J zt+Y7xRcLjo%6oRd{}JcbCMZj%WGf}LW!)Am(9B+u9IVkYMZ=i`op`~YhxN*-=Yf;g z*i#CNER(J0$$&9q+*i&`uTxXU2zSidHv`y)AuF~pg(A=T7-@7PVwH7(bOE@{uZIRa zGrx-hZEuUeiZ!Fz)BEeo-zCmEZq{X-e^f+6H|o1nNLz-6;_1IaZae?JliF?t63(4H zcFF$Lnc^CGayALPUYdpfcr^t^DrPqoc+woP<T^;V-H}|+TmZXY5D6AOrh1Ue*E$+L z2BMJQ%&0=&&d1h0c=}RyS_>NAWX0CC!O9c?aF|8MWLl4zW!!el?}~oK)cRek>&%{V z<i5F|gj&>B4AFN7cXb;h?r0wS)TFCp(Y+PoSY~1boRrN%KWP@^oIrDzKyR&2^*$de zssJH_Ny$A^Ad$>hibS*P(*!_3@&pntZgY5ChEffUn9}XZ;fqlD67m5Ng=pZ%ki)jS z`Tf~ba3WU_9-FRZeD%P__n%M?Z`bvQ?Oih(*x6T7lM(0|n?v4{H3E!jRt@YGH2rNU ztI)1zWobY+32!Qt(s4{ZK0kxv!CKWxHw7x|4;0lx98tH!WuXqE%e4&c{f8b-tLz|9 z*Y^L$j)8b^c?`-7!X{&XC56wF``CFx63~SegJ;25+&%ajVNb3hm;{iAB6#O!fJo8B zWHtz!9Jbw-iOErNKJ^f6GUL<Vp7GmJ{<j=Q#a)03r0)?lD|NV^FruNR7&u4h!OL5m zUEWV<A_A%+G9&;wyhDfR%oVfG$Mkz?TR@dlNt0Viky=5OQbCkcO;$7^S~w$_T3p>2 zN5FASjkLZ|+UNxN<T!V1gg!k}H7nE<kaZNDAC?C|#Udt_jz}ujtsUgmEx7FsWX`GP zXvs*N%E6~O9~1WI&kceoNc%`JSirK9-<T}?>l%AYqvoaQO9Y%BDvx#>6`LH)Kr-K* z(>InY-4n>PT3ZTWD8svJa$hrBTk}U`fn79%Wp={tXyLyHT*?<bk8LkjjBC;Uhd*q+ zY+AM+3DZMT5BB8dFMWEBA_4e97caw>0{}+VgQ`{o3$Ib_Z#ib&hwni^;&pWZ$IN}# zT5O-7%Q@q6;K9XsdXt{3^*>ty!XY0KoF=W0v{j%^YgpN^?diZLI)`{|C#;6$iQ#aY z5`L2E-f#&V%!9vXV(0eY{*KIkxF*eKh<Dt>do7Nw2|9Qq#gApx!Ash|iV(4cyE%dv z6c=5NXSaVL+-gBDr2=q{>Pir2hy(@xT&6syKhTM^<b5c}JasoAUaeYm?#k-VRC}gU zTJpkqeGgHd*w`%<_Z^CUKfm*{;vmu<du=P<UkSOiio;W-)MvKd4@bM|E-SavTA!`z zZn{vmi=HQqW)b3I=J&a-D0l2$40x=n0G}p-aJV{~I8&)+@?rr)2msHT>fWv2uJIzW zt!v4LQd@3FKD$ts&>-#0)T9>t4SF<V2*f|1FEN>;<If+B8)HK{S2VdETm)vs@=Aaw zoM>X5j{8N8fH?pN$A*20djKSo+)WEWGwe~)a~IV9aPL-`NhU)|{f&*C@(z4F)vbyw zmrZO(!!y?rHeRY6eEs+9j1Cn_yh*tns&4%<onppo+_dVn*&l3LuVx20(9BUdFdCv^ zH>|B#9VH!A^o}OjM>u8!^dc~{yC68oa}xYelzTkwwYfCaHz?V_w@KK;Jbz^d3Z;|Y z_eh}wieL%0FqbYw#g8YqvuOW&EJ6geDfR|-I$sAC_xtLWyK}v;`1=n5Nb;$b0@9G^ zi4i<&@K?Yl`Ok|yqF(~nUkRDJAjdHScbfE34C%sv!RS#E1W9;OC_ST4N5b4A=pqT} z0y#*CY%6*Vae0wV0M9;7&je<9SwcaDLd8w1pa8wH$j>|x8tA}bs1A|7nvX32wT@24 z$PnfD0QK+)5qTG%g~Gipi2UVf6Hv<x@@2-V^9;{Rcte8@1JOD-8->nrFcRz>W$J}n zwL28$3CFS`bAFrAY=hb9@hw}7&hvSC<}=g>yh>?$`y-E!2XI+sFe#U=9tL%>KiO#2 z_c?I6qxM`tSp%?nw8ZGjbGxk?8g;SnQ$tM`AoL$UIV|c8%z88aez^RK_b9Ey_6`ir zdUX=#;b>{*Z4#yfa>WDMCOoxPFOhq$<;R+np6;Ie6El5gQ&SAGeI0mJK<|`>hj(@j z7Ds+a4F_#`K>AQExRp<KllWSuZ|ZO|lbSpjCDyKiN2!X|$-h;dNbou+0GuP+&^ChD zhLB=Uzd+eo5v`l0rW!-_E7yPTx^IEy`Uir=UaD|xEi^_C*WeJzMa?L5Ur<zUe=O>U z5c><BbSCuc>VH4>z!j6*K8R+@JC@oL4$Wm(&K<MJUN><jY?@06&)7QecTb~4Po_vr zu7t~Gch+I3`nN@Vt<G>c$<fvfrJMxKTv+vD<h9osL@S!Gu6BykbOW5V{gLkZ?B4@_ znXa^*Maspc0k|i`E9b<6hWVIMw10XU7py#Gna>YjkGa7I_!!RZNGoL7A!+?|&lh>u zq-CQ)5RYU!1%e<_qDmMaNo(&)>En>39yJliWKMZv(9CBdCUazgiHl-z-szx<wJfl` zB2i=}f-!+;a(lWv3Byv0s*e~9$3f|+jCTN1M}oOTlI_iD{b|iBNna;O;Ubw^7(J$4 ziE|d#IY+cnJAWp7Minov!lBR-VmXk^qJB)e>ie{5hykNVFLM;d(o$b;<_S07?fOjZ z1Pe)5>?->a04m5E<Y4GDcEJA;GI#{(n%nhCb(oyP{qs|d|6M?lq9;L$iY$En{6F0; zdZBPn?{^gi@qM#E2;Bf1F6*b86e*aY(4%%@@Hvqa@4vchEM(P&i9rsv4h#(~1wF(= zEB_B&YDk4eenLu0%{(!Tj`BjlWH}oAXp(n3bS^}fwukLU45k|0TKkg)yQ-8iF<CJn zTQVzAFe?!Tuk`+2O3xVK$N=fcL?3O>1N(q``*J*Fq6Q?It`LF+Ex`Ow+v^}=b`+y| zpXc<s$zdra0CR(Ub*JR69Bx_Y3pqRU_-NmjTU=zIxQP1$rrsr*0kWq!&gDetDE+Pt zSjGhwj%)v(d$~q>U3HhOJPwtGU$n9v6WFz|e>tn$M&H|mGMJYJYw&V@GGs&uUf|>3 zJ^G>wfdDQdo&cbQyKQPemNc5QYi`eyn_=Wt9oSAufUA{E2fl}ZP0KYfSd>2*dv@%> zZjc+_J)S$2LMS)q$bL}ib-+js?>&V}c09c&QZl6mfLV#sP8|!5G5G4{0`6;)V(w7> z`MbD4GW5GRfaWuD51`vxR2{7YA5#;2XsU8BKx<NJilCX3yAoVo5q@6_GNv-6*pv9A z@m6dfJ*VQFg|)-}ho)-E%cV|C^~Vb**Q9gCuv;d#e%g05lQ_gBoV4!F&TU6ClG==n z&z_$PA31@s%TT<9X!8}v<e4TH=MCKr$Pg_mW|`bOHo-}ijYws|{cB3Anvj_k>n**u z!!Han?>M!Oo!-TNw^o}=TCzz={Hy5|!6An_5rug@Wo;VJ-d+{J1<2tnYvoH(>c<z~ zw2G!xik6}(HNk#o{OFF^Kh9Y4EYwRFW$vsNLtz@uLS@kOOnf6g;9L1`F!eIyo01Qt zUM7CHdzL=)e>vm|g$@Bd-sbfj5=hg%FBE_6D^~wS);YFi!iMcS+jdPg)nwbAJlVEw z+cnv?ZQi-Lvu)e1)w9<7<=xhgxVG!WvG3<P8Knvpbl-ScCi62yMwShpQ|5#kc9+iO zU;F8bO*R~Nc8jSBCyD|6dqL&i3Wdteapth!me}!S-<3NyGDBD%ipN==<|6T4@Av*p zHrO_#?YFpv6<r}7YAlS>rdOLos=q>fOYC6Z{%Wlt-cQ>`nKYuAT0!t)1VU$qXSdGx zzfV;`-{qAb4DG^JvBdvs(#3`2uGh%Z6$*hY2@&j;=`A>vBkOt;hvrriIMLwFVUbEa zZ@+_I@rcvQ4Jf1txBGy=!Ps63HAWJ8xkuP6Z6^(`?|9-ODQjYo6Df8oCw3_n4?O>F z!=OhS`LcS@J)#I3>p-(JS(D3mXmOxv{sgt87-qs?$GHXG9ecUKyt>f}jdud_&ih&} z&<*yQ5h6BS#av)A_b090E~4A6f!_~ns?b6)d*D}MmQAKBg!QkWml$Ke^gNT<>ZI5Y z26(%nfkGU2JUA?V{X=B#fWh{YAZ16^hoG>`%!yQ&Ud{CnQ{UDR0?uDK9<$xV7mB>+ z>Ln*1I!pNzeKk5$kDY&gN&|Fi3%r(GYvERw9y*8JwM~#X0ap#u!(Q+Fr7GeYMy>*x z4T=^|nnQbv9LYuZ`)bRJO#y%GGaC#lf+XhHHaIs%bDtV^j=grHY&7v@K0u)x1%0*B znIjV<(mi=iEJ<f<*cHsaE!`cJlc;z$c_V1!HLT<p3`ttMpX4}1qJi@zMUXU3X0;P6 zH;@Y`b&r8kmAR&C>sxK$U!VHU?Cxf`v=tB$6x&z9$u9Qy)<ti{1$Yu=jVCXba5gCl zcWC??0BIp&I-xkOxtMm<vhnU}RtFk+r_ay+8?6v05x_?{Luo?hl(Fb9)1F01ui}i; z0!@3{nv<3E60^fJ+mxA^xT^Vx&%=E%CsQb1Sbs94^vVsz9MEW+H{SYg7p;XOmUI^y zf-Vk|0~zZ|lR!_`GNT~Fc}&uGE|?A8RyF}=naW?MbHY0Ef3~dVF9JNb^7#3fYeXLV z|H86GHczKC|Kb)#C5&80&}Bhk{8=zL-DqdrcD(eECT#G?qF?Li&o#3&N0Sa?R`3gB zDCQL-T_}}X<Z$De$9cF}U8Wi_ZI{q_wjt0UZueds+VT}y?>hiG{KcxSV-b5;p9dQl z2xbKF;t=(kNpF#kn{F?C^upGjQc}U4h*x-!r%fCyGAga+#w!+Q&m4)hque&puuX<c zd^07&!%aZ+|J76AN9^%eqyMW#mxyCD_Y_@BG<=YmA*=Ebak;-{i3%a}#7Y%>tVJ#T zh(-|oN`PTP`t4Ja1R|SO)*CFjgKQj~3+rHC4-W$q;czWpaaJWxyT`@(3r#$oA8mi< z;Hcju(%xax$V6wjPjCW{aXZxr7)jcM0APDyl7?SocUwZ@|7oLn4?+Li_&h7I%hjSQ zT4uis@iT*;(X_*K6P=1Bw3^x1=n1+2pZ_0!UkX}V0+=R)!Rumcn4`Wls<sT&1kAGc z`X4!tT%UR_P3y7FDVJN9FWA<sl6B9<=jfw#+1P)Jp1jLSB{b^C;g(&0=CtOGhZNjg zq&}OMNcL2`*gKz;jT5y2^6f>j|I#<ioV<)1c_t5=h{G#7E#};fJlpC8vmV=~$<TFI zUeRA&exW8QZYKn)MN40-lq1v2{ORtPxhdD)Obq*_iHyG0=G^@ylr^R&AKL!Vw<h=4 zLr4WR5ObAVK&7PoeKXDs@CO14B+Z=n>?cK14#=^{Sv!M?mel=Gk5eRAF^>B#>{-e| zcDkygCaKjxLtWd_bm_u}<2n3BwHPz=%&7rMrW91u;!<BI^KSFz9U|vu#R3;`;uBO) zn#dV?8|T>3n)I~DO(bBYh3J|JCTAo_PtdO!yh-5d*mDN#WSej1_@c<nVyRJ1uB+AV za6&RnlXBvngW7~X5|aTz+O8+E_kr2$PWZ}ZkKmm6h<72}9d*^7vfS40Ax`I~9_F4F zok*|d8wbp#;=0;uYh6m!qUN8a-qziJ$xU%{t^z98^jld+ER~A}rqx&HSLKG;Az&ZB zqPt_uu3)WN`JGx(PwPdyQ(&UgJY7829z50%aXb;r9%SY_NG+4X4TYa2?anEk!`Ml$ z<vs5ioHkkcNC)JClq0moW1q>g6%ymw4NpKMlr=mN+g7dH(RHi65*s$z#49EP3eojy z<*@!dl*fLQG?%R7&>0Kuxqpv<s0d}ntv>rDKbg88<a?OwSTnN-izM29{dE;@76t|b zn%J<(k}4{K@qZC72#=8L7uLqbJ!^IJe-=mp)9{%{v2@pg->)b4d-eUnbqwvY|NIq8 zg!p#&C6y{KAfHC`QN6Y8=E>Sc9OOIB^u0Y*BhsM7oQ%h|%KiZ+01eJW9m|5t&Ie$V zQM=VwadJRStq}oJO-&jm2fuPAsJx2MUROf7U1IC2EqZUt8TyK7DOMvvyv_sNM*e!l zHOdRUvB>hzj0#dyFel)V2yU5_8l)PY{QZF9%%|`+UnWdx?-b?e5Wm7o&kmd#<ZK^W zfgD;HliA{&jG$-7lql9Ajx1`S4l1|~i$ZsN0!BDG`8yb%e#TzA%cVV@U-Q6k*m&zt zc*R>oI5R0+>mN4}225oetR#fH$<+x`8@^~0w_8QLX8c4i(Xa<Lp>7`3q$6;j=o2Dl znsJ|FdUd)+E@A!pidlDU#@ilMw+XA*A1(=90ht0)W^T<_R|OroY>X5L=uDn#YcBCz zNaPNd+TmMqBXg_Nt{*#km~KCu2u&X9pD$ZrfTk*XrKk+dhVnbmd`W9eghj2|6{A=> z+7*ArAQFKtZeKt&nn6rv5f<Yk@W2_U@&U`jXf*VjxDWx`n0u7c^Php`d%vt;4a7__ zH~>P}bA@(2MjsAED_ErOg8Wd<fjhD8(YS8bnH2tbNpfYQ7*<`RS<dFRQn6&lokEce z<Xu799PVFu6;0bKCCo!K9uAlGK^)RS)k5io;z5O*X)pf<m=Nz&jm=*Iv{1<1cca#N z)!+SP>ag5E3Ed~rtEcckFCdR|<Z{RhU2E$6Y)qb3BYSLA>KfaWm~gc*PaA7h54R$J zd*W<Y;#rrXd!A&qx5_8yTG<wPsRnvw<Y!d^$IYg;P_JHHZLf`GBN}CjcV4SXTgR^| zMQgjCfux6bd;2Mb$y=sAZ{*XtVccCSJl5)Kx(>ofG#L3v@|VPNjb{X=^DFkQt9iOc zKuvX_?EJ9v&_cqvc#TGW7jXsg4@cUMaT()If<x|m9ApFGq&+Tzelz>Nt=XQZ2qSbu z<#M%{hMnLkCF4r@OauK54%{BVesuRn0@qzgk=<zZ)P*$l24yo&qboZ15XkA?s`FB6 z2FjTT`iuLsJ7frC8)Tb1goi_329C$51BtJr?+X9W73@9Fn0_Av+Or`wECW0|z6QsA zWylO@>j;TWbqGvxCDla1;-ka&co(O3X;AqDo2Ec;Q_CKscaU+%FuVs)ODYl;ACKao zDtn^qO+bYDqN9XJK^*$|es$d%4wDkoqmhBR1G6|gU?j;&HyMLveVq~pokd_4K9tvq z{Mw2`4P^&+#BS~J`4{CVqS9*lfd!?|*2bL_vE-HSmiXX>r%<A4dZ5P)?>iHZx0!9U z9o#!tXb{f&EVB(GD;l~K|M?egizNF?As{6GpkJb+LP9RieEWH;Kw_`WLktD27-!Z! zSpBA2NkoKp-^3ZF4}0%Pk6zAIPPgZGSJz+e4r!E(!C`7rQR_duliN>@Oc2*2pm)+Z z&wQG}X;B#4hdbHh!`}8!fWD|*E)LQ0NQCVKW!+1ycr?~)N6^|-lqWFTiHPZ(E0fwk zUOx$A_xqIW>|H}k=^1@$I^R<~V;=N~&n?`15vM*3-leiF60jC?>=|GuO92BAj7Y&} zM{q>MwFpi>%Gve8^?GUcFW=YA&IDcrz>l!?t3FNohqg^zNEYT@Sa&L|b>q~nh$ZxT zN8=t(ZWgd@PE%?f?Qi@y%+O?m1b-38iFt3te|r330oGn|X@OHl>C3X6PX-l_fM@Ft zNDC}`(wolGUai10n*qlN8p%N~Zg?^wm*)IM6dPqA3rdt%3!x|>7R#n04>I}9NO8FV z2xAa^Fg-ct4mrn=P}6o$?Kyb~;BfW!E)`caJqqzbS-)N$0&^Wj{h+i1*uZSvO59yE zgo)*BVbXR*WoVvqS1g;GG<IYb9$)(1o-60uR%@cXx#>3TojvCoJcjn%Ox6)W5<y@d zgPvSJ;^AKvi8d(o`;^|JyZeL7#T{fWJ4@@tSZu^pT19DOzC^Qns%gNRRNQVVC_BZj zAU6;zJT>sH)IHy_iX(nUhy1zc$u1KN*`|8Q%X^!-B1)zqkmYq^7QV5ssC71oR<6Ih zoo6<3cj4l@aWSj2s`T0BD4vfEdeK|tXrg^nkF2_)qleX8cy_U{Sz8@0ktL3duV3Ar zy=Ky>Ki3IJ#M_juayfjzfpS?zV<1i1`6*5k9Ey7HvD*B-wMidiwg=jkS+D^eJ5)wt z&<(_r((RZ_Lr;>B3?#cPX@e;Z3`G;EcmKp{-t#f;g}$Imm)<PP%XMZ@x9h4$4)N!H z&IC3F$rVh_RCH9G;A$|_4Tt2K0maO1?|JypUNNacMFj=k?;$ZH&7#{;KmUz}XX1<5 zUlU7xF_J;)0)m^E_{J5LGNfaO3_{7pR{jm6dMbM5UHmO_#y7^;&JTyNbrON7F7Yju z_)_2z0SGiv=?v<DPI@dWet-vYL<#xA!`+VvK+6fog}>7;)cqWU^-DEyzuhMD(F-y} z5Xsr{6Uxe(^r-9jB={o1;e_TE;XX3he#(6HK`=z|3m}?l<#uoVs!#jEbw=_taYQT~ z!XdW_QbdI1T-Z)zO0cNfvV$10@MN|A>s!10H@fLVq++XlKmNKi7HfBpFev#Kd?KST zs;B&5d2_D%&~8GSMa<hsA9kaHRUCxqaP)!x2%$t)O${eDCC5`<6nF;FN97mE1{}Xg zw~CSzD2Bmq%4*Z?ONPl0Y1N`h^+ehpmi^;BI6X=jR}eF`I%jZr`D<4w%<}O2%#YBc ztt%8a@9r+3smIGip^1bXhA%J(an|9G-d-T1N`zY-B7vsrL3d!7R9zX~j9EyN$0+jq zw6C!{8pL}iVM{7t6%MBm&2hNH^bqPF+pKBnPiqc_W`P9A%(HD_!?&L2TEl9RYjjn= zzy~5?tjnfu18q+dXr!co`xxV7b#*nwS>iWUa-Rf5yHqxMuS-Y(vmJ)_jxQ8rMdz6E zy)`vd(}Xk+2*lE0tX3jb2d~HG`t(0$1NyZn>o!0lg}0+b%w^de=0lgL4OSMNW*4pi zZQc@E*6=t@fyl#Zw#(x;?q|?*O`cfw=E``?6Bw-*?p`tlq{U!>NmnUqDm7d*UOQzh ztIrS3p8w%sXjOsJW&B#w|I~lKJY}RLqBrK8R(00oDSZxq{x7t8sE!VK8Z%d9B@Y$O zE3GM49;v1|fW|Q5be%Xxp%YT6HcNj3URu2{oqx~cJ)PDa1>C%uW%U~Ef^kC&v?0XD zb0>FVpqE$j#k1>rtz&#q+QX-(Hh&c*M;iKVG$nmqlHE6<+!C|=mUncW@ij(MJIxT# zNLNx}<&wCi-2QU37J}^=%)trSsvi8wiu`79qUCV9c$Q7M+2a8%@f21ofXa9{v&Oa{ zKzaX;@pg|+ST7=>H(_~U5Tr>lY7nX~&M30+TDF$cJs@_z2Y(|!#mPM}>SzZ@XJup} z<=K0UC?*w`NqZedvo7()9OgF}$BbY;^^tKPQ?YD2=70xFYL|TfTP&|sHbkJqMSDMv zrJ;*$({gw^E8-KG_M<+KUN7@?R#AsFI|_RaU&sIyG=HnK2}(Rpk_1Yje6Kf<k@#jL zdJF2BtqoQmQwV5=;7EXmqw(Dza-dZf#$+m{6m+o)w?QA4ipK${?5r??3g}Ca?n%kB zU@v1vv$9c8jU@ZVBNrX-QKds3fLE4glFt%=EuK--UE)D2auO9W7vpEso4>Ks#qV79 z)IWaY2M|a=bpRYfpDA&27+Im_KKImc*v-rBL+=}zl;3mU;6qsm9^*LOC7kyKRA+jR zXBaPuDf_d}NJ{ZH5sjvMNoC{ga|U{L`db4G;^wCNZV@(TNG$Mw9CsAl5mVRUuzp4= ztE1sLd*dk1P<zGW|797(rsbfdX%0~zL9x;$B^HZ=suDtieD<`JqnGicaCE3P7W}J; zXPAZ$yS*9U8wh=Z8XNx`y26emY7mx>)Na$5F(S^48vAXNL+*N<5W#0hj=-8_Jh4}= z+pysyVon8}T`Vt1h=Awab?QF08@h$^YznsPCQA!+NB<0J^#`Mw&8U*RpcmMTnEZ`= zT?-Vjt8W~3@&HgG%$W!;`M8i`sjjx_LS0C#(*($}u!XOxIph4Z?D}ewld<Ae%=5yL z{I8e}KK7u0kFyQ$`osRuRu5WRHY`{efqX{F=6GOvuGir_pacKK)0eRqw#4tG_b(Kd zkiGog06?R5DdJ@h=~I*f__0ni55KDidg0Q84ts>Q<4KG2+;?grG-WDk%1~`D^k<Ta z&j`U-*5BB`UNH9}Z7s(>$ubr;l(7!o%Ny5bX6-cV6w)9-pKzY;Y$jN>%mFyF(KWvC zIP2xM@<ea8DbT4}{C>U`R9YQX!n-wK=K!t|Cb__sFE3ZN1ov>_;OpT=z{nR_7aY~V zc4mj2BOAuWHkf%;6<4>*cRmHxr0{aR7|%-y(-_JJZ}>Dx%|r6wu(cn$059E!^g<kW zu2Gz6P5@Vs(6U!dz$UUIL&OyQ>!#exP3&r=U~_J$`z_LwL%F|QIesH2zlrr}HRC>U zt?+8R_@dkViMnW(wnc%TZ;7#mYOH=(@5kp*A}3d79ePecgB`d^4wOVE>%p?i0gm6q zQjKrVOY<0#yllGLRO-*7^u)i_a~>a2R%;xp0iGx@wbGj@a8alFi>35`<2=eRm88t% zMv1^Z<}ATXF}gH9*_5kRVyZ8G8f{6>n}}rHK4ui?ip&>Em`-@AqzR?xt3^Eb{M5BO zv0(FLj>TgtsFF$$)Y`pF#Xe_E*V~EGJ;_t!pkQ6IcRpr9rx&BxW4y^&D2glM3<(y6 zdYt)s+zk-o;JAgvq%ss$M|B|=O3RgxKh~d3{A(g|f6G7nh=XFniQn5)R8eLvPNnwS zgZ+D;!;>sLDlY;lF{)`@<xpO)>)8r%@EVWmL`G1i%Fa5S0Y~iMEm)E7M$Za`j^ql* z%R7*M{uYOG&L9qx1zYaJ&rgfrv$AF9C)rmHb%N^CJAjT{T9CNMTaVKgL=?)1b00JP z6nIx8g#F(Gj-Mnjla>gDcojcxa@Ii<DcVZh=G0O9s*i;E-Wn2#GvQ=qWd*&=qGr$` z!aA?^)B7#oB2e_}d|o|BrZSUnE8}pYXJKX^UHgmSC0W{MFAC!NA#lU`43h3(aSG3} zQ=!GaBPUuZ?|ea+QmA9kow}n8`m+gO)6lRm2=||ACd{AxvcY#$sQutd!%cT@uSdhk z>KhL|`O_AfL6wpaN8CtMRXesw#IHy|kFf+z7*0g_SIEGf^Ld2n4j2h*OXnQu%;Am; zeLI;gUFxyEHfR58pKQrkRpZa5l1Bh*d3ZsIIbJH=yF!7w^9=QP(02%@zlrWC0HxXu zJ>!|S0CU`QH&~p1R$QQ41_*2>I!;?l5mr}$jXE{B#8zJiIUYY#(g-H4x}g!+)vQ}& zcC}-&riW^};?n%e@=GtSq@hLY=n^`gSunaumDPH}7}$^V0c6+hfM@Zjy1$y|1HBs5 z<al5(RHPa3{7|$`+f1yVZ%<|@l?;X{w=J&HXW@?H&)PB6-vg4osPKVcf>t^5m$S?a zNl6@+X0L-a#xtABOp-bC#0;z09N#8`)wk`RCn?f;%egLW9azp!a?h~I$4<J4=AD2` zu=oj(6el~Pk%0+OPF09!V6>XX$i*3=iq<3iG9OCJG}@%s<l_Kb02dfp%i?HZosC>y z3`Sc#9JcY69;coYGveVwf7;Yw$xluD)&k_o!@hQF`xppm2F`R)d};&PU$m7F<rL~^ za}HCTPqWooYaDRrn}Mnj`hm?YSf)NFx$EoQ6&(^k>i=ybYiDo2r<`X-MRCwdw`IY; z-3i`W#xH1bb}UWJxBAJe9M!*X3i7lyQ+`UBZWX-NI`w>Mzw~JQI0$QZ(0$B)FG05u zkSkr(4wv#iC$7fv$d%veh(BFSchiOJRg<FWPP`H00(17(zl|KEyb?T=qpy7LtS7Ea z+W`-h@5-KV;^&}?mF2;YccQD*tfC0QA6L)MKpa<)V6=2IhTxfh3U<`36y+UxC@=Jt zNthqi^=ZI^og-Wo1X;n70AmXc{)M3wH@vKBweLg7m4j+mzjw|m$Y%^rc$zp8ZMi66 z^c|>ZYy15Vpd8Lx69E0z$_T<NHy)Pjjo?iVs`N8KQo&zMJ#87Mu)FjFPDTb{50%=t zOu<i$US0#TRTeaoNbJ~Bo_Kjypl${Ooovys8_0-;=zoG^VIl%9CmB~V-A8SOBehMO zr-H?glyt+vSOz75l!dSQ?^$w-Ir$@A=**RSp#QB{0125@t?&RhRC&HSUb#t`4E68{ zF<G4)p(8v$Fa?^}0V&9ZO&MWx^vW%G3`=M53g=`W@A4Mf4_x!O|2Y@@$UiPEJo?%K z2Z9bW`-O48|M&5JTc9}A!c{MXY+NYiltAo2=IvXp6kKjT?4=*XueV+hnq57bA5fF} zjsUXJC>0)b_?t_N@=}f{#eU;(qOH$q8st(E9mw8zPV6UYag2&`_P<e?Y6{^J{_j-t zUMvi~AlNsd{}`VC3D6Tl6#*h}#fA$b6c=OD9~e6DZFY1RsW@F^^!AMo#Iast)uvKx zgG1P^8IcaN5ZiKouh%+OAqZxEsHyaiTecA*nftL`zLolfEhO7Bp;~YC%SGIS(bcKh zb|xca{xiV7e528qbK1IvYa>SH{dZnMe9vdI)^urc`}t0ssQLD@r+-Fy8abf65lCBu zjT<4LVzR(HVRdwkhjauuk0W_OjWrQT!(3n0aV|qy><wFR{HqpCLr>B7Aez=TZTFtQ z=-lVyff()wb)qS_wzYvwHYuKx+CS;I-TUaer7NFFm_CL3zFWefEkp$UcZ5Er)oXe4 zQcTY5@0`y4teuT&@#j)0_Pgy?oPzIye-W`jY!J(eeHDnDS%QmlG`2SKVgEc-+RHbv z`*h*vA>cQ6Ci{=KyIRO$Pr@YUwG=_1I_)(&T`Le7knpo7ZJ5p$OvEpqPq*dHcBL9( zSqDm@A+Lq-kf0%bX_=+FU8xcVVb;J)BTQ79!wtLc5!8<ZNPQwynIoHN!EKkJE6SL! zU<#Y31VP!r?W)@U60K|JR>lq~U5>DKB1T!PDBERVgiC83OxA8p_oC#c?#XnbkD4VP zw8m3Wb6Lin1v#fB_>N9n3%x>+<^y~Li2p04(d7iPxh5^1*}ojSp6EPxca?<=?ZDmG zsen&Jf3Qv%mD0}T^8C9j3+}xvX%MAhbO|6lnSi$vu(R~%Gx5Q8>~P-otdc!L$XOzq zIF7d<S>S&n16o?7e>7_EN+jqv(rl?o=c~@a%BCc0>NPm?igbqp^@BalJ&Occ$Sn~f zHqS%%IL*Jm=eVy|FfQ#J&7;A&&)|qEOU0tm#MN_oamj>iV3h$oU?eDa$B&KPvU@}D z*+vpJ$h$~xmwb@azYd1uk}*xgTvZf|jHx(4?}~y<`ElD}BU@qxF7mz-zC_}$CwG&O zq+xnA7%oSF5jht+vZ;<JEP}^947k;#5Mf|B8azCF_6>}XjP~bgi$rYi!iN5~*Wd?@ zPjBzmTf89UOZM+*6z7&UhC;CdfzR)<yTfVZxtpwzOaySHGj$z|3qgkrHE9;y<i*Gp zyNv)1_ly`!w9|tn(DOXX?X3Uk|E7lU?kP{~;qHFzP}cV{o!3|_R`7k=EGsxWo3M1~ zWt-Q+BNW=!)>e}UA?wGmAg)ONRdXa{p%Z?nvN}#yB>!yR$}Yl5))xWiSe~SF@T6H@ zngDqE<L>_U0Xgcs)!tXuI)ODWxxM2J3~8u6-NedZ5gZvMJTyKu4+}JX1pSwMfFGZ$ z>n$^1PKZVZ&f@~Asj0!yVgJkCuKkQU2)(VU9FeMHXkuJy5Hz$D4iPOTB?mS<12P(_ zPrNRV?^PlVn(M?=zW@l4yBmx)EKd?7jpb;KyD_dGHKts)?3M$mp%MR$LrW#hv=F5; zU{@S1t!<zU@t0SWfeKgFB-jv18Xt$(T2plPo^>uByEf2YXXwLhw$skEZwROx!diD7 zT5L$vT8#E2{c0r&NOAm+r1XXOqye>h@+980{Cd?K{#jH-x$h7$<d!Kp7`(DM{>PpM zoweY{JLEc#!Y2t{8=^3F2gW7+dEzIGqMp75UDX7%^Ztg=crcl%@*WnX`)W`adKGW> zqywe18mu)v=!?61JA<r8U}7T=Z*&N_hJ79ieMx{Rj(hvPW=?Fy!iTGj%-iM}v6+v- zUUHHSHZvlaAP>sDcRv7m(b{3@A*|cPIL)l{pVuY$l)C(~c3hCe@47w3^qp0^&AFYQ zuitK`!Xu5emPPpvC<yM~E;>>WAp-|$6cD4~-B`IVj_+t;_`ev7afd(st1*3Ue_peK z+nPN|HG|mUN7o+fCd|gMYw<mVNwnVXKSHK-2RzX$>`J+g6?=)4ligbe#pyey>1Si9 zg{G2~i35^>J$wf`cUE3ZfBE8(3!Yd~bfdkF;9e_F6>|c8NwTCtCV5VdO=&%GT6$qz zllnt|>^^URO<~5Qn;_+Dx6o@h1*?q>i;ug;i=`5^2?s|ei>JiMn*Ahgs_}MhoL9!B zl^$)+gCInfc_jHI0e+2#hO}Wsp$9aYI+x&jt8P(aZ>}Ye0>0Xr8|>qvon(f(E=E%k zq5YdQ<CRFXehPv4Jwe=uMbpy(<8VB5(tyL?c=Lhe4TG7*N?yBa_|7hrVOK1dQ}Sa? zcub?@VXp^fe)A$|(N*e4*VnreY1V7|`+X8s*f#^fNm(Kb0&{z(-LNc(_a-ODn;i;& zOfasgiGP#*LxBFV;7ojcGNiVR8%D<8Bp9{%jj;KKCLuB=#gIwmo~Ys&1?61G`Ai5^ zz-Zd@D(iD=+NyKwXT-2s8X)kTpsFp|z#d6fKwsaZt^qIF2vMYxw!;M(vnd0Bs@ZLX zDRso__)b5o|Eo9mU1Xa)D3b8I)W3cVgUce=bHlyXK^_bR%Zf~aAck%r;-=D&bj(7A z%D!Vfg%0Y0&%*i&#BtUW|1Qd>%c<H&okEK7LV53lg2|pofj}7vdsS!D-tU}gh7Qv0 z;15tUsk_?0EDl+ilPF5;-h(n(u?Vo75p{Kp6t`{T;-fStYyF}`UkC#=Swhon(ZzVb z=@3hXdZ~2OL?Cwt=KnzumWH82`}GSzrv#xvE-|W%J%eKob!bN?@@PtU{S-z!UpMAx zh$m?UssF<&3bPZ2brh-RH1>%{h`5U$NgYL>0r85=H3kT-43>dY0O)Vu$wY^1T^rhd z#1!>BMCrInb#2xy%6?0I8z@a#>N-&#llsyTreVW6!*&Tb0k@hsZ|KGq+s5=7oaZ_q zPG+ya|A}U~-#utjADe)Fwdj8~-^h3MFTzLr@I1CBXH8x4B+hyL%1k3sL=0G>ulvn< z{F)TpcxTwEJ0Xw)i>9Z4i_Q5LT>QuO$^1plyFrxyrWouMi*|k|L?Okb_ek6DjwL6R z=aaiu|Bqj(olB0$yx)Pg<=)yNy$)E>-bXpx3!PaI$~n*r-^NxDC5|VtxdG)Azj(qU zA4j7mMb>j_2=9ZPK>ipf2Q@PdyB;hbUT9Mvu$wELe^!2Sb?`ctX!gSVB>k_QK!gh? zTz~pkfd>d^HFb|p=f$9|cI4Zo^+^YNa2DjYlxS&>A07XOsFKo7`4hlLScHBc1XlHX zI%tJ+rZvvzWG7i)AVS~j8=wO#!&ofpMCPS41?D|1c87l-nm1qM6D%tUdKVD@1HvLu za1iW*cC@kTh3pyOrd{Ei{_P4=n@a#DI>#2x5`35Y)TA5SvuMFngD`5Ezz$EPeBJxC zlaAqH|7>HxQ>5EBl^G2{tLq>gCGG$}5uDN$k2G>wi!0bKfa$KJzxl$KqqvjB(sm0x zmlb9N4i=*hJ=<9LcXK2cCqr=U2=fME@pSt*{`J^K+39~0<*24PY%v=6RgG7?gzE_$ z${Ead&)z!a;>mee3T$e6brm04i&SEb#y0bF&h%T`nRH<;_mUO*SNyr={4CY>Y+g25 z_*P`IpFv-im8YJM8@$?vdFG;gS%I@B+UK319)2s~^xy-ql;T3K)s#+d^`Y!U`sJkO z!)pJCU#Gz)6`it$M~J^;DES(k{2{n?o<nBg=eTY{&dS5m+iL_j5Y+fXId<MivZ&VP zllap!(ZfTHBn89d;R2?(oL5fmPlAv+Gj=5vrBz!>4T2%2$q_CY38|zr9dU0R3N~?V z9iv5!w)Z;%Z58K{-VhREZ>1i=h$j@hDBDGT09BP9Z2c~v<AVXI2H`O7yD{h8?i}Ew z&!*Hd7`XH~?f`fg{=NQ~?eHw?i_9jPz<YlPePWp{zy40k3P-U<cL2)GJtW1Hf?UbY zvzd-%juD_EUyQcNoiRUrl{g0is{Fw7C5nP~z~*Yc(ykc&-%kFYA4;%<48%t-O&H0T zTYI_}n%~e<^oSR2TG3!u+>9SV|F^k~*oXuPW^r~sC+9X5`0noZw-F@h!7jLD*jUb1 z5rysQ@h!S9S5QGAZJKO+^@=q(usNa-O&i80F9b@5R)w)df|C*Ho+?R!+}?qNsXp;# zLQPSS4+jf)!`VQ7{><E~B)yrP=o&zgMpeS0D{OW7{FZU)GWXANsOL)^?e(+Ds=GmD zVy-j>t3%HQvDd0H1*m60-!XZiicrN6c%Wk61~Dy{?Dd#DUcX^gp+8Bvd%x#RDwB4> zB{IH6f>LsR!`H<y#0he^03wea?h~>xr2l|aG#HH_qW`M;WR$S8$sWv3XXEce&Vddc zHi=|+txIs!K-)r#vuWb5inwkOik~Z(59v%J*a_vD(zk%I%+Ga-<#&AYD+QF^NB(_B zmo{tcGEw^c$q(G_l4FaPzyc4fGpa*vp+&w9iO`I&p`ypj%VY#jMSjICS^7-h1XpG) z&FWGp1$W|AauK|`CiM3y>UXIz-4x&z@zKQ9!)}{L0L5XrZ3;mZ3}DfN@kQcS`XLI| z!qg@m+t~WxU(XyMOd~u(i<DkZV)(&2;)QlPLm%@7*Wu7Y*)sUAR<hXznuZw02lgjD ziXr0C6J{qLXg_2N{<z>SOS%eg7JMr)mJMNL>J{jND@bJgWVUW7zxP3)IQ_M-iDlr8 z3j6gATN0N@4R)J&U$bRf3Ir?#3THLD&VE?fz63UhLIednsxtbHoZ?h9IkP*33zPnk z$6H)738iAuz@v&>-U~2E(ar1{$)DA&tl{e2`a{KLT|_c)sSzB0e!Il|)`k9v$cS+# z!gn&=W?1txn(hs^*KDQzwBVmdaq67aROz8k+|x9S+Y=pg3@u9x?aejKYOBQ1%G2Fl z-{eI`L;}M=iJNI*&Jt}m6fo^Ro{9Whv(TxQT&$N`u7>?!$rylTl*?=uHrY1iN_F|e zvh;oAfu_LM!&D*JdRlnzMnszTq7Eg6RWJ@lqk!0%T9{_luUzZ35>%i8K^a{iV;k3= zR2od+irlqjAsRR)MV*Nv^+!cYMM-DUf3Pj>XWNRfN^>fiDie}!!**s9H~(rL$O1&Y zDM>9AxL7n!8%;qY;g32gT#qU4?_^>g1p#cGa!@u2A?`b;@^-MF7<u$oF&@`9Ur1la z=nUcXH-O*^%HGzmxZ{)OKX0KQ{A-W+e+%cMy)QgI(!lou3G&!yPIq$kc2!c0@<P6d zY-<Y)6jEuPlZH<M_0)!j1iknuO?Fh{JQ_jVN0Z_XM6e3!yz#+~g!G0x=?AKNjSi(9 zL-AehQfX=VBai{^I9as6Dfj}JHdIN3R#t5^4*+UA1~*0ra~22N4r2B0?)SNlj>S31 z3&(OkJk*Og>k3vIOPQP=j*jGa?R@LCPsV0RPG!-QKX%lYT`99K=N84AjZY(Y`W9Tc zQNmt&ELDD99B?hz{WHAkbwgegJJ)++#v8!(lAMc!y5DTb6C9lJ$P&!@o8r0MsZK~o z{SC;*4o~GW?z^8NXUgX9)$+A!lxcS1$bOI=KkV5m^;(Lq6nxjl*6D!(MC|cn4N8gu zaUok5LT)K{8*P<ZJ@>xPi`cjlImQ#o?vC24dohMVJ+2eBQBN!~4Yrj1^}=cQkfH)^ zumTQi>DLCgYH2Gl1YUDuEvDymAY&BYIphfX<(#F?rGncM&4Is&zcPm<=n}$@w$Q?m zLJE!Qk40Iz&*{3@ZVTK4c+FgkakZ1>y1R=E|LqTQC7=#(8Viurq?1)PE!wFpU*{W% z{K{HScem1bA6L4GlKa-7;uH$-Op4Q<eftasxGW@GhlwXBvt(|`2pB?JUGo~)LD6}T zW5nHV>M$mwrT*GAzx(L9=SS8~p<?>8*Dph083+GbL*6G7WPrGol?k|uANZn^so<YM z)ZXnUBibD7{|8|o5$eBWZ|DR7zv!B!SZ1a?3l{x%P_Kt1?;&7f)1(T)3x5iK7Y3!} zZ!Ec<WJa0p;Ux1?eM8(FJpNl_Rev<W47hGMxR&ILSaWmw3vNB6^dV0Ty>*56`fp`( ze&-@QG2tDFS+%)Dwz0?DzK+{gdoN^E{3Y3eiBm-vmMWj#x;gF3Z?|zX*>Y8vF|1?@ zx(sxFD@PZr0^Qxp;C$(r%C+d?k6+-&WC})LDuDRcq(fHx{QB^SHX`yff5xSJVq*%! zt(&Ew&nQfU3avv>zxRE{G|~7>Ys*3#$=jP7$!kaY{FdtC%5ob~s^79ET*3*ol97pQ z%YEiphFBwNw+R!nU0v(Fy})m8Vtu^ICU|ii3a49z2{PhW^U=WT>6e42sL`?ysT`+N z+$Vuw6p_IVl;gYGx7^_i>)z)(SpNk=3-E(|?wcCs3yHz6+_NXF{%!2StI;g$nv94F z76`DmCICju5G0)ixpipnm2HfEr;&?4q@e=+{;+!Ykw-+3%7iDP$_kmG4FoS`oa>}m zbXVzxlrsLt-)!p-f#CcD(Yn`}qcSjb-$I7!5@tP%ndnFK&u&d|p{Jt5%1LZ#WxXal zl!;l|1-S2IBuv7Kvn$fa0LHrKB?ItE%=tp_dEW`~$Sfvah62^JYA(ho;RskpPTPP< zi<kXoYSrnM$n&PC8k}O}j`yUNHK15D^(Q3&xtxz{wjF4eIB;f)JK9LVPPDo|T#wq^ zRH6anvEI!##g+zjl@O+^u2HQn(oOxL)Q0<>dtjYp3B$H;dx}d(y_!TmN<Z<P3K3Pu zMr0bCiB)p6_Zzehi!;0@sMCY7ZS!zpB<4Vr3d#layKdHOc1#kr-b8x<Er$BMcpR=G z!`<rfuP}+4+%t>N*bg+uOTm@WW@k~!>*~r5l;3zv0)F~B*sh+w&QB`nfpezXCo)Qr z2ydr!JA)E^9E1^OgMMgrB_z$ieQm;KW?ZyoKcmVy)DkYN!)~{q7uE60fh3y%oExb^ zNLYi|Yg!N@i9l_HE@#LQE|b`~2JfuC^=G4@iI(Mbi_bgiLh?*24{m`*kue;5vvEk- zV|S$Vob7Fd$ICh=p%7}nMm8fd?T}U_mH`GeUw3d7B!zQ?U%Cq0a1?V<E=S3H%Dz|d z_Kd_x#RJO|D=bTgaa%d#p7URlwyloqQ&=?DXfR{CHwRp1HSB8=h>PreB~$XtTS5Fx z47Pn5Rje)ESNHk@ohpY7Kj;>>UUT2io6o7;-V7?REQ-*Hw_hJ-sWUs(0+Z$hvYlg^ zr=^{jqB)oz=9(O4d|#v{`=4!_E*E5)?|#M6n^EgZs%@&2b3JxagSkLW8-wYT5P=W# zgO9_)+W2dMK2%P=m<JO(Qw)v{0ff6j7@3)ORDZ{%7_#?CYL|X^?mOt`x18<uO#%bs za75`8m_UhS;usrI4)-YeZ7CfaM;QxPO@?Sq76^kW%WVYBF%9o$7Bc{2+$pId@j*(# z^5(R)eK-w`0n=ow`w9Mi-!QO}e);DNEK;ZZAgsi9bkgYC8U+2HH3%fdxafNbCe4K7 zo4viaoiRSvh`<zTX%XSzgtjL#KWx-dB>=s6t`574P;cA?BP%#6FX2b}fQl_b*OfP3 zc)#Df%ZcC}#e<18I2=9v<Hes!>&$k=0`@j=Xgu&|YYAoMD&Ue-{RXtA=*eOMu!y&; zwP}R`$${upvgxv-G|jZ<MC>LuaKCTq+^_Jn<Ls})CQCC=GHj7Uo+hWOBKe`Fb7ynA zR4ezRZS2NfHIR!o)w>)YK}&j+nIs*#t`dj-XWyJYXD8k0tyInBgE@NTlhn+|h?BvK zm%6S*$|02);8Sc8j<O-yNKlf?GDUcB@Y?~_i`r^P@o9hV+@9ok(_xtQiaXr$5aD~; zpDw?8>v#d>_4CgAs+F+BYB#4^?%@vN;kxH8ov?N8^<3LvkGd4sOD~79JiUWo*HD`1 zXcL1Rzo7<hu4?lE?yAXXl|8Bd-BkS#Vkx?ysmVc?30IiY=p#qd^^8t)1z9Fww|Zwf zZChox-`eW^@eq&%g<>7XM5uFj=0#r$ekP+dR-f{eV#-I9THN}%#=r8~Ib+Y7DwDV& zL%wHbe$;4FO!9&m+#9q^$*BNRL!ZY*b~4fCy`_P<^15xjTE8PY-vwWvu!N>cD6Ooc zlGjE$z>7j*&E&FZ9j^SoTey0+3DPjc&j#mq5OvR42s9sy=2vR#VSBCqZcDQLJPZrz z&p7ZG87O#h1?EX)TNrnhfvu_2=7_M7ge9{pQ-AVn1YcGcen?l1Gj$JOw(%iPQucjt zwqZe!M7|b+C>Qx`%1AcF({_%h`f5}iM!V19)~7`6s-zB)^{xu0GOcIDGumaGfrktu zP(GW(+fYo~!X+=p?;%VbL;^AXO;-6FJwQbVX;uqopzE=xU%6|T{Bbku4o!7yPZxQn zx#O6k%NcJk(}ijCBY&Ul*vE$#sF1N#O}o_)DG(FctvuXkur#EjR_dvYYN3wsQOSB$ z@$rcus+Sdg`AL2s{!DC~9}A2IM<3ZwAGrbzqOmgv42}!Vklk+d8Ito8SssU%NC@+y zd!(f@=h3PpSA{vgp-TOkQ4gBt9_QHQq^A%<)kOsrl8Fm;e}=FZwrodRL6Mj#{OXmj z`TnE+Zud&Dp&@*?YWfDpqyIxj=K80cekG5wk;4C3ch)yDLOs|`5UR?@TixX)=<+5I z_U-}%3I}y2eW3&bgsZBmfJt-gv;@A6WG*pKGO`Kzq!l!M2OoIs1$)L^?6AsN-u(eM zOr@IphO0jMx_$K;e^N_|*D)m#mO>;p?Rg;CH)Y&0VBxI{bd9d6jomR3LdTQmIQVkY zHUBBi_+R4JR)!Y4_>8cuAtui$1&wmf?Y`Ee>%kN=HrPbYSXZ%~QZs@p{qwy{mNO5* zKT`ZEp97>sgg|EWiC?Pm;N)Bw&it|mHH$&cpoH_*4Kg6167yGu(IC)yMNsB2If3lI zAV{-9`C(2(@mZMrWR~j;ZcP=y=h0`G)$z$^O&!A5U;T~Oe62m5eNZndyVzFxhuzej zIiG&ma81_KRU)V^-P4Q&U4tH-<P1ge-;d9uOGB)|gJk=0T!wd#7G+K$d0nBYX!=s@ zN<k6Ol8LAW%h3TnPmntvb#&?Ltn{8=mbPks0zx?TwfETEG@G8!uYEj>!M`#xQj|ir zX0!>Lrq3n$*JHpBLfYk5;E3T^*Kxkaj3L)oUw$(oT$1-EA!4lx)wSZZs16jfPQwH~ zbc!I`g~!$hkF4E#=Q=}*11{WU#0`FfYlw6gB0L`T{pA%jleshoa4ltYKE^DD3TUSs zP?NzU-m_bp8s(`UcBZfNQ+n0P%l0s{$=iB|{B)|OyYoWqFA^s+XA9y<#I&}R5I=3@ zPfvdj=KI1t<3Q{`Y?e-R>v|47*^Z7QnSqHq+m;l{)poSAMLu8Ib2S^{Y23ra#~PB= z%OoWR<=EZ!#JIkc&1v8_?RHiV!t|~Sc)82E+IV~3gj&7N--6+0%a<U=7~GB0?w9Pj ztVYk$-Yex_Qd7IleiyzXWs&UpG+7Y6U^&@nWf62!*^W}77Z0fKysI)>vYN6|R8O?u zQD1);FyKHA(-FXMc@Z3ZiAtBkW>KCjrO_T!Y|kk8q}mh|IR2F`T|#8ha2QVe@RJU{ z6-?D~I3}iHL6YyZ2vVW*<_6akYSj|e_xuKyVlc=9W=9+ld;oJ7Z6HFErjS!%8L_^{ z2QyS|RU-;a`w?<>EOWSn@{RoNQ#eOz#pg=EJn0V_Lv`E!j`#b{{r{>{{yK&T+o0SH z{{F_Mn7%csLEl8C0EjfRuqW%a*Pa0RH>-9EfsOnoN+f47h*MH5ke=<*1>);-kgscY zGW&_4PK||is|k!w<_BNt#j5^o{R<TuMmd69pYHd=&wU%buYSI7*MY$FeYmKH$4pn^ z9dK#_adveML<OY;+O703=WldtL+FyO{hfYAHiI<-na;zQw&Aa}ZHE`|i-H#m#4Jd* z?~S}PB(NfMpg6B4ySOH|vl?c&2~>@kwk$NYC*E`p`)u0eq3W|8`}hqN+ZsJJR9Y@Z zorTMEg!4+oNP7;!fG&0O!)V9jQ@_4f`0YBZ+l|_Io+hONgQ!id+%NC9kJs2(XSo%o z@B^v;)oG@Qit(|DEj*K|2R|XvNZ{a09u3mgAaYlZJJ7Y(>V&iMT8xgd8+B2we}bIT zscgG%ENdc}u@tX{0-Sq$995lu5l*S6uK?Me6yCY8?}E*pT3Kv^dV2lYb;1*Qfsyk& z=~o*z9k^{W2i_{va65OR`@^#G6``iIuLo^e6%Kn(P?OX)Srl%LIyciH4-auSjCO|i z<IG~P?CI2UxtIC56zcf4>6FP$Gv5wwkKejoyBrlxLaoC~;KKKO_LB<k``BKlA2}Wi z`M@`h=3gkmTu(j~^jhodZ?fP6kMC95<b3D$0Porl9PSxv{<u5qSX6t;{uffpk3#uX z`0AKS>*)!lkt1f>U+SkF52G_?e&qm*QHp^Z%b=2(;HU2a+<f3yJIo}^E_RlnIW3Xu z_&6XwHEM|Flumw;Mw*iCEn19SOuwWLQE?$rTAR293?T~M0`T9B+CBPSB-)V+cI?^n zDv6}2!(V8C#Wg?s;fY6G{lU>~$W3`Wi|6f)4VIhJBh-e_FXhMlc+1}#%ok%l`hOVc zpTP38yz!@<QBo3GS8cI5Wi0U1XNIc{X3U4Uho?ek9+Yd<@~)+Ssa`ksKO-#=n%o}E z5$Q}Qc4YnV`*F9KygnjPXiEs!?LvNg`1e{%BIru{#;fYM$X`98R9$yH)*iex$CZD4 zn{9EOGf-eRR7x8+0n0zv{Wb|5*{XMr%v2^0;^jruo<kH1?Z!!F*FYyy;m~MkT*9$f zN-7FvfOfDAZ;p)4h6za(6;v0Lp2$E5m0d^|$$;5Y)Z<rvipyM~g!3LA)A#&?7>ttO z8|sYxHWm~7*Pel@C-h3jK@B@nRRG2&*h8aih-kF@YXZJcczjQ2n7)3Ge88$}XpF@u zg3cA%V?Mkn3kZRxiv9foH7l(Eh_`_02+Et<=A=YR4`1BCcuK;iSKO~n#8-NBc1tbf zdhQBwmzZA5f~_T4LQ@X(j6HZHq7H3b@j3m&$3p;5vA;C+9LzI`GO6Uiu?zZCNRjVD znPXgt{&^-Xv=47x1{EWXYms8l(*C6UXKRl`R_bwLNy$Ksz8=$q1iz`E4+u%1y?xxC zRvFqX?1ZrE-9HTfn2P4eas<C}Y<q(gc)ks+Z>lV1-hVW`&>;36>@q2oJ^1qvVT)9~ zy`O9zjz}K4i*e0p*tc{q7I8$m0U>ZlQ**0-)^|O1uj+C*C|H|$R(f3vjDr;90(nar zjyc($1bg4e;LutHc>*uQCZGkmlAWHd-qnud9(u@LkY}sF##iR-y%gxg#d9)*_`9>b zQP(2WUmL?g*^vwBQY@$kStb|1S((?k)qKAB<hN6Z^`!)Qoa0_EY7{u$UzBU8SQ&<P z)|b0v2Sm!jf2j;Ix2}QEbMFVk9TZkU_oDbl#BGU!C7bj`f$a<gJUJilnC2mXd|}Qv zSm&s1De<GEscvBRM^`q93}l4qvLaZ=O#BzZ`l8tBdAJf^E}0ukqFVtV#4OkD_=ERn zqNf=5#b`oWh!-I4aA1tU{w_G#D%y2;zDCwEzPX%f?gh=`L;A9q-eab2PH|^<P7nVj z=-D=NWNhOQga+SFa_PakCeW*#?=E++stPi~Q(YDM_@*;LPpAXZc&?8cPS^aQHsc+@ z11EQC62o&|g^J+BUQDN+(`|2Y2*50FWdGj!te0fJaMnEiVgA;=HPjhtTrXno>LyHl zweWAB!C)hc6SZCMN?C6w$(NjWXYBP@$$S=2+=%(Ea)`}fwg1vnCg-n^@}0?f)v#H` zUa-)c=Sa0QfZ8{)L@BByEGb8=u0<~?CMqsx`o540Ga)32mR~;4%`20`S<claR4grU z(ff?{T{XUY8^QMO9ARPXe)ITRkvO->Y&1mc6G};mhGywNv3DGCbMpv?dRW+7xLY)q zbuc3_&X=(ijvxHHtLasfSSW@C(N^!&W}^R>n9jPc4G+H2E5?KUpE;!Q|9D>I1*IRp z+&u5s<mD_(gjG=}vCq_r=wXp!ae-C7uTYA#KqHT~hzdedsG@=>0}>tKrcjDY%4;&2 z@sFXHYv^~>C&V-&CX(9<X*-)jdB-1rf16)y{PtbdMwCzMxKGc(2&O@rl=CqIbr{y~ z;(zK!GPgl)eu8R;;8X+&yL-h%du3lUkv5&DtD>Zdni>MXdx4l_F^F`in|lT4KJ6wW zE~?zI2X*fRtcOrAyD%O|FAY^q-q~5Tgt6O}`?t&1b-?Wx^e<z_3NVORvC$iYXd1Da z#+KVqTUUUUW2xT;;GC?u<-hOd-|m@3a*RLgW#c*<{K5Gm)oPj?<OF?}5_B$^aj+0j z+97Ek^IfXqw|TNg6WFuNfJdg;Ii=*hgLK7uH1xIS#&$hGFSWKbAZeoyHi%oBzz~Ec zyo3%6wNQ~j7wrkO`FCDg<5hyTL8FH7B(-fzyB--bhf5xDu6|aQDKIkS=7EAlo7p|% z%HTYWPxvVO_R;jNKefMoJCetc<YlEA8Hzn>`ba<(>|~)&2sYWWZ3E47cqow$=x@ht zEDfH@-u4V1Sv0Y_(fRQ-0k#;}m{Z6$H9cvTX2;b&@X*bbDo>#f(RZNSmJXNZ-8MAP zBit~cx62}96TsCx_%Zs|THQfF#n$h+J%n8jwN8W2wo&o;#~YeOE%I^Oo^`svTkUoT zwzgd0$#>3yt!iUm{euXrghT#iw*JEBDSID@t<liy;B=dZ@Q0f|Q|?7V{o>J4*NFwh zkovODD&+^PDVwWZ`SG?lHqGqf&=RPVmBAlO;0qkhKhSCxcJ}jSTGQM+C_|r}9LHCo z7lLH{_$dE1CVMv2nn94O9(7EC<&unBs_r+UZN0mr=gA%}myayUtg66%UKp9c2rV4Q zk*g^JE7Ns_gbEiSzLK)7cxHdmwMb<Hh-%Q<PoL8=dCUhIX^xZKFfW3k07mo#VRNjZ z$O2Zj!saH@|A_r&aF-_Udl$-g_MG4~NTmNhHU6+LJlBlTNuIw-_6Qo1!6!(moE#J) z2wYMXVW?7S$=G}PIimx(#l<33#Q%q@a|(|%+SYDt+g5jMvt!$~ZQJbF>e#kz+vqqI zRh)EA_Sye`bLyt*soSdct-0o!?-+NEw|6c^(xLA-NJRGf!rO|>QKWp~&04~s<|hXD zB2wu1sQ+gx`w$dMIHLw9{+gR7e=~Cva#%DCE0XZly#m|5GV$yvb8>;Uv7{4^Mdxz5 zMlIF}K&sAy3=_>*U$?4>l{uvT4CMeYIa&zG9|~bc1eq0x$3~9+=_4fxz|lhOL&@?n z=`6<cNu@;BEaaeF{s?Z-|5d;=3sOrk<$sRA=x6v9w*1)E$WWTxf!XD;e~fHHc+c4v zv4O~RO&iHMI0<LSi$3g6YAMV-O&4+0;mD5!pdP&Q&Dh=?+uDi4U3{zT4e2#Fp`pr= zig;(<HwSkq(=KZ1tdf~fZ;4Couip>rCxCxsX(xn^2i$sU<gRv>cKKw#JVDTg52;&? z#l;ZV4<`*!8~^CSipL7nXSzD^YDk^Ck2Sfhp4ZOY?Byo*Df7F|-&^)5#>JQtE(1H> z4Y7sKnFLi)SmzmY*=xp*ch}R|^<7tntfGBK!VVUuq1yrcY@ImtHvYQL+BJLp^pM`y z<;j#E6uZKF?BHZJx}sBPo;^}xYe??61)sJIZpom%a?)j;+tg~6_BYq;#1h5xM+{g+ zGh44{W7+h#_fCa_&>nKzh&Ewe1ORL?GtMXa=8bw&q82M4tOVrNPH*4zzO=RK!Wxrw z63qB?lZ)H9<b2db)o{9Rsg^7R>PUB?cSk|SsG4M?9LXVF{S4<`M`30B#L~S91hRw7 zD{Se*;)uPmaiJW({VUCd0a}O!JB8@0l-5unwWfDi>#Cp{fBfucpS5zAspfZC?<~HK zOOZ0g5A}{qur(*XbQ$gsJ5B3<^!3GA0{t>W(*eWEe`gP8J7)L^<nlMVd_;MKJE2<B zjm;4%8v^Un@ox}I=RYxey8{{34f*K*0jFU~U>arN(A)ps97yw>d4&McE~)?RyvuAV zfKOY0GFSaQ{dnt5%{TNHyQxGoUVsw>XBpeBZBLIr5i90k4A*C!^lc>@No3+*B=NU< zZ&vK1x|?0CW9yPak0U)Ms-l;5Vp=HdKq4GV;8))z%XlL>t|}%hbqL&04h>iTQ_5j3 z&owOy1D&NxFDjW8h1td{e7KROlagyiDPk23$BPoJs)2fBjDC6;zdElMhEgj10jB#g ztOKhKW7>fV3kD9Ae9N6hgxFk>WaRk`nF714`Wib&CB${lk3^6EmL83L2Q<HORlm<` zeUN?z#l;d|u;9SRXe38+1bKBTRBP%l2!<ybJNl3Cp93M7^Fl)}F1NS$O^r@WO=!QG zxlBI%2}&ykvM+v)pAHC3Ful0T5H|?98j29)SQbHSzJ)T*fwp)TI)n`>GJrKKb+SC} z7uaronzrYFgbNJke~qZ3s6=ynlFkl+&*GiN2;TFgD5QxwR8Soctz+lC3~cbNr>?$p z;guS|rp%CVWMOjvXWrMlI`d+ov|iD6L$Gik=$bdi9?j`vQqf9zZ;Z_8s~Mq7P;ki2 zKKsu?=5*%uRLnZBE;G+Jn#_ux%uplDDp8r-o47as*;>HLe!(RRK3&lP1g>|g%@=;K z%z@c4WuiVM@wSQYTTttGd=2N<7Z#~-bRAi1ucZQaUBW&+OoY9YWMY{`^**1ZYtNNf zm<@ic!ns`RtCPv@oUpkS&s=+EtZp;j_xSjz)m=$sY|OW?6Q|8Q?QoNe^TWkcf^WW> zdI=p}ATyPrp0J@*9rE1tX4<HY*FHrzhk2YBbkl2#<hh!c2ajEWRY9Jw%}OxpSUg{_ zR1+N4p+K%B_iw}33P`fSK~T6En71{=?RoS#dR}~64hp(?W*^OGUT1c7<i+X)@*GVq z-sFGGSsS!>QoG$ND-=@pDmRIo&c%7(A<eTjNkk3fy=2reUDDDm!mT^xv!1%#w5zi` zy3;|<-x<2z?EvQ-xu8?1A}%7s#-V^SpD-$dLCeS)%V6+(;G5-B9sMu4_yoD9CEYag zPWsznVGUhvW70XUPf+Vh%MCPrUUGh?o0GF4YJu|FMRs%ZA7z&iH8%-9RZL3~@|#Dy zWMk$wp6m=-Dl9AG*z<M@x_UlKfdLL5gOAKM7TS=|fyRS#ORokkAgjG!KOc)dWU*nI z-Dh7wB7Pf<hK;X4|El9|o|UFG`9K+;zax08D)v`17l}<#s$(&e&_P}zFBOnYz%ch) z7Bzv+zX*cPfOtb_!9-V~Gzt|(%@T=YG7<>YfjIf~4Iae$t|Y%p${_MA?LsK1r43E0 zM%I|drfD;i-B886#zph{_(JBe2p=?BpOo-_(!&(9Gn0({!XKOu_wexXl<*yp5ME5* zWI{_7Ak5UQ2NRDsFrxo|Tlz;13*>aWLh)bU2Q%PaaBtoBn*nn>R`%kKW>j(l*R3PE zj)dkx{Hf^>V+(CP$Lanbx@AN}@Gf)5JdEc7hdCfEOQFQ^aNS}6xWF$Z%4(ho9*X<S z4<mFj){xUvESLbB!w_?S8cbXHl<GDuC9HH99e6`8$n6-gYc3WlS1#g{pA@<r)#?j0 z9j$9~C&n#9VOeGAF4c7>;(Kqly$n{TnlV#jzc(z(3ty!dqoWR=Lrn851ZF_KJV<y~ zwB^U|8dKhlYR~{)3T8<$tD&(&7Lzv;1F51cn}6`6)oG}E!RD&sut!*0=jd?S*zX-V zrY*zo_KX13hm>-z5xMRlS2SVQYK}9-C*d~NLB@?Sh;~h)yav+<UlhO91y6WyKOh$J znW`!RbTGdKG$D=|UDFqtc(z#t^%8u(Be5v)>;lw_hGv+yG!b1HM0W04WG2Ojdz^Ks zp6`YtHm5n^`D5Dq+E{0A;P3Hkv@#Rkw{FBBge-ivd#?15C!7P-C%b+VanSiCy|-W! z;0_8H$p__fYL4ufyFKAHUF7cLK74F*oV%)MR-isjMwie`k2k#knEV}3uPQ+({Ctyt zAI&z-&XkxMp8Q*SPMEF)4()4$#dZ-jyjdPb#Z|b~?FV~KOG^bblnCHCIsSl}r5s!! zGnSF+M&$Al>LjB3c)Q6=p|3nYItyg3VQN97@(Z7s2_)j(jRo(Sh{6(4s@plx=eygd zHQ9@F7x)z+`^|QEGFF6#Y~YX27$=$y$^OyrGD5r);6vW(Gb^$(R24^HJ5^SzZn|d` z-HKNT9xkyYWS!k~q%#i}$~>k^mG4_)y1nmQceL7li#WCOoj5P_Dv_{Qv(3v#KZMG* z&@}fJisu}LeCh_iUTs2cRd%NN24$|)@H)S{?G1ENk}gqo+|sv7yr)p7h`O|FeK&D> z@M1GCAFGtn?X=4!LJAY+$)Oa#(^_(83w2`|o5A9s0i~H}><O{>KdAxb<=9Y#dnar4 z)@4WSL9)mD8Iz*~)pfWPHE1Pegk{y*FOr4#g&)ku=*m(#VP0s^8i{HDM4(RYa_GKy zE)lR`U%n5rkMG(J((+psIYKo)*8dihANNgN|JKd?cgOmFcE0bs=ZW$2g`2uo91M2S z-nbtYZ+u1F1k9bAQ>a<Pv!oOxvgwbf{lLhWkmT(j|Hedjvza*u5u%DDGVnj;XQ3ea zp(pteScgdXiv~R@psYdK4)_CfT5i{_CWuM!@@l8u9D_bzO&5omFluSkEJFvv%U-Q3 z94EV<I<?~ma)YriRj$_lSOehtT0XBs<n*I2Ll8KqZn7*N6-%y~)d!Y9nBb^%hNv7^ zwwhl?Dmv;E<lWXuKQAK1pO{BJVqA(_*8Ch@LSc2t=L>0E$q;g3P}Yy~05Ad?m&mhG z=_*ivNw~5hWhTe3wsOR|GN9qrH3e5}yi!2kd+;!A1<pb}Y6A9n+v3}e`Lp6XVoui2 z;7ZpQ!)8pgSN`!GIuKuTYQS7|nQxljA(_*~XE3vFE{9Yzh*0;;L#Bgs52y5JV<+CD z>3)tA5F0?(ySd5u-h5B9l_rTzbN{DG-32$7&z6pS;ED>Pf-^_7XbiBgw$9xr45+U^ zvc@aW*=1oTd4miM0EwsTL-BaA9>jaM>{xc-O!zxVL_aX?tifEJ`nXe)65WLMx$V}u zkKS1wO0Zi~VcnIy8L(M-7;5)7gn}y-DP38J7e~K0WW?p;RNj%dt!!`^{;33vMe0~p zfjbjCJK9i;e%dx1Tx{PAxeZx-M>Zmrov8_y!p6uB@oFlBcEa!!77Cr**Zi12Eo!Te z-*u%BrFs5Eoj~h};U8k@N1z{Mp#5fa3+VHlzOEHMtziIZdBhObs81nnH~ld2Ufxsx z4!*s_;3~_yHbOVFfmPT*7zS55^h+(HHhcaCW{*RBc9c|KDjv-p+j+xRH**8e0K(xF z$ql_~yGWi+fGSFNG<20amkxqWw~T`*aC+ygNtNm<lNILrY3F#4E;pa`u8G{Ii^C>? z1KyGqRiSw}NKh+Cv;$~yrjhxogdI1aK-=ITdM!vE#J2`C`G_Gks%Js(O5&Q|n+NBU z9Yz4bU-^kjoZrtSAOBiy$qlX@J?|YVPp0bjES$MLq^cIyK_~k=hrmBvoOMHU?9S;P z{{Gha0p?pr<^+G>K1tm#D4F2+i|D`1H$k2Oqvt5DgYWBSm+wa5|B?}r`+vtK5+Tyq z(!pTf2C1LrZ0mm8U%^B^jy5tx*wxgTNSzq$^#P=Uy_$UL>ej%>pHO{RDnLnaiGNDK zKJX<f^UXk_Tr_A@iVE@^<1oB^P^YWE+<nd3$o7EgW<U6LMz*^kE_fy#J?jqAsW*|1 z#<z%-=i*wb!CX<M2WWo5M0%3Tinf%;{6XMfd!Skk95&-EF!+dC#a(yO8%3^k#T^s1 zx3L2u-u#Jhc`kAHUHd99+aJePK;;h}QkBfO{QE?{6tV63l3l5qn@SfTPyT&nhjI<M zch9@T@>}^T_Uy8zFWuqB_qRlRs{My{DX1Y9WTn#QnsS$^%(yIizQw@di9lYvuhZAz zyAsM5nyh;okIuk3HnB%4x=ccZGsyL=@fMChEfH3FkSQy(VH{FVM_XOJFs{F)a5Q1g z+*$rB<jbZHGe3{gLMg%X(kAxHDPI?{1eC^c@qreKXM1qlYnkH|oJ?EeL~Rsn7Ob4s z9q2sfa})P4<YX_JrXR;aECAZ6?<1AidzNybD1tlY=KJ1m@WiA+I%(Jf#(_Apt+l4| zy?c<+FDN=)i)5SC+Q`7{i3Y)5Vkp<ra1Srq-4j4hY180!%6$p(TSrqBS_MFT!=3DN zA@uam1Q(9EfEdZj{8pIwH{JetgKvxFJWP<zyNPTo<waf0tGUcaoM!B^s#)WLKF$dM zjE8yn&r&!t(+M<F%VXrfP$|3q4S3UlZH0_Im@*Y_yYBtq$XqaQj7hH<yTeEFrpG+d z!GF5OwNV~@#r7mL!(g=s59+y1tDQf_PqJ{E1reZw;!rI_@qk?KD=&Td$B_y?kV^jh zxJdG_hNu#e_pAZ!7Mi4W8XOK|wDCO-@+19)qM8@)R%Vt{i^GFrsro8e`S&fCEbc#< z9{I&T6Dr&!n@_c;)0WNI@%E`Pn+VL&{{3}{3-q6@VAg)iG&eLX8db0080()N7nL>K z?+-nSjLJ?{h)f9JV|@NT&@|ZQz-xNl6VYn$E3d~W7XAL<2@P&uE^T0nKQ%tZ+&@M; zM*DspqoN#OpB#}+{d<8JfAS}IfrQM^yq$vb!Y_oxh5c`@;)9mV=tHAIJUB=;0-g?m z@LPs3H2fb?=DhN!pm2geD7+}GD~G#05vZ`fzCEl!EexUC$30I}u8L%&rcq(cyGvr+ zr|1!SZHU$a-QkIPZjnTvc(~*1i)4tvFQh(1Iwcmk!p!L4^G<@91hGYXIV9R9$PRGs zT0p&H*L!!31M;}J9=~>NXT`XcS^U}poPoxCG{}Z*W48u<rvd}6de2S%EoP`sU>$(B zO#-muYTP}xfnMDcm7X9~8Pz3Yq=o22#_>qY9O0?St>>N2PerREy)TU>`%U9jL|hUG z8b{XLov%Y*dfnF=aNqjCY(sZ#TUNyj?&8OJNBNaR1-gHPfOQc^w)D;AN-p8ch|ifi z=T6#csVn!;V3rNg_<5w>v-dIdcyvDS5L5g|dRF$C1CDf8kfOK$18Q9p%rar@4uOST z-2BpcpdX(>;nunXyc0dg*!Dmli;m_zPko16Z}kaDXyhwmdU5U0L~exR_2K#nb>pb} z_|Mz{dXP^EaJke9chZ}|Kb1^xt*M~GN5e_b+-J$%J5kSbjGnSC%&xvJdr5S1M+>YC z-SDUd0UCMTgGrbdL0zMN`9wamlhHy(C${MFPa0oJju{2_j=1>f9)J+0CPsX#n1O02 z+!$vMNjV>6Vx1g!Y~+!t3G_RWRKXa^H5kW_>mx5F5U|h@H&w3>Pk?n|V>hYiLcc%; z?(A1Efix@U>94-58laFelg5<@ea#Gb;NUGvRzIu8G_Qik7yjUdX&rb`*Ho367PTu6 zuF(pN&q&aE_T4J-XbaVUajf!ksR+-jS@<q%ubw=dQJL)89#{qIW5b!Z^c@swybqBb zc7#U`t85u^<ij>tmrTVfZ<y2fOyg)>0!@iMkB}Jo##wI7s)|}CJbRR1T)k?CczN3i z;BA_WWR%us<b~4ps}U=CaPsS`mUXU@xh)bHsLLA=su$Eh#S+-eIZ(^U5SF22-*AaM zW33XAmzSmk@geN3DQ3rq#R(Fa_D}jlalx;15nU*!ogpAc_uXe?)@L(**mnPzym&|5 z3{~t5e=`p?ZdNUGZiKmYxr2FdgulPP`_8LS^v^I-2<1fY-y(nC4fittM;Rpu@!v_q zZ*2(If3zXs^%VaZI#fCn>bYWZc0x!08T>ujn^Qd%Rbf*jMW8zzdxLVG6j@J#PJWJ< zF%iQ?PTWFEEh2%wL~fn>6SC7#8x4(=WnW0>`n4<s<hL?0G4-5*uOiRr5_Ae;0G!M@ zLHEAN(b_8=7}0Q&-kV0#K47PtLZKcOB80*-Wxfm(+})ngeU~5Z$MBB`MKyS7S?o_J z8-f1ZP@)>o_9P_grYJ!~ftKUU=r9kHeOI^w`c@A>swQ-Q=XcBoyws0$TTGYv(HyOs zF@*5%&f6V-BV!}rdEl?C;+9fXQ>FeKw*23LNokfFlXK(?1sebb=w=;zUs^`wcNRrY zdCjdA#I?w1<r`4xVmvF0_+~4gQ}%=_RKR~0`W?^feN4Sp5k!YyI0IHK;np|dFq8~s zYZ%s-05-C=34X0Jer_Jq6GVo&Wd_dniHy~FK5tB~Up4zU&6j!w$-2}qk8sCS%)#<T z5yroJy!>!L+Uo0fPS(CHq88YC?AC|+yloB9!|z%CH2`aP(M6WFzwMN3szcn1I-__< zyS7ctLD%Hr9085%C|Kk6usT+{W;<8cZsj^Bp;X~HVfy}lgys;h;N}Vbj3!))LDdZA zgB%$U?otuBy6#X-!W#R4XJm$(GX?fY!{op6HhK8YqEt-b@^TKs9pu=IV!kq1>U_v} zqm0KFf3x*M!n6!)8y2Ek265=CzH)@;Ipee*b^hn5&{YUK_UU9OG}HdsgKZ-A4n6-B z$<8lc>!<_)MbFA3ZDu!%d^MC@AwV~25g5w(+;>r)t{0GVb^u-q>PSz>VEQ|=U4{V> zI>yiiHD@l=Lcr1Ac9>i}!J0Ktwq20^I7o9q?w~W<*sW2y!Jbp+dX4Isd$6VaA7NMz z^zSS+fuPvEv7X+VH=;e&Uq8o0vl;?8Ol~*~uhb;?D~GS~?z+W;k0rn-O$0Ih`8&V= z&u9gYAXZeaXp7pCq4^0BOceJ1r~;%$0!gsbwy>K#yiA<R>RZ9{?%O}vmq*&yUtT=h zU!oQejRXprKL$Ux`P$Es7RgyUsA&58MYQ+M&KADl=rBLO??{P>zeA}1x2pSa^A-(C z%8kSC>$tynHt}x$4H{-sE_ZlBrR`l{_3@)V*xbSd*RvKU!xJSdNHGHom;bHpjufq! zqEOyQPe3TwU+&jF4Ki96|4PFmTx|0eAhS)^=QY)>x6%M)JkNy{@w_v6v#kZ=Tj0z8 zw`k*cR>F~YUFqW)#lR&~<U^pM&$?^BNu2ISgX6jyNR_prAEoYOu#c4^ckWB>PQJv) zHLZC6<RzrG5tDoGPJGlXWBy>Ft>!Ii+FF|lpadO8hXIQ(9(qO85eR-Gt@-}%G~C$} z0GqC`T+^lRED+{tt)sKzvfc0!>%tEBSCVDu#4Bq>inM0#cQx`cF^-&8zhN)&gr8Yc zCyzLfL+mQ^Jw9))(E5upp<SaFRP(*iM}^W8w0vZ6hAXi**$r?U;nOuqW;ZZ|g=Op9 zeF=Y-wYJOGsQRG<rZrxT1(g?HZzFN>2_e*l@Pvh8(2=e}a}=lZE0rj%isG@xlZehs z_2C6Gy{qgOCZm}pE~gAZ0P7gLhnU>WbV7Y8lxD)Z+=i9MROd;d)cMJX`Q-fuqqI?% ze|y#k@6guMeZuuk<;$-6)K2}hj)mL|_eAV3PW;ldlo~IED?zzeh$-tRKgZ@#EIXfu z7KlGtMki~#HEMqEWLXYgoR<+n+Ay)XHM#HI)LX>zC+>0%l=k~neql41{DV~g%3|Kt ziuMnE_l{VEBb<$d2|L27q=v;&J8!LZaCIevOOCqbn?i|BVzzr}q<-WeAQH_%jxeoH z0?fwMjEB`q2J#;i*?^7BTX~PI8pkHpWWuzBrZG_mArTXPW&GCi)K7T~q2OM(OmN0C z2czwrQAmEU@ro}Hs$*E0j=l>PU+bnY2~^>M%xpbi5u)vQcTzvzrXKJ#FCSnD-Evy@ zN3>?xNbAx?u4|_W#S#3nrVB#ezFX#h&XblU{0_BHnta|GO7iV4Du`kigHE7ar~2uG z1f>3<Q~kn0V>TNeV;rW93<1gCH?`kol8cLjF{`w;{RJaY<kl?KAYc6SX##T(19Jxh zbI2iaOMHfkDIWdZi2MINx-W8XHk!}GKovx^q@)it*G*w>Ha;UJM-e>oKN2C&!Q>f{ z`+Fd#+=`=$LS=&zALxhVJ$dHq1tmoZnw3U^SRu*_W2p1wMP)RZXM(W=S9~A7gPLu| z-p$e7W!AEX2gj&*io*d&q{9B{n=ah5DM`3X<WkW@cZgVGy#-Ta-)TnqFcUWZH}*g_ zM?$Y$aTay&Fa<Z6J*a^P&3W&YoC64Mhy8v?kK%p#CPPOr@Y%AdTEIPT;$F`QIL+w5 zC1>Ib+P(fj2cnVxo1=;E@69&_EWj;SII#B_t)C46`0GHGV<RnqCL)IoF2d~hszze^ zVyJ5-JE%(AR`pKx-+zFJ5#D-#XqKj3K>mrVefQs!mQ|f8-csKiy?aoGlEDsi%=GwU z!O_rBdOtVAiM0FLiG1M;_<|k0v+lo>)|y(-&@o1FQU~BGqY??1qt{N%Fu~UkDtrd0 zb2c^~dk!9q{BNblzfI1MPAM<e(7<esZc1FYlWwLcujJUVfZg5{?(5r#6yaI(ac$7f zMn0r;)e-b1hWp6ybEDODWS7qK@+Q+vY0Kz)ol^=g`O5U$`mhh#Z><`@!pF8X!F#u- zv$)n^CY_9?k+hqAm+)jp_x9Bs*K+JVV}_=ajZHBg9=IsZWi)%rBt6frpIvJjUz$qK zb^%iFN=Mze_*X0Bfp?zc=WO4!78T&G%!RuA8bc=$a>AhyJ(%Xn)(^44-S0`N4Hto) zQ$^Lw@M!;Y?~Jb~RcD~gc);c*KD5St7js3{2E@Y(c<ND?`U;StBIvS$=_Hhz=fayJ zKVy5CK<3_LZyPGH0&K$;Mf0%RQE%NUIlmEV&%;5+`x2(~-#!p4OIBEe1aNY!ITW#D zk<U>nF;rCJ9>LCnlme{t+4E_|ATkdT5lOIz&|S7qTR$v8ksH1EFc|23jlW<nNL>D6 zfhn@<x3jW2fxFGzDxARt51+S3y4e%T3P>o{39*5-y|-OIew8z<`BXo$1sH1N5!;u` zq=PPxgI()mHU`8&us6Ec5j<in&C$aGALR6*&Wx1afFMw{g|i>gOF<C{*&30^=tTC@ zo)Do_^-U6&-zi5LIW2!yu>`W_78rgq@Xk=d1yMLoo^8p7qQM~IvQnxwnqR<XoFULv z)r`scH)~HIOo+OQD+G9zG0#w6aG#{8<zl#5vGA!N!hZ8tBAkT)%Dc(D)U6Z6?+<X- zSsd~Twl`*+Le)S16$H0Qv+kY+4yN_BXVYJxA_-@g;T~Ik=&0HNqo(&g3DJ5ca<7Ae zlEJ}wZe)C}h@@C6BO^;MCdVP7r!!Qwx-WOeAtL^wzql!If>=X|(RdDDC7cbqu0pXn zy1v1|p+r$m&ebG9NgFU;T5Q2n#dFlzAUj7O4D)xklWMKGrF?<>Cqjy3FX4KnIF=Lw zkPN(E`L{$8_?=`gV%0O^2LN^RldpE}dkT*TX$4D0(hof8hU5@)T;2;3%TZ@io*N0t ze8|15&Sh4tcI$7OjmPam6?gUtWasp?t2P4lEQg$b%8W@$<5riNtgOq9Gw<wYX``1T z1@^rDLy1Lq?M+l`u9^{p8fh1&$=*aDI&E`&9dlO8g30V8(@}98qeqGs;bgB9?SVMC zEr1F@S4%D2$h=<5xXM|Zu3#ysyxmY+YOw*mt^(6(WJruyroXl=1=75GTz@{+p`$m9 z#C24MbUbt{r*)XE{CwOW9{se{u@k-^xaZkwy$fSN?<hD8)@p~W8WsMCSr6dfSg-pF ztIVsvgB+YIW@^XYiCW(PL($jY_;VgUxC2|nVs$7ZzrGgCg=GlQY*^wdcnLHjZqI=( zL`yEi6nOIk(2=v?F3spintt+X<q&tXQc<<G{u-<<`8C7lnX&9}y;D)0<*Y@k%-<Pj zKxt`0Df<fZaoxYU#M=gm#7~=9zhbVzOh*sx%6zO%uw7cpUN<(tmm5quX@xbxWS)lj zm4l5xJ&6n%Aczk<(uL9*VtYo%l^pVwSJq|R0wddV?UoI$Nlj6~maQ~4l%u4x4WbWo zWF<<wzVp5ibAPC*4EK^7CgN0f#XDWAAAX#AH5H1`-;oJVg+Al}#3u=0H3AIJsCKav zut)KC{u!f5V)dDrb6gfIA<ayCAu`pJJWG4mxw|G9A3rBUiCt=lcJPFlbJ2tiq=d;E z+wjMmB~B=Ic#1UH%Zvz$9xTuv!0P-S8#HBkf5F?QSA`bRh0AGh5aP{ynCxD+%3-~` z-jb4Y=y=aB+#N&cfukFS`i+IDdLH))%wghA9P=rNIyejPtA_^vOwS>&32T3*CMN^y z-u`G0dWb(gNHVsFQ`Hz4hFL16hdGeUXr+=%VB#zSk3Yhab|U-m9wHx~`W2oAF}_Kz z4OJOR8VK`n^JcvcjD#wYfc<Bmp1?YsxkN}oSSTFu;bOQWPY+JQDSsNv-0hEY8pukJ z64YzMBcM93>a6%@U|dm{dKec;=l9+Xm<+pZ_-%qtKk+$VL{PxT<javz=~q0cx2S>K z-e^8J^=sV`o90<zu)HKXDjh66!l)4QHv$b4D(&Jq=lmr<L_RF&s4u|^5#wPDM>aCy zr2&V4zeolb?JP8;pzH(cJF5Mm-|#1`qOD<|^X-@7ua^`m3z8}hDFkRbQgC!$Xl%yS zsbJr40^WDx9EaZTdyJA)m`Ff?ARL4arvWy~A#0nnP=YloorX|gTj9fIPC%<&?)A*V zO!UfBi<S~LDLN=@ns+`rHwpf3MhvXVj$A;S@`FkGoT<J>aJmSNXTA#FK$dibK)^fb zAJ<fMk6BX0g@SE7SDJ)xH!)3E52WA2gMZF+XsXMSuKwTv!lI6eaRXnq*Av&ZT@H^r z#~#6w(fPIPDyI91K)uh<mXFKeEF-*1bg+!orwlPyZO2Ldh5cC(p?#wa-{b7@F3b3y zL*^?NK9#<+R`=M$RV7OHkA<F#{kwMUfo9Jxi<Q>EP2M^|y&k;3)yl{31^r(}B`2-x zEhaf93XW<^*J%l1-_46Iyjrn?e**4z5*b_bUi2jsEPoDqefx9Y3&~uLXFd#9jQTp> zd&K4-%f$lYc)5CmF==yIL9qfz{(yR1pUJ*dlJ&QpUm@YgM=(@_1N?EG5nDC-t0Xo1 zhOJhAat=v0N}gF$(KRUKe(^X}x*WEo{Ckg1P3IV%K4jXZ{N$j9%L_L~TcuZ7^WyC> zDYF_B$v!&@<A;6#sgS6lB_~%N)a!Y;=#;<EsO=%>szgd#2^p_ttB~VfOE$70rLzqE zcCcMpB#Shv5$LW~r0pI$5P&V3zn(geqwE|>CdN=Q?CQS+hK9;VN~~=aJW0U%oi^?p zn$EqlaizjFIysU@;~b^s+hqDz0B(nextp52o~fieT3JR^6Kp7_va$R@T&EvY;Tj$~ z?!dLO-56jqPBW^vFi-YjU&aPoI-8Lwka(|FCz9-gwcPZwnE5&M1(7mGrUd8>+PJJX z?&+p4Or2J0ysJ=Pp`G^?LAT)}aCOktYh%?mw+<W7o7<D$VnL@t=n5Yo35-;>1@s-l zLpy`j!%EF({6Yr1l1eTc{lfbAg#9M3KCKb>t;-dVg9Nm)K9$lNeTK(n>BCBOu&i|d zcpXstk}xst-!jhACsfZ+eZZEP83|Vp<^&IRe~9>Q8*g7dphT~%Mrx>$TsE#ObC9J} z7j<VeijU64wBW+F4;%)bV;})r*+~Wbjr>`5MhA!a=2ydEq{Tk*9gB&=dk3W~*~Na) z|IPvELPz5=!=!$A4EQH}ao2~+%Dzava3Z8IW6W37BZRcY1|5NqAV6}F$|YDDSt^Dh zfQD4uIw@utjfbEwO2qD+qv}n5uVr?a9AvEUSzpP1DJX|fv}j)fnxnlt2cTtnKkUZ( zx+8<8`WqLTA(@D2S!f}%;xw@d(?kHJ-LJv@o_&}!Yn<Qn-_HOCIARH|4)KsQI|`cw zCMa55!RlXx{DUK3-svNgnbAtbw-WaHL?2+$sns;Z`E15WON;rl13w2RWNk?iA;Cm~ zUuIIn@(fH!N^hyiF{+ChV;w%$z{uaIjg9;92=e>egzl&o0k>bEE%Mh8hmCNw7#sfC zUe7xZsA{K80{l|fDmxcD79fBoW4Sc3VTqwh#5o4~dITP&t5!M{E1%iFqK!C~uRcQd zq~+(y%MylL*i*gy?q-O0NUcEdt4I4?l50oz$x9JNM>nu!6h%amf30aZkG|)ioU)f3 zylMHfH{9tv?)+sB>egk#I0Octqx()94DTNgkb0F;!>ntxj9iVI3T9~vO|ZK9z{T<E zlZ^L>WPiE)xvE%K89IcRE7c~jo78qf#!c$0PU}J5A3w@cpPQaf2YY=LVIh<3g0Pjl z>Q39D^X7RA(OWfmMOj;qoanY;Lb{kq(!mDP{n$Q?N}9jqmG*ue<~eMSqgBzHIda0i zxQnyoMb9IIb?KNW+`#qYO8cK@Z_WGh;17Nl_QQ7f1W8O9Z#3+iK#4t@bj_8v691%% z31z4XSnr~}PerEFK60|R5fbGg_<6OXx#UFuIR)1>j;LlAga7VCU&9Ff2eYLH;yY!O zKMg5XQW~P+a=I2MO75i3VQ$01gWq185z9pX3NpE{kB5}*CgVj_B@LHRqlf=9U2;3T zn!Re%Qndph^;bRQ8G6OK`t#tbr@-dEkkL<gg%B`iGKwBKD_Yc~bf)^!Y{!6?thW7< zcg94Se^jH%OsmF>pq?IViSOt-1XTZq*D{WUsM2pNP=y3+@V_;_4tr$3bO_Z><<Zhc z;!eCm@8xyp`*EPpVupyptq%_jg(6WlN)n$;96J+AcN2i3yN~{WQmXw|2T}Oobb7R} zj)vniMB2;6-n;A$|MCRZt2KxWe^w86<MOw)4c?$UJ=;<>T6*{BH@6=dyJ+<*E^9f< za|P3L75Tha!5GLzlfbzWFfua=?s$U8QUwQ`?W+$yLmY9DoB--PiHmybXDG|@-)L0~ zccZ*NrM=%_0mL{nm?#&=1=?gsog?z>*NJ)522YB}6|lehq3HyfxD)Q}0kABt2tOB5 z<G;n`oxtZ=x8s5pmR#2V?(X}(mKEZ=u!jVe6=&q5x5on&p`oGT409xBw&x!aaC8Xr zGT>w92ohxYx$fUrhM3JbIRBXfh4HUF%lQgQlCMQ{ul-)gsJKvPUElr?uC0Ob+go0K zywSPa_c(;bVxw_ZPwbaSR?_U19|)%W7zk8<63Fv)iyh!h%Kso@3koIt3%Kfm6vEtD z6%cUEaj|5o*8#-@Jy#aRz{h|TM(wK41}F}TpehO_GMobd_9!}6RBHh@tP-`)em6b_ zpf}Hbdp8eG1W!3GPn$MRSDxl$+Gm11is}c#{@b!HE-v@?DhpHPFsU5bsl0=$O0mg) zKe4l6kln%mJqTU15-knxK;~76?LZof4Mvh~@RH_*4w`n-<+PI*1|&q`RUm!hY{pH? zIx4~}ctuR+;jH>my6a4Pu2ZFJC@CYJ;E~P^8BU<}$)(m8RRqlZUA(;8PXWn_pk2dP z)AJAXt8*4CC)|TK*$YzVM+tA3sxs7p%mIGXOTMj=F0G!E#aFVu7kP4}LGsEB{3HxT z4AEE~${G!#*JszUPr+S5q;t47*nN3a6yAe!GZ=HB?}8JqgPctZv;y=`^2|FxoQlH4 zKvAkO#$?awRqm^z+cN$uFnCt0I#2fh<je*#^3K3Jh=*jn`Q_HA={(}ca;^|B+p%xm zHlC0TTk13Cce%7Y<rd@CBh<Z&;;**;4LSUkA@9*xxCHYI2qM)v#vJfA2*cjfA6UU@ z#|>#Ko~l%@&B@1fxCQ2jM4I4TF%q~k235iCXF`Z9G0fr~74}unJK9{2z;G#njGEOq zLBMdY`IQk*otN2{57s)Sm+!6V9j7ZIq$>;P$@z=0b0lB<n||m>xB=gFDO&~Wwm`Q{ z-e103?b0z|)R0fSgxD3xcqGWSppX@5!#pz6;f*0>M{Avy&!anJF$unm4};Y)L&rWJ zz8VMri<I#UW!?)?gXJh0+yo$wyJ@R#mgd-6**ATWSL$4(Lrp;$^A3r#bf`F|zpdyK z*tmM@_I-!U9mCLWZmE(tHRj<05JtLzit*3<fKz7=_NBJ90Wp633wccvo?*{lPY`*q zg?^I}S`*}uEWiE(GZhW-iPBJ)vs?o_{525G8D0#bf{G19)gpW^2Ey2)TZDSr3u<Z4 z@OPO3(n(cc#$8I5EL_!Nh`OMsJN9q)Wjj;e1snuU+Y4JlJhN5Z`|*J87AEcHcQR(j zJjm(D0hi-W+q8j)hy1OiVu>@7OKvZwz+b<9i3JGUasm(Ie-1uRu=`JX!s&mlxdNu) zmxivX<)zT*Tr{~^>1!}xjq#|%<O|OLD~>+>`wZnLWR;@v)P*v9MnDB`1n?JzGZID# z*#t*$X@|z~C%D`Q(|Dp{YCDQV_2V;CuPJf>G^(PjG6_%ebG(p(>H3QkFtT>7{^5Fz z2BC1zC-ES-8#T0$nv2CRTu7hgPXdM{v8(t`(nP5b&<vs^gJjfjNDP~lBQ`-Wx7R;Z zFtHHg(FWz1QVEhwe~{5lw^3u4KJXL0MkEb0gt7`)aS3xJnxD>i6(i*nPzZ&g!?N{+ zP+DevgV}bi*n&0)wvh?0P8%9yOOO(X?%-h>np_t5qHrq;kOCt}7OSsMi#!CpM+zR8 z?`=BqTyw|!j;Gi@ZOnsXM5fc$H*Z~~j(kQez+DUklIhEvyO!3KV7z`9W<#;)G2O7! zA<*q<-ODw>BE%StjTR|#k}NaK^=<W{DiyJCrNOyN?dKt7%SyXhyb`L)0z07F$P7mz z(i_lgYSlu-cwQiefO5=eb4H_EL3)_{**D7-P|KGZNO<bVc|X8ATH5ML2ePQTUwwb6 zeU+Lg`Um+91L#55Y%{tBPsevO-lgB%bi7?Vg%38`xEXsV_yIdw3uV{J<tBQbKTxaD z`q_!V07H|I%sLh$>$3M!$K1XFSE%GO>)*VxMy#zGfi$Gh=u}Zon4SnRM&UXPtUBoi ztyenH#xER|Re`u}L~kpZHPf2a+NeIb_mdQA2mfVHL_YEX(uN!P<u)By@X)N0C_b2O zWPJ9AZQ{V=yDY7;DuuFvzg#$+e>-RH+U~t!r*sU>@O5J#_`~`iS=ug^`p;F1qQsh& zM%GGl*T)mx`LAmGM{}OePTz6dhc5*-s4yGaFp$S9+71ctH3ka{K(@(+#|n(*ror4+ zyFQv~d4_{EXlSY;Cg|ba#z#fwZ&1TnW*~;*YIuQJz?<&vqi1;^ao~wlrn5`*%Ssc9 zQnFX5hP6Ybe=)6{vEV~!n61bYBFsIc@cDaa7IDL<P6?q7MgEUuE5mKSaug~9MiSNQ zxM*R(4~~T95>#GTaiGoPs4VVgi_78pQ!@D`V8H%sEc*NB83rrNpKhk|De|899k!BP zilwR-nv73Nk5*49)gZxiJ+%La)35W9Dav^&kdyQX>NsKm^qNU+vT!Z$_KB+b1wl1@ z0COxt8BhL!gLo?kpXKj0I~d)$djd`xsn*-vOn|jaq%Y&d-V_u6OONbPh^eF?K{>uS z^jow(^m%}$RrmTnyIdqk(CCktvxSLd1GxkNZqv?;I2RUti^|+$gaNip_$Bh+_@q3c z$WRJ{;B9<hA7=$y{6+9%za`)s4gP2Vj6hmcf6Xi_R<YyV-$5hD)yAPoRtbKm;Bo%+ z7y1x`jz^x!E=C%FDU-l@lMM|iin<!~-NGV85n}nriiM-%pnc(fuhu?%+*EPV(C)25 zYUW^x;3ASla<bwdbu<jH%Cw=VG^`L9*iu5kNK!vhp~*xGAjo*sIBGf21mnI`+}u7e zj}yU9lB7mlgffW-xR6!I<Y$||Us(TeKaZVw2Y0JvrShX0LI>Z<9BaYIdTK7guXbU} z+&f#rz$-{osj_Cr_BWBALi#k$8|>$R-)O=gxITFo7gW|$J8Q4%)mQPJ>tg$jDwT>l za$?~7u6Ncd*z9$EwVzPKb<A`wSn);O;Z8^;p(7_KptG-doa?&D7f|%XBwF+yG+gBv zRjcD7qdUAre?pzQ8yqR*=m!$f6sUPc!EtnQ)V0r1JLsyl^xJ(O5M)&c-J%24wp*^T z^3+QVO4isq^)Z>jPgd3gae&P9NI2dd7-wgwydJ=Vugh}K{M;pm#T}g+(xm_NQxH72 ztYC?$z6vhhVt^_py2;|APITzPJJA<bnQ&dKHg4>4)^gs2*IS}*+x5A)CSp(W#~%iR zJak-y;Scz%+)uok^%cPHR53V-O9B%iJ8S(bxB9pctM}i>vCgYCb?a5Twru=06Y$&d zs~uv`?J2=xqgx@E1}IjF_M?5erYWU6FxH5U9QZ(v6<&J3_RQN>18pKNWck0q>mQ%S zxy+udXzD+F)Zc~I+-`RgS8*X~7UofqS{fWj&MP9OE`?%{v3}k$^FStri(RJL)2lu4 zcN8wll~DTaW_MTI5KDI7>1@~h+Gf{OYwaNTlNYj$&IisFFw$dFdsC9O8xI>=<$Qhc zAP_ne(Q|Y`sn(RB3)-?FCVe=9eQ4O|6h2s~n)(>!PU*=0H#;bDmm_Uvi~W$`&`6Fw zPk6}^T4XFn5fMcT1M>n>2CFQlE~a%h?3?Y}?r5m<w~c=!-yU1o5p<g_xZaklMyWpN z?|q?|aA&lK*;*KkbwquQyqTWLaE%^CWlqh{%uXZa&=_a6EyQuyP@f9NRswg9{ycLo zy<lv?Yv#(1^X=2W_fD%B=w`yVyYO$d1JKBxC$Iz5`nAd(2bnva9bDh`vME=O&qy4- z0@goG)8MBRc?-GG``+;pLE|hRJ*oi~g2#8CO*g{cFrOe2{Z#-<zV$l+WMVV2R6Ay2 zwj6<Xqptx@iFjI+VO^vrOX{*r+ba{x^+Qy~9UnFx#VyA180cgsl_H0Svbw7i6EiV6 zMDnC0&^^>1%<qp{EfRr+?d1_7*O(nJZ|VDU+N7_s^NxYXB;KOCbZ9bADC4UBM5c7V zn?JSMjDoIalxC6dT2aqJ0*#aSXDwC9$cwruTgV=wllmQ*FyJ9k5_3ooh9E!fnG`)G zX_a3R`hhTyEvi2;b0gsK;=*|}I5;@m-QAa;i&^24gN#7Mgu{py$SD#@y)keW;c}Bq zm3xd1#&|`5mc!bg8C7SviEUB}MxHOsG7EB~q>{AZ+XvuQVU1Y`<TW_X5#St1z8^Rz zhDXQ7CS}eI%IzEF+w0I=)SPQLNb#mRI#R(n5xqs!<8o#M0nm88O1^ux(*$&MIn@ML z)xkhH&WHLvXDS9Hc@`@OAbAQ8k=<cGG&DXhHa;ycG%LLEI02of!PlQ3?>1REpsSby z%|Fh&vUw6wnKKAJR%XlmG-NM#+v-~%<BBx?%{J<<%!0<X2K6+|(GTu2Pw^76`}nDS zHms$b;Impg%+lTE{wAc;IccrFpC5(WsOdP8YeJmdw}rBVhum~3?Q}ZHQ?1)k4b%Ip z;LTsK0g9ary*;;bt$&q|0pV-`IA8A51^R;c@xJoYxIN~N|2xYE3nC@yW9#P!SD2&s zj9=rZXbu!c%&7n$gR7T=E_ozPcUQ&5FRivA!g#w)^+74^B}8d}bCbcz;98j#>QXdO zdh%{i&VO|DcAj8v_`|y!vUSl10e-b$v(r-OA_3~YJ<!LcCCdD(4nciozsEMcnB)Y@ zHZQe^Q_!*Ywjx=bJ-z8*)91=v?Bg%?-&)}q+YCF5LLKmI>wyE%t2H|prR#M`PfVY{ z0Hz!Uu!;Fe$br<V4}679PIDjO{*ytAwf)4{{HUB8B<_5AYXR#jU;FpR%jv#s&kMhS zsMEUcfwA^^W!7CUsfK)Ai<9ZLu%ep>bN6ht-E^~`ze0@M=zHrX9NtmOoMfPgv(vXu zy?We&gC`X5N1t9%k*~e-&!+9&IziTEgW7EwI_n5a9O?1W=o8emJ@z&#o#C?!ucu@1 zRD7=vZ<lv-((BuCV`UDkamHnR_j{WhK6BRDt)&E<_O&6)whrdWxfYNBEr!`|udent zD-iXH@|~@00TIIYn||k2?uXoR&yw|#;eJ|<9O%BE!YWtx)x=k;KX{5&P`sh9R1S0* zxG0cx<H4UH*8RJ+y;f6o9VDMZvPfPW!S~Vn&0d^w^>+eml-p)KsV~!@6ntG$VXw}X ztRsnX&2YJfzP?!-OK~{A3Rq&L8GAsESYpAhzWK!jUtIH)Jc@caJmU(t8s!5=h8E@r z1&Xg7Kf1Ruo}8}MlfSHkJzds;BM0Qx5U76*Ig<>Dh6W~vW=5n+92eW?2js-)VX=`p zAqg=UROPHBA)p~SN4}}ZX9Z;}Xb6vx<vn<EL-Cumjih2VSQm5RtD*m75ZFVCA*{s$ zu2@j!DPJe*1B;5gek~?WlkSZB5MwD~U=U6SFFIaIjwRX;K}JWGga76@yb?h@pG%DH ztSRiq!yRuw?kQmU%@JISV#R_XBy{nq)-edQWD_bvrKOPK#Ki$+%6&Hyw~eHT$Dx_R zDUtyF^Shrh7xmX%2!_lgF~fLdpLA8BERlEcP!Ngt)bSAcZMP>qwcze)aG*Ztg0OsZ zVIP~QCBc=&0)I4X2Dcv#46$TTK<6mqj3A$z`EX*W*K3$0J{=g1P`1c{Y;#kZkr9>{ zGIr0^J-nfg`<dTwg^UD)&;;UK$Obf=?hi0F0oO<vN0@tbRlEUu!%X#a#g`9lKw0AO z9A;3y^{1eP_+ZI!x_0I{bf3RsyP6{@dPd51>sWy9E>Ha*%vkt9P3K<=@8@Y~^EFUQ zU`(rXi&>7J_4cVc2-W4#sp>c$6fW1JEbn1*KAGgwexwxO)0KuA@K^R>#q9gq2&7T< zI=f?5Qse$n4~TyqKPhvF0*ejyr8!g7hsHc5HCLT|)vJ9ts_OuHi&1elm+2<iaTYH9 zEfDq?Aps~DIleaqskXVB)OmZ9AE-1v8B!#8PF(Pzr9ODGbb_?Y)^c_pe^z;JOK*N7 zWx5P-qB#xdrOql9Y{&a$Ue7^@@Je^0E09;R4*?KR3{rZ1rGo(<fe-j9sStB{991G$ zidB#B#*(uJq!-Ml8Uwq8C2;V;ZD%VN+0FX!pnwhR9g}@k2Abxfl;=oDBpSD;Y>U90 z#`iG4A0EYhI2uUh%|J#wVnw?f4PQ8@zbLNINHa04IYezzWPJbh>lU5Mq^20^1e916 z$c!hhGM20})hF-Vtzo^A_7&lvi3fTm92+rf)rDorboFx|0cd<~kPl8;_REVgx^mbr zy8xp1k6qY|G8{Wa*n8x63|>PQ`u5>xeQu4KDgTQec+Vd##CorZiil*Zd*tfx=+@6v zGNE+2Xl@=;ry)g7&?CPOhxRq8EZK*Gu_I%jV*1X~1J?TriF6uxSRbAytT<(FT+yp` zJiL(eIuNo~J#=HkOI)iq)`$b2!Pj*`y)g@V$~<eF1`f!$Qs8?@_Z<NX*2y9ZQb<r_ z3}$0*vgX)03N`f@G@#HR60*PF7zPW)1hyYItA8Tne+}f~FquHvocOy?wf8@a=-x-M zx)brD_UOVNff9gjJ}bw{a8+KFBa@VALqI|*@yh#0(USC$B!E;>`u@2i^A`sFnNPxs z@AnLbo)<e?-zrpnHZgH@Jtm6@1Exj{B&F5Do_Krenfz3_E;cB5GNP$DFfNb6hl};> z-=D*2P!E9OW*AK5g(D#q+-33B{FOcgh6`^s^8HQXvsm;e<%^nESm2*HssPEv*VsRC z;#I^)EXV&?{XzLfqW{5Aq@dzag`X{)2``c>UyTDvO$wm{X()c3mEWCqze$mpN&1D) z_N5UmpyOiUv?`A$d39$cBLU%JAQq`NZ}YI1v8XpUW=ogIM+09_2u0vNmL8FTkwhZe zh2aK?*o;e5=L@Fx@en#yV&%kz3yRv^e5yo0<unx`7RdDlNP(<C(hmPapTLOGDRL4D z$)kN^YR~mZ?&{Fs>kfi<^i03hc@@}+gU?;9{6`lTP7LhaiBEAoQ<s_3VwH=)#o`3` zE}uu4AWbJHW6QWh`0fUo&MJkWzL_7ex<y8_nT=w4B%cIN*n=}D^BA%7IQTqP73o^I z1dRQ>D{?=fWPiRRr68<RKAlx~b<!jE{dD`3;qx5s<<`A**ZEBE!MrKb-q%7pt`cZO zljn2n(GfTqDH=x}&f*<z6zaAV|NEAz+l~({j+ZndAwZeq6L9-4hCOb58rXfx^o;AS z;arXaQMMbu4x09{QYKnyb6t3h7YflIy!4EG98fP01=%%gX6G4vW%?5(3$=2F<X?vU zo}~?2A(0C`*m8=9$*1908buQKX^MlYef8zuGH~V3eT(14LsU`M&RQyd0-|&`Bp@h| z-lmEdWwABlUibs{>6PaavfKlt;q<AYdRNW8A}04JmB)w5A8J?F@cR7p9Zp*96VDoz z3SI>O0lK!0?_A}l`&%G0<)DF?Vwf4r-A)?5)#v2;LvoG@=#HoP=aFdgy}K9~<D{0L z_tO@w!`0Qf|C8i4E~uM#9)M&4p(CGQ1%L|<i?N4%8j5z$_(H?-=vVH$II@pB3_j)M zCy{KeenZQk?9W4EQV5hua-@fPBK89Go>u*94kd)c&5}8?z#GQJ3RZ@e^#Wfe!g&U5 zBChzf5@)T=Jg2hZKU24cGDgo!&E}_-wlq4sr<%78X{c<yqhZxCvV!Is4fJ4YP3yhe zB*#qcdbS@(wQMJZr7i6cC-%}fhVl{9(S6PDa%R)HKPAk^!S_3SP<x;PgmrE`6#waB zkoR$5ZrQTk<gH>hn4xmdu43;*f!Bgn5(X78`n^F8CB!(=E?La<O%J9f@j}z*r0>tb zK}Q*OfMom0>7CGz3NgmST$~n^8WonAK;k?-XN@Mhb4M-%E0RgFXj{F258uPEXtUo3 zX-%x?Y#PD}RuE~b%W}(T!5|)fllcID3*YrY-10wUy<=dcVYe(A+sVXECbsQNtcl&R zt&VL?JTWJj*tRCNZQDNm?S0O@``+`r`|o;JJyol!$Q^u4MV$OWrF*?-vcqr<eM*;a z;_vEsp)8b1IUv5=gdveQ7REnM3aM2X&~OijjviK|vL`GN|0DPd!|R^nU)XJTB=H9% zO||mI5RA^T+z)g?+1fXwMl^_5@mVsMe~3PL4xcv!R6)^wj3M}b>xbJRXpor_JJPlF z3FhQf)6_;Y)Z}7)%M(1-zn{yFd&Fgcp=Dsg)o34RBJVO1BEOPCbt7<(n7q$2DSTSt zl<b4YZi4nwTfMUp8Gg1~=x%}5(J%$<`bT^9mZvT8N`-c!QcJtMfcFxgZ_jjNqTHOl z=1b4`F<&c_@&!aE8(J;1o;IrW!?N#3967-7{NQ(ppeOp8pnHP}edt|o;Br!LiUL3f zZq&wsXyd)dQ+LPu#%566k?JgSx4*hx_@2S%(Nl>`Z)M%n*lYDfuBVD1UXzUxnJhI7 z-MV+6j+B_zVL`^@X)=Z_2W@wEwZ0CVfGGoDQ1cA@<B6{|xC1?j?uXV|?lDyqaqJBs zf+ZNMZ57M06FOqw79l=o29per<Fp_SUk9&kojFnk|07)yN$yIXvIdZ(nAQm88|*6+ z`0XteC%Jmd@ak*PJ-VlagOKx=xw&>`gpW3}Rkw3jgXeL?S_>vw8~YL-cx*NzuIxs) zKigWo&en20nD=9>nbu%MHEXW1-01vF=#%*O6BLq*QLyYRe#$=ML7qD70ECpeOi8Rd zkRZ>Asb;eM50fkB@@1jA&K6(y-+r92C&RLJea^haO^V0A4lYC$IX-g!?%R*Xw(A(* zeQ7b-u7Z=?g$kq$ZF)ZrrPd^D&z%(S*;}RZR`?wGFn0@koOAROp5!`pv<y(2ullPh z)vfI(+U0tfu&J08_;aD=+;%mXWb|7p4~!9xHT(8GSavvlk>558Zt9t@9$xdNp-qJM zP}4ZT707g?1rX2|`(J)-AT^tGpHGF0r=wvYjqY78=N|u5d1@tGy-GxS1flJ31hl`n zWfQR;Y+WIw4pF$Ps#NQ5*BOOzy*mZ6pF(w=V@*sWtitYcW)a)Rm~1PAD(C%lZXzo+ z_RNfhFj-M_k4jWZOOXl_<HHqLHFre^4MhT!q@@FX6awCi-XrSrbb9-h_OK5N;ip?( ztkgt7t)G7A;6kE)f58aYaW*EQ2~PP&CnnGY|F!|h<j|Z;*>ryIL6^o@KXQ|vpler4 z!Mjp)*NlA`ipKw_*sq?T51Uqjw0b~1LC4_9csC01n=3@$OS23m-tqq?NFI&FR|xxJ zC=!o$J&i8d)8kQDQ|JIASl5svNAjaj1pX5Ucn>B{SV97L4bY0@3iJf4;tF7*3)VFc z)uXMek&&S%qizM3Vua@Ao=JHP4AaLXV_`@@MTcj`@};6dH+QvI&7c>|2r4QcpeDdO z@^%h0b#Dpb=*<N<OxDWW#Z_*dHUhgd&8>1|C3hx^CMPV|m5Bcddhs}<n?2?rEUN_* zIpAq*dp65pAGAl+WQ$}&kS^-$t0J;7lD;9S<$^o$Il6N*9EVJBlA03MoGY&nnWW?F z1vn&}jq{?YAlG!c0lc1?opNvN-znZ!eWrpqPfwPH;VWorWWs#QK$mFayE|Sydi9sx z{@C(|-(R41h>W5Qx1C6z;FP&4Q-yvqn&@=SwhUa&>v9?mXYSN=<C^A}=q}GSOKif0 zzgUbu9`)WJ)x?K?6jv)K7{m~GyTr<{%i6f$$@?Ix8bTPMd2$fx2G3iE)|-jY=vJHt zEGT@qr&r6PgjX7V!$O05H#P`a*Eeols+E^U4($N)q@zab$zjuOxJM4Y?eTcM7W;t3 z9)iEHTP>c{R3Xo=0$j*qW}<)TqkC|HAA0l`H3QV3LlO~dSB-q337Np`os_-@j&T!i z+E(Jt+rGIsY>)9(JC|)ER91<O4EwIh=5M0jA3@nx!?e10jQ`_8=?jMKn(tqNf$Mz! zw|1I&UQjBB3h)4z7J`i&u4%@CGAH6|u)Lxb53gJ>TwLs56_ljH$ynqF_z8RdPc)v^ zP4|0~n=2<oLqlQ;#~v0cj$JuyFrA}3SYWzPecE6p;$`MStipGA{~qiirSE-3k}~8N z2~R;gD%g6fy5y{PlUTLW!8k%=jM44>Bvmi|F4Ccxk~QrZ?(_YrY%F6zYW^)%_si)e zbDHKoXSjKKItH-xtHMQ(y=Cp(?n64Z@<OGV&W`Gb;0L=O<(U=8a@mn9P?90O7%ARt zp?vAlY@tamY}`vw_KGU_>LGpKrFSrP{}}U2LilhP(1i{$(u73u?EcW}^HDQWdu>%| z#rcsU88D<|R8oglQ2}+Q6;#UWU-dD6GJB_y=<1bh6imJ3hf(S)!c11Wn~(6LI)DNk z?`g^XrEum5^;v0}0!!qH-}t+~odIh|9KLk<7nfHE<$JLd#Q-y&AUR2ogV+5M02KQ( zfGxDFT}zE-PL*r|<cLTk9XLUPM?EP#6DD!>`Fex=4Tlhl*oj<-P2z^Y1Mf$yLMIhf znIh2iBG+5pcueq$S<Eb2FpcUACKC{kGu3Ex1lLizm6z9nK?;=%6u@^qh2)3J!G9S< zKkeuhCL&DgWhbPP_t0*p_nr!^Q^ju8IAK1>?Mn4~h}F7c=)A4!>dQ`QzgukK9%qSS zQyCYaO!H@lV89f80DQCSf{pSP0)H#}=8L>16gVw~dxu9U3|32jFO8yy0QqO3muttd z1&!csrY!hjh}YSLd6=swzpq*@!^n;om&8W+?9o%5;?b3=t;jY}Z)MWhw*4OkVb;2^ zefQm|v4G`F$C8}H8BXsb$fg4RCMQycH;~)kSMs|y+x1k7#=6o%jmE!4s~W=nTfk*h zh3{YJHkfb2KSc{6b&EIkq7?W>95;FYES%!Qwz;v~K#l{E2Zr**d26oG<)0&{&lf$w z^8xjbmPP<L+;gRLTa2(4(p|pt4D|Y&Y(WZ<cz2JZmR}*#*HK{IU^OEFp3DKhj>>sB zSZhZ0k|$ku>BRY@`RLBWu-Fw*3CRAm4;Vn<N7XK5MIT56BFK=#9mJJj^AQ$1tACZz z4igT-sy5+HS4Niv%ANu=m<Fx0)jyxi#Q~Hc*P6Z+xF&h;1vrm`rIRY{X=V7C=Guir z^Xew>PZx__q(uH_6H05aI@a56YziP7N)+AExjc5Vt}|`VXmdoY)drbw0vMREOwU3K zlj=628wJqEWUvc%J7BSsTfR-1F`C@^X)EfW_m^C0e+ZfLHSnW8r|<VuO#`&<qEHf2 zvzUk~W$i1=bKFEswz6__#}v?=ZP)Z~<#J=CjQdybd^P_VERM$`oxl)%Z?#l#x^WUb z`X$*D8{8m5fcVOCK+E!(CO0?|qK{dwUe5Kb&k+4tD6_5F8dHV5uq(s;eB;_tf!>5_ z1;bA}yJ^G#^6ZI!?5xZZoDs3U*ePsb(U{*X@MFm-$>p0BCAOTXL<(;lZ?2VJZvOI% zs-Xfcu{6xF)jrUWGi1;nN|f9Q`L*3QWur)o;K>(O34K44HVFUzD=d+sRQ7)G4<{ze zdn2k%?53;!_ht-7#Q963o30S;SI^8oDn*Fy=a-ik$0*a6)O(KJn+$2?C&4lLA-Ru0 zL<G_d1qzpYo3dJ`6Y>!S9P9g}wUj8%aWu)<5^7q^HfnAjm`wb!izyB5I-Y!yBMq8F zTjK%;-Cw<T4!;g6_)wtAQ$QrBJIJ-OMks=p%uC{+1TJRB!rZI?Eg5eh#y)<DL_dEE z-e<5dS1<Ut<8>TZZKVCtWM_jyFgtI}2(Q$g*WvA>(92_QrTQ}6EdIAG7Yl;NRO2tp zwT1fl5p2tfe;K9t*4_l}mzOMR<C#Jmy22z_IX&z4Xx_Ye@1;`J80+<-)=rkkoYxOf zi;^gr^k50WD;tjFIOBS``fbapOJEkWfp)RYJ0oou%?6{5CSE&e$QaQ!&r7D-MLnZ# zD%8~;cD5mm-$_|#RJF;0HjMv-J}WkEJ%_n}0g(%;0gE=%wuH-moxS`p=a@UD*fEW? zd?}FV9y>L9mm}X60`nbfDm?V}G8Gy--_HcFmM@wnuIGf3I1Xj+cPFbe7=aJmUt!*I zt0M2vTv%Nt5XJJ2sXMjo>lq!rwHP<8&`L&q1i!4q5oJg@$p#{J{T=o8cWDEIFoaGm zGO1T_#stE&H+-Gr-xNmQ#KpbzxlKXBqfHxl@mzrhO}InpptuxWJU~V_*Xt<2$fR2L zXLDQFSSP7g6XkvCp2^kmW_HT*Xp{3;p1nf1!YfYqG_xj?t35`mUdMstOI$p>y`z!7 zN}fD)QBa9Vv&n9=$pK`sw&R|VGy~lrdoV8$2~{wgvmL+5ZgRQ#>hXT$4Apk>7GcOG zTJEg&45LwlClPKh)k1;iXGa}=aVLS+wez+F)xc{XQRu2>`!<A2AaR1Da^<BgRz*43 z9}Uv`ON_QBxD7Dl+Umy^3HlrXrLK;ekpsWE(KyRwTSmy*BjCP#JN7umTQ-J~31lg^ z@m_jTqwxbJ+oJPkv|ET7BE`Xh>QJS$$hn=_8fku~t5tCKG{2^CPZ$xQCCNBWN7IV3 zl^^HJE)R-WP^7X1Y;TsaNv5$$EbwPtrCm^^LQH4BfcxVK;khc!x@u{%6QOOARYR@b zd4XCLyg)KM$7Q5IvW(g(kS;X7kJmhg#fy1|98M)jx?Z3=hBQMlmzJ$Qku<_b?vB@W zl|yahQ&9Qs+S~c!=%!HP*iQ-sFh}WcyKu#%kc$?oM`@ra9XVe5;bz`M!v+#|hcjPQ zZqY!1(?9%6(JRFM;>*xWBDa4RbN?fd*huOFWSnr&6JL)IY7bjAc4{+O^^YO`*t?p} zy~<_zoX&)S5ybd$Z)pksTy%AB3BjM1m&X#C7C#zZLhuVk8nXha$_awQkIXd>tZf^; zXePwcmarlV>WN3J;bwEs`3rTyZ`v6$qe`rbe_iO)Jjpab3aX+kTr%Fs?XFo;sI|Nb zI~^ODrV+)OJ9wFIi-^fimXT%eyJf>p&NACKN^b0Bn4U#DeK}7G&ATBQ1vnCF_cKTA ztWkoNi#NW(3;n>0C30$@Bc4EK@Aq$@2=C<Po;PIk?mi0c5`oofZ7!g0Q*oF$K!AZS zB~Lwg0zX?G%)wuazff9}d}H=vBEcBVd!G6Wf*G6&tBTnRLQF8&MEE|so0#JhMwb8} z_1$34*0KK7RCKD&T%fY44P_{M%1s95V?i6+SUcy=cq(?S+qd^}Wz1G0P3NR6Tf5v( z{_uQbWU;pdp-WHxEIK+o;9B$yqJ}v*Kw>%n7l8V8dpzqpcqzjiYG1L!e`N02T5kik zuP0miiKv^@aWCtQ0DIjdCX`V!?;W>@B+yc%_ODb<q+4SD%>aLUB6%~m0UENO1?*Ds z(0SH{S$0Ho*W0t7^!@X%{RhU2*G#(Rk~W4l#(}HXV=Udum@?GxQ|W(?;Yh;&9?l(F z7MBiZ-_9`zjh-6F#H_h|D*4|kmtXZqL%HGo0J#va3pLv+)wAL}87LLyxAXX-e-T~s z`X#ps;NG|w6|w8tR&xMl>TWh)&He5UONO3aY_Rc<FR(!srh%uatHIEupROW@&{?wK z`d-=X&vcWRZi^DFnT~~beN9>Pq@c(;WmM(kfXFM627(6N-WAOK(#=d$j6TTiQOMu* zj8==ANO5yAF1h`qFg%@Y$LmGMF5$#+x;V19VV5+}nYh=nu+(1;39P^<$EA7ThIZ>u z*_nZ+x#)~wXrUHXWF2(KR6>Bliz(C7zd$sqkQZJ_+T;;EHMJ&cRm+I8m_I5*&MxxB zbyJ7C5w11SjZL!k^$L;}1m*JH{CKa|iC7=MjLdc9(e8dnIstJb(}J_VsW)3eCD=rU z>x?msgOXM)&?JguIr$2!yENOo!L3O^LzO!W!jg9)5MR~Pg<s*+OK6{<Hy)kV@#3fM zF}kk>UM$HRg`WX90_-DH(8f?5AS~o~Mo+@h_FNeN7a_=s@oB(@mz($Xj2cYr<l;j9 zUyrv=QFwqCM|vhA=hKRNQz?$9r-&pS9Kv=wbejtQD<PrpI^319$uz}4Iq>;<h*P8E zr#cIJK`J2Qis(U9@*-!jmHY3h3LS!IdY~isH#J?rsg2e<u&2fOdOLk~8%w~Uu?zdq zp~c41uzCTB-LN;t-gbC}2X(ojAU#cT+#uyUEq+}hzWo4px-p{rjw9V^cG}Zf5xv75 zkx&u8-?z*|a*nM7i2?5ZAfXqg-?zp7r*GgBsh_$DXr4PVLy=82bDT!B!AI<`3Q>W} z*h;tqh}H620`$WG^F&`tLMzw_MJ)qJoEk=3rBLkOk0?|f(2*7&XZT%hf?)yH%Ip!` zo$Kyw?V5!q$~)+XMzFFse7GPA&s^ugeh<QDIGY=X|1#(LK>jnWoVGE8n&>fEh`ZvM z(j2?#UPO8QgIQbj<My=5dkUv|I!>n?t<_uf9zpwyvo{vQ%+7?sfB_gq)PkSVd#T5h z3z37)qB)}aYI!oGgZl+D<VQSjdC8x%<vl=tmuQu-RFwtSpCLFfNX#Fx#N>?*ui4+d zBIS?L^~O4JX0tvql}>C(&+KdI{A|g4RMl-Sb4LUu1XI%Mc5CsYZ4><Mhr{NZ_e|Bm z({IAhBNEGYfM_MOrfd4OID9wJI_<$eKG&qt7lvPfYAi6mTKgB($Oz}rk?qUz!S;aX zlp(%8y@&3=*-KruSN$3e@{Mx&a@pzMZTbVPa%OIqwRo!nxwNFa+>fr=?iFqYDyPr& zI<us|?zcx-8Cs4%%XUh2_Ec7i(FUw!Yu?byENUvyE&1}9RF<t<w->iT$whJOc#b?c zi(EZ3ge=+EPO;2f=5NC^hCJyg-iSS9#P)-Mv0vo_TE|@|!Ex8U@QX|_o4?h$?p_3Q zs;dS9crmpwAkF0g>__PotSD*j0-{6o5|dOW{V@<erN;<2KdBsDCJ#;1OpQbd;Zpo> zrJI`+>zfAm<lWtGxE4p;HD(@D*=g60hdZEH14*$lBtp|eG00`ikI>b{a*MQdri$h$ z^w|9&N_}w!1<Acd=M6rJrGz65Gc}R&3t?tYHO;Uf{+mnroSH410sZo4p}Ih7pXfuF z-7DlD0<U@SF}n5WjU{q6u~WUv_7IM4_0R;1b@U9PO<k;@bzQg?IzRiPV4V1I#wU7P z&r*!sk2#T9kd9!4Ak6%2jzUNx9t)m)qR$zD`<oyhC}L$GOIchZSJk9~TMV`p<a+uU z5Kh%MJUkgziByyCUm?)si7X}8o{n5?S3YnSc>j0X0AW22q9gW8hiNC(y#>tJXZtlr z>JuGsaib=6vB>oSJTqNRLL6vg5o1ndiP2II{7^$%D^Q<Ovzwk^O{*6At6`M@k$GmM zE%#O2CR)ysC&R}&!b21bQIEu;K)^zK%u4goRMzlhiZHMhBqw)^87GKXb6(*MBL!h_ zU5U7=0XIvOHv^&Qlvk7qtUv>zNXXbnO3Me~I{fCnL)i-3Ci-3jozN5(2qHt?qPC|K z!q2`FS7@O*Gb0^l{;=;@Y8v23n(koGeo?3@*vjgvX8dGY2ZD`d0%lya)}CXhSDOpm zlp7I?+PawH%F<N38>~LRw+9a<mfI7k1zPhn*bJ8E9a1eaGXX1Rpadod5#!Y}zXNQb z!~OsxIr3d>PG{i;AkDj>s{C;8V2W~r>>-I`(mD3R@GpkA7RNU19nExKBl~Y6dWh&g zJ8D}|m8#qV48A`O(l;;rA0+;Red<}KT+-^@Gh&f|eWDn#CIY^^G#R&elO$6Mqv0T` z{OUOJ-d3qY)iUiFy60X?>ehlq(WxwT)huJ|M)U~Yu_bHbsaY*m)e{Q;)fM$S>0MQM z^n;w`?orU6Cj*)4k0TjD7Us4N6x>7?4a-`pLuyj8#t>zwgwP9*7{9wZqb(h5Jnk>` zxQ1BR1-n1P$$u}*@TaUAC0}}DahFM6;*?pJD#H}iMb1$&tP*{w5V;luRlegA*$K5) zS(iM2)aXw!m8qv!Tdo#txiaIj+4ng;yw}j@mIrNbe1ATL`JvihFe*~Z8TGo7(72U> z%Te<7t=B~Q&VUEg1df;v+54_1P6!IB=EGVqafSpPUub9=IP}wVNVN>JwJfQHR+aaL zH9b10?>^XuJk$msXAROjlY@WFRX0-rF?v<CWK}79o;>2`ol757U|RwMfj8@XbRmdL zarH->7Xq;*!trF4%3vE;mTg~#iJJSq|IMWsrl`P4<BMM&vv`5@g3mu1-6u2M{h%#~ z)6>uEUo54!ze-_Fg^i*(;MM|f%qBXpwuYEbEjCNa$8JpiTl;1cKg=*uc#h&et#42P zpF`|EB8({FE<Z;k5-{1&C?ycN`3V?K@95wlCZ;o)jxgv*z(39l_k=1HF!6*gT?bxZ zx_gP`qnVUoChf;sUsrkG;CxtL2x`{#Fr&v=?8SLnpg*G9G}fK8iEZ@0?Bu6bL)f-u zL;?05Gn{T&t8M@p2sY&+Wsuk$!9K__PUDT^0sQ%St$f~HDpUnLb@4Z){pbUK_K7^y z17+}j|M07oCKk{V0O+l|<e{DKkq#47G$6X;7q{yBUwEDbU!L*|B9|Rn0pHr3(DjPm zH0CA<*L9)%5^BUbjdFk1*8a@z3kqPzF|==8spDv|a`!1*4aTvk_F4E%Ql~*K?R&|n zJ!oUW>{h`(!8I{tLX4OLUb~y2&IgA-j1gXlMcn(&q%{+iLam`giqCPdmp4DRNhDMW zt9Y;#5poAzQ&jH1TJK=YEb<5PaWT+-H?1)?PahiA#b~h%LG;X+s7+ErA~<=V@I}(0 z!aA5WH{gu^+CRus3EiVZ`k(hk4Aenwm8YL0`^_CjnwHg)R$~avpEy*P&HI=a4$?Vj zjmW$fI`6*J<vDFYCX()yX{GWL+$4A>pVm8?TKlF$6^W@v+teSlPGJ&x7ZLfvwR730 zE}vzsx$d%tFIhGL0R-OqQ+qn|L+Cz~cCRNWEh-IcXB-rZT~7Hq!~XMI2L{BBeGc~c z;@$*Vo+L!`6~`vHf%xGvLix>_%Ik)i_G5x=Z<09k-uok#dII@+K!-tu0R^bZeae!j zRKr!j@*zsrt^%`V^Vx?FCtfqZ#6<u#)mFY68wO&SyrF~N19!0^Ew=j`c=)-_`jq>y zrwK-rm-n9M1&Ym|Q6E&xdkB}_WRVw5PEE2V6iVV(bjTz48i3dUT>DwGImB4&6d@cs z1gdkvE<=x!p+oqHps#Cc{3RYTYV@oP-l05Aj8Hx*8>?Ti0qS%pO(<I~ay-jKF)9(` z_lQGPYHOyf@frc)FvWNbyNi-JsrY}gPt771|CyCL(9s+8^hcc5$p2@dB@X@K=ld_7 z67-*D+|hkQv3SR%iLv1c$t47Mb1^LVwGsk3G}NrD8IVS(EL7mIoL;L=DIa`2b$z3G z9}#beD^q;SdYnKLN~ge5vdSmFZ;H8J2v}ng=m-j0cIJL*ime(+pu{Sc5<LYK6T})B z9hw`P4~y~A9JXE%uC2Fldt(q(V`8Qf(|j1GtzV^t3Qn$4@A&@Q5t_D!4U8t)(6CzW zCcW)htO$~w-qJq8iy+!q8weJqrD^KR@?fcI4ZrhBx98;gRo@85(ZKGed64~w`KHUY zJzn!M(HWB~3rO}JJP|yVVb?i3Wuy<8H3HRNIWiG%WH*Y~AJJ?vz+OGhuu+gu|AYQ5 zLLxuO)hrYiDkR9@a7n?<k&VcHD5#s8CLW#@|IF>{Jc&Y6r!gqwXmFw0o@iZTvzy|2 z<Wn^?6?O~>dkYmlV9p8%fV^S1eREQXa3ZF050vLegB1&DlFCv7kH-3Kj@4d>t17-& z$5*?&T6yn#HJY7g_;mr~%~FCiqW#*)%&3+!dZOCf>^tWsy@TQ)093e@HCSl_(atfY z*>W=cK()I%qW73^4`4>dWFKgh?O?2bT@oN4@$xoiC|>ppf4nu98JygWf1svx>#yEO zc0*7OdsS&lbC>pE6CDW;4-Id)h<bVgB=AEd{S}cF=JXm<v=092BmUfA`6An-tM+X7 zmAiH+oCSY5s_7!E6C~5>;xMvVNb!Zv8L2r{OAC_7u8=4X@FLE~sa}Uzb?c#ZvKXSA z`UN7rAj=?~R4)=EY!WIocL%5T<1?@5d1=L5e6se6akwb}=o@4=wE}szC=xp|)gn!p zk11kWXag&cVSGVNrn5W9N-?f{OINlF>{T0usfYE|Z>u9py0K@BNxgZv$+||KXFb+a zr>ZL-I*c{N81`ZPLY2mHNr!R-B(NjM2K!$26K`tbr-5oNlqS<~a}>^CCmj;an5<!W zv(GOfA!P!<65Q->GxRu}sR^($VQ9*d&o`U_6&_+(f6=&?B=EPO=#U>?`dq`39qdC5 z6o=-P$OidZ3Q*Cx#jfClS6T`lcen*#J^!<$P$^@{JY1g@;(tVJ-5)!!CXY}QOWhx4 z7D>gJXQW*6f}v9gbpK$f&u5cz$fF=4oWT>+Pp13;{D4J7B;Z9J&Xa=Eq98>7_%laA z`4g;L^X@M1(u5&}Ze;YE!x>9<up2qE`mf9&49V@oKg!U*@PUk2*|n@ql{1<Q`P4K6 zqeBWTMlPFB1US9SehgP1T@cIaC<7?r3h7fQCBADrt0#Nl?OYls1WR^Y6)WxeC+nw+ zQF4F=Qk|_LEz=p~E3oCZqsS(!wcWdiJ-sN-Rlp`YDCS=-3(jy6td6<Hp$_2BQ=!$O zNN;o$2a(nv`#DonMy$c{z-xM+6YJCd7ls4BrtHVy-V1HD(Oz(giA~$$d_P_&+Y{b5 z(a&v6s1j4TizBS%2x>FWKvgc%N0&oEv~p&2x~}(KkB09Zf{Y|>gO5Zs$NKtTW|A&b ziO<xtnzxPXh}o(ze?SfMmRlCAj~fP%L%bpkPx+<LM57^tmB78_8P^tkM8w77(F$o~ z_@F^P+O;u&hR+yOcb^$!@LkScwg;^2t6t)cA`;Cw9Ou3aPff9Y35@qt_WTCO7f?|i zX2QEo3@Oz>Zx2VEaTl(D_C&?OOy*qkjLuNrU-fX%4$#KL9rmGg%`WM@!hE^aF1)+= zEU?h66w@T>y4ZwAkqI7yt~#NmJXPyUULt+<Qhs60nu2jl*%n8nAhDfvM&Ig?llgM} zfjYVXjcRmbvaAd%b=NacJ4XvIZ~ZFo;yrb|zrk(kyp`F01Vs25xs1!HkU!f`Vry&! z>Ut=JG4`&xAo_*vyi{!9ys}hrwBC@9KVa}AEkHooAb6g*V=VB`(yU5VQDe@lrWp!J zwnqru+(Ai86E#YSB|i&O&yDiBwtoXPtw2=oyIU+!rGUD4Qj-GEtmC}>$vxayPCfNV zo%&i?5h%$F_$(B?xn>(+P9fg?qZ93MNX&l1*Iad0ce@sCt8|HG=zy_xKZvkzO^gPZ zfZ&qY@;rC1+={ta!z-gki6EW<9>)P*&;@tV`{d$EkGGEscfY%TMG^a2NXLK|-MmBe z9XAUA*)jk|B^VMJ*?W5P7IU;S3=;7b4B<#(Y&%Z#-LQX0Krn7<?>|EoL**Y9@ZW0L z|K36>)(?<^ps=C7$sFm_U>zgZKpktcAn6(pG3Gj~SMCV3ndU~aE-?$0dps@}!9LLG zH<2{Gm*+w6CdRYV8grj`_Q(*P(G^R4k}n8_^59pKqGp4(k2Cy@BjPTTL`c{X#V@J| z0u|^opP;Oc_hoHHMd$~FtaYgP>%dWs*6=O!j=*$>H*DdvnSY)oZ4`Hj5{>b*^>RBv zd^0yp+|-^47OhG=<|e8fO)kqeVBa6*<s{hEKQ&#%JR69uRXFtDz?~><#lM}8!mLmX z$}JW-sEo1b>NGhRJVPES8EEFLy$UyuKl?Cz^>2ot{)HWd6x*3^D{kV_%DA;xd;<GQ z^D7H?<V0Asvd}i&QN(w!9{WK^zaUBVabA3%2O}WB{=)f4Ua$(|{dZde26x?R0oi6_ zdbYV0A7$fG*X9Z8O8;sIrcsjv(ulB!!oQOZUPG~^Rh9lkk%w?1fT-1x4tad9mk-+> zw)gY~4-cnDn)b^8*RkACFbj1}4&VW=l@??pq&FFkXYApjyq8h6?UWtN=$Hqi)%0?G z0u!VAjm4}rx2mAJx+argLR9<vKL+G|#d$iyGIs^Aa9rE<Spo3La1=DYs=2M63XiKe zbx>&}<AY48OGlO;;H|Szx9?ymV*@b^(=*Qy@zt%S9L^SGO@g4GarBQ2NwMX}2<mR3 z>MN7y$%a0f>t#T(mlO@d$x4Y`VSl(^S;1kTUcX*h>sV#8@%>nWo`T&cA%{sf#zuUr z>&-)2<PK8ov!LZ<PD=OChaz`iDCd$JYNdX)cN_w7f<XHz*c7UBTvI95aeWfAqF*g$ z*2?!p(+1fUMfm#!5IDYo-BGZ@0i}ra5f4CgT%S!H(?FmGWJP)4ciqJCN`veP2(h_v zGbda!f+l_vF7^KVUttsK!PG9I<`%Dqdl#_CIYjtd=aVmWT2Oz1WC72nY>b+fWC^%6 zq+oBS7WfT$k2*^4mW3<sk=qn#YbCcgb5PTfLHJ^#LQJAUQKYZQLLzb`XoCbO{~+}f z)#H66dmU)i@c)7`U0M4e3ZQyN#kWeReryd*N#)v)IW`>@FEMIx&D$gOm%&kFCj^~C zt4Mw-#QR}%b5;L841LJV{uJ7;kga>m5YXcK#1>B%z^`QC&u5MlsjexdwJ<5^&e+W- z<9ZE1CKeH^uAyyGWItx)OsAx$=f~`gs+968k=nl@q7>|FPo6<+07GqhitvJ%*Of1r zK6G@J<TvJS#<T+FMGTGgQ&0x9puZBeVeN{-5{nmf8>xCi^FW2(csU8=g?d42a0QLZ z#E=xep1(A33xdeNciHK9=q&;?zDuj)-_)=VZI9Tyg75WhZ=R3OqZ!4QW8ojIJyawU zR5+rRuNM_i**XGZq=xg<x`B4km1W`SVJB&YH=k@zmNlx?LTrMs25`S&1)87yjJ&TN zifz=x(sTyQUu_U2h$+c65TMEV>bAdwysM{5J*BuIPlMBsAVD_RnP7wRDGF*S#nWts z)I&hD9M4LOd*_)j0`qf?ZpRVteCn$L-N2oX<dF7<;@m$i-SBRrHx$Y?(QXJm;-1m6 zPbmv2Hz+Y32FI#Ma->AKU@T)fj9S`AT?&(h^+drS?L`*^)X`#^(;wMWP?-odG~q6u z!BTfO4Efqr4C!cQopt@pSWE-{LOKDkolK^IE*R@xU^7qK5iJX4p^CJh+ioOPl19dq z9xXbTTCwXl2#x)%X_p<}i{u-1x~-bJvdk^%y1mkpb53H{c+0gHp&0I3J2si=iEK{; zwEQxr`8c19cc8L+4iJp6lT6-hw`bJ<J%+NnFwtjf$Yz&jbuhb}UlxVxvNx6C@Gwi? z9D2A>#5JdPA=LQ#7T`J!SI<tprZ#LFF(xdqTGWYbn<iTi5g5l02j=0B_10Ke|JrQG zD<cr+UJ8`OX>yRUZE3B9!s0hlA+W80Inv@`<z6w<S#51x(2VQkN|JZg`|Yg5b`wZK zY863j<%(2c6Oa_y(<LNd2$@Xh^^i@>w5I#l5bnpp^APp846(3qocinKrtz}oeD|T& z=jI3F40w&1`<|z4Gwcmh*fA3U_iv77|7_D5A5|XuWsKmX-#tNi44y(6Q=Zle<HMXG zxl*`krfSj3`3HN&-v4^nkEiY<CS#}9;IzN4doZYETC8xex4(&oL<PrUy5XmDrS7_V zg>1?kqDdr9XurPl-+noG4gBYZBS}Q(<8O>u&z}d)ZEit)G7ul%J*Z6eMduX)gl~0< zHRyDrm#3C-^)j{MkKfd)XA6s*W?udcH?)sG8!XTT>HBYVFt(G1R5s)ooiE8@<Q;2N zjqdy8kWN%6w95B+w4IzFgTEsNP(&TB6f!}}p{-!A@qM-xdh$T?c;tFcft_LBilT_$ z9Y7NVLKKLLm+ayWC4q>e6ER;SlU!oMh2k0bf?Sve-7QS2LyY)Z*u|7me#1j%CSuF8 zb(^g4*VWz|)b5xUxQ?q@3Uv56wlOSQ3r{&t!dbeN4${?9sCkmUCIo@J-3t`%xK3w* zJ8f~weWZl0c-omGA#;M_vYJXHthVddqR2OsbrL}CHGW&KnJ1bd$cY21!O?$@c%Z8I zt<t71B*so^I$zJW%v0(lt$YL(hq?YfCR|1i5o*6K;v4M%$`*8XO$B%iLSQj&K}A+k zGtWFf62W1*L^B!h1EjnkB>u%RUHtAiOZ0c%_62c$OftA_6cMnVs@)?mWRjwG*nORC zA3FI=65Jawy;)ce{u=FzhX+SKqEx!jvT|tRk>M(K`GbN}-yQ+vGpYr6V<pjB_=-s{ zUXOwu&yBNPzQcJpYDo^I=n9@jb~Z!xr_#3=K_`J9J0?v;$($QMpZxlC&#fd5SRGG2 zN6MgaC*rpTcl_Pt`(EIU+G9tR%mU5%$AJ*L4kGpNwwOlcIy<~Gu;J+rMY$i&XS-{V zfm6r@IhTl@go{v_@rS&I-o7uVCeb}OV{AF}uJ<DX`197m!J#bff35^3wojrw2nzz_ zF6wHpqFwNSq1avqRZh#5wjJE2z`g_pP7jpMb^-bo8y(j~gFjPMv+YkJvS*8BN!sSr z_4VxAUQpMkn>t4?mcxUZOiqsE-{Ok4LoIW_^Tu<lg_wG$Ifj`IL&t)J{QZ}?x<;a! zmm*DiVqY#4ny6rV)$Y{s%+bHywb^5Q939KWjiZTUyjmAtFMm_=Rk@ixzpA_wegqT* z8x*lB-<Ts|vBvp>b&KaIYAXi>`BBjHOb!KE>t!IjABy+a)jGve+OVs=T_<z(4n-|N zeHKgMf)Jh(gw;bi8^Vsa3JD`<TF`evfKM06?3SjHoWRNX9`sThu&XgOH^=s(9}n6x zoU=Pe6WlFvAr*)VCa}Io7?Yi)fN~{A<zs0SyO)jtHQ@*uj4BTY*!w_md;G1;7Qkdj z*xrXmBM=krr)Qal{u!p19NUtB77u2<1q~glt&JuqHacB$r(AdJIokrCquo*N5LJF) zOR{D>a<d+JyPjRf82fc`0F8=j+H<SHqjh7Z|7cRny}aG{lYsDFXlVWAX3fQhU$rjn z**9Y(Rm1-K=Dc|*VBCr0!w^0TZHVC6-^Tr2v`FoDxCU#$XgWf+zWSP56vJdEe?!}* z@64WDozjCVfm&0VbVZDEV};&QL~}5sHpzi0sPX_H=ZmzT+B@@pxw7F~Z_xWGP$LsW zd*l+o-xu`2s#$pLgPCtx{~j`BT|XVnE3)#dTcqys2beAG;16(Dn*c2r3m4Wb>ELgp z`A#D>Wf<n2&^bbYtH4?ZfDFB(4HRA_qf&hUFmsdDg>iBp`Ixg~&eq=u)sYymn%RuO z4BMmzCONoQ;Ffj;skMO+-QGh=a(Fd{ZisE15S#uBM5iZodQ0#0K41y#Ha^3T`#=^< zR1fycrD*)l-rPC)wq&35aBH~}AY+v)vrxYGbUQh|c}3lEH`#K*q+5+U???EALgUMF z0ewyn)eMD}dLyq81X*tqHx<Ej4LdAxju_euyX*yf*b!iILi#7!xOA=q5Ovk3O-!5s z6rDXGglj`ZZ^|8C#9qPE&|6NmzPek^LvSEY27>=Y6)hoFG!61cTjzbtUxmHY@#piu z$Tp$-cR`oBWk})DV*i;x3tbFN2Ybs+u<xA>#I&Bq>ueQrw8%e8=pZux6V~*Ndg}0Z zw!E+>*IR{Ks6U+a$O{df#HjQzb0U)#sUfSlkbi<&<YmlZWl|JF6Bfxv8WY_fhl9a( znUfNumI2A3w<$;M;UjuYlUMBoySIW_$1wr->v+aDaA1_eb>Sbea?G690%MBOprD}N zl%TBeyV!$+{!EPHeo0V@R24)_S_laq#z=wXyAPIu+V0CtJ5+%vITZTQHcLX+DyqsK z3At$A`&!+5`@T|-ZcxkF|2s_JGA93si2mm^G0z}$Z`|J2))%IFz}**z!*};lt?3jR zfXz_U*-_zP^v0w?A<q;DGfWpdCJ?`=AjYPd`(I%IseaN}Ek4T1+ZGU>g9va@BQodi zsi%`Lf1SoC$amlkdZ%z6H=i`m>)4Q@V?3|w^*Sx&;#4dT3+otAwrZrPV2&L55U~wO zGdT=4AaY$$s-z_1p1~e+!<i=;a&crEA8`*$AnvudSh)jeCIwD7*;@#=6by*(?f13O z@v#+ACmUqMKFndjY+y3bg&oTf?M8B6>ExIxTW&AlBL$l@2g@|-G0hfXt@N(LH}Z;N z#bzfb8s7ZyA?S!d+=@BbRDUsgT<fiMF!E$C*0ZSJ(SSH+h~vyiaMY>tJ*D)QfWYp0 z2RTX%@Yq%V7>MP&O9^pp3>4r>l){WO_GDoHruVeF+x1o{b1X$G?(Q>KSeyqtntg*I zuy&uE;A7<)^AxQ-7}b$zo!2os5ATZ1^)l~z1;X@zZ(|3ztsb$TsWNb-X;B#)-V-cg zGa6t7TW+n}Z@-1%XgDxKha$6vs~fvq1-T&*mIav^EZ9KeqbB?09AdF8eon52E&ZH= z`JQ7uMXgILkfh-ucl(u!d+(IcCTQ2c!1)k>I~(Hx(1RO@I$PV?{&V(*C}J(SoYN{A z`owycF}pFfgm^~+`LxSluWrnhHiL{=x-O6z`V?(f5vnEOWtsye=Oe&dygff@4PH6+ z>XxUEN(gH*lsO>J9icMqn^%aA@3${mDt{xz4fh0_9<1Je2XNz*_6T~GJ0~zTgS5;j zUej?W6xP4M0Z)V2%APvcUI9nUMHv-7H{6=`CjYv#KTG5lIC>a<BO)eo)1kb8G8_qX zayvZhn!tc>c7ckN*&(0}BnZ9SKn$^ajZMSaYAf$xpRU$%B-d@mPbNl@?!3hCLmydj zi43@N4GTeW*_m35x?oyn!%f*f$e*3)zC*l;Klp=?2q|6q()<0H1a!;>{SBCN#SA|O z1eTE6?^{xYoN`tvkC#6FSzXOr4F_U$Iv31-WfHSqf3XOXUqzF-&i^-H6Pd+zmJ0tL zub=nw2C-*xg9I7SZJ=5z@69a<-<Rl@3Plf3;ny<G2xx1N%pKpusStK>WnOAR5gmI8 zP+PRc21E1;;I-41<e5v0NdHQBH{3Q95KRUP{UM(vBd<)p%#9H;bD`BjfO3kcTDSqY znq4p5BSG-!(D~sa5c>3EgFMw6Q?7Gfur1={FiE1)<!6B54sk6d;QYq<b8oPZI{NUE zv271hid*p36=rV&`3J$7VBd~3iY1rH*=%Bb@4ttI!`RR<k8gxyAq&XMZ^P*vEtn{@ zn*cs`g!P`#t-Cp*79T3zDM1Sj;L83}a8T#(XtZHpILIqJ`gg8>Qk$FCyI6(^x63>q zI<J$}s6fG3RhECubS|;MD_*pi13|W!0Byu#g=XTOA17dtt?lUAKtjoOa7)=I_bR(s z9<X63S-WT5iWeLEQO=Tqo>{8xt3mryN#O?uEARI5$Nt(Z4+V#v-M{0}a?Xb_?WP@d z^R~8LgKjKzfxJpam#VfPYb0`uWM2yJiD7mxH{PPxA|0;O@^ocvwdE<v5msyK$=dm4 z*NcM)?Fn?ge>BVWMlP!NU7+06qABAP`$?W`^N_^x=JE%cxervY1LU1S&!Vx`A6MZ! zp?|!lRrVK}=Y8;zV;gr!p>A$9b<h=iMk6_=*^+=%6h&)hj1uH^vP~XG54WM9-r66F zjbz>kJIYMOu9}J4KX}$7Lu`&nHq~h^x{y4A0^1lvc@hfd;a!OPlQn_wN}bUAkHX6i zs^Y9IMtb03X1;RKn{=+o<G!3UujrJ9J(GRJd(jWW415DGS@KZ9IYiK?m)4q-VSD7U zZM$adsRQdV5Fab)nN(D-uz{aB#j3hFA)dh|bhf3J>9^o5u)^?9+%8@5lwNvh^abpc zE>sfn2AS3NZ9$!dPUsN?GnO2Fexe9C@ip7a!svzmuoCg01{WHRzbxH7Sc-~H1L5a2 z7JjcH=<Fn-lsdWvt53cMB<#Hdr50brrMDn7_J73Hh?Mt6&p|XkYtl+T^&e!UR!FUd zAccrS48(2wN9W6blH^I1x+&IE*jbq159CSj2L_(Z2v;40Bj9kKvV$fA8Tk}U+AG8$ zk6N|#MB_0EY7C1Gy4vL6;A8E_`+w#kkJQdYJgILEl`Z}?rM(9N;C324v6&t2Ajt38 zIoJEwjAEj76*2D3pMrxK^K|n+NjC%GblwlIH>;99#UU-o`S#QwXi9Vn-jQiK<!*s0 zLOgmOUO?Z#kv6t3>6#Ik?2JvTt6EXgxX_&PhbRRX(Q-S-Lz`b-5Y#RpS4U}O#H@Op zKqHI$Q^=VG7mO5kPp|c_6R;fzP~<NCvmM%q=0#uCHYdu!S+$G-IaX1jGKX0|q_GF7 zQ=f;V^;S!(AKkksJ<nCy-Nr+EJdSeizrHw~3zHsh2!V>6D%Hmp;th+#&)ZGBf9uGL z9aBWS!fijjY<bqIrWhHK!Y;nCJm6jXf+u(g;>T|TP@tfL4{ogm`wlPbd=xaKJj$Zj zW^f|ea~#%YNxchXceGOaK4lyAk&D}io<i=b#^o0tOVfS3*Lm@nh60^f&*_3w!jmj2 zI@|JJ>vawbM{Jl4#s?o;EL=_KWp$8Q#P>9`Fx+vQ^ARE@F0F}3@9lpTR_7ieG8~6p zn6bE*H=Br7kB%sp(EL(<TrEk%IE2M9*|Fx?HwZi%B`TwW?3yJqV3_!ncw*cw$6U*t zgGg~8-yVNV+e?#TunG8{4ak5uFRKw~c~N76dJfDt+6c7O(vAOUKpReq6o($TBrG%r z`LkXg_hoDxY#RE`QI~6qMk$t4uKgVPU}FyhQxrrPn%4H$i&bMihHhd!*4emDXV4w@ zO6v=SRs=gQ_ZOCCi&4?UGbnHb%}#vFp=^0w5<DMT)mWH<%NzoZbelm9sa8|uo?caG zzK1|JE@SDBqr(n2Dk^l~Vj7-<#P&BVv1)J#h|-?Dndu#fMl}xNuCk5}jOBxfZ>QYH z?wU>)a&@)o;;7s9I7_v;r@kr&A0T>+SX^i4@D%hKY5u>LLvFFuv7|e(D5b8}&XeXX z1y!3JCH5;oxJwMSQxaeqas%rnQAM+Rkgxb>nyrEe8#9Ck2X=!FDK~GsMk@X~jE|Vh z`0!qG%JBN>{@VAm>G_2^yREqdQ8;(vIWPD6Sb4vkx1cE<eH#N-3ZaHtXTy0}3kG|| zanG^0axb)a#J3bR)jqs6-sn~C_Z`L>i<<n0EwJ_^%j{_V<&zx?k}0kCB)sO8_gJH+ zrOZPG_DT!>48QhD_XLF$Me+_eoMa?4dgRvueCFZCqdZ=g3)Amup7sJ{RFoMUB;;$~ zbM5C_`ni;APvUe9JW?iXjBR8blWWslcOu(z@RJ2r6_grXo*BinnG0n!g9~o+J$-b2 z!!*6$jg&0xU_Mi>p39xrd`~+8(usn9cIa*{saS!b&+egnp@<F!(Kzyp5!?)+-|cFO zhzL5>c(wd=+Eoo%^t>-CL&_nm{z@(lj8YWkY^M4q0wKj9NS~S3;USKAuJ53~tY|Nd zS?N3R8`l7{tsO7a^i;XD?$TlF1ORd(AO&p9RrB+o-a*Rga+nj1-&=tbq8kYPo40#x zfl?!L#pp?t>BFS2Fr}TO&v@Q#oOD;+=|Ya~hKr-DILIYipUNohF?;Gy=1jtR78ROj zO+^nvn(iwNX`gI{peqU`_$~p8`}ZR0k1BZ2N*NX_?ce4UH0~(Q=Qr~x_Ud+T#f$Lm zh(?biyC!ZmwJ;ofHTlKayvxz+NS(MFh@4W{B=Kvz<(u$HhL7^zf~6}6leEG1;8z|$ zTyw|319@@ujca9;HgsCPLH^W3`C-!k)1%KSUr}AQ<Gm|c5Lz%CAyDgJta<dxk;<|; zz>6TFMeU|FS<a)c50xZhfIv0pSy`x+1$7k-Qezy@&tb`RRK`daWQeP*Ai{|3%M32O z0VNQs;^>bb1d5TskL{Zh201Tg3grpTSb_3Uc#S2;*_4BWW(dBqj~<}UJkoz;O!)sg z-TuFc;dfAO<p3P{#40u@jtiB<R|&5fg65x?a1w)61Q}W7r+j<})C;w<<DcJa|JZ94 z4+~X1Tc*<}@C3!m9BVPigS?3B3P^-wzF2DVou&mWrkPQc<Kx<zq5tH<t81<Sd2k<{ zbY}w2F@N8pNTAP@K{vC%*dHNiXg-aQMb)z<=u&ula1s6s3~n}hAEjB)MQ*<nan!Gq zBrG*xP<2(%IZ1ANa}CYhOtVXp+czsnJ!i(=%xGyO)V0W2L3Y{f31j;`Wz#J?ZsGE> zo!I0zayJr^n4&>%z#{PhQ_xAe^qI&^<JTMQfR8MqjYUUC?8bo8kO{bq7Cm6%alER( z-wm*PoxnVTsvChO6ptxFg2VJrKo(`Q?!9>oUW#3fyYR2*AoVP<bo%wYEx2pPbHf_* zysgyH+V^QGoN(2M*D&DR0b%slc#<y(Tl36s?VH;eCB*gUUt^w1eea)*r?%vT<B%7E zjWD{WAT-H@t<kuxQh<rbko{dBc#wrYsJ)JI8oL}h%(OA&7-`PD`3xC-8BX2jex+Eb zOHva3hdH^FxSq!&MlW%o54O(a3NLcV0V{4KDx?)(GAJ`DqCXvT6XFWz_m>aAn^)pT zA52u{U6FK}XF_iDw(R;6Cvwd;I*o9UOZqlP{`TuVem!tm6{#(33bn$^PvU8XtI&NR zSe?HQwpr--`=X&h>fJ=?>)HB}F9gYJNoU|U1xHSTio|RCUTtP0aYVuiSd(G4IIChs z8GtU5l=Y4XJ)w2j+{3mq&v7P-M|D?Dzqi+9@|fSwGNri)q1vnH^oY6CFq6yMQ}mG3 z3#@TFDnW*5Ig0rkH`-Z;J9h9hJK85$(q@1yj=W>pV)Z-6n>N%z668^U;Ect{ti#l- z!x(t#UCs)ciKC3fL2mr$;Batwta6}~Ubu>5IJg@BGZ0#m>h`ukGeJ!bao)jkt~>`$ zG-O39wlMx@zSnSHU*A2*$G{JIJm*6F*G*@i<*fyrbl?9E0J+T2SHuc7bp#2C*m3xF z<I{ukY@TuMBO<p8e#zB;MH1hr(9X4#o^YYmLEYgha&;&uh-@2TpOM^DpP&=4_lkcX zik&+KR?I(46oHRNZ98KVj$NerBA8fjqR}&;V)afUC{OrywsblS*`OVZXC0Qes_#IL zL5!qMu^aYZ65>{C@yO75=cpBD*jBwkYAr!oGm0Dw@FXMrP_L<fk2bkI+LJ189-mym zWK7<DdO{Ao$;9AJ+ht9ZaS+`mdc@&($Qnz0@c?OIKP_@Sy}m|+Z$diKMFkDMF+D-? zRE0S~4<PuTroY0($OTNd2!Gh88Pn&?=&mA}@6`A??2MSQFp3z4UXJ(PNtKW8IC4Ep z^n0#|$)(?7z8NzAl9dG&&C7Xb9dvL0x_U}De@X!(s5;_Gj%!G9w6y(u*fBfEc7Wnu zV<J~rrxhSBz~B?K#N6)H|B9UAwXh5xp%3v49bDxUyPGiDXa>mG@;9DoUC%zbGuP)& zibRI4tPWBg0d&+3Diz-qi@e^H^=dM-d2GFpwo+PO_7(85M-PwT@Pr3X`Tib0YqXF( z{SioWf)_b=RN@8I7Ya4~7y5vDnR|T(VLS7(sORc)AHh`*QgEW@8RvKAq(1^V$y?e& z;7-A~$tuX7!ScX+Xt&e{KGRN*4#0Xe^Hyt4*-DE1i(~KJe<OtEedF18v<Xk*)p+*m zab|G{+n*1iwSc4u7Tw97)@GJ*fJ#UUBR1B{R=LGzu`QzV)tlJmVnt$4b?>ErVnAtI z>lkC>%pwsM*lu&ic&4M9hCi2uDm511eK_G1bpxu!o8?=c2J@B`wJd9vq+<~G5*k`; zm`M^$MUv}?rWSZCXg_W?1=l?kf}Q+dguP>MW?l5{8{6#IcG9tJ+fF*RZJQmdW829S zI~^w-+qUoXp8LO5r|O=nv%l_7yK2p~=3aA*-yrnqX6%{{LKzB63QI%TDTBMeFJxs5 zymV)oxO5C8y#>YsC6wJvkwhZ!>XLL0lMTg@=3Y>ta1l6{r$=pUexnPeJ^wdvN3aUZ zt^!I|w!!{?7fAtGgmW+^l)~hztG8(Fb`nH|Au(ZyeS`B%V~WgUf)6&ygs_DgL~Wd& zm#AmpO4z|CN%UK>`^-@j@`t-3$iK*oC1I#B7fl^iV0uq2(j45IO$Np95{v;U2II$u zSgC@f%?b8(XGv#ZVG;HGUzcy~ma2x26W#djA3OI38E{dO{EG&ecW4h2!Um)^3pu2- z#H-oxXbHl5+$e9iKtk{l3B5lORGK3#YI7VOm3%v=<(^-e)CC%m6WN{-R0C587ePx4 zZs_P5?YL(y^$+HXH&=n{$)y*jt~esOY|nK4fmbc4sSf3m<t@%5wmhG#`M4SsRNf7g zh*c#h%3Y)8nga>0YTF^+-L^yULW24tBn|iebROHiG5cLI_}%C(Y~y#JD;Z<n4&B&= zgoDD7o`A#lyixPj+u`;-wFS9H4!5i>cJUU>l=C8Y{})zuMMzY>(FERVA|x90<j_-E zaeGE_1G-NJ^-W|jfdr!X$_}y9*;Vz8x+xfGkJ0y=0(b~Vl&JdA=?)Qsjd@Ww!yA&F zwR$3Bb4>8`67dQWJkh{E9mkm9j+9!+t%wTQ59C9T271Sd;K+KTOh%#$d~j7avSWNX zvc-#p(!rnH`CWzmw5JoDW862OL;Qf4w&wMI0sPVv%4wfqJB!-d;cQU1=hkw2DQ=84 zKicZM_9#&?v)A5A&38~FaD0M5wjPuRm|DhhQ0QOv5jWZ3csbESR|ia98&r?w30fW# z1sJuKd(%;}I>N<>dQE`&_qp24jMme7sj=Q0M)H+`-w(*paJ{y+C%TJqZ8PIp8l6MN zsyU$m{VVmnKk_^NCu@x~y)J)3Mk?MQH3$Fvtd|YZXRj0M>N)Kdn~D;)p{(EkG+~-E zmy9g#43ZJ#^%mSYFvi>|yS-Dg3J%U`Z)S_WQVh1IOor|e0_Ic6x3*9`R}`AUReB(C zlp_lx()q&zFq6GbS`N0sKcD{Z%b(@riI?YoLGnd;eM(|mZLmP{p>!udkMmPB9;h`g z2i|w(SuINEY(zuYB&RVHN&15QY-Ax-{igePg-wnw{JxOOsUB)Ci3aq%^8b@3eup{W zF;cbb1FqxrzLiPqB+o6fSFoq!$1{qaoKM1%e8gz04K8c#wxU9ZyYsDz>-T0GVSA^n z)5<bm)@OM*V`=!OEpI+Vm`#WZq|8q+UG{?(hAs72ZfKV6ltuxWD#FEow<e_oVMaO7 z*z-mo5L6NH2_f)1?(7?t;27mmVUi>T0|DlxCy&3qQM+h`Y9WUVj0_!;6@~s_rvCwV zGoQzQO&#l6WgDNsO0<h0@QSqF&`o($@5ApBQeLX!rF;1sR5kcZ<6p(6A_X>8o;>8Z zLU%fTL)Cr-${}L7stPYS;LhwSyi0#lr0=F$##lQ;<{}EkCm7mdC@;wNwf_lYwY!FP z09s+Shuz83xeP_)+>%IxvA45eAo%76C#5;pdD~mNEKS0)o~Tu<z5;iKD&*pBhwjLb zsrq7-zd~BQ(%y|i&Of5YXHpPih@0BQR`CeT*mJNRE&j+T!)0ROgY9a-`%rA#$0#>& zh4ys0f6<Pmb=*h~1X?Cgcj`Ck?#^5S=ijvwaFX-VHLwYNBPGxj_n}P$NT1m}@nbTq zY@hNP4wa317tOT=^%}$F=I*7cQvsd38Q#X@QW=g+unTC1KSjJrMk*Y{@AZloO9c<; zwv>UYfN6eo4oyI~H8YZ*723Orl})|@CVi$W_X^RBS^v1eDro(Q^mjFO!5kc1DJFIj z$^*(IfE0CLe|IA2X<GF&WNIe}`-#q%2IuJj=@-8*?aNloNnd}gyoG5-vxwnE!*KCw zxqZR>Y!EFtHgXvXsd%^VMzF6Q*AR85AT;5HQ6f=xbiUL+$tf!GXQnVp6bIHe1EDc9 zdWq->P+vv%pT5deimp){7wDP(-?bopb`1e&-=aWXCQ*5p`0*|nDlWv3IJIj*JXRR0 zl95({N`(|C2CB5Fxw&}q+~Js-2(g<`QQ`r~Fc5s58!J^AB-YT-z*2$?O^xM+O;1l> zq9OGH^C0{qTJ{K2B`TGVzCi0FwwV+hMv5|7RB;y@L|Vc-SsEd?VoELrhI9acnk$|O z<0>s2&DP}T<k;xw$XeX}xhudmW_xsGvcFg2?0oCE0FN1#Ewj6KBtj8tN>7)Ku!-=@ zWsiiVaFG?4ea|$xo&d}WfCBXkj{ZSKOKE%YGuRTJ#dKu^Z?ct2>Ut(+D-F*8=^0E| z|Iym$Ukq8)A)U@Pz4u(x&S_hR!@F1C6T@lfQp`tO>1z(6pQXyJlc+|vm2{sz*bROB z!Lr<eUfw`)mLCm%H@H!^&O|yKAF252Au(g)2_&J`Jdo)WRdtfZYspp*kNSvZ`>5=z zF?NM1ZnA+TiNM<CAiq}6X6Ph;F`<r(puRUfd`EwDm`!bgi>uDWt3~D0ZGSuNecPmN zYA1_W4EV&Q&o(4(pk8M|i#P8NqUXwhXoYp;s2?T6rHnD)FZpXcc)!a!3C%0xHVVr{ zi=vwp+Y#nXMrc`7Gm+C+;utSeBuRh5ZCMTXE88yp8UwrxCG0HtcU|Brs;F&(w$7WK zq)FRv`?nT13QqfwO6mBs<qOR0yS8cufl4*sP?#HxareBuWfTygNY|1?N&s?Lvfxmu zS8mt-?{AN`G~5Ntr_9?HIbEIh2K@Ef#oCa4ZpU&M<jD#*5E83P0w@vy3LXLpr_mS2 zvl~wbl9Q)kt}&|EV&D#(#}K7u??{Rt-Fc8wx0t@;rv(hmbk{`^@(j%mA*}F8ulo_x zcD{2pBFE3(ZJj0aPv1nPt%jbvric5w#su&9gOHh-#gg;CM$jZGb}N|KS5P7HIQZ3} zmjnfC(Yb^8<4{}T!faF&F_ET&d3&?Hv7f8O^ROaKwXYGTRmv{;L5m9pDgO1I5tlCU zzg?zzF>>H`#n|y}Lq)^Dd2{G;n0g+Yp>Teen4Z?RqGsz6eLupUudKVOCTalfW}w&* zy*iUEy!(jok)2HiU~>C=1$WMO^IR49YVJscNQ`jyUH)ho_6mdw3WRF1)EJ-|%Vs{3 zEN`~BJV)qa$u)nN;n91hnu>^;8VYDf%HIQ^-lmn%gGvgcLuO#iM94s*W6p@tA_qh< zZ;pj4<4BXI3E)!LvoHj_6Qzk0$K!rTVW5dvV5nfyL=Bk5@B@oV3fJqap@$TF5NzM6 zse!~?DbP3dK`a~^13riz`6RYq%7}~Dv=C2NhlHD2$eP{cZ<@&%PLK>W>8FO{b*xZ2 z-2=Di8*)Dod8?KoQCv8G1KrANk`+ZrG7k}S;6(NpPMn;ASh@Ik=R_hAg&a;=f>pBL zYg`NFz~_fI8p7P*P{MO?vxtzQz1g+96a_|7H#UZZC3!T7_o7f(EQYL%gb*z3{4aDa zZVQ)2NnWmLV{;<K;gNs_RK5pU+Z*hzGz#PoA8$TfCS+bJcO_P}<eO+%S3vA`lyY0L zg}mW-Xxryb!Z-hyUM&PfXrci%(6=^6Gu1RwPwORt%r&yFe_OfU#9=q1l-$++zREA6 zrm@8<+;tiAfj3h6kn3jjlWZW<alIU;zjdeoqpA1(PViy^++^ufpWBm9Laf2)sc1mH zQ_<{To{v;$tNF-?q`DHc!QFO3y8`kFD>(UVliy;AR^F31LY>N@+xMkKE0fNJZV8+8 zdXK;uTLttMybdMtu&*Qaegw_Ft(kW<yV?d{i=uxVVO13ZnoL-;VbxQ4Utch@w=_(a zDZ>uP+&2Dq@W{eh=cl&Ae{FeVwlaj!Q^7E@-*sWt64jLNzX|FNe@9??vq98AW9-0T zI~l^yy^{#{_T;sG#mAoySNTqNoKvOu@I!Y(ARB51wVtZg<2K4MU$^dle@EiyYRS%Q zO)`KCjr1xAuI@Pqa&4WWc%@3LZd2Qh4?DFBN}Wf*deyR4^*)4lENgvD=2K4qv{lin z8x!G3nz)fSN2y`1F0`YLSv0Hgf-`^Ayv(3<Yvd)77zPGxRw<E<HoKv3ksf`oDyVhC zpr^y~-+3?1HB>5*NdV=3sX?#Vt+@YG+JsL5y|>$pYl8H>eQb&&yX>F_I94})=J#2) z#W~g1BlfKM6P+Ob-xG)~u^Tv$l^XzF63P{L7Y9epn)*>9NUPN<Qm_*&er*uE6SIrP zN2?Qq%@Idl0L;9i5rB=avRS4q(4lBOTEo`WNR&Wt416g1$&NN1<1sQGBEyqQiM3#E zxv!{6ag+CZF)qH_NGThep_xyj4b8#>+~Hfc)L~05#3GV}C4_>-(|wBSJdGhEs$*(u z-xJa+6yjH~-jv=21T?(x^GWR4o1>1>gRVv=ji>7oS)`WF=qtp%8SN|vTpORe$1nE0 zloaJ*PcO*Vup6!mLl92&2TBZf)RWjwL<!ttkhSP!Fr0A&BC~1nO+=nzgE(MWyeR*f zE04esW$JHdz}-ZF@3FEZWhcppqzPyjLX{?wqJRj0m<vkfV@246nV>FNJz<N6NDeWJ zKLR8XPcHS*Um|#m1z-*O|Dc9D^YI_AAuaIFN~O6$KezjaGqWI>A3>2}a*6#LDKuZ4 z6r>j3jqR!`Rb`l_8Oci)1l$;c3iZT6(Wv=M=ASGR6%!$7a`K>Ne;AypAw7}vQdv>D zFKWTVnHXB}MH0-(gD<Sx6LwxohPT-8m5q=8g*(LdGGg9`EIT>m8b-Sg5zTL8{zT*# z!HK_vs}hE;z>@)Wk`+r<n*AA0IY7%Al37}?eWP64q}hu8fV-=-B}vfaC?e#SZL@*f z#%Ch?!#Gvq2PG_%pW`p@H-giNkQk9*lO3V80(bOkYoX9VOL2zksxW!XdMbDbb+G5! zx{j`sqzJi{8seQ*jKR<%JTqpy3H&xn1M%Ibuckkty~m3=ilo{O*n;5WlJyO6SK`4A zKMfv=Ur<`HK?^U$%6YQP`;!*JfW|f8b@-!v!75}lK|%7TlOfj$?V&@SS~+*$ngH(N z`E58&90wmW`r+469B=5a1FiE6g0W%u*r!QNZ^d#c44UU$jYgq^Qae^#hCp+>RsKkK zvZ>5#$5*4CAma*MdVF~(;VS1n=Okm)&`n6Z8U^^lkr;n)URq=Q=|C^=%md_dw;&Dl z)lp=uR`9|De`e(PL%>IivVtsLcN>47G8i<iKxM~ppAR(6J#U_}z?0*k3*lG}*zt?C zY;8Z!<*#=P=86l|lb7~Cgm7raIN8U^+FJvrcJ>k`B1b>sphG`Cg?;3g(zx0eKqY0M z<!F6kt>5EheG<%(^%5Xw2WJtYs{Hp3-!2T$Ew{<B^jl=YHqAZnlCIA|w%Z(J5`@(T zkNx>j&N!$VcXy6bLGpVUFu~!Ngc=BrTR$4+CzW@8#MndRJBSCTn;mJ#X>y$POp3ve zM2E33bc#zE#4~|V*mHVJBC80ubh>>$qXA^9hBSNe33M<LHq7`!EVRDFFAn>2jt#M) z5A@pAS1zEL>HtsD6=*6r=MzS6*@`)azL7x-Q;zYlGiZ+PZ+LhnB*L*}j_}5#!5_YA z9BRod-<HGiFah>=HZbKM#V6%Gq7FzR5U7`XeA#hs_+hM3F>KQ#)-1wufU4vhI_N%P zBBr=oi#sM^4U|P|;9QK^#5<IBlL)u7P_uD2*uVydm<b0h0Mg$!U;5+6msdeI&=N}W z!26X54)pdoN+FhzR2;zEm>R^%{U$Ocu_Bi!K#msgohk;IsG4JLB~lkLR-xoi+6`I^ zMMyM)`Lz64I6?i?MnEoip<o~R`S@;EtQZcD0gsBB8f7MsY*cc)KwMmK51gDPCux|W z2_^tfXd#`#ZoD8?7{L({k=3;|>0L8gL1dMb!pIU0gpNVb`D0{Y-i+c+M&M$!9Apr} z{asP|Zy#1p&DPu|QUFI%Om;+q#O|Mal11D7HW`Bl*fivKP0<W6J}xXeUU$nFvqsjY z0uO5mtoofaIhPaJCS}V&0W<snP*yZjJFY0AEyLR})YB!RuDb&gF^DLfg-4z2q3yn$ zx7(11!M1@d*a%tyRQNXZ?nwtRU!G*BE)-a)Fq;PE1m|gcx69HFf%m85Ybnn%-T2KR zdq!}PV<;X6S|}6MAI~}tv)Mazo2bnvUftO3;UQkM_%r?IK?>%(EI<6JJ}8hosmxtv z1pw~l$36Xv)<Fa8eLuP@WX@=+Ye7ZUt(B>$+n#@81!x~-(YUv0wV|r5d%s>E{22Dj zZsRuamrp<T%cL`$s!gkzk6$6LsR<`zaY!L6Ac47PBR{){HrNdIXyYCRd{IEw?s0Qw zEZ3?f2x6`FQG8vN{`)$taV&sAV|?CP|JQ71GaTl*ssW)(dxLvlh3cqMw3oM-f(OU2 z`z+Ljdyu#1=Uc{mGf=@ESHDuDVYK`ElA^v8^E$0*EEwDb*}f|6AAZ%Ad2ZJd11BpA ztA(2Y>Wh}(mEBAzC(V6-P}_*HyD-2lk^y1`i|Y>R=b!;&VuCgYnTmO(q!7$s*F9!L zcBx(M-#r%oOO#PyHJf1uxkgEwF0|iO)rK9OM!!8h*Y5Bzu@m@NOdk0LaV!e8{8_M` z(!d)48LQrw0NEekXp}tzTV4*N%hafzBfIiS)Ty1%J+;GcF@i(I8qs!+)OZ$^5mptJ zOd0aqW`CPy>g*?%BZ54Hd<Q~|4BK(wHe7mMhic_>j`YwVWLOQLWp_jv@U=2l_K{Yj z%fS~7LPWFa8t41_!h3b=F~I}^*O!(fGz+$IdfWRuwWDm$!BdI)4&Ghy8c2(-5uO7f zA5%K^QeuXFS_m7f&3C*){sQ|@)4=NHiwrX|w-^`{l9Qv4Mf*r8VCp4QL{W}cQ2iY> zzJb5*=~b%ot0Fxe4uS=zr?J?ZGSUF<=8lq(Hm=$=0LmKiFU}GM#*ec*9AFTtS&ymS zUnc3_X0(G~l{F`F?r^|rDeMCiwFBd)i6t5oL@xQUX3l&t@9-NH7immOins!bhpa%i zl!_H0aV?CLG)OcH0Wv(SPz$K~0h`D#td=nDR3THdpeDs34qHISAw1EZd^YXCP5vMQ z>W2b^zdvsRO+L94*klUq5n#yyz(l7X(eLmrBKiUoT_oc`Qgv8tOenGU5Kv8#=p|mt zN{=usA|ASUCinn>I!5kj0@kf+wdl%*=e4M%TJ9?njNy;lSC8@r#{TaCmVGMyuP`G3 z>j1kSh^vPCFgC<PFO^(4dEZf@5bby!)ocxb1PWxMC}$&U=R7+gM{bIdLLwq)MFtT$ z&sSN79xAf`WvS`#z^<kJLv$!1@>{SYB=&SA*K9A&Q>+A!jSkd0pm%B<V+B2`+<uAz z$wimOdNx%3!)WLa^7Q4%fJQla3`bLzBMlujh)U;v2o2rO(!;o~pMYesi{!Iq+Rb>Z zq<p<sg@f*rg^>p`yViUf(O5<_)}9P;>#-9gs8u!?FY~ts`Y?j|kS+EVZlTME9oIO@ zr7LkN?mVfW#D7$YMB733Fdfa--_Z^dg;IJb9hz!>*Z#+^+Gxk|2(sZ2Xj$ko9xBwy z_;a;=WeV3;#XvWz`={d&;kz;yV<tu){>`#{5aiw8h-w`nUVJA@CN46((Z+AV@A7Sc zWEJnoNOs}@ESQ%<-hUz<%pM$&wOE5oTJ=r#cQGgIv*#>~-fhJP>$lxObhjuM&>TG6 zTRzzg$ZF}Y0OdW6-Dr=)3=#ldx-<pDL09qk?jOJ*3FXBM?_`>iBWZd&io{%c6tUoY zQDgW@7F6a3T4^76u1;hR>=SOniY<edwW{wY&X1*l6#sd)$It#ykNlrHyUrL=3HMQ5 z;5yl?@fiK{I+@QHSlu84#DRZf$T`B$Y=TP}yT7VYT&W<#E`9X<ZqJP{%dKCc?4);C zWK6g78;T)Ht+qMybKErVv?GxXylV6#tcXYfp)!AGNdM9ducINS1t<AT4`UduzzSkR zN6r1cfDFmlP2nZ?>`!V@|B_+<Y%8RP^d0Pf(;KcClqX^uT#5PX1g|2pBk`5dVvZx? zz=&=H;P}OKGiL=znGD4jmMhtbg7PQi>zSIJ1Pn~b?0{!zN;nZAWjgg_DxgTaE2OOb z9=%l#_4K54b~In-okuKpzJ<BDhr3nwq6YK*7zh?Qz<A0J(gBAUfh5|_mlTsgSVU&Y z3f=_~e-))K*<xCZzMzaqCQcD0W{L<i{DXOxJZ^C>$vppJm8h&_kmScF`f$Qb?gjCd z7-mgPD!Nx5WPd5y04!!?9Ggh0!pVT&%HKcuao<j7!C}QOc9ESWKlp(8F61~gY+!z4 zS}=m~k<29tFw{Jq0Fv?l_68jIO$={xvb>SETgI`QG0GMH?y$leCUQG714LtLSX?H| zh9Wum>_1aE<qbz75aNj$cwNcErNJzsMe8kOr>HzA`~zO%MEtlqK|^9~RMMjS@S7wZ z%zhj}U*59cZ%l#YN)>92N+iT-^%}rnYBk0W*6CR~sbZ3F@~KH#m>85M3siXQ7=6Tr zns3riFs5pYTpJk}TkSQFM!R}+-O-NLN*s=#pb52QvS6zvzH@xpwug^yl`nBPY_-#w zzLvYeB4tvm+DI5xMh*K`Gb}r(P-l|3VYze|yuv`E<&VZD6CvJS8(ZP30U$XGKBH*Y zo!VAA!?cs{wbuOER~@;_Y!!2@s|Mph_r}?%0o(KIN(Eyq?wKVO=GRlGO;#FeuO~t5 z3!CkwP94aLro=XKFwi$sn&m4%Q0Ja}hOg!iW~!I`s<(&L{X+S8@CnFLEXB;vXnm}% z!t2IZAUb;M{aZPkSTDfj%KNz2f9tA5{YI^Qm-n~XEZ;>veC3+UA*gMS3a3yBbX-Ve zpQB+STj>ci%R|=c?lF)|QNH9u7KKE#`kW@m7g4ecaK}O@$=%Acslm_rO?ko;y_kE| zC-yJD@=(FHxAgFPe)X~jp)Z0Xdj)iS;}_EfIm9hP2q`lI*epzD*=0v7(ve_92hiEi zZaeSrQ+vTE4JxvNt2<17nh2ZkH22Fw=tDi<0v;v$YG|N}inX419Y^x6Egg_!e<37a z42J;M&qbtA5~#=(sz>-Y8w<7NTsF(eXJRJYJV(Q6YljdlQpUa(Y?8d4wUpUpCdP|a zJJji+`Iz|~=SMnN;gxLl!=?_RZl$sEubzWX)=%dP%}jIAfla0Ir--(zn=7c2O)%Zd zqYLg_^99|{G?{0)=QXxTs;B<<h5aUl*zxK<h;xd%NG8D+3Qmi8U61acT`L9;OMjNw zIsao0aBWB|KzNpa{2W?Y1L{#{>k0?>HvF-~3l({00j;NYlrBxT_sU9PS!2VwCicYx z13}jKn3%qD!#5|Wh&}lqkYgEEXyp?Hniy(+C_i97e`cN%lO<a^&%ug5I0}sn^b9=1 z;yULXWf=XEGJPPvkH+8)#>WGTelM1h61}U9fM>-@<|vs`+Bv>8#UMxI2XiG9jxVH! zF>?(qY-G_Z&=MRG4??BBhfX|%8z(XU0*#$3Mtx|3k-Abk=4r(HLe0s^d9XFxxPei_ z^#(bJ96M1L5$btOT-^l|C*M!z6hB%5IzfubY9uu5r2NLZDF(?X?E;`k+qvS1geZe% z${S|t8`a4(#b_|HhzUD{ePL(@X6cBB2C2qkt|4dL=lrS)F9xO&?Vsi@=bK{uMF^nJ zphnQdN_s9mgLkO9(B^?i3-Egu9x3^oWHNtLe}SRM6GTSAGhS*iYWYHz&@nBO`3>~p z&2WlOZ%j|nL@y2$(?=NgcX)20F`sL?(69vI?y6@;9QrQ(y5;4%TNEUVL96XLFq4dx zYrF0r;Lwf2o$wAHy*QxRu@kKtf%BqDcA$*U(XdEvr5%m}h+2>KQKLP7ZG&qlfRR02 zXz=$DDd)}(`ksu12fJ5@yYWVyt;#kYJqJm&<NNGq@8@xDI-0StYl2jj`$)~BA{t0s zse?hd%r&5sdN;@seB{EE4DWCout9_3ncVWe(6stOC)ucFwyi5atJd_=I$S+&@0soh zb`rx?V|x%SmzV6b@s0yf<Ds6>vn*`>-K6szDlkuloOIP&sx~>17>Ed*vs3>BkLhkJ zD&JNg_oeDJiokKYb_UQ8;{DVK<=RLAu)8_(5G?~UjPAlP?~5&G9t1L?HDBrdWBtx$ z_@S4|GpaC)r;iRclrH#a3>$3S&O}1UGsu}`K~ouqD$l|G-Eug2e&-%UMTbdNK4%0@ zn5ORLzdD3#`-6s1UThB2<6Xp{D7wv8L;uFEZ^UhOqt!UWIO70JT{$dl83}&K*wuG| z<@g%-wD<MlK;4J(6_cOmSHGuro_i&8UbOi5kt5gL^5nu}Ey(I)=HX(S^8PbX4CKNW zJ)u~m3=R}qTzX$k?Vnh$p;c@EorSFfS_S0NXKA|;9GFCA)yrMN*C%S$7V@waz0`WY zT7Li9vDlk$kRJb|Q12je3#qdl<YY{nMF_>+fo^DE7Va_?;=Yh?NP6VLoKWTj%-`h& zuY@__2gMZC&~Uy6Wi#;j8N8JbtIJ*Fpk1Ha4~RZNO^aX+l96q4OQ+1FRQ}bTXRK-O zxjWa_Fd@H;3ZW*C;y)e<Q`;{m2c$@lpDbYk>A!vMaxtlbG6lNtO&YP`HeA5Eyr@ai zx~m<>14bW--SL4De8EZK!m>u~f^DMWVCM#;X++W{4MfBcO>+P43HY-lm~MeQ{OVPp z)n{fMzG(Yv0LF?H%sf0WG`4Z_o25)bG-0fZ_&$BndWZu2zd}4tlCMot4!^_FC;j+0 z&aT1=mMljZI#Ui4?d)jr@82XUM3JN#D4$a3I7$fNZDMI~#0lyf{|udLQ_03PiN+f) z{31GWIL7&oT&K*Bw<kj|^Obzc6{T-tx&0$aa#+=$pw9B)AWVqr82%!jq%87DT5efd zc9PZ3<Qj%by{VEgnQ~}dm6m_a2#_n~J%eonNKka`X$2wDo&ao-w=X@K+$v(!K4`ce zk%(Ip1O<j*w=27u_B{%a^qye<9_!0MZ1;sno8P=KVhwkNs~?#egY}13)z`YwDJI_G zg9mnsHeF~S`_40VgEfi|C!T=)5A2{jZY~+gE@L??L`_Dl4&5;o@5%({UAEg%e^7Fe zUD`Hds*oNzerkf%O=vM*H2afUEGM0&74&Ju>LNQSj%<P_6nS%8Zin$<hf*%B)&c^$ zLYfR=O%jjBJ{lz3s1H+mj6h!8<>xOB<OxAs6d%y4?A`ABcPkhBlZ;({Jr{#uYq}g+ zaP!l@;B3M6Hfc-*0d{ZQ=b?9q5rj%7{XTy=mipE1bJ%E@t^C?m=~0~9A~7{HTKk*r zGam?lY1hP%63W;{N8W<2|FH{Oxj|xISIe|cCT|ur)&;TwI4!D2b#7hv5C1%W02q+) zz6|uYyLun@Z|5_<a(7fA^I(~sHgLYlSGA#>ksGo((jpw$@Hy%j9#4i!tNsuIiWoZs zn%grX$P7qcso0Ea)x?U1?z3+7k+BwsF1}HGi6X;V-%y#DC<ndsjNInN)R&mw*{L~# z?NKu=`aPHMmmptlC|HLn^&4WK<J>bppz!Qe?4XpV2h^LQ72*@#&k(qI`&C;9HHg`) z?pLyX2)pt<d!02x$-8FLwawp0)D26Tb8%FuYyIu)q-TcOVn5)jKtR49q{W2QGFIPb zV0;@=96YE>oo{aUVA+8r+m~OS;hKpVVR31~314=`Uvvc`3dIiEQZ22(vyo;@6lYd8 zdjdds?WmmdTR$}#k7#J*MvF#}_Bdb`7MRmI#+YyG2pn%7A~z^yBtWnNhnr^AMA_Bf z4<~c^g0H$CnVJFZx4=`23X-${M8yKwttu<g@yM7<{k@KAc#2FF)FYM;-z$12Z6Tc< zgw)5D5W^r2OG%ChE4(1+B>$h25!|g-^ei4NGLjiciSJ8nE}TgtaV;Uvhv4~6cEVMu z5=>b5;7g<w#ESXeI6;*O>-G>J+@je~^Lksq6oU)XR0<rJjWNhQ1(z~|2849MPo>|8 z;i)9%61e>^Q@l-BM$s>lh|CqRPyJ=dn=6p{(6%|AUqP-AjGe;9!&Ve9L>G!IAYhTi zGIY@4Q`rUlXGHah>XI-ShO{4t=aY+=`pLU2ot{Mj2=eWQh_I~rzV)q_0!^T+i)|~5 zBADDzL9(elu?fw1*@6#sw{cXrbCwI`KY1SCc>}o;6Saa|Obs57FK<V4lm+P!wStZj zYC%M1B4EPj^FM6pmRoG8S`~Pl|HSO%)wwijXvmjuDX>|k<))b8fE}@Ie<vmkwa{m# zxzzN2QNOUu*8qo!{70CiNYew~dt2WMikvUUqe~BTz@G|Dx7Kj`TZ2MJUHTlo=Kp(= zlBN{BGCIG5;<Mwt=B}=UG-$|HT?#RS7bMdtxq;~#SXJS7WQ51B$){E5Z5Xbf<Azf> z9QdF+9MYH-1<FL>tdD5$Y=pZ&Bhw5*E3Z4qiOn2HNu7zIBQFKct%Z8g@t~<vYqKC8 z>S{;rFEqUQvH#)3pJW-Zdxj2T6~C!gWGWXLR=Vy4@!$+*g1iT{<Y-R)VXHP%VL05& zlN3><RVx)yy%X|bZ5|5D*@2XILf&TPN?R(^+%EpRRJQ@EI~n9vF-rT1vF*q#+i&o; zayicH_Pw7aq2w^?o;QRs;DP>}J>qMP{hG*fnRI^FS!J1DqkrObXcY6LwY}E#i5O$# z{{~W+FI7E#q@&NJ-D5P~Ew|}4ZnD4Oo3f(^dtnt=lLmxrz-J^SZ1b|z4#Dhc1c7dY zm#H$fc5<98flR2Rrr*qCz#i?eeOx}-ZoX4##@N<pIK*Oj9+Pj_G!-l)DVdRtI2WA} zN5TnKf_8iUA)tMnqF+^`wdytzGx`c5R2H*p_L39p?s=qluZ`MJv(?3%)iWi-HTx{e zc<BSJWbHFE1wu2~6+)Wdm~!+)bv{=uk#i+MFm5x-LvM;TilIeMq*xZg$T$WQU+8Yg zZgCO6Wd4(>F$r(2oSdS<stJ4{&y%qd_ebcD)1r!%=7vy1Qz0`6?ny+F+|KKV!4y5~ zESmb3Nw&}K9GmY0<(enFj+TiQrt&(_U%DSObxQeShx=v8G^_&qn0trlMR$L>#Kj_E zQ(#!4!s-kZUpDAAU*#{{e<x}0izHQXOs=cg16Ch9=)+G*J87^@h5ckzByiOt0LwL} z;S|865b{nVX?}xlG*@(kEC9Do_g+r>xXfH*=eW(YB|#HYlN+s56QdmRWj@=|#Kh|* z=*kuPTEQ9u?zCs{>1vDp+UqV_j0sRG@`b;#HY=zbLmejfaPD*ueg!d@r^iei(SQdY zwRXIjAFP1s7g>&jWiQiC1hHbeYsNzDhQMeu3KboEEt*R8vs3iwqh09VB}3@(%<n&4 zmTDs-M#sPI4R+M!>8t?^P}FEw)*bn2c}DUNbkK?ikG$j$5TgK+PhZ4BA-AM@2E0i- zbR)XW`z-rIDuvl!Mb*{=K1vS#GdJ1?SB-LR=$Rfa^Zz3ChYOaV?hQ?5EK?9nvD(q$ zt{5pC2Oe{CtkSKI18rA!0Je!748M(&62{gpjy)Og<Um(FdtAC+y?D00fJXjVzQRWi zwXLw~g1o5{CX4sM3wMF`Klx<<*TxC##{1oQGOicGC%>RHhMuY{V@udyL}OFqko@}= zIAPS^bUmDd?}#WtRRnz5und@vd1#ufuXdZ63EEADYKA}!c`oOydndjXv*4Ql!Nlkx zDu1Z)Nz%`5lW{I+Bul^&vyxII0q-Uv9`6|RU?XUX1lJsdM#oNE`)2h!vTGl{=``Dp zVjls7k8H#E#BV0yCL{$)fJy_H9qDd~(y`91T5(YpjiQ57fD4AVX>a8#97{r)^uxOi zIFo#2MzjnsQ6DiN`i!_#vb`IrkKNqDLY$p+{GSPuaIEQZPQSRa87b?9Ev1VK?0gk* zE+H(5cj&-3Fc~}FN1$XWfSaF`WlsQA{DXp)<U_k^E)aMo^h4&w|3^<>G?n_W{Lh&M zd)ND)XnE9dj%<-fu|(+rhIDYm9*mQ-t^mZZhWai1iZ*o10C|q=V>}>}(Aa)xme`Cs zb~Tw8nUH@V8Wz6(_6}Xu;+HFb&iZD}(?iN?oHNVogP9>pzUw46VRnv&ZN&Z>amDYF zK1Q4Gw~wB48G_;)`h>rnJFj4>TOm4h%vIh?>p}dM7i+Jt+3c)O?XI>R2Bv%3emBle zLaSZ+>!xK2u03AJp-V--WcR{SS*hq1Briq*{zA&MLsS@3=*EVOwoD^rilKW1!WBLz zqxQ<4L|>J--7WqO@bu|1)pFqL(9B;(IsIRm3>2Pyoo}YA3ow%NEbO<45YTCzysU_2 zp;x+7a;~aY+JL>Xsa<~28y=SRD6I<-de?_BsMMUXX1bMm04ch{!C+Fiz$EDqxOa6- zZ!J$wyC~zPT<?-r<p?K+`++HK>Ds&^1Ubqfd+;`t*!Et9Xf7642AqiqCpOF$M*{eQ z^{OiLsC9oKimz(_Bu<G~ox@tX8w=tS*7M2Iqg`c~ojLQh-m*ZaP!A86Ti5#3cbq+@ zZA~!C0zuJWKP`Hz`ryQjK+Q~@Zgy`ax7id*uhKDW(E6Q;DU=2~f=q9y=ym@ag;rlM ze4UZ>vS^`8VU|w}<!ooOzpj)OT`H%LE<ra<ux||2<GUdL2K0MWV8JK<@nzQo|5?k` zBEj_Kk_+P+-iJ;b{%W<11yME2G{C_8F98W+RNPnS#o^{_!3#ubKq!raa7V`|NAc`% z!}#s5arwd4V)~A@gLjY9pVCBQ3l5>|X^sMzKE?OF$j)f6O>6q(8HVY0Fo$nvQV9Rz zzjq2$uO#G5$$*eoh?m<S%gl<0d8sl<xoU{5h<@saK?tDJuw-3_)SFxeP!+GFFWXw5 zH58|#_5l?v%kSrlq0aNhJH8Fxg781i^#}#WAwSaS7g;rtmnMy3P~dhSlu7~)d<%1% zP56l*Rr7^CNA{LYw=IT?s93ALwiEa1$%JRm*yloqZ;^<J&^>%4D3dUTso<#wkIE__ zmw>_``X4(vEJHF-F%bnvQcCu$MUWh;lF5T!U011yt=PY}-!9mNs)&-dX6FS2VL9Dy zQ_HBk!gc#C-Da*}4F-KHxZmeuMEwszyoFFBbdGkSF=_rTUf?v?B?I{WU7cjKK!P%V zo4*5J#*4WHtV0*ql*7fKuo{P3x><XuYa*am$2>(ugg;U1TrzWm@OsY7aqo2l$G<WB zHybkLJ%04Y`;SH5de}dk3v9U%@G^D5S?<ABjMerKuaX7I@W*II#|`n^CI(f9rmiDf z>#TGt3IePLjQIJP{`!T}YHhn)`jH*rs^WD`vU()sjLOG)M1r?>MNS!|aQS_yKRpZa z-P0fKD_&a*Uk86qLjS|PJ>?X(@tWq#g*&_Q-DI`hhu*w+c|l4WtuF@-Z1!bM1{qlX zz<70(|E>z2J?y{Q1Lz<6NxJlLQvnd$@*wv&Rai+%&}v-)YYFv`C`%`73=nl1TG!8c zrlS27yw{3HL92M(V*fB$M64pfm$>r91(0LEK_+c>J)!8=({a$DkR)B6bV?oU2V}?E zmLBrPzC2lAt5u;i5Baq7KQ3|>vc*+5nS9(|N4j0R3|#IdLROZ%16G!~x{xPdH)d+9 zkRHP(8-T$k!@ziI@bDQg-kz+RpL%#Fm|$gIyG4w)+rCz8KbAoX9nCEvr_Mvi>u&xQ z2=m+CSF*TI&AH69ql0EcG;+*Ge}FfLZY-tsALh{cHS76#q)h>6k1=d_?_WZqwG|!M zkpD41>&$xZii{bhh*b~#RKvfelvmq&#d(PQeaOo%66W_(LxT>8r4^}UFO?*{xQHaA zVQFBYY{U`IO~}`Takv_NL^b?kP@22}u3hp(jervf$qlNa$UZTOP(d4ZTwsTfA%(*V zd>e=IpAs{0@hkwFfA6R;u1w`1vz~746a!8WaRF7>mhb%=+B>upIt%2AP04{|OtcL& z1UjYsCnzm&Ye!^)MBPP0BM}=#-!Db&hG$P>!c&|TAYF8nXn!iune1j8rgG`O7kbwI z)BUIGE|;*s!Y#p#eDX!p>`XI6h3(h!{+6b(W$#tRL<inryd_uzos%jBy;Z*g?P8}l z3_%Rr?;a=$p<kUWvYlEb{Xo>g8K4;gL-Ft*C0HS*NOfP$MtmGdg+M5S#U(D!IJAtA zK(CFu=ds22GQWq;CV_#sVx=7B#oZnqD@GJr5+e8SII2a6Kgq|@WxwP+jW|e#6Gwdt zM?UpmJ@Gbo@f~xOG3mG5_<t-SYh>4*MEAvAzLmEPe#!md+;5!A1d&~$zs6WK_)<O^ z?@vW$zTFRWrjlDj+fRkCschJ!{I^vdHL_Opt}?|cBt>~5L9G`Hk|n|1aKTvUVrj*2 zqA`fOZhId)TZ!!Rhv*qk6Ujc#vy<X>`nT=QZ!f3V>I7+)a@T<pkNO<~t?uv;gUk3@ z!{Jm><l`V7Qc<FJ2*HN}JgW462DE{LuguTv^cN7wauReU$QV~M;oyG^+3k<+tXFlZ z_95@mtsK4O|7=D_Plrc&ud6-`6IJg%cVEB!ECh33@zq)WvR~WJLwp1;n->z=3(xak zOJ|_)5CQN*O(h$Lw^~LYAD4?M*?<=!GoORgTSH^rUpO7R$lu+l+`@X(l(F7|(WH?6 zWsCN3wAFTQ@l@Zm?2ydoTps)xmHO(!n($|^(mnGTtBYt$DWvT6LH3r_w*`HdSM|Qk zZQJ6@n)|D#$vFj&B_&K2;#xyA40*v>?*#|RT}w;KbS<C>`o6AzAoiKgY}MGZ8JG(r ztycN7lGy#Jd|nyS5mKxG$kykP)o23-f8zX)PYOAAC-PnF|LxQ*Yb3zK|0aRah(i5; z2ojt`ozLqc$#QK%$>Jz<xu_?kg*9%fLYV<kk5<JpN!RcPL2mC*95fyj&H)!|Y8F=- zAplSX0t|Ms9>3j52kArk_EfGMG81t@b$ZJ*n&S={Icz?OvvA8W_1;XU@cyArFbysy z;9l*Z*d9gI6nQy51c2Bly+MFTiA(E*mYrrZlH{&tf*c?hZG$S|HMagTMV%}Np)g$G z2=<2zT>)=O9d7*RKTJjJ$^a;L?FaeP5)^BL;l0XyLQAm5=UQ&Hw;L#hQu2JT^C8eO zLwu7EeF=NsQl<0Fgm+MlVHiCweeZX@y@^7*RUJ+_nwF94fgLTQ(y>Zw=kM33Kjt4K zG^mrKPe|&IUqS%tR!ZHAr!VnP^KC->D44a!6+H}6<DBkkvp1wUlTq{&JrV8=f@JV+ za3Be0ApVSc9%rf3Zy*NCK9lefJe~4s5aD&{kz3DIm%Bu*c6|*<t}2i7#N^Z*c|je5 zXP*Hx-fa<m3g@=EI#E5b415AJi{9LF;kuFZi$N{4Mt^U47m;H2YOzFV9oGFrh#>;D zN(CEm66XEf(`OdA9I6$n&^DYJr?%z)45A<BtS>hWpV)sAVwBW!4G+qsh@2m?b4<#t z;8Aozhj2|VO%?bbCv6ZUCBQ)U{dN$#!1+ZykcDX5$T_Xr&jI;U9&Xv5=^-8j^OYCJ zJ|Fy3u%;^Lb(UFhT^)?Gn7AK%8K;c@47vkRo7b+_-s7vNCIj93;qXt7TbZ+w7q3)r z|IDVIsL}FAXzp%LHm!F?F|Rd179dvLl(A(csL3ou&%rz<o%it8*^kZpr*<+F1DyrZ z;b@d{9WqQ=x_FK{ph%Jo6yCZR#smS#edksX21S~I&A~5sA7ev}B-~{vI-sUu^7=6F zc|iWp^NRd`Sh!3@l0U#c1~9I;_3)MB<6YLcO6y(X4#l@kMCr>LMr;~R-^Zk$o4>ON z{rU<_feE%Qtkt-rW}ZE?d8a@R)}2a&Ao`+_$(>lfQ}J!=?r)wv=^1PBqNVw>Pu#d{ z&Qu4U{D#99eq)ob(*<OW)`!ZL5LpcR?e)qvkS3y_J2E4dNd8LYeUfc0cboy=eiAHX zwRXw=DNOFsMx$uAnTEYBQSobc4SyDflMY;VF5|q%w4Yr1Ai?%d*7|;Eb;7NXFmaxx zf2?%k>iLP{WsV4xC-l{!7q$`Tt%CT&JPp^=%}*su;Gg8>v?X5f^YbowC~VF{g(Ac* z=mrl#r&i(*lzR5ikk>ibr!-|&br6oMcK9pyo<71a(}-X3v)fYzbb3#IJ$9INSH;UO zDE@0cP-8qv_siZ->YAz4^YyzKr{_`z!HV*;IIVBO$WGD7(Q8&HSF_UypV(_o1mP-K z*eiOv8LONjTPskH8ZC;qFhS2a>RN9b4>MTX#y|PElz}stZfZCEOM!YM=ZKYk?R3lY z5)t?ouBV!i7ez<5NoHJa%~SXo_&3%}HC}vlm!2yZ?4zi5S%HW_B`C2q$BD~QmnIT8 z1+0VO<aqdP{s0ky7;50#r!jE+azwhl4z7U=<gDwi#mZ9?AbvNt!kXm=%VDGVeCXl! zv*GHJ8+NgK$Rkp74mN<bV}Xx!hQW*JEgd-MBcAf7z$`1*E3+=zN?aT^z+Raav$gVb z<T%TkRA&#Zt{=(NELYk!wCyPT&>A+zZhdEKP~9RXQp$bnKYtVQWWHFT6A0K11N>>V z%g`;0?PK<tSH9km)QuUW>UID9^e-zB7`ml_<Zm00AEAk|9*2!4+>*%BLD@e$6)iRM zZ17EV_)!+9(+LZKYHmX&hN2dXQaWF%(!qLB-_{a^u~-C`SQYOG0zQ|z{SX-hyec^c zpzx>=n~womh5w7^AqcKg^=<wT8KD^(!Sj29J0+K58Q{i<xAFrQGbQEvLFy(Tk+9I< z6j~(wBnbtMm>oFghw%Ir47NJL`6dCvMowr@Spc(gF+McU)dx67?q|W_FpygH9=P5? zbqJQVmA_}Jd8#XGG6LLgxFG@^|4PudNeCL&OJ8hNB3P{*m2I``mAgrBnJnxwwi1h( zkXslu$2UAMwjp#0{axrPbcNK&^s^kd(b^YukkeR+zOl#NNS0t-I=Bs_XV&C=E?{h7 zKgDd01V;@~EmJ~~O0-G?W$}O6F{LTXdF~)m-jljvh-zyX@@heF?irm`uG^e9yb`T& zX>~RU_jkVd!nG?-ck=L$l0s^%%x#(<1ls&O`Qg3=A51gB0>p3bjNWlDR}XPiuP`E} z8=|^$!#zyL^kfHWd1PzhuxOLYx_iezOug**5O<L??hxi^ujB3|WZ0swgGb4O4o&n& zIRkJPz%MK$sm^~I>f|2peWEsCJ-T!Geox2I5yhAgPvEyYzvxmgPUpI8b3iGSfi}=u z1z_RJL&reuXhfSTC+uY)M<YT=8^2#5{9R4A&5b6g8RI*}4p^&t|1q-^Y{>Is=+)*_ zd#pdXlD=X<$Ov*;R)2H4lh+8)Z(+WCB;MxCyu~kt6v*zTm+}$bi6Q1{<PLCPA$;Us zMOZf9NrP=0Fe(i1lckoMgH1I+w<gB)cXv-+Dq${@CShFo*njf4;v7rE>U9r<;Smwb z(OoWTYtiu6e7zvUR8>@yxvX02Ej-MT@QcUP8Yf?qJ<3y_&g1%YHA85A7fSo?PixFt zViz#ck3X|h7;>c)CgE!e+k%0334MJ<i4YD$$_SWBgz#(_zDSBEEbL^CA)Y57P}Ubx z50yB~o0?9tb`ee|2C5SwU%WzJJ;MSPiUt1{5c+@boxkhm$r{ZH?!Se-Ll4MENlA&v z6bmD7oTm$%1?rnqOpfp+3lrf3l}zK>QT^Uo^7MedCbp9N0!bHG(&6PZs#DbYV6`X+ ze+S8j$Q%zLe&{-8gY;X!agJAp4r18vmv7T+I*?+i)>^u}+bKDWWMTkCdl&FwM2ewT zfY3H_@@N|-X@~akSkX7r*0_1kKjXD(giV&a+xp&mcK*e)#IN3FzggMoR{1YhKttbp z_jl9gIChO<PZf(}wq`t`LRc5P3!$;RTWtC0-1_HJZ}kSN$q{Q-eH<<OT8}*n!-S8O zL-hN03?fYvJ?bkqrD7Y2-``4!8l-f3j$;2SNKE({d)6zpP3efYFd_n$odZQ<WN_Aa zoYu6)CxPtZ=Z*rvv8+L<ciAt13LKq_g~d1ny6zQz!@1ogJULV~gP*!e`BVbUI~i?2 z8omwVb&sk)R@<`ne6wD1^-1W2_K0HUQ}+<!U4S?MnP!y#Rb{k$(*9|(#lq<>G7-VY z@}Z0fAls@kMwum;&*Ni=YjAK{BEPsdG#ag0{?F^pm{VR)c9@RgZ1LQr%Yc*byn5Ut zcV3{F@45VqCOD6KqIOcn{!#Iq#uwiF!mV=LiPqo1V1(8+!uzW54_$@mmim2mKGE}L z17wvUr-4hE_t2-iP2NNHz3+!7?asr(ncj*;i6AOVO1ML5sibtXj{Yt}TCdzIk<y&a zojfQgq{YSC>2%`})pbo-EheXbw-9RfuM?cg=R{UPPs5X1-vLJPhB?6SNJ8dIwe@{S z2&d|&OEQvstnd0;vhT#yA-~rL1Ll`8GA098ll?!dnuVG26sx^|my1Uyqsc23H~d~@ zsV?D3+A@qbZ7J6Ig%g_PSK?p`z>njgfAhK6SqL(h<g`a!6P{W-_3*QbHnpVsTW_a! z*xej(DEsr?@*i(1qiZqJRm`N0W!#0A&nOR1_eFxG>gj4UHoIc&*sGDr5}RNYemtpC zamxf1MU8|aQEo<?L9O-~gRi-EZ_ONPoW9kTk@TuS%L5mPK8PP^6C}KEh~pD8jtb6Z z8$#Lxb%%oG-OT}3?L66^1wXtK*6;08Wm}=DZ%6MT(5_K2a=9W&CrOjJVkWCJv4mb2 zM$P#%<qgzqLSv?i@GTH3yQja9CmXHEcuA66&@urPzR9W`Gk<LFkfH)m`Az&x0#8v_ zkvS-Aye2s~*7b4unl!`FL)JtgUSe!J{^fPjJwWQ;yV*J4*)1&e!TWg^%94BpE1*oj z-YWOe`eZGx{`4Q&{(Yyo{WF2`xR=miXXNB@(JsQbEz#koaU%CAotFQ2lyx*gzJz7n zO6cI72G771o?GprYZ}SR-*txDY7y$qiQsXAj%c&aC%jX=kF{)PEzRvI&bpb_t`>Cg zNwsNE?G)<J_m1*0Mi316_xJ&7e$j5zFEH_%=**v}`FEMV5YaT>3(B?HBM*$opShQ8 zIwGMrz<;dsZSSu}#8Y~oV|)K)-tr?(jCdrEu6R#mU^29~m!4MQaT~>X#j$dw-<{~R z?47RZCaK_2C0~{PHJiD&AxhkGS~sns(!pb}vtTJ<7mfU3+7Xms8<)ru<D`e3<%tJY zb<vbMt;eD1I7?a6vQ|#rNaN{wh5pH|hH(-)r{9mpN5A#rYhJ>n>k;~78|eg6pDrvx zr9V%*Q#D9|2uoa|MW01{9^=oi=LoagOZ<|9%X2d{OvgXB^Ou^oyYmff@%=s4+Ovx} zdu@G=M8A0N5H|^sQwlFKuQmA`c%O~Gb5l#Vo%Z|vYT}hn?7aq6U(fFtUu>TRG}^_t z2|oTBEmjbc)uzpISJ+hE-gg>SvOG(y*{JOxsSAptb1H@FxyZ90v-4A2^E0{U((1ow zIvlQb-p~BZb7`HN^PuRu!byG}^E|&|sqknSZ{U!PQ)f_6-d$IF|CvVHeIw_A%eZVm z^YTl3Izy1Xx7BLuzDag_<M+4s!m=(TlftZLK*`u8X>teG>q(2o+A2B!ypK0-CSf5W zB^du+Z#@;?6gg8f_j_j-bO)C>0`mCP(Oy*s)AQT$F#AqlIN>niYk@j&DdVH+R)zLc zE*c2oAd%M)u0@f1V_?^7eCt1qP1=I)GiSAoyVmlChhw75++9jesKgB<k{?7^rC}2I zAH8O`Sx|)%vcRTv$a)_f8{Yx6{<KYGkc=D33uM|&D(2q2)24mfV=3<9QOo&@oHHdu zV|)HTjJ-uzTkR7!TmxFPP^5T)LUEqr?(XhV+})j);suHqcL>nnF2RbXxDy~)AZSV; z1n1>{UGL&syo+ylFV5<mIWu$5{N#>lMC{Px=MUSMy+fXw*&-Nqr+cp0O+y+$*t^Lz z6A%!0b6nD$Kh-Rx2qe&fQh&srB$*(^gD4M<n^SA=4Q~R+O@5&t&8$~CxCJCKJAS-o zc=E1HN=LkM@>CDY0R~T;pI2|Vxl>b{Tb^VVI-*}1%k#!Lkk0t;7tV{Ji_l*sx(qg& z+@ejzs)HX~bB86|DFV?mBGrOl%&y&XMQF=?xD+4JT|YD)##`=GM>a;X{6W5e^?O^f zQ)ya{SoUPVq!DYj(@Cth0hvn)UCR9aYd&F_K-$rzC@j7Lli=Md?tNGSr<$+2Q#Cb9 zc=mW<=|9)>wz)IyrCm1M?n3a9XA|ih0bd=vp*#mxK5*HqFno}2p;ogvm$up>P{(Dh zxD}W*X{18Jsq-L0+f`7)+QcQ$F1f&^omNWxZ@nT80$7U>1J;c$Dei?U_8XX!2;G9_ zKIim4(Ksb!<G+P=Q5PY|Bq-|tg)Qk3fS~ABFyUd~FH9E(?`y}<Hl6F1<oLB>Dt`dd zRvBXNzCPSVpE)z&%FDk!(XNJwJ_&$6T#a;Q0oE4KQTzGS?}AFb{<Y7;Dk)hf74_VV zs=K`*{=J=6LO>Ha9r*`P80UhEPv^s5kq-Sl4!>mN#<k`(5lT=|&-wT^kW+0<wx4e) zi?tIZojn1a3gCOP*_`zL^20D}{$w(=ux&py43d4l_08CSaFv>3KK#CHt}?-_(D-=I zFl9q--!=DTQG-%riObq#$2}#GX{%(K0m2zJ%|f=sAA|c`Oj<BE(pz>p7MH?+*8kIk zz6S9}vF$2F(`QpZWs|pGJCInvZ4OqI9gx*}6ARRn{_@U=s|Xh>6`qo>_>|Y5JEJUQ zlb@Atd_dE5N~VSR!((3z^h3?8Q<AB8WKum#I2)9<k?v2z9OwDuNFI-nhL?lC$`r&m zFcaFO3Q}fvT^X1((z4RJ%;C*YT2bT6NodsR_>@s>^*b=TP=3u+No#&v)&&0{9Fuj< zmgARHrUhWp@!Cn@QCy)Hs*r@Shgw(jog5QjuQOCVIWhxpoP<CWs|B~5Hv7~V-NwN- zGJYxig7cLtvzIY|L6$@R*v_cC)KB*p(vAu!Kv$_xbd|Th_J|I`$?VEkc;=gb^9?n1 zu%v{3{O^1xr^kHvIkf3~ui76dK^0_c-&Ot2ylo_jd)<$uSGt2n>mHnLef(La$EZ|5 zXB6Q4a>Tq&<Q6kl3xuV6z`o$>7k2W3qCU4XudEoW>d~`0?CW8EQK4q0xd`ieI_(e2 zt{-0eA~nE<rX_yk`tQ}PVkYNQur97bsiW3pOkHt_;?V<83;N=~&+3}{`mIF@B>nUt zx1{ayIONzG>Xwzmm*nzdJRti9Q6AqkY2R^6(T(@L>PRc6vru-g^{aL3*IJT}+lI}T z*V!q;`&ApGFMXpCHKB)QN4<cV6*PxNk89YT848$82@JIY@-f(=<g6EU&VQcMySH_7 z?M}$+acUv%d3Wqr>(l)>OV`;P?@RpOErJ}wa=f6SS;#2@8cGcxO7GMCa$0G>xriR# z1N(6u8>0%VrcPWz3-&2ECV8bg*x%2lp=nNEXU;qQPyl(IKfdu{Bnf;kBI_geQQ}1V zu`J}sI^zi*n{)*%GPr_dHw!OR4YJVYoreXD9HAK=lJ`hJGd&NJ56)=5I8)7?HQnMh z>cnV-<3(Sz9Z(eO-vK>$4yp0_ryv`$X|mbZgoNU_Yoju;chbl2sdBU{TjX2pZ98ID z-mH2OiQRmEO3(hw-&b*%2fuy{viXz>*D~!hzW1MDXc~G~Kpw)}k$cqIPZvd<rwwn$ zER8-$;ZAIwaCQaVTBs)f{Mwk6#s8lh3nDUw(hh=TAh^;4eH>N^Jf?m5%Y47M|G&M1 z0}iVE-85;6gsS5YT7lI70pL8}`1PjQ1D}Ci%;O^G1h0XX)%>FU7n+<DEN>ritp-#F z#R(_BgYRdR9HF#Dtw^1zYKzB~!L#0*<I-a@jcC{MNgd{po)87UW&WJjXi~0H<)N&p zWo4sq@uQ}LW`IP+`sYKBRP1j@uO>IzwZ-8yS0f|yT+sAxxzN^`ZrD8N;j$IAgkKoa zV?KqNTf7tUfX2`h?26!aAs(lLQMpN2Rp;guJ@Fx|K#uUJMv02MwyGJHL!rIEhIq;w zL|IrcKpWy5DF6lsVz}L}J4;Ng%K~#PHUty!If@QpOSl_!h=PL7RDJf6g#>_C(nJEJ zr}kLDxnH{)^0CBX;iW`|uyEDY44odn?n!%tPa9th!CWQ-?>1rRBNm?sYQHbieGeEU zRzDS|9;wb{s%FG1Ggn4AcR@tb^WcB0GJho6BBFt(@u-KsfS%5^*@WG3PVkJQevVrd zrKS;}#P2#6ZHZcLbsr^#3c8iiM_tFgnnNbE)$YL*o%#CiW!@@)a6~De`n?g7u0>cX zG)Ze;XFiw<xS|dw>&+*Vip1AEQ9+KELTd=3Cq_DxB{uxm4wMa``|S#RlVb)y(NMWT z|Ipt8r<%3WTVf#<7Z<r=;fyW9N?&`!R3CD?5BH}XQwIOI3ejlCLs{0XtG%;tPAVUE z++fN)7sL9(!r7dvC7C$~_d_N9Rz|^<*BCl@ZlMk`E$3-+r1}4596}{kZF2P?{O=gV zo1-R}K7Cr5?dWH76{nFTTP7jOG&d3+$i#{nl-7BV8|1?dV|f*rXxNdUe#vI5GXQ-i zDnld|&rqcILu&f;GvS+ea*Q8Z_1}C|1N202Q$3|=Kl(VDA&lP(PYw0Jvu9{r8XNBS zk+>E4gVLY-QU3nt%}9m|FVt(w$QV54tGaRpB;LRs$R%Iz`t->e))qrWz1?;hZktJK z`SW75Eadwimsa5pL2$4P6-s)Sssk3<qmmAL&iHt4y^7~wZMzoG{Z4Q4J$)WFDn10q zoI8X}%}6Z}$#FEZYjyHhVt<T>Z{nX^ltux&?{Pdpz-69a*&w9FJ*9<F*qm$Q(sTyj z9_c5cSGzuAhp|X-=+Ce|o+d=|sCPO%f}JH!+<RR+VaZzPclIDRe<uj*Rtt0+KYHp0 zX@DzU7F+r?x9XkOGF?4vSz%NGipa_$`*akYudw7oCzUyo)DX4{Aj5Iz$`L7ETx0<g zTW^_~{$@L0vwff%#skhuWH<CsC<LZo8;t+U?S^&Of}5yuXy9qy?#ZHrFOTvjbA9!y zlw-hp61qKJHs{+hwd`enU)c<r0|hI=6O7buh?+A8jluo2An`mRDYN8m%7D#KbdX3Z zXIa6m#gYWt{)&gfKbzm8#QK)GdAK+O4{^_(Hy)%$6Ba9MS`?NtZ#^}#Hv)KItoF~& zt8gU+x7r3=fkruq@WNC-qrafo5ZG(Q?7f<VB@qU7cVU%3l3`f>U8kYwIr+nR4~?bt zw2?NE#q0MA9ZV8AI99sn?0h0JH$U$8SPN%{EN8HgJ6#9iffnb;F4}0Sd@;1+x{f=J zSQ)keGxV~Hu~m#2bR9H&Ey8-=%(h(#_4^K@;zM^>M>goy^;CJ?hh{OPhmE!h3rOq* zUM(W3x_=pNpN<S1aV=Q{vAK+3q1WyOWM?N~K7KUox$@|dxt%JXFR0ws;LK6qQb{oi zT>fS+w~e({@|i)0z)AH+12&-8##4lg`54+oQ94F3GgI|t-fgOIz~#qHl1gZ}pJMm( z|Jo4zT+QI;wt`Q`W7(%r$1$vV<P5U8xR_`0|4{CgWnm5>5f|0mapN9`B;%4o8YSxJ z&KO(6`NXuv>pvW%#2A6_h+ZkWe;!BUfKvvC({`&<m1<oq&v}i2n9R1GzP<)NUWE7s z1L+kv8K20*t{JXr-MQUDw1gH8`iGlhZXST|qM}p^#IY=RMUcfumemXQhE=BLH@d>} zos&uIJ!C<NzfSl(%u!V%ow!1$85J5CTlUyLI;O8*EeO*g1ZzX%SxF(pt7uPflkP!( z488$iVXRHBHr&NK-FQiOx#kZDug3Ag$rzMJAt0n%)n8H-!*a5m--FgUm~UE|D0i}F zxpyymL0e;5>1pD4#NH{C(Rt0;{om%vO$yh(MN#@a+V1|rq4@F>1#j<k%^phF4J^%_ zcbs(sA866tB^$q?3~VvA=)9>#!u;krdX8d@_nk4=5!vT9Q$$%c2CK>EdNs0(we`6L z+9!A3BYwS~t8Pn;^36GnloOM{8j~4a*HR{-$}tgmgUS{TK}n5b51QBXq5kR7^3&B( zyiKDhwGKC*cWJqdxgZxDJgC&*(rg(AuiZP;y2`?23Secyaxt^|X?o#F<jeGJi!oeo zQDSUo0b&z=XOzP{MO_`9Gc2olq#q2umtSc7L22fvajR_7C7TLOj#0i4CTW!ue}p1m z2ij2Z+7e`Rs8(5|?9<ZDiQZ}+kwzgZGL80WspV_*H5=SS4mrBayq50s2qemaA0{2o zFLBu}QKpwZt4!6OZ@%=*bOqtAFFJ45HsnHM+$*i}vs$2cfN{0!pl_+UrxEHTAk^n6 zv+J^4X71hHpiaL0$%*ov1o-G|7TAuK2=t`+O1EKLy6^!J$8S8dJ3W6*pS8=@>TKR> z^i?^TxTs~s{Yrss`5pJGi&2?Te|vj{-q$!d^K1lWt6tZ<Z?>p*UIaux^&kq8HSZ&f z)~)G@nBtWsU4TR{{$DZvio&WfC<jk|n&Gco8$NZabmfpJ>DuewaiQAo=@0pWFR;b9 zyE>JZ?xLb$u|{4IZ*vD_#8Rq|^-~7_gn~W_y_IKq$c)`^Dpd%vP$U*h&DtOivN=Qk zyPOUPFbXxx<MX=k^7&afGJ7Oj-4~BOB@Va{M8snaedB6Hb}aHbOq6W-e;?%zgRYCm zY+MSfA9T7?wdBXA8$G#tpkhPj4(Dr5N1(WCs1bh#hNCDq_rPuUvq7R6*U&i~T{L@W zZ!X3Dst)_acJwE}#YEfF00SSY5t^)`?&0)8ZQOHr!-vAu)*vhAc1d0{sy=ppC!8|` z9m?>tdS1m}z4FGMWiB)@*?Z?5F^$xaSDgcSbD2tC-b<PAp3cY$*AKXt4D`$)Y-39w zfaR%~a`!wm2P9NNMN>S?nwJzUVoVa8B3^82rk^DAAf3o-PdS=AYPs{wag&t2->Di+ z{)M;A=tlc&*1tL31*%bYamchL@sfxvB;Jd4w2nycNu*c7QM1K{<NWnAl0#1|0}rkH zMFACZ(nY@<u@YIEmU$hOEYsYk@!@8^rLvj^CJR_B5p`0FxU`zOc5*&#j9V!k;m3H5 zI$w2hW&QhaAxHkX))zZ?<Is~o&3qSTCxaK?8?*9weZ_!=@-Rv{pA{|(wT)0(7?lsd z_40uf#BrV8xF=_|Fjb?3qz6@d(}K>&@1gCvKow~DSTbjLz0MWCn<5ke46n3(?M*{N zX`3k-<|ZLaE_3HJSmLeX=bh&>mCz{n$E_H#o*Rqb2KL~n*Q{ybc`_SsB&aH+M0SIp z&x$e3LA^56DMW`hb5$JI$0foy9(?99+3c)Yn_}u_28-GbeMo_(lBpVrV|&0^hA29v z|BNhyY@B~Pn9Wf3;D(>6FgRS+zNhPp8Hg#@3Lt`OnQzs*8Y&jixIWPS_$aItk28&x z2G^o`4z$Ak=9e6&_=}nKc|*$+DN*_aBYmqcoK|eWeN=`+a_#HKIBD7UMGDLuDy?<P z4yXDxByT?NdV}k`xT?lJw@d$~9=7z5KGvdVqW1&*83(vh6MbPzPj8APTb8Bz;{1tT zZ1xDnP6~q^?mQEW>1T$9r4LL1-*yL%*4qT-Pr7WAlmhJk_>5B%Awjf?nve{qS`D*x zDSX^7a+~tG|7qzDSUi7Sdj~SnmAh*)JNsox$v>YGNuG<W@tTd*nuNGqc>2zaH7Gk$ z42;RWH~pR^b;VdGf{>Mr1CnFsjT-tG>}@wiSsT-7pPI-g&;z1FtP&0jQw6RUg+5tK z&7Hw-z2*qAvOCx&ekZOJc7p?xajDzV0gb&Hr%x(52zEu!njceBBwXVr)xn68C@^f_ z+Wkl6;6cF&vio8wV6`O&`=QyW&BH87A-v+@z7)m98lI?(IpOllWhObdO0Vqh$?v^I zi`NKZNt?K?sM0n&iV^-}<-%>4?=a{BF>Jq))pJ+e$8f!%rxh?TUsz>$y>82Tddd&S z9}bIU^~3Sm4gI%iR&p@jPwAjo6%(nlM$?gfb6O$<uA2JMTWwk*jjoypS;(akMxAQz zVWp!!$F=UrcD-@MpV=dyXBcUye+cKu*U0EL$Wm#o^*f@Z-zV1kV)dA>+r2PpV>HaD z!Q(v;bbVmdwg{eEGNUxLbnUpbKjae=>%NR?Sl|K{s`az%O&nZzetX|b|2UYK9loA- zFw}{gytLOYLU%;iDc7_(>i&xu#L*i~`o5C|x;vPt4r24jQr;-q2nNWUtKcYGh%P-O zqh8W-y!Z8g7&Upvv`*3bfbOpeFO)!7yUD=&-yRyB-w{Bn27HmXY9QkASx2KC!u`&= z8{ong`kDr$@(4L{L5I1A#ot^8toC*PTNgFfI<mq8j}MG3QVB}lUygD8ghRvXK@Wx( z!(COBW6(CWLbVa_4|2wkdz2lmrgJlMq-jPv+LjIPfYQUuD}H8#B;vj0?MT*LgSS-} z=c^l_-fIcE#bgQ?-XjauZq|~t^ezq^%J`az3qzm5f-jTnn}T(wcLczX<|X{8I7%)L z4asQ@(#WE{n2Cj{{rdvG>O7x~`K5YX_k}HY?Ny}rb3rnQ)ZOzTD`(VH^$#pVrkYp( zEW0CgT{!iyx-u+_`00K!dXt`Eq_UN#)LXx@`NNEXPe=YjD4{(vaggza;Wst7#FLoc zFu@P`&F8QG;3!7*lSoS9L7tcS`uYyhl!_zh*6>5;zq7~Kt|DUz1nCe)6qnETiTpi? z^f9+yRsZpF8F6znT@Lu_yBU!~^*r~_tH>d%I!r^5y8Tc4wY9Vk!F?jDqiH&GV}E;K zm%jb9v#&gGxXhR5&=e&skmtFS`-P*G#70`=)mfItxC`%T?P=qLAvKj>RJ0Ar0JvYP z;E`%`oA90RKl7(OV9>nNkDx@k9XB6ue=l$Ubc*N3pNhRn?P~tRB7iVu+1wl#6^kgo zZxrmbAB96Ue)%e9tE3;`XLQM`C8a2U6J=Vbuhiz@mDVeEE^NN%ZND{O22;_;CBS!% z4Ty{c7IPrKMIEdM1XBtWhfSwlLul)kwlDgSWDK+7=KJA+4h<)2m<Z00JLw98-im++ zVVH{YnKtO8Q@T2Cj<s;Y$THG<h~zY*&2Lq~SAD$lKA5Js_!D4k4{A(X$wX%Ee;v8n zTaoJjFd2$=ZJ_)({;<rKT93CZHB?i3Yq?m6$EkS@rVXMB<v@lRJeJ)Z>>JIutilFd z2?!w4f#+N&61SyD{4xR9Y0rf3h1Nf@@dq4O7b7jQIwVv0q*B$0w2e6c;GR*FA(pAi zg;WVV8IP;kb#75vPc_+Vu*Y&?Y%@KlLQXpOrU_GJ5ul@vi{x+|p*9qHcc#e~Cal+7 zj(JY&@gW8b+-7m3mkv77pSqqPYp;VE#IH^-?y@M#S2SBEs%HI};c=#?PT{{O@Px!H zaau&#xoQ$O6!VYr;3V}f&5x-nJv6jOzDMwgO6SU+)3)1n|0`ddz)Gr4m(O}Gfx@sp zYm!OLs@(a1uQC8lft%>1!Tr01oew0Pax4W})lisoo@f(C^>*7G`g(rKzCU_AoZmkI zaNNP-djm7m(1JPZ9`U0@)nslZgx)FT3n1Xc9i{=fYbeZSzh)=k1|DTjFAy*ExiaEs z67eQxGXK%(-nX8nuHhB4{ljRrNKC}x>9<oHx9@w&6Dun-aQH6@p6`U#sW@9Z+a>;9 zL*Ffzeij!gY)np4<h$%QhCAYV&2=95)*AQVQ&>G3joQ`1Uoy6XWvhrK0Om<(!S6P& z1hd*@F1s8y)7W{mzNAs&<Y}!vH)-g5bvW$x;jPy*D(<HTUdl;&sp>bxNNzyPGN>X{ z9ZG(E+PHi!D8wrjfzhac_TrPJ&@#hcE7!n3<fgAU@e!76r0-v*(yUDENoLa#|HUy? zW%PW#`5#D9IyV0Eetp#Tn~$<z=`?MBw~B7#st*tq=}7|wX1%<K@${?;#b<wO$z#5i zpIFgyZov7*!~9`C)gvOogVaf0E2ed<K`K^NS{9d@bt#w%M*o)oE+TPo{KwPVn8|jH zO0}Xdb3t+%<fZsJWz1Q8f9ccNGdOsTeGSye#cYVUf~!=EUp~(fer>OSCGhiOM}3(o zZNs?J=R*$C>%ee?E`6YRN@u*{iY76f-fNz?3i}E_+Xy{xGUL?Z(A{$+PSKN@W0P?F zu07CWy0Kw>62D!Qq*kkCZr+nt%~YC1M=oq1<n20XKc`)An$PETgYEQ=g<N}a1i3IZ zp)oy$1JH?L@C`zc`C?`CTvq?d@2$xTG-E&}uf{-eSFavoOu-|1%Y}^_@tGq4$n)#3 zNvAP@{jKD6zuwc}B;)ns?Y0g3kW0F`djqq_vMqlW7c$@M#~5b*$_=T&DV+xhGRSn{ ztS$W4!_qgt`R4UuauX<8OcF|4rbX#EtZWQQt<FkhChxXfwK@#@o?{jS+1+(NQ4ewG z&X!Fh;nUE$=RtPdY(_&8^dLH*wbSOYN?Q%_%Ab#o9p`{4@oSdk^knAsP@;tj=?3{H z<dxl_*I)AP3}y2)3oE1cpFswlS)5?{M^zmi@|Xnz<8I(kmnB~v8p0w$fORNjCq{DO zVTUwk{l({XsO=P#XF70cd*I#d*)%ukO}%RI087nl8%}TM4w)`B-!ix*=$S9MtTyM% z3bpW;F&uT5@zYMp)rE7S);>w>Y9GDG0Lf)c>GT!p*g`f8`I3#vAWeR+P!67Mi$RB- zI@n|jc5(4@vKbvO{bnXlbmw{7U2{lOY93dnJc<iZ<~olF6HTU$IhPJg^9l+~BI`W& z<DY9TU%Lka!A63e*b2wCHP_9dc<|AGlgc_-cr@$z0)b+y+pY}(#uHv*B=*yX-J)W@ z^?6?ZS^@KPtS}e`g0)x^a|_2dtClKej{IYyE6E0aU$8_+nz{^B<ZVeDx;I1=4CG^g z)&Zu3I*m!RKb28E&j#Mxp1>oWh+ZwPHvnB$KED4+YQiRRVPjGSzGmjea#{I9uJ}Ue zP@1@A1f%Vx;%moh?g)-tL76JCIJof&RtxdZ$jdL_4+WCaefsaq6GK}ud*hasKxG+a z3amfb%_WI&Yh9$|yiKw;J=XfmhyELO0@T~SvtLeSY0H(wBgI*6jN=g`$-=;Be$!$= z%hzYT@>DQ?#-sXae50Si300EF3=`i!BW$ou`_lJj_4~uSf0K7uznK+d^GoF^U?&p; zYJ%<cfmEMsNAYBpzvwheD`}ZSvYa24l7G-NvS1yeL}a2ZYpIH68ee>lxO%!fE>oOE z%$prn%#rUJMpggR=ow>+d*6pEA4SJ_PTPYBfDWQN3qm#yu3n~;mrb=t`D#3_+%dO^ zNtRqr79mAUu-wTHTWo$Hj=^&<Z&x+-NE3F#1^tfnja1f=R<kt6F9#+NdmSM1wpuri zedF3CpC`3zw^Oc#OZ!wl_z=~T?tiv|z4QQhj6F2HTfT$e7AU}D@_GIE7C4&P?Q<ic zTvttC@x!o0;f;#PHoy_dq2JYsBn;yRY)X6MRu_ryD=fd$HvOyKf+;a5t8;W!J%)Ko zX8d2QlUXLz8}BHr*Wdy5iD|B%u{jV6C@gtIFgFSGu_pH&Z|n8gaHYJQYYlDomN*fU z&Aprfbfh;98@KT%B>V;CRE;gBP{K@}VV)GH0vSetj4A%{%=~=+?WzL3b&r|!KvE_1 z$zo{D!L(Nt`+2U$tC(HR1!)4JzBS0Ayrp3}O2CdAMN5Jg@h@*nx)yhj&I1<KFf&lq zERTzQ2N<cgT>!&pWb<xEJwFWj#Z*@&_Ri7#9|{;I;MZADn0ovr`bC;tMt!je)D|GY z;SKZzGMUZj8gV$ebNFXg7nGZ0F$X@zy7;p!@QnNB8dH_t;BgwXvYXFr2Zqk=9%fce zO=*wRSC;Jl;8&<xl^gfY9k(dXCUcym7$XGRSu}yL?*SbGqXBI5I~#(PxjaKBj@wS* zh!$j1Jx%In*PBX!eq!d2-dg+@-k3sSv3Mrl#NQySIn6|UlM!kiaA!G4Rx-zEt_?0` z<fOx{{=Q?qaSv~2h`O6eOcaI_pE*rXcoR!`(_H4X2Z-R!Ic~YVW%647RhUo|kR>o2 zfBHKb*JjKO>uUgA^#>yMuL=s2jHh4t-X9ikzazr>+^AV>LqqW4P1#o(%PE*GbM~K? zia2u(_%oJZrpbE7mnum)`%U_-E>8t(NZN&n<bVIo&yT`m)(y*$r=uZx1Y_SO`*fyS zUVoKU1f?skV$h#Ap!DOTXTh6ZC399&md867WkUrAg!7uWsi`ueMND7y8$IHg*hS4X z=SuK(XYJa=m%SsZ%BXLi&47u_Y66}+0ennc>psvc<HtSw$*(7fC8+SJ!`sKp^Hrrv zZHO5ak87ltb=7#@TN9?(7j=)%MRkju`+PSw`FWaRq(J$j43d=)ew%va!Ne5V^OPBQ zHci7*`BSoW!VMD!b~nAcpO<mxcKY1Z_A3<ExM^eX&<6GPVNC8zbdtRrS>QjDp`&nY z@A8zI0t1lh3a#du^E~`x)N#m6`}J|A(4fXtSkr_3VHe7*0g{enu?>*q<C^`>r`rL` zkRO5J^&U{jrB^pr%B?5Vkj-wF>vo)`Os=1nJJokyiH#%SbwODcZ9S4Lb()dycx^tF zyR=sH8##skTon+>VO@tS@3Sl<psUP5;K$u{|D~$^y*7@4!b;9AA^$9$z^**N^q$YX zeC0V72O!US=i;rhS%~kwjxOrOb<3)D^Kj-KW9!9K%V}jZo4Zein|PPVRlciz&nh^` z`}@NkntUn>$oR-jXpJMjk#Pwth=^hHUN_^<<kmCsj2)f!=$}5Bw<ODGm%*q_34g?c zQkQSHDT<d{1WAACX-R9<9NGgP`EC5?HkVs`d(icA{**axyGe8o$a&h*RJy#xy}3Cp zrn~j+&ch^fE?r>iIBX%g)`+u8DdW=lG9@I=cKDO-DX}0dTKE&}h}nR>f`+k{c!tw$ zyD9J|V)34*YSQz1VZ;1(v~6ZBgiru%UaE}DZXYCXvKXTbVG7}a<#<&b`i}d>XiH>~ zqt+#BDmA@NG{EPy5C6qwwuTD&llU%kNeFE}QU*TA8PUvc-p=p*%k?q<U<m5$@kKTj z#OBHP&gGxF2Z%1hV6WGEHdxv^6XvnI_V-HoZOJ|rOVu>+A*a4}(TPwsKZ!%YI079u zkQt}rw{5%mG9jPx7UBu<yGOAFig=9fnlX7F#I`KQ_}pkP(USQlq>+BEitQ4@EjCis zOr!KpD0qz|?Uvhsu@t#nVZg2T0@$;|!@&Y!9s2CM5#zI2!L09tV`EAr&S0hIg>hsb z@Z!Jr(f5_>d&NFgNNVKsTi)kCe}XYGKFooXU)g*n{!dKXg`xOK9<p9MPe0>t#~&P1 zdQ6Biu>b1YJF6+<;vcP|C0n#L3TGI*$oSVU$)8O_m_#Nwn`f3BiC))Z0s5^P+MX)l z2a?N1#kiX<WZ2Aj7adNqIPD*PlVCeo@Fe2JT3x>x$vTDUl0>o0OudLQq^7}+E;H13 zU3<Me;Lxa=tf_5?Blf~~phkh4GT}sy`)kmBlBLXfcs9**xb&eiB~G$Hx=6pRlfqWX z9J9q0TGtJgsfHUeHh1j&IrxY}{*!ycYgHC*8%`8lDG}!hd8-U`ns5rd3*CZ@XI(m9 z5R#9_?w0>n&*-gdw}Dz2*GEy%mUkyJuh7y)((0ha($8XcvT1ZyN9G@5L*#Zhe^>6o zx_MY1VMH`dY@`rgFPsHY8NFKVtWp0`^)zOliV?SQU4aq=4Qqf7sG;7!$$F(n=E$sw zS7XEe7A6CNgd4Q~GdRO&3mLC1tWT8(R@P4-JL(%K9bi_hzgz<I|5B22&|5D}ptxrJ zV;tc6IbG2?dXUAA-HKTAx@6zt{t6trNsVEl?q7_j1mi(ud6*x6hmBiz&4PNjukFHD zEwZ9?G*7OF?97}nLyg^usaw<AIT46SZol9oo;q*nt>G0W-l`gSUklyM)@hr)(R;QS zn$mpp@me6;!fzsN7%aYrv#LF1i}<p$P*J5}3-^=<*`3$km8=}<@iIRqDU~Oi{*p&n zXf4+oWN?8dd}HD_N-46KeG8j*mUNop$r^7s=WVkEoH#O=FTE?2!ID<W&<ZKYSlwxA z#Du^1M%o1cs$cyJ86?)5z;{$o^BJyOk%V=KD0VT}u<Jqwe}PxPu;7<OIXdtFozHG^ z`(!->by+!{)lZY+Ynm~Vx*!9GX<H}1y}D*Dabl20lfGutMGb^lB*aJ9_e^+cDX6yV zQ9N8rh3zh5uY65r0?&v>MC5hipuqv5fC^3DCb<n1Grgv5Jmi_HSzxBlSrum5#<nB> zp_+bETg-}xrv1;lvG@GE<yr{q*-Br3a}t_V)dMTzN$6tvE-lqKk7r~x33tn&#R@hd ztnq^s_4niGoVBDgm`Z)HO(I^d?9diqD49!>m*(li&Y&;9+FH36Dx0EaCs+vl80#^g zXZDRR3*gfibCdzF9OLxj_=_LEC(^8#c`?zy{Ua|MA)?nE(JYBeZ>7+%aQP>a&8GVH z>YK_}q6Ym-Uw6)LIZx&%-0w<~jZ3)9hU0N`+0M+(DwY0cS3ghhEeTX6gWcp*zBL&b z)Gj{TOpiQl|9tzf`)5TTThqg(XgxJ~^ZnXuN?f9%xvw;10{=q4(s+i1i5o4*E^wUo zG4FpT5)|w>5W}T0|J7b<$$TEbGtAW^RZBw-+;C%R>KbCbyOZs_7{o6)U)*!i50L~( zTMl%!FpI0E<6m1!*aH8nF+R;kHL7!EyL-*865j6X4AY;Fn+KX~j#&UTdOk=0Rzm%F zQ3!4mS2tCgOIR~6*plZM>EOUVuF|ygt{Tr})mt_1JdUPcSi;2%H~!=9x78;%7giAl z0icww7b7yj4%=`GO0EZ3*C4N-!~ummdq51gSW)%960h;nKVm(QWZ>yI!uq}UL!JPv z(|9H9!SfDGsvu6<aZU#wB#@&STgW2)1Q;N{K1=f~Ej&3@i=5aGCvLNgqg>~)s0lL$ zVKxPRd|L5(E5%9J!#Y4#7#Z2Y6{BX#x8GhAXg1WOcMo44usPnDAGSRv`;F|D+OUyn zp>cDWZfZ@^J)z6m_J_L=&Gx&)AAFfu^A?$%mq;n=2WAqg8Q%58)Ro$hwnC@EB2|gJ znzg&X5#0NgdqSPfeFeE`4r4jVZv`#MP!P7>Z}b$d96w#dd(yGI0-vmA^3AtINqV>} zFgPhVh&dL0pez=WZ%rM|z7{@K2j$$Hl*NG^uV1VRr`;H|uL~|*iVtzN0)m5%84o>@ zc}o{V{l9n5{g{FYbu~Y(`kn(8;Lg641rDNTSO2c321TGiGl%ugck^dgF;u-Ff5T(s zT`GFsImEJ9nNO!2m)M?f7OK)$cK!1w!z@22DQ8y8hcv9^!7ed^zE_O4`N$&HY2?!u zY+f-+=Nj+_Vn1fsx$~O9OxjgXpI}`6%E01ha4q=HUANOPVKaV%{X~X=|Bj|vmnvcQ zZYjXO<m>Tm?vf{!YYOu%Z{=bFo+(XBm5{{`4U_$r|54x^BW@w>;~o(~(fV>azBmB0 ziVm@Z^U=Wht7W0SDOF|_oUuQ~GlnBO^{4AlJ&e%agTY{~dO+wcSD(1kGtECElnn_H zvsJ03gMOYIe&5=kRn1%e1<i67k*9vzj(=U}xKakefHO?c`tHZC$18zZ9UJU{$N%YG z=)ShDGars8oBud7$Fx1fmqGLSZBp3l&AtUK@vv?&8^a*mq+5-kG7vVB2Tj9*t8^y* zUxb`6RI(?`-w<v9C;a$99G+6Ggd4gY%M8r(4Qd+O9=uQlMfa6O29avi^t;UDurt+s zV!9R9sOcWxqy94U>PE<(uS=iT_GEpp{qD*+W^mWQ(fmvrN1v;l(1clSXoatlGtp3S zpvyGvT;uj6oQl`OJf$lf7Am<olOnW=m^u{c0XSY(1nO4X{8`iEMc5m+|EkV}7`K@I z(U9n_P76{y@Trl_`A6L2Z<pu$5nc9@1Cx5f(C4mCY}X)owdi@}e(nA8)sJrf%2lK5 z0i_u~J&<$y4Tf#7V#&bl^n@4rSl4QLwMiID=#k9$K4R`s*_Z3*m8IGyg81UXy3*Qx zph7&C@4Imj4b6cc(EeXO(+D%c=%NsILeX5QW5||HXb?4<Fidi91i|6XJmik#SRlbs zxU35(x173Puq$BYMkJ{Wk{GexnYL|4Kd%x{;|eMMjwrcSaolAZGY+CH3+t+y`fFgM zQcK>H9>SVOis#QSA`3;7yg72%aXHj-f&QZi78Wp+aEd82D)pZ!iqyT%3&F3o8P7-M z@u$yE<${dE*7?z{)qw@V)FnUhi1YjhH-yqTCfL=06Rr#_2Dfuj5SpnC#zs|esRUmL zAK!UTdDW@;trqC6YVUdpcB;)t+|jq3LOGTi3@o0Guf2ueMk0n?!g)eAhj{L*3f`Ny zEhF(u-LrDSddJhDlziRdt)us$EHoAzch16E^JcFEUsJy$C{K~Krn?$EewBMNZ{LSU zlt}Knu;-m_(8eRiZK-2Oc!}98SQBGjhvp9sq}a88e7W8tB8?eASI+(Zp0Cq%JZovX z;~5!Qr3UtLb80SfN1*5;Biv!AhsC^poGqgD_FF@;y6iSS6ZU5!?jvPl*-!M!#XG=a zY{i{{7cK($BV_fh)q2tw&wu8b5Uc3FJbR(-X;cDX1#Nx<41HDYI}O^!eDh}clWYw< zf=bR$^&@<n;;n0Dp=Jb4!{1l@I3F6CrNN4$!im_NT2{chBHNF5sfA9vf6T<JvVXu) z0FV{_$qI92HywEfBzZZU?Fvgw`wizDgKktKOS4{}7haD_58o{t+0uuP{d}>WLn}%f z3formztXcl$h^CrRfI);4El~oS{l+;rWakDTaz`kFgNFL>04h$<GE><#?!ld19P38 zL(83pzBQs?tP>6Wr+!_0TY}!*ffp=PzFyjv-gVUSG@WD8IggoCM(-eb#oA)&B^EkA zkcAo3eyX#h<XJEk@FCNa&`_J2?jz*Fu{RNQ5-UIOEP@dR_Nup9z#thQsKVm-+{8-* zlKkM1G5*z#X#Tp2C^mSdFS7h)$=0knSJf^F>up{mwA3YeS52$jZS!tEX{74r-53v2 z0FqgJ9sQSJY=@&f^r2zYm9+!4kW2|EhS}(V$Kq-n|7hiOWMTRV-yL~iqw+;S>nWWK z^r3#{vos)<PL2sfYct3(7G_45cFS$U{0_lhhs;5EF%`kC)v^ZRZnmS-l-WmCjjF&T zW%G&<e-^}KWffbk7g!kYRqd6nLu2_6;k7Y%duepl+rCb0{^WJ}YsmcZk8Y7_IQ4jF z401iw;>9Iij)i*fW>y1l$=?(TpvLY&NVj37x1O<?v(}L%s_!H}RKGBv*?mnNdZHaq zt3EG8H@7Gv*Wv9_@N4Icv+&b9Z&P>AU)*A)$Nsxr^>T^-DC~C!{YxhA;>iH3B-P%h zp^x{pnQ9?nU*HH^GtA5JZda#%`=&_f@4r`;_SMPu-4e%OA2!WheK(|MYlp*eMr%#$ zmd2|gzdN~qn*EVRK0&WmIV@D28hU!n%$?E-<y(VtyJt9FwB+O$znpo{aYB7P75?|} zFR4wTS9+SS$>OrOCqv*{g`#t&yjTE(krkfxGq5VLWX<<vK3qMvTG_4)Rdy544j1Wn zxDFYH(JwwsFbP=p!ClgRy}$acuXF)-egYVs4P?PnI3lQpL6ISCh{<A^roPJ2rb9M_ z%hCtIi7YswldL;$#J4X&Ii{ukKkLP8mY*{IPmiE7QxYFf(j=xt{2da^|H8Z`=E@Ar zYw?s{xs?r8*u2K`egF4@#%}9~OS_UV@EmrJvdn=N*xthehah!)iA;XNiWsNb!?(I9 z3g3jX5RzeMIVp>j``a7qDCeSSyX;2w4R5m>dRVtYIhRs&ddEX_KcOy+$kx<*sSED% zxP4AhP>$SZF?tM5oYLOJ!4BXgk8t>}XB;Mg;=KQS$vk0n3km`z>Nz1;XLlvPR$zU4 zRCQKQ0}Xr=&#KxMV)cDmnWll|ibY0yk8!oEt|IcA-SG8l-p(AphV{xBA(ZTNj+uPd zRa$hY9Cz!>RTs<EL{6PVJlvPWyA=F{wYdVc^9Oi@HQG}xA^G2ysvzb$P3cMM#m`}G zFwVCr;c&eAyk@R3WIXp;>14_i>V6NoWD_TwR*1b`aYs<qmuWxjv%_@9-iu}MK!j(Z zQKjte=oRfGQ4vH2cnGZa*-|@E*%k4z801O66^Dhe*Wt#e?#LCBr-fCN;vD>Q$!SX+ zb}MNh<aK=Gnx~4=p>lcKzJ28~o@O`pCvpC&KE%uhB(mGGnL5hvd5xQseiW9qP1cVw zCz|n5PZuwWsUOYqh*upDCp!_yaj8?|J@0l>8nsj4<`U}c9Cai%^rIt*Y%fkk<xdmi z_Kc{f-S@zbw$TrHRMh=>rEMOzpB}d*DDd5((k?;Y#p>RVg%XQ#zsDsds2Tc#njXv5 zeStcK$Y7EA5IvmcG&8Bt!FHUPcK2iVSl?(hukHL+Ce|$Z9}pQ}?8&$awAo%AXX5RT z(2uiaem3jk_3jBE^gm?sj6gBPHB>UW%)(Bg%;lFS0+&4V4Tm;O)digP^j78Kbr{x5 zO#Tm&m26k;B?_sXQVOMu6EcDIuPHUoO5JiZaFxQY=5|>M`BU5MbGk*l@o3CXLE`js zUMZhtPHGIW*SjokE^%V?OFK_)myz`$_1)*@UTi{OE=1We#z2O@bl@BNI<uHCgqF2Q zrLjG@StP3*DkOV*`T<sZ;|+bDJWFCOZiN$fh~rdH>Z1YJRjXcw8y;X{d9PROhNr@L z8x9#+eb0gKyFM;$GvKM;X`L};bf_mzYSr4^M(=kCGM-e$-;C{aLCyKjVB>KbnU5C% zL+zhxm>%^-mo!$qlBV*4R2`4nX|B=DtU({uHeaAOS4uW<wY*YgE**V&!QuZ5p}hl{ z>JrCX;*Q~wHSQ`FL3qZQjmY`dG=voSjGGZ!k)kO&bF%!DgoY2VU7zK?BfiHyE;SN+ zqZ}!~+`f})8oKnAvOGkdu})_ZgJAWfG@_b~HPf&mj3seZdTw#HFOO_h=+Tq`)?K{i zA9GsCpAzmTd{d0ztX?}bEXOxkMO2bvDejuWH0`Wcz(__64vkrKW!0GHHAm~JLe<ll zAY;d+-~#KZ(<Uyjpv{xI*4A+M{lRLHiTRiR((X(}cZ<~*DkWu>q}wiU%c+e%`8Yl? zdK2;FZ*J9AbwXpzUkIuT<hPk$5K5!1bG{7FX?4cZSr^Plx3P%<3LmSqYNw(_)@k0? ze@<hrBoQCLz%z-U`%2$2DiRiuFYh>oyrf+T+TCh<n@>Ym)XW@3AQ$Ljrx=m70C|<P zYx&s(cdSL-L?(KVkiPGW>fWKgY;34Zv{6)AT4`>AM<Z~N{&v}fD&jQfe>lwln^jFs zR=zX6pJr{q#qeOz5d6Pv5a@TO-Eb_iR78Z<L&=WFsIwC!27l~{Z}NkAoZxUWdg@7K zjrt%o9ZeG$7|7`DKXr>JQh1i0&Z}N&08bf+|Mi{)>Xz26rbQG};FVT~Xo9c%=ttg> z#&xYQzj!GdjZ1GoX_w`mz>5)s2tBX}?l6gyo3youk^9g?e(FTsxYt2lzr7vHm&-&{ ztMzt$qpt+#Cf>M~?~RN;#)xHz$VOj=7=B(jEFoV?UR9k)(%$OQ-Tx6%gYsYC@)1?l zLulro>+WE~dT#k4kp>`$hJM&p!&Qp_Nu6d-8ZjtMm_(SL|H_B&vzOdaZkIyun&95q zaGXY#YB0awWLgSNVRG)d0mvn-x+3>Ue=9>C-<$P4DHFK4e#9?(=4X%YC)D=jLlc?C zl`p(8*ev<M?C`K~3>u<}J_>d%HBz$^uMJV!*!oD}vZ%NA*_Ff>cv052Us^yTP;I|% z)H@=iC0aHylRU?zg?JgB-YI{L7=zSAM&~*3-`IZTK4Q%<GOzTM?PPNH=3U-s{Sz0q zlC;P_K_jy1iR#G0c?_`}mCI?(;-4%hI>@Y?>|*lW0Lsmt7PiUOzRBp6(yQ$T`kwki z*ye9uf6XITahXg%8J)MCM?J$^lS0jLhzdonCH%b$BOs{@`48|X+IYX}FQ1dYBxtSM z|Kou&r|axhr@>_uj7tYJqI*vaLwI%g4`IEFH#eI(V|6V{6sn_Dz6N7J_hV)s8Ue_Y zOsS*bfC4zR2eYECQq|PfaakJG=n97Gpq^kCj{QEo&5lhCbHZdx6)K4v^yf=ZS@UPm z{b+3M2T1PSU*H(zH_p7U>l@mF!LgyKFMYan-0a=$9=ytd(@L|Y8rSs1p$RXi1D{}L zYsF4O84hi!an5YH)306{GiDY?d|y_;`1o;#K_umgkosm}^btSkV@K4*(zx&IKm|X{ z=^Q#FzxJQ{MCQjo_6LOcVq#*xm}2mh{x6D-ynAF;_J;7@NE#MskJr*s89L3q^ep~n z9&k6=dm_^+pHR6bsw&?zQ`TY(oF>KiZ2Y^nz<dC#@v4k;Oy@OXcOZuj;8BOX=f|!a zpjVr@O9mjLdYi~j)1`NvX$09?9QHmTPd08x&@m6SzA57tmGb*lGovOLjT{bnj`ooG zTNxGTf$oX^0lz`KZ}%!-3zgJT2SZv+|L%{%cAdn$5P5sY7TEh>axDHcY<<ja%U<EZ zquim#m&Lfw-RD~;O^K?MwLGee$A^qh=)84cL15@Kl-;8+-t18m)rZJm6sM#L^7Mn6 zumy>kb^bamC}U6FC1HO1n>}h6@5J9}w3vXSRqV+!`RNuHZX5LQd7_SXopK5w^k_bb zMSS%m-n7zhghg#eZJl-P)KQ3M)T5#XU0ad8$Qc9p8JUq~=H$O^?E$?%=%T%#@#;R; zaw59?;11&xao0h=)V<+^UCCYlIwdE<ut%@T$+_!n#LyzS#2|jijF%EREfJ0++FZw4 z7xPyyk|_i^>k0!G;Ac~qCs)DK&vUML^hUcpWmj(T(hz2%$-}_%pBxu+6su1VUiGrZ zhXm|w`>?`&c=4O&FZ_H?R|eO8DlOfUi|4BlI#fSxf&}wn@33i**+EtKV)nn{b;Uzy zVTFH5b|ArDl&SZJ1(ePM*A(OJd-4k>$A@za*<5v_y;pI{ET&C20axRD9FIcZNIJ&U zHjt&fc5j);Y{`{C;t<ZDKmIo0x9>b*-rwbMD6*vZ`P~y%EOvfL?R2|cjryp&>E|=` z0U$yFhFV+S#9`ap71P`+>n=t+1Q*)ExkNYonw|geM&Se9rPlK|N*AN*A7@J4rTLJ( z1vFm`M-z0exGWNOKU_$cr8P5A@tFP5#7zBl#V#hDHGSYyuwm}?e9Ylu$qDCm0|W1_ zg?chEM}tz3O>@w%?!WR}s@tC<&h!YPo(6_jUnz~$-Vg7xIsI53Bg+mL)0(i6r;4Nr z>pzZ)>zz?)FC$$2dol&(yt!(CEfhx4_D*H?I_qog1)p!2Z(!-fdg0TfuM+0({+wri z3g;3%QOu|1dSzfNj<9#KIGFt->d%Q^NnQhh+F`G=T0F0JB=oHcbX^JQ;7omZL%z|g zgoe;|kkV44?@_d1c{g*#mu*^cx4IWh3pAm&yQIopyEc~=(A)b5`NzwiBN60%WMg57 zw#`gc=G>IJ$!)7-m62ohq_bxRa-)=e3UC4RZ&6Udhd$U3;e_jU-gKge$xax|Z33Ps z$%NN>CgMRoA^kpEl=GYK9hKdy^v{s-=DITMPgX3}#*ddWw~)xrf+;=Ecn86fb<3QN zRMOuSNw-xC;)jBVa+lT4T~r@u0?jMBkbFNDC3X{D%B~nu<Lg{1q#w+5W!giNHZFsX zgq<t`2TQ%@D~A^lqG;L^d6gRwEzg<lElKh!=L4h8>cPnzg2rv77qHuu<Vur%vt_sO zkFo>P0`PF3NOOWPqfi0<xtnoJPT~ryQ=Kl5&Q2y%^sQFjJir&n0;#k%{X!sd9kZ@r zri+1sunFIG!+$G8E493@h51%Qyjtu;P$eB!5EnureHV%^+4`EgDs;%3Bko{|Zg#uK znuNPaP*W*Rdu*2n#=F!B!-p)c@BXQ6=aBXkQMBHlB85~Ba4(XA^PL+^o!{k)asg)3 z&`8nL=0|>9f{D!%r7A2v0j8z)lQ-mAnu6o@@QnQ%n9575|2~orOy|lbyZnzX`l?x( zUFP}P=)0u<Z-Xn7OqFjcnY{b0x3nA0ocPv6Mp`nN7)@>cI%Q+4>Ed-Cd8Cp!b+kpA zGcQKeGQSJFHw>jXGbIK0p}5}7@rq0tNW54M$gGoOjh=95uws6xirFz4^^S?a!QrAY zh|-5UDW)>nqxH26a@D}S>=8va=gj(VQ)W-v?3)~{KRO|j7u}0qL2yxY#c8{mOi;`Q z+fLCgR@9=bZy9L8<`w!e0RI(mFq2lAPWq8}MvrXC>U*saL&QtnV%U&W7xO&>@_HvU zyJm`QQrM{HAO#=Kt=Y}P75lyX#|#KccAk1}m+FbGVcvDG`>)jBG3?U`l=emVqu~~u z3zk_h)_bQq$AjdtUyKHO8JP3A^7snLawOdw`3*c=R+{ez+|a@5+`(q0cb_bBXz$IB zNnwh;J+3zi-dUQ_(vb6;6V5sjQ={V}A`fxyyiE2|(n`Q$;1kzIKh*7XO9YGyfp$z5 zw|E22!wv)Tgz*CPO762$4VZ6bh)(!p`61Y*X;UY;*qpqid1lw5dhKdr1ouKaeIt!( zWOzmw-4ISBpt)H0U&l2MOh8H5v@(^f3Z{h|=k1N~)oN1>zDzE^mH@LkW4LK9W~J}Y z@NFolol`q-kS33Lbm}}XFg&e_7<3Pa_(av;EoxWHCa3@dj2+e!f_Thf9G$&ded{!P z5}k(T_g@138#);vTBoB><W+T}9iG0=p5hkSRop9>1)R$QzY%naC@X)YtTW|K)m3UW zT`4+K*Z^~BJT}>ezbPzN*jy=)S4vJNvsVfF{>b#CVll>$t#2|tV|hDGSH&09Bqc7J zEnT@T#4cLsp<iGcNinTh{Rda+z!vw8>2^ur>*Q06{{QQ5y#@kpQHny(3GjoO#n{=M zP|U+0=&?u=)!7Ve`q=+7TrTQ<Kg>$&JNzrc;sx*O3;aoljP%PE3S630zfs;+2%oNG z%@mACgSk*_MkVMK<}OP{N?Rmzn>Cw1HOm_F;Twi)(boAz@S!93xc%B+Qlajz97dwQ zk=waLhwu`Tpi;$*#*6#g{@(6tFH~S=3CF$MS?k6pVWaSqZQok!P5E%GNedelx)+~N zhEJeCPzoX*npQ{cWWM8)>qPc>c)yq7Kr0a|{hW}bTj~Tq6<U<G^2E6Y_=?>aG<n*` z$c>KlSJal}aB!*{sf3a}E(CXl+-vWg>z;83y0+&bl2mgM@VQ!N+Qr<kk^vM!ktw5_ zW=y1R)xT(YA%nkWH=XLEr^?n0xrH}BZ<9hICC`p@ccZ)E`iF1zG(6jT1<&#oY^*C| zH@1&G_DASWxj+J@64dHCnWJ3syCIS<{d8_9R3J2u|JM8cfkAnWYrC3Pq}WcRDJ7#6 zX61TA?qgg5KCxw>|HIfjct;v`+rCN1wr#Uxc5K_W(Xq{rJGPyUZKq?K6|<s_Z+&~8 zaqb@X-ZRFnzo16d`>toL`ONuSn=%}`TP`R+aX-4WKIsgQRc{bdo3<ZFG`FpL&H@(Q zNaVIk=&i=<$MNbH$`N)85c`xZl!qGCB=&ht2y7<tC)F%%9xb~p^HTFI8C(^1+I9|b zUrMubSM3JQ*VU`ed*!D+K=kXL$KJoWZOrkbzx8}Z-2eG(&`?gI*sx_*S$3~1-;ew_ zbQ;PfnQ?FbBkfB#eEN~_VEb;QWciV7Sn}+taP9EK?o)sb;E(!|uyv%hoC?i=mK%Mm z|D#aK1^3c)fnr4EyI}H`^l>DtwLv4E2}#8&Hk#?pTp^vi&+U!5k3wSh{c!`DPVP3K zYdEpkZ${NJ2h_8M{C9w8m>sh}USR)!B|QBxs*=7QA7BfWcDX|Gp#^2@w^WI8iFx_S zgvJs>W3m-vMMT)icycN{VnZ(EB|V#VPAxbHnlt!Lu<AC&q@b*G1sENp?18rrT-ttd zn$<F|beVIe9&Tx~hWB1r4mk}le1Q8NR9iJ^yk>h5sBx9;qTu3*j8;W!HvX>m34ZIJ zd?qb1K^*=ldDxDYWbDUus7WlFXIW>SBzdCzR)I@VIX?R~Xof=!OqYh-rl*Fl0o+X5 zvI@5P@RMyW57g+_EfRlj*uQ`~z>_hK*)%O7#kEx+<#a6RY_lLgQ6V*rbg#7wRhmMR z?IOxj(^{p1o6WiIc}qHdKGnSQ#<TC)FjLm@jeb2@q=;tn2Q^8dlWWv5OQ9t%*A>At zd(G6ZiR_84b$W$t2gfTETRlRoE0m~!Y<!2}(FtyORQ^@p?OYmWMV!^LC?iSU9{kJq z3*(_$1&kxBV_W?a0YG{gJx}RFJc<rU-+;*-nN&SVxhn5(+esED@0_fhk`*bThfO7l z)`ir^)XvKyk|&ibyf!iH9(=)zd8JrK#Es{Y;VZ3A7DM09JGK)u+qT@TYQh?~Jp8=( z#J+jMww&+u`Xz))w9f{%?jbSh`itdTm5yo54%s5%-?Y4Fvgv^eHtsQ#hGoZNm7=Bo zL>Gj$3vQeJp)9!<Ux~hpe+slnnggdUe1O#~yydSxGY$mqj7#o5S?vw_Znk#6J^~Z` ze_GAtx|93EE67$$GMmVn*7>2WudC>=eOsaq588-092Lc7J4JJCaA>6gOMMojUxYZa zW1V;&Inl~<lCE5Qy?E5gA>u|vQ7T`iTs<r9jfj0OrLUPUR|aJ=Bff?nqNXe`vW$OJ z|9?D}L=Uv^b=S(9Xc$|hWUb*5A;^2$jo2Qr$iS<l%Po<FezGIwlC2hq{eKXF4z0Qm zhQzu}E1RZ3&s9i-tI-CMMQcL;cxKINjq2|&-d^6epb;y0HB;WQST+HDJU)olCsnxs zTG&5-W<tU`&ehEWn|Xq!CXm}hu#`bSSRv`Gw=@uuc2$bU7jFNASr%4Btv!uy%U3O} z^$nY)EO~%It}MUh#wx4j(`*w%eV;w8hm^&#g-8C;Qplh&SC-RYo$<g)B{0jnSvu7~ zpK)<AifpNHE3<PsA>9@;v+gSIH%-MM@#JrB&DiGqE@(x(`3uo)gw#(mKquTrvoxk& zs=(M1=lvJ{nvGueO+tiI@y(NRQ|OYpFsJYjhXmzaPIdb2qLm21qN-sgwzIGM#@Nup z$Hs_jc`@M0GniY>V(b3H62CpN3R9omiA|$J6y#Nj)?4~S<#cHLdVsTS{WPl-bgCxu z(fV4u@PRQ3Xggd!r6MV-BR5-~2=(wM6#g0+Obaxiz<*Cw?ejbQybImEK<RK&P4`c& zxr|6#wV7LzVw$?l=*gkqDKKaGRD9Xg(>5NZx6L-WI1=!*Jo1_o?JBd$>j8N`Vn5W6 zp*eXJtFcwHi!Shg>Z$py)vWlU*p(|i`o1iM3-QfG9?b&Gf`lcN8*J=F*qlqASE46Y zHBpyIW;^o@OJvIKzIS>5^LoLLBgR&GG4b$%{!|w&BIOfQrA<1L+*?$k)YFN3XwYUN zwhY~|Z4Dv@pqXlUX$P$=?`|`-g|4AvpPw8b*!=0_pLlDuSdF#4Xzlw)AqJB4F+Nci zDIyfCL%?g%r<B1;){m$W|L2etOw7yMK^h0)eR&GD{1LXs;Tl#Ce3564zQRyp|CRG} z&Y`P>sm}bZaC!1%@Tk~?hXc2TI(OcdHKSPw+uNThw|cV^Z6D7d*Pqh|L@r66I0uk9 zAui}0{bVka;u6$`*ts0+3nS*`k&QUItiqL~32U1x#h{Bx?S0bfl_Fs<@YS&T+nE2f zRp<8l?5edJ%>fnW$-J+r9c3zt`GiV!JzY96@*Gd+6=)yaM~(T}6}Vo`iEre@byZ3` z*Rp+_-W#sP`&(b{HpZ_~Y4_@3yGZyVr<6Uta>oUD;W^iLe+_3>q1cGk<Ii1h`&8qV z)$!8HPf<04qi}rG!*sJv=Ms5N^x@lI*XHmh{%b>)s$Qj23-cjI)}Yj+`m|i<2F8Kn zg#G^Gz9y?NM|4$Xg^y-ROF*p`IFCk9`50z|-zv0L_4<pN7e|Vb#y<_IXh&1UD!Zbu zZkrAND@zq|UHJwP;76P9Bli&kzf(99d0IZ5+BO`gxqDT$?duk*V}+mps(s3=^GRB- zMMCf{Q%pSHiQp~};^FtjDDeEcGs1PfC1$c(xu|yj6bCI_WP@XU?})E`d_0HVrZrvI z8BS3K;1_N>TBb%q);h=4X#uQ|?=rDPhVdkv>E4{qQYqH72?$+@D-oS3R0&rObhMdl z?ywk1=+tbhMHShIuW&G*LF7Ut+xaDDcGpODxSMnOo^$v#2L}=fCQplTu>o{zB?8*= zxpNwEk*xn&_DCfTnE8&gvQi4y>J`Ws^-tJLHJDT)`Xtf=m}$pmPc7}9{`1^{Kq8=s z<A0txZeSQi^nZb%9uz7hKig`EdHHyG_(EZ6Y5Ec5MJX{%{nw(vXbXmwbz*_EiLBPm zhSV<wzq-c@w$i5`U=PC^izua#<*NiAvQqh;qY@jsf7Q`##b;QUfqnPMpyY0x9HA+b z%0C*q7q>8n`J{S)m8JWflWA{<<F2e0Sp+^r7bRSmzkGPl!1Q4fw&_z&<zJy$c*#D_ z_P&{X83{WErqmtHbyLB(+xGS=rM|kcE4T@Dt8eL(T_>QPoLjCh2Mmgted$aq^(Yvc zT<l$`Kfq%J{J2U`8JSLKe1DpMZbOl{QCSS-a3q>WdRe10c7qu!O%S7PzD(1ZI*ZI* zx@1l36a7!Z@%E_Yl)Y|%7k>A}WUUURK=Z{(c}7otpU0xUg+px_N@GUtu9}j5=8BN+ z2C^z34+I;zby&K)9kcyDgK`<zWRZs@MYGtN2}0T7H|D)wry4ag#b>M<&c39b+xzA` zaWC{0y0cV_J5;$`I?OWN{H`nTlPG`WyKP%7fmQL;F1$!pBD0NW?!M~#ntfpi++F+H z-##WeDcuS5WSTa3A#>l2WFGsp^**whT4W)}`{<IQ1YJRPs4_ZFp>sK}4Uzb_vCNai z(SF%W*78&68QN?<|41>Qv6FDbu~|gy3n;xDs;2w$s_=h~1l3b;G^<G_-pv5u8QI}e zmv;#m#X{y$<U`MohzB1IzR-Dyuz|%z0-CSV2k8il#bt(Bi6Rxb&V)SU7F<C=dE>9o zx-17VXdGwPTW)Lr?d^dSkI3+{xh_2>V&+Nz0IrUFsT@fo_nrU0f)J?IO_ml`=!vH- zlX=2)I5u<In<rjP*+rG;BS&?bkZ+tP=?kk`&L$J<AW=J^AV9<QsGRIuuzO9usd^$I zFp-MGYcWY8qcmxlv0F1zhiXtmroT4(gav~aRzUFIg5bsS8^(lMFfXa?`tl0|;R#B) z7dTbh9qY#j3Q6=vXo<;k9M%}64DE|uYZ2xE&6gtrz4D7+mJl9~XZXDJz;L##?Udn1 z)T<6?8=OZHPepUO?OWg!H4WhTN}_4ofgGS^U}x_`Ysrk{^IEk>bncN@Wu?C`?WE&> z!`mh`SI4ocb=2N{!K%<D8#}WYCFs;i_)>ivK~Qu>*^rr~Mfbdh;r3hg&z=L`y*<gF z;BMWzdT+^qR>prqr}K;|0g~5msQ}^@VcAg6`5-aO&h*ZNPMylNL9_3tk&`fb9G&V# zLoL62E3fIQ0>X6(%Vn=tus#CRK#mqwLI2G&%AX1UdPWO{vxz`ZhViD!oT62_H?u~? zSWJr{{Df{k^X&IBrzW$T1f!DLp53qx62kna(b1RY2TFx*+1*@kwL_rM2uZix+tI9P z8?9b>?gYGi6$ilm<1St5`O{6eH!_LNQ2+7sBXu@KL#OVc#;w9PeOwnW;)PE=!|x%T zPwR&A?W6SV4JEj~vj0kJJ7E`n;yXfhzT(RQt1Ubx)YY^tr`$&E7T)wT@yEq!l0LKQ zY0}owLK01sP(|`iMN+~yT!qTVvhBis?{Mk5`I039c!aU5P#Bo@E@R|Ezb)lo^~^vC zGgw*&q0b*D3Lph1vI<M9Xj_)LuJ(W5s-v5dU?u)9G{-BoI>nc-W&&&Fi1EQFHy$10 z1g(({hk)QlDLOa}k$w(<*d>)_m66sOQ&9DI4m$_@<B#=&kY#n`M8W->U9F^3?&eP7 z?cg9;yrKv1-+%E!dAcY)ew_*(@nVO-XwU`LIjG`=KSXhR$Ioxec-#GQ{)w@Jjdr^D zIP9{YUy2o_SZnc{eN#~O8hXN-K&EIo^*!|IndjeI|27N%gCO?CrH9t+_g!BShg8Rq zuDW*ENsXI_7W~zUQ9QhLb%&RK3g)!mhgtn(r!P=8i2{kV-Tf|>?mMlijk4sGBr$%L z8LZbU>4@Yaf3N}grg^2NW|J%56F`8&t625xZa?FIUCi?u-rL+q>89>-DW{_2$clH1 z7m<W~uDKSJrGGW=8FuAnOIBZzd6AW?pU?4ShJ=0Lmi5JeYMVRJtcE1~Txzznpp5pm zYn@jcgxW5t5#}$0gPGkP4}q(`7w=*O;K=T_rz%j$*HtKWwoF6t*=1a@O2^AEeh@(- ziNsfGp@6M#b+Vx{`=s<K0Ea;%hOjebgD`OMnrb;v!Q07?)>|*YtL|iSb&*RY8xE)J zs(=Jqz$V+{IXFm5spVl5FeI^Cz7J4Bvi7+4-Q_f>MM#dN9;_DyWY0DV`eMJI+PrL{ zh&yZU=j$J4>)UY<FloM6LNB#X6mYle2>|e#8$sBW<oftT#OVCk)CXw~@K`_cfvA_@ ziM^Y;bvBNgAZNt6({C-nMZP!DAyw;b0fD$*Gp>c$2GTYsvel~if^F~Z+yVcmBG<n% zjuH1i#Y2!%$OoxqUQ7c-3k=6{AfoT<wp3-VSkK{>a>cCk@kEKWug8sH{kfudWZ9hY z=+o0Savr`f>U7(zeaGEzye4F>9biEnPZ@RWxMWHx#>W7SU0fpNx-2`P<FA(Q{|~ek zW>bKq8`T39e~yBC|KN0wUZ2ByQuKn_eP@tttxr|@{?IAbsJsS+Zd0(zBc73hJ7y^y z-_Tq4;5^%MtU|dCLP6E3GTkDvTqqrOeCy;gJfggwtMk<^#cdY)@~ugKK&H2->UM^_ z`@8zgyys$nS9#e2z~;gF+q`rUaWmz`x{DrQ)dWGXK=$P8od4Mo&?#JA+cmLe+*LS# z&9R)IKI_&}`(keO$FJyl|0MS8T#~Q**Nju)+l94e*LSQ%7K6rA(YATdvE3!1x7M9- zl<k@1uUjOl`pJYTMFY7*?kNWA6)p1*wVg5t<jqAJmPY}JA`9)}ri2SaKNUbt92~hd zZgcq-)k{FI>}thxVZxzrPTfAAvoWApc(zccnoezgJm#!kUD2~pbUEeYd1A9?QOG;x z;x5v#Pq~A>&DNZEqweXtW@r1NG&{fqnJ81v%q|D%PQZio_KM=UF9D?Gbc}uK_B?q! z34d32D^A%p44hZ-!o~)#6witq6b`>_?$kS?(!F&FU01Vf)U6S!U}2>~X__&fBa7p@ ztuK?h6$Fk_gcD~1BJGY$lUGXECb@0T)T}wXB7V`5=BVP!f9hWSA{&B7K&x;Yg8Wts z`vA+drPIr;S11K9c5pqSryulx5&+lmy+c6vg#Q5#{a1C<J4GvNnpB%}b&*~ldZB0O zo~gK{oQO`9px7*%qj0Qu=14}+5op#V5M#$XYBTQnYb*~v49>8Dhn*)Cg-M;VVy*0G z#+e!C1889@kRtB(DY5@5e29u=v;jSLx>ozYP-#<|x)ow~M=!~RgU%CmOD2_pJJU5v zARhZ;Tg>VgCX!Fgl8&8GXWH9730B>l(nW>n4AlgoEZ!D7d><qE&xUbzZF453Mom<@ zDm|j}aBf4(g>v9>iNM<P(VuHirP;FYO=mAWMTO%2HYUMpX`7N<f{F#yP!xGkZTdQu z)2;g#HcOWHZ84V2g*gLb9tveiA~cpX{CxUdRuz_k6))~2Q@?l97lFUWy1bowTO+6q z3+wt+o_7INsxc;;fT5?h%Ht6fH?Dw;&MW^UUlI_giZP*b3(K}EA;Pgx-D2!P&$Dmz zdXxB&t3^O&XIILDNBRmm={d*%L{6#v=sU@EY22PW9O^QvNOlb<=UdfpVnW>gA$P32 zUUO2V*~w!MvCJn`TCdi#h}oEnZ@#ulWvtgHEBwsDe>1J^LnN6%vrvoopf+MB)`OD& z=-a}yxcytu17UXM%D*1*XV>ncr`A*)Msk-02!+#pnzqWSI}MsMS0VY#e_w7Kgdaoa z8MopJ$m=!>8P312E>Hke*>`y(FB>L|rX^8WQs(#a^y?=o<{fd-e{WB0E0rV6*?1r$ zFi{eIY;XV7lt~EF7fPO-@Qyf=<nk%WNz&6N^|c0RB;VC*+tIHy*<Bp|w@!k(JdP0) zh#`28yr~tC7F8h_i~{mJhtX!wSu1bK>MyAsHfX}xROVnyliG;Ua~5ukL)zXFBgbMj zB@q9io__|5@SCC9k8)suOl`OdfX(*(J);}I@1{4N_<&1r1h=^vxeQXOR&}Rw<Bl){ zf($!0v+$C^hiT7sxWr-S&VDqxA_TjH;AD5Ry>X9Q`LTXPplShD>?M#anvE3>AgF4? z3=`J7Yhd5-vHIcW|D<W*t_?S8U@`=w(4|JrifX`w)A91~Ptm-)i`rr4X(lbyFTXSi zDjH!4*@U+Reo^4~lK4B;aB?}ERf?_-YiN~etX59HPFJvbnG}-g8C=Z#tZEr729ldp z(I7&FD;3O882G4AL|W&nG|$lKcH`bZ9o~9kiq4KImv?Sr*A!f3Pw?M!s94%h6{k8a zP0aml_5-iY5&MK{?JUb|@*``R{Szn~Ltr*inlz*2qcgjJ0e|6A<5QKZb5BUiAbj)M zyDcKSX=*p)cp{IbDZeIl-|DB|bvdh(ZMe$!R<}U~tZT5_*RRTXlwPGz2b#k=th@PI zLt5PU@dQRLN^Ba^ZXcV@YmUKt>?~V+5UBXuj;?D>>8IsyV0A<!tchkd-v8u1HkWDj zc{8Way}Hdg<FMfZ&^1@u_bzJyXB~8$3X8`JF+@bjwOxBZ!(2bue<`vQH`q!AuoLP3 z{+LL_Zj-Zo>uB1|-06i05id2*inA<68INq7Xu)eHr=~LAhv!VXQs820^5c;AJ~C_t z2ZhPni|LaFD46rrA&f#^8D2Rdzj5Ua6B=3C`obg&(0$>)$4BT7I_Qm$lX9>AKnc}2 z$x}V)<)oynFK+4+i6y7~fK|k}f?h~l`BVaV(#C(4gLRA{&_*$paCkL)bVd4kz|J$- zq-5hp)uqwz3Ke9~a&FR-H77^Dp8{GSY(f6Y;;mmqdyNIwjC0pMae0YQ8z!Z=*sZ#? zT+w&p?)OzD+J+NHB>zA~6b#)|{0O-}NSxm`1fxnUz}<hz`LaJf2$mi#_~_K1^Ov!I zJG*kf(=jeifq#Rh$0-CSSTl49;0Vr0@SAeoX{#*H5>}Enw%D$6CyXLPAFJR71~I&k zc`{82jMmH)$lzAL7_?=a!cAZj_aj}IIfqS9RT5by!I}8Mdb6Priik*c@>vap!7Yx| zynu3>kX|rlcC3qWmViOT`ZXzce}IAs{{V|Mpwa*4C8C*^3@>WTux#O6nS1oSlg3G5 z^UWd!BKt@Z);Lu;qqr$3DIVWs1)*31w`R~Bt=A^ZN+_wj5w?cSc(=M2hBzHThyJew zwbN(IrpZgl*sre2T|@lVHx`wGU(&gS;*p7dyiz!mte~5}JMZri`Z^*B>2oPiBqU5! zol07oDnzRt-pMT1UNOM!5<V*sI7`A{DzA>H*<r&6zabvlv5*|A?Qz1{HsjM>=?V}b zB9#@MgXbC~Swo}ZqL-wX`i1?IU)Cn8?q_9V;i_a-bF`*Y*;TbL<NB*g>Sa>kzY(7^ zMfsWM!oX-Ft=U2wf=b&P175ig0dFj%HF@F7f?HVlU1`D9?wKVAx4sWxPm)exVF3&! zeZn=m%=YtK6s)bmi78us=}S*K;MOpM-&y5LH=XOJSCXN+3r=RPxT_MH7hsIPdXZ=i z&5MrwbZOJMlQmj$l{ZVH`83H^0)D>E@`=}Bv3`;~>tBa?Vl{gOT8F5Ox)54%_pW}W zUNhATJo!jIot026pn&-6&u2PV0Uj=*D^cn;^3zv|6tMOJc3doWeb+!uzWtI2ow#BZ zUjd(_m|FS*pUuxp6GqCYcGSLwr=w%)!Y+S&j>czL52Vm66{5X)1;4?<4>BWIr4o!@ ziMT6;G*oF6fh}kYJrVA)!W<ww^DL3dB4r93+~&DO^YcWXV+WnajNr`4)`~<V%Lw$# zwChN&(vun2UN)hCQB-4(7H*G5gO8iMu#ujj;etiz@fSpYi_q@(K>dm9NgAzKK17^l z3@JL{@8_3HC3g$}Kw+VQdv{0%H+`a$f*b!KR7N?3DkbEiC8x3n5kFeZWkoL?4lWx} zlHGz*nm9nI>L2L1iI3o@#=NrB(O{a<Ba$fXoi_RaBOGo|8c%K<Pn}47C7AL{(MxzD z%b%#mtWl&??HzXd`Ym;iKA!QK>+bkWT;9ZUHrwvHmw(tebbAtFr+&>P+KYPe^98AQ zbnsm?Uqj~-&nInQ$#Aj~Va|89cXnBC<)V&Q26+Wd4c215kpB(#0<ZL9`59X!0%?pl z!iaC*5GUX+RgVdbizT)~o$F{nE9i;cSyy0r@Ckm&$<}11K64*DpnF$+<o7Eac=0X0 z?iqjjw>qg6fEA&NH;G*BmE9;*u%Wfn%6peBZD5G$w6H(?GpQ`DY;DP8^R#Oy)#YC+ zI|SGAX{Yun@MimNY#_g~`KKSnVU>kj#S*9NT@3tA0RKN!4d=WUwN{2HOBHFz7JgZO z@=DdrpTaF2YD{knn<NzrShCMSAvY5@UQwe6y2NE%Rz{gpj2KMED;@GkN{i1)^*D9j zZ5$y!M1gu{w=W&M0h!s?BM)gydr|M~f$?rj?_CH#_3~<5l7PY`^f(oNuXj1jxIpIk zqJ_p*n2LW;^hgt>phY@Agz%n+n05c;^w#&*CqCb9ok^;nbz97Aw22fAHqiy{=D%+i z+pzGzJ^7)_QgG5pMR#EkUf0P#xoX6WxrHcMqLy|`NH(eAqog-WCXF(x`ht90_&o#L zC5yP6e5F0K1mAd;Y#%2ho-FUlqT&>|#Gy_VZng6A@_KuFCsJr4`$8@fG;7gqNx5z@ z4&AO~6I$c_Kwxiso>8)=i5!D_V?#E^zpLvKC&!oNKjGXl?WE$Q<82~hn|7>GXPB*7 zuCMD(p-!c&d1tQIP@Pj85dD=M^I`0M3HrjVP|D_e1<8d84oc7TlbxWmj3<kCFkXVs zkgI@Yq9W7k$cUqi5zWO+jhmt=$C9v+lEo$i)Zu4L^tkRI5!9a(DegfK4Ai|*xE~}E z^<EdD&1-I=VQ9wtIda{of=o|AM6V4dXg_r8TnOn8%tRL`(#C?*K^UrU9c*iL{u~%3 z=tX<hs-?1NoOUbS-uKwd`aFT3?*jt^JVOG}-z|>+={OUj%46~e+iN9zyiD6wVkt#j zHlPHBA+Er)JKzn&uuX#E(q&8uJfX|VOMhxr8#TE);GmTXwS~e0;k5<W>Losmn<lA< z5N0585uw7?c-^JpLlt*a%zw+3VWTwR#DshQ$*zUA;4B!QWYj)Jv*@en`^87bj_}89 zO&J9bZ}iVc(biwe`gM~ykur9@6bWV#?{Sp25d?iyOe7+i^OPVu1o-fy3K1TnY?r^v zplW>|;&N1|Vby|LW2scVP5?b{d`0%mGaT_7_VdK-?ukPOP0U(9Oq0T|Tl}>E-qYzQ z(5L=5{_W=*BRaFU?T%m4#Q;VUXV-XY^?9xEq`^z=#&kKkhKq`~Y_*vB12mxPv2}k0 zgarfzn+^(5y|Y>p#<Pyg^GauyZCtS)Xm8ge-xDegC;_bU#HyFN)2~);9s=Z5GsN8~ zRa&}yMT?){{^WINoShGarwa6Lk@$H<B;2Zhe1uOf1lt~eSLZ&dO<|~i9*lKr+1#qY z3ragE_Ay}vbO&ZK#IqAQ*L1bcF-<-&X!J_U9jh&NmY?UA>3a$<`HMg)eX0USr_NV} zn}tM+UQJK1?f57Xg-d1~UrkWbt{NPEd_Yhz+)R^hbn&fVOjIH3`vESy`;6iO?gJP< zI76zUJ9mBK2(0-CO*=`>eQs#3;`4K!k)N_MH^|o3HJED)J_!LA>uJ!`I1GSJ1NANy zu6Odl<_{CvKGMc3Af7J&yK1NVnd|XiI3<k+V-c^~IK1z#Z*RrA9hMz29hSlf;y;=q z6D%{?aXu-?ntthWim&1MascHs)Dcrij$E(?)uJ>gBH!q_Z|R;tcqMy0`-ciVweaKY zDX2?9)aJOhS%}GkBnq%J)Tn?D?%p2=ZQ%uKOUWo8T3W+ngB0#7DI#xli#5!TM);X| zp$5%{wDSrxuS=eg+IUmfO7B@tbQWh_u$F%ItHnrgI531T=bbSeTBvlWiFKHbk};Th zxdB}lng6h%q%B%>RqUz?gJ!eFB@=Mxgbag}5pfx5eS&o!+e6h%#!(Ov|E4i$%@;|? zrP8W&d)<M~A8dMcTHmM3j7%382zwC5;~!S|nBg)!C{jt{Os|MsOFD;q2&QTP)jeK= zjs`k=_SA#$BWT~w5qv4l8AKQ$m&k<o!L}p(u#ug`#D7c>CeBjc_lQfT@PZ6C+Aa^^ zeDM=;zpE%YvIOE(1z%p!QZ?w9J^V_8-1e)XfFUXDx@Y0zv|5FtM{g-Sa9qR?X|xq0 z4J@FTWSU(kb|RWYrWaW0UWmBobd5X+U}sCS1cEv)+9%(1Hsc}z^~#ACgw|LGgGWtR zn5emPC&a8C=IFT8ZBZ2#j2|9Y4{2y{q+TRtv~u+|fUJXk@F_nhXF!_;Sp@vVC)LUA zoa<<m)C9g5mT#O~1^nsQaax{qb`A(FKGIYL(<v*bMCjG*1Ey6G!n8`agzfX1LaJK& z)=wd^dZ>keY~B(^Gg1ur@?90hZU52);b3$-sdirySZF6p-Qk{`XE!=N2kTl^{f+EC z`soP*=yBLsZ@R&kkC7@m%%#_(;-@MXq3C@QT(`<XP%4I7Q1aZ!A<7A>J!9yNsOMc$ ztUHIad0iLX&(*F>La%XNugW&i`Z)QXwc@Lv?ex3W{~gqCBY)(z{<~%FK`CVxG95kc zL%PQL9-E~h(WUXij7aNgK3K8}fi0}v{b=S;k0!{W_Jv$7EIEI8*N24;aQu|shWPDy zzqv(aEW@lKR4e9VB<4zE_2O?z+?i`&;UJqFW`=6hYZMs>jg>@W0g-Yk^T`a+s6$3+ zr@G^aj)@6r3aK>mS>=AVKq`~5{qpbMI5H~WmpQ>JVX7sSugim-(w4fpM=L@#yV{F* zXmPBw`=B{#F6w3kl7yYqlv40*g^HnQuO3zsnpQbCzPyi;Q&Xf)f=763$(G^>-sI># zRzuZX<}>|>N!kIjV$n6YhF3Q!6Rt$UQctqj0hn0~6Ae^O?iHy}lp_Ol*u9Y9UbB6m zretfvzc+71C|*WX<2JJ?YN5R&uo7@oyU1uBIJ<C>G3t54H`afs3zu^+wgrr^&V^tr zF>cYIu>dvUzF(*}N-+Tp`8KmXG^OB=>9t0?v&p|K(~%gmAi*5uHS{uTT8K@Y1^^KP zeRxc-qFKJsIco%2zQu+K2_?8TL&bD!qZmn$TBYvYIob)jk+VoanyK7(%R0vI`$3wh z$eFSo4)HM%@a-O~#^Y@}!B|+zLe+Q$F5LK!YpkiKkCIC59@QfrL#UDzrAN1dT-9{V zkz*|0qapzj5cg+9lR*Pk4w{3rlMa#<B2AI=Mcg4|ckvW=P+cm`Kgy)^ah{gV+<h>q zwjp<*M^a%r0MpExDc$qKq(+Y=0`(<ZnDz~)4R_lE$)cHvz#WF~H4Y)`0}1xeOeUCs zU=1rw=oCMzAkD@7t<1(Yr{fR6>ZMZtN%vR#!m?4A5}V4$o2X}=h4-uH06!%k<CLn~ z&_AT5yT49Cg$VaQ*RVR{ZSyF{{`hX@mV73aFbMIP6FkP2+_tzI!y_ql_-2^+1onyG ziLc0$w-;6D8*x}uXK`V~XGdA;$zH#AxQer>xI~PRZ-}O>s>CjmFl_ng?H!X~Ii*yr zOq)&AxvuW0^C?X$s`lk_SkNuc;;suU9}C6*f;@p!QgLi%#l%?=7-UFqIL2U>NQv&m z6IWB3|4V;viM@=2z3s(%pQ(^pk67pR^S~TF)7$Cl^;xTYVT$C8e-(~MV9;s0FJHlY zmJ;3^+oCB3+D4q$i8~M_1v>?^LlNRTFa55xCcUzdY_!6@^jfMKaITe3ipQzi{{2sQ zSbDnFFGAkET=jk<6O;%{RMa5Dej;Jrw*<ISxAD)x2WhUKP&rWSBRbi#u=L-*%@r^W zMcfhjN&*&V&_W|K(%xQ5JCT`*Evsh=TD-`$93EPSpA}ttjlNwBfj4_NR;%X!3stME zHF*4c2UR`XPuAS1ls_9{G59H~$;CXl??u*GtL}___pLmHgPCRMx0GMOD+7o+R*q7D zDNz<~ak&zS!LD9=sV1`=`J8AuMIi)A)GMbt&O2Zc<)0=I1x@T_IV2bLLq*~6kd;`> z<`FSR^dLSNOT&U<LtG>CsExr47aUdELH`+j;L76z(88Lc_zS-GA4>pn)!DE2D06-X zlL`NVjz&H$D2u7puy?+8fl-qgSJz8r!U05R#y#B5JFl$Gg+sJt`2m-u#8e58@-%rD zLdkRld)Pi68^pJju4rRFY_<+isUHM1NhO!g=ksn^L5pd8z$6hipXJOkb45_%Srsel z_bs;%5dN~7GG1=R5d8<SX6ys0XChkK4XxaZ#~VXz!l+VH(oL-FeU)Oa$cq1P5;Fcs zsT8_W!<ivypx?3}dpnD)_)Aehd63-^<P_e@37=5Vei%HbONMIgc5hnDgc+pb`8luY z|0^HE=6j5gTC8DlNL%IF^fPC@5avK>h;OY;V1}zeNpf3-<kTb0iJGj+gp|6SrvG#i znbWgp8A9!;CIR0npiREW&r+qasA687!<J5$h|b4W>hmyLE{B#1KOA}{@31!@%hF(% zqv_%Vk6HZ5pXId6te%hPQ;!EnL9;<A-~Yyks6d6F!mF@@PJEkGWu8%%FWPU0JfVyB zl9~QzMZ+JvGlx*w%bP5}v-6FF^D`@M4rc3OqlGbl4e{4l1~>gHy}RR*I}Vr0p6%+u zKDPVW@{}(hR=~5}{dKuB+{1$QM|0)3=FDVXt0xa6AP2SBR3sUI>3V@DnR`luyR@ai zvVjhAcmiC0NW`&%1#iApAChMxfr_Fq8G8&gUqHcQ8gqvWQvZ~Q!AzQ|*8Y=9r&iQb zP+I8Gapwo69JfkLs<uMpAv?M!Ss~}GNMC48Mfl=if`{n{8IcObB+Q{N^afX&>M1fV z*Mf}_zcX@9x2txm<nw^^L+=TtrbE^-^<WGoM_GbU0S!WWuyRQVp?Va%E~M!fe}-hk z(OPgjglxcXSyyHknDPU128pjD=_|10YIeLFxh)g9vVLlHG&_V5nC`z2q#X)H2Cuh< z;mt_~SMa_qmBn~_h*oGIe5QmG6)5~393@UOQ{(P8fL<W!?9BRx(?H&y4eE<raUWox zKFY{Y!Rf)f$p>F6azPw1wP0cqc5_z{Ik$Qk{P7?Qq;pkZA5UrLNPuwFRYGx)wpb8< zv^IF85YO3b<|xi8MFKH>Qq_3u5lE6Ir<di*+01GpZ7WRX!fAcNfRb$FVRusNm;`$z zrf3~LkUq`)jF{krMF-A?$e8TE<@f4V@sgOL!u=?MYMq90taDBk*_cDtL|r1XAi?J- zu7AU0eB&OZ9&4cWft2<MQ*iooil*MoCFSph9Hts6GFQdz`@+Z9A@?RdfI9*Bfglav zuMQ{NkLX&0HAqA`q2yJ9Nv;fQRJe?wRF6D%t<~{rHF^?g;q_T_Fuh6M9wlwidS6I0 zLfl*7@i=n+c=J7WqqONspY!whSVZX+x|Zb9g>~y{PkZ{e^Q=Wn%ZKf`4>Lo%o1XL0 ze)AYg8E*^I=1Xr~lWdGfE~jujrW|s4hY$H!hZq!!BVCJ)Zf?A&I`TL+d)?!J3={J6 zscVtm?0xZuJ|g<h^H^rL$r=Q^?ncA-eCp{w9*2#q&P+=WpwZ&4+X?C6Q*a(yc9rnW zX~U@nPY-<gwdsU$c}J;4n;|F2ko?d!P`i|;!OhIvou_w%h`p}LU)maE;){nQ85;@m zTpT$-Plc%fn5-mUB9v_yH)AOq%oZga8ZZ~p9}RTik4OMCGE;wKD26Biv-$Z%m@KYl z31W#Q{rx|PQOq~LY=uYat+lEU(!3`Ux9mHngex>N`IjK5HcGph5L3s+IxZYf5?RAa zJsO`3Qa8U4jm4=^i0X+a^pC=hHurWW;j2rg9SeB$$uH-Zcw@apICHDkR?k%Y26QWt z!NEBRSx7bP_13ws3*2eTY?+yPA`g){qiq9!lCX#?eY2s@S2iDmphc$tg(1q#&!JLS zCIQwUh6lzc{$i*@i(HXhEVe*F6)hO#dVZd?fzOkDn(5zE=xmOf)NHee&8VHoQuk*} z1XqYwqe`7tY->}t2=S##ldJG4<mc!osMNc_*p;HA@%R5$ABrx*qKMG6^*6EBlJxBO z956{tJL2=Vv}$W1+t1trSXl@v;G<Ln*Scj|wH}j6WZx>OB>0t;@G*VD=vs(jfQ+O3 zyu$+qCPPsNWsCS^z(x4qf_eD#;L%=s6`ejMQR%5{F<=u+@V8Pxfv@2`*hb_IM$770 zIYQe+g_9D$>R|~A!o*>TpsO>)!EHHhwUs`XmaQv0P8OpJpW`a&B!zz^SDpu{<EdJZ zsq^V1bAWN99!;Tm+|TD9_phka%Ott=v#y&$8hy6_SlesV1r_=Aq|X_J8zUz#!S%dP zUG8#TDv5gJ2)dg=>lkhSftv}Ysru*cYZ4`YGo3&Dk1b6b?bG^tX9Gdz{8AauB*;Fl z)O#~`sVCe=JRGf0y$A6)t3Chfo+>>LkChiw30^ahQN9!1T=(psY<PC@DfkP<2_ctr z7oSbEKgWOb`NxN~eBqXbSXm3*cZA;u<|%Acn_n&>G+MaS*i4*-0fTvnXK?iVD~*dh zdqNl$&`1an+;pX)=Gq(cN=YJPc02w{Dn`$J;9sZTvDDQB-cs)mXAQx2qrd;v?ec3O zyr@-QKqNsFx_H108CkR0%-I_I)3&gd=iKe4vHqipX#{0%^1A%aOpNFT1J>Gt<mw+| z!7{fU4ResDO8nSL%+k=mZ~wI}s8bUz^1s&wff4<Ykw^TYTa<Ajr%M$@T=>@*MIQ#2 z*UMczTMR6c4S$k5n=?bR(R^ah#Y=G%5pMrK!}IHF74PT>;g`xo6!`QP%vll>X#K=d zH8-@)L*_Qe#gJr)i~B8m*M$HFaDo#>>GCi@DpfIxbguZ8RlX(@Wk9?ksrua!Z-!^G zyjXZX_DkLe)2RaPunLQ@$o^gHQ_3@yZ2xkP*$8#d3@tc-+^hk1lCt}KyW20ktxXz@ z<My^?g@$CM`^9rJG>{4J>%rXU+>DoJ4fQ2u%oJbpMsn^VX-P%?f&yD#?&;JNm<=)f zm%T_z?qit7?DW~Wh^$%vvd8S-o7VQOryxkCyA~1tQ_+>dyU}QpGxeL-^akmodUK`R zDwO#*4pLwZPG-w~PEp$~X7`uLxMSAKVx)suh5ue>T#=5$&1V9&zaQKFN32VrKpxPJ zD~Y>B4O_{eU}8vaKZ+0V@k3JmL5rDk0M4~5ghdq0fItEB6Fx7pE6tu)<x>`E82T#= z9}zUQ|7Ie<MYnYM8xI6brBf^5|4l=JhH#CO`yih=IZHZ{0QPOA26Z_Dzfr-bJQD|_ z2NPc*6Pft_u}y7_mKOi)TP$9yBi8+hT%;J)!k=9Y4vQ{ANBzH7RlZv-P*hl@{8OTI ze}pxJzQXDy1%1@Y<au3>#zBW+1R~xKcUEmlr^#LWl|7Ecvy&5;1PCLw3T3jtLkndJ z7gtx)>mx)U=OaT9wQY(lV=b;xkrX1eq=37Qf}~UEyi~nHwac!6yO*LCHwjAZyj<qZ zIqPl$jG(9j4UXy1?XCGF0Qzj+ge)B9ww64Zc*57yzWHzO3kM?9yA~)If$y3E!Sr`1 zdjT&E#vUt{7rr)j&Ms_ZbAHOmPSLUX)kd%<ye(fkt?(_$O@Vp)#_u})EZd1C+e@gp zVx9LQBd2IB)F$Bz_i=U8c_Ohh8VyMz1u2}X?Uo=>W69d#<8GbShhKJq;x+g<rdI01 ziCD(l%(qhxV)%$Hz-<Sa2A%?6JY~2JP7$p-#(sttzPW<K;=OfO*U(S%5g7VZo{zZo zWi30*A__^M&rap3kiEexhM&Y74=a0-wPJ*^SNR;=#F_a>?LEeKnnV~h@Eeg--l+F? z*f+DK$a&Q=`Akkb&GxLly}gIC#i5B|Yu8;uUFA@amizhn=?y#r7o=A%`0;ePu2!xX zpJM$2<_d255VH0oCnMd`UL%6f)%~|a#t_hwf`sF-fi*B3ec#zin@5dGWAi`mKu{#K zedxb;lD?zNQ^1bw!GG)-c}+yt$C~7GJME}fss`(kqNuCtZ*V|sHEWIk&0wQwSDDG- zW#c{Mt|dcgt;hez2O>~tfhjCer)lf5^@=BCq*iQ6=Oxv*t(YM!wL75@WzJ4a%Ux7) zPN77PkKG)KC7_}x5Nug5H#i%S3HJo67zIR9obRB=&k#LGciibznJ9pXy*iajo%%H{ z_v6nX1M#?V07%=d%+Y2q#f?DArECzSVw!lbF4@Fdu$H_dUphszWSVjTGS)m(pDFWw ztEt5OZ{il4h2<Dyg4K2)+snwIOrLPhJMeBPvP0sUG*X{VVu!HkeF!g5DC>Qy9wWe4 z==hMN*rs7DY@x^zO@)baxjlz`mSr)(oBi%=@y;nfp$x{1R@(dyn=V|MVe31bT_UVB zQ}P>vFp0?@_)wLMBei(R9&m@D#iQ^ZL#I^FW+@knfC42$sqeuA-UDz=E~a2Jn5`jl z6FIzY10hgyzZoawgq(G5xk&kJt7E6y2d4?x2V!C{>Ap3FR}#%MV5l)jUqKmtGyM!D zcJZH>OnL-V`T3*J{CP$<-L_sIPl2Q1;h8JGG9fzyVHJAzl18Zcz=Jf|@a6S4X085T zZ?V%n#bsznNWZ0*cjh)ykQiziCY|c-DM7lADS61ZP+~F%(38fBa>&>)<_&pZ9ZTu+ zfb|1oIWD>s>#*q|3J-3Vyh^mg3HrVNw0_x<2>Z7b56A`BEx<$_8V^5~OKf61Pk%GE zDQGHhJBOST67Ho2jaNH^<t^hwc_aR^TPzi1ii9hxqc~J>azL-2<BbGol{TQg^NFBm zqo0byh=)ks<M$_M`Sh~T^YIzuGkB1tf1NwLIx>G}n?G}YcXOMeW0WS%tr5hDmn~PX z%uy@%M3Ozs8<aZ)nB6{lA~nFW<lfG~Rm=SIjaJ_w?`XSif+cCXWv6qpVjt{)Ga^Y^ z(1XMcpI5LZB$6MLVc~$@uS>e=T<VxixbNh%6Qs2GjWh%b3cQ{^5a($cq1pqcp_6SH zwxn%rfLL%w`g|d^dy-285&bcH?L1(CY5bm!BqSun{(aZ=8Pm6N%KOExfJu#lAK-tX zm*14u?cDxl2WjRPN;UQ>tIbrfmp&aym~-4r?-$}4&T%L9(+;mFzbp@e3~D4GKlql( ze{V~j<FrS|fY_SXb`=GCv`7Dn4l~pr3X9GkwPFEr;vR)Sw-`o~JbdlgoRbK+`;L2k z|0(%g4!Z3G%QbhRAm0&uLG(rmx*Wsk>RFPkY=1l=b}_J_Q;I&tM$g(>h)lKJmJz7K zT)h68px1QxO<Ua18stpLjD$xdT9BS>sGp;F*(nH{r>KB@PhX(G729UrGM)RW5n*UU zqAmSW{Z1K2T^l)4z<t4J2!uMME*>=<K_$-&T0f}e_CBA^BhCZvSXB?0bK-XYHKwm% zQ?D8jb86_H<I^H>YD$kB7+F`5^$^9bkj0@h!h7^iQKF{DD)DpC%5!sX-Np^yN6C^d zy_KpI%N4QXI2UB3&Yh?bc%jV~|DG-29Xi#LNv<gu3(hePnkP-qp>80Ru(pjr#OQox z1HOQjql-iMggN<y{tDpHL<*>K1qFfe*tHni#|tAr#`1uUoC@kR;zE;h4AZGO<p%QM zh|nRPCL3{W`sQ0}cp6X{1X=M%h(OKmw@K%{z$ju7-T)`YH~e<oOWuAfRx*gdS4-|g zU2`8uPY6{gpH#k|wjSKHeYW2SzY%`I|91f_+PvQtO*n!Woh&G21ka-4PR<^{toUwE z#7EhOYQrHJR|TE&4$EXMFK~)>xlen;x4~wPdy3|j{Ou*Nsj+RIqB8OChg~&-QLw$o zSMCGs@qjfwLA)qu>UUrk1%VV^VA?YkSym`$DTQ%^u823HWc;$26{oF=iy;q}k1k>! zF<)$3dHzbtckKtDhK3}Bq@a4ye8G3U#JQU9*@8Vif1!&t?B-0J(~IVx3-e-QQ~XGZ z9a0>$8%eFCaI9FVZfPn)PgUV2ppT5G{-n6h#_!O&abyDCs{5B~jHRhlcNxyZVS%}@ zes@b^Ix?nH!_Z}V-R>owbjLE6?WjQ~BG3!sF1T9l-ZXN*5x1i1r(KwNP{xnZ+a@KN zGajUw0TY|Y#yG9;_Tb2=B2f-vkz&GODF}Z8hNW4;xnu(HN}WO8C;tEOK72-=qGf4i zaoGH;wf-Af^o9@F@0v`bL_8)E4x?pcw0pVUG;|0F4PC_r07FER(gU4l^<Y^Qmhzw` z0~GZIGx{|4AfJ_*r$~vUQm)=*v$sZriNvhaRZ794$l0-P2qiuXTO&gM=2Idt654co zxkd>ACV1eKCq;KFET6EXf;+b0*a}53M-l#=_ks%PZpn9COQ~?O`!CQnZ7{xO%{RL{ zUN<)~UB_uTRM=a0dasArl7)w^I8x-o!lNw%G*hNWwk51jZO?0X3m5`f0rBC<&+X$X zM#peF6wk?g!Cbuj?LgI(cO;ji<mBRaFJdnB!kL0CeW!0w>^?;=xDUqCKm^8QEQucW z$tO!lj;8wfVVx#R3#AdE7zi*HQWL(h>$mJfc=G-?aA!4;@-hzU1_PxbC;muHoxqC* z&H6z_z2NzjC~G?o1G#Brq8Fx|Fn=9oH!hA7BrKJ43ezE`fiP0g)@lE}!?}3Cuj#`N z?*FlQ3+%am_*)5;CejAwCk9-R)Q|I}%7NfLqqWsrPEH|l+`n{Yqj6CYT+<p@U4u*C zNy+EXL72}xfeu%IC>Y#&4J){q<;$#NC~OAipu8;<*nhfztRW#Xaq*w<gvNRz_U=u7 zM1=WBBRlZmq_0;Mwg#+4B%`04T&9Z@<60pC*6X9Jz3mZ#+G@7(K$DF`6FLsQ(+Dyp zW{#0`V%~9-#cSlI9%iK%dZq-%nA+w#+?HZ&tP*5d(g0(<56=Y(@4lqw2%xMOK$$Iz zFeELAy?^6033+K9CVOBg)&_<VyJcsTFr6eXJ&ksDyerV0P`z5SjuQ`1&4>h)1MO{; zwL6Jx&<g6yDg3LpZ>h-jC^VwZ{3Qb{`C(hRIyFkM89rao4Y$!MUZPHgc^ig2X&|L4 zWAP?n%+OBp^D&C0+9hZkCrWXn*=D}Od{jm7S9Z_FKMk!2MRQi%f4t}o%zrQ1RhK?1 z+!Z$2(euN~58miN`tGj?=bBhMo>c5T1^NS8t!NJ<q}dW@im>@5&+v!}MFWi+;Yi|2 zXvj58)G2V-6UL<m_?!V^nwM_;A02C+BNfP;V5EN=h@^7=5DgFZg@6!=44DB$|Ml0- zx5)DRXQ`SNd5~=L|Cr+3A8B<O%`<oh`YN2-Ej>d8NkFOqDjMjO`}Ifd@f#aHh9_kM z%s3)Ed`QY<5=CTwzR^P+@|)|kv70f9R0_ESe0w<}9{Ud=DYJJHLqXI2jE10%V_cpg z(AOC7;KE;PkVYQ9U?$mPFu0bhmJ+a*F*PriY8_afGFLb&^2^{7VC=~5igRL{kO=m& z1JvM{UNj7382aAAd4DCv!v_)H$+=)Ee4c>%WL>H+=cHYZc#(t#EeO{W>p7W#p@gxE zX<+zvPOPdwDHZU(Y~BtvF3jm+0I#eYXh}*@#*hch-JU;U7*G-u;u4yDkS3P=C=hQN zQQxarCBq>QY|K(lo7B=Qrcdoq0qsD{@`G!@n(bW^`O|c;?3e@YOx*`8;&gIydRPf; zz&^d7{f*)XnF;#Azy&9Bc)wR9Y}BT1nS<>a2KA(;<4~tWWeWMfp3We-nAQ>(&atzM zuuWnq!$?iUc%UFb2@XPnJxB*wIgg`;rImfkw4DllCj)`q8hwT(%<_xZ#J&MtpuxF* z!4t9<MRth8_J2Vb-3im9(lF1H;+dx9U_fG0N_x0Vd^G*|pDWkf7r>Va6iiLQ7SOAq z9sbin)DeU4(R$w>Td)i@v0Z9-LhP}6UT=}IIir#?pR(GvRDMTvmxuyBKhNd~@+Tkt z&BTa{beh(jN&pM`9+Z%P;)g_zqX|X>RWv#u^p)};o!k12lpJ*&S_Lo$%j#V5Ei$T} z2ajNW*sujF?EAmO;GxqO`o1p;QFp&+Vv{9xE@DmZ6a=sxXgOPMe`3IkdEg5cZ=4tO zi`x4c8Z=^nLEhCt7W>y|Adgq>il8km)R9jp6E2DL{RgN6u|bmRAU`~c1N)8weHp4? zIH96wQodRYO?3vIF-2e2q@&ak8Rs4SF3bGXn$>c86faU%!QjGU!a2zxmN=fRiZ*Gm zW-L0%hpnD`QW$4$&;Hle`G*fwz*`WcGyzZI(xiFf%cPds1YuhIPc>}nw1ilR?XU;D zeogBXW13s(%d8B_KdT3<Pds5}!M?#?!A7c^-S}X0Li^Jh_GAGdNf?=o<cH*Vc;PXE zP%4+hhJJ@D8T%<_4w<Frc|EB4lNFNnSRnid;nS@3k`tx4&Tgj4W}m^nByCn1^FcF5 zp@GLqdWG&VpA{bpMu=vGLnNzjBe?@n0gFr;U_XP;-!+>T7yq9z?LT|STj*6nxuT=N zrR8eyn`Pc<(8Uu-F~x)k1@+;!Ag$rw5xmg9IYVY*2AyKkDuXG4_fK%xEc7P?xmDB> z7S~G_-#tEtPmL#0zzExBvlt1<H+}o|4ONFpSogcDxV#tDdki50He=K{mE3P}=BU4* zKiljfiZgm=#S9e<%bwv<<JKG6U0D$G$$qxo?s0nNDQ%g;g0RJf0{S$me4awuZk&d& zEg}rk)R=4P=81y6IR;126;shzLN5|&rb@nM8C()CIb5+g{&x$gwF%Pvs(pYZa6{gt z|Aq7)@AJVuUuYL4pGvGlLk9Zqs>$x7N6w#s2#NyTN9tJU)R9H&I}Wc9vfyFu8fYn6 zDz}3;ho6P|QbQ=NL~@SsdaAG(W2(swx`Wd)qp5qbc589gYB`7HOjQQ!?enXeFeVI$ zFSvI5f~>`%QU`Q|?^yp(t<^^3@Ys@u$N~;h-d%J!?3azmf_{Zg5b$$T!tB*Al*+*% zLk8A*ur&vkjL5)FfKJvNtl>dH^2HjRrYfiZi>v>PYPye_M&Ts1&_Y75A@trsLJuMI z-m5f05h+0t5h(!zgx*DpbOq^1SCG)8BPb{+Xy`>mKtNE`lk0xg{har_pR@ieUw&)v z*)y~EywsoK)YDGGnPfBlGRA4B>jsjCF+FM@o9=9DWB|V=tC#DoQQ5lS+Xu8XpHh53 zChZ)cL-d)Y3x7s}6Bf$C-&hUpKg|=*v3{nshmUXDa$^Shu??w4zq612|L?!Vf9zU= z@`>tzBpe5rTzgZ2le##ytN~9HV3<m5)r7=HjE16=OE3fBY?P%5eayV+>ghuQ-inXW zyk?!3fBwK&SX9CS2~X7(&owY@&rW0V;QBNyFl7ikoNvr1;aeUkOm<NTYH%BuOxO#Z zN9~*SFD<<?%M?B@W%CPkXd3fuP~i*(s$T`JzPRh>M;HIv@2!)$fn}<SdvgLMZ=U5{ z@AgH_a9nRUb#s&7#JY6*^Yrr0<$ql}FzJCX(!`K^qyDG+Ph8aEW&o~BP3}i~*-Lsg z0XZaY>4-j+l<e?uNuIQud2hN4PY^F#8Y6wl+rMYZ$Uk=iIyR-s#%-Ll-6lX@DQjkn zQj<oCaPErR25R%1nj3vqaCd{;e5Lf6*h>2*O1Y>g_7*k**admXe9l-xdk!tXjYuo- zlz9{t`-?bE93tzmGt^0m&RjME5J8{uoP?{;WmXpH;SHX40lFwUF0xMn1>xnhIBx6X zWg#c6^Yu|*n-yZ^e!9wS{TVAc4H9h^i+pt4p+bZInV30IJ}dN>y7i;#zdJiHij>xY zRmMfdS*sAu+n(2iJl~KSxc0T6j9Ljp1e~6cEj^DG(QCiT@ISWX{|tQd6Z&LCB}(1R z*1CZQ>@EEVuKK#E1qbiqv=Wum4dRt{9G49i%190<50Wo=yrjw;(xk=E1c46X9n%2g zX{?6=xSL#VY|P$eWKbN=e$GvK{#67?`<+?<8}=X08r^{bh72qrv7{<-mEJ21^xGMU zgY2j~7XhiO9;?f%-S)1n4&o9o(evCtuFh<>p?F=z*~tV>_;89rW<Xc6=U~}#`Lrx= zS5k)A?m^L%pvRN=*hNSLrNjRSQkc*7^|hIN!9nVMZg%IP&1qUE;6%`0(_NTZ^7NHu zN!L*9-5<@j#p5c@2MY($c?&|JK;z8w`+E0J>Gp>=L_DlzI!GMlJex1Flc->!?2kwM zLm#S+#l&e6W7_#Pv+tg6-AWLy_*M~kE!UiWJHHIt*(#C_EHt@7UZC0dD$(_(ky+yO z7X2u7z>`iXdFF6h<>-A_A`EcmvN#0UaYm>{eq&&f@8(06kOdC!nMA#AQFj{en2|1a zz+tdaf-#?<kc>@h{{*@7J;m-flcs0y2dYcBj65~8Fqyk(d<^!><0uP)@IOR5Ybny# zkSCU!(L-WuYwBLxKiU)U1d*-9{(^y*RkVxzG5h)7PzScyoxhS1oG>ym`a1gp`hZ~1 zrZ;KmG%a%F)iKNeCX^4Tfd3=gl;zF~cGgAq;_LAgxCr<hw9uG&jPXrhOVSNpKq-~i z{?fW<rXH#=Xgt3<j*5P8lDLadi{O489;)_~sv*q<Nc^WomI^DY1N`?_{XA&^N_O2Y zS#VDFXnbRAF96@Vy$pm1MUyEdPt{YgMY?$4(|b_*4?}Ep*!++KFy>yE$KZ!uShKqL zG9j2H`((^@n|*(;Qz6nvU6mu|o@%fNTWBhWR$QFHD;^=cw?b1j3U!OryfmvRYsPKj zmYT-q+DZ-4ELODV%~!Q@Qk8GF=l|q73a`7&o@8DOXLwlbF838|bta!T?SQnaZDf?M zsu_4^dn_=#JsC(4*4Ysl&mAXy^O^%63i%{O`o33Gb$!}v`*-~w7n(AZ@j@XAZ*{cz zNl?7ly_w2X?{s`Qk7l#w8NJbjh|YKvo3FNv&<J(W`x{IB5s9BPaR6LXZ0U$FEu5B! z$@s&DSjqyGY%A?Q2VjOU8Nu>KkJVLPhmU#Pph7VQZ8Wff$OlaHc0oI_77+rM2~HgB zdyQBjdDHeY89hDSOtTj5PfB&*DFJ4PpRcMGI%NL42w;}c0N`tuFUi*2G~nARkws5j zT7?3yK+1FhvXJ-dV>U7g@PQn^A5eN0fpQ0~GyjapM5ccH|Mu@DU%;s!`JyzgeYj4y zcsNE-m;8eCzf<s@i_U(P&l(CL#<#e7al~s`4w5{O<>A8j;R*^rL1L&3aoSHV-}F;t z%Rt0`3K94w$i1p7(&+|62h{F~1sP<YV1ohz0iZNm8S*CCPnEP7BCoy(H6p0-3MzFB zBGZ+?@yo;y#89ldW_Y}k?v0XRfs@hI4~A=Gz9*sJkW-ZA$|0LC4847A_Q`vHCFIK{ zeg#GHowrQg?-ldd$X)CCz3j*uc|gA`4X<5!yb#?rdDlv6YYl<B<Sl$dI+a+hya!R_ zxbS#y-h8;kTtMcmVRo7&2IJts+L2#4k<XjjTl93cs&+Ck2X6e{Tlu0$Q{^`4dIaU^ zhWY!t_!cUk(ny>RVV^e_4m44W|NOZ5%lH$irK|v#@ngM0vVg5pE>{1`xtvA;mVD4K zub@IbkK75`5nalY`!U1;+;f2eep2y|JfODNnk-<drt3@l@u#8Y*Sv;zGkocGSZGM> zC{|fK^C*~}F~8s~N?0K-4xYednFNGy{d!YnXeD~<eZxN9%U$`d6B8t9g;kkyJytI6 z4UqJ7(L(^Fp^TJT@EG{E?wDnokp@0w_|HmA@nINckVTtdZM#E{r1)d~0lQMR`B?IQ zD|<Nu&Ahd=HGrJuLWXSr@YRO2<AA_ys*zSvJDW_ixrD|3mOIwH>5P#ET1@xiZ_+&1 zQ}Di(nhO90NGnI2u*}G+uPrz%-V~%wj2ugQd@}&cp%2K`b#8HFI%1g_?zCUF2WiDk zlFqTNkCKi=^h<N%WCpYkxe<?VzI&>V&`V?hdmbeG0BEYnA$_MF!M0aR5xSqlvK54c zNesfo)PV}36p)aqb(!r=Mt`GR0IG|(SP;>HFx5e%t=boDemXwFbMc;cJiWzBJ~wzw zVK>q&5#{)SZ*{c?AFuN$%~|^iNQ`sE#Q(gF7|baqkKbqDN)(`Mk#QK)$#7{D7ECb_ z-TdsXUv&<+3CyE+iF$H=1nL$QHdM0K#M$*4y6oTQ{9Tt^-u8TiQ0XM`;{FAkY#>$l z=8;J`26bxO$WO`5qw=y$T^I@bVQu%mwPFMQBqyz^wB>PX+yEjt8qJe3ab#PN2^@d> z%B|msIjZ-vZbTRf^5;dlgjehY(S4?UaMz%wq)njf_~J?v-^L_Rr2!7wu|jgWO8ExY zD?T-RsW&LhWmEK`3raS(pV%L0p-s3{CYqmffP7;60V*B_X=9P#F6dRMv2C2c@~K$> z0^-Nm3pAvTiY<#BTD_3L519{ik-0{iQkwrzwdE%$H5XZ^Qx2D*BuzkBXpdNI1{wzp z1+-^~<3ikWld)F@v;=7t6E?G<Vge?2d&;PIbY-+b{z!L}q)}=RbipJH@U}Y}rTG0D z08d0_o#p$da5zbyv<_kXnK?^3K>Jr<%ykKI%D>H6s}NZ~oTJDSK$h<Q-J)g=*FS9E zIH&oV@He5L#kK<LDCkRg$(u4A9T&}QFv{ya*ONhkv>8S|F||08%*6}^yFste#hJe> zd-n<6h0lo|)PmRpaQ%dMzY&QcdQCvbKyFarP(+3Eob4(fpSwAI4PXLP25KX!5bt?* zPTYGg#67s5h6Gu}F%3*206J7T_;v!$Z>jA@l4`7LEGk@YXNtB$X3I-+oWgRDD@zP- z&F(;I!!>r#`!7|2u0&9p%Bv2t@_RA$y{1=+&efi+{=&v>V?_X@v%l8sczt-Qh4{gI z_{8slk+|r4!q43w?t`$utRt=Bfk_^`<+ZG22OHVa^W&y?)qDMASRZSP*yQkMa{gbe z@bc>{-i2wYz`6}Q&bT-Vr?_ZpDzW+N*RYm5`R{wBbqo*(L@@V*C*O+0*1=<tp&oUw zYyHDXdt4A=@_<K$<8$2>nk=_Q#r=>mqJYaw|N0oocu`RulX@0G`j2O%3cpW>o#S{X zB~1nf+CcbYOpoL*iHf2TRhS+Npoqk9vT>c*sAZs$R5$juEaElg8X0El^Km19?{S~J z$nyl~7_a9<n?Y4d!wUw+#KeRPp9`Lg`^A9)(Q6$dr85H_x~g05P<rdb;QhztGRp|M z1U;Xm6a&fd>gL*%oXYt+81#QukJ_cKq?!luaxXaI1Z)3uc|1ds?MyaQxNnFVlFgyJ z{cA{mmhg-I6xl1Wo**JQsx3eea)&5-RMv9UO^-nXr&z@_+*eX7prS}EGb@B-?dA-V z1tblmocBgJk*%%DQ3rkEP61UUs8~g2Wr1+u7??08O14!XxL@6dS2}6mIB{-i>{+P= z?!*IdfOS);z_Mv|_1Pb*LL~b6M=kJWx*d96I$laqd#n~#1S`H%Z<Yxyi%HleDWZ}| zZO^YyPq@)-!_*v`+{msmDC88u-juWplTPl10*EP4ngeRJ%21Cvc9&MF@Mdah__3EV z=j$PF8+VczQ|oG`^~HQ`=1ck=YXJcpt~5fLo#w_U8|1h&EfgKV!yczVp~o0(#Y&O( z(*1_w<X1fh7S6%}PvAeByi^@ee6WLq8}2%7(oFiWsJb?)ZihWXYhx59P9M)y!PX3K z-RP!JZ_(xjKr=iTquI(9$Sz<G1V*G=a(*p_y)G(CGx&4wel}-aybby6^U}Qm53iO{ zBVrZk!*g#=9xNfZu0O@%<z{K{R7M@U^6p8_FD5;}H_Z+xtU_R?=@ICKflSXc6j$K= zNUjn&5U+Db<8jqII|}i_p_T8M%n6me7FrUJZ5@vl!ipl9CR=Lae#B<R1^+jKo*iB% zX<=;_^?>K%4A4i%vGM{_Z3D|acl7S_K9@^KD1;wHa>B6G$Ey?}1iS}-snzQpDjMXJ z*g8ZwxjE_;<(TeWY#)G^97M}c#4WZR1y+8eGQ}y24|#tB6rd$+&0I(LW-;W<_arK^ znGIB9^G@*4xlvdP&GVe8{LrsJ@?4l(md2YRgruwncr0%>lz*6F&0t6&K4bVf?<!gK zH{+HUAnj-II*(oE$)9oNAF)^%d`PPDYL0ueE*$DfTSw$1<@)1yV&8!JK_%=HB!)>t z&KpjQ_8@*i#5JjY#d)PNs$SX`TFQpXX$^i)<-w73GeWpBlD52(9%uic2N}y`dj7>L zVObEUsaz+B_nL5Yf*9J&N>Dh-teb5Z!>KdySb$qlhy#pQb~jr?N74E#`~#|T8h(8m zvduV4zP&tHJ|OowD1&@<enuAGRh9d)zP;wSxN!n`$=2Pi=34St(R&e0`{Q1yd=HZA zsv9GBqrv!~dClDq{-I4Sg+epCf$GB?{&NANv_#eV-(Njda64YOm~@Tq)g=fkmMf6v zh^8J`tMbUHW&Dp=K>r9=iLm?4CGEv)L0LL6(Jf_*e^Z7S@G!<w#=qu)^2>n>dJvST zE3KD^l<Qp*^yn^ipF{JV+aU&z&%3*Q*u4$IYrERoYOrICZkX5SnVo6VBjbf4o=mlh z{U8j<JxzY}M(s^!J>2PPZtp19Y{-Rc-p4X3%_}c`@h}`m+*cxeirRwO9Sj#G6ZMCZ zfJ>$+s_R3!>fI9OyjUULxFf9Oxd?CE)d6#_E8tB09JkJZ^MGM%e;nC4j$~3LxIwq2 zB5q4~51rj988EJ_(FY{1VV4E!b?WQ^(((~hBlIP+2OBsSx+O#vciOS(WqF<+$m_kK zRvO2mb|(eZ>;y!uK`->C$Mc+O!>N&d0GI<)9%Tw*r!wAt#gLH(_^9CFcCEHxL0By1 zwkp{3(qI(Dd}1uN*(2F0jZ;sZIj_t$$#a<7<UfI;f`RA4EMD5<H_o$$_TW@L7a>Xh zZ#eOJ9dTxyzy~TGkoulc>gc$}*-r|zdYnZRhl(u%XDt+Y!<K|(fFs>U#;K7&?m-yK zUp`otiW!XnGG6Z?;0C1}MJ5HukPo;Nd`X)|cZ1YI3W73vp(IbJ$}_xK)##91Dgq7% z!Xxc=GiFsYocKj{Merr{9dDYOSDfPm_)#h_{%C6U+-B>tfu*}Y#^!dfmVi{6+|~Q^ zizWi(xpWgNwR`I982>I(`Hh%r6F+?YYMMo-uL77a`e?C_I=MpKxNk*G@UnT?k<!GF z1Vepl8#k9nnCF*3%MEKg*SIOWm7>{qe9!aOtNv_H<kyq?%KkI&bEz$3vg|_yr#n-s z3mt=Ie=j-<K%;hHK<Ytp?pq^V<9&0Kv@W?b;yOoPvp)`9d*Ec`E@1OwH%|H2C3>G< zTeHXFd!j*5Y>r~`M}$Cn8$rm4#^9tK*?fiR3hV~3c-ZesYpfsHXR<nSy;`6792%yw zc;~(~3ja9Ykw}6vGNAwtIiJl7{|Z2IhPH*&ZcGD_;)ep^lEVXV>QM|tmLAUB|GXIO zgVD=CUbB^A&*L`os{&cgS+S`J%5@07y7}Y{==OYA4(im?spGWHWrV{`a7@=+1jD5w z6Y#`8A4PO%<%nMgbvz!Ooe)*!CW9V8`_(I2U5VYSJktcBD)S$=nwKVP52%3v9j`s2 zD5^_0)$o!;@(k6C9^>~a8Mx2zL_z&Z2~2r4%_?Aj&T`gO{&V~d&+8NjwMee!r&vn^ zWkiHC0!RX=|0p2NL5W$=t1Q$rEeQfFeca?T3gt>w*G%tVRCFOR>{jqPLALrN<^co% z0yAL41dBAF($q(csmn&;#<QZ(#F;FLO@YF;A%T>5GvEvi1<+Z&yip7jIwNu41?N}V zXAP$Ne9lqQ6}itb(zM!X8He?GnlqO7gK8cn%{k2;U!cpgvj$0Q55k0t-c!|S)YZNw z@_j2`?^Pc66Qa&ZDvzfsgt#?J=N#=^7_6tTU31G)L7LsLRub5d&nMX`>JPx(>ZDC) znis^#nWD{DDg5f^CX1oNwYu%w%{$}$w<8f`>&bo*`Q?1xCXY)jYA2$LP<Q&(lZkJ* zo;%yrfrIezxvz6IvtEH8#c^{`4~6~)%!!;OQ(IYP@G;Kk**hBFi5xYLUnif?NegF| zr8@dnvR`m-gPJ}iGC<_RA8AH4xU=`^Mk^(qZa^j<J06*p(Fn>DKLwaXHZk81O#H(p zYMMp6;$-QxE)}Lnna2^GKeSlYQI!TJ{%x^5`G^TqkmN|(FM@jdo-^<ZddzTB4Zyu* z={dN#1snXwV&w!3UeN-#=?fc*qdaM8KbYhLZhmQKXvPJm0?wqNEtY*d&k#_TC|}+S z=5lJH$Xee=hi~M7&JFCHlvv6+Az`}@H|OcjBg||2<Fb9mvVa-!+g|&(T9T?HtSc#J zhI$UyX#5z}UCHX@-a`EcGTHmS(Y4ENw*97U$up}8P_(|K0TbqC1vAl9l)(%++ohX` z=q0ZKk@rmlX3KS}4AS>LG<$Rftw`F}Aq+3+<Zuw`5i6ik0^p3~UZ`{<F_FBSIyihJ zg`xyxSF}y5r$hlDdR=6OO7Qx9D&NV6)8uJ_lX?5poXCCH2*$F+o|enZ55cK0w(*fp z01Db(rZy3ubfvv^HW(Cl>vgHU_X??HR&kyi19%Iih7v1sVoKDV_62k#aSq}<f{<|A zAcjG%8_~ORPSysSRX5Etd3gic6pELFH)MCSjkn=`t<`rw1krIlbS9vxmi(UYWzPi6 zcXv-{^70Ch^Xzl2Bt7{bnbcirWiraBeAeN~Z%0p|5Wse?#lCeLaEtBg?PZuoKHtH2 zQ`Cb_%lbu<Zc(gFOrNARC3WS%kf((`@?-HIAY{nHtCN~0?kw{&KAP^QeTTpOITyJB z)o)D~clphM{?>(k`}oAPAhAogOFxFvN*3UZ;(E_`RpaVjdCAh9JZb0Nh|{{eUl#%# zYhHJ*R>Vu$`B^{nA7XxTF9|<yTq-@b7uX(tGtH%qE$rdb>msWRt42$Ft+#$LmtP5I z`c22yz)VB@HjyVmK|>#t01$mR2C9?nyx@j1`V%z<xRLk=v6<)|0E8%^t35SxU?if4 zq`bCnK*;5djj;!=k~;+UQODYTw;V~+m2FiHsP++WK*6E&s>Rq2*U-Pz{tC2&s0=-C zNc@5?(tII$wi|B;Fq;5<qplx*@bKm&LYwq)xb&rP`B*3ae`}a8tc)``=c-=w`Atg` z>VYK1NcKAF9RXck-5s<iJb{ia?wyw$#XSlHz!Gmkwd#2VVUW(FnwaY4jRzRnNKt{; z8KU)>!FEZ!r;6+^#0gZ<jrR5IFD1_<05?MjfbY6(B=gySurhj(y){j_+-#$9u4v%L z_SLa6DtgK+*xTojxo^qxk^C6lJM0N#`I7b~xuWUHg`m!<8?hd`z0g7pO*e)}g;2fw ztJ>vC?fL-rc&`w``8lmNc>BT;uh1?ez$@;i1aX$yzffe?v);%RMN$+lvxjhMT{_pE zWiHf*h`&MTd}bvvxV4?kz&l5elT7?+LF<SP??V4DkC_jC$Ft5;$MHw82Os$=1gJ_% zB3JIhuV18~+ZOb`?p?1k%*i%ZKYQlA#vlv3Z2qX^#q0X_DAxPBnwV{%uVKG!E*79N znL~ET1B({XDGApY^g|3!xVN#Pf;lKmjbYd$Q>wSO8PV5yZ$Sg$bF;~c*QdaiRIFs1 zyEDuQZ24{W>zr0kssO+n51DC7rda+GGA5>5Oe{m#c3e?J>m!6hEyF8PHl>sszLejc zbZ9JAz4f8my7~2~Y9fTk;bqtdQS%q7{?C<socftX>e(e>j|9i|1GAeq?RLnDx#`0O zmk$52gtp(zc2Q*R{z>Q14vKM58~S8Mf2l_|nzz{bRpbRJ5J9;aH)LEO%g2mXbfLnR zvy(pEkE0<5$x~T8|Ba@K<rI+lEoB!wv1%2cg#$xV0h8N$_-wfk9A(xq-ud1Xg|CAg z!<6M8(Z98eYB79Oq8}N%VTBNwkaq&R;$&DxQ&NEzRJ7!>=<CU`sDyeNH368VMBU!E zRyS(1e6sU5MFdqYlj-;0&6RkQ%u2oKWQsbqbLe^m+1Go#HJvIu%w$8ZN$Fh7nh+eI z1QuaR_E!z0&lb+<%x!-q7rG}VY-auPrvm{`BTn}id9DmMBX~WH9&MJdhZuTa#~siF zQ?Y}hhaU50-=BUKwDJOLWAx;O43y(sWhY)XMRa6^p>9y%wz31ogKh?1(0(E|F$Pr5 z`N27~<y4`@C*^6Sb(MiUXc_oZ>SnVXK=DEy!H<^WMH@F=yQCv&ZpBSSw~TT*3CYVt zANVj{Aa}oi&-{T*)>}|ff(>v1fK3vZRCiwn=Tz%EFaR*)wHT1>$bdDjqAfqO`p5k{ zW`c-lp{1*iXKtCLvPB5T*wf15?}T|IMsm*h%@><LL^VR<4YdV8?Ig3(V>TpvZgFaT zWm2_aXUR7zGQIe`gWgSiUq?fFiROfrJ&1pvSp-wRXhGLlG$P77N6ryhOn>9g)@R{G z$$MNrxI*U+hR`*L-<T=cxyQK+^GqC;rGH@ND6cbM*>UTG!G}aWvRq3x@-991UGf;v z81QHnihGCSKuh{m_$SC~G6{dEwXW)6ovn=eO1@RD`pxcTSXW*C2ME(w=PH+%uTM2p z>$;?b1Hu<R^6g!bb*^)J!EjTi)atWACRyy2bZFpw4A+G`kQ7x{faqqHU-?Sxv|j;j zH63;l;?GMcgP=;vo#P*3kz}|RTa4y(8CWHb-!UMYRKt<U$Vc6S&ao5%qK5HpXwK{S zKMD$olX1>j4{Pp}@alxfO5?w#cC5*Nw<n3A7=?-?fp3{VS8_sU6k(oJ=kl*mA9sYh zR!F!1Zyp$`$UJBe_whgbNu)!446PO@%lYK;9J;BSI(h<rMLmW4&Wrv@Y+)Rv^v@A8 zgoK*z-v=A=T5%nWV`a%qli@$zOz-l42oRF-5#uG~5z7p*zv_O4hJc!nLz5d<|7|gv z0+2n3Nss-I9x!+)N-~}bhq9o{;dmjnBIGa0HF>SLc$^~PP5pFl5~>6U1(d73mh5Es z$U@=8aCXQc$um?+VFW%no_;m#yPA576etfeOR_7;-v49rFX_%OoR<m)Xc2h?+e&Z_ zhbQ`BZ6Zen@1ghapMrB1v}h`mDgZ<=ApW9eM=a!Agq#9txNZ)|kOL0c7+xO>n+TRo zb19m=iUNtP8D?&*{}NStnp_IxUTK>3q9X6Rhwf-!UdwYZIVfrCGeT;4m-`u?h##Cg zz7s-(T^r&8MA1A}C!e)gtkNTMR^M?9UZ2@`c^R%ysDk?OKL`w>cx}iH5Ibm_SU<ND zdQLk}6UClK9&Dni=i~>5EX84*wC!l71m#P*p!o*<I{~Nu?;CBO2do4veMn+zE|Ivl zE6p{*I<?Z^UD)U~G<0j>``c>!b<t^5ABbYJgoaM<em;Dl%aiHp6J$+_74?IKkXG`e zz)-6EeO4xk0#u^*5tN>m320r!Ns=ih1PXj`#V&v(cJ9PlST&G{^^iP@6Iw&=H_g3+ z5sj@Z!)2V(t_lv46pW}uRy!)cCT{GxQ%zz357>}CimX~7902m~|8uRIM`sn)*7bj% zP7b3L@Hs{d_*=JsMBC`%qe}%kfyhRZCc&UI(;N@R@8v!C3grj7N66UMvF7p|G7Dp- zcJlGp@vC&V<zp$5W3d>kH}PC~;?|({WHGZtR+7)<nD{Z3r`w5f^+bVO*@?+S9(|j- z*(vF7H)5xryxABl7Y~`OM#X}}sf0<IXOdWO2Moo02C6INMIGtRSGQTqQpME@2!-?F zS6P-ICF=zMNBZw+0JD^RD|PYAUXn)^Z`jcN5)5TYtf*OLOOnWH<Z8T?`xS%*+SP%9 zJn&&|vmx=?gv^#YPMUMa)7~_`g*xmOIp*e{7i@(0_Mg|CM-{hU4;X9rP)D@iG2-l> zhY{qo6kTP=!P_1chX0!Tl!9}rjNV21Y(5UzxT<ba$Bf=7PspO&!7$IdRZ=l0&Ete2 zA!gq{9+(w3e$#1tS6(+EZJc%*na%f!>jlrOOvKdtv&@z6%D?Z#2=<|!?X$QF6;ZiN zv6DkXe@;Jm{QP+;CMeVfx&Qegs{gN<533fp<#6F_RR@W^cSw!^_W}axNgCl&B-uEu zE*1eo;Rv+Hh`Kq97oB*{PSg6gt}mi#Q0y2fD%`=wt2e*%P*RW~n=<%rS%^|RrJ#6f zg+rO!ugiNeclOdhFlnEj<SG?2u}yrD4(l`=a1&Zw$jAu#cvv9i@#pV+;lGoCCvSBA zt&Grr=hqHJWz(!;#QdOi&>P?=D5Tv6XY!OBI^7&0XGmAP`t<0>8y!Pdt~It4fgdaP zz9cjt3;qGSYYcHl9oI%7RQ!okWXc|snFkPglx-`WyuR*R?I-(tR_I~qEz}u}or60U zB}n+Iq)46=#aM0JWUj@|91c|<!bLZBUKM|lE|Nh}?|+Kg$#!k-mikRjo(`w~$ueBD zekKK9mbFT!+y6QNP@_oI`x<|><Tp=``f4IhUm#cb(W`F~#ry(HnS$Th*=uGcj53SX z7sPS>6_4n#)e}%T2rm+Qu&gFI6kG0XseMt+Dnvj=V7e<x4ypyPX5bI@->WB#7=bKv z8UoY;ErM$tsu?GP5?VR@8^E^*D=%rg?et;{bd?2m%HdomVpCp}lF(rZni6jtMGW?J zWz=JIXcZgtEX#^fGG?qs@tLjOQL6vO^s-YDjgOt~g^wC%5&YC5>dk}s9|u?eR9&cW zxW<S__(X$WS~s6B^dMfS{M(#MQ?-@tblIwTp+-mbegO|}q*bl7Zhz}0)+z}zPNFf- z<U|?}Z3(89nn#qM>A;BP&}1H%x?R!)GQmN#o-b<S)aW{g&V#cCINxK<`#Bln8|3X4 zD69M`rMkVVW*#y8@8$hPHsp`@#TxuyIzs*=7DgUr74$9iDB8|6H#>x}D#pAB^Y!Qm z+Zt;%{eBhkDDrZS=7vRo#(EXo9xQm(i7vuu=nq>FZ#AvNeF=ltlFu2~FH+@RiI*DA zu8Zcb&T=S942yD_ushMaiG0+{oJ}zTfwxK|ow7$m?cyaqI{CgTu{;#pl=MV6CA*7b zj0JV(P`7ZlO`yAY9~)H_6qiZ2u!u2mQ{DU_B5?EYoxn33{%feyEPJDOg^&=ty5g+A zTOz1xaTG|~(B!m+#5uI?P{I*f-W5aX8E`Fs5Ag_ys)pA;?zzsuPm2}58SuBshFhiB zuHMVz$!>An7erm~PpbLQcTY7DmfazirP!Ol7IN7*KDxQrgiCYRX|H5EqR2KA^4%8W zrmLq<lxg#=Z1ay|yx9j;vi|)3$--e#rY*BVG9La??JYGRQUraeP&C(lFSmLdwLyEw zDHDmN^-B1|%(uAL5<doYjAbDE?S-`XVA)PG8q*Mo@)G8%B&wRVjJSG=U!vljnN^0D zZ(@z7G*D+rg!8g;)qJmJr|<Xw^|rKU`}+TDnYTItV><k+dV)-y`ugN!h(E6U9;v;4 zWiX<{da7W*=D{^0`IRK(yC2e58UlofGUb@_mvL+oA@R)16VgHSb->LhY?8+HhWt@^ zzgsQ$YYxLzfx_b{xXM_1`tiJ-lda-lW+;Ifnq5<-jhZD?dd@WS9x8UR7hJC&pzd#% z%e@F{eJKO(oDNXGvv+E#{pw^_Y<cb~#`qCURk^KUW;ef{QQ64+ib-t|pGjgY^eHD5 z`g6or89)A?UEi02S7ViK%<Nn>SPHa<%ATwitx;Q3wXqbm$V-r~*2)Xrw&Jlue@AlM z4`gi6<E)mRIu4@;{Q1T(%!=XC<;%{w2TO~lbqK991+j&)-SiV27ea$#?QYi$#dY4A zwx%0K8&bQZPg;4h{zf8VoioUl!;dZ1f}|VOZID8y%TpBT)RzTXr-vR`>3^(!>dpSU z%g0|-Tr={#MVx+~vMcE^s;4%2XjV?Px~O^ryb+>##Dq)IYs50&CqxKS?Vu_m!$&jt zg8Tn;YWvkRmY%HDFUy4R8&vFMf3@SwezCA$BJ+$PV>)Z4O|TD<Kt<>mGy_bcZuw-{ z4~XF9#W!OIQ<mMWIlqR`)nnC#z3%qBvGS`gj~9UvI<89F8t?%bMBZhOrkTYWJqp<I z&+*8I7pDCMZnQX14=Rs%O<a8Wt9w!O=bBB-tLMts{^vD}ow+j&?wLKiJ^bS!jD5>L z+Nr~Gq%Qq-lVRq=Q=?>BEf@MAvS2%ZE%p<i<C&tg!$QjD^kPq-hIdS2x~G1%VEp&5 zr(S!DD%VMS8fQX{wFYT%_N2LCx}tg+t>=$crfIE)s>KdI_x&b|B6P6e-lNwKWwx%J z_)jOn`Hr7=X*gc7H{ng{otjQK*t-3Mn<}YH4ZHg12mjSyS@EvAD>KRP<fWb6?60OP zJ)Tc&9S?{g&w1{V8)Z?i#SiZZs>P;~^@Od$8>QLi??FXYNr{TA`M}n^ybcq&P?JPt zym^TU>b{M{`y1ji6eEH*MYn9+YEU8W2`^IPb78^u1M_WM5>GRPBQZ#oF~rhi2>neq zdOoh!+3Z+{bwyT`i}XF^7Jzs1I<d}03mQS`ROH$fq!oTx4(Eo27=`p+eHqr;{E{ur z!X~vs(Bw`ztKsJBgks4dgfsym*LU)EuFBBsD!DrdS9Z@0(2mqQ*}FI)*$PfnS}k?{ zoRH;ezcp&h{_$^Rq=Y&jg0$SLbHP4hR`-3h_QIi5==*m<2Yb*-Eym;Ah#blFhaDDF zf*^s!PQqq%#<}UEa*Z7b_glUk0qn4$zsZojZj=G6Y~CL$9p#z%_rx?Wd+3^;w?aa| zhD|)Pg*~V?@h@t@NC7Nqogu;{SH%vs@EMR6PxNVG4jd@?bEi{YSaK{Bke}7YuEk7~ zVi^Dr!qiGVYCd$O;O_KspMBLjAH~Y9xSw>(e$cx()OJbrWXGf?|L5NH*d^a`t@V`S z!!r2NXIlyiNadT%xC--~Ia2uS2_d#^%u5NWab)tvWGL{6oNlMj$4hBtThkE9K|?7> zQG(+U(7dV)>QC&(W*VwNER=`t`H2g?>{PB6qT)hD7Q5g0R}#4J#c4|WS{Xd>Na{}h zTK2R3dmge=4wnv9J$J(n9(R5Id)Q`){2Z|z2m+ZOniyt62_B}#X#9&iToYG&ne8(0 z<gy_ytJ@NKZ9I#KPyOWcgYUZsNAu5Y#|bZ(-Mq&LIUU)=714@#hUn=4N%4^6*+vwG zw(lAjyHeOwyy*ro#oB_3T~cB~+#OZ~HenTHx89Hd?qypUoL7ooy%yF4`e?&{s+>Q= zT{WbZz47v$m%#t0!x*J*W>8;OdWeKH)GfqEL||?dlb52pg85?&7-)$PyY;Vqs{^Sx zKMfLri7rpf`jB{xpy|+Z4Wv#q{Y<G=Y8Cns8E@dkW=lkkhy~>JQlT4975}W&j?YqK zb$aOTE4qzjgEO|)FEe#SpA(6-nWkd9Fc`}p0UAmn8*fU9awwA>vSp7)p3)ntV2xq) zEsrQMVH8eHuMog#+X${WP)(&}lr)kOLX(cTRMthh@1!`L1#cRU$a`Aj8SuFkyn0^t zuj|2RwFD!fA@Q(-<!AoN6&ix{bhc=zV>_Ydqa4M4qjLJ2`ddl6)(piQ{A-V%-~YSG ze<0N?H{AdDTS5Bq!i$UfsYsoFG+wvli%-?QT#hGvT1hbX5~%%swo)~obV~>HA3Aa2 z((3q^PQ_G2My#(hG+4^P9NlU-VHl;;hMm=NIRphdm2e)H$Ev#wWF6j8phcB>j_`fZ z_}=^D*VkqtXUl<=a;%rjuCrnVj_|?1nZB}RsV=CA^&qqve*C;GVX*2|@ZXOg^QEMZ z>-YoQyH@9K_4i<RtLV$Fs>d9GUL~7^%btL(Poj_3MrukUQgkJpfGdkumFQ5bsZa;s zGcLtdi23Yg#|L*kgx>YuZq0y9PVkRwNO1|9=aPQUWBx^>=|ZR*{bpA964ul)G6{UL z*<y#xf!!&J8`f#HgZ92)B!<l=$Iy%0hRc_{EHA95wk{}wqV?A&fh23VMa)E4s(aq0 zS^h7GMaVqV;C?hp1}80b4orJwnu4lLc2)KlqD(`$1V7UFq)KJ)GD&&2K1i{fQi&wW zkP|y3wMM!`%3D$28_8YzxYXwtr?J|{YLknl=+|Z0&`89a(S)d+4BP={eDDAFifp8~ z{cI&j&&{nDce{f6o+Fe`5yxOnkri{XSx^BRXG}CQX%}&ErenQ>xSNC(B&=h}Wt=*w zflKfS<YSJbuSs{hP<x0;X(uJpVqD&5Khd6+(&q%mGmwBa_N6NXsR*F5R+-}kZFVvy zFw=(c`^V#Av<44;9_WkAm*ew_Z|=zpGNeK+p6R*T>{T(Lk@<CFhHq4Mtuq0ILxWex zHm7O=w#LkKWrC&ecD30kT<yVg4H~ev@T=?_J_uXj<o2=c3u7GELcFV8;OW?UYI8v- z=vi@g`@TK&lzaX`{{vws^S9oi5yPzFk7ug}j>>nlacwPinQ*ONgY<GlM+l$#@bgix zo(;3S_WYe}ySEPwQhvfB-S2O*MR7TF-8n}##4#w~J<)z^Pa$tAwGnt`c(T0Rd$IGz z-7qH=shBIZ%U{E$JY4H3iznF>@4YZ>dtxF)xYGH)|M+b^NB6DYCsp+PZg@KA5`iKj zqS~S-R#;X7Rq<x`T@Bl_Jm!o;H&)c0^f(+KmgOZHbV*Sx??as$&+^*ZGH1@?A@Ibs zD9sV)Wa7&0jkUqR?n4LdY|x>VkfRh=q&Fd)Ck!zpqUeVvtk<n^vgo!~WHB7k&@0)9 z5>P%Ai$cTVAXdq_l*I&<MU@tLtsJq2?A!KU6B6T#h91^&xe|AJ-g)V|PLC00yUCcC zqVct_IIi94z|V7agn2a9z9Yiw#HgN<$*b?V4Upar9w)S0S8tHW8ti-*vKXpBsZEp= z%Ya58Se7eS>%C>Fm*10qoHJhn)XteOqXx8kCgp}r91)Zgxs_?WJaSr*=kf#e+lGp- zlIoDvJFq_RUN&mW;+Y&Ygi~7A)}IAD>%5v+G%T7{ZY794B{xVqgTv|@`;J~uco0<+ zK2~hkjoq^TR)=DIsZ&QDfm&rRQ(B?rTyld?bV4weE#qx3?-;YvAj)h-6Uv8P<K{}k z*JvvlYHCd;>?5p8;n}!I?n=qnWYd5taf<36xD&to8G*bl{O!IH4H2L3Jsx@d5U#&f zP*45Da6#T*rO4VUN;qv19W>?fnfKypCDqAT=(PuL9*x@XR=wHSopW*8?deBE;HdyZ zqa2HFM=C4KEu<sZ``#vyq?DeTOXIv@Xi}olY;i%2#bcY^oEjE&FgKnR1cKwCkt|yk z+wbRN;d7={3qDJ4C^t1c+_kd{i==4UqQ|C(Y^_AT%vPCyz0!ZS7c3iz{X1l-gN!+f zT5(g0sP4wlu|C7hkL@tm%nLgh1yaX}cK>^MR)YXi8mZc)@zKk>8-$Xl(<4m+hlAjt zRcw9r^E3wiQfNgjy`QPCgG6@Wp%GHh-Ag1upAUsW$CQ|QF`8!?tK}zO+t}sKean}S z1&?E^V~#WGp?vn15zaR2d@qN9W<*gP+%@Kst`zrTEN8CM9zHQ5BxEqOa~D(q-g@^` z#Tuvm-*G$QEwdLxLo{)(ougo=wcOUGWVDe%G`_crd!p_4^XIUU$CNLTpVYjl3`Yt> zT$cZiaCmG;3VbGGZGoS0=V`w{Glj7wn3`_>t~5#smyicEY(q<j_B*f|*0=O;3Aga_ zAWD^Sar@*~?^YketZ|$I5Snf&eeRXHXA#2)sN#vRoxr~ZM-LIfNp3rorGJiN@=i9Z z=*Y!0q2KaUwI(O4d8;fDwWxC8Jm`U%J`1V>)HMM-A~2h!Xfg33Q5-Mcp^@xEgJ1zp zYa?2{Dw)12>Ys6TTg-~PE+&<4NS2wrQy88gANO||n%}S2v<)2#M|HEmzm)-Z=Jc)} znyZSKzNCF4TK#Meu>+s-4VIRju}?`Ki|nTMj$o~quQ2?B72?*f&!79jfyt!Y2ei{r zJj|66jt>cF^cCLC207YjHLZny+&bdxP1cYN`UVEeJ|g`+Hg{sp9&Ta&ZTg<)6AyR8 zL1O>-n?I+ww;!ph*h;@SAMjw`DjUDwW`D=>ZBSt3kEx|honNGPmfDd&SMDrx*${?a ze9?MtJ$fjEW_fm89V(0se(h;(?@!*cBhU@o_^+)~iocfC7<)JOWv+qcOiWN>xLVQT zEe5YWs2}OAMmJO~1mF`6#hTQlOo7EtR^5i#@z7D$?QyF(2xr#q_iBwu5nk9s<DNT0 zSl9%?8Y*3c$U@6{L5JVcjgw3MX5AW_h>_Jq!_ECFiksZeSepK;K3%jK8BRN6|3ljR zpME#}|Mt7b&ve*R^qwyZymDxKesVRBoJlh);?Io3T6F&C`f^3?C+RJ@_88@@%gl<- z2_1aKXoP-6QMctd(n|ay2$C+twHrf&F=~JRHT>D)PH+=Efvz7$9?*wO#?vt6+@>4D zO2uo7Kee7^k9`~4i9s3hWJnUfAroHcX3k6e48#}+mscwbSFvJEs~2@k>%n49V~|-B zL3-UJzd<ZXj}inD$$w@X<&-)|SInO<MoB4$q7;tIWoB#zFwUi8^=PjM&t|=q+jM*K zG+<By!TgM4$%?O#YfnHSxn3i(89k#Y{A07jwSXhcxpWx2|K(HjE=TKwX8w`oF*xWf zncM6dCsoIuTi;prwr(bz{*QzGNv*Z?;&eX5`|exAvi~MDDZaA;{mgcpLPA@jTjuS1 z<Lq)DLQcT^W|9V<AMfRWK-z@SkYbFcfGF-=jinG>F^e%tic(<>&=tw^Nl8ZMBkRLX zHl+_5roVgl-8!zU|L*F4@%q@^Lzcvy8T9FN=F|5-)7vdo^fh0QBBim8DR2RrSb|NO zpnFg4lW?lTpkA{*;5p@y?K};{P><sofNPDX3v2O4^-E-Kw@GhKR7npfOo9(4?jvgh zO8AY%iR*^Xl`uEdzP3Lx<T{?O;l7WzN-Elr7!GyYWQAZ5Xb}^zxwrxC{X_~HD#9Ry z&O5ZR<+TKb9j&#si-NzZEqQDQa&hVYH@Ex!|ITZiBiaxnPx!Uub%4uAB}=$f^Yz@f zW$_b^3H7*ICqJfcn$<Kd<C=hfQKm_1L#hOjH|H>43FXfry%TdgL8?nV*^OU=PdW&J z|ETk<w)uYl%*oOttp1I^-8(ZUv<3o#qQEzBo=HO#FV^!Ip1JC6z-m<sg;~xh#MSN{ z@Olv#o^@w4=5I|?9DK%J|8@6;vE_SUDC5@l{A&lmZ-Dv}4d+C=5EG_cD;pRTTgPnw zG%hZIQqjg@*NCZ1o>2K_dAVfb@!Xg#nmRY9LSsTg_-Zly6lgy^;9FHV`Y_=5*E>P^ z>e(MDuc{1BT;2)n6wdx3%VO!})~+0O5Z{z8*?U`(7X}?0JJt_7FdioXFYII)MNj-> z8cM!;keAlL0D8dV7j|5mciCD<j~h!I&N-wgIo{pmuTA{2N+Qc()@BG+l5bi@F+VzX z4Pfo}sY>HU)vw&b{l;64{4!>N45^L&_ifc;{v59XgC`>IG%iG(Ez<KxpDc~?$DEHp zVX`P8c=(5&fG;>?-AH-j*$h@2f#h9V3DNDMck82>?@R*k)+d_)M2y*90tyIr^S~q~ zeo<*px+Tgn?L1UJLP2uXuJ0Ya0U!u1;UjG~6qKi=A>Lp*pZzgKa;!q`163$ZYbX$` z>sE;e8~56nH{}e7;w3h7L(RFK##=0`5R6jn`_=i_+wFz<>Hinb$frc{W)a(8Gmiq> zQ}o3S0lU`BO~JCe{x&?DkFRmkO!#0q+1s@}x9VhJxMfX=c*6lttjlsf+5b#@j7{cn z4+o<47~*0|$Q0;Hx`uIs%JUuN;STZb*Ks^TD{6ClWWza<$MHxj>JFpYvh}ymeHvW0 z4xs#v+seWg0#+$=ygPcz_vpX|lGV17EL>dDzslLJ0N>^^gT&LO^I0^+lc;Q%e+Krz zu1;bm-jx{X5-PIj+665uQf&bmwn^v+T}2603`ka@U<aKjX#ZW%%tyQeRP*)+*`F(R zrnzNMi3v%*(D=2LFSIlF^RWo|)*ehzq$d*|B5c}X<&=IIf#kC*ohk@+yYM%Z=&#86 zFu9a~&T!u$o>a&NHcOCu(XEQ$rU9}@pny$7XbAr>;cF+^kNvvWspy_JPC}fo$5POc zXTIbD>&hsLi97yZBk)hjy6EaY;G=HIDs#y$<L`TaX(5=jZIAGf2W?UFlb<iwjzx7o z1U&RI%4GZTMds?KGP%Hpa}D^X=&k8C4%wn#9CD>%eq%JNdi_2BZV0Tne^s<#LBUUr zdSG#YIhDZEFqlLLtr`j>0aIAZqpLpDjL0)5Q24mz;ot+8;xvmXpXZ<lalZ3%*wwh5 zYCr;1)Mzf*RuaH%Vr*h0V)YIaWlkqFk~5#Dc)<KCE2oC`z9gXOwn-i0rZOj&QPr(e z*_BXrX}_=6{X_qk_XFH)U7jNflOM|e;9mYF+J>ABw6Q<wxDJ)#h_HHxDs_$Z`1k7r zCadknn}bhXnd&oo%OF8CEXPylw&OuK{K3A0W;!E<`{{ev;PKW~Rk8-6S+Mwh*Aaz~ zm`gdnHktwB8+JUr4=U+R{S~27Y&t76n8j<KrD$v<wMV?({q^=d&1y+b+>h-yEIpxm z1``r&JB})IxlYL{)dE>jVM}sn^?2U_Kr$Gs%PG9#1q}<5wclr&ea3C8H#Yl?wZ@Lb z%vj-^Cv^f%17nrWM$-X`&n#2ySL05M1g=7Nvv4XqMVjWd6j|||IDa>ExikV9f5=30 z^rlql9`8O^BD_$pi7NuLdH((EOQA=oW#*K8WgVQuSrK!nBF7VQvXgyLo(}Mneh>cC z;dxae_)5+JdFLY}%8LGLdVs_Yb>%1x^h0Krh<5g6H;v2ZJJuzxjBadW*Q5$lZEuR? zA8M3Xd(<WEki5gcm;?&YAfLNa6Ti?}At9UOJ9SAA7`yn!TaE3RSJ5XsrujQF=<V#f zFOZa%^h-K2cloDpbiMa~0RQy&W4)M8A7#|Ver~4R<A`sn;q~)F*?d}pEu@M`?MGHm zEfod_$<!OI_6dYWa8|-e!ayJ?t$b16JX=h07J(MOGVsS5wWZHBaoSF8Gbqw9AR~UQ zMpTQrQbJ5l5tC?Jl8UQp#hS=hu(1)IEGCKOS+R&3F6xRRpw?wx-dK=!ECJp0R?cd^ zGK-l?A+C6k57eVvVMqb`f2XG=aufQGG(<&g{4xz|(5yF{G^!ylR*SV-@dTY6tfcC# z;lqCy2fw=5Z+o*wVYi;6nIvK{p3EXvF888lwKHwu4aNq@AAZoY%^FfJfjp~kewFfW zk54Q1^6#JDUXFHpao!V0>!Uq*SMMlrY$-e>Ih1@e;KgK!kt}yt!%c9j9={P!qkH6$ zzFWbLvB!Z3?mxUUcMEtz{>c(GEKER<^VXAb4}KDe10s^;)yt(T*)5adY#iWjN@*Lj zY6WHvPJ)Y<G6p8va;37?m~RJRO&##5GhIB9SCN6;JS#rC2jgn<qDrxx?N{yJu-~7I z>^Sq_z6@Fu;kFlPt5RDJ{x}b1`ImN0{y2~gJ3WBKtEe}Z8&3P1WuhNwX;=DJ!Qa>A z8)!YMXZ<c43VF~|NO#voK}(TgJoJOD(En*%X{Ghd*`Z_}5p3wWkLzvFb?372%@eaX zM>KAny1o6n(5*>gPt{P5#QP(;qX#AiK7{Qr9+8=#dhQtupYjsj3c%;;?P+{brq0Dq zuBzp~f+)+CQjg_+->}~=-X9VBKY!EgyL)z6QS(Ln&+AbRopT1dley9F{V}V_T9d&L z;aylZ&F7XJAoimpIuge;N0(31GtA%}_}RlIjM6%tw~e@(oR_8F0*V+|#!s3Sa6(?m zt(W6$(7*)(+s54q0Ig77IrFWwS&UmH+h(4XMIw3!CW;0pR8vaf#D$@2wU*{P8A0?g zBLuUnAQX0$_7<hOuqTbAEpQV0AlZ6~N<w7b%P&vp4my*X@;`Or|5Pc4|5K&7nY6rB z{G0*oFEC6HmH9i4vADRT|HP?ZSh^1)PfN%*FD|yrMy)qnH+q<ctdIQnP$8an0rkos zwo;T(wkN}n)P1ng2jAQyc10#&8Nu&T>H)N&x@x5ct`Y_$qv-CfQuv(yZCE`<f^C^m zu$+G06FFayj15O7Y4XcGp=2`Tim2gO6AGZ+uDSQLO!O_DfKs{PbBw30gZX9&iQ=8m zndo>wUN$fd-je~XvIbV<La59o)sIyO%t6&&etXkk9b3ejQ$vp#h~@-w#c?nXH_etT z;vL+)d-3qopsA4l5K1$aAI#m>iBTi7RV4-EMYcofNc5XeTlZBt3c3f<Bz=E;wr+gi zq`GJSgM5lGh4r0KhOk!MhmX=PuGiCPt%VDV>t#aj7c#OL1-*1?cPW&$nv6`lG0(|d z<Tj60$^n^`Or|~Gd?{)nmCVQPVsVswHCVcs^%rg<?bf&SY`92=NlhurHQ)(gglJf3 z^6|w&hSTvm{k;$j^H8StF9H^5s}{D;IY5^avNJ0XS@IGQM|-#1OXI<rw7ZZ%&iE?} zLR;%j)t4Bo*Y14q-xr~$eU9#GQES67(Gma1S0KLkolRW)_#PF#oBJgyeD@xIbm&pv zPbNN{&mVioKdU|39jemrCkTfQKikqbaJ{Lghzd@9N7)Fj>%MZ7ayrf#;y>&yMVBvz zlz)3~-{bdF+9+MhyUD)*<TCFJqso5FW=4`7ri){1BQD;pG6lryny}E(_AKJnDi!Av zJ1M#9TB)-DY(nSI%W+R9D&-gDSy()GyI_$3{`P({gp*$*D^|=psmKm-Fz4_42viH( zP6S3gCuP&Npk9n*Ld`f#_XQqn`zI(m*+@RYaaXdv#(b>X;-<^Np|UKbT!7ny%*CMb zR;25*RAB}!6IEc`%gGNoAXhS+w+Ov0oRelslEHIoW??B7h&-n~-BPf|i_0HxR<&B_ z-akxCrxDDx?F{3EZ#x>HLGtaJ(O9-p%;jLrEI#oq-HmwoT!}iK=Tef3C70{ogbA9Z zmXi-A*t3bwkkz$?no`-kM5m2(r#Rk8Iw}2Al_^detH)UP43s}dV*}C%sc}jq#D7vk ztyB;GKYhJrP@7-$EnM8SSSVVgxP;;aFTtJQ?m-Kb;!<1#lwhS;@D!J##VPJutffG4 zTHLw$-T(XPoqKO)@-35j&U3b%wf9<wo$L+ibW-M_Y*rYrwMzLbv=6t9Y_C(uA5s4o zgP%_7j;o-IunhVXy=9Qkp@55^!zxd7*DvJ-<Y>nNcV#ssW|Z#|S-up5JIVPCxjxFf z{*gLaDJg0GBb+ecAnYUp)fw=}A`|5W0cY#+K~NOeVRXVn7!kmmg-q`{@k#c}&Mt_5 zt2WRP@T=g&J}UaVQ67V!vDLObE&ecMER)IrB_}t^)L-{xT~|+u)JX$_p;Zv{s?`)Z zpp4j7*31a!;14T|oo^ffYfne{@DG%vB}}n${4JR*o5Nbu_}P9OqE<DXmp=wb`0p3b zP9A0@JvJ<|o>s0VpVn>&7T2Y`%T{ho?>O%r87*(`5o&)XA1{}t9Yx*NOq_F0*qn^z zsWm@Kl$fe+;uSt)OXX+#T&ePN50kD@moV~M%ZmOu6U)5ceAM|I0*GbM%l@!W&RGET zNg<WPW{xCt@5H6wRhTLOL&^Q8h)7M%V3^NMte-biR+1T%t32NnuZt3hB9(m}5XqWa zCb_^{93${1ohidcVPyE=m*~e2>IL9y++Pq<4X3PC7BD8ud^fzP`BWjCz5D^=qcD@% zN-;a<Ihj*z6q|r>T7<lng#8?;lQzPsX=Vr+J*Bfp#*j?mOgO|%Po*qNfv%%;o3fvG z*dO<NHKRwz>V;TwFA+fgnSar<<8fYeP2{$w!YW?4m&bj0pjZ*MaOzJ#N;j3aUL&o} zk|+RET8VoP5f)|3DDD+`ClwGA{;S+&ngz|HOcI^0*SQD`Zp+4YV*4dapUQ>Nhnn7F z)o}7dVR7z>e;s|SCek<W%N;-E)SRT1rPRs`n|-eP_$!a_A{G~QBCdPIjIFKg+4E2F zy_2TBpfV7XmNiAr03FBBS)TbEmsaulhz`t?-KL*2syvCfjk6dyV#ODrVuHb{h0+3A z<tU3m-^n@+2>tprx%lnnTGnKfLKiL8fvMXrnGiscIXxBuV=!<@s$GY^UTLbdB#N(c zcxTHT>hbnpEh<M^Ya^*ocMLHir7y4}UD!U1E{&TohI~fGeLmaXh*d4q1=b6l;LbrA z@lCc=OW>yK3Oz*3;u#c|#sn?%BcFLbuhGGMyi+x`?s4H$a!_SZ29DITHrf84?)a9` zzA5N7#HlgYXDb_zR9cP%jtfpN@n%%du9uRJzFYb|_6gN&80T6B9BqXLK5d?CbhVrh z?!8Dz2z~!=6Nh@T>u#l?%;Ii*_AY<9)*73nhoC6O-zOX*cB01LsVIwh@6%l&_!-a~ zrB6A>Ux*h~Q6X?W!d*iO%B`qN6iOCKm!f}Q{?N~j{l<Iq8TPNreQp1z$A|N32ny!J zM#Gs=U|x-q*AZQKffmUgkfz9hQpR6;L&`ECz!#~PpOZc%ISyc7+nW~diSg1MBF%Kt z%z9~&>gZ%PgH#I}2@9e8wyQ5x-jj^`I$gaZF7cEzEO*+#ODI;h3{ELSH>cY7)<pc5 z0`syeP_I1lEnTsJggu>^w^CW{R7~nF+4?|HW_4YMzV_Kxj0>?JRzSmfA^&$6<EwL0 zvjTd*)0)r+7e5kFlmtb*FuLtvdy0y}4vHK4s*oCogkh^RCR&?~RT+1c06Ji>8pobE zkR3;;8Rb0_6>@{I9#&;nZIBe*JlDgUs`7jZ8-JJFgbbZjjk@@JyNx9xx^Xk(V0Rip z3N)i_s)$Ah^4reQ!%kZ|ji?2qaOL@nX-KP-olENU^1T|1Xgh7$cof7bDPZN@-OLgk zvU5xdJkPmbZjx#ccGhqFT|DE$uYj=+z0wNis}RS3egY9rAhoQ`FKq>b9fAiP^$y40 zi6#AcIGA@?AsDzQ^ssmp|5JG$YUJ{DG3p{30d~@~I3KFXX<XaX?biI~B;59In;Hk? zA(T;JpcZA5r>U_B32(H*UVa*DEHOWV5@hLVKzIWDTAH0o+=P#9X_NusdQ{kIFQXvU zc!2GuAGXun1?xCCYHRNV@l!rF!qZb_h_QszG4PY4c9XFz2U9KmenlBt2E+ZZaD{Vq zaqGH+eYj)c$^esmNQ3Flr8F?Gz5VYUhE~4h<?4W;#ofvGy!O_X^9k?Ce6h#F$A`eT zgM05@jKK<LaPw>3RPYE=Fv{`%Iid>j>qpi0Y(PB|4E<U%Rf9P>C@qei7r{r7FeIzJ z`yorc)<zo>t!*cb>lvJ*CABOrz%E>;yh#pBv8fly5=Pe2&$%7RqlpGMR1qh7=UtSg z5G~8P83n?Vwi7F1rz5!2j`^!54!}=^O;jo<wHXT~I+|NUmA2F|XR5eO1h?v(q5%J# zI9Yz}+jEqQd!<PQQdn^h#{T<F937rcCN{96!bnFq(ZLr%=av~PaE_Zv<@v)J4Ma<? zBEIz*=tl;i!;tBDc{qEx+JeIr5m-9{pqx*0`v~YZ&`d2bw*FnlY$~bwCLWWF;9c2B zHS@N~ak1=O%zk+saOC5RDx?(1nZ_0gNy95wsT_fp6B5nGAE!m2Z{ZP*Xy@0Vpf63h zVXz89oCQV4!x}Ni+AGzpP=Qr)zA{vh6&7Yiuy4InVbP@*2G>V7KnIyEt3A^bD7%c9 zOgZccN^A;^_%gWUDpt9+3c>$D3%~rU?)6*K&qm?8g@>6eJ7wDc2q<U8IIKbA{7Qe- zwo`UWBX0+Kqg@{tHhV3&!x_j9sMXHXL=pVy!^9*+{j^@o6BUI!O2<%kT6}UbDyF1q zmBZR84pvO%<o@L3;y5Ki>LO*~2t>CEhWpQWLWzN@C0Lw5yuNCj$Te-|oGP@InwGPZ z+-yaeV@Gt$`>SNa_tRGMqrEDfBgmhTvu!I!gz#GVopnh!*Y|K5e3ws8ZgwejTfbqa zHpPXM=$x50x&~!jh3tG^AeA-H?qSwGPJpgSg|<do_=E`XXC)CiJNvWhv`Tc&&Xh`0 zZ2(?Y0(p*SrTnQrLK5hs$dFRV&Pgd&5+`D!Nv4)}o34jmOga9UY|1!1)r%;UCuL%Y z^>@LkHM4jzqP(m*jit)<Ep0I7Ff;wMQw|nT`J;_Oc=Skll_uB_?@LKyA=qT|i+ELK zPY)CkAzk??`DO;6a#{|W!j)cNYFT(B9@2>L+9MGw!2>9Y*Nup2qwe8g{mey@<{$Q6 z{Fe{rZl>NFoN)O}9gUUVXCMR3k=IP5H~T;ABfo`w%%n4;A9KG|lPdC&7<w8m*EYm5 zf2Z+`ve<wz#7I;wsyMmVmV2>D;dCzKr9<BNYvc~IcGHgNim(h}PSqZ?iZXiMmp7M} z+MUm0Z7-X@zGBg=Iz><hGo?W*PrWdiVM-{5YOCd<L<%UA3+h@EItlP*$oODl_b9E> zub;*G$hG=&s?ye}f7#%Vy%AIYa^<91L>T*UwtYepYC@yY1{@bf4BL_&vPBvlqxunB zetH<p+#ch4TIDaF*}&W0Y^o}6KYrli&@zR#(WG?<gT)CKPdmDJ#yl=Mx+T!hoic-) zp%C%gQy3ufAyVQOf!|A>o{N{kL**{vdiZidd126fa)0M-`S3FzM_J&A<O_CwHX##3 zWu-4lRTjC^w~bzG`UO=cDzTUnH%!?l5fn<GvO?MCs&n+cZuxuRbP~5{!qFcVuw@0A zj~%S0FxyjsgD7XGdj;T-5u585rpqkMh4i7Xq+Jr(&40HYJ?Fs6!k}4bQA*&jD<V8l z0Em+ac-wToQ3D&o4aKKEXfq$8g>&rq=vgRdaKH+~PrKn5VA!)X6>}I0i;Wug!ht_i zo*yA%S)Ml0rY~bC+xiSqUg&-|@;6+wRgvpOB`s&BevJG-H8+}ldjnQ}wyN|og0X@& z?Zy4YJ?yme@&Wbv`|?s4G6#)1=ct@&BI@zz=2&{vi%GQks$!Lb&Yd?vku;LAKYu~z zbM)8D4Bw@rNVXFkohET2-b(9dXJz1C>pilmSUNIH8LPUc6xWvlTdX8lIZoJubh9}* z41y8m>2qAdpc%!F_*;g2usN$yu*0ez3Ab7ZMOA+$H+@<kBffgL57WHQ(15EUc6F|L zzBQ+g{fx9}osDt#Y~EFwi=l`Yi=FY~c+{I+GAU<#2SxL<$~?oYk)Pzg<KGpSep5vU z)OB9uqoa^(bpOSvB>Qc`$K6~BoVQ#RiV;|LthrJEUB{P59m2A>eWW5l<#;wy-Z0N+ zrdXPo3#EvYBE8q$R<u#PWf$UEPN|@oEK#u)<~f*dWEBnSP#tF1RqBNU=w83&s@qd` z#Sa#!KRo;)Q5F4R_LcP4ly2!nMOawiWr|H>@YE~|XWy+dw1lk)$ycHX*v8uasHJG9 zks@XA7*hy!VjGt2Ey+5%{FaqAS6PE@r8vd1_%43~cremV9{9F32bFAMRbN^LS5O0z z<Yz5OBuYMTzrvVHq0mVqG~-tZUag4Weh=sYJ$X}Uv*Wdp<?Qe2R58rawpH2X=M%G> zH8o}z1UVKqET+9EcGQ^knXIOoWsxmH#8d<|hncI}-x0MO<-IRknO^g4C6Bs**cswy z$Z|T@lbab|*sML0+BfKoI-cCs&u~ncOY1e)e`mD!;0u7ZfrEIN#OZwh!SzINi{nP0 zV}8G=M<)e&or2}O*siMft(i@o`7k*-MYr^y7t8Cyf5$;LM^qa87n)OtZ=*@v{&v(H zQB&khIUV4lx>zebTJ;9XW4U$B8kJZ30kTZB`!r(oVUqJ~O!gda=Q&twki!7|rD@$g z(<h*<W&bmkGcH+`Z$Me!0?CVs9A*Ozxi-AqG%o{G&9-0X!F6}84u$imUzYIApgpk7 z7HZ|AF|VaWtM8TG*IMzs?hjB_D;rjI;zJRIBVS;V7gH*0j?{X(84IOJQA~l^XJT`! zAiYy8O)4>P#_E#j=KDHXEtpc|AUr4_o!Eq~7#Wf%%u{TT)<{I~l_#As0V1CdG5PRs z_+gifOg=0@+jp{jQRHshbZx+LxiegLs3)wf{wC|iUTt6m-coliIY#Wp&c`P8g+q=h zMEmDA$GGLsu`i%=k?S;Rv(V_B81}dhUd<Q6XZMN0)$?B#E3FAmsji!p^Yb@>rNjXu zNI4`!Bh;Gn&o@l)lnR5&JkM$?Z~W6cHozna1|r(OQ)EXW*J}=$RC@D_)Ftb?YjHjN zp}k|!Y$rjr^G(TEEMqm>gJH3oA_uO7gN#Hj#C@$4qnVb)SxuVsR&e03f8aU27Sds% zK<DCgNA%S*c4WXhBJaxleH^dhsuSYRga00F#an$LLw$RS(XaUIM;bO>ql{R;o91bn zXct3Brl9?lYz6R!E}%+2E&gk|1XZSr`Q6y4Qmhe<1}ZWYoZ_Sbv*!V?U%#%N-b?Mi zy(UqHZLSI|9o~sb60{!;YM+j|fE~Jv-_WG3(T*L}-*Ajiv)p;1vQ@F32>kQTS**V= zt;zNFGuk;^fG<mVcGqu@$1z@0vBp=gbzT7bdAzw-T(fuyMtTjJ?Gm43S+_6Od+<b= zac$i-2O;7>5RBjhPfs?yfVman@e_(z261;37TnvX0V~=8g5<?B9)9mE|IxK$q;@;) z2(>U;?Y3~=P^m9i0D{O@S*6v_ok|R*_Z>B1k>6%}<ofE$F(FW4e49e&aNx+j)E?RX z0Qt%H|7Q1-Tu>0;_m<shxykmmJ$d)~4D4*T?#KDm^$;tX;nVE#tODnRa--*<eV&v; z9-hn`g9h>Jva4vbrSI3%!BPdw?l<%0g!axk8^i*WAII{m2@f>x0@a$7=A6Ju4%nv4 z7Opl=S`2~)@{UN~j&K!0-3m8ipj>zKbos1YB8O{M#Cj5XXCHZKmJDjRGq#Y_^nq?y zXR~$@#a3iZsXct}x4u@w{l#K;8Ui^rv`ih=0tDE({XpUHEh@RF!7IT+a0Clg4iyJt zERvz5Kazn6-T8ua7O@=v<jNlCSlD+26hLf;CcDyoIm#wV-N`|FyP6dR+)Z7xYF4PF z;?sJL*7`J|;YPqEG|=nNCG|pI1UrO9QLDjL_|u^C@}K=ANcYaXJGd&EF~<Y9;iFt( zk;%|8<$|ePC%wpzXa?gpmL&D38D?q0ju?e=4#>=c)(p!$UNA*%ewADp&tCY$`7{fV z38gp3)#9n(@E_jVe2cfIliQikkS*?}U*?tk_Jyk5(8D&r@!%n=cFCvD$u}>n{ka3P z87?^dR!1~8QEN)Z1JTmeO*P5_?Agyb*ih|PQe|Y!CkFbRWB<AXmg%&3*ZW==Ucwg7 zS?$w-KrKb2spnlZcRFss`NRFjhI!UgNJU_c_f5(l`U|O<hrBCA<_6}<xlh6yX{<a} z48QbEb(;1TbG8MbUl##N^4OcYHQ4VIGOd*Lxwqm$Gq$ppKk96F$)`$MI!=IP+3Oi3 zL=ERdk5eV$itsf5JK8&-<K{CCx5v6{)Ps^P?Y}AlU&+}~3zTIr%$He7`WkrF9*)l< zqOh9DXlD4%Sl>-wqwm=5Ww+Yk?tIGKX=t|K7L7x>n;2?kp8fK(==SL-mQi}v6he-v ziord=$F=hBS|-8H9+_>^)qIi4K3ggMW!kv$rzKUoWljYc!$n7^Y0Eu#d;8&8hh&1K zN#$H?Q_J7+`D2!WUiH=%Hhk1XxOYfxtJ$*IrQ?IAH;vohhYPtm;$Gh-e153#_<Ir} zmI_gNkQZT`v<~~i_rkJyuFSA%hmI){!aG5ozK}yN88$DRMwJuyt6eh1@t}Lh7qls; zXG9CH3Xu<B1={Vj8H)0~mFae)##Y~Tcl`HuG)WP5%ro)n<V&Gnhu_%77V6j2|2K0T zhyQfue~$=^;tem9S5hXp<p|FO3A0Z*lNjF-2vBGzX>3FOa9_eNE`P`Et<IUzxZ@RN zn{B7+HiAqaOTD*`XW*u1nI8OO8x}1=UmHA!&hjogBJ!@(MZUJ1t(tK*x=c}@Z8@1Y z*yG|KkDG_|bTCv~G@4#mRb)$!ft~LieM)m?rM|g;GI&r$(q^5EWW(k&@(K5_Sl-97 zRwRpWQU_K^Q`w=mN7f3NAIp#po3R1TebOGU=!8t}MF88C6=6o5JhriqYf)G_Y`iZB zqOEAp4@c8X^7{X?-T(IXf1;22u8yku?le;hghUYZg9bCOA*zeV+`b2xaCq;EF~xG$ z3Q+i3R~Oo|43?lEpIFu@1)Z!+Fp3JjZ)RUH(sxs`ZZI}o#9uMJ$3C@|2X|KVT|WPc z0Gv$R-**lSbosU~Qd2z!**iP7wv^~+Ri%H`|IjM$?^4k*P&0-tCuaZ6Y}{ND-0^NI zTwF28=N#XS+{2dZmracnA=ecD-F6A?;BN+kWnR5N$J|R|+uZf59~pf_|DRcx6@jA{ zFLzV#m<+tR0=9O-+CRKF%Pa)j5rXRV<D|ZXNn8$>h`U-mePa8={`SAX`k(I_IhhnB z0-pz@lap|RW=5DEP`TvwWnnEJp)ZBnQ@|1O-DN3Yd&%K!r)CLwUE!CxE4RFko{KN# zLG0exI47UIj=|7a`N@(Rn%(#KW(Ba3Uv>Q{IMkahYhEXL$b%<?u`06tbX(?K_3FM^ zJ7}X*u*<V%MSRDf4t(^AzLrl4uj-35=oXO|Kr!wq?3GNo?Df&4R~D<>f)hVJso;k@ zb`#fKaY%NBj*!g6mUO6`>6Jd7cKKC`dK7Bw7*O6^2ELq~$-3UhVb8gMFlUN#_w%tW z+>cLu2*FJIz0-S7Eb^+|wS{(;Mbwu4Y-$Dpmqq4_gLK*V^iXF&TOB;sCR+OciC!Uj zsL7Eklo@F_nSCq+N7(Xc!Ax`-Tg`GVI-cf@e=G%}&zV~P`-2iBwm))^8t_GrXzdi3 zbQ87K&m0LE2w}$pL6>Txmoq~Wp_dVrP&FLNoN-^t@(D^VEsFcH&U-TcP>zp*BO%>y zJwkq=Y@*8j>cHJG;!o4j0@jO&$U<hEcG||ch|>>y=1}LecsNCT20Nuf*G#n`^m2fG zwPC@1vDDNWbqg<GE-`1pFPS+U^$r9nY>@espv}4a!aFF2ntd4|+Dq5E#%~9{&F2{l zoi2;#a-S-mcU@)t#Bs0&z&t-*3rr*6kT=NTSp-_0E>ee-K!YG%XXlR!Oq)N$Pv(Et z|DR6`%ENy0z1W{_yive6d`CjBM<nFlF3RCSLN4zoh?rz21pOFK26|W?9MALAwlA38 z?p8Xq=veK(Ia#C*jFA&g{4u}pLsJFoy@1F2>$Pj=5WGxYW?CYTbT#)xJS`sud2f$g zxW}~Lx2u_VKGVEy8JDv0aY#G7+8wj@X+B}j_8IA56CSV@OSz#}eJ;E|u0*O>$k^mk zm1Ft2`s?ES%Db)~iHYt%Aj{folH8@kD0?Pxy$~t{kKiy@jZLOzoMG)elZnKxieWHs z7g3OEJl`D*a>RKd?lM%1-Vk|MBoc%6<Y_Gr(?xx;!91^dwUtoLq>3T|(PGZ*GnaxL z?rLsHQ%|UC<i(&v_Wl39Sv`vWWDHC(B1Zoe#%lk!0~Oca|2T>qsWd((0s%?lp{|;8 zNa!wENM)wqp_08A&KAM|S?wYc)a817IIIsqr-II85LGR^Vz+X#Dy;2Dk?aqC!(wb} zXz_es7Z~{MZn31seZunQa$lyI2WgA^J=MUb)T46++&T(W%Wh*_;0h-jcP)@b{BUpn z>3B|##oS+Rz~-1f2Z3^!pBS*tDe>x}vhe>7gz*f3Xgfzjce_8+Qe>_oE0+y(N(&*r z>SG^*o<`xw7e_*@5R=)nZ+m9po(-;JCa{X;VH-2O?k7|<p!z??L}3sx$lly{f1UdC ztHbXGz9hAbGE4l2{m7(H*9nU;AU3qV{l0Z&Et0)dYF+u>%Su{WNUFG*FHvmBsfK)| zd;tSwP>Ho2VC4LjR>$sf6Wr<im?ME;!mvjvGihiTbR@bT6iUAY(H+{QPjTWvgJ#X| zAAihzO|T4^Z4LSj{UfMWEM^t>=}0eJeF8~Qe~`0Ffo)v@xpKJxI_sZBIQ(2xsL1r| zx8F<Ek$l`!rVtW7B>ayY+YOOn2Gs-3cFV!Av6^C0=#f&D^W$8dx%|#}E7H>0In`0H zrU5w`WQK%ShyI@Yad_Jt^XdPd96%tbe|G4nlj8=MbtC7Jc~6jHQ_zO%V;t)KlF#>} zo9OS?5BYZRk{(1z;RszTnG#?Y@i=q9+;1gJckfzfxx~s;f1zP1j+qU!1od?ij2Q^R zc)wGgAPd)*>$AhyilUyy#QmDt(j-JJx_Kqv@`wFKqi~I%<<0&rBbCSfZ^pNZMsr^* zSM|qIC$LIdRYMjgCou<zIwTD0o;@Q3s3^+m3(I_g_d#%RK1dj=I{HF%JH70h=TXK@ z;CeAT&0>|2y_@>2+^D9>*!@U^V(80DszDLR=#1gZjh)O5Npt+^7ON-4&_g`maqHFM z;5Am%Tl|TtczVeGcd$T}in=x^p9yaaXxY<2&iBT+hYCKmbe3G68aGh(GgfC$PH!fK zqX*X7dVVG1Z2dM@!c3W%<f=Met{-kH8-X7CCWw)-p#*bmh1uHf_~0Vk1Szbc{QY6+ zQ|ot_(^|QGLzWEUSyf}%hv~%E`9ht2AuYfE$Z}tb(@T85?5Jt~d_pzOk6U}QcECel zXPF?msd02x-yR=D6jGrRLo_A6aPSsUJ`Id10pEUclZQp)G~c3zp{KN9(0NFM^mu?R z?{>XIlx(SoxrI$r?P2J)|3=8anC)7(1pqfFB*1Rs@N`GuX8r%QY%(Xu(&I7yV=9nM zzYSvsLo07jSm+_8Z~EsvRIQYBtG65kjE>$`?SwM4$-)ks?WCO&+64tDFx~Ae1)w51 zM@k6F=vr1fk~128q;-SyOpxF!jn$l2wm$U|%7Uk?N(3INT@J(S2>jRhM}J&aKqt;; z-06Bapp$i*t2_SoE2?U9%eKplCYKe}n`JNeYTev3?oSW(Hy3Cd`P?|B2|Z?<CX9+z zLysfPM53E2$XS+I%ln%1z0b748r3nyPycPHG8pz#sW_RTC-di~_?<UG(diiHm^X`2 zk?6eaO-9?!9_JY)e}R1f=Cz^PgxTKzzupf?J&$$Q_uydiVFRfOvO&>7@=ORgf5~4C z#|qTZRR1NV^G6$UX|cJ;^c^E3lM-)_GMH{GE^vOdwtzXs-EL3~_S)#xs;}7VT7!nG zg@y;uqi>W0am4S_#<MbwYC>Bvk8lquA4MISO>r<6{dDfdbC^MIMUhq-{8qw1I=7qQ zR^{IPdcx0_l=Z)4f6~mUw{}$MW}ihY$9FZ+N$H-7W~!Nv-qh6at?lzYz6*K08?`jE zyzjf<&Lpwx=*zBPv2gFoT+<_TP=oI=eR(rq4iUDz_RuF_yE9!^Vpa$~^=F@Zluf_! zo33q4ym>pGwPZhTDKzdV^lzdp-=?VgJW+n5qX>?lr96$F0{Fed6_6evF0RaNTfV;9 zI;O47y_-6S#FD8E;E_M0_}JHRq1EotCnec?{kL#{Z#0jP8#BPiyXR4y4D2YZ@?eZ1 z$*w1h!-2?)j*{oYV4igqF+S2fto0<KJZ23w8Y-S>HZj~gH>Py&C~Y7M!z7yB6NyjL zWK1%=DGb9L;4V(8PNRKE6&%(^gX*9s;yV9sdk<}DS)`|(=(T&cpE^i>5>p7CkscVz zju3ROj*Z`5fQr4M{r*bfLo~?;29;}VD^90iq<^7y%HKIpwOq7P(+c!kCyg*1l;|Bj zC#sd)9W!Psc}bmk_z5&>`?Y-lXuC<P7Wm`roAGTK;EtU98yF>)pIq;e=WKvnJ$Mcr z8*d8$P^p*X&9c5$ArUc5>{Cu9WOjzQ%wC}G1P|!Q+VFVl#rr;;d-I}AwEb-9*YPI& z;7rZ(eKpA9oKYzBRrPD?+lG0oQZu`2?do`qY_(C<F~(Ej8p~xyGJ!5o-mqzdHHiYO zKtp9>IP6PBM>juMX9P!?5a+q`;BX>0Iyx9O!}|({Rhj$G8YD=y0Iom7Ix>qBRtVPr z8Y7s401Gf5<5<1<;-4J2cFq0Z&}5qRr6>4cL){d8pM{<V-Ae3-8MqOalOW0@Ft9pY zTg?oZ3q+w=LoN5UvRcl<MefjQ9gJ~#{3=#7(`5sp8CD5pFNp$}K6y%pCU=u+vwflw zX9kM6W<5Lvshh%7Dgq}0E`O#|vA*XhFTC^A$SGzJLCNCaX(G1{iHWgarhw5+m<6H; zjL&HLW+3E28(L*)1<l1)X3gly3>BGkR&^2q`obUXcn0@QFQ4(&cBQX{vr#nN1KANL zlMw|r(hN}yZ+GooFMvGS&<@6NR@eEk)}|s8<Yo=5_nn-*t@gS;=h*GQvX?a<hg%%i zr;!^sxxYr=&TG^RyN)J8zy7@vrS59+zhO*v9NSp6XI!(9X?Dr}<CsB9%aU#R0_Obk zX;*-Hj6+{(!Vb7loUKk%Umcx{A&b$YNK4^IdOqX}XZSrc@}*LJ@W_Ixb^4JeV^3$b zQfD&D!+tPbSqrwL;J&gk>U)sSps~=c3CaD6Qa$X3enA&XV`%&#JY#g8qODL;5z%U_ z66gOa-y|QN0#Uiy3#+1-|6XLuGpC8umOA(cqc3YL#6nQXbf8EN&E5>VA2sWYMTe(_ zv)7yf5d`U$P|*C|iRZwiy)#yR)V5-Z7gMRy<sr){r{p|WexBk^`<luj_1-TocB@R* ziz&F7mdvRn_T%Bp0sWccY{3)j)vT_2#CdF>J9K@Iujk`fbpF2<>czntg%gHs(OhQc zB!?#F$HpOTD>2&Cz)Pm3$Cxk|`DotIWyobVgd5t3)M#)K$+2!=5Z<pc=_JeAkdCi} z3vhjP>B&&7<+coB&le08;`>c6*hSprd6vNM?klla!xy|}o>M229Wh-Sy-xc5MEv5Y zM_qv~Q1$#;mvC2SL7GgZbpoDR*zH$QY$x%HPlzICd}rjUQFjbcPzHW>0-=3>#$q)i zP6#45$~oSfuDTg5Qrx;Yj}78myqasxXAs0p`Y^}KWsg#T(60QI=z?7Wk0ikw_o`=R zqunzKgRoR{guiQ=fmB>5K9|IBm~-$aBuR>To#6ymDTKM8-*^Mz0Q_pW`N>YJmqhSw z7-lhB=67w>c9l~TbTa;H2k+fl`Pa2dY#uUAE1)sQdVS-)>FWg$XtGo(Vah8i9yStp z>K;|b%Ej_iWnPsQ$|8$XhlRQ+evw!)rpIaV&=dp!=v`@od*$LwqDXhA-PK@AYoXVD z!XjywI%f%^4m3OP7m_EeJ4v6^mq#I^A;Pcu_iL>pOh9v!jwBe-1tkU?6oXCG=ZgKY zZX)t$-`txZaSMi~!d>goFGz!x`SN*O(*xRraSws{gQ`7;PAYXAcoKZ16m<v}&#k(C z5q|@&v=++j!M(l;n7liKBfr*!yhE;ZzO~<5VLK~pZ(jN1Nhb;NSbzvk&evbkTedgQ zn$mh}+Bf)bT<O(t%SN~AIV3hpR-{F~5{keO{~Zv}?^`}kobts-K!A!^0X7$3F}dT- zgIBt9*()XVCK|7E#n^|jx<c=xaEr&ot9%CLNU;d}Mzi@1ZCN(z$cu9hDiEP|M6@cJ zh@~*_o?|YuF2!1mc6zslL#$Za*}%#h`vn0#8g9={KsDj2VtHmyc%hZ6-QXL~Y`Jtf z9&fa{(VqozJH$+{nyMOeF(Z|c6qjV$am~duZU&}+fc|C;9z6*P+|t9@e{opyx<hC~ z*7;OsalnX(>bDFkO#Im#708G_XdMq`mQD#RbqcL)(dLYGLAA<!F5yh9*ySc^3Z}|O z4qYCl%2~2-4*R(`Kp_em6PJ;|nUI!+33X=5VF<;kcvg<8IF*@`qtJV52`#cipao|o z#hFr!nbEKTzFeXHC<>=w7SeV&95AaeE59CK{+=`WXOI5V#}Vxu4Rd-rl~5h*@K$+g z(~%o%Hm(@CW_{jy)n!$|-#FV!Y}AzAjdA!ToBDjHW_g6JG{??<6vx;tTvyq@P<H~3 zqNYlZ1bQ1QL|po>qXp8PcXU1eI(eGB&wM%|NqD+qq<Xx1x{i@dAP~wkoTOG8aIH=$ ze9yYY#g^<^r^{n-??tK~eTky(qeo*ithVX$a{=&Or8F6Tr^Ml*co#MzA4jdM#7AAk zL{crSsbpQC`xajtzMqwr)z7w8pw5R^^8VibdVQ5St_KUDsg!O#anTq<wN3`Mo>SU@ zVouk#w8HL|*Y@Rd(Q|loRK9a{7-@3E{*wK#<1f&%$q#@d+(KeY#qd-crYKS?6jO&y zd`m9K-^yv<x!O2|!-}66tqsEM{3b8aju=al2ZObRCd&ro#4GN(Ura=h^HD-Uu+89M fd*kV0<4I=tBs9xK+W+-4)JNrwred|c)rbED2N0!5 literal 0 HcmV?d00001 diff --git a/examples/python3/tutorial/formation/chiba/timerreset.py b/examples/python3/tutorial/formation/chiba/timerreset.py new file mode 100644 index 00000000..104fc2b7 --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/timerreset.py @@ -0,0 +1,100 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- +import Sofa.Core +import Sofa.constants.Key as Key +import math +import numpy as np +import pandas as pd +import csv +import sys +import os +path=os.path.dirname(os.path.abspath(__file__))+'/data/' +class FingerController(Sofa.Core.Controller): + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, args, kwargs) + self.node = args[0] + self.fingerNode = self.node.getChild('finger') + self.pressureConstraint = self.fingerNode.cavity.getObject('SurfacePressureConstraint')#air chamber pressure + self.trackers = self.fingerNode.tracker.getObject('DOF') # trackers + #self.timestep=0 #for measuring the time elapsed during each step + self.MechanicalObject=self.fingerNode.getObject('tetras') + self.counter=0 #iteration counter + self.data=[] #pressure time angle data + self.totaltime=0.0 #total time elapsed + self.springs=self.fingerNode.hitching.getObject('springs') + #self.springs.spring.value.value[0].Ks=1000 + self.Ks=0 + print(self.data) + + + def onAnimateBeginEvent(self, event): # called at each begin of animation step + stepsize=2 #how many seconds per step + steps=27 #number of steps per iteration + totaliterations=1 #total number of iterations + self.totaltime=self.node.findData("time").value-self.counter*steps*stepsize + i=0 + if self.totaltime>=steps*stepsize and self.counter<=(totaliterations-1): + self.totaltime=0.0 + self.MechanicalObject.reset() + pressureValue=0.0 + self.pressureConstraint.value = [pressureValue] + pd.DataFrame(self.data).to_csv(path+'sofaangle'+str(self.counter)+'.csv') + self.data=[] + self.counter=self.counter+1 + #self.springs.stiffness.value=self.Ks+delta*self.counter + self.trackers.reset() + print(self.data) + #print(angle) + print(self.counter) + print("new iteration") + i=1 + + if self.totaltime==0.0: + print("start") + self.timestep=0 + #print(self.timestep) + pressureValue = self.pressureConstraint.value.value[0] + if self.totaltime<=steps*stepsize and self.counter<=totaliterations: + if self.totaltime-self.timestep>=stepsize : + pressureValue+=0.05 + #print("step") + #print(pressureValue) + self.timestep=self.totaltime + if pressureValue>1.3: + pressureValue=1.3 + #print("max pressure") + #print(self.node.findData("time").value) + self.pressureConstraint.value = [pressureValue] + position=self.trackers.findData('position').value + record=position + vector_1=[1,0] + x1=position[0][0] + z1=position[0][1] + y1=position[0][2] + x2=position[1][0] + z2=position[1][1] + y2=position[1][2] + vector_2=[x2-x1,y2-y1] + unit_vector_1 = vector_1 / np.linalg.norm(vector_1) + unit_vector_2 = vector_2 / np.linalg.norm(vector_2) + dot_product = np.dot(unit_vector_1, unit_vector_2) + angle = np.arccos(dot_product) + angle=math.degrees(angle) + if i == 1: + angle=0 + print(angle, ' angle reset') + self.data.append([pressureValue,self.totaltime,angle,x1,y1,z1,x2,y2,z2]) + #print(self.totaltime) + if self.counter>totaliterations: + pd.DataFrame(self.data).to_csv('sofaangle'+str(self.Ks)+'Ks.csv') + #print(self.counter) + #print("FINISHED") + return + + + + + + + + diff --git a/examples/python3/tutorial/formation/chiba/tutorial_chiba.md b/examples/python3/tutorial/formation/chiba/tutorial_chiba.md new file mode 100644 index 00000000..94a1d1be --- /dev/null +++ b/examples/python3/tutorial/formation/chiba/tutorial_chiba.md @@ -0,0 +1,71 @@ + +**Title:** Tutorial on Combining Deformable Models for Soft Robot Simulation + +**Duration:** This tutorial can vary in duration based on the depth and complexity of the material, but a typical plan could span 2-4 hours. + +**Target Audience:** Researchers, engineers, and students interested in soft robotics and the simulation of deformable robots. + +**Prerequisites:** Participants should have a basic understanding of robotics, mechanics, and computer simulations. Knowledge of finite element methods (FEM) and rigid body dynamics can be helpful. + +**Tutorial Outline:** + +**1. [[../docs/text/Introduction]]** + - Briefly introduce the field of soft robotics. + - Explain the motivation for combining FEM and DCM models. + +**2. [[../docs/text/Background Concepts]]** + - An overview of Discrete Cosserat Model (DCM) and their relevance in soft robotics. + - Finite Element Methods (FEM) and their use in simulating deformable structures ? + - The concept of compliance matrices and their role in soft robot modeling ? + +**3. [[../docs/text/Setting up the Environment]]** + - The software tools and libraries used (SOFA, **Cosserat** plugin). + - Instructions for setting up the simulation environment. + +**4. [[../docs/text/Direct Simulation]]** + - The direct simulation of a soft robot (e.g., the gripper example from the paper). + - How to create the DCM model for cables and integrate it with FEM for the soft body ? + - **Discussion** : the role of constraints, friction, and contact forces. + +--- +**5. [[../docs/text/Inverse Simulation]]** + - Demonstrate an inverse simulation for soft robots (e.g., using the soft finger or tentacle as examples). + - Explain how to compute actuation values to achieve desired end-effector positions. + - Discuss the handling of sliding constraints in the inverse problem. + +--- +**6. [[../docs/text/Model Convergence and Sensitivity Analysis]]** + - Here we will share insights on how to evaluate the convergence of your model with varying parameters + - e.g., number of sections defining a cable + - Discuss sensitivity to material properties and other simulation parameters. + +--- + +**7. [[../docs/text/Advanced Topics and Future Work]]** + - Explore potential applications of your method in soft robot design. + - Discuss the ongoing and future research in this field, including real-world experiments and stress validation on cables. +--- + +**8. Performance Optimization** + - How to **optimize the computation speed**, potentially using **parallelization**, model **order reduction**, or **recursive algorithms** for DCM. +--- +**9. Conclusion and Q&A** + - Summarize key takeaways from the tutorial. + - Open the floor for questions and discussions. +--- +**10. Practical Hands-On Session (Optional)** + - If feasible, you can provide participants with exercises or hands-on practice to apply the concepts learned. + +--- +**Materials:** +- Presentation slides (see GitHub Repo) +- Repo folder tutorials. +- Code examples and simulations on the Repo/example. +- Reference: + - Paper RAL-SoRo : + - Paper (Féderico) : + - Paper (Flavie) : +- Q&A session for participant engagement. +- Feedback : direct and mails +--- + diff --git a/git b/git new file mode 100644 index 00000000..e69de29b diff --git a/log b/log new file mode 100644 index 00000000..e69de29b diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.h b/src/Cosserat/forcefield/BeamHookeLawForceField.h index ff0c57f2..67a09038 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.h @@ -137,6 +137,7 @@ public : Data<Real> d_GA; Data<Real> d_EA; Data<Real> d_EI; + Data<bool> d_buildTorsion; bool compute_df; Mat33 m_K_section; diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.inl b/src/Cosserat/forcefield/BeamHookeLawForceField.inl index 4efb7588..fb40bf1b 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.inl @@ -76,7 +76,9 @@ namespace sofa::component::forcefield d_GI(initData(&d_GI, "GI", "The inertia parameter, GI")), d_GA(initData(&d_GA, "GA", "The inertia parameter, GA")), d_EA(initData(&d_EA, "EA", "The inertia parameter, EA")), - d_EI(initData(&d_EI, "EI", "The inertia parameter, EI")) + d_EI(initData(&d_EI, "EI", "The inertia parameter, EI")), + d_buildTorsion(initData(&d_buildTorsion, true,"build_torsion", "build torsion or the elongation of the beam ?")) + { compute_df=true; } @@ -93,11 +95,11 @@ namespace sofa::component::forcefield reinit(); } - /*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties - related to the cross-section of the beams. It calculates the area moment of inertia (Iy and Iz), - the polar moment of inertia (J), and the cross-sectional area (A). - These calculations depend on the chosen cross-section shape, either circular or rectangular. T - he formulas used for these calculations are based on standard equations for these properties.*/ + /*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties + related to the cross-section of the beams. It calculates the area moment of inertia (Iy and Iz), + the polar moment of inertia (J), and the cross-sectional area (A). + These calculations depend on the chosen cross-section shape, either circular or rectangular. + The formulas used for these calculations are based on standard equations for these properties.*/ template<typename DataTypes> void BeamHookeLawForceField<DataTypes>::reinit() { @@ -113,8 +115,8 @@ namespace sofa::component::forcefield Iy = LyLzLzLz / 12.0; Iz = LzLyLyLy / 12.0; - J = Iy + Iz; - A = Ly * Lz; + J = Iy + Iz; + A = Ly * Lz; } else //circular cross-section @@ -134,46 +136,27 @@ namespace sofa::component::forcefield } m_crossSectionArea = A; - if(!d_variantSections.getValue()) + if(d_variantSections.getValue()) { - if(!d_useInertiaParams.getValue()) - { - Real E = d_youngModulus.getValue(); - Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); - - m_K_section[0][0] = G*J; - m_K_section[1][1] = E*Iy; - m_K_section[2][2] = E*Iz; - } - else - { - msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation " - "of the stiffness matrix."; - m_K_section[0][0] = d_GI.getValue(); - m_K_section[1][1] = d_EI.getValue(); - m_K_section[2][2] = d_EI.getValue(); - } - - }else { - /*If the d_variantSections flag is set to true, it implies that multi-section beams are used for - the simulation. In this case, the code calculates and initializes a list of stiffness matrices - (m_K_sectionList) for each section. The properties of each section, such as Young's modulus and + /*If the d_variantSections flag is set to true, it implies that multi-section beams are used for + the simulation. In this case, the code calculates and initializes a list of stiffness matrices + (m_K_sectionList) for each section. The properties of each section, such as Young's modulus and Poisson's ratio, are specified in the d_youngModulusList and d_poissonRatioList data.*/ msg_info("BeamHookeLawForceField")<< "Multi section beam are used for the simulation!"; m_K_sectionList.clear(); - + const size_t szL = d_length.getValue().size(); if((szL != d_poissonRatioList.getValue().size())||(szL != d_youngModulusList.getValue().size())){ msg_error("BeamHookeLawForceField")<< "Please the size of the data length, youngModulusList and " - "poissonRatioList should be the same !"; + "poissonRatioList should be the same !"; return; } - /*Stiffness Matrix Initialization: Next, the code initializes the stiffness matrix m_K_section - based on the properties of the cross-section and the material's Young's modulus (E) and - Poisson's ratio. The stiffness matrix is essential for computing forces and simulating beam + /*Stiffness Matrix Initialization: Next, the code initializes the stiffness matrix m_K_section + based on the properties of the cross-section and the material's Young's modulus (E) and + Poisson's ratio. The stiffness matrix is essential for computing forces and simulating beam behavior.*/ for(size_t k=0; k<szL; k++) { @@ -181,14 +164,50 @@ namespace sofa::component::forcefield Real E = d_youngModulusList.getValue()[k]; Real G = E/(2.0*(1.0+d_poissonRatioList.getValue()[k])); + + _m_K_section[0][0] = G*J; _m_K_section[1][1] = E*Iy; _m_K_section[2][2] = E*Iz; m_K_sectionList.push_back(_m_K_section); } msg_info("BeamHookeLawForceField")<< "If you plan to use a multi section beam with (different " - "mechanical properties) and pre-calculated inertia parameters " - "(GI, GA, etc.), this is not yet supported."; + "mechanical properties) and pre-calculated inertia parameters " + "(GI, GA, etc.), this is not yet supported."; + + }else + { + if( d_useInertiaParams.getValue() ) + { + msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; + m_K_section[0][0] = d_GI.getValue(); + m_K_section[1][1] = d_EI.getValue(); + m_K_section[2][2] = d_EI.getValue(); + } + else + { + //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix + if (d_buildTorsion.getValue()){ + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); + m_K_section[0][0] = G*J; + m_K_section[1][1] = E*Iy; + m_K_section[2][2] = E*Iz; + }else { + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); + //Translational Stiffness (X, Y, Z directions): + // Gs * I(i): Shearing modulus times the second moment of the area (torsional stiffness). + // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). + m_K_section[1][1] = E * Iy; + m_K_section[2][2] = E * Iz; + + //Rotational Stiffness (X, Y, Z directions): + //E * A: Young's modulus times the cross-sectional area (axial stiffness). + //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). + m_K_section[0][0] = E * A; + } + } } } diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 69c78d65..4cec9bd0 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -152,6 +152,19 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject void reinit() override; void draw(const core::visual::VisualParams* vparams) override; + double computeTheta(const double &x, const Mat4x4 &gX){ + double Tr_gx = 0.0; + for (int i = 0; i<4; i++) { + Tr_gx += gX[i][i]; + } + + double theta; + if( x <= std::numeric_limits<double>::epsilon()) theta = 0.0; + else theta = (1.0/x) * std::acos((Tr_gx/2.0) -1); + + return theta; + } + protected: /**********************COSSERAT METHODS**************************/ void computeExponentialSE3(const double &x, const type::Vec3& k, Transform & Trans); @@ -165,18 +178,7 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject [[maybe_unused]] type::Vec6 compute_eta(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); type::Matrix4 computeLogarithm(const double & x, const Mat4x4 &gX); - double computeTheta(const double &x, const Mat4x4 &gX){ - double Tr_gx = 0.0; - for (int i = 0; i<4; i++) { - Tr_gx += gX[i][i]; - } - double theta; - if( x <= std::numeric_limits<double>::epsilon()) theta = 0.0; - else theta = (1.0/x) * std::acos((Tr_gx/2.0) -1); - - return theta; - } public: diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index f8ec5a2d..3d821918 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -133,12 +133,12 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3(const In1VecCoord & i m_nodesLogarithmeSE3Vectors.clear(); const unsigned int sz = curv_abs_frames.size(); - //Compute exponential at frame points + //Compute exponential at each frame point for (size_t i = 0; i < sz; i++) { Transform T ; - const type::Vec3 k = inDeform[m_indicesVectors[i]-1]; - const double x = m_framesLengthVectors[i]; + const type::Vec3 k = inDeform[m_indicesVectors[i]-1]; //Cosserat reduce coordinates + const double x = m_framesLengthVectors[i]; // The distance between the frame and the closest beam node toward the base computeExponentialSE3(x,k,T); m_framesExponentialSE3Vectors.push_back(T); @@ -149,8 +149,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3(const In1VecCoord & i } } - //Compute the exponential at the nodes - + //Compute the exponential on the nodes m_nodesExponentialSE3Vectors.push_back(Transform(type::Vec3(0.0,0.0,0.0),type::Quat(0.,0.,0.,1.))); for (unsigned int j = 0; j < inDeform.size(); j++) { @@ -386,28 +385,32 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() size_t input_index = 1; + for (size_t i=0; i < sz; i++) { if (curv_abs_section[input_index] > curv_abs_frames[i]) { - m_indicesVectors.push_back(input_index); - m_indicesVectorsDraw.push_back(input_index); // maybe I shouldn't do this here !!! + m_indicesVectors.emplace_back(input_index); + m_indicesVectorsDraw.emplace_back(input_index); // maybe I shouldn't do this here !!! } else if(curv_abs_section[input_index] == curv_abs_frames[i]){ - m_indicesVectors.push_back(input_index); + m_indicesVectors.emplace_back(input_index); input_index++; - m_indicesVectorsDraw.push_back(input_index); + m_indicesVectorsDraw.emplace_back(input_index); + + } else { input_index++; - m_indicesVectors.push_back(input_index); - m_indicesVectorsDraw.push_back(input_index); + m_indicesVectors.emplace_back(input_index); + m_indicesVectorsDraw.emplace_back(input_index); } //Fill the vector m_framesLengthVectors with the distance //between frame(output) and the closest beam node toward the base - m_framesLengthVectors.push_back(curv_abs_frames[i] - curv_abs_section[m_indicesVectors[i] - 1]); + //m_framesLengthVectors.push_back(curv_abs_frames[i] - curv_abs_section[m_indicesVectors[i] - 1]); + m_framesLengthVectors.emplace_back(curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); } for (size_t j = 0; j < curv_abs_section.size() - 1; j++) { - m_BeamLengthVectors.push_back(curv_abs_section[j + 1] - curv_abs_section[j]); + m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); } if(d_debug.getValue()){ diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 58b2e5c3..9508b5a2 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -66,9 +66,9 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu /// Output Model Type typedef TOut Out; typedef typename In2::Coord::value_type Real1; - typedef typename In1::Coord Coord1; + typedef typename In1::Coord Coord1; typedef typename In1::Deriv Deriv1; - typedef typename In1::VecCoord In1VecCoord; + typedef typename In1::VecCoord In1VecCoord; typedef typename In1::VecDeriv In1VecDeriv; typedef typename In1::MatrixDeriv In1MatrixDeriv; typedef Data<In1VecCoord> In1DataVecCoord; @@ -140,6 +140,7 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu using BaseCosserat<TIn1, TIn2, TOut>::m_nodeAdjointVectors; using BaseCosserat<TIn1, TIn2, TOut>::m_index_input; using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectorsDraw; + using BaseCosserat<TIn1, TIn2, TOut>::computeTheta; protected: /// Constructor @@ -178,6 +179,7 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) override; void computeBBox(const core::ExecParams* params, bool onlyVisible) override; + void computeLogarithm(const double & x, const Matrix4 &gX, Matrix4 &log_gX); protected: helper::ColorMap m_colorMap; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index d89c3fb9..c1a92b62 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -82,7 +82,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() { - m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion and bending), in local frame + m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion or elongation and bending), in local frame m_fromModel2 = this->getFromModels2()[0]; // Cosserat base, in global frame m_toModel = this->getToModels()[0]; // Cosserat rigid frames, in global frame @@ -90,7 +90,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() const OutDataVecCoord* xFromData = m_toModel->read(core::ConstVecCoordId::position()); const OutVecCoord xFrom = xFromData->getValue(); - m_vecTransform.clear(); + m_vecTransform.clear(); // initialise with the rigids frames for (unsigned int i = 0; i < xFrom.size(); i++) { m_vecTransform.push_back(xFrom[i]); } @@ -142,34 +142,32 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( } -//template <class TIn1, class TIn2, class TOut> -//Matrix4 DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double & x, const defaulttype::Matrix4 &gX){ - -// // Compute theta before everything -// const double theta = computeTheta(x, gX); -// Matrix4 I4; I4.clear(); I4.identity(); -// Matrix4 log_gX; log_gX.clear(); - - -// double csc_theta = 1.0/(sin(x * theta/2.0)); -// double sec_theta = 1.0/(cos(x * theta/2.0)); -// double cst = (1.0/8) * (csc_theta*csc_theta*csc_theta) * sec_theta; -// double x_theta = x*theta; -// double cos_2Xtheta = cos(2.0 * x_theta); -// double cos_Xtheta = cos(x_theta); -// double sin_2Xtheta = sin(2.0 *x_theta); -// double sin_Xtheta = sin(x_theta); - -// if(theta <= std::numeric_limits<double>::epsilon()) log_gX = I4; -// else { -// log_gX = cst * ((x_theta*cos_2Xtheta - sin_Xtheta)*I4 - -// (x_theta*cos_Xtheta + 2.0*x_theta*cos_2Xtheta - sin_Xtheta -sin_2Xtheta)*gX + -// (2.0*x_theta*cos_Xtheta + x_theta*cos_2Xtheta-sin_Xtheta - sin_2Xtheta) *(gX*gX)- -// (x_theta*cos_Xtheta - sin_Xtheta)*(gX*gX*gX)); -// } - -// return log_gX; -//} +template <class TIn1, class TIn2, class TOut> +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double & x, const Matrix4 &gX, Matrix4 &log_gX){ + + // Compute theta before everything + double theta = computeTheta(x, gX); + Matrix4 I4; I4.clear(); I4.identity(); + log_gX.clear(); + + + double csc_theta = 1.0/(sin(x * theta/2.0)); + double sec_theta = 1.0/(cos(x * theta/2.0)); + double cst = (1.0/8) * (csc_theta*csc_theta*csc_theta) * sec_theta; + double x_theta = x*theta; + double cos_2Xtheta = cos(2.0 * x_theta); + double cos_Xtheta = cos(x_theta); + double sin_2Xtheta = sin(2.0 *x_theta); + double sin_Xtheta = sin(x_theta); + + if(theta <= std::numeric_limits<double>::epsilon()) log_gX = I4; + else { + log_gX = cst * ((x_theta*cos_2Xtheta - sin_Xtheta)*I4 - + (x_theta*cos_Xtheta + 2.0*x_theta*cos_2Xtheta - sin_Xtheta -sin_2Xtheta)*gX + + (2.0*x_theta*cos_Xtheta + x_theta*cos_2Xtheta-sin_Xtheta - sin_2Xtheta) *(gX*gX)- + (x_theta*cos_Xtheta - sin_Xtheta)*(gX*gX*gX)); + } +} //template<class In1VecCoord, class Mat6x6> //void computeViolation(In1VecCoord& inDeform, const helper::vector<double> m_framesLengthVectors, const From e2a755ecd55a12da651e02f1ad4294eca7d87e48 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 1 Dec 2023 14:06:18 +0100 Subject: [PATCH 23/71] Enhanced the implementation to consider beam elongation, marking a significant stride towards a more sophisticated version of the code. This advancement lays the groundwork for defining beams with variable strain dimensions, ranging from 2 to 6, in future iterations of the code. --- docs/testScene/tuto_4.py | 28 +- .../forcefield/BeamHookeLawForceField.cpp | 154 +++++++- .../forcefield/BeamHookeLawForceField.h | 30 +- .../forcefield/BeamHookeLawForceField.inl | 61 ++-- src/Cosserat/mapping/BaseCosserat.cpp | 92 ++++- src/Cosserat/mapping/BaseCosserat.h | 41 ++- src/Cosserat/mapping/BaseCosserat.inl | 177 ++++----- .../mapping/DiscreteCosseratMapping.cpp | 341 +++++++++++++++++- .../mapping/DiscreteCosseratMapping.h | 1 + .../mapping/DiscreteCosseratMapping.inl | 73 ++-- .../DiscreteDynamicCosseratMapping.inl | 2 +- 11 files changed, 801 insertions(+), 199 deletions(-) diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py index d1200b99..319d8d43 100644 --- a/docs/testScene/tuto_4.py +++ b/docs/testScene/tuto_4.py @@ -27,7 +27,6 @@ force_null = [0., 0., 0., 0., 0., 0.] # N - class ForceController(Sofa.Core.Controller): def __init__(self, *args, **kwargs): Sofa.Core.Controller.__init__(self, *args, **kwargs) @@ -40,33 +39,36 @@ def __init__(self, *args, **kwargs): self.applyForce = True self.forceCoeff = 0. self.theta = 0.1 + self.incremental = 0.01 def onAnimateEndEvent(self, event): if self.applyForce: - self.forceCoeff += 0.01 + self.forceCoeff += self.incremental else: - self.forceCoeff -= 0.01 + self.forceCoeff -= self.incremental # choose the type of force if self.force_type == 1: - print('inside force type 1') + # print('inside force type 1') + self.incremental = 0.1 self.compute_force() elif self.force_type == 2: + self.incremental = 0.4 self.compute_orthogonal_force() elif self.force_type == 3: self.rotate_force() def compute_force(self): with self.forceNode.forces.writeable() as force: - vec = [0., 0., 0., - 0., self.forceCoeff/sqrt(2), self.forceCoeff/sqrt(2)] + vec = [0., 0., 0., 0., self.forceCoeff/sqrt(2), self.forceCoeff/sqrt(2)] for i, v in enumerate(vec): force[0][i] = v def compute_orthogonal_force(self): position = self.frames.position[self.size] # get the last rigid of the cosserat frame orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation - # Calculate the direction of the force in order to remain orthogonal to the x axis of the last frame of the beam. + # Calculate the direction of the force in order to remain orthogonal to the x_axis + # of the last frame of the beam. with self.forceNode.forces.writeable() as force: vec = orientation.rotate([0., self.forceCoeff * 5.e-2, 0.]) # vec.normalize() @@ -93,6 +95,8 @@ def onKeypressedEvent(self, event): self.applyForce = False +controller_type = 2 + def createScene(root_node): addHeader(root_node) root_node.gravity = [0, 0., 0.] @@ -112,11 +116,11 @@ def createScene(root_node): controller_state = tip_controller.addObject('MechanicalObject', template='Rigid3d', name="controlEndEffector", showObjectScale=0.3, position=[geoParams.beamLength, 0, 0, 0, 0, 0, 1], showObject=True) + if controller_type == 3: + cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=0., angularStiffness=1.e8, + external_points=0, external_rest_shape=controller_state.getLinkPath(), + points=geoParams.nbFrames, template="Rigid3d") - cosserat_frames.addObject('RestShapeSpringsForceField', name='spring', stiffness=0., angularStiffness=1.e8, - external_points=0, external_rest_shape=controller_state.getLinkPath(), - points=geoParams.nbFrames, template="Rigid3d") - - solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=3, tip_controller=controller_state)) + solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=controller_type, tip_controller=controller_state)) return root_node diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp index 64281a3e..698e22cf 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp @@ -27,24 +27,163 @@ * Contact information: https://project.inria.fr/softrobot/contact/ * * * ******************************************************************************/ -#define SOFA_COSSERAT_CPP_BeamHookeLawForceField +#define SOFA_COSSERAT_BEAMHOOKELAWFORCEFIELD_CPP #include "BeamHookeLawForceField.inl" #include <sofa/core/ObjectFactory.h> +using namespace sofa::defaulttype; + namespace sofa::component::forcefield { +template<> +void BeamHookeLawForceField<defaulttype::Vec6fTypes>::reinit() +{ + // Precompute and store values + Real Iy, Iz, J, A; + if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section + { + Real Ly = d_lengthY.getValue(); + Real Lz = d_lengthZ.getValue(); + + const Real LyLzLzLz = Ly * Lz * Lz * Lz; + const Real LzLyLyLy = Lz * Ly * Ly * Ly; + + Iy = LyLzLzLz / 12.0; + Iz = LzLyLyLy / 12.0; + J = Iy + Iz; + A = Ly * Lz; + + } + else //circular cross-section + { + msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; + + Real r = d_radius.getValue(); + Real rInner = d_innerRadius.getValue(); + const Real r4 = r * r * r * r; + const Real rInner4 = rInner * rInner * rInner * rInner; + + Iy = M_PI * (r4 - rInner4) / 4.0; + Iz = Iy; + J = Iy + Iz; + A = M_PI * (r * r - rInner4); + + } + m_crossSectionArea = A; + + if( d_useInertiaParams.getValue() ) + { + msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; + m_K_section66[0][0] = d_GI.getValue(); + m_K_section66[1][1] = d_EIy.getValue(); + m_K_section66[2][2] = d_EIz.getValue(); + m_K_section66[3][3] = d_EA.getValue(); + m_K_section66[4][4] = d_GA.getValue(); + m_K_section66[5][5] = d_GA.getValue(); + } + else + { + //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); + //Translational Stiffness (X, Y, Z directions): + // Gs * J(i): Shearing modulus times the second moment of the area (torsional stiffness). + // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). + m_K_section66[0][0] = G*J; + m_K_section66[1][1] = E*Iy; + m_K_section66[2][2] = E*Iz; + //Rotational Stiffness (X, Y, Z directions): + //E * A: Young's modulus times the cross-sectional area (axial stiffness). + //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). + m_K_section66[3][3] = E*A; + m_K_section66[4][4] = G*A; + m_K_section66[5][5] = G*A; + } +} + + +template<> +void BeamHookeLawForceField<defaulttype::Vec6fTypes>::addForce(const MechanicalParams* mparams, + DataVecDeriv& d_f, + const DataVecCoord& d_x, + const DataVecDeriv& d_v) +{ + SOFA_UNUSED(d_v); + SOFA_UNUSED(mparams); + + if(!this->getMState()) { + msg_info("BeamHookeLawForceField") << "No Mechanical State found, no force will be computed..." << "\n"; + compute_df=false; + return; + } + VecDeriv& f = *d_f.beginEdit(); + const VecCoord& x = d_x.getValue(); + // get the rest position (for non straight shape) + const VecCoord& x0 = this->mstate->read(VecCoordId::restPosition())->getValue(); + + f.resize(x.size()); + unsigned int sz = d_length.getValue().size(); + if(x.size()!= sz){ + msg_warning("BeamHookeLawForceField")<<" length : "<< sz <<"should have the same size as x... "<< x.size() <<"\n"; + compute_df = false; + return; + } + for (unsigned int i=0; i<x.size(); i++) + f[i] -= (m_K_section66 * (x[i] - x0[i])) * d_length.getValue()[i]; + + d_f.endEdit(); + +} + +template<> +void BeamHookeLawForceField<defaulttype::Vec6fTypes>::addDForce(const MechanicalParams* mparams, + DataVecDeriv& d_df , + const DataVecDeriv& d_dx) +{ + if (!compute_df) + return; + + WriteAccessor< DataVecDeriv > df = d_df; + ReadAccessor< DataVecDeriv > dx = d_dx; + Real kFactor = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + df.resize(dx.size()); + for (unsigned int i=0; i<dx.size(); i++) + df[i] -= (m_K_section66 * dx[i])*kFactor* d_length.getValue()[i]; +} + +template<> +void BeamHookeLawForceField<defaulttype::Vec6Types>::addKToMatrix(const MechanicalParams* mparams, + const MultiMatrixAccessor* matrix) +{ + MultiMatrixAccessor::MatrixRef mref = matrix->getMatrix(this->mstate); + BaseMatrix* mat = mref.matrix; + unsigned int offset = mref.offset; + Real kFact = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + const VecCoord& pos = this->mstate->read(core::ConstVecCoordId::position())->getValue(); + for (unsigned int n=0; n<pos.size(); n++) + { + for(unsigned int i = 0; i < 6; i++) + for (unsigned int j = 0; j< 6; j++) + mat->add(offset + i + 6*n, offset + j + 6*n, -kFact * m_K_section66[i][j]*d_length.getValue()[n]); + + } +} + //////////////////////////////////////////// FACTORY ////////////////////////////////////////////// // Registering the component // see: http://wiki.sofa-framework.org/wiki/ObjectFactory // 1-RegisterObject("description") + .add<> : Register the component // 2-.add<>(true) : Set default template -using namespace sofa::defaulttype; -int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used to compute internal stress for torsion (along x) and bending (y and z)") - .add<BeamHookeLawForceField<Vec3Types> >(true) +int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used to compute internal stress for torsion " + "(along x) and bending (y and z)") + .add<BeamHookeLawForceField<Vec3Types> >(true) + .add<BeamHookeLawForceField<Vec6Types> >() ; ////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -53,6 +192,9 @@ int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used t // avoid the code generation of the template for each compilation unit. // see: http://www.stroustrup.com/C++11FAQ.html#extern-templates -template class BeamHookeLawForceField<Vec3Types>; +template class SOFA_COSSERAT_API BeamHookeLawForceField<Vec3Types>; +template class SOFA_COSSERAT_API BeamHookeLawForceField<Vec6Types>; + + -} // forcefield +} // sofa::component::forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.h b/src/Cosserat/forcefield/BeamHookeLawForceField.h index 67a09038..a59e6e9f 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.h @@ -45,6 +45,8 @@ namespace sofa::component::forcefield { using sofa::type::Vec ; +using type::Vec6; +using type::Vector3; using sofa::type::Mat ; using sofa::type::vector; using sofa::core::MechanicalParams; @@ -65,18 +67,19 @@ class BeamHookeLawForceField : public ForceField<DataTypes> public : SOFA_CLASS(SOFA_TEMPLATE(BeamHookeLawForceField, DataTypes), SOFA_TEMPLATE(ForceField, DataTypes)); - typedef typename DataTypes::Real Real; + typedef typename DataTypes::Real Real ; + typedef typename DataTypes::Coord Coord ; + typedef typename DataTypes::Deriv Deriv; typedef typename DataTypes::VecCoord VecCoord; typedef typename DataTypes::VecDeriv VecDeriv; - typedef typename DataTypes::Coord Coord; - typedef typename DataTypes::Deriv Deriv; - typedef Data<VecCoord> DataVecCoord; typedef Data<VecDeriv> DataVecDeriv; - typedef Vec<3, Real> Vec3; - typedef Mat<3, 3, Real> Mat33; + typedef typename DataTypes::MatrixDeriv MatrixDeriv; + typedef typename sofa::core::behavior::MechanicalState<DataTypes> MechanicalState; + typedef Mat<3, 3, Real> Mat33; + typedef Mat<6, 6, Real> Mat66; typedef CompressedRowSparseMatrix<Mat33> CSRMat33B66; typedef typename CompressedRowSparseMatrix<Mat33>::ColBlockConstIterator _3_3_ColBlockConstIterator; @@ -136,11 +139,13 @@ public : Data<Real> d_GI; Data<Real> d_GA; Data<Real> d_EA; - Data<Real> d_EI; + Data<Real> d_EIy; + Data<Real> d_EIz; Data<bool> d_buildTorsion; bool compute_df; Mat33 m_K_section; + Mat66 m_K_section66; type::vector<Mat33> m_K_sectionList; /// Cross-section area @@ -153,11 +158,16 @@ private : /// Bring inherited attributes and function in the current lookup context. /// otherwise any access to the base::attribute would require /// the "this->" approach. - using ForceField<DataTypes>::getContext ; - using ForceField<DataTypes>::f_printLog ; +// using ForceField<DataTypes>::getContext ; +// using ForceField<DataTypes>::f_printLog ; //using ForceField<DataTypes>::mstate ; //////////////////////////////////////////////////////////////////////////// }; +#if !defined(SOFA_COSSERAT_BEAMHOOKELAWFORCEFIELD_CPP) +extern template class SOFA_COSSERAT_API BeamHookeLawForceField< defaulttype::Vec3Types>; +extern template class SOFA_COSSERAT_API BeamHookeLawForceField< defaulttype::Vec6Types>; +#endif + -} // forcefield +} // sofa::component::forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.inl b/src/Cosserat/forcefield/BeamHookeLawForceField.inl index fb40bf1b..af020430 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.inl @@ -34,20 +34,18 @@ #include <sofa/core/behavior/MechanicalState.h> #include <sofa/core/behavior/ForceField.inl> #include <sofa/helper/OptionsGroup.h> // ?? +#include <iostream> +#include <algorithm> +#include <ctime> using sofa::core::behavior::MechanicalState ; using sofa::core::objectmodel::BaseContext ; using sofa::helper::ReadAccessor ; using sofa::helper::WriteAccessor ; using sofa::core::VecCoordId; - -#include <iostream> using std::cout ; using std::endl ; -#include <algorithm> -#include <ctime> - namespace sofa::component::forcefield { @@ -76,7 +74,8 @@ namespace sofa::component::forcefield d_GI(initData(&d_GI, "GI", "The inertia parameter, GI")), d_GA(initData(&d_GA, "GA", "The inertia parameter, GA")), d_EA(initData(&d_EA, "EA", "The inertia parameter, EA")), - d_EI(initData(&d_EI, "EI", "The inertia parameter, EI")), + d_EIy(initData(&d_EIy, "EIy", "The inertia parameter, EIy")), + d_EIz(initData(&d_EIz, "EIz", "The inertia parameter, EIz")), d_buildTorsion(initData(&d_buildTorsion, true,"build_torsion", "build torsion or the elongation of the beam ?")) { @@ -95,13 +94,15 @@ namespace sofa::component::forcefield reinit(); } + + /*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties related to the cross-section of the beams. It calculates the area moment of inertia (Iy and Iz), the polar moment of inertia (J), and the cross-sectional area (A). These calculations depend on the chosen cross-section shape, either circular or rectangular. The formulas used for these calculations are based on standard equations for these properties.*/ template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::reinit() + void BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField::reinit() { // Precompute and store values Real Iy, Iz, J, A; @@ -181,38 +182,29 @@ namespace sofa::component::forcefield { msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; m_K_section[0][0] = d_GI.getValue(); - m_K_section[1][1] = d_EI.getValue(); - m_K_section[2][2] = d_EI.getValue(); + m_K_section[1][1] = d_EIy.getValue(); + m_K_section[2][2] = d_EIz.getValue(); } else { //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix - if (d_buildTorsion.getValue()){ - Real E = d_youngModulus.getValue(); - Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); - m_K_section[0][0] = G*J; - m_K_section[1][1] = E*Iy; - m_K_section[2][2] = E*Iz; - }else { - Real E = d_youngModulus.getValue(); - Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); - //Translational Stiffness (X, Y, Z directions): - // Gs * I(i): Shearing modulus times the second moment of the area (torsional stiffness). - // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). - m_K_section[1][1] = E * Iy; - m_K_section[2][2] = E * Iz; - - //Rotational Stiffness (X, Y, Z directions): - //E * A: Young's modulus times the cross-sectional area (axial stiffness). - //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). - m_K_section[0][0] = E * A; - } + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); + //Translational Stiffness (X, Y, Z directions): + // Gs * I(i): Shearing modulus times the second moment of the area (torsional stiffness). + // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). + m_K_section[0][0] = G*J; + m_K_section[1][1] = E*Iy; + m_K_section[2][2] = E*Iz; + //Rotational Stiffness (X, Y, Z directions): + //E * A: Young's modulus times the cross-sectional area (axial stiffness). + //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). } } } template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::addForce(const MechanicalParams* mparams, + void BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField::addForce(const MechanicalParams* mparams, DataVecDeriv& d_f, const DataVecCoord& d_x, const DataVecDeriv& d_v) @@ -239,8 +231,10 @@ namespace sofa::component::forcefield } if(!d_variantSections.getValue()) - for (unsigned int i=0; i<x.size(); i++) + for (unsigned int i=0; i<x.size(); i++){ +// Vector3 v = Vector3(x[i][0] - x0[i][0], x[i][1] - x0[i][1], x[i][2] - x0[i][2]); f[i] -= (m_K_section * (x[i] - x0[i])) * d_length.getValue()[i]; + } else for (unsigned int i=0; i<x.size(); i++) f[i] -= (m_K_sectionList[i] * (x[i] - x0[i])) * d_length.getValue()[i]; @@ -248,10 +242,9 @@ namespace sofa::component::forcefield } - template<typename DataTypes> + template<typename DataTypes> void BeamHookeLawForceField<DataTypes>::addDForce(const MechanicalParams* mparams, - DataVecDeriv& d_df , - const DataVecDeriv& d_dx) + DataVecDeriv& d_df , const DataVecDeriv& d_dx) { if (!compute_df) return; diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index 6781beaa..887ba9c0 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -28,18 +28,102 @@ namespace sofa::component::mapping { - using namespace sofa::defaulttype; +template<> +BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::build_Xi_hat(const Coord1& strain_i){ + se3 Xi; + + Xi[0][1] = -strain_i(2); + Xi[0][2] = strain_i[1]; + Xi[1][2] = -strain_i[0]; + + Xi[1][0] = -Xi(0,1); + Xi[2][0] = -Xi(0,2); + Xi[2][1] = -Xi(1,2); + + Xi[0][3] = 1.0; + Xi[0][3] = 1.0; + for (unsigned int i=3; i<6; i++) + Xi[i][3] = strain_i(i); + + return Xi; +} + + + +template<> +void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(const double & curv_abs_x_n, const Coord1& strain_n, Transform & Trans){ + Matrix4 I4; I4.identity(); + //Get the angular part of the + Vector3 k = Vector3(strain_n(0), strain_n(1), strain_n(2)); + SReal theta = k.norm(); // + + SE3 g_X_n; + se3 Xi_hat_n = build_Xi_hat(strain_n); + + if(d_debug.getValue()) + msg_info("BaseCosserat: ")<< "matrix Xi : "<< Xi_hat_n; + + if(theta <= std::numeric_limits<double>::epsilon()){ + g_X_n = I4 + curv_abs_x_n*Xi_hat_n; + }else { + double scalar1= (1.0 - std::cos(curv_abs_x_n*theta))/std::pow(theta,2); + double scalar2 = (curv_abs_x_n*theta - std::sin(curv_abs_x_n*theta))/std::pow(theta,3); + g_X_n = I4 + curv_abs_x_n*Xi_hat_n + scalar1*Xi_hat_n*Xi_hat_n + scalar2*Xi_hat_n*Xi_hat_n*Xi_hat_n ; + } + + // msg_info("BaseCosserat: ")<< "matrix g_X : "<< g_X; + type::Mat3x3 M; + g_X_n.getsub(0,0,M); //get the rotation matrix + + // convert the rotation 3x3 matrix to a quaternion + sofa::type::Quat<Real> R ; R.fromMatrix(M); + Trans = Transform(type::Vec3(g_X_n(0,3),g_X_n(1,3),g_X_n(2,3)),R); +} + +template<> +void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::compute_Tang_Exp(double & curv_abs_n, const Coord1 & strain_i, Mat6x6 & TgX){ + + SReal theta = type::Vec3(strain_i(0), strain_i(1), strain_i(2)).norm(); //Sometimes this is computed over all strain + Matrix3 tilde_k = getTildeMatrix(type::Vec3(strain_i(0), strain_i(1), strain_i(2))); + /* Younes @23-11-27 + old version + @Todo ???? is p the linear deformation? If so, why didn't I just put a zero vector in place of p and the first element of p is equal to 1? + Matrix3 tilde_p = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); + Using the new version does not bring any difference in my three reference scenes, but need more investogation + #TECHNICAL_DEBT + */ + Matrix3 tilde_q = getTildeMatrix(type::Vec3(strain_i(3), strain_i(4), strain_i(5))); + + Mat6x6 ad_Xi ; + buildAdjoint(tilde_k, tilde_q, ad_Xi); + + Mat6x6 Id6 = Mat6x6::Identity() ; + // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 + + if(theta <= std::numeric_limits<double>::epsilon()){ + double scalar0 = std::pow(curv_abs_n,2)/2.0; + TgX = curv_abs_n*Id6 + scalar0 * ad_Xi; + }else { + double scalar1 = (4.0 -4.0*cos(curv_abs_n*theta)-curv_abs_n*theta*sin(curv_abs_n*theta))/(2.0*theta*theta); + double scalar2 = (4.0*curv_abs_n*theta + curv_abs_n*theta*cos(curv_abs_n*theta)-5.0*sin(curv_abs_n*theta))/(2.0*theta*theta*theta); + double scalar3 = (2.0 -2.0*cos(curv_abs_n*theta)-curv_abs_n*theta*sin(curv_abs_n*theta))/(2.0*theta*theta*theta*theta); + double scalar4 = (2.0*curv_abs_n*theta + curv_abs_n*theta*cos(curv_abs_n*theta)-3.0*sin(curv_abs_n*theta))/(2.0*theta*theta*theta*theta*theta); + + TgX = curv_abs_n*Id6 + scalar1*ad_Xi + scalar2*ad_Xi*ad_Xi + scalar3*ad_Xi*ad_Xi*ad_Xi + scalar4*ad_Xi*ad_Xi*ad_Xi*ad_Xi ; + } +} + + // Register in the Factory int BaseCosseratClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") .add< BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() - .add< BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types > >() - + .add< BaseCosserat< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() ; template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; -template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types >; +template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; } // namespace sofa. diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 4cec9bd0..11f98415 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -82,8 +82,8 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject [[maybe_unused]] typedef typename In2::MatrixDeriv In2MatrixDeriv; typedef Data<In2VecCoord> In2DataVecCoord; typedef Data<In2VecDeriv> In2DataVecDeriv; - typedef type::Mat<6,6,Real> Mat6x6; - typedef type::Mat<4,4,Real> Mat4x4; + typedef type::Mat<6,6,SReal> Mat6x6; + typedef type::Mat<4,4,SReal> Mat4x4; typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; @@ -98,7 +98,8 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject typedef MultiLink<BaseCosserat<In1,In2,Out>, sofa::core::State< In2 >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels2; [[maybe_unused]] typedef MultiLink<BaseCosserat<In1,In2,Out>, sofa::core::State< Out >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkToModels; - typedef typename SolidTypes<Real>::Transform Transform ; + typedef typename SolidTypes<SReal>::Transform Transform ; + typedef typename type::vector<SReal> List; protected: Data<type::vector<double>> d_curv_abs_section ; @@ -136,7 +137,9 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject [[maybe_unused]] type::vector<Mat6x6> m_frameAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_node_coAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_frame_coAdjointEtaVectors; - + typedef typename sofa::type::Matrix4 se3; + typedef typename sofa::type::Matrix4 SE3; + typedef typename type::Mat<6,6,SReal> Tangent; protected: /// Constructor @@ -152,6 +155,9 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject void reinit() override; void draw(const core::visual::VisualParams* vparams) override; + + + /**********************COSSERAT METHODS**************************/ double computeTheta(const double &x, const Mat4x4 &gX){ double Tr_gx = 0.0; for (int i = 0; i<4; i++) { @@ -166,15 +172,15 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject } protected: - /**********************COSSERAT METHODS**************************/ - void computeExponentialSE3(const double &x, const type::Vec3& k, Transform & Trans); + + void computeExponentialSE3(const double &x, const Coord1& k, Transform & Trans); void computeAdjoint(const Transform & frame, Mat6x6 &adjoint); void compute_coAdjoint(const Transform & frame, Mat6x6 &co_adjoint); void compute_adjointVec6(const Vec6 & frame, Mat6x6 &adjoint); void update_ExponentialSE3(const In1VecCoord & inDeform); - void update_TangExpSE3(const In1VecCoord & inDeform, const type::vector<double> &curv_abs_section , const type::vector<double> &curv_abs_frames ); - void compute_Tang_Exp(double & x, const type::Vec3& k, Mat6x6 & TgX); + void update_TangExpSE3(const In1VecCoord & inDeform); + void compute_Tang_Exp(double & x, const Coord1& k, Mat6x6 & TgX); [[maybe_unused]] type::Vec6 compute_eta(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); type::Matrix4 computeLogarithm(const double & x, const Mat4x4 &gX); @@ -203,7 +209,7 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject mat[k][i] = R[k][i]; return mat; } - Mat6x6 build_projector(const Transform &T){ + Tangent build_projector(const Transform &T){ Mat6x6 P; Real R[4][4]; (T.getOrientation()).buildRotationMatrix(R); @@ -218,6 +224,21 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject return P; } + se3 build_Xi_hat(const Coord1 & strain_i){ + se3 Xi; + + Xi[0][1] = -strain_i(2); + Xi[0][2] = strain_i[1]; + Xi[1][2] = -strain_i[0]; + + Xi[1][0] = -Xi(0,1); + Xi[2][0] = -Xi(0,2); + Xi[2][1] = -Xi(1,2); + + Xi[0][3] = 1.0; + return Xi; + } + Matrix3 getTildeMatrix(const type::Vec3 & u){ type::Matrix3 tild; tild[0][1] = -u[2]; @@ -272,8 +293,8 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject #if !defined(SOFA_COSSERAT_CPP_BaseCosserat) -extern template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types >; extern template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; +extern template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; #endif } // namespace sofa diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index 3d821918..9f42b514 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -33,6 +33,8 @@ #include <string> +//To go further => https://www.mathworks.com/matlabcentral/fileexchange/83038-sorosim/ + namespace sofa::component::mapping { @@ -79,45 +81,33 @@ void BaseCosserat<TIn1, TIn2, TOut>::reinit() template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3(const double & x, const type::Vec3& k, Transform & Trans){ +void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3(const double & curv_abs_x_n, const Coord1& strain_n, Transform & g_X_n){ Matrix4 I4; I4.identity(); + //Get the angular part of the + Vector3 k = Vector3(strain_n(0), strain_n(1), strain_n(2)); + SReal theta = k.norm(); // - double theta = k.norm(); - - Matrix4 g_X; - Matrix4 Xi ; - - Xi[0][1] = -k(2); - Xi[0][2] = k[1]; - Xi[1][2] = -k[0]; - - Xi[1][0] = -Xi(0,1); - Xi[2][0] = -Xi(0,2); - Xi[2][1] = -Xi(1,2); - - Xi[0][3] = 1.0; + SE3 _g_X; + se3 Xi_hat_n = build_Xi_hat(strain_n); if(d_debug.getValue()) - msg_info("BaseCosserat: ")<< "matrix Xi : "<< Xi; + msg_info("BaseCosserat: ")<< "matrix Xi : "<< Xi_hat_n; if(theta <= std::numeric_limits<double>::epsilon()){ - g_X = I4 + x*Xi; + _g_X = I4 + curv_abs_x_n*Xi_hat_n; }else { - double scalar1= (1.0 - std::cos(x*theta))/(theta*theta); - double scalar2 = (x*theta - std::sin(x*theta))/(theta*theta*theta); - g_X = I4 + x*Xi + scalar1*Xi*Xi + scalar2*Xi*Xi*Xi ; + double scalar1= (1.0 - std::cos(curv_abs_x_n*theta))/std::pow(theta,2); + double scalar2 = (curv_abs_x_n*theta - std::sin(curv_abs_x_n*theta))/std::pow(theta,3); + _g_X = I4 + curv_abs_x_n*Xi_hat_n + scalar1*Xi_hat_n*Xi_hat_n + scalar2*Xi_hat_n*Xi_hat_n*Xi_hat_n ; } // msg_info("BaseCosserat: ")<< "matrix g_X : "<< g_X; type::Mat3x3 M; - g_X.getsub(0,0,M); - - // msg_info("BaseCosserat: ")<< "Sub matrix M : "<< g_X; - sofa::type::Quat<Real> R ; - R.fromMatrix(M); - type::Vec3 T = type::Vec3(g_X(0,3),g_X(1,3),g_X(2,3)); + _g_X.getsub(0,0,M); //get the rotation matrix - Trans = Transform(T,R); + // convert the rotation 3x3 matrix to a quaternion + sofa::type::Quat<Real> R ; R.fromMatrix(M); + g_X_n = Transform(type::Vec3(_g_X(0,3),_g_X(1,3),_g_X(2,3)),R); } @@ -126,7 +116,6 @@ template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3(const In1VecCoord & inDeform){ //helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = d_curv_abs_section; helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = d_curv_abs_frames; - //m_index_input = 0; m_framesExponentialSE3Vectors.clear(); m_nodesExponentialSE3Vectors.clear(); @@ -135,47 +124,49 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3(const In1VecCoord & i //Compute exponential at each frame point for (size_t i = 0; i < sz; i++) { - Transform T ; + Transform g_X_frame_i ; - const type::Vec3 k = inDeform[m_indicesVectors[i]-1]; //Cosserat reduce coordinates - const double x = m_framesLengthVectors[i]; // The distance between the frame and the closest beam node toward the base - computeExponentialSE3(x,k,T); - m_framesExponentialSE3Vectors.push_back(T); + const Coord1 strain_n = inDeform[m_indicesVectors[i]-1]; //Cosserat reduce coordinates (strain) the size varies from 1 to 6 + // The distance between the frame and the closest beam node toward the base + const SReal curv_abs_x = m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) + computeExponentialSE3(curv_abs_x, strain_n,g_X_frame_i); + m_framesExponentialSE3Vectors.push_back(g_X_frame_i); if(d_debug.getValue()){ msg_info("BaseCosserat:")<< "__________________________________________"; - msg_info("BaseCosserat:")<< "x :"<< x << "; k :"<< k; - msg_info("BaseCosserat:")<< "m_framesExponentialSE3Vectors :"<< T; + msg_info("BaseCosserat:")<< "x :"<< curv_abs_x << "; k :"<< strain_n; + msg_info("BaseCosserat:")<< "m_framesExponentialSE3Vectors :"<< g_X_frame_i; } } //Compute the exponential on the nodes - m_nodesExponentialSE3Vectors.push_back(Transform(type::Vec3(0.0,0.0,0.0),type::Quat(0.,0.,0.,1.))); + m_nodesExponentialSE3Vectors.push_back(Transform(type::Vec3(0.0,0.0,0.0),type::Quat(0.,0.,0.,1.))); //The first node. for (unsigned int j = 0; j < inDeform.size(); j++) { - type::Vec3 k = inDeform[j]; - double x = m_BeamLengthVectors[j]; - Transform T; computeExponentialSE3(x,k,T) ; - m_nodesExponentialSE3Vectors.push_back(T); + Coord1 strain_n = inDeform[j]; // Strain_n + const SReal curv_abs_x = m_BeamLengthVectors[j]; // curv_abs_x = L_n - L_(n-1) + + Transform g_X_node_j; computeExponentialSE3(curv_abs_x,strain_n,g_X_node_j) ; + m_nodesExponentialSE3Vectors.push_back(g_X_node_j); if(d_debug.getValue()){ msg_info("BaseCosserat:")<< "_________________Beam Node Expo___________________"<<j; - msg_info("BaseCosserat:")<< "Node m_framesExponentialSE3Vectors :"<< T; + msg_info("BaseCosserat:")<< "Node m_framesExponentialSE3Vectors :"<< g_X_node_j; msg_info("BaseCosserat:")<< "_________________Beam Node Expo___________________"; } - ////////////////// - // Eigen::Matrix4d gX = convertTransformToMatrix4x4(T); - // Eigen::Matrix4d log_gX= (1.0/x) * computeLogarithm(x, gX); - // std::cout << "k : \n"<< k << std::endl; - // std::cout << "The logarithm : \n"<< log_gX << std::endl; - // m_nodesLogarithmSE3Vectors.push_back(log_gX); } } +////////////////// Test the logarithm code +// Eigen::Matrix4d gX = convertTransformToMatrix4x4(T); +// Eigen::Matrix4d log_gX= (1.0/x) * computeLogarithm(x, gX); +// std::cout << "k : \n"<< k << std::endl; +// std::cout << "The logarithm : \n"<< log_gX << std::endl; +// m_nodesLogarithmSE3Vectors.push_back(log_gX); template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>:: computeAdjoint(const Transform & frame, Mat6x6 &adjoint) +void BaseCosserat<TIn1, TIn2, TOut>:: computeAdjoint(const Transform & frame, Tangent &adjoint) { Matrix3 R = extract_rotMatrix(frame); type::Vec3 u = frame.getOrigin(); @@ -205,30 +196,6 @@ void BaseCosserat<TIn1, TIn2, TOut>::compute_adjointVec6(const Vec6& eta, Mat6x6 -template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::compute_Tang_Exp(double & x, const type::Vec3& k, Mat6x6 & TgX){ - double theta = k.norm(); - Matrix3 tilde_p = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); - Matrix3 tilde_k = getTildeMatrix(k); - - Mat6x6 ad_Xi ; - buildAdjoint(tilde_k, tilde_p, ad_Xi); - - Mat6x6 Id6 = Mat6x6::Identity() ; - // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 - - if(theta <= std::numeric_limits<double>::epsilon()){ - double scalar0 = x*x/2.0; - TgX = x*Id6 + scalar0 * ad_Xi; - }else { - double scalar1 = (4.0 -4.0*cos(x*theta)-x*theta*sin(x*theta))/(2.0*theta*theta); - double scalar2 = (4.0*x*theta + x*theta*cos(x*theta)-5.0*sin(x*theta))/(2.0*theta*theta*theta); - double scalar3 = (2.0 -2.0*cos(x*theta)-x*theta*sin(x*theta))/(2.0*theta*theta*theta*theta); - double scalar4 = (2.0*x*theta + x*theta*cos(x*theta)-3.0*sin(x*theta))/(2.0*theta*theta*theta*theta*theta); - - TgX = x*Id6 + scalar1*ad_Xi + scalar2*ad_Xi*ad_Xi + scalar3*ad_Xi*ad_Xi*ad_Xi + scalar4*ad_Xi*ad_Xi*ad_Xi*ad_Xi ; - } -} template <class TIn1, class TIn2, class TOut> @@ -284,37 +251,41 @@ Matrix4 BaseCosserat<TIn1, TIn2, TOut>::computeLogarithm(const double & x, const template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3(const In1VecCoord & inDeform, const type::vector<double> - &curv_abs_section , const type::vector<double> &curv_abs_frames ){ +void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3(const In1VecCoord & inDeform){ + + // Curv abscissa of nodes and frames + helper::ReadAccessor<Data<type::vector<double>>> curv_abs_section = d_curv_abs_section; + helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = d_curv_abs_frames; m_framesTangExpVectors.clear(); unsigned int sz = curv_abs_frames.size(); //Compute tangExpo at frame points for (unsigned int i = 0; i < sz; i++) { - Mat6x6 temp ; + Tangent temp ; + + Coord1 strain_frame_i = inDeform[m_indicesVectors[i]-1]; + double curv_abs_x_i = m_framesLengthVectors[i]; + compute_Tang_Exp(curv_abs_x_i, strain_frame_i, temp) ; - type::Vec3 k = inDeform[m_indicesVectors[i]-1]; - double x = m_framesLengthVectors[i]; - compute_Tang_Exp(x,k,temp) ; m_framesTangExpVectors.push_back(temp); if (d_debug.getValue()){ printf("__________________________________________\n"); - std::cout << "x :"<< x << "; k :"<< k << std::endl; + std::cout << "x :"<< curv_abs_x_i << "; k :"<< strain_frame_i << std::endl; std::cout<< "m_framesTangExpVectors :"<< m_framesTangExpVectors[i] << std::endl; } } //Compute the TangExpSE3 at the nodes m_nodesTangExpVectors.clear(); - Mat6x6 tangExpO; tangExpO.clear(); + Tangent tangExpO; tangExpO.clear(); m_nodesTangExpVectors.push_back(tangExpO); for (size_t j = 1; j < curv_abs_section.size(); j++) { - type::Vec3 k = inDeform[j-1]; + Coord1 strain_node_i = inDeform[j-1]; double x = m_BeamLengthVectors[j - 1]; - Mat6x6 temp; temp.clear(); - compute_Tang_Exp(x,k,temp); + Tangent temp; temp.clear(); + compute_Tang_Exp(x,strain_node_i,temp); m_nodesTangExpVectors.push_back(temp); } if (d_debug.getValue()){ @@ -323,6 +294,40 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3(const In1VecCoord & inDef } } +template <class TIn1, class TIn2, class TOut> +void BaseCosserat<TIn1, TIn2, TOut>::compute_Tang_Exp(double & curv_abs_n, const Coord1 & strain_i, Mat6x6 & TgX){ + + SReal theta = type::Vec3(strain_i(0), strain_i(1), strain_i(2)).norm(); //Sometimes this is computed over all strain + Matrix3 tilde_k = getTildeMatrix(type::Vec3(strain_i(0), strain_i(1), strain_i(2))); + /* Younes @23-11-27 + old version + @Todo ???? is p the linear deformation? If so, why didn't I just put a zero vector in place of p and the first element of p is equal to 1? + Matrix3 tilde_p = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); + Using the new version does not bring any difference in my three reference scenes, but need more investogation + #TECHNICAL_DEBT + */ + Matrix3 tilde_q = getTildeMatrix(type::Vec3(0.0, 0.0, 0.0)); + + Mat6x6 ad_Xi ; + buildAdjoint(tilde_k, tilde_q, ad_Xi); + + Mat6x6 Id6 = Mat6x6::Identity() ; + // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 + + if(theta <= std::numeric_limits<double>::epsilon()){ + double scalar0 = std::pow(curv_abs_n,2)/2.0; + TgX = curv_abs_n*Id6 + scalar0 * ad_Xi; + }else { + double scalar1 = (4.0 -4.0*cos(curv_abs_n*theta)-curv_abs_n*theta*sin(curv_abs_n*theta))/(2.0*theta*theta); + double scalar2 = (4.0*curv_abs_n*theta + curv_abs_n*theta*cos(curv_abs_n*theta)-5.0*sin(curv_abs_n*theta))/(2.0*theta*theta*theta); + double scalar3 = (2.0 -2.0*cos(curv_abs_n*theta)-curv_abs_n*theta*sin(curv_abs_n*theta))/(2.0*theta*theta*theta*theta); + double scalar4 = (2.0*curv_abs_n*theta + curv_abs_n*theta*cos(curv_abs_n*theta)-3.0*sin(curv_abs_n*theta))/(2.0*theta*theta*theta*theta*theta); + + TgX = curv_abs_n*Id6 + scalar1*ad_Xi + scalar2*ad_Xi*ad_Xi + scalar3*ad_Xi*ad_Xi*ad_Xi + scalar4*ad_Xi*ad_Xi*ad_Xi*ad_Xi ; + } +} + + template <class TIn1, class TIn2, class TOut> [[maybe_unused]] type::Vec6 BaseCosserat<TIn1, TIn2, TOut>::compute_eta(const type::Vec6 & baseEta, const In1VecDeriv & k_dot, const double abs_input){ @@ -367,7 +372,8 @@ template <class TIn1, class TIn2, class TOut> template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::initialize() { - //find the beam on which each output frame is located + // For each frame in the global frame, find the segment of the beam to which it is attached. + // Here we only use the information from the curvilinear abscissa of each frame. helper::ReadAccessor<Data<type::vector< double>>> curv_abs_section = d_curv_abs_section; helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = d_curv_abs_frames; @@ -380,7 +386,6 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() m_indicesVectors.clear(); m_framesLengthVectors.clear(); m_BeamLengthVectors.clear(); - m_indicesVectorsDraw.clear(); size_t input_index = 1; @@ -395,8 +400,6 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() m_indicesVectors.emplace_back(input_index); input_index++; m_indicesVectorsDraw.emplace_back(input_index); - - } else { input_index++; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index 91df0b7f..5ed46311 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -30,10 +30,349 @@ namespace sofa::component::mapping { using namespace sofa::defaulttype; + +template <> +void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( + const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, + const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) { + + if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) + return; + const In1VecDeriv& in1_vel = dataVecIn1Vel[0]->getValue(); + const In2VecDeriv& in2_vel = dataVecIn2Vel[0]->getValue(); + OutVecDeriv& out_vel = *dataVecOutVel[0]->beginEdit(); + const auto baseIndex = d_baseIndex.getValue(); + + // Curv abscissa of nodes and frames + helper::ReadAccessor<Data<List>> curv_abs_section = d_curv_abs_section; + helper::ReadAccessor<Data<List>> curv_abs_frames = d_curv_abs_frames; + + const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); //Strains + // Compute the tangent Exponential SE3 vectors + this->update_TangExpSE3(inDeform); + + //Get base velocity as input this is also called eta + m_nodesVelocityVectors.clear(); + + //Get base velocity and convert to Vec6, for the facility of computation + type::Vec6 baseVelocity; // + for (auto u=0; u<6; u++) + baseVelocity[u] = in2_vel[baseIndex][u]; + + //Apply the local transform i.e. from SOFA's frame to Cosserat's frame + const In2VecCoord& xfrom2Data = m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); + Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()).inversed(); + Mat6x6 P = this->build_projector(TInverse); + type::Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame + m_nodesVelocityVectors.push_back(baseLocalVelocity); + if(d_debug.getValue()) + std::cout << "Base local Velocity :"<< baseLocalVelocity <<std::endl; + + //Compute velocity at nodes + for (unsigned int i = 1 ; i < curv_abs_section.size(); i++) { + Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); + Tangent Adjoint; Adjoint.clear(); + this->computeAdjoint(Trans, Adjoint); + + type::Vec6 node_Xi_dot; + for (unsigned int u =0; u<6; u++) + node_Xi_dot(i) = in1_vel[i-1][u]; + + Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i-1] + m_nodesTangExpVectors[i] *node_Xi_dot ); + m_nodesVelocityVectors.push_back(eta_node_i); + if(d_debug.getValue()) + std::cout<< "Node velocity : "<< i << " = " << eta_node_i<< std::endl; + } + + const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); + auto sz = curv_abs_frames.size(); + out_vel.resize(sz); + for (unsigned int i = 0 ; i < sz; i++) { + Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); + Tangent Adjoint; Adjoint.clear(); + this->computeAdjoint(Trans, Adjoint); + + type::Vec6 frame_Xi_dot; + for (unsigned int u =0; u<6; u++) + frame_Xi_dot(i) = in1_vel[i-1][u]; + + Vec6 eta_frame_i = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * frame_Xi_dot ); // eta + + auto T = Transform(out[i].getCenter(), out[i].getOrientation()); + Tangent Proj = this->build_projector(T); + + out_vel[i] = Proj * eta_frame_i; + + if(d_debug.getValue()) + std::cout<< "Frame velocity : "<< i << " = " << eta_frame_i<< std::endl; + } + dataVecOutVel[0]->endEdit(); + m_index_input = 0; +} + + + +template <> +void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( + const core::MechanicalParams* /*mparams*/, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, + const type::vector< In2DataVecDeriv*>& dataVecOut2Force, + const type::vector<const OutDataVecDeriv*>& dataVecInForce) { + + if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) + return; + + const OutVecDeriv& in = dataVecInForce[0]->getValue(); + + In1VecDeriv& out1 = *dataVecOut1Force[0]->beginEdit(); + In2VecDeriv& out2 = *dataVecOut2Force[0]->beginEdit(); + const auto baseIndex = d_baseIndex.getValue(); + + const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + type::vector<Vec6> local_F_Vec; local_F_Vec.clear(); + + out1.resize(x1from.size()); + + //convert the input from Deriv type to vec6 type, for the purpose of the matrix vector multiplication + for (unsigned int var = 0; var < in.size(); ++var) { + type::Vec6 vec; + for(unsigned j = 0; j < 6; j++) vec[j] = in[var][j]; + //Convert input from global frame(SOFA) to local frame + Transform _T = Transform(frame[var].getCenter(),frame[var].getOrientation()); + Mat6x6 P_trans =(this->build_projector(_T)); P_trans.transpose(); + type::Vec6 local_F = P_trans * vec; + local_F_Vec.push_back(local_F); + } + + //Compute output forces + auto sz = m_indicesVectors.size(); + auto index = m_indicesVectors[sz-1]; + m_totalBeamForceVectors.clear(); + m_totalBeamForceVectors.resize(sz); + + Vec6 F_tot; F_tot.clear(); + m_totalBeamForceVectors.push_back(F_tot); + + Tangent matB_trans; matB_trans.clear(); + for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; + + + for (auto s = sz ; s-- ; ) { + Tangent coAdjoint; + + this->compute_coAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; + Mat6x6 temp = m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) + temp.transpose(); + type::Vec6 f = matB_trans * temp * node_F_Vec; + + if(index != m_indicesVectors[s]){ + index--; + //bring F_tot to the reference of the new beam + this->compute_coAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + F_tot = coAdjoint * F_tot; + Mat6x6 temp = m_nodesTangExpVectors[index]; + temp.transpose(); + //apply F_tot to the new beam + type::Vec6 temp_f = matB_trans * temp * F_tot; + out1[index-1] += temp_f; + } + if(d_debug.getValue()) + std::cout << "f at s ="<< s <<" and index"<< index << " is : "<< f << std::endl; + + + //compute F_tot + F_tot += node_F_Vec; + out1[m_indicesVectors[s]-1] += f; + } + + Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); + Mat6x6 M = this->build_projector(frame0); + out2[baseIndex] += M * F_tot; + + if(d_debug.getValue()){ + std::cout << "Node forces "<< out1 << std::endl; + std::cout << "base Force: "<< out2[baseIndex] << std::endl; + } + + dataVecOut1Force[0]->endEdit(); + dataVecOut2Force[0]->endEdit(); +} + +template <> +void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( + const core::ConstraintParams*/*cparams*/ , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const, + const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) +{ + if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) + return; + + //We need only one input In model and input Root model (if present) + In1MatrixDeriv& out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space (reduced coordinate) + In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) + const OutMatrixDeriv& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames + + const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + + Tangent matB_trans; matB_trans.clear(); + for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; + + type::vector< std::tuple<int,Vec6> > NodesInvolved; + type::vector< std::tuple<int,Vec6> > NodesInvolvedCompressed; + //helper::vector<Vec6> NodesConstraintDirection; + + typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + + for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) + { + if (d_debug.getValue()){ + std::cout<<"************* Apply JT (MatrixDeriv) iteration on line "; + std::cout<<rowIt.index(); + std::cout<<"************* "<<std::endl; + } + auto colIt = rowIt.begin(); + auto colItEnd = rowIt.end(); + + // Creates a constraints if the input constraint is not empty. + if (colIt == colItEnd) + { + if (d_debug.getValue()){ + std::cout<<"no column for this constraint"<<std::endl; + } + continue; + } + typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number + typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + + NodesInvolved.clear(); + while (colIt != colItEnd) + { + int childIndex = colIt.index(); + + type::Vec6 valueConst; + for(unsigned j = 0; j < 6; j++) + valueConst[j] = colIt.val()[j]; + + int indexBeam = m_indicesVectors[childIndex]; + + Transform _T = Transform(frame[childIndex].getCenter(),frame[childIndex].getOrientation()); + Tangent P_trans =(this->build_projector(_T)); + P_trans.transpose(); + + Mat6x6 coAdjoint; + this->compute_coAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Tangent temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) + temp.transpose(); + + type::Vec6 local_F = coAdjoint * P_trans * valueConst; // constraint direction in local frame of the beam. + + type::Vec6 f = matB_trans * temp * local_F; // constraint direction in the strain space. + + o1.addCol(indexBeam-1, f); + std::tuple<int,Vec6> node_force = std::make_tuple(indexBeam, local_F); + + NodesInvolved.push_back(node_force); + colIt++; + + } + if (d_debug.getValue()){ + std::cout<<"==> NodesInvolved : "<<std::endl; + for (size_t i = 0; i < NodesInvolved.size(); i++) + std::cout << "index :" <<get<0>(NodesInvolved[i]) << " force :" + << get<1>(NodesInvolved[i]) << "\n "; + } + + // sort the Nodes Invoved by decreasing order + std::sort(begin(NodesInvolved), end(NodesInvolved), + [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { + return std::get<0>(t1) > std::get<0>(t2); // custom compare function + } ); + + NodesInvolvedCompressed.clear(); + + for (unsigned n=0; n<NodesInvolved.size(); n++) + { + std::tuple<int,Vec6> test_i = NodesInvolved[n]; + int numNode_i= std::get<0>(test_i); + Vec6 cumulativeF =std::get<1>(test_i); + + if (n<NodesInvolved.size()-1) + { + std::tuple<int,Vec6> test_i1 = NodesInvolved[n+1]; + int numNode_i1= std::get<0>(test_i1); + + while (numNode_i == numNode_i1) + { + cumulativeF += std::get<1>(test_i1); + //// This was if ((n!=NodesInvolved.size()-2)||(n==0)) before and I change it to + /// if ((n!=NodesInvolved.size()-1)||(n==0)) since the code can't leave the will loop + if ((n!=NodesInvolved.size()-1)||(n==0)){ + n++; + break; + } + test_i1 = NodesInvolved[n+1]; + numNode_i1= std::get<0>(test_i1); + } + + } + NodesInvolvedCompressed.push_back(std::make_tuple(numNode_i, cumulativeF)); + } + + if (d_debug.getValue()){ + std::cout<<" NodesInvolved after sort and compress"<<std::endl; + for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) + std::cout << "index :" <<get<0>(NodesInvolvedCompressed[i]) << " force :" + << get<1>(NodesInvolvedCompressed[i]) << "\n "; + } + + for (unsigned n=0; n<NodesInvolvedCompressed.size(); n++) + { + std::tuple<int,Vec6> test = NodesInvolvedCompressed[n]; + int numNode= std::get<0>(test); + int i = numNode; + Vec6 CumulativeF = std::get<1>(test); + + while(i>0) + { + //cumulate on beam frame + Mat6x6 coAdjoint; + this->compute_coAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + CumulativeF = coAdjoint * CumulativeF; + // transfer to strain space (local coordinates) + Mat6x6 temp = m_nodesTangExpVectors[i-1]; + temp.transpose(); + type::Vec6 temp_f = matB_trans * temp * CumulativeF; + + if(i>1) o1.addCol(i-2, temp_f); + i--; + } + + Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); + Mat6x6 M = this->build_projector(frame0); + + Vec6 base_force = M * CumulativeF; + o2.addCol(d_baseIndex.getValue(), base_force); + } + } + + //"""END ARTICULATION SYSTEM MAPPING""" + dataMatOut1Const[0]->endEdit(); + dataMatOut2Const[0]->endEdit(); +} + + // Register in the Factory int DiscreteCosseratMappingClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") - .add< DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >(true) ; + .add< DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >(true) + .add< DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() + ; template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; +template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; } // namespace sofa::component::mapping diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 9508b5a2..ea7c4cfb 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -187,6 +187,7 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu #if !defined(SOFA_COSSERAT_CPP_DiscreteCosseratMapping) extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; +extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; #endif } // namespace sofa::component::mapping diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index c1a92b62..5e2047d2 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -82,17 +82,17 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() { - m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion or elongation and bending), in local frame + m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion, bending_y/_z, elongation and shear_y/_z), in local frame m_fromModel2 = this->getFromModels2()[0]; // Cosserat base, in global frame m_toModel = this->getToModels()[0]; // Cosserat rigid frames, in global frame - // Fill the initial vectorvoid init() override; + // Fill the initial vector void init() override; const OutDataVecCoord* xFromData = m_toModel->read(core::ConstVecCoordId::position()); const OutVecCoord xFrom = xFromData->getValue(); m_vecTransform.clear(); // initialise with the rigids frames for (unsigned int i = 0; i < xFrom.size(); i++) { - m_vecTransform.push_back(xFrom[i]); + m_vecTransform.push_back(xFrom[i]); } if(d_debug.getValue()) @@ -116,27 +116,28 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( const In2VecCoord& in2 = dataVecIn2Pos[0]->getValue(); const auto sz = d_curv_abs_frames.getValue().size(); - OutVecCoord& out = *dataVecOutPos[0]->beginEdit(); + OutVecCoord& out = *dataVecOutPos[0]->beginEdit(); //frames states out.resize(sz); const auto baseIndex = d_baseIndex.getValue(); // update the Exponential matrices according to new deformation // Here we update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors + // Which are the homogeneous matrices of the frames and the nodes in local coordinate. this->update_ExponentialSE3(in1); - /* from cossserat to SOFA frame*/ + /* Apply the transformation to go from cossserat to SOFA frame*/ Transform frame0 = Transform(In2::getCPos(in2[baseIndex]),In2::getCRot(in2[baseIndex])); for(unsigned int i=0; i<sz; i++){ Transform frame = frame0; for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { - frame *= m_nodesExponentialSE3Vectors[u]; + frame *= m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) } - frame *= m_framesExponentialSE3Vectors[i]; + frame *= m_framesExponentialSE3Vectors[i]; //frame*gX(x) type::Vec3 v = frame.getOrigin(); type::Quat q = frame.getOrientation(); out[i] = OutCoord(v,q); } - // @todo + // m_index_input = 0; dataVecOutPos[0]->endEdit(); } @@ -173,8 +174,6 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double & //void computeViolation(In1VecCoord& inDeform, const helper::vector<double> m_framesLengthVectors, const // size_t sz, std::function<double(int i, int j)> f) //{ - - // for (std::size_t i = 0; i < sz; i++) { // Mat6x6 temp ; @@ -200,33 +199,32 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>:: applyJ( if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) return; - const In1VecDeriv& in1 = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv& in2_vecDeriv = dataVecIn2Vel[0]->getValue(); - OutVecDeriv& outVel = *dataVecOutVel[0]->beginEdit(); + const In1VecDeriv& in1_vel = dataVecIn1Vel[0]->getValue(); + const In2VecDeriv& in2_vel = dataVecIn2Vel[0]->getValue(); + OutVecDeriv& out_vel = *dataVecOutVel[0]->beginEdit(); const auto baseIndex = d_baseIndex.getValue(); - // This is the vector of the curv abscissa, X in the paper + // Curv abscissa of nodes and frames helper::ReadAccessor<Data<type::vector<double>>> curv_abs_section = d_curv_abs_section; helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = d_curv_abs_frames; + const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); //Strains // Compute the tangent Exponential SE3 vectors - const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); - this->update_TangExpSE3(inDeform, curv_abs_section.ref(), curv_abs_frames.ref()); + this->update_TangExpSE3(inDeform); //Get base velocity as input this is also called eta m_nodesVelocityVectors.clear(); - Deriv2 _baseVelocity; - if (!in2_vecDeriv.empty()) - _baseVelocity = in2_vecDeriv[baseIndex]; - //convert to Vec6 - type::Vec6 baseVelocity; - for (auto u=0; u<6; u++) {baseVelocity[u] = _baseVelocity[u];} - - //Apply the local transform i.e from SOFA's frame to Cosserat's frame + + //Get base velocity and convert to Vec6, for the facility of computation + type::Vec6 baseVelocity; // + for (auto u=0; u<6; u++) + baseVelocity[u] = in2_vel[baseIndex][u]; + + //Apply the local transform i.e. from SOFA's frame to Cosserat's frame const In2VecCoord& xfrom2Data = m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()).inversed(); Mat6x6 P = this->build_projector(TInverse); - type::Vec6 baseLocalVelocity = P * baseVelocity; + type::Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame m_nodesVelocityVectors.push_back(baseLocalVelocity); if(d_debug.getValue()) std::cout << "Base local Velocity :"<< baseLocalVelocity <<std::endl; @@ -237,31 +235,38 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>:: applyJ( Mat6x6 Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); - type::Vec6 Xi_dot = Vec6(in1[i-1],type::Vec3(0.0,0.0,0.0)) ; - Vec6 temp = Adjoint * (m_nodesVelocityVectors[i-1] + m_nodesTangExpVectors[i] * Xi_dot ); - m_nodesVelocityVectors.push_back(temp); + ///The null vector is replace by the linear velocity in Vec6Type + type::Vec6 Xi_dot = Vec6(in1_vel[i-1],type::Vec3(0.0,0.0,0.0)) ; + + Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i-1] + m_nodesTangExpVectors[i] * Xi_dot ); + m_nodesVelocityVectors.push_back(eta_node_i); if(d_debug.getValue()) - std::cout<< "Node velocity : "<< i << " = " << temp<< std::endl; + std::cout<< "Node velocity : "<< i << " = " << eta_node_i<< std::endl; } const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); auto sz = curv_abs_frames.size(); - outVel.resize(sz); + out_vel.resize(sz); for (unsigned int i = 0 ; i < sz; i++) { Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); Mat6x6 Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); + type::Vec6 frame_Xi_dot; - type::Vec6 Xi_dot = Vec6(in1[m_indicesVectors[i]-1],type::Vec3(0.0,0.0,0.0)) ; - Vec6 temp = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * Xi_dot ); // eta + for (auto u=0; u<3; u++) + { + frame_Xi_dot(u) = in1_vel[m_indicesVectors[i]-1][u]; + frame_Xi_dot(u+3) = 0.; + } + Vec6 eta_frame_i = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * frame_Xi_dot ); // eta auto T = Transform(out[i].getCenter(), out[i].getOrientation()); Mat6x6 Proj = this->build_projector(T); - outVel[i] = Proj * temp; + out_vel[i] = Proj * eta_frame_i; if(d_debug.getValue()) - std::cout<< "Frame velocity : "<< i << " = " << temp<< std::endl; + std::cout<< "Frame velocity : "<< i << " = " << eta_frame_i<< std::endl; } dataVecOutVel[0]->endEdit(); m_index_input = 0; diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index 18b32df1..c03fe6c9 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -181,7 +181,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( // Compute the tangent Exponential SE3 vectors const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); - this->update_TangExpSE3(inDeform,curv_abs_input.ref(),curv_abs_output.ref()); + this->update_TangExpSE3(inDeform); //Get base velocity as input this is also called eta m_nodesVelocityVectors.clear(); From b3579208dcd637ed9249b2d94eb2d1ad1da21228 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Mon, 4 Dec 2023 15:18:44 +0100 Subject: [PATCH 24/71] update the branche cosseratExtension and fix some bugs --- CMakeLists.txt | 3 + docs/testScene/tuto_1_6dofs.py | 67 +++ docs/testScene/tuto_2_6dofs.py | 114 +++++ src/Cosserat/CMakeLists.txt | 3 + .../forcefield/BeamHookeLawForceField.cpp | 156 +------ .../forcefield/BeamHookeLawForceField.h | 33 +- .../forcefield/BeamHookeLawForceField.inl | 412 +++++++++--------- .../BeamHookeLawForceFieldRigid.cpp | 63 +++ .../forcefield/BeamHookeLawForceFieldRigid.h | 172 ++++++++ .../BeamHookeLawForceFieldRigid.inl | 250 +++++++++++ src/Cosserat/mapping/BaseCosserat.cpp | 27 +- src/Cosserat/mapping/BaseCosserat.h | 1 + src/Cosserat/mapping/BaseCosserat.inl | 9 +- .../mapping/DiscreteCosseratMapping.cpp | 18 +- .../mapping/DiscreteCosseratMapping.inl | 18 +- 15 files changed, 948 insertions(+), 398 deletions(-) create mode 100644 docs/testScene/tuto_1_6dofs.py create mode 100644 docs/testScene/tuto_2_6dofs.py create mode 100644 src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp create mode 100644 src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h create mode 100644 src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl diff --git a/CMakeLists.txt b/CMakeLists.txt index dd366ad9..9835d97f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -37,6 +37,8 @@ set(HEADER_FILES ${SRC_ROOT_DIR}/engine/PointsManager.inl ${SRC_ROOT_DIR}/forcefield/BeamHookeLawForceField.h ${SRC_ROOT_DIR}/forcefield/BeamHookeLawForceField.inl + ${SRC_ROOT_DIR}/forcefield/BeamHookeLawForceFieldRigid.h + ${SRC_ROOT_DIR}/forcefield/BeamHookeLawForceFieldRigid.inl ${SRC_ROOT_DIR}/forcefield/CosseratInternalActuation.h ${SRC_ROOT_DIR}/forcefield/CosseratInternalActuation.inl ${SRC_ROOT_DIR}/constraint/CosseratSlidingConstraint.h @@ -56,6 +58,7 @@ set(SOURCE_FILES ${SRC_ROOT_DIR}/mapping/RigidDistanceMapping.cpp ${SRC_ROOT_DIR}/engine/PointsManager.cpp ${SRC_ROOT_DIR}/forcefield/BeamHookeLawForceField.cpp + ${SRC_ROOT_DIR}/forcefield/BeamHookeLawForceFieldRigid.cpp ${SRC_ROOT_DIR}/forcefield/CosseratInternalActuation.cpp ${SRC_ROOT_DIR}/constraint/CosseratSlidingConstraint.cpp ${SRC_ROOT_DIR}/mapping/LegendrePolynomialsMapping.cpp diff --git a/docs/testScene/tuto_1_6dofs.py b/docs/testScene/tuto_1_6dofs.py new file mode 100644 index 00000000..664ca37c --- /dev/null +++ b/docs/testScene/tuto_1_6dofs.py @@ -0,0 +1,67 @@ +# -*- coding: utf-8 -*- + +import Sofa + +stiffness_param = 1.e10 +beam_radius = 1. + + +def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, + angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", + points="0", template="Rigid3d") + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec6d', name='cosserat_state', + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceFieldRigid', crossSectionShape='circular', + length=list_sections_length, radius=2., youngModulus=1.e4, + poissonRatio=0.4) + return cosserat_coordinate_node + + +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', + name="FramesMO", position=framesF, showIndices=1, showObject=1, + showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, name='cosseratMapping', + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node + + +def createScene(root_node): + root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') + root_node.gravity = [0, 0., 0] + # + base_node = _add_rigid_base(root_node) + + # + cos_nul_state = [0.0, 0.0, 0.0, 0., 0., 0.] # torsion, y_bending, z_bending + bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] + list_sections_length = [10, 10, 10] + bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) + + section_curv_abs = [0, 10, 20, 30] + frames_curv_abs = [0, 10, 20, 30] + cosserat_G_frames = [[0., 0, 0, 0, 0, 0, 1], [10., 0, 0, 0, 0, 0, 1], [20., 0, 0, 0, 0, 0, 1], + [30., 0, 0, 0, 0, 0, 1]] + _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + + return root_node diff --git a/docs/testScene/tuto_2_6dofs.py b/docs/testScene/tuto_2_6dofs.py new file mode 100644 index 00000000..d7ec18c0 --- /dev/null +++ b/docs/testScene/tuto_2_6dofs.py @@ -0,0 +1,114 @@ +# -*- coding: utf-8 -*- +from useful.header import addHeader, addSolverNode, addVisual + +stiffness_param = 1.e10 +beam_radius = 1. + +nb_sections = 6 +nb_frames = 6 +beam_length = 30 + + +def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, + angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", + points="0", template="Rigid3d") + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + print(f' ===> bendind state : {bending_states}') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec6d', name='cosserat_state', + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceFieldRigid', crossSectionShape='circular', + length=list_sections_length, radius=2., youngModulus=1.e3, + poissonRatio=0.4) + return cosserat_coordinate_node + + +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=5): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', + name="FramesMO", position=framesF, showIndices=0., showObject=0, + showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, name='cosseratMapping', + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=1, radius=_radius) + return cosserat_in_Sofa_frame_node + + +def createScene(root_node): + root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') +# root_node.gravity = [0, 0, 0] +# root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass='0.0') +# root_node.addObject('SparseLDLSolver', name='solver') + + addHeader(root_node) + root_node.gravity = [0, -9.81, 0.] + + solver_node = addSolverNode(root_node, name="solver_node") + + # Add rigid base + base_node = _add_rigid_base(solver_node) + + # build beam geometry + + length_s = beam_length/float(nb_sections) + bending_states = [] + list_sections_length = [] + temp = 0. # where to start the base position + section_curv_abs = [0.] # section/segment curve abscissa + + for i in range(nb_sections): + bending_states.append([0, 0., 0., 0, 0., 0.]) # torsion, y-bending, z-bending, elongation, y-shear and z-shear + list_sections_length.append((((i + 1) * length_s) - i * length_s)) + temp += list_sections_length[i] + section_curv_abs.append(temp) +# bending_states[nb_sections-1] = [0, 0.0, 0.3, 0, 0., 0.] + bending_states[nb_sections-1] = [0., 0., 0., 0.2, 0., 0.] + + + print (f'The bending list : {bending_states}') + print (f'The section_curv_abs list : {section_curv_abs}') + + # call add cosserat state and force field + bending_node = _add_cosserat_state(solver_node, bending_states, list_sections_length) + + # comment : ??? + + length_f = beam_length/float(nb_frames) + cosserat_G_frames = [] + frames_curv_abs = [] + cable_position_f = [] # need sometimes for drawing segment + x, y, z = 0, 0, 0 + + for i in range(nb_frames+1): + sol = i * length_f + cosserat_G_frames.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + frames_curv_abs.append(sol + x) + + cosserat_G_frames[nb_frames] = [beam_length + x, y, z, 0, 0, 0, 1] + cable_position_f[nb_frames] = [beam_length + x, y, z] + frames_curv_abs[nb_frames] = beam_length + x + + cosserat_frames = _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + + ## Add a force component to test the stretch +# applied_force =[0, -1.e8, 0, 0, 0, 0] +# const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=10, indices=nb_frames, forces=applied_force) + + return root_node diff --git a/src/Cosserat/CMakeLists.txt b/src/Cosserat/CMakeLists.txt index ceff3af7..dbcf73be 100644 --- a/src/Cosserat/CMakeLists.txt +++ b/src/Cosserat/CMakeLists.txt @@ -21,6 +21,8 @@ set(HEADER_FILES forcefield/BeamHookeLawForceField.h forcefield/BeamHookeLawForceField.inl + forcefield/BeamHookeLawForceFieldRigid.h + forcefield/BeamHookeLawForceFieldRigid.inl forcefield/CosseratInternalActuation.h forcefield/CosseratInternalActuation.inl forcefield/MyUniformVelocityDampingForceField.h @@ -46,6 +48,7 @@ set(SOURCE_FILES mapping/LegendrePolynomialsMapping.cpp forcefield/BeamHookeLawForceField.cpp + forcefield/BeamHookeLawForceFieldRigid.cpp forcefield/CosseratInternalActuation.cpp forcefield/MyUniformVelocityDampingForceField.cpp diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp index 698e22cf..aa6b94e1 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp @@ -27,164 +27,25 @@ * Contact information: https://project.inria.fr/softrobot/contact/ * * * ******************************************************************************/ -#define SOFA_COSSERAT_BEAMHOOKELAWFORCEFIELD_CPP +#define SOFA_COSSERAT_CPP_BeamHookeLawForceField #include "BeamHookeLawForceField.inl" #include <sofa/core/ObjectFactory.h> -using namespace sofa::defaulttype; - namespace sofa::component::forcefield { -template<> -void BeamHookeLawForceField<defaulttype::Vec6fTypes>::reinit() -{ - // Precompute and store values - Real Iy, Iz, J, A; - if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section - { - Real Ly = d_lengthY.getValue(); - Real Lz = d_lengthZ.getValue(); - - const Real LyLzLzLz = Ly * Lz * Lz * Lz; - const Real LzLyLyLy = Lz * Ly * Ly * Ly; - - Iy = LyLzLzLz / 12.0; - Iz = LzLyLyLy / 12.0; - J = Iy + Iz; - A = Ly * Lz; - - } - else //circular cross-section - { - msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; - - Real r = d_radius.getValue(); - Real rInner = d_innerRadius.getValue(); - const Real r4 = r * r * r * r; - const Real rInner4 = rInner * rInner * rInner * rInner; - - Iy = M_PI * (r4 - rInner4) / 4.0; - Iz = Iy; - J = Iy + Iz; - A = M_PI * (r * r - rInner4); - - } - m_crossSectionArea = A; - - if( d_useInertiaParams.getValue() ) - { - msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; - m_K_section66[0][0] = d_GI.getValue(); - m_K_section66[1][1] = d_EIy.getValue(); - m_K_section66[2][2] = d_EIz.getValue(); - m_K_section66[3][3] = d_EA.getValue(); - m_K_section66[4][4] = d_GA.getValue(); - m_K_section66[5][5] = d_GA.getValue(); - } - else - { - //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix - Real E = d_youngModulus.getValue(); - Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); - //Translational Stiffness (X, Y, Z directions): - // Gs * J(i): Shearing modulus times the second moment of the area (torsional stiffness). - // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). - m_K_section66[0][0] = G*J; - m_K_section66[1][1] = E*Iy; - m_K_section66[2][2] = E*Iz; - //Rotational Stiffness (X, Y, Z directions): - //E * A: Young's modulus times the cross-sectional area (axial stiffness). - //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). - m_K_section66[3][3] = E*A; - m_K_section66[4][4] = G*A; - m_K_section66[5][5] = G*A; - } -} - - -template<> -void BeamHookeLawForceField<defaulttype::Vec6fTypes>::addForce(const MechanicalParams* mparams, - DataVecDeriv& d_f, - const DataVecCoord& d_x, - const DataVecDeriv& d_v) -{ - SOFA_UNUSED(d_v); - SOFA_UNUSED(mparams); - - if(!this->getMState()) { - msg_info("BeamHookeLawForceField") << "No Mechanical State found, no force will be computed..." << "\n"; - compute_df=false; - return; - } - VecDeriv& f = *d_f.beginEdit(); - const VecCoord& x = d_x.getValue(); - // get the rest position (for non straight shape) - const VecCoord& x0 = this->mstate->read(VecCoordId::restPosition())->getValue(); - - f.resize(x.size()); - unsigned int sz = d_length.getValue().size(); - if(x.size()!= sz){ - msg_warning("BeamHookeLawForceField")<<" length : "<< sz <<"should have the same size as x... "<< x.size() <<"\n"; - compute_df = false; - return; - } - for (unsigned int i=0; i<x.size(); i++) - f[i] -= (m_K_section66 * (x[i] - x0[i])) * d_length.getValue()[i]; - - d_f.endEdit(); - -} - -template<> -void BeamHookeLawForceField<defaulttype::Vec6fTypes>::addDForce(const MechanicalParams* mparams, - DataVecDeriv& d_df , - const DataVecDeriv& d_dx) -{ - if (!compute_df) - return; - - WriteAccessor< DataVecDeriv > df = d_df; - ReadAccessor< DataVecDeriv > dx = d_dx; - Real kFactor = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); - - df.resize(dx.size()); - for (unsigned int i=0; i<dx.size(); i++) - df[i] -= (m_K_section66 * dx[i])*kFactor* d_length.getValue()[i]; -} - -template<> -void BeamHookeLawForceField<defaulttype::Vec6Types>::addKToMatrix(const MechanicalParams* mparams, - const MultiMatrixAccessor* matrix) -{ - MultiMatrixAccessor::MatrixRef mref = matrix->getMatrix(this->mstate); - BaseMatrix* mat = mref.matrix; - unsigned int offset = mref.offset; - Real kFact = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); - - const VecCoord& pos = this->mstate->read(core::ConstVecCoordId::position())->getValue(); - for (unsigned int n=0; n<pos.size(); n++) - { - for(unsigned int i = 0; i < 6; i++) - for (unsigned int j = 0; j< 6; j++) - mat->add(offset + i + 6*n, offset + j + 6*n, -kFact * m_K_section66[i][j]*d_length.getValue()[n]); - - } -} - //////////////////////////////////////////// FACTORY ////////////////////////////////////////////// // Registering the component // see: http://wiki.sofa-framework.org/wiki/ObjectFactory // 1-RegisterObject("description") + .add<> : Register the component // 2-.add<>(true) : Set default template +using namespace sofa::defaulttype; +int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used to compute internal stress for torsion (along x) and bending (y and z)") + .add<BeamHookeLawForceField<Vec3Types> >(true) -int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used to compute internal stress for torsion " - "(along x) and bending (y and z)") - .add<BeamHookeLawForceField<Vec3Types> >(true) - .add<BeamHookeLawForceField<Vec6Types> >() - ; + ; ////////////////////////////////////////////////////////////////////////////////////////////////////// // Force template specialization for the most common sofa floating point related type. @@ -192,9 +53,6 @@ int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used t // avoid the code generation of the template for each compilation unit. // see: http://www.stroustrup.com/C++11FAQ.html#extern-templates -template class SOFA_COSSERAT_API BeamHookeLawForceField<Vec3Types>; -template class SOFA_COSSERAT_API BeamHookeLawForceField<Vec6Types>; - - +template class BeamHookeLawForceField<Vec3Types>; -} // sofa::component::forcefield +} // forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.h b/src/Cosserat/forcefield/BeamHookeLawForceField.h index a59e6e9f..d9e086f7 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.h @@ -45,8 +45,6 @@ namespace sofa::component::forcefield { using sofa::type::Vec ; -using type::Vec6; -using type::Vector3; using sofa::type::Mat ; using sofa::type::vector; using sofa::core::MechanicalParams; @@ -67,19 +65,18 @@ class BeamHookeLawForceField : public ForceField<DataTypes> public : SOFA_CLASS(SOFA_TEMPLATE(BeamHookeLawForceField, DataTypes), SOFA_TEMPLATE(ForceField, DataTypes)); - typedef typename DataTypes::Real Real ; - typedef typename DataTypes::Coord Coord ; - typedef typename DataTypes::Deriv Deriv; + typedef typename DataTypes::Real Real; typedef typename DataTypes::VecCoord VecCoord; typedef typename DataTypes::VecDeriv VecDeriv; + typedef typename DataTypes::Coord Coord; + typedef typename DataTypes::Deriv Deriv; + typedef Data<VecCoord> DataVecCoord; typedef Data<VecDeriv> DataVecDeriv; - typedef typename DataTypes::MatrixDeriv MatrixDeriv; - typedef typename sofa::core::behavior::MechanicalState<DataTypes> MechanicalState; - + typedef Vec<3, Real> Vec3; typedef Mat<3, 3, Real> Mat33; - typedef Mat<6, 6, Real> Mat66; + typedef CompressedRowSparseMatrix<Mat33> CSRMat33B66; typedef typename CompressedRowSparseMatrix<Mat33>::ColBlockConstIterator _3_3_ColBlockConstIterator; @@ -106,7 +103,7 @@ public : void addDForce(const MechanicalParams* mparams, DataVecDeriv& df , const DataVecDeriv& - dx ) override; + dx ) override; void addKToMatrix(const MechanicalParams* mparams, @@ -139,13 +136,10 @@ public : Data<Real> d_GI; Data<Real> d_GA; Data<Real> d_EA; - Data<Real> d_EIy; - Data<Real> d_EIz; - Data<bool> d_buildTorsion; + Data<Real> d_EI; bool compute_df; Mat33 m_K_section; - Mat66 m_K_section66; type::vector<Mat33> m_K_sectionList; /// Cross-section area @@ -158,16 +152,11 @@ private : /// Bring inherited attributes and function in the current lookup context. /// otherwise any access to the base::attribute would require /// the "this->" approach. -// using ForceField<DataTypes>::getContext ; -// using ForceField<DataTypes>::f_printLog ; + using ForceField<DataTypes>::getContext ; + using ForceField<DataTypes>::f_printLog ; //using ForceField<DataTypes>::mstate ; //////////////////////////////////////////////////////////////////////////// }; -#if !defined(SOFA_COSSERAT_BEAMHOOKELAWFORCEFIELD_CPP) -extern template class SOFA_COSSERAT_API BeamHookeLawForceField< defaulttype::Vec3Types>; -extern template class SOFA_COSSERAT_API BeamHookeLawForceField< defaulttype::Vec6Types>; -#endif - -} // sofa::component::forcefield +} // forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.inl b/src/Cosserat/forcefield/BeamHookeLawForceField.inl index af020430..e6e6d508 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.inl @@ -34,272 +34,260 @@ #include <sofa/core/behavior/MechanicalState.h> #include <sofa/core/behavior/ForceField.inl> #include <sofa/helper/OptionsGroup.h> // ?? -#include <iostream> -#include <algorithm> -#include <ctime> using sofa::core::behavior::MechanicalState ; using sofa::core::objectmodel::BaseContext ; using sofa::helper::ReadAccessor ; using sofa::helper::WriteAccessor ; using sofa::core::VecCoordId; + +#include <iostream> using std::cout ; using std::endl ; +#include <algorithm> +#include <ctime> + namespace sofa::component::forcefield { - using sofa::core::behavior::MultiMatrixAccessor ; - using sofa::core::behavior::BaseMechanicalState ; - using sofa::helper::WriteAccessor ; - - - template<typename DataTypes> - BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField() - : Inherit1(), - d_crossSectionShape( initData(&d_crossSectionShape, {"circular","rectangular"}, - "crossSectionShape", - "shape of the cross-section. Can be: circular (tube with external radius being radius and internal radius being innerRadius ) or rectangular (lengthY and lengthZ) . Default is circular" )), - d_youngModulus( initData( &d_youngModulus, 1.0e9, "youngModulus", "Young Modulus describes the stiffness of the material")), - d_poissonRatio( initData( &d_poissonRatio, 0.45, "poissonRatio", "poisson Ratio describes the compressibility of the material")), - d_length( initData( &d_length, "length", "length of each beam")), - d_radius( initData( &d_radius, 1.0, "radius", "external radius of the cross section (if circular)")), - d_innerRadius( initData( &d_innerRadius, 0.0, "innerRadius", "internal radius of the cross section (if circular)")), - d_lengthY( initData( &d_lengthY, 1.0, "lengthY", "side length of the cross section along local y axis (if rectangular)")), - d_lengthZ( initData( &d_lengthZ, 1.0, "lengthZ", "side length of the cross section along local z axis (if rectangular)")), - d_variantSections(initData(&d_variantSections, false, "variantSections", "In case we have variant beam sections this has to be set to true")), - d_youngModulusList(initData(&d_youngModulusList, "youngModulusList", "The list of Young modulus in case we have sections with variable physical properties")), - d_poissonRatioList(initData(&d_poissonRatioList, "poissonRatioList", "The list of poisson's ratio in case we have sections with variable physical properties")), - d_useInertiaParams(initData(&d_useInertiaParams, false, "useInertiaParams", "If the inertia parameters are given by the user, there is no longer any need to use @d_youngModulus and @d_poissonRatio.")), - d_GI(initData(&d_GI, "GI", "The inertia parameter, GI")), - d_GA(initData(&d_GA, "GA", "The inertia parameter, GA")), - d_EA(initData(&d_EA, "EA", "The inertia parameter, EA")), - d_EIy(initData(&d_EIy, "EIy", "The inertia parameter, EIy")), - d_EIz(initData(&d_EIz, "EIz", "The inertia parameter, EIz")), - d_buildTorsion(initData(&d_buildTorsion, true,"build_torsion", "build torsion or the elongation of the beam ?")) - - { - compute_df=true; - } +using sofa::core::behavior::MultiMatrixAccessor ; +using sofa::core::behavior::BaseMechanicalState ; +using sofa::helper::WriteAccessor ; - template<typename DataTypes> - BeamHookeLawForceField<DataTypes>::~BeamHookeLawForceField() - {} - template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::init() - { - Inherit1::init(); +template<typename DataTypes> +BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField() + : Inherit1(), + d_crossSectionShape( initData(&d_crossSectionShape, {"circular","rectangular"}, + "crossSectionShape", + "shape of the cross-section. Can be: circular (tube with external radius being radius and internal radius being innerRadius ) or rectangular (lengthY and lengthZ) . Default is circular" )), + d_youngModulus( initData( &d_youngModulus, 1.0e9, "youngModulus", "Young Modulus describes the stiffness of the material")), + d_poissonRatio( initData( &d_poissonRatio, 0.45, "poissonRatio", "poisson Ratio describes the compressibility of the material")), + d_length( initData( &d_length, "length", "length of each beam")), + d_radius( initData( &d_radius, 1.0, "radius", "external radius of the cross section (if circular)")), + d_innerRadius( initData( &d_innerRadius, 0.0, "innerRadius", "internal radius of the cross section (if circular)")), + d_lengthY( initData( &d_lengthY, 1.0, "lengthY", "side length of the cross section along local y axis (if rectangular)")), + d_lengthZ( initData( &d_lengthZ, 1.0, "lengthZ", "side length of the cross section along local z axis (if rectangular)")), + d_variantSections(initData(&d_variantSections, false, "variantSections", "In case we have variant beam sections this has to be set to true")), + d_youngModulusList(initData(&d_youngModulusList, "youngModulusList", "The list of Young modulus in case we have sections with variable physical properties")), + d_poissonRatioList(initData(&d_poissonRatioList, "poissonRatioList", "The list of poisson's ratio in case we have sections with variable physical properties")), + d_useInertiaParams(initData(&d_useInertiaParams, false, "useInertiaParams", "If the inertia parameters are given by the user, there is no longer any need to use @d_youngModulus and @d_poissonRatio.")), + d_GI(initData(&d_GI, "GI", "The inertia parameter, GI")), + d_GA(initData(&d_GA, "GA", "The inertia parameter, GA")), + d_EA(initData(&d_EA, "EA", "The inertia parameter, EA")), + d_EI(initData(&d_EI, "EI", "The inertia parameter, EI")) +{ + compute_df=true; +} - reinit(); - } +template<typename DataTypes> +BeamHookeLawForceField<DataTypes>::~BeamHookeLawForceField() +{} +template<typename DataTypes> +void BeamHookeLawForceField<DataTypes>::init() +{ + Inherit1::init(); + reinit(); +} - /*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties +/*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties related to the cross-section of the beams. It calculates the area moment of inertia (Iy and Iz), the polar moment of inertia (J), and the cross-sectional area (A). - These calculations depend on the chosen cross-section shape, either circular or rectangular. - The formulas used for these calculations are based on standard equations for these properties.*/ - template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField::reinit() + These calculations depend on the chosen cross-section shape, either circular or rectangular. T + he formulas used for these calculations are based on standard equations for these properties.*/ +template<typename DataTypes> +void BeamHookeLawForceField<DataTypes>::reinit() +{ + // Precompute and store values + Real Iy, Iz, J, A; + if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section { - // Precompute and store values - Real Iy, Iz, J, A; - if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section - { - Real Ly = d_lengthY.getValue(); - Real Lz = d_lengthZ.getValue(); + Real Ly = d_lengthY.getValue(); + Real Lz = d_lengthZ.getValue(); - const Real LyLzLzLz = Ly * Lz * Lz * Lz; - const Real LzLyLyLy = Lz * Ly * Ly * Ly; + const Real LyLzLzLz = Ly * Lz * Lz * Lz; + const Real LzLyLyLy = Lz * Ly * Ly * Ly; - Iy = LyLzLzLz / 12.0; - Iz = LzLyLyLy / 12.0; - J = Iy + Iz; - A = Ly * Lz; + Iy = LyLzLzLz / 12.0; + Iz = LzLyLyLy / 12.0; + J = Iy + Iz; + A = Ly * Lz; - } - else //circular cross-section - { - msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; + } + else //circular cross-section + { + msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; - Real r = d_radius.getValue(); - Real rInner = d_innerRadius.getValue(); - const Real r4 = r * r * r * r; - const Real rInner4 = rInner * rInner * rInner * rInner; + Real r = d_radius.getValue(); + Real rInner = d_innerRadius.getValue(); + const Real r4 = r * r * r * r; + const Real rInner4 = rInner * rInner * rInner * rInner; - Iy = M_PI * (r4 - rInner4) / 4.0; - Iz = Iy; - J = Iy + Iz; - A = M_PI * (r * r - rInner4); + Iy = M_PI * (r4 - rInner4) / 4.0; + Iz = Iy; + J = Iy + Iz; + A = M_PI * (r * r - rInner4); - } - m_crossSectionArea = A; + } + m_crossSectionArea = A; + + if(!d_variantSections.getValue()) + { + if(!d_useInertiaParams.getValue()) + { + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); - if(d_variantSections.getValue()) + m_K_section[0][0] = G*J; + m_K_section[1][1] = E*Iy; + m_K_section[2][2] = E*Iz; + } + else { - /*If the d_variantSections flag is set to true, it implies that multi-section beams are used for + msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation " + "of the stiffness matrix."; + m_K_section[0][0] = d_GI.getValue(); + m_K_section[1][1] = d_EI.getValue(); + m_K_section[2][2] = d_EI.getValue(); + } + + }else { + /*If the d_variantSections flag is set to true, it implies that multi-section beams are used for the simulation. In this case, the code calculates and initializes a list of stiffness matrices (m_K_sectionList) for each section. The properties of each section, such as Young's modulus and Poisson's ratio, are specified in the d_youngModulusList and d_poissonRatioList data.*/ - msg_info("BeamHookeLawForceField")<< "Multi section beam are used for the simulation!"; - m_K_sectionList.clear(); + msg_info("BeamHookeLawForceField")<< "Multi section beam are used for the simulation!"; + m_K_sectionList.clear(); - const size_t szL = d_length.getValue().size(); + const size_t szL = d_length.getValue().size(); - if((szL != d_poissonRatioList.getValue().size())||(szL != d_youngModulusList.getValue().size())){ - msg_error("BeamHookeLawForceField")<< "Please the size of the data length, youngModulusList and " - "poissonRatioList should be the same !"; - return; - } + if((szL != d_poissonRatioList.getValue().size())||(szL != d_youngModulusList.getValue().size())){ + msg_error("BeamHookeLawForceField")<< "Please the size of the data length, youngModulusList and " + "poissonRatioList should be the same !"; + return; + } - /*Stiffness Matrix Initialization: Next, the code initializes the stiffness matrix m_K_section + /*Stiffness Matrix Initialization: Next, the code initializes the stiffness matrix m_K_section based on the properties of the cross-section and the material's Young's modulus (E) and Poisson's ratio. The stiffness matrix is essential for computing forces and simulating beam behavior.*/ - for(size_t k=0; k<szL; k++) - { - Mat33 _m_K_section; - Real E = d_youngModulusList.getValue()[k]; - Real G = E/(2.0*(1.0+d_poissonRatioList.getValue()[k])); - - - - _m_K_section[0][0] = G*J; - _m_K_section[1][1] = E*Iy; - _m_K_section[2][2] = E*Iz; - m_K_sectionList.push_back(_m_K_section); - } - msg_info("BeamHookeLawForceField")<< "If you plan to use a multi section beam with (different " - "mechanical properties) and pre-calculated inertia parameters " - "(GI, GA, etc.), this is not yet supported."; - - }else + for(size_t k=0; k<szL; k++) { - if( d_useInertiaParams.getValue() ) - { - msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; - m_K_section[0][0] = d_GI.getValue(); - m_K_section[1][1] = d_EIy.getValue(); - m_K_section[2][2] = d_EIz.getValue(); - } - else - { - //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix - Real E = d_youngModulus.getValue(); - Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); - //Translational Stiffness (X, Y, Z directions): - // Gs * I(i): Shearing modulus times the second moment of the area (torsional stiffness). - // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). - m_K_section[0][0] = G*J; - m_K_section[1][1] = E*Iy; - m_K_section[2][2] = E*Iz; - //Rotational Stiffness (X, Y, Z directions): - //E * A: Young's modulus times the cross-sectional area (axial stiffness). - //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). - } + Mat33 _m_K_section; + Real E = d_youngModulusList.getValue()[k]; + Real G = E/(2.0*(1.0+d_poissonRatioList.getValue()[k])); + + _m_K_section[0][0] = G*J; + _m_K_section[1][1] = E*Iy; + _m_K_section[2][2] = E*Iz; + m_K_sectionList.push_back(_m_K_section); } + msg_info("BeamHookeLawForceField")<< "If you plan to use a multi section beam with (different " + "mechanical properties) and pre-calculated inertia parameters " + "(GI, GA, etc.), this is not yet supported."; } +} - template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField::addForce(const MechanicalParams* mparams, - DataVecDeriv& d_f, - const DataVecCoord& d_x, - const DataVecDeriv& d_v) - { - SOFA_UNUSED(d_v); - SOFA_UNUSED(mparams); - - if(!this->getMState()) { - msg_info("BeamHookeLawForceField") << "No Mechanical State found, no force will be computed..." << "\n"; - compute_df=false; - return; - } - VecDeriv& f = *d_f.beginEdit(); - const VecCoord& x = d_x.getValue(); - // get the rest position (for non straight shape) - const VecCoord& x0 = this->mstate->read(VecCoordId::restPosition())->getValue(); - - f.resize(x.size()); - unsigned int sz = d_length.getValue().size(); - if(x.size()!= sz){ - msg_warning("BeamHookeLawForceField")<<" length : "<< sz <<"should have the same size as x... "<< x.size() <<"\n"; - compute_df = false; - return; - } - - if(!d_variantSections.getValue()) - for (unsigned int i=0; i<x.size(); i++){ -// Vector3 v = Vector3(x[i][0] - x0[i][0], x[i][1] - x0[i][1], x[i][2] - x0[i][2]); - f[i] -= (m_K_section * (x[i] - x0[i])) * d_length.getValue()[i]; - } - else - for (unsigned int i=0; i<x.size(); i++) - f[i] -= (m_K_sectionList[i] * (x[i] - x0[i])) * d_length.getValue()[i]; - d_f.endEdit(); +template<typename DataTypes> +void BeamHookeLawForceField<DataTypes>::addForce(const MechanicalParams* mparams, + DataVecDeriv& d_f, + const DataVecCoord& d_x, + const DataVecDeriv& d_v) +{ + SOFA_UNUSED(d_v); + SOFA_UNUSED(mparams); + if(!this->getMState()) { + msg_info("BeamHookeLawForceField") << "No Mechanical State found, no force will be computed..." << "\n"; + compute_df=false; + return; + } + VecDeriv& f = *d_f.beginEdit(); + const VecCoord& x = d_x.getValue(); + // get the rest position (for non straight shape) + const VecCoord& x0 = this->mstate->read(VecCoordId::restPosition())->getValue(); + + f.resize(x.size()); + unsigned int sz = d_length.getValue().size(); + if(x.size()!= sz){ + msg_warning("BeamHookeLawForceField")<<" length : "<< sz <<"should have the same size as x... "<< x.size() <<"\n"; + compute_df = false; + return; } - template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::addDForce(const MechanicalParams* mparams, - DataVecDeriv& d_df , const DataVecDeriv& d_dx) - { - if (!compute_df) - return; + if(!d_variantSections.getValue()) + for (unsigned int i=0; i<x.size(); i++) + f[i] -= (m_K_section * (x[i] - x0[i])) * d_length.getValue()[i]; + else + for (unsigned int i=0; i<x.size(); i++) + f[i] -= (m_K_sectionList[i] * (x[i] - x0[i])) * d_length.getValue()[i]; + d_f.endEdit(); - WriteAccessor< DataVecDeriv > df = d_df; - ReadAccessor< DataVecDeriv > dx = d_dx; - Real kFactor = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); +} - df.resize(dx.size()); - if(!d_variantSections.getValue()) - for (unsigned int i=0; i<dx.size(); i++) - df[i] -= (m_K_section * dx[i])*kFactor* d_length.getValue()[i]; - else - for (unsigned int i=0; i<dx.size(); i++) - df[i] -= (m_K_sectionList[i] * dx[i])*kFactor* d_length.getValue()[i]; - } +template<typename DataTypes> +void BeamHookeLawForceField<DataTypes>::addDForce(const MechanicalParams* mparams, + DataVecDeriv& d_df , + const DataVecDeriv& d_dx) +{ + if (!compute_df) + return; + + WriteAccessor< DataVecDeriv > df = d_df; + ReadAccessor< DataVecDeriv > dx = d_dx; + Real kFactor = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + df.resize(dx.size()); + if(!d_variantSections.getValue()) + for (unsigned int i=0; i<dx.size(); i++) + df[i] -= (m_K_section * dx[i])*kFactor* d_length.getValue()[i]; + else + for (unsigned int i=0; i<dx.size(); i++) + df[i] -= (m_K_sectionList[i] * dx[i])*kFactor* d_length.getValue()[i]; +} + +template<typename DataTypes> +double BeamHookeLawForceField<DataTypes>::getPotentialEnergy(const MechanicalParams* mparams, + const DataVecCoord& d_x) const +{ + SOFA_UNUSED(mparams); + SOFA_UNUSED(d_x); - template<typename DataTypes> - double BeamHookeLawForceField<DataTypes>::getPotentialEnergy(const MechanicalParams* mparams, - const DataVecCoord& d_x) const - { - SOFA_UNUSED(mparams); - SOFA_UNUSED(d_x); + return 0.0; +} - return 0.0; - } +template<typename DataTypes> +void BeamHookeLawForceField<DataTypes>::addKToMatrix(const MechanicalParams* mparams, + const MultiMatrixAccessor* matrix) +{ + MultiMatrixAccessor::MatrixRef mref = matrix->getMatrix(this->mstate); + BaseMatrix* mat = mref.matrix; + unsigned int offset = mref.offset; + Real kFact = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); - template<typename DataTypes> - void BeamHookeLawForceField<DataTypes>::addKToMatrix(const MechanicalParams* mparams, - const MultiMatrixAccessor* matrix) + const VecCoord& pos = this->mstate->read(core::ConstVecCoordId::position())->getValue(); + for (unsigned int n=0; n<pos.size(); n++) { - MultiMatrixAccessor::MatrixRef mref = matrix->getMatrix(this->mstate); - BaseMatrix* mat = mref.matrix; - unsigned int offset = mref.offset; - Real kFact = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); - - const VecCoord& pos = this->mstate->read(core::ConstVecCoordId::position())->getValue(); - for (unsigned int n=0; n<pos.size(); n++) - { - if(!d_variantSections.getValue()) - for(unsigned int i = 0; i < 3; i++) - for (unsigned int j = 0; j< 3; j++) - mat->add(offset + i + 3*n, offset + j + 3*n, -kFact * m_K_section[i][j]*d_length.getValue()[n]); - else - for(unsigned int i = 0; i < 3; i++) - for (unsigned int j = 0; j< 3; j++) - mat->add(offset + i + 3*n, offset + j + 3*n, -kFact * m_K_sectionList[n][i][j] * d_length.getValue()[n]); - } + if(!d_variantSections.getValue()) + for(unsigned int i = 0; i < 3; i++) + for (unsigned int j = 0; j< 3; j++) + mat->add(offset + i + 3*n, offset + j + 3*n, -kFact * m_K_section[i][j]*d_length.getValue()[n]); + else + for(unsigned int i = 0; i < 3; i++) + for (unsigned int j = 0; j< 3; j++) + mat->add(offset + i + 3*n, offset + j + 3*n, -kFact * m_K_sectionList[n][i][j] * d_length.getValue()[n]); } +} - template<typename DataTypes> - typename BeamHookeLawForceField<DataTypes>::Real BeamHookeLawForceField<DataTypes>::getRadius() - { - return d_radius.getValue(); - } +template<typename DataTypes> +typename BeamHookeLawForceField<DataTypes>::Real BeamHookeLawForceField<DataTypes>::getRadius() +{ + return d_radius.getValue(); +} } // forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp new file mode 100644 index 00000000..8671698f --- /dev/null +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp @@ -0,0 +1,63 @@ +/****************************************************************************** +* SOFA, Simulation Open-Framework Architecture * +* (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * +* * +* This library is free software; you can redistribute it and/or modify it * +* under the terms of the GNU Lesser General Public License as published by * +* the Free Software Foundation; either version 2.1 of the License, or (at * +* your option) any later version. * +* * +* This library is distributed in the hope that it will be useful, but WITHOUT * +* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * +* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * +* for more details. * +* * +* You should have received a copy of the GNU Lesser General Public License * +* along with this library; if not, write to the Free Software Foundation, * +* Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * +******************************************************************************* +* Plugin SoftRobots v1.0 * +* * +* This plugin is also distributed under the GNU LGPL (Lesser General * +* Public License) license with the same conditions than SOFA. * +* * +* Contributors: Defrost team (INRIA, University of Lille, CNRS, * +* Ecole Centrale de Lille) * +* * +* Contact information: https://project.inria.fr/softrobot/contact/ * +* * +******************************************************************************/ +#define SOFA_COSSERAT_BeamHookeLawForceFieldRigid_CPP +#include "BeamHookeLawForceFieldRigid.inl" + +#include <sofa/core/ObjectFactory.h> + +using namespace sofa::defaulttype; + +namespace sofa::component::forcefield +{ + + +//////////////////////////////////////////// FACTORY ////////////////////////////////////////////// +// Registering the component +// see: http://wiki.sofa-framework.org/wiki/ObjectFactory +// 1-RegisterObject("description") + .add<> : Register the component +// 2-.add<>(true) : Set default template + + +int BeamHookeLawForceFieldRigidClass = core::RegisterObject("This component is used to compute internal stress for torsion " + "(along x) and bending (y and z)") + .add<BeamHookeLawForceFieldRigid<Vec6Types> >() + ; +////////////////////////////////////////////////////////////////////////////////////////////////////// + +// Force template specialization for the most common sofa floating point related type. +// This goes with the extern template declaration in the .h. Declaring extern template +// avoid the code generation of the template for each compilation unit. +// see: http://www.stroustrup.com/C++11FAQ.html#extern-templates + +template class SOFA_COSSERAT_API BeamHookeLawForceFieldRigid<Vec6Types>; + + + +} // sofa::component::forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h new file mode 100644 index 00000000..89001a0c --- /dev/null +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h @@ -0,0 +1,172 @@ +/****************************************************************************** +* SOFA, Simulation Open-Framework Architecture * +* (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * +* * +* This library is free software; you can redistribute it and/or modify it * +* under the terms of the GNU Lesser General Public License as published by * +* the Free Software Foundation; either version 2.1 of the License, or (at * +* your option) any later version. * +* * +* This library is distributed in the hope that it will be useful, but WITHOUT * +* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * +* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * +* for more details. * +* * +* You should have received a copy of the GNU Lesser General Public License * +* along with this library; if not, write to the Free Software Foundation, * +* Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * +******************************************************************************* +* Plugin SoftRobots v1.0 * +* * +* This plugin is also distributed under the GNU LGPL (Lesser General * +* Public License) license with the same conditions than SOFA. * +* * +* Contributors: Defrost team (INRIA, University of Lille, CNRS, * +* Ecole Centrale de Lille) * +* * +* Contact information: https://project.inria.fr/softrobot/contact/ * +* * +******************************************************************************/ +#pragma once +#include <Cosserat/config.h> + +#include <sofa/type/Vec.h> +#include <sofa/type/Mat.h> +#include <sofa/core/behavior/MechanicalState.h> +#include <sofa/core/objectmodel/Data.h> +#include <sofa/core/MechanicalParams.h> +#include <sofa/linearalgebra/CompressedRowSparseMatrix.h> +#include <sofa/core/behavior/MultiMatrixAccessor.h> +#include <sofa/core/behavior/ForceField.inl> +#include <sofa/linearalgebra/BaseMatrix.h> +#include <sofa/helper/OptionsGroup.h> + +namespace sofa::component::forcefield +{ + +using sofa::type::Vec ; +using type::Vec6; +using type::Vector3; +using sofa::type::Mat ; +using sofa::type::vector; +using sofa::core::MechanicalParams; +using sofa::linearalgebra::BaseMatrix; +using sofa::core::behavior::ForceField ; +using sofa::linearalgebra::CompressedRowSparseMatrix ; +using sofa::core::behavior::MultiMatrixAccessor ; + +using sofa::helper::OptionsGroup; + +/** + * This component is used to compute the Hooke's law on a beam computed on strain / stress + * Only bending and torsion strain / stress are considered here +*/ +template<typename DataTypes> +class BeamHookeLawForceFieldRigid : public ForceField<DataTypes> +{ +public : + SOFA_CLASS(SOFA_TEMPLATE(BeamHookeLawForceFieldRigid, DataTypes), SOFA_TEMPLATE(ForceField, DataTypes)); + + typedef typename DataTypes::Real Real ; + typedef typename DataTypes::Coord Coord ; + typedef typename DataTypes::Deriv Deriv; + typedef typename DataTypes::VecCoord VecCoord; + typedef typename DataTypes::VecDeriv VecDeriv; + typedef Data<VecCoord> DataVecCoord; + typedef Data<VecDeriv> DataVecDeriv; + + typedef typename DataTypes::MatrixDeriv MatrixDeriv; + typedef typename sofa::core::behavior::MechanicalState<DataTypes> MechanicalState; + + typedef Mat<3, 3, Real> Mat33; + typedef Mat<6, 6, Real> Mat66; + typedef CompressedRowSparseMatrix<Mat33> CSRMat33B66; + + typedef typename CompressedRowSparseMatrix<Mat33>::ColBlockConstIterator _3_3_ColBlockConstIterator; + typedef typename CompressedRowSparseMatrix<Mat33>::RowBlockConstIterator _3_3_RowBlockConstIterator; + typedef typename CompressedRowSparseMatrix<Mat33>::BlockConstAccessor _3_3_BlockConstAccessor; + typedef typename CompressedRowSparseMatrix<Mat33>::BlockAccessor _3_3_BlockAccessor; + + +public : + BeamHookeLawForceFieldRigid(); + virtual ~BeamHookeLawForceFieldRigid(); + + ////////////////////////// Inherited from BaseObject ///////////////////////// + void init() override; + void reinit() override; + /////////////////////////////////////////////////////////////////////////// + + ////////////////////////// Inherited from ForceField ///////////////////////// + void addForce(const MechanicalParams* mparams, + DataVecDeriv& f , + const DataVecCoord& x , + const DataVecDeriv& v) override; + + void addDForce(const MechanicalParams* mparams, + DataVecDeriv& df , + const DataVecDeriv& + dx ) override; + + + void addKToMatrix(const MechanicalParams* mparams, + const MultiMatrixAccessor* matrix) override; + + double getPotentialEnergy(const MechanicalParams* mparams, + const DataVecCoord& x) const override; + //////////////////////////////////////////////////////////////////////////// + + Real getRadius(); + +protected: + Data<helper::OptionsGroup> d_crossSectionShape; + Data<Real> d_youngModulus; /// youngModulus + Data<Real> d_poissonRatio; /// poissonRatio + Data<type::vector<Real>> d_length ; /// length of each beam + + /// Circular Cross Section + Data<Real> d_radius; + Data<Real> d_innerRadius; + /// Rectangular Cross Section + Data<Real> d_lengthY; + Data<Real> d_lengthZ; + //In case we have a beam with different properties per section + Data<bool> d_variantSections; /// bool to identify different beams sections + Data<type::vector<Real>> d_youngModulusList; /// youngModulus + Data<type::vector<Real>> d_poissonRatioList; /// poissonRatio + /// If the inertia parameters are given by the user, there is no longer any need to use YG. + Data<bool> d_useInertiaParams; + Data<Real> d_GI; + Data<Real> d_GA; + Data<Real> d_EA; + Data<Real> d_EIy; + Data<Real> d_EIz; + Data<bool> d_buildTorsion; + + bool compute_df; + Mat33 m_K_section; + Mat66 m_K_section66; + type::vector<Mat33> m_K_sectionList; + + /// Cross-section area + Real m_crossSectionArea; + +private : + + ////////////////////////// Inherited attributes //////////////////////////// + /// https://gcc.gnu.org/onlinedocs/gcc/Name-lookup.html + /// Bring inherited attributes and function in the current lookup context. + /// otherwise any access to the base::attribute would require + /// the "this->" approach. +// using ForceField<DataTypes>::getContext ; +// using ForceField<DataTypes>::f_printLog ; + //using ForceField<DataTypes>::mstate ; + //////////////////////////////////////////////////////////////////////////// +}; + +#if !defined(SOFA_COSSERAT_BeamHookeLawForceFieldRigid_CPP) +extern template class SOFA_COSSERAT_API BeamHookeLawForceFieldRigid< defaulttype::Vec6Types>; +#endif + + +} // sofa::component::forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl new file mode 100644 index 00000000..8ca552a0 --- /dev/null +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl @@ -0,0 +1,250 @@ +/****************************************************************************** +* SOFA, Simulation Open-Framework Architecture * +* (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * +* * +* This library is free software; you can redistribute it and/or modify it * +* under the terms of the GNU Lesser General Public License as published by * +* the Free Software Foundation; either version 2.1 of the License, or (at * +* your option) any later version. * +* * +* This library is distributed in the hope that it will be useful, but WITHOUT * +* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * +* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * +* for more details. * +* * +* You should have received a copy of the GNU Lesser General Public License * +* along with this library; if not, write to the Free Software Foundation, * +* Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * +******************************************************************************* +* Plugin SoftRobots v1.0 * +* * +* This plugin is also distributed under the GNU LGPL (Lesser General * +* Public License) license with the same conditions than SOFA. * +* * +* Contributors: Defrost team (INRIA, University of Lille, CNRS, * +* Ecole Centrale de Lille) * +* * +* Contact information: https://project.inria.fr/softrobot/contact/ * +* * +******************************************************************************/ +#pragma once +#include "BeamHookeLawForceFieldRigid.h" + +#include <sofa/linearalgebra/FullVector.h> +#include <sofa/core/behavior/MechanicalState.h> +#include <sofa/core/behavior/ForceField.inl> +#include <sofa/helper/OptionsGroup.h> // ?? +#include <iostream> +#include <algorithm> +#include <ctime> + +using sofa::core::behavior::MechanicalState ; +using sofa::core::objectmodel::BaseContext ; +using sofa::helper::ReadAccessor ; +using sofa::helper::WriteAccessor ; +using sofa::core::VecCoordId; +using std::cout ; +using std::endl ; + +namespace sofa::component::forcefield +{ + using sofa::core::behavior::MultiMatrixAccessor ; + using sofa::core::behavior::BaseMechanicalState ; + using sofa::helper::WriteAccessor ; + + + template<typename DataTypes> + BeamHookeLawForceFieldRigid<DataTypes>::BeamHookeLawForceFieldRigid() + : Inherit1(), + d_crossSectionShape( initData(&d_crossSectionShape, {"circular","rectangular"}, + "crossSectionShape", + "shape of the cross-section. Can be: circular (tube with external radius being radius and internal radius being innerRadius ) or rectangular (lengthY and lengthZ) . Default is circular" )), + d_youngModulus( initData( &d_youngModulus, 1.0e9, "youngModulus", "Young Modulus describes the stiffness of the material")), + d_poissonRatio( initData( &d_poissonRatio, 0.45, "poissonRatio", "poisson Ratio describes the compressibility of the material")), + d_length( initData( &d_length, "length", "length of each beam")), + d_radius( initData( &d_radius, 1.0, "radius", "external radius of the cross section (if circular)")), + d_innerRadius( initData( &d_innerRadius, 0.0, "innerRadius", "internal radius of the cross section (if circular)")), + d_lengthY( initData( &d_lengthY, 1.0, "lengthY", "side length of the cross section along local y axis (if rectangular)")), + d_lengthZ( initData( &d_lengthZ, 1.0, "lengthZ", "side length of the cross section along local z axis (if rectangular)")), + d_variantSections(initData(&d_variantSections, false, "variantSections", "In case we have variant beam sections this has to be set to true")), + d_youngModulusList(initData(&d_youngModulusList, "youngModulusList", "The list of Young modulus in case we have sections with variable physical properties")), + d_poissonRatioList(initData(&d_poissonRatioList, "poissonRatioList", "The list of poisson's ratio in case we have sections with variable physical properties")), + d_useInertiaParams(initData(&d_useInertiaParams, false, "useInertiaParams", "If the inertia parameters are given by the user, there is no longer any need to use @d_youngModulus and @d_poissonRatio.")), + d_GI(initData(&d_GI, "GI", "The inertia parameter, GI")), + d_GA(initData(&d_GA, "GA", "The inertia parameter, GA")), + d_EA(initData(&d_EA, "EA", "The inertia parameter, EA")), + d_EIy(initData(&d_EIy, "EIy", "The inertia parameter, EIy")), + d_EIz(initData(&d_EIz, "EIz", "The inertia parameter, EIz")), + d_buildTorsion(initData(&d_buildTorsion, true,"build_torsion", "build torsion or the elongation of the beam ?")) + + { + compute_df=true; + } + + template<typename DataTypes> + BeamHookeLawForceFieldRigid<DataTypes>::~BeamHookeLawForceFieldRigid() + {} + + template<typename DataTypes> + void BeamHookeLawForceFieldRigid<DataTypes>::init() + { + Inherit1::init(); + reinit(); + } + + /*Cross-Section Properties Initialization: The reinit function begins by recalculating the properties + related to the cross-section of the beams. It calculates the area moment of inertia (Iy and Iz), + the polar moment of inertia (J), and the cross-sectional area (A). + These calculations depend on the chosen cross-section shape, either circular or rectangular. + The formulas used for these calculations are based on standard equations for these properties.*/ + template<typename DataTypes> + void BeamHookeLawForceFieldRigid<DataTypes>::reinit() + { + // Precompute and store values + Real Iy, Iz, J, A; + if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section + { + Real Ly = d_lengthY.getValue(); + Real Lz = d_lengthZ.getValue(); + + const Real LyLzLzLz = Ly * Lz * Lz * Lz; + const Real LzLyLyLy = Lz * Ly * Ly * Ly; + + Iy = LyLzLzLz / 12.0; + Iz = LzLyLyLy / 12.0; + J = Iy + Iz; + A = Ly * Lz; + + } + else //circular cross-section + { + msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; + + Real r = d_radius.getValue(); + Real rInner = d_innerRadius.getValue(); + const Real r4 = r * r * r * r; + const Real rInner4 = rInner * rInner * rInner * rInner; + + Iy = M_PI * (r4 - rInner4) / 4.0; + Iz = Iy; + J = Iy + Iz; + A = M_PI * (r * r - rInner4); + + } + m_crossSectionArea = A; + + if( d_useInertiaParams.getValue() ) + { + msg_info("BeamHookeLawForceFieldRigid")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; + m_K_section66[0][0] = d_GI.getValue(); + m_K_section66[1][1] = d_EIy.getValue(); + m_K_section66[2][2] = d_EIz.getValue(); + m_K_section66[3][3] = d_EA.getValue(); + m_K_section66[4][4] = d_GA.getValue(); + m_K_section66[5][5] = d_GA.getValue(); + } + else + { + //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); + //Translational Stiffness (X, Y, Z directions): + // Gs * J(i): Shearing modulus times the second moment of the area (torsional stiffness). + // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). + m_K_section66[0][0] = G*J; + m_K_section66[1][1] = E*Iy; + m_K_section66[2][2] = E*Iz; + //Rotational Stiffness (X, Y, Z directions): + //E * A: Young's modulus times the cross-sectional area (axial stiffness). + //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). + m_K_section66[3][3] = E*A; + m_K_section66[4][4] = G*A; + m_K_section66[5][5] = G*A; + } + } + + template<typename DataTypes> + void BeamHookeLawForceFieldRigid<DataTypes>::addForce(const MechanicalParams* mparams, + DataVecDeriv& d_f, + const DataVecCoord& d_x, + const DataVecDeriv& d_v) + { + SOFA_UNUSED(d_v); + SOFA_UNUSED(mparams); + + if(!this->getMState()) { + msg_info("BeamHookeLawForceField") << "No Mechanical State found, no force will be computed..." << "\n"; + compute_df=false; + return; + } + VecDeriv& f = *d_f.beginEdit(); + const VecCoord& x = d_x.getValue(); + // get the rest position (for non straight shape) + const VecCoord& x0 = this->mstate->read(VecCoordId::restPosition())->getValue(); + + f.resize(x.size()); + unsigned int sz = d_length.getValue().size(); + if(x.size()!= sz){ + msg_warning("BeamHookeLawForceField")<<" length : "<< sz <<"should have the same size as x... "<< x.size() <<"\n"; + compute_df = false; + return; + } + for (unsigned int i=0; i<x.size(); i++) + f[i] -= (m_K_section66 * (x[i] - x0[i])) * d_length.getValue()[i]; + + d_f.endEdit(); + + } + + template<typename DataTypes> + void BeamHookeLawForceFieldRigid<DataTypes>::addDForce(const MechanicalParams* mparams, + DataVecDeriv& d_df , + const DataVecDeriv& d_dx) + { + if (!compute_df) + return; + + WriteAccessor< DataVecDeriv > df = d_df; + ReadAccessor< DataVecDeriv > dx = d_dx; + Real kFactor = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + df.resize(dx.size()); + for (unsigned int i=0; i<dx.size(); i++) + df[i] -= (m_K_section66 * dx[i])*kFactor* d_length.getValue()[i]; + } + + template<typename DataTypes> + void BeamHookeLawForceFieldRigid<DataTypes>::addKToMatrix(const MechanicalParams* mparams, + const MultiMatrixAccessor* matrix) + { + MultiMatrixAccessor::MatrixRef mref = matrix->getMatrix(this->mstate); + BaseMatrix* mat = mref.matrix; + unsigned int offset = mref.offset; + Real kFact = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + const VecCoord& pos = this->mstate->read(core::ConstVecCoordId::position())->getValue(); + for (unsigned int n=0; n<pos.size(); n++) + { + for(unsigned int i = 0; i < 6; i++) + for (unsigned int j = 0; j< 6; j++) + mat->add(offset + i + 6*n, offset + j + 6*n, -kFact * m_K_section66[i][j]*d_length.getValue()[n]); + + } + } + + template<typename DataTypes> + double BeamHookeLawForceFieldRigid<DataTypes>::getPotentialEnergy(const MechanicalParams* mparams, + const DataVecCoord& d_x) const + { + SOFA_UNUSED(mparams); + SOFA_UNUSED(d_x); + + return 0.0; + } + template<typename DataTypes> + typename BeamHookeLawForceFieldRigid<DataTypes>::Real BeamHookeLawForceFieldRigid<DataTypes>::getRadius() + { + return d_radius.getValue(); + } + +} // forcefield diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index 887ba9c0..8071197c 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -34,6 +34,8 @@ template<> BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::build_Xi_hat(const Coord1& strain_i){ se3 Xi; + msg_info("BaseCosserat")<<" ===========> Build Xi Hat rigid is called "; + Xi[0][1] = -strain_i(2); Xi[0][2] = strain_i[1]; Xi[1][2] = -strain_i[0]; @@ -43,9 +45,18 @@ BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, R Xi[2][1] = -Xi(1,2); Xi[0][3] = 1.0; - Xi[0][3] = 1.0; - for (unsigned int i=3; i<6; i++) - Xi[i][3] = strain_i(i); + + std::cout <<"Before the linear part : "<< Xi <<std::endl; + for (unsigned int i=0; i<3; i++) + Xi[i][3] += strain_i(i+3); + + std::cout <<"After the linear part : "<< Xi <<std::endl; + +// se3 = [ +// 0 -screw(3) screw(2) screw(4); +// screw(3) 0 -screw(1) screw(5); +// -screw(2) screw(1) 0 screw(6); +// 0 0 0 0]; return Xi; } @@ -68,12 +79,20 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(co if(theta <= std::numeric_limits<double>::epsilon()){ g_X_n = I4 + curv_abs_x_n*Xi_hat_n; }else { +// se3 Xi_hat_n_2 = Xi_hat_n * Xi_hat_n; +// se3 Xi_hat_n_3 = Xi_hat_n_2 * Xi_hat_n; +// SReal costheta = std::cos(theta); +// SReal sintheta = std::cos(theta); +// SReal theta2 = std::pow(theta,2); +// SReal theta3 = theta2 * theta; +// g_X_n = I4 + curv_abs_x_n*Xi_hat_n + ((1.-costheta)/(theta2))*Xi_hat_n_2 +((theta-sintheta)/theta3)*Xi_hat_n_3; double scalar1= (1.0 - std::cos(curv_abs_x_n*theta))/std::pow(theta,2); double scalar2 = (curv_abs_x_n*theta - std::sin(curv_abs_x_n*theta))/std::pow(theta,3); g_X_n = I4 + curv_abs_x_n*Xi_hat_n + scalar1*Xi_hat_n*Xi_hat_n + scalar2*Xi_hat_n*Xi_hat_n*Xi_hat_n ; } + if(d_debug.getValue()) + msg_info("BaseCosserat: ")<< "matrix g_X : "<< g_X_n; - // msg_info("BaseCosserat: ")<< "matrix g_X : "<< g_X; type::Mat3x3 M; g_X_n.getsub(0,0,M); //get the rotation matrix diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 11f98415..d6eb293b 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -235,6 +235,7 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject Xi[2][0] = -Xi(0,2); Xi[2][1] = -Xi(1,2); + //@TODO: Why this , if q = 0 ???? Xi[0][3] = 1.0; return Xi; } diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index 9f42b514..f58711d3 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -101,7 +101,8 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3(const double & curv_a _g_X = I4 + curv_abs_x_n*Xi_hat_n + scalar1*Xi_hat_n*Xi_hat_n + scalar2*Xi_hat_n*Xi_hat_n*Xi_hat_n ; } - // msg_info("BaseCosserat: ")<< "matrix g_X : "<< g_X; + if(d_debug.getValue()) + msg_info("BaseCosserat: ")<< "matrix _g_X : "<< _g_X; type::Mat3x3 M; _g_X.getsub(0,0,M); //get the rotation matrix @@ -129,12 +130,12 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3(const In1VecCoord & i const Coord1 strain_n = inDeform[m_indicesVectors[i]-1]; //Cosserat reduce coordinates (strain) the size varies from 1 to 6 // The distance between the frame and the closest beam node toward the base const SReal curv_abs_x = m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) - computeExponentialSE3(curv_abs_x, strain_n,g_X_frame_i); + computeExponentialSE3(curv_abs_x, strain_n, g_X_frame_i); m_framesExponentialSE3Vectors.push_back(g_X_frame_i); if(d_debug.getValue()){ - msg_info("BaseCosserat:")<< "__________________________________________"; - msg_info("BaseCosserat:")<< "x :"<< curv_abs_x << "; k :"<< strain_n; + msg_info("BaseCosserat:")<< "_________________"<<i<<"_________________________"; + msg_info("BaseCosserat:")<< "x :"<< curv_abs_x << "; strain :"<< strain_n; msg_info("BaseCosserat:")<< "m_framesExponentialSE3Vectors :"<< g_X_frame_i; } } diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index 5ed46311..d1d19526 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -37,6 +37,9 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) { + if(d_debug.getValue()) + std::cout<< " ########## ApplyJ R Function ########"<< std::endl; + if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) return; const In1VecDeriv& in1_vel = dataVecIn1Vel[0]->getValue(); @@ -84,18 +87,17 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( if(d_debug.getValue()) std::cout<< "Node velocity : "<< i << " = " << eta_node_i<< std::endl; } - const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); auto sz = curv_abs_frames.size(); out_vel.resize(sz); + for (unsigned int i = 0 ; i < sz; i++) { Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); Tangent Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); - - type::Vec6 frame_Xi_dot; - for (unsigned int u =0; u<6; u++) - frame_Xi_dot(i) = in1_vel[i-1][u]; + type::Vec6 frame_Xi_dot = in1_vel[m_indicesVectors[i]-1]; +// for (unsigned int u =0; u<6; u++) +// frame_Xi_dot(i) = in1_vel[m_indicesVectors[i]-1][u]; Vec6 eta_frame_i = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * frame_Xi_dot ); // eta @@ -103,7 +105,6 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( Tangent Proj = this->build_projector(T); out_vel[i] = Proj * eta_frame_i; - if(d_debug.getValue()) std::cout<< "Frame velocity : "<< i << " = " << eta_frame_i<< std::endl; } @@ -122,6 +123,8 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) return; + if(d_debug.getValue()) + std::cout<< " ########## ApplyJT force R Function ########"<< std::endl; const OutVecDeriv& in = dataVecInForce[0]->getValue(); In1VecDeriv& out1 = *dataVecOut1Force[0]->beginEdit(); @@ -210,6 +213,9 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) return; + if(d_debug.getValue()) + std::cout<< " ########## ApplyJT constraint R Function ########"<< std::endl; + //We need only one input In model and input Root model (if present) In1MatrixDeriv& out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space (reduced coordinate) In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 5e2047d2..14250cd4 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -96,7 +96,12 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() } if(d_debug.getValue()) - msg_info("DiscreteCosseratMapping")<< " m_vecTransform : "<< m_vecTransform; + { + msg_info("DiscreteCosseratMapping")<< " =================" + "============================ "; + msg_info("DiscreteCosseratMapping")<< " m_vecTransform : "<< m_vecTransform; + } + this->initialize(); } @@ -110,6 +115,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( if(dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) return; + if(d_debug.getValue()) + std::cout<< " ########## Apply Function ########"<< std::endl; ///Do Apply //We need only one input In model and input Root model (if present) const In1VecCoord& in1 = dataVecIn1Pos[0]->getValue(); @@ -133,6 +140,9 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( } frame *= m_framesExponentialSE3Vectors[i]; //frame*gX(x) + if(d_debug.getValue()) + std::cout<< "Frame : "<< i << " = " << frame<< std::endl; + type::Vec3 v = frame.getOrigin(); type::Quat q = frame.getOrientation(); out[i] = OutCoord(v,q); @@ -199,6 +209,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>:: applyJ( if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) return; + if(d_debug.getValue()) + std::cout<< " ########## ApplyJ Function ########"<< std::endl; const In1VecDeriv& in1_vel = dataVecIn1Vel[0]->getValue(); const In2VecDeriv& in2_vel = dataVecIn2Vel[0]->getValue(); OutVecDeriv& out_vel = *dataVecOutVel[0]->beginEdit(); @@ -282,6 +294,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>:: applyJT( if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) return; + if(d_debug.getValue()) + std::cout<< " ########## ApplyJT force Function ########"<< std::endl; const OutVecDeriv& in = dataVecInForce[0]->getValue(); In1VecDeriv& out1 = *dataVecOut1Force[0]->beginEdit(); @@ -371,6 +385,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) return; + if(d_debug.getValue()) + std::cout<< " ########## ApplyJT Constraint Function ########"<< std::endl; //We need only one input In model and input Root model (if present) In1MatrixDeriv& out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space (reduced coordinate) In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) From 5d7e28aefd7a1c9afb0e9636c6ba374404ee57b0 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 15 Dec 2023 10:57:19 +0100 Subject: [PATCH 25/71] update --- docs/testScene/edit_frames.py | 101 ++++++++++++++++++ docs/testScene/tuto_2.py | 7 +- docs/testScene/tuto_2_6dofs.py | 18 ++-- docs/testScene/tuto_3.py | 4 +- docs/testScene/tuto_4.py | 2 +- examples/python3/useful/__initi__.py | 30 ++++++ examples/python3/useful/compute_logmap.py | 90 ++++++++++++++++ .../python3/useful/compute_rotation_matrix.py | 25 +++++ src/Cosserat/engine/PointsManager.inl | 4 +- src/Cosserat/mapping/BaseCosserat.h | 100 +++++++++++++++-- .../mapping/DiscreteCosseratMapping.inl | 14 ++- 11 files changed, 363 insertions(+), 32 deletions(-) create mode 100644 docs/testScene/edit_frames.py create mode 100644 examples/python3/useful/__initi__.py create mode 100644 examples/python3/useful/compute_logmap.py create mode 100644 examples/python3/useful/compute_rotation_matrix.py diff --git a/docs/testScene/edit_frames.py b/docs/testScene/edit_frames.py new file mode 100644 index 00000000..0734875a --- /dev/null +++ b/docs/testScene/edit_frames.py @@ -0,0 +1,101 @@ +# -*- coding: utf-8 -*- +""" + Cosserat class in SofaPython3. +""" + +__authors__ = "adagolodjo" +__contact__ = "adagolodjo@protonmail.com" +__version__ = "1.0.0" +__copyright__ = "(c) 2021,Inria" +__date__ = "October, 26 2021" + +from useful.header import addHeader, addSolverNode +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters +from useful.params import Parameters +from cosserat.CosseratBase import CosseratBase +from math import sqrt +from splib3.numerics import Quat +import Sofa +from math import pi + +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, + nbSection=6, nbFrames=12, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=0.5, + beamLength=30) +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +force_null = [0., 0., 0., 0., 0., 0.] # N + +class ForceController(Sofa.Core.Controller): + def __init__(self, *args, **kwargs): + Sofa.Core.Controller.__init__(self, *args, **kwargs) + # self.forceNode = kwargs['forceNode'] + self.frames = kwargs['frame_node'].FramesMO + #self.edite_frames() + self.edit_pos = True + + def onAnimateEndEvent(self, event): + if self.edit_pos == True: + self.edite_frames() + self.edit_pos = False + + + + def edite_frames(self): + with self.frames.rest_position.writeable() as position: + last_frame = len(position) + print(f'===> The position : {position[last_frame-1]}') + position[last_frame-1][1] = 2 + + + + def compute_orthogonal_force(self): + position = self.frames.position[self.size] # get the last rigid of the cosserat frame + orientation = Quat(position[3], position[4], position[5], position[6]) # get the orientation + # Calculate the direction of the force in order to remain orthogonal to the x_axis + # of the last frame of the beam. + with self.forceNode.forces.writeable() as force: + vec = orientation.rotate([0., self.forceCoeff * 5.e-2, 0.]) + # vec.normalize() + # print(f' The new vec is : {vec}') + for count in range(3): + force[0][count] = vec[count] + + def rotate_force(self): + if self.forceCoeff <= 100. * pi: + with self.tip_controller.position.writeable() as position: + last_frame = self.frames.position[self.size] + vec = Quat(last_frame[3], last_frame[4], last_frame[5], last_frame[6]) # get the orientation + + vec.rotateFromEuler([self.theta, 0., 0.]) # apply rotation arround x-axis + vec.normalize() + for i, v in enumerate(vec): + position[0][i + 3] = v + + def onKeypressedEvent(self, event): + key = event['key'] + if key == "+": + self.applyForce = True + elif key == "-": + self.applyForce = False + + +controller_type = 2 + +def createScene(root_node): + addHeader(root_node) + root_node.gravity = [0, 0., 0.] + + solver_node = addSolverNode(root_node, name="solver_node") + + # create cosserat Beam + cosserat_beam = solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) + cosserat_frames = cosserat_beam.cosseratFrame + solver_node.addObject(ForceController(frame_node=cosserat_frames)) + + + + # solver_node.addObject(ForceController(forceNode=const_force_node, frame_node=cosserat_frames, force_type=controller_type, tip_controller=controller_state)) + + return root_node diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py index a3ebd7e5..0445b223 100644 --- a/docs/testScene/tuto_2.py +++ b/docs/testScene/tuto_2.py @@ -63,18 +63,17 @@ def createScene(root_node): section_curv_abs = [0.] # section/segment curve abscissa for i in range(nb_sections): - bending_states.append([0, 0.0, 0.]) # torsion, y_bending, z_bending + bending_states.append([0, 0.0, 0.0]) # torsion, y_bending, z_bending list_sections_length.append((((i + 1) * length_s) - i * length_s)) temp += list_sections_length[i] section_curv_abs.append(temp) - bending_states[nb_sections-1] = [0, 0.0, 0.3] - section_curv_abs[nb_sections] = beam_length + bending_states[nb_sections-1] = [0, 0.0, 0.52359878] # call add cosserat state and force field bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) # comment : ??? - nb_frames = 32 + nb_frames = 6 length_f = beam_length/float(nb_frames) cosserat_G_frames = [] frames_curv_abs = [] diff --git a/docs/testScene/tuto_2_6dofs.py b/docs/testScene/tuto_2_6dofs.py index d7ec18c0..f0a867a0 100644 --- a/docs/testScene/tuto_2_6dofs.py +++ b/docs/testScene/tuto_2_6dofs.py @@ -5,7 +5,7 @@ beam_radius = 1. nb_sections = 6 -nb_frames = 6 +nb_frames = 12 beam_length = 30 @@ -16,7 +16,7 @@ def _add_rigid_base(p_node): showObject=1, showObjectScale='0.1') rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", - points="0", template="Rigid3d") + points="0", template="Rigid3d", activeDirections=[0,1,1,1,1,1,1]) return rigid_base_node @@ -51,12 +51,12 @@ def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _fram def createScene(root_node): root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') -# root_node.gravity = [0, 0, 0] # root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass='0.0') # root_node.addObject('SparseLDLSolver', name='solver') addHeader(root_node) - root_node.gravity = [0, -9.81, 0.] + root_node.gravity = [0, 0, 0] +# root_node.gravity = [0, -9.81, 0.] solver_node = addSolverNode(root_node, name="solver_node") @@ -77,11 +77,7 @@ def createScene(root_node): temp += list_sections_length[i] section_curv_abs.append(temp) # bending_states[nb_sections-1] = [0, 0.0, 0.3, 0, 0., 0.] - bending_states[nb_sections-1] = [0., 0., 0., 0.2, 0., 0.] - - - print (f'The bending list : {bending_states}') - print (f'The section_curv_abs list : {section_curv_abs}') + bending_states[nb_sections-1] = [1., 0., 0., 0., 0., 0.] # call add cosserat state and force field bending_node = _add_cosserat_state(solver_node, bending_states, list_sections_length) @@ -108,7 +104,7 @@ def createScene(root_node): beam_radius) ## Add a force component to test the stretch -# applied_force =[0, -1.e8, 0, 0, 0, 0] -# const_force_node = cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=10, indices=nb_frames, forces=applied_force) + applied_force =[-1.e1, 0., 0, 0, 0, 0] + cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1e10, indices=nb_frames, forces=applied_force) return root_node diff --git a/docs/testScene/tuto_3.py b/docs/testScene/tuto_3.py index fb3bac86..9a2b2e73 100644 --- a/docs/testScene/tuto_3.py +++ b/docs/testScene/tuto_3.py @@ -14,8 +14,8 @@ from useful.params import Parameters from cosserat.CosseratBase import CosseratBase -geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, nbSection=6, nbFrames=12, buildCollisionModel=0) -physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., beamLength=30) +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1, nbSection=2, nbFrames=12, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=0.3, youngModulus=1.0e3, poissonRatio=0.38, beamRadius=1., beamLength=30) simuParams = SimulationParameters() Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py index 319d8d43..edccaf9b 100644 --- a/docs/testScene/tuto_4.py +++ b/docs/testScene/tuto_4.py @@ -9,7 +9,7 @@ __copyright__ = "(c) 2021,Inria" __date__ = "October, 26 2021" -from useful.header import addHeader, addSolverNode, addVisual +from useful.header import addHeader, addSolverNode from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters from useful.params import Parameters from cosserat.CosseratBase import CosseratBase diff --git a/examples/python3/useful/__initi__.py b/examples/python3/useful/__initi__.py new file mode 100644 index 00000000..885d9936 --- /dev/null +++ b/examples/python3/useful/__initi__.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python +# -*- coding: utf-8 -*- + +__author__ = 'Younes' +__copyright__ = '(c) {year}, Inria, {project_name}' +__credits__ = ['{credit_list}'] +__license__ = '{license}' +__version__ = '{mayor}.{minor}.{rel}' +__maintainer__ = '{maintainer}' +__email__ = 'yinoussa.adagolodjo-AT-inria.fr' +__status__ = '{dev_status}' +__date__ = "{Date}" + +""" +{Description} +{License_info} + +Content: +******** + .. scenes related to the use of cosserat model needle in a direct simulation + .. autosummary:: + :toctree: _autosummary + + cosserat.needle.params + + +""" + +__all__ = ["utils", "params", "geometry", "compute_logmap", "compute_rotation_matrix"] + diff --git a/examples/python3/useful/compute_logmap.py b/examples/python3/useful/compute_logmap.py new file mode 100644 index 00000000..0d0baaaa --- /dev/null +++ b/examples/python3/useful/compute_logmap.py @@ -0,0 +1,90 @@ +import numpy as np +from compute_rotation_matrix import * + + +def piecewise_logmap1(curv_abs, g_x): + # xi_hat = np.zeros((4, 4), dtype=float) + + theta = compute_theta(curv_abs, g_x) + + if theta == 0.0: + xi_hat = 1.0 / curv_abs * (g_x - np.identity(4)) + else: + t0 = curv_abs * theta + t1 = np.sin(t0) + t2 = np.cos(t0) + t3 = 2 * t1 * t2 + t4 = 1 - 2 * t1 ** 2 + t5 = t0 * t4 + + gp2 = np.dot(g_x, g_x) + gp3 = np.dot(gp2, g_x) + + xi_hat = 1.0 / curv_abs * (0.125 * (1.0 / np.sin(t0 / 2.0) ** 3) * np.cos(t0 / 2.0) * + ((t5 - t1) * np.identity(4) - (t0 * t2 + 2 * t5 - t1 - t3) * g_x + + (2 * t0 * t2 + t5 - t1 - t3) * gp2 - (t0 * t2 - t1) * gp3)) + + xci = np.array([xi_hat[2, 1], xi_hat[0, 2], xi_hat[1, 0], xi_hat[0, 3], xi_hat[1, 3], xi_hat[2, 3]]) + + return xci + + +def piecewise_logmap2(curv_abs, gX): + theta = compute_theta(curv_abs, gX) + I4 = np.identity(4) + xi_hat = np.zeros((4, 4)) + + csc_theta = 1.0 / np.sin(curv_abs * theta / 2.0) + sec_theta = 1.0 / np.cos(curv_abs * theta / 2.0) + cst = (1.0 / 8) * (csc_theta ** 3) * sec_theta + x_theta = curv_abs * theta + cos_2Xtheta = np.cos(2.0 * x_theta) + cos_Xtheta = np.cos(x_theta) + sin_2Xtheta = np.sin(2.0 * x_theta) + sin_Xtheta = np.sin(x_theta) + + if theta <= np.finfo(float).eps: + xi_hat = I4 + else: + xi_hat = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * I4 - + (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - sin_Xtheta - sin_2Xtheta) * gX + + (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - sin_Xtheta - sin_2Xtheta) * ( + np.dot(gX, gX)) - + (x_theta * cos_Xtheta - sin_Xtheta) * (np.dot(np.dot(gX, gX), gX))) + + xi = np.array([xi_hat[2, 1], xi_hat[0, 2], xi_hat[1, 0], xi_hat[0, 3], xi_hat[1, 3], xi_hat[2, 3]]) + return xi + + +def compute_theta(x, gX): + Tr_gx = np.trace(gX) + if x <= np.finfo(float).eps: + theta = 0.0 + else: + theta = (1.0 / x) * np.arccos((Tr_gx / 2.0) - 1) + + return theta + + +if __name__ == '__main__': + _curv_abs = 1 + angle_y = 20 * np.pi / 180 + + + R = rotation_matrix_y(angle_y) + + print(f'The rotation matrix is: \n {R}') + + _g_x = np.zeros((4, 4), dtype=float) + for i in range(3): + for j in range(3): + _g_x[i][j] = R[i][j] + + _g_x[0][3] = _curv_abs # to deploy the beam node and the rest part of transform is equal to null + _g_x[3][3] = 1 # The homogeneous matrix + + xci = piecewise_logmap1(_curv_abs, _g_x) + + print(f'The piecewise logmap is: {xci}') + + # 0.29241528 diff --git a/examples/python3/useful/compute_rotation_matrix.py b/examples/python3/useful/compute_rotation_matrix.py new file mode 100644 index 00000000..933b5e4a --- /dev/null +++ b/examples/python3/useful/compute_rotation_matrix.py @@ -0,0 +1,25 @@ +import numpy as np + +def rotation_matrix_x(angle): + rotation = np.array([[1, 0, 0], + [0, np.cos(angle), -np.sin(angle)], + [0, np.sin(angle), np.cos(angle)]]) + return rotation + + +def rotation_matrix_y(angle): + rotation = np.array([[np.cos(angle), 0, np.sin(angle)], + [0, 1, 0], + [-np.sin(angle), 0, np.cos(angle)]]) + return rotation + + +def rotation_matrix_z(angle): + rotation = np.array([[np.cos(angle), -np.sin(angle), 0], + [np.sin(angle), np.cos(angle), 0], + [0, 0, 1]]) + return rotation + +def compute_rotation_matrix(x, y, z): + rotation = np.dot(rotation_matrix_z(z), np.dot(rotation_matrix_y(y), rotation_matrix_x(x))) + return rotation diff --git a/src/Cosserat/engine/PointsManager.inl b/src/Cosserat/engine/PointsManager.inl index 50c03e08..efe9c633 100755 --- a/src/Cosserat/engine/PointsManager.inl +++ b/src/Cosserat/engine/PointsManager.inl @@ -102,12 +102,12 @@ namespace sofa::core::behavior { case 'S': case 's': - printf("A point is created \n"); + msg_info() << "A point is created ." ; addNewPointToState(); break; case 'L': case 'l': - printf("Remove point from state \n"); + msg_info() <<("Remove point from state \n"); removeLastPointfromState(); break; } diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index d6eb293b..840f4a44 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -30,6 +30,15 @@ #include <sofa/core/objectmodel/BaseObject.h> #include <sofa/type/Vec.h> +#include <iostream> +#include <cmath> + +#include <Eigen/Dense> +#include <cmath> + +using namespace std; +using namespace Eigen; + #include <cmath> namespace sofa::component::mapping @@ -139,7 +148,11 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject [[maybe_unused]] type::vector<Mat6x6> m_frame_coAdjointEtaVectors; typedef typename sofa::type::Matrix4 se3; typedef typename sofa::type::Matrix4 SE3; + typedef typename Eigen::Matrix4d _SE3; + typedef typename Eigen::Matrix4d _se3; typedef typename type::Mat<6,6,SReal> Tangent; + typedef typename Eigen::Matrix3d RotMat; + typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; protected: /// Constructor @@ -225,19 +238,19 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject } se3 build_Xi_hat(const Coord1 & strain_i){ - se3 Xi; + se3 Xi_hat; - Xi[0][1] = -strain_i(2); - Xi[0][2] = strain_i[1]; - Xi[1][2] = -strain_i[0]; + Xi_hat[0][1] = -strain_i(2); + Xi_hat[0][2] = strain_i[1]; + Xi_hat[1][2] = -strain_i[0]; - Xi[1][0] = -Xi(0,1); - Xi[2][0] = -Xi(0,2); - Xi[2][1] = -Xi(1,2); + Xi_hat[1][0] = -Xi_hat(0,1); + Xi_hat[2][0] = -Xi_hat(0,2); + Xi_hat[2][1] = -Xi_hat(1,2); //@TODO: Why this , if q = 0 ???? - Xi[0][3] = 1.0; - return Xi; + Xi_hat[0][3] = 1.0; + return Xi_hat; } Matrix3 getTildeMatrix(const type::Vec3 & u){ @@ -290,6 +303,75 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject return M; } + + Vec6 piecewise_logmap(const _SE3& g_x) { + _SE3 Xi_hat; + + double x = 1.0; + double theta = std::acos(g_x.trace() / 2.0 - 1.0); + + if (theta == 0) { + Xi_hat = 1.0 / x * (g_x - Matrix4d::Identity()); + } else { + double x_theta = x * theta; + double sin_x_theta = std::sin(x_theta); + double cos_x_theta = std::cos(x_theta); + double t3 = 2 * sin_x_theta * cos_x_theta; + double t4 = 1 - 2 * sin_x_theta * sin_x_theta; + double t5 = x_theta * t4; + + /// +// double csc_theta = 1.0/(sin(x * theta/2.0)); +// double sec_theta = 1.0/(cos(x * theta/2.0)); +// double cst = (1.0/8) * (csc_theta*csc_theta*csc_theta) * sec_theta; +// double x_theta = x*theta; +// double cos_2Xtheta = cos(2.0 * x_theta); +// double cos_Xtheta = cos(x_theta); +// double sin_2Xtheta = sin(2.0 *x_theta); +// double sin_Xtheta = sin(x_theta); + /// + + Matrix4d gp2 = g_x * g_x; + Matrix4d gp3 = gp2 * g_x; + + Xi_hat = 1.0 / x * (0.125 * (1.0 / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0)) * std::cos(x_theta / 2.0) * + ((t5 - sin_x_theta) * Matrix4d::Identity() - (x_theta * cos_x_theta + 2 * t5 - sin_x_theta - t3) * g_x + + (2 * x_theta * cos_x_theta + t5 - sin_x_theta - t3) * gp2 - (x_theta * cos_x_theta - sin_x_theta) * gp3)); + } + + Vec6 xci = Vec6(Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), Xi_hat(1, 3), Xi_hat(2, 3)); + //xci << Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), Xi_hat(1, 3), Xi_hat(2, 3); + + return xci; + } + + Eigen::Matrix3d rotationMatrixX(double angle) { + Eigen::Matrix3d rotation; + rotation << 1, 0, 0, + 0, cos(angle), -sin(angle), + 0, sin(angle), cos(angle); + return rotation; + } + + + Eigen::Matrix3d rotationMatrixY(double angle) { + Eigen::Matrix3d rotation; + rotation << cos(angle), 0, sin(angle), + 0, 1, 0, + -sin(angle), 0, cos(angle); + return rotation; + } + + RotMat rotationMatrixZ(double angle) { + RotMat rotation; + rotation << cos(angle), -sin(angle), 0, + sin(angle), cos(angle), 0, + 0, 0, 1; + return rotation; + } + + + }; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 14250cd4..10f83c8e 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -148,6 +148,12 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( out[i] = OutCoord(v,q); } // + if(d_debug.getValue()){ + for (auto i =0; i<out.size()-1; i++){ + type::Vec3 diff = out[i+1].getCenter() - out[i].getCenter(); + std::cout << "dist "<<i << " : "<< diff.norm() <<std::endl; + } + } m_index_input = 0; dataVecOutPos[0]->endEdit(); } @@ -171,8 +177,10 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double & double sin_2Xtheta = sin(2.0 *x_theta); double sin_Xtheta = sin(x_theta); - if(theta <= std::numeric_limits<double>::epsilon()) log_gX = I4; - else { + if(theta <= std::numeric_limits<double>::epsilon()) + log_gX = I4; + else + { log_gX = cst * ((x_theta*cos_2Xtheta - sin_Xtheta)*I4 - (x_theta*cos_Xtheta + 2.0*x_theta*cos_2Xtheta - sin_Xtheta -sin_2Xtheta)*gX + (2.0*x_theta*cos_Xtheta + x_theta*cos_2Xtheta-sin_Xtheta - sin_2Xtheta) *(gX*gX)- @@ -612,7 +620,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw(const core::visual::VisualP type::vector<int> index = d_index.getValue(); for (unsigned int i=0; i<sz-1; i++) { j = m_indicesVectorsDraw[i]-1; // to get the articulation on which the frame is related to - RGBAColor color = RGBAColor::fromVec4(_eval(xPos[j][d_deformationAxis.getValue()])); + RGBAColor color = _eval(xPos[j][d_deformationAxis.getValue()]); vparams->drawTool()->drawLine(positions[i],positions[i+1],color); } } From 653090265168dc3e8cd53d60cdc9473fd587314a Mon Sep 17 00:00:00 2001 From: Eulalie Coevoet <eulalie.coevoet@gmail.com> Date: Fri, 15 Dec 2023 11:36:31 +0100 Subject: [PATCH 26/71] [forcefield] add template vec6types to BeamHookeLawForceField --- .../forcefield/BeamHookeLawForceField.cpp | 137 ++++++++++++++++++ .../forcefield/BeamHookeLawForceField.h | 11 +- 2 files changed, 146 insertions(+), 2 deletions(-) diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp index aa6b94e1..a5715a89 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp @@ -35,6 +35,141 @@ namespace sofa::component::forcefield { +template<> +void BeamHookeLawForceField<defaulttype::Vec6Types>::reinit() +{ + // Precompute and store values + Real Iy, Iz, J, A; + if ( d_crossSectionShape.getValue().getSelectedItem() == "rectangular") //rectangular cross-section + { + Real Ly = d_lengthY.getValue(); + Real Lz = d_lengthZ.getValue(); + + const Real LyLzLzLz = Ly * Lz * Lz * Lz; + const Real LzLyLyLy = Lz * Ly * Ly * Ly; + + Iy = LyLzLzLz / 12.0; + Iz = LzLyLyLy / 12.0; + J = Iy + Iz; + A = Ly * Lz; + + } + else //circular cross-section + { + msg_info() << "Cross section shape." << d_crossSectionShape.getValue().getSelectedItem() ; + + Real r = d_radius.getValue(); + Real rInner = d_innerRadius.getValue(); + const Real r4 = r * r * r * r; + const Real rInner4 = rInner * rInner * rInner * rInner; + + Iy = M_PI * (r4 - rInner4) / 4.0; + Iz = Iy; + J = Iy + Iz; + A = M_PI * (r * r - rInner4); + + } + m_crossSectionArea = A; + + if( d_useInertiaParams.getValue() ) + { + msg_info("BeamHookeLawForceField")<< "Pre-calculated inertia parameters are used for the computation of the stiffness matrix."; + m_K_section66[0][0] = d_GI.getValue(); + m_K_section66[1][1] = d_EIy.getValue(); + m_K_section66[2][2] = d_EIz.getValue(); + m_K_section66[3][3] = d_EA.getValue(); + m_K_section66[4][4] = d_GA.getValue(); + m_K_section66[5][5] = d_GA.getValue(); + } + else + { + //Pour du vec 6, on a _m_K =diag([G*J E*Iy E*Iz E*A G*As G*As]); % stifness matrix + Real E = d_youngModulus.getValue(); + Real G = E/(2.0*(1.0+d_poissonRatio.getValue())); + //Translational Stiffness (X, Y, Z directions): + // Gs * J(i): Shearing modulus times the second moment of the area (torsional stiffness). + // E * Js(i): Young's modulus times the second moment of the area (bending stiffness). + m_K_section66[0][0] = G*J; + m_K_section66[1][1] = E*Iy; + m_K_section66[2][2] = E*Iz; + //Rotational Stiffness (X, Y, Z directions): + //E * A: Young's modulus times the cross-sectional area (axial stiffness). + //Gs * A: Shearing modulus times the cross-sectional area (shearing stiffness). + m_K_section66[3][3] = E*A; + m_K_section66[4][4] = G*A; + m_K_section66[5][5] = G*A; + } +} + +template<> +void BeamHookeLawForceField<defaulttype::Vec6Types>::addForce(const MechanicalParams* mparams, + DataVecDeriv& d_f, + const DataVecCoord& d_x, + const DataVecDeriv& d_v) +{ + SOFA_UNUSED(d_v); + SOFA_UNUSED(mparams); + + if(!this->getMState()) { + msg_info("BeamHookeLawForceField") << "No Mechanical State found, no force will be computed..." << "\n"; + compute_df=false; + return; + } + VecDeriv& f = *d_f.beginEdit(); + const VecCoord& x = d_x.getValue(); + // get the rest position (for non straight shape) + const VecCoord& x0 = this->mstate->read(VecCoordId::restPosition())->getValue(); + + f.resize(x.size()); + unsigned int sz = d_length.getValue().size(); + if(x.size()!= sz){ + msg_warning("BeamHookeLawForceField")<<" length : "<< sz <<"should have the same size as x... "<< x.size() <<"\n"; + compute_df = false; + return; + } + for (unsigned int i=0; i<x.size(); i++) + f[i] -= (m_K_section66 * (x[i] - x0[i])) * d_length.getValue()[i]; + + d_f.endEdit(); + +} + +template<> +void BeamHookeLawForceField<defaulttype::Vec6Types>::addDForce(const MechanicalParams* mparams, + DataVecDeriv& d_df , + const DataVecDeriv& d_dx) +{ + if (!compute_df) + return; + + WriteAccessor< DataVecDeriv > df = d_df; + ReadAccessor< DataVecDeriv > dx = d_dx; + Real kFactor = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + df.resize(dx.size()); + for (unsigned int i=0; i<dx.size(); i++) + df[i] -= (m_K_section66 * dx[i])*kFactor* d_length.getValue()[i]; +} + +template<> +void BeamHookeLawForceField<defaulttype::Vec6Types>::addKToMatrix(const MechanicalParams* mparams, + const MultiMatrixAccessor* matrix) +{ + MultiMatrixAccessor::MatrixRef mref = matrix->getMatrix(this->mstate); + BaseMatrix* mat = mref.matrix; + unsigned int offset = mref.offset; + Real kFact = (Real)mparams->kFactorIncludingRayleighDamping(this->rayleighStiffness.getValue()); + + const VecCoord& pos = this->mstate->read(core::ConstVecCoordId::position())->getValue(); + for (unsigned int n=0; n<pos.size(); n++) + { + for(unsigned int i = 0; i < 6; i++) + for (unsigned int j = 0; j< 6; j++) + mat->add(offset + i + 6*n, offset + j + 6*n, -kFact * m_K_section66[i][j]*d_length.getValue()[n]); + + } +} + //////////////////////////////////////////// FACTORY ////////////////////////////////////////////// // Registering the component // see: http://wiki.sofa-framework.org/wiki/ObjectFactory @@ -44,6 +179,7 @@ using namespace sofa::defaulttype; int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used to compute internal stress for torsion (along x) and bending (y and z)") .add<BeamHookeLawForceField<Vec3Types> >(true) + .add<BeamHookeLawForceField<Vec6Types> >() ; ////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -54,5 +190,6 @@ int BeamHookeLawForceFieldClass = core::RegisterObject("This component is used t // see: http://www.stroustrup.com/C++11FAQ.html#extern-templates template class BeamHookeLawForceField<Vec3Types>; +template class BeamHookeLawForceField<Vec6Types>; } // forcefield diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.h b/src/Cosserat/forcefield/BeamHookeLawForceField.h index d9e086f7..a6e4a68f 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.h @@ -60,7 +60,7 @@ using sofa::helper::OptionsGroup; * Only bending and torsion strain / stress are considered here */ template<typename DataTypes> -class BeamHookeLawForceField : public ForceField<DataTypes> +class SOFA_COSSERAT_API BeamHookeLawForceField : public ForceField<DataTypes> { public : SOFA_CLASS(SOFA_TEMPLATE(BeamHookeLawForceField, DataTypes), SOFA_TEMPLATE(ForceField, DataTypes)); @@ -76,6 +76,7 @@ public : typedef Vec<3, Real> Vec3; typedef Mat<3, 3, Real> Mat33; + typedef Mat<6, 6, Real> Mat66; typedef CompressedRowSparseMatrix<Mat33> CSRMat33B66; @@ -137,9 +138,12 @@ public : Data<Real> d_GA; Data<Real> d_EA; Data<Real> d_EI; + Data<Real> d_EIy; + Data<Real> d_EIz; bool compute_df; Mat33 m_K_section; + Mat66 m_K_section66; type::vector<Mat33> m_K_sectionList; /// Cross-section area @@ -154,9 +158,12 @@ private : /// the "this->" approach. using ForceField<DataTypes>::getContext ; using ForceField<DataTypes>::f_printLog ; - //using ForceField<DataTypes>::mstate ; //////////////////////////////////////////////////////////////////////////// }; +#if !defined(SOFA_COSSERAT_CPP_BeamHookeLawForceField) +extern template class SOFA_COSSERAT_API BeamHookeLawForceField<defaulttype::Vec3Types>; +extern template class SOFA_COSSERAT_API BeamHookeLawForceField<defaulttype::Vec6Types>; +#endif } // forcefield From 6f1ab2ab576d2a910fd53b88bbd02e4c99c29f0e Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Wed, 10 Jan 2024 21:46:57 +0100 Subject: [PATCH 27/71] integrate cosserat logmap code --- examples/python3/useful/__initi__.py | 2 +- examples/python3/useful/compute_logmap.py | 59 ++++++++++++++++------- 2 files changed, 42 insertions(+), 19 deletions(-) diff --git a/examples/python3/useful/__initi__.py b/examples/python3/useful/__initi__.py index 885d9936..a6fdafd6 100644 --- a/examples/python3/useful/__initi__.py +++ b/examples/python3/useful/__initi__.py @@ -26,5 +26,5 @@ """ -__all__ = ["utils", "params", "geometry", "compute_logmap", "compute_rotation_matrix"] +__all__ = ["utils", "params", "geometry", "compute_logmap", "compute_rotation_matrix", "logm"] diff --git a/examples/python3/useful/compute_logmap.py b/examples/python3/useful/compute_logmap.py index 0d0baaaa..1507a9ff 100644 --- a/examples/python3/useful/compute_logmap.py +++ b/examples/python3/useful/compute_logmap.py @@ -1,5 +1,7 @@ import numpy as np from compute_rotation_matrix import * +# from useful.logm import logm +from scipy.linalg import logm as logm_sci def piecewise_logmap1(curv_abs, g_x): @@ -8,22 +10,25 @@ def piecewise_logmap1(curv_abs, g_x): theta = compute_theta(curv_abs, g_x) if theta == 0.0: - xi_hat = 1.0 / curv_abs * (g_x - np.identity(4)) + xi_hat = (1.0/curv_abs) * (g_x - np.identity(4)) else: t0 = curv_abs * theta t1 = np.sin(t0) t2 = np.cos(t0) t3 = 2 * t1 * t2 - t4 = 1 - 2 * t1 ** 2 + t4 = 1 - 2 * (t1 ** 2) t5 = t0 * t4 gp2 = np.dot(g_x, g_x) gp3 = np.dot(gp2, g_x) - xi_hat = 1.0 / curv_abs * (0.125 * (1.0 / np.sin(t0 / 2.0) ** 3) * np.cos(t0 / 2.0) * - ((t5 - t1) * np.identity(4) - (t0 * t2 + 2 * t5 - t1 - t3) * g_x + - (2 * t0 * t2 + t5 - t1 - t3) * gp2 - (t0 * t2 - t1) * gp3)) + xi_hat = (1.0 / curv_abs) * (0.125 * (1./(np.sin(t0/2.0)**3))*(1./np.cos(t0/2.0)) * + ((t5 - t1) * np.identity(4) - (t0 * t2 + 2 * t5 - t1 - t3) * g_x + + (2 * t0 * t2 + t5 - t1 - t3) * gp2 - (t0 * t2 - t1) * gp3)) + print('-----------------------------------') + print(f'The xi_hat matrix is: \n {xi_hat}') + print('-----------------------------------') xci = np.array([xi_hat[2, 1], xi_hat[0, 2], xi_hat[1, 0], xi_hat[0, 3], xi_hat[1, 3], xi_hat[2, 3]]) return xci @@ -67,24 +72,42 @@ def compute_theta(x, gX): if __name__ == '__main__': - _curv_abs = 1 - angle_y = 20 * np.pi / 180 - - - R = rotation_matrix_y(angle_y) - - print(f'The rotation matrix is: \n {R}') - + _curv_abs = 4.0 # the abscissa curve of the beam + angle_y = (20.*np.pi)/180. _g_x = np.zeros((4, 4), dtype=float) - for i in range(3): - for j in range(3): - _g_x[i][j] = R[i][j] - + _g_x[0:3, 0:3] = rotation_matrix_z(angle_y) + print(f'The rotation matrix is: \n {_g_x[0:3, 0:3]}') _g_x[0][3] = _curv_abs # to deploy the beam node and the rest part of transform is equal to null _g_x[3][3] = 1 # The homogeneous matrix xci = piecewise_logmap1(_curv_abs, _g_x) + print(f'The piecewise xci is: {xci[0], xci[1], xci[2]}') + + print('Scipy ###################################') + xci_sci = (1.0/_curv_abs)*logm_sci(_g_x, disp=True) + print(f'The xci in scipy is: \n {xci_sci[2, 1], xci_sci[0, 2], xci_sci[1, 0]}') + + print('mat_matlab ###################################') + # xci_hat = np.log(_g_x) + # print(' ===================================') + # print(f'The log matrix in numpy is: \n {xci_hat}') + # xci_np = np.array([xci_hat[2,1], xci_hat[0,2], xci_hat[1,0], xci_hat[0,3], xci_hat[1,3], xci_hat[2,3]]) + # print(f'The log matrix in numpy is: \n {xci_np}') + # print('===================================') + mat_matlab = [[-0.000000001875958, 0, 0.349065847542556], + [0, 0, 0], + [-0.349065847542556, 0, -0.000000001875958]] + print(f'The xci in matlab is : \n {mat_matlab[2][1], mat_matlab[0][2], mat_matlab[1][0]}') + print('###################################') + + # print('===================================') + # xci_hat_2 = logm(_g_x[0:3, 0:3]) # The log matrix in numpy + # print('===================================') + # + # print(f'The log matrix in numpy is: \n {xci_hat2}') + print('===================================') + + - print(f'The piecewise logmap is: {xci}') # 0.29241528 From 493c7d753cdad55639a9af4afa109b23f06f52e6 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 13 Feb 2024 23:17:15 +0100 Subject: [PATCH 28/71] add a python file to compute logarithme --- docs/testScene/tuto_2.py | 3 +- examples/python3/useful/logm.py | 359 ++++++++++++++++++++++++++++++++ 2 files changed, 361 insertions(+), 1 deletion(-) create mode 100644 examples/python3/useful/logm.py diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py index 0445b223..5a8e422e 100644 --- a/docs/testScene/tuto_2.py +++ b/docs/testScene/tuto_2.py @@ -20,9 +20,10 @@ def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2. print(f' ===> bendind state : {bending_states}') cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', position=bending_states) - cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', + testNode = cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', length=list_sections_length, radius=2., youngModulus=1.e4, poissonRatio=0.4) + print(f' the dire of node is : {dir(testNode)}') return cosserat_coordinate_node diff --git a/examples/python3/useful/logm.py b/examples/python3/useful/logm.py new file mode 100644 index 00000000..ce56c810 --- /dev/null +++ b/examples/python3/useful/logm.py @@ -0,0 +1,359 @@ +import numpy as np +import scipy.linalg + +debuge = True + +def logm(A): + + if debuge==True : + print("In the logm function") + print(f'The dimension of dim is :',A.ndim) + print(f'The type of A is :',A.dtype) + + if not np.issubdtype(A.dtype, float) or not A.ndim == 2: + raise ValueError("Input must be a 2D array of floats.") + + if A.shape[0] != A.shape[1]: + raise ValueError("Input matrix must be square.") + + maxroots = 100 + exitflag = 0 + + if debuge==True : + print("In the logm function 2") + if not np.all(np.isfinite(A)): + L = np.full_like(A, np.nan, dtype=A.dtype) + return L, exitflag + + if debuge==True : + print("In the logm function 2.2") + + # Check for triangularity. + schur_input, T = scipy.linalg.schur(A) + if debuge==True : + print("In the logm function 2.3") + print(f'schur_input is : \n{schur_input}') + print(f'T is : \n {T}') + print("In the logm function 2.3..0") + if not schur_input: + print("In the logm function 2.3..1") + Q, T = scipy.linalg.schur(A, output='full') + if debuge==True : + print("In the logm function 2.3..2") + print(f'Q is : \n{Q}') + print(f'T is : \n {T}') + else: + print("In the logm function 2.3..1") + Q = np.eye(A.shape[0], dtype=A.dtype) + if debuge==True : + print("In the logm function 2.3..2") + print(f'Q is : \n{Q}') + + + if debuge==True : + print("In the logm function 2.4") + stay_real = np.isreal(A).all() + + if debuge==True : + print("In the logm function 3") + + # Compute the logarithm. + if np.all(np.diag(T)): + d = np.diag(T) + if np.any((np.real(d) <= 0) & (np.imag(d) == 0)): + print("Warning: Non-positive real eigenvalues.") + if schur_input: + L = np.diag(np.log(d)) + else: + logd = np.log(d) + L = np.dot(Q * logd, Q.T) + if np.isreal(logd).all(): + L = (L + L.T) / 2 + else: + n = T.shape[0] + ei = np.linalg.eigvals(T) + warns = np.any(ei == 0) + if np.any((np.real(ei) < 0) & (np.imag(ei) == 0)): + warns = True + if stay_real: + if schur_input: + Q = np.eye(n, dtype=A.dtype) + schur_input = False # Need to undo rsf2csf at the end. + Q, T = scipy.linalg.rsf2csf(Q, T) + if warns: + print("Warning: Non-positive real eigenvalues.") + + if debuge==True : + print("In the logm function 4") + # Get block structure of Schur factor. + blockformat = qtri_struct(T) + + # Get parameters. + s, m, Troot, exitflag = logm_params(T, maxroots) + + # Compute Troot - I = T(1/2^s) - I more accurately. + Troot = recompute_diag_blocks_sqrt(Troot, T, blockformat, s) + + # Compute Pade approximant. + L = pade_approx(Troot, m) + + # Scale back up. + L = 2**s * L + + if debuge==True : + print("In the logm function 5") + # Recompute diagonal blocks. + L = recompute_diag_blocks_log(L, T, blockformat) + + # Combine if needed + if not schur_input: + L = np.dot(np.dot(Q, L), Q.T) + + return L, exitflag + +def logm_params(T, maxroots): + if debuge==True : + print("In the logm_params function") + exitflag = 0 + n = T.shape[0] + I = np.eye(n, dtype=T.dtype) + + xvals = np.array([ + 1.586970738772063e-005, + 2.313807884242979e-003, + 1.938179313533253e-002, + 6.209171588994762e-002, + 1.276404810806775e-001, + 2.060962623452836e-001, + 2.879093714241194e-001 + ]) + + mmax = 7 + foundm = False + + # Get initial s0 so that T^(1/2^s0) < xvals(mmax). + s = 0 + d = np.linalg.eigvals(T) + while np.linalg.norm(d - 1, np.inf) > xvals[mmax - 1] and s < maxroots: + d = np.sqrt(d) + s += 1 + + s0 = s + if s == maxroots: + print("Warning: Too many matrix square roots.") + exitflag = 1 + + Troot = T.copy() + for k in range(1, min(s, maxroots) + 1): + Troot = sqrtm_tri(Troot) + + # Compute value of s and m needed. + TrootmI = Troot - I + d2 = np.linalg.norm(normAm(TrootmI, 2))**(1/2) + d3 = np.linalg.norm(normAm(TrootmI, 3))**(1/3) + a2 = max(d2, d3) + + if a2 <= xvals[1]: + m = np.where(a2 <= xvals[:2])[0][0] + 1 + foundm = True + + p = 0 + while not foundm: + more = False # More norm checks needed. + if s > s0: + d3 = np.linalg.norm(normAm(TrootmI, 3))**(1/3) + + d4 = np.linalg.norm(normAm(TrootmI, 4))**(1/4) + a3 = max(d3, d4) + + if a3 <= xvals[mmax - 1]: + j = np.where(a3 <= xvals[2:mmax])[0][0] + 2 + if j <= 6: + m = j + break + else: + if a3/2 <= xvals[4] and p < 2: + more = True + p += 1 + + if not more: + d5 = np.linalg.norm(normAm(TrootmI, 5))**(1/5) + a4 = max(d4, d5) + eta = min(a3, a4) + + if eta <= xvals[mmax - 1]: + m = np.where(eta <= xvals[5:mmax])[0][0] + 5 + break + + if s == maxroots: + if exitflag == 0: + print("Warning: Too many matrix square roots.") + exitflag = 1 + m = mmax # No good value found so take the largest. + break + + Troot = sqrtm_tri(Troot) + TrootmI = Troot - I + s += 1 + + return s, m, Troot, exitflag + +def recompute_diag_blocks_log(L, T, blockStruct): + if debuge==True : + print("In the recompute_diag_blocks_log function") + n = len(T) + last_block = 0 + + for j in range(n - 1): + if blockStruct[j] == 0: + if last_block != 0: + last_block = 0 + continue + else: + last_block = 0 + L[j, j] = np.log(T[j, j]) + elif blockStruct[j] == 1: + last_block = 1 + a1 = T[j, j] + a2 = T[j + 1, j + 1] + loga1 = np.log(a1) + loga2 = np.log(a2) + L[j, j] = loga1 + L[j + 1, j + 1] = loga2 + + if (a1 < 0 and np.imag(a1) == 0) or (a2 < 0 and np.imag(a1) == 0): + continue + + if a1 == a2: + a12 = T[j, j + 1] / a1 + else: + z = (a2 - a1) / (a2 + a1) + if check_condition(z): + a12 = T[j, j + 1] * (loga2 - loga1) / (a2 - a1) + else: + dd = (2 * np.arctanh(z) + 2j * np.pi * unwinding(loga2 - loga1)) / (a2 - a1) + a12 = T[j, j + 1] * dd + + L[j, j + 1] = a12 + elif blockStruct[j] == 2: + last_block = 2 + f = 0.5 * np.log(T[j, j]**2 - T[j, j + 1] * T[j + 1, j]) + t = np.arctan2(np.sqrt(-T[j, j + 1] * T[j + 1, j]), T[j, j]) / np.sqrt(-T[j, j + 1] * T[j + 1, j]) + L[j, j] = f + L[j + 1, j] = t * T[j + 1, j] + L[j, j + 1] = t * T[j, j + 1] + L[j + 1, j + 1] = f + + if blockStruct[-1] == 0: + L[n - 1, n - 1] = np.log(T[n - 1, n - 1]) + + return L + +def sqrt_obo(a, s): + if debuge==True : + print("In the sqrt_obo function") + if s == 0: + val = a - 1 + else: + n0 = s + if np.angle(a) >= np.pi / 2: + a = np.sqrt(a) + n0 = s - 1 + z0 = a - 1 + a = np.sqrt(a) + r = 1 + a + for i in range(1, n0): + a = np.sqrt(a) + r = r * (1 + a) + val = z0 / r + + return val + +def recompute_diag_blocks_sqrt(Troot, T, blockStruct, s): + if debuge==True : + print("In the recompute_diag_blocks_sqrt function") + n = len(T) + last_block = 0 + + for j in range(n - 1): + if blockStruct[j] == 0: + if last_block != 0: + last_block = 0 + continue + else: + last_block = 0 + Troot[j, j] = sqrt_obo(T[j, j], s) + else: + last_block = blockStruct[j] + I = np.eye(2, dtype=T.dtype) + if s == 0: + Troot[j:j + 2, j:j + 2] = T[j:j + 2, j:j + 2] - I + continue + A = sqrtm_tbt(T[j:j + 2, j:j + 2]) + Z0 = A - I + if s == 1: + Troot[j:j + 2, j:j + 2] = Z0 + continue + A = sqrtm_tbt(A) + P = A + I + for i in range(s - 2): + A = sqrtm_tbt(A) + P = P * (I + A) + + Troot[j:j + 2, j:j + 2] = np.linalg.solve(P, Z0) + + if T[j + 1, j] == 0 and T[j, j] >= 0 and T[j + 1, j + 1] >= 0: + Troot[j, j + 1] = powerm2by2(T[j:j + 2, j:j + 2], 1. / (2.**s)) + + if blockStruct[-1] == 0: + Troot[n - 1, n - 1] = sqrt_obo(T[n - 1, n - 1], s) + + return Troot + +def powerm2by2(A, p): + if debuge==True : + print("In the powerm2by2 function") + a1 = A[0, 0] + a2 = A[1, 1] + + if a1 == a2: + x12 = p * A[0, 1] * a1**(p - 1) + else: + z = (a2 - a1) / (a2 + a1) + if check_condition(z): + x12 = A[0, 1] * (a2**p - a1**p) / (a2 - a1) + else: + loga1 = np.log(a1) + loga2 = np.log(a2) + w = np.arctanh(z) + 1j * np.pi * unwinding(loga2 - loga1) + dd = 2 * np.exp(p * (loga1 + loga2) / 2) * np.sinh(p * w) / (a2 - a1) + x12 = A[0, 1] * dd + + return x12 + +def gauss_legendre(n): + if debuge==True : + print("In the gauss_legendre function") + k = np.arange(1, n) + v = k / np.sqrt((2 * k)**2 - 1) + V, x = np.linalg.eig(np.diag(v, -1) + np.diag(v, 1)) + w = 2 * V[0]**2 + + return x, w + +def pade_approx(T, m): + if debuge==True : + print("In the pade_approx function") + nodes, wts = gauss_legendre(m) + # Convert from [-1,1] to [0,1]. + nodes = (nodes + 1) / 2 + wts = wts / 2 + n = T.shape[0] + L = np.zeros_like(T, dtype=T.dtype) + + for j in range(m): + K = nodes[j] * T + K[np.diag_indices(n)] += 1 + L = L + wts[j] * np.linalg.solve(K, T) + + return L From 9e5015183b2c3c3e06971c68442b261d08a9f2e2 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 16 Feb 2024 10:47:31 +0100 Subject: [PATCH 29/71] fix issue of component name --- examples/python3/cosserat/cosseratObject.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/python3/cosserat/cosseratObject.py b/examples/python3/cosserat/cosseratObject.py index 734940ab..b5ae9483 100644 --- a/examples/python3/cosserat/cosseratObject.py +++ b/examples/python3/cosserat/cosseratObject.py @@ -201,7 +201,7 @@ def createScene(rootNode): ['SofaEngine', 'SofaLoader', 'SofaSimpleFem', 'SofaExporter']]) rootNode.addObject('VisualStyle', displayFlags='showVisualModels showBehaviorModels hideCollisionModels ' - 'hideBoundingCollisionModels hireForceFields ' + 'hideBoundingCollisionModels hideForceFields ' 'hideInteractionForceFields hideWireframe showMechanicalMappings') rootNode.findData('dt').value = 0.01 rootNode.findData('gravity').value = [0., -9.81, 0.] @@ -222,12 +222,12 @@ def createScene(rootNode): Cosserat(parent=solverNode, cosseratGeometry=cosserat_config, name="cosserat", radius=0.15)) # use this to add the collision if the beam will interact with another object - collisionModel = cosserat.addCollisionModel() + # collisionModel = cosserat.addCollisionModel() # Attach a force at the beam tip, # we can attach this force to non mechanical node thanks to the MechanicalMatrixMapper component - beamFrame = cosserat.cosseratFrame - beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-2, indices=12, - force=[0., -100., 0., 0., 0., 0.]) + # beamFrame = cosserat.cosseratFrame + # beamFrame.addObject('ConstantForceField', name='constForce', showArrowSize=1.e-2, indices=12, + # forces=[0., -100., 0., 0., 0., 0.]) return rootNode From 6ec94bff8e593345aba8690b02c9d0378dd7efd0 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Mon, 26 Feb 2024 18:36:31 +0100 Subject: [PATCH 30/71] update tutoriel scenes --- docs/testScene/tuto_1_6dofs.py | 2 +- docs/testScene/tuto_2_6dofs.py | 6 +- docs/testScene/tuto_compare_2.py | 126 +++++++++++++++++ examples/python3/tutorial/scene_w9991.py | 129 ++++++++++++++++++ examples/python3/useful/draw_mesh.py | 69 ++++++++++ src/Cosserat/mapping/BaseCosserat.cpp | 6 +- src/Cosserat/mapping/BaseCosserat.inl | 2 +- .../mapping/DiscreteCosseratMapping.inl | 1 + 8 files changed, 333 insertions(+), 8 deletions(-) create mode 100644 docs/testScene/tuto_compare_2.py create mode 100644 examples/python3/tutorial/scene_w9991.py create mode 100644 examples/python3/useful/draw_mesh.py diff --git a/docs/testScene/tuto_1_6dofs.py b/docs/testScene/tuto_1_6dofs.py index 664ca37c..af723fb0 100644 --- a/docs/testScene/tuto_1_6dofs.py +++ b/docs/testScene/tuto_1_6dofs.py @@ -52,7 +52,7 @@ def createScene(root_node): base_node = _add_rigid_base(root_node) # - cos_nul_state = [0.0, 0.0, 0.0, 0., 0., 0.] # torsion, y_bending, z_bending + cos_nul_state = [0.0, 0.0, 0.0, 0., 0., 0.] # torsion, y_bending, z_bending, x_extension, y_shear, z_shear bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] list_sections_length = [10, 10, 10] bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) diff --git a/docs/testScene/tuto_2_6dofs.py b/docs/testScene/tuto_2_6dofs.py index f0a867a0..3cf3c975 100644 --- a/docs/testScene/tuto_2_6dofs.py +++ b/docs/testScene/tuto_2_6dofs.py @@ -25,7 +25,7 @@ def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2. print(f' ===> bendind state : {bending_states}') cosserat_coordinate_node.addObject('MechanicalObject', template='Vec6d', name='cosserat_state', position=bending_states) - cosserat_coordinate_node.addObject('BeamHookeLawForceFieldRigid', crossSectionShape='circular', + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', length=list_sections_length, radius=2., youngModulus=1.e3, poissonRatio=0.4) return cosserat_coordinate_node @@ -55,8 +55,8 @@ def createScene(root_node): # root_node.addObject('SparseLDLSolver', name='solver') addHeader(root_node) - root_node.gravity = [0, 0, 0] -# root_node.gravity = [0, -9.81, 0.] + # root_node.gravity = [0, 0, 0] + root_node.gravity = [0, -9.81, 0.] solver_node = addSolverNode(root_node, name="solver_node") diff --git a/docs/testScene/tuto_compare_2.py b/docs/testScene/tuto_compare_2.py new file mode 100644 index 00000000..6fdbee4b --- /dev/null +++ b/docs/testScene/tuto_compare_2.py @@ -0,0 +1,126 @@ +# -*- coding: utf-8 -*- +from useful.header import addHeader, addSolverNode, addVisual +from math import pi + +stiffness_param = 1.e10 + +nb_sections = 3 +nb_frames = 3 + + +youngModulus: float = 1.205e11 +poissonRatio: float = 0.499 +beam_radius: float = 0.004 +density: float = 7.850e3 +beam_length: float = 2 + +totalMass = density * beam_length * beam_radius * beam_radius * pi + + +def _add_rigid_base(p_node, _name='rigid_base'): + rigid_base_node = p_node.addChild(_name) + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=0, showObjectScale='0.') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, + angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", + points="0", template="Rigid3d", activeDirections=[1,1,1,1,1,1,1]) + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=beam_radius,_template='Vec6d'): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + print(f' ===> bendind state : {bending_states}') + cosserat_coordinate_node.addObject('MechanicalObject', template=_template, name='cosserat_state', + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', + length=list_sections_length, radius=_radius, youngModulus=youngModulus, + poissonRatio=poissonRatio) + return cosserat_coordinate_node + + +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius=beam_radius, _beam_mass=totalMass): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', + name="FramesMO", position=framesF, showIndices=0., showObject=0, + showObjectScale=0.0) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, name='cosseratMapping', + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node + + +def createScene(root_node): + root_node.addObject('VisualStyle', displayFlags='hideBehaviorModels hideCollisionModels hideMechanicalMappings') +# root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass='0.0') +# root_node.addObject('SparseLDLSolver', name='solver') + + addHeader(root_node) + # root_node.gravity = [0, 0, 0] + root_node.gravity = [0, -9.81, 0.] + + solver_node_1 = addSolverNode(root_node, name="solver_node_1") + solver_node_2 = addSolverNode(root_node, name="solver_node_2") + + # Add rigid base + base_node = _add_rigid_base(solver_node_1) + base_node_2 = _add_rigid_base(solver_node_2,_name='rigid_base2') + + # build beam geometry + + length_s = beam_length/float(nb_sections) + bending_states = [] + bending_states_2 = [] + list_sections_length = [] + temp = 0. # where to start the base position + section_curv_abs = [0.] # section/segment curve abscissa + + for i in range(nb_sections): + bending_states.append([0, 0., 0., 0, 0., 0.]) # torsion, y-bending, z-bending, elongation, y-shear and z-shear + bending_states_2.append([0, 0., 0.]) # torsion, y-bending + list_sections_length.append((((i + 1) * length_s) - i * length_s)) + temp += list_sections_length[i] + section_curv_abs.append(temp) + bending_states[nb_sections-1] = [0, 0.0, 0.0, 1, 0., 0.] + bending_states_2[nb_sections-1] = [0, 0.0, 0.0] +# bending_states[nb_sections-1] = [1., 0., 0., 0., 0., 0.] + + # call add cosserat state and force field + bending_node = _add_cosserat_state(solver_node_1, bending_states, list_sections_length) + bending_node_2 = _add_cosserat_state(solver_node_2, bending_states_2, list_sections_length,_template='Vec3d') + + # comment : ??? + + length_f = beam_length/float(nb_frames) + cosserat_G_frames = [] + frames_curv_abs = [] + cable_position_f = [] # need sometimes for drawing segment + x, y, z = 0, 0, 0 + + for i in range(nb_frames+1): + sol = i * length_f + cosserat_G_frames.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + frames_curv_abs.append(sol + x) + + cosserat_G_frames[nb_frames] = [beam_length + x, y, z, 0, 0, 0, 1] + cable_position_f[nb_frames] = [beam_length + x, y, z] + frames_curv_abs[nb_frames] = beam_length + x + + cosserat_frames = _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + cosserat_frames_2 = _add_cosserat_frame(base_node_2, bending_node_2, cosserat_G_frames, section_curv_abs, frames_curv_abs, + beam_radius) + + ## Add a force component to test the stretch + #applied_force =[-1.e1, 0., 0, 0, 0, 0] + #cosserat_frames.addObject('ConstantForceField', name='constForce', showArrowSize=1e10, indices=nb_frames, forces=applied_force) + + return root_node diff --git a/examples/python3/tutorial/scene_w9991.py b/examples/python3/tutorial/scene_w9991.py new file mode 100644 index 00000000..c6df8f14 --- /dev/null +++ b/examples/python3/tutorial/scene_w9991.py @@ -0,0 +1,129 @@ +import Sofa +from useful.params import BeamPhysicsParameters, BeamGeometryParameters, SimulationParameters, Parameters + +geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30.0, nbSection=6, nbFrames=24, +showFramesObject=1, buildCollisionModel=0) +physicsParams = BeamPhysicsParameters(beamMass=1.0, youngModulus=1.0e4, poissonRatio=0.38, +beamRadius=0.2, beamLength=30.0) +simuParams = SimulationParameters() +Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +stiffness_param = 1.e10 + +def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template="Rigid3d", name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", showObject=1, showObjectScale="0.1") + rigid_base_node.addObject('RestShapeSpringsForceField', template="Rigid3d", name="spring", + stiffness=stiffness_param, angularStiffness=stiffness_param, + mstate="@cosserat_base_mo", external_points="0", points="0") + return rigid_base_node + + +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=0.2, _innerRadius=0.05): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + cosserat_coordinate_node.addObject('MechanicalObject', template="Vec3d", name="cosserat_state", + position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape="circular", innerRadius=_innerRadius, + length=list_sections_length, radius=_radius,youngModulus=physicsParams.youngModulus, poissonRatio=physicsParams.poissonRatio) + return cosserat_coordinate_node + +def _add_cosserat_frame(p_node, _bending_node, nb_framesF, _section_curv_abs, _frame_curv_abs, _radius=0.2, _innerRadius=0.05): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template="Rigid3d", name="FramesMO", + position=nb_framesF, showIndices=0, showObject=0, showObjectScale=0.8) + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=physicsParams.beamMass) + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', name="cosseratMapping", + curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs, + input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node + +def createScene(root_node): + root_node.addObject('RequiredPlugin', name="plugins", pluginName=[ + "Cosserat", # Needed to use components [BeamHookeLawForceField,DiscreteCosseratMapping] + "Sofa.Component.AnimationLoop", # Needed to use components [FreeMotionAnimationLoop] + "Sofa.Component.Collision.Detection.Algorithm", + "Sofa.Component.Collision.Detection.Intersection", # Needed to use components [LocalMinDistance] + "Sofa.Component.Collision.Geometry", + "Sofa.Component.Collision.Response.Contact", # Needed to use components [RuleBasedContactManager] + "Sofa.Component.Constraint.Lagrangian.Correction", # Needed to use components [GenericConstraintCorrection] + "Sofa.Component.Constraint.Lagrangian.Solver", # Needed to use components [GenericConstraintSolver] + "Sofa.Component.Constraint.Projective", # Needed to use components [FixedConstraint] + "Sofa.Component.Engine.Select", + "Sofa.Component.IO.Mesh", # Needed to use components MeshOBJLoader, MeshSTLLoader + "Sofa.Component.ODESolver.Backward", # Needed to use components [EulerImplicitSolver] + "Sofa.Component.LinearSolver.Direct", # Needed to use components [SparseLDLSolver] + "Sofa.Component.Mapping.Linear", + "Sofa.Component.Mass", # Needed to use components [UniformMass] + "Sofa.Component.MechanicalLoad", + "Sofa.Component.MechanicalLoad", + "Sofa.Component.ODESolver.Backward", + "Sofa.Component.Playback", + "Sofa.Component.Setting", # Needed to use components [BackgroundSetting] + "Sofa.Component.SolidMechanics.FEM.Elastic", + "Sofa.Component.SolidMechanics.FEM.HyperElastic", + "Sofa.Component.SolidMechanics.Spring", # Needed to use components [RestShapeSpringsForceField] + "Sofa.Component.StateContainer", # Needed to use components [MechanicalObject] + "Sofa.Component.Topology.Container.Constant", # Needed to use components [MeshTopology] + "Sofa.Component.Topology.Container.Dynamic", + "Sofa.Component.Topology.Container.Grid", # Needed to use components [RegularGridTopology] + "Sofa.Component.Topology.Mapping", # Needed to use components [Edge2QuadTopologicalMapping] + "Sofa.Component.Visual", # Needed to use components [VisualStyle] + "Sofa.GL.Component.Rendering3D", # Needed to use components [OglGrid, OglModel] + "Sofa.GUI.Component"]) + + + root_node.addObject('VisualStyle', displayFlags="showVisualModels showBehaviorModels showMechanicalMappings") + + root_node.gravity = [0.0, -9.18, 0.0] + root_node.dt = 0.01 + + root_node.addObject('FreeMotionAnimationLoop') + root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass="0.0") + root_node.addObject('GenericConstraintSolver', maxIterations="500", tolerance="1e-20", computeConstraintForces=1, printLog="0") + root_node.addObject('SparseLDLSolver', name="solver", template="CompressedRowSparseMatrixd") + + base_node = _add_rigid_base(root_node) + + nb_sections = geoParams.nbSection + beam_length = geoParams.beamLength + length_s = beam_length/float(nb_sections) + bending_states = [] + list_sections_length = [] + temp = 0.0 + section_curv_abs = [0.0] + + for i in range(nb_sections): + bending_states.append([0, 0.0, 0.0]) + list_sections_length.append((((i+1)*length_s)-i*length_s)) + temp += list_sections_length[i] + section_curv_abs.append(temp) + bending_states[nb_sections-1] = [0, 0.2, 0.0] + bending_states[nb_sections-2] = [0, 0.2, 0.0] + section_curv_abs[nb_sections] = beam_length + + bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) + nb_frames = geoParams.nbFrames + length_f = beam_length/float(nb_frames) + cosserat_G_frames = [] + frames_curv_abs = [] + cable_position_f = [] + x, y, z = 0, 0, 0 + + for i in range(nb_frames): + sol = i * length_f + cosserat_G_frames.append([sol + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([sol + x, y, z]) + frames_curv_abs.append(sol + x) + + cosserat_G_frames.append([beam_length + x, y, z, 0, 0, 0, 1]) + cable_position_f.append([beam_length + x, y, z]) + frames_curv_abs.append(beam_length + x) + + _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs) + + + + return root_node diff --git a/examples/python3/useful/draw_mesh.py b/examples/python3/useful/draw_mesh.py new file mode 100644 index 00000000..33298fc6 --- /dev/null +++ b/examples/python3/useful/draw_mesh.py @@ -0,0 +1,69 @@ +# import matplotlib.pyplot as plt +# from mpl_toolkits.mplot3d import Axes3D + +# # Define the vertices of the tetrahedron +# vertices = [ +# [0, 0, 0], +# [0.6, 0, 0], +# [0.35, 1, 0], +# [0.35, 0.35, 1] +# ] + +# # Define the edges of the tetrahedron +# edges = [ +# [0, 1], +# [0, 2], +# [0, 3], +# [1, 2], +# [1, 3], +# [2, 3] +# ] + +# # Create a 3D plot +# fig = plt.figure() +# ax = fig.add_subplot(111, projection='3d') + +# # Plot the vertices +# for vertex in vertices: +# ax.scatter(vertex[0], vertex[1], vertex[2], c='r') + +# # Plot the edges with colors +# for edge in edges: +# ax.plot([vertices[edge[0]][0], vertices[edge[1]][0]], +# [vertices[edge[0]][1], vertices[edge[1]][1]], +# [vertices[edge[0]][2], vertices[edge[1]][2]], c='g', marker='o') + +# # Set the plot limits +# ax.set_xlim([0, 1]) +# ax.set_ylim([0, 1]) +# ax.set_zlim([0, 1]) + +# # Show the plot +# plt.show() + + +# # Show the plot +# plt.show() + + + +from mpl_toolkits.mplot3d import Axes3D +import matplotlib.pyplot as plt +import numpy as np + +fig = plt.figure() +ax = fig.add_subplot(111, projection='3d') + +# Tetrahedron vertices +tetra_vertices = np.array([[0, 0, 0], [1, 0, 0], [0.5, 1, 0], [0.5, 0.5, np.sqrt(2)/2]]) + + +# Plot tetrahedron +c1 = (105./255.,212./255,207./255) +ax.scatter(tetra_vertices[:, 0], tetra_vertices[:, 1], tetra_vertices[:, 2], c=c1, marker='o') +c2 = (39./255.,98./255,94./255) + +ax.plot_trisurf(tetra_vertices[:, 0], tetra_vertices[:, 1], tetra_vertices[:, 2], linewidth=0.5, antialiased=True, color=c2) + +plt.show() +#ax.plot_trisurf(tetra_vertices[:, 0], tetra_vertices[:, 1], tetra_vertices[:, 2], linewidth=0.5, antialiased=True, color='bluegreen') diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index 8071197c..abdd86f0 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -34,7 +34,7 @@ template<> BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::build_Xi_hat(const Coord1& strain_i){ se3 Xi; - msg_info("BaseCosserat")<<" ===========> Build Xi Hat rigid is called "; + //msg_info("BaseCosserat")<<" ===========> Build Xi Hat rigid is called "; Xi[0][1] = -strain_i(2); Xi[0][2] = strain_i[1]; @@ -46,11 +46,11 @@ BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, R Xi[0][3] = 1.0; - std::cout <<"Before the linear part : "<< Xi <<std::endl; + //std::cout <<"Before the linear part : "<< Xi <<std::endl; for (unsigned int i=0; i<3; i++) Xi[i][3] += strain_i(i+3); - std::cout <<"After the linear part : "<< Xi <<std::endl; + //std::cout <<"After the linear part : "<< Xi <<std::endl; // se3 = [ // 0 -screw(3) screw(2) screw(4); diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index f58711d3..0dbc482f 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -47,7 +47,7 @@ template <class TIn1, class TIn2, class TOut> BaseCosserat<TIn1, TIn2, TOut>::BaseCosserat() : d_curv_abs_section(initData(&d_curv_abs_section, "curv_abs_input", " need to be com....")) , d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", " need to be com....")) - , d_debug( initData( &d_debug, true,"debug", "printf for the debug")) + , d_debug( initData( &d_debug, false,"debug", "printf for the debug")) , m_fromModel1(NULL) , m_fromModel2(NULL) , m_toModel(NULL) diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 10f83c8e..cd5ff792 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -598,6 +598,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw(const core::visual::VisualP const In1VecCoord xPos = artiData->getValue(); RGBAColor drawColor = d_color.getValue(); + // draw each segment of the beam as a cylinder. for (unsigned int i=0; i<sz-1; i++) vparams->drawTool()->drawCylinder(positions[i], positions[i+1], d_radius.getValue(), drawColor); From 6efb5b63d5b7536ea2a3be67313ceb4ea583f8fb Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 1 Mar 2024 08:58:39 +0100 Subject: [PATCH 31/71] update files and fix some bugs Update files and fix some bugs related to sofa version --- examples/python3/actuators/cable.py | 74 +-- examples/python3/cosserat/CosseratBase.py | 250 ++++++---- examples/python3/cosserat/usefulFunctions.py | 458 ++++++++++++++----- examples/python3/useful/params.py | 39 +- 4 files changed, 577 insertions(+), 244 deletions(-) diff --git a/examples/python3/actuators/cable.py b/examples/python3/actuators/cable.py index 3f54a60e..465508f1 100644 --- a/examples/python3/actuators/cable.py +++ b/examples/python3/actuators/cable.py @@ -1,13 +1,15 @@ -def PullingCable(attachedTo=None, - name="Cable", - cableGeometry=[[1.0, 0.0, 0.0], [0.0, 0.0, 0.0]], - rotation=[0.0, 0.0, 0.0], - translation=[0.0, 0.0, 0.0], - uniformScale=1.0, - pullPointLocation=None, - initialValue=0.0, - valueType="displacement", - input=None): +def PullingCable( + attachedTo=None, + name="Cable", + cableGeometry=[[1.0, 0.0, 0.0], [0.0, 0.0, 0.0]], + rotation=[0.0, 0.0, 0.0], + translation=[0.0, 0.0, 0.0], + uniformScale=1.0, + pullPointLocation=None, + initialValue=0.0, + valueType="displacement", + input=None, +): """Adds a cable constraint. The constraint apply to a parent mesh. @@ -42,32 +44,44 @@ def PullingCable(attachedTo=None, """ # This add a new node in the scene. This node is appended to the finger's node. - cable = attachedTo.addChild(name) + if attachedTo is not None: + cable = attachedTo.addChild(name) + else: + print("Attach node to the pulling cable!") + return # This add a MechanicalObject, a component holding the degree of freedom of our # mechanical modelling. In the case of a cable it is a set of positions specifying # the points where the cable is passing by. - cable.addObject('MechanicalObject', position=cableGeometry, showIndices="1", - rotation=rotation, translation=translation, scale=uniformScale) + cable.addObject( + "MechanicalObject", + position=cableGeometry, + showIndices="1", + rotation=rotation, + translation=translation, + scale=uniformScale, + ) # Add a CableConstraint object with a name. # the indices are referring to the MechanicalObject's positions. # The last indice is where the pullPoint is connected. if pullPointLocation is not None: - cable.addObject('CableConstraint', - indices=list(range(len(cableGeometry))), - pullPoint=pullPointLocation, - value=initialValue, - valueType=valueType, - hasPullPoint=True - ) + cable.addObject( + "CableConstraint", + indices=list(range(len(cableGeometry))), + pullPoint=pullPointLocation, + value=initialValue, + valueType=valueType, + hasPullPoint=True, + ) else: - cable.addObject('CableConstraint', - indices=list(range(len(cableGeometry))), - value=initialValue, - valueType=valueType, - hasPullPoint=False - ) + cable.addObject( + "CableConstraint", + indices=list(range(len(cableGeometry))), + value=initialValue, + valueType=valueType, + hasPullPoint=False, + ) # This add a BarycentricMapping. A BarycentricMapping is a key element as it will add a bi-directional link # between the cable's DoFs and the parents's ones so that movements of the cable's DoFs will be mapped @@ -75,7 +89,7 @@ def PullingCable(attachedTo=None, # cable.addObject('BarycentricMapping', name="Mapping", mapForces=False, mapMasses=False, # input=input) # cable.addObject('RigidMapping', name="Mapping") - cable.addObject('IdentityMapping', name="Mapping") + cable.addObject("IdentityMapping", name="Mapping") return cable @@ -85,8 +99,8 @@ def createScene(node): from stlib3.physics.deformable import ElasticMaterialObject MainHeader(node, plugins=["SoftRobots"]) - target = ElasticMaterialObject(volumeMeshFileName="mesh/liver.msh", - totalMass=0.5, - attachedTo=node) + target = ElasticMaterialObject( + volumeMeshFileName="mesh/liver.msh", totalMass=0.5, attachedTo=node + ) PullingCable(target) diff --git a/examples/python3/cosserat/CosseratBase.py b/examples/python3/cosserat/CosseratBase.py index 0a6aac98..0a38e424 100644 --- a/examples/python3/cosserat/CosseratBase.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -1,6 +1,6 @@ # -*- coding: utf-8 -*- """ - Cosserat class in SofaPython3. +Cosserat class in SofaPython3. """ __authors__ = "adagolodjo" @@ -32,45 +32,72 @@ class CosseratBase(Sofa.Prefab): params """ + prefabParameters = [ - {'name': 'name', 'type': 'string', 'help': 'Node name', 'default': 'Cosserat'}, - {'name': 'translation', 'type': 'Vec3d', 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, - {'name': 'rotation', 'type': 'Vec3d', 'help': 'Cosserat base Rotation', 'default': [0., 0., 0.]}, - {'name': 'attachingToLink', 'type': 'string', 'help': 'a rest shape force field will constraint the object ' - 'to follow arm position', 'default': '1'}, - {'name': 'showObject', 'type': 'string', 'help': ' Draw object arrow ', 'default': '0'} + {"name": "name", "type": "string", "help": "Node name", "default": "Cosserat"}, + { + "name": "translation", + "type": "Vec3d", + "help": "Cosserat base Rotation", + "default": [0.0, 0.0, 0.0], + }, + { + "name": "rotation", + "type": "Vec3d", + "help": "Cosserat base Rotation", + "default": [0.0, 0.0, 0.0], + }, + { + "name": "attachingToLink", + "type": "string", + "help": "a rest shape force field will constraint the object " + "to follow arm position", + "default": "1", + }, + { + "name": "showObject", + "type": "string", + "help": " Draw object arrow ", + "default": "0", + }, ] def __init__(self, *args, **kwargs): Sofa.Prefab.__init__(self, *args, **kwargs) - self.params = kwargs.get('params', Parameters()) # Use the Parameters class with default values + self.params = kwargs.get( + "params", Parameters() + ) # Use the Parameters class with default values beamPhysicsParams = self.params.beamPhysicsParams beamGeometryParams = self.params.beamGeoParams self.beamMass = beamPhysicsParams.beamMass # self.cosseratGeometry['beamMass'] - self.parent = kwargs.get('parent') + self.parent = kwargs.get("parent") self.useInertiaParams = beamPhysicsParams.useInertia # False self.radius = beamPhysicsParams.beamRadius # kwargs.get('radius') if self.parent.hasObject("EulerImplicitSolver") is False: - print('The code does not have parent EulerImplicit') + print("The code does not have parent EulerImplicit") self.solverNode = addSolverNode(self.parent) else: self.solverNode = self.parent - if 'inertialParams' in kwargs: + if "inertialParams" in kwargs: self.useInertiaParams = True - self.inertialParams = kwargs['inertialParams'] + self.inertialParams = kwargs["inertialParams"] self.rigidBaseNode = self._addRigidBaseNode() cosserat_geometry = CosseratGeometry(beamGeometryParams) self.frames3D = cosserat_geometry.cable_positionF - self.cosseratCoordinateNode = self._addCosseratCoordinate(cosserat_geometry.bendingState, - cosserat_geometry.sectionsLengthList) - self.cosseratFrame = self._addCosseratFrame(cosserat_geometry.framesF, cosserat_geometry.curv_abs_inputS, - cosserat_geometry.curv_abs_outputF) + self.cosseratCoordinateNode = self._addCosseratCoordinate( + cosserat_geometry.bendingState, cosserat_geometry.sectionsLengthList + ) + self.cosseratFrame = self._addCosseratFrame( + cosserat_geometry.framesF, + cosserat_geometry.curv_abs_inputS, + cosserat_geometry.curv_abs_outputF, + ) def init(self): pass @@ -79,62 +106,93 @@ def addCollisionModel(self): tab_edges = generate_edge_list(self.frames3D) return addEdgeCollision(self.cosseratFrame, self.frames3D, tab_edges) - def _addPointCollisionModel(self, nodeName='CollisionPoints'): + def _addPointCollisionModel(self, nodeName="CollisionPoints"): tab_edges = generate_edge_list(self.frames3D) - return addPointsCollision(self.cosseratFrame, self.frames3D, tab_edges, nodeName) + return addPointsCollision( + self.cosseratFrame, self.frames3D, tab_edges, nodeName + ) def _addSlidingPoints(self): - slidingPoint = self.cosseratFrame.addChild('slidingPoint') - slidingPoint.addObject('MechanicalObject', name="slidingPointMO", position=self.frames3D, - showObject="0", showIndices="0") - slidingPoint.addObject('IdentityMapping') + slidingPoint = self.cosseratFrame.addChild("slidingPoint") + slidingPoint.addObject( + "MechanicalObject", + name="slidingPointMO", + position=self.frames3D, + showObject="0", + showIndices="0", + ) + slidingPoint.addObject("IdentityMapping") return slidingPoint def _addSlidingPointsWithContainer(self): - slidingPoint = self.cosseratFrame.addChild('slidingPoint') + slidingPoint = self.cosseratFrame.addChild("slidingPoint") slidingPoint.addObject("PointSetTopologyContainer") slidingPoint.addObject("PointSetTopologyModifier") - slidingPoint.addObject('MechanicalObject', name="slidingPointMO", position=self.frames3D, - showObject="1", showIndices="0") - slidingPoint.addObject('IdentityMapping') + slidingPoint.addObject( + "MechanicalObject", + name="slidingPointMO", + position=self.frames3D, + showObject="1", + showIndices="0", + ) + slidingPoint.addObject("IdentityMapping") return slidingPoint def _addRigidBaseNode(self): - rigidBaseNode = self.addChild('rigidBase') + rigidBaseNode = self.addChild("rigidBase") trans = list(self.translation.value) rot = list(self.rotation.value) - positions = [[self.params.beamGeoParams.init_pos] + [0., 0., 0., 1.]] - - rigidBaseNode.addObject('MechanicalObject', template='Rigid3d', name="RigidBaseMO", showObjectScale=0.2, - translation=trans, position=positions, rotation=rot, - showObject=int(self.showObject.value)) + positions = [[self.params.beamGeoParams.init_pos] + [0.0, 0.0, 0.0, 1.0]] + + rigidBaseNode.addObject( + "MechanicalObject", + template="Rigid3d", + name="RigidBaseMO", + showObjectScale=0.2, + translation=trans, + position=positions, + rotation=rot, + showObject=int(self.showObject.value), + ) # one can choose to set this to false and directly attach the beam base # to a control object in order to be able to drive it. if int(self.attachingToLink.value): print("Adding the rest shape to the base") - rigidBaseNode.addObject('RestShapeSpringsForceField', name='spring', stiffness=1e8, angularStiffness=1.e8, - external_points=0, mstate="@RigidBaseMO", points=0, template="Rigid3d") + rigidBaseNode.addObject( + "RestShapeSpringsForceField", + name="spring", + stiffness=1e8, + angularStiffness=1.0e8, + external_points=0, + mstate="@RigidBaseMO", + points=0, + template="Rigid3d", + ) return rigidBaseNode def _addCosseratCoordinate(self, bendingStates, listOfSectionsLength): - cosseratCoordinateNode = self.addChild('cosseratCoordinate') - cosseratCoordinateNode.addObject('MechanicalObject', - template='Vec3d', name='cosseratCoordinateMO', - position=bendingStates, - showIndices=0) + cosseratCoordinateNode = self.addChild("cosseratCoordinate") + cosseratCoordinateNode.addObject( + "MechanicalObject", + template="Vec3d", + name="cosseratCoordinateMO", + position=bendingStates, + showIndices=0, + ) if self.useInertiaParams is False: - cosseratCoordinateNode.addObject('BeamHookeLawForceField', - crossSectionShape=self.params.beamPhysicsParams.beamShape, - length=listOfSectionsLength, - radius=self.radius, - youngModulus=self.params.beamPhysicsParams.youngModulus, - poissonRatio=self.params.beamPhysicsParams.poissonRatio, - rayleighStiffness=self.params.simuParams.rayleighStiffness, - lengthY=self.params.beamPhysicsParams.length_Y, - lengthZ=self.params.beamPhysicsParams.length_Z - ) + cosseratCoordinateNode.addObject( + "BeamHookeLawForceField", + crossSectionShape=self.params.beamPhysicsParams.beamShape, + length=listOfSectionsLength, + radius=self.radius, + youngModulus=self.params.beamPhysicsParams.youngModulus, + poissonRatio=self.params.beamPhysicsParams.poissonRatio, + rayleighStiffness=self.params.simuParams.rayleighStiffness, + lengthY=self.params.beamPhysicsParams.length_Y, + lengthZ=self.params.beamPhysicsParams.length_Z, + ) else: self._extracted_from_addCosseratCoordinate_15( cosseratCoordinateNode, listOfSectionsLength @@ -142,39 +200,56 @@ def _addCosseratCoordinate(self, bendingStates, listOfSectionsLength): return cosseratCoordinateNode # TODO Rename this here and in `addCosseratCoordinate` - def _extracted_from_addCosseratCoordinate_15(self, cosseratCoordinateNode, listOfSectionsLength): + def _extracted_from_addCosseratCoordinate_15( + self, cosseratCoordinateNode, listOfSectionsLength + ): GA = self.params.beamPhysicsParams.GA GI = self.params.beamPhysicsParams.GI EA = self.params.beamPhysicsParams.EA EI = self.params.beamPhysicsParams.EI - cosseratCoordinateNode.addObject('BeamHookeLawForceField', - crossSectionShape=self.params.beamPhysicsParams.beamShape, - length=listOfSectionsLength, - radius=self.params.beamPhysicsParams.beamRadius, - useInertiaParams=True, - GI=GI, GA=GA, EI=EI, EA=EA, - rayleighStiffness=self.rayleighStiffness.value, - lengthY=self.params.beamPhysicsParams.length_Y, - lengthZ=self.params.beamPhysicsParams.length_Z) + cosseratCoordinateNode.addObject( + "BeamHookeLawForceField", + crossSectionShape=self.params.beamPhysicsParams.beamShape, + length=listOfSectionsLength, + radius=self.params.beamPhysicsParams.beamRadius, + useInertiaParams=True, + GI=GI, + GA=GA, + EI=EI, + EA=EA, + rayleighStiffness=self.rayleighStiffness.value, + lengthY=self.params.beamPhysicsParams.length_Y, + lengthZ=self.params.beamPhysicsParams.length_Z, + ) def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): - - cosseratInSofaFrameNode = self.rigidBaseNode.addChild( - 'cosseratInSofaFrameNode') + cosseratInSofaFrameNode = self.rigidBaseNode.addChild("cosseratInSofaFrameNode") self.cosseratCoordinateNode.addChild(cosseratInSofaFrameNode) framesMO = cosseratInSofaFrameNode.addObject( - 'MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, + "MechanicalObject", + template="Rigid3d", + name="FramesMO", + position=framesF, showIndices=self.params.beamGeoParams.showFramesObject, - showObject=self.params.beamGeoParams.showFramesObject, showObjectScale=1.8) - if self.beamMass != 0.: + showObject=self.params.beamGeoParams.showFramesObject, + showObjectScale=1.8, + ) + if self.beamMass != 0.0: cosseratInSofaFrameNode.addObject( - 'UniformMass', totalMass=self.beamMass, showAxisSizeFactor='0') + "UniformMass", totalMass=self.beamMass, showAxisSizeFactor="0" + ) - cosseratInSofaFrameNode.addObject('DiscreteCosseratMapping', curv_abs_input=curv_abs_inputS, - curv_abs_output=curv_abs_outputF, name='cosseratMapping', - input1=self.cosseratCoordinateNode.cosseratCoordinateMO.getLinkPath(), - input2=self.rigidBaseNode.RigidBaseMO.getLinkPath(), - output=framesMO.getLinkPath(), debug=0, radius=self.radius) + cosseratInSofaFrameNode.addObject( + "DiscreteCosseratMapping", + curv_abs_input=curv_abs_inputS, + curv_abs_output=curv_abs_outputF, + name="cosseratMapping", + input1=self.cosseratCoordinateNode.cosseratCoordinateMO.getLinkPath(), + input2=self.rigidBaseNode.RigidBaseMO.getLinkPath(), + output=framesMO.getLinkPath(), + debug=0, + radius=self.radius, + ) return cosseratInSofaFrameNode @@ -185,29 +260,30 @@ def createScene(rootNode): addHeader(rootNode) addVisual(rootNode) - rootNode.findData('dt').value = 0.01 - rootNode.findData('gravity').value = [0., -9.81, 0.] - rootNode.addObject('BackgroundSetting', color='0 0.168627 0.211765') - rootNode.addObject('FreeMotionAnimationLoop') - rootNode.addObject('GenericConstraintSolver', tolerance=1e-5, maxIterations=5e2) - rootNode.addObject('Camera', position="-35 0 280", lookAt="0 0 0") - - solverNode = rootNode.addChild('solverNode') - solverNode.addObject('EulerImplicitSolver', - rayleighStiffness="0.2", rayleighMass='0.1') - solverNode.addObject('SparseLDLSolver', name='solver', - template="CompressedRowSparseMatrixd") - solverNode.addObject('GenericConstraintCorrection') + rootNode.findData("dt").value = 0.01 + rootNode.findData("gravity").value = [0.0, -9.81, 0.0] + rootNode.addObject("BackgroundSetting", color="0 0.168627 0.211765") + rootNode.addObject("FreeMotionAnimationLoop") + rootNode.addObject("GenericConstraintSolver", tolerance=1e-5, maxIterations=5e2) + rootNode.addObject("Camera", position="-35 0 280", lookAt="0 0 0") + + solverNode = rootNode.addChild("solverNode") + solverNode.addObject( + "EulerImplicitSolver", rayleighStiffness="0.2", rayleighMass="0.1" + ) + solverNode.addObject( + "SparseLDLSolver", name="solver", template="CompressedRowSparseMatrixd" + ) + solverNode.addObject("GenericConstraintCorrection") # Create a - cosserat = solverNode.addChild( - CosseratBase(parent=solverNode, params=Params)) + cosserat = solverNode.addChild(CosseratBase(parent=solverNode, params=Params)) # use this to add the collision if the beam will interact with another object cosserat.addCollisionModel() # Attach a force at the beam tip, # we can attach this force to a non-mechanical node to control the beam in order to be able to drive it. - beamFrame = cosserat.cosseratFrame + cosserat.cosseratFrame return rootNode diff --git a/examples/python3/cosserat/usefulFunctions.py b/examples/python3/cosserat/usefulFunctions.py index c91c3b9b..bdec3c31 100644 --- a/examples/python3/cosserat/usefulFunctions.py +++ b/examples/python3/cosserat/usefulFunctions.py @@ -17,44 +17,180 @@ import Sofa import numpy as np import math -from splib3.numerics import Vec3, Quat +from splib3.numerics import Quat # from stlib3.scene import MainScene lenSoftPart = 0.5 -rateLength = [1.2, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, - 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, 0.7, 0.5, - 0.7, 0.5, 0.7, 0.5, 0.45] +rateLength = [ + 1.2, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.7, + 0.5, + 0.45, +] draw_cylinder = 1 add_collision_point = 1 -pluginList = ['Cosserat', - 'Sofa.Component.AnimationLoop', - 'Sofa.Component.LinearSolver.Iterative', 'Sofa.Component.LinearSolver.Direct', 'Sofa.Component.StateContainer', - 'Sofa.Component.SolidMechanics.FEM.Elastic', 'Sofa.Component.SolidMechanics.Spring', 'Sofa.Component.MechanicalLoad', 'Sofa.Component.Mass', - 'Sofa.Component.Topology.Container.Dynamic', 'Sofa.Component.Topology.Container.Grid', - 'Sofa.Component.ODESolver.Backward', - 'Sofa.Component.Mapping.Linear', 'Sofa.Component.Mapping.NonLinear', 'Sofa.Component.Topology.Mapping', - 'Sofa.Component.Collision.Geometry', 'Sofa.Component.Collision.Detection.Algorithm','Sofa.Component.Collision.Detection.Intersection','Sofa.Component.Collision.Response.Contact', - 'Sofa.Component.Constraint.Lagrangian.Correction','Sofa.Component.Constraint.Lagrangian.Solver', - 'Sofa.Component.Engine.Select', - 'Sofa.GL.Component.Rendering3D', 'Sofa.Component.Setting', 'Sofa.Component.SceneUtility', 'Sofa.Component.IO.Mesh', 'Sofa.Component.Visual' - ] +pluginList = [ + "Cosserat", + "Sofa.Component.AnimationLoop", + "Sofa.Component.LinearSolver.Iterative", + "Sofa.Component.LinearSolver.Direct", + "Sofa.Component.StateContainer", + "Sofa.Component.SolidMechanics.FEM.Elastic", + "Sofa.Component.SolidMechanics.Spring", + "Sofa.Component.MechanicalLoad", + "Sofa.Component.Mass", + "Sofa.Component.Topology.Container.Dynamic", + "Sofa.Component.Topology.Container.Grid", + "Sofa.Component.ODESolver.Backward", + "Sofa.Component.Mapping.Linear", + "Sofa.Component.Mapping.NonLinear", + "Sofa.Component.Topology.Mapping", + "Sofa.Component.Collision.Geometry", + "Sofa.Component.Collision.Detection.Algorithm", + "Sofa.Component.Collision.Detection.Intersection", + "Sofa.Component.Collision.Response.Contact", + "Sofa.Component.Constraint.Lagrangian.Correction", + "Sofa.Component.Constraint.Lagrangian.Solver", + "Sofa.Component.Engine.Select", + "Sofa.GL.Component.Rendering3D", + "Sofa.Component.Setting", + "Sofa.Component.SceneUtility", + "Sofa.Component.IO.Mesh", + "Sofa.Component.Visual", +] PRig = 0.38 # poison ratio for the rigid part of the beam PSoft = 0.43 # poison ratio for the soft part of the beam -poisonRatioList = [PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, - PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, - PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft, PRig, PSoft] +poisonRatioList = [ + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, + PRig, + PSoft, +] # YRig = 215.e11 -YRig = 215.e9 - -temp = [8.1e4, YRig, 3.1e4, YRig, 2.5e4, YRig, 2.3e4, YRig, 2.4e4, YRig, 2.3e4, YRig, 1.95e4, YRig, - 1.93e4, YRig, 1.52e4, YRig, 1.03e4, YRig, 1.14e4, YRig, 1.07e4, YRig, 7.9e3, YRig, 7.3e3, - YRig, 6.0e3, YRig, 5.0e3, YRig, 2.975e3, YRig, 1.77e3, YRig, 1.615e3, YRig, 9.25e2, YRig, - 9.25e2] +YRig = 215.0e9 + +temp = [ + 8.1e4, + YRig, + 3.1e4, + YRig, + 2.5e4, + YRig, + 2.3e4, + YRig, + 2.4e4, + YRig, + 2.3e4, + YRig, + 1.95e4, + YRig, + 1.93e4, + YRig, + 1.52e4, + YRig, + 1.03e4, + YRig, + 1.14e4, + YRig, + 1.07e4, + YRig, + 7.9e3, + YRig, + 7.3e3, + YRig, + 6.0e3, + YRig, + 5.0e3, + YRig, + 2.975e3, + YRig, + 1.77e3, + YRig, + 1.615e3, + YRig, + 9.25e2, + YRig, + 9.25e2, +] youngModulusList = [x * 4 for x in temp] @@ -69,12 +205,50 @@ The first soft beam has no parameter, because it was not tested in the experimental part. But we set it to 0.36 like beam 1. The rigid part has no parameter, but we set it to 100, in order to simplify the code """ -rPlastic = 100. -plasticityTab = [0.36, rPlastic, 0.36, rPlastic, 0.35, rPlastic, 0.41, rPlastic, 0.34, rPlastic, 0.42, rPlastic, 0.48, - rPlastic, 0.45, rPlastic, 0.54, rPlastic, 0.17, rPlastic, 0.20, rPlastic, 0.2, rPlastic, 0.15, - rPlastic, - 0.15, rPlastic, 0.12, rPlastic, 0.2, rPlastic, 0.3, rPlastic, 0.3, rPlastic, 0.3, rPlastic, 0.3, - rPlastic, 0.3] +rPlastic = 100.0 +plasticityTab = [ + 0.36, + rPlastic, + 0.36, + rPlastic, + 0.35, + rPlastic, + 0.41, + rPlastic, + 0.34, + rPlastic, + 0.42, + rPlastic, + 0.48, + rPlastic, + 0.45, + rPlastic, + 0.54, + rPlastic, + 0.17, + rPlastic, + 0.20, + rPlastic, + 0.2, + rPlastic, + 0.15, + rPlastic, + 0.15, + rPlastic, + 0.12, + rPlastic, + 0.2, + rPlastic, + 0.3, + rPlastic, + 0.3, + rPlastic, + 0.3, + rPlastic, + 0.3, + rPlastic, + 0.3, +] def formated(value): @@ -82,7 +256,7 @@ def formated(value): def buildEdges(cable3DPos): - """ This function is used to build edges required in the EdgeSetTopologyContainer component""" + """This function is used to build edges required in the EdgeSetTopologyContainer component""" points_size = len(cable3DPos) edgeList = [] for i in range(0, points_size - 1): @@ -96,12 +270,11 @@ def __init__(self, *args, **kwargs): Sofa.Core.Controller.__init__(self, *args, **kwargs) self.rigidBaseNode = args[0] self.rateAngularDeformNode = args[1] - self.frameNode = args[0].getChild('MappedFrames') - self.cable3DPosNode = self.frameNode.getChild( - 'CollisInstrumentCombined') - self.rigidBaseMO = self.rigidBaseNode.getChild('RigidBaseMO') + self.frameNode = args[0].getChild("MappedFrames") + self.cable3DPosNode = self.frameNode.getChild("CollisInstrumentCombined") + self.rigidBaseMO = self.rigidBaseNode.getChild("RigidBaseMO") self.dX = 0.0025 - self.angularRate = 15. + self.angularRate = 15.0 self.length = 12.95 # Cosserat frames parameters self.nbFrames = 55 @@ -114,7 +287,7 @@ def __init__(self, *args, **kwargs): self.nbSection = 22 self.rateAngular = [] - leng = 0. + leng = 0.0 for i in range(len(rateLength)): leng = rateLength[i] + leng self.length = leng @@ -124,25 +297,25 @@ def __init__(self, *args, **kwargs): for i in range(len(rateLength)): temp += rateLength[i] self.curvInput.append(temp) - self.rateAngular.append([0, 0., 0.]) + self.rateAngular.append([0, 0.0, 0.0]) counter = 0 for i in range(len(self.curvInput) - 1): - middle = (self.curvInput[i + 1] + self.curvInput[i]) / 2. - self.frames.append([self.curvInput[i], 0., 0., 0., 0., 0., 1.]) - self.frames.append([middle, 0., 0., 0., 0., 0., 1.]) + middle = (self.curvInput[i + 1] + self.curvInput[i]) / 2.0 + self.frames.append([self.curvInput[i], 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) + self.frames.append([middle, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) self.curvOut.append(self.curvInput[i]) self.curvOut.append(middle) - self.cable3DPos.append([self.curvInput[i], 0., 0.]) - self.cable3DPos.append([middle, 0., 0.]) + self.cable3DPos.append([self.curvInput[i], 0.0, 0.0]) + self.cable3DPos.append([middle, 0.0, 0.0]) counter += 2 self.curvOut.append(self.length) - self.cable3DPos.append([self.length, 0., 0.]) + self.cable3DPos.append([self.length, 0.0, 0.0]) # print("self.cable3DPos: ", self.cable3DPos) - self.frames.append([self.length, 0., 0., 0., 0., 0., 1.]) + self.frames.append([self.length, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) counter += 1 self.nbFrames = counter self.initGraph() @@ -150,10 +323,10 @@ def __init__(self, *args, **kwargs): def applyRotation(self, angle=None): if angle is None: - angle = [0., 0., 0.] - QInit = Quat.createFromEuler(angle, 'ryxz', inDegree=True) + angle = [0.0, 0.0, 0.0] + QInit = Quat.createFromEuler(angle, "ryxz", inDegree=True) QInit.normalize() - return QInit.rotate([self.dX, 0., 0.]) + return QInit.rotate([self.dX, 0.0, 0.0]) def computeCosseratParameters(self): points_size = len(self.cable3DPos) @@ -162,20 +335,30 @@ def computeCosseratParameters(self): self.edgeList.append(i + 1) def createCylinderNode(self, length=0.5, abscissa=0.0, index=0): - translation = [abscissa, 0., 0.] - color = 'grey' if length == 0.5 else 'blue' - CylinderFEMNode = self.frameNode.addChild( - 'CylinderFEMNode' + str(index)) - CylinderFEMNode.addObject('CylinderGridTopology', name="grid", nx="5", ny="5", nz="8", length=length, - radius=0.25, axis="1 0 0") - CylinderFEMNode.addObject('MeshTopology', src="@grid") + translation = [abscissa, 0.0, 0.0] + color = "grey" if length == 0.5 else "blue" + CylinderFEMNode = self.frameNode.addChild("CylinderFEMNode" + str(index)) + CylinderFEMNode.addObject( + "CylinderGridTopology", + name="grid", + nx="5", + ny="5", + nz="8", + length=length, + radius=0.25, + axis="1 0 0", + ) + CylinderFEMNode.addObject("MeshTopology", src="@grid") CylinderFEMNode.addObject( - 'MechanicalObject', name="cylinder", template="Vec3d", translation=translation) - CylinderFEMNode.addObject('SkinningMapping', nbRef='1') - Visu = CylinderFEMNode.addChild('Visu') - Visu.addObject('OglModel', name="Visual", color=color) - Visu.addObject('IdentityMapping', - input="@../cylinder", output="@Visual") + "MechanicalObject", + name="cylinder", + template="Vec3d", + translation=translation, + ) + CylinderFEMNode.addObject("SkinningMapping", nbRef="1") + Visu = CylinderFEMNode.addChild("Visu") + Visu.addObject("OglModel", name="Visual", color=color) + Visu.addObject("IdentityMapping", input="@../cylinder", output="@Visual") def initGraph(self): # @info compute cosserat parameters @@ -184,12 +367,13 @@ def initGraph(self): self.frameNode.mapping.curv_abs_output.value = self.curvOut self.frameNode.mapping.curv_abs_input.value = self.curvInput self.rateAngularDeformNode.rateAngularDeformMO.position.value = self.rateAngular + self.rateAngularDeformNode.beamHookeLaw.findData("length").value = rateLength self.rateAngularDeformNode.beamHookeLaw.findData( - 'length').value = rateLength - self.rateAngularDeformNode.beamHookeLaw.findData( - 'youngModululsList').value = youngModulusList + "youngModululsList" + ).value = youngModulusList self.rateAngularDeformNode.beamHookeLaw.findData( - 'poissonRatioList').value = poisonRatioList + "poissonRatioList" + ).value = poisonRatioList if draw_cylinder == 1: # Draw the cylinder over the beam @@ -236,12 +420,12 @@ def __init__(self, *args, **kwargs): Sofa.Core.Controller.__init__(self, *args, **kwargs) self.node = args[0] - self.refNode = self.node.getChild('PlaneRef') - self.cochleaNode = self.node.getChild('cochleaNode') + self.refNode = self.node.getChild("PlaneRef") + self.cochleaNode = self.node.getChild("cochleaNode") self.MecaObject = self.cochleaNode.dofs self.RefObject = self.refNode.Ref - self.colorMapNode = self.cochleaNode.getChild('ColorMap') + self.colorMapNode = self.cochleaNode.getChild("ColorMap") self.colorMap = self.colorMapNode.ColorMap self.DataDisplay = self.colorMapNode.DataDisplay @@ -263,7 +447,7 @@ def onAnimateEndEvent(self, event): for i in range(nbNode): distX += [math.fabs(position[i][2] - posRef[i][2])] # print("> =========", forceX) - forceX += [math.fabs(0. * (position[i][2] - posRef[i][2]))] + forceX += [math.fabs(0.0 * (position[i][2] - posRef[i][2]))] self.colorMapNode.DataDisplay.pointData = forceX @@ -294,8 +478,9 @@ def buildPlasticity(self): # print("=+++++> idx: {} and rate is : {}".format(idx,pos[self.insertionIndex])) if abs(pos[self.insertionIndex]) > self.elsaticityRate: # print("=+++++> idx: {} and rate is : {}".format(idx,pos[self.insertionIndex])) - restPos[idx][self.insertionIndex] = pos[self.insertionIndex] - \ - self.elsaticityRate + restPos[idx][self.insertionIndex] = ( + pos[self.insertionIndex] - self.elsaticityRate + ) # print("The positions: {} restPos: {}".format(pos[self.insertionIndex], restPos[idx][self.insertionIndex])) """ ============================================================ @@ -308,8 +493,9 @@ def usePlasticityWithTable(self): with self.mechanicalObjectMO.rest_position.writeable() as restPos: for idx, pos in enumerate(positions): if abs(pos[self.insertionIndex]) > plasticityTab[idx]: - restPos[idx][self.insertionIndex] = pos[self.insertionIndex] - \ - plasticityTab[idx] + restPos[idx][self.insertionIndex] = ( + pos[self.insertionIndex] - plasticityTab[idx] + ) # ####################### @@ -318,7 +504,15 @@ def usePlasticityWithTable(self): class CosseratGeometry: - def __init__(self, positionS, curv_abs_inputS, sectionLength, framesF, curv_abs_outputF, cable_positionF): + def __init__( + self, + positionS, + curv_abs_inputS, + sectionLength, + framesF, + curv_abs_outputF, + cable_positionF, + ): self.positionS = positionS self.curv_abs_inputS = curv_abs_inputS self.sectionLength = sectionLength @@ -326,6 +520,7 @@ def __init__(self, positionS, curv_abs_inputS, sectionLength, framesF, curv_abs_ self.curv_abs_outputF = curv_abs_outputF self.cable_positionF = cable_positionF + def generate_cosserat_geometry(beamGeoParams): x, y, z = beamGeoParams.init_pos total_length = beamGeoParams.beamLength @@ -361,15 +556,23 @@ def generate_cosserat_geometry(beamGeoParams): cable_position_f.append([total_length + x, y, z]) curv_abs_output_f.append(total_length + x) - return CosseratGeometry(position_s, curv_abs_input_s, sectionLengthList, frames_f, curv_abs_output_f, cable_position_f) + return CosseratGeometry( + position_s, + curv_abs_input_s, + sectionLengthList, + frames_f, + curv_abs_output_f, + cable_position_f, + ) + def BuildCosseratGeometry(config): # Define: the number of section, the total length and the length of each beam. - [x, y, z] = config['init_pos'] - totalLength = config['tot_length'] - nbSection = config['nbSectionS'] - nbFrames = config['nbFramesF'] + [x, y, z] = config["init_pos"] + totalLength = config["tot_length"] + nbSection = config["nbSectionS"] + nbFrames = config["nbFramesF"] lengthS = totalLength / nbSection # Define: the length of each beam in a list, the positions of each beam @@ -402,7 +605,14 @@ def BuildCosseratGeometry(config): cable_positionF.append([totalLength + x, y, z]) curv_abs_outputF.append(totalLength + x) - return [positionS, curv_abs_inputS, longeurS, framesF, curv_abs_outputF, cable_positionF] + return [ + positionS, + curv_abs_inputS, + longeurS, + framesF, + curv_abs_outputF, + cable_positionF, + ] class MoveTargetProcess(Sofa.Core.Controller): @@ -410,13 +620,17 @@ def __init__(self, *args, **kwargs): Sofa.Core.Controller.__init__(self, *args, **kwargs) self.targetMO = args[0] self.targetIndex = 0 - self.targetList = [[85.0, 0, 0.35857], [85.0, 0.5, 0.35857], [ - 86.0, 1.5, 0.35857], [87.0, 2.5, 0.35857]] - pos = self.targetMO.findData('effectorGoal').value + self.targetList = [ + [85.0, 0, 0.35857], + [85.0, 0.5, 0.35857], + [86.0, 1.5, 0.35857], + [87.0, 2.5, 0.35857], + ] + pos = self.targetMO.findData("effectorGoal").value print("effectorGoal :", pos[0]) def onKeypressedEvent(self, event): - key = event['key'] + key = event["key"] if key == "+": # + # with self.targetMO.findData('effectorGoal').writeable() as posR: # print("effectorGoal :", posR) @@ -458,13 +672,14 @@ def __init__(self, *args, **kwargs): print("tip indice :", self.tipIndex) def onKeypressedEvent(self, event): - key = event['key'] + key = event["key"] if key == "+": # + with self.inputConstraintPointsMO.position.writeable() as posA: print("0. List The position :", posA) self.inputConstraintPointsMO.position.value = np.array( - [[40, 0, 0], [45, 0, 0]]) + [[40, 0, 0], [45, 0, 0]] + ) with self.inputConstraintPointsMO.position.writeable() as posA: print("1. List The position :", posA) @@ -474,9 +689,8 @@ def onKeypressedEvent(self, event): # print("1. List The position :", posA) # posA.append(self.needleCollisionMO.position[self.tipIndex]) - indice = self.diffMapping.findData('indices') - print("====> indices :", - self.diffMapping.addPointProcess([40.0, 0., 0.])) + indice = self.diffMapping.findData("indices") + print("====> indices :", self.diffMapping.addPointProcess([40.0, 0.0, 0.0])) if key == "-": # - with self.inputConstraintPointsMO.rest_position.writeable() as posA: @@ -485,40 +699,52 @@ def onKeypressedEvent(self, event): def Cube( - name="Cube", - surfaceMeshFileName="mesh/cube.obj", - translation=None, - rotation=None, - uniformScale=1., - totalMass=300., - volume=20., - inertiaMatrix=None, - color=None, - isAStaticObject=False, parent=None): + name="Cube", + surfaceMeshFileName="mesh/cube.obj", + translation=None, + rotation=None, + uniformScale=1.0, + totalMass=300.0, + volume=20.0, + inertiaMatrix=None, + color=None, + isAStaticObject=False, + parent=None, +): if color is None: - color = [1., 1., 0.] + color = [1.0, 1.0, 0.0] if inertiaMatrix is None: inertiaMatrix = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] if rotation is None: - rotation = [0., 0., 0.] + rotation = [0.0, 0.0, 0.0] if translation is None: - translation = [0., 0., 0.] + translation = [0.0, 0.0, 0.0] cubeNode = parent.addChild(name) - cubeNode.addObject('MechanicalObject', name="mstate", template="Rigid3", - translation=translation, rotation=rotation) - cubeNode.addObject('UniformMass', name="mass", vertexMass=[totalMass, volume, inertiaMatrix[:]], - showAxisSizeFactor='0.') + cubeNode.addObject( + "MechanicalObject", + name="mstate", + template="Rigid3", + translation=translation, + rotation=rotation, + ) + cubeNode.addObject( + "UniformMass", + name="mass", + vertexMass=[totalMass, volume, inertiaMatrix[:]], + showAxisSizeFactor="0.", + ) # cubeNode.addObject('UncoupledConstraintCorrection') - objectCollis = cubeNode.addChild('collision') - objectCollis.addObject('MeshObjLoader', name="loader", - filename=surfaceMeshFileName, triangulate="true") - objectCollis.addObject('MeshTopology', src="@loader") - objectCollis.addObject('MechanicalObject') - objectCollis.addObject('TriangleCollisionModel') - objectCollis.addObject('LineCollisionModel') - objectCollis.addObject('PointCollisionModel') - objectCollis.addObject('RigidMapping') + objectCollis = cubeNode.addChild("collision") + objectCollis.addObject( + "MeshObjLoader", name="loader", filename=surfaceMeshFileName, triangulate="true" + ) + objectCollis.addObject("MeshTopology", src="@loader") + objectCollis.addObject("MechanicalObject") + objectCollis.addObject("TriangleCollisionModel") + objectCollis.addObject("LineCollisionModel") + objectCollis.addObject("PointCollisionModel") + objectCollis.addObject("RigidMapping") return # visu = cubeNode.addChild('visualisation') diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py index cbc1aada..a6b2b2a6 100644 --- a/examples/python3/useful/params.py +++ b/examples/python3/useful/params.py @@ -7,11 +7,14 @@ @dataclass class BeamGeometryParameters: """Cosserat Beam Geometry parameters""" + beamLength: float = 1.0 # beam length in m nbSection: int = 5 # number of sections, sections along the beam length nbFrames: int = 30 # number of frames along the beam buildCollisionModel: int = 0 - init_pos: List[float] = field(default_factory=lambda: [0., 0., 0.]) # The beam rigid base position as a list [x, y, z] + init_pos: List[float] = field( + default_factory=lambda: [0.0, 0.0, 0.0] + ) # The beam rigid base position as a list [x, y, z] """Parameters for the visualisation of the beam""" showFramesObject: int = 1 @@ -21,6 +24,7 @@ class BeamGeometryParameters: @dataclass class BeamPhysicsParameters: """Cosserat Beam Physics parameters""" + """First set of parameters""" youngModulus: float = 1.205e8 poissonRatio: float = 0.3 @@ -46,36 +50,49 @@ class BeamPhysicsParameters: @dataclass class SimulationParameters: """Simulation parameters""" + rayleighStiffness: float = 0.2 rayleighMass: float = 0.1 firstOrder: bool = False + @dataclass class VisualParameters: """Visual parameters""" + showObject: int = 1 showObjectScale: float = 1.0 showObjectColor: List[float] = field(default_factory=lambda: [1.0, 0.0, 0.0, 1.0]) + @dataclass class ContactParameters: """Contact parameters""" - responseParams: str = 'mu=0.8' - response: str = 'FrictionContactConstraint' + + responseParams: str = "mu=0.8" + response: str = "FrictionContactConstraint" alarmDistance: float = 0.05 contactDistance: float = 0.01 isMultithreading: bool = False - tolerance: float = 1.e-8 + tolerance: float = 1.0e-8 maxIterations: int = 100 - epsilon: float = 1.e-6 + epsilon: float = 1.0e-6 + @dataclass class Parameters: """Parameters for the Cosserat Beam""" - beamPhysicsParams: BeamPhysicsParameters = field(default_factory=BeamPhysicsParameters) - simuParams: SimulationParameters = field(default_factory=SimulationParameters) # SimulationParameters() - contactParams: ContactParameters = field(default_factory=ContactParameters) # ContactParameters() - beamGeoParams: BeamGeometryParameters = field(default_factory=BeamGeometryParameters) - visualParams: VisualParameters = field(default_factory=VisualParameters) - + beamPhysicsParams: BeamPhysicsParameters = field( + default_factory=BeamPhysicsParameters + ) + simuParams: SimulationParameters = field( + default_factory=SimulationParameters + ) # SimulationParameters() + contactParams: ContactParameters = field( + default_factory=ContactParameters + ) # ContactParameters() + beamGeoParams: BeamGeometryParameters = field( + default_factory=BeamGeometryParameters + ) + visualParams: VisualParameters = field(default_factory=VisualParameters) From 7d6abfc7bf4292fa735c6e2f2e0ad21d4a76126d Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Wed, 20 Mar 2024 08:59:24 +0100 Subject: [PATCH 32/71] add __init__ file in actuator folder --- examples/python3/actuators/__init__.py | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) create mode 100644 examples/python3/actuators/__init__.py diff --git a/examples/python3/actuators/__init__.py b/examples/python3/actuators/__init__.py new file mode 100644 index 00000000..3c3c77f0 --- /dev/null +++ b/examples/python3/actuators/__init__.py @@ -0,0 +1,16 @@ +# -*- coding: utf-8 -*-longeurS +""" +Template for needle. + +Content: +******** + .. scenes related to the use of cosserat model needle in a direct simulation + .. autosummary:: + :toctree: _autosummary + + cosserat.needle.params + + +""" + +__all__ = [] From 921ea9adbc8eaf4cb91f27ad634b4aad5933be2d Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 5 Apr 2024 16:58:21 +0200 Subject: [PATCH 33/71] Fixed: Parent function of 'init' in DiscreteCosseratMapping was called very early, before the initialisation of mechanical parameters such as position. --- CMakeLists.txt | 2 +- src/Cosserat/mapping/DiscreteCosseratMapping.inl | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5175507e..d14d9e80 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -87,7 +87,7 @@ if(WIN32) add_definitions(-D_WINSOCKAPI_) endif() -add_library(${PROJECT_NAME} SHARED ${HEADER_FILES} ${SOURCE_FILES} ${DOC_FILES} ${RESOURCE_FILES} ) +add_library(${PROJECT_NAME} SHARED ${HEADER_FILES} ${SOURCE_FILES} ${DOC_FILES} ) target_link_libraries(${PROJECT_NAME} Sofa.Component.Constraint.Lagrangian.Model Sofa.Component.StateContainer diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 047b87c1..81228f3d 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -68,7 +68,7 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { - Inherit1::init(); + if(this->getFromModels1().empty() || this->getFromModels2().empty() || this->getToModels().empty()) { @@ -76,6 +76,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() return; } reinit(); + // I call Init here since we build the mechanics only in the + Inherit1::init(); m_colorMap.setColorScheme("Blue to Red"); m_colorMap.reinit(); @@ -151,7 +153,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( } // if(d_debug.getValue()){ - for (auto i =0; i<out.size()-1; i++){ + for (unsigned int i =0; i<out.size()-1; i++){ type::Vec3 diff = out[i+1].getCenter() - out[i].getCenter(); std::cout << "dist "<<i << " : "<< diff.norm() <<std::endl; } From 68fc7218e8cbc7834ffe7f7780224466ed840b5c Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 5 Apr 2024 17:02:02 +0200 Subject: [PATCH 34/71] Fixed: Parent function of 'init' in DiscreteCosseratMapping was called very early, before the initialisation of mechanical parameters such as position. --- src/Cosserat/mapping/DiscreteCosseratMapping.inl | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 1635c9b1..b5c288a9 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -72,14 +72,14 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { - Inherit1::init(); - if(this->getFromModels1().empty() || this->getFromModels2().empty() || this->getToModels().empty()) { msg_error() << "Error while initializing ; input getFromModels1/getFromModels2/output not found" ; return; } + reinit(); + Inherit1::init(); m_colorMap.setColorScheme("Blue to Red"); m_colorMap.reinit(); From bc00712bc86cbe02b244f27aff46ff883ed143df Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Sat, 6 Apr 2024 06:47:24 +0200 Subject: [PATCH 35/71] fixed: warning in the call of destructor in cosserat's forcefield --- src/Cosserat/forcefield/BeamHookeLawForceField.inl | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.inl b/src/Cosserat/forcefield/BeamHookeLawForceField.inl index 16602969..19370dc2 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.inl @@ -82,14 +82,12 @@ BeamHookeLawForceField<DataTypes>::BeamHookeLawForceField() } template<typename DataTypes> -BeamHookeLawForceField<DataTypes>::~BeamHookeLawForceField() -{} +BeamHookeLawForceField<DataTypes>::~BeamHookeLawForceField() = default; template<typename DataTypes> void BeamHookeLawForceField<DataTypes>::init() { Inherit1::init(); - reinit(); } From 12c4fd53ed79f4e1cc5e2419aeed3a20932dabaf Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 9 Apr 2024 20:12:19 +0200 Subject: [PATCH 36/71] update tutoriel and related scenes --- docs/testScene/tuto_1.py | 3 +- docs/testScene/tuto_2.py | 6 +-- docs/testScene/tuto_4.py | 2 +- docs/text/Introduction.md | 50 ++++++++++++++--------- docs/text/oneDimensionModels.md | 45 ++++++++++++++++++++ examples/python3/cosserat/CosseratBase.py | 33 ++++++++------- examples/python3/useful/geometry.py | 1 + examples/python3/useful/params.py | 2 + 8 files changed, 104 insertions(+), 38 deletions(-) create mode 100644 docs/text/oneDimensionModels.md diff --git a/docs/testScene/tuto_1.py b/docs/testScene/tuto_1.py index 63fb60cb..3475110c 100644 --- a/docs/testScene/tuto_1.py +++ b/docs/testScene/tuto_1.py @@ -54,7 +54,8 @@ def createScene(root_node): # cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] - list_sections_length = [10, 10, 10] + list_sections_length = [10, 10, 10] # SI units + bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) section_curv_abs = [0, 10, 20, 30] diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py index 5a8e422e..18fed022 100644 --- a/docs/testScene/tuto_2.py +++ b/docs/testScene/tuto_2.py @@ -64,17 +64,17 @@ def createScene(root_node): section_curv_abs = [0.] # section/segment curve abscissa for i in range(nb_sections): - bending_states.append([0, 0.0, 0.0]) # torsion, y_bending, z_bending + bending_states.append([0, 0., 0.2]) # torsion, y_bending, z_bending list_sections_length.append((((i + 1) * length_s) - i * length_s)) temp += list_sections_length[i] section_curv_abs.append(temp) - bending_states[nb_sections-1] = [0, 0.0, 0.52359878] + bending_states[nb_sections-1] = [0, 0.1, 0.2] # call add cosserat state and force field bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) # comment : ??? - nb_frames = 6 + nb_frames = 32 length_f = beam_length/float(nb_frames) cosserat_G_frames = [] frames_curv_abs = [] diff --git a/docs/testScene/tuto_4.py b/docs/testScene/tuto_4.py index edccaf9b..9c73a44b 100644 --- a/docs/testScene/tuto_4.py +++ b/docs/testScene/tuto_4.py @@ -95,7 +95,7 @@ def onKeypressedEvent(self, event): self.applyForce = False -controller_type = 2 +controller_type = 1 def createScene(root_node): addHeader(root_node) diff --git a/docs/text/Introduction.md b/docs/text/Introduction.md index 62b03fa6..72822387 100644 --- a/docs/text/Introduction.md +++ b/docs/text/Introduction.md @@ -64,7 +64,7 @@ Yinoussa Adagolodjo --- #### **Challenges in Soft Robotics** -- *Modeling* : due to deformable materials +- *Modeling* : due to non-linear deformable materials - [*Control*](../../../Soft_Robot/kinematics_dynamics_control.md) : due to the non-linear, multi-body dynamics of deformable materials - [*Multi-dimension*](../../../../../../Projects/ANR/brainStormingANR2023.md) : due to a wide range of shape, volume (3D), surface (2D) and cable (1D) - [*Multi-physics*](../../../../../../Projects/ANR/RobotMulti-physics.md) : due a wide range of physical behaviors, including mechanical deformation, thermal effects, electrical responses, @@ -76,22 +76,29 @@ Yinoussa Adagolodjo (To go further on the introduction of deformable robotics ⇾ [Introduction_General](../../../Soft_Robot/Introduction_General.md) ) --- -##### Why combine different models ? +##### 1D models usage in Soft-robot modeling ? - Introducing a versatile modeling tool for multidimensional Soft-Robot: - - Animal locomotion (Bio-inspired robotics) - - Flexible arms actuated by cables or similar mechanisms (Robotics) - - Medical devices like endoscopes, needles, and catheters (Medical robotics) +- 1D models are often used to represent the behavior of soft structures + - Cables, tubes, or fibers, that can deform in one dimension + - Examples include: + - Flexible arms actuated by cables or similar mechanisms (Robotics) + - Medical devices like endoscopes, needles, and catheters (Medical robotics) + --- -##### Why combine different models ? -- Existing design and modeling tools demand enhancement, particularly in the mechanical aspect. -![](../images/Pasted%20image%2020231108201224.png) -- Offer a wide range of design possibilities: - - Selection of actuators, force transmission within the structure, utilization of materials with varying stiffness profiles, and more. +##### How to model one 1D object ? see [oneDimensionModels](oneDimensionModels.md) +- **Geometric Methods** +- **Mechanics methods** +- *Statistical Methods* +- *Computational Methods* +- *Analytical Methods:* + --- -##### Cosserat Theory +##### Cosserat Theory (Mechanics) Choose strain as generalized coordinates, defined in global (or local) frame! ![400](../images/Pasted%20image%2020231108233708.png) [Lazarus et al. 2013] + +--- - The configuration of the Cosserat rod is defined by its centerline r(s). - The orientation of each mass point of the rod is represented by an orthonormal basis ($d_1(s), d_2(s), d_3(s)$) - The three local modes of deformation of the elastic rod : - (b1) material curvature $κ_1$ related to the direction $d_1$ of the cross-section, (b2) material curvature $κ_2$ related to $d_2$, and $κ_3$ twist. @@ -104,7 +111,7 @@ Choose strain as generalized coordinates, defined in global (or local) frame! - Piece-wise Constant Strain (PCS, treats rigid, soft, or hybrid robots uniformly) ![500](https://lh7-us.googleusercontent.com/hzJA2pzS-naPfFkf-98bPkGsQ86ZGdGwqGW3-un56s3ZcVkdOB0_Jus4a9W_nqO7jU7Tt_FDzCrFIbfA9XFqaPBmmq-do-TIJkFn6NX-RimX2UlWBTis_7bKzAp7fEmIeiuOZ1FueZ5yxijFSJls=nw) --- -##### Discrete Cosserat Modeling: DCM +##### Discrete Cosserat Modeling(DCM): Piece-Wise Constant Strain - Models the deformation of a soft manipulator arm using a finite number of sections - Assumes constant strains along each section - Accounts for shears and torsion @@ -113,14 +120,14 @@ Choose strain as generalized coordinates, defined in global (or local) frame! --- ##### DCM (Kinematics) - Configuration $g= \begin{pmatrix} \mathcal{R} & u \\ 0 & 1 \end{pmatrix} ∈SE(3)$ -- Velocity $\begin{align}\eta(s,t) &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ -- Strain $\begin{align}\xi(s,t) &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ -- Kinematics : $g'=g\hat{\xi}(X)$ ; $\dot{g} = g\hat{\eta}$ -- Differntial Kinematics : $\eta'=\dot{\xi}(X)-ad_{\xi(X)}\eta(X)$ -![](../images/Pasted%20image%2020231109002926.png) +- Strain $\begin{align}\xi(s,t) = g^{-1} \frac{\partial g}{\partial s} &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ +- Velocity $\begin{align}\eta(s,t) =g^{-1}\frac{\partial g}{\partial t} &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ --- -![0](../images/Pasted%20image%2020231108234643.png) +##### DCM (Kinematics) +- => Kinematics (deformation) : $\frac{\partial g}{\partial s} = g'=g\hat{\xi}$ ; $\dot{g} = g\hat{\eta}$ +- Differential Kinematics : $\eta'= \frac{\partial g}{\partial s} = \dot{\xi} - ad_{\xi}\eta$ +![](../images/Pasted%20image%2020231109002926.png) --- ##### DCM (Dynamics) ![800](../images/Pasted%20image%2020231109003349.png) @@ -183,4 +190,9 @@ For example, it allows us to effectively simulate scenarios where inextensible c - *FEM's Material Modeling*: FEM excels at modeling the deformations and stress distributions in complex materials, including soft and deformable ones. It considers the local behavior of materials, making it more accurate for understanding the mechanical properties of soft robots. - *Cosserat theory's Beam-Like Modeling*: DCM, on the other hand, is suitable for modeling the overall shape and bending of structures, making it a natural choice for cables, rods, and flexible elements in soft robots. ---- \ No newline at end of file +--- + + + + +![0](../images/Pasted%20image%2020231108234643.png) \ No newline at end of file diff --git a/docs/text/oneDimensionModels.md b/docs/text/oneDimensionModels.md new file mode 100644 index 00000000..d7a9972b --- /dev/null +++ b/docs/text/oneDimensionModels.md @@ -0,0 +1,45 @@ +--- +tutorial: one Dimension Models +tags: + - tuto/cosserat +cssclass: + - dashboard +--- +When modeling one-dimensional objects, various methods can be used, drawing from principles of geometry, mechanics, and other disciplines. Here are some common methods used for modeling one-dimensional objects: + +1. **Geometric Methods:** These focus on the shape, size, and arrangement of the one-dimensional objects in space. For example, you could use coordinate geometry to represent a 1D object (like a line segment) in terms of its endpoints or parametric equations. Another approach is to employ calculus methods to describe the curvature, length, or other geometric properties of the object. + - **Point Mass Model:** Simplifies an object to a single point with mass, useful for analyzing motion and dynamics. + - **Beam Theory:** Treats the object as a slender beam with one-dimensional deformation, commonly used for analyzing the behavior of structures like beams, rods, or cables. + - **Curve Modeling:** Represents the object as a one-dimensional curve in space, often used in computer graphics and animation for modeling shapes and trajectories. + +2. **Mechanics Methods:** These involve studying the forces, stresses, and +deformations that occur when you apply physical actions on one-dimensional +objects. In this case, you might use the laws of motion (e.g., Newton's Laws) or +Hooke's law to determine how an object will respond under different conditions. +For instance, you could model a spring as a one-dimensional elastic object and +apply mechanical methods to study its behavior under varying levels of tension. + + - **Differential Equations:** Describes the behavior of one-dimensional objects using differential equations derived from principles of mechanics, such as Newton's laws of motion or Euler-Bernoulli beam theory. + - **Finite Element Method (FEM):** Divides the object into small elements and solves differential equations numerically, commonly used for simulating the behavior of complex structures under various loading conditions. + - **Lagrangian Mechanics:** Describes the motion of one-dimensional objects using generalized coordinates and the principle of least action, useful for analyzing systems with constraints and forces. + +3. **Statistical Methods:** When modeling large collections of one-dimensional objects (e.g., particles in a fluid) or studying probabilistic properties (like the distribution of particle positions), you may use statistical methods such as stochastic processes, probability distributions, or ensemble averaging techniques. + - **Random Walks:** Models the stochastic motion of one-dimensional objects by simulating random steps or displacements, often used in the study of diffusion processes and Brownian motion. + - **Markov Chains:** Describes the probabilistic transitions of one-dimensional objects between different states or configurations, useful for modeling systems with discrete states and transition probabilities. + +4. **Computational Methods:** These involve using numerical algorithms and computational +techniques to approximate the solution to mathematical or physical problems +related to 1D objects. For example, you could use finite difference or finite +element methods to model the distribution of stresses within a one-dimensional +structure under mechanical loading. + + - **Numerical Integration:** Approximates the behavior of one-dimensional objects by discretizing time or space and using numerical integration techniques, such as Euler's method or Runge-Kutta methods. + - **Monte Carlo Simulation:** Generates random samples to simulate the behavior of one-dimensional objects and estimate statistical properties, useful for studying systems with complex interactions and uncertainty. + +5. **Analytical Methods:** In some cases, it may be possible to derive an exact +analytical solution for a given problem involving a 1D object. For example, you +might use trigonometric functions or other mathematical tools to find the +general solution for a one-dimensional wave equation. + - **Analytical Solutions:** Derives closed-form solutions to differential equations describing the behavior of one-dimensional objects, often used for simple systems with well-defined boundary conditions and material properties. + +These methods can be combined and adapted to suit the specific characteristics and requirements of the system being modeled, providing valuable insights into the behavior of one-dimensional objects in various fields of science and engineering. \ No newline at end of file diff --git a/examples/python3/cosserat/CosseratBase.py b/examples/python3/cosserat/CosseratBase.py index 0a38e424..9771208c 100644 --- a/examples/python3/cosserat/CosseratBase.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -47,18 +47,18 @@ class CosseratBase(Sofa.Prefab): "help": "Cosserat base Rotation", "default": [0.0, 0.0, 0.0], }, - { + { # to be removed "name": "attachingToLink", - "type": "string", + "type": bool, "help": "a rest shape force field will constraint the object " "to follow arm position", - "default": "1", + "default": True, }, { "name": "showObject", - "type": "string", + "type": bool, "help": " Draw object arrow ", - "default": "0", + "default": False, }, ] @@ -71,10 +71,12 @@ def __init__(self, *args, **kwargs): beamGeometryParams = self.params.beamGeoParams self.beamMass = beamPhysicsParams.beamMass # self.cosseratGeometry['beamMass'] + # Todo: add option in case None self.parent = kwargs.get("parent") self.useInertiaParams = beamPhysicsParams.useInertia # False self.radius = beamPhysicsParams.beamRadius # kwargs.get('radius') + # Todo: To be removed if self.parent.hasObject("EulerImplicitSolver") is False: print("The code does not have parent EulerImplicit") self.solverNode = addSolverNode(self.parent) @@ -142,19 +144,24 @@ def _addRigidBaseNode(self): rigidBaseNode = self.addChild("rigidBase") trans = list(self.translation.value) rot = list(self.rotation.value) + # To be improved with classes in top positions = [[self.params.beamGeoParams.init_pos] + [0.0, 0.0, 0.0, 1.0]] - rigidBaseNode.addObject( + + rigidBaseNodeMo = rigidBaseNode.addObject( "MechanicalObject", template="Rigid3d", name="RigidBaseMO", showObjectScale=0.2, - translation=trans, + translation=trans, # @Todo: To be removed position=positions, - rotation=rot, - showObject=int(self.showObject.value), + rotation=rot, # @Todo: To be removed + #showObject=int(self.showObject.value), ) + rigidBaseNodeMo.showObject.setParent(self.showObject) + + # @TODO: remove this hard coded. # one can choose to set this to false and directly attach the beam base # to a control object in order to be able to drive it. if int(self.attachingToLink.value): @@ -232,12 +239,10 @@ def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): position=framesF, showIndices=self.params.beamGeoParams.showFramesObject, showObject=self.params.beamGeoParams.showFramesObject, - showObjectScale=1.8, + showObjectScale=1.8, # Todo: remove this hard code ) - if self.beamMass != 0.0: - cosseratInSofaFrameNode.addObject( - "UniformMass", totalMass=self.beamMass, showAxisSizeFactor="0" - ) + + cosseratInSofaFrameNode.addObject("UniformMass", totalMass=self.beamMass, showAxisSizeFactor="0") cosseratInSofaFrameNode.addObject( "DiscreteCosseratMapping", diff --git a/examples/python3/useful/geometry.py b/examples/python3/useful/geometry.py index cb4b5929..bb8d86f7 100644 --- a/examples/python3/useful/geometry.py +++ b/examples/python3/useful/geometry.py @@ -53,6 +53,7 @@ def calculate_frame_parameters(beamGeoParams): curv_abs_output_f = [] cable_position_f = [] + # @Todo: improve this for for i in range(nb_frames): sol = i * length_f frames_f.append([sol + x, y, z, 0, 0, 0, 1]) diff --git a/examples/python3/useful/params.py b/examples/python3/useful/params.py index a6b2b2a6..2f553ed4 100644 --- a/examples/python3/useful/params.py +++ b/examples/python3/useful/params.py @@ -4,6 +4,7 @@ from typing import List +# @TODO: Improve this function, remove hard coding. @dataclass class BeamGeometryParameters: """Cosserat Beam Geometry parameters""" @@ -21,6 +22,7 @@ class BeamGeometryParameters: showRigidBaseObject: int = 1 +#Todo: two objects from the same base class to define different instead of useInertia @dataclass class BeamPhysicsParameters: """Cosserat Beam Physics parameters""" From 07b7acae737203b083fd9c5a0aa05b993fd5c008 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 23 Apr 2024 14:16:43 +0200 Subject: [PATCH 37/71] fix a bug related to the use of bool type in python prefabs --- docs/testScene/tuto_2.py | 7 ++--- docs/text/Introduction.md | 4 +-- examples/python3/cosserat/CosseratBase.py | 28 +++++++++---------- .../mapping/DiscreteCosseratMapping.inl | 2 -- 4 files changed, 19 insertions(+), 22 deletions(-) diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py index 18fed022..d063ec88 100644 --- a/docs/testScene/tuto_2.py +++ b/docs/testScene/tuto_2.py @@ -21,7 +21,7 @@ def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2. cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', position=bending_states) testNode = cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', - length=list_sections_length, radius=2., youngModulus=1.e4, + length=list_sections_length, radius=_radius, youngModulus=1.e4, poissonRatio=0.4) print(f' the dire of node is : {dir(testNode)}') return cosserat_coordinate_node @@ -64,7 +64,7 @@ def createScene(root_node): section_curv_abs = [0.] # section/segment curve abscissa for i in range(nb_sections): - bending_states.append([0, 0., 0.2]) # torsion, y_bending, z_bending + bending_states.append([0, 0., 0.0]) # torsion, y_bending, z_bending list_sections_length.append((((i + 1) * length_s) - i * length_s)) temp += list_sections_length[i] section_curv_abs.append(temp) @@ -91,7 +91,6 @@ def createScene(root_node): cable_position_f.append([beam_length + x, y, z]) frames_curv_abs.append(beam_length + x) - _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, - beam_radius) + _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, beam_radius) return root_node diff --git a/docs/text/Introduction.md b/docs/text/Introduction.md index 72822387..600e7b1c 100644 --- a/docs/text/Introduction.md +++ b/docs/text/Introduction.md @@ -66,8 +66,8 @@ Yinoussa Adagolodjo - *Modeling* : due to non-linear deformable materials - [*Control*](../../../Soft_Robot/kinematics_dynamics_control.md) : due to the non-linear, multi-body dynamics of deformable materials -- [*Multi-dimension*](../../../../../../Projects/ANR/brainStormingANR2023.md) : due to a wide range of shape, volume (3D), surface (2D) and cable (1D) -- [*Multi-physics*](../../../../../../Projects/ANR/RobotMulti-physics.md) : due a wide range of physical behaviors, including mechanical deformation, thermal effects, electrical responses, +- [*Multi-dimension*](../../../../../../Professionnel/research_md/Projects/ANR/brainStormingANR2023.md) : due to a wide range of shape, volume (3D), surface (2D) and cable (1D) +- [*Multi-physics*](../../../../../../Professionnel/research_md/Projects/ANR/RobotMulti-physics.md) : due a wide range of physical behaviors, including mechanical deformation, thermal effects, electrical responses, --- #### **Challenges in Soft Robotics** diff --git a/examples/python3/cosserat/CosseratBase.py b/examples/python3/cosserat/CosseratBase.py index 9771208c..25a6716f 100644 --- a/examples/python3/cosserat/CosseratBase.py +++ b/examples/python3/cosserat/CosseratBase.py @@ -27,7 +27,7 @@ class CosseratBase(Sofa.Prefab): Node1 ForceField // Base on Hook's law, it computed the force applied on the beam (Node0-Node1)-child MechanicalObject // The child of the two precedent nodes, Rigid positions Allow to compute the cosserat frame in the world frame (Sofa frame) - Cosserat Mapping // it allow the transfer from the local to the word frame + Cosserat Mapping // it allow the transfer from the locial to the word frame } params @@ -47,18 +47,18 @@ class CosseratBase(Sofa.Prefab): "help": "Cosserat base Rotation", "default": [0.0, 0.0, 0.0], }, - { # to be removed + { # @TODO: to be removed "name": "attachingToLink", - "type": bool, + "type": "string", "help": "a rest shape force field will constraint the object " "to follow arm position", - "default": True, + "default": "1", }, { "name": "showObject", - "type": bool, + "type": "string", "help": " Draw object arrow ", - "default": False, + "default": "0", }, ] @@ -76,7 +76,7 @@ def __init__(self, *args, **kwargs): self.useInertiaParams = beamPhysicsParams.useInertia # False self.radius = beamPhysicsParams.beamRadius # kwargs.get('radius') - # Todo: To be removed + # @TODO: To be removed if self.parent.hasObject("EulerImplicitSolver") is False: print("The code does not have parent EulerImplicit") self.solverNode = addSolverNode(self.parent) @@ -147,20 +147,18 @@ def _addRigidBaseNode(self): # To be improved with classes in top positions = [[self.params.beamGeoParams.init_pos] + [0.0, 0.0, 0.0, 1.0]] - rigidBaseNodeMo = rigidBaseNode.addObject( "MechanicalObject", template="Rigid3d", name="RigidBaseMO", showObjectScale=0.2, - translation=trans, # @Todo: To be removed + translation=trans, # @Todo: To be removed position=positions, - rotation=rot, # @Todo: To be removed - #showObject=int(self.showObject.value), + rotation=rot, # @Todo: To be removed + # showObject=int(self.showObject.value), ) rigidBaseNodeMo.showObject.setParent(self.showObject) - # @TODO: remove this hard coded. # one can choose to set this to false and directly attach the beam base # to a control object in order to be able to drive it. @@ -239,10 +237,12 @@ def _addCosseratFrame(self, framesF, curv_abs_inputS, curv_abs_outputF): position=framesF, showIndices=self.params.beamGeoParams.showFramesObject, showObject=self.params.beamGeoParams.showFramesObject, - showObjectScale=1.8, # Todo: remove this hard code + showObjectScale=1.8, # Todo: remove this hard code ) - cosseratInSofaFrameNode.addObject("UniformMass", totalMass=self.beamMass, showAxisSizeFactor="0") + cosseratInSofaFrameNode.addObject( + "UniformMass", totalMass=self.beamMass, showAxisSizeFactor="0" + ) cosseratInSofaFrameNode.addObject( "DiscreteCosseratMapping", diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 81228f3d..7ef71027 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -68,8 +68,6 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { - - if(this->getFromModels1().empty() || this->getFromModels2().empty() || this->getToModels().empty()) { msg_error() << "Error while initializing ; input getFromModels1/getFromModels2/output not found" ; From 27d07925e1c0ef9df4a132599ddf935bd6072d47 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Thu, 6 Jun 2024 23:23:18 +0200 Subject: [PATCH 38/71] update scenes --- README.md | 118 ++++++++++++++++----------------- docs/testScene/tuto_1.py | 128 ++++++++++++++++++++++++----------- docs/testScene/tuto_2.py | 140 +++++++++++++++++++++++++++------------ 3 files changed, 248 insertions(+), 138 deletions(-) diff --git a/README.md b/README.md index 3de23584..7afb195a 100644 --- a/README.md +++ b/README.md @@ -86,62 +86,62 @@ The link to download the Pdf of the Paper: __https://hal.archives-ouvertes.fr/ha %%% old_version -[![Gitter](https://img.shields.io/badge/chat-on_Gitter-ff69b4.svg)](https://app.gitter.im/#/room/#sofa-framework_cosserat-needle-insertion:gitter.im) -[![Support](https://img.shields.io/badge/support-on_GitHub_Discussions-blue.svg)](https://github.com/sofa-framework/sofa/discussions/categories/cosserat) - -![download](https://img.shields.io/github/downloads/SofaDefrost/Cosserat/total.svg) -![forks](https://img.shields.io/github/forks/SofaDefrost/Cosserat.svg) -![stars](https://img.shields.io/github/stars/SofaDefrost/Cosserat.svg) - - -# Description - -Cosserat model has been introduced in continuum robotics to simulate the deformation of the robot body whose geometry -and mechanical characteristics are similar to a rod. -By extension, this model can be used to simulate needles, wires. -The specificity of Cosserat's theory from the point of view of the mechanics of continuous media, is to consider that: each material point -of an object is rigid body(3 translations, 3 rotations), where most other models of continuum media mechanics consider -the material point as particles (3 translations). -For the modeling of linear structures, it is therefore possible to find a framework very close to the articulated solids with a series -of rigid body whose relative position is defined by a strain state. -This model can be used to model and control concentric tube robots, continuum robots actuated with cables, or pneumatic soft robots -with a constant cross-section. - -## Features - -1. Pieces-wise constant Strain PCS: This feature is base on the paper - 1. __Discrete cosserat approach for soft robot dynamics: A new piece-wise constant strain model with torsion and shears__ [Link to the paper](https://ieeexplore.ieee.org/document/7759808) - 2. __Coupling numerical deformable models in global and reduced coordinates for the simulation of the direct and the inverse kinematics of Soft Robots__ [Link to the paper](https://hal.archives-ouvertes.fr/hal-03192168/document) - -<div align="center"> - <a href="https://www.youtube.com/watch?v=qwzKAgw31pU"><img src="https://img.youtube.com/vi/qwzKAgw31pU/0.jpg" alt="link to youtube"></a> -</div> - -2. Pieces-wise Non-constant Strain: -3. DCM with Plastic model - -### Modelling cochlear implant using Discret Cosserat Model (DCM) - -| View 1 | View 2 | View 3 | -|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------| -| <img src="/doc/images/multiSectionWithColorMap1.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap2.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap3.png" width="300" title="DCM as an implant"> | - -### DCM for cable modeling to control deformable robots: -| Direct simulation of a soft gripper | The study the model convergence | -|------------------------------------------------------------------------------------------| --- | -| <img src="/doc/images/cosseratgripper_2.png" width="400" title="DCM for cable modeling"> | <img src="/doc/images/tenCossseratSections.png" width="400" title="DCM for cable modeling ">| - -### Some use cases - -| <img src="/doc/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="doc/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/doc/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | -| ------------- |:-------------:| -----:| -| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| - - -| <img src="/doc/images/example1.gif" width="300" title="PCS_Example1.py "> | <img src="./doc/images/example2.gif" widt="300" title="PCS_Example2.py"> | <img src="./doc/images/example2.gif" width="300" title="PCS_Example3.PCS"> | -| ------------- |:-------------:| -------------:| -| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| - - -Format: ![Alt Text] - +[![Gitter](https://img.shields.io/badge/chat-on_Gitter-ff69b4.svg)](https://app.gitter.im/#/room/#sofa-framework_cosserat-needle-insertion:gitter.im) +[![Support](https://img.shields.io/badge/support-on_GitHub_Discussions-blue.svg)](https://github.com/sofa-framework/sofa/discussions/categories/cosserat) + +![download](https://img.shields.io/github/downloads/SofaDefrost/Cosserat/total.svg) +![forks](https://img.shields.io/github/forks/SofaDefrost/Cosserat.svg) +![stars](https://img.shields.io/github/stars/SofaDefrost/Cosserat.svg) + + +# Description + +Cosserat model has been introduced in continuum robotics to simulate the deformation of the robot body whose geometry +and mechanical characteristics are similar to a rod. +By extension, this model can be used to simulate needles, wires. +The specificity of Cosserat's theory from the point of view of the mechanics of continuous media, is to consider that: each material point +of an object is rigid body(3 translations, 3 rotations), where most other models of continuum media mechanics consider +the material point as particles (3 translations). +For the modeling of linear structures, it is therefore possible to find a framework very close to the articulated solids with a series +of rigid body whose relative position is defined by a strain state. +This model can be used to model and control concentric tube robots, continuum robots actuated with cables, or pneumatic soft robots +with a constant cross-section. + +## Features + +1. Pieces-wise constant Strain PCS: This feature is base on the paper + 1. __Discrete cosserat approach for soft robot dynamics: A new piece-wise constant strain model with torsion and shears__ [Link to the paper](https://ieeexplore.ieee.org/document/7759808) + 2. __Coupling numerical deformable models in global and reduced coordinates for the simulation of the direct and the inverse kinematics of Soft Robots__ [Link to the paper](https://hal.archives-ouvertes.fr/hal-03192168/document) + +<div align="center"> + <a href="https://www.youtube.com/watch?v=qwzKAgw31pU"><img src="https://img.youtube.com/vi/qwzKAgw31pU/0.jpg" alt="link to youtube"></a> +</div> + +2. Pieces-wise Non-constant Strain: +3. DCM with Plastic model + +### Modelling cochlear implant using Discret Cosserat Model (DCM) + +| View 1 | View 2 | View 3 | +|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------|---------------------------------------------------------------------------------------------| +| <img src="/doc/images/multiSectionWithColorMap1.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap2.png" width="300" title="DCM as an implant"> | <img src="/doc/images/multiSectionWithColorMap3.png" width="300" title="DCM as an implant"> | + +### DCM for cable modeling to control deformable robots: +| Direct simulation of a soft gripper | The study the model convergence | +|------------------------------------------------------------------------------------------| --- | +| <img src="/doc/images/cosseratgripper_2.png" width="400" title="DCM for cable modeling"> | <img src="/doc/images/tenCossseratSections.png" width="400" title="DCM for cable modeling ">| + +### Some use cases + +| <img src="/doc/images/actuationConstraint_2.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="doc/images/circleActuationConstraint.png" width="300" title="DCM Beam actuation using a given cable"> | <img src="/doc/images/actuationConstraint_1.png" width="300" title="DCM Beam actuation using a cable"> | +| ------------- |:-------------:| -----:| +| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| + + +| <img src="/doc/images/example1.gif" width="300" title="PCS_Example1.py "> | <img src="./doc/images/example2.gif" widt="300" title="PCS_Example2.py"> | <img src="./doc/images/example2.gif" width="300" title="PCS_Example3.PCS"> | +| ------------- |:-------------:| -------------:| +| DCM Beam actuation using a cable ```d =``` | DCM Beam actuation using a cable ```d =```| Beam actuation using a cable ```d =```| + + +Format: ![Alt Text] + diff --git a/docs/testScene/tuto_1.py b/docs/testScene/tuto_1.py index 3475110c..803e4b28 100644 --- a/docs/testScene/tuto_1.py +++ b/docs/testScene/tuto_1.py @@ -2,67 +2,121 @@ import Sofa -stiffness_param = 1.e10 -beam_radius = 1. +stiffness_param = 1.0e10 +beam_radius = 1.0 def _add_rigid_base(p_node): - rigid_base_node = p_node.addChild('rigid_base') - rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", - position="0 0 0 0 0 0. 1", - showObject=1, showObjectScale='0.1') - rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, - angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", - points="0", template="Rigid3d") + rigid_base_node = p_node.addChild("rigid_base") + rigid_base_node.addObject( + "MechanicalObject", + template="Rigid3d", + name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, + showObjectScale="0.1", + ) + rigid_base_node.addObject( + "RestShapeSpringsForceField", + name="spring", + stiffness=stiffness_param, + angularStiffness=stiffness_param, + external_points="0", + mstate="@cosserat_base_mo", + points="0", + template="Rigid3d", + ) return rigid_base_node -def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): - cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') - cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', - position=bending_states) - cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', - length=list_sections_length, radius=2., youngModulus=1.e4, - poissonRatio=0.4) +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.0): + cosserat_coordinate_node = p_node.addChild("cosseratCoordinate") + cosserat_coordinate_node.addObject( + "MechanicalObject", + template="Vec3d", + name="cosserat_state", + position=bending_states, + ) + cosserat_coordinate_node.addObject( + "BeamHookeLawForceField", + crossSectionShape="circular", + length=list_sections_length, + radius=2.0, + youngModulus=1.0e4, + poissonRatio=0.4, + ) return cosserat_coordinate_node -def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): - cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') +def _add_cosserat_frame( + p_node, + _bending_node, + framesF, + _section_curv_abs, + _frame_curv_abs, + _radius, + _beam_mass=0.0, +): + cosserat_in_Sofa_frame_node = p_node.addChild("cosserat_in_Sofa_frame_node") _bending_node.addChild(cosserat_in_Sofa_frame_node) - frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', - name="FramesMO", position=framesF, showIndices=1, showObject=1, - showObjectScale=0.8) - - cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) - - cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, - curv_abs_output=_frame_curv_abs, name='cosseratMapping', - input1=_bending_node.cosserat_state.getLinkPath(), - input2=p_node.cosserat_base_mo.getLinkPath(), - output=frames_mo.getLinkPath(), debug=0, radius=_radius) + frames_mo = cosserat_in_Sofa_frame_node.addObject( + "MechanicalObject", + template="Rigid3d", + name="FramesMO", + position=framesF, + showIndices=1, + showObject=1, + showObjectScale=0.8, + ) + + cosserat_in_Sofa_frame_node.addObject("UniformMass", totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject( + "DiscreteCosseratMapping", + curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, + name="cosseratMapping", + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), + debug=0, + radius=_radius, + ) return cosserat_in_Sofa_frame_node def createScene(root_node): - root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') - root_node.gravity = [0, 0., 0] + root_node.addObject( + "VisualStyle", + displayFlags="showBehaviorModels showCollisionModels showMechanicalMappings", + ) + root_node.gravity = [0, 0.0, 0] # base_node = _add_rigid_base(root_node) # - cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending + cos_nul_state = [0.0, 0.1, 0.1] # torsion, y_bending, z_bending bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] - list_sections_length = [10, 10, 10] # SI units + list_sections_length = [10, 10, 10] # SI units bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) section_curv_abs = [0, 10, 20, 30] frames_curv_abs = [0, 10, 20, 30] - cosserat_G_frames = [[0., 0, 0, 0, 0, 0, 1], [10., 0, 0, 0, 0, 0, 1], [20., 0, 0, 0, 0, 0, 1], - [30., 0, 0, 0, 0, 0, 1]] - _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, - beam_radius) + cosserat_G_frames = [ + [0.0, 0, 0, 0, 0, 0, 1], + [10.0, 0, 0, 0, 0, 0, 1], + [20.0, 0, 0, 0, 0, 0, 1], + [30.0, 0, 0, 0, 0, 0, 1], + ] + _add_cosserat_frame( + base_node, + bending_node, + cosserat_G_frames, + section_curv_abs, + frames_curv_abs, + beam_radius, + ) return root_node diff --git a/docs/testScene/tuto_2.py b/docs/testScene/tuto_2.py index d063ec88..67c1f9ad 100644 --- a/docs/testScene/tuto_2.py +++ b/docs/testScene/tuto_2.py @@ -1,55 +1,104 @@ # -*- coding: utf-8 -*- -stiffness_param = 1.e10 -beam_radius = 1. +stiffness_param = 1.0e10 +beam_radius = 1.0 def _add_rigid_base(p_node): - rigid_base_node = p_node.addChild('rigid_base') - rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", - position="0 0 0 0 0 0. 1", - showObject=1, showObjectScale='0.1') - rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, - angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", - points="0", template="Rigid3d") + rigid_base_node = p_node.addChild("rigid_base") + rigid_base_node.addObject( + "MechanicalObject", + template="Rigid3d", + name="cosserat_base_mo", + position="0 0 0 0 0 0. 1", + showObject=1, + showObjectScale="0.1", + ) + rigid_base_node.addObject( + "RestShapeSpringsForceField", + name="spring", + stiffness=stiffness_param, + angularStiffness=stiffness_param, + external_points="0", + mstate="@cosserat_base_mo", + points="0", + template="Rigid3d", + ) return rigid_base_node -def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): - cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') - print(f' ===> bendind state : {bending_states}') - cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', - position=bending_states) - testNode = cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', - length=list_sections_length, radius=_radius, youngModulus=1.e4, - poissonRatio=0.4) - print(f' the dire of node is : {dir(testNode)}') +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.0): + cosserat_coordinate_node = p_node.addChild("cosseratCoordinate") + print(f" ===> bendind state : {bending_states}") + cosserat_coordinate_node.addObject( + "MechanicalObject", + template="Vec3d", + name="cosserat_state", + position=bending_states, + ) + testNode = cosserat_coordinate_node.addObject( + "BeamHookeLawForceField", + crossSectionShape="circular", + length=list_sections_length, + radius=_radius, + youngModulus=1.0e4, + poissonRatio=0.4, + ) + print(f" the dire of node is : {dir(testNode)}") return cosserat_coordinate_node -def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): - cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') +def _add_cosserat_frame( + p_node, + _bending_node, + framesF, + _section_curv_abs, + _frame_curv_abs, + _radius, + _beam_mass=0.0, +): + cosserat_in_Sofa_frame_node = p_node.addChild("cosserat_in_Sofa_frame_node") _bending_node.addChild(cosserat_in_Sofa_frame_node) - frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', - name="FramesMO", position=framesF, showIndices=0., showObject=0, - showObjectScale=0.8) - - cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) - - cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, - curv_abs_output=_frame_curv_abs, name='cosseratMapping', - input1=_bending_node.cosserat_state.getLinkPath(), - input2=p_node.cosserat_base_mo.getLinkPath(), - output=frames_mo.getLinkPath(), debug=0, radius=_radius) + frames_mo = cosserat_in_Sofa_frame_node.addObject( + "MechanicalObject", + template="Rigid3d", + name="FramesMO", + position=framesF, + showIndices=0.0, + showObject=0, + showObjectScale=0.8, + ) + + cosserat_in_Sofa_frame_node.addObject("UniformMass", totalMass=_beam_mass) + + cosserat_in_Sofa_frame_node.addObject( + "DiscreteCosseratMapping", + curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, + name="cosseratMapping", + input1=_bending_node.cosserat_state.getLinkPath(), + input2=p_node.cosserat_base_mo.getLinkPath(), + output=frames_mo.getLinkPath(), + debug=0, + radius=_radius, + ) return cosserat_in_Sofa_frame_node def createScene(root_node): - root_node.addObject('VisualStyle', displayFlags='showBehaviorModels showCollisionModels showMechanicalMappings') - root_node.gravity = [0, 0., 0] - root_node.addObject('EulerImplicitSolver', firstOrder="0", rayleighStiffness="0.0", rayleighMass='0.0') - root_node.addObject('SparseLDLSolver', name='solver') + root_node.addObject( + "VisualStyle", + displayFlags="showBehaviorModels showCollisionModels showMechanicalMappings", + ) + root_node.gravity = [0, 0.0, 0] + root_node.addObject( + "EulerImplicitSolver", + firstOrder="0", + rayleighStiffness="0.0", + rayleighMass="0.0", + ) + root_node.addObject("SparseLDLSolver", name="solver") # Add rigid base base_node = _add_rigid_base(root_node) @@ -57,25 +106,25 @@ def createScene(root_node): # build beam geometry nb_sections = 6 beam_length = 30 - length_s = beam_length/float(nb_sections) + length_s = beam_length / float(nb_sections) bending_states = [] list_sections_length = [] - temp = 0. # where to start the base position - section_curv_abs = [0.] # section/segment curve abscissa + temp = 0.0 # where to start the base position + section_curv_abs = [0.0] # section/segment curve abscissa for i in range(nb_sections): - bending_states.append([0, 0., 0.0]) # torsion, y_bending, z_bending + bending_states.append([0, 0.0, 0.2]) # torsion, y_bending, z_bending list_sections_length.append((((i + 1) * length_s) - i * length_s)) temp += list_sections_length[i] section_curv_abs.append(temp) - bending_states[nb_sections-1] = [0, 0.1, 0.2] + bending_states[nb_sections - 1] = [0, 0.0, 0.2] # call add cosserat state and force field bending_node = _add_cosserat_state(root_node, bending_states, list_sections_length) # comment : ??? nb_frames = 32 - length_f = beam_length/float(nb_frames) + length_f = beam_length / float(nb_frames) cosserat_G_frames = [] frames_curv_abs = [] cable_position_f = [] # need sometimes for drawing segment @@ -91,6 +140,13 @@ def createScene(root_node): cable_position_f.append([beam_length + x, y, z]) frames_curv_abs.append(beam_length + x) - _add_cosserat_frame(base_node, bending_node, cosserat_G_frames, section_curv_abs, frames_curv_abs, beam_radius) + _add_cosserat_frame( + base_node, + bending_node, + cosserat_G_frames, + section_curv_abs, + frames_curv_abs, + beam_radius, + ) return root_node From b34e570f646fa32b3e4b91e9e79bcd947bc5acd6 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Fri, 7 Jun 2024 00:00:52 +0200 Subject: [PATCH 39/71] Archive tutorial files for future reference (removed from docs) --- docs/text/Advanced Topics and Future Work.md | 48 ---- docs/text/Background Concepts.md | 71 ------ docs/text/Brouillons.md | 40 ---- docs/text/Complement.md | 82 ------- docs/text/Direct Simulation.md | 51 ----- docs/text/Introduction.md | 198 ----------------- docs/text/Inverse Simulation.md | 46 ---- ...el Convergence and Sensitivity Analysis.md | 51 ----- docs/text/Numerics.md | 10 - docs/text/Setting up the Environment.md | 204 ----------------- docs/text/Soft_robot_intro.md | 69 ------ docs/text/Theory.md | 40 ---- docs/text/cosserat_python_scene.md | 136 ------------ docs/text/cosserat_tutorial.md | 205 +++++++++++++++++- docs/text/oneDimensionModels.md | 45 ---- docs/text/tutorial.md | 121 ----------- 16 files changed, 204 insertions(+), 1213 deletions(-) delete mode 100644 docs/text/Advanced Topics and Future Work.md delete mode 100644 docs/text/Background Concepts.md delete mode 100644 docs/text/Brouillons.md delete mode 100644 docs/text/Complement.md delete mode 100644 docs/text/Direct Simulation.md delete mode 100644 docs/text/Introduction.md delete mode 100644 docs/text/Inverse Simulation.md delete mode 100644 docs/text/Model Convergence and Sensitivity Analysis.md delete mode 100644 docs/text/Numerics.md delete mode 100644 docs/text/Setting up the Environment.md delete mode 100644 docs/text/Soft_robot_intro.md delete mode 100644 docs/text/Theory.md delete mode 100644 docs/text/cosserat_python_scene.md mode change 120000 => 100644 docs/text/cosserat_tutorial.md delete mode 100644 docs/text/oneDimensionModels.md delete mode 100644 docs/text/tutorial.md diff --git a/docs/text/Advanced Topics and Future Work.md b/docs/text/Advanced Topics and Future Work.md deleted file mode 100644 index f21fe29c..00000000 --- a/docs/text/Advanced Topics and Future Work.md +++ /dev/null @@ -1,48 +0,0 @@ - -**Slide 1: Advanced Topics in Soft Robotics** - -- Title: Advanced Topics in Soft Robotics -- Content: - - Introduction to advanced topics and emerging areas in the field of soft robotics. - - Discussion of how soft robots are being used in various applications. - - Brief overview of the evolving challenges and opportunities in the domain. - ---- - -**Slide 2: Applications of Soft Robots** - -- Title: Applications of Soft Robots -- Content: - - Detailed exploration of practical applications where soft robots are making an impact. - - Examples of industries and domains benefiting from soft robotics (e.g., medical, automation, exploration). - - Emphasis on real-world scenarios where soft robots provide unique advantages. - ---- -**Slide 3: Future Work and Research Directions** - -- Title: Future Work and Research Directions -- Content: - - Presentation of potential research areas and directions for future work in soft robotics. - - Addressing unsolved challenges and open questions in the field. - - Discussion of how the combination of FEM and DCM can be extended and improved. ---- - -**Slide 4: Robotics in Education and Training** - -- Title: Robotics in Education and Training -- Content: - - Highlighting the role of educational and training programs in fostering expertise in soft robotics. - - Discussing how tutorials, like the one being prepared, can contribute to knowledge dissemination. - - Encouraging the audience to explore and contribute to the advancement of soft robotics. - ---- - -**Slide 5: Conclusion and Call to Action** - -- Title: Conclusion and Call to Action -- Content: - - Summarizing the key points discussed in the Advanced Topics and Future Work section. - - Inspiring the audience to take an active role in the field of soft robotics. - - Encouraging collaboration, innovation, and exploration of advanced topics. - - Thanking the audience for their attention and participation. ---- diff --git a/docs/text/Background Concepts.md b/docs/text/Background Concepts.md deleted file mode 100644 index 70c3b24b..00000000 --- a/docs/text/Background Concepts.md +++ /dev/null @@ -1,71 +0,0 @@ - -**Slide 1: Background Concepts - Introduction** - -- **Slide Title:** Understanding the Fundamentals - -**Content:** -- Briefly introduce the "Background Concepts" section. -- Explain that to grasp the hybrid FEM and DCM approach, participants need to understand some fundamental concepts. -- Highlight the importance of a strong foundation in soft robotics and simulation techniques. - ---- -**Slide 2: Soft Robotics Principles** - -- **Slide Title:** Soft Robotics: Core Principles - -**Content:** -- Define the core principles of soft robotics, including compliance, flexibility, and adaptability. -- Use images and examples to illustrate these principles. -- Emphasize the fundamental differences between soft robots and traditional rigid robots. ---- -[[cosserat_python_scene]] - - ---- -||X|Y|Z| -|---|---|---|---| -|0|0|0|0| -|1|0|0|0| -|2|0|0|0| -|3|0|0|0| -|4|0|0|0| -|5|0|0|-2.35| - - ---- - -**Slide 3: Finite Element Methods (FEM)** - -- **Slide Title:** FEM: A Cornerstone of Soft Robot Simulation - -**Content:** -- Provide an overview of Finite Element Methods (FEM) and their role in simulating soft robots. -- Explain how FEM breaks down complex structures into smaller elements. -- Describe how FEM handles material properties, deformations, and forces. -- Showcase real-world applications of FEM in soft robotics. - ---- - -**Slide 4: Deformable Continuous Models (DCM)** - -- **Slide Title:** DCM: Modeling Cable-Driven Mechanisms - -**Content:** -- Define Deformable Continuous Models (DCM) and their significance in soft robotics. -- Explain how DCM focuses on modeling cables and deformations in soft robots. -- Discuss the advantages of DCM, such as the representation of cable-driven actuation. -- Share practical examples of DCM applications in soft robotics. - ---- - -**Slide 5: Bridging the Gap with Hybrid Modeling** - -- **Slide Title:** Hybrid Modeling: Combining FEM and DCM - -**Content:** -- Introduce the core concept of the tutorial: the integration of FEM and DCM for more accurate simulations. -- Explain the motivations behind this hybrid approach. -- Highlight the complementary nature of FEM and DCM in simulating different aspects of soft robots. -- Preview the real-world implications and benefits of this hybrid modeling strategy. - ---- diff --git a/docs/text/Brouillons.md b/docs/text/Brouillons.md deleted file mode 100644 index 7f988840..00000000 --- a/docs/text/Brouillons.md +++ /dev/null @@ -1,40 +0,0 @@ - -**Overview** -Remember to make the tutorial interactive, engage the participants, and provide opportunities for questions and discussions. You may also consider sharing the tutorial materials, code, and relevant resources with participants for further learning and experimentation. - ---- -**Partie 1:** -Each slide should be visually engaging with relevant images, diagrams, and minimal text. You can also use this opportunity to set the tone for the tutorial, making it clear that participants are embarking on an exciting journey into the world of soft robotics simulations. - ---- -**Partie 2:** -Each slide should be visually appealing, with clear and concise explanations. Make use of diagrams, images, and bullet points to enhance understanding. The aim is to provide participants with a solid foundation in the background concepts essential for grasping the hybrid FEM and DCM approach. - ---- - -Configuring the environment with SOFA and the Cosserat plugin is a critical step in your soft robotics simulation journey. This subsection serves as a foundation for the practical implementation of the hybrid FEM and DCM approach, allowing you to accurately model and simulate soft robots with complex deformations and interactions. - ---- -- Voir Deformable Continuous Models (DCM) - ---- - -These five slides will provide a detailed overview of the "Inverse Simulation" subsection, explaining the purpose, examples, computational aspects, and concluding remarks. This will help your audience understand the role of Inverse Simulation in soft robotics. - ---- -These five slides will provide a detailed overview of the "Model Convergence and Sensitivity Analysis" subsection, explaining the purpose, examples, implications, and concluding remarks. This will help your audience understand the significance of these analyses in soft robotics. - ---- - -These five slides will provide a detailed overview of advanced topics, potential applications, future research directions, and the role of education and training in soft robotics. It will also motivate the audience to engage in the field and contribute to its growth. - - ----- -These ten slides incorporate elements from the provided paper and database, delivering a detailed introduction to the hybrid framework, its motivations, objectives, and contributions. It also includes an overview of FEM, DCM, advanced topics, and future work in the realm of soft robotics. The presentation concludes by encouraging the audience to explore the full paper for further information. - ---- - - -These ten slides provide a detailed introduction to the hybrid framework, its motivation, objectives, and contributions, as well as an overview of FEM, DCM, and a glimpse of advanced topics and future work in the field of soft robotics. It concludes by motivating the audience to explore the paper's contents. - ---- diff --git a/docs/text/Complement.md b/docs/text/Complement.md deleted file mode 100644 index faa8340b..00000000 --- a/docs/text/Complement.md +++ /dev/null @@ -1,82 +0,0 @@ -Certainly, here is an updated version of the extended introduction section with ten detailed slides, incorporating elements from the provided paper and relevant content from my database: - -**Slide 1: Title and Introduction** - -- Title: Introduction to the Hybrid Framework for Soft Robotics -- Content: - - Introduce the audience to the paper, "Hybrid Framework for Real-Time Simulation of Soft Robots." - - Highlight the focus on combining Finite Element Method (FEM) and Discrete Cosserat Models (DCM) in soft robotics. - - Briefly mention the key points covered in the following slides. - -**Slide 2: Soft Robots in Modern Applications** - -- Title: Soft Robots in Modern Applications -- Content: - - Showcase real-world examples of soft robots' applications in various domains. - - Cite specific instances where soft robots have revolutionized medical, industrial, and exploration fields. - - Highlight the need for adaptable and safe robotic systems. - -**Slide 3: Challenges in Soft Robotics Modeling** - -- Title: Modeling Challenges in Soft Robotics -- Content: - - Explain the unique modeling challenges in soft robotics arising from deformable materials. - - Discuss the importance of real-time simulations for control and decision-making in such robots. - - Reference previous research in the field that addresses these challenges. - -**Slide 4: The Hybrid Approach's Promise** - -- Title: Promise of a Hybrid Framework -- Content: - - Detail the motivations behind developing a hybrid framework combining FEM and DCM. - - Present the advantages of using FEM for deformable materials and DCM for cable-driven robots. - - Provide examples of applications where the hybrid framework can excel. - -**Slide 5: Research Objectives and Contributions** - -- Title: Research Objectives and Contributions -- Content: - - Define the primary objectives of the research presented in the paper. - - Highlight the key contributions this paper offers to the field of soft robotics. - - Give the audience a glimpse of what to expect in the upcoming sections. - -**Slide 6: Paper Structure and Roadmap** - -- Title: Paper Structure and Roadmap -- Content: - - Offer an overview of the paper's structure, detailing each section's focus. - - Provide a roadmap to guide the audience through different aspects of the hybrid framework. - - Help the audience navigate and follow the presentation. - -**Slide 7: The Role of FEM in Soft Robotics** - -- Title: Finite Element Method in Soft Robotics -- Content: - - Explain the role of FEM in modeling deformable materials for soft robots. - - Cite examples of soft robot components where FEM has been effectively applied. - - Emphasize FEM's capacity to handle geometric non-linearity. - -**Slide 8: Introduction to DCM for Cable-Driven Robots** - -- Title: Discrete Cosserat Models for Cable-Driven Robots -- Content: - - Delve into the details of DCM and its suitability for modeling cable-driven robots in soft robotics. - - Showcase real-world applications of cable-driven soft robots. - - Explain how DCM handles reduced coordinates for modeling efficiency. - -**Slide 9: Advanced Topics and Future Directions** - -- Title: Advanced Topics and Future Directions -- Content: - - Provide a preview of advanced topics that will be discussed later in the paper. - - Offer insights into potential future research directions in the field of soft robotics. - - Encourage the audience to explore these exciting areas for further study. - -**Slide 10: Conclusion and Call to Action** - -- Title: Conclusion and Call to Action -- Content: - - Summarize the importance of the hybrid framework for soft robotics. - - Invite the audience to read the full paper for comprehensive insights into the topic. - - Express gratitude for the audience's attention and participation. - diff --git a/docs/text/Direct Simulation.md b/docs/text/Direct Simulation.md deleted file mode 100644 index 82af0d81..00000000 --- a/docs/text/Direct Simulation.md +++ /dev/null @@ -1,51 +0,0 @@ ---- -title: Introduction to Direct Simulation ---- - ---- -**Slide 1: Introduction to Direct Simulation** - -- Title: Introduction to Direct Simulation -- Content: - - Definition of Direct Simulation. - - Purpose of Direct Simulation in soft robotics. - - Importance of accurately modeling deformable robots in real-time. - - Overview of the content covered in this subsection. ---- -**Slide 2: Simulation Setup** - -- Title: Simulation Setup -- Content: - - Detailed explanation of the simulation environment setup. - - Mention of the software used (SOFA) and the Cosserat plugin. - - Steps for setting up SOFA and enabling the Cosserat plugin. - - Loading example scenes for practical experimentation. - ---- -**Slide 3: Soft Gripper Example** - -- Title: Soft Gripper Example -- Content: - - Introduction to the soft gripper used in the simulation. - - Discussion on its mechanical properties and complexity. - - Highlighting the integration of DCM to simulate the cables. - - Mention of friction and contact constraints for realistic interaction with a rigid object. ---- -**Slide 4: Observations and Analysis** - -- Title: Observations and Analysis -- Content: - - Presentation of the results from the direct simulation of the soft gripper. - - Discussion on the influence of cable properties (e.g., radius) on the gripper's deformation. - - Emphasis on the effect of using pre-bent rods for manipulation. - - Visualization of stress levels in cables and materials. ---- -**Slide 5: Conclusions from Direct Simulation** - -- Title: Conclusions from Direct Simulation -- Content: - - Summarizing the key findings from the direct simulation experiments. - - Emphasis on the importance of accurately modeling cables and their interaction with deformable structures. - - Relating the results to the overall objective of combining FEM and DCM for soft robotics. - - Transition to the next subsection on "Inverse Simulation" and the broader tutorial structure. ---- diff --git a/docs/text/Introduction.md b/docs/text/Introduction.md deleted file mode 100644 index 600e7b1c..00000000 --- a/docs/text/Introduction.md +++ /dev/null @@ -1,198 +0,0 @@ ---- -tutorial: Introduction -tags: - - tuto/cosserat -cssclass: - - dashboard ---- -_Welcome to this tutorial on SOFA-Cosserat Plugin._ - -[Formation plugin : Cosserat - CodiMD](https://notes.inria.fr/gcfuFPDYSeeAlG4gzfDJwA#) - -Yinoussa Adagolodjo - ---- -#### SOFA - -- SOFA : Simulation Open Framework Architecture - - Dedicated to research -- Use for prototyping and development of physics-based simulation - - FEM / Rigid (articulated) Bodies / Contacts / Other models... - - Projections = MAPPING ! ---- -#### SOFA -- Free & Open Source: [https://www.sofa-framework.org/](https://www.sofa-framework.org/) - - Download, use, modify, cite and contribute to SOFA! -- International community and two major events per year  -- SOFA Week from $13-17^{th}$ of November  - - Onsite with online access - - Free – all you need is to register ---- -#### Tutorial Roadmap - -- What to expect ? - - An overview of the theory of Discrete Cosserat Model - - Numerics & Hands-on examples - - Reduce coordinates - - Reduce coordinate (Cosserat) to Global coordinate (SOFA) State - - Boundary conditions and interaction forces -- Ask your questions and actively participate throughout this tutorial. - - The first time I am doing this, so I need your feedback ---- -#### Introduction to Soft Robotics (SR) - -- Soft robotics is an emerging and innovative field of robotics -- Focuses on the design and development of robots made from : - - *Flexible*, - - *Deformable*, - - *Compliant materials*. ---- -#### Introduction to Soft Robotics (SR) -- Numerous advantages - - *Adaptability* : Their ability to deform and adapt to their environment - - *Safety* : Ideal for interactions with humans, delicate objects, or unstructured surroundings - - *Versatility* : Various applications - ---- -#### **Key Applications** - -- *Healthcare* : The gentle and non-invasive nature of SR is necessary -- *Industrial automation* : The high [Compliance](../../../Soft_Robot/Compliance.md), reduces the risk of damage during interactions with products -- *Search and rescue* : they can navigate through tight spaces and uneven terrains -- *Space exploration*, and *extreme environments* - ---- -#### **Challenges in Soft Robotics** - -- *Modeling* : due to non-linear deformable materials -- [*Control*](../../../Soft_Robot/kinematics_dynamics_control.md) : due to the non-linear, multi-body dynamics of deformable materials -- [*Multi-dimension*](../../../../../../Professionnel/research_md/Projects/ANR/brainStormingANR2023.md) : due to a wide range of shape, volume (3D), surface (2D) and cable (1D) -- [*Multi-physics*](../../../../../../Professionnel/research_md/Projects/ANR/RobotMulti-physics.md) : due a wide range of physical behaviors, including mechanical deformation, thermal effects, electrical responses, - ---- -#### **Challenges in Soft Robotics** - -- Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. -(To go further on the introduction of deformable robotics ⇾ [Introduction_General](../../../Soft_Robot/Introduction_General.md) ) - ---- -##### 1D models usage in Soft-robot modeling ? -- Introducing a versatile modeling tool for multidimensional Soft-Robot: -- 1D models are often used to represent the behavior of soft structures - - Cables, tubes, or fibers, that can deform in one dimension - - Examples include: - - Flexible arms actuated by cables or similar mechanisms (Robotics) - - Medical devices like endoscopes, needles, and catheters (Medical robotics) - ---- -##### How to model one 1D object ? see [oneDimensionModels](oneDimensionModels.md) -- **Geometric Methods** -- **Mechanics methods** -- *Statistical Methods* -- *Computational Methods* -- *Analytical Methods:* - ---- -##### Cosserat Theory (Mechanics) -Choose strain as generalized coordinates, defined in global (or local) frame! -![400](../images/Pasted%20image%2020231108233708.png) -[Lazarus et al. 2013] - ---- -- The configuration of the Cosserat rod is defined by its centerline r(s). -- The orientation of each mass point of the rod is represented by an orthonormal basis ($d_1(s), d_2(s), d_3(s)$) -- The three local modes of deformation of the elastic rod : - (b1) material curvature $κ_1$ related to the direction $d_1$ of the cross-section, (b2) material curvature $κ_2$ related to $d_2$, and $κ_3$ twist. ---- -##### Discrete Cosserat Modeling: DCM -- Serial rigid (6DoFs) bodies with reduced coordinates -![700](https://lh7-us.googleusercontent.com/q9X7GJY2GxkPSOqb7w_jzbsf5sIiUglQTnJDySqUer-mVAPQPr-ENDjkSMxFlB0LuyXX0DKcuMR3rKqdMmWGJiBBoXu9zM7sbXbgCrZZhKiD0mkcY7Pwru_J7JvyVSCD6o4cYXsV7L65TSJprRY_=nw) ---- -##### Discrete Cosserat Modeling: DCM -- Piece-wise Constant Strain (PCS, treats rigid, soft, or hybrid robots uniformly) -![500](https://lh7-us.googleusercontent.com/hzJA2pzS-naPfFkf-98bPkGsQ86ZGdGwqGW3-un56s3ZcVkdOB0_Jus4a9W_nqO7jU7Tt_FDzCrFIbfA9XFqaPBmmq-do-TIJkFn6NX-RimX2UlWBTis_7bKzAp7fEmIeiuOZ1FueZ5yxijFSJls=nw) ---- -##### Discrete Cosserat Modeling(DCM): Piece-Wise Constant Strain -- Models the deformation of a soft manipulator arm using a finite number of sections -- Assumes constant strains along each section -- Accounts for shears and torsion -- Simulates the inextensible behavior of a rod or cable -- Reduces model size, resulting in faster calculation times through the use of reduced coordinates. ---- -##### DCM (Kinematics) -- Configuration $g= \begin{pmatrix} \mathcal{R} & u \\ 0 & 1 \end{pmatrix} ∈SE(3)$ -- Strain $\begin{align}\xi(s,t) = g^{-1} \frac{\partial g}{\partial s} &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ -- Velocity $\begin{align}\eta(s,t) =g^{-1}\frac{\partial g}{\partial t} &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ ---- -##### DCM (Kinematics) - -- => Kinematics (deformation) : $\frac{\partial g}{\partial s} = g'=g\hat{\xi}$ ; $\dot{g} = g\hat{\eta}$ -- Differential Kinematics : $\eta'= \frac{\partial g}{\partial s} = \dot{\xi} - ad_{\xi}\eta$ -![](../images/Pasted%20image%2020231109002926.png) ---- -##### DCM (Dynamics) -![800](../images/Pasted%20image%2020231109003349.png) - ---- -##### DCM Dynamic -![](../images/Pasted%20image%2020231109003734.png) - ---- -##### Approximation via PCS, VS and PLS -![300](../images/Pasted%20image%2020231109003934.png) -- **PCS**: A local approximation scheme employing a local constant strain assumption. -- **VS**: A global approximation method based on the chosen basis functions. -- **PLS**: A local approximation scheme with a linear strain function assumption. ---- -##### PCS Cosserat -![](../images/Pasted%20image%2020231109004616.png) - ---- -##### Discrete Cosserat Modeling: DCM -###### Limitations: -- Challenges in simulating truss structures, intricate geometries, or volumetric deformations -- The PCS parametrization of a manipulator is not rooted in the arm's intrinsic variables ---- -##### Finite Element Modeling (FEM) -The Finite Element (FE) approach is typically represented by the position and velocity (global coordinates) of a system of interconnected nodes. -- This approach offers several advantages: - - **Versatility in object geometries:** It can be applied to a wide range of object geometries, including beams, shells, truss structures, and deformable volumes. - - **Material law customization:** Material properties can be tailored to meet specific requirements. - - **Ease of defining boundary conditions:** Boundary conditions for numerical models can be defined with ease. - - **Flexibility for creating truss structures:** Beams can be interconnected freely to create truss structures. ---- -##### Finite Element Modeling (FEM) -However, this approach also has limitations: -- **Time-consuming:** Simulations using the FE approach may be computationally intensive and time-consuming. -- **Additional constraints:** Additional constraints are often needed to prevent the extension of rod-like structures when modeling certain systems. ---- -##### Modeling Soft Robots: Combining DCM with FEM - -We combine Discrete Cosserat Modeling (DCM) with Finite Element Modeling (FEM) to harness the strengths of each model. This hybrid approach is particularly useful in scenarios like: -- Modeling the stiffness of cables used to actuate a soft robot with a deformable volumetric structure. -- This leads to a more realistic representation of the entire robot's behavior. -For example, it allows us to effectively simulate scenarios where inextensible cables are employed to control the motion of a soft robot. - ----- - *Combined Accuracy*: By combining FEM and DCM, you can leverage the strengths of both methods. FEM provides fine-grained material modeling, while DCM captures the shape and motion of deformable elements accurately. This leads to a more realistic representation of the entire robot's behavior. - -- *Unified Simulation Framework*:A combined FEM-DCM framework creates a unified simulation environment that can model both the deformable body of the robot (using FEM) and the actuation components (using DCM). This simplifies simulation setup and control algorithms. - ---- - -[Hands on](Setting%20up%20the%20Environment.md) - ---- - -[[Complement]] - ---- -##### [FEM and DCM](../../_docs/DCM_FEM.md) - -- *FEM's Material Modeling*: FEM excels at modeling the deformations and stress distributions in complex materials, including soft and deformable ones. It considers the local behavior of materials, making it more accurate for understanding the mechanical properties of soft robots. -- *Cosserat theory's Beam-Like Modeling*: DCM, on the other hand, is suitable for modeling the overall shape and bending of structures, making it a natural choice for cables, rods, and flexible elements in soft robots. ---- - - - - -![0](../images/Pasted%20image%2020231108234643.png) \ No newline at end of file diff --git a/docs/text/Inverse Simulation.md b/docs/text/Inverse Simulation.md deleted file mode 100644 index 3e8b6f27..00000000 --- a/docs/text/Inverse Simulation.md +++ /dev/null @@ -1,46 +0,0 @@ - -**Slide 1: Introduction to Inverse Simulation** - -- Title: Introduction to Inverse Simulation -- Content: - - Definition and purpose of Inverse Simulation in the context of soft robotics. - - Highlighting the role of Inverse Simulation in controlling deformable robots. - - Setting the stage for understanding how to determine cable actuation based on desired end-effector motion. ---- - -**Slide 2: Soft Finger Inverse Simulation** - -- Title: Soft Finger Inverse Simulation -- Content: - - Introduction to the soft finger model used for Inverse Simulation. - - Discussion on the complexity of the problem. - - Overview of the inputs and unknowns in the Inverse Simulation. - - Mention of constraints, including sliding constraints between DCM cable model and FEM silicone finger model. ---- -**Slide 3: Soft Tentacle Inverse Simulation** - -- Title: Soft Tentacle Inverse Simulation -- Content: - - Presentation of the soft tentacle robot used as an example for Inverse Simulation. - - Description of the scenario where the effector follows a predefined trajectory. - - Explanation of cable actuation to achieve desired end-effector motion. - - Highlighting the importance of controlling multiple cables in the inverse problem. ---- -**Slide 4: Timing and Computational Considerations** - -- Title: Timing and Computational Considerations -- Content: - - Discussing the computational resources required for Inverse Simulation. - - Mentioning the hardware used for the simulations. - - Providing a table with details on the number of elements, constraints, and computational time for each simulation scenario. - - Comparing the computational time between direct and inverse simulations. ---- -**Slide 5: Conclusions from Inverse Simulation** - -- Title: Conclusions from Inverse Simulation -- Content: - - Summarizing the key takeaways from the Inverse Simulation experiments. - - Emphasizing the challenges and complexities of solving inverse problems for deformable robots. - - Relating the results to the overall objective of combining FEM and DCM for soft robotics. - - Transition to the conclusion of the tutorial and future work. ---- diff --git a/docs/text/Model Convergence and Sensitivity Analysis.md b/docs/text/Model Convergence and Sensitivity Analysis.md deleted file mode 100644 index 61d482a7..00000000 --- a/docs/text/Model Convergence and Sensitivity Analysis.md +++ /dev/null @@ -1,51 +0,0 @@ - - -**Slide 1: Introduction to Model Convergence and Sensitivity Analysis** - -- Title: Introduction to Model Convergence and Sensitivity Analysis -- Content: - - Definition and purpose of Model Convergence and Sensitivity Analysis in the context of soft robotics. - - Explanation of why it's important to assess the convergence of the model and analyze its sensitivity. - - Setting the stage for understanding how variations in model parameters impact the behavior of deformable robots. - ---- - -**Slide 2: Assessing Model Convergence** - -- Title: Assessing Model Convergence -- Content: - - Discussing the concept of model convergence in the context of deformable robots. - - Explanation of how the model's behavior changes with varying numbers of sections. - - Presenting a specific example (soft finger) and its convergence with different numbers of cable sections. - - Highlighting the role of section numbers in ensuring a converged model. ---- -**Slide 3: Analyzing Model Sensitivity** - -- Title: Analyzing Model Sensitivity -- Content: - - Introduction to model sensitivity analysis for deformable robots. - - Explanation of how variations in parameters affect the model's response. - - Presenting results of sensitivity analysis in the context of cable radius. - - Discussing the observed impact on the deformation of the silicone finger with varying cable radii. - ---- - -**Slide 4: Implications for Design and Control** - -- Title: Implications for Design and Control -- Content: - - Discussing the practical implications of model convergence and sensitivity analysis. - - Explaining how these analyses can inform the design of soft robotic systems. - - Emphasizing the importance of parameter choices in controlling deformable robots. - - Providing insights into how these findings can be applied in real-world soft robotics applications. - ---- -**Slide 5: Conclusions from Model Convergence and Sensitivity Analysis** - -- Title: Conclusions from Model Convergence and Sensitivity Analysis -- Content: - - Summarizing the key takeaways from the Model Convergence and Sensitivity Analysis. - - Relating the results to the overall objective of combining FEM and DCM for soft robotics. - - Highlighting the significance of understanding convergence and sensitivity in modeling. - - Transitioning to the conclusion of the tutorial and future work. ---- diff --git a/docs/text/Numerics.md b/docs/text/Numerics.md deleted file mode 100644 index ebef7763..00000000 --- a/docs/text/Numerics.md +++ /dev/null @@ -1,10 +0,0 @@ - -### Spatial Discretization - -### Time Discretization - -### Reduce to Global State - -### Global to Reduce State - -### Boundary conditions and interaction forces \ No newline at end of file diff --git a/docs/text/Setting up the Environment.md b/docs/text/Setting up the Environment.md deleted file mode 100644 index 42b3973a..00000000 --- a/docs/text/Setting up the Environment.md +++ /dev/null @@ -1,204 +0,0 @@ ---- -cssclasses: - - dashboard - - multi-column - - two-column-list -tags: - - tuto/cosserat ---- -##### **Introduction to SOFA** -- Have SOFA installed on your machine -- Install Cosserat plugin - - In Tree - - Out Tree ---- -##### **Step 1: Installing SOFA** - -Before you begin with the specific Cosserat plugin, you need to install SOFA. Follow these steps: - -1. Go to the official SOFA website (https://www.sofa-framework.org/) to download the latest version. -2. Choose the appropriate version for your operating system (Windows, Linux, or macOS). -3. Follow the installation instructions for your OS. Typically, this involves extracting the downloaded archive and setting environment variables. ---- -##### **Step 2: Setting Up the Cosserat Plugin** -Now, we'll dive into the essential part – configuring the Cosserat plugin within SOFA. -1. **Create plugins folder:** - - Create folder externalPlugins - - **sofa** - - ├── **src** - - ├── **build** - - ├── **externalPlugins** - ---- -2. **Obtaining the Plugin:** -- GitHub : https://github.com/SofaDefrost/Cosserat -- Download the plugin : - - git clone git@github.com:SofaDefrost/Cosserat.git (if you are using ssh-key) - - git clone https://github.com/SofaDefrost/Cosserat.git - - or Download the **Zip** ---- - -**3. Add *CMakeList.txt* file inside the *externalPlugin* folder** -```Cmake - cmake_minimum_required(VERSION 3.1) - sofa_find_package(SofaFramework) - - sofa_add_subdirectory(plugin SofaPython3 SofaPython3 ON) # If you want to use python - sofa_add_subdirectory(plugin STLIB STLIB ON) # If you want to use python & Cosserat prefabs - sofa_add_subdirectory(plugin Cosserat Cosserat ON) -``` - ---- - -**4. Activating the Plugin:** To activate the Cosserat plugin, follow these steps: - -- Open your terminal and go to SOFA's **build-directory** - - run - ```bash - cmake-gui . - ``` - - In the *Search* bar, type **external**, - - In $SOFA\_EXTERNAL\_DIRECTORIES$ - - Fill in the empty box with: - - **path-to-cosserat-directory** - - Find the Cosserat plugin and enable it ---- - -5. **First Cosserat Scene: *tuto_1.py*** - - As said previously, this component is based on the PCS (Piece-wise Constant Strain) formulation. - ![](../images/Pasted%20image%2020231102173536.png) ---- -##### **Goals** : -- how to create a basic scene with the cosserat plugin - - It is important to note the difference between : - - **section** and **frames** - - **section** and **cross-section** -- The notion of force-field : here **BeamHookeLawForceField** -- The notion of mapping: here **DiscreteCosseratMapping** -- Functions: **apply, applyJ**, **applyJT** for forces and **ApplyJ^T** for constraints ---- -###### Start with the base -![600](images/exemple_rigid_translation.png) - ---- -###### The beam is always constructed along the x-axis -```python - def _add_rigid_base(p_node): - rigid_base_node = p_node.addChild('rigid_base') - rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", position="0 0 0 0 0 0. 1", showObject=1, showObjectScale='0.1') - rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", points="0", template="Rigid3d") - return rigid_base_node -``` - ---- -- Add Cosserat **Reduced coordinates** states (torsion and bending along y and z-axis) -- Add **BeamHookeLawForceField** based on the Hooke's Law -```python -def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): - cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') - cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', position=bending_states) - cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', length=list_sections_length, radius=2., youngModulus=1.e4, poissonRatio=0.4) - return cosserat_coordinate_node -``` - ---- -###### Parameters : -```python -list_sections_length = [10, 10, 10] -cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending -bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] -``` ---- -###### **BeamHookeLawForceField** -- **Force Computation**: The `addForce` method calculates and adds the forces acting on the beams. It uses Hooke's law to compute the forces based on the deformation of the beams and their properties. The computed forces are then stored in the `f` variable. ---- -- **Derivative of Force Computation**: The `addDForce` method computes the derivative of the forces with respect to the deformation. This is used for stiffness matrix calculations in the context of finite element simulations. - ---- -- **Stiffness Matrix Computation**: The `addKToMatrix` method is responsible for adding the stiffness matrix to the global matrix. This is used in FEM to represent the stiffness of the entire system. ---- -###### Add Mapped coordinates (frames) to the scene -- **Mapping** between **Reduced coordinates** (Cosserat's state) and Global cordinates (Sofa state). - - Frames are multi-mapped (under Cosserat state and rigid base) -![400](../images/CosseratMapping.png) ---- -```python -def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): - cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') - _bending_node.addChild(cosserat_in_Sofa_frame_node) - frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showIndices=0., showObject=0, showObjectScale=0.8) - - cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) - cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs, name='cosseratMapping', input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(), output=frames_mo.getLinkPath(), debug=0, radius=_radius) - return cosserat_in_Sofa_frame_node -``` ---- -###### The notion of mapping: **DiscreteCosseratMapping** -- **apply** : It calculates how the positions of elements in the input models (deformations and base) are transformed to the output model (rigid frames). The function applies the mapping to these input positions and updates the output frames accordingly. -- **applyJ** : compute the Jacobian matrix for the mapping operation. How small changes in input velocity (in this case, deformations) affect small changes in output velocity (in this case, the rigid frames). ---- - -- **applyJT force** : It updates forces in reduced coordinate based on forces in global coordinate. -- **applyJT Constraint** : It updates constraints in reduced coordinate based on constraints in global coordinate. - -###### The complete scene ![tuto_1.py](../testScene/tuto_1.py) ----- -- [x] Example 2: **![tuto_2.py](../testScene/tuto_2.py)** - - script for automating sections and frames - - **Goal**: show the role of the number of sections on the overall deformation - - Example: - - 6 sections; 32 frames: $b_y=0.2$ on the last bending_state - - 12 sections 32 frames: $b_y=0.2$ on the last bending_state - - 6 sections 6 frames: all variables $b_y=0.2$ - - Change to frames = 12/24/32 - - Shows that we have a smoother curvature than previously while emphasizing the fact that there is rather a geometry impact, but not a physical one. ----- - -- Scene **![tuto_3](../testScene/tuto_3.py)** - - Use the $CosseratBase$ Python class and $prefabs$ -```python -def createScene(root_node): - addHeader(root_node) - root_node.gravity = [0, -9.81, 0.] - solver_node = addSolverNode(root_node, name="solver_node") - - # create cosserat Beam - solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) - return root_node -``` ---- -- Uses also python $dataclass$ -```python -- geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1,nbSection=6, nbFrames=12, buildCollisionModel=0) -- physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., beamLength=30) -- simuParams = SimulationParameters() -- Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) - -``` ---- -##### Some known examples ![tuto_4](../testScene/tuto_4.py) - - Force type 1 - - Force type 2 - - Force type 3 - ---- -##### FEM & DCM coupling for finger actuation ![tuto_5.py](../testScene/tuto_5.py) -- The cable is modeled using the DCM -- The finger is modeled using FEM -- Constraints are based on the Lagrange multiplier - - **QPSlidingConstraint** - - **DifferenceMultiMapping** - ---- -##### An example of the use of pre-curved cables, use cases (see scenes from Flavie) [tuto9.py](http://tuto9.py) - ---- -##### Scene of three fingers lifting a cube ****[tuto8.py](http://tuto8.py)*** - ----- - -**Adding Constraints:** Depending on your simulation, you might need to introduce constraints that describe the interaction between the robot and its environment. This is also an essential part of configuring the scene. - ---- - ---- diff --git a/docs/text/Soft_robot_intro.md b/docs/text/Soft_robot_intro.md deleted file mode 100644 index c21abe9e..00000000 --- a/docs/text/Soft_robot_intro.md +++ /dev/null @@ -1,69 +0,0 @@ ---- -title: Introduction to Soft Robotics ---- - - -**Slide 1: Soft Robotics - A New Frontier** - -- Content: - - Soft robotics is an emerging and innovative field of robotics that focuses on the design and development of robots made from flexible, deformable, and compliant materials. - - Soft robotics is a cutting-edge field that focuses on the design and development of robots using compliant and deformable materials. - - These robots are in stark contrast to traditional rigid robots and offer numerous advantages, including adaptability, safety, and versatility in various applications. - ---- -**Slide 2: Characteristics of Soft Robots** - -- Content: - - Soft robots are characterized by their ability to deform and adapt to their environment, making them ideal for interactions with humans, delicate objects, or unstructured surroundings. - - Their compliance and flexibility are key attributes that enable them to handle complex tasks. - ---- - -**Slide 3: Applications in Healthcare** - -- Content: - - Soft robotics has found significant applications in the healthcare industry, where the gentle and non-invasive nature of soft robots is leveraged for tasks such as minimally invasive surgery and rehabilitation. - - Examples include surgical robots that can navigate delicate tissues with precision. ---- - -**Slide 4: Industrial Automation** - -- Content: - - In industrial automation, soft robots are increasingly used for tasks such as pick-and-place operations, packaging, and assembly. - - The compliance of soft robots reduces the risk of damage during interactions with products. ---- -**Slide 5: Search and Rescue Operations** - -- Content: - - Soft robots are being explored for search and rescue operations, where they can navigate through tight spaces and uneven terrains. - - These robots can be vital in disaster-stricken areas to locate survivors. - -**Slide 6: Space Exploration and Extreme Environments** - -- Content: - - Soft robots have potential applications in space exploration due to their ability to adapt to different environments. - - They can also be used in extreme environments on Earth, such as deep-sea exploration or nuclear decommissioning. - -**Slide 7: Challenges in Soft Robotics** - -- Content: - - Despite their promise, soft robots present unique challenges in modeling, control, and actuation. - - Addressing these challenges is crucial for the widespread adoption of soft robots in various fields. - -**Slide 8: Interdisciplinary Nature** - -- Content: - - Soft robotics is inherently interdisciplinary, drawing from fields like materials science, biomechanics, and control theory. - - Collaboration between experts from different domains is essential to advance the field. - -**Slide 9: Future Directions** - -- Content: - - The field of soft robotics continues to evolve, with ongoing research to overcome challenges and expand applications. - - Future directions include advancements in materials, control strategies, and the integration of soft robots into everyday life. - -**Slide 10: Conclusion** - -- Content: - - In conclusion, soft robotics represents a paradigm shift in the field of robotics, offering exciting possibilities for various industries. - - As technology advances and interdisciplinary collaboration thrives, soft robots are poised to transform the way we interact with machines and the world around us. \ No newline at end of file diff --git a/docs/text/Theory.md b/docs/text/Theory.md deleted file mode 100644 index 64beb6e0..00000000 --- a/docs/text/Theory.md +++ /dev/null @@ -1,40 +0,0 @@ ---- -marp: -tags: - - tuto/cosserat -cssclasses: - - multi-column - - two-column-list - - two-columns ---- - -Solide Works -![](../images/Pasted%20image%2020231025171449.png) - ---- - -![[../images/Untitled Diagram.svg]] - ---- - -#### Mathematical Description of Cosserat Rods - -##### Cosserat differential Kinematics - ->[!blank-container] ->- Configuration $g= \begin{pmatrix} \mathcal{R} & u \\ 0 & 1 \end{pmatrix} ∈SE(3)$ ->- Velocity $\eta(s,t) =\begin{align}y &= \begin{bmatrix}\mathcal{w} \\ \mathcal{v} \end{bmatrix}\end{align} \in R^6$ ->- Strain $\xi(s,t) =\begin{align}y &= \begin{bmatrix}\mathcal{k} \\ \mathcal{p} \end{bmatrix}\end{align} \in R^6$ - ---- -#### Reference Frames - ---- - -### Conservation of Momentum - ---- -### Linear Elasticity - - ---- \ No newline at end of file diff --git a/docs/text/cosserat_python_scene.md b/docs/text/cosserat_python_scene.md deleted file mode 100644 index 1893f237..00000000 --- a/docs/text/cosserat_python_scene.md +++ /dev/null @@ -1,136 +0,0 @@ -# Principes de base - -<aside> 💡 _Toutes les informations concernant le logiciel SOFA peuvent être retrouver sur le site : [SOFA – Documentation (sofa-framework.org)](https://www.sofa-framework.org/community/doc/), pour y comprendre le concept, les principes, ... ._ -</aside> - -## Théorie de Cosserat - -Cosserat sur base sur la notion de _Piecewise Constant Strain_. Elle repose sur le fait d’estimer la **deformation** de manière très grossière, comme ci-dessous. - -![PCS.png](images/PCS.png) - -### Base rigide - -![rigidbase.png](images/rigidbase.png) - -Comme son nom l’indique ici il s’agit de la base de la poutre. Il s’agit d’un repère qui pouvant être assigné à une translation et/ou rotations désirée, et qui résultera d’une position finale. A noter, que le repère est toujours associé à un ressort afin d’être fixe dans le repère global de SOFA. - -$$ Rotation =[x , y, z] $$ - -$$ Translation = [x,y,z] $$ - -$$ Position = [x , y, z, xq, yq, zq, wq] $$ - -### Exemple - Base rigide - -![exemple rigid translation.png](images/exemple_rigid_translation.png) - -$$ Rotation =[0 , 0, 0] $$ - -$$ Translation = [0,1,0] $$ - -$$ Position = [0 , 1, 0, 0, 0, 0, 1] $$ - -### Section - -![noeud curv.png](images/noeud_curv.png) - -Les sections sont situées dans le repère local de Cosserat. Une section représente la distance entre deux nœuds : - -$$ L0 /L1 = Section 1 $$ - -$$ L1/L2 = Section 2 $$ - -Une cross-section est une partie de la poutre qu’on vient couper de manière transversale. De manière générale, on suppose que les cross sections sont rondes et ont le même rayon tout le long de la poutre. Mais il est possible que la forme de la poutre ne soit pas circulaire mais rectangulaire, et que le rayon change d’une distance à une autre. Les coordonnées des sections et des noeuds se retrouvent dans un tableau nommé “curv_abs_input” (:Curviligne abscisse inputs). - -<aside> ❗ _**Attention à ne pas confondre : section et cross-section. Ceux ne sont pas les mêmes notions**_ - -</aside> - -Il est possible d’appliquer une déformation à partir d’un certain nœud, les deux déformations possibles sont la torsion (selon x), et la flexion (selon y ou z). - -$$ positionS = [x,y,z] $$ - -$$ Flexion = -+(1/LenghtSection) * pi $$ - -Pi : Angle de rotation - -(1/LengthSection) : Vecteur unitaire (normalisation) - --/+ : Sens de rotation - -### Exemple - Section (1) - -Pour une poutre de longueur de 8cm avec un nombre de sections de 6 on a : - -![exemple curv abs input.png](images/exemple_curv_abs_input.png) - -**Tableau curv_abs_input :** - -![Untitled](images/Untitled.png) - -### Exemple - Section (2) - -Pour une poutre de longueur de 8cm avec un nombre de sections de 6 on a : - -![position 90degres.png](images/position_90degres.png) - -**Tableau curv_abs_input :** - -||X|Y|Z| -|---|---|---|---| -|0|0|0|0| -|1|0|0|0| -|2|0|0|0| -|3|0|0|0| -|4|0|0|0| -|5|0|0|-2.35| - -### Frame - -![frame1.png](images/frame1.png) - -La frame est représenté dans le repère locale de Cosserat, puis elle est intégrée dans le repère global de SOFA. Une frame est représentée comme les bases rigides, on retrouve les coordonnées de translation et rotation : - -$$ R :[x , y, z, 0, 0, 0, 1] $$ - -Les frames ne sont pas obligatoirement à équidistances les unes par rapport aux autres. Il est possible de concentrer un certain nombre de frames à un certain endroit, ce qui permet une rapidité de calcul sur l’endroit d’étude désirée. - -<aside> 💡 Plus le nombre de frame augmentent plus la précision de la courbe sera haute. ****** - -</aside> - -## Plugin Cosserat - SOFA - -### RigidBases - -- MechanicalObject - - - Coordonnées du système : - - $$ R :[x , y, z, 0, 0, 0, 1] $$ - -- Spring - - Rigidité - - Rigidité angulaire - -### CosseratCoordinate - -- MechanicalObject - - Nombre de sections - - Taille totale de la poutre -- BeamHookLaw - - Forme de la cross-section - - Taille de la section - - Rayon - -### CosseratFrame - -- MechanicalObject - - Nombre de frame - - Taille totale de la poutre -- CosseratMapping - - MechanicalObject de RigidBases - - MechanicalObject de Cosserat Coordinate - - Curv in - - Curv out \ No newline at end of file diff --git a/docs/text/cosserat_tutorial.md b/docs/text/cosserat_tutorial.md deleted file mode 120000 index c8e94902..00000000 --- a/docs/text/cosserat_tutorial.md +++ /dev/null @@ -1 +0,0 @@ -/Users/yadagolo/travail/plugin/plugin.Cosserat/examples/python3/tutorial/tutorial.md \ No newline at end of file diff --git a/docs/text/cosserat_tutorial.md b/docs/text/cosserat_tutorial.md new file mode 100644 index 00000000..42b3973a --- /dev/null +++ b/docs/text/cosserat_tutorial.md @@ -0,0 +1,204 @@ +--- +cssclasses: + - dashboard + - multi-column + - two-column-list +tags: + - tuto/cosserat +--- +##### **Introduction to SOFA** +- Have SOFA installed on your machine +- Install Cosserat plugin + - In Tree + - Out Tree +--- +##### **Step 1: Installing SOFA** + +Before you begin with the specific Cosserat plugin, you need to install SOFA. Follow these steps: + +1. Go to the official SOFA website (https://www.sofa-framework.org/) to download the latest version. +2. Choose the appropriate version for your operating system (Windows, Linux, or macOS). +3. Follow the installation instructions for your OS. Typically, this involves extracting the downloaded archive and setting environment variables. +--- +##### **Step 2: Setting Up the Cosserat Plugin** +Now, we'll dive into the essential part – configuring the Cosserat plugin within SOFA. +1. **Create plugins folder:** + - Create folder externalPlugins + - **sofa** + - ├── **src** + - ├── **build** + - ├── **externalPlugins** + +--- +2. **Obtaining the Plugin:** +- GitHub : https://github.com/SofaDefrost/Cosserat +- Download the plugin : + - git clone git@github.com:SofaDefrost/Cosserat.git (if you are using ssh-key) + - git clone https://github.com/SofaDefrost/Cosserat.git + - or Download the **Zip** +--- + +**3. Add *CMakeList.txt* file inside the *externalPlugin* folder** +```Cmake + cmake_minimum_required(VERSION 3.1) + sofa_find_package(SofaFramework) + + sofa_add_subdirectory(plugin SofaPython3 SofaPython3 ON) # If you want to use python + sofa_add_subdirectory(plugin STLIB STLIB ON) # If you want to use python & Cosserat prefabs + sofa_add_subdirectory(plugin Cosserat Cosserat ON) +``` + +--- + +**4. Activating the Plugin:** To activate the Cosserat plugin, follow these steps: + +- Open your terminal and go to SOFA's **build-directory** + - run + ```bash + cmake-gui . + ``` + - In the *Search* bar, type **external**, + - In $SOFA\_EXTERNAL\_DIRECTORIES$ + - Fill in the empty box with: + - **path-to-cosserat-directory** + - Find the Cosserat plugin and enable it +--- + +5. **First Cosserat Scene: *tuto_1.py*** + - As said previously, this component is based on the PCS (Piece-wise Constant Strain) formulation. + ![](../images/Pasted%20image%2020231102173536.png) +--- +##### **Goals** : +- how to create a basic scene with the cosserat plugin + - It is important to note the difference between : + - **section** and **frames** + - **section** and **cross-section** +- The notion of force-field : here **BeamHookeLawForceField** +- The notion of mapping: here **DiscreteCosseratMapping** +- Functions: **apply, applyJ**, **applyJT** for forces and **ApplyJ^T** for constraints +--- +###### Start with the base +![600](images/exemple_rigid_translation.png) + +--- +###### The beam is always constructed along the x-axis +```python + def _add_rigid_base(p_node): + rigid_base_node = p_node.addChild('rigid_base') + rigid_base_node.addObject('MechanicalObject', template='Rigid3d', name="cosserat_base_mo", position="0 0 0 0 0 0. 1", showObject=1, showObjectScale='0.1') + rigid_base_node.addObject('RestShapeSpringsForceField', name='spring', stiffness=stiffness_param, angularStiffness=stiffness_param, external_points="0", mstate="@cosserat_base_mo", points="0", template="Rigid3d") + return rigid_base_node +``` + +--- +- Add Cosserat **Reduced coordinates** states (torsion and bending along y and z-axis) +- Add **BeamHookeLawForceField** based on the Hooke's Law +```python +def _add_cosserat_state(p_node, bending_states, list_sections_length, _radius=2.): + cosserat_coordinate_node = p_node.addChild('cosseratCoordinate') + cosserat_coordinate_node.addObject('MechanicalObject', template='Vec3d', name='cosserat_state', position=bending_states) + cosserat_coordinate_node.addObject('BeamHookeLawForceField', crossSectionShape='circular', length=list_sections_length, radius=2., youngModulus=1.e4, poissonRatio=0.4) + return cosserat_coordinate_node +``` + +--- +###### Parameters : +```python +list_sections_length = [10, 10, 10] +cos_nul_state = [0.0, 0.0, 0.0] # torsion, y_bending, z_bending +bending_states = [cos_nul_state, cos_nul_state, cos_nul_state] +``` +--- +###### **BeamHookeLawForceField** +- **Force Computation**: The `addForce` method calculates and adds the forces acting on the beams. It uses Hooke's law to compute the forces based on the deformation of the beams and their properties. The computed forces are then stored in the `f` variable. +--- +- **Derivative of Force Computation**: The `addDForce` method computes the derivative of the forces with respect to the deformation. This is used for stiffness matrix calculations in the context of finite element simulations. + +--- +- **Stiffness Matrix Computation**: The `addKToMatrix` method is responsible for adding the stiffness matrix to the global matrix. This is used in FEM to represent the stiffness of the entire system. +--- +###### Add Mapped coordinates (frames) to the scene +- **Mapping** between **Reduced coordinates** (Cosserat's state) and Global cordinates (Sofa state). + - Frames are multi-mapped (under Cosserat state and rigid base) +![400](../images/CosseratMapping.png) +--- +```python +def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _frame_curv_abs, _radius, _beam_mass=0.0): + cosserat_in_Sofa_frame_node = p_node.addChild('cosserat_in_Sofa_frame_node') + _bending_node.addChild(cosserat_in_Sofa_frame_node) + frames_mo = cosserat_in_Sofa_frame_node.addObject('MechanicalObject', template='Rigid3d', name="FramesMO", position=framesF, showIndices=0., showObject=0, showObjectScale=0.8) + + cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, curv_abs_output=_frame_curv_abs, name='cosseratMapping', input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(), output=frames_mo.getLinkPath(), debug=0, radius=_radius) + return cosserat_in_Sofa_frame_node +``` +--- +###### The notion of mapping: **DiscreteCosseratMapping** +- **apply** : It calculates how the positions of elements in the input models (deformations and base) are transformed to the output model (rigid frames). The function applies the mapping to these input positions and updates the output frames accordingly. +- **applyJ** : compute the Jacobian matrix for the mapping operation. How small changes in input velocity (in this case, deformations) affect small changes in output velocity (in this case, the rigid frames). +--- + +- **applyJT force** : It updates forces in reduced coordinate based on forces in global coordinate. +- **applyJT Constraint** : It updates constraints in reduced coordinate based on constraints in global coordinate. + +###### The complete scene ![tuto_1.py](../testScene/tuto_1.py) +---- +- [x] Example 2: **![tuto_2.py](../testScene/tuto_2.py)** + - script for automating sections and frames + - **Goal**: show the role of the number of sections on the overall deformation + - Example: + - 6 sections; 32 frames: $b_y=0.2$ on the last bending_state + - 12 sections 32 frames: $b_y=0.2$ on the last bending_state + - 6 sections 6 frames: all variables $b_y=0.2$ + - Change to frames = 12/24/32 + - Shows that we have a smoother curvature than previously while emphasizing the fact that there is rather a geometry impact, but not a physical one. +---- + +- Scene **![tuto_3](../testScene/tuto_3.py)** + - Use the $CosseratBase$ Python class and $prefabs$ +```python +def createScene(root_node): + addHeader(root_node) + root_node.gravity = [0, -9.81, 0.] + solver_node = addSolverNode(root_node, name="solver_node") + + # create cosserat Beam + solver_node.addChild(CosseratBase(parent=solver_node, params=Params)) + return root_node +``` +--- +- Uses also python $dataclass$ +```python +- geoParams = BeamGeometryParameters(init_pos=[0., 0., 0.], beamLength=30., showFramesObject=1,nbSection=6, nbFrames=12, buildCollisionModel=0) +- physicsParams = BeamPhysicsParameters(beamMass=1., youngModulus=1.0e4, poissonRatio=0.38, beamRadius=1., beamLength=30) +- simuParams = SimulationParameters() +- Params = Parameters(beamGeoParams=geoParams, beamPhysicsParams=physicsParams, simuParams=simuParams) + +``` +--- +##### Some known examples ![tuto_4](../testScene/tuto_4.py) + - Force type 1 + - Force type 2 + - Force type 3 + +--- +##### FEM & DCM coupling for finger actuation ![tuto_5.py](../testScene/tuto_5.py) +- The cable is modeled using the DCM +- The finger is modeled using FEM +- Constraints are based on the Lagrange multiplier + - **QPSlidingConstraint** + - **DifferenceMultiMapping** + +--- +##### An example of the use of pre-curved cables, use cases (see scenes from Flavie) [tuto9.py](http://tuto9.py) + +--- +##### Scene of three fingers lifting a cube ****[tuto8.py](http://tuto8.py)*** + +---- + +**Adding Constraints:** Depending on your simulation, you might need to introduce constraints that describe the interaction between the robot and its environment. This is also an essential part of configuring the scene. + +--- + +--- diff --git a/docs/text/oneDimensionModels.md b/docs/text/oneDimensionModels.md deleted file mode 100644 index d7a9972b..00000000 --- a/docs/text/oneDimensionModels.md +++ /dev/null @@ -1,45 +0,0 @@ ---- -tutorial: one Dimension Models -tags: - - tuto/cosserat -cssclass: - - dashboard ---- -When modeling one-dimensional objects, various methods can be used, drawing from principles of geometry, mechanics, and other disciplines. Here are some common methods used for modeling one-dimensional objects: - -1. **Geometric Methods:** These focus on the shape, size, and arrangement of the one-dimensional objects in space. For example, you could use coordinate geometry to represent a 1D object (like a line segment) in terms of its endpoints or parametric equations. Another approach is to employ calculus methods to describe the curvature, length, or other geometric properties of the object. - - **Point Mass Model:** Simplifies an object to a single point with mass, useful for analyzing motion and dynamics. - - **Beam Theory:** Treats the object as a slender beam with one-dimensional deformation, commonly used for analyzing the behavior of structures like beams, rods, or cables. - - **Curve Modeling:** Represents the object as a one-dimensional curve in space, often used in computer graphics and animation for modeling shapes and trajectories. - -2. **Mechanics Methods:** These involve studying the forces, stresses, and -deformations that occur when you apply physical actions on one-dimensional -objects. In this case, you might use the laws of motion (e.g., Newton's Laws) or -Hooke's law to determine how an object will respond under different conditions. -For instance, you could model a spring as a one-dimensional elastic object and -apply mechanical methods to study its behavior under varying levels of tension. - - - **Differential Equations:** Describes the behavior of one-dimensional objects using differential equations derived from principles of mechanics, such as Newton's laws of motion or Euler-Bernoulli beam theory. - - **Finite Element Method (FEM):** Divides the object into small elements and solves differential equations numerically, commonly used for simulating the behavior of complex structures under various loading conditions. - - **Lagrangian Mechanics:** Describes the motion of one-dimensional objects using generalized coordinates and the principle of least action, useful for analyzing systems with constraints and forces. - -3. **Statistical Methods:** When modeling large collections of one-dimensional objects (e.g., particles in a fluid) or studying probabilistic properties (like the distribution of particle positions), you may use statistical methods such as stochastic processes, probability distributions, or ensemble averaging techniques. - - **Random Walks:** Models the stochastic motion of one-dimensional objects by simulating random steps or displacements, often used in the study of diffusion processes and Brownian motion. - - **Markov Chains:** Describes the probabilistic transitions of one-dimensional objects between different states or configurations, useful for modeling systems with discrete states and transition probabilities. - -4. **Computational Methods:** These involve using numerical algorithms and computational -techniques to approximate the solution to mathematical or physical problems -related to 1D objects. For example, you could use finite difference or finite -element methods to model the distribution of stresses within a one-dimensional -structure under mechanical loading. - - - **Numerical Integration:** Approximates the behavior of one-dimensional objects by discretizing time or space and using numerical integration techniques, such as Euler's method or Runge-Kutta methods. - - **Monte Carlo Simulation:** Generates random samples to simulate the behavior of one-dimensional objects and estimate statistical properties, useful for studying systems with complex interactions and uncertainty. - -5. **Analytical Methods:** In some cases, it may be possible to derive an exact -analytical solution for a given problem involving a 1D object. For example, you -might use trigonometric functions or other mathematical tools to find the -general solution for a one-dimensional wave equation. - - **Analytical Solutions:** Derives closed-form solutions to differential equations describing the behavior of one-dimensional objects, often used for simple systems with well-defined boundary conditions and material properties. - -These methods can be combined and adapted to suit the specific characteristics and requirements of the system being modeled, providing valuable insights into the behavior of one-dimensional objects in various fields of science and engineering. \ No newline at end of file diff --git a/docs/text/tutorial.md b/docs/text/tutorial.md deleted file mode 100644 index 4aaaa839..00000000 --- a/docs/text/tutorial.md +++ /dev/null @@ -1,121 +0,0 @@ ---- -title: DCM-FEM for Soft-Robot modeling Tutorial -tags: - - tutorial -Audience: Researchers, engineers, and students interested in soft robotics and the simulation of deformable robots. -Duration: This tutorial can vary in duration based on the depth and complexity of the material, but a typical plan could span 2-4 hours. -Prerequisites: Participants should have a basic understanding of robotics, mechanics, and computer simulations. Knowledge of finite element methods (FEM) and rigid body dynamics can be helpful. -cssclasses: - - dashboard ---- - -_Welcome to this tutorial on SOFA-Cosserat Plugin._ - -[Formation plugin : Cosserat - CodiMD](https://notes.inria.fr/gcfuFPDYSeeAlG4gzfDJwA#) - -Yinoussa Adagolodjo - ---- -#### SOFA - -- SOFA : Simulation Open Framework Architecture - - Dedicated to research -- Use for prototyping and development of physics-based simulation - - FEM / Rigid (articulated) Bodies / Contacts / Other models... - - Projections = MAPPING ! ---- -#### SOFA -- Free & Open Source: [https://www.sofa-framework.org/](https://www.sofa-framework.org/) - - Download, use, modify, cite and contribute to SOFA! -- International community and two major events per year  -- SOFA Week from $13-17^{th}$ of November  - - Onsite with online access - - Free – all you need is to register ---- -#### Tutorial Roadmap - -- What to expect ? - - An overview of the theory of Discrete Cosserat Model - - Numerics & Hands-on examples - - Reduce coordinates - - Reduce coordinate (Cosserat) to Global coordinate (SOFA) State - - Boundary conditions and interaction forces -- Ask your questions and actively participate throughout this tutorial. - - The first time I am doing this, so I need your feedback ---- -#### [Introduction](Introduction.md) - -- Briefly introduce the field of soft robotics -- The motivation for combining FEM and DCM models. - - ---- -#### [Setting up the Environment](Setting%20up%20the%20Environment.md) -- An overview of Discrete Cosserat Model (DCM) -- The software tools and libraries used (SOFA, **Cosserat** plugin). -- Instructions for setting up the simulation environment. -- [cosserat_python_scene](cosserat_python_scene.md) - ---- -## [Background Concepts](Background%20Concepts.md) -- An overview of Discrete Cosserat Model (DCM) and their relevance in soft robotics. -- Finite Element Methods (FEM) and their use in simulating deformable structures ? -- The concept of compliance matrices and their role in soft robot modeling ? ---- -## [Direct Simulation](Direct%20Simulation.md) - - How to - - Build the DCM scene ? - - Integrate it with FEM for the soft body ? - - The direct simulation of a soft robot (e.g., the gripper example from the paper). - - The role of constraints, friction, and contact forces. - ---- - -## [Inverse Simulation](Inverse%20Simulation.md) - - Demonstrate an inverse simulation for soft robots (e.g., using the soft finger or tentacle as examples). - - Explain how to compute actuation values to achieve desired end-effector positions. - - Discuss the handling of sliding constraints in the inverse problem. - ---- - -## [Model Convergence and Sensitivity Analysis](Model%20Convergence%20and%20Sensitivity%20Analysis.md) - - Here we will share insights on how to evaluate the convergence of your model with varying parameters - - e.g., number of sections defining a cable - - Discuss sensitivity to material properties and other simulation parameters. - ---- - -## [Advanced Topics and Future Work](Advanced%20Topics%20and%20Future%20Work.md) - - Explore potential applications of your method in soft robot design. - - Discuss the ongoing and future research in this field, including real-world experiments and stress validation on cables. - ---- - -## **8. Performance Optimization** - - How to **optimize the computation speed**, potentially using **parallelization**, model **order reduction**, or **recursive algorithms** for DCM. - ---- - -## **9. Conclusion and Q&A** - - Summarize key takeaways from the tutorial. - - Open the floor for questions and discussions. - ---- - -## **10. Practical Hands-On Session (Optional)** - - If feasible, you can provide participants with exercises or hands-on practice to apply the concepts learned. - ---- - -## 11. **Materials:** -- Presentation slides (see GitHub Repo) -- Repo folder tutorials. -- Code examples and simulations on the Repo/example. -- Reference: - - Paper RAL-SoRo : - - Paper (Féderico) : - - Paper (Flavie) : -- Q&A session for participant engagement. -- Feedback : direct and mails - ---- \ No newline at end of file From 27c7515ec25c67d3518c1cd31e571c7afb98acff Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Fri, 7 Jun 2024 11:33:29 +0200 Subject: [PATCH 40/71] Basic review of BaseCosserat --- src/Cosserat/initCosserat.cpp | 5 + src/Cosserat/mapping/BaseCosserat.cpp | 23 +-- src/Cosserat/mapping/BaseCosserat.h | 259 +++++++------------------- src/Cosserat/mapping/BaseCosserat.inl | 195 +++++++++++++++++-- 4 files changed, 262 insertions(+), 220 deletions(-) diff --git a/src/Cosserat/initCosserat.cpp b/src/Cosserat/initCosserat.cpp index dfcadd80..4e7d5b76 100644 --- a/src/Cosserat/initCosserat.cpp +++ b/src/Cosserat/initCosserat.cpp @@ -33,6 +33,8 @@ using sofa::helper::system::PluginManager; #include <cstring> #include <string> +// TODO(dmarchal: 2024/06/07) This is the wrong namespace, it should be "cosserat" +// or sofacosserat if you rename the plugin into SofaCosserat :) namespace sofa::component { @@ -81,6 +83,9 @@ const char* getModuleVersion() const char* getModuleDescription() { + // TODO(dmarchal: 2024/06/07): I think this is not the correct module description... as we are planning + // to use these string to generate the documentation... please correct that and also be much more + // descriptive with multi line comment. return "A dynamic adapter that modulates the DOF repartition of a beam model according to its radius of curvature."; } diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index 3ac6d7bf..37818365 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -34,8 +34,6 @@ template<> BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::build_Xi_hat(const Coord1& strain_i){ se3 Xi; - //msg_info("BaseCosserat")<<" ===========> Build Xi Hat rigid is called "; - Xi[0][1] = -strain_i(2); Xi[0][2] = strain_i[1]; Xi[1][2] = -strain_i[0]; @@ -46,12 +44,9 @@ BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, R Xi[0][3] = 1.0; - //std::cout <<"Before the linear part : "<< Xi <<std::endl; for (unsigned int i=0; i<3; i++) Xi[i][3] += strain_i(i+3); - //std::cout <<"After the linear part : "<< Xi <<std::endl; - // se3 = [ // 0 -screw(3) screw(2) screw(4); // screw(3) 0 -screw(1) screw(5); @@ -66,6 +61,7 @@ BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, R template<> void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(const double & curv_abs_x_n, const Coord1& strain_n, Transform & Trans){ Matrix4 I4; I4.identity(); + //Get the angular part of the Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); SReal theta = k.norm(); // @@ -73,25 +69,17 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(co SE3 g_X_n; se3 Xi_hat_n = build_Xi_hat(strain_n); - if(d_debug.getValue()) - msg_info("BaseCosserat: ")<< "matrix Xi : "<< Xi_hat_n; + msg_info()<< "matrix Xi : "<< Xi_hat_n; if(theta <= std::numeric_limits<double>::epsilon()){ g_X_n = I4 + curv_abs_x_n*Xi_hat_n; }else { -// se3 Xi_hat_n_2 = Xi_hat_n * Xi_hat_n; -// se3 Xi_hat_n_3 = Xi_hat_n_2 * Xi_hat_n; -// SReal costheta = std::cos(theta); -// SReal sintheta = std::cos(theta); -// SReal theta2 = std::pow(theta,2); -// SReal theta3 = theta2 * theta; -// g_X_n = I4 + curv_abs_x_n*Xi_hat_n + ((1.-costheta)/(theta2))*Xi_hat_n_2 +((theta-sintheta)/theta3)*Xi_hat_n_3; double scalar1= (1.0 - std::cos(curv_abs_x_n*theta))/std::pow(theta,2); double scalar2 = (curv_abs_x_n*theta - std::sin(curv_abs_x_n*theta))/std::pow(theta,3); g_X_n = I4 + curv_abs_x_n*Xi_hat_n + scalar1*Xi_hat_n*Xi_hat_n + scalar2*Xi_hat_n*Xi_hat_n*Xi_hat_n ; } - if(d_debug.getValue()) - msg_info("BaseCosserat: ")<< "matrix g_X : "<< g_X_n; + + msg_info()<< "matrix g_X : "<< g_X_n; type::Mat3x3 M; g_X_n.getsub(0,0,M); //get the rotation matrix @@ -106,6 +94,7 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::compute_Tang_Exp(double SReal theta = type::Vec3(strain_i(0), strain_i(1), strain_i(2)).norm(); //Sometimes this is computed over all strain Matrix3 tilde_k = getTildeMatrix(type::Vec3(strain_i(0), strain_i(1), strain_i(2))); + /* Younes @23-11-27 old version @Todo ???? is p the linear deformation? If so, why didn't I just put a zero vector in place of p and the first element of p is equal to 1? @@ -113,13 +102,13 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::compute_Tang_Exp(double Using the new version does not bring any difference in my three reference scenes, but need more investogation #TECHNICAL_DEBT */ + //TODO(dmarchal: 2024/06/07) could the debt by solved ? Matrix3 tilde_q = getTildeMatrix(type::Vec3(strain_i(3), strain_i(4), strain_i(5))); Mat6x6 ad_Xi ; buildAdjoint(tilde_k, tilde_q, ad_Xi); Mat6x6 Id6 = Mat6x6::Identity() ; - // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 if(theta <= std::numeric_limits<double>::epsilon()){ double scalar0 = std::pow(curv_abs_n,2)/2.0; diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 4a665612..205c9230 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -41,8 +41,15 @@ using namespace Eigen; #include <cmath> +// TODO(dmarchal, 2024/06/07): This is polluating the namespace of sofa::components +// plugins should be in their own namespace like +// eg: cosserat::component::mapping namespace sofa::component::mapping { + +// with a private namespace the used named are not polluating the whole sofa::component::mapping +// ones. +namespace { using sofa::defaulttype::SolidTypes ; using sofa::core::objectmodel::BaseContext ; using sofa::type::Matrix3; @@ -51,6 +58,7 @@ using type::Vec3; using type::Vec6; using std::get; using sofa::core::objectmodel::BaseObject; +} /*! * \class BaseCosserat @@ -75,6 +83,9 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject /// Output Model Type typedef TOut Out; + + // TODO(dmarchal:2024/06/07) This very long list of public typedefs looks questionnable + // at least this has to be justified by comment on why these typedefs are public typedef typename In1::Coord Coord1 ; typedef typename In1::Deriv Deriv1 ; typedef typename In1::VecCoord In1VecCoord; @@ -110,17 +121,29 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject typedef typename SolidTypes<SReal>::Transform Transform ; typedef typename type::vector<SReal> List; + typedef typename sofa::type::Matrix4 se3; + typedef typename sofa::type::Matrix4 SE3; + typedef typename Eigen::Matrix4d _SE3; + typedef typename Eigen::Matrix4d _se3; + typedef typename type::Mat<6,6,SReal> Tangent; + typedef typename Eigen::Matrix3d RotMat; + typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; + protected: Data<type::vector<double>> d_curv_abs_section ; Data<type::vector<double>> d_curv_abs_frames ; - Data<bool> d_debug ; + Data<bool> d_debug ; /// Input Models container. New inputs are added through addInputModel(In* ). core::State<In1>* m_fromModel1; + + // TODO(dmarchal): why this maybe_unused on a data field ? [[maybe_unused]] core::State<In2>* m_fromModel2; core::State<Out>* m_toModel; public: + // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this really needed ? + /*===========COSSERAT VECTORS ======================*/ unsigned int m_index_input; OutVecCoord m_vecTransform ; @@ -142,209 +165,41 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject type::vector<Vec6> m_totalBeamForceVectors; type::vector<Mat6x6> m_nodeAdjointVectors; + + // TODO(dmarchal:2024/06/07): explain why these attributes are unused [[maybe_unused]] type::vector<Mat6x6> m_nodeAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_frameAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_node_coAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_frame_coAdjointEtaVectors; - typedef typename sofa::type::Matrix4 se3; - typedef typename sofa::type::Matrix4 SE3; - typedef typename Eigen::Matrix4d _SE3; - typedef typename Eigen::Matrix4d _se3; - typedef typename type::Mat<6,6,SReal> Tangent; - typedef typename Eigen::Matrix3d RotMat; - typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; -protected: - /// Constructor - BaseCosserat() ; - /// Destructor - ~BaseCosserat() override = default; public: - - - /**********************SOFA METHODS**************************/ + /********************** Inhertited from BaseObject **************/ void init() override; - void bwdInit() override; // get the points - void reinit() override; void draw(const core::visual::VisualParams* vparams) override; - - - /**********************COSSERAT METHODS**************************/ - double computeTheta(const double &x, const Mat4x4 &gX){ - double Tr_gx = 0.0; - for (int i = 0; i<4; i++) { - Tr_gx += gX[i][i]; - } - - double theta; - if( x <= std::numeric_limits<double>::epsilon()) theta = 0.0; - else theta = (1.0/x) * std::acos((Tr_gx/2.0) -1); - - return theta; - } - -protected: - - void computeExponentialSE3(const double &x, const Coord1& k, Transform & Trans); - void computeAdjoint(const Transform & frame, Mat6x6 &adjoint); - void compute_coAdjoint(const Transform & frame, Mat6x6 &co_adjoint); - void compute_adjointVec6(const Vec6 & frame, Mat6x6 &adjoint); - - void update_ExponentialSE3(const In1VecCoord & inDeform); - void update_TangExpSE3(const In1VecCoord & inDeform); - void compute_Tang_Exp(double & x, const Coord1& k, Mat6x6 & TgX); - - [[maybe_unused]] type::Vec6 compute_eta(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); - type::Matrix4 computeLogarithm(const double & x, const Mat4x4 &gX); - - - -public: - /**********************OTHER METHODS**************************/ + /************************* BaseCosserat **************************/ + // TODO(dmarchal:2024/06/07), so we have "initialize" and "init" co-existances of both and their + // roles is unclear and generates ambiguities void initialize(); - void print_matrix(const Mat6x6 R){ - for (unsigned int k = 0; k < 6 ; k++) { - for (unsigned int i = 0; i < 6; i++) - printf(" %lf",R[k][i]); - //std::cout<< " " << R[k][i]; - printf("\n"); - } - } - - Matrix3 extract_rotMatrix(const Transform & frame){ - type::Quat q = frame.getOrientation(); - Real R[4][4]; q.buildRotationMatrix(R); - Matrix3 mat; - - for (unsigned int k = 0; k < 3 ; k++) - for (unsigned int i = 0; i < 3; i++) - mat[k][i] = R[k][i]; - return mat; - } - Tangent build_projector(const Transform &T){ - Mat6x6 P; - Real R[4][4]; (T.getOrientation()).buildRotationMatrix(R); - - for (unsigned int i = 0; i < 3; i++) { - for (unsigned int j = 0; j < 3; j++) { - P[i][j+3] = R[i][j]; - P[i+3][j] = R[i][j]; - } - } - // print_matrix(P); - // printf("__________________________\n"); - return P; - } - se3 build_Xi_hat(const Coord1 & strain_i){ - se3 Xi_hat; + // TODO(dmarchal: 2024/06/07), there is a mix of coding style naming convention + // in Sofa we use "CamlCaseStyle" instead of the "python_style" + double computeTheta(const double &x, const Mat4x4 &gX); + void print_matrix(const Mat6x6 R); - Xi_hat[0][1] = -strain_i(2); - Xi_hat[0][2] = strain_i[1]; - Xi_hat[1][2] = -strain_i[0]; + Matrix3 extract_rotMatrix(const Transform & frame); + Tangent build_projector(const Transform &T); + se3 build_Xi_hat(const Coord1 & strain_i); + Matrix3 getTildeMatrix(const type::Vec3 & u); - Xi_hat[1][0] = -Xi_hat(0,1); - Xi_hat[2][0] = -Xi_hat(0,2); - Xi_hat[2][1] = -Xi_hat(1,2); + void buildAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & Adjoint); + void build_coaAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint); - //@TODO: Why this , if q = 0 ???? - Xi_hat[0][3] = 1.0; - return Xi_hat; - } - - Matrix3 getTildeMatrix(const type::Vec3 & u){ - type::Matrix3 tild; - tild[0][1] = -u[2]; - tild[0][2] = u[1]; - tild[1][2] = -u[0]; - - tild[1][0] = -tild[0][1]; - tild[2][0] = -tild[0][2]; - tild[2][1] = -tild[1][2]; - return tild; - } - - void buildAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & Adjoint){ - - Adjoint.clear(); - for (unsigned int i = 0; i < 3; i++) { - for (int j = 0; j < 3; ++j) { - Adjoint [i][j]= A[i][j]; - Adjoint [i+3][j+3]= A[i][j]; - Adjoint [i+3][j]= B[i][j]; - } - } - } - - void build_coaAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint){ - - coAdjoint.clear(); - for (unsigned int i = 0; i < 3; i++) { - for (int j = 0; j < 3; ++j) { - coAdjoint [i][j]= A[i][j]; - coAdjoint [i+3][j+3]= A[i][j]; - coAdjoint [i][j+3]= B[i][j]; - } - } - } - - Matrix4 convertTransformToMatrix4x4(const Transform & T){ - Matrix4 M; M.identity(); - Matrix3 R = extract_rotMatrix(T); - type::Vec3 trans = T.getOrigin(); - - for (unsigned int i = 0; i < 3; i++) { - for (unsigned int j=0; j<3; j++){ - M(i,j) = R[i][j]; - M(i,3) = trans[i]; - } - } - return M; - } - - - Vec6 piecewise_logmap(const _SE3& g_x) { - _SE3 Xi_hat; - - double x = 1.0; - double theta = std::acos(g_x.trace() / 2.0 - 1.0); - - if (theta == 0) { - Xi_hat = 1.0 / x * (g_x - Matrix4d::Identity()); - } else { - double x_theta = x * theta; - double sin_x_theta = std::sin(x_theta); - double cos_x_theta = std::cos(x_theta); - double t3 = 2 * sin_x_theta * cos_x_theta; - double t4 = 1 - 2 * sin_x_theta * sin_x_theta; - double t5 = x_theta * t4; - - /// -// double csc_theta = 1.0/(sin(x * theta/2.0)); -// double sec_theta = 1.0/(cos(x * theta/2.0)); -// double cst = (1.0/8) * (csc_theta*csc_theta*csc_theta) * sec_theta; -// double x_theta = x*theta; -// double cos_2Xtheta = cos(2.0 * x_theta); -// double cos_Xtheta = cos(x_theta); -// double sin_2Xtheta = sin(2.0 *x_theta); -// double sin_Xtheta = sin(x_theta); - /// - - Matrix4d gp2 = g_x * g_x; - Matrix4d gp3 = gp2 * g_x; - - Xi_hat = 1.0 / x * (0.125 * (1.0 / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0)) * std::cos(x_theta / 2.0) * - ((t5 - sin_x_theta) * Matrix4d::Identity() - (x_theta * cos_x_theta + 2 * t5 - sin_x_theta - t3) * g_x + - (2 * x_theta * cos_x_theta + t5 - sin_x_theta - t3) * gp2 - (x_theta * cos_x_theta - sin_x_theta) * gp3)); - } - - Vec6 xci = Vec6(Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), Xi_hat(1, 3), Xi_hat(2, 3)); - //xci << Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), Xi_hat(1, 3), Xi_hat(2, 3); - - return xci; - } + Matrix4 convertTransformToMatrix4x4(const Transform & T); + Vec6 piecewise_logmap(const _SE3& g_x) ; + // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't + // be (re)implemented in a base classe. Eigen::Matrix3d rotationMatrixX(double angle) { Eigen::Matrix3d rotation; rotation << 1, 0, 0, @@ -353,7 +208,8 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject return rotation; } - + // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't + // be (re)implemented in a base classe. Eigen::Matrix3d rotationMatrixY(double angle) { Eigen::Matrix3d rotation; rotation << cos(angle), 0, sin(angle), @@ -362,6 +218,9 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject return rotation; } + // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't + // be (re)implemented in a base classe. + // the type of the data return should also be unified between rotationMatrixX, Y and Z RotMat rotationMatrixZ(double angle) { RotMat rotation; rotation << cos(angle), -sin(angle), 0, @@ -370,8 +229,28 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject return rotation; } +protected: + /// Constructor + BaseCosserat() ; + /// Destructor + ~BaseCosserat() override = default; + void computeExponentialSE3(const double &x, const Coord1& k, Transform & Trans); + // TODO(dmarchal: 2024/06/07): + // - two naming convention + // - unclear the difference between computeAdjoing and buildAdjoint ... is there room for factoring things ? + void computeAdjoint(const Transform & frame, Mat6x6 &adjoint); + void compute_coAdjoint(const Transform & frame, Mat6x6 &co_adjoint); + + void compute_adjointVec6(const Vec6 & frame, Mat6x6 &adjoint); + + void update_ExponentialSE3(const In1VecCoord & inDeform); + void update_TangExpSE3(const In1VecCoord & inDeform); + void compute_Tang_Exp(double & x, const Coord1& k, Mat6x6 & TgX); + + [[maybe_unused]] type::Vec6 compute_eta(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); + type::Matrix4 computeLogarithm(const double & x, const Mat4x4 &gX); }; diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index 2b857bfd..43a1e0d2 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -35,11 +35,16 @@ // To go further => // https://www.mathworks.com/matlabcentral/fileexchange/83038-sorosim/ -namespace sofa::component::mapping { -using sofa::core::objectmodel::BaseContext; -using sofa::helper::AdvancedTimer; -using sofa::helper::WriteAccessor; -using sofa::type::vector; +namespace sofa::component::mapping +{ + +namespace +{ + using sofa::core::objectmodel::BaseContext; + using sofa::helper::AdvancedTimer; + using sofa::helper::WriteAccessor; + using sofa::type::vector; +} template <class TIn1, class TIn2, class TOut> BaseCosserat<TIn1, TIn2, TOut>::BaseCosserat() @@ -63,12 +68,6 @@ void BaseCosserat<TIn1, TIn2, TOut>::init() { const OutVecCoord xfrom = xfromData->getValue(); } -template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::bwdInit() {} - -template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::reinit() {} - template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { @@ -466,11 +465,181 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() { } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::draw( - const core::visual::VisualParams *vparams) { +void BaseCosserat<TIn1, TIn2, TOut>::draw(const core::visual::VisualParams *vparams) +{ + // TODO(dmarchal: 2024/06/07) It is unclear to me why we are overriding a base function + // to enforce it does nothing, if (!vparams->displayFlags().getShowMappings()) if (!d_debug.getValue()) return; } + +template <class TIn1, class TIn2, class TOut> +double BaseCosserat<TIn1, TIn2, TOut>::computeTheta(const double &x, const Mat4x4 &gX){ + double Tr_gx = 0.0; + for (int i = 0; i<4; i++) { + Tr_gx += gX[i][i]; + } + + double theta; + if( x <= std::numeric_limits<double>::epsilon()) theta = 0.0; + else theta = (1.0/x) * std::acos((Tr_gx/2.0) -1); + + return theta; +} + +template <class TIn1, class TIn2, class TOut> +void BaseCosserat<TIn1, TIn2, TOut>::print_matrix(const Mat6x6 R){ + // TODO(dmarchal: 2024/06/07): Remove the use of printf in addition to + // reconsider the implementation of common utility functions in instance method. + for (unsigned int k = 0; k < 6 ; k++) { + for (unsigned int i = 0; i < 6; i++) + printf(" %lf",R[k][i]); + printf("\n"); + } +} + +template <class TIn1, class TIn2, class TOut> +Matrix3 BaseCosserat<TIn1, TIn2, TOut>::extract_rotMatrix(const Transform & frame) +{ + + type::Quat q = frame.getOrientation(); + + // TODO(dmarchal: 2024/06/07) The following code should probably become utility function + // building a 3x3 matix from a quaternion should probably does not need this amount of code. + Real R[4][4]; + q.buildRotationMatrix(R); + Matrix3 mat; + for (unsigned int k = 0; k < 3 ; k++) + for (unsigned int i = 0; i < 3; i++) + mat[k][i] = R[k][i]; + return mat; +} + + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::build_projector(const Transform &T) -> Tangent +{ + Mat6x6 P; + + // TODO(dmarchal: 2024/06/07) The following code should probably become utility function + // building a 3x3 matix from a quaternion should probably does not need this amount of code. + Real R[4][4]; (T.getOrientation()).buildRotationMatrix(R); + for (unsigned int i = 0; i < 3; i++) { + for (unsigned int j = 0; j < 3; j++) { + P[i][j+3] = R[i][j]; + P[i+3][j] = R[i][j]; + } + } + return P; +} + + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::build_Xi_hat(const Coord1 & strain_i) -> se3 +{ + se3 Xi_hat; + + Xi_hat[0][1] = -strain_i(2); + Xi_hat[0][2] = strain_i[1]; + Xi_hat[1][2] = -strain_i[0]; + + Xi_hat[1][0] = -Xi_hat(0,1); + Xi_hat[2][0] = -Xi_hat(0,2); + Xi_hat[2][1] = -Xi_hat(1,2); + + //@TODO: Why this , if q = 0 ???? + Xi_hat[0][3] = 1.0; + return Xi_hat; +} + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::getTildeMatrix(const type::Vec3 & u) -> Matrix3 +{ + type::Matrix3 tild; + tild[0][1] = -u[2]; + tild[0][2] = u[1]; + tild[1][2] = -u[0]; + + tild[1][0] = -tild[0][1]; + tild[2][0] = -tild[0][2]; + tild[2][1] = -tild[1][2]; + return tild; +} + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & Adjoint) -> void +{ + Adjoint.clear(); + for (unsigned int i = 0; i < 3; i++) { + for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j + Adjoint [i][j]= A[i][j]; + Adjoint [i+3][j+3]= A[i][j]; + Adjoint [i+3][j]= B[i][j]; + } + } +} + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::build_coaAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint) -> void +{ + coAdjoint.clear(); + for (unsigned int i = 0; i < 3; i++) { + for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j + coAdjoint [i][j]= A[i][j]; + coAdjoint [i+3][j+3]= A[i][j]; + + // TODO(dmarchal: 2024/06/07) if co-adjoint is juste this single change (the j+3) + coAdjoint [i][j+3]= B[i][j]; + } + } +} + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4(const Transform & T) -> Matrix4 +{ + Matrix4 M; M.identity(); + Matrix3 R = extract_rotMatrix(T); + type::Vec3 trans = T.getOrigin(); + + for (unsigned int i = 0; i < 3; i++) { + for (unsigned int j=0; j<3; j++){ + M(i,j) = R[i][j]; + M(i,3) = trans[i]; + } + } + return M; +} + +template <class TIn1, class TIn2, class TOut> +auto BaseCosserat<TIn1, TIn2, TOut>::piecewise_logmap(const _SE3& g_x) -> Vec6 +{ + _SE3 Xi_hat; + + double x = 1.0; + double theta = std::acos(g_x.trace() / 2.0 - 1.0); + + if (theta == 0) { + Xi_hat = 1.0 / x * (g_x - Matrix4d::Identity()); + } else { + double x_theta = x * theta; + double sin_x_theta = std::sin(x_theta); + double cos_x_theta = std::cos(x_theta); + double t3 = 2 * sin_x_theta * cos_x_theta; + double t4 = 1 - 2 * sin_x_theta * sin_x_theta; + double t5 = x_theta * t4; + + Matrix4d gp2 = g_x * g_x; + Matrix4d gp3 = gp2 * g_x; + + Xi_hat = 1.0 / x * (0.125 * (1.0 / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0)) * std::cos(x_theta / 2.0) * + ((t5 - sin_x_theta) * Matrix4d::Identity() - (x_theta * cos_x_theta + 2 * t5 - sin_x_theta - t3) * g_x + + (2 * x_theta * cos_x_theta + t5 - sin_x_theta - t3) * gp2 - (x_theta * cos_x_theta - sin_x_theta) * gp3)); + } + + Vec6 xci = Vec6(Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), Xi_hat(1, 3), Xi_hat(2, 3)); + return xci; +} + } // namespace sofa::component::mapping From db430ee3a7e6d71d4c03fae90be453b9aba6cf42 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Fri, 7 Jun 2024 15:04:26 +0200 Subject: [PATCH 41/71] Rename print_matrix, build_projector, extract_matrix in CamlCase --- src/Cosserat/mapping/BaseCosserat.h | 10 +++++++--- src/Cosserat/mapping/BaseCosserat.inl | 12 ++++++------ src/Cosserat/mapping/DiscreteCosseratMapping.cpp | 12 ++++++------ src/Cosserat/mapping/DiscreteCosseratMapping.inl | 12 ++++++------ .../mapping/DiscreteDynamicCosseratMapping.inl | 12 ++++++------ 5 files changed, 31 insertions(+), 27 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 205c9230..7a50d422 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -69,6 +69,8 @@ using sofa::core::objectmodel::BaseObject; */ +// TODO(dmarchal: 2024/06/07) This component looks like a mapping but inherit from BaseObject * +// can you clarify why is is not inhering from BaseMapping template <class TIn1, class TIn2, class TOut> class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { @@ -139,6 +141,8 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject // TODO(dmarchal): why this maybe_unused on a data field ? [[maybe_unused]] core::State<In2>* m_fromModel2; + + core::State<Out>* m_toModel; public: @@ -185,10 +189,10 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject // TODO(dmarchal: 2024/06/07), there is a mix of coding style naming convention // in Sofa we use "CamlCaseStyle" instead of the "python_style" double computeTheta(const double &x, const Mat4x4 &gX); - void print_matrix(const Mat6x6 R); + void printMatrix(const Mat6x6 R); - Matrix3 extract_rotMatrix(const Transform & frame); - Tangent build_projector(const Transform &T); + Matrix3 extractRotMatrix(const Transform & frame); + Tangent buildProjector(const Transform &T); se3 build_Xi_hat(const Coord1 & strain_i); Matrix3 getTildeMatrix(const type::Vec3 & u); diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index 43a1e0d2..a977bf3b 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -177,7 +177,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3( template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, Tangent &adjoint) { - Matrix3 R = extract_rotMatrix(frame); + Matrix3 R = extractRotMatrix(frame); type::Vec3 u = frame.getOrigin(); Matrix3 tilde_u = getTildeMatrix(u); Matrix3 tilde_u_R = tilde_u * R; @@ -187,7 +187,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::compute_coAdjoint(const Transform &frame, Mat6x6 &co_adjoint) { - Matrix3 R = extract_rotMatrix(frame); + Matrix3 R = extractRotMatrix(frame); type::Vec3 u = frame.getOrigin(); Matrix3 tilde_u = getTildeMatrix(u); Matrix3 tilde_u_R = tilde_u * R; @@ -490,7 +490,7 @@ double BaseCosserat<TIn1, TIn2, TOut>::computeTheta(const double &x, const Mat4x } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::print_matrix(const Mat6x6 R){ +void BaseCosserat<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R){ // TODO(dmarchal: 2024/06/07): Remove the use of printf in addition to // reconsider the implementation of common utility functions in instance method. for (unsigned int k = 0; k < 6 ; k++) { @@ -501,7 +501,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::print_matrix(const Mat6x6 R){ } template <class TIn1, class TIn2, class TOut> -Matrix3 BaseCosserat<TIn1, TIn2, TOut>::extract_rotMatrix(const Transform & frame) +Matrix3 BaseCosserat<TIn1, TIn2, TOut>::extractRotMatrix(const Transform & frame) { type::Quat q = frame.getOrientation(); @@ -519,7 +519,7 @@ Matrix3 BaseCosserat<TIn1, TIn2, TOut>::extract_rotMatrix(const Transform & fram template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::build_projector(const Transform &T) -> Tangent +auto BaseCosserat<TIn1, TIn2, TOut>::buildProjector(const Transform &T) -> Tangent { Mat6x6 P; @@ -600,7 +600,7 @@ template <class TIn1, class TIn2, class TOut> auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4(const Transform & T) -> Matrix4 { Matrix4 M; M.identity(); - Matrix3 R = extract_rotMatrix(T); + Matrix3 R = extractRotMatrix(T); type::Vec3 trans = T.getOrigin(); for (unsigned int i = 0; i < 3; i++) { diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index d1d19526..007e4053 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -66,7 +66,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( //Apply the local transform i.e. from SOFA's frame to Cosserat's frame const In2VecCoord& xfrom2Data = m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()).inversed(); - Mat6x6 P = this->build_projector(TInverse); + Mat6x6 P = this->buildProjector(TInverse); type::Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame m_nodesVelocityVectors.push_back(baseLocalVelocity); if(d_debug.getValue()) @@ -102,7 +102,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( Vec6 eta_frame_i = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * frame_Xi_dot ); // eta auto T = Transform(out[i].getCenter(), out[i].getOrientation()); - Tangent Proj = this->build_projector(T); + Tangent Proj = this->buildProjector(T); out_vel[i] = Proj * eta_frame_i; if(d_debug.getValue()) @@ -144,7 +144,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( for(unsigned j = 0; j < 6; j++) vec[j] = in[var][j]; //Convert input from global frame(SOFA) to local frame Transform _T = Transform(frame[var].getCenter(),frame[var].getOrientation()); - Mat6x6 P_trans =(this->build_projector(_T)); P_trans.transpose(); + Mat6x6 P_trans =(this->buildProjector(_T)); P_trans.transpose(); type::Vec6 local_F = P_trans * vec; local_F_Vec.push_back(local_F); } @@ -192,7 +192,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( } Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); - Mat6x6 M = this->build_projector(frame0); + Mat6x6 M = this->buildProjector(frame0); out2[baseIndex] += M * F_tot; if(d_debug.getValue()){ @@ -267,7 +267,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( int indexBeam = m_indicesVectors[childIndex]; Transform _T = Transform(frame[childIndex].getCenter(),frame[childIndex].getOrientation()); - Tangent P_trans =(this->build_projector(_T)); + Tangent P_trans =(this->buildProjector(_T)); P_trans.transpose(); Mat6x6 coAdjoint; @@ -359,7 +359,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( } Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); - Mat6x6 M = this->build_projector(frame0); + Mat6x6 M = this->buildProjector(frame0); Vec6 base_force = M * CumulativeF; o2.addCol(d_baseIndex.getValue(), base_force); diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index a75136fc..e4875b05 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -270,7 +270,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()) .inversed(); - Mat6x6 P = this->build_projector(TInverse); + Mat6x6 P = this->buildProjector(TInverse); type::Vec6 baseLocalVelocity = P * baseVelocity; // This is the base velocity in Locale frame m_nodesVelocityVectors.push_back(baseLocalVelocity); @@ -314,7 +314,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( m_framesTangExpVectors[i] * frame_Xi_dot); // eta auto T = Transform(out[i].getCenter(), out[i].getOrientation()); - Mat6x6 Proj = this->build_projector(T); + Mat6x6 Proj = this->buildProjector(T); out_vel[i] = Proj * eta_frame_i; @@ -364,7 +364,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( // Convert input from global frame(SOFA) to local frame Transform _T = Transform(frame[var].getCenter(), frame[var].getOrientation()); - Mat6x6 P_trans = (this->build_projector(_T)); + Mat6x6 P_trans = (this->buildProjector(_T)); P_trans.transpose(); type::Vec6 local_F = P_trans * vec; local_F_Vec.push_back(local_F); @@ -421,7 +421,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( } Transform frame0 = Transform(frame[0].getCenter(), frame[0].getOrientation()); - Mat6x6 M = this->build_projector(frame0); + Mat6x6 M = this->buildProjector(frame0); out2[baseIndex] += M * F_tot; if (d_debug.getValue()) { @@ -508,7 +508,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( Transform _T = Transform(frame[childIndex].getCenter(), frame[childIndex].getOrientation()); - Mat6x6 P_trans = (this->build_projector(_T)); + Mat6x6 P_trans = (this->buildProjector(_T)); P_trans.transpose(); Mat6x6 coAdjoint; @@ -608,7 +608,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( Transform frame0 = Transform(frame[0].getCenter(), frame[0].getOrientation()); - Mat6x6 M = this->build_projector(frame0); + Mat6x6 M = this->buildProjector(frame0); Vec6 base_force = M * CumulativeF; o2.addCol(d_baseIndex.getValue(), base_force); diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index dbdcd3aa..debdd561 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -197,7 +197,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( //Apply the local transform i.e from SOFA frame to Frederico frame const In2VecCoord& xfrom2Data = m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); Transform Tinverse = Transform(xfrom2Data[0].getCenter(),xfrom2Data[0].getOrientation()).inversed(); - Mat6x6 P = this->build_projector(Tinverse); + Mat6x6 P = this->buildProjector(Tinverse); m_nodeAdjointVectors.clear(); type::Vec6 baseLocalVelocity = P * baseVelocity; @@ -244,7 +244,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( //Convert from Federico node to Sofa node Transform _T = Transform(out[i].getCenter(),out[i].getOrientation()); - Mat6x6 _P = this->build_projector(_T); + Mat6x6 _P = this->buildProjector(_T); //std::cout<< "Eta local : "<< eta << std::endl; outVel[i] = _P * etaFrame; @@ -348,7 +348,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( //Convert input from global frame(SOFA) to local frame Transform _T = Transform(frame[var].getCenter(),frame[var].getOrientation()); - Mat6x6 P_trans =(this->build_projector(_T)); P_trans.transpose(); + Mat6x6 P_trans =(this->buildProjector(_T)); P_trans.transpose(); type::Vec6 local_F = P_trans * vec; local_F_Vec.push_back(local_F); } @@ -393,7 +393,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( out1[m_indicesVectors[s]-1] += f; } Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); - Mat6x6 M = this->build_projector(frame0); + Mat6x6 M = this->buildProjector(frame0); out2[0] += M * F_tot; if(d_debug.getValue()){ @@ -473,7 +473,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::applyJT( int indexBeam = m_indicesVectors[childIndex]; Transform _T = Transform(frame[childIndex].getCenter(),frame[childIndex].getOrientation()); - Mat6x6 P_trans =(this->build_projector(_T)); + Mat6x6 P_trans =(this->buildProjector(_T)); P_trans.transpose(); Mat6x6 coAdjoint; @@ -576,7 +576,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::applyJT( } Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); - Mat6x6 M = this->build_projector(frame0); + Mat6x6 M = this->buildProjector(frame0); Vec6 base_force = M * CumulativeF; o2.addCol(0, base_force); From 25a113785b715bd33536c1b80fd2cbcbbee685dd Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Fri, 7 Jun 2024 15:25:57 +0200 Subject: [PATCH 42/71] Rename "python_names" into CamlCase. --- src/Cosserat/mapping/BaseCosserat.cpp | 6 +-- src/Cosserat/mapping/BaseCosserat.h | 47 ++++++++--------- src/Cosserat/mapping/BaseCosserat.inl | 50 ++++++------------- .../mapping/DiscreteCosseratMapping.cpp | 10 ++-- .../mapping/DiscreteCosseratMapping.inl | 12 ++--- .../DiscreteDynamicCosseratMapping.inl | 32 +++--------- 6 files changed, 58 insertions(+), 99 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index 37818365..bef42c08 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -31,7 +31,7 @@ namespace sofa::component::mapping using namespace sofa::defaulttype; template<> -BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::build_Xi_hat(const Coord1& strain_i){ +BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const Coord1& strain_i){ se3 Xi; Xi[0][1] = -strain_i(2); @@ -67,7 +67,7 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(co SReal theta = k.norm(); // SE3 g_X_n; - se3 Xi_hat_n = build_Xi_hat(strain_n); + se3 Xi_hat_n = buildXiHat(strain_n); msg_info()<< "matrix Xi : "<< Xi_hat_n; @@ -90,7 +90,7 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(co } template<> -void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::compute_Tang_Exp(double & curv_abs_n, const Coord1 & strain_i, Mat6x6 & TgX){ +void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp(double & curv_abs_n, const Coord1 & strain_i, Mat6x6 & TgX){ SReal theta = type::Vec3(strain_i(0), strain_i(1), strain_i(2)).norm(); //Sometimes this is computed over all strain Matrix3 tilde_k = getTildeMatrix(type::Vec3(strain_i(0), strain_i(1), strain_i(2))); diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 7a50d422..74f481df 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -131,20 +131,6 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject typedef typename Eigen::Matrix3d RotMat; typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; -protected: - Data<type::vector<double>> d_curv_abs_section ; - Data<type::vector<double>> d_curv_abs_frames ; - Data<bool> d_debug ; - - /// Input Models container. New inputs are added through addInputModel(In* ). - core::State<In1>* m_fromModel1; - - // TODO(dmarchal): why this maybe_unused on a data field ? - [[maybe_unused]] core::State<In2>* m_fromModel2; - - - core::State<Out>* m_toModel; - public: // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this really needed ? @@ -186,21 +172,19 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject // roles is unclear and generates ambiguities void initialize(); - // TODO(dmarchal: 2024/06/07), there is a mix of coding style naming convention - // in Sofa we use "CamlCaseStyle" instead of the "python_style" double computeTheta(const double &x, const Mat4x4 &gX); void printMatrix(const Mat6x6 R); Matrix3 extractRotMatrix(const Transform & frame); Tangent buildProjector(const Transform &T); - se3 build_Xi_hat(const Coord1 & strain_i); + se3 buildXiHat(const Coord1 & strain_i); Matrix3 getTildeMatrix(const type::Vec3 & u); void buildAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & Adjoint); - void build_coaAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint); + void buildCoAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint); Matrix4 convertTransformToMatrix4x4(const Transform & T); - Vec6 piecewise_logmap(const _SE3& g_x) ; + Vec6 piecewiseLogmap(const _SE3& g_x) ; // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't // be (re)implemented in a base classe. @@ -233,6 +217,19 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject return rotation; } +protected: + Data<type::vector<double>> d_curv_abs_section ; + Data<type::vector<double>> d_curv_abs_frames ; + Data<bool> d_debug ; + + /// Input Models container. New inputs are added through addInputModel(In* ). + core::State<In1>* m_fromModel1; + + // TODO(dmarchal): why this maybe_unused on a data field ? + [[maybe_unused]] core::State<In2>* m_fromModel2; + + core::State<Out>* m_toModel; + protected: /// Constructor BaseCosserat() ; @@ -245,15 +242,15 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject // - two naming convention // - unclear the difference between computeAdjoing and buildAdjoint ... is there room for factoring things ? void computeAdjoint(const Transform & frame, Mat6x6 &adjoint); - void compute_coAdjoint(const Transform & frame, Mat6x6 &co_adjoint); + void computeAdjoint(const Vec6 & frame, Mat6x6 &adjoint); - void compute_adjointVec6(const Vec6 & frame, Mat6x6 &adjoint); + void computeCoAdjoint(const Transform & frame, Mat6x6 &coAdjoint); - void update_ExponentialSE3(const In1VecCoord & inDeform); - void update_TangExpSE3(const In1VecCoord & inDeform); - void compute_Tang_Exp(double & x, const Coord1& k, Mat6x6 & TgX); + void updateExponentialSE3(const In1VecCoord & inDeform); + void updateTangExpSE3(const In1VecCoord & inDeform); + void computeTangExp(double & x, const Coord1& k, Mat6x6 & TgX); - [[maybe_unused]] type::Vec6 compute_eta(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); + [[maybe_unused]] type::Vec6 computeETA(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); type::Matrix4 computeLogarithm(const double & x, const Mat4x4 &gX); }; diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index a977bf3b..b5c2abd6 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -78,7 +78,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3( SReal theta = k.norm(); // SE3 _g_X; - se3 Xi_hat_n = build_Xi_hat(strain_n); + se3 Xi_hat_n = buildXiHat(strain_n); if (d_debug.getValue()) msg_info("BaseCosserat: ") << "matrix Xi : " << Xi_hat_n; @@ -107,7 +107,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3( // Fill exponential vectors template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::update_ExponentialSE3( +void BaseCosserat<TIn1, TIn2, TOut>::updateExponentialSE3( const In1VecCoord &inDeform) { // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = // d_curv_abs_section; @@ -185,17 +185,17 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::compute_coAdjoint(const Transform &frame, +void BaseCosserat<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, Mat6x6 &co_adjoint) { Matrix3 R = extractRotMatrix(frame); type::Vec3 u = frame.getOrigin(); Matrix3 tilde_u = getTildeMatrix(u); Matrix3 tilde_u_R = tilde_u * R; - build_coaAdjoint(R, tilde_u_R, co_adjoint); + buildCoAdjoint(R, tilde_u_R, co_adjoint); } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::compute_adjointVec6(const Vec6 &eta, +void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, Mat6x6 &adjoint) { Matrix3 tildeMat = getTildeMatrix(type::Vec3(eta[0], eta[1], eta[2])); adjoint.setsub(0, 0, tildeMat); @@ -238,30 +238,8 @@ Matrix4 BaseCosserat<TIn1, TIn2, TOut>::computeLogarithm(const double &x, return log_gX; } -// template<class In1VecCoord, class Mat6x6> -// void computeViolation(In1VecCoord& inDeform, const helper::vector<double> -// m_framesLengthVectors, const -// size_t sz, std::function<double(int i, int j)> f) -//{ - -// for (std::size_t i = 0; i < sz; i++) { -// Mat6x6 temp ; - -// type::Vec3 k = inDeform[m_indicesVectors[i]-1]; -// double x = m_framesLengthVectors[i]; -// compute_Tang_Exp(x,k,temp) ; -// m_framesTangExpVectors.push_back(temp); - -//// if (d_debug.getValue()){ -//// printf("__________________________________________\n"); -//// std::cout << "x :"<< x << "; k :"<< k << std::endl; -//// std::cout<< "m_framesTangExpVectors :"<< -///m_framesTangExpVectors[i] << std::endl; / } -// } -//} - template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3( +void BaseCosserat<TIn1, TIn2, TOut>::updateTangExpSE3( const In1VecCoord &inDeform) { // Curv abscissa of nodes and frames @@ -278,7 +256,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3( Coord1 strain_frame_i = inDeform[m_indicesVectors[i] - 1]; double curv_abs_x_i = m_framesLengthVectors[i]; - compute_Tang_Exp(curv_abs_x_i, strain_frame_i, temp); + computeTangExp(curv_abs_x_i, strain_frame_i, temp); m_framesTangExpVectors.push_back(temp); @@ -302,7 +280,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3( double x = m_BeamLengthVectors[j - 1]; Tangent temp; temp.clear(); - compute_Tang_Exp(x, strain_node_i, temp); + computeTangExp(x, strain_node_i, temp); m_nodesTangExpVectors.push_back(temp); } if (d_debug.getValue()) { @@ -312,7 +290,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::update_TangExpSE3( } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::compute_Tang_Exp(double &curv_abs_n, +void BaseCosserat<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, const Coord1 &strain_i, Mat6x6 &TgX) { @@ -363,7 +341,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::compute_Tang_Exp(double &curv_abs_n, template <class TIn1, class TIn2, class TOut> [[maybe_unused]] type::Vec6 -BaseCosserat<TIn1, TIn2, TOut>::compute_eta(const type::Vec6 &baseEta, +BaseCosserat<TIn1, TIn2, TOut>::computeETA(const type::Vec6 &baseEta, const In1VecDeriv &k_dot, const double abs_input) { @@ -398,7 +376,7 @@ BaseCosserat<TIn1, TIn2, TOut>::compute_eta(const type::Vec6 &baseEta, computeExponentialSE3(_diff0, x1from[m_index_input], out_Trans); computeAdjoint(out_Trans, Adjoint); - compute_Tang_Exp(diff0, x1from[m_index_input], Tg); + computeTangExp(diff0, x1from[m_index_input], Tg); return Adjoint * (baseEta + Tg * Xi_dot); } @@ -537,7 +515,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::buildProjector(const Transform &T) -> Tange template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::build_Xi_hat(const Coord1 & strain_i) -> se3 +auto BaseCosserat<TIn1, TIn2, TOut>::buildXiHat(const Coord1 & strain_i) -> se3 { se3 Xi_hat; @@ -582,7 +560,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, const Matrix } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::build_coaAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint) -> void +auto BaseCosserat<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint) -> void { coAdjoint.clear(); for (unsigned int i = 0; i < 3; i++) { @@ -613,7 +591,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4(const Transform } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::piecewise_logmap(const _SE3& g_x) -> Vec6 +auto BaseCosserat<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3& g_x) -> Vec6 { _SE3 Xi_hat; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index 007e4053..b7666255 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -53,7 +53,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); //Strains // Compute the tangent Exponential SE3 vectors - this->update_TangExpSE3(inDeform); + this->updateTangExpSE3(inDeform); //Get base velocity as input this is also called eta m_nodesVelocityVectors.clear(); @@ -165,7 +165,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( for (auto s = sz ; s-- ; ) { Tangent coAdjoint; - this->compute_coAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + this->computeCoAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; Mat6x6 temp = m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); @@ -174,7 +174,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( if(index != m_indicesVectors[s]){ index--; //bring F_tot to the reference of the new beam - this->compute_coAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply F_tot = coAdjoint * F_tot; Mat6x6 temp = m_nodesTangExpVectors[index]; temp.transpose(); @@ -271,7 +271,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( P_trans.transpose(); Mat6x6 coAdjoint; - this->compute_coAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + this->computeCoAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Tangent temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); @@ -347,7 +347,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( { //cumulate on beam frame Mat6x6 coAdjoint; - this->compute_coAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply CumulativeF = coAdjoint * CumulativeF; // transfer to strain space (local coordinates) Mat6x6 temp = m_nodesTangExpVectors[i-1]; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index e4875b05..c4b8b679 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -143,7 +143,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( // Here we update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors // Which are the homogeneous matrices of the frames and the nodes in local // coordinate. - this->update_ExponentialSE3(in1); + this->updateExponentialSE3(in1); /* Apply the transformation to go from cossserat to SOFA frame*/ Transform frame0 = Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); @@ -254,7 +254,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( m_fromModel1->read(core::ConstVecCoordId::position()) ->getValue(); // Strains // Compute the tangent Exponential SE3 vectors - this->update_TangExpSE3(inDeform); + this->updateTangExpSE3(inDeform); // Get base velocity as input this is also called eta m_nodesVelocityVectors.clear(); @@ -388,7 +388,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( for (auto s = sz; s--;) { Mat6x6 coAdjoint; - this->compute_coAdjoint( + this->computeCoAdjoint( m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; @@ -401,7 +401,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( if (index != m_indicesVectors[s]) { index--; // bring F_tot to the reference of the new beam - this->compute_coAdjoint( + this->computeCoAdjoint( m_nodesExponentialSE3Vectors[index], coAdjoint); // m_nodesExponentialSE3Vectors computed in apply F_tot = coAdjoint * F_tot; @@ -512,7 +512,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( P_trans.transpose(); Mat6x6 coAdjoint; - this->compute_coAdjoint( + this->computeCoAdjoint( m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] @@ -592,7 +592,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( while (i > 0) { // cumulate on beam frame Mat6x6 coAdjoint; - this->compute_coAdjoint( + this->computeCoAdjoint( m_nodesExponentialSE3Vectors[i - 1], coAdjoint); // m_nodesExponentialSE3Vectors computed in apply CumulativeF = coAdjoint * CumulativeF; diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index debdd561..216c9454 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -139,7 +139,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::apply( out.resize(sz); //update the Exponential Matrices according to new deformation - this->update_ExponentialSE3(in1); // ==> update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors + this->updateExponentialSE3(in1); Transform frame0 = Transform(In2::getCPos(in2[0]),In2::getCRot(in2[0])); for(unsigned int i=0; i<sz; i++){ @@ -183,7 +183,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( // Compute the tangent Exponential SE3 vectors const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); - this->update_TangExpSE3(inDeform); + this->updateTangExpSE3(inDeform); //Get base velocity as input this is also called eta m_nodesVelocityVectors.clear(); @@ -266,54 +266,41 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::computeJ_Jdot_i(const Mat Mat6x3 Si_dot; Mat6x6 adj_eta; //to be computed - //std::cout << "indice vector : "<< this->m_indicesVectors <<" vecId :"<< this->m_indicesVectors[frameId] << std::endl; - //std::cout << "this->m_framesTangExpVectors[frameId] :"<< this->m_framesTangExpVectors[frameId] << std::endl; - //std::cout << "m_nodesTangExpVectors[frameId] :"<< this->m_nodesTangExpVectors << std::endl; bool reachNode = false; for (unsigned int i = 1; i < sz; i++) { M = Adjoint; unsigned int u = m_indicesVectors[frameId]; - //std::cout << "frame : "<< frameId << " ==> section :" << i << " ==> u :"<< u << std::endl; if(i < u ){ for (int j = u; j>0; j--) { M = M * m_nodeAdjointVectors[j] ; } - //std::cout << "this->m_nodesTangExpVectors[u] : "<< this->m_nodesTangExpVectors[u]<< std::endl; Mat6x6 temp = M * m_nodesTangExpVectors[u]; Si = temp * m_matrixBi; J_i.push_back(Si); Vec6 etaNode = m_nodesVelocityVectors[i]; - this->compute_adjointVec6(etaNode, adj_eta); + this->computeAdjoint(etaNode, adj_eta); Si_dot = temp * adj_eta * m_matrixBi; J_dot_i.push_back(Si_dot); - //std::cout << "K1 Si : "<< Si << std::endl; }else{ if(!reachNode){ Mat6x6 temp = M * m_framesTangExpVectors[frameId] ; Si = temp * m_matrixBi; J_i.push_back(Si); - this->compute_adjointVec6(etaFrame, adj_eta); + this->computeAdjoint(etaFrame, adj_eta); Si_dot = temp * adj_eta * m_matrixBi; J_dot_i.push_back(Si_dot); reachNode = true; - //std::cout << "K2 Si : "<< Si << std::endl; }else { Si.clear(); J_i.push_back(Si); Si_dot.clear(); J_dot_i.push_back(Si); - //std::cout << "K3 Si : "<< Si << std::endl; } } } - // printf("J_%d:\n",frameId); - for (unsigned int k=0; k<J_i.size(); k++) { - std::cout << J_i[k] << std::endl; - } - printf("_____________________________________\n"); } template <class TIn1, class TIn2, class TOut> @@ -331,8 +318,6 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( In2VecDeriv& out2 = *dataVecOut2Force[0]->beginEdit(); //Maybe need, in case the apply funcion is not call this must be call before - //update_ExponentialSE3(in1); - const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); @@ -341,7 +326,6 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( out1.resize(x1from.size()); //convert the input from Deriv type to vec6 type, for the purpose of the matrix vector multiplication - // std::cout<< "Size of frames :"<< in.size()<< std::endl; for (size_t var = 0; var < in.size(); ++var) { type::Vec6 vec; for(unsigned j = 0; j < 6; j++) vec[j] = in[var][j]; @@ -368,7 +352,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( for (unsigned int s = sz ; s-- ; ) { Mat6x6 coAdjoint; // - this->compute_coAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + this->computeCoAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; Mat6x6 temp = m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); @@ -377,7 +361,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( if(index!=m_indicesVectors[s]){ // TODO to be replaced by while index--; //bring F_tot to the reference of the new beam - this->compute_coAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply F_tot = coAdjoint * F_tot; Mat6x6 temp = m_nodesTangExpVectors[index]; temp.transpose(); @@ -477,7 +461,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::applyJT( P_trans.transpose(); Mat6x6 coAdjoint; - this->compute_coAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + this->computeCoAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); @@ -563,7 +547,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::applyJT( { //cumulate on beam frame Mat6x6 coAdjoint; - this->compute_coAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply CumulativeF = coAdjoint * CumulativeF; // transfer to strain space (local coordinates) Mat6x6 temp = m_nodesTangExpVectors[i-1]; From 3a9a50ca06a462382c6108e1cd8fa1d4b9ddb3e3 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Sun, 9 Jun 2024 15:21:55 +0200 Subject: [PATCH 43/71] Rename the cosserat/config.h.in file to cosserat/initCosserat.h.in - cosserat/config.h.in -> cosserat/initCosserat.h.in --- CMakeLists.txt | 2 +- git | 0 log | 0 src/Cosserat/config.h.in | 55 ---------- src/Cosserat/initCosserat.cpp | 140 ++++++++++++-------------- src/Cosserat/initCosserat.h.in | 54 ++++++++++ src/Cosserat/mapping/BaseCosserat.h | 13 ++- src/Cosserat/mapping/BaseCosserat.inl | 25 ++--- 8 files changed, 141 insertions(+), 148 deletions(-) delete mode 100644 git delete mode 100644 log delete mode 100644 src/Cosserat/config.h.in create mode 100644 src/Cosserat/initCosserat.h.in diff --git a/CMakeLists.txt b/CMakeLists.txt index d14d9e80..7abab4e1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,7 +20,7 @@ endif() set(SRC_ROOT_DIR src/${PROJECT_NAME}) set(HEADER_FILES - ${SRC_ROOT_DIR}/config.h.in + ${SRC_ROOT_DIR}/initCosserat.h.in ${SRC_ROOT_DIR}/mapping/BaseCosserat.h ${SRC_ROOT_DIR}/mapping/BaseCosserat.inl ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.h diff --git a/git b/git deleted file mode 100644 index e69de29b..00000000 diff --git a/log b/log deleted file mode 100644 index e69de29b..00000000 diff --git a/src/Cosserat/config.h.in b/src/Cosserat/config.h.in deleted file mode 100644 index e1b413ce..00000000 --- a/src/Cosserat/config.h.in +++ /dev/null @@ -1,55 +0,0 @@ -/****************************************************************************** -* SOFA, Simulation Open-Framework Architecture * -* (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * -* * -* This library is free software; you can redistribute it and/or modify it * -* under the terms of the GNU Lesser General Public License as published by * -* the Free Software Foundation; either version 2.1 of the License, or (at * -* your option) any later version. * -* * -* This library is distributed in the hope that it will be useful, but WITHOUT * -* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * -* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * -* for more details. * -* * -* You should have received a copy of the GNU Lesser General Public License * -* along with this library; if not, write to the Free Software Foundation, * -* Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * -******************************************************************************* -* Plugin Cosserat v1.0 * -* * -* This plugin is also distributed under the GNU LGPL (Lesser General * -* Public License) license with the same conditions than SOFA. * -* * -* Contributors: Defrost team (INRIA, University of Lille, CNRS, * -* Ecole Centrale de Lille) * -* * -* Contact information: https://project.inria.fr/softrobot/contact/ * -* * -******************************************************************************/ -#ifndef SOFA_COSSERAT_INIT_H -#define SOFA_COSSERAT_INIT_H - -#include <sofa/config.h> - -#define COSSERAT_VERSION @PROJECT_VERSION@ - -#ifdef SOFA_BUILD_COSSERAT -#define SOFA_TARGET @PROJECT_NAME@ -#define SOFA_COSSERAT_API SOFA_EXPORT_DYNAMIC_LIBRARY -#else -# define SOFA_COSSERAT_API SOFA_IMPORT_DYNAMIC_LIBRARY -#endif - - -/** \mainpage - This is the plugin for the Discret Cosserat Plugin -*/ - -namespace cosserat -{ - constexpr const char* MODULE_NAME = "@PROJECT_NAME@"; - constexpr const char* MODULE_VERSION = "@PROJECT_VERSION@"; -} - -#endif /* SOFA_COSSERAT_INIT_H */ diff --git a/src/Cosserat/initCosserat.cpp b/src/Cosserat/initCosserat.cpp index 4e7d5b76..d311946b 100644 --- a/src/Cosserat/initCosserat.cpp +++ b/src/Cosserat/initCosserat.cpp @@ -1,30 +1,30 @@ /****************************************************************************** -* SOFA, Simulation Open-Framework Architecture, version 1.0 beta 4 * -* (c) 2006-2009 MGH, INRIA, USTL, UJF, CNRS * -* * -* This program is free software; you can redistribute it and/or modify it * -* under the terms of the GNU General Public License as published by the Free * -* Software Foundation; either version 2 of the License, or (at your option) * -* any later version. * -* * -* This program is distributed in the hope that it will be useful, but WITHOUT * -* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * -* FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for * -* more details. * -* * -* You should have received a copy of the GNU General Public License along * -* with this program; if not, write to the Free Software Foundation, Inc., 51 * -* Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. * -******************************************************************************* -* SOFA :: Applications * -* * -* Authors: M. Adam, J. Allard, B. Andre, P-J. Bensoussan, S. Cotin, C. Duriez,* -* H. Delingette, F. Falipou, F. Faure, S. Fonteneau, L. Heigeas, C. Mendoza, * -* M. Nesme, P. Neumann, J-P. de la Plata Alcade, F. Poyer and F. Roy * -* * -* Contact information: contact@sofa-framework.org * -******************************************************************************/ -#include <Cosserat/config.h> + * SOFA, Simulation Open-Framework Architecture, version 1.0 beta 4 * + * (c) 2006-2009 MGH, INRIA, USTL, UJF, CNRS * + * * + * This program is free software; you can redistribute it and/or modify it * + * under the terms of the GNU General Public License as published by the Free * + * Software Foundation; either version 2 of the License, or (at your option) * + * any later version. * + * * + * This program is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for * + * more details. * + * * + * You should have received a copy of the GNU General Public License along * + * with this program; if not, write to the Free Software Foundation, Inc., 51 * + * Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. * + ******************************************************************************* + * SOFA :: Applications * + * * + * Authors: M. Adam, J. Allard, B. Andre, P-J. Bensoussan, S. Cotin, C. Duriez,* + * H. Delingette, F. Falipou, F. Faure, S. Fonteneau, L. Heigeas, C. Mendoza, * + * M. Nesme, P. Neumann, J-P. de la Plata Alcade, F. Poyer and F. Roy * + * * + * Contact information: contact@sofa-framework.org * + ******************************************************************************/ +#include <Cosserat/initCosserat.h> #include <sofa/core/ObjectFactory.h> #include <sofa/helper/system/PluginManager.h> @@ -33,67 +33,59 @@ using sofa::helper::system::PluginManager; #include <cstring> #include <string> -// TODO(dmarchal: 2024/06/07) This is the wrong namespace, it should be "cosserat" -// or sofacosserat if you rename the plugin into SofaCosserat :) -namespace sofa::component -{ +// TODO(dmarchal: 2024/06/07) This is the wrong namespace, it should be +// "cosserat" or sofacosserat if you rename the plugin into SofaCosserat :) +namespace cosserat { extern "C" { SOFA_COSSERAT_API void initExternalModule(); -SOFA_COSSERAT_API const char* getModuleLicense(); -SOFA_COSSERAT_API const char* getModuleName(); -SOFA_COSSERAT_API const char* getModuleVersion(); -SOFA_COSSERAT_API const char* getModuleDescription(); -SOFA_COSSERAT_API const char* getModuleComponentList(); +SOFA_COSSERAT_API const char *getModuleLicense(); +SOFA_COSSERAT_API const char *getModuleName(); +SOFA_COSSERAT_API const char *getModuleVersion(); +SOFA_COSSERAT_API const char *getModuleDescription(); +SOFA_COSSERAT_API const char *getModuleComponentList(); } -//Here are just several convenient functions to help user to know what contains the plugin +// Here are just several convenient functions to help user to know what contains +// the plugin + +void initExternalModule() { + static bool first = true; + if (first) { + first = false; + } + // Automatically load the STLIB plugin if available. + if (!PluginManager::getInstance().findPlugin("STLIB").empty()) { + PluginManager::getInstance().loadPlugin("STLIB"); + } -void initExternalModule() -{ - static bool first = true; - if (first) - { - first = false; - } - // Automatically load the STLIB plugin if available. - if( !PluginManager::getInstance().findPlugin("STLIB").empty() ) - { - PluginManager::getInstance().loadPlugin("STLIB") ; - } - #ifdef SOFTROBOTS_PYTHON - PythonEnvironment::addPythonModulePathsForPluginsByName("Cosserat"); + PythonEnvironment::addPythonModulePathsForPluginsByName("Cosserat"); #endif } -const char* getModuleLicense() -{ - return "LGPL"; -} +const char *getModuleLicense() { return "LGPL"; } -const char* getModuleName() -{ - return cosserat::MODULE_NAME; -} +const char *getModuleName() { return cosserat::MODULE_NAME; } -const char* getModuleVersion() -{ - return cosserat::MODULE_VERSION; -} +const char *getModuleVersion() { return cosserat::MODULE_VERSION; } -const char* getModuleDescription() -{ - // TODO(dmarchal: 2024/06/07): I think this is not the correct module description... as we are planning - // to use these string to generate the documentation... please correct that and also be much more - // descriptive with multi line comment. - return "A dynamic adapter that modulates the DOF repartition of a beam model according to its radius of curvature."; +const char *getModuleDescription() { + static std::string classes = + sofa::core::ObjectFactory::getInstance()->listClassesFromTarget( + cosserat::MODULE_NAME); + // TODO(dmarchal: 2024/06/07): I think this is not the correct module + // description... as we are planning to use these string to generate the + // documentation... please correct that and also be much more descriptive with + // multi line comment. + return classes.c_str(); } -const char* getModuleComponentList() -{ - // string containing the names of the classes provided by the plugin - static std::string classes = sofa::core::ObjectFactory::getInstance()->listClassesFromTarget(sofa_tostring(SOFA_TARGET)); - return classes.c_str(); +const char *getModuleComponentList() { + // string containing the names of the classes provided by the plugin + static std::string classes = + sofa::core::ObjectFactory::getInstance()->listClassesFromTarget( + sofa_tostring(SOFA_TARGET)); + return classes.c_str(); } -} // namespace sofa::component +} // namespace cosserat diff --git a/src/Cosserat/initCosserat.h.in b/src/Cosserat/initCosserat.h.in new file mode 100644 index 00000000..319bce38 --- /dev/null +++ b/src/Cosserat/initCosserat.h.in @@ -0,0 +1,54 @@ +/****************************************************************************** + * SOFA, Simulation Open-Framework Architecture * + * (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * + * * + * This library is free software; you can redistribute it and/or modify it * + * under the terms of the GNU Lesser General Public License as published by * + * the Free Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. * + * * + * This library is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * + * for more details. * + * * + * You should have received a copy of the GNU Lesser General Public License * + * along with this library; if not, write to the Free Software Foundation, * + * Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * + ******************************************************************************* + * Plugin Cosserat v1.0 * + * * + * This plugin is also distributed under the GNU LGPL (Lesser General * + * Public License) license with the same conditions than SOFA. * + * * + * Contributors: Defrost team (INRIA, University of Lille, CNRS, * + * Ecole Centrale de Lille) * + * * + * Contact information: https://project.inria.fr/softrobot/contact/ * + * * + ******************************************************************************/ +#ifndef SOFA_COSSERAT_INIT_H +#define SOFA_COSSERAT_INIT_H + +#include <sofa/config.h> + +#define COSSERAT_VERSION @PROJECT_VERSION @ + +#ifdef SOFA_BUILD_COSSERAT +#define SOFA_TARGET @PROJECT_NAME @ +#define SOFA_COSSERAT_API SOFA_EXPORT_DYNAMIC_LIBRARY +#else +#define SOFA_COSSERAT_API SOFA_IMPORT_DYNAMIC_LIBRARY +#endif + +/** \mainpage + This is the plugin for the Discret Cosserat Plugin +*/ + +namespace cosserat { +SOFA_COSSERAT_API void init(); +constexpr const char *MODULE_NAME = "@PROJECT_NAME@"; +constexpr const char *MODULE_VERSION = "@PROJECT_VERSION@"; +} // namespace cosserat + +#endif /* SOFA_COSSERAT_INIT_H */ diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 74f481df..9e91f1d9 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -157,6 +157,8 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject type::vector<Mat6x6> m_nodeAdjointVectors; // TODO(dmarchal:2024/06/07): explain why these attributes are unused + // TODO : yadagolo: Need for the dynamic function, which is not working yet. + // But the component is in this folder [[maybe_unused]] type::vector<Mat6x6> m_nodeAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_frameAdjointEtaVectors; [[maybe_unused]] type::vector<Mat6x6> m_node_coAdjointEtaVectors; @@ -165,11 +167,14 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject public: /********************** Inhertited from BaseObject **************/ void init() override; - void draw(const core::visual::VisualParams* vparams) override; + void draw(const core::visual::VisualParams* ) override; /************************* BaseCosserat **************************/ - // TODO(dmarchal:2024/06/07), so we have "initialize" and "init" co-existances of both and their + // TODO(dmarchal:2024/06/07), so we have "initialize" and "init" + // co-existances of both and their // roles is unclear and generates ambiguities + //TODO @yadagolo: Yes, because the function is used by callback, when we + // do dynamic meshing. void initialize(); double computeTheta(const double &x, const Mat4x4 &gX); @@ -188,7 +193,7 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't // be (re)implemented in a base classe. - Eigen::Matrix3d rotationMatrixX(double angle) { + RotMat rotationMatrixX(double angle) { Eigen::Matrix3d rotation; rotation << 1, 0, 0, 0, cos(angle), -sin(angle), @@ -198,7 +203,7 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't // be (re)implemented in a base classe. - Eigen::Matrix3d rotationMatrixY(double angle) { + RotMat rotationMatrixY(double angle) { Eigen::Matrix3d rotation; rotation << cos(angle), 0, sin(angle), 0, 1, 0, diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index b5c2abd6..77819574 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -176,8 +176,9 @@ void BaseCosserat<TIn1, TIn2, TOut>::updateExponentialSE3( template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, - Tangent &adjoint) { - Matrix3 R = extractRotMatrix(frame); + Tangent &adjoint) +{ + Matrix3 R = extractRotMatrix(frame); type::Vec3 u = frame.getOrigin(); Matrix3 tilde_u = getTildeMatrix(u); Matrix3 tilde_u_R = tilde_u * R; @@ -186,8 +187,9 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, - Mat6x6 &co_adjoint) { - Matrix3 R = extractRotMatrix(frame); + Mat6x6 &co_adjoint) +{ + Matrix3 R = extractRotMatrix(frame); type::Vec3 u = frame.getOrigin(); Matrix3 tilde_u = getTildeMatrix(u); Matrix3 tilde_u_R = tilde_u * R; @@ -196,7 +198,8 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, - Mat6x6 &adjoint) { + Mat6x6 &adjoint) +{ Matrix3 tildeMat = getTildeMatrix(type::Vec3(eta[0], eta[1], eta[2])); adjoint.setsub(0, 0, tildeMat); adjoint.setsub(3, 3, tildeMat); @@ -205,8 +208,8 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, template <class TIn1, class TIn2, class TOut> Matrix4 BaseCosserat<TIn1, TIn2, TOut>::computeLogarithm(const double &x, - const Mat4x4 &gX) { - + const Mat4x4 &gX) +{ // Compute theta before everything const double theta = computeTheta(x, gX); Mat4x4 I4; @@ -443,14 +446,8 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() { } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::draw(const core::visual::VisualParams *vparams) +void BaseCosserat<TIn1, TIn2, TOut>::draw(const core::visual::VisualParams *) { - // TODO(dmarchal: 2024/06/07) It is unclear to me why we are overriding a base function - // to enforce it does nothing, - if (!vparams->displayFlags().getShowMappings()) - - if (!d_debug.getValue()) - return; } template <class TIn1, class TIn2, class TOut> From 5042087904ad22105b78b05caadf5cbeb2836eb4 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Sun, 9 Jun 2024 23:55:17 +0200 Subject: [PATCH 44/71] Update the Cosserat mapping names to follow a consistent naming --- src/Cosserat/CMakeLists.txt | 2 +- src/Cosserat/initCosserat.cpp | 15 +- src/Cosserat/initCosserat.h.in | 6 +- src/Cosserat/mapping/BaseCosserat.cpp | 237 +-- src/Cosserat/mapping/BaseCosserat.h | 284 ++-- src/Cosserat/mapping/BaseCosserat.inl | 794 +++++----- .../mapping/DifferenceMultiMapping.cpp | 4 +- src/Cosserat/mapping/DifferenceMultiMapping.h | 86 +- .../mapping/DifferenceMultiMapping.inl | 1302 ++++++++--------- .../mapping/DiscreteCosseratMapping.cpp | 72 +- .../mapping/DiscreteCosseratMapping.h | 269 ++-- .../mapping/DiscreteCosseratMapping.inl | 1162 +++++++-------- .../DiscreteDynamicCosseratMapping.cpp | 6 +- .../mapping/DiscreteDynamicCosseratMapping.h | 97 +- .../DiscreteDynamicCosseratMapping.inl | 778 +++++----- src/Cosserat/mapping/RigidDistanceMapping.cpp | 6 +- src/Cosserat/mapping/RigidDistanceMapping.h | 99 +- src/Cosserat/mapping/RigidDistanceMapping.inl | 58 +- 18 files changed, 2680 insertions(+), 2597 deletions(-) diff --git a/src/Cosserat/CMakeLists.txt b/src/Cosserat/CMakeLists.txt index dbcf73be..bbba6fd6 100644 --- a/src/Cosserat/CMakeLists.txt +++ b/src/Cosserat/CMakeLists.txt @@ -40,8 +40,8 @@ set(SOURCE_FILES initCosserat.cpp mapping/BaseCosserat.cpp + mapping/DiscreteCosseratMapping.cpp mapping/ProjectionEngine.cpp - mapping/DiscreteCosseratMapping.cpp mapping/DiscreteDynamicCosseratMapping.cpp mapping/DifferenceMultiMapping.cpp mapping/RigidDistanceMapping.cpp diff --git a/src/Cosserat/initCosserat.cpp b/src/Cosserat/initCosserat.cpp index d311946b..d127d9fa 100644 --- a/src/Cosserat/initCosserat.cpp +++ b/src/Cosserat/initCosserat.cpp @@ -35,7 +35,7 @@ using sofa::helper::system::PluginManager; // TODO(dmarchal: 2024/06/07) This is the wrong namespace, it should be // "cosserat" or sofacosserat if you rename the plugin into SofaCosserat :) -namespace cosserat { +namespace Cosserat { extern "C" { SOFA_COSSERAT_API void initExternalModule(); @@ -65,19 +65,12 @@ void initExternalModule() { } const char *getModuleLicense() { return "LGPL"; } -const char *getModuleName() { return cosserat::MODULE_NAME; } +const char *getModuleName() { return Cosserat::MODULE_NAME; } -const char *getModuleVersion() { return cosserat::MODULE_VERSION; } +const char *getModuleVersion() { return Cosserat::MODULE_VERSION; } const char *getModuleDescription() { - static std::string classes = - sofa::core::ObjectFactory::getInstance()->listClassesFromTarget( - cosserat::MODULE_NAME); - // TODO(dmarchal: 2024/06/07): I think this is not the correct module - // description... as we are planning to use these string to generate the - // documentation... please correct that and also be much more descriptive with - // multi line comment. - return classes.c_str(); + return "This plugin is used to implement slender object"; } const char *getModuleComponentList() { diff --git a/src/Cosserat/initCosserat.h.in b/src/Cosserat/initCosserat.h.in index 319bce38..d0938489 100644 --- a/src/Cosserat/initCosserat.h.in +++ b/src/Cosserat/initCosserat.h.in @@ -35,7 +35,7 @@ #define COSSERAT_VERSION @PROJECT_VERSION @ #ifdef SOFA_BUILD_COSSERAT -#define SOFA_TARGET @PROJECT_NAME @ +#define SOFA_TARGET Cosserat #define SOFA_COSSERAT_API SOFA_EXPORT_DYNAMIC_LIBRARY #else #define SOFA_COSSERAT_API SOFA_IMPORT_DYNAMIC_LIBRARY @@ -45,10 +45,10 @@ This is the plugin for the Discret Cosserat Plugin */ -namespace cosserat { +namespace Cosserat { SOFA_COSSERAT_API void init(); constexpr const char *MODULE_NAME = "@PROJECT_NAME@"; constexpr const char *MODULE_VERSION = "@PROJECT_VERSION@"; -} // namespace cosserat +} // namespace Cosserat #endif /* SOFA_COSSERAT_INIT_H */ diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index bef42c08..6e08e404 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -1,137 +1,166 @@ /****************************************************************************** -* SOFA, Simulation Open-Framework Architecture, development version * -* (c) 2006-2019 INRIA, USTL, UJF, CNRS, MGH * -* * -* This program is free software; you can redistribute it and/or modify it * -* under the terms of the GNU Lesser General Public License as published by * -* the Free Software Foundation; either version 2.1 of the License, or (at * -* your option) any later version. * -* * -* This program is distributed in the hope that it will be useful, but WITHOUT * -* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * -* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * -* for more details. * -* * -* You should have received a copy of the GNU Lesser General Public License * -* along with this program. If not, see <http://www.gnu.org/licenses/>. * -******************************************************************************* -* Authors: The SOFA Team and external contributors (see Authors.txt) * -* * -* Contact information: contact@sofa-framework.org * -******************************************************************************/ + * SOFA, Simulation Open-Framework Architecture, development version * + * (c) 2006-2019 INRIA, USTL, UJF, CNRS, MGH * + * * + * This program is free software; you can redistribute it and/or modify it * + * under the terms of the GNU Lesser General Public License as published by * + * the Free Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * + * for more details. * + * * + * You should have received a copy of the GNU Lesser General Public License * + * along with this program. If not, see <http://www.gnu.org/licenses/>. * + ******************************************************************************* + * Authors: The SOFA Team and external contributors (see Authors.txt) * + * * + * Contact information: contact@sofa-framework.org * + ******************************************************************************/ #define SOFA_COSSERAT_CPP_BaseCosserat -#include "BaseCosserat.inl" +#include <Cosserat/mapping/BaseCosserat.inl> -#include <sofa/defaulttype/VecTypes.h> -#include <sofa/defaulttype/RigidTypes.h> #include <sofa/core/ObjectFactory.h> +#include <sofa/defaulttype/RigidTypes.h> +#include <sofa/defaulttype/VecTypes.h> -namespace sofa::component::mapping -{ +namespace Cosserat::mapping { using namespace sofa::defaulttype; -template<> -BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const Coord1& strain_i){ - se3 Xi; +template <> +BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 +BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat( + const Coord1 &strain_i) { + se3 Xi; - Xi[0][1] = -strain_i(2); - Xi[0][2] = strain_i[1]; - Xi[1][2] = -strain_i[0]; + Xi[0][1] = -strain_i(2); + Xi[0][2] = strain_i[1]; + Xi[1][2] = -strain_i[0]; - Xi[1][0] = -Xi(0,1); - Xi[2][0] = -Xi(0,2); - Xi[2][1] = -Xi(1,2); + Xi[1][0] = -Xi(0, 1); + Xi[2][0] = -Xi(0, 2); + Xi[2][1] = -Xi(1, 2); - Xi[0][3] = 1.0; + Xi[0][3] = 1.0; - for (unsigned int i=0; i<3; i++) - Xi[i][3] += strain_i(i+3); + for (unsigned int i = 0; i < 3; i++) + Xi[i][3] += strain_i(i + 3); -// se3 = [ -// 0 -screw(3) screw(2) screw(4); -// screw(3) 0 -screw(1) screw(5); -// -screw(2) screw(1) 0 screw(6); -// 0 0 0 0]; + // se3 = [ + // 0 -screw(3) screw(2) screw(4); + // screw(3) 0 -screw(1) screw(5); + // -screw(2) screw(1) 0 screw(6); + // 0 0 0 0]; - return Xi; + return Xi; } +template <> +void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3( + const double &curv_abs_x_n, const Coord1 &strain_n, Transform &Trans) { + Matrix4 I4; + I4.identity(); + + // Get the angular part of the + Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); + SReal theta = k.norm(); // + + SE3 g_X_n; + se3 Xi_hat_n = buildXiHat(strain_n); + + msg_info() << "matrix Xi : " << Xi_hat_n; + + if (theta <= std::numeric_limits<double>::epsilon()) { + g_X_n = I4 + curv_abs_x_n * Xi_hat_n; + } else { + double scalar1 = + (1.0 - std::cos(curv_abs_x_n * theta)) / std::pow(theta, 2); + double scalar2 = (curv_abs_x_n * theta - std::sin(curv_abs_x_n * theta)) / + std::pow(theta, 3); + g_X_n = I4 + curv_abs_x_n * Xi_hat_n + scalar1 * Xi_hat_n * Xi_hat_n + + scalar2 * Xi_hat_n * Xi_hat_n * Xi_hat_n; + } + msg_info() << "matrix g_X : " << g_X_n; -template<> -void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3(const double & curv_abs_x_n, const Coord1& strain_n, Transform & Trans){ - Matrix4 I4; I4.identity(); - - //Get the angular part of the - Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); - SReal theta = k.norm(); // - - SE3 g_X_n; - se3 Xi_hat_n = buildXiHat(strain_n); - - msg_info()<< "matrix Xi : "<< Xi_hat_n; - - if(theta <= std::numeric_limits<double>::epsilon()){ - g_X_n = I4 + curv_abs_x_n*Xi_hat_n; - }else { - double scalar1= (1.0 - std::cos(curv_abs_x_n*theta))/std::pow(theta,2); - double scalar2 = (curv_abs_x_n*theta - std::sin(curv_abs_x_n*theta))/std::pow(theta,3); - g_X_n = I4 + curv_abs_x_n*Xi_hat_n + scalar1*Xi_hat_n*Xi_hat_n + scalar2*Xi_hat_n*Xi_hat_n*Xi_hat_n ; - } - - msg_info()<< "matrix g_X : "<< g_X_n; - - type::Mat3x3 M; - g_X_n.getsub(0,0,M); //get the rotation matrix + sofa::type::Mat3x3 M; + g_X_n.getsub(0, 0, M); // get the rotation matrix - // convert the rotation 3x3 matrix to a quaternion - sofa::type::Quat<Real> R ; R.fromMatrix(M); - Trans = Transform(type::Vec3(g_X_n(0,3),g_X_n(1,3),g_X_n(2,3)),R); + // convert the rotation 3x3 matrix to a quaternion + sofa::type::Quat<Real> R; + R.fromMatrix(M); + Trans = Transform(Vec3(g_X_n(0, 3), g_X_n(1, 3), g_X_n(2, 3)), R); } -template<> -void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp(double & curv_abs_n, const Coord1 & strain_i, Mat6x6 & TgX){ +template <> +void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( + double &curv_abs_n, const Coord1 &strain_i, Mat6x6 &TgX) { - SReal theta = type::Vec3(strain_i(0), strain_i(1), strain_i(2)).norm(); //Sometimes this is computed over all strain - Matrix3 tilde_k = getTildeMatrix(type::Vec3(strain_i(0), strain_i(1), strain_i(2))); + SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) + .norm(); // Sometimes this is computed over all strain + Matrix3 tilde_k = + getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); /* Younes @23-11-27 old version - @Todo ???? is p the linear deformation? If so, why didn't I just put a zero vector in place of p and the first element of p is equal to 1? - Matrix3 tilde_p = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); - Using the new version does not bring any difference in my three reference scenes, but need more investogation + @Todo ???? is p the linear deformation? If so, why didn't I just put a zero + vector in place of p and the first element of p is equal to 1? Matrix3 tilde_p + = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); Using the new version does not + bring any difference in my three reference scenes, but need more investogation #TECHNICAL_DEBT */ - //TODO(dmarchal: 2024/06/07) could the debt by solved ? - Matrix3 tilde_q = getTildeMatrix(type::Vec3(strain_i(3), strain_i(4), strain_i(5))); + // TODO(dmarchal: 2024/06/07) could the debt by solved ? + Matrix3 tilde_q = + getTildeMatrix(Vec3(strain_i(3), strain_i(4), strain_i(5))); - Mat6x6 ad_Xi ; + Mat6x6 ad_Xi; buildAdjoint(tilde_k, tilde_q, ad_Xi); - Mat6x6 Id6 = Mat6x6::Identity() ; - - if(theta <= std::numeric_limits<double>::epsilon()){ - double scalar0 = std::pow(curv_abs_n,2)/2.0; - TgX = curv_abs_n*Id6 + scalar0 * ad_Xi; - }else { - double scalar1 = (4.0 -4.0*cos(curv_abs_n*theta)-curv_abs_n*theta*sin(curv_abs_n*theta))/(2.0*theta*theta); - double scalar2 = (4.0*curv_abs_n*theta + curv_abs_n*theta*cos(curv_abs_n*theta)-5.0*sin(curv_abs_n*theta))/(2.0*theta*theta*theta); - double scalar3 = (2.0 -2.0*cos(curv_abs_n*theta)-curv_abs_n*theta*sin(curv_abs_n*theta))/(2.0*theta*theta*theta*theta); - double scalar4 = (2.0*curv_abs_n*theta + curv_abs_n*theta*cos(curv_abs_n*theta)-3.0*sin(curv_abs_n*theta))/(2.0*theta*theta*theta*theta*theta); - - TgX = curv_abs_n*Id6 + scalar1*ad_Xi + scalar2*ad_Xi*ad_Xi + scalar3*ad_Xi*ad_Xi*ad_Xi + scalar4*ad_Xi*ad_Xi*ad_Xi*ad_Xi ; + Mat6x6 Id6 = Mat6x6::Identity(); + + if (theta <= std::numeric_limits<double>::epsilon()) { + double scalar0 = std::pow(curv_abs_n, 2) / 2.0; + TgX = curv_abs_n * Id6 + scalar0 * ad_Xi; + } else { + double scalar1 = (4.0 - 4.0 * cos(curv_abs_n * theta) - + curv_abs_n * theta * sin(curv_abs_n * theta)) / + (2.0 * theta * theta); + double scalar2 = (4.0 * curv_abs_n * theta + + curv_abs_n * theta * cos(curv_abs_n * theta) - + 5.0 * sin(curv_abs_n * theta)) / + (2.0 * theta * theta * theta); + double scalar3 = (2.0 - 2.0 * cos(curv_abs_n * theta) - + curv_abs_n * theta * sin(curv_abs_n * theta)) / + (2.0 * theta * theta * theta * theta); + double scalar4 = (2.0 * curv_abs_n * theta + + curv_abs_n * theta * cos(curv_abs_n * theta) - + 3.0 * sin(curv_abs_n * theta)) / + (2.0 * theta * theta * theta * theta * theta); + + TgX = curv_abs_n * Id6 + scalar1 * ad_Xi + scalar2 * ad_Xi * ad_Xi + + scalar3 * ad_Xi * ad_Xi * ad_Xi + + scalar4 * ad_Xi * ad_Xi * ad_Xi * ad_Xi; } } - // Register in the Factory -int BaseCosseratClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") - .add< BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() - .add< BaseCosserat< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() -; - - -template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; -template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; - -} // namespace sofa. +int BaseCosseratClass = + sofa::core::RegisterObject( + "Set the positions and velocities of points attached to a rigid parent") + .add<BaseCosserat<sofa::defaulttype::Vec3Types, + sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>>() + .add<BaseCosserat<sofa::defaulttype::Vec6Types, + sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>>(); + +template class SOFA_COSSERAT_API + BaseCosserat<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; +template class SOFA_COSSERAT_API + BaseCosserat<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; + +} // namespace cosserat::mapping diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 9e91f1d9..a2c50e68 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -1,37 +1,37 @@ /****************************************************************************** -* SOFA, Simulation Open-Framework Architecture, development version * -* (c) 2006-2019 INRIA, USTL, UJF, CNRS, MGH * -* * -* This program is free software; you can redistribute it and/or modify it * -* under the terms of the GNU Lesser General Public License as published by * -* the Free Software Foundation; either version 2.1 of the License, or (at * -* your option) any later version. * -* * -* This program is distributed in the hope that it will be useful, but WITHOUT * -* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * -* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * -* for more details. * -* * -* You should have received a copy of the GNU Lesser General Public License * -* along with this program. If not, see <http://www.gnu.org/licenses/>. * -******************************************************************************* -* Authors: The SOFA Team and external contributors (see Authors.txt) * -* * -* Contact information: contact@sofa-framework.org * -******************************************************************************/ + * SOFA, Simulation Open-Framework Architecture, development version * + * (c) 2006-2019 INRIA, USTL, UJF, CNRS, MGH * + * * + * This program is free software; you can redistribute it and/or modify it * + * under the terms of the GNU Lesser General Public License as published by * + * the Free Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * + * for more details. * + * * + * You should have received a copy of the GNU Lesser General Public License * + * along with this program. If not, see <http://www.gnu.org/licenses/>. * + ******************************************************************************* + * Authors: The SOFA Team and external contributors (see Authors.txt) * + * * + * Contact information: contact@sofa-framework.org * + ******************************************************************************/ #pragma once -#include <Cosserat/config.h> +#include <Cosserat/initCosserat.h> #include <sofa/core/BaseMapping.h> -#include <sofa/core/config.h> #include <sofa/core/Multi2Mapping.h> -#include <sofa/defaulttype/SolidTypes.h> -#include <sofa/defaulttype/RigidTypes.h> +#include <sofa/core/config.h> #include <sofa/core/objectmodel/BaseObject.h> +#include <sofa/defaulttype/RigidTypes.h> +#include <sofa/defaulttype/SolidTypes.h> #include <sofa/type/Vec.h> -#include <iostream> #include <cmath> +#include <iostream> #include <Eigen/Dense> #include <cmath> @@ -41,24 +41,26 @@ using namespace Eigen; #include <cmath> -// TODO(dmarchal, 2024/06/07): This is polluating the namespace of sofa::components +// TODO(dmarchal, 2024/06/07): This is polluating the namespace of +// sofa::components // plugins should be in their own namespace like // eg: cosserat::component::mapping -namespace sofa::component::mapping -{ +namespace Cosserat::mapping { -// with a private namespace the used named are not polluating the whole sofa::component::mapping -// ones. +// with a private namespace the used named are not polluating the whole +// sofa::component::mapping ones. namespace { -using sofa::defaulttype::SolidTypes ; -using sofa::core::objectmodel::BaseContext ; +using sofa::core::objectmodel::BaseContext; +using sofa::core::objectmodel::BaseObject; +using sofa::defaulttype::SolidTypes; using sofa::type::Matrix3; using sofa::type::Matrix4; -using type::Vec3; -using type::Vec6; using std::get; -using sofa::core::objectmodel::BaseObject; -} +using sofa::type::vector; +using sofa::type::Vec3; +using sofa::type::Vec6; +using sofa::type::Mat; +} // namespace /*! * \class BaseCosserat @@ -68,14 +70,12 @@ using sofa::core::objectmodel::BaseObject; * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ - -// TODO(dmarchal: 2024/06/07) This component looks like a mapping but inherit from BaseObject * -// can you clarify why is is not inhering from BaseMapping +// TODO(dmarchal: 2024/06/07) This component looks like a mapping but inherit +// from BaseObject * can you clarify why is is not inhering from BaseMapping template <class TIn1, class TIn2, class TOut> -class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject -{ +class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { public: - SOFA_CLASS(SOFA_TEMPLATE3(BaseCosserat, TIn1,TIn2, TOut), BaseObject ); + SOFA_CLASS(SOFA_TEMPLATE3(BaseCosserat, TIn1, TIn2, TOut), BaseObject); typedef BaseObject Inherit; /// Input Model Type @@ -85,184 +85,192 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject /// Output Model Type typedef TOut Out; - - // TODO(dmarchal:2024/06/07) This very long list of public typedefs looks questionnable - // at least this has to be justified by comment on why these typedefs are public - typedef typename In1::Coord Coord1 ; - typedef typename In1::Deriv Deriv1 ; + // TODO(dmarchal:2024/06/07) This very long list of public typedefs looks + // questionnable at least this has to be justified by comment on why these + // typedefs are public + typedef typename In1::Coord Coord1; + typedef typename In1::Deriv Deriv1; typedef typename In1::VecCoord In1VecCoord; typedef typename In1::VecDeriv In1VecDeriv; [[maybe_unused]] typedef typename In1::MatrixDeriv In1MatrixDeriv; - typedef Data<In1VecCoord> In1DataVecCoord; - typedef Data<In1VecDeriv> In1DataVecDeriv; + typedef sofa::Data<In1VecCoord> In1DataVecCoord; + typedef sofa::Data<In1VecDeriv> In1DataVecDeriv; - typedef typename In2::Coord::value_type Real ; - typedef typename In2::Coord Coord2 ; - typedef typename In2::Deriv Deriv2 ; + typedef typename In2::Coord::value_type Real; + typedef typename In2::Coord Coord2; + typedef typename In2::Deriv Deriv2; typedef typename In2::VecCoord In2VecCoord; typedef typename In2::VecDeriv In2VecDeriv; [[maybe_unused]] typedef typename In2::MatrixDeriv In2MatrixDeriv; - typedef Data<In2VecCoord> In2DataVecCoord; - typedef Data<In2VecDeriv> In2DataVecDeriv; - typedef type::Mat<6,6,SReal> Mat6x6; - typedef type::Mat<4,4,SReal> Mat4x4; + typedef sofa::Data<In2VecCoord> In2DataVecCoord; + typedef sofa::Data<In2VecDeriv> In2DataVecDeriv; + typedef Mat<6, 6, SReal> Mat6x6; + typedef Mat<4, 4, SReal> Mat4x4; typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; typedef typename Out::Deriv OutDeriv; typedef typename Out::VecDeriv OutVecDeriv; typedef typename Out::MatrixDeriv OutMatrixDeriv; - typedef Data<OutVecCoord> OutDataVecCoord; - typedef Data<OutVecDeriv> OutDataVecDeriv; - typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; - - typedef MultiLink<BaseCosserat<In1,In2,Out>, sofa::core::State< In1 >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels1; - typedef MultiLink<BaseCosserat<In1,In2,Out>, sofa::core::State< In2 >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels2; - [[maybe_unused]] typedef MultiLink<BaseCosserat<In1,In2,Out>, sofa::core::State< Out >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkToModels; - - typedef typename SolidTypes<SReal>::Transform Transform ; - typedef typename type::vector<SReal> List; - - typedef typename sofa::type::Matrix4 se3; - typedef typename sofa::type::Matrix4 SE3; - typedef typename Eigen::Matrix4d _SE3; - typedef typename Eigen::Matrix4d _se3; - typedef typename type::Mat<6,6,SReal> Tangent; + typedef sofa::Data<OutVecCoord> OutDataVecCoord; + typedef sofa::Data<OutVecDeriv> OutDataVecDeriv; + typedef sofa::Data<OutMatrixDeriv> OutDataMatrixDeriv; + + typedef sofa::MultiLink<BaseCosserat<In1, In2, Out>, sofa::core::State<In1>, + sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> + LinkFromModels1; + typedef sofa::MultiLink<BaseCosserat<In1, In2, Out>, sofa::core::State<In2>, + sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> + LinkFromModels2; + [[maybe_unused]] typedef sofa::MultiLink< + BaseCosserat<In1, In2, Out>, sofa::core::State<Out>, + sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> + LinkToModels; + + typedef typename SolidTypes<SReal>::Transform Transform; + typedef typename sofa::type::vector<SReal> List; + + typedef typename sofa::type::Matrix4 se3; + typedef typename sofa::type::Matrix4 SE3; + typedef typename Eigen::Matrix4d _SE3; + typedef typename Eigen::Matrix4d _se3; + typedef typename sofa::type::Mat<6, 6, SReal> Tangent; typedef typename Eigen::Matrix3d RotMat; typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; public: - // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this really needed ? + // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this + // really needed ? /*===========COSSERAT VECTORS ======================*/ unsigned int m_index_input; - OutVecCoord m_vecTransform ; + OutVecCoord m_vecTransform; - type::vector<Transform> m_framesExponentialSE3Vectors; - type::vector<Transform> m_nodesExponentialSE3Vectors; - type::vector<Matrix4> m_nodesLogarithmeSE3Vectors; + vector<Transform> m_framesExponentialSE3Vectors; + vector<Transform> m_nodesExponentialSE3Vectors; + vector<Matrix4> m_nodesLogarithmeSE3Vectors; // @todo comment or explain more vectors - type::vector<unsigned int> m_indicesVectors; - type::vector<unsigned int> m_indicesVectorsDraw; + vector<unsigned int> m_indicesVectors; + vector<unsigned int> m_indicesVectorsDraw; - type::vector<double> m_BeamLengthVectors; - type::vector<double> m_framesLengthVectors; + vector<double> m_BeamLengthVectors; + vector<double> m_framesLengthVectors; - type::vector<Vec6> m_nodesVelocityVectors; - type::vector<Mat6x6> m_nodesTangExpVectors; - type::vector<Mat6x6> m_framesTangExpVectors; - type::vector<Vec6> m_totalBeamForceVectors; + vector<Vec6> m_nodesVelocityVectors; + vector<Mat6x6> m_nodesTangExpVectors; + vector<Mat6x6> m_framesTangExpVectors; + vector<Vec6> m_totalBeamForceVectors; - type::vector<Mat6x6> m_nodeAdjointVectors; + vector<Mat6x6> m_nodeAdjointVectors; // TODO(dmarchal:2024/06/07): explain why these attributes are unused // TODO : yadagolo: Need for the dynamic function, which is not working yet. // But the component is in this folder - [[maybe_unused]] type::vector<Mat6x6> m_nodeAdjointEtaVectors; - [[maybe_unused]] type::vector<Mat6x6> m_frameAdjointEtaVectors; - [[maybe_unused]] type::vector<Mat6x6> m_node_coAdjointEtaVectors; - [[maybe_unused]] type::vector<Mat6x6> m_frame_coAdjointEtaVectors; + [[maybe_unused]] vector<Mat6x6> m_nodeAdjointEtaVectors; + [[maybe_unused]] vector<Mat6x6> m_frameAdjointEtaVectors; + [[maybe_unused]] vector<Mat6x6> m_node_coAdjointEtaVectors; + [[maybe_unused]] vector<Mat6x6> m_frame_coAdjointEtaVectors; public: /********************** Inhertited from BaseObject **************/ void init() override; - void draw(const core::visual::VisualParams* ) override; + void draw(const sofa::core::visual::VisualParams *) override; /************************* BaseCosserat **************************/ // TODO(dmarchal:2024/06/07), so we have "initialize" and "init" // co-existances of both and their // roles is unclear and generates ambiguities - //TODO @yadagolo: Yes, because the function is used by callback, when we + // TODO @yadagolo: Yes, because the function is used by callback, when we // do dynamic meshing. void initialize(); double computeTheta(const double &x, const Mat4x4 &gX); void printMatrix(const Mat6x6 R); - Matrix3 extractRotMatrix(const Transform & frame); + Matrix3 extractRotMatrix(const Transform &frame); Tangent buildProjector(const Transform &T); - se3 buildXiHat(const Coord1 & strain_i); - Matrix3 getTildeMatrix(const type::Vec3 & u); + se3 buildXiHat(const Coord1 &strain_i); + Matrix3 getTildeMatrix(const Vec3 &u); - void buildAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & Adjoint); - void buildCoAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint); + void buildAdjoint(const Matrix3 &A, const Matrix3 &B, Mat6x6 &Adjoint); + void buildCoAdjoint(const Matrix3 &A, const Matrix3 &B, Mat6x6 &coAdjoint); - Matrix4 convertTransformToMatrix4x4(const Transform & T); - Vec6 piecewiseLogmap(const _SE3& g_x) ; + Matrix4 convertTransformToMatrix4x4(const Transform &T); + Vec6 piecewiseLogmap(const _SE3 &g_x); - // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't - // be (re)implemented in a base classe. + // TODO(dmarchal: 2024/06/07), this looks like a very common utility + // function... it shouldn't be (re)implemented in a base classe. RotMat rotationMatrixX(double angle) { Eigen::Matrix3d rotation; - rotation << 1, 0, 0, - 0, cos(angle), -sin(angle), - 0, sin(angle), cos(angle); + rotation << 1, 0, 0, 0, cos(angle), -sin(angle), 0, sin(angle), cos(angle); return rotation; } - // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't - // be (re)implemented in a base classe. + // TODO(dmarchal: 2024/06/07), this looks like a very common utility + // function... it shouldn't be (re)implemented in a base classe. RotMat rotationMatrixY(double angle) { Eigen::Matrix3d rotation; - rotation << cos(angle), 0, sin(angle), - 0, 1, 0, - -sin(angle), 0, cos(angle); + rotation << cos(angle), 0, sin(angle), 0, 1, 0, -sin(angle), 0, cos(angle); return rotation; } - // TODO(dmarchal: 2024/06/07), this looks like a very common utility function... it shouldn't - // be (re)implemented in a base classe. - // the type of the data return should also be unified between rotationMatrixX, Y and Z + // TODO(dmarchal: 2024/06/07), this looks like a very common utility + // function... it shouldn't be (re)implemented in a base classe. the type of + // the data return should also be unified between rotationMatrixX, Y and Z RotMat rotationMatrixZ(double angle) { RotMat rotation; - rotation << cos(angle), -sin(angle), 0, - sin(angle), cos(angle), 0, - 0, 0, 1; + rotation << cos(angle), -sin(angle), 0, sin(angle), cos(angle), 0, 0, 0, 1; return rotation; } protected: - Data<type::vector<double>> d_curv_abs_section ; - Data<type::vector<double>> d_curv_abs_frames ; - Data<bool> d_debug ; + sofa::Data<vector<double>> d_curv_abs_section; + sofa::Data<vector<double>> d_curv_abs_frames; + sofa::Data<bool> d_debug; /// Input Models container. New inputs are added through addInputModel(In* ). - core::State<In1>* m_fromModel1; + sofa::core::State<In1> *m_fromModel1; // TODO(dmarchal): why this maybe_unused on a data field ? - [[maybe_unused]] core::State<In2>* m_fromModel2; + [[maybe_unused]] sofa::core::State<In2> *m_fromModel2; - core::State<Out>* m_toModel; + sofa::core::State<Out> *m_toModel; -protected: +protected: /// Constructor - BaseCosserat() ; + BaseCosserat(); /// Destructor - ~BaseCosserat() override = default; + ~BaseCosserat() override = default; - void computeExponentialSE3(const double &x, const Coord1& k, Transform & Trans); + void computeExponentialSE3(const double &x, const Coord1 &k, + Transform &Trans); // TODO(dmarchal: 2024/06/07): // - two naming convention - // - unclear the difference between computeAdjoing and buildAdjoint ... is there room for factoring things ? - void computeAdjoint(const Transform & frame, Mat6x6 &adjoint); - void computeAdjoint(const Vec6 & frame, Mat6x6 &adjoint); + // - unclear the difference between computeAdjoing and buildAdjoint ... is + // there room for factoring things ? + void computeAdjoint(const Transform &frame, Mat6x6 &adjoint); + void computeAdjoint(const Vec6 &frame, Mat6x6 &adjoint); - void computeCoAdjoint(const Transform & frame, Mat6x6 &coAdjoint); + void computeCoAdjoint(const Transform &frame, Mat6x6 &coAdjoint); - void updateExponentialSE3(const In1VecCoord & inDeform); - void updateTangExpSE3(const In1VecCoord & inDeform); - void computeTangExp(double & x, const Coord1& k, Mat6x6 & TgX); + void updateExponentialSE3(const In1VecCoord &inDeform); + void updateTangExpSE3(const In1VecCoord &inDeform); + void computeTangExp(double &x, const Coord1 &k, Mat6x6 &TgX); - [[maybe_unused]] type::Vec6 computeETA(const Vec6 & baseEta, const In1VecDeriv & k_dot, double abs_input); - type::Matrix4 computeLogarithm(const double & x, const Mat4x4 &gX); + [[maybe_unused]] Vec6 + computeETA(const Vec6 &baseEta, const In1VecDeriv &k_dot, double abs_input); + Matrix4 computeLogarithm(const double &x, const Mat4x4 &gX); }; - #if !defined(SOFA_COSSERAT_CPP_BaseCosserat) -extern template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; -extern template class SOFA_COSSERAT_API BaseCosserat< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; +extern template class SOFA_COSSERAT_API + BaseCosserat<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; +extern template class SOFA_COSSERAT_API + BaseCosserat<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; #endif -} // namespace sofa +} // namespace cosserat::mapping diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index 77819574..507aedb1 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -20,7 +20,9 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include "BaseCosserat.h" + +#include <Cosserat/initCosserat.h> +#include <Cosserat/mapping/BaseCosserat.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/behavior/MechanicalState.h> @@ -35,136 +37,134 @@ // To go further => // https://www.mathworks.com/matlabcentral/fileexchange/83038-sorosim/ -namespace sofa::component::mapping -{ +namespace Cosserat::mapping { -namespace -{ - using sofa::core::objectmodel::BaseContext; - using sofa::helper::AdvancedTimer; - using sofa::helper::WriteAccessor; - using sofa::type::vector; -} +namespace { +using sofa::core::objectmodel::BaseContext; +using sofa::helper::AdvancedTimer; +using sofa::helper::WriteAccessor; +using sofa::type::vector; +} // namespace template <class TIn1, class TIn2, class TOut> BaseCosserat<TIn1, TIn2, TOut>::BaseCosserat() : d_curv_abs_section(initData(&d_curv_abs_section, "curv_abs_input", " need to be com....")), - d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", - " need to be com....")), - d_debug(initData(&d_debug, false, "debug", "printf for the debug")), - m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), - m_index_input(0) {} + d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", + " need to be com....")), + d_debug(initData(&d_debug, false, "debug", "printf for the debug")), + m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), + m_index_input(0) {} // _________________________________________________________________________________________ template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::init() { - Inherit1::init(); + Inherit1::init(); - // Fill the initial vector - const OutDataVecCoord *xfromData = - m_toModel->read(core::ConstVecCoordId::position()); - const OutVecCoord xfrom = xfromData->getValue(); + // Fill the initial vector + const OutDataVecCoord *xfromData = + m_toModel->read(sofa::core::ConstVecCoordId::position()); + const OutVecCoord xfrom = xfromData->getValue(); } template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { - Matrix4 I4; - I4.identity(); - // Get the angular part of the - sofa::type::Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); - SReal theta = k.norm(); // - - SE3 _g_X; - se3 Xi_hat_n = buildXiHat(strain_n); - - if (d_debug.getValue()) - msg_info("BaseCosserat: ") << "matrix Xi : " << Xi_hat_n; - - if (theta <= std::numeric_limits<double>::epsilon()) { - _g_X = I4 + curv_abs_x_n * Xi_hat_n; - } else { - double scalar1 = - (1.0 - std::cos(curv_abs_x_n * theta)) / std::pow(theta, 2); - double scalar2 = (curv_abs_x_n * theta - std::sin(curv_abs_x_n * theta)) / - std::pow(theta, 3); - _g_X = I4 + curv_abs_x_n * Xi_hat_n + scalar1 * Xi_hat_n * Xi_hat_n + - scalar2 * Xi_hat_n * Xi_hat_n * Xi_hat_n; - } - - if (d_debug.getValue()) - msg_info("BaseCosserat: ") << "matrix _g_X : " << _g_X; - type::Mat3x3 M; - _g_X.getsub(0, 0, M); // get the rotation matrix - - // convert the rotation 3x3 matrix to a quaternion - sofa::type::Quat<Real> R; - R.fromMatrix(M); - g_X_n = Transform(type::Vec3(_g_X(0, 3), _g_X(1, 3), _g_X(2, 3)), R); + Matrix4 I4; + I4.identity(); + // Get the angular part of the + sofa::type::Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); + SReal theta = k.norm(); // + + SE3 _g_X; + se3 Xi_hat_n = buildXiHat(strain_n); + + if (d_debug.getValue()) + msg_info("BaseCosserat: ") << "matrix Xi : " << Xi_hat_n; + + if (theta <= std::numeric_limits<double>::epsilon()) { + _g_X = I4 + curv_abs_x_n * Xi_hat_n; + } else { + double scalar1 = + (1.0 - std::cos(curv_abs_x_n * theta)) / std::pow(theta, 2); + double scalar2 = (curv_abs_x_n * theta - std::sin(curv_abs_x_n * theta)) / + std::pow(theta, 3); + _g_X = I4 + curv_abs_x_n * Xi_hat_n + scalar1 * Xi_hat_n * Xi_hat_n + + scalar2 * Xi_hat_n * Xi_hat_n * Xi_hat_n; + } + + if (d_debug.getValue()) + msg_info("BaseCosserat: ") << "matrix _g_X : " << _g_X; + sofa::type::Mat3x3 M; + _g_X.getsub(0, 0, M); // get the rotation matrix + + // convert the rotation 3x3 matrix to a quaternion + sofa::type::Quat<Real> R; + R.fromMatrix(M); + g_X_n = Transform(Vec3(_g_X(0, 3), _g_X(1, 3), _g_X(2, 3)), R); } // Fill exponential vectors template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::updateExponentialSE3( const In1VecCoord &inDeform) { - // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = - // d_curv_abs_section; - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = - d_curv_abs_frames; - - m_framesExponentialSE3Vectors.clear(); - m_nodesExponentialSE3Vectors.clear(); - m_nodesLogarithmeSE3Vectors.clear(); - const unsigned int sz = curv_abs_frames.size(); - - // Compute exponential at each frame point - for (size_t i = 0; i < sz; i++) { - Transform g_X_frame_i; - - const Coord1 strain_n = inDeform[m_indicesVectors[i] - - 1]; // Cosserat reduce coordinates (strain) - // the size varies from 1 to 6 - // The distance between the frame and the closest beam node toward the base - const SReal curv_abs_x = - m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) - computeExponentialSE3(curv_abs_x, strain_n, g_X_frame_i); - m_framesExponentialSE3Vectors.push_back(g_X_frame_i); - - if (d_debug.getValue()) { - msg_info("BaseCosserat:") - << "_________________" << i << "_________________________"; - msg_info("BaseCosserat:") - << "x :" << curv_abs_x << "; strain :" << strain_n; - msg_info("BaseCosserat:") - << "m_framesExponentialSE3Vectors :" << g_X_frame_i; + // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = + // d_curv_abs_section; + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = + d_curv_abs_frames; + + m_framesExponentialSE3Vectors.clear(); + m_nodesExponentialSE3Vectors.clear(); + m_nodesLogarithmeSE3Vectors.clear(); + const unsigned int sz = curv_abs_frames.size(); + + // Compute exponential at each frame point + for (size_t i = 0; i < sz; i++) { + Transform g_X_frame_i; + + const Coord1 strain_n = inDeform[m_indicesVectors[i] - + 1]; // Cosserat reduce coordinates (strain) + // the size varies from 1 to 6 + // The distance between the frame and the closest beam node toward the base + const SReal curv_abs_x = + m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) + computeExponentialSE3(curv_abs_x, strain_n, g_X_frame_i); + m_framesExponentialSE3Vectors.push_back(g_X_frame_i); + + if (d_debug.getValue()) { + msg_info("BaseCosserat:") + << "_________________" << i << "_________________________"; + msg_info("BaseCosserat:") + << "x :" << curv_abs_x << "; strain :" << strain_n; + msg_info("BaseCosserat:") + << "m_framesExponentialSE3Vectors :" << g_X_frame_i; + } } - } - - // Compute the exponential on the nodes - m_nodesExponentialSE3Vectors.push_back( - Transform(type::Vec3(0.0, 0.0, 0.0), - type::Quat(0., 0., 0., 1.))); // The first node. - for (unsigned int j = 0; j < inDeform.size(); j++) { - Coord1 strain_n = inDeform[j]; // Strain_n - const SReal curv_abs_x = - m_BeamLengthVectors[j]; // curv_abs_x = L_n - L_(n-1) - - Transform g_X_node_j; - computeExponentialSE3(curv_abs_x, strain_n, g_X_node_j); - m_nodesExponentialSE3Vectors.push_back(g_X_node_j); - - if (d_debug.getValue()) { - msg_info("BaseCosserat:") - << "_________________Beam Node Expo___________________" << j; - msg_info("BaseCosserat:") - << "Node m_framesExponentialSE3Vectors :" << g_X_node_j; - msg_info("BaseCosserat:") - << "_________________Beam Node Expo___________________"; + // Compute the exponential on the nodes + m_nodesExponentialSE3Vectors.push_back( + Transform(sofa::type::Vec3(0.0, 0.0, 0.0), + sofa::type::Quat(0., 0., 0., 1.))); // The first node. + + for (unsigned int j = 0; j < inDeform.size(); j++) { + Coord1 strain_n = inDeform[j]; // Strain_n + const SReal curv_abs_x = + m_BeamLengthVectors[j]; // curv_abs_x = L_n - L_(n-1) + + Transform g_X_node_j; + computeExponentialSE3(curv_abs_x, strain_n, g_X_node_j); + m_nodesExponentialSE3Vectors.push_back(g_X_node_j); + + if (d_debug.getValue()) { + msg_info("BaseCosserat:") + << "_________________Beam Node Expo___________________" << j; + msg_info("BaseCosserat:") + << "Node m_framesExponentialSE3Vectors :" << g_X_node_j; + msg_info("BaseCosserat:") + << "_________________Beam Node Expo___________________"; + } } - } } ////////////////// Test the logarithm code @@ -176,132 +176,128 @@ void BaseCosserat<TIn1, TIn2, TOut>::updateExponentialSE3( template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, - Tangent &adjoint) -{ - Matrix3 R = extractRotMatrix(frame); - type::Vec3 u = frame.getOrigin(); - Matrix3 tilde_u = getTildeMatrix(u); - Matrix3 tilde_u_R = tilde_u * R; - buildAdjoint(R, tilde_u_R, adjoint); + Tangent &adjoint) { + Matrix3 R = extractRotMatrix(frame); + Vec3 u = frame.getOrigin(); + Matrix3 tilde_u = getTildeMatrix(u); + Matrix3 tilde_u_R = tilde_u * R; + buildAdjoint(R, tilde_u_R, adjoint); } template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, - Mat6x6 &co_adjoint) -{ - Matrix3 R = extractRotMatrix(frame); - type::Vec3 u = frame.getOrigin(); - Matrix3 tilde_u = getTildeMatrix(u); - Matrix3 tilde_u_R = tilde_u * R; - buildCoAdjoint(R, tilde_u_R, co_adjoint); + Mat6x6 &co_adjoint) { + Matrix3 R = extractRotMatrix(frame); + Vec3 u = frame.getOrigin(); + Matrix3 tilde_u = getTildeMatrix(u); + Matrix3 tilde_u_R = tilde_u * R; + buildCoAdjoint(R, tilde_u_R, co_adjoint); } template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, - Mat6x6 &adjoint) -{ - Matrix3 tildeMat = getTildeMatrix(type::Vec3(eta[0], eta[1], eta[2])); - adjoint.setsub(0, 0, tildeMat); - adjoint.setsub(3, 3, tildeMat); - adjoint.setsub(3, 0, getTildeMatrix(type::Vec3(eta[3], eta[4], eta[5]))); + Mat6x6 &adjoint) { + Matrix3 tildeMat = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); + adjoint.setsub(0, 0, tildeMat); + adjoint.setsub(3, 3, tildeMat); + adjoint.setsub(3, 0, getTildeMatrix(Vec3(eta[3], eta[4], eta[5]))); } template <class TIn1, class TIn2, class TOut> Matrix4 BaseCosserat<TIn1, TIn2, TOut>::computeLogarithm(const double &x, - const Mat4x4 &gX) -{ - // Compute theta before everything - const double theta = computeTheta(x, gX); - Mat4x4 I4; - I4.identity(); - Mat4x4 log_gX; - - double csc_theta = 1.0 / (sin(x * theta / 2.0)); - double sec_theta = 1.0 / (cos(x * theta / 2.0)); - double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; - double x_theta = x * theta; - double cos_2XTheta = cos(2.0 * x_theta); - double cos_XTheta = cos(x_theta); - double sin_2XTheta = sin(2.0 * x_theta); - double sin_XTheta = sin(x_theta); - - if (theta <= std::numeric_limits<double>::epsilon()) - log_gX = I4; - else { - log_gX = cst * ((x_theta * cos_2XTheta - sin_XTheta) * I4 - - (x_theta * cos_XTheta + 2.0 * x_theta * cos_2XTheta - - sin_XTheta - sin_2XTheta) * - gX + - (2.0 * x_theta * cos_XTheta + x_theta * cos_2XTheta - - sin_XTheta - sin_2XTheta) * - (gX * gX) - - (x_theta * cos_XTheta - sin_XTheta) * (gX * gX * gX)); - } - - return log_gX; + const Mat4x4 &gX) { + // Compute theta before everything + const double theta = computeTheta(x, gX); + Mat4x4 I4; + I4.identity(); + Mat4x4 log_gX; + + double csc_theta = 1.0 / (sin(x * theta / 2.0)); + double sec_theta = 1.0 / (cos(x * theta / 2.0)); + double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; + double x_theta = x * theta; + double cos_2XTheta = cos(2.0 * x_theta); + double cos_XTheta = cos(x_theta); + double sin_2XTheta = sin(2.0 * x_theta); + double sin_XTheta = sin(x_theta); + + if (theta <= std::numeric_limits<double>::epsilon()) + log_gX = I4; + else { + log_gX = cst * ((x_theta * cos_2XTheta - sin_XTheta) * I4 - + (x_theta * cos_XTheta + 2.0 * x_theta * cos_2XTheta - + sin_XTheta - sin_2XTheta) * + gX + + (2.0 * x_theta * cos_XTheta + x_theta * cos_2XTheta - + sin_XTheta - sin_2XTheta) * + (gX * gX) - + (x_theta * cos_XTheta - sin_XTheta) * (gX * gX * gX)); + } + + return log_gX; } template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::updateTangExpSE3( const In1VecCoord &inDeform) { - // Curv abscissa of nodes and frames - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_section = - d_curv_abs_section; - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = - d_curv_abs_frames; - - m_framesTangExpVectors.clear(); - unsigned int sz = curv_abs_frames.size(); - // Compute tangExpo at frame points - for (unsigned int i = 0; i < sz; i++) { - Tangent temp; - - Coord1 strain_frame_i = inDeform[m_indicesVectors[i] - 1]; - double curv_abs_x_i = m_framesLengthVectors[i]; - computeTangExp(curv_abs_x_i, strain_frame_i, temp); - - m_framesTangExpVectors.push_back(temp); + // Curv abscissa of nodes and frames + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = + d_curv_abs_section; + sofa::helper::ReadAccessor<sofa::Data<sofa::type::vector<double>>> curv_abs_frames = + d_curv_abs_frames; + + m_framesTangExpVectors.clear(); + unsigned int sz = curv_abs_frames.size(); + // Compute tangExpo at frame points + for (unsigned int i = 0; i < sz; i++) { + Tangent temp; + + Coord1 strain_frame_i = inDeform[m_indicesVectors[i] - 1]; + double curv_abs_x_i = m_framesLengthVectors[i]; + computeTangExp(curv_abs_x_i, strain_frame_i, temp); + + m_framesTangExpVectors.push_back(temp); + + if (d_debug.getValue()) { + printf("__________________________________________\n"); + std::cout << "x :" << curv_abs_x_i << "; k :" << strain_frame_i + << std::endl; + std::cout << "m_framesTangExpVectors :" << m_framesTangExpVectors[i] + << std::endl; + } + } + // Compute the TangExpSE3 at the nodes + m_nodesTangExpVectors.clear(); + Tangent tangExpO; + tangExpO.clear(); + m_nodesTangExpVectors.push_back(tangExpO); + + for (size_t j = 1; j < curv_abs_section.size(); j++) { + Coord1 strain_node_i = inDeform[j - 1]; + double x = m_BeamLengthVectors[j - 1]; + Tangent temp; + temp.clear(); + computeTangExp(x, strain_node_i, temp); + m_nodesTangExpVectors.push_back(temp); + } if (d_debug.getValue()) { - printf("__________________________________________\n"); - std::cout << "x :" << curv_abs_x_i << "; k :" << strain_frame_i - << std::endl; - std::cout << "m_framesTangExpVectors :" << m_framesTangExpVectors[i] - << std::endl; + printf("_________________Node TangExpo___________________\n"); + std::cout << "Node TangExpo : " << m_nodesTangExpVectors << std::endl; } - } - - // Compute the TangExpSE3 at the nodes - m_nodesTangExpVectors.clear(); - Tangent tangExpO; - tangExpO.clear(); - m_nodesTangExpVectors.push_back(tangExpO); - - for (size_t j = 1; j < curv_abs_section.size(); j++) { - Coord1 strain_node_i = inDeform[j - 1]; - double x = m_BeamLengthVectors[j - 1]; - Tangent temp; - temp.clear(); - computeTangExp(x, strain_node_i, temp); - m_nodesTangExpVectors.push_back(temp); - } - if (d_debug.getValue()) { - printf("_________________Node TangExpo___________________\n"); - std::cout << "Node TangExpo : " << m_nodesTangExpVectors << std::endl; - } } template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, - const Coord1 &strain_i, - Mat6x6 &TgX) { - - SReal theta = type::Vec3(strain_i(0), strain_i(1), strain_i(2)) - .norm(); // Sometimes this is computed over all strain - Matrix3 tilde_k = - getTildeMatrix(type::Vec3(strain_i(0), strain_i(1), strain_i(2))); - /* Younes @23-11-27 + const Coord1 &strain_i, + Mat6x6 &TgX) { + + SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) + .norm(); // Sometimes this is computed over all strain + Matrix3 tilde_k = + getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); + /* Younes @23-11-27 old version @Todo ???? is p the linear deformation? If so, why didn't I just put a zero vector in place of p and the first element of p is equal to 1? Matrix3 tilde_p @@ -309,230 +305,232 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, bring any difference in my three reference scenes, but need more investogation #TECHNICAL_DEBT */ - Matrix3 tilde_q = getTildeMatrix(type::Vec3(0.0, 0.0, 0.0)); - - Mat6x6 ad_Xi; - buildAdjoint(tilde_k, tilde_q, ad_Xi); - - Mat6x6 Id6 = Mat6x6::Identity(); - // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 - - if (theta <= std::numeric_limits<double>::epsilon()) { - double scalar0 = std::pow(curv_abs_n, 2) / 2.0; - TgX = curv_abs_n * Id6 + scalar0 * ad_Xi; - } else { - double scalar1 = (4.0 - 4.0 * cos(curv_abs_n * theta) - - curv_abs_n * theta * sin(curv_abs_n * theta)) / - (2.0 * theta * theta); - double scalar2 = (4.0 * curv_abs_n * theta + - curv_abs_n * theta * cos(curv_abs_n * theta) - - 5.0 * sin(curv_abs_n * theta)) / - (2.0 * theta * theta * theta); - double scalar3 = (2.0 - 2.0 * cos(curv_abs_n * theta) - - curv_abs_n * theta * sin(curv_abs_n * theta)) / - (2.0 * theta * theta * theta * theta); - double scalar4 = (2.0 * curv_abs_n * theta + - curv_abs_n * theta * cos(curv_abs_n * theta) - - 3.0 * sin(curv_abs_n * theta)) / - (2.0 * theta * theta * theta * theta * theta); - - TgX = curv_abs_n * Id6 + scalar1 * ad_Xi + scalar2 * ad_Xi * ad_Xi + - scalar3 * ad_Xi * ad_Xi * ad_Xi + - scalar4 * ad_Xi * ad_Xi * ad_Xi * ad_Xi; - } -} - -template <class TIn1, class TIn2, class TOut> -[[maybe_unused]] type::Vec6 -BaseCosserat<TIn1, TIn2, TOut>::computeETA(const type::Vec6 &baseEta, - const In1VecDeriv &k_dot, - const double abs_input) { - - // Fill the initial vector - const In1DataVecCoord *x1fromData = - m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + Matrix3 tilde_q = getTildeMatrix(Vec3(0.0, 0.0, 0.0)); - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_input = - d_curv_abs_section; - // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_output = - // d_curv_abs_frames; + Mat6x6 ad_Xi; + buildAdjoint(tilde_k, tilde_q, ad_Xi); - Transform out_Trans; - Mat6x6 Adjoint, Tg; + Mat6x6 Id6 = Mat6x6::Identity(); + // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 - type::Vec6 Xi_dot; - for (unsigned int i = 0; i < 3; i++) - Xi_dot[i] = k_dot[m_index_input][i]; - - double diff0; - double _diff0; + if (theta <= std::numeric_limits<double>::epsilon()) { + double scalar0 = std::pow(curv_abs_n, 2) / 2.0; + TgX = curv_abs_n * Id6 + scalar0 * ad_Xi; + } else { + double scalar1 = (4.0 - 4.0 * cos(curv_abs_n * theta) - + curv_abs_n * theta * sin(curv_abs_n * theta)) / + (2.0 * theta * theta); + double scalar2 = (4.0 * curv_abs_n * theta + + curv_abs_n * theta * cos(curv_abs_n * theta) - + 5.0 * sin(curv_abs_n * theta)) / + (2.0 * theta * theta * theta); + double scalar3 = (2.0 - 2.0 * cos(curv_abs_n * theta) - + curv_abs_n * theta * sin(curv_abs_n * theta)) / + (2.0 * theta * theta * theta * theta); + double scalar4 = (2.0 * curv_abs_n * theta + + curv_abs_n * theta * cos(curv_abs_n * theta) - + 3.0 * sin(curv_abs_n * theta)) / + (2.0 * theta * theta * theta * theta * theta); + + TgX = curv_abs_n * Id6 + scalar1 * ad_Xi + scalar2 * ad_Xi * ad_Xi + + scalar3 * ad_Xi * ad_Xi * ad_Xi + + scalar4 * ad_Xi * ad_Xi * ad_Xi * ad_Xi; + } +} - if (m_index_input == 0) { - diff0 = abs_input; // - _diff0 = -abs_input; - } else { - diff0 = abs_input - curv_abs_input[m_index_input - 1]; - _diff0 = curv_abs_input[m_index_input - 1] - abs_input; - } +template <class TIn1, class TIn2, class TOut> +[[maybe_unused]] Vec6 +BaseCosserat<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, + const In1VecDeriv &k_dot, + const double abs_input) { + + // Fill the initial vector + const In1DataVecCoord *x1fromData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_input = + d_curv_abs_section; + // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_output = + // d_curv_abs_frames; + + Transform out_Trans; + Mat6x6 Adjoint, Tg; + + sofa::type::Vec6 Xi_dot; + for (unsigned int i = 0; i < 3; i++) + Xi_dot[i] = k_dot[m_index_input][i]; + + double diff0; + double _diff0; + + if (m_index_input == 0) { + diff0 = abs_input; // + _diff0 = -abs_input; + } else { + diff0 = abs_input - curv_abs_input[m_index_input - 1]; + _diff0 = curv_abs_input[m_index_input - 1] - abs_input; + } - computeExponentialSE3(_diff0, x1from[m_index_input], out_Trans); - computeAdjoint(out_Trans, Adjoint); + computeExponentialSE3(_diff0, x1from[m_index_input], out_Trans); + computeAdjoint(out_Trans, Adjoint); - computeTangExp(diff0, x1from[m_index_input], Tg); + computeTangExp(diff0, x1from[m_index_input], Tg); - return Adjoint * (baseEta + Tg * Xi_dot); + return Adjoint * (baseEta + Tg * Xi_dot); } //___________________________________________________________________________ template <class TIn1, class TIn2, class TOut> void BaseCosserat<TIn1, TIn2, TOut>::initialize() { - // For each frame in the global frame, find the segment of the beam to which - // it is attached. Here we only use the information from the curvilinear - // abscissa of each frame. - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_section = - d_curv_abs_section; - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = - d_curv_abs_frames; - - size_t sz = d_curv_abs_frames.getValue().size(); - - if (d_debug.getValue()) - msg_info("BaseCosserat:") - << " curv_abs_section " << d_curv_abs_frames.getValue().size() - << "; curv_abs_frames: " << d_curv_abs_frames.getValue().size(); - - m_indicesVectors.clear(); - m_framesLengthVectors.clear(); - m_BeamLengthVectors.clear(); - m_indicesVectorsDraw.clear(); - - size_t input_index = 1; - - for (size_t i = 0; i < sz; i++) { - if (curv_abs_section[input_index] > curv_abs_frames[i]) { - m_indicesVectors.emplace_back(input_index); - m_indicesVectorsDraw.emplace_back( - input_index); // maybe I shouldn't do this here !!! - } else if (curv_abs_section[input_index] == curv_abs_frames[i]) { - m_indicesVectors.emplace_back(input_index); - input_index++; - m_indicesVectorsDraw.emplace_back(input_index); - } else { - input_index++; - m_indicesVectors.emplace_back(input_index); - m_indicesVectorsDraw.emplace_back(input_index); + // For each frame in the global frame, find the segment of the beam to which + // it is attached. Here we only use the information from the curvilinear + // abscissa of each frame. + sofa::helper::ReadAccessor<sofa::Data<sofa::type::vector<double>>> curv_abs_section = + d_curv_abs_section; + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = + d_curv_abs_frames; + + size_t sz = d_curv_abs_frames.getValue().size(); + + if (d_debug.getValue()) + msg_info("BaseCosserat:") + << " curv_abs_section " << d_curv_abs_frames.getValue().size() + << "; curv_abs_frames: " << d_curv_abs_frames.getValue().size(); + + m_indicesVectors.clear(); + m_framesLengthVectors.clear(); + m_BeamLengthVectors.clear(); + m_indicesVectorsDraw.clear(); + + size_t input_index = 1; + + for (size_t i = 0; i < sz; i++) { + if (curv_abs_section[input_index] > curv_abs_frames[i]) { + m_indicesVectors.emplace_back(input_index); + m_indicesVectorsDraw.emplace_back( + input_index); // maybe I shouldn't do this here !!! + } else if (curv_abs_section[input_index] == curv_abs_frames[i]) { + m_indicesVectors.emplace_back(input_index); + input_index++; + m_indicesVectorsDraw.emplace_back(input_index); + } else { + input_index++; + m_indicesVectors.emplace_back(input_index); + m_indicesVectorsDraw.emplace_back(input_index); + } + // Fill the vector m_framesLengthVectors with the distance + // between frame(output) and the closest beam node toward the base + // m_framesLengthVectors.push_back(curv_abs_frames[i] - + // curv_abs_section[m_indicesVectors[i] - 1]); + m_framesLengthVectors.emplace_back( + curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); + } + + for (size_t j = 0; j < curv_abs_section.size() - 1; j++) { + m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - + curv_abs_section[j]); + } + + if (d_debug.getValue()) { + msg_info("BaseCosserat:") << "m_indicesVectors : " << m_indicesVectors; + msg_info("BaseCosserat:") + << "m_framesLengthVectors : " << m_framesLengthVectors; + msg_info("BaseCosserat:") + << "m_BeamLengthVectors : " << m_BeamLengthVectors; } - // Fill the vector m_framesLengthVectors with the distance - // between frame(output) and the closest beam node toward the base - // m_framesLengthVectors.push_back(curv_abs_frames[i] - - // curv_abs_section[m_indicesVectors[i] - 1]); - m_framesLengthVectors.emplace_back( - curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); - } - - for (size_t j = 0; j < curv_abs_section.size() - 1; j++) { - m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - - curv_abs_section[j]); - } - - if (d_debug.getValue()) { - msg_info("BaseCosserat:") << "m_indicesVectors : " << m_indicesVectors; - msg_info("BaseCosserat:") - << "m_framesLengthVectors : " << m_framesLengthVectors; - msg_info("BaseCosserat:") - << "m_BeamLengthVectors : " << m_BeamLengthVectors; - } } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::draw(const core::visual::VisualParams *) -{ -} +void BaseCosserat<TIn1, TIn2, TOut>::draw(const sofa::core::visual::VisualParams *) {} template <class TIn1, class TIn2, class TOut> -double BaseCosserat<TIn1, TIn2, TOut>::computeTheta(const double &x, const Mat4x4 &gX){ +double BaseCosserat<TIn1, TIn2, TOut>::computeTheta(const double &x, + const Mat4x4 &gX) { double Tr_gx = 0.0; - for (int i = 0; i<4; i++) { + for (int i = 0; i < 4; i++) { Tr_gx += gX[i][i]; } double theta; - if( x <= std::numeric_limits<double>::epsilon()) theta = 0.0; - else theta = (1.0/x) * std::acos((Tr_gx/2.0) -1); + if (x <= std::numeric_limits<double>::epsilon()) + theta = 0.0; + else + theta = (1.0 / x) * std::acos((Tr_gx / 2.0) - 1); - return theta; + return theta; } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R){ +void BaseCosserat<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R) { // TODO(dmarchal: 2024/06/07): Remove the use of printf in addition to - // reconsider the implementation of common utility functions in instance method. - for (unsigned int k = 0; k < 6 ; k++) { + // reconsider the implementation of common utility functions in instance + // method. + for (unsigned int k = 0; k < 6; k++) { for (unsigned int i = 0; i < 6; i++) - printf(" %lf",R[k][i]); + printf(" %lf", R[k][i]); printf("\n"); } } template <class TIn1, class TIn2, class TOut> -Matrix3 BaseCosserat<TIn1, TIn2, TOut>::extractRotMatrix(const Transform & frame) -{ +Matrix3 +BaseCosserat<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { - type::Quat q = frame.getOrientation(); + sofa::type::Quat q = frame.getOrientation(); - // TODO(dmarchal: 2024/06/07) The following code should probably become utility function - // building a 3x3 matix from a quaternion should probably does not need this amount of code. + // TODO(dmarchal: 2024/06/07) The following code should probably become + // utility function building a 3x3 matix from a quaternion should probably + // does not need this amount of code. Real R[4][4]; q.buildRotationMatrix(R); Matrix3 mat; - for (unsigned int k = 0; k < 3 ; k++) + for (unsigned int k = 0; k < 3; k++) for (unsigned int i = 0; i < 3; i++) mat[k][i] = R[k][i]; - return mat; + return mat; } - template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildProjector(const Transform &T) -> Tangent -{ +auto BaseCosserat<TIn1, TIn2, TOut>::buildProjector(const Transform &T) + -> Tangent { Mat6x6 P; - // TODO(dmarchal: 2024/06/07) The following code should probably become utility function - // building a 3x3 matix from a quaternion should probably does not need this amount of code. - Real R[4][4]; (T.getOrientation()).buildRotationMatrix(R); - for (unsigned int i = 0; i < 3; i++) { + // TODO(dmarchal: 2024/06/07) The following code should probably become + // utility function building a 3x3 matix from a quaternion should probably + // does not need this amount of code. + Real R[4][4]; + (T.getOrientation()).buildRotationMatrix(R); + for (unsigned int i = 0; i < 3; i++) { for (unsigned int j = 0; j < 3; j++) { - P[i][j+3] = R[i][j]; - P[i+3][j] = R[i][j]; + P[i][j + 3] = R[i][j]; + P[i + 3][j] = R[i][j]; } } - return P; + return P; } - template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildXiHat(const Coord1 & strain_i) -> se3 -{ +auto BaseCosserat<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) -> se3 { se3 Xi_hat; Xi_hat[0][1] = -strain_i(2); Xi_hat[0][2] = strain_i[1]; Xi_hat[1][2] = -strain_i[0]; - Xi_hat[1][0] = -Xi_hat(0,1); - Xi_hat[2][0] = -Xi_hat(0,2); - Xi_hat[2][1] = -Xi_hat(1,2); + Xi_hat[1][0] = -Xi_hat(0, 1); + Xi_hat[2][0] = -Xi_hat(0, 2); + Xi_hat[2][1] = -Xi_hat(1, 2); //@TODO: Why this , if q = 0 ???? Xi_hat[0][3] = 1.0; - return Xi_hat; + return Xi_hat; } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::getTildeMatrix(const type::Vec3 & u) -> Matrix3 -{ - type::Matrix3 tild; +auto BaseCosserat<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) + -> Matrix3 { + sofa::type::Matrix3 tild; tild[0][1] = -u[2]; tild[0][2] = u[1]; tild[1][2] = -u[0]; @@ -540,56 +538,59 @@ auto BaseCosserat<TIn1, TIn2, TOut>::getTildeMatrix(const type::Vec3 & u) -> Mat tild[1][0] = -tild[0][1]; tild[2][0] = -tild[0][2]; tild[2][1] = -tild[1][2]; - return tild; + return tild; } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & Adjoint) -> void -{ +auto BaseCosserat<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, + const Matrix3 &B, + Mat6x6 &Adjoint) -> void { Adjoint.clear(); for (unsigned int i = 0; i < 3; i++) { - for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j - Adjoint [i][j]= A[i][j]; - Adjoint [i+3][j+3]= A[i][j]; - Adjoint [i+3][j]= B[i][j]; + for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j + Adjoint[i][j] = A[i][j]; + Adjoint[i + 3][j + 3] = A[i][j]; + Adjoint[i + 3][j] = B[i][j]; } } } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, const Matrix3 & B, Mat6x6 & coAdjoint) -> void -{ +auto BaseCosserat<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, + const Matrix3 &B, + Mat6x6 &coAdjoint) -> void { coAdjoint.clear(); for (unsigned int i = 0; i < 3; i++) { for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j - coAdjoint [i][j]= A[i][j]; - coAdjoint [i+3][j+3]= A[i][j]; + coAdjoint[i][j] = A[i][j]; + coAdjoint[i + 3][j + 3] = A[i][j]; - // TODO(dmarchal: 2024/06/07) if co-adjoint is juste this single change (the j+3) - coAdjoint [i][j+3]= B[i][j]; + // TODO(dmarchal: 2024/06/07) if co-adjoint is juste this single change + // (the j+3) + coAdjoint[i][j + 3] = B[i][j]; } } } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4(const Transform & T) -> Matrix4 -{ - Matrix4 M; M.identity(); +auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( + const Transform &T) -> Matrix4 { + Matrix4 M; + M.identity(); Matrix3 R = extractRotMatrix(T); - type::Vec3 trans = T.getOrigin(); + sofa::type::Vec3 trans = T.getOrigin(); for (unsigned int i = 0; i < 3; i++) { - for (unsigned int j=0; j<3; j++){ - M(i,j) = R[i][j]; - M(i,3) = trans[i]; + for (unsigned int j = 0; j < 3; j++) { + M(i, j) = R[i][j]; + M(i, 3) = trans[i]; } } return M; } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3& g_x) -> Vec6 -{ +auto BaseCosserat<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3 &g_x) -> Vec6 { _SE3 Xi_hat; double x = 1.0; @@ -608,13 +609,20 @@ auto BaseCosserat<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3& g_x) -> Vec6 Matrix4d gp2 = g_x * g_x; Matrix4d gp3 = gp2 * g_x; - Xi_hat = 1.0 / x * (0.125 * (1.0 / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0)) * std::cos(x_theta / 2.0) * - ((t5 - sin_x_theta) * Matrix4d::Identity() - (x_theta * cos_x_theta + 2 * t5 - sin_x_theta - t3) * g_x + - (2 * x_theta * cos_x_theta + t5 - sin_x_theta - t3) * gp2 - (x_theta * cos_x_theta - sin_x_theta) * gp3)); + Xi_hat = 1.0 / x * + (0.125 * + (1.0 / std::sin(x_theta / 2.0) / std::sin(x_theta / 2.0) / + std::sin(x_theta / 2.0)) * + std::cos(x_theta / 2.0) * + ((t5 - sin_x_theta) * Matrix4d::Identity() - + (x_theta * cos_x_theta + 2 * t5 - sin_x_theta - t3) * g_x + + (2 * x_theta * cos_x_theta + t5 - sin_x_theta - t3) * gp2 - + (x_theta * cos_x_theta - sin_x_theta) * gp3)); } - Vec6 xci = Vec6(Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), Xi_hat(1, 3), Xi_hat(2, 3)); + Vec6 xci = Vec6(Xi_hat(2, 1), Xi_hat(0, 2), Xi_hat(1, 0), Xi_hat(0, 3), + Xi_hat(1, 3), Xi_hat(2, 3)); return xci; } -} // namespace sofa::component::mapping +} // namespace cosserat::mapping diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.cpp b/src/Cosserat/mapping/DifferenceMultiMapping.cpp index 1f295088..d6bc2a22 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.cpp +++ b/src/Cosserat/mapping/DifferenceMultiMapping.cpp @@ -25,13 +25,13 @@ #include <sofa/defaulttype/VecTypes.h> #include <sofa/core/ObjectFactory.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using namespace sofa::defaulttype; // Register in the Factory -int DifferenceMultiMappingClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") +int DifferenceMultiMappingClass = sofa::core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") .add< DifferenceMultiMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types, sofa::defaulttype::Vec3Types > >() ; diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.h b/src/Cosserat/mapping/DifferenceMultiMapping.h index 6cc0ab51..bf94fe50 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.h +++ b/src/Cosserat/mapping/DifferenceMultiMapping.h @@ -20,8 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <Cosserat/config.h> - +#include <Cosserat/initCosserat.h> #include <Cosserat/mapping/BaseCosserat.h> #include <sofa/core/BaseMapping.h> @@ -31,7 +30,7 @@ #include <sofa/defaulttype/RigidTypes.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using sofa::defaulttype::SolidTypes ; using sofa::core::objectmodel::BaseContext ; @@ -39,8 +38,10 @@ using sofa::type::Matrix3; using sofa::type::Matrix4; using sofa::type::Vec3; using sofa::type::Vec6; +using sofa::type::Quat; using std::get; -using type::vector; +using sofa::type::vector; +using Cosserat::mapping::BaseCosserat; /*! * \class DifferenceMultiMapping @@ -49,15 +50,14 @@ using type::vector; * This is a component: * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ -using mapping::BaseCosserat; - template <class TIn1, class TIn2, class TOut> -class DifferenceMultiMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> //, public component::mapping::BaseCosserat<TIn1, TIn2, TOut> +class DifferenceMultiMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> { public: - SOFA_CLASS(SOFA_TEMPLATE3(DifferenceMultiMapping, TIn1,TIn2, TOut), SOFA_TEMPLATE3(core::Multi2Mapping, TIn1, TIn2, TOut) ); - typedef core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; + SOFA_CLASS(SOFA_TEMPLATE3(DifferenceMultiMapping, TIn1,TIn2, TOut), + SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut) ); + typedef sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; /// Input Model Type typedef TIn1 In1; @@ -71,9 +71,9 @@ class DifferenceMultiMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> //, typedef typename In1::VecCoord In1VecCoord; typedef typename In1::VecDeriv In1VecDeriv; typedef typename In1::MatrixDeriv In1MatrixDeriv; - typedef Data<In1VecCoord> In1DataVecCoord; - typedef Data<In1VecDeriv> In1DataVecDeriv; - typedef Data<In1MatrixDeriv> In1DataMatrixDeriv; + typedef sofa::Data<In1VecCoord> In1DataVecCoord; + typedef sofa::Data<In1VecDeriv> In1DataVecDeriv; + typedef sofa::Data<In1MatrixDeriv> In1DataMatrixDeriv; typedef sofa::defaulttype::Rigid3dTypes::Coord Rigid; @@ -83,36 +83,36 @@ class DifferenceMultiMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> //, typedef typename In2::VecCoord In2VecCoord; typedef typename In2::VecDeriv In2VecDeriv; typedef typename In2::MatrixDeriv In2MatrixDeriv; - typedef Data<In2VecCoord> In2DataVecCoord; - typedef Data<In2VecDeriv> In2DataVecDeriv; - typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; - typedef type::Mat<4,4,Real> Mat4x4; + typedef sofa::Data<In2VecCoord> In2DataVecCoord; + typedef sofa::Data<In2VecDeriv> In2DataVecDeriv; + typedef sofa::Data<In2MatrixDeriv> In2DataMatrixDeriv; + typedef sofa::type::Mat<4,4,Real> Mat4x4; typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; typedef typename Out::Deriv OutDeriv; typedef typename Out::VecDeriv OutVecDeriv; typedef typename Out::MatrixDeriv OutMatrixDeriv; - typedef Data<OutVecCoord> OutDataVecCoord; - typedef Data<OutVecDeriv> OutDataVecDeriv; - typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; + typedef sofa::Data<OutVecCoord> OutDataVecCoord; + typedef sofa::Data<OutVecDeriv> OutDataVecDeriv; + typedef sofa::Data<OutMatrixDeriv> OutDataMatrixDeriv; typedef typename SolidTypes<Real>::Transform Transform ; public: /********************** The component Data **************************/ //Input data - Data<vector<Rigid>> d_direction; - Data<vector<unsigned int>> d_indices; - Data<double> d_radius; - Data<sofa::type::Vec4f> d_color; - Data<bool> d_drawArrows; - Data<bool> d_lastPointIsFixed; + sofa::Data<vector<Rigid>> d_direction; + sofa::Data<vector<unsigned int>> d_indices; + sofa::Data<double> d_radius; + sofa::Data<sofa::type::Vec4f> d_color; + sofa::Data<bool> d_drawArrows; + sofa::Data<bool> d_lastPointIsFixed; protected: - core::State<In1>* m_fromModel1; - core::State<In2>* m_fromModel2; - core::State<Out>* m_toModel; + sofa::core::State<In1>* m_fromModel1; + sofa::core::State<In2>* m_fromModel2; + sofa::core::State<Out>* m_toModel; protected: /// Constructor @@ -126,32 +126,32 @@ class DifferenceMultiMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> //, void bwdInit() override; // get the points void reset() override; void reinit() override; - void draw(const core::visual::VisualParams* vparams) override; + void draw(const sofa::core::visual::VisualParams* vparams) override; /**********************MAPPING METHODS**************************/ void apply( - const core::MechanicalParams* /* mparams */, const type::vector<OutDataVecCoord*>& dataVecOutPos, - const type::vector<const In1DataVecCoord*>& dataVecIn1Pos , - const type::vector<const In2DataVecCoord*>& dataVecIn2Pos) override; + const sofa::core::MechanicalParams* /* mparams */, const vector<OutDataVecCoord*>& dataVecOutPos, + const vector<const In1DataVecCoord*>& dataVecIn1Pos , + const vector<const In2DataVecCoord*>& dataVecIn2Pos) override; void applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; + const sofa::core::MechanicalParams* /* mparams */, const vector< OutDataVecDeriv*>& dataVecOutVel, + const vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; //ApplyJT Force void applyJT( - const core::MechanicalParams* /* mparams */, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2RootForce, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) override; + const sofa::core::MechanicalParams* /* mparams */, const vector< In1DataVecDeriv*>& dataVecOut1Force, + const vector< In2DataVecDeriv*>& dataVecOut2RootForce, + const vector<const OutDataVecDeriv*>& dataVecInForce) override; - void applyDJT(const core::MechanicalParams* /*mparams*/, core::MultiVecDerivId /*inForce*/, core::ConstMultiVecDerivId /*outForce*/) override{} + void applyDJT(const sofa::core::MechanicalParams* /*mparams*/, sofa::core::MultiVecDerivId /*inForce*/, sofa::core::ConstMultiVecDerivId /*outForce*/) override{} /// This method must be reimplemented by all mappings if they need to support constraints. void applyJT( - const core::ConstraintParams* cparams , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const , - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) override; + const sofa::core::ConstraintParams* cparams , const vector< In1DataMatrixDeriv*>& dataMatOut1Const , + const vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const vector<const OutDataMatrixDeriv*>& dataMatInConst) override; /**********************MAPPING METHODS**************************/ void initiateTopologies(); @@ -178,7 +178,7 @@ class DifferenceMultiMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> //, Real thirdConstraint; } Constraint; - type::vector<Constraint> m_constraints; + vector<Constraint> m_constraints; }; } // sofa::component::mapping diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.inl b/src/Cosserat/mapping/DifferenceMultiMapping.inl index c9540d2e..d86f5b79 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.inl +++ b/src/Cosserat/mapping/DifferenceMultiMapping.inl @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include "DifferenceMultiMapping.h" +#include <cosserat/mapping/DifferenceMultiMapping.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/visual/VisualParams.h> @@ -33,710 +33,692 @@ #include <string> -namespace sofa::component::mapping +namespace Cosserat::mapping { - using sofa::core::objectmodel::BaseContext; - using sofa::helper::AdvancedTimer; - using sofa::helper::WriteAccessor; - using sofa::type::RGBAColor; - - template <class TIn1, class TIn2, class TOut> - DifferenceMultiMapping<TIn1, TIn2, TOut>::DifferenceMultiMapping() - : d_direction(initData(&d_direction, "direction", "The list of directions of fix points .\n")), - d_indices(initData(&d_indices, "indices", "Indices of fixe points of the cable")), - d_radius(initData(&d_radius, 2.0, "radius", "The size of the cable")), - d_color(initData(&d_color, type::Vec4f(1, 0, 0, 1), "color", "The color of the cable")), - d_drawArrows(initData(&d_drawArrows, false, "drawArrows", "The color of the cable")), - d_lastPointIsFixed(initData(&d_lastPointIsFixed, true, "lastPointIsFixed", "This select the last point as fixed of not," - "one.")), - m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL) +using sofa::core::objectmodel::BaseContext; +using sofa::helper::AdvancedTimer; +using sofa::helper::WriteAccessor; +using sofa::type::RGBAColor; + +template <class TIn1, class TIn2, class TOut> +DifferenceMultiMapping<TIn1, TIn2, TOut>::DifferenceMultiMapping() + : d_direction(initData(&d_direction, "direction", "The list of directions of fix points .\n")), + d_indices(initData(&d_indices, "indices", "Indices of fixe points of the cable")), + d_radius(initData(&d_radius, 2.0, "radius", "The size of the cable")), + d_color(initData(&d_color, sofa::type::Vec4f(1, 0, 0, 1), "color", "The color of the cable")), + d_drawArrows(initData(&d_drawArrows, false, "drawArrows", "The color of the cable")), + d_lastPointIsFixed(initData(&d_lastPointIsFixed, true, "lastPointIsFixed", "This select the last point as fixed of not," + "one.")), + m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL) +{ +} + +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::initiateTopologies() +{ + m_toModel = this->getToModels()[0]; + if (!m_toModel) { + std::cout << " No output mechanical state found. Consider setting the " + << this->toModels.getName() << " attribute." << std::endl; + return; } - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::initiateTopologies() - { - m_toModel = this->getToModels()[0]; - if (!m_toModel) - { - std::cout << " No output mechanical state found. Consider setting the " - << this->toModels.getName() << " attribute." << std::endl; - return; - } + if (!d_direction.isSet()) + msg_warning() << "No direction nor indices is given."; - if (!d_direction.isSet()) - msg_warning() << "No direction nor indices is given."; +} - } +// _________________________________________________________________________________________ - // _________________________________________________________________________________________ +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::init() +{ + Inherit1::init(); - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::init() + if (this->getFromModels1().empty()) { - Inherit1::init(); + msg_error() << "Error while initializing ; input getFromModels1 not found"; + return; + } - if (this->getFromModels1().empty()) - { - msg_error() << "Error while initializing ; input getFromModels1 not found"; - return; - } + if (this->getFromModels2().empty()) + { + msg_error() << "Error while initializing ; output getFromModels2 not found"; + return; + } - if (this->getFromModels2().empty()) - { - msg_error() << "Error while initializing ; output getFromModels2 not found"; - return; - } + if (this->getToModels().empty()) + { + msg_error() << "Error while initializing ; output Model not found"; + // return; + } + m_fromModel1 = this->getFromModels1()[0]; + m_fromModel2 = this->getFromModels2()[0]; + m_toModel = this->getToModels()[0]; - if (this->getToModels().empty()) - { - msg_error() << "Error while initializing ; output Model not found"; - // return; - } - m_fromModel1 = this->getFromModels1()[0]; - m_fromModel2 = this->getFromModels2()[0]; - m_toModel = this->getToModels()[0]; + m_toModel = m_fromModel1; - m_toModel = m_fromModel1; + initiateTopologies(); - initiateTopologies(); + printf("init\n"); +} - printf("init\n"); - } +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::bwdInit() +{ +} - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::bwdInit() - { - } +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::reinit() +{ +} - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::reinit() - { - } +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::reset() +{ + reinit(); +} - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::reset() - { - reinit(); - } +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::computeProximity(const In1VecCoord &x1, const In2VecCoord &x2) +{ - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::computeProximity(const In1VecCoord &x1, const In2VecCoord &x2) - { + In1VecCoord from = x1; + In2VecCoord dst = x2; + m_constraints.clear(); - In1VecCoord from = x1; - In2VecCoord dst = x2; - m_constraints.clear(); + size_t szFrom = from.size(); + size_t szDst = dst.size(); + vector<Rigid> direction = d_direction.getValue(); - size_t szFrom = from.size(); - size_t szDst = dst.size(); - type::vector<Rigid> direction = d_direction.getValue(); + /// get the last rigid direction, the main goal is to use it for the + /// 3D bilateral constraint i.e the fix point of the cable in the robot structure + // Rigid direction = d_direction.getValue()[szDst-1]; - /// get the last rigid direction, the main goal is to use it for the - /// 3D bilateral constraint i.e the fix point of the cable in the robot structure - // Rigid direction = d_direction.getValue()[szDst-1]; + // For each point in the FEM find the closest edge of the cable + for (size_t i = 0; i < szFrom; i++) + { + Coord2 P = from[i]; + Constraint constraint; - // For each point in the FEM find the closest edge of the cable - for (size_t i = 0; i < szFrom; i++) + // find the min distance between a from mstate point, and it's projection on each edge of the cable (destination mstate) + Real min_dist = std::numeric_limits<Real>::max(); + for (size_t j = 0; j < szDst - 1; j++) { - Coord2 P = from[i]; - Constraint constraint; - - // find the min distance between a from mstate point, and it's projection on each edge of the cable (destination mstate) - Real min_dist = std::numeric_limits<Real>::max(); - for (size_t j = 0; j < szDst - 1; j++) + Coord1 Q1 = dst[j]; + Coord1 Q2 = dst[j + 1]; + // the axis + Coord1 dirAxe = Q2 - Q1; + Real length = dirAxe.norm(); + Real fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); + + if (std::abs(fact_v) < min_dist) { - Coord1 Q1 = dst[j]; - Coord1 Q2 = dst[j + 1]; - // the axis - Coord1 dirAxe = Q2 - Q1; - Real length = dirAxe.norm(); - Real fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); - - if (std::abs(fact_v) < min_dist) - { - // if(fact_v < min_dist){ - min_dist = std::abs(fact_v); + // if(fact_v < min_dist){ + min_dist = std::abs(fact_v); - // define the constraint variables - Deriv1 proj; // distVec; - Real alpha; // dist; + // define the constraint variables + Deriv1 proj; // distVec; + Real alpha; // dist; - /// To solve the case that the closest node is - /// not the node 0 but the node 1 of the beam - if (fact_v < 0.0 && j != 0 && std::abs(fact_v) > 1e-8) + /// To solve the case that the closest node is + /// not the node 0 but the node 1 of the beam + if (fact_v < 0.0 && j != 0 && std::abs(fact_v) > 1e-8) + { + // if fact_v < 0.0 that means the last beam is the good beam + // printf("if fact_v < 0.0 that means the last beam is the good beam \n"); + Q1 = dst[j - 1]; + dirAxe = dst[j] - Q1; + length = dirAxe.norm(); + fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); + dirAxe.normalize(); + alpha = (P - Q1) * dirAxe; + + proj = Q1 + dirAxe * alpha; + // distVec = P - proj; // violation vector + // dist = (P - proj).norm(); // constraint violation + constraint.eid = j - 1; + // The direction of the axe or the beam + constraint.dirAxe = dirAxe; + // the node contribution to the constraint which is 1-coeff + alpha = alpha / length; // normalize, ensure that <1.0 + if (alpha < 1e-8) + constraint.alpha = 1.0; + else + constraint.alpha = 1.0 - alpha; + + // The projection on the axe + constraint.proj = proj; + constraint.Q = from[i]; + + ///// + length = (dst[j] - Q1).norm(); + constraint.Q1Q2 = length; + constraint.r2 = fact_v; + + // We move the constraint point onto the projection + Deriv1 t1 = P - proj; // violation vector + constraint.dist = t1.norm(); // constraint violation + t1.normalize(); // direction of the constraint + + //// First method compute normals using projections + // if(t1.norm()<1.0e-1 && dirAxe[2] < 0.99){ + // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1],dirAxe[2]+50.0); + // t1 = cross(dirAxe,temp); + // t1.normalize(); + // constraint.t1 = t1; + // } + // if(t1.norm()<1.0e-1){ + // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1]+50.0,dirAxe[2]); + // t1 = cross(dirAxe,temp); + // t1.normalize(); + // constraint.t1 = t1; + // } + + // if(t1.norm()<1.0e-1) + // { + + //// Second method compute normals using frames directions + Rigid dir = direction[constraint.eid]; + Vec3 vY = Vec3(0., 1., 0.); + Quat ori = dir.getOrientation(); + vY = ori.rotate(vY); + vY.normalize(); + t1 = vY; + // } + + constraint.t1 = t1; + // tangential 2 + Deriv1 t2 = cross(t1, dirAxe); t2.normalize(); + constraint.t2 = t2; + + if (i == szFrom - 1) { - // if fact_v < 0.0 that means the last beam is the good beam - // printf("if fact_v < 0.0 that means the last beam is the good beam \n"); - Q1 = dst[j - 1]; - dirAxe = dst[j] - Q1; - length = dirAxe.norm(); - fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); - dirAxe.normalize(); - alpha = (P - Q1) * dirAxe; - - proj = Q1 + dirAxe * alpha; - // distVec = P - proj; // violation vector - // dist = (P - proj).norm(); // constraint violation - constraint.eid = j - 1; - // The direction of the axe or the beam - constraint.dirAxe = dirAxe; - // the node contribution to the constraint which is 1-coeff - alpha = alpha / length; // normalize, ensure that <1.0 - if (alpha < 1e-8) - constraint.alpha = 1.0; - else - constraint.alpha = 1.0 - alpha; - - // The projection on the axe - constraint.proj = proj; - constraint.Q = from[i]; - - ///// - length = (dst[j] - Q1).norm(); - constraint.Q1Q2 = length; - constraint.r2 = fact_v; - - // We move the constraint point onto the projection - Deriv1 t1 = P - proj; // violation vector - constraint.dist = t1.norm(); // constraint violation - t1.normalize(); // direction of the constraint - - //// First method compute normals using projections - // if(t1.norm()<1.0e-1 && dirAxe[2] < 0.99){ - // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1],dirAxe[2]+50.0); - // t1 = cross(dirAxe,temp); - // t1.normalize(); - // constraint.t1 = t1; - // } - // if(t1.norm()<1.0e-1){ - // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1]+50.0,dirAxe[2]); - // t1 = cross(dirAxe,temp); - // t1.normalize(); - // constraint.t1 = t1; - // } - - // if(t1.norm()<1.0e-1) - // { - - //// Second method compute normals using frames directions - Rigid dir = direction[constraint.eid]; - type::Vec3 vY = type::Vec3(0., 1., 0.); - type::Quat ori = dir.getOrientation(); - vY = ori.rotate(vY); - vY.normalize(); - t1 = vY; - // } - - constraint.t1 = t1; - // tangential 2 - Deriv1 t2 = cross(t1, dirAxe); t2.normalize(); - constraint.t2 = t2; - - if (i == szFrom - 1) + /// This handle the fix point constraint the last point of + /// of cstr points indeed here we have + /// 3D bilateral constraint and alpha=1.0 + // We use the given direction of fill H + + if (!direction.empty()) { - /// This handle the fix point constraint the last point of - /// of cstr points indeed here we have - /// 3D bilateral constraint and alpha=1.0 - // We use the given direction of fill H - - if (!direction.empty()) - { - type::Quat _ori = direction[szDst - 1].getOrientation(); - type::Vec3 _vY = _ori.rotate(type::Vec3(0., 1., 0.)); _vY.normalize(); - type::Vec3 _vZ = _ori.rotate(type::Vec3(0., 0., 1.)); _vZ.normalize(); - - constraint.t1 = _vY; - constraint.t2 = _vZ; - } - constraint.proj = dst[szDst - 1]; - constraint.eid = szDst - 2; - constraint.alpha = 1.0; - constraint.dist = (dst[szDst - 1] - from[szFrom - 1]).norm(); + Quat _ori = direction[szDst - 1].getOrientation(); + Vec3 _vY = _ori.rotate(Vec3(0., 1., 0.)); _vY.normalize(); + Vec3 _vZ = _ori.rotate(Vec3(0., 0., 1.)); _vZ.normalize(); + + constraint.t1 = _vY; + constraint.t2 = _vZ; } + constraint.proj = dst[szDst - 1]; + constraint.eid = szDst - 2; + constraint.alpha = 1.0; + constraint.dist = (dst[szDst - 1] - from[szFrom - 1]).norm(); } + } + else + { + // compute needs for constraint + dirAxe.normalize(); + alpha = (P - Q1) * dirAxe; + + proj = Q1 + dirAxe * alpha; + // distVec = P - proj; // violation vector + // dist = (P - proj).norm(); // constraint violation + constraint.eid = j; + // The direction of the axe or the beam + constraint.dirAxe = dirAxe; + // the node contribution to the constraint which is 1-coeff + alpha = alpha / length; // normalize, ensure that <1.0 + if (alpha < 1e-8) + constraint.alpha = 1.0; else + constraint.alpha = 1.0 - alpha; + + // The projection on the axe + constraint.proj = proj; + constraint.Q = from[i]; + + ///// + constraint.Q1Q2 = length; + constraint.r2 = fact_v; + + // We move the constraint point onto the projection + Deriv1 t1 = P - proj; // violation vector + constraint.dist = t1.norm(); // constraint violation + t1.normalize(); // direction of the constraint + + /// If the violation is very small t1 is close to zero + /// + //// First method compute normals using projections + // if(t1.norm()<1.0e-1 && dirAxe[2] < 0.99){ + // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1],dirAxe[2]+50.0); + // t1 = cross(dirAxe,temp); + // t1.normalize(); + // constraint.t1 = t1; + // } + // if(t1.norm()<1.0e-1){ + // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1]+50.0,dirAxe[2]); + // t1 = cross(dirAxe,temp); + // t1.normalize(); + // constraint.t1 = t1; + // } + + //// Second method compute normals using frames directions + Vec3 vY = Vec3(0., 1., 0.); + Quat ori = (direction[szDst - 1]).getOrientation(); + vY = ori.rotate(vY); vY.normalize(); + t1 = vY; + // } + constraint.t1 = t1; + // tangential 2 + Deriv1 t2 = cross(t1, dirAxe); + t2.normalize(); + constraint.t2 = t2; + + /// This is need because we are applying the a + /// bilateral constraint on the last node of the mstate + if (i == szFrom - 1) { - // compute needs for constraint - dirAxe.normalize(); - alpha = (P - Q1) * dirAxe; - - proj = Q1 + dirAxe * alpha; - // distVec = P - proj; // violation vector - // dist = (P - proj).norm(); // constraint violation - constraint.eid = j; - // The direction of the axe or the beam - constraint.dirAxe = dirAxe; - // the node contribution to the constraint which is 1-coeff - alpha = alpha / length; // normalize, ensure that <1.0 - if (alpha < 1e-8) - constraint.alpha = 1.0; - else - constraint.alpha = 1.0 - alpha; - - // The projection on the axe - constraint.proj = proj; - constraint.Q = from[i]; - - ///// - constraint.Q1Q2 = length; - constraint.r2 = fact_v; - - // We move the constraint point onto the projection - Deriv1 t1 = P - proj; // violation vector - constraint.dist = t1.norm(); // constraint violation - t1.normalize(); // direction of the constraint - - /// If the violation is very small t1 is close to zero - /// - //// First method compute normals using projections - // if(t1.norm()<1.0e-1 && dirAxe[2] < 0.99){ - // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1],dirAxe[2]+50.0); - // t1 = cross(dirAxe,temp); - // t1.normalize(); - // constraint.t1 = t1; - // } - // if(t1.norm()<1.0e-1){ - // type::Vec3 temp = type::Vec3(dirAxe[0],dirAxe[1]+50.0,dirAxe[2]); - // t1 = cross(dirAxe,temp); - // t1.normalize(); - // constraint.t1 = t1; - // } - - //// Second method compute normals using frames directions - type::Vec3 vY = type::Vec3(0., 1., 0.); - type::Quat ori = (direction[szDst - 1]).getOrientation(); - vY = ori.rotate(vY); vY.normalize(); - t1 = vY; - // } - constraint.t1 = t1; - // tangential 2 - Deriv1 t2 = cross(t1, dirAxe); - t2.normalize(); - constraint.t2 = t2; - - /// This is need because we are applying the a - /// bilateral constraint on the last node of the mstate - if (i == szFrom - 1) + /// This handle the fix point constraint the last point of + /// of cstr points indeed here we have + /// 3D bilateral constraint and alpha=1.0 + // We use the given direction of fill H + if (!d_direction.getValue().empty()) { - /// This handle the fix point constraint the last point of - /// of cstr points indeed here we have - /// 3D bilateral constraint and alpha=1.0 - // We use the given direction of fill H - if (!d_direction.getValue().empty()) - { - type::Quat _ori = (direction[szDst - 1]).getOrientation(); - type::Vec3 _vY = _ori.rotate(type::Vec3(0., 1., 0.)); _vY.normalize(); - type::Vec3 _vZ = _ori.rotate(type::Vec3(0., 0., 1.)); _vZ.normalize(); - - constraint.t1 = _vY; - constraint.t2 = _vZ; - } - constraint.proj = dst[szDst - 1]; - constraint.eid = szDst - 2; - constraint.alpha = 1.0; - constraint.dist = (dst[szDst - 1] - from[szFrom - 1]).norm(); + Quat _ori = (direction[szDst - 1]).getOrientation(); + Vec3 _vY = _ori.rotate(Vec3(0., 1., 0.)); _vY.normalize(); + Vec3 _vZ = _ori.rotate(Vec3(0., 0., 1.)); _vZ.normalize(); + + constraint.t1 = _vY; + constraint.t2 = _vZ; } + constraint.proj = dst[szDst - 1]; + constraint.eid = szDst - 2; + constraint.alpha = 1.0; + constraint.dist = (dst[szDst - 1] - from[szFrom - 1]).norm(); } } - } - m_constraints.push_back(constraint); + } } + m_constraints.push_back(constraint); } +} - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::computeNeedleProximity(const In1VecCoord &x1, const In2VecCoord &x2) - { +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::computeNeedleProximity(const In1VecCoord &x1, const In2VecCoord &x2) +{ - In1VecCoord from = x1; - In2VecCoord dst = x2; - m_constraints.clear(); + In1VecCoord from = x1; + In2VecCoord dst = x2; + m_constraints.clear(); - size_t szFrom = from.size(); - size_t szDst = dst.size(); - type::vector<Rigid> direction = d_direction.getValue(); + size_t szFrom = from.size(); + size_t szDst = dst.size(); + vector<Rigid> direction = d_direction.getValue(); - /// get the last rigid direction, the main goal is to use it for the - /// 3D bilateral constraint i.e the fix point of the cable in the robot structure - // Rigid direction = d_direction.getValue()[szDst-1]; + /// get the last rigid direction, the main goal is to use it for the + /// 3D bilateral constraint i.e the fix point of the cable in the robot structure + // Rigid direction = d_direction.getValue()[szDst-1]; - // For each point in the FEM find the closest edge of the cable - for (size_t i = 0; i < szFrom; i++) - { - Coord2 P = from[i]; - Constraint constraint; + // For each point in the FEM find the closest edge of the cable + for (size_t i = 0; i < szFrom; i++) + { + Coord2 P = from[i]; + Constraint constraint; - // find the min distance between a from mstate point, and it's projection on each edge of the cable (destination mstate) - Real min_dist = std::numeric_limits<Real>::max(); - for (size_t j = 0; j < szDst - 1; j++) + // find the min distance between a from mstate point, and it's projection on each edge of the cable (destination mstate) + Real min_dist = std::numeric_limits<Real>::max(); + for (size_t j = 0; j < szDst - 1; j++) + { + Coord1 Q1 = dst[j]; + Coord1 Q2 = dst[j + 1]; + // the axis + Coord1 dirAxe = Q2 - Q1; + Real length = dirAxe.norm(); + Real fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); + + if (std::abs(fact_v) < min_dist) { - Coord1 Q1 = dst[j]; - Coord1 Q2 = dst[j + 1]; - // the axis - Coord1 dirAxe = Q2 - Q1; - Real length = dirAxe.norm(); - Real fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); - - if (std::abs(fact_v) < min_dist) - { - // if(fact_v < min_dist){ - min_dist = std::abs(fact_v); + // if(fact_v < min_dist){ + min_dist = std::abs(fact_v); - // define the constraint variables - Deriv1 proj; - Real alpha; + // define the constraint variables + Deriv1 proj; + Real alpha; - /// To solve the case that the closest node is - /// not the node 0 but the node 1 of the beam - if (fact_v < 0.0 && j != 0 && std::abs(fact_v) > 1e-8) - { - // if fact_v < 0.0 that means the last beam is the good beam - // printf("if fact_v < 0.0 that means the last beam is the good beam \n"); - Q1 = dst[j - 1]; - dirAxe = dst[j] - Q1; - length = dirAxe.norm(); - fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); - dirAxe.normalize(); - alpha = (P - Q1) * dirAxe; - - proj = Q1 + dirAxe * alpha; - // distVec = P - proj; // violation vector - // dist = (P - proj).norm(); // constraint violation - constraint.eid = j - 1; - // The direction of the axe or the beam - constraint.dirAxe = dirAxe; - // the node contribution to the constraint which is 1-coeff - alpha = alpha / length; // normalize, ensure that <1.0 - if (alpha < 1e-8) - constraint.alpha = 1.0; - else - constraint.alpha = 1.0 - alpha; - - // The projection on the axe - constraint.proj = proj; - constraint.Q = from[i]; - - ///// - length = (dst[j] - Q1).norm(); - constraint.Q1Q2 = length; - constraint.r2 = fact_v; - - // We move the constraint point onto the projection - Deriv1 t1 = P - proj; // violation vector - constraint.dist = t1.norm(); // constraint violation - t1.normalize(); // direction of the constraint - - //// Second method compute normals using frames directions - Rigid dir = direction[constraint.eid]; - type::Vec3 vY = type::Vec3(0., 1., 0.); - type::Quat ori = dir.getOrientation(); - vY = ori.rotate(vY); vY.normalize(); - t1 = vY; - // } - - constraint.t1 = t1; - // tangential 2 - Deriv1 t2 = cross(t1, dirAxe); - t2.normalize(); - constraint.t2 = t2; - } + /// To solve the case that the closest node is + /// not the node 0 but the node 1 of the beam + if (fact_v < 0.0 && j != 0 && std::abs(fact_v) > 1e-8) + { + // if fact_v < 0.0 that means the last beam is the good beam + // printf("if fact_v < 0.0 that means the last beam is the good beam \n"); + Q1 = dst[j - 1]; + dirAxe = dst[j] - Q1; + length = dirAxe.norm(); + fact_v = dot(P - Q1, dirAxe) / dot(dirAxe, dirAxe); + dirAxe.normalize(); + alpha = (P - Q1) * dirAxe; + + proj = Q1 + dirAxe * alpha; + // distVec = P - proj; // violation vector + // dist = (P - proj).norm(); // constraint violation + constraint.eid = j - 1; + // The direction of the axe or the beam + constraint.dirAxe = dirAxe; + // the node contribution to the constraint which is 1-coeff + alpha = alpha / length; // normalize, ensure that <1.0 + if (alpha < 1e-8) + constraint.alpha = 1.0; else - { - // compute needs for constraint - dirAxe.normalize(); - alpha = (P - Q1) * dirAxe; - - proj = Q1 + dirAxe * alpha; - // distVec = P - proj; // violation vector - // dist = (P - proj).norm(); // constraint violation - constraint.eid = j; - // The direction of the axe or the beam - constraint.dirAxe = dirAxe; - // the node contribution to the constraint which is 1-coeff - alpha = alpha / length; // normalize, ensure that <1.0 - if (alpha < 1e-8) - constraint.alpha = 1.0; - else - constraint.alpha = 1.0 - alpha; - - // The projection on the axe - constraint.proj = proj; - constraint.Q = from[i]; - - ///// - constraint.Q1Q2 = length; - constraint.r2 = fact_v; - - // We move the constraint point onto the projection - Deriv1 t1 = P - proj; // violation vector - constraint.dist = t1.norm(); // constraint violation - t1.normalize(); // direction of the constraint - - //// Second method compute normals using frames directions - Rigid dir = direction[constraint.eid]; - type::Vec3 vY = type::Vec3(0., 1., 0.); - type::Quat ori = dir.getOrientation(); - vY = ori.rotate(vY); vY.normalize(); - t1 = vY; - // } - constraint.t1 = t1; - // tangential 2 - Deriv1 t2 = cross(t1, dirAxe); t2.normalize(); - constraint.t2 = t2; - } + constraint.alpha = 1.0 - alpha; + + // The projection on the axe + constraint.proj = proj; + constraint.Q = from[i]; + + ///// + length = (dst[j] - Q1).norm(); + constraint.Q1Q2 = length; + constraint.r2 = fact_v; + + // We move the constraint point onto the projection + Deriv1 t1 = P - proj; // violation vector + constraint.dist = t1.norm(); // constraint violation + t1.normalize(); // direction of the constraint + + //// Second method compute normals using frames directions + Rigid dir = direction[constraint.eid]; + Vec3 vY = Vec3(0., 1., 0.); + Quat ori = dir.getOrientation(); + vY = ori.rotate(vY); vY.normalize(); + t1 = vY; + // } + + constraint.t1 = t1; + // tangential 2 + Deriv1 t2 = cross(t1, dirAxe); + t2.normalize(); + constraint.t2 = t2; + } + else + { + // compute needs for constraint + dirAxe.normalize(); + alpha = (P - Q1) * dirAxe; + + proj = Q1 + dirAxe * alpha; + // distVec = P - proj; // violation vector + // dist = (P - proj).norm(); // constraint violation + constraint.eid = j; + // The direction of the axe or the beam + constraint.dirAxe = dirAxe; + // the node contribution to the constraint which is 1-coeff + alpha = alpha / length; // normalize, ensure that <1.0 + if (alpha < 1e-8) + constraint.alpha = 1.0; + else + constraint.alpha = 1.0 - alpha; + + // The projection on the axe + constraint.proj = proj; + constraint.Q = from[i]; + + ///// + constraint.Q1Q2 = length; + constraint.r2 = fact_v; + + // We move the constraint point onto the projection + Deriv1 t1 = P - proj; // violation vector + constraint.dist = t1.norm(); // constraint violation + t1.normalize(); // direction of the constraint + + //// Second method compute normals using frames directions + Rigid dir = direction[constraint.eid]; + Vec3 vY = Vec3(0., 1., 0.); + Quat ori = dir.getOrientation(); + vY = ori.rotate(vY); vY.normalize(); + t1 = vY; + // } + constraint.t1 = t1; + // tangential 2 + Deriv1 t2 = cross(t1, dirAxe); t2.normalize(); + constraint.t2 = t2; } } - m_constraints.push_back(constraint); } + m_constraints.push_back(constraint); } +} - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::apply( - const core::MechanicalParams * /* mparams */, const type::vector<OutDataVecCoord *> &dataVecOutPos, - const type::vector<const In1DataVecCoord *> &dataVecIn1Pos, - const type::vector<const In2DataVecCoord *> &dataVecIn2Pos) - { +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::apply( + const sofa::core::MechanicalParams * /* mparams */, const vector<OutDataVecCoord *> &dataVecOutPos, + const vector<const In1DataVecCoord *> &dataVecIn1Pos, + const vector<const In2DataVecCoord *> &dataVecIn2Pos) +{ - if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) - return; + if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) + return; - // printf("///Do Apply//We need only one input In model and input Root model (if present) \n"); - const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); - const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); + // printf("///Do Apply//We need only one input In model and input Root model (if present) \n"); + const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); + const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); - OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); + OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); - if (d_lastPointIsFixed.getValue()) - { - computeProximity(in1, in2); + if (d_lastPointIsFixed.getValue()) + { + computeProximity(in1, in2); - // auto out = sofa::helper::writeOnly(*dataVecOutPos[0]); - size_t sz = m_constraints.size(); - out.resize(sz); + // auto out = sofa::helper::writeOnly(*dataVecOutPos[0]); + size_t sz = m_constraints.size(); + out.resize(sz); - for (unsigned int i = 0; i < sz; i++) - { - Constraint &c = m_constraints[i]; - if (i < sz - 1) - { - out[i][0] = 0.0; - out[i][1] = c.t1 * (in1[i] - c.proj); // c.dist; - out[i][2] = c.t2 * (in1[i] - c.proj); // 0.0 - } - else - { - out[sz - 1][0] = c.dirAxe * (in1[in1.size() - 1] - in2[in2.size() - 1]); - out[sz - 1][1] = c.t1 * (in1[in1.size() - 1] - in2[in2.size() - 1]); // std::abs(in2[in2.size()-1][1] - in1[in1.size()-1][1]); - out[sz - 1][2] = c.t2 * (in1[in1.size() - 1] - in2[in2.size() - 1]); // std::abs(in2[in2.size()-1][2] - in1[in1.size()-1][2]); - } - } - } - else + for (unsigned int i = 0; i < sz; i++) { - computeNeedleProximity(in1, in2); - - // auto out = sofa::helper::writeOnly(*dataVecOutPos[0]); - size_t sz = m_constraints.size(); - out.resize(sz); - - for (unsigned int i = 0; i < sz; i++) + Constraint &c = m_constraints[i]; + if (i < sz - 1) { - Constraint &c = m_constraints[i]; out[i][0] = 0.0; out[i][1] = c.t1 * (in1[i] - c.proj); // c.dist; out[i][2] = c.t2 * (in1[i] - c.proj); // 0.0 } + else + { + out[sz - 1][0] = c.dirAxe * (in1[in1.size() - 1] - in2[in2.size() - 1]); + out[sz - 1][1] = c.t1 * (in1[in1.size() - 1] - in2[in2.size() - 1]); // std::abs(in2[in2.size()-1][1] - in1[in1.size()-1][1]); + out[sz - 1][2] = c.t2 * (in1[in1.size() - 1] - in2[in2.size() - 1]); // std::abs(in2[in2.size()-1][2] - in1[in1.size()-1][2]); + } } - dataVecOutPos[0]->endEdit(); } - - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::applyJ( - const core::MechanicalParams * /* mparams */, const type::vector<OutDataVecDeriv *> &dataVecOutVel, - const type::vector<const In1DataVecDeriv *> &dataVecIn1Vel, - const type::vector<const In2DataVecDeriv *> &dataVecIn2Vel) + else { - if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) - return; - const In1VecDeriv &in1 = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv &in2 = dataVecIn2Vel[0]->getValue(); - OutVecDeriv &outVel = *dataVecOutVel[0]->beginEdit(); + computeNeedleProximity(in1, in2); - // const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); + // auto out = sofa::helper::writeOnly(*dataVecOutPos[0]); size_t sz = m_constraints.size(); - outVel.resize(sz); - - if (d_lastPointIsFixed.getValue()) + out.resize(sz); + + for (unsigned int i = 0; i < sz; i++) { - for (size_t i = 0; i < sz; i++) - { - Constraint &c = m_constraints[i]; - int ei1 = c.eid; - int ei2 = c.eid + 1; - if (i < sz - 1) - { - Real v0 = c.dirAxe * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); - Real v1 = c.t1 * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); - Real v2 = c.t2 * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); - outVel[i] = OutDeriv(v0, v1, v2); - } - else - { - Real v0 = c.dirAxe * (in1[i] - in2[ei2]); - Real v1 = c.t1 * (in1[i] - in2[ei2]); - Real v2 = c.t2 * (in1[i] - in2[ei2]); - outVel[i] = OutDeriv(v0, v1, v2); - } - } + Constraint &c = m_constraints[i]; + out[i][0] = 0.0; + out[i][1] = c.t1 * (in1[i] - c.proj); // c.dist; + out[i][2] = c.t2 * (in1[i] - c.proj); // 0.0 } - else + } + dataVecOutPos[0]->endEdit(); +} + +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::applyJ( + const sofa::core::MechanicalParams * /* mparams */, const vector<OutDataVecDeriv *> &dataVecOutVel, + const vector<const In1DataVecDeriv *> &dataVecIn1Vel, + const vector<const In2DataVecDeriv *> &dataVecIn2Vel) +{ + if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) + return; + const In1VecDeriv &in1 = dataVecIn1Vel[0]->getValue(); + const In2VecDeriv &in2 = dataVecIn2Vel[0]->getValue(); + OutVecDeriv &outVel = *dataVecOutVel[0]->beginEdit(); + + // const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); + size_t sz = m_constraints.size(); + outVel.resize(sz); + + if (d_lastPointIsFixed.getValue()) + { + for (size_t i = 0; i < sz; i++) { - for (size_t i = 0; i < sz; i++) + Constraint &c = m_constraints[i]; + int ei1 = c.eid; + int ei2 = c.eid + 1; + if (i < sz - 1) { - Constraint &c = m_constraints[i]; - - int ei1 = c.eid; - int ei2 = c.eid + 1; Real v0 = c.dirAxe * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); Real v1 = c.t1 * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); Real v2 = c.t2 * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); - + outVel[i] = OutDeriv(v0, v1, v2); + } + else + { + Real v0 = c.dirAxe * (in1[i] - in2[ei2]); + Real v1 = c.t1 * (in1[i] - in2[ei2]); + Real v2 = c.t2 * (in1[i] - in2[ei2]); outVel[i] = OutDeriv(v0, v1, v2); } } - dataVecOutVel[0]->endEdit(); } - - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::applyJT( - const core::MechanicalParams * /*mparams*/, const type::vector<In1DataVecDeriv *> &dataVecOut1Force, - const type::vector<In2DataVecDeriv *> &dataVecOut2Force, - const type::vector<const OutDataVecDeriv *> &dataVecInForce) + else { - if (dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) - return; - - const OutVecDeriv &in = dataVecInForce[0]->getValue(); - if (in.empty()) - return; - - In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); - In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); - // Compute output forces - size_t sz = m_constraints.size(); - if (d_lastPointIsFixed.getValue()) + for (size_t i = 0; i < sz; i++) { - for (size_t i = 0; i < sz; i++) - { - Constraint &c = m_constraints[i]; - int ei1 = c.eid; - int ei2 = c.eid + 1; - OutDeriv f = in[i]; - if (i < sz - 1) - { - Deriv2 f1 = (f[0] * c.dirAxe) + (f[1] * c.t1) + (f[2] * c.t2); - Deriv1 f2_1 = (c.alpha * f[0] * c.dirAxe) + (c.alpha * f[1] * c.t1) + (c.alpha * f[2] * c.t2); - Deriv1 f2_2 = ((1 - c.alpha) * f[0] * c.dirAxe) + ((1 - c.alpha) * f[1] * c.t1) + ((1 - c.alpha) * f[2] * c.t2); - out1[i] += f1; out2[ei1] -= f2_1; out2[ei2] -= f2_2; - } - else - { - Deriv2 f1 = (f[0] * c.dirAxe) + (f[1] * c.t1) + (f[2] * c.t2); - out1[i] += f1; out2[ei2] -= f1; - } - } + Constraint &c = m_constraints[i]; + + int ei1 = c.eid; + int ei2 = c.eid + 1; + Real v0 = c.dirAxe * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); + Real v1 = c.t1 * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); + Real v2 = c.t2 * (in1[i] - c.alpha * in2[ei1] - (1 - c.alpha) * in2[ei2]); + + outVel[i] = OutDeriv(v0, v1, v2); } - else + } + dataVecOutVel[0]->endEdit(); +} + +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::applyJT( + const sofa::core::MechanicalParams * /*mparams*/, const vector<In1DataVecDeriv *> &dataVecOut1Force, + const vector<In2DataVecDeriv *> &dataVecOut2Force, + const vector<const OutDataVecDeriv *> &dataVecInForce) +{ + if (dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) + return; + + const OutVecDeriv &in = dataVecInForce[0]->getValue(); + if (in.empty()) + return; + + In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); + In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); + // Compute output forces + size_t sz = m_constraints.size(); + if (d_lastPointIsFixed.getValue()) + { + for (size_t i = 0; i < sz; i++) { - for (size_t i = 0; i < sz; i++) + Constraint &c = m_constraints[i]; + int ei1 = c.eid; + int ei2 = c.eid + 1; + OutDeriv f = in[i]; + if (i < sz - 1) { - Constraint &c = m_constraints[i]; - int ei1 = c.eid; - int ei2 = c.eid + 1; - OutDeriv f = in[i]; Deriv2 f1 = (f[0] * c.dirAxe) + (f[1] * c.t1) + (f[2] * c.t2); Deriv1 f2_1 = (c.alpha * f[0] * c.dirAxe) + (c.alpha * f[1] * c.t1) + (c.alpha * f[2] * c.t2); Deriv1 f2_2 = ((1 - c.alpha) * f[0] * c.dirAxe) + ((1 - c.alpha) * f[1] * c.t1) + ((1 - c.alpha) * f[2] * c.t2); - out1[i] += f1; - out2[ei1] -= f2_1; - out2[ei2] -= f2_2; + out1[i] += f1; out2[ei1] -= f2_1; out2[ei2] -= f2_2; + } + else + { + Deriv2 f1 = (f[0] * c.dirAxe) + (f[1] * c.t1) + (f[2] * c.t2); + out1[i] += f1; out2[ei2] -= f1; } } - dataVecOut1Force[0]->endEdit(); - dataVecOut2Force[0]->endEdit(); } - - //___________________________________________________________________________ - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::applyJT( - const core::ConstraintParams * /*cparams*/, const type::vector<In1DataMatrixDeriv *> &dataMatOut1Const, - const type::vector<In2DataMatrixDeriv *> &dataMatOut2Const, - const type::vector<const OutDataMatrixDeriv *> &dataMatInConst) + else { - if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty()) - return; + for (size_t i = 0; i < sz; i++) + { + Constraint &c = m_constraints[i]; + int ei1 = c.eid; + int ei2 = c.eid + 1; + OutDeriv f = in[i]; + Deriv2 f1 = (f[0] * c.dirAxe) + (f[1] * c.t1) + (f[2] * c.t2); + Deriv1 f2_1 = (c.alpha * f[0] * c.dirAxe) + (c.alpha * f[1] * c.t1) + (c.alpha * f[2] * c.t2); + Deriv1 f2_2 = ((1 - c.alpha) * f[0] * c.dirAxe) + ((1 - c.alpha) * f[1] * c.t1) + ((1 - c.alpha) * f[2] * c.t2); + out1[i] += f1; + out2[ei1] -= f2_1; + out2[ei2] -= f2_2; + } + } + dataVecOut1Force[0]->endEdit(); + dataVecOut2Force[0]->endEdit(); +} + +//___________________________________________________________________________ +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::applyJT( + const sofa::core::ConstraintParams * /*cparams*/, const vector<In1DataMatrixDeriv *> &dataMatOut1Const, + const vector<In2DataMatrixDeriv *> &dataMatOut2Const, + const vector<const OutDataMatrixDeriv *> &dataMatInConst) +{ + if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty()) + return; - // We need only one input In model and input Root model (if present) - In1MatrixDeriv &out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the FEM cable points - In2MatrixDeriv &out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the frames cable points - const OutMatrixDeriv &in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped point - const In1DataVecCoord *x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + // We need only one input In model and input Root model (if present) + In1MatrixDeriv &out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the FEM cable points + In2MatrixDeriv &out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the frames cable points + const OutMatrixDeriv &in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped point + const In1DataVecCoord *x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); - typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); - typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); + typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); - for (rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) - { - typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); - typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); + for (rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) + { + typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); + typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); - // Creates a constraints if the input constraint is not empty. - if (colIt == colItEnd) - { - continue; - } - typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number - typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + // Creates a constraints if the input constraint is not empty. + if (colIt == colItEnd) + { + continue; + } + typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number + typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); - if (d_lastPointIsFixed.getValue()) + if (d_lastPointIsFixed.getValue()) + { + if ((rowIt.index() / 2) < (int)(x1from.size() - 1)) { - if ((rowIt.index() / 2) < (int)(x1from.size() - 1)) + while (colIt != colItEnd) { - while (colIt != colItEnd) - { - int childIndex = colIt.index(); - Constraint c = m_constraints[childIndex]; - const OutDeriv h = colIt.val(); - int indexBeam = c.eid; - - Deriv2 h1 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); - Deriv1 h2_1 = (c.alpha * h[0] * c.dirAxe) + (c.alpha * h[1] * c.t1) + (c.alpha * h[2] * c.t2); - Deriv1 h2_2 = ((1.0 - c.alpha) * h[0] * c.dirAxe) + ((1.0 - c.alpha) * h[1] * c.t1) + ((1.0 - c.alpha) * h[2] * c.t2); - - o1.addCol(childIndex, h1); - o2.addCol(indexBeam, -h2_1); - o2.addCol(indexBeam + 1, -h2_2); + int childIndex = colIt.index(); + Constraint c = m_constraints[childIndex]; + const OutDeriv h = colIt.val(); + int indexBeam = c.eid; - colIt++; - } - } - else - { - while (colIt != colItEnd) - { - int childIndex = colIt.index(); - Constraint c = m_constraints[childIndex]; - const OutDeriv h = colIt.val(); - int indexBeam = c.eid; + Deriv2 h1 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); + Deriv1 h2_1 = (c.alpha * h[0] * c.dirAxe) + (c.alpha * h[1] * c.t1) + (c.alpha * h[2] * c.t2); + Deriv1 h2_2 = ((1.0 - c.alpha) * h[0] * c.dirAxe) + ((1.0 - c.alpha) * h[1] * c.t1) + ((1.0 - c.alpha) * h[2] * c.t2); - Deriv2 h1 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); - Deriv1 h2 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); + o1.addCol(childIndex, h1); + o2.addCol(indexBeam, -h2_1); + o2.addCol(indexBeam + 1, -h2_2); - o1.addCol(childIndex, h1); - o2.addCol(indexBeam + 1, -h2); - colIt++; - } + colIt++; } } else @@ -749,71 +731,89 @@ namespace sofa::component::mapping int indexBeam = c.eid; Deriv2 h1 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); - Deriv1 h2_1 = (c.alpha * h[0] * c.dirAxe) + (c.alpha * h[1] * c.t1) + (c.alpha * h[2] * c.t2); - Deriv1 h2_2 = ((1.0 - c.alpha) * h[0] * c.dirAxe) + ((1.0 - c.alpha) * h[1] * c.t1) + ((1.0 - c.alpha) * h[2] * c.t2); + Deriv1 h2 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); o1.addCol(childIndex, h1); - o2.addCol(indexBeam, -h2_1); - o2.addCol(indexBeam + 1, -h2_2); - + o2.addCol(indexBeam + 1, -h2); colIt++; } } } - dataMatOut1Const[0]->endEdit(); - dataMatOut2Const[0]->endEdit(); + else + { + while (colIt != colItEnd) + { + int childIndex = colIt.index(); + Constraint c = m_constraints[childIndex]; + const OutDeriv h = colIt.val(); + int indexBeam = c.eid; + + Deriv2 h1 = (h[0] * c.dirAxe) + (h[1] * c.t1) + (h[2] * c.t2); + Deriv1 h2_1 = (c.alpha * h[0] * c.dirAxe) + (c.alpha * h[1] * c.t1) + (c.alpha * h[2] * c.t2); + Deriv1 h2_2 = ((1.0 - c.alpha) * h[0] * c.dirAxe) + ((1.0 - c.alpha) * h[1] * c.t1) + ((1.0 - c.alpha) * h[2] * c.t2); + + o1.addCol(childIndex, h1); + o2.addCol(indexBeam, -h2_1); + o2.addCol(indexBeam + 1, -h2_2); + + colIt++; + } + } } + dataMatOut1Const[0]->endEdit(); + dataMatOut2Const[0]->endEdit(); +} - template <class TIn1, class TIn2, class TOut> - void DifferenceMultiMapping<TIn1, TIn2, TOut>::draw(const core::visual::VisualParams *vparams) - { - /// draw cable - if (!vparams->displayFlags().getShowInteractionForceFields()) - return; +template <class TIn1, class TIn2, class TOut> +void DifferenceMultiMapping<TIn1, TIn2, TOut>::draw(const sofa::core::visual::VisualParams *vparams) +{ + /// draw cable + if (!vparams->displayFlags().getShowInteractionForceFields()) + return; - typedef sofa::type::RGBAColor RGBAColor; - vparams->drawTool()->saveLastState(); - vparams->drawTool()->disableLighting(); + typedef sofa::type::RGBAColor RGBAColor; + vparams->drawTool()->saveLastState(); + vparams->drawTool()->disableLighting(); - std::vector<type::Vec3> vertices; - RGBAColor color = RGBAColor::magenta(); + std::vector<Vec3> vertices; + RGBAColor color = RGBAColor::magenta(); - if (d_drawArrows.getValue() && d_lastPointIsFixed.getValue()) + if (d_drawArrows.getValue() && d_lastPointIsFixed.getValue()) + { + for (size_t i = 0; i < m_constraints.size(); i++) { - for (size_t i = 0; i < m_constraints.size(); i++) + color = RGBAColor::green(); + vertices.push_back(m_constraints[i].proj); + vertices.push_back(m_constraints[i].Q); + vparams->drawTool()->drawLines(vertices, 4.0, color); + if (i == (m_constraints.size() - 1)) { - color = RGBAColor::green(); - vertices.push_back(m_constraints[i].proj); - vertices.push_back(m_constraints[i].Q); - vparams->drawTool()->drawLines(vertices, 4.0, color); - if (i == (m_constraints.size() - 1)) - { - Coord2 P1 = m_constraints[i].Q; - Real radius_arrow = 0.30; - Coord2 x = m_constraints[i].dirAxe * 5.0; - Coord2 y = m_constraints[i].t1 * 5.0; - Coord2 z = m_constraints[i].t2 * 5.0; - - vparams->drawTool()->drawArrow(P1, P1 + x, radius_arrow, RGBAColor::red()); - vparams->drawTool()->drawArrow(P1, P1 + y, radius_arrow, RGBAColor::green()); - vparams->drawTool()->drawArrow(P1, P1 + z, radius_arrow, RGBAColor::blue()); - } - else - { - Coord2 P1 = m_constraints[i].Q; - Real radius_arrow = 0.30; - // Coord2 x = m_constraints[i].dirAxe * 5.0; - Coord2 y = m_constraints[i].t1 * 5.0; - Coord2 z = m_constraints[i].t2 * 5.0; - vparams->drawTool()->drawArrow(P1, P1 + y, radius_arrow, RGBAColor::blue()); - vparams->drawTool()->drawArrow(P1, P1 + z, radius_arrow, RGBAColor::blue()); - } + Coord2 P1 = m_constraints[i].Q; + Real radius_arrow = 0.30; + Coord2 x = m_constraints[i].dirAxe * 5.0; + Coord2 y = m_constraints[i].t1 * 5.0; + Coord2 z = m_constraints[i].t2 * 5.0; + + vparams->drawTool()->drawArrow(P1, P1 + x, radius_arrow, RGBAColor::red()); + vparams->drawTool()->drawArrow(P1, P1 + y, radius_arrow, RGBAColor::green()); + vparams->drawTool()->drawArrow(P1, P1 + z, radius_arrow, RGBAColor::blue()); + } + else + { + Coord2 P1 = m_constraints[i].Q; + Real radius_arrow = 0.30; + // Coord2 x = m_constraints[i].dirAxe * 5.0; + Coord2 y = m_constraints[i].t1 * 5.0; + Coord2 z = m_constraints[i].t2 * 5.0; + vparams->drawTool()->drawArrow(P1, P1 + y, radius_arrow, RGBAColor::blue()); + vparams->drawTool()->drawArrow(P1, P1 + z, radius_arrow, RGBAColor::blue()); } - const In1DataVecDeriv *xDestData = m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord &fromPos = xDestData[0].getValue(); - vparams->drawTool()->draw3DText_Indices(fromPos, 6, RGBAColor(0.0, 1.0, 0.0, 1.0)); } - vparams->drawTool()->restoreLastState(); + const In1DataVecDeriv *xDestData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord &fromPos = xDestData[0].getValue(); + vparams->drawTool()->draw3DText_Indices(fromPos, 6, RGBAColor(0.0, 1.0, 0.0, 1.0)); } + vparams->drawTool()->restoreLastState(); +} } // namespace sofa diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index b7666255..85fef06d 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -20,22 +20,22 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #define SOFA_COSSERAT_CPP_DiscreteCosseratMapping -#include "DiscreteCosseratMapping.inl" +#include <Cosserat/mapping/DiscreteCosseratMapping.inl> #include <sofa/defaulttype/VecTypes.h> #include <sofa/defaulttype/RigidTypes.h> #include <sofa/core/ObjectFactory.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using namespace sofa::defaulttype; template <> void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) { + const sofa::core::MechanicalParams* /* mparams */, const vector< OutDataVecDeriv*>& dataVecOutVel, + const vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const vector<const In2DataVecDeriv*>& dataVecIn2Vel) { if(d_debug.getValue()) std::cout<< " ########## ApplyJ R Function ########"<< std::endl; @@ -48,10 +48,10 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( const auto baseIndex = d_baseIndex.getValue(); // Curv abscissa of nodes and frames - helper::ReadAccessor<Data<List>> curv_abs_section = d_curv_abs_section; - helper::ReadAccessor<Data<List>> curv_abs_frames = d_curv_abs_frames; + sofa::helper::ReadAccessor<Data<List>> curv_abs_section = d_curv_abs_section; + sofa::helper::ReadAccessor<Data<List>> curv_abs_frames = d_curv_abs_frames; - const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); //Strains + const In1VecCoord& inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); //Strains // Compute the tangent Exponential SE3 vectors this->updateTangExpSE3(inDeform); @@ -59,15 +59,15 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( m_nodesVelocityVectors.clear(); //Get base velocity and convert to Vec6, for the facility of computation - type::Vec6 baseVelocity; // + Vec6 baseVelocity; // for (auto u=0; u<6; u++) baseVelocity[u] = in2_vel[baseIndex][u]; //Apply the local transform i.e. from SOFA's frame to Cosserat's frame - const In2VecCoord& xfrom2Data = m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); + const In2VecCoord& xfrom2Data = m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()).inversed(); Mat6x6 P = this->buildProjector(TInverse); - type::Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame + Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame m_nodesVelocityVectors.push_back(baseLocalVelocity); if(d_debug.getValue()) std::cout << "Base local Velocity :"<< baseLocalVelocity <<std::endl; @@ -78,7 +78,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( Tangent Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); - type::Vec6 node_Xi_dot; + Vec6 node_Xi_dot; for (unsigned int u =0; u<6; u++) node_Xi_dot(i) = in1_vel[i-1][u]; @@ -87,7 +87,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( if(d_debug.getValue()) std::cout<< "Node velocity : "<< i << " = " << eta_node_i<< std::endl; } - const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); + const OutVecCoord& out = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); auto sz = curv_abs_frames.size(); out_vel.resize(sz); @@ -95,7 +95,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); Tangent Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); - type::Vec6 frame_Xi_dot = in1_vel[m_indicesVectors[i]-1]; + Vec6 frame_Xi_dot = in1_vel[m_indicesVectors[i]-1]; // for (unsigned int u =0; u<6; u++) // frame_Xi_dot(i) = in1_vel[m_indicesVectors[i]-1][u]; @@ -116,9 +116,9 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( template <> void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( - const core::MechanicalParams* /*mparams*/, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2Force, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) { + const sofa::core::MechanicalParams* /*mparams*/, const vector< In1DataVecDeriv*>& dataVecOut1Force, + const vector< In2DataVecDeriv*>& dataVecOut2Force, + const vector<const OutDataVecDeriv*>& dataVecInForce) { if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) return; @@ -131,21 +131,21 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( In2VecDeriv& out2 = *dataVecOut2Force[0]->beginEdit(); const auto baseIndex = d_baseIndex.getValue(); - const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); + const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); - type::vector<Vec6> local_F_Vec; local_F_Vec.clear(); + vector<Vec6> local_F_Vec; local_F_Vec.clear(); out1.resize(x1from.size()); //convert the input from Deriv type to vec6 type, for the purpose of the matrix vector multiplication for (unsigned int var = 0; var < in.size(); ++var) { - type::Vec6 vec; + Vec6 vec; for(unsigned j = 0; j < 6; j++) vec[j] = in[var][j]; //Convert input from global frame(SOFA) to local frame Transform _T = Transform(frame[var].getCenter(),frame[var].getOrientation()); Mat6x6 P_trans =(this->buildProjector(_T)); P_trans.transpose(); - type::Vec6 local_F = P_trans * vec; + Vec6 local_F = P_trans * vec; local_F_Vec.push_back(local_F); } @@ -169,7 +169,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; Mat6x6 temp = m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); - type::Vec6 f = matB_trans * temp * node_F_Vec; + Vec6 f = matB_trans * temp * node_F_Vec; if(index != m_indicesVectors[s]){ index--; @@ -179,7 +179,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( Mat6x6 temp = m_nodesTangExpVectors[index]; temp.transpose(); //apply F_tot to the new beam - type::Vec6 temp_f = matB_trans * temp * F_tot; + Vec6 temp_f = matB_trans * temp * F_tot; out1[index-1] += temp_f; } if(d_debug.getValue()) @@ -206,9 +206,9 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( template <> void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( - const core::ConstraintParams*/*cparams*/ , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const, - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) + const sofa::core::ConstraintParams*/*cparams*/ , const vector< In1DataMatrixDeriv*>& dataMatOut1Const, + const vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const vector<const OutDataMatrixDeriv*>& dataMatInConst) { if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) return; @@ -221,15 +221,15 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) const OutMatrixDeriv& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames - const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); + const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); Tangent matB_trans; matB_trans.clear(); for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; - type::vector< std::tuple<int,Vec6> > NodesInvolved; - type::vector< std::tuple<int,Vec6> > NodesInvolvedCompressed; + vector< std::tuple<int,Vec6> > NodesInvolved; + vector< std::tuple<int,Vec6> > NodesInvolvedCompressed; //helper::vector<Vec6> NodesConstraintDirection; typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); @@ -260,7 +260,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( { int childIndex = colIt.index(); - type::Vec6 valueConst; + Vec6 valueConst; for(unsigned j = 0; j < 6; j++) valueConst[j] = colIt.val()[j]; @@ -275,9 +275,9 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( Tangent temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); - type::Vec6 local_F = coAdjoint * P_trans * valueConst; // constraint direction in local frame of the beam. + Vec6 local_F = coAdjoint * P_trans * valueConst; // constraint direction in local frame of the beam. - type::Vec6 f = matB_trans * temp * local_F; // constraint direction in the strain space. + Vec6 f = matB_trans * temp * local_F; // constraint direction in the strain space. o1.addCol(indexBeam-1, f); std::tuple<int,Vec6> node_force = std::make_tuple(indexBeam, local_F); @@ -352,7 +352,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( // transfer to strain space (local coordinates) Mat6x6 temp = m_nodesTangExpVectors[i-1]; temp.transpose(); - type::Vec6 temp_f = matB_trans * temp * CumulativeF; + Vec6 temp_f = matB_trans * temp * CumulativeF; if(i>1) o1.addCol(i-2, temp_f); i--; @@ -373,7 +373,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( // Register in the Factory -int DiscreteCosseratMappingClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") +int DiscreteCosseratMappingClass = sofa::core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") .add< DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >(true) .add< DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() ; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index ab4fc8f0..84b3749c 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -1,47 +1,48 @@ /****************************************************************************** -* SOFA, Simulation Open-Framework Architecture, development version * -* (c) 2006-2019 INRIA, USTL, UJF, CNRS, MGH * -* * -* This program is free software; you can redistribute it and/or modify it * -* under the terms of the GNU Lesser General Public License as published by * -* the Free Software Foundation; either version 2.1 of the License, or (at * -* your option) any later version. * -* * -* This program is distributed in the hope that it will be useful, but WITHOUT * -* ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * -* FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * -* for more details. * -* * -* You should have received a copy of the GNU Lesser General Public License * -* along with this program. If not, see <http://www.gnu.org/licenses/>. * -******************************************************************************* -* Authors: The SOFA Team and external contributors (see Authors.txt) * -* * -* Contact information: contact@sofa-framework.org * -******************************************************************************/ + * SOFA, Simulation Open-Framework Architecture, development version * + * (c) 2006-2019 INRIA, USTL, UJF, CNRS, MGH * + * * + * This program is free software; you can redistribute it and/or modify it * + * under the terms of the GNU Lesser General Public License as published by * + * the Free Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. * + * * + * This program is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * + * for more details. * + * * + * You should have received a copy of the GNU Lesser General Public License * + * along with this program. If not, see <http://www.gnu.org/licenses/>. * + ******************************************************************************* + * Authors: The SOFA Team and external contributors (see Authors.txt) * + * * + * Contact information: contact@sofa-framework.org * + ******************************************************************************/ #pragma once -#include <Cosserat/config.h> +#include <Cosserat/initCosserat.h> -#include <Cosserat/mapping/BaseCosserat.h> #include <Cosserat/forcefield/BeamHookeLawForceField.h> +#include <Cosserat/mapping/BaseCosserat.h> #include <sofa/core/BaseMapping.h> -#include <sofa/core/config.h> #include <sofa/core/Multi2Mapping.h> -#include <sofa/defaulttype/SolidTypes.h> +#include <sofa/core/config.h> #include <sofa/defaulttype/RigidTypes.h> +#include <sofa/defaulttype/SolidTypes.h> #include <sofa/helper/ColorMap.h> -namespace sofa::component::mapping -{ - using sofa::component::forcefield::BeamHookeLawForceField; - using sofa::defaulttype::SolidTypes ; - using sofa::core::objectmodel::BaseContext ; - using sofa::type::Matrix3; - using sofa::type::Matrix4; - using sofa::type::Vec3; - using sofa::type::Vec6; - using std::get; +namespace Cosserat::mapping { +using sofa::component::forcefield::BeamHookeLawForceField; +using sofa::core::objectmodel::BaseContext; +using sofa::defaulttype::SolidTypes; +using sofa::type::Matrix3; +using sofa::type::Matrix4; +using sofa::type::Vec3; +using sofa::type::Vec6; +using sofa::type::Quat; +using std::get; +using sofa::Data; /*! * \class DiscreteCosseratMapping @@ -50,14 +51,16 @@ namespace sofa::component::mapping * This is a component: * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ -using mapping::BaseCosserat; +// using Cosserat::mapping::BaseCosserat; template <class TIn1, class TIn2, class TOut> -class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, public component::mapping::BaseCosserat<TIn1, TIn2, TOut> -{ +class DiscreteCosseratMapping + : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, + public Cosserat::mapping::BaseCosserat<TIn1, TIn2, TOut> { public: - SOFA_CLASS(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1,TIn2, TOut), SOFA_TEMPLATE3(core::Multi2Mapping, TIn1, TIn2, TOut) ); - typedef core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; + SOFA_CLASS(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1, TIn2, TOut), + SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut)); + typedef sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; /// Input Model Type typedef TIn1 In1; @@ -66,58 +69,65 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu /// Output Model Type typedef TOut Out; typedef typename In2::Coord::value_type Real1; - typedef typename In1::Coord Coord1; - typedef typename In1::Deriv Deriv1; - typedef typename In1::VecCoord In1VecCoord; - typedef typename In1::VecDeriv In1VecDeriv; - typedef typename In1::MatrixDeriv In1MatrixDeriv; - typedef Data<In1VecCoord> In1DataVecCoord; - typedef Data<In1VecDeriv> In1DataVecDeriv; - typedef Data<In1MatrixDeriv> In1DataMatrixDeriv; + typedef typename In1::Coord Coord1; + typedef typename In1::Deriv Deriv1; + typedef typename In1::VecCoord In1VecCoord; + typedef typename In1::VecDeriv In1VecDeriv; + typedef typename In1::MatrixDeriv In1MatrixDeriv; + typedef Data<In1VecCoord> In1DataVecCoord; + typedef Data<In1VecDeriv> In1DataVecDeriv; + typedef Data<In1MatrixDeriv> In1DataMatrixDeriv; typedef typename In2::Coord::value_type Real2; - typedef typename In2::Coord Coord2 ; - typedef typename In2::Deriv Deriv2 ; - typedef typename In2::VecCoord In2VecCoord; - typedef typename In2::VecDeriv In2VecDeriv; - typedef typename In2::MatrixDeriv In2MatrixDeriv; - typedef Data<In2VecCoord> In2DataVecCoord; - typedef Data<In2VecDeriv> In2DataVecDeriv; - typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; - typedef type::Mat<6,6,Real2> Mat6x6; - typedef type::Mat<3,6,Real2> Mat3x6; - typedef type::Mat<6,3,Real2> Mat6x3; - typedef type::Mat<4,4,Real2> Mat4x4; - - typedef typename Out::VecCoord OutVecCoord; - typedef typename Out::Coord OutCoord; - typedef typename Out::Deriv OutDeriv; - typedef typename Out::VecDeriv OutVecDeriv; - typedef typename Out::MatrixDeriv OutMatrixDeriv; - typedef Data<OutVecCoord> OutDataVecCoord; - typedef Data<OutVecDeriv> OutDataVecDeriv; - typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; - typedef typename SolidTypes<Real2>::Transform Transform ; + typedef typename In2::Coord Coord2; + typedef typename In2::Deriv Deriv2; + typedef typename In2::VecCoord In2VecCoord; + typedef typename In2::VecDeriv In2VecDeriv; + typedef typename In2::MatrixDeriv In2MatrixDeriv; + typedef Data<In2VecCoord> In2DataVecCoord; + typedef Data<In2VecDeriv> In2DataVecDeriv; + typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; + typedef sofa::type::Mat<6, 6, Real2> Mat6x6; + typedef sofa::type::Mat<3, 6, Real2> Mat3x6; + typedef sofa::type::Mat<6, 3, Real2> Mat6x3; + typedef sofa::type::Mat<4, 4, Real2> Mat4x4; + + typedef typename Out::VecCoord OutVecCoord; + typedef typename Out::Coord OutCoord; + typedef typename Out::Deriv OutDeriv; + typedef typename Out::VecDeriv OutVecDeriv; + typedef typename Out::MatrixDeriv OutMatrixDeriv; + typedef Data<OutVecCoord> OutDataVecCoord; + typedef Data<OutVecDeriv> OutDataVecDeriv; + typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; + typedef typename SolidTypes<Real2>::Transform Transform; protected: - core::State<In1>* m_fromModel1; - core::State<In2>* m_fromModel2; - core::State<Out>* m_toModel; - Data<int> d_deformationAxis; - Data<Real2> d_max; - Data<Real2> d_min; - Data<Real1> d_radius ; - Data<bool> d_drawMapBeam ; - Data<sofa::type::RGBAColor> d_color; - Data<type::vector<int> > d_index; - Data<unsigned int> d_baseIndex; + sofa::core::State<In1> *m_fromModel1; + sofa::core::State<In2> *m_fromModel2; + sofa::core::State<Out> *m_toModel; + Data<int> d_deformationAxis; + Data<Real2> d_max; + Data<Real2> d_min; + Data<Real1> d_radius; + Data<bool> d_drawMapBeam; + Data<sofa::type::RGBAColor> d_color; + Data<vector<int>> d_index; + Data<unsigned int> d_baseIndex; public: - typedef MultiLink<DiscreteCosseratMapping<In1,In2,Out>, sofa::core::State< In1 >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels1; - typedef MultiLink<DiscreteCosseratMapping<In1,In2,Out>, sofa::core::State< In2 >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels2; - typedef MultiLink<DiscreteCosseratMapping<In1,In2,Out>, sofa::core::State< Out >, BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkToModels; - - + typedef sofa::MultiLink<DiscreteCosseratMapping<In1, In2, Out>, + sofa::core::State<In1>, + sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> + LinkFromModels1; + typedef sofa::MultiLink<DiscreteCosseratMapping<In1, In2, Out>, + sofa::core::State<In2>, + sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> + LinkFromModels2; + typedef sofa::MultiLink<DiscreteCosseratMapping<In1, In2, Out>, + sofa::core::State<Out>, + sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> + LinkToModels; protected: ////////////////////////// Inherited attributes //////////////////////////// @@ -126,17 +136,17 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu /// otherwise any access to the base::attribute would require /// the "this->" approach. /// - using BaseCosserat<TIn1, TIn2, TOut>:: m_indicesVectors ; - using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_section ; - using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_frames ; + using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectors; + using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_section; + using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_frames; using BaseCosserat<TIn1, TIn2, TOut>::m_nodesTangExpVectors; using BaseCosserat<TIn1, TIn2, TOut>::m_nodesVelocityVectors; using BaseCosserat<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_framesTangExpVectors ; - using BaseCosserat<TIn1, TIn2, TOut>::m_totalBeamForceVectors ; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors ; + using BaseCosserat<TIn1, TIn2, TOut>::m_framesTangExpVectors; + using BaseCosserat<TIn1, TIn2, TOut>::m_totalBeamForceVectors; + using BaseCosserat<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors; using BaseCosserat<TIn1, TIn2, TOut>::d_debug; - using BaseCosserat<TIn1, TIn2, TOut>::m_vecTransform ; + using BaseCosserat<TIn1, TIn2, TOut>::m_vecTransform; using BaseCosserat<TIn1, TIn2, TOut>::m_nodeAdjointVectors; using BaseCosserat<TIn1, TIn2, TOut>::m_index_input; using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectorsDraw; @@ -144,50 +154,61 @@ class DiscreteCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, pu protected: /// Constructor - DiscreteCosseratMapping() ; + DiscreteCosseratMapping(); /// Destructor - ~DiscreteCosseratMapping() override {} + ~DiscreteCosseratMapping() override {} public: /**********************SOFA METHODS**************************/ void init() override; void reinit() override; - void draw(const core::visual::VisualParams* vparams) override; + void draw(const sofa::core::visual::VisualParams *vparams) override; /**********************MAPPING METHODS**************************/ - void apply( - const core::MechanicalParams* /* mparams */, const type::vector<OutDataVecCoord*>& dataVecOutPos, - const type::vector<const In1DataVecCoord*>& dataVecIn1Pos , - const type::vector<const In2DataVecCoord*>& dataVecIn2Pos) override; - - void applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; - - //ApplyJT Force - void applyJT( - const core::MechanicalParams* /* mparams */, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2RootForce, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) override; - - void applyDJT(const core::MechanicalParams* /*mparams*/, core::MultiVecDerivId /*inForce*/, core::ConstMultiVecDerivId /*outForce*/) override{} - - /// This method must be reimplemented by all mappings if they need to support constraints. + void + apply(const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecCoord *> &dataVecOutPos, + const vector<const In1DataVecCoord *> &dataVecIn1Pos, + const vector<const In2DataVecCoord *> &dataVecIn2Pos) override; + + void + applyJ(const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecDeriv *> &dataVecOutVel, + const vector<const In1DataVecDeriv *> &dataVecIn1Vel, + const vector<const In2DataVecDeriv *> &dataVecIn2Vel) override; + + // ApplyJT Force + void + applyJT(const sofa::core::MechanicalParams * /* mparams */, + const vector<In1DataVecDeriv *> &dataVecOut1Force, + const vector<In2DataVecDeriv *> &dataVecOut2RootForce, + const vector<const OutDataVecDeriv *> &dataVecInForce) override; + + void applyDJT(const sofa::core::MechanicalParams * /*mparams*/, + sofa::core::MultiVecDerivId /*inForce*/, + sofa::core::ConstMultiVecDerivId /*outForce*/) override {} + + /// This method must be reimplemented by all mappings if they need to support + /// constraints. virtual void applyJT( - const core::ConstraintParams* cparams , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const , - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) override; - void computeBBox(const core::ExecParams* params, bool onlyVisible) override; - void computeLogarithm(const double & x, const Matrix4 &gX, Matrix4 &log_gX); -protected: - helper::ColorMap m_colorMap; + const sofa::core::ConstraintParams *cparams, + const vector<In1DataMatrixDeriv *> &dataMatOut1Const, + const vector<In2DataMatrixDeriv *> &dataMatOut2Const, + const vector<const OutDataMatrixDeriv *> &dataMatInConst) override; + void computeBBox(const sofa::core::ExecParams *params, bool onlyVisible) override; + void computeLogarithm(const double &x, const Matrix4 &gX, Matrix4 &log_gX); +protected: + sofa::helper::ColorMap m_colorMap; }; #if !defined(SOFA_COSSERAT_CPP_DiscreteCosseratMapping) -extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; -extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; +extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< + sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; +extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< + sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; #endif -} // namespace sofa::component::mapping +} // namespace Cosserat::mapping diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index c4b8b679..df957bdf 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include "DiscreteCosseratMapping.h" +#include <Cosserat/mapping/DiscreteCosseratMapping.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/behavior/MechanicalState.h> @@ -34,7 +34,7 @@ #include <string> -namespace sofa::component::mapping { +namespace Cosserat::mapping { using sofa::core::objectmodel::BaseContext; using sofa::defaulttype::SolidTypes; @@ -45,166 +45,166 @@ using sofa::type::RGBAColor; template <class TIn1, class TIn2, class TOut> DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), - d_deformationAxis( - initData(&d_deformationAxis, (int)1, "deformationAxis", - "the axis in which we want to show the deformation.\n")), - d_max(initData(&d_max, (Real2)1.0e-2, "max", - "the maximum of the deformation.\n")), - d_min(initData(&d_min, (Real2)0.0, "min", - "the minimum of the deformation.\n")), - d_radius( - initData(&d_radius, (Real2)0.05, "radius", - "the axis in which we want to show the deformation.\n")), - d_drawMapBeam( - initData(&d_drawMapBeam, true, "nonColored", - "if this parameter is false, you draw the beam with " - "color according to the force apply to each beam")), - d_color(initData( - &d_color, - sofa::type::RGBAColor(40 / 255.0, 104 / 255.0, 137 / 255.0, 0.8), - "color", "The default beam color")), - d_index( - initData(&d_index, "index", - "if this parameter is false, you draw the beam with color " - "according to the force apply to each beam")), - d_baseIndex(initData(&d_baseIndex, (unsigned int)0, "baseIndex", - "This parameter defines the index of the rigid " - "base of Cosserat models, 0 by default this can" - "take another value if the rigid base is given " - "by another body.")) {} + d_deformationAxis( + initData(&d_deformationAxis, (int)1, "deformationAxis", + "the axis in which we want to show the deformation.\n")), + d_max(initData(&d_max, (Real2)1.0e-2, "max", + "the maximum of the deformation.\n")), + d_min(initData(&d_min, (Real2)0.0, "min", + "the minimum of the deformation.\n")), + d_radius( + initData(&d_radius, (Real2)0.05, "radius", + "the axis in which we want to show the deformation.\n")), + d_drawMapBeam( + initData(&d_drawMapBeam, true, "nonColored", + "if this parameter is false, you draw the beam with " + "color according to the force apply to each beam")), + d_color(initData( + &d_color, + sofa::type::RGBAColor(40 / 255.0, 104 / 255.0, 137 / 255.0, 0.8), + "color", "The default beam color")), + d_index( + initData(&d_index, "index", + "if this parameter is false, you draw the beam with color " + "according to the force apply to each beam")), + d_baseIndex(initData(&d_baseIndex, (unsigned int)0, "baseIndex", + "This parameter defines the index of the rigid " + "base of Cosserat models, 0 by default this can" + "take another value if the rigid base is given " + "by another body.")) {} template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { - if (this->getFromModels1().empty() || this->getFromModels2().empty() || - this->getToModels().empty()) { - msg_error() << "Error while initializing ; input " - "getFromModels1/getFromModels2/output not found"; - return; - } - - reinit(); - // I call Init here since we build the mechanics only in the - Inherit1::init(); - - m_colorMap.setColorScheme("Blue to Red"); - m_colorMap.reinit(); + if (this->getFromModels1().empty() || this->getFromModels2().empty() || + this->getToModels().empty()) { + msg_error() << "Error while initializing ; input " + "getFromModels1/getFromModels2/output not found"; + return; + } + + reinit(); + // I call Init here since we build the mechanics only in the + Inherit1::init(); + + m_colorMap.setColorScheme("Blue to Red"); + m_colorMap.reinit(); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() { - m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion, - // bending_y/_z, elongation and - // shear_y/_z), in local frame - m_fromModel2 = this->getFromModels2()[0]; // Cosserat base, in global frame - m_toModel = this->getToModels()[0]; // Cosserat rigid frames, in global frame - - // Fill the initial vector void init() override; - const OutDataVecCoord *xFromData = - m_toModel->read(core::ConstVecCoordId::position()); - const OutVecCoord xFrom = xFromData->getValue(); - - m_vecTransform.clear(); // initialise with the rigids frames - for (unsigned int i = 0; i < xFrom.size(); i++) { - m_vecTransform.push_back(xFrom[i]); - } - - if (d_debug.getValue()) { - msg_info("DiscreteCosseratMapping") << " =================" - "============================ "; - msg_info("DiscreteCosseratMapping") - << " m_vecTransform : " << m_vecTransform; - } - - this->initialize(); + m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion, + // bending_y/_z, elongation and + // shear_y/_z), in local frame + m_fromModel2 = this->getFromModels2()[0]; // Cosserat base, in global frame + m_toModel = this->getToModels()[0]; // Cosserat rigid frames, in global frame + + // Fill the initial vector void init() override; + const OutDataVecCoord *xFromData = + m_toModel->read(sofa::core::ConstVecCoordId::position()); + const OutVecCoord xFrom = xFromData->getValue(); + + m_vecTransform.clear(); // initialise with the rigids frames + for (unsigned int i = 0; i < xFrom.size(); i++) { + m_vecTransform.push_back(xFrom[i]); + } + + if (d_debug.getValue()) { + msg_info("DiscreteCosseratMapping") << " =================" + "============================ "; + msg_info("DiscreteCosseratMapping") + << " m_vecTransform : " << m_vecTransform; + } + + this->initialize(); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( - const core::MechanicalParams * /* mparams */, - const type::vector<OutDataVecCoord *> &dataVecOutPos, - const type::vector<const In1DataVecCoord *> &dataVecIn1Pos, - const type::vector<const In2DataVecCoord *> &dataVecIn2Pos) { - if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) - return; - - if (d_debug.getValue()) - std::cout << " ########## Apply Function ########" << std::endl; - /// Do Apply - // We need only one input In model and input Root model (if present) - const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); - const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); - - const auto sz = d_curv_abs_frames.getValue().size(); - OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states - out.resize(sz); - const auto baseIndex = d_baseIndex.getValue(); - - // update the Exponential matrices according to new deformation - // Here we update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors - // Which are the homogeneous matrices of the frames and the nodes in local - // coordinate. - this->updateExponentialSE3(in1); - /* Apply the transformation to go from cossserat to SOFA frame*/ - Transform frame0 = - Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); - for (unsigned int i = 0; i < sz; i++) { - Transform frame = frame0; - for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { - frame *= - m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) - } - frame *= m_framesExponentialSE3Vectors[i]; // frame*gX(x) + const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecCoord *> &dataVecOutPos, + const vector<const In1DataVecCoord *> &dataVecIn1Pos, + const vector<const In2DataVecCoord *> &dataVecIn2Pos) { + if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) + return; if (d_debug.getValue()) - std::cout << "Frame : " << i << " = " << frame << std::endl; - - type::Vec3 v = frame.getOrigin(); - type::Quat q = frame.getOrientation(); - out[i] = OutCoord(v, q); - } - // - if (d_debug.getValue()) { - for (unsigned int i = 0; i < out.size() - 1; i++) { - type::Vec3 diff = out[i + 1].getCenter() - out[i].getCenter(); - std::cout << "dist " << i << " : " << diff.norm() << std::endl; + std::cout << " ########## Apply Function ########" << std::endl; + /// Do Apply + // We need only one input In model and input Root model (if present) + const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); + const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); + + const auto sz = d_curv_abs_frames.getValue().size(); + OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states + out.resize(sz); + const auto baseIndex = d_baseIndex.getValue(); + + // update the Exponential matrices according to new deformation + // Here we update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors + // Which are the homogeneous matrices of the frames and the nodes in local + // coordinate. + this->updateExponentialSE3(in1); + /* Apply the transformation to go from cossserat to SOFA frame*/ + Transform frame0 = + Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); + for (unsigned int i = 0; i < sz; i++) { + Transform frame = frame0; + for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { + frame *= + m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) + } + frame *= m_framesExponentialSE3Vectors[i]; // frame*gX(x) + + if (d_debug.getValue()) + std::cout << "Frame : " << i << " = " << frame << std::endl; + + Vec3 v = frame.getOrigin(); + Quat q = frame.getOrientation(); + out[i] = OutCoord(v, q); } - } - m_index_input = 0; - dataVecOutPos[0]->endEdit(); + // + if (d_debug.getValue()) { + for (unsigned int i = 0; i < out.size() - 1; i++) { + Vec3 diff = out[i + 1].getCenter() - out[i].getCenter(); + std::cout << "dist " << i << " : " << diff.norm() << std::endl; + } + } + m_index_input = 0; + dataVecOutPos[0]->endEdit(); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( const double &x, const Matrix4 &gX, Matrix4 &log_gX) { - // Compute theta before everything - double theta = computeTheta(x, gX); - Matrix4 I4; - I4.clear(); - I4.identity(); - log_gX.clear(); - - double csc_theta = 1.0 / (sin(x * theta / 2.0)); - double sec_theta = 1.0 / (cos(x * theta / 2.0)); - double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; - double x_theta = x * theta; - double cos_2Xtheta = cos(2.0 * x_theta); - double cos_Xtheta = cos(x_theta); - double sin_2Xtheta = sin(2.0 * x_theta); - double sin_Xtheta = sin(x_theta); - - if (theta <= std::numeric_limits<double>::epsilon()) - log_gX = I4; - else { - log_gX = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * I4 - - (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - - sin_Xtheta - sin_2Xtheta) * - gX + - (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - - sin_Xtheta - sin_2Xtheta) * - (gX * gX) - - (x_theta * cos_Xtheta - sin_Xtheta) * (gX * gX * gX)); - } + // Compute theta before everything + double theta = computeTheta(x, gX); + Matrix4 I4; + I4.clear(); + I4.identity(); + log_gX.clear(); + + double csc_theta = 1.0 / (sin(x * theta / 2.0)); + double sec_theta = 1.0 / (cos(x * theta / 2.0)); + double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; + double x_theta = x * theta; + double cos_2Xtheta = cos(2.0 * x_theta); + double cos_Xtheta = cos(x_theta); + double sin_2Xtheta = sin(2.0 * x_theta); + double sin_Xtheta = sin(x_theta); + + if (theta <= std::numeric_limits<double>::epsilon()) + log_gX = I4; + else { + log_gX = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * I4 - + (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - + sin_Xtheta - sin_2Xtheta) * + gX + + (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - + sin_Xtheta - sin_2Xtheta) * + (gX * gX) - + (x_theta * cos_Xtheta - sin_Xtheta) * (gX * gX * gX)); + } } // template<class In1VecCoord, class Mat6x6> @@ -230,485 +230,485 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( - const core::MechanicalParams * /* mparams */, - const type::vector<OutDataVecDeriv *> &dataVecOutVel, - const type::vector<const In1DataVecDeriv *> &dataVecIn1Vel, - const type::vector<const In2DataVecDeriv *> &dataVecIn2Vel) { - - if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) - return; - if (d_debug.getValue()) - std::cout << " ########## ApplyJ Function ########" << std::endl; - const In1VecDeriv &in1_vel = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv &in2_vel = dataVecIn2Vel[0]->getValue(); - OutVecDeriv &out_vel = *dataVecOutVel[0]->beginEdit(); - const auto baseIndex = d_baseIndex.getValue(); - - // Curv abscissa of nodes and frames - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_section = - d_curv_abs_section; - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_frames = - d_curv_abs_frames; - - const In1VecCoord &inDeform = - m_fromModel1->read(core::ConstVecCoordId::position()) - ->getValue(); // Strains - // Compute the tangent Exponential SE3 vectors - this->updateTangExpSE3(inDeform); - - // Get base velocity as input this is also called eta - m_nodesVelocityVectors.clear(); - - // Get base velocity and convert to Vec6, for the facility of computation - type::Vec6 baseVelocity; // - for (auto u = 0; u < 6; u++) - baseVelocity[u] = in2_vel[baseIndex][u]; - - // Apply the local transform i.e. from SOFA's frame to Cosserat's frame - const In2VecCoord &xfrom2Data = - m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); - Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), - xfrom2Data[baseIndex].getOrientation()) - .inversed(); - Mat6x6 P = this->buildProjector(TInverse); - type::Vec6 baseLocalVelocity = - P * baseVelocity; // This is the base velocity in Locale frame - m_nodesVelocityVectors.push_back(baseLocalVelocity); - if (d_debug.getValue()) - std::cout << "Base local Velocity :" << baseLocalVelocity << std::endl; - - // Compute velocity at nodes - for (unsigned int i = 1; i < curv_abs_section.size(); i++) { - Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; - Adjoint.clear(); - this->computeAdjoint(Trans, Adjoint); - - /// The null vector is replace by the linear velocity in Vec6Type - type::Vec6 Xi_dot = Vec6(in1_vel[i - 1], type::Vec3(0.0, 0.0, 0.0)); - - Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i - 1] + - m_nodesTangExpVectors[i] * Xi_dot); - m_nodesVelocityVectors.push_back(eta_node_i); + const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecDeriv *> &dataVecOutVel, + const vector<const In1DataVecDeriv *> &dataVecIn1Vel, + const vector<const In2DataVecDeriv *> &dataVecIn2Vel) { + + if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) + return; + if (d_debug.getValue()) + std::cout << " ########## ApplyJ Function ########" << std::endl; + const In1VecDeriv &in1_vel = dataVecIn1Vel[0]->getValue(); + const In2VecDeriv &in2_vel = dataVecIn2Vel[0]->getValue(); + OutVecDeriv &out_vel = *dataVecOutVel[0]->beginEdit(); + const auto baseIndex = d_baseIndex.getValue(); + + // Curv abscissa of nodes and frames + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = + d_curv_abs_section; + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = + d_curv_abs_frames; + + const In1VecCoord &inDeform = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()) + ->getValue(); // Strains + // Compute the tangent Exponential SE3 vectors + this->updateTangExpSE3(inDeform); + + // Get base velocity as input this is also called eta + m_nodesVelocityVectors.clear(); + + // Get base velocity and convert to Vec6, for the facility of computation + Vec6 baseVelocity; // + for (auto u = 0; u < 6; u++) + baseVelocity[u] = in2_vel[baseIndex][u]; + + // Apply the local transform i.e. from SOFA's frame to Cosserat's frame + const In2VecCoord &xfrom2Data = + m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); + Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), + xfrom2Data[baseIndex].getOrientation()) + .inversed(); + Mat6x6 P = this->buildProjector(TInverse); + Vec6 baseLocalVelocity = + P * baseVelocity; // This is the base velocity in Locale frame + m_nodesVelocityVectors.push_back(baseLocalVelocity); if (d_debug.getValue()) - std::cout << "Node velocity : " << i << " = " << eta_node_i << std::endl; - } - - const OutVecCoord &out = - m_toModel->read(core::ConstVecCoordId::position())->getValue(); - auto sz = curv_abs_frames.size(); - out_vel.resize(sz); - for (unsigned int i = 0; i < sz; i++) { - Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; - Adjoint.clear(); - this->computeAdjoint(Trans, Adjoint); - type::Vec6 frame_Xi_dot; - - for (auto u = 0; u < 3; u++) { - frame_Xi_dot(u) = in1_vel[m_indicesVectors[i] - 1][u]; - frame_Xi_dot(u + 3) = 0.; + std::cout << "Base local Velocity :" << baseLocalVelocity << std::endl; + + // Compute velocity at nodes + for (unsigned int i = 1; i < curv_abs_section.size(); i++) { + Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); + Mat6x6 Adjoint; + Adjoint.clear(); + this->computeAdjoint(Trans, Adjoint); + + /// The null vector is replace by the linear velocity in Vec6Type + Vec6 Xi_dot = Vec6(in1_vel[i - 1], Vec3(0.0, 0.0, 0.0)); + + Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i - 1] + + m_nodesTangExpVectors[i] * Xi_dot); + m_nodesVelocityVectors.push_back(eta_node_i); + if (d_debug.getValue()) + std::cout << "Node velocity : " << i << " = " << eta_node_i << std::endl; } - Vec6 eta_frame_i = - Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i] - 1] + - m_framesTangExpVectors[i] * frame_Xi_dot); // eta - auto T = Transform(out[i].getCenter(), out[i].getOrientation()); - Mat6x6 Proj = this->buildProjector(T); + const OutVecCoord &out = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + auto sz = curv_abs_frames.size(); + out_vel.resize(sz); + for (unsigned int i = 0; i < sz; i++) { + Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); + Mat6x6 Adjoint; + Adjoint.clear(); + this->computeAdjoint(Trans, Adjoint); + Vec6 frame_Xi_dot; + + for (auto u = 0; u < 3; u++) { + frame_Xi_dot(u) = in1_vel[m_indicesVectors[i] - 1][u]; + frame_Xi_dot(u + 3) = 0.; + } + Vec6 eta_frame_i = + Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i] - 1] + + m_framesTangExpVectors[i] * frame_Xi_dot); // eta - out_vel[i] = Proj * eta_frame_i; + auto T = Transform(out[i].getCenter(), out[i].getOrientation()); + Mat6x6 Proj = this->buildProjector(T); - if (d_debug.getValue()) - std::cout << "Frame velocity : " << i << " = " << eta_frame_i - << std::endl; - } - dataVecOutVel[0]->endEdit(); - m_index_input = 0; + out_vel[i] = Proj * eta_frame_i; + + if (d_debug.getValue()) + std::cout << "Frame velocity : " << i << " = " << eta_frame_i + << std::endl; + } + dataVecOutVel[0]->endEdit(); + m_index_input = 0; } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const core::MechanicalParams * /*mparams*/, - const type::vector<In1DataVecDeriv *> &dataVecOut1Force, - const type::vector<In2DataVecDeriv *> &dataVecOut2Force, - const type::vector<const OutDataVecDeriv *> &dataVecInForce) { - - if (dataVecOut1Force.empty() || dataVecInForce.empty() || - dataVecOut2Force.empty()) - return; - - if (d_debug.getValue()) - std::cout << " ########## ApplyJT force Function ########" << std::endl; - const OutVecDeriv &in = dataVecInForce[0]->getValue(); - - In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); - In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); - const auto baseIndex = d_baseIndex.getValue(); - - const OutVecCoord &frame = - m_toModel->read(core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord *x1fromData = - m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); - type::vector<Vec6> local_F_Vec; - local_F_Vec.clear(); - - out1.resize(x1from.size()); - - // convert the input from Deriv type to vec6 type, for the purpose of the - // matrix vector multiplication - for (unsigned int var = 0; var < in.size(); ++var) { - type::Vec6 vec; - for (unsigned j = 0; j < 6; j++) - vec[j] = in[var][j]; - // Convert input from global frame(SOFA) to local frame - Transform _T = - Transform(frame[var].getCenter(), frame[var].getOrientation()); - Mat6x6 P_trans = (this->buildProjector(_T)); - P_trans.transpose(); - type::Vec6 local_F = P_trans * vec; - local_F_Vec.push_back(local_F); - } - - // Compute output forces - auto sz = m_indicesVectors.size(); - auto index = m_indicesVectors[sz - 1]; - m_totalBeamForceVectors.clear(); - m_totalBeamForceVectors.resize(sz); - - Vec6 F_tot; - F_tot.clear(); - m_totalBeamForceVectors.push_back(F_tot); - - Mat3x6 matB_trans; - matB_trans.clear(); - for (unsigned int k = 0; k < 3; k++) - matB_trans[k][k] = 1.0; - - for (auto s = sz; s--;) { - Mat6x6 coAdjoint; - - this->computeCoAdjoint( - m_framesExponentialSE3Vectors[s], - coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; - Mat6x6 temp = - m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in - // applyJ (here we transpose) - temp.transpose(); - type::Vec3 f = matB_trans * temp * node_F_Vec; - - if (index != m_indicesVectors[s]) { - index--; - // bring F_tot to the reference of the new beam - this->computeCoAdjoint( - m_nodesExponentialSE3Vectors[index], - coAdjoint); // m_nodesExponentialSE3Vectors computed in apply - F_tot = coAdjoint * F_tot; - Mat6x6 temp = m_nodesTangExpVectors[index]; - temp.transpose(); - // apply F_tot to the new beam - type::Vec3 temp_f = matB_trans * temp * F_tot; - out1[index - 1] += temp_f; - } + const sofa::core::MechanicalParams * /*mparams*/, + const vector<In1DataVecDeriv *> &dataVecOut1Force, + const vector<In2DataVecDeriv *> &dataVecOut2Force, + const vector<const OutDataVecDeriv *> &dataVecInForce) { + + if (dataVecOut1Force.empty() || dataVecInForce.empty() || + dataVecOut2Force.empty()) + return; + if (d_debug.getValue()) - std::cout << "f at s =" << s << " and index" << index << " is : " << f - << std::endl; + std::cout << " ########## ApplyJT force Function ########" << std::endl; + const OutVecDeriv &in = dataVecInForce[0]->getValue(); + + In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); + In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); + const auto baseIndex = d_baseIndex.getValue(); + + const OutVecCoord &frame = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord *x1fromData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + vector<Vec6> local_F_Vec; + local_F_Vec.clear(); + + out1.resize(x1from.size()); + + // convert the input from Deriv type to vec6 type, for the purpose of the + // matrix vector multiplication + for (unsigned int var = 0; var < in.size(); ++var) { + Vec6 vec; + for (unsigned j = 0; j < 6; j++) + vec[j] = in[var][j]; + // Convert input from global frame(SOFA) to local frame + Transform _T = + Transform(frame[var].getCenter(), frame[var].getOrientation()); + Mat6x6 P_trans = (this->buildProjector(_T)); + P_trans.transpose(); + Vec6 local_F = P_trans * vec; + local_F_Vec.push_back(local_F); + } - // compute F_tot - F_tot += node_F_Vec; - out1[m_indicesVectors[s] - 1] += f; - } + // Compute output forces + auto sz = m_indicesVectors.size(); + auto index = m_indicesVectors[sz - 1]; + m_totalBeamForceVectors.clear(); + m_totalBeamForceVectors.resize(sz); - Transform frame0 = Transform(frame[0].getCenter(), frame[0].getOrientation()); - Mat6x6 M = this->buildProjector(frame0); - out2[baseIndex] += M * F_tot; + Vec6 F_tot; + F_tot.clear(); + m_totalBeamForceVectors.push_back(F_tot); - if (d_debug.getValue()) { - std::cout << "Node forces " << out1 << std::endl; - std::cout << "base Force: " << out2[baseIndex] << std::endl; - } + Mat3x6 matB_trans; + matB_trans.clear(); + for (unsigned int k = 0; k < 3; k++) + matB_trans[k][k] = 1.0; - dataVecOut1Force[0]->endEdit(); - dataVecOut2Force[0]->endEdit(); -} + for (auto s = sz; s--;) { + Mat6x6 coAdjoint; -template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const core::ConstraintParams * /*cparams*/, - const type::vector<In1DataMatrixDeriv *> &dataMatOut1Const, - const type::vector<In2DataMatrixDeriv *> &dataMatOut2Const, - const type::vector<const OutDataMatrixDeriv *> &dataMatInConst) { - if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || - dataMatInConst.empty()) - return; - - if (d_debug.getValue()) - std::cout << " ########## ApplyJT Constraint Function ########" - << std::endl; - // We need only one input In model and input Root model (if present) - In1MatrixDeriv &out1 = - *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space - // (reduced coordinate) - In2MatrixDeriv &out2 = - *dataMatOut2Const[0] - ->beginEdit(); // constraints on the reference frame (base frame) - const OutMatrixDeriv &in = - dataMatInConst[0] - ->getValue(); // input constraints defined on the mapped frames - - const OutVecCoord &frame = - m_toModel->read(core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord *x1fromData = - m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); - - Mat3x6 matB_trans; - matB_trans.clear(); - for (unsigned int k = 0; k < 3; k++) - matB_trans[k][k] = 1.0; - - type::vector<std::tuple<int, Vec6>> NodesInvolved; - type::vector<std::tuple<int, Vec6>> NodesInvolvedCompressed; - // helper::vector<Vec6> NodesConstraintDirection; - - typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); - - for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); - rowIt != rowItEnd; ++rowIt) { - if (d_debug.getValue()) { - std::cout << "************* Apply JT (MatrixDeriv) iteration on line "; - std::cout << rowIt.index(); - std::cout << "************* " << std::endl; - } - typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); - typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); - - // Creates a constraints if the input constraint is not empty. - if (colIt == colItEnd) { - if (d_debug.getValue()) { - std::cout << "no column for this constraint" << std::endl; - } - continue; + this->computeCoAdjoint( + m_framesExponentialSE3Vectors[s], + coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; + Mat6x6 temp = + m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in + // applyJ (here we transpose) + temp.transpose(); + Vec3 f = matB_trans * temp * node_F_Vec; + + if (index != m_indicesVectors[s]) { + index--; + // bring F_tot to the reference of the new beam + this->computeCoAdjoint( + m_nodesExponentialSE3Vectors[index], + coAdjoint); // m_nodesExponentialSE3Vectors computed in apply + F_tot = coAdjoint * F_tot; + Mat6x6 temp = m_nodesTangExpVectors[index]; + temp.transpose(); + // apply F_tot to the new beam + Vec3 temp_f = matB_trans * temp * F_tot; + out1[index - 1] += temp_f; + } + if (d_debug.getValue()) + std::cout << "f at s =" << s << " and index" << index << " is : " << f + << std::endl; + + // compute F_tot + F_tot += node_F_Vec; + out1[m_indicesVectors[s] - 1] += f; } - typename In1MatrixDeriv::RowIterator o1 = - out1.writeLine(rowIt.index()); // we store the constraint number - typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); - - NodesInvolved.clear(); - while (colIt != colItEnd) { - int childIndex = colIt.index(); - - const OutDeriv valueConst_ = colIt.val(); - type::Vec6 valueConst; - for (unsigned j = 0; j < 6; j++) - valueConst[j] = valueConst_[j]; - - int indexBeam = m_indicesVectors[childIndex]; - - Transform _T = Transform(frame[childIndex].getCenter(), - frame[childIndex].getOrientation()); - Mat6x6 P_trans = (this->buildProjector(_T)); - P_trans.transpose(); - - Mat6x6 coAdjoint; - this->computeCoAdjoint( - m_framesExponentialSE3Vectors[childIndex], - coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] - // computed in applyJ - // (here we transpose) - temp.transpose(); - - type::Vec6 local_F = - coAdjoint * P_trans * - valueConst; // constraint direction in local frame of the beam. - - type::Vec3 f = matB_trans * temp * - local_F; // constraint direction in the strain space. - o1.addCol(indexBeam - 1, f); - std::tuple<int, Vec6> test = std::make_tuple(indexBeam, local_F); + Transform frame0 = Transform(frame[0].getCenter(), frame[0].getOrientation()); + Mat6x6 M = this->buildProjector(frame0); + out2[baseIndex] += M * F_tot; - NodesInvolved.push_back(test); - colIt++; - } if (d_debug.getValue()) { - std::cout << "==> NodesInvolved : " << std::endl; - for (size_t i = 0; i < NodesInvolved.size(); i++) - std::cout << "index :" << get<0>(NodesInvolved[i]) - << " force :" << get<1>(NodesInvolved[i]) << "\n "; + std::cout << "Node forces " << out1 << std::endl; + std::cout << "base Force: " << out2[baseIndex] << std::endl; } - // sort the Nodes Invoved by decreasing order - std::sort( - begin(NodesInvolved), end(NodesInvolved), - [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { - return std::get<0>(t1) > std::get<0>(t2); // custom compare function - }); - - NodesInvolvedCompressed.clear(); - - for (unsigned n = 0; n < NodesInvolved.size(); n++) { - std::tuple<int, Vec6> test_i = NodesInvolved[n]; - int numNode_i = std::get<0>(test_i); - Vec6 cumulativeF = std::get<1>(test_i); - - if (n < NodesInvolved.size() - 1) { - std::tuple<int, Vec6> test_i1 = NodesInvolved[n + 1]; - int numNode_i1 = std::get<0>(test_i1); - - while (numNode_i == numNode_i1) { - cumulativeF += std::get<1>(test_i1); - //// This was if ((n!=NodesInvolved.size()-2)||(n==0)) before and I - ///change it to - /// if ((n!=NodesInvolved.size()-1)||(n==0)) since the code can't - /// leave the will loop - if ((n != NodesInvolved.size() - 1) || (n == 0)) { - n++; - break; - } - test_i1 = NodesInvolved[n + 1]; - numNode_i1 = std::get<0>(test_i1); - } - } - NodesInvolvedCompressed.push_back( - std::make_tuple(numNode_i, cumulativeF)); - } + dataVecOut1Force[0]->endEdit(); + dataVecOut2Force[0]->endEdit(); +} - if (d_debug.getValue()) { - std::cout << " NodesInvolved after sort and compress" << std::endl; - for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) - std::cout << "index :" << get<0>(NodesInvolvedCompressed[i]) - << " force :" << get<1>(NodesInvolvedCompressed[i]) << "\n "; - } +template <class TIn1, class TIn2, class TOut> +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( + const sofa::core::ConstraintParams * /*cparams*/, + const vector<In1DataMatrixDeriv *> &dataMatOut1Const, + const vector<In2DataMatrixDeriv *> &dataMatOut2Const, + const vector<const OutDataMatrixDeriv *> &dataMatInConst) { + if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || + dataMatInConst.empty()) + return; - for (unsigned n = 0; n < NodesInvolvedCompressed.size(); n++) { - std::tuple<int, Vec6> test = NodesInvolvedCompressed[n]; - int numNode = std::get<0>(test); - int i = numNode; - Vec6 CumulativeF = std::get<1>(test); + if (d_debug.getValue()) + std::cout << " ########## ApplyJT Constraint Function ########" + << std::endl; + // We need only one input In model and input Root model (if present) + In1MatrixDeriv &out1 = + *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space + // (reduced coordinate) + In2MatrixDeriv &out2 = + *dataMatOut2Const[0] + ->beginEdit(); // constraints on the reference frame (base frame) + const OutMatrixDeriv &in = + dataMatInConst[0] + ->getValue(); // input constraints defined on the mapped frames + + const OutVecCoord &frame = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord *x1fromData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + + Mat3x6 matB_trans; + matB_trans.clear(); + for (unsigned int k = 0; k < 3; k++) + matB_trans[k][k] = 1.0; + + vector<std::tuple<int, Vec6>> NodesInvolved; + vector<std::tuple<int, Vec6>> NodesInvolvedCompressed; + // helper::vector<Vec6> NodesConstraintDirection; + + typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + + for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); + rowIt != rowItEnd; ++rowIt) { + if (d_debug.getValue()) { + std::cout << "************* Apply JT (MatrixDeriv) iteration on line "; + std::cout << rowIt.index(); + std::cout << "************* " << std::endl; + } + typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); + typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); + + // Creates a constraints if the input constraint is not empty. + if (colIt == colItEnd) { + if (d_debug.getValue()) { + std::cout << "no column for this constraint" << std::endl; + } + continue; + } + typename In1MatrixDeriv::RowIterator o1 = + out1.writeLine(rowIt.index()); // we store the constraint number + typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + + NodesInvolved.clear(); + while (colIt != colItEnd) { + int childIndex = colIt.index(); + + const OutDeriv valueConst_ = colIt.val(); + Vec6 valueConst; + for (unsigned j = 0; j < 6; j++) + valueConst[j] = valueConst_[j]; + + int indexBeam = m_indicesVectors[childIndex]; + + Transform _T = Transform(frame[childIndex].getCenter(), + frame[childIndex].getOrientation()); + Mat6x6 P_trans = (this->buildProjector(_T)); + P_trans.transpose(); + + Mat6x6 coAdjoint; + this->computeCoAdjoint( + m_framesExponentialSE3Vectors[childIndex], + coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] + // computed in applyJ + // (here we transpose) + temp.transpose(); + + Vec6 local_F = + coAdjoint * P_trans * + valueConst; // constraint direction in local frame of the beam. + + Vec3 f = matB_trans * temp * + local_F; // constraint direction in the strain space. - while (i > 0) { - // cumulate on beam frame - Mat6x6 coAdjoint; - this->computeCoAdjoint( - m_nodesExponentialSE3Vectors[i - 1], - coAdjoint); // m_nodesExponentialSE3Vectors computed in apply - CumulativeF = coAdjoint * CumulativeF; - // transfer to strain space (local coordinates) - Mat6x6 temp = m_nodesTangExpVectors[i - 1]; - temp.transpose(); - type::Vec3 temp_f = matB_trans * temp * CumulativeF; + o1.addCol(indexBeam - 1, f); + std::tuple<int, Vec6> test = std::make_tuple(indexBeam, local_F); - if (i > 1) - o1.addCol(i - 2, temp_f); - i--; - } + NodesInvolved.push_back(test); + colIt++; + } + if (d_debug.getValue()) { + std::cout << "==> NodesInvolved : " << std::endl; + for (size_t i = 0; i < NodesInvolved.size(); i++) + std::cout << "index :" << get<0>(NodesInvolved[i]) + << " force :" << get<1>(NodesInvolved[i]) << "\n "; + } - Transform frame0 = - Transform(frame[0].getCenter(), frame[0].getOrientation()); - Mat6x6 M = this->buildProjector(frame0); + // sort the Nodes Invoved by decreasing order + std::sort( + begin(NodesInvolved), end(NodesInvolved), + [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { + return std::get<0>(t1) > std::get<0>(t2); // custom compare function + }); + + NodesInvolvedCompressed.clear(); + + for (unsigned n = 0; n < NodesInvolved.size(); n++) { + std::tuple<int, Vec6> test_i = NodesInvolved[n]; + int numNode_i = std::get<0>(test_i); + Vec6 cumulativeF = std::get<1>(test_i); + + if (n < NodesInvolved.size() - 1) { + std::tuple<int, Vec6> test_i1 = NodesInvolved[n + 1]; + int numNode_i1 = std::get<0>(test_i1); + + while (numNode_i == numNode_i1) { + cumulativeF += std::get<1>(test_i1); + //// This was if ((n!=NodesInvolved.size()-2)||(n==0)) before and I + ///change it to + /// if ((n!=NodesInvolved.size()-1)||(n==0)) since the code can't + /// leave the will loop + if ((n != NodesInvolved.size() - 1) || (n == 0)) { + n++; + break; + } + test_i1 = NodesInvolved[n + 1]; + numNode_i1 = std::get<0>(test_i1); + } + } + NodesInvolvedCompressed.push_back( + std::make_tuple(numNode_i, cumulativeF)); + } - Vec6 base_force = M * CumulativeF; - o2.addCol(d_baseIndex.getValue(), base_force); + if (d_debug.getValue()) { + std::cout << " NodesInvolved after sort and compress" << std::endl; + for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) + std::cout << "index :" << get<0>(NodesInvolvedCompressed[i]) + << " force :" << get<1>(NodesInvolvedCompressed[i]) << "\n "; + } + + for (unsigned n = 0; n < NodesInvolvedCompressed.size(); n++) { + std::tuple<int, Vec6> test = NodesInvolvedCompressed[n]; + int numNode = std::get<0>(test); + int i = numNode; + Vec6 CumulativeF = std::get<1>(test); + + while (i > 0) { + // cumulate on beam frame + Mat6x6 coAdjoint; + this->computeCoAdjoint( + m_nodesExponentialSE3Vectors[i - 1], + coAdjoint); // m_nodesExponentialSE3Vectors computed in apply + CumulativeF = coAdjoint * CumulativeF; + // transfer to strain space (local coordinates) + Mat6x6 temp = m_nodesTangExpVectors[i - 1]; + temp.transpose(); + Vec3 temp_f = matB_trans * temp * CumulativeF; + + if (i > 1) + o1.addCol(i - 2, temp_f); + i--; + } + + Transform frame0 = + Transform(frame[0].getCenter(), frame[0].getOrientation()); + Mat6x6 M = this->buildProjector(frame0); + + Vec6 base_force = M * CumulativeF; + o2.addCol(d_baseIndex.getValue(), base_force); + } } - } - //"""END ARTICULATION SYSTEM MAPPING""" - dataMatOut1Const[0]->endEdit(); - dataMatOut2Const[0]->endEdit(); + //"""END ARTICULATION SYSTEM MAPPING""" + dataMatOut1Const[0]->endEdit(); + dataMatOut2Const[0]->endEdit(); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeBBox( - const core::ExecParams *, bool) { - // const VecCoord& x = getVertices(); //m_vertices.getValue(); - const OutVecCoord &x = - m_toModel->read(core::ConstVecCoordId::position())->getValue(); - - SReal minBBox[3] = {std::numeric_limits<Real1>::max(), - std::numeric_limits<Real1>::max(), - std::numeric_limits<Real1>::max()}; - SReal maxBBox[3] = {-std::numeric_limits<Real1>::max(), - -std::numeric_limits<Real1>::max(), - -std::numeric_limits<Real1>::max()}; - for (std::size_t i = 0; i < x.size(); i++) { - const OutCoord &p = x[i]; - for (int c = 0; c < 3; c++) { - if (p[c] > maxBBox[c]) - maxBBox[c] = p[c]; - if (p[c] < minBBox[c]) - minBBox[c] = p[c]; + const sofa::core::ExecParams *, bool) { + // const VecCoord& x = getVertices(); //m_vertices.getValue(); + const OutVecCoord &x = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + + SReal minBBox[3] = {std::numeric_limits<Real1>::max(), + std::numeric_limits<Real1>::max(), + std::numeric_limits<Real1>::max()}; + SReal maxBBox[3] = {-std::numeric_limits<Real1>::max(), + -std::numeric_limits<Real1>::max(), + -std::numeric_limits<Real1>::max()}; + for (std::size_t i = 0; i < x.size(); i++) { + const OutCoord &p = x[i]; + for (int c = 0; c < 3; c++) { + if (p[c] > maxBBox[c]) + maxBBox[c] = p[c]; + if (p[c] < minBBox[c]) + minBBox[c] = p[c]; + } } - } - this->f_bbox.setValue(sofa::type::TBoundingBox<SReal>(minBBox, maxBBox)); + this->f_bbox.setValue(sofa::type::TBoundingBox<SReal>(minBBox, maxBBox)); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( - const core::visual::VisualParams *vparams) { - if (!vparams->displayFlags().getShowMechanicalMappings()) - return; - - // draw cable - typedef RGBAColor RGBAColor; - - const auto stateLifeCycle = vparams->drawTool()->makeStateLifeCycle(); - - const OutDataVecCoord *xfromData = - m_toModel->read(core::ConstVecCoordId::position()); - const OutVecCoord xData = xfromData->getValue(); - type::vector<type::Vec3> positions; - type::vector<sofa::type::Quat<Real2>> Orientation; - positions.clear(); - Orientation.clear(); - unsigned int sz = xData.size(); - for (unsigned int i = 0; i < sz; i++) { - positions.push_back(xData[i].getCenter()); - Orientation.push_back(xData[i].getOrientation()); - } - - // Get access articulated - const In1DataVecCoord *artiData = - m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord xPos = artiData->getValue(); - - RGBAColor drawColor = d_color.getValue(); - // draw each segment of the beam as a cylinder. - for (unsigned int i = 0; i < sz - 1; i++) - vparams->drawTool()->drawCylinder(positions[i], positions[i + 1], - d_radius.getValue(), drawColor); - - // Define color map - Real2 min = d_min.getValue(); - Real2 max = d_max.getValue(); - helper::ColorMap::evaluator<Real2> _eval = m_colorMap.getEvaluator(min, max); - - glLineWidth(d_radius.getValue()); - glBegin(GL_LINES); - if (d_drawMapBeam.getValue()) { - sofa::type::RGBAColor _color = d_color.getValue(); - RGBAColor colorL = RGBAColor(_color[0], _color[1], _color[2], _color[3]); - glColor4f(colorL[0], colorL[1], colorL[2], colorL[3]); - for (unsigned int i = 0; i < sz - 1; i++) { - vparams->drawTool()->drawLine(positions[i], positions[i + 1], colorL); + const sofa::core::visual::VisualParams *vparams) { + if (!vparams->displayFlags().getShowMechanicalMappings()) + return; + + // draw cable + typedef RGBAColor RGBAColor; + + const auto stateLifeCycle = vparams->drawTool()->makeStateLifeCycle(); + + const OutDataVecCoord *xfromData = + m_toModel->read(sofa::core::ConstVecCoordId::position()); + const OutVecCoord xData = xfromData->getValue(); + vector<Vec3> positions; + vector<sofa::type::Quat<Real2>> Orientation; + positions.clear(); + Orientation.clear(); + unsigned int sz = xData.size(); + for (unsigned int i = 0; i < sz; i++) { + positions.push_back(xData[i].getCenter()); + Orientation.push_back(xData[i].getOrientation()); } - } else { - int j = 0; - type::vector<int> index = d_index.getValue(); - for (unsigned int i = 0; i < sz - 1; i++) { - j = m_indicesVectorsDraw[i] - - 1; // to get the articulation on which the frame is related to - RGBAColor color = _eval(xPos[j][d_deformationAxis.getValue()]); - vparams->drawTool()->drawLine(positions[i], positions[i + 1], color); + + // Get access articulated + const In1DataVecCoord *artiData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord xPos = artiData->getValue(); + + RGBAColor drawColor = d_color.getValue(); + // draw each segment of the beam as a cylinder. + for (unsigned int i = 0; i < sz - 1; i++) + vparams->drawTool()->drawCylinder(positions[i], positions[i + 1], + d_radius.getValue(), drawColor); + + // Define color map + Real2 min = d_min.getValue(); + Real2 max = d_max.getValue(); + sofa::helper::ColorMap::evaluator<Real2> _eval = m_colorMap.getEvaluator(min, max); + + glLineWidth(d_radius.getValue()); + glBegin(GL_LINES); + if (d_drawMapBeam.getValue()) { + sofa::type::RGBAColor _color = d_color.getValue(); + RGBAColor colorL = RGBAColor(_color[0], _color[1], _color[2], _color[3]); + glColor4f(colorL[0], colorL[1], colorL[2], colorL[3]); + for (unsigned int i = 0; i < sz - 1; i++) { + vparams->drawTool()->drawLine(positions[i], positions[i + 1], colorL); + } + } else { + int j = 0; + vector<int> index = d_index.getValue(); + for (unsigned int i = 0; i < sz - 1; i++) { + j = m_indicesVectorsDraw[i] - + 1; // to get the articulation on which the frame is related to + RGBAColor color = _eval(xPos[j][d_deformationAxis.getValue()]); + vparams->drawTool()->drawLine(positions[i], positions[i + 1], color); + } } - } - glLineWidth(1); - if (!vparams->displayFlags().getShowMappings()) - if (!d_debug.getValue()) - return; - glEnd(); + glLineWidth(1); + if (!vparams->displayFlags().getShowMappings()) + if (!d_debug.getValue()) + return; + glEnd(); } } // namespace sofa::component::mapping diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.cpp index e75e962d..a1de1b1b 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.cpp @@ -20,19 +20,19 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #define SOFA_COSSERAT_CPP_DiscreteDynamicCosseratMapping -#include "DiscreteDynamicCosseratMapping.inl" +#include <Cosserat/mapping/DiscreteDynamicCosseratMapping.inl> #include <sofa/defaulttype/VecTypes.h> #include <sofa/defaulttype/RigidTypes.h> #include <sofa/core/ObjectFactory.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using namespace sofa::defaulttype; // Register in the Factory -int DiscretDynamicCosseratMappingClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") +int DiscretDynamicCosseratMappingClass = sofa::core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") .add< DiscreteDynamicCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() ; diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index ad43b528..25eb3a04 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -20,8 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <Cosserat/config.h> - +#include <Cosserat/initCosserat.h> #include <Cosserat/mapping/BaseCosserat.h> #include <sofa/core/BaseMapping.h> @@ -29,15 +28,18 @@ #include <sofa/defaulttype/SolidTypes.h> #include <sofa/defaulttype/RigidTypes.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using sofa::defaulttype::SolidTypes ; using sofa::core::objectmodel::BaseContext ; using sofa::type::Matrix3; using sofa::type::Matrix4; -using type::Vec3; -using type::Vec6; +using sofa::type::Vec3; +using sofa::type::Vec6; using std::get; +using sofa::Data; +using sofa::type::Mat; +using Cosserat::mapping::BaseCosserat; /*! * \class DiscretDynamicCosseratMapping @@ -49,11 +51,13 @@ using std::get; template <class TIn1, class TIn2, class TOut> -class DiscreteDynamicCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TOut>, public component::mapping::BaseCosserat<TIn1, TIn2, TOut> +class DiscreteDynamicCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, + BaseCosserat<TIn1, TIn2, TOut> { public: - SOFA_CLASS(SOFA_TEMPLATE3(DiscreteDynamicCosseratMapping, TIn1,TIn2, TOut), SOFA_TEMPLATE3(core::Multi2Mapping, TIn1, TIn2, TOut) ); - typedef core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; + SOFA_CLASS(SOFA_TEMPLATE3(DiscreteDynamicCosseratMapping, TIn1,TIn2, TOut), + SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut) ); + typedef sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; /// Input Model Type typedef TIn1 In1; @@ -80,10 +84,10 @@ class DiscreteDynamicCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TO typedef Data<In2VecCoord> In2DataVecCoord; typedef Data<In2VecDeriv> In2DataVecDeriv; typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; - typedef type::Mat<6,6,Real> Mat6x6; - typedef type::Mat<3,6,Real> Mat3x6; - typedef type::Mat<6,3,Real> Mat6x3; - typedef type::Mat<4,4,Real> Mat4x4; + typedef Mat<6,6,Real> Mat6x6; + typedef Mat<3,6,Real> Mat3x6; + typedef Mat<6,3,Real> Mat6x3; + typedef Mat<4,4,Real> Mat4x4; typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; @@ -94,19 +98,19 @@ class DiscreteDynamicCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TO typedef Data<OutVecDeriv> OutDataVecDeriv; typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; - typedef MultiLink<DiscreteDynamicCosseratMapping<In1,In2,Out>, sofa::core::State< In1 >, - BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels1; - typedef MultiLink<DiscreteDynamicCosseratMapping<In1,In2,Out>, sofa::core::State< In2 >, - BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkFromModels2; - typedef MultiLink<DiscreteDynamicCosseratMapping<In1,In2,Out>, sofa::core::State< Out >, - BaseLink::FLAG_STOREPATH|BaseLink::FLAG_STRONGLINK> LinkToModels; + typedef sofa::MultiLink<DiscreteDynamicCosseratMapping<In1,In2,Out>, sofa::core::State< In1 >, + sofa::BaseLink::FLAG_STOREPATH|sofa::BaseLink::FLAG_STRONGLINK> LinkFromModels1; + typedef sofa::MultiLink<DiscreteDynamicCosseratMapping<In1,In2,Out>, sofa::core::State< In2 >, + sofa::BaseLink::FLAG_STOREPATH|sofa::BaseLink::FLAG_STRONGLINK> LinkFromModels2; + typedef sofa::MultiLink<DiscreteDynamicCosseratMapping<In1,In2,Out>, sofa::core::State< Out >, + sofa::BaseLink::FLAG_STOREPATH|sofa::BaseLink::FLAG_STRONGLINK> LinkToModels; typedef typename SolidTypes<Real>::Transform Transform ; protected: - core::State<In1>* m_fromModel1; - core::State<In2>* m_fromModel2; - core::State<Out>* m_toModel; + sofa::core::State<In1>* m_fromModel1; + sofa::core::State<In2>* m_fromModel2; + sofa::core::State<Out>* m_toModel; protected: /// Constructor @@ -114,11 +118,11 @@ class DiscreteDynamicCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TO /// Destructor ~DiscreteDynamicCosseratMapping() override {} - type::vector<type::vector<Mat6x3>> m_frameJacobienVector; - type::vector<type::vector<Mat6x3>> m_frameJacobienDotVector; - type::vector<Mat6x6> m_nodeJacobienVector; - type::vector<type::vector<Mat6x6>> m_nodeJacobienDotVector; - type::vector<Matrix3> m_MassExpressionVector; + vector<vector<Mat6x3>> m_frameJacobienVector; + vector<vector<Mat6x3>> m_frameJacobienDotVector; + vector<Mat6x6> m_nodeJacobienVector; + vector<vector<Mat6x6>> m_nodeJacobienDotVector; + vector<Matrix3> m_MassExpressionVector; Mat6x3 m_matrixBi; // matrixB_i is a constant matrix due to the assumption of constant strain along the section ////////////////////////// Inherited attributes //////////////////////////// @@ -127,7 +131,7 @@ class DiscreteDynamicCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TO /// otherwise any access to the base::attribute would require /// the "this->" approach. /// - using BaseCosserat<TIn1, TIn2, TOut>:: m_indicesVectors ; + using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectors ; using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_section ; using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_frames ; using BaseCosserat<TIn1, TIn2, TOut>::m_nodesTangExpVectors; @@ -150,39 +154,44 @@ class DiscreteDynamicCosseratMapping : public core::Multi2Mapping<TIn1, TIn2, TO virtual void bwdInit() override; // get the points virtual void reset() override; virtual void reinit() override; - void draw(const core::visual::VisualParams* vparams) override; + void draw(const sofa::core::visual::VisualParams* vparams) override; /**********************MAPPING METHODS**************************/ void apply( - const core::MechanicalParams* /* mparams */, const type::vector<OutDataVecCoord*>& dataVecOutPos, - const type::vector<const In1DataVecCoord*>& dataVecIn1Pos , - const type::vector<const In2DataVecCoord*>& dataVecIn2Pos) override; + const sofa::core::MechanicalParams* /* mparams */, + const vector<OutDataVecCoord*>& dataVecOutPos, + const vector<const In1DataVecCoord*>& dataVecIn1Pos , + const vector<const In2DataVecCoord*>& dataVecIn2Pos) override; void applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; + const sofa::core::MechanicalParams* /* mparams */, + const vector< OutDataVecDeriv*>& dataVecOutVel, + const vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; //ApplyJT Force void applyJT( - const core::MechanicalParams* /* mparams */, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2RootForce, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) override; + const sofa::core::MechanicalParams* /* mparams */, + const vector< In1DataVecDeriv*>& dataVecOut1Force, + const vector< In2DataVecDeriv*>& dataVecOut2RootForce, + const vector<const OutDataVecDeriv*>& dataVecInForce) override; - void applyDJT(const core::MechanicalParams* /*mparams*/, core::MultiVecDerivId /*inForce*/, - core::ConstMultiVecDerivId /*outForce*/) override{} + void applyDJT(const sofa::core::MechanicalParams* /*mparams*/, + sofa::core::MultiVecDerivId /*inForce*/, + sofa::core::ConstMultiVecDerivId /*outForce*/) override{} /// This method must be reimplemented by all mappings if they need to support constraints. virtual void applyJT( - const core::ConstraintParams* cparams , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const , - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) override; + const sofa::core::ConstraintParams* cparams , + const vector< In1DataMatrixDeriv*>& dataMatOut1Const , + const vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const vector<const OutDataMatrixDeriv*>& dataMatInConst) override; /**********************DISCRET DYNAMIC COSSERAT METHODS**************************/ [[maybe_unused]] void computeMassComponent(const double sectionMass){ SOFA_UNUSED(sectionMass); } - void computeJ_Jdot_i(const Mat6x6 &Adjoint, size_t frameId, type::vector<Mat6x3> &J_i, - const type::Vec6 &etaFrame, type::vector<Mat6x3> &J_dot_i); + void computeJ_Jdot_i(const Mat6x6 &Adjoint, size_t frameId, vector<Mat6x3> &J_i, + const Vec6 &etaFrame, vector<Mat6x3> &J_dot_i); }; diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index 216c9454..cfff43ac 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include "DiscreteDynamicCosseratMapping.h" +#include <Cosserat/mapping/DiscreteDynamicCosseratMapping.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/visual/VisualParams.h> @@ -34,7 +34,7 @@ #include <string> -namespace sofa::component::mapping +namespace Cosserat::mapping { using sofa::core::objectmodel::BaseContext ; using sofa::helper::AdvancedTimer; @@ -43,9 +43,9 @@ using sofa::helper::WriteAccessor; template <class TIn1, class TIn2, class TOut> DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::DiscreteDynamicCosseratMapping() - : m_fromModel1(NULL) - , m_fromModel2(NULL) - , m_toModel(NULL) + : m_fromModel1(NULL) + , m_fromModel2(NULL) + , m_toModel(NULL) { } @@ -57,45 +57,45 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::init() { Inherit1::init(); - if(this->getFromModels1().empty()) - { - msg_error() << "Error while initializing ; input getFromModels1 not found" ; - return; - } - - if(this->getFromModels2().empty()) - { - msg_error() << "Error while initializing ; output getFromModels2 not found" ; - return; - } - - if(this->getToModels().empty()) - { - msg_error() << "Error while initializing ; output Model not found" ; - return; - } - - printf("=================================> Init from the DiscretDynamicCosseratMapping component \n"); - - m_fromModel1 = this->getFromModels1()[0]; - m_fromModel2 = this->getFromModels2()[0]; - m_toModel = this->getToModels()[0]; - - // Fill the initial vector - const OutDataVecCoord* xfromData = m_toModel->read(core::ConstVecCoordId::position()); - const OutVecCoord xfrom = xfromData->getValue(); - // WriteAccessor<Data < helper::vector<double>>> curv_abs_output = d_curv_abs_frames; - // curv_abs_output.clear(); - - m_vecTransform.clear(); - for (unsigned int i = 0; i < xfrom.size(); i++) { - m_vecTransform.push_back(xfrom[i]); - } - - //initialize the constant matrix m_matrixBi[0][0] = 1.0; - for(size_t i = 0 ; i < 3; i++) m_matrixBi[i][i] = 1.0; - - this->initialize(); + if(this->getFromModels1().empty()) + { + msg_error() << "Error while initializing ; input getFromModels1 not found" ; + return; + } + + if(this->getFromModels2().empty()) + { + msg_error() << "Error while initializing ; output getFromModels2 not found" ; + return; + } + + if(this->getToModels().empty()) + { + msg_error() << "Error while initializing ; output Model not found" ; + return; + } + + printf("=================================> Init from the DiscretDynamicCosseratMapping component \n"); + + m_fromModel1 = this->getFromModels1()[0]; + m_fromModel2 = this->getFromModels2()[0]; + m_toModel = this->getToModels()[0]; + + // Fill the initial vector + const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); + const OutVecCoord xfrom = xfromData->getValue(); + // WriteAccessor<Data < helper::vector<double>>> curv_abs_output = d_curv_abs_frames; + // curv_abs_output.clear(); + + m_vecTransform.clear(); + for (unsigned int i = 0; i < xfrom.size(); i++) { + m_vecTransform.push_back(xfrom[i]); + } + + //initialize the constant matrix m_matrixBi[0][0] = 1.0; + for(size_t i = 0 ; i < 3; i++) m_matrixBi[i][i] = 1.0; + + this->initialize(); } @@ -114,130 +114,129 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::reinit() template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::reset() { - reinit(); + reinit(); } template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::apply( - const core::MechanicalParams* /* mparams */, const type::vector<OutDataVecCoord*>& dataVecOutPos, - const type::vector<const In1DataVecCoord*>& dataVecIn1Pos , - const type::vector<const In2DataVecCoord*>& dataVecIn2Pos) + const sofa::core::MechanicalParams* /* mparams */, + const vector<OutDataVecCoord*>& dataVecOutPos, + const vector<const In1DataVecCoord*>& dataVecIn1Pos , + const vector<const In2DataVecCoord*>& dataVecIn2Pos) { - if(dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) - return; + if(dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) + return; - ///Do Apply - //We need only one input In model and input Root model (if present) - const In1VecCoord& in1 = dataVecIn1Pos[0]->getValue(); - const In2VecCoord& in2 = dataVecIn2Pos[0]->getValue(); + ///Do Apply + //We need only one input In model and input Root model (if present) + const In1VecCoord& in1 = dataVecIn1Pos[0]->getValue(); + const In2VecCoord& in2 = dataVecIn2Pos[0]->getValue(); - size_t sz = d_curv_abs_frames.getValue().size(); - OutVecCoord& out = *dataVecOutPos[0]->beginEdit(); - out.resize(sz); + size_t sz = d_curv_abs_frames.getValue().size(); + OutVecCoord& out = *dataVecOutPos[0]->beginEdit(); + out.resize(sz); - //update the Exponential Matrices according to new deformation + //update the Exponential Matrices according to new deformation this->updateExponentialSE3(in1); - Transform frame0 = Transform(In2::getCPos(in2[0]),In2::getCRot(in2[0])); - for(unsigned int i=0; i<sz; i++){ - Transform frame = frame0; - for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { - frame *= m_nodesExponentialSE3Vectors[u]; - } - frame *= m_framesExponentialSE3Vectors[i]; - - type::Vec3 v = frame.getOrigin(); - type::Quat q = frame.getOrientation(); - out[i] = OutCoord(v,q); - } - - m_index_input = 0; - dataVecOutPos[0]->endEdit(); + Transform frame0 = Transform(In2::getCPos(in2[0]),In2::getCRot(in2[0])); + for(unsigned int i=0; i<sz; i++){ + Transform frame = frame0; + for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { + frame *= m_nodesExponentialSE3Vectors[u]; + } + frame *= m_framesExponentialSE3Vectors[i]; + + Vec3 v = frame.getOrigin(); + sofa::type::Quat q = frame.getOrientation(); + out[i] = OutCoord(v,q); + } + + m_index_input = 0; + dataVecOutPos[0]->endEdit(); } - - template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) { - - if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) - return; - const In1VecDeriv& in1 = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv& in2_vecDeriv = dataVecIn2Vel[0]->getValue(); - OutVecDeriv& outVel = *dataVecOutVel[0]->beginEdit(); - - - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_input = d_curv_abs_section; // This is the vector of X in the paper - helper::ReadAccessor<Data<type::vector<double>>> curv_abs_output = d_curv_abs_frames; - helper::ReadAccessor<Data<bool>> debug = d_debug; - m_frameJacobienVector.clear(); - m_frameJacobienDotVector.clear(); - - - // Compute the tangent Exponential SE3 vectors - const In1VecCoord& inDeform = m_fromModel1->read(core::ConstVecCoordId::position())->getValue(); + const sofa::core::MechanicalParams* /* mparams */, + const vector< OutDataVecDeriv*>& dataVecOutVel, + const vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const vector<const In2DataVecDeriv*>& dataVecIn2Vel) { + + if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) + return; + const In1VecDeriv& in1 = dataVecIn1Vel[0]->getValue(); + const In2VecDeriv& in2_vecDeriv = dataVecIn2Vel[0]->getValue(); + OutVecDeriv& outVel = *dataVecOutVel[0]->beginEdit(); + + sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_input = d_curv_abs_section; // This is the vector of X in the paper + sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_output = d_curv_abs_frames; + sofa::helper::ReadAccessor<Data<bool>> debug = d_debug; + m_frameJacobienVector.clear(); + m_frameJacobienDotVector.clear(); + + // Compute the tangent Exponential SE3 vectors + const In1VecCoord& inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); this->updateTangExpSE3(inDeform); - //Get base velocity as input this is also called eta - m_nodesVelocityVectors.clear(); - Deriv2 _baseVelocity; - if (!in2_vecDeriv.empty()) - _baseVelocity = in2_vecDeriv[0]; - //convert to Vec6 - type::Vec6 baseVelocity; - for (size_t u=0;u<6;u++) {baseVelocity[u] = _baseVelocity[u];} - - //Apply the local transform i.e from SOFA frame to Frederico frame - const In2VecCoord& xfrom2Data = m_fromModel2->read(core::ConstVecCoordId::position())->getValue(); - Transform Tinverse = Transform(xfrom2Data[0].getCenter(),xfrom2Data[0].getOrientation()).inversed(); - Mat6x6 P = this->buildProjector(Tinverse); - m_nodeAdjointVectors.clear(); + //Get base velocity as input this is also called eta + m_nodesVelocityVectors.clear(); + Deriv2 _baseVelocity; + if (!in2_vecDeriv.empty()) + _baseVelocity = in2_vecDeriv[0]; - type::Vec6 baseLocalVelocity = P * baseVelocity; - m_nodesVelocityVectors.push_back(baseLocalVelocity); - if(debug) - std::cout << "Base local Velocity :"<< baseLocalVelocity <<std::endl; + //convert to Vec6 + Vec6 baseVelocity; + for (size_t u=0;u<6;u++) {baseVelocity[u] = _baseVelocity[u];} - //Compute velocity at nodes - for (size_t i = 1 ; i < curv_abs_input.size(); i++) { - Transform t= m_nodesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; Adjoint.clear(); - this->computeAdjoint(t,Adjoint); - //Add this line because need for the jacobian computation - m_nodeAdjointVectors.push_back(Adjoint); + //Apply the local transform i.e from SOFA frame to Frederico frame + const In2VecCoord& xfrom2Data = m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); + Transform Tinverse = Transform(xfrom2Data[0].getCenter(),xfrom2Data[0].getOrientation()).inversed(); + Mat6x6 P = this->buildProjector(Tinverse); + m_nodeAdjointVectors.clear(); + + Vec6 baseLocalVelocity = P * baseVelocity; + m_nodesVelocityVectors.push_back(baseLocalVelocity); + if(debug) + std::cout << "Base local Velocity :"<< baseLocalVelocity <<std::endl; + + //Compute velocity at nodes + for (size_t i = 1 ; i < curv_abs_input.size(); i++) + { + Transform t= m_nodesExponentialSE3Vectors[i].inversed(); + Mat6x6 Adjoint; Adjoint.clear(); + this->computeAdjoint(t,Adjoint); + //Add this line because need for the jacobian computation + m_nodeAdjointVectors.push_back(Adjoint); //Compute velocity (eta) at node i != 0 eq.(13) paper - type::Vec6 Xi_dot = Vec6(in1[i-1],type::Vec3(0.0,0.0,0.0)) ; + Vec6 Xi_dot = Vec6(in1[i-1],Vec3(0.0,0.0,0.0)) ; Vec6 temp = Adjoint * (m_nodesVelocityVectors[i-1] + m_nodesTangExpVectors[i] * Xi_dot ); m_nodesVelocityVectors.push_back(temp); if(debug) - std::cout<< "Node velocity : "<< i << " = " << temp<< std::endl; - } - - const OutVecCoord& out = m_toModel->read(core::ConstVecCoordId::position())->getValue(); - size_t sz =curv_abs_output.size(); - outVel.resize(sz); - for (size_t i = 0 ; i < sz; i++) { - Transform t= m_framesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; Adjoint.clear(); - this->computeAdjoint(t,Adjoint); - - type::Vec6 Xi_dot = Vec6(in1[m_indicesVectors[i]-1], - type::Vec3(0.0,0.0,0.0)) ; + std::cout<< "Node velocity : "<< i << " = " << temp<< std::endl; + } + + const OutVecCoord& out = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + size_t sz =curv_abs_output.size(); + outVel.resize(sz); + for (size_t i = 0 ; i < sz; i++) { + Transform t= m_framesExponentialSE3Vectors[i].inversed(); + Mat6x6 Adjoint; Adjoint.clear(); + this->computeAdjoint(t,Adjoint); + + Vec6 Xi_dot = Vec6(in1[m_indicesVectors[i]-1], Vec3(0.0,0.0,0.0)); // eta Vec6 etaFrame = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * Xi_dot ); //Compute here jacobien and jacobien_dot - type::vector<Mat6x3> J_i, J_dot_i; + vector<Mat6x3> J_i, J_dot_i; computeJ_Jdot_i(Adjoint, i, J_i, etaFrame, J_dot_i); m_frameJacobienVector.push_back(J_i); m_frameJacobienVector.push_back(J_dot_i); @@ -249,334 +248,337 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( outVel[i] = _P * etaFrame; if(debug) - std::cout<< "Frame velocity : "<< i << " = " << etaFrame<< std::endl; - } - // std::cout << "Inside the apply J, outVel after computation : "<< outVel << std::endl; - dataVecOutVel[0]->endEdit(); - m_index_input = 0; + std::cout<< "Frame velocity : "<< i << " = " << etaFrame<< std::endl; + } + // std::cout << "Inside the apply J, outVel after computation : "<< outVel << std::endl; + dataVecOutVel[0]->endEdit(); + m_index_input = 0; } template <class TIn1, class TIn2, class TOut> -void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::computeJ_Jdot_i(const Mat6x6 &Adjoint, size_t frameId, - type::vector<Mat6x3> &J_i, const Vec6& etaFrame, - type::vector<Mat6x3> &J_dot_i){ - size_t sz = d_curv_abs_section.getValue().size(); - Mat6x3 Si; - Mat6x6 M; - - Mat6x3 Si_dot; - Mat6x6 adj_eta; //to be computed - - bool reachNode = false; - for (unsigned int i = 1; i < sz; i++) { - M = Adjoint; - unsigned int u = m_indicesVectors[frameId]; - if(i < u ){ - for (int j = u; j>0; j--) { - M = M * m_nodeAdjointVectors[j] ; - } - Mat6x6 temp = M * m_nodesTangExpVectors[u]; - Si = temp * m_matrixBi; - J_i.push_back(Si); - - Vec6 etaNode = m_nodesVelocityVectors[i]; +void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::computeJ_Jdot_i( + const Mat6x6 &Adjoint, size_t frameId, + vector<Mat6x3> &J_i, const Vec6& etaFrame, vector<Mat6x3> &J_dot_i){ + size_t sz = d_curv_abs_section.getValue().size(); + Mat6x3 Si; + Mat6x6 M; + + Mat6x3 Si_dot; + Mat6x6 adj_eta; //to be computed + + bool reachNode = false; + for (unsigned int i = 1; i < sz; i++) { + M = Adjoint; + unsigned int u = m_indicesVectors[frameId]; + if(i < u ){ + for (int j = u; j>0; j--) { + M = M * m_nodeAdjointVectors[j] ; + } + Mat6x6 temp = M * m_nodesTangExpVectors[u]; + Si = temp * m_matrixBi; + J_i.push_back(Si); + + Vec6 etaNode = m_nodesVelocityVectors[i]; this->computeAdjoint(etaNode, adj_eta); - Si_dot = temp * adj_eta * m_matrixBi; - J_dot_i.push_back(Si_dot); - }else{ - if(!reachNode){ - Mat6x6 temp = M * m_framesTangExpVectors[frameId] ; - Si = temp * m_matrixBi; - J_i.push_back(Si); + Si_dot = temp * adj_eta * m_matrixBi; + J_dot_i.push_back(Si_dot); + }else{ + if(!reachNode){ + Mat6x6 temp = M * m_framesTangExpVectors[frameId] ; + Si = temp * m_matrixBi; + J_i.push_back(Si); this->computeAdjoint(etaFrame, adj_eta); - Si_dot = temp * adj_eta * m_matrixBi; - J_dot_i.push_back(Si_dot); - reachNode = true; - }else { - Si.clear(); - J_i.push_back(Si); - Si_dot.clear(); - J_dot_i.push_back(Si); - } - } - } + Si_dot = temp * adj_eta * m_matrixBi; + J_dot_i.push_back(Si_dot); + reachNode = true; + }else { + Si.clear(); + J_i.push_back(Si); + Si_dot.clear(); + J_dot_i.push_back(Si); + } + } + } } template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJT( - const core::MechanicalParams* /*mparams*/, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2Force, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) { + const sofa::core::MechanicalParams* /*mparams*/, + const vector< In1DataVecDeriv*>& dataVecOut1Force, + const vector< In2DataVecDeriv*>& dataVecOut2Force, + const vector<const OutDataVecDeriv*>& dataVecInForce) { - if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) - return; + if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) + return; - const OutVecDeriv& in = dataVecInForce[0]->getValue(); + const OutVecDeriv& in = dataVecInForce[0]->getValue(); - In1VecDeriv& out1 = *dataVecOut1Force[0]->beginEdit(); - In2VecDeriv& out2 = *dataVecOut2Force[0]->beginEdit(); + In1VecDeriv& out1 = *dataVecOut1Force[0]->beginEdit(); + In2VecDeriv& out2 = *dataVecOut2Force[0]->beginEdit(); - //Maybe need, in case the apply funcion is not call this must be call before - const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); - type::vector<Vec6> local_F_Vec ; local_F_Vec.clear(); + //Maybe need, in case the apply funcion is not call this must be call before + const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + vector<Vec6> local_F_Vec ; local_F_Vec.clear(); - out1.resize(x1from.size()); + out1.resize(x1from.size()); - //convert the input from Deriv type to vec6 type, for the purpose of the matrix vector multiplication - for (size_t var = 0; var < in.size(); ++var) { - type::Vec6 vec; - for(unsigned j = 0; j < 6; j++) vec[j] = in[var][j]; + //convert the input from Deriv type to vec6 type, for the purpose of the matrix vector multiplication + for (size_t var = 0; var < in.size(); ++var) + { + Vec6 vec; + for(unsigned j = 0; j < 6; j++) vec[j] = in[var][j]; - //Convert input from global frame(SOFA) to local frame - Transform _T = Transform(frame[var].getCenter(),frame[var].getOrientation()); + //Convert input from global frame(SOFA) to local frame + Transform _T = Transform(frame[var].getCenter(),frame[var].getOrientation()); Mat6x6 P_trans =(this->buildProjector(_T)); P_trans.transpose(); - type::Vec6 local_F = P_trans * vec; - local_F_Vec.push_back(local_F); - } - - //Compute output forces - size_t sz = m_indicesVectors.size(); - - unsigned int index = m_indicesVectors[sz-1]; - m_totalBeamForceVectors.clear(); - m_totalBeamForceVectors.resize(sz); - - Vec6 F_tot; F_tot.clear(); - m_totalBeamForceVectors.push_back(F_tot); - - Mat3x6 matB_trans; matB_trans.clear(); - for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; - for (unsigned int s = sz ; s-- ; ) { - Mat6x6 coAdjoint; - // - this->computeCoAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; - Mat6x6 temp = m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) - temp.transpose(); - type::Vec3 f = matB_trans * temp * node_F_Vec; - - if(index!=m_indicesVectors[s]){ // TODO to be replaced by while - index--; - //bring F_tot to the reference of the new beam - this->computeCoAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply - F_tot = coAdjoint * F_tot; - Mat6x6 temp = m_nodesTangExpVectors[index]; - temp.transpose(); - //apply F_tot to the new beam - type::Vec3 temp_f = matB_trans * temp * F_tot; - out1[index-1] += temp_f; - } - if(d_debug.getValue()) - std::cout << "f at s ="<< s <<" and index"<< index << " is : "<< f << std::endl; - - //compte F_tot - F_tot += node_F_Vec; - out1[m_indicesVectors[s]-1] += f; - } - Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); + Vec6 local_F = P_trans * vec; + local_F_Vec.push_back(local_F); + } + + //Compute output forces + size_t sz = m_indicesVectors.size(); + + unsigned int index = m_indicesVectors[sz-1]; + m_totalBeamForceVectors.clear(); + m_totalBeamForceVectors.resize(sz); + + Vec6 F_tot; F_tot.clear(); + m_totalBeamForceVectors.push_back(F_tot); + + Mat3x6 matB_trans; matB_trans.clear(); + for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; + for (unsigned int s = sz ; s-- ; ) { + Mat6x6 coAdjoint; + // + this->computeCoAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; + Mat6x6 temp = m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) + temp.transpose(); + Vec3 f = matB_trans * temp * node_F_Vec; + + if(index!=m_indicesVectors[s]){ // TODO to be replaced by while + index--; + //bring F_tot to the reference of the new beam + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[index],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + F_tot = coAdjoint * F_tot; + Mat6x6 temp = m_nodesTangExpVectors[index]; + temp.transpose(); + //apply F_tot to the new beam + Vec3 temp_f = matB_trans * temp * F_tot; + out1[index-1] += temp_f; + } + if(d_debug.getValue()) + std::cout << "f at s ="<< s <<" and index"<< index << " is : "<< f << std::endl; + + //compte F_tot + F_tot += node_F_Vec; + out1[m_indicesVectors[s]-1] += f; + } + Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); Mat6x6 M = this->buildProjector(frame0); - out2[0] += M * F_tot; + out2[0] += M * F_tot; - if(d_debug.getValue()){ - std::cout << "Node forces "<< out1 << std::endl; - std::cout << "base Force: "<< out2[0] << std::endl; - } + if(d_debug.getValue()){ + std::cout << "Node forces "<< out1 << std::endl; + std::cout << "base Force: "<< out2[0] << std::endl; + } - dataVecOut1Force[0]->endEdit(); - dataVecOut2Force[0]->endEdit(); + dataVecOut1Force[0]->endEdit(); + dataVecOut2Force[0]->endEdit(); } //___________________________________________________________________________ template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const core::ConstraintParams*/*cparams*/ , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const, - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) + const sofa::core::ConstraintParams*/*cparams*/ , + const vector< In1DataMatrixDeriv*>& dataMatOut1Const, + const vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const vector<const OutDataMatrixDeriv*>& dataMatInConst) { - if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) - return; - - //We need only one input In model and input Root model (if present) - In1MatrixDeriv& out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space (reduced coordinate) - In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) - const OutMatrixDeriv& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames + if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) + return; - const OutVecCoord& frame = m_toModel->read(core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord* x1fromData = m_fromModel1->read(core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); - helper::ReadAccessor<Data<bool>> debug = d_debug; + //We need only one input In model and input Root model (if present) + In1MatrixDeriv& out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space (reduced coordinate) + In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) + const OutMatrixDeriv& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames - Mat3x6 matB_trans; matB_trans.clear(); - for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; + const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + sofa::helper::ReadAccessor<Data<bool>> debug = d_debug; + Mat3x6 matB_trans; matB_trans.clear(); + for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; - type::vector< std::tuple<int,Vec6> > NodesInvolved; - type::vector< std::tuple<int,Vec6> > NodesInvolvedCompressed; - //helper::vector<Vec6> NodesConstraintDirection; + vector< std::tuple<int,Vec6> > NodesInvolved; + vector< std::tuple<int,Vec6> > NodesInvolvedCompressed; + //helper::vector<Vec6> NodesConstraintDirection; - typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); - for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) - { - if (debug){ - std::cout<<"************* Apply JT (MatrixDeriv) iteration on line "; - std::cout<<rowIt.index(); - std::cout<<"************* "<<std::endl; - } - typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); - typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); + for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) + { + if (debug) + { + std::cout<<"************* Apply JT (MatrixDeriv) iteration on line "; + std::cout<<rowIt.index(); + std::cout<<"************* "<<std::endl; + } + typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); + typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); - // Creates a constraints if the input constraint is not empty. + // Creates a constraints if the input constraint is not empty. - if (colIt == colItEnd) - { - if (debug){ - std::cout<<"no column for this constraint"<<std::endl; - } - continue; - } - typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number - typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + if (colIt == colItEnd) + { + if (debug){ + std::cout<<"no column for this constraint"<<std::endl; + } + continue; + } + typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number + typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); - NodesInvolved.clear(); - //NodesConstraintDirection.clear(); + NodesInvolved.clear(); + //NodesConstraintDirection.clear(); - while (colIt != colItEnd) - { - int childIndex = colIt.index(); + while (colIt != colItEnd) + { + int childIndex = colIt.index(); - const OutDeriv valueConst_ = colIt.val(); - type::Vec6 valueConst; - for(unsigned j = 0; j < 6; j++) valueConst[j] = valueConst_[j]; + const OutDeriv valueConst_ = colIt.val(); + Vec6 valueConst; + for(unsigned j = 0; j < 6; j++) valueConst[j] = valueConst_[j]; - int indexBeam = m_indicesVectors[childIndex]; + int indexBeam = m_indicesVectors[childIndex]; - Transform _T = Transform(frame[childIndex].getCenter(),frame[childIndex].getOrientation()); + Transform _T = Transform(frame[childIndex].getCenter(),frame[childIndex].getOrientation()); Mat6x6 P_trans =(this->buildProjector(_T)); - P_trans.transpose(); + P_trans.transpose(); - Mat6x6 coAdjoint; - this->computeCoAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) - temp.transpose(); + Mat6x6 coAdjoint; + this->computeCoAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) + temp.transpose(); - type::Vec6 local_F = coAdjoint * P_trans * valueConst; // constraint direction in local frame of the beam. + Vec6 local_F = coAdjoint * P_trans * valueConst; // constraint direction in local frame of the beam. - type::Vec3 f = matB_trans * temp * local_F; // constraint direction in the strain space. + Vec3 f = matB_trans * temp * local_F; // constraint direction in the strain space. - o1.addCol(indexBeam-1, f); - //std::cout<< "colIt :"<< colIt.index() <<" ; indexBeam :"<< indexBeam << " childIndex :"<< childIndex << " local_F : "<< local_F << std::endl; - std::tuple<int,Vec6> test = std::make_tuple(indexBeam, local_F); + o1.addCol(indexBeam-1, f); + //std::cout<< "colIt :"<< colIt.index() <<" ; indexBeam :"<< indexBeam << " childIndex :"<< childIndex << " local_F : "<< local_F << std::endl; + std::tuple<int,Vec6> test = std::make_tuple(indexBeam, local_F); - NodesInvolved.push_back(test); - colIt++; + NodesInvolved.push_back(test); + colIt++; - } - if (debug){ - std::cout<<"==> NodesInvolved : "<<std::endl; - for (size_t i = 0; i < NodesInvolved.size(); i++) - std::cout << "index :" <<get<0>(NodesInvolved[i]) << " force :" - << get<1>(NodesInvolved[i]) << "\n "; - } + } + if (debug){ + std::cout<<"==> NodesInvolved : "<<std::endl; + for (size_t i = 0; i < NodesInvolved.size(); i++) + std::cout << "index :" <<get<0>(NodesInvolved[i]) << " force :" + << get<1>(NodesInvolved[i]) << "\n "; + } - //std::cout<<" NodesInvolved before sort "<<NodesInvolved<<std::endl; + //std::cout<<" NodesInvolved before sort "<<NodesInvolved<<std::endl; - // sort the Nodes Invoved by decreasing order - std::sort(begin(NodesInvolved), end(NodesInvolved), - [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { - return std::get<0>(t1) > std::get<0>(t2); // custom compare function - } ); + // sort the Nodes Invoved by decreasing order + std::sort(begin(NodesInvolved), end(NodesInvolved), + [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { + return std::get<0>(t1) > std::get<0>(t2); // custom compare function + } ); - // for (size_t i = 0; i < NodesInvolved.size(); i++) - // std::cout << "index :" <<get<0>(NodesInvolved[i]) << " force :" - // << get<1>(NodesInvolved[i]) << "\n "; + // for (size_t i = 0; i < NodesInvolved.size(); i++) + // std::cout << "index :" <<get<0>(NodesInvolved[i]) << " force :" + // << get<1>(NodesInvolved[i]) << "\n "; - NodesInvolvedCompressed.clear(); + NodesInvolvedCompressed.clear(); - for (unsigned n=0; n<NodesInvolved.size(); n++) - { - std::tuple<int,Vec6> test_i = NodesInvolved[n]; - int numNode_i= std::get<0>(test_i); - Vec6 cumulativeF =std::get<1>(test_i); + for (unsigned n=0; n<NodesInvolved.size(); n++) + { + std::tuple<int,Vec6> test_i = NodesInvolved[n]; + int numNode_i= std::get<0>(test_i); + Vec6 cumulativeF =std::get<1>(test_i); - if (n<NodesInvolved.size()-1) - { - std::tuple<int,Vec6> test_i1 = NodesInvolved[n+1]; - int numNode_i1= std::get<0>(test_i1); + if (n<NodesInvolved.size()-1) + { + std::tuple<int,Vec6> test_i1 = NodesInvolved[n+1]; + int numNode_i1= std::get<0>(test_i1); - while (numNode_i == numNode_i1) - { - cumulativeF += std::get<1>(test_i1); - if ((n!=NodesInvolved.size()-2)||(n==0)){ - n++; - break; - } - test_i1 = NodesInvolved[n+1]; - numNode_i1= std::get<0>(test_i1); - } + while (numNode_i == numNode_i1) + { + cumulativeF += std::get<1>(test_i1); + if ((n!=NodesInvolved.size()-2)||(n==0)){ + n++; + break; + } + test_i1 = NodesInvolved[n+1]; + numNode_i1= std::get<0>(test_i1); + } - } - NodesInvolvedCompressed.push_back(std::make_tuple(numNode_i, cumulativeF)); - } + } + NodesInvolvedCompressed.push_back(std::make_tuple(numNode_i, cumulativeF)); + } - if (debug){ - std::cout<<" NodesInvolved after sort and compress"<<std::endl; - for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) - std::cout << "index :" <<get<0>(NodesInvolvedCompressed[i]) << " force :" - << get<1>(NodesInvolvedCompressed[i]) << "\n "; - } + if (debug){ + std::cout<<" NodesInvolved after sort and compress"<<std::endl; + for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) + std::cout << "index :" <<get<0>(NodesInvolvedCompressed[i]) << " force :" + << get<1>(NodesInvolvedCompressed[i]) << "\n "; + } - for (unsigned n=0; n<NodesInvolvedCompressed.size(); n++) - { + for (unsigned n=0; n<NodesInvolvedCompressed.size(); n++) + { - std::tuple<int,Vec6> test = NodesInvolvedCompressed[n]; - int numNode= std::get<0>(test); - int i = numNode; - Vec6 CumulativeF = std::get<1>(test); + std::tuple<int,Vec6> test = NodesInvolvedCompressed[n]; + int numNode= std::get<0>(test); + int i = numNode; + Vec6 CumulativeF = std::get<1>(test); - while(i>0) - { - //cumulate on beam frame - Mat6x6 coAdjoint; - this->computeCoAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply - CumulativeF = coAdjoint * CumulativeF; - // transfer to strain space (local coordinates) - Mat6x6 temp = m_nodesTangExpVectors[i-1]; - temp.transpose(); - type::Vec3 temp_f = matB_trans * temp * CumulativeF; + while(i>0) + { + //cumulate on beam frame + Mat6x6 coAdjoint; + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + CumulativeF = coAdjoint * CumulativeF; + // transfer to strain space (local coordinates) + Mat6x6 temp = m_nodesTangExpVectors[i-1]; + temp.transpose(); + Vec3 temp_f = matB_trans * temp * CumulativeF; - if(i>1) o1.addCol(i-2, temp_f); + if(i>1) o1.addCol(i-2, temp_f); - i--; - } + i--; + } - Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); + Transform frame0 = Transform(frame[0].getCenter(),frame[0].getOrientation()); Mat6x6 M = this->buildProjector(frame0); - Vec6 base_force = M * CumulativeF; - o2.addCol(0, base_force); - } - } + Vec6 base_force = M * CumulativeF; + o2.addCol(0, base_force); + } + } - ////// END ARTICULATION SYSTEM MAPPING - dataMatOut1Const[0]->endEdit(); - dataMatOut2Const[0]->endEdit(); + ////// END ARTICULATION SYSTEM MAPPING + dataMatOut1Const[0]->endEdit(); + dataMatOut2Const[0]->endEdit(); } template <class TIn1, class TIn2, class TOut> -void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::draw(const core::visual::VisualParams* vparams) +void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::draw(const sofa::core::visual::VisualParams* vparams) { - if (!vparams->displayFlags().getShowMappings()) - return; + if (!vparams->displayFlags().getShowMappings()) + return; } } // namespace sofa::component::mapping diff --git a/src/Cosserat/mapping/RigidDistanceMapping.cpp b/src/Cosserat/mapping/RigidDistanceMapping.cpp index 3686ee20..d7baf569 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.cpp +++ b/src/Cosserat/mapping/RigidDistanceMapping.cpp @@ -20,18 +20,18 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #define SOFA_COSSERAT_CPP_RigidDistanceMapping -#include "RigidDistanceMapping.inl" +#include <Cosserat/mapping/RigidDistanceMapping.inl> #include <sofa/defaulttype/VecTypes.h> #include <sofa/defaulttype/RigidTypes.h> #include <sofa/core/ObjectFactory.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using namespace sofa::defaulttype; // Register in the Factory -int RigidDistanceMappingClass = core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") +int RigidDistanceMappingClass = sofa::core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") .add< RigidDistanceMapping< sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() ; diff --git a/src/Cosserat/mapping/RigidDistanceMapping.h b/src/Cosserat/mapping/RigidDistanceMapping.h index 6d637352..35952813 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.h +++ b/src/Cosserat/mapping/RigidDistanceMapping.h @@ -20,8 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <Cosserat/config.h> - +#include <Cosserat/initCosserat.h> #include <Cosserat/mapping/BaseCosserat.h> #include <sofa/core/BaseMapping.h> @@ -31,15 +30,19 @@ #include <sofa/defaulttype/RigidTypes.h> #include <sofa/helper/ColorMap.h> -namespace sofa::component::mapping +namespace Cosserat::mapping { using sofa::defaulttype::SolidTypes ; using sofa::core::objectmodel::BaseContext ; using sofa::type::Matrix3; using sofa::type::Matrix4; -using type::Vec3; -using type::Vec6; +using sofa::type::Vec3; +using sofa::type::Vec6; using std::get; +using sofa::type::vector; +using sofa::Data; +using sofa::type::Mat; +using sofa::type::Vec4f; /*! * \class RigidDistanceMapping @@ -48,14 +51,14 @@ using std::get; * This is a component: * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ -using component::mapping::BaseCosserat; +using Cosserat::mapping::BaseCosserat; // template <class TIn1, class TIn2, class TOut> -class RigidDistanceMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> +class RigidDistanceMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> { public: - SOFA_CLASS(SOFA_TEMPLATE3(RigidDistanceMapping, TIn1,TIn2, TOut), SOFA_TEMPLATE3(core::Multi2Mapping, TIn1, TIn2, TOut) ); - typedef core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; + SOFA_CLASS(SOFA_TEMPLATE3(RigidDistanceMapping, TIn1,TIn2, TOut), SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut) ); + typedef sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; /// Input Model Type typedef TIn1 In1; @@ -64,25 +67,25 @@ class RigidDistanceMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> /// Output Model Type typedef TOut Out; - typedef typename In1::Coord Coord1 ; - typedef typename In1::Deriv Deriv1 ; - typedef typename In1::VecCoord In1VecCoord; - typedef typename In1::VecDeriv In1VecDeriv; + typedef typename In1::Coord Coord1; + typedef typename In1::Deriv Deriv1; + typedef typename In1::VecCoord In1VecCoord; + typedef typename In1::VecDeriv In1VecDeriv; typedef typename In1::MatrixDeriv In1MatrixDeriv; - typedef Data<In1VecCoord> In1DataVecCoord; - typedef Data<In1VecDeriv> In1DataVecDeriv; - typedef Data<In1MatrixDeriv> In1DataMatrixDeriv; + typedef Data<In1VecCoord> In1DataVecCoord; + typedef Data<In1VecDeriv> In1DataVecDeriv; + typedef Data<In1MatrixDeriv> In1DataMatrixDeriv; - typedef typename In2::Coord::value_type Real ; - typedef typename In2::Coord Coord2 ; - typedef typename In2::Deriv Deriv2 ; - typedef typename In2::VecCoord In2VecCoord; - typedef typename In2::VecDeriv In2VecDeriv; - typedef typename In2::MatrixDeriv In2MatrixDeriv; - typedef Data<In2VecCoord> In2DataVecCoord; - typedef Data<In2VecDeriv> In2DataVecDeriv; - typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; - typedef type::Mat<4,4,Real> Mat4x4; + typedef typename In2::Coord::value_type Real; + typedef typename In2::Coord Coord2; + typedef typename In2::Deriv Deriv2; + typedef typename In2::VecCoord In2VecCoord; + typedef typename In2::VecDeriv In2VecDeriv; + typedef typename In2::MatrixDeriv In2MatrixDeriv; + typedef Data<In2VecCoord> In2DataVecCoord; + typedef Data<In2VecDeriv> In2DataVecDeriv; + typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; + typedef Mat<4,4,Real> Mat4x4; typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; @@ -97,16 +100,16 @@ class RigidDistanceMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> typedef typename SolidTypes< Real>::SpatialVector SpatialVector ; protected: - Data<type::vector<unsigned int> > d_index1 ; - Data<type::vector<unsigned int> > d_index2 ; + Data<vector<unsigned int> > d_index1 ; + Data<vector<unsigned int> > d_index2 ; Data<Real> d_max ; Data<Real> d_min ; Data<Real> d_radius ; - Data<type::Vec4f> d_color; - Data<type::vector<unsigned int> > d_index; + Data<Vec4f> d_color; + Data<vector<unsigned int> > d_index; Data<bool> d_debug ; - core::State<Out>* m_toModel; + sofa::core::State<Out>* m_toModel; protected: /// Constructor @@ -118,32 +121,38 @@ class RigidDistanceMapping : public core::Multi2Mapping<TIn1, TIn2, TOut> /**********************SOFA METHODS**************************/ void init() override; - void draw(const core::visual::VisualParams* /*vparams*/) override {} + void draw(const sofa::core::visual::VisualParams* /*vparams*/) override {} /**********************MAPPING METHODS**************************/ void apply( - const core::MechanicalParams* /* mparams */, const type::vector<OutDataVecCoord*>& dataVecOutPos, - const type::vector<const In1DataVecCoord*>& dataVecIn1Pos , - const type::vector<const In2DataVecCoord*>& dataVecIn2Pos) override; + const sofa::core::MechanicalParams* /* mparams */, + const vector<OutDataVecCoord*>& dataVecOutPos, + const vector<const In1DataVecCoord*>& dataVecIn1Pos , + const vector<const In2DataVecCoord*>& dataVecIn2Pos) override; void applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; + const sofa::core::MechanicalParams* /* mparams */, + const vector< OutDataVecDeriv*>& dataVecOutVel, + const vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const vector<const In2DataVecDeriv*>& dataVecIn2Vel) override; //ApplyJT Force void applyJT( - const core::MechanicalParams* /* mparams */, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2RootForce, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) override; + const sofa::core::MechanicalParams* /* mparams */, + const vector< In1DataVecDeriv*>& dataVecOut1Force, + const vector< In2DataVecDeriv*>& dataVecOut2RootForce, + const vector<const OutDataVecDeriv*>& dataVecInForce) override; - void applyDJT(const core::MechanicalParams* /*mparams*/, core::MultiVecDerivId /*inForce*/, core::ConstMultiVecDerivId /*outForce*/) override{} + void applyDJT(const sofa::core::MechanicalParams* /*mparams*/, + sofa::core::MultiVecDerivId /*inForce*/, + sofa::core::ConstMultiVecDerivId /*outForce*/) override{} /// This method must be reimplemented by all mappings if they need to support constraints. void applyJT( - const core::ConstraintParams* cparams , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const , - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) override; + const sofa::core::ConstraintParams* cparams , + const vector< In1DataMatrixDeriv*>& dataMatOut1Const , + const vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const vector<const OutDataMatrixDeriv*>& dataMatInConst) override; }; diff --git a/src/Cosserat/mapping/RigidDistanceMapping.inl b/src/Cosserat/mapping/RigidDistanceMapping.inl index d0e2f685..e5eddc40 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.inl +++ b/src/Cosserat/mapping/RigidDistanceMapping.inl @@ -20,7 +20,8 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include "RigidDistanceMapping.h" +#include <Cosserat/initCosserat.h> +#include <Cosserat/mapping/RigidDistanceMapping.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/visual/VisualParams.h> @@ -34,14 +35,13 @@ #include <string> -namespace sofa::component::mapping +namespace Cosserat::mapping { - - using sofa::core::objectmodel::BaseContext ; - using sofa::helper::AdvancedTimer; - using sofa::helper::WriteAccessor; - using sofa::defaulttype::SolidTypes ; - using sofa::type::RGBAColor; +using sofa::core::objectmodel::BaseContext ; +using sofa::helper::AdvancedTimer; +using sofa::helper::WriteAccessor; +using sofa::defaulttype::SolidTypes ; +using sofa::type::RGBAColor; template <class TIn1, class TIn2, class TOut> RigidDistanceMapping<TIn1, TIn2, TOut>::RigidDistanceMapping() @@ -50,13 +50,13 @@ RigidDistanceMapping<TIn1, TIn2, TOut>::RigidDistanceMapping() , d_max(initData(&d_max, (Real)1.0e-2, "max", "the maximum of the deformation.\n")) , d_min(initData(&d_min, (Real)0.0, "min", "the minimum of the deformation.\n")) , d_radius(initData(&d_radius, (Real)3.0, "radius", "the axis in which we want to show the deformation.\n")) - , d_color(initData(&d_color, type::Vec4f (1, 0., 1., 0.8) ,"color", "The default beam color")) + , d_color(initData(&d_color, Vec4f (1, 0., 1., 0.8) ,"color", "The default beam color")) , d_index(initData(&d_index, "index", "if this parameter is false, you draw the beam with color " - "according to the force apply to each beam")) + "according to the force apply to each beam")) , d_debug(initData(&d_debug, false, "debug", "show debug output.\n")) , m_toModel(NULL) { - d_debug.setValue(false); + d_debug.setValue(false); } @@ -71,8 +71,8 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>::init() return; } - const type::vector<unsigned int> &m1Indices = d_index1.getValue(); - const type::vector<unsigned int> &m2Indices = d_index2.getValue(); + const vector<unsigned int> &m1Indices = d_index1.getValue(); + const vector<unsigned int> &m2Indices = d_index2.getValue(); m_minInd = std::min(m1Indices.size(), m2Indices.size()); if (m_minInd == 0) { @@ -84,9 +84,10 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>::init() template <class TIn1, class TIn2, class TOut> void RigidDistanceMapping<TIn1, TIn2, TOut>::apply( - const core::MechanicalParams* /* mparams */, const type::vector<OutDataVecCoord*>& dataVecOutPos, - const type::vector<const In1DataVecCoord*>& dataVecIn1Pos , - const type::vector<const In2DataVecCoord*>& dataVecIn2Pos) + const sofa::core::MechanicalParams* /* mparams */, + const vector<OutDataVecCoord*>& dataVecOutPos, + const vector<const In1DataVecCoord*>& dataVecIn1Pos , + const vector<const In2DataVecCoord*>& dataVecIn2Pos) { if(dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) @@ -107,7 +108,7 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>::apply( int tm1 = m1Indices[pid]; int tm2 = m2Indices[pid]; Vec3 outCenter = in2[tm2].getCenter()-in1[tm1].getCenter(); - type::Quat outOri = in2[tm2].getOrientation()* in1[tm1].getOrientation().inverse(); + sofa::type::Quat outOri = in2[tm2].getOrientation()* in1[tm1].getOrientation().inverse(); outOri.normalize(); out[pid] = OutCoord(outCenter,outOri); // This difference is in the word space @@ -124,9 +125,10 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>::apply( template <class TIn1, class TIn2, class TOut> void RigidDistanceMapping<TIn1, TIn2, TOut>:: applyJ( - const core::MechanicalParams* /* mparams */, const type::vector< OutDataVecDeriv*>& dataVecOutVel, - const type::vector<const In1DataVecDeriv*>& dataVecIn1Vel, - const type::vector<const In2DataVecDeriv*>& dataVecIn2Vel) { + const sofa::core::MechanicalParams* /* mparams */, + const vector< OutDataVecDeriv*>& dataVecOutVel, + const vector<const In1DataVecDeriv*>& dataVecIn1Vel, + const vector<const In2DataVecDeriv*>& dataVecIn2Vel) { if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) return; @@ -152,9 +154,10 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>:: applyJ( template <class TIn1, class TIn2, class TOut> void RigidDistanceMapping<TIn1, TIn2, TOut>:: applyJT( - const core::MechanicalParams* /*mparams*/, const type::vector< In1DataVecDeriv*>& dataVecOut1Force, - const type::vector< In2DataVecDeriv*>& dataVecOut2Force, - const type::vector<const OutDataVecDeriv*>& dataVecInForce) { + const sofa::core::MechanicalParams* /*mparams*/, + const vector< In1DataVecDeriv*>& dataVecOut1Force, + const vector< In2DataVecDeriv*>& dataVecOut2Force, + const vector<const OutDataVecDeriv*>& dataVecInForce) { if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) return; @@ -182,9 +185,10 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>:: applyJT( //___________________________________________________________________________ template <class TIn1, class TIn2, class TOut> void RigidDistanceMapping<TIn1, TIn2, TOut>::applyJT( - const core::ConstraintParams*/*cparams*/ , const type::vector< In1DataMatrixDeriv*>& dataMatOut1Const, - const type::vector< In2DataMatrixDeriv*>& dataMatOut2Const , - const type::vector<const OutDataMatrixDeriv*>& dataMatInConst) + const sofa::core::ConstraintParams*/*cparams*/ , + const vector< In1DataMatrixDeriv*>& dataMatOut1Const, + const vector< In2DataMatrixDeriv*>& dataMatOut2Const , + const vector<const OutDataMatrixDeriv*>& dataMatInConst) { if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) return; @@ -199,7 +203,7 @@ void RigidDistanceMapping<TIn1, TIn2, TOut>::applyJT( for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) { typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); -// typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); + // typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number From 6f6dbe621d31e1dd328410facafdb94b39c2975b Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Mon, 10 Jun 2024 18:09:14 +0200 Subject: [PATCH 45/71] Updating Cosserat namespace --- CMakeLists.txt | 6 ++--- src/Cosserat/CMakeLists.txt | 9 ++++--- .../{mapping => engine}/ProjectionEngine.cpp | 0 .../{mapping => engine}/ProjectionEngine.h | 22 +---------------- .../{mapping => engine}/ProjectionEngine.inl | 24 ++----------------- .../forcefield/BeamHookeLawForceField.cpp | 2 +- .../forcefield/BeamHookeLawForceField.h | 2 +- .../forcefield/BeamHookeLawForceField.inl | 2 +- .../BeamHookeLawForceFieldRigid.cpp | 2 +- .../forcefield/BeamHookeLawForceFieldRigid.h | 2 +- .../BeamHookeLawForceFieldRigid.inl | 1 + .../forcefield/CosseratInternalActuation.cpp | 3 +-- .../forcefield/CosseratInternalActuation.h | 2 +- .../forcefield/CosseratInternalActuation.inl | 3 ++- .../MyUniformVelocityDampingForceField.cpp | 3 ++- .../MyUniformVelocityDampingForceField.h | 10 ++++---- .../MyUniformVelocityDampingForceField.inl | 3 ++- src/Cosserat/initCosserat.h.in | 7 ++++++ src/Cosserat/mapping/BaseCosserat.h | 4 +++- .../mapping/DiscreteCosseratMapping.h | 6 ++--- .../mapping/DiscreteCosseratMapping.inl | 1 + .../mapping/LegendrePolynomialsMapping.h | 3 ++- 22 files changed, 46 insertions(+), 71 deletions(-) rename src/Cosserat/{mapping => engine}/ProjectionEngine.cpp (100%) rename src/Cosserat/{mapping => engine}/ProjectionEngine.h (90%) rename src/Cosserat/{mapping => engine}/ProjectionEngine.inl (90%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7abab4e1..9dcb01c4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -27,8 +27,8 @@ set(HEADER_FILES ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.inl ${SRC_ROOT_DIR}/mapping/DiscreteDynamicCosseratMapping.h ${SRC_ROOT_DIR}/mapping/DiscreteDynamicCosseratMapping.inl - ${SRC_ROOT_DIR}/mapping/ProjectionEngine.h - ${SRC_ROOT_DIR}/mapping/ProjectionEngine.inl + ${SRC_ROOT_DIR}/engine/ProjectionEngine.h + ${SRC_ROOT_DIR}/engine/ProjectionEngine.inl ${SRC_ROOT_DIR}/mapping/DifferenceMultiMapping.h ${SRC_ROOT_DIR}/mapping/DifferenceMultiMapping.inl ${SRC_ROOT_DIR}/mapping/RigidDistanceMapping.h @@ -53,7 +53,7 @@ set(SOURCE_FILES ${SRC_ROOT_DIR}/mapping/BaseCosserat.cpp ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.cpp ${SRC_ROOT_DIR}/mapping/DiscreteDynamicCosseratMapping.cpp - ${SRC_ROOT_DIR}/mapping/ProjectionEngine.cpp + ${SRC_ROOT_DIR}/engine/ProjectionEngine.cpp ${SRC_ROOT_DIR}/mapping/DifferenceMultiMapping.cpp ${SRC_ROOT_DIR}/mapping/RigidDistanceMapping.cpp ${SRC_ROOT_DIR}/engine/PointsManager.cpp diff --git a/src/Cosserat/CMakeLists.txt b/src/Cosserat/CMakeLists.txt index bbba6fd6..425aadd5 100644 --- a/src/Cosserat/CMakeLists.txt +++ b/src/Cosserat/CMakeLists.txt @@ -9,14 +9,16 @@ set(HEADER_FILES mapping/DiscreteCosseratMapping.inl mapping/DiscretDynamicCosseratMapping.h mapping/DiscreteDynamicCosseratMapping.inl - mapping/ProjectionEngine.h - mapping/ProjectionEngine.inl mapping/DifferenceMultiMapping.h mapping/DifferenceMultiMapping.inl mapping/RigidDistanceMapping.h mapping/RigidDistanceMapping.inl mapping/LegendrePolynomialsMapping.h mapping/LegendrePolynomialsMapping.inl + + engine/ProjectionEngine.h + engine/ProjectionEngine.inl + forcefield/BeamHookeLawForceField.h @@ -41,12 +43,13 @@ set(SOURCE_FILES mapping/BaseCosserat.cpp mapping/DiscreteCosseratMapping.cpp - mapping/ProjectionEngine.cpp mapping/DiscreteDynamicCosseratMapping.cpp mapping/DifferenceMultiMapping.cpp mapping/RigidDistanceMapping.cpp mapping/LegendrePolynomialsMapping.cpp + engine/ProjectionEngine.cpp + forcefield/BeamHookeLawForceField.cpp forcefield/BeamHookeLawForceFieldRigid.cpp forcefield/CosseratInternalActuation.cpp diff --git a/src/Cosserat/mapping/ProjectionEngine.cpp b/src/Cosserat/engine/ProjectionEngine.cpp similarity index 100% rename from src/Cosserat/mapping/ProjectionEngine.cpp rename to src/Cosserat/engine/ProjectionEngine.cpp diff --git a/src/Cosserat/mapping/ProjectionEngine.h b/src/Cosserat/engine/ProjectionEngine.h similarity index 90% rename from src/Cosserat/mapping/ProjectionEngine.h rename to src/Cosserat/engine/ProjectionEngine.h index fc5c7d38..86e2ef31 100644 --- a/src/Cosserat/mapping/ProjectionEngine.h +++ b/src/Cosserat/engine/ProjectionEngine.h @@ -22,14 +22,12 @@ #ifndef COSSERAT_ProjectionEngine_H #define COSSERAT_ProjectionEngine_H -#include <Cosserat/config.h> - +#include <Cosserat/initCosserat.h> #include <sofa/core/behavior/PairInteractionConstraint.h> #include <sofa/core/behavior/MechanicalState.h> #include <sofa/core/DataEngine.h> #include <sofa/type/Vec.h> #include <sofa/simulation/AnimateBeginEvent.h> - #include <iostream> @@ -66,17 +64,7 @@ class ProjectionEngine : public core::DataEngine Data<VecCoord> d_dest; ///< vector to substract to input Data<VecCoord> d_output; - - //Data<Deriv> d_force; ///< interaction force - - // Real m_dist; // constraint violation - // Real m_thirdConstraint; // 0 if A<proj<B, -1 if proj<A, 1 if B<proj - // bool m_yetIntegrated; - // unsigned int m_cid; - - ProjectionEngine(); - virtual ~ProjectionEngine(){} public: @@ -84,14 +72,11 @@ class ProjectionEngine : public core::DataEngine void reinit() override; void handleEvent(core::objectmodel::Event *ev) override; - void computeProximity(); - void draw(const core::visual::VisualParams* vparams) override; void drawLinesBetweenPoints(const core::visual::VisualParams* vparams); - private: // storage of force Deriv m_dirAxe, m_dirProj, m_dirOrtho; @@ -119,11 +104,6 @@ class ProjectionEngine : public core::DataEngine }; -//#if !defined(SOFA_COSSERAT_CPP_ProjectionEngine) -//extern template class SOFA_CONSTRAINT_API ProjectionEngine< sofa::defaulttype::Vec3Types >; - -//#endif - } // namespace sofa::component::constraintset diff --git a/src/Cosserat/mapping/ProjectionEngine.inl b/src/Cosserat/engine/ProjectionEngine.inl similarity index 90% rename from src/Cosserat/mapping/ProjectionEngine.inl rename to src/Cosserat/engine/ProjectionEngine.inl index 77b4533a..a12c2dd7 100644 --- a/src/Cosserat/mapping/ProjectionEngine.inl +++ b/src/Cosserat/engine/ProjectionEngine.inl @@ -55,9 +55,7 @@ void ProjectionEngine<DataTypes>::init() template<class DataTypes> void ProjectionEngine<DataTypes>::reinit() -{ - -} +{} template<class DataTypes> @@ -218,24 +216,9 @@ void ProjectionEngine<DataTypes>::draw(const core::visual::VisualParams* vparams vparams->drawTool()->disableLighting(); sofa::type::RGBAColor color; - // Constraint& c = m_constraints[0]; - - // if(c.thirdConstraint<0) - // color = sofa::defaulttype::RGBAColor::yellow(); - // else if(c.thirdConstraint>0) - // color = sofa::defaulttype::RGBAColor::green(); - // else color = sofa::type::RGBAColor::magenta(); std::vector<sofa::type::Vec3> vertices; - // vertices.push_back(DataTypes::getCPos((this->mstate1->read(core::ConstVecCoordId::position())->getValue())[d_m1.getValue()])); - - // vparams->drawTool()->drawPoints(vertices, 10, color); - // vertices.clear(); - - // color = sofa::defaulttype::RGBAColor::blue(); - // vertices.push_back(DataTypes::getCPos((this->mstate2->read(core::ConstVecCoordId::position())->getValue())[d_m2a.getValue()])); - // vertices.push_back(DataTypes::getCPos((this->mstate2->read(core::ConstVecCoordId::position())->getValue())[d_m2b.getValue()])); vparams->drawTool()->drawLines(vertices, 1, color); for (size_t i =0 ; i < m_constraints.size(); i++) { @@ -244,9 +227,7 @@ void ProjectionEngine<DataTypes>::draw(const core::visual::VisualParams* vparams vertices.push_back(m_constraints[i].Q); vparams->drawTool()->drawLines(vertices, 1, color); } - //printf("ProjectionEngine<DataTypes>::draw(const core::visual::VisualParams* vparams) After \n"); - //drawLinesBetweenPoints(vparams); vparams->drawTool()->restoreLastState(); } @@ -269,5 +250,4 @@ void ProjectionEngine<DataTypes>::drawLinesBetweenPoints(const core::visual::Vis } // namespace sofa::component::constraintset - -#endif +#endif \ No newline at end of file diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp index f6104007..958c7f12 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.cpp +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.cpp @@ -28,7 +28,7 @@ * * ******************************************************************************/ #define SOFA_COSSERAT_CPP_BeamHookeLawForceField -#include "BeamHookeLawForceField.inl" +#include <Cosserat/forcefield/BeamHookeLawForceField.inl> #include <sofa/core/ObjectFactory.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.h b/src/Cosserat/forcefield/BeamHookeLawForceField.h index 98163b26..2c2f4e26 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.h @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/config.h> +#include <Cosserat/initCosserat.h> #include <sofa/type/Vec.h> #include <sofa/type/Mat.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.inl b/src/Cosserat/forcefield/BeamHookeLawForceField.inl index 19370dc2..bcf8e69d 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.inl @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include "BeamHookeLawForceField.h" +#include <Cosserat/forcefield/BeamHookeLawForceField.h> #include <sofa/linearalgebra/FullVector.h> #include <sofa/core/behavior/MechanicalState.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp index 8671698f..36cf1835 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.cpp @@ -28,7 +28,7 @@ * * ******************************************************************************/ #define SOFA_COSSERAT_BeamHookeLawForceFieldRigid_CPP -#include "BeamHookeLawForceFieldRigid.inl" +#include <Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl> #include <sofa/core/ObjectFactory.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h index 009abc4a..35b7b396 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/config.h> +#include <Cosserat/initCosserat.h> #include <sofa/type/Vec.h> #include <sofa/type/Mat.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl index 8ca552a0..443d4a91 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.inl @@ -29,6 +29,7 @@ ******************************************************************************/ #pragma once #include "BeamHookeLawForceFieldRigid.h" +#include <Cosserat/forcefield/BeamHookeLawForceFieldRigid.h> #include <sofa/linearalgebra/FullVector.h> #include <sofa/core/behavior/MechanicalState.h> diff --git a/src/Cosserat/forcefield/CosseratInternalActuation.cpp b/src/Cosserat/forcefield/CosseratInternalActuation.cpp index 47031ee8..ed1dc954 100644 --- a/src/Cosserat/forcefield/CosseratInternalActuation.cpp +++ b/src/Cosserat/forcefield/CosseratInternalActuation.cpp @@ -28,8 +28,7 @@ * * ******************************************************************************/ #define SOFA_COSSERAT_CPP_CosseratInternalActuation -#include "CosseratInternalActuation.inl" - +#include <Cosserat/forcefield/CosseratInternalActuation.inl> #include <sofa/core/ObjectFactory.h> namespace sofa::component::forcefield diff --git a/src/Cosserat/forcefield/CosseratInternalActuation.h b/src/Cosserat/forcefield/CosseratInternalActuation.h index 0e8e21bf..bc64d3ce 100644 --- a/src/Cosserat/forcefield/CosseratInternalActuation.h +++ b/src/Cosserat/forcefield/CosseratInternalActuation.h @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/config.h> +#include <Cosserat/initCosserat.h> #include <sofa/type/Vec.h> #include <sofa/type/Mat.h> diff --git a/src/Cosserat/forcefield/CosseratInternalActuation.inl b/src/Cosserat/forcefield/CosseratInternalActuation.inl index 228781cb..a3fe434f 100644 --- a/src/Cosserat/forcefield/CosseratInternalActuation.inl +++ b/src/Cosserat/forcefield/CosseratInternalActuation.inl @@ -28,7 +28,8 @@ * * ******************************************************************************/ #pragma once -#include "CosseratInternalActuation.h" +#include <Cosserat/initCosserat.h> +#include <Cosserat/forcefield/CosseratInternalActuation.h> #include <sofa/linearalgebra/FullVector.h> #include <sofa/core/behavior/ForceField.inl> diff --git a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp index 57b2ff6c..9ffb8748 100644 --- a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp +++ b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp @@ -21,7 +21,8 @@ ******************************************************************************/ #define SOFA_COMPONENT_FORCEFIELD_UNIFORMVELOCITYDAMPINGFORCEFIELD_CPP -#include "MyUniformVelocityDampingForceField.inl" +#include <Cosserat/initCosserat.h> +#include <Cosserat/forcefield/MyUniformVelocityDampingForceField.inl> #include <sofa/core/ObjectFactory.h> #include <sofa/defaulttype/VecTypes.h> #include <sofa/defaulttype/RigidTypes.h> diff --git a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h index 664a69ec..48be188a 100644 --- a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h +++ b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <SofaBoundaryCondition/config.h> +#include <Cosserat/initCosserat.h> #include <sofa/core/behavior/ForceField.h> @@ -30,7 +30,7 @@ using sofa::type::Vec ; using sofa::type::Mat ; using sofa::type::vector; using sofa::core::MechanicalParams; -using sofa::defaulttype::BaseMatrix; +using sofa::linearalgebra::BaseMatrix; using sofa::core::behavior::ForceField ; using sofa::core::behavior::MultiMatrixAccessor ; @@ -68,19 +68,17 @@ class MyUniformVelocityDampingForceField : public core::behavior::ForceField<Dat void addDForce(const core::MechanicalParams* mparams, DataVecDeriv& d_df , const DataVecDeriv& d_dx) override; - void addKToMatrix(sofa::defaulttype::BaseMatrix *, SReal, unsigned int &) override {} + void addKToMatrix(sofa::linearalgebra::BaseMatrix *, SReal, unsigned int &) override {} - void addBToMatrix(sofa::defaulttype::BaseMatrix * mat, SReal bFact, unsigned int& offset) override; + void addBToMatrix(sofa::linearalgebra::BaseMatrix * mat, SReal bFact, unsigned int& offset) override; void addKToMatrix(const core::MechanicalParams* mparams, const sofa::core::behavior::MultiMatrixAccessor* matrix ) override; SReal getPotentialEnergy(const core::MechanicalParams* params, const DataVecCoord& x) const override; - }; - #if !defined(SOFA_COMPONENT_FORCEFIELD_UNIFORMVELOCITYDAMPINGFORCEFIELD_CPP) extern template class SOFA_SOFABOUNDARYCONDITION_API MyUniformVelocityDampingForceField<defaulttype::Vec3Types>; extern template class SOFA_SOFABOUNDARYCONDITION_API MyUniformVelocityDampingForceField<defaulttype::Vec2Types>; diff --git a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl index 9df952a6..c5b4b895 100644 --- a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl +++ b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl @@ -20,7 +20,8 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once - +#include <Cosserat/initCosserat.h> +#include <Cosserat/forcefield/MyUniformVelocityDampingForceField.h> #include "MyUniformVelocityDampingForceField.h" #include <sofa/defaulttype/BaseMatrix.h> #include <sofa/core/MechanicalParams.h> diff --git a/src/Cosserat/initCosserat.h.in b/src/Cosserat/initCosserat.h.in index d0938489..1f4dd378 100644 --- a/src/Cosserat/initCosserat.h.in +++ b/src/Cosserat/initCosserat.h.in @@ -46,6 +46,13 @@ */ namespace Cosserat { + +namespace type { +//using Vec3 = sofa::defaulttype::Vec3; +//using cosserat::type::SE3; +} + + SOFA_COSSERAT_API void init(); constexpr const char *MODULE_NAME = "@PROJECT_NAME@"; constexpr const char *MODULE_VERSION = "@PROJECT_VERSION@"; diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index a2c50e68..09c77c39 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -60,6 +60,8 @@ using sofa::type::vector; using sofa::type::Vec3; using sofa::type::Vec6; using sofa::type::Mat; + +typedef typename Eigen::Matrix4d _SE3; } // namespace /*! @@ -132,7 +134,7 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { typedef typename sofa::type::Matrix4 se3; typedef typename sofa::type::Matrix4 SE3; - typedef typename Eigen::Matrix4d _SE3; + typedef typename Eigen::Matrix4d _se3; typedef typename sofa::type::Mat<6, 6, SReal> Tangent; typedef typename Eigen::Matrix3d RotMat; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 84b3749c..ae0ff831 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -58,9 +58,9 @@ class DiscreteCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, public Cosserat::mapping::BaseCosserat<TIn1, TIn2, TOut> { public: - SOFA_CLASS(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1, TIn2, TOut), - SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut)); - typedef sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; + SOFA_CLASS2(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1, TIn2, TOut), + SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut), + SOFA_TEMPLATE3(Cosserat::mapping::BaseCosserat, TIn1, TIn2, TOut)); /// Input Model Type typedef TIn1 In1; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index df957bdf..6046a248 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -85,6 +85,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { reinit(); // I call Init here since we build the mechanics only in the Inherit1::init(); + Inherit2::init(); m_colorMap.setColorScheme("Blue to Red"); m_colorMap.reinit(); diff --git a/src/Cosserat/mapping/LegendrePolynomialsMapping.h b/src/Cosserat/mapping/LegendrePolynomialsMapping.h index 4726bfbf..5a1571be 100644 --- a/src/Cosserat/mapping/LegendrePolynomialsMapping.h +++ b/src/Cosserat/mapping/LegendrePolynomialsMapping.h @@ -2,7 +2,8 @@ // Created by younes on 17/11/2021. // #pragma once -#include <Cosserat/config.h> +#include <Cosserat/initCosserat.h> +#include <Cosserat/mapping/BaseCosserat.h> #include <sofa/core/BaseMapping.h> #include <sofa/core/config.h> From bef44782ec78bbfa6f70cc2a4694a9384f6b17da Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Tue, 11 Jun 2024 10:59:39 +0200 Subject: [PATCH 46/71] Rename BaseCosserat into BaseCosseratMapping --- src/Cosserat/mapping/BaseCosserat.cpp | 26 +++++---- src/Cosserat/mapping/BaseCosserat.h | 20 +++---- src/Cosserat/mapping/BaseCosserat.inl | 55 ++++++++++--------- src/Cosserat/mapping/DifferenceMultiMapping.h | 2 +- .../mapping/DifferenceMultiMapping.inl | 2 +- .../mapping/DiscreteCosseratMapping.h | 34 ++++++------ .../mapping/DiscreteDynamicCosseratMapping.h | 30 +++++----- src/Cosserat/mapping/RigidDistanceMapping.h | 2 +- 8 files changed, 89 insertions(+), 82 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosserat.cpp index 6e08e404..852484cc 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosserat.cpp @@ -19,20 +19,21 @@ * * * Contact information: contact@sofa-framework.org * ******************************************************************************/ -#define SOFA_COSSERAT_CPP_BaseCosserat +#define SOFA_COSSERAT_CPP_BaseCosseratMapping #include <Cosserat/mapping/BaseCosserat.inl> #include <sofa/core/ObjectFactory.h> #include <sofa/defaulttype/RigidTypes.h> #include <sofa/defaulttype/VecTypes.h> -namespace Cosserat::mapping { +namespace Cosserat::mapping +{ using namespace sofa::defaulttype; template <> -BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::se3 -BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat( - const Coord1 &strain_i) { +BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::se3 +BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const Coord1 &strain_i) +{ se3 Xi; Xi[0][1] = -strain_i(2); @@ -58,7 +59,7 @@ BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat( } template <> -void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3( +void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &Trans) { Matrix4 I4; I4.identity(); @@ -95,7 +96,7 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3( } template <> -void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( +void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( double &curv_abs_n, const Coord1 &strain_i, Mat6x6 &TgX) { SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) @@ -145,22 +146,23 @@ void BaseCosserat<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( } } + // Register in the Factory -int BaseCosseratClass = +int BaseCosseratMappingClass = sofa::core::RegisterObject( "Set the positions and velocities of points attached to a rigid parent") - .add<BaseCosserat<sofa::defaulttype::Vec3Types, + .add<BaseCosseratMapping<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>>() - .add<BaseCosserat<sofa::defaulttype::Vec6Types, + .add<BaseCosseratMapping<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>>(); template class SOFA_COSSERAT_API - BaseCosserat<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, + BaseCosseratMapping<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>; template class SOFA_COSSERAT_API - BaseCosserat<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, + BaseCosseratMapping<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>; } // namespace cosserat::mapping diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosserat.h index 09c77c39..02ce1448 100644 --- a/src/Cosserat/mapping/BaseCosserat.h +++ b/src/Cosserat/mapping/BaseCosserat.h @@ -75,9 +75,9 @@ typedef typename Eigen::Matrix4d _SE3; // TODO(dmarchal: 2024/06/07) This component looks like a mapping but inherit // from BaseObject * can you clarify why is is not inhering from BaseMapping template <class TIn1, class TIn2, class TOut> -class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { +class BaseCosseratMapping : public virtual sofa::core::objectmodel::BaseObject { public: - SOFA_CLASS(SOFA_TEMPLATE3(BaseCosserat, TIn1, TIn2, TOut), BaseObject); + SOFA_CLASS(SOFA_TEMPLATE3(BaseCosseratMapping, TIn1, TIn2, TOut), BaseObject); typedef BaseObject Inherit; /// Input Model Type @@ -118,14 +118,14 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { typedef sofa::Data<OutVecDeriv> OutDataVecDeriv; typedef sofa::Data<OutMatrixDeriv> OutDataMatrixDeriv; - typedef sofa::MultiLink<BaseCosserat<In1, In2, Out>, sofa::core::State<In1>, + typedef sofa::MultiLink<BaseCosseratMapping<In1, In2, Out>, sofa::core::State<In1>, sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> LinkFromModels1; - typedef sofa::MultiLink<BaseCosserat<In1, In2, Out>, sofa::core::State<In2>, + typedef sofa::MultiLink<BaseCosseratMapping<In1, In2, Out>, sofa::core::State<In2>, sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> LinkFromModels2; [[maybe_unused]] typedef sofa::MultiLink< - BaseCosserat<In1, In2, Out>, sofa::core::State<Out>, + BaseCosseratMapping<In1, In2, Out>, sofa::core::State<Out>, sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> LinkToModels; @@ -241,9 +241,9 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { protected: /// Constructor - BaseCosserat(); + BaseCosseratMapping(); /// Destructor - ~BaseCosserat() override = default; + ~BaseCosseratMapping() override = default; void computeExponentialSE3(const double &x, const Coord1 &k, Transform &Trans); @@ -266,12 +266,12 @@ class BaseCosserat : public virtual sofa::core::objectmodel::BaseObject { Matrix4 computeLogarithm(const double &x, const Mat4x4 &gX); }; -#if !defined(SOFA_COSSERAT_CPP_BaseCosserat) +#if !defined(SOFA_COSSERAT_CPP_BaseCosseratMapping) extern template class SOFA_COSSERAT_API - BaseCosserat<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, +BaseCosseratMapping<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>; extern template class SOFA_COSSERAT_API - BaseCosserat<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, +BaseCosseratMapping<sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>; #endif diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosserat.inl index 507aedb1..e2729486 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosserat.inl @@ -39,15 +39,17 @@ namespace Cosserat::mapping { -namespace { +namespace +{ +using namespace sofa::defaulttype; using sofa::core::objectmodel::BaseContext; using sofa::helper::AdvancedTimer; using sofa::helper::WriteAccessor; using sofa::type::vector; -} // namespace +} template <class TIn1, class TIn2, class TOut> -BaseCosserat<TIn1, TIn2, TOut>::BaseCosserat() +BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() : d_curv_abs_section(initData(&d_curv_abs_section, "curv_abs_input", " need to be com....")), d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", @@ -59,7 +61,7 @@ BaseCosserat<TIn1, TIn2, TOut>::BaseCosserat() // _________________________________________________________________________________________ template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::init() { +void BaseCosseratMapping<TIn1, TIn2, TOut>::init() { Inherit1::init(); // Fill the initial vector @@ -69,7 +71,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::init() { } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3( +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { Matrix4 I4; I4.identity(); @@ -107,7 +109,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeExponentialSE3( // Fill exponential vectors template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::updateExponentialSE3( +void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( const In1VecCoord &inDeform) { // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = // d_curv_abs_section; @@ -175,7 +177,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::updateExponentialSE3( // m_nodesLogarithmSE3Vectors.push_back(log_gX); template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, Tangent &adjoint) { Matrix3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); @@ -185,7 +187,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, Mat6x6 &co_adjoint) { Matrix3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); @@ -195,7 +197,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, Mat6x6 &adjoint) { Matrix3 tildeMat = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); adjoint.setsub(0, 0, tildeMat); @@ -204,7 +206,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, } template <class TIn1, class TIn2, class TOut> -Matrix4 BaseCosserat<TIn1, TIn2, TOut>::computeLogarithm(const double &x, +Matrix4 BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, const Mat4x4 &gX) { // Compute theta before everything const double theta = computeTheta(x, gX); @@ -238,7 +240,7 @@ Matrix4 BaseCosserat<TIn1, TIn2, TOut>::computeLogarithm(const double &x, } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::updateTangExpSE3( +void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( const In1VecCoord &inDeform) { // Curv abscissa of nodes and frames @@ -289,7 +291,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::updateTangExpSE3( } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, const Coord1 &strain_i, Mat6x6 &TgX) { @@ -340,7 +342,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, template <class TIn1, class TIn2, class TOut> [[maybe_unused]] Vec6 -BaseCosserat<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, +BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, const In1VecDeriv &k_dot, const double abs_input) { @@ -382,7 +384,7 @@ BaseCosserat<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, //___________________________________________________________________________ template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::initialize() { +void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { // For each frame in the global frame, find the segment of the beam to which // it is attached. Here we only use the information from the curvilinear // abscissa of each frame. @@ -442,10 +444,10 @@ void BaseCosserat<TIn1, TIn2, TOut>::initialize() { } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::draw(const sofa::core::visual::VisualParams *) {} +void BaseCosseratMapping<TIn1, TIn2, TOut>::draw(const sofa::core::visual::VisualParams *) {} template <class TIn1, class TIn2, class TOut> -double BaseCosserat<TIn1, TIn2, TOut>::computeTheta(const double &x, +double BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta(const double &x, const Mat4x4 &gX) { double Tr_gx = 0.0; for (int i = 0; i < 4; i++) { @@ -462,7 +464,7 @@ double BaseCosserat<TIn1, TIn2, TOut>::computeTheta(const double &x, } template <class TIn1, class TIn2, class TOut> -void BaseCosserat<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R) { +void BaseCosseratMapping<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R) { // TODO(dmarchal: 2024/06/07): Remove the use of printf in addition to // reconsider the implementation of common utility functions in instance // method. @@ -475,7 +477,7 @@ void BaseCosserat<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R) { template <class TIn1, class TIn2, class TOut> Matrix3 -BaseCosserat<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { +BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { sofa::type::Quat q = frame.getOrientation(); @@ -492,7 +494,7 @@ BaseCosserat<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildProjector(const Transform &T) +auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildProjector(const Transform &T) -> Tangent { Mat6x6 P; @@ -511,7 +513,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::buildProjector(const Transform &T) } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) -> se3 { +auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) -> se3 { se3 Xi_hat; Xi_hat[0][1] = -strain_i(2); @@ -528,7 +530,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) -> se3 { } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) +auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) -> Matrix3 { sofa::type::Matrix3 tild; tild[0][1] = -u[2]; @@ -542,7 +544,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, +auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, const Matrix3 &B, Mat6x6 &Adjoint) -> void { Adjoint.clear(); @@ -556,7 +558,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, +auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, const Matrix3 &B, Mat6x6 &coAdjoint) -> void { coAdjoint.clear(); @@ -573,7 +575,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( +auto BaseCosseratMapping<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( const Transform &T) -> Matrix4 { Matrix4 M; M.identity(); @@ -590,7 +592,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( } template <class TIn1, class TIn2, class TOut> -auto BaseCosserat<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3 &g_x) -> Vec6 { +auto BaseCosseratMapping<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3 &g_x) -> Vec6 { _SE3 Xi_hat; double x = 1.0; @@ -625,4 +627,7 @@ auto BaseCosserat<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3 &g_x) -> Vec6 { return xci; } + + + } // namespace cosserat::mapping diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.h b/src/Cosserat/mapping/DifferenceMultiMapping.h index bf94fe50..7ec2b653 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.h +++ b/src/Cosserat/mapping/DifferenceMultiMapping.h @@ -41,7 +41,7 @@ using sofa::type::Vec6; using sofa::type::Quat; using std::get; using sofa::type::vector; -using Cosserat::mapping::BaseCosserat; +using Cosserat::mapping::BaseCosseratMapping; /*! * \class DifferenceMultiMapping diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.inl b/src/Cosserat/mapping/DifferenceMultiMapping.inl index d86f5b79..fec6b9d5 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.inl +++ b/src/Cosserat/mapping/DifferenceMultiMapping.inl @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <cosserat/mapping/DifferenceMultiMapping.h> +#include <Cosserat/mapping/DifferenceMultiMapping.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/visual/VisualParams.h> diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index ae0ff831..d3eb3edb 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -56,11 +56,11 @@ using sofa::Data; template <class TIn1, class TIn2, class TOut> class DiscreteCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, - public Cosserat::mapping::BaseCosserat<TIn1, TIn2, TOut> { + public Cosserat::mapping::BaseCosseratMapping<TIn1, TIn2, TOut> { public: SOFA_CLASS2(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1, TIn2, TOut), SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut), - SOFA_TEMPLATE3(Cosserat::mapping::BaseCosserat, TIn1, TIn2, TOut)); + SOFA_TEMPLATE3(Cosserat::mapping::BaseCosseratMapping, TIn1, TIn2, TOut)); /// Input Model Type typedef TIn1 In1; @@ -136,21 +136,21 @@ class DiscreteCosseratMapping /// otherwise any access to the base::attribute would require /// the "this->" approach. /// - using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectors; - using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_section; - using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_frames; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesTangExpVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesVelocityVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_framesTangExpVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_totalBeamForceVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors; - using BaseCosserat<TIn1, TIn2, TOut>::d_debug; - using BaseCosserat<TIn1, TIn2, TOut>::m_vecTransform; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodeAdjointVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_index_input; - using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectorsDraw; - using BaseCosserat<TIn1, TIn2, TOut>::computeTheta; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_section; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_frames; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesTangExpVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesVelocityVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesTangExpVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_totalBeamForceVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_debug; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectorsDraw; + using BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta; protected: /// Constructor diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index 25eb3a04..349748bc 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -39,7 +39,7 @@ using sofa::type::Vec6; using std::get; using sofa::Data; using sofa::type::Mat; -using Cosserat::mapping::BaseCosserat; +using Cosserat::mapping::BaseCosseratMapping; /*! * \class DiscretDynamicCosseratMapping @@ -52,7 +52,7 @@ using Cosserat::mapping::BaseCosserat; template <class TIn1, class TIn2, class TOut> class DiscreteDynamicCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, - BaseCosserat<TIn1, TIn2, TOut> + BaseCosseratMapping<TIn1, TIn2, TOut> { public: SOFA_CLASS(SOFA_TEMPLATE3(DiscreteDynamicCosseratMapping, TIn1,TIn2, TOut), @@ -131,19 +131,19 @@ class DiscreteDynamicCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TI /// otherwise any access to the base::attribute would require /// the "this->" approach. /// - using BaseCosserat<TIn1, TIn2, TOut>::m_indicesVectors ; - using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_section ; - using BaseCosserat<TIn1, TIn2, TOut>::d_curv_abs_frames ; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesTangExpVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesVelocityVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_framesTangExpVectors ; - using BaseCosserat<TIn1, TIn2, TOut>::m_totalBeamForceVectors ; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors ; - using BaseCosserat<TIn1, TIn2, TOut>::d_debug; - using BaseCosserat<TIn1, TIn2, TOut>::m_vecTransform ; - using BaseCosserat<TIn1, TIn2, TOut>::m_nodeAdjointVectors; - using BaseCosserat<TIn1, TIn2, TOut>::m_index_input; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectors ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_section ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_frames ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesTangExpVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesVelocityVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesTangExpVectors ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_totalBeamForceVectors ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_debug; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform ; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; public: diff --git a/src/Cosserat/mapping/RigidDistanceMapping.h b/src/Cosserat/mapping/RigidDistanceMapping.h index 35952813..c75c2ae0 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.h +++ b/src/Cosserat/mapping/RigidDistanceMapping.h @@ -51,7 +51,7 @@ using sofa::type::Vec4f; * This is a component: * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ -using Cosserat::mapping::BaseCosserat; +using Cosserat::mapping::BaseCosseratMapping; // template <class TIn1, class TIn2, class TOut> class RigidDistanceMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> From 6b170ea3c0ae8fb55d5e37f990e6517d56c8ca08 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Tue, 11 Jun 2024 11:22:38 +0200 Subject: [PATCH 47/71] Rename BaseCosserat files into BaseCosseratMapping --- CMakeLists.txt | 6 +++--- .../mapping/{BaseCosserat.cpp => BaseCosseratMapping.cpp} | 2 +- .../mapping/{BaseCosserat.h => BaseCosseratMapping.h} | 0 .../mapping/{BaseCosserat.inl => BaseCosseratMapping.inl} | 2 +- src/Cosserat/mapping/DifferenceMultiMapping.h | 2 +- src/Cosserat/mapping/DiscreteCosseratMapping.h | 2 +- src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h | 2 +- src/Cosserat/mapping/LegendrePolynomialsMapping.h | 2 +- src/Cosserat/mapping/RigidDistanceMapping.h | 2 +- 9 files changed, 10 insertions(+), 10 deletions(-) rename src/Cosserat/mapping/{BaseCosserat.cpp => BaseCosseratMapping.cpp} (99%) rename src/Cosserat/mapping/{BaseCosserat.h => BaseCosseratMapping.h} (100%) rename src/Cosserat/mapping/{BaseCosserat.inl => BaseCosseratMapping.inl} (99%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9dcb01c4..906ebfe1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,8 +21,8 @@ set(SRC_ROOT_DIR src/${PROJECT_NAME}) set(HEADER_FILES ${SRC_ROOT_DIR}/initCosserat.h.in - ${SRC_ROOT_DIR}/mapping/BaseCosserat.h - ${SRC_ROOT_DIR}/mapping/BaseCosserat.inl + ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.h + ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.inl ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.h ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.inl ${SRC_ROOT_DIR}/mapping/DiscreteDynamicCosseratMapping.h @@ -50,7 +50,7 @@ set(HEADER_FILES ) set(SOURCE_FILES ${SRC_ROOT_DIR}/initCosserat.cpp - ${SRC_ROOT_DIR}/mapping/BaseCosserat.cpp + ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.cpp ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.cpp ${SRC_ROOT_DIR}/mapping/DiscreteDynamicCosseratMapping.cpp ${SRC_ROOT_DIR}/engine/ProjectionEngine.cpp diff --git a/src/Cosserat/mapping/BaseCosserat.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp similarity index 99% rename from src/Cosserat/mapping/BaseCosserat.cpp rename to src/Cosserat/mapping/BaseCosseratMapping.cpp index 852484cc..5c6c87b8 100644 --- a/src/Cosserat/mapping/BaseCosserat.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #define SOFA_COSSERAT_CPP_BaseCosseratMapping -#include <Cosserat/mapping/BaseCosserat.inl> +#include <Cosserat/mapping/BaseCosseratMapping.inl> #include <sofa/core/ObjectFactory.h> #include <sofa/defaulttype/RigidTypes.h> diff --git a/src/Cosserat/mapping/BaseCosserat.h b/src/Cosserat/mapping/BaseCosseratMapping.h similarity index 100% rename from src/Cosserat/mapping/BaseCosserat.h rename to src/Cosserat/mapping/BaseCosseratMapping.h diff --git a/src/Cosserat/mapping/BaseCosserat.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl similarity index 99% rename from src/Cosserat/mapping/BaseCosserat.inl rename to src/Cosserat/mapping/BaseCosseratMapping.inl index e2729486..fdf25e88 100644 --- a/src/Cosserat/mapping/BaseCosserat.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -22,7 +22,7 @@ #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/mapping/BaseCosserat.h> +#include <Cosserat/mapping/BaseCosseratMapping.h> #include <sofa/core/Multi2Mapping.inl> #include <sofa/core/behavior/MechanicalState.h> diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.h b/src/Cosserat/mapping/DifferenceMultiMapping.h index 7ec2b653..f4567d0c 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.h +++ b/src/Cosserat/mapping/DifferenceMultiMapping.h @@ -21,7 +21,7 @@ ******************************************************************************/ #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/mapping/BaseCosserat.h> +#include <Cosserat/mapping/BaseCosseratMapping.h> #include <sofa/core/BaseMapping.h> #include <sofa/core/config.h> diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index d3eb3edb..cb057461 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -23,7 +23,7 @@ #include <Cosserat/initCosserat.h> #include <Cosserat/forcefield/BeamHookeLawForceField.h> -#include <Cosserat/mapping/BaseCosserat.h> +#include <Cosserat/mapping/BaseCosseratMapping.h> #include <sofa/core/BaseMapping.h> #include <sofa/core/Multi2Mapping.h> diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index 349748bc..bf30dc10 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -21,7 +21,7 @@ ******************************************************************************/ #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/mapping/BaseCosserat.h> +#include <Cosserat/mapping/BaseCosseratMapping.h> #include <sofa/core/BaseMapping.h> #include <sofa/core/Multi2Mapping.h> diff --git a/src/Cosserat/mapping/LegendrePolynomialsMapping.h b/src/Cosserat/mapping/LegendrePolynomialsMapping.h index 5a1571be..4a726839 100644 --- a/src/Cosserat/mapping/LegendrePolynomialsMapping.h +++ b/src/Cosserat/mapping/LegendrePolynomialsMapping.h @@ -3,7 +3,7 @@ // #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/mapping/BaseCosserat.h> +#include <Cosserat/mapping/BaseCosseratMapping.h> #include <sofa/core/BaseMapping.h> #include <sofa/core/config.h> diff --git a/src/Cosserat/mapping/RigidDistanceMapping.h b/src/Cosserat/mapping/RigidDistanceMapping.h index c75c2ae0..8258e666 100644 --- a/src/Cosserat/mapping/RigidDistanceMapping.h +++ b/src/Cosserat/mapping/RigidDistanceMapping.h @@ -21,7 +21,7 @@ ******************************************************************************/ #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/mapping/BaseCosserat.h> +#include <Cosserat/mapping/BaseCosseratMapping.h> #include <sofa/core/BaseMapping.h> #include <sofa/core/config.h> From 15f60377e81535291426f8609854e53943d9c6a9 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Tue, 11 Jun 2024 11:39:47 +0200 Subject: [PATCH 48/71] Refactor the code so that BaseCosseratMapping is the base class of CosseratMapping --- src/Cosserat/mapping/BaseCosseratMapping.cpp | 12 ------------ src/Cosserat/mapping/BaseCosseratMapping.h | 3 ++- src/Cosserat/mapping/DiscreteCosseratMapping.h | 9 +++------ src/Cosserat/mapping/DiscreteCosseratMapping.inl | 1 - .../mapping/DiscreteDynamicCosseratMapping.h | 5 ++--- 5 files changed, 7 insertions(+), 23 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp index 5c6c87b8..0dfbb4bc 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -146,18 +146,6 @@ void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( } } - -// Register in the Factory -int BaseCosseratMappingClass = - sofa::core::RegisterObject( - "Set the positions and velocities of points attached to a rigid parent") - .add<BaseCosseratMapping<sofa::defaulttype::Vec3Types, - sofa::defaulttype::Rigid3Types, - sofa::defaulttype::Rigid3Types>>() - .add<BaseCosseratMapping<sofa::defaulttype::Vec6Types, - sofa::defaulttype::Rigid3Types, - sofa::defaulttype::Rigid3Types>>(); - template class SOFA_COSSERAT_API BaseCosseratMapping<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>; diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 02ce1448..0a7ba357 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -75,7 +75,8 @@ typedef typename Eigen::Matrix4d _SE3; // TODO(dmarchal: 2024/06/07) This component looks like a mapping but inherit // from BaseObject * can you clarify why is is not inhering from BaseMapping template <class TIn1, class TIn2, class TOut> -class BaseCosseratMapping : public virtual sofa::core::objectmodel::BaseObject { +class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> +{ public: SOFA_CLASS(SOFA_TEMPLATE3(BaseCosseratMapping, TIn1, TIn2, TOut), BaseObject); typedef BaseObject Inherit; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index cb057461..c5547b8b 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -54,13 +54,10 @@ using sofa::Data; // using Cosserat::mapping::BaseCosserat; template <class TIn1, class TIn2, class TOut> -class DiscreteCosseratMapping - : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, - public Cosserat::mapping::BaseCosseratMapping<TIn1, TIn2, TOut> { +class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { public: - SOFA_CLASS2(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1, TIn2, TOut), - SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut), - SOFA_TEMPLATE3(Cosserat::mapping::BaseCosseratMapping, TIn1, TIn2, TOut)); + SOFA_CLASS(SOFA_TEMPLATE3(DiscreteCosseratMapping, TIn1, TIn2, TOut), + SOFA_TEMPLATE3(Cosserat::mapping::BaseCosseratMapping, TIn1, TIn2, TOut)); /// Input Model Type typedef TIn1 In1; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 6046a248..df957bdf 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -85,7 +85,6 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { reinit(); // I call Init here since we build the mechanics only in the Inherit1::init(); - Inherit2::init(); m_colorMap.setColorScheme("Blue to Red"); m_colorMap.reinit(); diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index bf30dc10..ed8d6c14 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -51,12 +51,11 @@ using Cosserat::mapping::BaseCosseratMapping; template <class TIn1, class TIn2, class TOut> -class DiscreteDynamicCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut>, - BaseCosseratMapping<TIn1, TIn2, TOut> +class DiscreteDynamicCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { public: SOFA_CLASS(SOFA_TEMPLATE3(DiscreteDynamicCosseratMapping, TIn1,TIn2, TOut), - SOFA_TEMPLATE3(sofa::core::Multi2Mapping, TIn1, TIn2, TOut) ); + SOFA_TEMPLATE3(Cosserat::mapping::BaseCosseratMapping, TIn1, TIn2, TOut) ); typedef sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Inherit; /// Input Model Type From 6f463c9d021a915ffc4dff659c60b954484cf3c6 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 15:03:27 +0200 Subject: [PATCH 49/71] Add a Cosserat/fwd.h file to declare new types in Cosserat plugin Put in this fwd.h file all forward declaration of c++ types. In our case this is where we will declare the SE3 from Matrix4. --- CMakeLists.txt | 1 + src/Cosserat/fwd.h | 41 ++++++++++++++++++++++ src/Cosserat/initCosserat.h.in | 21 ++++------- src/Cosserat/mapping/BaseCosseratMapping.h | 36 +++++++------------ 4 files changed, 61 insertions(+), 38 deletions(-) create mode 100644 src/Cosserat/fwd.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 906ebfe1..ab03c205 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,6 +21,7 @@ set(SRC_ROOT_DIR src/${PROJECT_NAME}) set(HEADER_FILES ${SRC_ROOT_DIR}/initCosserat.h.in + ${SRC_ROOT_DIR}/fwd.h ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.h ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.inl ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.h diff --git a/src/Cosserat/fwd.h b/src/Cosserat/fwd.h new file mode 100644 index 00000000..b800535a --- /dev/null +++ b/src/Cosserat/fwd.h @@ -0,0 +1,41 @@ +/****************************************************************************** + * SOFA, Simulation Open-Framework Architecture * + * (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * + * * + * This library is free software; you can redistribute it and/or modify it * + * under the terms of the GNU Lesser General Public License as published by * + * the Free Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. * + * * + * This library is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * + * for more details. * + * * + * You should have received a copy of the GNU Lesser General Public License * + * along with this library; if not, write to the Free Software Foundation, * + * Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * + ******************************************************************************* + * Plugin Cosserat v1.0 * + * * + * This plugin is also distributed under the GNU LGPL (Lesser General * + * Public License) license with the same conditions than SOFA. * + * * + * Contributors: Defrost team (INRIA, University of Lille, CNRS, * + * Ecole Centrale de Lille) * + * * + * Contact information: https://project.inria.fr/softrobot/contact/ * + * * + ******************************************************************************/ +#pragma once + +#include <Cosserat/initCosserat.h> +#include <sofa/type/fwd.h> +namespace Cosserat +{ + namespace type + { + using SE3 = sofa::type::Matrix4; + } +} + diff --git a/src/Cosserat/initCosserat.h.in b/src/Cosserat/initCosserat.h.in index 1f4dd378..cbf8f178 100644 --- a/src/Cosserat/initCosserat.h.in +++ b/src/Cosserat/initCosserat.h.in @@ -27,8 +27,7 @@ * Contact information: https://project.inria.fr/softrobot/contact/ * * * ******************************************************************************/ -#ifndef SOFA_COSSERAT_INIT_H -#define SOFA_COSSERAT_INIT_H +#pragma once #include <sofa/config.h> @@ -45,17 +44,9 @@ This is the plugin for the Discret Cosserat Plugin */ -namespace Cosserat { - -namespace type { -//using Vec3 = sofa::defaulttype::Vec3; -//using cosserat::type::SE3; +namespace Cosserat +{ + SOFA_COSSERAT_API void init(); + constexpr const char *MODULE_NAME = "@PROJECT_NAME@"; + constexpr const char *MODULE_VERSION = "@PROJECT_VERSION@"; } - - -SOFA_COSSERAT_API void init(); -constexpr const char *MODULE_NAME = "@PROJECT_NAME@"; -constexpr const char *MODULE_VERSION = "@PROJECT_VERSION@"; -} // namespace Cosserat - -#endif /* SOFA_COSSERAT_INIT_H */ diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 0a7ba357..4f60e732 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -21,35 +21,27 @@ ******************************************************************************/ #pragma once #include <Cosserat/initCosserat.h> +#include <Cosserat/fwd.h> -#include <sofa/core/BaseMapping.h> #include <sofa/core/Multi2Mapping.h> #include <sofa/core/config.h> #include <sofa/core/objectmodel/BaseObject.h> #include <sofa/defaulttype/RigidTypes.h> #include <sofa/defaulttype/SolidTypes.h> #include <sofa/type/Vec.h> - -#include <cmath> #include <iostream> - #include <Eigen/Dense> #include <cmath> -using namespace std; -using namespace Eigen; - -#include <cmath> - -// TODO(dmarchal, 2024/06/07): This is polluating the namespace of -// sofa::components -// plugins should be in their own namespace like -// eg: cosserat::component::mapping -namespace Cosserat::mapping { +namespace Cosserat::mapping +{ // with a private namespace the used named are not polluating the whole // sofa::component::mapping ones. -namespace { +namespace +{ +using namespace std; +using namespace Eigen; using sofa::core::objectmodel::BaseContext; using sofa::core::objectmodel::BaseObject; using sofa::defaulttype::SolidTypes; @@ -61,19 +53,17 @@ using sofa::type::Vec3; using sofa::type::Vec6; using sofa::type::Mat; -typedef typename Eigen::Matrix4d _SE3; -} // namespace +using Cosserat::type::SE3; +using _SE3 = Eigen::Matrix4d; + +} +// TODO(dmarchal: 2024/10/07) Is the description valid ? /*! - * \class BaseCosserat + * \class BaseCosseratMapping * @brief Computes and map the length of the beams * - * This is a component: - * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ - -// TODO(dmarchal: 2024/06/07) This component looks like a mapping but inherit -// from BaseObject * can you clarify why is is not inhering from BaseMapping template <class TIn1, class TIn2, class TOut> class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> { From 87a30a7da0599214228b332badfdd9f923b9181c Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 15:10:16 +0200 Subject: [PATCH 50/71] Move SE3, se3, _SE3, _se3 out of the class. --- src/Cosserat/mapping/BaseCosseratMapping.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp index 0dfbb4bc..70a3c21c 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -31,8 +31,7 @@ namespace Cosserat::mapping using namespace sofa::defaulttype; template <> -BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::se3 -BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const Coord1 &strain_i) +auto BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const Coord1 &strain_i) -> se3 { se3 Xi; From 18d833574e59b9d25829031196c23860df9f482c Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 15:10:38 +0200 Subject: [PATCH 51/71] FIXUP --- src/Cosserat/mapping/BaseCosseratMapping.h | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 4f60e732..ac4bb9f4 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -53,7 +53,9 @@ using sofa::type::Vec3; using sofa::type::Vec6; using sofa::type::Mat; -using Cosserat::type::SE3; +using se3 = sofa::type::Matrix4; +using SE3 = sofa::type::Matrix4; +using _se3 = Eigen::Matrix4d; using _SE3 = Eigen::Matrix4d; } @@ -123,10 +125,6 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> typedef typename SolidTypes<SReal>::Transform Transform; typedef typename sofa::type::vector<SReal> List; - typedef typename sofa::type::Matrix4 se3; - typedef typename sofa::type::Matrix4 SE3; - - typedef typename Eigen::Matrix4d _se3; typedef typename sofa::type::Mat<6, 6, SReal> Tangent; typedef typename Eigen::Matrix3d RotMat; typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; From 3e736395b81c6211e6f762d08660becda2ee1c6a Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 16:00:56 +0200 Subject: [PATCH 52/71] Add a types.h file to factorize all types declaration in cosserat plugins --- CMakeLists.txt | 1 + src/Cosserat/mapping/BaseCosseratMapping.h | 26 ++++----- src/Cosserat/mapping/BaseCosseratMapping.inl | 3 +- .../mapping/DiscreteCosseratMapping.cpp | 4 +- src/Cosserat/types.h | 53 +++++++++++++++++++ 5 files changed, 69 insertions(+), 18 deletions(-) create mode 100644 src/Cosserat/types.h diff --git a/CMakeLists.txt b/CMakeLists.txt index ab03c205..162ee198 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,6 +22,7 @@ set(SRC_ROOT_DIR src/${PROJECT_NAME}) set(HEADER_FILES ${SRC_ROOT_DIR}/initCosserat.h.in ${SRC_ROOT_DIR}/fwd.h + ${SRC_ROOT_DIR}/types.h ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.h ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.inl ${SRC_ROOT_DIR}/mapping/DiscreteCosseratMapping.h diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index ac4bb9f4..17b90db5 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -21,7 +21,7 @@ ******************************************************************************/ #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/fwd.h> +#include <Cosserat/types.h> #include <sofa/core/Multi2Mapping.h> #include <sofa/core/config.h> @@ -47,6 +47,9 @@ using sofa::core::objectmodel::BaseObject; using sofa::defaulttype::SolidTypes; using sofa::type::Matrix3; using sofa::type::Matrix4; +using sofa::type::Mat6x6; +using sofa::type::Mat4x4; + using std::get; using sofa::type::vector; using sofa::type::Vec3; @@ -58,6 +61,10 @@ using SE3 = sofa::type::Matrix4; using _se3 = Eigen::Matrix4d; using _SE3 = Eigen::Matrix4d; +using Cosserat::type::Transform; +using Cosserat::type::Tangent; +using Cosserat::type::RotMat; + } // TODO(dmarchal: 2024/10/07) Is the description valid ? @@ -70,14 +77,11 @@ template <class TIn1, class TIn2, class TOut> class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> { public: - SOFA_CLASS(SOFA_TEMPLATE3(BaseCosseratMapping, TIn1, TIn2, TOut), BaseObject); - typedef BaseObject Inherit; + SOFA_ABSTRACT_CLASS(SOFA_TEMPLATE3(BaseCosseratMapping, TIn1, TIn2, TOut), + SOFA_TEMPLATE3(sofa::core::Multi2Mapping,TIn1, TIn2, TOut)); - /// Input Model Type typedef TIn1 In1; typedef TIn2 In2; - - /// Output Model Type typedef TOut Out; // TODO(dmarchal:2024/06/07) This very long list of public typedefs looks @@ -99,8 +103,6 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> [[maybe_unused]] typedef typename In2::MatrixDeriv In2MatrixDeriv; typedef sofa::Data<In2VecCoord> In2DataVecCoord; typedef sofa::Data<In2VecDeriv> In2DataVecDeriv; - typedef Mat<6, 6, SReal> Mat6x6; - typedef Mat<4, 4, SReal> Mat4x4; typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; @@ -117,18 +119,12 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> typedef sofa::MultiLink<BaseCosseratMapping<In1, In2, Out>, sofa::core::State<In2>, sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> LinkFromModels2; + [[maybe_unused]] typedef sofa::MultiLink< BaseCosseratMapping<In1, In2, Out>, sofa::core::State<Out>, sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> LinkToModels; - typedef typename SolidTypes<SReal>::Transform Transform; - typedef typename sofa::type::vector<SReal> List; - - typedef typename sofa::type::Mat<6, 6, SReal> Tangent; - typedef typename Eigen::Matrix3d RotMat; - typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; - public: // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this // really needed ? diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index fdf25e88..0bb59b0a 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -61,7 +61,8 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() // _________________________________________________________________________________________ template <class TIn1, class TIn2, class TOut> -void BaseCosseratMapping<TIn1, TIn2, TOut>::init() { +void BaseCosseratMapping<TIn1, TIn2, TOut>::init() +{ Inherit1::init(); // Fill the initial vector diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index 85fef06d..ef389af3 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -48,8 +48,8 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( const auto baseIndex = d_baseIndex.getValue(); // Curv abscissa of nodes and frames - sofa::helper::ReadAccessor<Data<List>> curv_abs_section = d_curv_abs_section; - sofa::helper::ReadAccessor<Data<List>> curv_abs_frames = d_curv_abs_frames; + sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_section = d_curv_abs_section; + sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_frames = d_curv_abs_frames; const In1VecCoord& inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); //Strains // Compute the tangent Exponential SE3 vectors diff --git a/src/Cosserat/types.h b/src/Cosserat/types.h new file mode 100644 index 00000000..cf5c720f --- /dev/null +++ b/src/Cosserat/types.h @@ -0,0 +1,53 @@ +/****************************************************************************** + * SOFA, Simulation Open-Framework Architecture * + * (c) 2006-2018 INRIA, USTL, UJF, CNRS, MGH * + * * + * This library is free software; you can redistribute it and/or modify it * + * under the terms of the GNU Lesser General Public License as published by * + * the Free Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. * + * * + * This library is distributed in the hope that it will be useful, but WITHOUT * + * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or * + * FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License * + * for more details. * + * * + * You should have received a copy of the GNU Lesser General Public License * + * along with this library; if not, write to the Free Software Foundation, * + * Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. * + ******************************************************************************* + * Plugin Cosserat v1.0 * + * * + * This plugin is also distributed under the GNU LGPL (Lesser General * + * Public License) license with the same conditions than SOFA. * + * * + * Contributors: Defrost team (INRIA, University of Lille, CNRS, * + * Ecole Centrale de Lille) * + * * + * Contact information: https://project.inria.fr/softrobot/contact/ * + * * + ******************************************************************************/ +#pragma once + +#include <Cosserat/initCosserat.h> +#include <sofa/type/vector.h> +#include <sofa/type/Mat.h> +#include <sofa/defaulttype/SolidTypes.h> +#include <Eigen/Dense> +namespace Cosserat +{ + + namespace type + { + using SE3 = sofa::type::Matrix4; + + typedef typename sofa::defaulttype::SolidTypes<SReal>::Transform Transform; + typedef typename sofa::type::vector<SReal> List; + + typedef typename sofa::type::Mat<6, 6, SReal> Tangent; + typedef typename Eigen::Matrix3d RotMat; + typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; + + } +} + From dc496d8fe897a75685aaa81f75638bb14012b123 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 16:04:07 +0200 Subject: [PATCH 53/71] Add a comment in BaseCOsseratMapping. --- src/Cosserat/mapping/BaseCosseratMapping.inl | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 0bb59b0a..56c226da 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -68,6 +68,9 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() // Fill the initial vector const OutDataVecCoord *xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); + + //TODO(dmarchal, 2024/07/12): is this line really needed ? + // it initialize a local variable, is it to force a xfromData updates ? const OutVecCoord xfrom = xfromData->getValue(); } @@ -83,8 +86,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( SE3 _g_X; se3 Xi_hat_n = buildXiHat(strain_n); - if (d_debug.getValue()) - msg_info("BaseCosserat: ") << "matrix Xi : " << Xi_hat_n; + msg_info() << "matrix Xi : " << Xi_hat_n; if (theta <= std::numeric_limits<double>::epsilon()) { _g_X = I4 + curv_abs_x_n * Xi_hat_n; From 837c3bfea0a3dd8585bf4f359759ad03e635c218 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 16:14:11 +0200 Subject: [PATCH 54/71] Replace Matrix3 by Mat3x3 and Matrix4 by Mat4x4. --- src/Cosserat/mapping/BaseCosseratMapping.cpp | 6 +-- src/Cosserat/mapping/BaseCosseratMapping.h | 22 ++++---- src/Cosserat/mapping/BaseCosseratMapping.inl | 57 +++++++++----------- 3 files changed, 39 insertions(+), 46 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp index 70a3c21c..370865bb 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -60,7 +60,7 @@ auto BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const template <> void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &Trans) { - Matrix4 I4; + Mat4x4 I4; I4.identity(); // Get the angular part of the @@ -100,7 +100,7 @@ void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) .norm(); // Sometimes this is computed over all strain - Matrix3 tilde_k = + Mat3x3 tilde_k = getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); /* Younes @23-11-27 @@ -112,7 +112,7 @@ void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( #TECHNICAL_DEBT */ // TODO(dmarchal: 2024/06/07) could the debt by solved ? - Matrix3 tilde_q = + Mat3x3 tilde_q = getTildeMatrix(Vec3(strain_i(3), strain_i(4), strain_i(5))); Mat6x6 ad_Xi; diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 17b90db5..2aeabbfb 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -45,10 +45,9 @@ using namespace Eigen; using sofa::core::objectmodel::BaseContext; using sofa::core::objectmodel::BaseObject; using sofa::defaulttype::SolidTypes; -using sofa::type::Matrix3; -using sofa::type::Matrix4; using sofa::type::Mat6x6; using sofa::type::Mat4x4; +using sofa::type::Mat3x3; using std::get; using sofa::type::vector; @@ -135,7 +134,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> vector<Transform> m_framesExponentialSE3Vectors; vector<Transform> m_nodesExponentialSE3Vectors; - vector<Matrix4> m_nodesLogarithmeSE3Vectors; + vector<Mat4x4> m_nodesLogarithmeSE3Vectors; // @todo comment or explain more vectors vector<unsigned int> m_indicesVectors; @@ -152,8 +151,9 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> vector<Mat6x6> m_nodeAdjointVectors; // TODO(dmarchal:2024/06/07): explain why these attributes are unused - // TODO : yadagolo: Need for the dynamic function, which is not working yet. - // But the component is in this folder + // : yadagolo: Need for the dynamic function, which is not working yet. But the component is in this folder + // : dmarchal: don't add something that will be used "one day" + // : dmarchal: it look like as if you should be working in a branch for making new feature and merge it when it is ready. [[maybe_unused]] vector<Mat6x6> m_nodeAdjointEtaVectors; [[maybe_unused]] vector<Mat6x6> m_frameAdjointEtaVectors; [[maybe_unused]] vector<Mat6x6> m_node_coAdjointEtaVectors; @@ -175,15 +175,15 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> double computeTheta(const double &x, const Mat4x4 &gX); void printMatrix(const Mat6x6 R); - Matrix3 extractRotMatrix(const Transform &frame); + sofa::type::Mat3x3 extractRotMatrix(const Transform &frame); Tangent buildProjector(const Transform &T); se3 buildXiHat(const Coord1 &strain_i); - Matrix3 getTildeMatrix(const Vec3 &u); + Mat3x3 getTildeMatrix(const Vec3 &u); - void buildAdjoint(const Matrix3 &A, const Matrix3 &B, Mat6x6 &Adjoint); - void buildCoAdjoint(const Matrix3 &A, const Matrix3 &B, Mat6x6 &coAdjoint); + void buildAdjoint(const Mat3x3 &A, const Mat3x3 &B, Mat6x6 &Adjoint); + void buildCoAdjoint(const Mat3x3 &A, const Mat3x3 &B, Mat6x6 &coAdjoint); - Matrix4 convertTransformToMatrix4x4(const Transform &T); + Mat4x4 convertTransformToMatrix4x4(const Transform &T); Vec6 piecewiseLogmap(const _SE3 &g_x); // TODO(dmarchal: 2024/06/07), this looks like a very common utility @@ -248,7 +248,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> [[maybe_unused]] Vec6 computeETA(const Vec6 &baseEta, const In1VecDeriv &k_dot, double abs_input); - Matrix4 computeLogarithm(const double &x, const Mat4x4 &gX); + Mat4x4 computeLogarithm(const double &x, const Mat4x4 &gX); }; #if !defined(SOFA_COSSERAT_CPP_BaseCosseratMapping) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 56c226da..cdd8a433 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -77,7 +77,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { - Matrix4 I4; + Mat4x4 I4; I4.identity(); // Get the angular part of the sofa::type::Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); @@ -99,8 +99,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( scalar2 * Xi_hat_n * Xi_hat_n * Xi_hat_n; } - if (d_debug.getValue()) - msg_info("BaseCosserat: ") << "matrix _g_X : " << _g_X; + msg_info() << "matrix _g_X : " << _g_X; + sofa::type::Mat3x3 M; _g_X.getsub(0, 0, M); // get the rotation matrix @@ -172,45 +172,39 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( } } -////////////////// Test the logarithm code -// Eigen::Matrix4d gX = convertTransformToMatrix4x4(T); -// Eigen::Matrix4d log_gX= (1.0/x) * computeLogarithm(x, gX); -// std::cout << "k : \n"<< k << std::endl; -// std::cout << "The logarithm : \n"<< log_gX << std::endl; -// m_nodesLogarithmSE3Vectors.push_back(log_gX); - template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, Tangent &adjoint) { - Matrix3 R = extractRotMatrix(frame); + Mat3x3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); - Matrix3 tilde_u = getTildeMatrix(u); - Matrix3 tilde_u_R = tilde_u * R; + Mat3x3 tilde_u = getTildeMatrix(u); + Mat3x3 tilde_u_R = tilde_u * R; buildAdjoint(R, tilde_u_R, adjoint); } template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, Mat6x6 &co_adjoint) { - Matrix3 R = extractRotMatrix(frame); + Mat3x3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); - Matrix3 tilde_u = getTildeMatrix(u); - Matrix3 tilde_u_R = tilde_u * R; + Mat3x3 tilde_u = getTildeMatrix(u); + Mat3x3 tilde_u_R = tilde_u * R; buildCoAdjoint(R, tilde_u_R, co_adjoint); } template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, Mat6x6 &adjoint) { - Matrix3 tildeMat = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); + Mat3x3 tildeMat = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); adjoint.setsub(0, 0, tildeMat); adjoint.setsub(3, 3, tildeMat); adjoint.setsub(3, 0, getTildeMatrix(Vec3(eta[3], eta[4], eta[5]))); } template <class TIn1, class TIn2, class TOut> -Matrix4 BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, - const Mat4x4 &gX) { +auto BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, + const Mat4x4 &gX) -> Mat4x4 +{ // Compute theta before everything const double theta = computeTheta(x, gX); Mat4x4 I4; @@ -300,7 +294,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) .norm(); // Sometimes this is computed over all strain - Matrix3 tilde_k = + Mat3x3 tilde_k = getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); /* Younes @23-11-27 old version @@ -310,7 +304,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, bring any difference in my three reference scenes, but need more investogation #TECHNICAL_DEBT */ - Matrix3 tilde_q = getTildeMatrix(Vec3(0.0, 0.0, 0.0)); + Mat3x3 tilde_q = getTildeMatrix(Vec3(0.0, 0.0, 0.0)); Mat6x6 ad_Xi; buildAdjoint(tilde_k, tilde_q, ad_Xi); @@ -479,8 +473,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R) { } template <class TIn1, class TIn2, class TOut> -Matrix3 -BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { +Mat3x3 BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { sofa::type::Quat q = frame.getOrientation(); @@ -489,7 +482,7 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) // does not need this amount of code. Real R[4][4]; q.buildRotationMatrix(R); - Matrix3 mat; + Mat3x3 mat; for (unsigned int k = 0; k < 3; k++) for (unsigned int i = 0; i < 3; i++) mat[k][i] = R[k][i]; @@ -534,7 +527,7 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) - template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) - -> Matrix3 { + -> Mat3x3 { sofa::type::Matrix3 tild; tild[0][1] = -u[2]; tild[0][2] = u[1]; @@ -547,8 +540,8 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec } template <class TIn1, class TIn2, class TOut> -auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, - const Matrix3 &B, +auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Mat3x3 &A, + const Mat3x3 &B, Mat6x6 &Adjoint) -> void { Adjoint.clear(); for (unsigned int i = 0; i < 3; i++) { @@ -561,8 +554,8 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Matrix3 &A, } template <class TIn1, class TIn2, class TOut> -auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, - const Matrix3 &B, +auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Mat3x3 &A, + const Mat3x3 &B, Mat6x6 &coAdjoint) -> void { coAdjoint.clear(); for (unsigned int i = 0; i < 3; i++) { @@ -579,10 +572,10 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Matrix3 &A, template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( - const Transform &T) -> Matrix4 { - Matrix4 M; + const Transform &T) -> Mat4x4 { + Mat4x4 M; M.identity(); - Matrix3 R = extractRotMatrix(T); + Mat3x3 R = extractRotMatrix(T); sofa::type::Vec3 trans = T.getOrigin(); for (unsigned int i = 0; i < 3; i++) { From f4b88f22df97cd5b9563d545ad6d608ef34259d2 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 16:23:45 +0200 Subject: [PATCH 55/71] Replace if(d_debug) msg_info("YOLO") by msg_info() Because msg_info already contains a test on wether we should print a message and this is connected by the printLog data field. More generally "debug" datafield is questionnable. --- src/Cosserat/mapping/BaseCosseratMapping.cpp | 6 - src/Cosserat/mapping/BaseCosseratMapping.inl | 153 +++++++++---------- 2 files changed, 68 insertions(+), 91 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp index 370865bb..dc813123 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -48,12 +48,6 @@ auto BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const for (unsigned int i = 0; i < 3; i++) Xi[i][3] += strain_i(i + 3); - // se3 = [ - // 0 -screw(3) screw(2) screw(4); - // screw(3) 0 -screw(1) screw(5); - // -screw(2) screw(1) 0 screw(6); - // 0 0 0 0]; - return Xi; } diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index cdd8a433..48a775de 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -50,13 +50,14 @@ using sofa::type::vector; template <class TIn1, class TIn2, class TOut> BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() + // TODO(dmarchal: 2024/06/12): please add the help comments ! : d_curv_abs_section(initData(&d_curv_abs_section, "curv_abs_input", " need to be com....")), - d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", - " need to be com....")), - d_debug(initData(&d_debug, false, "debug", "printf for the debug")), - m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), - m_index_input(0) {} + d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", + " need to be com....")), + d_debug(initData(&d_debug, false, "debug", "printf for the debug")), + m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), + m_index_input(0) {} // _________________________________________________________________________________________ @@ -67,7 +68,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() // Fill the initial vector const OutDataVecCoord *xfromData = - m_toModel->read(sofa::core::ConstVecCoordId::position()); + m_toModel->read(sofa::core::ConstVecCoordId::position()); //TODO(dmarchal, 2024/07/12): is this line really needed ? // it initialize a local variable, is it to force a xfromData updates ? @@ -76,7 +77,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( - const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { + const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { Mat4x4 I4; I4.identity(); // Get the angular part of the @@ -92,7 +93,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( _g_X = I4 + curv_abs_x_n * Xi_hat_n; } else { double scalar1 = - (1.0 - std::cos(curv_abs_x_n * theta)) / std::pow(theta, 2); + (1.0 - std::cos(curv_abs_x_n * theta)) / std::pow(theta, 2); double scalar2 = (curv_abs_x_n * theta - std::sin(curv_abs_x_n * theta)) / std::pow(theta, 3); _g_X = I4 + curv_abs_x_n * Xi_hat_n + scalar1 * Xi_hat_n * Xi_hat_n + @@ -113,11 +114,11 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( // Fill exponential vectors template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( - const In1VecCoord &inDeform) { + const In1VecCoord &inDeform) { // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = // d_curv_abs_section; sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = - d_curv_abs_frames; + d_curv_abs_frames; m_framesExponentialSE3Vectors.clear(); m_nodesExponentialSE3Vectors.clear(); @@ -128,53 +129,46 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( for (size_t i = 0; i < sz; i++) { Transform g_X_frame_i; - const Coord1 strain_n = inDeform[m_indicesVectors[i] - - 1]; // Cosserat reduce coordinates (strain) - // the size varies from 1 to 6 - // The distance between the frame and the closest beam node toward the base + const Coord1 strain_n = inDeform[m_indicesVectors[i] - 1]; // Cosserat reduce coordinates (strain) + + // the size varies from 1 to 6 + // The distance between the frame and the closest beam node toward the base const SReal curv_abs_x = - m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) + m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) computeExponentialSE3(curv_abs_x, strain_n, g_X_frame_i); m_framesExponentialSE3Vectors.push_back(g_X_frame_i); - if (d_debug.getValue()) { - msg_info("BaseCosserat:") - << "_________________" << i << "_________________________"; - msg_info("BaseCosserat:") - << "x :" << curv_abs_x << "; strain :" << strain_n; - msg_info("BaseCosserat:") + msg_info() + << "_________________" << i << "_________________________" << msgendl + << "x :" << curv_abs_x << "; strain :" << strain_n << msgendl << "m_framesExponentialSE3Vectors :" << g_X_frame_i; - } } // Compute the exponential on the nodes m_nodesExponentialSE3Vectors.push_back( - Transform(sofa::type::Vec3(0.0, 0.0, 0.0), - sofa::type::Quat(0., 0., 0., 1.))); // The first node. + Transform(sofa::type::Vec3(0.0, 0.0, 0.0), + sofa::type::Quat(0., 0., 0., 1.))); // The first node. for (unsigned int j = 0; j < inDeform.size(); j++) { Coord1 strain_n = inDeform[j]; // Strain_n const SReal curv_abs_x = - m_BeamLengthVectors[j]; // curv_abs_x = L_n - L_(n-1) + m_BeamLengthVectors[j]; // curv_abs_x = L_n - L_(n-1) Transform g_X_node_j; computeExponentialSE3(curv_abs_x, strain_n, g_X_node_j); m_nodesExponentialSE3Vectors.push_back(g_X_node_j); - if (d_debug.getValue()) { - msg_info("BaseCosserat:") - << "_________________Beam Node Expo___________________" << j; - msg_info("BaseCosserat:") - << "Node m_framesExponentialSE3Vectors :" << g_X_node_j; - msg_info("BaseCosserat:") + msg_info() + << "_________________Beam Node Expo___________________" << msgendl + << "Node m_framesExponentialSE3Vectors :" << g_X_node_j << msgendl << "_________________Beam Node Expo___________________"; - } + } } template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, - Tangent &adjoint) { + Tangent &adjoint) { Mat3x3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); Mat3x3 tilde_u = getTildeMatrix(u); @@ -184,7 +178,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Transform &fram template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &frame, - Mat6x6 &co_adjoint) { + Mat6x6 &co_adjoint) { Mat3x3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); Mat3x3 tilde_u = getTildeMatrix(u); @@ -194,7 +188,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &fr template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, - Mat6x6 &adjoint) { + Mat6x6 &adjoint) { Mat3x3 tildeMat = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); adjoint.setsub(0, 0, tildeMat); adjoint.setsub(3, 3, tildeMat); @@ -203,7 +197,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, - const Mat4x4 &gX) -> Mat4x4 + const Mat4x4 &gX) -> Mat4x4 { // Compute theta before everything const double theta = computeTheta(x, gX); @@ -226,10 +220,10 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, log_gX = cst * ((x_theta * cos_2XTheta - sin_XTheta) * I4 - (x_theta * cos_XTheta + 2.0 * x_theta * cos_2XTheta - sin_XTheta - sin_2XTheta) * - gX + + gX + (2.0 * x_theta * cos_XTheta + x_theta * cos_2XTheta - sin_XTheta - sin_2XTheta) * - (gX * gX) - + (gX * gX) - (x_theta * cos_XTheta - sin_XTheta) * (gX * gX * gX)); } @@ -238,18 +232,20 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( - const In1VecCoord &inDeform) { + const In1VecCoord &inDeform) { // Curv abscissa of nodes and frames sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = - d_curv_abs_section; + d_curv_abs_section; sofa::helper::ReadAccessor<sofa::Data<sofa::type::vector<double>>> curv_abs_frames = - d_curv_abs_frames; + d_curv_abs_frames; m_framesTangExpVectors.clear(); unsigned int sz = curv_abs_frames.size(); + // Compute tangExpo at frame points - for (unsigned int i = 0; i < sz; i++) { + for (unsigned int i = 0; i < sz; i++) + { Tangent temp; Coord1 strain_frame_i = inDeform[m_indicesVectors[i] - 1]; @@ -258,13 +254,9 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( m_framesTangExpVectors.push_back(temp); - if (d_debug.getValue()) { - printf("__________________________________________\n"); - std::cout << "x :" << curv_abs_x_i << "; k :" << strain_frame_i - << std::endl; - std::cout << "m_framesTangExpVectors :" << m_framesTangExpVectors[i] - << std::endl; - } + msg_info() + << "x :" << curv_abs_x_i << "; k :" << strain_frame_i << msgendl + << "m_framesTangExpVectors :" << m_framesTangExpVectors[i]; } // Compute the TangExpSE3 at the nodes @@ -281,21 +273,18 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( computeTangExp(x, strain_node_i, temp); m_nodesTangExpVectors.push_back(temp); } - if (d_debug.getValue()) { - printf("_________________Node TangExpo___________________\n"); - std::cout << "Node TangExpo : " << m_nodesTangExpVectors << std::endl; - } + msg_info() << "Node TangExpo : " << m_nodesTangExpVectors; } template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, - const Coord1 &strain_i, - Mat6x6 &TgX) { + const Coord1 &strain_i, + Mat6x6 &TgX) { SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) - .norm(); // Sometimes this is computed over all strain + .norm(); // Sometimes this is computed over all strain Mat3x3 tilde_k = - getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); + getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); /* Younes @23-11-27 old version @Todo ???? is p the linear deformation? If so, why didn't I just put a zero @@ -340,18 +329,16 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, template <class TIn1, class TIn2, class TOut> [[maybe_unused]] Vec6 BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, - const In1VecDeriv &k_dot, - const double abs_input) { + const In1VecDeriv &k_dot, + const double abs_input) { // Fill the initial vector const In1DataVecCoord *x1fromData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_input = - d_curv_abs_section; - // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_output = - // d_curv_abs_frames; + d_curv_abs_section; Transform out_Trans; Mat6x6 Adjoint, Tg; @@ -386,14 +373,13 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { // it is attached. Here we only use the information from the curvilinear // abscissa of each frame. sofa::helper::ReadAccessor<sofa::Data<sofa::type::vector<double>>> curv_abs_section = - d_curv_abs_section; + d_curv_abs_section; sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = - d_curv_abs_frames; + d_curv_abs_frames; size_t sz = d_curv_abs_frames.getValue().size(); - if (d_debug.getValue()) - msg_info("BaseCosserat:") + msg_info() << " curv_abs_section " << d_curv_abs_frames.getValue().size() << "; curv_abs_frames: " << d_curv_abs_frames.getValue().size(); @@ -408,7 +394,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { if (curv_abs_section[input_index] > curv_abs_frames[i]) { m_indicesVectors.emplace_back(input_index); m_indicesVectorsDraw.emplace_back( - input_index); // maybe I shouldn't do this here !!! + input_index); // maybe I shouldn't do this here !!! } else if (curv_abs_section[input_index] == curv_abs_frames[i]) { m_indicesVectors.emplace_back(input_index); input_index++; @@ -423,21 +409,18 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { // m_framesLengthVectors.push_back(curv_abs_frames[i] - // curv_abs_section[m_indicesVectors[i] - 1]); m_framesLengthVectors.emplace_back( - curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); + curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); } for (size_t j = 0; j < curv_abs_section.size() - 1; j++) { m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - - curv_abs_section[j]); + curv_abs_section[j]); } - if (d_debug.getValue()) { - msg_info("BaseCosserat:") << "m_indicesVectors : " << m_indicesVectors; - msg_info("BaseCosserat:") - << "m_framesLengthVectors : " << m_framesLengthVectors; - msg_info("BaseCosserat:") - << "m_BeamLengthVectors : " << m_BeamLengthVectors; - } + msg_info() + << "m_indicesVectors : " << m_indicesVectors << msgendl + << "m_framesLengthVectors : " << msgendl + << "m_BeamLengthVectors : " << msgendl; } template <class TIn1, class TIn2, class TOut> @@ -445,7 +428,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::draw(const sofa::core::visual::Visua template <class TIn1, class TIn2, class TOut> double BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta(const double &x, - const Mat4x4 &gX) { + const Mat4x4 &gX) { double Tr_gx = 0.0; for (int i = 0; i < 4; i++) { Tr_gx += gX[i][i]; @@ -491,7 +474,7 @@ Mat3x3 BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform & template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildProjector(const Transform &T) - -> Tangent { +-> Tangent { Mat6x6 P; // TODO(dmarchal: 2024/06/07) The following code should probably become @@ -527,7 +510,7 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) - template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) - -> Mat3x3 { +-> Mat3x3 { sofa::type::Matrix3 tild; tild[0][1] = -u[2]; tild[0][2] = u[1]; @@ -541,8 +524,8 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Mat3x3 &A, - const Mat3x3 &B, - Mat6x6 &Adjoint) -> void { + const Mat3x3 &B, + Mat6x6 &Adjoint) -> void { Adjoint.clear(); for (unsigned int i = 0; i < 3; i++) { for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j @@ -555,8 +538,8 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Mat3x3 &A, template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Mat3x3 &A, - const Mat3x3 &B, - Mat6x6 &coAdjoint) -> void { + const Mat3x3 &B, + Mat6x6 &coAdjoint) -> void { coAdjoint.clear(); for (unsigned int i = 0; i < 3; i++) { for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j @@ -572,7 +555,7 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Mat3x3 &A, template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( - const Transform &T) -> Mat4x4 { + const Transform &T) -> Mat4x4 { Mat4x4 M; M.identity(); Mat3x3 R = extractRotMatrix(T); From 9aa7ac6a42e826c3806c7a62d573d1287f1b5dde Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 17:08:09 +0200 Subject: [PATCH 56/71] Replace ReadAccessor with sofa::helper::getReadAccessor; The sofa::helper::getReadAccessor function is to be used on type free expression this way: auto a = getReadAccessor(m_data); --- src/Cosserat/mapping/BaseCosseratMapping.h | 3 ++- src/Cosserat/mapping/BaseCosseratMapping.inl | 27 ++++++++------------ 2 files changed, 12 insertions(+), 18 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 2aeabbfb..9dfdf8b7 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -29,7 +29,7 @@ #include <sofa/defaulttype/RigidTypes.h> #include <sofa/defaulttype/SolidTypes.h> #include <sofa/type/Vec.h> -#include <iostream> +//#include <iostream> #include <Eigen/Dense> #include <cmath> @@ -64,6 +64,7 @@ using Cosserat::type::Transform; using Cosserat::type::Tangent; using Cosserat::type::RotMat; + } // TODO(dmarchal: 2024/10/07) Is the description valid ? diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 48a775de..a72e0b76 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -114,11 +114,9 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( // Fill exponential vectors template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( - const In1VecCoord &inDeform) { - // helper::ReadAccessor<Data<helper::vector<double>>> curv_abs_input = - // d_curv_abs_section; - sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = - d_curv_abs_frames; + const In1VecCoord &inDeform) +{ + auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); m_framesExponentialSE3Vectors.clear(); m_nodesExponentialSE3Vectors.clear(); @@ -235,13 +233,11 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( const In1VecCoord &inDeform) { // Curv abscissa of nodes and frames - sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = - d_curv_abs_section; - sofa::helper::ReadAccessor<sofa::Data<sofa::type::vector<double>>> curv_abs_frames = - d_curv_abs_frames; + auto curv_abs_section = sofa::helper::getReadAccessor(d_curv_abs_section); + auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); - m_framesTangExpVectors.clear(); unsigned int sz = curv_abs_frames.size(); + m_framesTangExpVectors.resize(sz); // Compute tangExpo at frame points for (unsigned int i = 0; i < sz; i++) @@ -252,7 +248,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( double curv_abs_x_i = m_framesLengthVectors[i]; computeTangExp(curv_abs_x_i, strain_frame_i, temp); - m_framesTangExpVectors.push_back(temp); + m_framesTangExpVectors[i] = temp; msg_info() << "x :" << curv_abs_x_i << "; k :" << strain_frame_i << msgendl @@ -337,8 +333,7 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); - sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_input = - d_curv_abs_section; + auto curv_abs_input = sofa::helper::getReadAccessor(d_curv_abs_section); Transform out_Trans; Mat6x6 Adjoint, Tg; @@ -372,10 +367,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { // For each frame in the global frame, find the segment of the beam to which // it is attached. Here we only use the information from the curvilinear // abscissa of each frame. - sofa::helper::ReadAccessor<sofa::Data<sofa::type::vector<double>>> curv_abs_section = - d_curv_abs_section; - sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = - d_curv_abs_frames; + auto curv_abs_section = sofa::helper::getReadAccessor(d_curv_abs_section); + auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); size_t sz = d_curv_abs_frames.getValue().size(); From 077e98438b1af08459acc875d7f5d7833596a11c Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 17:19:58 +0200 Subject: [PATCH 57/71] remove toModel, fromModel1, fromModel2 to use he inherited attributes from MultiMapping --- src/Cosserat/mapping/BaseCosseratMapping.h | 10 +++------- src/Cosserat/mapping/BaseCosseratMapping.inl | 5 ++--- 2 files changed, 5 insertions(+), 10 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 9dfdf8b7..f2d7f663 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -217,13 +217,9 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> sofa::Data<vector<double>> d_curv_abs_frames; sofa::Data<bool> d_debug; - /// Input Models container. New inputs are added through addInputModel(In* ). - sofa::core::State<In1> *m_fromModel1; - - // TODO(dmarchal): why this maybe_unused on a data field ? - [[maybe_unused]] sofa::core::State<In2> *m_fromModel2; - - sofa::core::State<Out> *m_toModel; + using Inherit1::fromModels1; + using Inherit1::fromModels2; + using Inherit1::toModels; protected: /// Constructor diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index a72e0b76..e5922282 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -56,7 +56,6 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", " need to be com....")), d_debug(initData(&d_debug, false, "debug", "printf for the debug")), - m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), m_index_input(0) {} // _________________________________________________________________________________________ @@ -68,7 +67,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() // Fill the initial vector const OutDataVecCoord *xfromData = - m_toModel->read(sofa::core::ConstVecCoordId::position()); + toModels[0]->read(sofa::core::ConstVecCoordId::position()); //TODO(dmarchal, 2024/07/12): is this line really needed ? // it initialize a local variable, is it to force a xfromData updates ? @@ -330,7 +329,7 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, // Fill the initial vector const In1DataVecCoord *x1fromData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + fromModels1[0]->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); auto curv_abs_input = sofa::helper::getReadAccessor(d_curv_abs_section); From 2d44aef63cfc2b847c7b6a40bf513376629bbc41 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 17:33:37 +0200 Subject: [PATCH 58/71] Several cleaning BaseCosseratMapping --- src/Cosserat/mapping/BaseCosseratMapping.h | 2 +- src/Cosserat/mapping/BaseCosseratMapping.inl | 66 ++++++++++---------- 2 files changed, 33 insertions(+), 35 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index f2d7f663..7314f597 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -163,7 +163,6 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> public: /********************** Inhertited from BaseObject **************/ void init() override; - void draw(const sofa::core::visual::VisualParams *) override; /************************* BaseCosserat **************************/ // TODO(dmarchal:2024/06/07), so we have "initialize" and "init" @@ -224,6 +223,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> protected: /// Constructor BaseCosseratMapping(); + /// Destructor ~BaseCosseratMapping() override = default; diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index e5922282..de58c0e5 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -37,16 +37,9 @@ // To go further => // https://www.mathworks.com/matlabcentral/fileexchange/83038-sorosim/ -namespace Cosserat::mapping { - -namespace +namespace Cosserat::mapping { -using namespace sofa::defaulttype; -using sofa::core::objectmodel::BaseContext; -using sofa::helper::AdvancedTimer; -using sofa::helper::WriteAccessor; -using sofa::type::vector; -} + template <class TIn1, class TIn2, class TOut> BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() @@ -65,20 +58,20 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() { Inherit1::init(); - // Fill the initial vector - const OutDataVecCoord *xfromData = - toModels[0]->read(sofa::core::ConstVecCoordId::position()); - - //TODO(dmarchal, 2024/07/12): is this line really needed ? - // it initialize a local variable, is it to force a xfromData updates ? + //TODO(dmarchal, 2024/07/12): is the following line really needed ? + // it initialize a local variable which initialize another data. + // is it to force a xfromData updates through the use of getValue(). In addition + // this is puzzleing as toModel is the destination of the computation of the mapping. + // to me it should be safe to remove the two line.. and thus the init :) + const OutDataVecCoord *xfromData = toModels[0]->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xfrom = xfromData->getValue(); } template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { - Mat4x4 I4; - I4.identity(); + const auto I4 = Mat4x4::Identity(); + // Get the angular part of the sofa::type::Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); SReal theta = k.norm(); // @@ -120,6 +113,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( m_framesExponentialSE3Vectors.clear(); m_nodesExponentialSE3Vectors.clear(); m_nodesLogarithmeSE3Vectors.clear(); + const unsigned int sz = curv_abs_frames.size(); // Compute exponential at each frame point @@ -369,11 +363,11 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { auto curv_abs_section = sofa::helper::getReadAccessor(d_curv_abs_section); auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); - size_t sz = d_curv_abs_frames.getValue().size(); + size_t sz = curv_abs_frames.size(); msg_info() - << " curv_abs_section " << d_curv_abs_frames.getValue().size() - << "; curv_abs_frames: " << d_curv_abs_frames.getValue().size(); + << " curv_abs_section " << curv_abs_frames.size() + << "; curv_abs_frames: " << curv_abs_frames.size(); m_indicesVectors.clear(); m_framesLengthVectors.clear(); @@ -381,13 +375,14 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { m_indicesVectorsDraw.clear(); size_t input_index = 1; - - for (size_t i = 0; i < sz; i++) { - if (curv_abs_section[input_index] > curv_abs_frames[i]) { + for (size_t i = 0; i < sz; ++i) + { + if (curv_abs_section[input_index] > curv_abs_frames[i]) + { m_indicesVectors.emplace_back(input_index); - m_indicesVectorsDraw.emplace_back( - input_index); // maybe I shouldn't do this here !!! - } else if (curv_abs_section[input_index] == curv_abs_frames[i]) { + m_indicesVectorsDraw.emplace_back(input_index); // maybe I shouldn't do this here !!! + } else if (curv_abs_section[input_index] == curv_abs_frames[i]) + { m_indicesVectors.emplace_back(input_index); input_index++; m_indicesVectorsDraw.emplace_back(input_index); @@ -396,6 +391,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { m_indicesVectors.emplace_back(input_index); m_indicesVectorsDraw.emplace_back(input_index); } + // Fill the vector m_framesLengthVectors with the distance // between frame(output) and the closest beam node toward the base // m_framesLengthVectors.push_back(curv_abs_frames[i] - @@ -404,7 +400,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); } - for (size_t j = 0; j < curv_abs_section.size() - 1; j++) { + for (size_t j = 0; j < sz - 1; j++) + { m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); } @@ -415,9 +412,6 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { << "m_BeamLengthVectors : " << msgendl; } -template <class TIn1, class TIn2, class TOut> -void BaseCosseratMapping<TIn1, TIn2, TOut>::draw(const sofa::core::visual::VisualParams *) {} - template <class TIn1, class TIn2, class TOut> double BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta(const double &x, const Mat4x4 &gX) { @@ -519,8 +513,10 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildAdjoint(const Mat3x3 &A, const Mat3x3 &B, Mat6x6 &Adjoint) -> void { Adjoint.clear(); - for (unsigned int i = 0; i < 3; i++) { - for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j + for (unsigned int i = 0; i < 3; ++i) + { + for (int j = 0; j < 3; ++j) + { Adjoint[i][j] = A[i][j]; Adjoint[i + 3][j + 3] = A[i][j]; Adjoint[i + 3][j] = B[i][j]; @@ -533,8 +529,10 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Mat3x3 &A, const Mat3x3 &B, Mat6x6 &coAdjoint) -> void { coAdjoint.clear(); - for (unsigned int i = 0; i < 3; i++) { - for (int j = 0; j < 3; ++j) { // TODO(dmarchal:2024/06/07) unify i++ and ++j + for (unsigned int i = 0; i < 3; ++i) + { + for (int j = 0; j < 3; ++j) + { coAdjoint[i][j] = A[i][j]; coAdjoint[i + 3][j + 3] = A[i][j]; From e7392fed682f56c347e178d28cc463018e51a2f9 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Wed, 12 Jun 2024 18:00:12 +0200 Subject: [PATCH 59/71] Clean Vec6,Mat4x4 usage in BaseCosseratMapping for more readability (should't be breaking) --- src/Cosserat/mapping/BaseCosseratMapping.inl | 109 +++++++++---------- 1 file changed, 51 insertions(+), 58 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index de58c0e5..60b0b920 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -40,6 +40,10 @@ namespace Cosserat::mapping { +using sofa::helper::getReadAccessor; +using sofa::type::Vec6; +using sofa::type::Vec3; +using sofa::type::Quat; template <class TIn1, class TIn2, class TOut> BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() @@ -73,7 +77,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( const auto I4 = Mat4x4::Identity(); // Get the angular part of the - sofa::type::Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); + Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); SReal theta = k.norm(); // SE3 _g_X; @@ -94,11 +98,11 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( msg_info() << "matrix _g_X : " << _g_X; - sofa::type::Mat3x3 M; + Mat3x3 M; _g_X.getsub(0, 0, M); // get the rotation matrix // convert the rotation 3x3 matrix to a quaternion - sofa::type::Quat<Real> R; + Quat<Real> R; R.fromMatrix(M); g_X_n = Transform(Vec3(_g_X(0, 3), _g_X(1, 3), _g_X(2, 3)), R); } @@ -124,8 +128,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( // the size varies from 1 to 6 // The distance between the frame and the closest beam node toward the base - const SReal curv_abs_x = - m_framesLengthVectors[i]; // curv_abs_x = frame_curv_abs - L_(n-1) + const SReal curv_abs_x = m_framesLengthVectors[i]; computeExponentialSE3(curv_abs_x, strain_n, g_X_frame_i); m_framesExponentialSE3Vectors.push_back(g_X_frame_i); @@ -137,13 +140,13 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( // Compute the exponential on the nodes m_nodesExponentialSE3Vectors.push_back( - Transform(sofa::type::Vec3(0.0, 0.0, 0.0), - sofa::type::Quat(0., 0., 0., 1.))); // The first node. + Transform(Vec3(0.0, 0.0, 0.0), + Quat(0., 0., 0., 1.))); // The first node. - for (unsigned int j = 0; j < inDeform.size(); j++) { - Coord1 strain_n = inDeform[j]; // Strain_n - const SReal curv_abs_x = - m_BeamLengthVectors[j]; // curv_abs_x = L_n - L_(n-1) + for (unsigned int j = 0; j < inDeform.size(); ++j) + { + Coord1 strain_n = inDeform[j]; + const SReal curv_abs_x = m_BeamLengthVectors[j]; Transform g_X_node_j; computeExponentialSE3(curv_abs_x, strain_n, g_X_node_j); @@ -226,8 +229,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( const In1VecCoord &inDeform) { // Curv abscissa of nodes and frames - auto curv_abs_section = sofa::helper::getReadAccessor(d_curv_abs_section); - auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); + auto curv_abs_section = getReadAccessor(d_curv_abs_section); + auto curv_abs_frames = getReadAccessor(d_curv_abs_frames); unsigned int sz = curv_abs_frames.size(); m_framesTangExpVectors.resize(sz); @@ -288,7 +291,6 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, buildAdjoint(tilde_k, tilde_q, ad_Xi); Mat6x6 Id6 = Mat6x6::Identity(); - // for (unsigned int i =0; i< 6;i++) Id6[i][i]=1.0; //define identity 6x6 if (theta <= std::numeric_limits<double>::epsilon()) { double scalar0 = std::pow(curv_abs_n, 2) / 2.0; @@ -319,37 +321,38 @@ template <class TIn1, class TIn2, class TOut> [[maybe_unused]] Vec6 BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, const In1VecDeriv &k_dot, - const double abs_input) { + const double abs_input) +{ - // Fill the initial vector - const In1DataVecCoord *x1fromData = - fromModels1[0]->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); + // Get the positions from model 0. This function returns the position wrapped in a Data<> + auto d_x1 = fromModels1[0]->read(sofa::core::ConstVecCoordId::position()); - auto curv_abs_input = sofa::helper::getReadAccessor(d_curv_abs_section); + // To access the actual content (in this case position) from a data, we have to use + // a read accessor that insures the data is updated according to DDGNode state + auto x1 = getReadAccessor(*d_x1); + + // Same as for x1, query a read accessor so we can access the content of d_curv_abs_section + auto curv_abs_input = getReadAccessor(d_curv_abs_section); Transform out_Trans; Mat6x6 Adjoint, Tg; + Vec6 Xi_dot; - sofa::type::Vec6 Xi_dot; - for (unsigned int i = 0; i < 3; i++) + for (unsigned int i = 0; i < 3; ++i) Xi_dot[i] = k_dot[m_index_input][i]; - double diff0; - double _diff0; + double diff0 = abs_input; + double _diff0 = -abs_input; - if (m_index_input == 0) { - diff0 = abs_input; // - _diff0 = -abs_input; - } else { + if (m_index_input != 0) + { diff0 = abs_input - curv_abs_input[m_index_input - 1]; _diff0 = curv_abs_input[m_index_input - 1] - abs_input; } - computeExponentialSE3(_diff0, x1from[m_index_input], out_Trans); + computeExponentialSE3(_diff0, x1[m_index_input], out_Trans); computeAdjoint(out_Trans, Adjoint); - - computeTangExp(diff0, x1from[m_index_input], Tg); + computeTangExp(diff0, x1[m_index_input], Tg); return Adjoint * (baseEta + Tg * Xi_dot); } @@ -360,20 +363,18 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { // For each frame in the global frame, find the segment of the beam to which // it is attached. Here we only use the information from the curvilinear // abscissa of each frame. - auto curv_abs_section = sofa::helper::getReadAccessor(d_curv_abs_section); - auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); - - size_t sz = curv_abs_frames.size(); + auto curv_abs_section = getReadAccessor(d_curv_abs_section); + auto curv_abs_frames = getReadAccessor(d_curv_abs_frames); msg_info() - << " curv_abs_section " << curv_abs_frames.size() - << "; curv_abs_frames: " << curv_abs_frames.size(); + << " curv_abs_section " << curv_abs_frames.size() << "; curv_abs_frames: " << curv_abs_frames.size(); m_indicesVectors.clear(); m_framesLengthVectors.clear(); m_BeamLengthVectors.clear(); m_indicesVectorsDraw.clear(); + size_t sz = curv_abs_frames.size(); size_t input_index = 1; for (size_t i = 0; i < sz; ++i) { @@ -394,16 +395,13 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { // Fill the vector m_framesLengthVectors with the distance // between frame(output) and the closest beam node toward the base - // m_framesLengthVectors.push_back(curv_abs_frames[i] - - // curv_abs_section[m_indicesVectors[i] - 1]); m_framesLengthVectors.emplace_back( curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); } - for (size_t j = 0; j < sz - 1; j++) + for (size_t j = 0; j < sz - 1; ++j) { - m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - - curv_abs_section[j]); + m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); } msg_info() @@ -415,18 +413,12 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { template <class TIn1, class TIn2, class TOut> double BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta(const double &x, const Mat4x4 &gX) { - double Tr_gx = 0.0; - for (int i = 0; i < 4; i++) { - Tr_gx += gX[i][i]; - } + double Tr_gx = sofa::type::trace(gX); - double theta; - if (x <= std::numeric_limits<double>::epsilon()) - theta = 0.0; - else - theta = (1.0 / x) * std::acos((Tr_gx / 2.0) - 1); + if (x > std::numeric_limits<double>::epsilon()) + return (1.0 / x) * std::acos((Tr_gx / 2.0) - 1); - return theta; + return 0.0; } template <class TIn1, class TIn2, class TOut> @@ -444,7 +436,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::printMatrix(const Mat6x6 R) { template <class TIn1, class TIn2, class TOut> Mat3x3 BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform &frame) { - sofa::type::Quat q = frame.getOrientation(); + Quat q = frame.getOrientation(); // TODO(dmarchal: 2024/06/07) The following code should probably become // utility function building a 3x3 matix from a quaternion should probably @@ -546,13 +538,14 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildCoAdjoint(const Mat3x3 &A, template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::convertTransformToMatrix4x4( const Transform &T) -> Mat4x4 { - Mat4x4 M; - M.identity(); + Mat4x4 M = Mat4x4::Identity(); Mat3x3 R = extractRotMatrix(T); - sofa::type::Vec3 trans = T.getOrigin(); + Vec3 trans = T.getOrigin(); - for (unsigned int i = 0; i < 3; i++) { - for (unsigned int j = 0; j < 3; j++) { + for (unsigned int i = 0; i < 3; i++) + { + for (unsigned int j = 0; j < 3; j++) + { M(i, j) = R[i][j]; M(i, 3) = trans[i]; } From ee8b742a4b2351ccca29b254b637cc72fa48e63b Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 11:38:33 +0200 Subject: [PATCH 60/71] Cosmetic cleaning in BaseCosserat & DiscreteCorreseratMapping.h --- src/Cosserat/mapping/BaseCosseratMapping.h | 17 +-- src/Cosserat/mapping/BaseCosseratMapping.inl | 25 ++-- .../mapping/DiscreteCosseratMapping.h | 119 +++++++++--------- 3 files changed, 72 insertions(+), 89 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 7314f597..f380eea6 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -113,18 +113,6 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> typedef sofa::Data<OutVecDeriv> OutDataVecDeriv; typedef sofa::Data<OutMatrixDeriv> OutDataMatrixDeriv; - typedef sofa::MultiLink<BaseCosseratMapping<In1, In2, Out>, sofa::core::State<In1>, - sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> - LinkFromModels1; - typedef sofa::MultiLink<BaseCosseratMapping<In1, In2, Out>, sofa::core::State<In2>, - sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> - LinkFromModels2; - - [[maybe_unused]] typedef sofa::MultiLink< - BaseCosseratMapping<In1, In2, Out>, sofa::core::State<Out>, - sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> - LinkToModels; - public: // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this // really needed ? @@ -231,9 +219,8 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> Transform &Trans); // TODO(dmarchal: 2024/06/07): - // - two naming convention - // - unclear the difference between computeAdjoing and buildAdjoint ... is - // there room for factoring things ? + // - clarify the difference between computeAdjoing and buildAdjoint ... + // - clarify why we need Transform and Vec6. void computeAdjoint(const Transform &frame, Mat6x6 &adjoint); void computeAdjoint(const Vec6 &frame, Mat6x6 &adjoint); diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 60b0b920..e3104065 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -121,7 +121,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( const unsigned int sz = curv_abs_frames.size(); // Compute exponential at each frame point - for (size_t i = 0; i < sz; i++) { + for (size_t i = 0; i < sz; ++i) + { Transform g_X_frame_i; const Coord1 strain_n = inDeform[m_indicesVectors[i] - 1]; // Cosserat reduce coordinates (strain) @@ -334,12 +335,9 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, // Same as for x1, query a read accessor so we can access the content of d_curv_abs_section auto curv_abs_input = getReadAccessor(d_curv_abs_section); - Transform out_Trans; - Mat6x6 Adjoint, Tg; - Vec6 Xi_dot; - - for (unsigned int i = 0; i < 3; ++i) - Xi_dot[i] = k_dot[m_index_input][i]; + auto& kdot = k_dot[m_index_input]; + Vec6 Xi_dot {kdot[0], kdot[1], kdot[2], + 0,0,0}; double diff0 = abs_input; double _diff0 = -abs_input; @@ -350,11 +348,16 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, _diff0 = curv_abs_input[m_index_input - 1] - abs_input; } - computeExponentialSE3(_diff0, x1[m_index_input], out_Trans); - computeAdjoint(out_Trans, Adjoint); - computeTangExp(diff0, x1[m_index_input], Tg); + Transform outTransform; + computeExponentialSE3(_diff0, x1[m_index_input], outTransform); + + Mat6x6 adjointMatrix; + computeAdjoint(outTransform, adjointMatrix); + + Tangent tangentMatrix; + computeTangExp(diff0, x1[m_index_input], tangentMatrix); - return Adjoint * (baseEta + Tg * Xi_dot); + return adjointMatrix * (baseEta + tangentMatrix * Xi_dot); } //___________________________________________________________________________ diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index c5547b8b..5cd0398d 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -44,15 +44,12 @@ using sofa::type::Quat; using std::get; using sofa::Data; + /*! * \class DiscreteCosseratMapping * @brief Computes and map the length of the beams * - * This is a component: - * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ -// using Cosserat::mapping::BaseCosserat; - template <class TIn1, class TIn2, class TOut> class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { public: @@ -99,10 +96,9 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; typedef typename SolidTypes<Real2>::Transform Transform; -protected: - sofa::core::State<In1> *m_fromModel1; - sofa::core::State<In2> *m_fromModel2; - sofa::core::State<Out> *m_toModel; + ////////////////////////////////////////////////////////////////////// + /// @name Data Fields + /// @{ Data<int> d_deformationAxis; Data<Real2> d_max; Data<Real2> d_min; @@ -111,92 +107,89 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { Data<sofa::type::RGBAColor> d_color; Data<vector<int>> d_index; Data<unsigned int> d_baseIndex; + /// @} + ////////////////////////////////////////////////////////////////////// public: - typedef sofa::MultiLink<DiscreteCosseratMapping<In1, In2, Out>, - sofa::core::State<In1>, - sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> - LinkFromModels1; - typedef sofa::MultiLink<DiscreteCosseratMapping<In1, In2, Out>, - sofa::core::State<In2>, - sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> - LinkFromModels2; - typedef sofa::MultiLink<DiscreteCosseratMapping<In1, In2, Out>, - sofa::core::State<Out>, - sofa::BaseLink::FLAG_STOREPATH | sofa::BaseLink::FLAG_STRONGLINK> - LinkToModels; - -protected: - ////////////////////////// Inherited attributes //////////////////////////// - /// https://gcc.gnu.org/onlinedocs/gcc/Name-lookup.html - /// Bring inherited attributes and function in the current lookup context. - /// otherwise any access to the base::attribute would require - /// the "this->" approach. - /// - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_section; - using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_frames; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesTangExpVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesVelocityVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesTangExpVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_totalBeamForceVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::d_debug; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectorsDraw; - using BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta; - -protected: - /// Constructor - DiscreteCosseratMapping(); - /// Destructor - ~DiscreteCosseratMapping() override {} - -public: - /**********************SOFA METHODS**************************/ + ////////////////////////////////////////////////////////////////////// + /// The following methods are inherited from BaseObject + /// @{ void init() override; void reinit() override; void draw(const sofa::core::visual::VisualParams *vparams) override; + /// @} + ////////////////////////////////////////////////////////////////////// + - /**********************MAPPING METHODS**************************/ - void - apply(const sofa::core::MechanicalParams * /* mparams */, + ////////////////////////////////////////////////////////////////////// + /// The following method are inherited from MultiMapping + /// @{ + void apply(const sofa::core::MechanicalParams * /* mparams */, const vector<OutDataVecCoord *> &dataVecOutPos, const vector<const In1DataVecCoord *> &dataVecIn1Pos, const vector<const In2DataVecCoord *> &dataVecIn2Pos) override; - void - applyJ(const sofa::core::MechanicalParams * /* mparams */, + void applyJ(const sofa::core::MechanicalParams * /* mparams */, const vector<OutDataVecDeriv *> &dataVecOutVel, const vector<const In1DataVecDeriv *> &dataVecIn1Vel, const vector<const In2DataVecDeriv *> &dataVecIn2Vel) override; - // ApplyJT Force - void - applyJT(const sofa::core::MechanicalParams * /* mparams */, + void applyJT(const sofa::core::MechanicalParams * /* mparams */, const vector<In1DataVecDeriv *> &dataVecOut1Force, const vector<In2DataVecDeriv *> &dataVecOut2RootForce, const vector<const OutDataVecDeriv *> &dataVecInForce) override; + // TODO(dmarchal:2024/06/13): Override with an empty function is a rare code pattern + // to make it clear this is the intented and not just an "I'm too lazy to implement it" + // please always have a precise code comment explaning with details why it is empty. void applyDJT(const sofa::core::MechanicalParams * /*mparams*/, sofa::core::MultiVecDerivId /*inForce*/, sofa::core::ConstMultiVecDerivId /*outForce*/) override {} - /// This method must be reimplemented by all mappings if they need to support - /// constraints. - virtual void applyJT( + /// Support for constraints. + void applyJT( const sofa::core::ConstraintParams *cparams, const vector<In1DataMatrixDeriv *> &dataMatOut1Const, const vector<In2DataMatrixDeriv *> &dataMatOut2Const, const vector<const OutDataMatrixDeriv *> &dataMatInConst) override; + /// @} + ///////////////////////////////////////////////////////////////////////////// + + void computeBBox(const sofa::core::ExecParams *params, bool onlyVisible) override; void computeLogarithm(const double &x, const Matrix4 &gX, Matrix4 &log_gX); protected: + ////////////////////////// Inherited attributes //////////////////////////// + /// https://gcc.gnu.org/onlinedocs/gcc/Name-lookup.html + /// Bring inherited attributes and function in the current lookup context. + /// otherwise any access to the base::attribute would require + /// the "this->" approach. + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_section; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_curv_abs_frames; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesTangExpVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesVelocityVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesExponentialSE3Vectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_framesTangExpVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_totalBeamForceVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodesExponentialSE3Vectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::d_debug; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectorsDraw; + using BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta; + ////////////////////////////////////////////////////////////////////////////// + sofa::helper::ColorMap m_colorMap; + sofa::core::State<In1> *m_fromModel1; + sofa::core::State<In2> *m_fromModel2; + sofa::core::State<Out> *m_toModel; + +protected: + DiscreteCosseratMapping(); + ~DiscreteCosseratMapping() override {} }; #if !defined(SOFA_COSSERAT_CPP_DiscreteCosseratMapping) From 293f3d70ec7f960df0ae4d329bedae76f1931b29 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 11:44:38 +0200 Subject: [PATCH 61/71] Removes un-needed includes in BaseCosseratMapping.h --- src/Cosserat/mapping/BaseCosseratMapping.h | 18 ++++-------------- 1 file changed, 4 insertions(+), 14 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index f380eea6..13aa59ad 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -24,26 +24,15 @@ #include <Cosserat/types.h> #include <sofa/core/Multi2Mapping.h> -#include <sofa/core/config.h> -#include <sofa/core/objectmodel/BaseObject.h> -#include <sofa/defaulttype/RigidTypes.h> -#include <sofa/defaulttype/SolidTypes.h> -#include <sofa/type/Vec.h> -//#include <iostream> -#include <Eigen/Dense> -#include <cmath> namespace Cosserat::mapping { -// with a private namespace the used named are not polluating the whole -// sofa::component::mapping ones. +// Use a private namespace so we are not polluating the Cosserat::mapping. namespace { using namespace std; using namespace Eigen; -using sofa::core::objectmodel::BaseContext; -using sofa::core::objectmodel::BaseObject; using sofa::defaulttype::SolidTypes; using sofa::type::Mat6x6; using sofa::type::Mat4x4; @@ -55,8 +44,9 @@ using sofa::type::Vec3; using sofa::type::Vec6; using sofa::type::Mat; -using se3 = sofa::type::Matrix4; -using SE3 = sofa::type::Matrix4; +// TODO(dmarchal: 2024/06/12): please check the comment to confirme this is true +using SE3 = sofa::type::Matrix4; ///< The "coordinate" in SE3 +using se3 = sofa::type::Matrix4; ///< The "speed" of change of SE3. using _se3 = Eigen::Matrix4d; using _SE3 = Eigen::Matrix4d; From 6a6f10d514f9397dadfba3d6f269c8efd852ad56 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 15:17:35 +0200 Subject: [PATCH 62/71] Factorize toModel, fromModel1, fromModel2 in BaseCosseratMapping --- src/Cosserat/mapping/BaseCosseratMapping.h | 8 ++++++-- src/Cosserat/mapping/BaseCosseratMapping.inl | 4 ++++ .../mapping/DiscreteCosseratMapping.cpp | 1 + .../mapping/DiscreteCosseratMapping.h | 9 +++++---- .../mapping/DiscreteCosseratMapping.inl | 19 ++++++++++--------- .../mapping/DiscreteDynamicCosseratMapping.h | 8 +++----- .../DiscreteDynamicCosseratMapping.inl | 12 ++---------- src/Cosserat/types.h | 4 +++- 8 files changed, 34 insertions(+), 31 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 13aa59ad..7224e92d 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -198,6 +198,10 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> using Inherit1::fromModels2; using Inherit1::toModels; + sofa::core::State<In1>* m_fromModel1; + sofa::core::State<In2>* m_fromModel2; + sofa::core::State<Out>* m_toModel; + protected: /// Constructor BaseCosseratMapping(); @@ -210,8 +214,8 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> // TODO(dmarchal: 2024/06/07): // - clarify the difference between computeAdjoing and buildAdjoint ... - // - clarify why we need Transform and Vec6. - void computeAdjoint(const Transform &frame, Mat6x6 &adjoint); + // - clarify why we need Transform and Vec6 and Tangent & Mat6x6 + void computeAdjoint(const Transform &frame, Tangent &adjoint); void computeAdjoint(const Vec6 &frame, Mat6x6 &adjoint); void computeCoAdjoint(const Transform &frame, Mat6x6 &coAdjoint); diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index e3104065..cef60bed 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -69,6 +69,10 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() // to me it should be safe to remove the two line.. and thus the init :) const OutDataVecCoord *xfromData = toModels[0]->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xfrom = xfromData->getValue(); + + m_fromModel1 = fromModels1[0]; + m_fromModel2 = fromModels2[0]; + m_toModel = toModels[0]; } template <class TIn1, class TIn2, class TOut> diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index ef389af3..5b2ef2b2 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -52,6 +52,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_frames = d_curv_abs_frames; const In1VecCoord& inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); //Strains + // Compute the tangent Exponential SE3 vectors this->updateTangExpSE3(inDeform); diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 5cd0398d..8083f6d7 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -180,13 +180,14 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectorsDraw; using BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta; + + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_toModel; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel1; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel2; + ////////////////////////////////////////////////////////////////////////////// sofa::helper::ColorMap m_colorMap; - sofa::core::State<In1> *m_fromModel1; - sofa::core::State<In2> *m_fromModel2; - sofa::core::State<Out> *m_toModel; - protected: DiscreteCosseratMapping(); ~DiscreteCosseratMapping() override {} diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index df957bdf..25cd62e4 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -43,8 +43,7 @@ using sofa::helper::WriteAccessor; using sofa::type::RGBAColor; template <class TIn1, class TIn2, class TOut> -DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() - : m_fromModel1(NULL), m_fromModel2(NULL), m_toModel(NULL), +DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : d_deformationAxis( initData(&d_deformationAxis, (int)1, "deformationAxis", "the axis in which we want to show the deformation.\n")), @@ -74,7 +73,9 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() "by another body.")) {} template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() +{ + if (this->getFromModels1().empty() || this->getFromModels2().empty() || this->getToModels().empty()) { msg_error() << "Error while initializing ; input " @@ -91,12 +92,12 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() { } template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() { - m_fromModel1 = this->getFromModels1()[0]; // Cosserat deformations (torsion, - // bending_y/_z, elongation and - // shear_y/_z), in local frame - m_fromModel2 = this->getFromModels2()[0]; // Cosserat base, in global frame - m_toModel = this->getToModels()[0]; // Cosserat rigid frames, in global frame +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() +{ + + m_fromModel1 = this->getFromModels1()[0]; /// Cosserat deformations (torsion, bending_y/_z, elongation and shear_y/_z), in local frame + m_fromModel2 = this->getFromModels2()[0]; ///< Cosserat base, in global frame + m_toModel = this->getToModels()[0]; ///< Cosserat rigid frames, in global frame // Fill the initial vector void init() override; const OutDataVecCoord *xFromData = diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index ed8d6c14..64b685c9 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -106,11 +106,6 @@ class DiscreteDynamicCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TO typedef typename SolidTypes<Real>::Transform Transform ; -protected: - sofa::core::State<In1>* m_fromModel1; - sofa::core::State<In2>* m_fromModel2; - sofa::core::State<Out>* m_toModel; - protected: /// Constructor DiscreteDynamicCosseratMapping() ; @@ -143,6 +138,9 @@ class DiscreteDynamicCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TO using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform ; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_toModel; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel1; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel2; public: diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index cfff43ac..2478a2a3 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -43,11 +43,7 @@ using sofa::helper::WriteAccessor; template <class TIn1, class TIn2, class TOut> DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::DiscreteDynamicCosseratMapping() - : m_fromModel1(NULL) - , m_fromModel2(NULL) - , m_toModel(NULL) -{ -} +{} // _________________________________________________________________________________________ @@ -77,10 +73,6 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::init() printf("=================================> Init from the DiscretDynamicCosseratMapping component \n"); - m_fromModel1 = this->getFromModels1()[0]; - m_fromModel2 = this->getFromModels2()[0]; - m_toModel = this->getToModels()[0]; - // Fill the initial vector const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xfrom = xfromData->getValue(); @@ -208,7 +200,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( for (size_t i = 1 ; i < curv_abs_input.size(); i++) { Transform t= m_nodesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; Adjoint.clear(); + Tangent Adjoint; Adjoint.clear(); this->computeAdjoint(t,Adjoint); //Add this line because need for the jacobian computation m_nodeAdjointVectors.push_back(Adjoint); diff --git a/src/Cosserat/types.h b/src/Cosserat/types.h index cf5c720f..282c78c5 100644 --- a/src/Cosserat/types.h +++ b/src/Cosserat/types.h @@ -44,10 +44,12 @@ namespace Cosserat typedef typename sofa::defaulttype::SolidTypes<SReal>::Transform Transform; typedef typename sofa::type::vector<SReal> List; - typedef typename sofa::type::Mat<6, 6, SReal> Tangent; typedef typename Eigen::Matrix3d RotMat; typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; + using Tangent = sofa::type::Mat6x6; + //class Tangent : public sofa::type::Mat<6, 6, SReal>{}; + } } From 005994265c2bcb9e9877aab9a5279373fce61661 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 16:05:46 +0200 Subject: [PATCH 63/71] Refactor the init() between BaseCosseratMapping & its child classes (breaking) --- src/Cosserat/mapping/BaseCosseratMapping.h | 3 +- src/Cosserat/mapping/BaseCosseratMapping.inl | 18 +++++++ .../mapping/DiscreteCosseratMapping.h | 3 +- .../mapping/DiscreteCosseratMapping.inl | 38 +++------------ .../mapping/DiscreteDynamicCosseratMapping.h | 9 +--- .../DiscreteDynamicCosseratMapping.inl | 48 +------------------ 6 files changed, 29 insertions(+), 90 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 7224e92d..426d2860 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -140,7 +140,8 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> public: /********************** Inhertited from BaseObject **************/ - void init() override; + void init() final override; + virtual void doBaseCosseratInit() = 0; /************************* BaseCosserat **************************/ // TODO(dmarchal:2024/06/07), so we have "initialize" and "init" diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index cef60bed..50f5affc 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -62,6 +62,24 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() { Inherit1::init(); + if(fromModels1.empty()) + { + msg_error() << "Error while initializing ; input getFromModels1 not found" ; + return; + } + + if(fromModels2.empty()) + { + msg_error() << "Error while initializing ; output getFromModels2 not found" ; + return; + } + + if(toModels.empty()) + { + msg_error() << "Error while initializing ; output Model not found" ; + return; + } + //TODO(dmarchal, 2024/07/12): is the following line really needed ? // it initialize a local variable which initialize another data. // is it to force a xfromData updates through the use of getValue(). In addition diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 8083f6d7..2319255b 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -114,8 +114,7 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { ////////////////////////////////////////////////////////////////////// /// The following methods are inherited from BaseObject /// @{ - void init() override; - void reinit() override; + void doBaseCosseratInit() final override; void draw(const sofa::core::visual::VisualParams *vparams) override; /// @} ////////////////////////////////////////////////////////////////////// diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 25cd62e4..0e2ebee8 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -73,32 +73,8 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : "by another body.")) {} template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::init() +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() { - - if (this->getFromModels1().empty() || this->getFromModels2().empty() || - this->getToModels().empty()) { - msg_error() << "Error while initializing ; input " - "getFromModels1/getFromModels2/output not found"; - return; - } - - reinit(); - // I call Init here since we build the mechanics only in the - Inherit1::init(); - - m_colorMap.setColorScheme("Blue to Red"); - m_colorMap.reinit(); -} - -template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() -{ - - m_fromModel1 = this->getFromModels1()[0]; /// Cosserat deformations (torsion, bending_y/_z, elongation and shear_y/_z), in local frame - m_fromModel2 = this->getFromModels2()[0]; ///< Cosserat base, in global frame - m_toModel = this->getToModels()[0]; ///< Cosserat rigid frames, in global frame - // Fill the initial vector void init() override; const OutDataVecCoord *xFromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); @@ -109,14 +85,12 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::reinit() m_vecTransform.push_back(xFrom[i]); } - if (d_debug.getValue()) { - msg_info("DiscreteCosseratMapping") << " =================" - "============================ "; - msg_info("DiscreteCosseratMapping") - << " m_vecTransform : " << m_vecTransform; - } - this->initialize(); + + m_colorMap.setColorScheme("Blue to Red"); + m_colorMap.reinit(); + + msg_info() << " m_vecTransform : " << m_vecTransform; } template <class TIn1, class TIn2, class TOut> diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index 64b685c9..428a8b3c 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -142,17 +142,10 @@ class DiscreteDynamicCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TO using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel1; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel2; - public: - - /**********************SOFA METHODS**************************/ - void init() override; - virtual void bwdInit() override; // get the points - virtual void reset() override; - virtual void reinit() override; + void doBaseCosseratInit() final override; void draw(const sofa::core::visual::VisualParams* vparams) override; - /**********************MAPPING METHODS**************************/ void apply( const sofa::core::MechanicalParams* /* mparams */, diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index 2478a2a3..918c0328 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -49,68 +49,22 @@ DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::DiscreteDynamicCosseratMapping // _________________________________________________________________________________________ template <class TIn1, class TIn2, class TOut> -void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::init() +void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() { - Inherit1::init(); - - if(this->getFromModels1().empty()) - { - msg_error() << "Error while initializing ; input getFromModels1 not found" ; - return; - } - - if(this->getFromModels2().empty()) - { - msg_error() << "Error while initializing ; output getFromModels2 not found" ; - return; - } - - if(this->getToModels().empty()) - { - msg_error() << "Error while initializing ; output Model not found" ; - return; - } - - printf("=================================> Init from the DiscretDynamicCosseratMapping component \n"); - // Fill the initial vector const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xfrom = xfromData->getValue(); - // WriteAccessor<Data < helper::vector<double>>> curv_abs_output = d_curv_abs_frames; - // curv_abs_output.clear(); m_vecTransform.clear(); for (unsigned int i = 0; i < xfrom.size(); i++) { m_vecTransform.push_back(xfrom[i]); } - //initialize the constant matrix m_matrixBi[0][0] = 1.0; for(size_t i = 0 ; i < 3; i++) m_matrixBi[i][i] = 1.0; this->initialize(); } - -template <class TIn1, class TIn2, class TOut> -void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::bwdInit() -{ - -} - -template <class TIn1, class TIn2, class TOut> -void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::reinit() -{ - -} - -template <class TIn1, class TIn2, class TOut> -void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::reset() -{ - reinit(); -} - - - template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::apply( const sofa::core::MechanicalParams* /* mparams */, From bda1ff11c7c8b10ea823a3070c7b48d84759e533 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 16:37:20 +0200 Subject: [PATCH 64/71] Factorize initialization in BaseCosseratMapping. --- src/Cosserat/mapping/BaseCosseratMapping.inl | 27 ++++++++++--------- .../mapping/DiscreteCosseratMapping.inl | 14 ---------- .../DiscreteDynamicCosseratMapping.inl | 18 +++---------- 3 files changed, 18 insertions(+), 41 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 50f5affc..da5da5c7 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -64,33 +64,36 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() if(fromModels1.empty()) { - msg_error() << "Error while initializing ; input getFromModels1 not found" ; + msg_error() << "input1 not found" ; return; } if(fromModels2.empty()) { - msg_error() << "Error while initializing ; output getFromModels2 not found" ; + msg_error() << "input2 not found" ; return; } if(toModels.empty()) { - msg_error() << "Error while initializing ; output Model not found" ; + msg_error() << "output missing" ; return; } - //TODO(dmarchal, 2024/07/12): is the following line really needed ? - // it initialize a local variable which initialize another data. - // is it to force a xfromData updates through the use of getValue(). In addition - // this is puzzleing as toModel is the destination of the computation of the mapping. - // to me it should be safe to remove the two line.. and thus the init :) - const OutDataVecCoord *xfromData = toModels[0]->read(sofa::core::ConstVecCoordId::position()); - const OutVecCoord xfrom = xfromData->getValue(); - m_fromModel1 = fromModels1[0]; m_fromModel2 = fromModels2[0]; m_toModel = toModels[0]; + + // Fill the initial vector + const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); + const OutVecCoord xfrom = xfromData->getValue(); + + m_vecTransform.clear(); + for (unsigned int i = 0; i < xfrom.size(); i++) { + m_vecTransform.push_back(xfrom[i]); + } + + doBaseCosseratInit(); } template <class TIn1, class TIn2, class TOut> @@ -392,7 +395,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { auto curv_abs_frames = getReadAccessor(d_curv_abs_frames); msg_info() - << " curv_abs_section " << curv_abs_frames.size() << "; curv_abs_frames: " << curv_abs_frames.size(); + << " curv_abs_section " << curv_abs_section.size() << "; curv_abs_frames: " << curv_abs_frames.size(); m_indicesVectors.clear(); m_framesLengthVectors.clear(); diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 0e2ebee8..78b39d99 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -75,22 +75,8 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() { - // Fill the initial vector void init() override; - const OutDataVecCoord *xFromData = - m_toModel->read(sofa::core::ConstVecCoordId::position()); - const OutVecCoord xFrom = xFromData->getValue(); - - m_vecTransform.clear(); // initialise with the rigids frames - for (unsigned int i = 0; i < xFrom.size(); i++) { - m_vecTransform.push_back(xFrom[i]); - } - - this->initialize(); - m_colorMap.setColorScheme("Blue to Red"); m_colorMap.reinit(); - - msg_info() << " m_vecTransform : " << m_vecTransform; } template <class TIn1, class TIn2, class TOut> diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index 918c0328..44b9204a 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -45,26 +45,14 @@ template <class TIn1, class TIn2, class TOut> DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::DiscreteDynamicCosseratMapping() {} - -// _________________________________________________________________________________________ - template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() { - // Fill the initial vector - const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); - const OutVecCoord xfrom = xfromData->getValue(); - - m_vecTransform.clear(); - for (unsigned int i = 0; i < xfrom.size(); i++) { - m_vecTransform.push_back(xfrom[i]); - } - - for(size_t i = 0 ; i < 3; i++) m_matrixBi[i][i] = 1.0; - - this->initialize(); + for(size_t i = 0 ; i < 3; i++) + m_matrixBi[i][i] = 1.0; } + template <class TIn1, class TIn2, class TOut> void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::apply( const sofa::core::MechanicalParams* /* mparams */, From 334cf6b8dea45131d03171e430c1a028fe5765c9 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 17:09:05 +0200 Subject: [PATCH 65/71] FIXUP initialization. --- docs/testScene/tuto_compare_2.py | 8 +- src/Cosserat/mapping/BaseCosseratMapping.inl | 133 +++++++++++------- .../mapping/DiscreteCosseratMapping.inl | 20 ++- 3 files changed, 98 insertions(+), 63 deletions(-) diff --git a/docs/testScene/tuto_compare_2.py b/docs/testScene/tuto_compare_2.py index 6fdbee4b..faf12613 100644 --- a/docs/testScene/tuto_compare_2.py +++ b/docs/testScene/tuto_compare_2.py @@ -49,11 +49,13 @@ def _add_cosserat_frame(p_node, _bending_node, framesF, _section_curv_abs, _fram cosserat_in_Sofa_frame_node.addObject('UniformMass', totalMass=_beam_mass) - cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', curv_abs_input=_section_curv_abs, - curv_abs_output=_frame_curv_abs, name='cosseratMapping', + cosserat_in_Sofa_frame_node.addObject('DiscreteCosseratMapping', + curv_abs_input=_section_curv_abs, + curv_abs_output=_frame_curv_abs, + name='cosseratMapping', input1=_bending_node.cosserat_state.getLinkPath(), input2=p_node.cosserat_base_mo.getLinkPath(), - output=frames_mo.getLinkPath(), debug=0, radius=_radius) + output=frames_mo.getLinkPath(), printLog=True, radius=_radius) return cosserat_in_Sofa_frame_node diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index da5da5c7..0629087e 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -60,7 +60,9 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::init() { - Inherit1::init(); + m_fromModel1 = nullptr; + m_fromModel2 = nullptr; + m_toModel = nullptr; if(fromModels1.empty()) { @@ -84,6 +86,22 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() m_fromModel2 = fromModels2[0]; m_toModel = toModels[0]; + if(m_fromModel1==nullptr) + { + msg_error() << "input1 not found" ; + return; + } + if(m_fromModel2==nullptr) + { + msg_error() << "input1 not found" ; + return; + } + if(m_toModel==nullptr) + { + msg_error() << "input1 not found" ; + return; + } + // Fill the initial vector const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xfrom = xfromData->getValue(); @@ -93,9 +111,65 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() m_vecTransform.push_back(xfrom[i]); } + initialize(); doBaseCosseratInit(); + Inherit1::init(); +} + +//___________________________________________________________________________ +template <class TIn1, class TIn2, class TOut> +void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { + // For each frame in the global frame, find the segment of the beam to which + // it is attached. Here we only use the information from the curvilinear + // abscissa of each frame. + auto curv_abs_section = getReadAccessor(d_curv_abs_section); + auto curv_abs_frames = getReadAccessor(d_curv_abs_frames); + + msg_info() + << " curv_abs_section " << curv_abs_section.size() << "; curv_abs_frames: " << curv_abs_frames.size(); + + m_indicesVectors.clear(); + m_framesLengthVectors.clear(); + m_BeamLengthVectors.clear(); + m_indicesVectorsDraw.clear(); + + size_t sz = curv_abs_frames.size(); + size_t input_index = 1; + for (size_t i = 0; i < sz; ++i) + { + if (curv_abs_section[input_index] > curv_abs_frames[i]) + { + m_indicesVectors.emplace_back(input_index); + m_indicesVectorsDraw.emplace_back(input_index); // maybe I shouldn't do this here !!! + } else if (curv_abs_section[input_index] == curv_abs_frames[i]) + { + m_indicesVectors.emplace_back(input_index); + input_index++; + m_indicesVectorsDraw.emplace_back(input_index); + } else { + input_index++; + m_indicesVectors.emplace_back(input_index); + m_indicesVectorsDraw.emplace_back(input_index); + } + + // Fill the vector m_framesLengthVectors with the distance + // between frame(output) and the closest beam node toward the base + m_framesLengthVectors.emplace_back( + curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); + } + + for (size_t j = 0; j < sz - 1; ++j) + { + m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); + } + + msg_info() + << "m_indicesVectors : " << m_indicesVectors << msgendl + << "m_framesLengthVectors : " << msgendl + << "m_BeamLengthVectors : " << msgendl; } + template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { @@ -137,6 +211,7 @@ template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( const In1VecCoord &inDeform) { + msg_info() << " ########## updateMap 2########"; auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); m_framesExponentialSE3Vectors.clear(); @@ -145,10 +220,14 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( const unsigned int sz = curv_abs_frames.size(); + msg_info() << " ########## updateMap 3 , "<< sz << " et " << inDeform.size() << "########"; + // Compute exponential at each frame point for (size_t i = 0; i < sz; ++i) { Transform g_X_frame_i; + msg_info() << " ########## updateMap 4, "<< i << "-> " << "########"; + msg_info() << " ########## updateMap 5, "<< i << "-> " << m_indicesVectors[i] << "########"; const Coord1 strain_n = inDeform[m_indicesVectors[i] - 1]; // Cosserat reduce coordinates (strain) @@ -385,58 +464,6 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, return adjointMatrix * (baseEta + tangentMatrix * Xi_dot); } -//___________________________________________________________________________ -template <class TIn1, class TIn2, class TOut> -void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { - // For each frame in the global frame, find the segment of the beam to which - // it is attached. Here we only use the information from the curvilinear - // abscissa of each frame. - auto curv_abs_section = getReadAccessor(d_curv_abs_section); - auto curv_abs_frames = getReadAccessor(d_curv_abs_frames); - - msg_info() - << " curv_abs_section " << curv_abs_section.size() << "; curv_abs_frames: " << curv_abs_frames.size(); - - m_indicesVectors.clear(); - m_framesLengthVectors.clear(); - m_BeamLengthVectors.clear(); - m_indicesVectorsDraw.clear(); - - size_t sz = curv_abs_frames.size(); - size_t input_index = 1; - for (size_t i = 0; i < sz; ++i) - { - if (curv_abs_section[input_index] > curv_abs_frames[i]) - { - m_indicesVectors.emplace_back(input_index); - m_indicesVectorsDraw.emplace_back(input_index); // maybe I shouldn't do this here !!! - } else if (curv_abs_section[input_index] == curv_abs_frames[i]) - { - m_indicesVectors.emplace_back(input_index); - input_index++; - m_indicesVectorsDraw.emplace_back(input_index); - } else { - input_index++; - m_indicesVectors.emplace_back(input_index); - m_indicesVectorsDraw.emplace_back(input_index); - } - - // Fill the vector m_framesLengthVectors with the distance - // between frame(output) and the closest beam node toward the base - m_framesLengthVectors.emplace_back( - curv_abs_frames[i] - curv_abs_section[m_indicesVectors.back() - 1]); - } - - for (size_t j = 0; j < sz - 1; ++j) - { - m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); - } - - msg_info() - << "m_indicesVectors : " << m_indicesVectors << msgendl - << "m_framesLengthVectors : " << msgendl - << "m_BeamLengthVectors : " << msgendl; -} template <class TIn1, class TIn2, class TOut> double BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta(const double &x, diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 78b39d99..cb535ab3 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -85,16 +85,19 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( const vector<OutDataVecCoord *> &dataVecOutPos, const vector<const In1DataVecCoord *> &dataVecIn1Pos, const vector<const In2DataVecCoord *> &dataVecIn2Pos) { + if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) return; - if (d_debug.getValue()) - std::cout << " ########## Apply Function ########" << std::endl; + msg_info() << " ########## Apply Function ########"; + /// Do Apply // We need only one input In model and input Root model (if present) const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); + msg_info() << " ########## Apply Function 2########"; + const auto sz = d_curv_abs_frames.getValue().size(); OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states out.resize(sz); @@ -105,6 +108,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( // Which are the homogeneous matrices of the frames and the nodes in local // coordinate. this->updateExponentialSE3(in1); + /* Apply the transformation to go from cossserat to SOFA frame*/ Transform frame0 = Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); @@ -116,19 +120,21 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( } frame *= m_framesExponentialSE3Vectors[i]; // frame*gX(x) - if (d_debug.getValue()) - std::cout << "Frame : " << i << " = " << frame << std::endl; + msg_info() << "Frame : " << i << " = " << frame; Vec3 v = frame.getOrigin(); Quat q = frame.getOrientation(); out[i] = OutCoord(v, q); } - // - if (d_debug.getValue()) { + + if (this->f_printLog.getValue()) + { + std::stringstream tmp; for (unsigned int i = 0; i < out.size() - 1; i++) { Vec3 diff = out[i + 1].getCenter() - out[i].getCenter(); - std::cout << "dist " << i << " : " << diff.norm() << std::endl; + tmp << "dist " << i << " : " << diff.norm() << msgendl; } + msg_info() << tmp.str(); } m_index_input = 0; dataVecOutPos[0]->endEdit(); From aa20251363a2f26a7670b5f9808e9086dc29b1ef Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 21:08:20 +0200 Subject: [PATCH 66/71] Factorizing in init funciton. --- src/Cosserat/mapping/BaseCosseratMapping.inl | 16 ------------ .../mapping/DiscreteCosseratMapping.inl | 25 ------------------- 2 files changed, 41 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 0629087e..48ebac5a 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -86,22 +86,6 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() m_fromModel2 = fromModels2[0]; m_toModel = toModels[0]; - if(m_fromModel1==nullptr) - { - msg_error() << "input1 not found" ; - return; - } - if(m_fromModel2==nullptr) - { - msg_error() << "input1 not found" ; - return; - } - if(m_toModel==nullptr) - { - msg_error() << "input1 not found" ; - return; - } - // Fill the initial vector const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xfrom = xfromData->getValue(); diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index cb535ab3..ad6d7e70 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -89,15 +89,11 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) return; - msg_info() << " ########## Apply Function ########"; - /// Do Apply // We need only one input In model and input Root model (if present) const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); - msg_info() << " ########## Apply Function 2########"; - const auto sz = d_curv_abs_frames.getValue().size(); OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states out.resize(sz); @@ -174,27 +170,6 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( } } -// template<class In1VecCoord, class Mat6x6> -// void computeViolation(In1VecCoord& inDeform, const helper::vector<double> -// m_framesLengthVectors, const -// size_t sz, std::function<double(int i, int j)> f) -//{ -// for (std::size_t i = 0; i < sz; i++) { -// Mat6x6 temp ; - -// type::Vec3 k = inDeform[m_indicesVectors[i]-1]; -// double x = m_framesLengthVectors[i]; -// compute_Tang_Exp(x,k,temp) ; -// m_framesTangExpVectors.push_back(temp); - -//// if (d_debug.getValue()){ -//// printf("__________________________________________\n"); -//// std::cout << "x :"<< x << "; k :"<< k << std::endl; -//// std::cout<< "m_framesTangExpVectors :"<< -///m_framesTangExpVectors[i] << std::endl; / } -// } -//} - template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( const sofa::core::MechanicalParams * /* mparams */, From 60446a581f6caa522fac41e4cdb32ccd2e35176e Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 21:26:17 +0200 Subject: [PATCH 67/71] Types declaration in BaseCosseratMapping removed. --- src/Cosserat/mapping/BaseCosseratMapping.cpp | 2 +- src/Cosserat/mapping/BaseCosseratMapping.h | 35 ++++++---------- src/Cosserat/mapping/BaseCosseratMapping.inl | 44 ++++++++------------ 3 files changed, 31 insertions(+), 50 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp index dc813123..ed591d18 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -83,7 +83,7 @@ void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentia g_X_n.getsub(0, 0, M); // get the rotation matrix // convert the rotation 3x3 matrix to a quaternion - sofa::type::Quat<Real> R; + sofa::type::Quat<SReal> R; R.fromMatrix(M); Trans = Transform(Vec3(g_X_n(0, 3), g_X_n(1, 3), g_X_n(2, 3)), R); } diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index 426d2860..ecd478e1 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -79,29 +79,18 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> // typedefs are public typedef typename In1::Coord Coord1; typedef typename In1::Deriv Deriv1; - typedef typename In1::VecCoord In1VecCoord; - typedef typename In1::VecDeriv In1VecDeriv; - [[maybe_unused]] typedef typename In1::MatrixDeriv In1MatrixDeriv; - typedef sofa::Data<In1VecCoord> In1DataVecCoord; - typedef sofa::Data<In1VecDeriv> In1DataVecDeriv; + //typedef typename In1::VecCoord In1VecCoord; + //typedef typename In1::VecDeriv In1VecDeriv; - typedef typename In2::Coord::value_type Real; typedef typename In2::Coord Coord2; typedef typename In2::Deriv Deriv2; - typedef typename In2::VecCoord In2VecCoord; - typedef typename In2::VecDeriv In2VecDeriv; - [[maybe_unused]] typedef typename In2::MatrixDeriv In2MatrixDeriv; - typedef sofa::Data<In2VecCoord> In2DataVecCoord; - typedef sofa::Data<In2VecDeriv> In2DataVecDeriv; + //typedef typename In2::VecCoord In2VecCoord; + //typedef typename In2::VecDeriv In2VecDeriv; - typedef typename Out::VecCoord OutVecCoord; typedef typename Out::Coord OutCoord; typedef typename Out::Deriv OutDeriv; - typedef typename Out::VecDeriv OutVecDeriv; - typedef typename Out::MatrixDeriv OutMatrixDeriv; - typedef sofa::Data<OutVecCoord> OutDataVecCoord; - typedef sofa::Data<OutVecDeriv> OutDataVecDeriv; - typedef sofa::Data<OutMatrixDeriv> OutDataMatrixDeriv; + //typedef typename Out::VecCoord OutVecCoord; + //typedef typename Out::VecDeriv OutVecDeriv; public: // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this @@ -109,7 +98,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> /*===========COSSERAT VECTORS ======================*/ unsigned int m_index_input; - OutVecCoord m_vecTransform; + vector<OutCoord> m_vecTransform; vector<Transform> m_framesExponentialSE3Vectors; vector<Transform> m_nodesExponentialSE3Vectors; @@ -119,7 +108,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> vector<unsigned int> m_indicesVectors; vector<unsigned int> m_indicesVectorsDraw; - vector<double> m_BeamLengthVectors; + vector<double> m_beamLengthVectors; vector<double> m_framesLengthVectors; vector<Vec6> m_nodesVelocityVectors; @@ -149,7 +138,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> // roles is unclear and generates ambiguities // TODO @yadagolo: Yes, because the function is used by callback, when we // do dynamic meshing. - void initialize(); + void initializeFrames(); double computeTheta(const double &x, const Mat4x4 &gX); void printMatrix(const Mat6x6 R); @@ -221,12 +210,12 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> void computeCoAdjoint(const Transform &frame, Mat6x6 &coAdjoint); - void updateExponentialSE3(const In1VecCoord &inDeform); - void updateTangExpSE3(const In1VecCoord &inDeform); + void updateExponentialSE3(const vector<Coord1> &inDeform); + void updateTangExpSE3(const vector<Coord1> &inDeform); void computeTangExp(double &x, const Coord1 &k, Mat6x6 &TgX); [[maybe_unused]] Vec6 - computeETA(const Vec6 &baseEta, const In1VecDeriv &k_dot, double abs_input); + computeETA(const Vec6 &baseEta, const vector<Deriv1> &k_dot, double abs_input); Mat4x4 computeLogarithm(const double &x, const Mat4x4 &gX); }; diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 48ebac5a..48fd82cb 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -55,7 +55,6 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() d_debug(initData(&d_debug, false, "debug", "printf for the debug")), m_index_input(0) {} -// _________________________________________________________________________________________ template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::init() @@ -87,22 +86,23 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() m_toModel = toModels[0]; // Fill the initial vector - const OutDataVecCoord* xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); - const OutVecCoord xfrom = xfromData->getValue(); + auto xfromData = m_toModel->read(sofa::core::ConstVecCoordId::position()); + const vector<OutCoord> xfrom = xfromData->getValue(); m_vecTransform.clear(); for (unsigned int i = 0; i < xfrom.size(); i++) { m_vecTransform.push_back(xfrom[i]); } - initialize(); + initializeFrames(); doBaseCosseratInit(); Inherit1::init(); } //___________________________________________________________________________ template <class TIn1, class TIn2, class TOut> -void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { +void BaseCosseratMapping<TIn1, TIn2, TOut>::initializeFrames() +{ // For each frame in the global frame, find the segment of the beam to which // it is attached. Here we only use the information from the curvilinear // abscissa of each frame. @@ -114,7 +114,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { m_indicesVectors.clear(); m_framesLengthVectors.clear(); - m_BeamLengthVectors.clear(); + m_beamLengthVectors.clear(); m_indicesVectorsDraw.clear(); size_t sz = curv_abs_frames.size(); @@ -144,7 +144,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initialize() { for (size_t j = 0; j < sz - 1; ++j) { - m_BeamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); + m_beamLengthVectors.emplace_back(curv_abs_section[j + 1] - curv_abs_section[j]); } msg_info() @@ -185,7 +185,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( _g_X.getsub(0, 0, M); // get the rotation matrix // convert the rotation 3x3 matrix to a quaternion - Quat<Real> R; + Quat<SReal> R; R.fromMatrix(M); g_X_n = Transform(Vec3(_g_X(0, 3), _g_X(1, 3), _g_X(2, 3)), R); } @@ -193,10 +193,9 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( // Fill exponential vectors template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( - const In1VecCoord &inDeform) + const vector<Coord1> &inDeform) { - msg_info() << " ########## updateMap 2########"; - auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); + auto curv_abs_frames = getReadAccessor(d_curv_abs_frames); m_framesExponentialSE3Vectors.clear(); m_nodesExponentialSE3Vectors.clear(); @@ -204,14 +203,10 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( const unsigned int sz = curv_abs_frames.size(); - msg_info() << " ########## updateMap 3 , "<< sz << " et " << inDeform.size() << "########"; - // Compute exponential at each frame point for (size_t i = 0; i < sz; ++i) { Transform g_X_frame_i; - msg_info() << " ########## updateMap 4, "<< i << "-> " << "########"; - msg_info() << " ########## updateMap 5, "<< i << "-> " << m_indicesVectors[i] << "########"; const Coord1 strain_n = inDeform[m_indicesVectors[i] - 1]; // Cosserat reduce coordinates (strain) @@ -235,7 +230,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( for (unsigned int j = 0; j < inDeform.size(); ++j) { Coord1 strain_n = inDeform[j]; - const SReal curv_abs_x = m_BeamLengthVectors[j]; + const SReal curv_abs_x = m_beamLengthVectors[j]; Transform g_X_node_j; computeExponentialSE3(curv_abs_x, strain_n, g_X_node_j); @@ -315,7 +310,7 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( - const In1VecCoord &inDeform) { + const vector<Coord1> &inDeform) { // Curv abscissa of nodes and frames auto curv_abs_section = getReadAccessor(d_curv_abs_section); @@ -348,7 +343,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( for (size_t j = 1; j < curv_abs_section.size(); j++) { Coord1 strain_node_i = inDeform[j - 1]; - double x = m_BeamLengthVectors[j - 1]; + double x = m_beamLengthVectors[j - 1]; Tangent temp; temp.clear(); computeTangExp(x, strain_node_i, temp); @@ -409,12 +404,12 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, template <class TIn1, class TIn2, class TOut> [[maybe_unused]] Vec6 BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, - const In1VecDeriv &k_dot, + const vector<Deriv1> &k_dot, const double abs_input) { // Get the positions from model 0. This function returns the position wrapped in a Data<> - auto d_x1 = fromModels1[0]->read(sofa::core::ConstVecCoordId::position()); + auto d_x1 = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); // To access the actual content (in this case position) from a data, we have to use // a read accessor that insures the data is updated according to DDGNode state @@ -480,7 +475,7 @@ Mat3x3 BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform & // TODO(dmarchal: 2024/06/07) The following code should probably become // utility function building a 3x3 matix from a quaternion should probably // does not need this amount of code. - Real R[4][4]; + SReal R[4][4]; q.buildRotationMatrix(R); Mat3x3 mat; for (unsigned int k = 0; k < 3; k++) @@ -497,7 +492,7 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildProjector(const Transform &T) // TODO(dmarchal: 2024/06/07) The following code should probably become // utility function building a 3x3 matix from a quaternion should probably // does not need this amount of code. - Real R[4][4]; + SReal R[4][4]; (T.getOrientation()).buildRotationMatrix(R); for (unsigned int i = 0; i < 3; i++) { for (unsigned int j = 0; j < 3; j++) { @@ -526,7 +521,7 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) - } template <class TIn1, class TIn2, class TOut> -auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const sofa::type::Vec3 &u) +auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const Vec3 &u) -> Mat3x3 { sofa::type::Matrix3 tild; tild[0][1] = -u[2]; @@ -628,7 +623,4 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::piecewiseLogmap(const _SE3 &g_x) -> return xci; } - - - } // namespace cosserat::mapping From 40279f68e77eca9d8fa1134e423b3feaf949cc77 Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Thu, 13 Jun 2024 21:46:43 +0200 Subject: [PATCH 68/71] Modernize types declaration in DiscreetCosseratMapping Among other things: - instead of re-defining a new type in each class, re-using the one defined in its parent. - remove useless headers - remove type declaration that does not seems to be needed. --- src/Cosserat/mapping/BaseCosseratMapping.h | 6 - src/Cosserat/mapping/DifferenceMultiMapping.h | 5 - .../mapping/DiscreteCosseratMapping.h | 131 ++++++++---------- .../mapping/DiscreteCosseratMapping.inl | 34 ++--- 4 files changed, 74 insertions(+), 102 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index ecd478e1..baa2e7fc 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -79,18 +79,12 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> // typedefs are public typedef typename In1::Coord Coord1; typedef typename In1::Deriv Deriv1; - //typedef typename In1::VecCoord In1VecCoord; - //typedef typename In1::VecDeriv In1VecDeriv; typedef typename In2::Coord Coord2; typedef typename In2::Deriv Deriv2; - //typedef typename In2::VecCoord In2VecCoord; - //typedef typename In2::VecDeriv In2VecDeriv; typedef typename Out::Coord OutCoord; typedef typename Out::Deriv OutDeriv; - //typedef typename Out::VecCoord OutVecCoord; - //typedef typename Out::VecDeriv OutVecDeriv; public: // TODO(dmarchal: 2024/06/07): There is a lot of public attributes is this diff --git a/src/Cosserat/mapping/DifferenceMultiMapping.h b/src/Cosserat/mapping/DifferenceMultiMapping.h index f4567d0c..c9ff7e37 100644 --- a/src/Cosserat/mapping/DifferenceMultiMapping.h +++ b/src/Cosserat/mapping/DifferenceMultiMapping.h @@ -45,12 +45,7 @@ using Cosserat::mapping::BaseCosseratMapping; /*! * \class DifferenceMultiMapping - * @brief Computes and map the length of the beams - * - * This is a component: - * https://www.sofa-framework.org/community/doc/programming-with-sofa/create-your-component/ */ - template <class TIn1, class TIn2, class TOut> class DifferenceMultiMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> { diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 2319255b..4b82ffe2 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -22,29 +22,24 @@ #pragma once #include <Cosserat/initCosserat.h> -#include <Cosserat/forcefield/BeamHookeLawForceField.h> #include <Cosserat/mapping/BaseCosseratMapping.h> - -#include <sofa/core/BaseMapping.h> -#include <sofa/core/Multi2Mapping.h> -#include <sofa/core/config.h> -#include <sofa/defaulttype/RigidTypes.h> -#include <sofa/defaulttype/SolidTypes.h> #include <sofa/helper/ColorMap.h> -namespace Cosserat::mapping { -using sofa::component::forcefield::BeamHookeLawForceField; -using sofa::core::objectmodel::BaseContext; -using sofa::defaulttype::SolidTypes; -using sofa::type::Matrix3; -using sofa::type::Matrix4; +namespace Cosserat::mapping +{ +namespace +{ +using Mat3x6 = sofa::type::Mat<3, 6, SReal>; +using Mat6x3 = sofa::type::Mat<6, 3, SReal>; +using sofa::type::Mat4x4; +using sofa::type::Mat6x6; using sofa::type::Vec3; using sofa::type::Vec6; using sofa::type::Quat; -using std::get; using sofa::Data; +} - +// TODO(dmarchal: 2024/10/07) Is the description valid ? I don't think so. /*! * \class DiscreteCosseratMapping * @brief Computes and map the length of the beams @@ -59,53 +54,41 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { /// Input Model Type typedef TIn1 In1; typedef TIn2 In2; - - /// Output Model Type typedef TOut Out; - typedef typename In2::Coord::value_type Real1; - typedef typename In1::Coord Coord1; - typedef typename In1::Deriv Deriv1; - typedef typename In1::VecCoord In1VecCoord; - typedef typename In1::VecDeriv In1VecDeriv; - typedef typename In1::MatrixDeriv In1MatrixDeriv; - typedef Data<In1VecCoord> In1DataVecCoord; - typedef Data<In1VecDeriv> In1DataVecDeriv; - typedef Data<In1MatrixDeriv> In1DataMatrixDeriv; - - typedef typename In2::Coord::value_type Real2; - typedef typename In2::Coord Coord2; - typedef typename In2::Deriv Deriv2; - typedef typename In2::VecCoord In2VecCoord; - typedef typename In2::VecDeriv In2VecDeriv; - typedef typename In2::MatrixDeriv In2MatrixDeriv; - typedef Data<In2VecCoord> In2DataVecCoord; - typedef Data<In2VecDeriv> In2DataVecDeriv; - typedef Data<In2MatrixDeriv> In2DataMatrixDeriv; - typedef sofa::type::Mat<6, 6, Real2> Mat6x6; - typedef sofa::type::Mat<3, 6, Real2> Mat3x6; - typedef sofa::type::Mat<6, 3, Real2> Mat6x3; - typedef sofa::type::Mat<4, 4, Real2> Mat4x4; - - typedef typename Out::VecCoord OutVecCoord; - typedef typename Out::Coord OutCoord; - typedef typename Out::Deriv OutDeriv; - typedef typename Out::VecDeriv OutVecDeriv; - typedef typename Out::MatrixDeriv OutMatrixDeriv; - typedef Data<OutVecCoord> OutDataVecCoord; - typedef Data<OutVecDeriv> OutDataVecDeriv; - typedef Data<OutMatrixDeriv> OutDataMatrixDeriv; - typedef typename SolidTypes<Real2>::Transform Transform; + + using typename Inherit1::In1VecCoord; + using typename Inherit1::In1VecDeriv; + using typename Inherit1::In1MatrixDeriv; + using typename Inherit1::In1DataVecCoord; + using typename Inherit1::In1DataVecDeriv; + using typename Inherit1::In1DataMatrixDeriv; + + using typename Inherit1::In2VecCoord; + using typename Inherit1::In2VecDeriv; + using typename Inherit1::In2MatrixDeriv; + using typename Inherit1::In2DataVecCoord; + using typename Inherit1::In2DataVecDeriv; + using typename Inherit1::In2DataMatrixDeriv; + + using typename Inherit1::OutCoord; + using typename Inherit1::OutDeriv; + using typename Inherit1::OutVecCoord; + using typename Inherit1::OutVecDeriv; + using typename Inherit1::OutMatrixDeriv; + using typename Inherit1::OutDataVecCoord; + using typename Inherit1::OutDataVecDeriv; + using typename Inherit1::OutDataMatrixDeriv; ////////////////////////////////////////////////////////////////////// /// @name Data Fields /// @{ - Data<int> d_deformationAxis; - Data<Real2> d_max; - Data<Real2> d_min; - Data<Real1> d_radius; - Data<bool> d_drawMapBeam; + Data<int> d_deformationAxis; + Data<SReal> d_max; + Data<SReal> d_min; + Data<SReal> d_radius; + Data<bool> d_drawMapBeam; Data<sofa::type::RGBAColor> d_color; - Data<vector<int>> d_index; + Data<vector<int>> d_index; Data<unsigned int> d_baseIndex; /// @} ////////////////////////////////////////////////////////////////////// @@ -124,19 +107,19 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { /// The following method are inherited from MultiMapping /// @{ void apply(const sofa::core::MechanicalParams * /* mparams */, - const vector<OutDataVecCoord *> &dataVecOutPos, - const vector<const In1DataVecCoord *> &dataVecIn1Pos, - const vector<const In2DataVecCoord *> &dataVecIn2Pos) override; + const vector<OutDataVecCoord *> &dataVecOutPos, + const vector<const In1DataVecCoord *> &dataVecIn1Pos, + const vector<const In2DataVecCoord *> &dataVecIn2Pos) override; void applyJ(const sofa::core::MechanicalParams * /* mparams */, - const vector<OutDataVecDeriv *> &dataVecOutVel, - const vector<const In1DataVecDeriv *> &dataVecIn1Vel, - const vector<const In2DataVecDeriv *> &dataVecIn2Vel) override; + const vector<OutDataVecDeriv *> &dataVecOutVel, + const vector<const In1DataVecDeriv *> &dataVecIn1Vel, + const vector<const In2DataVecDeriv *> &dataVecIn2Vel) override; void applyJT(const sofa::core::MechanicalParams * /* mparams */, - const vector<In1DataVecDeriv *> &dataVecOut1Force, - const vector<In2DataVecDeriv *> &dataVecOut2RootForce, - const vector<const OutDataVecDeriv *> &dataVecInForce) override; + const vector<In1DataVecDeriv *> &dataVecOut1Force, + const vector<In2DataVecDeriv *> &dataVecOut2RootForce, + const vector<const OutDataVecDeriv *> &dataVecInForce) override; // TODO(dmarchal:2024/06/13): Override with an empty function is a rare code pattern // to make it clear this is the intented and not just an "I'm too lazy to implement it" @@ -147,16 +130,16 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { /// Support for constraints. void applyJT( - const sofa::core::ConstraintParams *cparams, - const vector<In1DataMatrixDeriv *> &dataMatOut1Const, - const vector<In2DataMatrixDeriv *> &dataMatOut2Const, - const vector<const OutDataMatrixDeriv *> &dataMatInConst) override; + const sofa::core::ConstraintParams *cparams, + const vector<In1DataMatrixDeriv *> &dataMatOut1Const, + const vector<In2DataMatrixDeriv *> &dataMatOut2Const, + const vector<const OutDataMatrixDeriv *> &dataMatInConst) override; /// @} ///////////////////////////////////////////////////////////////////////////// void computeBBox(const sofa::core::ExecParams *params, bool onlyVisible) override; - void computeLogarithm(const double &x, const Matrix4 &gX, Matrix4 &log_gX); + void computeLogarithm(const double &x, const Mat4x4 &gX, Mat4x4 &log_gX); protected: ////////////////////////// Inherited attributes //////////////////////////// @@ -194,11 +177,11 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { #if !defined(SOFA_COSSERAT_CPP_DiscreteCosseratMapping) extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< - sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, - sofa::defaulttype::Rigid3Types>; + sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; extern template class SOFA_COSSERAT_API DiscreteCosseratMapping< - sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, - sofa::defaulttype::Rigid3Types>; + sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, + sofa::defaulttype::Rigid3Types>; #endif } // namespace Cosserat::mapping diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index ad6d7e70..0beadc52 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -47,12 +47,12 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : d_deformationAxis( initData(&d_deformationAxis, (int)1, "deformationAxis", "the axis in which we want to show the deformation.\n")), - d_max(initData(&d_max, (Real2)1.0e-2, "max", + d_max(initData(&d_max, (SReal)1.0e-2, "max", "the maximum of the deformation.\n")), - d_min(initData(&d_min, (Real2)0.0, "min", + d_min(initData(&d_min, (SReal)0.0, "min", "the minimum of the deformation.\n")), d_radius( - initData(&d_radius, (Real2)0.05, "radius", + initData(&d_radius, (SReal)0.05, "radius", "the axis in which we want to show the deformation.\n")), d_drawMapBeam( initData(&d_drawMapBeam, true, "nonColored", @@ -138,11 +138,11 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( - const double &x, const Matrix4 &gX, Matrix4 &log_gX) { + const double &x, const Mat4x4 &gX, Mat4x4 &log_gX) { // Compute theta before everything double theta = computeTheta(x, gX); - Matrix4 I4; + Mat4x4 I4; I4.clear(); I4.identity(); log_gX.clear(); @@ -564,17 +564,17 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeBBox( - const sofa::core::ExecParams *, bool) { - // const VecCoord& x = getVertices(); //m_vertices.getValue(); + const sofa::core::ExecParams *, bool) +{ const OutVecCoord &x = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - SReal minBBox[3] = {std::numeric_limits<Real1>::max(), - std::numeric_limits<Real1>::max(), - std::numeric_limits<Real1>::max()}; - SReal maxBBox[3] = {-std::numeric_limits<Real1>::max(), - -std::numeric_limits<Real1>::max(), - -std::numeric_limits<Real1>::max()}; + SReal minBBox[3] = {std::numeric_limits<SReal>::max(), + std::numeric_limits<SReal>::max(), + std::numeric_limits<SReal>::max()}; + SReal maxBBox[3] = {-std::numeric_limits<SReal>::max(), + -std::numeric_limits<SReal>::max(), + -std::numeric_limits<SReal>::max()}; for (std::size_t i = 0; i < x.size(); i++) { const OutCoord &p = x[i]; for (int c = 0; c < 3; c++) { @@ -602,7 +602,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( m_toModel->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xData = xfromData->getValue(); vector<Vec3> positions; - vector<sofa::type::Quat<Real2>> Orientation; + vector<sofa::type::Quat<SReal>> Orientation; positions.clear(); Orientation.clear(); unsigned int sz = xData.size(); @@ -623,9 +623,9 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( d_radius.getValue(), drawColor); // Define color map - Real2 min = d_min.getValue(); - Real2 max = d_max.getValue(); - sofa::helper::ColorMap::evaluator<Real2> _eval = m_colorMap.getEvaluator(min, max); + SReal min = d_min.getValue(); + SReal max = d_max.getValue(); + sofa::helper::ColorMap::evaluator<SReal> _eval = m_colorMap.getEvaluator(min, max); glLineWidth(d_radius.getValue()); glBegin(GL_LINES); From b63fb6d9f5745f006af7e457cc45748f8ea733fa Mon Sep 17 00:00:00 2001 From: Damien Marchal <damien.marchal@univ-lille1.fr> Date: Tue, 18 Jun 2024 10:17:02 +0200 Subject: [PATCH 69/71] Refactor computeAdjoint. --- src/Cosserat/mapping/BaseCosseratMapping.cpp | 111 --------- src/Cosserat/mapping/BaseCosseratMapping.h | 13 +- src/Cosserat/mapping/BaseCosseratMapping.inl | 131 ++++++----- .../mapping/DiscreteCosseratMapping.cpp | 150 ++++++------- .../mapping/DiscreteCosseratMapping.h | 2 +- .../mapping/DiscreteCosseratMapping.inl | 211 ++++++++++-------- .../mapping/DiscreteDynamicCosseratMapping.h | 2 +- .../DiscreteDynamicCosseratMapping.inl | 29 +-- src/Cosserat/types.h | 8 +- 9 files changed, 282 insertions(+), 375 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.cpp b/src/Cosserat/mapping/BaseCosseratMapping.cpp index ed591d18..649828e7 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.cpp +++ b/src/Cosserat/mapping/BaseCosseratMapping.cpp @@ -28,117 +28,6 @@ namespace Cosserat::mapping { -using namespace sofa::defaulttype; - -template <> -auto BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::buildXiHat(const Coord1 &strain_i) -> se3 -{ - se3 Xi; - - Xi[0][1] = -strain_i(2); - Xi[0][2] = strain_i[1]; - Xi[1][2] = -strain_i[0]; - - Xi[1][0] = -Xi(0, 1); - Xi[2][0] = -Xi(0, 2); - Xi[2][1] = -Xi(1, 2); - - Xi[0][3] = 1.0; - - for (unsigned int i = 0; i < 3; i++) - Xi[i][3] += strain_i(i + 3); - - return Xi; -} - -template <> -void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeExponentialSE3( - const double &curv_abs_x_n, const Coord1 &strain_n, Transform &Trans) { - Mat4x4 I4; - I4.identity(); - - // Get the angular part of the - Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); - SReal theta = k.norm(); // - - SE3 g_X_n; - se3 Xi_hat_n = buildXiHat(strain_n); - - msg_info() << "matrix Xi : " << Xi_hat_n; - - if (theta <= std::numeric_limits<double>::epsilon()) { - g_X_n = I4 + curv_abs_x_n * Xi_hat_n; - } else { - double scalar1 = - (1.0 - std::cos(curv_abs_x_n * theta)) / std::pow(theta, 2); - double scalar2 = (curv_abs_x_n * theta - std::sin(curv_abs_x_n * theta)) / - std::pow(theta, 3); - g_X_n = I4 + curv_abs_x_n * Xi_hat_n + scalar1 * Xi_hat_n * Xi_hat_n + - scalar2 * Xi_hat_n * Xi_hat_n * Xi_hat_n; - } - - msg_info() << "matrix g_X : " << g_X_n; - - sofa::type::Mat3x3 M; - g_X_n.getsub(0, 0, M); // get the rotation matrix - - // convert the rotation 3x3 matrix to a quaternion - sofa::type::Quat<SReal> R; - R.fromMatrix(M); - Trans = Transform(Vec3(g_X_n(0, 3), g_X_n(1, 3), g_X_n(2, 3)), R); -} - -template <> -void BaseCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::computeTangExp( - double &curv_abs_n, const Coord1 &strain_i, Mat6x6 &TgX) { - - SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) - .norm(); // Sometimes this is computed over all strain - Mat3x3 tilde_k = - getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); - - /* Younes @23-11-27 - old version - @Todo ???? is p the linear deformation? If so, why didn't I just put a zero - vector in place of p and the first element of p is equal to 1? Matrix3 tilde_p - = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); Using the new version does not - bring any difference in my three reference scenes, but need more investogation - #TECHNICAL_DEBT - */ - // TODO(dmarchal: 2024/06/07) could the debt by solved ? - Mat3x3 tilde_q = - getTildeMatrix(Vec3(strain_i(3), strain_i(4), strain_i(5))); - - Mat6x6 ad_Xi; - buildAdjoint(tilde_k, tilde_q, ad_Xi); - - Mat6x6 Id6 = Mat6x6::Identity(); - - if (theta <= std::numeric_limits<double>::epsilon()) { - double scalar0 = std::pow(curv_abs_n, 2) / 2.0; - TgX = curv_abs_n * Id6 + scalar0 * ad_Xi; - } else { - double scalar1 = (4.0 - 4.0 * cos(curv_abs_n * theta) - - curv_abs_n * theta * sin(curv_abs_n * theta)) / - (2.0 * theta * theta); - double scalar2 = (4.0 * curv_abs_n * theta + - curv_abs_n * theta * cos(curv_abs_n * theta) - - 5.0 * sin(curv_abs_n * theta)) / - (2.0 * theta * theta * theta); - double scalar3 = (2.0 - 2.0 * cos(curv_abs_n * theta) - - curv_abs_n * theta * sin(curv_abs_n * theta)) / - (2.0 * theta * theta * theta * theta); - double scalar4 = (2.0 * curv_abs_n * theta + - curv_abs_n * theta * cos(curv_abs_n * theta) - - 3.0 * sin(curv_abs_n * theta)) / - (2.0 * theta * theta * theta * theta * theta); - - TgX = curv_abs_n * Id6 + scalar1 * ad_Xi + scalar2 * ad_Xi * ad_Xi + - scalar3 * ad_Xi * ad_Xi * ad_Xi + - scalar4 * ad_Xi * ad_Xi * ad_Xi * ad_Xi; - } -} - template class SOFA_COSSERAT_API BaseCosseratMapping<sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types>; diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index baa2e7fc..c2371c39 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -51,7 +51,7 @@ using _se3 = Eigen::Matrix4d; using _SE3 = Eigen::Matrix4d; using Cosserat::type::Transform; -using Cosserat::type::Tangent; +using Cosserat::type::TangentTransform; using Cosserat::type::RotMat; @@ -91,7 +91,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> // really needed ? /*===========COSSERAT VECTORS ======================*/ - unsigned int m_index_input; + unsigned int m_indexInput; vector<OutCoord> m_vecTransform; vector<Transform> m_framesExponentialSE3Vectors; @@ -138,8 +138,7 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> void printMatrix(const Mat6x6 R); sofa::type::Mat3x3 extractRotMatrix(const Transform &frame); - Tangent buildProjector(const Transform &T); - se3 buildXiHat(const Coord1 &strain_i); + TangentTransform buildProjector(const Transform &T); Mat3x3 getTildeMatrix(const Vec3 &u); void buildAdjoint(const Mat3x3 &A, const Mat3x3 &B, Mat6x6 &Adjoint); @@ -198,15 +197,17 @@ class BaseCosseratMapping : public sofa::core::Multi2Mapping<TIn1, TIn2, TOut> // TODO(dmarchal: 2024/06/07): // - clarify the difference between computeAdjoing and buildAdjoint ... - // - clarify why we need Transform and Vec6 and Tangent & Mat6x6 - void computeAdjoint(const Transform &frame, Tangent &adjoint); + // - clarify why we need Transform and Vec6 and TangentTransform & Mat6x6 + void computeAdjoint(const Transform &frame, TangentTransform &adjoint); void computeAdjoint(const Vec6 &frame, Mat6x6 &adjoint); void computeCoAdjoint(const Transform &frame, Mat6x6 &coAdjoint); void updateExponentialSE3(const vector<Coord1> &inDeform); void updateTangExpSE3(const vector<Coord1> &inDeform); + void computeTangExp(double &x, const Coord1 &k, Mat6x6 &TgX); + void computeTangExpImplementation(double &x, const Vec6 &k, Mat6x6 &TgX); [[maybe_unused]] Vec6 computeETA(const Vec6 &baseEta, const vector<Deriv1> &k_dot, double abs_input); diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 48fd82cb..4f2cd439 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -53,7 +53,7 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::BaseCosseratMapping() d_curv_abs_frames(initData(&d_curv_abs_frames, "curv_abs_output", " need to be com....")), d_debug(initData(&d_debug, false, "debug", "printf for the debug")), - m_index_input(0) {} + m_indexInput(0) {} template <class TIn1, class TIn2, class TOut> @@ -153,15 +153,43 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::initializeFrames() << "m_BeamLengthVectors : " << msgendl; } +auto buildXiHat(const Vec3& strain_i) -> se3 +{ + se3 Xi_hat; + + Xi_hat[0][1] = -strain_i[2]; + Xi_hat[0][2] = strain_i[1]; + Xi_hat[1][2] = -strain_i[0]; + + Xi_hat[1][0] = -Xi_hat(0, 1); + Xi_hat[2][0] = -Xi_hat(0, 2); + Xi_hat[2][1] = -Xi_hat(1, 2); + + //@TODO: Why this , if q = 0 ???? + Xi_hat[0][3] = 1.0; + return Xi_hat; +} + +auto buildXiHat(const Vec6& strain_i) -> se3 +{ + se3 Xi = buildXiHat(Vec3(strain_i(0), strain_i(1), strain_i(2))); + + for (unsigned int i = 0; i < 3; i++) + Xi[i][3] += strain_i(i + 3); + + return Xi; +} template <class TIn1, class TIn2, class TOut> -void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3( - const double &curv_abs_x_n, const Coord1 &strain_n, Transform &g_X_n) { +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeExponentialSE3(const double &curv_abs_x_n, + const Coord1 &strain_n, + Transform &g_X_n) +{ const auto I4 = Mat4x4::Identity(); - // Get the angular part of the + // Get the angular part of the strain Vec3 k = Vec3(strain_n(0), strain_n(1), strain_n(2)); - SReal theta = k.norm(); // + SReal theta = k.norm(); SE3 _g_X; se3 Xi_hat_n = buildXiHat(strain_n); @@ -246,7 +274,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateExponentialSE3( template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Transform &frame, - Tangent &adjoint) { + TangentTransform &adjoint) +{ Mat3x3 R = extractRotMatrix(frame); Vec3 u = frame.getOrigin(); Mat3x3 tilde_u = getTildeMatrix(u); @@ -266,21 +295,21 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::computeCoAdjoint(const Transform &fr template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeAdjoint(const Vec6 &eta, - Mat6x6 &adjoint) { - Mat3x3 tildeMat = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); - adjoint.setsub(0, 0, tildeMat); - adjoint.setsub(3, 3, tildeMat); - adjoint.setsub(3, 0, getTildeMatrix(Vec3(eta[3], eta[4], eta[5]))); + Mat6x6 &adjoint) +{ + Mat3x3 tildeMat1 = getTildeMatrix(Vec3(eta[0], eta[1], eta[2])); + Mat3x3 tildeMat2 = getTildeMatrix(Vec3(eta[3], eta[4], eta[5])); + buildAdjoint(tildeMat1, tildeMat2, adjoint); } + template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm(const double &x, const Mat4x4 &gX) -> Mat4x4 { // Compute theta before everything const double theta = computeTheta(x, gX); - Mat4x4 I4; - I4.identity(); + Mat4x4 I4 = Mat4x4::Identity(); Mat4x4 log_gX; double csc_theta = 1.0 / (sin(x * theta / 2.0)); @@ -322,7 +351,7 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( // Compute tangExpo at frame points for (unsigned int i = 0; i < sz; i++) { - Tangent temp; + TangentTransform temp; Coord1 strain_frame_i = inDeform[m_indicesVectors[i] - 1]; double curv_abs_x_i = m_framesLengthVectors[i]; @@ -337,14 +366,14 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( // Compute the TangExpSE3 at the nodes m_nodesTangExpVectors.clear(); - Tangent tangExpO; + TangentTransform tangExpO; tangExpO.clear(); m_nodesTangExpVectors.push_back(tangExpO); for (size_t j = 1; j < curv_abs_section.size(); j++) { Coord1 strain_node_i = inDeform[j - 1]; double x = m_beamLengthVectors[j - 1]; - Tangent temp; + TangentTransform temp; temp.clear(); computeTangExp(x, strain_node_i, temp); m_nodesTangExpVectors.push_back(temp); @@ -355,27 +384,27 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::updateTangExpSE3( template <class TIn1, class TIn2, class TOut> void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExp(double &curv_abs_n, const Coord1 &strain_i, - Mat6x6 &TgX) { - - SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)) - .norm(); // Sometimes this is computed over all strain - Mat3x3 tilde_k = - getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); - /* Younes @23-11-27 - old version - @Todo ???? is p the linear deformation? If so, why didn't I just put a zero - vector in place of p and the first element of p is equal to 1? Matrix3 tilde_p - = getTildeMatrix(type::Vec3(1.0, 0.0, 0.0)); Using the new version does not - bring any difference in my three reference scenes, but need more investogation - #TECHNICAL_DEBT - */ - Mat3x3 tilde_q = getTildeMatrix(Vec3(0.0, 0.0, 0.0)); + Mat6x6 &TgX) +{ + if constexpr( Coord1::static_size == 3 ) + computeTangExpImplementation(curv_abs_n, Vec6(strain_i(0),strain_i(1),strain_i(2),0,0,0), TgX); + else + computeTangExpImplementation(curv_abs_n, strain_i, TgX); +} + +template <class TIn1, class TIn2, class TOut> +void BaseCosseratMapping<TIn1, TIn2, TOut>::computeTangExpImplementation(double &curv_abs_n, + const Vec6 &strain_i, + Mat6x6 &TgX) +{ + SReal theta = Vec3(strain_i(0), strain_i(1), strain_i(2)).norm(); + Mat3x3 tilde_k = getTildeMatrix(Vec3(strain_i(0), strain_i(1), strain_i(2))); + Mat3x3 tilde_q = getTildeMatrix(Vec3(strain_i(3), strain_i(4), strain_i(5))); Mat6x6 ad_Xi; buildAdjoint(tilde_k, tilde_q, ad_Xi); Mat6x6 Id6 = Mat6x6::Identity(); - if (theta <= std::numeric_limits<double>::epsilon()) { double scalar0 = std::pow(curv_abs_n, 2) / 2.0; TgX = curv_abs_n * Id6 + scalar0 * ad_Xi; @@ -418,27 +447,28 @@ BaseCosseratMapping<TIn1, TIn2, TOut>::computeETA(const Vec6 &baseEta, // Same as for x1, query a read accessor so we can access the content of d_curv_abs_section auto curv_abs_input = getReadAccessor(d_curv_abs_section); - auto& kdot = k_dot[m_index_input]; + auto& kdot = k_dot[m_indexInput]; Vec6 Xi_dot {kdot[0], kdot[1], kdot[2], 0,0,0}; + // if m_indexInput is == 0 double diff0 = abs_input; double _diff0 = -abs_input; - if (m_index_input != 0) + if (m_indexInput != 0) { - diff0 = abs_input - curv_abs_input[m_index_input - 1]; - _diff0 = curv_abs_input[m_index_input - 1] - abs_input; + diff0 = abs_input - curv_abs_input[m_indexInput - 1]; + _diff0 = curv_abs_input[m_indexInput - 1] - abs_input; } Transform outTransform; - computeExponentialSE3(_diff0, x1[m_index_input], outTransform); + computeExponentialSE3(_diff0, x1[m_indexInput], outTransform); - Mat6x6 adjointMatrix; + TangentTransform adjointMatrix; computeAdjoint(outTransform, adjointMatrix); - Tangent tangentMatrix; - computeTangExp(diff0, x1[m_index_input], tangentMatrix); + TangentTransform tangentMatrix; + computeTangExp(diff0, x1[m_indexInput], tangentMatrix); return adjointMatrix * (baseEta + tangentMatrix * Xi_dot); } @@ -486,8 +516,8 @@ Mat3x3 BaseCosseratMapping<TIn1, TIn2, TOut>::extractRotMatrix(const Transform & template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildProjector(const Transform &T) --> Tangent { - Mat6x6 P; +-> TangentTransform { + TangentTransform P; // TODO(dmarchal: 2024/06/07) The following code should probably become // utility function building a 3x3 matix from a quaternion should probably @@ -503,23 +533,6 @@ auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildProjector(const Transform &T) return P; } -template <class TIn1, class TIn2, class TOut> -auto BaseCosseratMapping<TIn1, TIn2, TOut>::buildXiHat(const Coord1 &strain_i) -> se3 { - se3 Xi_hat; - - Xi_hat[0][1] = -strain_i(2); - Xi_hat[0][2] = strain_i[1]; - Xi_hat[1][2] = -strain_i[0]; - - Xi_hat[1][0] = -Xi_hat(0, 1); - Xi_hat[2][0] = -Xi_hat(0, 2); - Xi_hat[2][1] = -Xi_hat(1, 2); - - //@TODO: Why this , if q = 0 ???? - Xi_hat[0][3] = 1.0; - return Xi_hat; -} - template <class TIn1, class TIn2, class TOut> auto BaseCosseratMapping<TIn1, TIn2, TOut>::getTildeMatrix(const Vec3 &u) -> Mat3x3 { diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp index 5b2ef2b2..554bb993 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.cpp +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.cpp @@ -37,21 +37,23 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( const vector<const In1DataVecDeriv*>& dataVecIn1Vel, const vector<const In2DataVecDeriv*>& dataVecIn2Vel) { - if(d_debug.getValue()) - std::cout<< " ########## ApplyJ R Function ########"<< std::endl; - if(dataVecOutVel.empty() || dataVecIn1Vel.empty() ||dataVecIn2Vel.empty() ) return; - const In1VecDeriv& in1_vel = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv& in2_vel = dataVecIn2Vel[0]->getValue(); - OutVecDeriv& out_vel = *dataVecOutVel[0]->beginEdit(); + + msg_info() << " ########## ApplyJ R Function ########"; + + const In1VecDeriv& in1_vel = sofa::helper::getReadAccessor(*dataVecIn1Vel[0]); + const In2VecDeriv& in2_vel = sofa::helper::getReadAccessor(*dataVecIn2Vel[0]); + + auto out_vel = sofa::helper::getWriteOnlyAccessor(*dataVecOutVel[0]); + const auto baseIndex = d_baseIndex.getValue(); // Curv abscissa of nodes and frames - sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_section = d_curv_abs_section; - sofa::helper::ReadAccessor<Data<vector<double>>> curv_abs_frames = d_curv_abs_frames; + auto curv_abs_section = sofa::helper::getReadAccessor(d_curv_abs_section); + auto curv_abs_frames = sofa::helper::getReadAccessor(d_curv_abs_frames); - const In1VecCoord& inDeform = m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); //Strains + const auto inDeform = sofa::helper::getReadAccessor(*m_fromModel1->read(sofa::core::ConstVecCoordId::position())); // Compute the tangent Exponential SE3 vectors this->updateTangExpSE3(inDeform); @@ -65,18 +67,19 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( baseVelocity[u] = in2_vel[baseIndex][u]; //Apply the local transform i.e. from SOFA's frame to Cosserat's frame - const In2VecCoord& xfrom2Data = m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In2VecCoord& xfrom2Data = sofa::helper::getReadAccessor(*m_fromModel2->read(sofa::core::ConstVecCoordId::position())); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()).inversed(); Mat6x6 P = this->buildProjector(TInverse); Vec6 baseLocalVelocity = P * baseVelocity; //This is the base velocity in Locale frame m_nodesVelocityVectors.push_back(baseLocalVelocity); - if(d_debug.getValue()) - std::cout << "Base local Velocity :"<< baseLocalVelocity <<std::endl; + + msg_info() << "Base local Velocity :"<< baseLocalVelocity; //Compute velocity at nodes - for (unsigned int i = 1 ; i < curv_abs_section.size(); i++) { + for (unsigned int i = 1 ; i < curv_abs_section.size(); i++) + { Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); - Tangent Adjoint; Adjoint.clear(); + TangentTransform Adjoint; this->computeAdjoint(Trans, Adjoint); Vec6 node_Xi_dot; @@ -85,36 +88,28 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJ( Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i-1] + m_nodesTangExpVectors[i] *node_Xi_dot ); m_nodesVelocityVectors.push_back(eta_node_i); - if(d_debug.getValue()) - std::cout<< "Node velocity : "<< i << " = " << eta_node_i<< std::endl; + msg_info() << "Node velocity : "<< i << " = " << eta_node_i; } - const OutVecCoord& out = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const OutVecCoord& out = sofa::helper::getReadAccessor(*m_toModel->read(sofa::core::ConstVecCoordId::position())); + auto sz = curv_abs_frames.size(); out_vel.resize(sz); - for (unsigned int i = 0 ; i < sz; i++) { Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); - Tangent Adjoint; Adjoint.clear(); + TangentTransform Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); Vec6 frame_Xi_dot = in1_vel[m_indicesVectors[i]-1]; -// for (unsigned int u =0; u<6; u++) -// frame_Xi_dot(i) = in1_vel[m_indicesVectors[i]-1][u]; - Vec6 eta_frame_i = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * frame_Xi_dot ); // eta auto T = Transform(out[i].getCenter(), out[i].getOrientation()); - Tangent Proj = this->buildProjector(T); + TangentTransform Proj = this->buildProjector(T); out_vel[i] = Proj * eta_frame_i; - if(d_debug.getValue()) - std::cout<< "Frame velocity : "<< i << " = " << eta_frame_i<< std::endl; + msg_info() << "Frame velocity : "<< i << " = " << eta_frame_i; } - dataVecOutVel[0]->endEdit(); - m_index_input = 0; + m_indexInput = 0; } - - template <> void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( const sofa::core::MechanicalParams* /*mparams*/, const vector< In1DataVecDeriv*>& dataVecOut1Force, @@ -124,12 +119,11 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( if(dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) return; - if(d_debug.getValue()) - std::cout<< " ########## ApplyJT force R Function ########"<< std::endl; + msg_info() << " ########## ApplyJT force R Function ########"; const OutVecDeriv& in = dataVecInForce[0]->getValue(); - In1VecDeriv& out1 = *dataVecOut1Force[0]->beginEdit(); - In2VecDeriv& out2 = *dataVecOut2Force[0]->beginEdit(); + In1VecDeriv out1 = sofa::helper::getWriteAccessor(*dataVecOut1Force[0]); + In2VecDeriv out2 = sofa::helper::getWriteAccessor(*dataVecOut2Force[0]); const auto baseIndex = d_baseIndex.getValue(); const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); @@ -159,12 +153,11 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( Vec6 F_tot; F_tot.clear(); m_totalBeamForceVectors.push_back(F_tot); - Tangent matB_trans; matB_trans.clear(); + TangentTransform matB_trans; matB_trans.clear(); for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; - for (auto s = sz ; s-- ; ) { - Tangent coAdjoint; + TangentTransform coAdjoint; this->computeCoAdjoint(m_framesExponentialSE3Vectors[s], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; @@ -183,9 +176,8 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( Vec6 temp_f = matB_trans * temp * F_tot; out1[index-1] += temp_f; } - if(d_debug.getValue()) - std::cout << "f at s ="<< s <<" and index"<< index << " is : "<< f << std::endl; + msg_info() << "f at s ="<< s <<" and index"<< index << " is : "<< f; //compute F_tot F_tot += node_F_Vec; @@ -196,13 +188,9 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>:: applyJT( Mat6x6 M = this->buildProjector(frame0); out2[baseIndex] += M * F_tot; - if(d_debug.getValue()){ - std::cout << "Node forces "<< out1 << std::endl; - std::cout << "base Force: "<< out2[baseIndex] << std::endl; - } - - dataVecOut1Force[0]->endEdit(); - dataVecOut2Force[0]->endEdit(); + msg_info() + << "Node forces "<< out1 << msgendl + << "base Force: "<< out2[baseIndex]; } template <> @@ -214,43 +202,41 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( if(dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty() ) return; - if(d_debug.getValue()) - std::cout<< " ########## ApplyJT constraint R Function ########"<< std::endl; + msg_info() << " ########## ApplyJT constraint R Function ########"; //We need only one input In model and input Root model (if present) - In1MatrixDeriv& out1 = *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space (reduced coordinate) - In2MatrixDeriv& out2 = *dataMatOut2Const[0]->beginEdit(); // constraints on the reference frame (base frame) + In1MatrixDeriv& out1 = sofa::helper::getWriteAccessor(*dataMatOut1Const[0]); // constraints on the strain space (reduced coordinate) + In2MatrixDeriv& out2 = sofa::helper::getWriteAccessor(*dataMatOut2Const[0]); // constraints on the reference frame (base frame) const OutMatrixDeriv& in = dataMatInConst[0]->getValue(); // input constraints defined on the mapped frames const OutVecCoord& frame = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); const In1DataVecCoord* x1fromData = m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); - Tangent matB_trans; matB_trans.clear(); + TangentTransform matB_trans; matB_trans.clear(); for(unsigned int k=0; k<3; k++) matB_trans[k][k] = 1.0; vector< std::tuple<int,Vec6> > NodesInvolved; vector< std::tuple<int,Vec6> > NodesInvolvedCompressed; - //helper::vector<Vec6> NodesConstraintDirection; typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + bool doPrintLog = f_printLog.getValue(); for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); rowIt != rowItEnd; ++rowIt) { - if (d_debug.getValue()){ - std::cout<<"************* Apply JT (MatrixDeriv) iteration on line "; - std::cout<<rowIt.index(); - std::cout<<"************* "<<std::endl; - } + msg_info_when(doPrintLog) + <<"************* Apply JT (MatrixDeriv) iteration on line " + << rowIt.index() + <<"************* "; + auto colIt = rowIt.begin(); auto colItEnd = rowIt.end(); // Creates a constraints if the input constraint is not empty. if (colIt == colItEnd) { - if (d_debug.getValue()){ - std::cout<<"no column for this constraint"<<std::endl; - } + msg_info_when(doPrintLog) + <<"no column for this constraint"; continue; } typename In1MatrixDeriv::RowIterator o1 = out1.writeLine(rowIt.index()); // we store the constraint number @@ -268,12 +254,12 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( int indexBeam = m_indicesVectors[childIndex]; Transform _T = Transform(frame[childIndex].getCenter(),frame[childIndex].getOrientation()); - Tangent P_trans =(this->buildProjector(_T)); + TangentTransform P_trans =(this->buildProjector(_T)); P_trans.transpose(); Mat6x6 coAdjoint; this->computeCoAdjoint(m_framesExponentialSE3Vectors[childIndex], coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Tangent temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) + Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] computed in applyJ (here we transpose) temp.transpose(); Vec6 local_F = coAdjoint * P_trans * valueConst; // constraint direction in local frame of the beam. @@ -285,19 +271,20 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( NodesInvolved.push_back(node_force); colIt++; - } - if (d_debug.getValue()){ - std::cout<<"==> NodesInvolved : "<<std::endl; + + if(doPrintLog) + { + std::stringstream tmp; for (size_t i = 0; i < NodesInvolved.size(); i++) - std::cout << "index :" <<get<0>(NodesInvolved[i]) << " force :" - << get<1>(NodesInvolved[i]) << "\n "; + tmp << "index :" <<get<0>(NodesInvolved[i]) << " force :" << get<1>(NodesInvolved[i]) << msgendl; + msg_info() <<"==> NodesInvolved : " << tmp.str(); } - // sort the Nodes Invoved by decreasing order + // sort the Nodes Involved by decreasing order std::sort(begin(NodesInvolved), end(NodesInvolved), [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { - return std::get<0>(t1) > std::get<0>(t2); // custom compare function + return std::get<0>(t1) > std::get<0>(t2); } ); NodesInvolvedCompressed.clear(); @@ -316,8 +303,6 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( while (numNode_i == numNode_i1) { cumulativeF += std::get<1>(test_i1); - //// This was if ((n!=NodesInvolved.size()-2)||(n==0)) before and I change it to - /// if ((n!=NodesInvolved.size()-1)||(n==0)) since the code can't leave the will loop if ((n!=NodesInvolved.size()-1)||(n==0)){ n++; break; @@ -330,13 +315,17 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( NodesInvolvedCompressed.push_back(std::make_tuple(numNode_i, cumulativeF)); } - if (d_debug.getValue()){ - std::cout<<" NodesInvolved after sort and compress"<<std::endl; + if(doPrintLog) + { + std::stringstream tmp; + tmp<<" NodesInvolved after sort and compress"<<msgendl; for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) - std::cout << "index :" <<get<0>(NodesInvolvedCompressed[i]) << " force :" - << get<1>(NodesInvolvedCompressed[i]) << "\n "; + tmp << "index :" <<get<0>(NodesInvolvedCompressed[i]) << " force :" + << get<1>(NodesInvolvedCompressed[i]) << msgendl; + msg_info() << tmp.str(); } + auto baseIndex = d_baseIndex.getValue(); for (unsigned n=0; n<NodesInvolvedCompressed.size(); n++) { std::tuple<int,Vec6> test = NodesInvolvedCompressed[n]; @@ -348,7 +337,7 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( { //cumulate on beam frame Mat6x6 coAdjoint; - this->computeCoAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); //m_nodesExponentialSE3Vectors computed in apply + this->computeCoAdjoint(m_nodesExponentialSE3Vectors[i-1],coAdjoint); CumulativeF = coAdjoint * CumulativeF; // transfer to strain space (local coordinates) Mat6x6 temp = m_nodesTangExpVectors[i-1]; @@ -363,22 +352,15 @@ void DiscreteCosseratMapping<Vec6Types, Rigid3Types, Rigid3Types>::applyJT( Mat6x6 M = this->buildProjector(frame0); Vec6 base_force = M * CumulativeF; - o2.addCol(d_baseIndex.getValue(), base_force); + o2.addCol(baseIndex, base_force); } } - - //"""END ARTICULATION SYSTEM MAPPING""" - dataMatOut1Const[0]->endEdit(); - dataMatOut2Const[0]->endEdit(); } - // Register in the Factory int DiscreteCosseratMappingClass = sofa::core::RegisterObject("Set the positions and velocities of points attached to a rigid parent") .add< DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >(true) - .add< DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >() - ; - + .add< DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types > >(); template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec3Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; template class SOFA_COSSERAT_API DiscreteCosseratMapping< sofa::defaulttype::Vec6Types, sofa::defaulttype::Rigid3Types, sofa::defaulttype::Rigid3Types >; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.h b/src/Cosserat/mapping/DiscreteCosseratMapping.h index 4b82ffe2..7dc835b9 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.h @@ -159,7 +159,7 @@ class DiscreteCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TOut> { using BaseCosseratMapping<TIn1, TIn2, TOut>::d_debug; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indexInput; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indicesVectorsDraw; using BaseCosseratMapping<TIn1, TIn2, TOut>::computeTheta; diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 0beadc52..9d48634f 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -59,9 +59,9 @@ DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : "if this parameter is false, you draw the beam with " "color according to the force apply to each beam")), d_color(initData( - &d_color, - sofa::type::RGBAColor(40 / 255.0, 104 / 255.0, 137 / 255.0, 0.8), - "color", "The default beam color")), + &d_color, + sofa::type::RGBAColor(40 / 255.0, 104 / 255.0, 137 / 255.0, 0.8), + "color", "The default beam color")), d_index( initData(&d_index, "index", "if this parameter is false, you draw the beam with color " @@ -81,10 +81,10 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( - const sofa::core::MechanicalParams * /* mparams */, - const vector<OutDataVecCoord *> &dataVecOutPos, - const vector<const In1DataVecCoord *> &dataVecIn1Pos, - const vector<const In2DataVecCoord *> &dataVecIn2Pos) { + const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecCoord *> &dataVecOutPos, + const vector<const In1DataVecCoord *> &dataVecIn1Pos, + const vector<const In2DataVecCoord *> &dataVecIn2Pos) { if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) return; @@ -107,23 +107,32 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( /* Apply the transformation to go from cossserat to SOFA frame*/ Transform frame0 = - Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); - for (unsigned int i = 0; i < sz; i++) { + Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); + + // Cache the printLog value out of the loop, otherwise it will trigger a graph update at + // every iteration. + bool doPrintLog = this->f_printLog.getValue(); + for (unsigned int i = 0; i < sz; i++) + { Transform frame = frame0; for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { frame *= - m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) + m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) } frame *= m_framesExponentialSE3Vectors[i]; // frame*gX(x) - msg_info() << "Frame : " << i << " = " << frame; + // This is a lazy printing approach, so there is no time consuming action in the core + // of the loop. + msg_info_when(doPrintLog) + << "Frame : " << i << " = " << frame; - Vec3 v = frame.getOrigin(); - Quat q = frame.getOrientation(); - out[i] = OutCoord(v, q); + Vec3 origin = frame.getOrigin(); + Quat orientation = frame.getOrientation(); + out[i] = OutCoord(origin, orientation); } - if (this->f_printLog.getValue()) + // If the printLog attribute is checked then print distance between out frames. + if (doPrintLog) { std::stringstream tmp; for (unsigned int i = 0; i < out.size() - 1; i++) { @@ -132,21 +141,27 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( } msg_info() << tmp.str(); } - m_index_input = 0; - dataVecOutPos[0]->endEdit(); + + // TODO(dmarchal:2024/06/13): This looks a suspicious design pattern, elaborate more on the purpose + // of m_indexInput and how to use it. + m_indexInput = 0; } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( - const double &x, const Mat4x4 &gX, Mat4x4 &log_gX) { + const double &x, const Mat4x4 &gX, Mat4x4 &log_gX) { - // Compute theta before everything + // computes theta double theta = computeTheta(x, gX); - Mat4x4 I4; - I4.clear(); - I4.identity(); - log_gX.clear(); + // if theta is very small we retun log_gX as the identity. + if (theta <= std::numeric_limits<double>::epsilon()) + { + log_gX = Mat4x4::Identity(); + return; + } + + // otherwise we compute it double csc_theta = 1.0 / (sin(x * theta / 2.0)); double sec_theta = 1.0 / (cos(x * theta / 2.0)); double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; @@ -156,26 +171,25 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( double sin_2Xtheta = sin(2.0 * x_theta); double sin_Xtheta = sin(x_theta); - if (theta <= std::numeric_limits<double>::epsilon()) - log_gX = I4; - else { - log_gX = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * I4 - - (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - - sin_Xtheta - sin_2Xtheta) * - gX + - (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - - sin_Xtheta - sin_2Xtheta) * - (gX * gX) - - (x_theta * cos_Xtheta - sin_Xtheta) * (gX * gX * gX)); - } + // TODO(dmarchal:2024/06/13): Why is there a clear here. Does not the line + // just after enough ? + log_gX.clear(); + log_gX = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * Mat4x4::Identity() - + (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - + sin_Xtheta - sin_2Xtheta) * + gX + + (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - + sin_Xtheta - sin_2Xtheta) * + (gX * gX) - + (x_theta * cos_Xtheta - sin_Xtheta) * (gX * gX * gX)); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( - const sofa::core::MechanicalParams * /* mparams */, - const vector<OutDataVecDeriv *> &dataVecOutVel, - const vector<const In1DataVecDeriv *> &dataVecIn1Vel, - const vector<const In2DataVecDeriv *> &dataVecIn2Vel) { + const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecDeriv *> &dataVecOutVel, + const vector<const In1DataVecDeriv *> &dataVecIn1Vel, + const vector<const In2DataVecDeriv *> &dataVecIn2Vel) { if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) return; @@ -188,12 +202,12 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( // Curv abscissa of nodes and frames sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = - d_curv_abs_section; + d_curv_abs_section; sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = - d_curv_abs_frames; + d_curv_abs_frames; const In1VecCoord &inDeform = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()) + m_fromModel1->read(sofa::core::ConstVecCoordId::position()) ->getValue(); // Strains // Compute the tangent Exponential SE3 vectors this->updateTangExpSE3(inDeform); @@ -208,13 +222,13 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( // Apply the local transform i.e. from SOFA's frame to Cosserat's frame const In2VecCoord &xfrom2Data = - m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); + m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), xfrom2Data[baseIndex].getOrientation()) - .inversed(); + .inversed(); Mat6x6 P = this->buildProjector(TInverse); Vec6 baseLocalVelocity = - P * baseVelocity; // This is the base velocity in Locale frame + P * baseVelocity; // This is the base velocity in Locale frame m_nodesVelocityVectors.push_back(baseLocalVelocity); if (d_debug.getValue()) std::cout << "Base local Velocity :" << baseLocalVelocity << std::endl; @@ -222,7 +236,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( // Compute velocity at nodes for (unsigned int i = 1; i < curv_abs_section.size(); i++) { Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; + TangentTransform Adjoint; Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); @@ -230,19 +244,20 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( Vec6 Xi_dot = Vec6(in1_vel[i - 1], Vec3(0.0, 0.0, 0.0)); Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i - 1] + - m_nodesTangExpVectors[i] * Xi_dot); + m_nodesTangExpVectors[i] * Xi_dot); m_nodesVelocityVectors.push_back(eta_node_i); if (d_debug.getValue()) std::cout << "Node velocity : " << i << " = " << eta_node_i << std::endl; } const OutVecCoord &out = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); auto sz = curv_abs_frames.size(); out_vel.resize(sz); - for (unsigned int i = 0; i < sz; i++) { + for (unsigned int i = 0; i < sz; i++) + { Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; + TangentTransform Adjoint; ///< the class insure that the constructed adjoint is zeroed. Adjoint.clear(); this->computeAdjoint(Trans, Adjoint); Vec6 frame_Xi_dot; @@ -252,8 +267,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( frame_Xi_dot(u + 3) = 0.; } Vec6 eta_frame_i = - Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i] - 1] + - m_framesTangExpVectors[i] * frame_Xi_dot); // eta + Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i] - 1] + + m_framesTangExpVectors[i] * frame_Xi_dot); // eta auto T = Transform(out[i].getCenter(), out[i].getOrientation()); Mat6x6 Proj = this->buildProjector(T); @@ -265,15 +280,15 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( << std::endl; } dataVecOutVel[0]->endEdit(); - m_index_input = 0; + m_indexInput = 0; } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const sofa::core::MechanicalParams * /*mparams*/, - const vector<In1DataVecDeriv *> &dataVecOut1Force, - const vector<In2DataVecDeriv *> &dataVecOut2Force, - const vector<const OutDataVecDeriv *> &dataVecInForce) { + const sofa::core::MechanicalParams * /*mparams*/, + const vector<In1DataVecDeriv *> &dataVecOut1Force, + const vector<In2DataVecDeriv *> &dataVecOut2Force, + const vector<const OutDataVecDeriv *> &dataVecInForce) { if (dataVecOut1Force.empty() || dataVecInForce.empty() || dataVecOut2Force.empty()) @@ -288,9 +303,9 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( const auto baseIndex = d_baseIndex.getValue(); const OutVecCoord &frame = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); const In1DataVecCoord *x1fromData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); vector<Vec6> local_F_Vec; local_F_Vec.clear(); @@ -305,7 +320,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( vec[j] = in[var][j]; // Convert input from global frame(SOFA) to local frame Transform _T = - Transform(frame[var].getCenter(), frame[var].getOrientation()); + Transform(frame[var].getCenter(), frame[var].getOrientation()); Mat6x6 P_trans = (this->buildProjector(_T)); P_trans.transpose(); Vec6 local_F = P_trans * vec; @@ -331,12 +346,12 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( Mat6x6 coAdjoint; this->computeCoAdjoint( - m_framesExponentialSE3Vectors[s], - coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + m_framesExponentialSE3Vectors[s], + coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; Mat6x6 temp = - m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in - // applyJ (here we transpose) + m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in + // applyJ (here we transpose) temp.transpose(); Vec3 f = matB_trans * temp * node_F_Vec; @@ -344,8 +359,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( index--; // bring F_tot to the reference of the new beam this->computeCoAdjoint( - m_nodesExponentialSE3Vectors[index], - coAdjoint); // m_nodesExponentialSE3Vectors computed in apply + m_nodesExponentialSE3Vectors[index], + coAdjoint); // m_nodesExponentialSE3Vectors computed in apply F_tot = coAdjoint * F_tot; Mat6x6 temp = m_nodesTangExpVectors[index]; temp.transpose(); @@ -377,10 +392,10 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const sofa::core::ConstraintParams * /*cparams*/, - const vector<In1DataMatrixDeriv *> &dataMatOut1Const, - const vector<In2DataMatrixDeriv *> &dataMatOut2Const, - const vector<const OutDataMatrixDeriv *> &dataMatInConst) { + const sofa::core::ConstraintParams * /*cparams*/, + const vector<In1DataMatrixDeriv *> &dataMatOut1Const, + const vector<In2DataMatrixDeriv *> &dataMatOut2Const, + const vector<const OutDataMatrixDeriv *> &dataMatInConst) { if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || dataMatInConst.empty()) return; @@ -390,19 +405,19 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( << std::endl; // We need only one input In model and input Root model (if present) In1MatrixDeriv &out1 = - *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space - // (reduced coordinate) + *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space + // (reduced coordinate) In2MatrixDeriv &out2 = - *dataMatOut2Const[0] - ->beginEdit(); // constraints on the reference frame (base frame) + *dataMatOut2Const[0] + ->beginEdit(); // constraints on the reference frame (base frame) const OutMatrixDeriv &in = - dataMatInConst[0] + dataMatInConst[0] ->getValue(); // input constraints defined on the mapped frames const OutVecCoord &frame = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); const In1DataVecCoord *x1fromData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord x1from = x1fromData->getValue(); Mat3x6 matB_trans; @@ -434,7 +449,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( continue; } typename In1MatrixDeriv::RowIterator o1 = - out1.writeLine(rowIt.index()); // we store the constraint number + out1.writeLine(rowIt.index()); // we store the constraint number typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); NodesInvolved.clear(); @@ -455,16 +470,16 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( Mat6x6 coAdjoint; this->computeCoAdjoint( - m_framesExponentialSE3Vectors[childIndex], - coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + m_framesExponentialSE3Vectors[childIndex], + coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] - // computed in applyJ - // (here we transpose) + // computed in applyJ + // (here we transpose) temp.transpose(); Vec6 local_F = - coAdjoint * P_trans * - valueConst; // constraint direction in local frame of the beam. + coAdjoint * P_trans * + valueConst; // constraint direction in local frame of the beam. Vec3 f = matB_trans * temp * local_F; // constraint direction in the strain space. @@ -484,10 +499,10 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( // sort the Nodes Invoved by decreasing order std::sort( - begin(NodesInvolved), end(NodesInvolved), - [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { - return std::get<0>(t1) > std::get<0>(t2); // custom compare function - }); + begin(NodesInvolved), end(NodesInvolved), + [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { + return std::get<0>(t1) > std::get<0>(t2); // custom compare function + }); NodesInvolvedCompressed.clear(); @@ -515,7 +530,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( } } NodesInvolvedCompressed.push_back( - std::make_tuple(numNode_i, cumulativeF)); + std::make_tuple(numNode_i, cumulativeF)); } if (d_debug.getValue()) { @@ -535,8 +550,8 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( // cumulate on beam frame Mat6x6 coAdjoint; this->computeCoAdjoint( - m_nodesExponentialSE3Vectors[i - 1], - coAdjoint); // m_nodesExponentialSE3Vectors computed in apply + m_nodesExponentialSE3Vectors[i - 1], + coAdjoint); // m_nodesExponentialSE3Vectors computed in apply CumulativeF = coAdjoint * CumulativeF; // transfer to strain space (local coordinates) Mat6x6 temp = m_nodesTangExpVectors[i - 1]; @@ -549,7 +564,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( } Transform frame0 = - Transform(frame[0].getCenter(), frame[0].getOrientation()); + Transform(frame[0].getCenter(), frame[0].getOrientation()); Mat6x6 M = this->buildProjector(frame0); Vec6 base_force = M * CumulativeF; @@ -564,10 +579,10 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeBBox( - const sofa::core::ExecParams *, bool) + const sofa::core::ExecParams *, bool) { const OutVecCoord &x = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); SReal minBBox[3] = {std::numeric_limits<SReal>::max(), std::numeric_limits<SReal>::max(), @@ -589,7 +604,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeBBox( template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( - const sofa::core::visual::VisualParams *vparams) { + const sofa::core::visual::VisualParams *vparams) { if (!vparams->displayFlags().getShowMechanicalMappings()) return; @@ -599,7 +614,7 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( const auto stateLifeCycle = vparams->drawTool()->makeStateLifeCycle(); const OutDataVecCoord *xfromData = - m_toModel->read(sofa::core::ConstVecCoordId::position()); + m_toModel->read(sofa::core::ConstVecCoordId::position()); const OutVecCoord xData = xfromData->getValue(); vector<Vec3> positions; vector<sofa::type::Quat<SReal>> Orientation; @@ -613,14 +628,14 @@ void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( // Get access articulated const In1DataVecCoord *artiData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); const In1VecCoord xPos = artiData->getValue(); RGBAColor drawColor = d_color.getValue(); // draw each segment of the beam as a cylinder. for (unsigned int i = 0; i < sz - 1; i++) vparams->drawTool()->drawCylinder(positions[i], positions[i + 1], - d_radius.getValue(), drawColor); + d_radius.getValue(), drawColor); // Define color map SReal min = d_min.getValue(); diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h index 428a8b3c..c7a318bd 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.h @@ -137,7 +137,7 @@ class DiscreteDynamicCosseratMapping : public BaseCosseratMapping<TIn1, TIn2, TO using BaseCosseratMapping<TIn1, TIn2, TOut>::d_debug; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_vecTransform ; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_nodeAdjointVectors; - using BaseCosseratMapping<TIn1, TIn2, TOut>::m_index_input; + using BaseCosseratMapping<TIn1, TIn2, TOut>::m_indexInput; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_toModel; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel1; using BaseCosseratMapping<TIn1, TIn2, TOut>::m_fromModel2; diff --git a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl index 44b9204a..3b6a8f4c 100644 --- a/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteDynamicCosseratMapping.inl @@ -70,16 +70,18 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::apply( const In2VecCoord& in2 = dataVecIn2Pos[0]->getValue(); size_t sz = d_curv_abs_frames.getValue().size(); - OutVecCoord& out = *dataVecOutPos[0]->beginEdit(); + OutVecCoord out = sofa::helper::getWriteAccessor(*dataVecOutPos[0]); out.resize(sz); //update the Exponential Matrices according to new deformation this->updateExponentialSE3(in1); Transform frame0 = Transform(In2::getCPos(in2[0]),In2::getCRot(in2[0])); - for(unsigned int i=0; i<sz; i++){ + for(unsigned int i=0; i<sz; i++) + { Transform frame = frame0; - for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { + for (unsigned int u = 0; u < m_indicesVectors[i]; u++) + { frame *= m_nodesExponentialSE3Vectors[u]; } frame *= m_framesExponentialSE3Vectors[i]; @@ -89,8 +91,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>::apply( out[i] = OutCoord(v,q); } - m_index_input = 0; - dataVecOutPos[0]->endEdit(); + m_indexInput = 0; } @@ -142,7 +143,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( for (size_t i = 1 ; i < curv_abs_input.size(); i++) { Transform t= m_nodesExponentialSE3Vectors[i].inversed(); - Tangent Adjoint; Adjoint.clear(); + TangentTransform Adjoint; Adjoint.clear(); this->computeAdjoint(t,Adjoint); //Add this line because need for the jacobian computation m_nodeAdjointVectors.push_back(Adjoint); @@ -159,19 +160,21 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( const OutVecCoord& out = m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); size_t sz =curv_abs_output.size(); outVel.resize(sz); - for (size_t i = 0 ; i < sz; i++) { - Transform t= m_framesExponentialSE3Vectors[i].inversed(); - Mat6x6 Adjoint; Adjoint.clear(); - this->computeAdjoint(t,Adjoint); + for (size_t i = 0 ; i < sz; i++) + { + Transform transform= m_framesExponentialSE3Vectors[i].inversed(); + TangentTransform tangentTransform; + tangentTransform.clear(); + this->computeAdjoint(transform, tangentTransform); Vec6 Xi_dot = Vec6(in1[m_indicesVectors[i]-1], Vec3(0.0,0.0,0.0)); // eta - Vec6 etaFrame = Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + Vec6 etaFrame = tangentTransform * (m_nodesVelocityVectors[m_indicesVectors[i]-1] + m_framesTangExpVectors[i] * Xi_dot ); //Compute here jacobien and jacobien_dot vector<Mat6x3> J_i, J_dot_i; - computeJ_Jdot_i(Adjoint, i, J_i, etaFrame, J_dot_i); + computeJ_Jdot_i(tangentTransform, i, J_i, etaFrame, J_dot_i); m_frameJacobienVector.push_back(J_i); m_frameJacobienVector.push_back(J_dot_i); @@ -186,7 +189,7 @@ void DiscreteDynamicCosseratMapping<TIn1, TIn2, TOut>:: applyJ( } // std::cout << "Inside the apply J, outVel after computation : "<< outVel << std::endl; dataVecOutVel[0]->endEdit(); - m_index_input = 0; + m_indexInput = 0; } template <class TIn1, class TIn2, class TOut> diff --git a/src/Cosserat/types.h b/src/Cosserat/types.h index 282c78c5..0c016cda 100644 --- a/src/Cosserat/types.h +++ b/src/Cosserat/types.h @@ -47,8 +47,12 @@ namespace Cosserat typedef typename Eigen::Matrix3d RotMat; typedef typename Eigen::Matrix<SReal, 6, 1> Vector6d; - using Tangent = sofa::type::Mat6x6; - //class Tangent : public sofa::type::Mat<6, 6, SReal>{}; + //using TangentTransform = sofa::type::Mat6x6; + class TangentTransform : public sofa::type::Mat<6, 6, SReal> + { + public: + //TangentTransform(SReal v=0) : sofa::type::Mat6x6(v){} + }; } } From 35dada72bef6c6f41a1376165713f39c0c52f170 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Tue, 25 Jun 2024 15:46:57 +0200 Subject: [PATCH 70/71] add callback function in case we are doing dynamic discretisation of cosserat beam --- src/Cosserat/mapping/BaseCosseratMapping.h | 2 +- src/Cosserat/mapping/BaseCosseratMapping.inl | 3 +- .../mapping/DiscreteCosseratMapping.inl | 1156 +++++++++-------- 3 files changed, 590 insertions(+), 571 deletions(-) diff --git a/src/Cosserat/mapping/BaseCosseratMapping.h b/src/Cosserat/mapping/BaseCosseratMapping.h index c2371c39..d32d71fe 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.h +++ b/src/Cosserat/mapping/BaseCosseratMapping.h @@ -28,7 +28,7 @@ namespace Cosserat::mapping { -// Use a private namespace so we are not polluating the Cosserat::mapping. +// Use a private namespace so we are not polluting the Cosserat::mapping. namespace { using namespace std; diff --git a/src/Cosserat/mapping/BaseCosseratMapping.inl b/src/Cosserat/mapping/BaseCosseratMapping.inl index 4f2cd439..da6deaae 100644 --- a/src/Cosserat/mapping/BaseCosseratMapping.inl +++ b/src/Cosserat/mapping/BaseCosseratMapping.inl @@ -90,9 +90,8 @@ void BaseCosseratMapping<TIn1, TIn2, TOut>::init() const vector<OutCoord> xfrom = xfromData->getValue(); m_vecTransform.clear(); - for (unsigned int i = 0; i < xfrom.size(); i++) { + for (unsigned int i = 0; i < xfrom.size(); i++) m_vecTransform.push_back(xfrom[i]); - } initializeFrames(); doBaseCosseratInit(); diff --git a/src/Cosserat/mapping/DiscreteCosseratMapping.inl b/src/Cosserat/mapping/DiscreteCosseratMapping.inl index 9d48634f..d671f0f8 100644 --- a/src/Cosserat/mapping/DiscreteCosseratMapping.inl +++ b/src/Cosserat/mapping/DiscreteCosseratMapping.inl @@ -43,629 +43,649 @@ using sofa::helper::WriteAccessor; using sofa::type::RGBAColor; template <class TIn1, class TIn2, class TOut> -DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() : - d_deformationAxis( - initData(&d_deformationAxis, (int)1, "deformationAxis", - "the axis in which we want to show the deformation.\n")), - d_max(initData(&d_max, (SReal)1.0e-2, "max", - "the maximum of the deformation.\n")), - d_min(initData(&d_min, (SReal)0.0, "min", - "the minimum of the deformation.\n")), - d_radius( - initData(&d_radius, (SReal)0.05, "radius", - "the axis in which we want to show the deformation.\n")), - d_drawMapBeam( - initData(&d_drawMapBeam, true, "nonColored", - "if this parameter is false, you draw the beam with " - "color according to the force apply to each beam")), - d_color(initData( - &d_color, - sofa::type::RGBAColor(40 / 255.0, 104 / 255.0, 137 / 255.0, 0.8), - "color", "The default beam color")), - d_index( - initData(&d_index, "index", - "if this parameter is false, you draw the beam with color " - "according to the force apply to each beam")), - d_baseIndex(initData(&d_baseIndex, (unsigned int)0, "baseIndex", - "This parameter defines the index of the rigid " - "base of Cosserat models, 0 by default this can" - "take another value if the rigid base is given " - "by another body.")) {} +DiscreteCosseratMapping<TIn1, TIn2, TOut>::DiscreteCosseratMapping() + : d_deformationAxis( + initData(&d_deformationAxis, (int)1, "deformationAxis", + "the axis in which we want to show the deformation.\n")), + d_max(initData(&d_max, (SReal)1.0e-2, "max", + "the maximum of the deformation.\n")), + d_min(initData(&d_min, (SReal)0.0, "min", + "the minimum of the deformation.\n")), + d_radius( + initData(&d_radius, (SReal)0.05, "radius", + "the axis in which we want to show the deformation.\n")), + d_drawMapBeam( + initData(&d_drawMapBeam, true, "nonColored", + "if this parameter is false, you draw the beam with " + "color according to the force apply to each beam")), + d_color(initData( + &d_color, + sofa::type::RGBAColor(40 / 255.0, 104 / 255.0, 137 / 255.0, 0.8), + "color", "The default beam color")), + d_index( + initData(&d_index, "index", + "if this parameter is false, you draw the beam with color " + "according to the force apply to each beam")), + d_baseIndex(initData(&d_baseIndex, (unsigned int)0, "baseIndex", + "This parameter defines the index of the rigid " + "base of Cosserat models, 0 by default this can" + "take another value if the rigid base is given " + "by another body.")) { + this->addUpdateCallback( + "updateFrames", {&d_curv_abs_section, &d_curv_abs_frames, &d_debug}, + [this](const sofa::core::DataTracker &t) { + SOFA_UNUSED(t); + this->initializeFrames(); + const In1VecCoord &inDeform = + m_fromModel1->read(sofa::core::ConstVecCoordId::position())->getValue(); + this->updateExponentialSE3(inDeform); + return sofa::core::objectmodel::ComponentState::Valid; + }, + {}); +} template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() -{ - m_colorMap.setColorScheme("Blue to Red"); - m_colorMap.reinit(); +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::doBaseCosseratInit() { + m_colorMap.setColorScheme("Blue to Red"); + m_colorMap.reinit(); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::apply( - const sofa::core::MechanicalParams * /* mparams */, - const vector<OutDataVecCoord *> &dataVecOutPos, - const vector<const In1DataVecCoord *> &dataVecIn1Pos, - const vector<const In2DataVecCoord *> &dataVecIn2Pos) { - - if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) - return; - - /// Do Apply - // We need only one input In model and input Root model (if present) - const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); - const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); - - const auto sz = d_curv_abs_frames.getValue().size(); - OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states - out.resize(sz); - const auto baseIndex = d_baseIndex.getValue(); - - // update the Exponential matrices according to new deformation - // Here we update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors - // Which are the homogeneous matrices of the frames and the nodes in local - // coordinate. - this->updateExponentialSE3(in1); - - /* Apply the transformation to go from cossserat to SOFA frame*/ - Transform frame0 = - Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); - - // Cache the printLog value out of the loop, otherwise it will trigger a graph update at - // every iteration. - bool doPrintLog = this->f_printLog.getValue(); - for (unsigned int i = 0; i < sz; i++) - { - Transform frame = frame0; - for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { - frame *= - m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) - } - frame *= m_framesExponentialSE3Vectors[i]; // frame*gX(x) - - // This is a lazy printing approach, so there is no time consuming action in the core - // of the loop. - msg_info_when(doPrintLog) - << "Frame : " << i << " = " << frame; - - Vec3 origin = frame.getOrigin(); - Quat orientation = frame.getOrientation(); - out[i] = OutCoord(origin, orientation); + const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecCoord *> &dataVecOutPos, + const vector<const In1DataVecCoord *> &dataVecIn1Pos, + const vector<const In2DataVecCoord *> &dataVecIn2Pos) { + + if (dataVecOutPos.empty() || dataVecIn1Pos.empty() || dataVecIn2Pos.empty()) + return; + + // Checking the componentState, to trigger a callback if other data fields (specifically + // d_curv_abs_section and d_curv_abs_frames) were changed dynamically + if (this->d_componentState.getValue() != sofa::core::objectmodel::ComponentState::Valid) + return; + /// Do Apply + // We need only one input In model and input Root model (if present) + const In1VecCoord &in1 = dataVecIn1Pos[0]->getValue(); + const In2VecCoord &in2 = dataVecIn2Pos[0]->getValue(); + + const auto sz = d_curv_abs_frames.getValue().size(); + OutVecCoord &out = *dataVecOutPos[0]->beginEdit(); // frames states + out.resize(sz); + const auto baseIndex = d_baseIndex.getValue(); + + // update the Exponential matrices according to new deformation + // Here we update m_framesExponentialSE3Vectors & m_nodesExponentialSE3Vectors + // Which are the homogeneous matrices of the frames and the nodes in local + // coordinate. + this->updateExponentialSE3(in1); + + /* Apply the transformation to go from cossserat to SOFA frame*/ + Transform frame0 = + Transform(In2::getCPos(in2[baseIndex]), In2::getCRot(in2[baseIndex])); + + // Cache the printLog value out of the loop, otherwise it will trigger a graph + // update at every iteration. + bool doPrintLog = this->f_printLog.getValue(); + for (unsigned int i = 0; i < sz; i++) { + Transform frame = frame0; + for (unsigned int u = 0; u < m_indicesVectors[i]; u++) { + frame *= + m_nodesExponentialSE3Vectors[u]; // frame = gX(L_0)*...*gX(L_{n-1}) } - - // If the printLog attribute is checked then print distance between out frames. - if (doPrintLog) - { - std::stringstream tmp; - for (unsigned int i = 0; i < out.size() - 1; i++) { - Vec3 diff = out[i + 1].getCenter() - out[i].getCenter(); - tmp << "dist " << i << " : " << diff.norm() << msgendl; - } - msg_info() << tmp.str(); + frame *= m_framesExponentialSE3Vectors[i]; // frame*gX(x) + + // This is a lazy printing approach, so there is no time consuming action in + // the core of the loop. + msg_info_when(doPrintLog) << "Frame : " << i << " = " << frame; + + Vec3 origin = frame.getOrigin(); + Quat orientation = frame.getOrientation(); + out[i] = OutCoord(origin, orientation); + } + + // If the printLog attribute is checked then print distance between out + // frames. + if (doPrintLog) { + std::stringstream tmp; + for (unsigned int i = 0; i < out.size() - 1; i++) { + Vec3 diff = out[i + 1].getCenter() - out[i].getCenter(); + tmp << "dist " << i << " : " << diff.norm() << msgendl; } + msg_info() << tmp.str(); + } - // TODO(dmarchal:2024/06/13): This looks a suspicious design pattern, elaborate more on the purpose - // of m_indexInput and how to use it. - m_indexInput = 0; + // TODO(dmarchal:2024/06/13): This looks a suspicious design pattern, + // elaborate more on the purpose of m_indexInput and how to use it. + m_indexInput = 0; } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeLogarithm( - const double &x, const Mat4x4 &gX, Mat4x4 &log_gX) { - - // computes theta - double theta = computeTheta(x, gX); - - // if theta is very small we retun log_gX as the identity. - if (theta <= std::numeric_limits<double>::epsilon()) - { - log_gX = Mat4x4::Identity(); - return; - } - - // otherwise we compute it - double csc_theta = 1.0 / (sin(x * theta / 2.0)); - double sec_theta = 1.0 / (cos(x * theta / 2.0)); - double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; - double x_theta = x * theta; - double cos_2Xtheta = cos(2.0 * x_theta); - double cos_Xtheta = cos(x_theta); - double sin_2Xtheta = sin(2.0 * x_theta); - double sin_Xtheta = sin(x_theta); - - // TODO(dmarchal:2024/06/13): Why is there a clear here. Does not the line - // just after enough ? - log_gX.clear(); - log_gX = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * Mat4x4::Identity() - - (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - - sin_Xtheta - sin_2Xtheta) * - gX + - (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - - sin_Xtheta - sin_2Xtheta) * - (gX * gX) - - (x_theta * cos_Xtheta - sin_Xtheta) * (gX * gX * gX)); + const double &x, const Mat4x4 &gX, Mat4x4 &log_gX) { + + // computes theta + double theta = computeTheta(x, gX); + + // if theta is very small we retun log_gX as the identity. + if (theta <= std::numeric_limits<double>::epsilon()) { + log_gX = Mat4x4::Identity(); + return; + } + + // otherwise we compute it + double csc_theta = 1.0 / (sin(x * theta / 2.0)); + double sec_theta = 1.0 / (cos(x * theta / 2.0)); + double cst = (1.0 / 8) * (csc_theta * csc_theta * csc_theta) * sec_theta; + double x_theta = x * theta; + double cos_2Xtheta = cos(2.0 * x_theta); + double cos_Xtheta = cos(x_theta); + double sin_2Xtheta = sin(2.0 * x_theta); + double sin_Xtheta = sin(x_theta); + + log_gX.clear(); + log_gX = cst * ((x_theta * cos_2Xtheta - sin_Xtheta) * Mat4x4::Identity() - + (x_theta * cos_Xtheta + 2.0 * x_theta * cos_2Xtheta - + sin_Xtheta - sin_2Xtheta) * + gX + + (2.0 * x_theta * cos_Xtheta + x_theta * cos_2Xtheta - + sin_Xtheta - sin_2Xtheta) * + (gX * gX) - + (x_theta * cos_Xtheta - sin_Xtheta) * (gX * gX * gX)); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJ( - const sofa::core::MechanicalParams * /* mparams */, - const vector<OutDataVecDeriv *> &dataVecOutVel, - const vector<const In1DataVecDeriv *> &dataVecIn1Vel, - const vector<const In2DataVecDeriv *> &dataVecIn2Vel) { - - if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) - return; + const sofa::core::MechanicalParams * /* mparams */, + const vector<OutDataVecDeriv *> &dataVecOutVel, + const vector<const In1DataVecDeriv *> &dataVecIn1Vel, + const vector<const In2DataVecDeriv *> &dataVecIn2Vel) { + + if (dataVecOutVel.empty() || dataVecIn1Vel.empty() || dataVecIn2Vel.empty()) + return; + + if (this->d_componentState.getValue() != sofa::core::objectmodel::ComponentState::Valid) + return; + if (d_debug.getValue()) + std::cout << " ########## ApplyJ Function ########" << std::endl; + const In1VecDeriv &in1_vel = dataVecIn1Vel[0]->getValue(); + const In2VecDeriv &in2_vel = dataVecIn2Vel[0]->getValue(); + OutVecDeriv &out_vel = *dataVecOutVel[0]->beginEdit(); + const auto baseIndex = d_baseIndex.getValue(); + + // Curv abscissa of nodes and frames + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = + d_curv_abs_section; + sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = + d_curv_abs_frames; + + const In1VecCoord &inDeform = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()) + ->getValue(); // Strains + // Compute the tangent Exponential SE3 vectors + this->updateTangExpSE3(inDeform); + + // Get base velocity as input this is also called eta + m_nodesVelocityVectors.clear(); + + // Get base velocity and convert to Vec6, for the facility of computation + Vec6 baseVelocity; // + for (auto u = 0; u < 6; u++) + baseVelocity[u] = in2_vel[baseIndex][u]; + + // Apply the local transform i.e. from SOFA's frame to Cosserat's frame + const In2VecCoord &xfrom2Data = + m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); + Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), + xfrom2Data[baseIndex].getOrientation()) + .inversed(); + Mat6x6 P = this->buildProjector(TInverse); + Vec6 baseLocalVelocity = + P * baseVelocity; // This is the base velocity in Locale frame + m_nodesVelocityVectors.push_back(baseLocalVelocity); + if (d_debug.getValue()) + std::cout << "Base local Velocity :" << baseLocalVelocity << std::endl; + + // Compute velocity at nodes + for (unsigned int i = 1; i < curv_abs_section.size(); i++) { + Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); + TangentTransform Adjoint; + Adjoint.clear(); + this->computeAdjoint(Trans, Adjoint); + + /// The null vector is replace by the linear velocity in Vec6Type + Vec6 Xi_dot = Vec6(in1_vel[i - 1], Vec3(0.0, 0.0, 0.0)); + + Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i - 1] + + m_nodesTangExpVectors[i] * Xi_dot); + m_nodesVelocityVectors.push_back(eta_node_i); if (d_debug.getValue()) - std::cout << " ########## ApplyJ Function ########" << std::endl; - const In1VecDeriv &in1_vel = dataVecIn1Vel[0]->getValue(); - const In2VecDeriv &in2_vel = dataVecIn2Vel[0]->getValue(); - OutVecDeriv &out_vel = *dataVecOutVel[0]->beginEdit(); - const auto baseIndex = d_baseIndex.getValue(); - - // Curv abscissa of nodes and frames - sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_section = - d_curv_abs_section; - sofa::helper::ReadAccessor<sofa::Data<vector<double>>> curv_abs_frames = - d_curv_abs_frames; - - const In1VecCoord &inDeform = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()) - ->getValue(); // Strains - // Compute the tangent Exponential SE3 vectors - this->updateTangExpSE3(inDeform); - - // Get base velocity as input this is also called eta - m_nodesVelocityVectors.clear(); - - // Get base velocity and convert to Vec6, for the facility of computation - Vec6 baseVelocity; // - for (auto u = 0; u < 6; u++) - baseVelocity[u] = in2_vel[baseIndex][u]; - - // Apply the local transform i.e. from SOFA's frame to Cosserat's frame - const In2VecCoord &xfrom2Data = - m_fromModel2->read(sofa::core::ConstVecCoordId::position())->getValue(); - Transform TInverse = Transform(xfrom2Data[baseIndex].getCenter(), - xfrom2Data[baseIndex].getOrientation()) - .inversed(); - Mat6x6 P = this->buildProjector(TInverse); - Vec6 baseLocalVelocity = - P * baseVelocity; // This is the base velocity in Locale frame - m_nodesVelocityVectors.push_back(baseLocalVelocity); - if (d_debug.getValue()) - std::cout << "Base local Velocity :" << baseLocalVelocity << std::endl; - - // Compute velocity at nodes - for (unsigned int i = 1; i < curv_abs_section.size(); i++) { - Transform Trans = m_nodesExponentialSE3Vectors[i].inversed(); - TangentTransform Adjoint; - Adjoint.clear(); - this->computeAdjoint(Trans, Adjoint); - - /// The null vector is replace by the linear velocity in Vec6Type - Vec6 Xi_dot = Vec6(in1_vel[i - 1], Vec3(0.0, 0.0, 0.0)); - - Vec6 eta_node_i = Adjoint * (m_nodesVelocityVectors[i - 1] + - m_nodesTangExpVectors[i] * Xi_dot); - m_nodesVelocityVectors.push_back(eta_node_i); - if (d_debug.getValue()) - std::cout << "Node velocity : " << i << " = " << eta_node_i << std::endl; + std::cout << "Node velocity : " << i << " = " << eta_node_i << std::endl; + } + + const OutVecCoord &out = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + auto sz = curv_abs_frames.size(); + out_vel.resize(sz); + for (unsigned int i = 0; i < sz; i++) { + Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); + TangentTransform + Adjoint; ///< the class insure that the constructed adjoint is zeroed. + Adjoint.clear(); + this->computeAdjoint(Trans, Adjoint); + Vec6 frame_Xi_dot; + + for (auto u = 0; u < 3; u++) { + frame_Xi_dot(u) = in1_vel[m_indicesVectors[i] - 1][u]; + frame_Xi_dot(u + 3) = 0.; } + Vec6 eta_frame_i = + Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i] - 1] + + m_framesTangExpVectors[i] * frame_Xi_dot); // eta - const OutVecCoord &out = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - auto sz = curv_abs_frames.size(); - out_vel.resize(sz); - for (unsigned int i = 0; i < sz; i++) - { - Transform Trans = m_framesExponentialSE3Vectors[i].inversed(); - TangentTransform Adjoint; ///< the class insure that the constructed adjoint is zeroed. - Adjoint.clear(); - this->computeAdjoint(Trans, Adjoint); - Vec6 frame_Xi_dot; - - for (auto u = 0; u < 3; u++) { - frame_Xi_dot(u) = in1_vel[m_indicesVectors[i] - 1][u]; - frame_Xi_dot(u + 3) = 0.; - } - Vec6 eta_frame_i = - Adjoint * (m_nodesVelocityVectors[m_indicesVectors[i] - 1] + - m_framesTangExpVectors[i] * frame_Xi_dot); // eta - - auto T = Transform(out[i].getCenter(), out[i].getOrientation()); - Mat6x6 Proj = this->buildProjector(T); + auto T = Transform(out[i].getCenter(), out[i].getOrientation()); + Mat6x6 Proj = this->buildProjector(T); - out_vel[i] = Proj * eta_frame_i; + out_vel[i] = Proj * eta_frame_i; - if (d_debug.getValue()) - std::cout << "Frame velocity : " << i << " = " << eta_frame_i - << std::endl; - } - dataVecOutVel[0]->endEdit(); - m_indexInput = 0; + if (d_debug.getValue()) + std::cout << "Frame velocity : " << i << " = " << eta_frame_i + << std::endl; + } + dataVecOutVel[0]->endEdit(); + m_indexInput = 0; } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const sofa::core::MechanicalParams * /*mparams*/, - const vector<In1DataVecDeriv *> &dataVecOut1Force, - const vector<In2DataVecDeriv *> &dataVecOut2Force, - const vector<const OutDataVecDeriv *> &dataVecInForce) { + const sofa::core::MechanicalParams * /*mparams*/, + const vector<In1DataVecDeriv *> &dataVecOut1Force, + const vector<In2DataVecDeriv *> &dataVecOut2Force, + const vector<const OutDataVecDeriv *> &dataVecInForce) { + + if (dataVecOut1Force.empty() || dataVecInForce.empty() || + dataVecOut2Force.empty()) + return; + + if (this->d_componentState.getValue() != sofa::core::objectmodel::ComponentState::Valid) + return; + + if (d_debug.getValue()) + std::cout << " ########## ApplyJT force Function ########" << std::endl; + const OutVecDeriv &in = dataVecInForce[0]->getValue(); + + In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); + In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); + const auto baseIndex = d_baseIndex.getValue(); + + const OutVecCoord &frame = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord *x1fromData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + vector<Vec6> local_F_Vec; + local_F_Vec.clear(); + + out1.resize(x1from.size()); + + // convert the input from Deriv type to vec6 type, for the purpose of the + // matrix vector multiplication + for (unsigned int var = 0; var < in.size(); ++var) { + Vec6 vec; + for (unsigned j = 0; j < 6; j++) + vec[j] = in[var][j]; + // Convert input from global frame(SOFA) to local frame + Transform _T = + Transform(frame[var].getCenter(), frame[var].getOrientation()); + Mat6x6 P_trans = (this->buildProjector(_T)); + P_trans.transpose(); + Vec6 local_F = P_trans * vec; + local_F_Vec.push_back(local_F); + } + + // Compute output forces + auto sz = m_indicesVectors.size(); + auto index = m_indicesVectors[sz - 1]; + m_totalBeamForceVectors.clear(); + m_totalBeamForceVectors.resize(sz); + + Vec6 F_tot; + F_tot.clear(); + m_totalBeamForceVectors.push_back(F_tot); + + Mat3x6 matB_trans; + matB_trans.clear(); + for (unsigned int k = 0; k < 3; k++) + matB_trans[k][k] = 1.0; + + for (auto s = sz; s--;) { + Mat6x6 coAdjoint; + + this->computeCoAdjoint( + m_framesExponentialSE3Vectors[s], + coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; + Mat6x6 temp = + m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in + // applyJ (here we transpose) + temp.transpose(); + Vec3 f = matB_trans * temp * node_F_Vec; + + if (index != m_indicesVectors[s]) { + index--; + // bring F_tot to the reference of the new beam + this->computeCoAdjoint( + m_nodesExponentialSE3Vectors[index], + coAdjoint); // m_nodesExponentialSE3Vectors computed in apply + F_tot = coAdjoint * F_tot; + Mat6x6 temp = m_nodesTangExpVectors[index]; + temp.transpose(); + // apply F_tot to the new beam + Vec3 temp_f = matB_trans * temp * F_tot; + out1[index - 1] += temp_f; + } + if (d_debug.getValue()) + std::cout << "f at s =" << s << " and index" << index << " is : " << f + << std::endl; - if (dataVecOut1Force.empty() || dataVecInForce.empty() || - dataVecOut2Force.empty()) - return; + // compute F_tot + F_tot += node_F_Vec; + out1[m_indicesVectors[s] - 1] += f; + } - if (d_debug.getValue()) - std::cout << " ########## ApplyJT force Function ########" << std::endl; - const OutVecDeriv &in = dataVecInForce[0]->getValue(); - - In1VecDeriv &out1 = *dataVecOut1Force[0]->beginEdit(); - In2VecDeriv &out2 = *dataVecOut2Force[0]->beginEdit(); - const auto baseIndex = d_baseIndex.getValue(); - - const OutVecCoord &frame = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord *x1fromData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); - vector<Vec6> local_F_Vec; - local_F_Vec.clear(); - - out1.resize(x1from.size()); - - // convert the input from Deriv type to vec6 type, for the purpose of the - // matrix vector multiplication - for (unsigned int var = 0; var < in.size(); ++var) { - Vec6 vec; - for (unsigned j = 0; j < 6; j++) - vec[j] = in[var][j]; - // Convert input from global frame(SOFA) to local frame - Transform _T = - Transform(frame[var].getCenter(), frame[var].getOrientation()); - Mat6x6 P_trans = (this->buildProjector(_T)); - P_trans.transpose(); - Vec6 local_F = P_trans * vec; - local_F_Vec.push_back(local_F); - } + Transform frame0 = Transform(frame[0].getCenter(), frame[0].getOrientation()); + Mat6x6 M = this->buildProjector(frame0); + out2[baseIndex] += M * F_tot; - // Compute output forces - auto sz = m_indicesVectors.size(); - auto index = m_indicesVectors[sz - 1]; - m_totalBeamForceVectors.clear(); - m_totalBeamForceVectors.resize(sz); + if (d_debug.getValue()) { + std::cout << "Node forces " << out1 << std::endl; + std::cout << "base Force: " << out2[baseIndex] << std::endl; + } - Vec6 F_tot; - F_tot.clear(); - m_totalBeamForceVectors.push_back(F_tot); + dataVecOut1Force[0]->endEdit(); + dataVecOut2Force[0]->endEdit(); +} - Mat3x6 matB_trans; - matB_trans.clear(); - for (unsigned int k = 0; k < 3; k++) - matB_trans[k][k] = 1.0; +template <class TIn1, class TIn2, class TOut> +void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( + const sofa::core::ConstraintParams * /*cparams*/, + const vector<In1DataMatrixDeriv *> &dataMatOut1Const, + const vector<In2DataMatrixDeriv *> &dataMatOut2Const, + const vector<const OutDataMatrixDeriv *> &dataMatInConst) { + if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || + dataMatInConst.empty()) + return; + + if (this->d_componentState.getValue() != sofa::core::objectmodel::ComponentState::Valid) + return; + + if (d_debug.getValue()) + std::cout << " ########## ApplyJT Constraint Function ########" + << std::endl; + // We need only one input In model and input Root model (if present) + In1MatrixDeriv &out1 = + *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space + // (reduced coordinate) + In2MatrixDeriv &out2 = + *dataMatOut2Const[0] + ->beginEdit(); // constraints on the reference frame (base frame) + const OutMatrixDeriv &in = + dataMatInConst[0] + ->getValue(); // input constraints defined on the mapped frames + + const OutVecCoord &frame = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + const In1DataVecCoord *x1fromData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord x1from = x1fromData->getValue(); + + Mat3x6 matB_trans; + matB_trans.clear(); + for (unsigned int k = 0; k < 3; k++) + matB_trans[k][k] = 1.0; + + vector<std::tuple<int, Vec6>> NodesInvolved; + vector<std::tuple<int, Vec6>> NodesInvolvedCompressed; + // helper::vector<Vec6> NodesConstraintDirection; + + typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); + + for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); + rowIt != rowItEnd; ++rowIt) { + if (d_debug.getValue()) { + std::cout << "************* Apply JT (MatrixDeriv) iteration on line "; + std::cout << rowIt.index(); + std::cout << "************* " << std::endl; + } + typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); + typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); + + // Creates a constraints if the input constraint is not empty. + if (colIt == colItEnd) { + if (d_debug.getValue()) { + std::cout << "no column for this constraint" << std::endl; + } + continue; + } + typename In1MatrixDeriv::RowIterator o1 = + out1.writeLine(rowIt.index()); // we store the constraint number + typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); + + NodesInvolved.clear(); + while (colIt != colItEnd) { + int childIndex = colIt.index(); + + const OutDeriv valueConst_ = colIt.val(); + Vec6 valueConst; + for (unsigned j = 0; j < 6; j++) + valueConst[j] = valueConst_[j]; + + int indexBeam = m_indicesVectors[childIndex]; + + Transform _T = Transform(frame[childIndex].getCenter(), + frame[childIndex].getOrientation()); + Mat6x6 P_trans = (this->buildProjector(_T)); + P_trans.transpose(); + + Mat6x6 coAdjoint; + this->computeCoAdjoint( + m_framesExponentialSE3Vectors[childIndex], + coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply + Mat6x6 temp = + m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] + // computed in applyJ + // (here we transpose) + temp.transpose(); + + Vec6 local_F = + coAdjoint * P_trans * + valueConst; // constraint direction in local frame of the beam. + + Vec3 f = matB_trans * temp * + local_F; // constraint direction in the strain space. + + o1.addCol(indexBeam - 1, f); + std::tuple<int, Vec6> test = std::make_tuple(indexBeam, local_F); + + NodesInvolved.push_back(test); + colIt++; + } + if (d_debug.getValue()) { + std::cout << "==> NodesInvolved : " << std::endl; + for (size_t i = 0; i < NodesInvolved.size(); i++) + std::cout << "index :" << get<0>(NodesInvolved[i]) + << " force :" << get<1>(NodesInvolved[i]) << "\n "; + } - for (auto s = sz; s--;) { - Mat6x6 coAdjoint; + // sort the Nodes Invoved by decreasing order + std::sort( + begin(NodesInvolved), end(NodesInvolved), + [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { + return std::get<0>(t1) > std::get<0>(t2); // custom compare function + }); - this->computeCoAdjoint( - m_framesExponentialSE3Vectors[s], - coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Vec6 node_F_Vec = coAdjoint * local_F_Vec[s]; - Mat6x6 temp = - m_framesTangExpVectors[s]; // m_framesTangExpVectors[s] computed in - // applyJ (here we transpose) - temp.transpose(); - Vec3 f = matB_trans * temp * node_F_Vec; - - if (index != m_indicesVectors[s]) { - index--; - // bring F_tot to the reference of the new beam - this->computeCoAdjoint( - m_nodesExponentialSE3Vectors[index], - coAdjoint); // m_nodesExponentialSE3Vectors computed in apply - F_tot = coAdjoint * F_tot; - Mat6x6 temp = m_nodesTangExpVectors[index]; - temp.transpose(); - // apply F_tot to the new beam - Vec3 temp_f = matB_trans * temp * F_tot; - out1[index - 1] += temp_f; + NodesInvolvedCompressed.clear(); + + for (unsigned n = 0; n < NodesInvolved.size(); n++) { + std::tuple<int, Vec6> test_i = NodesInvolved[n]; + int numNode_i = std::get<0>(test_i); + Vec6 cumulativeF = std::get<1>(test_i); + + if (n < NodesInvolved.size() - 1) { + std::tuple<int, Vec6> test_i1 = NodesInvolved[n + 1]; + int numNode_i1 = std::get<0>(test_i1); + + while (numNode_i == numNode_i1) { + cumulativeF += std::get<1>(test_i1); + //// This was if ((n!=NodesInvolved.size()-2)||(n==0)) before and I + /// change it to + /// if ((n!=NodesInvolved.size()-1)||(n==0)) since the code can't + /// leave the will loop + if ((n != NodesInvolved.size() - 1) || (n == 0)) { + n++; + break; + } + test_i1 = NodesInvolved[n + 1]; + numNode_i1 = std::get<0>(test_i1); } - if (d_debug.getValue()) - std::cout << "f at s =" << s << " and index" << index << " is : " << f - << std::endl; - - // compute F_tot - F_tot += node_F_Vec; - out1[m_indicesVectors[s] - 1] += f; + } + NodesInvolvedCompressed.push_back( + std::make_tuple(numNode_i, cumulativeF)); } - Transform frame0 = Transform(frame[0].getCenter(), frame[0].getOrientation()); - Mat6x6 M = this->buildProjector(frame0); - out2[baseIndex] += M * F_tot; - if (d_debug.getValue()) { - std::cout << "Node forces " << out1 << std::endl; - std::cout << "base Force: " << out2[baseIndex] << std::endl; + std::cout << " NodesInvolved after sort and compress" << std::endl; + for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) + std::cout << "index :" << get<0>(NodesInvolvedCompressed[i]) + << " force :" << get<1>(NodesInvolvedCompressed[i]) << "\n "; } - dataVecOut1Force[0]->endEdit(); - dataVecOut2Force[0]->endEdit(); -} - -template <class TIn1, class TIn2, class TOut> -void DiscreteCosseratMapping<TIn1, TIn2, TOut>::applyJT( - const sofa::core::ConstraintParams * /*cparams*/, - const vector<In1DataMatrixDeriv *> &dataMatOut1Const, - const vector<In2DataMatrixDeriv *> &dataMatOut2Const, - const vector<const OutDataMatrixDeriv *> &dataMatInConst) { - if (dataMatOut1Const.empty() || dataMatOut2Const.empty() || - dataMatInConst.empty()) - return; - - if (d_debug.getValue()) - std::cout << " ########## ApplyJT Constraint Function ########" - << std::endl; - // We need only one input In model and input Root model (if present) - In1MatrixDeriv &out1 = - *dataMatOut1Const[0]->beginEdit(); // constraints on the strain space - // (reduced coordinate) - In2MatrixDeriv &out2 = - *dataMatOut2Const[0] - ->beginEdit(); // constraints on the reference frame (base frame) - const OutMatrixDeriv &in = - dataMatInConst[0] - ->getValue(); // input constraints defined on the mapped frames - - const OutVecCoord &frame = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - const In1DataVecCoord *x1fromData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord x1from = x1fromData->getValue(); - - Mat3x6 matB_trans; - matB_trans.clear(); - for (unsigned int k = 0; k < 3; k++) - matB_trans[k][k] = 1.0; - - vector<std::tuple<int, Vec6>> NodesInvolved; - vector<std::tuple<int, Vec6>> NodesInvolvedCompressed; - // helper::vector<Vec6> NodesConstraintDirection; - - typename OutMatrixDeriv::RowConstIterator rowItEnd = in.end(); - - for (typename OutMatrixDeriv::RowConstIterator rowIt = in.begin(); - rowIt != rowItEnd; ++rowIt) { - if (d_debug.getValue()) { - std::cout << "************* Apply JT (MatrixDeriv) iteration on line "; - std::cout << rowIt.index(); - std::cout << "************* " << std::endl; - } - typename OutMatrixDeriv::ColConstIterator colIt = rowIt.begin(); - typename OutMatrixDeriv::ColConstIterator colItEnd = rowIt.end(); - - // Creates a constraints if the input constraint is not empty. - if (colIt == colItEnd) { - if (d_debug.getValue()) { - std::cout << "no column for this constraint" << std::endl; - } - continue; - } - typename In1MatrixDeriv::RowIterator o1 = - out1.writeLine(rowIt.index()); // we store the constraint number - typename In2MatrixDeriv::RowIterator o2 = out2.writeLine(rowIt.index()); - - NodesInvolved.clear(); - while (colIt != colItEnd) { - int childIndex = colIt.index(); - - const OutDeriv valueConst_ = colIt.val(); - Vec6 valueConst; - for (unsigned j = 0; j < 6; j++) - valueConst[j] = valueConst_[j]; - - int indexBeam = m_indicesVectors[childIndex]; - - Transform _T = Transform(frame[childIndex].getCenter(), - frame[childIndex].getOrientation()); - Mat6x6 P_trans = (this->buildProjector(_T)); - P_trans.transpose(); - - Mat6x6 coAdjoint; - this->computeCoAdjoint( - m_framesExponentialSE3Vectors[childIndex], - coAdjoint); // m_framesExponentialSE3Vectors[s] computed in apply - Mat6x6 temp = m_framesTangExpVectors[childIndex]; // m_framesTangExpVectors[s] - // computed in applyJ - // (here we transpose) - temp.transpose(); - - Vec6 local_F = - coAdjoint * P_trans * - valueConst; // constraint direction in local frame of the beam. - - Vec3 f = matB_trans * temp * - local_F; // constraint direction in the strain space. - - o1.addCol(indexBeam - 1, f); - std::tuple<int, Vec6> test = std::make_tuple(indexBeam, local_F); - - NodesInvolved.push_back(test); - colIt++; - } - if (d_debug.getValue()) { - std::cout << "==> NodesInvolved : " << std::endl; - for (size_t i = 0; i < NodesInvolved.size(); i++) - std::cout << "index :" << get<0>(NodesInvolved[i]) - << " force :" << get<1>(NodesInvolved[i]) << "\n "; - } + for (unsigned n = 0; n < NodesInvolvedCompressed.size(); n++) { + std::tuple<int, Vec6> test = NodesInvolvedCompressed[n]; + int numNode = std::get<0>(test); + int i = numNode; + Vec6 CumulativeF = std::get<1>(test); - // sort the Nodes Invoved by decreasing order - std::sort( - begin(NodesInvolved), end(NodesInvolved), - [](std::tuple<int, Vec6> const &t1, std::tuple<int, Vec6> const &t2) { - return std::get<0>(t1) > std::get<0>(t2); // custom compare function - }); + while (i > 0) { + // cumulate on beam frame + Mat6x6 coAdjoint; + this->computeCoAdjoint( + m_nodesExponentialSE3Vectors[i - 1], + coAdjoint); // m_nodesExponentialSE3Vectors computed in apply + CumulativeF = coAdjoint * CumulativeF; + // transfer to strain space (local coordinates) + Mat6x6 temp = m_nodesTangExpVectors[i - 1]; + temp.transpose(); + Vec3 temp_f = matB_trans * temp * CumulativeF; - NodesInvolvedCompressed.clear(); - - for (unsigned n = 0; n < NodesInvolved.size(); n++) { - std::tuple<int, Vec6> test_i = NodesInvolved[n]; - int numNode_i = std::get<0>(test_i); - Vec6 cumulativeF = std::get<1>(test_i); - - if (n < NodesInvolved.size() - 1) { - std::tuple<int, Vec6> test_i1 = NodesInvolved[n + 1]; - int numNode_i1 = std::get<0>(test_i1); - - while (numNode_i == numNode_i1) { - cumulativeF += std::get<1>(test_i1); - //// This was if ((n!=NodesInvolved.size()-2)||(n==0)) before and I - ///change it to - /// if ((n!=NodesInvolved.size()-1)||(n==0)) since the code can't - /// leave the will loop - if ((n != NodesInvolved.size() - 1) || (n == 0)) { - n++; - break; - } - test_i1 = NodesInvolved[n + 1]; - numNode_i1 = std::get<0>(test_i1); - } - } - NodesInvolvedCompressed.push_back( - std::make_tuple(numNode_i, cumulativeF)); - } + if (i > 1) + o1.addCol(i - 2, temp_f); + i--; + } - if (d_debug.getValue()) { - std::cout << " NodesInvolved after sort and compress" << std::endl; - for (size_t i = 0; i < NodesInvolvedCompressed.size(); i++) - std::cout << "index :" << get<0>(NodesInvolvedCompressed[i]) - << " force :" << get<1>(NodesInvolvedCompressed[i]) << "\n "; - } + Transform frame0 = + Transform(frame[0].getCenter(), frame[0].getOrientation()); + Mat6x6 M = this->buildProjector(frame0); - for (unsigned n = 0; n < NodesInvolvedCompressed.size(); n++) { - std::tuple<int, Vec6> test = NodesInvolvedCompressed[n]; - int numNode = std::get<0>(test); - int i = numNode; - Vec6 CumulativeF = std::get<1>(test); - - while (i > 0) { - // cumulate on beam frame - Mat6x6 coAdjoint; - this->computeCoAdjoint( - m_nodesExponentialSE3Vectors[i - 1], - coAdjoint); // m_nodesExponentialSE3Vectors computed in apply - CumulativeF = coAdjoint * CumulativeF; - // transfer to strain space (local coordinates) - Mat6x6 temp = m_nodesTangExpVectors[i - 1]; - temp.transpose(); - Vec3 temp_f = matB_trans * temp * CumulativeF; - - if (i > 1) - o1.addCol(i - 2, temp_f); - i--; - } - - Transform frame0 = - Transform(frame[0].getCenter(), frame[0].getOrientation()); - Mat6x6 M = this->buildProjector(frame0); - - Vec6 base_force = M * CumulativeF; - o2.addCol(d_baseIndex.getValue(), base_force); - } + Vec6 base_force = M * CumulativeF; + o2.addCol(d_baseIndex.getValue(), base_force); } + } - //"""END ARTICULATION SYSTEM MAPPING""" - dataMatOut1Const[0]->endEdit(); - dataMatOut2Const[0]->endEdit(); + //"""END ARTICULATION SYSTEM MAPPING""" + dataMatOut1Const[0]->endEdit(); + dataMatOut2Const[0]->endEdit(); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::computeBBox( - const sofa::core::ExecParams *, bool) -{ - const OutVecCoord &x = - m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); - - SReal minBBox[3] = {std::numeric_limits<SReal>::max(), - std::numeric_limits<SReal>::max(), - std::numeric_limits<SReal>::max()}; - SReal maxBBox[3] = {-std::numeric_limits<SReal>::max(), - -std::numeric_limits<SReal>::max(), - -std::numeric_limits<SReal>::max()}; - for (std::size_t i = 0; i < x.size(); i++) { - const OutCoord &p = x[i]; - for (int c = 0; c < 3; c++) { - if (p[c] > maxBBox[c]) - maxBBox[c] = p[c]; - if (p[c] < minBBox[c]) - minBBox[c] = p[c]; - } + const sofa::core::ExecParams *, bool) { + const OutVecCoord &x = + m_toModel->read(sofa::core::ConstVecCoordId::position())->getValue(); + + SReal minBBox[3] = {std::numeric_limits<SReal>::max(), + std::numeric_limits<SReal>::max(), + std::numeric_limits<SReal>::max()}; + SReal maxBBox[3] = {-std::numeric_limits<SReal>::max(), + -std::numeric_limits<SReal>::max(), + -std::numeric_limits<SReal>::max()}; + for (std::size_t i = 0; i < x.size(); i++) { + const OutCoord &p = x[i]; + for (int c = 0; c < 3; c++) { + if (p[c] > maxBBox[c]) + maxBBox[c] = p[c]; + if (p[c] < minBBox[c]) + minBBox[c] = p[c]; } - this->f_bbox.setValue(sofa::type::TBoundingBox<SReal>(minBBox, maxBBox)); + } + this->f_bbox.setValue(sofa::type::TBoundingBox<SReal>(minBBox, maxBBox)); } template <class TIn1, class TIn2, class TOut> void DiscreteCosseratMapping<TIn1, TIn2, TOut>::draw( - const sofa::core::visual::VisualParams *vparams) { - if (!vparams->displayFlags().getShowMechanicalMappings()) - return; - - // draw cable - typedef RGBAColor RGBAColor; - - const auto stateLifeCycle = vparams->drawTool()->makeStateLifeCycle(); - - const OutDataVecCoord *xfromData = - m_toModel->read(sofa::core::ConstVecCoordId::position()); - const OutVecCoord xData = xfromData->getValue(); - vector<Vec3> positions; - vector<sofa::type::Quat<SReal>> Orientation; - positions.clear(); - Orientation.clear(); - unsigned int sz = xData.size(); - for (unsigned int i = 0; i < sz; i++) { - positions.push_back(xData[i].getCenter()); - Orientation.push_back(xData[i].getOrientation()); + const sofa::core::visual::VisualParams *vparams) { + if (!vparams->displayFlags().getShowMechanicalMappings()) + return; + + // draw cable + typedef RGBAColor RGBAColor; + + const auto stateLifeCycle = vparams->drawTool()->makeStateLifeCycle(); + + const OutDataVecCoord *xfromData = + m_toModel->read(sofa::core::ConstVecCoordId::position()); + const OutVecCoord xData = xfromData->getValue(); + vector<Vec3> positions; + vector<sofa::type::Quat<SReal>> Orientation; + positions.clear(); + Orientation.clear(); + unsigned int sz = xData.size(); + for (unsigned int i = 0; i < sz; i++) { + positions.push_back(xData[i].getCenter()); + Orientation.push_back(xData[i].getOrientation()); + } + + // Get access articulated + const In1DataVecCoord *artiData = + m_fromModel1->read(sofa::core::ConstVecCoordId::position()); + const In1VecCoord xPos = artiData->getValue(); + + RGBAColor drawColor = d_color.getValue(); + // draw each segment of the beam as a cylinder. + for (unsigned int i = 0; i < sz - 1; i++) + vparams->drawTool()->drawCylinder(positions[i], positions[i + 1], + d_radius.getValue(), drawColor); + + // Define color map + SReal min = d_min.getValue(); + SReal max = d_max.getValue(); + sofa::helper::ColorMap::evaluator<SReal> _eval = + m_colorMap.getEvaluator(min, max); + + glLineWidth(d_radius.getValue()); + glBegin(GL_LINES); + if (d_drawMapBeam.getValue()) { + sofa::type::RGBAColor _color = d_color.getValue(); + RGBAColor colorL = RGBAColor(_color[0], _color[1], _color[2], _color[3]); + glColor4f(colorL[0], colorL[1], colorL[2], colorL[3]); + for (unsigned int i = 0; i < sz - 1; i++) { + vparams->drawTool()->drawLine(positions[i], positions[i + 1], colorL); } - - // Get access articulated - const In1DataVecCoord *artiData = - m_fromModel1->read(sofa::core::ConstVecCoordId::position()); - const In1VecCoord xPos = artiData->getValue(); - - RGBAColor drawColor = d_color.getValue(); - // draw each segment of the beam as a cylinder. - for (unsigned int i = 0; i < sz - 1; i++) - vparams->drawTool()->drawCylinder(positions[i], positions[i + 1], - d_radius.getValue(), drawColor); - - // Define color map - SReal min = d_min.getValue(); - SReal max = d_max.getValue(); - sofa::helper::ColorMap::evaluator<SReal> _eval = m_colorMap.getEvaluator(min, max); - - glLineWidth(d_radius.getValue()); - glBegin(GL_LINES); - if (d_drawMapBeam.getValue()) { - sofa::type::RGBAColor _color = d_color.getValue(); - RGBAColor colorL = RGBAColor(_color[0], _color[1], _color[2], _color[3]); - glColor4f(colorL[0], colorL[1], colorL[2], colorL[3]); - for (unsigned int i = 0; i < sz - 1; i++) { - vparams->drawTool()->drawLine(positions[i], positions[i + 1], colorL); - } - } else { - int j = 0; - vector<int> index = d_index.getValue(); - for (unsigned int i = 0; i < sz - 1; i++) { - j = m_indicesVectorsDraw[i] - - 1; // to get the articulation on which the frame is related to - RGBAColor color = _eval(xPos[j][d_deformationAxis.getValue()]); - vparams->drawTool()->drawLine(positions[i], positions[i + 1], color); - } + } else { + int j = 0; + vector<int> index = d_index.getValue(); + for (unsigned int i = 0; i < sz - 1; i++) { + j = m_indicesVectorsDraw[i] - + 1; // to get the articulation on which the frame is related to + RGBAColor color = _eval(xPos[j][d_deformationAxis.getValue()]); + vparams->drawTool()->drawLine(positions[i], positions[i + 1], color); } - glLineWidth(1); - if (!vparams->displayFlags().getShowMappings()) - if (!d_debug.getValue()) - return; - glEnd(); + } + glLineWidth(1); + if (!vparams->displayFlags().getShowMappings()) + if (!d_debug.getValue()) + return; + glEnd(); } -} // namespace sofa::component::mapping +} // namespace Cosserat::mapping From 6eee0d9827020e1c05fa84add54859fb1233ca17 Mon Sep 17 00:00:00 2001 From: Yinoussa Adagolodjo <yinoussa.adagolodjo2@univ-lille.fr> Date: Wed, 26 Jun 2024 11:41:03 +0200 Subject: [PATCH 71/71] mv the initCosserat.h.in file into config.h.in --- CMakeLists.txt | 2 +- Tests/CMakeLists.txt | 2 +- src/Cosserat/CMakeLists.txt | 2 +- src/Cosserat/{initCosserat.h.in => config.h.in} | 0 src/Cosserat/engine/ProjectionEngine.h | 2 +- src/Cosserat/forcefield/BeamHookeLawForceField.h | 2 +- src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h | 2 +- src/Cosserat/forcefield/CosseratInternalActuation.h | 2 +- src/Cosserat/forcefield/CosseratInternalActuation.inl | 2 +- src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp | 2 +- src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h | 2 +- src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl | 2 +- src/Cosserat/fwd.h | 2 +- src/Cosserat/initCosserat.cpp | 2 +- src/Cosserat/types.h | 2 +- 15 files changed, 14 insertions(+), 14 deletions(-) rename src/Cosserat/{initCosserat.h.in => config.h.in} (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 162ee198..9a698d4e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,7 +20,7 @@ endif() set(SRC_ROOT_DIR src/${PROJECT_NAME}) set(HEADER_FILES - ${SRC_ROOT_DIR}/initCosserat.h.in + ${SRC_ROOT_DIR}/config.h.in ${SRC_ROOT_DIR}/fwd.h ${SRC_ROOT_DIR}/types.h ${SRC_ROOT_DIR}/mapping/BaseCosseratMapping.h diff --git a/Tests/CMakeLists.txt b/Tests/CMakeLists.txt index dd12b2fd..d15db727 100644 --- a/Tests/CMakeLists.txt +++ b/Tests/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.1) +cmake_minimum_required(VERSION 3.12) set(This Cosserat_test) diff --git a/src/Cosserat/CMakeLists.txt b/src/Cosserat/CMakeLists.txt index 425aadd5..fb8ef70d 100644 --- a/src/Cosserat/CMakeLists.txt +++ b/src/Cosserat/CMakeLists.txt @@ -1,7 +1,7 @@ project(Cosserat.src VERSION 21.06.99) set(HEADER_FILES - initCosserat.h + config.h mapping/BaseCosserat.h mapping/BaseCosserat.inl diff --git a/src/Cosserat/initCosserat.h.in b/src/Cosserat/config.h.in similarity index 100% rename from src/Cosserat/initCosserat.h.in rename to src/Cosserat/config.h.in diff --git a/src/Cosserat/engine/ProjectionEngine.h b/src/Cosserat/engine/ProjectionEngine.h index 86e2ef31..a5662425 100644 --- a/src/Cosserat/engine/ProjectionEngine.h +++ b/src/Cosserat/engine/ProjectionEngine.h @@ -22,7 +22,7 @@ #ifndef COSSERAT_ProjectionEngine_H #define COSSERAT_ProjectionEngine_H -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/core/behavior/PairInteractionConstraint.h> #include <sofa/core/behavior/MechanicalState.h> #include <sofa/core/DataEngine.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceField.h b/src/Cosserat/forcefield/BeamHookeLawForceField.h index 2c2f4e26..98163b26 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceField.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceField.h @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/type/Vec.h> #include <sofa/type/Mat.h> diff --git a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h index 35b7b396..009abc4a 100644 --- a/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h +++ b/src/Cosserat/forcefield/BeamHookeLawForceFieldRigid.h @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/type/Vec.h> #include <sofa/type/Mat.h> diff --git a/src/Cosserat/forcefield/CosseratInternalActuation.h b/src/Cosserat/forcefield/CosseratInternalActuation.h index bc64d3ce..0e8e21bf 100644 --- a/src/Cosserat/forcefield/CosseratInternalActuation.h +++ b/src/Cosserat/forcefield/CosseratInternalActuation.h @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/type/Vec.h> #include <sofa/type/Mat.h> diff --git a/src/Cosserat/forcefield/CosseratInternalActuation.inl b/src/Cosserat/forcefield/CosseratInternalActuation.inl index a3fe434f..eaffb920 100644 --- a/src/Cosserat/forcefield/CosseratInternalActuation.inl +++ b/src/Cosserat/forcefield/CosseratInternalActuation.inl @@ -28,7 +28,7 @@ * * ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <Cosserat/forcefield/CosseratInternalActuation.h> #include <sofa/linearalgebra/FullVector.h> diff --git a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp index 9ffb8748..2f1d6d5a 100644 --- a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp +++ b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.cpp @@ -21,7 +21,7 @@ ******************************************************************************/ #define SOFA_COMPONENT_FORCEFIELD_UNIFORMVELOCITYDAMPINGFORCEFIELD_CPP -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <Cosserat/forcefield/MyUniformVelocityDampingForceField.inl> #include <sofa/core/ObjectFactory.h> #include <sofa/defaulttype/VecTypes.h> diff --git a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h index 48be188a..f72318d4 100644 --- a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h +++ b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.h @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/core/behavior/ForceField.h> diff --git a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl index c5b4b895..ddadc227 100644 --- a/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl +++ b/src/Cosserat/forcefield/MyUniformVelocityDampingForceField.inl @@ -20,7 +20,7 @@ * Contact information: contact@sofa-framework.org * ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <Cosserat/forcefield/MyUniformVelocityDampingForceField.h> #include "MyUniformVelocityDampingForceField.h" #include <sofa/defaulttype/BaseMatrix.h> diff --git a/src/Cosserat/fwd.h b/src/Cosserat/fwd.h index b800535a..d50cb394 100644 --- a/src/Cosserat/fwd.h +++ b/src/Cosserat/fwd.h @@ -29,7 +29,7 @@ ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/type/fwd.h> namespace Cosserat { diff --git a/src/Cosserat/initCosserat.cpp b/src/Cosserat/initCosserat.cpp index d127d9fa..63f8b6ff 100644 --- a/src/Cosserat/initCosserat.cpp +++ b/src/Cosserat/initCosserat.cpp @@ -24,7 +24,7 @@ * * * Contact information: contact@sofa-framework.org * ******************************************************************************/ -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/core/ObjectFactory.h> #include <sofa/helper/system/PluginManager.h> diff --git a/src/Cosserat/types.h b/src/Cosserat/types.h index 0c016cda..ce6d2780 100644 --- a/src/Cosserat/types.h +++ b/src/Cosserat/types.h @@ -29,7 +29,7 @@ ******************************************************************************/ #pragma once -#include <Cosserat/initCosserat.h> +#include <Cosserat/config.h> #include <sofa/type/vector.h> #include <sofa/type/Mat.h> #include <sofa/defaulttype/SolidTypes.h>